From 65a64db192c1893b6b87c8abe4a6634ca053edd7 Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Thu, 27 Feb 2025 15:00:56 +0000 Subject: [PATCH 01/12] Partially successful tests for frame angular velocity in RNE tests --- src/coordinates/coordinate_implementations.jl | 11 ++++++++ src/interface.jl | 12 ++++----- test/inverse_dynamics_test.jl | 26 ++++++++++--------- test/runtests.jl | 2 +- 4 files changed, 32 insertions(+), 19 deletions(-) diff --git a/src/coordinates/coordinate_implementations.jl b/src/coordinates/coordinate_implementations.jl index ea9e32c..fa2276d 100644 --- a/src/coordinates/coordinate_implementations.jl +++ b/src/coordinates/coordinate_implementations.jl @@ -489,6 +489,17 @@ _velocity(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = get_angular_vel( _jacobian(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = J_cache_view(cache, c) _acceleration(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = _get_angular_acc(cache, c.coord_data.frameID) +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:FrameAngularVelocity}) + c = mc.coord_data + f_view = f_cache_view(cache, mc) + @assert length(f_view) == 3 + f = f_cache_view(cache, mc)[SVector(1, 2, 3)] # Get the force applied to the coord as an SVector + fID = c.frameID + get_frame_torques(cache)[fID] += f + nothing +end + + #################################################################################################### # CoordNorm #################################################################################################### diff --git a/src/interface.jl b/src/interface.jl index 73b384c..514b50b 100644 --- a/src/interface.jl +++ b/src/interface.jl @@ -505,20 +505,20 @@ function _inverse_dynamics!(bundle::MechRNEBundle) # Backward pass foreach(get_force_components(m)) do component # add forces for each component to coordinates _add_opspace_force!(bundle, component) - @show f_cache_view(bundle, m[component.coord]) + # @show f_cache_view(bundle, m[component.coord]) end - @show frame_forces - println("Backward pass part 1") + # @show frame_forces + # println("Backward pass part 1") compute_in_reverse_coordinate_order(coordinates(m)) do coord # propagate forces through coordinates __propagate_opspace_force!(bundle, coord) - @show frame_forces + # @show frame_forces end - println("Backward pass part 2") + # println("Backward pass part 2") for (parent, child) in Iterators.reverse(m.rbtree.walk) # propagate forces through frames/joints frame_forces[parent] += frame_forces[child] δ = origin(get_transform(cache, CompiledFrameID(parent))) - origin(get_transform(cache, CompiledFrameID(child))) frame_torques[parent] += frame_torques[child] - cross(δ, frame_forces[child]) - @show frame_forces + # @show frame_forces end # Project forces to joints foreach(joints(m)) do joint diff --git a/test/inverse_dynamics_test.jl b/test/inverse_dynamics_test.jl index c05ac96..5551719 100644 --- a/test/inverse_dynamics_test.jl +++ b/test/inverse_dynamics_test.jl @@ -1,15 +1,17 @@ -function test_inverse_dynamics(m) +function test_inverse_dynamics(m; N=20) rng = MersenneTwister(1234) - # q = rand!(rng, zero_q(Float64, m)) - # q̇ = rand!(rng, zero_q̇(Float64, m)) - # u = rand!(rng, zero_u(Float64, m)) - # u = zero_u(Float64, m) - q = [0., π/2] - q̇ = [0., 0.] - u = [1., 0.] - time = 0.0 # Time is irrelevant to these tests as no `TimeFuncJoint`s - gravity = SVector(0.0, 0.0, -10.) + for i = 1:N + t = 0.0 + q = rand!(rng, zero_q(Float64, m)) + q̇ = rand!(rng, zero_q̇(Float64, m)) + gravity = randn(rng, SVector{3, Float64}) + _test_inverse_dynamics(m, t, q, q̇, gravity) + end +end + +function _test_inverse_dynamics(m, time, q, q̇, gravity) + u = zero_u(Float64, m) icache = new_inverse_dynamics_cache(m) dcache = new_dynamics_cache(m) @@ -18,8 +20,8 @@ function test_inverse_dynamics(m) q̈ = get_q̈(dcache) inverse_dynamics!(icache, time, q, q̇, q̈, gravity) - @show get_u(icache) - @show u + # u is the control input used to compute forward dynamics, and is correct + # get_u(icache) is the result of the inverse dynamics computation, and should be equal to u @test get_u(icache) ≈ u atol=1e-7 rtol=1e-7 # @show icache.cache.frame_cache.forces[6] - icache.cache.frame_cache.rbstates[6].acceleration.linear diff --git a/test/runtests.jl b/test/runtests.jl index b973b90..7f69b31 100644 --- a/test/runtests.jl +++ b/test/runtests.jl @@ -143,7 +143,7 @@ results = @testset "All tests" begin results = @testset "Velocity Kinematics AD" test_on_mechanisms(test_velocity_kinematics_vs_autodiff, small_immut_mechanisms); results = @testset "Coordinate tests" test_on_mechanisms(test_coordinates, compiled_systems); results = @testset "Dynamics tests" test_on_mechanisms(test_dynamics, systems_with_inertances); - # results = @testset "Inverse Dynamics tests" test_on_mechanisms(test_inverse_dynamics, compiled_mechanisms); # TODO + results = @testset "Inverse Dynamics tests" test_on_mechanisms(test_inverse_dynamics, compiled_mechanisms); # TODO results = @testset "Energy tests" test_on_mechanisms(test_energy, systems_with_inertances); results = @testset "RSON tests" test_on_mechanisms(test_rson, systems); # TODO ForwardDiff compat tests From e805bd6ddb45c36ccc6b9c30cc01906c04df035e Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Fri, 28 Feb 2025 14:19:26 +0000 Subject: [PATCH 02/12] Added visualization --- examples/rne_visualization.jl | 104 ++++++++++++++++++++++++++++++++++ 1 file changed, 104 insertions(+) create mode 100644 examples/rne_visualization.jl diff --git a/examples/rne_visualization.jl b/examples/rne_visualization.jl new file mode 100644 index 0000000..488d696 --- /dev/null +++ b/examples/rne_visualization.jl @@ -0,0 +1,104 @@ +# ## RNE Visualization + +using + GLMakie, + LinearAlgebra, + StaticArrays, + VMRobotControl + +X = SVector{3, Float64}(1.0, 0.0, 0.0) +Y = SVector{3, Float64}(0.0, 1.0, 0.0) +Z = SVector{3, Float64}(0.0, 0.0, 1.0) + +T1 = zero(Transform{Float64}) +J1 = Revolute(Y, T1) + +T2 = Transform(Z) +J2 = Revolute(Y, T2) + +T3 = Transform(Z) +J3 = Rigid(T3) + +mech = Mechanism{Float64}("2Link") +cart_frame = add_frame!(mech, "Cart") +L2_frame = add_frame!(mech, "L2") +EE_frame = add_frame!(mech, "EE") + +add_joint!(mech, J1; parent="root_frame", child=cart_frame, id="J1") +add_joint!(mech, J2; parent=cart_frame, child=L2_frame, id="J2") +add_joint!(mech, J3, parent=L2_frame, child=EE_frame; id="J3") + +# Then, we add a coordinate to the mechanism to represent the tip of the pendulum, and a +# coordinate to represent the position of the cart. These are used to add point masses to +# the mechanism. +add_coordinate!(mech, FrameOrigin(EE_frame); id="tip_pos") +add_coordinate!(mech, FrameOrigin(cart_frame); id="cart_pos") +add_component!(mech, PointMass(1.0, "cart_pos"); id="cart_mass") +add_component!(mech, PointMass(1.0, "tip_pos"); id="pendulum_mass") + +# We compile the mechanism, and setup an ODE problem to simulate the dynamics of the rail robot. +m = compile(mech) +cache = Observable(new_inverse_dynamics_cache(m)) + + +begin +t = 0.0 +q = [0.0, π/2] +q̇ = zero_q̇(m) +q̈ = zero_q̈(m) +g = SVector{3, Float64}(0.0, 0.0, -9.81) +inverse_dynamics!(cache[], t, q, q̇, q̈, g) + +fig = Figure() +display(fig) +ls = LScene(fig[1, 1]; show_axis=false) +robotsketch!(ls, cache; linewidth=3) + +frameIDs = get_compiled_frameID.((cache[],), frames(cache[])) +tfs = map(cache) do cache + tfs = map(id -> get_transform(cache, id), frameIDs) +end +positions = map(tfs) do tfs + map(tf -> Point3f(origin(tf)...), tfs) +end +fs = map(cache) do cache + fs = map(id -> VMRobotControl.get_frame_force(cache, id), frameIDs) +end +f_scale = map(fs) do fs + 0.1/norm(maximum(fs)) +end +τs = map(cache) do cache + map(id -> VMRobotControl.get_frame_torque(cache, id), frameIDs) +end + +arrows!(ls, positions, fs; lengthscale=f_scale, arrowsize=0.1, color=:red, ) +arrows!(ls, positions, τs; lengthscale=f_scale, arrowsize=0.1, color=:red, ) + + +end + +using Test, Random +Revise.includet("../test/inverse_dynamics_test.jl") +@testset test_inverse_dynamics(m) + +# function create_rotated_cylinder_mesh(N1, N2, r1, r2, ϕ) +# for θ2 = LinRange(0, ϕ, N2) +# pᶜ = Point3f(r2*cos(θ2), r2*sin(θ2), 0) +# for θ1 = LinRange(0, 2π, N1) +# points = Point3f() +# end + +# end +# end + + + +# module_path = joinpath(splitpath(splitdir(pathof(VMRobotControl))[1])[1:end-1]) +# savepath = joinpath(module_path, "docs/src/assets/rail_robot.mp4") +# animate_robot_odesolution(fig, sol, cache, savepath; f_setup=animate_f_setup, f_control=animate_f_control); + +# ```@raw html +# +# ``` From 90ccc6c72b9e51cb9c570a34c64a9b0da854d931 Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Fri, 28 Feb 2025 16:54:14 +0000 Subject: [PATCH 03/12] Added docstring for add_deadzone_springs! --- src/components/storages.jl | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/src/components/storages.jl b/src/components/storages.jl index bea2021..61621bf 100644 --- a/src/components/storages.jl +++ b/src/components/storages.jl @@ -314,6 +314,17 @@ end const ReLUSpring{T, C} = RectifiedSpring{T, C} ReLUSpring(args...;kwargs...) = RectifiedSpring(args...; kwargs...) +""" +add_deadzone_springs!(mechanism, stiffness, bounds, coord_id) + + Creates a spring with a deadzone, that acts with stiffness `stiffness` outside of + bounds `bounds`, e.g. (-1.0, 1.0), on the coordinate `coord_id`. + + The deadzone is implemented as two ReLU springs on two new coordinates, which are + offset from the original coordinate by the bounds. This is because the ReLU spring + is centered at zero, so the new coordinates are used to shift the 'zero point' to + match the bounds. +""" function add_deadzone_springs!(mechanism, stiffness, bounds, coord_id) lb, ub = bounds lb_coord_id = add_coordinate!(mechanism, ConstCoord(lb); id="lb_$coord_id") From 361c4cdd2463eecaa6065dc00299f11e5517b1b1 Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Tue, 4 Mar 2025 14:36:33 +0000 Subject: [PATCH 04/12] Renamed panda mechanisms, split tests into runtests_manual.jl and setup_test_mechanisms.jl to make running tests independently simpler. Fixed projecting joint torque for revolute joints. --- RSONs/rsons/franka_panda/pandaDrill.rson | 2 +- .../franka_panda/pandaDummyInstrument.rson | 2 +- RSONs/rsons/franka_panda/pandaSurgical.rson | 2 +- .../franka_panda/pandaSurgicalStryker.rson | 2 +- RSONs/rsons/franka_panda/pandaSurgicalV2.rson | 2 +- .../rsons/franka_panda/pandaVeterinarian.rson | 2 +- examples/rne_visualization.jl | 117 ++++++++++++------ src/components/components.jl | 6 +- src/coordinates/coordinate_implementations.jl | 4 +- src/interface.jl | 89 ++++++++----- src/joints/joint_definitions.jl | 10 +- test/inverse_dynamics_test.jl | 2 - test/runtests.jl | 109 +--------------- test/runtests_manual.jl | 38 ++++++ test/setup_test_mechanisms.jl | 102 +++++++++++++++ 15 files changed, 293 insertions(+), 196 deletions(-) create mode 100644 test/runtests_manual.jl create mode 100644 test/setup_test_mechanisms.jl diff --git a/RSONs/rsons/franka_panda/pandaDrill.rson b/RSONs/rsons/franka_panda/pandaDrill.rson index d133af8..87388a9 100644 --- a/RSONs/rsons/franka_panda/pandaDrill.rson +++ b/RSONs/rsons/franka_panda/pandaDrill.rson @@ -1,7 +1,7 @@ { "rson_version": "0.1.0", "type": "mechanism", - "name": "panda", + "name": "panda_drill", "frames": [ "root_frame", "L1_frame", diff --git a/RSONs/rsons/franka_panda/pandaDummyInstrument.rson b/RSONs/rsons/franka_panda/pandaDummyInstrument.rson index 950e6fa..1e6eaa9 100644 --- a/RSONs/rsons/franka_panda/pandaDummyInstrument.rson +++ b/RSONs/rsons/franka_panda/pandaDummyInstrument.rson @@ -1,7 +1,7 @@ { "rson_version": "0.1.0", "type": "mechanism", - "name": "panda", + "name": "panda_dummy_instrument", "frames": [ "root_frame", "L1_frame", diff --git a/RSONs/rsons/franka_panda/pandaSurgical.rson b/RSONs/rsons/franka_panda/pandaSurgical.rson index 07869fe..5f31608 100644 --- a/RSONs/rsons/franka_panda/pandaSurgical.rson +++ b/RSONs/rsons/franka_panda/pandaSurgical.rson @@ -1,7 +1,7 @@ { "rson_version": "0.1.0", "type": "mechanism", - "name": "panda", + "name": "panda_surgical", "frames": [ "root_frame", "L1_frame", diff --git a/RSONs/rsons/franka_panda/pandaSurgicalStryker.rson b/RSONs/rsons/franka_panda/pandaSurgicalStryker.rson index bbbd121..924012b 100644 --- a/RSONs/rsons/franka_panda/pandaSurgicalStryker.rson +++ b/RSONs/rsons/franka_panda/pandaSurgicalStryker.rson @@ -1,7 +1,7 @@ { "rson_version": "0.1.0", "type": "mechanism", - "name": "panda", + "name": "panda_surgical_stryker", "frames": [ "root_frame", "L1_frame", diff --git a/RSONs/rsons/franka_panda/pandaSurgicalV2.rson b/RSONs/rsons/franka_panda/pandaSurgicalV2.rson index da0ccfe..d1be519 100644 --- a/RSONs/rsons/franka_panda/pandaSurgicalV2.rson +++ b/RSONs/rsons/franka_panda/pandaSurgicalV2.rson @@ -1,7 +1,7 @@ { "rson_version": "0.1.0", "type": "mechanism", - "name": "panda", + "name": "panda_surgical_v2", "frames": [ "root_frame", "L1_frame", diff --git a/RSONs/rsons/franka_panda/pandaVeterinarian.rson b/RSONs/rsons/franka_panda/pandaVeterinarian.rson index a0fb1c1..3c89feb 100644 --- a/RSONs/rsons/franka_panda/pandaVeterinarian.rson +++ b/RSONs/rsons/franka_panda/pandaVeterinarian.rson @@ -1,7 +1,7 @@ { "rson_version": "0.1.0", "type": "mechanism", - "name": "panda", + "name": "panda_veterinarian", "frames": [ "root_frame", "L1_frame", diff --git a/examples/rne_visualization.jl b/examples/rne_visualization.jl index 488d696..2c67890 100644 --- a/examples/rne_visualization.jl +++ b/examples/rne_visualization.jl @@ -5,54 +5,87 @@ using LinearAlgebra, StaticArrays, VMRobotControl - -X = SVector{3, Float64}(1.0, 0.0, 0.0) -Y = SVector{3, Float64}(0.0, 1.0, 0.0) -Z = SVector{3, Float64}(0.0, 0.0, 1.0) - -T1 = zero(Transform{Float64}) -J1 = Revolute(Y, T1) - -T2 = Transform(Z) -J2 = Revolute(Y, T2) - -T3 = Transform(Z) -J3 = Rigid(T3) - -mech = Mechanism{Float64}("2Link") -cart_frame = add_frame!(mech, "Cart") -L2_frame = add_frame!(mech, "L2") -EE_frame = add_frame!(mech, "EE") - -add_joint!(mech, J1; parent="root_frame", child=cart_frame, id="J1") -add_joint!(mech, J2; parent=cart_frame, child=L2_frame, id="J2") -add_joint!(mech, J3, parent=L2_frame, child=EE_frame; id="J3") - -# Then, we add a coordinate to the mechanism to represent the tip of the pendulum, and a -# coordinate to represent the position of the cart. These are used to add point masses to -# the mechanism. -add_coordinate!(mech, FrameOrigin(EE_frame); id="tip_pos") -add_coordinate!(mech, FrameOrigin(cart_frame); id="cart_pos") -add_component!(mech, PointMass(1.0, "cart_pos"); id="cart_mass") -add_component!(mech, PointMass(1.0, "tip_pos"); id="pendulum_mass") - +# begin +# X = SVector{3, Float64}(1.0, 0.0, 0.0) +# Y = SVector{3, Float64}(0.0, 1.0, 0.0) +# Z = SVector{3, Float64}(0.0, 0.0, 1.0) + +# T1 = zero(Transform{Float64}) +# J1 = Revolute(Y, T1) + +# T2 = Transform(Z) +# J2 = Revolute(Y, T2) + +# T3 = Transform(Z) +# J3 = Rigid(T3) + +# mech = Mechanism{Float64}("2Link") +# cart_frame = add_frame!(mech, "Cart") +# L2_frame = add_frame!(mech, "L2") +# EE_frame = add_frame!(mech, "EE") + +# add_joint!(mech, J1; parent="root_frame", child=cart_frame, id="J1") +# add_joint!(mech, J2; parent=cart_frame, child=L2_frame, id="J2") +# add_joint!(mech, J3, parent=L2_frame, child=EE_frame; id="J3") + +# # Then, we add a coordinate to the mechanism to represent the tip of the pendulum, and a +# # coordinate to represent the position of the cart. These are used to add point masses to +# # the mechanism. +# add_coordinate!(mech, FrameOrigin(EE_frame); id="tip_pos") +# add_coordinate!(mech, FrameOrigin(cart_frame); id="cart_pos") +# add_component!(mech, PointMass(1.0, "cart_pos"); id="cart_mass") +# add_component!(mech, PointMass(1.0, "tip_pos"); id="pendulum_mass") +# m = compile(mech) +# end + # We compile the mechanism, and setup an ODE problem to simulate the dynamics of the rail robot. -m = compile(mech) +m = compiled_mechanisms[end] cache = Observable(new_inverse_dynamics_cache(m)) +# @testset test_inverse_dynamics(m) +bundle = cache[] begin + + t = 0.0 q = [0.0, π/2] -q̇ = zero_q̇(m) -q̈ = zero_q̈(m) -g = SVector{3, Float64}(0.0, 0.0, -9.81) -inverse_dynamics!(cache[], t, q, q̇, q̈, g) +q = zero_q(m) + randn(7) +q̇ = zero_q̇(m) + randn(7) +g = SVector{3, Float64}(0.0, 0.0, -10) #+ rand(SVector{3, Float64}) + +# rng = MersenneTwister(1234) +# t = 0.0 +# q = rand!(rng, zero_q(Float64, m)) +# q̇ = rand!(rng, zero_q̇(Float64, m)) +# g = randn(rng, SVector{3, Float64}) + +u = zero_u(m) + +dcache = new_dynamics_cache(m) +dynamics!(dcache, t, q, q̇, g, u) +q̈ = get_q̈(dcache) + +VMRobotControl._inverse_dynamics_set_inputs!(bundle, t, q, q̇, q̈, g) +VMRobotControl._inverse_dynamics_forward_pass!(bundle) +VMRobotControl._inverse_dynamics_zero!(bundle) +VMRobotControl._inverse_dynamics_backward_pass_a!(bundle) +VMRobotControl._inverse_dynamics_backward_pass_b!(bundle) +VMRobotControl._inverse_dynamics_backward_pass_c!(bundle) +VMRobotControl._inverse_dynamics_backward_pass_d!(bundle) + +# q̈_out = dynamics!(dcache, t, q, q̇, g, get_u(bundle)) + +@test get_u(cache[]) ≈ u atol=1e-7 rtol=1e-7 +# @test q̈ ≈ q̈_out atol=1e-7 rtol=1e-7 +end + +begin fig = Figure() display(fig) ls = LScene(fig[1, 1]; show_axis=false) -robotsketch!(ls, cache; linewidth=3) +robotsketch!(ls, cache; linewidth=3, scale=0.05) frameIDs = get_compiled_frameID.((cache[],), frames(cache[])) tfs = map(cache) do cache @@ -65,14 +98,18 @@ fs = map(cache) do cache fs = map(id -> VMRobotControl.get_frame_force(cache, id), frameIDs) end f_scale = map(fs) do fs - 0.1/norm(maximum(fs)) + 0.2/maximum(norm(fs)) end τs = map(cache) do cache map(id -> VMRobotControl.get_frame_torque(cache, id), frameIDs) end +τ_scale = map(τs) do τs + 0.4/maximum(norm(τs)) +end + -arrows!(ls, positions, fs; lengthscale=f_scale, arrowsize=0.1, color=:red, ) -arrows!(ls, positions, τs; lengthscale=f_scale, arrowsize=0.1, color=:red, ) +arrows!(ls, positions, fs; lengthscale=f_scale, arrowsize=map(f->*(f, 50), f_scale), color=:red, ) +arrows!(ls, positions, τs; lengthscale=τ_scale, arrowsize=0.04, color=:blue, ) end diff --git a/src/components/components.jl b/src/components/components.jl index d2abfaa..639c97f 100644 --- a/src/components/components.jl +++ b/src/components/components.jl @@ -359,10 +359,8 @@ Add opspace force `f` to the cache for coordinate `c`. @inline function _add_opspace_force!(bundle::CacheBundle, c::C) where C<:ComponentData @assert hasfield(C, :coord) "Component '$c' does not have a field 'coord'. If this is a valid component, please implement `_add_opspace_force!` for it." f::SVector = opspace_force(bundle, c) - coord_id = c.coord - coord = bundle[coord_id] - f_cache_view(bundle, coord) .-= f # f is negated, due to the definition of bias forces. e.g. If a spring opspace force is Kz - nothing + f_view = f_cache_view(bundle, bundle[c.coord]) + f_view .-= f # f is negated, due to the definition of bias forces. e.g. If a spring opspace force is Kz end function _opspace_force(cache::CacheBundle, c::ComponentData) diff --git a/src/coordinates/coordinate_implementations.jl b/src/coordinates/coordinate_implementations.jl index fa2276d..df44b55 100644 --- a/src/coordinates/coordinate_implementations.jl +++ b/src/coordinates/coordinate_implementations.jl @@ -493,9 +493,9 @@ function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:FrameAngularVe c = mc.coord_data f_view = f_cache_view(cache, mc) @assert length(f_view) == 3 - f = f_cache_view(cache, mc)[SVector(1, 2, 3)] # Get the force applied to the coord as an SVector + f = f_cache_view(cache, mc)[SVector(1, 2, 3)] # Get the applied torque as an SVector fID = c.frameID - get_frame_torques(cache)[fID] += f + get_frame_torques(cache)[fID] += f # Apply torque to the frame nothing end diff --git a/src/interface.jl b/src/interface.jl index 514b50b..b560f80 100644 --- a/src/interface.jl +++ b/src/interface.jl @@ -481,8 +481,27 @@ end ===============================================================================# function inverse_dynamics! end -function _inverse_dynamics!(bundle::MechRNEBundle) - # Forward pass +function _inverse_dynamics!(bundle::MechRNEBundle) + _inverse_dynamics_forward_pass!(bundle) + _inverse_dynamics_zero!(bundle) + _inverse_dynamics_backward_pass_a!(bundle) + _inverse_dynamics_backward_pass_b!(bundle) + _inverse_dynamics_backward_pass_c!(bundle) + _inverse_dynamics_backward_pass_d!(bundle) + nothing +end + +function _inverse_dynamics_set_inputs!(bundle, t, q, q̇, q̈, gravity)! + t_cache, q_cache, q̇_cache, q̈_cache, g_cache, u_cache, = get_t(bundle), get_q(bundle), get_q̇(bundle), get_q̈(bundle), get_gravity(bundle), get_u(bundle) + + t_cache[] = t + copyto!(q_cache, q) + copyto!(q̇_cache, q̇) + copyto!(q̈_cache, q̈) + g_cache[] = gravity +end + +function _inverse_dynamics_forward_pass!(bundle) _acceleration_kinematics!(bundle) m, cache = bundle.mechanism, bundle.cache compute_in_coordinate_order(coordinates(m)) do coord @@ -490,60 +509,66 @@ function _inverse_dynamics!(bundle::MechRNEBundle) __velocity!(bundle, coord) __acceleration!(bundle, coord) end - - # - u = get_u(bundle) - frame_forces = get_frame_forces(bundle) - frame_torques = get_frame_torques(bundle) + nothing +end +function _inverse_dynamics_zero!(bundle) + u = get_u(bundle) + frame_forces, frame_torques = get_frame_forces(bundle), get_frame_torques(bundle) # Zero all coordinate/frame forces and torques. fill!(bundle.cache.coord_cache.f, zero(eltype(bundle.cache.coord_cache.f))) fill!(frame_forces, zero(eltype(frame_forces))) fill!(frame_torques, zero(eltype(frame_torques))) fill!(u, zero(eltype(u))) + nothing +end - # Backward pass - foreach(get_force_components(m)) do component # add forces for each component to coordinates +function _inverse_dynamics_backward_pass_a!(bundle) + # Add forces for each component to coordinates + foreach(get_force_components(bundle.mechanism)) do component _add_opspace_force!(bundle, component) - # @show f_cache_view(bundle, m[component.coord]) end - # @show frame_forces - # println("Backward pass part 1") - compute_in_reverse_coordinate_order(coordinates(m)) do coord # propagate forces through coordinates + # Now the force for each coordinate with a component *directly* attached to it is set + nothing +end + +function _inverse_dynamics_backward_pass_b!(bundle) + # Propagate forces through coordinates. + compute_in_reverse_coordinate_order(coordinates(bundle.mechanism)) do coord __propagate_opspace_force!(bundle, coord) - # @show frame_forces end - # println("Backward pass part 2") - for (parent, child) in Iterators.reverse(m.rbtree.walk) # propagate forces through frames/joints + # Now, *frame* forces/torques contain the force/torque applied to each frame by the components + nothing +end + +function _inverse_dynamics_backward_pass_c!(bundle) + frame_forces, frame_torques = get_frame_forces(bundle), get_frame_torques(bundle) + # propagate forces through frames/joints + for (parent, child) in Iterators.reverse(bundle.mechanism.rbtree.walk) # TODO check this order is correct... might not work frame_forces[parent] += frame_forces[child] - δ = origin(get_transform(cache, CompiledFrameID(parent))) - origin(get_transform(cache, CompiledFrameID(child))) - frame_torques[parent] += frame_torques[child] - cross(δ, frame_forces[child]) - # @show frame_forces + δ = origin(get_transform(bundle, CompiledFrameID(child))) - origin(get_transform(bundle, CompiledFrameID(parent))) + frame_torques[parent] += frame_torques[child] + cross(δ, frame_forces[child]) end +end + +function _inverse_dynamics_backward_pass_d!(bundle) + u = get_u(bundle) + frame_forces, frame_torques = get_frame_forces(bundle), get_frame_torques(bundle) # Project forces to joints - foreach(joints(m)) do joint + foreach(joints(bundle.mechanism)) do joint length(q_idxs(joint)) == 0 && return nothing p, c = joint.parentFrameID, joint.childFrameID - tf_p, tf_c = get_transform(cache, p), get_transform(cache, c) + tf_p, tf_c = get_transform(bundle, p), get_transform(bundle, c) f_p, τ_p, f_c, τ_c = frame_forces[p], frame_torques[p], frame_forces[c], frame_torques[c] u[q_idxs(joint)] .= _project_forces_to_jointspace(joint.jointData, tf_p, tf_c, f_p, f_c, τ_p, τ_c) nothing end - nothing end function inverse_dynamics!(bundle::MechRNEBundle, t, q, q̇, q̈, gravity) - t_cache, q_cache, q̇_cache, q̈_cache, g_cache, u_cache, = - get_t(bundle), get_q(bundle), get_q̇(bundle), get_q̈(bundle), get_gravity(bundle), get_u(bundle) - - t_cache[] = t - copyto!(q_cache, q) - copyto!(q̇_cache, q̇) - copyto!(q̈_cache, q̈) - g_cache[] = gravity + _inverse_dynamics_set_inputs!(bundle, t, q, q̇, q̈, gravity) _inverse_dynamics!(bundle) - - u_cache + get_u(bundle) end diff --git a/src/joints/joint_definitions.jl b/src/joints/joint_definitions.jl index 5454f04..4625ab9 100644 --- a/src/joints/joint_definitions.jl +++ b/src/joints/joint_definitions.jl @@ -617,7 +617,13 @@ end ###################### function _project_forces_to_jointspace(j::RevoluteData, tf_p::Transform{T}, tf_c::Transform{T}, f_p::S, f_c::S, τ_p::S, τ_c::S) where {T, S<: SVector{3, T}} - axis = rotor(tf_p) * j.axis - τ = -dot(axis, τ_p) + # The torque is expressed in the world frame at the origin of the child frame. + # To get the axis in the same rotational frame, we first get it in the parent frame, + # then rotate it to the world frame + + # The minus sign is due to the fact that the torque is expressed on the right side of the + # equation + τ = -dot(rotor(tf_p) * rotor(j.transform) * j.axis, τ_c) + return SVector(τ) end \ No newline at end of file diff --git a/test/inverse_dynamics_test.jl b/test/inverse_dynamics_test.jl index 5551719..33edc7f 100644 --- a/test/inverse_dynamics_test.jl +++ b/test/inverse_dynamics_test.jl @@ -24,8 +24,6 @@ function _test_inverse_dynamics(m, time, q, q̇, gravity) # get_u(icache) is the result of the inverse dynamics computation, and should be equal to u @test get_u(icache) ≈ u atol=1e-7 rtol=1e-7 - # @show icache.cache.frame_cache.forces[6] - icache.cache.frame_cache.rbstates[6].acceleration.linear - # if isa(m, CompiledMechanism) # elseif isa(m, CompiledVirtualMechanismSystem) diff --git a/test/runtests.jl b/test/runtests.jl index 7f69b31..fdaf24b 100644 --- a/test/runtests.jl +++ b/test/runtests.jl @@ -1,111 +1,4 @@ -using Pkg - -## If running lots of tests, do this: -# using TestEnv -# TestEnv.activate("VMRobotControl") - -# TEST_ENZYME = "Enzyme" ∈ keys(Pkg.project().dependencies) -TEST_ENZYME = false -# TEST_ENZYME = true - - -using DiffResults -using FileIO -using ForwardDiff -using LinearAlgebra -using ProgressMeter -using Random - -using VMRobotControl - -using VMRobotControl: joint_transform, joint_twist, joint_vpa, jacobian_column, AbstractJointData -using VMRobotControl: Twist, SpatialAcceleration -using VMRobotControl.Hessians: my_hessian, hessian_vector_product -using VMRobotControl.Transforms: angular_velocity, AxisAngle, AxisAngleDerivative, quatmul_matrix, quatmul_geodual_bivector_matrix -using VMRobotControl: get_inertance_components -using VMRobotControl: Storage, Inertance, GenericComponent - -using StaticArrays -# using StatsBase: sample -using Test -using UUIDs - -try - FileIO.add_format(format"DAE", (), ".dae", [:DigitalAssetExchangeFormatIO => UUID("43182933-f65b-495a-9e05-4d939cea427d")]) -catch e - if e == ErrorException("format DAE is already registered") - else - rethrow(e) - end -end - -if TEST_ENZYME - @info "Enabling Enzyme tests" - import Enzyme - using Enzyme: - autodiff, - Active, - Const, - Duplicated, - Reverse -end - -################################################################################ - -function test_on_mechanisms(test, mechanisms::Vector) - @showprogress desc=string(test) for m in mechanisms - @testset "Robot: '$(name(m))'" begin - test(m) - end - end -end - -module_path = joinpath(splitpath(dirname(pathof(VMRobotControl)))[1:end-1]) -# Walk dir to find all rsons -rsons = String[] -for (root, dirs, files) in walkdir(joinpath(module_path, "RSONs")) - for file in files - if endswith(file, ".rson") - path = joinpath(root, file) - push!(rsons, path) - end - end -end - -urdfs = joinpath.((module_path,), ("URDFs",), [ - "sciurus17_description/urdf/sciurus17.urdf", - "franka_description/urdfs/fr3.urdf" -]) - - -systems = let - p = Progress(length(rsons) + length(urdfs); desc="Parsing robot files...", dt=0.1) - systems = Any[] - for rson in rsons - rson_parser_cfg = RSONParserConfig(; parse_visuals=false, suppress_warnings=false, error_on_not_recognized=false) - push!(systems, parseRSON(rson, rson_parser_cfg)) - next!(p) - end - urdf_parser_cfg = URDFParserConfig(;parse_visuals=false, suppress_warnings=true) - for urfd in urdfs - push!(systems, parseURDF(urfd, urdf_parser_cfg)) - next!(p) - end - systems -end - -compiled_systems = @showprogress desc="Compiling Robots/Virtual Mechanism Systems" dt=0.2 map(compile, systems) -compiled_mechanisms = [s for s in compiled_systems if s isa CompiledMechanism] - -# For dynamics tests, only consider systems with any inertances defined -systems_with_inertances = [s - for s in compiled_systems - if ( - (isa(s, CompiledMechanism) && !isempty(get_inertance_components(s))) - || - (isa(s, CompiledVirtualMechanismSystem) && !isempty(get_inertance_components(s.robot)) && !isempty(get_inertance_components(s.virtual_mechanism))) - ) -] +include("setup_test_mechanisms.jl") if isdefined(Main, :Revise) Revise.includet("pendulum_test.jl") diff --git a/test/runtests_manual.jl b/test/runtests_manual.jl new file mode 100644 index 0000000..134df4b --- /dev/null +++ b/test/runtests_manual.jl @@ -0,0 +1,38 @@ +begin + using TestEnv + TestEnv.activate("VMRobotControl") + + include("setup_test_mechanisms.jl") + + Revise.includet("pendulum_test.jl") + Revise.includet("scara_test.jl") + Revise.includet("joint_test.jl") + Revise.includet("velocity_kinematics_test.jl") + Revise.includet("coordinate_test.jl") + Revise.includet("dynamics_test.jl") + Revise.includet("inverse_dynamics_test.jl") + Revise.includet("energy_test.jl") + Revise.includet("rson_test.jl") + Revise.includet("Enzyme_compat_test.jl") +end + +# Run one at a time by highlighting a line +results = @testset "All tests" begin + results = pendulum_tests(); + results = scara_tests(); + results = single_joint_tests(mobile_jointtypes); + results = single_joint_mechanism_tests(all_jointtypes); + results = double_joint_tests(mobile_jointtypes); + results = double_joint_mechanism_tests(all_jointtypes); + small_immut_mechanisms = [m for m in compiled_mechanisms if ndof(m) < 5]; + results = @testset "Velocity Kinematics FD" test_on_mechanisms(test_velocity_kinematics_vs_finitediff, compiled_mechanisms); + results = @testset "Velocity Kinematics AD" test_on_mechanisms(test_velocity_kinematics_vs_autodiff, small_immut_mechanisms); + results = @testset "Coordinate tests" test_on_mechanisms(test_coordinates, compiled_systems); + results = @testset "Dynamics tests" test_on_mechanisms(test_dynamics, systems_with_inertances); + results = @testset "Inverse Dynamics tests" test_on_mechanisms(test_inverse_dynamics, compiled_mechanisms); # TODO + results = @testset "Energy tests" test_on_mechanisms(test_energy, systems_with_inertances); + results = @testset "RSON tests" test_on_mechanisms(test_rson, systems); + # TODO ForwardDiff compat tests + TEST_ENZYME && (@testset "Enzyme compat tests" test_on_mechanisms(test_enzyme_compat, compiled_systems)); +end; +nothing diff --git a/test/setup_test_mechanisms.jl b/test/setup_test_mechanisms.jl new file mode 100644 index 0000000..5cd3a94 --- /dev/null +++ b/test/setup_test_mechanisms.jl @@ -0,0 +1,102 @@ +# TEST_ENZYME = "Enzyme" ∈ keys(Pkg.project().dependencies) +TEST_ENZYME = false +# TEST_ENZYME = true + + +using DiffResults +using FileIO +using ForwardDiff +using LinearAlgebra +using ProgressMeter +using Random + +using VMRobotControl + +using VMRobotControl: joint_transform, joint_twist, joint_vpa, jacobian_column, AbstractJointData +using VMRobotControl: Twist, SpatialAcceleration +using VMRobotControl.Hessians: my_hessian, hessian_vector_product +using VMRobotControl.Transforms: angular_velocity, AxisAngle, AxisAngleDerivative, quatmul_matrix, quatmul_geodual_bivector_matrix +using VMRobotControl: get_inertance_components +using VMRobotControl: Storage, Inertance, GenericComponent + +using StaticArrays +# using StatsBase: sample +using Test +using UUIDs + +try + FileIO.add_format(format"DAE", (), ".dae", [:DigitalAssetExchangeFormatIO => UUID("43182933-f65b-495a-9e05-4d939cea427d")]) +catch e + if e == ErrorException("format DAE is already registered") + else + rethrow(e) + end +end + +if TEST_ENZYME + @info "Enabling Enzyme tests" + import Enzyme + using Enzyme: + autodiff, + Active, + Const, + Duplicated, + Reverse +end + +################################################################################ + +function test_on_mechanisms(test, mechanisms::Vector) + @showprogress desc=string(test) for m in mechanisms + @testset "Robot: '$(name(m))'" begin + test(m) + end + end +end + +module_path = joinpath(splitpath(dirname(pathof(VMRobotControl)))[1:end-1]) +# Walk dir to find all rsons +rsons = String[] +for (root, dirs, files) in walkdir(joinpath(module_path, "RSONs")) + for file in files + if endswith(file, ".rson") + path = joinpath(root, file) + push!(rsons, path) + end + end +end + +urdfs = joinpath.((module_path,), ("URDFs",), [ + "sciurus17_description/urdf/sciurus17.urdf", + "franka_description/urdfs/fr3.urdf" +]) + + +systems = let + p = Progress(length(rsons) + length(urdfs); desc="Parsing robot files...", dt=0.1) + systems = Any[] + for rson in rsons + rson_parser_cfg = RSONParserConfig(; parse_visuals=false, suppress_warnings=false, error_on_not_recognized=false) + push!(systems, parseRSON(rson, rson_parser_cfg)) + next!(p) + end + urdf_parser_cfg = URDFParserConfig(;parse_visuals=false, suppress_warnings=true) + for urfd in urdfs + push!(systems, parseURDF(urfd, urdf_parser_cfg)) + next!(p) + end + systems +end + +compiled_systems = @showprogress desc="Compiling Robots/Virtual Mechanism Systems" dt=0.2 map(compile, systems) +compiled_mechanisms = [s for s in compiled_systems if s isa CompiledMechanism] + +# For dynamics tests, only consider systems with any inertances defined +systems_with_inertances = [s + for s in compiled_systems + if ( + (isa(s, CompiledMechanism) && !isempty(get_inertance_components(s))) + || + (isa(s, CompiledVirtualMechanismSystem) && !isempty(get_inertance_components(s.robot)) && !isempty(get_inertance_components(s.virtual_mechanism))) + ) +] From 3232f7a5c52be4e27de75ae3c7444f91b024cf3d Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Wed, 5 Mar 2025 15:30:51 +0000 Subject: [PATCH 05/12] Updated RNE support for more coordinates/joints. Improved testing. Not all tests pass --- src/coordinates/coordinate_implementations.jl | 111 +++++++++++++++--- src/coordinates/coordinates.jl | 2 +- src/joints/joint_definitions.jl | 13 +- src/joints/mechanism_joint.jl | 30 +++++ test/inverse_dynamics_test.jl | 40 +++++-- 5 files changed, 167 insertions(+), 29 deletions(-) diff --git a/src/coordinates/coordinate_implementations.jl b/src/coordinates/coordinate_implementations.jl index df44b55..94a9b0e 100644 --- a/src/coordinates/coordinate_implementations.jl +++ b/src/coordinates/coordinate_implementations.jl @@ -62,6 +62,13 @@ end @inline __acceleration!(cache::CacheBundle, c::CMC{<:CoordDifference}) = nothing +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:CoordDifference}) + f_view = f_cache_view(cache, mc) + f_cache_view(cache, cache[mc.coord_data.parent]) .+= f_view + f_cache_view(cache, cache[mc.coord_data.child]) .-= f_view + nothing +end + function _configuration(cache::CacheBundle, c::CMC{<:CoordDifference}) z_p = _configuration(cache, c.coord_data.parent) z_c = _configuration(cache, c.coord_data.child) @@ -106,6 +113,14 @@ end @inline __acceleration!(cache::CacheBundle, c::CMC{<:CoordSum}) = nothing +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:CoordSum}) + f_view = f_cache_view(cache, mc) + f_cache_view(cache, cache[mc.coord_data.c1]) .+= f_view + f_cache_view(cache, cache[mc.coord_data.c2]) .+= f_view + nothing +end + + function _configuration(cache::CacheBundle, c::CMC{<:CoordSum}) z_1 = _configuration(cache, c.coord_data.c1) z_2 = _configuration(cache, c.coord_data.c2) @@ -131,15 +146,16 @@ end # CoordStack #################################################################################################### -@inline __configuration!(cache::CacheBundle, c::CMC{<:CoordStack}) = nothing -@inline __velocity!(cache::CacheBundle, c::CMC{<:CoordStack}) = nothing -function __jacobian!(cache::CacheBundle, c::CMC{<:CoordStack}) - J_ret = J_cache_view(cache, c) +@inline __configuration!(cache::CacheBundle, mc::CMC{<:CoordStack}) = nothing +@inline __velocity!(cache::CacheBundle, mc::CMC{<:CoordStack}) = nothing +function __jacobian!(cache::CacheBundle, mc::CMC{<:CoordStack}) + c = mc.coord_data + J_ret = J_cache_view(cache, mc) fill!(J_ret, zero(eltype(J_ret))) - J_ret_1 = _vms_jacobian_result_view(cache, J_ret, c.coord_data.c1) - J_ret_2 = _vms_jacobian_result_view(cache, J_ret, c.coord_data.c2) - J1 = _jacobian(cache, c.coord_data.c1) - J2 = _jacobian(cache, c.coord_data.c2) + J_ret_1 = _vms_jacobian_result_view(cache, J_ret, c.c1) + J_ret_2 = _vms_jacobian_result_view(cache, J_ret, c.c2) + J1 = _jacobian(cache, c.c1) + J2 = _jacobian(cache, c.c2) # Instead, do it manually Nc1 = size(J1, 1) J_ret_1[1:Nc1, :] .= J1 @@ -148,6 +164,19 @@ function __jacobian!(cache::CacheBundle, c::CMC{<:CoordStack}) end @inline __acceleration!(cache::CacheBundle, c::CMC{<:CoordStack}) = nothing +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:CoordStack}) + f_view = f_cache_view(cache, mc) + f2 = f_cache_view(cache, cache[mc.coord_data.c2]) + f1 = f_cache_view(cache, cache[mc.coord_data.c1]) + for i in 1:length(f1) + f1[i] += f_view[i] + end + for i in 1:length(f2) + f2[i] += f_view[i+length(f1)] + end + nothing +end + function _configuration(cache::CacheBundle, c::CMC{<:CoordStack}) z1 = _configuration(cache, c.coord_data.c1) z2 = _configuration(cache, c.coord_data.c2) @@ -179,6 +208,15 @@ end @inline __jacobian!(cache::CacheBundle, c::CMC{<:CoordSlice}) = nothing @inline __acceleration!(cache::CacheBundle, c::CMC{<:CoordSlice}) = nothing +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:CoordSlice}) + f_applied = f_cache_view(cache, mc) + f_ret = f_cache_view(cache, mc.coord_data.coord) + for (i, idx) in enumerate(mc.coord_data.idxs) + f_ret[idx] += f_applied[i] + end + nothing +end + function _configuration(cache::CacheBundle, c::CMC{<:CoordSlice}) _configuration(cache, c.coord_data.coord)[c.coord_data.idxs] end @@ -206,6 +244,7 @@ function __jacobian!(cache::CacheBundle, c::CMC{<:ConstCoord}) nothing end @inline __acceleration!(cache::CacheBundle, c::CMC{<:ConstCoord}) = nothing +@inline __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:ConstCoord}) = nothing _configuration(cache::CacheBundle, c::CMC{<:ConstCoord{Nc, Tc}}) where {Tc, Nc} = SVector{Nc, eltype(cache)}(c.coord_data.val) _velocity(cache::CacheBundle, c::CMC{<:ConstCoord{Nc, Tc}}) where {Tc, Nc} = zero(SVector{Nc, eltype(cache)}) @@ -224,6 +263,7 @@ function __jacobian!(cache::CacheBundle, c::CMC{<:ReferenceCoord}) nothing end @inline __acceleration!(cache::CacheBundle, c::CMC{<:ReferenceCoord}) = nothing +@inline __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:ReferenceCoord}) = nothing _configuration( cache::CacheBundle, c::CMC{<:ReferenceCoord{Nc, Tc}}) where {Tc, Nc} = SVector{Nc, eltype(cache)}(c.coord_data.val[]) _velocity( cache::CacheBundle, c::CMC{<:ReferenceCoord{Nc, Tc}}) where {Tc, Nc} = SVector{Nc, eltype(cache)}(c.coord_data.vel[]) @@ -246,6 +286,13 @@ function __jacobian!(cache::CacheBundle, c::CMC{<:JointSubspace}) nothing end @inline __acceleration!(cache::CacheBundle, c::CMC{<:JointSubspace}) = nothing +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:JointSubspace}) + f_view = f_cache_view(cache, mc) + @assert length(f_view) == 1 + _apply_joint_force_to_frames!(cache, mc.coord_data.joint, f_view[1]) + nothing +end + _configuration(cache::CacheBundle, c::CMC{<:JointSubspace}) = get_q(cache, c.coord_data.joint) _velocity(cache::CacheBundle, c::CMC{<:JointSubspace}) = get_q̇(cache, c.coord_data.joint) @@ -364,7 +411,10 @@ function __jacobian!(cache::CacheBundle, c::CMC{<:FrameOrigin}) nothing end __acceleration!(cache::CacheBundle, c::CMC{<:FrameOrigin}) = nothing -__propagate_opspace_force!(cache::CacheBundle, c::CMC{<:FrameOrigin}) = get_frame_forces(cache)[c.coord_data.frameID] += f_cache_view(cache, c) +function __propagate_opspace_force!(cache::CacheBundle, c::CMC{<:FrameOrigin}) + get_frame_forces(cache)[c.coord_data.frameID] += f_cache_view(cache, c) + nothing +end _configuration(cache::CacheBundle, c::CMC{<:FrameOrigin}) = origin(get_transform(cache, c.coord_data.frameID)) _velocity(cache::CacheBundle, c::CMC{<:FrameOrigin}) = get_linear_vel(cache, c.coord_data.frameID) @@ -439,7 +489,7 @@ function __acceleration!(cache::CacheBundle, cmc::CMC{<:QuaternionAttitude}) α_cache_view(cache, cmc) .= bivector(ddrotor_tf) end -# function __propagate_opspace_force!(cache::CacheBundle, cmc::CMC{<:QuaternionAttitude}, f) +function __propagate_opspace_force!(cache::CacheBundle, cmc::CMC{<:QuaternionAttitude}) # c = cmc.coord_data # fID = c.frameID @@ -462,7 +512,7 @@ end # τ = cross(configuration(cache, cmc), f) # get_frame_torques(cache)[fID] .+= τ # nothing -# end +end _configuration(cache::CacheBundle, cmc::CMC{<:QuaternionAttitude}) = SVector{length(cmc), eltype(cache)}(z_cache_view(cache, cmc)) _velocity(cache::CacheBundle, cmc::CMC{<:QuaternionAttitude}) = SVector{length(cmc), eltype(cache)}(ż_cache_view(cache, cmc)) @@ -484,11 +534,6 @@ function __jacobian!(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) end __acceleration!(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = nothing -# _configuration(cache::MechanismCacheBundle, c::CMC{<:FrameAngularVelocity}) = rotor(transform(cache, c.coord_data.frameID)) -_velocity(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = get_angular_vel(cache, c.coord_data.frameID) -_jacobian(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = J_cache_view(cache, c) -_acceleration(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = _get_angular_acc(cache, c.coord_data.frameID) - function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:FrameAngularVelocity}) c = mc.coord_data f_view = f_cache_view(cache, mc) @@ -499,6 +544,10 @@ function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:FrameAngularVe nothing end +# _configuration(cache::MechanismCacheBundle, c::CMC{<:FrameAngularVelocity}) = rotor(transform(cache, c.coord_data.frameID)) +_velocity(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = get_angular_vel(cache, c.coord_data.frameID) +_jacobian(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = J_cache_view(cache, c) +_acceleration(cache::CacheBundle, c::CMC{<:FrameAngularVelocity}) = _get_angular_acc(cache, c.coord_data.frameID) #################################################################################################### # CoordNorm @@ -546,6 +595,20 @@ function __acceleration!(cache::CacheBundle, c::CMC{<:CoordNorm}) α_cache_view(cache, c) .= αᵢ end +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:CoordNorm}) + c = mc.coord_data + f_view = f_cache_view(cache, mc) + @assert length(f_view) == 1 + f_ret = f_cache_view(cache, cache[c.coord]) + zₐ = _configuration(cache, c.coord) + zᵢ = _configuration(cache, mc) + for i in 1:length(f_ret) + f_ret[i] += f_view[1] * zₐ[i] / zᵢ[1] + end + nothing +end + + _configuration(cache::CacheBundle, c::CMC{<:CoordNorm}) = SVector(z_cache_view(cache, c)[1]) _velocity(cache::CacheBundle, c::CMC{<:CoordNorm}) = SVector(ż_cache_view(cache, c)[1]) _jacobian(cache::CacheBundle, c::CMC{<:CoordNorm}) = J_cache_view(cache, c) @@ -626,6 +689,15 @@ function __acceleration!(cache::CacheBundle, cmc::CMC{<:RotatedCoord}) nothing end +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:RotatedCoord}) + c = mc.coord_data + f_view = f_cache_view(cache, mc) + f_ret = f_cache_view(cache, cache[c.world_frame_coord]) + nothing +end + + + _configuration(cache::CacheBundle, cmc::CMC{<:RotatedCoord}) = SVector{length(cmc)}(z_cache_view(cache, cmc)) _velocity(cache::CacheBundle, cmc::CMC{<:RotatedCoord}) = SVector{length(cmc)}(ż_cache_view(cache, cmc)) _jacobian(cache::CacheBundle, cmc::CMC{<:RotatedCoord}) = J_cache_view(cache, cmc) @@ -711,6 +783,13 @@ function __acceleration!(cache::CacheBundle, cmc::CMC{<:UnrotatedCoord}) nothing end +function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:UnrotatedCoord}) + c = mc.coord_data + f_view = f_cache_view(cache, mc) + f_ret = f_cache_view(cache, cache[c.link_frame_coord]) + nothing +end + _configuration(cache::CacheBundle, cmc::CMC{<:UnrotatedCoord}) = SVector{length(cmc)}(z_cache_view(cache, cmc)) _velocity(cache::CacheBundle, cmc::CMC{<:UnrotatedCoord}) = SVector{length(cmc)}(ż_cache_view(cache, cmc)) _jacobian(cache::MechanismCacheBundle, cmc::CMC{<:UnrotatedCoord}) = J_cache_view(cache, cmc) diff --git a/src/coordinates/coordinates.jl b/src/coordinates/coordinates.jl index 7e41ae8..2b69af7 100644 --- a/src/coordinates/coordinates.jl +++ b/src/coordinates/coordinates.jl @@ -19,7 +19,7 @@ struct CompiledCoord{C<:CoordinateData} cache_idxs::UnitRange{Int} end -Base.show(io::IO, ::Type{<:CompiledCoord{C}}) where C = print(io, "CompiledCoord{$C}") +# Base.show(io::IO, ::Type{<:CompiledCoord{C}}) where C = print(io, "CompiledCoord{$C}") """ CompiledCoordID{C} diff --git a/src/joints/joint_definitions.jl b/src/joints/joint_definitions.jl index 4625ab9..f545f53 100644 --- a/src/joints/joint_definitions.jl +++ b/src/joints/joint_definitions.jl @@ -623,7 +623,12 @@ function _project_forces_to_jointspace(j::RevoluteData, tf_p::Transform{T}, tf_c # The minus sign is due to the fact that the torque is expressed on the right side of the # equation - τ = -dot(rotor(tf_p) * rotor(j.transform) * j.axis, τ_c) - - return SVector(τ) -end \ No newline at end of file + u = -dot(rotor(tf_p) * rotor(j.transform) * j.axis, τ_c) + return SVector(u) +end + +function _project_forces_to_jointspace(j::PrismaticData, tf_p::Transform{T}, tf_c::Transform{T}, f_p::S, f_c::S, τ_p::S, τ_c::S) where {T, S<: SVector{3, T}} + # Rotate axis to world frame, then dot with force + u = -dot(rotor(tf_c) * j.axis, f_c) + return SVector(u) +end diff --git a/src/joints/mechanism_joint.jl b/src/joints/mechanism_joint.jl index 9ca7e6f..a70c77d 100644 --- a/src/joints/mechanism_joint.jl +++ b/src/joints/mechanism_joint.jl @@ -141,3 +141,33 @@ function q̇_idxs(j::CompiledMechanismJoint) end Base.show(io::IO, ::Type{CompiledMechanismJoint{T, JD}}) where {T, JD} = print(io, "CompiledMechanismJoint($T, $JD)") + + + + +###################### +# Apply forces to frames +###################### + +# This must come after the definition of CompiledJointID... hence living here + +function _apply_joint_force_to_frames!(bundle, jID::CompiledJointID, u::Real) + # Axis in world frame + mj = bundle[jID] + _apply_joint_force_to_frames!(bundle, mj.jointData, mj.parentFrameID, mj.childFrameID, u) + nothing +end + + +function _apply_joint_force_to_frames!( + bundle::CacheBundle, + jointData::RevoluteData, + parentFrameID::CompiledFrameID, + childFrameID::CompiledFrameID, + u::Real) + # Axis in world frame + axis = rotor(get_transform(bundle, parentFrameID)) * jointData.axis + get_frame_torques(bundle)[parentFrameID] -= axis * u + get_frame_torques(bundle)[childFrameID] += axis * u + nothing +end diff --git a/test/inverse_dynamics_test.jl b/test/inverse_dynamics_test.jl index 33edc7f..7dcf2f5 100644 --- a/test/inverse_dynamics_test.jl +++ b/test/inverse_dynamics_test.jl @@ -5,26 +5,50 @@ function test_inverse_dynamics(m; N=20) t = 0.0 q = rand!(rng, zero_q(Float64, m)) q̇ = rand!(rng, zero_q̇(Float64, m)) + q̈ = rand!(rng, zero_q̈(Float64, m)) gravity = randn(rng, SVector{3, Float64}) - _test_inverse_dynamics(m, t, q, q̇, gravity) + _test_inverse_dynamics(m, t, q, q̇, q̈, gravity; rng) end end -function _test_inverse_dynamics(m, time, q, q̇, gravity) +function _test_inverse_dynamics(m, time, q, q̇, q̈, gravity; rng=MersenneTwister(1234)) u = zero_u(Float64, m) icache = new_inverse_dynamics_cache(m) - dcache = new_dynamics_cache(m) + dcache = new_dynamics_cache(m) + ############################ + # Test 1 + # Run forward dynamics then inverse dynamics, and compare the control input dynamics!(dcache, time, q, q̇, gravity, u) - q̈ = get_q̈(dcache) - inverse_dynamics!(icache, time, q, q̇, q̈, gravity) - - # u is the control input used to compute forward dynamics, and is correct - # get_u(icache) is the result of the inverse dynamics computation, and should be equal to u + inverse_dynamics!(icache, time, q, q̇, get_q̈(dcache), gravity) @test get_u(icache) ≈ u atol=1e-7 rtol=1e-7 + ############################ + # Test 2 + # Run inverse dynamics then forward dynamics, and compare the acceleration + inverse_dynamics!(icache, time, q, q̇, q̈, gravity) + dynamics!(dcache, time, q, q̇, gravity, get_u(icache)) + @test get_q̈(dcache) ≈ q̈ atol=1e-7 rtol=1e-7 + + ############################ + # Test 3 + # Run inverse dynamics with a single coordinate and compare to jacobian transpose method + VMRobotControl._inverse_dynamics_set_inputs!(icache, time, q, 0 .* q̇, 0 .* q̈, 0 * gravity) + VMRobotControl._inverse_dynamics_forward_pass!(icache) + for coordID in values(m.rbtree.coord_id_map) + VMRobotControl._inverse_dynamics_zero!(icache) + # Apply random force to the coordinate + f = randn(rng, length(icache[coordID])) + VMRobotControl.f_cache_view(icache, icache[coordID]) .+= f + VMRobotControl._inverse_dynamics_backward_pass_a!(icache) + VMRobotControl._inverse_dynamics_backward_pass_b!(icache) + VMRobotControl._inverse_dynamics_backward_pass_c!(icache) + VMRobotControl._inverse_dynamics_backward_pass_d!(icache) + J = jacobian(dcache, coordID) + @test get_u(icache) ≈ -J' * f + end # if isa(m, CompiledMechanism) # elseif isa(m, CompiledVirtualMechanismSystem) # end From a74e9674975f9f0ae41d997101bb54de61dfbc2a Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Fri, 7 Mar 2025 15:40:20 +0000 Subject: [PATCH 06/12] Fixes, add RectifiedSpring/RELUSpring to docs, remove from compliant_path_following.jl example. Fix URDF parsing mesh scaling. --- docs/src/api/api.md | 1 + examples/compliant_path_following.jl | 4 ++-- src/components/storages.jl | 11 +++++++++++ src/mesh_utils.jl | 14 +++++++++++++- src/urdf/parse_urdf.jl | 9 ++++++--- 5 files changed, 33 insertions(+), 6 deletions(-) diff --git a/docs/src/api/api.md b/docs/src/api/api.md index 85d0ca2..84d1fa9 100644 --- a/docs/src/api/api.md +++ b/docs/src/api/api.md @@ -162,6 +162,7 @@ VMRobotControl.Storage LinearSpring TanhSpring GaussianSpring +RectifiedSpring GravityCompensator ForceSource PowerSource diff --git a/examples/compliant_path_following.jl b/examples/compliant_path_following.jl index 07855be..7c0b601 100644 --- a/examples/compliant_path_following.jl +++ b/examples/compliant_path_following.jl @@ -128,8 +128,8 @@ add_component!(vm, LinearDamper(100.0, "CartPosition"); id="CartDamper"); # the force will be reduced to ensure that the power does not exceed 10W. vms = VirtualMechanismSystem("System", robot, vm) err_coord = CoordDifference(".virtual_mechanism.CartPosition", ".robot.TCP") -err_spring = LinearSpring(3000.0 * identity(3), "CartError") -err_damper = LinearDamper(50.0 * identity(3), "CartError") +err_spring = LinearSpring(3000.0, "CartError") +err_damper = LinearDamper(50.0, "CartError") add_coordinate!(vms, err_coord; id="CartError") add_component!(vms, err_spring; id="CartErrSpring") diff --git a/src/components/storages.jl b/src/components/storages.jl index 61621bf..c26a856 100644 --- a/src/components/storages.jl +++ b/src/components/storages.jl @@ -300,7 +300,18 @@ end ############################ # ReLUSpring ############################ +""" + RectifiedSpring(stiffness, coord, flipped::Bool) + ReLUSpring(stiffness, coord, flipped::Bool) + +A linear spring which acts only when the coordinate is positive (flipped=false) or negative +(flipped=true). +Check implementation details if applying to any coordinate larger than 1D, to ensure +behaviour is as expected. + +See also [`add_deadzone_springs`](@ref). +""" @kwdef struct RectifiedSpring{T<:Real, K, C} <: Storage{T} stiffness::K coord::C diff --git a/src/mesh_utils.jl b/src/mesh_utils.jl index f3952a2..6022e58 100644 --- a/src/mesh_utils.jl +++ b/src/mesh_utils.jl @@ -6,7 +6,19 @@ end transform_mesh(mesh, tf::Nothing) = mesh -function rescale_mesh(mesh, scale) + +function rescale_geometry(geom, scale) + if typeof(geom) <: GeometryBasics.Mesh + return rescale_mesh(geom, scale) + elseif typeof(geom) <: Vector{<:Tuple{<:GeometryBasics.Mesh, <:Any}} + return [(rescale_mesh(mesh, scale), kwargs) for (mesh, kwargs) in geom] + else + error("Unsupported geometry type: $(typeof(geom))") + end +end + + +function rescale_mesh(mesh::GeometryBasics.Mesh, scale) c, f = GeometryBasics.coordinates(mesh), GeometryBasics.faces(mesh) if prod(scale)< 0 # If scaling will turn the mesh inside out, then reverse the chirality of the faces by diff --git a/src/urdf/parse_urdf.jl b/src/urdf/parse_urdf.jl index aedd06a..8b7a51b 100644 --- a/src/urdf/parse_urdf.jl +++ b/src/urdf/parse_urdf.jl @@ -150,7 +150,8 @@ function parse_link!(mechanism, link, cfg) end function parse_inertial!(mechanism, inertial, link_frame, cfg) - transform = nothing + # Default to no transform + transform = zero(Transform{cfg.element_type}) mass = nothing inertia = nothing for node in eachelement(inertial) @@ -287,11 +288,13 @@ function parse_geometry(geometry_node, cfg) geom = Sphere3{Float64}(SVector(0, 0, 0), r) elseif nn == "mesh" filename = node["filename"] - geom = load_mesh(filename, cfg) + geom = load_mesh(filename, cfg) + # This will either be a mesh, or vector of tuples containing mesh and kwargs for + # visual properties if haskey(node, "scale") scale_vec = parse_3vec(node["scale"], cfg) scale = GeometryBasics.Point{3, Float64}(scale_vec...) - geom = VMRobotControl.rescale_mesh(geom, scale) + geom = VMRobotControl.rescale_geometry(geom, scale) end else raise_not_recognized(nn, cfg) From 5b6e6d0eabdb0b34631cd22e76724d6317df48fa Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Fri, 7 Mar 2025 15:40:46 +0000 Subject: [PATCH 07/12] Add URDF of shadow robotics hand. --- URDFs/sr_description/LICENSE | 28 ++ URDFs/sr_description/README.md | 7 + .../cable_connector_base_E3M5.dae | 83 +++++ .../cable_connector_palm_E3M5.dae | 83 +++++ .../f_distal/bt_2p/f_distal_bt_2p.dae | 235 ++++++++++++++ .../f_distal/bt_2p/f_distal_bt_2p_adapter.dae | 126 ++++++++ .../f_distal/bt_sp/f_distal_bt_sp.dae | 128 ++++++++ .../components/f_distal/mst/f_distal_mst.dae | 134 ++++++++ .../f_distal/mst/f_distal_mstXL.dae | 134 ++++++++ .../components/f_distal/pst/f_distal_pst.dae | 132 ++++++++ .../f_distal/pst/f_distal_pst_scaled.dae | 210 ++++++++++++ .../components/f_knuckle/f_knuckle_C6M2.dae | 133 ++++++++ .../components/f_knuckle/f_knuckle_E2M3.dae | 133 ++++++++ .../components/f_knuckle/f_knuckle_E3M5.dae | 133 ++++++++ .../f_knuckle_E3M5_no_rot_scaled.dae | 210 ++++++++++++ .../f_knuckle/f_knuckle_E3M5_scaled.dae | 153 +++++++++ .../components/f_knuckle/f_knuckle_E4.dae | 133 ++++++++ .../components/f_knuckle/f_knuckle_G1M5.dae | 133 ++++++++ .../components/f_knuckle/f_knuckle_G4.dae | 133 ++++++++ .../components/f_middle/f_middle_C6M2.dae | 139 ++++++++ .../components/f_middle/f_middle_E2M3.dae | 139 ++++++++ .../components/f_middle/f_middle_E3M5.dae | 139 ++++++++ .../f_middle/f_middle_E3M5_no_rot_scaled.dae | 210 ++++++++++++ .../components/f_middle/f_middle_E4.dae | 130 ++++++++ .../components/f_middle/f_middle_G1M5.dae | 139 ++++++++ .../components/f_middle/f_middle_G4.dae | 139 ++++++++ .../components/f_proximal/f_proximal_C6M2.dae | 139 ++++++++ .../components/f_proximal/f_proximal_E2M3.dae | 139 ++++++++ .../components/f_proximal/f_proximal_E3M5.dae | 139 ++++++++ .../f_proximal_E3M5_no_rot_scaled.dae | 153 +++++++++ .../f_proximal/f_proximal_E3M5_scaled.dae | 153 +++++++++ .../components/f_proximal/f_proximal_E4.dae | 139 ++++++++ .../components/f_proximal/f_proximal_G1M5.dae | 139 ++++++++ .../components/f_proximal/f_proximal_G4.dae | 139 ++++++++ .../components/forearm/forearm_C6M2.dae | 134 ++++++++ .../components/forearm/forearm_E2M3.dae | 202 ++++++++++++ .../components/forearm/forearm_E3M5.dae | 262 +++++++++++++++ .../forearm/forearm_E3M5_scaled.dae | 299 +++++++++++++++++ .../meshes/components/forearm/forearm_E4.dae | 304 ++++++++++++++++++ .../components/forearm/forearm_G1M5.dae | 122 +++++++ .../meshes/components/forearm/forearm_G4.dae | 122 +++++++ .../forearm/forearm_collision_C6M2.dae | 134 ++++++++ .../forearm/forearm_collision_E2M3.dae | 93 ++++++ .../forearm/forearm_collision_E3M5.dae | 83 +++++ .../forearm/forearm_collision_E3M5_scaled.dae | 120 +++++++ .../forearm/forearm_collision_E4.dae | 83 +++++ .../lf_metacarpal/lf_metacarpal_C6M2.dae | 139 ++++++++ .../lf_metacarpal/lf_metacarpal_E2M3.dae | 139 ++++++++ .../lf_metacarpal/lf_metacarpal_E3M5.dae | 139 ++++++++ .../lf_metacarpal_E3M5_no_rot_scaled.dae | 210 ++++++++++++ .../lf_metacarpal/lf_metacarpal_E4.dae | 122 +++++++ .../mounting_plate/mounting_plate_E3M5.dae | 107 ++++++ .../mounting_plate/mounting_plate_E4.dae | 107 ++++++ .../mounting_plate/mounting_plate_G1M5.dae | 107 ++++++ .../mounting_plate/mounting_plate_G4.dae | 107 ++++++ .../meshes/components/palm/palm_C6M2.dae | 132 ++++++++ .../meshes/components/palm/palm_E2M3.dae | 143 ++++++++ .../meshes/components/palm/palm_E3M5.dae | 132 ++++++++ .../components/palm/palm_E3M5_scaled.dae | 153 +++++++++ .../meshes/components/palm/palm_E4.dae | 122 +++++++ .../meshes/components/palm/palm_G1M5.dae | 143 ++++++++ .../meshes/components/palm/palm_G4.dae | 122 +++++++ .../th_distal/bt_2p/th_distal_bt_2p.dae | 235 ++++++++++++++ .../bt_2p/th_distal_bt_2p_adapter.dae | 235 ++++++++++++++ .../th_distal/bt_sp/th_distal_bt_sp.dae | 127 ++++++++ .../th_distal/mst/th_distal_mst.dae | 133 ++++++++ .../th_distal/pst/th_distal_pst.dae | 132 ++++++++ .../th_distal/pst/th_distal_pst_scaled.dae | 210 ++++++++++++ .../components/th_middle/th_middle_C6M2.dae | 139 ++++++++ .../components/th_middle/th_middle_E2M3.dae | 139 ++++++++ .../components/th_middle/th_middle_E3M5.dae | 139 ++++++++ .../th_middle_E3M5_no_rot_scaled.dae | 210 ++++++++++++ .../components/th_middle/th_middle_E4.dae | 139 ++++++++ .../components/th_middle/th_middle_G1M5.dae | 139 ++++++++ .../components/th_middle/th_middle_G4.dae | 139 ++++++++ .../th_proximal/th_proximal_C6M2.dae | 139 ++++++++ .../th_proximal/th_proximal_E2M3.dae | 139 ++++++++ .../th_proximal/th_proximal_E3M5.dae | 139 ++++++++ .../th_proximal_E3M5_no_rot_scaled.dae | 210 ++++++++++++ .../components/th_proximal/th_proximal_E4.dae | 139 ++++++++ .../th_proximal/th_proximal_G1M5.dae | 139 ++++++++ .../components/th_proximal/th_proximal_G4.dae | 139 ++++++++ .../meshes/components/wrist/wrist_C6M2.dae | 133 ++++++++ .../meshes/components/wrist/wrist_E2M3.dae | 133 ++++++++ .../meshes/components/wrist/wrist_E3M5.dae | 133 ++++++++ .../components/wrist/wrist_E3M5_no_rot.dae | 153 +++++++++ .../wrist/wrist_E3M5_no_rot_scaled.dae | 153 +++++++++ .../meshes/components/wrist/wrist_E4.dae | 133 ++++++++ URDFs/sr_description/package.xml | 53 +++ URDFs/sr_description/robots/sr_hand.urdf | 29 ++ 90 files changed, 12798 insertions(+) create mode 100644 URDFs/sr_description/LICENSE create mode 100644 URDFs/sr_description/README.md create mode 100644 URDFs/sr_description/meshes/components/cable_connector/cable_connector_base_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/cable_connector/cable_connector_palm_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/f_distal/bt_2p/f_distal_bt_2p.dae create mode 100644 URDFs/sr_description/meshes/components/f_distal/bt_2p/f_distal_bt_2p_adapter.dae create mode 100644 URDFs/sr_description/meshes/components/f_distal/bt_sp/f_distal_bt_sp.dae create mode 100644 URDFs/sr_description/meshes/components/f_distal/mst/f_distal_mst.dae create mode 100644 URDFs/sr_description/meshes/components/f_distal/mst/f_distal_mstXL.dae create mode 100644 URDFs/sr_description/meshes/components/f_distal/pst/f_distal_pst.dae create mode 100644 URDFs/sr_description/meshes/components/f_distal/pst/f_distal_pst_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5_no_rot_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E4.dae create mode 100644 URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_G1M5.dae create mode 100644 URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_G4.dae create mode 100644 URDFs/sr_description/meshes/components/f_middle/f_middle_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/f_middle/f_middle_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/f_middle/f_middle_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/f_middle/f_middle_E3M5_no_rot_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/f_middle/f_middle_E4.dae create mode 100644 URDFs/sr_description/meshes/components/f_middle/f_middle_G1M5.dae create mode 100644 URDFs/sr_description/meshes/components/f_middle/f_middle_G4.dae create mode 100644 URDFs/sr_description/meshes/components/f_proximal/f_proximal_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/f_proximal/f_proximal_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5_no_rot_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/f_proximal/f_proximal_E4.dae create mode 100644 URDFs/sr_description/meshes/components/f_proximal/f_proximal_G1M5.dae create mode 100644 URDFs/sr_description/meshes/components/f_proximal/f_proximal_G4.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_E3M5_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_E4.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_G1M5.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_G4.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_collision_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_collision_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_collision_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_collision_E3M5_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/forearm/forearm_collision_E4.dae create mode 100644 URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E3M5_no_rot_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E4.dae create mode 100644 URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_E4.dae create mode 100644 URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_G1M5.dae create mode 100644 URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_G4.dae create mode 100644 URDFs/sr_description/meshes/components/palm/palm_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/palm/palm_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/palm/palm_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/palm/palm_E3M5_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/palm/palm_E4.dae create mode 100644 URDFs/sr_description/meshes/components/palm/palm_G1M5.dae create mode 100644 URDFs/sr_description/meshes/components/palm/palm_G4.dae create mode 100644 URDFs/sr_description/meshes/components/th_distal/bt_2p/th_distal_bt_2p.dae create mode 100644 URDFs/sr_description/meshes/components/th_distal/bt_2p/th_distal_bt_2p_adapter.dae create mode 100644 URDFs/sr_description/meshes/components/th_distal/bt_sp/th_distal_bt_sp.dae create mode 100644 URDFs/sr_description/meshes/components/th_distal/mst/th_distal_mst.dae create mode 100644 URDFs/sr_description/meshes/components/th_distal/pst/th_distal_pst.dae create mode 100644 URDFs/sr_description/meshes/components/th_distal/pst/th_distal_pst_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/th_middle/th_middle_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/th_middle/th_middle_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/th_middle/th_middle_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/th_middle/th_middle_E3M5_no_rot_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/th_middle/th_middle_E4.dae create mode 100644 URDFs/sr_description/meshes/components/th_middle/th_middle_G1M5.dae create mode 100644 URDFs/sr_description/meshes/components/th_middle/th_middle_G4.dae create mode 100644 URDFs/sr_description/meshes/components/th_proximal/th_proximal_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/th_proximal/th_proximal_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/th_proximal/th_proximal_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/th_proximal/th_proximal_E3M5_no_rot_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/th_proximal/th_proximal_E4.dae create mode 100644 URDFs/sr_description/meshes/components/th_proximal/th_proximal_G1M5.dae create mode 100644 URDFs/sr_description/meshes/components/th_proximal/th_proximal_G4.dae create mode 100644 URDFs/sr_description/meshes/components/wrist/wrist_C6M2.dae create mode 100644 URDFs/sr_description/meshes/components/wrist/wrist_E2M3.dae create mode 100644 URDFs/sr_description/meshes/components/wrist/wrist_E3M5.dae create mode 100644 URDFs/sr_description/meshes/components/wrist/wrist_E3M5_no_rot.dae create mode 100644 URDFs/sr_description/meshes/components/wrist/wrist_E3M5_no_rot_scaled.dae create mode 100644 URDFs/sr_description/meshes/components/wrist/wrist_E4.dae create mode 100644 URDFs/sr_description/package.xml create mode 100644 URDFs/sr_description/robots/sr_hand.urdf diff --git a/URDFs/sr_description/LICENSE b/URDFs/sr_description/LICENSE new file mode 100644 index 0000000..0870439 --- /dev/null +++ b/URDFs/sr_description/LICENSE @@ -0,0 +1,28 @@ +BSD 3-Clause License +Copyright (c) 2022, Shadow Robot Company Ltd +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. \ No newline at end of file diff --git a/URDFs/sr_description/README.md b/URDFs/sr_description/README.md new file mode 100644 index 0000000..b25a9f1 --- /dev/null +++ b/URDFs/sr_description/README.md @@ -0,0 +1,7 @@ +From: https://github.com/shadow-robot/sr_common + +This package contains the description for Shadow Robot's Hands. + +You can find the different complete models in [robots](robots). + +You can also find more information about the computation of the [hand kinematics](doc/HandInertia.md). diff --git a/URDFs/sr_description/meshes/components/cable_connector/cable_connector_base_E3M5.dae b/URDFs/sr_description/meshes/components/cable_connector/cable_connector_base_E3M5.dae new file mode 100644 index 0000000..ea3dc8e --- /dev/null +++ b/URDFs/sr_description/meshes/components/cable_connector/cable_connector_base_E3M5.dae @@ -0,0 +1,83 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:30:09 + 2022-02-10T09:30:09 + + Z_UP + + + + + + + 28.33431 57.12572 183.2646 28.33 58.14146 183.2646 28.33867 58.14145 183.2646 28.19943 25.68105 183.2646 18.33454 57.07963 183.2646 5.728507 25.68105 183.2646 18.33011 58.12125 183.2646 27.64823 50.18185 197.1763 26.23972 57.85178 183.7646 23.33541 58.14346 183.2646 26.2141 58.00422 183.5019 23.69103 58.14324 183.2646 26.19103 58.14197 183.2646 23.44241 50.01022 198.1551 23.54812 41.85612 213.0616 29.44288 41.85494 212.1651 30.39398 37.89211 219.4549 23.65216 33.71112 227.9293 31.46643 33.70673 227.2636 23.75476 25.55724 242.791 33.75476 25.55724 242.791 20.55389 45.92826 207.0144 20.94338 50.00099 198.9619 18.42947 49.99182 199.7792 19.20372 53.5207 192.4882 17.2939 44.38079 211.7785 16.81973 41.84804 217.3583 20.19382 41.85505 215.1975 16.69419 25.55724 252.4563 19.04771 25.55724 249.2346 19.29011 29.63244 240.5296 21.36229 54.07321 191.0398 21.80962 58.1363 183.2646 20.28466 58.12899 183.2646 22.57241 58.13991 183.2646 19.56193 33.70713 231.955 15.4568 33.70318 235.9913 14.86788 29.63035 245.703 14.34067 25.55724 255.6781 22.1933 50.0056 198.5582 21.87147 41.85858 214.1237 21.60745 33.70913 229.9419 21.49712 29.63349 237.9458 19.86317 37.78134 223.511 16.10741 37.77575 226.5431 15.65625 34.99348 232.9695 5.728507 25.68105 250.4218 5.680414 25.55724 250.6781 10.01054 25.55724 253.1781 19.30717 58.12515 183.2646 16.80963 49.98599 199.9407 14.42725 41.8436 217.1544 12.1756 25.55724 254.4281 13.81122 33.70193 235.4441 12.16088 33.70069 234.9002 15.16769 49.98025 200.118 12.00526 41.83924 216.9714 8.842841 33.69824 233.8247 28.32435 58.14145 183.2646 27.26506 58.14167 183.2646 29.2624 49.99868 197.0376 26.37697 58.14192 183.2646 30.85746 49.99539 196.5677 33.37624 41.84934 209.8708 37.24905 25.55724 238.0555 34.78134 33.70417 224.201 36.08428 25.55724 239.634 33.67234 33.70503 225.2247 34.91952 25.55724 241.2125 32.56753 33.70588 226.2454 31.39838 41.85218 211.0259 35.89503 33.70329 223.1739 38.41382 25.55724 236.4771 28.31502 52.62783 188.8711 29.13781 47.3805 195.537 28.29631 48.26679 194.6078 28.27821 44.04628 200.4541 30.5891 47.37923 195.0643 32.84388 37.63274 206.864 31.14501 37.6342 208.0153 35.09867 27.88625 218.6637 31.48491 27.88832 222.7136 30.79358 31.09409 218.2082 32.38257 27.88781 221.7052 30.3039 37.63493 208.5851 33.28378 27.88729 220.6943 34.18899 27.88677 219.6806 33.75476 18.13976 236.6846 34.65443 18.13976 235.1293 35.5541 18.13976 233.574 36.45378 18.13976 232.0187 37.35345 18.13976 230.4634 29.46751 37.63566 209.1515 28.22621 31.92582 217.3161 28.19943 25.68105 226.0862 23.71434 21.93718 231.4931 23.67428 25.68105 226.3719 25.9369 25.68105 226.2298 23.75476 18.13976 236.6846 23.75476 21.8485 239.7378 23.74769 23.70287 241.2605 20.616 21.93514 237.3184 17.51099 21.93311 243.1483 21.65992 25.68105 229.6501 17.66175 25.68105 236.1428 17.39387 18.13976 250.3898 20.57431 18.13976 243.5372 22.16454 18.13976 240.1109 21.78289 21.8485 243.0618 20.19169 19.99413 244.9627 16.62171 19.99413 251.7103 19.43033 23.70287 247.8091 17.83914 21.8485 249.7099 19.81101 21.8485 246.3859 15.86727 21.8485 253.034 13.06375 18.13976 247.8898 15.2933 25.68105 235.2013 14.13591 25.68105 234.744 8.733619 18.13976 245.3898 10.59298 25.68105 233.3583 7.969012 25.68105 242.6007 28.33431 61.52029 168.1908 28.33 62.45647 168.4637 18.33454 61.47782 168.1784 18.33011 62.43784 168.4583 + + + + + + + + + + 0.00155425 0 -0.9999988 0 0 -1 0.00174731 0.8681504 0.4962984 4.79419e-4 0.8649618 0.5018376 5.085e-4 0.8652718 0.501303 4.39352e-4 0.8648565 0.502019 0.07541781 0.8753477 0.4775758 0.07555645 0.8750368 0.4781234 0.07282251 0.8755173 0.4776675 0.07152581 0.8802108 0.4691621 0.05942761 0.8756425 0.4792897 0.04033958 0.882958 0.4677157 0.04141658 0.8760837 0.4803769 0 0.8854545 0.464726 0.1437895 0.8802653 0.4521699 0.1409342 0.885177 0.4433953 0.2653176 0.8692636 0.4171181 0.5139021 0.7713441 0.3754107 -0.004253029 0.8863739 0.4629506 -0.004094958 0.8775996 0.479377 0.3966525 0.8241765 0.4042278 0.433354 0.8214257 0.3707618 0.4378006 0.8173333 0.3745623 0.4829284 0.8014527 0.3527802 0.07644826 0.8883344 0.4527887 0.08158004 0.8846544 0.4590548 0.1448316 0.8768668 0.4583977 0.1428151 0.8804107 0.4521956 0.2059714 0.8652265 0.4571204 -0.004177749 0.8863748 0.4629498 0.05949795 0.8807098 0.4699044 0.1475911 0.8716956 0.4672942 0.1455788 0.8753013 0.4611448 0.2910742 0.8401986 0.4575393 0.2819549 0.8509674 0.443121 0.4250383 0.795105 0.4326089 0.410834 0.8101422 0.4181926 0.4885647 0.7663766 0.4170991 0.2747976 0.8590526 0.4318738 0.3250895 0.8549209 0.4042615 0.3369071 0.8432303 0.4188752 0.377871 0.8396815 0.3900623 0.3773589 0.8424186 0.3846182 0.2124598 0.8773052 0.4303447 0.2339732 0.8662336 0.4414703 0.2784094 0.8548904 0.4377795 0.2746261 0.8590998 0.4318892 0.3415485 0.8331677 0.4349437 0.4021757 0.8188982 0.4094639 0.4107903 0.8101601 0.418201 0.4597314 0.7963609 0.3930093 0.4882206 0.7664665 0.4173367 0.5139037 0.7713429 0.3754107 -0.2247757 0.8932576 0.3893157 -0.003513038 0.8947228 0.446608 0.07166111 0.8920899 0.4461395 0.002427756 0.9038379 0.4278681 0.03924882 0.9037258 0.4263089 0.04051148 0.8976792 0.4387838 -0.2080285 0.9093393 0.3603142 -0.1550983 0.9126439 0.3781874 -0.2133942 0.9043524 0.3696075 -0.1294734 0.9113264 0.3907952 -0.2160071 0.9010715 0.3760467 -0.003582656 0.8988791 0.4381822 0.04451882 0.8962589 0.4412914 0.04351478 0.9007735 0.4321039 -0.03407132 0.9024158 0.4295172 -0.03286743 0.9099757 0.4133571 -0.1337532 0.9019558 0.410592 -0.1337525 0.9019569 0.41059 -0.1261059 0.9175309 0.3771399 -0.127831 0.9151417 0.3823283 -0.1269012 0.9150106 0.3829515 -0.1242589 0.9137244 0.3868687 -0.07594174 0.9098984 0.4078208 -0.03601831 0.914614 0.4027208 -0.03667664 0.9111394 0.4104632 1.72858e-4 0.8608168 0.508915 2.24318e-4 0.864838 0.5020509 -1.35042e-4 0.8649448 0.5018672 -0.01913005 0.8670495 0.4978548 2.40124e-4 0.8679703 0.4966162 0 0.8608896 0.5087918 0 0.8528575 0.5221439 0.1478619 0.8557022 0.4958937 0.1478725 0.8556635 0.4959574 0.5018202 0.7817058 0.3702871 0.3766804 0.8319578 0.4073796 0.493409 0.789932 0.3640809 0.3692255 0.8393508 0.3989522 0.4852409 0.7977105 0.358049 0.2603732 0.8569092 0.4448736 0.2551625 0.8630717 0.4358893 0.3820179 0.8266614 0.4131507 0.3142811 0.8442658 0.4340997 0.3693825 0.8392016 0.3991206 0.3696183 0.8391494 0.3990119 0.3620426 0.8462807 0.390812 0.1397346 0.8611049 0.4888484 0.1395871 0.8647981 0.4823272 0.2665584 0.8500181 0.4543304 0.2676215 0.8487048 0.4561568 0.3926571 0.8155646 0.4250584 0.3844162 0.8240618 0.4161088 0.5104502 0.7730095 0.3766919 -0.1671549 -0.7846226 -0.597015 -0.2025647 -0.793694 -0.5736004 -0.3719238 -0.7493358 -0.5478764 -0.3719294 -0.7493329 -0.5478767 -0.5038366 -0.7384611 -0.4481338 -0.4420863 -0.7521324 -0.4887295 -0.5137909 -0.7256345 -0.4576829 -0.3595862 -0.7681077 -0.5298192 -0.5198399 -0.7173919 -0.4638054 -0.5192202 -0.7176218 -0.4641436 -0.6372931 -0.6767224 -0.3686521 -0.5053084 -0.7366672 -0.4494275 -0.6461881 -0.6653663 -0.3738029 -0.5142546 -0.7250538 -0.4580821 -0.6552526 -0.6534377 -0.3790293 -0.5233817 -0.7127374 -0.4669873 -0.6644412 -0.640926 -0.3843588 -0.5326819 -0.6996707 -0.4761416 -0.3491332 -0.7831637 -0.5145491 -0.3547393 -0.7751247 -0.522821 -0.3548302 -0.7751108 -0.52278 -0.2402998 -0.7833808 -0.5732109 -0.1912127 -0.7882388 -0.5849079 -0.1934934 -0.782373 -0.5919907 -0.09469419 -0.7763429 -0.6231572 -0.1054965 -0.8073101 -0.5806213 -0.06254684 -0.8133902 -0.5783463 -0.06215584 -0.8129284 -0.5790372 -0.03702557 -0.8068665 -0.5895724 -0.04135411 -0.81708 -0.5750392 -0.03132098 -0.8220681 -0.5685272 -0.03597658 -0.8230708 -0.5667982 0 -0.8110252 -0.5850114 -0.0377928 -0.8066868 -0.5897698 0.764924 -0.4680876 0.4424764 0.6991915 -0.494888 0.5159624 0.7741295 -0.4474417 0.447794 0.7072455 -0.4769176 0.521875 0.7831098 -0.4260696 0.4529943 0.7151491 -0.4583462 0.5277127 0.7918516 -0.4039421 0.4580413 0.7229142 -0.4391442 0.5334299 0 -0.6355754 0.7720388 0 -0.6355771 0.7720375 -6.0201e-4 -0.6346096 0.7728326 0 -0.6365462 0.7712386 -0.7172886 -0.5825765 -0.3822328 -0.6186203 -0.6871615 -0.3809436 -0.6542223 -0.6406172 -0.4019986 -0.739484 -0.5461839 -0.3935056 -0.739623 -0.545942 -0.3935801 -0.7167302 -0.6128966 -0.3326492 -0.7023202 -0.6055323 -0.3742687 -0.750133 -0.5622182 -0.348154 -0.7501347 -0.562217 -0.3481524 0.7941774 -0.3838311 0.471122 0.8987336 -0.1352121 0.4171282 0.8703662 -0.1743982 0.4604867 0.9043254 0.0776773 0.4197165 0.7761829 -0.2757273 0.5670228 0.824961 -0.1490411 0.5451843 0.7941785 -0.3838409 0.4711122 0.7251411 -0.4399669 0.5297164 0.8097952 -0.2433178 0.5338805 0.8097582 -0.2434942 0.5338561 0.8408353 -0.2102109 0.498806 0.8570531 -0.3274664 0.397776 0.8197429 -0.3025648 0.4862881 0.8515387 -0.2699732 0.44944 0.8408417 -0.2102041 0.4987981 0.8703141 -0.1747305 0.4604591 0.859967 -0.01426213 0.5101504 0.8599756 -0.01427876 0.5101353 0.8546894 -0.1115902 0.5070046 0.8043765 -0.08781701 0.587594 0.2570205 -0.8577665 -0.4451711 0.183125 -0.8684657 -0.4606871 0.2303916 -0.8537513 -0.4669355 0.1884891 -0.8584145 -0.4770709 0.2673091 -0.8450908 -0.4629983 0.1951888 -0.8443084 -0.499044 -0.386019 -0.6355767 0.6686043 -0.385707 -0.6363346 0.6680632 -0.3857055 -0.6363368 0.668062 -0.3860251 -0.6355684 0.6686086 -0.3860154 -0.6355769 0.6686062 -0.3863459 -0.6354004 0.6685831 -0.3847108 -0.6348401 0.6700565 0.9815717 -0.004213809 -0.1910477 0.9830363 0.004528343 -0.1833549 0.982943 0.004819512 -0.1838477 0.9831906 0.005994379 -0.1824838 0.9831393 0.006191849 -0.1827533 0.9832531 0.006601512 -0.1821256 0.9832183 0.006746292 -0.1823083 0.9832876 0.006931602 -0.1819277 -0.9426649 -0.1948146 -0.2709801 -0.9427866 -0.1954759 -0.2700794 -0.9435643 -0.1947432 -0.2678836 0.9999908 -0.004289507 -7.78971e-7 0.9999909 -0.004289567 5.88595e-7 0.9999909 -0.004288971 -5.96316e-7 0.9999908 -0.004290044 2.49914e-7 0.9999909 -0.004288554 0 -0.9321406 0.3620966 0 -0.932141 0.3620957 1.56093e-7 -0.9321407 0.3620964 0 -0.9321409 0.3620959 2.60154e-7 0 -1 0 0 -1 0 0 -1 -1.57485e-6 0 -1 7.97141e-7 1.5625e-5 0 -1 6.88933e-6 0 -1 -1.44639e-5 0 -1 7.54831e-5 0 -1 0.9999903 0.00424534 0.001236617 0.9999903 0.004238367 0.001236617 0.004423975 -0.9600241 -0.2798824 0.004425287 -0.9600242 -0.2798824 0 0.279861 -0.9600406 -3.05176e-6 0.2799072 -0.9600272 -0.001939952 0.9600316 0.2798849 -0.00194025 0.9600318 0.2798846 -0.001908957 0.9600061 0.2799728 -0.9999902 -0.004254281 -0.001240074 -0.9999903 -0.004253029 -0.001240074 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 3 1 4 1 4 1 3 1 5 1 4 1 5 1 6 1 7 2 8 2 9 2 9 3 8 3 10 3 9 4 10 4 11 4 11 5 10 5 12 5 9 6 13 6 7 6 7 7 13 7 14 7 7 8 14 8 15 8 15 9 14 9 16 9 16 10 14 10 17 10 16 11 17 11 18 11 18 12 17 12 19 12 18 13 19 13 20 13 21 14 22 14 23 14 23 15 22 15 24 15 25 16 26 16 27 16 28 17 29 17 30 17 31 18 32 18 33 18 13 19 9 19 34 19 35 20 36 20 30 20 30 21 36 21 37 21 30 22 37 22 28 22 28 23 37 23 38 23 33 24 24 24 31 24 31 25 24 25 22 25 31 26 22 26 39 26 39 27 22 27 21 27 39 28 21 28 40 28 32 29 31 29 34 29 34 30 31 30 39 30 34 31 39 31 13 31 13 32 39 32 40 32 13 33 40 33 14 33 14 34 40 34 41 34 14 35 41 35 17 35 17 36 41 36 42 36 17 37 42 37 19 37 27 38 26 38 43 38 43 39 26 39 44 39 43 40 44 40 35 40 35 41 44 41 45 41 35 42 45 42 36 42 23 43 25 43 21 43 21 44 25 44 27 44 21 45 27 45 40 45 40 46 27 46 43 46 40 47 43 47 41 47 41 48 43 48 35 48 41 49 35 49 42 49 42 50 35 50 30 50 42 51 30 51 19 51 19 52 30 52 29 52 46 53 47 53 48 53 33 54 49 54 24 54 24 55 49 55 50 55 51 56 25 56 50 56 50 57 25 57 23 57 50 58 23 58 24 58 38 59 37 59 52 59 52 60 37 60 53 60 52 61 53 61 48 61 48 62 53 62 54 62 48 63 54 63 46 63 49 64 6 64 50 64 50 65 6 65 55 65 50 66 55 66 51 66 51 67 55 67 56 67 51 68 56 68 54 68 54 69 56 69 57 69 54 70 57 70 46 70 37 71 36 71 53 71 53 72 36 72 45 72 53 73 45 73 54 73 54 74 45 74 44 74 54 75 44 75 51 75 51 76 44 76 26 76 51 77 26 77 25 77 58 78 59 78 60 78 61 79 12 79 10 79 10 80 8 80 61 80 61 81 8 81 7 81 61 82 7 82 59 82 58 83 60 83 1 83 2 84 1 84 62 84 62 85 1 85 60 85 62 86 60 86 63 86 64 87 65 87 66 87 66 88 65 88 67 88 66 89 67 89 68 89 68 90 67 90 69 90 68 91 69 91 20 91 7 92 15 92 70 92 70 93 15 93 16 93 65 94 70 94 67 94 67 95 70 95 16 95 67 96 16 96 69 96 69 97 16 97 18 97 69 98 18 98 20 98 59 99 7 99 60 99 60 100 7 100 70 100 60 101 70 101 63 101 63 102 70 102 65 102 63 103 65 103 71 103 71 104 65 104 64 104 71 105 64 105 72 105 73 106 74 106 75 106 75 107 74 107 76 107 77 108 78 108 79 108 79 109 78 109 80 109 81 110 82 110 83 110 83 111 82 111 84 111 83 112 84 112 85 112 85 113 84 113 79 113 85 114 79 114 86 114 86 115 79 115 80 115 87 116 81 116 88 116 88 117 81 117 83 117 88 118 83 118 89 118 89 119 83 119 85 119 89 120 85 120 90 120 90 121 85 121 86 121 90 122 86 122 91 122 91 123 86 123 80 123 82 124 92 124 84 124 84 125 92 125 76 125 84 126 76 126 79 126 79 127 76 127 74 127 79 128 74 128 77 128 77 129 74 129 73 129 77 130 73 130 0 130 76 131 92 131 93 131 93 132 92 132 82 132 93 133 82 133 94 133 95 134 96 134 97 134 82 135 81 135 94 135 94 136 81 136 87 136 94 137 87 137 97 137 97 138 87 138 98 138 97 139 98 139 95 139 91 140 72 140 90 140 90 141 72 141 64 141 90 142 64 142 89 142 89 143 64 143 66 143 89 144 66 144 88 144 88 145 66 145 68 145 88 146 68 146 87 146 87 147 68 147 20 147 98 148 87 148 99 148 99 149 87 149 20 149 99 150 20 150 100 150 100 151 20 151 19 151 101 152 102 152 103 152 103 153 102 153 104 153 103 154 96 154 101 154 101 155 96 155 95 155 101 156 95 156 98 156 105 157 102 157 106 157 106 158 102 158 101 158 106 159 101 159 107 159 107 160 101 160 98 160 108 161 99 161 100 161 107 162 109 162 106 162 106 163 109 163 110 163 106 164 110 164 105 164 29 165 28 165 111 165 111 166 28 166 112 166 108 167 100 167 113 167 19 168 29 168 100 168 100 169 29 169 111 169 100 170 111 170 113 170 113 171 111 171 112 171 98 172 99 172 107 172 107 173 99 173 108 173 107 174 108 174 109 174 109 175 108 175 113 175 109 176 113 176 110 176 110 177 113 177 112 177 110 178 112 178 114 178 114 179 112 179 28 179 114 180 28 180 38 180 102 181 105 181 115 181 104 182 102 182 116 182 116 183 102 183 115 183 116 184 115 184 117 184 117 185 115 185 118 185 117 186 118 186 119 186 48 187 47 187 118 187 105 188 110 188 115 188 115 189 110 189 118 189 114 190 38 190 52 190 48 191 118 191 52 191 52 192 118 192 110 192 52 193 110 193 114 193 0 194 2 194 77 194 77 195 2 195 62 195 77 196 62 196 78 196 78 197 62 197 63 197 78 198 63 198 80 198 80 199 63 199 71 199 80 200 71 200 91 200 91 201 71 201 72 201 47 202 46 202 118 202 118 203 46 203 120 203 118 204 120 204 119 204 0 205 73 205 3 205 3 206 73 206 75 206 75 207 76 207 3 207 3 208 76 208 93 208 3 209 93 209 94 209 5 210 46 210 57 210 57 211 56 211 5 211 5 212 56 212 55 212 5 213 55 213 6 213 46 214 5 214 120 214 120 214 5 214 119 214 96 214 5 214 97 214 97 214 5 214 3 214 97 214 3 214 94 214 119 214 5 214 117 214 117 215 5 215 96 215 117 214 96 214 116 214 116 216 96 216 103 216 116 217 103 217 104 217 33 1 58 1 49 1 49 1 58 1 6 1 34 218 9 218 11 218 12 1 61 1 33 1 33 219 61 219 59 219 33 220 59 220 58 220 12 1 33 1 11 1 11 221 33 221 32 221 11 1 32 1 34 1 121 222 122 222 0 222 0 223 122 223 1 223 123 224 121 224 4 224 4 225 121 225 0 225 121 226 123 226 122 226 122 227 123 227 124 227 124 228 6 228 122 228 122 229 6 229 58 229 122 230 58 230 1 230 124 231 123 231 6 231 6 232 123 232 4 232

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/cable_connector/cable_connector_palm_E3M5.dae b/URDFs/sr_description/meshes/components/cable_connector/cable_connector_palm_E3M5.dae new file mode 100644 index 0000000..9b3fedd --- /dev/null +++ b/URDFs/sr_description/meshes/components/cable_connector/cable_connector_palm_E3M5.dae @@ -0,0 +1,83 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:31:08 + 2022-02-10T09:31:08 + + Z_UP + + + + + + + 23.68411 23.95628 4.347712 23.29755 10.86026 27.02741 33.68265 23.95628 4.518117 33.2961 10.86026 27.19781 23.71296 24.87076 2.654866 33.7115 24.87075 2.825271 23.74265 25.68771 0.9128577 33.74119 25.68772 1.083287 23.77308 26.40453 -0.8726677 33.77163 26.40454 -0.7022374 23.80416 27.01891 -2.695956 33.80271 27.01891 -2.525551 23.83577 27.52887 -4.551155 33.83433 27.52886 -4.38075 23.86784 27.93275 -6.432298 33.86639 27.93274 -6.261892 23.90024 28.22926 -8.333321 33.89879 28.22926 -8.162904 23.93288 28.41745 -10.2481 33.93142 28.41745 -10.07768 23.96564 28.49672 -12.17046 33.96419 28.49672 -12.00004 24.11651 28.61028 -21.02219 34.11505 28.61028 -20.85177 24.14343 19.13335 -22.60153 34.14197 19.13335 -22.43111 23.30607 9.994233 26.52747 33.30463 9.994228 26.69787 + + + + + + + + + + -0.008520245 0.8660258 0.4999269 -0.008520126 0.8660253 0.4999275 -0.008097231 0.8798591 0.4751659 -0.008098065 0.8798632 0.4751582 -0.007236361 0.9054061 0.424485 -0.007233679 0.9053995 0.4244992 -0.006349623 0.9280278 0.3724569 -0.006349563 0.9280265 0.3724601 -0.005440652 0.9476609 0.3192324 -0.005442202 0.9476634 0.3192251 -0.004515051 0.9642435 0.2649796 -0.004515886 0.9642459 0.264971 -0.003575623 0.9777259 0.2098557 -0.003575623 0.9777266 0.2098526 -0.002625942 0.9880571 0.1540659 -0.002624928 0.9880555 0.154076 -0.001666665 0.9952062 0.09778475 -0.001666605 0.9952065 0.09778165 -7.02046e-4 0.9991511 0.04118967 -7.02028e-4 0.9991511 0.04118973 -2.18582e-4 0.9999178 0.01282507 -2.18584e-4 0.9999178 0.01282364 0.0168097 0.1644071 -0.9862494 0.01680999 0.1644072 -0.9862494 0.003115415 -0.983139 -0.1828333 0.00311625 -0.983139 -0.1828333 -0.01475697 -0.5000076 0.8658953 -0.01475709 -0.5000058 0.8658964 -0.9998549 -6.35187e-7 -0.01704156 -0.9998549 -5.18093e-6 -0.01704138 -0.9998548 7.92017e-7 -0.0170415 -0.9998548 -3.72009e-6 -0.01704114 -0.9998548 -9.96255e-7 -0.01704126 -0.9998549 2.93822e-6 -0.0170409 -0.9998548 0 -0.01704269 -0.9998549 -6.46456e-6 -0.01703846 -0.9998548 2.9742e-6 -0.01704454 -0.9998549 2.83551e-6 -0.01704108 -0.9998548 2.65638e-6 -0.01704293 -0.9998549 -1.62074e-6 -0.01703941 0.9998549 0 0.01704049 0.9998548 4.66053e-6 0.01704561 0.9998549 1.01029e-6 0.01704126 0.9998549 -8.54753e-6 0.01704347 0.9998548 7.22277e-6 0.01704138 0.9998548 -4.65016e-6 0.01704108 0.9998549 -3.24149e-6 0.01704329 0.9998549 3.03587e-6 0.01703929 0.9998548 4.25325e-6 0.01704031 0.9998548 0 0.0170415 0.9998549 -6.46462e-6 0.01704126 0.9998548 2.867e-7 0.01704186 + + + + + + + + + + + + + + +

0 0 1 0 2 0 2 1 1 1 3 1 4 2 0 2 5 2 5 3 0 3 2 3 6 4 4 4 7 4 7 5 4 5 5 5 8 6 6 6 9 6 9 7 6 7 7 7 10 8 8 8 11 8 11 9 8 9 9 9 12 10 10 10 13 10 13 11 10 11 11 11 14 12 12 12 15 12 15 13 12 13 13 13 16 14 14 14 17 14 17 15 14 15 15 15 18 16 16 16 19 16 19 17 16 17 17 17 20 18 18 18 21 18 21 19 18 19 19 19 22 20 20 20 23 20 23 21 20 21 21 21 24 22 22 22 25 22 25 23 22 23 23 23 26 24 24 24 27 24 27 25 24 25 25 25 1 26 26 26 3 26 3 27 26 27 27 27 20 28 22 28 24 28 26 29 1 29 24 29 24 30 1 30 0 30 0 31 4 31 24 31 24 32 4 32 6 32 24 33 6 33 8 33 8 34 10 34 24 34 24 35 10 35 12 35 24 36 12 36 14 36 14 37 16 37 24 37 24 38 16 38 18 38 24 39 18 39 20 39 25 40 23 40 21 40 3 41 27 41 2 41 2 42 27 42 25 42 9 43 7 43 25 43 25 44 7 44 5 44 25 45 5 45 2 45 21 46 19 46 25 46 25 47 19 47 17 47 25 48 17 48 15 48 15 49 13 49 25 49 25 50 13 50 11 50 25 51 11 51 9 51

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_distal/bt_2p/f_distal_bt_2p.dae b/URDFs/sr_description/meshes/components/f_distal/bt_2p/f_distal_bt_2p.dae new file mode 100644 index 0000000..f66c8b1 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_distal/bt_2p/f_distal_bt_2p.dae @@ -0,0 +1,235 @@ + + + + + + Blender User + Blender 2.65.0 r52920 + + 2012-12-14T09:15:39 + 2012-12-14T09:15:39 + + Y_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0.000999987 + 1 + 0.1 + 0.1 + 1 + 1 + 1 + 2 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 2880 + 2 + 30.002 + 1.000799 + 0.04999995 + 29.99998 + 1 + 2 + 0 + 0 + 1 + 1 + 1 + 1 + 8192 + 1 + 1 + 0 + 1 + 1 + 1 + 3 + 0 + 0 + 0 + 0 + 45 + 0 + 1 + 1 + 1 + 3 + 0.15 + 75 + 1 + 1 + 0 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.248 0.68 0.336 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + -0.02630311 -0.145797 1.812762 0.03092855 -0.1589426 1.848879 -0.05050516 -0.1606379 1.853537 -0.03244769 0.1744402 1.011661 -0.03504699 0.1550523 0.9901369 -0.1102896 0.1540641 1.003041 0.1439927 -0.2949027 1.845797 0.1553341 -0.316236 1.832981 0.1172378 -0.3297742 1.870098 0.1665669 -0.4779156 1.658597 0.1954912 -0.4535934 1.68678 0.1449141 -0.5027391 1.708237 0.01737165 0.01660853 1.389251 0.03943461 0.02156704 1.375564 0.03237915 0.03111761 1.346405 0.2914574 -0.03352451 0.04756832 0.2487289 -0.08352851 0.01274698 0.2731174 -0.02436941 0.01741623 -1.95711e-4 0.1415239 1.402911 0.0120902 0.1408236 1.402657 -0.09831357 0.1257223 1.39716 0.0266655 0.08223986 1.391816 0.05361992 0.07285314 1.417605 0.04837381 0.07059931 1.423798 -0.02310633 0.105547 1.462541 -0.04182416 0.0878911 1.464527 -0.03003853 0.09385305 1.465076 -0.1386583 -0.255604 1.843512 -0.1545192 -0.2797141 1.855967 -0.1821019 -0.2452862 1.796298 -0.0111652 0.2705328 0.4896604 0.009399414 0.270702 0.2524672 -0.04291498 0.2700616 0.495241 -0.02292245 -0.2269002 1.784326 0.004561364 -0.07868379 1.83395 -0.01694363 -0.08024412 1.838237 -0.03242844 -0.2870759 0.7746403 0.00184983 -0.280487 0.7528116 0.04429644 -0.2840577 0.7864748 0.0254262 0.2694172 0.5025365 0.2008923 -0.1922207 0.8514864 0.2118269 -0.1972813 0.8333411 0.2609542 -0.129875 0.8596956 -0.1711627 -0.11699 1.921852 -0.1470984 -0.09065634 1.933253 -0.1807508 -0.06888401 1.886231 0.04234278 -0.04339772 1.865057 0.03832364 -0.04737448 1.869551 0.04621917 -0.03954946 1.860115 -0.09875059 -0.2761061 1.883057 -0.225494 -0.1973027 0.8496111 -0.2594479 -0.1813299 0.8332999 -0.1953749 -0.232625 0.8255243 -0.1969338 -0.04529953 1.053185 -0.1907292 -0.02130031 1.070489 -0.1874027 -0.0127905 1.023944 -0.005622506 -0.01219367 1.825848 -0.008421957 -0.0300334 1.864121 0.00266385 -0.0177263 1.837894 -0.05133241 0.2696741 0.6046035 -0.1267825 0.2613348 0.7512629 -0.02822643 0.27068 0.7529202 0.183605 0.1259281 1.302698 0.1745103 0.1443215 1.276648 0.1806342 0.1308308 1.309003 -0.089962 0.01819443 1.157508 -0.05888694 0.08890432 1.093813 -0.09344935 0.07303315 1.095531 0.02497982 -0.1667178 0.9580184 -0.03052014 -0.1251941 0.972746 -0.0462082 -0.1724945 0.9561694 0.0322507 -0.2328251 1.434923 0.02755844 -0.09431064 1.404784 0.0511741 -0.09294974 1.411901 -0.07177525 0.268218 0.579496 -0.01321023 0.2304368 0.6167596 0.03056514 0.2305037 0.5968503 -0.0151031 0.1944255 0.5524389 -0.1718906 0.1554031 1.252542 -0.1852452 0.1527155 1.257302 -0.1829996 0.1635519 1.270121 0.06686615 -0.05592066 1.771409 0.06882601 -0.02182239 1.794676 0.06604051 -0.07283163 1.817871 -0.0403673 0.1205573 1.443794 0.007081806 0.1129678 1.455312 -0.008453726 0.1283624 1.432422 -0.07844161 0.2676398 0.5458982 0.1803687 0.0516597 0.9617278 0.1308607 0.1069294 0.9775844 0.136761 0.1207531 0.9950689 0.03958553 -0.4833888 1.691969 -0.006894111 -0.4873276 1.671205 0.009230673 -0.4906517 1.722068 -0.03691148 -0.003476798 1.727756 -0.02846127 -0.03512382 1.714272 -0.04374051 -0.03645998 1.717941 0.04293459 0.2304477 0.5264178 0.0130521 0.230404 0.4954838 -0.1576937 0.04696714 1.215109 -0.01169759 0.03222167 1.256547 0.1204284 0.04148459 1.230002 -0.1224067 0.2622367 0.2524387 0.04742425 -0.00713706 1.748561 0.054452 -0.04708141 1.747123 0.04784429 -0.04429745 1.739475 0.1050807 -0.002204239 1.018064 0.06055968 -0.06858175 0.9933513 0.08233839 -0.1343714 0.969689 -0.06688684 0.2685987 0.5170424 -0.06330513 -0.06480109 1.795807 -0.09231376 -0.05160295 1.759546 -0.04826843 -0.05206537 1.760816 -0.05816346 -0.2250872 1.931738 -0.04161649 -0.2135827 1.91811 -0.02329021 -0.2261331 1.935355 0.1208586 -0.1114528 1.467167 0.1161074 -0.1187624 1.481307 0.1020332 -0.1129773 1.459724 -0.03521966 -0.0920999 1.87081 -0.04694139 -0.09086674 1.867422 -0.08351707 -0.2632297 0.8958711 -0.06665986 -0.3401129 1.091342 -0.1247431 -0.3116288 1.068408 -0.05470889 -0.07716041 1.868386 -0.06208688 -0.08818501 1.860056 0.1330721 -0.1411746 0.9702992 0.1121389 -0.1732608 0.9632732 0.1169559 -0.1541488 0.9624215 0.02506834 -0.04668813 1.876561 0.02212983 -0.09007847 1.865255 0.02772015 -0.02618992 1.885111 0.06437379 -0.270065 0.8198546 0.1373685 -0.2504904 0.8139687 0.130326 -0.2427765 0.8330833 0.1160516 -0.1517673 1.563144 0.1096081 -0.1577627 1.57672 0.04191964 -0.2662892 1.52691 -0.04908919 0.09815943 1.465029 0.002645075 0.05957537 1.454086 -0.05175095 0.06132292 1.449285 0.03398293 0.2688339 0.5947837 -0.01180529 0.2706436 0.6158927 -0.01371937 -0.04688084 1.746572 0.03557598 -0.03773498 1.721444 -0.03360301 -0.03280007 1.707885 -0.007892727 -0.1086679 1.688679 0.03680336 -0.1165143 1.703422 0.01709276 -0.1240788 1.684972 0.05645811 -0.135219 1.715177 0.03519451 -0.02232927 1.405333 -0.02901434 -0.2848826 1.973121 -0.05381596 -0.2504708 1.954295 -0.1151686 -0.271925 1.950581 -0.2888813 -0.1367592 0.8560286 -0.06274157 0.04506742 1.310975 -0.0844053 0.03449028 1.304093 -0.0905596 0.0293076 1.329957 -0.009831786 -0.2753305 1.551856 0.05040222 -0.1783258 1.642086 0.01098966 -0.1837949 1.653415 0.03185343 -0.00639373 1.800285 0.04433864 -0.00844264 1.799444 0.0369392 -9.60255e-4 1.777189 -0.2194406 -0.1285868 1.152557 -0.1995561 -0.1786636 1.138172 -0.1847423 -0.1286051 1.019858 -0.00560677 0.1605313 1.232066 -0.03846305 0.1617856 1.232066 -0.0819472 0.1705203 1.242125 0.03200346 0.01862233 1.361023 0.04412496 -0.001269161 1.415675 -0.005467653 0.007808983 1.390733 0.04527384 0.03997296 1.319169 0.04601961 0.03459167 1.2889 0.02489089 0.04656416 1.284047 0.03118377 -0.04299646 1.871902 0.283092 0.1398541 0.06142687 0.2956926 0.0793448 0.04678535 0.2704686 0.1418717 0.02835202 0.2538739 -0.1536321 0.8252031 0.2768259 -0.1131846 0.8350475 0.2811299 -0.09065437 0.8673251 0.04401731 -0.531045 1.809513 0.03306019 -0.5037731 1.865726 -0.01927739 -0.5355996 1.815055 -0.0739085 -0.04286062 1.735527 -0.06791228 -0.001980543 1.744838 -0.06281703 -0.03977662 1.727054 -0.02934122 0.05663418 1.256587 0.02307182 0.03188806 1.256049 0.04159325 0.05025482 1.274114 -0.1735662 -0.03330403 1.824608 -0.030761 0.04562693 1.609361 -0.03425925 0.05327129 1.588358 0.256214 -0.0881586 1.159215 0.2569631 -0.2998731 1.744082 0.2457853 -0.3636199 1.712514 -0.04694145 0.06304228 1.44456 -0.05470889 0.0767458 1.445523 -0.06208568 0.06572371 1.437195 0.05062538 0.05283302 1.233425 0.05682224 0.1590604 1.235397 0.07376688 0.04657191 1.235662 -0.05222952 0.01271027 1.377267 -0.07179909 -0.002288997 1.418477 -0.110569 0.019113 1.359675 0.05998313 -0.03852415 1.84501 0.05361998 -0.08105587 1.840467 0.08461487 -0.3065196 1.891564 -0.05526286 0.003225862 1.740322 -0.0422604 0.005658626 1.736139 -0.04888755 0.004284441 1.737893 -0.05340373 -0.2203913 1.766443 -0.04584616 -0.07628762 1.827367 0.04806792 0.267655 0.5450609 0.04853606 -0.01440888 1.013069 -0.2850582 -0.1119282 1.157661 -0.2836633 -0.3340377 1.722264 -0.2862661 -0.06597131 1.177376 0.04329234 -0.1303758 1.792945 0.05630147 -0.1279585 1.775037 0.04633224 -0.1138303 1.740349 -0.07775622 -0.08350002 1.847182 -0.08263444 -0.03711605 1.853349 -0.08976292 -0.07788211 1.831747 -0.01098501 -0.01203888 1.825903 -0.08333426 -0.01988202 1.823044 -0.01451534 -0.0120061 1.825919 -0.08342534 0.01068496 1.380224 -0.1022245 2.33674e-4 1.346019 -0.08538979 -0.001995682 1.386853 -0.02685588 0.06117075 1.449701 -0.0209887 0.1127983 1.468865 -0.02848374 -0.003435969 1.80136 -0.02360743 -0.002861142 1.801476 -0.0365985 0.001278519 1.784471 0.08355146 0.2629684 0.7527164 -0.05624479 -0.1385548 1.792864 -0.04968982 -0.07510668 1.824122 0.04695188 0.2304649 0.5636583 -0.2529471 -0.3084556 1.845014 -0.2413276 -0.2668363 1.853145 -0.27472 -0.2795643 1.798048 0.1157329 0.052863 1.241345 0.1176522 0.05132371 1.242588 0.1195524 0.04856437 1.243364 -0.08598184 -0.04440701 1.739775 -0.06334704 -0.06341701 1.792005 0.129373 -0.171864 1.814124 0.06955444 -0.005118966 1.359185 0.05599182 -0.01467722 1.38608 0.01192319 0.1079389 1.458161 0.02506834 0.1072177 1.4537 0.04219341 0.1123737 1.4417 -0.1735782 -0.1282713 0.8871033 -0.1113049 -0.1933267 0.8658366 -0.1616044 -0.1897262 0.8810364 -0.1498392 -0.07005357 0.9081369 -0.1416282 -0.06190383 0.9202819 -0.1526585 -0.01654738 0.9289627 0.07770383 0.03164392 1.325247 0.08036291 -0.002910971 1.351659 0.07310616 0.01224261 1.378551 0.03055679 0.03896367 1.033103 0.08250725 0.04305309 1.046824 0.01403957 0.05756157 1.047141 0.01553392 -0.1982117 1.705506 -0.004549801 -0.0474022 1.748004 0.02965843 -0.05730217 1.775204 -0.05666136 0.1025621 1.454669 -0.05037641 0.1078547 1.45552 0.1624584 0.2474544 0.752236 0.1984094 0.2349895 0.2524345 -0.1281401 -0.2158167 1.916072 -0.1674637 -0.2036994 1.884229 -0.2000337 -0.1827029 1.816158 0.05531102 0.1333823 1.399949 0.04491931 0.1364424 1.401093 -0.1925506 0.2472994 0.7521265 -0.1928315 0.2475702 0.2524387 -0.01947057 -0.2728541 1.545407 -0.04567807 -0.1753332 1.642641 0.02090173 -0.1754959 1.643058 0.1370425 -0.1271457 1.924961 0.1707794 -0.1812574 1.85559 0.1659528 -0.1043271 1.889304 -0.04410868 0.03105491 1.327383 -0.05322527 0.02520132 1.351497 -0.03438395 0.004936158 1.354915 0.003619432 -0.2054893 1.725501 -0.001472413 -0.1838814 1.665092 0.08589571 -0.1684979 1.619316 -0.02639251 -0.07322388 1.362104 -0.111226 -0.1058182 1.451567 -0.05110466 -0.09200012 1.413603 -0.08806085 -0.02116596 1.822675 -0.08237087 -0.01957118 1.823159 -0.01995015 0.05762869 1.576386 -0.01540344 -0.214038 0.9408974 -0.05613297 -0.2135646 0.9438618 -0.1016736 -0.1926202 0.949199 -0.02080827 0.1589291 1.298066 -0.01710659 0.1211258 1.284978 0.02858477 0.1173055 1.295474 -0.04198557 0.03931516 1.238238 -0.09596288 0.03576016 1.245647 -0.1120867 0.03693306 1.243881 -0.1428174 -0.1654234 0.9611198 -0.128213 -0.1875118 0.96203 -0.1445505 -0.1731925 0.9659653 -0.1603659 -0.138434 0.9684094 -0.1828289 -0.1156295 0.9878912 -0.1844676 -0.09080165 0.9881859 0.03044629 -0.292298 1.904137 0.02441859 -0.330323 1.914194 -0.03649473 -0.3009781 1.911405 -0.1085903 -0.2754123 0.7947295 -0.1046963 -0.2702823 0.8155787 0.02939307 -0.2046771 1.723269 0.08333599 -0.1607442 1.602536 -0.1632128 -0.2173081 0.8536136 -0.1467044 -0.241568 0.8393051 -0.05311912 -0.2679786 0.8296875 0.01547193 -0.09212368 1.414025 0.03194028 -0.05253916 1.305274 -0.05837053 0.03579354 1.331932 -0.1267214 -0.2140343 1.902331 -0.164699 -0.1740368 1.817281 0.009651541 0.1501195 1.378264 0.0299282 0.1486558 1.377008 -0.007767081 0.1580173 1.352868 -0.05673897 -0.03850674 1.723565 0.2691687 -0.09755426 0.04680019 0.2096865 -0.1474986 0.01296728 -0.05396795 -0.2635236 1.881308 0.1060456 -0.241052 1.822265 0.02150404 -0.2337992 1.436714 0.02761906 -0.3813497 1.387466 0.04616552 -0.2457456 1.469688 -0.0867815 -0.009129941 1.764473 -0.08333599 -0.04648447 1.745483 0.119684 0.1561143 1.245633 0.08398473 0.05374157 1.236538 -0.008659243 -0.0461204 1.884165 0.01195865 -0.04898512 1.882447 0.01816493 0.1491595 1.378022 0.02583611 0.1482756 1.3777 -0.02986145 -0.01243567 1.825754 -0.03144472 -0.01835155 1.839442 -0.0256493 -0.01229411 1.825806 0.02617418 -0.2142822 1.917518 -0.006529688 -0.214663 1.919821 -0.02308636 -0.2039579 1.903066 0.06112611 -0.0312007 0.9218226 0.140479 -0.1390021 0.8835672 0.04023551 -0.07619959 0.9054443 -0.01418578 0.1420791 1.403177 -0.01036036 0.1418628 1.403037 -0.1399882 -0.2395274 0.905276 -0.1710689 -0.2930188 1.092758 -0.1871371 -0.2210416 0.9627432 -0.02847516 0.1631419 1.313426 -0.02225965 0.1573652 1.304787 -0.02936536 0.157056 1.305636 0.2478113 0.1324118 0.9273348 0.2067666 0.1629081 0.9343965 0.2168511 0.1385501 0.9534543 0.04621917 0.1143627 1.437252 0.03832364 0.1065348 1.446689 0.1634331 0.01733207 1.275784 0.1715927 -0.1809263 1.811913 0.1534687 -0.1630614 1.778974 0.1004913 -0.2152431 1.903756 0.1681531 -0.1882351 1.845953 -0.09123098 -0.01339989 1.797668 0.06816488 -0.01937335 1.795561 -0.08606719 -0.01181524 1.79831 0.1199383 -0.149593 0.9839819 0.1519588 -0.1332675 1.016159 0.1389946 -0.1162791 0.9952211 -0.03252077 0.141384 1.40286 -0.03774809 0.1411222 1.402768 -0.02941155 0.1418893 1.403666 0.1211656 -0.1062543 1.937616 0.09024709 -0.1326844 1.960376 0.00539875 -0.105381 1.725383 0.009983122 -0.1026945 1.708132 -0.03527796 -0.1018245 1.7131 0.006500899 0.01474601 1.02368 0.1549189 -0.25233 1.802441 0.1111174 -0.2724521 1.861008 0.06139826 0.02673721 1.31048 -0.04476225 -0.2261568 0.9726227 -0.05823105 -0.2387862 0.9970157 -0.03229629 -0.2412784 0.991618 0.1609442 -0.1736025 1.800639 0.1405496 0.0509305 1.199294 -0.07971656 -0.19001 0.9610014 -0.02616012 -0.2001037 0.9560254 0.06747043 -0.1344057 1.752725 0.0716474 -0.1500799 1.756064 0.05870181 -0.1256924 1.728446 -0.06245732 -0.2696839 1.536191 -0.1207497 -0.1663264 1.614877 -0.1322401 -0.1619325 1.594228 0.05647987 0.1057281 1.327282 0.06088668 0.1438288 1.352696 0.06304669 0.1015173 1.338852 -0.1743221 0.00918138 1.069727 -0.1759823 -0.001831471 1.113236 -0.1841903 -0.007989406 1.058222 -0.02297991 0.1506672 1.378567 -0.02018469 0.1514189 1.378517 -0.02848404 0.1505759 1.378525 -0.09399235 0.03197228 1.031245 -0.09595501 0.05159413 1.051376 -0.1509385 0.01860982 1.041233 0.02979457 0.08400088 1.386977 0.07399159 0.08270043 1.39055 0.03144317 0.0938819 1.359829 0.06581401 -0.01528626 1.786885 0.06304675 -0.0523917 1.761713 0.06188744 -0.01114511 1.782324 -0.01324254 -0.04859888 1.294451 -0.02098709 0.01493066 1.318438 -0.03269129 -0.05098497 1.301003 -0.04888755 0.1581942 1.315032 -0.04374057 0.1174489 1.29508 -0.05052524 0.1664752 1.315924 0.182105 0.02927279 1.270527 0.1872256 0.03318834 1.277819 0.1925922 0.02236789 1.290472 -0.1575439 -0.1669485 1.801492 -0.1016187 -0.1501177 1.75611 -0.09205049 -0.1373691 1.723246 0.0668323 0.1704283 1.042002 0.06861281 0.1489188 1.099798 0.1136785 0.1305752 1.086652 0.02668672 0.1395636 1.402234 0.0222615 0.1398549 1.402304 -0.02780139 0.07439279 1.413375 -0.03521972 0.06180906 1.447949 -0.02225959 0.003456175 1.727648 -0.01570081 -0.03476864 1.713294 -0.09957259 -0.06116455 1.785814 -0.2223176 -0.08100283 1.820735 -0.2229777 -0.1584087 1.793158 -0.2005838 -0.1038426 1.882911 0.01926749 -0.01662534 1.208033 -0.142139 -0.13104 1.520879 -0.08579391 -0.04715132 1.849496 0.04992461 -0.0100857 1.798941 0.05355888 -0.005055487 1.772278 -0.1502739 0.03386074 1.252052 -0.1079099 0.009619891 1.317231 -0.1033123 -0.00978136 1.370535 -0.1521241 0.04382324 1.245189 -0.1543819 0.04408365 1.245556 -0.03269177 -0.2048943 1.723866 -0.09693515 -0.1740743 1.634852 -0.01324218 -0.2025082 1.717312 0.03352886 -0.1265127 1.759779 0.07646989 -0.1391624 1.794533 0.01402837 -0.1433587 1.806063 -0.01619851 0.1063343 1.325617 0.01240843 0.1175734 1.294738 0.01099681 0.1036029 1.333121 -0.2662278 0.2083444 0.7529733 -0.2360854 0.163405 0.9345196 -0.2203872 0.2373147 0.7525238 -0.06269264 -0.04966008 1.873916 -0.06736457 -0.04115688 1.8673 -0.057002 -0.203064 1.718837 -0.1114389 -0.162959 1.608449 -0.2336354 0.2315473 0.2524386 -0.2340027 0.2285067 0.0462327 -0.02830457 0.007723689 1.734669 -0.02936536 0.003146946 1.728498 -0.03544014 0.007163286 1.735389 0.03237742 0.1035325 1.450267 0.0315966 0.1068263 1.450579 -0.00242567 -0.1392353 1.805325 0.02189874 -0.1333624 1.796628 0.01688873 -0.1342341 1.781138 -0.08333605 0.1074245 1.322622 -0.0739085 0.1110484 1.312665 -0.04322844 0.1035683 1.333216 0.2048224 -0.3157423 1.87211 0.2330378 -0.2923489 1.826835 0.1934654 -0.2564967 1.871639 -0.2196142 -0.06722158 1.149809 -0.2079181 -0.03831714 1.167684 -0.07363808 0.1171289 1.437174 -0.07173442 0.08611315 1.43638 -0.06726717 0.09932959 1.45041 -0.06352788 0.08905446 1.373093 -0.09568452 0.08066672 1.396137 -0.09957253 0.0927447 1.362952 -0.03709304 -0.4957693 1.882455 -0.07344943 -0.5154424 1.844182 0.04992902 -0.2743471 1.961489 0.03763502 -0.2421705 1.945804 0.01355087 0.1550327 1.307099 0.01919531 0.1166551 1.297261 -0.1934245 0.08277428 0.9750503 -0.1761595 0.0724644 0.960065 -0.2251182 0.009225964 0.946101 0.06882601 0.1320865 1.371815 0.06816482 0.1345357 1.372699 -0.08823037 0.1419562 1.375265 0.06174111 -0.2122246 0.976972 0.02747035 -0.2378034 0.9930908 0.08791977 -0.2118981 0.9988442 -0.1226208 0.02277159 1.136428 -0.1232265 -0.01084333 1.193891 -0.1159783 -0.2527511 1.851096 -0.04563015 -0.1980465 1.705052 0.004561722 0.07522529 1.411088 0.05664199 0.1171538 1.425315 0.05998307 0.1153849 1.422148 0.0649181 0.1211965 1.410602 -0.1582467 -0.226924 1.114589 -0.1717046 -0.1385535 0.9795708 -0.2151107 -0.2083329 0.05810475 -0.2329097 -0.1781684 0.02837324 -0.1818488 -0.2227229 0.0332061 -0.0633471 0.09049201 1.369143 -0.09717565 0.07610189 1.40868 -0.04968976 0.07880222 1.40126 0.1953817 -0.1909027 1.797534 0.1421321 -0.2107783 1.875697 -0.223944 0.09726071 1.319613 -0.2181841 0.1175825 1.311162 -0.09717571 0.1415958 1.345689 -0.1041976 0.09740966 1.350137 -0.06953144 0.1152761 1.301049 -0.05407524 -0.04765486 1.291854 -0.1464844 -0.007267594 1.181215 0.06897419 -0.5319631 1.645353 0.02692157 -0.2654826 0.886187 0.05672103 -0.3183593 1.048308 -0.07239294 0.1536284 1.333171 -0.06791228 0.1519284 1.321977 0.1070029 -0.3178586 1.100067 -0.2805516 0.07581651 0.9491006 -0.3095765 0.01694494 0.9200965 -0.2995335 -0.01916241 0.918906 0.05712676 -0.02050888 1.822969 -0.06009829 -0.01484131 1.82493 -0.06620341 -0.01591408 1.824494 -0.07487255 -0.01719737 1.82436 0.1966561 0.03703916 1.104331 0.2124022 0.01335918 1.077708 0.1999219 0.0585342 1.010669 0.02310049 -0.01375973 1.82564 0.01623511 -0.01345723 1.825383 -0.07763028 -0.0491029 1.863862 0.05090022 -0.1446812 1.976397 0.01320654 -0.2189098 1.958218 0.04939752 -0.2195216 1.947558 -0.09857159 -0.2473363 0.01718932 -0.1804944 -0.1739668 0.003122568 -0.05612635 -0.2310864 0.003203868 -0.04523175 -0.1415596 1.98546 -0.03842258 -0.1040499 1.978789 -0.1002228 -0.1330287 1.971053 0.2492616 -0.05173528 0.9137034 0.1170456 0.01609426 0.939943 0.1252612 -0.0491687 0.9157384 0.181717 -0.1825295 0.8660886 0.0814886 -0.1219409 0.8897739 -0.01848006 -0.01215678 1.825856 -0.1361111 -0.4830334 1.853868 -0.08413779 -0.4583344 1.911028 -0.1334436 -0.4397541 1.90273 -0.01563036 -0.1583181 0.8762947 0.01221895 -0.2591852 0.8381368 -0.0519917 0.07979851 1.398523 0.06188464 0.1315378 0.9800883 -0.1084628 0.1301906 0.9798303 -0.02691197 0.1035643 0.9720657 -0.01545202 -0.4614274 1.920115 0.2949936 -0.002494752 0.8941609 0.2997351 -0.001517236 0.8733031 0.2953623 0.04049682 0.8893678 -0.201187 -0.1846429 0.9131959 -0.2248271 -0.184686 0.9965124 -0.2381126 -0.1346499 0.9468465 -0.1603847 -0.2243701 1.112378 -0.1567756 -0.1743183 1.003472 0.03389447 0.002946853 1.402382 -0.03612214 -0.1514502 0.8874157 -0.0762664 -0.139196 0.8946881 -0.07350647 -0.1460607 0.8812052 0.07803624 -0.1707419 0.9662511 -0.2695917 -0.07980394 0.9039213 -0.2654843 0.05390083 0.9520549 0.02262681 -0.06732392 1.345894 0.05083739 0.1242991 1.421638 -0.04478597 0.149494 1.378143 -0.06229311 0.1543946 1.352928 -0.05360549 0.1486148 1.377823 -0.05443972 0.06264024 1.121688 -0.08336526 0.04852175 1.127325 -0.1078459 0.04792743 1.114678 -0.1416549 0.03454118 0.9461116 -0.1130309 -0.1980435 0.9581496 0.1695026 -0.2703232 1.096965 0.1156224 -0.2313253 0.8969851 0.1596825 -0.2263931 0.9810143 0.006236672 -0.09208011 1.870756 0.01414954 -0.09115004 1.868201 0.04159307 -0.02431309 1.410461 -0.009159803 -0.00860697 1.435836 0.05982488 -0.01321792 1.797801 -0.1305253 0.0491932 1.238794 -0.1407251 0.04009813 1.243975 -0.1440989 0.04592818 1.241956 0.00425738 -0.2279739 0.9719675 -0.2209071 -0.2197489 0.7997519 -0.1795847 -0.2475138 0.7967751 -0.06897491 0.1463445 1.376997 -0.07791751 0.1446858 1.376393 0.2152691 -0.09986484 0.003140449 0.2581328 0.01513016 0.005185604 0.1886072 -0.1613869 0.9215835 0.216084 -0.07927542 0.9386283 0.210985 -0.1248663 0.9461996 -0.04009139 -0.04296219 1.278961 -0.01167851 -0.04051339 1.272233 -0.2280668 -0.3477448 1.873659 -0.2114219 -0.289305 1.896688 -0.2312632 0.09376198 0.9664549 0.006735384 0.1601171 1.311884 0.005549848 0.1182704 1.292823 -0.04423451 -0.1164936 1.732252 -0.1293026 -0.1454415 0.9719947 -0.1575079 -0.1544502 0.9921944 -0.1287547 -0.1811589 0.9799413 0.06957763 -0.05258321 1.762239 -0.1938511 -0.2768626 1.813163 -0.1925671 -0.3278426 1.82009 -0.2155762 -0.2906267 1.77794 0.1513131 -0.3078121 1.924848 0.1498108 -0.2640843 1.91361 -0.005198836 -0.1944801 1.695253 0.1558007 0.02411055 1.264822 -0.2078279 -0.2629645 1.101582 0.02662527 0.1258767 1.430879 -0.07592594 0.1501291 1.357398 -0.08411443 0.1482272 1.345023 -0.02850639 -0.3339878 1.916833 -0.02282315 -0.386906 1.89709 -0.08007824 -0.3424428 1.904983 0.05948835 0.0212695 1.281973 0.1510716 0.1639962 1.274796 0.1411353 -0.04494589 1.855439 0.1669787 -0.04781824 1.83416 -0.08098483 0.08803099 0.9661998 -0.2168433 0.02874201 1.276926 -0.2154147 -0.06004303 1.813668 0.06604045 0.08107739 1.395009 -0.1286211 0.005206167 1.020915 -0.09009355 -0.03313177 1.006254 0.2022629 -0.2356789 1.110658 0.1301856 -0.1312695 1.518437 0.1219673 -0.1393782 1.528246 -0.09570485 -0.5427121 1.711832 -0.1238551 -0.5229044 1.784003 -0.1676057 -0.5079006 1.722417 -0.1183784 -0.1155321 0.8918427 0.04525345 -0.01772797 1.823828 0.05174982 -0.01940262 1.823219 0.1671297 0.04197692 1.258093 0.1483078 0.05092585 1.251355 0.1710619 0.0873714 1.276505 0.1109616 -0.3880362 1.846534 0.1345775 -0.4033233 1.798932 0.08250099 -0.4475098 1.801501 0.1023997 -0.1614469 1.595719 0.2038219 0.03960174 0.9801484 0.1628737 0.1059123 1.003991 0.1964179 -0.2151251 0.801668 0.2237305 -0.1908419 0.8114933 0.06662136 -0.2030412 0.9498164 0.02979129 -0.2100701 0.9430853 0.006400287 -0.05673849 1.890608 0.02776432 -0.08122193 1.955183 0.09618049 -0.06568455 1.913874 0.1502141 0.03970974 1.252117 0.1564055 0.04659849 1.253355 -0.007801651 0.02069658 1.319716 0.186182 -0.06813627 1.828416 -0.011527 0.1507781 1.378607 -0.007423043 0.1506713 1.378569 -0.04570883 -0.1336359 1.769393 -0.05714029 -0.1280592 1.780737 -0.03668785 -0.1373865 1.801211 -0.0325796 -0.003659248 1.80128 -0.04478597 -0.004415035 1.801005 -0.1975272 0.1513218 1.27057 0.02029901 -0.09921437 1.684777 0.04412502 -0.1266981 1.691761 0.07240438 -0.1168696 1.733284 -0.007173359 0.0021981 1.362765 -0.01042836 0.01308757 1.382394 0.002674341 0.004493117 1.35686 0.04128116 0.09304136 0.968149 0.08743691 0.06124216 0.9564419 0.2245867 0.06962275 0.9581241 -0.03027004 -0.04674249 1.883798 -0.02685588 -0.09273821 1.872563 -0.1802964 0.08833551 1.259035 -0.1861313 0.05375695 1.256028 -0.198449 0.08034706 1.272209 0.1736164 0.1329241 1.271385 0.167137 0.1387134 1.26375 0.1093149 0.03571188 1.247627 0.1145384 0.03405034 1.251229 0.05876553 -0.01025456 1.767869 -0.2173429 -0.164055 1.77661 -0.223286 0.0233519 1.291076 -0.2182237 0.01227921 1.294826 -0.1296301 0.07024806 1.054845 -0.1119546 0.08012723 1.067718 -0.09287559 0.09233283 1.060642 0.02623218 0.02869254 1.265895 -0.1697323 -0.1208819 0.9951854 -0.1064078 -0.2623293 1.107411 -0.09348219 -0.2241201 0.9931069 -0.007183909 -0.2428613 0.8627527 -0.05583447 -0.2576594 0.8775576 -0.08661699 -0.2273001 0.8654428 -0.2006763 0.1347481 1.26722 -0.1949085 0.1022251 1.271556 -0.09834921 -0.02180474 1.794627 -0.09631592 -0.01658463 1.796002 0.02764338 0.1709303 1.24091 -0.008158445 0.1751787 1.251616 0.114161 -0.2627628 0.7844254 0.1841555 -0.3311839 1.761829 0.1521409 -0.3521967 1.821199 0.007826924 -0.06032407 1.326662 0.009393215 0.01087784 1.345232 -0.08132749 -0.09286046 1.412041 -0.0585432 -0.09214621 1.404184 -0.07201457 -0.2361975 1.444125 -0.1356329 -0.4488478 1.759034 -0.109019 -0.4699302 1.715107 -0.1458746 -0.4438626 1.682587 -0.05599808 0.04692459 1.038012 -0.1501203 -0.0220589 1.009396 -0.153272 -0.07236921 0.9909031 -0.1853368 -0.03922683 1.004752 -0.1315192 -0.1258193 0.9715831 -0.1002305 -0.156907 0.9601119 -0.009414255 -0.2779946 0.8193202 -0.01202827 -0.286493 0.8008624 -0.1777459 0.01007467 1.02964 -0.02253407 -0.1196842 1.738383 -0.03956675 -0.1242002 1.74824 -0.03384464 -0.1387806 1.749089 0.02212983 0.06383055 1.442393 0.02772015 0.1277191 1.462249 -0.2041492 -0.05532515 1.836302 -0.2147858 0.1245983 1.309896 0.09102803 0.08224916 1.164825 0.05564647 0.0757057 1.18258 0.09777158 0.06227809 1.191017 0.002255022 0.150296 1.378435 0.1101641 -0.1173673 0.9751123 0.07107627 -0.1572093 0.960328 0.02846032 0.1768719 1.057882 0.2568153 0.03499788 0.9400004 0.005281925 -0.5533341 1.703306 -0.04523462 -0.550064 1.754545 -0.03146207 -0.552972 1.68529 -0.007966339 0.158109 1.305309 -0.008552491 0.1190424 1.290702 -0.01431024 -0.2177175 0.7621234 0.1929879 -0.1585211 1.790433 0.1930681 0.1014201 1.318103 0.1942548 -0.08317291 1.80138 0.02712917 -0.1138955 0.9768584 0.1540853 -0.06779128 0.9938072 -0.1041976 -0.03362089 1.827093 -0.09978377 -0.01499557 1.77592 0.203167 -0.01003235 0.9445423 0.2214775 6.48934e-5 0.9814857 -0.02616989 0.001505374 1.361071 -0.04207921 0.01745414 1.370272 -0.01837676 0.004373729 1.365758 -0.06817001 0.1057438 1.446615 -0.1026021 -0.1077821 1.964715 -0.1266921 0.07256424 1.174116 -0.163424 0.08244562 1.138467 -0.1724821 0.05774384 1.179099 -0.01039272 -0.1875743 0.9495581 -0.06188035 0.02644145 1.339541 -0.09191721 0.04337412 1.293018 -0.04709255 0.03634202 1.312339 -0.001730859 0.1094197 1.460935 -0.006160378 0.07295954 1.454086 -8.40658e-4 0.09978759 1.46298 -0.08275181 -0.01693999 1.390217 -0.1467176 0.07133764 1.243139 -0.129082 -0.2017063 0.9981239 -0.09542977 -0.2101687 0.977461 -0.05929309 0.001589477 1.730353 -0.00148046 0.04480308 1.611624 -0.1718379 -0.009184062 1.033069 0.1212568 0.01809799 1.115679 0.1039385 0.01186597 1.14455 0.09890329 0.04368579 1.100689 -0.147579 -0.1246768 1.491433 -0.1508698 -0.1142234 1.475113 -0.1409442 -0.1174862 1.47359 0.2106406 -0.2313468 1.829053 -0.001730799 -0.04453736 1.88381 -0.1026104 -0.1429827 1.80503 -0.06188029 -0.1274675 1.762402 0.02260869 0.04604828 1.310263 0.06575936 0.1376358 1.373754 0.06053936 0.1401391 1.374738 -2.34583e-5 -0.1351388 1.745944 0.007613122 -0.1179028 1.742545 -0.008043348 -0.1331082 1.742594 0.1363864 0.05476069 1.249199 0.1443675 0.06039178 1.253222 -0.01250076 -0.2117302 0.941606 -0.02846133 0.1187852 1.29141 -0.03691148 0.1504365 1.304896 -0.05968087 -0.06401711 1.336809 -0.009202361 -0.008209884 1.709567 -0.01510298 0.004303038 1.727887 -0.02141505 0.01422405 1.742252 -0.04807883 -0.01293379 1.823722 -0.04144477 -0.0224567 1.846975 0.1272057 -0.04482448 1.001274 -0.04182416 -0.06605416 1.8874 -0.03631031 -0.05270546 1.884517 -0.0532782 -0.09999686 1.686927 -0.04942965 -0.1217809 1.678251 -7.26162e-4 -0.1199526 1.673228 0.07037013 0.05002921 1.035757 0.0812062 0.07559937 1.04611 0.1523958 0.1468616 1.255628 0.1425092 0.1534481 1.25247 0.1464834 7.73129e-4 1.019632 0.1177011 0.04071158 1.245692 0.1197569 0.0368058 1.24898 0.1123732 0.03966718 1.24508 -0.01515847 -0.09059995 1.397261 0.00433731 -0.08451175 1.391831 -0.1151206 0.04686617 1.236759 0.01276892 -0.02899795 1.859582 -0.04354518 -0.4833287 1.661057 -0.01318645 -0.2870451 1.114068 0.05090415 -0.1569338 1.81428 0.02692461 -0.1779897 1.833407 0.06268513 -0.1655433 1.798495 0.01843994 0.1025658 1.057305 0.0221827 0.07271003 1.043764 -0.01642584 0.1022143 1.055791 0.06197685 0.1307206 1.398982 -0.1257683 -0.3572449 1.952954 -0.1434571 -0.3098592 1.94831 -0.1890786 -0.3347851 1.917353 -0.07221662 -0.06256586 1.860669 0.06915831 0.0107302 1.315372 -0.1408093 0.1232252 0.9832528 0.01003563 -0.1436322 1.82675 -0.03030335 -0.154594 1.839776 0.004401564 -0.1614702 1.842061 0.05654406 -0.03708523 1.849017 -0.1452315 -0.0196042 0.9382972 -0.1510971 -0.2341649 1.802598 -0.03853082 0.07532018 1.044792 -0.06140947 0.09906834 1.055254 -0.08080792 0.05090475 1.23344 0.001234412 0.05103099 1.231178 -0.1349136 0.05837005 1.040409 -0.08144503 0.06095302 1.039406 -0.1273869 0.02913564 1.028549 -0.163466 0.02116358 1.02652 -0.02650779 0.1837394 1.047106 -0.004222154 0.1665665 1.095795 -0.07433098 -0.02329319 1.407659 -0.02104622 -0.03063106 1.427819 -0.006228744 -0.06796771 1.530401 -0.07866972 0.1355223 1.4008 -0.08646214 0.1329948 1.399807 -0.08815395 0.1223232 1.418926 -0.07062166 0.1585128 0.9790924 -0.1016715 0.05952262 1.081716 -0.1356331 0.03842902 1.100698 -0.1402975 0.03980839 1.071345 -0.2541011 -0.01457703 0.9773293 -0.23693 -0.04846316 0.9325307 0.0649181 -0.03271263 1.833464 0.05974113 -0.3792057 1.886147 -0.09231376 0.1023061 1.336684 -0.0980786 -0.08590686 1.951939 -0.02484351 0.0678119 1.061799 -0.01142358 0.07450956 1.093663 -0.05919927 0.07073014 1.085417 -0.1455242 0.04861569 1.24176 -0.1556316 0.05933147 1.245802 0.03868669 0.02665525 0.9428805 0.1708919 0.02695286 0.944046 0.02586007 -0.4148052 1.478374 0.04585129 -0.4522625 1.601539 -0.002011775 -0.4533203 1.572647 0.1118126 0.05976861 1.046979 0.03932547 0.1528638 1.31473 0.1421661 0.1671192 1.274386 0.1621859 -0.0351212 1.043181 0.1515392 -0.003069162 1.064434 0.140441 0.00285989 1.044601 0.08010071 0.003758013 1.169766 -0.01663696 0.01749581 1.167028 -2.93252e-4 0.06070876 1.1274 -0.05403882 -0.4706134 1.798456 0.006507098 -0.4837641 1.771317 -0.05547797 -0.4843199 1.754586 0.1629788 0.03004479 1.25961 0.1466746 0.03000903 1.257671 0.0497803 -0.3921236 1.434852 0.1802418 -0.3619629 1.719972 0.1593481 -0.3997351 1.702721 0.1608724 -0.3831712 1.772731 0.1921851 -0.1784614 0.9771788 -0.0916056 0.02070814 1.354584 0.1144819 0.04713159 1.241657 0.03706115 0.1486245 1.314969 0.03741335 0.1129168 1.307532 0.03170233 0.1143397 1.303623 -0.05604207 -0.01452589 1.824994 -0.03614431 -0.01274257 1.825643 0.09612512 -0.08139115 1.936859 0.07187741 -0.1008701 1.961784 0.01868152 -0.04720151 1.879372 0.04893589 -0.2163 0.9537235 -0.2840561 0.1863585 0.04577869 -0.2612948 0.210781 0.04750907 -0.2314118 0.2120263 0.02060246 0.06958645 -0.4720472 1.748353 0.01488089 -0.4272278 1.863811 -0.0430597 -0.4492757 1.839016 -0.04902619 -0.4165357 1.872851 -0.1766671 -0.2079986 0.01564967 -0.2361084 -0.1379457 0.007923781 -0.01109117 -0.4232447 1.489981 -0.06281703 0.1141324 1.304192 0.1058904 -0.1970185 0.8718425 0.05839067 -0.2238649 0.8647358 -0.02743941 -0.02791339 1.420368 0.1913387 -0.0696426 0.9156742 0.1913583 -0.1168451 0.9106318 0.129213 0.06165593 1.24731 0.01888281 -0.09333729 1.87421 -0.05175083 -0.0925861 1.872146 0.1709236 0.1320282 1.268394 0.1655998 0.1177179 1.267567 -0.05134874 -0.4547577 1.590099 -0.050206 -0.4171356 1.481845 -0.07639926 -0.009006083 1.799331 0.2500175 -0.1251659 0.8758993 -0.08758544 0.07480114 1.412253 -0.08215981 0.1114346 1.433723 0.1546831 -0.205085 0.9134386 0.191698 -0.4337906 1.809058 0.1974232 -0.3949111 1.843371 0.1439192 -0.4422994 1.867846 -0.2575981 -0.200349 1.128541 -0.2324267 -0.2366933 1.113066 0.27869 0.06250661 0.01729667 0.2352958 0.134597 0.003396272 -0.005762219 0.1417187 1.402985 -0.0623126 0.1390596 1.402189 -0.0540111 0.1397458 1.402283 -0.09745901 0.1268243 1.397561 -0.05938321 -0.3816567 1.389793 -0.07832592 -0.2164678 0.9543203 -0.0508579 -0.2231532 0.95029 -0.1666089 0.1570684 1.250501 0.006934404 0.01275283 1.331775 0.01777255 0.02786809 1.335939 0.006564259 0.03778213 1.31756 -0.01714003 0.03956758 1.311778 -0.07689046 0.2305368 0.5681598 -0.05588543 0.2305184 0.6006577 -0.08209055 -0.005864143 1.76093 -0.07853013 -0.3896091 1.426666 -0.1964805 -0.04429262 1.82637 -0.08557945 -0.4478654 1.594172 -0.07726186 -0.3980154 1.448475 0.00330621 -0.003689348 1.801269 0.009914159 -0.003880321 1.801108 -0.001773893 -0.1528671 1.781881 -0.01631546 -0.1432946 1.798781 0.003424048 -0.1471018 1.780551 -0.008552491 -0.03486663 1.713564 0.1810741 -0.2859686 1.788413 0.1619824 0.05547016 1.162088 -0.1957839 0.142041 1.26273 0.1160542 0.1468197 1.034279 0.07795929 0.1551319 1.003672 0.005549848 -0.03563857 1.715685 -0.06029552 -0.2663366 1.88379 -0.09386831 -0.2075075 0.9529297 -0.117959 -0.2558955 1.109256 0.0270428 -0.2186171 1.761569 0.1568952 -0.01152002 1.025143 0.1624226 -0.04844617 1.008433 0.1266216 -0.4338548 1.745943 -0.0910719 -0.1665178 1.801764 -0.1046312 -0.1981384 1.884573 -0.05475854 -0.1783116 1.833571 -0.01415145 -0.2267047 0.9495826 -0.01948428 -0.3800187 1.370692 -0.2464458 0.00228393 1.060842 -0.2755042 -0.03889846 1.153342 -0.2302353 0.03394061 1.094626 -0.02037447 -0.2270707 1.419292 -0.04603195 -0.1131932 1.740182 0.18565 0.121571 1.306327 0.1803545 0.1156097 1.292977 0.1249728 -0.4370314 1.684045 0.01924431 -0.2231724 0.9499028 -0.1439788 -0.0596764 1.897411 -0.05441915 -0.08400499 1.958609 0.2833844 -0.00615108 0.9105331 0.2752909 0.06469339 0.9291238 0.0145235 0.01826959 1.366735 0.1240984 0.04329615 1.245929 0.13844 0.02975797 1.259309 0.1189652 0.04541105 1.243862 0.1216874 0.04238533 1.245642 0.0902782 -0.4572811 1.667829 0.06117993 -0.4696903 1.65954 0.09291785 -0.4625464 1.713744 0.05503773 -0.2490753 1.479726 -0.2026862 0.1722952 0.9478591 -0.2335258 0.1486045 0.9543794 -0.1375253 0.03362625 1.251552 -0.1438313 0.03486746 1.249998 -0.2574872 -0.06710511 1.028594 -0.2553055 -0.0306527 1.044439 -0.1738042 -0.4158846 1.682711 -0.1530125 -0.4310653 1.666512 -0.05327838 -0.1818794 1.843371 -0.1005954 -0.1664846 1.801074 0.0407902 -0.2253475 1.932617 -0.09773218 -0.1344838 1.7526 -0.1191303 -0.4414997 1.623515 -0.04132485 0.1412352 1.403586 0.15193 0.09177327 1.260086 0.1617575 0.09608823 1.268833 -0.01219373 -0.2252886 0.9470167 -0.07810848 -0.2475845 1.474138 -0.1226128 -0.2366631 0.8851994 0.08435672 -0.4435281 1.62056 0.08098948 -0.4252522 1.927095 0.07184851 -0.3603865 1.961587 0.00932908 -0.3741098 1.970535 0.08063185 -0.2512871 1.086217 0.01017677 -0.2087998 0.8578072 -0.1890314 0.140183 0.9732269 -0.2373914 0.1194984 0.9649832 1.96872e-4 -0.1142713 1.726146 -0.1318058 0.1337575 1.095445 -0.1325925 0.09523814 1.144275 -0.1921682 -0.1874399 1.128782 -0.2106186 -0.1537559 1.14317 0.1220989 -0.2323744 1.114971 -0.04564285 0.01168978 1.022568 0.03314101 -0.064291 1.794406 -0.06594425 -0.1271941 1.694754 -0.03547567 -0.122582 1.681662 0.06779521 -0.02977788 1.819619 0.1186809 -0.4282884 1.645517 0.02419114 0.1407276 1.12711 -0.02818512 0.01531833 1.321664 -0.03428465 0.01516813 1.327127 0.1499806 -0.2041736 1.124119 -0.007677197 0.05166453 1.294166 -0.03911536 -0.1463668 1.767892 -0.2209666 -0.3249648 1.719542 -0.2209661 -0.1178235 1.155019 -0.2050904 -0.3715076 1.699683 -0.04977846 -0.0510891 1.880076 0.2325847 -0.1194545 0.8876929 -0.2115486 0.03447306 1.269489 -0.2140464 0.1170191 1.300706 -0.2084249 0.1063207 1.289623 -0.2405164 0.01119929 1.212647 -0.2685158 -0.01949977 1.199405 -0.258067 -0.2212822 1.788603 -0.01883214 -0.01595824 1.834859 -0.02216851 -0.01713556 1.837496 -0.05437177 0.005353629 1.754436 -0.07829797 -0.00332868 1.756767 -0.08178025 -0.005366325 1.778573 0.1661631 -0.1830716 1.13585 0.1740571 -0.3750463 1.706981 0.1413944 -0.4194791 1.685547 -0.1011722 0.1586169 1.236988 -0.09732913 0.05217546 1.234682 0.06388908 0.1110756 1.429542 0.002886772 0.05474257 1.584316 0.04361093 0.1453588 1.376638 0.05970048 0.1405386 1.374884 0.05710351 0.1415555 1.375254 0.07760846 0.0850085 1.060466 -0.221273 -0.234615 1.857474 -0.184966 -0.1952801 1.846123 -0.2355661 -0.1940733 1.786767 -0.132528 0.1547744 1.038583 -0.1640644 0.1294754 1.00662 -0.1780745 0.1221358 1.036754 -0.01155847 -0.002749443 1.801459 -0.01582056 -0.00309503 1.80148 0.1828114 -0.1475995 1.145413 -0.01734817 -0.01215267 1.825857 0.1904833 -0.3266491 1.717607 -0.1661696 0.03084641 1.257412 -0.176388 0.02957659 1.258082 0.03391683 -0.4295656 1.938584 -0.04004091 -0.4089781 1.954673 0.1930291 -0.09734541 1.154479 -0.09804064 -0.0293312 1.819775 -0.09737652 -0.4676955 1.768288 -0.04873007 -0.3465743 1.976837 0.04383504 -0.02983844 1.849621 0.1866456 0.1817714 0.003107428 -0.2181046 0.1869883 0.003618478 0.1983482 0.2032706 0.01330244 -0.0431441 0.1565783 1.309514 0.1034496 0.1699528 1.252974 -0.04011237 0.161266 1.317453 -0.1952037 0.15547 1.280483 -0.2011976 0.1496723 1.282752 0.01408499 0.0982114 1.464886 -0.0787422 0.0129528 0.9378932 -0.09076595 -0.04122006 0.9181759 0.09051126 -0.1940883 1.872665 0.08559006 -0.2127715 1.93463 0.1538536 -0.4063363 1.724488 0.03805094 -0.1494992 1.822665 0.1864066 -0.09586882 1.844828 -0.201585 0.09489756 1.000604 -0.1799849 0.04977911 1.252099 -0.1730339 0.0682826 1.254718 -0.1774145 0.04439795 1.250861 0.1635217 -0.02445292 1.084612 0.01108574 0.1612798 1.328509 0.02463692 0.1571962 1.317801 -0.008784532 0.1038039 1.463277 0.1543623 -0.358886 1.812663 0.1126697 -0.3892903 1.841585 0.1366896 -0.4053792 1.790588 0.121311 -0.3389589 1.864934 0.05705434 -0.3783603 1.887434 -0.06255966 0.1474137 1.377386 0.07065129 -0.3397145 1.897488 0.225637 -0.03814238 1.020407 0.2258028 -0.0609622 0.9701052 -0.02859532 -0.346333 1.914596 -0.01663607 -0.3801828 1.900145 0.04044938 -0.3440521 1.907268 0.01250982 -0.2240826 1.776585 -0.08716815 -0.4701465 1.655891 -0.1182037 -0.4620088 1.677979 -0.3084549 0.14744 0.04799628 -0.3152599 0.1312726 0.7527212 -0.2903646 0.1816806 0.7519652 -0.1358847 -0.1034603 0.9809677 0.1529475 0.1605377 1.262517 -0.07472908 -0.3291897 1.909392 -0.08804935 -0.3785566 1.886946 -0.2742573 -0.1196773 0.8837212 0.2143062 0.009345889 1.203369 0.1897904 0.02333521 1.22425 0.04222315 -0.4679403 1.90483 0.1767004 0.009779214 1.288648 0.1683331 0.01848572 1.272982 0.06827074 0.1559307 0.9781389 -0.07107114 0.1782953 0.9699205 -0.09420162 0.1262935 1.404394 -0.09788751 0.1245308 1.396939 0.1301358 -0.1919186 0.003507494 -0.07874226 -0.09377962 0.98418 0.1691176 -0.1797974 1.139553 0.1315199 -0.2228423 1.111825 -0.1780475 -0.3606003 1.823138 -0.1643175 -0.4039921 1.79707 -0.1345568 -0.3902181 1.849508 0.2730919 -0.04755258 0.90415 0.08707028 0.0517565 1.071788 0.0318396 0.06696623 1.069319 -0.1950403 -0.3841902 1.750062 -0.1826916 -0.4029502 1.75179 -0.1832852 -0.4079008 1.725682 -0.1988291 -0.4806165 1.750783 -0.2080705 -0.4710338 1.675196 0.01371443 0.1777586 1.018549 -0.07179933 0.02823078 1.266098 -0.03636682 0.03340274 1.251557 0.1757296 0.136605 1.275013 0.1763676 0.1607267 0.957858 0.1623872 0.1796542 0.9400373 0.08248722 0.1907927 0.9515513 -0.2771915 -0.2366726 1.747799 -0.2864269 -0.2804795 1.745447 -0.05052524 0.01251143 1.738766 -0.05135732 -0.2334571 1.436428 -0.1582347 -0.08683013 0.9923043 0.00467199 -0.07792001 1.557745 -0.01819843 -0.08216255 1.569401 -0.0229212 -0.1368793 1.742287 0.04278874 0.01605683 1.75604 -0.2062003 0.03437978 1.264096 -0.2075091 0.03261852 1.21682 -0.1964611 -0.1713099 1.790822 -0.05303835 -0.106433 1.706522 -0.07218152 0.02455556 1.368288 -0.05568236 0.005494534 1.404691 -0.04742479 0.1403475 1.402483 0.1505841 -0.4025343 1.760348 -0.1191549 -0.2282514 1.920328 0.02391487 -0.004113852 1.799241 0.04243081 -0.2190418 1.922317 -0.2102067 -0.3423221 1.765756 -0.06484586 -0.2652574 1.523893 -0.1048982 -0.1178179 1.73589 -0.02310931 -0.2276358 1.950083 0.08831632 -0.1042073 1.439571 0.1800686 -0.3422565 1.765577 0.1313658 0.07932072 1.144941 0.1618695 0.07343316 1.11494 0.2226938 -0.4137527 1.691711 0.230036 -0.193074 1.124136 -0.1000899 0.008482515 1.321719 -0.05527436 0.1567834 1.317521 -0.08162039 0.02191507 1.284464 0.1299849 -0.2061917 1.893067 -0.04232645 0.1248128 1.468699 -0.2234215 0.05068957 0.9742414 -0.05121564 0.1053128 1.07042 -0.01630699 0.108802 1.066136 -9.12538e-4 -0.3242399 1.035539 -0.02027189 -0.2718169 0.8910602 -0.2401771 0.03636473 0.9942528 0.1397169 -0.3959088 1.909151 0.1930692 -0.3437593 1.880236 0.1494405 -0.3462101 1.922455 -0.06137531 0.001369118 1.743492 0.1219022 -0.2290548 0.8478007 0.05534005 0.04940426 1.125418 0.07997053 0.1298478 0.980891 -0.05673903 0.1154022 1.300703 -0.1161134 0.06052196 0.9572876 -0.09465348 0.06687879 0.9695921 -0.08759534 -0.2229566 1.935411 -0.106274 -0.2127486 1.940854 0.1244884 0.05579084 1.245171 -0.100026 -0.3163529 1.966312 0.009304404 -0.4806504 1.650647 0.2274648 -0.03530603 1.05106 0.2506644 -0.04488086 1.17997 -0.07509744 -0.1582657 1.820851 -0.048958 -0.1654927 1.837796 -0.007576465 0.006235063 1.412555 -0.1244992 -0.3357312 1.885472 -0.1689223 -0.3233577 1.851476 0.1610863 -0.07933908 0.997437 0.1183454 0.0328291 1.253755 0.153572 -0.109183 0.9866684 0.1354188 -0.1484161 0.9754756 -0.2066226 -0.2906292 1.800897 0.1753086 0.03773504 1.263693 0.1817929 -0.2860026 1.787119 0.1567028 -0.3157964 1.830701 -0.1837983 -0.4076542 1.697741 -0.1639386 -0.427892 1.746078 0.07646989 -0.142714 1.735765 -0.2774279 0.1329302 0.9276154 0.09329092 -0.3231117 1.889076 0.09972828 0.04677528 1.238797 0.1044255 -0.1846831 0.9865167 0.1323655 -0.1673579 1.006525 0.1733478 0.1129654 0.9722844 0.1820382 0.1328237 0.9697972 0.1713774 0.1154091 1.277213 0.2364016 -0.01603215 1.196115 0.1665711 0.1537122 1.283315 -0.2211003 0.04268372 1.113554 0.2041669 0.22194 0.03313302 0.2515401 0.1902499 0.04734283 0.2309331 0.1837525 0.01687508 -0.06248563 -0.08223623 0.9032472 -0.09518009 -0.1395066 1.782385 0.07179051 -0.2679555 0.7488037 0.05287218 -0.2796249 0.7718002 0.03443443 -0.276317 0.7525365 -0.2059152 -0.04700076 0.916886 -0.2440038 -0.4200614 1.774167 -0.267706 -0.3502035 1.793191 -0.2643783 -0.3870928 1.750707 -0.09570109 -0.3171792 1.901245 -0.1479767 -0.3300415 1.871097 -0.06770032 -0.1122136 1.742967 -0.0390399 -0.1417676 1.824868 -0.2357349 -0.4417421 1.692729 0.2147234 -0.4275464 1.74249 0.1699905 -0.477166 1.766159 -0.1282569 0.03426152 1.249741 0.1759749 0.02124458 1.271935 0.002644658 0.004213213 1.723144 0.0513035 -0.004660964 1.747526 -0.02127945 0.1615008 1.310052 -0.01570087 0.1191404 1.290433 0.03248661 -0.001101374 1.740501 0.03161549 -0.03955078 1.726434 0.02549874 0.01094371 1.740958 0.09499806 -0.5310348 1.700003 0.09411489 -0.5290824 1.754528 0.03345656 -0.5484468 1.748941 0.1159537 -0.5127466 1.651879 -0.154619 -0.365184 1.848314 -0.1465937 -0.4086759 1.819445 -0.06410139 -0.006494641 1.80018 -0.2184565 0.07785642 1.017521 -0.06126308 0.1554831 1.320125 -0.1817892 -0.005758047 1.088323 -0.1686857 0.02819842 1.039558 0.09153282 -0.4792785 1.8694 -0.0565415 -0.03187674 1.860017 0.129033 -0.2457017 0.7518776 0.07399165 0.1349973 1.363818 -0.1819817 -0.3950391 1.775676 0.1427575 -0.289839 1.845569 -0.1636896 0.1689897 1.267225 -0.1734513 0.1661819 1.274776 -0.1965296 -0.0959562 1.038121 -0.1941555 -0.06616795 1.005035 -0.0016523 0.02043426 1.734557 -0.0203371 -0.2778233 0.0454939 0.002750098 -0.260131 0.01852267 0.035838 -0.2745849 0.04630041 0.03508263 0.06462907 1.110853 0.03754138 -0.3052082 1.908492 -0.01556897 -0.3142473 1.915994 -0.08333426 0.134027 1.400182 -0.03642857 0.2304078 0.4918094 -0.1601466 -0.1996825 1.905393 -0.1339216 -0.1347956 1.951778 -0.133221 -0.3079408 1.881777 0.01013058 0.006903171 1.756156 0.02458506 0.003312826 1.740728 -6.85086e-5 0.006913006 1.733441 -0.002599954 -0.01235479 1.825784 -0.1828369 -0.2754814 1.828357 -0.05970013 -0.1758129 0.9522067 -0.02429562 -0.01225554 1.82582 -0.08574074 -0.5397844 1.76847 -0.05426073 -0.4887089 1.70635 0.0524097 0.1077342 1.321771 -0.03373527 -0.07154959 1.540242 0.1218088 0.03047156 1.084322 0.1213772 0.02785629 1.059059 -0.00215131 0.1407533 1.28054 -8.80451e-4 0.1578007 1.306156 0.0733276 0.04957145 1.115473 0.0490626 0.06654697 1.09221 -0.303393 0.07909697 0.9281302 -0.03957223 0.008952319 1.341329 -0.01949495 -0.002467811 1.801422 0.1720516 0.1484811 1.284231 0.01009154 -0.04301518 1.279106 0.01919531 -0.03725397 1.720122 0.01161819 -0.005024075 1.719587 -0.04904901 0.04827779 1.282389 -0.05811536 0.02802735 1.267421 -0.261344 -0.4008644 1.701585 -0.2740953 -0.1613689 1.140506 -0.07199698 0.2304322 0.5240317 -0.03544014 0.1610571 1.312505 -0.298942 0.1258973 0.02036571 -0.2651693 0.1419834 0.004194378 -0.3041772 0.04353153 0.0123015 -0.06242942 0.1474313 1.377393 0.01837062 -0.01164054 1.415092 0.1127279 -0.4960592 1.82563 -0.2744792 -0.02035093 0.002794563 0.07752555 -0.02710533 1.809191 0.1546002 -0.2510602 1.801692 -0.1629499 -0.215753 1.886893 0.1503902 -0.07545143 1.892596 0.1732417 -0.1944566 0.02048879 0.02029919 -0.1826619 1.845521 -0.1086576 -0.1470329 1.747631 0.09870803 -0.2802138 1.873454 0.04482555 0.06669396 1.434528 -0.2125045 -0.1292842 0.9030042 -0.2481207 -0.09572327 0.9458091 -0.2500827 -0.1214807 1.008522 0.01623052 -0.004573225 1.800947 -0.1539324 0.02496206 1.096739 -0.1453581 0.05645245 1.050616 0.005234122 0.1072657 1.460291 0.006236672 0.06182885 1.447895 -0.04058647 -0.0130226 1.825541 -0.0801239 -0.2876495 1.897485 -0.07315325 -0.1180116 1.709933 0.004121661 0.1371201 1.412789 0.1378381 0.02965712 1.040475 0.1469898 0.01230299 1.034787 -0.1446914 -0.2779758 1.861846 0.1872752 0.04145115 1.144337 0.1424305 0.02850162 1.260792 0.003984332 0.0750904 1.411459 -0.08296996 -0.1180165 1.733828 0.126815 -0.05323344 1.001226 0.142351 -0.02896457 1.02023 0.1205801 0.009228885 1.031924 -0.2541196 -0.0597521 0.9591939 0.2169376 -0.12921 1.003195 0.05758124 -0.4231973 1.852544 0.01291394 -0.4625132 1.818264 -0.09125751 -0.01065349 1.778081 -0.1065781 -0.06190246 1.787844 -0.09277504 -0.07998275 1.837519 -0.0431745 -0.2189208 1.958249 0.02597844 -0.121846 1.76267 -0.00887227 -0.2828658 1.902237 0.06672275 0.09816247 1.348069 0.00610429 0.003380179 1.730423 -0.1832025 0.0241056 1.26598 0.2570517 -0.07674008 1.190378 0.2476634 -0.2484056 1.76723 -0.08525663 -0.2532857 1.491306 -0.0725488 -0.00199896 1.751311 0.1605539 0.1089851 1.037531 0.005234122 -0.04662287 1.883146 -0.08856409 0.1440165 1.344489 -0.09469652 0.1402893 1.357885 -0.1765456 -0.04108637 1.017137 -0.1948396 -0.05594921 1.035741 -0.1796675 -0.07823157 1.008167 -0.2110626 -0.04407876 1.160051 -0.1944673 -0.03598535 1.053729 -0.08863389 -0.2953171 1.898826 0.09993916 -0.1864361 0.9634131 0.08601146 -0.1962141 0.9589996 0.01414948 0.06275904 1.445339 0.2342419 -0.3607945 1.796455 0.09337359 -0.2596628 1.856701 -0.2073422 0.01159065 1.284993 0.1038633 -0.255501 0.04655075 0.1008484 -0.2370293 0.01852291 0.1525442 -0.2304853 0.04831731 0.04500305 -0.2647911 1.878609 0.01997542 -0.3211187 1.977882 -0.1665035 0.0493561 1.248992 -0.08427417 -0.5369288 1.645998 -0.1291559 -0.5250135 1.662281 0.0727784 -0.07390105 1.820809 -0.0130589 -0.09926801 0.8970481 0.0452454 -0.2309176 0.004727363 -0.07374686 0.1367453 1.401262 -0.1508354 -0.2422783 1.817868 -0.09188103 0.1232658 1.412903 0.06423974 0.06696563 0.9697248 0.09613627 0.0360319 0.9556031 0.1097239 -0.1228789 1.477473 0.04396778 0.1511014 1.355038 0.05802035 0.1459645 1.354061 0.0431056 0.1524555 1.329477 0.05320006 -0.04676318 1.863201 -0.1049681 -0.01713591 1.209347 0.007517397 -0.01284176 1.825606 -0.1901227 0.02174663 1.267923 0.09741359 0.03652918 1.245 0.1569276 -0.24222 0.7919196 -0.03552889 0.1627327 1.10263 0.05195623 0.1454877 1.331425 0.07727324 -0.2641518 1.113612 -0.07146239 0.1000153 1.067842 0.2057995 0.2295553 0.05263507 -0.038033 -0.06032401 1.326662 -0.1164988 -0.1019723 1.43662 -0.1951486 0.06730663 1.122035 -0.03201413 -0.2185692 1.926041 -0.1719672 -0.2169286 0.9102683 -0.1481565 0.05226576 1.242675 -0.1574943 -0.2937229 1.862168 -0.0860995 0.1714101 1.027185 -0.1722866 -5.11076e-4 1.126282 -0.0930534 -0.3755208 1.886586 -0.1058146 -0.4297626 1.834889 0.2269305 -0.2111408 1.773142 -0.09969568 -0.1950766 1.878317 0.04049867 -0.2625087 1.515718 0.1135092 -0.132632 1.525108 -0.06354182 -0.05328321 1.881114 -0.02135288 -0.181198 1.842903 -0.2689287 -0.1191875 0.02048933 -0.2904202 -0.02525413 0.00851202 -0.08368539 -0.1245762 1.772499 -0.03257966 0.1502498 1.378418 -0.03656393 0.1578341 1.351347 -0.0312851 -0.1500745 1.781214 -0.03803294 -0.2142331 1.749524 0.06197685 -0.02318841 1.821844 0.1693268 0.1460583 1.267359 -0.09564161 0.1376873 1.37382 -0.200347 -0.1820307 1.856458 -0.1379142 0.01283538 0.9473383 -0.05360549 -0.005294203 1.800685 0.1160067 0.03489744 1.250571 0.03199315 -0.2835692 1.121879 -0.1966766 0.04227584 1.257652 -0.2132716 0.01904743 1.279525 -0.01362639 0.001110434 1.182332 -0.02190023 0.08269423 1.108056 0.1813827 -0.1745547 1.798986 0.185625 0.01175737 1.291687 0.003619253 -0.05158019 1.302639 1.30008e-5 -0.003498613 1.801338 -0.007181286 -0.002919673 1.801447 -0.01616907 0.1508092 1.378617 -0.08893519 -0.1316929 1.705485 -0.2804677 -0.1599429 0.8175504 0.06696963 0.1040081 1.332008 0.00676614 0.1050136 1.329245 -0.1945635 -0.09142839 1.029513 -0.2877305 -0.1198141 0.04621487 -0.3027782 -0.04192316 0.0203492 0.1339267 0.01672536 1.091454 0.1454911 -0.003243207 1.125863 0.1583219 -0.01536405 1.074386 0.01701283 0.0918771 1.094098 -0.01573687 0.1073867 1.075339 0.1878784 0.1173091 1.312618 -0.06218105 -0.2123989 1.744485 0.1155304 -0.01867455 0.9358245 0.1115875 -0.0614416 0.9203653 -0.0150001 -0.06507521 1.339718 -0.07773214 -0.2740043 0.7516902 -0.1224554 -0.2689741 0.7739923 -0.1394113 -0.25568 0.7493862 -0.006160378 -0.08091855 1.876959 0.2340289 0.09723329 0.9569082 0.01891779 0.1052083 1.071659 -0.2224274 -0.1454065 0.9184142 0.01868152 0.1067 1.456513 0.01240843 -0.03633558 1.7176 -0.08659625 0.1721704 1.051895 -0.3289195 0.04399639 0.04693323 0.03630089 0.1469065 1.377164 0.007826924 -0.2142331 1.749524 0.00792247 -0.1465318 1.770934 0.008585333 -0.1392309 1.757889 -0.1757514 -0.2620581 1.915294 0.1639791 -0.1843189 1.82063 0.1698463 -0.06742531 1.051183 -0.1623563 8.46501e-4 1.143349 -0.1479915 0.02904164 1.099805 -0.1328052 0.0118348 1.146921 -0.1351295 0.1861152 0.9525323 -0.1919882 0.03067564 1.258795 -0.1804619 0.03970116 1.252202 0.01851558 0.03612762 1.312928 0.03822261 9.59828e-4 1.752005 -0.04232645 -0.02907657 1.891568 -0.01850742 0.05763471 1.207435 0.07082635 0.1755259 0.9688866 -0.06111514 -0.009319901 1.408715 -0.03587853 -0.01313143 1.419188 0.1627871 -0.09820443 1.026613 -0.1247283 -0.4018849 1.934566 -0.1855135 -0.4104024 1.885739 -0.0363003 -0.5399525 1.629436 -0.04137909 0.01360017 1.398405 -0.02315837 0.1419186 1.403092 0.04603248 0.007324159 1.171416 0.08282703 0.02788913 1.13594 0.01779806 -0.07568329 1.825706 0.06162762 0.08709239 1.077835 -0.1739881 0.03176438 1.255919 0.24975 -0.1374559 1.143706 0.2275459 -0.091865 1.028796 0.1036475 -0.2416326 1.925631 0.02966034 -0.1500107 0.8803861 0.01230216 -0.2703569 1.538783 0.03874707 0.1012786 1.068116 0.05188453 -0.04017686 1.855204 0.1147636 0.01890635 1.120909 -0.227046 -0.1717125 0.8692527 0.02843385 -0.01480072 1.824894 -0.2705017 0.177244 0.02045977 -0.08649909 0.06791836 1.191467 -0.03473758 0.1349951 1.136259 0.04787105 0.1096021 1.316639 0.009877741 -0.2237694 1.930794 -0.02201402 -0.1521758 1.786086 -0.198839 0.01171743 1.285823 -0.1460599 0.01282477 1.133535 0.09844291 0.07045704 1.058568 -0.1560352 0.0486955 1.245378 0.04837381 -0.08330971 1.84666 0.07466822 -0.2528158 0.8909834 -0.008231937 0.04952239 1.273519 -0.03547447 0.04244095 1.266503 -0.2051443 0.1279087 1.277815 -0.2060483 0.1387744 1.276987 -0.09408253 -0.02420467 1.821479 -0.09186112 -0.0336945 1.839841 -0.2174276 -0.06403392 1.140124 0.007680475 -0.5385743 1.625554 -0.02239096 -0.01221507 1.825835 0.07240438 -0.1650068 1.797013 -0.2029073 -0.1154935 0.8984674 0.2783639 0.09121602 0.9095413 0.2575386 0.1035357 0.9379853 0.03741335 -0.04099231 1.730394 -0.01879179 0.141885 1.403045 0.04022872 -0.1100692 1.976401 0.02769923 -0.07111972 1.813168 -0.3082273 0.09195554 0.9097166 -0.3274001 0.03143984 0.886001 -0.02247887 0.007580757 1.757559 0.2498247 -0.2845448 1.779319 -0.008390188 -0.01393431 1.421393 0.08045321 -0.3151539 1.962725 0.01548165 -0.2600175 1.874691 0.07261961 -0.1022218 1.441665 -0.1468622 -0.1521943 1.57449 0.06779521 0.1241312 1.396757 -0.3219391 0.0251199 0.9040815 -0.3289796 -0.02767151 0.8707455 -0.3183735 -0.03949356 0.890641 -0.2054457 -0.3652503 1.750498 0.05064791 0.009487807 1.384359 0.05647575 0.0263018 1.352091 -0.2014269 0.01741927 1.274685 -0.07788085 0.07045507 1.424194 -0.3220136 -0.03225076 0.04765403 -0.306611 -0.0793417 0.04663234 -0.1589113 -0.4967001 1.800643 0.1148029 0.05194938 1.241745 0.1694932 0.1524074 1.276857 -0.03052031 0.04436713 0.9493271 -0.2768496 0.1135933 0.9446175 -0.1527293 -0.02600592 1.010871 -0.09834927 0.1321042 1.371766 0.2349438 -0.1546264 0.04809391 -0.2120184 -0.3545063 1.702273 0.03691619 -0.01609569 1.824423 -0.1399348 -0.1581224 1.574193 -0.007966279 0.004199981 1.72817 -0.2012289 -0.1857608 1.834788 0.05245465 0.1453565 1.36814 -0.2253876 -0.4058119 1.837385 -0.03334146 -0.07809627 1.558229 -0.1959692 0.01911485 1.272217 0.2986242 0.02435588 0.04806941 0.1111525 -0.2438251 1.826317 0.1264826 -3.22906e-4 1.15509 0.09991204 -0.0896486 0.905624 0.01293814 0.002669215 1.732376 -0.2032681 0.1399806 1.26898 0.002227485 -0.2032169 1.900724 -0.1989408 -0.4589357 1.812185 -0.01614648 0.04016554 1.301834 0.03177893 -0.1933194 0.9584115 -0.1029844 0.1175956 1.411629 0.1923354 -0.3158159 1.719312 0.1840618 -0.1442322 1.146972 0.1488397 -0.07743537 1.007501 0.1647977 -0.06638079 1.031539 -0.1120831 0.1725019 1.259566 -0.06574535 0.1532167 1.313761 0.1418697 0.00881946 1.086827 -0.05540591 -0.04520654 1.875884 -0.1506779 -0.2477329 0.04801529 0.1436592 0.08233517 1.254815 -0.2009637 0.1265043 1.270326 -0.1327092 -0.1156479 1.462281 -0.2023646 0.05093759 1.157989 0.1061819 -0.2838446 1.94552 0.1017133 5.39214e-4 1.167508 -0.03631031 0.1012036 1.461655 0.1516059 -0.007126748 1.110146 -0.01510298 0.09897303 1.464006 -0.1511624 -0.1401383 1.52755 0.1072768 0.01091915 0.9496211 0.1700159 0.01072233 1.28746 0.003510415 -0.1360113 1.987591 -0.01499998 -0.2189844 1.762579 0.1926322 -0.07785433 1.160563 0.1915978 -0.1107257 1.154611 -0.1339502 -0.4189094 1.79412 -0.1361916 -0.4371916 1.688989 -0.02100366 -0.07582819 1.893272 0.0261957 -0.2725545 1.890818 -0.3197773 -0.08017307 0.8435632 -0.01410549 -0.4556039 1.586472 -0.3083057 -0.08998876 0.8738612 -0.09863185 2.71266e-4 1.178108 0.1140164 -0.4327998 1.714257 -0.04965603 -0.4042109 1.872085 0.1367977 -4.48998e-4 1.139405 0.04615259 -0.4080746 1.855907 0.1070203 -0.4193243 1.790307 0.1459304 0.0396378 1.251856 0.05188453 0.1137325 1.432343 0.133534 -0.5045073 1.766845 -0.09602618 -0.07285201 1.817926 0.06565469 -0.147129 1.787568 0.01568949 -0.3983612 1.881299 -0.1615706 -0.4216858 1.748521 -0.0764079 0.1527713 1.10659 0.1109825 -0.1194213 0.9789684 8.77586e-4 0.01936089 1.324386 -0.1133069 -0.4043908 1.846606 -0.02148044 -0.04656833 1.889698 -0.01510298 -0.05362832 1.887052 0.1430852 0.03661632 1.252488 0.1002908 -0.4032607 1.837144 -0.04038631 -0.1851057 1.653012 -0.01366722 -0.2297501 1.426329 -0.1531968 0.03673732 1.24989 0.06554943 0.01683306 1.35112 0.03513681 -0.547146 1.672917 0.09093123 -0.1931186 1.871133 -0.0016523 0.1743756 1.311707 0.0264607 0.08630138 0.9757229 -0.3229373 0.09624582 0.0476951 -0.06834769 -0.1427534 1.815138 0.1355915 -0.4250605 1.709975 -0.1273744 0.0335977 0.956539 -0.2144727 -0.3306324 1.761951 -0.01510298 -0.05493599 1.886868 -0.2044621 0.1460822 1.282906 -8.4064e-4 -0.05412143 1.885842 0.1301144 -0.1996256 1.905237 -0.2018213 -0.03196752 1.179504 0.1718303 -0.05073779 0.915166 -0.00914061 -0.1539928 1.784992 -0.03395837 0.1985313 0.9503048 0.1587853 -0.1787574 0.8956898 0.04688304 -0.1384829 0.8926661 0.1115875 -0.01938515 1.001708 0.1154153 -0.06187701 0.9857373 0.1075976 -0.09321475 0.9748169 0.09613621 -0.116859 0.96647 0.08043861 -0.11447 0.9035865 0.07772773 -0.1381864 0.958878 0.04605996 -0.1587333 0.9483662 0.006574988 -0.1517254 0.8904042 0.005237638 -0.1715137 0.9437147 -0.02065169 -0.1743987 0.9458173 -0.05665624 -0.1666957 0.9455693 -0.05665636 0.08586865 0.9765038 -0.01529294 0.09196048 0.9790989 -0.09465342 -0.1477057 0.9524809 -0.1111345 -0.1137801 0.9017229 -0.1273744 -0.1144247 0.9655342 -0.1281365 -0.09143626 0.9094911 -0.141091 -0.08466523 0.9770326 -0.1451814 -0.03878688 0.9918407 -0.137483 -0.008427977 1.002777 -0.1281364 0.01060938 1.012582 -0.1147635 0.02876019 1.020334 -0.09444582 0.04742848 1.023403 0.2948142 -0.05813097 0.8582118 -0.06776708 0.06178468 1.028833 0.03621929 0.1379404 1.401607 -0.03544378 0.07114946 1.032037 -0.009554386 0.07200789 1.035502 0.02645027 0.06626635 1.03036 0.05738461 0.05122905 1.027672 0.08043849 0.03364306 1.018487 0.09949558 0.00804454 1.009179 0.1896449 0.2375989 0.7522765 0.2365301 0.2079619 0.7533686 0.2605591 0.1811105 0.7518485 0.2847431 0.1321034 0.7527775 0.2964735 0.08444231 0.7593392 0.2941082 -0.02741289 0.7535164 -0.1677685 -0.500797 1.658317 0.279885 -0.07556754 0.7521492 0.2544851 -0.1292648 0.7534772 0.2161487 -0.1794754 0.7515695 0.1746468 -0.2166406 0.7523409 -0.2089111 -0.2137047 0.7515174 -0.07828748 0.1485973 1.331135 -0.3136448 -0.06676673 0.7526202 -0.2944915 -0.1109437 0.7537131 -0.2586421 -0.1665557 0.7546198 -0.3262022 -0.01400935 0.7496936 -0.0850777 -0.2713248 0.0485987 -0.3304759 0.03598445 0.7586652 -0.08041268 -0.179114 1.639989 -0.3258982 0.08838558 0.7531009 0.09282577 0.01051443 1.022952 0.205065 -0.1877794 0.04591977 0.02549874 0.1648629 1.318101 -0.2639224 -0.1573753 0.0560317 -0.1990573 0.150029 1.2882 0.1242979 0.03151977 1.257217 0.1004204 0.01747566 1.022867 0.03000676 -0.175668 0.9522945 + + + + + + + + + + -4.28424e-7 -0.9396926 -0.3420205 -0.1222932 0.7447382 -0.6560558 -0.7059069 0.04919797 -0.706594 0.680213 -0.7298294 -0.06826013 -0.01779186 0.9488933 0.315095 0.7809725 -0.2778069 -0.5593793 4.76587e-5 0.3417558 -0.9397887 -3.19992e-5 -0.9397019 -0.3419948 -0.2062281 0.3225364 0.9238183 0.4956749 -0.6331814 -0.5944644 -0.01494187 0.9998881 -5.82249e-4 0.2075113 -0.3449585 0.9153922 0.06773531 -0.9795774 -0.1893145 0.02932953 0.9995644 0.003255844 0.5783271 -0.6260199 0.5231029 -0.6815118 0.3428913 0.6465038 0.6946672 -0.7191721 -0.0151326 0.3781085 -0.608956 -0.697285 -0.541141 -0.7372586 0.404495 -0.964258 0.2641617 -0.02061772 -0.008103609 0.9065701 0.4219774 -0.09452736 0.9954903 0.007974922 0.8745753 0.483545 0.0360859 -0.2930653 0.7077878 0.642767 0.002389848 -0.3314365 0.9434745 0.2932836 -0.1937639 -0.9361839 -0.08611714 0.9962086 0.01234251 -0.2160345 0.8546456 -0.4721335 -0.3520805 0.7442994 -0.5675013 0.9984461 -0.0556696 -0.002519428 -0.003272771 0.8287488 0.5596112 -0.1097773 0.9939453 0.004674792 0.4726081 0.6067153 -0.6391699 -0.1308435 0.9857306 0.1059016 -0.2476383 0.3230714 -0.9134003 -0.3714594 0.8568114 0.35762 7.64091e-4 0.9429764 0.3328587 -0.1264737 0.9919698 6.83983e-4 0.7749566 0.1583607 -0.611853 -0.01185554 -0.3418896 0.9396654 -0.09344643 0.9956149 -0.004331171 -1.65748e-6 -0.9396924 -0.3420206 0.04024106 -0.7870765 -0.6155414 0.2252624 -0.8943088 -0.3866115 1.69947e-5 -0.9396959 -0.3420113 -0.06943637 0.9975419 -0.009415328 -0.309989 -0.8935657 -0.3247265 -0.06408703 0.9978817 -0.01117765 -0.4595944 -0.3187879 0.8289434 0.5415104 -0.1731427 -0.8226714 -0.9299498 -0.03245586 0.3662515 0.2653481 -0.8562029 0.4432911 0.8118997 -0.5681006 0.1344648 0.09340876 0.3855898 -0.9179299 0.04166722 0.9991204 0.004728198 -2.38634e-7 0.9396929 0.3420194 0.3326238 0.6930907 -0.6395207 0.00341165 0.9396497 0.3421211 -0.1834586 0.3667348 0.9120574 -0.5560021 -0.6385226 0.532119 -0.4554169 0.8875624 0.06948763 0.2784382 -0.7411298 0.6108999 0.1734239 0.9494796 0.2615582 0.9237033 0.2974137 0.24149 0.03122502 0.8175867 -0.5749581 0 -0.9396926 -0.3420203 0.5120921 0.8477563 -0.1380986 0.4926928 0.3843271 0.7807345 -0.02363574 0.9997159 -0.003097712 0.9053776 0.2681925 -0.329187 0.8122979 -0.5235155 0.2571061 0.10325 -0.8868451 0.4503833 -0.6307802 0.2591224 -0.7314178 -0.2472649 -0.5411704 0.8037379 -0.003087937 0.9395223 0.3424737 0.9877465 -0.1463388 -0.05423772 -0.4595863 -0.3187776 0.8289519 0.09960734 0.01266354 -0.9949463 0 -0.9396926 -0.3420201 0.8882482 -0.1781181 0.4234254 -0.5952628 -0.09898102 -0.7974114 -0.2731378 0.9065724 -0.3217487 -0.8871031 -0.1394907 0.439989 0.0772745 0.9970098 1.69955e-4 -0.008767247 -0.3437244 0.9390297 -0.9997038 -0.0233879 -0.006730794 0.247137 0.9201439 0.3037412 -0.806541 -0.1604709 0.5689823 -0.001099586 0.3513529 -0.9362425 -0.866141 0.3302834 0.3751168 -0.9419037 -0.01746803 0.3354285 -0.1183744 0.940222 0.3193276 0.1013777 0.9948348 0.005129814 0.5770475 0.3121854 -0.7546898 -0.9574136 -0.1056362 -0.2687013 -0.8606554 0.1449097 0.4881327 0.6628978 0.2589921 -0.7024881 1.41002e-6 0.9396927 0.3420199 0.01645725 0.9394904 0.3421794 0.2671654 0.6865203 0.6762489 -0.2865126 0.0386815 -0.9572953 -0.6884248 -0.2942965 0.6629185 -0.9693472 -0.1918833 -0.1534494 -0.1391013 -0.6723539 0.7270428 0.6457249 0.2855561 -0.7081645 0.1433335 -0.3208155 0.9362334 0.0688467 0.9975078 0.01543921 0.1928443 0.9811721 -0.01059877 0.1856437 0.9825397 -0.01232838 -0.09177833 -0.9630655 -0.2531433 0.2994059 0.9536654 -0.02963775 -3.98473e-4 0.3491617 -0.9370623 -0.2087078 0.9779781 -6.26811e-5 -0.2038829 0.9789951 6.45007e-4 0.006150186 0.7068794 -0.7073075 0.8181724 -0.1869553 0.5437294 0.6363532 0.659214 0.400614 -0.01022553 -0.9418003 -0.3360176 5.17818e-4 0.9394243 0.342756 -0.1105549 0.6283215 -0.7700582 4.50583e-7 0.9396927 0.3420199 -0.07110261 0.09833991 -0.9926095 -0.2374601 -0.3384895 0.9105149 -0.009790301 -0.8718692 -0.4896408 -0.5110831 -0.3698885 -0.7758714 -0.6752857 -0.03582495 -0.7366858 -0.07332676 -0.2441287 -0.9669666 -0.3409661 -0.8960964 0.2841712 -1.3771e-4 0.9397383 0.3418947 -0.06613409 -0.5399157 0.839117 2.02691e-5 0.939685 0.3420411 -4.23741e-4 0.9395698 0.3423571 0.3947907 0.8474272 0.3549752 0.2218407 -0.8404929 -0.4943264 0.08478552 0.9664639 0.2424026 -1.07344e-5 -0.9396913 -0.3420239 0.6895102 -0.4228489 -0.5880261 -0.001160264 0.93564 0.3529542 -0.8178763 -0.2123841 0.5347628 -0.857499 0.1680994 -0.4862492 0.03092342 0.07774192 -0.9964939 0.1558753 0.7095726 0.6871751 0.09543079 0.5188743 0.8495073 -0.03568553 0.9188411 0.393011 -0.02663153 -0.8541164 -0.5193997 0.007132649 0.3390864 -0.9407283 -0.0112521 0.3956937 -0.9183136 -0.6471881 -0.698024 -0.3064474 -0.1066213 0.789417 -0.6045267 0.5653675 0.6406061 0.5195993 0.8121032 -0.1345592 0.5677871 -0.2899968 -0.8990465 -0.3280507 0.2259359 -0.9568713 -0.1826205 -0.00162518 -0.3710314 0.9286189 -0.7444043 0.2122209 0.6331071 -0.03797715 0.9059726 -0.4216293 0.6049965 -0.02234029 0.7959147 0.0368784 0.9858825 0.1633269 -0.009641289 -0.3542496 0.9351012 -0.6162512 -0.4787092 -0.6253574 0.5872957 0.7992473 -0.1276217 0.1900284 0.825076 0.5321081 0.1947877 0.9210278 0.3372915 0.1653843 0.4431856 0.8810417 0.9429013 0.1935298 -0.2710781 -0.7325544 -0.6226218 0.2751471 0.8820146 0.1866002 -0.4327016 0.8867185 -0.4550951 -0.08135545 -0.009303033 0.1010197 0.9948409 0.2781981 -0.6741421 0.6842063 -2.21149e-7 0.9396927 0.34202 0.8363454 0.2636741 -0.4806269 0.3373903 -0.2962439 0.8935365 0.9611554 0.2094424 -0.1797618 0.8470102 -0.1691974 -0.5039306 0.01685994 0.9305117 0.3658739 0.4337224 0.8487476 0.3025103 0.004954636 0.304465 -0.9525106 -6.53359e-5 -0.9396883 -0.3420317 -0.08120119 0.3381389 -0.9375865 2.56889e-5 -0.9396854 -0.34204 5.57693e-6 -0.9396896 -0.3420283 -0.9501059 -0.09746438 0.2963097 0.02476286 -0.9429286 -0.332073 0.6471915 -0.4422167 0.6209569 0.2933817 0.9313441 0.2156971 -0.01324212 -0.9399768 -0.3409811 -0.1954067 -0.5807055 -0.7903147 0.00434345 0.9382418 0.3459529 0.004567742 -0.9439278 -0.3301202 0 -0.9396926 -0.3420205 1.0634e-6 -0.9396912 -0.3420241 -0.5099925 0.811407 0.2855282 -0.8929886 -0.1647312 0.4188497 -9.26411e-4 0.9397449 0.3418751 -0.00796616 0.9998599 -0.01472914 -0.1217181 0.8071201 -0.5777038 0.5014176 0.03683978 0.8644207 -0.2282209 0.9734233 0.01903349 -4.60171e-6 -0.939694 -0.3420165 0.7993751 0.1578496 0.5797266 -0.9037814 0.4191735 -0.08644479 0.010782 -0.2835658 0.9588922 -0.93101 -0.0663219 0.3589173 1.78036e-5 -0.9396947 -0.3420146 -0.05485928 -0.8658974 0.4972044 0.06937628 0.4584033 0.8860324 1.58648e-4 0.9396935 0.3420177 0.3675422 0.2813017 -0.8864435 -0.394745 0.4787701 -0.784191 -6.84541e-4 -0.3396393 0.9405555 -0.3874043 0.8036805 0.4516808 -0.1996721 0.846691 0.4931992 -0.008314311 0.9363623 0.3509368 3.22201e-7 -0.9396902 -0.3420268 0.07499009 -0.3265364 0.9422051 0.7303248 0.4316599 0.5294294 -0.8066502 -0.5281518 -0.2652758 -0.5895195 -0.7161387 -0.373647 0 0.9396929 0.3420194 0.4270973 0.7631168 0.4850163 -0.9421298 0.3148814 0.1150698 0.8272434 -0.07541328 0.5567596 0.003307282 0.9368539 0.3497054 -0.0758931 0.9145716 0.3972392 0.002827525 -0.9386039 -0.3449853 0.1791148 -0.925157 -0.3346678 -0.8936198 0.2201629 -0.3911164 0.3411269 -0.8828359 -0.3228516 -0.01733613 0.9392977 0.3426649 1.29791e-7 0.9396926 0.3420202 -0.5047315 -0.1683037 0.8467112 7.08722e-4 0.2738469 -0.9617731 -0.1249637 0.8896953 -0.43912 -0.002355515 0.9395518 0.3423988 0.8874874 0.441446 0.1322556 0.03144669 -0.1263543 -0.9914866 -0.9461724 -0.1384074 0.2925767 0.2590116 -0.3518188 0.8995202 -0.164744 -0.360008 -0.9182885 -0.2173618 0.2090458 0.9534431 0.008213877 -0.3468121 0.9378987 0.01420623 -0.3435791 0.9390163 -0.6923952 0.3522203 -0.6297063 -0.005725502 0.404362 -0.9145811 -0.3646728 -0.6870555 0.6284652 0.002464473 -0.3532304 0.9355332 7.89935e-7 -0.9396916 -0.3420233 7.42736e-4 -0.2778577 0.960622 0.0687744 -0.7565183 0.6503462 0.9748231 0.01643174 0.2223733 -0.8511459 -0.4659511 -0.2417437 0.006355643 -0.3549435 0.9348662 1.60643e-6 -0.9396929 -0.3420194 0.8011347 0.5332859 0.2716421 0.649985 0.1210063 0.7502512 -0.1967608 -0.8894239 0.4125657 -0.31001 0.38624 -0.8687419 -0.1584115 -0.07432901 0.9845715 -0.00555706 -0.3385623 0.9409275 0.9774655 -0.08563536 0.1929454 0.5357217 0.6874951 0.4902579 -0.1051241 0.9599868 0.2595655 0.2895103 -0.8018426 -0.5227161 -0.008141815 -0.3406944 0.9401389 -0.5941445 -0.7427057 -0.3088373 0.6702319 -0.6734278 -0.3119041 0.2030405 0.7433561 0.6373354 0.3248107 -0.2875391 0.9010102 -0.3723782 0.2435446 -0.895556 0.3170977 0.9231435 0.2173826 -0.1201226 -0.3862209 -0.9145513 0.03753548 0.7936733 0.6071851 -0.5467231 -0.8274355 0.1282355 -1.19451e-5 -0.3421199 0.9396563 -1.68756e-6 -0.9396927 -0.34202 0.3205084 -0.10272 -0.9416596 0.8451652 -0.1782112 -0.5039211 -0.2443504 0.3246468 -0.9137272 -0.7739245 -0.0288549 0.63262 -0.004569888 -0.3310559 0.9436002 0.2841535 0.3907557 -0.8755379 0.9101852 -0.1189211 0.3967626 0.5301861 0.1918796 0.8258844 0 0.9396927 0.3420201 0.8583912 -0.04777818 -0.5107659 0.6587904 0.2084097 0.7228836 0.008240342 -0.3458243 0.9382632 0.01775538 0.9417985 0.3357086 0.4656972 0.2969402 -0.8336382 -0.1548442 -0.9281121 -0.3385724 -0.7851055 -0.5507678 -0.2833094 0.004697442 -0.3526881 0.9357292 -0.003031492 -0.357807 0.9337906 0.2450482 0.7624515 0.5988482 -0.4087231 0.9031137 0.1316474 0.1525141 0.3598043 -0.9204783 -0.8141445 -0.3847058 0.434937 0.3617043 0.8752366 0.3211402 0.06792473 0.5405815 0.8385452 -0.01247429 -0.3149567 0.9490241 1.21366e-5 -0.9396938 -0.3420171 0.9998853 0.0151503 -1.55167e-4 0.6892178 0.2420876 -0.6829146 -1.09687e-6 -0.9396926 -0.3420201 -0.02766466 -0.3237904 0.9457244 -0.001428365 -0.3584378 0.9335525 0.749989 -0.5950016 -0.2889456 0.3399773 -0.8446834 -0.4134313 -0.424515 -0.9017095 0.08189606 -0.005367875 -0.3405723 0.9402031 0.1037873 0.6702029 -0.7348852 0.4456494 0.3030634 -0.8423474 8.92187e-7 0.3420577 -0.9396789 -0.576297 0.6504328 -0.4947919 0.7922823 -0.5804557 0.1880425 0.7787038 0.5728564 -0.2558438 0.6348963 -0.7630613 0.1210125 0.163367 0.08521497 -0.9828782 -0.007048249 -0.3343958 0.9424064 0.001419425 0.9352028 0.3541096 0.3468212 -0.1451528 -0.9266313 -0.01334303 -0.3464446 0.9379756 0.06061059 -0.3461065 0.9362354 0.7387326 0.631999 0.234204 -0.007531285 -0.3487132 0.9371992 0.02758044 0.961227 0.2743755 0.08051568 0.9366538 0.3408766 0.4268072 0.9042276 -0.01442193 -8.21752e-6 -0.3420706 0.9396743 -0.5784807 0.6700947 -0.4651164 -0.6856432 -0.4487373 0.5731738 -0.4645311 0.7394483 -0.4872647 0.008437573 -0.3003269 0.953799 0.008856832 -0.3341286 0.9424859 0.01343953 -0.3027486 0.9529757 -0.2166913 -0.2468107 0.9445259 -0.6270397 0.1718668 -0.7597915 0.8147842 0.1891583 -0.5480383 -0.01288908 -0.914923 -0.4034228 0.8748512 0.1558801 -0.4586248 -0.8745973 -0.4558257 -0.1652344 0.4166657 0.2769865 -0.8658338 -0.5212693 0.851095 0.06257617 0.4963161 0.6366961 -0.5901597 0.86046 0.2751404 0.4288432 0.01120442 -0.3416965 0.9397436 0.5647399 0.7613841 0.3183755 -0.1220601 -0.4721425 -0.8730309 -0.7456625 -0.2162679 -0.6302505 0.1069008 0.2140818 -0.9709486 -0.007779121 0.920279 -0.3911853 0.009107112 -0.3379502 0.9411199 0.2920522 -0.942561 0.1621239 -0.8895813 0.2116201 -0.4047988 -0.8881492 0.1341729 -0.4395323 -0.3111454 -0.2267929 -0.922905 0.5929888 0.804759 -0.02696502 -0.01098048 -0.6086368 0.7933731 0.2932237 0.9314047 0.215651 -0.0457136 0.3471723 -0.9366865 -0.05779927 0.2938805 -0.954093 0.09478092 -0.9092864 0.4052342 -0.6239066 0.4266111 -0.6547851 0.4428511 0.224367 0.8680682 -0.929894 -0.03250467 0.3663885 -0.7345129 0.6374429 0.2327172 0.1408342 0.8044387 0.5770998 0.01532429 -0.2847525 0.9584786 0.02108651 0.3295683 -0.9438963 0.2863517 0.9008051 0.3264241 0.2017166 -0.3002339 0.9322929 -0.02770876 -0.9989519 0.0364353 -0.02245825 0.5069129 -0.8617048 0.9998955 -0.01434922 -0.001749694 0.9998431 -0.01558834 -0.008409202 -0.003787994 -0.3395483 0.940581 0.02825093 0.330691 -0.9433161 0.1231923 -0.6579038 0.7429577 -0.06782728 0.3280856 -0.9422098 -0.007936298 0.9398829 0.3414047 0.8549294 0.2003505 -0.4784928 0.2108613 0.6377307 -0.7408354 -0.6271123 -0.2675372 0.7315422 -0.2211145 0.2178036 0.9506155 -0.2253736 0.853994 0.4689361 0.02574211 0.2721081 -0.9619222 0.01652967 0.3036364 -0.9526447 -4.54292e-7 -0.9396928 -0.3420196 -0.03853183 0.3257748 -0.944662 0.004431307 -0.7097792 0.7044103 -0.8817286 0.01857024 0.4713914 0.03585183 0.9367398 0.3481859 -0.2316837 0.02140402 -0.9725556 0.5318809 0.5564185 0.6383582 6.06519e-7 0.9396926 0.3420203 -0.01241594 0.29267 -0.9561329 -0.01358401 0.3133317 -0.9495466 -0.06568032 0.9530329 0.2956593 0.680726 -0.6354281 0.3644766 -0.514269 -0.7211694 -0.4641573 -0.02906984 0.3058888 -0.9516234 -0.3402274 -0.8214958 -0.4575915 0.8198772 0.2829226 0.497751 -0.07077288 0.08683127 -0.993706 -1.58817e-6 -0.9396925 -0.3420205 0.2438943 0.9689642 0.04029858 -0.01240706 -0.3882907 0.9214534 -0.2984373 0.3102431 0.9025986 0.2598344 0.2898399 -0.9211291 -0.01794731 0.3140558 -0.9492349 -0.2052513 0.3367508 -0.918951 -1.8029e-6 -0.9396929 -0.3420195 0.02102977 0.310968 -0.9501878 -0.0544455 -0.8326299 0.5511472 -0.1039531 0.909641 0.4021777 0.02381122 0.3342036 -0.9422001 0.9601192 -0.02936714 -0.2780445 0.1513302 -0.267974 -0.9514669 0.1090927 -0.3510897 0.9299649 0.03766924 0.3612722 -0.9316992 0.2830501 -0.03471636 -0.9584766 0.03507548 0.3604393 -0.932123 0.2027164 -0.5660653 -0.799047 0.05085885 -0.7504964 -0.6589148 -0.1728535 -0.3339512 -0.9266058 0.7802725 0.2762139 0.5611423 0.1396225 0.7513153 0.6450044 0.04537659 0.3565129 -0.9331878 0.1132555 0.9331628 0.3411456 0.7196027 -0.2218 0.6580097 0.03527444 0.4164619 -0.9084686 0.3882895 0.8187354 0.4229699 -0.5164366 -0.1095601 0.8492879 -0.4103935 -0.1836403 0.8932264 -0.6840147 -0.2700469 -0.6776419 0.001789808 0.9404677 0.3398784 -0.139444 0.6288279 -0.7649384 0.01585644 0.4146508 -0.9098425 0.07534492 0.6356753 0.7682709 0.01890498 0.3683342 -0.9295012 -0.6991019 -0.1833437 -0.6911163 -0.7924345 -0.2949034 0.5339284 5.4213e-7 0.9396927 0.3420196 0.3801444 -0.7667129 -0.5173408 5.87292e-4 0.3781182 -0.9257572 -0.01628726 0.3899214 -0.9207041 -0.02289819 -0.5114443 -0.8590112 -0.2891654 -0.8246865 0.4860818 -0.03518849 0.3678846 -0.9292054 -0.02731645 0.3608909 -0.9322078 0.05819708 0.9495187 0.3082651 -3.17558e-7 -0.9396924 -0.3420205 -0.3273931 0.837099 0.4382683 0.4310616 0.6925512 -0.5784106 -0.001738071 0.02836781 0.999596 0.4761618 -0.8715899 -0.1166228 -0.03648656 0.3999535 -0.9158088 -0.01530843 0.3907222 -0.9203814 -0.8013432 0.2874764 -0.5246013 0.7646671 0.3819036 0.5190702 -0.20973 0.3260224 0.9218041 -0.157099 0.4036287 -0.9013344 -0.02935141 0.36925 -0.9288665 -1.63892e-6 -0.9396903 -0.3420264 -0.3470391 0.5254613 0.7768232 0.04532015 -0.9812808 0.1871743 -0.04971277 0.3545697 -0.9337071 -0.3345627 0.03956717 -0.9415425 0.007500469 0.3445777 -0.9387279 0.2109534 -0.9251471 -0.315597 0.302276 0.5413354 -0.7845925 6.2825e-5 0.9428204 0.3333013 0.4015089 0.480724 0.7795479 -0.8186842 -0.4804713 0.3144893 -0.07241034 -0.6590873 -0.7485724 0.07233673 0.9513185 -0.2996007 0.08432358 -0.7132058 -0.6958642 0.2762286 -0.9061123 -0.320403 -0.8494554 0.5173294 -0.1039025 0.8886543 -0.4191923 -0.1859334 -0.9003205 0.4213826 0.1089023 0.1888417 -0.4529598 -0.8713014 0.5851575 0.1708672 -0.7927139 -2.88152e-6 0.342059 -0.9396786 0.4312173 0.4579576 0.7773844 0.3158407 0.4969252 0.8082759 1.44221e-6 -0.939692 -0.3420218 0.2680994 -0.9047116 -0.3310886 -0.5637159 0.5678676 -0.5997923 -0.2322126 0.9614467 -0.1473011 0.02247911 0.7204381 -0.6931549 -0.3085399 -0.3589522 -0.8808838 0.1027057 -0.9310915 -0.3500288 -0.6307749 0.2591233 -0.731422 0.3853387 -0.4718632 -0.7930065 -3.69547e-4 0.9394817 0.342599 0.434614 0.09584224 -0.8955026 0.3427801 0.01790416 -0.9392451 0.03097748 0.41746 -0.9081672 0.6148662 -0.1844042 -0.766769 -0.08855324 -0.9405809 -0.3278201 -0.07741558 -0.9396198 -0.3333486 2.14119e-5 -0.3415244 0.9398729 0.560512 -0.6132602 0.5565413 -0.9395181 -0.0586223 0.3374451 0.795659 -0.5583358 -0.2349213 -0.2905032 0.8936685 -0.342001 0.6933481 -0.5315248 0.4865694 -0.841847 -0.4703192 -0.2647515 0.3965305 0.06208097 -0.9159201 -0.2155452 0.5886998 -0.7790846 -0.3762406 0.3976369 -0.836856 1.10567e-4 0.3416143 -0.9398403 -0.02377158 0.4127076 -0.9105533 -0.2687467 -0.9044119 -0.3313825 -0.4413339 0.6746814 -0.5916329 -0.8202461 0.5266481 0.2232449 -0.2059731 0.291038 0.9342762 0.8388361 0.04923206 -0.5421533 -0.6938683 0.2744457 -0.6657523 -0.2634026 -0.9057164 -0.3321099 -1.65717e-5 -0.9396855 -0.3420396 0.6219093 0.513373 0.5913348 0.9380457 0.250756 -0.2391479 -0.5036254 0.744538 0.4382061 -0.3330815 -0.8861385 -0.3222038 0.01507341 -0.2863559 0.9580047 -0.5916037 0.3678783 -0.7174054 1.12874e-5 -0.9396895 -0.3420284 -0.8271563 -0.1084916 -0.5514002 0.3615771 0.8773943 0.3153429 -0.6981139 0.3809425 -0.6062341 0.3884679 0.8891047 -0.2420445 -1.08181e-6 -0.9396906 -0.3420258 -0.2429535 -0.9134714 -0.3264104 3.06967e-6 -0.9396899 -0.3420276 0.1349675 -0.8601927 -0.4917848 -0.4499583 -0.8311793 -0.3266167 -0.2235575 -0.919941 -0.3220722 0.998341 -0.0207284 0.05371826 0.7353938 0.3676611 -0.5692287 -0.7344666 0.6298645 -0.2526449 -0.007918298 0.9346117 0.3555818 -0.09703266 -0.9348324 -0.3415744 0.2802737 0.6631278 0.6940519 -0.1895495 0.1392676 -0.9719442 -0.8660181 0.4974476 -0.0505833 -0.1313899 -0.391491 -0.9107533 -0.3929952 -0.2113779 -0.8949156 -1.22409e-5 -0.3420898 0.9396672 0.1874867 0.434547 0.8809186 -0.1238858 -0.9326786 -0.3387668 0.8935472 0.1521729 -0.4223939 -0.731344 0.6818324 -0.01551163 0.1021447 -0.9348928 -0.3399146 -0.0150178 0.9214189 0.3882805 0.6442432 -0.1244259 0.7546316 -0.4818273 0.8673143 0.1249334 0.01671999 -0.560577 -0.8279334 0.2530967 -0.9082598 -0.333176 0.2416005 -0.5405374 -0.8058837 0.3686372 -0.2021265 -0.9073321 -0.4195248 0.8987893 0.1271871 2.81334e-4 -0.001014769 -0.9999994 0.7575434 0.1786236 -0.6278708 0.859939 -0.5091955 -0.0349968 0.09446173 -0.9358443 -0.3395178 -0.4173306 0.7020694 0.577004 0.9067017 0.4004129 -0.13252 -0.03633898 -0.8475781 -0.5294249 -0.9718835 0.1403516 -0.1890606 -1.51879e-6 -0.9396909 -0.3420249 0.4487419 0.2207716 0.8659623 -0.689123 -0.6817465 -0.2456241 0.6891916 0.2376259 -0.6845062 -0.01610487 -0.7959782 -0.6051113 -0.9596878 0.1926171 -0.2046902 -0.5849289 -0.762506 -0.2764829 -0.5854634 -0.7621268 -0.2763974 -0.3356646 -0.3127049 -0.8885634 -0.1239233 0.7529301 -0.6463276 -0.429895 -0.8489459 -0.3073775 0.6804181 -0.07119089 -0.7293578 -0.3896554 -0.8646446 -0.3171093 0.4776849 0.3658862 0.7987143 0.1128209 -0.5285934 -0.8413443 -0.3806009 -0.8682314 -0.3183038 0.8904719 -0.1466292 0.4307663 -0.4073747 -0.7861774 -0.4647266 0.1700529 0.9256641 0.3379765 0.3564769 -0.8784263 -0.3182633 0.2202445 -0.4335885 0.8737812 0.3612219 -0.8766179 -0.3178992 0.1293154 0.1217828 -0.9840968 -0.3048229 0.361496 0.8811377 -0.7309381 -0.1871472 0.6562815 -0.4050583 0.7209936 0.5622242 -0.8900075 -0.3796465 -0.2524977 0.5543594 -0.7818982 -0.2851682 0.0176618 -0.3573858 0.9337899 3.20099e-7 0.9396924 0.3420208 0.004102349 0.9401457 0.3407477 1.09801e-5 0.9527128 0.303872 0.5544493 -0.781845 -0.2851392 0.2640197 0.7174828 0.6446022 0.6672069 -2.51028e-4 0.7448725 0.7282729 -0.6443689 -0.2332537 0.1648577 0.9857398 0.03374826 -1.5451e-6 -0.9396919 -0.3420224 0.3921428 0.3788008 0.8382923 0.8355576 0.3867117 0.3902533 -0.964541 -0.247779 -0.09091883 -0.9539884 -0.2823243 -0.1009909 -0.180122 0.2980583 -0.9373992 -0.4264612 -0.3016837 0.852712 0.06868827 -0.3724036 0.9255255 -0.892876 -0.4222838 -0.1563611 -0.7828995 0.1992019 -0.5893955 -0.8351334 -0.5177091 -0.1858208 -0.7661414 0.603719 0.2203422 -0.9783651 -0.1800752 -0.1018557 -0.7776331 -0.5898992 -0.2174988 -0.05600643 0.9361321 0.34716 -0.3379977 0.9405358 0.03391188 0.8271744 -0.5291075 -0.1892824 0.8324063 -0.5215591 -0.1872856 -0.120977 0.01712864 -0.9925075 0.02343761 0.9364302 0.3500702 1.07726e-4 -0.3417035 0.9398078 0.426585 0.801761 -0.4185742 0.6970615 -0.6729697 -0.2474209 -0.5633554 0.6624704 0.4937244 -0.4860696 0.7118974 -0.5068908 -0.5790971 0.812123 -0.0714339 0.02371025 -0.2313545 0.9725805 0.9102141 -0.3885926 -0.1431987 0.001455962 -0.3638541 0.9314549 -0.05603772 0.9229026 0.380934 0.9484559 -0.2986012 -0.1061542 0.09372115 -0.9348812 -0.3423649 0.05710911 -0.4792869 0.8757984 0.9798839 -0.1863408 -0.07144725 -0.9994434 0.0265398 0.02020651 0.4644328 0.8747225 -0.1384302 -0.06016373 -0.3415142 0.9379491 0.4088855 0.6650559 0.6249106 0.004355609 0.4265304 -0.9044628 -0.3289247 0.3312471 -0.884355 0.1267619 0.6568204 -0.7433159 -0.03252124 0.9261124 0.3758435 -0.1831628 0.8755525 -0.4470561 -0.6147539 0.741146 0.2697781 4.47331e-6 -0.9396908 -0.3420251 -0.002400696 0.2698785 -0.9628914 0.9751619 -0.2211196 0.01286095 -0.0994299 0.7599772 0.6422994 -0.04817068 -0.8831071 -0.4666919 0.2565119 -0.9457256 0.1995111 0.81962 -0.5685731 -0.07034033 0.2360183 0.5889401 0.7729456 0.9511299 -0.1393373 0.2755666 0.949099 0.1763731 -0.2609668 -0.5445371 0.6770232 -0.495095 -0.1015099 0.1766806 -0.9790198 3.94592e-5 -0.3419626 0.9397135 -0.9121357 -0.3888795 0.1295427 0.1983593 0.9727624 -0.1199455 -0.2115239 -0.1378586 -0.9676014 0.7093526 -0.5037279 0.4930285 0.5220361 -0.4310497 0.7359853 0.9280776 0.09504848 -0.3600524 -1.60937e-5 -0.3421625 0.9396408 -0.5290234 0.3660126 -0.7656168 -0.2156798 0.03375864 -0.9758805 0.3094331 0.692369 -0.6518255 0.04217594 0.8766177 -0.4793357 0.9965751 0.07649236 -0.03141534 0.1102461 -0.3570463 0.927558 -0.1923731 -0.9212954 -0.337946 4.85258e-6 -0.9396932 -0.3420185 0.4386589 0.8453449 0.3049104 -0.896603 0.4428328 0.001501262 0.01295411 -0.3457726 0.938229 0.4988023 0.3737595 -0.7819848 -0.232395 -0.3499193 0.907496 -0.3604796 -0.3876308 0.8484085 -0.173034 -0.4377946 0.882267 0.637814 0.7234781 0.2641453 0.2400634 -0.6113219 0.7540922 -0.05585116 -0.8850781 -0.4620793 0.01405 0.4208474 0.9070227 -0.8999726 0.05074399 0.4329832 0.2368844 -0.2228466 -0.9456349 0.0131402 0.9154006 0.4023297 0.004961073 -0.3411973 0.9399786 -0.7985203 0.5667102 0.2029901 -0.6732621 -0.5255205 0.5201408 5.13618e-7 -0.9396937 -0.3420171 0.4004181 -0.4128246 0.8180717 -0.2626216 -0.8951889 0.3600928 -0.01261389 0.9590647 -0.2829059 -0.805729 -0.5013073 0.3154233 -0.003839015 0.9212899 0.3888574 -0.03674554 -0.4047359 0.913695 -0.8342301 -0.5379812 0.120981 0.4014706 -0.3500888 0.846321 -0.6648257 -0.7468783 -0.01340359 0.1515811 0.9878405 -0.03455877 -0.828835 -0.5537459 -0.07998692 -0.00324136 -0.9396498 -0.3421224 0.5338761 -0.820897 0.2027422 -0.001253485 -0.9397888 -0.3417537 0.9607303 0.1938735 -0.1985203 0.1957527 0.7449971 0.6376991 -0.1929083 0.9484189 0.2515711 0.1289465 0.9913108 -0.02599489 -0.9764826 0.2017869 0.07591986 0.3305794 0.8832206 0.3326239 -0.4182119 0.3057859 -0.8553325 0.4226248 -0.2927901 0.8577076 0.3631092 -0.1399586 0.921175 -0.4764772 0.3332944 -0.8135627 0.496906 0.1814495 0.8486228 -0.8791306 -0.1109446 0.4634875 0.2517911 -0.3969138 0.8826441 -0.8725337 -0.4858037 0.05176508 -0.3729885 0.2163884 -0.9022504 0.05800223 -0.003865003 -0.998309 -0.6902532 0.2229109 -0.6883759 -0.2946831 0.898652 0.3249405 -0.3861745 0.6247461 -0.6786468 -0.3465489 0.7572667 0.5535801 0.2250844 -0.5368195 -0.8131185 0.864566 -0.4853358 0.1302867 -0.1183531 0.8470333 0.5181961 -0.2372389 0.5384461 0.808575 0.2326166 0.9340597 0.2709649 4.81227e-4 0.7124863 0.7016857 -0.4593991 0.743483 -0.4859893 -0.8185212 -0.4631689 0.3398495 -0.8393365 -0.4291345 0.3337031 -5.79452e-7 -0.9396926 -0.3420204 0.2922319 0.3943076 -0.8712761 -0.9247908 -0.3693053 0.09151792 -0.9315925 -0.3536478 0.08407509 0.8159715 0.2259685 -0.5320985 -1.16393e-6 -0.9396927 -0.3420202 -0.01932811 -0.9946727 -0.101256 0.5720686 0.646379 -0.5049076 0.5770444 0.08105212 0.812681 0.9364097 -0.3382948 0.09323847 0.8814364 -0.4449008 0.158534 -0.1131168 0.8028061 -0.5854118 0.8323175 -0.4367323 0.3413393 0.8379785 -0.4588073 0.2954455 0.4679635 0.826213 0.3136594 0.8490857 -0.4959669 -0.1818529 -0.8839777 0.4519245 -0.1197817 0.368184 -0.02728438 0.9293526 -0.8906628 0.3148147 -0.3280419 0.2672375 -0.9324771 -0.2430441 0.3652683 -0.8972269 0.2481189 0.8032412 0.07767015 -0.5905683 -0.8045518 0.3556915 -0.4755838 -0.1313176 0.9446408 -0.3006815 -0.2609471 -0.6324786 -0.7292994 -0.9155753 0.3593419 0.180542 -0.0562129 -0.9409383 -0.3338791 0.2079629 0.7859742 0.5822339 -0.8255677 0.3678239 -0.4279528 0.6697807 -0.3114861 0.67407 0.4755231 -0.7316315 0.4884597 -0.1521324 -0.9241706 -0.3503775 0.1262118 -0.6885054 0.7141644 -0.08952915 -0.8777828 0.4706187 -0.7580028 -0.5758246 -0.306362 -0.3499482 -0.7434955 -0.5698691 0.09426075 0.6925145 -0.7152193 -0.7532929 0.2703321 -0.5995585 -0.5401715 0.4618818 0.7034771 -0.3434982 -0.845991 0.407809 0.2066132 -0.7677389 -0.6065377 0.7005346 -0.3957499 0.5938294 0.4803716 -0.0680437 -0.8744217 -0.3484326 0.2050898 0.9146217 0.01491057 0.9474714 0.3194926 0.9667348 0.2002725 -0.1591054 -0.3723178 0.4946527 0.7853013 0.2059629 0.7833632 0.5864481 -0.3821023 -0.2950863 0.8757408 -0.5087283 -0.4068874 0.7587082 0.2751876 -0.03033387 -0.9609119 -0.6446586 -0.3346754 0.6873192 -0.6275506 -0.3682126 0.6860027 0.7018586 0.2117342 -0.6801199 -0.01872581 -0.9109002 -0.4122014 0.7725238 -0.1840704 -0.6077213 -0.8411191 -0.181558 0.5094658 -0.878779 -0.2251239 0.4207929 -0.007507503 0.9345923 0.3556417 -0.8993417 0.1744419 -0.4009419 -0.94469 0.309767 0.1077275 0.8109358 0.2103247 -0.5460281 0.0587694 -0.9219697 -0.3827767 0.8884873 -0.1876124 0.4187981 0.9023819 -0.2071891 0.3778617 1.53064e-7 0.9396927 0.3420201 -0.7413206 0.6711475 -0.002176702 0.7563948 -0.2871139 0.5877351 0.6938744 0.7199109 0.01632899 -0.8161287 -0.07337403 0.573193 -0.7252939 0.6477415 0.2331944 0.4921144 -0.3464947 0.7986018 -0.2759542 -0.1370577 0.9513488 0.2804433 0.2190702 -0.9345372 0.4139559 -0.2970697 0.8604593 0.1201292 -0.04999989 -0.9914983 -0.6767141 0.6022534 0.423496 0.1635896 -0.4331993 0.8863278 0.09000253 0.08489727 0.9923166 0.8248549 -0.1779494 -0.5366084 -0.1904675 0.9724254 -0.1345766 -0.104572 0.8073082 -0.5807909 4.91945e-6 -0.9396922 -0.3420212 0.7598667 0.6484562 0.04590278 0.3985144 0.8614221 0.3148623 -0.750589 0.6578589 0.06195002 -0.5882343 0.07681131 0.8050344 -0.5033718 0.8122426 0.2947519 0.5765914 0.627109 -0.5237144 0.8379253 0.4909937 0.238341 -0.9556014 0.2660135 0.1267394 0.1751656 -0.9286074 -0.3271167 -0.2390388 0.3821706 -0.8926399 -0.8931232 -0.3719245 0.2529886 -0.5940217 0.5139797 0.61884 0.2811025 -0.4525457 -0.8462764 0.4638819 0.1578726 -0.8717166 0.5726104 -0.6865234 -0.4481102 -0.7265017 -0.6871626 0.001707553 0.7529515 -0.6563982 0.04696285 -0.04180139 -0.8565261 -0.5144082 0.9200055 -0.3691409 -0.1316244 0.2127392 -0.801391 -0.5590301 -1.23242e-6 0.9396925 0.3420205 0.8689324 0.297597 -0.3954649 0.4562769 0.2965956 -0.8389532 0.2320585 -0.9188239 -0.3192358 -0.7827036 -0.6166067 0.0846827 2.58098e-5 -0.9396855 -0.3420397 -0.107181 -0.9845075 -0.1387709 0.3006237 -0.9529455 0.03899198 0.1930098 0.6731786 0.7138472 0.2256928 -0.02780783 -0.9738016 0.3933188 -0.9031786 -0.1719557 0.7733458 0.4434517 -0.453086 -0.2093648 0.9564891 0.2032117 -0.8006342 0.5445259 -0.2499532 -0.4166712 0.3404415 -0.8429024 -0.9043378 0.4236393 0.05199021 0.449625 -0.6095234 0.6529307 -0.07040756 0.3420433 -0.9370428 -0.2900096 0.8232461 0.4880167 0.002851068 0.9580208 0.2866845 0.3650675 -0.9163058 -0.1646494 -0.9782409 -0.0944311 -0.1847364 0.826954 -0.5618067 -0.02280986 0.7240226 -0.6601766 0.1998954 0.5062983 0.1364876 0.8514888 0.8267889 0.5519273 -0.1086114 -1.85192e-6 -0.9396916 -0.342023 -0.2958374 -0.7491266 0.5926968 0.8216074 0.1224898 0.5567385 -0.5295062 -0.3066228 0.7909524 -0.2697516 0.9628849 0.009318053 0.7043451 -0.02790188 0.7093092 -0.9671552 -0.1504653 -0.204868 0.656234 0.01091104 0.7544787 -0.7749466 -0.5614489 -0.290229 0.1580361 0.3331444 -0.9295372 0.05673718 -0.8563917 -0.5131997 -0.06493932 -0.9309272 -0.359385 0.3273859 -0.005280256 0.944876 -0.1248611 -0.6963537 0.706754 0.01483869 0.8433367 -0.5371806 0.1062819 -0.02338337 0.9940611 0.1567946 -0.1064257 0.9818804 -1.1763e-6 -0.9396929 -0.3420192 0.04082387 0.2700691 -0.9619752 -0.03854686 0.8533085 0.5199794 -0.1113794 0.001931011 0.9937761 0.3517231 -0.2374814 -0.9054797 -0.02729821 -0.4401242 -0.8975219 -0.6739958 -0.2295513 0.7021651 -0.4314705 -0.01547342 0.9019944 0.405991 0.6688963 0.6226951 0.1654427 0.9834497 -0.07386016 -0.621133 -0.09143882 0.7783527 1.55448e-6 -0.9396924 -0.3420205 0.05730533 0.9216013 0.3838843 -0.6767936 0.1512095 0.7204762 -0.7744694 0.07805782 0.6277773 0.1164004 -0.9462118 0.3018845 0.7156205 -0.6351739 0.2905879 -0.0797919 -0.52529 0.847174 -0.0384292 0.9194572 0.3913075 0.8690452 -0.4038005 -0.285842 -0.3639473 -0.9246824 0.1118251 0.0156176 0.9980596 0.06027561 0.008611857 0.1850673 -0.9826881 0.9650872 0.2389668 -0.107245 -0.1069542 -0.8484833 -0.518302 -2.29546e-5 -0.9396873 -0.3420349 -0.03005242 0.8916995 0.4516291 0.6649293 -0.2662173 0.697852 -0.7702093 -0.6329195 0.07867926 -0.1022515 -0.8257863 0.5546365 -0.362509 -0.8913187 -0.2722831 0.2370333 0.6606443 0.7122951 0.5678458 0.7973307 -0.2044867 -0.6781736 -0.02745532 0.7343887 0.929335 -0.04080873 -0.3669757 0.07070279 0.9884372 0.1341384 0.03027296 -0.1836999 0.9825161 0.6844009 0.6846488 0.2507018 -0.8770919 0.3171792 -0.3607035 -0.9884653 0.06779772 -0.1354249 9.57384e-6 -0.939692 -0.3420217 0.8052957 0.1799438 -0.5649063 0.9809216 0.1927646 -0.02519005 -0.9790223 0.005183696 -0.2036872 -0.1667001 -0.8170138 0.5519959 -0.552764 0.6410511 -0.5324525 -0.9268114 -0.3525241 -0.1294112 0.1416403 0.4422838 -0.8856201 0.9882382 0.1069156 0.1093358 -0.315145 0.8915445 0.3253184 -0.3547926 0.8580964 -0.3712046 -0.4732266 0.1155833 -0.8733254 1.75405e-5 -0.3418623 0.93975 0.9926542 0.1126317 0.04417949 -0.2433275 0.9318735 -0.269079 0.5558745 0.1245276 0.8218858 0.6171929 -0.675247 0.4038744 -0.143197 -0.089715 -0.9856196 -0.9191364 -0.2594918 0.2963989 -0.2646304 -0.9047237 0.3338351 0.9693474 0.245626 0.005790829 -0.5635973 0.6569257 -0.500806 0.7611196 0.370182 0.5325997 -0.5019409 0.6332955 0.5890604 0.7075324 0.5397835 0.4561049 0.3183975 -0.3858081 -0.8658956 -0.008993804 -0.9355763 -0.3530103 0.00513488 -0.9394311 -0.3426992 0.5556851 0.2216299 0.8013079 -0.8402735 0.311044 -0.4440632 -0.7679712 0.001894831 -0.6404814 -0.9153845 -0.3077441 -0.2595474 0.3929492 0.2704341 0.8788951 -0.02141749 -0.4074344 0.9129834 -0.7926768 0.5619734 0.2363246 0.316377 -0.2431756 0.9169358 -0.06680101 0.9142091 0.3996993 -0.3376514 0.9412693 -0.001910507 0.9852722 -0.04069381 0.16608 -0.1697608 0.251109 0.9529561 -0.7502554 0.3441456 -0.5645179 0.1034817 0.8973588 0.4289972 -0.3518157 0.2154232 0.9109438 0.7977834 -0.2654899 -0.541347 0.7353195 0.527309 -0.4257352 -0.3968335 0.3981873 0.8270248 -0.938215 -0.3395097 -0.06697541 0.5644371 0.8087024 0.1655635 -0.6298479 0.2483983 0.735928 -0.2497352 0.3278841 -0.9111115 0.4283376 -0.7700109 0.4728742 -0.1406039 0.1042456 0.9845625 0.07670044 0.8529556 0.5163176 0.2817543 0.3354621 -0.8989326 0.505685 -0.6948931 0.5112791 -0.4120435 0.9061344 -0.0956059 -0.6441201 0.3063934 -0.7008797 -0.6353963 0.7718528 -0.02268713 -0.5142729 0.8312397 -0.2111017 -0.328711 -0.4427927 0.8341965 -0.8494579 0.05365842 -0.524921 0.5267302 0.5613607 0.6383021 -0.4188206 -0.00494343 -0.9080555 0.9103561 -0.3170132 -0.2659969 -0.5119671 0.3356143 -0.7907292 -0.2983511 0.7969318 -0.525249 -0.488376 0.8640886 0.1218185 -0.00726366 -0.4544519 0.8907417 0.4379534 -0.1101259 -0.892227 -0.02377974 0.8948411 0.445751 2.02819e-7 0.9396922 0.3420211 5.25817e-4 -0.6831071 0.730318 -0.6323848 0.4098361 0.6573613 0.06354141 0.3892614 0.9189331 -3.56246e-7 -0.9396904 -0.3420264 2.02763e-7 -0.9396927 -0.3420201 -0.08828204 0.4156526 0.9052288 0.9983294 -0.05742305 -0.006389439 0.002305269 0.9403677 0.3401519 -0.4137508 -0.6615018 -0.6254803 -0.1847683 0.9587509 0.2160032 -0.2110859 -0.8214734 0.5297397 0.2020024 -0.9194869 -0.3372518 0.9717255 0.221515 0.08173537 0.002794086 -0.9404797 -0.3398385 -0.8710011 -0.2209846 -0.4387742 -0.6941999 0.2793442 -0.6633651 0.3430802 -0.5399435 0.7686071 0.6485986 0.7607254 -0.02483576 -0.04438698 0.1654414 -0.9852202 -0.9139962 0.1525157 -0.3759652 -0.9416716 -0.3122219 0.1255869 0.7755632 -0.2090309 0.5956574 -3.0204e-5 -0.9396939 -0.3420166 0.9260417 -0.3587528 0.1172322 0.1367889 -0.5583047 -0.8182815 0.1699355 -0.05364573 0.983994 0.5732802 -0.537401 -0.6185064 0.832884 -0.2066661 0.5134136 0.3239023 -0.2434987 0.9142186 0.8740615 -0.1841588 0.4495576 0.4694914 0.6278913 0.6207498 0.4789412 0.7332295 0.4826903 -0.3465865 -0.8810762 -0.3218425 0.4017717 -0.7441678 -0.5336607 0.002315044 0.9394876 0.3425753 -0.1537706 -0.8563792 -0.4929189 0.2553365 0.6498552 0.7158851 0.2347674 0.5495043 0.8018287 -0.3716638 0.8967337 0.2402808 -0.5827198 0.59451 -0.5540718 0.1639888 0.566713 0.8074306 0.03862762 -0.1448265 0.9887027 -0.3940464 0.1388652 -0.9085394 -0.2997086 -0.9444302 -0.1350038 0.1935535 0.8916686 0.4092237 -0.6765809 0.7285505 -0.1070164 -0.09361666 0.6224907 0.7770078 -7.82417e-7 0.9396927 0.3420196 0.003768682 0.3343178 -0.9424529 0.01420539 -0.4437869 -0.8960196 0.01013487 0.3281739 -0.9445629 -0.2959498 0.6393213 0.7097057 0.1514245 -0.7004319 0.697471 -0.003573715 0.8409518 -0.5410982 -0.3780155 0.6922585 0.6147215 -0.4780834 0.6480655 0.59283 0.7406805 -0.5432581 -0.3953011 0.5190185 0.1511064 0.8413006 0.5720217 -0.7704617 -0.2813893 -0.5364613 0.7374179 -0.4103949 0.6211035 -0.2822028 -0.731158 -0.7155441 0.1020239 0.6910773 0.3454156 0.9376793 0.03801989 0.08869737 0.9271077 0.3641484 0.3843393 0.7456079 0.5443824 -0.7152588 0.3899301 -0.5799649 5.07858e-6 -0.939692 -0.3420218 0.6547336 0.6787645 -0.33257 -0.5647573 0.7717146 0.2924134 -0.001288592 -0.9384033 -0.3455395 1.84932e-4 -0.9378883 -0.3469373 0.07460969 0.905001 0.4188158 0.5062854 -0.8109654 -0.2932749 0.01701861 -0.9302675 -0.366487 -0.9926355 0.1180302 0.02727115 0.5314649 -0.8319488 0.1593928 -0.03869831 0.936665 0.3480821 0.0273872 0.762848 0.6459976 0.2234428 -0.5562846 -0.8003879 -0.07367968 0.09953647 0.9923023 -0.5669828 0.1691015 0.8061856 0.9219409 0.3615036 -0.1390685 -0.06398159 0.3019911 -0.9511612 0.751698 -0.1708325 -0.6369979 -0.2145213 0.6936423 0.6876344 0.8206382 0.1507994 -0.5511919 0.8671736 -0.4751189 0.1492384 -0.5282596 0.1595711 0.8339537 -0.5755784 0.7679933 0.2808837 0.6032648 0.7970192 -0.02884644 -0.4296784 0.7931208 0.4316664 -0.9988788 -0.04419463 -0.01697093 0.003077626 0.9314092 -0.3639609 -0.01046609 -0.9326186 -0.3607119 0.02214425 0.5390047 -0.8420116 0.2378244 0.9280396 -0.2866742 -0.6096474 0.7166662 0.3387027 0.5379377 0.7864954 0.3033941 -0.9924867 0.004042923 -0.1222862 -0.1423222 0.9522172 0.2702343 -0.1240663 0.7040644 0.6992145 -0.7275337 -0.6348635 -0.2600832 -0.40028 -0.01801925 -0.9162157 0.7910737 -0.06275224 -0.6084936 -0.1793826 0.875285 -0.449108 -0.7504034 0.6537516 0.09748679 0.339849 0.6057283 -0.7194413 0.4650505 -0.04019343 -0.8843712 -0.3496257 -0.8808714 -0.3191043 0.6556558 0.7089502 0.2598173 0.141235 0.8482591 0.5104011 0.005239486 -0.9377816 -0.347186 -0.8563634 0.4926032 -0.154867 -0.002288162 0.9347131 0.3553959 4.49399e-7 -0.9396926 -0.3420199 0.2023902 -0.2235557 0.9534469 0.4489204 0.8728702 0.1912279 0.0049901 0.3041203 -0.9526206 -8.76826e-4 -0.9394223 -0.3427609 0.1573579 -0.1632443 -0.9739557 0.4269518 -0.9033944 0.03988438 -0.470599 0.6380211 -0.6094799 -0.8402797 -0.5390221 0.05818176 -0.4535802 -0.2140872 -0.8651195 0.449356 0.6694507 0.5915359 -0.6454664 -0.6992301 -0.3073279 0.6145867 0.7451215 0.2589926 -0.1204856 -0.9859551 0.1156532 -0.7208 0.6707217 0.1748704 0.2670174 0.2768148 -0.9230793 -0.06560736 0.9582999 0.2781311 0.8701359 0.1416305 -0.4720216 0.7644413 0.5798574 0.2817713 0.5622517 0.2235763 -0.7961699 5.91995e-4 -0.3215416 0.9468953 0.9101195 0.09306591 -0.4037588 -0.06689274 0.9201143 0.385895 -0.7059213 -0.6100627 0.3598593 -0.3881359 -0.01481473 0.921483 -0.003009438 -0.3648839 0.9310482 -9.50461e-6 -0.3420715 0.9396739 0.004993677 0.9393768 0.3428501 0.07965528 -0.7258081 -0.6832699 -0.1306274 0.9308228 0.3413289 -0.6715658 0.2371315 -0.7019742 -0.003596484 0.9380539 0.3464706 -0.1589609 -0.662914 -0.7316259 -0.09207046 0.6652311 0.740939 0.3089536 -0.8936049 -0.3256041 -0.9359955 -0.05337429 0.3479421 0.02283877 0.9122136 0.4090781 1.59003e-6 -0.9396907 -0.3420252 -0.452549 0.8400961 -0.299062 -0.9840086 -0.02889448 0.1757618 0.8882471 -0.1781188 0.4234274 -0.2151569 0.7882688 0.5764893 0.9374471 0.1448389 -0.316567 -0.4462705 -0.1888962 0.8747347 -0.03539764 -0.9506677 -0.3081847 -0.2973984 0.7794939 0.5513107 0.03012865 0.1896922 0.9813812 -0.03026145 0.918174 0.3950199 -0.1475981 -0.9077232 0.392751 -0.8205242 0.5537655 0.1417177 -0.01666295 -0.9310458 -0.3645217 -6.77247e-4 -0.9393768 -0.3428857 0.9613041 0.1925355 -0.1970391 -0.7681666 -0.6086242 0.1987381 0.54277 0.3602546 -0.7586945 1.95695e-7 0.9396927 0.34202 -4.71764e-5 -0.9396933 -0.3420186 0.7396675 -0.2116078 0.6388381 -0.02580314 0.8070352 0.5899393 0.8397473 0.08246856 0.5366782 0.1593531 -0.6299615 -0.760102 -1.19392e-6 -0.9396923 -0.3420209 -0.7574394 -0.3328529 -0.5616891 -0.6778084 0.2144662 -0.7032639 -0.9647057 0.1288358 -0.2296611 0.8107684 0.5817346 0.06511104 -0.8507573 -0.4943082 -0.1785261 -0.1218326 0.9648806 -0.2327279 0.002325952 -0.9392436 -0.3432434 -0.01074987 0.6675253 -0.7445095 -0.001998603 0.3368926 -0.941541 0.2955194 0.01285237 -0.9552503 0.02962225 0.79514 0.6057021 0.6414407 0.721257 0.2614235 -0.005770266 -0.6977128 -0.7163543 -0.73684 0.6737595 -0.05581146 0.8356333 -0.4274774 0.344935 0.4995881 0.7257233 0.4730089 -0.1103451 -0.2711441 0.9561929 -0.9824223 0.05458998 -0.1785112 0.5268626 0.5353983 -0.6601247 0.7469813 -0.624706 -0.2275111 0.5533379 -0.3278099 0.7657401 0.6987432 -0.3781682 0.6072451 0.2663135 0.7880331 0.5550506 0.04565972 -0.1034563 0.9935854 0.3897079 0.3398874 -0.8559232 -0.2595247 -0.9130954 -0.3144897 0.4580616 -0.263077 0.8490996 0.9660558 -0.1436974 -0.2146794 -0.293742 -0.695628 -0.6556047 0.05769258 -0.43522 0.8984737 -4.11997e-6 -0.9396927 -0.3420196 0.219685 -0.03219038 0.9750397 -0.2757396 0.9601114 -0.04640918 0.1081057 0.8506178 0.5145508 -0.7967518 -0.08189791 -0.5987313 0.8530165 0.2976 0.4287157 0.4069586 -0.2560699 0.8768197 0.284799 0.3351694 -0.8980818 -0.1269314 0.7834901 0.6083022 0.9819472 0.1764172 0.06823849 -0.1262193 0.343025 -0.9308074 -0.0275591 -0.001866579 -0.9996185 -0.3448673 0.9379689 -0.03578972 -0.8314137 0.5209959 0.1931695 -0.8082237 0.1080475 -0.5788785 0.2839422 0.9192515 0.2726783 -0.9989879 0.01483762 -0.0424602 -0.3463581 -0.3556696 0.8680641 -5.68633e-5 0.3424451 -0.9395378 -0.570474 -0.4021704 -0.7161135 0.1616767 0.02203297 -0.9865978 0.09466761 -0.1953494 0.976154 -0.3116739 0.9211127 0.2332612 0.02816689 0.9995286 -0.01221591 0.06647741 0.908307 0.4129883 -0.6473929 0.2370076 -0.7243687 -0.5597299 0.1804788 0.8087829 0.9238071 0.3828455 0.003121674 -1.61229e-6 -0.9396914 -0.3420233 0.1500258 -0.9585991 -0.242033 0.04730641 0.9712706 0.2332286 0.9786538 0.1860237 -0.0873605 0.3604413 -0.8327261 -0.4202966 -0.6070274 0.07464897 -0.791167 0.2559033 0.001428484 -0.9667013 0.6454429 0.3949077 0.6537978 0.9862911 0.01580631 -0.1642562 -0.6945989 0.3335432 0.637402 -0.155182 0.551409 0.8196748 -0.3677372 -0.8339665 0.4114232 0.07757973 0.986113 0.1468418 -0.9730948 -0.04943972 -0.2250385 0.03318029 0.8807889 -0.4723452 -0.3426021 -0.2282713 -0.9113265 -0.8432059 0.2711226 -0.4642157 0.9724022 -0.2039668 -0.1132764 -4.1321e-7 -0.9396927 -0.3420199 -0.6030459 -0.1604301 0.7814076 -0.1838663 0.8152973 -0.5490751 0.01855665 -0.2906094 0.9566618 0.262416 0.9610566 0.08664858 0.7554597 0.08352178 -0.6498499 -0.02076935 0.7481135 0.6632457 -0.1930431 -0.9661925 -0.1708989 0.6633194 -0.2808682 -0.6936284 0.1698864 0.6800665 0.7131958 -0.3985614 -0.1553984 0.9038807 -0.8163722 0.08164888 0.5717254 -0.5639426 -0.3257182 0.7588652 -0.3438615 -0.02287101 -0.9387418 -0.5499894 -0.3440923 0.7609941 0.4574176 -0.3206385 -0.8294336 0.007428348 -0.3782993 0.9256535 -0.5734366 -0.3438076 0.7436173 -0.1348071 -0.9675199 -0.2138508 -0.1207695 0.7326087 0.6698502 0.05769073 -0.435453 0.898361 -0.3993691 -0.4361764 0.8063836 -0.01651924 0.9914354 -0.1295491 0.4700385 0.1443499 -0.8707623 0.5102114 -0.7417309 -0.4353386 0.6646779 0.3500232 -0.660066 -0.5194712 0.330411 -0.7880219 -0.5119919 0.8520762 0.1087676 -0.7953032 -0.2648197 0.5453104 0.8354008 0.003227651 -0.5496318 -0.5095023 0.8537045 0.1076852 0.9883684 0.1034933 -0.1114319 0.2541995 0.6987279 0.6687018 0.9992852 -0.03511774 -0.01399189 0.1047211 -0.8345093 -0.5409508 -3.88929e-7 0.9396926 0.3420201 0.3043891 0.7205093 0.623068 0.0151031 -0.06408691 -0.99783 9.77089e-4 0.9408643 0.3387821 -0.2184662 -0.5543671 -0.8030876 0.9752266 -0.06097835 -0.2126377 0.4250461 0.248811 0.870304 0.05110001 0.9209581 0.3862964 0.2012814 0.9787491 -0.0391907 0.4527992 0.5591689 0.6944804 0.01980781 0.9419564 0.3351507 0.695885 -0.1710034 -0.6974968 0.7500811 0.4561136 0.4788932 -0.9661151 -0.1386889 -0.2176852 0.04245471 0.2455087 -0.9684643 0.139406 0.2454165 0.9593418 -0.5931726 0.6192698 -0.5144426 0.277209 0.8057112 0.5234355 0.6253791 0.3992231 0.6704639 0.7768601 -0.3430657 -0.5280098 -0.4667869 -0.6049291 -0.6451131 -0.09242266 -0.7944541 -0.6002507 0.4553869 0.7013209 0.5484265 -0.6223706 0.7149826 -0.3185198 -0.6846445 -0.7084562 0.1713236 -0.660985 -0.2644212 -0.702268 -0.2940461 -0.3287538 0.897473 -0.5907058 -0.4755008 -0.651894 -0.5428463 -0.5101268 -0.6671496 0.7258239 -0.2939137 -0.621928 -0.03394752 -0.3664495 0.9298185 -0.2767735 -0.5969545 -0.7530218 -0.8987186 0.1839925 -0.3980597 -0.01857095 -0.9405713 -0.3390882 -0.5782626 0.7661021 0.2805349 0.8016858 0.3414041 -0.4906558 -0.01089006 0.5448026 -0.8384936 0.03178989 0.9058539 0.4223957 0.0919401 -0.9611917 0.2601107 3.76699e-6 -0.9396941 -0.3420163 -0.4458304 0.5570803 -0.7006404 -0.05183833 0.9188647 0.3911527 -0.09946835 0.9929884 0.06387561 3.04588e-4 0.3141269 -0.9493809 -0.3449937 0.3496367 -0.871053 0.5739361 -0.8046622 -0.1520403 -0.02618318 0.7859823 0.6176943 0.09569531 0.7757543 0.6237369 0.9676272 -0.07506 0.2409639 0.04705023 0.6816561 0.7301585 0.09332251 0.6335299 0.7680696 -0.001068353 -0.9394493 -0.3426867 0.9985171 0.01456838 -0.05245351 0.007852554 -0.9947941 -0.1016022 6.75394e-6 -0.9396933 -0.3420183 -0.03358423 -0.7931869 -0.6080517 0.4014728 0.8185344 -0.4108782 0.1486299 0.4063107 0.9015657 0.6133747 0.1268392 -0.7795405 0.823547 0.5478447 0.1470943 -0.9047906 -0.3521519 -0.2394639 0.96111 -0.2379446 0.1401781 0.02934044 0.9600102 0.2784239 0.3513693 -0.8792854 -0.3215536 -0.3942831 0.7950369 0.4609308 -0.7711182 -0.5988477 -0.2162359 0.8934457 0.4142538 0.1736334 0.1201051 0.97036 0.2097046 -0.2733432 0.5941389 -0.7564936 0.7614606 0.6119846 0.213665 0.04076939 -0.9991233 -0.009506464 0.7285401 0.6363317 0.2535971 -0.7104021 0.2388141 -0.6620397 0.5374953 -0.1415772 0.8312969 0.1442033 -0.2596461 0.9548766 0.8724042 0.4585088 0.1693537 -0.2212136 0.1220908 -0.9675528 0.3257208 0.427112 0.8434936 0.2516251 -0.7190033 0.6478573 -0.3311862 -0.1546952 -0.9307981 -0.6772067 -0.2233734 0.7010673 3.86428e-7 0.3420268 -0.9396903 0.009755194 -0.3153237 0.948934 1.05274e-5 -0.9396846 -0.3420424 0 0.9396925 0.3420205 -0.451191 0.4229186 0.7858541 -0.5202902 -0.2185881 -0.8255407 0.9443999 0.103407 -0.3121151 0.1961508 -0.5958024 -0.7788095 -0.8646713 0.4183948 0.2780094 -0.07097303 -0.04002368 -0.996675 -0.05618476 -0.115357 -0.9917339 0.1655983 0.9068869 0.3874705 0.7867389 0.2091072 -0.5807892 0.3730902 -0.8749348 0.3086953 -0.08298957 -0.7308285 -0.6774972 0.06045466 0.9212283 0.3842964 -0.3123543 0.354005 0.8815413 -0.003094315 0.634809 -0.7726628 -0.5820676 -0.7528687 -0.3072229 -0.1211068 0.8937683 -0.4318695 -0.8893607 -0.1078548 -0.4443027 -0.571754 -0.5201697 0.6344453 -0.7937861 0.4957886 0.3522746 -4.80602e-5 -0.342449 0.9395364 -0.129871 0.932846 0.3360534 -0.101491 0.9225326 -0.3723346 0.717181 -0.6211192 0.3160102 0.546414 0.1708143 -0.8199111 -0.03306573 0.7796514 0.6253402 0.9796596 0.008069157 0.2005044 -0.9701263 0.1430046 -0.1959707 0.01972842 0.9053819 0.4241394 0.005718171 0.9400657 0.3409455 0.6513791 0.6596412 0.3749383 0.5510094 0.7082164 0.4413822 0.5460502 0.7276829 0.4150986 0.5189285 0.7208424 0.4594557 -0.01281082 0.9923254 0.1229889 0.1395294 -0.9300559 -0.3398935 -0.1052628 0.9551485 0.2767871 3.58846e-5 0.3415852 -0.9398508 -0.007826447 -0.936933 -0.3494215 0.6707041 0.04564595 0.7403193 -0.5122148 0.4965533 -0.7007645 -0.9191104 0.3859177 0.0793963 0.6785214 -0.5064452 -0.532092 -0.2578923 0.240326 -0.9358071 0.5177493 -0.7884595 -0.3320651 0.8290452 0.2667859 0.4914358 0.4510579 -0.8258378 -0.3384358 0.563299 -0.7666704 -0.3080757 0 0.9396925 0.3420206 0.6985591 -0.6500135 -0.2991619 0.7258882 -0.6234129 -0.2905905 0.7652875 -0.5744351 -0.2904468 6.01671e-6 -0.939695 -0.3420135 -0.0332477 -0.1934793 0.9805408 0.8306545 -0.4896553 -0.2650488 0.3708378 0.173738 0.9123017 0.9007615 -0.3554987 -0.2494984 0.9038959 -0.3467923 -0.2504144 -0.6675947 -0.3521867 -0.6559587 0.7976956 0.5656762 0.2090264 0.9637808 -0.157074 -0.2155326 0.9734986 -0.02891188 -0.2268582 -0.12634 -0.9575247 0.2591997 0.6101311 -0.7290555 -0.3101907 0.1611598 -0.5740904 -0.802775 0.8117535 0.2063188 -0.5463412 0.7138602 0.1624307 -0.68119 -0.05975681 0.1661423 -0.9842895 -0.8133897 0.5668398 0.1307277 0.6909508 -0.2414444 0.6813894 0.1807868 -0.7676802 -0.6148033 -0.9235182 0.1551216 0.350787 -1.26255e-5 -0.3421 0.9396635 -0.736717 -0.05571943 0.6739017 0.6963497 0.5858324 0.4146053 0.2365794 0.7344204 0.6361265 0.8292552 0.2491469 -0.5002614 0.756948 0.009125947 -0.6534115 0.9715281 0.117368 -0.2058103 -0.7859958 0.2406561 -0.5694693 -0.8427627 0.3119016 0.4387122 0.01412308 0.8222765 -0.5689129 0.02081423 0.9997829 9.45458e-4 0.02454435 0.9091947 0.4156472 -0.4666437 0.7630664 0.4471837 0.9752576 0.2207967 -0.01101851 0.3847013 0.2060799 0.8997423 -0.4893872 0.276107 0.8272032 -0.2069572 0.263112 0.9423061 0.7525698 -0.2925274 -0.5899715 0.9823958 0.1094021 0.1514259 0.2425024 -0.3954364 0.8859021 0.1835163 -0.2600061 0.9480077 0.007509171 0.3429867 -0.9393103 0.7927726 -0.3619076 0.4904431 0.3650422 -0.2646351 0.8925875 -0.5002301 0.7847869 0.3658951 -4.55609e-7 -0.9396926 -0.3420203 0.5020324 0.5264996 0.6861207 0.9562146 0.125461 -0.2644112 0.0727871 -0.9183904 -0.3889231 0.4774654 -0.1127518 0.8713862 0.003580927 -0.9386427 -0.3448727 -1.33459e-5 -0.3420604 0.939678 -0.6347352 0.4653819 0.6168718 0.1442799 0.00666356 -0.9895144 -0.7264286 0.2582423 0.6368771 0.5815302 0.7853114 0.212388 -0.2493443 0.8948601 0.3702065 0.3948212 -0.135637 -0.9086907 -4.63216e-7 0.9396929 0.3420192 1.52234e-5 -0.9397001 -0.3419995 0.3556706 0.7638552 0.5385385 -0.2193053 -0.8549115 -0.4701399 -0.256003 -0.6143853 0.7463197 0.903856 -0.4270544 0.02586519 0.2269692 -0.8017871 -0.5528311 -0.7892776 -0.5185505 0.3288561 -0.373282 0.7337117 -0.5677391 -0.993879 -0.05170178 0.09762924 -0.9890168 -0.1471866 -0.0134868 -2.69937e-4 0.3196626 -0.9475314 -0.6597204 0.7024983 -0.2669554 -7.50092e-6 -0.9396915 -0.3420233 -0.905317 -0.1338106 0.4031077 0.6290187 -0.2000093 0.7512202 0.1389875 -0.780717 -0.6092319 0.2264268 -0.3467352 0.9102228 -0.2174625 0.3591488 -0.9075915 -0.8925933 0.4250037 0.1504952 0.8564064 0.3717345 -0.3583037 0.4444459 0.7590188 0.4757713 0.8543417 0.2697893 0.4442005 0 0.9396925 0.3420204 0.03304159 -0.5390431 0.8416299 0.05860579 -0.8830201 -0.4656618 -0.9676695 -0.1424357 -0.2081531 -0.7947259 -0.2149709 0.5676251 -0.7344915 -0.4398341 0.5167863 0.6017516 -0.3025574 0.7391576 0.4491386 0.2783449 -0.8489987 0.1281682 0.9031837 0.4096733 -0.8272433 -0.3001093 0.4749768 0.5107133 0.5271541 -0.6791763 0.03094589 0.4282073 -0.9031504 -0.5938715 0.8045587 -0.001373827 0.279994 0.1912924 -0.9407501 -0.4177138 0.832917 0.3629938 3.23563e-7 0.9396927 0.3420197 -0.8302921 -0.2608887 -0.492496 -0.37156 -0.3069444 0.8762011 4.56848e-6 -0.9396896 -0.3420286 0.2565128 0.9210315 -0.2930911 0.4592019 -0.2175787 0.8612741 0.06873106 0.3372479 -0.9389036 0.2749425 0.2696694 -0.9228678 0.2062892 0.9099964 0.3596543 -0.4244706 -0.8164414 0.3914695 -0.03180402 -0.8427947 0.5372948 0.4635858 -0.3007655 -0.8334437 0.1901613 0.005402266 -0.981738 -0.6959148 -0.4945837 -0.5206626 -0.2940389 -0.3287543 0.8974753 0.855601 0.2239158 -0.4666995 -0.6361156 0.3706491 0.6767394 0.4171232 0.8646284 0.2800462 -0.5523533 -0.2758684 -0.78664 -0.7697558 0.5990147 0.2205839 -0.5102072 0.7694115 0.3843106 -0.1326028 -0.9709219 -0.1993168 -0.2098813 -0.411918 -0.8867207 0.532787 0.3871464 -0.7524996 0.7508009 -0.620827 -0.2255474 0.5384233 0.8289942 -0.151225 3.20717e-5 -0.9243771 -0.3814799 -9.42815e-4 -0.9390972 -0.3436504 0.4256393 -0.4615492 -0.7783339 -0.26166 -0.934343 -0.2419447 -0.9481979 -0.1043849 0.300041 -0.4710592 0.1493321 0.8693695 0.5121237 -0.07613068 -0.8555311 -0.8726436 -0.4815752 0.08110743 1.56632e-6 0.9396928 0.3420197 -0.2027848 0.02731174 -0.9788424 0.9675118 0.134518 0.2140699 -0.2704447 -0.5806523 -0.767921 -0.8204604 0.03928947 0.5703518 0.2418835 -0.3032397 0.9217039 0.9866732 0.150866 0.06095421 -0.9993448 0.02525353 0.02592879 -0.3450934 0.9347401 0.08468365 0.6906745 -0.4274055 -0.5833466 -0.6595363 0.05237406 0.7498459 -0.9981227 0.06115889 -0.003261923 -0.5917608 -0.6723278 0.4447411 -0.8887749 -0.431147 -0.1555353 -0.8191959 -0.1597815 0.5508065 0.9339134 0.334921 0.1250346 -0.5664659 0.126312 -0.8143474 0.2385174 -0.6494277 -0.7220478 0.008284449 0.07750338 0.9969577 -0.599103 0.1694302 -0.7825402 0.0422272 0.6460998 0.762084 -0.6564967 0.1520151 0.7388529 0.2461909 0.2851838 -0.9263154 -7.67652e-5 -0.9397005 -0.3419986 1.46661e-6 0.3420497 -0.9396819 -0.03156518 -0.8238182 -0.5659747 -0.08959859 -0.8998097 0.4269831 -0.3095046 0.01892954 -0.9507095 -0.7793673 -0.6012794 0.1762093 -0.1020362 0.7914852 -0.6026108 -0.07852303 0.9469274 0.3117094 0.2360857 -0.5912848 -0.7711328 0.3970482 0.3350179 -0.8544681 0.1859019 0.9282385 0.3222017 0.7299843 -0.6167356 -0.2945505 0.9987339 -0.04183912 0.02793145 -0.6082888 0.08075177 -0.7895973 0.5448033 0.6175804 -0.56726 0.06362181 0.9888322 -0.1347706 -0.4967359 -0.4256663 0.7563475 0.5584143 0.7793307 0.2842835 -0.007808566 -0.9352168 -0.3539897 -5.40094e-7 -0.9396926 -0.3420201 0.2687506 0.003027617 0.963205 -0.08788657 -0.8259739 0.5568151 -0.5146394 -0.840196 -0.1709298 0.2871882 0.910135 0.2986257 -0.06946247 -0.9196037 -0.3866577 -0.9448714 -0.3257778 0.03296816 -2.33059e-7 -0.9396924 -0.3420208 0.2762894 -0.7981415 -0.5353823 -0.5517947 0.3197993 -0.7702279 0.8658316 0.4974001 -0.05411905 0.6739948 0.4830963 -0.5588819 -2.92996e-5 -0.9396908 -0.3420252 -0.03947889 0.7907367 -0.6108819 -0.03725671 -0.1709296 -0.9845786 0.3489095 0.8546501 0.3844938 -0.729258 -0.3864073 0.5646877 -0.01017576 -0.9394266 -0.342599 -0.5335256 -0.6898985 0.4892755 -0.4478568 -0.7309377 0.5149316 -0.3447122 -0.8973952 0.2754188 -0.9654222 -0.1439089 0.2173711 -7.47233e-7 -0.9396928 -0.3420197 -0.3604729 0.7209845 0.5918114 -0.3999273 0.6899673 0.6033268 -0.5726912 0.7648169 0.2950932 -7.39833e-7 -0.939693 -0.342019 0.06201201 -0.9372341 -0.3431426 -0.2451628 0.3456097 -0.9057865 0.4063071 -0.5251708 0.7477368 0 -0.9396926 -0.34202 0.9288672 0.3475862 0.1280227 0.6017497 -0.3025547 0.7391602 0.9996191 -0.01025974 -0.02562135 -0.2571371 0.5945557 -0.7618294 -0.5545275 0.8187029 -0.1490798 -0.9871902 0.1248183 0.09937793 0.06322091 -0.8823237 -0.4663776 -0.08116674 0.8023963 0.5912464 -0.8524236 -0.4200475 -0.3113425 -0.6287341 -0.2780206 0.7262218 -0.1439309 0.1513986 0.9779377 0.8365588 -0.09891796 -0.5388735 -0.7470352 0.2559628 0.6135321 -0.4452204 -0.6904138 -0.570182 0.5346558 0.801571 0.2676325 -0.5112235 0.5476078 0.6624019 0.1287901 -0.6390866 0.7582753 -0.4364634 0.3519685 -0.8280204 0.8107787 -0.5545459 0.1873943 -0.1971723 -0.4245944 0.883653 -0.2338392 -0.8222944 0.5187979 -0.5018692 -0.5922605 0.6303609 -0.4139525 -0.01216399 -0.9102172 -0.893207 0.4491353 0.02141624 -0.7181735 0.6152932 -0.3250247 0.03282797 0.8343074 0.5503214 0.2755906 -0.6350486 0.7216392 -0.9196602 -0.1123129 0.3763121 -0.6626978 -0.5637542 0.4929633 -1.36387e-7 0.9396927 0.34202 0.3396378 -0.2967042 0.8925316 0.06518387 0.6708078 -0.7387611 -0.3261685 0.4501525 -0.8312501 0.01542168 0.9958027 -0.09021663 0.3531684 -0.7642396 -0.5396386 -0.5772796 -0.1108061 -0.8089933 0.1083855 -0.8206118 -0.5611137 0.6527385 0.4068596 -0.6390599 -0.1551406 -0.02506107 0.9875745 0.7660964 0.6049416 0.2171218 -4.12387e-6 1.98018e-5 -1 0.8101053 0.03592914 0.5851825 0.08170992 -0.9662916 -0.2441393 0.009026467 -0.9424782 -0.3341457 -0.2262035 0.8837631 0.4096276 -0.2434448 0.3242033 -0.9141263 0.005088508 -0.9377829 -0.3471847 0.2782034 -0.9349645 0.2201008 0.8062498 0.1911564 -0.5598397 0.8773874 0.4521963 0.1603432 -0.9630939 0.2536825 0.08997452 -0.004342913 0.3428673 -0.9393738 -0.9009848 0.3071033 0.3064537 0.7225871 0.1491286 -0.6750027 -0.8250858 -0.0351597 0.5639126 0.3185004 0.3259564 -0.890118 -1.14967e-6 -0.9396915 -0.3420233 -0.8587788 -0.383804 0.3394015 -0.002055525 0.9415689 0.3368142 -0.6887731 -0.6701489 -0.276572 -0.6321405 -0.7589144 0.156356 0 0.9396929 0.3420193 -0.3105446 -0.2318801 -0.9218425 -0.4507252 0.38063 0.8074451 -0.9324279 0.3611989 -0.01065081 0.4152978 0.8868661 0.2024753 -0.9879463 -0.154515 0.009337902 -0.2739389 0.9567727 -0.09769028 1.72813e-6 0.9396926 0.3420203 0.3910613 -0.06789147 -0.9178572 0.5367526 0.5934543 -0.5997572 0.4292203 -0.7715733 0.4695151 0.9275014 -0.05651408 0.3695231 0.8120521 -0.1346145 0.567847 -0.2370494 -0.602522 0.7620857 0.8542475 -0.4542199 0.2528742 -0.3317797 -0.7513101 -0.5704869 -0.0441488 -0.9737555 0.2232739 0.1353207 0.94178 0.3077962 -0.0338779 0.7647002 0.643495 0.9999836 -0.005098462 -0.002636253 -2.00657e-7 0.9396928 0.3420197 0.5828576 -0.115243 -0.8043607 -0.787366 -0.1930918 -0.585466 0.3205298 -0.7446556 -0.5854473 0.8846482 -0.1839087 0.4284569 -0.2727826 0.9320439 0.2385034 0.197821 -0.112266 -0.9737881 0.6308711 0.2440838 -0.736495 -0.9103175 -0.01038491 -0.4137805 0.2539944 0.8218981 0.5098732 -0.4417603 0.3604556 -0.8215349 0.01226967 0.9103135 -0.4137376 0.4505237 0.8467034 0.2830579 -0.9058293 0.4056012 0.1223152 -0.7757884 -0.2020761 -0.5977604 -0.5509275 0.8092806 0.2038228 0.09494364 0.6893306 0.7181984 0.06408166 0.6753743 0.7346858 -7.52995e-7 -0.9396925 -0.3420205 0.4148254 -0.4367681 -0.7982189 -0.6381651 0.7519929 -0.1650825 0.002689421 0.7762736 0.6303905 0.006081104 -0.9361956 -0.3514268 0.5039601 0.2311871 0.8322121 0.2544077 -0.9416041 0.2205865 0.1381256 0.787957 0.6000375 0.08280533 0.8893216 0.4497227 -0.6534518 0.6762125 0.3402022 0.3468372 0.1068235 0.9318222 -0.6939602 0.3961161 -0.6012581 0.2895824 0.8023512 0.5218952 0.3999302 0.8505893 0.3413996 0 0.9396927 0.3420197 0.5297048 0.7986946 0.2854817 -0.458052 0.8594154 -0.227142 -0.006735265 -0.8096573 -0.5868643 0.9016076 0.04028308 0.4306749 -0.3089973 -0.8931718 -0.326749 0.003584325 -0.3339369 0.9425886 -0.6072918 0.08105719 -0.790333 -0.01031428 0.941009 0.3382245 0.6593757 -0.4977821 -0.5634151 -0.1220488 0.9577956 0.260253 1.51846e-5 -0.9396966 -0.342009 0.1406426 0.9700869 0.1978662 -0.8528128 -0.5202798 -0.04493761 -0.6593138 -0.316268 0.6821144 -0.05948418 -0.5573608 -0.8281369 0.0546292 0.9949766 -0.08388715 0.8289566 -0.5520386 0.08991432 0.671801 -0.4577009 0.5824032 0.9474902 0.2978354 -0.1164326 -0.6220098 -0.7386901 0.2596934 -0.2448331 0.9662109 -0.08058071 0.6683313 0.7274426 0.155437 0.002703607 0.3438654 -0.9390151 -0.09663254 0.9540835 0.2835259 -0.1737662 -0.926337 -0.3342229 0.2494328 0.4996582 0.8295329 -0.9323974 0.1229337 -0.3398859 -0.00801301 0.9391363 0.3434514 0.1515709 0.815928 0.5579319 -0.4588428 -0.2723313 0.8457535 -0.51598 0.06462538 -0.8541594 0.1896548 -0.9622349 0.1952821 0.6705843 0.04580539 0.7404178 0.7819659 -0.1817562 0.5962331 -0.6271871 0.7693265 0.1215449 -0.150478 -0.1519484 -0.9768665 0.007396459 0.9393011 0.3430144 0.2433207 0.9363771 0.2529682 0.09937644 -0.901315 -0.4216107 0.7644389 0.5798625 0.2817671 0.004160702 -0.3550487 0.9348385 -0.2638749 0.7133817 -0.6491968 -0.2686007 -0.9453622 0.1847807 0.0911048 -0.7447469 0.661099 -0.7977101 -0.4119635 -0.4403916 0.6385528 0.2778907 -0.7176539 -0.9522638 -0.2634761 0.1541889 -0.8675999 -0.4201673 -0.2659511 0.2642651 0.9635296 0.04212647 0.9736333 -0.1886546 -0.1282483 -0.5101503 -0.795358 0.3273415 -0.04474818 -0.591091 -0.8053627 0.8081372 -0.5536527 -0.200955 0.04542857 -0.7271086 -0.6850178 0.6821085 -0.2558438 0.6850342 0.2506707 0.6589325 -0.7092052 0.9726691 0.1428511 -0.1830535 -0.5562038 0.4044835 0.7259685 -0.181776 0.8769021 0.4449722 0.9874977 0.1429606 -0.06641376 -0.9517815 -0.1963656 -0.2356954 0.6659045 0.1200131 0.7363207 0.01038706 0.9049532 0.4253845 -0.1738962 0.3781789 -0.909253 -0.03953504 -0.8789348 -0.4753005 4.90037e-7 0.9396926 0.3420202 -0.06403458 0.186017 0.9804577 0.2913346 0.8330815 -0.4702119 0.3121754 0.9467948 -0.07826888 -0.8717405 0.4850399 0.06931734 -0.5193982 0.3335728 -0.7867369 -0.9776198 -0.007310211 0.2102529 0.09443986 0.9039988 0.4169739 -0.06595057 -0.9366067 -0.3441199 -0.5434442 0.8298731 0.1264083 -0.9301756 -0.3516457 -0.1054459 0.006991922 0.9728131 0.231486 -0.9672011 0.1216197 -0.2230035 -0.252706 0.1992111 -0.9468128 0.9571949 -0.1384969 0.2541583 -0.07913398 0.01786571 -0.9967039 0.2664129 0.9633843 -0.03024375 0.05301374 -0.8819602 -0.4683328 -0.9159375 0.3976014 0.05451232 -1.45063e-7 -0.939693 -0.3420188 -0.07877957 -0.188118 0.9789819 -0.02099555 0.9314472 0.3632702 0.008066117 -0.2627921 0.9648187 0.3454201 -0.8796141 -0.3270534 -0.9979351 -0.008439481 -0.06367254 -0.3188104 0.568472 -0.7584191 -0.9106782 0.3688406 -0.1860694 0.01030778 0.9393077 0.342921 0.001281499 -0.3259575 0.9453836 -7.09517e-7 -0.9396923 -0.342021 -0.9264947 -0.1165935 0.3577898 -0.0683853 -0.5950307 -0.8007883 -0.3881252 0.7763136 -0.4966849 0.3650293 -0.264546 0.8926192 1.55289e-7 0.9396926 0.34202 -0.379088 0.8785229 0.2906711 0.8825315 0.4693782 0.02867317 -0.2543542 0.8484157 0.4642142 1.25162e-5 -0.9396843 -0.3420429 -0.6987674 -0.08112543 -0.7107341 2.60584e-6 -0.9396919 -0.3420225 7.10986e-7 0.9396926 0.3420201 -0.4650681 -0.2825185 0.8389844 7.31031e-4 -0.9852166 0.1713122 -0.02489012 0.3024389 0.9528437 -0.01697438 -0.5616788 -0.8271813 -0.977015 -0.1808983 0.1127718 -0.8822885 -0.4628003 0.08592349 -7.9358e-4 -0.9756072 0.2195219 -0.9526203 -0.2869602 -0.1008388 -0.1467493 0.5056583 0.8501614 -0.556562 -0.3956773 0.730533 0.9459471 -0.09915733 0.308791 0.004256725 -0.9839431 0.1784321 -0.7566404 -0.360989 -0.5451442 0.06239199 -0.7328392 -0.6775352 -0.6441435 -0.7579033 0.1032557 -3.34549e-4 -0.9853842 0.1703463 0.003429591 -0.9833518 0.1816803 0.713906 -0.1791142 0.6769463 -0.1616129 -0.3568542 -0.9200741 0.7739809 -0.5967577 0.2117399 0.4168064 -0.8791084 -0.2311726 -0.6154537 -0.7639157 -0.194035 -0.01164245 -0.9859686 0.166524 -0.7839972 0.1086531 -0.6111814 0.006718695 -0.984533 0.1750702 0.8414137 -0.08706593 0.5333315 -0.3621872 0.824879 0.4340451 0.2992824 -0.4705905 -0.830045 0.06155145 -0.05724537 -0.9964609 -0.1237676 0.8310178 0.5423015 -0.1248353 0.9857354 0.1128799 0.8507598 -0.1459043 0.5048959 -0.8354015 0.3508234 -0.423116 0.3127631 0.4201383 0.8518586 2.25871e-5 -0.9396944 -0.3420153 0.4435932 -0.8515682 0.2793864 0.2917898 0.5707672 0.7675177 -0.6285865 -0.08311456 -0.7732858 -0.002482831 -0.939584 -0.3423094 0.8825591 0.4699431 -0.01558834 -0.2031132 0.7457507 0.6345084 0.005211293 0.9394115 0.3427519 0.5420898 -0.02967578 0.8397964 -0.9945376 -0.04992884 0.09166252 -0.7788161 0.4554067 -0.4313353 0.6473002 0.2720595 -0.7120296 -0.2386122 -0.5149053 0.8233692 -0.3213735 0.8886716 0.3270809 -0.1290311 0.793073 0.5953035 -7.74297e-7 -0.9396913 -0.3420236 0.979934 -0.04779428 0.1935071 0 0.9396927 0.3420198 -0.9023927 -0.0856477 0.4223173 0.1056123 0.971576 0.2118633 0.8002425 0.5486542 0.2420545 0.4336546 0.8836939 0.1761503 0.3291113 -0.8850691 -0.3291479 -0.68449 0.3393422 0.6452288 0.03792381 0.7873948 0.6152815 -0.4480295 -0.3284396 0.8315028 0.789417 -0.5707087 -0.2260807 0.003172636 0.7276344 -0.685958 -0.1217385 0.8814995 0.4562219 0.04273945 -0.1869759 -0.9814344 -0.7510294 -0.2886922 -0.5938111 0.3386931 0.933788 0.1154434 -0.2015027 0.8373257 -0.5082148 -0.9747596 -0.1101381 0.1941987 -0.02780562 -0.7428686 0.6688596 0.2661384 0.8298147 -0.4904874 -4.76705e-7 -0.939693 -0.3420194 0.8436586 0.3545808 0.4031285 -0.4911847 -0.8127536 -0.3133193 0.1217291 0.9869233 -0.105662 0.02805763 -0.9219294 0.3863404 -0.6581515 0.6189136 0.4286987 -0.4285835 0.3801806 0.8196212 -0.07138007 -0.9369257 -0.3421622 1.98369e-5 -0.9396825 -0.342048 -0.5770635 -0.8163362 0.02434891 -0.6416709 -0.75075 0.1569496 -0.327055 0.720174 0.6118696 -0.5621945 -0.8262286 0.03582894 -0.4124431 -0.9089444 0.06091666 -0.4032597 0.0322625 0.9145167 -0.5606631 0.7069566 0.4311256 0.2181391 -0.916369 -0.3356832 0.9107679 0.09227257 -0.4024768 -0.8357913 -0.1901947 0.5150523 -5.8886e-7 -0.9396924 -0.342021 -0.8047046 0.5278649 0.2716787 -0.505823 -0.4839301 0.7141112 -0.9672488 0.2502326 0.0425834 0.3373487 -0.2909411 0.8952928 -0.001727402 0.9397607 0.3418288 5.87254e-6 -0.939693 -0.3420192 0.8172781 0.5547772 0.1558167 -0.08655768 0.4217992 0.9025482 -0.6478419 -0.7160305 -0.2600024 -0.07226049 -0.9973856 -4.84795e-4 -0.249362 -0.7370514 0.6281509 -0.4855234 -0.1138011 -0.8667851 -0.4016019 0.8406991 0.3632366 -0.1516604 -0.6555092 0.7398018 0.3539953 -0.2814458 0.8918944 -0.7680435 0.412186 0.4901141 0.2668634 -0.1724618 -0.9481776 0.396036 -0.8496174 0.3482897 2.91807e-6 0.9396924 0.3420208 -0.9605687 -0.04513871 0.2743542 -0.590238 -0.1965866 0.7829259 -0.1910627 -0.3833809 -0.9036117 0.007009983 0.9623595 0.2716891 -0.7446109 -0.2610108 0.6143517 0.627016 0.4466278 0.6382591 0.4286953 0.6601008 0.6168364 -0.3365659 0.004540741 -0.941649 -0.9917908 -0.1128752 -0.06008678 -0.317234 0.8919821 0.3220719 0.4477511 -0.2643659 -0.8541836 -0.5203128 0.5936407 0.6138936 0.2776569 0.486391 -0.8284507 -0.8380403 0.5430147 -0.0531367 -0.5473951 0.8024739 -0.2374751 0 -0.9396927 -0.3420199 -0.04533505 0.1015697 0.9937949 -0.7074706 0.6504032 0.2765159 0.3347274 -0.6565359 0.6759572 0.6288307 -0.200019 0.751375 0.1056329 0.07153099 0.9918292 -0.4664875 0.6848052 0.5598492 0.02534699 -0.9994856 0.01965111 -0.2695477 0.9118914 0.3095129 0.3678122 0.3250588 -0.8712353 -2.48813e-7 -0.9396926 -0.3420204 0.01101255 -0.4353814 0.9001787 0.3046285 -0.5644943 -0.7671685 0.6593518 0.746921 0.08581608 -0.1381075 -0.8242947 -0.5490578 -0.07715904 0.8484895 0.5235571 -0.08120179 0.3381416 -0.9375855 0.06214427 -0.9161744 -0.3959326 -0.6241283 -0.7447867 0.2361284 0.04104894 0.9608299 0.2740817 -0.9999676 0.007359564 0.003278315 -0.8695015 -0.2331389 0.4354463 0.8559195 -0.2238577 0.4661433 0.02474498 -0.9421324 -0.3343264 1.63497e-4 -0.9378803 -0.346959 -0.5435928 0.7655237 0.3442098 0.9710068 0.128135 -0.2018101 -0.1562173 0.7507377 0.6418636 0.04935985 -0.9442372 -0.3255452 0.2128797 -0.1751599 -0.9612498 0.2515446 -0.5667241 -0.7845695 -3.69136e-7 -0.939693 -0.342019 -0.4147692 0.8667914 -0.2768378 0.002333581 0.9055369 0.4242612 -0.1870251 -0.9671494 0.1721733 0.2415542 0.1541569 0.9580643 -0.3757924 -0.8333686 -0.4053109 0.9462398 0.2848219 0.1533192 0.2491255 -0.07168984 0.9658142 0.568812 0.7905195 0.2270064 -0.1282633 -0.9886366 0.07839816 0.01119357 0.9380033 0.346446 -0.1837308 0.8585348 0.4787079 -0.3982359 -0.868849 0.2941252 -0.1091265 0.4160723 0.9027597 -0.00262928 0.3365712 -0.9416544 -0.3416804 0.8305943 0.4397359 0.1626703 -0.4817718 -0.8610658 -0.1320649 -0.587801 0.7981534 -0.3571017 -0.6688972 0.6519624 -0.2804992 0.9428897 -0.179664 -0.4495865 -0.7676061 0.4567853 -0.3773639 -0.8436967 0.3818014 0.03354269 0.9741005 0.2236138 0.8903572 -0.1740399 0.4206829 0.8978573 0.4400131 0.01552236 -0.5438457 0.3998527 0.7378005 -0.5080499 0.672736 -0.5378769 0.1743708 -0.858793 -0.4817358 -0.9801952 0.05575287 -0.1900236 0.8805338 0.4699345 -0.06182247 -0.9436843 0.2169593 0.2497771 0.9326232 -0.1077591 0.3443865 -0.5020485 -0.2214639 -0.836003 0.003459155 0.9377744 0.3472276 -0.3028752 0.7339031 0.6079908 0.6800377 -0.2319154 0.6955314 -0.7193427 0.2731389 -0.6387028 -0.2163845 -0.9723046 0.08832687 0.3047604 -0.7345343 -0.6062842 -0.378385 0.4220734 0.8238197 0.9725019 0.08651256 -0.2162303 0.3483781 -0.3288478 0.8777766 0.2537226 -0.6185172 0.743681 -0.6580581 -0.2769476 0.7001855 0.9987339 -0.04183959 0.02792984 0.8595445 0.4231095 0.2866387 0.7020518 0.1763196 -0.6899527 0.4726488 -0.3129964 0.823794 -0.1577515 0.8819376 0.4441851 -0.7378081 -0.2788888 -0.6147034 -0.02502495 0.5844899 -0.811015 -0.1656062 0.8804574 0.4442626 0.2643719 -0.9643619 -0.01065772 -0.6269808 -0.7208233 -0.2954807 -0.678011 -0.258214 0.6882053 -0.4110401 -0.570614 0.7109471 0.3421722 0.100055 -0.934295 0.001848459 -0.3315313 0.9434424 -0.4612013 -0.3672452 -0.8077279 -0.7089442 -0.1580777 0.6873205 0.247727 0.8420471 0.4791536 -0.004674375 0.9385464 0.3451216 0.3036596 0.254943 0.9180386 0.1166958 -0.9069653 -0.4047173 -0.1208308 -0.9435133 0.3085166 0.02365928 0.7714984 0.6357914 0.05086296 0.8956758 0.4417892 -0.3655095 0.9308074 7.0975e-4 -0.9017674 0.1730169 -0.3960815 0.04217892 0.3493418 -0.9360456 0.03555965 -0.975326 0.2178869 0.535794 0.7446732 -0.3979781 0.4844022 -0.556873 0.6747199 0.1165761 -0.3417238 -0.9325422 -0.2785614 0.8268396 0.4886102 0.9276247 0.08351904 -0.3640564 -0.6959891 0.6375502 0.3303469 0.5879044 0.266152 -0.7638924 -2.4425e-5 -0.9396857 -0.3420391 -0.007304608 -0.7918192 -0.6107119 0.9692105 0.04670047 -0.2417643 -0.3935973 -0.1092601 0.9127669 -0.2092288 0.4958575 0.8428218 -0.4131724 -0.4386017 -0.7980709 0.7819706 -0.1817511 0.5962287 0.7028732 0.2520252 -0.6651712 -1.31767e-6 -0.9396887 -0.342031 0.1536772 -0.5662469 0.8097826 -0.909997 0.3300173 0.2509864 -0.5537595 -0.5475186 -0.6273547 0.8375438 0.3164445 0.4454025 -0.3329954 -0.06444287 0.9407238 0.004891037 0.3381844 -0.9410672 0.6940053 0.5934516 0.4076418 -0.2014671 -0.3268366 0.9233574 0.1657953 -0.4333378 -0.8858501 0.02818459 -0.3968589 0.9174468 -0.2050736 -0.9712472 -0.1209282 -0.9997937 0.01943892 0.005876481 0.6938683 -0.07844924 0.7158159 4.26054e-5 0.3419428 -0.9397208 -0.05253595 0.8426153 -0.5359475 0.2243989 0.4702159 0.8535468 0.08898288 -0.9324221 -0.3502445 0.8433279 -0.1768612 -0.5074625 0.2791287 -0.7362061 0.6165127 0.3134213 -0.8289487 0.4632616 0.2722322 -0.7485123 0.6046643 0.08398491 0.6699284 0.7376601 0.8499291 -0.2144264 -0.4812918 -0.6338919 0.7635762 -0.1230136 -0.9879463 0.1545148 -0.00933808 -0.9058172 -0.2848247 0.3136402 -0.07567572 -0.5234123 -0.8487124 -0.004026949 0.3395652 -0.9405739 0.695352 -0.08470875 0.7136598 0.08192574 0.3047733 -0.9488948 -0.4026163 -0.9109782 -0.08954834 0.2614096 0.6734675 -0.6914524 0.4357019 -0.5994741 0.6714124 0.001902282 0.7001035 -0.7140388 0.3820071 0.9013516 0.2040486 -3.27191e-5 0.3198479 -0.9474689 0.2173303 0.692225 0.6881803 0.01932793 -0.3167038 0.9483276 0.2006239 -0.9174784 0.3434873 0.1369315 0.5916686 0.7944672 -0.2163652 -0.432778 0.8751509 2.05202e-5 -0.9396892 -0.3420297 -0.4418694 0.2901507 -0.8488605 -0.02660989 0.007967829 0.9996142 0.3085919 0.3257085 0.8936919 0.06323361 -0.9208456 -0.3847659 0.1424811 0.2606317 -0.9548666 0.2365954 0.4971714 0.8347714 -0.4136509 0.1267746 0.9015659 -0.7990205 0.1001278 -0.5929085 0.03488349 -0.7731757 0.6332318 -0.7515032 0.6187416 0.2289143 0.575318 -0.6623245 0.4799327 -0.04240787 0.07357597 0.9963876 -0.9284371 0.1762127 -0.3270376 -0.2585266 0.6521748 0.7126234 0.2986108 0.8567891 0.4204093 -0.4720001 0.7585922 0.4491703 0.8202948 -0.05565983 0.5692261 0.5158722 0.3388805 -0.7867882 0.9225739 0.1329324 -0.3621969 0.3098592 -0.2838284 0.9074298 -0.9482758 -0.2191239 0.2296904 -0.6786612 0.3467949 0.6474198 0.6578121 0.744479 0.1141677 -0.3892737 0.658586 -0.6439957 0.5117291 -0.6168138 -0.5980586 0.5592399 -0.1194164 0.82036 -0.7820861 0.002735018 0.6231644 -0.9432564 0.1568176 -0.2927038 -0.8579888 0.1587787 -0.4885126 0.5562 -0.09183919 -0.8259584 0.935859 0.151818 -0.3179925 0.5199772 0.4996832 0.6927774 0.3854725 -0.9093844 -0.1563042 0.05214393 -0.6855974 -0.7261111 0.3652144 -0.9102937 0.1948948 0.4142044 -0.8854966 0.2105481 -0.05670607 -0.334541 0.9406735 0.5712875 -0.7990899 0.1873127 -0.2792726 0.8885109 -0.3640815 -0.4881253 -0.2729953 0.8289796 -0.5694659 0.526469 0.6312995 0.008379876 0.9389469 0.3439602 -6.87276e-4 -0.939907 -0.3414299 0.005237817 -0.9155342 -0.4022061 -0.4615853 -0.3389707 -0.8197792 0.3133481 -0.940244 -0.1332445 0.234205 0.951497 0.1995036 0.6531966 -0.7444168 0.1384845 0.04830312 0.9732391 -0.2246609 -0.3468235 0.3932685 -0.8515006 0.7124013 -0.7017158 0.008898973 -0.05238473 0.993439 -0.1016598 -0.003696143 0.6197336 -0.7848036 0.1748851 -0.5171771 -0.8378204 -0.9999601 -0.008927702 6.93557e-5 -0.1533578 0.9322261 0.327774 0.057594 0.5334815 -0.8438486 -0.4938995 0.2070075 0.8445183 -0.4835189 -0.1500815 0.8623718 -0.1794587 -0.9498878 0.2559448 -0.5311906 0.1992723 0.8234847 0.9658107 -0.1151061 -0.2322937 0.9091889 -0.4012135 0.1113696 -0.3944373 -0.2466471 -0.885203 -0.5284296 0.3666292 -0.7657318 0.01270979 0.9101376 0.4141111 -0.4551411 0.2994307 -0.838563 -2.5206e-5 -0.9396909 -0.342025 5.72669e-7 -0.9396904 -0.3420262 0.05080509 -0.1642006 -0.9851177 0.5840263 0.6318705 0.5095616 0.4347137 -0.8992474 -0.04876554 -0.1812269 0.3375419 -0.9237003 0.0565645 -0.8711696 -0.4877129 0.4710332 -0.8776512 -0.08863461 1.09729e-5 -0.9396882 -0.3420327 0.3377932 -0.9412199 8.41596e-4 0.1976034 -0.979029 0.04954773 0.6327216 0.7518736 -0.1853357 -0.6652562 0.5817143 0.4680199 0.3570706 0.76644 0.5339197 0.895089 0.06225883 0.4415195 -0.9008514 0.1320564 -0.4135552 0.7117986 0.2234659 0.6658872 -0.9787364 -0.1916952 -0.07299321 -0.7916407 -2.15645e-4 0.6109869 0.634328 -0.7196182 0.2824495 -0.06040447 0.9319799 0.3574422 0.3814969 0.2333808 0.8944236 0.7807956 0.4843981 -0.3946097 -0.3582892 0.8194309 0.4473945 -0.07547104 0.9382069 -0.3377452 -0.5542938 0.8241546 0.1163083 0.402543 0.6851335 -0.6070844 2.74627e-7 -0.9396939 -0.3420169 0.1599336 -0.9241864 0.346844 -0.2807404 -0.3251097 0.9030441 0.9199491 0.1671081 -0.3546386 0.1559283 0.5994074 -0.7851096 0.04509603 0.6798159 0.7319949 -0.08977824 0.9694654 0.2282031 0.8727062 -0.4763607 0.1070711 -0.3580105 0.2786158 -0.8911799 -0.08224385 -0.7207524 -0.6882964 0.9902867 -0.1341387 0.03659379 0.1855654 -0.280025 -0.9418871 0.5899311 -0.2066417 0.7805641 -0.9577969 0.239105 -0.159543 -0.01491171 0.9400096 0.3408221 -0.8695816 -0.4915861 -0.04659497 -0.70697 0.6863603 0.1705954 0.4517062 -0.2410495 -0.8589858 0.3993251 -0.3077303 0.8636212 0.3925282 -0.2925204 0.8719825 0.5340456 -0.1345019 0.8346883 -0.1742023 0.9473943 0.2685102 -0.1118559 0.9580524 0.2638635 0.0683515 -0.3460047 0.9357397 -0.07082784 -0.5688375 -0.8193944 -0.7003138 0.2346308 -0.6741728 0.07910484 -0.9923568 -0.09471255 -0.7042989 0.6260578 -0.3346858 -0.8373512 0.2024656 -0.5077898 -0.3766915 0.8932924 0.2452191 0.2796961 0.2828291 -0.9174846 -0.2331885 0.1232131 -0.9645941 0.6309511 0.1903501 -0.7521088 3.02571e-4 0.33995 -0.9404435 -0.8811448 0.01830595 0.4724922 0.8086174 0.4231526 0.4087539 0.2426565 0.3473519 -0.9057949 0.002626419 0.9576123 0.2880481 -0.3764568 -0.03944706 -0.925594 0.6801602 0.2006263 0.7050753 -0.1931099 -0.9664661 -0.1692681 -0.4265019 -0.3990928 -0.8116778 -0.07922303 0.9845254 0.1563118 0.6954746 0.7185195 0.006688058 -0.09188872 0.8030516 0.5887823 -0.9852705 -0.08780419 0.1467405 -0.19542 0.9213116 0.3361489 -0.8326588 -0.4031235 -0.3796981 0.01985698 -0.6148311 -0.7884088 -0.9361406 -0.1218248 0.3298478 -0.6586232 -0.2838332 0.6968889 0.8305453 0.4007199 0.3868048 -0.4115455 -0.8471977 -0.3359855 0.3343024 0.9340598 0.1255952 0.3133431 0.8671691 0.3870838 0.596005 0.7717148 -0.221888 -0.001986443 0.9996263 -0.02726155 0.2029849 0.8819973 0.4252973 -0.08095407 0.4602378 -0.8840971 0.2121891 -0.265132 -0.9405747 0.1568124 0.2189158 0.9630606 -0.3670521 -0.3802154 -0.8489459 0.7928716 -0.2294242 0.5645522 2.12277e-6 -0.9396938 -0.3420168 -0.007114708 0.3747702 -0.9270904 -0.4762324 -0.05152779 -0.8778085 -0.8952446 0.05599379 -0.4420428 0.724171 -0.6889266 -0.03092998 0.9762542 -0.1830114 -0.1159071 0.693764 0.2992419 0.6550922 0.0051409 0.3484857 -0.9373 -0.04153734 -0.9793034 -0.1980895 0.2684946 0.07239294 -0.9605571 -0.3574886 0.9339076 0.004308164 0.1807835 -0.4568109 -0.871 -0.002016425 0.934825 0.3551031 -0.9727539 0.01788848 0.231149 0.7330937 -0.2807071 0.6194974 -0.9633293 0.2511036 -0.09457093 -0.3120206 -0.8924722 -0.3257862 -0.9744643 0.07748049 -0.2107511 -0.8853372 0.3931772 -0.2481728 0.2524136 0.8385432 0.4828381 0.7214722 0.3249174 -0.6114792 0.03737902 0.9186741 0.3932439 -0.6473838 0.4951136 0.5794453 -0.09783482 -0.8054308 -0.5845593 0.9393666 -0.2506022 -0.23407 0.06328123 0.8041802 -0.5910074 -0.5223443 0.290789 -0.8016223 0.550428 0.1269223 0.8251787 0.4266095 0.8874249 -0.174589 0.1872174 0.8830946 0.4302251 0.003436386 0.9436097 0.3310422 0.825951 -0.1016757 0.5544971 0.6152503 0.7664035 0.1846422 0.003981053 -0.9372431 -0.3486541 0.5259453 0.8479014 0.06666928 0.2650731 0.7158729 -0.6459584 -0.4521471 -0.1852474 0.8724943 -0.9260358 0.1674783 0.3382435 -0.526083 0.1917841 -0.8285261 0.9783753 -0.07479977 -0.1928389 -0.07987993 0.765449 0.6385195 -0.4885197 -0.8094345 -0.3258285 0.7078124 -0.2095844 -0.6745932 -0.199088 -0.9798659 -0.01506501 0.173652 -0.0566765 0.9831748 -0.2289836 0.8158618 0.5309765 0.3321903 0.9199155 -0.2083387 0.9876111 -0.1538265 0.03101086 -0.2104151 0.8800401 -0.4257405 0.8760147 -0.1856613 0.4451158 -0.3231806 0.04996252 -0.9450175 -0.599146 0.7483072 0.284711 0.456889 0.7944465 -0.4001341 0.4358861 -0.8751158 0.2101802 0.0396353 -0.8237909 -0.5655065 -0.2152192 0.8789007 0.4256926 -0.1839883 -0.9827862 0.0167219 0.04696136 -0.3693146 -0.928117 0.01605618 0.2714298 -0.9623243 0.0902819 0.9103853 0.403792 0.6079103 0.09807789 0.787925 -0.2862738 -0.3203437 0.9030101 0.1755898 -0.9253905 -0.3358878 -0.8266061 -0.06616467 -0.5588779 -0.3140276 0.7021913 0.6389946 0.2071359 -0.9194527 -0.3342176 -0.3226016 -0.8889605 -0.3250805 -0.3178889 -0.9479071 -0.02046495 -0.06150114 0.402693 0.9132667 -0.2822442 -0.3895272 0.8767023 -0.004154086 0.940992 0.3384033 -0.5359156 -0.6172675 0.5759993 0.806446 0.1952409 -0.5581449 0.002537369 -0.9396585 -0.3421047 0.9959246 0.06704419 0.06032741 0.9957743 -0.07056009 -0.05877757 0.9562749 0.1357901 -0.2590357 -0.9764096 0.2025432 0.07483577 -0.144142 -0.7470755 0.6489232 0.973199 -0.2224081 -0.05846714 0.2493892 0.9319735 0.2631171 -5.02387e-7 -0.9396929 -0.3420194 0.9379394 -0.3250308 -0.1209324 0.909345 -0.3979027 -0.1215121 -0.4678957 -0.399271 0.7884518 0.7766766 -0.5915771 -0.2163563 -0.4248324 0.674926 -0.6033178 1.63726e-5 -0.9396963 -0.3420102 0.3185139 0.7686059 -0.5547917 0.602413 -0.7955941 0.06425428 0.7758573 -0.5927101 -0.2161949 -0.002764403 0.3830187 -0.9237365 -0.5793938 0.3403375 -0.7405899 0.6174098 -0.7334569 -0.2843346 0.585507 -0.7646183 -0.2693333 0.4756616 0.2958984 -0.828366 -0.9095444 -0.1173452 0.3986967 0.4716482 -0.09161472 -0.8770146 -1.03121e-5 0.3421411 -0.9396486 0.8212484 -0.5367982 -0.1933876 0.06073206 -0.3479757 0.9355344 0.3118345 -0.894424 -0.3205696 0.3160845 -0.8919929 -0.3231709 0.001673579 0.3142322 -0.9493446 -0.5156702 -0.6671521 0.53758 -0.8734718 0.2891477 0.3917149 0.02043628 0.9237874 0.3823601 0.01828241 -0.9374907 -0.34753 -5.45401e-7 0.3421061 -0.9396614 0.8385131 0.2711337 0.4726335 0.07175183 -0.9217094 -0.381187 -0.3885008 0.2994112 -0.8714472 -0.1966357 -0.9291671 -0.3130221 -0.4385914 -0.8983448 -0.02478516 -0.4427459 -0.8910748 0.09980875 -0.3307463 -0.8776592 -0.3468735 -0.3245251 -0.248113 0.9127559 -0.1188796 0.4248927 0.8974039 0.5752432 -0.5415017 -0.6130834 -0.4693441 -0.8397625 -0.2729745 -0.9590356 0.1628503 0.2317981 -1.41699e-5 -0.9396796 -0.3420559 -0.6006822 -0.7409803 -0.3002151 0.4602076 -0.07756137 0.8844169 0.5986906 -0.30168 0.7419964 -0.2287642 0.7743233 -0.5899918 0.9774276 -0.02912241 0.209254 -0.7365018 -0.6480241 -0.1939846 0.5675047 -0.7658848 -0.3022564 0.2045507 0.9416998 0.267134 -0.8118335 -0.5440015 -0.2121056 0.259304 -0.1969426 -0.9455025 0.6623557 -0.5435947 0.5155481 -0.5922544 -0.7289308 -0.3433579 -0.9189632 -0.3690728 -0.1388946 -0.918685 -0.3695315 -0.1395147 0.2656839 0.947959 0.1754591 -0.06582248 -0.5803675 -0.8116902 0.1571058 0.9328691 0.3241499 -0.5813933 0.6640279 -0.4701585 5.42811e-5 0.3413825 -0.9399245 -0.02827394 0.8930388 0.4490905 -0.9968888 -0.07596379 -0.02103126 -0.9964182 -0.07989925 -0.0276916 0.5067601 0.7613518 -0.4043979 -0.2379264 -0.836842 -0.4930381 -0.9346417 -0.1036831 -0.3401393 -0.977069 0.2001551 0.07262361 -0.9726338 0.2143045 0.08976113 -0.001360177 -0.3358903 0.9419001 0.04485839 0.01593017 -0.9988663 -0.9069696 0.3908553 0.1569659 -0.9155266 0.3763825 0.1419408 -3.14337e-4 -0.3431642 0.9392753 0.3435315 0.3308733 -0.8789249 -0.8784487 0.4772101 0.02446699 -0.8277244 0.5230183 0.2032837 -0.001155316 0.3529365 -0.9356465 3.47279e-5 0.3415994 -0.9398456 -0.7365338 0.6477679 0.1947169 -0.6750099 0.6930359 0.2531068 0.6663004 0.5799754 -0.4686922 -0.9270151 0.1492649 -0.3440392 -0.8481591 -0.2206562 -0.4815984 0.9265586 -0.3550313 0.1242654 0.9806098 -0.04494804 0.1907462 -0.002368271 0.3457134 -0.9383372 -0.4695647 0.8297409 0.3017266 -0.4983588 0.822895 0.2729145 1.74282e-4 -0.3410372 0.9400498 0.5627732 0.8196901 -0.106745 0.1788095 0.947063 0.2666438 -0.2925422 0.8907445 0.347841 -0.2977088 0.3359692 -0.893585 -0.1575183 0.9379966 0.3087887 -0.02942091 -0.8218346 0.5689661 -2.11597e-7 0.3421381 -0.9396497 -0.1665934 -0.9523811 0.2553757 -0.07651847 0.9375134 0.3394315 0.1524626 0.936504 0.3157774 0.1950618 0.9208227 0.3376929 3.32266e-4 0.008133172 -0.9999669 -0.06272566 0.8767145 0.4769037 0.6899576 -0.05925327 0.7214205 0.2862388 -0.9506291 -0.1198823 0.2916641 0.6121438 -0.7349912 -6.3518e-5 -0.9396814 -0.3420512 0.4718564 0.827749 0.3036167 0.4390718 0.8525609 0.2834707 -0.02258843 0.9209429 0.3890426 0.9467727 0.2597048 -0.1901967 0.6496638 0.710712 0.2698621 0.6070864 0.4707813 0.6401649 2.85714e-4 0.3455424 -0.938403 0.7267503 0.6551872 0.2063096 -0.06298667 0.9315873 0.358019 0.6609706 0.7441285 -0.09690523 0.6920863 -0.4465316 0.5671208 0.8189865 0.5280702 0.2245057 -2.91149e-4 -0.3396441 0.9405539 -3.18165e-4 -0.3432188 0.9392555 0.9171191 0.37401 0.1378734 0.9196102 0.367832 0.1379007 -0.9292561 0.3416295 -0.1406148 0.7480775 -0.03658628 -0.6626021 0.9684202 0.2418553 0.0605669 0.7186698 0.6548697 0.233793 0.4236478 -0.6934887 -0.5827487 0.002703249 0.3362014 -0.9417864 -0.4825999 -0.5226559 -0.7028003 -0.02513718 0.9418765 0.3350177 0.02160835 0.9423912 0.3338142 -0.9187878 -0.08297395 -0.385933 0.177212 0.9256727 0.3342543 0.8392983 -0.265219 -0.4745916 0.1836536 0.9236837 0.3362735 -0.3668468 0.733251 0.5725088 -0.3595316 -0.003289401 -0.9331271 0.2472441 0.7944247 0.554761 -0.2109953 0.9163672 0.3402236 -0.6315064 -0.0526275 -0.7735826 -0.4152611 0.851553 0.3200246 0.1215034 -0.47768 0.8700913 0.06532526 0.9378675 0.3407887 0.05858886 0.9370597 0.3442186 0.351534 0.7115603 0.6083632 0.6086157 0.7419576 0.2812222 -0.3976193 0.5570924 0.7290727 0.02385312 -0.6500688 -0.7595009 0.01189821 0.9348959 0.3547226 0.9802365 -0.01989167 0.196827 -0.5548696 -0.7170724 0.4218139 0.4109567 0.4086397 0.8149406 -0.3213402 0.3532941 0.878592 -0.0487889 -0.9383542 -0.342215 -0.1072677 0.9348042 0.3385778 -0.0943486 0.9338194 0.3450796 -0.21085 0.943152 0.2569175 0.5432389 -0.2073969 -0.8135589 -2.26557e-6 -0.9396931 -0.3420188 -0.1923047 0.9218261 0.3365349 -0.8842356 0.4642049 0.05139279 1.81714e-6 -0.9396916 -0.3420226 0.3222867 0.8903546 0.3215588 0.08397382 -0.4129976 0.9068524 0.159459 -0.9280246 -0.3366649 0.3697847 0.8713215 0.3225804 -0.5469553 -0.2793255 0.7891876 0.5072754 0.8130311 0.2857485 0.7878798 0.615826 -0.001927852 -0.03513002 -0.3441325 0.9382637 -2.93748e-5 -0.9397001 -0.3419996 -0.03383678 0.3285583 -0.9438774 0.6028015 0.7453995 0.2846223 0.2568617 -0.8578667 0.4450696 -0.8754072 0.3277081 0.3553444 0.2910038 0.3354746 -0.8959763 -0.4097611 0.7776331 0.4768466 0.7314705 0.6414967 0.2311554 -0.1429268 0.6432249 0.7522193 -4.11447e-7 0.9396926 0.34202 -0.4247337 -0.3018194 0.8535258 -8.116e-4 0.3452098 -0.9385252 -0.9201079 0.1286716 -0.3699257 0.005307495 0.9401286 0.3407785 0.5926444 -0.199617 0.7803369 -0.2137231 0.7433385 -0.6338536 0.5844975 -0.2646099 0.767036 -0.7903409 0.2061137 -0.5769563 0.8264489 0.5241696 0.2054958 0.4453471 0.8161195 -0.3682594 0.1563137 0.03318589 -0.9871498 -0.5409956 0.3194553 -0.7779923 0.8853708 0.4397712 0.1507308 0.954773 0.2759131 0.1108173 0.9638028 0.2499748 0.09271931 -7.04086e-4 -0.9396871 -0.3420346 0.04753798 -0.9777117 -0.2044993 0.03042113 0.9050997 0.4241099 -0.8116328 -0.07898426 -0.5788038 0.7759445 -0.02671796 -0.6302348 0.1982365 0.06643128 -0.9779004 -0.2072805 0.7120722 0.6708114 -0.8648682 0.4555045 0.2109943 0.9952988 0.08885616 0.03853553 -0.5207901 0.3323848 -0.7863194 0.004254877 -0.9133238 -0.407212 -0.4676321 0.05162757 -0.8824143 -0.533685 -0.8268032 0.1776982 0.9922647 -0.1175769 -0.03983342 0.9964551 -0.07866996 -0.02980142 -0.2531539 -0.9519239 -0.1724933 -0.4867735 -0.82086 -0.2987313 0.2376447 0.6555624 -0.7167726 0.4617338 0.392256 -0.7955734 -0.006608188 0.3413627 -0.9399085 0.9572377 -0.2751069 -0.08951163 -0.08638972 0.9791281 0.1839703 -1.0181e-6 -0.9396927 -0.3420197 -2.07642e-7 0.9396927 0.3420202 -0.5898702 -0.6012016 0.5390825 -0.08488386 -0.9589013 -0.2707453 0.8088888 0.0679593 -0.584021 0.9559538 -0.2798407 -0.08855265 -0.1261947 -0.3203131 0.9388686 0.451375 0.1550436 0.8787617 0.8907694 -0.4253119 -0.1601236 0.7832587 -0.5906562 -0.1939877 0.4811424 0.7865772 -0.3870379 0.8751515 -0.4603557 -0.1489378 -0.5967468 -0.7762291 0.2033762 -0.4478442 0.2832069 0.8480738 0.1124217 -0.7290305 -0.6751857 0.7395008 0.4813167 -0.4706091 0.7961084 -0.5681068 -0.2084852 0.001182734 0.330508 -0.9438025 -0.8062502 0.2134213 -0.5517354 -0.1736623 0.6130796 -0.7706975 -0.5221924 -0.8477827 -0.09262621 -0.4538835 -0.7452052 -0.4885272 0.6911016 -0.6890524 -0.2181407 -0.2585213 0.6202765 0.7405564 0.6413151 -0.7215641 -0.2608836 0.5198554 0.2685104 -0.8109579 -0.4264048 0.5650789 -0.7063037 -0.2410706 0.5364152 0.8087915 0.010396 -0.9736396 -0.2278553 -3.23897e-6 -0.9396938 -0.3420168 0.5163806 -0.8058851 -0.2896555 -0.1148614 0.7211502 0.6831906 0.5887125 -0.7730991 -0.2360835 -0.07140791 -0.8964062 0.4374434 -0.2014642 -0.3268393 0.9233571 -0.5355269 -0.2808424 0.7964538 -0.1647076 0.9688557 0.1849051 0.6005696 -0.2761493 0.7503718 -0.3244985 -0.02319586 0.9456017 0.426025 0.302769 -0.8525454 0.8612703 0.4932455 -0.122157 0.4151551 -0.4405173 -0.7959841 0.129481 0.9670192 0.2193366 0 -0.9396926 -0.3420204 -0.7918102 0.3897716 0.4702285 0.3125281 -0.8925584 -0.3250628 -0.2288572 0.9614917 -0.1521785 -0.7621317 -0.2809054 0.5833072 4.08978e-6 -0.9396913 -0.342024 -0.3107816 -0.9172842 -0.2490067 0.4542408 -0.8574125 -0.2418867 -8.72964e-6 0.3421006 -0.9396634 0.1361091 -0.57796 -0.8046345 0.3965007 -0.8635946 -0.3114348 0.02897369 -0.9177674 -0.3960598 0.59854 -0.7957683 0.09221088 -0.3483268 0.3070074 -0.885672 -0.4436706 0.3976625 0.8031319 -0.5189853 -0.130474 0.8447667 0.04165881 0.7357447 0.6759765 -0.5837196 -0.624653 0.5187292 -0.01356941 0.9403933 0.3398182 -0.480313 -0.7340171 -0.4801232 -0.007480502 0.9405409 0.3395981 0.9902908 -0.04557019 0.13133 -0.2404864 -0.7612003 0.6022794 0.1047061 -0.2861889 0.9524351 -0.4255304 0.8934641 0.143686 0.736006 0.6562722 -0.1661384 0.07669603 0.8383736 -0.5396735 -0.2052658 0.3367494 -0.9189483 0.7286492 -0.1117929 0.6757015 -0.5534665 -0.7982397 -0.2376725 0.723633 0.6839229 0.09276133 -0.5863406 0.7781113 -0.2252721 -0.5019605 -0.8166534 -0.2848035 -0.3266875 -0.6744729 -0.6620889 0.01784348 0.2585157 -0.9658422 -0.4124698 -0.8895533 -0.1963764 -1.60727e-5 8.31223e-4 -0.9999997 -0.3165425 -0.4849647 -0.8152363 -0.001561582 -0.8733987 -0.4870033 0.6990174 -0.699134 -0.1502879 -0.9097715 -0.3974072 -0.1199309 -0.9054043 -0.4087277 -0.114825 -0.8500905 -0.3066757 0.4281311 2.78068e-7 0.9396926 0.3420203 -0.9590746 -0.2501155 -0.1327338 -0.8167553 -0.5302181 -0.227551 0.8253028 -0.1601824 0.541495 -0.480725 -0.8172896 0.3177124 -0.6537872 0.2388972 -0.7179765 0.7921124 0.3717339 0.4841197 -0.006629288 0.3417527 -0.9397665 -0.8131354 -0.1887539 0.5506204 -0.7232614 -0.6664847 -0.1808065 -0.6736795 -0.693825 -0.2544854 -0.3833308 0.6224265 -0.6823802 0.005193948 0.7115221 0.7026445 -0.01887995 0.9704604 0.2405204 -0.968631 -0.1536625 0.1952992 0.7064246 0.1900124 -0.6818061 9.82591e-4 0.8446139 -0.5353751 0.1053067 0.2681837 0.9575949 0.04752266 -0.9378707 -0.3437154 -0.5627418 0.6346066 -0.5297132 -0.2203674 -0.2426889 0.9447435 0.03079617 0.9822603 0.1849768 -0.966691 -0.2356355 -0.09992158 -0.4479784 0.2137741 -0.8681106 0.4601594 0.1062358 0.8814575 0.6466837 -0.2666333 0.7146377 0.6939677 0.07676434 -0.7159022 -0.2458288 -0.8870984 -0.3906719 -0.9875071 -0.1524487 -0.03986281 -0.1090055 -0.8120297 -0.573346 -0.9963299 -0.07946002 -0.03182762 -0.3044384 -0.02750879 0.9521348 -0.1753199 0.8813252 0.4387812 0.5690441 0.772166 0.2827517 -0.9994849 0.0202887 0.0248667 -0.9591262 0.2613834 0.1084235 -0.9662663 0.2405017 0.09213173 -0.5465139 0.785754 0.2896777 -9.04968e-7 -0.9396929 -0.3420193 -0.002651035 0.5603969 -0.82822 0.1671252 0.6300257 0.7583778 0.8143912 0.4630362 -0.3498061 -0.9955808 0.08986681 0.02725565 -0.06693524 0.1152554 0.9910781 -0.1524468 0.6976094 0.7000722 -0.07203406 0.9970997 0.0245586 0.003064692 -0.006821811 -0.9999721 0.3132412 0.8916531 0.3268558 0.6723157 0.5997446 0.433933 -0.2067615 0.7417897 0.6379638 0.4065163 -0.8084989 0.4255281 0.3723769 0.3890838 -0.8425849 0.3131229 0.7882221 -0.5297736 0.4420348 0.836862 -0.3229044 -0.1409166 0.9524086 0.2702965 0.03844451 0.9734117 0.2258137 -0.9865799 0.07431679 0.1453862 0.003636896 -0.002372145 -0.9999905 0.9170772 0.1625484 0.3640708 -0.002517461 -0.3737642 0.9275204 0.8110305 -0.2833359 0.5118109 -0.001256108 5.05025e-4 -0.9999991 0.001348972 0.001514315 -0.9999979 -0.4104741 -0.0142917 -0.9117603 0.9977502 0.0257892 -0.06188154 0.006912887 0.00209403 -0.999974 0.3463392 0.8862307 0.3076431 -0.3218957 -0.2698662 0.9074996 -0.3718897 -0.6228743 0.6882774 5.04941e-7 -0.9396924 -0.3420205 0.7755445 -0.2630828 -0.5738625 0.121819 0.7067121 -0.6969348 -7.94063e-4 0.001158893 -0.999999 0.9621394 -0.1921328 0.1933203 0.7194392 -0.4618283 -0.5187697 0.5035793 -0.857356 -0.1065297 0.3437213 0.8612673 0.3742651 -0.902072 0.4312539 0.01691663 -1.21328e-4 -0.3423662 0.9395666 0.158833 -0.338911 0.9273141 0.6013424 -0.5089315 -0.6159352 0.9668053 -0.140863 0.2131788 -0.02166444 0.009863078 -0.9997166 0.8441019 -0.4667854 -0.2638246 -0.9453855 0.3028435 -0.1205488 0.06945264 0.8618783 0.5023366 0.5007476 0.04400891 -0.8644739 -0.6287565 0.2477993 0.7370622 0.9105645 -0.1166634 0.3965627 0.9789955 0.2038816 -5.24519e-5 0.9711076 0.2386261 -0.002771198 -0.7098643 -0.7042814 -0.008970379 -0.4873395 0.8732045 0.003770232 0.8977711 -0.345098 0.2737051 0.9992889 0.03770136 -1.63185e-4 0.9985826 0.05320298 -0.001474857 -3.07346e-7 0.9396926 0.3420202 0.008981645 -0.9372351 -0.3485825 -0.84397 0.2415704 -0.4789139 -7.05312e-5 -0.9396991 -0.3420022 0.1580373 0.3331475 -0.9295359 -0.9705873 0.2407454 -0.001391351 -0.9622288 0.2722253 -0.003046333 -0.1203603 0.9376285 -0.3261384 0.2267601 0.8656531 0.4463458 -0.9962162 0.08690071 -0.001200199 -0.9935004 0.1137915 -0.00290215 -0.6083957 -0.4905462 0.6238742 0.4313765 -0.07549816 -0.8990074 0.02977305 0.9747552 0.2212821 -0.6474547 0.4171313 -0.6378118 0.6049396 -0.5610438 -0.5650467 -0.9964087 -0.08461636 -0.003131389 -0.9959138 -0.09023779 -0.003597259 0.01489448 0.4253339 0.904914 0.8370757 0.220762 0.5005682 -1.54744e-6 -0.9396924 -0.3420208 -0.9062486 -0.4227319 -0.003360152 -0.9174594 -0.3978244 -0.00205481 -0.9504684 -0.310796 -0.003933787 0.5883521 -0.5513674 -0.5914692 0.678073 0.08079618 -0.7305402 0.5260818 -0.2940418 0.7979832 -0.1713825 0.5648122 0.8072269 1.84645e-5 -0.9396987 -0.3420035 9.74858e-6 -0.9396929 -0.3420192 -0.9728251 -0.231541 2.11986e-4 -0.8404887 -0.5418276 -0.001238524 -0.7560619 -0.6535935 -0.03443902 0.5799503 0.602507 0.5483093 0.4760534 0.2957726 -0.8281858 -6.26251e-6 -0.939689 -0.3420302 -0.7220698 -0.6918107 -0.003633439 -0.2380905 -0.5217338 -0.8192111 -0.8445454 -0.5354835 -6.53419e-4 -0.8531719 -0.08252924 0.5150598 -0.02252018 0.9944214 0.1030476 0.9879488 0.05926531 -0.1429846 -0.6880004 -0.72571 5.29121e-4 0.3719556 -0.3402602 0.8636389 0.2000343 0.41514 -0.8874937 -0.5218315 -0.8530477 -0.001283049 0.004185855 -0.3550584 0.9348347 0.8071244 -0.0525819 -0.5880352 -0.517031 -0.8559643 -0.002008497 -0.2322865 -0.7575477 0.6100527 0.2733364 0.6954886 -0.6645171 -0.8598467 0.190508 -0.4736776 0.7335127 0.6725991 0.09782433 -0.3383663 -0.9409999 -0.005226731 -0.3219071 0.8891439 0.3252677 0.6330962 0.7617651 0.1374886 -0.7828806 -0.1105532 0.6122711 0.2698717 0.7721684 0.5752609 -0.4022058 0.9081957 0.1158064 0.002265036 -0.9381402 -0.346248 0.7975601 -0.6032303 -0.003318786 0.4507286 0.8792283 0.154277 -0.2847648 -0.9585972 -6.78054e-4 0.02905839 0.8888793 0.457219 0.1224026 -0.9394162 0.3201793 -0.7288493 -0.2240548 0.6469761 0.05763167 -0.9983224 -0.005567371 -0.2163027 0.9453803 -0.2438629 3.46191e-7 -0.9396924 -0.3420205 0.5325886 0.5401607 0.6515949 -0.09990447 -0.9949969 -6.13301e-4 0.5126796 -0.7001383 0.4969567 -0.08114939 -0.9966976 -0.002950489 0.3300771 -0.5269533 0.7831789 0.2182744 0.9721572 0.08524537 0.2701263 -0.9628133 -0.00473845 0.2182404 -0.9758931 -0.001959621 0.003884553 0.759162 0.6508901 0.9293998 -0.3434796 0.135047 -0.03432452 -0.3443593 0.9382102 0.1269225 -0.9919103 -0.002180397 -0.4700829 0.3565766 0.8073879 0.4571659 -0.8893726 -0.003957688 0.03510314 0.499002 0.8658896 0.3623436 -0.9320446 1.88656e-5 4.48132e-7 0.9396928 0.3420198 -0.1478831 0.9645919 0.2183873 0.09943306 -0.8086442 0.5798342 0.5187377 -0.1196876 0.8465141 -0.336114 -0.7683522 -0.5446672 0 -0.9396926 -0.3420201 0.5373266 -0.8433742 -2.84161e-4 0.7206187 -0.1077792 0.6849032 -0.2721413 -0.2054962 -0.9400587 -0.5088163 0.8591486 0.05449283 -0.7379173 -0.6368061 0.2235082 0.630753 -0.7759703 -0.004542768 0.6670939 -0.7449716 -0.001711428 0.1649275 -0.7673783 -0.6196204 9.66559e-4 0.9438247 0.3304449 -0.3029788 0.8002241 -0.5175377 0.645829 0.6979103 0.309558 0.7429538 -0.6693319 -0.00379312 -0.752179 0.6562314 0.05989295 -0.6545183 -0.6386941 0.4045686 0.0190218 0.9407274 0.33863 -0.1771417 -0.8469313 0.5013266 0.8575504 -0.5143731 -0.005262851 -0.1836413 0.3481291 -0.9192835 -0.9080781 0.162607 -0.3859444 8.19103e-6 -0.939691 -0.3420247 0.7948195 -0.6068458 -2.0021e-4 0.9444239 -0.3287046 -0.004102349 0.9039659 -0.4276043 -4.0487e-4 0.3724251 -0.5323107 0.7602269 -0.9119737 -0.3143127 -0.2636502 0.3636245 -0.8679072 -0.3383994 0.1295824 0.8469049 0.5157136 0.9590494 -0.2832365 -0.001148998 0.507418 0.2767566 -0.816047 0.2477641 -0.1356314 0.9592795 0.08307236 -0.1845309 -0.9793097 0.9193713 0.1731405 0.3532403 -0.04915678 0.9374327 -0.3446792 0.9834075 -0.1812747 -0.007007241 0 0.9396923 0.3420211 0.9924205 -0.1228592 -0.002662718 0.5126024 -0.2420277 0.8238091 0.880501 -0.2592694 0.3968595 -0.5209888 0.3238743 -0.7897316 0.5703305 -0.03771299 -0.8205491 0.4589151 -0.08008384 0.8848635 0.7144742 -0.5912461 0.3741051 -0.7314491 0.6818904 -0.002759516 0.8967285 0.442572 0.002819955 -1.97913e-6 -0.9396932 -0.3420185 -0.03032255 -0.9431257 -0.3310507 -0.9073066 0.1889242 -0.3756359 0.8480799 0.5298534 -0.003983259 0.001795768 0.770834 0.6370337 0.5375787 0.3487581 -0.7677088 0.4895838 -0.4208087 -0.7636935 -0.1147118 0.8540449 0.5073938 0.6513841 0.7587305 -0.005185842 0.1591098 -0.9665384 0.2012152 0.01238507 -0.941469 -0.3368722 -0.2654289 0.3278841 0.906664 0.7181573 -0.6534148 -0.2393726 0.2322686 -0.8989245 -0.3714647 0.7451606 0.6668846 -8.88047e-4 -0.2592048 0.02319121 -0.9655439 0.5830265 0.8124529 -5.32579e-4 -0.7878525 0.5582692 -0.2600461 0.5342295 0.8453249 0.004954397 0.6693462 -0.4581032 0.5849077 -0.03879302 0.9961671 0.07839792 -0.7272912 -0.5634222 -0.3919221 0.3258146 0.5212089 -0.7887878 -0.3084174 0.8205453 0.4812321 0.09923946 0.7535929 0.6498072 0.8427488 -0.2656819 0.4681749 0.3408094 0.9401318 0.001067936 -0.1084145 0.94927 -0.2951825 -0.1565594 0.7869173 -0.5968673 0.7054682 0.1407628 0.6946225 -0.02666765 0.2874554 -0.9574227 -1.53568e-6 -0.9396924 -0.3420205 -0.2965397 -0.2046794 -0.9328292 -0.381186 0.8882741 -0.2562547 0.447733 0.7344805 0.509974 -0.9747605 0.05645453 -0.2159972 -0.1017509 0.8765658 0.4704033 0.813683 0.5466241 0.1977931 -0.9282565 0.3490401 0.1284943 0.05580049 -0.6932597 -0.7185245 2.94726e-6 -0.939693 -0.342019 -0.8583284 -0.4986857 0.1207677 0.2729045 -0.8987107 -0.3432816 0.5145729 -0.2541794 0.8189064 0.2587028 -0.6282061 0.7337779 -0.09291487 0.5172306 -0.8507875 0.5369333 -0.751932 0.3824932 -0.4356937 -0.02737146 -0.8996787 -0.2564277 0.7373689 0.6249256 0.2472628 -0.4116771 0.8771449 -0.202095 -0.1975263 0.9592398 -0.5296723 -0.4939305 0.6895505 -0.7926059 0.2712352 0.5460836 0.9036591 0.1576967 -0.3981606 -0.5710303 0.5323732 0.6249027 0.0110954 -0.03155559 0.9994405 0.9147551 -0.3795022 0.1385682 -4.61579e-5 -0.9396904 -0.3420264 0.5502122 0.2940877 0.7815234 -0.2672775 0.9584731 0.09945899 -0.9987391 0.01905345 -0.04644596 -0.2254325 0.8163886 0.5316859 0.795476 0.5854209 -0.1565257 -0.2965045 -0.1379674 -0.9450132 0.228603 -0.9568321 -0.1794802 0.5671761 0.6961794 0.4400519 -0.03902089 0.9830538 -0.1791164 -0.7087135 -0.08254253 0.7006511 0.8152118 -0.2807623 0.5065594 0.6842233 0.4191087 -0.5968135 0.9097193 -0.1354521 -0.3925092 0.9419217 0.1762915 -0.2858406 -0.5147068 0.7927991 -0.3264147 0.4097949 0.5025465 0.7612589 4.71132e-4 0.2221923 -0.9750027 0.4052282 -0.0985555 0.9088878 -9.63505e-4 -0.9391621 -0.343473 0.1942211 0.0317378 -0.9804443 3.89852e-4 0.9406594 0.3393521 -0.5400141 0.4541171 0.7086343 -0.1989028 -0.3265358 0.9240195 0.101859 -0.5220137 -0.8468332 0.4878746 -0.8720364 0.0391277 -0.001104056 0.338983 -0.9407919 0.3593226 -0.1317339 -0.9238687 -0.8786345 -0.437686 0.1908724 0.6744976 -0.6730214 0.3034716 0.3159742 -0.8246504 0.469161 -0.7902462 0.5999588 -0.1247413 -5.05934e-6 -0.9396894 -0.3420291 0.5142163 0.8558955 0.05499601 -0.5554836 0.6308455 0.5417305 -0.6418363 -0.7210071 -0.2611419 -0.7468962 0.248461 -0.6167764 -4.33301e-4 0.3443917 -0.9388261 -0.687658 0.3346682 -0.6443009 0.1519077 0.4147533 0.8971642 -0.1098713 -0.8378055 -0.5347995 0.259384 0.2425364 -0.9348241 -0.4365648 -0.8217368 0.3662785 -0.1555026 -0.6159094 0.7723176 -0.06624299 -0.9374513 -0.3417558 0.941953 -0.1222236 0.3127076 -0.9926827 0.004205584 -0.1206783 0.3997913 -0.2976657 0.8669269 -0.002300381 -0.939308 -0.3430673 -0.09086394 -0.983291 -0.1577422 -0.9198092 -0.1125251 0.3758847 0.1735817 -0.7740353 -0.6088832 0.07067745 0.6106722 0.7887231 0.1785176 0.8876466 0.4245174 0.6677218 0.666113 -0.3323269 -0.1723757 -0.7329146 -0.6581207 -0.7419974 0.6292126 0.2313683 -0.2488495 0.9109995 0.3288676 -0.1442075 0.06753516 0.9872402 0.4143851 -0.7869567 0.4571477 0.1760589 -0.1697929 0.9696255 -0.2725647 -0.3658959 -0.8898476 -0.4287518 -0.2725031 0.8613442 0.3703166 -0.2291128 -0.9002071 -0.3604121 0.3569226 -0.8618059 0.05354529 0.01144587 -0.9984999 -0.2799936 0.4581645 -0.8436165 0.02753943 0.1155675 0.9929178 0.8197519 0.5722109 -0.02411556 -0.002816796 0.3458345 -0.9382913 0.1149588 -0.8899376 0.4413564 -0.03250777 0.9680771 -0.2485356 0.2355188 0.8746735 0.4236476 -0.08290684 -0.1096619 -0.9905053 1.7479e-5 -0.9396945 -0.342015 0.2070579 0.5032172 -0.8389872 0.8236744 0.5564357 -0.1092686 -0.1741818 0.01482731 0.9846019 0.3526096 0.05314463 -0.9342601 -0.4136001 -0.5630767 -0.7154575 0.7791252 -0.3469479 -0.5221027 -8.6145e-7 -0.939693 -0.3420191 -0.03734612 -0.03232795 0.9987794 0.1573024 0.218734 0.963022 -0.3712779 0.5055882 0.7788025 -0.07328206 0.6668877 0.7415461 0.1638818 -0.3123756 0.9357159 0.7622857 -0.3279997 0.5579755 0.1066976 -0.800722 0.5894573 0.006828725 -0.3327402 0.9429937 0.3317244 -0.3572699 0.8731078 0.5074833 -0.5314922 0.6782159 -0.001621186 0.08255916 0.9965848 5.71526e-4 -0.333917 0.9426023 -0.4588729 -0.2735759 0.8453354 -0.7937878 0.1045525 0.5991407 0.5890105 0.7919278 0.1609874 -0.8429763 -0.5056247 -0.1836695 -0.03405493 -0.83037 0.5561709 -0.7385451 0.2735545 -0.6162136 -0.9980117 0.01051694 -0.06214493 0.1105552 0.8872233 -0.4478976 0.1282318 0.9745856 -0.1836833 -0.1879609 0.9141226 0.3592361 0.6321201 -0.5327964 -0.5626298 -0.3772603 0.4601701 0.8036903 0.03072327 0.5213404 0.8527955 0.2252066 -0.8943138 -0.3866328 -0.452414 0.1466279 0.8796715 -0.8574973 0.1680744 -0.4862607 0.9233096 -0.03655683 0.3823125 1.75969e-6 -0.9396932 -0.3420186 -0.2804396 -0.0573976 0.958154 0 0.9396927 0.34202 0.6672939 0.6137329 -0.4219607 -0.8163786 -0.3624225 -0.4496399 0.7795215 -0.5522472 -0.2955831 -0.4565719 -0.7561373 0.4688266 -0.0125941 0.3823763 0.9239209 -0.2622056 -0.6797738 -0.6849496 -0.07351201 0.01894211 -0.9971145 0.1079337 -0.8775796 -0.4671235 0.3768407 -0.2988108 0.8767572 -0.9067396 0.3738161 0.1951532 0.12067 -0.9596609 -0.2539482 -0.5740557 -0.3098159 0.7579408 -0.3969612 0.84866 0.3495684 0.4066103 -0.2560546 0.8769859 -0.2172245 -0.7527711 -0.621409 -0.923958 0.3805005 0.03899931 0.354264 0.8311849 -0.4285192 0.9773025 0.2018883 0.06419479 -0.7353064 -0.6764553 0.04162532 0.684509 0.7245345 0.08060586 -0.5091385 0.4490571 -0.7342518 -0.9855142 -0.008924841 0.1693583 -0.8413181 0.3410495 0.4193674 0.1639562 -0.7128754 -0.6818556 0.3385787 0.7386963 0.5828312 -0.1915668 0.9808894 -0.03402853 0.4691593 0.2815139 -0.8370422 -0.1627445 -0.582794 -0.7961567 0.4367182 -0.373607 0.8183489 0.1033406 -0.5642426 -0.8191161 -0.5014199 -0.005070328 0.8651892 0.9483704 -0.2969368 -0.1114547 0.2210177 -0.5209115 -0.8245013 -0.348877 0.9296932 -0.1181329 -0.5177133 -0.5180379 -0.6808889 -0.009145975 0.9349992 0.354532 0.03054392 -0.5097599 0.8597744 -0.1934844 0.7336209 -0.6514323 -0.6826425 -0.2590245 0.6833049 -0.0226466 0.9372048 0.3480438 0.9575651 0.1037974 -0.2688776 -0.1703519 -0.9296985 0.3265592 0.0268712 -0.9955764 0.09003037 -0.9692019 0.2439618 0.03362083 -0.6898735 -0.6986317 -0.1897056 -0.7836719 0.3994281 0.4757264 0.2673513 0.9172211 -0.2953449 -0.3187195 -0.8905781 -0.3244819 -0.7295964 0.6827124 -0.03991025 -0.5341987 0.8453475 0.004402518 0.957892 -0.03304022 -0.2852216 -0.7231042 0.4015488 -0.562031 -0.6734183 0.7308034 0.1115081 0.2368041 0.9133873 0.3311306 2.89794e-7 0.9396926 0.3420201 -0.9746567 0.02720749 0.222045 0.2212108 -0.9325381 0.2853741 -0.1027632 0.911935 0.3972584 0.1906476 -0.9815779 -0.01258176 -0.2115625 0.8574686 0.4690297 0.1125812 0.2591654 -0.9592491 0.1764808 -0.412111 -0.8938787 0.08311617 0.8521239 0.5166979 1.95816e-5 -0.9396978 -0.342006 -0.8523375 0.3959279 0.3417043 0.9442885 0.3261647 0.04399716 -0.005789399 0.9400222 0.341064 -0.2601246 0.3322175 -0.9066238 -0.005110621 -0.9399043 -0.3413995 0.1923722 -0.9400382 -0.2816402 -0.6680758 -0.6779609 -0.3066656 -0.2978106 0.07837903 0.951402 -0.5853311 -0.7774437 -0.2301497 -0.8856066 0.4396255 0.1497682 -0.09643661 -0.8962123 -0.4330165 0.2715358 -0.7404201 0.6148548 -0.4269747 -0.4240086 -0.7986922 -0.1194526 -0.6711592 -0.7316257 -0.2113021 0.5251548 0.8243567 0.5110027 -0.856441 0.07338333 0.269329 -0.9351735 0.2300269 -0.7613897 0.1134288 -0.6382943 -0.4964579 0.7027602 0.5095662 -0.001244246 0.3541027 -0.9352058 -0.6115591 0.3716256 -0.6984912 -0.06790977 -0.7458751 -0.662615 0.1825693 0.02812135 -0.9827908 0.0538786 0.3302267 0.9423627 0.1666868 0.8795704 0.4456137 0.9161865 0.3771854 0.1354017 -0.1690833 -0.223975 -0.9598156 -0.9882604 0.01710909 -0.1518183 -0.05775773 0.9540399 0.2940609 -0.778508 0.5401009 -0.3197128 -0.3371006 0.357514 0.870946 -0.4869819 0.7598909 0.4305978 -0.8233436 0.5283387 0.2072764 -0.294105 0.9255322 0.238521 2.05297e-5 -0.939685 -0.342041 -0.2139291 0.4983426 -0.8401719 -0.07589089 0.9144388 0.3975453 -0.001399219 -0.3488278 0.9371858 0.01858812 0.6781128 0.7347227 -0.7205308 0.3894033 -0.57376 -2.13674e-7 0.9396927 0.3420199 -0.7665436 0.5484231 -0.3341301 0.3175672 0.7874474 0.528278 0.5083307 0.7246524 0.465273 0.1794722 0.3887724 0.9036846 0.8119247 0.1622207 -0.5607697 0.5413529 0.8033369 -0.2481671 0.9846219 0.0913667 -0.1489023 -0.6673899 0.7400419 -0.08323925 -0.3666356 0.8358643 -0.4085453 -0.2037653 0.939655 0.2748238 -0.2471541 0.9372277 -0.2460067 -0.2562214 0.8987219 -0.3558785 -0.6771898 -0.2537683 -0.6906631 0.009771227 0.9511291 -0.3086391 0.6995676 -0.7144559 0.01257222 0.4902445 0.137795 0.8606235 0.296958 -0.2494016 0.9217454 0.08642554 0.9083596 -0.4091619 -0.3020066 -0.3206971 0.8977446 -0.2530375 0.8681065 0.4270401 0.3975577 0.8699912 -0.2916561 -0.006553351 0.9400221 0.3410504 0.3864184 0.7709759 -0.5062382 -0.6315625 0.6027618 -0.4876549 0.6389321 0.7084734 -0.2997186 0.6139759 0.6299906 -0.4755477 0.8088456 0.4572623 -0.3697026 0.2141054 0.7745476 0.5951763 0.7197284 -0.40307 -0.5652661 0.1162436 -0.9660518 -0.230719 -0.8544908 -0.06562423 0.5153046 -0.8720133 0.4842138 -0.07162249 0.5647564 0.7552536 -0.3326292 -0.5234701 -0.4188572 -0.7419823 0.786273 0.01906263 -0.6175852 -0.713674 0.6590802 0.2372402 0.06000518 -0.9880116 -0.1422407 0.02113407 -0.7037712 -0.7101123 0.915017 0.3798901 0.1357479 0.2884728 -0.9188667 -0.2691977 -0.7912082 -0.2190521 0.5709691 -0.007092058 -0.9393173 -0.3429763 -0.2395331 -0.3870732 0.8903921 0.4317972 -0.2176997 -0.8753045 0.3892223 -0.5417698 -0.7449777 0.2323185 -0.4233499 -0.8756729 0.4490413 0.838404 0.3089346 0.01074576 0.9397208 0.3417741 0.04885542 -0.8363569 -0.5460039 -0.04392468 -0.503014 0.8631613 6.35263e-7 0.9396928 0.3420199 -0.0518158 0.8875989 0.4576933 -0.1140595 -0.5595479 -0.820912 0.5361636 -0.6869277 -0.49057 0.4309682 0.8584545 -0.2780691 -0.3761773 -0.4599565 -0.80432 -0.3687857 -0.4506805 -0.8129479 -0.1207013 0.067106 -0.9904181 0.2744498 -0.3432064 0.8982687 -0.5855746 -0.2769097 -0.7618553 -0.5332779 -0.2370901 -0.8120363 -0.4848109 -0.8219462 -0.2989364 -0.7409964 -0.08412516 -0.6662186 0.09956145 0.8034578 0.5869779 0.01334935 -0.3088068 0.951031 -0.01965492 -0.4153775 0.9094368 -0.6554992 0.1784123 -0.7338187 -0.536178 -0.6361693 -0.554799 -0.3664812 -0.9294072 -0.04351681 -0.8636099 0.2207176 -0.4532787 0.04879945 0.3491463 -0.9357967 -0.935661 -0.08136916 0.3433912 -0.286651 0.3272544 -0.9004086 -0.8185368 -0.5723084 -0.04960572 -0.004153788 -0.3622506 0.9320714 -0.1549201 0.9271739 0.3410988 -0.57055 -0.8212517 0.004265427 -0.009381949 -0.354174 0.9351325 0.3487409 0.9202372 0.177604 -0.5381076 -0.2374957 0.808725 0.8227813 -0.3805704 0.4221341 0.6969535 0.6425516 0.3184072 -0.6284751 -0.2632363 -0.7319329 0.007315814 0.9354944 0.3532657 0.07265168 -0.8185498 -0.5698229 -0.5334285 -0.8096925 -0.2446469 -0.3265897 -0.3113918 0.8923981 -0.7216163 0.4694855 -0.5087764 0.1261669 0.9391256 0.3195699 -0.771994 -0.5965816 -0.2193529 0.5160478 0.332005 -0.7895994 -0.3668379 0.9302499 0.008069276 -0.1532579 -0.9881249 0.01101297 -0.6147768 -0.7840716 -0.08533048 1.91947e-6 -0.9396926 -0.3420205 -0.06088262 0.4348452 -0.8984448 0.4365447 -0.2982557 0.8488064 -0.3963211 -0.7246521 0.5637456 -0.545696 0.6265051 -0.5565134 0.9114264 -0.3919962 -0.1250636 0.5417242 -0.2913616 0.7884436 0.6654039 0.2004679 -0.7190621 -0.1730757 -0.8556011 0.4878438 0.7233197 0.1401323 0.6761447 -0.200001 0.9776821 0.06432235 -0.005649268 0.922557 0.3858193 -0.07190257 -0.9497137 -0.3047522 -1.2447e-5 -0.9396939 -0.3420166 -0.07891601 0.03446453 0.9962854 -0.640343 -0.3541583 0.6815664 0.5918225 -0.1999765 0.7808685 -0.04184573 -0.8604851 -0.5077543 0.13262 0.9734002 0.1868261 -0.9203032 0.1903976 0.3417465 -0.8352289 0.5075778 -0.2115596 0.9809141 -0.0360673 0.1910665 -0.9063313 -0.1173893 0.4059354 1.52769e-5 -0.9396958 -0.3420116 0.7249262 -0.6485381 -0.2321217 -0.412568 0.8574323 0.3075672 0.9822722 -0.1633541 -0.09196025 2.29626e-4 0.3657933 -0.9306961 -0.338027 -0.5588264 0.7572653 0.3332366 0.7780723 0.5325006 0.1913886 -0.5393443 -0.8200476 0.7531554 0.03587698 -0.6568636 -0.1262038 0.343026 -0.9308091 0.5689857 -0.7723056 -0.2824878 0.007167994 -0.9247009 -0.380627 0.6915925 -0.6259202 0.3604496 0.4815793 -0.4474028 0.7535995 -0.4181905 0.3057914 -0.855341 0.5232183 0.1727912 0.8344973 0.3756859 -0.4975973 -0.7818292 -0.3104817 -0.7018903 0.6410548 0.9389875 0.09108418 -0.3316715 -0.2440014 -0.3545683 0.902632 -0.1684076 -0.7216002 -0.6715148 -0.07311993 0.6401798 -0.7647373 0.6486839 -0.1519466 -0.7457356 -1.2762e-6 -0.9396923 -0.3420208 -0.7886556 0.244204 -0.5642577 -0.2697201 -0.5777571 -0.7703556 0.1240724 -0.1887599 0.9741539 0.8158727 0.01411205 0.5780592 -0.3335379 -0.01477658 -0.9426208 0.2204602 0.193856 0.9559378 -0.6662721 0.502125 -0.5513185 -0.4232156 0.6012716 -0.6777618 0.9504936 0.18656 0.2485104 0.005979418 0.9356532 0.3528704 -0.3050268 -0.7430921 0.595628 -0.3616037 0.7229982 -0.5886564 -0.2791715 -0.1842716 0.9423944 0.6136357 -0.7388859 -0.2783861 0.04824596 -0.4382192 -0.8975725 0.1722072 0.8308014 0.5292577 0.2106801 0.6746945 0.7073904 0.7339262 0.6218875 0.2731453 7.64831e-7 0.9396924 0.3420204 0.8345101 -0.5501018 0.03131955 0.03795588 0.9728133 -0.2284594 0.2786585 0.8633677 -0.4206494 0.2991839 0.8961919 0.327611 -0.002246677 -0.3358578 0.9419101 0.04880928 0.3491488 -0.9357954 0.2863107 0.8138465 -0.5056481 0.3324815 0.8503741 -0.4078236 -0.7359086 -0.2160622 -0.641682 -1.04388e-4 -0.3424056 0.9395523 -0.2476531 0.3230646 -0.9133987 -0.003038406 -0.9416534 -0.3365708 0.4114717 -0.4172716 0.8102934 -0.8006321 0.01355332 0.599003 0.7668699 0.4781054 -0.4281657 0.2247456 -0.005202591 -0.9744036 0.001026272 -0.9396426 -0.3421561 0.5315256 0.3395432 -0.7760096 -0.08740043 -0.8203716 -0.565112 -0.7044516 -0.4945145 -0.5091202 9.58936e-6 -0.9396958 -0.3420113 0.7359616 0.0699653 -0.6733984 0.5251829 0.04541039 -0.8497771 -0.8473629 0.5309988 -0.00405234 0.5152751 -0.1440138 -0.8448382 0.002972066 0.9394677 0.3426246 0.6796182 0.2465498 -0.6908924 0.5588645 -0.2555437 -0.7889029 0.07945549 0.05872285 0.9951073 0.001305699 -0.9389625 -0.3440169 -0.003456413 -0.3318989 0.9433086 0.8737517 0.342192 -0.3456336 -0.8065645 -0.1845861 -0.5615886 0.2898529 0.731967 0.6166115 0.9326224 -0.1077611 0.3443877 0.1201504 -0.1834577 -0.9756573 2.33842e-7 -0.9396924 -0.3420205 -8.76367e-7 -0.9396925 -0.3420205 -0.137162 -0.3679176 -0.9196864 1.12626e-5 0.9527133 0.303871 -0.1916284 0.6996364 0.6883222 -0.07355231 -0.8703222 -0.4869593 0.946009 0.3035711 0.1136295 -0.9928739 0.1098001 0.04631918 -0.2374797 -0.600475 0.7635661 -0.01430672 -0.9393293 -0.3427181 0.8326091 0.177132 0.5247726 -0.3260362 -0.728909 -0.6019902 -0.265916 -0.8272629 -0.4948987 -0.7631703 -0.5447863 0.3475328 -0.7923609 0.3825734 0.4751862 -0.791292 -0.1042628 -0.6024834 0.1593627 0.9699469 -0.1838658 -0.3881617 0.2704921 -0.881002 -0.03199005 0.87323 0.4862571 0.4157258 -0.2997367 0.8586793 -0.990792 0.08316123 0.1068427 -0.4990759 0.6621217 -0.5590331 0.04612654 0.9977509 0.04863619 -3.11646e-4 -0.254574 0.9670532 0.5007891 0.6416671 0.5809249 0.2449555 0.4754849 0.8449324 -0.5590841 0.6771329 0.4784517 0.9993624 0.0336405 -0.01196616 0.176411 -0.7813252 -0.5986738 0.168555 -0.8723635 -0.4588803 -0.9338957 0.3252074 -0.1485906 -0.2593836 -0.7583332 0.5980392 0.457008 -0.1830563 -0.8704218 -0.5765887 -0.08860868 -0.8122155 0.04706805 0.7393597 -0.6716635 -0.02179306 0.7910211 0.6114006 -0.02272129 -0.9394433 -0.3419505 -0.2451008 0.9323268 -0.2658801 0.6656568 -0.7071821 -0.2383158 0.01532465 0.9367535 0.3496541 -0.6556671 0.7355085 0.1706694 -0.4268776 0.565351 -0.7058001 0 -0.9396926 -0.34202 -0.3286646 0.905093 0.2697892 -0.4096383 0.3301991 -0.8503911 0.9988197 -0.0199393 0.04429095 0.4958333 -0.7664552 0.4082838 0.6683648 -0.7373172 -0.09824359 0.501586 0.6757659 0.5401408 0.8447519 0.4463902 -0.2951784 0.01295465 -0.92284 -0.3849657 -0.6345821 0.6807091 -0.3659791 0.5912375 0.7332546 -0.3358211 -0.4405471 0.6527745 -0.616282 -0.826152 -0.1962608 0.5281615 -0.6901229 -0.6719896 -0.2686274 -0.3395758 0.7940649 0.504132 -7.96983e-4 -0.9396386 -0.3421679 -0.002566814 -0.7043145 -0.7098835 -0.07302194 0.9321391 -0.3546611 -0.9234433 0.3607149 0.1309094 0.1104487 -0.8863462 -0.4496571 0.9604651 0.2105309 -0.1821635 0.4500635 0.7487882 0.486579 0.3147811 0.8932526 0.3209557 -0.9575666 -0.05633211 0.2826532 0.2421462 0.07454121 0.9673721 -0.07646161 0.2223553 0.9719628 0.8399888 -0.3717767 0.3952227 -0.7259204 0.4242483 -0.5413436 -0.1392174 0.9902456 -0.005683422 -0.8977645 -0.05406379 -0.4371453 0.1522283 0.7764406 -0.6115282 0.1588369 -0.3389046 0.9273157 0.00802797 -0.935765 -0.3525328 0.01374667 -0.7441412 0.667881 0.3687336 -0.879985 0.2994359 0.01502174 -0.9115306 -0.4109578 0 -0.9396929 -0.3420194 0.1872469 0.3189142 0.929103 0.5690414 -0.7882539 -0.2341962 -0.01270246 -0.3878973 0.921615 0.5526766 0.8323929 0.040874 0.6269499 -0.1748894 0.7591756 -0.9588697 0.1908718 0.2100877 0.6261888 0.7511393 -0.2089909 0.7679466 0.1673197 -0.6182736 -0.297387 -0.9220891 0.247614 0.08495008 0.9490497 0.3034604 0.7309176 0.2685889 -0.627391 0.6570505 0.5139741 0.5514665 0.5940461 0.6227087 0.5092575 -1.29092e-6 -0.9396927 -0.34202 -0.004595041 0.9997888 0.02002823 0.9799336 -0.04779583 0.1935088 -0.8302435 0.250273 0.4980554 0.146052 0.6156143 0.7743952 -0.7583013 -0.6127299 -0.2225785 0.605574 -0.7845796 -0.1330979 0.8573698 0.03371572 -0.5135955 0.03239321 0.9455608 0.3238294 0.3344528 0.9356693 -0.112536 0.04007017 0.3490613 -0.9362428 -0.5450216 0.8383446 -0.0113908 -0.3904649 0.8648431 0.3155686 -0.7769049 -0.6021751 0.1838591 0.001148223 0.3459784 -0.9382418 -0.1822221 -0.795419 -0.578017 0.003069579 0.9403827 0.3401045 -6.73256e-7 -0.939688 -0.342033 -0.2354442 -0.9604156 -0.1488892 -0.4149451 0.1131548 0.9027826 -0.04673647 -0.3388086 0.9396939 0.6449376 -0.4233379 0.6362707 -0.2653563 -0.9634619 0.03643065 2.95739e-5 -0.3419336 0.939724 -0.08936613 -0.06369918 0.9939597 0.06295591 -0.2605476 -0.9634063 -0.1605435 -0.2798913 0.9465129 0.3906786 -0.7452267 0.5403771 -0.9631242 -0.002901792 0.2690419 -0.2194952 0.002872765 -0.9756093 -0.2892475 -0.8166407 -0.4994335 0.9818355 0.1681 -0.08798474 0.5060818 -0.4376994 -0.7431692 -0.02739387 -0.8480807 -0.5291586 0.3599108 -0.02735292 0.9325857 -0.8499377 0.1063249 0.5160436 -0.9874413 -0.1328722 -0.08546692 0.02456486 -0.8577926 0.5134087 -0.5069305 0.7119985 0.4858803 -0.05422663 0.8877521 0.4571167 -0.923177 -0.07824599 0.3763268 2.15067e-6 -0.9396924 -0.3420205 -0.6715558 0.6958816 0.2544833 -0.7146129 0.6572087 0.2395939 0.4839384 -0.04367285 -0.8740116 -0.6610639 0.7394621 -0.1272411 -0.700453 -0.1774855 0.6912775 0.02509617 -0.9311857 -0.3636803 -0.976918 0.169599 -0.1298747 -0.9217214 -0.2930811 0.2540339 -0.3673628 0.8529049 0.3709418 0.4932161 0.3489843 -0.7968361 0.3556061 -0.2868404 0.8895319 -6.28705e-6 -0.9396896 -0.3420286 0.03356462 -0.7161304 -0.697159 0.07451671 0.6875975 0.7222582 1.07911e-4 0.9397102 0.3419716 0.5694866 0.6764072 0.4670744 0.5738047 -0.7572669 0.3119213 -0.3521804 0.02374809 -0.9356308 -0.7666176 0.6012634 0.2253436 -0.3912577 0.8651291 0.3137978 -0.579761 -0.698496 0.4195002 -0.001225352 0.3510915 -0.9363404 0.01567167 0.5535741 -0.8326525 -0.9678159 0.07361233 -0.2406526 0.6428269 0.7195315 0.2627698 -0.01872807 -0.3978852 0.9172441 -0.3045058 -0.08141678 0.9490245 -0.2396601 0.9412326 0.2380008 0.1843553 0.8552756 -0.4842692 -0.2666401 0.9627251 0.04542803 -0.168798 -0.5802166 -0.7967785 -0.006137728 0.09033423 0.9958925 -0.7357705 -0.3371798 -0.5873257 -0.5508475 -0.8154093 0.1779743 -0.6233301 0.2789784 -0.7305004 -0.8856881 -0.2383287 -0.3984419 -0.1248475 0.7639612 0.633069 -0.7470772 0.221221 -0.6268468 0.7043104 -0.6278544 0.3312788 0.7067652 0.126357 0.6960725 0.09448915 0.7961853 0.5976293 0.4291105 0.5914244 -0.6827016 -0.1598445 0.5351445 -0.8295 -0.2958332 0.1380215 -0.9452157 1.95319e-5 -0.9396877 -0.3420338 0.008442759 0.9397326 0.341806 0.8715495 -0.01910048 -0.4899355 -0.2653326 0.1414429 0.9537257 0.7344228 0.2706611 0.6223871 0.6794283 0.2788653 -0.6786835 0.004342794 0.9382419 0.3459526 -0.7272728 0.644829 0.2350955 0.273187 0.8345178 -0.4784861 1.68198e-7 0.9396925 0.3420206 0.4762179 -0.8160597 -0.3275104 0.6173804 0.2894287 -0.7314865 -0.2283221 -0.9153454 -0.3316804 -0.03874021 -0.8805314 0.472402 0.09534001 -0.2891452 0.9525257 0.06447511 -0.738592 -0.6710626 0.233803 0.9247229 -0.3003728 -0.986072 -0.02132809 0.1649463 0.05916917 0.9706426 0.233135 -0.08343791 0.9563092 0.2801976 -0.4456583 0.8420457 0.3038876 -0.5489923 -0.02691239 0.835394 0.9371808 0.3377856 -0.08713883 -0.00410062 0.3553926 -0.934708 -0.2824465 0.8397544 0.4637203 -0.141669 -0.9473301 0.2872207 -0.389351 -0.05524593 0.9194312 -0.6470917 0.4324319 0.6279132 -0.3619944 0.874146 0.3237726 -0.4818152 -0.3809028 0.789156 0.07552683 -0.7473008 0.6601797 0.7612116 0.4367603 -0.4793719 0.03318333 0.9090023 0.415468 -0.7759597 0.06182247 -0.6277456 -0.2266131 -0.3754611 0.8987078 0.1343024 -0.6312566 0.7638573 -3.13653e-4 -0.3451479 0.9385483 -0.3175328 0.7518257 0.5778677 -0.7175233 0.6880499 0.1083867 0.6206373 -0.6860663 0.3796343 0.4967518 0.341792 -0.7977567 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 11 3 12 4 13 4 14 4 15 5 16 5 17 5 18 6 19 6 20 6 21 7 22 7 23 7 24 8 25 8 26 8 27 9 28 9 29 9 30 10 31 10 32 10 33 11 34 11 35 11 36 12 37 12 38 12 31 13 30 13 39 13 40 14 41 14 42 14 43 15 44 15 45 15 46 16 47 16 48 16 27 17 49 17 28 17 50 18 51 18 52 18 53 19 54 19 55 19 56 20 57 20 58 20 59 21 60 21 61 21 62 22 63 22 64 22 65 23 66 23 67 23 68 24 69 24 70 24 71 25 72 25 73 25 60 26 59 26 74 26 75 27 76 27 77 27 78 28 79 28 80 28 81 29 82 29 83 29 84 30 85 30 86 30 87 31 60 31 74 31 88 32 89 32 90 32 91 33 92 33 93 33 94 34 95 34 96 34 77 35 97 35 98 35 99 36 100 36 101 36 60 37 87 37 102 37 103 38 104 38 105 38 106 39 107 39 108 39 102 40 87 40 109 40 110 41 111 41 112 41 113 42 114 42 115 42 116 43 117 43 118 43 35 44 119 44 120 44 109 45 32 45 102 45 121 46 122 46 123 46 102 47 32 47 31 47 120 48 124 48 125 48 126 49 127 49 128 49 129 50 130 50 131 50 132 51 133 51 134 51 135 52 136 52 137 52 138 53 139 53 140 53 61 54 141 54 142 54 143 55 144 55 145 55 146 56 147 56 148 56 148 57 149 57 150 57 151 58 152 58 153 58 154 59 51 59 50 59 155 60 156 60 157 60 158 61 159 61 160 61 161 62 162 62 163 62 164 63 165 63 166 63 167 64 168 64 169 64 170 65 171 65 172 65 173 66 174 66 175 66 176 67 47 67 46 67 61 68 142 68 59 68 177 69 178 69 179 69 180 70 181 70 182 70 183 71 184 71 185 71 186 72 187 72 188 72 189 73 190 73 191 73 192 74 193 74 194 74 195 75 196 75 197 75 198 76 199 76 200 76 201 77 202 77 203 77 204 78 205 78 206 78 83 79 207 79 208 79 6 80 8 80 209 80 210 81 211 81 212 81 213 82 214 82 110 82 31 83 39 83 215 83 107 84 106 84 216 84 217 85 218 85 219 85 220 86 221 86 222 86 223 87 224 87 225 87 226 88 227 88 228 88 229 89 230 89 231 89 24 90 232 90 233 90 234 91 235 91 236 91 215 92 141 92 237 92 0 93 238 93 239 93 215 94 240 94 141 94 241 95 242 95 243 95 244 96 245 96 246 96 112 97 247 97 248 97 249 98 250 98 251 98 252 99 253 99 254 99 255 100 256 100 257 100 258 101 259 101 260 101 261 102 262 102 263 102 264 103 265 103 266 103 267 104 268 104 269 104 270 105 199 105 271 105 141 106 61 106 237 106 272 107 273 107 237 107 237 108 273 108 31 108 274 109 275 109 276 109 237 110 31 110 215 110 277 111 20 111 278 111 60 112 102 112 279 112 279 113 102 113 280 113 281 114 282 114 283 114 284 115 285 115 286 115 287 116 288 116 289 116 290 117 291 117 292 117 293 118 294 118 295 118 227 119 296 119 297 119 298 120 138 120 194 120 299 121 300 121 301 121 302 122 303 122 304 122 305 123 306 123 307 123 308 124 309 124 310 124 311 125 312 125 313 125 314 126 315 126 316 126 52 127 317 127 318 127 319 128 320 128 283 128 321 129 322 129 323 129 324 130 325 130 293 130 324 131 293 131 295 131 287 132 326 132 288 132 327 133 276 133 328 133 329 134 330 134 331 134 112 135 332 135 96 135 333 136 334 136 16 136 33 137 335 137 336 137 337 138 338 138 339 138 111 139 340 139 341 139 203 140 342 140 343 140 344 141 345 141 176 141 346 142 347 142 330 142 348 143 349 143 350 143 351 144 352 144 353 144 354 145 355 145 356 145 20 146 357 146 358 146 359 147 360 147 361 147 362 148 363 148 364 148 365 149 366 149 367 149 23 150 368 150 369 150 370 151 371 151 372 151 373 152 371 152 374 152 375 153 376 153 377 153 378 154 379 154 380 154 381 155 382 155 383 155 284 156 384 156 385 156 386 157 387 157 388 157 216 158 264 158 389 158 390 159 6 159 391 159 173 160 392 160 174 160 393 161 394 161 395 161 396 162 397 162 249 162 398 163 393 163 399 163 400 164 401 164 402 164 403 165 404 165 405 165 406 166 407 166 408 166 409 167 410 167 411 167 412 168 413 168 414 168 415 169 416 169 417 169 418 170 419 170 420 170 421 171 422 171 423 171 424 172 425 172 426 172 427 173 428 173 429 173 430 174 431 174 432 174 433 175 434 175 435 175 436 176 437 176 438 176 439 177 20 177 440 177 441 178 232 178 442 178 443 179 444 179 95 179 445 180 111 180 110 180 112 181 186 181 188 181 446 182 447 182 448 182 294 183 449 183 450 183 451 184 225 184 224 184 162 185 452 185 453 185 454 186 455 186 456 186 457 187 454 187 458 187 294 188 293 188 449 188 459 189 460 189 461 189 462 190 463 190 464 190 465 191 466 191 467 191 468 192 469 192 470 192 471 193 472 193 125 193 473 194 282 194 474 194 475 195 273 195 476 195 477 196 478 196 479 196 480 197 369 197 481 197 482 198 483 198 484 198 485 199 486 199 487 199 488 200 489 200 490 200 54 201 491 201 492 201 234 202 376 202 235 202 493 203 494 203 495 203 496 204 497 204 498 204 185 205 499 205 500 205 501 206 502 206 151 206 282 207 473 207 283 207 503 208 504 208 466 208 505 209 506 209 507 209 508 210 509 210 510 210 511 211 512 211 513 211 514 212 515 212 65 212 33 213 516 213 335 213 319 214 473 214 517 214 293 215 518 215 441 215 519 216 520 216 521 216 310 217 522 217 523 217 524 218 525 218 526 218 527 219 528 219 529 219 530 220 396 220 531 220 532 221 446 221 533 221 534 222 535 222 536 222 449 223 515 223 537 223 537 224 515 224 538 224 537 225 538 225 449 225 539 226 540 226 541 226 542 227 543 227 486 227 539 228 541 228 544 228 433 229 230 229 99 229 529 230 528 230 140 230 545 231 546 231 547 231 227 232 548 232 296 232 549 233 550 233 551 233 450 234 449 234 538 234 552 235 553 235 554 235 555 236 227 236 556 236 557 237 224 237 223 237 558 238 559 238 560 238 561 239 562 239 563 239 564 240 565 240 566 240 567 241 568 241 569 241 570 242 569 242 571 242 129 243 131 243 176 243 550 244 549 244 572 244 573 245 574 245 575 245 576 246 577 246 571 246 441 247 198 247 578 247 579 248 580 248 581 248 184 249 582 249 499 249 583 250 584 250 585 250 586 251 587 251 588 251 577 252 570 252 571 252 0 253 2 253 238 253 589 254 590 254 165 254 591 255 150 255 251 255 592 256 593 256 594 256 211 257 96 257 212 257 68 258 595 258 108 258 596 259 258 259 597 259 325 260 21 260 598 260 599 261 519 261 521 261 600 262 601 262 602 262 603 263 604 263 605 263 606 264 597 264 258 264 309 265 607 265 522 265 608 266 609 266 610 266 159 267 292 267 291 267 345 268 611 268 612 268 171 269 613 269 614 269 452 270 615 270 453 270 616 271 617 271 618 271 393 272 395 272 619 272 52 273 620 273 621 273 622 274 623 274 509 274 170 275 263 275 171 275 16 276 624 276 625 276 626 277 627 277 628 277 629 278 465 278 630 278 631 279 632 279 241 279 580 280 633 280 606 280 634 281 466 281 635 281 636 282 112 282 248 282 637 283 638 283 639 283 269 284 640 284 144 284 641 285 642 285 643 285 644 286 490 286 645 286 567 287 569 287 570 287 249 288 149 288 401 288 646 289 268 289 267 289 249 290 647 290 372 290 648 291 587 291 361 291 577 292 576 292 594 292 577 293 594 293 321 293 649 294 85 294 254 294 650 295 651 295 510 295 652 296 653 296 654 296 191 297 655 297 261 297 656 298 657 298 658 298 85 299 24 299 252 299 581 300 580 300 659 300 441 301 442 301 198 301 660 302 533 302 661 302 138 303 140 303 528 303 420 304 662 304 21 304 659 305 580 305 606 305 663 306 664 306 415 306 608 307 610 307 665 307 117 308 666 308 667 308 668 309 669 309 670 309 258 310 596 310 671 310 672 311 548 311 673 311 674 312 675 312 676 312 20 313 19 313 440 313 677 314 678 314 679 314 680 315 137 315 136 315 681 316 682 316 554 316 41 317 683 317 684 317 685 318 686 318 128 318 633 319 597 319 606 319 687 320 688 320 689 320 674 321 690 321 691 321 671 322 321 322 594 322 424 323 692 323 425 323 64 324 658 324 693 324 596 325 321 325 671 325 331 326 694 326 695 326 101 327 249 327 397 327 696 328 697 328 698 328 376 329 699 329 700 329 79 330 701 330 80 330 702 331 703 331 704 331 705 332 706 332 707 332 579 333 581 333 708 333 709 334 710 334 708 334 708 335 710 335 579 335 711 336 119 336 712 336 713 337 714 337 715 337 716 338 717 338 63 338 718 339 719 339 655 339 104 340 720 340 422 340 721 341 722 341 723 341 0 342 239 342 35 342 724 343 725 343 726 343 175 344 174 344 727 344 728 345 590 345 638 345 568 346 567 346 710 346 729 347 730 347 589 347 731 348 732 348 733 348 734 349 713 349 735 349 736 350 737 350 445 350 738 351 169 351 739 351 568 352 710 352 709 352 38 353 740 353 133 353 7 354 741 354 742 354 743 355 707 355 744 355 745 356 746 356 747 356 748 357 749 357 750 357 264 358 266 358 751 358 162 359 453 359 163 359 752 360 753 360 754 360 755 361 756 361 301 361 757 362 758 362 132 362 754 363 55 363 759 363 760 364 761 364 762 364 253 365 763 365 764 365 765 366 766 366 661 366 767 367 768 367 769 367 509 368 329 368 770 368 771 369 128 369 772 369 773 370 437 370 436 370 567 371 774 371 710 371 775 372 776 372 777 372 297 373 551 373 572 373 778 374 779 374 780 374 781 375 782 375 783 375 784 376 108 376 107 376 771 377 785 377 128 377 577 378 132 378 134 378 753 379 311 379 754 379 192 380 786 380 787 380 627 381 788 381 789 381 790 382 791 382 792 382 200 383 793 383 494 383 565 384 794 384 566 384 795 385 796 385 797 385 772 386 128 386 798 386 798 387 128 387 686 387 799 388 800 388 801 388 755 389 311 389 753 389 323 390 757 390 577 390 802 391 803 391 804 391 433 392 805 392 230 392 806 393 616 393 618 393 639 394 807 394 808 394 193 395 809 395 810 395 301 396 756 396 798 396 301 397 798 397 299 397 700 398 699 398 236 398 811 399 409 399 411 399 812 400 813 400 814 400 301 401 311 401 755 401 815 402 816 402 817 402 489 403 818 403 490 403 345 404 344 404 819 404 238 405 820 405 821 405 173 406 175 406 822 406 347 407 823 407 824 407 825 408 826 408 827 408 675 409 828 409 829 409 299 410 798 410 830 410 364 411 831 411 832 411 833 412 537 412 293 412 830 413 798 413 686 413 834 414 835 414 836 414 837 415 549 415 838 415 839 416 785 416 771 416 495 417 494 417 793 417 840 418 841 418 711 418 842 419 843 419 844 419 845 420 846 420 839 420 847 421 342 421 848 421 839 422 846 422 849 422 850 423 851 423 852 423 853 424 854 424 72 424 616 425 855 425 617 425 728 426 166 426 590 426 856 427 344 427 176 427 839 428 849 428 785 428 857 429 858 429 394 429 859 430 860 430 861 430 862 431 863 431 864 431 277 432 599 432 865 432 866 433 867 433 868 433 125 434 472 434 869 434 308 435 310 435 523 435 101 436 727 436 870 436 4 437 871 437 5 437 862 438 846 438 863 438 872 439 873 439 874 439 863 440 846 440 845 440 875 441 46 441 48 441 259 442 876 442 260 442 441 443 140 443 139 443 877 444 27 444 29 444 864 445 863 445 878 445 864 446 878 446 879 446 855 447 880 447 881 447 322 448 52 448 318 448 882 449 883 449 884 449 885 450 884 450 752 450 886 451 887 451 773 451 888 452 889 452 890 452 891 453 892 453 893 453 281 454 474 454 282 454 579 455 894 455 580 455 895 456 896 456 897 456 883 457 882 457 879 457 883 458 879 458 878 458 898 459 507 459 899 459 875 460 207 460 900 460 271 461 25 461 24 461 315 462 901 462 653 462 884 463 885 463 882 463 487 464 902 464 485 464 794 465 903 465 44 465 904 466 905 466 906 466 752 467 754 467 885 467 907 468 908 468 806 468 909 469 910 469 354 469 911 470 912 470 913 470 914 471 849 471 846 471 915 472 916 472 739 472 254 473 253 473 481 473 917 474 918 474 919 474 920 475 921 475 922 475 923 476 924 476 925 476 926 477 647 477 927 477 912 478 911 478 928 478 929 479 930 479 931 479 628 480 932 480 626 480 157 481 230 481 933 481 934 482 850 482 852 482 935 483 936 483 937 483 938 484 939 484 348 484 384 485 940 485 941 485 176 486 942 486 129 486 629 487 598 487 537 487 943 488 928 488 338 488 944 489 945 489 946 489 924 490 947 490 93 490 948 491 949 491 950 491 951 492 952 492 562 492 911 493 913 493 953 493 486 494 543 494 954 494 955 495 609 495 956 495 957 496 805 496 433 496 355 497 958 497 959 497 934 498 342 498 960 498 687 499 961 499 962 499 963 500 964 500 717 500 965 501 966 501 913 501 966 502 953 502 913 502 376 503 967 503 377 503 40 504 42 504 968 504 893 505 969 505 970 505 610 506 971 506 932 506 679 507 947 507 924 507 972 508 973 508 974 508 975 509 587 509 976 509 977 510 625 510 978 510 479 511 94 511 211 511 253 512 764 512 481 512 979 513 20 513 358 513 980 514 981 514 982 514 983 515 984 515 985 515 986 516 78 516 80 516 987 517 744 517 988 517 692 518 989 518 990 518 991 519 74 519 992 519 993 520 341 520 340 520 984 521 983 521 994 521 467 522 937 522 936 522 590 523 807 523 639 523 836 524 444 524 443 524 45 525 995 525 765 525 996 526 994 526 997 526 998 527 376 527 999 527 1000 528 1001 528 1002 528 268 529 444 529 1003 529 6 530 1004 530 7 530 396 531 1005 531 397 531 79 532 1006 532 701 532 436 533 1007 533 1008 533 112 534 188 534 332 534 996 535 997 535 966 535 268 536 1003 536 1009 536 877 537 1010 537 27 537 1011 538 984 538 1012 538 996 539 966 539 965 539 269 540 1013 540 319 540 1014 541 1015 541 849 541 931 542 1016 542 678 542 1017 543 1018 543 1019 543 1020 544 1021 544 985 544 85 545 252 545 254 545 301 546 308 546 311 546 1022 547 1023 547 1024 547 746 548 854 548 853 548 747 549 746 549 1025 549 602 550 509 550 600 550 760 551 386 551 1026 551 1021 552 983 552 985 552 1027 553 431 553 1028 553 930 554 1029 554 1016 554 1020 555 1030 555 338 555 1031 556 1032 556 688 556 774 557 1033 557 1034 557 1035 558 12 558 14 558 881 559 203 559 305 559 338 560 1030 560 943 560 851 561 1036 561 1037 561 934 562 1038 562 1039 562 1040 563 1041 563 1042 563 31 564 475 564 102 564 1028 565 431 565 430 565 1043 566 667 566 135 566 1020 567 338 567 1021 567 1044 568 469 568 1045 568 789 569 681 569 554 569 1046 570 454 570 1047 570 1048 571 219 571 1049 571 112 572 111 572 341 572 384 573 941 573 385 573 1050 574 522 574 1051 574 2 575 1052 575 1053 575 1054 576 115 576 352 576 1055 577 435 577 434 577 1051 578 522 578 1012 578 1051 579 1012 579 1056 579 934 580 852 580 718 580 982 581 1057 581 382 581 1056 582 1012 582 996 582 828 583 1058 583 1059 583 984 584 994 584 996 584 254 585 481 585 369 585 1030 586 1060 586 686 586 984 587 996 587 1012 587 1061 588 994 588 983 588 359 589 1062 589 121 589 912 590 928 590 943 590 912 591 943 591 1063 591 1064 592 1065 592 1066 592 943 593 1067 593 1063 593 1068 594 355 594 955 594 1069 595 1045 595 1070 595 462 596 269 596 1071 596 1072 597 796 597 1073 597 312 598 1074 598 1075 598 1067 599 1076 599 1063 599 415 600 664 600 1077 600 1078 601 640 601 269 601 957 602 1079 602 1080 602 82 603 736 603 1081 603 1076 604 1082 604 1063 604 1083 605 767 605 437 605 1084 606 990 606 1085 606 1082 607 1076 607 1086 607 822 608 175 608 1087 608 319 609 33 609 213 609 639 610 808 610 398 610 1088 611 762 611 696 611 1089 612 1090 612 1075 612 1089 613 1075 613 1091 613 311 614 313 614 754 614 1092 615 124 615 120 615 570 616 1093 616 567 616 1091 617 1075 617 1074 617 1094 618 1095 618 1096 618 1091 619 1074 619 1050 619 1097 620 1098 620 1099 620 354 621 107 621 216 621 1050 622 1074 622 522 622 1100 623 938 623 1101 623 1102 624 1103 624 1104 624 1105 625 1106 625 1086 625 1086 626 1106 626 1107 626 1108 627 1109 627 855 627 916 628 1110 628 1111 628 1112 629 1113 629 1114 629 1115 630 914 630 846 630 1086 631 1107 631 1082 631 1116 632 1117 632 1118 632 476 633 946 633 945 633 1119 634 1120 634 1121 634 376 635 1122 635 1123 635 1106 636 1105 636 1124 636 389 637 264 637 1077 637 228 638 1125 638 1100 638 1106 639 1124 639 1126 639 1127 640 328 640 1128 640 1129 641 1066 641 1130 641 1124 642 1131 642 1126 642 736 643 445 643 1132 643 748 644 1133 644 749 644 1130 645 1066 645 1134 645 1135 646 176 646 875 646 1136 647 1137 647 1138 647 1139 648 832 648 428 648 1140 649 202 649 738 649 386 650 388 650 1026 650 1141 651 1139 651 427 651 1142 652 1143 652 995 652 269 653 81 653 83 653 1144 654 139 654 138 654 1145 655 664 655 1146 655 989 656 822 656 990 656 1147 657 351 657 353 657 373 658 1148 658 1054 658 1106 659 1149 659 1107 659 872 660 874 660 1150 660 1151 661 285 661 781 661 453 662 104 662 103 662 1120 663 505 663 1152 663 1153 664 1154 664 1155 664 376 665 615 665 452 665 917 666 1156 666 918 666 1157 667 1158 667 634 667 1159 668 802 668 252 668 1160 669 1161 669 1162 669 1161 670 1163 670 1164 670 204 671 527 671 529 671 622 672 509 672 1165 672 1166 673 677 673 901 673 986 674 616 674 806 674 89 675 1008 675 90 675 705 676 792 676 706 676 789 677 1167 677 1168 677 1169 678 1170 678 1171 678 249 679 1037 679 647 679 319 680 1013 680 1172 680 1173 681 729 681 1174 681 1175 682 1176 682 1177 682 1178 683 664 683 663 683 847 684 848 684 1179 684 1180 685 1181 685 1169 685 596 686 547 686 1182 686 1169 687 1181 687 1170 687 530 688 1183 688 1184 688 1185 689 1064 689 1129 689 1186 690 370 690 1187 690 1188 691 1189 691 894 691 1190 692 982 692 1191 692 334 693 1192 693 624 693 1087 694 155 694 326 694 664 695 1178 695 1193 695 1029 696 1194 696 1195 696 1196 697 1197 697 1198 697 34 698 611 698 35 698 1093 699 1199 699 567 699 265 700 1200 700 1201 700 387 701 146 701 388 701 1202 702 1203 702 1197 702 1100 703 1125 703 572 703 162 704 376 704 452 704 1202 705 1204 705 1203 705 636 706 143 706 112 706 670 707 1205 707 1206 707 436 708 1207 708 773 708 1050 709 1204 709 1091 709 1208 710 306 710 1209 710 133 711 683 711 41 711 137 712 1025 712 71 712 62 713 1210 713 63 713 1211 714 1212 714 1213 714 650 715 623 715 622 715 773 716 1207 716 886 716 1214 717 219 717 1215 717 729 718 394 718 730 718 332 719 1216 719 96 719 1217 720 983 720 1021 720 1178 721 1218 721 637 721 810 722 1219 722 1220 722 1221 723 760 723 762 723 39 724 97 724 215 724 1129 725 1064 725 1066 725 1204 726 1202 726 1091 726 103 727 105 727 1222 727 625 728 624 728 978 728 1094 729 1096 729 1223 729 797 730 1224 730 1225 730 1226 731 1080 731 1079 731 1227 732 229 732 1228 732 982 733 1229 733 1057 733 1149 734 1106 734 1230 734 990 735 822 735 1087 735 153 736 152 736 1231 736 161 737 163 737 1232 737 502 738 1233 738 152 738 707 739 706 739 1035 739 1197 740 1196 740 1202 740 1202 741 1196 741 1234 741 1220 742 844 742 843 742 204 743 441 743 172 743 1202 744 1234 744 1091 744 1091 745 1234 745 1089 745 1235 746 966 746 997 746 821 747 820 747 1236 747 113 748 115 748 1237 748 1238 749 73 749 116 749 1150 750 860 750 859 750 1106 751 1126 751 1239 751 1106 752 1239 752 1230 752 836 753 443 753 477 753 1230 754 1239 754 1162 754 1162 755 1239 755 1160 755 1240 756 1005 756 1241 756 1242 757 665 757 1243 757 157 758 156 758 1244 758 427 759 429 759 1245 759 156 760 1246 760 1244 760 906 761 603 761 895 761 1247 762 1148 762 373 762 25 763 271 763 1248 763 1249 764 507 764 898 764 879 765 1250 765 1251 765 300 766 985 766 984 766 356 767 107 767 354 767 1252 768 122 768 1253 768 856 769 176 769 1135 769 898 770 1254 770 1249 770 1255 771 1256 771 1257 771 210 772 1258 772 187 772 1253 773 122 773 121 773 577 774 134 774 1259 774 323 775 318 775 757 775 976 776 587 776 648 776 813 777 920 777 1260 777 1261 778 4 778 1207 778 1245 779 429 779 1262 779 659 780 1263 780 1264 780 274 781 1265 781 1266 781 1010 782 49 782 27 782 1161 783 1160 783 1163 783 1267 784 960 784 1036 784 1268 785 153 785 867 785 857 786 92 786 1269 786 1270 787 1271 787 195 787 873 788 1272 788 1273 788 1274 789 591 789 13 789 1181 790 1180 790 1275 790 1181 791 1275 791 1198 791 75 792 59 792 142 792 1198 793 1275 793 1196 793 1196 794 1275 794 1276 794 1015 795 1277 795 785 795 1278 796 655 796 719 796 1279 797 1280 797 126 797 1196 798 1276 798 1281 798 1196 799 1281 799 1234 799 1017 800 433 800 1018 800 1004 801 741 801 7 801 1214 802 1098 802 219 802 1282 803 676 803 430 803 73 804 743 804 116 804 1239 805 1283 805 1160 805 1160 806 1283 806 1284 806 269 807 144 807 143 807 944 808 1177 808 468 808 1160 809 1284 809 1163 809 1285 810 1286 810 750 810 704 811 703 811 1287 811 1177 812 1288 812 468 812 1163 813 1289 813 1164 813 866 814 1134 814 1268 814 785 815 126 815 128 815 1164 816 1289 816 1171 816 343 817 1290 817 203 817 1291 818 513 818 1292 818 1164 819 1171 819 1170 819 1293 820 1294 820 1188 820 964 821 1295 821 1059 821 1102 822 477 822 210 822 477 823 443 823 478 823 269 824 422 824 81 824 552 825 1183 825 1296 825 656 826 658 826 1297 826 1298 827 1098 827 1097 827 868 828 867 828 632 828 1225 829 1097 829 1118 829 1299 830 1300 830 1301 830 1146 831 1193 831 1302 831 1055 832 434 832 1303 832 1304 833 1305 833 1306 833 506 834 1307 834 507 834 1308 835 1309 835 1310 835 493 836 893 836 970 836 73 837 72 837 854 837 1311 838 654 838 1312 838 697 839 1313 839 1314 839 1206 840 1205 840 1315 840 10 841 1316 841 1317 841 1318 842 1046 842 1047 842 1242 843 1243 843 197 843 1187 844 1319 844 1186 844 810 845 1320 845 1321 845 1322 846 1323 846 363 846 1324 847 1325 847 1326 847 982 848 381 848 383 848 1205 849 1308 849 1315 849 498 850 902 850 496 850 327 851 1265 851 274 851 1327 852 1328 852 1329 852 940 853 688 853 941 853 690 854 675 854 691 854 539 855 1330 855 1327 855 1331 856 1332 856 642 856 1333 857 1102 857 967 857 1152 858 1249 858 1334 858 1335 859 954 859 543 859 1336 860 1337 860 759 860 1338 861 974 861 1064 861 315 862 653 862 652 862 551 863 224 863 1339 863 1132 864 1081 864 736 864 1340 865 1305 865 1304 865 1341 866 419 866 1110 866 10 867 1242 867 1316 867 41 868 684 868 180 868 1217 869 295 869 294 869 1342 870 1286 870 1285 870 112 871 96 871 268 871 500 872 574 872 573 872 1284 873 1283 873 1343 873 33 874 214 874 213 874 1344 875 80 875 1345 875 1284 876 1343 876 1163 876 312 877 1346 877 1347 877 1163 878 1343 878 1289 878 523 879 522 879 1074 879 1003 880 1348 880 1009 880 1349 881 1350 881 1351 881 1352 882 922 882 905 882 1171 883 1289 883 1353 883 499 884 582 884 574 884 1251 885 862 885 864 885 1171 886 1353 886 1169 886 1169 887 1353 887 1354 887 238 888 2 888 820 888 891 889 982 889 1355 889 98 890 1356 890 77 890 1169 891 1354 891 1180 891 690 892 674 892 926 892 881 893 305 893 855 893 43 894 1357 894 1358 894 1275 895 1180 895 1359 895 176 896 46 896 875 896 1360 897 1361 897 1362 897 1275 898 1359 898 1276 898 214 899 225 899 110 899 1363 900 56 900 58 900 1276 901 1359 901 1364 901 1276 902 1364 902 1281 902 1237 903 1054 903 560 903 41 904 180 904 42 904 1365 905 798 905 756 905 1101 906 1366 906 349 906 1043 907 117 907 667 907 668 908 1367 908 669 908 93 909 92 909 1368 909 1191 910 20 910 277 910 480 911 481 911 764 911 373 912 1054 912 351 912 420 913 1369 913 406 913 345 914 942 914 176 914 194 915 1370 915 298 915 919 916 1371 916 1372 916 1373 917 1374 917 778 917 814 918 1375 918 1376 918 760 919 1026 919 761 919 222 920 402 920 147 920 545 921 1377 921 546 921 1378 922 287 922 289 922 1368 923 92 923 857 923 235 924 376 924 1379 924 64 925 1380 925 658 925 741 926 931 926 742 926 766 927 1095 927 660 927 1381 928 325 928 598 928 1361 929 1382 929 1383 929 1146 930 664 930 1193 930 491 931 1346 931 1090 931 1373 932 634 932 1374 932 1384 933 1385 933 1246 933 1386 934 1387 934 975 934 910 935 1261 935 89 935 1388 936 87 936 991 936 470 937 1044 937 279 937 1141 938 1389 938 1139 938 1390 939 1391 939 1392 939 509 940 602 940 1393 940 1362 941 1009 941 1348 941 1141 942 362 942 1389 942 591 943 1394 943 150 943 1395 944 972 944 974 944 952 945 1396 945 562 945 1321 946 640 946 1397 946 1367 947 500 947 669 947 206 948 456 948 455 948 1384 949 1246 949 156 949 1283 950 1398 950 1343 950 1116 951 1399 951 1117 951 1400 952 693 952 658 952 1401 953 1192 953 334 953 1402 954 249 954 353 954 433 955 1403 955 1053 955 1343 956 1404 956 1289 956 1110 957 419 957 1405 957 899 958 1406 958 1407 958 1387 959 1408 959 975 959 1289 960 1404 960 1353 960 1409 961 999 961 376 961 1337 962 1410 962 1411 962 1412 963 1413 963 252 963 1414 964 838 964 939 964 475 965 470 965 279 965 1151 966 781 966 783 966 1180 967 1354 967 1415 967 1416 968 1079 968 435 968 1417 969 649 969 439 969 1180 970 1415 970 1359 970 964 971 963 971 1295 971 1418 972 1419 972 849 972 1359 973 1415 973 1420 973 354 974 216 974 909 974 1421 975 1005 975 1184 975 1359 976 1420 976 1364 976 517 977 268 977 646 977 134 978 41 978 40 978 1134 979 151 979 1268 979 927 980 1037 980 1422 980 630 981 465 981 467 981 1395 982 974 982 1338 982 155 983 1384 983 156 983 172 984 1423 984 170 984 1016 985 1029 985 1042 985 1226 986 1416 986 1424 986 1425 987 1426 987 1427 987 1428 988 899 988 1407 988 1343 989 1398 989 1404 989 142 990 141 990 75 990 1243 991 932 991 1429 991 210 992 332 992 1258 992 1430 993 679 993 1431 993 1104 994 1432 994 375 994 82 995 375 995 737 995 17 996 16 996 625 996 1101 997 349 997 57 997 248 998 1433 998 1434 998 1435 999 1237 999 559 999 825 1000 1436 1000 826 1000 1354 1001 1353 1001 1437 1001 465 1002 779 1002 635 1002 890 1003 262 1003 1219 1003 1354 1004 1437 1004 1415 1004 1438 1005 508 1005 662 1005 101 1006 870 1006 250 1006 246 1007 1036 1007 244 1007 967 1008 1102 1008 1104 1008 1383 1009 1439 1009 1362 1009 1225 1010 1440 1010 328 1010 1441 1011 1271 1011 1442 1011 747 1012 1025 1012 1443 1012 1006 1013 1154 1013 713 1013 1444 1014 186 1014 1103 1014 570 1015 968 1015 1093 1015 1445 1016 682 1016 1007 1016 345 1017 819 1017 1446 1017 1447 1018 902 1018 1448 1018 14 1019 13 1019 822 1019 1449 1020 1450 1020 1451 1020 268 1021 95 1021 444 1021 1452 1022 1453 1022 411 1022 1010 1023 316 1023 1454 1023 637 1024 398 1024 70 1024 1455 1025 1456 1025 127 1025 1061 1026 983 1026 1217 1026 252 1027 1413 1027 1457 1027 1458 1028 489 1028 488 1028 1404 1029 1398 1029 1459 1029 658 1030 657 1030 1400 1030 721 1031 723 1031 1460 1031 1461 1032 1462 1032 1463 1032 283 1033 33 1033 336 1033 121 1034 732 1034 1253 1034 1404 1035 1459 1035 1464 1035 1404 1036 1464 1036 1353 1036 1035 1037 14 1037 988 1037 759 1038 1337 1038 885 1038 1353 1039 1464 1039 1437 1039 1066 1040 1465 1040 1134 1040 1466 1041 1154 1041 908 1041 1467 1042 668 1042 1468 1042 437 1043 773 1043 887 1043 1448 1044 651 1044 1447 1044 1415 1045 1437 1045 335 1045 1078 1046 1469 1046 640 1046 356 1047 355 1047 1470 1047 1350 1048 563 1048 1471 1048 982 1049 1472 1049 980 1049 1420 1050 1415 1050 516 1050 751 1051 416 1051 415 1051 476 1052 1299 1052 946 1052 1420 1053 516 1053 1473 1053 1420 1054 1473 1054 1364 1054 1474 1055 982 1055 1190 1055 1475 1056 1476 1056 709 1056 1330 1057 544 1057 608 1057 882 1058 1411 1058 724 1058 1477 1059 117 1059 1043 1059 97 1060 39 1060 98 1060 1478 1061 1479 1061 1480 1061 1026 1062 1313 1062 697 1062 1398 1063 336 1063 1459 1063 1481 1064 1469 1064 961 1064 578 1065 969 1065 496 1065 1332 1066 748 1066 1286 1066 1072 1067 1119 1067 1121 1067 426 1068 1482 1068 424 1068 424 1069 1482 1069 449 1069 556 1070 1483 1070 856 1070 276 1071 1484 1071 1225 1071 718 1072 655 1072 1485 1072 1361 1073 1326 1073 1382 1073 133 1074 1486 1074 683 1074 886 1075 1487 1075 887 1075 1437 1076 1464 1076 335 1076 850 1077 1039 1077 851 1077 98 1078 30 1078 1356 1078 1358 1079 44 1079 43 1079 553 1080 1271 1080 1270 1080 172 1081 441 1081 1423 1081 717 1082 964 1082 1059 1082 1415 1083 335 1083 516 1083 1488 1084 406 1084 1369 1084 42 1085 180 1085 182 1085 566 1086 794 1086 44 1086 1029 1087 1195 1087 1489 1087 1286 1088 748 1088 750 1088 67 1089 1490 1089 726 1089 219 1090 218 1090 1215 1090 476 1091 1491 1091 1299 1091 1492 1092 745 1092 1493 1092 19 1093 439 1093 440 1093 791 1094 1227 1094 706 1094 1072 1095 1121 1095 1494 1095 589 1096 730 1096 807 1096 496 1097 537 1097 833 1097 1393 1098 601 1098 1165 1098 152 1099 1495 1099 1231 1099 1496 1100 361 1100 586 1100 1497 1101 458 1101 908 1101 1498 1102 642 1102 641 1102 3 1103 5 1103 1499 1103 1500 1104 1410 1104 1336 1104 1501 1105 950 1105 1502 1105 960 1106 847 1106 717 1106 1468 1107 123 1107 1467 1107 1503 1108 1183 1108 530 1108 1459 1109 336 1109 1464 1109 1052 1110 1504 1110 1053 1110 1505 1111 320 1111 1506 1111 1031 1112 688 1112 1507 1112 204 1113 614 1113 205 1113 874 1114 1508 1114 860 1114 1113 1115 824 1115 1479 1115 227 1116 1125 1116 228 1116 1025 1117 403 1117 1443 1117 72 1118 1025 1118 853 1118 133 1119 740 1119 1486 1119 1226 1120 1079 1120 1416 1120 1315 1121 1308 1121 1386 1121 1509 1122 1510 1122 952 1122 599 1123 254 1123 519 1123 648 1124 361 1124 360 1124 1007 1125 438 1125 1445 1125 317 1126 36 1126 758 1126 1511 1127 1055 1127 1303 1127 1138 1128 1301 1128 978 1128 600 1129 1512 1129 1513 1129 1088 1130 1514 1130 1515 1130 900 1131 1081 1131 1516 1131 717 1132 847 1132 1517 1132 1518 1133 508 1133 510 1133 935 1134 1480 1134 936 1134 1100 1135 572 1135 938 1135 1357 1136 1519 1136 275 1136 1263 1137 606 1137 1520 1137 1333 1138 376 1138 1521 1138 509 1139 1512 1139 600 1139 916 1140 1111 1140 657 1140 852 1141 851 1141 1522 1141 1269 1142 1523 1142 858 1142 1223 1143 715 1143 1524 1143 99 1144 1385 1144 100 1144 1223 1145 1460 1145 1525 1145 65 1146 1526 1146 1527 1146 1528 1147 1186 1147 1529 1147 1191 1148 497 1148 1474 1148 1464 1149 336 1149 335 1149 35 1150 120 1150 214 1150 210 1151 187 1151 1103 1151 744 1152 987 1152 1530 1152 662 1153 520 1153 22 1153 1231 1154 1018 1154 1399 1154 421 1155 81 1155 422 1155 597 1156 545 1156 547 1156 306 1157 1208 1157 307 1157 1339 1158 224 1158 472 1158 1531 1159 999 1159 1532 1159 349 1160 1366 1160 350 1160 413 1161 509 1161 1533 1161 356 1162 784 1162 107 1162 249 1163 1147 1163 353 1163 1534 1164 454 1164 843 1164 786 1165 1434 1165 1433 1165 154 1166 1535 1166 51 1166 1517 1167 847 1167 1179 1167 420 1168 1536 1168 1537 1168 198 1169 200 1169 578 1169 1013 1170 34 1170 1172 1170 515 1171 449 1171 1526 1171 1538 1172 166 1172 728 1172 603 1173 921 1173 604 1173 496 1174 902 1174 487 1174 1539 1175 1540 1175 1509 1175 313 1176 1347 1176 754 1176 1432 1177 111 1177 737 1177 1541 1178 1542 1178 1543 1178 1386 1179 975 1179 1315 1179 1499 1180 886 1180 3 1180 454 1181 1534 1181 433 1181 738 1182 167 1182 169 1182 1470 1183 1068 1183 1302 1183 847 1184 960 1184 342 1184 1527 1185 1544 1185 1545 1185 1546 1186 1027 1186 693 1186 732 1187 731 1187 1253 1187 707 1188 1035 1188 744 1188 972 1189 1458 1189 973 1189 548 1190 875 1190 900 1190 557 1191 869 1191 472 1191 1547 1192 110 1192 473 1192 1331 1193 1502 1193 1332 1193 9 1194 665 1194 10 1194 1548 1195 1549 1195 569 1195 973 1196 1256 1196 1255 1196 730 1197 394 1197 393 1197 412 1198 509 1198 413 1198 1550 1199 790 1199 792 1199 1551 1200 1552 1200 1553 1200 345 1201 612 1201 942 1201 628 1202 627 1202 1168 1202 1062 1203 732 1203 121 1203 611 1204 1554 1204 712 1204 112 1205 341 1205 186 1205 710 1206 1555 1206 1294 1206 947 1207 91 1207 93 1207 1545 1208 1544 1208 1556 1208 1407 1209 1406 1209 1557 1209 489 1210 1442 1210 818 1210 1558 1211 763 1211 253 1211 1439 1212 1559 1212 1009 1212 1231 1213 1495 1213 1018 1213 553 1214 1167 1214 789 1214 443 1215 95 1215 478 1215 880 1216 168 1216 881 1216 1560 1217 1499 1217 1119 1217 1099 1218 1098 1218 1214 1218 1561 1219 1390 1219 1392 1219 1562 1220 824 1220 1478 1220 1563 1221 1564 1221 1565 1221 298 1222 890 1222 1111 1222 227 1223 572 1223 1125 1223 1525 1224 660 1224 1094 1224 203 1225 202 1225 342 1225 344 1226 1554 1226 819 1226 1104 1227 375 1227 377 1227 1360 1228 1362 1228 477 1228 358 1229 357 1229 86 1229 1096 1230 715 1230 1223 1230 867 1231 1566 1231 632 1231 1419 1232 1543 1232 1014 1232 487 1233 428 1233 465 1233 373 1234 1567 1234 371 1234 999 1235 1232 1235 1360 1235 1014 1236 1568 1236 1015 1236 1569 1237 1570 1237 1571 1237 713 1238 715 1238 735 1238 828 1239 1036 1239 960 1239 638 1240 590 1240 639 1240 1015 1241 1568 1241 1277 1241 448 1242 43 1242 45 1242 1189 1243 1572 1243 1069 1243 669 1244 500 1244 573 1244 1545 1245 1556 1245 1251 1245 217 1246 1048 1246 1408 1246 949 1247 1431 1247 923 1247 1573 1248 1524 1248 1574 1248 754 1249 1347 1249 55 1249 1568 1250 1279 1250 1277 1250 1575 1251 261 1251 170 1251 191 1252 190 1252 655 1252 169 1253 986 1253 1344 1253 710 1254 1293 1254 579 1254 163 1255 453 1255 1576 1255 840 1256 1092 1256 1577 1256 1578 1257 99 1257 101 1257 317 1258 1552 1258 36 1258 1280 1259 127 1259 126 1259 1211 1260 1213 1260 1579 1260 1580 1261 957 1261 1581 1261 380 1262 379 1262 1582 1262 1583 1263 866 1263 1584 1263 209 1264 1166 1264 315 1264 1584 1265 866 1265 868 1265 830 1266 1060 1266 299 1266 1077 1267 264 1267 415 1267 1071 1268 269 1268 143 1268 1585 1269 777 1269 1467 1269 1586 1270 1228 1270 1274 1270 1413 1271 803 1271 232 1271 1425 1272 1427 1272 106 1272 1587 1273 383 1273 357 1273 1279 1274 126 1274 785 1274 605 1275 1571 1275 1570 1275 1507 1276 962 1276 1434 1276 1550 1277 705 1277 743 1277 510 1278 1448 1278 1518 1278 1575 1279 420 1279 1537 1279 205 1280 456 1280 206 1280 651 1281 1448 1281 510 1281 820 1282 1053 1282 1403 1282 1544 1283 1588 1283 1589 1283 1441 1284 196 1284 195 1284 114 1285 327 1285 1504 1285 1590 1286 961 1286 1469 1286 1591 1287 1544 1287 1589 1287 1471 1288 563 1288 1192 1288 1385 1289 99 1289 1246 1289 1592 1290 1128 1290 1574 1290 1593 1291 1594 1291 195 1291 1085 1292 990 1292 287 1292 58 1293 1483 1293 1363 1293 1360 1294 1576 1294 1361 1294 645 1295 531 1295 1595 1295 810 1296 1321 1296 657 1296 717 1297 1059 1297 1058 1297 1085 1298 287 1298 1378 1298 217 1299 1408 1299 1387 1299 576 1300 571 1300 1596 1300 347 1301 824 1301 330 1301 1597 1302 283 1302 1505 1302 1544 1303 1591 1303 1598 1303 875 1304 48 1304 1599 1304 71 1305 118 1305 1477 1305 526 1306 525 1306 951 1306 1349 1307 561 1307 1350 1307 1589 1308 1600 1308 1591 1308 678 1309 1016 1309 679 1309 919 1310 918 1310 1371 1310 1557 1311 1406 1311 586 1311 119 1312 1577 1312 120 1312 586 1313 257 1313 1496 1313 1496 1314 257 1314 1062 1314 71 1315 1238 1315 118 1315 596 1316 1601 1316 321 1316 300 1317 984 1317 1011 1317 1505 1318 928 1318 911 1318 843 1319 454 1319 456 1319 1029 1320 1489 1320 1040 1320 789 1321 788 1321 681 1321 1602 1322 227 1322 555 1322 228 1323 1101 1323 57 1323 1329 1324 183 1324 185 1324 21 1325 23 1325 518 1325 901 1326 677 1326 1430 1326 348 1327 939 1327 349 1327 155 1328 1087 1328 1384 1328 935 1329 937 1329 1158 1329 1603 1330 1137 1330 1391 1330 1330 1331 9 1331 11 1331 1604 1332 99 1332 1578 1332 57 1333 344 1333 856 1333 459 1334 762 1334 1088 1334 1578 1335 1083 1335 1605 1335 346 1336 330 1336 329 1336 1318 1337 1208 1337 455 1337 1061 1338 997 1338 994 1338 115 1339 1054 1339 1237 1339 467 1340 936 1340 1606 1340 351 1341 1607 1341 352 1341 1514 1342 698 1342 1608 1342 1294 1343 1579 1343 1188 1343 1277 1344 1279 1344 785 1344 1543 1345 1419 1345 1541 1345 523 1346 1074 1346 312 1346 197 1347 196 1347 1458 1347 770 1348 329 1348 331 1348 1609 1349 1484 1349 276 1349 515 1350 514 1350 1610 1350 1315 1351 976 1351 1206 1351 1419 1352 1418 1352 1541 1352 1232 1353 163 1353 1360 1353 659 1354 606 1354 1263 1354 1541 1355 1418 1355 914 1355 758 1356 36 1356 38 1356 1541 1357 914 1357 1611 1357 170 1358 1423 1358 418 1358 809 1359 247 1359 145 1359 1071 1360 143 1360 636 1360 1442 1361 1296 1361 1503 1361 1155 1362 1466 1362 458 1362 1294 1363 367 1363 1211 1363 425 1364 692 1364 1084 1364 1612 1365 458 1365 1466 1365 271 1366 198 1366 1248 1366 938 1367 1414 1367 939 1367 347 1368 509 1368 823 1368 34 1369 1613 1369 130 1369 1537 1370 304 1370 303 1370 493 1371 495 1371 271 1371 747 1372 1493 1372 745 1372 782 1373 432 1373 431 1373 731 1374 956 1374 1614 1374 1194 1375 379 1375 1292 1375 256 1376 1068 1376 733 1376 733 1377 1068 1377 731 1377 101 1378 397 1378 769 1378 1381 1379 467 1379 325 1379 1328 1380 1395 1380 183 1380 307 1381 1047 1381 617 1381 1417 1382 19 1382 18 1382 1228 1383 1580 1383 1581 1383 653 1384 948 1384 950 1384 607 1385 1012 1385 522 1385 1384 1386 1615 1386 1616 1386 1617 1387 1096 1387 1618 1387 1426 1388 919 1388 1427 1388 1619 1389 1132 1389 1620 1389 509 1390 1393 1390 1165 1390 512 1391 858 1391 1523 1391 388 1392 146 1392 1226 1392 137 1393 680 1393 292 1393 179 1394 977 1394 978 1394 57 1395 711 1395 344 1395 1538 1396 1621 1396 164 1396 1618 1397 1095 1397 766 1397 12 1398 1586 1398 1274 1398 957 1399 435 1399 1079 1399 1600 1400 1541 1400 1611 1400 1600 1401 1611 1401 1591 1401 1591 1402 1611 1402 1115 1402 599 1403 521 1403 865 1403 331 1404 1157 1404 1513 1404 1622 1405 1252 1405 540 1405 700 1406 236 1406 1521 1406 938 1407 1366 1407 1623 1407 1624 1408 249 1408 1402 1408 1356 1409 32 1409 1388 1409 505 1410 507 1410 1249 1410 1022 1411 1024 1411 1334 1411 430 1412 432 1412 1529 1412 255 1413 1625 1413 1307 1413 1067 1414 943 1414 685 1414 1034 1415 1626 1415 1627 1415 1067 1416 685 1416 1456 1416 1067 1417 1456 1417 1076 1417 487 1418 535 1418 527 1418 1076 1419 1455 1419 127 1419 1076 1420 127 1420 1086 1420 1086 1421 127 1421 1280 1421 268 1422 1628 1422 105 1422 1191 1423 1629 1423 20 1423 1086 1424 1280 1424 1105 1424 385 1425 941 1425 1630 1425 1105 1426 1280 1426 1124 1426 1124 1427 1280 1427 1279 1427 1525 1428 1094 1428 1223 1428 1285 1429 589 1429 165 1429 1124 1430 1279 1430 1131 1430 1131 1431 1279 1431 1568 1431 318 1432 317 1432 758 1432 1076 1433 1456 1433 1455 1433 1010 1434 1454 1434 49 1434 325 1435 467 1435 420 1435 676 1436 1059 1436 1028 1436 1 1437 1402 1437 2 1437 1298 1438 1121 1438 1024 1438 1013 1439 1631 1439 34 1439 1351 1440 1350 1440 1462 1440 1377 1441 1632 1441 1633 1441 1521 1442 376 1442 700 1442 631 1443 868 1443 632 1443 1503 1444 530 1444 818 1444 1595 1445 531 1445 1233 1445 392 1446 870 1446 174 1446 174 1447 870 1447 727 1447 799 1448 527 1448 204 1448 993 1449 1103 1449 341 1449 243 1450 242 1450 1099 1450 1322 1451 1373 1451 780 1451 1634 1452 1360 1452 477 1452 556 1453 856 1453 555 1453 1227 1454 933 1454 229 1454 1543 1455 1568 1455 1014 1455 637 1456 639 1456 398 1456 595 1457 1291 1457 378 1457 1268 1458 151 1458 153 1458 716 1459 1295 1459 963 1459 196 1460 1442 1460 1635 1460 1636 1461 957 1461 1394 1461 252 1462 1457 1462 1558 1462 909 1463 1261 1463 910 1463 811 1464 1450 1464 1449 1464 1558 1465 1457 1465 763 1465 1410 1466 1500 1466 1610 1466 843 1467 888 1467 1370 1467 1400 1468 940 1468 384 1468 421 1469 82 1469 81 1469 1101 1470 938 1470 1623 1470 1065 1471 644 1471 1637 1471 1515 1472 1638 1472 877 1472 824 1473 1113 1473 1112 1473 1565 1474 1436 1474 825 1474 956 1475 1068 1475 955 1475 339 1476 1639 1476 337 1476 423 1477 376 1477 421 1477 795 1478 797 1478 99 1478 934 1479 244 1479 1038 1479 1590 1480 1469 1480 1078 1480 214 1481 125 1481 223 1481 657 1482 940 1482 1400 1482 249 1483 1567 1483 1147 1483 321 1484 1601 1484 322 1484 1242 1485 197 1485 1316 1485 1351 1486 1462 1486 1461 1486 404 1487 1640 1487 405 1487 871 1488 1120 1488 5 1488 497 1489 1191 1489 498 1489 495 1490 793 1490 200 1490 865 1491 1641 1491 1191 1491 1564 1492 1002 1492 484 1492 487 1493 1262 1493 428 1493 1642 1494 1643 1494 1644 1494 48 1495 1613 1495 1599 1495 1278 1496 1522 1496 851 1496 1172 1497 34 1497 33 1497 1597 1498 911 1498 281 1498 929 1499 1194 1499 930 1499 642 1500 1342 1500 1645 1500 13 1501 1646 1501 1647 1501 286 1502 1151 1502 693 1502 35 1503 962 1503 961 1503 582 1504 1129 1504 1130 1504 1609 1505 1460 1505 1648 1505 312 1506 1075 1506 1346 1506 1649 1507 970 1507 969 1507 1426 1508 917 1508 919 1508 1613 1509 47 1509 130 1509 966 1510 1235 1510 281 1510 856 1511 1483 1511 58 1511 915 1512 1536 1512 1341 1512 1501 1513 1502 1513 1331 1513 2 1514 1402 1514 1052 1514 945 1515 468 1515 475 1515 614 1516 889 1516 205 1516 1470 1517 784 1517 356 1517 441 1518 139 1518 1423 1518 1650 1519 1540 1519 1651 1519 33 1520 35 1520 214 1520 487 1521 486 1521 954 1521 1008 1522 1207 1522 436 1522 1159 1523 803 1523 802 1523 146 1524 148 1524 1080 1524 828 1525 1059 1525 829 1525 326 1526 155 1526 1227 1526 669 1527 573 1527 1652 1527 780 1528 779 1528 1323 1528 926 1529 1282 1529 430 1529 1653 1530 934 1530 1290 1530 1539 1531 1509 1531 525 1531 442 1532 1248 1532 198 1532 1576 1533 1628 1533 1324 1533 632 1534 1566 1534 1116 1534 1598 1535 1591 1535 1115 1535 391 1536 6 1536 209 1536 930 1537 1194 1537 1029 1537 982 1538 893 1538 892 1538 1376 1539 1352 1539 905 1539 458 1540 1592 1540 1155 1540 1312 1541 1501 1541 1331 1541 9 1542 608 1542 665 1542 1654 1543 1179 1543 656 1543 1485 1544 655 1544 305 1544 249 1545 1220 1545 1219 1545 926 1546 430 1546 1319 1546 909 1547 389 1547 1655 1547 448 1548 447 1548 1519 1548 1070 1549 1656 1549 545 1549 1311 1550 1312 1550 1498 1550 1308 1551 1310 1551 1386 1551 112 1552 145 1552 247 1552 1108 1553 855 1553 986 1553 693 1554 1151 1554 783 1554 1062 1555 733 1555 732 1555 1620 1556 451 1556 224 1556 1657 1557 1218 1557 1178 1557 1442 1558 196 1558 1441 1558 1658 1559 498 1559 1191 1559 650 1560 542 1560 651 1560 1659 1561 334 1561 333 1561 231 1562 805 1562 1580 1562 898 1563 1048 1563 1049 1563 404 1564 403 1564 460 1564 447 1565 722 1565 721 1565 546 1566 1642 1566 1644 1566 1660 1567 165 1567 164 1567 899 1568 1625 1568 1406 1568 852 1569 1522 1569 718 1569 579 1570 1188 1570 894 1570 1110 1571 1405 1571 1144 1571 152 1572 1233 1572 1495 1572 1656 1573 1377 1573 545 1573 675 1574 829 1574 1059 1574 763 1575 1457 1575 518 1575 672 1576 227 1576 1661 1576 353 1577 115 1577 114 1577 318 1578 758 1578 757 1578 908 1579 79 1579 806 1579 1662 1580 1443 1580 403 1580 1322 1581 363 1581 362 1581 483 1582 220 1582 1436 1582 943 1583 1030 1583 686 1583 910 1584 788 1584 958 1584 13 1585 1647 1585 173 1585 1145 1586 1077 1586 664 1586 662 1587 508 1587 1641 1587 840 1588 1577 1588 841 1588 88 1589 90 1589 682 1589 924 1590 93 1590 1368 1590 1580 1591 805 1591 957 1591 1174 1592 729 1592 750 1592 73 1593 1550 1593 743 1593 1220 1594 1287 1594 703 1594 710 1595 1294 1595 1293 1595 834 1596 1362 1596 1663 1596 1664 1597 721 1597 276 1597 1665 1598 1112 1598 1114 1598 37 1599 36 1599 1551 1599 1386 1600 1310 1600 218 1600 1575 1601 191 1601 261 1601 116 1602 118 1602 1238 1602 1563 1603 1000 1603 1002 1603 1061 1604 450 1604 1235 1604 1300 1605 179 1605 1301 1605 465 1606 831 1606 1323 1606 948 1607 1431 1607 949 1607 316 1608 315 1608 652 1608 77 1609 1356 1609 1388 1609 1666 1610 1584 1610 631 1610 249 1611 1624 1611 1287 1611 1427 1612 919 1612 1372 1612 1427 1613 1372 1613 265 1613 52 1614 621 1614 317 1614 218 1615 243 1615 1215 1615 462 1616 704 1616 463 1616 45 1617 44 1617 1031 1617 795 1618 1073 1618 796 1618 513 1619 1489 1619 1195 1619 172 1620 171 1620 614 1620 454 1621 328 1621 1127 1621 1439 1622 1009 1622 1362 1622 417 1623 811 1623 1657 1623 464 1624 463 1624 1 1624 693 1625 782 1625 1546 1625 23 1626 369 1626 763 1626 193 1627 1667 1627 1370 1627 901 1628 1430 1628 948 1628 1016 1629 1042 1629 947 1629 1397 1630 640 1630 1469 1630 1609 1631 1648 1631 1668 1631 1339 1632 711 1632 57 1632 588 1633 1557 1633 586 1633 293 1634 578 1634 833 1634 827 1635 826 1635 760 1635 15 1636 17 1636 1669 1636 378 1637 1292 1637 379 1637 1670 1638 390 1638 391 1638 1542 1639 1600 1639 1671 1639 1566 1640 1399 1640 1116 1640 1185 1641 1129 1641 582 1641 1245 1642 1262 1642 1335 1642 1672 1643 571 1643 569 1643 596 1644 1182 1644 1601 1644 1383 1645 1673 1645 1439 1645 1182 1646 154 1646 50 1646 75 1647 141 1647 76 1647 701 1648 1674 1648 1142 1648 1142 1649 1674 1649 1143 1649 1233 1650 1675 1650 1495 1650 415 1651 417 1651 663 1651 578 1652 496 1652 833 1652 1676 1653 1584 1653 1666 1653 487 1654 536 1654 535 1654 1677 1655 487 1655 801 1655 1008 1656 1261 1656 1207 1656 651 1657 485 1657 1447 1657 924 1658 1368 1658 925 1658 1529 1659 1186 1659 1319 1659 713 1660 734 1660 1006 1660 113 1661 327 1661 114 1661 509 1662 508 1662 1438 1662 68 1663 1678 1663 595 1663 1296 1664 1183 1664 1503 1664 475 1665 280 1665 102 1665 800 1666 455 1666 1208 1666 38 1667 1306 1667 1305 1667 461 1668 460 1668 291 1668 194 1669 1679 1669 1344 1669 1616 1670 100 1670 1385 1670 1053 1671 1504 1671 433 1671 1329 1672 1328 1672 183 1672 205 1673 888 1673 456 1673 1285 1674 165 1674 1660 1674 1680 1675 1681 1675 929 1675 1146 1676 506 1676 1145 1676 243 1677 1099 1677 1214 1677 138 1678 528 1678 1679 1678 1682 1679 1582 1679 1683 1679 630 1680 467 1680 1381 1680 1631 1681 83 1681 208 1681 1308 1682 1666 1682 1309 1682 1684 1683 1685 1683 302 1683 1371 1684 1686 1684 812 1684 1519 1685 1664 1685 275 1685 143 1686 145 1686 112 1686 907 1687 618 1687 457 1687 472 1688 471 1688 1687 1688 1098 1689 1023 1689 219 1689 1665 1690 1114 1690 1479 1690 704 1691 1287 1691 463 1691 1141 1692 1335 1692 542 1692 529 1693 140 1693 441 1693 1267 1694 1036 1694 245 1694 914 1695 1418 1695 849 1695 134 1696 133 1696 41 1696 87 1697 1388 1697 109 1697 1613 1698 48 1698 47 1698 106 1699 1427 1699 265 1699 1316 1700 1458 1700 972 1700 1688 1701 526 1701 561 1701 1201 1702 905 1702 904 1702 1533 1703 331 1703 413 1703 84 1704 24 1704 85 1704 432 1705 782 1705 781 1705 1423 1706 139 1706 1405 1706 717 1707 1689 1707 960 1707 734 1708 1690 1708 1674 1708 604 1709 1571 1709 605 1709 801 1710 487 1710 527 1710 650 1711 510 1711 623 1711 316 1712 652 1712 1311 1712 674 1713 676 1713 1282 1713 1397 1714 1469 1714 1481 1714 1598 1715 1556 1715 1544 1715 1144 1716 1405 1716 139 1716 1431 1717 924 1717 923 1717 436 1718 438 1718 1007 1718 1254 1719 1022 1719 1334 1719 1493 1720 1691 1720 817 1720 1224 1721 1692 1721 1097 1721 1544 1722 1527 1722 1588 1722 1588 1723 1527 1723 1526 1723 890 1724 889 1724 613 1724 49 1725 1454 1725 1498 1725 80 1726 701 1726 1142 1726 477 1727 479 1727 210 1727 854 1728 1492 1728 1550 1728 644 1729 645 1729 1693 1729 560 1730 1054 1730 1148 1730 1588 1731 1694 1731 1589 1731 86 1732 649 1732 1417 1732 1411 1733 1410 1733 725 1733 385 1734 1630 1734 558 1734 1 1735 1624 1735 1402 1735 1589 1736 1694 1736 1671 1736 1589 1737 1671 1737 1600 1737 420 1738 419 1738 1536 1738 1541 1739 1600 1739 1542 1739 76 1740 240 1740 77 1740 351 1741 1054 1741 1607 1741 583 1742 585 1742 1034 1742 1467 1743 123 1743 122 1743 70 1744 1193 1744 1178 1744 25 1745 1248 1745 1695 1745 192 1746 787 1746 193 1746 118 1747 117 1747 1477 1747 236 1748 1333 1748 1521 1748 420 1749 406 1749 408 1749 330 1750 1478 1750 1157 1750 1696 1751 918 1751 1156 1751 1584 1752 868 1752 631 1752 561 1753 563 1753 1350 1753 1157 1754 634 1754 1322 1754 285 1755 1528 1755 781 1755 974 1756 973 1756 1255 1756 376 1757 82 1757 421 1757 1652 1758 1676 1758 1205 1758 1335 1759 427 1759 1245 1759 1380 1760 1654 1760 1297 1760 1472 1761 982 1761 891 1761 414 1762 413 1762 1513 1762 1467 1763 122 1763 1585 1763 501 1764 1595 1764 502 1764 533 1765 722 1765 532 1765 1031 1766 786 1766 192 1766 689 1767 688 1767 940 1767 1530 1768 692 1768 424 1768 209 1769 8 1769 1166 1769 159 1770 291 1770 160 1770 1388 1771 32 1771 109 1771 1599 1772 1613 1772 208 1772 1298 1773 1097 1773 1692 1773 746 1774 853 1774 1025 1774 916 1775 1341 1775 1110 1775 1665 1776 1478 1776 1112 1776 1020 1777 1060 1777 1030 1777 521 1778 1641 1778 865 1778 232 1779 803 1779 1697 1779 882 1780 726 1780 879 1780 1200 1781 1376 1781 1201 1781 184 1782 1185 1782 582 1782 723 1783 660 1783 1525 1783 1158 1784 504 1784 503 1784 1310 1785 1309 1785 218 1785 1443 1786 1698 1786 815 1786 1478 1787 1480 1787 1157 1787 1429 1788 1168 1788 1594 1788 275 1789 274 1789 1357 1789 305 1790 307 1790 855 1790 781 1791 1529 1791 432 1791 1128 1792 1592 1792 1127 1792 26 1793 232 1793 24 1793 89 1794 1261 1794 1008 1794 823 1795 1438 1795 407 1795 224 1796 557 1796 472 1796 1117 1797 1018 1797 433 1797 1679 1798 528 1798 535 1798 1346 1799 1075 1799 1090 1799 1476 1800 1699 1800 568 1800 228 1801 57 1801 226 1801 0 1802 35 1802 464 1802 370 1803 1186 1803 1700 1803 1110 1804 298 1804 1111 1804 1701 1805 565 1805 564 1805 634 1806 1158 1806 503 1806 925 1807 1368 1807 749 1807 1505 1808 1506 1808 339 1808 1702 1809 1000 1809 1563 1809 1703 1810 1683 1810 1704 1810 1026 1811 388 1811 1313 1811 1585 1812 122 1812 1252 1812 1029 1813 1040 1813 1042 1813 1408 1814 588 1814 587 1814 235 1815 1634 1815 236 1815 445 1816 737 1816 111 1816 1155 1817 1154 1817 1466 1817 196 1818 1635 1818 1458 1818 1108 1819 168 1819 880 1819 1157 1820 1480 1820 1158 1820 1609 1821 1668 1821 1484 1821 157 1822 1244 1822 230 1822 473 1823 319 1823 1547 1823 189 1824 1209 1824 190 1824 1019 1825 1675 1825 1508 1825 1446 1826 611 1826 345 1826 1614 1827 544 1827 541 1827 170 1828 418 1828 420 1828 871 1829 506 1829 505 1829 741 1830 929 1830 931 1830 101 1831 250 1831 249 1831 967 1832 376 1832 1333 1832 319 1833 213 1833 1547 1833 1309 1834 241 1834 243 1834 617 1835 855 1835 307 1835 882 1836 724 1836 726 1836 942 1837 612 1837 130 1837 298 1838 1144 1838 138 1838 1227 1839 157 1839 933 1839 64 1840 63 1840 1380 1840 1472 1841 891 1841 493 1841 518 1842 23 1842 763 1842 311 1843 523 1843 312 1843 467 1844 1369 1844 420 1844 1537 1845 303 1845 487 1845 1358 1846 1266 1846 566 1846 912 1847 1705 1847 1706 1847 711 1848 1707 1848 344 1848 1708 1849 314 1849 316 1849 780 1850 1323 1850 1322 1850 154 1851 1709 1851 1535 1851 1710 1852 912 1852 965 1852 218 1853 1387 1853 1386 1853 1228 1854 1581 1854 1274 1854 547 1855 1711 1855 1182 1855 426 1856 1085 1856 1378 1856 965 1857 912 1857 1706 1857 390 1858 1004 1858 6 1858 1712 1859 604 1859 921 1859 405 1860 1640 1860 1662 1860 1705 1861 912 1861 1713 1861 1705 1862 1713 1862 1714 1862 207 1863 875 1863 208 1863 951 1864 562 1864 561 1864 1316 1865 972 1865 1317 1865 895 1866 605 1866 896 1866 1715 1867 812 1867 1686 1867 1714 1868 1713 1868 1716 1868 735 1869 715 1869 1096 1869 1713 1870 1717 1870 1716 1870 1451 1871 1450 1871 1538 1871 192 1872 995 1872 45 1872 1462 1873 1192 1873 1401 1873 690 1874 1718 1874 675 1874 1250 1875 66 1875 1545 1875 1513 1876 1141 1876 601 1876 1719 1877 22 1877 519 1877 263 1878 262 1878 613 1878 1693 1879 1595 1879 501 1879 467 1880 504 1880 937 1880 1328 1881 1720 1881 1395 1881 252 1882 1558 1882 253 1882 1392 1883 1510 1883 1540 1883 1318 1884 455 1884 1046 1884 1660 1885 1645 1885 1285 1885 493 1886 271 1886 84 1886 657 1887 1111 1887 810 1887 774 1888 1034 1888 1555 1888 1721 1889 1132 1889 445 1889 742 1890 931 1890 678 1890 289 1891 790 1891 1492 1891 574 1892 1130 1892 1583 1892 512 1893 1523 1893 1489 1893 826 1894 386 1894 760 1894 21 1895 662 1895 22 1895 1641 1896 521 1896 662 1896 487 1897 303 1897 536 1897 1474 1898 497 1898 969 1898 330 1899 1157 1899 331 1899 221 1900 1722 1900 400 1900 615 1901 423 1901 453 1901 328 1902 1440 1902 1128 1902 632 1903 1116 1903 242 1903 1083 1904 887 1904 1487 1904 270 1905 200 1905 199 1905 626 1906 932 1906 971 1906 1138 1907 946 1907 1299 1907 1057 1908 980 1908 84 1908 550 1909 572 1909 551 1909 1691 1910 747 1910 817 1910 749 1911 1368 1911 1174 1911 745 1912 854 1912 746 1912 1309 1913 243 1913 218 1913 1170 1914 1714 1914 1723 1914 1362 1915 1361 1915 1383 1915 636 1916 1236 1916 842 1916 762 1917 761 1917 696 1917 359 1918 123 1918 360 1918 1087 1919 175 1919 1615 1919 1723 1920 1714 1920 1716 1920 725 1921 724 1921 1411 1921 595 1922 511 1922 1291 1922 1700 1923 1186 1923 371 1923 268 1924 96 1924 95 1924 1050 1925 1051 1925 1204 1925 1724 1926 1203 1926 1204 1926 795 1927 1725 1927 1073 1927 1724 1928 1204 1928 1051 1928 1724 1929 1051 1929 1706 1929 595 1930 378 1930 1726 1930 1072 1931 1494 1931 796 1931 1225 1932 1484 1932 1440 1932 62 1933 1027 1933 1028 1933 987 1934 1727 1934 1530 1934 821 1935 1236 1935 636 1935 1194 1936 1292 1936 1195 1936 575 1937 1583 1937 1584 1937 898 1938 1049 1938 1254 1938 461 1939 1221 1939 459 1939 148 1940 150 1940 957 1940 269 1941 104 1941 422 1941 552 1942 554 1942 1445 1942 399 1943 619 1943 1678 1943 1206 1944 648 1944 360 1944 1265 1945 113 1945 1237 1945 1728 1946 1714 1946 1181 1946 1707 1947 1729 1947 1730 1947 514 1948 1410 1948 1610 1948 1181 1949 1714 1949 1170 1949 1322 1950 362 1950 1141 1950 242 1951 1116 1951 1099 1951 1731 1952 1036 1952 675 1952 1717 1953 1162 1953 1732 1953 787 1954 809 1954 193 1954 1642 1955 1633 1955 1643 1955 1687 1956 125 1956 124 1956 458 1957 907 1957 457 1957 694 1958 331 1958 1533 1958 1682 1959 1683 1959 1426 1959 1627 1960 365 1960 367 1960 367 1961 366 1961 1211 1961 78 1962 806 1962 79 1962 1428 1963 1408 1963 1048 1963 192 1964 80 1964 1142 1964 1282 1965 926 1965 674 1965 511 1966 513 1966 1291 1966 88 1967 910 1967 89 1967 492 1968 1336 1968 54 1968 679 1969 1016 1969 947 1969 799 1970 206 1970 800 1970 873 1971 1508 1971 874 1971 1298 1972 1494 1972 1121 1972 1338 1973 1064 1973 1185 1973 368 1974 23 1974 1719 1974 70 1975 398 1975 399 1975 826 1976 1436 1976 386 1976 160 1977 291 1977 1733 1977 893 1978 982 1978 1474 1978 1673 1979 1382 1979 1559 1979 801 1980 189 1980 1677 1980 264 1981 751 1981 415 1981 1039 1982 1036 1982 851 1982 1647 1983 392 1983 173 1983 1638 1984 1670 1984 1708 1984 838 1985 1339 1985 57 1985 363 1986 1323 1986 831 1986 1655 1987 389 1987 1077 1987 1203 1988 1724 1988 1197 1988 331 1989 695 1989 770 1989 447 1990 446 1990 722 1990 631 1991 241 1991 1309 1991 1458 1992 488 1992 1256 1992 262 1993 655 1993 1278 1993 1402 1994 353 1994 1052 1994 797 1995 796 1995 1494 1995 423 1996 422 1996 720 1996 1339 1997 1687 1997 711 1997 1219 1998 262 1998 1278 1998 1454 1999 316 1999 1311 1999 685 2000 943 2000 686 2000 1071 2001 842 2001 702 2001 1119 2002 5 2002 1120 2002 357 2003 383 2003 86 2003 1705 2004 1724 2004 1706 2004 1734 2005 295 2005 1217 2005 812 2006 1715 2006 813 2006 1722 2007 401 2007 400 2007 1065 2008 1637 2008 1465 2008 1302 2009 1193 2009 69 2009 1201 2010 1376 2010 905 2010 1481 2011 657 2011 1397 2011 980 2012 493 2012 84 2012 1705 2013 1197 2013 1724 2013 894 2014 1189 2014 1069 2014 1302 2015 1068 2015 255 2015 1031 2016 192 2016 45 2016 454 2017 1735 2017 458 2017 582 2018 1130 2018 574 2018 1181 2019 1198 2019 1728 2019 1335 2020 1141 2020 427 2020 1728 2021 1198 2021 1197 2021 1728 2022 1197 2022 1705 2022 1122 2023 1360 2023 1379 2023 801 2024 527 2024 799 2024 1736 2025 870 2025 392 2025 1228 2026 231 2026 1580 2026 1505 2027 283 2027 320 2027 1504 2028 327 2028 328 2028 219 2029 1048 2029 217 2029 553 2030 1296 2030 1271 2030 1681 2031 1582 2031 379 2031 521 2032 520 2032 662 2032 1540 2033 1510 2033 1509 2033 687 2034 689 2034 1481 2034 44 2035 903 2035 1031 2035 598 2036 21 2036 518 2036 7 2037 742 2037 8 2037 668 2038 776 2038 1367 2038 1712 2039 1571 2039 604 2039 1727 2040 989 2040 692 2040 195 2041 1594 2041 1270 2041 1685 2042 536 2042 302 2042 1259 2043 40 2043 570 2043 869 2044 223 2044 125 2044 83 2045 82 2045 1081 2045 166 2046 165 2046 590 2046 2 2047 1053 2047 820 2047 1255 2048 1257 2048 1065 2048 549 2049 551 2049 1339 2049 747 2050 1691 2050 1493 2050 1389 2051 832 2051 1139 2051 549 2052 1339 2052 838 2052 1737 2053 1327 2053 1329 2053 812 2054 814 2054 1371 2054 1695 2055 442 2055 26 2055 1182 2056 50 2056 1601 2056 960 2057 1689 2057 828 2057 509 2058 414 2058 1512 2058 301 2059 607 2059 309 2059 915 2060 304 2060 1536 2060 531 2061 396 2061 1738 2061 1031 2062 1507 2062 786 2062 1637 2063 1693 2063 501 2063 837 2064 838 2064 938 2064 1714 2065 1728 2065 1705 2065 1083 2066 1487 2066 1605 2066 58 2067 57 2067 856 2067 475 2068 279 2068 280 2068 537 2069 496 2069 487 2069 1663 2070 1003 2070 835 2070 1329 2071 185 2071 776 2071 1332 2072 1502 2072 748 2072 974 2073 1255 2073 1064 2073 1155 2074 1592 2074 1574 2074 66 2075 1250 2075 1490 2075 238 2076 248 2076 239 2076 1195 2077 1292 2077 513 2077 1324 2078 1628 2078 1325 2078 268 2079 1559 2079 1382 2079 1638 2080 1708 2080 1010 2080 1235 2081 997 2081 1061 2081 702 2082 844 2082 703 2082 1678 2083 619 2083 511 2083 525 2084 952 2084 951 2084 1719 2085 23 2085 22 2085 1210 2086 716 2086 63 2086 420 2087 408 2087 1438 2087 1723 2088 1164 2088 1170 2088 379 2089 1194 2089 1681 2089 1223 2090 1648 2090 1460 2090 1646 2091 250 2091 1736 2091 30 2092 98 2092 39 2092 1470 2093 355 2093 1068 2093 696 2094 1026 2094 697 2094 1695 2095 1248 2095 442 2095 203 2096 718 2096 1485 2096 577 2097 1259 2097 570 2097 777 2098 668 2098 1467 2098 766 2099 660 2099 661 2099 1257 2100 488 2100 644 2100 982 2101 892 2101 1355 2101 879 2102 1251 2102 864 2102 252 2103 802 2103 1412 2103 540 2104 1252 2104 1253 2104 626 2105 959 2105 627 2105 1723 2106 1716 2106 1732 2106 183 2107 1395 2107 184 2107 1723 2108 1732 2108 1164 2108 768 2109 1083 2109 1578 2109 1295 2110 1028 2110 1059 2110 1103 2111 340 2111 1432 2111 463 2112 1287 2112 1624 2112 1644 2113 1643 2113 1711 2113 1574 2114 1128 2114 1573 2114 1302 2115 255 2115 1146 2115 1256 2116 488 2116 1257 2116 810 2117 1220 2117 193 2117 1200 2118 814 2118 1376 2118 1179 2119 342 2119 1140 2119 1732 2120 1161 2120 1164 2120 1615 2121 100 2121 1616 2121 1114 2122 1113 2122 1479 2122 1516 2123 1081 2123 1132 2123 768 2124 767 2124 1083 2124 1374 2125 635 2125 1739 2125 1716 2126 1717 2126 1732 2126 581 2127 1740 2127 708 2127 26 2128 442 2128 232 2128 35 2129 611 2129 712 2129 507 2130 1307 2130 899 2130 70 2131 1678 2131 68 2131 1740 2132 1475 2132 708 2132 1504 2133 328 2133 433 2133 687 2134 962 2134 1507 2134 398 2135 808 2135 393 2135 337 2136 1639 2136 324 2136 1741 2137 1390 2137 1561 2137 266 2138 904 2138 751 2138 1410 2139 1337 2139 1336 2139 1732 2140 1162 2140 1161 2140 1134 2141 1465 2141 151 2141 464 2142 1078 2142 462 2142 1314 2143 1742 2143 873 2143 277 2144 278 2144 599 2144 296 2145 1619 2145 1620 2145 1033 2146 583 2146 1034 2146 1492 2147 790 2147 1550 2147 627 2148 789 2148 1168 2148 302 2149 536 2149 303 2149 1383 2150 1382 2150 1673 2150 378 2151 1291 2151 1292 2151 221 2152 400 2152 222 2152 482 2153 1314 2153 483 2153 1570 2154 896 2154 605 2154 1218 2155 1451 2155 728 2155 1520 2156 260 2156 876 2156 1432 2157 340 2157 111 2157 660 2158 1095 2158 1094 2158 1707 2159 711 2159 1729 2159 407 2160 1438 2160 408 2160 708 2161 1475 2161 709 2161 371 2162 1528 2162 374 2162 921 2163 603 2163 922 2163 1717 2164 1713 2164 1743 2164 1717 2165 1743 2165 1162 2165 108 2166 1425 2166 106 2166 1162 2167 1743 2167 1230 2167 679 2168 924 2168 1431 2168 1727 2169 692 2169 1530 2169 988 2170 14 2170 989 2170 861 2171 249 2171 401 2171 1585 2172 1252 2172 1622 2172 1100 2173 1101 2173 228 2173 301 2174 309 2174 308 2174 539 2175 1327 2175 1737 2175 697 2176 1314 2176 698 2176 1743 2177 1149 2177 1230 2177 1140 2178 738 2178 739 2178 1603 2179 946 2179 1137 2179 1743 2180 1107 2180 1149 2180 1087 2181 1615 2181 1384 2181 1629 2182 1587 2182 357 2182 934 2183 718 2183 1290 2183 722 2184 446 2184 532 2184 1487 2185 886 2185 1560 2185 202 2186 167 2186 738 2186 566 2187 44 2187 1358 2187 1726 2188 380 2188 1682 2188 576 2189 592 2189 594 2189 1263 2190 1744 2190 1264 2190 1593 2191 1429 2191 1594 2191 1452 2192 1621 2192 1453 2192 1223 2193 1524 2193 1573 2193 8 2194 677 2194 1166 2194 86 2195 1417 2195 979 2195 715 2196 714 2196 1524 2196 467 2197 466 2197 504 2197 487 2198 954 2198 1262 2198 201 2199 203 2199 881 2199 220 2200 1150 2200 221 2200 1082 2201 1107 2201 1063 2201 1550 2202 792 2202 705 2202 114 2203 1504 2203 353 2203 1063 2204 1107 2204 1743 2204 319 2205 646 2205 267 2205 1063 2206 1743 2206 1713 2206 1063 2207 1713 2207 912 2207 1480 2208 1479 2208 1488 2208 1099 2209 1116 2209 1118 2209 1211 2210 366 2210 1212 2210 1236 2211 1403 2211 1534 2211 1563 2212 1002 2212 1564 2212 709 2213 1476 2213 568 2213 218 2214 217 2214 1387 2214 1377 2215 1642 2215 546 2215 897 2216 409 2216 417 2216 1313 2217 1511 2217 1314 2217 1555 2218 367 2218 1294 2218 1419 2219 1014 2219 849 2219 67 2220 726 2220 725 2220 1229 2221 981 2221 1057 2221 375 2222 1432 2222 737 2222 1235 2223 474 2223 281 2223 518 2224 1413 2224 441 2224 904 2225 906 2225 416 2225 564 2226 1266 2226 1435 2226 643 2227 642 2227 1745 2227 342 2228 202 2228 1140 2228 24 2229 1159 2229 252 2229 1379 2230 1634 2230 235 2230 285 2231 374 2231 1528 2231 464 2232 35 2232 1590 2232 1484 2233 1573 2233 1128 2233 786 2234 1433 2234 787 2234 25 2235 1695 2235 26 2235 842 2236 1534 2236 843 2236 219 2237 1023 2237 1049 2237 1344 2238 1679 2238 534 2238 1443 2239 1640 2239 1698 2239 1692 2240 1494 2240 1298 2240 1454 2241 1311 2241 1498 2241 189 2242 1208 2242 1209 2242 841 2243 119 2243 711 2243 344 2244 1746 2244 1554 2244 1165 2245 601 2245 622 2245 1513 2246 601 2246 600 2246 461 2247 827 2247 1221 2247 299 2248 1020 2248 985 2248 537 2249 487 2249 629 2249 913 2250 912 2250 1710 2250 1674 2251 1747 2251 1143 2251 835 2252 444 2252 836 2252 1224 2253 797 2253 1692 2253 1138 2254 978 2254 1136 2254 1154 2255 714 2255 713 2255 147 2256 149 2256 148 2256 226 2257 56 2257 227 2257 819 2258 1554 2258 1748 2258 1627 2259 1626 2259 365 2259 966 2260 281 2260 953 2260 1191 2261 1641 2261 1658 2261 1497 2262 907 2262 458 2262 591 2263 251 2263 1646 2263 1552 2264 1551 2264 36 2264 706 2265 1586 2265 1035 2265 1251 2266 1250 2266 1545 2266 222 2267 400 2267 402 2267 1527 2268 1545 2268 66 2268 462 2269 1078 2269 269 2269 433 2270 99 2270 1225 2270 1443 2271 815 2271 747 2271 1708 2272 316 2272 1010 2272 213 2273 110 2273 1547 2273 494 2274 1649 2274 200 2274 1442 2275 1503 2275 818 2275 121 2276 123 2276 359 2276 1174 2277 1368 2277 1173 2277 288 2278 326 2278 1227 2278 1576 2279 453 2279 103 2279 476 2280 273 2280 1491 2280 1661 2281 1135 2281 672 2281 4 2282 506 2282 871 2282 244 2283 1036 2283 1039 2283 802 2284 804 2284 1412 2284 257 2285 733 2285 1062 2285 284 2286 1749 2286 285 2286 1631 2287 1613 2287 34 2287 1629 2288 982 2288 1587 2288 1006 2289 908 2289 1154 2289 141 2290 240 2290 76 2290 410 2291 1750 2291 411 2291 628 2292 1168 2292 1429 2292 286 2293 1400 2293 384 2293 354 2294 910 2294 1751 2294 965 2295 913 2295 1710 2295 907 2296 806 2296 618 2296 1313 2297 1226 2297 1424 2297 934 2298 1039 2298 850 2298 1507 2299 688 2299 687 2299 1303 2300 434 2300 1017 2300 534 2301 536 2301 1685 2301 1680 2302 929 2302 741 2302 1376 2303 1375 2303 1352 2303 1658 2304 1448 2304 498 2304 1674 2305 1618 2305 1747 2305 396 2306 249 2306 1738 2306 1036 2307 246 2307 245 2307 979 2308 1417 2308 18 2308 1742 2309 1303 2309 1272 2309 920 2310 449 2310 921 2310 1243 2311 1429 2311 1593 2311 1752 2312 1608 2312 1001 2312 1390 2313 1603 2313 1391 2313 728 2314 638 2314 637 2314 222 2315 147 2315 387 2315 555 2316 1135 2316 1661 2316 915 2317 739 2317 302 2317 568 2318 1548 2318 569 2318 423 2319 615 2319 376 2319 1052 2320 353 2320 1504 2320 1297 2321 1654 2321 656 2321 950 2322 949 2322 1502 2322 1726 2323 1682 2323 1425 2323 1377 2324 1633 2324 1642 2324 1481 2325 961 2325 687 2325 991 2326 87 2326 74 2326 1189 2327 1753 2327 1572 2327 1011 2328 1012 2328 607 2328 1754 2329 959 2329 626 2329 1056 2330 996 2330 965 2330 1356 2331 30 2331 32 2331 1227 2332 1228 2332 1586 2332 656 2333 1179 2333 916 2333 1679 2334 535 2334 534 2334 297 2335 296 2335 551 2335 636 2336 248 2336 821 2336 1466 2337 908 2337 1612 2337 468 2338 1288 2338 469 2338 1480 2339 935 2339 1158 2339 1596 2340 571 2340 1755 2340 352 2341 115 2341 353 2341 1117 2342 433 2342 1225 2342 1706 2343 1056 2343 965 2343 686 2344 1060 2344 830 2344 20 2345 1629 2345 357 2345 1417 2346 439 2346 19 2346 1034 2347 1627 2347 1555 2347 566 2348 1266 2348 564 2348 454 2349 433 2349 328 2349 1650 2350 1392 2350 1540 2350 514 2351 65 2351 67 2351 1622 2352 540 2352 539 2352 372 2353 647 2353 370 2353 1051 2354 1056 2354 1706 2354 1274 2355 1581 2355 1636 2355 302 2356 304 2356 915 2356 1684 2357 534 2357 1685 2357 573 2358 575 2358 1584 2358 267 2359 269 2359 319 2359 137 2360 71 2360 1043 2360 1548 2361 1756 2361 1757 2361 1548 2362 1757 2362 1549 2362 1479 2363 406 2363 1488 2363 1680 2364 1704 2364 1681 2364 322 2365 318 2365 323 2365 1549 2366 1757 2366 1758 2366 1562 2367 1478 2367 330 2367 462 2368 702 2368 704 2368 1549 2369 1758 2369 1672 2369 1672 2370 1758 2370 1759 2370 1320 2371 144 2371 1321 2371 1672 2372 1759 2372 1760 2372 1120 2373 871 2373 505 2373 110 2374 1721 2374 445 2374 792 2375 791 2375 706 2375 1103 2376 993 2376 340 2376 1760 2377 1759 2377 1761 2377 1516 2378 1132 2378 548 2378 211 2379 94 2379 96 2379 1760 2380 1761 2380 1755 2380 1755 2381 1761 2381 1762 2381 1382 2382 1326 2382 1325 2382 339 2383 338 2383 928 2383 244 2384 1039 2384 1038 2384 348 2385 350 2385 938 2385 10 2386 665 2386 1242 2386 663 2387 1657 2387 1178 2387 1755 2388 1762 2388 1763 2388 1763 2389 1762 2389 1764 2389 548 2390 1132 2390 1619 2390 274 2391 1266 2391 1357 2391 933 2392 230 2392 229 2392 1314 2393 872 2393 220 2393 1763 2394 1764 2394 592 2394 1602 2395 1661 2395 227 2395 1061 2396 294 2396 450 2396 592 2397 1764 2397 1765 2397 503 2398 466 2398 634 2398 592 2399 1765 2399 1766 2399 668 2400 670 2400 1468 2400 1372 2401 1371 2401 814 2401 592 2402 1766 2402 593 2402 271 2403 199 2403 198 2403 581 2404 1767 2404 1768 2404 29 2405 1498 2405 641 2405 593 2406 1766 2406 1769 2406 1704 2407 1582 2407 1681 2407 268 2408 1325 2408 1628 2408 593 2409 1769 2409 1770 2409 1257 2410 644 2410 1065 2410 763 2411 369 2411 480 2411 1430 2412 1431 2412 948 2412 1621 2413 1538 2413 1450 2413 1770 2414 1769 2414 1771 2414 609 2415 608 2415 544 2415 288 2416 1227 2416 791 2416 1770 2417 1771 2417 1772 2417 72 2418 71 2418 1025 2418 569 2419 1549 2419 1672 2419 909 2420 216 2420 389 2420 1772 2421 1771 2421 259 2421 259 2422 1771 2422 1773 2422 1368 2423 857 2423 1173 2423 299 2424 985 2424 300 2424 395 2425 394 2425 858 2425 1337 2426 1411 2426 882 2426 1483 2427 556 2427 227 2427 349 2428 838 2428 57 2428 259 2429 1773 2429 876 2429 876 2430 1773 2430 1774 2430 691 2431 675 2431 674 2431 1567 2432 373 2432 1147 2432 1617 2433 1618 2433 1674 2433 876 2434 1774 2434 1520 2434 1520 2435 1774 2435 1775 2435 68 2436 784 2436 69 2436 202 2437 201 2437 881 2437 1520 2438 1775 2438 1744 2438 1744 2439 1775 2439 1776 2439 695 2440 509 2440 770 2440 910 2441 958 2441 1751 2441 1336 2442 55 2442 54 2442 1744 2443 1776 2443 1777 2443 1363 2444 227 2444 56 2444 938 2445 350 2445 1366 2445 1744 2446 1777 2446 1264 2446 1264 2447 1777 2447 1778 2447 681 2448 88 2448 682 2448 473 2449 110 2449 112 2449 735 2450 1617 2450 1674 2450 182 2451 181 2451 1779 2451 1722 2452 861 2452 401 2452 1145 2453 506 2453 4 2453 1264 2454 1778 2454 1767 2454 1767 2455 1778 2455 1780 2455 376 2456 234 2456 699 2456 1115 2457 1611 2457 914 2457 439 2458 278 2458 1781 2458 1767 2459 1780 2459 1782 2459 517 2460 112 2460 268 2460 1767 2461 1782 2461 1768 2461 1373 2462 778 2462 780 2462 673 2463 227 2463 672 2463 1379 2464 376 2464 1123 2464 1768 2465 1782 2465 1783 2465 1768 2466 1783 2466 1740 2466 1740 2467 1783 2467 1784 2467 168 2468 167 2468 881 2468 619 2469 395 2469 512 2469 934 2470 1653 2470 342 2470 38 2471 1305 2471 740 2471 848 2472 342 2472 1179 2472 35 2473 712 2473 119 2473 1740 2474 1784 2474 1475 2474 1475 2475 1784 2475 1785 2475 1623 2476 1366 2476 1101 2476 1380 2477 1517 2477 1654 2477 1475 2478 1785 2478 1786 2478 519 2479 368 2479 1719 2479 909 2480 4 2480 1261 2480 1475 2481 1786 2481 1476 2481 395 2482 858 2482 512 2482 453 2483 423 2483 720 2483 1236 2484 1534 2484 842 2484 1476 2485 1786 2485 1787 2485 82 2486 376 2486 375 2486 509 2487 694 2487 1533 2487 1476 2488 1787 2488 1699 2488 1699 2489 1787 2489 1756 2489 491 2490 54 2490 53 2490 963 2491 717 2491 716 2491 1699 2492 1756 2492 1548 2492 750 2493 589 2493 1285 2493 1463 2494 1462 2494 1401 2494 354 2495 1751 2495 355 2495 617 2496 1047 2496 618 2496 433 2497 435 2497 957 2497 1321 2498 1397 2498 657 2498 1618 2499 1096 2499 1095 2499 1212 2500 272 2500 1213 2500 1028 2501 1295 2501 716 2501 1213 2502 272 2502 237 2502 1073 2503 1725 2503 1072 2503 986 2504 806 2504 78 2504 872 2505 1150 2505 220 2505 279 2506 1044 2506 1572 2506 1006 2507 734 2507 1674 2507 1072 2508 1560 2508 1119 2508 809 2509 145 2509 1320 2509 1213 2510 237 2510 61 2510 1213 2511 61 2511 1753 2511 767 2512 1240 2512 437 2512 1421 2513 1241 2513 1005 2513 1566 2514 1231 2514 1399 2514 203 2515 1485 2515 305 2515 860 2516 1675 2516 1738 2516 426 2517 1378 2517 1492 2517 1652 2518 573 2518 1676 2518 1693 2519 645 2519 1595 2519 1678 2520 511 2520 595 2520 816 2521 538 2521 1493 2521 1753 2522 61 2522 1572 2522 61 2523 60 2523 1572 2523 601 2524 650 2524 622 2524 71 2525 73 2525 1238 2525 629 2526 630 2526 598 2526 1572 2527 60 2527 279 2527 744 2528 1035 2528 988 2528 420 2529 1438 2529 662 2529 272 2530 1212 2530 1788 2530 1677 2531 1537 2531 487 2531 1528 2532 371 2532 1186 2532 1788 2533 1212 2533 366 2533 293 2534 441 2534 578 2534 1788 2535 366 2535 1789 2535 554 2536 682 2536 1445 2536 712 2537 1746 2537 1729 2537 1631 2538 208 2538 1613 2538 1702 2539 1608 2539 1752 2539 1789 2540 366 2540 365 2540 1755 2541 1763 2541 1596 2541 1190 2542 1191 2542 1474 2542 1673 2543 1559 2543 1439 2543 296 2544 1620 2544 224 2544 1789 2545 365 2545 1790 2545 565 2546 1032 2546 903 2546 1423 2547 1405 2547 418 2547 1092 2548 120 2548 1577 2548 382 2549 381 2549 982 2549 533 2550 660 2550 722 2550 148 2551 957 2551 1080 2551 1446 2552 1748 2552 611 2552 146 2553 1080 2553 1226 2553 284 2554 1148 2554 1749 2554 473 2555 112 2555 517 2555 1790 2556 365 2556 1626 2556 1576 2557 1324 2557 1361 2557 343 2558 342 2558 1290 2558 743 2559 705 2559 707 2559 1790 2560 1626 2560 1791 2560 1626 2561 585 2561 1791 2561 1791 2562 585 2562 1792 2562 158 2563 1025 2563 137 2563 1622 2564 1737 2564 777 2564 56 2565 226 2565 57 2565 1561 2566 1392 2566 1650 2566 992 2567 74 2567 59 2567 675 2568 1036 2568 828 2568 1604 2569 1605 2569 795 2569 1564 2570 484 2570 1565 2570 1792 2571 585 2571 584 2571 1258 2572 332 2572 188 2572 305 2573 1209 2573 306 2573 1574 2574 714 2574 1155 2574 669 2575 1652 2575 670 2575 197 2576 1593 2576 195 2576 584 2577 1779 2577 1793 2577 275 2578 1664 2578 276 2578 1794 2579 360 2579 123 2579 1615 2580 727 2580 100 2580 788 2581 910 2581 88 2581 1307 2582 506 2582 1146 2582 1795 2583 1779 2583 181 2583 1634 2584 1102 2584 236 2584 0 2585 464 2585 1 2585 239 2586 1434 2586 962 2586 671 2587 1770 2587 258 2587 459 2588 404 2588 460 2588 1507 2589 1434 2589 786 2589 1793 2590 1779 2590 1795 2590 1374 2591 1739 2591 778 2591 1150 2592 874 2592 860 2592 181 2593 1796 2593 1795 2593 1797 2594 1796 2594 180 2594 1502 2595 1133 2595 748 2595 1796 2596 181 2596 180 2596 51 2597 620 2597 52 2597 867 2598 153 2598 1566 2598 647 2599 926 2599 1187 2599 402 2600 149 2600 147 2600 180 2601 684 2601 1797 2601 1781 2602 278 2602 20 2602 263 2603 613 2603 171 2603 1108 2604 986 2604 169 2604 1468 2605 670 2605 1794 2605 813 2606 1375 2606 814 2606 1797 2607 684 2607 683 2607 581 2608 659 2608 1767 2608 1797 2609 683 2609 1798 2609 1301 2610 179 2610 978 2610 1389 2611 364 2611 832 2611 1044 2612 1045 2612 1069 2612 1622 2613 777 2613 1585 2613 518 2614 1457 2614 1413 2614 1486 2615 1340 2615 1798 2615 84 2616 271 2616 24 2616 1486 2617 1798 2617 683 2617 266 2618 1201 2618 904 2618 841 2619 1577 2619 119 2619 1425 2620 1682 2620 1426 2620 91 2621 1269 2621 92 2621 385 2622 1148 2622 284 2622 1070 2623 545 2623 633 2623 1488 2624 1606 2624 1480 2624 1235 2625 450 2625 474 2625 49 2626 1498 2626 28 2626 706 2627 1227 2627 1586 2627 801 2628 800 2628 189 2628 1288 2629 1632 2629 1656 2629 740 2630 1305 2630 1340 2630 210 2631 479 2631 211 2631 1683 2632 917 2632 1426 2632 268 2633 105 2633 269 2633 1478 2634 824 2634 1112 2634 740 2635 1340 2635 1486 2635 1363 2636 1483 2636 227 2636 1350 2637 1471 2637 1462 2637 539 2638 544 2638 1330 2638 1638 2639 1010 2639 877 2639 11 2640 1317 2640 1720 2640 281 2641 911 2641 953 2641 271 2642 495 2642 270 2642 1362 2643 1348 2643 1663 2643 1579 2644 1213 2644 1753 2644 573 2645 1584 2645 1676 2645 1344 2646 534 2646 1684 2646 1460 2647 723 2647 1525 2647 434 2648 433 2648 1017 2648 325 2649 420 2649 21 2649 1265 2650 1435 2650 1266 2650 103 2651 1222 2651 1576 2651 1313 2652 1424 2652 1511 2652 289 2653 288 2653 791 2653 634 2654 1373 2654 1322 2654 478 2655 95 2655 94 2655 568 2656 1699 2656 1548 2656 620 2657 1799 2657 621 2657 1647 2658 1736 2658 392 2658 542 2659 1800 2659 651 2659 621 2660 1799 2660 1553 2660 526 2661 951 2661 561 2661 982 2662 1629 2662 1191 2662 621 2663 1553 2663 1552 2663 31 2664 273 2664 475 2664 391 2665 209 2665 314 2665 1482 2666 1712 2666 449 2666 409 2667 1570 2667 410 2667 1709 2668 1801 2668 1802 2668 1709 2669 1802 2669 1535 2669 1666 2670 631 2670 1309 2670 248 2671 247 2671 1433 2671 1407 2672 588 2672 1408 2672 1535 2673 1802 2673 1803 2673 1599 2674 208 2674 875 2674 594 2675 593 2675 671 2675 911 2676 1597 2676 1505 2676 1400 2677 286 2677 693 2677 1146 2678 255 2678 1307 2678 448 2679 1519 2679 43 2679 1535 2680 1803 2680 620 2680 620 2681 1803 2681 1799 2681 1752 2682 1001 2682 1000 2682 688 2683 1032 2683 565 2683 413 2684 331 2684 1513 2684 1703 2685 917 2685 1683 2685 627 2686 958 2686 788 2686 1362 2687 834 2687 477 2687 1465 2688 501 2688 151 2688 276 2689 1460 2689 1609 2689 944 2690 946 2690 1603 2690 970 2691 1649 2691 493 2691 698 2692 1314 2692 482 2692 1804 2693 1801 2693 1709 2693 899 2694 1307 2694 1625 2694 644 2695 1693 2695 1637 2695 426 2696 1084 2696 1085 2696 959 2697 958 2697 627 2697 372 2698 1567 2698 249 2698 1804 2699 1709 2699 1643 2699 1805 2700 561 2700 1349 2700 1643 2701 1806 2701 1804 2701 291 2702 460 2702 1807 2702 1511 2703 1742 2703 1314 2703 750 2704 729 2704 589 2704 1806 2705 1643 2705 1633 2705 1632 2706 1176 2706 1633 2706 1633 2707 1176 2707 1808 2707 1225 2708 1224 2708 1097 2708 1071 2709 702 2709 462 2709 1137 2710 946 2710 1138 2710 941 2711 688 2711 1630 2711 1088 2712 696 2712 1514 2712 1633 2713 1808 2713 1806 2713 580 2714 894 2714 1069 2714 65 2715 1527 2715 66 2715 1634 2716 477 2716 1102 2716 624 2717 1192 2717 563 2717 1173 2718 394 2718 729 2718 1647 2719 1646 2719 1736 2719 1339 2720 472 2720 1687 2720 416 2721 897 2721 417 2721 205 2722 889 2722 888 2722 387 2723 147 2723 146 2723 1008 2724 1007 2724 90 2724 602 2725 601 2725 1393 2725 1532 2726 1360 2726 1122 2726 1341 2727 1536 2727 419 2727 1136 2728 978 2728 563 2728 1034 2729 585 2729 1626 2729 509 2730 623 2730 510 2730 182 2731 583 2731 1033 2731 1137 2732 1136 2732 563 2732 1137 2733 563 2733 562 2733 1625 2734 257 2734 1406 2734 1270 2735 1594 2735 1167 2735 562 2736 1396 2736 1137 2736 767 2737 397 2737 1005 2737 1575 2738 1537 2738 1677 2738 106 2739 265 2739 1809 2739 1220 2740 703 2740 844 2740 333 2741 16 2741 15 2741 1001 2742 698 2742 482 2742 624 2743 563 2743 978 2743 1621 2744 1450 2744 1453 2744 971 2745 1754 2745 626 2745 1330 2746 11 2746 1327 2746 1302 2747 69 2747 1470 2747 1518 2748 1448 2748 1658 2748 695 2749 694 2749 509 2749 611 2750 1748 2750 1554 2750 609 2751 1754 2751 971 2751 583 2752 1779 2752 584 2752 1137 2753 1396 2753 1391 2753 665 2754 932 2754 1243 2754 1618 2755 766 2755 1747 2755 1233 2756 1738 2756 1675 2756 1689 2757 1058 2757 828 2757 987 2758 988 2758 1727 2758 286 2759 285 2759 1151 2759 177 2760 1791 2760 178 2760 178 2761 1791 2761 1792 2761 51 2762 1535 2762 620 2762 1104 2763 1103 2763 1432 2763 680 2764 136 2764 135 2764 584 2765 1669 2765 1792 2765 1792 2766 1669 2766 178 2766 239 2767 962 2767 35 2767 538 2768 1492 2768 1493 2768 1175 2769 1390 2769 1741 2769 34 2770 130 2770 612 2770 779 2771 1739 2771 635 2771 1741 2772 1808 2772 1176 2772 1741 2773 1176 2773 1175 2773 1001 2774 482 2774 1002 2774 649 2775 599 2775 278 2775 1561 2776 1806 2776 1808 2776 1561 2777 1808 2777 1741 2777 1182 2778 1711 2778 154 2778 955 2779 355 2779 1754 2779 1379 2780 1360 2780 1634 2780 1006 2781 1674 2781 701 2781 1529 2782 1319 2782 430 2782 1806 2783 1561 2783 1804 2783 1804 2784 1561 2784 1650 2784 1188 2785 1579 2785 1189 2785 1646 2786 251 2786 250 2786 890 2787 613 2787 262 2787 1539 2788 1802 2788 1651 2788 1651 2789 1802 2789 1801 2789 1651 2790 1801 2790 1650 2790 1810 2791 1401 2791 334 2791 675 2792 1059 2792 676 2792 763 2793 480 2793 764 2793 1069 2794 1572 2794 1044 2794 578 2795 200 2795 1649 2795 843 2796 1370 2796 1667 2796 1650 2797 1801 2797 1804 2797 1803 2798 1802 2798 1539 2798 447 2799 721 2799 1664 2799 490 2800 530 2800 531 2800 504 2801 1811 2801 937 2801 268 2802 1009 2802 1559 2802 1803 2803 1812 2803 524 2803 1127 2804 458 2804 1735 2804 1803 2805 1539 2805 1812 2805 1474 2806 969 2806 893 2806 1157 2807 1141 2807 1513 2807 193 2808 1370 2808 194 2808 524 2809 1799 2809 1803 2809 558 2810 560 2810 1148 2810 654 2811 653 2811 1501 2811 1553 2812 524 2812 1688 2812 712 2813 1554 2813 1746 2813 1669 2814 17 2814 977 2814 1553 2815 1799 2815 524 2815 500 2816 499 2816 574 2816 175 2817 727 2817 1615 2817 898 2818 899 2818 1428 2818 1241 2819 1421 2819 552 2819 1805 2820 1553 2820 1688 2820 1041 2821 1489 2821 1523 2821 824 2822 407 2822 1479 2822 1321 2823 144 2823 640 2823 649 2824 254 2824 599 2824 1042 2825 1041 2825 91 2825 449 2826 1530 2826 424 2826 411 2827 1750 2827 1452 2827 823 2828 407 2828 824 2828 1805 2829 1551 2829 1553 2829 101 2830 769 2830 1578 2830 758 2831 38 2831 132 2831 546 2832 1644 2832 547 2832 1351 2833 37 2833 1349 2833 879 2834 1490 2834 1250 2834 1677 2835 189 2835 1575 2835 490 2836 531 2836 645 2836 1349 2837 37 2837 1805 2837 137 2838 292 2838 159 2838 1805 2839 37 2839 1551 2839 570 2840 40 2840 968 2840 163 2841 1576 2841 1360 2841 1461 2842 1304 2842 1351 2842 1351 2843 1304 2843 1306 2843 1314 2844 873 2844 872 2844 206 2845 455 2845 800 2845 232 2846 1697 2846 233 2846 1351 2847 1306 2847 37 2847 1045 2848 1656 2848 1070 2848 1461 2849 1463 2849 1340 2849 151 2850 502 2850 152 2850 1461 2851 1340 2851 1304 2851 527 2852 535 2852 528 2852 236 2853 1102 2853 1333 2853 751 2854 904 2854 416 2854 1730 2855 1746 2855 344 2855 1493 2856 817 2856 816 2856 537 2857 598 2857 293 2857 1340 2858 1463 2858 1798 2858 1158 2859 937 2859 1811 2859 314 2860 209 2860 315 2860 240 2861 97 2861 77 2861 1205 2862 1676 2862 1308 2862 1798 2863 1463 2863 1810 2863 1798 2864 1810 2864 1797 2864 1278 2865 719 2865 1522 2865 1684 2866 302 2866 739 2866 986 2867 80 2867 1344 2867 438 2868 1241 2868 1445 2868 1659 2869 1797 2869 1810 2869 1024 2870 1098 2870 1298 2870 1770 2871 1772 2871 258 2871 1269 2872 858 2872 857 2872 265 2873 1201 2873 266 2873 333 2874 1796 2874 1659 2874 606 2875 258 2875 260 2875 464 2876 1590 2876 1078 2876 465 2877 1323 2877 779 2877 1659 2878 1796 2878 1797 2878 15 2879 1795 2879 333 2879 333 2880 1795 2880 1796 2880 663 2881 417 2881 1657 2881 975 2882 1408 2882 587 2882 1571 2883 538 2883 1569 2883 12 2884 1274 2884 13 2884 15 2885 1793 2885 1795 2885 204 2886 529 2886 441 2886 1730 2887 1729 2887 1746 2887 731 2888 1068 2888 956 2888 1635 2889 1442 2889 489 2889 382 2890 1057 2890 383 2890 584 2891 1793 2891 1669 2891 248 2892 1434 2892 239 2892 1669 2893 1793 2893 15 2893 1449 2894 1451 2894 1218 2894 182 2895 1779 2895 583 2895 1335 2896 1262 2896 954 2896 17 2897 625 2897 977 2897 1218 2898 728 2898 637 2898 1760 2899 571 2899 1672 2899 944 2900 468 2900 945 2900 177 2901 1790 2901 1791 2901 319 2902 517 2902 646 2902 455 2903 454 2903 1046 2903 651 2904 1800 2904 485 2904 1300 2905 1790 2905 177 2905 1607 2906 1054 2906 352 2906 849 2907 1015 2907 785 2907 609 2908 955 2908 1754 2908 1032 2909 1031 2909 903 2909 1491 2910 1789 2910 1300 2910 1596 2911 1763 2911 576 2911 433 2912 1534 2912 1403 2912 711 2913 1687 2913 840 2913 995 2914 1143 2914 1813 2914 276 2915 1225 2915 328 2915 1300 2916 1789 2916 1790 2916 1392 2917 1391 2917 1396 2917 1789 2918 1491 2918 273 2918 1334 2919 1249 2919 1254 2919 1789 2920 273 2920 1788 2920 968 2921 42 2921 182 2921 1586 2922 12 2922 1035 2922 1812 2923 1539 2923 525 2923 823 2924 509 2924 1438 2924 551 2925 296 2925 224 2925 1409 2926 1232 2926 999 2926 973 2927 1458 2927 1256 2927 273 2928 272 2928 1788 2928 169 2929 1344 2929 1684 2929 362 2930 364 2930 1389 2930 488 2931 490 2931 644 2931 255 2932 1068 2932 256 2932 269 2933 83 2933 1631 2933 257 2934 256 2934 733 2934 1499 2935 5 2935 1119 2935 437 2936 1240 2936 438 2936 53 2937 1346 2937 491 2937 795 2938 99 2938 1604 2938 1027 2939 62 2939 693 2939 661 2940 533 2940 446 2940 1592 2941 458 2941 1127 2941 319 2942 1172 2942 33 2942 1519 2943 447 2943 1664 2943 540 2944 1614 2944 541 2944 1199 2945 1033 2945 774 2945 1259 2946 134 2946 40 2946 168 2947 1108 2947 169 2947 1103 2948 187 2948 1444 2948 908 2949 1006 2949 79 2949 619 2950 512 2950 511 2950 1394 2951 957 2951 150 2951 1320 2952 145 2952 144 2952 1772 2953 259 2953 258 2953 1303 2954 1017 2954 1272 2954 431 2955 1546 2955 782 2955 1045 2956 1288 2956 1656 2956 1361 2957 1324 2957 1326 2957 1316 2958 197 2958 1458 2958 214 2959 120 2959 125 2959 1555 2960 1627 2960 367 2960 601 2961 542 2961 650 2961 1428 2962 1048 2962 898 2962 1399 2963 1018 2963 1117 2963 1514 2964 696 2964 698 2964 1510 2965 1396 2965 952 2965 1247 2966 373 2966 374 2966 1240 2967 1241 2967 438 2967 739 2968 169 2968 1684 2968 606 2969 260 2969 1520 2969 1199 2970 182 2970 1033 2970 88 2971 681 2971 788 2971 716 2972 1210 2972 1028 2972 402 2973 401 2973 149 2973 1335 2974 543 2974 542 2974 287 2975 1087 2975 326 2975 673 2976 548 2976 227 2976 774 2977 1555 2977 710 2977 1563 2978 1638 2978 1702 2978 458 2979 1612 2979 908 2979 99 2980 1244 2980 1246 2980 1228 2981 229 2981 231 2981 597 2982 547 2982 596 2982 926 2983 927 2983 690 2983 1327 2984 11 2984 1328 2984 1191 2985 277 2985 865 2985 127 2986 685 2986 128 2986 1711 2987 1709 2987 154 2987 374 2988 285 2988 1749 2988 1395 2989 1338 2989 184 2989 931 2990 930 2990 1016 2990 465 2991 635 2991 466 2991 1388 2992 991 2992 77 2992 469 2993 1288 2993 1045 2993 1206 2994 360 2994 1794 2994 1103 2995 186 2995 341 2995 18 2996 20 2996 979 2996 8 2997 742 2997 677 2997 1294 2998 1211 2998 1579 2998 1147 2999 373 2999 351 2999 355 3000 1751 3000 958 3000 1372 3001 1200 3001 265 3001 1809 3002 265 3002 264 3002 249 3003 1814 3003 1037 3003 1458 3004 1635 3004 489 3004 339 3005 928 3005 1505 3005 567 3006 1199 3006 774 3006 1219 3007 1278 3007 249 3007 327 3008 113 3008 1265 3008 225 3009 1620 3009 1721 3009 719 3010 718 3010 1522 3010 1630 3011 688 3011 565 3011 439 3012 649 3012 278 3012 1342 3013 1332 3013 1286 3013 920 3014 922 3014 1260 3014 1118 3015 1097 3015 1099 3015 1041 3016 1523 3016 1269 3016 873 3017 1273 3017 1508 3017 1755 3018 571 3018 1760 3018 1065 3019 1465 3019 1066 3019 301 3020 300 3020 1011 3020 825 3021 827 3021 290 3021 334 3022 624 3022 16 3022 1258 3023 188 3023 187 3023 202 3024 881 3024 167 3024 614 3025 613 3025 889 3025 998 3026 999 3026 1531 3026 553 3027 552 3027 1296 3027 1145 3028 4 3028 1655 3028 1237 3029 560 3029 559 3029 1207 3030 3 3030 886 3030 1135 3031 548 3031 672 3031 880 3032 855 3032 1109 3032 496 3033 969 3033 497 3033 653 3034 950 3034 1501 3034 1645 3035 1342 3035 1285 3035 1069 3036 1070 3036 633 3036 992 3037 59 3037 75 3037 1573 3038 1648 3038 1223 3038 1477 3039 1043 3039 71 3039 172 3040 614 3040 204 3040 70 3041 399 3041 1678 3041 819 3042 1748 3042 1446 3042 153 3043 1231 3043 1566 3043 1605 3044 1604 3044 1578 3044 1701 3045 559 3045 558 3045 787 3046 247 3046 809 3046 477 3047 834 3047 836 3047 70 3048 69 3048 1193 3048 598 3049 518 3049 293 3049 800 3050 1208 3050 189 3050 1123 3051 1122 3051 1379 3051 1701 3052 1435 3052 559 3052 290 3053 827 3053 461 3053 241 3054 632 3054 242 3054 1183 3055 1421 3055 1184 3055 1315 3056 975 3056 976 3056 834 3057 1663 3057 835 3057 210 3058 1216 3058 332 3058 53 3059 1347 3059 1346 3059 1602 3060 555 3060 1661 3060 1251 3061 1556 3061 862 3061 1487 3062 1560 3062 1725 3062 1810 3063 334 3063 1659 3063 1742 3064 1272 3064 873 3064 399 3065 393 3065 619 3065 666 3066 117 3066 116 3066 934 3067 245 3067 244 3067 902 3068 1447 3068 485 3068 787 3069 1433 3069 247 3069 214 3070 223 3070 225 3070 108 3071 595 3071 1726 3071 1144 3072 298 3072 1110 3072 1517 3073 1179 3073 1654 3073 815 3074 817 3074 747 3074 665 3075 610 3075 932 3075 593 3076 1770 3076 671 3076 1084 3077 692 3077 990 3077 927 3078 1422 3078 1731 3078 1108 3079 880 3079 1109 3079 1482 3080 538 3080 1712 3080 426 3081 425 3081 1084 3081 1263 3082 1520 3082 1744 3082 38 3083 37 3083 1306 3083 1358 3084 1357 3084 1266 3084 512 3085 1489 3085 513 3085 942 3086 130 3086 129 3086 1670 3087 391 3087 1708 3087 1336 3088 759 3088 55 3088 1502 3089 923 3089 1133 3089 1736 3090 250 3090 870 3090 918 3091 1686 3091 1371 3091 552 3092 1421 3092 1183 3092 754 3093 759 3093 885 3093 1563 3094 1565 3094 290 3094 765 3095 446 3095 448 3095 1187 3096 926 3096 1319 3096 13 3097 591 3097 1646 3097 886 3098 1499 3098 1560 3098 654 3099 1501 3099 1312 3099 1047 3100 454 3100 618 3100 1255 3101 1065 3101 1064 3101 203 3102 1290 3102 718 3102 1726 3103 378 3103 380 3103 197 3104 1243 3104 1593 3104 540 3105 731 3105 1614 3105 1102 3106 210 3106 1103 3106 1060 3107 1020 3107 299 3107 1019 3108 1018 3108 1675 3108 842 3109 844 3109 702 3109 281 3110 283 3110 1597 3110 1272 3111 1017 3111 1019 3111 249 3112 251 3112 150 3112 431 3113 1027 3113 1546 3113 1367 3114 185 3114 500 3114 775 3115 1329 3115 776 3115 1254 3116 1049 3116 1022 3116 1715 3117 1686 3117 1696 3117 45 3118 765 3118 448 3118 923 3119 925 3119 1133 3119 1700 3120 371 3120 370 3120 1121 3121 1152 3121 1334 3121 468 3122 470 3122 475 3122 62 3123 1028 3123 1210 3123 1175 3124 1603 3124 1390 3124 1511 3125 1424 3125 1055 3125 857 3126 394 3126 1173 3126 35 3127 961 3127 1590 3127 1704 3128 1683 3128 1582 3128 416 3129 906 3129 895 3129 838 3130 1414 3130 938 3130 1737 3131 1329 3131 775 3131 980 3132 1472 3132 493 3132 960 3133 1267 3133 934 3133 1462 3134 1471 3134 1192 3134 86 3135 85 3135 649 3135 268 3136 1382 3136 1325 3136 765 3137 661 3137 446 3137 553 3138 789 3138 554 3138 192 3139 194 3139 1344 3139 1166 3140 901 3140 315 3140 283 3141 336 3141 319 3141 1622 3142 539 3142 1737 3142 309 3143 522 3143 310 3143 1807 3144 1733 3144 291 3144 361 3145 1496 3145 359 3145 1177 3146 1176 3146 1632 3146 371 3147 1567 3147 372 3147 184 3148 1338 3148 1185 3148 1011 3149 607 3149 301 3149 1127 3150 1735 3150 454 3150 565 3151 903 3151 794 3151 1328 3152 11 3152 1720 3152 132 3153 38 3153 133 3153 254 3154 368 3154 519 3154 514 3155 67 3155 725 3155 1781 3156 20 3156 439 3156 1576 3157 1222 3157 1628 3157 1573 3158 1668 3158 1648 3158 342 3159 1653 3159 1290 3159 1630 3160 565 3160 1701 3160 555 3161 856 3161 1135 3161 1271 3162 1296 3162 1442 3162 1707 3163 1730 3163 344 3163 1111 3164 1219 3164 810 3164 236 3165 699 3165 234 3165 1424 3166 1416 3166 435 3166 659 3167 1264 3167 1767 3167 1118 3168 1117 3168 1225 3168 1177 3169 1632 3169 1288 3169 967 3170 1104 3170 377 3170 465 3171 428 3171 831 3171 720 3172 104 3172 453 3172 349 3173 939 3173 838 3173 509 3174 412 3174 414 3174 1579 3175 1753 3175 1189 3175 1774 3176 752 3176 1775 3176 418 3177 1405 3177 419 3177 1775 3178 752 3178 1776 3178 767 3179 1005 3179 1240 3179 548 3180 900 3180 1516 3180 1274 3181 1636 3181 1394 3181 178 3182 977 3182 179 3182 682 3183 90 3183 1007 3183 821 3184 248 3184 238 3184 1778 3185 1777 3185 883 3185 1778 3186 883 3186 1780 3186 1470 3187 69 3187 784 3187 1780 3188 883 3188 1782 3188 1782 3189 883 3189 878 3189 308 3190 523 3190 311 3190 1782 3191 878 3191 1783 3191 11 3192 10 3192 1317 3192 907 3193 1497 3193 908 3193 1159 3194 1697 3194 803 3194 1784 3195 1783 3195 863 3195 1021 3196 337 3196 1734 3196 14 3197 822 3197 989 3197 1784 3198 863 3198 1785 3198 192 3199 1344 3199 1345 3199 1786 3200 1785 3200 845 3200 1152 3201 505 3201 1249 3201 1786 3202 845 3202 1815 3202 1786 3203 1815 3203 1787 3203 1787 3204 1815 3204 1756 3204 531 3205 1738 3205 1233 3205 28 3206 1498 3206 29 3206 905 3207 603 3207 906 3207 493 3208 1649 3208 494 3208 1098 3209 1024 3209 1023 3209 289 3210 791 3210 790 3210 1509 3211 952 3211 525 3211 1757 3212 839 3212 1758 3212 1813 3213 1143 3213 1747 3213 1737 3214 775 3214 777 3214 1253 3215 731 3215 540 3215 693 3216 62 3216 64 3216 603 3217 605 3217 895 3217 43 3218 1519 3218 1357 3218 249 3219 1278 3219 1814 3219 495 3220 200 3220 270 3220 1762 3221 1761 3221 772 3221 1762 3222 772 3222 1816 3222 1762 3223 1816 3223 1764 3223 530 3224 1184 3224 396 3224 1481 3225 689 3225 657 3225 1764 3226 1816 3226 1765 3226 321 3227 323 3227 577 3227 194 3228 138 3228 1679 3228 383 3229 1057 3229 84 3229 1766 3230 1765 3230 1365 3230 1463 3231 1401 3231 1810 3231 991 3232 992 3232 77 3232 1766 3233 1365 3233 1769 3233 1769 3234 1365 3234 756 3234 855 3235 616 3235 986 3235 1217 3236 1021 3236 1734 3236 1769 3237 756 3237 1771 3237 1771 3238 756 3238 755 3238 1794 3239 123 3239 1468 3239 1771 3240 755 3240 1773 3240 769 3241 397 3241 767 3241 376 3242 162 3242 161 3242 1532 3243 376 3243 1531 3243 1773 3244 753 3244 1774 3244 1496 3245 1062 3245 359 3245 621 3246 1552 3246 317 3246 1774 3247 753 3247 752 3247 778 3248 1739 3248 779 3248 1111 3249 890 3249 1219 3249 629 3250 487 3250 465 3250 1696 3251 1686 3251 918 3251 216 3252 106 3252 1809 3252 797 3253 1225 3253 99 3253 1372 3254 814 3254 1200 3254 216 3255 1809 3255 264 3255 1665 3256 1479 3256 1478 3256 711 3257 712 3257 1729 3257 811 3258 411 3258 1450 3258 589 3259 807 3259 590 3259 257 3260 586 3260 1406 3260 1508 3261 1675 3261 860 3261 837 3262 938 3262 549 3262 524 3263 526 3263 1688 3263 338 3264 337 3264 1021 3264 742 3265 678 3265 677 3265 822 3266 13 3266 173 3266 586 3267 361 3267 587 3267 1515 3268 1608 3268 1702 3268 1042 3269 91 3269 947 3269 777 3270 776 3270 668 3270 1794 3271 670 3271 1206 3271 1381 3272 598 3272 630 3272 542 3273 486 3273 1800 3273 558 3274 1148 3274 385 3274 403 3275 1807 3275 460 3275 885 3276 1337 3276 882 3276 932 3277 628 3277 1429 3277 459 3278 1221 3278 762 3278 430 3279 676 3279 1028 3279 1265 3280 1237 3280 1435 3280 286 3281 384 3281 284 3281 601 3282 1141 3282 542 3282 655 3283 190 3283 1209 3283 1287 3284 1220 3284 249 3284 34 3285 612 3285 611 3285 1581 3286 957 3286 1636 3286 547 3287 1644 3287 1711 3287 1412 3288 804 3288 1413 3288 1318 3289 1047 3289 307 3289 222 3290 387 3290 386 3290 261 3291 655 3291 262 3291 1424 3292 435 3292 1055 3292 459 3293 1088 3293 1515 3293 1620 3294 225 3294 451 3294 110 3295 225 3295 1721 3295 1528 3296 1529 3296 781 3296 1494 3297 1692 3297 797 3297 820 3298 1403 3298 1236 3298 1619 3299 296 3299 548 3299 574 3300 1583 3300 575 3300 657 3301 689 3301 940 3301 690 3302 927 3302 1731 3302 1498 3303 1312 3303 642 3303 363 3304 831 3304 364 3304 1330 3305 608 3305 9 3305 905 3306 922 3306 603 3306 417 3307 409 3307 811 3307 1657 3308 811 3308 1449 3308 1262 3309 429 3309 428 3309 1690 3310 735 3310 1674 3310 1614 3311 956 3311 609 3311 50 3312 52 3312 322 3312 1378 3313 289 3313 1492 3313 1130 3314 1134 3314 1583 3314 1573 3315 1484 3315 1668 3315 982 3316 383 3316 1587 3316 717 3317 1058 3317 1689 3317 170 3318 261 3318 263 3318 1444 3319 187 3319 186 3319 1708 3320 391 3320 314 3320 1178 3321 637 3321 70 3321 1451 3322 1538 3322 728 3322 1392 3323 1396 3323 1510 3323 1637 3324 501 3324 1465 3324 1776 3325 752 3325 884 3325 1776 3326 884 3326 1777 3326 1538 3327 164 3327 166 3327 1738 3328 249 3328 861 3328 403 3329 1733 3329 1807 3329 1777 3330 884 3330 883 3330 1273 3331 1019 3331 1508 3331 610 3332 609 3332 971 3332 938 3333 572 3333 549 3333 437 3334 887 3334 1083 3334 1595 3335 1233 3335 502 3335 1241 3336 552 3336 1445 3336 810 3337 809 3337 1320 3337 1043 3338 135 3338 137 3338 1783 3339 878 3339 863 3339 1598 3340 1115 3340 862 3340 916 3341 657 3341 656 3341 784 3342 68 3342 108 3342 1663 3343 1348 3343 1003 3343 949 3344 923 3344 1502 3344 1785 3345 863 3345 845 3345 735 3346 1690 3346 734 3346 998 3347 1531 3347 376 3347 832 3348 831 3348 428 3348 461 3349 291 3349 290 3349 1093 3350 968 3350 1199 3350 380 3351 1582 3351 1682 3351 1756 3352 1815 3352 839 3352 652 3353 654 3353 1311 3353 1025 3354 158 3354 403 3354 1756 3355 839 3355 1757 3355 647 3356 1037 3356 927 3356 722 3357 660 3357 723 3357 578 3358 1649 3358 969 3358 1758 3359 839 3359 771 3359 1758 3360 771 3360 1759 3360 1175 3361 1177 3361 944 3361 1759 3362 771 3362 1761 3362 101 3363 100 3363 727 3363 1628 3364 1222 3364 105 3364 1761 3365 771 3365 772 3365 1293 3366 1188 3366 579 3366 1702 3367 1638 3367 1515 3367 564 3368 1435 3368 1701 3368 1745 3369 642 3369 1645 3369 735 3370 1096 3370 1617 3370 808 3371 730 3371 393 3371 900 3372 207 3372 83 3372 1765 3373 1816 3373 798 3373 1575 3374 189 3374 191 3374 1220 3375 843 3375 1667 3375 1765 3376 798 3376 1365 3376 508 3377 1658 3377 1641 3377 1605 3378 1725 3378 795 3378 647 3379 1187 3379 370 3379 783 3380 782 3380 693 3380 1158 3381 1811 3381 504 3381 1601 3382 50 3382 322 3382 1563 3383 1670 3383 1638 3383 859 3384 861 3384 1722 3384 813 3385 1260 3385 1375 3385 1375 3386 1260 3386 1352 3386 1676 3387 1666 3387 1308 3387 1656 3388 1632 3388 1377 3388 1773 3389 755 3389 753 3389 1556 3390 1598 3390 862 3390 1154 3391 1153 3391 714 3391 1495 3392 1675 3392 1018 3392 1657 3393 1449 3393 1218 3393 240 3394 215 3394 97 3394 677 3395 679 3395 1430 3395 1140 3396 739 3396 916 3396 736 3397 82 3397 737 3397 818 3398 530 3398 490 3398 1274 3399 1394 3399 591 3399 725 3400 1410 3400 514 3400 1594 3401 1168 3401 1167 3401 1814 3402 1278 3402 851 3402 1440 3403 1484 3403 1128 3403 1049 3404 1023 3404 1022 3404 1733 3405 403 3405 158 3405 1687 3406 1092 3406 840 3406 1155 3407 714 3407 1153 3407 3 3408 1207 3408 4 3408 1526 3409 65 3409 515 3409 854 3410 1550 3410 73 3410 726 3411 1490 3411 879 3411 1570 3412 1569 3412 410 3412 860 3413 1738 3413 861 3413 484 3414 483 3414 1436 3414 479 3415 478 3415 94 3415 204 3416 206 3416 799 3416 155 3417 157 3417 1227 3417 1702 3418 1752 3418 1000 3418 269 3419 1631 3419 1013 3419 1247 3420 1749 3420 1148 3420 897 3421 1570 3421 409 3421 807 3422 730 3422 808 3422 1300 3423 177 3423 179 3423 307 3424 1208 3424 1318 3424 1002 3425 482 3425 484 3425 1491 3426 1300 3426 1299 3426 1384 3427 1616 3427 1385 3427 1565 3428 825 3428 290 3428 1812 3429 525 3429 524 3429 67 3430 66 3430 1490 3430 426 3431 1492 3431 538 3431 1037 3432 1036 3432 1731 3432 981 3433 980 3433 1057 3433 929 3434 1681 3434 1194 3434 1712 3435 538 3435 1571 3435 212 3436 96 3436 1216 3436 1135 3437 875 3437 548 3437 396 3438 1184 3438 1005 3438 1132 3439 1721 3439 1620 3439 558 3440 1630 3440 1701 3440 1221 3441 827 3441 760 3441 411 3442 1453 3442 1450 3442 1175 3443 944 3443 1603 3443 483 3444 1314 3444 220 3444 313 3445 312 3445 1347 3445 1608 3446 698 3446 1001 3446 1413 3447 804 3447 803 3447 745 3448 1492 3448 854 3448 160 3449 1733 3449 158 3449 416 3450 895 3450 897 3450 1209 3451 305 3451 655 3451 636 3452 842 3452 1071 3452 1409 3453 376 3453 1232 3453 1655 3454 1077 3454 1145 3454 1532 3455 1122 3455 376 3455 749 3456 1174 3456 750 3456 520 3457 519 3457 22 3457 1215 3458 243 3458 1214 3458 63 3459 1517 3459 1380 3459 1488 3460 1369 3460 1606 3460 161 3461 1232 3461 376 3461 220 3462 222 3462 386 3462 1312 3463 1331 3463 642 3463 1150 3464 859 3464 1722 3464 1150 3465 1722 3465 221 3465 888 3466 890 3466 1370 3466 1157 3467 1322 3467 1141 3467 1081 3468 900 3468 83 3468 339 3469 1506 3469 1639 3469 1768 3470 1740 3470 581 3470 1206 3471 976 3471 648 3471 896 3472 1570 3472 897 3472 1669 3473 977 3473 178 3473 230 3474 1244 3474 99 3474 1133 3475 925 3475 749 3475 835 3476 1003 3476 444 3476 945 3477 475 3477 476 3477 192 3478 1142 3478 995 3478 403 3479 405 3479 1662 3479 1655 3480 4 3480 909 3480 1352 3481 1260 3481 922 3481 915 3482 1341 3482 916 3482 467 3483 1606 3483 1369 3483 274 3484 276 3484 327 3484 934 3485 1267 3485 245 3485 471 3486 125 3486 1687 3486 968 3487 182 3487 1199 3487 1562 3488 330 3488 824 3488 347 3489 346 3489 509 3489 1069 3490 633 3490 580 3490 1731 3491 1718 3491 690 3491 108 3492 1726 3492 1425 3492 137 3493 159 3493 158 3493 170 3494 420 3494 1575 3494 1731 3495 675 3495 1718 3495 1688 3496 561 3496 1805 3496 1441 3497 195 3497 1271 3497 127 3498 1456 3498 685 3498 1037 3499 1814 3499 851 3499 212 3500 1216 3500 210 3500 1436 3501 220 3501 386 3501 1407 3502 1408 3502 1428 3502 185 3503 184 3503 499 3503 1511 3504 1303 3504 1742 3504 383 3505 84 3505 86 3505 231 3506 230 3506 805 3506 456 3507 888 3507 843 3507 995 3508 1813 3508 765 3508 765 3509 1813 3509 1747 3509 1754 3510 355 3510 959 3510 1121 3511 1120 3511 1152 3511 1687 3512 124 3512 1092 3512 1482 3513 426 3513 538 3513 55 3514 1347 3514 53 3514 1643 3515 1709 3515 1711 3515 1072 3516 1725 3516 1560 3516 634 3517 635 3517 1374 3517 298 3518 1370 3518 890 3518 269 3519 105 3519 104 3519 1037 3520 1731 3520 1422 3520 769 3521 768 3521 1578 3521 473 3522 33 3522 283 3522 761 3523 1026 3523 696 3523 1720 3524 1317 3524 1395 3524 1625 3525 255 3525 257 3525 1334 3526 1024 3526 1121 3526 192 3527 1345 3527 80 3527 1662 3528 1640 3528 1443 3528 297 3529 572 3529 227 3529 1479 3530 407 3530 406 3530 498 3531 1448 3531 902 3531 658 3532 1380 3532 1297 3532 346 3533 329 3533 509 3533 633 3534 545 3534 597 3534 1041 3535 1269 3535 91 3535 992 3536 75 3536 77 3536 388 3537 1226 3537 1313 3537 457 3538 618 3538 454 3538 1734 3539 324 3539 295 3539 1651 3540 1540 3540 1539 3540 670 3541 1652 3541 1205 3541 1139 3542 428 3542 427 3542 1407 3543 1557 3543 588 3543 1605 3544 1487 3544 1725 3544 1800 3545 486 3545 485 3545 374 3546 1749 3546 1247 3546 254 3547 369 3547 368 3547 990 3548 1087 3548 287 3548 1299 3549 1301 3549 1138 3549 901 3550 948 3550 653 3550 714 3551 1574 3551 1524 3551 441 3552 1413 3552 232 3552 150 3553 149 3553 249 3553 63 3554 717 3554 1517 3554 337 3555 324 3555 1734 3555 1217 3556 294 3556 1061 3556 936 3557 1480 3557 1606 3557 449 3558 293 3558 325 3558 1747 3559 766 3559 765 3559 862 3560 1115 3560 846 3560 1537 3561 1536 3561 304 3561 609 3562 544 3562 1614 3562 193 3563 1220 3563 1667 3563 721 3564 1460 3564 276 3564 576 3565 1763 3565 592 3565 1815 3566 845 3566 839 3566 921 3567 449 3567 1712 3567 1179 3568 1140 3568 916 3568 743 3569 744 3569 1530 3569 999 3570 1360 3570 1532 3570 1513 3571 1512 3571 414 3571 1040 3572 1489 3572 1041 3572 1272 3573 1019 3573 1273 3573 1270 3574 1167 3574 553 3574 981 3575 1229 3575 982 3575 891 3576 893 3576 493 3576 776 3577 185 3577 1367 3577 866 3578 1268 3578 867 3578 1727 3579 988 3579 989 3579 470 3580 469 3580 1044 3580 557 3581 223 3581 869 3581 577 3582 757 3582 132 3582 642 3583 1332 3583 1342 3583 979 3584 358 3584 86 3584 463 3585 1624 3585 1 3585 1583 3586 1134 3586 866 3586 1816 3587 772 3587 798 3587 1658 3588 508 3588 1518 3588 1355 3589 892 3589 891 3589 1565 3590 484 3590 1436 3590 1317 3591 972 3591 1395 3591 1514 3592 1608 3592 1515 3592

+
+
+ 1 +
+
+ + + + 7.481132 -6.50764 5.343665 + 0 0 1 46.69194 + 0 1 0 0.619768 + 1 0 0 63.5593 + 1 1 1 + + + + 4.076245 1.005454 5.903862 + 0 0 1 106.9363 + 0 1 0 3.163707 + 1 0 0 37.26105 + 1 1 1 + + + + 0 0 0 + 0 0 1 0 + 0 1 0 0 + 1 0 0 0 + 1 1 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_distal/bt_2p/f_distal_bt_2p_adapter.dae b/URDFs/sr_description/meshes/components/f_distal/bt_2p/f_distal_bt_2p_adapter.dae new file mode 100644 index 0000000..fbdf121 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_distal/bt_2p/f_distal_bt_2p_adapter.dae @@ -0,0 +1,126 @@ + + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + Mon Sep 8 16:29:32 2014 + Mon Sep 8 16:29:32 2014 + + + + + + + + + 0 0 0 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + 0.0117387 0.0032069 0.00451553 0.0122467 0.00373589 0.00439479 0.0122467 0.00426488 0.00451553 0.0117387 0.00426488 0.00451553 0.0117387 0.00492452 0.0053427 0.0122467 0.00492452 0.00588529 0.0117387 0.0046891 0.00637415 0.0122467 0.00426488 0.00671246 0.0122467 0.00373589 0.00683319 0.0117387 0.00373589 0.00683319 0.0122467 0.0032069 0.00671246 0.0117387 0.0032069 0.00671246 0.0122467 0.00254725 0.00588529 0.0122467 0.00254725 0.0053427 0.0117387 0.00254725 0.0053427 0.0122467 0.0032069 0.00451553 0.0117387 -0.00625711 0.0125413 0.0117387 0.00588894 0.0112948 0.0117387 0.00621136 0.0119063 0.0117387 -0.00618778 0.0120721 0.0117387 0.00505989 0.0103467 0.0117387 0.00546026 0.0107578 0.0117387 0.00559987 0.0109225 0.0117387 -0.00610273 0.0118146 0.0117387 -0.00601045 0.0116075 0.0117387 -0.0058212 0.0112936 0.0117387 -0.00577066 0.0112136 0.0117387 0.00254725 0.00588529 0.0117387 0.0046891 0.00485384 0.0117387 0.00691089 0.00259463 0.0117387 0.00492452 0.00588529 0.0117387 -0.00680511 0.00259463 0.0117387 -0.00650753 0.00187621 0.0117387 0.00505485 0.0103416 0.0117387 0.00426488 0.00671246 0.0117387 -0.00498711 0.0103416 0.0117387 0.00278268 0.00637415 0.0117387 0.00632485 0.0125413 0.0117387 0.00629419 0.0122143 0.0117387 -0.00537614 0.0107437 0.0117387 -0.00499215 0.0103467 0.0117387 0.00278268 0.00485384 0.0117387 0.00683355 0.00220583 0.0117387 0.00628369 0.00165597 0.0117387 0.00373589 0.00439479 0.0124887 -0.00680511 0.0245776 0.0123882 -0.00680511 0.0242026 0.0121137 -0.00680511 0.0239281 0.0117387 -0.00680511 0.0238276 0.0117387 -0.00625711 0.0253276 0.0117387 -0.00625711 0.0238276 0.0123882 -0.00625711 0.0242026 0.0128439 -0.00625711 0.0253276 0.0132627 0.00691089 0.00964936 0.0135167 0.00691089 0.00964936 0.0135167 0.00691089 0.0248196 0.0128439 0.00632485 0.0128763 0.011796 0.00632485 0.0125734 0.0123882 0.00632485 0.0249526 0.0121137 0.00632485 0.0239281 0.0132627 0.00160969 0.0059889 0.0132627 0.00186614 0.00669349 0.0132627 -0.00680511 0.00964936 0.0132627 0.00560564 0.00669349 0.0132627 -0.00578911 0.00157863 0.0132627 0.00589489 0.00157863 0.0132627 0.00447431 0.0035852 0.0132627 0.00160969 0.00523909 0.0132627 0.00628369 0.00165597 0.0132627 0.00512367 0.0039601 0.0132627 0.00683355 0.00220583 0.0132627 0.00691089 0.00259463 0.0132627 0.00560564 0.0045345 0.0132627 0.00586209 0.00523909 0.0132627 0.00299746 0.0035852 0.0132627 0.00234811 0.0039601 0.0132627 -0.00617792 0.00165597 0.0132627 -0.00650753 0.00187621 0.0139646 -0.00615158 0.0253276 0.0135167 -0.00629711 0.0253276 0.0140172 -0.00547312 0.0253276 0.0141332 -0.00598301 0.0253276 0.0135167 0.00640289 0.0253276 0.0128439 0.00632485 0.0253276 0.0139646 0.00625736 0.0253276 0.0137522 0.00636559 0.0253276 0.0137419 0.00595287 0.0253276 0.0142787 0.00564089 0.0253276 0.0141139 0.00505485 0.0253276 0.0147867 -0.00553511 0.0248196 0.0141139 -0.00498711 0.0253276 0.0140069 -0.00546782 0.0128763 0.0138685 -0.00573747 0.0128763 0.0137419 -0.00588514 0.0253276 0.0133299 -0.00616044 0.0253276 0.0128439 -0.00625711 0.0128763 0.0133246 0.00621773 0.0128763 0.0133299 0.00622817 0.0253276 0.0135904 0.0060823 0.0128763 0.0137309 0.00594182 0.0128763 0.0138714 0.00580133 0.0128763 0.0141139 0.00505485 0.0128763 0.0140172 0.00554085 0.0253276 0.0117659 0.00505485 0.0106031 0.0118325 -0.00498711 0.010807 0.0119902 0.00505485 0.0111003 0.0120875 0.00505485 0.011205 0.0121769 0.00505485 0.0113013 0.0120875 -0.00498711 0.011205 0.0121769 -0.00498711 0.0113013 0.0124023 0.00505485 0.0114575 0.0124023 -0.00498711 0.0114575 0.0126561 0.00505485 0.0115617 0.0129263 0.00505485 0.011609 0.0129263 -0.00498711 0.011609 0.0117944 0.0054473 0.0108894 0.0117387 0.00544664 0.0107438 0.0118325 0.00505485 0.010807 0.0117387 0.00531908 0.0106128 0.0117387 0.00578077 0.0111359 0.0117387 0.00599423 0.0114495 0.012018 0.00580133 0.0114846 0.0117387 0.00617313 0.0118078 0.0121524 0.0060823 0.0119175 0.0117387 0.00625597 0.0120722 0.0119834 0.00626269 0.0122286 0.0123035 0.00632485 0.0127818 0.0128908 0.00609421 0.0121547 0.0128694 0.00626269 0.0124847 0.0128923 0.0060823 0.0121314 0.0117387 0.00615985 0.0117736 0.0117387 0.00607488 0.0116073 0.011834 0.0060823 0.0116969 0.0129227 0.00540964 0.011665 0.0129223 0.0054473 0.011671 0.0125888 0.00580133 0.0117947 0.0117387 0.00579923 0.011163 0.0117957 0.00580133 0.0112452 0.0122865 0.00580133 0.0116706 0.0129258 0.00510238 0.0116165 0.0124124 0.00626269 0.0124047 0.0125107 0.0060823 0.0120646 0.0126388 0.0054473 0.0116214 0.0124683 0.00505485 0.0114846 0.0118511 0.00505485 0.0108639 0.0119404 0.0054473 0.0111374 0.0121362 0.0054473 0.0113483 0.0123727 0.0054473 0.0115121 0.0135862 0.00529604 0.0118744 0.0129088 0.00582866 0.0118783 0.0129209 0.00549035 0.0116929 0.0129238 0.00529769 0.0116473 0.0129249 0.00518834 0.0116301 0.0140154 0.00505485 0.0124141 0.0140517 0.0054473 0.0128763 0.0140068 0.00553553 0.0128763 0.0138246 0.00576733 0.0124974 0.0128685 0.00626475 0.0124977 0.0132364 0.00626269 0.0128763 0.0132185 0.00620767 0.0124974 0.0135564 0.0060355 0.0124974 0.0136884 0.00566843 0.012153 0.0139967 0.00542942 0.0124974 0.0138367 0.00537742 0.012153 0.0131665 0.00604764 0.012153 0.0130851 0.00579717 0.0118744 0.0134575 0.00589937 0.012153 0.0136244 0.00505485 0.0118744 0.0129106 0.00580133 0.011851 0.0133027 0.0056863 0.0118744 0.0129817 0.00547907 0.0116872 0.0131061 0.00541572 0.0116872 0.0132048 0.00531703 0.0116872 0.0134754 0.00551363 0.0118744 0.0132681 0.00519269 0.0116872 0.01329 0.00505485 0.0116872 0.0133808 0.00505485 0.0117381 0.0133808 -0.00498711 0.0117381 0.0136244 -0.00498711 0.0118744 0.01376 0.00505485 0.0120179 0.0138878 0.00505485 0.012153 0.0140561 0.00505485 0.0124974 0.0141139 -0.00498711 0.0128763 0.0133243 -0.00614923 0.0128763 0.0135846 -0.00601877 0.0128763 0.0128923 -0.00601457 0.0121314 0.0129223 -0.00537957 0.011671 0.01329 -0.00498711 0.0116872 0.0132679 -0.00512575 0.0116872 0.013996 -0.00536386 0.0124974 0.0138219 -0.00570329 0.0124974 0.0137308 -0.00587391 0.0128763 0.014051 -0.00538184 0.0128763 0.0140561 -0.00498711 0.0124974 0.0140154 -0.00498711 0.0124141 0.0138878 -0.00498711 0.012153 0.0138361 -0.00531156 0.012153 0.0135858 -0.00522971 0.0118744 0.01376 -0.00498711 0.0120179 0.0129226 -0.00534443 0.0116654 0.013104 -0.00534946 0.0116872 0.0129785 -0.00541237 0.0116872 0.0129106 -0.0057336 0.011851 0.0132991 -0.00562115 0.0118744 0.0130795 -0.00573123 0.0118744 0.0129258 -0.00503506 0.0116165 0.0129249 -0.00512182 0.0116302 0.0132038 -0.00525066 0.0116872 0.0134736 -0.00544827 0.0118744 0.0134527 -0.00583509 0.012153 0.013159 -0.00598231 0.012153 0.0128694 -0.00619496 0.0124847 0.0132272 -0.00619788 0.0128763 0.0132098 -0.00614273 0.0124974 0.0135508 -0.00597178 0.0124974 0.0136861 -0.00560387 0.012153 0.0129088 -0.00576092 0.0118783 0.0117387 -0.00571304 0.0111359 0.0117387 -0.00614363 0.0119063 0.0117387 -0.00573324 0.0111631 0.012018 -0.0057336 0.0114846 0.0118511 -0.00498711 0.0108639 0.0117659 -0.00498711 0.0106031 0.0117387 -0.00525139 0.0106111 0.0117944 -0.00537957 0.0108894 0.0117387 -0.00533913 0.0107006 0.0117387 -0.00553198 0.0109251 0.0128685 -0.00619702 0.0124977 0.0124124 -0.00619496 0.0124047 0.0123035 -0.00625711 0.0127818 0.011796 -0.00625711 0.0125734 0.0117387 -0.0062282 0.0122238 0.0119834 -0.00619496 0.0122286 0.0128908 -0.00602647 0.0121547 0.0125107 -0.00601457 0.0120646 0.0121524 -0.00601457 0.0119175 0.0125888 -0.0057336 0.0117947 0.011834 -0.00601457 0.0116969 0.0117387 -0.00598915 0.0115597 0.0129209 -0.00542262 0.0116929 0.0122865 -0.0057336 0.0116706 0.0123727 -0.00537957 0.0115121 0.0117957 -0.0057336 0.0112452 0.0119404 -0.00537957 0.0111374 0.0119902 -0.00498711 0.0111003 0.0121362 -0.00537957 0.0113483 0.0126388 -0.00537957 0.0116214 0.0129238 -0.00523201 0.0116477 0.0124683 -0.00498711 0.0114846 0.0126561 -0.00498711 0.0115617 0.0139967 0.00681668 0.00974356 0.0139092 0.00684873 0.0248196 0.0140021 0.00681317 0.00974707 0.0139974 0.00680377 0.0248196 0.0144037 0.00652786 0.0248196 0.0146796 0.00612157 0.0248196 0.0147246 0.00603334 0.0248196 0.0147867 0.00564089 0.0109194 0.0147867 -0.00553511 0.0109194 0.0147866 0.00565892 0.0109013 0.0146875 0.00612626 0.010434 0.0146846 -0.00603419 0.0104203 0.0146846 0.00613997 0.0104203 0.0144132 0.00653777 0.0100225 0.0144132 -0.00643199 0.0100225 0.0144074 0.00654619 0.0100141 0.0144074 -0.00644041 0.0100141 0.0135167 -0.00680511 0.00964936 0.0139967 -0.0067109 0.00974356 0.0140021 -0.0067074 0.00974707 0.0142632 -0.00656256 0.0248196 0.0144037 -0.00642208 0.0248196 0.0146796 -0.0060158 0.0248196 0.0147246 -0.00592756 0.0248196 0.0146875 -0.00602049 0.010434 0.0147866 -0.00555315 0.0109013 0.0123882 0.00632485 0.0242026 0.0123882 0.00632034 0.0242026 0.0124887 0.00632485 0.0245776 0.0124887 0.00632034 0.0245776 0.0123882 0.00632034 0.0249526 0.0121137 0.00632485 0.0252272 0.0117387 0.00724744 0.023844 0.0118947 0.00724744 0.023844 0.0121137 0.00691089 0.0239281 0.0121886 0.00676321 0.0251777 0.0121065 0.00724744 0.0252172 0.0122961 0.00724744 0.0250795 0.0121796 0.00724744 0.0239709 0.0124846 0.00724744 0.0244992 0.0123882 0.00691089 0.0242026 0.0124887 0.00691089 0.0245776 0.0124765 0.00724744 0.0245763 0.012452 0.00724744 0.0248094 0.0124486 0.00691089 0.0248196 0.0123856 0.00688975 0.0249514 0.0123726 0.00688538 0.0249786 0.0120294 0.00663975 0.025269 0.0121109 0.00670299 0.0252223 0.0117387 0.00691089 0.0238276 0.0117387 0.00632485 0.0238276 0.0110892 0.00632034 0.0242026 0.0109928 0.00724744 0.0244992 0.0110009 0.00724744 0.0245763 0.0111034 0.00724744 0.0249444 0.0117387 0.00640289 0.0253276 0.0117387 0.00632485 0.0253276 0.0117387 0.00632034 0.0253276 0.0121137 0.00632034 0.0252272 0.0114337 0.00724744 0.0252628 0.0121137 0.00632034 0.0239281 0.0110892 0.00632034 0.0249526 0.0113637 0.00632034 0.0239281 0.0117387 0.00632034 0.0238276 0.0109887 0.00632034 0.0245776 0.0113637 0.00632034 0.0252272 0.0115291 0.00775544 0.0244566 0.0119186 0.00775544 0.0247396 0.0116884 0.00775544 0.0243409 0.0115965 0.00775544 0.0243819 0.011881 0.00775544 0.0243819 0.0116403 0.00775544 0.0247987 0.0118295 0.00771677 0.0241508 0.0115086 0.00775544 0.0246524 0.0114822 0.00771677 0.0242246 0.0114981 0.00775544 0.0245523 0.0121538 0.00771677 0.0247125 0.0119794 0.00775544 0.0245523 0.0121727 0.00771677 0.024532 0.0121167 0.00771677 0.0243594 0.0119483 0.00775544 0.0244566 0.0119952 0.00771677 0.0242246 0.0114144 0.00771677 0.0248696 0.0115612 0.00771677 0.0249763 0.0117387 0.00775544 0.0248196 0.0118372 0.00775544 0.0247987 0.0119162 0.00771677 0.0249763 0.0113853 0.00760665 0.0240912 0.0113608 0.00771677 0.0243594 0.0112919 0.00760665 0.0249799 0.0114942 0.00760665 0.0251269 0.0117387 0.00771677 0.025014 0.0119833 0.00760665 0.0251269 0.0116137 0.00760665 0.0239896 0.0113206 0.00744184 0.0240022 0.0112181 0.00760665 0.024277 0.0111408 0.00760665 0.0245148 0.0111227 0.00744184 0.024222 0.0124152 0.00744184 0.0247974 0.0123366 0.00760665 0.0245148 0.0122594 0.00760665 0.024277 0.0120921 0.00760665 0.0240912 0.0123548 0.00744184 0.024222 0.0112101 0.00744184 0.0250536 0.0114494 0.00744184 0.0252275 0.0117387 0.00744184 0.025289 0.0117387 0.00760665 0.0251788 0.0115589 0.00775544 0.0247396 0.0113047 0.00771677 0.024532 0.0113237 0.00771677 0.0247125 0.0111669 0.00760665 0.0247634 0.0110313 0.00744184 0.0245033 0.0110622 0.00744184 0.0247974 0.0110254 0.00724744 0.0248094 0.0115828 0.00724744 0.023844 0.0113687 0.00724744 0.0239393 0.0115908 0.00744184 0.0238818 0.0112979 0.00724744 0.0239709 0.0110892 0.00724744 0.0242026 0.011648 0.00771677 0.0241508 0.011789 0.00775544 0.0243409 0.0118637 0.00760665 0.0239896 0.0118866 0.00744184 0.0238818 0.0121568 0.00744184 0.0240022 0.0124462 0.00744184 0.0245033 0.0123882 0.00724744 0.0242026 0.0121087 0.00724744 0.0239393 0.0119689 0.00775544 0.0246524 0.012063 0.00771677 0.0248696 0.0121855 0.00760665 0.0249799 0.0123105 0.00760665 0.0247634 0.0123741 0.00724744 0.0249444 0.0122673 0.00744184 0.0250536 0.012028 0.00744184 0.0252275 0.0111814 0.00724744 0.0250795 0.0113709 0.00724744 0.0252172 0.0117387 0.00724744 0.0253276 0.0120438 0.00724744 0.0252628 0.0121137 -0.00624631 0.0239281 0.0122975 -0.00673272 0.0250714 0.0122433 -0.00669729 0.0251326 0.0121137 -0.00710991 0.0252272 0.0120891 -0.00658124 0.0252407 0.0120506 -0.00655076 0.025259 0.0123726 -0.0067796 0.0249786 0.0123455 -0.00710991 0.0250185 0.0123856 -0.00678397 0.0249514 0.012377 -0.00710991 0.0249476 0.0124723 -0.00710991 0.0247336 0.0124723 -0.00710991 0.0244217 0.012377 -0.00710991 0.0242076 0.0121137 -0.00625711 0.0239281 0.0124887 -0.00625711 0.0245776 0.0124887 -0.00624631 0.0245776 0.0123882 -0.00625711 0.0249526 0.0123882 -0.00624631 0.0249526 0.0121137 -0.00625711 0.0252272 0.0117387 -0.00624631 0.0253276 0.01174 -0.00710991 0.0253154 0.0113719 -0.00710991 0.025213 0.0110892 -0.00624631 0.0249526 0.0110536 -0.00710991 0.0248827 0.0113719 -0.00710991 0.0239423 0.0113637 -0.00624631 0.0239281 0.0110892 -0.00624631 0.0242026 0.0112369 -0.00710991 0.0240203 0.0118171 -0.00710991 0.0238317 0.011507 -0.00710991 0.0238643 0.0113637 -0.00624631 0.0252272 0.0109887 -0.00624631 0.0245776 0.0117387 -0.00624631 0.0238276 0.0121137 -0.00624631 0.0252272 0.0123882 -0.00624631 0.0242026 0.0116639 -0.00761791 0.0248078 0.011764 -0.00761791 0.024337 0.011764 -0.00761791 0.0248183 0.0114967 -0.00761791 0.0245776 0.0118597 -0.00761791 0.0247872 0.0115768 -0.00761791 0.0247575 0.0116639 -0.00761791 0.0243475 0.0114467 -0.00757924 0.0242533 0.0118597 -0.00761791 0.0243681 0.0115176 -0.00761791 0.0244792 0.0115768 -0.00761791 0.0243978 0.0117843 -0.00757924 0.0241436 0.0116039 -0.00757924 0.0241626 0.0113023 -0.00757924 0.0245776 0.0111895 -0.00746912 0.0248222 0.0113401 -0.00757924 0.0247551 0.0115529 -0.00746912 0.0251494 0.0117843 -0.00757924 0.0250116 0.0118016 -0.00746912 0.0251755 0.0120393 -0.00746912 0.0250983 0.0119569 -0.00757924 0.0249556 0.0122251 -0.00746912 0.024931 0.0124345 -0.00730432 0.0244297 0.0120918 -0.00757924 0.0248341 0.0121656 -0.00757924 0.0246684 0.0123268 -0.00746912 0.0247026 0.0119754 -0.00761791 0.0245273 0.0121656 -0.00757924 0.0244869 0.0120944 -0.00730432 0.0239616 0.0120393 -0.00746912 0.024057 0.0111895 -0.00746912 0.0243331 0.0111375 -0.00746912 0.0245776 0.0113364 -0.00746912 0.0250244 0.0115189 -0.00730432 0.0252541 0.011507 -0.00710991 0.0252909 0.0118171 -0.00710991 0.0253235 0.0118131 -0.00730432 0.0252851 0.0115176 -0.00761791 0.0246761 0.0114467 -0.00757924 0.0249019 0.0116039 -0.00757924 0.0249927 0.0120944 -0.00730432 0.0251937 0.0124345 -0.00730432 0.0247255 0.0123142 -0.00730432 0.0249957 0.0123455 -0.00710991 0.0241368 0.0124723 -0.00710991 0.0245776 0.0119345 -0.00761791 0.0247199 0.0119754 -0.00761791 0.0246279 0.0123268 -0.00746912 0.0244526 0.0122251 -0.00746912 0.0242243 0.0123142 -0.00730432 0.0241595 0.0121137 -0.00710991 0.0239281 0.01174 -0.00710991 0.0238398 0.0118131 -0.00730432 0.0238702 0.0115189 -0.00730432 0.0239011 0.0118016 -0.00746912 0.0239797 0.0119569 -0.00757924 0.0241997 0.0119345 -0.00761791 0.0244354 0.0120918 -0.00757924 0.0243211 0.0115529 -0.00746912 0.0240058 0.0113364 -0.00746912 0.0241308 0.0112628 -0.00730432 0.024049 0.0113401 -0.00757924 0.0244001 0.0110991 -0.00710991 0.0242099 0.0112628 -0.00730432 0.0251063 0.0112369 -0.00710991 0.025135 0.0110991 -0.00710991 0.0249454 0.0110889 -0.00730432 0.024867 0.0110274 -0.00730432 0.0245776 0.0109887 -0.00710991 0.0245776 0.0110536 -0.00710991 0.0242726 0.0110889 -0.00730432 0.0242883 0.0120495 0.00665539 0.0252575 0.0119384 0.00656649 0.0253006 0.011743 0.00640637 0.0253276 0.0123561 0.00687647 0.0250034 0.0135167 0.00683562 0.0250688 0.0122971 0.00683809 0.0250709 0.0135167 0.0067621 0.0251788 0.0122433 0.00680307 0.0251326 0.0135167 0.00665207 0.0252524 0.0135167 0.00659729 0.025289 0.0138632 0.00670722 0.0251788 0.0142414 0.00587636 0.0253276 0.0144731 0.00564089 0.025289 0.0144263 0.00593643 0.025289 0.0141332 0.00608878 0.0253276 0.0145831 0.00598736 0.0251788 0.0146379 0.00564089 0.0251788 0.0146878 0.00602139 0.025014 0.0147867 0.00564089 0.0248196 0.0138972 0.00681195 0.025014 0.0135167 0.00687222 0.025014 0.0142632 0.00666834 0.0248196 0.0138123 0.00655048 0.025289 0.0141758 0.00654796 0.0251788 0.0142905 0.00620305 0.025289 0.0140789 0.00641463 0.025289 0.0144238 0.00629992 0.0251788 0.0142405 0.00663705 0.025014 0.0145129 0.00636464 0.025014 0.0145442 0.00638737 0.0248196 0.0145279 0.00564089 0.0252524 0.0144731 -0.00553511 0.025289 0.0147115 0.00564089 0.0250688 0.0147481 0.00564089 0.025014 0.0147481 -0.00553511 0.025014 0.0138972 -0.00670618 0.025014 0.0135167 -0.00676644 0.025014 0.0137522 -0.00625982 0.0253276 0.0135167 -0.00649152 0.025289 0.0142414 -0.00577058 0.0253276 0.0142787 -0.00553511 0.0253276 0.0140789 -0.00630886 0.025289 0.0145279 -0.00553511 0.0252524 0.0144263 -0.00583066 0.025289 0.0145831 -0.00588159 0.0251788 0.0144238 -0.00619414 0.0251788 0.0145129 -0.00625887 0.025014 0.0142405 -0.00653128 0.025014 0.0141758 -0.00644219 0.0251788 0.0138123 -0.00644471 0.025289 0.0135167 -0.00654629 0.0252524 0.0135167 -0.00665632 0.0251788 0.0138632 -0.00660145 0.0251788 0.0142905 -0.00609727 0.025289 0.0146379 -0.00553511 0.0251788 0.0147115 -0.00553511 0.0250688 0.0146878 -0.00591562 0.025014 0.0135167 -0.00680511 0.0248196 0.0139092 -0.00674296 0.0248196 0.0139974 -0.006698 0.0248196 0.0145442 -0.0062816 0.0248196 0.0124486 -0.00680511 0.0248196 0.0135167 -0.00672984 0.0250688 0.012112 -0.00659848 0.0252247 0.0122634 -0.00671142 0.0251136 0.0117387 -0.00629711 0.0253276 0.011743 -0.00630059 0.0253276 0.0118363 -0.0063773 0.0253213 0.0120294 -0.00653397 0.025269 0.0122467 0.00278268 0.00485384 0.0122467 0.00373589 0.00345499 0.0122467 0.00278268 0.00637415 0.0122467 0.00186614 0.00669349 0.0122467 0.00160969 0.0059889 0.0122467 0.00186614 0.0045345 0.0122467 0.00234811 0.0039601 0.0122467 0.00447431 0.0035852 0.0122467 0.0046891 0.00485384 0.0122467 0.00586209 0.00523909 0.0122467 0.00492452 0.0053427 0.0122467 0.0046891 0.00637415 0.0122467 0.00560564 0.00669349 0.0122467 0.00512367 0.00726788 0.0122467 0.00299746 0.0035852 0.0132627 0.00373589 0.00345499 0.0122467 0.00512367 0.0039601 0.0122467 0.00560564 0.0045345 0.0122467 0.00586209 0.0059889 0.0132627 0.00586209 0.0059889 0.0132627 0.00512367 0.00726788 0.0122467 0.00447431 0.00764279 0.0132627 0.00447431 0.00764279 0.0132627 0.00373589 0.00777299 0.0122467 0.00373589 0.00777299 0.0132627 0.00299746 0.00764279 0.0122467 0.00299746 0.00764279 0.0132627 0.00234811 0.00726788 0.0122467 0.00234811 0.00726788 0.0122467 0.00160969 0.00523909 0.0132627 0.00186614 0.0045345 0.0132627 -0.00680511 0.00259463 0.0117387 -0.00672777 0.00220583 0.0132627 -0.00672777 0.00220583 0.0117387 -0.00617792 0.00165597 0.0117387 -0.00578911 0.00157863 0.0132627 0.00661331 0.00187621 0.0117387 0.00661331 0.00187621 0.0117387 0.00589489 0.00157863 0.0117387 -0.006773 0.0020955 0.0117387 0.00450578 0.00516949 0.0117387 0.000363588 0.00210179 0.0117387 0.000562772 0.00505005 0.0117387 0.000610564 0.00497225 0.0117387 0.00141655 0.003042 0.0117387 0.00100659 0.0024414 0.0117387 0.00373589 0.004725 0.0117387 -0.00640111 0.00172362 0.0117387 0.0005461 0.00513981 0.0117387 0.00329139 0.00638389 0.0117387 0.0053 0.00862475 0.0117387 0.00691089 0.0026035 0.0117387 -0.00141655 0.003042 0.0117387 -0.00149856 0.00376453 0.0117387 0.000562772 0.00526235 0.0117387 0.000363588 0.00821061 0.0117387 -0.000363588 0.00821061 0.0117387 0.000683101 0.00491681 0.0117387 0.00149856 0.00376453 0.0117387 0.00141655 0.00727041 0.0117387 0.00149856 0.00654787 0.0117387 -0.00149856 0.00654787 0.0117387 -0.00123363 0.00444173 0.0117387 -0.000610564 0.00497225 0.0117387 -0.000562772 0.00505005 0.0117387 -0.000610564 0.00534015 0.0117387 -0.0005461 0.00517259 0.0117387 -0.0063 0.0234318 0.0117387 -0.0063 0.00200475 0.00958989 -0.0063 0.0202248 0.0132501 0.00691089 0.0248067 0.0132335 0.00691089 0.00125833 0.0131851 0.00691089 0.00109831 0.0131967 0.00691089 0.0249376 0.0131491 0.00691089 0.0250541 0.0130252 0.00691089 0.0251927 0.0124443 0.00691089 0.0237536 0.0132387 0.00691089 0.0026035 0.012725 0.00691089 0.0253885 0.0125371 0.00691089 0.0240667 0.0122183 0.00691089 0.0235199 0.0117387 -0.00690911 2.77356e-06 0.0131893 -0.00690911 0.00109717 0.012968 -0.00690911 0.0252569 0.0130255 -0.00690911 0.0251926 0.0132688 -0.00690911 0.0015875 0.0127248 -0.00690911 0.0253887 0.0127681 -0.00690911 0.0253653 0.0122212 -0.00690911 0.0235168 0.0124537 -0.00690911 0.0237493 0.0132503 -0.00690911 0.0248073 0.013197 -0.00690911 0.0249375 0.0117387 -0.0067811 1.53676e-06 0.0117387 0.00691089 2.77356e-06 0.0117387 0.0064135 1.09978e-07 0.0117387 -0.0064135 1.09978e-07 0.0112196 0.00853223 0.0254318 0.0106918 0.00872819 0.0254318 0.01122 -0.00853202 0.0254318 0.0122306 -0.00754002 0.0254318 0.010692 -0.00872814 0.0254318 0.0113387 -0.00760193 0.0254318 0.0107773 0.0063 0.0254318 0.0109373 0.0063 0.0254318 0.0113369 0.00760324 0.0254318 0.00490003 0.00720666 0.0254318 0.0064262 -0.00559833 0.0254318 0.00578453 -0.00647466 0.0254318 0.0120668 0.00780254 0.0254318 0.0122305 0.00754032 0.0254318 0.0107773 -0.0063 0.0254318 0.00385982 0.00769257 0.0254318 0.00991246 -0.00606879 0.0254318 0.00988963 -0.0060589 0.0254318 -0.00747227 0.000608993 0.0254318 0.0102278 -0.00620539 0.0254318 0.001397 -0.00879475 0.0254318 0.00385982 -0.00769257 0.0254318 0.00900889 -0.00551085 0.0254318 -0.00743296 -0.00102631 0.0254318 0.0110442 0.00731036 0.0254318 0.0101327 0.00879475 0.0254318 0.0109371 0.00691035 0.0254318 0.0105763 0.00628499 0.0254318 0.00900239 0.00550625 0.0254318 0.0074422 1.95156e-18 0.0254318 -0.0030851 -0.00759728 0.0254318 0.001397 0.00879475 0.0254318 -0.00580274 0.00382576 0.0254318 -0.00524565 -0.00470894 0.0254318 -0.00659209 -0.00386154 0.0254318 -0.00619086 -0.0045862 0.0254318 0.00900889 0.00551085 0.0254318 0.00916144 0.0056183 0.0254318 -0.00437065 -0.00572571 0.0254318 -0.00539475 -0.00567849 0.0254318 -0.0032061 -0.00667651 0.0254318 0.00960297 0.00590907 0.0254318 -0.00294018 0.00684809 0.0254318 -0.00517612 0.00592489 0.0254318 -0.00495928 0.00508066 0.0254318 -0.00570452 0.00529441 0.0254318 -0.00284375 0.00773156 0.0254318 -0.004153 0.00593196 0.0254318 -0.00355452 0.00730667 0.0254318 -0.00422307 0.00681737 0.0254318 -0.004847 0.00626355 0.0254318 -0.000852474 0.00850919 0.0254318 -0.000444516 -0.00786995 0.0254318 -0.00107649 -0.00844826 0.0254318 0.000557317 -0.00875563 0.0254318 0.001397 -0.0080772 0.0254318 -0.000115343 0.00793801 0.0254318 0.0101327 0.0095885 0.024638 0.0108781 0.00949975 0.024638 0.0108392 0.0095089 0.0015875 0.0121935 0.00882672 0.024638 0.0122046 0.00881926 0.024638 0.0128832 0.00795461 0.024638 0.0129933 0.00779108 0.0015875 0.0132281 0.00712 0.0015875 0.0130743 0.00760831 0.024638 0.0132685 0.00691089 0.024638 0.0126625 0.00823031 0.0249418 0.0116866 0.00821782 0.0254318 0.0118849 0.00844798 0.0253713 0.0129681 0.00691089 0.0252565 0.01242 0.00730542 0.0254278 0.0124922 0.00717491 0.0254257 0.0125371 0.00691089 0.0254283 0.0127677 0.00691089 0.0253653 0.0126203 0.00742392 0.0253713 0.0123625 0.00740946 0.0254294 0.0124034 0.00733541 0.0254282 0.0101327 0.0091841 0.0253141 0.0108235 0.00927377 0.0251993 0.0107631 0.00902345 0.0253713 0.0115543 0.00918471 0.0249418 0.0115819 0.00923847 0.024638 0.0108639 0.00944102 0.0249418 0.0112237 0.00937145 0.024638 0.0113582 0.00880249 0.0253713 0.0120529 0.0086431 0.0251993 0.0114758 0.00903162 0.0251993 0.0123136 0.00797973 0.0253713 0.0125227 0.00812994 0.0251993 0.0121652 0.00877347 0.0249418 0.0127115 0.00826555 0.024638 0.0128589 0.00752082 0.0251993 0.0130183 0.00758557 0.0249418 0.0117387 0.00666841 4.71331e-07 0.0117387 0.0067811 1.54049e-06 0.0116804 0.00676675 -1.78098e-09 0.0118477 0.00691089 1.24183e-05 0.0125983 0.00691089 0.000309432 0.0130389 0.00691089 0.00077031 0.0129594 0.00691089 0.000655523 0.0132685 0.00691089 0.0015875 0.0101327 0.0095108 0.00109694 0.011225 0.0093739 0.0015875 0.0120638 0.00883507 0.00109694 0.0115103 0.00927408 0.0015875 0.0121123 0.00889582 0.0015875 0.0121872 0.00882085 0.0015875 0.012615 0.00839308 0.0015875 0.0129233 0.00775737 0.00109694 0.0128891 0.00795686 0.0015875 0.0131523 0.00710271 0.00109694 0.0131586 0.00691089 0.00101067 0.0127201 0.00765953 0.00065439 0.0125543 0.00834464 0.00109694 0.012378 0.00820405 0.00065439 0.0114766 0.00920407 0.00109694 0.0113787 0.00900092 0.00065439 0.0101327 0.00910971 0.000478787 0.0108219 0.00943315 0.00109694 0.0101327 0.0094546 0.000986641 0.0129325 0.00705254 0.00065439 0.0119232 0.00865878 0.00065439 0.0107717 0.00921331 0.00065439 0.0106936 0.00887091 0.000303185 0.0101327 0.00893411 0.000303185 0.0125901 0.00697439 0.000303185 0.0124037 0.00750715 0.000303185 0.0123191 0.00691089 0.000146879 0.012005 0.00731514 7.76966e-05 0.0121034 0.00798507 0.000303185 0.0117574 0.00770915 7.76966e-05 0.0117043 0.00838419 0.000303185 0.0112263 0.00868449 0.000303185 0.0110343 0.00828577 7.76966e-05 0.011563 0.00710229 -1.78098e-09 0.0114283 0.0080382 7.76966e-05 0.0105951 0.00843946 7.76966e-05 0.0104859 0.0079612 -1.78098e-09 0.0101327 0.00849156 7.76966e-05 0.0117387 0.0043 0.00962475 0.0111774 -0.0020066 0.00200475 0.0117387 -0.0020066 0.00200475 0.00316293 -0.0020066 0.00656788 0.00477301 -0.0020066 0.00601795 0.00981849 0.000683101 0.00539559 0.0117387 0.00123363 0.00587067 0.00981849 0.00123363 0.00587067 0.00981849 0.00149856 0.00654787 0.00981849 0.00141655 0.00727041 0.0117387 0.00100659 0.007871 0.00981849 0.00100659 0.007871 0.00981849 0.000363588 0.00821061 0.0117387 -0.00100659 0.007871 0.00981849 -0.00100659 0.007871 0.0117387 -0.00141655 0.00727041 0.00981849 -0.00141655 0.00727041 0.0117387 -0.00123363 0.00587067 0.0117387 -0.000683101 0.00539559 0.0117387 0.0005461 0.00517259 0.00981849 0.0005461 0.00513981 0.00981849 -0.00123363 0.00444173 0.0117387 -0.00100659 0.0024414 0.00981849 -0.000363588 0.00210179 0.0117387 -0.000363588 0.00210179 0.00981849 0.000363588 0.00210179 0.00981849 0.00100659 0.0024414 0.00981849 0.00149856 0.00376453 0.0117387 0.00123363 0.00444173 0.00981849 0.00123363 0.00444173 0.0117387 -0.0005461 0.00513981 0.00981849 -0.000562772 0.00505005 0.0117387 -0.000683101 0.00491681 0.00981849 -0.000683101 0.00491681 0.00981849 -0.000683101 0.00539559 0.00981849 -0.000610564 0.00534015 0.0117387 -0.000562772 0.00526235 0.00981849 -0.000562772 0.00526235 0.00981849 0.0005461 0.00517259 0.00981849 0.000562772 0.00526235 0.0117387 0.000610564 0.00534015 0.0117387 0.000683101 0.00539559 0.0117387 0.0063 0.00962475 0.00958989 0.00616603 0.00912475 0.0117387 0.00616603 0.00912475 0.00958989 0.0058 0.00875872 0.0117387 0.0058 0.00875872 0.00958989 0.0053 0.00862475 0.00958989 0.0048 0.00875872 0.0117387 0.0048 0.00875872 0.0117387 0.00443397 0.00912475 0.00958989 0.0043 0.00962475 0.0064262 -0.0037846 0.00911675 0.00527301 -0.0025146 0.00550995 0.00858989 -0.0042926 0.00601795 0.0064262 -0.0042926 0.00860875 0.00858989 -0.00424975 0.00582567 0.00496317 -0.00424919 0.00582618 0.00493544 -0.00426548 0.00585419 0.00512379 -0.00414387 0.00566386 0.00858989 -0.00408319 0.00560697 0.0052334 -0.0039775 0.00555216 0.00858989 -0.00413939 0.00566316 0.00520766 -0.00403975 0.00557867 0.00858989 -0.00394158 0.00553481 0.00527301 -0.0037846 0.00550995 0.00858989 -0.00397687 0.0055528 0.00525528 -0.00392457 0.00552961 0.00858989 -0.00426774 0.00876573 0.00858989 -0.00421959 0.00886023 0.0064262 -0.0040386 0.00904869 0.00858989 -0.00394158 0.00909189 0.00858989 -0.0037846 0.00911675 -0.00159935 -0.0090043 -0.00345806 0.00173467 -0.0090043 -0.0033922 0.0028245 -0.0090043 -0.00255701 0.00163492 -0.0090043 -0.00147209 0.00323902 -0.0090043 -0.0020062 0.000894821 -0.0090043 -0.0020098 -0.00163492 -0.0090043 -0.00147209 -0.00218795 -0.0090043 0.000229964 -0.00370819 -0.0090043 -0.000874886 -0.00348985 -0.0090043 -0.00152875 -0.00315726 -0.0090043 -0.00213256 -0.00272131 -0.0090043 -0.00266656 -0.00249909 -0.0090043 0.00287588 -0.00190526 -0.0090043 0.0011 -0.00362624 -0.0090043 0.00116896 0.000457406 -0.0090043 0.00215192 0.00129313 -0.0090043 0.00177984 0.00205712 -0.0090043 0.00258909 0.00367332 -0.0090043 0.000243286 0.00358785 -0.0090043 0.000320064 0.00373985 -0.0090043 -0.000727752 0.00380526 -0.0090043 -0.000133848 0.00209232 -0.0090043 -0.000679837 0.00379601 -0.0090043 -9.15173e-05 -0.00167594 -0.0090043 0.00331812 -0.00210505 -0.0090043 0.00315365 0.000978851 -0.0090043 0.00315863 0.00311414 -0.0090043 0.00111233 0.00218795 -0.0090043 0.000229964 0.00249924 -0.0090043 0.0021654 0.000379083 -0.0090043 0.00330573 -0.000244139 -0.0090043 0.00338396 -0.000457406 -0.0090043 0.00215192 -0.000790343 -0.0090043 0.0033959 -0.00129313 -0.0090043 0.00177984 -0.00144814 -0.0090043 0.00335561 0.0105899 -0.00550625 0.0238442 0.0105899 0.0048 0.0210908 0.0105899 0.000978869 0.0226949 0.0105899 -0.000978869 0.0226949 0.0105899 -5.10722e-18 0.0209995 0.0105899 0.0043 0.0202248 0.011332 0.00629423 0.0234857 0.0113836 0.0063 0.0234604 0.0111329 0.00625936 0.0205069 0.0112083 0.00628038 0.0235464 0.0107675 0.00600663 0.0209323 0.0106503 0.00581001 0.0238442 0.0105899 0.00550625 0.0212032 0.010593 0.00557603 0.0211859 0.0109871 0.0061931 0.0238272 0.0108224 0.00606752 0.0238442 0.0107048 0.00589818 0.0210145 0.0106475 0.00579914 0.0210896 0.0106247 -0.00573865 0.0211234 0.0106503 -0.00581001 0.0238442 0.0105899 -0.00550625 0.0212032 0.0109871 -0.00619309 0.0238305 0.0106516 -0.005797 0.0210861 0.0109445 -0.00616176 0.0207228 0.010991 -0.00618561 0.0206695 0.0113836 -0.0063 0.0234609 0.0113836 -0.0063 0.0202248 0.0112562 -0.0062897 0.0235168 0.0111381 -0.00626107 0.020501 0.0113794 -0.00629999 0.0202295 0.0111774 -0.0020066 0.008812 0.000772976 -0.000146068 0.0072699 0.00260782 -0.000447158 0.00705719 0.00151232 -0.000279092 0.0072131 0.00281185 -0.000469659 0.00701496 0.00981849 -0.000472936 0.00701675 0.00317402 -0.000509602 0.00693999 0.00409208 -0.000543338 0.00668884 0.00390746 -0.000542371 0.00674365 0.00506766 -0.000345002 0.00632038 0.00487929 -0.000425355 0.00640121 0.00469962 -0.000469905 0.0064725 0.00429718 -0.000532144 0.00662103 0.00526264 -0.000188173 0.00623105 0.00523035 -0.000225333 0.00624626 0.00981849 -0.000472936 0.00647065 0.00532243 7.23729e-05 0.00620242 0.00532979 3.69212e-05 0.00619885 0.00532513 -6.18282e-05 0.00620111 0.00470556 0.000472212 0.00647103 0.0050698 0.000343835 0.00631943 0.00981849 0.0005461 0.0067437 0.0037389 0.000543673 0.00679513 0.00281086 0.000469146 0.00701468 0.00981849 0.000472936 0.00701675 0.00148251 0.000273947 0.00721612 0.00981849 0.00027305 0.00721664 0.00147722 0.000272991 0.00721651 0.00702921 -0.000536877 0.00346876 0.00630778 -0.000145872 0.00409496 0.00629404 -0.000104431 0.00410472 0.00981849 -0.000472936 0.00384175 0.00690527 -0.000545387 0.0035966 0.00669376 -0.000498317 0.00379209 0.00663583 -0.000472362 0.00384135 0.00710414 -0.000514456 0.0033855 0.00981849 -2.54494e-18 0.0030226 0.00737685 -8.48908e-05 0.00302924 0.00736852 -0.000143383 0.00304176 0.00981849 0.00027305 0.00309576 0.00737852 6.67837e-05 0.0030267 0.00732947 0.0002714 0.00309841 0.00716724 0.000481634 0.0033113 0.0066972 0.000499642 0.00378911 0.00689491 0.000544769 0.0036068 0.00693197 0.000542924 0.00356883 0.00702064 0.000538509 0.00347797 0.00642543 0.000323399 0.00400874 0.00981849 0.00027305 0.00404164 0.00650126 0.00039042 0.00395053 0.00662482 0.000467637 0.00385073 0.00663568 0.000472438 0.00384149 0.00981849 0.000472936 0.00384175 0.0062798 5.25822e-06 0.00411477 0.00634508 0.000220873 0.00406814 0.00638471 0.000271435 0.00403885 0.0064262 -0.0025146 0.00911675 0.00858989 -0.00234602 0.00908796 0.00858989 -0.00207692 0.00886182 0.0064262 -0.00207466 0.00886275 0.00858989 -0.00219655 0.00900487 0.00858989 -0.00226409 0.00904241 0.00858989 -0.0020195 0.0087225 0.0111774 -0.0020066 0.00860875 0.00858989 -0.00234602 0.00553874 0.00858989 -0.0025146 0.00550995 0.00858989 -0.00226409 0.00558429 0.00520816 -0.00226066 0.00557816 0.00520562 -0.00225692 0.00558075 0.00858989 -0.00207692 0.00576488 0.00858989 -0.0020195 0.0059042 0.00501796 -0.00208221 0.00577085 0.00501982 -0.0020833 0.00576897 0.00510705 -0.00213455 0.00568086 0.0111774 -0.0020066 0.00601795 0.00477619 -0.00200661 0.00601475 -0.0044775 -0.00762547 0.00693232 -0.00426955 -0.00777808 0.00668997 -0.00407606 -0.00791265 0.00629223 -0.00335516 -0.00835659 0.00517202 -0.0040392 -0.0079375 0.00605465 -0.00403859 -0.00793791 0.0060198 -0.00403859 -0.00793791 0.00528009 -0.00470426 -0.00744897 0.024638 -0.00472518 -0.00743049 0.024638 -0.00483549 -0.00734172 0.00721488 -0.00515352 -0.00706507 0.00738427 -0.00807902 -0.00194522 0.0075398 -0.00807254 -0.00200943 0.024638 -0.00791555 -0.0026333 0.0075398 -0.00762465 -0.00348835 0.0075398 -0.00761316 -0.00351393 0.0075398 -0.00730392 -0.00421274 0.024638 -0.00688122 -0.00497617 0.024638 -0.00686636 -0.00500302 0.024638 -0.00687797 -0.00497431 0.0075398 -0.00681456 -0.00508601 0.0075398 -0.00652835 -0.00551355 0.0075398 -0.00599829 -0.00619403 0.024638 -0.00590332 -0.00629521 0.024638 -0.0059069 -0.00629859 0.0075398 -0.00538353 -0.00684899 0.024638 -0.00827183 0.000542332 0.0075398 -0.00828453 -0.000227444 0.024638 -0.00826408 0.000664371 0.024638 -0.00822667 0.00107234 0.0075398 -0.00805684 0.00208084 0.024638 -0.00782014 0.00294452 0.024638 -0.00785981 0.00281972 0.0075398 -0.00755183 0.00366781 0.0075398 -0.0072877 0.00424554 0.024638 -0.0068463 0.00503552 0.024638 -0.00575992 0.00646268 0.024638 -0.00406662 0.00791904 0.00625554 -0.00472133 0.00743525 0.024638 -0.00418876 0.00783513 0.0065624 -0.0042429 0.00779705 0.00665097 -0.00529668 0.00692456 0.024638 -0.00460319 0.007529 0.00704561 -0.00525367 0.00697273 0.00742486 -0.0054013 0.00683169 0.024638 -0.00342762 0.00831581 0.00519161 -0.0038073 0.00808836 0.00526238 -0.00402169 0.00794891 0.00527879 -0.00257736 0.0087372 0.024638 -0.00285293 0.00861739 0.00497725 -0.00223507 0.00888973 0.00454235 -0.00230315 0.00886219 0.00460609 -0.00157778 0.0091258 0.00417613 -0.00128384 0.00921453 0.00435406 -0.00255987 0.00875292 0.00480616 -0.00102646 0.009282 0.00445922 -0.00185816 0.00903159 0.0040344 -0.00191135 0.00901264 0.00413159 0.000171484 0.00951145 0.00467512 0.000361563 0.00953351 0.024638 -0.00102672 0.0092828 0.024638 -0.000437582 0.00941518 0.00462389 0.00088312 0.00957494 0.00461998 0.000663844 0.00956092 0.00464939 0.00126796 0.00958764 0.024638 0.000607972 0.00955531 0.00465231 0.000608343 0.00954825 0.024638 -0.00128112 -0.0092153 0.00435544 -0.00185123 -0.00903313 0.024638 -0.000302896 -0.00943991 0.0046439 0.000483308 -0.00954592 0.024638 -0.000248991 -0.00944285 0.024638 -0.000414649 -0.00941953 0.024638 -0.00245929 -0.00879679 0.00473423 -0.00335254 -0.00835152 0.024638 -0.0033549 -0.00835674 0.00517196 -0.00272953 -0.00867594 0.00491117 -0.00178251 -0.0090579 0.00400499 -0.00185152 -0.00903385 0.00402001 0.0101327 0.008001 -1.78098e-09 0.00769066 -0.00786606 -1.78098e-09 0.0117202 -0.0064135 -1.78098e-09 0.0113738 -0.00740329 -1.78098e-09 0.00650581 -0.00738363 -1.78098e-09 0.0111225 0.00765466 -1.78098e-09 0.0113738 0.00740329 -1.78098e-09 0.00769066 0.00786606 -1.78098e-09 0.0108215 0.00784379 -1.78098e-09 0.0108215 -0.00784379 -1.78098e-09 0.0111225 -0.00765466 -1.78098e-09 0.00678734 -0.0074803 -1.78098e-09 0.0072898 -0.0062103 -1.78098e-09 0.00719313 0.00669631 -1.78098e-09 0.00755342 0.0076512 -1.78098e-09 0.00700151 0.00750644 -1.78098e-09 0.00714185 0.00752358 -1.78098e-09 0.00719664 0.00753681 -1.78098e-09 0.00691783 -0.00710833 -1.78098e-09 0.00758177 0.00766205 -1.78098e-09 0.00775245 0.00772736 -1.78098e-09 0.0117202 0.0064135 -1.78098e-09 0.00650581 0.00738363 -1.78098e-09 0.00757772 -0.00766532 -1.78098e-09 0.00691783 0.00710833 -1.78098e-09 0.00220424 -0.0095885 0.00417308 0.00407554 -0.0095885 0.00237976 0.000392306 -0.0059817 0.00727924 0.000752665 -0.00594026 0.00725084 0.000914034 -0.00589352 0.00723227 0.000951554 -0.00587539 0.00722666 0.00124278 -0.00573467 0.00718308 0.00179523 -0.00513715 0.00706529 0.00173334 -0.00524378 0.00708073 0.00163409 -0.00538321 0.00710429 0.00162209 -0.00539515 0.00710682 0.00143668 -0.00557963 0.00714594 0.00407554 0.0095885 0.00237976 0.00444445 0.0095885 0.0015875 0.001397 0.0095885 0.00450795 0.00220424 0.0095885 0.00417308 0.00356687 0.0095885 0.00309042 0.00264334 -0.00798046 0.0254318 0.00264334 -0.00798046 0.00808355 0.00385982 -0.00769257 0.00808355 0.00685803 -0.00452999 0.0144335 0.0064262 0.00559833 0.0144335 0.00685803 0.00452999 0.0144335 0.0064262 0.0047121 0.0144335 0.00729556 0.00228375 0.0144335 0.0074422 -1.04083e-17 0.0144335 0.0064262 -0.0047121 0.0144335 0.00490003 -0.00720666 0.0254318 0.0064741 -0.00537433 0.00808355 0.0064262 -0.00559833 0.0144335 0.0064741 -0.00537433 0.0144335 0.00624697 -0.00599823 0.0254318 0.00578453 -0.00647466 0.00808355 0.0064262 -0.0020066 0.00860875 0.0064262 0.0047121 0.00808355 0.0064262 -0.00422454 0.00886275 0.0064262 -0.0022606 0.00904869 0.00624697 0.00599823 0.0254318 0.0064741 0.00537433 0.0144335 0.00624697 0.00599823 0.00808355 0.00578453 0.00647466 0.0254318 0.00490003 0.00720666 0.00808355 0.00385982 0.00769257 0.00808355 0.00264334 0.00798046 0.0254318 0.00264334 0.00798046 0.00808355 0.001397 0.0080772 0.0254318 0.001397 -0.0080772 0.00808355 0.000984668 -0.00806687 0.00808355 0.000984668 -0.00806687 0.0254318 -0.000444516 -0.00786995 0.00808355 -0.00188208 -0.00739984 0.00808355 -0.00188208 -0.00739984 0.0254318 -0.00437065 -0.00572571 0.00808355 -0.00524565 -0.00470894 0.00808355 -0.00600975 -0.00341724 0.0254318 -0.00652019 -0.00200692 0.0254318 -0.00652019 -0.00200692 0.00808355 -0.00675876 -0.000521537 0.0254318 -0.00671639 0.000974965 0.00808355 -0.00671639 0.000974965 0.0254318 -0.00639228 0.00244794 0.0254318 -0.00158054 0.00752313 0.0254318 0.001397 0.0080772 0.00808355 0.00685803 0.00452999 0.0254318 0.0064262 0.00559833 0.0254318 0.00744122 0.000187544 0.0210151 0.00742233 0.000842109 0.0213758 0.00742012 0.000887813 0.0214302 0.00740639 0.00113027 0.0221384 0.00740916 0.0010858 0.0224438 0.00729556 0.00228375 0.0254318 0.00741568 0.000970366 0.0226905 0.00741844 0.000920915 0.0227851 0.0074206 0.000878094 0.0228415 0.00743027 0.000652614 0.0230526 0.00743235 0.000593129 0.0230919 0.0074422 1.2761e-18 0.0254318 0.0074395 0.00031066 0.0232165 0.00742827 -0.000705285 0.023013 0.00744057 0.000240956 0.0232341 0.00743958 -0.000305765 0.0232179 0.00743293 -0.000560948 0.0231004 0.00741649 -0.000957812 0.0227299 0.00740924 -0.00108447 0.0224483 0.0074068 -0.00112384 0.0221292 0.00729556 -0.00228375 0.0254318 0.00740649 -0.00112878 0.0220712 0.00741155 -0.00104584 0.021701 0.00742218 -0.000845362 0.0213795 0.00729556 -0.00228375 0.0144335 0.00743373 -0.000549897 0.0211422 0.0074422 2.14346e-18 0.0144335 0.00744179 -0.000120964 0.0210059 0.00744157 -2.9983e-07 0.0210095 0.00740686 -0.00112282 0.022 0.00685803 -0.00452999 0.0254318 0.00741568 0.000969751 0.0215699 0.00744156 -1.18403e-09 0.0210095 0.00741556 -0.000972052 0.0215692 0.0105899 -0.00056515 0.0231086 0.00743042 -0.000648478 0.0230555 0.00743829 -0.000373712 0.0231965 0.00741858 -0.000918078 0.0227891 0.00740813 -0.00110253 0.0223788 0.00741554 -0.000974449 0.0226929 0.0105899 -0.000978869 0.0215646 0.00741322 -0.00101691 0.0216363 0.0105899 -0.0011303 0.0221297 0.00744117 -0.00019214 0.0210159 0.00743558 -0.000486311 0.0211094 0.00743321 -0.00056379 0.0211527 0.0105899 -0.00056515 0.0211509 0.00742442 -0.000796682 0.021328 0.00743386 0.000545648 0.0211399 0.0105899 0.00056515 0.0211509 0.00744034 0.000257433 0.0210292 0.0074319 0.000606532 0.021176 0.00743324 0.000564906 0.0211513 0.0105899 0.0011303 0.0221297 0.00740641 0.00113006 0.0221298 0.0074065 0.00112854 0.0220666 0.0105899 0.000978869 0.0215646 0.00741015 0.00106939 0.0217637 0.00741165 0.001044 0.0216966 0.00741048 0.00106392 0.0225114 0.0105899 0.00056515 0.0231086 0.0074422 -3.44604e-18 0.02326 0.0105899 -4.19e-18 0.02326 0.0074331 0.000563542 0.023105 -0.00218581 -0.0043942 0.00808355 -0.00218581 -0.0035941 0.0072898 -0.00206496 -0.00500171 0.0072898 -0.00172084 -0.00551674 0.00808355 -0.00120582 -0.00586086 0.00808355 -0.000598306 -0.0059817 0.00808355 -0.00172084 -0.00551674 0.0072898 -0.00120582 -0.00586086 0.0072898 -0.00565161 -0.0062103 0.0072898 -0.000598306 -0.0059817 0.0072898 -1.44869e-10 -0.0059817 0.0072898 -0.00802223 0.000528107 0.0072898 -0.00172084 -0.00247157 0.0072898 -0.00797827 0.00104412 0.0072898 -0.00620898 0.00552817 0.0072898 -0.00120582 -0.00212744 0.0072898 -0.00711143 0.00403724 0.0072898 -0.00669578 0.00480291 0.0072898 -0.0076753 -0.00256415 0.0072898 -0.00795678 -0.0012187 0.0072898 -0.00632441 -0.00536896 0.0072898 -0.00660315 -0.00495257 0.0072898 -0.00218581 -0.0043942 0.0072898 -0.00703396 -0.00419361 0.0072898 0.0064262 -0.0042926 0.00808355 0.00263704 -0.00439507 0.00808355 -0.00120582 -0.00212744 0.00808355 -0.00495928 0.00508066 0.00808355 -0.00580274 0.00382576 0.00808355 -0.00639228 0.00244794 0.00808355 -0.004153 0.00593196 0.00808355 -0.00294018 0.00684809 0.00808355 -0.000598306 -0.0020066 0.00808355 0.00144208 -0.00558506 0.00808355 0.00179523 -0.00513715 0.00808355 0.00490003 -0.00720666 0.00808355 -0.00206496 -0.00298659 0.00808355 -0.00675876 -0.000521537 0.00808355 -0.00600975 -0.00341724 0.00808355 -0.00206496 -0.00500171 0.00808355 -0.0032061 -0.00667651 0.00808355 0.000392306 -0.0059817 0.00808355 0.000953409 -0.00587924 0.00808355 0.0064262 -0.0020066 0.00808355 0.00624697 -0.00599823 0.00808355 0.00214838 -0.00468924 0.00808355 0.0064262 -0.0047121 0.00808355 0.00578453 0.00647466 0.00808355 0.0064741 0.00537433 0.00808355 -0.00158054 0.00752313 0.00808355 -0.000115343 0.00793801 0.00808355 0.0109387 -0.0063 0.0252302 0.0113836 0.0063 0.0202248 0.00958989 -0.0063 0.00200475 0.00958989 -0.0043 0.0202248 0.00958989 0.0043 0.0202248 0.00958989 0.00443397 0.00912475 0.00958989 -0.0053 0.0212248 0.00958989 -0.00616603 0.0207247 0.00958989 -0.00443397 0.0207247 0.00958989 0.0063 0.00962475 0.00958989 -0.0050046 0.00949513 0.00958989 -0.00467098 0.00982875 0.00958989 -0.00521879 0.00555195 0.00958989 -0.0052926 0.00860875 0.00958989 -0.00521879 0.00907475 0.00958989 -0.0042506 0.0100429 0.00958989 -0.0025146 0.0101168 0.00958989 -0.0020195 0.00200475 0.00958989 -0.0025146 0.00450995 0.00958989 -0.0037846 0.00450995 0.00958989 -0.0042506 0.00458376 0.00958989 -0.00467098 0.00479795 0.0101327 -0.0095885 0.024638 0.0115824 -0.00923819 0.024638 0.0115103 -0.00927408 0.0015875 0.0128898 -0.00795572 0.0015875 0.0129933 -0.00779108 0.0015875 0.00900239 -0.00550625 0.0254318 0.00940121 -0.00550625 0.0253808 0.00978748 0.00550625 0.025224 0.00978748 -0.00550625 0.025224 0.0101242 -0.00550625 0.0249662 0.0103747 0.00550625 0.0246423 0.0104564 0.00550625 0.0244465 0.0105351 -0.00550625 0.0242575 0.0105899 0.00550625 0.0238442 0.0101327 -0.0090985 0.0253713 0.0116872 -0.00821738 0.0254318 0.0120674 -0.00780181 0.0254318 0.0124806 -0.0072084 0.0254257 0.0125387 -0.00690911 0.0254282 0.0126208 -0.00742274 0.0253713 0.0128594 -0.00751953 0.0251993 0.0130189 -0.00758421 0.0249418 0.0131491 -0.00690911 0.0250547 0.0130749 -0.00760692 0.024638 0.0132688 -0.00690911 0.024638 0.0124223 -0.00730346 0.0254275 0.0124036 -0.007334 0.0254281 0.0123417 -0.00743483 0.02543 0.0107633 -0.00902339 0.0253713 0.0108238 -0.0092737 0.0251993 0.0114763 -0.00903136 0.0251993 0.0101327 -0.0091841 0.0253141 0.0101327 -0.00935602 0.0251993 0.0126632 -0.00822935 0.0249418 0.0128838 -0.00795344 0.024638 0.0123142 -0.0079789 0.0253713 0.0125234 -0.00812903 0.0251993 0.0121659 -0.0087729 0.0249418 0.0127123 -0.00826458 0.024638 0.0118855 -0.00844748 0.0253713 0.0113587 -0.00880226 0.0253713 0.0120536 -0.00864255 0.0251993 0.0121942 -0.00882614 0.024638 0.0122053 -0.00881867 0.024638 0.0108784 -0.00949968 0.024638 0.0108642 -0.00944095 0.0249418 0.0112241 -0.00937128 0.024638 0.0115548 -0.00918444 0.0249418 0.001397 -0.0095885 0.024638 0.0101327 -0.00952808 0.0249418 0.0101327 -0.00947089 0.0250273 0.0101327 -0.00879475 0.0254318 0.001397 0.00919162 0.0253254 0.001397 0.00948216 0.0250349 -0.000163712 0.00946335 0.024638 -0.00105082 0.00927776 0.024638 -0.00191702 0.0090106 0.024638 -0.00276108 0.00866113 0.024638 -0.00321886 0.00843108 0.024638 -0.00271586 0.00856488 0.0250349 -0.00316861 0.00833737 0.0250349 -0.00399299 0.00796832 0.024638 -0.00402092 0.00794788 0.024638 -0.00472133 0.00743525 0.024638 -0.00465458 0.00735247 0.0250349 -0.00532704 0.00675558 0.0250349 -0.00548464 0.00674595 0.024638 -0.00633611 0.00577517 0.024638 -0.00653018 0.00549382 0.024638 -0.0073618 0.00408619 0.024638 -0.00750348 0.00378151 0.024638 -0.00771902 0.00291161 0.0250349 -0.00792594 0.00255848 0.024638 -0.00821236 0.00119154 0.024638 -0.00823534 0.000957283 0.024638 -0.00828453 -0.000227444 0.024638 -0.00827737 -0.000328374 0.024638 -0.00822118 -0.00111984 0.024638 -0.00808314 -0.001946 0.024638 -0.0079686 -0.00198696 0.0250349 -0.00794112 -0.00254276 0.024638 -0.0076621 -0.00339179 0.024638 -0.00756275 -0.00335388 0.0250349 -0.0076095 -0.00351235 0.024638 -0.00720856 -0.00416568 0.0250349 -0.00654794 -0.00548581 0.024638 -0.00591743 -0.00612496 0.0250349 -0.00530946 -0.00677268 0.0250349 -0.00463769 -0.00736604 0.0250349 -0.00470426 -0.00744897 0.024638 -0.00424027 -0.00779889 0.024638 -0.0034818 -0.00828479 0.024638 -0.0026791 -0.00869924 0.024638 -0.00263478 -0.00860258 0.0250349 -0.00179972 -0.00893936 0.0250349 -0.00183486 -0.00903973 0.024638 -0.00129475 -0.00921141 0.024638 -0.000394972 -0.00931503 0.0250349 0.00126938 0.00948131 0.0250349 0.000372797 0.00942777 0.0250349 0.000403487 0.00913886 0.0253254 -0.000146789 0.00935836 0.0250349 -0.00102425 0.00917479 0.0250349 -0.00188097 0.00891055 0.0250349 -0.00178251 0.00863722 0.0253254 -0.00259229 0.00830194 0.0253254 -0.00393424 0.00787967 0.0250349 -0.00568171 0.00639063 0.0250349 -0.00546802 0.00619379 0.0253254 -0.00602032 0.00553479 0.0253254 -0.00625149 0.00571076 0.0250349 -0.00675603 0.0049793 0.0250349 -0.00650943 0.0048257 0.0253254 -0.0071925 0.00419815 0.0250349 -0.00740589 0.00373926 0.0250349 -0.00744275 0.00282168 0.0253254 -0.00795307 0.00205759 0.0250349 -0.00810686 0.0011782 0.0250349 -0.008158 0.000656952 0.0250349 -0.00817822 -0.000224915 0.0250349 -0.00786817 0.000636682 0.0253254 -0.00788777 -0.000218009 0.0253254 -0.00811558 -0.00110731 0.0250349 -0.00768462 -0.00192559 0.0253254 -0.00783864 -0.00251436 0.0250349 -0.00729131 -0.00325029 0.0253254 -0.00694801 -0.00403714 0.0253254 -0.00677586 -0.00494717 0.0250349 -0.00652861 -0.00479461 0.0253254 -0.00646098 -0.00542461 0.0250349 -0.00622338 -0.00525741 0.0253254 -0.00569652 -0.00593626 0.0253254 -0.00510711 -0.00656421 0.0253254 -0.00401093 -0.00747499 0.0253254 -0.00417882 -0.0077121 0.0250349 -0.00328345 -0.00794103 0.0253254 -0.00342865 -0.00819268 0.0250349 -0.00126551 -0.00910917 0.0250349 0.000493224 -0.00944004 0.0250349 0.001397 -0.00948216 0.0250349 0.000520313 -0.00915077 0.0253254 0.00127323 0.0091908 0.0253254 0.00127851 0.00879396 0.0254318 0.000445411 0.0087442 0.0254318 -0.000100555 0.00907153 0.0253254 -3.73965e-05 0.00867971 0.0254318 -0.000951648 0.00889347 0.0253254 -0.00164799 0.00826383 0.0254318 -0.0024235 0.00794274 0.0254318 -0.00303131 0.00808132 0.0253254 -0.00377375 0.00763749 0.0253254 -0.0044722 0.00712631 0.0253254 -0.00512415 0.00654762 0.0253254 -0.00693242 0.00406866 0.0253254 -0.00617255 0.00461588 0.0254318 -0.00657714 0.00389179 0.0254318 -0.00677506 0.00346616 0.0254318 -0.00713927 0.00362383 0.0253254 -0.00706537 0.00269884 0.0254318 -0.00766956 0.00199408 0.0253254 -0.00728229 0.00190731 0.0254318 -0.00781862 0.00114175 0.0253254 -0.00742488 0.00109196 0.0254318 -0.00749101 -0.000208574 0.0254318 -0.00782707 -0.00107307 0.0253254 -0.0072967 -0.00184175 0.0254318 -0.00755866 -0.00243677 0.0253254 -0.0071762 -0.00233077 0.0254318 -0.00692051 -0.0031088 0.0254318 -0.00589881 -0.00502902 0.0254318 -0.00483068 -0.00627943 0.0254318 -0.00420741 -0.00682996 0.0254318 -0.00445583 -0.00713946 0.0253254 -0.00378159 -0.00715109 0.0254318 -0.00251366 -0.00833849 0.0253254 -0.00234822 -0.00797775 0.0254318 -0.0017037 -0.00866516 0.0253254 -0.00157254 -0.00829058 0.0254318 -0.00118562 -0.00882983 0.0253254 -0.000341213 -0.00902951 0.0253254 -0.000267778 -0.00863949 0.0254318 0.001397 -0.00919162 0.0253254 0.0101327 0.0090985 0.0253713 0.0101327 0.00935602 0.0251993 0.001397 0.0095885 0.024638 0.0101327 0.00952808 0.0249418 0.0101327 0.00947089 0.0250273 0.0105757 -0.00606752 0.0247592 0.0109387 -0.00627929 0.0249803 0.0103416 -0.00623732 0.0254318 0.0104071 -0.0062557 0.0254318 0.010583 -0.00627675 0.0254318 0.00916144 -0.0056183 0.0254318 0.00924569 -0.00567678 0.0254318 0.00942183 -0.00578613 0.0254318 0.00944164 -0.00579843 0.0254318 0.00960474 -0.00550625 0.0252982 0.00981737 -0.00581001 0.0252765 0.00990644 -0.00605936 0.0254244 0.00979557 -0.00601815 0.0254318 0.0109387 -0.00623767 0.0245745 0.0109387 -0.00621152 0.0243722 0.0109387 -0.00617203 0.0240667 0.0104564 -0.00550625 0.0244465 0.0103747 -0.00550625 0.0246423 0.0107596 -0.00606752 0.0243181 0.0108224 -0.00606752 0.0238442 0.0109614 -0.00617883 0.0238987 0.0107983 -0.00623958 0.0248886 0.0105935 -0.00581001 0.0242733 0.0107075 -0.0058956 0.0238442 0.0101196 -0.00550625 0.0249721 0.0104645 -0.00623958 0.0253202 0.0102832 -0.00606752 0.0251372 0.0101621 -0.00581001 0.025015 0.0104269 -0.00581001 0.0246727 0.0107075 0.0058956 0.0238442 0.0107596 0.00606752 0.0243181 0.00944308 0.00580377 0.0254318 0.00981737 0.00581001 0.0252765 0.0100309 0.00613094 0.0254318 0.0099067 0.00605927 0.0254243 0.0102278 0.00620539 0.0254318 0.0103387 0.00623073 0.0254318 0.0105913 0.0062884 0.0254318 0.0104645 0.00623958 0.0253202 0.0109373 0.00623816 0.0245839 0.0107983 0.00623958 0.0248886 0.0109373 0.00624518 0.024638 0.0109373 0.00628026 0.0249782 0.01094 0.00616906 0.0240085 0.00941907 0.00578796 0.0254318 0.00940121 0.00550625 0.0253808 0.00960474 0.00550625 0.0252982 0.0101621 0.00581001 0.025015 0.0101196 0.00550625 0.0249721 0.0101242 0.00550625 0.0249662 0.0104269 0.00581001 0.0246727 0.0105351 0.00550625 0.0242575 0.0105935 0.00581001 0.0242733 0.0105757 0.00606752 0.0247592 0.0102832 0.00606752 0.0251372 0.00988973 0.00605775 0.0254318 0.00991256 0.00606959 0.0254318 -1.44869e-10 -0.0020066 0.0072898 0.00162213 -0.0020066 0.00710703 0.0014138 -0.000538713 0.00715139 0.00296724 -0.000983651 0.00665858 0.00243793 -0.000863119 0.00687006 0.00187746 -0.000696683 0.00704389 0.00316106 -0.00100966 0.00656405 0.0038255 -0.00104877 0.00620538 0.00552005 0.00348435 0.00476132 0.00454512 -0.0042926 0.00569939 0.00477301 -0.0042926 0.00550995 0.00495916 -0.00425665 0.00534302 0.00512008 -0.00415252 0.00518902 0.00520956 -0.00226283 0.00509918 0.00520514 -0.00225728 0.00510361 0.00493383 -0.00203317 0.00536642 0.00488961 -0.000434946 0.00540674 0.00401723 -0.00102716 0.00608301 0.00454512 -0.0020066 0.00569939 0.00454485 -0.000829517 0.00569905 0.00477301 -0.0020066 0.00550995 0.00497569 0.000139696 0.00532763 0.00491796 0.000368082 0.00538097 0.00454434 0.00082356 0.00569842 0.00463201 0.00284701 0.005629 0.00478371 0.00285414 0.00550066 0.0048609 0.000491392 0.00543257 0.00531514 0.00310363 0.00498903 0.00473952 0.000663681 0.00553879 0.00513744 0.00296836 0.0051712 0.00511961 0.00295479 0.00518948 0.00501778 -0.0020825 0.00528664 0.00555088 0.00371092 0.00472535 0.00554843 0.00373551 0.00472821 0.00552551 0.00396485 0.00475498 0.00544653 0.00417992 0.0048452 0.00544346 0.00418827 0.0048487 0.0052377 0.00443923 0.00507027 0.00488931 0.00460046 0.00540701 0.00319815 -0.0042926 0.00655081 0.0033095 -0.0062103 0.00649526 0.00428484 -0.0062103 0.00589757 0.0045332 -0.0062103 0.00568545 0.00215123 -0.00469305 0.00696439 0.00239761 -0.00450922 0.00688423 0.00263975 -0.00440321 0.00679298 0.00287271 -0.00432632 0.0066999 0.00114038 -0.0062103 0.00720005 0.00137509 -0.00564092 0.00715893 0.00161699 -0.0062103 0.00708563 0.00225267 -0.0062103 0.00693301 0.00114038 0.0062103 0.00720005 0.0016203 0.000607072 0.00709951 1.54961e-05 6.09449e-06 0.00728978 0.0046475 0.00461988 0.00561437 0.0045332 0.0062103 0.00568545 0.00360819 0.00425705 0.00633421 0.00407496 0.0045137 0.00604449 0.0033095 0.0062103 0.00649526 0.00405442 0.0045049 0.00605793 0.00390634 0.00444146 0.00615481 0.00358444 0.00423792 0.00634767 0.00329427 0.00373589 0.006503 0.00331799 0.00388187 0.00649093 0.00315871 0.0062103 0.00655772 0.00329617 0.00369455 0.00650203 0.00333166 0.00355271 0.00648392 0.00343586 0.00338151 0.00642931 0.00316069 0.0010084 0.00656337 0.00349533 0.00104941 0.00639718 0.00424333 0.000973969 0.00592751 0.00454359 0.00285878 0.00569742 0.00607773 0.000753602 0.00402523 0.00656782 0.00103723 0.0031629 0.00656327 0.00103945 0.00317248 0.00649526 0.0062103 0.0033095 0.00644573 0.00105153 0.00340497 0.0063907 0.00103812 0.00350715 0.00589757 0.0062103 0.00428484 0.00619324 0.000902648 0.00384513 0.00593172 0.000426337 0.00423744 0.00568545 -0.0062103 0.0045332 0.00527301 -0.0025066 0.00503354 0.0059506 -0.000485527 0.00421088 0.00597017 -0.00053897 0.00418309 0.00606034 -0.000725215 0.00405135 0.00657128 -0.0010363 0.00315587 0.00693301 -0.0062103 0.00225267 0.00649526 -0.0062103 0.0033095 0.00638733 -0.00103694 0.00351328 0.00625769 -0.000961869 0.00373932 0.0068351 -0.00061262 0.00253429 0.00685962 -0.000496894 0.00246714 0.00689957 7.24e-05 0.00235311 0.00708562 0.0062103 0.00161699 0.00688002 0.000358897 0.00240966 0.00708562 -0.0062103 0.00161699 0.00720005 -0.0062103 0.00114038 0.0060198 0.0074803 -1.78098e-09 0.000952628 0.0074803 0.00055 0.00677931 0.0074803 -4.17038e-06 -0.00592149 0.0074803 0.00128168 0.00389281 0.0074803 -0.00464251 0.00055 0.0074803 -0.000952629 -0.00055 0.0074803 0.000952629 -0.00392896 0.0074803 0.00500831 -0.00403112 0.0074803 0.00470929 -0.00510829 0.0074803 0.00325764 -0.00560269 0.0074803 0.0023058 0.00616109 0.0074803 -0.000529462 -0.00399655 0.0074803 -0.0045535 -0.00473689 0.0074803 -0.00377739 -0.000952628 0.0074803 -0.00055 -1.44869e-10 0.0074803 0.0011 0.00536368 0.0074803 0.00273293 0.00465046 0.0074803 -0.0038833 0.00526237 0.0074803 -0.00300238 0.000952628 0.0074803 -0.00055 0.0011 0.0074803 -1.78098e-09 0.00487012 0.0074803 0.00353835 -6.83606e-05 -0.0074803 -0.00605823 0.00623491 -0.0074803 -0.000430377 0.0060198 -0.0074803 -1.78098e-09 -0.000952628 -0.0074803 0.00055 0.00570934 -0.0074803 -0.00202736 -0.00445375 -0.0074803 0.00410742 -0.00510827 -0.0074803 0.00325767 -0.00419687 -0.0074803 0.00442385 -0.00403111 -0.0074803 0.0047093 -0.00055 -0.0074803 0.000952629 -0.00216725 -0.0074803 -0.00565772 -0.00313097 -0.0074803 -0.00518689 -0.00055 -0.0074803 -0.000952629 0.000952628 -0.0074803 -0.00055 0.00353835 -0.0074803 0.00487012 0.000952628 -0.0074803 0.00055 0.00487012 -0.0074803 0.00353835 -1.44869e-10 -0.0074803 0.0060198 -0.0047369 -0.0074803 -0.00377737 -0.000952628 -0.0074803 -0.00055 -0.00575364 -0.0074803 -0.00189801 -0.0011 -0.0074803 -1.78098e-09 0.0038928 -0.0074803 -0.00464251 0.00100102 -0.0074803 -0.00597535 -0.00593273 -0.00789442 -0.00195709 -0.00525954 -0.00836298 -0.00230397 -0.00475829 -0.00836298 -0.00321398 -0.00410128 -0.00836298 -0.00401877 -0.00412097 -0.00789442 -0.00469522 -0.00358728 -0.00789442 -0.00508575 -0.00331 -0.00836298 -0.004692 -0.00117095 -0.00789442 -0.00613648 0.000686299 -0.00789442 -0.00618815 0.00378955 -0.00789442 -0.00494359 0.0042568 -0.00836298 -0.00385366 0.00488151 -0.00836298 -0.00302355 -0.00395974 -0.00893083 0.00212749 0.00424635 -0.00897412 -0.000189928 0.00461131 -0.00890088 -0.000297667 0.00512034 -0.00871008 -0.000521684 0.00575288 -0.0083076 -0.000841713 -0.00428351 -0.00808725 0.00429361 -0.00360825 -0.00844818 0.00431164 -0.0023912 -0.00892997 0.00380603 -0.00294845 -0.00893083 0.003393 -0.00262454 -0.00884987 0.00401527 -0.0028302 -0.00877603 0.00412535 -0.00223801 -0.00900221 0.003226 -0.00223241 -0.00899324 0.00341161 -0.00377752 -0.0090043 0.000496415 -0.00372497 -0.00893083 -0.00251602 -0.00411736 -0.00893083 -0.00180363 -0.00471634 -0.00871377 -0.00206602 -0.00453579 -0.00871377 0.00243699 -0.00335625 -0.0090043 0.00180324 -0.00378117 -0.00836116 0.00431722 -0.00402242 -0.00871377 0.00321441 -0.00375296 -0.00837536 0.00431631 -0.00337738 -0.00871377 0.00388659 -0.00351158 -0.00893083 0.00280617 -0.00297639 -0.0090043 0.00237849 0.00563632 -0.00836298 -0.00109679 0.0050542 -0.00871377 -0.000983519 -0.00569309 -0.00836298 0.000748145 -0.00573471 -0.00836298 -0.000289941 0.00588706 -0.00789442 -0.00209047 0.00580354 -0.00789442 -0.00227265 0.00534643 -0.00836298 -0.00209445 0.00441232 -0.00893083 -0.00085861 0.00479522 -0.00789442 -0.00400417 0.00479425 -0.00871377 -0.00187814 0.00401397 -0.00789442 -0.00478702 0.00437736 -0.00871377 -0.00271128 0.0035475 -0.0090043 -0.00138973 0.00418538 -0.00893083 -0.00163962 0.00283623 -0.00789442 -0.00554459 0.00261432 -0.00836298 -0.00511237 0.00349273 -0.00836298 -0.00455762 0.00381716 -0.00871377 -0.00345566 0.003132 -0.00871377 -0.00408691 0.00382143 -0.00893083 -0.00236695 0.00234431 -0.00871377 -0.00458437 0.00273424 -0.00893083 -0.00356787 0.00333238 -0.00893083 -0.00301679 0.00165032 -0.00836298 -0.00549977 0.00147988 -0.00871377 -0.00493176 0.00204659 -0.00893083 -0.00400216 -7.04887e-05 -0.00789442 -0.0062468 0.000632304 -0.00836298 -0.00570712 0.000567 -0.00871377 -0.00511769 0.00231752 -0.0090043 -0.0030241 -0.00143183 -0.00836298 -0.00556065 -0.000406415 -0.00836298 -0.00572764 0.00109503 -0.0090043 -0.00364925 0.00129194 -0.00893083 -0.00430542 -0.00261228 -0.00789442 -0.00564937 -0.00241037 -0.00836298 -0.00521163 -0.00128395 -0.00871377 -0.00498636 -0.000364441 -0.00871377 -0.0051361 0.000494991 -0.00893083 -0.00446775 -0.000318157 -0.00893083 -0.00448381 -0.00322843 -0.00789442 -0.00534834 -0.00216143 -0.00871377 -0.00467338 0.000419551 -0.0090043 -0.00378683 -0.00112089 -0.00893083 -0.00435309 -0.000950058 -0.0090043 -0.00368964 -0.000269668 -0.0090043 -0.00380045 -0.00296815 -0.00871377 -0.00420742 -0.0025912 -0.00893083 -0.00367307 -0.00188693 -0.00893083 -0.00407986 -0.00321064 -0.00893083 -0.00314604 -0.00367771 -0.00871377 -0.00360372 -0.00219628 -0.0090043 -0.00311327 -0.0060564 -0.00789442 -0.00142895 -0.0055886 -0.00836298 -0.00131854 -0.00426686 -0.00871377 -0.00288204 -0.00501142 -0.00871377 -0.00118236 -0.00514244 -0.00871377 -0.000259997 -0.00448935 -0.00893083 -0.000226976 -0.00437497 -0.00893083 -0.0010322 -0.00577707 -0.00789442 0.0023776 -0.0054651 -0.00836298 0.00176174 -0.00510512 -0.00871377 0.000670878 -0.00490067 -0.00871377 0.00157979 -0.00380514 -0.0090043 -0.000192383 -0.0048617 -0.00789442 0.00388562 -0.0044857 -0.00836298 0.00358462 -0.00505819 -0.00836298 0.00271766 -0.00427828 -0.00893083 0.00137916 -0.00445677 -0.00893083 0.000585677 0.00154447 0.0090043 0.002924 0.000978851 0.0090043 0.00315863 -0.00380528 0.0090043 -0.000189518 -0.00377712 0.0090043 0.000499429 -0.00218795 0.0090043 -0.000229964 0.00311414 0.0090043 0.00111233 0.00327659 0.0090043 0.000743324 0.00358789 0.0090043 0.000320016 -0.00362525 0.0090043 0.00117202 0.00282406 0.0090043 -0.0025575 0.00129313 0.0090043 -0.00177984 -0.00335465 0.0090043 0.00180622 -0.00297417 0.0090043 0.00238127 -0.00370881 0.0090043 -0.000872256 -0.00349086 0.0090043 -0.00152643 -0.00272284 0.0090043 -0.002665 -0.00190526 0.0090043 -0.0011 -0.000457406 0.0090043 -0.00215192 -0.000271173 0.0090043 -0.00380034 0.000457406 0.0090043 -0.00215192 0.00231686 0.0090043 -0.00302461 0.00173378 0.0090043 -0.00339265 0.00354738 0.0090043 -0.00139002 0.00190526 0.0090043 -0.0011 0.00367332 0.0090043 0.000243286 0.00367663 0.0090043 0.000237575 0.00372567 0.0090043 0.000134764 -0.00163492 0.0090043 0.00147209 -0.00089482 0.0090043 0.0020098 0.00580333 0.00789442 -0.00227312 0.0046184 0.00789442 -0.00418135 0.00261298 0.00836298 -0.00511306 -0.000442448 0.00789442 -0.00620951 -0.00223469 0.00789442 -0.00583384 -0.00444724 0.00789442 -0.00435319 -0.00573493 0.00836298 -0.00028562 -0.00546361 0.00836298 0.00176635 -0.00294513 0.00893083 0.00339587 -0.00237183 0.0089366 0.00378643 -0.00223482 0.00900128 0.00325648 -0.00291733 0.00874333 0.00416136 -0.00269606 0.00882468 0.00405836 -0.00239046 0.00893023 0.00380656 -0.00367135 0.00841769 0.00431624 -0.00299572 0.00871224 0.00418585 -0.00400031 0.00824821 0.00431909 0.00601591 0.0080601 -0.000962848 0.00522315 0.00866351 -0.000571256 0.00441229 0.00893083 -0.000858782 0.00512034 0.00871008 -0.000521684 0.00430069 0.00896609 -0.000202404 0.00380729 0.0090043 -0.000143805 0.00373982 0.0090043 -0.000727897 -0.00337358 0.00871377 0.00388989 0.00382113 0.00893083 -0.00236744 0.00323876 0.0090043 -0.00200662 0.00418525 0.00893083 -0.00163996 0.0047941 0.00871377 -0.00187854 0.00505417 0.00871377 -0.000983713 0.00546015 0.00852464 -0.00069279 0.00563627 0.00836298 -0.00109701 -0.00448236 0.00836298 0.0035888 -0.0044563 0.00893083 0.000589235 -0.00448952 0.00893083 -0.000223594 -0.00501226 0.00871377 -0.00117881 -0.00526729 0.00789442 0.00335904 -0.00505578 0.00836298 0.00272215 -0.00453362 0.00871377 0.00244101 -0.00401943 0.00871377 0.00321815 -0.00249627 0.0090043 0.00287832 -0.00569249 0.00836298 0.000752689 -0.00489934 0.00871377 0.00158392 -0.00395785 0.00893083 0.002131 -0.00350896 0.00893083 0.00280945 -0.00510458 0.00871377 0.000674954 -0.00618487 0.00789442 -0.000880273 -0.00558953 0.00836298 -0.00131457 -0.00514263 0.00871377 -0.000256123 -0.00427712 0.00893083 0.00138276 -0.00515883 0.00789442 -0.00348013 -0.00476028 0.00836298 -0.00321103 -0.00526107 0.00836298 -0.00230048 -0.00471771 0.00871377 -0.00206289 -0.00570147 0.00789442 -0.00249318 -0.00411856 0.00893083 -0.0018009 -0.0043757 0.00893083 -0.0010291 -0.00358995 0.00789442 -0.0050838 -0.00367978 0.00871377 -0.0036016 -0.00410359 0.00836298 -0.00401641 -0.00372653 0.00893083 -0.00251371 -0.00426865 0.00871377 -0.0028794 -0.00322841 0.00789442 -0.00534835 -0.0024129 0.00836298 -0.00521046 -0.00331249 0.00836298 -0.00469025 -0.00321244 0.00893083 -0.0031442 -0.00143428 0.00836298 -0.00556002 -0.0021637 0.00871377 -0.00467233 -0.00259314 0.00893083 -0.0036717 -0.00297038 0.00871377 -0.00420584 -0.00315858 0.0090043 -0.00213061 -0.000408684 0.00836298 -0.00572748 -0.00128615 0.00871377 -0.00498579 -0.00188891 0.00893083 -0.00407895 0.000684112 0.00789442 -0.00618832 0.000630299 0.00836298 -0.00570734 -0.00112281 0.00893083 -0.00435259 -0.00160103 0.0090043 -0.00345728 -0.00219793 0.0090043 -0.00311211 0.000565202 0.00871377 -0.0051179 -0.000366476 0.00871377 -0.00513595 0.00283474 0.00789442 -0.00554528 0.00164864 0.00836298 -0.00550027 0.00147837 0.00871377 -0.00493221 -0.000319933 0.00893083 -0.00448368 -0.000951684 0.0090043 -0.00368923 0.00378843 0.00789442 -0.00494437 0.00310693 0.00789442 -0.00541982 0.00349174 0.00836298 -0.00455838 0.000493421 0.00893083 -0.00446792 0.00425613 0.00836298 -0.0038544 0.00313111 0.00871377 -0.00408759 0.00204554 0.00893083 -0.00400269 0.00234311 0.00871377 -0.00458499 0.00129061 0.00893083 -0.00430582 0.000418221 0.0090043 -0.00378698 0.00488113 0.00836298 -0.00302417 0.00109392 0.0090043 -0.00364958 0.00534625 0.00836298 -0.0020949 0.00381656 0.00871377 -0.00345632 0.00273346 0.00893083 -0.00356847 0.00437701 0.00871377 -0.00271184 0.00333186 0.00893083 -0.00301736 -1.44869e-10 -0.0062103 0.0072898 -0.00533138 -0.00649332 0.00725786 -0.00389932 -0.0074803 0.0060198 -0.00389991 -0.00747997 0.00604891 -0.00393582 -0.00745974 0.00624742 -0.00396202 -0.00744485 0.00631778 -0.00412433 -0.0073502 0.00657974 -1.44869e-10 -0.00729212 0.00664275 -0.00439029 -0.00718565 0.00683318 -1.44869e-10 -0.00683325 0.00710162 -1.44869e-10 -0.00669631 0.00719313 0.00112525 -0.00669631 0.00710457 0.00315871 -0.0062103 0.00655772 0.00422801 -0.00669631 0.00581936 0.00508631 -0.00669631 0.00508631 0.00515467 -0.0062103 0.00515467 0.00581936 -0.00669631 0.00422801 0.00589757 -0.0062103 0.00428484 0.00640912 -0.00669631 0.00326561 0.00655772 -0.0062103 0.00315871 0.00684107 -0.00669631 0.0022228 0.00719313 -0.00669631 -1.78098e-09 0.00710457 -0.00669631 0.00112525 0.00657924 -0.00710833 0.00213773 0.00616383 -0.00710833 0.00314063 0.00559664 -0.00710833 0.0040662 0.00489164 -0.00710833 0.00489164 0.0040662 -0.00710833 0.00559664 0.00326561 -0.00669631 0.00640912 0.0022228 -0.00669631 0.00684107 0.00213773 -0.00710833 0.00657924 0.00108219 -0.00710833 0.00683266 -1.44869e-10 -0.00710833 0.00691782 0.00683266 -0.00710833 0.00108219 0.00642571 -0.00738363 0.00101773 0.00579672 -0.00738363 0.00295358 0.0046003 -0.00738363 0.0046003 0.00382402 -0.00738363 0.00526331 0.00295357 -0.00738363 0.00579672 0.00314063 -0.00710833 0.00616383 -1.44869e-10 -0.00738363 0.00650581 0.00618739 -0.00738363 0.00201041 0.00594569 -0.0074803 0.000941703 0.00572517 -0.0074803 0.00186022 0.00526331 -0.00738363 0.00382402 0.00536368 -0.0074803 0.00273293 0.00425664 -0.0074803 0.00425664 0.00273293 -0.0074803 0.00536368 0.00201041 -0.00738363 0.00618739 0.00101773 -0.00738363 0.00642571 0.00186022 -0.0074803 0.00572517 0.000941704 -0.0074803 0.00594568 -0.00389932 0.0074803 0.0060198 -0.00394366 0.00745529 0.00627058 -0.00409837 0.00736563 0.00654716 -1.44869e-10 0.00738363 0.00650581 -1.44869e-10 0.0062103 0.0072898 -0.0050829 0.00669477 0.00719376 0.00161699 0.0062103 0.00708563 0.00526331 0.00738363 0.00382402 0.00572517 0.0074803 0.00186022 0.00186022 0.0074803 0.00572517 0.00273293 0.0074803 0.00536368 0.00201041 0.00738363 0.00618739 -1.44869e-10 0.0074803 0.0060198 0.00489164 0.00710833 0.00489164 0.00684107 0.00669631 0.0022228 0.00657924 0.00710833 0.00213773 0.00616383 0.00710833 0.00314063 0.00579672 0.00738363 0.00295358 0.0040662 0.00710833 0.00559664 0.00508631 0.00669631 0.00508631 0.00353835 0.0074803 0.00487012 0.00382402 0.00738363 0.00526331 0.0046003 0.00738363 0.0046003 0.00581936 0.00669631 0.00422801 0.00112525 0.00669631 0.00710457 -1.44869e-10 0.00710833 0.00691782 -1.44869e-10 0.00669631 0.00719313 0.000941704 0.0074803 0.00594568 0.00101773 0.00738363 0.00642571 0.00108219 0.00710833 0.00683266 0.00295357 0.00738363 0.00579672 0.00314063 0.00710833 0.00616383 0.00213773 0.00710833 0.00657924 0.0022228 0.00669631 0.00684107 0.00225267 0.0062103 0.00693301 0.00422801 0.00669631 0.00581936 0.00326561 0.00669631 0.00640912 0.00568545 0.0062103 0.0045332 0.00515467 0.0062103 0.00515467 0.00428484 0.0062103 0.00589757 0.00693301 0.0062103 0.00225267 0.00655772 0.0062103 0.00315871 0.00640912 0.00669631 0.00326561 0.00559664 0.00710833 0.0040662 0.00425664 0.0074803 0.00425664 0.00642571 0.00738363 0.00101773 0.00618739 0.00738363 0.00201041 0.00594569 0.0074803 0.000941703 0.00683266 0.00710833 0.00108219 0.00710457 0.00669631 0.00112525 0.0072898 0.0062103 -1.78098e-09 0.00720005 0.0062103 0.00114038 0.00709435 -0.00841437 5.47637e-05 0.00737391 -0.0082124 1.41394e-05 0.0101327 -0.00849156 7.76966e-05 0.00449378 -0.00932196 0.000707036 0.00449523 -0.00923437 0.00058802 0.00536144 -0.0091066 0.000448285 0.0101327 -0.00910971 0.000478787 0.00449544 -0.00946699 0.000980253 0.00492941 -0.0091839 0.000528777 0.00444445 -0.0095885 0.0015875 0.0101327 -0.0095885 0.0015875 0.0101327 -0.00860186 0.000133896 0.0101327 -0.0095108 0.00109694 0.0132265 -0.00690911 0.00122582 0.0123041 -0.00690911 0.000134626 0.0125901 -0.00697439 0.000303185 0.0129536 -0.00690911 0.00066028 0.0131154 -0.00690911 0.000910914 0.0131837 -0.00690911 0.00107808 0.01247 -0.00690911 0.000217365 0.0126034 -0.00690911 0.000304176 0.0121081 -0.00690911 6.48592e-05 0.012005 -0.00731514 7.76966e-05 0.0116804 -0.00676675 -1.78098e-09 0.0117387 -0.00666748 4.67606e-07 0.0132281 -0.00712 0.0015875 0.0131523 -0.00710271 0.00109694 0.0125543 -0.00834464 0.00109694 0.0108392 -0.0095089 0.0015875 0.0108219 -0.00943315 0.00109694 0.0112254 -0.00937375 0.0015875 0.0114766 -0.00920407 0.00109694 0.0129233 -0.00775737 0.00109694 0.012378 -0.00820405 0.00065439 0.0129325 -0.00705254 0.00065439 0.0127201 -0.00765953 0.00065439 0.0117043 -0.00838419 0.000303185 0.0112263 -0.00868449 0.000303185 0.0101327 -0.0094546 0.000986641 0.0101327 -0.00928531 0.00065439 0.0121123 -0.00889582 0.0015875 0.0113787 -0.00900092 0.00065439 0.0107717 -0.00921331 0.00065439 0.0106936 -0.00887091 0.000303185 0.0121499 -0.00690911 7.97194e-05 0.0124037 -0.00750715 0.000303185 0.0117574 -0.00770915 7.76966e-05 0.0121034 -0.00798507 0.000303185 0.0114283 -0.0080382 7.76966e-05 0.0110343 -0.00828577 7.76966e-05 0.012615 -0.00839308 0.0015875 0.0121879 -0.00882021 0.0015875 0.0120638 -0.00883507 0.00109694 0.0119232 -0.00865878 0.00065439 0.0101327 -0.00893411 0.000303185 0.0101327 -0.008001 -1.78098e-09 0.0105951 -0.00843946 7.76966e-05 0.0104859 -0.0079612 -1.78098e-09 0.0117387 -0.00690911 2.74376e-06 0.011563 -0.00710229 -1.78098e-09 0.00675903 0.00860723 0.000123834 0.00449651 0.00936904 0.000782138 0.00449523 0.00923437 0.00058802 0.00578751 0.00900019 0.000353901 0.0101327 0.00928531 0.00065439 0.00492941 0.0091839 0.000528777 0.00449433 0.00946396 0.000981746 0.00449375 0.00948914 0.0010347 0.00448953 0.00951813 0.00112007 0.0101327 0.0095885 0.0015875 0.0061207 0.00889272 0.000274109 0.00761582 0.008001 -1.78098e-09 0.00737391 0.0082124 1.41394e-05 0.0101327 0.00860186 0.000133896 0.00690183 0.0085332 9.18639e-05 0.00638754 0.00788357 -0.000555718 0.00635491 0.0079436 -0.000520443 0.00668844 0.00812357 -0.000140956 0.0068866 0.00782352 -0.000209836 0.0043518 0.00908095 0.00033124 0.00437097 0.0090907 0.000355886 0.00445598 0.00917202 0.000503304 0.00395673 0.00900084 -0.000147922 0.00396797 0.00900905 -2.64104e-05 0.0041271 0.00901627 9.46318e-05 0.00429885 0.00900145 9.13088e-05 0.00430248 0.00905588 0.000267865 0.00424635 0.00897412 -0.000189928 0.00519788 0.00892046 0.000200188 0.0044865 0.00892708 -0.00025939 0.00461131 0.00890088 -0.000297667 0.00491968 0.00880099 -0.000424931 0.00537873 0.00867282 -0.000213118 0.0056344 0.00853176 -0.000305192 0.00526944 0.00912306 0.000465425 0.00536144 0.0091066 0.000448285 0.00557297 0.0087887 0.000105305 0.00586313 0.00865921 2.96068e-05 0.00653236 0.00872474 0.000174577 0.00442558 0.00908373 0.000349259 0.00435958 0.00899271 8.10978e-05 0.00481397 0.00901855 0.00028492 0.0047057 0.00892222 3.61548e-06 0.00504679 0.00881594 -9.84761e-05 0.00621675 0.00846372 -5.70658e-05 0.00594446 0.008318 -0.000412075 0.00652848 0.00825064 -0.000118839 0.00659693 0.00786106 -0.000373511 0.00568255 0.00835974 -0.000805935 0.00575288 0.0083076 -0.000841713 0.00621616 0.00808386 -0.000490671 0.00620723 0.00789572 -0.000847986 0.00615325 0.00790657 -0.00101603 0.00709435 0.00841437 5.47637e-05 0.00691732 0.0079162 -0.000154642 0.00722413 0.00777482 -8.32732e-05 0.00703269 0.00780244 -0.00015506 0.00775998 0.0077303 -1.78098e-09 0.00743441 0.00775626 -3.07392e-05 0.00728192 0.00776957 -6.62225e-05 0.00429885 -0.00900145 9.13088e-05 0.00703269 -0.00780244 -0.00015506 0.0067799 -0.00783735 -0.00027013 0.00620723 -0.00789572 -0.000847986 0.00638754 -0.00788357 -0.000555718 0.00395673 -0.00900084 -0.000147922 0.00386577 -0.00900442 -0.000104153 0.00380729 -0.0090043 -0.000143805 0.00445598 -0.00917202 0.000503304 0.00437846 -0.00909451 0.000365505 0.00430069 -0.00896609 -0.000202404 0.0044865 -0.00892708 -0.00025939 0.0047057 -0.00892222 3.61548e-06 0.00442558 -0.00908373 0.000349259 0.00491968 -0.00880099 -0.000424931 0.00522315 -0.00866351 -0.000571256 0.00546015 -0.00852464 -0.00069279 0.00568255 -0.00835974 -0.000805935 0.00519788 -0.00892046 0.000200188 0.00526944 -0.00912306 0.000465425 0.00586313 -0.00865921 2.96068e-05 0.00578751 -0.00900019 0.000353901 0.0061207 -0.00889272 0.000274109 0.00601591 -0.0080601 -0.000962848 0.00621616 -0.00808386 -0.000490671 0.00615325 -0.00790657 -0.00101603 0.00635491 -0.0079436 -0.000520443 0.00435958 -0.00899271 8.10978e-05 0.00504679 -0.00881594 -9.84761e-05 0.00481397 -0.00901855 0.00028492 0.00537873 -0.00867282 -0.000213118 0.0056344 -0.00853176 -0.000305192 0.00557297 -0.0087887 0.000105305 0.00594446 -0.008318 -0.000412075 0.00621675 -0.00846372 -5.70658e-05 0.00668844 -0.00812357 -0.000140956 0.00653236 -0.00872474 0.000174577 0.00675903 -0.00860723 0.000123834 0.00652848 -0.00825064 -0.000118839 0.00690183 -0.0085332 9.18639e-05 0.00691732 -0.0079162 -0.000154642 0.00722413 -0.00777482 -8.32732e-05 0.00761582 -0.008001 -1.78098e-09 0.00743544 -0.00775617 -3.05454e-05 0.00775998 -0.0077303 -1.78098e-09 -0.00218581 -0.0035941 0.00808355 -0.00206496 -0.00298659 0.0072898 -0.00172084 -0.00247157 0.00808355 -0.000598306 -0.0020066 0.0072898 0.00199805 -0.00484091 0.00701063 0.00211201 -0.00472231 0.00697715 0.00253466 -0.0044379 0.00683496 0.00316274 -0.00429459 0.0065675 0.00301998 -0.00430263 0.00663483 0.00319815 -0.0042926 0.00808355 0.00527301 -0.0037926 0.00551001 0.00527301 -0.0025066 0.00551001 0.00523293 -0.0039833 0.00507516 0.00526503 -0.00388161 0.0050419 0.00527301 -0.0037926 0.00503354 0.00514944 -0.00412169 0.00515989 0.00523135 -0.00398245 0.00555427 0.00522697 -0.00400219 0.00508134 0.00512634 -0.00414594 0.00518281 0.00512586 -0.00414129 0.00566176 0.00477301 -0.0042926 0.00601795 0.00477619 -0.00429259 0.00601475 0.00496381 -0.00425365 0.00533858 0.0049618 -0.00424999 0.00582757 0.00510705 -0.00416465 0.00568086 0.00520766 -0.00225945 0.00557867 0.00510834 -0.00213572 0.00520058 0.00493544 -0.00203372 0.00585419 0.0052558 -0.00237655 0.00505151 0.00525528 -0.00237463 0.00552961 0.00981849 -2.10179e-18 0.0072898 0.00981849 0.000472936 0.00329565 0.00981849 0.00141655 0.003042 0.00981849 0.0005461 0.0035687 0.00981849 -0.00027305 0.00404164 0.00981849 0.000683101 0.00491681 0.00981849 -0.000610564 0.00497225 0.00981849 -0.0005461 0.0035687 0.00981849 -0.00149856 0.00376453 0.00981849 -0.00141655 0.003042 0.00981849 -0.000472936 0.00329565 0.00981849 -0.00027305 0.00309576 0.00981849 -0.00100659 0.0024414 0.00981849 -0.000363588 0.00821061 0.00981849 -0.00027305 0.00721664 0.00981849 -0.0005461 0.0067437 0.00981849 -0.00149856 0.00654787 0.00981849 -0.00027305 0.00627076 0.00981849 -0.00123363 0.00587067 0.00981849 -0.0005461 0.00517259 0.00981849 -0.0005461 0.00513981 0.00981849 -2.54494e-18 0.0061976 0.00981849 -2.10179e-18 0.0041148 0.00981849 0.00027305 0.00627076 0.00981849 0.000472936 0.00647065 0.00981849 0.000610564 0.00497225 0.00981849 0.000562772 0.00505005 0.00981849 0.000610564 0.00534015 1.57122e-05 5.50707e-06 0.00728978 0.000672296 0.000262594 0.00725873 0.000681503 0.000236991 0.00725861 0.00138593 0.000528782 0.00715684 0.00221865 0.000393045 0.00712283 0.00218617 0.000452907 0.00707114 0.00146221 0.000321028 0.00719244 0.000709667 0.000160914 0.00726694 0.000719145 0.000136043 0.00727258 1.6576e-05 3.15739e-06 0.00728979 0.00319286 0.000511262 0.00693563 0.00258713 0.000444479 0.00706097 0.00207411 0.000758668 0.00698851 0.00209778 0.000676507 0.00698899 0.00241859 0.000857948 0.00687689 0.00298485 0.000986855 0.0066507 0.00351196 0.000900603 0.00641354 0.00366723 0.000578204 0.00666722 0.00390701 0.000542188 0.00674378 0.00417817 0.000539794 0.00666095 0.00408669 0.000546916 0.0065157 0.00390597 0.00104193 0.00615504 0.00442616 0.000900582 0.00579226 0.0047346 0.000466566 0.0064599 0.00442438 0.000481025 0.00638445 0.00453903 0.000504586 0.00653485 0.00509187 4.74354e-05 0.00614206 0.005277 0.000168436 0.00622422 0.00505917 0.000115849 0.00614943 0.00526067 0.000190693 0.00623198 0.00519964 0.000254577 0.00626057 0.00517407 0.000272153 0.00627216 0.00496166 0.000394897 0.0063665 0.00504853 -0.000131205 0.00615214 0.00508781 -5.99214e-05 0.00614289 0.00531666 -9.08233e-05 0.00620521 0.00532805 4.7928e-08 0.00619969 0.00509702 2.39916e-05 0.00614106 0.00511592 -0.000316716 0.00629882 0.00517219 -0.000271778 0.00627297 0.00463843 0.000762244 0.00562371 0.00466806 0.000494745 0.00566374 0.00480689 0.000257517 0.00555615 0.00493322 0.000325121 0.00536699 0.00481784 0.000225841 0.00554765 0.00498257 7.12665e-05 0.0053212 0.00485186 4.82419e-05 0.00552138 0.00497821 -0.000119343 0.00532528 0.0049703 -0.00017531 0.00533267 0.0049198 -0.000363218 0.00537929 0.00478609 -0.000308086 0.00557232 0.00478264 -0.000611336 0.0055016 0.00473752 -0.000665934 0.0055405 0.00466642 -0.0004967 0.005665 0.00456142 -0.000821034 0.00568636 0.00451647 -0.000637538 0.00577806 0.00428234 -0.000770574 0.00594531 0.00473188 -0.000369397 0.0062625 0.00460131 -0.000494282 0.00651152 0.00430155 -0.000954079 0.00588539 0.00299112 -0.000860822 0.00666485 0.00341982 -0.00104438 0.00643786 0.00358945 -0.000579461 0.00669363 0.00246301 -0.00076494 0.00687188 0.00189981 -0.000622898 0.00704398 0.00162127 -0.000609398 0.00710329 0.00200829 -0.000360932 0.00715352 0.00312044 -0.000564346 0.00684085 0.00365813 -0.000541066 0.00681768 0.00143193 -0.000484011 0.00715114 0.00072262 -0.000281945 0.0072539 1.54961e-05 -6.09449e-06 0.00728978 1.61443e-05 4.33222e-06 0.00728979 0.000690819 0.000211461 0.00725994 0.00142259 0.000422281 0.00716249 0.000700216 0.000186078 0.00726272 0.00144215 0.000370678 0.0071745 0.00212486 0.000596674 0.00700326 0.00247428 0.000667137 0.00689904 0.00215461 0.00052143 0.0070309 0.00250935 0.000581103 0.00693734 0.00304371 0.000747123 0.00669185 0.00354854 0.000764875 0.00646765 0.00394438 0.000723715 0.00626436 0.00400567 0.000610653 0.00637827 0.00425735 0.000635598 0.00608715 0.00432586 0.000526845 0.00622786 0.00441922 0.000559205 0.00599083 0.00449199 0.000456797 0.00614836 0.00459575 0.000435217 0.00588435 0.0046739 0.000346402 0.00606394 0.00467329 0.000358055 0.00583851 0.00475778 0.000241519 0.00579152 0.00479297 0.000170622 0.0057741 0.00484223 0.000182482 0.00599794 0.00482455 6.01265e-05 0.00576091 0.00482799 3.03643e-05 0.0057597 0.00491397 -3.65624e-05 0.00598302 0.0048218 -7.60402e-05 0.00576192 0.00479405 -0.000168013 0.00577361 0.00477593 -0.000207884 0.00578229 0.00488031 -0.000123968 0.00598793 0.00486125 -0.000155396 0.00599251 0.00470456 -0.000320305 0.00582058 0.00460966 -0.000390622 0.00609305 0.00430965 -0.000613829 0.0060563 0.00411276 -0.000588622 0.00632876 0.00392749 -0.000623595 0.00641376 0.00386783 -0.000736715 0.00630555 0.00352651 -0.000656729 0.00658572 0.00307012 -0.000644594 0.00675885 0.00249385 -0.000670668 0.0068927 0.00252922 -0.000584056 0.00693166 0.00147107 -0.000377413 0.0071698 0.000742493 -0.000226957 0.0072553 1.59283e-05 -4.91964e-06 0.00728978 1.61443e-05 -4.33222e-06 0.00728979 0.000752597 -0.000199691 0.00725851 0.00149156 -0.000326889 0.00718848 0.00195145 -0.000482086 0.00707782 0.00197954 -0.000418303 0.00711079 0.00256772 -0.000508551 0.00698723 0.00400505 -0.000556711 0.00654632 0.00419895 -0.000529917 0.00647281 0.00448167 -0.000464818 0.00636167 0.00437949 -0.000506703 0.00620218 0.00475266 -0.000281129 0.00603037 0.00489357 -0.000275887 0.00620159 0.00493341 -0.000246418 0.00618762 0.00502413 -0.00016165 0.00615882 0.0047867 -0.000247698 0.00601705 0.00490969 -5.46005e-05 0.00598333 0.00509376 -4.03976e-05 0.00614169 0.00491629 2.163e-05 0.0059829 0.00491262 4.30262e-05 0.0059831 0.00488845 0.000108519 0.0059863 0.00504706 0.000133205 0.00615252 0.00487918 0.000126 0.00598817 0.00500039 0.000187156 0.00616583 0.00489535 0.000274639 0.00620095 0.0047542 0.000279701 0.00602975 0.00480362 0.000332108 0.00623486 0.00460294 0.000424209 0.00631337 0.00313877 0.000565571 0.00683549 0.00360186 0.000654164 0.00655477 0.00254747 0.000505902 0.00699203 0.00308801 0.00064584 0.00675253 1.63604e-05 3.7448e-06 0.00728979 -1.44869e-10 2.60209e-18 0.0072898 1.63604e-05 -3.7448e-06 0.00728979 1.6576e-05 -3.15739e-06 0.00728979 0.00147663 -0.000272672 0.00721584 0.00076277 -0.000172698 0.00726338 1.59283e-05 4.91964e-06 0.00728978 0.00140378 0.0004752 0.00715658 0.00244363 0.000760639 0.00687862 0.00300861 0.000863178 0.0066572 0.00390983 0.000873171 0.006187 0.00422849 0.000791976 0.0059821 0.00439606 0.00071532 0.00586556 0.00458318 0.000582637 0.00572829 0.00476447 0.000352091 0.00558915 0.00480176 0.000148031 0.00577013 0.00484725 9.49313e-05 0.00552492 0.00484895 -8.09857e-05 0.00552362 0.00482582 -5.11776e-05 0.00576046 0.00484361 -0.000119487 0.00552772 0.00480822 -0.0002539 0.00555512 0.00470311 -0.000449997 0.00563674 0.00467181 -0.000359728 0.00583937 0.00453352 -0.000485401 0.00592182 0.00401597 -0.000853472 0.00612115 0.00404917 -0.000701067 0.00620655 0.00383255 -0.00088377 0.00623348 0.00347458 -0.00076641 0.00650295 0.003438 -0.000899333 0.00645225 0.00302612 -0.000745464 0.00669896 0.00192467 -0.000550812 0.00705538 0.00145111 -0.000430012 0.0071573 0.000732489 -0.000254405 0.00725376 1.57122e-05 -5.50706e-06 0.00728978 0.00648214 0.000529409 0.0037994 0.00636839 0.000449952 0.00392075 0.00629805 0.000376432 0.00399332 0.00683605 0.000537821 0.00366343 0.00587622 0.000130395 0.00431407 0.00598838 0.000292878 0.00418526 0.00590928 0.000340919 0.00426868 0.00600967 0.000365717 0.00415605 0.00600684 0.000624236 0.00413026 0.00608063 0.000532687 0.00405643 0.00631677 0.000805718 0.00369725 0.0062609 0.000964426 0.00373395 0.00683752 0.000565682 0.00338487 0.00727487 0.000377763 0.00317434 0.00699452 0.000458901 0.00318211 0.00720136 0.000456783 0.00326941 0.00717978 0.000472502 0.00329591 0.00706616 0.00052775 0.00342833 0.00735947 0.000185935 0.00305523 0.00713025 0.000179123 0.00299376 0.00734527 0.000235635 0.00307605 0.00711804 0.000227843 0.00301136 0.00707862 0.000332453 0.00306721 0.00729932 0.000339659 0.00314108 0.0073793 1.27706e-07 0.00302552 0.00738038 3.75085e-05 0.00302389 0.0070366 -0.000405623 0.00312526 0.00708899 -0.000309647 0.00305266 0.00731141 -0.000317382 0.0031243 0.00733101 -0.000272596 0.0030965 0.00733764 -0.000257427 0.00308708 0.00699184 -0.000461805 0.00318569 0.0071786 -0.000470814 0.00329672 0.00719825 -0.000459298 0.00327328 0.00725033 -0.000409021 0.00320686 0.00660582 0.00101868 0.00308291 0.00662529 0.000817337 0.00314555 0.00670032 0.000929665 0.00287174 0.00673222 0.000881697 0.00279615 0.00680093 0.000729171 0.0026246 0.0067934 0.000568112 0.00278982 0.00682379 0.000655621 0.00256458 0.00686675 0.00045483 0.00244724 0.00684974 0.000350746 0.00265879 0.00686114 0.000276206 0.0026314 0.00689784 0.000128908 0.00235818 0.00687648 9.89423e-05 0.00259407 0.00687798 5.55558e-05 0.00259041 0.00689627 -0.000163859 0.00236276 0.00687513 -0.000125798 0.00259739 0.00688849 -0.000276763 0.00238535 0.00682262 -0.000474753 0.00272271 0.00677799 -0.000789505 0.00268328 0.00672931 -0.000886553 0.00280314 0.00664133 -0.000993019 0.00300564 0.00665617 -0.000792732 0.00308367 0.00656776 -0.0010368 0.00316287 0.00654509 -0.000557992 0.00373 0.00683244 -0.000537211 0.00366683 0.00667045 -0.000586964 0.00358682 0.00693218 -0.000543539 0.00356884 0.00635117 -0.000434089 0.00393868 0.00648266 -0.000375714 0.00396501 0.00638075 -0.000460627 0.00390781 0.00651463 -0.000400414 0.00394004 0.00664204 -0.000476045 0.00383629 0.00618821 -0.000172199 0.00410304 0.00636528 -0.000251538 0.00405342 0.00624199 -0.000294958 0.00404985 0.00638148 -0.000272972 0.00404149 0.00626153 -0.000326599 0.00403028 0.00638621 -0.000279225 0.00403802 0.00645542 -0.00105272 0.00338656 0.00649267 -0.000861305 0.00339631 0.00643165 -0.000855073 0.00350444 0.00631383 -0.000803828 0.00370202 0.00620933 -0.000918877 0.00381908 0.00609022 -0.000772892 0.00400629 0.00615883 -0.00065539 0.00394245 0.00613088 -0.000616395 0.00398372 0.00602755 -0.000415961 0.00413127 0.00589685 -0.000281567 0.00428583 0.005884 -0.000201576 0.00430345 0.00587066 7.35256e-18 0.00432164 0.00587069 1.01496e-05 0.0043216 0.00606333 -0.000146918 0.00415407 0.00595169 8.74091e-06 0.00423493 0.00595696 0.000112258 0.00422785 0.00605588 9.51247e-05 0.00416304 0.0060875 0.000247727 0.00412476 0.00614715 0.000639661 0.00395977 0.00625452 0.000758832 0.00379645 0.00641635 0.000665248 0.00369468 0.00643468 0.000855723 0.00349916 0.00658234 0.000698896 0.00345247 0.00648403 0.000861322 0.00341189 0.00658808 0.000838881 0.00321827 0.00668487 0.000671686 0.00329322 0.00670714 0.000735705 0.00297832 0.00680137 0.000578593 0.00310267 0.00673456 0.000694355 0.00291987 0.00682808 0.000543607 0.00305748 0.00681294 0.000508977 0.00274512 0.00696602 7.55952e-05 0.00281416 0.00696747 4.24359e-05 0.0028115 0.00686842 -0.000212724 0.00261375 0.0069647 -9.61354e-05 0.00281657 0.00684363 -0.000383605 0.00267334 0.00677378 -0.00061734 0.00283392 0.00673206 -0.000698492 0.00292525 0.00682565 -0.000547074 0.00306162 0.0067516 -0.000628476 0.00318535 0.0065951 -0.000835435 0.0032047 0.00669176 -0.000668274 0.00328224 0.00659089 -0.000698165 0.00343949 0.00653051 -0.000697953 0.00353011 0.0063691 -0.000639555 0.00376034 0.00626938 -0.000771361 0.00377309 0.00625858 -0.000548173 0.00390864 0.00614546 -0.000388663 0.00405327 0.00604605 -0.000461124 0.00410541 0.00597657 -0.000242085 0.00420134 0.00596436 -0.000173453 0.00421788 0.00605058 7.40906e-06 0.00416941 0.00616753 7.99433e-05 0.00412322 0.00620067 0.000208182 0.00409081 0.0061089 0.000308943 0.00409857 0.00618018 0.000447976 0.00400962 0.00624688 0.000535472 0.00392392 0.00635428 0.000629956 0.00378065 0.00654821 0.000559159 0.00372652 0.00653351 0.000698253 0.00352566 0.00667369 0.000587228 0.00358303 0.00672631 0.000587978 0.00352076 0.00672137 0.00065098 0.00323464 0.00687736 0.000548516 0.00333469 0.0069651 0.000488177 0.00322117 0.0068853 0.000440316 0.0029587 0.00705765 0.000372175 0.00309634 0.00690428 0.000393142 0.00292528 0.00694002 0.000269198 0.00286145 0.0069511 0.000211576 0.00284139 0.00714666 6.40238e-05 0.00296983 0.00714826 3.59415e-05 0.00296749 0.00714522 -8.14172e-05 0.00297195 0.00713805 -0.000137808 0.00298244 0.00695818 -0.000162748 0.0028285 0.00693408 -0.000294727 0.00287215 0.0071115 -0.000249413 0.00302074 0.00691368 -0.00036609 0.00290863 0.00686623 -0.000480099 0.00299192 0.00691045 -0.0005298 0.00329238 0.00684503 -0.000562859 0.00337547 0.00673554 -0.000587405 0.00350971 0.00641342 -0.000663866 0.00369879 0.0064979 -0.000537493 0.00378218 0.00623058 -0.000516596 0.0039451 0.00612687 -0.000351003 0.00407639 0.00607562 -0.000204906 0.0041392 0.00622312 0.000259619 0.00406863 0.00632107 0.000176621 0.00408545 0.00628571 6.75538e-05 0.00411061 0.00616198 6.22667e-06 0.00412862 0.00627976 -2.57429e-18 0.0041148 0.00617533 -0.000123469 0.00411562 -0.00441963 0.0080046 0.00427194 -0.00459241 0.00789442 0.00423524 -0.00416801 0.00792959 0.0047729 -0.00416924 0.00792949 0.00477101 -0.00387357 0.00811805 0.00477604 -0.00424155 0.00792391 0.00466009 -0.00433162 0.00805844 0.00428666 -0.0043634 0.00791422 0.0044862 -0.00433362 0.00791679 0.00451883 -0.00223411 0.00899184 0.00343012 -0.00200536 0.00900574 0.00362835 -0.00216433 0.00900485 0.00328531 -0.00195396 0.00901258 0.00373069 -0.00196545 0.00900984 0.00371016 -0.00199562 0.00900674 0.00364831 -0.00374555 0.00837946 0.00431689 -0.00378103 0.00836118 0.00431719 -0.00318659 0.00850028 0.0046652 -0.00305832 0.00851524 0.00507014 -0.00352592 0.00832084 0.00474202 -0.00406712 0.00793645 0.00503857 -0.00258001 0.00874361 0.00481791 -0.00272761 0.00871616 0.00447814 -0.00335025 0.00856639 0.00427855 -0.00317156 0.0086425 0.00424081 -0.0029975 0.00859279 0.00460138 -0.00249145 0.00881621 0.00432824 -0.00263805 0.00884515 0.00402387 -0.00242908 0.00884147 0.00427953 -0.00226634 0.00890524 0.00412531 -0.00248816 0.00889685 0.00391209 -0.00205628 0.00895923 0.0043437 -0.00213681 0.00895407 0.00395717 -0.00209042 0.00897126 0.00387903 -0.00233153 0.0089507 0.00372684 -0.0022676 0.00897479 0.00358936 -0.00201238 0.00900017 0.00370223 -0.00459239 -0.00789442 0.00423527 -0.00416925 -0.00792949 0.00477101 -0.00417418 -0.00792911 0.00476345 -0.00391835 -0.00829213 0.00432164 -0.00378693 -0.00817046 0.00477161 -0.00406712 -0.00793645 0.00503858 -0.00416801 -0.00792958 0.00477291 -0.00182375 -0.00904361 0.00396326 -0.00194043 -0.00901577 0.00375472 -0.00196525 -0.00900984 0.00371035 -0.00223581 -0.00899046 0.00344711 -0.00226241 -0.0090043 0.00307352 -0.00207772 -0.00900533 0.003472 -0.00201676 -0.00899847 0.00371523 -0.00227096 -0.00897335 0.00359961 -0.00263492 -0.0087563 0.00442483 -0.0024761 -0.00890093 0.00390128 -0.00225323 -0.00891024 0.00411063 -0.00212569 -0.00895816 0.00393982 -0.00236201 -0.00893995 0.00377329 -0.00233867 -0.00894812 0.00373867 -0.00306436 -0.00868608 0.00421131 -0.00314126 -0.00852295 0.00465135 -0.00299585 -0.0087124 0.00418616 -0.00371254 -0.00814734 0.00524961 -0.003009 -0.00854035 0.00504961 -0.00288384 -0.008646 0.00455447 -0.00241459 -0.00884727 0.00426747 -0.00221929 -0.00889602 0.00452665 -0.00204186 -0.00896463 0.004325 -0.00189876 -0.00901711 0.00410994 -0.0020988 -0.00896812 0.00389444 -0.0018679 -0.0090281 0.00405349 -0.00345922 -0.00835753 0.00473044 -0.00330746 -0.00858505 0.00427064 0.0112442 -0.00628766 0.0203813 0.0106997 -0.00590148 0.0210192 0.0107139 -0.0059323 0.0209995 0.0108712 -0.00611239 0.0208079 0.0109139 -0.00614605 0.0207579 0.00958989 -0.0058 0.0210908 0.0105899 -0.0053 0.0212248 0.0105899 -0.0048 0.0210908 0.00958989 -0.0048 0.0210908 0.0105899 -0.00443397 0.0207247 0.0105899 -0.0043 0.0202248 0.00958989 0.00443397 0.0207247 0.0105899 0.00443397 0.0207247 0.00958989 0.0048 0.0210908 0.0105899 0.0053 0.0212248 0.0106425 0.00579045 0.0210962 0.00958989 0.0053 0.0212248 0.00958989 0.0058 0.0210908 0.0113794 0.00629999 0.0202295 0.0109965 0.00619922 0.0206623 0.00958989 0.0063 0.0202248 0.00958989 0.00616603 0.0207247 0.0109877 0.00619237 0.0206726 0.0109464 0.0061603 0.020721 0.0108089 0.0060537 0.020882 0.00739028 -0.00759877 -1.78098e-09 0.00743434 -0.00767141 -2.49612e-05 0.00742802 -0.00761216 -1.78098e-09 0.00747987 -0.00775263 -2.63657e-05 0.00775245 -0.00772736 -1.78098e-09 0.00728103 -0.00755998 -1.78098e-09 0.00721445 -0.00760292 -5.3944e-05 0.0073742 -0.00767545 -3.8864e-05 0.00737515 -0.00776134 -4.29134e-05 0.00736404 -0.00758945 -1.78098e-09 0.00736668 -0.00759604 -6.71103e-06 0.00659693 -0.00786106 -0.000373511 0.00700022 -0.00750135 -1.78098e-09 0.00617283 -0.00757781 -0.00102113 0.00623666 -0.00768194 -0.000947593 0.00619141 -0.00757833 -0.000935761 0.00621764 -0.00757836 -0.000851778 0.00626158 -0.00768198 -0.000867778 0.00625785 -0.0077956 -0.000866422 0.00636379 -0.00767704 -0.000665752 0.00636274 -0.00778908 -0.000665044 0.00632118 -0.00788931 -0.000637101 0.00642371 -0.00778335 -0.000585424 0.00618075 -0.00789567 -0.000932975 0.00623284 -0.00779555 -0.000946594 0.00616344 -0.00789442 -0.00101958 0.00641562 -0.00788056 -0.000531292 0.00642292 -0.00767274 -0.000584772 0.00658108 -0.00756502 -0.000353532 0.00599936 -0.0074803 -0.000885544 0.0060311 -0.0074803 -0.00078384 0.00613513 -0.00750615 -0.000821726 0.00625171 -0.00750541 -0.00059039 0.00616109 -0.0074803 -0.000529462 0.0064645 -0.0074803 -0.000206588 0.00682333 -0.00749913 -8.85594e-05 0.00677931 -0.0074803 -4.17038e-06 0.00692251 -0.00748732 -1.78098e-09 0.00689494 -0.00772818 -0.000225814 0.00661865 -0.00776176 -0.00040088 0.00661303 -0.00765688 -0.000393802 0.00686073 -0.00755278 -0.000160238 0.00610646 -0.00750614 -0.000913547 0.00632412 -0.00757569 -0.000639083 0.00631828 -0.00750477 -0.000498841 0.00638532 -0.0075734 -0.000553897 0.00652846 -0.00750246 -0.000287207 0.00719664 -0.00753681 -1.78098e-09 0.00688586 -0.00763316 -0.000208409 0.00722415 -0.00768609 -8.33254e-05 0.00722414 -0.00768778 -8.33254e-05 0.0068866 -0.00782352 -0.000209836 0.00621582 -0.00779427 -0.00102825 0.00593709 -0.00779427 -0.00210823 0.00611945 -0.00789442 -0.00119 0.00547228 -0.00779427 -0.00312215 0.00542617 -0.00789442 -0.00309583 0.00529791 -0.00789442 -0.00328048 0.00483597 -0.00779427 -0.00403821 0.00461917 -0.00789442 -0.00418059 0.00310692 -0.00789442 -0.00541983 0.0021025 -0.00789442 -0.00588277 0.00179041 -0.00789442 -0.005964 0.00103218 -0.00789442 -0.00616134 0.00104095 -0.00779427 -0.0062137 -7.10875e-05 -0.00779427 -0.00629989 -0.0011809 -0.00779427 -0.00618863 -0.000439987 -0.00789442 -0.00620976 -0.00155163 -0.00789442 -0.00602817 -0.00223471 -0.00789442 -0.00583383 -0.00444476 -0.00789442 -0.00435579 -0.00488435 -0.00789442 -0.00389495 -0.00515669 -0.00789442 -0.00348335 -0.00554134 -0.00779427 -0.00299787 -0.00549465 -0.00789442 -0.0029726 -0.00569982 -0.00789442 -0.00249699 -0.00623744 -0.00779427 -0.000887724 -0.00618488 -0.00789442 -0.000880243 -0.00582616 -0.00779427 0.00239781 -0.00621476 -0.00789442 -0.000314159 -0.00624318 -0.00789442 0.000224197 -0.00629623 -0.00779427 0.000226105 -0.0061577 -0.00779427 0.00133284 -0.00616973 -0.00789442 0.000810934 -0.00610581 -0.00789442 0.00132161 -0.00463141 -0.00779427 0.00427126 -0.00592278 -0.00789442 0.00190954 -0.00548197 -0.00789442 0.00294573 -0.00531203 -0.00779427 0.00338762 -0.00526727 -0.00789442 0.00335907 -0.00531491 -0.00768097 0.00338945 -0.00616102 -0.00768097 0.00133356 -0.00624081 -0.00768097 -0.0008882 -0.00598315 -0.00779427 -0.00197372 -0.00598639 -0.00768097 -0.00197479 -0.00492586 -0.00779427 -0.00392805 -0.00415599 -0.00779427 -0.00473513 -0.00492852 -0.00768097 -0.00393018 -0.00415824 -0.00768097 -0.00473768 -0.00325587 -0.00779427 -0.00539379 -0.00325763 -0.00768097 -0.00539671 -0.0022537 -0.00779427 -0.00588341 -0.00225492 -0.00768097 -0.00588659 -0.00118154 -0.00768097 -0.00619198 -7.11262e-05 -0.00768097 -0.0063033 0.00212037 -0.00779427 -0.00593277 0.00313333 -0.00779427 -0.00546589 0.00212152 -0.00768097 -0.00593597 0.00313502 -0.00768097 -0.00546884 0.00404808 -0.00779427 -0.0048277 0.00405027 -0.00768097 -0.00483031 0.00547524 -0.00768097 -0.00312383 -0.0052753 -0.00757781 0.00336419 -0.00578587 -0.00757781 0.00238122 -0.00582932 -0.00768097 0.0023991 -0.00629964 -0.00768097 0.000226224 -0.00611511 -0.00757781 0.00132362 -0.00554434 -0.00768097 -0.00299949 -0.00594177 -0.00757781 -0.00196007 -0.00550302 -0.00757781 -0.00297713 -0.00489179 -0.00757781 -0.00390089 -0.00412725 -0.00757781 -0.00470238 -0.00223812 -0.00757781 -0.00584272 0.00104152 -0.00768097 -0.00621706 0.00311166 -0.00757781 -0.00542809 0.00483858 -0.00768097 -0.00404039 0.00480252 -0.00757781 -0.00401028 0.0059403 -0.00768097 -0.00210937 0.00621918 -0.00768097 -0.0010288 -0.00453491 -0.007506 0.00418226 -0.00520135 -0.007506 0.00331703 -0.00570477 -0.007506 0.00234784 -0.00625269 -0.00757781 0.00022454 -0.00616504 -0.007506 0.000221392 -0.0061943 -0.00757781 -0.000881584 -0.00585848 -0.007506 -0.0019326 -0.00406939 -0.007506 -0.00463646 -0.00323335 -0.00757781 -0.00535649 -0.00318803 -0.007506 -0.00528141 -0.00117273 -0.00757781 -0.00614583 -6.96067e-05 -0.007506 -0.00616862 -7.05963e-05 -0.00757781 -0.00625632 0.00103375 -0.00757781 -0.00617073 0.0021057 -0.00757781 -0.00589174 0.00207619 -0.007506 -0.00580915 0.00402009 -0.00757781 -0.00479431 0.00543444 -0.00757781 -0.00310055 0.00589603 -0.00757781 -0.00209365 -0.00560267 -0.0074803 0.00230583 -0.00602939 -0.007506 0.00130507 -0.00592149 -0.0074803 0.00128171 -0.00605471 -0.0074803 0.000217429 -0.00610747 -0.007506 -0.000869224 -0.00599817 -0.0074803 -0.000853671 -0.00542588 -0.007506 -0.0029354 -0.00532878 -0.0074803 -0.00288287 -0.00482322 -0.007506 -0.0038462 -0.00399657 -0.0074803 -0.00455349 -0.00220674 -0.007506 -0.00576082 -0.00115629 -0.007506 -0.00605968 -0.0011356 -0.0074803 -0.00595124 0.00101926 -0.007506 -0.00608423 0.00306804 -0.007506 -0.005352 0.00203903 -0.0074803 -0.00570519 0.00301313 -0.0074803 -0.00525622 0.00396374 -0.007506 -0.00472711 0.0047352 -0.007506 -0.00395406 0.00465046 -0.0074803 -0.0038833 0.00535826 -0.007506 -0.00305709 0.00526237 -0.0074803 -0.00300238 0.00581338 -0.007506 -0.0020643 0.0060863 -0.007506 -0.00100682 0.00597738 -0.0074803 -0.000988802 -0.00412223 -0.00784347 0.00528009 -0.00415471 -0.00771999 0.00517409 -0.00414911 -0.00772021 0.00528009 -0.00411812 -0.00759939 0.00517022 -0.00404512 -0.00793771 0.00516248 -0.00412813 -0.00784321 0.00517128 -0.00417291 -0.00771865 0.00506174 -0.00402765 -0.00751209 0.00516063 -0.00390632 -0.0074803 0.00514777 -0.00392896 -0.0074803 0.00500832 -0.00404776 -0.00751188 0.00503434 -0.00413655 -0.00759863 0.00505378 -0.00414763 -0.0078416 0.00505621 -0.00423777 -0.00783312 0.00480533 -0.0042572 -0.00771162 0.00481436 -0.00436567 -0.00758797 0.0045411 -0.00422156 -0.00759466 0.0047978 -0.00429215 -0.00750885 0.00449003 -0.00413954 -0.00751074 0.00475969 -0.00433362 -0.00791679 0.00451883 -0.00438908 -0.00781823 0.00455736 -0.00463392 -0.00768097 0.00427357 -0.00440064 -0.00769959 0.00456539 -0.00459938 -0.00757781 0.00424172 -0.00411238 -0.00759952 0.00528009 -0.00402139 -0.00751213 0.00528009 -0.00389932 -0.0074803 0.00528009 -0.00412223 -0.00784347 0.0060198 -0.00414911 -0.00772021 0.0060198 -0.00411238 -0.00759952 0.0060198 -0.00422216 -0.007402 0.00653785 -0.00417856 -0.007427 0.00647764 -0.00405265 -0.00749592 0.0062226 -0.0040219 -0.00751187 0.00604548 -0.00419676 -0.00730578 0.00665214 -0.00407689 -0.0073783 0.00651847 -0.00454257 -0.00757592 0.00699329 -0.00432475 -0.00770426 0.00661571 -0.00426955 -0.00777808 0.00668997 -0.00422086 -0.00781261 0.00661664 -0.00410295 -0.00789436 0.00637644 -0.00417677 -0.00780684 0.00632921 -0.00415374 -0.00782239 0.0062549 -0.00412274 -0.00784313 0.00604962 -0.00485669 -0.00729671 0.0071252 -0.00457809 -0.00751793 0.00690637 -0.0043269 -0.00722598 0.00678223 -0.00414956 -0.00771994 0.00604588 -0.00417711 -0.00770305 0.00622687 -0.00419788 -0.00769013 0.00629357 -0.00429374 -0.00762867 0.00649393 -0.00428075 -0.00773525 0.00654731 -0.00433502 -0.00760138 0.0065581 -0.00451695 -0.00756415 0.00684704 -0.00451813 -0.007475 0.00677894 -0.004577 -0.00743259 0.00683638 -0.00516303 -0.00703224 0.00729609 -0.00514712 -0.00697765 0.00722053 -0.0055078 -0.00670519 0.00741795 -0.00414036 -0.00758437 0.00621513 -0.00429807 -0.00749248 0.00653005 -0.00448079 -0.00737595 0.00674174 -0.00484741 -0.00722694 0.00705061 -0.00472494 -0.00743011 0.00713125 -0.00550873 -0.00672523 0.00750158 -0.0058375 -0.00637747 0.0075398 -0.00548599 -0.00666667 0.00734423 -0.00581079 -0.00635344 0.00741604 -0.00576088 -0.00630856 0.00733755 -0.00544589 -0.00661423 0.00728912 -0.00402139 -0.00751213 0.0060198 -0.00411283 -0.00759928 0.00604437 -0.00416111 -0.00757286 0.00627827 -0.00407549 -0.00748382 0.00628706 -0.00425685 -0.00751739 0.00646878 -0.00441246 -0.00728697 0.00674291 -0.00453953 -0.00733655 0.00679698 -0.00447297 -0.00724852 0.00679584 -0.00480922 -0.00714415 0.00700367 -0.00510805 -0.00690909 0.0071684 -0.00539224 -0.00655407 0.00725915 -0.00574363 -0.00629305 0.00732573 -0.00467559 -0.00699506 0.00701832 -0.00474854 -0.00706226 0.00699226 -0.00488604 -0.0068421 0.00711448 -0.00505143 -0.00683638 0.00714716 -0.00498535 -0.00676992 0.00715985 -0.00582841 -0.00636929 0.00746255 -0.00578562 -0.00605798 0.0072898 -0.00570906 -0.00626196 0.00730204 -0.00597511 -0.00622107 0.0075398 -0.00594972 -0.00619922 0.0074148 -0.00725693 -0.00430669 0.0075398 -0.0080452 -0.00213201 0.0075398 -0.0082046 -0.00125163 0.0075398 -0.0081714 -0.00124722 0.0074148 -0.00828045 -0.000360221 0.0075398 -0.00823839 0.000540426 0.0074148 -0.00828015 -0.000328687 0.0075398 -0.00823646 0.000957426 0.0075398 -0.00819339 0.00106856 0.0074148 -0.00805166 0.00194671 0.0074148 -0.00808444 0.00195358 0.0075398 -0.00792743 0.00255901 0.0075398 -0.00736317 0.00408684 0.0075398 -0.00730635 0.00413148 0.0074148 -0.00755183 0.00366781 0.0075398 -0.00733651 0.00414606 0.0075398 -0.00690964 0.00493238 0.0075398 -0.00688099 0.00491503 0.0074148 -0.00653192 0.00549514 0.0075398 -0.00640983 0.00567703 0.0075398 -0.00583748 0.00637746 0.0075398 -0.00638292 0.00565709 0.0074148 -0.00752092 0.0036549 0.0074148 -0.00743648 0.00361964 0.00732329 -0.00782782 0.0028098 0.0074148 -0.00774043 0.00278268 0.00732329 -0.0079621 0.00192792 0.00732329 -0.00824698 -0.000358958 0.0074148 -0.00808069 -0.00123516 0.00732329 -0.00792338 -0.002104 0.00732329 -0.00779542 -0.00259872 0.00732329 -0.00801256 -0.0021245 0.0074148 -0.00750836 -0.00344252 0.00732329 -0.00788336 -0.00262403 0.0074148 -0.00759349 -0.00347607 0.0074148 -0.00722705 -0.00429154 0.0074148 -0.00714544 -0.00425015 0.00732329 -0.00670886 -0.00501929 0.00732329 -0.00678624 -0.00506813 0.0074148 -0.00650103 -0.00549418 0.0074148 -0.00588036 -0.00613952 0.00732329 -0.005802 -0.00634554 0.00739285 -0.00574453 0.00629388 0.00732329 -0.0063094 0.0056026 0.00732329 -0.00642638 -0.00544126 0.00732329 -0.00739206 -0.00339669 0.0072898 -0.00780156 -0.00207598 0.0072898 -0.00815554 -0.000355509 0.00732329 -0.00814703 0.000535219 0.00732329 -0.00803063 -0.000350796 0.0072898 -0.00810247 0.00105823 0.00732329 -0.00783976 0.00190225 0.0072898 -0.00762104 0.00274563 0.0072898 -0.00732113 0.00357148 0.0072898 -0.00722397 0.00409165 0.00732329 -0.00680271 0.00486764 0.00732329 -0.00565159 0.0062103 0.0072898 -0.00406873 0.00738305 0.00650557 -0.00451165 0.007105 0.00691413 -0.0047575 0.00693746 0.00706102 -0.00508095 0.00669623 0.00719297 -0.00558931 0.00664316 0.00751761 -0.00582251 0.006364 0.00746466 -0.00575799 0.00630598 0.00734139 -0.00579912 0.00634296 0.0073967 -0.00581258 0.00635507 0.0074148 -0.00540987 0.00642652 0.00727126 -0.00570746 0.00626054 0.00730993 -0.00552291 0.00654236 0.00730701 -0.00529945 0.00692777 0.00743751 -0.00546978 0.00648536 0.00727544 -0.00520296 0.00682948 0.00720913 -0.00526001 0.00694355 0.0073377 -0.00556326 0.00659108 0.00736241 -0.00558626 0.00662599 0.00743536 -0.00548467 0.0067459 0.00748869 -0.00482836 0.00700493 0.00703849 -0.0051473 0.00676009 0.00718517 -0.00488779 0.00708461 0.00705266 -0.00524231 0.00689354 0.00726238 -0.00493741 0.00722928 0.00717638 -0.00525367 0.00697273 0.00742486 -0.00444933 0.00714747 0.00687689 -0.0045296 0.00721173 0.00684164 -0.00463231 0.007392 0.0068862 -0.00492621 0.00716364 0.00710123 -0.00463533 0.00747392 0.00695759 -0.00460319 0.007529 0.00704561 -0.0049196 0.00727093 0.00726598 -0.00429887 0.0072436 0.00675817 -0.00438583 0.00730364 0.00671809 -0.0045947 0.00729872 0.00684495 -0.00449004 0.00758426 0.00681917 -0.00419825 0.00741579 0.0065057 -0.00445502 0.00739298 0.0067159 -0.0044923 0.00749336 0.00675206 -0.00444872 0.00764712 0.00690352 -0.00415013 0.00744303 0.0064337 -0.00423016 0.00753322 0.00642437 -0.00427542 0.00750626 0.00649728 -0.00426701 0.00764611 0.00644734 -0.00425204 0.00775526 0.00649724 -0.00431233 0.00761646 0.0065238 -0.0043006 0.00772134 0.00657923 -0.00405945 0.00749234 0.00624369 -0.00404563 0.00739663 0.00647315 -0.00404471 0.00750007 0.00619485 -0.00416995 0.00770747 0.00619832 -0.00414652 0.00758098 0.00623572 -0.00414573 0.00782777 0.00622283 -0.00418327 0.00769924 0.00624864 -0.00416059 0.00781778 0.00627924 -0.0040841 0.0079072 0.00631994 -0.00392663 0.00746493 0.00621677 -0.00413321 0.00758829 0.00618814 -0.00403858 0.00793792 0.0060198 -0.00402139 0.00751213 0.0060198 -0.00402139 0.00751213 0.00528009 -0.00411238 0.00759952 0.0060198 -0.00411238 0.00759952 0.00528009 -0.00414911 0.00772021 0.0060198 -0.00412223 0.00784347 0.0060198 -0.00412223 0.00784347 0.00528009 -0.00403858 0.00793792 0.00528009 -0.00389932 0.0074803 0.00528009 -0.00414911 0.00772021 0.00528009 -0.00390632 0.0074803 0.00514774 -0.00404777 0.00751188 0.00503433 -0.00402765 0.0075121 0.0051606 -0.00413656 0.00759863 0.00505377 -0.00411812 0.0075994 0.00517019 -0.00415471 0.00771999 0.00517407 -0.00417291 0.00771865 0.00506173 -0.00413955 0.00751075 0.00475968 -0.00422157 0.00759467 0.00479779 -0.00425721 0.00771162 0.00481435 -0.00414763 0.00784161 0.0050562 -0.00412813 0.00784321 0.00517126 -0.00404512 0.00793771 0.00516245 -0.00436568 0.00758797 0.00454109 -0.00438909 0.00781824 0.00455735 -0.00423777 0.00783313 0.00480532 -0.00419688 0.0074803 0.00442385 -0.00453494 0.007506 0.00418223 -0.00429216 0.00750885 0.00449003 -0.00463395 0.00768097 0.00427354 -0.00440065 0.0076996 0.00456538 -0.00463144 0.00779427 0.00427123 -0.00605741 0.00789442 -0.00142464 -0.00554133 0.00779427 -0.00299789 -0.00325585 0.00779427 -0.0053938 -0.00225368 0.00779427 -0.00588342 -7.04733e-05 0.00789442 -0.0062468 0.00588706 0.00789442 -0.00209046 0.00611939 0.00789442 -0.00119024 -0.00445378 0.0074803 0.00410739 -0.00599817 0.0074803 -0.000853697 -0.00605471 0.0074803 0.000217399 0.00570934 0.0074803 -0.00202736 0.00535826 0.007506 -0.00305709 0.00597738 0.0074803 -0.000988802 -0.00542587 0.007506 -0.00293543 -0.00482321 0.007506 -0.00384622 -0.00550301 0.00757781 -0.00297716 -0.00585847 0.007506 -0.00193263 -0.00532877 0.0074803 -0.00288289 -0.00623743 0.00779427 -0.000887753 -0.00598638 0.00768097 -0.00197482 -0.00624081 0.00768097 -0.000888234 -0.00594176 0.00757781 -0.0019601 -0.0061943 0.00757781 -0.000881614 -0.00575363 0.0074803 -0.00189804 -0.00610747 0.007506 -0.000869254 0.00313503 0.00768097 -0.00546884 0.00581338 0.007506 -0.0020643 0.00617283 0.00757781 -0.00102113 0.0059403 0.00768097 -0.00210937 0.00593709 0.00779427 -0.00210823 0.00621582 0.00779427 -0.00102825 0.00543444 0.00757781 -0.00310055 0.00589603 0.00757781 -0.00209365 0.00542617 0.00789442 -0.00309583 0.00473521 0.007506 -0.00395406 0.00547524 0.00768097 -0.00312383 0.00547229 0.00779427 -0.00312214 0.00479522 0.00789442 -0.00400417 0.00529746 0.00789442 -0.00328113 0.00480253 0.00757781 -0.00401027 0.00405028 0.00768097 -0.00483031 0.00483859 0.00768097 -0.00404038 0.00483597 0.00779427 -0.0040382 0.00401398 0.00789442 -0.00478701 0.0040201 0.00757781 -0.00479431 0.00313334 0.00779427 -0.00546588 0.00404809 0.00779427 -0.00482769 0.00104097 0.00779427 -0.0062137 0.00212153 0.00768097 -0.00593597 0.00396374 0.007506 -0.0047271 0.00103219 0.00789442 -0.00616134 0.00178855 0.00789442 -0.00596448 0.00210251 0.00789442 -0.00588277 0.00212038 0.00779427 -0.00593276 0.00311167 0.00757781 -0.00542808 0.00210572 0.00757781 -0.00589173 0.00104153 0.00768097 -0.00621706 0.00306805 0.007506 -0.00535199 0.0020762 0.007506 -0.00580915 -7.10722e-05 0.00779427 -0.00629989 -0.00117093 0.00789442 -0.00613648 0.00301314 0.0074803 -0.00525622 0.00103377 0.00757781 -0.00617073 -7.05809e-05 0.00757781 -0.00625632 -7.11108e-05 0.00768097 -0.0063033 -0.00118152 0.00768097 -0.00619198 -0.00118088 0.00779427 -0.00618863 -0.00155427 0.00789442 -0.00602742 0.00203904 0.0074803 -0.00570518 0.00100104 0.0074803 -0.00597535 0.00101928 0.007506 -0.00608423 -6.95914e-05 0.007506 -0.00616862 -0.00117272 0.00757781 -0.00614584 -0.00261501 0.00789442 -0.00564803 -6.83462e-05 0.0074803 -0.00605823 -0.00115628 0.007506 -0.00605969 -0.0022549 0.00768097 -0.0058866 -0.00412095 0.00789442 -0.00469524 -0.00113559 0.0074803 -0.00595124 -0.0022381 0.00757781 -0.00584273 -0.00325761 0.00768097 -0.00539672 -0.00415597 0.00779427 -0.00473514 -0.00488433 0.00789442 -0.00389497 -0.00220673 0.007506 -0.00576083 -0.00323333 0.00757781 -0.0053565 -0.00412723 0.00757781 -0.00470239 -0.00415822 0.00768097 -0.0047377 -0.00492584 0.00779427 -0.00392807 -0.00549463 0.00789442 -0.00297263 -0.00216723 0.0074803 -0.00565773 -0.00313096 0.0074803 -0.0051869 -0.00318801 0.007506 -0.00528142 -0.00406938 0.007506 -0.00463648 -0.00492851 0.00768097 -0.00393019 -0.00593272 0.00789442 -0.00195712 -0.00489178 0.00757781 -0.00390091 -0.00554433 0.00768097 -0.00299951 -0.00598314 0.00779427 -0.00197375 -0.00624318 0.00789442 0.000224164 -0.00616504 0.007506 0.000221359 -0.00625269 0.00757781 0.000224507 -0.00621501 0.00789442 -0.000309458 -0.00610581 0.00789442 0.00132157 -0.00616911 0.00789442 0.000815881 -0.0060294 0.007506 0.00130504 -0.00629964 0.00768097 0.000226194 -0.00629623 0.00779427 0.000226071 -0.0061577 0.00779427 0.00133281 -0.00592122 0.00789442 0.00191457 -0.00611512 0.00757781 0.00132359 -0.00582933 0.00768097 0.00239907 -0.00616103 0.00768097 0.00133353 -0.00582618 0.00779427 0.00239777 -0.00520137 0.007506 0.003317 -0.00570478 0.007506 0.00234781 -0.00578589 0.00757781 0.00238119 -0.00527532 0.00757781 0.00336416 -0.00531205 0.00779427 0.00338759 -0.00547941 0.00789442 0.00295065 -0.00577708 0.00789442 0.00237757 -0.00485815 0.00789442 0.00389024 -0.00459941 0.00757781 0.00424169 -0.00531493 0.00768097 0.00338942 0.00616344 0.00789442 -0.00101958 0.00621918 0.00768097 -0.0010288 0.00618075 0.00789567 -0.000932975 0.00623284 0.00779555 -0.000946594 0.00632118 0.00788931 -0.000637101 0.00641562 0.00788056 -0.000531292 0.00623666 0.00768194 -0.000947593 0.00625785 0.0077956 -0.000866422 0.00636274 0.00778908 -0.000665044 0.00642371 0.00778335 -0.000585424 0.00661865 0.00776176 -0.00040088 0.00689494 0.00772818 -0.000225814 0.0060863 0.007506 -0.00100682 0.00619141 0.00757833 -0.000935761 0.00610646 0.00750614 -0.000913547 0.00621764 0.00757836 -0.000851778 0.00632412 0.00757569 -0.000639083 0.00658108 0.00756502 -0.000353532 0.00678734 0.0074803 -1.78098e-09 0.00682333 0.00749913 -8.85594e-05 0.0064645 0.0074803 -0.000206588 0.00623491 0.0074803 -0.000430377 0.00652846 0.00750246 -0.000287207 0.00631828 0.00750477 -0.000498841 0.0060311 0.0074803 -0.00078384 0.00625171 0.00750541 -0.00059039 0.00613513 0.00750615 -0.000821726 0.00599936 0.0074803 -0.000885544 0.0067799 0.00783735 -0.00027013 0.00721499 0.00760589 -5.55831e-05 0.00626158 0.00768198 -0.000867778 0.00636379 0.00767704 -0.000665752 0.00642292 0.00767274 -0.000584772 0.00638532 0.0075734 -0.000553897 0.00661303 0.00765688 -0.000393802 0.00688586 0.00763316 -0.000208409 0.00686073 0.00755278 -0.000160238 0.0072615 0.00755761 -1.78098e-09 0.0073919 0.00759942 -1.78098e-09 0.0071975 0.00753908 -2.59458e-06 0.00722406 0.00768619 -8.30646e-05 0.00728146 0.00768192 -6.46654e-05 0.00721431 0.00760329 -5.3523e-05 0.00727254 0.00760022 -3.41627e-05 0.00743331 0.00767148 -2.5181e-05 0.00742707 0.00761069 -1.78098e-09 0.00747992 0.00775263 -2.64439e-05 0.00722424 0.00768778 -8.36085e-05 -1.44869e-10 0.0074803 -0.0011 0.000646564 0.0079043 -0.000889918 0.00109397 0.0079043 -0.000114983 0.000952628 0.0079043 -0.00055 0.000817459 0.0079043 0.000736045 0.00104616 0.0079043 0.00033992 0.00044741 0.0079043 0.0010049 0.00055 0.0074803 0.000952629 -0.00104616 0.0079043 0.00033992 -0.000952628 0.0074803 0.00055 -0.0011 0.0074803 -1.78098e-09 -0.00055 0.0074803 -0.000952629 -0.000952628 0.0079043 -0.00055 0.000228703 0.0079043 -0.00107596 -0.000228703 0.0079043 -0.00107596 -0.000646564 0.0079043 -0.000889918 0.00055 -0.0074803 -0.000952629 0.00044741 -0.0079043 -0.0010049 0.000539413 -0.0079043 -0.000938056 0.000931811 -0.0079043 -0.000537982 0.00104616 -0.0079043 -0.00033992 0.0011 -0.0074803 -1.78098e-09 0.00108209 -0.0079043 1.88322e-06 0.00109397 -0.0079043 0.000114983 0.00055 -0.0074803 0.000952629 -1.44869e-10 -0.0074803 0.0011 -0.000646564 -0.0079043 0.000889918 -0.000952628 -0.0079043 0.00055 -0.00108209 -0.0079043 1.88322e-06 -0.000931811 -0.0079043 -0.000537982 -0.000817459 -0.0079043 -0.000736045 -0.000539413 -0.0079043 -0.000938056 -1.44869e-10 -0.0074803 -0.0011 -0.00044741 -0.0079043 -0.0010049 -0.00089482 -0.0090043 -0.0020098 -0.00104616 -0.0079043 -0.00033992 -0.00209232 -0.0090043 -0.000679837 -0.00109397 -0.0079043 0.000114983 -0.000542674 -0.0079043 0.000936175 -0.000228703 -0.0079043 0.00107596 -1.44869e-10 -0.0079043 0.00107596 0.000228703 -0.0079043 0.00107596 0.000542674 -0.0079043 0.000936175 0.000646564 -0.0079043 0.000889918 0.00190526 -0.0090043 0.0011 0.000952628 -0.0079043 0.00055 0.000817459 -0.0079043 -0.000736045 -1.44869e-10 -0.0090043 -0.0022 -1.44869e-10 -0.0079043 -0.0011 -0.000539413 0.0079043 0.000938056 -0.000817459 0.0079043 0.000736045 -0.000931811 0.0079043 0.000537982 -0.00209232 0.0090043 0.000679838 -0.00108209 0.0079043 -1.88305e-06 -0.00109397 0.0079043 -0.000114983 -0.00129313 0.0090043 -0.00177984 -0.000542674 0.0079043 -0.000936175 -1.44869e-10 0.0079043 -0.00107596 0.000542674 0.0079043 -0.000936175 0.00218795 0.0090043 -0.000229964 0.00108209 0.0079043 -1.88305e-06 0.00209232 0.0090043 0.000679838 0.000931811 0.0079043 0.000537982 0.00163492 0.0090043 0.00147209 0.000894821 0.0090043 0.0020098 0.000539413 0.0079043 0.000938056 -1.44869e-10 0.0090043 0.0022 -1.44869e-10 0.0079043 0.0011 -0.00044741 0.0079043 0.0010049 -0.00182404 -0.0090297 0.00359034 -0.00226028 -0.0090043 0.0030716 -0.00224523 -0.00900431 0.00308052 -0.00188481 -0.00902133 0.00352598 -0.00222574 -0.00900434 0.00309665 -0.00211972 -0.00900481 0.00318203 -0.00194434 -0.0090076 0.0033165 -0.00177896 -0.00901581 0.00343776 -0.00171656 -0.00901891 0.00348352 -0.00199546 -0.00900674 0.00364843 -0.00200524 -0.00900573 0.00362839 -0.00205734 -0.00900544 0.00351598 -0.00218081 -0.00900475 0.00324957 -0.00226871 -0.0090043 0.00306089 -0.000357822 -0.00936274 0.00427201 0.000604077 -0.0092821 0.00396145 0.000626233 -0.00947486 0.00425252 -0.000280041 -0.00921769 0.00400024 -0.000932192 -0.0091351 0.00387258 -0.000802365 -0.00915515 0.00392391 -0.000618626 -0.00917715 0.00395077 -0.00164966 -0.00906985 0.00380659 -0.000977026 -0.00912818 0.00385485 -0.0014083 -0.00914088 0.00396316 -0.00123192 -0.00908882 0.00375407 -0.00142906 -0.00905837 0.00367612 -0.0016196 -0.00907438 0.00377954 -0.000433443 -0.00941597 0.0046246 -0.000847851 -0.00932783 0.00452797 -0.000732541 -0.00929592 0.00421071 -0.00122679 -0.00923058 0.00438206 -0.00108026 -0.00922172 0.00410994 -0.00113071 -0.00920997 0.00409109 -0.00157569 -0.00912644 0.00417769 -0.00160959 -0.00908617 0.00383683 -0.000249696 -0.00944794 0.00464738 -0.000240546 -0.00938089 0.00428262 0.000817284 -0.00948615 0.004222 0.00127501 -0.00949963 0.00411431 0.000210303 -0.00925778 0.00399526 0.000175375 -0.00951214 0.00467525 0.000187093 -0.00943606 0.00429059 0.000668477 -0.00956148 0.00464901 0.000883171 -0.00957509 0.0046201 0.001397 -0.0095885 0.00450795 0.00380896 -0.00900431 -0.00013618 0.00399512 -0.0090285 0.000166865 0.00397666 -0.00907372 0.000427688 0.00411973 -0.00921241 0.000662068 0.0041359 -0.00923104 0.000688678 0.00381417 -0.0090043 -0.00013919 0.00396797 -0.00900905 -2.64104e-05 0.00381155 -0.00900431 -0.000137677 0.00384329 -0.00900488 -9.11447e-05 0.00430248 -0.00905588 0.000267865 0.00414404 -0.0090201 0.000111362 0.0041271 -0.00901627 9.46318e-05 0.00437097 -0.0090907 0.000355886 0.0043518 -0.00908095 0.00033124 0.00408092 -0.00907884 0.000373097 0.00410886 -0.00911779 0.000479447 0.00412264 -0.00918263 0.000617562 0.00448499 -0.00923525 0.000589112 0.00416339 -0.00923137 0.00068084 0.00327804 -0.00951259 0.00284017 0.00269815 -0.00951259 0.00339589 0.00202575 -0.00951259 0.00383516 0.00128427 -0.00950638 0.0041442 0.00346559 -0.0092964 0.00202361 0.00374551 -0.00951259 0.00218706 0.00356687 -0.0095885 0.00309042 0.00293589 -0.0095885 0.00369511 0.0040396 -0.00924176 0.000783151 0.00391912 -0.00927092 0.000996949 0.0040825 -0.00951169 0.00145822 0.00416358 -0.00929519 0.000769312 0.00415342 -0.00939344 0.000961239 0.00449632 -0.00945717 0.000955263 0.0041455 -0.00942506 0.00104202 0.00449268 -0.00949807 0.00105936 0.00447023 -0.00957276 0.00136451 0.00408464 -0.00951215 0.00145898 0.00411321 -0.00948951 0.00128098 -0.00226253 0.0090043 0.00307343 -0.00211984 0.00900481 0.00318195 -0.00188492 0.00902134 0.00352593 -0.00170464 0.00902053 0.0034921 -0.00182426 0.00902969 0.00359018 -0.00161974 0.00907438 0.00377949 -0.00206722 0.00900539 0.00349487 -0.0022604 0.0090043 0.00307152 -0.00225829 0.00900431 0.00306961 -0.00161097 0.00908582 0.00383587 -0.00113325 0.00920938 0.0040901 -0.00123385 0.00908851 0.00375315 -0.0014714 0.00905186 0.00365938 -0.000243552 0.00938042 0.00428238 -0.000283414 0.00921728 0.00399979 -0.000735786 0.00929528 0.00420997 -0.000621643 0.00917682 0.00395053 -0.000799363 0.00915556 0.00392465 -0.000934583 0.0091347 0.00387128 0.000503329 0.00927951 0.00398353 0.000207058 0.00925747 0.00399541 0.000183576 0.00943552 0.00429069 -0.000201068 0.00922713 0.00401178 0.00118793 0.0092964 0.0038333 0.000774445 0.0092862 0.00392403 0.00127501 0.00949963 0.00411431 -0.0018239 0.00904361 0.00396322 -0.0016498 0.00906985 0.00380654 -0.0017839 0.00905747 0.0040037 -0.00141033 0.00914036 0.00396203 -0.00122984 0.00922974 0.00438061 -0.00108309 0.00922107 0.00410891 -0.000851415 0.00932699 0.00452687 -0.000361562 0.00936213 0.0042716 -0.000306182 0.0094393 0.00464342 0.000817321 0.00948601 0.00422193 0.000622167 0.00947439 0.00425303 0.000600529 0.0092819 0.0039622 0.00377929 0.0092964 0.00134992 0.00346559 0.0092964 0.00202361 0.00202575 0.00951259 0.00383516 0.00249651 0.0092964 0.0031421 0.00303305 0.0092964 0.00262791 0.00327804 0.00951259 0.00284017 0.00374551 0.00951259 0.00218706 0.00128427 0.00950638 0.0041442 0.00269815 0.00951259 0.00339589 0.00293589 0.0095885 0.00369511 0.00416339 0.00923137 0.00068084 0.0040983 0.00918176 0.000626782 0.00412264 0.00918263 0.000617562 0.00397516 0.00907879 0.000425572 0.00408092 0.00907884 0.000373097 0.00410886 0.00911779 0.000479447 0.00403017 0.00911796 0.000515277 0.00403133 0.00911879 0.000517165 0.00388391 0.00901901 0.000199219 0.00380896 0.00900431 -0.00013618 0.00381155 0.00900431 -0.000137677 0.00384329 0.00900488 -9.11447e-05 0.00386577 0.00900442 -0.000104153 0.00381417 0.0090043 -0.00013919 0.00414404 0.0090201 0.000111362 0.00399512 0.0090285 0.000166865 0.00389089 0.0090229 0.000226634 0.00437846 0.00909451 0.000365505 0.00448499 0.00923525 0.000589112 0.00381274 0.00929139 0.00126091 0.00410611 0.00949694 0.00132474 0.00416203 0.00932861 0.000827348 0.0038958 0.00927746 0.00104623 0.00414009 0.00944116 0.00108928 0.00403963 0.00924176 0.000783121 0.0040825 0.00951169 0.00145822 0.00408464 0.00951215 0.00145898 0.00445481 0.00958637 0.00150531 0.00446453 0.00957962 0.00141986 0.00409446 0.00950591 0.0013926 0.00414754 0.00941804 0.00102285 -0.00225817 -0.00900431 0.0030697 -0.00224288 -0.0090043 0.00307661 -0.00222144 -0.0090043 0.00308934 -0.00191425 -0.0090043 0.00324111 -0.0017044 -0.00902054 0.00349224 -0.0014597 -0.00902808 0.00350752 -0.00147127 -0.00905185 0.00365943 -0.000175148 -0.00922908 0.00401076 -0.000221261 -0.00906166 0.00371698 -0.000201006 -0.00922715 0.0040118 -0.000796594 -0.00904275 0.00367047 0.00118793 -0.0092964 0.0038333 0.000774303 -0.00928627 0.00392409 0.000446257 -0.00907568 0.00367064 0.00050384 -0.00927965 0.00398345 0.00285565 -0.0090043 0.00166745 0.00229486 -0.00908021 0.00288831 0.00154447 -0.0090043 0.002924 0.00172296 -0.00908021 0.00326192 0.00318567 -0.00908021 0.00186016 0.00278807 -0.00908021 0.00241565 0.00303305 -0.0092964 0.00262791 0.00249651 -0.0092964 0.0031421 0.00109197 -0.00908021 0.00352368 0.00187435 -0.0092964 0.00354854 0.00382846 -0.00906554 0.000566712 0.00391818 -0.00906906 0.000479048 0.00327527 -0.0090043 0.000745783 0.00377929 -0.0092964 0.00134992 0.00347403 -0.00908021 0.00124088 0.00382395 -0.00928975 0.00123101 0.00388352 -0.00928088 0.00107244 0.00360289 -0.00907602 0.000921728 0.00373052 -0.00906924 0.000691464 0.00397374 -0.00925563 0.000881167 0.003451 -0.0090043 0.000473449 0.00401498 -0.00924694 0.000819793 0.00400139 -0.00911169 0.000559168 0.0038848 -0.00903498 0.000373511 0.00391772 -0.00903788 0.000331936 0.00402458 -0.00910285 0.000505531 0.00403265 -0.00911214 0.000518808 0.00409688 -0.0091861 0.000624476 0.00385131 -0.0090348 0.00041466 0.00401756 -0.00911065 0.00053961 0.00379552 -0.00902109 0.000287613 0.00372784 -0.00901179 0.000263063 0.00376323 -0.00901198 0.000329858 0.00378005 -0.00901169 0.000309071 0.00367661 -0.0090043 0.000237605 0.00389168 -0.00902516 0.000226034 0.00368951 -0.0090043 0.000213826 0.00374813 -0.0090043 7.52826e-05 0.00386463 -0.00901195 0.000116056 0.00381998 -0.0090046 -8.59778e-05 0.00380968 -0.00900431 -0.000132935 -0.00226883 0.0090043 0.0030608 -0.00224293 0.0090043 0.00307656 -0.00224529 0.00900431 0.00308048 -0.00222156 0.0090043 0.00308926 -0.00222585 0.00900434 0.00309656 -0.00210516 0.0090043 0.00315357 -0.00194447 0.0090076 0.00331642 -0.00191438 0.0090043 0.00324103 -0.00177906 0.00901581 0.00343771 -0.00167606 0.0090043 0.00331806 -0.00171669 0.00901891 0.00348345 -0.00143046 0.00905817 0.00367554 -0.000793688 0.00904286 0.00367091 -0.000979191 0.00912781 0.00385367 -0.00145983 0.00902808 0.00350747 -0.00144826 0.0090043 0.00335555 0.000445761 0.00907565 0.00367077 -0.000787539 0.0090043 0.00339597 -0.000221267 0.00906165 0.00371697 -0.000244083 0.0090043 0.00338397 0.00037861 0.0090043 0.00330595 0.00205712 0.0090043 0.00258909 0.00229486 0.00908021 0.00288831 0.00249924 0.0090043 0.0021654 0.00285565 0.0090043 0.00166745 0.00109197 0.00908021 0.00352368 0.00172296 0.00908021 0.00326192 0.00187435 0.0092964 0.00354854 0.00278807 0.00908021 0.00241565 0.00318567 0.00908021 0.00186016 0.00411973 0.00920984 0.000662049 0.00407278 0.00914831 0.000584768 0.00401751 0.00911064 0.000539551 0.0039177 0.00903787 0.000331877 0.00385128 0.00903479 0.00041463 0.00388478 0.00903497 0.000373466 0.00393196 0.00906974 0.000492273 0.00399731 0.00912143 0.000555208 0.0039194 0.0090643 0.000480188 0.00387475 0.00928211 0.00109593 0.00347403 0.00908021 0.00124088 0.00379558 0.00929396 0.00130657 0.00360388 0.00907597 0.000919612 0.00388426 0.00928069 0.00107063 0.00397341 0.00925574 0.000882132 0.00397448 0.00925544 0.000879867 0.0041359 0.00923104 0.000688678 0.00373161 0.00906919 0.000689847 0.00345253 0.0090043 0.00047149 0.00382849 0.00906554 0.000566674 0.00372807 0.00901182 0.000263134 0.00378004 0.0090118 0.000309056 0.00376326 0.00901198 0.00032988 0.00368953 0.0090043 0.000213796 0.00379549 0.00902108 0.000287576 0.00382179 0.00900671 -7.87321e-05 0.00380526 0.0090043 -0.000133851 0.00380968 0.00900431 -0.000132942 0.00925788 -0.0020195 0.00543631 0.00954747 -0.0020195 0.00490309 0.00928677 -0.0020195 0.00539525 0.00942225 -0.0020195 0.00520276 0.00870193 -0.0020195 0.00587875 0.0111774 -0.0020195 0.00200475 0.0111774 -0.0020195 0.0059042 0.00958843 -0.0020195 0.00460843 0.00956832 -0.0020195 0.00481436 0.00897242 -0.0020195 0.00570788 0.00958989 -0.00157047 0.00978463 0.00951571 -0.00168466 0.00937569 0.00936115 -0.00185563 0.00918002 0.00951318 -0.00168761 0.0093724 0.009297 -0.00201318 0.00923325 0.00929159 -0.0018901 0.00911707 0.00858989 -0.0025146 0.00911675 0.00896946 -0.00198993 0.00887624 0.00858989 -0.00208312 0.00887688 0.00897257 -0.00201847 0.00891706 0.0090804 -0.0025146 0.00926492 0.00951377 -0.00214117 0.0096703 0.00897257 -0.00232076 0.00915977 0.00897257 -0.00214889 0.00906422 0.00951377 -0.00181006 0.00948622 0.009297 -0.00224883 0.00936426 0.00958989 -0.00201418 0.0100313 0.00951377 -0.0025146 0.00973407 0.00958989 -0.0037846 0.0101168 0.00951377 -0.0037846 0.00973407 0.00944172 -0.0025146 0.00962624 0.009297 -0.0037846 0.00940964 0.009297 -0.0025146 0.00940964 0.00897257 -0.0025146 0.00919287 0.00944172 -0.0037846 0.00962624 0.00858989 -0.0042926 0.00860875 0.00858989 -0.00403608 0.00904374 0.00897257 -0.00412794 0.00908131 0.00858989 -0.00408319 0.00901973 0.00858989 -0.00419558 0.00890734 0.0090804 -0.00444077 0.00860875 0.00897257 -0.00436872 0.00860875 0.00897257 -0.0037846 0.00919287 0.0090804 -0.0037846 0.00926492 0.00897257 -0.0039651 0.00916428 0.009297 -0.00403209 0.00937044 0.009297 -0.00425535 0.00925669 0.00897257 -0.00425716 0.00895209 0.00897257 -0.00434013 0.00878925 0.009297 -0.00443254 0.0090795 0.009297 -0.00454629 0.00885624 0.009297 -0.00458549 0.00860875 0.00951377 -0.00413234 0.00967899 0.00951377 -0.00444604 0.00951915 0.00951377 -0.004695 0.00927019 0.00951377 -0.00485484 0.00895649 0.00951377 -0.00490992 0.00860875 0.00944172 -0.00480209 0.00860875 0.00944172 -0.00480209 0.00601795 0.009297 -0.00458549 0.00601795 0.0090804 -0.00444077 0.00601795 0.00897257 -0.00436872 0.00601795 0.00897257 -0.00412794 0.00554539 0.00858989 -0.00426774 0.00586097 0.00858989 -0.00419558 0.00571935 0.00897257 -0.00425716 0.00567461 0.00897257 -0.00434013 0.00583745 0.009297 -0.00454629 0.00577046 0.009297 -0.00425535 0.00537002 0.00897257 -0.0039651 0.00546242 0.009297 -0.00403209 0.00525626 0.009297 -0.0037846 0.00521705 0.00951377 -0.00485484 0.00567021 0.009297 -0.00443254 0.0055472 0.00951377 -0.00413234 0.00494771 0.00951377 -0.00490992 0.00601795 0.00958989 -0.0052926 0.00601795 0.00951377 -0.004695 0.0053565 0.00951377 -0.00444604 0.00510755 0.00958989 -0.0050046 0.00513157 0.00858989 -0.0037846 0.00550995 0.00897257 -0.0037846 0.00543383 0.0090804 -0.0025146 0.00536178 0.0090804 -0.0037846 0.00536178 0.00944172 -0.0025146 0.00500046 0.00944172 -0.0037846 0.00500046 0.00951377 -0.0037846 0.00489263 0.00894724 -0.0020195 0.00572745 0.00896963 -0.0020195 0.00571006 0.00929228 -0.0020195 0.00538742 0.00950431 -0.0020195 0.00500637 0.00858989 -0.00219655 0.00562183 0.00858989 -0.00208312 0.00574982 0.00897257 -0.0025146 0.00543383 0.00897257 -0.00232076 0.00546693 0.00897257 -0.00214889 0.00556248 0.00899115 -0.0020195 0.00569333 0.009297 -0.00224883 0.00526244 0.009297 -0.0025146 0.00521705 0.00951377 -0.0025146 0.00489263 0.00951377 -0.00214117 0.0049564 0.00958989 -0.0020195 0.00459354 0.0117387 -0.00149576 0.00950663 0.0117387 -0.0020066 0.008812 0.00934449 -0.00186737 0.00916254 0.00912826 -0.00196031 0.00897668 0.00908744 -0.00196987 0.00894828 0.00903258 -0.00198271 0.0089101 0.0111774 -0.0020195 0.0087225 0.00874396 -0.00201573 0.00875528 0.00938126 -0.00184148 0.00920112 0.00957443 -0.00149362 0.00950341 0.0117387 -0.00185586 0.00918017 0.0117387 -0.00102429 0.00962475 0.00958989 -0.00102429 0.00962475 0.00958989 -0.00135222 0.00956945 0.00958299 -0.00146578 0.00952202 0.0124467 0.00691089 0.000204457 0.0125225 0.00691089 0.000248963 0.0124937 0.00691089 0.000202397 0.0128023 0.00691089 0.000439184 0.01281 0.00691089 0.000478244 0.0129331 0.00691089 0.000617543 0.0130391 0.00691089 0.000747772 0.012368 0.00691089 0.0001639 0.0119324 0.00691089 2.48273e-05 0.0120159 0.00691089 4.1416e-05 0.0121462 0.00691089 8.67602e-05 0.0128023 -0.00690911 0.000439184 0.0121344 -0.00690911 5.35455e-05 0.0131567 -0.00690911 0.0010052 0.013104 -0.00690911 0.000873691 0.0130775 -0.00690911 0.000836769 0.0130391 -0.00690911 0.000747772 0.0130361 -0.00690911 0.000765162 0.0128101 -0.00690911 0.000478031 0.012624 -0.00690911 0.000317594 0.0124937 -0.00690911 0.000202397 0.0123042 -0.00690911 0.000134645 0.0117393 -0.00690911 2.77356e-06 0.0117487 -0.00690911 2.77356e-06 0.0118332 -0.00690911 1.06675e-05 0.0119259 -0.00690911 2.36426e-05 0.0132387 -0.006773 0.0020955 0.0132387 0.00589489 0.0015875 0.0132387 -0.00690911 0.00149277 0.0132387 0.00691089 0.00149277 0.0119432 -0.00690911 1.55215e-05 0.0117487 0.00691089 2.77356e-06 0.0119432 0.00691089 1.55215e-05 0.0121344 0.00691089 5.35455e-05 0.00371487 0.00313836 0.00627224 0.00360894 0.00321413 0.00633378 0.00352637 0.00329398 0.00637935 0.00428577 0.0028931 0.00589689 0.0117387 0.00296599 0.00605849 0.00405442 0.00296855 0.00605723 0.00401724 0.00298067 0.00608301 0.0117387 0.00284689 0.005614 0.0046497 0.00284784 0.00561404 0.00544318 0.00328297 0.00484902 0.0117387 0.00296599 0.00516949 0.00505805 0.00292504 0.0052495 0.00544657 0.00329185 0.00484515 0.0117387 0.00329139 0.0048441 0.0051334 0.00449851 0.00517367 0.00528715 0.00439613 0.00501868 0.00543008 0.0042127 0.00486368 0.0117387 0.00418039 0.0048441 0.00502451 0.00456041 0.00528161 0.00442489 0.00460663 0.00579323 0.00454468 0.00461855 0.00569884 0.0117387 0.00450578 0.00605849 0.0117387 0.00462489 0.005614 0.00459801 0.00462385 0.00565681 0.0117387 0.00418039 0.00638389 0.0117387 0.00373589 0.006503 0.00340166 0.00404514 0.00644747 0.00352737 0.00417773 0.00637883 0.011702 -0.00706998 0.0234318 0.0117387 -0.00690911 0.0234318 0.0119037 -0.00690911 0.0234318 0.0117754 -0.00706998 0.0234318 0.0124595 -0.00725622 0.0240667 0.0125387 -0.00690911 0.0240667 0.0125379 -0.00694608 0.0254275 0.011018 -0.00725622 0.0240667 0.0109387 -0.00690911 0.0254318 0.0110459 -0.00730911 0.0254318 0.0112399 -0.00753458 0.0240667 0.0110546 -0.00730218 0.0240667 0.0113465 -0.00758588 0.0240667 0.0122375 -0.00753458 0.0240667 0.0121387 -0.00760193 0.0254318 0.0117387 -0.00770911 0.0254318 0.0109387 -0.0063 0.0254318 0.0109387 -0.00629968 0.025191 0.0109387 -0.0062471 0.0246475 0.0109373 0.00621064 0.0243716 0.0109373 0.0063 0.0252323 0.0109373 0.00629889 0.0251589 0.0124195 0.00730283 0.0240667 0.0122441 0.00752942 0.0240667 0.0121369 0.00760351 0.0254318 0.0119233 0.00768858 0.0240667 0.0117367 0.00769028 0.0240667 0.0117369 0.00771054 0.0254318 0.0115652 0.00769184 0.0240667 0.0112415 0.00753854 0.0240667 0.0109371 0.00691035 0.0240667 0.0117387 0.0063 0.0234318 0.0115721 0.0069105 0.0234318 0.0117755 0.00707101 0.0234318 0.0117017 0.00707168 0.0234318 0.0118417 0.00703818 0.0234318 0.0117387 0.00691089 0.0234318 0.0119021 0.00691089 0.0234318 0.0117387 -0.00768906 0.0240667 0.0119167 -0.00768906 0.0240667 0.0115901 -0.0069807 0.0234318 0.0115737 -0.00690911 0.0234318 0.0114379 -0.00728635 0.0235168 0.0124229 -0.00730218 0.0240667 0.0123829 -0.00721931 0.0237493 0.0121845 -0.00746807 0.0237493 0.012131 -0.00758588 0.0240667 0.0121734 -0.00711846 0.0235168 0.0118874 -0.0069807 0.0234318 0.0115796 -0.00760611 0.0237493 0.0118978 -0.00760611 0.0237493 0.0120396 -0.00728635 0.0235168 0.0118461 -0.00737952 0.0235168 0.0118416 -0.00703812 0.0234318 0.0116314 -0.00737952 0.0235168 0.011293 -0.00746807 0.0237493 0.0115607 -0.00768906 0.0240667 0.0116358 -0.00703812 0.0234318 0.011304 -0.00711846 0.0235168 0.0110946 -0.00721931 0.0237493 0.0112562 -0.00690911 0.0235168 0.0110238 -0.00690911 0.0237493 0.0110886 -0.00624312 0.023657 0.0110318 -0.00621516 0.023754 0.0109387 -0.00690911 0.0240667 0.010979 -0.00618911 0.0238442 0.0115737 -0.0063 0.0234318 0.0112564 -0.00628973 0.0235167 0.0111384 0.0069104 0.023633 0.0112546 0.00691043 0.0235168 0.0110011 0.00691037 0.0238279 0.0110222 0.00691037 0.0237493 0.0110938 0.0072223 0.0237493 0.0125013 0.00691089 0.0238566 0.0122387 0.00691089 0.0235283 0.012398 0.00691089 0.0236701 0.0120415 0.00691089 0.0234472 0.0124633 0.00724625 0.0240667 0.0121285 0.00758673 0.0240667 0.0119035 0.00760584 0.0237493 0.0115835 0.00760875 0.0237493 0.0113445 0.0075873 0.0240667 0.0110172 0.0072594 0.0240667 0.0110527 0.00730354 0.0240667 0.0112942 0.00747176 0.0237493 0.0113029 0.00712094 0.0235168 0.0116334 0.00738176 0.0235168 0.0121902 0.00746361 0.0237493 0.0118494 0.0073798 0.0235168 0.0123861 0.00721055 0.0237493 0.0121751 0.00711302 0.0235168 0.0113333 0.00691045 0.0234957 0.0115886 0.00698249 0.0234318 0.0116349 0.00704006 0.0234318 0.0114382 0.0072893 0.0235168 0.0120429 0.0072838 0.0235168 0.0118869 0.00697978 0.0234318 0.0110705 0.00623564 0.0236775 0.0111281 0.00625433 0.0236228 0.0115723 0.0063 0.0234318 0.0109373 0.00617111 0.0240667 0.0109776 0.00618826 0.0238442 0.0109882 0.00619368 0.0238252 0.0117387 0.00677477 0.0020955 0.0132387 0.00677477 0.0020955 0.0117387 0.00640289 0.00172362 0.0132387 0.00640289 0.00172362 0.0117387 0.00589489 0.0015875 0.0117387 -0.00690911 0.0026035 0.0132387 -0.00690911 0.0026035 0.0132387 -0.00640111 0.00172362 0.0132387 -0.00589311 0.0015875 0.0117387 -0.00589311 0.0015875 + + + + + + + + + + 0 0.222521 0.974928 0 -0.222521 0.974928 0 -0.222521 0.974928 0 -0.62349 0.781831 0 -0.62349 0.781831 0 -0.900969 0.433884 0 -0.900969 0.433884 0 -1 0 0 -1 0 0 -0.900969 -0.433883 0 -0.900969 -0.433883 0 -0.62349 -0.781831 0 -0.62349 -0.781831 0 -0.222521 -0.974928 0 -0.222521 -0.974928 0 0.222521 -0.974928 0 0.222521 -0.974928 0 0.62349 -0.781831 0 0.62349 -0.781831 0 0.900969 -0.433883 0 0.900969 -0.433883 0 1 0 0 1 0 0 0.900968 0.433885 0 0.900968 0.433885 0 0.62349 0.781831 0 0.62349 0.781831 0 0.222521 0.974928 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 1 0 0 1 0 0 -1 0 0 -1 0 0 -0.987541 0.157364 0 -0.980785 0.19509 -0.00123011 -0.889719 0.456507 0.000933344 -0.889719 0.456509 0.000933344 -0.831468 0.555569 -0.00186539 -0.703767 0.71043 0.00126968 -0.703764 0.710433 0.00126968 -0.555569 0.831468 -0.00190219 -0.152711 0.988271 0 -0.19509 0.980784 -0.00134033 -0.448102 0.893982 0.00100702 -0.448102 0.893982 0.00100702 -0.156435 -0.987688 0 -0.19509 -0.980784 -0.00125285 -0.453991 -0.891006 0.000941315 -0.45399 -0.891006 0.000941315 -0.555569 -0.831469 -0.00188121 -0.707107 -0.707105 0.00125578 -0.707105 -0.707107 0.00125578 -0.831469 -0.555569 -0.00188122 -0.987688 -0.156435 0 -0.980784 -0.19509 -0.00125284 -0.891008 -0.453987 0.000941298 -0.891006 -0.45399 0.000941298 -0.994629 0 0.103502 -0.994629 0 0.103502 -0.950615 0 0.310373 -0.950615 0 0.310373 -0.950616 0 0.310371 -0.950616 0 0.310371 -0.861795 0 0.507256 -0.861795 0 0.507256 -0.732769 0 0.680478 -0.732769 0 0.680478 -0.732773 0 0.680473 -0.732773 0 0.680473 -0.569561 0 0.821949 -0.569561 0 0.821949 -0.379784 0 0.925075 -0.379784 0 0.925075 -0.379778 0 0.925078 -0.379778 0 0.925078 -0.172281 0 0.985048 -0.172281 0 0.985048 -0.851307 -0.155541 0.501082 -0.0597518 -0.987546 0.145545 -0.939046 -0.155541 0.306594 -0.86273 -0.385728 0.326973 -0.875975 -0.345566 0.336528 -0.921211 -0.163567 0.35301 -0.960755 -0.19873 0.193535 -0.944988 -0.108648 0.308535 -0.98907 -0.105632 0.10287 -0.989343 -0.102961 0.102952 -0.86273 -0.385728 0.326973 -0.764971 -0.460523 0.450265 -0.807998 -0.487078 0.331503 -0.615375 -0.651631 0.443499 -0.534616 -0.683893 0.496464 -0.557815 -0.739042 0.377702 -0.423557 -0.844504 0.327737 -0.423571 -0.844502 0.327724 -0.28205 -0.868775 0.407035 -0.294622 -0.922809 0.248238 -0.227011 -0.890946 0.393295 -0.138242 -0.956398 0.257277 -0.133089 -0.985492 0.105323 -0.0522052 -0.99428 0.0931813 -0.0271052 -0.987546 0.154979 -0.0271047 -0.987546 0.15498 -0.0785792 -0.889925 0.449286 -0.078578 -0.889925 0.449288 -0.0271079 -0.987543 0.154996 -0.122178 -0.70503 0.698574 -0.122179 -0.70503 0.698573 -0.0785794 -0.889925 0.449286 -0.337373 -0.838245 0.428398 -0.454303 -0.707059 0.541919 -0.403919 -0.70503 0.582908 -0.40392 -0.70503 0.582908 -0.170186 -0.15553 0.973061 -0.153689 -0.451885 0.878738 -0.15369 -0.451879 0.87874 -0.153688 -0.451877 0.878742 -0.122176 -0.705034 0.69857 -0.615373 -0.651631 0.4435 -0.726694 -0.453896 0.51565 -0.653689 -0.45188 0.607039 -0.65369 -0.451878 0.607038 -0.508094 -0.451878 0.733244 -0.508094 -0.451878 0.733244 -0.170184 -0.155537 0.97306 -0.170183 -0.15554 0.97306 -0.170183 -0.15554 0.97306 -0.170187 -0.155544 0.973058 -0.170187 -0.155545 0.973058 -0.0597517 -0.987546 0.145545 -0.17322 -0.889925 0.421934 -0.173219 -0.889926 0.421933 -0.269331 -0.70503 0.656044 -0.269331 -0.705029 0.656044 -0.338793 -0.451878 0.825243 -0.338791 -0.45188 0.825243 -0.375155 -0.155541 0.913819 -0.375156 -0.15554 0.913819 -0.851307 -0.155541 0.501083 -0.723851 -0.155542 0.672196 -0.723853 -0.155543 0.672193 -0.723855 -0.155542 0.672191 -0.562629 -0.155542 0.811945 -0.562629 -0.155542 0.811946 -0.375162 -0.155542 0.913816 -0.487043 -0.0771409 0.869965 -0.721828 -0.114326 0.682564 -0.146685 -0.884815 0.44225 -0.110866 -0.705602 0.699882 -0.000755622 -0.453249 0.891384 -0.09419 -0.184859 0.978241 -0.113364 -0.156246 0.981191 -0.137204 -0.137203 0.980995 -0.128181 -0.156109 0.979387 -0.178436 -0.0909177 0.979742 -0.160307 -0.155697 0.97471 -0.210211 -0.0332949 0.977089 -0.000756935 -0.453255 0.891381 -0.181679 -0.155324 0.971013 -0.181661 -0.15534 0.971014 -0.889533 -0.140888 0.434605 -0.976649 -0.154686 0.149092 -0.976649 -0.154686 0.149092 -0.88105 -0.448913 0.149093 -0.881048 -0.448916 0.149093 -0.881048 -0.448916 0.149093 -0.699202 -0.699205 0.149094 -0.699202 -0.699205 0.149094 -0.15478 -0.977244 0.145041 -0.159049 -0.975932 0.149196 -0.448917 -0.881048 0.149094 -0.448917 -0.881047 0.149094 -0.448916 -0.881048 0.149095 -0.699204 -0.699202 0.149095 -0.159161 -0.976594 0.144677 -0.155568 -0.886652 0.435485 -0.408874 -0.802458 0.434606 -0.408874 -0.802459 0.434606 -0.636834 -0.636836 0.434606 -0.636834 -0.636835 0.434607 -0.802459 -0.408873 0.434607 -0.802459 -0.408873 0.434606 -0.889532 -0.140889 0.434607 -0.889532 -0.140888 0.434607 -0.146685 -0.884817 0.442247 -0.144235 -0.714446 0.684662 -0.331789 -0.651172 0.682563 -0.331788 -0.651173 0.682562 -0.516773 -0.516774 0.682562 -0.516773 -0.516773 0.682562 -0.651172 -0.331789 0.682562 -0.651172 -0.331787 0.682563 -0.721829 -0.114326 0.682563 -0.72183 -0.114328 0.682561 -0.110866 -0.705606 0.699878 -0.128452 -0.471759 0.872321 -0.223869 -0.439369 0.869964 -0.223869 -0.439369 0.869964 -0.348685 -0.348685 0.869964 -0.348685 -0.348684 0.869965 -0.439369 -0.223868 0.869965 -0.439369 -0.223869 0.869964 -0.487044 -0.0771399 0.869964 -0.487046 -0.077142 0.869963 -0.210328 0 0.977631 -0.210328 0 0.977631 -0.488502 0 0.872563 -0.488502 0 0.872563 -0.488499 0 0.872565 -0.488499 0 0.872565 -0.726595 0 0.687066 -0.726595 0 0.687066 -0.726592 0 0.687069 -0.726592 0 0.687069 -0.898494 0 0.438986 -0.898494 0 0.438986 -0.898495 0 0.438984 -0.898495 0 0.438984 -0.988548 0 0.150909 -0.988548 0 0.150909 -0.801323 0.411151 0.434553 -0.976506 0.155606 0.149071 -0.443096 0.883993 0.149071 -0.151002 0.977212 0.149178 -0.155321 0.977165 0.144994 -0.142914 0.885209 0.442697 -0.107095 0.705773 0.700297 -0.18886 0.155208 0.969661 0.0073249 0.45303 0.891465 0.00732624 0.453024 0.891468 -0.207793 0.154784 0.965849 -0.194322 0.030965 0.980449 -0.487028 0.0776074 0.869931 -0.879778 0.451406 0.149074 -0.879778 0.451406 0.149074 -0.879777 0.451408 0.149072 -0.695904 0.702492 0.149072 -0.976505 0.155609 0.149074 -0.889425 0.141732 0.434552 -0.889424 0.141732 0.434553 -0.889424 0.141731 0.434554 -0.72177 0.115015 0.682509 -0.695901 0.702495 0.149071 -0.695903 0.702493 0.149073 -0.633845 0.639847 0.434553 -0.801323 0.411151 0.434553 -0.650277 0.333651 0.682507 -0.721772 0.115014 0.682507 -0.721773 0.115015 0.682507 -0.113374 0.156236 0.981191 -0.110184 0.219822 0.969298 -0.220991 0.440886 0.869932 -0.127701 0.471858 0.872378 -0.107095 0.70577 0.7003 -0.12788 0.156114 0.979426 -0.130011 0.131241 0.982788 -0.347078 0.350363 0.869933 -0.220991 0.440886 0.869932 -0.327508 0.653392 0.682509 -0.141896 0.714744 0.684841 -0.142913 0.885204 0.442708 -0.16007 0.15571 0.974747 -0.162308 0.0832795 0.98322 -0.438782 0.225138 0.869933 -0.347077 0.350364 0.869933 -0.514367 0.519239 0.682508 -0.327508 0.653392 0.682509 -0.403582 0.805162 0.434554 -0.152352 0.887115 0.435678 -0.155321 0.977162 0.145016 -0.443095 0.883994 0.14907 -0.443097 0.883993 0.149071 -0.403583 0.805161 0.434552 -0.633845 0.639847 0.434553 -0.514368 0.519238 0.682508 -0.650276 0.333652 0.682508 -0.438783 0.225136 0.869933 -0.487026 0.0776077 0.869932 -0.487025 0.0776044 0.869933 -0.170184 0.155537 0.97306 -0.153689 0.451885 0.878738 -0.122178 0.705028 0.698575 -0.0785818 0.889918 0.4493 -0.0271079 0.987543 0.154996 -0.648788 0.611214 0.453312 -0.135119 0.957435 0.255071 -0.0507354 0.994598 0.0905578 -0.323938 0.864142 0.385126 -0.323941 0.86414 0.385128 -0.287187 0.863572 0.414448 -0.648801 0.611194 0.453321 -0.645821 0.645625 0.407534 -0.557433 0.649079 0.517653 -0.790661 0.397832 0.465386 -0.939046 0.155541 0.306594 -0.989342 0.102971 0.102952 -0.98914 0.104956 0.102891 -0.945193 0.106654 0.308602 -0.960999 0.197485 0.193599 -0.937821 0.156142 0.310018 -0.856389 0.391673 0.336438 -0.856392 0.391665 0.336439 -0.0271052 0.987546 0.154979 -0.0271047 0.987546 0.15498 -0.0597518 0.987546 0.145544 -0.0597517 0.987546 0.145545 -0.135935 0.985272 0.103736 -0.135118 0.957435 0.25507 -0.078578 0.889925 0.449288 -0.0785785 0.889925 0.449287 -0.17322 0.889925 0.421934 -0.17322 0.889925 0.421935 -0.286792 0.888115 0.35917 -0.283802 0.875835 0.390345 -0.122179 0.705031 0.698572 -0.122177 0.70503 0.698574 -0.269331 0.70503 0.656045 -0.269331 0.70503 0.656044 -0.403919 0.70503 0.582908 -0.40392 0.70503 0.582907 -0.514177 0.705423 0.487854 -0.5331 0.715441 0.451607 -0.153688 0.451877 0.878742 -0.15369 0.451879 0.87874 -0.338793 0.45188 0.825242 -0.338791 0.451878 0.825243 -0.508094 0.451878 0.733244 -0.508094 0.451878 0.733244 -0.653689 0.451879 0.607039 -0.65369 0.45188 0.607037 -0.752715 0.452986 0.477728 -0.783137 0.47171 0.405198 -0.851307 0.155541 0.501083 -0.851307 0.155542 0.501082 -0.723851 0.155542 0.672196 -0.723853 0.155543 0.672193 -0.723855 0.155542 0.672191 -0.170185 0.155552 0.973057 -0.170183 0.155534 0.973061 -0.170187 0.155543 0.973059 -0.562629 0.155542 0.811946 -0.562629 0.155542 0.811945 -0.375162 0.155542 0.913816 -0.375155 0.155541 0.913819 -0.375156 0.15554 0.913819 -0.170185 0.15554 0.973059 -0.170182 0.155547 0.973059 0.192587 0.98128 0 0.156435 0.987688 -0.00119112 0.549408 0.835553 0.00141474 0.453991 0.891006 0.00069587 0.549738 0.835337 0.000690729 0.453988 0.891003 -0.00292929 0.82447 0.565896 0.00336136 0.707105 0.707108 0.000925966 0.707108 0.707105 0.000925966 0.826814 0.562473 -0.00160392 0.977016 0.213085 0.00586348 0.987688 0.156435 0 0.891006 0.45399 0.000634199 0.891004 0.453994 0.000634199 0.978472 0.206374 -0.00119094 0.999928 0.0112794 0.00415295 0.550055 0 -0.835128 0.55011 0 -0.835092 0.55011 0 -0.835092 0.192586 0 -0.98128 0.192586 0 -0.98128 0.999975 0 -0.00712681 0.999975 0 -0.00712681 0.978232 0 -0.207514 0.978232 0 -0.207514 0.978239 0 -0.207481 0.978239 0 -0.207481 0.826069 0 -0.563569 0.826069 0 -0.563569 0.826028 0 -0.563629 0.826028 0 -0.563629 0.550055 0 -0.835128 0.156435 -0.987688 0 0.192771 -0.981243 -0.000966406 0.453987 -0.891008 0.000742606 0.54969 -0.835368 0.000690708 0.453993 -0.891005 0.000695842 0.550755 -0.834666 -0.00152201 0.707104 -0.707109 0.00105319 0.825606 -0.564247 0.000906085 0.707109 -0.707104 0.000925966 0.826814 -0.562473 -0.0016039 0.891006 -0.45399 0.000885816 0.978117 -0.208057 0.000601568 0.891004 -0.453994 0.000634199 0.978472 -0.206375 -0.00119094 0.987688 -0.156435 0.000193564 0.999975 -0.00712681 0 -0.258822 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.965925 0.707107 0 -0.707107 0.707107 0 -0.707107 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965926 0 0.258819 0.965926 0 0.258819 0.707107 0 0.707107 0.707107 0 0.707107 0.258822 0 0.965925 0 0.0486407 -0.998816 0.258138 -0.0726881 -0.96337 0.40647 0.0364657 -0.912936 0.406454 0.0364657 -0.912943 0.706277 -0.0484431 -0.706277 0.49032 0.0120581 0.871459 0.618581 0.0408834 0.784657 0.723164 0.0921518 0.684501 0.587714 -0.0153866 0.808923 0.743147 0 -0.669129 0.951057 0 -0.309017 0.964792 -0.0484389 -0.258517 0.993861 0.0364655 0.104454 0.985884 0.0364008 0.163427 0.994498 -0.0068902 0.104528 0.901795 0.00401387 0.432146 0.865417 0.0375592 0.499643 0.899072 0.037417 0.4362 0.865204 0.0435304 0.499527 0.830767 0.0204527 0.556244 0.756151 -0.0117298 0.654292 0.292562 0.0478223 0.95505 0.424557 0.116461 0.89788 0.490306 0.0120581 0.871467 0.587782 -0.0015681 0.809018 0.207912 -0.00678081 0.978124 0 0.0486407 -0.998816 -0.104529 0 -0.994522 -0.40618 -0.0524453 -0.912287 -0.258946 0.0130824 -0.965803 -0.406689 0.0132452 -0.913471 -0.706997 -0.0176034 -0.706997 -0.743147 0 -0.669129 -0.951057 0 -0.309017 -0.965776 -0.0176019 -0.258781 -0.994435 0.0132451 0.104514 -0.994434 0.0132451 0.104521 -0.965588 -0.026447 0.258729 -0.865893 0.0176746 0.499918 -0.86589 0.0176746 0.499923 -0.706859 -0.0264476 0.706859 -0.587732 0.0132454 0.808948 -0.258822 0 0.965925 -0.258822 0 0.965925 0.258822 0 0.965925 -0.587732 0.0132454 0.808948 -0.255098 -0.0179174 0.966749 -0.207916 0 0.978147 0.00308301 0 0.999995 0.136578 0.000671397 0.990629 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.172578 0.979943 0.0996383 0 0.979943 -0.199276 -0.172578 0.979943 0.099638 -0.0810526 0.979944 -0.182047 -0.0810532 0.979943 -0.182047 -0.148091 0.979943 -0.133342 -0.148091 0.979943 -0.133342 -0.189523 0.979943 -0.0615807 -0.189523 0.979943 -0.0615803 -0.198185 0.979943 0.0208314 0.198184 0.979944 0.0208313 0.198185 0.979943 0.0208298 0.189523 0.979943 -0.0615809 0.189523 0.979943 -0.0615802 0.148091 0.979943 -0.133342 0.148091 0.979943 -0.133342 0.0810527 0.979943 -0.182048 -0.117132 0.979943 0.161219 -0.117132 0.979943 0.161218 -0.0414305 0.979943 0.194923 -0.0414323 0.979944 0.194921 0.0414304 0.979944 0.194921 0.0414328 0.979943 0.194922 0.117132 0.979943 0.161218 -0.229425 0.825733 -0.515295 -0.229426 0.825733 -0.515295 -0.419179 0.825733 -0.377432 -0.41918 0.825732 -0.377431 -0.536455 0.825732 -0.174306 -0.536456 0.825732 -0.174306 0.560973 0.825732 0.0589597 0.560972 0.825733 0.0589608 0.536456 0.825732 -0.174306 0.536454 0.825733 -0.174303 0.419178 0.825733 -0.377431 0.419179 0.825733 -0.377432 -0.331548 0.825733 0.456334 -0.331548 0.825733 0.456334 -0.117277 0.825733 0.551734 -0.117275 0.825732 0.551737 0.117278 0.825732 0.551737 0.117275 0.825733 0.551735 -0.340472 0.547086 -0.764706 -0.34047 0.547088 -0.764706 -0.622068 0.547088 -0.560112 -0.622066 0.54709 -0.560113 -0.796103 0.547091 -0.258671 -0.796104 0.547091 -0.25867 0.832487 0.547091 0.0874985 0.832488 0.54709 0.0874975 0.796105 0.547091 -0.258668 0.796106 0.547088 -0.258671 0.622067 0.547088 -0.560114 0.622067 0.547088 -0.560114 -0.49202 0.547094 0.677203 -0.492018 0.54709 0.677208 -0.174037 0.547089 0.818782 -0.174036 0.547088 0.818784 0.174037 0.547088 0.818783 0.174036 0.547089 0.818783 -0.172578 0.979943 0.0996388 -0.488492 0.825732 0.282033 -0.488491 0.825733 0.282032 -0.724926 0.54709 0.418538 -0.724926 0.547093 0.418536 -0.850085 0.190981 0.490796 -0.850086 0.190987 0.490792 -0.198184 0.979943 0.0208297 -0.560972 0.825733 0.0589596 -0.560973 0.825732 0.0589609 -0.832488 0.54709 0.0874985 -0.832488 0.547091 0.0874974 -0.976216 0.190985 0.102604 -0.976216 0.190981 0.102607 0 0.190987 -0.981593 -0.399253 0.190987 -0.896728 -0.399251 0.190984 -0.896729 -0.399238 0.190989 -0.896734 -0.729464 0.19099 -0.656815 -0.729468 0.190983 -0.656812 -0.933551 0.190984 -0.303329 -0.933551 0.190983 -0.303329 -0.976217 0.190983 0.1026 0 0.979943 -0.199276 0 0.825733 -0.564061 0 0.825733 -0.564061 0 0.547087 -0.837076 0 0.547087 -0.837076 0 0.190987 -0.981593 0 0.190987 -0.981593 0.0810531 0.979944 -0.182047 0.229426 0.825733 -0.515296 0.229426 0.825733 -0.515295 0.340471 0.547088 -0.764705 0.340471 0.547086 -0.764707 0.399251 0.190984 -0.896729 0.399253 0.190987 -0.896728 0.850088 0.190981 0.490793 0.976216 0.190981 0.102607 0.976216 0.190985 0.102604 0.976217 0.190983 0.1026 0.933551 0.190983 -0.303329 0.933551 0.190984 -0.303329 0.729465 0.190983 -0.656816 0.729467 0.19099 -0.656811 0.399238 0.190989 -0.896734 0.172578 0.979943 0.0996386 0.488491 0.825733 0.282033 0.488492 0.825732 0.282032 0.724925 0.547093 0.418537 0.724927 0.547091 0.418536 0.850085 0.190983 0.490796 0.850084 0.190985 0.490797 0.117133 0.979943 0.161218 0.331548 0.825733 0.456334 0.331548 0.825733 0.456334 0.492022 0.547089 0.677206 0.492017 0.547094 0.677206 0.576965 0.190981 0.794127 0.576964 0.190981 0.794127 -0.850084 0.190983 0.490798 -0.576964 0.190981 0.794127 -0.576965 0.190981 0.794127 -0.576964 0.19098 0.794128 -0.204082 0.190979 0.960144 -0.204089 0.19099 0.960141 0.204083 0.19099 0.960142 0.20409 0.19098 0.960143 0.576964 0.19098 0.794128 0.258822 0 -0.965925 0.231902 -0.0382207 0.971988 0.055465 -0.0152517 0.998344 -0.00929332 -0.0150386 0.999844 0.749971 -0.0950768 0.654602 0.669008 -0.0191313 0.743009 0.780329 0.0115642 0.625262 0.670443 -0.0406397 0.740847 0.577453 0.00587604 0.816403 0.309014 0.00563121 0.951041 0.504667 -0.125923 0.854081 -0.102301 0.205044 0.973392 0.356748 -0.104457 0.928342 0.356737 -0.104451 0.928347 0.900511 -0.0213389 0.434309 0.913172 -0.0286085 0.406568 0.89989 -0.0285864 0.435178 0.912672 -0.0436951 0.40635 0.986075 0.0306031 0.163459 0.998558 -0.0536936 0 0.998558 -0.0536936 0 0.962813 0.0802126 -0.257987 0.912805 -0.0402559 -0.406406 0.912802 -0.0402559 -0.406414 0.706095 0.0534734 -0.706095 0.66913 0 -0.743145 0.309019 0 -0.951056 0.258452 0.0534721 -0.964543 0.258822 0 -0.965925 0.707107 0 -0.707107 0.707107 0 -0.707107 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965926 0 0.258819 0.965926 0 0.258819 0.707107 0 0.707107 0.707107 0 0.707107 0.258822 0 0.965925 0.258822 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.965925 -0.255036 0.0290711 0.966494 -0.104523 -0.0151073 0.994408 -0.706822 0.0283908 0.706822 -0.499908 -0.0189743 0.86587 -0.499908 -0.0189743 0.86587 -0.965753 0.0188961 0.258773 -0.808941 -0.0142185 0.587718 -0.808935 -0.0142185 0.587726 -0.965753 0.018896 -0.258774 -0.978147 0 -0.207914 -0.978147 0 0.207913 -0.499917 -0.0189743 -0.865865 -0.499908 -0.0189743 -0.86587 -0.706822 0.0283908 -0.706822 -0.808935 -0.0142185 -0.587726 -0.808941 -0.0142185 -0.587718 -0.104437 -0.0402581 -0.993716 -0.104442 -0.0402581 -0.993716 -0.156432 0 -0.987689 -0.257949 0.028534 -0.965737 -0.258822 0 -0.965925 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.1743 -0.825734 -0.536454 -0.0996377 -0.979943 -0.172581 -0.161219 -0.979943 0.117134 0.0615825 -0.979943 -0.189526 0.0615789 -0.979943 -0.189525 0.133343 -0.979943 -0.148092 -0.194924 -0.979943 0.0414321 -0.194924 -0.979943 0.0414318 -0.194924 -0.979943 -0.0414329 -0.194923 -0.979943 -0.0414321 -0.161219 -0.979943 -0.117133 -0.0875014 -0.547093 -0.832486 -0.0589628 -0.825734 -0.56097 -0.0589574 -0.82573 -0.560976 -0.0208292 -0.979943 -0.198188 -0.0208332 -0.979943 -0.198185 -0.551737 -0.825732 -0.117275 -0.551737 -0.825732 -0.117275 -0.551737 -0.825732 0.117274 -0.551738 -0.825732 0.117274 -0.456336 -0.825732 0.331549 -0.456334 -0.825733 0.331549 -0.282031 -0.825733 0.488491 -0.099638 -0.979943 0.172581 -0.0208311 -0.979943 0.198187 -0.0589631 -0.825731 0.560974 0.174305 -0.825731 0.536457 0.258668 -0.547092 0.796103 0.560111 -0.547092 0.622066 0.656814 -0.190987 0.729466 0.896731 -0.190985 0.399248 0.0615791 -0.979943 0.189527 0.133343 -0.979943 0.148093 0.377431 -0.825732 0.419182 0.515297 -0.825732 0.229425 0.764703 -0.547092 0.340469 0.837071 -0.547095 0 0.133344 -0.979943 0.148093 0.182051 -0.979943 0.0810536 0.515296 -0.825733 0.229423 0.564063 -0.825732 0 0.837071 -0.547095 0 0.764702 -0.547095 -0.340468 0.199279 -0.979943 0 0.18205 -0.979943 -0.0810544 0.515296 -0.825732 -0.229426 0.377434 -0.825732 -0.419179 0.560116 -0.547086 -0.622066 0.258672 -0.547086 -0.796107 0.30333 -0.190987 -0.93355 -0.102598 -0.190988 -0.976216 -0.818781 -0.54709 -0.174039 -0.81878 -0.547092 -0.174037 -0.81878 -0.547092 0.174038 -0.818782 -0.54709 0.174036 -0.677208 -0.547089 0.492019 -0.677204 -0.547093 0.49202 -0.418536 -0.547092 0.724926 -0.418536 -0.547092 0.724926 -0.0874973 -0.547092 0.832487 -0.490795 -0.190985 0.850085 -0.490796 -0.190983 0.850085 -0.10261 -0.190982 0.976216 -0.102604 -0.19099 0.976215 -0.102598 -0.190988 0.976216 0.303331 -0.190987 0.933549 -0.16122 -0.979943 0.117133 -0.0996395 -0.979943 0.172581 -0.282029 -0.825734 0.488491 -0.0589587 -0.825733 0.560971 -0.0874951 -0.547095 0.832485 0.25867 -0.547095 0.796101 0.30333 -0.190985 0.93355 0.656813 -0.190986 0.729466 0.896729 -0.190985 0.399251 0.896729 -0.190984 0.399251 0.764703 -0.547092 0.340469 0.560111 -0.547091 0.622067 0.377431 -0.825732 0.41918 0.174306 -0.825732 0.536455 0.0615808 -0.979943 0.189525 -0.0208297 -0.979943 0.198186 0.656814 -0.19098 -0.729467 0.896727 -0.190982 -0.399257 0.896729 -0.190984 -0.399251 0.896731 -0.190981 -0.399249 0.981593 -0.190982 0 0.981593 -0.190982 0 0.981593 -0.190982 0 0.182051 -0.979943 0.0810549 0.199279 -0.979943 0 0.564063 -0.825732 0 0.515297 -0.825732 -0.229426 0.764702 -0.547094 -0.340468 0.560106 -0.547096 -0.622067 0.65681 -0.190986 -0.729469 0.303331 -0.190985 -0.93355 -0.102603 -0.190991 -0.976215 -0.102604 -0.19099 -0.976215 -0.0874976 -0.547088 -0.83249 0.258669 -0.547089 -0.796106 0.174304 -0.825732 -0.536456 0.377434 -0.825732 -0.419179 0.133344 -0.979943 -0.148092 0.18205 -0.979943 -0.0810545 -0.490795 -0.190985 -0.850085 -0.0996383 -0.979943 -0.172579 -0.282032 -0.82573 -0.488495 -0.282032 -0.825731 -0.488494 -0.418536 -0.547092 -0.724926 -0.418536 -0.547092 -0.724926 -0.490796 -0.190984 -0.850085 -0.490803 -0.19099 -0.850079 -0.161219 -0.979943 -0.117132 -0.456337 -0.825732 -0.331547 -0.456337 -0.825731 -0.33155 -0.677207 -0.547089 -0.492022 -0.677207 -0.547092 -0.492017 -0.794126 -0.190987 -0.576964 -0.794126 -0.190985 -0.576966 -0.490795 -0.190985 0.850085 -0.794126 -0.190985 0.576966 -0.794126 -0.190987 0.576964 -0.794131 -0.190984 0.576958 -0.960143 -0.190984 0.204085 -0.960142 -0.190985 0.204086 -0.960142 -0.190985 -0.204086 -0.960142 -0.190984 -0.204087 -0.794131 -0.190984 -0.576958 0.00414306 0.591133 0.806563 0 0.00374579 0.999993 0.0041491 0.55556 0.831466 0.00600782 0.589599 0.807674 -0.00757195 0.19509 0.980756 0.0225891 0.371479 0.928167 0.000318925 0.166213 0.98609 0 0.980785 0.19509 0.00634947 0.986866 0.161414 -0.0178978 0.831331 0.55549 0.0292588 0.984659 0.17202 0.0135777 0.938375 0.345352 0.00262831 0.868355 0.495937 0.00265716 0.831469 0.555564 0.00965606 0.865659 0.50054 -0.0123481 0.555526 0.831407 0.0234803 0.735376 0.677252 0.00414377 0.591147 0.806553 0.195003 0.0308853 0.980316 0.175915 0.0896337 0.980316 0.139607 0.139607 0.980316 0.0896333 0.175915 0.980316 0.0308854 0.195003 0.980316 0.0308855 0.195003 0.980316 0.0876542 0.553426 0.828273 0.0876553 0.553428 0.828271 0.0876548 0.55343 0.82827 0.195003 0.0308858 0.980316 0.553429 0.0876555 0.828271 0.553429 0.0876552 0.828271 0.175915 0.0896333 0.980316 0.499255 0.254384 0.828271 0.499254 0.254383 0.828272 0.743658 0.378913 0.550815 0.743659 0.378913 0.550814 0.553429 0.0876551 0.828271 0.824356 0.130566 0.550808 0.824352 0.130562 0.550815 0.824343 0.130564 0.550828 0.969162 0.153501 0.192778 0.130565 0.824355 0.550811 0.130562 0.824352 0.550815 0.130563 0.824346 0.550823 0.1535 0.969162 0.192776 0.153501 0.969162 0.192778 0.445475 0.874294 0.192777 0.0896332 0.175915 0.980316 0.254383 0.499254 0.828272 0.254383 0.499255 0.828272 0.378913 0.743659 0.550814 0.378913 0.743658 0.550816 0.445475 0.874294 0.192776 0.445475 0.874294 0.192776 0.139607 0.139607 0.980316 0.396211 0.39621 0.828272 0.396211 0.39621 0.828272 0.590172 0.590171 0.550814 0.590172 0.590171 0.550814 0.693844 0.693843 0.192779 0.693842 0.693845 0.192776 0.969161 0.1535 0.192779 0.874291 0.445479 0.192779 0.874293 0.445475 0.192777 0.874294 0.445475 0.192778 0.693844 0.693842 0.192778 0.195096 0 0.980784 0.195096 0 0.980784 0.555568 0 0.831471 0.555568 0 0.831471 0.555567 0 0.831472 0.555567 0 0.831472 0.831474 0 0.555564 0.831474 0 0.555564 0.83146 0 0.555584 0.83146 0 0.555584 0.980785 0 0.19509 0.980785 0 0.19509 0.153501 -0.969162 0.192778 0.254382 -0.499256 0.828272 0.0308853 -0.195003 0.980316 0.195003 -0.0308854 0.980316 0.195003 -0.0308857 0.980316 0.0896339 -0.175915 0.980316 0.0896323 -0.175914 0.980316 0.139606 -0.139607 0.980316 0.553429 -0.0876554 0.828271 0.553429 -0.0876552 0.828271 0.553429 -0.0876552 0.828271 0.39621 -0.39621 0.828272 0.590171 -0.590171 0.550814 0.590171 -0.590171 0.550814 0.378913 -0.743659 0.550814 0.0308859 -0.195003 0.980316 0.0876556 -0.553429 0.828271 0.0876553 -0.553429 0.828271 0.0876552 -0.553429 0.828271 0.130566 -0.824356 0.550808 0.175915 -0.0896334 0.980316 0.139607 -0.139607 0.980316 0.396212 -0.396211 0.828271 0.254383 -0.499256 0.828271 0.378912 -0.743658 0.550816 0.130562 -0.824352 0.550815 0.130564 -0.824343 0.550828 0.824356 -0.130566 0.550808 0.824352 -0.130562 0.550815 0.824343 -0.130564 0.550828 0.969161 -0.153501 0.192779 0.969162 -0.153501 0.192778 0.874294 -0.445475 0.192777 0.175915 -0.0896335 0.980316 0.499254 -0.254384 0.828272 0.499256 -0.254383 0.828271 0.743659 -0.378913 0.550814 0.743658 -0.378913 0.550816 0.874294 -0.445475 0.192776 0.874291 -0.445479 0.192778 0.153501 -0.969162 0.192779 0.445471 -0.874295 0.192778 0.445475 -0.874293 0.19278 0.445477 -0.874292 0.192777 0.693843 -0.693843 0.192776 0.69384 -0.693845 0.192783 0.693846 -0.693841 0.192776 0 -0.987367 0.158453 0.00438949 -0.980776 0.195089 0.00634902 -0.986864 0.161429 -0.00764953 -0.831436 0.555568 0.00307215 -0.891612 0.45279 0.00544004 -0.508465 0.861066 0.0104993 -0.674359 0.738329 0.0104994 -0.674359 0.738329 0.0345384 -0.783525 0.6204 0.00307216 -0.891609 0.452796 0.00762824 -0.83145 0.555548 -0.0188579 -0.555468 0.831324 0 -0.00374629 0.999993 0.000154322 -0.0823844 0.996601 0.0109018 -0.304125 0.95257 0.00544003 -0.508434 0.861084 0.00471756 -0.555561 0.831462 -0.00757195 -0.19509 0.980756 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.173649 0.984808 0 -0.173649 0.984808 0 -0.173649 0.984808 0 -0.499999 0.866026 0 -0.499999 0.866026 0 -0.766045 0.642787 0 -0.766045 0.642787 0 -0.939692 0.342021 0 -0.939692 0.342021 0 -1 0 0 -1 0 0 -0.939693 -0.34202 0 -0.939693 -0.34202 0 -0.766044 -0.642788 0 -0.766044 -0.642788 0 -0.499999 -0.866026 0 -0.499999 -0.866026 0 -0.173649 -0.984808 0 -0.173649 -0.984808 0 0.173649 -0.984808 0 0.173649 -0.984808 0 0.499999 -0.866026 0 0.499999 -0.866026 0 0.766044 -0.642788 0 0.766044 -0.642788 0 0.939693 -0.34202 0 0.939693 -0.34202 0 1 0 0 1 0 0 0.939692 0.342021 0 0.939692 0.342021 0 0.766045 0.642787 0 0.766045 0.642787 0 0.499999 0.866026 0 0.499999 0.866026 0 0.173649 0.984808 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.195087 -0.980786 0 -0.195087 -0.980786 0 0.980785 -0.19509 0 0.980785 -0.19509 0 0.831471 -0.555568 0 0.831471 -0.555568 0 0.55557 -0.83147 0 0.55557 -0.83147 0 0.195087 -0.980786 0 0.195087 -0.980786 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.111964 0.993712 0 0.11822 0.992987 0.000194229 0.330278 0.943884 -0.000183414 0.348053 0.937475 0.000119073 0.330281 0.943883 0.00011875 0.532029 0.846721 0.00303742 0.348046 0.937459 -0.00592725 0.707095 0.707095 0.00575872 0.558427 0.829554 -0.000364261 0.707107 0.707107 -0.000373691 0.558415 0.829544 -0.0053958 0.737583 0.675256 0.000646537 0.846724 0.532032 -0.000602982 0.875504 0.483211 0.000272522 0.846724 0.532033 0.000269864 0.875504 0.48321 0.000753712 0.943883 0.330279 -0.000699268 0.963353 0.268236 0.00074496 0.981843 0.189693 0 0.85891 0.474052 0.193774 0.341456 0.919706 0.193775 0.109683 0.162937 0.980521 0.0683626 0.184134 0.980521 0.958099 0.266773 0.104303 0.939013 0.283733 0.194292 0.899768 0.235628 0.367282 0.89977 0.235629 0.367277 0.795079 0.24646 0.554173 0.731445 0.192378 0.654201 0.731438 0.192376 0.654209 0.529042 0.172712 0.830834 0.473429 0.125843 0.871796 0.21315 0.102354 0.971643 0.290532 0.0589116 0.95505 0.206455 0.0748261 0.975591 0.473417 0.125839 0.871803 0.205586 0.190278 0.959963 0.213147 0.10236 0.971643 0.213147 0.102359 0.971643 0.144872 0.13263 0.980521 0.165847 0.103487 0.980707 0.0232204 0.195037 0.980521 0.0232202 0.195037 0.980521 0.0659995 0.554361 0.829655 0.0659988 0.554359 0.829657 0.0659992 0.554358 0.829658 0.0985095 0.827426 0.552867 0.0985092 0.827426 0.552867 0.0985092 0.827425 0.552868 0.11598 0.974166 0.193775 0.115979 0.974167 0.193774 0.0683627 0.184134 0.980521 0.194309 0.523368 0.829657 0.194309 0.523368 0.829657 0.290022 0.781169 0.552867 0.290022 0.781169 0.552867 0.341456 0.919706 0.193774 0.341455 0.919706 0.193774 0.547839 0.813833 0.193774 0.109683 0.162937 0.980521 0.311756 0.463119 0.829656 0.311756 0.463118 0.829657 0.46532 0.69124 0.55287 0.46532 0.691242 0.552867 0.547843 0.81383 0.193774 0.547843 0.81383 0.193774 0.144872 0.132631 0.980521 0.411774 0.376979 0.829656 0.411774 0.376979 0.829656 0.614605 0.562671 0.552867 0.614604 0.562669 0.55287 0.723603 0.662458 0.193774 0.723603 0.662458 0.193774 0.181524 0.100187 0.97827 0.488772 0.269764 0.829656 0.488772 0.269764 0.829656 0.729531 0.402644 0.552867 0.729531 0.402644 0.552867 0.85891 0.474051 0.193776 0.85891 0.474051 0.193776 0.944871 0.159369 -0.286043 0.00602882 0.00141754 -0.999981 0.0100106 0.00112793 -0.999949 0.0240944 0.00948423 -0.999665 0.327064 0.0932126 -0.940394 0.327063 0.0932124 -0.940394 0.194093 0.0928762 -0.976577 0.0240911 0.0094978 -0.999665 0.0255055 0.00892474 -0.999635 0.0879611 0.0663551 -0.993911 0.623433 0.0037606 -0.781868 0.623453 0.00376466 -0.781852 0.496631 0.193646 -0.846085 0.855557 0.294448 -0.425819 0.812647 0.149801 -0.563173 0.812656 0.149803 -0.56316 0.943705 0.31526 -0.100165 0.110603 0.981629 -0.155474 0.110603 0.981629 -0.155473 0.326263 0.932406 -0.155473 0.326261 0.932406 -0.155476 0.326265 0.932405 -0.155473 0.525563 0.836428 -0.155473 0.525562 0.836428 -0.155476 0.698508 0.698508 -0.155476 0.698508 0.698509 -0.155475 0.698508 0.698508 -0.155474 0.836428 0.525563 -0.155474 0.836428 0.525562 -0.155475 0.836427 0.525563 -0.155476 0.932405 0.326263 -0.155476 0.932406 0.326263 -0.155475 0.969769 0.18736 -0.156349 0.944873 0.159369 -0.286036 0.860409 0.232032 -0.453715 0.842096 0.294662 -0.451718 0.842095 0.294663 -0.451719 0.755414 0.474657 -0.451719 0.755414 0.474657 -0.45172 0.630852 0.630853 -0.45172 0.630854 0.630853 -0.451717 0.474659 0.755414 -0.451718 0.474657 0.755414 -0.451719 0.294662 0.842095 -0.451719 0.294663 0.842095 -0.451718 0.0794201 0.704873 -0.704873 0.0794201 0.704873 -0.704873 0.0998903 0.886551 -0.451718 0.0998895 0.886551 -0.451717 0.0998898 0.88655 -0.451719 0.738221 0.172633 -0.652095 0.645269 0.310239 -0.698126 0.669527 0.234279 -0.704874 0.669529 0.234277 -0.704872 0.600611 0.377388 -0.704872 0.600609 0.377389 -0.704873 0.501575 0.501574 -0.704873 0.501574 0.501574 -0.704874 0.377387 0.60061 -0.704874 0.377387 0.60061 -0.704874 0.234278 0.669527 -0.704874 0.234278 0.669527 -0.704874 0.079421 0.704872 -0.704874 0.0510858 0.453393 -0.889845 0.433163 0.327247 -0.839809 0.241364 0.678264 -0.694047 0.464144 0.16241 -0.870743 0.419975 0.173912 -0.890716 0.386332 0.242749 -0.889843 0.386333 0.242748 -0.889843 0.32263 0.32263 -0.889843 0.322629 0.32263 -0.889843 0.242748 0.386332 -0.889843 0.242749 0.386333 -0.889843 0.150696 0.430663 -0.889843 0.150695 0.430663 -0.889843 0.0510823 0.453399 -0.889843 0.0510878 0.453412 -0.889836 0.144218 0.102825 -0.984189 0.118993 0.113002 -0.986444 0.133275 0.0837422 -0.987535 0.133275 0.0837423 -0.987535 0.111299 0.111299 -0.987535 0.111299 0.111299 -0.987535 0.0837425 0.133275 -0.987535 0.0837422 0.133275 -0.987535 0.0519862 0.148568 -0.987535 0.0519864 0.148568 -0.987535 0.0176235 0.156411 -0.987535 0.0176233 0.156411 -0.987535 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.653321 0.757081 0 -0.653321 0.757081 0 -0.931273 0.364322 0 -0.931273 0.364322 0 -0.99362 -0.112779 0 -0.99362 -0.112779 0 -0.825931 -0.563771 0 -0.825931 -0.563771 0 -0.467027 -0.884243 0 -0.467027 -0.884243 0 0 -1 0 0 -1 0 0.467027 -0.884243 0 0.467027 -0.884243 0 0.825931 -0.563771 0 0.825931 -0.563771 0 0.99362 -0.112779 0 0.99362 -0.112779 0 0.931273 0.364322 0 0.931273 0.364322 0 0.653321 0.757081 0 0.653321 0.757081 0 -1 0 0 -1 0 0 0.653324 -0.757078 0 0.653324 -0.757078 0 0.931272 -0.364324 0 0.931272 -0.364324 0 0.99362 0.112779 0 0.99362 0.112779 0 0.825932 0.56377 0 0.825932 0.56377 0 0.467025 0.884244 0 0.467025 0.884244 0 0 1 0 0 1 0 -0.467025 0.884244 0 -0.467025 0.884244 0 -0.825932 0.56377 0 -0.825932 0.56377 0 -0.99362 0.112779 0 -0.99362 0.112779 0 -0.931272 -0.364324 0 -0.931272 -0.364324 0 -0.653324 -0.757078 0 -0.653324 -0.757078 0 1 0 0 1 0 0 0.983186 -0.182605 0 0.983186 -0.182605 0 0.85206 -0.523444 0 0.85206 -0.523444 0 0.607268 -0.794497 0 0.607268 -0.794497 0 0.607268 0.794497 0 0.607268 0.794497 0 0.85206 0.523444 0 0.85206 0.523444 0 0.983186 0.182605 0 0.983186 0.182605 0 -0.983186 0.182605 0 -0.983186 0.182605 0 -0.85206 0.523444 0 -0.85206 0.523444 0 -0.607268 0.794497 0 -0.607268 0.794497 0 -0.607268 -0.794497 0 -0.607268 -0.794497 0 -0.85206 -0.523444 0 -0.85206 -0.523444 0 -0.983186 -0.182605 0 -0.983186 -0.182605 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.999995 0.00305586 0.000202429 0.891002 0.454 -0.000388699 0.865 0.501771 0.00339063 0.987683 0.156429 -0.0155522 0.870867 0.491272 -0.00013705 0.986067 0.166346 -0.000675933 0.707104 0.70711 -0.00290704 0.634531 0.772892 0.00602494 0.89099 0.453983 -0.0162483 0.640912 0.767443 0.000205171 0.864284 0.503004 -0.000253376 0.453992 0.891006 -0.0026588 0.392509 0.919744 0.0101137 0.707065 0.707076 -0.0112793 0.395784 0.918275 -0.000662446 0.633567 0.773687 0 0.156453 0.987685 -0.00712184 0.00791573 0.999943 0.0137262 0.453925 0.890934 -0.00456211 0.147521 0.989048 -0.000247364 0.391993 0.919968 0 0.987689 -0.156432 0.00767814 0.965898 -0.258809 -0.00256891 0.453987 -0.891005 0.00510946 0.707099 -0.707096 0.00510901 0.707096 -0.707099 -0.00256911 0.891003 -0.45399 -0.00256911 0.891002 -0.453993 -0.00256891 0.453984 -0.891006 0.00767762 0.258812 -0.965897 0 0.156442 -0.987687 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0.574752 -0.816793 -0.0500902 0.121347 -0.992386 0.0210803 0.384389 -0.922956 -0.0199322 0.162393 -0.986726 -0.000208074 0.00265603 -0.999996 0 0.121342 -0.992387 0.021081 0.313317 -0.949635 0.00503923 0.313326 -0.949632 0.00503875 0.743579 -0.668515 -0.0133408 0.454442 -0.890776 0.000301921 0.454344 -0.890826 0.000301957 0.612998 -0.790085 0.00031202 0.613007 -0.790077 0.000311811 0.980785 -0.19509 0 0.998684 -0.0482838 -0.0172944 0.831073 -0.555302 0.030946 0.972908 -0.230757 -0.0141789 0.481964 -0.875966 0.019866 0.614079 -0.789229 0.00492468 0.863856 -0.503706 -0.00575439 0.831467 -0.555573 -0.00130467 0.86534 -0.501184 -0.00128746 0.865333 -0.501197 -0.00128688 0.907362 0.420336 -0.00337533 0.831452 0.555556 0.00673521 0.988697 0.149834 -0.00538613 0.980785 0.19509 0 0.458795 0.888538 0.0026718 0.617183 0.786815 -0.00265872 0.747453 0.664225 -0.0109269 0.608052 0.783178 0.13002 0.607047 0.794532 0.0146234 0.831456 0.555565 -0.00529064 0.907362 0.420337 -0.00337478 0.907357 0.420348 -0.00337479 0.458793 0.888539 0.00267185 0.445739 0.895159 0.00267131 0.445743 0.895157 0.00267125 0.00265603 0.999996 0 0.275017 0.961392 0.00952412 0.274318 0.961591 0.00959372 0.448103 0.893936 -0.00907652 0.0831331 0.996519 0.00620974 0.235839 0.971768 -0.00678281 0.0906678 0.995881 -0.000114618 1 0 0 0.000104258 0.258823 -0.965925 -0.00399678 0.373857 -0.927478 -4.33888e-05 0.13762 -0.990485 -0.00281752 0.736331 -0.676616 -8.31357e-05 0.588197 -0.808718 0.000105897 0.393228 -0.919441 -0.00963377 0.862439 -0.506069 0.000511586 0.707106 -0.707107 0.000533054 0.883609 -0.468225 -0.00105425 0.987155 0.159759 0.000630839 0.99988 -0.0155046 0.000611262 0.965926 -0.258818 -0.00944796 0.998733 -0.0494323 -0.00235289 0.966182 -0.25785 -0.00299588 0.712681 0.701482 0.000694229 0.847245 0.531202 0.00066579 0.965926 0.258818 -0.0138768 0.863311 0.504482 -0.00460652 0.948981 0.315299 -0.00360791 0.258406 0.96603 -0.000994694 0.379552 0.92517 0.000548608 0.498123 0.867106 0.000529737 0.707103 0.707111 -0.0143712 0.512033 0.858845 -0.00837058 0.615147 0.788368 -0.000379543 -0.408812 0.912619 -0.00206458 -0.330281 0.94388 -0.00483865 -0.223555 0.974679 -0.0105539 -0.102326 0.994695 -0.00186036 -0.258822 0.965923 0.00046636 0.0229056 0.999738 0.000453113 0.258823 0.965925 -0.0143853 0.0236093 0.999618 -0.0086543 0.142284 0.989788 0.000160328 -0.891683 0.45266 -0.000291466 -0.793706 0.608302 -0.00468577 -0.68308 0.730328 -0.00329333 -0.707099 0.707107 0.000357463 -0.550155 0.835062 0.000357463 -0.550245 0.835003 0.000160329 -0.891641 0.452744 -0.00264326 -0.965923 0.258818 -0.00275869 -0.965176 0.261587 0.000661839 -0.999517 0.0310626 0.000635682 -0.965926 -0.258818 -0.011335 -0.999902 -0.00819918 0.000616507 -0.883789 -0.467885 0.000616507 -0.883784 -0.467894 -0.00274652 -0.972015 -0.234903 1.67282e-05 -0.380328 -0.924852 -3.20123e-05 -0.707106 -0.707107 -0.00490855 -0.597641 -0.801749 -0.000914457 -0.766227 -0.64257 0 0.00294965 -0.999996 -1.41313e-18 -0.00294965 -0.999996 -8.24541e-05 -0.258823 -0.965925 -0.00453646 -0.104804 -0.994483 1.67271e-05 -0.378994 -0.925399 0.000888569 0.997734 0.0672771 -0.00397334 0.228081 -0.973634 -0.00024382 0.603195 -0.797594 4.70786e-05 0.486218 -0.873837 4.5686e-05 0.258823 -0.965925 -0.0189699 0.475101 -0.879727 -0.00973885 0.361233 -0.932425 0.000844352 0.965925 -0.25882 -0.0281395 0.998835 0.0392035 -0.0137448 0.991461 -0.129678 -0.00298971 0.954079 -0.29954 -0.000101076 0.892983 -0.450091 0.000220403 0.80815 -0.588977 0.000217088 0.707109 -0.707104 -0.012447 0.800672 -0.598974 -0.00553858 0.707438 -0.706753 -0.000995643 0.79771 0.60304 0.000899471 0.897174 0.441677 0.000880939 0.965925 0.25882 -0.0183942 0.903319 0.428576 -0.00594149 0.966909 0.255052 -0.000924027 0.369529 0.929219 0.000346937 0.527195 0.849744 0.000337696 0.707109 0.707104 -0.0245263 0.534981 0.844508 -0.00884387 0.672581 0.73997 0.0011716 0.258823 0.965924 -0.0237969 0.0443169 0.998734 -0.0103899 0.210777 0.977479 -0.00149742 -0.386813 0.922157 -0.00773566 -0.234011 0.972203 -0.0054604 -0.258819 0.96591 -0.000942459 -0.0955672 0.995423 0.00120004 0.0435741 0.999049 -0.00165097 -0.769661 0.638451 -0.0110077 -0.661548 0.749822 -0.00597611 -0.707097 0.707092 0.00125368 -0.52967 0.848203 0.00125368 -0.529698 0.848186 -0.00409935 -0.978071 0.208231 -0.0120129 -0.933795 0.357606 -0.00164084 -0.965924 0.25882 0.000191412 -0.859973 0.51034 0.000191412 -0.859992 0.510308 -0.0032219 -0.955828 -0.293908 -0.0134492 -0.990681 -0.135535 -0.00293342 -0.965921 -0.258819 0.00110113 -0.998768 0.0496036 0.00110113 -0.998769 0.0496009 -0.00237511 -0.654185 -0.75633 -0.0107224 -0.784406 -0.620155 -0.00081527 -0.707109 -0.707104 0.000176624 -0.887485 -0.460837 0.000176624 -0.887513 -0.460782 0 0.0960826 -0.995373 6.62169e-19 -0.00495923 -0.999988 -9.18452e-05 -0.0667585 -0.997769 -0.00312212 -0.223792 -0.974632 -0.0103204 -0.359432 -0.933114 -0.0034819 -0.258821 -0.965919 0.000938879 -0.501835 -0.864963 0.000938879 -0.501829 -0.864966 0 -0.168329 -0.985731 0.00731357 -0.258812 -0.9659 -0.00112916 -0.924556 -0.381044 0.00140277 -0.748395 -0.663251 0.00660926 -0.70709 -0.707092 -0.00331922 -0.485898 -0.874009 -0.00331922 -0.485889 -0.874014 0 -0.993632 -0.112676 -0.00112916 -0.924556 -0.381046 0.00784804 -0.965896 -0.25881 0 -0.993632 -0.112676 -0.0112936 -0.148398 0.988863 0.0159516 -0.48583 0.873908 -0.00827668 -0.00791566 0.999934 0 -0.16834 0.985729 -0.00211707 -0.485899 0.874012 -0.00206386 -0.390927 0.920419 -0.00206427 -0.392612 0.919702 -0.00805103 -0.637082 0.770754 -0.00800934 -0.637504 0.770405 0.0289095 -0.924187 0.380844 0.00545393 -0.74838 0.663248 0.00153718 -0.985793 0.16796 -0.00347706 -0.865855 0.500283 0.00200506 -0.924554 0.381045 0.00212007 -0.863844 0.503755 0.00212014 -0.863456 0.50442 0 -0.993632 0.112676 0 -0.993632 0.112676 -0.00338417 -0.999994 -0.00015616 -0.0260913 -0.99966 0 -0.566188 -0.824272 0.00263091 -0.602444 -0.798142 0.00554747 -0.588458 -0.808517 0.0042334 -0.57512 -0.818063 0.00324696 -0.45877 -0.888518 -0.0081151 -0.539422 -0.842034 -0.0013989 -0.624106 -0.78134 0.000818896 -0.512722 -0.858493 0.0102617 -0.501588 -0.86483 0.0218999 -0.539717 -0.841846 0.000437188 -0.540449 -0.841377 0 -0.602129 -0.798399 -0.000148874 -0.662007 -0.749498 -2.54488e-05 -0.624497 -0.781027 -2.56188e-05 -0.656221 -0.754569 0.000310042 -0.999947 0.00953897 0.00389028 -0.996399 -0.0847832 -0.000312432 -0.986327 -0.164799 0.000314099 -0.984001 -0.178161 -0.000245072 -0.986327 -0.164803 -0.00024502 -0.984001 -0.178161 -0.000296065 -0.970956 -0.239258 0.000162803 -0.96814 -0.250408 -0.000122178 -0.950014 -0.312208 0.00023216 -0.946713 -0.322078 -0.000254618 -0.916563 -0.399891 0.000250855 -0.912144 -0.409869 0.000232933 -0.916561 -0.399895 0.000232955 -0.91214 -0.409878 -0.000255004 -0.874853 -0.484388 0.000256898 -0.869666 -0.49364 -0.000219327 -0.874847 -0.484399 -0.000219305 -0.869664 -0.493644 -0.000238347 -0.834793 -0.550564 0.000143575 -0.830986 -0.556294 -4.97795e-05 -0.789988 -0.613122 8.93994e-05 -0.787754 -0.61599 -9.40037e-05 -0.729129 -0.684376 9.3628e-05 -0.750788 -0.660544 0.000287907 -0.72913 -0.684375 0.00028809 -0.750792 -0.660536 0.00171853 -0.662006 -0.749493 -0.00309203 -0.726395 -0.68726 0.00492955 -0.690973 -0.722879 0.00184398 -0.717137 0.696932 -0.000220463 -0.774354 0.632753 0.000358955 -0.997489 -0.0708186 0.000163589 -0.997489 -0.0708172 0.000163589 -0.999954 0.00955637 -0.00031296 -0.999737 0.0229279 0.000289197 -0.99639 0.0848948 -0.000154611 -0.995222 0.0976418 6.57542e-05 -0.99639 0.084893 6.57244e-05 -0.995222 0.0976417 0.000152107 -0.987225 0.159335 -0.000284677 -0.98505 0.172269 0.000308037 -0.967977 0.251037 -0.000305765 -0.964438 0.26431 9.22062e-05 -0.967978 0.251035 9.20995e-05 -0.964438 0.264309 0.000308599 -0.939938 0.341345 -0.00031054 -0.935299 0.353859 0.000291631 -0.911847 0.410531 -0.000151548 -0.906758 0.421652 8.88183e-05 -0.911848 0.410529 8.87981e-05 -0.906755 0.421659 0.000135307 -0.878849 0.477099 -0.000266902 -0.872974 0.487766 0.000291486 -0.830309 0.557304 -0.000286046 -0.823169 0.567797 0.000127292 -0.830308 0.557305 0.000127209 -0.823169 0.567797 0.000289887 -0.766426 0.642333 -0.00038259 -0.44673 0.894477 0.0184978 -0.663828 0.747874 -0.00415162 -0.590605 0.80696 0.000128754 -0.535714 0.844342 0.00983117 -0.554603 0.832077 0.00792282 -0.567999 0.823002 0.00664449 -0.584687 0.811243 0.00509655 -0.605418 0.7959 0.00348016 -0.631312 0.775527 0.00175939 -0.665813 0.746119 0.000424137 -0.700588 0.713566 0.000246129 -0.663833 0.747881 0.000246625 -0.700651 0.713504 -0.000163417 -0.717139 0.69693 -3.56701e-07 -0.700625 0.71353 -4.32799e-07 -0.730776 0.682617 0.000369506 -0.474736 0.880127 0.00168522 -0.513357 0.858167 0.00384975 -0.382534 0.923918 -0.00665659 -0.449018 0.89352 -0.00216809 -0.545271 0.83826 0 -0.543225 0.839587 6.63362e-05 -0.545273 0.838259 6.63472e-05 -0.590602 0.806962 -0.00066033 -0.513102 0.858328 0.000400645 -0.419601 0.907709 0.000349718 -0.419606 0.907706 0.000349717 -0.445017 0.895522 0.000780123 -0.279016 0.953509 0.113888 -0.155355 0.937136 0.312477 -0.321036 0.945227 0.0589982 -0.340039 0.940411 0.000445811 -0.273415 0.961882 0.00519974 -0.38254 0.923934 -0.00298191 -0.24963 0.968339 0.00200705 -0.328569 0.944479 0.00137792 -0.327153 0.944957 0.00520628 -0.32249 0.946516 0.0103992 -0.32329 0.946141 0.0173404 -0.312464 0.948577 0.0506757 -0.294726 0.955582 -0.000154788 -0.204756 0.978813 -4.12545e-05 -0.248887 0.968533 -4.14257e-05 -0.208514 0.978019 0.000331346 -0.132401 0.991196 0.000165207 -0.0999789 0.99499 -0.0001477 -0.204776 0.978808 -0.00107988 -0.149504 0.988758 0.00235156 -0.180691 0.983539 0.00118686 -0.026382 0.999652 0 -0.0636674 0.997971 0.000958287 -0.00663991 0.999977 -0.00113617 -0.0998891 0.994997 0.00168877 -0.0596133 0.998222 0.000353515 -0.0596122 0.998222 0.000353515 -0.314667 -0.949202 9.1354e-05 -0.289053 -0.957313 0.000473288 -0.271233 -0.962513 0.00102089 -0.249224 -0.968444 0.00175718 -0.208913 -0.977926 0.00390742 -0.181169 -0.983434 0.0059782 -0.374018 -0.927366 -0.0100966 -0.0631307 -0.998005 0.000951853 -0.0465537 -0.998916 0.000346453 -0.099576 -0.99503 -0.000147745 -0.139374 -0.99024 0.000474261 -0.149347 -0.988785 0.000257199 -0.139372 -0.99024 0.000257218 -0.149344 -0.988785 0.000172871 -0.23013 -0.97316 -0.000294588 -0.30292 -0.953007 -0.00413584 -0.407339 -0.913276 0.00159966 -0.557761 -0.829999 0.00214125 -0.524031 -0.851699 0.000291884 -0.458784 -0.888548 0.000292705 -0.504497 -0.86341 0.00232081 -0.37403 -0.927411 -0.00333266 -0.467371 -0.884045 0.00538434 -0.435271 -0.900294 0.00307836 -0.381593 -0.92433 0.000681864 -0.360438 -0.932783 0.00023706 -0.344216 -0.938891 6.42185e-05 -0.328701 -0.944433 0.00159621 -0.329004 -0.944328 3.77598e-05 -0.331511 -0.943451 3.77646e-05 -0.335359 -0.94209 4.12138e-05 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.114248 0.993452 0 -0.179574 0.983324 -0.0287744 -0.278553 0.960416 -0.0032346 -0.434472 0.900672 0.00497984 -0.434466 0.900675 0.00497984 -0.515547 0.856398 -0.0281845 -0.579028 0.815275 -0.00730166 -0.86489 0.501961 0 -0.815514 0.578629 -0.011199 -0.710353 0.70134 -0.0593358 -0.785044 0.618961 -0.0243358 -0.704448 0.709708 0.00816262 -0.704449 0.709707 0.00816262 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.077383 0.997001 0 -0.077383 0.997001 0 -0.230298 0.97312 0 -0.230298 0.97312 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.423231 0.906022 0 -0.423231 0.906022 0 -0.637568 0.770394 0 -0.637568 0.770394 0 -0.997394 -0.0721476 0 -0.997394 -0.0721476 0 -0.912537 0.408995 0 -0.97789 0.209122 0 -0.939655 0.342088 0.00497895 -0.912537 0.408995 0 -0.717566 0.69649 0 -0.717566 0.69649 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.912537 -0.408995 0 -0.977788 -0.2091 0.0144303 -0.939666 -0.342092 0 -0.997394 0.0721476 0 -0.997394 0.0721476 0 -0.912537 -0.408995 0 -0.717566 -0.69649 0 -0.717566 -0.69649 0 -0.637568 -0.770394 0 -0.637568 -0.770394 0 -0.423231 -0.906022 0 -0.423231 -0.906022 0 -0.230298 -0.97312 0 -0.230298 -0.97312 0 -0.077383 -0.997001 0 -0.077383 -0.997001 0 0.0250386 0.999686 0 0.0250386 0.999686 0 0.136495 0.990641 0 0.136495 0.990641 0 0.310819 0.950469 0 0.310819 0.950469 0 0.479436 0.877577 0 0.479436 0.877577 0 0.632436 0.774613 0 0.632436 0.774613 0 0.757971 0.652289 0 0.757971 0.652289 0 0.860687 0.509135 0 0.860687 0.509135 0 0.940308 0.340325 0 0.940308 0.340325 0 0.987346 0.158582 0 0.987346 0.158582 0 0.999599 -0.0283042 0 0.999599 -0.0283042 0 0.976637 -0.214894 0 0.976637 -0.214894 0 0.919376 -0.393381 0 0.919376 -0.393381 0 0.82995 -0.557838 0 0.82995 -0.557838 0 0.726046 -0.687646 0 0.726046 -0.687646 0 0.602735 -0.797942 0 0.602735 -0.797942 0 0.444695 -0.895682 0 0.444695 -0.895682 0 0.272445 -0.962171 0 0.272445 -0.962171 0 0.0916504 -0.995791 0 0.0916504 -0.995791 0 -0.927125 -0.374752 0 -0.927125 -0.374752 0 -0.997069 -0.0764523 0.00292177 -0.998397 -0.0562243 0.00655662 -0.999999 -0.00155683 -9.65882e-05 -0.999998 -0.0018618 -9.65882e-05 -0.997943 -0.0640801 0.00167665 -0.999728 -0.0158905 0.0170643 -0.999527 -0.0276489 0.0134475 -0.9992 -0.0385474 0.0106162 -0.999201 -0.0385417 0.0106177 -0.99883 -0.0476336 0.0083485 -0.998003 -0.0629462 0.00520849 -0.998003 -0.0629503 0.00520774 -0.997554 -0.0697896 0.00403313 -0.995182 -0.0980409 0.000845933 -0.995178 -0.0980782 0.000858831 -0.996305 -0.0858102 -0.00347565 -0.996842 -0.0791654 -0.00616009 -0.997322 -0.0725944 -0.00892367 -0.997322 -0.072593 -0.00892437 -0.997723 -0.066333 -0.0121664 -0.998161 -0.0583127 -0.0165399 -0.998512 -0.0496997 -0.0224648 -0.998787 -0.0387105 -0.0304211 -0.998787 -0.0387055 -0.0304248 -0.997915 -0.0640783 -0.00776871 -0.999876 -0.0156904 -0.000980488 -0.997575 0.0687349 -0.0109206 -0.998717 0.0426302 -0.0273459 -0.998391 0.0529902 -0.0201979 -0.998021 0.0610873 -0.0148934 -0.999977 -0.00674834 0 -0.999963 0.00856318 -1.86197e-17 -0.997915 0.0640783 -0.00766989 -0.998823 0.0308113 -0.0374519 -0.998717 0.0426285 -0.0273472 -0.997169 0.0747768 -0.0079373 -0.997169 0.0747684 -0.00794136 -0.996668 0.0814006 -0.00525617 -0.996026 0.0890372 -0.00227787 -0.996026 0.0890327 -0.00227954 -0.994356 0.106033 0.00361863 -0.997273 0.0737205 0.0033595 -0.997704 0.0675867 0.00441117 -0.998147 0.0605824 0.00565036 -0.998147 0.0605829 0.00565028 -0.998543 0.0534927 0.00712575 -0.998967 0.0445202 0.009069 -0.998967 0.0445235 0.00906803 -0.999322 0.0349679 0.0115451 -0.999614 0.0236366 0.0146021 -0.997943 0.0640801 0.00171379 -0.999961 0.00878028 9.92531e-05 -0.999998 -0.0018611 -9.66021e-05 -0.99542 -0.0955995 0 -0.981553 -0.191188 0 -0.981553 -0.191188 0 -0.995435 0.09544 0 -0.981553 0.191188 0 -0.981553 0.191188 0 -0.927125 0.374752 0 -0.927125 0.374752 0 0.00333003 -0.862593 0.505888 0.00320327 -0.024935 0.999684 0.00258224 0.831548 0.555447 0.0020378 0.996372 -0.0850841 -0.00831245 0.300846 -0.953636 -0.0121983 0.258799 -0.965854 -0.00234851 0.59919 -0.800604 0.00291586 0.456402 -0.889769 0.00291586 0.456386 -0.889777 -0.0113185 0.725111 -0.688539 -0.00744372 0.707086 -0.707088 -0.000638027 0.83024 -0.557406 0.0020378 0.996372 -0.0850844 -0.0111983 0.967914 -0.251031 -0.0120062 0.965856 -0.2588 0.00152675 0.911954 -0.410289 0.00152675 0.911961 -0.410274 0.00258224 0.83155 0.555443 -0.00171908 0.912942 0.408086 -0.00924211 0.965885 0.258808 -0.00788966 0.9684 0.249277 -0.00105707 0.996522 0.0833276 0.00320331 -0.0297271 0.999553 -0.00328375 0.138605 0.990342 -0.0107463 0.258804 0.96587 -0.00495278 0.303039 0.952965 -0.000219154 0.458599 0.888643 0.000716294 0.601324 0.799005 0.000709253 0.707106 0.707107 -0.0250478 0.601728 0.798308 -0.00949823 0.726901 0.686677 0.00015166 -0.509874 0.860249 -0.00103819 -0.358636 0.933477 -0.0120437 -0.2588 0.965856 -0.00685685 -0.197017 0.980376 0.00320285 -0.0297262 0.999553 0.00333003 -0.862595 0.505885 -0.00527221 -0.765728 0.643143 -0.0116148 -0.707058 0.70706 -0.00241986 -0.646946 0.762532 0.00015166 -0.509929 0.860216 7.55344e-05 -0.999709 0.0241377 7.55344e-05 -0.999709 0.0241229 -0.00459621 -0.965916 0.258816 -0.0159511 -0.981378 0.191425 -0.004485 -0.935378 0.35362 0.00302218 -0.886281 -0.463139 0.00302218 -0.886281 -0.463137 -0.0109002 -0.965869 -0.258803 -0.0170545 -0.951378 -0.307553 -0.000379366 -0.989567 -0.144073 0.00126206 -0.403525 -0.914968 -0.000474465 -0.55135 -0.834274 -0.00704003 -0.707089 -0.70709 -0.0119977 -0.683763 -0.729606 -0.002657 -0.79625 -0.604962 0 0.136535 -0.990635 -2.53368e-17 -0.1072 -0.994237 -0.0118331 -0.2588 -0.965858 -0.0134717 -0.24433 -0.969599 0.00126206 -0.403555 -0.914955 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 0.980785 0.195091 0 0.980785 0.195091 0 0.83147 0.55557 0 0.83147 0.55557 0 0.55557 0.83147 0 0.55557 0.83147 0 0.195091 0.980785 0 0.195091 0.980785 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.118267 -0.992982 0 0.111964 -0.993712 0.000206712 0.348185 -0.937426 -0.00021776 0.330278 -0.943884 0.000119825 0.348186 -0.937425 0.000120154 0.330281 -0.943883 0.000435445 0.558623 -0.829421 -0.000457506 0.532031 -0.846725 0.00066779 0.707111 -0.707102 -0.000376719 0.558662 -0.829395 -0.000367269 0.707106 -0.707107 -0.000487826 0.737806 -0.675012 0.000650411 0.875711 -0.482835 -0.00100277 0.846724 -0.532032 0.000273598 0.87571 -0.482837 0.000276291 0.846723 -0.532032 0.00125342 0.963491 -0.267737 -0.00127154 0.943883 -0.330279 0.00135584 0.981897 -0.189418 0 0.126633 0 0.99195 0.126633 0 0.99195 0.376144 0 0.926561 0.376144 0 0.926561 0.376139 0 0.926563 0.376139 0 0.926563 0.604392 0 0.796687 0.604392 0 0.796687 0.790931 0 0.611905 0.790931 0 0.611905 0.790957 0 0.611872 0.790957 0 0.611872 0.922975 0 0.384861 0.922975 0 0.384861 0.922977 0 0.384856 0.922977 0 0.384856 0.991342 0 0.131305 0.991342 0 0.131305 0.116025 -0.974161 0.193773 0.0232298 -0.195037 0.980521 0.0683889 -0.184125 0.980521 0.109723 -0.162911 0.980521 0.144917 -0.132583 0.980521 0.165873 -0.103442 0.980707 0.271998 -0.0657782 0.960047 0.207411 -0.0229788 0.977984 0.265824 -0.830032 0.490291 0.270231 -0.0661414 0.960521 0.472876 -0.125283 0.872177 0.529108 -0.172502 0.830835 0.731055 -0.191791 0.654808 0.731057 -0.191791 0.654807 0.795198 -0.24607 0.554175 0.899619 -0.235077 0.368001 0.899619 -0.235077 0.368001 0.939168 -0.283224 0.194287 0.958198 -0.266266 0.104689 0.209097 -0.109871 0.971703 0.209113 -0.109844 0.971703 0.209102 -0.10987 0.971702 0.12195 -0.11255 0.986134 0.0683892 -0.184125 0.980521 0.194384 -0.523343 0.829654 0.194384 -0.523343 0.829655 0.290132 -0.781128 0.552868 0.290133 -0.781128 0.552867 0.0232294 -0.195037 0.980521 0.0660259 -0.55436 0.829654 0.0660256 -0.554359 0.829654 0.0660263 -0.554357 0.829656 0.0985494 -0.827421 0.552868 0.0985479 -0.827423 0.552865 0.098548 -0.827422 0.552866 0.859114 -0.473684 0.193772 0.209201 -0.115346 0.971046 0.48889 -0.269556 0.829654 0.488889 -0.269556 0.829655 0.729703 -0.402333 0.552867 0.729703 -0.402333 0.552867 0.859113 -0.473685 0.19377 0.859113 -0.473686 0.193771 0.144917 -0.132583 0.980521 0.411901 -0.376844 0.829654 0.411901 -0.376844 0.829654 0.614793 -0.562467 0.552865 0.614792 -0.562467 0.552867 0.723822 -0.662219 0.193773 0.723822 -0.662218 0.193773 0.109722 -0.162911 0.980521 0.311866 -0.463047 0.829655 0.311867 -0.463047 0.829654 0.465484 -0.691132 0.552867 0.465485 -0.691132 0.552865 0.548036 -0.8137 0.193775 0.548073 -0.813675 0.193775 0.116025 -0.974162 0.193772 0.341586 -0.919658 0.193771 0.341587 -0.919658 0.193773 0.341587 -0.919658 0.193772 0.548036 -0.813701 0.193772 0 -0.980785 0.19509 -0.00231874 -0.965923 0.258819 0.00155132 -0.831468 0.55557 0.00155132 -0.83147 0.555568 -0.00309611 -0.707105 0.707102 0 -0.19509 0.980785 -0.00231872 -0.258818 0.965923 0.00155141 -0.555572 0.831467 0.00155141 -0.555568 0.83147 -0.0449689 -0.964949 0.258558 -0.00641367 0.965906 0.258814 -0.00171976 0.258818 0.965925 -0.00470064 0.7071 0.707098 -0.00642123 0.965905 0.258816 -0.0575865 0.964277 0.258562 -0.0575861 0.964276 0.258563 -0.057585 0.964276 0.258564 -0.127893 0.957445 0.258733 -0.197812 0.945525 0.25856 -0.197813 0.945525 0.258559 -0.127891 0.957446 0.258731 -0.197793 0.945528 0.258561 -0.284704 0.923088 0.258558 -0.284704 0.923088 0.258558 -0.369534 0.892521 0.258556 -0.369534 0.89252 0.258557 -0.369534 0.89252 0.258557 -0.433729 0.863096 0.258737 -0.433727 0.863098 0.258734 -0.495654 0.829141 0.258557 -0.495654 0.82914 0.258559 -0.57052 0.779522 0.258558 -0.570521 0.779521 0.258558 -0.570522 0.779521 0.258555 -0.641262 0.722451 0.25855 -0.641262 0.72245 0.258552 -0.641261 0.722451 0.258553 -0.692719 0.673198 0.258736 -0.692717 0.673201 0.258735 -0.692718 0.673201 0.258733 -0.740365 0.620491 0.258554 -0.740365 0.620491 0.258555 -0.795178 0.54849 0.258556 -0.795178 0.54849 0.258556 -0.795178 0.54849 0.258556 -0.843292 0.471181 0.258547 -0.843292 0.471182 0.258545 -0.875879 0.407301 0.258733 -0.87588 0.407296 0.258735 -0.875881 0.407295 0.258734 -0.903496 0.341827 0.258555 -0.903496 0.341827 0.258554 -0.931645 0.255322 0.258551 -0.931645 0.255322 0.258551 -0.931644 0.255323 0.258551 -0.951556 0.166412 0.25855 -0.951556 0.166412 0.258549 -0.961335 0.0943171 0.258725 -0.961335 0.094317 0.258725 -0.961335 0.0943172 0.258725 -0.965743 0.0221482 0.258554 -0.965742 0.0221472 0.258557 -0.963572 -0.0684092 0.258552 -0.963572 -0.0684099 0.258552 -0.963572 -0.0684106 0.258551 -0.95279 -0.159195 0.258548 -0.95279 -0.159196 0.25855 -0.95279 -0.159199 0.258549 -0.937897 -0.231112 0.258719 -0.937898 -0.231112 0.258719 -0.917711 -0.301592 0.25855 -0.917711 -0.301592 0.258552 -0.885397 -0.386294 0.258554 -0.885395 -0.386297 0.258555 -0.885395 -0.386297 0.258553 -0.845107 -0.467918 0.258549 -0.845105 -0.467919 0.258552 -0.8451 -0.467928 0.258551 -0.806373 -0.53182 0.25871 -0.806372 -0.53182 0.258711 -0.763125 -0.592274 0.258556 -0.763126 -0.592273 0.258555 -0.704336 -0.661105 0.258556 -0.704337 -0.661104 0.258556 -0.704337 -0.661104 0.258557 -0.639498 -0.724012 0.258552 -0.639498 -0.724011 0.258553 -0.639488 -0.72402 0.258553 -0.58163 -0.771217 0.258711 -0.581629 -0.771217 0.258712 -0.52108 -0.813402 0.258561 -0.52108 -0.813402 0.25856 -0.443184 -0.858334 0.258556 -0.443184 -0.858334 0.258557 -0.443184 -0.858334 0.258556 -0.361314 -0.89588 0.258556 -0.361312 -0.89588 0.25856 -0.361318 -0.895877 0.25856 -0.292609 -0.920567 0.258719 -0.292611 -0.920567 0.258717 -0.222304 -0.940068 0.258561 -0.222302 -0.940067 0.258564 -0.134633 -0.956567 0.258562 -0.134636 -0.956566 0.258561 -0.134635 -0.956568 0.258558 -0.0449708 -0.96495 0.258554 -0.00469833 0.707101 0.707097 -0.042176 0.70623 0.706725 -0.0421777 0.706227 0.706728 -0.0936379 0.701011 0.706977 -0.0936373 0.701012 0.706976 -0.144877 0.692497 0.706724 -0.144878 0.692495 0.706726 -0.208516 0.676066 0.706722 -0.208516 0.676066 0.706722 -0.270646 0.653681 0.706719 -0.270646 0.653682 0.706719 -0.317559 0.631928 0.706982 -0.317558 0.63193 0.70698 -0.363016 0.60726 0.706721 -0.363016 0.607256 0.706724 -0.417847 0.570918 0.706723 -0.417847 0.570924 0.706718 -0.469665 0.529127 0.70671 -0.469665 0.529125 0.706712 -0.507183 0.492895 0.70698 -0.507183 0.492894 0.70698 -0.542243 0.454448 0.706718 -0.542243 0.454449 0.706717 -0.582388 0.401713 0.706719 -0.582388 0.401714 0.706718 -0.617636 0.345099 0.706706 -0.617637 0.3451 0.706704 -0.641289 0.298208 0.70698 -0.64129 0.298209 0.706979 -0.661721 0.250354 0.706716 -0.661722 0.250356 0.706715 -0.682342 0.186999 0.706712 -0.68234 0.186998 0.706713 -0.696926 0.121881 0.70671 -0.696927 0.121882 0.706709 -0.703867 0.0690567 0.706967 -0.703867 0.0690561 0.706968 -0.707311 0.0162206 0.706717 -0.707307 0.0162184 0.70672 -0.705724 -0.0501037 0.706713 -0.705726 -0.0501024 0.706711 -0.697832 -0.116596 0.706708 -0.697829 -0.116598 0.70671 -0.686712 -0.169216 0.70696 -0.686713 -0.169216 0.706959 -0.672136 -0.220888 0.706712 -0.672133 -0.220889 0.706715 -0.648463 -0.282923 0.706718 -0.648465 -0.282923 0.706716 -0.618962 -0.342708 0.706709 -0.618959 -0.342708 0.706712 -0.590423 -0.389397 0.706945 -0.590423 -0.389397 0.706945 -0.558913 -0.433781 0.706718 -0.558916 -0.433781 0.706716 -0.515856 -0.484193 0.706717 -0.51585 -0.484192 0.706723 -0.46837 -0.530268 0.706715 -0.468373 -0.530269 0.706712 -0.425867 -0.564683 0.706944 -0.425865 -0.564683 0.706946 -0.381636 -0.59573 0.706725 -0.381636 -0.59573 0.706724 -0.324587 -0.628642 0.706719 -0.324585 -0.628641 0.706721 -0.264624 -0.65614 0.706721 -0.264622 -0.656139 0.706722 -0.214246 -0.674027 0.706956 -0.214248 -0.674028 0.706954 -0.162813 -0.688499 0.706725 -0.162809 -0.688496 0.70673 -0.0986067 -0.700581 0.706727 -0.0986089 -0.700584 0.706724 -0.0329352 -0.706728 0.706718 -0.0329324 -0.706724 0.706722 -0.00172096 0.258818 0.965925 -0.0154453 0.258617 0.965856 -0.0154462 0.258615 0.965857 -0.0342789 0.256627 0.965902 -0.0342787 0.256627 0.965902 -0.0530536 0.253588 0.965856 -0.0530539 0.253587 0.965856 -0.0763579 0.247573 0.965856 -0.0763579 0.247573 0.965856 -0.09911 0.239377 0.965855 -0.0991101 0.239376 0.965855 -0.116251 0.231336 0.965903 -0.116251 0.231337 0.965903 -0.132936 0.222376 0.965856 -0.132935 0.222375 0.965856 -0.153013 0.209069 0.965856 -0.153014 0.209072 0.965855 -0.171993 0.193767 0.965853 -0.171992 0.193765 0.965854 -0.185669 0.180439 0.965903 -0.18567 0.18044 0.965903 -0.198569 0.166418 0.965855 -0.198569 0.166419 0.965855 -0.213269 0.147107 0.965855 -0.213269 0.147106 0.965855 -0.22618 0.126376 0.965853 -0.22618 0.126377 0.965853 -0.234763 0.109168 0.965903 -0.234763 0.109169 0.965903 -0.242321 0.0916796 0.965855 -0.242322 0.0916809 0.965854 -0.249874 0.0684789 0.965854 -0.249873 0.0684778 0.965854 -0.255215 0.0446332 0.965854 -0.255215 0.0446337 0.965854 -0.257676 0.0252805 0.965901 -0.257676 0.0252808 0.965901 -0.259016 0.00593917 0.965855 -0.259015 0.00593825 0.965855 -0.258437 -0.0183475 0.965854 -0.258438 -0.0183469 0.965854 -0.255548 -0.0426986 0.965853 -0.255546 -0.0426993 0.965854 -0.251399 -0.0619481 0.965899 -0.251398 -0.0619482 0.965899 -0.246136 -0.0808898 0.965854 -0.246135 -0.08089 0.965854 -0.237466 -0.103606 0.965855 -0.237467 -0.103606 0.965855 -0.226664 -0.125501 0.965853 -0.226663 -0.125501 0.965854 -0.216152 -0.142557 0.965896 -0.216152 -0.142557 0.965896 -0.204673 -0.158849 0.965855 -0.204674 -0.158849 0.965855 -0.188905 -0.177311 0.965855 -0.188901 -0.17731 0.965856 -0.171517 -0.194183 0.965854 -0.171519 -0.194184 0.965854 -0.155908 -0.206729 0.965896 -0.155907 -0.206728 0.965897 -0.139753 -0.218153 0.965856 -0.139754 -0.218153 0.965856 -0.118863 -0.230207 0.965855 -0.118861 -0.230206 0.965856 -0.0969039 -0.240276 0.965856 -0.0969035 -0.240276 0.965856 -0.0784342 -0.246755 0.965899 -0.0784347 -0.246755 0.965898 -0.05962 -0.252125 0.965856 -0.0596181 -0.252122 0.965857 -0.0361098 -0.256548 0.965857 -0.0361112 -0.25655 0.965856 -0.0120599 -0.258802 0.965855 -0.0120584 -0.2588 0.965856 0 0.19509 0.980785 -0.00231872 0.258818 0.965923 0.00155141 0.555572 0.831467 0.00155141 0.555568 0.83147 -0.00309611 0.707105 0.707102 0 0.980785 0.19509 -0.00231874 0.965923 0.258819 0.00155132 0.831468 0.55557 0.00155132 0.83147 0.555568 0.769476 0.552233 0.320852 0.612513 0.788924 0.0492718 0.213575 0.972388 0.0940656 0.127893 0.991754 0.0081496 0.147513 0.981973 0.11819 0.260216 0.927699 0.267698 0.116437 0.972784 0.200335 0.116435 0.972784 0.200336 0.260217 0.927698 0.267699 0.332089 0.82873 0.45047 0.354919 0.819281 0.450345 0.369033 0.193462 0.909058 0.12465 0.176276 0.976416 0.124627 0.176943 0.976299 0.123888 0.178443 0.97612 0.115472 0.186005 0.97574 0.369103 0.192588 0.909216 0.19568 0.315195 0.928634 0.379286 0.201059 0.903171 0.335433 0.540321 0.771711 0.259948 0.559587 0.78695 0.302097 0.697355 0.649949 0.302098 0.697353 0.649951 0.604373 0.790128 0.102133 0.604373 0.790128 0.102133 0.972613 0.193464 0.128825 0.972613 0.193465 0.128825 0.905539 0.193465 0.377585 0.905539 0.193464 0.377587 0.905537 0.193466 0.37759 0.776013 0.193467 0.600312 0.826471 0.552234 0.109467 0.580831 0.810381 0.0769315 0.612162 0.789115 0.0505584 0.213575 0.972387 0.0940647 0.263555 0.956686 0.123658 0.506969 0.830231 0.231731 0.499988 0.840563 0.208483 0.769474 0.552234 0.320853 0.826471 0.552234 0.109467 0.826474 0.55223 0.109468 0.43727 0.708797 0.553535 0.512663 0.552893 0.656875 0.497833 0.567036 0.656226 0.592972 0.193465 0.781636 0.592974 0.193463 0.781635 0.157329 0.980018 0.121707 0.442075 0.829227 0.341983 0.442075 0.829227 0.341983 0.659412 0.552233 0.510113 0.659412 0.552233 0.510113 0.776012 0.193465 0.600314 0.775988 0.193466 0.600344 0.826471 -0.552234 0.109467 0.336517 -0.510992 0.790977 0.121158 -0.183974 0.975436 0.124627 -0.176943 0.976299 0.12465 -0.176276 0.976416 0.294321 -0.567656 0.768858 0.348598 -0.672343 0.653019 0.40625 -0.757413 0.511161 0.315788 -0.835119 0.450392 0.199271 -0.872574 0.445989 0.21935 -0.960546 0.170987 0.16552 -0.958688 0.231344 0.0621745 -0.996819 0.0498686 0.262268 -0.956985 0.124081 0.219515 -0.970463 0.100071 0.189592 -0.970847 0.146666 0.157758 -0.98227 0.101287 0.129494 -0.991466 0.0150262 0.559628 -0.826931 0.0547934 0.587134 -0.805745 0.0777664 0.613373 -0.788322 0.048199 0.121158 -0.183974 0.975436 0.368004 -0.206919 0.906509 0.378143 -0.200211 0.903838 0.369033 -0.193462 0.909058 0.592973 -0.193463 0.781636 0.592974 -0.193465 0.781635 0.775988 -0.193466 0.600344 0.776012 -0.193465 0.600314 0.776013 -0.193467 0.600312 0.905538 -0.193466 0.377587 0.972613 -0.193464 0.128825 0.972613 -0.193465 0.128824 0.905539 -0.193465 0.377585 0.905538 -0.193461 0.37759 0.826474 -0.55223 0.109468 0.826471 -0.552234 0.109467 0.769475 -0.552234 0.320852 0.769475 -0.552233 0.320853 0.659412 -0.552233 0.510113 0.659412 -0.552233 0.510113 0.503875 -0.552233 0.66419 0.507355 -0.5666 0.649273 0.374427 -0.568365 0.732643 0.348596 -0.672343 0.653021 0.605127 -0.789518 0.102384 0.605127 -0.789518 0.102383 0.497994 -0.841952 0.207652 0.505507 -0.830366 0.234424 0.442075 -0.829226 0.341984 0.442075 -0.829227 0.341983 0.400459 -0.831395 0.385248 0.219361 -0.960546 0.170976 -0.236796 -0.00254769 -0.971556 -0.0010818 0 -0.999999 -0.0010818 0 -0.999999 -0.226752 -0.00274927 -0.973949 -0.111954 0.0141382 -0.993613 -0.133726 0.0354124 -0.990385 -0.0505372 0.000383102 -0.998722 -0.368658 0.0118872 -0.929489 -0.330015 0.0399919 -0.943128 -0.293211 0.0110706 -0.955984 -0.226752 -0.00274927 -0.973949 -0.438808 -0.00427353 -0.898571 -0.438801 -0.00427353 -0.898574 -0.531829 0.0276131 -0.846401 -0.494701 0.0852122 -0.864875 -0.540623 0.0377899 -0.840416 -0.788829 0.00975623 -0.614536 -0.726417 0.0197022 -0.686972 -0.63918 0.0152425 -0.768906 -0.717241 0.0248802 -0.696381 -0.668125 0.00487386 -0.744033 -0.691681 0.000412107 -0.722203 -0.760341 -0.013129 -0.649392 -0.702297 0.0336727 -0.711087 -0.717216 0.0248948 -0.696406 -0.739664 0.0134441 -0.672842 -0.739736 0.0134103 -0.672764 -0.756179 0.00641586 -0.654334 -0.736423 -0.00398709 -0.67651 -0.724206 -0.00538622 -0.689563 -0.972063 0.0695689 0.224175 -0.709934 -0.00350931 -0.70426 -0.709923 -0.0035103 -0.704271 -0.741618 0.00576919 -0.670798 -0.690189 -0.00429896 -0.723616 -0.672893 4.61647e-05 -0.73974 -0.663899 0.000498896 -0.747822 -0.572823 0.0122775 -0.819587 -0.607934 -0.000371744 -0.793987 -0.639255 -0.0003715 -0.768995 -0.610872 0.00877437 -0.791681 -0.666572 -0.0080533 -0.745397 -0.640853 0.00571979 -0.767642 -0.654566 0.00226892 -0.756002 -0.678286 -3.72306e-05 -0.734798 -0.682829 0.000128596 -0.730579 -0.713449 0.00148098 -0.700705 -0.712472 0.00127514 -0.701699 -0.695648 -0.00239691 -0.718379 -0.688826 -0.00392522 -0.724916 -0.683675 -0.00529321 -0.729768 -0.678638 -0.00669418 -0.734442 -0.701156 0.0126914 -0.712894 -0.611981 -0.000618393 -0.790872 -0.645925 0.00179466 -0.763399 -0.621956 -0.000272096 -0.783052 -0.645872 -5.18439e-05 -0.763446 -0.675757 0.00357246 -0.737116 -0.666914 -0.0105357 -0.74506 -0.652654 -0.0166964 -0.757472 -0.723893 0.022304 -0.689552 -0.723891 0.0223036 -0.689553 -0.690195 -0.00429803 -0.723611 -0.757002 0.00438522 -0.653398 -0.756937 0.00437669 -0.653473 -0.783003 -0.00566018 -0.621992 -0.783093 -0.00564629 -0.621879 -0.763371 -0.00942279 -0.645892 -0.763299 -0.00944411 -0.645976 -0.755291 -0.0118547 -0.655283 -0.744078 -0.0153779 -0.667915 -0.703773 0.000856813 -0.710424 -0.760404 0.00223703 -0.649446 -0.712842 -0.0322346 -0.700584 -0.730873 -0.022088 -0.682156 -0.680462 -0.00270214 -0.732778 -0.651442 -0.0115348 -0.758611 -0.649395 -0.0126889 -0.760345 -0.382682 0.00552283 -0.923864 -0.426566 0.00142919 -0.904455 -0.522489 -0.00564197 -0.852627 -0.534245 -0.0148339 -0.845199 -0.649419 0.00956432 -0.760371 -0.649418 0.00956432 -0.760372 -0.318436 0.0433002 -0.946955 -0.320789 0.0410758 -0.946259 -0.331253 0.0327888 -0.942972 -0.331251 0.0327899 -0.942973 -0.349088 0.0236233 -0.936792 -0.374693 0.0130848 -0.927057 -0.374695 0.0130843 -0.927056 -0.405179 0.00748673 -0.914207 -0.426792 0.00551589 -0.904333 -0.0857021 0.0639539 -0.994266 -0.0781533 0.0882287 -0.99303 -0.0269205 0 -0.999638 -0.118891 0.0160222 -0.992778 -0.14617 -0.00382782 -0.989252 -0.233101 -0.0542947 -0.970936 -0.176945 0.0620542 -0.982263 -0.205756 0.0384812 -0.977846 -0.231768 0.0267292 -0.972404 -0.231751 0.0267345 -0.972408 -0.233364 0.0267345 -0.972022 -0.232486 0.0274545 -0.972212 -0.380972 -0.0944623 -0.919748 -0.308339 0.0590494 -0.949442 -0.316241 0.0463693 -0.947545 -0.233445 -0.00254773 -0.972367 -0.23671 -0.00284158 -0.971576 -0.0784585 0.00419078 -0.996909 -0.137542 -0.0103732 -0.990442 -0.0471804 -0.000115144 -0.998886 -0.651501 -0.012921 -0.758538 -0.618214 -0.0110666 -0.785932 -0.649409 -0.0110764 -0.760359 -0.618763 -0.00292565 -0.785572 -0.522472 0.00984522 -0.8526 -0.486094 -0.0118656 -0.873826 -0.575251 -0.0425042 -0.816872 -0.541153 -0.020798 -0.840667 -0.38176 0.0695885 -0.921638 -0.536672 -0.0347982 -0.843073 -0.507218 -0.0181224 -0.861627 -0.47254 -0.00814715 -0.881272 -0.47257 -0.00815408 -0.881255 -0.452605 -0.00538223 -0.891695 -0.431528 0.00116541 -0.902099 -0.434479 -0.00388477 -0.900674 -0.392287 -0.00114936 -0.919842 -0.382683 -0.00115011 -0.923879 -0.44341 -0.0137162 -0.896214 -0.233401 0.019827 -0.972178 -0.3672 -0.0187268 -0.929953 -0.305964 -0.00869573 -0.952003 -0.44776 0.00216561 -0.894151 -0.460076 0.00318928 -0.887874 -0.478827 0.00592767 -0.877889 -0.478823 0.00592685 -0.877892 -0.496661 0.010594 -0.86788 -0.444116 -0.00691306 -0.895943 -0.528692 0.00479516 -0.8488 -0.565419 0.0186583 -0.824593 -0.50798 -0.00458738 -0.861357 -0.569165 0.00211379 -0.822221 -0.559284 -0.000855256 -0.828976 -0.611867 0.000914045 -0.79096 -0.595537 -0.00319627 -0.803321 -0.622078 -0.000618235 -0.782955 -0.825022 -0.00670758 -0.56506 -0.838123 -0.00947972 -0.545399 -0.903348 -0.000516433 -0.428909 -0.892412 0.000218676 -0.451222 -0.852639 -0.00148218 -0.522498 -0.879718 -0.0124036 -0.475334 -0.760164 0.0251442 -0.649245 -0.865141 -0.0185419 -0.501186 -0.850875 -0.0133183 -0.525199 -0.8145 -0.00501424 -0.580142 -0.806772 -0.00413773 -0.590849 -0.800519 -0.00351848 -0.599297 -0.745492 -0.000473017 -0.666514 -0.771632 0 -0.63607 -0.771632 0 -0.63607 -0.752425 0 -0.658678 -0.78677 -0.00244034 -0.617242 -0.791346 0.00277333 -0.611362 -0.800357 0.00352408 -0.599514 -0.807223 0.00415618 -0.590232 -0.813166 0.00489433 -0.582011 -0.821218 0.00600412 -0.570583 -0.829615 0.00765858 -0.558283 -0.909404 0.0329113 -0.41461 -0.97201 -0.0272209 -0.233359 -0.894002 0.0156647 -0.447789 -0.923877 0.00210128 -0.382684 -0.893685 0.00209565 -0.44869 -0.923882 -0.00141958 -0.382676 -0.880897 0.000266577 -0.473308 -0.852637 0.0027937 -0.522496 -0.866341 0.00753628 -0.499396 -0.760315 -0.0153271 -0.649374 -0.851763 0.0136456 -0.523749 -0.840125 0.00998965 -0.542301 -0.921577 0.0246359 -0.387414 -0.931486 0.0186001 -0.3633 -0.939185 0.0141936 -0.343119 -0.945286 0.0111237 -0.326052 -0.950145 0.0087935 -0.311684 -0.95516 0.00659833 -0.296018 -0.960211 -0.00438319 -0.279243 -0.954218 -0.00697971 -0.299029 -0.94983 -0.00897744 -0.312638 -0.94503 -0.0112017 -0.326792 -0.939963 -0.0138635 -0.340995 -0.933402 -0.0174057 -0.35841 -0.926036 -0.0219626 -0.376795 -0.916735 -0.0278054 -0.398528 -0.972091 0.0239427 -0.233378 -0.904225 -0.0112834 -0.426908 -0.923877 -0.00211472 -0.382684 -0.923881 -0.00211472 -0.382675 -0.964001 0.00260509 -0.265887 -0.969512 0 -0.245046 -0.97237 0 -0.233446 -0.97237 0 -0.233446 -0.996917 0 -0.0784587 -0.996917 0 -0.0784587 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.619099 -0.716453 0.321575 -0.679662 -0.716053 -0.159143 -0.640892 -0.716113 -0.276478 -0.58199 -0.716236 -0.38509 -0.504823 -0.716422 -0.481553 -0.411843 -0.716674 -0.562818 -0.306 -0.716987 -0.626333 -0.190649 -0.717364 -0.670106 -0.0694485 -0.717801 -0.692776 0.053761 -0.718306 -0.693647 0.175089 -0.71887 -0.672733 0.290707 -0.719492 -0.630731 0.396969 -0.720179 -0.568998 0.490535 -0.720925 -0.489532 0.568484 -0.72173 -0.394882 -0.290944 -0.948691 0.123845 0.139519 -0.989782 -0.0294423 0.0855798 -0.995395 -0.0431937 0.288526 -0.956096 -0.0513061 0.199929 -0.979633 -0.0186194 0.199934 -0.979632 -0.01862 0.521824 -0.832256 -0.187213 0.470574 -0.878181 -0.0857778 0.392528 -0.91844 -0.0488869 0.725209 -0.662602 -0.187166 0.646302 -0.751549 -0.132165 -0.537076 -0.735133 0.413678 -0.545524 -0.716773 0.434327 -0.466125 -0.771529 0.432979 -0.403767 -0.827406 0.390347 -0.285071 -0.891986 0.350851 -0.346905 -0.86844 0.354216 -0.420095 -0.854436 0.30571 -0.13174 -0.974847 0.179772 -0.131746 -0.974845 0.17978 -0.16785 -0.962612 0.212612 -0.214557 -0.948013 0.235025 -0.210352 -0.949068 0.234569 -0.239804 -0.920127 0.309615 -0.239803 -0.920127 0.309614 -0.0668175 -0.99429 0.0832 -0.0929576 -0.995221 0.0299035 -0.0880257 -0.994826 0.0507163 -0.0884078 -0.993672 0.0692858 -0.0898688 -0.991828 0.0905591 -0.101427 -0.986368 0.129582 -0.115112 -0.981347 0.153975 -0.0937789 -0.994252 -0.0516544 -0.101552 -0.994252 -0.0339109 -0.299925 -0.948691 -0.100153 -0.0985106 -0.994252 0.0419327 -0.0985107 -0.994252 0.0419326 -0.104454 -0.994252 0.0234956 -0.0829363 -0.994252 -0.0677072 -0.093779 -0.994252 -0.0516546 -0.276969 -0.948691 -0.152558 -0.299925 -0.948691 -0.100154 -0.484376 -0.859778 -0.161747 -0.426142 -0.859777 0.281401 -0.263866 -0.948691 0.174243 -0.263866 -0.948691 0.174243 -0.0893423 -0.994252 0.0589969 -0.0893422 -0.994252 0.0589969 -0.403772 -0.827402 0.390352 -0.368069 -0.859752 0.35405 -0.36905 -0.859291 0.354149 -0.228149 -0.948691 0.218937 -0.22815 -0.948691 0.218937 -0.0772492 -0.994252 0.0741297 -0.0772492 -0.994252 0.0741297 0.566732 -0.819914 -0.0809621 0.504729 -0.860381 -0.0706557 0.490386 -0.859778 -0.142491 -0.510259 -0.859777 0.0204591 0.699988 -0.689997 -0.184179 0.655099 -0.720639 -0.226991 0.668404 -0.723518 -0.172505 0.644152 -0.741643 -0.187171 0.628387 -0.722595 -0.288072 0.628388 -0.722595 -0.288071 0.568486 -0.72173 -0.394879 0.599005 -0.742529 -0.299738 0.456684 -0.859778 -0.228522 0.490386 -0.859778 -0.142491 0.303646 -0.948691 -0.0882303 0.313594 -0.948823 -0.0373403 0.353474 -0.925437 -0.136468 0.490534 -0.720925 -0.489533 0.53446 -0.743352 -0.402219 0.408031 -0.859778 -0.307072 0.456684 -0.859778 -0.228522 0.282778 -0.948691 -0.1415 0.303647 -0.948691 -0.0882301 0.102812 -0.994252 -0.0298738 0.102329 -0.994225 -0.0323417 0.0230774 -0.99973 -0.00266502 0.396963 -0.720178 -0.569002 0.452665 -0.74411 -0.491319 0.346022 -0.859777 -0.375569 0.408032 -0.859777 -0.307072 0.252653 -0.948691 -0.190138 0.282778 -0.948691 -0.1415 0.0957459 -0.994252 -0.0479106 0.102812 -0.994252 -0.0298739 0.290703 -0.719492 -0.630732 0.356312 -0.744804 -0.564188 0.272685 -0.859777 -0.431772 0.346022 -0.859777 -0.37557 0.214256 -0.948691 -0.232552 0.252652 -0.948691 -0.190138 0.0855454 -0.994252 -0.0643788 0.0957456 -0.994252 -0.0479107 0.175095 -0.71887 -0.672732 0.248554 -0.745435 -0.618505 0.190418 -0.859778 -0.473838 0.272682 -0.859778 -0.431771 0.168844 -0.948691 -0.267352 0.214255 -0.948691 -0.232551 0.0725446 -0.994252 -0.0787396 0.0855454 -0.994252 -0.0643788 0.0537604 -0.718306 -0.693647 0.132909 -0.746006 -0.652542 0.10192 -0.859777 -0.500396 0.19042 -0.859777 -0.47384 0.117907 -0.948691 -0.293399 0.168845 -0.948691 -0.267352 0.0571692 -0.994252 -0.0905228 0.0725449 -0.994252 -0.0787396 -0.0694546 -0.717801 -0.692776 0.0131436 -0.746512 -0.665243 0.0100876 -0.859778 -0.510569 0.101919 -0.859778 -0.500395 0.063108 -0.948691 -0.309843 0.117907 -0.948691 -0.293399 0.0399224 -0.994252 -0.0993425 0.0571694 -0.994252 -0.0905228 -0.190656 -0.717364 -0.670105 -0.106865 -0.746959 -0.656225 -0.0820799 -0.859778 -0.504029 0.0100876 -0.859778 -0.510569 0.00624621 -0.948691 -0.316144 0.0631092 -0.948691 -0.309844 0.0213682 -0.994252 -0.10491 0.0399225 -0.994252 -0.0993425 -0.306001 -0.716987 -0.626333 -0.223213 -0.747344 -0.625822 -0.171556 -0.859777 -0.480991 -0.082079 -0.859777 -0.504031 -0.050823 -0.948691 -0.312094 0.00624529 -0.948691 -0.316143 0.0021146 -0.994252 -0.107043 0.0213681 -0.994252 -0.10491 -0.411845 -0.716674 -0.562817 -0.332146 -0.747669 -0.575039 -0.255418 -0.859778 -0.442202 -0.171557 -0.859778 -0.480988 -0.106228 -0.948691 -0.297827 -0.0508227 -0.948691 -0.312094 -0.0172081 -0.994252 -0.105672 0.00211471 -0.994252 -0.107043 -0.504826 -0.716422 -0.48155 -0.430132 -0.747933 -0.505552 -0.330919 -0.859777 -0.388942 -0.255418 -0.859777 -0.442205 -0.158154 -0.948691 -0.273812 -0.106228 -0.948691 -0.297828 -0.0359676 -0.994252 -0.100841 -0.0172086 -0.994252 -0.105672 -0.58199 -0.716236 -0.385089 -0.514009 -0.748138 -0.419624 -0.395586 -0.859778 -0.322947 -0.330919 -0.859778 -0.388941 -0.204904 -0.948691 -0.240832 -0.158154 -0.948691 -0.273811 -0.0535496 -0.994252 -0.0927101 -0.0359674 -0.994252 -0.100842 -0.640892 -0.716113 -0.276477 -0.581065 -0.748282 -0.320058 -0.447302 -0.859778 -0.24638 -0.395586 -0.859778 -0.322947 -0.244946 -0.948691 -0.199968 -0.204904 -0.948691 -0.240831 -0.0693786 -0.994252 -0.0815433 -0.0535496 -0.994252 -0.0927099 -0.679663 -0.716053 -0.159142 -0.629133 -0.748368 -0.210086 -0.484376 -0.859778 -0.161747 -0.447302 -0.859778 -0.246379 -0.276969 -0.948691 -0.152558 -0.244946 -0.948691 -0.199968 -0.0829363 -0.994252 -0.0677073 -0.0693786 -0.994252 -0.0815435 -0.313062 -0.948691 -0.0444706 -0.505594 -0.859777 -0.0718198 -0.505593 -0.859778 -0.0718196 -0.69256 -0.71462 -0.0983782 -0.632584 -0.773771 -0.0333928 -0.666296 -0.716258 0.207422 -0.682255 -0.714827 0.153464 -0.49822 -0.859778 0.112068 -0.510258 -0.859778 0.0204595 -0.315951 -0.948691 0.0126684 -0.313062 -0.948691 -0.0444704 -0.106 -0.994252 -0.0150573 -0.101552 -0.994252 -0.0339111 -0.609813 -0.769473 0.189838 -0.692566 -0.716126 0.0866938 -0.698881 -0.714688 0.0280221 -0.631168 -0.771612 0.0790076 -0.69707 -0.716058 -0.0367964 -0.6191 -0.716453 0.321574 -0.610558 -0.748114 0.259893 -0.469872 -0.859778 0.200008 -0.49822 -0.859778 0.112068 -0.308497 -0.948691 0.0693924 -0.315951 -0.948691 0.012668 -0.106978 -0.994252 0.00428927 -0.106 -0.994252 -0.0150572 -0.55248 -0.716713 0.425544 -0.553934 -0.747901 0.36579 -0.42614 -0.859778 0.281401 -0.469871 -0.859778 0.200008 -0.290944 -0.948691 0.123845 -0.308497 -0.948691 0.0693925 -0.104454 -0.994252 0.0234956 -0.106978 -0.994252 0.00428929 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.628408 0.722576 -0.288076 0.568505 0.721704 -0.3949 0.490562 0.72089 -0.489557 0.39699 0.72014 -0.569032 0.290729 0.719451 -0.630767 0.175106 0.718822 -0.67278 0.0537659 0.718256 -0.693699 -0.0694548 0.717756 -0.692822 -0.19066 0.717317 -0.670153 -0.306017 0.716945 -0.626374 -0.411866 0.716636 -0.56285 -0.504845 0.716391 -0.481576 -0.697062 0.716066 -0.0367997 -0.692544 0.716148 0.0866869 -0.666261 0.716295 0.207406 0.303641 0.948691 -0.088249 0.725209 0.662602 -0.187167 -0.115082 0.981276 0.154446 -0.100132 0.986914 0.126391 -0.0893352 0.99216 0.0873912 -0.0879622 0.994633 0.0544813 -0.234965 0.942088 0.239295 -0.200616 0.952748 0.22809 -0.171317 0.961481 0.214954 -0.13469 0.973779 0.18334 -0.134696 0.973776 0.183349 -0.436742 0.852564 0.287038 -0.359599 0.865125 0.349638 -0.302286 0.885133 0.353784 -0.256312 0.907816 0.331924 -0.54888 0.718434 0.427297 -0.521985 0.734672 0.433346 -0.479047 0.761883 0.435946 0.566724 0.819918 -0.0809832 0.673177 0.724024 -0.150407 0.582138 0.760051 -0.288857 0.699988 0.689997 -0.184176 0.470573 0.878181 -0.0857802 0.199927 0.979634 -0.0186249 0.288526 0.956096 -0.0513072 0.306438 0.94898 -0.074385 0.392527 0.91844 -0.0488984 0.392524 0.918441 -0.0488978 0.0855808 0.995395 -0.0431866 0.139519 0.989782 -0.0294416 0.199932 0.979633 -0.0186255 0.0230773 0.99973 -0.00266547 0.102329 0.994225 -0.0323386 0.10281 0.994252 -0.0298802 0.10281 0.994252 -0.0298803 0.0957411 0.994252 -0.0479208 -0.425051 0.831019 0.358802 -0.367528 0.860266 0.353362 -0.227941 0.948691 0.219155 -0.192184 0.948912 0.250263 -0.293088 0.926119 0.237495 0.0855361 0.994252 -0.0643921 0.0957411 0.994252 -0.0479208 0.282764 0.948691 -0.14153 0.303642 0.948691 -0.0882492 0.490379 0.859777 -0.142522 0.493269 0.860242 -0.129113 0.566721 0.81992 -0.0809827 -0.416405 0.81501 0.402946 -0.366898 0.8597 0.355389 -0.425885 0.859777 0.281788 -0.104435 0.994252 0.0235813 -0.106975 0.994252 0.00437243 -0.315942 0.948691 0.0129136 -0.313096 0.948691 -0.0442417 -0.505647 0.859777 -0.07145 -0.484489 0.859777 -0.161415 -0.619053 0.716507 0.321545 -0.619052 0.716507 0.321547 -0.55365 0.747849 0.366325 -0.552426 0.716783 0.425497 -0.552427 0.716783 0.425496 -0.666261 0.716296 0.207407 -0.610369 0.748079 0.260437 -0.469699 0.859777 0.200415 -0.425885 0.859777 0.281789 -0.263708 0.94869 0.174484 -0.227941 0.94869 0.219156 -0.0771785 0.994252 0.0742041 -0.08545 0.994087 0.067007 -0.0143689 0.999736 0.0179089 -0.692544 0.716148 0.0866867 -0.647129 0.748247 0.146121 -0.498129 0.859777 0.112477 -0.469699 0.859777 0.200415 -0.290837 0.948691 0.124097 -0.263708 0.948691 0.174483 -0.0892888 0.994252 0.0590781 -0.0771785 0.994252 0.0742037 -0.697062 0.716066 -0.0368001 -0.662747 0.748353 0.0270883 -0.510244 0.859777 0.020855 -0.498129 0.859777 0.112478 -0.30844 0.948691 0.0696459 -0.290837 0.948691 0.124097 -0.0984747 0.994252 0.042018 -0.0892889 0.994252 0.0590785 -0.679665 0.71605 -0.159146 -0.656724 0.748399 -0.0927983 -0.505646 0.859777 -0.0714502 -0.510243 0.859777 0.0208545 -0.315942 0.948691 0.0129131 -0.30844 0.948691 0.0696456 -0.104435 0.994252 0.0235814 -0.0984746 0.994252 0.0420178 -0.582007 0.716213 -0.385105 -0.612788 0.714779 -0.33702 -0.447461 0.859777 -0.246093 -0.484488 0.859777 -0.161415 -0.299994 0.948691 -0.0999478 -0.313095 0.948691 -0.0442418 -0.106011 0.994252 -0.0149799 -0.106975 0.994252 0.0043724 -0.531979 0.770126 -0.352 -0.640905 0.716098 -0.276486 -0.663612 0.714659 -0.221092 -0.583298 0.772297 -0.251634 -0.679665 0.71605 -0.159147 -0.504845 0.716391 -0.481576 -0.51423 0.748172 -0.419292 -0.39578 0.859777 -0.322711 -0.447462 0.859777 -0.246093 -0.277068 0.948691 -0.15238 -0.299994 0.948691 -0.0999476 -0.101575 0.994252 -0.0338413 -0.106011 0.994252 -0.0149798 -0.411865 0.716636 -0.56285 -0.430382 0.747973 -0.50528 -0.331133 0.859778 -0.388759 -0.395778 0.859778 -0.322711 -0.245065 0.948691 -0.199822 -0.277067 0.948691 -0.152381 -0.0938121 0.994252 -0.0515946 -0.101575 0.994252 -0.0338414 -0.306015 0.716945 -0.626374 -0.33241 0.747715 -0.574827 -0.255642 0.859777 -0.442074 -0.331133 0.859777 -0.388759 -0.205038 0.94869 -0.24072 -0.245067 0.94869 -0.199822 -0.0829772 0.994252 -0.0676578 -0.0938125 0.994252 -0.0515945 -0.190664 0.717317 -0.670152 -0.223488 0.747392 -0.625666 -0.171781 0.859777 -0.48091 -0.255643 0.859777 -0.442074 -0.158294 0.948691 -0.273732 -0.205037 0.948691 -0.24072 -0.0694235 0.994252 -0.0815052 -0.0829767 0.994252 -0.0676578 -0.0694555 0.717756 -0.692822 -0.107127 0.747009 -0.656126 -0.0822887 0.859777 -0.503996 -0.171781 0.859777 -0.48091 -0.106367 0.94869 -0.297779 -0.158294 0.94869 -0.273732 -0.0535968 0.994252 -0.0926828 -0.0694235 0.994252 -0.0815052 0.0537678 0.718256 -0.693698 0.0128912 0.746565 -0.665187 0.0098948 0.859776 -0.510575 -0.0822896 0.859776 -0.503997 -0.0509534 0.948691 -0.312073 -0.106365 0.948691 -0.297779 -0.0360143 0.994252 -0.100825 -0.0535967 0.994252 -0.0926828 0.175103 0.718822 -0.672781 0.132684 0.746056 -0.65253 0.101756 0.859777 -0.500429 0.00989524 0.859777 -0.510574 0.0061271 0.948691 -0.316146 -0.0509536 0.948691 -0.312073 -0.0172524 0.994252 -0.105665 -0.0360146 0.994252 -0.100825 0.290725 0.719451 -0.630769 0.248359 0.745486 -0.618521 0.190285 0.859778 -0.473892 0.101757 0.859778 -0.500428 0.063008 0.948691 -0.309865 0.0061265 0.948691 -0.316147 0.00207437 0.994252 -0.107044 -0.0172525 0.994252 -0.105665 0.39699 0.72014 -0.569032 0.356147 0.744852 -0.56423 0.27258 0.859776 -0.431838 0.190284 0.859776 -0.473895 0.117823 0.948691 -0.293434 0.0630082 0.948691 -0.309865 0.0213339 0.994252 -0.104917 0.00207484 0.994252 -0.107044 0.490561 0.72089 -0.489558 0.452535 0.744154 -0.491372 0.345948 0.859777 -0.375637 0.272581 0.859777 -0.431836 0.168781 0.948691 -0.267392 0.117824 0.948691 -0.293434 0.0398941 0.994252 -0.0993542 0.0213334 0.994252 -0.104918 0.568507 0.721704 -0.394897 0.534368 0.743389 -0.402273 0.407986 0.859777 -0.307133 0.345948 0.859777 -0.375637 0.214211 0.94869 -0.232595 0.168781 0.94869 -0.267394 0.0571475 0.994252 -0.0905368 0.0398942 0.994252 -0.099354 0.628407 0.722576 -0.288078 0.598941 0.742561 -0.299787 0.45666 0.859777 -0.228571 0.407986 0.859777 -0.307133 0.252624 0.948691 -0.190176 0.214211 0.948691 -0.232593 0.0725296 0.994252 -0.0787537 0.0571476 0.994252 -0.0905363 0.668413 0.723509 -0.172507 0.644118 0.741665 -0.187203 0.490378 0.859777 -0.142521 0.45666 0.859778 -0.22857 0.282764 0.948691 -0.141531 0.252624 0.948691 -0.190177 0.085536 0.994252 -0.0643919 0.0725296 0.994252 -0.078754 -0.00319071 0.529057 -0.84858 -0.00319368 0.555569 -0.831464 -0.00216778 0.530078 -0.847946 0.00366536 0.195089 -0.980779 -0.0113827 0.321281 -0.946916 0 0.112138 -0.993693 0 0.980785 -0.19509 -0.0232955 0.999657 -0.0119406 0.0445041 0.830646 -0.555019 -0.0315739 0.993759 -0.10699 -0.0200831 0.976602 -0.214115 -0.0102701 0.947359 -0.320009 -0.00634096 0.907058 -0.420957 -0.00394461 0.850609 -0.525784 -0.00394892 0.831463 -0.555567 -0.0065612 0.849432 -0.527658 0.0109487 0.555539 -0.831418 -0.022805 0.769914 -0.63774 -0.0108972 0.688299 -0.725345 -0.0436824 0.830675 -0.555041 -0.0652984 0.554386 -0.829694 -0.0769606 0.194512 -0.977876 -0.0769607 0.194512 -0.977876 -0.228987 0.194512 -0.953798 -0.228987 0.194512 -0.953798 -0.228988 0.194509 -0.953798 -0.375374 0.19451 -0.906234 -0.375376 0.194513 -0.906233 -0.375379 0.194512 -0.906232 -0.512517 0.194512 -0.836356 -0.512518 0.194509 -0.836356 -0.637045 0.19451 -0.745882 -0.637045 0.19451 -0.745882 -0.637043 0.194513 -0.745883 -0.745882 0.194513 -0.637043 -0.745882 0.194513 -0.637043 -0.74588 0.194515 -0.637045 -0.836354 0.194514 -0.512519 -0.836355 0.194514 -0.512519 -0.906236 0.194513 -0.375367 -0.906234 0.194511 -0.375374 -0.906233 0.194513 -0.375375 -0.953798 0.194512 -0.228987 -0.977877 0.194511 -0.0769601 -0.977876 0.194512 -0.0769606 -0.953798 0.194513 -0.228987 -0.953798 0.194512 -0.228986 -0.829695 0.554385 -0.0652984 -0.829695 0.554385 -0.0652982 -0.809265 0.554384 -0.194287 -0.809265 0.554384 -0.194287 -0.768909 0.554384 -0.318493 -0.768909 0.554384 -0.318493 -0.709619 0.554384 -0.434855 -0.709621 0.554383 -0.434855 -0.632857 0.554382 -0.540511 -0.632854 0.554386 -0.540511 -0.54051 0.554386 -0.632855 -0.540511 0.554385 -0.632855 -0.434853 0.554385 -0.70962 -0.434853 0.554385 -0.70962 -0.318494 0.554385 -0.768908 -0.318494 0.554384 -0.768908 -0.194288 0.554384 -0.809266 -0.194286 0.554386 -0.809265 -0.0652984 0.554386 -0.829694 -0.0652979 0.554387 -0.829694 -0.55504 0.830676 -0.0436825 -0.55504 0.830676 -0.0436824 -0.541373 0.830676 -0.129972 -0.541373 0.830676 -0.129972 -0.514376 0.830676 -0.213062 -0.514376 0.830676 -0.213062 -0.474714 0.830675 -0.290904 -0.47471 0.830677 -0.290904 -0.423358 0.830678 -0.361584 -0.423361 0.830676 -0.361584 -0.361585 0.830676 -0.42336 -0.361583 0.830677 -0.423359 -0.290902 0.830677 -0.474712 -0.290906 0.830675 -0.474714 -0.213063 0.830675 -0.514376 -0.213062 0.830676 -0.514375 -0.129971 0.830676 -0.541373 -0.129971 0.830676 -0.541373 -0.0436827 0.830676 -0.55504 -0.0436826 0.830676 -0.555039 -0.195068 0.98067 -0.0153521 -0.195068 0.98067 -0.0153521 -0.190264 0.98067 -0.0456784 -0.190264 0.98067 -0.0456783 -0.180776 0.98067 -0.07488 -0.180776 0.98067 -0.07488 -0.166836 0.98067 -0.102238 -0.166837 0.98067 -0.102238 -0.14879 0.98067 -0.127078 -0.14879 0.98067 -0.127078 -0.127078 0.98067 -0.14879 -0.127078 0.98067 -0.148789 -0.102238 0.98067 -0.166836 -0.102238 0.98067 -0.166837 -0.0748803 0.98067 -0.180777 -0.0748795 0.98067 -0.180776 -0.045678 0.98067 -0.190264 -0.045678 0.98067 -0.190264 -0.0153521 0.98067 -0.195067 -0.0153523 0.98067 -0.195067 0 -0.99697 -0.0777808 -0.0059477 -0.980768 -0.195087 -0.0072312 -0.983907 -0.178534 -0.000837552 -0.960416 -0.278567 -0.00103602 -0.776543 -0.630064 -0.0083191 -0.862185 -0.506526 -0.00195494 -0.831468 -0.55557 0.000153468 -0.922424 -0.386179 0.000153468 -0.92241 -0.386212 -0.00507258 -0.555565 -0.831458 0.00110165 -0.660157 -0.751127 0.00110165 -0.66016 -0.751124 0 -0.0854438 -0.996343 -0.00745602 -0.26914 -0.963072 -6.33437e-05 -0.195091 -0.980785 3.54882e-05 -0.479954 -0.877294 3.54882e-05 -0.479915 -0.877315 -0.228987 -0.194512 -0.953798 -0.474713 -0.830675 -0.290906 -0.195068 -0.98067 -0.0153521 -0.190264 -0.98067 -0.0456783 -0.0748798 -0.98067 -0.180777 -0.045678 -0.98067 -0.190264 -0.0153523 -0.98067 -0.195067 -0.166836 -0.98067 -0.102237 -0.166837 -0.98067 -0.102238 -0.14879 -0.98067 -0.127078 -0.361584 -0.830677 -0.423359 -0.768909 -0.554384 -0.318493 -0.514376 -0.830676 -0.213062 -0.514376 -0.830676 -0.213062 -0.180776 -0.98067 -0.0748798 -0.180776 -0.98067 -0.0748802 -0.540511 -0.554385 -0.632855 -0.540511 -0.554386 -0.632854 -0.632856 -0.554386 -0.540509 -0.102238 -0.98067 -0.166836 -0.127078 -0.98067 -0.148789 -0.361584 -0.830676 -0.423361 -0.42336 -0.830676 -0.361585 -0.632856 -0.554382 -0.540512 -0.70962 -0.554383 -0.434856 -0.836355 -0.194514 -0.512519 -0.906236 -0.194513 -0.375367 -0.0153522 -0.98067 -0.195067 -0.0436827 -0.830676 -0.55504 -0.0436824 -0.830676 -0.55504 -0.065298 -0.554386 -0.829694 -0.0652984 -0.554386 -0.829694 -0.0769606 -0.194512 -0.977876 -0.0769607 -0.194512 -0.977876 -0.045678 -0.98067 -0.190264 -0.129971 -0.830676 -0.541373 -0.129971 -0.830676 -0.541373 -0.194286 -0.554384 -0.809266 -0.194287 -0.554386 -0.809265 -0.228987 -0.194509 -0.953798 -0.228988 -0.194513 -0.953797 -0.375379 -0.194512 -0.906232 -0.0748799 -0.98067 -0.180776 -0.213062 -0.830675 -0.514377 -0.213063 -0.830676 -0.514375 -0.318494 -0.554385 -0.768908 -0.318494 -0.554384 -0.768909 -0.375376 -0.194513 -0.906233 -0.375374 -0.19451 -0.906234 -0.102238 -0.98067 -0.166837 -0.290904 -0.830677 -0.474711 -0.290904 -0.830675 -0.474714 -0.434853 -0.554385 -0.709619 -0.434853 -0.554385 -0.70962 -0.512517 -0.194509 -0.836357 -0.512518 -0.194512 -0.836356 -0.836355 -0.194514 -0.512519 -0.74588 -0.194515 -0.637045 -0.745882 -0.194513 -0.637043 -0.745882 -0.194513 -0.637043 -0.637045 -0.194513 -0.745881 -0.637044 -0.194508 -0.745883 -0.637045 -0.19451 -0.745882 -0.906233 -0.194513 -0.375375 -0.906234 -0.194511 -0.375374 -0.768909 -0.554384 -0.318492 -0.70962 -0.554384 -0.434854 -0.474711 -0.830677 -0.290903 -0.423359 -0.830678 -0.361582 -0.14879 -0.98067 -0.127078 -0.127078 -0.98067 -0.14879 -0.953798 -0.194513 -0.228987 -0.190264 -0.98067 -0.0456784 -0.541373 -0.830676 -0.129972 -0.541373 -0.830676 -0.129972 -0.809265 -0.554384 -0.194287 -0.809265 -0.554384 -0.194287 -0.953798 -0.194512 -0.228987 -0.953798 -0.194512 -0.228986 -0.195068 -0.98067 -0.0153521 -0.55504 -0.830676 -0.0436824 -0.55504 -0.830676 -0.0436825 -0.829695 -0.554385 -0.0652982 -0.829695 -0.554385 -0.0652985 -0.977877 -0.194511 -0.0769606 -0.977876 -0.194512 -0.0769601 0.00337109 -0.401922 -0.915668 0 -0.0667431 -0.99777 0.00586516 -0.306678 -0.951795 0.0122698 -0.213471 -0.976872 -0.0254058 -0.453859 -0.890711 0.00692458 -0.156432 -0.987665 0.0329008 -0.733722 -0.678653 0.0188442 -0.633004 -0.773919 0.00829097 -0.524711 -0.85124 0.00337108 -0.401898 -0.915678 0.00626532 -0.805409 -0.592686 0.0127521 -0.805397 -0.592598 0.0819173 -0.874871 -0.477378 -0.0106838 -0.45396 -0.890958 0.00405896 -0.707101 -0.707101 0.00388126 -0.731529 -0.681799 0.00388373 -0.707101 -0.707102 0.00238025 -0.727594 -0.686004 -0.00359745 -0.845661 -0.533708 0.229591 -0.908561 -0.349005 0 -0.997519 -0.0704044 0.00664396 -0.97142 -0.237276 -0.00118709 -0.987688 -0.156434 0.000335619 -0.930738 -0.365687 0.00247216 -0.891004 -0.453989 0.00247216 -0.891005 -0.453987 0.0510878 -0.453412 -0.889836 0.294662 -0.842095 -0.451719 0.110603 -0.981629 -0.155474 0.975493 -0.188183 -0.11402 0.472498 -0.165334 -0.865685 0.782686 -0.0896693 -0.615924 0.819719 -0.320894 -0.474434 0.860544 -0.257876 -0.439276 0.896297 -0.206202 -0.392597 0.921709 -0.18284 -0.342084 0.944915 -0.179918 -0.273433 0.611375 -0.35072 -0.709377 0.242837 -0.691888 -0.679943 0.420538 -0.33496 -0.843178 0.542949 -0.097782 -0.834053 0.0242751 -0.00849422 -0.999669 0.0536589 -0.147139 -0.987659 0.0830984 -0.127991 -0.988288 0.137766 -0.104309 -0.984957 0.219834 -0.0865673 -0.971689 0.333122 -0.114216 -0.93594 0.00602883 -0.000679285 -0.999982 0.0104413 -0.00140801 -0.999945 0.0240506 -0.00940712 -0.999667 0.944917 -0.179918 -0.273426 0.952642 -0.260856 -0.156295 0.932405 -0.326263 -0.155475 0.836428 -0.525563 -0.155474 0.836428 -0.525562 -0.155475 0.836428 -0.525563 -0.155476 0.932406 -0.326263 -0.155476 0.326262 -0.932406 -0.155473 0.326263 -0.932406 -0.155474 0.326265 -0.932405 -0.155473 0.525562 -0.836429 -0.155473 0.782695 -0.089671 -0.615913 0.85124 -0.265077 -0.452907 0.842095 -0.294663 -0.451718 0.842095 -0.294662 -0.451719 0.755414 -0.474658 -0.451719 0.755414 -0.474657 -0.45172 0.630853 -0.630852 -0.45172 0.542879 -0.0977671 -0.8341 0.679725 -0.196989 -0.706519 0.669528 -0.234277 -0.704874 0.669528 -0.234279 -0.704872 0.60061 -0.377389 -0.704872 0.60061 -0.377388 -0.704873 0.501575 -0.501575 -0.704873 0.501575 -0.501574 -0.704874 0.377387 -0.60061 -0.704874 0.110603 -0.981629 -0.155473 0.0998898 -0.88655 -0.451719 0.0998896 -0.886551 -0.451718 0.0998903 -0.886551 -0.451717 0.0794201 -0.704873 -0.704873 0.698512 -0.698504 -0.155475 0.525563 -0.836427 -0.155476 0.474658 -0.755413 -0.451719 0.294663 -0.842095 -0.451719 0.234278 -0.669527 -0.704874 0.0794205 -0.704872 -0.704874 0.0794211 -0.704873 -0.704873 0.333129 -0.114218 -0.935938 0.416272 -0.181796 -0.89088 0.386332 -0.242748 -0.889843 0.386333 -0.242749 -0.889843 0.322629 -0.32263 -0.889843 0.32263 -0.32263 -0.889843 0.242749 -0.386332 -0.889843 0.242749 -0.386333 -0.889843 0.150695 -0.430663 -0.889843 0.698508 -0.698509 -0.155474 0.698508 -0.698509 -0.155474 0.630853 -0.630854 -0.451718 0.474658 -0.755415 -0.451717 0.377387 -0.60061 -0.704874 0.234278 -0.669528 -0.704874 0.150696 -0.430663 -0.889843 0.0510863 -0.453398 -0.889843 0.05108 -0.453393 -0.889846 0.0176235 -0.156411 -0.987535 0.0176233 -0.156411 -0.987535 0.0519862 -0.148568 -0.987535 0.0519863 -0.148568 -0.987535 0.0837424 -0.133275 -0.987535 0.0837423 -0.133275 -0.987535 0.111299 -0.1113 -0.987535 0.111299 -0.111299 -0.987535 0.133275 -0.0837422 -0.987535 0.133275 -0.0837424 -0.987535 0.125354 -0.100016 -0.987058 0.0259754 -0.00942484 -0.999618 0.00602883 0 -0.999982 0.00602883 0 -0.999982 0.00337109 0.401922 -0.915668 0 0.999665 -0.0258944 0.000764439 0.996903 -0.0786314 0.134612 0.895444 -0.424335 0.0176977 0.821441 -0.57002 0.01007 0.821551 -0.570046 0.00428832 0.673132 -0.73951 0.00388126 0.731529 -0.681799 0.00388373 0.707101 -0.707102 0.00238025 0.727594 -0.686004 -0.00640563 0.89099 -0.453979 0.00186856 0.85136 -0.524579 0.00187308 0.891005 -0.453989 0.00127046 0.903107 -0.429413 -0.00206738 0.987686 -0.156433 0.0147596 0.947041 -0.320773 0.00439883 0.979663 -0.200601 0.00338044 0.453984 -0.891004 0.00869931 0.410507 -0.911816 -0.0158591 0.707018 -0.707018 0.0141465 0.53515 -0.844639 0.00736524 0.610708 -0.791822 0 0.156436 -0.987688 0.0145288 0.0832779 -0.99642 -0.0254058 0.453859 -0.890711 0.0122698 0.213471 -0.976872 0.00586516 0.306678 -0.951795 0.00595042 0.804045 -0.594538 0.549696 0.624715 -0.554586 0.629763 0.618504 -0.469948 0.807856 0.409298 -0.424079 0.733993 0.660935 -0.156267 0.477251 0.483634 -0.73371 0.387044 0.479202 -0.787758 0.497439 0.316191 -0.807822 0.372309 0.380669 -0.84645 0.10243 0.182619 -0.977833 0.0662284 0.909129 -0.411215 0.0662555 0.909196 -0.411063 0.0252358 0.865173 -0.500838 0.0808773 0.993923 -0.0746779 0.0505916 0.990794 -0.125568 0.0832683 0.990237 -0.111792 0.0764531 0.952373 -0.295197 0.0764565 0.952379 -0.295176 0.0222199 0.999197 -0.0333465 0.0220621 0.999112 -0.0358896 0.00652913 0.99766 -0.0680541 0.118792 0.985969 -0.117274 0.121907 0.985438 -0.118539 0.0800298 0.940795 -0.329394 -0.109586 0.950498 -0.290765 -0.487326 0.795638 -0.359824 0.0244153 0.842258 -0.538521 0.0420645 0.817577 -0.574281 0.0395525 0.818227 -0.573533 0.064367 0.784586 -0.61667 0.166507 0.977902 -0.126427 0.171163 0.977334 -0.124582 0.167961 0.978228 -0.121897 0.253816 0.955984 -0.147217 0.251605 0.957388 -0.141785 0.335948 0.925823 -0.173179 0.339199 0.924791 -0.172355 0.337212 0.925849 -0.170563 0.415699 0.886413 -0.203634 0.415412 0.886679 -0.203059 0.0275848 0.79078 -0.611478 0.0568736 0.780245 -0.622883 0.080823 0.723665 -0.685402 0.071718 0.728304 -0.681491 0.102542 0.663196 -0.741388 0.094367 0.668424 -0.737769 0.119155 0.574533 -0.809762 0.117467 0.575918 -0.809024 0.159441 0.48289 -0.861043 0.0454021 0.942511 -0.331077 0.100182 0.934414 -0.341811 0.108389 0.926959 -0.359163 0.151861 0.915709 -0.372043 0.162202 0.90291 -0.39805 0.206442 0.886274 -0.414608 0.218629 0.86652 -0.448715 0.256792 0.847258 -0.464986 0.273479 0.821889 -0.499709 0.31346 0.796335 -0.517295 0.328565 0.758184 -0.563207 0.376117 0.719517 -0.583808 0.393803 0.668674 -0.63071 0.420947 0.641494 -0.641318 0.449181 0.587293 -0.673293 0.571266 0.423641 -0.702982 0.549724 0.624734 -0.554536 0.497041 0.834223 -0.238794 0.493692 0.835948 -0.239708 0.495796 0.834246 -0.241288 0.579975 0.766031 -0.277174 0.58361 0.760096 -0.285753 0.642872 0.701351 -0.307931 0.650035 0.69102 -0.316141 0.81411 -0.500886 -0.293833 0.945316 0.139966 -0.294595 0.0818679 0.52401 -0.847769 0.128005 0.478614 -0.868644 0.171306 0.374258 -0.911364 0.153742 0.394984 -0.905732 0.180568 0.26188 -0.948058 0.276174 0.117809 -0.95386 0.372321 0.38068 -0.846439 0.0978297 0.0499479 -0.993949 0.271149 -0.117865 -0.955294 0.0960426 0.0532685 -0.993951 0.0979477 0.0522123 -0.993821 0.222874 -0.0428898 -0.973903 0.0764565 -0.952379 -0.295176 0.372309 -0.380669 -0.84645 0.10243 -0.18262 -0.977833 0.42153 -0.514556 -0.746689 0.497427 -0.316212 -0.807822 0.497439 -0.316192 -0.807822 0.733993 -0.660935 -0.156267 0.807856 -0.409298 -0.424079 0.629763 -0.618504 -0.469948 0.549696 -0.624715 -0.554586 0.00652914 -0.99766 -0.0680541 0.0220621 -0.999112 -0.0358896 0.0222199 -0.999197 -0.0333465 0.00653166 -0.99766 -0.0680543 0.0746492 -0.990505 -0.115444 -0.0553689 -0.984064 -0.168975 0.00595034 -0.804045 -0.594538 0.0252358 -0.865173 -0.500838 0.0662555 -0.909196 -0.411063 0.0662284 -0.909129 -0.411215 0.104012 -0.987855 -0.115433 0.118623 -0.985906 -0.117971 0.122023 -0.9855 -0.117901 0.166507 -0.977902 -0.126427 0.171163 -0.977334 -0.124582 -0.487326 -0.795638 -0.359824 0.0505914 -0.837931 -0.543427 0.0183395 -0.823478 -0.567052 0.167961 -0.978228 -0.121897 0.249793 -0.957222 -0.146045 0.255132 -0.956258 -0.143106 0.335948 -0.925823 -0.173179 0.339199 -0.924791 -0.172355 0.337212 -0.925849 -0.170563 0.415222 -0.886682 -0.203434 0.415848 -0.886431 -0.20325 0.497041 -0.834223 -0.238794 0.493692 -0.835948 -0.239708 0.0395525 -0.818227 -0.573533 0.064367 -0.784586 -0.61667 0.0275848 -0.79078 -0.611478 0.105309 -0.760883 -0.640287 0.0383024 -0.744546 -0.666471 0.127844 -0.698243 -0.704353 0.0520311 -0.694259 -0.717843 0.158431 -0.625334 -0.764106 0.0630991 -0.618665 -0.783117 0.495796 -0.834246 -0.241288 0.586369 -0.760156 -0.279883 0.577659 -0.765466 -0.283499 0.652125 -0.691228 -0.311346 0.641057 -0.700675 -0.313209 0.884052 0.325517 -0.335397 0.704995 0.674468 -0.219258 -0.109586 -0.950498 -0.290765 0.0800299 -0.940795 -0.329394 0.0454021 -0.942511 -0.331077 0.112803 -0.932118 -0.344139 0.0970658 -0.929549 -0.355692 0.170656 -0.910195 -0.377388 0.145692 -0.908504 -0.391655 0.231337 -0.875836 -0.423549 0.196851 -0.876607 -0.439101 0.286528 -0.830808 -0.477138 0.246655 -0.837631 -0.487376 0.348643 -0.771676 -0.531944 0.297412 -0.781267 -0.548788 0.415828 -0.683788 -0.599601 0.357925 -0.702111 -0.615573 0.462336 -0.596627 -0.655959 0.409776 -0.630539 -0.659169 0.466953 -0.566456 -0.679031 0.630079 -0.3802 -0.677088 0.117467 -0.575918 -0.809024 0.159441 -0.48289 -0.861043 0.0818679 -0.52401 -0.847769 0.197836 -0.404441 -0.89291 0.106134 -0.448977 -0.887218 0.224459 -0.308756 -0.924277 0.117159 -0.349169 -0.929707 0.211108 -0.217583 -0.952938 0.360415 -0.0834499 -0.929052 0.250784 0.0790948 -0.964806 0.198898 0.0243193 -0.979718 0.0960194 -0.0532556 -0.993954 0.097481 -0.0498703 -0.993987 0.0975233 -0.0497915 -0.993987 0.980785 -0.195091 0 0.980785 -0.195091 0 0.831469 -0.555571 0 0.831469 -0.555571 0 0.55557 -0.83147 0 0.55557 -0.83147 0 0.195091 -0.980785 0 0.195091 -0.980785 0 -0.825141 0.564927 0 -0.785078 0.618988 0.0225002 -0.720622 0.693322 0.00296133 -0.598888 0.800821 -0.00425293 -0.598888 0.800822 -0.00425293 -0.515634 0.856541 0.0214122 -0.459598 0.888098 0.00722167 -0.0562094 0.998419 0 -0.0562025 0.998419 -1.621e-07 -0.153588 0.988062 0.0120481 -0.179618 0.983567 0.0182801 -0.315835 0.948791 -0.0066486 -0.315837 0.94879 -0.0066486 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.924683 0.380719 -0.00371796 -0.924673 0.380743 -0.00371826 -0.952869 0.303284 0.00767802 -0.991221 0.13196 -0.00818111 -0.995999 0.0893609 0 -0.737598 0.674597 -0.0294605 -0.915446 0.399433 0.0491073 -0.843203 0.537397 -0.0146082 -0.953963 0.299901 -0.00367194 -0.538901 0.842344 0.00649044 -0.780865 0.624677 -0.00528951 -0.727352 0.686231 -0.0068282 -0.781499 0.623869 -0.00684718 -0.781476 0.623898 -0.00684743 -0.00308007 0.999995 0 -0.166797 0.985991 0.00102994 -0.182212 0.983222 0.00852133 -0.51333 0.858144 -0.00900744 -0.549045 0.83575 -0.00850515 -0.513031 0.858328 -0.00852637 -0.512971 0.858364 -0.00852662 -0.778267 -0.627932 0.0012529 -0.781792 -0.623538 0.00125306 -0.778995 -0.627029 -0.000575457 -0.506119 -0.862464 0.000728528 -0.506067 -0.862494 0.000712693 -0.505969 -0.862551 0.00071219 -0.50613 -0.862457 0.00071219 -0.506079 -0.862487 0.000697864 -0.163495 -0.986544 -0.000573034 -0.166798 -0.985991 0.00102904 -0.00322674 -0.999995 0 -0.991358 -0.131185 0 -0.991105 -0.133078 -0.000546355 -0.926276 -0.376846 0.000503967 -0.805935 -0.588181 -0.0671659 -0.923643 -0.383241 0.00313976 -0.923658 -0.383204 0.00314012 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.000603901 -0.00612006 -0.999981 -0.0290814 -0.0170121 -0.999432 -0.000945081 -0.00034762 -1 -0.0412997 -0.0151909 -0.999031 -0.0430117 -0.0108166 -0.999016 -0.126293 -0.0408033 -0.991153 -0.127575 -0.0376956 -0.991112 -0.215841 -0.0671723 -0.974115 -0.215674 -0.0674547 -0.974133 -0.0630904 -0.671673 -0.738157 0.00906725 -0.650736 -0.75925 -0.0620331 -0.469574 -0.880711 0.01376 -0.444425 -0.89571 0.00637544 -0.446306 -0.894858 -0.0299942 -0.232048 -0.972242 0.0167811 -0.215173 -0.976432 -0.0503319 -0.759897 -0.648093 -0.0503333 -0.759902 -0.648086 -0.00681342 -0.748566 -0.663025 -0.215617 -0.0678231 -0.97412 -0.284165 -0.0874531 -0.954779 -0.282908 -0.0897736 -0.954937 -0.347931 -0.106087 -0.931499 -0.344296 -0.115071 -0.931783 -0.42832 -0.129241 -0.894337 -0.423556 -0.135133 -0.895734 -0.0330754 -0.885937 -0.462624 -0.113978 -0.897816 -0.425365 -0.00854026 -0.966594 -0.25617 -0.0758155 -0.972532 -0.220076 -0.0758159 -0.972532 -0.220075 -0.0749859 -0.997183 -0.00167223 -0.169281 -0.983838 0.0583709 -0.425672 -0.14574 -0.893064 -0.504215 -0.149837 -0.85048 -0.496328 -0.172468 -0.850831 -0.574132 -0.164995 -0.801966 -0.565102 -0.194413 -0.801788 -0.630045 -0.17552 -0.756463 -0.619407 -0.199733 -0.759238 -0.678899 -0.172083 -0.713782 -0.666756 -0.196591 -0.71888 -0.230974 -0.740858 0.630699 -0.069193 -0.865585 0.495958 -0.221491 -0.865533 0.449215 -0.0586846 -0.943709 0.325528 -0.143454 -0.916865 0.372531 -0.100701 -0.968332 0.228457 -0.0332483 -0.98322 0.17937 -0.242545 -0.0943825 0.965538 -0.209326 -0.309566 0.927551 -0.266461 -0.228192 0.936444 -0.192571 -0.445736 0.874206 -0.24792 -0.33508 0.908987 -0.166263 -0.530775 0.831044 -0.260888 -0.437897 0.86034 -0.124343 -0.666019 0.735498 -0.208272 -0.569322 0.795296 -0.180121 -0.710568 0.680184 -0.104217 -0.784342 0.611512 -0.229116 0.380088 0.896124 -0.233579 0.368445 0.899827 -0.223673 0.245686 0.943191 -0.231839 0.202051 0.951539 -0.235248 0.130757 0.9631 -0.24568 0.033831 0.96876 -0.243799 0.0217573 0.969582 -0.242554 0.0336977 0.969553 -0.230805 -0.144798 0.962165 -0.1678 0.725163 0.667819 -0.147057 0.745979 0.64953 -0.20873 0.634854 0.743903 -0.190597 0.65782 0.728661 -0.235297 0.528905 0.815411 -0.137565 0.617685 0.7743 -0.196152 0.512588 0.835929 -0.685275 -0.197363 -0.701032 -0.724427 -0.166619 -0.668913 -0.713804 -0.195506 -0.672503 -0.760708 -0.146043 -0.632452 -0.75629 -0.182606 -0.628236 -0.794807 -0.118733 -0.595134 -0.790659 -0.147307 -0.594271 -0.810545 -0.100068 -0.577064 -0.804649 -0.122207 -0.581039 -0.823171 -0.068936 -0.563594 -0.825433 -0.0886617 -0.557494 -0.834268 -0.0321407 -0.550421 -0.834464 -0.0406794 -0.549559 -0.837675 0.00747312 -0.546117 -0.83691 0.00938805 -0.547261 -0.832928 0.0449847 -0.55155 -0.829945 0.0558857 -0.555039 -0.824756 0.0828515 -0.559386 -0.812148 0.0965491 -0.575407 -0.804578 0.115647 -0.582477 -0.791122 0.133522 -0.596907 -0.782686 0.149818 -0.604117 -0.758413 0.156225 -0.632775 -0.751068 0.165238 -0.639212 -0.731831 0.176751 -0.658166 -0.719768 0.189039 -0.667981 -0.693813 0.178684 -0.697636 -0.658464 0.201138 -0.725237 -0.644022 0.207803 -0.736243 -0.0558672 0.903919 0.424038 -0.0558808 0.90392 0.424036 -0.148373 0.852329 0.501518 -0.21059 0.913621 0.347776 -0.111137 0.954586 0.276429 -0.095406 0.992367 0.0781363 -0.104921 0.990891 0.0844198 -0.0709558 0.996218 -0.0501527 -0.0190843 0.996462 -0.0818502 -0.653066 0.172418 -0.737413 -0.592985 0.193167 -0.7817 -0.579285 0.170783 -0.797033 -0.5436 0.176224 -0.820636 -0.534765 0.164031 -0.828927 -0.488887 0.166725 -0.856266 -0.420856 0.127701 -0.898094 -0.415356 0.141212 -0.898632 -0.484109 0.146264 -0.862697 -0.0190842 0.996462 -0.0818501 -0.132689 0.965214 -0.225292 -0.0532076 0.961874 -0.268266 -0.420866 0.127689 -0.898091 -0.345911 0.114809 -0.931217 -0.346226 0.105791 -0.932167 -0.271397 0.0871705 -0.958512 -0.271867 0.0836061 -0.958696 -0.204884 0.0633345 -0.976735 -0.204881 0.0633699 -0.976733 -0.0143661 0.601896 -0.798445 -0.0395544 0.609544 -0.791765 -0.020897 0.75737 -0.652652 -0.04876 0.764422 -0.64287 -0.066749 0.822107 -0.565406 -0.00315872 0.876125 -0.482073 -0.0581519 0.886893 -0.4583 -0.204859 0.0634047 -0.976736 -0.132296 0.0392807 -0.990432 -0.131475 0.0421591 -0.990423 -0.0461873 0.0115526 -0.998866 -0.0445157 0.0163744 -0.998875 -0.000945081 0.00034762 -1 -6.56327e-05 -0.00319501 -0.999995 -0.0388355 -0.0174526 -0.999093 -0.00949651 -0.112231 -0.993637 -0.090548 -0.141381 -0.985806 -0.0539862 -0.245587 -0.96787 -0.146689 -0.276506 -0.949751 -0.105038 -0.379262 -0.919308 -0.186069 -0.402798 -0.896177 -0.155065 -0.453885 -0.877464 -0.241168 -0.475085 -0.846246 -0.192998 -0.565 -0.802202 -0.311928 -0.584954 -0.748686 -0.25682 -0.671006 -0.695554 -0.390355 -0.678058 -0.622784 -0.33007 -0.752757 -0.569571 -0.477489 -0.738479 -0.476081 -0.410482 -0.807273 -0.424046 -0.55426 -0.767114 -0.323006 -0.490109 -0.816739 -0.304517 -0.638414 -0.745889 -0.189943 -0.564227 -0.810849 -0.155476 -0.715055 -0.698234 -0.0341453 -0.647946 -0.76076 -0.0375603 -0.789955 -0.607182 0.0854443 -0.721304 -0.685502 0.0990283 -0.853323 -0.475897 0.212985 -0.802107 -0.560454 0.206196 -0.879469 -0.389957 0.272889 -0.843703 -0.474153 0.251682 -0.909916 -0.269014 0.31573 -0.882463 -0.341474 0.323504 -0.925913 -0.121534 0.357653 -0.919858 -0.161181 0.357606 -0.929129 0.0281441 0.368683 -0.929908 0.037778 0.365847 -0.920047 0.169394 0.353298 -0.91334 0.222529 0.341014 -0.893352 0.310808 0.324532 -0.879045 0.39042 0.273592 -0.858493 0.445505 0.253999 -0.823965 0.529309 0.202272 -0.800754 0.570492 0.182569 -0.764314 0.639453 0.0832111 -0.750399 0.657177 0.0708445 -0.700242 0.713901 0.00264811 -0.677573 0.735287 -0.0157487 -0.638984 0.757276 -0.135029 -0.571315 0.798875 -0.188144 -0.541863 0.779891 -0.313296 -0.47655 0.801775 -0.360635 -0.45382 0.760827 -0.463886 -0.417215 0.766548 -0.488196 -0.392294 0.735408 -0.552522 -0.346686 0.737376 -0.579729 -0.340456 0.663761 -0.665966 -0.27528 0.658737 -0.700204 -0.276264 0.576853 -0.768712 -0.210802 0.565361 -0.797452 -0.219552 0.473429 -0.853031 -0.154138 0.45704 -0.875988 -0.167434 0.364395 -0.916069 -0.111708 0.34755 -0.930984 -0.123072 0.27345 -0.95398 -0.0611271 0.252707 -0.96561 -0.0851363 0.14767 -0.985366 -0.0102098 0.120758 -0.99263 -0.0378915 0.0171048 -0.999135 -6.56329e-05 0.00319501 -0.999995 -6.56294e-05 0.00319502 -0.999995 -0.0319721 0.014929 -0.999377 0.00485077 0.175873 -0.984401 -0.0585209 0.198657 -0.97832 -0.0271801 0.356315 -0.933971 -0.0772926 0.373154 -0.924544 -0.0629559 0.479966 -0.875025 -0.105788 0.492931 -0.863613 -0.0881158 0.619188 -0.780283 -0.138213 0.631801 -0.762709 -0.12527 0.746429 -0.653568 -0.174074 0.755086 -0.632095 -0.169624 0.84544 -0.506418 -0.217115 0.849184 -0.481402 -0.219105 0.916653 -0.334277 -0.246892 0.915564 -0.31747 -0.27607 0.936445 -0.216463 -0.29508 0.933468 -0.203875 -0.313951 0.948232 -0.0478701 -0.361001 0.932467 -0.0135837 -0.382184 0.90983 0.161696 -0.432293 0.878883 0.201714 -0.464109 0.810598 0.357118 -0.469204 0.805726 0.36146 -0.529789 0.718713 0.450305 -0.529292 0.71935 0.449873 -0.558625 0.602719 0.569796 -0.569262 0.583218 0.579481 -0.608801 0.463202 0.644054 -0.621895 0.42782 0.655909 -0.628426 0.313304 0.711984 -0.643587 0.24084 0.726493 -0.65038 0.167103 0.741001 -0.660653 0.0407068 0.749587 -0.658513 0.0277939 0.752056 -0.647258 -0.173749 0.742205 -0.657038 -0.119895 0.744262 -0.611867 -0.367882 0.700201 -0.65758 -0.27691 0.700649 -0.579735 -0.51678 0.629957 -0.630676 -0.405022 0.66197 -0.540563 -0.610439 0.578926 -0.619542 -0.508729 0.597798 -0.470228 -0.750802 0.463877 -0.579375 -0.674382 0.457748 -0.416175 -0.851887 0.317942 -0.51771 -0.790694 0.326772 -0.3482 -0.918489 0.187443 -0.465296 -0.873975 0.140243 -0.298709 -0.954264 0.0123806 -0.396274 -0.917929 -0.0192904 -0.238781 -0.962153 -0.131321 -0.342888 -0.912947 -0.221258 -0.185364 -0.928628 -0.321386 -0.27739 -0.863203 -0.421824 -0.138102 -0.85611 -0.498 -0.220519 -0.764934 -0.605184 -0.099509 -0.744841 -0.65978 -0.169841 -0.634491 -0.754039 -0.0821032 -0.61308 -0.785743 -0.126871 -0.545082 -0.828728 -0.0476047 -0.522011 -0.851609 -0.10607 -0.375673 -0.920662 -0.0190631 -0.346713 -0.937778 -0.0691383 -0.190158 -0.979316 0.00459181 -0.163672 -0.986504 -0.0352495 -0.0161364 -0.999248 -6.56289e-05 -0.00319502 -0.999995 0.000603902 0.00612006 -0.999981 -0.02346 0.01495 -0.999613 0.0179226 0.231193 -0.972743 -0.0297101 0.248341 -0.968217 0.00376541 0.451299 -0.892365 0.0130805 0.453306 -0.891259 -0.0289694 0.467564 -0.883484 -0.000945081 -0.000347621 -1 -0.0414695 -0.0152534 -0.999023 -0.0253781 -0.0612391 -0.9978 -0.109618 -0.0915579 -0.989748 -0.0903006 -0.142196 -0.985711 -0.183409 -0.173285 -0.967643 -0.161565 -0.226443 -0.960531 -0.23901 -0.248803 -0.938601 -0.222874 -0.277147 -0.934621 -0.301314 -0.296658 -0.906203 -0.276287 -0.350773 -0.894776 -0.382658 -0.36872 -0.847124 -0.354395 -0.427185 -0.831816 -0.468312 -0.433261 -0.770045 -0.437842 -0.491034 -0.753113 -0.557786 -0.479577 -0.677408 -0.524765 -0.539302 -0.658616 -0.63625 -0.507677 -0.580904 -0.603166 -0.551702 -0.576035 -0.714042 -0.499533 -0.490521 -0.679331 -0.560005 -0.47424 -0.788755 -0.47733 -0.387326 -0.755085 -0.527204 -0.389747 -0.855586 -0.419868 -0.302793 -0.826528 -0.482032 -0.290681 -0.916963 -0.336594 -0.214203 -0.894963 -0.391812 -0.213366 -0.944394 -0.280223 -0.172034 -0.926876 -0.328376 -0.181852 -0.971178 -0.194242 -0.138142 -0.963256 -0.236368 -0.127549 -0.990066 -0.0894673 -0.108464 -0.988144 -0.109874 -0.107232 -0.994959 0.020733 -0.0981175 -0.994622 0.0255596 -0.100364 -0.985856 0.12469 -0.111984 -0.981207 0.151505 -0.119499 -0.964872 0.227147 -0.13201 -0.949725 0.265475 -0.165969 -0.928877 0.320219 -0.186136 -0.905546 0.364169 -0.217643 -0.881684 0.407815 -0.237317 -0.848195 0.435944 -0.300861 -0.829439 0.459503 -0.31763 -0.794794 0.488941 -0.359499 -0.769123 0.51392 -0.379915 -0.732302 0.50926 -0.452093 -0.669512 0.548422 -0.500986 -0.638818 0.515619 -0.571007 -0.574703 0.537244 -0.617321 -0.552519 0.495805 -0.67 -0.510432 0.502305 -0.697961 -0.491725 0.47548 -0.729469 -0.440255 0.478096 -0.76 -0.431855 0.422761 -0.796728 -0.360809 0.417427 -0.83401 -0.358862 0.363156 -0.859846 -0.285984 0.350501 -0.891831 -0.289751 0.295734 -0.910267 -0.21611 0.277357 -0.936146 -0.223191 0.226869 -0.948007 -0.159416 0.207589 -0.965139 -0.165772 0.169743 -0.971446 -0.096329 0.146576 -0.984498 -0.109485 0.0954288 -0.989397 -0.027246 0.0659079 -0.997454 -0.0426228 0.015679 -0.998968 -0.00094508 0.000347621 -1 -0.183016 -0.735063 -0.652831 -0.087483 -0.594946 -0.798991 -0.160613 -0.611225 -0.774989 -0.080447 -0.451696 -0.888538 -0.124991 -0.479751 -0.868456 -0.202355 -0.962137 -0.182608 -0.0915272 -0.920184 -0.380638 -0.210718 -0.908089 -0.3619 -0.100682 -0.829617 -0.54918 -0.175504 -0.845529 -0.504261 -0.13882 -0.802658 -0.580059 -0.0790151 -0.738725 -0.669359 -0.730898 -0.00945728 -0.682422 -0.732871 -0.031464 -0.67964 -0.734385 -0.032077 -0.677975 -0.739244 -0.0513615 -0.671476 -0.740402 -0.0523832 -0.67012 -0.74719 -0.0740696 -0.66047 -0.749634 -0.0738222 -0.657723 -0.763108 -0.100223 -0.638453 -0.764527 -0.100006 -0.636786 -0.783368 -0.127873 -0.608262 -0.783344 -0.12789 -0.60829 -0.805678 -0.149274 -0.573236 -0.803992 -0.149989 -0.575414 -0.830525 -0.169715 -0.530495 -0.825805 -0.175642 -0.535906 -0.854946 -0.184915 -0.484637 -0.849545 -0.189 -0.492496 -0.879647 -0.192957 -0.434728 -0.871281 -0.209134 -0.443996 -0.90232 -0.198918 -0.382428 -0.894814 -0.202467 -0.397887 -0.248923 -0.921702 0.297494 -0.147403 -0.985952 0.0785504 -0.22113 -0.963027 0.153884 -0.114688 -0.991353 -0.063763 -0.211199 -0.977363 -0.0124826 -0.182822 -0.974368 -0.131084 -0.121733 -0.961962 -0.24456 -0.240866 -0.653468 0.71761 -0.174921 -0.819424 0.545846 -0.255911 -0.767522 0.587725 -0.17508 -0.90275 0.392924 -0.225837 -0.853469 0.469668 -0.197158 -0.90522 0.376438 -0.143731 -0.956762 0.252879 -0.236084 -0.0942558 0.967151 -0.227018 -0.260959 0.938277 -0.245619 -0.230749 0.941502 -0.221889 -0.430073 0.875101 -0.240823 -0.382606 0.891974 -0.204101 -0.582177 0.787028 -0.229601 -0.524294 0.819999 -0.239288 -0.588474 0.772295 -0.201084 -0.714209 0.670425 -0.223956 0.36361 0.90423 -0.236916 0.235536 0.942546 -0.232 0.206225 0.950604 -0.239089 0.049259 0.969747 -0.237117 0.0430871 0.970525 -0.23616 0.0491687 0.970469 -0.234078 -0.107513 0.966255 -0.208407 0.788502 0.578646 -0.232827 0.732033 0.64025 -0.209424 0.660033 0.721456 -0.230399 0.584006 0.778366 -0.228725 0.521181 0.822225 -0.210258 0.580288 0.786802 -0.242657 0.414304 0.877194 -0.187287 0.954446 0.232286 -0.210393 0.935624 0.283446 -0.202098 0.888461 0.41206 -0.151627 0.931493 0.330651 -0.213155 0.852155 0.47791 -0.901593 -0.205602 -0.380603 -0.923393 -0.192602 -0.33204 -0.914332 -0.219242 -0.340486 -0.941973 -0.186492 -0.279118 -0.93388 -0.205102 -0.292918 -0.95753 -0.167122 -0.23496 -0.950889 -0.198852 -0.237208 -0.970874 -0.147922 -0.188474 -0.965537 -0.170591 -0.196561 -0.980651 -0.118924 -0.155503 -0.977902 -0.145439 -0.150187 -0.988437 -0.0885855 -0.123061 -0.986719 -0.105622 -0.12341 -0.993081 -0.0535271 -0.104524 -0.993025 -0.0652676 -0.0981874 -0.995426 -0.0221666 -0.0929297 -0.995366 -0.0264603 -0.0924509 -0.995899 0.0102379 -0.0898945 -0.995716 0.0121001 -0.0916746 -0.994028 0.0490023 -0.0975087 -0.993011 0.0571668 -0.103258 -0.989811 0.0882933 -0.111704 -0.986648 0.0977695 -0.13026 -0.981686 0.124239 -0.144418 -0.976964 0.136151 -0.164328 -0.970228 0.160299 -0.181551 -0.963168 0.163316 -0.213625 -0.953594 0.184696 -0.237793 -0.945697 0.186632 -0.26613 -0.932447 0.206254 -0.29665 -0.924708 0.19572 -0.326509 -0.907982 0.208805 -0.363275 -0.901289 0.200287 -0.384141 -0.879947 0.208182 -0.427028 -0.873778 0.20978 -0.438754 -0.149299 0.866867 -0.47566 -0.162904 0.876728 -0.452561 -0.136124 0.941077 -0.309588 -0.156685 0.949171 -0.272993 -0.166567 0.975134 -0.146179 -0.18379 0.97643 -0.113163 -0.217928 0.975965 0.000706845 -0.116303 0.992115 -0.0467077 -0.186361 0.97782 0.095589 -0.103699 0.593567 -0.798076 -0.121981 0.623206 -0.772486 -0.134934 0.683847 -0.71704 -0.148823 0.70311 -0.695333 -0.118908 0.793741 -0.59652 -0.0790126 0.756796 -0.648859 -0.13395 0.813116 -0.56648 -0.113943 0.22014 -0.968791 -0.130049 0.300641 -0.944829 -0.099403 0.35862 -0.928176 -0.119083 0.412442 -0.903167 -0.125702 0.464536 -0.876587 -0.104467 0.422044 -0.900536 -0.139124 0.505281 -0.851667 -0.882183 0.19358 -0.429278 -0.854593 0.190943 -0.48292 -0.851498 0.183595 -0.491165 -0.827626 0.175742 -0.533057 -0.827123 0.167159 -0.536586 -0.806806 0.151826 -0.570975 -0.806112 0.149602 -0.572541 -0.786489 0.132015 -0.60333 -0.786549 0.131427 -0.603381 -0.771118 0.109471 -0.62721 -0.771327 0.110426 -0.626786 -0.758054 0.0899028 -0.645965 -0.757224 0.0930026 -0.6465 -0.747615 0.0697024 -0.660464 -0.747737 0.0716998 -0.660113 -0.740109 0.0513501 -0.670523 -0.738759 0.0541234 -0.671793 -0.73426 0.0314588 -0.678139 -0.733955 0.0328281 -0.678405 -0.731077 0.0131515 -0.682168 -0.731224 0.0129791 -0.682014 -0.730604 -0.000593793 -0.682802 -0.730642 -0.00911837 -0.682699 -0.551557 0.0372901 -0.833303 -0.55233 -0.0288398 -0.833126 -0.551086 -0.02724 -0.834004 -0.557143 -0.0975053 -0.824673 -0.549656 -0.0943459 -0.830047 -0.566137 -0.158936 -0.808844 -0.559467 -0.153008 -0.814608 -0.580449 -0.220924 -0.783755 -0.562726 -0.22109 -0.796529 -0.601283 -0.296557 -0.741966 -0.582365 -0.297124 -0.756683 -0.630433 -0.368398 -0.683255 -0.602194 -0.380097 -0.70206 -0.657102 -0.433018 -0.617019 -0.633998 -0.437797 -0.63748 -0.693924 -0.482163 -0.534779 -0.658861 -0.507031 -0.555718 -0.723801 -0.528852 -0.443201 -0.697967 -0.53998 -0.470388 -0.761876 -0.547583 -0.345973 -0.724444 -0.58373 -0.366661 -0.790751 -0.564198 -0.237472 -0.764455 -0.585728 -0.269316 -0.824746 -0.548985 -0.13568 -0.789583 -0.594359 -0.15263 -0.848714 -0.528291 -0.0243485 -0.825877 -0.561298 -0.0535971 -0.874873 -0.479344 0.0694749 -0.84705 -0.527953 0.0614195 -0.891684 -0.42081 0.166788 -0.876077 -0.458442 0.149402 -0.9083 -0.342361 0.240374 -0.891438 -0.382301 0.243277 -0.917482 -0.253104 0.306863 -0.910476 -0.280803 0.303617 -0.924535 -0.153471 0.34883 -0.918717 -0.171977 0.355503 -0.926755 -0.0631963 0.370312 -0.926088 -0.0703527 0.370691 -0.925949 0.0290286 0.376532 -0.926727 0.0322311 0.374351 -0.923172 0.13871 0.358488 -0.923939 0.153206 0.35052 -0.913383 0.245728 0.324576 -0.9167 0.266001 0.298169 -0.902515 0.346515 0.255721 -0.900857 0.37197 0.223819 -0.881392 0.438649 0.175314 -0.882121 0.455297 0.120694 -0.858597 0.509105 0.0601929 -0.852765 0.522268 0.00534624 -0.824152 0.563208 -0.0597456 -0.821797 0.55561 -0.126282 -0.791052 0.579996 -0.194531 -0.783376 0.568994 -0.250137 -0.747639 0.581279 -0.321171 -0.747072 0.548954 -0.374878 -0.715691 0.546083 -0.435409 -0.70864 0.523216 -0.473365 -0.673467 0.511016 -0.534139 -0.678068 0.46947 -0.565527 -0.650837 0.449014 -0.612207 -0.645343 0.427002 -0.633405 -0.616773 0.401143 -0.677255 -0.625276 0.364028 -0.6903 -0.603819 0.333425 -0.724038 -0.600558 0.315658 -0.734636 -0.579224 0.282767 -0.764554 -0.588867 0.256329 -0.766506 -0.573061 0.217689 -0.790071 -0.572576 0.204662 -0.793896 -0.557343 0.164539 -0.813815 -0.565287 0.150421 -0.811064 -0.555443 0.100045 -0.825514 -0.557074 0.0934587 -0.825187 -0.548979 0.0399579 -0.83488 -0.342723 0.0586443 -0.937604 -0.343922 -0.0472897 -0.937807 -0.340813 -0.0430617 -0.939144 -0.350762 -0.158844 -0.922895 -0.331754 -0.149699 -0.931413 -0.359277 -0.25817 -0.89681 -0.342442 -0.24199 -0.90784 -0.377206 -0.354099 -0.855762 -0.333648 -0.350263 -0.875211 -0.395066 -0.471183 -0.788613 -0.349823 -0.466906 -0.812172 -0.424127 -0.576698 -0.698238 -0.358546 -0.59071 -0.722846 -0.441352 -0.672093 -0.594558 -0.38991 -0.6732 -0.628308 -0.478697 -0.737814 -0.475898 -0.401817 -0.766333 -0.501275 -0.49561 -0.800216 -0.337676 -0.442463 -0.810555 -0.383703 -0.534815 -0.819919 -0.204219 -0.456558 -0.858711 -0.232744 -0.550076 -0.833729 -0.0480844 -0.499483 -0.860267 -0.102266 -0.58541 -0.806029 0.0872438 -0.514147 -0.855775 0.0574555 -0.59665 -0.76572 0.240169 -0.55448 -0.810269 0.189781 -0.623857 -0.69234 0.362585 -0.567878 -0.749617 0.339983 -0.630049 -0.601502 0.491154 -0.601339 -0.654012 0.458978 -0.646888 -0.488201 0.585829 -0.612172 -0.539396 0.578184 -0.648633 -0.358484 0.671391 -0.635066 -0.398266 0.661873 -0.65495 -0.216818 0.723899 -0.642154 -0.242727 0.727133 -0.653475 -0.089013 0.751696 -0.652049 -0.0998973 0.751567 -0.651879 0.0407696 0.757226 -0.653819 0.0457013 0.75527 -0.648909 0.19518 0.735406 -0.651859 0.217943 0.726347 -0.637561 0.344342 0.689162 -0.648972 0.380489 0.658835 -0.630181 0.488623 0.603423 -0.632758 0.533753 0.561003 -0.608413 0.617467 0.498566 -0.620401 0.65959 0.424316 -0.592213 0.724927 0.351802 -0.591062 0.760408 0.269117 -0.559224 0.805668 0.195365 -0.567878 0.818359 0.0883411 -0.535432 0.844424 0.0161541 -0.530453 0.843746 -0.08193 -0.494341 0.855427 -0.154502 -0.504028 0.823454 -0.260539 -0.474274 0.820971 -0.317915 -0.465781 0.790492 -0.397707 -0.431726 0.777761 -0.456838 -0.447792 0.715122 -0.536734 -0.42276 0.696638 -0.579628 -0.41299 0.656287 -0.631449 -0.384679 0.629834 -0.674782 -0.406397 0.560276 -0.721756 -0.385204 0.530387 -0.755187 -0.378006 0.491504 -0.784561 -0.354625 0.454812 -0.816937 -0.378078 0.39724 -0.836216 -0.359716 0.352666 -0.863847 -0.358363 0.320956 -0.876678 -0.338748 0.268841 -0.901651 -0.358385 0.23453 -0.903635 -0.344528 0.163922 -0.924354 -0.348504 0.147013 -0.925706 -0.336202 0.0656394 -0.9395 -0.135478 -0.415021 -0.899668 -0.103327 -0.313257 -0.944031 -0.131458 -0.343589 -0.929874 -0.0944658 -0.194569 -0.97633 -0.125727 -0.21245 -0.96905 -0.111771 -0.0557774 -0.992167 -0.116971 -0.0637161 -0.991089 -0.116724 -0.00412943 -0.993156 -0.111487 0.0876936 -0.989889 -0.104117 0.0814511 -0.991224 -0.119957 0.189815 -0.974464 -0.325113 0.902835 0.28141 -0.547006 0.710217 0.443144 -0.517081 0.802953 0.29647 -0.531587 0.827545 0.180513 -0.543506 0.838914 0.0287145 -0.543497 0.83892 0.0287121 -0.51706 0.802917 0.296604 -0.521767 0.771328 0.364434 -0.48503 0.778881 0.397607 -0.520476 0.729237 0.444204 -0.53927 0.720951 0.435222 -0.650719 0.650678 0.391386 -0.0726132 0.995871 0.054486 -0.0609145 0.997814 0.0256427 -0.0464466 0.998645 0.0234666 -0.12836 0.988592 0.0788031 -0.0972375 0.994354 0.0424832 -0.0972377 0.994354 0.0424835 -0.233338 0.970798 0.0557258 -0.198488 0.979904 -0.0197574 -0.210125 0.976205 0.0535791 -0.382766 0.863946 0.327243 -0.428862 0.838113 0.337112 -0.447537 0.825054 0.34496 -0.425717 0.83225 0.355141 -0.425704 0.832255 0.355145 -0.408196 0.907857 0.0957679 -0.445449 0.888736 0.108274 -0.444888 0.889143 0.107234 -0.491824 0.862771 0.1172 -0.493652 0.861364 0.119832 -0.580553 0.804071 0.128175 -0.559946 0.82351 0.0910594 -0.375146 0.92274 0.0884096 -0.381257 0.920421 0.0864163 -0.410309 0.906612 0.0984939 -0.337459 0.893708 0.295647 -0.370119 0.876931 0.306602 -0.283232 0.922046 0.26384 -0.299469 0.917311 0.26241 -0.287836 0.924026 0.251649 -0.25145 0.939847 0.231213 -0.24651 0.944646 0.216512 -0.227574 0.952493 0.202402 -0.221425 0.955534 0.194747 -0.204998 0.961804 0.18141 -0.203103 0.96369 0.173351 -0.375138 0.922744 0.0884058 -0.343508 0.936486 0.0706914 -0.345659 0.934983 0.0795438 -0.323148 0.944266 0.0627515 -0.327702 0.942266 0.0688913 -0.309208 0.949465 0.0539174 -0.310651 0.948343 0.0643599 -0.290003 0.956078 0.042588 -0.290029 0.955489 0.0540675 -0.27699 0.960212 0.035629 -0.279332 0.959132 0.0451601 -0.271227 0.961986 0.0319362 -0.268233 0.963115 0.0214873 -0.176146 0.973639 0.144915 -0.177929 0.973216 0.145576 -0.177068 0.973597 0.144067 -0.160302 0.979702 0.120362 -0.161073 0.979264 0.122869 -0.145149 0.984652 0.0969144 -0.144387 0.983904 0.105285 -0.133138 0.987949 0.0789382 -0.118342 0.992941 0.0079603 -0.535042 -0.726652 0.430937 -0.510318 -0.80893 0.291904 -0.628723 -0.680955 0.375511 -0.474913 -0.794712 0.378007 -0.499104 -0.788665 0.359031 -0.583036 -0.806836 0.0953204 -0.525332 -0.83207 0.178003 -0.510372 -0.809015 0.291575 -0.279562 -0.959712 0.0282674 -0.268322 -0.963023 0.0242749 -0.245879 -0.967937 0.0513882 -0.216371 -0.976267 -0.00929797 -0.21038 -0.976143 0.0537047 -0.12677 -0.990339 0.0561876 -0.0975747 -0.993923 0.0509608 -0.0936961 -0.994762 0.0408581 -0.10916 -0.991754 0.0671493 -0.115637 -0.989701 0.0843808 -0.0395353 -0.999018 0.0200187 -0.053616 -0.998313 0.0222623 -0.0536162 -0.998313 0.0222628 -0.15981 -0.97979 0.120304 -0.150268 -0.983033 0.105194 -0.143295 -0.984498 0.101148 -0.127725 -0.989625 0.0658014 -0.210403 -0.976139 0.0536969 -0.24095 -0.947469 0.210346 -0.19775 -0.964585 0.174559 -0.205114 -0.962867 0.175544 -0.174046 -0.974452 0.141955 -0.175232 -0.974164 0.142473 -0.174696 -0.974423 0.141355 -0.161553 -0.979272 0.122175 -0.377891 -0.87332 0.307426 -0.308433 -0.908237 0.282798 -0.327271 -0.90322 0.277646 -0.266355 -0.931193 0.248867 -0.27933 -0.926544 0.251975 -0.270894 -0.932702 0.238085 -0.228097 -0.950423 0.211346 -0.538349 -0.842243 0.0284097 -0.552391 -0.824037 0.125806 -0.482724 -0.86791 0.117087 -0.481478 -0.86884 0.115311 -0.48268 -0.868135 0.115593 -0.438277 -0.892669 0.105146 -0.436713 -0.893334 0.106 -0.40063 -0.911485 0.0932242 -0.396167 -0.913278 0.0947349 -0.368002 -0.92625 0.0814612 -0.360837 -0.928902 0.0832932 -0.338125 -0.938558 0.0691376 -0.328529 -0.941866 0.0704143 -0.31351 -0.947813 0.0579788 -0.302835 -0.951323 0.057228 -0.294325 -0.954498 0.0480321 -0.282963 -0.958051 0.0454995 -0.281573 -0.958555 0.0434709 -0.274873 -0.960778 0.0367455 -0.272046 -0.961743 0.0322779 -0.412408 -0.841872 0.348097 -0.412414 -0.841869 0.348096 -0.432832 -0.833711 0.342902 -0.415579 -0.847097 0.331241 -0.356658 -0.878763 0.317128 0.0122485 0.978375 -0.206478 0.000206735 0.996738 -0.0807107 0 0.999997 -0.00236686 -0.00526066 0.537315 -0.843365 0.0190502 0.706979 -0.706978 0.083448 0.564189 -0.821418 0.0133181 0.734033 -0.678984 0.0014156 0.830149 -0.557539 -0.00346866 0.911498 -0.411289 -0.00341748 0.96592 -0.258818 0.0438671 0.925496 -0.376209 0.0438678 0.925495 -0.376211 0.0811425 0.103341 -0.991331 0.0104605 0.326301 -0.945208 -0.00526066 0.537312 -0.843367 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0.00126717 -0.386104 -0.922454 0.0337905 -0.258671 -0.965374 0.029149 -0.242418 -0.969734 0 -0.103683 -0.99461 0.0189508 -0.738186 -0.674331 0.0533327 -0.622664 -0.780669 0.0139228 -0.707039 -0.707037 -0.00135365 -0.603622 -0.79727 -0.00135365 -0.603564 -0.797314 0.000375258 -0.989496 -0.144563 0 -0.999997 -0.00236686 0.0361098 -0.942185 -0.333143 0.0917636 -0.864501 -0.494184 0.00854636 -0.965891 -0.25881 -0.00503923 -0.831732 -0.555155 -0.00503923 -0.831729 -0.55516 0.0881844 0.0666217 -0.993874 0.140987 0.397092 -0.906885 0.140991 0.397092 -0.906884 0.165921 0.10996 -0.979989 0.0747539 0.210541 -0.974723 0.0764424 0.195464 -0.977727 0.178542 0.650457 -0.738261 0.204949 0.62663 -0.751885 0.263338 0.348513 -0.899551 0.237202 0.383818 -0.892423 0.284098 -7.83285e-05 -0.958795 0.28011 0.0482844 -0.958753 0.258242 -0.00062995 -0.96608 0.194992 0.0669934 -0.978514 0.221899 0.0483559 -0.97387 0.17845 0.414784 -0.89225 0.293307 0.382539 -0.876148 0.262046 0.738013 -0.621827 0.262035 0.738014 -0.621831 0.496445 -0.32987 -0.80295 0.168699 0.934486 -0.313491 0.168703 0.934483 -0.313499 0.221959 0.973911 -0.0472438 0.619874 0.773394 -0.132735 0.889957 0.414052 -0.191147 0.977093 -0.0300181 -0.210687 0.892225 0.411004 -0.187108 0.870202 0.411041 -0.27165 0.870306 0.410921 -0.2715 0.813995 0.408837 -0.412632 0.803748 0.424345 -0.417038 0.729156 0.426288 -0.53536 0.71411 0.439597 -0.544795 0.978249 -0.0346609 -0.20452 0.953988 -0.0346659 -0.297834 0.954054 -0.0348443 -0.297601 0.892104 -0.0346372 -0.450501 0.887002 -0.0112442 -0.461629 0.80783 -0.0113074 -0.589307 0.793562 0.00926198 -0.608419 0.620927 -0.420221 -0.661713 0.716619 -0.422997 -0.554555 0.72551 -0.446744 -0.523503 0.793549 -0.44478 -0.415271 0.788349 -0.4714 -0.395333 0.840876 -0.47345 -0.262246 0.84089 -0.47324 -0.262579 0.862542 -0.47317 -0.179254 0.863667 -0.467916 -0.187441 0.639434 -0.331083 -0.693907 0.650549 -0.410147 -0.639191 0.67996 0.0855536 -0.728241 0.708293 0.00922635 -0.705858 0.598433 0.487009 -0.636161 0.633796 0.438021 -0.637527 0.222796 0.97375 -0.0466099 0.217256 0.973757 -0.0678006 0.217288 0.973751 -0.0677814 0.203937 0.973421 -0.104214 0.200067 0.974253 -0.103944 0.179906 0.974509 -0.134036 0.175739 0.975194 -0.134581 0.155321 0.974927 -0.159348 0.144438 0.977439 -0.154113 0.114403 0.977372 -0.177924 0.100887 0.980914 -0.166222 0.0893685 0.980991 -0.172248 0.0509694 0.980878 -0.187829 0.501521 -0.185469 -0.845031 0.540138 -0.241994 -0.806033 0.506572 0.201947 -0.838213 0.554883 0.0855567 -0.827517 0.432189 0.559097 -0.707547 0.482103 0.486952 -0.728323 0.621937 0.7721 -0.1306 0.606602 0.772129 -0.189344 0.606687 0.77208 -0.18927 0.568646 0.77013 -0.289035 0.559175 0.776801 -0.289662 0.505026 0.778509 -0.372657 0.493832 0.784089 -0.375945 0.437369 0.782649 -0.44291 0.408967 0.803206 -0.433135 0.326639 0.803094 -0.498344 0.289793 0.832609 -0.471998 0.206182 0.831949 -0.515121 0.335142 0.559169 -0.758294 0.272924 0.651253 -0.708084 0.401367 0.201995 -0.893366 0.33446 0.348366 -0.875659 0.397223 -0.000105553 -0.917722 0.397278 -0.000628482 -0.917698 0.368328 -0.18488 -0.911128 0.368317 -0.1849 -0.911128 0.856237 -0.466932 -0.220982 0.856236 -0.466933 -0.220981 0.856237 -0.466933 -0.220981 0.80385 -0.466933 -0.368509 0.803849 -0.466936 -0.368507 0.803847 -0.466939 -0.368507 0.726269 -0.466942 -0.504478 0.72627 -0.466934 -0.504484 0.726268 -0.466939 -0.504483 0.625925 -0.46694 -0.624648 0.625925 -0.46694 -0.624648 0.625932 -0.466924 -0.624652 0.505966 -0.466923 -0.725246 0.505968 -0.46694 -0.725233 0.505971 -0.466932 -0.725236 0.370146 -0.466932 -0.803098 0.370147 -0.46694 -0.803093 0.370151 -0.46693 -0.803097 0.222738 -0.46693 -0.855783 0.222734 -0.466913 -0.855793 0.222733 -0.466918 -0.855791 0.0683319 -0.466917 -0.881657 0.0683351 -0.466927 -0.881652 0.0683316 -0.466944 -0.881643 -0.0882125 -0.466943 -0.879876 -0.088211 -0.466947 -0.879875 -0.0882065 -0.466909 -0.879895 -0.241995 -0.46691 -0.850549 -0.241985 -0.466932 -0.85054 -0.241985 -0.466921 -0.850546 -0.388181 -0.466922 -0.794544 -0.388179 -0.466927 -0.794542 -0.388178 -0.466932 -0.794539 -0.522207 -0.466931 -0.713635 -0.522204 -0.466939 -0.713633 -0.522205 -0.466932 -0.713636 -0.639866 -0.466932 -0.610365 -0.639861 -0.466941 -0.610363 -0.639865 -0.466926 -0.610371 -0.737473 -0.466928 -0.487968 -0.737471 -0.466931 -0.487968 -0.737471 -0.466929 -0.487968 -0.811962 -0.466931 -0.350276 -0.811962 -0.466931 -0.350276 -0.883065 -0.466929 -0.0466148 -0.811962 -0.46693 -0.350276 -0.861005 -0.466933 -0.201603 -0.861004 -0.466935 -0.201604 -0.861006 -0.466931 -0.201605 -0.883064 -0.466931 -0.0466152 -0.844326 -0.466933 0.262844 -0.883065 -0.46693 -0.0466146 -0.877445 -0.466933 0.109836 -0.877445 -0.466932 0.109836 -0.877444 -0.466935 0.109836 -0.844325 -0.466935 0.262843 -0.70057 -0.466933 0.539607 -0.700567 -0.466938 0.539607 -0.844326 -0.466933 0.262844 -0.784745 -0.466934 0.407614 -0.784745 -0.466934 0.407614 -0.784741 -0.466939 0.407614 -0.700566 -0.466939 0.539606 -0.791882 -0.0299169 0.609941 -0.791879 -0.0299411 0.609943 -0.887029 -0.0299395 0.460742 -0.887029 -0.0299382 0.460742 -0.954376 -0.0299386 0.297103 -0.954376 -0.0299404 0.297103 -0.991812 -0.0299373 0.124152 -0.991812 -0.0299282 0.124151 -0.998162 -0.029933 -0.0526905 -0.998162 -0.0299394 -0.0526899 -0.973229 -0.0299344 -0.227881 -0.973229 -0.0299337 -0.227881 -0.917792 -0.0299369 -0.395931 -0.917793 -0.0299528 -0.395929 -0.833592 -0.0299567 -0.551569 -0.833591 -0.0299339 -0.551571 -0.723265 -0.0299331 -0.689922 -0.723265 -0.0299297 -0.689922 -0.59027 -0.0299285 -0.806651 -0.590271 -0.0299419 -0.80665 -0.438772 -0.0299414 -0.898099 -0.438772 -0.0299353 -0.8981 -0.273525 -0.029936 -0.961399 -0.273528 -0.0299588 -0.961398 -0.0997092 -0.0299598 -0.994566 -0.0997056 -0.0299226 -0.994567 0.0772416 -0.0299222 -0.996563 0.0772399 -0.0299391 -0.996563 0.251762 -0.0299392 -0.967326 0.251763 -0.0299317 -0.967326 0.418394 -0.0299319 -0.907772 0.418395 -0.0299254 -0.907772 0.571918 -0.0299265 -0.819764 0.571917 -0.0299442 -0.819765 0.707511 -0.0299435 -0.706068 0.707512 -0.0299315 -0.706067 0.820933 -0.0299319 -0.570239 0.820933 -0.0299316 -0.570239 0.908625 -0.0299324 -0.416539 0.908625 -0.0299357 -0.416539 0.967839 -0.0299357 -0.249784 0.967839 -0.0299351 -0.249784 -0.721482 0.413085 0.55572 -0.721478 0.4131 0.555714 -0.808167 0.413098 0.41978 -0.808165 0.413105 0.419778 -0.869525 0.413103 0.270688 -0.869527 0.413098 0.27069 -0.903635 0.413097 0.113114 -0.90364 0.413086 0.113115 -0.909425 0.413089 -0.0480057 -0.909423 0.413092 -0.048006 -0.886708 0.413088 -0.207622 -0.886705 0.413095 -0.207622 -0.836197 0.413097 -0.360729 -0.836196 0.4131 -0.360729 -0.759479 0.413102 -0.502532 -0.759485 0.413088 -0.502535 -0.658966 0.413087 -0.628588 -0.658968 0.413083 -0.628589 -0.537798 0.41308 -0.734941 -0.537785 0.413114 -0.734931 -0.399759 0.413116 -0.818247 -0.399767 0.41309 -0.818256 -0.249211 0.41309 -0.875929 -0.24921 0.413091 -0.875928 -0.0908415 0.413091 -0.906148 -0.0908402 0.413099 -0.906144 0.0703728 0.4131 -0.907963 0.0703718 0.413087 -0.907969 0.229381 0.413087 -0.88133 0.229381 0.413069 -0.881339 0.381203 0.41307 -0.827078 0.381202 0.413082 -0.827072 0.521074 0.413083 -0.746889 0.521073 0.413093 -0.746885 0.644612 0.413093 -0.643296 0.644612 0.413095 -0.643295 0.74795 0.413094 -0.519543 0.747952 0.413087 -0.519545 0.827848 0.413088 -0.379509 0.827846 0.413093 -0.379507 0.881795 0.413092 -0.227578 0.881795 0.413093 -0.227578 -0.503071 0.772511 0.387488 -0.50307 0.772513 0.387486 -0.563516 0.772512 0.292702 -0.56352 0.772509 0.292705 -0.606304 0.772509 0.188747 -0.6063 0.772513 0.188744 -0.630083 0.772512 0.0788722 -0.630083 0.772512 0.0788722 -0.634117 0.772512 -0.0334733 -0.634117 0.772512 -0.0334733 -0.618275 0.772514 -0.14477 -0.61828 0.77251 -0.14477 -0.583063 0.772509 -0.25153 -0.583064 0.772508 -0.25153 -0.529573 0.772507 -0.350407 -0.529565 0.772514 -0.350403 -0.459476 0.772515 -0.438294 -0.459474 0.772517 -0.438293 -0.374984 0.772518 -0.512448 -0.374997 0.772503 -0.512462 -0.278752 0.772502 -0.570559 -0.278749 0.772507 -0.570554 -0.173769 0.772507 -0.610767 -0.173767 0.772513 -0.61076 -0.0633406 0.772513 -0.631832 -0.0633435 0.772503 -0.631844 0.0490691 0.772503 -0.633112 0.0490692 0.772504 -0.633111 0.159942 0.772504 -0.614537 0.159941 0.772515 -0.614524 0.2658 0.772514 -0.576691 0.265797 0.772522 -0.576681 0.363324 0.772521 -0.520775 0.363332 0.772508 -0.520789 0.449475 0.772509 -0.448557 0.449473 0.772511 -0.448554 0.521527 0.772511 -0.362265 0.521526 0.772512 -0.362264 0.577236 0.772512 -0.264621 0.577237 0.772511 -0.264622 0.614855 0.772511 -0.158684 0.614851 0.772514 -0.158683 -0.180276 0.973766 0.138856 -0.180274 0.973766 0.138855 -0.201935 0.973766 0.104889 -0.201935 0.973766 0.104889 -0.217266 0.973766 0.0676362 -0.217269 0.973766 0.0676373 -0.225791 0.973766 0.0282639 -0.225789 0.973766 0.0282636 -0.227236 0.973766 -0.0119951 -0.227235 0.973766 -0.0119952 -0.22156 0.973766 -0.0518781 -0.221558 0.973766 -0.0518779 -0.208937 0.973767 -0.0901339 -0.208937 0.973767 -0.0901338 -0.189768 0.973767 -0.125566 -0.18977 0.973766 -0.125567 -0.164654 0.973766 -0.157063 -0.164656 0.973765 -0.157065 -0.134379 0.973765 -0.183639 -0.134375 0.973767 -0.183635 -0.099887 0.973767 -0.204453 -0.0998876 0.973767 -0.204454 -0.0622686 0.973767 -0.218864 -0.0622678 0.973767 -0.218862 -0.0226982 0.973767 -0.226412 -0.0226987 0.973767 -0.226415 0.0175835 0.973767 -0.226869 0.0175836 0.973767 -0.226866 0.0573136 0.973767 -0.22021 0.0573142 0.973766 -0.220214 0.0952494 0.973766 -0.206656 0.0952512 0.973765 -0.206662 0.130201 0.973765 -0.186626 0.130198 0.973766 -0.186621 0.161067 0.973766 -0.160738 0.161068 0.973766 -0.160739 0.186889 0.973766 -0.129817 0.186888 0.973766 -0.129817 0.206851 0.973766 -0.0948265 0.206851 0.973766 -0.0948261 0.220331 0.973766 -0.0568638 0.220333 0.973766 -0.0568646 -0.748833 -0.661526 0.0404099 -0.748039 -0.662514 0.0388973 -0.975918 -0.211767 0.0523274 -0.975764 -0.212773 0.0511083 -0.955205 0.291505 0.0510744 -0.955466 0.290796 0.0502215 -0.691876 0.721071 0.0369507 -0.692226 0.720758 0.0364732 -0.25213 0.967599 0.013499 -0.252293 0.967559 0.0133476 -0.744679 -0.655506 0.125559 -0.740814 -0.661555 0.116361 -0.965329 -0.205654 0.160769 -0.965152 -0.211762 0.15375 -0.942405 0.295795 0.156136 -0.944506 0.291487 0.151473 -0.681661 0.72294 0.112677 -0.684078 0.721036 0.1102 -0.248212 0.967829 0.0412063 -0.249268 0.967588 0.0404714 -0.239251 0.967511 0.0817363 -0.233849 0.968797 0.0821379 -0.656047 0.721269 0.222203 -0.643726 0.731399 0.225105 -0.905566 0.294531 0.305289 -0.894916 0.317125 0.313939 -0.928263 -0.204776 0.310475 -0.928777 -0.172883 0.32785 -0.718703 -0.654002 0.236106 -0.670435 -0.621208 0.405731 -0.670627 -0.621223 0.40539 -0.737286 -0.621895 0.263925 -0.704191 -0.564564 0.430561 -0.6855 -0.62041 0.381027 -0.850834 -0.11761 0.512103 -0.856987 -0.173112 0.485392 -0.802284 0.355671 0.479414 -0.823321 0.317475 0.470481 -0.56975 0.748472 0.339373 -0.590923 0.731778 0.339574 -0.205399 0.970909 0.123076 -0.214223 0.968832 0.124394 -0.670801 -0.468132 0.57522 -0.652466 -0.564699 0.505375 -0.763942 -0.0300045 0.644587 -0.779328 -0.117638 0.615474 -0.697935 0.414039 0.584345 -0.730796 0.355722 0.58258 -0.486733 0.773354 0.406221 -0.517279 0.748492 0.414948 -0.173705 0.97391 0.146031 -0.185998 0.970878 0.150996 -0.748606 -0.663016 0 -0.748606 -0.663016 0 -0.977041 -0.213052 0 -0.977041 -0.213052 0 -0.956673 0.291163 0 -0.956673 0.291163 0 -0.692687 0.721238 0 -0.692687 0.721238 0 -0.252315 0.967645 0 -0.252315 0.967645 0 -0.976942 -0.21303 -0.0142113 -0.956493 0.291108 -0.019422 -0.692555 0.7211 -0.0195564 -0.20388 0.843026 -0.497735 -0.244574 0.869855 -0.42841 -0.20658 0.901425 -0.38047 -0.241082 0.927406 -0.286003 -0.235076 0.936797 -0.259135 -0.264471 0.953429 -0.145011 -0.247512 0.960195 -0.129476 -0.252594 0.967436 -0.0162582 -0.252288 0.967541 -0.0146706 -0.144284 0.772588 -0.618296 -0.144265 0.772588 -0.6183 -0.205021 0.81976 -0.534752 -0.696189 -0.695458 -0.177932 -0.705205 -0.688608 -0.168835 -0.70208 -0.692387 -0.166387 -0.713895 -0.684131 -0.149396 -0.712159 -0.685799 -0.150033 -0.727126 -0.675015 -0.12507 -0.724268 -0.67815 -0.124695 -0.737398 -0.669647 -0.0884195 -0.736324 -0.670687 -0.0894839 -0.747684 -0.662462 -0.0459563 -0.746727 -0.663508 -0.04644 -0.748614 -0.662985 -0.00522526 -0.748595 -0.663006 -0.00532808 -0.695087 -0.694875 -0.184401 -0.694717 -0.696225 -0.180662 -0.697552 -0.694058 -0.178058 -0.235439 0.737971 -0.63243 -0.172142 0.692878 -0.700205 -0.169927 0.658814 -0.732863 -0.126981 0.624683 -0.770485 -0.187549 0.525439 -0.829903 -0.976922 -0.213102 -0.0145245 -0.968712 -0.214656 -0.12458 -0.967387 -0.219273 -0.126817 -0.94019 -0.240759 -0.240992 -0.938261 -0.244461 -0.244754 -0.900959 -0.267335 -0.341768 -0.896445 -0.280948 -0.342715 -0.85722 -0.310333 -0.410935 -0.853228 -0.317061 -0.414095 -0.814064 -0.343503 -0.4683 -0.808668 -0.363794 -0.462288 -0.775952 -0.38934 -0.496299 -0.771283 -0.397725 -0.496927 -0.742819 -0.418872 -0.52227 -0.739032 -0.443683 -0.50693 -0.703913 -0.472946 -0.529934 -0.702541 -0.49834 -0.508029 -0.677636 -0.520914 -0.519094 -0.6803 -0.547487 -0.487289 -0.956524 0.290953 -0.0201832 -0.943283 0.285041 -0.170203 -0.945064 0.275177 -0.17644 -0.909999 0.248974 -0.331533 -0.908398 0.240149 -0.34226 -0.856375 0.206761 -0.47315 -0.858211 0.175454 -0.48238 -0.805596 0.136746 -0.576468 -0.800364 0.120345 -0.587312 -0.743822 0.081558 -0.663383 -0.74763 0.0326324 -0.663313 -0.699959 -0.00444314 -0.714169 -0.693656 -0.0246971 -0.719883 -0.6472 -0.0592878 -0.760011 -0.656293 -0.119674 -0.744954 -0.591158 -0.173893 -0.787587 -0.604299 -0.234636 -0.761425 -0.548548 -0.285096 -0.786012 -0.569448 -0.347424 -0.745001 -0.695087 -0.694875 -0.184396 -0.698748 -0.691829 -0.182001 -0.698787 -0.691761 -0.182107 -0.710267 -0.68132 -0.176983 -0.709278 -0.683673 -0.171802 -0.725492 -0.66739 -0.16808 -0.724771 -0.671 -0.15642 -0.673893 -0.582945 -0.45392 -0.658168 -0.569609 -0.4923 -0.668486 -0.589094 -0.453976 -0.519936 -0.397134 -0.756274 -0.545618 -0.450278 -0.706789 -0.381902 -0.252703 -0.888984 -0.692716 0.720909 -0.0208346 -0.681579 0.711236 -0.172027 -0.690309 0.70001 -0.182921 -0.653789 0.676904 -0.338175 -0.655425 0.66547 -0.357166 -0.604902 0.629733 -0.48737 -0.623305 0.590146 -0.513048 -0.569681 0.553005 -0.607988 -0.566974 0.529935 -0.630642 -0.509398 0.48835 -0.70854 -0.535168 0.420626 -0.732577 -0.484056 0.382096 -0.787206 -0.479431 0.352087 -0.803854 -0.427464 0.312219 -0.848406 -0.46166 0.222528 -0.858692 -0.380576 0.155066 -0.911656 -0.418111 0.0608706 -0.906354 -0.34246 -0.00772569 -0.939501 -0.389883 -0.107893 -0.914522 -0.313517 -0.184459 -0.931494 -0.36825 -0.268717 -0.890047 -0.0873898 0.441218 -0.893135 -0.16454 0.398191 -0.902425 -0.170375 0.345675 -0.922757 -0.0895082 0.272019 -0.95812 -0.16274 0.142358 -0.976345 -0.0801166 0.0592006 -0.995026 -0.153717 -0.062643 -0.986127 -0.74155 -0.652406 -0.156427 -0.763669 -0.606707 -0.220718 -0.660183 -0.598378 -0.453984 -0.331958 -0.309782 -0.890977 -0.33195 -0.309775 -0.890982 -0.548294 -0.447163 -0.706696 -0.117455 -0.103336 -0.987687 -0.725208 -0.638039 -0.258804 -0.760968 -0.595045 -0.258551 -0.760968 -0.595045 -0.258553 -0.80269 -0.537351 -0.258732 -0.80269 -0.537352 -0.25873 -0.840093 -0.476858 -0.258553 -0.840094 -0.476855 -0.258556 -0.840096 -0.476855 -0.25855 -0.881126 -0.395942 -0.258548 -0.881125 -0.39594 -0.258553 -0.881129 -0.395933 -0.258552 -0.914524 -0.311127 -0.258545 -0.914525 -0.311128 -0.258542 -0.935176 -0.241881 -0.258727 -0.935175 -0.24188 -0.258731 -0.950542 -0.172103 -0.258554 -0.950542 -0.172102 -0.258555 -0.950541 -0.172103 -0.258558 -0.962518 -0.0819003 -0.258555 -0.96252 -0.0819012 -0.25855 -0.965954 0.00921473 -0.258549 -0.965953 0.00923135 -0.258553 -0.965953 0.00923142 -0.258553 -0.962463 0.082003 -0.258728 -0.962464 0.0820042 -0.258724 -0.962464 0.0820024 -0.258725 -0.953655 0.153917 -0.258555 -0.953654 0.153918 -0.258559 -0.935063 0.2425 -0.258557 -0.935065 0.242502 -0.258547 -0.935064 0.242499 -0.258551 -0.907979 0.329738 -0.258547 -0.880798 0.396552 -0.258731 -0.880799 0.396554 -0.258725 -0.907979 0.329738 -0.258547 -0.880799 0.39655 -0.258732 -0.848965 0.460876 -0.258556 -0.848967 0.460876 -0.258551 -0.802075 0.538354 -0.258555 -0.802074 0.538353 -0.258559 -0.802074 0.538355 -0.258556 -0.748025 0.611239 -0.258545 -0.748025 0.611237 -0.25855 -0.748023 0.611236 -0.258558 -0.54787 0.447684 -0.706695 -0.547858 0.447674 -0.706711 -0.587437 0.394288 -0.706721 -0.587436 0.394288 -0.706722 -0.621782 0.337546 -0.706718 -0.621785 0.337546 -0.706715 -0.644894 0.290345 -0.706973 -0.644894 0.290345 -0.706974 -0.665006 0.241502 -0.706713 -0.66501 0.241503 -0.706709 -0.684843 0.177607 -0.706715 -0.68484 0.177607 -0.706718 -0.698454 0.112729 -0.706721 -0.698457 0.112729 -0.706718 -0.704693 0.0600403 -0.706967 -0.704692 0.0600406 -0.706968 -0.707471 0.00676098 -0.70671 -0.70747 0.0067611 -0.706711 -0.704953 -0.0599842 -0.706713 -0.704956 -0.059985 -0.70671 -0.69618 -0.126049 -0.706714 -0.696177 -0.126048 -0.706717 -0.684705 -0.177098 -0.706976 -0.684703 -0.177097 -0.706978 -0.669806 -0.227873 -0.706707 -0.669804 -0.227872 -0.706708 -0.645336 -0.289987 -0.706718 -0.645335 -0.289986 -0.706718 -0.615283 -0.349248 -0.70672 -0.615281 -0.349247 -0.706722 -0.5877 -0.39343 -0.706981 -0.5877 -0.393429 -0.706981 -0.557332 -0.435809 -0.706719 -0.557333 -0.435811 -0.706717 -0.547947 -0.447129 -0.706986 -0.660181 -0.598375 -0.453992 -0.547854 0.447671 -0.706716 -0.547854 0.447672 -0.706715 -0.200632 0.163944 -0.965852 -0.220242 -0.140573 -0.965263 -0.204088 -0.159588 -0.965857 -0.204088 -0.159588 -0.965857 -0.215139 -0.144023 -0.965905 -0.215139 -0.144022 -0.965905 -0.225307 -0.127889 -0.965858 -0.225309 -0.127891 -0.965857 -0.236314 -0.10619 -0.965857 -0.236313 -0.106189 -0.965857 -0.245276 -0.0834447 -0.965855 -0.245277 -0.0834455 -0.965855 -0.250649 -0.06483 -0.965905 -0.250649 -0.0648299 -0.965905 -0.25493 -0.0461571 -0.965857 -0.254931 -0.0461573 -0.965857 -0.258145 -0.0219655 -0.965856 -0.258145 -0.0219655 -0.965856 -0.259067 0.00247579 -0.965856 -0.259069 0.00247562 -0.965856 -0.25797 0.0219792 -0.965903 -0.257969 0.0219792 -0.965903 -0.255764 0.04128 -0.965857 -0.255764 0.04128 -0.965858 -0.25078 0.0650371 -0.965857 -0.250781 0.0650372 -0.965857 -0.24352 0.0884362 -0.965856 -0.243516 0.0884354 -0.965857 -0.236076 0.106286 -0.965904 -0.236076 0.106286 -0.965904 -0.227688 0.123605 -0.965857 -0.22769 0.123605 -0.965857 -0.215111 0.144383 -0.965858 -0.215109 0.144382 -0.965858 -0.200619 0.163932 -0.965856 -0.200612 0.163927 -0.965859 -0.21243 -0.838149 -0.502375 -0.184864 -0.480397 -0.857347 -0.168256 -0.289831 -0.942172 -0.714012 0.677918 -0.174971 -0.741698 0.650566 -0.163243 -0.71658 0.647709 -0.258814 -0.524116 0.412894 -0.744863 -0.55934 0.434102 -0.706183 -0.667308 0.56771 -0.482085 -0.51544 0.484213 -0.707007 -0.73157 0.630747 -0.258775 -0.073217 -0.00367519 -0.997309 -0.245931 0.112287 -0.962761 -0.327886 0.205155 -0.922173 -0.22448 0.137002 -0.9648 -0.550445 0.44464 -0.706615 -0.714014 0.677915 -0.174972 -0.069789 -0.197427 -0.97783 -0.178233 -0.112004 -0.977593 -0.322039 0.0677389 -0.9443 -0.397064 0.132883 -0.90812 -0.530847 0.324691 -0.7828 -0.571591 0.363225 -0.735766 -0.66758 0.538301 -0.514362 -0.68158 0.552793 -0.479446 -0.713026 0.680032 -0.170732 -0.713918 0.679704 -0.168296 -0.0816765 -0.391754 -0.916437 -0.189722 -0.31081 -0.931345 -0.352891 -0.0977821 -0.930541 -0.42555 -0.0290334 -0.904469 -0.567394 0.213084 -0.795399 -0.603883 0.256449 -0.754691 -0.690352 0.490767 -0.531566 -0.700459 0.507596 -0.501701 -0.701266 0.689509 -0.181116 -0.701292 0.689807 -0.179878 -0.0985171 -0.570378 -0.815453 -0.136739 -0.572185 -0.808645 -0.396889 -0.263532 -0.879221 -0.467812 -0.195707 -0.861888 -0.620471 0.0940886 -0.778565 -0.653177 0.139897 -0.744169 -0.726915 0.435721 -0.530793 -0.733748 0.453744 -0.505698 -0.694967 0.695738 -0.181574 -0.695224 0.694656 -0.18471 -0.135903 -0.678687 -0.721744 -0.205569 -0.655437 -0.726735 -0.456048 -0.372929 -0.80805 -0.500937 -0.344643 -0.793904 -0.682204 0.00998858 -0.731093 -0.702984 0.0307309 -0.710541 -0.768405 0.392301 -0.505622 -0.772966 0.400366 -0.492169 -0.696602 0.695312 -0.176885 -0.696687 0.694398 -0.180107 -0.148266 -0.788503 -0.596892 -0.239809 -0.754882 -0.610447 -0.50411 -0.49586 -0.707104 -0.560648 -0.451158 -0.694357 -0.745823 -0.0910577 -0.659891 -0.769066 -0.0562721 -0.636688 -0.819177 0.33692 -0.464148 -0.82197 0.351298 -0.44828 -0.704832 0.690644 -0.161934 -0.70609 0.688169 -0.166914 -0.191322 -0.849286 -0.492046 -0.216968 -0.85624 -0.468805 -0.569583 -0.56698 -0.595071 -0.594466 -0.560761 -0.57633 -0.813788 -0.151431 -0.561087 -0.825369 -0.145205 -0.545603 -0.86701 0.300598 -0.39741 -0.869606 0.303205 -0.389681 -0.716387 0.683162 -0.141704 -0.716308 0.682698 -0.144317 -0.205325 -0.907599 -0.366205 -0.26272 -0.89603 -0.357923 -0.612718 -0.643126 -0.45931 -0.646988 -0.620017 -0.44383 -0.869327 -0.221912 -0.441617 -0.88222 -0.201337 -0.425619 -0.913336 0.256437 -0.316317 -0.913816 0.265738 -0.307122 -0.729246 0.674968 -0.11233 -0.730629 0.672958 -0.115363 -0.234996 -0.941143 -0.242955 -0.249269 -0.942065 -0.224454 -0.659905 -0.685439 -0.307732 -0.669046 -0.683415 -0.292098 -0.919393 -0.258085 -0.296832 -0.923413 -0.255695 -0.286231 -0.948591 0.234342 -0.212739 -0.949301 0.235437 -0.208319 -0.739698 0.668585 -0.0764267 -0.739784 0.668317 -0.0779147 -0.250791 -0.961792 -0.109815 -0.266409 -0.9585 -0.101512 -0.685819 -0.714071 -0.140553 -0.694603 -0.706969 -0.133123 -0.947719 -0.288428 -0.136519 -0.950473 -0.281815 -0.131077 -0.972297 0.212038 -0.0983847 -0.971853 0.215208 -0.0958509 -0.748124 0.662617 -0.0353473 -0.748708 0.66192 -0.036034 -0.252317 -0.967645 0 -0.252317 -0.967645 0 -0.692695 -0.721231 0 -0.692695 -0.721231 0 -0.956676 -0.291154 0 -0.956676 -0.291154 0 -0.977037 0.213071 0 -0.977037 0.213071 0 -0.748591 0.663032 0 -0.748591 0.663032 0 -0.670803 0.468137 0.575214 -0.704179 0.564573 0.430569 -0.252151 -0.967596 0.0133424 -0.252294 -0.967556 0.0135068 -0.69192 -0.721053 0.0364626 -0.692221 -0.720737 0.0369785 -0.955257 -0.291482 0.0502254 -0.955427 -0.290773 0.051099 -0.97598 0.211774 0.0511367 -0.975698 0.212779 0.0523274 -0.248404 -0.967816 0.0403387 -0.249174 -0.967575 0.0413665 -0.682198 -0.722857 0.109923 -0.683708 -0.720953 0.113005 -0.943217 -0.29571 0.151318 -0.943742 -0.2914 0.156322 -0.966435 0.205599 0.154056 -0.964066 0.211703 0.160495 -0.234739 -0.968744 0.080201 -0.238791 -0.967449 0.0837909 -0.646234 -0.731046 0.218983 -0.65431 -0.720887 0.228473 -0.898683 -0.316757 0.303371 -0.902092 -0.294161 0.315752 -0.933829 0.172629 0.313308 -0.923397 0.204442 0.324872 -0.670443 0.62123 0.405684 -0.74411 0.620969 0.246371 -0.713489 0.652965 0.254105 -0.746187 0.655306 0.117381 -0.739663 0.661339 0.12462 -0.748932 0.661501 0.0389593 -0.747981 0.662491 0.0403756 -0.20727 -0.970852 0.12036 -0.212861 -0.968756 0.127288 -0.575266 -0.748075 0.330837 -0.586413 -0.731308 0.348293 -0.811131 -0.355216 0.464638 -0.815078 -0.316991 0.484937 -0.862917 0.117408 0.491518 -0.845368 0.172764 0.505476 -0.7002 0.597093 0.391408 -0.670422 0.621228 0.405721 -0.176342 -0.973863 0.143155 -0.183876 -0.970807 0.154022 -0.494596 -0.773012 0.397275 -0.510562 -0.748054 0.42396 -0.710804 -0.413615 0.568929 -0.718968 -0.355232 0.597407 -0.781685 0.0299768 0.622953 -0.762601 0.117417 0.636123 -0.657412 0.554324 0.510425 -0.631852 0.563567 0.532124 -0.861001 0.466939 -0.201608 -0.811956 0.466941 -0.350277 -0.73747 0.466928 -0.487972 -0.639862 0.466932 -0.61037 -0.522203 0.466935 -0.713635 -0.388172 0.466945 -0.794534 -0.24198 0.466935 -0.850539 -0.0882069 0.466943 -0.879877 0.505971 0.466925 -0.725241 0.625934 0.466925 -0.624651 0.726272 0.466927 -0.504489 0.803851 0.466936 -0.368503 0.856236 0.466932 -0.220984 -0.529572 -0.772507 -0.35041 -0.180277 -0.973766 0.138855 -0.201936 -0.973766 0.104888 -0.217269 -0.973766 0.0676355 -0.225788 -0.973766 0.0282624 -0.227235 -0.973766 -0.0119964 0.206851 -0.973766 -0.0948265 0.220333 -0.973766 -0.0568644 -0.189769 -0.973766 -0.125567 -0.189769 -0.973766 -0.125568 -0.164653 -0.973766 -0.157064 -0.836195 -0.413097 -0.360734 -0.583063 -0.772508 -0.251533 -0.583062 -0.772509 -0.251532 -0.208938 -0.973766 -0.0901355 -0.208939 -0.973766 -0.0901363 -0.973228 0.0299338 -0.227886 -0.886704 -0.413095 -0.207626 -0.886705 -0.413094 -0.207626 -0.618279 -0.77251 -0.144773 -0.618275 -0.772514 -0.144771 -0.221559 -0.973766 -0.051879 -0.221558 -0.973766 -0.0518785 0.418398 0.029955 -0.90777 0.220333 -0.973766 -0.0568645 0.614855 -0.772511 -0.158684 0.614851 -0.772514 -0.158684 0.881794 -0.413096 -0.227578 0.881795 -0.413093 -0.227578 0.967839 0.0299357 -0.249784 0.967839 0.0299351 -0.249784 0.856235 0.466936 -0.220981 0.856235 0.466936 -0.220981 0.206854 -0.973766 -0.0948272 0.577236 -0.772512 -0.26462 0.577238 -0.772511 -0.264621 0.827847 -0.413091 -0.379507 0.827844 -0.413096 -0.379506 0.908625 0.0299362 -0.416538 0.908625 0.0299357 -0.416538 0.803853 0.466928 -0.368508 0.803852 0.46693 -0.368508 0.186888 -0.973766 -0.129817 0.521529 -0.77251 -0.362265 0.521527 -0.772512 -0.362264 0.747949 -0.413097 -0.519542 0.747952 -0.41309 -0.519543 0.820934 0.0299507 -0.570238 0.820933 0.029935 -0.570239 0.726273 0.466927 -0.504486 0.726271 0.466933 -0.504484 0.449474 -0.77251 -0.448555 0.644614 -0.41309 -0.643295 0.644611 -0.413097 -0.643294 0.707513 0.0299404 -0.706066 0.707513 0.0299547 -0.706065 0.625932 0.466926 -0.624651 0.625934 0.466921 -0.624653 0.521073 -0.413091 -0.746886 0.571918 0.0299535 -0.819764 0.571917 0.0299419 -0.819765 0.505969 0.466933 -0.725238 0.505971 0.466924 -0.725242 0.0683328 0.466942 -0.881644 0.222733 0.466942 -0.855778 0.251766 0.0299321 -0.967325 0.418396 0.0299328 -0.907771 0.381197 -0.413107 -0.827062 0.521068 -0.413106 -0.746881 0.363324 -0.77252 -0.520777 0.449465 -0.772519 -0.448548 0.161068 -0.973766 -0.160739 0.186888 -0.973766 -0.129817 0.222734 0.46692 -0.855789 0.222736 0.46693 -0.855783 0.370153 0.46693 -0.803096 0.370154 0.466918 -0.803103 0.370157 0.466933 -0.803093 0.161071 -0.973765 -0.160741 0.130202 -0.973765 -0.186626 0.363332 -0.772511 -0.520785 0.265802 -0.77251 -0.576695 0.3812 -0.413095 -0.827066 0.229384 -0.413095 -0.881326 0.251767 0.0299391 -0.967325 0.0772417 0.0299391 -0.996563 0.0683344 0.466947 -0.881641 0.0683352 0.466943 -0.881643 0.130202 -0.973765 -0.186626 0.0952519 -0.973765 -0.206661 0.265807 -0.772503 -0.576703 0.159947 -0.772502 -0.614538 0.229385 -0.413087 -0.881329 0.0703734 -0.413087 -0.907969 0.0772401 0.0299222 -0.996563 -0.0997062 0.0299226 -0.994567 -0.0882086 0.466939 -0.879879 -0.0882082 0.466935 -0.879881 0.095249 -0.973766 -0.206656 0.0573146 -0.973766 -0.220214 0.15994 -0.772517 -0.614521 0.0490679 -0.772517 -0.633095 0.0703715 -0.4131 -0.907963 -0.0908382 -0.4131 -0.906144 -0.0997023 0.0299599 -0.994566 -0.273522 0.0299589 -0.961399 -0.241983 0.466929 -0.850542 -0.241984 0.466946 -0.850533 0.0573159 -0.973765 -0.220217 0.0175846 -0.973766 -0.226873 0.0490716 -0.772503 -0.633112 -0.0633398 -0.772503 -0.631844 -0.0908377 -0.413091 -0.906148 -0.249208 -0.413091 -0.875929 -0.273525 0.0299359 -0.961399 -0.43877 0.0299353 -0.898101 -0.388172 0.466946 -0.794534 -0.388173 0.466935 -0.79454 0.0175838 -0.973767 -0.226869 -0.0226977 -0.973767 -0.226415 -0.0633402 -0.772513 -0.631832 -0.173766 -0.772513 -0.610761 -0.249208 -0.41309 -0.875929 -0.399765 -0.41309 -0.818257 -0.438772 0.0299081 -0.8981 -0.590268 0.0299106 -0.806653 -0.522202 0.466936 -0.713635 -0.522203 0.466932 -0.713637 -0.0226978 -0.973767 -0.226412 -0.0622673 -0.973767 -0.218862 -0.173767 -0.772507 -0.610769 -0.278748 -0.772507 -0.570555 -0.399765 -0.413088 -0.818258 -0.537791 -0.413088 -0.734941 -0.590266 0.0299283 -0.806654 -0.723262 0.0299297 -0.689925 -0.639863 0.46693 -0.61037 -0.639864 0.466926 -0.610372 -0.0622677 -0.973767 -0.218864 -0.0998869 -0.973767 -0.204454 -0.27875 -0.772502 -0.57056 -0.374993 -0.772503 -0.512464 -0.537793 -0.413075 -0.734947 -0.658967 -0.413078 -0.628594 -0.723262 0.0299332 -0.689925 -0.833589 0.0299339 -0.551574 -0.737468 0.466931 -0.487972 -0.737464 0.466944 -0.487966 -0.0998865 -0.973767 -0.204453 -0.134375 -0.973767 -0.183635 -0.374984 -0.772518 -0.512447 -0.459473 -0.772518 -0.438294 -0.658964 -0.413086 -0.62859 -0.759483 -0.413088 -0.502538 -0.833589 0.0299315 -0.551574 -0.917791 0.0299323 -0.395934 -0.811956 0.46694 -0.350277 -0.811956 0.46694 -0.350277 -0.134378 -0.973765 -0.18364 -0.164655 -0.973765 -0.157065 -0.459474 -0.772515 -0.438296 -0.529565 -0.772514 -0.350404 -0.759478 -0.413102 -0.502534 -0.836194 -0.4131 -0.360733 -0.917791 0.0299314 -0.395934 -0.973228 0.0299342 -0.227886 -0.861003 0.466935 -0.201608 -0.861002 0.466937 -0.201607 -0.883064 0.46693 -0.0466198 -0.227235 -0.973766 -0.0119963 -0.634117 -0.772512 -0.0334767 -0.634117 -0.772512 -0.0334766 -0.909422 -0.413094 -0.0480107 -0.909422 -0.413093 -0.0480107 -0.998162 0.0299394 -0.0526955 -0.998162 0.0299329 -0.0526949 -0.883062 0.466935 -0.0466185 -0.883061 0.466938 -0.0466191 -0.877445 0.466935 0.109831 -0.22579 -0.973766 0.0282624 -0.630086 -0.77251 0.0788685 -0.630083 -0.772512 0.0788685 -0.903636 -0.413096 0.11311 -0.903636 -0.413096 0.11311 -0.991812 0.0299373 0.124147 -0.991812 0.0299405 0.124146 -0.877445 0.466935 0.109831 -0.877445 0.466933 0.109831 -0.844327 0.466933 0.262839 -0.217265 -0.973767 0.0676348 -0.606305 -0.772509 0.188743 -0.606305 -0.772509 0.188743 -0.869527 -0.413103 0.270684 -0.869529 -0.413098 0.270684 -0.954378 0.0299386 0.297098 -0.954378 0.0299404 0.297097 -0.844329 0.466931 0.262839 -0.844327 0.466935 0.262838 -0.784743 0.466939 0.40761 -0.201938 -0.973765 0.104889 -0.563524 -0.772506 0.292702 -0.563521 -0.772509 0.292701 -0.80817 -0.413098 0.419775 -0.808167 -0.413105 0.419774 -0.887031 0.0299391 0.460738 -0.887031 0.0299382 0.460738 -0.784747 0.466932 0.40761 -0.784747 0.466934 0.407609 -0.700571 0.466938 0.539601 -0.180275 -0.973766 0.138854 -0.50307 -0.772513 0.387484 -0.50308 -0.772505 0.387489 -0.721479 -0.413107 0.555707 -0.721482 -0.4131 0.555709 -0.791885 0.0299368 0.609936 -0.791885 0.0299411 0.609935 -0.700569 0.466942 0.5396 -0.70057 0.466939 0.539602 0.351616 0.00405341 -0.936136 0.119621 -0.979888 -0.159719 0.24535 -0.768521 -0.590914 0.202318 -0.837517 -0.507576 0.865227 0.468064 -0.179718 0.97841 0.0300268 -0.204481 0.89085 -0.414128 -0.186774 0.620333 -0.773449 -0.130243 0.860826 0.473322 -0.186933 0.84098 0.473246 -0.262279 0.840779 0.473456 -0.262545 0.782147 0.470657 -0.408324 0.800467 0.444097 -0.40253 0.708717 0.446186 -0.546477 0.73399 0.422504 -0.531741 0.620927 0.420221 -0.661713 0.650549 0.410147 -0.639191 0.639434 0.331083 -0.693907 0.533419 0.331169 -0.778326 0.976934 0.0346711 -0.210709 0.95406 0.0346663 -0.297603 0.953982 0.0348447 -0.297833 0.886837 0.0345872 -0.460787 0.892352 0.0112285 -0.4512 0.794259 0.0112948 -0.607475 0.807328 -0.00925207 -0.590031 0.686927 -0.00919618 -0.726668 0.702574 -0.0852958 -0.706481 0.525866 -0.0852695 -0.846282 0.538499 -0.201336 -0.818219 0.621344 -0.772158 -0.133055 0.606628 -0.772131 -0.189252 0.606656 -0.772082 -0.189361 0.566804 -0.769839 -0.293395 0.561675 -0.776522 -0.285542 0.499812 -0.778283 -0.380084 0.499561 -0.78389 -0.36872 0.429198 -0.781968 -0.452012 0.418844 -0.802604 -0.424731 0.315164 -0.802395 -0.506789 0.303456 -0.832004 -0.464417 0.206975 -0.831989 -0.514738 0.119621 -0.979888 -0.159719 0.0893686 -0.980991 -0.172248 0.105365 -0.980839 -0.163869 0.110746 -0.977266 -0.180796 0.147686 -0.97736 -0.151515 0.152797 -0.974825 -0.162386 0.177593 -0.975169 -0.132314 0.178287 -0.974475 -0.136429 0.200913 -0.974214 -0.102669 0.203412 -0.973379 -0.105627 0.217278 -0.973752 -0.0678074 0.217263 -0.973757 -0.0677739 0.222596 -0.973759 -0.0473794 0.222091 -0.973919 -0.0464574 0.50151 0.185453 -0.845041 0.501521 0.185469 -0.845031 0.368317 0.1849 -0.911128 0.405517 0.112137 -0.907183 0.337723 -0.33855 -0.878252 0.368008 -0.20144 -0.90774 0.373201 -0.337862 -0.864043 0.279021 -0.640732 -0.715269 0.891268 -0.411082 -0.191451 0.870253 -0.411044 -0.271483 0.870252 -0.410924 -0.271665 0.810403 -0.408454 -0.420015 0.807722 -0.423965 -0.409681 0.719744 -0.42598 -0.548187 0.723909 -0.439311 -0.531942 0.619021 -0.437085 -0.65251 0.614852 -0.486086 -0.621029 0.461935 -0.485915 -0.741958 0.455151 -0.558058 -0.693836 0.311805 -0.558216 -0.768877 0.304418 -0.639563 -0.705896 0.206479 -0.644007 -0.736628 0.211583 -0.640742 -0.738026 0.216201 -0.644171 -0.73369 0.246386 -0.76848 -0.590536 0.134724 -0.352095 -0.926217 0.134724 -0.3521 -0.926216 0.264245 -0.338873 -0.902962 0.264269 -0.338738 -0.903005 0.21151 -0.640977 -0.737843 0.293577 -0.362324 -0.884609 0.25417 -0.362515 -0.896649 0.20052 -0.423839 -0.883262 0.125241 -0.390621 -0.911992 0.125239 -0.390621 -0.911993 0.0766715 -0.19605 -0.977592 0.0901736 -0.0672594 -0.993652 0.088503 -0.0663032 -0.993867 0.246805 -0.0665747 -0.966776 0.225068 -0.0184761 -0.974168 0.312506 -0.0184964 -0.949736 0.283324 0.00405462 -0.959016 -0.257893 0.0845376 0.962468 -0.705984 0.0563662 0.705981 -0.406387 -0.0424422 0.912715 -0.406367 -0.0424422 0.912724 -0.96439 0.0563703 0.258408 -0.951056 0 0.309018 -0.743144 0 0.669132 -0.962468 0.0845418 -0.257892 -0.993626 -0.0424419 -0.104434 -0.993626 -0.0424419 -0.104435 -0.704576 0.0845421 -0.704574 -0.864637 -0.0565999 -0.499199 -0.864638 -0.0565999 -0.499197 -0.258402 0.0563657 -0.964392 -0.587251 -0.0424449 -0.808291 -0.587253 -0.0424449 -0.80829 0.258402 0.0563655 -0.964392 0.20791 0 -0.978148 -0.20791 0 -0.978148 0.704577 0.0845413 -0.704574 0.587253 -0.0424455 -0.80829 0.587251 -0.0424455 -0.808291 0.962468 0.0845417 -0.257892 0.864637 -0.0566009 -0.499199 0.864637 -0.0566009 -0.499199 0.96439 0.0563692 0.258408 0.993626 -0.0424419 -0.104431 0.993626 -0.0424419 -0.104434 0.705984 0.0563662 0.705981 0.743144 0 0.669132 0.951056 0 0.309018 0 -0.0566056 0.998397 0 -0.0566056 0.998397 0.257893 0.0845373 0.962468 0.406367 -0.0424426 0.912724 0.406386 -0.0424426 0.912715 -0.258408 -0.0563638 0.96439 -0.58725 0.0424449 0.808292 -0.587253 0.0424449 0.80829 -0.704576 -0.0845421 0.704574 -0.864637 0.0565999 0.499199 -0.864638 0.0565999 0.499197 -0.962468 -0.0845408 0.257893 -0.993626 0.0424428 0.104434 -0.993626 0.0424428 0.104435 -0.96439 -0.0563721 -0.258407 -0.951056 0 -0.309018 -0.743144 0 -0.669132 -0.705984 -0.0563662 -0.705981 -0.406387 0.0424422 -0.912715 -0.406367 0.0424422 -0.912724 -0.257887 -0.0845427 -0.962469 0 0.0565969 -0.998397 0 0.0565969 -0.998397 0.257887 -0.0845424 -0.962469 0.406367 0.0424426 -0.912723 0.406386 0.0424426 -0.912715 0.705984 -0.0563662 -0.705981 0.743144 0 -0.669132 0.951056 0 -0.309018 0.96439 -0.0563711 -0.258407 0.993626 0.0424428 0.104431 0.993626 0.0424428 0.104434 0.962468 -0.0845409 0.257893 0.864637 0.0566009 0.499199 0.864637 0.0566009 0.499199 0.704577 -0.0845413 0.704574 0.587253 0.0424455 0.80829 0.58725 0.0424455 0.808292 0.258408 -0.0563636 0.96439 0.207918 0 0.978146 -0.207918 0 0.978146 0.420193 -0.699252 0.578346 0.420191 -0.699252 0.578347 0.6191 -0.699252 0.357438 0.6191 -0.699252 0.357437 0.6191 -0.699252 0.357438 0.710959 -0.699252 0.0747247 0.710959 -0.699252 0.0747248 0.710959 -0.699253 0.074723 0.679886 -0.699253 -0.220909 0.679886 -0.699252 -0.220909 0.531256 -0.699252 -0.478344 0.531255 -0.699253 -0.478345 0.290777 -0.699254 -0.653064 0.290765 -0.699252 -0.653072 0.290764 -0.699252 -0.653072 0 -0.699252 -0.714875 0 -0.699252 -0.714875 0 -0.699252 -0.714875 -0.290764 -0.699252 -0.653072 -0.290765 -0.699252 -0.653072 -0.290778 -0.699254 -0.653063 -0.531256 -0.699253 -0.478344 -0.531255 -0.699252 -0.478346 -0.679886 -0.699252 -0.220909 -0.679886 -0.699252 -0.22091 -0.710959 -0.699252 0.0747256 -0.710959 -0.699252 0.0747246 -0.710959 -0.699252 0.0747246 -0.6191 -0.699253 0.357436 -0.6191 -0.699252 0.357437 -0.6191 -0.699252 0.357438 -0.420192 -0.699252 0.578347 -0.420193 -0.699252 0.578346 -0.420188 -0.699253 0.578348 -0.148632 -0.699253 0.699252 -0.148635 -0.699252 0.699253 0.148633 -0.699252 0.699253 0.148635 -0.699253 0.699251 0.420188 -0.699253 0.578348 0.420192 0.699252 -0.578346 0.420191 0.699252 -0.578347 0.6191 0.699252 -0.357438 0.6191 0.699252 -0.357437 0.6191 0.699252 -0.357438 0.710959 0.699252 -0.0747247 0.710959 0.699252 -0.0747248 0.710959 0.699253 -0.0747229 0.679886 0.699253 0.220908 0.679886 0.699253 0.220909 0.531255 0.699253 0.478345 0.531255 0.699253 0.478345 0.290777 0.699254 0.653064 0.290765 0.699252 0.653072 0.290764 0.699252 0.653072 0 0.699252 0.714875 0 0.699252 0.714875 0 0.699252 0.714875 -0.290764 0.699252 0.653072 -0.290765 0.699252 0.653072 -0.290778 0.699254 0.653063 -0.531255 0.699253 0.478345 -0.531255 0.699253 0.478345 -0.679886 0.699253 0.220908 -0.679886 0.699252 0.22091 -0.710959 0.699252 -0.0747256 -0.710959 0.699252 -0.0747246 -0.710959 0.699252 -0.0747246 -0.6191 0.699253 -0.357436 -0.6191 0.699252 -0.357437 -0.6191 0.699252 -0.357438 -0.420192 0.699252 -0.578347 -0.420193 0.699252 -0.578346 -0.420189 0.699253 -0.578348 -0.14863 0.699253 -0.699253 -0.14863 0.699253 -0.699253 0.14863 0.699253 -0.699253 0.14863 0.699253 -0.699253 0.420189 0.699253 -0.578348 -0.0355746 -0.990095 -0.135814 -0.000652936 -1 0.000252705 -0.000647821 -1 0.000258391 0.0423329 -0.996482 -0.0723326 0.0907849 -0.989635 -0.111273 0.0754589 -0.992202 -0.0992045 0.0437598 -0.996013 -0.0777374 -0.00199051 -0.997892 -0.0648594 -0.0312568 -0.99452 -0.0997643 0.0140087 -0.99615 -0.0865391 -0.0355938 -0.990092 -0.135837 -0.17721 -0.983646 -0.0321938 -0.175633 -0.983602 -0.0409878 -0.180971 -0.98281 -0.0365363 -0.0205202 -0.97776 -0.208719 -0.169598 -0.984833 -0.0366105 -0.128435 -0.991633 0.0129485 -0.133635 -0.991027 -0.00263446 -0.120799 -0.992635 0.00915503 -0.0939987 -0.994728 0.0409872 -0.0939993 -0.994728 0.0409987 -0.0939962 -0.994729 0.0409874 -0.0915797 -0.995058 0.0383799 -0.00380793 -0.999992 -0.000827177 -0.0019332 -0.999997 0.00125953 -0.0756793 -0.870517 -0.486285 -0.135206 -0.831692 -0.538523 -0.138746 -0.830513 -0.539442 -0.1198 -0.845753 -0.519952 -0.0839099 -0.82431 -0.559885 -0.138745 -0.830513 -0.539442 -0.0900944 -0.867677 -0.488896 -0.0312125 -0.867254 -0.496886 -0.0842906 -0.861213 -0.501206 0.0391784 -0.893199 -0.447953 -0.0448485 -0.901066 -0.431357 -0.0448501 -0.901066 -0.431357 -0.275693 -0.949892 -0.147303 -0.083689 -0.918158 -0.387275 -0.0721097 -0.921627 -0.381318 -0.0131199 -0.942207 -0.334775 -0.063874 -0.92945 -0.363377 -0.040332 -0.96107 -0.273344 -0.0719102 -0.951944 -0.29771 -0.0578362 -0.970784 -0.232882 -0.0247681 -0.980024 -0.197334 -0.0521904 -0.96787 -0.245977 -0.135008 -0.975056 -0.176179 -0.163903 -0.969625 -0.181557 -0.14926 -0.976964 -0.152523 -0.185197 -0.968791 -0.164762 -0.172382 -0.977115 -0.124626 -0.203399 -0.968881 -0.14106 -0.181326 -0.975723 -0.122822 -0.208643 -0.968176 -0.138212 -0.200815 -0.975391 -0.0910285 -0.227064 -0.967413 -0.112047 -0.223046 -0.972582 -0.0658406 -0.24439 -0.965587 -0.0889662 -0.275703 -0.949891 -0.14729 -0.135123 -0.973895 -0.182404 -0.135128 -0.973894 -0.182404 -0.150738 -0.971175 -0.184654 -0.138448 -0.831532 -0.537947 -0.153044 -0.822667 -0.547537 -0.0752101 -0.977448 -0.197329 -0.0842915 -0.861213 -0.501206 -0.0997468 -0.848355 -0.519947 -0.121863 -0.972974 -0.196143 -0.103144 -0.975163 -0.196005 -0.108127 -0.973569 -0.201179 -0.0901373 -0.974939 -0.203395 -0.0891509 -0.975096 -0.203078 -0.0764649 -0.975705 -0.205314 -0.0690113 -0.977507 -0.199292 -0.000761035 -0.999999 -0.000693592 -0.0191337 -0.999302 -0.032098 -0.117477 -0.992837 -0.0217463 -0.0877957 -0.991356 -0.0974945 -0.087794 -0.991356 -0.0974915 -0.204654 -0.967131 -0.150913 -0.176555 -0.952577 -0.247841 -0.284416 -0.858027 -0.427665 -0.265681 -0.882591 -0.387874 -0.0378994 -0.829356 -0.557433 -0.0378913 -0.829372 -0.557411 -0.117112 -0.82184 -0.557551 -0.153518 -0.850962 -0.502291 0.00127462 -0.999997 -0.0021031 0.000283331 -0.999993 -0.00381967 -0.000757916 -0.999999 -0.000688201 0.0347027 -0.993881 -0.104867 -0.0241062 -0.996736 -0.0770516 0.00960773 -0.999775 -0.0188987 -0.0128241 -0.999911 -0.00360162 -0.00949242 -0.999946 -0.00414489 -0.0032974 -0.975555 -0.219732 -0.0291136 -0.973793 -0.225563 -0.0204661 -0.978936 -0.203141 0.0347058 -0.99388 -0.104868 -0.0573782 -0.942809 -0.328357 -0.0580406 -0.942935 -0.32788 -0.0583284 -0.942255 -0.329777 -0.198212 -0.936043 -0.29075 -0.233615 -0.949067 -0.211416 -0.0573201 -0.942852 -0.328244 -0.109012 -0.891343 -0.440028 -0.112797 -0.903701 -0.41304 -0.162169 -0.81975 -0.549282 -0.162415 -0.829539 -0.534309 -0.218422 -0.821624 -0.526522 -0.452547 -0.83083 -0.323918 -0.452546 -0.830831 -0.323916 -0.385061 -0.830831 -0.401805 -0.385062 -0.83083 -0.401807 -0.304374 -0.83083 -0.465917 -0.304374 -0.830831 -0.465915 -0.206676 -0.830495 -0.517266 -0.0886697 -0.977166 -0.193094 -0.504512 -0.830831 -0.234922 -0.505607 -0.830198 -0.234803 -0.178365 -0.980399 -0.0836829 -0.178193 -0.980438 -0.083603 -0.177339 -0.980679 -0.0825769 -0.159073 -0.980679 -0.113859 -0.159074 -0.980679 -0.11386 -0.135352 -0.980679 -0.141238 -0.135352 -0.980679 -0.141237 -0.106989 -0.980679 -0.163772 -0.106989 -0.980679 -0.163773 -0.0819927 -0.980789 -0.177001 -0.0811041 -0.977343 -0.195508 -0.0615788 -0.982757 -0.174346 -0.383274 -0.749443 -0.539848 -0.474789 -0.802752 -0.360784 -0.476357 -0.814083 -0.332195 -0.420362 -0.79847 -0.430978 -0.401059 -0.830312 -0.386954 -0.40106 -0.830309 -0.386959 -0.522717 -0.817422 -0.24205 -0.505088 -0.830137 -0.236133 -0.534229 -0.822435 -0.195449 -0.154316 -0.97673 -0.148946 -0.173649 -0.799538 -0.574965 -0.173388 -0.798877 -0.575962 -0.159166 -0.867664 -0.470984 -0.170289 -0.873466 -0.456134 -0.176247 -0.914036 -0.365343 -0.175098 -0.910859 -0.373733 -0.174052 -0.914442 -0.365379 -0.187634 -0.9508 -0.24652 -0.176042 -0.980301 -0.089545 -0.190106 -0.969644 -0.153789 -0.156293 -0.948117 -0.27685 -0.487155 -0.824393 -0.288194 -0.483843 -0.808505 -0.334985 -0.0019332 0.999997 0.00125953 0.043774 0.996011 -0.0777522 -0.00197286 0.997892 -0.0648727 -0.00064678 1 0.000259548 0.0424629 0.996468 -0.0724425 0.0908078 0.98963 -0.111292 0.0754812 0.992198 -0.0992238 -0.00198158 0.997891 -0.0648831 -0.0147407 0.993239 -0.115147 -0.0355044 0.990106 -0.135759 0.000107382 0.982886 -0.184214 -0.0610668 0.984169 -0.166382 -0.180977 0.982809 -0.0365173 -0.174857 0.983714 -0.04162 -0.177201 0.983649 -0.0321727 -0.0940066 0.994728 0.0409848 -0.12079 0.992636 0.00916989 -0.133616 0.99103 -0.00262373 -0.128414 0.991636 0.0129489 -0.169564 0.984839 -0.0365972 -0.02108 0.999577 -0.0200534 -0.0940094 0.994727 0.0409884 -0.0940066 0.994728 0.0409851 -0.000652936 1 0.000252705 -0.277444 0.949057 -0.149381 -0.0772124 0.925923 -0.369736 -0.0136061 0.942475 -0.334 -0.0913668 0.945698 -0.311941 -0.0406101 0.961185 -0.272899 -0.0917525 0.958861 -0.26864 -0.0579798 0.970824 -0.232679 -0.0107757 0.98031 -0.197172 -0.101004 0.858754 -0.502334 -0.0314809 0.867529 -0.49639 -0.0898746 0.867974 -0.48841 -0.0353798 0.877691 -0.47792 -0.0860115 0.891463 -0.444855 -0.0449867 0.901126 -0.431218 -0.0686425 0.90195 -0.42635 -0.00816219 0.938164 -0.346095 -0.00818525 0.938159 -0.346108 -0.120373 0.828885 -0.546314 -0.0840701 0.850366 -0.519433 -0.0840612 0.850367 -0.519432 -0.13856 0.83158 -0.537843 -0.14122 0.822442 -0.551041 -0.150679 0.830895 -0.535639 -0.0754752 0.977438 -0.197278 -0.234801 0.966992 -0.0989702 -0.287294 0.948159 -0.135858 -0.245144 0.965344 -0.0895231 -0.205433 0.974105 -0.0944269 -0.225354 0.967999 -0.110421 -0.185172 0.974766 -0.124666 -0.205847 0.969039 -0.13635 -0.179393 0.975415 -0.128001 -0.196512 0.970869 -0.137102 -0.166914 0.975589 -0.142709 -0.185358 0.968791 -0.16458 -0.169911 0.972496 -0.159315 -0.144625 0.973383 -0.177789 -0.151783 0.972046 -0.179133 -0.134279 0.974057 -0.182157 -0.135013 0.973936 -0.182265 -0.121704 0.973018 -0.196023 -0.108164 0.974637 -0.195917 -0.103603 0.97408 -0.201085 -0.108337 0.973552 -0.201146 -0.0896117 0.974981 -0.203427 -0.0692275 0.977506 -0.199225 -0.0767327 0.975688 -0.205291 -0.0903907 0.975022 -0.202884 -0.1355 0.830818 -0.539798 -0.138846 0.830544 -0.539368 -0.505399 0.830174 -0.235335 -0.241805 0.964785 0.103537 -0.304373 0.830831 -0.465915 -0.304375 0.83083 -0.465916 -0.385062 0.83083 -0.401807 -0.385061 0.830831 -0.401806 -0.452545 0.830831 -0.323917 -0.452547 0.83083 -0.323917 -0.504259 0.830853 -0.235385 -0.213248 0.830831 -0.514048 -0.21092 0.821942 -0.529079 -0.0886816 0.977159 -0.193123 -0.0886799 0.97716 -0.193118 -0.074958 0.980679 -0.180692 -0.10699 0.980679 -0.163773 -0.106989 0.980679 -0.163772 -0.135351 0.980679 -0.141237 -0.135353 0.980679 -0.141238 -0.159074 0.980679 -0.113859 -0.159073 0.980679 -0.113859 -0.177053 0.980689 -0.0830718 -0.178388 0.980448 -0.083065 -0.226133 0.824372 -0.518917 -0.162394 0.829536 -0.53432 -0.34973 0.860975 -0.369339 -0.226146 0.82437 -0.518914 -0.226147 0.824369 -0.518916 -0.155959 0.936709 -0.313452 -0.155959 0.936709 -0.313453 -0.138283 0.941162 -0.30837 -0.143796 0.936287 -0.320452 -0.143888 0.936208 -0.32064 -0.116465 0.987008 -0.110688 -0.095138 0.994846 -0.0350768 0.0524292 0.997063 -0.0558296 0.0524317 0.997063 -0.0558254 -0.000757916 0.999999 -0.000688201 -0.000761994 0.999999 -0.000695251 -0.0110881 0.999927 -0.00478585 -0.00333021 0.999944 -0.010077 0.00127462 0.999997 -0.0021031 -0.0204661 0.978936 -0.203141 0.0347058 0.99388 -0.104868 0.0201361 0.99449 -0.102882 -0.00791066 0.998761 -0.0491362 0.0100289 0.999785 -0.018171 -0.0032974 0.975555 -0.219732 -0.0291136 0.973793 -0.225563 -0.204644 0.967132 -0.150918 -0.116454 0.987011 -0.110669 -0.0580406 0.942935 -0.32788 -0.0583284 0.942255 -0.329777 -0.0573782 0.942809 -0.328357 -0.0573201 0.942852 -0.328244 -0.0972929 0.9046 -0.415009 -0.120448 0.892662 -0.434336 -0.157618 0.828825 -0.536847 -0.166195 0.81982 -0.547973 -0.165772 0.820927 -0.546442 -0.190411 0.98046 -0.0494109 -0.513267 0.815543 -0.267296 -0.520954 0.818609 -0.24184 -0.527913 0.825484 -0.199709 -0.419785 0.852692 -0.310961 -0.419843 0.852496 -0.31142 -0.475629 0.786074 -0.394798 -0.482862 0.808888 -0.335478 -0.482857 0.808821 -0.335645 -0.503926 0.830843 -0.236132 -0.503926 0.830844 -0.236128 -0.165747 0.82093 -0.546444 -0.384743 0.78742 -0.481604 -0.428397 0.808829 -0.402831 -0.514729 0.823147 -0.239756 -0.529532 0.831143 -0.169699 -0.166381 0.979149 -0.11655 -0.180944 0.976335 -0.118442 -0.187412 0.977333 -0.0984782 -0.181535 0.970374 -0.159435 -0.166074 0.963179 -0.211437 -0.186942 0.949514 -0.251944 -0.176148 0.929431 -0.324236 -0.177891 0.923017 -0.341167 -0.168153 0.88953 -0.424808 -0.167909 0.89171 -0.420311 -0.165027 0.890012 -0.425023 -0.173309 0.814249 -0.554042 0.00118256 -0.999997 -0.00194348 0.00117038 -0.999997 -0.00191653 0.00114708 -0.999997 -0.00193052 0.0018301 -0.999991 -0.00377124 0.00202127 -0.999991 -0.00365888 0.00705936 -0.999873 -0.0143264 0.00666165 -0.999872 -0.014532 0.0135056 -0.999173 -0.0383421 -0.0135662 -0.9987 -0.0491267 0.0242485 -0.996886 -0.0750362 0.012772 -0.996311 -0.0848635 -0.0206562 -0.98752 -0.156133 -0.059944 -0.992933 -0.102424 0.0148849 -0.995789 -0.090458 -0.0206562 -0.98752 -0.156133 -0.0499551 -0.912576 -0.405844 0.0189493 -0.914135 -0.404966 0.0189663 -0.914139 -0.404957 0.0189576 -0.914136 -0.404964 0.047639 -0.958758 -0.280204 -0.0883195 -0.983063 -0.160581 -0.088302 -0.983064 -0.160585 -0.0499568 -0.912576 -0.405843 0.0100598 -0.876748 -0.480845 -0.0332148 -0.8725 -0.487485 -0.0538977 -0.853653 -0.518046 -0.084329 -0.871364 -0.483336 -0.0843285 -0.871364 -0.483336 -0.0450752 -0.981932 -0.183788 -0.0335405 -0.981992 -0.185923 -0.0211237 -0.985512 -0.168288 -0.018769 -0.985531 -0.168453 -0.00303402 -0.990322 -0.138756 0.0120971 -0.990301 -0.138408 0.00942935 -0.988038 -0.153924 -0.0497756 -0.980807 -0.188521 -0.128857 -0.831369 -0.540575 -0.135516 -0.841171 -0.523513 -0.135511 -0.841169 -0.523518 -0.135511 -0.841169 -0.523518 -0.084138 -0.841713 -0.533329 -0.177339 -0.980679 -0.0825765 -0.17734 -0.980679 -0.0825769 -0.159073 -0.980679 -0.113859 -0.159073 -0.980679 -0.11386 -0.135353 -0.980679 -0.141238 -0.135353 -0.980679 -0.141238 -0.10699 -0.980679 -0.163773 -0.10699 -0.980679 -0.163773 -0.0749575 -0.980679 -0.180692 -0.0749577 -0.98068 -0.180691 -0.504509 -0.830833 -0.234921 -0.504509 -0.830833 -0.234921 -0.452543 -0.830833 -0.323916 -0.452542 -0.830834 -0.323915 -0.385059 -0.830834 -0.401801 -0.385059 -0.830833 -0.401803 -0.304372 -0.830833 -0.465912 -0.304372 -0.830832 -0.465914 -0.213247 -0.830832 -0.514046 -0.213247 -0.830832 -0.514047 -0.0411511 -0.998102 -0.0458118 -0.260281 -0.938047 -0.228739 -0.260287 -0.938044 -0.228745 -0.178777 -0.980746 -0.0785895 -0.504157 -0.830791 -0.235821 -0.506172 -0.83512 -0.215324 -0.489722 -0.840732 -0.23096 -0.441158 -0.838873 -0.318861 -0.455417 -0.84598 -0.277331 -0.415012 -0.855818 -0.308772 -0.170949 -0.98187 -0.0819048 -0.159607 -0.981793 -0.102992 -0.143779 -0.983628 -0.108648 -0.134743 -0.983561 -0.120213 -0.122267 -0.984571 -0.125183 -0.0309146 -0.976705 -0.212347 -0.0550375 -0.977049 -0.205782 -0.367629 -0.854125 -0.367857 -0.388354 -0.860245 -0.330393 -0.352787 -0.863978 -0.359281 -0.248108 -0.855498 -0.454495 -0.329711 -0.839741 -0.431423 -0.392384 -0.842568 -0.368937 -0.168619 -0.952714 -0.252793 -0.271788 -0.939036 -0.210578 -0.296535 -0.939907 -0.16924 -0.479619 -0.8287 -0.288484 -0.479621 -0.828698 -0.288486 -0.479696 -0.828683 -0.288402 -0.233219 -0.941674 -0.242608 -0.27147 -0.93768 -0.216936 -0.271453 -0.937683 -0.216942 -0.479543 -0.828717 -0.288559 -0.221249 -0.941763 0.253242 -0.221254 -0.94176 0.253249 -0.0402513 -0.998096 -0.0467458 -0.221244 -0.941763 0.253246 -0.175181 -0.98203 -0.0702097 -0.140053 -0.98193 -0.127273 -0.145042 -0.982852 -0.113866 -0.112581 -0.991503 -0.0651724 -0.114184 -0.991526 -0.0619524 -0.113587 -0.991565 -0.0624235 -0.0964602 -0.990765 -0.0952928 -0.0964605 -0.990765 -0.0952893 -0.113591 -0.991565 -0.0624175 -0.0570558 -0.998079 -0.0241412 -0.059525 -0.998081 -0.0170862 -0.00441014 -0.999365 -0.0353546 -0.0119826 -0.999925 -0.00261879 -0.00201936 -0.999998 -0.000410737 -0.00202264 -0.999998 -0.00041594 -0.000860693 -0.999981 -0.00603875 0.00118276 0.999997 -0.00194373 0.00116845 0.999997 -0.0019121 0.000580601 0.999997 -0.00226526 0.00213442 0.999991 -0.00359224 -0.000391085 0.999987 -0.00507676 0.0077248 0.999872 -0.013982 -0.00151776 0.999823 -0.0187607 0.0169488 0.999173 -0.0369692 -0.0135595 0.9987 -0.0491268 0.0242514 0.996886 -0.0750348 -0.0206528 0.98752 -0.156136 -0.0206528 0.98752 -0.156136 0.0148784 0.995794 -0.0904052 -0.0598166 0.992943 -0.102404 0.0127561 0.99631 -0.0848743 0.0190283 0.913898 -0.405498 0.0190277 0.913897 -0.405501 0.0190081 0.91389 -0.405517 -0.0883184 0.983062 -0.160591 0.0223399 0.983415 -0.179991 0.0157245 0.988032 -0.153446 0.0190329 0.913896 -0.405503 -0.0499491 0.912348 -0.406358 0.00542064 0.900528 -0.434763 -0.0333728 0.872513 -0.48745 -0.0333788 0.872512 -0.48745 -0.0519718 0.872361 -0.486092 -0.0839769 0.841797 -0.533222 -0.0839859 0.841793 -0.533227 -0.138533 0.831637 -0.537763 -0.1269 0.837474 -0.53154 -0.135621 0.841249 -0.523361 -0.1356 0.841247 -0.52337 0.00848384 0.990299 -0.138694 -0.0212897 0.990018 -0.139321 -0.00374188 0.985528 -0.169474 -0.0322745 0.985346 -0.167488 -0.0235178 0.981944 -0.187704 -0.048601 0.981896 -0.183078 -0.0465138 0.980774 -0.189525 -0.0749569 0.98068 -0.180691 -0.0749582 0.980679 -0.180692 -0.106989 0.980679 -0.163773 -0.10699 0.980679 -0.163773 -0.135353 0.980679 -0.141238 -0.135353 0.980679 -0.141238 -0.159074 0.980679 -0.11386 -0.159073 0.980679 -0.11386 -0.17734 0.980679 -0.0825766 -0.177339 0.980679 -0.0825767 -0.213247 0.830832 -0.514047 -0.213247 0.830832 -0.514047 -0.304373 0.830832 -0.465913 -0.304371 0.830833 -0.465913 -0.38506 0.830833 -0.401802 -0.385058 0.830834 -0.401802 -0.452541 0.830834 -0.323915 -0.452543 0.830833 -0.323915 -0.504509 0.830833 -0.234921 -0.504509 0.830833 -0.234921 -0.0479535 0.795447 -0.604124 -0.0479141 0.795433 -0.604145 -0.0479168 0.795434 -0.604143 -0.545197 0.837715 -0.0315251 -0.545132 0.837759 -0.0314687 -0.497479 0.867473 0.00234319 -0.33235 0.921957 -0.198844 -0.332353 0.921957 -0.198839 -0.233981 0.954212 -0.186368 -0.233932 0.95422 -0.186386 -0.372819 0.919955 -0.121198 -0.0451547 0.794493 -0.605592 -0.0451475 0.794498 -0.605586 -0.0411587 0.998101 -0.0458234 -0.313383 0.867268 -0.38683 -0.198956 0.954349 -0.222787 -0.198973 0.954342 -0.222805 -0.489407 0.84084 -0.231233 -0.504024 0.830775 -0.236162 -0.504024 0.830775 -0.236162 -0.507355 0.83421 -0.216066 -0.176696 0.980644 -0.0843575 -0.41439 0.85593 -0.309296 -0.459867 0.842519 -0.280507 -0.440536 0.838978 -0.319441 -0.489405 0.84084 -0.231237 -0.414652 0.855924 -0.308961 -0.367164 0.854255 -0.36802 -0.384271 0.86306 -0.327817 -0.302754 0.862033 -0.406496 -0.313383 0.867271 -0.386822 -0.173776 0.981809 -0.0765045 -0.153398 0.98154 -0.114228 -0.151802 0.983516 -0.0982508 -0.127426 0.983376 -0.129364 -0.130774 0.9845 -0.116865 -0.0400324 0.978191 -0.203811 -0.0296233 0.972513 -0.230957 -0.0433206 0.99811 -0.0435788 -0.219876 0.943167 0.24918 -0.219874 0.943168 0.249177 -0.125313 0.991662 -0.0300614 -0.314746 0.932642 0.176393 -0.146519 0.982492 -0.115075 -0.138786 0.982976 -0.120398 -0.00201956 0.999998 -0.000410695 -0.113578 0.991568 -0.0623938 -0.114162 0.99153 -0.0619322 -0.112558 0.991507 -0.0651538 -0.113582 0.991568 -0.0623885 -0.0837902 0.989314 -0.119317 -0.0893325 0.995164 -0.0408565 -0.0386891 0.990625 -0.131017 -0.0821025 0.996292 -0.0257292 -0.0730492 0.997093 -0.0216442 0.0073289 0.998922 -0.0458281 -0.00202376 0.999998 -0.000417378 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.550048 -0.140579 -0.823216 0.998156 -0.0426142 -0.0432224 0.968478 -0.221591 -0.113793 0.977871 -0.181842 -0.103446 0.967464 -0.175573 -0.182173 0.776087 -0.461321 -0.429967 0.776079 -0.461322 -0.429981 0.821344 -0.464923 -0.330517 0.867652 -0.336253 -0.366217 0.86755 -0.336374 -0.366347 0.379858 -0.744249 -0.549364 0.445158 -0.81789 -0.364542 0.445025 -0.670206 -0.59395 0.521853 -0.673708 -0.523247 0.542212 -0.678007 -0.4963 0.680178 -0.487195 -0.547722 0.680184 -0.487191 -0.547718 0.192411 -0.165185 -0.967312 0.19241 -0.165184 -0.967312 0.19241 -0.476812 -0.857688 0.103108 -0.919628 -0.379015 0.225859 -0.949327 -0.218554 0.220771 -0.901744 -0.371642 0.194674 -0.79682 -0.571996 0.19241 -0.734412 -0.650859 0.192413 -0.734416 -0.650854 0.192414 -0.476821 -0.857682 0.550056 -0.140572 -0.823212 0.550056 -0.140572 -0.823212 0.827753 -0.0944452 -0.553086 0.827754 -0.0944438 -0.553085 0.827753 -0.0944435 -0.553087 0.980241 -0.0332948 -0.194983 0.980241 -0.0332954 -0.194982 0.192411 -0.47681 -0.857689 0.550051 -0.405781 -0.729921 0.550056 -0.405787 -0.729915 0.827754 -0.272633 -0.490403 0.827754 -0.272633 -0.490402 0.980241 -0.096113 -0.172884 0.980241 -0.0961128 -0.172885 0.980785 0 -0.195091 0.980785 0 -0.195091 0.83147 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.555569 0.83147 0 -0.555569 0.555573 0 -0.831468 0.555573 0 -0.831468 0.555565 0 -0.831473 0.555565 0 -0.831473 0.195091 0 -0.980785 0.195091 0 -0.980785 0.828269 0.0876543 -0.553432 0.550817 0.130567 -0.82435 0.192778 0.969162 -0.153498 0.192777 0.874292 -0.445478 0.192778 0.874293 -0.445475 0.192779 0.874293 -0.445476 0.192779 0.693844 -0.693842 0.192779 0.153507 -0.96916 0.19278 0.153505 -0.969161 0.19278 0.445469 -0.874296 0.192779 0.445473 -0.874294 0.192778 0.445472 -0.874294 0.192779 0.693845 -0.693842 0.550813 0.824353 -0.130567 0.550817 0.824351 -0.130564 0.192779 0.969162 -0.1535 0.550809 0.130569 -0.824355 0.550814 0.130564 -0.824352 0.550815 0.378911 -0.743659 0.550815 0.37891 -0.74366 0.550815 0.590172 -0.59017 0.550815 0.590172 -0.590169 0.550814 0.743659 -0.378913 0.550814 0.743659 -0.378913 0.550814 0.824352 -0.130564 0.82827 0.553431 -0.0876547 0.82827 0.0876567 -0.553431 0.828271 0.0876548 -0.55343 0.828271 0.254382 -0.499257 0.82827 0.254384 -0.499257 0.82827 0.396214 -0.396212 0.828271 0.396212 -0.396212 0.828271 0.499256 -0.254384 0.828271 0.499256 -0.254384 0.82827 0.55343 -0.0876537 0.828272 0.553428 -0.0876544 0.980317 0.0308844 -0.194998 0.980317 0.0308848 -0.194998 0.980317 0.0896306 -0.17591 0.980317 0.0896304 -0.17591 0.980317 0.139603 -0.139603 0.980317 0.139603 -0.139603 0.980317 0.17591 -0.0896307 0.980317 0.17591 -0.0896307 0.980317 0.194998 -0.0308846 0.980317 0.194998 -0.0308846 0.980785 0.195091 0 0.980785 0.195091 0 0.831472 0.555567 0 0.831472 0.555567 0 0.83147 0.55557 0 0.83147 0.55557 0 0.555569 0.83147 0 0.555569 0.83147 0 0.555572 0.831468 0 0.555572 0.831468 0 0.195091 0.980785 0 0.195091 0.980785 0 0.828272 0.553428 0.0876539 0.550813 0.824353 0.130564 0.192785 0.153518 0.969158 0.192784 0.445452 0.874304 0.19278 0.445481 0.87429 0.192779 0.445477 0.874292 0.192779 0.693837 0.693849 0.192777 0.693845 0.693842 0.192779 0.969162 0.153496 0.192778 0.969162 0.153498 0.192777 0.874289 0.445484 0.192778 0.874291 0.445479 0.192776 0.874293 0.445475 0.192775 0.693841 0.693846 0.550817 0.130562 0.824351 0.550819 0.13056 0.82435 0.192775 0.153495 0.969163 0.550817 0.824351 0.130562 0.550814 0.824352 0.130565 0.550812 0.743658 0.378917 0.550814 0.743659 0.378913 0.550815 0.590172 0.59017 0.550813 0.59017 0.590173 0.550813 0.378919 0.743657 0.550811 0.378916 0.743659 0.550812 0.130574 0.824352 0.828269 0.0876608 0.553431 0.82827 0.553431 0.0876547 0.82827 0.55343 0.0876533 0.828271 0.499255 0.254383 0.828271 0.499255 0.254383 0.828272 0.39621 0.396212 0.828271 0.39621 0.396213 0.828272 0.254385 0.499254 0.828272 0.254385 0.499254 0.828272 0.0876555 0.553427 0.828265 0.0876524 0.553438 0.980317 0.194998 0.0308845 0.980317 0.194998 0.0308845 0.980317 0.17591 0.0896307 0.980317 0.17591 0.0896311 0.980317 0.139603 0.139604 0.980317 0.139603 0.139603 0.980317 0.0896313 0.17591 0.980317 0.0896311 0.17591 0.980317 0.0308834 0.194998 0.980317 0.030884 0.194998 0.195086 0 0.980786 0.195086 0 0.980786 0.555575 0 0.831466 0.555575 0 0.831466 0.555573 0 0.831468 0.555573 0 0.831468 0.83147 0 0.555569 0.83147 0 0.555569 0.831465 0 0.555577 0.831465 0 0.555577 0.980785 0 0.195091 0.980785 0 0.195091 0.177739 -0.957145 0.228653 0.181594 -0.938261 0.294432 0.0862212 -0.921113 0.379627 0.459261 -0.663353 0.590798 0.459508 -0.663257 0.590713 0.821581 -0.32723 0.466824 0.783956 -0.28458 0.551749 0.783975 -0.284568 0.551728 0.944344 -0.315767 0.0922255 0.959803 -0.16707 0.225536 0.919231 -0.0863481 0.384132 0.91923 -0.0863497 0.384136 0.192414 -0.476812 0.857687 0.192411 -0.476824 0.857681 0.19241 -0.476821 0.857683 0.192335 -0.735964 0.649126 0.191249 -0.734577 0.651015 0.191215 -0.907514 0.373973 0.550059 -0.14057 0.823211 0.192415 -0.165176 0.967313 0.192406 -0.165194 0.967311 0.550053 -0.140574 0.823214 0.550558 -0.399844 0.73281 0.553905 -0.404553 0.727685 0.512883 -0.778876 0.360975 0.534509 -0.637655 0.554704 0.550056 -0.140578 0.823211 0.827753 -0.0944491 0.553086 0.827755 -0.0944468 0.553084 0.827749 -0.0944446 0.553093 0.979546 -0.0338693 0.198348 0.980153 -0.0359029 0.194965 0.995134 -0.0164044 0.0971606 -0.00178958 -0.55537 0.831602 0 -0.925434 0.378909 0.0541746 -0.852262 0.520302 0.0262453 -0.905967 0.422534 0.0262459 -0.905966 0.422537 0.01038 -0.95217 0.305391 0.0103798 -0.952171 0.305389 0.00126499 -0.978479 0.20634 0.00126497 -0.97848 0.20634 0 -0.993464 0.114148 -0.0532892 -0.988367 0.142446 -0.000110253 -0.925375 0.379053 -0.000112539 -0.830307 0.557306 0.00139208 -0.744453 0.667674 -0.0017697 -0.671658 0.740859 0.0294522 -0.561773 0.826767 0.00141309 -0.744329 0.667811 0 -0.243021 0.970021 0.0177169 -0.166257 0.985923 0.00122332 -0.385504 0.922706 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.98646 0 -0.164001 0.0654074 0 -0.997859 0.0654074 0 -0.997859 0.195093 0 -0.980785 0.195093 0 -0.980785 0.382683 0 -0.92388 0.382683 0 -0.92388 0.608757 0 -0.793356 0.608757 0 -0.793356 0.793352 0 -0.608763 0.793352 0 -0.608763 0.888821 0 -0.458255 0.910402 0.000507106 -0.413725 0.92832 2.0674e-05 -0.371783 0.98614 -6.85432e-05 -0.165913 0 0.0232443 -0.99973 -0.000506811 0.126572 -0.991957 -0.00119265 0.629481 -0.777015 0.000636452 0.496173 -0.868224 0.000615449 0.258822 -0.965925 -0.0129635 0.485493 -0.874144 -0.00440449 0.301454 -0.953471 -0.00579215 0.984228 -0.176807 0.00037079 0.905041 -0.425324 0.000351113 0.707107 -0.707107 -0.0185429 0.894111 -0.447461 -0.00558569 0.763809 -0.645418 -0.00336678 0.963337 0.268272 0.000135232 0.998453 0.0556037 0.000129019 0.965925 -0.258821 -0.0187429 0.999269 0.0333205 -0.00579196 0.984228 -0.176811 -0.00878829 0.619252 0.785143 0.000443116 0.80266 0.596436 0.000414371 0.965926 0.258818 -0.023985 0.813688 0.580807 -0.0130939 0.901188 0.43323 -0.0259507 0.407494 0.912839 0.000170624 0.707107 0.707106 0.000183062 0.399208 0.91686 -0.00487532 -0.258811 0.965916 0.000523461 -0.115889 0.993262 0.000486572 0.258815 0.965927 -0.0270831 -0.118501 0.992585 -0.00824377 0.157903 0.98742 0.00126881 -0.866951 0.498393 -0.00190182 -0.768365 0.640009 -0.00677206 -0.648487 0.761195 -0.0165398 -0.529178 0.84835 -0.000368176 -0.707107 0.707106 0.000190375 -0.386673 0.922217 0.000190375 -0.386756 0.922182 0.00126881 -0.866944 0.498403 -0.00353735 -0.96592 0.258817 -0.00562176 -0.954338 0.298676 -0.000334049 -0.937753 -0.347302 -0.00872208 -0.990651 -0.136141 -0.00872159 -0.99065 -0.13615 -0.00141219 -0.965925 -0.25882 0.000707849 -0.995564 0.0940804 0.000707849 -0.995564 0.0940825 -0.000425412 -0.575223 -0.817997 -0.00216722 -0.695487 -0.718536 -0.00288883 -0.707104 -0.707103 0.000136224 -0.836705 -0.547655 0.000136224 -0.836725 -0.547624 0 -0.0823979 -0.9966 -0.003048 -0.255744 -0.96674 -0.0031676 -0.258821 -0.96592 0.00069602 -0.460258 -0.887785 0.000696019 -0.460224 -0.887803 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.781834 0.623487 0.00028313 -0.852436 0.522806 -0.00514064 -0.974902 0.222515 0.00732991 -0.977006 0.213148 0.00517709 -0.999733 0.0231199 0 -0.558775 0.82932 0.000480961 -0.687473 0.72621 -0.000580602 -0.781752 0.623428 0.0141477 -0.852402 0.522888 0.000161275 -0.8524 0.522891 0.000161383 0.974928 0.222521 0 0.96588 0.258806 -0.00975218 0.707013 0.707014 -0.0162829 0.781805 0.62347 0.00814792 0.781808 0.623466 0.00814792 0.258769 0.965741 -0.0195568 0.433848 0.900892 0.0130543 0.433847 0.900892 0.0130543 -0.433847 0.900892 0.0130543 -0.433846 0.900892 0.0130543 -0.258769 0.965741 -0.0195567 0 0.999892 0.0146925 0 0.999892 0.0146925 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.000231809 4.9178e-07 1 0.000231933 0 1 0.000231879 6.52897e-07 1 0.000233087 -3.53257e-06 1 0.000230622 1.99226e-06 1 0.000232056 0 1 0.000232947 6.15867e-07 1 0.000222426 -1.1635e-05 -0.875119 -0.483907 0.00126822 -0.790649 -0.612078 -0.0153163 -0.985765 -0.167691 0.0121617 -0.976603 -0.215049 0 -0.875106 -0.48393 0.00126826 -0.87512 -0.483905 0.00126749 -0.790652 -0.612086 0.0148297 -0.703961 -0.710237 -0.00134541 -0.444445 -0.895802 0.00272278 -0.559516 -0.828708 0.0135948 -0.444401 -0.895723 0.0137164 -0.25843 -0.965828 -0.0197559 -0.00909039 -0.999849 0.0148408 -0.00909146 -0.999849 0.0148408 0.259075 -0.965663 -0.0193581 0.428048 -0.903664 0.012921 0.428046 -0.903665 0.012921 0.707218 -0.706816 -0.0159192 0.779455 -0.626408 0.00796522 0.779453 -0.62641 0.00796521 0.965946 -0.258569 -0.00945594 0.974682 -0.223594 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.967531 0.252751 0 0.716026 0.698073 0.25837 0.0589711 0.964244 0.207197 0.165233 0.964244 0.114986 0.23877 0.964244 -0.25837 0.0589711 0.964244 0 0.265015 0.964244 0 0.265015 0.964244 -0.114987 0.23877 0.964244 -0.698074 0.159331 0.698074 -0.698074 0.15933 0.698073 -0.559812 0.446436 0.698073 -0.943274 0.215296 0.252749 -0.943274 0.215296 0.25275 -0.756449 0.603243 0.25275 -0.756446 0.603247 0.25275 -0.756446 0.603247 0.25275 -0.419796 0.871716 0.252751 -0.419796 0.871716 0.25275 -0.419796 0.871716 0.252751 -0.310672 0.645117 0.698074 -0.55981 0.446436 0.698074 -0.207196 0.165235 0.964244 -0.25837 0.0589711 0.964244 0 0.967531 0.252751 0 0.967531 0.252751 0 0.716026 0.698073 -0.310672 0.645117 0.698073 -0.114986 0.23877 0.964244 -0.207195 0.165235 0.964245 0.419796 0.871716 0.252751 0.114986 0.23877 0.964244 0.310672 0.645117 0.698074 0.310672 0.645117 0.698073 0.419796 0.871716 0.252751 0.419797 0.871715 0.252751 0.756449 0.603243 0.25275 0.207197 0.165235 0.964244 0.559811 0.446437 0.698073 0.559811 0.446435 0.698074 0.756446 0.603247 0.25275 0.756446 0.603247 0.25275 0.25837 0.0589712 0.964244 0.698074 0.15933 0.698074 0.698074 0.159331 0.698073 0.943274 0.215296 0.252749 0.943274 0.215296 0.25275 0.64072 -4.69722e-05 0.767775 0.991045 0 0.13353 0.95286 0.03968 0.300806 0.707107 -4.67793e-05 0.707107 0.647784 0.0423034 0.760648 0.861215 -0.0134298 0.508063 0.965845 -0.012952 0.258797 0.870972 0.0999594 0.481057 0.870948 0.0999741 0.481097 0.258821 0 0.965925 0.151156 0.059028 0.986746 0.401977 3.0562e-05 0.91565 0.258378 -0.059274 0.964224 0.697999 -0.160122 0.697967 0.943053 -0.216338 0.252682 -0.379338 -0.0670259 0.922827 -0.96337 -0.212135 0.164063 -0.648855 -0.21841 0.728893 -0.863291 -0.160757 0.478421 -0.863287 -0.160756 0.478428 -0.106647 -0.259922 0.959723 -0.929413 -0.265866 0.255942 -0.765083 -0.592286 0.252678 -0.76508 -0.592289 0.252678 -0.76508 -0.592289 0.252678 -0.430025 -0.866737 0.252678 -0.430022 -0.866738 0.252678 -0.430021 -0.866739 0.252677 -0.00879637 -0.967511 0.252677 -0.00879624 -0.967511 0.252677 -0.00879741 -0.967511 0.252678 0.414192 -0.874413 0.252678 0.414193 -0.874413 0.252678 0.943054 -0.216338 0.252679 0.943054 -0.216339 0.25268 0.754184 -0.606103 0.252679 0.754186 -0.6061 0.252679 0.754186 -0.6061 0.252679 0.41419 -0.874414 0.252678 0.698007 -0.160124 0.697959 0.698002 -0.160126 0.697963 0.558212 -0.448606 0.697963 0.55821 -0.448607 0.697964 0.306565 -0.647197 0.697964 0.306564 -0.647197 0.697965 -0.00651054 -0.716103 0.697965 -0.0065094 -0.716103 0.697964 -0.318281 -0.641517 0.697964 -0.318282 -0.641516 0.697964 -0.566275 -0.438383 0.697963 -0.566275 -0.43838 0.697965 -0.690461 -0.177563 0.701238 -0.379325 -0.0670231 0.922833 0.258379 -0.0592723 0.964224 0.258378 -0.0592724 0.964224 0.206632 -0.16606 0.964224 0.206632 -0.16606 0.964224 0.113481 -0.239572 0.964224 0.11348 -0.239572 0.964224 -0.00240957 -0.265079 0.964224 -0.00241001 -0.265079 0.964224 -0.117818 -0.237469 0.964224 -0.117817 -0.23747 0.964224 -0.209618 -0.162275 0.964224 -0.209617 -0.162276 0.964224 -0.258287 -0.0571019 0.964379 0.965085 0.0416596 0.258601 0.693789 -0.0267774 0.71968 0.706941 -0.0221959 0.706924 0.693092 -0.0221899 0.720508 0.706981 -0.018791 0.706983 0.439484 0.00988124 0.898196 0.25879 -0.0162282 0.965797 0.441739 -0.0154924 0.89701 0.258674 -0.0345382 0.965347 0.150237 3.48364e-05 0.98865 0.998944 0.000231564 0.0459541 0.975064 -0.0136657 0.221505 0.880572 -0.0938386 0.464529 0.965748 -0.0191925 0.258772 0.875224 -0.0176475 0.483396 0.875311 -0.0176485 0.483238 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 + + + + + + + + + + + + + + +

0 0 1 0 44 0 44 1 1 1 2 1 44 2 2 2 3 2 3 3 2 3 571 3 3 4 571 4 28 4 28 5 571 5 573 5 28 6 573 6 4 6 4 7 573 7 5 7 4 8 5 8 30 8 30 9 5 9 574 9 30 10 574 10 6 10 6 11 574 11 7 11 6 12 7 12 34 12 34 13 7 13 8 13 34 14 8 14 9 14 9 15 8 15 10 15 9 16 10 16 11 16 11 17 10 17 565 17 11 18 565 18 36 18 36 19 565 19 12 19 36 20 12 20 27 20 27 21 12 21 13 21 27 22 13 22 14 22 14 23 13 23 563 23 14 24 563 24 41 24 41 25 563 25 15 25 41 26 15 26 0 26 0 27 15 27 1 27 231 28 31 28 16 28 16 29 31 29 48 29 16 30 48 30 50 30 22 31 119 31 30 31 30 32 119 32 136 32 136 33 17 33 30 33 30 34 17 34 120 34 30 35 120 35 131 35 131 36 130 36 30 36 30 37 130 37 122 37 30 38 122 38 18 38 231 39 19 39 31 39 31 40 19 40 218 40 31 41 218 41 23 41 6 42 33 42 30 42 30 43 33 43 20 43 30 44 20 44 118 44 118 45 116 45 30 45 30 46 116 46 21 46 30 47 21 47 22 47 23 48 24 48 31 48 31 49 24 49 238 49 31 50 238 50 25 50 25 51 26 51 31 51 31 52 26 52 219 52 31 53 219 53 217 53 27 54 14 54 598 54 28 55 4 55 29 55 29 56 4 56 30 56 595 57 31 57 32 57 32 58 31 58 35 58 32 59 35 59 597 59 597 60 35 60 598 60 6 61 34 61 33 61 33 62 34 62 9 62 33 63 9 63 35 63 35 64 9 64 11 64 35 65 11 65 598 65 598 66 11 66 36 66 598 67 36 67 27 67 42 68 600 68 43 68 300 69 299 69 37 69 37 70 299 70 29 70 37 71 29 71 38 71 38 72 29 72 30 72 38 73 30 73 124 73 124 74 30 74 18 74 217 75 226 75 31 75 31 76 226 76 39 76 31 77 39 77 225 77 225 78 223 78 31 78 31 79 223 79 40 79 31 80 40 80 35 80 14 81 41 81 598 81 598 82 41 82 0 82 598 83 0 83 601 83 29 84 42 84 28 84 28 85 42 85 43 85 28 86 43 86 3 86 3 87 43 87 601 87 3 88 601 88 44 88 44 89 601 89 0 89 31 90 594 90 62 90 551 91 555 91 45 91 551 92 45 92 267 92 45 93 46 93 267 93 267 94 46 94 47 94 267 95 47 95 62 95 62 96 47 96 48 96 62 97 48 97 31 97 406 98 49 98 52 98 50 99 401 99 95 99 95 100 229 100 50 100 50 101 229 101 230 101 50 102 230 102 16 102 401 103 51 103 95 103 95 104 51 104 402 104 95 105 402 105 52 105 52 106 402 106 404 106 52 107 404 107 406 107 71 108 29 108 53 108 53 109 29 109 299 109 53 110 299 110 54 110 299 111 284 111 54 111 54 112 284 112 290 112 54 113 290 113 55 113 55 114 290 114 291 114 55 115 291 115 294 115 83 116 306 116 281 116 56 117 59 117 126 117 126 118 59 118 300 118 126 119 300 119 57 119 57 120 300 120 37 120 281 121 58 121 83 121 83 122 58 122 278 122 83 123 278 123 56 123 56 124 278 124 276 124 56 125 276 125 59 125 60 126 61 126 62 126 585 127 583 127 53 127 61 128 590 128 62 128 62 129 590 129 588 129 62 130 588 130 53 130 53 131 588 131 586 131 53 132 586 132 585 132 583 133 63 133 53 133 53 134 63 134 582 134 53 135 582 135 71 135 68 136 599 136 70 136 74 137 64 137 578 137 578 138 64 138 65 138 578 139 65 139 66 139 66 140 65 140 69 140 60 141 62 141 67 141 67 142 62 142 594 142 67 143 594 143 596 143 65 144 68 144 69 144 69 145 68 145 70 145 69 146 70 146 72 146 72 147 70 147 71 147 72 148 71 148 73 148 73 149 71 149 582 149 74 150 75 150 64 150 64 151 75 151 593 151 64 152 593 152 76 152 76 153 593 153 67 153 76 154 67 154 77 154 77 155 67 155 596 155 598 156 601 156 64 156 64 157 601 157 65 157 531 158 78 158 93 158 531 159 93 159 79 159 49 160 559 160 52 160 52 161 559 161 79 161 52 162 79 162 94 162 94 163 79 163 93 163 534 164 80 164 533 164 533 165 80 165 93 165 533 166 93 166 81 166 81 167 93 167 78 167 86 168 85 168 97 168 97 169 85 169 82 169 97 170 82 170 83 170 83 171 82 171 305 171 83 172 305 172 306 172 87 173 505 173 86 173 505 174 508 174 86 174 86 175 508 175 84 175 86 176 84 176 85 176 86 177 102 177 87 177 87 178 102 178 88 178 87 179 88 179 534 179 534 180 88 180 90 180 534 181 90 181 80 181 267 182 62 182 54 182 54 183 62 183 53 183 89 184 258 184 512 184 512 185 258 185 257 185 182 186 90 186 101 186 101 187 90 187 88 187 182 188 192 188 90 188 90 189 192 189 80 189 192 190 91 190 80 190 80 191 91 191 92 191 80 192 92 192 93 192 92 193 191 193 93 193 93 194 191 194 184 194 93 195 184 195 94 195 95 196 52 196 212 196 212 197 52 197 94 197 212 198 94 198 183 198 183 199 94 199 184 199 56 200 158 200 83 200 83 201 158 201 97 201 158 202 96 202 97 202 97 203 96 203 98 203 97 204 98 204 86 204 98 205 99 205 86 205 86 206 99 206 100 206 86 207 100 207 102 207 101 208 88 208 154 208 154 209 88 209 102 209 154 210 102 210 155 210 155 211 102 211 100 211 33 212 35 212 103 212 103 213 35 213 222 213 103 214 222 214 117 214 117 215 222 215 104 215 117 216 104 216 144 216 144 217 104 217 221 217 144 218 221 218 105 218 105 219 221 219 244 219 105 220 244 220 106 220 106 221 244 221 108 221 106 222 108 222 107 222 107 223 108 223 109 223 107 224 109 224 110 224 110 225 109 225 111 225 110 226 111 226 143 226 143 227 111 227 248 227 143 228 248 228 112 228 112 229 248 229 249 229 112 230 249 230 113 230 113 231 249 231 114 231 145 232 115 232 144 232 126 233 57 233 125 233 144 234 115 234 117 234 22 235 21 235 115 235 115 236 21 236 116 236 115 237 116 237 117 237 117 238 116 238 118 238 117 239 118 239 103 239 103 240 118 240 20 240 103 241 20 241 33 241 22 242 115 242 119 242 119 243 115 243 145 243 119 244 145 244 136 244 17 245 137 245 120 245 120 246 137 246 121 246 120 247 121 247 131 247 132 248 122 248 130 248 122 249 132 249 18 249 18 250 132 250 123 250 18 251 123 251 124 251 124 252 123 252 125 252 124 253 125 253 38 253 38 254 125 254 57 254 38 255 57 255 37 255 56 256 126 256 157 256 157 257 126 257 140 257 141 258 127 258 140 258 140 259 127 259 128 259 140 260 128 260 157 260 135 261 149 261 141 261 141 262 149 262 129 262 141 263 129 263 127 263 130 264 131 264 132 264 132 265 131 265 121 265 132 266 121 266 123 266 123 267 121 267 138 267 133 268 134 268 142 268 142 269 134 269 150 269 142 270 150 270 135 270 135 271 150 271 168 271 135 272 168 272 149 272 17 273 136 273 137 273 137 274 136 274 145 274 137 275 145 275 121 275 121 276 145 276 146 276 121 277 146 277 138 277 138 278 146 278 147 278 113 279 139 279 112 279 112 280 139 280 152 280 112 281 152 281 142 281 142 282 152 282 151 282 142 283 151 283 133 283 126 284 125 284 140 284 140 285 125 285 123 285 140 286 123 286 141 286 141 287 123 287 138 287 141 288 138 288 135 288 135 289 138 289 147 289 135 290 147 290 142 290 142 291 147 291 143 291 142 292 143 292 112 292 144 293 105 293 145 293 145 294 105 294 106 294 145 295 106 295 146 295 146 296 106 296 107 296 146 297 107 297 147 297 147 298 107 298 110 298 147 299 110 299 143 299 176 300 167 300 148 300 179 301 180 301 163 301 128 302 127 302 164 302 129 303 149 303 165 303 168 304 150 304 170 304 170 305 151 305 171 305 171 306 151 306 152 306 171 307 152 307 172 307 172 308 152 308 139 308 172 309 139 309 174 309 174 310 139 310 113 310 174 311 113 311 175 311 150 312 134 312 170 312 170 313 134 313 133 313 170 314 133 314 151 314 153 315 181 315 162 315 162 316 181 316 101 316 101 317 154 317 162 317 162 318 154 318 155 318 162 319 155 319 156 319 155 320 100 320 156 320 156 321 100 321 99 321 156 322 99 322 160 322 56 323 157 323 158 323 158 324 157 324 159 324 158 325 159 325 96 325 96 326 159 326 160 326 96 327 160 327 98 327 98 328 160 328 99 328 157 329 128 329 159 329 159 330 128 330 164 330 159 331 164 331 160 331 160 332 164 332 166 332 160 333 166 333 156 333 156 334 166 334 161 334 156 335 161 335 162 335 162 336 161 336 163 336 162 337 163 337 153 337 153 338 163 338 180 338 127 339 129 339 164 339 164 340 129 340 165 340 164 341 165 341 166 341 166 342 165 342 169 342 166 343 169 343 161 343 161 344 169 344 173 344 161 345 173 345 163 345 163 346 173 346 148 346 163 347 148 347 179 347 179 348 148 348 167 348 149 349 168 349 165 349 165 350 168 350 170 350 165 351 170 351 169 351 169 352 170 352 171 352 169 353 171 353 173 353 173 354 171 354 172 354 173 355 172 355 148 355 148 356 172 356 174 356 148 357 174 357 176 357 176 358 174 358 175 358 113 359 114 359 175 359 175 360 114 360 187 360 175 361 187 361 176 361 176 362 187 362 177 362 176 363 177 363 167 363 167 364 177 364 178 364 167 365 178 365 179 365 179 366 178 366 198 366 179 367 198 367 180 367 180 368 198 368 195 368 180 369 195 369 153 369 153 370 195 370 194 370 153 371 194 371 181 371 181 372 194 372 193 372 181 373 193 373 101 373 101 374 193 374 182 374 190 375 189 375 196 375 192 376 182 376 193 376 183 377 184 377 214 377 212 378 213 378 95 378 95 379 213 379 227 379 210 380 233 380 211 380 204 381 216 381 185 381 199 382 186 382 201 382 201 383 186 383 239 383 201 384 239 384 202 384 114 385 205 385 187 385 187 386 205 386 188 386 187 387 188 387 177 387 192 388 189 388 91 388 91 389 189 389 190 389 91 390 190 390 92 390 92 391 190 391 191 391 192 392 193 392 189 392 189 393 193 393 194 393 189 394 194 394 196 394 196 395 194 395 195 395 196 396 195 396 198 396 184 397 191 397 214 397 214 398 191 398 190 398 214 399 190 399 215 399 215 400 190 400 196 400 215 401 196 401 197 401 197 402 196 402 198 402 197 403 198 403 178 403 247 404 199 404 200 404 200 405 199 405 201 405 200 406 201 406 204 406 204 407 201 407 202 407 204 408 202 408 216 408 206 409 247 409 207 409 207 410 247 410 200 410 207 411 200 411 203 411 203 412 200 412 204 412 203 413 204 413 210 413 210 414 204 414 185 414 210 415 185 415 233 415 205 416 206 416 188 416 188 417 206 417 207 417 188 418 207 418 208 418 208 419 207 419 203 419 208 420 203 420 209 420 209 421 203 421 210 421 209 422 210 422 213 422 213 423 210 423 211 423 213 424 211 424 227 424 212 425 183 425 213 425 213 426 183 426 214 426 213 427 214 427 209 427 209 428 214 428 215 428 209 429 215 429 208 429 208 430 215 430 197 430 208 431 197 431 188 431 188 432 197 432 178 432 188 433 178 433 177 433 205 434 114 434 249 434 239 435 186 435 246 435 216 436 202 436 236 436 233 437 185 437 234 437 227 438 211 438 228 438 217 439 219 439 242 439 218 440 19 440 232 440 231 441 16 441 230 441 238 442 24 442 237 442 237 443 24 443 23 443 237 444 23 444 235 444 219 445 26 445 242 445 242 446 26 446 25 446 242 447 25 447 220 447 243 448 224 448 226 448 224 449 221 449 104 449 35 450 40 450 222 450 222 451 40 451 223 451 222 452 223 452 104 452 104 453 223 453 225 453 104 454 225 454 224 454 224 455 225 455 39 455 224 456 39 456 226 456 95 457 227 457 229 457 229 458 227 458 228 458 229 459 228 459 230 459 230 460 228 460 232 460 230 461 232 461 231 461 231 462 232 462 19 462 211 463 233 463 228 463 228 464 233 464 234 464 228 465 234 465 232 465 232 466 234 466 235 466 232 467 235 467 218 467 218 468 235 468 23 468 185 469 216 469 234 469 234 470 216 470 236 470 234 471 236 471 235 471 235 472 236 472 240 472 235 473 240 473 237 473 237 474 240 474 220 474 237 475 220 475 238 475 238 476 220 476 25 476 202 477 239 477 236 477 236 478 239 478 246 478 236 479 246 479 240 479 240 480 246 480 241 480 240 481 241 481 220 481 220 482 241 482 245 482 220 483 245 483 242 483 242 484 245 484 243 484 242 485 243 485 217 485 217 486 243 486 226 486 221 487 224 487 244 487 244 488 224 488 243 488 244 489 243 489 108 489 108 490 243 490 245 490 108 491 245 491 109 491 186 492 199 492 246 492 246 493 199 493 247 493 246 494 247 494 206 494 109 495 245 495 111 495 111 496 245 496 241 496 111 497 241 497 248 497 248 498 241 498 246 498 248 499 246 499 249 499 249 500 246 500 206 500 249 501 206 501 205 501 54 502 55 502 250 502 250 503 55 503 251 503 250 504 251 504 252 504 252 505 251 505 253 505 252 506 253 506 265 506 265 507 253 507 515 507 265 508 515 508 263 508 515 509 254 509 263 509 263 510 254 510 523 510 263 511 523 511 262 511 262 512 523 512 260 512 256 513 512 513 257 513 523 514 255 514 260 514 260 515 255 515 256 515 260 516 256 516 259 516 259 517 256 517 257 517 265 518 269 518 252 518 252 519 269 519 268 519 252 520 268 520 250 520 250 521 268 521 267 521 250 522 267 522 54 522 257 523 258 523 259 523 259 524 258 524 275 524 259 525 275 525 260 525 260 526 275 526 274 526 260 527 274 527 262 527 262 528 274 528 261 528 262 529 261 529 263 529 263 530 261 530 264 530 263 531 264 531 265 531 265 532 264 532 266 532 265 533 266 533 269 533 551 534 267 534 552 534 552 535 267 535 268 535 552 536 268 536 553 536 553 537 268 537 269 537 553 538 269 538 270 538 270 539 269 539 266 539 270 540 266 540 271 540 271 541 266 541 264 541 271 542 264 542 554 542 554 543 264 543 261 543 554 544 261 544 272 544 272 545 261 545 274 545 272 546 274 546 273 546 273 547 274 547 275 547 273 548 275 548 89 548 89 549 275 549 258 549 312 550 300 550 313 550 313 551 300 551 59 551 313 552 59 552 310 552 310 553 59 553 276 553 310 554 276 554 277 554 277 555 276 555 278 555 277 556 278 556 279 556 279 557 278 557 58 557 279 558 58 558 280 558 280 559 58 559 281 559 280 560 281 560 308 560 308 561 281 561 306 561 299 562 282 562 283 562 299 563 283 563 284 563 283 564 376 564 284 564 284 565 376 565 288 565 284 566 288 566 290 566 286 567 298 567 285 567 285 568 501 568 286 568 286 569 501 569 499 569 286 570 499 570 287 570 288 571 375 571 290 571 290 572 375 572 289 572 290 573 289 573 291 573 291 574 289 574 292 574 291 575 292 575 294 575 294 576 292 576 293 576 294 577 293 577 295 577 295 578 293 578 381 578 295 579 381 579 296 579 296 580 381 580 287 580 296 581 287 581 497 581 497 582 287 582 499 582 495 583 297 583 386 583 386 584 297 584 494 584 298 585 286 585 494 585 494 586 286 586 387 586 494 587 387 587 386 587 282 588 299 588 364 588 364 589 299 589 300 589 364 590 300 590 365 590 365 591 300 591 312 591 365 592 312 592 367 592 367 593 312 593 301 593 367 594 301 594 368 594 368 595 301 595 302 595 302 596 301 596 314 596 302 597 314 597 303 597 303 598 314 598 363 598 363 599 314 599 311 599 363 600 311 600 304 600 304 601 311 601 384 601 384 602 311 602 315 602 384 603 315 603 385 603 305 604 315 604 306 604 306 605 315 605 307 605 306 606 307 606 308 606 385 607 315 607 309 607 309 608 315 608 305 608 309 609 305 609 386 609 386 610 305 610 496 610 386 611 496 611 495 611 277 612 315 612 310 612 310 613 315 613 311 613 312 614 313 614 301 614 301 615 313 615 310 615 301 616 310 616 314 616 314 617 310 617 311 617 308 618 307 618 280 618 280 619 307 619 315 619 280 620 315 620 279 620 279 621 315 621 277 621 316 622 317 622 319 622 319 623 317 623 377 623 316 624 325 624 317 624 317 625 325 625 323 625 317 626 323 626 357 626 370 627 318 627 320 627 320 628 318 628 319 628 320 629 319 629 330 629 330 630 319 630 377 630 330 631 377 631 327 631 357 632 321 632 317 632 317 633 321 633 334 633 317 634 334 634 335 634 377 635 317 635 378 635 318 636 370 636 322 636 357 637 323 637 359 637 318 638 369 638 319 638 319 639 369 639 324 639 319 640 324 640 316 640 316 641 324 641 338 641 316 642 338 642 325 642 325 643 338 643 358 643 325 644 358 644 323 644 377 645 326 645 327 645 327 646 326 646 328 646 327 647 328 647 330 647 330 648 328 648 329 648 330 649 329 649 320 649 320 650 329 650 331 650 320 651 331 651 370 651 357 652 332 652 321 652 321 653 332 653 333 653 321 654 333 654 334 654 334 655 333 655 341 655 334 656 341 656 335 656 335 657 341 657 336 657 335 658 336 658 317 658 369 659 343 659 324 659 324 660 343 660 337 660 324 661 337 661 338 661 338 662 337 662 345 662 338 663 345 663 358 663 358 664 345 664 346 664 326 665 380 665 328 665 328 666 380 666 349 666 328 667 349 667 329 667 329 668 349 668 350 668 329 669 350 669 331 669 331 670 350 670 351 670 332 671 339 671 333 671 333 672 339 672 340 672 333 673 340 673 341 673 341 674 340 674 356 674 341 675 356 675 336 675 336 676 356 676 342 676 343 677 366 677 337 677 337 678 366 678 344 678 337 679 344 679 345 679 345 680 344 680 347 680 345 681 347 681 346 681 346 682 347 682 361 682 380 683 348 683 349 683 349 684 348 684 374 684 349 685 374 685 350 685 350 686 374 686 352 686 350 687 352 687 351 687 351 688 352 688 373 688 339 689 353 689 340 689 340 690 353 690 354 690 340 691 354 691 356 691 356 692 354 692 355 692 356 693 355 693 342 693 342 694 355 694 383 694 357 695 359 695 332 695 332 696 359 696 360 696 332 697 360 697 339 697 339 698 360 698 362 698 339 699 362 699 353 699 353 700 362 700 363 700 353 701 363 701 304 701 323 702 358 702 359 702 359 703 358 703 346 703 359 704 346 704 360 704 360 705 346 705 361 705 360 706 361 706 362 706 362 707 361 707 303 707 362 708 303 708 363 708 282 709 364 709 366 709 366 710 364 710 365 710 366 711 365 711 344 711 344 712 365 712 367 712 344 713 367 713 347 713 347 714 367 714 368 714 347 715 368 715 361 715 361 716 368 716 302 716 361 717 302 717 303 717 318 718 322 718 369 718 369 719 322 719 371 719 369 720 371 720 343 720 343 721 371 721 372 721 343 722 372 722 366 722 366 723 372 723 283 723 366 724 283 724 282 724 370 725 331 725 322 725 322 726 331 726 351 726 322 727 351 727 371 727 371 728 351 728 373 728 371 729 373 729 372 729 372 730 373 730 376 730 372 731 376 731 283 731 381 732 293 732 348 732 348 733 293 733 292 733 348 734 292 734 374 734 374 735 292 735 289 735 374 736 289 736 352 736 352 737 289 737 375 737 352 738 375 738 373 738 373 739 375 739 288 739 373 740 288 740 376 740 377 741 378 741 326 741 326 742 378 742 379 742 326 743 379 743 380 743 380 744 379 744 382 744 380 745 382 745 348 745 348 746 382 746 287 746 348 747 287 747 381 747 317 748 336 748 378 748 378 749 336 749 342 749 378 750 342 750 379 750 379 751 342 751 383 751 379 752 383 752 382 752 382 753 383 753 286 753 382 754 286 754 287 754 304 755 384 755 353 755 353 756 384 756 385 756 353 757 385 757 354 757 354 758 385 758 309 758 354 759 309 759 355 759 355 760 309 760 386 760 355 761 386 761 383 761 383 762 386 762 387 762 383 763 387 763 286 763 50 764 420 764 388 764 562 765 561 765 408 765 408 766 561 766 560 766 408 767 560 767 559 767 558 768 391 768 389 768 389 769 391 769 395 769 389 770 395 770 394 770 558 771 390 771 391 771 391 772 390 772 557 772 391 773 557 773 458 773 458 774 557 774 392 774 458 775 392 775 408 775 408 776 392 776 393 776 408 777 393 777 562 777 394 778 395 778 396 778 396 779 395 779 397 779 396 780 397 780 555 780 555 781 397 781 398 781 555 782 398 782 45 782 398 783 467 783 45 783 45 784 467 784 399 784 45 785 399 785 46 785 399 786 400 786 46 786 46 787 400 787 466 787 46 788 466 788 47 788 466 789 473 789 47 789 47 790 473 790 416 790 47 791 416 791 48 791 50 792 388 792 401 792 401 793 388 793 422 793 401 794 422 794 51 794 51 795 422 795 403 795 51 796 403 796 402 796 402 797 403 797 405 797 402 798 405 798 404 798 404 799 405 799 421 799 404 800 421 800 406 800 406 801 421 801 407 801 406 802 407 802 49 802 49 803 407 803 418 803 49 804 418 804 559 804 559 805 418 805 457 805 559 806 457 806 408 806 410 807 487 807 418 807 418 808 487 808 409 808 418 809 409 809 457 809 419 810 411 810 410 810 410 811 411 811 488 811 410 812 488 812 487 812 414 813 492 813 419 813 419 814 492 814 491 814 419 815 491 815 411 815 417 816 412 816 413 816 413 817 412 817 415 817 413 818 415 818 414 818 414 819 415 819 485 819 414 820 485 820 492 820 416 821 474 821 48 821 48 822 474 822 417 822 48 823 417 823 50 823 50 824 417 824 413 824 50 825 413 825 420 825 388 826 410 826 422 826 422 827 410 827 418 827 414 828 419 828 413 828 413 829 419 829 410 829 413 830 410 830 420 830 420 831 410 831 388 831 405 832 403 832 421 832 421 833 403 833 422 833 421 834 422 834 407 834 407 835 422 835 418 835 429 836 424 836 423 836 423 837 424 837 431 837 423 838 431 838 425 838 460 839 426 839 432 839 468 840 427 840 425 840 460 841 432 841 428 841 428 842 432 842 423 842 423 843 432 843 433 843 423 844 433 844 429 844 431 845 479 845 449 845 425 846 431 846 468 846 468 847 431 847 449 847 468 848 449 848 469 848 478 849 434 849 477 849 429 850 433 850 430 850 461 851 438 851 460 851 424 852 434 852 431 852 431 853 434 853 478 853 431 854 478 854 479 854 460 855 438 855 426 855 426 856 438 856 436 856 426 857 436 857 432 857 432 858 436 858 484 858 432 859 484 859 433 859 476 860 477 860 481 860 481 861 477 861 434 861 481 862 434 862 435 862 435 863 434 863 424 863 435 864 424 864 429 864 453 865 484 865 454 865 454 866 484 866 436 866 454 867 436 867 437 867 437 868 436 868 438 868 437 869 438 869 455 869 455 870 438 870 461 870 455 871 461 871 439 871 428 872 423 872 462 872 462 873 423 873 440 873 462 874 440 874 441 874 441 875 440 875 442 875 441 876 442 876 463 876 463 877 442 877 465 877 463 878 465 878 395 878 395 879 465 879 397 879 425 880 427 880 443 880 443 881 427 881 446 881 443 882 446 882 444 882 444 883 446 883 448 883 444 884 448 884 464 884 464 885 448 885 445 885 427 886 468 886 446 886 446 887 468 887 447 887 446 888 447 888 448 888 448 889 447 889 470 889 448 890 470 890 445 890 445 891 470 891 472 891 469 892 449 892 450 892 450 893 449 893 480 893 450 894 480 894 471 894 471 895 480 895 452 895 471 896 452 896 451 896 451 897 452 897 475 897 451 898 475 898 416 898 416 899 475 899 474 899 493 900 453 900 490 900 490 901 453 901 454 901 490 902 454 902 489 902 489 903 454 903 437 903 489 904 437 904 486 904 486 905 437 905 455 905 486 906 455 906 456 906 456 907 455 907 439 907 456 908 439 908 459 908 409 909 486 909 457 909 457 910 486 910 456 910 457 911 456 911 408 911 408 912 456 912 459 912 408 913 459 913 458 913 458 914 459 914 391 914 460 915 428 915 461 915 461 916 428 916 462 916 461 917 462 917 439 917 439 918 462 918 441 918 439 919 441 919 459 919 459 920 441 920 463 920 459 921 463 921 391 921 391 922 463 922 395 922 398 923 397 923 464 923 464 924 397 924 465 924 464 925 465 925 444 925 444 926 465 926 442 926 444 927 442 927 443 927 443 928 442 928 440 928 443 929 440 929 425 929 425 930 440 930 423 930 473 931 466 931 472 931 472 932 466 932 400 932 472 933 400 933 445 933 445 934 400 934 399 934 445 935 399 935 464 935 464 936 399 936 467 936 464 937 467 937 398 937 468 938 469 938 447 938 447 939 469 939 450 939 447 940 450 940 470 940 470 941 450 941 471 941 470 942 471 942 472 942 472 943 471 943 451 943 472 944 451 944 473 944 473 945 451 945 416 945 417 946 474 946 476 946 476 947 474 947 475 947 476 948 475 948 477 948 477 949 475 949 452 949 477 950 452 950 478 950 478 951 452 951 480 951 478 952 480 952 479 952 479 953 480 953 449 953 483 954 415 954 412 954 429 955 430 955 435 955 435 956 430 956 482 956 435 957 482 957 481 957 481 958 482 958 483 958 481 959 483 959 476 959 476 960 483 960 412 960 476 961 412 961 417 961 433 962 484 962 430 962 430 963 484 963 453 963 430 964 453 964 482 964 482 965 453 965 493 965 482 966 493 966 483 966 483 967 493 967 485 967 483 968 485 968 415 968 409 969 487 969 486 969 486 970 487 970 488 970 486 971 488 971 489 971 489 972 488 972 411 972 489 973 411 973 490 973 490 974 411 974 491 974 490 975 491 975 493 975 493 976 491 976 492 976 493 977 492 977 485 977 298 978 494 978 502 978 496 979 305 979 82 979 502 980 494 980 503 980 503 981 494 981 297 981 503 982 297 982 82 982 82 983 297 983 495 983 82 984 495 984 496 984 55 985 294 985 514 985 514 986 294 986 295 986 514 987 295 987 498 987 498 988 295 988 296 988 296 989 497 989 498 989 498 990 497 990 499 990 498 991 499 991 500 991 500 992 499 992 501 992 500 993 501 993 502 993 502 994 501 994 285 994 502 995 285 995 298 995 505 996 87 996 506 996 508 997 505 997 507 997 84 998 508 998 518 998 85 999 84 999 519 999 85 1000 516 1000 82 1000 82 1001 516 1001 503 1001 503 1002 516 1002 502 1002 502 1003 516 1003 504 1003 502 1004 504 1004 500 1004 505 1005 506 1005 507 1005 507 1006 506 1006 524 1006 507 1007 524 1007 509 1007 508 1008 507 1008 518 1008 518 1009 507 1009 509 1009 518 1010 509 1010 520 1010 520 1011 509 1011 511 1011 520 1012 511 1012 522 1012 524 1013 510 1013 509 1013 509 1014 510 1014 526 1014 509 1015 526 1015 511 1015 511 1016 526 1016 527 1016 511 1017 527 1017 512 1017 500 1018 504 1018 498 1018 498 1019 504 1019 513 1019 498 1020 513 1020 514 1020 514 1021 513 1021 251 1021 514 1022 251 1022 55 1022 521 1023 515 1023 253 1023 85 1024 519 1024 516 1024 516 1025 519 1025 517 1025 516 1026 517 1026 504 1026 504 1027 517 1027 521 1027 504 1028 521 1028 513 1028 513 1029 521 1029 253 1029 513 1030 253 1030 251 1030 84 1031 518 1031 519 1031 519 1032 518 1032 520 1032 519 1033 520 1033 517 1033 517 1034 520 1034 522 1034 517 1035 522 1035 521 1035 521 1036 522 1036 254 1036 521 1037 254 1037 515 1037 512 1038 256 1038 511 1038 511 1039 256 1039 255 1039 511 1040 255 1040 522 1040 522 1041 255 1041 523 1041 522 1042 523 1042 254 1042 87 1043 534 1043 506 1043 506 1044 534 1044 525 1044 506 1045 525 1045 524 1045 524 1046 525 1046 536 1046 524 1047 536 1047 510 1047 510 1048 536 1048 548 1048 510 1049 548 1049 526 1049 526 1050 548 1050 549 1050 526 1051 549 1051 527 1051 527 1052 549 1052 528 1052 527 1053 528 1053 512 1053 512 1054 528 1054 89 1054 529 1055 530 1055 551 1055 535 1056 543 1056 546 1056 531 1057 79 1057 532 1057 533 1058 537 1058 534 1058 534 1059 537 1059 525 1059 531 1060 543 1060 78 1060 78 1061 543 1061 535 1061 78 1062 535 1062 81 1062 525 1063 537 1063 536 1063 536 1064 537 1064 538 1064 536 1065 538 1065 548 1065 542 1066 539 1066 547 1066 540 1067 539 1067 541 1067 541 1068 539 1068 542 1068 541 1069 542 1069 529 1069 531 1070 532 1070 543 1070 543 1071 532 1071 544 1071 543 1072 544 1072 546 1072 546 1073 544 1073 545 1073 546 1074 545 1074 556 1074 533 1075 81 1075 547 1075 547 1076 81 1076 535 1076 547 1077 535 1077 542 1077 542 1078 535 1078 546 1078 542 1079 546 1079 529 1079 529 1080 546 1080 556 1080 529 1081 556 1081 530 1081 548 1082 538 1082 549 1082 549 1083 538 1083 550 1083 549 1084 550 1084 528 1084 528 1085 550 1085 273 1085 528 1086 273 1086 89 1086 540 1087 554 1087 272 1087 533 1088 547 1088 537 1088 537 1089 547 1089 539 1089 537 1090 539 1090 538 1090 538 1091 539 1091 540 1091 538 1092 540 1092 550 1092 550 1093 540 1093 272 1093 550 1094 272 1094 273 1094 551 1095 552 1095 529 1095 529 1096 552 1096 553 1096 529 1097 553 1097 541 1097 541 1098 553 1098 270 1098 541 1099 270 1099 540 1099 540 1100 270 1100 271 1100 540 1101 271 1101 554 1101 555 1102 551 1102 396 1102 396 1103 551 1103 530 1103 396 1104 530 1104 394 1104 394 1105 530 1105 556 1105 394 1106 556 1106 389 1106 544 1107 393 1107 392 1107 392 1108 557 1108 544 1108 544 1109 557 1109 390 1109 544 1110 390 1110 558 1110 389 1111 556 1111 558 1111 558 1112 556 1112 545 1112 558 1113 545 1113 544 1113 559 1114 560 1114 79 1114 79 1115 560 1115 561 1115 79 1116 561 1116 562 1116 393 1117 544 1117 562 1117 562 1118 544 1118 532 1118 562 1119 532 1119 79 1119 563 1120 569 1120 15 1120 15 1121 569 1121 577 1121 15 1122 577 1122 1 1122 1 1123 577 1123 564 1123 1 1124 564 1124 2 1124 10 1125 591 1125 565 1125 565 1126 591 1126 566 1126 565 1127 566 1127 12 1127 12 1128 566 1128 567 1128 12 1129 567 1129 13 1129 13 1130 567 1130 592 1130 13 1131 592 1131 563 1131 563 1132 592 1132 568 1132 563 1133 568 1133 569 1133 564 1134 570 1134 2 1134 2 1135 570 1135 579 1135 2 1136 579 1136 571 1136 571 1137 579 1137 580 1137 571 1138 580 1138 573 1138 573 1139 580 1139 572 1139 573 1140 572 1140 5 1140 5 1141 572 1141 581 1141 5 1142 581 1142 574 1142 581 1143 575 1143 574 1143 574 1144 575 1144 576 1144 574 1145 576 1145 7 1145 7 1146 576 1146 584 1146 7 1147 584 1147 8 1147 8 1148 584 1148 587 1148 8 1149 587 1149 10 1149 10 1150 587 1150 589 1150 10 1151 589 1151 591 1151 577 1152 578 1152 564 1152 564 1153 578 1153 66 1153 564 1154 66 1154 570 1154 570 1155 66 1155 69 1155 570 1156 69 1156 579 1156 579 1157 69 1157 72 1157 579 1158 72 1158 580 1158 580 1159 72 1159 73 1159 580 1160 73 1160 572 1160 572 1161 73 1161 582 1161 572 1162 582 1162 581 1162 581 1163 582 1163 63 1163 581 1164 63 1164 575 1164 575 1165 63 1165 583 1165 575 1166 583 1166 576 1166 576 1167 583 1167 585 1167 576 1168 585 1168 584 1168 584 1169 585 1169 586 1169 584 1170 586 1170 587 1170 587 1171 586 1171 588 1171 587 1172 588 1172 589 1172 589 1173 588 1173 590 1173 589 1174 590 1174 591 1174 591 1175 590 1175 61 1175 591 1176 61 1176 566 1176 566 1177 61 1177 60 1177 566 1178 60 1178 567 1178 567 1179 60 1179 67 1179 567 1180 67 1180 592 1180 592 1181 67 1181 593 1181 592 1182 593 1182 568 1182 568 1183 593 1183 75 1183 568 1184 75 1184 569 1184 569 1185 75 1185 74 1185 569 1186 74 1186 577 1186 577 1187 74 1187 578 1187 594 1188 31 1188 595 1188 594 1189 595 1189 596 1189 596 1190 595 1190 32 1190 596 1191 32 1191 77 1191 77 1192 32 1192 597 1192 77 1193 597 1193 76 1193 76 1194 597 1194 598 1194 76 1195 598 1195 64 1195 29 1196 71 1196 70 1196 29 1197 70 1197 42 1197 42 1198 70 1198 599 1198 42 1199 599 1199 600 1199 600 1200 599 1200 68 1200 600 1201 68 1201 43 1201 43 1202 68 1202 65 1202 43 1203 65 1203 601 1203 666 1204 665 1204 3844 1204 801 1205 631 1205 610 1205 3929 1206 3927 1206 614 1206 843 1207 3821 1207 3820 1207 602 1208 610 1208 3932 1208 3932 1209 610 1209 631 1209 3932 1210 631 1210 3825 1210 3825 1211 631 1211 630 1211 823 1212 821 1212 801 1212 603 1213 3813 1213 3931 1213 608 1214 604 1214 3931 1214 605 1215 606 1215 620 1215 607 1216 608 1216 3809 1216 3809 1217 608 1217 3931 1217 3809 1218 3931 1218 609 1218 609 1219 3931 1219 3813 1219 610 1220 3936 1220 801 1220 801 1221 3936 1221 3931 1221 801 1222 3931 1222 823 1222 823 1223 3931 1223 604 1223 3803 1224 818 1224 611 1224 843 1225 845 1225 3821 1225 3821 1226 845 1226 613 1226 3821 1227 613 1227 612 1227 612 1228 613 1228 848 1228 612 1229 848 1229 3758 1229 3758 1230 848 1230 849 1230 3758 1231 849 1231 799 1231 843 1232 614 1232 841 1232 841 1233 614 1233 3860 1233 841 1234 3860 1234 3855 1234 821 1235 615 1235 801 1235 801 1236 615 1236 616 1236 801 1237 616 1237 3748 1237 3748 1238 616 1238 625 1238 840 1239 839 1239 3803 1239 3803 1240 839 1240 617 1240 3803 1241 617 1241 818 1241 3800 1242 612 1242 809 1242 809 1243 612 1243 3758 1243 809 1244 3758 1244 618 1244 618 1245 3758 1245 619 1245 3931 1246 3929 1246 603 1246 603 1247 3929 1247 614 1247 603 1248 614 1248 3818 1248 3818 1249 614 1249 843 1249 3818 1250 843 1250 3817 1250 3817 1251 843 1251 3820 1251 3758 1252 3747 1252 619 1252 619 1253 3747 1253 3757 1253 619 1254 3757 1254 812 1254 812 1255 3757 1255 3748 1255 812 1256 3748 1256 814 1256 611 1257 605 1257 3803 1257 3803 1258 605 1258 620 1258 3803 1259 620 1259 3806 1259 3806 1260 620 1260 827 1260 3806 1261 827 1261 3809 1261 3809 1262 827 1262 621 1262 3809 1263 621 1263 607 1263 809 1264 622 1264 3800 1264 3800 1265 622 1265 623 1265 3800 1266 623 1266 3803 1266 3803 1267 623 1267 805 1267 3803 1268 805 1268 840 1268 814 1269 3748 1269 624 1269 624 1270 3748 1270 625 1270 624 1271 625 1271 816 1271 816 1272 625 1272 831 1272 816 1273 831 1273 817 1273 817 1274 831 1274 626 1274 817 1275 626 1275 627 1275 835 1276 628 1276 629 1276 629 1277 628 1277 817 1277 629 1278 817 1278 829 1278 829 1279 817 1279 627 1279 934 1280 933 1280 3890 1280 3890 1281 630 1281 934 1281 934 1282 630 1282 631 1282 934 1283 631 1283 632 1283 632 1284 631 1284 1300 1284 3791 1285 771 1285 635 1285 3897 1286 639 1286 640 1286 636 1287 642 1287 633 1287 633 1288 642 1288 725 1288 642 1289 3897 1289 725 1289 725 1290 3897 1290 640 1290 725 1291 640 1291 760 1291 760 1292 640 1292 3791 1292 760 1293 3791 1293 634 1293 634 1294 3791 1294 635 1294 636 1295 637 1295 642 1295 642 1296 637 1296 638 1296 642 1297 638 1297 729 1297 639 1298 3899 1298 640 1298 640 1299 3899 1299 3898 1299 640 1300 3898 1300 643 1300 729 1301 733 1301 642 1301 642 1302 733 1302 641 1302 642 1303 641 1303 732 1303 3860 1304 614 1304 3861 1304 3861 1305 614 1305 640 1305 3861 1306 640 1306 3900 1306 3900 1307 640 1307 643 1307 3784 1308 2108 1308 644 1308 2063 1309 645 1309 3790 1309 3790 1310 645 1310 2068 1310 3790 1311 2068 1311 3775 1311 3932 1312 3825 1312 3933 1312 3933 1313 3825 1313 3826 1313 650 1314 646 1314 647 1314 2063 1315 3790 1315 648 1315 648 1316 3790 1316 3933 1316 648 1317 3933 1317 1344 1317 650 1318 3829 1318 649 1318 649 1319 3829 1319 1338 1319 650 1320 647 1320 3829 1320 3829 1321 647 1321 1342 1321 3829 1322 1342 1322 654 1322 3826 1323 651 1323 3933 1323 3933 1324 651 1324 652 1324 3933 1325 652 1325 1344 1325 1344 1326 652 1326 3829 1326 1344 1327 3829 1327 653 1327 653 1328 3829 1328 654 1328 657 1329 753 1329 754 1329 2108 1330 655 1330 644 1330 644 1331 655 1331 754 1331 644 1332 754 1332 656 1332 657 1333 754 1333 658 1333 658 1334 754 1334 655 1334 658 1335 655 1335 2074 1335 670 1336 1145 1336 1325 1336 659 1337 660 1337 667 1337 664 1338 661 1338 3839 1338 3839 1339 661 1339 1335 1339 3839 1340 1335 1340 3838 1340 3838 1341 1335 1341 1336 1341 3838 1342 1336 1342 662 1342 3832 1343 679 1343 3833 1343 3833 1344 679 1344 1371 1344 3833 1345 1371 1345 664 1345 664 1346 1371 1346 663 1346 664 1347 663 1347 661 1347 665 1348 666 1348 685 1348 667 1349 660 1349 683 1349 687 1350 668 1350 1158 1350 1213 1351 669 1351 1325 1351 1325 1352 669 1352 1149 1352 1325 1353 1149 1353 670 1353 659 1354 667 1354 727 1354 727 1355 667 1355 3851 1355 727 1356 3851 1356 671 1356 671 1357 3851 1357 3848 1357 671 1358 3848 1358 672 1358 3840 1359 673 1359 3832 1359 3832 1360 673 1360 1511 1360 668 1361 687 1361 674 1361 674 1362 687 1362 690 1362 674 1363 690 1363 1161 1363 1158 1364 1155 1364 687 1364 687 1365 1155 1365 1182 1365 687 1366 1182 1366 1181 1366 675 1367 676 1367 679 1367 679 1368 676 1368 1519 1368 679 1369 1519 1369 1515 1369 1177 1370 1482 1370 677 1370 1172 1371 1173 1371 1487 1371 1511 1372 1510 1372 3832 1372 3832 1373 1510 1373 1509 1373 3832 1374 1509 1374 679 1374 679 1375 1509 1375 678 1375 679 1376 678 1376 675 1376 1515 1377 1514 1377 679 1377 679 1378 1514 1378 1513 1378 679 1379 1513 1379 1512 1379 1145 1380 680 1380 1325 1380 1325 1381 680 1381 679 1381 1325 1382 679 1382 681 1382 681 1383 679 1383 1512 1383 1177 1384 677 1384 1175 1384 677 1385 1483 1385 1175 1385 1175 1386 1483 1386 682 1386 1175 1387 682 1387 1173 1387 1173 1388 682 1388 1485 1388 1173 1389 1485 1389 1487 1389 660 1390 684 1390 683 1390 683 1391 684 1391 690 1391 683 1392 690 1392 685 1392 685 1393 690 1393 1542 1393 685 1394 1542 1394 1543 1394 1543 1395 686 1395 685 1395 685 1396 686 1396 1544 1396 685 1397 1544 1397 665 1397 1482 1398 1177 1398 1480 1398 1480 1399 1177 1399 1178 1399 1480 1400 1178 1400 1478 1400 1181 1401 1188 1401 687 1401 687 1402 1188 1402 688 1402 687 1403 688 1403 1325 1403 1325 1404 688 1404 1203 1404 1325 1405 1203 1405 1213 1405 699 1406 1493 1406 689 1406 1562 1407 1563 1407 690 1407 690 1408 1563 1408 1540 1408 690 1409 1540 1409 1542 1409 1478 1410 1178 1410 1476 1410 1476 1411 1178 1411 691 1411 1476 1412 691 1412 1475 1412 699 1413 689 1413 1169 1413 1487 1414 1488 1414 1172 1414 1172 1415 1488 1415 693 1415 1172 1416 693 1416 692 1416 692 1417 693 1417 694 1417 687 1418 695 1418 690 1418 690 1419 695 1419 696 1419 690 1420 696 1420 1551 1420 1179 1421 1467 1421 1468 1421 694 1422 1489 1422 692 1422 692 1423 1489 1423 698 1423 692 1424 698 1424 697 1424 697 1425 698 1425 1490 1425 697 1426 1490 1426 699 1426 699 1427 1490 1427 1491 1427 699 1428 1491 1428 1493 1428 1551 1429 1538 1429 690 1429 690 1430 1538 1430 700 1430 690 1431 700 1431 1562 1431 703 1432 706 1432 709 1432 1179 1433 1468 1433 701 1433 689 1434 1495 1434 1169 1434 1169 1435 1495 1435 1497 1435 1169 1436 1497 1436 711 1436 709 1437 702 1437 703 1437 703 1438 702 1438 704 1438 703 1439 704 1439 691 1439 691 1440 704 1440 1474 1440 691 1441 1474 1441 1475 1441 1468 1442 705 1442 701 1442 701 1443 705 1443 707 1443 701 1444 707 1444 706 1444 706 1445 707 1445 708 1445 706 1446 708 1446 709 1446 1467 1447 1179 1447 710 1447 710 1448 1179 1448 715 1448 710 1449 715 1449 1465 1449 1497 1450 712 1450 711 1450 711 1451 712 1451 1500 1451 711 1452 1500 1452 1166 1452 1166 1453 1500 1453 713 1453 1166 1454 713 1454 714 1454 714 1455 713 1455 679 1455 714 1456 679 1456 1135 1456 1135 1457 679 1457 680 1457 1161 1458 690 1458 1163 1458 1163 1459 690 1459 1462 1459 1163 1460 1462 1460 715 1460 715 1461 1462 1461 1463 1461 715 1462 1463 1462 1465 1462 2119 1463 716 1463 718 1463 718 1464 716 1464 717 1464 718 1465 717 1465 762 1465 762 1466 717 1466 743 1466 762 1467 743 1467 764 1467 764 1468 743 1468 765 1468 765 1469 743 1469 741 1469 765 1470 741 1470 766 1470 766 1471 741 1471 719 1471 766 1472 719 1472 767 1472 719 1473 720 1473 767 1473 767 1474 720 1474 750 1474 767 1475 750 1475 769 1475 769 1476 750 1476 721 1476 769 1477 721 1477 722 1477 722 1478 721 1478 724 1478 722 1479 724 1479 723 1479 723 1480 724 1480 725 1480 723 1481 725 1481 760 1481 721 1482 750 1482 726 1482 743 1483 717 1483 742 1483 659 1484 727 1484 728 1484 660 1485 659 1485 744 1485 725 1486 724 1486 633 1486 633 1487 724 1487 752 1487 633 1488 752 1488 636 1488 636 1489 752 1489 637 1489 637 1490 752 1490 751 1490 637 1491 751 1491 638 1491 638 1492 751 1492 729 1492 729 1493 751 1493 734 1493 729 1494 734 1494 733 1494 730 1495 731 1495 734 1495 731 1496 732 1496 734 1496 734 1497 732 1497 641 1497 734 1498 641 1498 733 1498 672 1499 735 1499 734 1499 734 1500 735 1500 736 1500 734 1501 736 1501 730 1501 727 1502 671 1502 747 1502 747 1503 671 1503 672 1503 660 1504 739 1504 684 1504 684 1505 739 1505 1502 1505 1502 1506 739 1506 737 1506 737 1507 739 1507 738 1507 737 1508 738 1508 1503 1508 1503 1509 738 1509 1506 1509 1506 1510 738 1510 742 1510 1506 1511 742 1511 1505 1511 1505 1512 742 1512 717 1512 1505 1513 717 1513 716 1513 660 1514 744 1514 739 1514 739 1515 744 1515 746 1515 739 1516 746 1516 738 1516 738 1517 746 1517 740 1517 738 1518 740 1518 742 1518 742 1519 740 1519 741 1519 742 1520 741 1520 743 1520 749 1521 720 1521 719 1521 659 1522 728 1522 744 1522 744 1523 728 1523 745 1523 744 1524 745 1524 746 1524 746 1525 745 1525 749 1525 746 1526 749 1526 740 1526 740 1527 749 1527 719 1527 740 1528 719 1528 741 1528 727 1529 747 1529 728 1529 728 1530 747 1530 748 1530 728 1531 748 1531 745 1531 745 1532 748 1532 726 1532 745 1533 726 1533 749 1533 749 1534 726 1534 750 1534 749 1535 750 1535 720 1535 672 1536 734 1536 747 1536 747 1537 734 1537 751 1537 747 1538 751 1538 748 1538 748 1539 751 1539 752 1539 748 1540 752 1540 726 1540 726 1541 752 1541 724 1541 726 1542 724 1542 721 1542 634 1543 635 1543 770 1543 657 1544 1114 1544 753 1544 753 1545 1114 1545 755 1545 753 1546 755 1546 754 1546 787 1547 3772 1547 788 1547 788 1548 3772 1548 3771 1548 788 1549 3771 1549 3770 1549 754 1550 755 1550 656 1550 656 1551 755 1551 794 1551 656 1552 794 1552 756 1552 3766 1553 757 1553 785 1553 785 1554 757 1554 3763 1554 785 1555 3763 1555 3762 1555 771 1556 758 1556 780 1556 780 1557 758 1557 759 1557 780 1558 759 1558 3767 1558 634 1559 770 1559 760 1559 761 1560 2119 1560 778 1560 778 1561 2119 1561 718 1561 778 1562 718 1562 775 1562 718 1563 762 1563 775 1563 775 1564 762 1564 764 1564 775 1565 764 1565 763 1565 764 1566 765 1566 763 1566 763 1567 765 1567 766 1567 763 1568 766 1568 773 1568 766 1569 767 1569 773 1569 773 1570 767 1570 769 1570 773 1571 769 1571 768 1571 768 1572 769 1572 722 1572 768 1573 722 1573 770 1573 770 1574 722 1574 723 1574 770 1575 723 1575 760 1575 635 1576 771 1576 770 1576 770 1577 771 1577 780 1577 770 1578 780 1578 768 1578 768 1579 780 1579 772 1579 768 1580 772 1580 773 1580 773 1581 772 1581 774 1581 773 1582 774 1582 763 1582 763 1583 774 1583 781 1583 763 1584 781 1584 775 1584 775 1585 781 1585 776 1585 775 1586 776 1586 778 1586 778 1587 776 1587 782 1587 784 1588 777 1588 782 1588 782 1589 777 1589 2114 1589 782 1590 2114 1590 778 1590 778 1591 2114 1591 779 1591 778 1592 779 1592 761 1592 3767 1593 3766 1593 780 1593 780 1594 3766 1594 785 1594 780 1595 785 1595 772 1595 772 1596 785 1596 786 1596 772 1597 786 1597 774 1597 774 1598 786 1598 789 1598 774 1599 789 1599 781 1599 781 1600 789 1600 791 1600 781 1601 791 1601 776 1601 776 1602 791 1602 792 1602 776 1603 792 1603 782 1603 782 1604 792 1604 783 1604 782 1605 783 1605 784 1605 784 1606 783 1606 2123 1606 3762 1607 3769 1607 785 1607 785 1608 3769 1608 787 1608 785 1609 787 1609 786 1609 786 1610 787 1610 788 1610 786 1611 788 1611 789 1611 789 1612 788 1612 790 1612 789 1613 790 1613 791 1613 791 1614 790 1614 795 1614 791 1615 795 1615 792 1615 792 1616 795 1616 793 1616 792 1617 793 1617 783 1617 783 1618 793 1618 796 1618 783 1619 796 1619 2123 1619 2123 1620 796 1620 798 1620 3770 1621 756 1621 788 1621 788 1622 756 1622 794 1622 788 1623 794 1623 790 1623 790 1624 794 1624 1099 1624 790 1625 1099 1625 795 1625 795 1626 1099 1626 1098 1626 795 1627 1098 1627 793 1627 793 1628 1098 1628 1101 1628 793 1629 1101 1629 796 1629 796 1630 1101 1630 797 1630 796 1631 797 1631 798 1631 798 1632 797 1632 1093 1632 850 1633 3759 1633 799 1633 799 1634 3759 1634 3758 1634 1012 1635 800 1635 801 1635 1584 1636 803 1636 1582 1636 1582 1637 803 1637 802 1637 1565 1638 1279 1638 1564 1638 1564 1639 1279 1639 2218 1639 3748 1640 938 1640 1001 1640 1001 1641 1151 1641 1290 1641 1565 1642 802 1642 1279 1642 1279 1643 802 1643 803 1643 1279 1644 803 1644 1290 1644 1290 1645 803 1645 1012 1645 1290 1646 1012 1646 1001 1646 1001 1647 1012 1647 801 1647 1001 1648 801 1648 3748 1648 804 1649 840 1649 805 1649 804 1650 805 1650 806 1650 806 1651 805 1651 623 1651 806 1652 623 1652 807 1652 807 1653 623 1653 622 1653 807 1654 622 1654 808 1654 808 1655 622 1655 809 1655 808 1656 809 1656 810 1656 810 1657 809 1657 618 1657 810 1658 618 1658 811 1658 811 1659 618 1659 619 1659 811 1660 619 1660 2258 1660 2258 1661 619 1661 812 1661 2258 1662 812 1662 813 1662 813 1663 812 1663 814 1663 813 1664 814 1664 815 1664 815 1665 814 1665 624 1665 815 1666 624 1666 2261 1666 2261 1667 624 1667 816 1667 2261 1668 816 1668 2263 1668 2263 1669 816 1669 817 1669 2263 1670 817 1670 833 1670 818 1671 837 1671 611 1671 611 1672 837 1672 819 1672 832 1673 831 1673 625 1673 832 1674 625 1674 820 1674 820 1675 625 1675 616 1675 820 1676 616 1676 2253 1676 2253 1677 616 1677 615 1677 2253 1678 615 1678 2254 1678 2254 1679 615 1679 821 1679 2254 1680 821 1680 2257 1680 2257 1681 821 1681 823 1681 2257 1682 823 1682 822 1682 822 1683 823 1683 604 1683 822 1684 604 1684 824 1684 824 1685 604 1685 608 1685 824 1686 608 1686 825 1686 825 1687 608 1687 607 1687 825 1688 607 1688 2247 1688 2247 1689 607 1689 621 1689 2247 1690 621 1690 826 1690 826 1691 621 1691 827 1691 826 1692 827 1692 828 1692 828 1693 827 1693 620 1693 828 1694 620 1694 2250 1694 829 1695 2265 1695 629 1695 629 1696 2265 1696 2264 1696 2265 1697 829 1697 627 1697 2265 1698 627 1698 830 1698 830 1699 627 1699 626 1699 830 1700 626 1700 2251 1700 2251 1701 626 1701 831 1701 2251 1702 831 1702 832 1702 833 1703 817 1703 628 1703 833 1704 628 1704 834 1704 834 1705 628 1705 835 1705 834 1706 835 1706 836 1706 836 1707 835 1707 629 1707 836 1708 629 1708 2264 1708 837 1709 818 1709 617 1709 837 1710 617 1710 838 1710 838 1711 617 1711 839 1711 838 1712 839 1712 2272 1712 2272 1713 839 1713 840 1713 2272 1714 840 1714 804 1714 2250 1715 620 1715 606 1715 2250 1716 606 1716 2270 1716 2270 1717 606 1717 605 1717 2270 1718 605 1718 2271 1718 2271 1719 605 1719 611 1719 2271 1720 611 1720 819 1720 841 1721 1307 1721 842 1721 841 1722 842 1722 843 1722 843 1723 842 1723 844 1723 843 1724 844 1724 845 1724 845 1725 844 1725 846 1725 845 1726 846 1726 613 1726 613 1727 846 1727 847 1727 613 1728 847 1728 848 1728 848 1729 847 1729 1303 1729 848 1730 1303 1730 849 1730 849 1731 1303 1731 850 1731 849 1732 850 1732 799 1732 3650 1733 800 1733 3651 1733 3651 1734 800 1734 1012 1734 871 1735 851 1735 3661 1735 3661 1736 851 1736 994 1736 1003 1737 852 1737 3725 1737 3725 1738 852 1738 864 1738 1573 1739 1603 1739 2224 1739 1574 1740 1573 1740 2235 1740 2235 1741 1573 1741 2224 1741 2235 1742 2224 1742 853 1742 853 1743 2224 1743 1271 1743 853 1744 1271 1744 3680 1744 3680 1745 1271 1745 854 1745 2236 1746 2235 1746 853 1746 855 1747 856 1747 3708 1747 3708 1748 856 1748 2238 1748 3708 1749 2238 1749 853 1749 853 1750 2238 1750 857 1750 853 1751 857 1751 2236 1751 861 1752 2234 1752 3709 1752 3709 1753 2234 1753 858 1753 3709 1754 858 1754 855 1754 855 1755 858 1755 2239 1755 855 1756 2239 1756 856 1756 865 1757 860 1757 859 1757 859 1758 860 1758 2231 1758 859 1759 2231 1759 861 1759 861 1760 2231 1760 862 1760 861 1761 862 1761 2234 1761 3725 1762 864 1762 863 1762 863 1763 864 1763 2225 1763 863 1764 2225 1764 865 1764 865 1765 2225 1765 866 1765 865 1766 866 1766 860 1766 3680 1767 854 1767 867 1767 867 1768 854 1768 1153 1768 3681 1769 3683 1769 869 1769 869 1770 3683 1770 3684 1770 869 1771 3684 1771 1153 1771 1153 1772 3684 1772 868 1772 1153 1773 868 1773 867 1773 3681 1774 869 1774 870 1774 870 1775 869 1775 851 1775 870 1776 851 1776 871 1776 3334 1777 872 1777 1789 1777 892 1778 2177 1778 893 1778 873 1779 1774 1779 877 1779 877 1780 1774 1780 875 1780 3334 1781 1789 1781 3347 1781 1774 1782 874 1782 875 1782 875 1783 874 1783 876 1783 875 1784 876 1784 894 1784 894 1785 876 1785 1757 1785 894 1786 1757 1786 892 1786 1789 1787 1790 1787 3347 1787 3347 1788 1790 1788 1787 1788 3347 1789 1787 1789 877 1789 877 1790 1787 1790 1777 1790 877 1791 1777 1791 873 1791 872 1792 3334 1792 1796 1792 1796 1793 3334 1793 878 1793 1796 1794 878 1794 883 1794 3336 1795 879 1795 1808 1795 885 1796 886 1796 879 1796 879 1797 886 1797 1733 1797 879 1798 1733 1798 1808 1798 3583 1799 3582 1799 894 1799 1808 1800 880 1800 3336 1800 3336 1801 880 1801 881 1801 3336 1802 881 1802 878 1802 878 1803 881 1803 882 1803 878 1804 882 1804 883 1804 3533 1805 3532 1805 906 1805 906 1806 3532 1806 3382 1806 3382 1807 884 1807 906 1807 906 1808 884 1808 1744 1808 906 1809 1744 1809 885 1809 885 1810 1744 1810 1738 1810 885 1811 1738 1811 886 1811 887 1812 888 1812 3548 1812 3344 1813 901 1813 888 1813 888 1814 901 1814 889 1814 888 1815 889 1815 3548 1815 3582 1816 3580 1816 894 1816 894 1817 3580 1817 890 1817 894 1818 890 1818 900 1818 900 1819 890 1819 891 1819 900 1820 891 1820 3566 1820 892 1821 893 1821 894 1821 894 1822 893 1822 895 1822 894 1823 895 1823 3583 1823 896 1824 3534 1824 906 1824 906 1825 3534 1825 897 1825 906 1826 897 1826 3533 1826 3548 1827 898 1827 887 1827 887 1828 898 1828 902 1828 887 1829 902 1829 904 1829 3566 1830 3558 1830 900 1830 900 1831 3558 1831 899 1831 900 1832 899 1832 3344 1832 3344 1833 899 1833 3546 1833 3344 1834 3546 1834 901 1834 902 1835 903 1835 904 1835 904 1836 903 1836 905 1836 904 1837 905 1837 906 1837 906 1838 905 1838 907 1838 906 1839 907 1839 896 1839 928 1840 2697 1840 908 1840 908 1841 2697 1841 2698 1841 2698 1842 1217 1842 908 1842 908 1843 1217 1843 1245 1843 908 1844 1245 1844 1333 1844 1239 1845 913 1845 1236 1845 1236 1846 913 1846 2703 1846 1236 1847 2703 1847 909 1847 1245 1848 1243 1848 1333 1848 1333 1849 1243 1849 910 1849 1333 1850 910 1850 920 1850 920 1851 910 1851 1236 1851 920 1852 1236 1852 2705 1852 2705 1853 1236 1853 909 1853 2701 1854 1223 1854 2700 1854 2700 1855 1223 1855 1225 1855 2700 1856 1225 1856 2698 1856 2698 1857 1225 1857 911 1857 2698 1858 911 1858 1217 1858 1239 1859 1232 1859 913 1859 913 1860 1232 1860 912 1860 913 1861 912 1861 2701 1861 2701 1862 912 1862 1229 1862 2701 1863 1229 1863 1223 1863 913 1864 2701 1864 1302 1864 1302 1865 2701 1865 1301 1865 2710 1866 915 1866 2713 1866 2713 1867 915 1867 914 1867 2710 1868 916 1868 915 1868 915 1869 916 1869 2709 1869 915 1870 2709 1870 1299 1870 914 1871 917 1871 2713 1871 2713 1872 917 1872 3922 1872 2713 1873 3922 1873 3921 1873 922 1874 918 1874 2715 1874 3921 1875 3926 1875 2713 1875 2713 1876 3926 1876 922 1876 2713 1877 922 1877 2714 1877 2714 1878 922 1878 2715 1878 1333 1879 920 1879 919 1879 919 1880 920 1880 921 1880 919 1881 921 1881 1536 1881 1536 1882 921 1882 2706 1882 922 1883 3925 1883 918 1883 918 1884 3925 1884 923 1884 918 1885 923 1885 924 1885 924 1886 923 1886 1536 1886 924 1887 1536 1887 925 1887 925 1888 1536 1888 2706 1888 930 1889 926 1889 1530 1889 1530 1890 926 1890 927 1890 927 1891 926 1891 928 1891 927 1892 928 1892 908 1892 931 1893 2695 1893 929 1893 929 1894 2695 1894 2694 1894 929 1895 2694 1895 2693 1895 3889 1896 929 1896 1526 1896 1526 1897 929 1897 2693 1897 1526 1898 2693 1898 1530 1898 1530 1899 2693 1899 2692 1899 1530 1900 2692 1900 930 1900 931 1901 929 1901 932 1901 932 1902 929 1902 3887 1902 932 1903 3887 1903 3886 1903 933 1904 934 1904 937 1904 3886 1905 935 1905 932 1905 932 1906 935 1906 3891 1906 932 1907 3891 1907 936 1907 936 1908 3891 1908 933 1908 936 1909 933 1909 2691 1909 2691 1910 933 1910 937 1910 938 1911 3753 1911 1001 1911 2259 1912 2424 1912 2245 1912 2245 1913 2424 1913 939 1913 2245 1914 939 1914 2423 1914 940 1915 2339 1915 2259 1915 2259 1916 2339 1916 941 1916 2259 1917 941 1917 2424 1917 940 1918 2259 1918 942 1918 942 1919 2259 1919 943 1919 942 1920 943 1920 944 1920 950 1921 945 1921 2260 1921 2260 1922 945 1922 946 1922 2260 1923 946 1923 943 1923 943 1924 946 1924 2341 1924 943 1925 2341 1925 944 1925 947 1926 948 1926 953 1926 953 1927 948 1927 949 1927 953 1928 949 1928 2260 1928 2260 1929 949 1929 2331 1929 2260 1930 2331 1930 950 1930 2262 1931 2308 1931 951 1931 951 1932 952 1932 2262 1932 2262 1933 952 1933 2312 1933 2262 1934 2312 1934 953 1934 953 1935 2312 1935 2311 1935 953 1936 2311 1936 947 1936 2303 1937 2302 1937 2268 1937 2268 1938 2302 1938 2300 1938 2300 1939 954 1939 2268 1939 2268 1940 954 1940 955 1940 2268 1941 955 1941 2266 1941 2266 1942 955 1942 2309 1942 2266 1943 2309 1943 2262 1943 2262 1944 2309 1944 956 1944 2262 1945 956 1945 2308 1945 2269 1946 957 1946 2296 1946 2296 1947 2305 1947 2269 1947 2269 1948 2305 1948 958 1948 2269 1949 958 1949 2268 1949 2268 1950 958 1950 2304 1950 2268 1951 2304 1951 2303 1951 957 1952 2269 1952 2298 1952 2298 1953 2269 1953 959 1953 2298 1954 959 1954 2292 1954 2292 1955 959 1955 2291 1955 2291 1956 959 1956 962 1956 2291 1957 962 1957 960 1957 2284 1958 961 1958 962 1958 962 1959 961 1959 2283 1959 962 1960 2283 1960 960 1960 964 1961 965 1961 963 1961 964 1962 963 1962 962 1962 962 1963 963 1963 2277 1963 962 1964 2277 1964 2284 1964 2423 1965 2421 1965 2245 1965 2245 1966 2421 1966 2282 1966 2245 1967 2282 1967 964 1967 964 1968 2282 1968 2281 1968 964 1969 2281 1969 965 1969 966 1970 2514 1970 2252 1970 2267 1971 967 1971 968 1971 2516 1972 2525 1972 2249 1972 2249 1973 2525 1973 2523 1973 2249 1974 2523 1974 2267 1974 2267 1975 2523 1975 2521 1975 2267 1976 2521 1976 967 1976 2252 1977 2514 1977 969 1977 2514 1978 970 1978 969 1978 969 1979 970 1979 2512 1979 969 1980 2512 1980 971 1980 971 1981 2519 1981 969 1981 969 1982 2519 1982 972 1982 969 1983 972 1983 2249 1983 2249 1984 972 1984 2518 1984 2249 1985 2518 1985 2516 1985 2488 1986 2487 1986 2255 1986 2255 1987 2487 1987 2486 1987 2255 1988 2486 1988 2252 1988 2252 1989 2486 1989 973 1989 2252 1990 973 1990 966 1990 976 1991 2484 1991 2256 1991 2256 1992 2484 1992 2483 1992 2256 1993 2483 1993 2255 1993 2255 1994 2483 1994 2482 1994 2255 1995 2482 1995 2488 1995 974 1996 2478 1996 2256 1996 2256 1997 2478 1997 975 1997 2256 1998 975 1998 976 1998 2474 1999 2472 1999 977 1999 977 2000 2472 2000 978 2000 977 2001 978 2001 974 2001 974 2002 978 2002 2479 2002 974 2003 2479 2003 2478 2003 2469 2004 2467 2004 2246 2004 2246 2005 2467 2005 2477 2005 2246 2006 2477 2006 977 2006 977 2007 2477 2007 979 2007 977 2008 979 2008 2474 2008 984 2009 2471 2009 2248 2009 2248 2010 2471 2010 980 2010 2248 2011 980 2011 2246 2011 2246 2012 980 2012 2470 2012 2246 2013 2470 2013 2469 2013 981 2014 2457 2014 990 2014 990 2015 2457 2015 982 2015 990 2016 982 2016 2248 2016 2248 2017 982 2017 983 2017 2248 2018 983 2018 984 2018 985 2019 987 2019 986 2019 986 2020 987 2020 988 2020 986 2021 988 2021 990 2021 990 2022 988 2022 989 2022 990 2023 989 2023 981 2023 968 2024 2617 2024 2267 2024 2267 2025 2617 2025 991 2025 2267 2026 991 2026 2615 2026 2615 2027 2614 2027 2267 2027 2267 2028 2614 2028 992 2028 2267 2029 992 2029 986 2029 986 2030 992 2030 993 2030 986 2031 993 2031 985 2031 3661 2032 994 2032 995 2032 995 2033 994 2033 1154 2033 996 2034 3663 2034 997 2034 997 2035 3663 2035 998 2035 997 2036 998 2036 1154 2036 1154 2037 998 2037 999 2037 1154 2038 999 2038 995 2038 1001 2039 3753 2039 1000 2039 996 2040 997 2040 1000 2040 1000 2041 997 2041 1151 2041 1000 2042 1151 2042 1001 2042 1004 2043 2244 2043 2226 2043 1004 2044 2226 2044 1002 2044 1002 2045 2226 2045 852 2045 1002 2046 852 2046 1003 2046 3736 2047 2240 2047 1004 2047 1004 2048 2240 2048 1005 2048 1004 2049 1005 2049 2244 2049 1011 2050 1006 2050 1007 2050 1007 2051 1006 2051 2240 2051 1007 2052 2240 2052 3737 2052 3737 2053 2240 2053 3736 2053 1013 2054 2242 2054 1008 2054 1008 2055 2242 2055 1009 2055 1008 2056 1009 2056 1007 2056 1007 2057 1009 2057 1010 2057 1007 2058 1010 2058 1011 2058 3651 2059 1012 2059 1008 2059 1008 2060 1012 2060 803 2060 1008 2061 803 2061 1013 2061 3412 2062 3413 2062 1368 2062 2928 2063 2929 2063 1088 2063 2925 2064 1014 2064 1088 2064 1088 2065 1014 2065 1015 2065 1088 2066 1015 2066 2928 2066 1088 2067 1411 2067 2925 2067 2925 2068 1411 2068 1410 2068 2925 2069 1410 2069 2952 2069 1017 2070 1016 2070 1018 2070 1017 2071 1018 2071 2680 2071 2680 2072 1018 2072 1019 2072 2680 2073 1019 2073 1020 2073 1410 2074 1021 2074 2952 2074 2952 2075 1021 2075 1022 2075 2952 2076 1022 2076 1023 2076 1023 2077 1022 2077 1024 2077 2987 2078 2985 2078 1397 2078 1397 2079 2985 2079 2983 2079 1397 2080 2983 2080 1398 2080 1398 2081 2983 2081 1025 2081 1398 2082 1025 2082 1026 2082 1026 2083 1025 2083 2982 2083 1026 2084 2982 2084 1400 2084 1400 2085 2982 2085 1027 2085 1400 2086 1027 2086 1401 2086 1401 2087 1027 2087 1028 2087 1401 2088 1028 2088 1403 2088 1403 2089 1028 2089 1029 2089 1403 2090 1029 2090 1030 2090 1030 2091 1029 2091 2981 2091 1030 2092 2981 2092 1031 2092 1031 2093 2981 2093 1033 2093 1031 2094 1033 2094 1032 2094 1032 2095 1033 2095 1034 2095 1032 2096 1034 2096 1405 2096 1405 2097 1034 2097 1035 2097 1405 2098 1035 2098 1036 2098 1036 2099 1035 2099 2979 2099 1036 2100 2979 2100 1037 2100 1037 2101 2979 2101 1038 2101 1037 2102 1038 2102 1039 2102 1039 2103 1038 2103 2954 2103 1039 2104 2954 2104 1022 2104 1022 2105 2954 2105 2953 2105 1022 2106 2953 2106 1024 2106 1386 2107 3001 2107 1050 2107 1050 2108 3001 2108 3000 2108 1397 2109 1396 2109 2987 2109 2987 2110 1396 2110 1041 2110 2987 2111 1041 2111 1040 2111 1040 2112 1041 2112 1042 2112 1040 2113 1042 2113 2988 2113 2988 2114 1042 2114 1394 2114 2988 2115 1394 2115 1043 2115 1043 2116 1394 2116 1393 2116 1043 2117 1393 2117 2991 2117 2991 2118 1393 2118 1044 2118 2991 2119 1044 2119 2992 2119 2992 2120 1044 2120 1392 2120 2992 2121 1392 2121 1046 2121 1046 2122 1392 2122 1045 2122 1046 2123 1045 2123 1047 2123 1047 2124 1045 2124 1390 2124 1047 2125 1390 2125 2993 2125 2993 2126 1390 2126 1389 2126 2993 2127 1389 2127 2996 2127 2996 2128 1389 2128 1048 2128 2996 2129 1048 2129 2997 2129 2997 2130 1048 2130 1049 2130 2997 2131 1049 2131 2999 2131 2999 2132 1049 2132 1388 2132 2999 2133 1388 2133 3000 2133 3000 2134 1388 2134 1387 2134 3000 2135 1387 2135 1050 2135 1051 2136 1055 2136 3096 2136 3096 2137 1055 2137 1052 2137 3096 2138 1052 2138 1382 2138 1051 2139 3093 2139 1055 2139 1055 2140 3093 2140 1053 2140 1055 2141 1053 2141 1054 2141 1054 2142 3077 2142 1055 2142 1055 2143 3077 2143 1056 2143 1055 2144 1056 2144 3069 2144 3069 2145 1057 2145 1055 2145 1055 2146 1057 2146 3050 2146 1055 2147 3050 2147 1058 2147 1058 2148 3050 2148 3056 2148 1058 2149 3056 2149 1386 2149 1386 2150 3056 2150 3042 2150 1386 2151 3042 2151 3001 2151 2637 2152 1059 2152 1062 2152 1062 2153 1059 2153 1060 2153 1062 2154 1060 2154 1377 2154 1377 2155 1060 2155 1378 2155 3104 2156 3096 2156 1061 2156 1061 2157 3096 2157 1382 2157 1061 2158 1382 2158 1060 2158 1060 2159 1382 2159 1381 2159 1060 2160 1381 2160 1378 2160 1068 2161 2640 2161 1062 2161 1062 2162 2640 2162 1063 2162 1062 2163 1063 2163 2637 2163 1064 2164 1065 2164 1066 2164 1066 2165 1065 2165 1068 2165 1066 2166 1068 2166 1067 2166 1067 2167 1068 2167 1062 2167 1067 2168 1062 2168 3482 2168 3482 2169 1062 2169 1376 2169 3482 2170 1376 2170 1069 2170 3478 2171 1070 2171 3480 2171 3480 2172 1070 2172 1071 2172 3480 2173 1071 2173 1066 2173 1066 2174 1071 2174 2650 2174 1066 2175 2650 2175 1064 2175 1376 2176 1375 2176 1069 2176 1069 2177 1375 2177 1074 2177 1069 2178 1074 2178 3484 2178 3484 2179 1074 2179 1075 2179 1072 2180 1374 2180 1073 2180 1072 2181 1073 2181 1079 2181 1374 2182 1072 2182 1074 2182 1074 2183 1072 2183 3486 2183 1074 2184 3486 2184 1075 2184 1132 2185 1076 2185 1504 2185 1504 2186 1076 2186 1077 2186 1504 2187 1077 2187 1078 2187 1078 2188 1077 2188 1079 2188 1078 2189 1079 2189 1080 2189 1080 2190 1079 2190 1073 2190 1091 2191 3402 2191 1082 2191 3402 2192 1081 2192 1082 2192 1082 2193 1081 2193 3399 2193 1082 2194 3399 2194 3397 2194 3397 2195 3396 2195 1082 2195 1082 2196 3396 2196 1083 2196 1082 2197 1083 2197 1415 2197 3412 2198 1368 2198 3411 2198 3411 2199 1368 2199 1084 2199 3411 2200 1084 2200 3409 2200 3409 2201 1084 2201 1085 2201 3409 2202 1085 2202 3404 2202 3404 2203 1085 2203 1086 2203 3404 2204 1086 2204 1083 2204 1083 2205 1086 2205 1416 2205 1083 2206 1416 2206 1415 2206 1090 2207 1087 2207 1082 2207 2929 2208 1016 2208 1088 2208 1088 2209 1016 2209 1017 2209 1088 2210 1017 2210 1412 2210 1412 2211 1017 2211 1089 2211 1412 2212 1089 2212 1082 2212 1082 2213 1089 2213 2681 2213 1082 2214 2681 2214 1090 2214 1087 2215 2684 2215 1082 2215 1082 2216 2684 2216 2685 2216 1082 2217 2685 2217 2686 2217 2663 2218 1091 2218 1092 2218 1092 2219 1091 2219 1082 2219 1092 2220 1082 2220 2688 2220 2688 2221 1082 2221 2686 2221 1100 2222 2121 2222 1093 2222 2105 2223 2212 2223 1094 2223 1094 2224 2214 2224 2105 2224 2105 2225 2214 2225 1095 2225 2105 2226 1095 2226 2107 2226 2107 2227 1095 2227 1102 2227 2109 2228 1096 2228 1103 2228 1686 2229 1097 2229 1104 2229 1104 2230 1097 2230 1111 2230 1101 2231 1098 2231 1114 2231 1114 2232 1098 2232 1099 2232 1114 2233 1099 2233 755 2233 755 2234 1099 2234 794 2234 1100 2235 1093 2235 1114 2235 1114 2236 1093 2236 797 2236 1114 2237 797 2237 1101 2237 1102 2238 1095 2238 1103 2238 1103 2239 1095 2239 2073 2239 1103 2240 2073 2240 2109 2240 2763 2241 2728 2241 1111 2241 1111 2242 2728 2242 2753 2242 1111 2243 2753 2243 1104 2243 2214 2244 1967 2244 1095 2244 1095 2245 1967 2245 1105 2245 1095 2246 1105 2246 1114 2246 1114 2247 1105 2247 2048 2247 1114 2248 2048 2248 1106 2248 1117 2249 3297 2249 1106 2249 1106 2250 3297 2250 1107 2250 1108 2251 1109 2251 1117 2251 1117 2252 1109 2252 1110 2252 2716 2253 2725 2253 1111 2253 1111 2254 2725 2254 2721 2254 1111 2255 2721 2255 2763 2255 1107 2256 1112 2256 1106 2256 1106 2257 1112 2257 1113 2257 1106 2258 1113 2258 1114 2258 1114 2259 1113 2259 2167 2259 1114 2260 2167 2260 1100 2260 1108 2261 1117 2261 3270 2261 3270 2262 1117 2262 1115 2262 3270 2263 1115 2263 1662 2263 2214 2264 2720 2264 1967 2264 1967 2265 2720 2265 1116 2265 1967 2266 1116 2266 1111 2266 1111 2267 1116 2267 2718 2267 1111 2268 2718 2268 2716 2268 1110 2269 3289 2269 1117 2269 1117 2270 3289 2270 3290 2270 1117 2271 3290 2271 3297 2271 1368 2272 3413 2272 1320 2272 1320 2273 3413 2273 1118 2273 1118 2274 3440 2274 1320 2274 1320 2275 3440 2275 3439 2275 1320 2276 3439 2276 2060 2276 2060 2277 3439 2277 1119 2277 2060 2278 1119 2278 2059 2278 1120 2279 1288 2279 1121 2279 1121 2280 1288 2280 1289 2280 1121 2281 1289 2281 1122 2281 1122 2282 1289 2282 1123 2282 1123 2283 1289 2283 1124 2283 1124 2284 1289 2284 1280 2284 1124 2285 1280 2285 1612 2285 1281 2286 1125 2286 1126 2286 1126 2287 1127 2287 1281 2287 1281 2288 1127 2288 1128 2288 1281 2289 1128 2289 1280 2289 1280 2290 1128 2290 1129 2290 1280 2291 1129 2291 1612 2291 1134 2292 716 2292 1130 2292 1130 2293 716 2293 2119 2293 1130 2294 2119 2294 1131 2294 1132 2295 1504 2295 1133 2295 1133 2296 1504 2296 716 2296 1133 2297 716 2297 3499 2297 3499 2298 716 2298 1134 2298 1164 2299 714 2299 1135 2299 1164 2300 1135 2300 1136 2300 1136 2301 1135 2301 680 2301 1136 2302 680 2302 1137 2302 1148 2303 1147 2303 1138 2303 1139 2304 1156 2304 1140 2304 1140 2305 1156 2305 1141 2305 1140 2306 1141 2306 1142 2306 1142 2307 1141 2307 1144 2307 1142 2308 1144 2308 1143 2308 1148 2309 1138 2309 1144 2309 1144 2310 1138 2310 1207 2310 1144 2311 1207 2311 1143 2311 1137 2312 680 2312 1145 2312 1137 2313 1145 2313 1282 2313 1282 2314 1145 2314 670 2314 1282 2315 670 2315 1150 2315 1293 2316 1146 2316 1144 2316 1144 2317 1146 2317 1148 2317 1149 2318 669 2318 1147 2318 1148 2319 1146 2319 1147 2319 1147 2320 1146 2320 1291 2320 1147 2321 1291 2321 1149 2321 1149 2322 1291 2322 1150 2322 1149 2323 1150 2323 670 2323 1152 2324 1290 2324 1151 2324 1152 2325 1151 2325 1141 2325 851 2326 869 2326 1144 2326 1144 2327 869 2327 1153 2327 1144 2328 1153 2328 1293 2328 1293 2329 1153 2329 854 2329 1293 2330 854 2330 1271 2330 1151 2331 997 2331 1141 2331 1141 2332 997 2332 1154 2332 1141 2333 1154 2333 1144 2333 1144 2334 1154 2334 994 2334 1144 2335 994 2335 851 2335 1139 2336 1182 2336 1155 2336 1156 2337 1139 2337 1157 2337 1157 2338 1295 2338 1156 2338 1156 2339 1295 2339 1152 2339 1156 2340 1152 2340 1141 2340 1139 2341 1155 2341 1157 2341 1157 2342 1155 2342 1158 2342 1157 2343 1158 2343 1294 2343 1294 2344 1158 2344 668 2344 1294 2345 668 2345 1159 2345 1159 2346 668 2346 674 2346 1159 2347 674 2347 1160 2347 1160 2348 674 2348 1161 2348 1160 2349 1161 2349 1162 2349 1162 2350 1161 2350 1163 2350 1162 2351 1163 2351 1180 2351 714 2352 1164 2352 1165 2352 714 2353 1165 2353 1166 2353 1166 2354 1165 2354 1167 2354 1166 2355 1167 2355 711 2355 711 2356 1167 2356 1168 2356 711 2357 1168 2357 1169 2357 1169 2358 1168 2358 1287 2358 1169 2359 1287 2359 699 2359 699 2360 1287 2360 1170 2360 699 2361 1170 2361 697 2361 697 2362 1170 2362 1171 2362 697 2363 1171 2363 692 2363 692 2364 1171 2364 1285 2364 692 2365 1285 2365 1172 2365 1172 2366 1285 2366 1174 2366 1172 2367 1174 2367 1173 2367 1173 2368 1174 2368 1284 2368 1173 2369 1284 2369 1175 2369 1175 2370 1284 2370 1176 2370 1175 2371 1176 2371 1177 2371 1177 2372 1176 2372 1276 2372 1177 2373 1276 2373 1178 2373 1178 2374 1276 2374 1275 2374 1178 2375 1275 2375 691 2375 691 2376 1275 2376 1274 2376 691 2377 1274 2377 703 2377 703 2378 1274 2378 1277 2378 703 2379 1277 2379 706 2379 706 2380 1277 2380 1278 2380 706 2381 1278 2381 701 2381 701 2382 1278 2382 1296 2382 701 2383 1296 2383 1179 2383 1179 2384 1296 2384 1297 2384 1179 2385 1297 2385 715 2385 715 2386 1297 2386 1180 2386 715 2387 1180 2387 1163 2387 1181 2388 1182 2388 1140 2388 1140 2389 1182 2389 1139 2389 1240 2390 1238 2390 1142 2390 1184 2391 1185 2391 1142 2391 1211 2392 1215 2392 1209 2392 1209 2393 1215 2393 1183 2393 1209 2394 1183 2394 1142 2394 1142 2395 1183 2395 1233 2395 1142 2396 1233 2396 1231 2396 1231 2397 1235 2397 1142 2397 1142 2398 1235 2398 1234 2398 1142 2399 1234 2399 1184 2399 1185 2400 1214 2400 1142 2400 1142 2401 1214 2401 1241 2401 1142 2402 1241 2402 1240 2402 1238 2403 1237 2403 1188 2403 1188 2404 1237 2404 1186 2404 1188 2405 1186 2405 1187 2405 1187 2406 1242 2406 1188 2406 1188 2407 1242 2407 1189 2407 1188 2408 1189 2408 1190 2408 1190 2409 1191 2409 1188 2409 1188 2410 1191 2410 1192 2410 1188 2411 1192 2411 1193 2411 1193 2412 1246 2412 1188 2412 1188 2413 1246 2413 1195 2413 1188 2414 1195 2414 1194 2414 1194 2415 1195 2415 1197 2415 1220 2416 1200 2416 1203 2416 1199 2417 1218 2417 1203 2417 1203 2418 1218 2418 1196 2418 1203 2419 1196 2419 1220 2419 1197 2420 1244 2420 1194 2420 1194 2421 1244 2421 1198 2421 1194 2422 1198 2422 1203 2422 1203 2423 1198 2423 1219 2423 1203 2424 1219 2424 1199 2424 1200 2425 1222 2425 1203 2425 1203 2426 1222 2426 1201 2426 1203 2427 1201 2427 1221 2427 1221 2428 1202 2428 1203 2428 1203 2429 1202 2429 1204 2429 1203 2430 1204 2430 1212 2430 1207 2431 1212 2431 1205 2431 1205 2432 1224 2432 1207 2432 1207 2433 1224 2433 1216 2433 1207 2434 1216 2434 1206 2434 1206 2435 1230 2435 1207 2435 1207 2436 1230 2436 1228 2436 1207 2437 1228 2437 1208 2437 1208 2438 1227 2438 1207 2438 1207 2439 1227 2439 1226 2439 1207 2440 1226 2440 1209 2440 1209 2441 1226 2441 1210 2441 1209 2442 1210 2442 1211 2442 1238 2443 1188 2443 1142 2443 1142 2444 1188 2444 1181 2444 1142 2445 1181 2445 1140 2445 1212 2446 1207 2446 1203 2446 1203 2447 1207 2447 1138 2447 1203 2448 1138 2448 1213 2448 669 2449 1213 2449 1147 2449 1147 2450 1213 2450 1138 2450 1241 2451 1214 2451 1239 2451 1215 2452 1211 2452 912 2452 1206 2453 1216 2453 1223 2453 1204 2454 1202 2454 1225 2454 1219 2455 1198 2455 1217 2455 1217 2456 1198 2456 1245 2456 1196 2457 1218 2457 1217 2457 1217 2458 1218 2458 1199 2458 1217 2459 1199 2459 1219 2459 1196 2460 1217 2460 1220 2460 1220 2461 1217 2461 911 2461 1220 2462 911 2462 1200 2462 1202 2463 1221 2463 1225 2463 1225 2464 1221 2464 1201 2464 1225 2465 1201 2465 911 2465 911 2466 1201 2466 1222 2466 911 2467 1222 2467 1200 2467 1216 2468 1224 2468 1223 2468 1223 2469 1224 2469 1205 2469 1223 2470 1205 2470 1225 2470 1225 2471 1205 2471 1212 2471 1225 2472 1212 2472 1204 2472 1211 2473 1210 2473 912 2473 912 2474 1210 2474 1226 2474 912 2475 1226 2475 1229 2475 1229 2476 1226 2476 1227 2476 1227 2477 1208 2477 1229 2477 1229 2478 1208 2478 1228 2478 1229 2479 1228 2479 1223 2479 1223 2480 1228 2480 1230 2480 1223 2481 1230 2481 1206 2481 1235 2482 1231 2482 1232 2482 1232 2483 1231 2483 1233 2483 1232 2484 1233 2484 912 2484 912 2485 1233 2485 1183 2485 912 2486 1183 2486 1215 2486 1214 2487 1185 2487 1239 2487 1239 2488 1185 2488 1184 2488 1239 2489 1184 2489 1232 2489 1232 2490 1184 2490 1234 2490 1232 2491 1234 2491 1235 2491 1186 2492 1237 2492 1236 2492 1236 2493 1237 2493 1238 2493 1236 2494 1238 2494 1239 2494 1239 2495 1238 2495 1240 2495 1239 2496 1240 2496 1241 2496 1190 2497 1189 2497 910 2497 910 2498 1189 2498 1242 2498 910 2499 1242 2499 1236 2499 1236 2500 1242 2500 1187 2500 1236 2501 1187 2501 1186 2501 1246 2502 1193 2502 1243 2502 1243 2503 1193 2503 1192 2503 1243 2504 1192 2504 910 2504 910 2505 1192 2505 1191 2505 910 2506 1191 2506 1190 2506 1198 2507 1244 2507 1245 2507 1245 2508 1244 2508 1197 2508 1245 2509 1197 2509 1243 2509 1243 2510 1197 2510 1195 2510 1243 2511 1195 2511 1246 2511 1256 2512 1252 2512 1257 2512 1257 2513 1252 2513 1288 2513 1257 2514 1288 2514 1120 2514 2215 2515 1247 2515 1248 2515 1248 2516 1247 2516 1269 2516 1269 2517 1247 2517 1286 2517 1269 2518 1286 2518 1249 2518 1249 2519 1286 2519 1250 2519 1249 2520 1250 2520 1253 2520 1253 2521 1250 2521 1251 2521 1253 2522 1251 2522 1254 2522 1254 2523 1251 2523 1252 2523 1254 2524 1252 2524 1256 2524 1255 2525 1249 2525 1253 2525 1253 2526 1254 2526 1255 2526 1255 2527 1254 2527 1256 2527 1255 2528 1256 2528 1946 2528 1946 2529 1256 2529 1257 2529 2421 2530 1564 2530 2218 2530 2216 2531 1258 2531 1259 2531 1259 2532 1258 2532 1260 2532 1259 2533 1260 2533 3032 2533 1264 2534 1261 2534 1262 2534 1262 2535 1261 2535 3037 2535 1262 2536 3037 2536 2218 2536 2218 2537 3037 2537 2002 2537 2218 2538 2002 2538 2421 2538 3032 2539 3033 2539 1259 2539 1259 2540 3033 2540 3034 2540 1259 2541 3034 2541 1262 2541 1262 2542 3034 2542 1263 2542 1262 2543 1263 2543 1264 2543 3027 2544 2216 2544 1265 2544 1265 2545 2216 2545 1248 2545 3027 2546 1266 2546 2216 2546 2216 2547 1266 2547 3030 2547 2216 2548 3030 2548 1258 2548 1267 2549 1268 2549 1269 2549 1269 2550 1268 2550 1270 2550 1269 2551 1270 2551 1248 2551 1248 2552 1270 2552 3026 2552 1248 2553 3026 2553 1265 2553 1249 2554 1255 2554 1269 2554 1269 2555 1255 2555 2977 2555 1269 2556 2977 2556 1267 2556 1293 2557 1271 2557 1292 2557 1292 2558 1271 2558 2224 2558 1292 2559 2224 2559 1272 2559 1283 2560 2217 2560 1176 2560 1277 2561 1274 2561 1273 2561 1273 2562 1274 2562 1275 2562 1273 2563 1275 2563 2217 2563 2217 2564 1275 2564 1276 2564 2217 2565 1276 2565 1176 2565 1277 2566 1273 2566 1278 2566 1278 2567 1273 2567 1279 2567 1278 2568 1279 2568 1296 2568 1289 2569 1136 2569 1280 2569 1280 2570 1136 2570 1137 2570 1280 2571 1137 2571 1281 2571 1281 2572 1137 2572 1282 2572 1281 2573 1282 2573 1292 2573 1292 2574 1282 2574 1150 2574 1176 2575 1284 2575 1283 2575 1283 2576 1284 2576 1174 2576 1283 2577 1174 2577 2215 2577 2215 2578 1174 2578 1285 2578 2215 2579 1285 2579 1247 2579 1247 2580 1285 2580 1171 2580 1247 2581 1171 2581 1286 2581 1286 2582 1171 2582 1170 2582 1286 2583 1170 2583 1250 2583 1250 2584 1170 2584 1287 2584 1250 2585 1287 2585 1251 2585 1251 2586 1287 2586 1168 2586 1251 2587 1168 2587 1252 2587 1252 2588 1168 2588 1167 2588 1252 2589 1167 2589 1288 2589 1288 2590 1167 2590 1165 2590 1288 2591 1165 2591 1289 2591 1289 2592 1165 2592 1164 2592 1289 2593 1164 2593 1136 2593 1279 2594 1290 2594 1296 2594 1296 2595 1290 2595 1152 2595 1296 2596 1152 2596 1295 2596 1150 2597 1291 2597 1292 2597 1292 2598 1291 2598 1146 2598 1292 2599 1146 2599 1293 2599 1159 2600 1160 2600 1294 2600 1294 2601 1160 2601 1162 2601 1294 2602 1162 2602 1180 2602 1295 2603 1157 2603 1296 2603 1296 2604 1157 2604 1294 2604 1296 2605 1294 2605 1297 2605 1297 2606 1294 2606 1180 2606 1298 2607 673 2607 3840 2607 2711 2608 1307 2608 1299 2608 1299 2609 1307 2609 841 2609 841 2610 3855 2610 1299 2610 1299 2611 3855 2611 3923 2611 1299 2612 3923 2612 915 2612 1300 2613 1301 2613 632 2613 632 2614 1301 2614 1306 2614 2702 2615 1302 2615 2711 2615 1307 2616 850 2616 1303 2616 2696 2617 1305 2617 1304 2617 1304 2618 1305 2618 632 2618 1304 2619 632 2619 2699 2619 2699 2620 632 2620 1306 2620 1302 2621 3655 2621 3760 2621 844 2622 842 2622 846 2622 846 2623 842 2623 1307 2623 846 2624 1307 2624 847 2624 847 2625 1307 2625 1303 2625 2707 2626 2704 2626 2708 2626 2708 2627 2704 2627 2702 2627 2708 2628 2702 2628 2712 2628 2712 2629 2702 2629 2711 2629 1319 2630 3724 2630 1300 2630 1300 2631 3724 2631 1310 2631 1308 2632 1309 2632 1301 2632 1301 2633 1309 2633 1313 2633 1307 2634 2711 2634 850 2634 850 2635 2711 2635 1302 2635 850 2636 1302 2636 3759 2636 3759 2637 1302 2637 3760 2637 1310 2638 3721 2638 1300 2638 1300 2639 3721 2639 1311 2639 1300 2640 1311 2640 1301 2640 1301 2641 1311 2641 1312 2641 1301 2642 1312 2642 1308 2642 1313 2643 3673 2643 1301 2643 1301 2644 3673 2644 1314 2644 1301 2645 1314 2645 1302 2645 1302 2646 1314 2646 3671 2646 1302 2647 3671 2647 3655 2647 3746 2648 1316 2648 1315 2648 1315 2649 1316 2649 1317 2649 1315 2650 1317 2650 1300 2650 1300 2651 1317 2651 1318 2651 1300 2652 1318 2652 1319 2652 1320 2653 2060 2653 1364 2653 1364 2654 2060 2654 2078 2654 1364 2655 2078 2655 1366 2655 1366 2656 2078 2656 2080 2656 1366 2657 2080 2657 1321 2657 1321 2658 2080 2658 1322 2658 1321 2659 1322 2659 1362 2659 1322 2660 2090 2660 1362 2660 1362 2661 2090 2661 2101 2661 1362 2662 2101 2662 1363 2662 1363 2663 2101 2663 2100 2663 1363 2664 2100 2664 1358 2664 1358 2665 2100 2665 1354 2665 1354 2666 2100 2666 1323 2666 1354 2667 1323 2667 1343 2667 1343 2668 1323 2668 1324 2668 1343 2669 1324 2669 1344 2669 1344 2670 1324 2670 2075 2670 1344 2671 2075 2671 648 2671 687 2672 1325 2672 1552 2672 1552 2673 1325 2673 1326 2673 1552 2674 1326 2674 1553 2674 1553 2675 1326 2675 1516 2675 1553 2676 1516 2676 1327 2676 1327 2677 1516 2677 1328 2677 1327 2678 1328 2678 1555 2678 1555 2679 1328 2679 1531 2679 1555 2680 1531 2680 1556 2680 1556 2681 1531 2681 1329 2681 1556 2682 1329 2682 1330 2682 1330 2683 1329 2683 1524 2683 1330 2684 1524 2684 1331 2684 1331 2685 1524 2685 1523 2685 1331 2686 1523 2686 1558 2686 1558 2687 1523 2687 1332 2687 1558 2688 1332 2688 1333 2688 1333 2689 1332 2689 908 2689 1365 2690 1369 2690 1320 2690 663 2691 1371 2691 1334 2691 661 2692 663 2692 1348 2692 1335 2693 661 2693 1360 2693 1336 2694 1335 2694 1359 2694 662 2695 1336 2695 1355 2695 3830 2696 1337 2696 1339 2696 649 2697 1338 2697 3830 2697 649 2698 3830 2698 650 2698 650 2699 3830 2699 1339 2699 650 2700 1339 2700 646 2700 646 2701 1339 2701 1340 2701 646 2702 1340 2702 647 2702 647 2703 1340 2703 1342 2703 1342 2704 1340 2704 1341 2704 1342 2705 1341 2705 654 2705 654 2706 1341 2706 653 2706 653 2707 1341 2707 1343 2707 653 2708 1343 2708 1344 2708 1337 2709 1345 2709 1339 2709 1339 2710 1345 2710 1346 2710 1339 2711 1346 2711 1347 2711 662 2712 1355 2712 1347 2712 661 2713 1348 2713 1360 2713 1360 2714 1348 2714 1349 2714 1360 2715 1349 2715 1350 2715 1350 2716 1349 2716 1365 2716 1350 2717 1365 2717 1367 2717 663 2718 1334 2718 1348 2718 1348 2719 1334 2719 1351 2719 1348 2720 1351 2720 1349 2720 1349 2721 1351 2721 1352 2721 1349 2722 1352 2722 1365 2722 1365 2723 1352 2723 1370 2723 1365 2724 1370 2724 1369 2724 1353 2725 1358 2725 1354 2725 1347 2726 1355 2726 1339 2726 1339 2727 1355 2727 1356 2727 1339 2728 1356 2728 1340 2728 1340 2729 1356 2729 1353 2729 1340 2730 1353 2730 1341 2730 1341 2731 1353 2731 1354 2731 1341 2732 1354 2732 1343 2732 1336 2733 1359 2733 1355 2733 1355 2734 1359 2734 1361 2734 1355 2735 1361 2735 1356 2735 1356 2736 1361 2736 1357 2736 1356 2737 1357 2737 1353 2737 1353 2738 1357 2738 1363 2738 1353 2739 1363 2739 1358 2739 1335 2740 1360 2740 1359 2740 1359 2741 1360 2741 1350 2741 1359 2742 1350 2742 1361 2742 1361 2743 1350 2743 1367 2743 1361 2744 1367 2744 1357 2744 1357 2745 1367 2745 1362 2745 1357 2746 1362 2746 1363 2746 1320 2747 1364 2747 1365 2747 1365 2748 1364 2748 1366 2748 1365 2749 1366 2749 1367 2749 1367 2750 1366 2750 1321 2750 1367 2751 1321 2751 1362 2751 1320 2752 1369 2752 1368 2752 1368 2753 1369 2753 1459 2753 1369 2754 1370 2754 1459 2754 1459 2755 1370 2755 1352 2755 1459 2756 1352 2756 1501 2756 1371 2757 679 2757 1334 2757 1334 2758 679 2758 1501 2758 1334 2759 1501 2759 1351 2759 1351 2760 1501 2760 1352 2760 1368 2761 1459 2761 1458 2761 1373 2762 1504 2762 1078 2762 690 2763 1372 2763 1461 2763 1372 2764 1373 2764 1418 2764 1418 2765 1373 2765 1078 2765 1418 2766 1078 2766 1419 2766 1078 2767 1080 2767 1419 2767 1419 2768 1080 2768 1073 2768 1419 2769 1073 2769 1374 2769 1074 2770 1422 2770 1374 2770 1374 2771 1422 2771 1421 2771 1374 2772 1421 2772 1419 2772 1074 2773 1375 2773 1422 2773 1422 2774 1375 2774 1376 2774 1422 2775 1376 2775 1423 2775 1423 2776 1376 2776 1062 2776 1423 2777 1062 2777 1379 2777 1062 2778 1377 2778 1379 2778 1379 2779 1377 2779 1378 2779 1379 2780 1378 2780 1380 2780 1380 2781 1378 2781 1381 2781 1380 2782 1381 2782 1426 2782 1426 2783 1381 2783 1382 2783 1426 2784 1382 2784 1384 2784 1382 2785 1383 2785 1384 2785 1384 2786 1383 2786 1055 2786 1384 2787 1055 2787 1385 2787 1055 2788 1058 2788 1385 2788 1385 2789 1058 2789 1386 2789 1385 2790 1386 2790 1427 2790 1386 2791 1050 2791 1427 2791 1427 2792 1050 2792 1387 2792 1427 2793 1387 2793 1430 2793 1430 2794 1387 2794 1388 2794 1430 2795 1388 2795 1431 2795 1388 2796 1049 2796 1431 2796 1431 2797 1049 2797 1048 2797 1431 2798 1048 2798 1433 2798 1433 2799 1048 2799 1389 2799 1433 2800 1389 2800 1434 2800 1389 2801 1390 2801 1434 2801 1434 2802 1390 2802 1045 2802 1434 2803 1045 2803 1391 2803 1391 2804 1045 2804 1392 2804 1391 2805 1392 2805 1436 2805 1392 2806 1044 2806 1436 2806 1436 2807 1044 2807 1393 2807 1436 2808 1393 2808 1437 2808 1437 2809 1393 2809 1394 2809 1437 2810 1394 2810 1438 2810 1394 2811 1042 2811 1438 2811 1438 2812 1042 2812 1395 2812 1438 2813 1395 2813 1439 2813 1439 2814 1395 2814 1396 2814 1439 2815 1396 2815 1442 2815 1396 2816 1397 2816 1442 2816 1442 2817 1397 2817 1398 2817 1442 2818 1398 2818 1399 2818 1398 2819 1026 2819 1399 2819 1399 2820 1026 2820 1400 2820 1399 2821 1400 2821 1444 2821 1444 2822 1400 2822 1401 2822 1444 2823 1401 2823 1402 2823 1402 2824 1401 2824 1403 2824 1402 2825 1403 2825 1404 2825 1403 2826 1030 2826 1404 2826 1404 2827 1030 2827 1031 2827 1404 2828 1031 2828 1447 2828 1031 2829 1032 2829 1447 2829 1447 2830 1032 2830 1405 2830 1447 2831 1405 2831 1449 2831 1449 2832 1405 2832 1036 2832 1449 2833 1036 2833 1406 2833 1406 2834 1036 2834 1037 2834 1406 2835 1037 2835 1407 2835 1407 2836 1037 2836 1039 2836 1407 2837 1039 2837 1408 2837 1408 2838 1039 2838 1022 2838 1022 2839 1409 2839 1408 2839 1408 2840 1409 2840 1410 2840 1408 2841 1410 2841 1454 2841 1454 2842 1410 2842 1411 2842 1454 2843 1411 2843 1456 2843 1456 2844 1411 2844 1088 2844 1456 2845 1088 2845 1413 2845 1088 2846 1412 2846 1413 2846 1413 2847 1412 2847 1082 2847 1413 2848 1082 2848 1414 2848 1082 2849 1415 2849 1414 2849 1414 2850 1415 2850 1416 2850 1414 2851 1416 2851 1457 2851 1457 2852 1416 2852 1086 2852 1457 2853 1086 2853 1417 2853 1417 2854 1086 2854 1085 2854 1417 2855 1085 2855 1458 2855 1458 2856 1085 2856 1084 2856 1458 2857 1084 2857 1368 2857 1372 2858 1418 2858 1461 2858 1461 2859 1418 2859 1419 2859 1461 2860 1419 2860 1420 2860 1420 2861 1419 2861 1421 2861 1420 2862 1421 2862 1464 2862 1464 2863 1421 2863 1422 2863 1464 2864 1422 2864 1466 2864 1466 2865 1422 2865 1423 2865 1466 2866 1423 2866 1424 2866 1424 2867 1423 2867 1379 2867 1424 2868 1379 2868 1425 2868 1425 2869 1379 2869 1380 2869 1425 2870 1380 2870 1469 2870 1469 2871 1380 2871 1426 2871 1469 2872 1426 2872 1470 2872 1470 2873 1426 2873 1384 2873 1470 2874 1384 2874 1471 2874 1471 2875 1384 2875 1385 2875 1471 2876 1385 2876 1472 2876 1472 2877 1385 2877 1427 2877 1472 2878 1427 2878 1428 2878 1428 2879 1427 2879 1430 2879 1428 2880 1430 2880 1429 2880 1429 2881 1430 2881 1431 2881 1429 2882 1431 2882 1432 2882 1432 2883 1431 2883 1433 2883 1432 2884 1433 2884 1473 2884 1473 2885 1433 2885 1434 2885 1473 2886 1434 2886 1477 2886 1477 2887 1434 2887 1391 2887 1477 2888 1391 2888 1435 2888 1435 2889 1391 2889 1436 2889 1435 2890 1436 2890 1479 2890 1479 2891 1436 2891 1437 2891 1479 2892 1437 2892 1481 2892 1481 2893 1437 2893 1438 2893 1481 2894 1438 2894 1440 2894 1440 2895 1438 2895 1439 2895 1440 2896 1439 2896 1441 2896 1441 2897 1439 2897 1442 2897 1441 2898 1442 2898 1484 2898 1484 2899 1442 2899 1399 2899 1484 2900 1399 2900 1443 2900 1443 2901 1399 2901 1444 2901 1443 2902 1444 2902 1486 2902 1486 2903 1444 2903 1402 2903 1486 2904 1402 2904 1445 2904 1445 2905 1402 2905 1404 2905 1445 2906 1404 2906 1446 2906 1446 2907 1404 2907 1447 2907 1446 2908 1447 2908 1448 2908 1448 2909 1447 2909 1449 2909 1448 2910 1449 2910 1450 2910 1450 2911 1449 2911 1406 2911 1450 2912 1406 2912 1451 2912 1451 2913 1406 2913 1407 2913 1451 2914 1407 2914 1452 2914 1452 2915 1407 2915 1408 2915 1452 2916 1408 2916 1492 2916 1492 2917 1408 2917 1454 2917 1492 2918 1454 2918 1453 2918 1453 2919 1454 2919 1456 2919 1453 2920 1456 2920 1455 2920 1455 2921 1456 2921 1413 2921 1455 2922 1413 2922 1494 2922 1494 2923 1413 2923 1414 2923 1494 2924 1414 2924 1496 2924 1496 2925 1414 2925 1457 2925 1496 2926 1457 2926 1498 2926 1498 2927 1457 2927 1417 2927 1498 2928 1417 2928 1499 2928 1499 2929 1417 2929 1458 2929 1499 2930 1458 2930 1460 2930 1460 2931 1458 2931 1459 2931 1460 2932 1459 2932 1501 2932 690 2933 1461 2933 1462 2933 1462 2934 1461 2934 1420 2934 1462 2935 1420 2935 1463 2935 1463 2936 1420 2936 1464 2936 1463 2937 1464 2937 1465 2937 1465 2938 1464 2938 1466 2938 1465 2939 1466 2939 710 2939 710 2940 1466 2940 1424 2940 710 2941 1424 2941 1467 2941 1467 2942 1424 2942 1425 2942 1467 2943 1425 2943 1468 2943 1468 2944 1425 2944 1469 2944 1468 2945 1469 2945 705 2945 705 2946 1469 2946 1470 2946 705 2947 1470 2947 707 2947 707 2948 1470 2948 1471 2948 707 2949 1471 2949 708 2949 708 2950 1471 2950 1472 2950 708 2951 1472 2951 709 2951 709 2952 1472 2952 1428 2952 709 2953 1428 2953 702 2953 702 2954 1428 2954 1429 2954 702 2955 1429 2955 704 2955 704 2956 1429 2956 1432 2956 704 2957 1432 2957 1474 2957 1474 2958 1432 2958 1473 2958 1474 2959 1473 2959 1475 2959 1475 2960 1473 2960 1477 2960 1475 2961 1477 2961 1476 2961 1476 2962 1477 2962 1435 2962 1476 2963 1435 2963 1478 2963 1478 2964 1435 2964 1479 2964 1478 2965 1479 2965 1480 2965 1480 2966 1479 2966 1481 2966 1480 2967 1481 2967 1482 2967 1482 2968 1481 2968 1440 2968 1482 2969 1440 2969 677 2969 677 2970 1440 2970 1441 2970 677 2971 1441 2971 1483 2971 1483 2972 1441 2972 1484 2972 1483 2973 1484 2973 682 2973 682 2974 1484 2974 1443 2974 682 2975 1443 2975 1485 2975 1485 2976 1443 2976 1486 2976 1485 2977 1486 2977 1487 2977 1487 2978 1486 2978 1445 2978 1487 2979 1445 2979 1488 2979 1488 2980 1445 2980 1446 2980 1488 2981 1446 2981 693 2981 693 2982 1446 2982 1448 2982 693 2983 1448 2983 694 2983 694 2984 1448 2984 1450 2984 694 2985 1450 2985 1489 2985 1489 2986 1450 2986 1451 2986 1489 2987 1451 2987 698 2987 698 2988 1451 2988 1452 2988 698 2989 1452 2989 1490 2989 1490 2990 1452 2990 1492 2990 1490 2991 1492 2991 1491 2991 1491 2992 1492 2992 1453 2992 1491 2993 1453 2993 1493 2993 1493 2994 1453 2994 1455 2994 1493 2995 1455 2995 689 2995 689 2996 1455 2996 1494 2996 689 2997 1494 2997 1495 2997 1495 2998 1494 2998 1496 2998 1495 2999 1496 2999 1497 2999 1497 3000 1496 3000 1498 3000 1497 3001 1498 3001 712 3001 712 3002 1498 3002 1499 3002 712 3003 1499 3003 1500 3003 1500 3004 1499 3004 1460 3004 1500 3005 1460 3005 713 3005 713 3006 1460 3006 1501 3006 713 3007 1501 3007 679 3007 684 3008 1502 3008 690 3008 690 3009 1502 3009 1372 3009 1502 3010 737 3010 1372 3010 1372 3011 737 3011 1503 3011 1372 3012 1503 3012 1373 3012 716 3013 1504 3013 1505 3013 1505 3014 1504 3014 1373 3014 1505 3015 1373 3015 1506 3015 1506 3016 1373 3016 1503 3016 1529 3017 1535 3017 1507 3017 1527 3018 3889 3018 1526 3018 3841 3019 1508 3019 1528 3019 1298 3020 3841 3020 1532 3020 1298 3021 1532 3021 673 3021 1509 3022 1510 3022 1532 3022 1532 3023 1510 3023 1511 3023 1532 3024 1511 3024 673 3024 1509 3025 1532 3025 678 3025 678 3026 1532 3026 1533 3026 678 3027 1533 3027 675 3027 1517 3028 1328 3028 1516 3028 1325 3029 681 3029 1326 3029 1326 3030 681 3030 1512 3030 1512 3031 1513 3031 1326 3031 1326 3032 1513 3032 1514 3032 1326 3033 1514 3033 1516 3033 1516 3034 1514 3034 1515 3034 1516 3035 1515 3035 1517 3035 1517 3036 1515 3036 1519 3036 1517 3037 1519 3037 1518 3037 1518 3038 1519 3038 676 3038 1518 3039 676 3039 675 3039 1520 3040 1521 3040 1525 3040 1525 3041 1521 3041 1522 3041 1529 3042 927 3042 908 3042 908 3043 1332 3043 1529 3043 1529 3044 1332 3044 1523 3044 1529 3045 1523 3045 1535 3045 1535 3046 1523 3046 1524 3046 1535 3047 1524 3047 1329 3047 1530 3048 1525 3048 1526 3048 1526 3049 1525 3049 1522 3049 1526 3050 1522 3050 1527 3050 1508 3051 3842 3051 1528 3051 1528 3052 3842 3052 1520 3052 1528 3053 1520 3053 1507 3053 1507 3054 1520 3054 1525 3054 1507 3055 1525 3055 1529 3055 1529 3056 1525 3056 1530 3056 1529 3057 1530 3057 927 3057 675 3058 1533 3058 1518 3058 1518 3059 1533 3059 1534 3059 1518 3060 1534 3060 1517 3060 1517 3061 1534 3061 1531 3061 1517 3062 1531 3062 1328 3062 3841 3063 1528 3063 1532 3063 1532 3064 1528 3064 1507 3064 1532 3065 1507 3065 1533 3065 1533 3066 1507 3066 1535 3066 1533 3067 1535 3067 1534 3067 1534 3068 1535 3068 1329 3068 1534 3069 1329 3069 1531 3069 1536 3070 923 3070 1537 3070 700 3071 1538 3071 1539 3071 1551 3072 696 3072 1552 3072 1552 3073 696 3073 695 3073 1552 3074 695 3074 687 3074 700 3075 1539 3075 1562 3075 1563 3076 1541 3076 1540 3076 1540 3077 1541 3077 1561 3077 1540 3078 1561 3078 1542 3078 1542 3079 1561 3079 1543 3079 686 3080 1545 3080 1544 3080 1544 3081 1545 3081 3844 3081 1544 3082 3844 3082 665 3082 1546 3083 1548 3083 1547 3083 1547 3084 1548 3084 1549 3084 1547 3085 1549 3085 1545 3085 1545 3086 1549 3086 3845 3086 1545 3087 3845 3087 3844 3087 3924 3088 1537 3088 1550 3088 1550 3089 1537 3089 923 3089 1550 3090 923 3090 3925 3090 1551 3091 1552 3091 1538 3091 1538 3092 1552 3092 1553 3092 1538 3093 1553 3093 1539 3093 1539 3094 1553 3094 1327 3094 1539 3095 1327 3095 1554 3095 1327 3096 1555 3096 1554 3096 1554 3097 1555 3097 1556 3097 1554 3098 1556 3098 1557 3098 1557 3099 1556 3099 1330 3099 1557 3100 1330 3100 1559 3100 1333 3101 919 3101 1558 3101 1558 3102 919 3102 1559 3102 1558 3103 1559 3103 1331 3103 1331 3104 1559 3104 1330 3104 919 3105 1536 3105 1559 3105 1559 3106 1536 3106 1537 3106 1559 3107 1537 3107 1557 3107 1557 3108 1537 3108 1560 3108 1557 3109 1560 3109 1554 3109 1554 3110 1560 3110 1561 3110 1554 3111 1561 3111 1539 3111 1539 3112 1561 3112 1541 3112 1539 3113 1541 3113 1562 3113 1562 3114 1541 3114 1563 3114 3924 3115 3843 3115 1537 3115 1537 3116 3843 3116 1546 3116 1537 3117 1546 3117 1560 3117 1560 3118 1546 3118 1547 3118 1560 3119 1547 3119 1561 3119 1561 3120 1547 3120 1545 3120 1561 3121 1545 3121 1543 3121 1543 3122 1545 3122 686 3122 2285 3123 1616 3123 2004 3123 1617 3124 2421 3124 2002 3124 1564 3125 2421 3125 2344 3125 2338 3126 1565 3126 1566 3126 1566 3127 1565 3127 1564 3127 1566 3128 1564 3128 2343 3128 2343 3129 1564 3129 2344 3129 1567 3130 802 3130 1568 3130 1568 3131 802 3131 1565 3131 1568 3132 1565 3132 1569 3132 1569 3133 1565 3133 2338 3133 1567 3134 1570 3134 802 3134 802 3135 1570 3135 2334 3135 802 3136 2334 3136 1582 3136 1582 3137 2334 3137 1571 3137 1582 3138 1571 3138 1581 3138 1572 3139 1596 3139 2241 3139 2230 3140 2232 3140 1645 3140 1573 3141 1574 3141 1961 3141 2230 3142 1645 3142 2233 3142 1574 3143 1575 3143 1961 3143 1961 3144 1575 3144 2237 3144 1961 3145 2237 3145 1645 3145 1645 3146 2237 3146 1576 3146 1645 3147 1576 3147 2233 3147 2232 3148 2227 3148 1645 3148 1645 3149 2227 3149 2228 3149 1645 3150 2228 3150 2229 3150 1646 3151 2243 3151 2035 3151 2035 3152 2243 3152 1577 3152 2035 3153 1577 3153 1596 3153 1596 3154 1577 3154 1578 3154 1596 3155 1578 3155 2241 3155 1591 3156 3805 3156 1579 3156 1579 3157 3805 3157 1595 3157 1580 3158 2322 3158 1579 3158 1580 3159 1579 3159 2324 3159 1581 3160 2332 3160 1582 3160 1582 3161 2332 3161 1583 3161 1582 3162 1583 3162 1584 3162 1584 3163 1583 3163 2327 3163 1584 3164 2327 3164 1579 3164 1579 3165 2327 3165 2325 3165 1579 3166 2325 3166 2324 3166 2322 3167 2321 3167 1579 3167 1579 3168 2321 3168 2320 3168 1579 3169 2320 3169 1591 3169 1591 3170 2320 3170 2318 3170 1591 3171 2318 3171 1585 3171 1585 3172 2316 3172 1591 3172 1591 3173 2316 3173 1586 3173 1591 3174 1586 3174 1590 3174 3807 3175 1594 3175 2313 3175 1635 3176 1588 3176 1587 3176 1587 3177 1588 3177 3804 3177 1587 3178 3804 3178 2313 3178 2313 3179 3804 3179 1589 3179 2313 3180 1589 3180 3807 3180 1590 3181 1592 3181 1591 3181 1591 3182 1592 3182 2313 3182 1591 3183 2313 3183 1593 3183 1593 3184 2313 3184 1594 3184 1595 3185 3805 3185 2241 3185 2241 3186 3805 3186 3808 3186 2241 3187 3808 3187 1572 3187 1596 3188 1597 3188 2035 3188 2035 3189 1597 3189 1598 3189 2035 3190 1598 3190 1599 3190 1599 3191 1600 3191 2035 3191 2035 3192 1600 3192 3812 3192 2035 3193 3812 3193 3811 3193 3814 3194 2036 3194 3810 3194 3810 3195 2036 3195 2035 3195 3810 3196 2035 3196 1601 3196 1601 3197 2035 3197 3811 3197 3814 3198 1602 3198 2036 3198 2036 3199 1602 3199 1618 3199 2036 3200 1618 3200 1619 3200 1958 3201 2222 3201 1604 3201 1604 3202 2222 3202 1603 3202 1604 3203 1603 3203 1605 3203 1605 3204 1603 3204 1573 3204 1605 3205 1573 3205 1606 3205 1606 3206 1573 3206 1961 3206 1125 3207 2219 3207 1958 3207 1958 3208 2219 3208 2220 3208 1958 3209 2220 3209 1607 3209 1607 3210 1608 3210 1958 3210 1958 3211 1608 3211 2221 3211 1958 3212 2221 3212 1609 3212 1609 3213 1610 3213 1958 3213 1958 3214 1610 3214 2223 3214 1958 3215 2223 3215 2222 3215 1121 3216 1611 3216 1120 3216 1120 3217 1611 3217 1946 3217 1120 3218 1946 3218 1257 3218 1121 3219 1122 3219 1611 3219 1611 3220 1122 3220 1123 3220 1611 3221 1123 3221 1613 3221 1613 3222 1123 3222 1124 3222 1613 3223 1124 3223 1612 3223 1612 3224 1129 3224 1613 3224 1613 3225 1129 3225 1128 3225 1613 3226 1128 3226 1614 3226 1614 3227 1128 3227 1127 3227 1614 3228 1127 3228 1958 3228 1958 3229 1127 3229 1126 3229 1958 3230 1126 3230 1125 3230 2004 3231 1616 3231 1615 3231 1615 3232 1616 3232 2276 3232 1615 3233 2276 3233 2002 3233 2002 3234 2276 3234 2274 3234 2002 3235 2274 3235 1617 3235 1618 3236 3819 3236 1619 3236 1619 3237 3819 3237 3816 3237 1619 3238 3816 3238 2037 3238 2037 3239 3816 3239 3815 3239 2037 3240 3815 3240 1622 3240 1620 3241 1625 3241 1628 3241 3815 3242 1621 3242 1622 3242 1622 3243 1621 3243 1623 3243 1622 3244 1623 3244 1628 3244 1628 3245 1623 3245 1624 3245 1628 3246 1624 3246 1620 3246 1625 3247 3823 3247 1628 3247 1628 3248 3823 3248 3822 3248 1628 3249 3822 3249 1627 3249 1626 3250 1629 3250 1632 3250 1627 3251 1626 3251 1628 3251 1628 3252 1626 3252 1632 3252 1628 3253 1632 3253 2032 3253 2032 3254 1632 3254 2288 3254 2032 3255 2288 3255 2004 3255 2004 3256 2288 3256 2287 3256 2004 3257 2287 3257 2285 3257 1629 3258 1630 3258 1632 3258 1632 3259 1630 3259 1631 3259 1632 3260 1631 3260 3798 3260 3798 3261 3797 3261 1632 3261 1632 3262 3797 3262 3796 3262 1632 3263 3796 3263 1633 3263 3796 3264 3802 3264 1633 3264 1633 3265 3802 3265 3801 3265 1633 3266 3801 3266 2294 3266 2294 3267 3801 3267 3799 3267 2294 3268 3799 3268 1634 3268 1634 3269 3799 3269 1635 3269 1634 3270 1635 3270 2295 3270 2295 3271 1635 3271 1587 3271 1636 3272 2462 3272 2035 3272 1636 3273 2035 3273 1643 3273 1637 3274 1638 3274 1639 3274 1639 3275 1638 3275 1640 3275 1639 3276 1640 3276 1642 3276 1642 3277 1640 3277 1641 3277 1642 3278 1641 3278 2035 3278 2035 3279 1641 3279 2465 3279 2035 3280 2465 3280 1643 3280 2462 3281 1644 3281 2035 3281 2035 3282 1644 3282 2460 3282 2035 3283 2460 3283 2458 3283 2538 3284 2537 3284 1645 3284 2229 3285 1646 3285 1645 3285 1645 3286 1646 3286 2035 3286 1645 3287 2035 3287 2538 3287 2538 3288 2035 3288 2458 3288 2537 3289 2536 3289 1645 3289 1645 3290 2536 3290 2535 3290 1645 3291 2535 3291 1647 3291 1647 3292 1648 3292 1645 3292 1645 3293 1648 3293 1649 3293 1645 3294 1649 3294 2531 3294 2508 3295 1660 3295 1650 3295 1650 3296 1660 3296 1651 3296 1650 3297 1651 3297 2510 3297 2510 3298 1651 3298 1965 3298 2510 3299 1965 3299 2526 3299 2526 3300 1965 3300 1652 3300 2526 3301 1652 3301 1653 3301 1653 3302 1652 3302 1963 3302 1653 3303 1963 3303 1654 3303 1654 3304 1963 3304 1645 3304 1654 3305 1645 3305 2530 3305 2530 3306 1645 3306 2531 3306 2508 3307 2507 3307 1660 3307 1660 3308 2507 3308 2506 3308 1660 3309 2506 3309 1655 3309 1655 3310 1656 3310 1660 3310 1660 3311 1656 3311 2504 3311 1660 3312 2504 3312 2502 3312 1657 3313 2499 3313 1658 3313 1658 3314 2499 3314 1659 3314 1658 3315 1659 3315 2496 3315 2496 3316 2495 3316 1658 3316 1658 3317 2495 3317 2493 3317 1658 3318 2493 3318 2492 3318 2492 3319 2491 3319 1658 3319 1658 3320 2491 3320 2489 3320 1658 3321 2489 3321 2038 3321 2038 3322 2489 3322 1637 3322 2038 3323 1637 3323 2039 3323 2039 3324 1637 3324 1639 3324 2502 3325 1657 3325 1660 3325 1660 3326 1657 3326 1658 3326 1660 3327 1658 3327 1661 3327 1661 3328 1658 3328 2049 3328 1661 3329 2049 3329 1105 3329 1105 3330 2049 3330 2048 3330 2025 3331 2010 3331 1677 3331 1677 3332 3307 3332 1662 3332 1662 3333 3307 3333 1663 3333 1662 3334 1663 3334 1682 3334 3270 3335 1662 3335 1664 3335 1664 3336 1662 3336 3272 3336 1674 3337 3219 3337 3311 3337 1672 3338 1665 3338 3309 3338 3309 3339 1665 3339 3310 3339 1679 3340 1681 3340 1666 3340 1666 3341 1681 3341 1667 3341 1666 3342 1667 3342 3190 3342 3300 3343 3198 3343 1667 3343 1667 3344 3198 3344 3197 3344 1667 3345 3197 3345 3190 3345 3219 3346 3218 3346 3311 3346 3311 3347 3218 3347 3207 3347 3311 3348 3207 3348 3300 3348 3300 3349 3207 3349 3203 3349 3300 3350 3203 3350 3198 3350 3105 3351 3107 3351 1668 3351 1668 3352 3107 3352 1669 3352 1668 3353 1669 3353 1670 3353 1677 3354 2010 3354 1668 3354 1668 3355 2010 3355 1998 3355 1668 3356 1998 3356 3105 3356 1670 3357 3123 3357 1668 3357 1668 3358 3123 3358 3136 3358 1668 3359 3136 3359 3309 3359 3309 3360 3136 3360 1671 3360 3309 3361 1671 3361 1672 3361 3279 3362 3276 3362 1682 3362 1682 3363 3276 3363 1673 3363 1682 3364 1673 3364 1662 3364 1662 3365 1673 3365 3273 3365 1662 3366 3273 3366 3272 3366 1674 3367 3311 3367 1675 3367 1675 3368 3311 3368 1676 3368 1675 3369 1676 3369 3146 3369 1665 3370 3138 3370 3310 3370 3310 3371 3138 3371 3137 3371 3310 3372 3137 3372 1676 3372 1676 3373 3137 3373 3152 3373 1676 3374 3152 3374 3146 3374 1662 3375 2045 3375 1677 3375 1677 3376 2045 3376 2006 3376 1677 3377 2006 3377 1678 3377 1679 3378 1680 3378 1681 3378 1681 3379 1680 3379 3139 3379 1681 3380 3139 3380 1682 3380 1682 3381 3139 3381 3141 3381 1682 3382 3141 3382 3279 3382 1678 3383 1683 3383 1677 3383 1677 3384 1683 3384 2042 3384 1677 3385 2042 3385 2018 3385 2018 3386 2008 3386 1677 3386 1677 3387 2008 3387 2007 3387 1677 3388 2007 3388 2025 3388 2750 3389 1686 3389 2752 3389 2752 3390 1686 3390 1104 3390 1684 3391 3332 3391 3316 3391 1684 3392 3316 3392 1686 3392 2746 3393 1684 3393 2749 3393 2749 3394 1684 3394 1686 3394 2749 3395 1686 3395 1685 3395 1685 3396 1686 3396 2750 3396 2867 3397 2866 3397 1705 3397 1705 3398 2866 3398 2864 3398 1705 3399 2864 3399 1687 3399 2746 3400 2745 3400 1684 3400 1684 3401 2745 3401 2888 3401 1684 3402 2888 3402 1688 3402 1691 3403 1693 3403 1689 3403 1689 3404 1693 3404 1687 3404 1689 3405 1687 3405 1690 3405 1690 3406 1687 3406 2864 3406 1691 3407 1692 3407 1693 3407 1693 3408 1692 3408 2898 3408 1693 3409 2898 3409 2897 3409 1695 3410 1696 3410 1694 3410 1694 3411 1696 3411 3332 3411 1694 3412 3332 3412 2876 3412 2876 3413 3332 3413 1684 3413 2897 3414 2915 3414 1693 3414 1693 3415 2915 3415 1948 3415 1693 3416 1948 3416 3325 3416 1695 3417 2873 3417 1696 3417 1696 3418 2873 3418 1702 3418 1696 3419 1702 3419 1703 3419 3316 3420 1697 3420 1686 3420 1686 3421 1697 3421 3321 3421 1686 3422 3321 3422 1988 3422 1988 3423 3321 3423 1699 3423 1988 3424 1699 3424 1989 3424 3324 3425 1993 3425 1698 3425 1698 3426 1992 3426 3324 3426 3324 3427 1992 3427 1700 3427 3324 3428 1700 3428 1699 3428 1699 3429 1700 3429 1991 3429 1699 3430 1991 3430 1989 3430 1948 3431 1701 3431 3325 3431 3325 3432 1701 3432 1997 3432 3325 3433 1997 3433 3324 3433 3324 3434 1997 3434 1996 3434 3324 3435 1996 3435 1993 3435 1702 3436 2871 3436 1703 3436 1703 3437 2871 3437 1704 3437 1703 3438 1704 3438 1705 3438 1705 3439 1704 3439 2869 3439 1705 3440 2869 3440 2867 3440 2885 3441 2883 3441 1688 3441 1688 3442 2883 3442 1706 3442 1688 3443 1706 3443 2880 3443 2880 3444 2879 3444 1688 3444 1688 3445 2879 3445 1707 3445 1688 3446 1707 3446 1684 3446 2805 3447 2803 3447 1811 3447 2793 3448 1797 3448 1798 3448 1708 3449 2791 3449 1709 3449 2790 3450 2788 3450 1710 3450 2787 3451 2786 3451 1711 3451 1712 3452 1713 3452 1714 3452 1785 3453 1779 3453 1780 3453 2785 3454 2784 3454 1775 3454 1715 3455 2783 3455 1776 3455 1771 3456 1716 3456 1772 3456 2779 3457 2778 3457 1768 3457 2777 3458 1759 3458 1760 3458 2776 3459 1717 3459 1761 3459 1755 3460 2775 3460 1718 3460 1753 3461 2773 3461 1719 3461 1812 3462 1720 3462 1737 3462 2180 3463 1721 3463 1752 3463 1752 3464 1721 3464 2175 3464 2184 3465 1722 3465 1752 3465 1752 3466 1722 3466 2181 3466 1752 3467 2181 3467 2180 3467 2187 3468 2186 3468 1746 3468 1746 3469 2186 3469 2185 3469 1746 3470 2185 3470 1723 3470 2770 3471 2741 3471 2195 3471 2193 3472 1724 3472 1745 3472 2656 3473 1809 3473 1725 3473 1725 3474 1809 3474 1810 3474 1725 3475 1810 3475 2659 3475 2659 3476 1810 3476 1739 3476 2677 3477 2690 3477 1742 3477 1742 3478 2690 3478 1726 3478 1742 3479 1726 3479 1741 3479 2675 3480 1727 3480 1728 3480 1728 3481 1727 3481 2672 3481 2672 3482 1729 3482 1728 3482 1728 3483 1729 3483 1730 3483 1728 3484 1730 3484 1742 3484 1742 3485 1730 3485 2679 3485 1742 3486 2679 3486 2677 3486 1728 3487 884 3487 3382 3487 3382 3488 1731 3488 1728 3488 1728 3489 1731 3489 1732 3489 1728 3490 1732 3490 2666 3490 2666 3491 2670 3491 1728 3491 1728 3492 2670 3492 2676 3492 1728 3493 2676 3493 2675 3493 882 3494 881 3494 1735 3494 1735 3495 881 3495 1803 3495 1735 3496 1803 3496 1800 3496 1738 3497 1720 3497 886 3497 886 3498 1720 3498 1812 3498 886 3499 1812 3499 1733 3499 883 3500 882 3500 1734 3500 1734 3501 882 3501 1735 3501 1734 3502 1735 3502 1736 3502 1736 3503 1735 3503 1800 3503 1736 3504 1800 3504 1798 3504 1810 3505 1737 3505 1740 3505 1740 3506 1737 3506 1720 3506 1740 3507 1720 3507 1743 3507 1743 3508 1720 3508 1738 3508 1743 3509 1738 3509 1744 3509 1739 3510 1810 3510 1741 3510 1741 3511 1810 3511 1740 3511 1741 3512 1740 3512 1742 3512 1742 3513 1740 3513 1743 3513 1742 3514 1743 3514 1728 3514 1728 3515 1743 3515 1744 3515 1728 3516 1744 3516 884 3516 1724 3517 2187 3517 1745 3517 1745 3518 2187 3518 1746 3518 1745 3519 1746 3519 1751 3519 1747 3520 1748 3520 1801 3520 2195 3521 2193 3521 2770 3521 2770 3522 2193 3522 1745 3522 2770 3523 1745 3523 1749 3523 1749 3524 1745 3524 1751 3524 1749 3525 1751 3525 1750 3525 1750 3526 1751 3526 2772 3526 2773 3527 2772 3527 1719 3527 1719 3528 2772 3528 1751 3528 1719 3529 1751 3529 1754 3529 1754 3530 1751 3530 1746 3530 1754 3531 1746 3531 1752 3531 1752 3532 1746 3532 1723 3532 1752 3533 1723 3533 2184 3533 2775 3534 1753 3534 1718 3534 1718 3535 1753 3535 1719 3535 1718 3536 1719 3536 1756 3536 1756 3537 1719 3537 1754 3537 1756 3538 1754 3538 1758 3538 1758 3539 1754 3539 1752 3539 1758 3540 1752 3540 892 3540 892 3541 1752 3541 2175 3541 892 3542 2175 3542 2177 3542 1717 3543 1755 3543 1761 3543 1761 3544 1755 3544 1718 3544 1761 3545 1718 3545 1762 3545 1762 3546 1718 3546 1756 3546 1762 3547 1756 3547 1764 3547 1764 3548 1756 3548 1758 3548 1764 3549 1758 3549 1757 3549 1757 3550 1758 3550 892 3550 1759 3551 2776 3551 1760 3551 1760 3552 2776 3552 1761 3552 1760 3553 1761 3553 1763 3553 1763 3554 1761 3554 1762 3554 1763 3555 1762 3555 1767 3555 1767 3556 1762 3556 1764 3556 1767 3557 1764 3557 876 3557 876 3558 1764 3558 1757 3558 2778 3559 2777 3559 1768 3559 1768 3560 2777 3560 1760 3560 1768 3561 1760 3561 1765 3561 1765 3562 1760 3562 1763 3562 1765 3563 1763 3563 1766 3563 1766 3564 1763 3564 1767 3564 1766 3565 1767 3565 874 3565 874 3566 1767 3566 876 3566 1716 3567 2779 3567 1772 3567 1772 3568 2779 3568 1768 3568 1772 3569 1768 3569 1769 3569 1769 3570 1768 3570 1765 3570 1769 3571 1765 3571 1770 3571 1770 3572 1765 3572 1766 3572 1770 3573 1766 3573 1774 3573 1774 3574 1766 3574 874 3574 2783 3575 1771 3575 1776 3575 1776 3576 1771 3576 1772 3576 1776 3577 1772 3577 1773 3577 1773 3578 1772 3578 1769 3578 1773 3579 1769 3579 1778 3579 1778 3580 1769 3580 1770 3580 1778 3581 1770 3581 873 3581 873 3582 1770 3582 1774 3582 2784 3583 1715 3583 1775 3583 1775 3584 1715 3584 1776 3584 1775 3585 1776 3585 1782 3585 1782 3586 1776 3586 1773 3586 1782 3587 1773 3587 1783 3587 1783 3588 1773 3588 1778 3588 1783 3589 1778 3589 1777 3589 1777 3590 1778 3590 873 3590 1779 3591 2785 3591 1780 3591 1780 3592 2785 3592 1775 3592 1780 3593 1775 3593 1781 3593 1781 3594 1775 3594 1782 3594 1781 3595 1782 3595 1784 3595 1784 3596 1782 3596 1783 3596 1784 3597 1783 3597 1787 3597 1787 3598 1783 3598 1777 3598 1713 3599 1785 3599 1714 3599 1714 3600 1785 3600 1780 3600 1714 3601 1780 3601 1786 3601 1786 3602 1780 3602 1781 3602 1786 3603 1781 3603 1788 3603 1788 3604 1781 3604 1784 3604 1788 3605 1784 3605 1790 3605 1790 3606 1784 3606 1787 3606 2786 3607 1712 3607 1711 3607 1711 3608 1712 3608 1714 3608 1711 3609 1714 3609 1791 3609 1791 3610 1714 3610 1786 3610 1791 3611 1786 3611 1793 3611 1793 3612 1786 3612 1788 3612 1793 3613 1788 3613 1789 3613 1789 3614 1788 3614 1790 3614 2788 3615 2787 3615 1710 3615 1710 3616 2787 3616 1711 3616 1710 3617 1711 3617 1795 3617 1795 3618 1711 3618 1791 3618 1795 3619 1791 3619 1792 3619 1792 3620 1791 3620 1793 3620 1792 3621 1793 3621 872 3621 872 3622 1793 3622 1789 3622 2791 3623 2790 3623 1709 3623 1709 3624 2790 3624 1710 3624 1709 3625 1710 3625 1799 3625 1799 3626 1710 3626 1795 3626 1799 3627 1795 3627 1794 3627 1794 3628 1795 3628 1792 3628 1794 3629 1792 3629 1796 3629 1796 3630 1792 3630 872 3630 1797 3631 1708 3631 1798 3631 1798 3632 1708 3632 1709 3632 1798 3633 1709 3633 1736 3633 1736 3634 1709 3634 1799 3634 1736 3635 1799 3635 1734 3635 1734 3636 1799 3636 1794 3636 1734 3637 1794 3637 883 3637 883 3638 1794 3638 1796 3638 1803 3639 1801 3639 1800 3639 1800 3640 1801 3640 1748 3640 1800 3641 1748 3641 1798 3641 1798 3642 1748 3642 2795 3642 1798 3643 2795 3643 2793 3643 1804 3644 2802 3644 1805 3644 1805 3645 2802 3645 1747 3645 1805 3646 1747 3646 1806 3646 1806 3647 1747 3647 1801 3647 1806 3648 1801 3648 1802 3648 1802 3649 1801 3649 1803 3649 1802 3650 1803 3650 880 3650 880 3651 1803 3651 881 3651 2802 3652 2800 3652 1747 3652 1747 3653 2800 3653 2799 3653 1747 3654 2799 3654 1748 3654 1748 3655 2799 3655 2796 3655 1748 3656 2796 3656 2795 3656 2803 3657 1804 3657 1811 3657 1811 3658 1804 3658 1805 3658 1811 3659 1805 3659 1807 3659 1807 3660 1805 3660 1806 3660 1807 3661 1806 3661 1813 3661 1813 3662 1806 3662 1802 3662 1813 3663 1802 3663 1808 3663 1808 3664 1802 3664 880 3664 1809 3665 2805 3665 1810 3665 1810 3666 2805 3666 1811 3666 1810 3667 1811 3667 1737 3667 1737 3668 1811 3668 1807 3668 1737 3669 1807 3669 1812 3669 1812 3670 1807 3670 1813 3670 1812 3671 1813 3671 1733 3671 1733 3672 1813 3672 1808 3672 1814 3673 3608 3673 3364 3673 3364 3674 3608 3674 3363 3674 1814 3675 3364 3675 1815 3675 1815 3676 3364 3676 3366 3676 1815 3677 3366 3677 3607 3677 1842 3678 3604 3678 3366 3678 3366 3679 3604 3679 3606 3679 3366 3680 3606 3680 3607 3680 1816 3681 1817 3681 1818 3681 1818 3682 1817 3682 3352 3682 3608 3683 3610 3683 3363 3683 3363 3684 3610 3684 3611 3684 3363 3685 3611 3685 3361 3685 3361 3686 3611 3686 1819 3686 3361 3687 1819 3687 3359 3687 1928 3688 1920 3688 1831 3688 1831 3689 1920 3689 3355 3689 1819 3690 1820 3690 3359 3690 3359 3691 1820 3691 3635 3691 3359 3692 3635 3692 1821 3692 1817 3693 1822 3693 3352 3693 3352 3694 1822 3694 1825 3694 3352 3695 1825 3695 1841 3695 1823 3696 1824 3696 1837 3696 1825 3697 1826 3697 1841 3697 1841 3698 1826 3698 1883 3698 1841 3699 1883 3699 3587 3699 3587 3700 3588 3700 1841 3700 1841 3701 3588 3701 3590 3701 1841 3702 3590 3702 3592 3702 1816 3703 1818 3703 1827 3703 1827 3704 1818 3704 1830 3704 1827 3705 1830 3705 1828 3705 1920 3706 1921 3706 3355 3706 3355 3707 1921 3707 1829 3707 3355 3708 1829 3708 1830 3708 1830 3709 1829 3709 1913 3709 1830 3710 1913 3710 1828 3710 1928 3711 1831 3711 1832 3711 1832 3712 1831 3712 1833 3712 1832 3713 1833 3713 1938 3713 1823 3714 1834 3714 1824 3714 1824 3715 1834 3715 1835 3715 1824 3716 1835 3716 1833 3716 1833 3717 1835 3717 1940 3717 1833 3718 1940 3718 1938 3718 1865 3719 1866 3719 3359 3719 3359 3720 1866 3720 1836 3720 3359 3721 1836 3721 1837 3721 1837 3722 1836 3722 1869 3722 1837 3723 1869 3723 1823 3723 1821 3724 1838 3724 3359 3724 3359 3725 1838 3725 1839 3725 3359 3726 1839 3726 3640 3726 3640 3727 1840 3727 3359 3727 3359 3728 1840 3728 3643 3728 3359 3729 3643 3729 1865 3729 3592 3730 3594 3730 1841 3730 1841 3731 3594 3731 3596 3731 1841 3732 3596 3732 1842 3732 1842 3733 3596 3733 3602 3733 1842 3734 3602 3734 3604 3734 3134 3735 1843 3735 1941 3735 3162 3736 3167 3736 1939 3736 3166 3737 1844 3737 1933 3737 3172 3738 1929 3738 1931 3738 1930 3739 1924 3739 1845 3739 3181 3740 3180 3740 1925 3740 3179 3741 1917 3741 1918 3741 3133 3742 1846 3742 1914 3742 3189 3743 3196 3743 1909 3743 1847 3744 3202 3744 1906 3744 1905 3745 1900 3745 1907 3745 3206 3746 1848 3746 1902 3746 1889 3747 3230 3747 1849 3747 3227 3748 3232 3748 1884 3748 3231 3749 3237 3749 1850 3749 1870 3750 1862 3750 1872 3750 2162 3751 3252 3751 3135 3751 1851 3752 1852 3752 2653 3752 2653 3753 2654 3753 1851 3753 1851 3754 2654 3754 2628 3754 1851 3755 2628 3755 1853 3755 1854 3756 1855 3756 1851 3756 1851 3757 1855 3757 2646 3757 2646 3758 2649 3758 1851 3758 1851 3759 2649 3759 1856 3759 1851 3760 1856 3760 1852 3760 1867 3761 2634 3761 1857 3761 1857 3762 2642 3762 1867 3762 1867 3763 2642 3763 2643 3763 1867 3764 2643 3764 1858 3764 2620 3765 2619 3765 1875 3765 1875 3766 2619 3766 2625 3766 1875 3767 2625 3767 1859 3767 1874 3768 2158 3768 2159 3768 1874 3769 2159 3769 3135 3769 3135 3770 2159 3770 1860 3770 3135 3771 1860 3771 2162 3771 1861 3772 1873 3772 1872 3772 2139 3773 2140 3773 1862 3773 1862 3774 2140 3774 2141 3774 1862 3775 2141 3775 1872 3775 1872 3776 2141 3776 1863 3776 1872 3777 1863 3777 1861 3777 2132 3778 2137 3778 1862 3778 1862 3779 2137 3779 1864 3779 1862 3780 1864 3780 2139 3780 1865 3781 2132 3781 1866 3781 1866 3782 2132 3782 1862 3782 1866 3783 1862 3783 1836 3783 1836 3784 1862 3784 1870 3784 1836 3785 1870 3785 1869 3785 2635 3786 2634 3786 1882 3786 1882 3787 2634 3787 1867 3787 1882 3788 1867 3788 1851 3788 1851 3789 1867 3789 1858 3789 1851 3790 1858 3790 1854 3790 1823 3791 1869 3791 1868 3791 1868 3792 1869 3792 1870 3792 1868 3793 1870 3793 1871 3793 1871 3794 1870 3794 1872 3794 1871 3795 1872 3795 1874 3795 1874 3796 1872 3796 1873 3796 1874 3797 1873 3797 2158 3797 1859 3798 2635 3798 1875 3798 1875 3799 2635 3799 1882 3799 1875 3800 1882 3800 1880 3800 1822 3801 1817 3801 1876 3801 1876 3802 1817 3802 1877 3802 1876 3803 1877 3803 1891 3803 1891 3804 1877 3804 1878 3804 1891 3805 1878 3805 1890 3805 1890 3806 1878 3806 1895 3806 3248 3807 3247 3807 1880 3807 1880 3808 3247 3808 1879 3808 1880 3809 1879 3809 1875 3809 1875 3810 1879 3810 3249 3810 1875 3811 3249 3811 2620 3811 3237 3812 3248 3812 1850 3812 1850 3813 3248 3813 1880 3813 1850 3814 1880 3814 1881 3814 1881 3815 1880 3815 1882 3815 1881 3816 1882 3816 1887 3816 1887 3817 1882 3817 1851 3817 1887 3818 1851 3818 1883 3818 1883 3819 1851 3819 1853 3819 1883 3820 1853 3820 3587 3820 3232 3821 3231 3821 1884 3821 1884 3822 3231 3822 1850 3822 1884 3823 1850 3823 1885 3823 1885 3824 1850 3824 1881 3824 1885 3825 1881 3825 1886 3825 1886 3826 1881 3826 1887 3826 1886 3827 1887 3827 1826 3827 1826 3828 1887 3828 1883 3828 3230 3829 3227 3829 1849 3829 1849 3830 3227 3830 1884 3830 1849 3831 1884 3831 1888 3831 1888 3832 1884 3832 1885 3832 1888 3833 1885 3833 1892 3833 1892 3834 1885 3834 1886 3834 1892 3835 1886 3835 1825 3835 1825 3836 1886 3836 1826 3836 3129 3837 1889 3837 1890 3837 1890 3838 1889 3838 1849 3838 1890 3839 1849 3839 1891 3839 1891 3840 1849 3840 1888 3840 1891 3841 1888 3841 1876 3841 1876 3842 1888 3842 1892 3842 1876 3843 1892 3843 1822 3843 1822 3844 1892 3844 1825 3844 3211 3845 1893 3845 1894 3845 1894 3846 1893 3846 1895 3846 1894 3847 1895 3847 1896 3847 1896 3848 1895 3848 1878 3848 1896 3849 1878 3849 1899 3849 1899 3850 1878 3850 1877 3850 1899 3851 1877 3851 1816 3851 1816 3852 1877 3852 1817 3852 1893 3853 3217 3853 1895 3853 1895 3854 3217 3854 1897 3854 1895 3855 1897 3855 1890 3855 1890 3856 1897 3856 3223 3856 1890 3857 3223 3857 3129 3857 1848 3858 3211 3858 1902 3858 1902 3859 3211 3859 1894 3859 1902 3860 1894 3860 1904 3860 1904 3861 1894 3861 1896 3861 1904 3862 1896 3862 1898 3862 1898 3863 1896 3863 1899 3863 1898 3864 1899 3864 1827 3864 1827 3865 1899 3865 1816 3865 1900 3866 3206 3866 1907 3866 1907 3867 3206 3867 1902 3867 1907 3868 1902 3868 1901 3868 1901 3869 1902 3869 1904 3869 1901 3870 1904 3870 1903 3870 1903 3871 1904 3871 1898 3871 1903 3872 1898 3872 1828 3872 1828 3873 1898 3873 1827 3873 3202 3874 1905 3874 1906 3874 1906 3875 1905 3875 1907 3875 1906 3876 1907 3876 1912 3876 1912 3877 1907 3877 1901 3877 1912 3878 1901 3878 1908 3878 1908 3879 1901 3879 1903 3879 1908 3880 1903 3880 1913 3880 1913 3881 1903 3881 1828 3881 3196 3882 1847 3882 1909 3882 1909 3883 1847 3883 1906 3883 1909 3884 1906 3884 1910 3884 1910 3885 1906 3885 1912 3885 1910 3886 1912 3886 1911 3886 1911 3887 1912 3887 1908 3887 1911 3888 1908 3888 1829 3888 1829 3889 1908 3889 1913 3889 1846 3890 3189 3890 1914 3890 1914 3891 3189 3891 1909 3891 1914 3892 1909 3892 1915 3892 1915 3893 1909 3893 1910 3893 1915 3894 1910 3894 1916 3894 1916 3895 1910 3895 1911 3895 1916 3896 1911 3896 1921 3896 1921 3897 1911 3897 1829 3897 1917 3898 3133 3898 1918 3898 1918 3899 3133 3899 1914 3899 1918 3900 1914 3900 1923 3900 1923 3901 1914 3901 1915 3901 1923 3902 1915 3902 1919 3902 1919 3903 1915 3903 1916 3903 1919 3904 1916 3904 1920 3904 1920 3905 1916 3905 1921 3905 3180 3906 3179 3906 1925 3906 1925 3907 3179 3907 1918 3907 1925 3908 1918 3908 1922 3908 1922 3909 1918 3909 1923 3909 1922 3910 1923 3910 1927 3910 1927 3911 1923 3911 1919 3911 1927 3912 1919 3912 1928 3912 1928 3913 1919 3913 1920 3913 1924 3914 3181 3914 1845 3914 1845 3915 3181 3915 1925 3915 1845 3916 1925 3916 1926 3916 1926 3917 1925 3917 1922 3917 1926 3918 1922 3918 1932 3918 1932 3919 1922 3919 1927 3919 1932 3920 1927 3920 1832 3920 1832 3921 1927 3921 1928 3921 1929 3922 1930 3922 1931 3922 1931 3923 1930 3923 1845 3923 1931 3924 1845 3924 1936 3924 1936 3925 1845 3925 1926 3925 1936 3926 1926 3926 1937 3926 1937 3927 1926 3927 1932 3927 1937 3928 1932 3928 1938 3928 1938 3929 1932 3929 1832 3929 1844 3930 3172 3930 1933 3930 1933 3931 3172 3931 1931 3931 1933 3932 1931 3932 1934 3932 1934 3933 1931 3933 1936 3933 1934 3934 1936 3934 1935 3934 1935 3935 1936 3935 1937 3935 1935 3936 1937 3936 1940 3936 1940 3937 1937 3937 1938 3937 3167 3938 3166 3938 1939 3938 1939 3939 3166 3939 1933 3939 1939 3940 1933 3940 1942 3940 1942 3941 1933 3941 1934 3941 1942 3942 1934 3942 1943 3942 1943 3943 1934 3943 1935 3943 1943 3944 1935 3944 1835 3944 1835 3945 1935 3945 1940 3945 1843 3946 3162 3946 1941 3946 1941 3947 3162 3947 1939 3947 1941 3948 1939 3948 1944 3948 1944 3949 1939 3949 1942 3949 1944 3950 1942 3950 1945 3950 1945 3951 1942 3951 1943 3951 1945 3952 1943 3952 1834 3952 1834 3953 1943 3953 1835 3953 3135 3954 3134 3954 1874 3954 1874 3955 3134 3955 1941 3955 1874 3956 1941 3956 1871 3956 1871 3957 1941 3957 1944 3957 1871 3958 1944 3958 1868 3958 1868 3959 1944 3959 1945 3959 1868 3960 1945 3960 1823 3960 1823 3961 1945 3961 1834 3961 2971 3962 2973 3962 1955 3962 1955 3963 2973 3963 1956 3963 1956 3964 2973 3964 2975 3964 1956 3965 2975 3965 1946 3965 1946 3966 2975 3966 1947 3966 1946 3967 1947 3967 1255 3967 1701 3968 1948 3968 1986 3968 1986 3969 1948 3969 1949 3969 1986 3970 1949 3970 1953 3970 1949 3971 1950 3971 1953 3971 1953 3972 1950 3972 1951 3972 1953 3973 1951 3973 2924 3973 2924 3974 1952 3974 1953 3974 1953 3975 1952 3975 2923 3975 1953 3976 2923 3976 1978 3976 1978 3977 2923 3977 2935 3977 1978 3978 2935 3978 1955 3978 1955 3979 2935 3979 1954 3979 1955 3980 1954 3980 2971 3980 1953 3981 1978 3981 1977 3981 1955 3982 1956 3982 1957 3982 1957 3983 1956 3983 1946 3983 1946 3984 1611 3984 1957 3984 1957 3985 1611 3985 1613 3985 1957 3986 1613 3986 1975 3986 1613 3987 1614 3987 1975 3987 1975 3988 1614 3988 1958 3988 1975 3989 1958 3989 1974 3989 1974 3990 1958 3990 1604 3990 1974 3991 1604 3991 1959 3991 1604 3992 1605 3992 1959 3992 1959 3993 1605 3993 1606 3993 1959 3994 1606 3994 1960 3994 1960 3995 1606 3995 1961 3995 1960 3996 1961 3996 1962 3996 1961 3997 1645 3997 1962 3997 1962 3998 1645 3998 1963 3998 1962 3999 1963 3999 1964 3999 1963 4000 1652 4000 1964 4000 1964 4001 1652 4001 1965 4001 1964 4002 1965 4002 1966 4002 1966 4003 1965 4003 1651 4003 1966 4004 1651 4004 1968 4004 1105 4005 1967 4005 1661 4005 1661 4006 1967 4006 1968 4006 1661 4007 1968 4007 1660 4007 1660 4008 1968 4008 1651 4008 1967 4009 1111 4009 1968 4009 1968 4010 1111 4010 1979 4010 1968 4011 1979 4011 1966 4011 1966 4012 1979 4012 1969 4012 1966 4013 1969 4013 1964 4013 1964 4014 1969 4014 1970 4014 1964 4015 1970 4015 1962 4015 1962 4016 1970 4016 1971 4016 1962 4017 1971 4017 1960 4017 1960 4018 1971 4018 1972 4018 1960 4019 1972 4019 1959 4019 1959 4020 1972 4020 1973 4020 1959 4021 1973 4021 1974 4021 1974 4022 1973 4022 1985 4022 1974 4023 1985 4023 1975 4023 1975 4024 1985 4024 1976 4024 1975 4025 1976 4025 1957 4025 1957 4026 1976 4026 1977 4026 1957 4027 1977 4027 1955 4027 1955 4028 1977 4028 1978 4028 1111 4029 1097 4029 1979 4029 1979 4030 1097 4030 1980 4030 1979 4031 1980 4031 1969 4031 1969 4032 1980 4032 1987 4032 1969 4033 1987 4033 1970 4033 1970 4034 1987 4034 1981 4034 1970 4035 1981 4035 1971 4035 1971 4036 1981 4036 1990 4036 1971 4037 1990 4037 1972 4037 1972 4038 1990 4038 1982 4038 1972 4039 1982 4039 1973 4039 1973 4040 1982 4040 1983 4040 1973 4041 1983 4041 1985 4041 1985 4042 1983 4042 1984 4042 1985 4043 1984 4043 1976 4043 1976 4044 1984 4044 1994 4044 1976 4045 1994 4045 1977 4045 1977 4046 1994 4046 1995 4046 1977 4047 1995 4047 1953 4047 1953 4048 1995 4048 1986 4048 1097 4049 1686 4049 1980 4049 1980 4050 1686 4050 1988 4050 1980 4051 1988 4051 1987 4051 1987 4052 1988 4052 1989 4052 1987 4053 1989 4053 1981 4053 1981 4054 1989 4054 1991 4054 1981 4055 1991 4055 1990 4055 1990 4056 1991 4056 1700 4056 1990 4057 1700 4057 1982 4057 1982 4058 1700 4058 1992 4058 1982 4059 1992 4059 1983 4059 1983 4060 1992 4060 1698 4060 1983 4061 1698 4061 1984 4061 1984 4062 1698 4062 1993 4062 1984 4063 1993 4063 1994 4063 1994 4064 1993 4064 1996 4064 1994 4065 1996 4065 1995 4065 1995 4066 1996 4066 1997 4066 1995 4067 1997 4067 1986 4067 1986 4068 1997 4068 1701 4068 1998 4069 2010 4069 3094 4069 3094 4070 2010 4070 2001 4070 3094 4071 2001 4071 1999 4071 1999 4072 2001 4072 3086 4072 3063 4073 3070 4073 2023 4073 2023 4074 3070 4074 2000 4074 2023 4075 2000 4075 2001 4075 2001 4076 2000 4076 3038 4076 2001 4077 3038 4077 3086 4077 2024 4078 3040 4078 2023 4078 2023 4079 3040 4079 3039 4079 2023 4080 3039 4080 3063 4080 3037 4081 3047 4081 2002 4081 2002 4082 3047 4082 2003 4082 2002 4083 2003 4083 2024 4083 2024 4084 2003 4084 3041 4084 2024 4085 3041 4085 3040 4085 2004 4086 1615 4086 2022 4086 2005 4087 2015 4087 2014 4087 2045 4088 1662 4088 1115 4088 2006 4089 2045 4089 2043 4089 2007 4090 2008 4090 2028 4090 2025 4091 2007 4091 2009 4091 2010 4092 2025 4092 2026 4092 1678 4093 2015 4093 1683 4093 1683 4094 2015 4094 2005 4094 1683 4095 2005 4095 2042 4095 2011 4096 2016 4096 2019 4096 2012 4097 2014 4097 2013 4097 2013 4098 2014 4098 2015 4098 2013 4099 2015 4099 2044 4099 2044 4100 2015 4100 1678 4100 2044 4101 1678 4101 2006 4101 2033 4102 2016 4102 2017 4102 2017 4103 2016 4103 2011 4103 2017 4104 2011 4104 2021 4104 2008 4105 2018 4105 2019 4105 2019 4106 2018 4106 2020 4106 2019 4107 2020 4107 2011 4107 2011 4108 2020 4108 2041 4108 2011 4109 2041 4109 2021 4109 2021 4110 2041 4110 2040 4110 2021 4111 2040 4111 1639 4111 1639 4112 2040 4112 2039 4112 2010 4113 2026 4113 2001 4113 2001 4114 2026 4114 2027 4114 2001 4115 2027 4115 2023 4115 2023 4116 2027 4116 2022 4116 2023 4117 2022 4117 2024 4117 2024 4118 2022 4118 1615 4118 2024 4119 1615 4119 2002 4119 2025 4120 2009 4120 2026 4120 2026 4121 2009 4121 2030 4121 2026 4122 2030 4122 2027 4122 2027 4123 2030 4123 2031 4123 2027 4124 2031 4124 2022 4124 2022 4125 2031 4125 2032 4125 2022 4126 2032 4126 2004 4126 2034 4127 1622 4127 1628 4127 2007 4128 2028 4128 2009 4128 2009 4129 2028 4129 2029 4129 2009 4130 2029 4130 2030 4130 2030 4131 2029 4131 2034 4131 2030 4132 2034 4132 2031 4132 2031 4133 2034 4133 1628 4133 2031 4134 1628 4134 2032 4134 2008 4135 2019 4135 2028 4135 2028 4136 2019 4136 2016 4136 2028 4137 2016 4137 2029 4137 2029 4138 2016 4138 2033 4138 2029 4139 2033 4139 2034 4139 2034 4140 2033 4140 2037 4140 2034 4141 2037 4141 1622 4141 1639 4142 1642 4142 2021 4142 2021 4143 1642 4143 2035 4143 2021 4144 2035 4144 2017 4144 2017 4145 2035 4145 2036 4145 2017 4146 2036 4146 2033 4146 2033 4147 2036 4147 1619 4147 2033 4148 1619 4148 2037 4148 2038 4149 2039 4149 2012 4149 2012 4150 2039 4150 2040 4150 2012 4151 2040 4151 2014 4151 2014 4152 2040 4152 2041 4152 2014 4153 2041 4153 2005 4153 2005 4154 2041 4154 2020 4154 2005 4155 2020 4155 2042 4155 2042 4156 2020 4156 2018 4156 2047 4157 2049 4157 1658 4157 2006 4158 2043 4158 2044 4158 2044 4159 2043 4159 2046 4159 2044 4160 2046 4160 2013 4160 2013 4161 2046 4161 2047 4161 2013 4162 2047 4162 2012 4162 2012 4163 2047 4163 1658 4163 2012 4164 1658 4164 2038 4164 2045 4165 1115 4165 2043 4165 2043 4166 1115 4166 1117 4166 2043 4167 1117 4167 2046 4167 2046 4168 1117 4168 1106 4168 2046 4169 1106 4169 2047 4169 2047 4170 1106 4170 2048 4170 2047 4171 2048 4171 2049 4171 2061 4172 2207 4172 2209 4172 2051 4173 2212 4173 2105 4173 2209 4174 2050 4174 2061 4174 2061 4175 2050 4175 2051 4175 2061 4176 2051 4176 2052 4176 2052 4177 2051 4177 2105 4177 2061 4178 2055 4178 2191 4178 2191 4179 2192 4179 2061 4179 2061 4180 2192 4180 2206 4180 2061 4181 2206 4181 2207 4181 3431 4182 2054 4182 2053 4182 2053 4183 2054 4183 2058 4183 2053 4184 2058 4184 3446 4184 2061 4185 2104 4185 2055 4185 2055 4186 2104 4186 2056 4186 2055 4187 2056 4187 2189 4187 2189 4188 2056 4188 2089 4188 2189 4189 2089 4189 2058 4189 2058 4190 2089 4190 2057 4190 2058 4191 2057 4191 3446 4191 2059 4192 3449 4192 2060 4192 2060 4193 3449 4193 3448 4193 2060 4194 3448 4194 2062 4194 2062 4195 3448 4195 2057 4195 2062 4196 2057 4196 2088 4196 2088 4197 2057 4197 2089 4197 2061 4198 2052 4198 2106 4198 2081 4199 2079 4199 2092 4199 2078 4200 2060 4200 2062 4200 2063 4201 648 4201 2075 4201 2064 4202 2065 4202 2095 4202 3780 4203 2066 4203 2084 4203 3779 4204 3777 4204 2076 4204 2076 4205 3777 4205 2067 4205 2067 4206 3775 4206 2076 4206 2076 4207 3775 4207 2068 4207 2076 4208 2068 4208 645 4208 3780 4209 2084 4209 3781 4209 2064 4210 3783 4210 2065 4210 2065 4211 3783 4211 2069 4211 2065 4212 2069 4212 2070 4212 2109 4213 2073 4213 655 4213 2108 4214 3784 4214 2072 4214 2072 4215 3784 4215 3786 4215 3786 4216 3787 4216 2072 4216 2072 4217 3787 4217 2071 4217 2072 4218 2071 4218 2094 4218 1095 4219 658 4219 2073 4219 2073 4220 658 4220 2074 4220 2073 4221 2074 4221 655 4221 645 4222 2063 4222 2076 4222 2076 4223 2063 4223 2075 4223 2076 4224 2075 4224 2082 4224 2100 4225 2077 4225 1323 4225 1323 4226 2077 4226 2082 4226 1323 4227 2082 4227 1324 4227 1324 4228 2082 4228 2075 4228 2078 4229 2079 4229 2080 4229 2080 4230 2079 4230 2081 4230 2080 4231 2081 4231 1322 4231 1322 4232 2081 4232 2090 4232 2066 4233 3779 4233 2084 4233 2084 4234 3779 4234 2076 4234 2084 4235 2076 4235 2085 4235 2085 4236 2076 4236 2082 4236 2085 4237 2082 4237 2083 4237 2083 4238 2082 4238 2077 4238 2083 4239 2077 4239 2103 4239 2070 4240 3781 4240 2065 4240 2065 4241 3781 4241 2084 4241 2065 4242 2084 4242 2095 4242 2095 4243 2084 4243 2085 4243 2095 4244 2085 4244 2097 4244 2097 4245 2085 4245 2083 4245 2097 4246 2083 4246 2086 4246 2086 4247 2083 4247 2103 4247 2086 4248 2103 4248 2087 4248 2078 4249 2062 4249 2079 4249 2079 4250 2062 4250 2088 4250 2079 4251 2088 4251 2092 4251 2092 4252 2088 4252 2089 4252 2092 4253 2089 4253 2056 4253 2101 4254 2090 4254 2102 4254 2102 4255 2090 4255 2081 4255 2102 4256 2081 4256 2091 4256 2091 4257 2081 4257 2092 4257 2091 4258 2092 4258 2093 4258 2093 4259 2092 4259 2056 4259 2093 4260 2056 4260 2104 4260 2094 4261 2064 4261 2072 4261 2072 4262 2064 4262 2095 4262 2072 4263 2095 4263 2096 4263 2096 4264 2095 4264 2097 4264 2096 4265 2097 4265 2098 4265 2098 4266 2097 4266 2086 4266 2098 4267 2086 4267 2099 4267 2099 4268 2086 4268 2087 4268 2099 4269 2087 4269 2106 4269 2100 4270 2101 4270 2077 4270 2077 4271 2101 4271 2102 4271 2077 4272 2102 4272 2103 4272 2103 4273 2102 4273 2091 4273 2103 4274 2091 4274 2087 4274 2087 4275 2091 4275 2093 4275 2087 4276 2093 4276 2106 4276 2106 4277 2093 4277 2104 4277 2106 4278 2104 4278 2061 4278 2052 4279 2105 4279 2106 4279 2106 4280 2105 4280 2107 4280 2106 4281 2107 4281 2099 4281 2099 4282 2107 4282 1102 4282 2099 4283 1102 4283 2098 4283 2098 4284 1102 4284 1103 4284 2098 4285 1103 4285 2096 4285 2096 4286 1103 4286 1096 4286 2096 4287 1096 4287 2072 4287 2072 4288 1096 4288 2109 4288 2072 4289 2109 4289 2108 4289 2108 4290 2109 4290 655 4290 1114 4291 657 4291 1095 4291 1095 4292 657 4292 658 4292 2124 4293 2110 4293 2123 4293 1131 4294 2119 4294 3527 4294 3527 4295 2119 4295 3528 4295 2116 4296 2115 4296 2111 4296 2111 4297 2115 4297 2112 4297 2111 4298 2112 4298 3518 4298 2113 4299 2145 4299 777 4299 777 4300 2145 4300 2144 4300 777 4301 2144 4301 2114 4301 2114 4302 2144 4302 2115 4302 2114 4303 2115 4303 779 4303 779 4304 2115 4304 2116 4304 779 4305 2116 4305 761 4305 761 4306 2116 4306 2117 4306 761 4307 2117 4307 2119 4307 2119 4308 2117 4308 2118 4308 2119 4309 2118 4309 3528 4309 2123 4310 2110 4310 784 4310 784 4311 2110 4311 2148 4311 784 4312 2148 4312 777 4312 777 4313 2148 4313 2120 4313 777 4314 2120 4314 2113 4314 1093 4315 2121 4315 798 4315 798 4316 2121 4316 2122 4316 798 4317 2122 4317 2123 4317 2123 4318 2122 4318 2163 4318 2123 4319 2163 4319 2124 4319 2131 4320 3518 4320 2112 4320 3257 4321 2125 4321 2126 4321 2126 4322 2125 4322 3256 4322 2126 4323 3256 4323 2161 4323 3254 4324 3252 4324 2162 4324 2157 4325 2127 4325 3280 4325 3280 4326 2127 4326 2164 4326 3280 4327 2164 4327 2128 4327 2128 4328 2164 4328 2166 4328 2122 4329 2121 4329 2165 4329 2129 4330 2130 4330 2149 4330 2149 4331 2130 4331 3517 4331 2149 4332 3517 4332 2131 4332 2132 4333 2133 4333 2137 4333 2137 4334 2133 4334 2134 4334 2137 4335 2134 4335 2135 4335 2135 4336 2134 4336 3514 4336 2135 4337 3514 4337 2136 4337 1865 4338 3513 4338 2132 4338 2132 4339 3513 4339 3512 4339 2132 4340 3512 4340 2133 4340 1864 4341 2137 4341 2150 4341 2150 4342 2137 4342 2135 4342 2150 4343 2135 4343 2129 4343 2129 4344 2135 4344 2136 4344 2131 4345 2112 4345 2149 4345 2149 4346 2112 4346 2115 4346 2149 4347 2115 4347 2151 4347 2151 4348 2115 4348 2144 4348 2151 4349 2144 4349 2138 4349 1864 4350 2150 4350 2139 4350 2139 4351 2150 4351 2152 4351 2139 4352 2152 4352 2140 4352 2140 4353 2152 4353 2153 4353 2140 4354 2153 4354 2141 4354 2141 4355 2153 4355 1863 4355 1863 4356 2153 4356 2142 4356 1863 4357 2142 4357 1861 4357 1861 4358 2142 4358 2143 4358 1861 4359 2143 4359 1873 4359 2144 4360 2145 4360 2138 4360 2138 4361 2145 4361 2113 4361 2138 4362 2113 4362 2146 4362 2146 4363 2113 4363 2120 4363 2146 4364 2120 4364 2147 4364 2147 4365 2120 4365 2148 4365 2147 4366 2148 4366 2154 4366 2154 4367 2148 4367 2110 4367 2154 4368 2110 4368 2156 4368 2129 4369 2149 4369 2150 4369 2150 4370 2149 4370 2151 4370 2150 4371 2151 4371 2152 4371 2152 4372 2151 4372 2138 4372 2152 4373 2138 4373 2153 4373 2153 4374 2138 4374 2146 4374 2153 4375 2146 4375 2142 4375 2142 4376 2146 4376 2147 4376 2142 4377 2147 4377 2143 4377 2143 4378 2147 4378 2154 4378 2143 4379 2154 4379 2155 4379 2155 4380 2154 4380 2156 4380 2155 4381 2156 4381 2160 4381 2160 4382 2156 4382 2127 4382 2160 4383 2127 4383 2126 4383 2126 4384 2127 4384 2157 4384 2126 4385 2157 4385 3257 4385 1873 4386 2143 4386 2158 4386 2158 4387 2143 4387 2155 4387 2158 4388 2155 4388 2159 4388 2159 4389 2155 4389 2160 4389 2159 4390 2160 4390 1860 4390 1860 4391 2160 4391 2126 4391 1860 4392 2126 4392 2162 4392 2162 4393 2126 4393 2161 4393 2162 4394 2161 4394 3254 4394 2110 4395 2124 4395 2156 4395 2156 4396 2124 4396 2163 4396 2156 4397 2163 4397 2127 4397 2127 4398 2163 4398 2122 4398 2127 4399 2122 4399 2164 4399 2164 4400 2122 4400 2165 4400 2164 4401 2165 4401 2166 4401 3298 4402 1100 4402 2167 4402 2169 4403 2165 4403 2121 4403 1100 4404 3298 4404 2121 4404 2121 4405 3298 4405 2168 4405 2121 4406 2168 4406 2169 4406 3423 4407 3424 4407 2170 4407 2767 4408 2171 4408 2210 4408 2211 4409 2212 4409 2051 4409 2205 4410 2727 4410 2210 4410 2210 4411 2727 4411 2172 4411 2210 4412 2172 4412 2767 4412 2195 4413 2741 4413 2739 4413 2173 4414 2737 4414 2196 4414 2196 4415 2737 4415 2174 4415 2196 4416 2174 4416 2742 4416 3420 4417 2176 4417 2175 4417 2175 4418 2176 4418 3419 4418 2175 4419 3419 4419 2177 4419 3420 4420 2175 4420 3425 4420 3425 4421 2175 4421 1721 4421 3425 4422 1721 4422 3424 4422 2054 4423 3431 4423 2178 4423 2178 4424 2179 4424 2183 4424 2183 4425 2179 4425 3426 4425 2183 4426 3426 4426 3427 4426 3424 4427 1721 4427 2170 4427 2170 4428 1721 4428 2180 4428 2170 4429 2180 4429 2197 4429 2197 4430 2180 4430 2181 4430 2197 4431 2181 4431 2182 4431 2178 4432 2183 4432 2054 4432 2054 4433 2183 4433 2199 4433 2054 4434 2199 4434 2058 4434 2181 4435 1722 4435 2182 4435 2182 4436 1722 4436 2184 4436 2182 4437 2184 4437 2198 4437 2198 4438 2184 4438 1723 4438 2198 4439 1723 4439 2200 4439 1723 4440 2185 4440 2200 4440 2200 4441 2185 4441 2186 4441 2200 4442 2186 4442 2201 4442 2201 4443 2186 4443 2187 4443 2201 4444 2187 4444 2203 4444 2058 4445 2199 4445 2189 4445 2189 4446 2199 4446 2188 4446 2189 4447 2188 4447 2055 4447 2055 4448 2188 4448 2202 4448 2055 4449 2202 4449 2191 4449 2191 4450 2202 4450 2190 4450 2191 4451 2190 4451 2192 4451 2192 4452 2190 4452 2204 4452 2192 4453 2204 4453 2206 4453 2187 4454 1724 4454 2203 4454 2203 4455 1724 4455 2193 4455 2203 4456 2193 4456 2194 4456 2194 4457 2193 4457 2195 4457 2194 4458 2195 4458 2196 4458 2196 4459 2195 4459 2739 4459 2196 4460 2739 4460 2173 4460 3423 4461 2170 4461 3427 4461 3427 4462 2170 4462 2197 4462 3427 4463 2197 4463 2183 4463 2183 4464 2197 4464 2182 4464 2183 4465 2182 4465 2199 4465 2199 4466 2182 4466 2198 4466 2199 4467 2198 4467 2188 4467 2188 4468 2198 4468 2200 4468 2188 4469 2200 4469 2202 4469 2202 4470 2200 4470 2201 4470 2202 4471 2201 4471 2190 4471 2190 4472 2201 4472 2203 4472 2190 4473 2203 4473 2204 4473 2204 4474 2203 4474 2194 4474 2204 4475 2194 4475 2208 4475 2208 4476 2194 4476 2196 4476 2208 4477 2196 4477 2205 4477 2205 4478 2196 4478 2742 4478 2205 4479 2742 4479 2727 4479 2206 4480 2204 4480 2207 4480 2207 4481 2204 4481 2208 4481 2207 4482 2208 4482 2209 4482 2209 4483 2208 4483 2205 4483 2209 4484 2205 4484 2050 4484 2050 4485 2205 4485 2210 4485 2050 4486 2210 4486 2051 4486 2051 4487 2210 4487 2171 4487 2051 4488 2171 4488 2211 4488 2211 4489 2724 4489 2212 4489 2212 4490 2724 4490 2213 4490 2212 4491 2213 4491 1094 4491 1094 4492 2213 4492 2719 4492 1094 4493 2719 4493 2214 4493 2215 4494 1248 4494 2216 4494 2215 4495 2216 4495 1283 4495 1283 4496 2216 4496 1259 4496 1283 4497 1259 4497 2217 4497 2217 4498 1259 4498 1262 4498 2217 4499 1262 4499 1273 4499 1273 4500 1262 4500 2218 4500 1273 4501 2218 4501 1279 4501 1125 4502 1281 4502 2219 4502 2219 4503 1281 4503 1292 4503 2219 4504 1292 4504 2220 4504 2220 4505 1292 4505 1607 4505 1607 4506 1292 4506 1608 4506 1608 4507 1292 4507 1272 4507 1608 4508 1272 4508 2221 4508 2224 4509 1603 4509 2222 4509 2222 4510 2223 4510 2224 4510 2224 4511 2223 4511 1610 4511 2224 4512 1610 4512 1272 4512 1272 4513 1610 4513 1609 4513 1272 4514 1609 4514 2221 4514 801 4515 800 4515 3650 4515 1315 4516 1300 4516 3650 4516 3650 4517 1300 4517 631 4517 3650 4518 631 4518 801 4518 2229 4519 2225 4519 864 4519 2229 4520 864 4520 1646 4520 1646 4521 864 4521 852 4521 1646 4522 852 4522 2226 4522 2231 4523 860 4523 2227 4523 2227 4524 860 4524 866 4524 2227 4525 866 4525 2228 4525 2228 4526 866 4526 2225 4526 2228 4527 2225 4527 2229 4527 2233 4528 862 4528 2230 4528 2230 4529 862 4529 2231 4529 2230 4530 2231 4530 2232 4530 2232 4531 2231 4531 2227 4531 2237 4532 2239 4532 1576 4532 1576 4533 2239 4533 858 4533 1576 4534 858 4534 2233 4534 2233 4535 858 4535 2234 4535 2233 4536 2234 4536 862 4536 2235 4537 2236 4537 1574 4537 1574 4538 2236 4538 857 4538 1574 4539 857 4539 1575 4539 1575 4540 857 4540 2238 4540 1575 4541 2238 4541 2237 4541 2237 4542 2238 4542 856 4542 2237 4543 856 4543 2239 4543 2240 4544 1006 4544 1578 4544 1578 4545 1006 4545 2241 4545 2241 4546 1006 4546 1011 4546 2241 4547 1011 4547 1595 4547 1011 4548 1010 4548 1595 4548 1595 4549 1010 4549 1009 4549 1595 4550 1009 4550 1579 4550 1579 4551 1009 4551 2242 4551 1579 4552 2242 4552 1584 4552 1584 4553 2242 4553 1013 4553 1584 4554 1013 4554 803 4554 1646 4555 2226 4555 2243 4555 2243 4556 2226 4556 2244 4556 2243 4557 2244 4557 1577 4557 1577 4558 2244 4558 1578 4558 1578 4559 2244 4559 1005 4559 1578 4560 1005 4560 2240 4560 2245 4561 964 4561 810 4561 810 4562 964 4562 962 4562 807 4563 808 4563 810 4563 974 4564 824 4564 977 4564 977 4565 824 4565 825 4565 977 4566 825 4566 2246 4566 2246 4567 825 4567 2247 4567 2246 4568 2247 4568 2248 4568 2248 4569 2247 4569 826 4569 2248 4570 826 4570 990 4570 836 4571 2249 4571 2267 4571 2270 4572 986 4572 2250 4572 2250 4573 986 4573 990 4573 2250 4574 990 4574 828 4574 828 4575 990 4575 826 4575 830 4576 2251 4576 2249 4576 2249 4577 2251 4577 832 4577 2249 4578 832 4578 969 4578 969 4579 832 4579 820 4579 969 4580 820 4580 2252 4580 2252 4581 820 4581 2253 4581 2252 4582 2253 4582 2255 4582 2255 4583 2253 4583 2254 4583 2255 4584 2254 4584 2256 4584 2256 4585 2254 4585 2257 4585 2256 4586 2257 4586 974 4586 974 4587 2257 4587 822 4587 974 4588 822 4588 824 4588 810 4589 811 4589 2245 4589 2245 4590 811 4590 2258 4590 2245 4591 2258 4591 2259 4591 2259 4592 2258 4592 813 4592 2259 4593 813 4593 943 4593 943 4594 813 4594 815 4594 943 4595 815 4595 2260 4595 2260 4596 815 4596 2261 4596 2260 4597 2261 4597 953 4597 953 4598 2261 4598 2263 4598 953 4599 2263 4599 2262 4599 2262 4600 2263 4600 833 4600 2262 4601 833 4601 2266 4601 2266 4602 833 4602 834 4602 836 4603 2264 4603 2249 4603 2249 4604 2264 4604 2265 4604 2249 4605 2265 4605 830 4605 834 4606 836 4606 2266 4606 2266 4607 836 4607 2267 4607 2266 4608 2267 4608 2268 4608 2268 4609 2267 4609 986 4609 2268 4610 986 4610 2269 4610 2269 4611 986 4611 959 4611 2270 4612 2271 4612 986 4612 986 4613 2271 4613 819 4613 986 4614 819 4614 837 4614 962 4615 959 4615 810 4615 810 4616 959 4616 986 4616 810 4617 986 4617 838 4617 838 4618 986 4618 837 4618 806 4619 807 4619 804 4619 804 4620 807 4620 810 4620 804 4621 810 4621 2272 4621 2272 4622 810 4622 838 4622 2421 4623 2420 4623 2282 4623 2282 4624 2420 4624 2280 4624 2421 4625 1617 4625 2273 4625 2273 4626 1617 4626 2274 4626 2273 4627 2274 4627 2275 4627 2275 4628 2274 4628 2276 4628 2275 4629 2276 4629 2427 4629 2427 4630 2276 4630 1616 4630 2427 4631 1616 4631 2286 4631 2418 4632 2277 4632 2278 4632 2278 4633 2277 4633 963 4633 2278 4634 963 4634 2279 4634 2279 4635 963 4635 965 4635 2279 4636 965 4636 2280 4636 2280 4637 965 4637 2281 4637 2280 4638 2281 4638 2282 4638 2283 4639 961 4639 2418 4639 2418 4640 961 4640 2284 4640 2418 4641 2284 4641 2277 4641 1616 4642 2285 4642 2286 4642 2286 4643 2285 4643 2287 4643 2286 4644 2287 4644 2428 4644 2428 4645 2287 4645 2288 4645 2428 4646 2288 4646 2429 4646 2429 4647 2288 4647 1632 4647 2429 4648 1632 4648 2289 4648 2418 4649 2416 4649 2283 4649 2283 4650 2416 4650 2290 4650 2283 4651 2290 4651 960 4651 960 4652 2290 4652 2291 4652 2291 4653 2290 4653 2292 4653 2292 4654 2290 4654 2293 4654 2292 4655 2293 4655 2297 4655 1632 4656 1633 4656 2289 4656 2289 4657 1633 4657 2294 4657 2289 4658 2294 4658 2430 4658 2430 4659 2294 4659 1634 4659 2430 4660 1634 4660 2431 4660 2431 4661 1634 4661 2295 4661 2431 4662 2295 4662 2432 4662 2432 4663 2295 4663 1587 4663 2432 4664 1587 4664 2433 4664 2412 4665 2305 4665 2414 4665 2414 4666 2305 4666 2296 4666 2414 4667 2296 4667 2415 4667 2415 4668 2296 4668 957 4668 2415 4669 957 4669 2297 4669 2297 4670 957 4670 2298 4670 2297 4671 2298 4671 2292 4671 2310 4672 954 4672 2299 4672 2299 4673 954 4673 2300 4673 2299 4674 2300 4674 2301 4674 2301 4675 2300 4675 2302 4675 2301 4676 2302 4676 2409 4676 2409 4677 2302 4677 2303 4677 2409 4678 2303 4678 2411 4678 2411 4679 2303 4679 2304 4679 2411 4680 2304 4680 2412 4680 2412 4681 2304 4681 958 4681 2412 4682 958 4682 2305 4682 2402 4683 951 4683 2306 4683 2306 4684 951 4684 2308 4684 2306 4685 2308 4685 2307 4685 2307 4686 2308 4686 956 4686 2307 4687 956 4687 2405 4687 2405 4688 956 4688 2309 4688 2405 4689 2309 4689 2310 4689 2310 4690 2309 4690 955 4690 2310 4691 955 4691 954 4691 2330 4692 947 4692 2400 4692 2400 4693 947 4693 2311 4693 2400 4694 2311 4694 2401 4694 2401 4695 2311 4695 2312 4695 2401 4696 2312 4696 2402 4696 2402 4697 2312 4697 952 4697 2402 4698 952 4698 951 4698 1587 4699 2313 4699 2433 4699 2433 4700 2313 4700 1592 4700 2433 4701 1592 4701 2314 4701 2314 4702 1592 4702 1590 4702 2314 4703 1590 4703 2434 4703 2434 4704 1590 4704 1586 4704 2434 4705 1586 4705 2315 4705 2315 4706 1586 4706 2316 4706 2315 4707 2316 4707 2317 4707 2317 4708 2316 4708 1585 4708 2317 4709 1585 4709 2436 4709 2436 4710 1585 4710 2318 4710 2436 4711 2318 4711 2319 4711 2319 4712 2318 4712 2320 4712 2319 4713 2320 4713 2437 4713 2437 4714 2320 4714 2321 4714 2437 4715 2321 4715 2439 4715 2439 4716 2321 4716 2322 4716 2439 4717 2322 4717 2440 4717 2440 4718 2322 4718 1580 4718 2440 4719 1580 4719 2323 4719 2323 4720 1580 4720 2324 4720 2323 4721 2324 4721 2441 4721 2441 4722 2324 4722 2325 4722 2441 4723 2325 4723 2326 4723 2326 4724 2325 4724 2327 4724 2326 4725 2327 4725 2328 4725 2328 4726 2327 4726 1583 4726 2328 4727 1583 4727 2329 4727 2331 4728 949 4728 2330 4728 2330 4729 949 4729 948 4729 2330 4730 948 4730 947 4730 2330 4731 2397 4731 2331 4731 2331 4732 2397 4732 2396 4732 2331 4733 2396 4733 950 4733 950 4734 2396 4734 2395 4734 950 4735 2395 4735 945 4735 945 4736 2395 4736 946 4736 1583 4737 2332 4737 2329 4737 2329 4738 2332 4738 1581 4738 2329 4739 1581 4739 2444 4739 2444 4740 1581 4740 1571 4740 2444 4741 1571 4741 2446 4741 2446 4742 1571 4742 2334 4742 1570 4743 2333 4743 2334 4743 2334 4744 2333 4744 2448 4744 2334 4745 2448 4745 2446 4745 946 4746 2395 4746 2341 4746 2341 4747 2395 4747 2335 4747 2341 4748 2335 4748 2340 4748 1570 4749 1567 4749 2333 4749 2333 4750 1567 4750 1568 4750 2333 4751 1568 4751 2336 4751 2336 4752 1568 4752 1569 4752 2336 4753 1569 4753 2337 4753 2337 4754 1569 4754 2338 4754 2337 4755 2338 4755 2342 4755 2391 4756 2339 4756 2393 4756 2393 4757 2339 4757 940 4757 2393 4758 940 4758 2394 4758 2394 4759 940 4759 942 4759 2394 4760 942 4760 2340 4760 2340 4761 942 4761 944 4761 2340 4762 944 4762 2341 4762 2338 4763 1566 4763 2342 4763 2342 4764 1566 4764 2343 4764 2342 4765 2343 4765 2452 4765 2452 4766 2343 4766 2344 4766 2452 4767 2344 4767 2453 4767 2453 4768 2344 4768 2421 4768 2421 4769 2426 4769 2345 4769 2345 4770 2426 4770 2346 4770 2345 4771 2346 4771 2348 4771 2348 4772 2346 4772 2347 4772 2348 4773 2347 4773 2349 4773 2349 4774 2347 4774 2350 4774 2349 4775 2350 4775 2352 4775 2352 4776 2350 4776 2351 4776 2352 4777 2351 4777 2353 4777 2353 4778 2351 4778 2354 4778 2353 4779 2354 4779 2419 4779 2419 4780 2354 4780 2355 4780 2419 4781 2355 4781 2417 4781 2417 4782 2355 4782 2356 4782 2417 4783 2356 4783 2357 4783 2357 4784 2356 4784 2358 4784 2357 4785 2358 4785 2359 4785 2359 4786 2358 4786 2360 4786 2359 4787 2360 4787 2361 4787 2361 4788 2360 4788 2362 4788 2361 4789 2362 4789 2363 4789 2363 4790 2362 4790 2364 4790 2363 4791 2364 4791 2413 4791 2413 4792 2364 4792 2365 4792 2413 4793 2365 4793 2367 4793 2367 4794 2365 4794 2366 4794 2367 4795 2366 4795 2410 4795 2410 4796 2366 4796 2435 4796 2410 4797 2435 4797 2408 4797 2408 4798 2435 4798 2368 4798 2408 4799 2368 4799 2407 4799 2407 4800 2368 4800 2369 4800 2407 4801 2369 4801 2406 4801 2406 4802 2369 4802 2438 4802 2406 4803 2438 4803 2370 4803 2370 4804 2438 4804 2371 4804 2370 4805 2371 4805 2404 4805 2404 4806 2371 4806 2372 4806 2404 4807 2372 4807 2374 4807 2374 4808 2372 4808 2373 4808 2374 4809 2373 4809 2375 4809 2375 4810 2373 4810 2376 4810 2375 4811 2376 4811 2403 4811 2403 4812 2376 4812 2442 4812 2403 4813 2442 4813 2399 4813 2399 4814 2442 4814 2443 4814 2399 4815 2443 4815 2377 4815 2377 4816 2443 4816 2378 4816 2377 4817 2378 4817 2398 4817 2398 4818 2378 4818 2445 4818 2398 4819 2445 4819 2379 4819 2379 4820 2445 4820 2381 4820 2379 4821 2381 4821 2380 4821 2380 4822 2381 4822 2447 4822 2380 4823 2447 4823 2382 4823 2382 4824 2447 4824 2449 4824 2382 4825 2449 4825 2383 4825 2383 4826 2449 4826 2384 4826 2383 4827 2384 4827 2385 4827 2385 4828 2384 4828 2450 4828 2385 4829 2450 4829 2392 4829 2392 4830 2450 4830 2451 4830 2392 4831 2451 4831 2386 4831 2386 4832 2451 4832 2387 4832 2386 4833 2387 4833 2390 4833 2390 4834 2387 4834 2388 4834 2390 4835 2388 4835 2389 4835 2389 4836 2388 4836 2421 4836 2421 4837 2422 4837 2389 4837 2389 4838 2422 4838 2425 4838 2389 4839 2425 4839 2390 4839 2390 4840 2425 4840 2391 4840 2390 4841 2391 4841 2386 4841 2386 4842 2391 4842 2393 4842 2386 4843 2393 4843 2392 4843 2392 4844 2393 4844 2394 4844 2392 4845 2394 4845 2385 4845 2385 4846 2394 4846 2340 4846 2385 4847 2340 4847 2383 4847 2383 4848 2340 4848 2335 4848 2383 4849 2335 4849 2382 4849 2382 4850 2335 4850 2395 4850 2382 4851 2395 4851 2380 4851 2380 4852 2395 4852 2396 4852 2380 4853 2396 4853 2379 4853 2379 4854 2396 4854 2397 4854 2379 4855 2397 4855 2398 4855 2398 4856 2397 4856 2330 4856 2398 4857 2330 4857 2377 4857 2377 4858 2330 4858 2400 4858 2377 4859 2400 4859 2399 4859 2399 4860 2400 4860 2401 4860 2399 4861 2401 4861 2403 4861 2403 4862 2401 4862 2402 4862 2403 4863 2402 4863 2375 4863 2375 4864 2402 4864 2306 4864 2375 4865 2306 4865 2374 4865 2374 4866 2306 4866 2307 4866 2374 4867 2307 4867 2404 4867 2404 4868 2307 4868 2405 4868 2404 4869 2405 4869 2370 4869 2370 4870 2405 4870 2310 4870 2370 4871 2310 4871 2406 4871 2406 4872 2310 4872 2299 4872 2406 4873 2299 4873 2407 4873 2407 4874 2299 4874 2301 4874 2407 4875 2301 4875 2408 4875 2408 4876 2301 4876 2409 4876 2408 4877 2409 4877 2410 4877 2410 4878 2409 4878 2411 4878 2410 4879 2411 4879 2367 4879 2367 4880 2411 4880 2412 4880 2367 4881 2412 4881 2413 4881 2413 4882 2412 4882 2414 4882 2413 4883 2414 4883 2363 4883 2363 4884 2414 4884 2415 4884 2363 4885 2415 4885 2361 4885 2361 4886 2415 4886 2297 4886 2361 4887 2297 4887 2359 4887 2359 4888 2297 4888 2293 4888 2359 4889 2293 4889 2357 4889 2357 4890 2293 4890 2290 4890 2357 4891 2290 4891 2417 4891 2417 4892 2290 4892 2416 4892 2417 4893 2416 4893 2419 4893 2419 4894 2416 4894 2418 4894 2419 4895 2418 4895 2353 4895 2353 4896 2418 4896 2278 4896 2353 4897 2278 4897 2352 4897 2352 4898 2278 4898 2279 4898 2352 4899 2279 4899 2349 4899 2349 4900 2279 4900 2280 4900 2349 4901 2280 4901 2348 4901 2348 4902 2280 4902 2420 4902 2348 4903 2420 4903 2345 4903 2345 4904 2420 4904 2421 4904 2421 4905 2423 4905 2422 4905 2422 4906 2423 4906 939 4906 2422 4907 939 4907 2425 4907 2425 4908 939 4908 2424 4908 2425 4909 2424 4909 2391 4909 2391 4910 2424 4910 941 4910 2391 4911 941 4911 2339 4911 2421 4912 2273 4912 2426 4912 2426 4913 2273 4913 2275 4913 2426 4914 2275 4914 2346 4914 2346 4915 2275 4915 2427 4915 2346 4916 2427 4916 2347 4916 2347 4917 2427 4917 2286 4917 2347 4918 2286 4918 2350 4918 2350 4919 2286 4919 2428 4919 2350 4920 2428 4920 2351 4920 2351 4921 2428 4921 2429 4921 2351 4922 2429 4922 2354 4922 2354 4923 2429 4923 2289 4923 2354 4924 2289 4924 2355 4924 2355 4925 2289 4925 2430 4925 2355 4926 2430 4926 2356 4926 2356 4927 2430 4927 2431 4927 2356 4928 2431 4928 2358 4928 2358 4929 2431 4929 2432 4929 2358 4930 2432 4930 2360 4930 2360 4931 2432 4931 2433 4931 2360 4932 2433 4932 2362 4932 2362 4933 2433 4933 2314 4933 2362 4934 2314 4934 2364 4934 2364 4935 2314 4935 2434 4935 2364 4936 2434 4936 2365 4936 2365 4937 2434 4937 2315 4937 2365 4938 2315 4938 2366 4938 2366 4939 2315 4939 2317 4939 2366 4940 2317 4940 2435 4940 2435 4941 2317 4941 2436 4941 2435 4942 2436 4942 2368 4942 2368 4943 2436 4943 2319 4943 2368 4944 2319 4944 2369 4944 2369 4945 2319 4945 2437 4945 2369 4946 2437 4946 2438 4946 2438 4947 2437 4947 2439 4947 2438 4948 2439 4948 2371 4948 2371 4949 2439 4949 2440 4949 2371 4950 2440 4950 2372 4950 2372 4951 2440 4951 2323 4951 2372 4952 2323 4952 2373 4952 2373 4953 2323 4953 2441 4953 2373 4954 2441 4954 2376 4954 2376 4955 2441 4955 2326 4955 2376 4956 2326 4956 2442 4956 2442 4957 2326 4957 2328 4957 2442 4958 2328 4958 2443 4958 2443 4959 2328 4959 2329 4959 2443 4960 2329 4960 2378 4960 2378 4961 2329 4961 2444 4961 2378 4962 2444 4962 2445 4962 2445 4963 2444 4963 2446 4963 2445 4964 2446 4964 2381 4964 2381 4965 2446 4965 2448 4965 2381 4966 2448 4966 2447 4966 2447 4967 2448 4967 2333 4967 2447 4968 2333 4968 2449 4968 2449 4969 2333 4969 2336 4969 2449 4970 2336 4970 2384 4970 2384 4971 2336 4971 2337 4971 2384 4972 2337 4972 2450 4972 2450 4973 2337 4973 2342 4973 2450 4974 2342 4974 2451 4974 2451 4975 2342 4975 2452 4975 2451 4976 2452 4976 2387 4976 2387 4977 2452 4977 2453 4977 2387 4978 2453 4978 2388 4978 2388 4979 2453 4979 2421 4979 2454 4980 987 4980 2455 4980 2455 4981 987 4981 985 4981 2455 4982 985 4982 2456 4982 2456 4983 985 4983 993 4983 2456 4984 993 4984 2613 4984 2587 4985 2457 4985 2586 4985 2586 4986 2457 4986 981 4986 2586 4987 981 4987 2584 4987 2584 4988 981 4988 989 4988 2584 4989 989 4989 2454 4989 2454 4990 989 4990 988 4990 2454 4991 988 4991 987 4991 2540 4992 2458 4992 2541 4992 2541 4993 2458 4993 2460 4993 2541 4994 2460 4994 2459 4994 2459 4995 2460 4995 1644 4995 2459 4996 1644 4996 2461 4996 2461 4997 1644 4997 2462 4997 2461 4998 2462 4998 2463 4998 2463 4999 2462 4999 1636 4999 2463 5000 1636 5000 2544 5000 2544 5001 1636 5001 1643 5001 2544 5002 1643 5002 2545 5002 2545 5003 1643 5003 2465 5003 2545 5004 2465 5004 2464 5004 2464 5005 2465 5005 1641 5005 2464 5006 1641 5006 2547 5006 2547 5007 1641 5007 1640 5007 2547 5008 1640 5008 2549 5008 2549 5009 1640 5009 1638 5009 2549 5010 1638 5010 2550 5010 2550 5011 1638 5011 1637 5011 2550 5012 1637 5012 2490 5012 2590 5013 2471 5013 2589 5013 2589 5014 2471 5014 984 5014 2589 5015 984 5015 2466 5015 2466 5016 984 5016 983 5016 2466 5017 983 5017 2587 5017 2587 5018 983 5018 982 5018 2587 5019 982 5019 2457 5019 2476 5020 2467 5020 2592 5020 2592 5021 2467 5021 2469 5021 2592 5022 2469 5022 2468 5022 2468 5023 2469 5023 2470 5023 2468 5024 2470 5024 2590 5024 2590 5025 2470 5025 980 5025 2590 5026 980 5026 2471 5026 2597 5027 978 5027 2596 5027 2596 5028 978 5028 2472 5028 2596 5029 2472 5029 2473 5029 2473 5030 2472 5030 2474 5030 2473 5031 2474 5031 2475 5031 2475 5032 2474 5032 979 5032 2475 5033 979 5033 2476 5033 2476 5034 979 5034 2477 5034 2476 5035 2477 5035 2467 5035 2602 5036 976 5036 2599 5036 2599 5037 976 5037 975 5037 2599 5038 975 5038 2598 5038 2598 5039 975 5039 2478 5039 2598 5040 2478 5040 2597 5040 2597 5041 2478 5041 2479 5041 2597 5042 2479 5042 978 5042 2485 5043 2488 5043 2480 5043 2480 5044 2488 5044 2482 5044 2480 5045 2482 5045 2481 5045 2481 5046 2482 5046 2483 5046 2481 5047 2483 5047 2602 5047 2602 5048 2483 5048 2484 5048 2602 5049 2484 5049 976 5049 2606 5050 973 5050 2605 5050 2605 5051 973 5051 2486 5051 2605 5052 2486 5052 2485 5052 2485 5053 2486 5053 2487 5053 2485 5054 2487 5054 2488 5054 1637 5055 2489 5055 2490 5055 2490 5056 2489 5056 2491 5056 2490 5057 2491 5057 2552 5057 2552 5058 2491 5058 2492 5058 2552 5059 2492 5059 2554 5059 2554 5060 2492 5060 2493 5060 2554 5061 2493 5061 2494 5061 2494 5062 2493 5062 2495 5062 2494 5063 2495 5063 2556 5063 2556 5064 2495 5064 2496 5064 2556 5065 2496 5065 2497 5065 2497 5066 2496 5066 1659 5066 2497 5067 1659 5067 2498 5067 2498 5068 1659 5068 2499 5068 2498 5069 2499 5069 2500 5069 2500 5070 2499 5070 1657 5070 2500 5071 1657 5071 2501 5071 2501 5072 1657 5072 2502 5072 2501 5073 2502 5073 2503 5073 2503 5074 2502 5074 2504 5074 2503 5075 2504 5075 2559 5075 2559 5076 2504 5076 1656 5076 2559 5077 1656 5077 2561 5077 2561 5078 1656 5078 1655 5078 2561 5079 1655 5079 2505 5079 2505 5080 1655 5080 2506 5080 2505 5081 2506 5081 2562 5081 2562 5082 2506 5082 2507 5082 2562 5083 2507 5083 2563 5083 2563 5084 2507 5084 2508 5084 2563 5085 2508 5085 2509 5085 2509 5086 2508 5086 1650 5086 2509 5087 1650 5087 2566 5087 2566 5088 1650 5088 2510 5088 2566 5089 2510 5089 2527 5089 2609 5090 971 5090 2511 5090 2511 5091 971 5091 2512 5091 2511 5092 2512 5092 2513 5092 2513 5093 2512 5093 970 5093 2513 5094 970 5094 2607 5094 2607 5095 970 5095 2514 5095 2607 5096 2514 5096 2606 5096 2606 5097 2514 5097 966 5097 2606 5098 966 5098 973 5098 2524 5099 2516 5099 2515 5099 2515 5100 2516 5100 2518 5100 2515 5101 2518 5101 2517 5101 2517 5102 2518 5102 972 5102 2517 5103 972 5103 2609 5103 2609 5104 972 5104 2519 5104 2609 5105 2519 5105 971 5105 2618 5106 967 5106 2520 5106 2520 5107 967 5107 2521 5107 2520 5108 2521 5108 2522 5108 2522 5109 2521 5109 2523 5109 2522 5110 2523 5110 2524 5110 2524 5111 2523 5111 2525 5111 2524 5112 2525 5112 2516 5112 2510 5113 2526 5113 2527 5113 2527 5114 2526 5114 1653 5114 2527 5115 1653 5115 2528 5115 2528 5116 1653 5116 1654 5116 2528 5117 1654 5117 2529 5117 2529 5118 1654 5118 2530 5118 2529 5119 2530 5119 2571 5119 2571 5120 2530 5120 2531 5120 2571 5121 2531 5121 2532 5121 2532 5122 2531 5122 1649 5122 2532 5123 1649 5123 2533 5123 2533 5124 1649 5124 1648 5124 2533 5125 1648 5125 2574 5125 2574 5126 1648 5126 1647 5126 2574 5127 1647 5127 2534 5127 2534 5128 1647 5128 2535 5128 2534 5129 2535 5129 2575 5129 2575 5130 2535 5130 2536 5130 2575 5131 2536 5131 2576 5131 2576 5132 2536 5132 2537 5132 2576 5133 2537 5133 2540 5133 2540 5134 2537 5134 2538 5134 2540 5135 2538 5135 2458 5135 2539 5136 2540 5136 2577 5136 2577 5137 2540 5137 2541 5137 2577 5138 2541 5138 2542 5138 2542 5139 2541 5139 2459 5139 2542 5140 2459 5140 2543 5140 2543 5141 2459 5141 2461 5141 2543 5142 2461 5142 2580 5142 2580 5143 2461 5143 2463 5143 2580 5144 2463 5144 2581 5144 2581 5145 2463 5145 2544 5145 2581 5146 2544 5146 2582 5146 2582 5147 2544 5147 2545 5147 2582 5148 2545 5148 2583 5148 2583 5149 2545 5149 2464 5149 2583 5150 2464 5150 2546 5150 2546 5151 2464 5151 2547 5151 2546 5152 2547 5152 2585 5152 2585 5153 2547 5153 2549 5153 2585 5154 2549 5154 2548 5154 2548 5155 2549 5155 2550 5155 2548 5156 2550 5156 2551 5156 2551 5157 2550 5157 2490 5157 2551 5158 2490 5158 2588 5158 2588 5159 2490 5159 2552 5159 2588 5160 2552 5160 2553 5160 2553 5161 2552 5161 2554 5161 2553 5162 2554 5162 2555 5162 2555 5163 2554 5163 2494 5163 2555 5164 2494 5164 2591 5164 2591 5165 2494 5165 2556 5165 2591 5166 2556 5166 2593 5166 2593 5167 2556 5167 2497 5167 2593 5168 2497 5168 2594 5168 2594 5169 2497 5169 2498 5169 2594 5170 2498 5170 2595 5170 2595 5171 2498 5171 2500 5171 2595 5172 2500 5172 2557 5172 2557 5173 2500 5173 2501 5173 2557 5174 2501 5174 2558 5174 2558 5175 2501 5175 2503 5175 2558 5176 2503 5176 2560 5176 2560 5177 2503 5177 2559 5177 2560 5178 2559 5178 2600 5178 2600 5179 2559 5179 2561 5179 2600 5180 2561 5180 2601 5180 2601 5181 2561 5181 2505 5181 2601 5182 2505 5182 2603 5182 2603 5183 2505 5183 2562 5183 2603 5184 2562 5184 2604 5184 2604 5185 2562 5185 2563 5185 2604 5186 2563 5186 2564 5186 2564 5187 2563 5187 2509 5187 2564 5188 2509 5188 2565 5188 2565 5189 2509 5189 2566 5189 2565 5190 2566 5190 2567 5190 2567 5191 2566 5191 2527 5191 2567 5192 2527 5192 2568 5192 2568 5193 2527 5193 2528 5193 2568 5194 2528 5194 2569 5194 2569 5195 2528 5195 2529 5195 2569 5196 2529 5196 2608 5196 2608 5197 2529 5197 2571 5197 2608 5198 2571 5198 2570 5198 2570 5199 2571 5199 2532 5199 2570 5200 2532 5200 2572 5200 2572 5201 2532 5201 2533 5201 2572 5202 2533 5202 2610 5202 2610 5203 2533 5203 2574 5203 2610 5204 2574 5204 2573 5204 2573 5205 2574 5205 2534 5205 2573 5206 2534 5206 2611 5206 2611 5207 2534 5207 2575 5207 2611 5208 2575 5208 2612 5208 2612 5209 2575 5209 2576 5209 2612 5210 2576 5210 2539 5210 2539 5211 2576 5211 2540 5211 2618 5212 2577 5212 2616 5212 2616 5213 2577 5213 2542 5213 2616 5214 2542 5214 2578 5214 2578 5215 2542 5215 2543 5215 2578 5216 2543 5216 2579 5216 2579 5217 2543 5217 2580 5217 2579 5218 2580 5218 2613 5218 2613 5219 2580 5219 2581 5219 2613 5220 2581 5220 2456 5220 2456 5221 2581 5221 2582 5221 2456 5222 2582 5222 2455 5222 2455 5223 2582 5223 2583 5223 2455 5224 2583 5224 2454 5224 2454 5225 2583 5225 2546 5225 2454 5226 2546 5226 2584 5226 2584 5227 2546 5227 2585 5227 2584 5228 2585 5228 2586 5228 2586 5229 2585 5229 2548 5229 2586 5230 2548 5230 2587 5230 2587 5231 2548 5231 2551 5231 2587 5232 2551 5232 2466 5232 2466 5233 2551 5233 2588 5233 2466 5234 2588 5234 2589 5234 2589 5235 2588 5235 2553 5235 2589 5236 2553 5236 2590 5236 2590 5237 2553 5237 2555 5237 2590 5238 2555 5238 2468 5238 2468 5239 2555 5239 2591 5239 2468 5240 2591 5240 2592 5240 2592 5241 2591 5241 2593 5241 2592 5242 2593 5242 2476 5242 2476 5243 2593 5243 2594 5243 2476 5244 2594 5244 2475 5244 2475 5245 2594 5245 2595 5245 2475 5246 2595 5246 2473 5246 2473 5247 2595 5247 2557 5247 2473 5248 2557 5248 2596 5248 2596 5249 2557 5249 2558 5249 2596 5250 2558 5250 2597 5250 2597 5251 2558 5251 2560 5251 2597 5252 2560 5252 2598 5252 2598 5253 2560 5253 2600 5253 2598 5254 2600 5254 2599 5254 2599 5255 2600 5255 2601 5255 2599 5256 2601 5256 2602 5256 2602 5257 2601 5257 2603 5257 2602 5258 2603 5258 2481 5258 2481 5259 2603 5259 2604 5259 2481 5260 2604 5260 2480 5260 2480 5261 2604 5261 2564 5261 2480 5262 2564 5262 2485 5262 2485 5263 2564 5263 2565 5263 2485 5264 2565 5264 2605 5264 2605 5265 2565 5265 2567 5265 2605 5266 2567 5266 2606 5266 2606 5267 2567 5267 2568 5267 2606 5268 2568 5268 2607 5268 2607 5269 2568 5269 2569 5269 2607 5270 2569 5270 2513 5270 2513 5271 2569 5271 2608 5271 2513 5272 2608 5272 2511 5272 2511 5273 2608 5273 2570 5273 2511 5274 2570 5274 2609 5274 2609 5275 2570 5275 2572 5275 2609 5276 2572 5276 2517 5276 2517 5277 2572 5277 2610 5277 2517 5278 2610 5278 2515 5278 2515 5279 2610 5279 2573 5279 2515 5280 2573 5280 2524 5280 2524 5281 2573 5281 2611 5281 2524 5282 2611 5282 2522 5282 2522 5283 2611 5283 2612 5283 2522 5284 2612 5284 2520 5284 2520 5285 2612 5285 2539 5285 2520 5286 2539 5286 2618 5286 2618 5287 2539 5287 2577 5287 993 5288 992 5288 2613 5288 2613 5289 992 5289 2614 5289 2613 5290 2614 5290 2579 5290 2579 5291 2614 5291 2615 5291 2579 5292 2615 5292 2578 5292 2578 5293 2615 5293 991 5293 2578 5294 991 5294 2616 5294 2616 5295 991 5295 2617 5295 2616 5296 2617 5296 2618 5296 2618 5297 2617 5297 968 5297 2618 5298 968 5298 967 5298 2644 5299 2643 5299 2642 5299 2626 5300 2619 5300 2620 5300 2622 5301 2621 5301 2623 5301 2623 5302 2621 5302 2639 5302 1060 5303 3119 5303 1061 5303 1061 5304 3119 5304 3104 5304 2622 5305 2623 5305 2624 5305 2624 5306 2623 5306 1859 5306 2624 5307 1859 5307 2625 5307 2619 5308 2626 5308 2625 5308 2625 5309 2626 5309 2627 5309 2625 5310 2627 5310 2624 5310 2628 5311 2630 5311 1853 5311 1853 5312 2630 5312 3452 5312 1853 5313 3452 5313 3587 5313 2654 5314 2629 5314 2628 5314 2628 5315 2629 5315 3458 5315 2628 5316 3458 5316 2630 5316 2652 5317 2631 5317 2655 5317 2655 5318 2631 5318 2632 5318 2655 5319 2632 5319 2633 5319 2636 5320 1857 5320 2638 5320 2638 5321 1857 5321 2634 5321 2638 5322 2634 5322 2623 5322 2623 5323 2634 5323 2635 5323 2623 5324 2635 5324 1859 5324 1063 5325 2636 5325 2637 5325 2637 5326 2636 5326 2638 5326 2637 5327 2638 5327 1059 5327 1059 5328 2638 5328 2623 5328 1059 5329 2623 5329 1060 5329 1060 5330 2623 5330 2639 5330 1060 5331 2639 5331 3119 5331 2640 5332 2641 5332 1063 5332 1063 5333 2641 5333 2644 5333 1063 5334 2644 5334 2636 5334 2636 5335 2644 5335 2642 5335 2636 5336 2642 5336 1857 5336 2643 5337 2644 5337 1858 5337 1858 5338 2644 5338 2641 5338 1858 5339 2641 5339 1854 5339 1854 5340 2641 5340 2645 5340 1854 5341 2645 5341 1855 5341 1855 5342 2645 5342 2647 5342 1855 5343 2647 5343 2646 5343 2646 5344 2647 5344 2648 5344 2646 5345 2648 5345 2649 5345 2640 5346 1068 5346 2641 5346 2641 5347 1068 5347 1065 5347 2641 5348 1065 5348 2645 5348 2645 5349 1065 5349 1064 5349 2645 5350 1064 5350 2647 5350 2647 5351 1064 5351 2650 5351 2647 5352 2650 5352 2648 5352 2648 5353 2650 5353 1071 5353 2648 5354 1071 5354 2651 5354 2651 5355 1071 5355 1070 5355 2651 5356 1070 5356 2652 5356 2652 5357 1070 5357 3478 5357 2652 5358 3478 5358 2631 5358 2649 5359 2648 5359 1856 5359 1856 5360 2648 5360 2651 5360 1856 5361 2651 5361 1852 5361 1852 5362 2651 5362 2652 5362 1852 5363 2652 5363 2653 5363 2653 5364 2652 5364 2655 5364 2653 5365 2655 5365 2654 5365 2654 5366 2655 5366 2633 5366 2654 5367 2633 5367 2629 5367 2908 5368 2656 5368 1725 5368 2660 5369 2657 5369 2658 5369 2908 5370 1725 5370 2658 5370 2658 5371 1725 5371 2659 5371 2658 5372 2659 5372 2660 5372 2893 5373 2661 5373 2660 5373 2660 5374 2661 5374 2662 5374 2660 5375 2662 5375 2657 5375 2664 5376 2663 5376 1092 5376 1092 5377 2687 5377 2664 5377 2664 5378 2687 5378 2669 5378 2664 5379 2669 5379 2665 5379 2665 5380 2669 5380 3378 5380 3380 5381 3379 5381 2670 5381 1731 5382 2668 5382 1732 5382 1732 5383 2668 5383 3380 5383 1732 5384 3380 5384 2666 5384 2666 5385 3380 5385 2670 5385 3382 5386 2667 5386 1731 5386 1731 5387 2667 5387 3381 5387 1731 5388 3381 5388 2668 5388 2674 5389 2676 5389 2687 5389 2687 5390 2676 5390 2670 5390 2687 5391 2670 5391 2669 5391 2669 5392 2670 5392 3379 5392 2669 5393 3379 5393 3378 5393 2671 5394 1729 5394 2683 5394 2683 5395 1729 5395 2672 5395 2683 5396 2672 5396 2673 5396 2673 5397 2672 5397 1727 5397 2673 5398 1727 5398 2674 5398 2674 5399 1727 5399 2675 5399 2674 5400 2675 5400 2676 5400 2689 5401 2690 5401 2678 5401 2678 5402 2690 5402 2677 5402 2678 5403 2677 5403 2682 5403 2682 5404 2677 5404 2679 5404 2682 5405 2679 5405 2671 5405 2671 5406 2679 5406 1730 5406 2671 5407 1730 5407 1729 5407 1020 5408 2893 5408 2680 5408 2680 5409 2893 5409 2660 5409 2680 5410 2660 5410 1017 5410 1017 5411 2660 5411 2689 5411 1017 5412 2689 5412 1089 5412 1089 5413 2689 5413 2678 5413 1089 5414 2678 5414 2681 5414 2681 5415 2678 5415 2682 5415 2681 5416 2682 5416 1090 5416 1090 5417 2682 5417 2671 5417 1090 5418 2671 5418 1087 5418 1087 5419 2671 5419 2683 5419 1087 5420 2683 5420 2684 5420 2684 5421 2683 5421 2673 5421 2684 5422 2673 5422 2685 5422 2685 5423 2673 5423 2674 5423 2685 5424 2674 5424 2686 5424 2686 5425 2674 5425 2687 5425 2686 5426 2687 5426 2688 5426 2688 5427 2687 5427 1092 5427 2659 5428 1739 5428 2660 5428 2660 5429 1739 5429 1741 5429 2660 5430 1741 5430 2689 5430 2689 5431 1741 5431 1726 5431 2689 5432 1726 5432 2690 5432 936 5433 2691 5433 632 5433 632 5434 2691 5434 937 5434 632 5435 937 5435 934 5435 2696 5436 930 5436 2692 5436 2696 5437 2692 5437 1305 5437 1305 5438 2692 5438 2693 5438 1305 5439 2693 5439 2694 5439 2694 5440 2695 5440 1305 5440 1305 5441 2695 5441 931 5441 1305 5442 931 5442 632 5442 632 5443 931 5443 932 5443 632 5444 932 5444 936 5444 2697 5445 928 5445 2696 5445 2696 5446 928 5446 926 5446 2696 5447 926 5447 930 5447 2696 5448 1304 5448 2697 5448 2697 5449 1304 5449 2699 5449 2697 5450 2699 5450 2698 5450 2698 5451 2699 5451 1306 5451 2698 5452 1306 5452 2700 5452 2700 5453 1306 5453 1301 5453 2700 5454 1301 5454 2701 5454 913 5455 1302 5455 2702 5455 913 5456 2702 5456 2703 5456 2703 5457 2702 5457 2704 5457 2703 5458 2704 5458 909 5458 909 5459 2704 5459 2707 5459 909 5460 2707 5460 2705 5460 2708 5461 2706 5461 921 5461 2708 5462 921 5462 2707 5462 2707 5463 921 5463 920 5463 2707 5464 920 5464 2705 5464 2715 5465 918 5465 2712 5465 2712 5466 918 5466 924 5466 2712 5467 924 5467 2708 5467 2708 5468 924 5468 925 5468 2708 5469 925 5469 2706 5469 916 5470 2711 5470 2709 5470 2709 5471 2711 5471 1299 5471 916 5472 2710 5472 2711 5472 2711 5473 2710 5473 2713 5473 2711 5474 2713 5474 2712 5474 2712 5475 2713 5475 2714 5475 2712 5476 2714 5476 2715 5476 2719 5477 2213 5477 2717 5477 2716 5478 2718 5478 2717 5478 2717 5479 2718 5479 1116 5479 2717 5480 1116 5480 2719 5480 2719 5481 1116 5481 2720 5481 2719 5482 2720 5482 2214 5482 2763 5483 2721 5483 2722 5483 2722 5484 2721 5484 2726 5484 2722 5485 2726 5485 2765 5485 2765 5486 2726 5486 2723 5486 2765 5487 2723 5487 2766 5487 2766 5488 2723 5488 2724 5488 2766 5489 2724 5489 2211 5489 2213 5490 2724 5490 2717 5490 2717 5491 2724 5491 2723 5491 2717 5492 2723 5492 2716 5492 2716 5493 2723 5493 2726 5493 2716 5494 2726 5494 2725 5494 2725 5495 2726 5495 2721 5495 2172 5496 2727 5496 2755 5496 2753 5497 2728 5497 2751 5497 2751 5498 2728 5498 2763 5498 2887 5499 2888 5499 2745 5499 2729 5500 2887 5500 2758 5500 2844 5501 2729 5501 2731 5501 2768 5502 2844 5502 2730 5502 2844 5503 2731 5503 2730 5503 2730 5504 2731 5504 2732 5504 2730 5505 2732 5505 2733 5505 2733 5506 2732 5506 2759 5506 2733 5507 2759 5507 2735 5507 2735 5508 2759 5508 2761 5508 2735 5509 2761 5509 2743 5509 2768 5510 2730 5510 2740 5510 2740 5511 2730 5511 2733 5511 2740 5512 2733 5512 2734 5512 2734 5513 2733 5513 2735 5513 2734 5514 2735 5514 2736 5514 2736 5515 2735 5515 2743 5515 2736 5516 2743 5516 2738 5516 2742 5517 2174 5517 2738 5517 2738 5518 2174 5518 2737 5518 2738 5519 2737 5519 2736 5519 2736 5520 2737 5520 2173 5520 2736 5521 2173 5521 2734 5521 2734 5522 2173 5522 2739 5522 2734 5523 2739 5523 2740 5523 2740 5524 2739 5524 2741 5524 2740 5525 2741 5525 2768 5525 2727 5526 2742 5526 2755 5526 2755 5527 2742 5527 2738 5527 2755 5528 2738 5528 2756 5528 2756 5529 2738 5529 2743 5529 2756 5530 2743 5530 2744 5530 2744 5531 2743 5531 2761 5531 2887 5532 2745 5532 2758 5532 2758 5533 2745 5533 2746 5533 2758 5534 2746 5534 2747 5534 2747 5535 2746 5535 2749 5535 2747 5536 2749 5536 2748 5536 2748 5537 2749 5537 1685 5537 2748 5538 1685 5538 2760 5538 2760 5539 1685 5539 2750 5539 2760 5540 2750 5540 2762 5540 2762 5541 2750 5541 2752 5541 2762 5542 2752 5542 2751 5542 2751 5543 2752 5543 1104 5543 2751 5544 1104 5544 2753 5544 2767 5545 2172 5545 2754 5545 2754 5546 2172 5546 2755 5546 2754 5547 2755 5547 2764 5547 2764 5548 2755 5548 2756 5548 2764 5549 2756 5549 2757 5549 2757 5550 2756 5550 2744 5550 2729 5551 2758 5551 2731 5551 2731 5552 2758 5552 2747 5552 2731 5553 2747 5553 2732 5553 2732 5554 2747 5554 2748 5554 2732 5555 2748 5555 2759 5555 2759 5556 2748 5556 2760 5556 2759 5557 2760 5557 2761 5557 2761 5558 2760 5558 2762 5558 2761 5559 2762 5559 2744 5559 2744 5560 2762 5560 2751 5560 2744 5561 2751 5561 2757 5561 2757 5562 2751 5562 2763 5562 2757 5563 2763 5563 2764 5563 2764 5564 2763 5564 2722 5564 2764 5565 2722 5565 2754 5565 2754 5566 2722 5566 2765 5566 2754 5567 2765 5567 2766 5567 2766 5568 2211 5568 2754 5568 2754 5569 2211 5569 2171 5569 2754 5570 2171 5570 2767 5570 2768 5571 2741 5571 2770 5571 2768 5572 2770 5572 2769 5572 2770 5573 1749 5573 2769 5573 2769 5574 1749 5574 1750 5574 2769 5575 1750 5575 2771 5575 1750 5576 2772 5576 2771 5576 2771 5577 2772 5577 2773 5577 2771 5578 2773 5578 2774 5578 2773 5579 1753 5579 2774 5579 2774 5580 1753 5580 2775 5580 2774 5581 2775 5581 2825 5581 2775 5582 1755 5582 2825 5582 2825 5583 1755 5583 1717 5583 2825 5584 1717 5584 2822 5584 1717 5585 2776 5585 2822 5585 2822 5586 2776 5586 1759 5586 2822 5587 1759 5587 2821 5587 1759 5588 2777 5588 2821 5588 2821 5589 2777 5589 2778 5589 2821 5590 2778 5590 2780 5590 2778 5591 2779 5591 2780 5591 2780 5592 2779 5592 1716 5592 2780 5593 1716 5593 2781 5593 1716 5594 1771 5594 2781 5594 2781 5595 1771 5595 2783 5595 2781 5596 2783 5596 2782 5596 2783 5597 1715 5597 2782 5597 2782 5598 1715 5598 2784 5598 2782 5599 2784 5599 2817 5599 2784 5600 2785 5600 2817 5600 2817 5601 2785 5601 1779 5601 2817 5602 1779 5602 2815 5602 1779 5603 1785 5603 2815 5603 2815 5604 1785 5604 1713 5604 2815 5605 1713 5605 2812 5605 1713 5606 1712 5606 2812 5606 2812 5607 1712 5607 2786 5607 2812 5608 2786 5608 2811 5608 2786 5609 2787 5609 2811 5609 2811 5610 2787 5610 2788 5610 2811 5611 2788 5611 2789 5611 2788 5612 2790 5612 2789 5612 2789 5613 2790 5613 2791 5613 2789 5614 2791 5614 2809 5614 2795 5615 2797 5615 2792 5615 2791 5616 1708 5616 2809 5616 2809 5617 1708 5617 1797 5617 2809 5618 1797 5618 2792 5618 2792 5619 1797 5619 2793 5619 2792 5620 2793 5620 2795 5620 2802 5621 2794 5621 2798 5621 2795 5622 2796 5622 2797 5622 2797 5623 2796 5623 2799 5623 2797 5624 2799 5624 2798 5624 2798 5625 2799 5625 2800 5625 2798 5626 2800 5626 2802 5626 2656 5627 2801 5627 1809 5627 1809 5628 2801 5628 2804 5628 2802 5629 1804 5629 2794 5629 2794 5630 1804 5630 2803 5630 2794 5631 2803 5631 2804 5631 2804 5632 2803 5632 2805 5632 2804 5633 2805 5633 1809 5633 2801 5634 2910 5634 2804 5634 2804 5635 2910 5635 2806 5635 2804 5636 2806 5636 2794 5636 2794 5637 2806 5637 2830 5637 2794 5638 2830 5638 2798 5638 2798 5639 2830 5639 2807 5639 2798 5640 2807 5640 2797 5640 2797 5641 2807 5641 2831 5641 2797 5642 2831 5642 2792 5642 2792 5643 2831 5643 2808 5643 2792 5644 2808 5644 2809 5644 2809 5645 2808 5645 2810 5645 2809 5646 2810 5646 2789 5646 2789 5647 2810 5647 2833 5647 2789 5648 2833 5648 2811 5648 2811 5649 2833 5649 2813 5649 2811 5650 2813 5650 2812 5650 2812 5651 2813 5651 2814 5651 2812 5652 2814 5652 2815 5652 2815 5653 2814 5653 2816 5653 2815 5654 2816 5654 2817 5654 2817 5655 2816 5655 2818 5655 2817 5656 2818 5656 2782 5656 2782 5657 2818 5657 2819 5657 2782 5658 2819 5658 2781 5658 2781 5659 2819 5659 2820 5659 2781 5660 2820 5660 2780 5660 2780 5661 2820 5661 2839 5661 2780 5662 2839 5662 2821 5662 2821 5663 2839 5663 2823 5663 2821 5664 2823 5664 2822 5664 2822 5665 2823 5665 2824 5665 2822 5666 2824 5666 2825 5666 2825 5667 2824 5667 2826 5667 2825 5668 2826 5668 2774 5668 2774 5669 2826 5669 2841 5669 2774 5670 2841 5670 2771 5670 2771 5671 2841 5671 2827 5671 2771 5672 2827 5672 2769 5672 2769 5673 2827 5673 2843 5673 2769 5674 2843 5674 2768 5674 2768 5675 2843 5675 2844 5675 2910 5676 2912 5676 2806 5676 2806 5677 2912 5677 2828 5677 2806 5678 2828 5678 2830 5678 2830 5679 2828 5679 2829 5679 2830 5680 2829 5680 2807 5680 2807 5681 2829 5681 2832 5681 2807 5682 2832 5682 2831 5682 2831 5683 2832 5683 2848 5683 2831 5684 2848 5684 2808 5684 2808 5685 2848 5685 2850 5685 2808 5686 2850 5686 2810 5686 2810 5687 2850 5687 2834 5687 2810 5688 2834 5688 2833 5688 2833 5689 2834 5689 2835 5689 2833 5690 2835 5690 2813 5690 2813 5691 2835 5691 2836 5691 2813 5692 2836 5692 2814 5692 2814 5693 2836 5693 2837 5693 2814 5694 2837 5694 2816 5694 2816 5695 2837 5695 2853 5695 2816 5696 2853 5696 2818 5696 2818 5697 2853 5697 2838 5697 2818 5698 2838 5698 2819 5698 2819 5699 2838 5699 2855 5699 2819 5700 2855 5700 2820 5700 2820 5701 2855 5701 2857 5701 2820 5702 2857 5702 2839 5702 2839 5703 2857 5703 2858 5703 2839 5704 2858 5704 2823 5704 2823 5705 2858 5705 2859 5705 2823 5706 2859 5706 2824 5706 2824 5707 2859 5707 2840 5707 2824 5708 2840 5708 2826 5708 2826 5709 2840 5709 2861 5709 2826 5710 2861 5710 2841 5710 2841 5711 2861 5711 2842 5711 2841 5712 2842 5712 2827 5712 2827 5713 2842 5713 2862 5713 2827 5714 2862 5714 2843 5714 2843 5715 2862 5715 2863 5715 2843 5716 2863 5716 2844 5716 2844 5717 2863 5717 2729 5717 2912 5718 2845 5718 2828 5718 2828 5719 2845 5719 2846 5719 2828 5720 2846 5720 2829 5720 2829 5721 2846 5721 2847 5721 2829 5722 2847 5722 2832 5722 2832 5723 2847 5723 2865 5723 2832 5724 2865 5724 2848 5724 2848 5725 2865 5725 2849 5725 2848 5726 2849 5726 2850 5726 2850 5727 2849 5727 2868 5727 2850 5728 2868 5728 2834 5728 2834 5729 2868 5729 2851 5729 2834 5730 2851 5730 2835 5730 2835 5731 2851 5731 2870 5731 2835 5732 2870 5732 2836 5732 2836 5733 2870 5733 2872 5733 2836 5734 2872 5734 2837 5734 2837 5735 2872 5735 2852 5735 2837 5736 2852 5736 2853 5736 2853 5737 2852 5737 2854 5737 2853 5738 2854 5738 2838 5738 2838 5739 2854 5739 2874 5739 2838 5740 2874 5740 2855 5740 2855 5741 2874 5741 2875 5741 2855 5742 2875 5742 2857 5742 2857 5743 2875 5743 2856 5743 2857 5744 2856 5744 2858 5744 2858 5745 2856 5745 2877 5745 2858 5746 2877 5746 2859 5746 2859 5747 2877 5747 2860 5747 2859 5748 2860 5748 2840 5748 2840 5749 2860 5749 2878 5749 2840 5750 2878 5750 2861 5750 2861 5751 2878 5751 2881 5751 2861 5752 2881 5752 2842 5752 2842 5753 2881 5753 2882 5753 2842 5754 2882 5754 2862 5754 2862 5755 2882 5755 2884 5755 2862 5756 2884 5756 2863 5756 2863 5757 2884 5757 2886 5757 2863 5758 2886 5758 2729 5758 2729 5759 2886 5759 2887 5759 2845 5760 1689 5760 2846 5760 2846 5761 1689 5761 1690 5761 2846 5762 1690 5762 2847 5762 2847 5763 1690 5763 2864 5763 2847 5764 2864 5764 2865 5764 2865 5765 2864 5765 2866 5765 2865 5766 2866 5766 2849 5766 2849 5767 2866 5767 2867 5767 2849 5768 2867 5768 2868 5768 2868 5769 2867 5769 2869 5769 2868 5770 2869 5770 2851 5770 2851 5771 2869 5771 1704 5771 2851 5772 1704 5772 2870 5772 2870 5773 1704 5773 2871 5773 2870 5774 2871 5774 2872 5774 2872 5775 2871 5775 1702 5775 2872 5776 1702 5776 2852 5776 2852 5777 1702 5777 2873 5777 2852 5778 2873 5778 2854 5778 2854 5779 2873 5779 1695 5779 2854 5780 1695 5780 2874 5780 2874 5781 1695 5781 1694 5781 2874 5782 1694 5782 2875 5782 2875 5783 1694 5783 2876 5783 2875 5784 2876 5784 2856 5784 2856 5785 2876 5785 1684 5785 2856 5786 1684 5786 2877 5786 2877 5787 1684 5787 1707 5787 2877 5788 1707 5788 2860 5788 2860 5789 1707 5789 2879 5789 2860 5790 2879 5790 2878 5790 2878 5791 2879 5791 2880 5791 2878 5792 2880 5792 2881 5792 2881 5793 2880 5793 1706 5793 2881 5794 1706 5794 2882 5794 2882 5795 1706 5795 2883 5795 2882 5796 2883 5796 2884 5796 2884 5797 2883 5797 2885 5797 2884 5798 2885 5798 2886 5798 2886 5799 2885 5799 1688 5799 2886 5800 1688 5800 2887 5800 2887 5801 1688 5801 2888 5801 2893 5802 1020 5802 2894 5802 2894 5803 1020 5803 2889 5803 2894 5804 2889 5804 2890 5804 2890 5805 2889 5805 2891 5805 2890 5806 2891 5806 2892 5806 2892 5807 2891 5807 2913 5807 2892 5808 2913 5808 2896 5808 2896 5809 2913 5809 2914 5809 2896 5810 2914 5810 2897 5810 2897 5811 2914 5811 2915 5811 2661 5812 2893 5812 2901 5812 2901 5813 2893 5813 2894 5813 2901 5814 2894 5814 2895 5814 2895 5815 2894 5815 2890 5815 2895 5816 2890 5816 2900 5816 2900 5817 2890 5817 2892 5817 2900 5818 2892 5818 2899 5818 2899 5819 2892 5819 2896 5819 2899 5820 2896 5820 2898 5820 2898 5821 2896 5821 2897 5821 2898 5822 1692 5822 2899 5822 2899 5823 1692 5823 2907 5823 2899 5824 2907 5824 2900 5824 2900 5825 2907 5825 2905 5825 2900 5826 2905 5826 2895 5826 2895 5827 2905 5827 2903 5827 2895 5828 2903 5828 2901 5828 2901 5829 2903 5829 2902 5829 2901 5830 2902 5830 2661 5830 2658 5831 2657 5831 2902 5831 2902 5832 2657 5832 2662 5832 2902 5833 2662 5833 2661 5833 2908 5834 2658 5834 2909 5834 2909 5835 2658 5835 2902 5835 2909 5836 2902 5836 2911 5836 2911 5837 2902 5837 2903 5837 2911 5838 2903 5838 2904 5838 2904 5839 2903 5839 2905 5839 2904 5840 2905 5840 2906 5840 2906 5841 2905 5841 2907 5841 2906 5842 2907 5842 1691 5842 1691 5843 2907 5843 1692 5843 2656 5844 2908 5844 2801 5844 2801 5845 2908 5845 2909 5845 2801 5846 2909 5846 2910 5846 2910 5847 2909 5847 2911 5847 2910 5848 2911 5848 2912 5848 2912 5849 2911 5849 2904 5849 2912 5850 2904 5850 2845 5850 2845 5851 2904 5851 2906 5851 2845 5852 2906 5852 1689 5852 1689 5853 2906 5853 1691 5853 1020 5854 1019 5854 2916 5854 1020 5855 2916 5855 2889 5855 2889 5856 2916 5856 2917 5856 2889 5857 2917 5857 2891 5857 2891 5858 2917 5858 2918 5858 2891 5859 2918 5859 2913 5859 2913 5860 2918 5860 2959 5860 2913 5861 2959 5861 2914 5861 2914 5862 2959 5862 1948 5862 2914 5863 1948 5863 2915 5863 2917 5864 2916 5864 2932 5864 2918 5865 2917 5865 2936 5865 2959 5866 2918 5866 2960 5866 2919 5867 2924 5867 2920 5867 2920 5868 2924 5868 1951 5868 2920 5869 1951 5869 2962 5869 2962 5870 1951 5870 1950 5870 2962 5871 1950 5871 2921 5871 2921 5872 1950 5872 1949 5872 2921 5873 1949 5873 2922 5873 2922 5874 1949 5874 1948 5874 2922 5875 1948 5875 2959 5875 2935 5876 2923 5876 2919 5876 2919 5877 2923 5877 1952 5877 2919 5878 1952 5878 2924 5878 2925 5879 2942 5879 1014 5879 1014 5880 2942 5880 2926 5880 1014 5881 2926 5881 2927 5881 2927 5882 2926 5882 2940 5882 2927 5883 2940 5883 2928 5883 2928 5884 2940 5884 2930 5884 2928 5885 2930 5885 2929 5885 2929 5886 2930 5886 2931 5886 2929 5887 2931 5887 1016 5887 1016 5888 2931 5888 2932 5888 1016 5889 2932 5889 1018 5889 1018 5890 2932 5890 2916 5890 1018 5891 2916 5891 1019 5891 2952 5892 2933 5892 2925 5892 2925 5893 2933 5893 2934 5893 2925 5894 2934 5894 2942 5894 2919 5895 2964 5895 2935 5895 2935 5896 2964 5896 2966 5896 2935 5897 2966 5897 1954 5897 1954 5898 2966 5898 2972 5898 1954 5899 2972 5899 2971 5899 2917 5900 2932 5900 2936 5900 2936 5901 2932 5901 2931 5901 2936 5902 2931 5902 2937 5902 2937 5903 2931 5903 2930 5903 2937 5904 2930 5904 2938 5904 2938 5905 2930 5905 2940 5905 2938 5906 2940 5906 2939 5906 2939 5907 2940 5907 2926 5907 2939 5908 2926 5908 2941 5908 2941 5909 2926 5909 2942 5909 2941 5910 2942 5910 2943 5910 2943 5911 2942 5911 2934 5911 2943 5912 2934 5912 2944 5912 2944 5913 2934 5913 2933 5913 2944 5914 2933 5914 2951 5914 2951 5915 2933 5915 2945 5915 2951 5916 2945 5916 2946 5916 2946 5917 2945 5917 2947 5917 2946 5918 2947 5918 2955 5918 2918 5919 2936 5919 2960 5919 2960 5920 2936 5920 2937 5920 2960 5921 2937 5921 2948 5921 2948 5922 2937 5922 2938 5922 2948 5923 2938 5923 2961 5923 2961 5924 2938 5924 2939 5924 2961 5925 2939 5925 2963 5925 2963 5926 2939 5926 2941 5926 2963 5927 2941 5927 2949 5927 2949 5928 2941 5928 2943 5928 2949 5929 2943 5929 2950 5929 2950 5930 2943 5930 2944 5930 2950 5931 2944 5931 2965 5931 2965 5932 2944 5932 2951 5932 2965 5933 2951 5933 2967 5933 2967 5934 2951 5934 2946 5934 2967 5935 2946 5935 2968 5935 2968 5936 2946 5936 2955 5936 2968 5937 2955 5937 2958 5937 2952 5938 1023 5938 2933 5938 2933 5939 1023 5939 1024 5939 2933 5940 1024 5940 2945 5940 2945 5941 1024 5941 2953 5941 2945 5942 2953 5942 2947 5942 2947 5943 2953 5943 2954 5943 2954 5944 2976 5944 2947 5944 2947 5945 2976 5945 2956 5945 2947 5946 2956 5946 2955 5946 2955 5947 2956 5947 3022 5947 2955 5948 3022 5948 2958 5948 2958 5949 3022 5949 2957 5949 2958 5950 2957 5950 2970 5950 2959 5951 2960 5951 2922 5951 2922 5952 2960 5952 2948 5952 2922 5953 2948 5953 2921 5953 2921 5954 2948 5954 2961 5954 2921 5955 2961 5955 2962 5955 2962 5956 2961 5956 2963 5956 2962 5957 2963 5957 2920 5957 2920 5958 2963 5958 2949 5958 2920 5959 2949 5959 2919 5959 2919 5960 2949 5960 2950 5960 2919 5961 2950 5961 2964 5961 2964 5962 2950 5962 2965 5962 2964 5963 2965 5963 2966 5963 2966 5964 2965 5964 2967 5964 2966 5965 2967 5965 2972 5965 2972 5966 2967 5966 2968 5966 2972 5967 2968 5967 2974 5967 2974 5968 2968 5968 2958 5968 2974 5969 2958 5969 2969 5969 2969 5970 2958 5970 2970 5970 2969 5971 2970 5971 2978 5971 2971 5972 2972 5972 2973 5972 2973 5973 2972 5973 2974 5973 2973 5974 2974 5974 2975 5974 2975 5975 2974 5975 2969 5975 2975 5976 2969 5976 1947 5976 1947 5977 2969 5977 2978 5977 1947 5978 2978 5978 1255 5978 2954 5979 1038 5979 2976 5979 2976 5980 1038 5980 2980 5980 2976 5981 2980 5981 2956 5981 2978 5982 2970 5982 3021 5982 3021 5983 2970 5983 2957 5983 3021 5984 2957 5984 3022 5984 2977 5985 1255 5985 2978 5985 1038 5986 2979 5986 2980 5986 2980 5987 2979 5987 1035 5987 2980 5988 1035 5988 3020 5988 3020 5989 1035 5989 1034 5989 3020 5990 1034 5990 3019 5990 3019 5991 1034 5991 1033 5991 3019 5992 1033 5992 3016 5992 1033 5993 2981 5993 3016 5993 3016 5994 2981 5994 1029 5994 3016 5995 1029 5995 3015 5995 1029 5996 1028 5996 3015 5996 3015 5997 1028 5997 1027 5997 3015 5998 1027 5998 3014 5998 3014 5999 1027 5999 2982 5999 3014 6000 2982 6000 3012 6000 3012 6001 2982 6001 1025 6001 3012 6002 1025 6002 2984 6002 1025 6003 2983 6003 2984 6003 2984 6004 2983 6004 2985 6004 2984 6005 2985 6005 3008 6005 3008 6006 2985 6006 2987 6006 3008 6007 2987 6007 2986 6007 2986 6008 2987 6008 1040 6008 2986 6009 1040 6009 2989 6009 2989 6010 1040 6010 2988 6010 2988 6011 1043 6011 2989 6011 2989 6012 1043 6012 2991 6012 2989 6013 2991 6013 2990 6013 2990 6014 2991 6014 3005 6014 2991 6015 2992 6015 3005 6015 3005 6016 2992 6016 1046 6016 3005 6017 1046 6017 2995 6017 2993 6018 2994 6018 2995 6018 2995 6019 2994 6019 3003 6019 2995 6020 3003 6020 3005 6020 2993 6021 2996 6021 2994 6021 2994 6022 2996 6022 2997 6022 2994 6023 2997 6023 2998 6023 2998 6024 2997 6024 3002 6024 3002 6025 2997 6025 2999 6025 3002 6026 2999 6026 3000 6026 3000 6027 3001 6027 3043 6027 3000 6028 3043 6028 3002 6028 3002 6029 3043 6029 3046 6029 3002 6030 3046 6030 3045 6030 3045 6031 3024 6031 3002 6031 3002 6032 3024 6032 3036 6032 3002 6033 3036 6033 2998 6033 2998 6034 3036 6034 3035 6034 2998 6035 3035 6035 2994 6035 2994 6036 3035 6036 3004 6036 2994 6037 3004 6037 3003 6037 3003 6038 3004 6038 3006 6038 3003 6039 3006 6039 3005 6039 3005 6040 3006 6040 3007 6040 3005 6041 3007 6041 2990 6041 2990 6042 3007 6042 3031 6042 2990 6043 3031 6043 2989 6043 2989 6044 3031 6044 3029 6044 2989 6045 3029 6045 2986 6045 2986 6046 3029 6046 3028 6046 2986 6047 3028 6047 3008 6047 3008 6048 3028 6048 3009 6048 3008 6049 3009 6049 2984 6049 2984 6050 3009 6050 3010 6050 2984 6051 3010 6051 3012 6051 3012 6052 3010 6052 3011 6052 3012 6053 3011 6053 3014 6053 3014 6054 3011 6054 3013 6054 3014 6055 3013 6055 3015 6055 3015 6056 3013 6056 3017 6056 3015 6057 3017 6057 3016 6057 3016 6058 3017 6058 3018 6058 3016 6059 3018 6059 3019 6059 3019 6060 3018 6060 3025 6060 3019 6061 3025 6061 3020 6061 3020 6062 3025 6062 3021 6062 3020 6063 3021 6063 2980 6063 2980 6064 3021 6064 3022 6064 2980 6065 3022 6065 2956 6065 3045 6066 3044 6066 3024 6066 3024 6067 3044 6067 3023 6067 3024 6068 3023 6068 3048 6068 2978 6069 3021 6069 2977 6069 2977 6070 3021 6070 3025 6070 2977 6071 3025 6071 1267 6071 1267 6072 3025 6072 3018 6072 1267 6073 3018 6073 1268 6073 1268 6074 3018 6074 3017 6074 1268 6075 3017 6075 1270 6075 1270 6076 3017 6076 3013 6076 1270 6077 3013 6077 3026 6077 3026 6078 3013 6078 3011 6078 3026 6079 3011 6079 1265 6079 1265 6080 3011 6080 3010 6080 1265 6081 3010 6081 3027 6081 3027 6082 3010 6082 3009 6082 3027 6083 3009 6083 1266 6083 1266 6084 3009 6084 3028 6084 1266 6085 3028 6085 3030 6085 3030 6086 3028 6086 3029 6086 3030 6087 3029 6087 1258 6087 1258 6088 3029 6088 3031 6088 1258 6089 3031 6089 1260 6089 1260 6090 3031 6090 3007 6090 1260 6091 3007 6091 3032 6091 3032 6092 3007 6092 3006 6092 3032 6093 3006 6093 3033 6093 3033 6094 3006 6094 3004 6094 3033 6095 3004 6095 3034 6095 3034 6096 3004 6096 3035 6096 3034 6097 3035 6097 1263 6097 1263 6098 3035 6098 3036 6098 1263 6099 3036 6099 1264 6099 1264 6100 3036 6100 3024 6100 1264 6101 3024 6101 1261 6101 1261 6102 3024 6102 3048 6102 1261 6103 3048 6103 3037 6103 3038 6104 2000 6104 3074 6104 3039 6105 3040 6105 3057 6105 3041 6106 2003 6106 3058 6106 3050 6107 3062 6107 3053 6107 3055 6108 3043 6108 3042 6108 3042 6109 3043 6109 3001 6109 3049 6110 3044 6110 3054 6110 3054 6111 3044 6111 3045 6111 3054 6112 3045 6112 3055 6112 3055 6113 3045 6113 3046 6113 3055 6114 3046 6114 3043 6114 3047 6115 3037 6115 3051 6115 3051 6116 3037 6116 3048 6116 3051 6117 3048 6117 3049 6117 3049 6118 3048 6118 3023 6118 3049 6119 3023 6119 3044 6119 3050 6120 3053 6120 3056 6120 2003 6121 3047 6121 3058 6121 3058 6122 3047 6122 3051 6122 3058 6123 3051 6123 3052 6123 3052 6124 3051 6124 3049 6124 3052 6125 3049 6125 3060 6125 3060 6126 3049 6126 3054 6126 3060 6127 3054 6127 3053 6127 3053 6128 3054 6128 3055 6128 3053 6129 3055 6129 3056 6129 3056 6130 3055 6130 3042 6130 3040 6131 3041 6131 3057 6131 3057 6132 3041 6132 3058 6132 3057 6133 3058 6133 3059 6133 3059 6134 3058 6134 3052 6134 3059 6135 3052 6135 3066 6135 3066 6136 3052 6136 3060 6136 3066 6137 3060 6137 3061 6137 3061 6138 3060 6138 3053 6138 3061 6139 3053 6139 3069 6139 3069 6140 3053 6140 3062 6140 3063 6141 3039 6141 3064 6141 3064 6142 3039 6142 3057 6142 3064 6143 3057 6143 3072 6143 3072 6144 3057 6144 3059 6144 3072 6145 3059 6145 3065 6145 3065 6146 3059 6146 3066 6146 3065 6147 3066 6147 3067 6147 3067 6148 3066 6148 3061 6148 3067 6149 3061 6149 3068 6149 3068 6150 3061 6150 3069 6150 3070 6151 3063 6151 3071 6151 3071 6152 3063 6152 3064 6152 3071 6153 3064 6153 3075 6153 3075 6154 3064 6154 3072 6154 3075 6155 3072 6155 3076 6155 3076 6156 3072 6156 3065 6156 3076 6157 3065 6157 3073 6157 3073 6158 3065 6158 3067 6158 3073 6159 3067 6159 3077 6159 3077 6160 3067 6160 3068 6160 2000 6161 3070 6161 3074 6161 3074 6162 3070 6162 3071 6162 3074 6163 3071 6163 3080 6163 3080 6164 3071 6164 3075 6164 3080 6165 3075 6165 3083 6165 3083 6166 3075 6166 3076 6166 3083 6167 3076 6167 3084 6167 3084 6168 3076 6168 3073 6168 3084 6169 3073 6169 1054 6169 1054 6170 3073 6170 3077 6170 3086 6171 3038 6171 3078 6171 3078 6172 3038 6172 3074 6172 3078 6173 3074 6173 3079 6173 3079 6174 3074 6174 3080 6174 3079 6175 3080 6175 3081 6175 3081 6176 3080 6176 3083 6176 3081 6177 3083 6177 3082 6177 3082 6178 3083 6178 3084 6178 3082 6179 3084 6179 1053 6179 1053 6180 3084 6180 1054 6180 1999 6181 3086 6181 3085 6181 3085 6182 3086 6182 3078 6182 3085 6183 3078 6183 3089 6183 3089 6184 3078 6184 3079 6184 3089 6185 3079 6185 3091 6185 3091 6186 3079 6186 3081 6186 3091 6187 3081 6187 3092 6187 3092 6188 3081 6188 3082 6188 3092 6189 3082 6189 3093 6189 3093 6190 3082 6190 1053 6190 3094 6191 1999 6191 3087 6191 3087 6192 1999 6192 3085 6192 3087 6193 3085 6193 3095 6193 3095 6194 3085 6194 3089 6194 3095 6195 3089 6195 3088 6195 3088 6196 3089 6196 3091 6196 3088 6197 3091 6197 3090 6197 3090 6198 3091 6198 3092 6198 3090 6199 3092 6199 1051 6199 1051 6200 3092 6200 3093 6200 1998 6201 3094 6201 3097 6201 3097 6202 3094 6202 3087 6202 3097 6203 3087 6203 3099 6203 3099 6204 3087 6204 3095 6204 3099 6205 3095 6205 3101 6205 3101 6206 3095 6206 3088 6206 3101 6207 3088 6207 3102 6207 3102 6208 3088 6208 3090 6208 3102 6209 3090 6209 3096 6209 3096 6210 3090 6210 1051 6210 3105 6211 1998 6211 3097 6211 3105 6212 3097 6212 3098 6212 3098 6213 3097 6213 3099 6213 3098 6214 3099 6214 3100 6214 3100 6215 3099 6215 3101 6215 3100 6216 3101 6216 3106 6216 3106 6217 3101 6217 3102 6217 3106 6218 3102 6218 3103 6218 3103 6219 3102 6219 3096 6219 3103 6220 3096 6220 3104 6220 2626 6221 2620 6221 3128 6221 2624 6222 2627 6222 3121 6222 3107 6223 3105 6223 3109 6223 3109 6224 3105 6224 3098 6224 3109 6225 3098 6225 3111 6225 3111 6226 3098 6226 3100 6226 3111 6227 3100 6227 3112 6227 3112 6228 3100 6228 3106 6228 3112 6229 3106 6229 3118 6229 3118 6230 3106 6230 3103 6230 1669 6231 3107 6231 3108 6231 3108 6232 3107 6232 3109 6232 3108 6233 3109 6233 3110 6233 3110 6234 3109 6234 3111 6234 3110 6235 3111 6235 3113 6235 3113 6236 3111 6236 3112 6236 3113 6237 3112 6237 3117 6237 3117 6238 3112 6238 3118 6238 1670 6239 1669 6239 3114 6239 3114 6240 1669 6240 3108 6240 3114 6241 3108 6241 3115 6241 3115 6242 3108 6242 3110 6242 3115 6243 3110 6243 3116 6243 3116 6244 3110 6244 3113 6244 3116 6245 3113 6245 3122 6245 3122 6246 3113 6246 3117 6246 2622 6247 3122 6247 2621 6247 2621 6248 3122 6248 3117 6248 2621 6249 3117 6249 2639 6249 2639 6250 3117 6250 3118 6250 2639 6251 3118 6251 3119 6251 3119 6252 3118 6252 3103 6252 3119 6253 3103 6253 3104 6253 3123 6254 1670 6254 3125 6254 3125 6255 1670 6255 3114 6255 3125 6256 3114 6256 3120 6256 3120 6257 3114 6257 3115 6257 3120 6258 3115 6258 3127 6258 3127 6259 3115 6259 3116 6259 3127 6260 3116 6260 3121 6260 3121 6261 3116 6261 3122 6261 3121 6262 3122 6262 2624 6262 2624 6263 3122 6263 2622 6263 3136 6264 3123 6264 3124 6264 3124 6265 3123 6265 3125 6265 3124 6266 3125 6266 3250 6266 3250 6267 3125 6267 3120 6267 3250 6268 3120 6268 3126 6268 3126 6269 3120 6269 3127 6269 3126 6270 3127 6270 3128 6270 3128 6271 3127 6271 3121 6271 3128 6272 3121 6272 2626 6272 2626 6273 3121 6273 2627 6273 3129 6274 3223 6274 3226 6274 1897 6275 3217 6275 3130 6275 1893 6276 3211 6276 3216 6276 1848 6277 3206 6277 3210 6277 1900 6278 1905 6278 3131 6278 3202 6279 1847 6279 3132 6279 3196 6280 3189 6280 3195 6280 1846 6281 3133 6281 3188 6281 1929 6282 3172 6282 3175 6282 1844 6283 3166 6283 3171 6283 3167 6284 3162 6284 3165 6284 1843 6285 3134 6285 3158 6285 3135 6286 3252 6286 3159 6286 3143 6287 3142 6287 3144 6287 1671 6288 3136 6288 3124 6288 1672 6289 1671 6289 3242 6289 1665 6290 1672 6290 3243 6290 3138 6291 1665 6291 3233 6291 3137 6292 3138 6292 3228 6292 3139 6293 1680 6293 3140 6293 3141 6294 3139 6294 3155 6294 3146 6295 3142 6295 1675 6295 1675 6296 3142 6296 3143 6296 1675 6297 3143 6297 1674 6297 3148 6298 3144 6298 3150 6298 3150 6299 3144 6299 3142 6299 3150 6300 3142 6300 3145 6300 3145 6301 3142 6301 3146 6301 3145 6302 3146 6302 3152 6302 3147 6303 3148 6303 3149 6303 3149 6304 3148 6304 3150 6304 3149 6305 3150 6305 3151 6305 3151 6306 3150 6306 3145 6306 3151 6307 3145 6307 3153 6307 3153 6308 3145 6308 3152 6308 3153 6309 3152 6309 3137 6309 3182 6310 3174 6310 3154 6310 3141 6311 3155 6311 3264 6311 3264 6312 3155 6312 3161 6312 3264 6313 3161 6313 3156 6313 3156 6314 3161 6314 3157 6314 3156 6315 3157 6315 3253 6315 3253 6316 3157 6316 3158 6316 3253 6317 3158 6317 3159 6317 3159 6318 3158 6318 3134 6318 3159 6319 3134 6319 3135 6319 3139 6320 3140 6320 3155 6320 3155 6321 3140 6321 3160 6321 3155 6322 3160 6322 3161 6322 3161 6323 3160 6323 3164 6323 3161 6324 3164 6324 3157 6324 3157 6325 3164 6325 3165 6325 3157 6326 3165 6326 3158 6326 3158 6327 3165 6327 3162 6327 3158 6328 3162 6328 1843 6328 1680 6329 3163 6329 3140 6329 3140 6330 3163 6330 3168 6330 3140 6331 3168 6331 3160 6331 3160 6332 3168 6332 3170 6332 3160 6333 3170 6333 3164 6333 3164 6334 3170 6334 3171 6334 3164 6335 3171 6335 3165 6335 3165 6336 3171 6336 3166 6336 3165 6337 3166 6337 3167 6337 3163 6338 3173 6338 3168 6338 3168 6339 3173 6339 3169 6339 3168 6340 3169 6340 3170 6340 3170 6341 3169 6341 3175 6341 3170 6342 3175 6342 3171 6342 3171 6343 3175 6343 3172 6343 3171 6344 3172 6344 1844 6344 3173 6345 3154 6345 3169 6345 3169 6346 3154 6346 3174 6346 3169 6347 3174 6347 3175 6347 3175 6348 3174 6348 1930 6348 3175 6349 1930 6349 1929 6349 1917 6350 3179 6350 3176 6350 3176 6351 3179 6351 3182 6351 3176 6352 3182 6352 3177 6352 3177 6353 3182 6353 3154 6353 3177 6354 3154 6354 3183 6354 3183 6355 3154 6355 3173 6355 3183 6356 3173 6356 3178 6356 3178 6357 3173 6357 3163 6357 3178 6358 3163 6358 1679 6358 1679 6359 3163 6359 1680 6359 3179 6360 3180 6360 3182 6360 3182 6361 3180 6361 3181 6361 3182 6362 3181 6362 3174 6362 3174 6363 3181 6363 1924 6363 3174 6364 1924 6364 1930 6364 1679 6365 1666 6365 3178 6365 3178 6366 1666 6366 3186 6366 3178 6367 3186 6367 3183 6367 3183 6368 3186 6368 3184 6368 3183 6369 3184 6369 3177 6369 3177 6370 3184 6370 3185 6370 3177 6371 3185 6371 3176 6371 3176 6372 3185 6372 3188 6372 3176 6373 3188 6373 1917 6373 1917 6374 3188 6374 3133 6374 1666 6375 3190 6375 3186 6375 3186 6376 3190 6376 3187 6376 3186 6377 3187 6377 3184 6377 3184 6378 3187 6378 3191 6378 3184 6379 3191 6379 3185 6379 3185 6380 3191 6380 3193 6380 3185 6381 3193 6381 3188 6381 3188 6382 3193 6382 3195 6382 3188 6383 3195 6383 1846 6383 1846 6384 3195 6384 3189 6384 3190 6385 3197 6385 3187 6385 3187 6386 3197 6386 3199 6386 3187 6387 3199 6387 3191 6387 3191 6388 3199 6388 3192 6388 3191 6389 3192 6389 3193 6389 3193 6390 3192 6390 3194 6390 3193 6391 3194 6391 3195 6391 3195 6392 3194 6392 3132 6392 3195 6393 3132 6393 3196 6393 3196 6394 3132 6394 1847 6394 3197 6395 3198 6395 3199 6395 3199 6396 3198 6396 3200 6396 3199 6397 3200 6397 3192 6397 3192 6398 3200 6398 3201 6398 3192 6399 3201 6399 3194 6399 3194 6400 3201 6400 3205 6400 3194 6401 3205 6401 3132 6401 3132 6402 3205 6402 3131 6402 3132 6403 3131 6403 3202 6403 3202 6404 3131 6404 1905 6404 3198 6405 3203 6405 3200 6405 3200 6406 3203 6406 3204 6406 3200 6407 3204 6407 3201 6407 3201 6408 3204 6408 3208 6408 3201 6409 3208 6409 3205 6409 3205 6410 3208 6410 3209 6410 3205 6411 3209 6411 3131 6411 3131 6412 3209 6412 3210 6412 3131 6413 3210 6413 1900 6413 1900 6414 3210 6414 3206 6414 3203 6415 3207 6415 3204 6415 3204 6416 3207 6416 3212 6416 3204 6417 3212 6417 3208 6417 3208 6418 3212 6418 3213 6418 3208 6419 3213 6419 3209 6419 3209 6420 3213 6420 3215 6420 3209 6421 3215 6421 3210 6421 3210 6422 3215 6422 3216 6422 3210 6423 3216 6423 1848 6423 1848 6424 3216 6424 3211 6424 3207 6425 3218 6425 3212 6425 3212 6426 3218 6426 3220 6426 3212 6427 3220 6427 3213 6427 3213 6428 3220 6428 3214 6428 3213 6429 3214 6429 3215 6429 3215 6430 3214 6430 3222 6430 3215 6431 3222 6431 3216 6431 3216 6432 3222 6432 3130 6432 3216 6433 3130 6433 1893 6433 1893 6434 3130 6434 3217 6434 3218 6435 3219 6435 3220 6435 3220 6436 3219 6436 3221 6436 3220 6437 3221 6437 3214 6437 3214 6438 3221 6438 3224 6438 3214 6439 3224 6439 3222 6439 3222 6440 3224 6440 3225 6440 3222 6441 3225 6441 3130 6441 3130 6442 3225 6442 3226 6442 3130 6443 3226 6443 1897 6443 1897 6444 3226 6444 3223 6444 3219 6445 1674 6445 3221 6445 3221 6446 1674 6446 3143 6446 3221 6447 3143 6447 3224 6447 3224 6448 3143 6448 3144 6448 3224 6449 3144 6449 3225 6449 3225 6450 3144 6450 3148 6450 3225 6451 3148 6451 3226 6451 3226 6452 3148 6452 3147 6452 3226 6453 3147 6453 3129 6453 3129 6454 3147 6454 1889 6454 3235 6455 3227 6455 3230 6455 3137 6456 3228 6456 3153 6456 3153 6457 3228 6457 3229 6457 3153 6458 3229 6458 3151 6458 3151 6459 3229 6459 3234 6459 3151 6460 3234 6460 3149 6460 3149 6461 3234 6461 3235 6461 3149 6462 3235 6462 3147 6462 3147 6463 3235 6463 3230 6463 3147 6464 3230 6464 1889 6464 3236 6465 3231 6465 3232 6465 3138 6466 3233 6466 3228 6466 3228 6467 3233 6467 3238 6467 3228 6468 3238 6468 3229 6468 3229 6469 3238 6469 3240 6469 3229 6470 3240 6470 3234 6470 3234 6471 3240 6471 3236 6471 3234 6472 3236 6472 3235 6472 3235 6473 3236 6473 3232 6473 3235 6474 3232 6474 3227 6474 3241 6475 3248 6475 3237 6475 1665 6476 3243 6476 3233 6476 3233 6477 3243 6477 3244 6477 3233 6478 3244 6478 3238 6478 3238 6479 3244 6479 3239 6479 3238 6480 3239 6480 3240 6480 3240 6481 3239 6481 3241 6481 3240 6482 3241 6482 3236 6482 3236 6483 3241 6483 3237 6483 3236 6484 3237 6484 3231 6484 3246 6485 1879 6485 3247 6485 1672 6486 3242 6486 3243 6486 3243 6487 3242 6487 3245 6487 3243 6488 3245 6488 3244 6488 3244 6489 3245 6489 3251 6489 3244 6490 3251 6490 3239 6490 3239 6491 3251 6491 3246 6491 3239 6492 3246 6492 3241 6492 3241 6493 3246 6493 3247 6493 3241 6494 3247 6494 3248 6494 3128 6495 2620 6495 3249 6495 1671 6496 3124 6496 3242 6496 3242 6497 3124 6497 3250 6497 3242 6498 3250 6498 3245 6498 3245 6499 3250 6499 3126 6499 3245 6500 3126 6500 3251 6500 3251 6501 3126 6501 3128 6501 3251 6502 3128 6502 3246 6502 3246 6503 3128 6503 3249 6503 3246 6504 3249 6504 1879 6504 2166 6505 2165 6505 3299 6505 3271 6506 1108 6506 3270 6506 3291 6507 1110 6507 3288 6507 3288 6508 1110 6508 1109 6508 3159 6509 3252 6509 3254 6509 3253 6510 3159 6510 3255 6510 3156 6511 3253 6511 3258 6511 3264 6512 3156 6512 3265 6512 3159 6513 3254 6513 3255 6513 3255 6514 3254 6514 2161 6514 3255 6515 2161 6515 3259 6515 3259 6516 2161 6516 3256 6516 3259 6517 3256 6517 3260 6517 3260 6518 3256 6518 2125 6518 3260 6519 2125 6519 3261 6519 3261 6520 2125 6520 3257 6520 3261 6521 3257 6521 3262 6521 3262 6522 3257 6522 2157 6522 3262 6523 2157 6523 3263 6523 3253 6524 3255 6524 3258 6524 3258 6525 3255 6525 3259 6525 3258 6526 3259 6526 3282 6526 3282 6527 3259 6527 3260 6527 3282 6528 3260 6528 3283 6528 3283 6529 3260 6529 3261 6529 3283 6530 3261 6530 3284 6530 3284 6531 3261 6531 3262 6531 3284 6532 3262 6532 3286 6532 3286 6533 3262 6533 3263 6533 3286 6534 3263 6534 3287 6534 3264 6535 3265 6535 3266 6535 3266 6536 3265 6536 3267 6536 3266 6537 3267 6537 3278 6537 3278 6538 3267 6538 3268 6538 3278 6539 3268 6539 3277 6539 3277 6540 3268 6540 3285 6540 3277 6541 3285 6541 3275 6541 3275 6542 3285 6542 3269 6542 3275 6543 3269 6543 3274 6543 3274 6544 3269 6544 3288 6544 3274 6545 3288 6545 3271 6545 3271 6546 3288 6546 1109 6546 3271 6547 1109 6547 1108 6547 3270 6548 1664 6548 3271 6548 3271 6549 1664 6549 3272 6549 3271 6550 3272 6550 3274 6550 3274 6551 3272 6551 3273 6551 3274 6552 3273 6552 3275 6552 3275 6553 3273 6553 1673 6553 3275 6554 1673 6554 3277 6554 3277 6555 1673 6555 3276 6555 3277 6556 3276 6556 3278 6556 3278 6557 3276 6557 3279 6557 3278 6558 3279 6558 3266 6558 3266 6559 3279 6559 3141 6559 3266 6560 3141 6560 3264 6560 2157 6561 3280 6561 3263 6561 3263 6562 3280 6562 2128 6562 3263 6563 2128 6563 2166 6563 2166 6564 3299 6564 3263 6564 3263 6565 3299 6565 3292 6565 3263 6566 3292 6566 3287 6566 3287 6567 3292 6567 3281 6567 3287 6568 3281 6568 3294 6568 3156 6569 3258 6569 3265 6569 3265 6570 3258 6570 3282 6570 3265 6571 3282 6571 3267 6571 3267 6572 3282 6572 3283 6572 3267 6573 3283 6573 3268 6573 3268 6574 3283 6574 3284 6574 3268 6575 3284 6575 3285 6575 3285 6576 3284 6576 3286 6576 3285 6577 3286 6577 3269 6577 3269 6578 3286 6578 3287 6578 3269 6579 3287 6579 3288 6579 3288 6580 3287 6580 3294 6580 3288 6581 3294 6581 3291 6581 3289 6582 3295 6582 3290 6582 3294 6583 3295 6583 3291 6583 3291 6584 3295 6584 3289 6584 3291 6585 3289 6585 1110 6585 1113 6586 1112 6586 3296 6586 3296 6587 1112 6587 1107 6587 3281 6588 3292 6588 3293 6588 3293 6589 3292 6589 3299 6589 3294 6590 3281 6590 3295 6590 3295 6591 3281 6591 3293 6591 3295 6592 3293 6592 3290 6592 3290 6593 3293 6593 3296 6593 3290 6594 3296 6594 3297 6594 3297 6595 3296 6595 1107 6595 2167 6596 1113 6596 3298 6596 3298 6597 1113 6597 3296 6597 3298 6598 3296 6598 2168 6598 2168 6599 3296 6599 3293 6599 2168 6600 3293 6600 2169 6600 2169 6601 3293 6601 3299 6601 2169 6602 3299 6602 2165 6602 3313 6603 3300 6603 1667 6603 1681 6604 3301 6604 1667 6604 1667 6605 3301 6605 3358 6605 1667 6606 3358 6606 3313 6606 1682 6607 3302 6607 1681 6607 1681 6608 3302 6608 3303 6608 1681 6609 3303 6609 3301 6609 1663 6610 3305 6610 1682 6610 1682 6611 3305 6611 3360 6611 1682 6612 3360 6612 3302 6612 3307 6613 3304 6613 1663 6613 1663 6614 3304 6614 3362 6614 1663 6615 3362 6615 3305 6615 1677 6616 3306 6616 3307 6616 3307 6617 3306 6617 3365 6617 3307 6618 3365 6618 3304 6618 1668 6619 3368 6619 1677 6619 1677 6620 3368 6620 3367 6620 1677 6621 3367 6621 3306 6621 3309 6622 3350 6622 1668 6622 1668 6623 3350 6623 3349 6623 1668 6624 3349 6624 3368 6624 3310 6625 3308 6625 3309 6625 3309 6626 3308 6626 3351 6626 3309 6627 3351 6627 3350 6627 1676 6628 3354 6628 3310 6628 3310 6629 3354 6629 3353 6629 3310 6630 3353 6630 3308 6630 3311 6631 3315 6631 1676 6631 1676 6632 3315 6632 3312 6632 1676 6633 3312 6633 3354 6633 3313 6634 3357 6634 3300 6634 3300 6635 3357 6635 3314 6635 3300 6636 3314 6636 3311 6636 3311 6637 3314 6637 3356 6637 3311 6638 3356 6638 3315 6638 3317 6639 3316 6639 3332 6639 3317 6640 3318 6640 3316 6640 3316 6641 3318 6641 3346 6641 3316 6642 3346 6642 1697 6642 3346 6643 3319 6643 1697 6643 1697 6644 3319 6644 3320 6644 1697 6645 3320 6645 3321 6645 3320 6646 3322 6646 3321 6646 3321 6647 3322 6647 3323 6647 3321 6648 3323 6648 1699 6648 3323 6649 3345 6649 1699 6649 1699 6650 3345 6650 3343 6650 1699 6651 3343 6651 3324 6651 3343 6652 3342 6652 3324 6652 3324 6653 3342 6653 3341 6653 3324 6654 3341 6654 3325 6654 3341 6655 3340 6655 3325 6655 3325 6656 3340 6656 3339 6656 3325 6657 3339 6657 1693 6657 3339 6658 3338 6658 1693 6658 1693 6659 3338 6659 3326 6659 1693 6660 3326 6660 1687 6660 3326 6661 3327 6661 1687 6661 1687 6662 3327 6662 3337 6662 1687 6663 3337 6663 1705 6663 3337 6664 3328 6664 1705 6664 1705 6665 3328 6665 3335 6665 1705 6666 3335 6666 1703 6666 3335 6667 3329 6667 1703 6667 1703 6668 3329 6668 3330 6668 1703 6669 3330 6669 1696 6669 3330 6670 3331 6670 1696 6670 1696 6671 3331 6671 3333 6671 1696 6672 3333 6672 3332 6672 3332 6673 3333 6673 3348 6673 3332 6674 3348 6674 3317 6674 878 6675 3334 6675 3331 6675 3331 6676 3330 6676 878 6676 878 6677 3330 6677 3329 6677 878 6678 3329 6678 3336 6678 3329 6679 3335 6679 3336 6679 3336 6680 3335 6680 3328 6680 3336 6681 3328 6681 879 6681 879 6682 3328 6682 3337 6682 879 6683 3337 6683 885 6683 885 6684 3337 6684 3327 6684 885 6685 3327 6685 906 6685 3327 6686 3326 6686 906 6686 906 6687 3326 6687 3338 6687 906 6688 3338 6688 904 6688 3338 6689 3339 6689 904 6689 904 6690 3339 6690 3340 6690 904 6691 3340 6691 887 6691 3340 6692 3341 6692 887 6692 887 6693 3341 6693 3342 6693 887 6694 3342 6694 888 6694 888 6695 3342 6695 3343 6695 888 6696 3343 6696 3344 6696 3344 6697 3343 6697 3345 6697 3344 6698 3345 6698 900 6698 3345 6699 3323 6699 900 6699 900 6700 3323 6700 3322 6700 900 6701 3322 6701 894 6701 3322 6702 3320 6702 894 6702 894 6703 3320 6703 3319 6703 894 6704 3319 6704 875 6704 3319 6705 3346 6705 875 6705 875 6706 3346 6706 3318 6706 875 6707 3318 6707 877 6707 877 6708 3318 6708 3317 6708 877 6709 3317 6709 3347 6709 3347 6710 3317 6710 3348 6710 3347 6711 3348 6711 3334 6711 3334 6712 3348 6712 3333 6712 3334 6713 3333 6713 3331 6713 1841 6714 1842 6714 3349 6714 3349 6715 3350 6715 1841 6715 1841 6716 3350 6716 3351 6716 1841 6717 3351 6717 3352 6717 3351 6718 3308 6718 3352 6718 3352 6719 3308 6719 3353 6719 3352 6720 3353 6720 1818 6720 1818 6721 3353 6721 3354 6721 1818 6722 3354 6722 1830 6722 1830 6723 3354 6723 3312 6723 1830 6724 3312 6724 3355 6724 3312 6725 3315 6725 3355 6725 3355 6726 3315 6726 3356 6726 3355 6727 3356 6727 1831 6727 3356 6728 3314 6728 1831 6728 1831 6729 3314 6729 3357 6729 1831 6730 3357 6730 1833 6730 3357 6731 3313 6731 1833 6731 1833 6732 3313 6732 3358 6732 1833 6733 3358 6733 1824 6733 1824 6734 3358 6734 3301 6734 1824 6735 3301 6735 1837 6735 1837 6736 3301 6736 3303 6736 1837 6737 3303 6737 3359 6737 3303 6738 3302 6738 3359 6738 3359 6739 3302 6739 3360 6739 3359 6740 3360 6740 3361 6740 3360 6741 3305 6741 3361 6741 3361 6742 3305 6742 3362 6742 3361 6743 3362 6743 3363 6743 3362 6744 3304 6744 3363 6744 3363 6745 3304 6745 3365 6745 3363 6746 3365 6746 3364 6746 3364 6747 3365 6747 3306 6747 3364 6748 3306 6748 3366 6748 3366 6749 3306 6749 3367 6749 3366 6750 3367 6750 1842 6750 1842 6751 3367 6751 3368 6751 1842 6752 3368 6752 3349 6752 3369 6753 3535 6753 3537 6753 3382 6754 3531 6754 3370 6754 3370 6755 3531 6755 3371 6755 3370 6756 3371 6756 3372 6756 3372 6757 3371 6757 3373 6757 3372 6758 3373 6758 3374 6758 3374 6759 3375 6759 3372 6759 3372 6760 3375 6760 3376 6760 3372 6761 3376 6761 3369 6761 3369 6762 3376 6762 3377 6762 3369 6763 3377 6763 3535 6763 2663 6764 2664 6764 3390 6764 3390 6765 2664 6765 3369 6765 3390 6766 3369 6766 3395 6766 3395 6767 3369 6767 3537 6767 2664 6768 2665 6768 3369 6768 3369 6769 2665 6769 3378 6769 3369 6770 3378 6770 3372 6770 3372 6771 3378 6771 3379 6771 3372 6772 3379 6772 3380 6772 3380 6773 2668 6773 3372 6773 3372 6774 2668 6774 3381 6774 3372 6775 3381 6775 3370 6775 3370 6776 3381 6776 2667 6776 3370 6777 2667 6777 3382 6777 3386 6778 3383 6778 3398 6778 3406 6779 3385 6779 3543 6779 3543 6780 3385 6780 3384 6780 3410 6781 3408 6781 3385 6781 3385 6782 3408 6782 3545 6782 3385 6783 3545 6783 3384 6783 3383 6784 3386 6784 3405 6784 3405 6785 3386 6785 3540 6785 3405 6786 3540 6786 3538 6786 3387 6787 3388 6787 3398 6787 3398 6788 3388 6788 3389 6788 3398 6789 3389 6789 3386 6789 3403 6790 3390 6790 3395 6790 3398 6791 3400 6791 3387 6791 3387 6792 3400 6792 3401 6792 3387 6793 3401 6793 3391 6793 3391 6794 3401 6794 3392 6794 3391 6795 3392 6795 3393 6795 3393 6796 3392 6796 3403 6796 3393 6797 3403 6797 3394 6797 3394 6798 3403 6798 3395 6798 3394 6799 3395 6799 3537 6799 3405 6800 3396 6800 3383 6800 3383 6801 3396 6801 3397 6801 3383 6802 3397 6802 3398 6802 3398 6803 3397 6803 3399 6803 3398 6804 3399 6804 3400 6804 3400 6805 3399 6805 1081 6805 3400 6806 1081 6806 3401 6806 3401 6807 1081 6807 3402 6807 3401 6808 3402 6808 3392 6808 3392 6809 3402 6809 1091 6809 3392 6810 1091 6810 3403 6810 3403 6811 1091 6811 2663 6811 3403 6812 2663 6812 3390 6812 3409 6813 3404 6813 3405 6813 3405 6814 3404 6814 1083 6814 3405 6815 1083 6815 3396 6815 3543 6816 3542 6816 3406 6816 3406 6817 3542 6817 3407 6817 3406 6818 3407 6818 3436 6818 3538 6819 3408 6819 3405 6819 3405 6820 3408 6820 3410 6820 3405 6821 3410 6821 3409 6821 3409 6822 3410 6822 3385 6822 3409 6823 3385 6823 3411 6823 3411 6824 3385 6824 3406 6824 3411 6825 3406 6825 3412 6825 3412 6826 3406 6826 3436 6826 3412 6827 3436 6827 3413 6827 3586 6828 3414 6828 3421 6828 3585 6829 3422 6829 3584 6829 3584 6830 3422 6830 3415 6830 3584 6831 3415 6831 3581 6831 3581 6832 3415 6832 3570 6832 3570 6833 3415 6833 3428 6833 3570 6834 3428 6834 3416 6834 3571 6835 3429 6835 3572 6835 3572 6836 3429 6836 3430 6836 3572 6837 3430 6837 3573 6837 3573 6838 3430 6838 3417 6838 3417 6839 3430 6839 3432 6839 3417 6840 3432 6840 3418 6840 2177 6841 3419 6841 3421 6841 3421 6842 3419 6842 2176 6842 3414 6843 2177 6843 3421 6843 3420 6844 3415 6844 2176 6844 2176 6845 3415 6845 3422 6845 2176 6846 3422 6846 3421 6846 3421 6847 3422 6847 3585 6847 3421 6848 3585 6848 3586 6848 3423 6849 3428 6849 3424 6849 3424 6850 3428 6850 3415 6850 3424 6851 3415 6851 3425 6851 3425 6852 3415 6852 3420 6852 3427 6853 3426 6853 3429 6853 3423 6854 3427 6854 3428 6854 3428 6855 3427 6855 3429 6855 3428 6856 3429 6856 3416 6856 3416 6857 3429 6857 3571 6857 3426 6858 2179 6858 3429 6858 3429 6859 2179 6859 2178 6859 3429 6860 2178 6860 3430 6860 3430 6861 2178 6861 3431 6861 3430 6862 3431 6862 3432 6862 3407 6863 3542 6863 3555 6863 3437 6864 3438 6864 3552 6864 3552 6865 3438 6865 3433 6865 3552 6866 3433 6866 3553 6866 3553 6867 3433 6867 3434 6867 3553 6868 3434 6868 3555 6868 3555 6869 3434 6869 3435 6869 3555 6870 3435 6870 3407 6870 3407 6871 3435 6871 3436 6871 3437 6872 3559 6872 3438 6872 3438 6873 3559 6873 3443 6873 3438 6874 3443 6874 3450 6874 3450 6875 2059 6875 3438 6875 3438 6876 2059 6876 1119 6876 3438 6877 1119 6877 3433 6877 3433 6878 1119 6878 3439 6878 3433 6879 3439 6879 3434 6879 3434 6880 3439 6880 3440 6880 3434 6881 3440 6881 3435 6881 3435 6882 3440 6882 1118 6882 3435 6883 1118 6883 3436 6883 3436 6884 1118 6884 3413 6884 3418 6885 3432 6885 3441 6885 3441 6886 3432 6886 3444 6886 3447 6887 3442 6887 3445 6887 3445 6888 3442 6888 3565 6888 3445 6889 3565 6889 3444 6889 3444 6890 3565 6890 3567 6890 3444 6891 3567 6891 3441 6891 3451 6892 3561 6892 3562 6892 3559 6893 3561 6893 3443 6893 3443 6894 3561 6894 3451 6894 3443 6895 3451 6895 3450 6895 3432 6896 3431 6896 2053 6896 3432 6897 2053 6897 3444 6897 3444 6898 2053 6898 3446 6898 3444 6899 3446 6899 3445 6899 3445 6900 3446 6900 2057 6900 3445 6901 2057 6901 3447 6901 3447 6902 2057 6902 3448 6902 3447 6903 3448 6903 3449 6903 2059 6904 3450 6904 3449 6904 3449 6905 3450 6905 3451 6905 3449 6906 3451 6906 3447 6906 3447 6907 3451 6907 3562 6907 3447 6908 3562 6908 3442 6908 3587 6909 3452 6909 3459 6909 3453 6910 3454 6910 3593 6910 3593 6911 3454 6911 3595 6911 3460 6912 3459 6912 3589 6912 3589 6913 3459 6913 3454 6913 3589 6914 3454 6914 3591 6914 3591 6915 3454 6915 3453 6915 3595 6916 3454 6916 3597 6916 3597 6917 3454 6917 3456 6917 3597 6918 3456 6918 3455 6918 3464 6919 3455 6919 3457 6919 3457 6920 3455 6920 3456 6920 3457 6921 3456 6921 3479 6921 3479 6922 3456 6922 2631 6922 3479 6923 2631 6923 3478 6923 3458 6924 2629 6924 3454 6924 3454 6925 2629 6925 2633 6925 3454 6926 2633 6926 3456 6926 3456 6927 2633 6927 2632 6927 3456 6928 2632 6928 2631 6928 3459 6929 3452 6929 3454 6929 3454 6930 3452 6930 2630 6930 3454 6931 2630 6931 3458 6931 3460 6932 3587 6932 3459 6932 3457 6933 3479 6933 3461 6933 3483 6934 3600 6934 3462 6934 3462 6935 3600 6935 3463 6935 3462 6936 3463 6936 3481 6936 3481 6937 3463 6937 3598 6937 3481 6938 3598 6938 3461 6938 3461 6939 3598 6939 3464 6939 3461 6940 3464 6940 3457 6940 3473 6941 3474 6941 3465 6941 3465 6942 3474 6942 3466 6942 3465 6943 3466 6943 3485 6943 3485 6944 3466 6944 3468 6944 3485 6945 3468 6945 3467 6945 3467 6946 3468 6946 3469 6946 3467 6947 3469 6947 3483 6947 3483 6948 3469 6948 3470 6948 3483 6949 3470 6949 3600 6949 3488 6950 3471 6950 3473 6950 3473 6951 3471 6951 3472 6951 3473 6952 3472 6952 3474 6952 3487 6953 3476 6953 3489 6953 3475 6954 3476 6954 3477 6954 3477 6955 3476 6955 3487 6955 3477 6956 3487 6956 3497 6956 3479 6957 3478 6957 3480 6957 3479 6958 3480 6958 3461 6958 3461 6959 3480 6959 1066 6959 3461 6960 1066 6960 3481 6960 3481 6961 1066 6961 1067 6961 3481 6962 1067 6962 3462 6962 3462 6963 1067 6963 3482 6963 3462 6964 3482 6964 3483 6964 3483 6965 3482 6965 1069 6965 3483 6966 1069 6966 3467 6966 1069 6967 3484 6967 3467 6967 3467 6968 3484 6968 1075 6968 3467 6969 1075 6969 3485 6969 3485 6970 1075 6970 3486 6970 3485 6971 3486 6971 3465 6971 3465 6972 3486 6972 1072 6972 3465 6973 1072 6973 3473 6973 3473 6974 1072 6974 1079 6974 3473 6975 1079 6975 3488 6975 3488 6976 1079 6976 1077 6976 3488 6977 1077 6977 1076 6977 1132 6978 3497 6978 1076 6978 1076 6979 3497 6979 3487 6979 1076 6980 3487 6980 3488 6980 3488 6981 3487 6981 3489 6981 3488 6982 3489 6982 3471 6982 3525 6983 3490 6983 3491 6983 3525 6984 3491 6984 3526 6984 3614 6985 3492 6985 3493 6985 3493 6986 3492 6986 3498 6986 3493 6987 3498 6987 3494 6987 3494 6988 3498 6988 3495 6988 3494 6989 3495 6989 3491 6989 3491 6990 3495 6990 3496 6990 3491 6991 3496 6991 3526 6991 3614 6992 3475 6992 3492 6992 3492 6993 3475 6993 3477 6993 3492 6994 3477 6994 3497 6994 3497 6995 1132 6995 3492 6995 3492 6996 1132 6996 1133 6996 3492 6997 1133 6997 3498 6997 3498 6998 1133 6998 3499 6998 3498 6999 3499 6999 3495 6999 3495 7000 3499 7000 1134 7000 3495 7001 1134 7001 3496 7001 3496 7002 1134 7002 1130 7002 3496 7003 1130 7003 3526 7003 3526 7004 1130 7004 1131 7004 3617 7005 3633 7005 3502 7005 3502 7006 3633 7006 3500 7006 3505 7007 3618 7007 3502 7007 3502 7008 3618 7008 3501 7008 3502 7009 3501 7009 3617 7009 3620 7010 3503 7010 3504 7010 3504 7011 3503 7011 3506 7011 3504 7012 3506 7012 3505 7012 3505 7013 3506 7013 3507 7013 3505 7014 3507 7014 3618 7014 3516 7015 3515 7015 3508 7015 3508 7016 3515 7016 3511 7016 3508 7017 3511 7017 3642 7017 3642 7018 3511 7018 3644 7018 1865 7019 3509 7019 3510 7019 3510 7020 3509 7020 3644 7020 3644 7021 3511 7021 3510 7021 3510 7022 3511 7022 3513 7022 3510 7023 3513 7023 1865 7023 3514 7024 2134 7024 3515 7024 3515 7025 2134 7025 2133 7025 3515 7026 2133 7026 3511 7026 3511 7027 2133 7027 3512 7027 3511 7028 3512 7028 3513 7028 2136 7029 3514 7029 3504 7029 3504 7030 3514 7030 3515 7030 3504 7031 3515 7031 3620 7031 3620 7032 3515 7032 3516 7032 2136 7033 3504 7033 2129 7033 2129 7034 3504 7034 3505 7034 2129 7035 3505 7035 2130 7035 2130 7036 3505 7036 3517 7036 3517 7037 3505 7037 3502 7037 3517 7038 3502 7038 2131 7038 2131 7039 3502 7039 3500 7039 2131 7040 3500 7040 3518 7040 3518 7041 3500 7041 3521 7041 3526 7042 1131 7042 3527 7042 3523 7043 3519 7043 3520 7043 3520 7044 3519 7044 3628 7044 3520 7045 3628 7045 3529 7045 3632 7046 3631 7046 3521 7046 3521 7047 3631 7047 3522 7047 3521 7048 3522 7048 3530 7048 3530 7049 3522 7049 3630 7049 3530 7050 3630 7050 3523 7050 3523 7051 3630 7051 3626 7051 3523 7052 3626 7052 3519 7052 3500 7053 3633 7053 3521 7053 3521 7054 3633 7054 3524 7054 3521 7055 3524 7055 3632 7055 3628 7056 3490 7056 3529 7056 3529 7057 3490 7057 3525 7057 3529 7058 3525 7058 3526 7058 3526 7059 3527 7059 3529 7059 3529 7060 3527 7060 3528 7060 3529 7061 3528 7061 3520 7061 3520 7062 3528 7062 2118 7062 3520 7063 2118 7063 3523 7063 3523 7064 2118 7064 2117 7064 3523 7065 2117 7065 3530 7065 3530 7066 2117 7066 2116 7066 3530 7067 2116 7067 3521 7067 3521 7068 2116 7068 2111 7068 3521 7069 2111 7069 3518 7069 3531 7070 3382 7070 3532 7070 3531 7071 3532 7071 3371 7071 3371 7072 3532 7072 3533 7072 3371 7073 3533 7073 3373 7073 3373 7074 3533 7074 897 7074 3373 7075 897 7075 3374 7075 3374 7076 897 7076 3534 7076 3374 7077 3534 7077 3375 7077 3375 7078 3534 7078 3376 7078 3376 7079 3534 7079 896 7079 3376 7080 896 7080 3377 7080 3536 7081 3537 7081 3535 7081 3377 7082 896 7082 3535 7082 3535 7083 896 7083 907 7083 3535 7084 907 7084 3536 7084 3389 7085 3388 7085 3541 7085 3541 7086 3388 7086 3387 7086 3387 7087 3391 7087 3541 7087 3541 7088 3391 7088 3393 7088 3541 7089 3393 7089 3536 7089 3536 7090 3393 7090 3394 7090 3536 7091 3394 7091 3537 7091 3389 7092 3541 7092 3386 7092 3386 7093 3541 7093 3539 7093 3386 7094 3539 7094 3540 7094 3544 7095 3408 7095 3539 7095 3539 7096 3408 7096 3538 7096 3539 7097 3538 7097 3540 7097 898 7098 3544 7098 902 7098 902 7099 3544 7099 3539 7099 902 7100 3539 7100 903 7100 903 7101 3539 7101 3541 7101 903 7102 3541 7102 905 7102 905 7103 3541 7103 3536 7103 905 7104 3536 7104 907 7104 898 7105 3554 7105 3544 7105 3544 7106 3554 7106 3542 7106 3544 7107 3542 7107 3543 7107 3543 7108 3384 7108 3544 7108 3544 7109 3384 7109 3545 7109 3544 7110 3545 7110 3408 7110 899 7111 3560 7111 3546 7111 3546 7112 3560 7112 3550 7112 3546 7113 3550 7113 901 7113 901 7114 3550 7114 3551 7114 901 7115 3551 7115 889 7115 889 7116 3551 7116 3547 7116 889 7117 3547 7117 3548 7117 3548 7118 3547 7118 3549 7118 3548 7119 3549 7119 898 7119 898 7120 3549 7120 3554 7120 3560 7121 3559 7121 3550 7121 3550 7122 3559 7122 3437 7122 3550 7123 3437 7123 3551 7123 3551 7124 3437 7124 3552 7124 3551 7125 3552 7125 3547 7125 3547 7126 3552 7126 3553 7126 3547 7127 3553 7127 3549 7127 3549 7128 3553 7128 3555 7128 3549 7129 3555 7129 3554 7129 3554 7130 3555 7130 3542 7130 891 7131 890 7131 3578 7131 3574 7132 3557 7132 3556 7132 3556 7133 3557 7133 3568 7133 3560 7134 899 7134 3558 7134 3559 7135 3560 7135 3561 7135 3561 7136 3560 7136 3563 7136 3561 7137 3563 7137 3562 7137 3562 7138 3563 7138 3442 7138 3442 7139 3563 7139 3564 7139 3442 7140 3564 7140 3565 7140 3560 7141 3558 7141 3563 7141 3563 7142 3558 7142 3566 7142 3563 7143 3566 7143 3564 7143 3564 7144 3566 7144 891 7144 3564 7145 891 7145 3556 7145 3556 7146 891 7146 3578 7146 3556 7147 3578 7147 3574 7147 3565 7148 3564 7148 3567 7148 3567 7149 3564 7149 3556 7149 3567 7150 3556 7150 3441 7150 3441 7151 3556 7151 3568 7151 3441 7152 3568 7152 3418 7152 3568 7153 3575 7153 3418 7153 3571 7154 3575 7154 3416 7154 3416 7155 3575 7155 3569 7155 3416 7156 3569 7156 3570 7156 3571 7157 3572 7157 3575 7157 3575 7158 3572 7158 3573 7158 3575 7159 3573 7159 3417 7159 3575 7160 3568 7160 3569 7160 3569 7161 3568 7161 3557 7161 3569 7162 3557 7162 3574 7162 3417 7163 3418 7163 3575 7163 3576 7164 3579 7164 3577 7164 3577 7165 3579 7165 890 7165 3578 7166 890 7166 3579 7166 3576 7167 3570 7167 3579 7167 3579 7168 3570 7168 3569 7168 3579 7169 3569 7169 3578 7169 3578 7170 3569 7170 3574 7170 890 7171 3580 7171 3577 7171 3577 7172 3580 7172 3582 7172 3577 7173 3582 7173 3576 7173 3584 7174 3581 7174 3582 7174 3582 7175 3581 7175 3570 7175 3582 7176 3570 7176 3576 7176 3582 7177 3583 7177 3584 7177 3584 7178 3583 7178 895 7178 3584 7179 895 7179 3585 7179 3585 7180 895 7180 893 7180 2177 7181 3414 7181 893 7181 893 7182 3414 7182 3586 7182 893 7183 3586 7183 3585 7183 3588 7184 3587 7184 3460 7184 3460 7185 3589 7185 3588 7185 3588 7186 3589 7186 3591 7186 3588 7187 3591 7187 3590 7187 3590 7188 3591 7188 3453 7188 3590 7189 3453 7189 3592 7189 3592 7190 3453 7190 3593 7190 3592 7191 3593 7191 3594 7191 3594 7192 3593 7192 3595 7192 3594 7193 3595 7193 3596 7193 3455 7194 3464 7194 3601 7194 3601 7195 3602 7195 3455 7195 3455 7196 3602 7196 3596 7196 3455 7197 3596 7197 3597 7197 3597 7198 3596 7198 3595 7198 3598 7199 3463 7199 3599 7199 3599 7200 3463 7200 3600 7200 3599 7201 3600 7201 3470 7201 3464 7202 3598 7202 3601 7202 3601 7203 3598 7203 3599 7203 3601 7204 3599 7204 3602 7204 3470 7205 3469 7205 3599 7205 3599 7206 3469 7206 3468 7206 3599 7207 3468 7207 3605 7207 3468 7208 3466 7208 3605 7208 3605 7209 3466 7209 3474 7209 3605 7210 3474 7210 3603 7210 3603 7211 3474 7211 3472 7211 3603 7212 3472 7212 3471 7212 3475 7213 3612 7213 3476 7213 3476 7214 3612 7214 3603 7214 3476 7215 3603 7215 3489 7215 3489 7216 3603 7216 3471 7216 3602 7217 3599 7217 3604 7217 3604 7218 3599 7218 3605 7218 3604 7219 3605 7219 3606 7219 3606 7220 3605 7220 3603 7220 3606 7221 3603 7221 3607 7221 3607 7222 3603 7222 3612 7222 3607 7223 3612 7223 1815 7223 1815 7224 3612 7224 1814 7224 1814 7225 3612 7225 3613 7225 1814 7226 3613 7226 3608 7226 3608 7227 3613 7227 3609 7227 3608 7228 3609 7228 3610 7228 3610 7229 3609 7229 3615 7229 3610 7230 3615 7230 3611 7230 3611 7231 3615 7231 3616 7231 3611 7232 3616 7232 1819 7232 1819 7233 3616 7233 3627 7233 3612 7234 3475 7234 3613 7234 3613 7235 3475 7235 3614 7235 3613 7236 3614 7236 3609 7236 3609 7237 3614 7237 3493 7237 3609 7238 3493 7238 3615 7238 3615 7239 3493 7239 3494 7239 3615 7240 3494 7240 3616 7240 3616 7241 3494 7241 3491 7241 3616 7242 3491 7242 3627 7242 3627 7243 3491 7243 3490 7243 3633 7244 3617 7244 3619 7244 3619 7245 3617 7245 3501 7245 3619 7246 3501 7246 3618 7246 3618 7247 3507 7247 3619 7247 3619 7248 3507 7248 3506 7248 3619 7249 3506 7249 3622 7249 3622 7250 3506 7250 3503 7250 3622 7251 3503 7251 3620 7251 3621 7252 3625 7252 3622 7252 3622 7253 3625 7253 3623 7253 3622 7254 3623 7254 3619 7254 3619 7255 3623 7255 3624 7255 3619 7256 3624 7256 3633 7256 3639 7257 1838 7257 1821 7257 3624 7258 3623 7258 3636 7258 3636 7259 3623 7259 3625 7259 3636 7260 3625 7260 3621 7260 3519 7261 3626 7261 3629 7261 3627 7262 3490 7262 3628 7262 3628 7263 3519 7263 3627 7263 3627 7264 3519 7264 3629 7264 3627 7265 3629 7265 1819 7265 3631 7266 3634 7266 3522 7266 3522 7267 3634 7267 3629 7267 3522 7268 3629 7268 3630 7268 3630 7269 3629 7269 3626 7269 3631 7270 3632 7270 3634 7270 3634 7271 3632 7271 3524 7271 3634 7272 3524 7272 3636 7272 3636 7273 3524 7273 3633 7273 3636 7274 3633 7274 3624 7274 1819 7275 3629 7275 1820 7275 1820 7276 3629 7276 3634 7276 1820 7277 3634 7277 3635 7277 3635 7278 3634 7278 3636 7278 3635 7279 3636 7279 1821 7279 1821 7280 3636 7280 3621 7280 1821 7281 3621 7281 3639 7281 3639 7282 3638 7282 1838 7282 3641 7283 3637 7283 3638 7283 3638 7284 3637 7284 1838 7284 3620 7285 3641 7285 3622 7285 3622 7286 3641 7286 3638 7286 3622 7287 3638 7287 3621 7287 3621 7288 3638 7288 3639 7288 3509 7289 1865 7289 3643 7289 3641 7290 3640 7290 3637 7290 3637 7291 3640 7291 1839 7291 3637 7292 1839 7292 1838 7292 3641 7293 3620 7293 3640 7293 3640 7294 3620 7294 3516 7294 3640 7295 3516 7295 1840 7295 3516 7296 3508 7296 1840 7296 1840 7297 3508 7297 3642 7297 1840 7298 3642 7298 3643 7298 3643 7299 3642 7299 3644 7299 3643 7300 3644 7300 3509 7300 3651 7301 3645 7301 3647 7301 3735 7302 3646 7302 3651 7302 3651 7303 3646 7303 3653 7303 3647 7304 3734 7304 3651 7304 3651 7305 3734 7305 3648 7305 3651 7306 3648 7306 3735 7306 1008 7307 3649 7307 3651 7307 3651 7308 3649 7308 3732 7308 3651 7309 3732 7309 3733 7309 1315 7310 3650 7310 3746 7310 3746 7311 3650 7311 3651 7311 3746 7312 3651 7312 3652 7312 3652 7313 3651 7313 3653 7313 3733 7314 3654 7314 3651 7314 3651 7315 3654 7315 3741 7315 3651 7316 3741 7316 3645 7316 3665 7317 3678 7317 3667 7317 3761 7318 3760 7318 3655 7318 3761 7319 3655 7319 3756 7319 3756 7320 3655 7320 3669 7320 3756 7321 3669 7321 3656 7321 3749 7322 3657 7322 3659 7322 3659 7323 3657 7323 3755 7323 3659 7324 3755 7324 3669 7324 3669 7325 3755 7325 3658 7325 3669 7326 3658 7326 3656 7326 3662 7327 3752 7327 3664 7327 3664 7328 3752 7328 3751 7328 3664 7329 3751 7329 3668 7329 3668 7330 3751 7330 3750 7330 3668 7331 3750 7331 3659 7331 3659 7332 3750 7332 3660 7332 3659 7333 3660 7333 3749 7333 3678 7334 3661 7334 3667 7334 3667 7335 3661 7335 995 7335 3667 7336 995 7336 999 7336 1000 7337 3754 7337 996 7337 996 7338 3754 7338 3662 7338 996 7339 3662 7339 3663 7339 3663 7340 3662 7340 3664 7340 3663 7341 3664 7341 998 7341 998 7342 3664 7342 3668 7342 998 7343 3668 7343 999 7343 3665 7344 3667 7344 3677 7344 3677 7345 3667 7345 3670 7345 3677 7346 3670 7346 3675 7346 3675 7347 3670 7347 3666 7347 3675 7348 3666 7348 3672 7348 3672 7349 3666 7349 3671 7349 3672 7350 3671 7350 1314 7350 999 7351 3668 7351 3667 7351 3667 7352 3668 7352 3659 7352 3667 7353 3659 7353 3670 7353 3670 7354 3659 7354 3669 7354 3670 7355 3669 7355 3666 7355 3666 7356 3669 7356 3655 7356 3666 7357 3655 7357 3671 7357 1314 7358 3673 7358 3672 7358 3672 7359 3673 7359 3674 7359 3672 7360 3674 7360 3675 7360 3675 7361 3674 7361 3679 7361 3675 7362 3679 7362 3677 7362 3677 7363 3679 7363 3676 7363 3677 7364 3676 7364 3665 7364 3665 7365 3676 7365 3688 7365 3665 7366 3688 7366 3678 7366 3678 7367 3688 7367 3687 7367 3678 7368 3687 7368 3661 7368 3661 7369 3687 7369 871 7369 3679 7370 3674 7370 3697 7370 3688 7371 3676 7371 3690 7371 3680 7372 867 7372 3693 7372 3693 7373 867 7373 868 7373 3693 7374 868 7374 3692 7374 3692 7375 868 7375 3684 7375 3692 7376 3684 7376 3682 7376 871 7377 3687 7377 870 7377 870 7378 3687 7378 3689 7378 870 7379 3689 7379 3681 7379 3681 7380 3689 7380 3682 7380 3681 7381 3682 7381 3683 7381 3683 7382 3682 7382 3684 7382 3696 7383 3685 7383 3693 7383 3693 7384 3685 7384 3686 7384 3693 7385 3686 7385 3680 7385 3687 7386 3688 7386 3689 7386 3689 7387 3688 7387 3690 7387 3689 7388 3690 7388 3682 7388 3682 7389 3690 7389 3691 7389 3682 7390 3691 7390 3692 7390 3692 7391 3691 7391 3694 7391 3692 7392 3694 7392 3693 7392 3693 7393 3694 7393 3695 7393 3693 7394 3695 7394 3696 7394 3696 7395 3695 7395 3702 7395 3676 7396 3679 7396 3690 7396 3690 7397 3679 7397 3697 7397 3690 7398 3697 7398 3691 7398 3691 7399 3697 7399 3698 7399 3691 7400 3698 7400 3694 7400 3694 7401 3698 7401 3699 7401 3694 7402 3699 7402 3695 7402 3695 7403 3699 7403 3700 7403 3695 7404 3700 7404 3702 7404 3702 7405 3700 7405 3701 7405 3674 7406 3673 7406 3697 7406 3697 7407 3673 7407 1313 7407 3697 7408 1313 7408 3698 7408 3698 7409 1313 7409 1309 7409 3698 7410 1309 7410 3699 7410 3699 7411 1309 7411 1308 7411 3699 7412 1308 7412 3700 7412 3700 7413 1308 7413 1312 7413 3700 7414 1312 7414 3701 7414 3701 7415 1312 7415 1311 7415 1311 7416 3721 7416 3701 7416 3701 7417 3721 7417 3720 7417 3701 7418 3720 7418 3702 7418 3702 7419 3720 7419 3703 7419 3702 7420 3703 7420 3696 7420 3696 7421 3703 7421 3704 7421 3696 7422 3704 7422 3685 7422 3685 7423 3704 7423 3705 7423 3685 7424 3705 7424 3686 7424 3686 7425 3705 7425 3706 7425 3686 7426 3706 7426 3680 7426 3680 7427 3706 7427 853 7427 3703 7428 3720 7428 3717 7428 3705 7429 3704 7429 3712 7429 3725 7430 863 7430 3714 7430 3714 7431 863 7431 865 7431 3714 7432 865 7432 3707 7432 865 7433 859 7433 3707 7433 3707 7434 859 7434 861 7434 3707 7435 861 7435 3710 7435 853 7436 3706 7436 3708 7436 3708 7437 3706 7437 3711 7437 3708 7438 3711 7438 855 7438 855 7439 3711 7439 3710 7439 855 7440 3710 7440 3709 7440 3709 7441 3710 7441 861 7441 3716 7442 3728 7442 3714 7442 3714 7443 3728 7443 3726 7443 3714 7444 3726 7444 3725 7444 3706 7445 3705 7445 3711 7445 3711 7446 3705 7446 3712 7446 3711 7447 3712 7447 3710 7447 3710 7448 3712 7448 3718 7448 3710 7449 3718 7449 3707 7449 3707 7450 3718 7450 3713 7450 3707 7451 3713 7451 3714 7451 3714 7452 3713 7452 3715 7452 3714 7453 3715 7453 3716 7453 3716 7454 3715 7454 3730 7454 3704 7455 3703 7455 3712 7455 3712 7456 3703 7456 3717 7456 3712 7457 3717 7457 3718 7457 3718 7458 3717 7458 3722 7458 3718 7459 3722 7459 3713 7459 3713 7460 3722 7460 3723 7460 3713 7461 3723 7461 3715 7461 3715 7462 3723 7462 3719 7462 3715 7463 3719 7463 3730 7463 3730 7464 3719 7464 3731 7464 3720 7465 3721 7465 3717 7465 3717 7466 3721 7466 1310 7466 3717 7467 1310 7467 3722 7467 3722 7468 1310 7468 3724 7468 3722 7469 3724 7469 3723 7469 3723 7470 3724 7470 1319 7470 3723 7471 1319 7471 3719 7471 3719 7472 1319 7472 1318 7472 3719 7473 1318 7473 3731 7473 3731 7474 1318 7474 1317 7474 1003 7475 3725 7475 3738 7475 3738 7476 3725 7476 3726 7476 3738 7477 3726 7477 3727 7477 3727 7478 3726 7478 3728 7478 3727 7479 3728 7479 3743 7479 3743 7480 3728 7480 3716 7480 3743 7481 3716 7481 3729 7481 3729 7482 3716 7482 3730 7482 3729 7483 3730 7483 3744 7483 3744 7484 3730 7484 3731 7484 3744 7485 3731 7485 1316 7485 1316 7486 3731 7486 1317 7486 3733 7487 3732 7487 1007 7487 1007 7488 3732 7488 3649 7488 1007 7489 3649 7489 1008 7489 3741 7490 3654 7490 3740 7490 3740 7491 3654 7491 3733 7491 3745 7492 3648 7492 3742 7492 3742 7493 3648 7493 3734 7493 3742 7494 3734 7494 3647 7494 3745 7495 3652 7495 3653 7495 3653 7496 3646 7496 3745 7496 3745 7497 3646 7497 3735 7497 3745 7498 3735 7498 3648 7498 1002 7499 3739 7499 1004 7499 1004 7500 3739 7500 3740 7500 1004 7501 3740 7501 3736 7501 3736 7502 3740 7502 3733 7502 3736 7503 3733 7503 3737 7503 3737 7504 3733 7504 1007 7504 3727 7505 3739 7505 3738 7505 3738 7506 3739 7506 1002 7506 3738 7507 1002 7507 1003 7507 3727 7508 3742 7508 3739 7508 3739 7509 3742 7509 3647 7509 3739 7510 3647 7510 3740 7510 3740 7511 3647 7511 3645 7511 3740 7512 3645 7512 3741 7512 3727 7513 3743 7513 3742 7513 3742 7514 3743 7514 3729 7514 3742 7515 3729 7515 3745 7515 3745 7516 3729 7516 3744 7516 3745 7517 3744 7517 3652 7517 3652 7518 3744 7518 1316 7518 3652 7519 1316 7519 3746 7519 3761 7520 3756 7520 3747 7520 938 7521 3748 7521 3757 7521 3657 7522 3749 7522 3753 7522 3753 7523 3749 7523 3660 7523 3660 7524 3750 7524 3753 7524 3753 7525 3750 7525 3751 7525 3753 7526 3751 7526 3752 7526 3752 7527 3662 7527 3753 7527 3753 7528 3662 7528 3754 7528 3753 7529 3754 7529 1000 7529 3753 7530 938 7530 3657 7530 3657 7531 938 7531 3757 7531 3657 7532 3757 7532 3755 7532 3755 7533 3757 7533 3658 7533 3747 7534 3756 7534 3757 7534 3757 7535 3756 7535 3656 7535 3757 7536 3656 7536 3658 7536 3758 7537 3759 7537 3747 7537 3747 7538 3759 7538 3760 7538 3747 7539 3760 7539 3761 7539 644 7540 656 7540 3784 7540 3784 7541 656 7541 3793 7541 3784 7542 3793 7542 3785 7542 758 7543 771 7543 3768 7543 3762 7544 3763 7544 3764 7544 3764 7545 3763 7545 757 7545 3764 7546 757 7546 3765 7546 757 7547 3766 7547 3765 7547 3765 7548 3766 7548 3767 7548 3765 7549 3767 7549 3768 7549 3768 7550 3767 7550 759 7550 3768 7551 759 7551 758 7551 3794 7552 3793 7552 756 7552 756 7553 3793 7553 656 7553 3762 7554 3764 7554 3769 7554 3769 7555 3764 7555 3795 7555 3769 7556 3795 7556 787 7556 756 7557 3770 7557 3794 7557 3794 7558 3770 7558 3771 7558 3794 7559 3771 7559 3795 7559 3795 7560 3771 7560 3772 7560 3795 7561 3772 7561 787 7561 3931 7562 3936 7562 3789 7562 3789 7563 3936 7563 3935 7563 3773 7564 3778 7564 2066 7564 3774 7565 2094 7565 2071 7565 3775 7566 2067 7566 3776 7566 3776 7567 2067 7567 3777 7567 3776 7568 3777 7568 3778 7568 3778 7569 3777 7569 3779 7569 3778 7570 3779 7570 2066 7570 2066 7571 3780 7571 3773 7571 3773 7572 3780 7572 3781 7572 3773 7573 3781 7573 3782 7573 3782 7574 3781 7574 2070 7574 3774 7575 2071 7575 3792 7575 2070 7576 2069 7576 3782 7576 3782 7577 2069 7577 3783 7577 3782 7578 3783 7578 3774 7578 3774 7579 3783 7579 2064 7579 3774 7580 2064 7580 2094 7580 3784 7581 3785 7581 3786 7581 3786 7582 3785 7582 3792 7582 3786 7583 3792 7583 3787 7583 3787 7584 3792 7584 2071 7584 3788 7585 3933 7585 3790 7585 3788 7586 3790 7586 3934 7586 3791 7587 640 7587 3928 7587 3928 7588 3930 7588 3791 7588 3791 7589 3930 7589 3789 7589 3791 7590 3789 7590 3790 7590 3790 7591 3789 7591 3935 7591 3790 7592 3935 7592 3934 7592 771 7593 3791 7593 3790 7593 3785 7594 3793 7594 3792 7594 3792 7595 3793 7595 3794 7595 3792 7596 3794 7596 3774 7596 3774 7597 3794 7597 3795 7597 3774 7598 3795 7598 3782 7598 3782 7599 3795 7599 3764 7599 3782 7600 3764 7600 3773 7600 3773 7601 3764 7601 3765 7601 3773 7602 3765 7602 3778 7602 3778 7603 3765 7603 3768 7603 3778 7604 3768 7604 3776 7604 3776 7605 3768 7605 771 7605 3776 7606 771 7606 3775 7606 3775 7607 771 7607 3790 7607 1629 7608 1626 7608 3821 7608 1629 7609 3821 7609 1630 7609 3796 7610 3797 7610 612 7610 612 7611 3797 7611 3798 7611 612 7612 3798 7612 3821 7612 3821 7613 3798 7613 1631 7613 3821 7614 1631 7614 1630 7614 1635 7615 3799 7615 3800 7615 3800 7616 3799 7616 3801 7616 3800 7617 3801 7617 612 7617 612 7618 3801 7618 3802 7618 612 7619 3802 7619 3796 7619 3807 7620 1589 7620 3803 7620 3803 7621 1589 7621 3804 7621 3803 7622 3804 7622 3800 7622 3800 7623 3804 7623 1588 7623 3800 7624 1588 7624 1635 7624 3805 7625 1591 7625 3806 7625 3806 7626 1591 7626 1593 7626 3806 7627 1593 7627 3803 7627 3803 7628 1593 7628 1594 7628 3803 7629 1594 7629 3807 7629 3805 7630 3806 7630 3808 7630 3808 7631 3806 7631 3809 7631 3808 7632 3809 7632 1572 7632 3813 7633 1598 7633 609 7633 609 7634 1598 7634 1597 7634 609 7635 1597 7635 3809 7635 3809 7636 1597 7636 1596 7636 3809 7637 1596 7637 1572 7637 3810 7638 1601 7638 603 7638 603 7639 1601 7639 3811 7639 3811 7640 3812 7640 603 7640 603 7641 3812 7641 1600 7641 603 7642 1600 7642 3813 7642 3813 7643 1600 7643 1599 7643 3813 7644 1599 7644 1598 7644 3810 7645 603 7645 3814 7645 3814 7646 603 7646 3818 7646 3814 7647 3818 7647 1602 7647 1621 7648 3815 7648 3817 7648 3815 7649 3816 7649 3817 7649 3817 7650 3816 7650 3819 7650 3817 7651 3819 7651 3818 7651 3818 7652 3819 7652 1618 7652 3818 7653 1618 7653 1602 7653 1625 7654 1620 7654 3820 7654 3820 7655 1620 7655 1624 7655 3820 7656 1624 7656 3817 7656 3817 7657 1624 7657 1623 7657 3817 7658 1623 7658 1621 7658 1626 7659 1627 7659 3821 7659 3821 7660 1627 7660 3822 7660 3821 7661 3822 7661 3820 7661 3820 7662 3822 7662 3823 7662 3820 7663 3823 7663 1625 7663 3825 7664 3881 7664 3824 7664 3864 7665 3881 7665 3865 7665 3865 7666 3881 7666 3825 7666 3865 7667 3825 7667 3890 7667 3890 7668 3825 7668 630 7668 3872 7669 3826 7669 3877 7669 3877 7670 3826 7670 3825 7670 3877 7671 3825 7671 3827 7671 3827 7672 3825 7672 3824 7672 3867 7673 1345 7673 3828 7673 3828 7674 1345 7674 1337 7674 3828 7675 1337 7675 3829 7675 3829 7676 1337 7676 3830 7676 3829 7677 3830 7677 1338 7677 3838 7678 662 7678 3837 7678 3837 7679 662 7679 1347 7679 3837 7680 1347 7680 3867 7680 3867 7681 1347 7681 1346 7681 3867 7682 1346 7682 1345 7682 3888 7683 3832 7683 3831 7683 3831 7684 3832 7684 3833 7684 664 7685 3834 7685 3833 7685 3833 7686 3834 7686 3835 7686 3833 7687 3835 7687 3831 7687 3839 7688 3880 7688 664 7688 664 7689 3880 7689 3836 7689 664 7690 3836 7690 3834 7690 3837 7691 3870 7691 3838 7691 3838 7692 3870 7692 3863 7692 3838 7693 3863 7693 3839 7693 3839 7694 3863 7694 3862 7694 3839 7695 3862 7695 3880 7695 3840 7696 3832 7696 1298 7696 1298 7697 3832 7697 3841 7697 3888 7698 1522 7698 1521 7698 1521 7699 1520 7699 3888 7699 3888 7700 1520 7700 3842 7700 3888 7701 3842 7701 3832 7701 3832 7702 3842 7702 1508 7702 3832 7703 1508 7703 3841 7703 3843 7704 3924 7704 3854 7704 685 7705 666 7705 3844 7705 3843 7706 3854 7706 1546 7706 3844 7707 3845 7707 685 7707 685 7708 3845 7708 1549 7708 685 7709 1549 7709 3854 7709 3854 7710 1549 7710 1548 7710 3854 7711 1548 7711 1546 7711 730 7712 3846 7712 731 7712 731 7713 3846 7713 3901 7713 731 7714 3901 7714 732 7714 732 7715 3901 7715 642 7715 730 7716 736 7716 3846 7716 3846 7717 736 7717 735 7717 3846 7718 735 7718 3847 7718 3847 7719 735 7719 672 7719 3847 7720 672 7720 3902 7720 3902 7721 672 7721 3848 7721 3902 7722 3848 7722 3849 7722 3849 7723 3848 7723 3851 7723 3849 7724 3851 7724 3850 7724 3850 7725 3851 7725 3852 7725 3852 7726 3851 7726 667 7726 3852 7727 667 7727 3905 7727 3905 7728 667 7728 3853 7728 3853 7729 667 7729 683 7729 3853 7730 683 7730 3907 7730 3907 7731 683 7731 3906 7731 3906 7732 683 7732 685 7732 3906 7733 685 7733 3854 7733 3858 7734 3917 7734 3860 7734 3923 7735 3855 7735 3856 7735 3856 7736 3855 7736 3860 7736 3856 7737 3860 7737 3916 7737 3916 7738 3860 7738 3917 7738 3857 7739 3858 7739 3859 7739 3859 7740 3858 7740 3860 7740 3859 7741 3860 7741 3920 7741 3920 7742 3860 7742 3861 7742 3862 7743 3863 7743 3874 7743 3876 7744 3878 7744 3873 7744 3864 7745 3865 7745 3884 7745 3881 7746 3864 7746 3882 7746 3824 7747 3881 7747 3866 7747 3871 7748 651 7748 3826 7748 3824 7749 3878 7749 3827 7749 3827 7750 3878 7750 3876 7750 3827 7751 3876 7751 3877 7751 652 7752 651 7752 3868 7752 3868 7753 651 7753 3871 7753 3868 7754 3871 7754 3869 7754 3829 7755 652 7755 3828 7755 3828 7756 652 7756 3868 7756 3828 7757 3868 7757 3867 7757 3867 7758 3868 7758 3869 7758 3867 7759 3869 7759 3837 7759 3837 7760 3869 7760 3870 7760 3863 7761 3870 7761 3874 7761 3874 7762 3870 7762 3869 7762 3874 7763 3869 7763 3875 7763 3875 7764 3869 7764 3871 7764 3875 7765 3871 7765 3872 7765 3872 7766 3871 7766 3826 7766 3880 7767 3862 7767 3873 7767 3873 7768 3862 7768 3874 7768 3873 7769 3874 7769 3876 7769 3876 7770 3874 7770 3875 7770 3876 7771 3875 7771 3877 7771 3877 7772 3875 7772 3872 7772 3879 7773 3834 7773 3836 7773 3824 7774 3866 7774 3878 7774 3878 7775 3866 7775 3879 7775 3878 7776 3879 7776 3873 7776 3873 7777 3879 7777 3836 7777 3873 7778 3836 7778 3880 7778 3883 7779 3831 7779 3835 7779 3881 7780 3882 7780 3866 7780 3866 7781 3882 7781 3883 7781 3866 7782 3883 7782 3879 7782 3879 7783 3883 7783 3835 7783 3879 7784 3835 7784 3834 7784 3864 7785 3884 7785 3882 7785 3882 7786 3884 7786 3885 7786 3882 7787 3885 7787 3883 7787 3883 7788 3885 7788 3888 7788 3883 7789 3888 7789 3831 7789 3891 7790 935 7790 3884 7790 1522 7791 3888 7791 1527 7791 1527 7792 3888 7792 3889 7792 3884 7793 935 7793 3885 7793 935 7794 3886 7794 3885 7794 3885 7795 3886 7795 3887 7795 3885 7796 3887 7796 3888 7796 3888 7797 3887 7797 929 7797 3888 7798 929 7798 3889 7798 3865 7799 3890 7799 3884 7799 3884 7800 3890 7800 933 7800 3884 7801 933 7801 3891 7801 3915 7802 3856 7802 3916 7802 3892 7803 3893 7803 3909 7803 3894 7804 3895 7804 3896 7804 3900 7805 643 7805 3914 7805 3897 7806 642 7806 3901 7806 3898 7807 3899 7807 3913 7807 3913 7808 3899 7808 639 7808 3913 7809 639 7809 3897 7809 3900 7810 3914 7810 3861 7810 3897 7811 3901 7811 3913 7811 3913 7812 3901 7812 3846 7812 3913 7813 3846 7813 3911 7813 3846 7814 3847 7814 3911 7814 3911 7815 3847 7815 3902 7815 3911 7816 3902 7816 3903 7816 3902 7817 3849 7817 3903 7817 3903 7818 3849 7818 3850 7818 3903 7819 3850 7819 3904 7819 3850 7820 3852 7820 3904 7820 3904 7821 3852 7821 3905 7821 3904 7822 3905 7822 3908 7822 3854 7823 3894 7823 3906 7823 3906 7824 3894 7824 3896 7824 3906 7825 3896 7825 3907 7825 3907 7826 3896 7826 3908 7826 3907 7827 3908 7827 3853 7827 3853 7828 3908 7828 3905 7828 3895 7829 3892 7829 3896 7829 3896 7830 3892 7830 3909 7830 3896 7831 3909 7831 3908 7831 3908 7832 3909 7832 3918 7832 3908 7833 3918 7833 3904 7833 3904 7834 3918 7834 3910 7834 3904 7835 3910 7835 3903 7835 3903 7836 3910 7836 3912 7836 3903 7837 3912 7837 3911 7837 3911 7838 3912 7838 3919 7838 3911 7839 3919 7839 3913 7839 3913 7840 3919 7840 3914 7840 3913 7841 3914 7841 3898 7841 3898 7842 3914 7842 643 7842 3893 7843 3915 7843 3909 7843 3909 7844 3915 7844 3916 7844 3909 7845 3916 7845 3918 7845 3918 7846 3916 7846 3917 7846 3918 7847 3917 7847 3910 7847 3910 7848 3917 7848 3858 7848 3910 7849 3858 7849 3912 7849 3912 7850 3858 7850 3857 7850 3912 7851 3857 7851 3919 7851 3919 7852 3857 7852 3859 7852 3919 7853 3859 7853 3914 7853 3914 7854 3859 7854 3920 7854 3914 7855 3920 7855 3861 7855 3894 7856 3921 7856 3895 7856 3895 7857 3921 7857 3922 7857 3895 7858 3922 7858 3892 7858 3892 7859 3922 7859 917 7859 3892 7860 917 7860 3893 7860 3893 7861 917 7861 914 7861 3893 7862 914 7862 3915 7862 3915 7863 914 7863 915 7863 3915 7864 915 7864 3856 7864 3856 7865 915 7865 3923 7865 3854 7866 3924 7866 1550 7866 1550 7867 3925 7867 3854 7867 3854 7868 3925 7868 922 7868 3854 7869 922 7869 3894 7869 3894 7870 922 7870 3926 7870 3894 7871 3926 7871 3921 7871 640 7872 614 7872 3927 7872 640 7873 3927 7873 3928 7873 3928 7874 3927 7874 3929 7874 3928 7875 3929 7875 3930 7875 3930 7876 3929 7876 3931 7876 3930 7877 3931 7877 3789 7877 3932 7878 3933 7878 3788 7878 3932 7879 3788 7879 602 7879 602 7880 3788 7880 3934 7880 602 7881 3934 7881 610 7881 610 7882 3934 7882 3935 7882 610 7883 3935 7883 3936 7883

+
+
+
+
+ + + + + + + + + + + + + + + + +
diff --git a/URDFs/sr_description/meshes/components/f_distal/bt_sp/f_distal_bt_sp.dae b/URDFs/sr_description/meshes/components/f_distal/bt_sp/f_distal_bt_sp.dae new file mode 100644 index 0000000..fe58c58 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_distal/bt_sp/f_distal_bt_sp.dae @@ -0,0 +1,128 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:38:06 + 2022-02-10T09:38:06 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.248 0.68 0.336 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + -6.357494 -6.75325 29.10017 -6.130147 -7.19108 28.94184 -5.924187 -6.914879 29.48484 -6.031842 -6.523951 29.7254 4.66999 -7.93175 29.61421 5.007694 -7.724135 29.55431 4.759533 -7.409827 30.12325 4.459158 -7.492341 30.27258 3.796751 9.05961 28.70727 3.523746 9.332245 28.71916 3.365565 9.285593 28.91112 3.575551 8.945204 29.0246 -4.25608 8.940427 28.30541 -4.50148 8.739069 28.20744 -4.385713 8.589134 28.53703 -4.191161 8.69139 28.66566 5.164283 8.588023 3.976665 4.876677 8.756595 3.985315 5.253551 8.545804 3.988217 5.507101 8.385594 3.984412 -4.277998 8.506994 28.75294 -4.526146 8.39814 28.56336 -6.13907 7.938196 3.988768 -6.386789 7.747265 3.991377 -6.395797 7.741821 4.040007 -6.073765 7.990608 4.039587 -6.397624 7.741595 4.329779 -6.062654 8.000522 4.32962 -6.399413 7.74041 5.3259 -6.061621 8.001731 5.325253 -6.409022 7.731755 6.889887 -6.063134 8.000456 6.885754 -6.436666 7.706383 8.626496 -6.067146 7.996743 8.615322 -6.445129 7.69714 10.36597 -6.065603 7.997599 10.36803 -6.418894 7.717509 12.11951 -6.055126 8.005756 12.12546 -6.404771 7.727993 13.87953 -6.049722 8.009727 13.88489 -6.433272 7.70444 15.64654 -6.061378 7.99997 15.64716 -6.430684 7.707047 17.40801 -6.06052 8.000837 17.40711 -6.423048 7.713973 19.16704 -6.058285 8.002953 19.16617 -6.41989 7.71718 20.92426 -6.05917 8.002716 20.9247 -6.41592 7.721398 22.66522 -6.070927 7.994681 22.67639 -6.376527 7.755496 24.30697 -6.088754 7.982728 24.36892 -6.165074 7.922974 25.61044 -5.940869 8.092399 25.78758 -5.801313 8.188416 26.42325 -5.591503 8.333909 26.65967 -5.401376 8.449325 26.99766 -5.192024 8.58618 27.21767 -5.036507 8.641843 27.46101 -4.817121 8.795639 27.63536 -4.748679 8.727878 27.84789 -4.492576 8.935961 27.97935 5.263176 8.543108 4.037837 5.589548 8.33734 4.036511 5.262462 8.545373 4.329097 5.601436 8.331892 4.328423 5.253469 8.55152 5.326086 5.599406 8.333858 5.325477 5.238829 8.560684 6.886415 5.594207 8.337236 6.886063 5.222577 8.570734 8.614976 5.58879 8.340508 8.615123 5.206614 8.580595 10.37069 5.583312 8.343834 10.37086 5.193773 8.588537 12.12927 5.578342 8.347004 12.12966 5.189289 8.591337 13.8882 5.576366 8.348409 13.88863 5.188375 8.59194 15.6472 5.575628 8.34907 15.6476 5.188225 8.592079 17.4062 5.575063 8.349658 17.40654 5.188414 8.592024 19.16524 5.574555 8.350235 19.16561 5.190185 8.591073 20.92413 5.575469 8.349783 20.92452 5.1962 8.58765 22.68089 5.581751 8.34539 22.68029 5.196852 8.587227 24.41737 5.586594 8.340929 24.40475 5.135028 8.624117 26.02749 5.498836 8.396875 25.9511 4.899071 8.759922 27.21009 5.203703 8.578304 26.99555 4.543155 8.947531 27.82118 4.806535 8.798222 27.60569 4.18207 9.115184 28.18302 4.411666 8.968242 28.04382 3.816232 9.255045 28.48457 4.061736 9.049736 28.42079 3.572163 -8.582118 9.147506 3.875523 -8.472003 9.276745 4.104078 -8.643674 9.546887 3.778837 -8.83407 9.43977 4.43887 -8.85571 9.965812 4.097073 -9.079872 9.857392 4.75577 -9.15275 10.50049 4.378961 -9.432432 10.39097 5.100952 -9.420923 11.12394 4.708973 -9.722868 11.00556 5.459273 -9.700529 11.90207 5.047229 -10.04845 11.79965 5.782037 -9.987969 12.8077 5.378551 -10.34208 12.7102 6.107057 -10.20197 13.83826 5.687902 -10.58391 13.75481 6.38285 -10.38939 15.0387 5.942357 -10.8017 14.95915 6.604795 -10.50455 16.31885 6.161866 -10.92248 16.25032 6.754791 -10.54608 17.6618 6.313472 -10.96574 17.61406 6.799349 -10.54043 19.07774 6.353235 -10.95563 19.04244 6.791643 -10.43355 20.46644 6.32596 -10.85219 20.46679 6.713667 -10.25328 21.85427 6.223712 -10.67738 21.87946 6.569076 -10.00969 23.20674 6.065589 -10.43109 23.25139 6.348814 -9.723248 24.50821 5.851207 -10.12761 24.56204 6.093803 -9.386904 25.72636 5.642862 -9.741848 25.77967 5.799177 -9.026816 26.85064 5.40343 -9.323889 26.90292 5.541343 -8.613517 27.84213 5.168291 -8.894834 27.87119 5.293243 -8.152626 28.75128 4.920796 -8.415664 28.79203 -5.003184 -7.809041 9.792239 -4.919827 -8.076631 9.85871 -5.144513 -8.262012 10.1971 -5.321724 -7.873913 10.14058 -5.470678 -8.46139 10.67792 -5.673114 -8.006749 10.60127 -5.819246 -8.590259 11.19715 -6.021872 -8.17908 11.15142 -6.163554 -8.772847 11.85374 -6.398924 -8.336119 11.81466 -6.49132 -8.992583 12.63306 -6.767885 -8.481462 12.57185 -6.83998 -9.109251 13.4765 -7.106985 -8.63154 13.43023 -7.143057 -9.23872 14.4588 -7.434556 -8.756937 14.43555 -7.380866 -9.37562 15.54881 -7.729655 -8.814579 15.51709 -7.590056 -9.426679 16.68753 -7.946235 -8.864408 16.67277 -7.731583 -9.442034 17.90724 -8.08113 -8.909089 17.91623 -7.809164 -9.394022 19.1429 -8.184679 -8.837684 19.17956 -7.796933 -9.32599 20.40206 -8.197479 -8.739147 20.46003 -7.759816 -9.163208 21.6485 -8.122734 -8.6201 21.74334 -7.667119 -8.946258 22.86794 -7.98914 -8.452844 22.99477 -7.493409 -8.716469 24.05345 -7.805787 -8.237139 24.19617 -7.245748 -8.476113 25.20258 -7.586774 -7.95907 25.34502 -6.980472 -8.194002 26.27276 -7.312724 -7.663572 26.43606 -6.726671 -7.856177 27.24575 -7.003453 -7.364103 27.43102 -6.409854 -7.510487 28.19118 -6.665625 -7.069642 28.33252 -6.131884 -7.707531 28.3242 -5.885277 -7.351486 29.05884 -5.769942 -7.930025 28.48685 -5.492717 -7.553309 29.25681 -5.366386 -8.209383 28.6041 -5.10384 -7.775898 29.40756 -4.971761 -8.411152 28.75083 -4.741461 -7.922933 29.5666 -4.444183 -8.640539 28.92949 -4.205161 -8.135552 29.7477 -3.933918 -8.800786 29.13535 -3.714903 -8.283339 29.9315 -3.39943 -8.944149 29.30643 -3.189539 -8.409844 30.09262 -2.757901 -9.119226 29.43175 -2.580582 -8.556561 30.22581 -2.126148 -9.25906 29.51872 -2.002309 -8.660219 30.32142 -1.467724 -9.361701 29.59045 -1.348944 -8.742966 30.40859 -0.7699479 -9.407056 29.66094 -0.7196161 -8.764362 30.48471 -0.0419811 -9.427245 29.69377 -0.03977179 -8.795366 30.49707 0.636435 -9.416126 29.66814 0.600157 -8.770956 30.49051 1.318057 -9.380369 29.60455 1.245749 -8.752991 30.42002 1.965024 -9.290437 29.53648 1.864923 -8.683506 30.33826 2.662798 -9.140445 29.44675 2.492494 -8.57213 30.24442 3.317144 -8.967748 29.32278 3.081303 -8.434607 30.12095 3.861903 -8.825981 29.15552 3.639283 -8.300412 29.96062 4.351287 -8.676523 28.96308 4.10005 -8.169201 29.78921 -6.43983 -8.110662 27.34086 -6.075726 -8.34975 27.51155 -5.627809 -8.659503 27.6686 -5.233775 -8.883213 27.81612 -4.736529 -9.10462 28.00782 -4.220285 -9.291273 28.21364 -3.635097 -9.496652 28.36795 -3.001239 -9.687941 28.48779 -2.290046 -9.85859 28.58571 -1.602274 -9.984766 28.64957 -0.7843473 -10.04613 28.74109 -0.0304687 -10.05898 28.78892 0.6841607 -10.05519 28.74756 1.432625 -10.008 28.66557 2.11354 -9.893486 28.60805 2.893511 -9.712214 28.50606 3.552225 -9.523682 28.38348 4.120831 -9.331187 28.23809 4.624062 -9.149835 28.0499 -6.677905 -8.504597 26.34268 -6.36946 -8.729833 26.47943 -5.915579 -9.0397 26.6633 -5.500966 -9.287436 26.83727 -5.014233 -9.526041 27.02413 -4.439929 -9.791796 27.19621 -3.823315 -10.04437 27.3293 -3.17581 -10.25865 27.44703 -2.452674 -10.44399 27.54451 -1.731124 -10.59101 27.6047 -0.845075 -10.68137 27.68059 -0.05288589 -10.7179 27.69854 0.717633 -10.69339 27.6882 1.545987 -10.61688 27.62078 2.280674 -10.47878 27.56585 3.089414 -10.27884 27.4632 3.752619 -10.07057 27.34219 4.363154 -9.830729 27.2076 4.897747 -9.592443 27.04516 -6.894612 -8.854882 25.27476 -6.609251 -9.091223 25.39606 -6.19296 -9.389358 25.56044 -5.733524 -9.698004 25.72716 -5.258763 -9.967162 25.88035 -4.648059 -10.28114 26.04117 -4.043579 -10.54279 26.17241 -3.336194 -10.79769 26.29734 -2.608354 -11.00089 26.39211 -1.844631 -11.16426 26.45977 -0.9240069 -11.27558 26.51967 -0.09079563 -11.31793 26.53534 0.7436965 -11.2922 26.52795 1.646851 -11.1932 26.47388 2.432399 -11.04011 26.41054 3.233624 -10.8281 26.3144 3.931251 -10.58703 26.19405 4.554056 -10.32748 26.06148 5.142906 -10.03315 25.90662 -7.126463 -9.121362 24.11856 -6.798647 -9.428679 24.23677 -6.43665 -9.713956 24.36305 -5.957242 -10.06347 24.51307 -5.493031 -10.36049 24.64384 -4.881467 -10.69973 24.78679 -4.265126 -10.99268 24.90728 -3.504014 -11.29096 25.0249 -2.753779 -11.52098 25.11258 -1.933095 -11.70803 25.18275 -0.9903925 -11.83284 25.23367 -0.1087193 -11.87874 25.25117 0.7828481 -11.85246 25.24164 1.741835 -11.73789 25.19464 2.56978 -11.56683 25.13 3.362529 -11.34053 25.04431 4.113741 -11.05725 24.93297 4.743487 -10.77152 24.81535 5.368382 -10.43336 24.67403 -7.329868 -9.335105 22.90217 -6.959384 -9.709878 23.00301 -6.629871 -10.00297 23.091 -6.164409 -10.36432 23.21094 -5.666908 -10.71436 23.331 -5.082591 -11.06357 23.4459 -4.445198 -11.3949 23.54604 -3.672382 -11.71873 23.64424 -2.884899 -11.97978 23.72454 -1.996104 -12.1958 23.79239 -1.04021 -12.33108 23.83566 -0.1109383 -12.38132 23.85227 0.8350947 -12.35096 23.84198 1.831118 -12.2242 23.80134 2.699769 -12.03052 23.74107 3.5028 -11.78229 23.66448 4.296272 -11.46144 23.56715 4.94928 -11.13586 23.46952 5.575028 -10.7718 23.35127 -7.471887 -9.517437 21.64396 -7.102524 -9.908166 21.6955 -6.74753 -10.25283 21.76138 -6.314274 -10.61186 21.84666 -5.779263 -11.01113 21.95301 -5.220142 -11.37014 22.03757 -4.551984 -11.7408 22.10513 -3.799999 -12.07769 22.16996 -2.989686 -12.36285 22.23895 -2.048452 -12.60281 22.29935 -1.081179 -12.74841 22.33544 -0.1088665 -12.80369 22.353 0.8825557 -12.76837 22.34045 1.900786 -12.63166 22.30743 2.810783 -12.41489 22.25421 3.632131 -12.14346 22.1887 4.427594 -11.80143 22.122 5.102267 -11.43862 22.05674 5.694827 -11.06922 21.96746 -7.508163 -9.699919 20.37313 -7.184998 -10.06216 20.33345 -6.827086 -10.42578 20.36836 -6.419424 -10.78285 20.42886 -5.885191 -11.19643 20.51014 -5.321815 -11.58239 20.57683 -4.639739 -11.98139 20.59606 -3.889631 -12.34204 20.62314 -3.065953 -12.64684 20.68122 -2.111449 -12.89998 20.72545 -1.124028 -13.05937 20.75387 -0.1054756 -13.12181 20.77566 0.9177029 -13.08122 20.76115 1.937307 -12.93703 20.74245 2.880775 -12.70311 20.69914 3.715213 -12.41477 20.6492 4.491952 -12.0584 20.6316 5.197104 -11.65853 20.60427 5.776733 -11.27492 20.53139 -7.49692 -9.800904 19.12587 -7.203605 -10.13759 19.06142 -6.831735 -10.52352 19.04916 -6.41788 -10.90463 19.03408 -5.916252 -11.30815 19.03036 -5.354991 -11.70716 19.04479 -4.687686 -12.11145 19.02775 -3.92995 -12.48919 19.03644 -3.092601 -12.81196 19.07705 -2.157185 -13.07163 19.09501 -1.157927 -13.24329 19.10431 -0.09707152 -13.31096 19.11452 0.9486096 -13.2635 19.11735 1.960319 -13.11155 19.12908 2.914459 -12.86729 19.10095 3.770056 -12.55833 19.06911 4.542938 -12.18801 19.08454 5.230879 -11.78553 19.06992 5.817171 -11.38063 19.04134 -7.445474 -9.8097 17.87182 -7.123853 -10.17707 17.77402 -6.777582 -10.54174 17.7044 -6.367007 -10.92362 17.633 -5.872933 -11.32957 17.58382 -5.328553 -11.7184 17.53451 -4.68948 -12.11542 17.50446 -3.929055 -12.49869 17.47617 -3.085377 -12.83259 17.46245 -2.164125 -13.09766 17.44567 -1.163605 -13.2768 17.43719 -0.09740555 -13.34696 17.43583 0.9512107 -13.29768 17.44041 1.957286 -13.14077 17.45563 2.90513 -12.89166 17.4656 3.761171 -12.57437 17.48352 4.543419 -12.1954 17.52327 5.205009 -11.79831 17.53099 5.79069 -11.38991 17.56838 -7.323316 -9.765047 16.59985 -6.992674 -10.13257 16.49007 -6.635392 -10.50328 16.39824 -6.245328 -10.85696 16.28308 -5.762905 -11.24651 16.17396 -5.224302 -11.62672 16.05636 -4.602611 -12.01238 16.0111 -3.869032 -12.38009 15.93938 -3.023025 -12.71485 15.87727 -2.115371 -12.9739 15.82823 -1.134108 -13.1473 15.80035 -0.1000101 -13.21561 15.78947 0.9252305 -13.17018 15.79691 1.917659 -13.01706 15.82194 2.863647 -12.76776 15.86568 3.705312 -12.45486 15.93548 4.459741 -12.09594 16.01971 5.094433 -11.715 16.0409 5.651526 -11.33171 16.14879 -7.100612 -9.724205 15.43616 -6.796227 -10.04132 15.2847 -6.44859 -10.36936 15.14285 -6.042466 -10.72481 15.00087 -5.591404 -11.07123 14.8495 -5.047214 -11.43803 14.69034 -4.432738 -11.79693 14.56022 -3.728038 -12.13916 14.46059 -2.92294 -12.44878 14.36883 -2.050063 -12.69413 14.29642 -1.093254 -12.85976 14.24998 -0.08847713 -12.92382 14.23062 0.9001579 -12.87994 14.24298 1.849662 -12.73593 14.28332 2.748703 -12.50427 14.35012 3.565293 -12.21142 14.44681 4.3043 -11.87479 14.56158 4.913921 -11.53025 14.67226 5.464339 -11.16616 14.81976 -6.842257 -9.597936 14.34285 -6.522435 -9.919403 14.17907 -6.188186 -10.19935 13.9824 -5.79965 -10.50598 13.80893 -5.342037 -10.83329 13.63276 -4.825913 -11.15552 13.45029 -4.225057 -11.48651 13.29124 -3.547849 -11.78804 13.13826 -2.758723 -12.06947 13.00913 -1.922659 -12.29194 12.92313 -1.03045 -12.43105 12.85507 -0.1021169 -12.4854 12.82543 0.8215222 -12.45095 12.8421 1.71985 -12.32806 12.89662 2.591236 -12.11603 12.97885 3.389488 -11.85547 13.12091 4.093312 -11.57171 13.30314 4.687843 -11.25223 13.43971 5.210879 -10.92971 13.60195 -6.566088 -9.416238 13.35209 -6.24208 -9.706458 13.17251 -5.878714 -9.996558 12.97268 -5.485635 -10.2732 12.76778 -5.042753 -10.53763 12.54319 -4.517123 -10.82628 12.3322 -3.940146 -11.10752 12.14718 -3.302358 -11.36378 11.97943 -2.584957 -11.59832 11.83898 -1.797643 -11.79612 11.75558 -0.9561756 -11.90778 11.66813 -0.09380888 -11.95002 11.62878 0.7607112 -11.91819 11.64099 1.591986 -11.81422 11.69791 2.408028 -11.62633 11.77909 3.152363 -11.41304 11.94262 3.827489 -11.17175 12.14121 4.395186 -10.9119 12.32259 4.926279 -10.62306 12.51964 -6.224244 -9.283327 12.51405 -5.91467 -9.509235 12.3004 -5.561704 -9.722638 12.05709 -5.136141 -9.97964 11.822 -4.690325 -10.22649 11.60508 -4.201021 -10.44639 11.3775 -3.655351 -10.67664 11.18903 -3.052181 -10.89437 11.02258 -2.397622 -11.09672 10.89929 -1.668941 -11.23687 10.77238 -0.8698569 -11.32371 10.67498 -0.0508157 -11.36093 10.64233 0.7457056 -11.32577 10.65051 1.49318 -11.24989 10.72572 2.225777 -11.10412 10.82492 2.920714 -10.92009 10.97286 3.540048 -10.73168 11.16807 4.081253 -10.52508 11.36207 4.592323 -10.29955 11.5916 -5.878269 -9.067408 11.73709 -5.541998 -9.308194 11.53263 -5.193435 -9.495727 11.29745 -4.800977 -9.675546 11.04916 -4.380414 -9.86419 10.83314 -3.886589 -10.06644 10.61867 -3.353785 -10.25869 10.42696 -2.769504 -10.42066 10.24049 -2.143535 -10.58963 10.12082 -1.48369 -10.70147 10.00814 -0.7791002 -10.74783 9.904295 -0.04330599 -10.77394 9.874292 0.6744819 -10.75344 9.890419 1.329076 -10.71152 9.97356 2.021049 -10.58727 10.06978 2.686148 -10.42816 10.20355 3.261484 -10.29475 10.40084 3.778196 -10.14333 10.61195 4.279013 -9.931301 10.8119 -5.544659 -8.823265 11.05443 -5.19865 -9.007952 10.82334 -4.841508 -9.196777 10.61818 -4.442312 -9.390467 10.40969 -4.031711 -9.55518 10.20828 -3.580076 -9.68964 9.995205 -3.083895 -9.834115 9.813306 -2.53809 -9.969308 9.647217 -1.963942 -10.09548 9.527813 -1.346798 -10.20553 9.444621 -0.715109 -10.24382 9.360161 -0.07059907 -10.25775 9.327282 0.5670538 -10.25463 9.349664 1.17703 -10.21435 9.409718 1.829025 -10.08761 9.475043 2.465185 -9.976345 9.621304 2.998047 -9.874239 9.79872 3.47872 -9.743968 9.976538 3.957773 -9.59709 10.19039 -5.192986 -8.695345 10.54604 -4.865448 -8.823333 10.31358 -4.530445 -8.9376 10.09543 -4.167636 -9.057394 9.889021 -3.758342 -9.214503 9.71128 -3.296814 -9.362683 9.527397 -2.831903 -9.473087 9.356498 -2.326927 -9.565223 9.19892 -1.769447 -9.661976 9.078494 -1.207868 -9.727787 8.987162 -0.6379143 -9.76827 8.929438 -0.04849606 -9.779892 8.904393 0.5348673 -9.787337 8.932798 1.090696 -9.770137 8.99617 1.676619 -9.671894 9.05892 2.26434 -9.564421 9.175602 2.754055 -9.487871 9.331547 3.211237 -9.386084 9.497504 3.678581 -9.236702 9.678384 -4.867921 -8.485016 10.07739 -4.541655 -8.633969 9.885527 -4.216272 -8.746667 9.695137 -3.875564 -8.841595 9.508383 -3.506215 -8.921956 9.322937 -3.099164 -9.004056 9.146741 -2.662856 -9.101697 9.000676 -2.169931 -9.201927 8.867301 -1.654358 -9.2782 8.754552 -1.120965 -9.331295 8.669241 -0.5943091 -9.337117 8.599806 -0.06503176 -9.339074 8.572568 0.4710944 -9.349039 8.598391 1.010539 -9.344457 8.661452 1.550199 -9.275624 8.725783 2.051001 -9.185902 8.815114 2.515802 -9.096748 8.935472 2.971218 -9.003537 9.083228 3.397861 -8.917943 9.25745 -4.68796 -8.163187 9.707105 -4.364973 -8.28898 9.522902 -4.017624 -8.422008 9.346826 -3.651428 -8.559283 9.185154 -3.280681 -8.653697 9.021198 -2.907694 -8.697042 8.853287 -2.520021 -8.726883 8.700261 -2.062864 -8.802142 8.577095 -1.557085 -8.897245 8.486474 -1.038002 -8.92683 8.395943 -0.5260387 -8.942319 8.339337 -0.03762698 -8.951058 8.322223 0.4607089 -8.945702 8.336147 0.9555264 -8.931694 8.383818 1.431116 -8.908847 8.460577 1.911206 -8.799786 8.527039 2.367134 -8.713191 8.63265 2.796527 -8.683346 8.793888 3.197312 -8.649355 8.972472 3.506956 9.395212 28.66546 3.240667 9.466652 28.8527 3.181841 9.51434 28.85149 2.913562 9.589606 29.00931 2.810668 9.630653 29.03846 2.575678 9.690237 29.16086 2.377054 9.746579 29.22433 2.191404 9.783623 29.31017 1.939833 9.84273 29.37656 1.775634 9.866287 29.44158 1.501093 9.916683 29.49074 1.323578 9.935054 29.54651 0.9641869 9.982759 29.5906 0.8743372 9.987555 29.6212 0.4206362 10.01996 29.64774 0.3435888 10.02043 29.67091 -0.08041501 10.03028 29.66527 -0.08158957 10.02828 29.68466 -0.6087561 10.01123 29.63653 -0.5325196 10.01189 29.65996 -1.06158 9.973875 29.57919 -0.9627513 9.980163 29.61228 -1.59417 9.902549 29.46875 -1.431721 9.920126 29.52394 -2.019485 9.824868 29.3472 -1.832439 9.855346 29.4234 -2.467662 9.72188 29.18418 -2.242406 9.769319 29.28609 -2.869314 9.610563 29.00606 -2.624525 9.674828 29.13567 -3.252954 9.488043 28.80846 -2.981603 9.565814 28.96936 -3.591199 9.3644 28.60966 -3.336074 9.434023 28.79481 -3.913996 9.230604 28.39687 -3.64968 9.293053 28.62873 -4.225572 9.081478 28.1793 -3.983406 9.0964 28.46825 3.856384 9.261736 28.41052 3.476704 9.412009 28.65245 3.084389 9.548333 28.86534 2.648018 9.678946 29.06418 2.198658 9.790213 29.23023 1.676393 9.89034 29.37879 1.065973 9.973555 29.50005 0.5051334 10.01699 29.56335 -0.0818547 10.03014 29.58413 -0.7048668 10.0062 29.5494 -1.208786 9.957969 29.47902 -1.762531 9.875472 29.356 -2.271682 9.771183 29.19916 -2.733362 9.652315 29.02097 -3.185909 9.512827 28.80836 -3.56668 9.378108 28.59916 -3.915429 9.238002 28.37072 -4.246492 9.090868 28.12484 -4.532263 8.950723 27.89035 4.235455 9.097249 28.05142 3.839195 9.270767 28.29827 3.402244 9.439806 28.51174 2.929081 9.597359 28.69005 2.413785 9.738843 28.84407 1.81635 9.865087 28.98796 1.193914 9.957972 29.09144 0.5918999 10.01052 29.14982 -0.08495998 10.02773 29.17109 -0.7964089 9.99838 29.1369 -1.378681 9.935652 29.06598 -1.931927 9.843904 28.95923 -2.494824 9.717384 28.80861 -3.03744 9.562108 28.63207 -3.503384 9.40294 28.45618 -3.911201 9.240945 28.26227 -4.29243 9.069744 28.01042 -4.625132 8.904918 27.74953 -4.917747 8.746523 27.49028 4.583011 8.929461 27.38907 4.16599 9.131319 27.5528 3.706471 9.325683 27.65103 3.165481 9.520464 27.71323 2.559779 9.698863 27.76418 1.904831 9.845148 27.8144 1.259186 9.947791 27.84326 0.6223843 10.00679 27.86086 -0.09987843 10.02569 27.86978 -0.8371458 9.994389 27.85645 -1.45977 9.92376 27.83235 -2.022606 9.82556 27.7991 -2.591427 9.692523 27.75179 -3.188436 9.512869 27.69852 -3.733817 9.312767 27.64277 -4.234814 9.097637 27.53586 -4.661822 8.887899 27.3394 -5.01176 8.695351 27.13094 -5.327659 8.505106 26.90084 4.759527 8.837166 26.08414 4.288298 9.075712 26.13211 3.805824 9.286594 26.15551 3.224677 9.500107 26.16783 2.597217 9.687967 26.17726 1.932109 9.837329 26.18976 1.275761 9.944189 26.19027 0.6258164 10.00542 26.19197 -0.1116836 10.02418 26.19587 -0.8480828 9.993138 26.19088 -1.479197 9.920711 26.18574 -2.045318 9.820863 26.18051 -2.605897 9.689029 26.17443 -3.202718 9.507094 26.17298 -3.783529 9.290012 26.16903 -4.336682 9.049394 26.13371 -4.817433 8.805157 26.07061 -5.26125 8.548144 26.0013 -5.646435 8.300114 25.91322 4.788268 8.821319 24.42842 4.306429 9.067276 24.43582 3.81862 9.280777 24.43984 3.215783 9.502344 24.44266 2.601989 9.686717 24.44378 1.953348 9.831315 24.44852 1.284179 9.941658 24.44464 0.6246908 10.00449 24.44384 -0.1198198 10.02275 24.44698 -0.8511397 9.992598 24.44341 -1.481158 9.920296 24.44174 -2.047579 9.820331 24.44144 -2.602757 9.68974 24.44276 -3.198727 9.505851 24.45013 -3.821052 9.271612 24.45363 -4.357981 9.039276 24.44167 -4.836686 8.793909 24.43044 -5.327877 8.506921 24.41517 -5.751983 8.228827 24.39804 4.773182 8.829008 22.68439 4.301413 9.069794 22.68434 3.815219 9.281375 22.68558 3.196768 9.508329 22.6875 2.612526 9.685194 22.68641 2.001277 9.820926 22.68845 1.303712 9.937336 22.68568 0.629909 10.00321 22.68541 -0.1153429 10.02127 22.68854 -0.8468849 9.992352 22.68532 -1.475383 9.920799 22.68421 -2.04676 9.820097 22.68431 -2.605186 9.687977 22.68576 -3.228622 9.491522 22.69074 -3.9346 9.224785 22.68799 -4.393608 9.025739 22.68648 -4.825156 8.800587 22.68852 -5.32745 8.506937 22.68306 -5.749222 8.231375 22.6797 4.757804 8.836754 20.9272 4.29581 9.072429 20.92612 3.810116 9.282526 20.9272 3.174018 9.515228 20.92942 2.610101 9.686343 20.92742 2.018719 9.816741 20.92846 1.310594 9.935543 20.92629 0.6320679 10.00247 20.92631 -0.111514 10.02005 20.92948 -0.8385135 9.992747 20.92653 -1.458451 9.922644 20.92594 -2.046225 9.819382 20.92582 -2.606626 9.686862 20.92678 -3.237221 9.486371 20.93049 -3.970902 9.210092 20.92486 -4.394809 9.026576 20.92676 -4.802714 8.812302 20.9316 -5.318237 8.51181 20.92686 -5.743829 8.234924 20.92467 4.752805 8.838793 19.16839 4.29421 9.072854 19.16722 3.805567 9.283314 19.1685 3.150269 9.5223 19.17118 2.601849 9.688639 19.16861 2.020441 9.815659 19.16926 1.311478 9.934906 19.16718 0.6326013 10.00195 19.16722 -0.1089937 10.01893 19.17046 -0.828427 9.993377 19.16788 -1.438241 9.92445 19.16813 -2.057083 9.81587 19.16788 -2.61241 9.684953 19.16807 -3.235926 9.485546 19.17131 -3.966881 9.211833 19.16515 -4.381896 9.032917 19.16777 -4.781193 8.822957 19.17324 -5.309854 8.516057 19.16822 -5.741935 8.235887 19.16591 4.751835 8.838618 17.40937 4.294067 9.07248 17.40824 3.801302 9.283954 17.40978 3.126571 9.529318 17.41293 2.592556 9.691127 17.40985 2.018728 9.815237 17.41027 1.310529 9.934578 17.40818 0.6326048 10.0015 17.40814 -0.1068273 10.01783 17.41147 -0.8180686 9.994022 17.40929 -1.418348 9.925959 17.4105 -2.074945 9.810714 17.41024 -2.621535 9.682264 17.40947 -3.233358 9.485356 17.41237 -3.955493 9.216409 17.40616 -4.37146 9.037302 17.40878 -4.773639 8.82539 17.41421 -5.306759 8.517197 17.40919 -5.741625 8.235823 17.40687 4.751642 8.838015 15.65036 4.294251 9.071938 15.64926 3.797607 9.28437 15.65104 3.104476 9.535723 15.65461 2.583434 9.69347 15.65108 2.015216 9.815057 15.65133 1.305271 9.934844 15.64935 0.6310814 10.00125 15.64921 -0.1049933 10.01677 15.65252 -0.807987 9.994614 15.6507 -1.39948 9.927231 15.65289 -2.094772 9.805086 15.65267 -2.631755 9.679317 15.65092 -3.229748 9.485574 15.65353 -3.944649 9.220442 15.64719 -4.371857 9.035471 15.6492 -4.796205 8.810717 15.65348 -5.31484 8.511997 15.64951 -5.743049 8.23484 15.64756 4.751836 8.837196 13.89134 4.29503 9.071163 13.89026 3.797126 9.283584 13.89218 3.091378 9.538754 13.89596 2.576664 9.694729 13.89222 2.007553 9.81532 13.89251 1.287997 9.93673 13.89085 0.625056 10.00162 13.8904 -0.1042391 10.01576 13.89359 -0.7995747 9.994937 13.89205 -1.384573 9.927799 13.8951 -2.113812 9.799667 13.89499 -2.639063 9.677408 13.89251 -3.218892 9.488476 13.89509 -3.934611 9.223515 13.88815 -4.390751 9.02325 13.88849 -4.865568 8.770009 13.88991 -5.341608 8.496473 13.88862 -5.745572 8.233976 13.88757 4.753548 8.835493 12.13232 4.298033 9.069513 12.13118 3.807815 9.278687 12.13288 3.10772 9.53097 12.1361 2.580346 9.691989 12.13295 1.998052 9.815372 12.13378 1.261094 9.939908 12.13277 0.6163955 10.00243 12.13181 -0.1046104 10.01467 12.13467 -0.7956674 9.994467 12.13322 -1.379445 9.926651 12.13675 -2.128077 9.795345 12.1369 -2.637984 9.67827 12.13425 -3.192621 9.497345 12.13729 -3.91486 9.231028 12.12962 -4.390463 9.022004 12.12898 -4.89094 8.755045 12.12912 -5.350824 8.491127 12.12893 -5.747989 8.232428 12.12836 4.758853 8.831664 10.37355 4.304572 9.06645 10.37213 3.833703 9.268391 10.37283 3.161679 9.509879 10.37411 2.599007 9.683916 10.37292 1.990713 9.814521 10.37507 1.233535 9.943285 10.37497 0.6127002 10.00305 10.3735 -0.1034073 10.01341 10.37592 -0.793762 9.993556 10.37439 -1.37803 9.924798 10.37803 -2.133732 9.792209 10.37819 -2.643033 9.676057 10.37497 -3.194851 9.49582 10.37698 -3.904414 9.235494 10.37039 -4.383541 9.025012 10.37002 -4.893499 8.753363 10.36995 -5.351647 8.49063 10.36999 -5.74988 8.230959 10.36972 4.765006 8.827239 8.617582 4.308729 9.064243 8.615981 3.84657 9.263041 8.616286 3.183848 9.500909 8.616662 2.604703 9.680794 8.616173 1.981557 9.814627 8.618887 1.210506 9.946553 8.619524 0.6223211 10.00298 8.617725 -0.09708881 10.01184 8.619421 -0.7915049 9.992468 8.617668 -1.377887 9.922554 8.621295 -2.141432 9.787537 8.621146 -2.678937 9.662359 8.615518 -3.277191 9.465289 8.612903 -3.926295 9.2283 8.611298 -4.38142 9.026617 8.613398 -4.892097 8.754137 8.613769 -5.350811 8.491137 8.613929 -5.750101 8.230774 8.614098 4.77115 8.822792 6.888699 4.311706 9.062464 6.887025 3.852549 9.260256 6.887054 3.187412 9.498873 6.886452 2.603442 9.680235 6.884777 1.971156 9.815226 6.886248 1.190231 9.949578 6.885954 0.6371875 10.00259 6.883484 -0.08892023 10.01019 6.884308 -0.7887093 9.991415 6.882542 -1.376263 9.920688 6.886809 -2.142971 9.784861 6.888244 -2.692953 9.657011 6.883309 -3.308039 9.45475 6.880512 -3.927108 9.229249 6.881455 -4.375037 9.029873 6.884408 -4.889661 8.755402 6.8849 -5.349695 8.491806 6.885071 -5.749406 8.23132 6.885221 4.776716 8.818653 5.32772 4.313658 9.061007 5.326105 3.853204 9.25932 5.324792 3.177102 9.501694 5.319477 2.5961 9.681539 5.310156 1.957453 9.816544 5.302528 1.174732 9.951744 5.292998 0.6531117 10.00182 5.28748 -0.08051908 10.00855 5.287181 -0.7840415 9.990681 5.286757 -1.367864 9.92014 5.295051 -2.135053 9.784415 5.306162 -2.690237 9.657382 5.310522 -3.299695 9.458569 5.317332 -3.914775 9.234858 5.321314 -4.36709 9.033514 5.324197 -4.887255 8.756523 5.324676 -5.348724 8.492292 5.324871 -5.748961 8.231553 5.325047 4.781208 8.814937 4.329482 4.313194 9.059988 4.327891 3.840266 9.262783 4.322288 3.134526 9.515301 4.303346 2.571599 9.687561 4.274317 1.930346 9.820409 4.241795 1.164202 9.952648 4.206745 0.6660106 10.00037 4.193199 -0.07291722 10.00695 4.191428 -0.7728148 9.990967 4.195073 -1.337117 9.923659 4.214137 -2.101725 9.788948 4.250666 -2.665465 9.663657 4.280402 -3.254254 9.47431 4.312385 -3.892927 9.24266 4.32485 -4.360656 9.035552 4.328052 -4.886789 8.756076 4.328672 -5.349323 8.491337 4.329015 -5.749794 8.230436 4.329333 4.794881 8.805299 4.037427 4.318305 9.054348 4.035157 3.819791 9.267206 4.025439 3.072469 9.534033 3.996753 2.531217 9.696417 3.96352 1.88067 9.82754 3.922261 1.135582 9.955445 3.878385 0.6627843 9.99923 3.863072 -0.0693103 10.00507 3.861046 -0.754342 9.991719 3.865545 -1.281978 9.930899 3.886767 -2.042429 9.797673 3.932678 -2.623875 9.672784 3.971515 -3.192064 9.493392 4.009709 -3.87421 9.246305 4.030148 -4.367967 9.028732 4.036069 -4.900514 8.746291 4.03755 -5.362555 8.481003 4.038305 -5.76074 8.220837 4.038973 4.382371 9.016527 3.982233 3.85861 9.245546 3.970828 3.12243 9.51021 3.939121 2.544126 9.685755 3.904989 1.876552 9.823573 3.863262 1.140724 9.950519 3.818504 0.6659224 9.994796 3.80246 -0.06753289 10.00112 3.80015 -0.7486802 9.988677 3.804675 -1.267754 9.929388 3.826157 -2.030858 9.794961 3.873518 -2.637813 9.661729 3.912666 -3.247212 9.467624 3.950479 -3.936661 9.21344 3.975178 -4.453539 8.979393 3.983194 -4.991222 8.690651 3.98544 -5.445982 8.423174 3.986608 -5.83126 8.166245 3.987644 3.082805 9.401738 29.04182 3.252453 9.017088 29.22886 2.750048 9.577027 29.14114 2.881314 9.298715 29.26747 2.392704 9.695569 29.2709 2.467565 9.46675 29.39306 2.021624 9.77998 29.40177 2.086595 9.549869 29.52933 1.670922 9.843562 29.50281 1.724211 9.61449 29.63478 1.201948 9.915021 29.60024 1.250241 9.714346 29.71722 0.8144615 9.976496 29.64617 0.8407295 9.873698 29.70691 0.2937992 10.01235 29.68675 0.315455 9.944064 29.7267 -0.08260452 10.01925 29.69739 -0.08313024 9.955551 29.73479 -0.4846927 10.00382 29.67539 -0.5039847 9.937463 29.7146 -0.9020808 9.969536 29.6375 -0.929189 9.869085 29.69656 -1.313198 9.900476 29.57781 -1.3634 9.703044 29.69217 -1.71937 9.835309 29.48865 -1.772638 9.606783 29.61918 -2.078248 9.767035 29.37636 -2.172309 9.538149 29.48962 -2.487755 9.671206 29.22955 -2.562344 9.445538 29.35195 -2.816195 9.557826 29.10415 -2.919283 9.295292 29.24052 -3.23138 9.35104 28.96257 -3.375823 8.986636 29.15518 -3.56744 9.155367 28.84997 -3.736215 8.801419 29.01612 -3.934664 8.858507 28.77751 -4.030989 8.632487 28.89724 -6.482052 7.672229 3.988374 -6.339412 7.781834 3.981507 -6.062914 7.99152 3.979707 -5.712545 8.240915 3.978268 -5.282609 8.514304 3.976522 -4.752162 8.814126 3.973382 -4.216156 9.08043 3.965185 -3.593891 9.325166 3.94014 -2.823832 9.583741 3.897267 -2.179128 9.751783 3.865236 -1.391703 9.897765 3.819114 -0.7889288 9.972249 3.792698 -0.07000887 9.98972 3.786323 0.6938334 9.980341 3.789721 1.236338 9.923873 3.809566 2.013101 9.782782 3.854196 2.718761 9.610345 3.889851 3.461674 9.370179 3.93329 4.081757 9.13965 3.961784 4.626336 8.881224 3.972288 -5.718333 -6.969845 29.65457 -5.323049 -7.144555 29.86985 -4.922198 -7.332559 30.05886 -4.567414 -7.451424 30.23243 -4.043694 -7.639801 30.41934 -3.573874 -7.771781 30.59222 -3.041181 -7.883753 30.76016 -2.467689 -8.018037 30.88316 -1.901105 -8.103134 30.98818 -1.268927 -8.164505 31.08834 -0.6550753 -8.152246 31.19516 -0.023108 -8.19963 31.18205 0.5884721 -8.156195 31.19789 1.202067 -8.169514 31.09801 1.789312 -8.118947 31.00517 2.388568 -8.031349 30.9007 2.931883 -7.906695 30.79096 3.495614 -7.78651 30.62412 3.926904 -7.674936 30.46531 3.255541 -8.152764 8.737549 3.634216 -8.104426 8.926218 3.344282 -7.654033 8.554615 3.732773 -7.592443 8.748157 3.432142 -7.444439 8.514969 3.843355 -7.339887 8.713024 3.583843 -7.153218 8.511294 4.013806 -6.888443 8.67506 3.981414 -5.883049 8.376797 4.440734 -5.286642 8.450659 4.840274 -2.790311 7.989241 5.124778 -2.507069 8.027666 5.232014 -1.401456 7.796895 5.436259 -1.319909 7.847553 5.289698 -0.3157539 7.512208 5.528094 -0.3852978 7.624139 5.148208 1.528381 6.830986 5.434251 1.512246 6.967319 5.276002 3.561757 5.817844 5.544458 3.570179 5.951493 5.753388 6.146284 4.096549 5.873628 6.126758 4.182708 5.919508 7.047631 3.466351 5.9986 7.032607 3.519381 5.918138 7.220189 3.336993 6.026828 7.210538 3.399106 5.881467 7.263706 3.306656 6.043814 7.257017 3.399641 5.838448 7.319301 3.310305 6.093473 7.32013 3.466278 5.766644 7.474703 3.387917 6.162037 7.454397 3.610099 5.606664 7.864104 3.613317 6.137356 7.726751 3.813262 5.322622 8.345425 3.857124 5.850718 8.084429 3.933057 4.978192 8.662817 3.951071 5.482878 8.380742 3.968152 2.840573 -8.193188 8.554922 2.917867 -7.727749 8.377217 3.003298 -7.522554 8.331809 3.144673 -7.26154 8.328824 3.551652 -6.068695 8.234787 4.499429 -2.901629 7.916944 4.96122 -1.330165 7.707788 5.002239 0.0598939 7.331215 4.959404 1.673829 6.728402 5.10988 3.586735 5.747825 5.5568 6.173136 4.017702 5.671638 7.08684 3.367461 5.600845 7.272697 3.206937 5.485918 7.333192 3.140279 5.352036 7.412786 3.103428 5.174705 7.59442 3.146661 4.953518 8.011515 3.381301 4.704782 8.570934 3.740407 4.385287 8.944075 3.918446 2.379333 -8.236318 8.385848 2.450393 -7.804535 8.215993 2.544023 -7.592163 8.166399 2.673289 -7.334713 8.15858 3.042216 -6.173133 8.086425 3.931856 -3.042967 7.837616 4.534492 -1.391422 7.65037 4.692313 0.1432273 7.258418 4.74962 1.713252 6.690228 4.842846 3.611536 5.689346 5.06118 6.23637 3.868327 5.096034 7.164376 3.186517 5.05971 7.345814 3.042326 5.001165 7.413822 3.004504 4.875896 7.549748 2.99038 4.593172 7.793119 3.024956 4.278514 8.18609 3.208518 4.033631 8.750267 3.59861 3.761452 9.167957 3.861501 1.913565 -8.336879 8.280627 1.978828 -7.89849 8.097957 2.051858 -7.660761 8.025416 2.133507 -7.407824 8.00769 2.289436 -6.315389 7.938368 2.730972 -3.336984 7.716812 3.522794 -1.656605 7.571113 3.89698 -0.1423578 7.236863 4.164157 1.620308 6.683335 4.265274 3.604939 5.666462 4.333815 6.264148 3.800047 4.3397 7.195766 3.115388 4.328986 7.379811 2.985162 4.297883 7.489959 2.962822 4.176711 7.755923 2.959932 3.873997 8.075405 2.987707 3.588223 8.419027 3.136456 3.287496 8.988342 3.529344 2.9431 9.438041 3.808895 1.434169 -8.458169 8.216428 1.484299 -7.9935 8.01039 1.546617 -7.719573 7.914391 1.593888 -7.461813 7.883504 1.611988 -6.40729 7.80419 1.663078 -3.563212 7.577205 2.004237 -2.11921 7.435639 2.381139 -0.8954949 7.21489 3.015256 1.340764 6.685175 3.253085 3.555505 5.662857 3.304372 6.26509 3.784757 3.309184 7.201781 3.10166 3.306986 7.389706 2.975131 3.293432 7.529222 2.955957 3.225567 7.888647 2.955704 3.040698 8.294266 2.987183 2.849721 8.664981 3.156235 2.535795 9.322597 3.601254 2.229925 9.671364 3.811194 0.9579001 -8.479461 8.136802 0.9819694 -8.038187 7.934071 1.015673 -7.758482 7.828852 1.038746 -7.498253 7.789836 1.0375 -6.451144 7.708554 1.012023 -3.643953 7.484314 1.124662 -2.300151 7.338595 1.386681 -1.20139 7.167984 1.935012 1.235018 6.67311 2.138469 3.538059 5.660352 2.17564 6.264251 3.782409 2.179501 7.202482 3.100028 2.179372 7.391623 2.974055 2.176213 7.540184 2.955227 2.157036 7.933169 2.955135 2.091212 8.386246 2.986716 1.963402 8.791821 3.158372 1.657838 9.528975 3.607677 1.410791 9.839289 3.780528 0.4671726 -8.49647 8.09264 0.4717336 -8.048271 7.882763 0.478339 -7.774012 7.774603 0.4913173 -7.51759 7.734089 0.4935362 -6.472396 7.652274 0.4698522 -3.671049 7.428144 0.5062111 -2.346783 7.278891 0.6333947 -1.271128 7.123507 0.9101403 1.212893 6.659307 1.012154 3.534692 5.657966 1.030304 6.264029 3.781962 1.032231 7.202533 3.099886 1.032325 7.391867 2.973973 1.031891 7.542002 2.955162 1.028588 7.942029 2.954957 1.013306 8.409502 2.985583 0.9653304 8.834568 3.152843 0.8367212 9.616145 3.591493 0.7492855 9.915541 3.757595 -0.04788833 -8.494444 8.075737 -0.04321599 -8.042886 7.864126 -0.0403909 -7.775379 7.758487 -0.03863275 -7.522364 7.718546 -0.04045742 -6.478212 7.635991 -0.05119472 -3.677711 7.410969 -0.05510509 -2.355977 7.260068 -0.06428921 -1.282455 7.10758 -0.09993457 1.209431 6.654175 -0.1140104 3.534164 5.657082 -0.1166194 6.263983 3.781858 -0.1169089 7.202533 3.099873 -0.1169271 7.391885 2.973968 -0.1168959 7.542171 2.955157 -0.11659 7.942998 2.954924 -0.1145569 8.412632 2.985309 -0.1051745 8.841979 3.151292 -0.08092057 9.633544 3.586775 -0.07236051 9.930364 3.752593 -0.5401924 -8.497965 8.0988 -0.5626108 -8.050294 7.891074 -0.5926466 -7.772452 7.784184 -0.6129619 -7.514125 7.744549 -0.6256311 -6.467723 7.664033 -0.6412761 -3.66409 7.44289 -0.6813455 -2.341256 7.292832 -0.8061969 -1.267657 7.132946 -1.124238 1.21391 6.662131 -1.242727 3.534856 5.658435 -1.263817 6.264038 3.782028 -1.266034 7.202528 3.099897 -1.266112 7.39185 2.973974 -1.265448 7.541865 2.955167 -1.26046 7.941291 2.954971 -1.236658 8.407607 2.985709 -1.158166 8.832157 3.153591 -0.963751 9.609631 3.593975 -0.853435 9.906983 3.760783 -1.051399 -8.476078 8.151716 -1.080302 -8.028985 7.946722 -1.128526 -7.750822 7.843708 -1.17606 -7.490189 7.808962 -1.214078 -6.437531 7.73307 -1.253279 -3.618729 7.514376 -1.324039 -2.28675 7.362596 -1.55861 -1.195713 7.181766 -2.146629 1.236482 6.677025 -2.367885 3.538265 5.661045 -2.408677 6.26418 3.78269 -2.412734 7.202408 3.100182 -2.412303 7.391455 2.974106 -2.408123 7.539014 2.95526 -2.383679 7.927955 2.955224 -2.300609 8.375548 2.987215 -2.139781 8.782622 3.160911 -1.81478 9.509466 3.615415 -1.575973 9.812358 3.790627 -1.555437 -8.443428 8.23865 -1.593516 -7.978417 8.029886 -1.648969 -7.709057 7.934443 -1.716744 -7.448332 7.906454 -1.844193 -6.367339 7.837849 -2.086681 -3.469887 7.623461 -2.230192 -2.082123 7.461511 -2.526943 -0.8874941 7.224042 -3.21001 1.3419 6.687215 -3.473764 3.555379 5.663718 -3.532918 6.264256 3.786717 -3.537104 7.201093 3.103081 -3.532707 7.38862 2.975742 -3.515666 7.52343 2.95635 -3.434907 7.867299 2.956189 -3.215391 8.26042 2.988442 -2.959495 8.647953 3.160816 -2.655144 9.303671 3.612134 -2.390824 9.641358 3.823486 -2.047981 -8.339276 8.32393 -2.092561 -7.893328 8.131737 -2.166028 -7.649435 8.05644 -2.283916 -7.382148 8.039011 -2.650358 -6.22305 7.979164 -3.506482 -3.118447 7.777 -3.870314 -1.570626 7.596114 -4.069757 -0.1256903 7.242583 -4.335511 1.622086 6.684815 -4.450732 3.60365 5.670232 -4.536546 6.259556 3.810737 -4.537636 7.191903 3.123882 -4.517168 7.375742 2.989732 -4.477739 7.475896 2.966153 -4.340323 7.714171 2.963347 -4.017557 8.024543 2.993424 -3.691864 8.394053 3.151759 -3.409989 8.969943 3.553225 -3.060508 9.411746 3.823234 -2.516636 -8.240135 8.439786 -2.571386 -7.799463 8.259845 -2.644606 -7.581618 8.201047 -2.78622 -7.314025 8.19279 -3.225025 -6.119224 8.119066 -4.248041 -2.950055 7.865759 -4.662822 -1.356667 7.660027 -4.754787 0.1517325 7.260948 -4.810678 1.714234 6.693109 -4.92451 3.608032 5.700855 -5.182749 6.224192 3.897501 -5.211993 7.15299 3.213142 -5.160405 7.336695 3.062205 -5.095622 7.401354 3.021888 -4.970284 7.523745 3.007209 -4.702611 7.757946 3.044868 -4.399888 8.164436 3.245265 -4.150172 8.738749 3.63769 -3.863148 9.140754 3.876982 -2.918474 -8.194738 8.589931 -2.997112 -7.716128 8.407456 -3.092847 -7.502745 8.366741 -3.243132 -7.208824 8.359212 -3.668639 -5.933844 8.247326 -4.599056 -2.835925 7.925415 -5.009882 -1.302373 7.712758 -5.034512 0.07933747 7.335532 -4.986896 1.681309 6.734576 -5.151021 3.589949 5.760593 -5.609968 6.168004 4.036357 -5.744825 7.075479 3.395452 -5.699392 7.255905 3.246491 -5.592835 7.313992 3.183889 -5.456758 7.391713 3.145988 -5.27733 7.574158 3.186917 -5.075568 7.991288 3.428533 -4.847153 8.53131 3.776564 -4.518353 8.887377 3.930185 -3.299145 -8.150317 8.759699 -3.401095 -7.637929 8.57894 -3.524161 -7.390178 8.548075 -3.706658 -6.911688 8.510023 -4.173425 -5.237816 8.298274 -4.935009 -2.541123 7.962933 -5.301362 -1.318404 7.799999 -5.35512 -0.258214 7.524148 -5.208766 1.557888 6.849396 -5.349411 3.587761 5.83866 -5.788516 6.155015 4.104862 -5.945888 7.046354 3.475393 -5.953509 7.214684 3.351779 -5.923661 7.257644 3.326282 -5.891919 7.31274 3.336938 -5.849668 7.462899 3.427617 -5.725604 7.828855 3.652809 -5.46978 8.273376 3.876613 -5.128436 8.579863 3.956041 -3.675784 -8.084664 8.942273 -3.796074 -7.552666 8.772261 -3.940219 -7.199614 8.729112 -4.219625 -6.212797 8.602738 -4.806615 -3.565555 8.165824 -5.280468 -1.827474 7.917007 -5.501238 -1.15991 7.832724 -5.592221 -0.3108387 7.633169 -5.522672 1.593386 6.970555 -5.639153 3.706424 5.899238 -5.907495 6.194038 4.134232 -6.006944 7.050549 3.499882 -6.032662 7.21353 3.394235 -6.060795 7.261748 3.411422 -6.126311 7.329441 3.493551 -6.21633 7.461828 3.649159 -6.204145 7.70489 3.835186 -5.961188 8.014204 3.93956 -5.625852 8.285732 3.969064 -4.041897 -8.006489 9.136686 -4.167548 -7.475997 8.980219 -4.308024 -7.08443 8.928528 -4.602136 -5.90226 8.74935 -5.166496 -2.849791 8.15414 -5.475197 -1.502989 7.915438 -5.642356 -1.00608 7.853943 -5.741688 -0.1943736 7.6624 -5.720841 1.801478 6.924242 -5.808651 4.16902 5.611448 -5.969398 6.362982 4.033248 -6.044183 7.091463 3.5071 -6.104156 7.249728 3.461658 -6.201023 7.328749 3.552394 -6.333207 7.422236 3.698129 -6.431401 7.517274 3.828324 -6.442215 7.636536 3.926383 -6.30544 7.789572 3.9643 -6.022666 8.014019 3.974188 -4.382464 -7.926013 9.338044 -4.500204 -7.402863 9.188313 -4.63733 -7.00154 9.137705 -4.901066 -5.785387 8.926684 -5.372745 -2.653669 8.225123 -5.614379 -1.357242 7.948165 -5.746539 -0.8716366 7.870079 -5.83166 -0.004542231 7.621903 -5.820458 2.274321 6.606264 -5.932217 5.292215 4.746111 -6.040385 6.814224 3.723774 -6.132545 7.218868 3.530021 -6.256692 7.345312 3.618197 -6.395161 7.438675 3.761507 -6.478967 7.500467 3.853714 -6.515873 7.548562 3.908292 -6.517943 7.610803 3.954423 -6.470149 7.671255 3.971485 -6.322582 7.791031 3.976574 -4.703914 -7.853214 9.553667 -4.810967 -7.337221 9.407623 -4.952458 -6.923975 9.362524 -5.195055 -5.70909 9.138916 -5.592446 -2.595643 8.37957 -5.74505 -1.301181 8.030304 -5.830527 -0.8040986 7.912104 -5.8881 0.05318367 7.639158 -5.873157 2.381767 6.547669 -6.003573 5.636671 4.523033 -6.148576 6.973718 3.754931 -6.298476 7.325136 3.703904 -6.427639 7.442443 3.806701 -6.503243 7.499354 3.880447 -6.5302 7.527778 3.910306 -6.537085 7.556404 3.930738 -6.535553 7.603518 3.962257 -6.523089 7.631913 3.974941 -6.474206 7.675268 3.978892 -5.123348 -7.30464 9.668862 -5.267467 -6.864116 9.620672 -5.490845 -5.693795 9.405001 -5.838445 -2.720488 8.660181 -5.935355 -1.354388 8.233616 -5.969459 -0.8312914 8.058926 -6.006736 -0.05701506 7.805293 -5.99447 2.020553 6.860923 -6.095456 5.12095 5.044002 -6.312937 6.75428 4.243574 -6.450606 7.300789 4.000086 -6.514183 7.456493 3.949286 -6.536895 7.509126 3.932842 -6.542269 7.533402 3.932418 -6.542317 7.561418 3.946032 -6.540317 7.603083 3.97264 -6.536234 7.622972 3.983351 -6.524068 7.637533 3.986547 -5.422654 -6.634722 30.26892 -5.749955 -6.531733 30.0397 -5.553092 -6.075119 30.62354 -5.886121 -5.970357 30.3662 -5.748454 -5.447894 30.90382 -6.0609 -5.350356 30.64814 -5.897694 -4.814302 31.16838 -6.227849 -4.696664 30.88302 -6.041015 -4.124034 31.39637 -6.372051 -4.014397 31.09475 -6.167778 -3.405322 31.57744 -6.473965 -3.319438 31.27427 -6.253587 -2.544754 31.75901 -6.550611 -2.550611 31.42616 -6.274448 -1.767524 31.88471 -6.595126 -1.735169 31.52467 -6.243515 -0.9970076 31.96994 -6.565514 -1.021935 31.60255 -6.202903 -0.1121877 31.95481 -6.51487 -0.2017315 31.60516 -6.095938 0.6172568 31.93718 -6.40386 0.5335676 31.59901 -5.96629 1.001405 31.98511 -6.270671 0.8996363 31.66945 -5.820928 1.165943 32.07861 -6.126589 1.054563 31.78073 -5.634358 1.457226 32.06698 -5.948812 1.329641 31.79512 -5.289205 2.685146 31.50426 -5.609761 2.52553 31.28736 -4.70873 5.744333 29.94928 -4.976225 5.644484 29.73924 -4.412326 7.457103 29.23541 -4.685957 7.363216 29.00844 -4.284551 8.016694 29.05675 -4.554962 7.923594 28.83985 -4.176429 8.411184 28.91839 -4.449695 8.291097 28.72882 -4.981576 -6.81416 30.50672 -5.131969 -6.229724 30.88317 -5.336699 -5.605794 31.17521 -5.532688 -4.926411 31.45064 -5.652221 -4.246664 31.71623 -5.796332 -3.436458 31.93282 -5.879308 -2.540691 32.13861 -5.908412 -1.763564 32.26251 -5.906883 -0.9128962 32.32027 -5.866157 -0.008290529 32.29843 -5.766124 0.7047094 32.26524 -5.638351 1.104581 32.29147 -5.486106 1.290819 32.35815 -5.266312 1.665256 32.27195 -4.860605 3.057967 31.57217 -4.36362 5.934828 30.12057 -4.130828 7.551415 29.43779 -4.0315 8.089542 29.24381 -3.902513 8.506592 29.09483 -4.592579 -6.967432 30.69102 -4.717926 -6.433523 31.05949 -4.917122 -5.769897 31.41343 -5.095464 -5.068494 31.74072 -5.236081 -4.340487 32.03487 -5.381653 -3.513357 32.27612 -5.465701 -2.633625 32.49203 -5.523871 -1.773507 32.6175 -5.546367 -0.850277 32.6592 -5.49804 0.05793595 32.64057 -5.382876 0.7863026 32.61075 -5.24441 1.217079 32.62485 -5.083324 1.436723 32.66066 -4.832152 1.944008 32.47375 -4.370079 3.598045 31.59263 -3.973865 6.180772 30.28251 -3.793431 7.64831 29.66107 -3.693805 8.1649 29.47549 -3.530443 8.604614 29.32573 -4.133815 -7.121479 30.87547 -4.301842 -6.574248 31.2479 -4.484905 -5.89387 31.64764 -4.671144 -5.177504 32.00331 -4.806736 -4.436405 32.32447 -4.920745 -3.634943 32.60147 -5.019428 -2.700486 32.83877 -5.099083 -1.766824 32.96947 -5.119318 -0.8214748 33.01832 -5.065136 0.08640503 33.00561 -4.951941 0.853013 32.96168 -4.815115 1.330663 32.94469 -4.648138 1.632972 32.90681 -4.357556 2.458992 32.48252 -3.837664 4.62731 31.25918 -3.552659 6.618129 30.2957 -3.437343 7.775866 29.83914 -3.350368 8.257965 29.66306 -3.175028 8.748151 29.47295 -3.631445 -7.247518 31.07934 -3.830688 -6.667058 31.47576 -3.983914 -6.019124 31.89118 -4.160614 -5.306118 32.26834 -4.267135 -4.549841 32.63592 -4.406811 -3.691022 32.93809 -4.514822 -2.718024 33.195 -4.590496 -1.80136 33.33547 -4.617027 -0.8614636 33.3909 -4.573107 0.07808971 33.37449 -4.460064 0.9143071 33.31396 -4.325753 1.44607 33.26099 -4.159784 1.819084 33.14032 -3.862983 2.829541 32.53016 -3.377361 5.119003 31.21296 -3.121076 6.828604 30.43959 -2.99468 7.855544 30.07355 -2.903672 8.337439 29.89502 -2.777649 8.83048 29.66148 -3.074165 -7.350565 31.28132 -3.244676 -6.788633 31.69623 -3.411882 -6.15024 32.11622 -3.55831 -5.448343 32.52435 -3.694018 -4.654486 32.91745 -3.836425 -3.775379 33.247 -3.923224 -2.814523 33.53001 -3.991388 -1.859776 33.70243 -4.030513 -0.8873344 33.7678 -3.986659 0.1094615 33.7522 -3.891648 0.9904014 33.66426 -3.766614 1.5565 33.57727 -3.588551 1.967108 33.41452 -3.274945 3.050175 32.72619 -2.88421 5.304247 31.38097 -2.707813 6.920963 30.62107 -2.623289 7.916532 30.24065 -2.540019 8.429867 30.03247 -2.413592 8.898218 29.80717 -2.4951 -7.49404 31.40161 -2.68492 -6.898432 31.85923 -2.835826 -6.2582 32.31032 -2.976055 -5.57283 32.72693 -3.112361 -4.806599 33.12006 -3.234179 -3.878756 33.50224 -3.296153 -2.854755 33.83383 -3.34947 -1.830482 34.03836 -3.386621 -0.8139768 34.11195 -3.355747 0.1954151 34.08535 -3.265289 1.078505 33.98217 -3.146793 1.660702 33.86855 -2.978333 2.093612 33.66533 -2.694256 3.212109 32.90906 -2.359834 5.414833 31.56951 -2.177645 6.994553 30.82859 -2.072587 7.971889 30.45694 -1.993238 8.504113 30.22939 -1.912042 8.968563 29.98118 -1.898026 -7.594498 31.50927 -2.035298 -6.998672 32.00339 -2.188599 -6.340483 32.48695 -2.289528 -5.661256 32.92839 -2.419452 -4.88855 33.34438 -2.506726 -4.008156 33.73823 -2.560757 -2.981409 34.08856 -2.612337 -1.918812 34.31937 -2.652928 -0.8296058 34.41217 -2.641459 0.2365531 34.37856 -2.559795 1.156445 34.26153 -2.46204 1.751254 34.1238 -2.333671 2.186944 33.88661 -2.120413 3.307281 33.08301 -1.862147 5.483045 31.7253 -1.710193 7.049254 30.97515 -1.640378 8.02495 30.58608 -1.588219 8.593747 30.32177 -1.494789 9.130295 30.02274 -1.279746 -7.685159 31.57578 -1.409711 -7.090788 32.08491 -1.507001 -6.457189 32.57696 -1.565569 -5.738557 33.07017 -1.649114 -4.939891 33.52927 -1.749181 -4.03637 33.94427 -1.796681 -3.018391 34.30205 -1.83722 -1.953466 34.54374 -1.868026 -0.8295262 34.65015 -1.846091 0.2741578 34.61803 -1.786233 1.235384 34.47948 -1.711509 1.832157 34.32296 -1.613931 2.265825 34.06256 -1.47025 3.373716 33.23743 -1.279671 5.536259 31.86191 -1.147843 7.099245 31.10233 -1.139191 8.077727 30.69031 -1.123049 8.72286 30.36546 -1.013768 9.47457 29.92793 -0.6423007 -7.705927 31.65416 -0.7011687 -7.15249 32.14629 -0.7674459 -6.540946 32.63401 -0.8195202 -5.790234 33.15992 -0.8649668 -4.971121 33.64574 -0.9296865 -4.049736 34.08365 -0.9674211 -3.017488 34.45437 -1.002559 -1.952672 34.69993 -1.017343 -0.8256126 34.81303 -0.9952626 0.2866111 34.77993 -0.9596102 1.269144 34.62615 -0.9090585 1.889696 34.44314 -0.8438848 2.348223 34.1439 -0.767277 3.427675 33.32909 -0.6883773 5.567907 31.94663 -0.6508772 7.102782 31.18057 -0.6743091 8.026926 30.7796 -0.6767788 8.724972 30.41919 -0.5723189 9.603762 29.90894 -0.02130866 -7.750004 31.64217 -0.0477032 -7.177143 32.16 -0.04993486 -6.552612 32.67058 -0.0608623 -5.80608 33.2001 -0.07973563 -4.988971 33.68829 -0.06707823 -4.071444 34.13346 -0.08187484 -3.050349 34.5054 -0.1028596 -1.964558 34.75832 -0.1082774 -0.8159955 34.87548 -0.1060397 0.3134409 34.83977 -0.09821462 1.297019 34.67751 -0.07621586 1.938688 34.46355 -0.0506125 2.43835 34.11203 -0.03874266 3.472212 33.33855 -0.0473501 5.582235 31.97649 -0.06428742 7.092581 31.2155 -0.0819571 7.97857 30.8265 -0.08559465 8.684473 30.46277 -0.08385205 9.618595 29.92828 0.5991397 -7.706733 31.65802 0.6101458 -7.154317 32.15523 0.6332526 -6.539485 32.65293 0.6587014 -5.782272 33.18596 0.6924188 -4.966092 33.66851 0.7616141 -4.044914 34.10736 0.7769556 -3.036976 34.47209 0.7975657 -1.962817 34.71915 0.811194 -0.8169432 34.83305 0.7994695 0.3165089 34.79736 0.7769241 1.287038 34.6436 0.752456 1.898342 34.45962 0.7146025 2.354095 34.15873 0.6566722 3.432472 33.3416 0.5806868 5.571541 31.95549 0.537411 7.104639 31.18537 0.554982 8.022749 30.78878 0.5366209 8.705311 30.44145 0.3991547 9.601116 29.92459 1.218913 -7.68886 31.58571 1.27613 -7.100682 32.1044 1.333647 -6.467162 32.60598 1.403238 -5.740965 33.10259 1.50561 -4.939982 33.55991 1.58047 -4.045978 33.97811 1.607803 -3.046563 34.338 1.656324 -1.971239 34.58182 1.681464 -0.8261607 34.69109 1.676949 0.3073875 34.65231 1.630118 1.261003 34.51033 1.561226 1.847408 34.35371 1.462401 2.278152 34.09362 1.319164 3.385568 33.26726 1.156437 5.544759 31.88465 1.070616 7.099076 31.11673 1.043107 8.060038 30.71762 1.003689 8.697704 30.40495 0.91854 9.468774 29.94717 1.816261 -7.604685 31.52489 1.902139 -7.021707 32.02444 2.029248 -6.375473 32.50601 2.151324 -5.675155 32.96004 2.269745 -4.895293 33.38798 2.345553 -4.014354 33.79043 2.386883 -3.007494 34.14312 2.451042 -1.940103 34.37376 2.483851 -0.8339481 34.47192 2.486462 0.2619611 34.43004 2.414688 1.182762 34.30739 2.316699 1.771051 34.16847 2.176594 2.206001 33.93172 1.955193 3.328695 33.12543 1.71663 5.498844 31.76278 1.59364 7.058745 31.00844 1.504015 8.019522 30.63033 1.40258 8.580681 30.38506 1.364903 9.130414 30.06027 2.423799 -7.505087 31.42014 2.561537 -6.921056 31.88884 2.707612 -6.280428 32.3438 2.830706 -5.59279 32.77344 2.954328 -4.816135 33.17966 3.056118 -3.887186 33.57889 3.127644 -2.902993 33.89835 3.194916 -1.880028 34.10018 3.222246 -0.8157711 34.18639 3.217082 0.2223415 34.14627 3.129046 1.102494 34.04077 3.01236 1.682648 33.92252 2.845469 2.12118 33.70914 2.563001 3.253733 32.93484 2.263725 5.437385 31.59424 2.094551 7.013 30.85902 2.007559 7.98106 30.48348 1.929043 8.51361 30.25182 1.858714 8.975539 30.00141 2.978816 -7.367834 31.31384 3.10808 -6.819795 31.73956 3.275324 -6.182846 32.16174 3.421787 -5.48883 32.5694 3.580629 -4.681027 32.9611 3.701781 -3.808049 33.3069 3.782088 -2.879545 33.59037 3.848156 -1.897651 33.77568 3.874418 -0.8735921 33.85695 3.86803 0.1290622 33.82058 3.781141 1.006392 33.72512 3.65169 1.580468 33.63153 3.448563 2.018064 33.45603 3.108155 3.147453 32.73335 2.763602 5.352622 31.40628 2.56022 6.954555 30.67967 2.465739 7.928262 30.31575 2.384842 8.428956 30.1106 2.268781 8.903117 29.87692 3.543704 -7.259004 31.12109 3.700395 -6.686982 31.53589 3.866393 -6.053618 31.93762 4.032476 -5.369658 32.30616 4.175221 -4.578857 32.67625 4.32038 -3.715222 32.98413 4.406634 -2.786038 33.24488 4.463302 -1.829395 33.4119 4.470554 -0.8503804 33.48898 4.445451 0.1004372 33.46082 4.35173 0.9330253 33.38539 4.219146 1.47199 33.32178 4.021561 1.872945 33.19294 3.69417 2.930332 32.5507 3.268731 5.173841 31.23576 3.047336 6.867745 30.46041 2.94455 7.871107 30.0931 2.858755 8.345945 29.91353 2.71132 8.842569 29.68922 4.013317 -7.143735 30.93556 4.170247 -6.57676 31.33469 4.362516 -5.922609 31.71362 4.547931 -5.226571 32.05939 4.711925 -4.469974 32.37374 4.855716 -3.662767 32.63801 4.955184 -2.735094 32.87501 5.017992 -1.766155 33.02838 5.006313 -0.8068209 33.10573 4.962251 0.09476649 33.08531 4.860131 0.8654581 33.03088 4.727165 1.351142 33.00496 4.546034 1.66622 32.96389 4.247943 2.513351 32.51985 3.772765 4.670077 31.27228 3.509221 6.645078 30.31085 3.388092 7.780067 29.87137 3.294147 8.24794 29.70775 3.138783 8.749392 29.4967 4.503196 -7.010587 30.71732 4.650292 -6.453081 31.09403 4.831097 -5.810307 31.45474 5.000308 -5.126412 31.78082 5.170336 -4.389057 32.06152 5.32039 -3.567125 32.30553 5.405374 -2.695265 32.52355 5.464821 -1.779594 32.66224 5.476793 -0.8291252 32.71564 5.427471 0.06837904 32.69861 5.318779 0.7994319 32.66207 5.18271 1.235243 32.66971 5.013849 1.471334 32.69499 4.749299 2.031554 32.47032 4.287981 3.749322 31.5426 3.890062 6.265978 30.29591 3.700456 7.679221 29.71556 3.580426 8.187365 29.54989 3.432524 8.628931 29.38584 4.855212 -7.004594 30.43441 5.068084 -6.399399 30.79121 5.233541 -5.803467 31.11855 5.464383 -5.088451 31.39889 5.618898 -4.381246 31.6661 5.776695 -3.529806 31.90396 5.863984 -2.658369 32.10779 5.899328 -1.810219 32.2463 5.920018 -0.8972006 32.28809 5.873945 0.009921073 32.27236 5.752185 0.7395613 32.25577 5.602246 1.142742 32.28948 5.41577 1.417025 32.29999 5.13407 2.078246 32.02697 4.699663 3.781162 31.15123 4.262461 6.292355 29.96971 4.02598 7.675112 29.45042 3.882945 8.195421 29.30069 3.746443 8.601622 29.15336 -5.034354 8.362862 27.85046 -4.749835 8.38636 28.26782 -5.235392 8.108044 27.83044 -4.925118 8.165081 28.25157 -5.426596 7.85654 27.74659 -5.059178 7.910885 28.24329 -5.629865 7.411015 27.73299 -5.255562 7.350213 28.31781 -5.811827 6.619132 27.93356 -5.523486 6.009485 28.78697 -6.179621 4.780954 28.5576 -6.08411 3.275612 29.93694 -6.682583 2.542511 29.46298 -6.546665 1.550778 30.65539 -7.191709 1.010461 30.00826 -6.841848 0.8679161 30.82678 -7.457135 0.4762365 30.03646 -7.014033 0.63142 30.74095 -7.618226 0.1947586 29.89074 -7.149762 0.3424161 30.62302 -7.733553 -0.3139454 29.79494 -7.257108 -0.292479 30.58976 -7.810343 -1.074413 29.74277 -7.32417 -0.9982464 30.55353 -7.820031 -1.956465 29.68566 -7.338762 -1.820828 30.4963 -7.785852 -2.763867 29.57871 -7.303859 -2.640973 30.39003 -7.687565 -3.585652 29.44991 -7.241243 -3.39144 30.23697 -7.53974 -4.388305 29.26982 -7.097527 -4.181706 30.07353 -7.38637 -5.110148 29.04171 -6.983664 -4.834047 29.84326 -7.164193 -5.829929 28.80536 -6.761552 -5.566733 29.62026 -6.93691 -6.47726 28.55454 -6.603678 -6.145642 29.35315 -5.305642 8.370728 27.33215 -5.563416 8.046232 27.28709 -5.795579 7.755766 27.19782 -6.015562 7.411271 27.08476 -6.173736 6.868171 27.13983 -6.406794 5.765781 27.37293 -6.790149 3.82545 28.06971 -7.475025 1.426734 28.93928 -7.874421 0.3746739 29.16965 -8.077966 0.003939092 29.04214 -8.206138 -0.4014342 28.88576 -8.287655 -1.178073 28.80975 -8.311922 -2.045729 28.72212 -8.261962 -2.896181 28.64151 -8.125016 -3.800103 28.5449 -7.977672 -4.598696 28.35371 -7.76773 -5.41142 28.13862 -7.552603 -6.104763 27.89482 -7.283598 -6.781815 27.65293 -5.626808 8.264074 26.78333 -5.881333 7.986409 26.6313 -6.156693 7.617591 26.55156 -6.395238 7.280365 26.41913 -6.567846 6.858577 26.36385 -6.780318 6.100279 26.36478 -7.086493 4.524264 26.76161 -7.694917 2.032044 27.58921 -8.201169 0.4325247 28.0761 -8.486478 -0.1994866 28.06272 -8.641772 -0.5889504 27.88986 -8.733287 -1.256431 27.75292 -8.769585 -2.139124 27.6383 -8.693962 -3.061552 27.60675 -8.552617 -3.969997 27.51616 -8.38384 -4.80468 27.34107 -8.137583 -5.683067 27.12267 -7.90127 -6.406642 26.87158 -7.595547 -7.099002 26.65376 -6.007907 8.02573 26.16824 -6.243722 7.7959 25.93266 -6.520663 7.446499 25.77006 -6.758643 7.106547 25.64117 -6.940322 6.749733 25.53102 -7.139219 6.163069 25.42297 -7.372274 5.078168 25.48827 -7.785016 3.113224 25.97126 -8.374049 0.8625987 26.69809 -8.785438 -0.2765936 26.90361 -9.009832 -0.803813 26.79422 -9.11868 -1.352185 26.61775 -9.152205 -2.234132 26.50784 -9.092362 -3.17751 26.43981 -8.962059 -4.118421 26.30735 -8.76274 -5.03169 26.15378 -8.5064 -5.889153 25.96844 -8.233085 -6.647763 25.75285 -7.899932 -7.362117 25.54934 -6.379971 7.744679 25.37296 -6.611178 7.524534 25.13153 -6.871813 7.222844 24.89185 -7.11536 6.900886 24.67248 -7.308948 6.55489 24.54725 -7.481231 6.090481 24.44497 -7.664251 5.299245 24.39287 -7.959846 3.689798 24.67129 -8.512537 1.289123 25.32666 -8.965137 -0.2096699 25.58581 -9.290246 -1.024483 25.57246 -9.434656 -1.558568 25.39787 -9.471977 -2.360329 25.25755 -9.422525 -3.303464 25.1738 -9.292406 -4.277822 25.03881 -9.077317 -5.225523 24.90216 -8.817558 -6.075757 24.73707 -8.497733 -6.891804 24.56723 -8.167488 -7.589205 24.37242 -6.633109 7.534016 24.19578 -6.924697 7.258003 24.02899 -7.183498 6.976904 23.83369 -7.427097 6.669167 23.5951 -7.631084 6.344507 23.40134 -7.79904 5.931379 23.30562 -7.950264 5.312567 23.18576 -8.128281 4.153077 23.24315 -8.463839 2.276381 23.62116 -8.971031 0.2668964 24.02474 -9.44365 -1.128533 24.22783 -9.663283 -1.814938 24.09247 -9.719017 -2.481586 23.89988 -9.675321 -3.410904 23.79446 -9.538559 -4.422605 23.69145 -9.330619 -5.36122 23.56755 -9.054013 -6.253822 23.43828 -8.720296 -7.078823 23.30105 -8.384645 -7.777851 23.13566 -6.71308 7.463874 22.63654 -7.070394 7.123246 22.58465 -7.403076 6.769696 22.50018 -7.672496 6.43996 22.32791 -7.899233 6.097445 22.14426 -8.065483 5.732269 22.03646 -8.189258 5.265114 21.89469 -8.300168 4.401017 21.84292 -8.460835 2.955667 21.98747 -8.811736 1.05962 22.31859 -9.405678 -0.9728084 22.74218 -9.761177 -2.03685 22.73164 -9.862517 -2.673424 22.52488 -9.828214 -3.541581 22.39066 -9.704309 -4.507716 22.28637 -9.49709 -5.473561 22.1905 -9.201049 -6.418554 22.10193 -8.875249 -7.2248 21.98266 -8.506154 -7.973213 21.86499 -6.726844 7.451683 20.91775 -7.104087 7.089352 20.91144 -7.495052 6.670608 20.89389 -7.830215 6.268337 20.82746 -8.069173 5.927204 20.71755 -8.236374 5.598204 20.62014 -8.360857 5.175913 20.51689 -8.444878 4.474746 20.46885 -8.531744 3.215763 20.55113 -8.773217 1.398641 20.80686 -9.351948 -0.9690805 21.26387 -9.754982 -2.282035 21.33882 -9.899799 -2.94309 21.14921 -9.882627 -3.656839 20.9652 -9.76797 -4.594848 20.86465 -9.555788 -5.606566 20.80419 -9.279823 -6.51015 20.71842 -8.957893 -7.32284 20.62297 -8.568336 -8.10676 20.55029 -6.733321 7.445743 19.16334 -7.117142 7.074552 19.16297 -7.542709 6.617553 19.15793 -7.874267 6.222179 19.1451 -8.134565 5.85941 19.1178 -8.327633 5.497715 19.086 -8.456898 5.072027 19.0457 -8.524094 4.44818 19.03063 -8.57192 3.316195 19.09772 -8.725258 1.60686 19.33563 -9.168807 -0.7539957 19.75372 -9.579835 -2.338341 19.90061 -9.810976 -3.202719 19.77133 -9.827977 -3.825328 19.55882 -9.720972 -4.727416 19.46224 -9.528208 -5.678398 19.40344 -9.268684 -6.562141 19.31984 -8.940051 -7.41221 19.26094 -8.567739 -8.170701 19.2183 -6.742653 7.437761 17.40486 -7.117422 7.074566 17.40476 -7.552628 6.60766 17.40302 -7.876784 6.222181 17.41809 -8.12917 5.870081 17.46142 -8.32759 5.494193 17.51027 -8.458537 5.057135 17.53621 -8.514323 4.467159 17.56777 -8.522089 3.462012 17.6137 -8.565234 1.974257 17.7482 -8.815169 -0.04669797 18.07626 -9.301183 -2.217673 18.43053 -9.626394 -3.475877 18.42145 -9.672004 -4.089912 18.20773 -9.576887 -4.823131 18.07086 -9.402678 -5.723231 18.02728 -9.146181 -6.63093 17.96814 -8.832594 -7.468862 17.93985 -8.483586 -8.197781 17.89988 -6.749518 7.432208 15.64549 -7.108541 7.085017 15.64751 -7.530799 6.634034 15.65469 -7.840108 6.269354 15.70139 -8.044181 5.980915 15.81654 -8.224581 5.62132 15.9532 -8.3596 5.164149 16.06662 -8.416549 4.558886 16.17351 -8.406023 3.593024 16.25166 -8.393589 2.203063 16.36259 -8.523973 0.3812712 16.63996 -8.950174 -2.00554 17.01678 -9.323975 -3.648243 17.09866 -9.413809 -4.367157 16.91043 -9.335213 -4.933977 16.71691 -9.173953 -5.765975 16.66489 -8.939435 -6.628138 16.62035 -8.653101 -7.4468 16.63731 -8.317747 -8.187098 16.639 -6.742244 7.438646 13.88415 -7.091884 7.103988 13.89354 -7.469966 6.705814 13.92639 -7.720903 6.414075 14.02771 -7.871894 6.189968 14.21893 -8.037115 5.834642 14.42773 -8.172807 5.365561 14.60351 -8.22955 4.728233 14.75444 -8.205735 3.755133 14.87125 -8.149295 2.42233 14.98219 -8.144197 0.8285375 15.14598 -8.368468 -1.231342 15.45337 -8.83323 -3.456086 15.75164 -9.048298 -4.57374 15.70355 -9.00953 -5.118559 15.50882 -8.863647 -5.807484 15.41931 -8.655732 -6.606725 15.39743 -8.386488 -7.433585 15.44633 -8.071415 -8.160837 15.47144 -6.75019 7.433104 12.12624 -7.068918 7.130514 12.14473 -7.35909 6.831332 12.21634 -7.518731 6.646976 12.3627 -7.630027 6.462971 12.58212 -7.785521 6.099082 12.85149 -7.919754 5.625618 13.16541 -7.972851 4.942829 13.37526 -7.944197 3.92796 13.55365 -7.875005 2.611644 13.72806 -7.805144 1.084694 13.8359 -7.918103 -0.8525617 14.0833 -8.386901 -3.430421 14.50659 -8.647325 -4.820406 14.58417 -8.624639 -5.35073 14.4186 -8.488409 -5.856243 14.28363 -8.29839 -6.604321 14.27818 -8.065014 -7.371775 14.34465 -7.772985 -8.078245 14.37583 -6.751131 7.433648 10.37962 -7.018866 7.181464 10.41551 -7.197638 7.003145 10.50342 -7.284378 6.907769 10.62435 -7.350205 6.802946 10.78921 -7.451386 6.547204 11.0812 -7.591266 6.00452 11.63848 -7.643641 5.190086 11.97018 -7.593122 4.09014 12.15585 -7.486245 2.715699 12.23822 -7.376286 1.162053 12.16291 -7.439166 -0.6268662 12.35241 -7.831383 -3.132681 12.89112 -8.158186 -4.852629 13.36136 -8.182008 -5.547335 13.40156 -8.059171 -5.967286 13.28097 -7.883384 -6.598222 13.25714 -7.676071 -7.289904 13.30556 -7.406698 -8.00012 13.36865 -6.668766 7.51024 8.683104 -6.82818 7.363857 8.82247 -6.93713 7.259018 9.002654 -7.017835 7.175266 9.196228 -7.088876 7.079634 9.390258 -7.149188 6.887998 9.582872 -7.212233 6.349869 9.89662 -7.235892 5.369021 10.23726 -7.162789 4.161335 10.43779 -6.99991 2.665493 10.31052 -6.839009 1.057225 9.837533 -6.825377 -0.2794561 9.794641 -7.040671 -2.003989 10.38359 -7.483228 -4.099298 11.6192 -7.654626 -5.427296 12.2814 -7.589813 -6.049318 12.37108 -7.436436 -6.563988 12.34267 -7.247951 -7.230066 12.39784 -7.017808 -7.88496 12.4757 -6.558026 7.611124 6.911067 -6.617942 7.557869 6.965586 -6.653319 7.523019 7.032004 -6.682619 7.48754 7.101948 -6.708961 7.420645 7.17069 -6.727144 7.184278 7.237662 -6.741773 6.457051 7.387457 -6.748037 5.372103 7.727054 -6.722241 4.145008 8.204337 -6.662355 2.645161 8.561969 -6.59996 1.08512 8.637618 -6.575335 -0.04898279 8.716378 -6.599514 -1.087489 9.002249 -6.807734 -2.515858 9.805171 -7.050941 -4.518354 10.90692 -7.088139 -5.911683 11.47074 -6.982226 -6.544589 11.56707 -6.820526 -7.154291 11.63134 -6.627068 -7.732297 11.69805 -6.520474 7.645119 5.329482 -6.549062 7.620792 5.339354 -6.559487 7.609214 5.350995 -6.567433 7.594214 5.36317 -6.574202 7.548495 5.377704 -6.578228 7.35029 5.421154 -6.580276 6.748754 5.625484 -6.580583 5.880558 6.177457 -6.57416 4.748443 6.939846 -6.557162 3.231273 7.677931 -6.530259 1.470431 8.195997 -6.513901 0.1282466 8.445806 -6.462801 -0.7165332 8.581333 -6.471238 -1.462414 8.86363 -6.540945 -3.00984 9.569921 -6.605158 -5.382703 10.56027 -6.525142 -6.476892 10.87917 -6.382763 -7.051177 10.95243 -6.217633 -7.631674 11.04657 -6.513589 7.65084 4.329873 -6.53707 7.631115 4.330519 -6.54316 7.623267 4.330991 -6.547046 7.611728 4.329616 -6.549998 7.579836 4.32377 -6.551494 7.480836 4.33775 -6.551382 7.206809 4.506561 -6.549303 6.675536 5.043296 -6.540494 5.784428 5.842019 -6.506532 4.295095 6.793127 -6.436424 2.132919 7.689481 -6.455703 0.3537222 8.260715 -6.409883 -0.6015854 8.459417 -6.353902 -1.153305 8.581022 -6.309131 -2.28443 8.977095 -6.271782 -4.72602 9.87634 -6.127727 -6.325662 10.31823 -5.9765 -6.972827 10.40837 -5.827041 -7.534864 10.50676 -6.509077 7.653063 4.039264 -6.533957 7.632024 4.038261 -6.540009 7.623286 4.036341 -6.543274 7.608479 4.029602 -6.545577 7.574426 4.011209 -6.546598 7.528665 4.000938 -6.545567 7.451282 4.048867 -6.538959 7.269997 4.243032 -6.50988 6.831486 4.637513 -6.40621 5.676412 5.421195 -6.213806 3.367457 6.531659 -6.27414 0.9244447 7.749533 -6.285637 -0.4226616 8.250766 -6.231287 -0.978447 8.382781 -6.165197 -1.620142 8.566027 -6.053048 -3.296574 9.09403 -5.78841 -5.838805 9.757976 -5.604309 -6.865259 9.954628 -5.465376 -7.380404 10.03862 5.577243 -7.677483 28.99721 5.226102 -7.274728 29.81175 5.860293 -7.078008 29.34121 5.493128 -6.664953 30.14854 6.091138 -6.445767 29.68169 5.660556 -6.074446 30.48936 6.38343 -5.661393 29.99613 5.923743 -5.319877 30.78235 6.597633 -4.841033 30.30481 6.094351 -4.563854 31.07291 6.797817 -3.9691 30.53664 6.277858 -3.697308 31.30286 6.974545 -2.969072 30.70909 6.414471 -2.760988 31.48352 7.047361 -1.946901 30.84556 6.450336 -1.866299 31.63035 7.048964 -0.9530532 30.89865 6.449209 -0.9566395 31.69183 6.966967 -0.05177414 30.91745 6.389527 -0.05296969 31.69428 6.800779 0.6266589 30.9417 6.259461 0.6902676 31.68827 6.527159 1.167523 30.91423 6.076062 1.099687 31.71805 6.107404 2.186286 30.54767 5.799004 1.642349 31.5795 5.574036 4.148016 29.67579 5.376384 2.949824 30.97184 5.228182 5.96647 28.9809 4.928858 4.998288 30.01889 4.993229 7.252744 28.62795 4.610053 6.842358 29.28743 4.774899 7.935312 28.55009 4.38534 7.820697 29.0302 4.602391 8.31136 28.49872 4.226675 8.288651 28.92379 4.363991 8.656002 28.46993 4.060671 8.649806 28.81965 5.890563 -8.108886 28.07809 6.210058 -7.515055 28.41356 6.512291 -6.864567 28.72707 6.83044 -6.070541 29.04809 7.133457 -5.166728 29.33004 7.371189 -4.234154 29.56576 7.558474 -3.209664 29.74769 7.659839 -2.099561 29.87264 7.667763 -0.9908471 29.91777 7.55479 -0.05380731 29.94577 7.310403 0.6113486 29.97535 6.931264 1.369041 29.86131 6.455385 2.696486 29.43899 5.94164 4.815783 28.61964 5.637035 6.414072 28.16317 5.442142 7.367286 27.98019 5.217863 7.911561 27.97435 4.983336 8.317616 27.94712 4.661799 8.709208 27.98589 6.228428 -8.499831 27.04036 6.577675 -7.914616 27.35516 6.941036 -7.227835 27.65441 7.29462 -6.41962 27.96738 7.649024 -5.479798 28.22397 7.943433 -4.447802 28.43609 8.147387 -3.360619 28.6102 8.254796 -2.21565 28.72335 8.245987 -1.085103 28.77653 8.081217 -0.1357904 28.8136 7.717298 0.7111577 28.77054 7.222888 1.885018 28.51203 6.689094 3.630535 28.02977 6.341546 5.378853 27.51602 6.118194 6.646162 27.26828 5.909483 7.409368 27.19348 5.613768 7.922541 27.26655 5.309 8.342714 27.32226 5.031862 8.627565 27.45047 6.553009 -8.859142 25.89943 6.924169 -8.276 26.19128 7.344695 -7.548393 26.47337 7.74483 -6.708299 26.75976 8.122005 -5.761042 26.99051 8.461647 -4.654781 27.17146 8.69182 -3.486689 27.31525 8.799879 -2.291956 27.40135 8.753973 -1.149424 27.45644 8.513379 -0.215215 27.50523 8.037303 0.9020434 27.35439 7.455023 2.55631 26.91225 7.044333 4.247373 26.58843 6.811816 5.65873 26.36591 6.609488 6.655355 26.29064 6.352812 7.337743 26.30441 6.013226 7.859503 26.42 5.726729 8.187873 26.58711 5.483087 8.391716 26.78352 6.795721 -9.218048 24.67711 7.231265 -8.600863 24.9211 7.683966 -7.865877 25.17097 8.141703 -6.980293 25.39922 8.551383 -5.986613 25.59935 8.903008 -4.854014 25.75941 9.149179 -3.629052 25.85255 9.236694 -2.368745 25.92152 9.113901 -1.190516 25.96998 8.768624 -0.1760052 26.00164 8.263242 1.142304 25.83494 7.756614 2.929876 25.43774 7.470682 4.510204 25.21671 7.276816 5.770068 25.12749 7.050772 6.621455 25.15264 6.750568 7.219473 25.25585 6.417436 7.654637 25.45703 6.127554 7.936556 25.66357 5.845061 8.158097 25.84043 7.00061 -9.522717 23.36113 7.495538 -8.869834 23.55454 7.975959 -8.119517 23.76083 8.461003 -7.215477 23.94297 8.903574 -6.16491 24.09138 9.261718 -4.986667 24.2086 9.493534 -3.707486 24.27617 9.525236 -2.409676 24.32526 9.284632 -1.216536 24.36502 8.859133 -0.03110569 24.34559 8.353773 1.631414 24.0886 8.028205 3.236624 23.88759 7.848289 4.636816 23.80526 7.675154 5.731297 23.80373 7.420173 6.481729 23.88721 7.089036 7.021322 24.02415 6.724926 7.431102 24.2058 6.348906 7.771476 24.31384 5.969829 8.070101 24.37875 7.174175 -9.743007 21.97171 7.685791 -9.089271 22.12296 8.201332 -8.302124 22.26911 8.693829 -7.384946 22.40327 9.143381 -6.31074 22.50777 9.502218 -5.089404 22.58111 9.708408 -3.767082 22.62522 9.6712 -2.469175 22.6723 9.344496 -1.296917 22.73299 8.893387 0.009888648 22.70236 8.477409 1.781533 22.4752 8.278108 3.345268 22.36018 8.157965 4.664251 22.32151 7.986348 5.62262 22.37022 7.702003 6.292029 22.47009 7.303173 6.845607 22.56448 6.850129 7.324099 22.637 6.400552 7.728031 22.6648 5.950048 8.084051 22.67711 7.287962 -9.889102 20.54151 7.796336 -9.241348 20.6436 8.332167 -8.426796 20.73082 8.832083 -7.475923 20.80758 9.271507 -6.373306 20.86438 9.603515 -5.135298 20.9031 9.752551 -3.823306 20.93793 9.614385 -2.553781 21.00087 9.228742 -1.302744 21.05614 8.773395 0.2793343 20.95167 8.537075 1.935336 20.83751 8.448846 3.412172 20.7846 8.363015 4.665674 20.75657 8.172886 5.549761 20.79691 7.839657 6.194398 20.86451 7.371201 6.786969 20.9046 6.879492 7.296931 20.92099 6.4116 7.717628 20.92375 5.936044 8.093815 20.92446 7.313911 -9.974475 19.10423 7.826891 -9.314123 19.13326 8.342898 -8.507955 19.17263 8.841865 -7.530724 19.19929 9.269998 -6.396364 19.20709 9.56669 -5.159144 19.2195 9.653867 -3.894552 19.26311 9.427512 -2.659034 19.35955 9.016161 -1.289435 19.41065 8.66653 0.4254765 19.28426 8.553946 2.014473 19.20108 8.52417 3.440927 19.1569 8.460834 4.641299 19.13315 8.262544 5.482615 19.13955 7.878917 6.161677 19.15539 7.382419 6.776244 19.16597 6.892798 7.28374 19.16751 6.422049 7.708043 19.16642 5.935838 8.093426 19.16574 7.237252 -10.00079 17.66935 7.739492 -9.334809 17.64755 8.245594 -8.511121 17.61914 8.723316 -7.524815 17.60255 9.117715 -6.401924 17.57758 9.367674 -5.200809 17.58018 9.387009 -4.01143 17.65025 9.095819 -2.730125 17.74248 8.64982 -1.064898 17.69295 8.473646 0.5749155 17.59744 8.467254 2.081263 17.55502 8.484646 3.482501 17.52137 8.446752 4.66099 17.48008 8.260331 5.485202 17.44477 7.881474 6.159868 17.41745 7.394086 6.764571 17.40998 6.920598 7.257615 17.40699 6.439254 7.692569 17.4068 5.94005 8.089602 17.40656 7.076318 -9.953747 16.28829 7.557731 -9.280455 16.21885 8.039428 -8.45606 16.14886 8.482962 -7.464086 16.06914 8.826189 -6.375135 16.01063 9.012068 -5.22181 16.01722 8.947425 -4.086438 16.1333 8.670703 -2.792732 16.23784 8.305646 -0.9239826 16.1179 8.234767 0.6853681 16.01776 8.283542 2.150737 15.96037 8.334903 3.539 15.90495 8.325049 4.721056 15.83914 8.1687 5.559708 15.76469 7.853778 6.188333 15.68873 7.420217 6.738515 15.65247 6.944729 7.234643 15.64601 6.452868 7.68048 15.64725 5.943759 8.086338 15.64752 6.831248 -9.849445 14.99235 7.300696 -9.142112 14.87447 7.742426 -8.323903 14.77574 8.122563 -7.386892 14.65862 8.419983 -6.366894 14.59104 8.568065 -5.340868 14.62416 8.457379 -4.237825 14.75427 8.18872 -2.80157 14.82407 7.921683 -0.8565598 14.65486 7.912676 0.7740594 14.5269 7.993562 2.23342 14.42789 8.077687 3.620733 14.34743 8.106112 4.817821 14.26369 7.990145 5.676672 14.14843 7.736454 6.302266 14.00531 7.37957 6.784247 13.91311 6.939958 7.24224 13.88983 6.459717 7.675391 13.88855 5.946585 8.083995 13.88855 6.525664 -9.668083 13.77941 6.94081 -8.984773 13.63339 7.33948 -8.158584 13.48394 7.67065 -7.26244 13.35876 7.925279 -6.343274 13.31149 8.03098 -5.47865 13.3739 7.847809 -4.184541 13.40548 7.523953 -2.356868 13.31935 7.40352 -0.6279497 13.08953 7.473294 0.8759645 12.96646 7.596518 2.321791 12.8961 7.722167 3.731273 12.83937 7.792335 4.972831 12.75032 7.726298 5.861253 12.59912 7.535419 6.498908 12.35904 7.288513 6.881799 12.18863 6.915264 7.269877 12.13795 6.462019 7.674777 12.13056 5.948991 8.082136 12.12963 6.17999 -9.428379 12.70185 6.536726 -8.769021 12.53438 6.861826 -8.011511 12.36937 7.145701 -7.193258 12.2507 7.369719 -6.373058 12.20703 7.442421 -5.534707 12.18735 7.216523 -3.87089 11.87679 6.930561 -1.958016 11.57335 6.892006 -0.4838907 11.25933 6.999468 0.9026171 11.20017 7.13218 2.348936 11.19969 7.273278 3.800419 11.19581 7.378505 5.126438 11.1568 7.385881 6.12709 11.01978 7.281843 6.751018 10.67784 7.131412 7.042928 10.47526 6.846771 7.338675 10.40027 6.450887 7.686642 10.37674 5.949634 8.082077 10.37143 5.791395 -9.191245 11.78812 6.098409 -8.54386 11.60292 6.373461 -7.803455 11.42047 6.608329 -7.066936 11.30732 6.793178 -6.376175 11.25117 6.837622 -5.231328 10.93783 6.614745 -2.849826 9.932575 6.529363 -1.324461 9.475652 6.58391 -0.3311462 9.302468 6.657731 0.8430892 9.29771 6.727239 2.287503 9.307991 6.823055 3.79531 9.29483 6.945685 5.218956 9.344336 7.017754 6.387913 9.331439 6.972009 7.041286 9.100858 6.873997 7.29139 8.881476 6.703389 7.473572 8.719526 6.413905 7.721162 8.639465 5.945353 8.086347 8.618178 5.403936 -8.913002 11.00351 5.654551 -8.317821 10.8302 5.879852 -7.655194 10.66993 6.083085 -6.977809 10.56134 6.254435 -6.284113 10.48166 6.366508 -4.701619 10.03279 6.317804 -2.287221 9.068624 6.37906 -1.056854 8.694806 6.475755 -0.2232534 8.582227 6.524559 0.970282 8.466116 6.554249 2.487021 8.209397 6.599344 4.006166 7.801891 6.648751 5.314558 7.425812 6.679501 6.464475 7.210123 6.666624 7.23638 7.072417 6.632553 7.497806 6.986001 6.563453 7.599472 6.924249 6.374954 7.756447 6.894011 5.940206 8.091246 6.886643 5.018537 -8.676365 10.38441 5.233958 -8.075221 10.19882 5.403129 -7.479425 10.04342 5.574855 -6.894074 9.954509 5.770866 -5.850394 9.770605 6.011308 -3.364643 9.122081 6.123933 -1.665053 8.573696 6.243234 -0.8637102 8.3912 6.340746 -0.02144205 8.276138 6.363601 1.389037 7.998982 6.403504 3.070709 7.499743 6.498536 4.666137 6.822052 6.547537 5.854242 6.10943 6.565246 6.745669 5.59079 6.565193 7.361077 5.390092 6.554981 7.570352 5.343636 6.518362 7.639867 5.330584 6.362812 7.767129 5.325694 5.939233 8.092138 5.324956 4.649904 -8.428987 9.861083 4.817504 -7.904709 9.70169 4.967024 -7.355599 9.563344 5.127794 -6.871811 9.509696 5.373266 -5.636638 9.296929 5.726771 -2.781676 8.615683 5.869931 -1.383785 8.20436 5.956582 -0.6929655 8.029984 6.005753 0.3410884 7.787891 5.989946 1.995968 7.247016 6.094099 3.91432 6.449388 6.337851 5.592532 5.663076 6.471251 6.612176 4.963617 6.520005 7.185997 4.470188 6.536141 7.477573 4.318107 6.537395 7.58927 4.312587 6.508594 7.645331 4.322298 6.358346 7.769165 4.325912 5.937626 8.09235 4.327383 4.302038 -8.202362 9.434206 4.437189 -7.727241 9.294104 4.585165 -7.286059 9.210402 4.749943 -6.745666 9.143301 5.06798 -5.153737 8.854002 5.472203 -2.444087 8.249172 5.689587 -1.231961 7.975043 5.795482 -0.4494736 7.803779 5.804484 1.019393 7.373548 5.830461 2.892208 6.569586 5.986622 5.228731 5.207285 6.164716 6.569654 4.334009 6.319794 7.130631 4.018075 6.41279 7.373692 3.90422 6.473466 7.492419 3.919528 6.509171 7.570316 3.976156 6.492934 7.641258 4.016397 6.337252 7.779437 4.030207 5.920757 8.101101 4.034395 3.983384 -8.077976 9.134303 4.095383 -7.5803 8.977066 4.237507 -7.207094 8.92423 4.450136 -6.414743 8.809373 4.923922 -4.233757 8.4326 5.370298 -2.039607 8.0258 5.601368 -1.14698 7.878258 5.706267 -0.3292029 7.699896 5.67902 1.445256 7.125517 5.741954 3.447776 6.146957 5.944119 5.949076 4.431118 6.050919 6.95556 3.684593 6.120105 7.216449 3.537734 6.186099 7.310299 3.553842 6.299726 7.405272 3.671867 6.405293 7.514962 3.815443 6.414428 7.651252 3.926491 6.221842 7.852026 3.969558 5.821429 8.164323 3.980618 -6.257265 -5.914426 29.98899 -6.408264 -5.334437 30.25752 -6.598224 -4.639531 30.48122 -6.699733 -4.011757 30.7032 -6.820161 -3.275048 30.86512 -6.878567 -2.565492 31.0127 -6.9161 -1.736862 31.11591 -6.888313 -1.001481 31.18696 -6.832859 -0.2556928 31.20192 -6.726192 0.4527733 31.20384 -6.594463 0.7853266 31.29411 -6.448578 0.9442304 31.41009 -6.251451 1.287638 31.39853 -5.879269 2.598199 30.85455 -5.243263 5.665766 29.40251 -4.954342 7.305117 28.73363 -4.783153 7.880422 28.61129 -4.677812 8.201932 28.54043 + + + + + + + + + + -0.6639135 -0.5340412 0.5234682 -0.6685723 -0.5145142 0.5369231 0.4999342 -0.6471349 0.5755712 0.472825 -0.6554729 0.5888903 0.5746643 0.5489718 0.6069521 0.5750467 0.5551054 0.600982 -0.6613991 0.5674491 0.4904619 -0.6397505 0.5734694 0.5117149 0.4183439 0.7407127 -0.5256741 0.3823626 0.6213915 -0.6838651 -0.6418339 0.5534785 0.5307645 -0.6461272 0.5482834 0.5309473 -0.6104508 0.7916769 -0.02444911 -0.6111008 0.7909665 -0.03046238 -0.6113632 0.7913436 -0.003237187 -0.611572 0.7911806 -0.003619074 -0.611575 0.7911865 -1.56618e-4 -0.611888 0.7909443 -3.25211e-4 -0.6118866 0.7909453 6.17237e-4 -0.6134817 0.789709 5.09292e-5 -0.6134672 0.7897183 0.001772284 -0.6178472 0.7862982 2.55212e-4 -0.6178289 0.7863117 0.001171886 -0.6207056 0.7840438 1.64114e-4 -0.6207059 0.7840435 1.78936e-4 -0.6210529 0.7837688 6.48965e-5 -0.6210561 0.783766 3.14765e-4 -0.6215905 0.7833424 1.41122e-4 -0.6215915 0.7833415 4.14803e-4 -0.6221447 0.7829023 2.19872e-4 -0.6221433 0.7829034 -2.44559e-4 -0.6216693 0.78328 -8.31305e-5 -0.6216695 0.7832797 -3.85016e-4 -0.6209786 0.7838276 -1.53781e-4 -0.6209804 0.7838261 -3.14603e-4 -0.6206565 0.7840826 -2.06291e-4 -0.6206569 0.7840822 -4.84971e-4 -0.6209181 0.7838754 -5.71999e-4 -0.6209058 0.783884 -0.001382708 -0.6195846 0.7849293 -9.82153e-4 -0.6196742 0.7848591 -3.18419e-4 -0.6035298 0.7973395 0.001274585 -0.6099676 0.7922985 0.01423633 -0.5708293 0.8210678 0.001302719 -0.6412703 0.7606423 0.1009738 -0.5841466 0.8099789 0.05202883 -0.7371444 0.5856426 0.3371067 -0.6939371 0.6576985 0.2930598 -0.7191826 0.560691 0.4103681 -0.6925792 0.5922097 0.4118517 -0.6903077 0.5607992 0.457143 -0.6639118 0.5787032 0.4736284 0.5326781 0.8443651 -0.05745947 0.5321895 0.8444945 -0.06002765 0.5333011 0.8459091 -0.005272448 0.5328913 0.8461632 -0.00590384 0.5329078 0.8461734 -4.11422e-4 0.5325494 0.8463987 -5.8272e-4 0.5325498 0.8463987 2.52823e-5 0.5322871 0.846564 -5.96853e-5 0.5322881 0.8465634 8.2184e-5 0.5322306 0.8465995 6.56661e-5 0.5322318 0.8465988 8.47998e-5 0.532137 0.8466582 5.61582e-5 0.5321377 0.8466578 6.19711e-5 0.5318605 0.846832 -2.3283e-5 0.5318611 0.8468316 7.36869e-6 0.5315783 0.8470092 -7.9489e-5 0.5315792 0.8470087 -1.52191e-5 0.531316 0.8471739 -9.48877e-5 0.531315 0.8471745 -2.07768e-5 0.5310169 0.8473613 -1.13421e-4 0.5310153 0.8473623 -3.03358e-5 0.5307103 0.8475533 -1.24948e-4 0.5307106 0.8475531 -7.61803e-5 0.5307691 0.8475165 -5.84412e-5 0.5307698 0.847516 -1.65034e-4 0.5320367 0.8467214 2.14714e-4 0.5320352 0.8467223 5.89042e-6 0.5342351 0.8453357 6.86651e-4 0.5342426 0.8453305 0.001145899 0.5296741 0.848201 -6.27923e-4 0.531053 0.8472944 0.008658349 0.5091519 0.8606584 -0.005631208 0.5406717 0.839284 0.05724179 0.5029053 0.8641963 0.01585495 0.6663687 0.6511909 0.3631849 0.6358318 0.7125871 0.2965428 0.6590493 0.4857358 0.5742079 0.6373476 0.6199854 0.4576092 0.6069841 0.54659 0.5768967 0.606154 0.583403 0.5405722 0.4861646 -0.4906486 -0.7231237 0.5042231 -0.4449386 -0.7401275 0.524373 -0.5137076 -0.6790711 0.5361632 -0.4825486 -0.6925864 0.5555357 -0.5421426 -0.6304455 0.5688117 -0.5153307 -0.6410052 0.5896011 -0.570438 -0.5718138 0.5993104 -0.5499548 -0.5817018 0.6178212 -0.6052361 -0.5019825 0.6256933 -0.5911962 -0.5089156 0.6424275 -0.6341736 -0.430245 0.6506403 -0.6210355 -0.437015 0.6646047 -0.6617247 -0.3470175 0.6680657 -0.6567173 -0.3498727 0.67791 -0.6865174 -0.2629296 0.6837944 -0.67897 -0.2672545 0.6892518 -0.7011413 -0.182573 0.6895348 -0.7008088 -0.1827808 0.6909763 -0.7160223 -0.09931826 0.6913125 -0.7156648 -0.09955435 0.6900461 -0.7235205 -0.01882749 0.6818085 -0.7314006 -0.01380294 0.6774982 -0.7330586 0.06017798 0.6670852 -0.7419933 0.06665921 0.6626658 -0.7370169 0.1329669 0.6521613 -0.7451513 0.1394109 0.6469299 -0.7354133 0.2016161 0.6386834 -0.7411954 0.2066714 0.6323295 -0.7272095 0.2670689 0.6244551 -0.7322805 0.2717007 0.6170543 -0.7158412 0.3268262 0.6072705 -0.7215673 0.3325105 0.5990035 -0.7035818 0.3823186 0.5853039 -0.7111898 0.3893951 0.5760681 -0.6904023 0.437596 0.5609259 -0.6978193 0.445433 0.5481854 -0.67609 0.4923366 0.5357992 -0.6814171 0.4985881 0.5246277 -0.6594405 0.5384274 0.5067331 -0.6664698 0.5468453 -0.6685234 -0.3686873 -0.6458685 -0.642434 -0.3894593 -0.6600002 -0.6738688 -0.3983224 -0.6222863 -0.6679773 -0.4029118 -0.6256745 -0.7061362 -0.4115592 -0.5761864 -0.7057467 -0.411897 -0.5764222 -0.7475848 -0.4251559 -0.5102544 -0.7314931 -0.4407812 -0.5202209 -0.768127 -0.4543468 -0.451165 -0.7575468 -0.4647966 -0.4583528 -0.7888162 -0.473723 -0.3916063 -0.7856041 -0.477237 -0.3937908 -0.8149753 -0.4860712 -0.3155156 -0.802434 -0.5011408 -0.3239716 -0.8244629 -0.5106106 -0.2440038 -0.8158012 -0.5213252 -0.2503767 -0.8314493 -0.5268654 -0.1763666 -0.8291209 -0.5298991 -0.1782292 -0.8389444 -0.534174 -0.1040707 -0.8319841 -0.5438264 -0.1097974 -0.8360236 -0.5478055 -0.03120481 -0.8294207 -0.5574325 -0.03647589 -0.8270751 -0.5607829 0.03833228 -0.823808 -0.5657686 0.03530323 -0.8173791 -0.5676224 0.09846991 -0.8191126 -0.5648304 0.1001051 -0.8070924 -0.5676673 0.1623454 -0.8067787 -0.5681929 0.162065 -0.7880179 -0.5724992 0.2264344 -0.7848052 -0.5780177 0.2235541 -0.761702 -0.5814936 0.2857892 -0.761835 -0.5812548 0.2859204 -0.7406756 -0.5813233 0.3368425 -0.7453144 -0.5722023 0.3421856 -0.7230185 -0.5720984 0.3872308 -0.7292194 -0.5588494 0.3948754 -0.7016899 -0.5603608 0.4400308 -0.7054969 -0.5518779 0.4446405 -0.678693 -0.5498586 0.4868586 -0.6847628 -0.534654 0.4952223 -0.647393 -0.5775979 0.4972555 -0.6292588 -0.6025675 0.4908623 -0.604826 -0.6074449 0.5149721 -0.5822108 -0.6376129 0.5044606 -0.5822322 -0.62068 0.5251305 -0.5672801 -0.6405104 0.517629 -0.5335838 -0.6508069 0.5401285 -0.5082382 -0.6775448 0.5316269 -0.4825149 -0.6753383 0.5577613 -0.4616051 -0.6976857 0.5478644 -0.4466448 -0.6890556 0.5707109 -0.4246726 -0.7097231 0.5620911 -0.3796974 -0.7148624 0.5871982 -0.3540821 -0.7366448 0.5761774 -0.3177249 -0.7387347 0.5944089 -0.308773 -0.7463136 0.58964 -0.2506286 -0.7570119 0.6034221 -0.2361233 -0.7672011 0.5963625 -0.1865153 -0.7703795 0.6096947 -0.1790098 -0.7751401 0.6058989 -0.1128809 -0.7800344 0.6154709 -0.1004465 -0.7864897 0.6093806 -0.0496183 -0.7849431 0.617578 -0.04705494 -0.7861607 0.6162284 0.03622138 -0.7854815 0.6178244 0.03629261 -0.7855089 0.6177853 0.09827494 -0.7845135 0.6122751 0.08914208 -0.7817268 0.6172171 0.1717178 -0.7750418 0.6081309 0.1674761 -0.7741536 0.6104409 0.2412464 -0.7652972 0.5967583 0.2259739 -0.7629131 0.6057222 0.3086864 -0.746299 0.5897039 0.2990207 -0.7458456 0.595232 0.3670857 -0.7291917 0.5775185 0.3450534 -0.7302019 0.5896977 0.4358965 -0.7017516 0.563506 0.414739 -0.7052089 0.5750409 0.478707 -0.6849964 0.5491992 0.4591844 -0.6879035 0.562084 -0.6712874 -0.5879831 0.4512751 -0.6498141 -0.6173146 0.4434687 -0.6278399 -0.6239134 0.4653486 -0.6057463 -0.6514793 0.4567781 -0.6070005 -0.636474 0.4758688 -0.5908739 -0.6571159 0.4680457 -0.5617591 -0.6643638 0.4929985 -0.5342843 -0.6936739 0.4830702 -0.5062839 -0.6949998 0.5105409 -0.4820877 -0.7202215 0.4988713 -0.4665604 -0.7124862 0.5241039 -0.4384062 -0.7391971 0.511261 -0.4019116 -0.7413958 0.5374006 -0.3730316 -0.7660073 0.5235269 -0.3349257 -0.7664304 0.5480959 -0.3181341 -0.779895 0.5390313 -0.2656043 -0.7891771 0.5537634 -0.2520101 -0.7988212 0.5462376 -0.1994907 -0.8036274 0.5607019 -0.1868244 -0.8112217 0.5540903 -0.1245607 -0.8139399 0.5674386 -0.1099299 -0.8213966 0.5596634 -0.05020999 -0.8192031 0.5713014 -0.04846268 -0.8199294 0.5704097 0.03741264 -0.8199798 0.5711685 0.03505265 -0.8192242 0.5724012 0.1131976 -0.8195976 0.5616459 0.09603625 -0.8153284 0.5709786 0.1833096 -0.8107582 0.5559396 0.1716069 -0.809243 0.5618513 0.2567016 -0.7966722 0.5471909 0.242416 -0.7954366 0.5554413 0.3229399 -0.7768293 0.5405979 0.3089758 -0.7771985 0.5481756 0.3903167 -0.7554969 0.5261915 0.3633839 -0.7590414 0.5401928 0.4543234 -0.7281981 0.5131451 0.4307286 -0.7336552 0.5255694 0.4966158 -0.7081092 0.5019505 0.4800425 -0.7120153 0.5124388 -0.6998074 -0.5915803 0.400378 -0.6798012 -0.6195668 0.3924377 -0.6492764 -0.6349831 0.4186128 -0.6271324 -0.6618004 0.4107618 -0.6214506 -0.6572229 0.4264472 -0.6111469 -0.6703916 0.4208025 -0.5894336 -0.6771333 0.4405208 -0.5620641 -0.7074705 0.4284501 -0.5267333 -0.717355 0.4560196 -0.5016962 -0.7426324 0.4436193 -0.4827594 -0.7400397 0.4682787 -0.4577773 -0.7631214 0.456164 -0.4191995 -0.7695283 0.4817655 -0.4001876 -0.7851465 0.4726466 -0.3527869 -0.7942377 0.4946998 -0.3354327 -0.8068602 0.4862733 -0.2775753 -0.8182507 0.5034064 -0.2665721 -0.8255449 0.4974085 -0.2123865 -0.8336232 0.5098672 -0.2009073 -0.8401615 0.5037508 -0.1305034 -0.8472225 0.5149593 -0.1209095 -0.852061 0.5092865 -0.05111008 -0.8542798 0.5172948 -0.04728055 -0.8557156 0.515282 0.03414595 -0.8555933 0.5165213 0.03441959 -0.8556699 0.5163762 0.1201708 -0.8519995 0.5095646 0.1100462 -0.8498266 0.515446 0.1958163 -0.8412929 0.5038675 0.1843842 -0.8403397 0.509737 0.2671595 -0.8247984 0.4983308 0.2575029 -0.8242931 0.5042154 0.3413235 -0.8035219 0.4876996 0.3230073 -0.8048008 0.4979578 0.4105018 -0.7789098 0.4741178 0.3891814 -0.7825793 0.485909 0.4743384 -0.7506684 0.4598917 0.4498865 -0.7575348 0.4730152 0.5143358 -0.7308159 0.4487391 0.4960877 -0.7366374 0.459633 -0.7204179 -0.6023486 0.3437649 -0.7109411 -0.6163176 0.3386965 -0.6810179 -0.6360178 0.3628996 -0.6487743 -0.6742532 0.3528097 -0.6330682 -0.677705 0.3740865 -0.6213446 -0.6916151 0.3682384 -0.6068461 -0.6956719 0.3844199 -0.5863783 -0.7179539 0.3751038 -0.546289 -0.7356396 0.4005032 -0.5216814 -0.7588153 0.3899332 -0.5000882 -0.7613315 0.4126575 -0.4810392 -0.7785328 0.4030981 -0.435713 -0.7935206 0.4248285 -0.4201418 -0.8059039 0.4171327 -0.3722453 -0.8193153 0.4360689 -0.3531126 -0.832928 0.426078 -0.2940486 -0.8444077 0.4477847 -0.2781493 -0.8541957 0.439298 -0.2246586 -0.8622258 0.4539771 -0.2142239 -0.8678248 0.4483174 -0.1360243 -0.8781162 0.4587041 -0.1288003 -0.881563 0.4541555 -0.05370402 -0.8867276 0.4591623 -0.051301 -0.8875793 0.4577896 0.0314415 -0.8879024 0.4589563 0.03439933 -0.8886545 0.4572854 0.1238998 -0.8822322 0.4542193 0.1186337 -0.8812654 0.4574903 0.2056553 -0.8693396 0.4493936 0.1972724 -0.868902 0.4539747 0.2786446 -0.8523739 0.4425109 0.2677388 -0.8523271 0.4492824 0.3602527 -0.8284991 0.4287273 0.3411464 -0.8306818 0.4399852 0.4238349 -0.8031537 0.4186983 0.4106118 -0.805954 0.4264227 0.4917795 -0.7711217 0.4043817 0.4726571 -0.777121 0.415546 0.535412 -0.7478929 0.3924161 0.5150995 -0.756156 0.4036096 -0.7320253 -0.6169494 0.2889853 -0.729142 -0.621236 0.2870853 -0.7077023 -0.6389036 0.3015953 -0.6806036 -0.6722036 0.2914124 -0.6527713 -0.6870661 0.319108 -0.6314403 -0.7107415 0.310048 -0.621383 -0.7112675 0.3286059 -0.6056195 -0.7282773 0.3206825 -0.5728962 -0.7434664 0.3450329 -0.544018 -0.7705163 0.3321882 -0.5155544 -0.7793943 0.3560173 -0.4994891 -0.7937383 0.3471168 -0.456864 -0.8098495 0.3679935 -0.4352562 -0.8265781 0.3568204 -0.3878759 -0.8410047 0.3771781 -0.3720594 -0.8520746 0.3681588 -0.3113166 -0.867493 0.3879923 -0.2942921 -0.8773825 0.3789358 -0.2361305 -0.8880403 0.3944956 -0.2255318 -0.8933185 0.3887383 -0.1414963 -0.9056391 0.3997458 -0.1355822 -0.908146 0.3960914 -0.05556207 -0.9147227 0.4002439 -0.05402767 -0.9151967 0.3993698 0.03127473 -0.9160133 0.3999271 0.03178423 -0.9161224 0.3996369 0.1280407 -0.9090336 0.3965647 0.1234869 -0.9084116 0.399424 0.2154045 -0.8947651 0.3911474 0.206304 -0.8946613 0.3962575 0.2916041 -0.8764275 0.3831996 0.279001 -0.8771978 0.3907464 0.3752959 -0.8494062 0.3710287 0.3599979 -0.8519414 0.3802599 0.4404044 -0.8224543 0.360018 0.4233795 -0.8271005 0.3696681 0.5058286 -0.7890093 0.3487147 0.4910867 -0.7942894 0.3576848 0.5582981 -0.7586144 0.3358683 0.5363695 -0.7689875 0.3478017 -0.7445293 -0.6251074 0.2343435 -0.7391362 -0.6327254 0.2309464 -0.7218005 -0.6484735 0.2418394 -0.7085375 -0.6652606 0.2353788 -0.6796153 -0.6862666 0.2591548 -0.6515319 -0.7168469 0.2482677 -0.6329264 -0.7261716 0.2684752 -0.620731 -0.7388919 0.2621675 -0.596678 -0.7514581 0.2815779 -0.5717554 -0.7747359 0.2699631 -0.532249 -0.7934763 0.2951381 -0.515069 -0.8080215 0.2860165 -0.4764944 -0.824016 0.3065139 -0.4566354 -0.8389238 0.2961269 -0.4005557 -0.860282 0.3153889 -0.3880251 -0.8686605 0.3080023 -0.3272839 -0.8875399 0.3242812 -0.3116738 -0.8962162 0.3156834 -0.2466447 -0.9109184 0.3307479 -0.2364865 -0.9156677 0.325003 -0.1468693 -0.9300854 0.3367055 -0.1414187 -0.9321129 0.3334162 -0.05683112 -0.9395572 0.3376426 -0.05561852 -0.9398791 0.3369481 0.03386193 -0.9410949 0.3364428 0.03133797 -0.9406601 0.3379004 0.1323969 -0.9331603 0.3341899 0.1279547 -0.9327731 0.3369898 0.2272136 -0.9171428 0.3274493 0.2156516 -0.9175447 0.334075 0.3075478 -0.8966987 0.3183485 0.2919225 -0.8986815 0.327342 0.388864 -0.86799 0.3088338 0.3754194 -0.8709577 0.3170065 0.4612643 -0.8361191 0.2968843 0.4402147 -0.8432739 0.3083834 0.5216661 -0.8034079 0.2870546 0.5055301 -0.8102126 0.2966398 0.5856653 -0.7633563 0.2725498 0.5591281 -0.7780367 0.2864171 -0.7627324 -0.6222306 0.1762628 -0.7517697 -0.6370086 0.1704774 -0.7265642 -0.6630754 0.1800982 -0.7233343 -0.6670773 0.1783132 -0.7017798 -0.6862934 0.1910671 -0.6801964 -0.7100398 0.1821443 -0.6481365 -0.7336066 0.2043052 -0.6323704 -0.7492622 0.1967588 -0.611204 -0.7620088 0.2139449 -0.5958665 -0.776139 0.20628 -0.5502431 -0.803113 0.2285656 -0.5319364 -0.8178394 0.2195052 -0.4894689 -0.8390036 0.2376828 -0.4770814 -0.8479108 0.2311724 -0.4137672 -0.875662 0.249024 -0.4009771 -0.8835931 0.2418281 -0.340201 -0.9044877 0.2572262 -0.3275427 -0.9111095 0.250191 -0.2541591 -0.930814 0.2626568 -0.2467319 -0.9340391 0.2582525 -0.1531699 -0.9509615 0.2687215 -0.1468651 -0.9530133 0.2649461 -0.05951493 -0.9608492 0.2706045 -0.05679053 -0.9614614 0.2690111 0.03769111 -0.9624727 0.2687486 0.03381854 -0.9619709 0.2710507 0.1367402 -0.9540598 0.2665935 0.1323887 -0.9538967 0.2693594 0.2381235 -0.9358671 0.2597112 0.2273288 -0.9367566 0.2660991 0.3217173 -0.9127994 0.251586 0.3077169 -0.9153763 0.2596086 0.4002615 -0.8832727 0.2441728 0.3891761 -0.8863038 0.2510134 0.4779604 -0.8468496 0.2332376 0.4616782 -0.8532053 0.242681 0.5396982 -0.8122518 0.2212987 0.5215494 -0.820958 0.2324097 0.6043952 -0.7691249 0.2077344 0.5862797 -0.7801074 0.2184231 -0.782485 -0.6128165 0.1103332 -0.7710391 -0.6280741 0.1049842 -0.7342478 -0.668191 0.1200047 -0.7293516 -0.6739567 0.1175954 -0.7130034 -0.689683 0.126347 -0.7029474 -0.700737 0.1217893 -0.6640951 -0.7348256 0.1378735 -0.6477038 -0.7506864 0.1301917 -0.6193832 -0.7716628 0.1445719 -0.6098988 -0.780137 0.139319 -0.5707493 -0.8060063 0.1568414 -0.550057 -0.8222691 0.1459826 -0.5014981 -0.849361 0.1645773 -0.4911777 -0.8564918 0.1586386 -0.4316954 -0.884643 0.1761991 -0.4150614 -0.8943855 0.1667292 -0.3525063 -0.9174382 0.1845172 -0.3400988 -0.9234805 0.177529 -0.2598943 -0.9469219 0.1891932 -0.2539138 -0.9492736 0.1854928 -0.1617683 -0.9674515 0.1945992 -0.153061 -0.9699246 0.1892583 -0.06418776 -0.978268 0.1971588 -0.05917823 -0.9791898 0.194127 0.04163962 -0.9799104 0.1950433 0.03739947 -0.9795616 0.1976376 0.1408622 -0.9710804 0.1927713 0.1367259 -0.9711421 0.1954204 0.2444829 -0.951385 0.1873358 0.2380205 -0.9522227 0.1913591 0.3308653 -0.9261428 0.1810735 0.3216521 -0.9283031 0.18653 0.4140092 -0.8938755 0.1719975 0.4012555 -0.8981193 0.1799328 0.4915233 -0.8557296 0.1616536 0.4794366 -0.8611158 0.1691748 0.5586977 -0.8159254 0.1487372 0.539461 -0.8265969 0.1603729 0.6142092 -0.7765267 0.1405466 0.604501 -0.7829928 0.1466318 -0.7917627 -0.6093693 0.04220038 -0.7892779 -0.6126813 0.04076963 -0.7482761 -0.6614876 0.05017 -0.742786 -0.6678506 0.0473777 -0.7181985 -0.6937453 0.05393064 -0.7142037 -0.6980155 0.05183994 -0.6747885 -0.7352784 0.06345152 -0.6626198 -0.7467331 0.05766099 -0.6248506 -0.777435 0.07181054 -0.6171736 -0.783904 0.06776076 -0.5789667 -0.811551 0.07862973 -0.5695635 -0.8186312 0.07375973 -0.5146148 -0.8530497 0.08647549 -0.5049744 -0.8593329 0.08091902 -0.4450392 -0.8905745 0.09389972 -0.4342166 -0.8965367 0.08762472 -0.3620943 -0.9266107 0.1013914 -0.3513719 -0.9313726 0.09530508 -0.2678399 -0.9573571 0.1083028 -0.2594395 -0.9602352 0.1031478 -0.1692482 -0.9791151 0.1126441 -0.1614527 -0.9809747 0.1078044 -0.06433349 -0.9915578 0.1125808 -0.06318777 -0.9917117 0.111871 0.04476106 -0.9928192 0.110935 0.0409879 -0.9927214 0.1132444 0.1464196 -0.98326 0.1084489 0.1411567 -0.9836619 0.1117326 0.249534 -0.9627478 0.1041622 0.2439065 -0.9637963 0.1077334 0.3412293 -0.9349833 0.09679251 0.3303704 -0.9381772 0.1033387 0.4289169 -0.898905 0.0894435 0.4168661 -0.9038219 0.09658539 0.5045664 -0.8594468 0.08224451 0.4939332 -0.8649595 0.08874273 0.5691532 -0.8189358 0.07354539 0.5571333 -0.8264951 0.08067435 0.6197062 -0.7818263 0.06864476 0.6136687 -0.7862343 0.07243287 -0.7902003 -0.6122031 -0.02812188 -0.7935788 -0.6079031 -0.02620476 -0.7556506 -0.6544289 -0.02674096 -0.7562381 -0.6537623 -0.02643716 -0.726922 -0.6864296 -0.01997226 -0.7202762 -0.6932941 -0.02335929 -0.6823658 -0.7308597 -0.01487064 -0.6776444 -0.7351856 -0.01732754 -0.6352697 -0.7722531 -0.007588744 -0.6268002 -0.7790846 -0.01219969 -0.5814666 -0.81356 -0.004124164 -0.5793223 -0.8150815 -0.00527805 -0.5276031 -0.8494864 0.00283569 -0.518221 -0.8552425 -0.002706646 -0.4499251 -0.8930514 0.005179107 -0.4461716 -0.894943 0.002858638 -0.3678319 -0.9298361 0.01023441 -0.359896 -0.9329764 0.005475282 -0.2761979 -0.9609621 0.01632684 -0.2676658 -0.9634478 0.0111137 -0.1760393 -0.9841721 0.02038043 -0.1694322 -0.9854077 0.01626616 -0.06562036 -0.997615 0.02140873 -0.06383979 -0.9977543 0.02027225 0.04684472 -0.9986932 0.02043008 0.04527229 -0.9987453 0.02140796 0.1538265 -0.9879522 0.01697158 0.1482635 -0.9887378 0.02038252 0.2540377 -0.9671075 0.01296162 0.2484239 -0.9685115 0.01646113 0.3473948 -0.9376887 0.007539689 0.340012 -0.9403437 0.01207369 0.4358083 -0.9000289 0.004394233 0.4319835 -0.9018567 0.006703257 0.5146372 -0.8574068 -0.001531839 0.5050382 -0.8630867 0.004242479 0.5721913 -0.8201042 -0.005120992 0.5681746 -0.8229036 -0.002717554 0.6306537 -0.7759707 -0.0120638 0.6212514 -0.7835867 -0.006232321 -0.7937018 -0.6004741 -0.09730541 -0.789915 -0.6051273 -0.09927457 -0.754335 -0.6488966 -0.09955942 -0.7614325 -0.6411508 -0.09563535 -0.7286434 -0.6776603 -0.09927451 -0.7309493 -0.6753459 -0.09808677 -0.6841427 -0.7228206 -0.09736067 -0.6868095 -0.7204722 -0.09598129 -0.6383025 -0.7639235 -0.09481954 -0.6375943 -0.764465 -0.0952211 -0.5875225 -0.8040403 -0.0913062 -0.5842727 -0.8062004 -0.09309381 -0.5297289 -0.8434833 -0.08901357 -0.5286158 -0.8441152 -0.08963853 -0.4531635 -0.8872525 -0.08617323 -0.4509517 -0.8882473 -0.08751833 -0.371939 -0.9245122 -0.08329886 -0.3678447 -0.9259184 -0.08582234 -0.2776063 -0.9572223 -0.08161044 -0.2769581 -0.9573765 -0.08200371 -0.1756721 -0.9811284 -0.08078646 -0.1763328 -0.9810432 -0.08038103 -0.06653654 -0.9946318 -0.07924938 -0.06555378 -0.9946471 -0.07987481 0.04469847 -0.995953 -0.07797229 0.04714113 -0.9957185 -0.0795145 0.1539447 -0.9849705 -0.07832115 0.1547838 -0.9847972 -0.07884562 0.2575019 -0.9628567 -0.08124095 0.2541661 -0.963916 -0.07915651 0.3533722 -0.9316428 -0.08467489 0.3478887 -0.9339998 -0.08135098 0.4356977 -0.8962088 -0.08353024 0.4379094 -0.8950018 -0.08489567 0.5148241 -0.8529822 -0.08589255 0.5134907 -0.8538689 -0.08506149 0.5762726 -0.8123097 -0.08979493 0.5735346 -0.8144308 -0.08809489 0.6341838 -0.7673434 -0.09484398 0.6322195 -0.769126 -0.09350782 -0.7941473 -0.5827497 -0.1724328 -0.7947991 -0.5819578 -0.1721037 -0.7503046 -0.6386922 -0.1706317 -0.7572699 -0.6313681 -0.1670836 -0.7128318 -0.6782594 -0.1784239 -0.730257 -0.6619079 -0.1691229 -0.6827922 -0.7078431 -0.1809783 -0.6892882 -0.7024081 -0.1774958 -0.6365851 -0.7495153 -0.1816212 -0.6422739 -0.7454145 -0.1784421 -0.585898 -0.789 -0.1849396 -0.5932348 -0.7845012 -0.1806391 -0.5245489 -0.831076 -0.1848275 -0.5278331 -0.8294009 -0.1829929 -0.4503588 -0.8734203 -0.18524 -0.4547852 -0.8716632 -0.1826851 -0.3710515 -0.909972 -0.1851267 -0.3733062 -0.9093297 -0.1837443 -0.2800931 -0.9421702 -0.1840201 -0.27894 -0.9423732 -0.1847298 -0.1763207 -0.9669845 -0.1839891 -0.1761103 -0.9669978 -0.184121 -0.06607133 -0.9806923 -0.1840583 -0.06671649 -0.9807256 -0.1836473 0.04587978 -0.9818317 -0.1841235 0.04484587 -0.9819996 -0.1834821 0.1550338 -0.9705862 -0.1841928 0.1544122 -0.9707585 -0.1838067 0.2580719 -0.9483551 -0.1844497 0.2584257 -0.9482148 -0.1846749 0.3510081 -0.9182803 -0.1831789 0.3558968 -0.9157862 -0.1862074 0.4307826 -0.8843137 -0.180044 0.4389612 -0.8792397 -0.1850692 0.5085879 -0.8418313 -0.1807168 0.5104911 -0.8404269 -0.1818837 0.5758243 -0.797415 -0.1804319 0.5810711 -0.792858 -0.1836647 0.6289091 -0.7568942 -0.1777209 0.6369248 -0.7488927 -0.1829936 -0.7805216 -0.5727066 -0.2505855 -0.7928299 -0.558833 -0.2431594 -0.7472276 -0.6146032 -0.2528121 -0.7553676 -0.6063454 -0.2485259 -0.7046511 -0.6621016 -0.2551242 -0.716507 -0.6515212 -0.2492749 -0.6673903 -0.6964141 -0.2638136 -0.685758 -0.6821377 -0.2538192 -0.626851 -0.7303792 -0.2713007 -0.6416252 -0.7205228 -0.2629905 -0.5775073 -0.7676158 -0.2779414 -0.5912068 -0.7600551 -0.2697979 -0.5191253 -0.8067303 -0.2823034 -0.5276778 -0.8029752 -0.2771045 -0.4429441 -0.8497143 -0.2859834 -0.4511027 -0.8470677 -0.2810385 -0.3632587 -0.8851442 -0.2907972 -0.372182 -0.8832419 -0.2852443 -0.2739003 -0.9158391 -0.2936285 -0.2811909 -0.915031 -0.2892232 -0.1691687 -0.9399321 -0.2964954 -0.1768798 -0.9400109 -0.2917076 -0.06525033 -0.9527612 -0.2966287 -0.06645435 -0.952917 -0.2958598 0.04092729 -0.9547242 -0.2946636 0.04604339 -0.953476 -0.2979323 0.1469987 -0.9451313 -0.2917503 0.1555091 -0.9420611 -0.2972166 0.2520213 -0.9231511 -0.2903055 0.2589159 -0.9198175 -0.2947855 0.3429377 -0.8948565 -0.2857018 0.3533092 -0.8887067 -0.2921867 0.4202793 -0.8636143 -0.2784524 0.4336529 -0.8542119 -0.2868224 0.5034245 -0.8184503 -0.2769529 0.5103584 -0.8126582 -0.2812849 0.5645987 -0.780296 -0.2690103 0.5806855 -0.764819 -0.2790277 0.6201478 -0.7385218 -0.2645798 0.6323568 -0.7251998 -0.2724155 -0.7679507 -0.557011 -0.316213 -0.7756221 -0.5488919 -0.3116541 -0.7247053 -0.6049863 -0.3298392 -0.7482113 -0.5835968 -0.3155862 -0.693824 -0.6347556 -0.3401377 -0.7126162 -0.6193544 -0.3295125 -0.6540299 -0.6719352 -0.3474883 -0.6714076 -0.6594099 -0.3382164 -0.6059278 -0.7098753 -0.3590664 -0.6302896 -0.6952269 -0.3455356 -0.5571018 -0.742251 -0.372426 -0.5822764 -0.7299208 -0.3580085 -0.5010243 -0.776554 -0.3820189 -0.5214819 -0.7686879 -0.3703725 -0.4297436 -0.8147119 -0.3893135 -0.4465237 -0.8102543 -0.3796113 -0.3543888 -0.848008 -0.3940699 -0.3652692 -0.8465104 -0.3872966 -0.2629439 -0.877602 -0.4008431 -0.2739788 -0.8773509 -0.393943 -0.1615739 -0.8992313 -0.4065429 -0.1709107 -0.9001822 -0.4005767 -0.06322878 -0.9108178 -0.4079378 -0.06632488 -0.9114728 -0.4059785 0.03980827 -0.9126392 -0.4068234 0.0413807 -0.9121345 -0.407797 0.1406967 -0.9044498 -0.4027099 0.1480045 -0.9012461 -0.407247 0.2432555 -0.8844754 -0.3981581 0.2520917 -0.8794026 -0.4038577 0.3317672 -0.8592432 -0.3893995 0.3479369 -0.8482126 -0.3993437 0.408316 -0.8303381 -0.3792319 0.4294895 -0.8135926 -0.3919261 0.4816706 -0.7951444 -0.3684275 0.5040095 -0.7746511 -0.3819558 0.5451261 -0.7580182 -0.3581147 0.568066 -0.733906 -0.3724019 0.5958413 -0.7255033 -0.34441 0.6204226 -0.6965112 -0.3604831 -0.751986 -0.5307546 -0.3909179 -0.7604539 -0.5218224 -0.3865379 -0.703886 -0.5887454 -0.3973959 -0.7249372 -0.570385 -0.3861697 -0.6630012 -0.6225284 -0.4157979 -0.6959966 -0.5985453 -0.3966516 -0.6290633 -0.6456808 -0.4328693 -0.6583329 -0.6275404 -0.4156812 -0.5897048 -0.6739231 -0.4450573 -0.6136652 -0.6609543 -0.4319197 -0.5329774 -0.7106519 -0.4592484 -0.5615803 -0.6989684 -0.4427989 -0.4762576 -0.7403044 -0.4744766 -0.5038558 -0.7322458 -0.4581982 -0.4122785 -0.7706826 -0.4858753 -0.432774 -0.7670835 -0.4735925 -0.3403778 -0.7996351 -0.4946987 -0.3560838 -0.7987624 -0.4849569 -0.2469263 -0.8280624 -0.5033291 -0.2606934 -0.8291294 -0.4945538 -0.1541741 -0.845766 -0.5107939 -0.164878 -0.8478972 -0.5038706 -0.05937355 -0.855903 -0.5137168 -0.06528216 -0.8576567 -0.510062 0.04310709 -0.8571197 -0.5133104 0.03928482 -0.8586488 -0.5110567 0.137423 -0.8505215 -0.5076693 0.141051 -0.8486822 -0.5097482 0.2336453 -0.8334501 -0.5007702 0.241043 -0.8285172 -0.505428 0.3190792 -0.8118802 -0.4889161 0.3383172 -0.7967754 -0.5006901 0.3894529 -0.7905845 -0.4725491 0.4175579 -0.7658292 -0.4890307 0.4554272 -0.7642479 -0.4566303 0.487196 -0.7326653 -0.4752281 0.5208016 -0.7303426 -0.4420016 0.5498481 -0.6969354 -0.4603782 0.5792832 -0.6903554 -0.4334058 0.6003364 -0.6630508 -0.4471688 -0.7210301 -0.514548 -0.4640646 -0.7414453 -0.4961773 -0.451738 -0.6846505 -0.5513697 -0.4767025 -0.708355 -0.5324476 -0.4633926 -0.6454601 -0.5872843 -0.4883427 -0.6713654 -0.569004 -0.4748716 -0.6025416 -0.6183197 -0.5046033 -0.6326516 -0.6024273 -0.4866554 -0.5579988 -0.642279 -0.5254666 -0.5929633 -0.6278387 -0.5041955 -0.5094066 -0.6662226 -0.5446581 -0.5399076 -0.657613 -0.5253999 -0.4520095 -0.6945128 -0.5597674 -0.4786794 -0.689485 -0.5435776 -0.3838847 -0.7217666 -0.5759215 -0.4136676 -0.7192573 -0.558165 -0.3136628 -0.7455491 -0.588024 -0.3386016 -0.7455841 -0.5739804 -0.232041 -0.7693342 -0.5952157 -0.25025 -0.7718641 -0.5844663 -0.1405605 -0.7851026 -0.6032053 -0.1580407 -0.7903097 -0.5919745 -0.05288577 -0.793164 -0.6067075 -0.06018227 -0.7961999 -0.6020332 0.03630936 -0.7966938 -0.6032916 0.04127812 -0.7940425 -0.6064592 0.1264372 -0.793376 -0.5954563 0.1404122 -0.7845762 -0.6039243 0.2214605 -0.7757033 -0.590965 0.2335134 -0.7658538 -0.5991157 0.2979721 -0.7603911 -0.5770771 0.3217093 -0.7384346 -0.5926362 0.3641201 -0.7462835 -0.557205 0.3987292 -0.7126041 -0.5772439 0.4325142 -0.7208421 -0.5415886 0.4629917 -0.6874005 -0.5595707 0.5009735 -0.6873318 -0.5259283 0.5310636 -0.6489518 -0.5448238 0.5500361 -0.6639875 -0.5065382 0.582577 -0.6191689 -0.52653 -0.6937957 -0.5003345 -0.5179893 -0.7105044 -0.4869551 -0.5079944 -0.6476616 -0.5367851 -0.5407367 -0.6833576 -0.5145254 -0.5179634 -0.6151735 -0.5528748 -0.5620419 -0.6512713 -0.5324774 -0.5406603 -0.5803108 -0.5714522 -0.5802429 -0.6109955 -0.5575817 -0.5619495 -0.5331303 -0.601487 -0.5949669 -0.5622372 -0.5907548 -0.578704 -0.476975 -0.6285355 -0.6143599 -0.5120489 -0.6213783 -0.5930388 -0.4212569 -0.6485411 -0.6339851 -0.4539156 -0.6460831 -0.6136263 -0.3631277 -0.667833 -0.649721 -0.3877956 -0.6693741 -0.6336822 -0.2895885 -0.6903623 -0.662977 -0.3114218 -0.693826 -0.6493242 -0.2167881 -0.706114 -0.6740964 -0.2337606 -0.7109649 -0.6632381 -0.1347448 -0.7189982 -0.6818251 -0.1469151 -0.7245669 -0.6733638 -0.05062472 -0.7276244 -0.6841052 -0.05369335 -0.729425 -0.6819504 0.0274735 -0.7320352 -0.6807126 0.03616505 -0.7259213 -0.6868264 0.1145591 -0.7295938 -0.6742174 0.1329511 -0.7152118 -0.6861459 0.205969 -0.715468 -0.6675944 0.2202057 -0.701431 -0.6778672 0.2736024 -0.7068321 -0.6523267 0.2975104 -0.6815014 -0.6686131 0.3438372 -0.6925762 -0.6341248 0.3763183 -0.6573464 -0.6529014 0.410153 -0.6725392 -0.6160078 0.4446161 -0.6313119 -0.6354225 0.4661329 -0.6559576 -0.5936664 0.5026735 -0.6052023 -0.6172923 0.5207571 -0.6292194 -0.5769706 0.5513562 -0.5818597 -0.5978676 -0.6682209 -0.4664247 -0.5795938 -0.6830266 -0.4549057 -0.5714329 -0.6209183 -0.5138512 -0.5919606 -0.6495379 -0.4979329 -0.5745984 -0.5813704 -0.5363255 -0.6118525 -0.6153015 -0.5215619 -0.5910816 -0.5430075 -0.5475039 -0.6366965 -0.5803291 -0.5374986 -0.6118117 -0.5013805 -0.5599478 -0.6596031 -0.5350713 -0.5547456 -0.6371468 -0.4553975 -0.5763414 -0.6785601 -0.4827587 -0.5755562 -0.6600599 -0.397629 -0.6003866 -0.6938495 -0.4234644 -0.6018761 -0.6770696 -0.334891 -0.616013 -0.713005 -0.3648869 -0.6219603 -0.6928369 -0.2668397 -0.6332659 -0.7264784 -0.2887147 -0.6395518 -0.7124727 -0.1956494 -0.6479635 -0.7361146 -0.214466 -0.6548799 -0.7246631 -0.1220414 -0.6553355 -0.7454136 -0.1385155 -0.6636314 -0.7351237 -0.04486328 -0.6608902 -0.7491406 -0.05236214 -0.6657078 -0.7443731 0.02789127 -0.6643663 -0.7468866 0.02949267 -0.663201 -0.74786 0.1047711 -0.6666573 -0.7379642 0.116719 -0.6566586 -0.7451015 0.1885046 -0.6593893 -0.7277855 0.1994677 -0.6466514 -0.7362436 0.2605804 -0.6476517 -0.7159924 0.2770566 -0.6271211 -0.7279827 0.3221754 -0.6400035 -0.6975662 0.3537011 -0.6020706 -0.7158258 0.3857442 -0.6227969 -0.6806801 0.4161811 -0.5819566 -0.6986558 0.4483091 -0.5973862 -0.6649426 0.4749228 -0.5570036 -0.6813189 0.4943062 -0.5820107 -0.6456973 0.5245445 -0.5347891 -0.6624603 -0.6319069 -0.4419856 -0.6366651 -0.6557647 -0.4276431 -0.6221688 -0.5967438 -0.4622656 -0.6559019 -0.6271576 -0.4489439 -0.6364925 -0.5606922 -0.4847653 -0.6712875 -0.5882667 -0.4744366 -0.6548681 -0.5183908 -0.5096202 -0.6867011 -0.5468415 -0.5031461 -0.669185 -0.4696207 -0.5312781 -0.7051241 -0.500658 -0.5298391 -0.6845526 -0.4238016 -0.5390375 -0.7278949 -0.4554328 -0.5435015 -0.7051149 -0.3732536 -0.5475949 -0.7488802 -0.3999459 -0.554322 -0.7299113 -0.3205742 -0.5592881 -0.7644796 -0.3379061 -0.5663765 -0.7516896 -0.2550258 -0.577893 -0.7752429 -0.2669586 -0.5842318 -0.7664243 -0.1844543 -0.58991 -0.7861189 -0.196456 -0.5973803 -0.777523 -0.1113913 -0.5964503 -0.7948831 -0.1226553 -0.6043426 -0.7872267 -0.04326361 -0.6018757 -0.7974171 -0.04572254 -0.6038077 -0.7958177 0.02714741 -0.6038517 -0.7966344 0.03125047 -0.6003609 -0.7991184 0.09761583 -0.603738 -0.7911837 0.109312 -0.5928416 -0.7978658 0.1697882 -0.6018561 -0.7803468 0.1828165 -0.5861937 -0.7892751 0.2431834 -0.5935604 -0.7671687 0.2590987 -0.571758 -0.7784348 0.3066813 -0.5785518 -0.7557941 0.3304628 -0.5465519 -0.7694644 0.3566209 -0.5742755 -0.7369052 0.3912258 -0.5262376 -0.7549943 0.4051791 -0.5782715 -0.7081187 0.4474797 -0.5127302 -0.7327139 0.4529348 -0.5734342 -0.682659 0.4923839 -0.5037097 -0.7098131 -0.6008604 -0.4353525 -0.6703992 -0.6269246 -0.4281988 -0.6508543 -0.5680316 -0.440099 -0.6954517 -0.5959098 -0.4398326 -0.671892 -0.534575 -0.4442321 -0.7189489 -0.5620689 -0.4449762 -0.6971906 -0.4966845 -0.4531773 -0.7402262 -0.5221766 -0.4546247 -0.7215594 -0.4543525 -0.4695288 -0.757038 -0.4754226 -0.4723294 -0.7422118 -0.4049563 -0.4870753 -0.773801 -0.4274536 -0.4929936 -0.7577868 -0.3509148 -0.5005682 -0.7913851 -0.3735232 -0.5085684 -0.7757827 -0.3010622 -0.506076 -0.808238 -0.3199059 -0.5153235 -0.7950484 -0.2441087 -0.5156232 -0.8213061 -0.2552126 -0.5223037 -0.813674 -0.1751154 -0.5263106 -0.8320648 -0.1851017 -0.5334975 -0.8252986 -0.1088503 -0.5342422 -0.8382941 -0.1159029 -0.5396699 -0.8338603 -0.03912067 -0.5397788 -0.8408975 -0.04511111 -0.5446901 -0.8374233 0.02927434 -0.5443373 -0.8383556 0.03030538 -0.5434071 -0.8389222 0.09561759 -0.5467562 -0.8318144 0.1022203 -0.5403897 -0.8351827 0.1591031 -0.5440374 -0.8238383 0.1669576 -0.5348672 -0.8282766 0.232735 -0.5260336 -0.8179994 0.239212 -0.5167344 -0.8220483 0.2853836 -0.5233061 -0.8029366 0.3055961 -0.4958298 -0.8128738 0.3306003 -0.5270726 -0.782878 0.3581381 -0.4890934 -0.7953143 0.3837309 -0.5218337 -0.7618663 0.4126206 -0.4764434 -0.7763672 0.4379819 -0.5041382 -0.7443229 0.4637582 -0.4582473 -0.7582466 0.5932391 0.4337287 0.6781938 0.5473766 0.7054133 0.4503011 0.5329045 0.1556335 0.8317398 0.4791941 0.7914055 0.3795398 0.4955407 0.2393479 0.8349564 0.3308445 0.9365687 0.1156757 0.4492718 0.3978779 0.7999051 0.206896 0.9752833 -0.0775665 0.3808267 0.4902775 0.7839637 0.1934913 0.9810907 -0.004722297 0.2942906 0.6098328 0.7358649 0.1619816 0.9854229 0.0519979 0.1853542 0.8957944 0.4039757 0.1302572 0.9874542 0.08925992 0.0966711 0.9482943 0.3023124 0.06501555 0.9972824 0.03465342 0.0241155 0.9942835 0.1040143 0.01992636 0.9987458 0.04593294 -0.04167217 0.9933164 0.107639 -0.04160708 0.9941098 0.1000731 -0.09317451 0.9915865 0.08986008 -0.1042791 0.9440881 0.3127676 -0.1685431 0.9676072 0.1879617 -0.1895442 0.8988041 0.3952522 -0.2204708 0.9628407 0.1559824 -0.258717 0.827612 0.4981206 -0.2886822 0.9357531 0.202556 -0.3371613 0.7903469 0.511541 -0.3282643 0.9312331 0.1582642 -0.3858641 0.7825809 0.4885448 -0.4429498 0.8264425 0.3475461 -0.4564598 0.7387586 0.4958632 -0.5337017 0.7020922 0.4714119 -0.515753 0.6536433 0.5538495 -0.593871 0.6228863 0.5092445 -0.5670488 0.6121051 0.5511652 -0.6322152 0.5925065 0.4992396 -0.6050055 0.5945804 0.5295683 -0.66829 0.5709289 0.4768949 -0.6354326 0.5864907 0.502249 0.6352385 0.3209632 0.7024634 0.5148817 0.8219629 0.2434625 0.5979276 0.4915046 0.6331714 0.2946401 0.9509677 -0.09406268 0.4878355 0.7743427 0.4030012 0.2057506 0.9602143 -0.1888265 0.4012535 0.8598179 0.3157673 0.1909211 0.9686901 -0.1587095 0.3078961 0.9275527 0.211769 0.1733868 0.9775769 -0.1195011 0.2181198 0.9693026 0.1134735 0.1370894 0.9843413 -0.1108094 0.147565 0.9868772 0.0655601 0.1109939 0.9920321 -0.05960536 0.08245915 0.9954622 0.04749161 0.06532496 0.9974734 -0.0279228 0.0223217 0.9997487 -0.002114832 0.02006506 0.9996851 -0.01507067 -0.03748154 0.9991637 -0.01634699 -0.0359773 0.999352 -0.001068115 -0.0921052 0.9954904 -0.02270644 -0.08700126 0.9954646 0.03848385 -0.1416072 0.9895758 -0.02621555 -0.1435474 0.988167 0.05403989 -0.1922167 0.9809442 -0.02831113 -0.1947526 0.9792745 0.05561447 -0.242587 0.9699537 -0.01848012 -0.2485736 0.9658416 0.0732215 -0.2932806 0.9560219 -0.002962589 -0.3010276 0.9497993 0.08522695 -0.3465888 0.9376289 0.02699077 -0.345177 0.9341168 0.0909878 -0.4412145 0.8880863 0.1289675 -0.4246858 0.8893588 0.1693609 -0.5449152 0.7985519 0.2556998 -0.5109566 0.8193914 0.2598483 -0.6324223 0.6853004 0.361117 -0.5927525 0.7240961 0.3526037 -0.6901104 0.5984235 0.4069853 -0.650372 0.6473687 0.3974041 0.5518536 0.806205 0.2132869 0.3845327 0.9220865 -0.04348808 0.4599404 0.8798259 0.1198388 0.3004736 0.9466612 -0.1163969 0.3882639 0.9191161 0.06690907 0.281571 0.955056 -0.09266036 0.3299223 0.9430645 0.04219877 0.2602576 0.9635599 -0.06179362 0.2710937 0.9622779 0.02301257 0.2250575 0.9733874 -0.0432015 0.2094544 0.9777469 0.01182836 0.1797865 0.9832283 -0.03064119 0.149045 0.9887899 0.008957743 0.131766 0.9911376 -0.01685702 0.0872178 0.9961857 0.002715587 0.07559776 0.9970352 -0.01435303 0.02522832 0.9996637 -0.006023347 0.02200579 0.9996972 -0.0110203 -0.04074203 0.9991207 -0.009900689 -0.03808867 0.999259 -0.005542457 -0.105879 0.994327 -0.01017153 -0.09560042 0.9954171 0.002347052 -0.1618268 0.9867743 -0.009417355 -0.1490654 0.9887959 0.00789076 -0.2165413 0.9762143 -0.01075309 -0.2032838 0.9790795 0.008898198 -0.2719141 0.9622632 -0.01058876 -0.2535194 0.9672606 0.01161038 -0.3212739 0.9469682 -0.005868792 -0.3003691 0.9537256 0.01363343 -0.3684713 0.9296377 -0.001670539 -0.3397989 0.9404097 0.01289921 -0.4143425 0.910081 0.008544266 -0.3786019 0.9255016 0.010365 -0.4555 0.8900426 0.01854932 -0.4010579 0.9160172 -0.008067131 -0.5190015 0.852298 0.06500566 -0.4379001 0.8990162 -0.003668069 -0.6154457 0.7704962 0.1660193 -0.5350403 0.8403739 0.08662432 0.4877054 0.8723091 0.03493541 0.4140311 0.9094667 -0.03806245 0.4441596 0.895535 0.02719062 0.3839603 0.9227848 -0.03229099 0.3925505 0.9195767 0.01681977 0.3518712 0.9358174 -0.02079737 0.3395754 0.9405437 0.00813955 0.3103354 0.9504868 -0.01633626 0.2827411 0.9591925 0.002711415 0.261197 0.9652011 -0.01276421 0.2179704 0.9759554 -1.4707e-4 0.2047643 0.978774 -0.008554279 0.1570118 0.9875968 1.55364e-4 0.146657 0.9891707 -0.005749166 0.09223622 0.9957369 -6.99089e-4 0.08660989 0.9962359 -0.003597676 0.02613562 0.9996567 -0.0018664 0.02534592 0.9996761 -0.002294242 -0.04238593 0.9990998 -0.001766324 -0.04116678 0.9991518 -0.001093626 -0.1126316 0.9936345 -0.002175629 -0.1071473 0.9942431 3.08962e-4 -0.1717537 0.9851377 -0.002151429 -0.163838 0.9864864 0.001257896 -0.2275689 0.9737597 -0.00210458 -0.2197402 0.9755569 0.001749038 -0.2878327 0.9576726 -0.003957211 -0.2759028 0.9611821 0.00260961 -0.343841 0.9390041 -0.006688654 -0.3241158 0.9460141 0.002529203 -0.3934636 0.9193202 -0.006077647 -0.3699039 0.9290683 0.001794934 -0.4406016 0.8977025 -7.28234e-4 -0.4116348 0.911342 0.003586709 -0.4853299 0.874302 0.007130742 -0.4456287 0.8952139 0.002718389 -0.5243375 0.8513614 0.01593649 -0.4754104 0.8797638 -8.88084e-4 -0.563035 0.8258997 0.02968961 -0.4983612 0.866928 -0.008487343 0.4940819 0.869399 0.005342185 0.4692646 0.8830236 -0.007769823 0.4519682 0.8920252 0.003994166 0.4340946 0.9008535 -0.004996001 0.400607 0.9162462 0.002665519 0.3890913 0.9211957 -0.002559483 0.3448771 0.9386475 8.47282e-4 0.3385432 0.9409486 -0.002103447 0.2868196 0.9579846 1.88102e-4 0.2823926 0.9592972 -0.001818835 0.219094 0.9757033 -0.001016557 0.2178663 0.9759774 -0.00156188 0.1606926 0.9870045 -5.38696e-4 0.1569133 0.9876102 -0.002119719 0.09379351 0.9955915 -6.2395e-4 0.09222126 0.9957379 -0.001246154 0.02542293 0.9996762 -0.001081585 0.02614909 0.9996578 -7.67205e-4 -0.04211324 0.9991127 -4.73853e-4 -0.04240691 0.9991003 -6.02285e-4 -0.1140081 0.9934798 -4.93971e-4 -0.1127145 0.9936275 -5.48399e-6 -0.1736875 0.9848008 -4.19739e-4 -0.1718879 0.9851166 2.03898e-4 -0.2289285 0.9734433 -5.7159e-5 -0.227765 0.9737161 3.70589e-4 -0.2915906 0.9565429 -8.90923e-4 -0.2882022 0.9575695 5.22151e-4 -0.3500844 0.9367145 -0.002655029 -0.3444198 0.9388157 -3.29606e-4 -0.3987481 0.9170569 -0.002583026 -0.3944075 0.9189353 -8.859e-4 -0.4526572 0.8916808 -0.002632975 -0.4413089 0.8973546 0.001186668 -0.5008811 0.8655135 -0.002165555 -0.4830539 0.875588 0.002145588 -0.5414303 0.8407457 2.52596e-4 -0.5173664 0.8557596 0.002748548 -0.5780462 0.8159849 0.005594789 -0.5457453 0.8379482 0.002222955 0.4971321 0.8676748 3.25212e-4 0.4933632 0.8698229 -9.85332e-4 0.4546532 0.8906685 4.30704e-4 0.4515905 0.8922251 -7.00296e-4 0.4009512 0.9160996 -1.1619e-4 0.4004884 0.9163019 -2.74552e-4 0.3449742 0.9386121 -5.61678e-4 0.3448502 0.9386577 -6.1151e-4 0.2876858 0.9577249 1.01354e-4 0.2868138 0.9579864 -2.36301e-4 0.2175788 0.9760425 -7.17536e-4 0.21911 0.9757003 -1.0008e-4 0.1627004 0.9866753 -6.46124e-4 0.1606918 0.9870036 -0.001447916 0.09484618 0.9954918 -5.90192e-4 0.09379261 0.9955914 -9.90854e-4 0.02451485 0.9996991 -9.30587e-4 0.02542579 0.9996766 -5.4721e-4 -0.04119384 0.9991512 -2.3787e-4 -0.04211235 0.9991127 -6.20747e-4 -0.1140132 0.9934793 -1.06986e-4 -0.1140108 0.9934796 -1.09107e-4 -0.1737995 0.9847812 -7.46236e-5 -0.1736907 0.9848003 -3.99527e-5 -0.2289749 0.9734323 -1.4873e-5 -0.2289295 0.973443 0 -0.294853 0.9555417 -0.001371979 -0.2915925 0.9565426 -1.35929e-4 -0.3522773 0.9358928 -0.002333104 -0.3500936 0.9367136 -0.001486361 -0.3971194 0.9177669 -4.89874e-4 -0.3988282 0.9170251 -0.001112103 -0.4561219 0.8899171 -7.48943e-4 -0.4529713 0.8915251 3.70616e-4 -0.504445 0.8634429 -0.001251399 -0.501126 0.8653745 -5.22475e-5 -0.5483118 0.8362733 -0.001148402 -0.5415375 0.8406762 8.99005e-4 -0.5899599 0.8074322 -9.19322e-4 -0.5769611 0.8167697 0.001763463 0.4955665 0.86857 -4.57497e-4 0.4971238 0.8676797 2.39088e-5 0.4546013 0.890695 -2.15077e-5 0.4546483 0.8906711 -7.0746e-6 0.3990305 0.9169376 -4.6063e-4 0.4009538 0.9160983 1.68718e-4 0.3445051 0.9387843 -5.3138e-4 0.3449748 0.938612 -3.48727e-4 0.2897372 0.9571058 9.07121e-4 0.2876856 0.957725 1.49213e-4 0.216778 0.9762209 1.4031e-4 0.2175866 0.9760409 4.5894e-4 0.1646068 0.9863591 -5.94076e-4 0.1627045 0.9866739 -0.001393854 0.09730076 0.9952549 -4.3528e-4 0.09484744 0.9954909 -0.0013929 0.02422267 0.9997064 -7.79796e-4 0.02451598 0.9996992 -6.56151e-4 -0.03949874 0.9992196 -2.34243e-4 -0.0411902 0.9991509 -9.45456e-4 -0.1131171 0.9935817 -8.68539e-5 -0.1140118 0.9934794 -4.15718e-4 -0.1735684 0.9848218 -2.13169e-4 -0.1737992 0.984781 -2.89625e-4 -0.2302393 0.9731338 -6.57424e-4 -0.2289751 0.9734324 -2.36957e-4 -0.3005666 0.9537572 -0.002660989 -0.2948424 0.9555457 -5.50873e-4 -0.3534317 0.9354581 -0.002080678 -0.3522745 0.9358953 -0.001635849 -0.3978513 0.9174494 9.99478e-4 -0.3971492 0.9177533 0.001201868 -0.4625597 0.8865881 3.37372e-4 -0.4561784 0.8898852 0.002395927 -0.5046983 0.8632958 -1.16197e-4 -0.504472 0.8634281 -2.88655e-5 -0.5469561 0.8371613 3.62985e-4 -0.5483422 0.836254 -1.28105e-4 -0.592625 0.8054783 -5.54774e-4 -0.5900248 0.8073851 2.49446e-4 0.494022 0.8694494 -4.90935e-4 0.4955714 0.8685673 -4.45841e-6 0.4544155 0.8907898 -1.12568e-4 0.4546029 0.8906943 -5.22579e-5 0.3970169 0.9178112 -5.51172e-4 0.3990307 0.9169376 1.02295e-4 0.3435569 0.9391316 -7.60544e-4 0.3445051 0.9387845 -3.85293e-4 0.2903656 0.9569159 2.2451e-4 0.2897395 0.9571056 7.10933e-6 0.2153253 0.9765424 -1.87738e-4 0.2167788 0.9762208 3.38565e-4 0.1654573 0.986217 -3.58842e-4 0.1646074 0.9863589 -7.14067e-4 0.0981608 0.9951706 -2.98089e-4 0.09730082 0.9952548 -6.3571e-4 0.023633 0.9997206 -6.4238e-4 0.02422428 0.9997065 -3.90531e-4 -0.03753036 0.9992956 4.65353e-5 -0.03949618 0.9992195 -7.79768e-4 -0.1123639 0.9936672 -3.79262e-5 -0.1131166 0.9935817 -3.16306e-4 -0.1730328 0.9849161 -4.52709e-4 -0.173568 0.9848217 -6.36645e-4 -0.2301269 0.9731605 -4.27452e-4 -0.2302385 0.9731342 -4.66869e-4 -0.3029994 0.9529899 -0.001307427 -0.3005502 0.9537659 -3.59149e-4 -0.3524044 0.9358478 -5.42899e-4 -0.3534377 0.9354575 -0.001010775 -0.3972814 0.9176967 7.07616e-4 -0.3978488 0.9174509 5.46008e-4 -0.465045 0.8852871 -3.79618e-5 -0.4625568 0.8865895 7.38736e-4 -0.5035815 0.8639477 -2.43341e-4 -0.5046952 0.8632974 -6.90277e-4 -0.5453366 0.8382173 1.9707e-5 -0.5469512 0.8371644 -5.47527e-4 -0.5929551 0.8052355 -2.86518e-4 -0.592625 0.8054785 -1.9183e-4 0.4928938 0.8700894 -3.92292e-4 0.4940247 0.8694479 -2.67117e-5 0.4545999 0.8906959 -1.96621e-4 0.454415 0.8907901 -2.60329e-4 0.3955714 0.9184351 -6.11571e-4 0.397016 0.9178117 -1.39344e-4 0.342621 0.9394734 -8.49139e-4 0.3435594 0.9391309 -4.66739e-4 0.2902489 0.9569512 -1.12461e-4 0.2903668 0.9569155 -7.27157e-5 0.2134351 0.9769572 -3.91506e-4 0.2153266 0.9765421 2.65028e-4 0.1658692 0.9861478 -2.73808e-4 0.1654574 0.986217 -4.4394e-4 0.09827965 0.9951589 -2.64068e-4 0.0981608 0.9951705 -3.10896e-4 0.02288818 0.9997379 -6.04782e-4 0.02363455 0.9997207 -2.87912e-4 -0.03549605 0.9993699 1.54396e-4 -0.0375275 0.9992954 -6.90822e-4 -0.1123144 0.9936727 -2.69055e-4 -0.112364 0.9936671 -2.89438e-4 -0.1728176 0.9849535 -9.00773e-4 -0.1730328 0.9849156 -9.782e-4 -0.2294571 0.9733188 -3.02431e-4 -0.2301275 0.9731603 -5.23783e-4 -0.3046156 0.9524751 -6.71727e-4 -0.302995 0.9529922 -3.85154e-5 -0.3506805 0.9364953 1.23894e-4 -0.3524032 0.935848 -6.98405e-4 -0.3958835 0.9183007 4.03723e-4 -0.3972845 0.9176956 -5.86627e-7 -0.4654073 0.8850967 -3.33637e-4 -0.4650473 0.8852858 -2.22413e-4 -0.5020546 0.8648359 -3.04308e-4 -0.5035775 0.8639497 -9.28826e-4 -0.5440551 0.8390495 -1.26851e-4 -0.5453343 0.8382185 -5.74591e-4 -0.5929256 0.8052574 -1.90141e-4 -0.5929533 0.8052368 -1.98003e-4 0.4918806 0.8706627 -3.585e-4 0.4928962 0.8700882 -2.65312e-5 0.4549451 0.8905196 -2.27608e-4 0.4546003 0.8906955 -3.39068e-4 0.3943728 0.9189503 -6.21373e-4 0.3955718 0.9184352 -2.27248e-4 0.3417491 0.9397909 -8.55428e-4 0.3426218 0.9394733 -4.89763e-4 0.2899864 0.9570308 -1.78918e-4 0.2902492 0.9569511 -9.27575e-5 0.2113947 0.9774007 -4.41416e-4 0.2134355 0.9769572 2.54208e-4 0.1661722 0.9860968 -2.73749e-4 0.16587 0.9861477 -3.98943e-4 0.09823894 0.9951629 -2.55058e-4 0.09827923 0.9951589 -2.37633e-4 0.02207607 0.9997562 -5.98056e-4 0.02288967 0.9997379 -2.5507e-4 -0.03345632 0.9994402 1.69455e-4 -0.03549307 0.9993698 -6.68027e-4 -0.1126641 0.993633 -4.22923e-4 -0.1123141 0.9936728 -2.96908e-4 -0.1728751 0.9849432 -0.001132965 -0.1728173 0.9849533 -0.001109659 -0.2287707 0.9734804 -3.01536e-4 -0.2294567 0.9733187 -5.23043e-4 -0.3063649 0.951914 -5.50943e-4 -0.3046118 0.9524767 1.24256e-4 -0.3490146 0.9371173 1.7816e-4 -0.3506752 0.936497 -6.11977e-4 -0.3954765 0.9184761 -5.58001e-5 -0.3958864 0.9182995 -1.73358e-4 -0.4661644 0.8846979 -7.78564e-4 -0.4654105 0.8850948 -5.54072e-4 -0.5004808 0.8657476 -3.19219e-4 -0.5020503 0.8648379 -9.60496e-4 -0.5432372 0.8395794 -1.25287e-4 -0.5440568 0.8390483 -4.14276e-4 -0.5932174 0.8050424 -2.14712e-4 -0.5929237 0.8052587 -1.33174e-4 0.4908845 0.8712247 -3.52063e-4 0.4918813 0.8706623 -2.5961e-5 0.4553364 0.8903196 -2.27036e-4 0.4549444 0.8905199 -3.5438e-4 0.3932672 0.9194241 -6.09301e-4 0.3943741 0.9189499 -2.41651e-4 0.3409068 0.9400967 -8.58883e-4 0.3417499 0.9397909 -4.96204e-4 0.2897663 0.9570974 -2.26777e-4 0.2899853 0.9570312 -1.57479e-4 0.2092419 0.9778639 -5.17436e-4 0.2113955 0.9774007 2.05961e-4 0.1663753 0.9860625 -3.47614e-4 0.1661731 0.9860966 -4.31829e-4 0.09802341 0.9951841 -2.2801e-4 0.09823906 0.9951629 -1.4168e-4 0.02107763 0.9997777 -5.81473e-4 0.02207803 0.9997563 -1.61275e-4 -0.03150105 0.9995038 1.55251e-4 -0.03345382 0.9994401 -6.36929e-4 -0.1131895 0.9935733 -4.96356e-4 -0.1126638 0.9936332 -3.10591e-4 -0.1730251 0.9849168 -0.001203954 -0.172875 0.9849431 -0.00114113 -0.2280416 0.9736514 -3.06336e-4 -0.2287694 0.9734805 -5.37322e-4 -0.3082176 0.9513158 -5.14362e-4 -0.3063618 0.9519152 1.86465e-4 -0.3477224 0.9375976 6.98809e-6 -0.3490086 0.9371194 -6.00195e-4 -0.3973348 0.9176734 -8.64803e-4 -0.3954783 0.9184753 -3.32822e-4 -0.4680596 0.8836959 -0.00136578 -0.4661664 0.8846966 -8.14897e-4 -0.4991035 0.8665425 -2.68833e-4 -0.5004778 0.865749 -8.00514e-4 -0.5433628 0.839498 -2.91525e-5 -0.5432376 0.8395791 1.30795e-5 -0.5937081 0.8046805 -1.06467e-4 -0.5932184 0.8050417 3.01059e-5 0.4899426 0.8717547 -3.52318e-4 0.4908859 0.8712239 -4.32623e-5 0.4558657 0.8900486 -1.90238e-4 0.4553367 0.8903192 -3.64089e-4 0.3924096 0.9197906 -5.17739e-4 0.3932689 0.9194236 -2.31855e-4 0.3400131 0.9404203 -9.10881e-4 0.3409082 0.9400966 -5.13311e-4 0.2900124 0.9570229 -4.31327e-4 0.2897683 0.9570968 -5.08038e-4 0.2072896 0.9782794 -7.56804e-4 0.2092422 0.9778639 -1.05441e-4 0.166379 0.9860618 -5.76934e-4 0.166376 0.9860623 -5.78395e-4 0.09741646 0.9952438 -1.2424e-4 0.09802347 0.9951841 1.0487e-4 0.01938259 0.9998121 -5.64583e-4 0.02108085 0.9997778 1.38457e-4 -0.02993261 0.999552 4.15703e-5 -0.03149914 0.9995036 -5.88178e-4 -0.1140221 0.993478 -6.47324e-4 -0.1131891 0.9935734 -3.57079e-4 -0.1730551 0.9849115 -0.001162171 -0.1730251 0.9849168 -0.001148164 -0.2267027 0.9739641 -1.1523e-4 -0.2280404 0.9736515 -5.31266e-4 -0.3098098 0.9507985 -3.44762e-4 -0.3082141 0.951317 2.48481e-4 -0.347173 0.9378011 -3.43196e-4 -0.3477178 0.9375991 -5.99581e-4 -0.4020052 0.9156351 -0.002040565 -0.3973343 0.9176737 -6.65e-4 -0.4705985 0.8823454 -0.001857578 -0.468057 0.8836976 -0.001111447 -0.4982152 0.8670535 -7.02249e-5 -0.4991045 0.8665418 -3.71457e-4 -0.5448743 0.8385178 3.69205e-4 -0.5433642 0.8394967 8.59031e-4 -0.5934379 0.8048797 5.30579e-4 -0.5937088 0.8046799 4.56808e-4 0.4892508 0.8721432 -3.68084e-4 0.4899441 0.871754 -1.38843e-4 0.4569699 0.8894823 -5.40815e-5 0.4558665 0.8900481 -4.18317e-4 0.392462 0.9197682 -1.76386e-4 0.3924096 0.9197906 -1.93293e-4 0.3390114 0.9407818 -0.001012921 0.3400142 0.9404201 -5.52595e-4 0.2920196 0.956412 -8.7875e-4 0.2900198 0.9570194 -0.001540422 0.2072865 0.9782798 -0.001090645 0.2072892 0.9782792 -0.001089274 0.1666259 0.98602 -7.67482e-4 0.1663796 0.9860615 -8.68681e-4 0.09652572 0.9953305 -1.78044e-5 0.09741598 0.9952437 3.08645e-4 0.01697057 0.9998558 -6.22987e-4 0.0193867 0.999812 3.64281e-4 -0.02922117 0.9995729 -3.30908e-4 -0.02993124 0.9995518 -6.13394e-4 -0.115397 0.993319 -9.83916e-4 -0.1140215 0.9934781 -5.19355e-4 -0.1727582 0.9849638 -0.001019954 -0.1730551 0.9849115 -0.001146376 -0.2237797 0.9746398 3.412e-4 -0.2267004 0.9739644 -5.55253e-4 -0.3101199 0.9506976 1.61972e-4 -0.3098069 0.9507995 2.7661e-4 -0.3459686 0.9382462 1.22416e-4 -0.3471722 0.9378013 -4.56322e-4 -0.4023491 0.915486 -7.13975e-4 -0.4020047 0.9156374 -6.05278e-4 -0.4706395 0.8823254 -7.1572e-4 -0.4705967 0.8823482 -7.03036e-4 -0.4977403 0.8673263 -2.82678e-5 -0.4982162 0.8670528 -1.89414e-4 -0.5457913 0.8379213 1.30365e-5 -0.5448738 0.838518 3.05992e-4 -0.593811 0.8046046 7.48832e-6 -0.5934363 0.804881 1.06878e-4 0.4890803 0.8722387 -4.22992e-4 0.4892495 0.8721439 -3.66914e-4 0.4591346 0.8883668 1.59335e-4 0.4569705 0.8894817 -5.57996e-4 0.3941513 0.9190456 4.21652e-4 0.3924614 0.9197686 -1.42411e-4 0.338171 0.9410843 -9.08929e-4 0.339013 0.9407817 -5.17005e-4 0.2954944 0.9553437 -0.00124824 0.2920281 0.9564065 -0.002505481 0.209919 0.9777179 -0.001349031 0.2072848 0.978278 -0.002289474 0.1676511 0.9858462 -7.34686e-4 0.1666263 0.9860195 -0.001172423 0.09582191 0.9953986 1.49153e-4 0.09652525 0.9953305 3.99549e-4 0.01446282 0.9998952 -7.04737e-4 0.01697432 0.9998559 3.159e-4 -0.02874678 0.9995866 -5.48731e-4 -0.02922034 0.9995728 -7.36481e-4 -0.1168812 0.9931453 -0.00113964 -0.115395 0.9933196 -6.40295e-4 -0.1728123 0.9849541 -0.001200973 -0.1727583 0.9849636 -0.001177132 -0.2223484 0.9749671 -5.88025e-4 -0.2237729 0.9746409 -0.001018822 -0.3104834 0.9505788 -4.30013e-4 -0.3101219 0.9506968 -3.04765e-4 -0.3444363 0.9388097 3.37118e-4 -0.3459642 0.9382477 -3.73721e-4 -0.4022055 0.9155494 -1.63418e-5 -0.4023494 0.9154863 -6.46953e-5 -0.4701439 0.8825898 -1.60264e-4 -0.4706391 0.8823258 -3.4315e-4 -0.4974724 0.8674798 -1.25819e-5 -0.4977406 0.867326 -1.05309e-4 -0.5461978 0.8376563 -1.12541e-4 -0.5457927 0.8379203 1.88741e-5 -0.5943888 0.8041778 -1.89172e-4 -0.5938129 0.8046033 -3.33847e-5 0.4889855 0.8722918 -4.85345e-4 0.4890801 0.8722388 -4.51844e-4 0.4609537 0.8874243 -2.46222e-5 0.4591354 0.8883662 -6.28735e-4 0.3951451 0.9186187 9.6113e-5 0.3941509 0.9190458 -2.21525e-4 0.3378244 0.941209 -5.41765e-4 0.3381718 0.9410843 -3.89279e-4 0.2966256 0.9549936 -7.35321e-4 0.2954945 0.9553438 -0.001148879 0.2099769 0.9777058 -0.001036465 0.2099207 0.9777179 -0.001056671 0.1686475 0.9856765 -3.78361e-4 0.1676511 0.9858461 -8.13799e-4 0.09549415 0.9954299 4.83353e-4 0.09582102 0.9953984 5.95804e-4 0.01231354 0.9999238 -8.48441e-4 0.01446533 0.9998955 3.79215e-5 -0.0278843 0.999611 -6.54339e-4 -0.02874577 0.9995864 -9.98391e-4 -0.1183983 0.9929655 -0.001278102 -0.1168788 0.9931459 -7.6499e-4 -0.1741276 0.9847214 -0.001856267 -0.1728123 0.9849541 -0.001271426 -0.2267873 0.9739399 -0.002955496 -0.2223421 0.9749674 -0.001617789 -0.3128631 0.9497964 -0.001835644 -0.3104854 0.9505776 -0.0010643 -0.3429589 0.9393504 4.23477e-4 -0.3444324 0.9388111 -1.71024e-4 -0.4051391 0.9142551 3.4555e-4 -0.4022054 0.9155486 0.001257658 -0.4707462 0.8822687 1.31583e-5 -0.4701454 0.882589 2.3866e-4 -0.4973907 0.8675267 1.38836e-5 -0.4974729 0.8674795 -1.49091e-5 -0.5462033 0.8376528 -1.89422e-5 -0.5461983 0.837656 -1.82772e-5 -0.5938874 0.8045483 1.29315e-4 -0.5943895 0.8041773 -9.6853e-6 0.4888954 0.8723424 -5.06926e-4 0.4889863 0.8722915 -4.73319e-4 0.4625092 0.8866146 -1.15478e-4 0.4609567 0.8874225 -6.44773e-4 0.3956269 0.9184113 -1.10528e-4 0.395144 0.9186192 -2.65323e-4 0.3376767 0.9412621 -4.12674e-4 0.3378241 0.9412092 -3.47765e-4 0.2965949 0.9550033 -5.24363e-4 0.2966257 0.9549938 -5.12617e-4 0.2087888 0.9779604 -9.15238e-4 0.2099794 0.9777058 -4.68403e-4 0.1695508 0.9855214 -2.63273e-4 0.168647 0.9856763 -6.71258e-4 0.09541654 0.9954373 5.94659e-4 0.09549373 0.9954299 6.20077e-4 0.0104649 0.9999449 -9.02863e-4 0.01231521 0.9999243 -1.19238e-4 -0.02681952 0.9996401 -6.51266e-4 -0.02788317 0.9996106 -0.001079916 -0.11952 0.9928311 -0.00118035 -0.1183955 0.9929663 -7.9485e-4 -0.1744423 0.9846665 -0.001366853 -0.1741278 0.9847223 -0.001221776 -0.2264138 0.9740305 -0.001175761 -0.2268051 0.9739394 -0.001301288 -0.3123786 0.9499577 -2.17616e-4 -0.3128693 0.9497962 -4.00337e-4 -0.3422569 0.9396061 6.76887e-4 -0.3429594 0.9393502 3.91969e-4 -0.4066422 0.9135876 2.18306e-4 -0.405138 0.9142553 6.93272e-4 -0.4705955 0.8823491 -1.7859e-5 -0.470746 0.8822688 -7.62347e-5 -0.4971608 0.8676585 1.51305e-5 -0.4973904 0.867527 -6.57234e-5 -0.5459824 0.8377967 4.49368e-5 -0.5462028 0.8376531 -2.83519e-5 -0.5926916 0.8054295 3.54208e-4 -0.5938879 0.8045479 1.53979e-5 0.488812 0.8723891 -5.69642e-4 0.4888961 0.872342 -5.36987e-4 0.4637083 0.885988 -2.47027e-4 0.4625117 0.886613 -7.01481e-4 0.395564 0.9184384 -3.85597e-4 0.395625 0.9184121 -3.62954e-4 0.3374629 0.9413387 -5.25713e-4 0.3376765 0.9412622 -4.22429e-4 0.2957088 0.9552779 -5.89034e-4 0.2965933 0.9550039 -2.31908e-4 0.2068326 0.9783759 -9.76596e-4 0.2087904 0.9779604 -1.63932e-4 0.1702135 0.9854072 -3.15678e-4 0.169551 0.9855213 -6.46709e-4 0.09555739 0.9954239 4.72748e-4 0.09541732 0.9954373 4.25664e-4 0.009173631 0.9999575 -9.78355e-4 0.0104655 0.9999452 -3.78533e-4 -0.0253908 0.9996775 -5.33838e-4 -0.02681821 0.9996398 -0.001167654 -0.1199678 0.9927774 -9.74901e-4 -0.1195173 0.9928318 -8.04862e-4 -0.174223 0.9847056 -0.001149952 -0.1744421 0.9846667 -0.00125879 -0.2230477 0.9748075 -1.55027e-4 -0.2264119 0.9740307 -0.00140804 -0.3101227 0.9506964 6.67507e-4 -0.3123786 0.9499577 -3.13719e-4 -0.3418008 0.9397722 6.77577e-4 -0.342257 0.9396063 4.68545e-4 -0.4066694 0.9135754 6.0786e-5 -0.406643 0.9135872 7.1068e-5 -0.47002 0.8826559 -9.14479e-5 -0.4705958 0.882349 -3.37462e-4 -0.4968957 0.8678104 -3.98839e-5 -0.4971614 0.8676581 -1.4353e-4 -0.5458484 0.8378841 -3.08017e-5 -0.5459833 0.8377961 -8.00744e-5 -0.5922625 0.8057452 8.42094e-5 -0.5926921 0.8054292 -4.86478e-5 0.4886884 0.8724579 -0.00104779 0.4888105 0.8723894 -9.69727e-4 0.4638614 0.8859072 -0.001119136 0.4637097 0.8859865 -0.001211881 0.3941208 0.9190567 -0.00191015 0.3955646 0.9184376 -0.001122415 0.3369265 0.9415298 -0.001509726 0.3374668 0.9413368 -0.00110203 0.2926782 0.9562101 -0.001361429 0.2956937 0.9552828 4.01486e-4 0.2029401 0.9791898 -0.00161904 0.2068123 0.9783803 7.97124e-4 0.1701244 0.9854223 -8.29591e-4 0.1702185 0.9854061 -7.59731e-4 0.09536081 0.9954428 -1.95624e-4 0.09556347 0.9954234 -9.71841e-5 0.00890696 0.9999594 -0.001396775 0.00917375 0.9999573 -0.001217544 -0.02282959 0.9997395 2.77072e-5 -0.02539008 0.9996763 -0.001634895 -0.1184422 0.992961 -1.37625e-4 -0.1199679 0.9927774 -9.73148e-4 -0.1735686 0.984821 -0.001251339 -0.1742314 0.9847033 -0.00175029 -0.216919 0.9761894 7.28092e-4 -0.2230673 0.9747989 -0.002856254 -0.3060922 0.9520013 0.001071274 -0.3101456 0.9506877 -0.001668393 -0.3409724 0.9400734 -1.1552e-4 -0.3418083 0.9397695 -7.3533e-4 -0.404884 0.9143678 -7.45019e-4 -0.4066781 0.9135699 -0.001765072 -0.4691127 0.8831382 -6.16107e-4 -0.4700202 0.8826549 -0.001229763 -0.4967527 0.867892 -5.32275e-4 -0.4968969 0.8678094 -6.21213e-4 -0.5458639 0.8378738 -4.84028e-4 -0.5458487 0.8378837 -4.74133e-4 -0.5921716 0.8058119 -3.64978e-4 -0.5922638 0.8057441 -4.08496e-4 0.488521 0.872532 -0.005917668 0.4886769 0.872447 -0.005591571 0.4631668 0.8862256 -0.008990883 0.4638651 0.885874 -0.007514655 0.3928689 0.9194968 -0.0134074 0.3941901 0.9189653 -0.01081645 0.3365969 0.9415892 -0.01059639 0.3370954 0.9414253 -0.009226679 0.2879164 0.9576021 -0.01012104 0.2926539 0.9562181 -8.11602e-4 0.1981202 0.9801371 -0.008930742 0.2027859 0.9792219 0.001556515 0.1695515 0.9855007 -0.006378114 0.1702843 0.9853848 -0.004488587 0.09235262 0.9957169 -0.004344582 0.09535098 0.9954438 1.68694e-4 0.007992625 0.9999524 -0.005601942 0.008912026 0.9999541 -0.003541886 -0.01947873 0.9998096 0.001187741 -0.02286022 0.9997211 -0.005941748 -0.1144024 0.9934308 0.002702414 -0.1185824 0.9929345 -0.00438261 -0.1728688 0.9849312 -0.005203425 -0.1738543 0.9847429 -0.007503986 -0.2099605 0.9777097 6.18167e-4 -0.2176288 0.975934 -0.01380097 -0.3011832 0.9535647 -0.001770734 -0.3067671 0.9516934 -0.01318126 -0.3408157 0.9400768 -0.01001751 -0.341138 0.9399509 -0.01083397 -0.4033225 0.9149885 -0.01127153 -0.4049209 0.9142383 -0.01440268 -0.4685437 0.8834077 -0.007606923 -0.469102 0.8830994 -0.008875429 -0.4979196 0.8671849 -0.008161842 -0.4967462 0.8678768 -0.005756139 -0.5469698 0.8371226 -0.007049381 -0.5458605 0.8378615 -0.004941463 -0.5924947 0.8055599 -0.004841148 -0.5921695 0.8058019 -0.004309892 0.487854 0.8715589 -0.04882586 0.4880028 0.8715578 -0.04733163 0.464666 0.8828391 -0.06841629 0.4612088 0.8816342 -0.1000378 0.4008476 0.9128911 -0.0771442 0.3895354 0.9042954 -0.1746774 0.3403821 0.9358018 -0.09173452 0.3378273 0.9322415 -0.1296089 0.2945952 0.9495019 -0.1079815 0.292374 0.9463333 -0.1377348 0.2063248 0.9752091 -0.07998418 0.2038835 0.9700907 -0.131741 0.1735313 0.9826193 -0.06592607 0.1731384 0.9817938 -0.07812792 0.09490603 0.9931775 -0.06775969 0.09432744 0.9928216 -0.07353758 0.008806765 0.9978775 -0.06452029 0.008156895 0.9973334 -0.07252418 -0.01858401 0.998494 -0.05161887 -0.01987355 0.997667 -0.06531149 -0.1154451 0.991961 -0.05182588 -0.1166983 0.9913296 -0.06039339 -0.1777311 0.9808468 -0.07969492 -0.1760434 0.9821807 -0.06580173 -0.2205532 0.9667567 -0.1293746 -0.2147374 0.9728271 -0.08657538 -0.3081189 0.9432964 -0.1235094 -0.3058379 0.9462422 -0.1053042 -0.3465265 0.9244642 -0.1590139 -0.3415722 0.935631 -0.08901262 -0.4083682 0.8958724 -0.1750657 -0.4025753 0.911202 -0.08743089 -0.4703245 0.8749046 -0.1154855 -0.4676703 0.8814638 -0.06562125 -0.5019798 0.8528237 -0.1439029 -0.4971351 0.8656687 -0.05894601 -0.550953 0.8256838 -0.1212309 -0.5462509 0.8359094 -0.05353015 -0.5942545 0.8017842 -0.06327426 -0.5920092 0.8048039 -0.04261475 0.5257014 0.5426964 0.6550717 0.5306117 0.5483286 0.6463644 0.4904749 0.5464242 0.6788629 0.4818091 0.5403689 0.6898271 0.439483 0.5348541 0.721655 0.4361198 0.5306786 0.7267598 0.3867306 0.5295794 0.7549737 0.385802 0.5282286 0.7563937 0.3221216 0.5269343 0.7864974 0.3227458 0.5277297 0.7857077 0.2490825 0.5263114 0.8129909 0.2526624 0.5319309 0.8082149 0.1820514 0.5275239 0.8298047 0.1873303 0.5347405 0.8239904 0.1020057 0.5252351 0.8448213 0.1023105 0.5263007 0.8441209 0.03364366 0.5126178 0.8579576 0.0320791 0.5058353 0.8620334 -0.06647062 0.5055866 0.8602115 -0.06323754 0.5212706 0.8510453 -0.1197595 0.5306531 0.8390858 -0.1204506 0.5271136 0.8412151 -0.208876 0.5369388 0.817354 -0.2108064 0.5295474 0.8216693 -0.2621051 0.5327436 0.8046647 -0.2674989 0.5241584 0.8085188 -0.3435235 0.52489 0.7787697 -0.3426607 0.5259923 0.778406 -0.3933056 0.5325045 0.7494997 -0.3913164 0.5353339 0.7485247 -0.4562367 0.536051 0.7102798 -0.450129 0.5444121 0.7078131 -0.5008663 0.5456602 0.6718541 -0.4978299 0.5512323 0.6695584 -0.5352588 0.5506997 0.6404904 -0.5318808 0.5541844 0.6402988 -0.5689144 0.55581 0.606145 -0.5653983 0.561175 0.6044895 -0.6092664 0.5580732 0.5633373 -0.6114481 0.5549423 0.5640661 -0.5837448 0.7532987 -0.3029573 -0.608828 0.7852956 -0.1124253 -0.4671599 0.6274806 -0.6229204 -0.6019715 0.7944779 0.08021932 -0.4330231 0.6044845 -0.6686475 -0.5135291 0.7685263 -0.3816483 -0.3560944 0.5552049 -0.7516279 -0.464414 0.7878528 -0.4044848 -0.2404433 0.4410441 -0.8646776 -0.4744891 0.8421493 0.256212 -0.205654 0.4239487 -0.8820284 -0.4132806 0.8424914 0.345554 -0.2283052 0.5405752 -0.8097255 -0.3643372 0.9031406 -0.2271463 -0.2593918 0.6809501 -0.6848526 -0.3015835 0.8165404 -0.4922493 -0.1792321 0.5838469 -0.7918325 -0.2554235 0.9286902 -0.2688743 -0.1670522 0.7056748 -0.6885613 -0.1856734 0.8409727 -0.5082228 -0.09877192 0.5689628 -0.8164102 -0.1220688 0.7624447 -0.6354348 -0.01647365 0.6150913 -0.7882839 -0.02441149 0.7734317 -0.6334095 0.008653163 0.7708494 -0.6369587 0.01155734 0.6735829 -0.7390214 0.09221416 0.7526111 -0.6519764 0.09113568 0.5949182 -0.798603 0.1739202 0.8112942 -0.5581698 0.1689947 0.7162083 -0.6771163 0.2001273 0.7966749 -0.5703142 0.1820167 0.5808019 -0.7934351 0.2578264 0.7252205 -0.6384206 0.2455888 0.6258045 -0.7403073 0.2854753 0.7180159 -0.634789 0.2647199 0.6208388 -0.7378907 0.3603873 0.8003538 -0.4791189 0.2875369 0.5747535 -0.7661468 0.4117247 0.777367 -0.4755876 0.3529107 0.6372439 -0.6851089 0.554214 0.5276762 0.6437428 0.5243829 0.62064 0.5829481 0.5196617 0.5006523 0.6923143 0.5017471 0.5987211 0.6243261 0.473201 0.4356376 0.7657027 0.4400318 0.6600963 0.6088063 0.4163235 0.4507513 0.789619 0.3695804 0.7265011 0.5793156 0.349803 0.5084043 0.7868691 0.3064898 0.7409487 0.5975443 0.2674142 0.5317098 0.8036009 0.2463997 0.6922671 0.6782724 0.1985309 0.6266865 0.753558 0.1923266 0.6937767 0.6940349 0.1093802 0.7033282 0.7023999 0.1012842 0.7967128 0.5958108 0.03379005 0.8139306 0.5799788 0.03049433 0.8482961 0.5286435 -0.06203907 0.7924298 0.6068 -0.06275075 0.8164303 0.5740243 -0.1262013 0.7684329 0.6273629 -0.1214982 0.673581 0.7290589 -0.220012 0.6548925 0.7229872 -0.2130434 0.6047816 0.7673667 -0.2810728 0.6655496 0.6914058 -0.2623596 0.5639817 0.783002 -0.3608416 0.646144 0.6725261 -0.3429656 0.5483751 0.7626661 -0.4099766 0.666218 0.6229549 -0.3925251 0.5620326 0.7280408 -0.4791737 0.6167114 0.6245476 -0.4572236 0.5636988 0.6878883 -0.5225956 0.5882614 0.6171243 -0.5042775 0.5658365 0.6523292 -0.5689384 0.5864965 0.5764816 -0.5396349 0.5706108 0.6190296 -0.6045345 0.5824958 0.5433569 -0.5800282 0.5771995 0.5748113 -0.6360753 0.576355 0.5130529 -0.6118978 0.5773749 0.5405732 -0.6265575 -0.5645909 0.5372737 -0.5984652 -0.5992025 0.5317856 -0.5843089 -0.5912183 0.5559175 -0.5695905 -0.6102724 0.5505766 -0.5636857 -0.6011803 0.5664281 -0.5533584 -0.6141732 0.5626595 -0.5117998 -0.6323263 0.5815708 -0.4991472 -0.6452168 0.5784006 -0.4617158 -0.6570088 0.5959514 -0.4514049 -0.6683124 0.5912634 -0.4293025 -0.667474 0.6084225 -0.4135254 -0.6822194 0.6029707 -0.3586909 -0.692736 0.6256659 -0.3436819 -0.7056119 0.619673 -0.3094236 -0.7088571 0.6338602 -0.3025942 -0.7147415 0.6305406 -0.2368809 -0.7275683 0.6438415 -0.2288017 -0.7334078 0.6401271 -0.1802103 -0.7385274 0.6496934 -0.1745469 -0.7424232 0.6467931 -0.1046349 -0.7487106 0.6545869 -0.09837186 -0.7521274 0.6516344 -0.04628187 -0.7531844 0.6561793 -0.04302632 -0.7549524 0.6543666 0.03548157 -0.7540264 0.6558853 0.03661149 -0.7544843 0.6552963 0.09221273 -0.7517867 0.6529271 0.09018158 -0.7509778 0.6541404 0.1689012 -0.7427524 0.647913 0.1665562 -0.7420432 0.6493312 0.2260329 -0.7339078 0.6405376 0.2194331 -0.7322318 0.644737 0.2994635 -0.7158303 0.6308 0.292322 -0.714805 0.6352966 0.3473515 -0.7034642 0.6200687 0.3355616 -0.7021131 0.6280411 0.4178825 -0.6791062 0.6034808 0.4017912 -0.6798096 0.6135331 0.4581376 -0.6645965 0.5902723 0.4452619 -0.6646825 0.5999492 0.4465662 -0.4248763 -0.7874382 0.444541 -0.4234161 -0.789368 0.4602249 -0.3767576 -0.8038948 0.4517546 -0.3693936 -0.8120752 0.4773024 -0.3523494 -0.8050047 0.4626876 -0.3177219 -0.8276311 0.4795307 -0.2603646 -0.83801 0.4709132 -0.2489727 -0.8463177 0.4371111 -0.2289193 -0.8697873 0.4730333 -0.2446523 -0.8463953 0.3306248 -0.2071947 -0.9207376 0.4521855 -0.2419239 -0.8584878 0.3157333 -0.2169823 -0.9237052 0.3514533 -0.2299004 -0.9075387 0.3490105 -0.254997 -0.9017585 0.3259364 -0.2499744 -0.9117446 0.3982366 -0.2908101 -0.8699638 0.3348327 -0.2933894 -0.8954383 0.4137472 -0.4267015 -0.804201 0.3692698 -0.4271693 -0.8253281 0.4230306 -0.5551065 -0.7161718 0.383713 -0.5583102 -0.7355638 0.3767057 -0.5764247 -0.7251396 0.4130718 -0.5744602 -0.7066593 0.3754296 -0.5540304 -0.7430363 0.3865055 -0.5578039 -0.7344851 0.4820474 -0.190042 -0.8552863 0.4782955 -0.1648738 -0.8625835 0.4732151 0.417092 -0.7759522 0.4578202 0.4495961 -0.7669837 0.429158 0.5544155 -0.7130547 0.4363387 0.5444898 -0.7163375 0.4144692 0.5774366 -0.7034077 0.4259226 0.5654586 -0.7062907 0.3927883 0.5893799 -0.7059382 0.4147583 0.5699506 -0.7093179 0.3606967 0.6022312 -0.7121907 0.3834013 0.5626918 -0.7323806 0.3483071 0.6286868 -0.695295 0.3187375 0.5223879 -0.7908966 0.3983701 -0.4306246 -0.8098541 0.3976248 -0.4300583 -0.8105212 0.4104693 -0.383952 -0.8271009 0.4035699 -0.3775148 -0.8334352 0.4211298 -0.3595963 -0.8326706 0.4106828 -0.3327239 -0.848902 0.4222172 -0.2386898 -0.8745055 0.4172881 -0.2284733 -0.8795855 0.3849542 -0.2023296 -0.9004849 0.4206289 -0.2247304 -0.8789583 0.2580021 -0.1726127 -0.9505998 0.3905741 -0.2204645 -0.8937826 0.2578741 -0.2015448 -0.9449236 0.2668809 -0.2056708 -0.9415275 0.2476689 -0.2601344 -0.9332686 0.2399834 -0.258139 -0.9358271 0.2379587 -0.3342949 -0.9119334 0.1519875 -0.3322049 -0.9308812 0.2869808 -0.4547613 -0.8431099 0.1344233 -0.4486702 -0.8835301 0.238326 -0.5680986 -0.7876959 0.2455367 -0.5683559 -0.7852919 0.2194861 -0.5838418 -0.7816359 0.2315218 -0.5857378 -0.7767297 0.2217131 -0.5876374 -0.7781554 0.2193822 -0.5840918 -0.7814782 0.2963232 -0.3951584 -0.8695071 0.3020179 -0.3606611 -0.8824449 0.4221407 0.316806 -0.8493712 0.4146201 0.3752452 -0.8290244 0.4065968 0.5674029 -0.7160538 0.4138889 0.5525513 -0.7234522 0.3846654 0.5990515 -0.7022606 0.4056236 0.5769888 -0.7089101 0.3566823 0.6118069 -0.7060242 0.3853513 0.5877466 -0.7113778 0.3347124 0.623649 -0.7064204 0.3539417 0.5971555 -0.7198129 0.3232606 0.6533823 -0.6845394 0.3191983 0.5865437 -0.7443649 0.3451928 -0.4383301 -0.8298848 0.3427208 -0.4363873 -0.8319307 0.3568325 -0.3922441 -0.8478296 0.3492051 -0.3842881 -0.8546218 0.363951 -0.3609687 -0.8586276 0.3560607 -0.3407869 -0.8701063 0.360707 -0.2087167 -0.9090258 0.3589947 -0.2048602 -0.9105796 0.3054485 -0.1553683 -0.9394477 0.359777 -0.1946867 -0.9125007 0.1679009 -0.1254417 -0.9777902 0.3097295 -0.1862639 -0.932402 0.1549834 -0.1669479 -0.9737088 0.1803491 -0.1816586 -0.9666821 0.1541991 -0.2593558 -0.9533925 0.1655834 -0.2624191 -0.9506411 0.1056854 -0.3418025 -0.9338104 0.1259992 -0.3441716 -0.930414 0.14757 -0.4669526 -0.8718821 0.07468307 -0.4595412 -0.885011 0.1691755 -0.5712633 -0.8031426 0.1257377 -0.5665073 -0.8144074 0.1695481 -0.5876377 -0.7911608 0.1645234 -0.5855591 -0.7937586 0.1594385 -0.5944483 -0.7881691 0.1620704 -0.6089195 -0.7764988 0.2012834 -0.3380229 -0.9193615 0.1683449 -0.5679396 -0.8056703 0.2687445 0.1487863 -0.9516508 0.2713729 0.010881 -0.9624128 0.3389697 0.5064247 -0.7928642 0.3354565 0.5152332 -0.7886721 0.3407922 0.6078797 -0.7171771 0.3541454 0.5941044 -0.7222334 0.3179292 0.6287 -0.7096882 0.3408884 0.6104918 -0.714909 0.2942078 0.639024 -0.710697 0.3169319 0.6156219 -0.7215011 0.2771459 0.6590583 -0.6991655 0.2857075 0.6076263 -0.7410543 0.2882134 -0.4510938 -0.8446583 0.2815524 -0.4467096 -0.8492225 0.2971052 -0.4046103 -0.864881 0.2823246 -0.3910638 -0.875992 0.3029842 -0.3620692 -0.8815364 0.2913014 -0.3374624 -0.8951328 0.2856638 -0.1584493 -0.9451403 0.2936718 -0.1759908 -0.939566 0.2088075 -0.09158873 -0.9736586 0.2849056 -0.1493055 -0.9468563 0.1218423 -0.0915808 -0.9883155 0.2162211 -0.1382787 -0.9665027 0.113441 -0.138758 -0.9838076 0.1377441 -0.1610629 -0.9772847 0.1125265 -0.2406133 -0.9640763 0.1426485 -0.2586734 -0.9553741 0.05996954 -0.3073276 -0.9497123 0.1477217 -0.3413293 -0.9282632 0.04042237 -0.4572594 -0.8884143 0.08464968 -0.4679736 -0.879679 0.05471587 -0.5745724 -0.8166228 0.0389989 -0.571774 -0.8194837 0.05111259 -0.5916275 -0.8045896 0.05282711 -0.5925423 -0.8038054 0.03710752 -0.5757703 -0.8167691 0.04843741 -0.6154761 -0.7866659 0.03777074 -0.1883747 -0.9813706 0.04854488 -0.4532158 -0.8900781 0.04655009 0.01035523 -0.9988623 0.05318444 -0.05459243 -0.9970913 0.1325148 0.2097783 -0.9687275 0.1237583 0.2790602 -0.9522655 0.2716245 0.5635975 -0.7801141 0.2655401 0.5743355 -0.7743561 0.2708576 0.6395643 -0.7194398 0.2869262 0.6259465 -0.7251651 0.2591483 0.6452319 -0.7186919 0.2692444 0.6325329 -0.7262297 0.2555394 0.663226 -0.7034423 0.2574901 0.6390148 -0.7248165 0.2319788 -0.4645519 -0.8546213 0.2233007 -0.4589079 -0.8599653 0.2353584 -0.4150674 -0.8788205 0.220888 -0.4029665 -0.8881591 0.2402561 -0.3692677 -0.8977296 0.227826 -0.3475379 -0.9095674 0.2364564 -0.1582401 -0.9586701 0.2281201 -0.1411514 -0.963347 0.2037433 -0.07690513 -0.9759992 0.2322434 -0.09457814 -0.9680486 0.1461151 -0.08131057 -0.9859204 0.206687 -0.1030167 -0.9729688 0.1262503 -0.1262895 -0.9839268 0.1612914 -0.1604353 -0.973779 0.1192505 -0.2117148 -0.970029 0.1614974 -0.2506065 -0.9545235 0.05823552 -0.2457123 -0.967592 0.1718895 -0.3187659 -0.9321171 0.02379465 -0.4210885 -0.9067074 0.1099443 -0.4576687 -0.8822992 0.01168352 -0.5697782 -0.8217155 0.03098225 -0.5747477 -0.817744 0.007323384 -0.5892335 -0.8079296 0.01142495 -0.5921999 -0.8057102 0.00273478 -0.5584769 -0.8295156 0.007507562 -0.5772997 -0.8164979 0.001454412 -0.1360155 -0.9907057 0.007718622 -0.1966703 -0.9804393 0.00446397 1.39215e-4 -0.9999901 0.00652635 -0.007891893 -0.9999476 0.02376884 0.0881167 -0.9958266 0.01899385 0.1044432 -0.9943495 0.1320405 0.4667871 -0.874457 0.1268882 0.4810424 -0.8674663 0.1992732 0.6126784 -0.7647976 0.1871444 0.6229963 -0.7595081 0.203628 0.6297983 -0.7495931 0.2062245 0.6256337 -0.7523656 0.1988452 0.6648549 -0.7200199 0.1995072 0.6173127 -0.7610006 0.1658002 -0.4734011 -0.8651021 0.1625674 -0.4708445 -0.8671087 0.1726988 -0.4189598 -0.8914302 0.16806 -0.4146783 -0.8943142 0.1740936 -0.3650227 -0.9145764 0.1713673 -0.3603342 -0.9169474 0.1744775 -0.1611108 -0.9713912 0.1678453 -0.1475793 -0.9747042 0.1693822 -0.07607388 -0.9826101 0.1707856 -0.07681411 -0.9823095 0.150223 -0.07736843 -0.9856202 0.1697106 -0.0814315 -0.9821239 0.1328197 -0.1178479 -0.9841092 0.1561242 -0.132841 -0.9787638 0.1003207 -0.1759799 -0.9792686 0.1516709 -0.2205254 -0.9635168 0.03105723 -0.2056637 -0.9781299 0.1258118 -0.2623057 -0.9567483 0.008366942 -0.4031506 -0.9150954 0.05152106 -0.4231009 -0.9046166 0.002134919 -0.5673032 -0.8235062 0.01076531 -0.5697726 -0.8217319 8.03518e-4 -0.5881915 -0.8087213 0.002118587 -0.58923 -0.8079626 -1.4844e-4 -0.5543315 -0.832296 8.51471e-4 -0.5584952 -0.8295074 -5.85957e-4 -0.1257428 -0.9920627 7.14032e-4 -0.1360847 -0.990697 5.23562e-4 -2.08019e-4 -0.9999999 6.48373e-4 -5.81494e-4 -0.9999997 0.007329285 0.07059216 -0.9974784 0.003827333 0.07910817 -0.9968587 0.05561071 0.4039771 -0.9130772 0.04234278 0.4325145 -0.9006322 0.1240671 0.5534279 -0.8236048 0.08178097 0.5850547 -0.80686 0.1467505 0.5679476 -0.8098766 0.1339904 0.5946817 -0.792717 0.1523244 0.5871132 -0.7950443 0.1523467 0.5996816 -0.7856034 0.09518218 -0.4754368 -0.8745858 0.0976426 -0.4774706 -0.8732054 0.09893673 -0.4228172 -0.9007981 0.0957759 -0.4198631 -0.9025198 0.1039342 -0.3670505 -0.9243764 0.1003677 -0.3608877 -0.9271929 0.105605 -0.1604018 -0.9813863 0.1036885 -0.156459 -0.9822267 0.1056043 -0.07782471 -0.9913582 0.1036992 -0.07685261 -0.9916351 0.1066092 -0.07840299 -0.991205 0.1056189 -0.07822889 -0.9913248 0.1039888 -0.1142087 -0.9879994 0.1080933 -0.1161251 -0.9873353 0.07218682 -0.1509539 -0.9859017 0.107822 -0.1775994 -0.9781784 0.01723778 -0.1855224 -0.9824888 0.07739841 -0.2151544 -0.9735082 0.003128767 -0.3961319 -0.9181884 0.02103894 -0.4040133 -0.9145111 4.3175e-4 -0.5664454 -0.8240993 0.003439664 -0.5673131 -0.823495 7.39383e-5 -0.587906 -0.8089293 4.29199e-4 -0.5881904 -0.8087223 -5.82474e-5 -0.5537542 -0.8326803 7.81864e-5 -0.5543293 -0.8322975 -1.41313e-4 -0.1243218 -0.992242 4.40701e-5 -0.1257314 -0.9920644 1.53632e-4 -5.11296e-4 -0.9999999 5.62024e-5 -2.30826e-4 -1 0.002461135 0.06545412 -0.9978526 7.03707e-4 0.06963646 -0.9975722 0.02091634 0.368127 -0.9295402 0.009429991 0.3922683 -0.9198026 0.06980371 0.4969414 -0.8649721 0.02733564 0.528499 -0.8484938 0.08776444 0.5027355 -0.8599736 0.07281851 0.5289467 -0.8455252 0.08349764 0.4990658 -0.8625321 0.08523714 0.4762531 -0.8751672 0.02701109 -0.4743782 -0.8799067 0.02967143 -0.4766638 -0.8785849 0.02831768 -0.4244107 -0.905027 0.02803641 -0.4241415 -0.9051619 0.0298506 -0.3674085 -0.9295806 0.02980071 -0.3673333 -0.9296119 0.03036046 -0.156063 -0.9872805 0.03108149 -0.1575204 -0.9870265 0.03123933 -0.07872509 -0.9964067 0.02993297 -0.0780667 -0.9964988 0.03385901 -0.07991766 -0.9962263 0.0312488 -0.07945168 -0.9963489 0.03515112 -0.1132591 -0.9929435 0.03417861 -0.1128581 -0.9930231 0.02487576 -0.140381 -0.9897851 0.03555476 -0.1469978 -0.9884976 0.005611598 -0.1789328 -0.9838453 0.0254476 -0.1863737 -0.9821493 9.08684e-4 -0.3941746 -0.9190353 0.006021678 -0.3962339 -0.9181299 9.7705e-5 -0.5662159 -0.824257 9.12317e-4 -0.5664477 -0.8240973 9.29933e-6 -0.5878354 -0.8089807 9.71135e-5 -0.5879054 -0.8089298 -4.88316e-6 -0.5536962 -0.8327188 9.5808e-6 -0.5537523 -0.8326815 -1.36948e-5 -0.1241995 -0.9922574 2.74214e-6 -0.1243215 -0.992242 2.84417e-5 -5.81157e-4 -0.9999998 4.15052e-6 -5.12531e-4 -0.9999999 4.21661e-4 0.0645622 -0.9979137 8.39954e-5 0.06537687 -0.9978607 0.003847181 0.3605118 -0.9327468 0.001242399 0.3662835 -0.9305025 0.0136376 0.481657 -0.8762538 0.004654824 0.4900013 -0.8717093 0.01410704 0.4873444 -0.873096 0.01374202 0.48815 -0.8726517 0.00993067 0.4937521 -0.8695461 0.01360589 0.4534546 -0.8911756 -0.03773629 -0.4766343 -0.8782914 -0.03930187 -0.4753394 -0.8789243 -0.04095971 -0.4222422 -0.9055573 -0.03936493 -0.4236784 -0.904957 -0.04523158 -0.362949 -0.9307106 -0.042993 -0.3665688 -0.9293971 -0.0469008 -0.1550905 -0.9867864 -0.04673701 -0.155442 -0.9867388 -0.04910153 -0.07721704 -0.9958045 -0.04621791 -0.07881402 -0.9958174 -0.05566143 -0.07881993 -0.9953338 -0.04914486 -0.08018302 -0.9955679 -0.05458277 -0.1141778 -0.9919598 -0.05627882 -0.1134166 -0.9919524 -0.0367918 -0.1513854 -0.9877899 -0.05502939 -0.1408814 -0.988496 -0.008448243 -0.1874383 -0.9822402 -0.03719031 -0.1794044 -0.9830722 -0.001344442 -0.3969832 -0.917825 -0.008862793 -0.3942093 -0.9189781 -1.4992e-4 -0.566549 -0.8240281 -0.001334726 -0.5662162 -0.8242558 -1.43055e-5 -0.5879421 -0.808903 -1.47966e-4 -0.5878353 -0.8089807 1.24098e-5 -0.5538123 -0.8326416 -1.50552e-5 -0.5536965 -0.8327186 2.45684e-5 -0.124393 -0.992233 -1.71225e-6 -0.124199 -0.9922574 -4.0102e-5 -4.90151e-4 -0.9999999 -8.80404e-6 -5.8113e-4 -0.9999998 -6.50337e-4 0.06580692 -0.9978322 -1.37297e-4 0.06456434 -0.9979135 -0.005467176 0.3685974 -0.9295731 -0.001948058 0.3606238 -0.9327093 -0.02052903 0.4966331 -0.8677178 -0.006409823 0.4821624 -0.8760585 -0.02394622 0.4958553 -0.8680749 -0.02033621 0.4880525 -0.8725774 -0.01893788 0.4542571 -0.8906694 -0.02391535 0.4946345 -0.868772 -0.1106852 -0.4760032 -0.8724504 -0.1108688 -0.4758405 -0.8725159 -0.1140671 -0.4201456 -0.900259 -0.1111974 -0.4228743 -0.89934 -0.1173289 -0.3627098 -0.9244867 -0.1143344 -0.3674483 -0.9229894 -0.1187149 -0.1524534 -0.9811548 -0.1153459 -0.1595003 -0.9804362 -0.1200171 -0.07570052 -0.9898815 -0.1165637 -0.07759857 -0.9901471 -0.1213962 -0.07845741 -0.9894986 -0.1201449 -0.0787298 -0.9896298 -0.1170885 -0.1185777 -0.9860171 -0.1236842 -0.1155464 -0.9855715 -0.08080816 -0.1798612 -0.9803673 -0.1199193 -0.1598665 -0.9798276 -0.01883071 -0.2075219 -0.9780491 -0.08213859 -0.195921 -0.9771736 -0.003346502 -0.4040691 -0.9147224 -0.02214336 -0.3977805 -0.9172134 -5.462e-4 -0.567414 -0.8234326 -0.003628313 -0.5665634 -0.8240103 -1.39214e-4 -0.5882618 -0.8086705 -5.40641e-4 -0.587943 -0.8089022 9.4726e-5 -0.5548355 -0.8319602 -1.48595e-4 -0.5538152 -0.8326396 2.35458e-4 -0.1266961 -0.9919416 -7.15427e-5 -0.1243927 -0.9922332 -2.24947e-4 -7.84666e-5 -1 -7.99257e-5 -4.89654e-4 -0.9999999 -0.003580033 0.07195258 -0.9974017 -0.001006186 0.06582462 -0.9978307 -0.02707982 0.4013489 -0.915525 -0.01245504 0.3696901 -0.9290717 -0.08623284 0.5556485 -0.8269333 -0.03161954 0.4985843 -0.8662644 -0.1072549 0.5598419 -0.8216285 -0.08164876 0.5104886 -0.8559994 -0.09964215 0.5016111 -0.8593357 -0.102822 0.5171318 -0.8497072 -0.1794759 -0.4709981 -0.8636836 -0.1774773 -0.4728979 -0.8630582 -0.1852372 -0.4150611 -0.8907365 -0.180607 -0.4195516 -0.8895829 -0.1882243 -0.3622137 -0.9128926 -0.1839942 -0.3692491 -0.9109343 -0.1868069 -0.1527388 -0.9704504 -0.1821095 -0.1624954 -0.9697585 -0.1724208 -0.08262258 -0.9815522 -0.1827104 -0.07726156 -0.9801263 -0.1442267 -0.08501803 -0.9858857 -0.1720381 -0.07857614 -0.9819515 -0.1362919 -0.1287234 -0.9822703 -0.1498548 -0.1197949 -0.9814239 -0.1124961 -0.2205371 -0.9688695 -0.1494125 -0.1928567 -0.9697846 -0.03344064 -0.243646 -0.9692876 -0.1149083 -0.2284079 -0.9667605 -0.00870198 -0.4205354 -0.9072344 -0.04911178 -0.4072628 -0.9119897 -0.002983212 -0.5695848 -0.8219272 -0.0107721 -0.5674846 -0.8233137 -0.001393675 -0.5894713 -0.8077882 -0.002936959 -0.5882678 -0.808661 2.13495e-4 -0.5617703 -0.8272932 -0.001495838 -0.5548329 -0.8319605 0.001031577 -0.1425092 -0.989793 -0.001128017 -0.1266597 -0.9919456 -9.03046e-4 -2.55909e-4 -0.9999996 -9.83282e-4 -3.07484e-5 -0.9999995 -0.01249724 0.08869302 -0.9959807 -0.005082905 0.07222914 -0.9973751 -0.07303464 0.4451895 -0.8924529 -0.05275517 0.4094725 -0.9107959 -0.1453055 0.6058247 -0.7822166 -0.09141731 0.5570364 -0.8254413 -0.1593793 0.6103775 -0.7759109 -0.1376738 0.5750519 -0.80645 -0.1568949 0.5979567 -0.7860227 -0.1578484 0.6017242 -0.7829509 -0.2449425 -0.4591745 -0.8539098 -0.2400763 -0.4645902 -0.8523611 -0.2485703 -0.4042138 -0.880241 -0.2395781 -0.4138953 -0.8782328 -0.2532458 -0.3542128 -0.9002221 -0.2457882 -0.3683016 -0.8966282 -0.2429974 -0.1694527 -0.9551116 -0.2445525 -0.1661224 -0.9552997 -0.1907856 -0.1106762 -0.9753726 -0.2365434 -0.08929097 -0.9675094 -0.1315242 -0.1004881 -0.9862067 -0.1872604 -0.08806228 -0.9783551 -0.125531 -0.1442165 -0.9815517 -0.1380951 -0.1288782 -0.9819981 -0.1365205 -0.2531733 -0.9577398 -0.1502064 -0.2285158 -0.9618829 -0.07605451 -0.31362 -0.9464979 -0.1466247 -0.27381 -0.9505417 -0.02850192 -0.4568737 -0.8890748 -0.1045414 -0.4276334 -0.8978869 -0.01690894 -0.5738219 -0.8188056 -0.03362339 -0.5697172 -0.8211528 -0.01128947 -0.593093 -0.8050549 -0.01656854 -0.5894351 -0.8076459 -0.003774702 -0.5891817 -0.8079919 -0.01204305 -0.5615355 -0.8273651 0.001432716 -0.2296968 -0.9732612 -0.01222598 -0.1408587 -0.9899543 -0.006552934 -0.007996261 -0.9999466 -0.01028525 0.001947522 -0.9999453 -0.04938775 0.1470934 -0.9878889 -0.02393811 0.09501516 -0.9951881 -0.1657425 0.5082289 -0.8451231 -0.1469123 0.481364 -0.8641212 -0.2193365 0.6279201 -0.7467315 -0.204743 0.6176606 -0.7593259 -0.2148255 0.62738 -0.7484947 -0.2240765 0.6370202 -0.7375602 -0.1954004 0.6021049 -0.7741371 -0.2457928 0.7175804 -0.6516628 -0.302732 -0.4480454 -0.8411949 -0.300638 -0.4502054 -0.8407925 -0.3087193 -0.3921904 -0.8665328 -0.2990537 -0.4027278 -0.865088 -0.3159387 -0.3447653 -0.8839229 -0.3066512 -0.363904 -0.8795107 -0.3110938 -0.1933467 -0.9305041 -0.3090535 -0.1969766 -0.9304226 -0.2599309 -0.154282 -0.9532224 -0.3076369 -0.1458048 -0.9402663 -0.1459609 -0.12555 -0.9812914 -0.2570872 -0.1332223 -0.9571615 -0.1217346 -0.1582067 -0.9798731 -0.1509448 -0.1496751 -0.9771454 -0.1313515 -0.2610313 -0.9563521 -0.1456972 -0.2540521 -0.9561537 -0.08284968 -0.3430033 -0.9356734 -0.1553185 -0.3216903 -0.934019 -0.06135964 -0.466121 -0.8825907 -0.1042369 -0.4580587 -0.8827893 -0.07846993 -0.571031 -0.8171695 -0.05810987 -0.5738268 -0.8169126 -0.07191574 -0.5931196 -0.801896 -0.07541781 -0.5914897 -0.8027778 -0.04973191 -0.6256726 -0.778499 -0.07353383 -0.5825104 -0.8094902 -0.01456761 -0.5184954 -0.8549565 -0.09842789 -0.1911689 -0.9766097 -0.04815852 -0.07018005 -0.9963713 -0.09490406 0.04301929 -0.9945566 -0.2210053 0.3959117 -0.8912971 -0.1387113 0.2374202 -0.9614525 -0.2904675 0.5883489 -0.7546353 -0.2821328 0.577083 -0.7664049 -0.2776876 0.6213646 -0.7326634 -0.3009452 0.6400966 -0.7069005 -0.260082 0.624211 -0.736694 -0.2841819 0.6535347 -0.7015219 -0.2493524 0.6191132 -0.7446626 -0.2729653 0.6719474 -0.6884596 -0.3575322 -0.4396604 -0.8239354 -0.358994 -0.4384279 -0.8239565 -0.3686655 -0.3834257 -0.8468002 -0.3605991 -0.3906489 -0.8469722 -0.37797 -0.3343113 -0.8633508 -0.3675551 -0.35549 -0.8593778 -0.3777069 -0.2161855 -0.9003341 -0.3724042 -0.2248666 -0.9004166 -0.3471795 -0.1963399 -0.9170154 -0.3748121 -0.1935987 -0.9066618 -0.2172171 -0.1652056 -0.9620415 -0.3433379 -0.1844383 -0.9209244 -0.1753717 -0.1811694 -0.9676892 -0.2218175 -0.1814432 -0.9580581 -0.1847831 -0.261902 -0.9472395 -0.1848909 -0.2618811 -0.9472243 -0.153963 -0.3430324 -0.9266197 -0.1583642 -0.3422502 -0.9261671 -0.1920931 -0.4591298 -0.8673523 -0.1191135 -0.4664075 -0.8765136 -0.1855854 -0.5688909 -0.8011999 -0.1665039 -0.5707088 -0.8040945 -0.1850313 -0.5851209 -0.789555 -0.179311 -0.5872275 -0.7893108 -0.1769275 -0.5997442 -0.7803869 -0.182025 -0.5932049 -0.7842034 -0.1621422 -0.5703976 -0.805206 -0.2674624 -0.3024663 -0.914865 -0.279684 0.0216124 -0.9598489 -0.3383845 0.2373235 -0.9105896 -0.358776 0.5258532 -0.7712057 -0.362997 0.5372914 -0.7612826 -0.34872 0.5903266 -0.7279484 -0.3691296 0.6173737 -0.6946893 -0.3249757 0.6055983 -0.7263894 -0.3495141 0.6274251 -0.6958287 -0.2900518 0.5921896 -0.7517856 -0.3294063 0.6454096 -0.6891574 -0.2379105 0.521023 -0.8197156 -0.3192775 0.6890013 -0.6506453 -0.4088553 -0.4324678 -0.8036225 -0.4116773 -0.4300859 -0.8034601 -0.4227898 -0.3751425 -0.8249346 -0.4131616 -0.3829 -0.8262476 -0.4370859 -0.3217479 -0.8399014 -0.422604 -0.3491872 -0.8363457 -0.4334316 -0.2345104 -0.8701391 -0.4289951 -0.2416436 -0.870386 -0.3980358 -0.2235451 -0.8897163 -0.4260994 -0.2192286 -0.8777119 -0.2762492 -0.1950435 -0.9410868 -0.3764176 -0.2068899 -0.9030539 -0.2701402 -0.2062623 -0.940468 -0.2855251 -0.2062718 -0.9359099 -0.2765106 -0.2550953 -0.9265357 -0.2639208 -0.2584134 -0.9292839 -0.2940039 -0.3119758 -0.9034561 -0.1840381 -0.340435 -0.9220814 -0.3247026 -0.4395132 -0.8374941 -0.1933428 -0.4591042 -0.8670881 -0.2576476 -0.5706558 -0.7797242 -0.2962377 -0.5668603 -0.7687086 -0.2237464 -0.5882838 -0.7770841 -0.2537662 -0.582877 -0.7719179 -0.2285053 -0.5829404 -0.7797216 -0.2245994 -0.5861414 -0.7784558 -0.333946 -0.2985892 -0.8940495 -0.2966871 -0.3935086 -0.8701308 -0.4280804 0.4030725 -0.8088757 -0.4200438 0.3215833 -0.8486151 -0.4120302 0.5531699 -0.7240403 -0.4150108 0.5676525 -0.7110111 -0.3915435 0.574863 -0.7184889 -0.4068123 0.5971864 -0.691283 -0.3567245 0.5757175 -0.735729 -0.3903627 0.6097 -0.6898427 -0.3076838 0.5448322 -0.7800568 -0.3719691 0.6354221 -0.6766666 -0.2256869 0.4272944 -0.8754913 -0.3802794 0.7040114 -0.5997964 -0.4538083 -0.4242908 -0.7836041 -0.4544233 -0.4237157 -0.783559 -0.4716712 -0.3633989 -0.8034099 -0.4564636 -0.375398 -0.8066704 -0.4930634 -0.3010663 -0.8162399 -0.471576 -0.3358272 -0.8153749 -0.4853791 -0.2449123 -0.8393005 -0.4803346 -0.2500565 -0.8406845 -0.4654887 -0.2436447 -0.850857 -0.480296 -0.2406312 -0.8434526 -0.3403849 -0.2235473 -0.9133263 -0.4137161 -0.2264899 -0.8817831 -0.328158 -0.2243738 -0.9175886 -0.3410518 -0.223849 -0.9130035 -0.3581967 -0.2498145 -0.8996044 -0.3480824 -0.2525498 -0.9028052 -0.3729386 -0.2927536 -0.8804614 -0.3417952 -0.3029757 -0.8895964 -0.352461 -0.4385665 -0.8266987 -0.3666283 -0.434926 -0.8224494 -0.3675466 -0.5642015 -0.7393147 -0.3831926 -0.5610699 -0.733733 -0.3361428 -0.5854235 -0.7377584 -0.3692922 -0.5787116 -0.7271288 -0.3906558 -0.5433258 -0.7430917 -0.3399769 -0.5665962 -0.7505895 -0.5275636 -0.005003452 -0.8495008 -0.4615726 -0.1931473 -0.8658204 -0.4708721 0.4586057 -0.7536314 -0.4694204 0.4205926 -0.7763676 -0.4342821 0.546428 -0.7161113 -0.4357239 0.5519555 -0.7109781 -0.4175584 0.5653616 -0.7113447 -0.424501 0.5745317 -0.6997945 -0.3860189 0.5524878 -0.7387467 -0.416532 0.5885654 -0.6928867 -0.2848182 0.4440707 -0.8495174 -0.4177008 0.6338939 -0.6509261 -0.1535413 0.261645 -0.9528731 -0.4839923 0.8031215 -0.3474875 -0.4942361 -0.4151446 -0.7637969 -0.493253 -0.4162089 -0.7638531 -0.5114748 -0.3523119 -0.7837538 -0.496262 -0.3640782 -0.7881441 -0.5250694 -0.2938139 -0.7987338 -0.5123507 -0.3071956 -0.8019524 -0.518348 -0.2527841 -0.8169551 -0.521048 -0.2519621 -0.8154902 -0.4741092 -0.2521509 -0.8435878 -0.5166381 -0.2497259 -0.8189763 -0.4082117 -0.2492145 -0.8782114 -0.4674403 -0.2488734 -0.8482699 -0.3983397 -0.2434456 -0.8843415 -0.39853 -0.2434383 -0.8842577 -0.3738823 -0.2561054 -0.8914158 -0.4048648 -0.250094 -0.8795099 -0.1421014 -0.3420538 -0.9288738 -0.3956125 -0.28891 -0.8717922 0.1773064 -0.4722136 -0.863468 -0.2703112 -0.4471824 -0.8526194 -0.3149825 -0.569328 -0.759376 -0.2615323 -0.5771269 -0.7736444 -0.6492516 -0.4879928 -0.5833828 -0.4059801 -0.5738854 -0.7112213 -0.7251166 -0.42936 -0.5383828 -0.6463374 -0.4842451 -0.5897074 -0.7338403 -0.1351205 -0.6657484 -0.7220111 -0.1834637 -0.667114 -0.5868468 0.3258179 -0.7412514 -0.5858088 0.3307352 -0.7398934 -0.4733445 0.5022852 -0.7236399 -0.473801 0.5163325 -0.7133817 -0.4317737 0.5491687 -0.7155315 -0.4406369 0.5594145 -0.7020645 -0.4092745 0.5467575 -0.7304455 -0.4314199 0.5737825 -0.6961686 -0.276053 0.3865303 -0.8799939 -0.4583076 0.6337214 -0.6231785 -0.3252625 0.459449 -0.8265053 -0.3851044 0.6011337 -0.7002378 -0.5344215 -0.4038923 -0.7424721 -0.5321676 -0.406638 -0.7425923 -0.5512548 -0.3418904 -0.761071 -0.5365754 -0.3531429 -0.7664054 -0.5640864 -0.2902208 -0.7730321 -0.5524298 -0.3008096 -0.77739 -0.5656276 -0.2585415 -0.7830849 -0.5634982 -0.2590866 -0.7844387 -0.5263445 -0.2605838 -0.8093564 -0.5654637 -0.2573432 -0.7835977 -0.4771946 -0.2677527 -0.8370147 -0.5287844 -0.2641638 -0.8066007 -0.4704199 -0.2634535 -0.842198 -0.4733427 -0.2632606 -0.8406192 -0.182386 -0.287061 -0.9403889 -0.462853 -0.2568461 -0.8484086 0.6921725 -0.2966367 -0.6579545 -0.2903115 -0.3292781 -0.8984962 0.8806386 -0.2245416 -0.4172011 0.5149571 -0.4010068 -0.7576362 0.1354243 -0.5458043 -0.8268967 0.7636882 -0.339183 -0.5493044 -0.7410942 -0.4197123 -0.524043 -0.4632958 -0.5496414 -0.6951628 -0.7661713 -0.4033893 -0.5002587 -0.7492428 -0.4288392 -0.5047101 -0.7706738 -0.2317541 -0.5935927 -0.7670668 -0.2745239 -0.5798666 -0.6950411 0.1161825 -0.7095207 -0.6924633 0.1277523 -0.7100521 -0.5382695 0.4176347 -0.7320159 -0.5387542 0.4331809 -0.7225637 -0.4465439 0.5231432 -0.7258924 -0.4672642 0.5358429 -0.703233 -0.4177903 0.5371319 -0.7327623 -0.4486171 0.5712399 -0.6873338 -0.3712145 0.4908256 -0.7882195 -0.4809226 0.6326649 -0.6069998 -0.3973034 0.5263125 -0.7517614 -0.4256829 0.5941138 -0.6825122 -0.5724831 -0.3872197 -0.7227199 -0.5663908 -0.3955245 -0.7230228 -0.5897724 -0.3308644 -0.7366799 -0.5756555 -0.3421205 -0.7426805 -0.6021437 -0.2874529 -0.7448449 -0.5916705 -0.2966932 -0.7495994 -0.6086357 -0.2595442 -0.7497996 -0.6023935 -0.2614913 -0.7541516 -0.6003605 -0.260994 -0.7559428 -0.6086378 -0.2596312 -0.7497678 -0.5933493 -0.2741517 -0.7568207 -0.6004727 -0.2725213 -0.7517744 -0.6006425 -0.2812517 -0.7484158 -0.5944954 -0.2828328 -0.7527158 -0.537288 -0.2884167 -0.7925513 -0.5975818 -0.2743031 -0.7534281 0.1382279 -0.4210816 -0.8964282 -0.569651 -0.3322336 -0.7517438 0.1293429 -0.5200045 -0.8443139 -0.1318492 -0.5236631 -0.8416607 -0.7386388 -0.3942335 -0.5468024 -0.144493 -0.558793 -0.8166224 -0.7726068 -0.4010328 -0.4921906 -0.756637 -0.4144596 -0.5056913 -0.7680442 -0.4290273 -0.4754405 -0.7703571 -0.4247402 -0.475548 -0.7754961 -0.3454171 -0.5284817 -0.7771776 -0.3387397 -0.5303305 -0.7403874 0.003950655 -0.6721689 -0.7402902 -8.04773e-4 -0.672287 -0.6142984 0.3552057 -0.7046039 -0.6053581 0.3478615 -0.7159148 -0.5153013 0.4880222 -0.7044849 -0.5425609 0.4884751 -0.6833884 -0.4340248 0.5193466 -0.7361397 -0.5191761 0.586066 -0.6220796 -0.4335835 0.5536543 -0.7109658 -0.5447097 0.6912144 -0.4748832 -0.432947 0.5649413 -0.7024232 -0.5911549 0.7693392 -0.2421845 -0.6126908 -0.3649914 -0.7009931 -0.6013681 -0.3790931 -0.70331 -0.6267679 -0.3227864 -0.7092044 -0.6177099 -0.3301703 -0.7137381 -0.6392042 -0.2871599 -0.7134124 -0.630975 -0.2943717 -0.7177855 -0.653787 -0.2560064 -0.7120558 -0.6410706 -0.2608644 -0.7217882 -0.6687841 -0.253282 -0.6989822 -0.6536324 -0.2570367 -0.7118264 -0.66859 -0.2644475 -0.6950216 -0.6626893 -0.2669186 -0.6997123 -0.672885 -0.2734165 -0.6873641 -0.6635195 -0.2791541 -0.694129 -0.7004304 -0.2524064 -0.6675989 -0.6755517 -0.2644966 -0.688238 -0.7522622 -0.2689607 -0.6014664 -0.6610944 -0.3149595 -0.6809955 -0.8601334 -0.2784573 -0.4273548 -0.4801355 -0.4771081 -0.7360963 -0.843954 -0.3224521 -0.4286796 -0.7739914 -0.3764335 -0.5091514 -0.8014967 -0.3999668 -0.4445555 -0.7961694 -0.4049008 -0.4496331 -0.7793037 -0.4578132 -0.4278937 -0.7700728 -0.4676021 -0.4339772 -0.7811885 -0.4666605 -0.4146959 -0.7706422 -0.4787738 -0.4205785 -0.8803374 -0.2023767 -0.4290103 -0.830215 -0.282589 -0.4805067 -0.9116147 0.1783368 -0.3703441 -0.8501047 0.1547734 -0.503356 -0.8742814 0.2903711 -0.3889946 -0.8716036 0.291889 -0.3938378 -0.6781377 0.4515348 -0.579867 -0.7939354 0.5018226 -0.3432797 -0.5340304 0.5810075 -0.6142001 -0.6387555 0.739568 -0.2122044 -0.5604511 0.7018209 -0.4397069 -0.611198 0.776803 -0.1517039 -0.5845457 -0.5678346 0.5795432 -0.573084 -0.5640035 0.5945376 -0.6190253 -0.5182422 0.5901124 -0.595793 -0.5068554 0.6229994 -0.6421437 -0.4704651 0.6052389 -0.6287327 -0.461762 0.6256766 -0.6751944 -0.4139679 0.610527 -0.6521599 -0.3983163 0.6450051 -0.6914253 -0.3519504 0.6309216 -0.6811428 -0.3444575 0.6460601 -0.7134512 -0.2868914 0.6392815 -0.6957395 -0.2735905 0.6641498 -0.7275907 -0.2103188 0.652976 -0.7171114 -0.2031998 0.6666792 -0.746405 -0.1257246 0.6535081 -0.7396374 -0.1203699 0.6621538 -0.7498927 -0.0429179 0.6601659 -0.7479489 -0.04128313 0.6624712 -0.7511839 0.04573673 0.6585068 -0.7527774 0.04439133 0.6567767 -0.7488265 0.1255317 0.6507694 -0.7558315 0.1194966 0.6437696 -0.736079 0.166567 0.6560817 -0.7492231 0.1483881 0.6454811 -0.7205561 0.2748062 0.6366164 -0.7365924 0.2275599 0.6369051 -0.6803271 0.4585894 0.5717087 -0.7061241 0.4268099 0.5649976 -0.6432053 0.4609788 0.61138 -0.6826732 0.4409465 0.5826866 -0.6505503 0.4385963 0.6200141 -0.6431727 0.4412581 0.6257957 -0.6640825 0.3826391 0.6423252 -0.6544849 0.3867677 0.6496617 -0.6559578 0.3613512 0.66268 -0.6660889 0.3533267 0.6568758 -0.6345886 0.4048331 0.6583369 -0.6545456 0.3842055 0.6511194 -0.6105679 0.4626796 0.6427554 -0.6344579 0.4330404 0.6402651 -0.5567303 -0.5786598 0.5959902 -0.5537211 -0.5776445 0.5997666 -0.5761335 -0.5422143 0.6116158 -0.5591937 -0.5328266 0.6351365 -0.6027458 -0.4918646 0.6283047 -0.5815077 -0.4759528 0.6597861 -0.6298769 -0.4409316 0.6394017 -0.606134 -0.423804 0.6730467 -0.6569061 -0.3717964 0.6559282 -0.6375203 -0.3577451 0.6823388 -0.6724003 -0.3004381 0.6764724 -0.6608968 -0.29086 0.6918207 -0.6931598 -0.2217671 0.6858199 -0.6844612 -0.215217 0.696559 -0.7107516 -0.1366321 0.6900463 -0.7051857 -0.1316038 0.696702 -0.7147481 -0.04610276 0.6978609 -0.7171164 -0.04812055 0.6952902 -0.7207385 0.04914373 0.6914629 -0.7257136 0.0450496 0.6865204 -0.7164326 0.1324 0.6849779 -0.7271208 0.1229484 0.6754103 -0.7011044 0.1787497 0.6902907 -0.7170976 0.1572962 0.6789911 -0.6747714 0.3121621 0.6687589 -0.7019559 0.2388789 0.6709656 -0.6197552 0.5025632 0.6027717 -0.6652588 0.4498954 0.5958396 -0.5406936 0.4981192 0.6778848 -0.6165857 0.4645856 0.635596 -0.5828621 0.4440585 0.6805027 -0.517351 0.4637481 0.7192258 -0.6205179 0.3792573 0.6863828 -0.5745554 0.3976032 0.7154005 -0.6190898 0.3649359 0.6953773 -0.621024 0.3635041 0.6944019 -0.5900778 0.4272173 0.6850501 -0.6159747 0.4056709 0.6752824 -0.5529875 0.4915342 0.6727548 -0.5890182 0.4511658 0.6704528 -0.5231348 -0.6003531 0.6049018 -0.5050199 -0.5966516 0.623668 -0.5423284 -0.5597357 0.6265587 -0.524587 -0.5523108 0.6478899 -0.5666714 -0.5136819 0.6442162 -0.5352504 -0.4957502 0.6839144 -0.589849 -0.459748 0.66386 -0.5674005 -0.4446622 0.6930601 -0.6130117 -0.3948982 0.6843041 -0.5939217 -0.3812457 0.7084553 -0.6390091 -0.3168912 0.7008905 -0.6214655 -0.3036091 0.7222204 -0.6613098 -0.2377843 0.7114268 -0.6456784 -0.2272879 0.7289991 -0.6726248 -0.151162 0.7243798 -0.6612879 -0.1421911 0.7365324 -0.6795251 -0.04961818 0.7319725 -0.6781947 -0.04857146 0.7332754 -0.684834 0.05135273 0.7268875 -0.6886081 0.04847133 0.7235119 -0.6792022 0.1369129 0.7210682 -0.6874632 0.1297079 0.714542 -0.6652787 0.1902157 0.7219573 -0.6795642 0.1703382 0.7135667 -0.6401581 0.3587352 0.6793428 -0.6647912 0.2982141 0.6849242 -0.6115152 0.5218943 0.5947062 -0.6278206 0.5048953 0.5923869 -0.5806845 0.503169 0.6400208 -0.6060991 0.4909817 0.6257642 -0.5670281 0.4401595 0.6962319 -0.5290631 0.4533472 0.7173345 -0.5840378 0.3763581 0.7192041 -0.5524287 0.3905732 0.7363934 -0.5801315 0.3721621 0.7245295 -0.5843081 0.3684942 0.7230464 -0.5538828 0.4453685 0.7034633 -0.5743991 0.4271036 0.6983181 -0.5258768 0.5150391 0.6768962 -0.5491575 0.4904083 0.6767022 -0.4624173 -0.6297104 0.6242076 -0.4519663 -0.6258127 0.6356769 -0.4901957 -0.5882441 0.6431773 -0.4640036 -0.5743613 0.6743959 -0.5161876 -0.5328451 0.6705419 -0.4920432 -0.5200531 0.6981678 -0.5472638 -0.481995 0.6842391 -0.5211247 -0.4661166 0.7149577 -0.57098 -0.4121564 0.7100064 -0.5543158 -0.4016194 0.7289965 -0.6007103 -0.3361496 0.7253624 -0.5778636 -0.3206074 0.750523 -0.6168416 -0.2542961 0.7448758 -0.6014039 -0.244157 0.7607238 -0.6282908 -0.1601774 0.7613108 -0.6205096 -0.1541318 0.7689025 -0.6405914 -0.05329322 0.7660304 -0.636739 -0.05026853 0.7694393 -0.6457453 0.04920542 0.7619659 -0.6447837 0.04995709 0.7627309 -0.6381695 0.1376372 0.7574931 -0.6440265 0.132674 0.7534107 -0.6190399 0.2042961 0.7583223 -0.6377344 0.1804797 0.7488137 -0.5820266 0.4095098 0.7025288 -0.618179 0.337636 0.7098287 -0.5803821 0.5242542 0.6231487 -0.5860193 0.5193259 0.6219984 -0.5652886 0.5039737 0.6530385 -0.5609764 0.5058143 0.6553301 -0.4777864 0.4371677 0.7619742 -0.3988131 0.462779 0.7916967 -0.5170536 0.3580923 0.7774481 -0.4363019 0.3958234 0.8080621 -0.5205475 0.3742179 0.7674579 -0.5186653 0.3758934 0.7679132 -0.4922036 0.4621486 0.7376682 -0.5192548 0.4420269 0.7314279 -0.4851831 0.5241183 0.6999267 -0.497095 0.5134657 0.6994638 -0.4211159 -0.6417699 0.6409313 -0.4172006 -0.6401939 0.6450546 -0.4401749 -0.6045156 0.663933 -0.4259048 -0.5947828 0.6817907 -0.4721 -0.5522114 0.6871567 -0.4503626 -0.5392592 0.711599 -0.4949885 -0.4989581 0.7113559 -0.4773096 -0.4871836 0.7313191 -0.5172443 -0.4319527 0.7388337 -0.4992493 -0.4198141 0.7579621 -0.53886 -0.3562255 0.7633699 -0.5225792 -0.3439647 0.7801278 -0.5617005 -0.268942 0.7824083 -0.5487838 -0.2597332 0.7945912 -0.5831918 -0.1698737 0.7943742 -0.5729085 -0.1613693 0.803577 -0.597813 -0.06400173 0.7990767 -0.5856717 -0.05432432 0.808726 -0.5988674 0.04196423 0.799748 -0.5927153 0.04662996 0.8040611 -0.5880066 0.1371878 0.7971372 -0.5930765 0.1330764 0.7940725 -0.5656739 0.221988 0.794188 -0.5869954 0.1960841 0.7854856 -0.5197686 0.4634414 0.7176787 -0.562102 0.4010983 0.7232991 -0.4796254 0.5525094 0.6816838 -0.5216561 0.5278095 0.6702926 -0.4754418 0.5123143 0.7151847 -0.4574571 0.5176216 0.7230498 -0.4651737 0.4217986 0.7782669 -0.3951032 0.4453952 0.8034405 -0.4869648 0.3458145 0.802046 -0.4500722 0.3660407 0.8145239 -0.478454 0.3830882 0.7901425 -0.4856067 0.3758693 0.7892454 -0.4557007 0.4735063 0.7537431 -0.4722391 0.4604349 0.7516581 -0.4465829 0.5220305 0.7266691 -0.4517527 0.5193234 0.7254121 -0.360352 -0.6633399 0.6558405 -0.3487045 -0.6582207 0.6671962 -0.3855758 -0.6209238 0.6824845 -0.3675824 -0.6072244 0.7043875 -0.4103585 -0.5737809 0.7087888 -0.3909487 -0.5605219 0.7300509 -0.4352606 -0.5186901 0.7358729 -0.4137869 -0.5036866 0.7583405 -0.4580826 -0.456112 0.7629693 -0.4372748 -0.442204 0.7831006 -0.4837644 -0.3748369 0.7908661 -0.4634696 -0.3602257 0.8095884 -0.5070885 -0.2853521 0.8132869 -0.4890423 -0.2730282 0.8284282 -0.5262856 -0.1873608 0.8294091 -0.5064811 -0.1713085 0.8450623 -0.5414011 -0.07805496 0.8371334 -0.5258123 -0.06486093 0.8481242 -0.5425012 0.03700309 0.8392398 -0.5389366 0.03988927 0.8414015 -0.5330045 0.1407693 0.8343203 -0.5416811 0.1332982 0.8299478 -0.5134383 0.2400053 0.8238803 -0.5330535 0.2161214 0.8180132 -0.4769202 0.4947667 0.7264662 -0.504184 0.4606421 0.7304844 -0.4441677 0.5686349 0.6923651 -0.4726462 0.5531054 0.6860613 -0.4433559 0.5147747 0.7337864 -0.4388679 0.5162239 0.7354645 -0.4419398 0.4206289 0.7923134 -0.4308159 0.4247698 0.7962213 -0.4314767 0.3537383 0.8298777 -0.4410833 0.3490018 0.8268272 -0.4111874 0.39907 0.8195537 -0.4305741 0.3839268 0.8168269 -0.4013189 0.4827709 0.77838 -0.414168 0.4739416 0.7770743 -0.3914252 0.5232205 0.7569853 -0.3990129 0.5198162 0.7553675 -0.3067321 -0.6774906 0.6685222 -0.3024103 -0.6757681 0.6722243 -0.3279517 -0.6390663 0.6957312 -0.3041282 -0.6238592 0.7199345 -0.3547055 -0.5929471 0.7229093 -0.3306394 -0.5776122 0.7463523 -0.3773384 -0.5361812 0.7550666 -0.358532 -0.5240172 0.7725676 -0.3976055 -0.4738653 0.7857236 -0.377917 -0.4619243 0.8023746 -0.4151924 -0.3925514 0.8206818 -0.391145 -0.3779338 0.8391495 -0.4313337 -0.3014586 0.8503376 -0.4152497 -0.2913423 0.8617932 -0.4474521 -0.1974639 0.8722355 -0.4379342 -0.1899544 0.8787099 -0.4626697 -0.08082187 0.882839 -0.4594566 -0.07796126 0.8847723 -0.4706117 0.03762531 0.8815378 -0.4741621 0.03463071 0.8797562 -0.4641519 0.1495497 0.8730394 -0.4771171 0.1380952 0.8679222 -0.4461129 0.2580421 0.85697 -0.4659938 0.2340445 0.8532719 -0.4150971 0.5139333 0.750711 -0.4370058 0.4887879 0.7550579 -0.3874465 0.5818848 0.7150493 -0.4105809 0.5707975 0.7110652 -0.3839558 0.5216249 0.761896 -0.3851706 0.5212517 0.7615381 -0.3803068 0.4283171 0.8197018 -0.3843369 0.4267238 0.8186525 -0.3719316 0.3645988 0.8536596 -0.3830118 0.3579185 0.8515845 -0.3577673 0.4116918 0.8381602 -0.3696023 0.4000667 0.8386542 -0.3463725 0.4885382 0.8008474 -0.3541309 0.4813145 0.8018277 -0.3429279 0.5190066 0.782964 -0.3442972 0.5182816 0.7828434 -0.2392101 -0.6941236 0.6789484 -0.230785 -0.6904213 0.6856068 -0.2588008 -0.6512337 0.7133842 -0.2393137 -0.6383664 0.7315855 -0.2798844 -0.6098932 0.7414142 -0.2605054 -0.5963615 0.7592693 -0.2995488 -0.5508107 0.7790239 -0.2848148 -0.5397922 0.7921522 -0.3203915 -0.49024 0.810564 -0.3034834 -0.4771482 0.8247591 -0.3466481 -0.4114541 0.8429357 -0.3248678 -0.396352 0.8587002 -0.3587646 -0.3182818 0.8774878 -0.3427103 -0.3081204 0.8874748 -0.3702515 -0.2143077 0.9038728 -0.3513478 -0.2008893 0.9144389 -0.378762 -0.09257209 0.9208527 -0.36346 -0.08047491 0.9281275 -0.3811572 0.0332272 0.923913 -0.3778232 0.03593671 0.9251802 -0.3782711 0.1497983 0.9134942 -0.3828656 0.1458017 0.9122258 -0.3673981 0.266696 0.8910061 -0.3802214 0.2511086 0.8901552 -0.3433156 0.5250923 0.778725 -0.3590896 0.5074375 0.7833019 -0.322161 0.591502 0.7391466 -0.3378409 0.5845705 0.7376592 -0.3187172 0.5287309 0.7866784 -0.3253965 0.5268934 0.7851755 -0.3153554 0.4346396 0.8435873 -0.3228072 0.4321635 0.8420392 -0.3073657 0.3713632 0.8761368 -0.3171347 0.3666809 0.8746261 -0.2896684 0.4250574 0.8575655 -0.3069058 0.4124712 0.8577157 -0.2768815 0.5041276 0.8180415 -0.2954911 0.4899535 0.8201407 -0.2678199 0.5269685 0.8065835 -0.2816327 0.5192003 0.8069165 -0.1771911 -0.7036829 0.6880652 -0.1773202 -0.7037423 0.6879712 -0.1919001 -0.6623221 0.7242264 -0.1749664 -0.6520752 0.7376887 -0.2061154 -0.6197358 0.757261 -0.1900389 -0.6096464 0.7695561 -0.2162779 -0.5643948 0.7966696 -0.2015705 -0.5546357 0.8073095 -0.2332772 -0.5028422 0.832305 -0.217629 -0.4907813 0.8436654 -0.2521084 -0.4268252 0.8684824 -0.2383425 -0.4161768 0.8774905 -0.2687889 -0.3305147 0.9047168 -0.2595064 -0.3240655 0.9097461 -0.2802466 -0.2225919 0.9337638 -0.2724126 -0.2168469 0.9374268 -0.2887512 -0.09808123 0.952367 -0.2806662 -0.09185898 0.9553996 -0.2895953 0.03359353 0.9565595 -0.2899999 0.03327208 0.9564483 -0.2824885 0.1540644 0.9468181 -0.2915332 0.1461484 0.9453302 -0.2742081 0.2759525 0.9212276 -0.2863709 0.2605572 0.9220097 -0.2552891 0.5392991 0.8024862 -0.2709665 0.5206131 0.8096539 -0.2424258 0.5995244 0.7627584 -0.2517813 0.5952624 0.7630655 -0.2388755 0.53606 0.8096778 -0.2466511 0.5339449 0.8087436 -0.2351033 0.4408152 0.8662612 -0.2430074 0.4380964 0.8654589 -0.2265219 0.379692 0.8969515 -0.2360873 0.3744567 0.8966856 -0.20523 0.4442597 0.8720745 -0.2269971 0.4274488 0.8750771 -0.2040274 0.5144461 0.8328974 -0.2183459 0.5038088 0.8357643 -0.2101149 0.5277202 0.8230208 -0.2130047 0.5246029 0.82427 -0.1085728 -0.7111921 0.6945631 -0.1069245 -0.7101001 0.6959347 -0.1217614 -0.6667613 0.7352575 -0.1127904 -0.6605057 0.7423009 -0.1302482 -0.6267921 0.7682233 -0.1211538 -0.6203776 0.7748894 -0.1368759 -0.5747144 0.8068262 -0.1270707 -0.5682995 0.8129507 -0.1461819 -0.5106363 0.8472788 -0.1374949 -0.5044032 0.8524509 -0.1579994 -0.4328971 0.8874889 -0.1494896 -0.4263224 0.8921335 -0.1696343 -0.33859 0.9255167 -0.163331 -0.3339011 0.9283497 -0.1789389 -0.2266904 0.9573884 -0.1758265 -0.2242401 0.9585413 -0.186644 -0.100519 0.9772717 -0.1829733 -0.09763324 0.9782579 -0.1872869 0.0329355 0.981753 -0.1881062 0.03230565 0.9816173 -0.1787641 0.1584707 0.971046 -0.186913 0.1515429 0.9706175 -0.1620856 0.2912539 0.9428147 -0.1788883 0.2705025 0.9459532 -0.1458922 0.5551374 0.8188638 -0.1625419 0.5345617 0.8293516 -0.1485028 0.6024788 0.7841979 -0.1473386 0.6030156 0.7840048 -0.1476049 0.5404791 0.8283086 -0.149444 0.5400131 0.8282828 -0.1423727 0.4448047 0.8842392 -0.1503493 0.4423589 0.8841457 -0.1320805 0.3917223 0.9105539 -0.1461989 0.385007 0.9112605 -0.1085238 0.4557602 0.8834621 -0.1210008 0.4488508 0.8853767 -0.1122148 0.5088958 0.8534829 -0.1051004 0.5116225 0.8527581 -0.1192054 0.5177818 0.8471671 -0.1160652 0.52086 0.8457149 -0.03723984 -0.7146471 0.6984932 -0.03920996 -0.715844 0.6971585 -0.04084849 -0.6710526 0.7402836 -0.03289288 -0.6660963 0.7451402 -0.04968631 -0.632264 0.7731583 -0.03995037 -0.6256588 0.7790732 -0.05519151 -0.5782024 0.8140246 -0.0509535 -0.5753867 0.8162928 -0.05806988 -0.5130137 0.856414 -0.05609065 -0.5116267 0.857375 -0.0628066 -0.4349559 0.8982588 -0.05859553 -0.4318736 0.9000289 -0.06670087 -0.3423455 0.9372037 -0.06274372 -0.3393664 0.9385594 -0.06606209 -0.2275797 0.971516 -0.06439822 -0.2262654 0.9719346 -0.0671162 -0.1015643 0.9925624 -0.06575787 -0.1004877 0.9927629 -0.06805229 0.03166598 0.9971792 -0.06883835 0.03104174 0.9971448 -0.06397789 0.1629293 0.9845613 -0.071002 0.1567577 0.9850816 -0.04188072 0.3173342 0.9473886 -0.06626778 0.2872112 0.9555724 -0.03264522 0.5762034 0.8166543 -0.05283212 0.5510166 0.8328202 -0.04698687 0.5987334 0.799569 -0.03658765 0.6037168 0.7963589 -0.05119293 0.5414808 0.8391531 -0.0440948 0.5432077 0.8384397 -0.04532676 0.4490954 0.8923333 -0.05159837 0.4469851 0.8930521 -0.03971832 0.4010338 0.9152019 -0.04770243 0.3965595 0.9167688 -0.03414148 0.4576335 0.8884851 -0.03289812 0.4584327 0.8881201 -0.0493921 0.4960958 0.8668618 -0.02904921 0.5044932 0.862927 -0.06287842 0.4970872 0.8654194 -0.04948896 0.5101846 0.85864 0.03205347 -0.7153554 0.6980254 0.032687 -0.7148993 0.6984631 0.02860182 -0.6690303 0.7426847 0.02773481 -0.6696148 0.7421906 0.03215825 -0.6295859 0.7762652 0.02756977 -0.6326391 0.773956 0.03511476 -0.5760563 0.8166556 0.03217607 -0.5779347 0.8154485 0.03712242 -0.5097209 0.8595387 0.03380388 -0.5120218 0.8583071 0.04220926 -0.4322875 0.9007474 0.03595751 -0.4366388 0.8989182 0.04173898 -0.3405281 0.9393075 0.04049378 -0.3414557 0.9390252 0.04278075 -0.2247272 0.9734821 0.04125922 -0.2259148 0.9732729 0.04576963 -0.09934729 0.9939997 0.04342865 -0.1011813 0.9939197 0.04665142 0.03192031 0.9984012 0.04610162 0.03147971 0.9984406 0.04001867 0.157258 0.9867464 0.04560548 0.1622446 0.9856961 0.01859897 0.2888311 0.9571995 0.04033637 0.3148174 0.9482948 0.009820282 0.5514996 0.8341174 0.03182291 0.5740082 0.8182311 0.03106981 0.6047098 0.7958397 0.01706635 0.5988364 0.8006896 0.03728407 0.54436 0.8380227 0.02730566 0.5422158 0.8397956 0.03569352 0.4493965 0.8926191 0.0374974 0.4499824 0.8922499 0.02689534 0.3959718 0.9178687 0.0377385 0.4023597 0.9147035 0.01533007 0.4537937 0.890975 0.02086317 0.4580268 0.8886936 0.02478063 0.5024584 0.8642463 0.01311337 0.4965711 0.867897 0.03206437 0.5053918 0.8622941 0.02463638 0.4977796 0.8669536 0.1017476 -0.7102918 0.696515 0.09753769 -0.7130697 0.6942752 0.1099119 -0.6634011 0.7401476 0.1053332 -0.6664267 0.7380925 0.1161788 -0.6229943 0.7735508 0.1093784 -0.6278868 0.7705807 0.1226312 -0.5682008 0.813701 0.1136483 -0.5744437 0.8106161 0.1302109 -0.5041025 0.8537715 0.1236281 -0.5088104 0.8519555 0.1402818 -0.4291374 0.8922792 0.1329264 -0.4343917 0.8908616 0.1460991 -0.3387055 0.9294804 0.1462775 -0.3385711 0.9295012 0.1517101 -0.225071 0.9624589 0.1527419 -0.2243052 0.9624744 0.1592388 -0.09724748 0.9824388 0.1561809 -0.09953737 0.9827004 0.1633448 0.03438192 0.9859698 0.1612435 0.03272694 0.9863719 0.1570618 0.1529761 0.975669 0.1626425 0.1580774 0.9739399 0.1417371 0.2709444 0.9521029 0.1563225 0.2903869 0.9440545 0.1270047 0.5339007 0.8359544 0.142321 0.553555 0.8205617 0.1309778 0.6037279 0.7863571 0.1297821 0.6032533 0.7869195 0.1274243 0.541652 0.8308889 0.13151 0.5423686 0.829784 0.1188951 0.4450729 0.8875665 0.1296817 0.4480082 0.8845741 0.1044096 0.3840098 0.9174067 0.1214932 0.3916516 0.9120573 0.077035 0.4427828 0.8933135 0.09454667 0.4535071 0.8862237 0.09443801 0.5159135 0.8514193 0.07536631 0.5069888 0.8586515 0.1018384 0.5220319 0.8468245 0.09411269 0.5146998 0.8521896 0.1694601 -0.704928 0.6887378 0.1695857 -0.7048396 0.6887974 0.1764801 -0.6553328 0.7344343 0.1676312 -0.6611778 0.7312617 0.1909393 -0.610407 0.7687298 0.175899 -0.6208244 0.7639612 0.2024672 -0.5573378 0.8052215 0.1899261 -0.5665416 0.8018471 0.2182021 -0.4947324 0.8412062 0.2042205 -0.5049301 0.8386536 0.2325081 -0.4206283 0.8769332 0.222125 -0.4283277 0.8758972 0.2446358 -0.3294774 0.91192 0.2375137 -0.3348551 0.911844 0.2551442 -0.2188415 0.941812 0.2470483 -0.2248595 0.9425526 0.2615215 -0.09300911 0.9607059 0.2556166 -0.09740006 0.9618594 0.2664784 0.0361734 0.9631619 0.2636488 0.03403037 0.9640184 0.2614448 0.1474364 0.9538916 0.2696546 0.154749 0.9504416 0.2547361 0.2622253 0.930778 0.2664322 0.2778083 0.92295 0.2383646 0.5224093 0.8187008 0.2514053 0.5419116 0.8019521 0.2250683 0.5972537 0.7698261 0.2339894 0.6007093 0.7644588 0.2211799 0.5359214 0.8147809 0.2290583 0.5371013 0.8118218 0.2145066 0.4388713 0.8725703 0.2251418 0.4415366 0.8685372 0.2042129 0.374927 0.9042826 0.215547 0.3797993 0.8996067 0.1677211 0.420116 0.8918364 0.204277 0.4411261 0.8738871 0.1728836 0.5097669 0.8427627 0.1931357 0.5165756 0.8341751 0.1831449 0.5244579 0.8315059 0.190301 0.5277443 0.8278113 0.2313569 -0.6912204 0.6846082 0.2207577 -0.6989919 0.6802031 0.2472578 -0.6412621 0.7263929 0.2313838 -0.6524561 0.7216389 0.2647022 -0.5977581 0.7567152 0.2478823 -0.609758 0.7528278 0.28292 -0.544144 0.7898505 0.2661648 -0.5566151 0.786979 0.3057756 -0.4790379 0.8228148 0.2854679 -0.4940015 0.8212617 0.3266541 -0.4031705 0.8548396 0.3083835 -0.4171093 0.8549383 0.3374947 -0.3127218 0.8878641 0.3227813 -0.3246718 0.8890448 0.3523862 -0.2034015 0.9134833 0.333796 -0.2182167 0.9170398 0.361177 -0.08450293 0.9286606 0.3502945 -0.09309542 0.9320017 0.3635721 0.0377804 0.9307997 0.3597118 0.03477638 0.9324152 0.3603004 0.1464701 0.9212656 0.365002 0.1508221 0.9187091 0.3509333 0.2542712 0.9012171 0.3631691 0.2709979 0.8914418 0.329015 0.5114672 0.7938203 0.3415554 0.5318199 0.7749243 0.3071469 0.5881206 0.7481811 0.320886 0.5934143 0.7381678 0.3036078 0.5283738 0.7928704 0.3126001 0.5295273 0.7885951 0.2939139 0.4299114 0.8536925 0.3094241 0.4336473 0.8462901 0.286089 0.3687902 0.8843907 0.2963157 0.3735705 0.8790006 0.2725732 0.4172995 0.8669286 0.2830914 0.4266148 0.8589873 0.2532469 0.4905565 0.8337988 0.2717249 0.5032681 0.8202968 0.2516282 0.5209816 0.8156357 0.2615589 0.5265715 0.808894 0.2965042 -0.6782444 0.6723615 0.2919073 -0.681711 0.6708654 0.3111953 -0.6276924 0.7135543 0.2941828 -0.6394402 0.7103328 0.3374577 -0.5800266 0.7414119 0.3124466 -0.5963605 0.7394129 0.3586104 -0.5279025 0.7698817 0.3396893 -0.5413573 0.7691188 0.3794232 -0.4630206 0.8010305 0.3605825 -0.4767175 0.8016986 0.3979666 -0.385067 0.8326742 0.3777073 -0.4002227 0.8349605 0.4151431 -0.2982984 0.8594617 0.4011301 -0.3090515 0.8623118 0.432092 -0.1952373 0.8804426 0.422938 -0.2020927 0.8833357 0.4435434 -0.08220052 0.8924754 0.4415155 -0.08370512 0.8933407 0.4512054 0.03522038 0.8917249 0.4531664 0.03667521 0.8906712 0.4480575 0.1404415 0.8829047 0.4595445 0.1508793 0.8752453 0.4336532 0.2394052 0.8686944 0.4514722 0.2644985 0.8521816 0.4067353 0.4963863 0.7669205 0.4211269 0.5213851 0.7421657 0.3797427 0.5771012 0.7230145 0.3970884 0.5834142 0.7084833 0.3764767 0.5201669 0.7666106 0.3834244 0.5208062 0.7627232 0.3714634 0.4222234 0.8268873 0.3808581 0.4242509 0.8215584 0.3571102 0.3572154 0.8630582 0.374175 0.3644316 0.8527501 0.3383225 0.4030737 0.8503351 0.354471 0.4164471 0.8372108 0.3313674 0.4811023 0.8116258 0.3397333 0.4876824 0.8042059 0.322871 0.5170077 0.7927532 0.3308859 0.5210917 0.7867515 0.3535786 -0.6583073 0.6645402 0.3383668 -0.6703218 0.6604367 0.3765738 -0.6092199 0.6978849 0.3573364 -0.6240667 0.6948752 0.3977521 -0.5635002 0.7240587 0.3782226 -0.5783855 0.7227849 0.4227119 -0.5072961 0.7509762 0.3996822 -0.525516 0.7510573 0.4480324 -0.4440178 0.7759608 0.4256041 -0.4612044 0.7785575 0.473116 -0.3653188 0.8016879 0.4518457 -0.3820383 0.8061529 0.4965388 -0.2769463 0.8226482 0.4764512 -0.2941575 0.8285323 0.5154589 -0.1769194 0.838452 0.4969317 -0.1931052 0.8460315 0.5259298 -0.07062828 0.8475904 0.5139889 -0.08095103 0.8539686 0.5297842 0.03907996 0.8472316 0.5239819 0.03420817 0.8510422 0.5196721 0.1349298 0.8436438 0.5284512 0.143382 0.8367682 0.4995223 0.2217177 0.8374478 0.5188552 0.250262 0.8174096 0.4638286 0.4699028 0.7510356 0.485202 0.5100622 0.7102223 0.428722 0.562258 0.7071517 0.4573693 0.5730099 0.6800537 0.4322267 0.5155858 0.739832 0.423129 0.5148182 0.7456033 0.4336222 0.42128 0.796552 0.4199792 0.4185656 0.8052455 0.4290731 0.3489516 0.8331442 0.435625 0.3519126 0.8284856 0.4110226 0.3865022 0.825637 0.4251783 0.4011355 0.8113654 0.3980821 0.4731514 0.7859125 0.4070615 0.482009 0.7758662 0.3861227 0.5141705 0.7658577 0.3930104 0.5187498 0.7592375 0.4130128 -0.6404131 0.6475273 0.4052838 -0.6461882 0.646673 0.4301328 -0.5962415 0.6778509 0.4165193 -0.6057115 0.6779567 0.4604868 -0.5423896 0.7026845 0.4335888 -0.5609454 0.7052242 0.4833447 -0.4893574 0.7258839 0.4624141 -0.5049906 0.7288056 0.508616 -0.4220412 0.7504606 0.4841926 -0.4410491 0.7556675 0.5328808 -0.3475186 0.7715368 0.5123149 -0.3634888 0.7780806 0.5562114 -0.2611917 0.7889283 0.5410131 -0.2734091 0.7953317 0.5736008 -0.1642075 0.8025074 0.5615737 -0.1744758 0.8088221 0.5839423 -0.05817741 0.8097078 0.572653 -0.06855982 0.816926 0.587501 0.04700976 0.8078569 0.579237 0.03940701 0.8142062 0.5787329 0.1335015 0.8045158 0.5831714 0.138171 0.8005124 0.5519466 0.1943859 0.8109063 0.5768169 0.2342548 0.7825645 0.4925875 0.3849132 0.7805122 0.5426103 0.4872501 0.6842233 0.4419171 0.5335097 0.7211635 0.5068545 0.556699 0.6581677 0.4654787 0.5177741 0.7178019 0.4297198 0.5158535 0.7411047 0.4608907 0.4373989 0.77218 0.3662847 0.4264335 0.827037 0.4752201 0.361354 0.8022402 0.4365346 0.3483812 0.8294987 0.4637807 0.3739889 0.8031437 0.4746952 0.3850734 0.7914436 0.4460067 0.4610559 0.7671412 0.4611268 0.4753269 0.749284 0.433168 0.512439 0.7414659 0.4424533 0.5195963 0.7309274 0.4528445 -0.6267771 0.6340997 0.4462291 -0.6327926 0.6328138 0.480284 -0.5745392 0.6627458 0.456616 -0.5931636 0.6630678 0.5043703 -0.5261127 0.6847015 0.4841658 -0.5407662 0.687863 0.5362355 -0.4676977 0.7026453 0.5087946 -0.4878909 0.7092888 0.5625487 -0.4042657 0.7211853 0.5414818 -0.4199572 0.7283087 0.5935159 -0.326713 0.7355254 0.5691533 -0.3456339 0.7460575 0.6097178 -0.2477058 0.7529184 0.596753 -0.2580942 0.7597851 0.623171 -0.1565185 0.7662635 0.6161072 -0.1619506 0.7708334 0.6359855 -0.05127221 0.7699959 0.6318851 -0.05464494 0.7731334 0.6401057 0.04972493 0.7666761 0.6388818 0.04861181 0.7677676 0.6326528 0.1322008 0.7630684 0.6377184 0.1380211 0.7578031 0.6122129 0.177639 0.7704802 0.6307504 0.2125052 0.7463213 0.5695998 0.3266418 0.754229 0.6030213 0.4339163 0.6693893 0.5654522 0.5228443 0.6378854 0.5776869 0.5290874 0.6215661 0.5577276 0.5053777 0.6584327 0.5512943 0.5054328 0.6637864 0.4770963 0.4495348 0.7551805 0.3696023 0.4461069 0.8150968 0.5084549 0.3845953 0.7704286 0.3990936 0.3678125 0.8399038 0.5072897 0.3731001 0.7768228 0.5078011 0.3734491 0.7763208 0.4695571 0.441372 0.7646614 0.5011243 0.4629683 0.7311189 0.461238 0.508143 0.7273584 0.4799124 0.519842 0.7067167 0.5088732 -0.596637 0.620542 0.4794107 -0.6185427 0.6225516 0.5318455 -0.5610466 0.6343241 0.5214761 -0.5679001 0.6368297 0.555239 -0.5135179 0.654224 0.5435667 -0.5218371 0.6574356 0.5884123 -0.452653 0.6699823 0.5725635 -0.4639571 0.6759548 0.6119067 -0.3930278 0.6863669 0.601319 -0.4016152 0.6907393 0.6415087 -0.314373 0.6997401 0.6286481 -0.3245736 0.7067204 0.663405 -0.2327849 0.7111294 0.6519569 -0.2431462 0.7182146 0.6787297 -0.145829 0.7197638 0.6704449 -0.1534757 0.7259125 0.6895561 -0.04869949 0.7225931 0.6888484 -0.0493105 0.7232264 0.6930086 0.04767334 0.7193514 0.6974472 0.05189126 0.714755 0.6876085 0.1309831 0.7141695 0.6933053 0.1384311 0.7072232 0.6819173 0.1946451 0.7050547 0.6845678 0.2014554 0.7005589 0.6625562 0.4268659 0.6154713 0.661336 0.4054414 0.6310722 0.6222115 0.51023 0.5937325 0.6310506 0.5264849 0.5697271 0.5828662 0.4842464 0.6525124 0.6306927 0.4930346 0.599286 0.5783096 0.4275832 0.6947883 0.6050282 0.4281903 0.671263 0.5894116 0.3704106 0.7179067 0.5965524 0.3720595 0.7111238 0.5851463 0.3687024 0.722262 0.5888106 0.3728848 0.7171186 0.5583207 0.4422147 0.7019432 0.5616902 0.446828 0.6963109 0.5366542 0.5168701 0.6669691 0.5376159 0.5183584 0.6650366 -0.7025822 0.5530211 0.4478237 -0.6889773 0.5632278 0.4561632 -0.7158583 0.5289695 0.4557831 -0.7134589 0.5316364 0.456442 -0.7562635 0.4031384 0.5153107 -0.7664528 0.387538 0.5122151 -0.7763554 0.3379661 0.5320256 -0.7730226 0.3417966 0.534426 -0.8100642 0.3118976 0.4965037 -0.7752913 0.3409724 0.5316589 -0.8655163 0.307424 0.395439 -0.76121 0.3778107 0.527085 -0.8537125 0.3483736 0.3870542 -0.7587817 0.413208 0.5034973 -0.8072913 0.4169316 0.4176708 -0.7675582 0.4470754 0.4593235 -0.8062779 0.4224513 0.4140664 -0.8000951 0.4311602 0.4170715 -0.8405947 0.2263041 0.492125 -0.8487438 0.1986297 0.4900818 -0.8547599 0.09778487 0.5097289 -0.8471378 0.116068 0.5185421 -0.8586137 0.05171382 0.5100081 -0.8570556 0.05513888 0.512265 -0.8578793 -0.02381259 0.5132994 -0.8565833 -0.02067601 0.5155946 -0.8479552 -0.1047262 0.5196196 -0.8475594 -0.1035135 0.5205075 -0.8356102 -0.181217 0.518571 -0.8343402 -0.1761479 0.522349 -0.814141 -0.2657771 0.5162723 -0.8123898 -0.2560848 0.5238736 -0.7928666 -0.3302958 0.5121204 -0.7923516 -0.3213497 0.5185686 -0.7627778 -0.4018202 0.5066662 -0.76269 -0.3885699 0.5170276 -0.7404922 -0.452521 0.4968863 -0.7424315 -0.4368217 0.5079196 -0.7062447 -0.5081726 0.4929292 -0.7087091 -0.496025 0.5016879 -0.7389529 0.5457844 0.3950545 -0.7174733 0.5644001 0.4082701 -0.7467555 0.5391225 0.389491 -0.7364389 0.5500696 0.3938038 -0.7658849 0.4810446 0.4266339 -0.7840818 0.4555557 0.4215266 -0.8030397 0.3559389 0.4779485 -0.8052059 0.3528204 0.4766145 -0.8330172 0.2903646 0.4709255 -0.8167706 0.3107976 0.4860976 -0.8796808 0.268911 0.3922356 -0.8179066 0.3248624 0.4748613 -0.8897466 0.2994899 0.344466 -0.8077641 0.3678265 0.4606744 -0.8483989 0.3769596 0.3716459 -0.787778 0.4216157 0.4490503 -0.8436139 0.3989556 0.3593746 -0.81891 0.4271075 0.3833611 -0.85747 0.3370731 0.3887507 -0.872749 0.3001757 0.3849724 -0.8864044 0.1064763 0.4504997 -0.8840227 0.1150957 0.4530531 -0.8913938 0.04947072 0.4505217 -0.8880664 0.05839169 0.455992 -0.8896586 -0.02118647 0.4561347 -0.889196 -0.01982945 0.4570965 -0.8819591 -0.09555613 0.4615379 -0.8826288 -0.09825551 0.4596871 -0.867998 -0.1809279 0.4624334 -0.8672294 -0.1766811 0.4655074 -0.8441521 -0.2670408 0.4648618 -0.8435534 -0.2607044 0.4695221 -0.8231651 -0.3341367 0.4590774 -0.8230165 -0.3226045 0.4675149 -0.7896171 -0.4065909 0.4595527 -0.7904888 -0.3971173 0.4662888 -0.7629859 -0.4639582 0.4501059 -0.7656869 -0.4477615 0.4617718 -0.7299244 -0.5201686 0.4434355 -0.7339573 -0.5059472 0.4531272 -0.7698249 0.5361312 0.3463136 -0.7428439 0.5724418 0.3471217 -0.7789323 0.5339316 0.3289097 -0.7595892 0.5566993 0.3363183 -0.7891803 0.5178011 0.3302674 -0.7839378 0.5244879 0.3321958 -0.8184497 0.4287315 0.3825302 -0.8316463 0.4071123 0.3776561 -0.8539027 0.2930802 0.430063 -0.8542824 0.2923834 0.4297834 -0.879154 0.2468345 0.4076288 -0.8590492 0.2731539 0.432922 -0.9016735 0.2618233 0.3441419 -0.8494294 0.3188256 0.4204998 -0.9034528 0.3165552 0.2890778 -0.8365651 0.3814253 0.3932858 -0.8858418 0.3668467 0.2840914 -0.8611471 0.3965643 0.3180604 -0.8760156 0.3894349 0.2844948 -0.8784875 0.3850339 0.282858 -0.9105324 0.2032678 0.3600183 -0.922749 0.1557639 0.3525223 -0.9216502 0.04735374 0.3851217 -0.9186064 0.05816423 0.3908701 -0.9207637 -0.01276916 0.3899118 -0.9209872 -0.01356738 0.3893568 -0.9140828 -0.08847653 0.3957582 -0.9145689 -0.09107285 0.3940427 -0.8974826 -0.1797999 0.4027368 -0.8973929 -0.1790586 0.4032669 -0.8760973 -0.2620452 0.4047049 -0.8759828 -0.2590331 0.4068859 -0.8515701 -0.3383102 0.4004682 -0.8517926 -0.3281192 0.4083961 -0.8212435 -0.4069826 0.3999053 -0.822698 -0.3979944 0.4059168 -0.7875725 -0.4722921 0.3958156 -0.7908864 -0.458884 0.4048758 -0.7525002 -0.5285 0.3929774 -0.7568331 -0.5166781 0.4003089 -0.7705283 0.5862292 0.2502431 -0.7365814 0.6385974 0.2228033 -0.7953646 0.5457407 0.2637468 -0.7785478 0.5706176 0.2612643 -0.8119091 0.5206006 0.2641569 -0.7989337 0.5386393 0.2675309 -0.8328527 0.4758333 0.2827352 -0.8319088 0.4773609 0.2829388 -0.8747351 0.3382661 0.3470082 -0.8844671 0.3170846 0.3423087 -0.9018313 0.2395098 0.3596323 -0.8953769 0.2513334 0.367603 -0.9278659 0.2175511 0.3028805 -0.8952384 0.2642558 0.3587719 -0.9420967 0.2522139 0.2210028 -0.8811094 0.3281778 0.3405078 -0.9260709 0.3112637 0.2133255 -0.8812265 0.368883 0.2955759 -0.9069638 0.3653427 0.2096221 -0.8877835 0.395802 0.2349069 -0.9102523 0.3377196 0.2395544 -0.9355005 0.2740142 0.2230587 -0.9455523 0.08673554 0.3137003 -0.949701 0.06747019 0.305804 -0.9471063 -0.003989875 0.3208953 -0.9468398 -0.002837955 0.321693 -0.9405049 -0.08341258 0.3293828 -0.9412368 -0.08831536 0.3259965 -0.9257214 -0.1753712 0.3350892 -0.9258467 -0.1773296 0.3337097 -0.9061222 -0.2545677 0.3378429 -0.9061326 -0.2541535 0.3381267 -0.8780774 -0.3361222 0.3405906 -0.8784897 -0.3317642 0.3437852 -0.8502651 -0.4026718 0.3389763 -0.8513326 -0.3970358 0.3429218 -0.8127586 -0.4751071 0.3371898 -0.8149099 -0.4675787 0.3424792 -0.7806941 -0.5253672 0.3383877 -0.7817659 -0.5227308 0.3399921 -0.6717664 0.7388526 0.05316781 -0.6508704 0.7579262 0.04376769 -0.7485077 0.6517002 0.1225693 -0.7534567 0.6456349 0.1243325 -0.8111647 0.5554898 0.1828743 -0.8101237 0.5569949 0.1829107 -0.8426699 0.4980555 0.2045685 -0.8366322 0.5078852 0.2051815 -0.8806852 0.4021399 0.250354 -0.8920655 0.3775506 0.248344 -0.9141755 0.2731909 0.2994159 -0.9204077 0.2579379 0.2937988 -0.9365621 0.1975697 0.2895129 -0.9262644 0.2175032 0.3077771 -0.9513297 0.2132166 0.2225099 -0.916798 0.2658298 0.2980201 -0.9470586 0.2667933 0.1786099 -0.9081959 0.3234696 0.2656084 -0.9401825 0.3087931 0.1438878 -0.9081243 0.3649647 0.2052103 -0.9197635 0.3646069 0.1452481 -0.9209534 0.3621007 0.1439723 -0.9579954 0.188329 0.2162804 -0.9713835 0.1285344 0.1997327 -0.9688571 0.001760244 0.2476144 -0.9682695 0.005672097 0.2498443 -0.9632126 -0.07346278 0.2585049 -0.9637944 -0.0794894 0.2545228 -0.9494215 -0.1638951 0.2678381 -0.9495359 -0.1687203 0.2644148 -0.9291417 -0.2501354 0.2722649 -0.929227 -0.248749 0.273242 -0.9022697 -0.3296265 0.2779493 -0.9022469 -0.3297829 0.277838 -0.8735184 -0.4000679 0.2773292 -0.8747034 -0.394965 0.2808855 -0.8345863 -0.4737372 0.2811384 -0.8356801 -0.4704657 0.2833741 -0.8037046 -0.5248929 0.2802613 -0.8058798 -0.5197938 0.2835001 -0.6547982 0.7557835 0.005553841 -0.6422346 0.766487 0.005703389 -0.6943298 0.7192711 0.02356278 -0.7022277 0.7115591 0.02366805 -0.7584438 0.6476516 0.07287299 -0.7827086 0.6180742 0.0731554 -0.8209207 0.5588577 0.1173341 -0.8287597 0.547254 0.1169204 -0.8763307 0.4532444 0.1631385 -0.8849867 0.4364523 0.1621972 -0.9215232 0.3256222 0.2115783 -0.9312847 0.2999513 0.2067319 -0.9550229 0.1891512 0.2283703 -0.9499474 0.2041628 0.236469 -0.9734475 0.1576676 0.1659548 -0.9500206 0.2138313 0.2274581 -0.9779645 0.1915758 0.0829721 -0.9417381 0.2711428 0.1990256 -0.9621842 0.2594941 0.08285111 -0.9384975 0.3097738 0.1525211 -0.9403094 0.3303658 0.0817117 -0.9232452 0.3664819 0.115366 -0.9526745 0.2828869 0.1112943 -0.9684011 0.2315861 0.09256023 -0.9838514 0.03134888 0.1762208 -0.985414 0.01621901 0.1693998 -0.9804623 -0.06707638 0.1849179 -0.9804982 -0.06779372 0.1844651 -0.9694877 -0.1507385 0.1933171 -0.9693912 -0.1557517 0.1897953 -0.9496765 -0.2373689 0.2043784 -0.9489701 -0.2441576 0.199607 -0.9244303 -0.3171404 0.2117795 -0.9234162 -0.3225159 0.2080529 -0.8922777 -0.3967671 0.2154449 -0.8927648 -0.3949906 0.216688 -0.8576241 -0.4641849 0.2213897 -0.8565941 -0.4669573 0.2195396 -0.820965 -0.5269345 0.2199015 -0.8237468 -0.5207986 0.2240762 -0.6548863 0.7557274 -4.07801e-4 -0.6534155 0.7569997 -4.45942e-5 -0.6901621 0.7236518 0.002103865 -0.6882475 0.7254711 0.002663552 -0.7298677 0.6834454 0.01398485 -0.7397176 0.6728132 0.01184511 -0.7838321 0.6197025 0.03970217 -0.7975642 0.6020501 0.03777873 -0.8502323 0.5204339 0.07907998 -0.864378 0.4968302 0.07752692 -0.9162548 0.3778463 0.1330764 -0.9286633 0.3474706 0.1298029 -0.9640231 0.2035388 0.1709723 -0.9642781 0.2025966 0.1706531 -0.9829187 0.1176818 0.1414982 -0.9719899 0.1578475 0.174126 -0.9923135 0.114902 0.04595142 -0.9666523 0.204019 0.1547886 -0.9835177 0.1806402 -0.007896006 -0.9585834 0.2636049 0.1078436 -0.9595622 0.2814528 0.004976332 -0.9422687 0.3285518 0.06467854 -0.9483838 0.3166912 0.01658034 -0.9528297 0.3034142 0.007450282 -0.9879081 0.1296566 0.08501118 -0.9959791 0.06566697 0.06094002 -0.9919391 -0.05671447 0.1133149 -0.9919584 -0.05932295 0.1118008 -0.9823982 -0.1394109 0.1243327 -0.9820683 -0.145022 0.1204603 -0.9660006 -0.2206298 0.1347782 -0.9646326 -0.2305679 0.1277588 -0.9408112 -0.3079895 0.1414816 -0.9400367 -0.3114433 0.1390482 -0.9087789 -0.3894132 0.1499278 -0.9079756 -0.391934 0.1482169 -0.8763513 -0.4564006 0.1539712 -0.8761028 -0.4570117 0.1535723 -0.835799 -0.5253745 0.1594411 -0.836631 -0.5237182 0.1605238 -0.6541824 0.7563368 -1.25501e-4 -0.6548896 0.7557245 -3.37902e-4 -0.6927022 0.7212235 -6.61112e-4 -0.6900357 0.7237753 3.9214e-4 -0.7309317 0.6824507 -2.4573e-4 -0.7283664 0.6851873 7.86421e-4 -0.7688831 0.6393432 0.007691562 -0.7757697 0.6309923 0.005496203 -0.8232463 0.5668688 0.03041881 -0.8399958 0.5419549 0.02630662 -0.8973459 0.4362154 0.06698256 -0.9151189 0.398473 0.06145489 -0.9606444 0.2580037 0.10294 -0.9690253 0.227809 0.09535759 -0.9877373 0.1108232 0.10997 -0.9861214 0.1196816 0.115069 -0.9954015 0.07275241 0.0623154 -0.9865337 0.1207033 0.1103727 -0.9911947 0.1323391 0.004422843 -0.9771423 0.1954451 0.08363151 -0.9723432 0.2309561 -0.03475791 -0.9567902 0.2879865 0.0402047 -0.9553912 0.2901163 -0.05531942 -0.9478268 0.317005 -0.03364992 -0.9757118 0.2184453 -0.0163781 -0.985226 0.1678644 -0.03393173 -0.9985645 -0.03457009 0.04091268 -0.9983429 -0.04499304 0.03587573 -0.9905748 -0.1266703 0.05211836 -0.9900363 -0.1322036 0.04848128 -0.976123 -0.2083828 0.06132251 -0.9749984 -0.2148236 0.05682337 -0.9517936 -0.2977041 0.07390218 -0.9500946 -0.304143 0.06940835 -0.9231073 -0.3754391 0.08317846 -0.9203028 -0.3833965 0.07778233 -0.8888049 -0.4498103 0.08773022 -0.8880352 -0.4515587 0.08653497 -0.8523936 -0.5137674 0.09730601 -0.8487439 -0.5205583 0.09302204 -0.6539915 0.756502 -1.46883e-4 -0.6541819 0.7563373 -2.04609e-4 -0.6951788 0.7188364 -8.93587e-4 -0.69271 0.7212163 1.15882e-4 -0.7318217 0.6814958 -7.37849e-4 -0.7309294 0.6824531 -3.1858e-4 -0.7662708 0.6425131 0.002436578 -0.7684054 0.6399614 0.001535594 -0.8127588 0.5825381 0.008535683 -0.8199033 0.5724731 0.005762279 -0.8827703 0.4693001 0.0217719 -0.8934292 0.4488631 0.01749765 -0.9571078 0.2866364 0.04224038 -0.9610156 0.2736957 0.03923904 -0.9930002 0.105683 0.05274152 -0.9917546 0.1149628 0.05662477 -0.9985613 0.04400521 0.03064316 -0.9959519 0.07221621 0.05352222 -0.9960435 0.08653753 -0.02022117 -0.9899246 0.1367278 0.03681176 -0.9812691 0.1675074 -0.09514379 -0.9713127 0.2377978 0.001992523 -0.9629598 0.2380826 -0.1265914 -0.9544948 0.2887384 -0.07463043 -0.955533 0.2724056 -0.1129254 -0.960752 0.2468033 -0.1266642 -0.9981459 0.04221934 -0.04384499 -0.9979917 -0.007802724 -0.06286358 -0.9930671 -0.115401 -0.02237117 -0.9926289 -0.1187226 -0.02434891 -0.9801377 -0.1981074 -0.009138643 -0.9787801 -0.2044703 -0.01347309 -0.9594063 -0.2820135 0.002842545 -0.9564853 -0.2917549 -0.003870725 -0.9323951 -0.3612581 0.01148992 -0.9294399 -0.3689199 0.006311953 -0.8970288 -0.4414831 0.02079081 -0.8947349 -0.4462523 0.01756012 -0.8660314 -0.4991038 0.029751 -0.8608622 -0.5082714 0.02401328 -0.6534233 0.7569928 3.1482e-5 -0.6539909 0.7565023 -1.39466e-4 -0.695931 0.7181087 1.16649e-4 -0.695181 0.7188346 4.26086e-4 -0.7315042 0.681837 2.91237e-4 -0.7318271 0.6814903 1.22039e-4 -0.7653378 0.6436278 0.001115918 -0.7662456 0.6425475 7.08923e-4 -0.8127016 0.5826791 0.001106858 -0.8125273 0.582922 0.00118488 -0.8844069 0.4667155 -0.001067101 -0.8821904 0.470893 1.60351e-4 -0.9579582 0.2869026 -0.001790702 -0.9568386 0.290619 -6.75581e-4 -0.9955719 0.09384721 -0.005432426 -0.9942493 0.1070907 2.26606e-5 -0.9994378 0.006217002 -0.03294819 -0.9991052 0.04184955 -0.006130695 -0.9952102 0.02021354 -0.0956462 -0.9959928 0.08586668 -0.02500635 -0.981415 0.0942375 -0.1671645 -0.982944 0.1742669 -0.05875557 -0.9674855 0.1891985 -0.1678562 -0.965175 0.240952 -0.1018799 -0.9520107 0.2473691 -0.1802341 -0.9479737 0.2769687 -0.1569531 -0.9831614 0.1207657 -0.1371473 -0.9854877 0.07831269 -0.1506027 -0.9893256 -0.110637 -0.09483903 -0.9898315 -0.1074329 -0.09322971 -0.9791151 -0.1854715 -0.08327037 -0.9773157 -0.1926616 -0.08795279 -0.9609565 -0.2667549 -0.07351505 -0.958505 -0.2740533 -0.07850468 -0.9354861 -0.3480291 -0.061167 -0.9322062 -0.3557887 -0.06637889 -0.901909 -0.429166 -0.04875266 -0.8975675 -0.4375273 -0.05424487 -0.8691005 -0.4927291 -0.04338645 -0.867407 -0.4955434 -0.04518711 -0.6523973 0.7578771 1.53977e-4 -0.6534228 0.7569931 -1.60934e-4 -0.6951584 0.7188562 7.61889e-4 -0.6959309 0.7181087 4.48697e-4 -0.7299613 0.6834874 0.001196801 -0.7315039 0.6818372 3.57953e-4 -0.7625356 0.6469446 0.00148648 -0.7653554 0.6436079 1.53339e-4 -0.8169665 0.5766755 -0.00335443 -0.8128439 0.58248 -0.001360118 -0.8971112 0.4411886 -0.02332818 -0.8850311 0.4653101 -0.01437479 -0.9610523 0.2727044 -0.04484277 -0.9578091 0.2845898 -0.04012948 -0.9945361 0.08221387 -0.06433355 -0.9940443 0.09076625 -0.06031233 -0.9960831 -0.01786053 -0.08659917 -0.9975608 0.004525423 -0.06965714 -0.9918507 -0.01892739 -0.1259924 -0.9963328 0.02140319 -0.0828433 -0.9815574 0.04184913 -0.1865313 -0.988876 0.1052324 -0.1051214 -0.9659045 0.1378817 -0.2191283 -0.970984 0.1947159 -0.1388381 -0.9483171 0.2036617 -0.2433445 -0.9485661 0.2466106 -0.1985084 -0.9567946 0.1794572 -0.228778 -0.9585804 0.1544913 -0.2392826 -0.9824908 -0.07855838 -0.1689389 -0.9800483 -0.09449625 -0.1748593 -0.9712746 -0.1784106 -0.1574654 -0.9707701 -0.1802098 -0.1585239 -0.9563247 -0.2525264 -0.1472191 -0.9536872 -0.2595903 -0.1519659 -0.9344995 -0.3296339 -0.1343594 -0.9284968 -0.3426448 -0.1431371 -0.9039452 -0.4097684 -0.1223646 -0.896974 -0.4223033 -0.1307579 -0.8689346 -0.4821829 -0.1115906 -0.8631373 -0.4910644 -0.1176861 -0.6509014 0.7591623 8.7017e-5 -0.6523959 0.7578783 -4.20981e-4 -0.6914411 0.7224318 0.001247465 -0.6951636 0.7188516 -2.43389e-4 -0.7250351 0.688705 0.003083288 -0.7299691 0.6834801 4.60361e-4 -0.7577072 0.65259 0.002462089 -0.7626281 0.6468372 2.11719e-5 -0.8364427 0.5477411 -0.01852905 -0.8179105 0.5752826 -0.008509933 -0.917814 0.3927709 -0.05786693 -0.8991155 0.435887 -0.03992319 -0.9652125 0.2457076 -0.08940237 -0.9611747 0.2637096 -0.0812425 -0.9905919 0.05895096 -0.1235015 -0.9905359 0.07263195 -0.1164614 -0.9880526 -0.04198038 -0.1482902 -0.9908617 -0.02157276 -0.133146 -0.9815241 -0.05677342 -0.1827218 -0.9890847 -0.02049326 -0.1459165 -0.9666362 -0.02924507 -0.2544785 -0.9849026 0.04504007 -0.1671476 -0.9443445 0.05440336 -0.3244282 -0.9687721 0.1407623 -0.2041242 -0.9353821 0.1526373 -0.3190019 -0.9463253 0.2027936 -0.2516812 -0.9295675 0.1924048 -0.3144594 -0.9298049 0.1975046 -0.3105714 -0.9642173 0.02569866 -0.2638646 -0.9581416 -0.03588378 -0.284037 -0.9571381 -0.1724449 -0.2327006 -0.9575507 -0.1710899 -0.232002 -0.9448065 -0.2396697 -0.2233814 -0.9427202 -0.2447165 -0.2266992 -0.9257713 -0.3139142 -0.2107262 -0.9195833 -0.3261691 -0.2190441 -0.8968848 -0.395407 -0.1981183 -0.8915526 -0.4043381 -0.2040706 -0.8660605 -0.465488 -0.1823739 -0.8564864 -0.4793384 -0.1914831 -0.6513613 0.7587676 5.51717e-4 -0.6508959 0.7591668 7.00811e-4 -0.6884468 0.7252843 0.001959979 -0.691448 0.7224257 8.47877e-4 -0.7172701 0.6967799 0.004636824 -0.725129 0.6886126 9.22269e-4 -0.7560615 0.6545006 -2.52353e-4 -0.7583593 0.6518356 -0.00132507 -0.880548 0.4711472 -0.05153399 -0.8391526 0.5432791 -0.02589935 -0.9387772 0.3313827 -0.09424877 -0.9198661 0.3856414 -0.07160496 -0.9731189 0.1844735 -0.1378739 -0.9649323 0.2362686 -0.1143807 -0.9834839 0.0212363 -0.1797453 -0.9851656 0.04874777 -0.1645373 -0.9772918 -0.06314712 -0.2022705 -0.9807052 -0.04678529 -0.1898124 -0.9710984 -0.08080303 -0.2245857 -0.9777162 -0.05819177 -0.2017049 -0.9631756 -0.06253498 -0.2614999 -0.9757834 -0.02544867 -0.217254 -0.9511799 0.01610189 -0.3082169 -0.9689614 0.07011991 -0.2370591 -0.9357972 0.1154858 -0.3330866 -0.9498069 0.1625884 -0.2672673 -0.9193772 0.1519994 -0.3628247 -0.9250593 0.1921073 -0.3276587 -0.9361933 0.06763714 -0.3449167 -0.9357416 0.05776906 -0.347923 -0.9375505 -0.1719229 -0.3023933 -0.9409668 -0.1605322 -0.2980118 -0.9262357 -0.2331129 -0.2962192 -0.9263421 -0.2328751 -0.2960735 -0.9106452 -0.3013973 -0.2826394 -0.9049426 -0.3117961 -0.28959 -0.8856432 -0.3779959 -0.2697319 -0.8778671 -0.3899264 -0.2780411 -0.8555292 -0.449253 -0.2573744 -0.8466963 -0.4611635 -0.2653934 -0.6524915 0.7577958 5.88195e-4 -0.6513579 0.7587701 9.31428e-4 -0.6855351 0.7280378 0.001608729 -0.6884899 0.7252457 5.96962e-4 -0.7050489 0.7091434 0.004676222 -0.7178639 0.6961835 -2.65873e-4 -0.7388744 0.6738416 0.001481354 -0.7583353 0.6518363 -0.006094455 -0.8770972 0.4780822 -0.04623723 -0.8786125 0.4752014 -0.04715687 -0.9623753 0.2438285 -0.1199226 -0.9369299 0.3398128 -0.08179134 -0.9788892 0.04839706 -0.1985793 -0.9731337 0.1851975 -0.1367947 -0.9718275 -0.0325765 -0.2334312 -0.9781836 0.01233237 -0.2073759 -0.9637873 -0.08682763 -0.2521411 -0.9685059 -0.069377 -0.2391301 -0.9620955 -0.09023493 -0.2573519 -0.9640969 -0.08405441 -0.2518973 -0.9665161 -0.05626916 -0.2503609 -0.9646556 -0.06221914 -0.2560632 -0.9639607 0.005707323 -0.265984 -0.9686557 0.02491796 -0.2471547 -0.9470292 0.08144766 -0.3106478 -0.9594705 0.133755 -0.2480443 -0.9252467 0.07408159 -0.3720627 -0.9421553 0.1600823 -0.2944777 -0.9163095 0.00825119 -0.4003859 -0.9250482 0.07658356 -0.3720495 -0.9137424 -0.1600353 -0.3734484 -0.9169623 -0.1482105 -0.3704238 -0.8995661 -0.2367649 -0.3670468 -0.9041429 -0.2270251 -0.3619191 -0.8882256 -0.2911013 -0.3554089 -0.8831605 -0.2998064 -0.3607546 -0.867619 -0.3595795 -0.3434238 -0.8597707 -0.3708928 -0.3510454 -0.8407309 -0.4310238 -0.3277044 -0.8305704 -0.4437714 -0.3364818 -0.6450097 0.7641678 0.00318402 -0.6524854 0.7578009 8.52156e-4 -0.6745609 0.7382096 0.003774225 -0.6856817 0.7279015 -4.27268e-4 -0.6903538 0.7234634 0.00351423 -0.7071129 0.7070912 -0.003683269 -0.729112 0.6843488 -0.007906436 -0.7507873 0.6603057 -0.01774543 -0.8531866 0.5185006 -0.05683064 -0.900083 0.4267276 -0.08805721 -0.9761175 0.1417365 -0.1646378 -0.9644227 0.227162 -0.1352273 -0.9766333 -0.01072734 -0.2146446 -0.9809544 0.06481319 -0.183106 -0.9704285 -0.05797106 -0.2343246 -0.9757328 -0.02581 -0.2174389 -0.9642772 -0.09915554 -0.2456374 -0.9679683 -0.08437341 -0.2364709 -0.9666554 -0.08469539 -0.2416695 -0.9652342 -0.08976864 -0.2454883 -0.9741546 -0.03168541 -0.2236494 -0.9684044 -0.05676758 -0.2428383 -0.9723163 -0.002417385 -0.2336559 -0.9741768 0.01034975 -0.2255495 -0.9559966 0.01937425 -0.2927376 -0.9701706 0.1048645 -0.2185693 -0.9290798 -0.02151548 -0.3692533 -0.9610571 0.113751 -0.2518533 -0.8960257 -0.1000592 -0.4325808 -0.9340515 0.01137304 -0.3569571 -0.8835316 -0.1557464 -0.4417183 -0.8906515 -0.1359246 -0.4338946 -0.869719 -0.2352325 -0.433883 -0.8736822 -0.2271715 -0.4302006 -0.8613363 -0.2789083 -0.4246293 -0.8564271 -0.2867456 -0.429313 -0.8433108 -0.3453176 -0.4118042 -0.8365167 -0.3544006 -0.4178999 -0.8223072 -0.4084037 -0.3962543 -0.8091526 -0.4237734 -0.4070484 -0.6287891 0.7775601 0.004971861 -0.6453371 0.7638974 8.88177e-4 -0.6627023 0.7488761 0.003211498 -0.676528 0.7364168 -3.51738e-4 -0.7090072 0.7051599 -0.007648348 -0.6967485 0.7173047 -0.003941357 -0.8097501 0.5852452 -0.0423426 -0.738167 0.6744294 -0.01595854 -0.9603803 0.2484775 -0.1262091 -0.8561258 0.5132125 -0.06051141 -0.9844229 0.02647376 -0.1738124 -0.9761012 0.1647074 -0.1417677 -0.9825652 -0.01834225 -0.1850116 -0.984392 0.01300132 -0.1755089 -0.9801889 -0.05398964 -0.1905643 -0.9817348 -0.04085242 -0.185817 -0.9767721 -0.09520095 -0.191972 -0.9775627 -0.09073889 -0.1900996 -0.9785916 -0.0838871 -0.18794 -0.9772337 -0.0900644 -0.1921006 -0.9793468 -0.04868662 -0.1962385 -0.9810722 -0.04259747 -0.1888989 -0.9716891 -0.0373004 -0.2333003 -0.9807039 -0.003728926 -0.195464 -0.9347382 -0.07391303 -0.3475651 -0.9752367 0.04802286 -0.2158868 -0.8954331 -0.1117165 -0.4309512 -0.9586615 0.03603446 -0.2822583 -0.8594012 -0.162375 -0.484834 -0.9047858 -0.090707 -0.4160952 -0.8474225 -0.179557 -0.4996345 -0.8607391 -0.1593884 -0.4834495 -0.8401213 -0.216296 -0.4974057 -0.8369742 -0.2218105 -0.5002745 -0.8289439 -0.2713986 -0.4890757 -0.8267303 -0.2746161 -0.4910224 -0.8166624 -0.3281292 -0.4747566 -0.8063549 -0.3408358 -0.4833453 -0.7960181 -0.3901307 -0.462767 -0.7829771 -0.4042609 -0.4727792 -0.6184667 0.7858079 0.002205848 -0.6291847 0.7772559 4.36144e-4 -0.6476617 0.7619253 0.002050101 -0.6641868 0.7475667 2.9845e-4 -0.7469149 0.6648762 -0.007597029 -0.7040091 0.7101873 -0.00234127 -0.8936368 0.4476674 -0.03173613 -0.7822286 0.6228812 -0.01172351 -0.9898985 0.1257768 -0.06543064 -0.9437063 0.3280573 -0.04239112 -0.9966714 0.002386808 -0.08148854 -0.9958856 0.05654227 -0.07081782 -0.9949488 -0.02923542 -0.09603369 -0.9966757 0.003281652 -0.08140665 -0.9872173 -0.08526128 -0.1346575 -0.995168 -0.02405166 -0.09519594 -0.9774427 -0.1217582 -0.1725711 -0.988893 -0.07147532 -0.1303148 -0.9781271 -0.09975689 -0.1825264 -0.9855834 -0.07546007 -0.1514301 -0.9713237 -0.08064597 -0.2236661 -0.9878073 -0.04670989 -0.1485094 -0.9642654 -0.05979096 -0.2581033 -0.9821782 -0.03416031 -0.1848218 -0.9086708 -0.1191596 -0.4001481 -0.9671627 -0.0462743 -0.2499105 -0.8440248 -0.1814563 -0.504674 -0.9298018 -0.06781274 -0.3617597 -0.8070107 -0.2147317 -0.5501127 -0.8542792 -0.1670691 -0.4922348 -0.8090931 -0.2075723 -0.549802 -0.8239064 -0.1935473 -0.5326517 -0.8022881 -0.2203581 -0.5547757 -0.8036796 -0.2187212 -0.5534077 -0.7911356 -0.2663819 -0.5505862 -0.7901529 -0.2676774 -0.5513687 -0.7826064 -0.3101552 -0.5397509 -0.772728 -0.3217774 -0.5471297 -0.7654044 -0.37403 -0.5236961 -0.7525095 -0.3872036 -0.5327316 -0.6163069 0.7875062 2.62748e-4 -0.6185109 0.7857764 -1.76336e-4 -0.6431896 0.765707 1.89349e-4 -0.6481068 0.7615495 -1.05885e-4 -0.7901644 0.6128807 -0.004201471 -0.7441489 0.6680109 -0.002010464 -0.9471599 0.3204882 -0.0132513 -0.8862364 0.4631674 -0.007804155 -0.9952029 0.09576481 -0.02000683 -0.9898445 0.1411187 -0.01713365 -0.9996598 0.01183634 -0.02324235 -0.9996287 0.01536893 -0.02249991 -0.9991592 -0.02179682 -0.03472602 -0.9996667 -0.005189001 -0.02529269 -0.9888638 -0.1076709 -0.1027399 -0.9991628 -0.02169662 -0.03468364 -0.9423627 -0.2284414 -0.2444733 -0.9971713 -0.04579544 -0.05960083 -0.9135481 -0.2335083 -0.3330222 -0.9959527 -0.04809552 -0.0759291 -0.8756254 -0.2089176 -0.4354694 -0.9920212 -0.04929661 -0.1160335 -0.8885285 -0.131507 -0.4395713 -0.9646978 -0.0595054 -0.2565492 -0.8497125 -0.1461237 -0.5065932 -0.8938155 -0.123238 -0.4311685 -0.8044284 -0.2045488 -0.5577228 -0.8192512 -0.194857 -0.5393126 -0.7699983 -0.2377983 -0.5920765 -0.7863635 -0.2268459 -0.5746073 -0.7682451 -0.2315582 -0.5968085 -0.7874947 -0.2191144 -0.5760565 -0.7620143 -0.2352812 -0.6033051 -0.769481 -0.2299291 -0.5958454 -0.7552994 -0.2602735 -0.6014821 -0.7521882 -0.2635311 -0.6039574 -0.7457044 -0.3022467 -0.5937777 -0.7406554 -0.3075622 -0.5973569 -0.7350972 -0.3554139 -0.5773328 -0.7199151 -0.3699365 -0.5872558 -0.6167371 0.7871612 -0.003550887 -0.6163061 0.7875 -0.003277003 -0.6455854 0.7636748 -0.004503965 -0.643284 0.7656166 -0.004131436 -0.821173 0.5706125 -0.008745908 -0.7901911 0.6128261 -0.006510853 -0.975002 0.2217124 -0.01466059 -0.9472788 0.320251 -0.01010924 -0.997008 0.07574748 -0.01541227 -0.9954252 0.09458005 -0.01354116 -0.9996321 0.02478587 -0.01101332 -0.9998112 0.01308655 -0.01436769 -0.9990606 -0.03165811 -0.02959215 -0.9998196 -0.01025998 -0.01599115 -0.9539669 -0.2347103 -0.1867039 -0.9988238 -0.03633886 -0.03210031 -0.8728692 -0.3570582 -0.3325791 -0.9961189 -0.0640074 -0.06041753 -0.8277207 -0.3640271 -0.4270396 -0.9911004 -0.08696067 -0.1007863 -0.8267105 -0.2983127 -0.4770318 -0.9784395 -0.1053662 -0.1776354 -0.7752322 -0.2663831 -0.572761 -0.9615837 -0.07441616 -0.2642331 -0.7364217 -0.2303909 -0.6360843 -0.8741742 -0.1387254 -0.4653761 -0.7272552 -0.2251301 -0.6483952 -0.747324 -0.2144461 -0.6289036 -0.696357 -0.2624697 -0.6679795 -0.7016528 -0.2600553 -0.6633662 -0.7019889 -0.2562477 -0.6644914 -0.7098655 -0.252959 -0.6573452 -0.7205703 -0.2444688 -0.6488556 -0.7219887 -0.2438849 -0.647497 -0.7177352 -0.253016 -0.6487212 -0.7111276 -0.2573048 -0.6542873 -0.7064162 -0.2953907 -0.6432111 -0.7015514 -0.2997354 -0.6465171 -0.7004528 -0.3341781 -0.6306274 -0.6814539 -0.3509181 -0.6422438 -0.6178272 0.785654 -0.03220629 -0.6164361 0.7869725 -0.02609199 -0.6352183 0.7713328 -0.03928744 -0.6435015 0.7635251 -0.05417716 -0.759821 0.6475434 -0.05796331 -0.808865 0.5806212 -0.09282481 -0.9685115 0.2380806 -0.07282292 -0.9669159 0.2452067 -0.07033789 -0.9935294 0.09107172 -0.06786328 -0.9931048 0.1000888 -0.06103581 -0.9977394 0.02796423 -0.06110626 -0.9977656 0.03501754 -0.0568996 -0.9598952 -0.2155709 -0.1792497 -0.9962764 -0.05460631 -0.06672024 -0.8095256 -0.4623302 -0.3618276 -0.9524804 -0.2381548 -0.1899042 -0.7901499 -0.4561851 -0.4093388 -0.9140654 -0.303067 -0.2695084 -0.8141123 -0.3948103 -0.4258474 -0.9150535 -0.2794507 -0.2908343 -0.8220984 -0.3350495 -0.4603217 -0.9431518 -0.2045712 -0.2619452 -0.5544221 -0.4341516 -0.7100201 -0.991959 -0.03598821 -0.1213355 -0.6773449 -0.3011068 -0.6712217 -0.8586301 -0.1723024 -0.4827695 -0.6922252 -0.2545391 -0.6753031 -0.7325254 -0.2242995 -0.6427257 -0.6754031 -0.2728345 -0.685122 -0.6879265 -0.2639222 -0.6760934 -0.6803936 -0.2619771 -0.6844214 -0.6842262 -0.2603279 -0.6812224 -0.6867489 -0.2511596 -0.6821252 -0.6956793 -0.2484497 -0.6740201 -0.680087 -0.2563803 -0.6868412 -0.6856817 -0.253692 -0.6822617 -0.6708876 -0.2939611 -0.680806 -0.6728193 -0.2922663 -0.6796284 -0.667648 -0.3231117 -0.6707049 -0.6578574 -0.3312344 -0.676393 0.5615943 -0.619541 0.548435 0.6007388 -0.5967159 0.532018 0.5727078 -0.5943737 0.564558 0.6132975 -0.5703563 0.5464063 0.6178823 -0.5355955 0.5756378 0.6558333 -0.5081617 0.5582603 0.6512982 -0.4787256 0.5887552 0.6787924 -0.459246 0.5730045 0.6905424 -0.4056349 0.5988419 0.7135771 -0.385782 0.5847907 0.7237247 -0.3276419 0.6073496 0.7378977 -0.3146976 0.5970532 0.7552844 -0.238731 0.6103713 0.7662889 -0.2277255 0.600785 0.7815514 -0.136934 0.6086269 0.7863622 -0.1306145 0.6037999 0.7972699 -0.03347915 0.6026937 0.7932485 -0.04008102 0.6075773 0.8010491 0.0604552 0.5955381 0.7964955 0.05097091 0.6024923 0.8039435 0.1766347 0.567869 0.7941199 0.1437461 0.5905173 0.7771208 0.4170767 0.4713072 0.7818464 0.310921 0.5404115 0.741912 0.4757032 0.4725179 0.7396354 0.4942507 0.4567884 0.7448588 0.4294651 0.510632 0.7535613 0.4612604 0.4683848 0.7577413 0.3536756 0.5483992 0.7797455 0.3959664 0.4849824 0.7308816 0.3015161 0.612291 0.7631132 0.3479463 0.5446023 0.7048876 0.2988508 0.6432898 0.7145903 0.3267629 0.618536 0.6775791 0.3955289 0.620035 0.6746868 0.3735232 0.6366147 0.6507146 0.4980081 0.5732003 0.6484836 0.4706044 0.5983316 0.6233505 0.5481143 0.5576781 0.6243833 0.5533132 0.5513529 0.5854766 -0.6386507 0.4993421 0.6185909 -0.6197347 0.482985 0.5991546 -0.6131834 0.5148009 0.6417689 -0.5865367 0.4940725 0.6445974 -0.5536172 0.5272591 0.6866524 -0.5227707 0.5051923 0.6864042 -0.4916616 0.5358342 0.7101536 -0.4735069 0.5210309 0.7321107 -0.4141622 0.5408176 0.7536613 -0.3945749 0.5256478 0.7689341 -0.3338353 0.5452472 0.7802326 -0.3217474 0.5363913 0.8007179 -0.2435667 0.5472899 0.8071724 -0.2359564 0.5411075 0.8285029 -0.1367721 0.5430251 0.8324091 -0.1311817 0.5384111 0.8449538 -0.02777928 0.5341174 0.8437644 -0.0299862 0.5358754 0.8524271 0.08736723 0.5154951 0.8450714 0.06581521 0.5305871 0.8479228 0.2918573 0.4425452 0.8405767 0.1877446 0.5081171 0.7970447 0.458065 0.3935686 0.8025494 0.4271577 0.4164743 0.7898237 0.4241067 0.4430713 0.7915788 0.4676656 0.393309 0.7694109 0.3838915 0.5105236 0.7975802 0.4124723 0.4401505 0.7740104 0.3058486 0.5544049 0.7998903 0.3408823 0.493938 0.7688302 0.2685914 0.5803093 0.7808406 0.2938997 0.5512813 0.7576434 0.3183122 0.5697841 0.7557137 0.3076736 0.5781297 0.72998 0.4557757 0.509311 0.7310261 0.409873 0.5455318 0.69799 0.5248895 0.4871355 0.69818 0.5237278 0.4881128 0.6732609 0.5362903 0.5090309 0.6687111 0.5725419 0.4743642 0.6088809 -0.6563448 0.445506 0.6342968 -0.641023 0.4321541 0.63459 -0.6239993 0.4559829 0.6605983 -0.6058645 0.443326 0.6833077 -0.5637116 0.4640258 0.7061848 -0.5455961 0.4512515 0.7251027 -0.5004189 0.4730826 0.7434522 -0.4843408 0.4611864 0.7705528 -0.4211818 0.4783871 0.7832594 -0.4087342 0.4684453 0.8153434 -0.3303355 0.4754931 0.8172362 -0.3280879 0.4737969 0.8500999 -0.2349559 0.4713025 0.8472177 -0.2391209 0.4743875 0.8753905 -0.1281828 0.4661124 0.8729122 -0.132555 0.4695249 0.8914665 -0.0143572 0.4528591 0.886743 -0.0251255 0.4615796 0.9016258 0.1405203 0.4090538 0.8911861 0.09418398 0.4437533 0.8632503 0.3873773 0.3236322 0.8722363 0.3034129 0.3835942 0.8357515 0.4278118 0.3442335 0.8278909 0.4621114 0.3178836 0.8485449 0.3652615 0.3828257 0.845655 0.4113554 0.3400799 0.8372326 0.3006592 0.4567775 0.8566754 0.353073 0.3760941 0.8260523 0.2448209 0.5076421 0.8427721 0.2901084 0.4534011 0.8204484 0.2735687 0.5020206 0.8188775 0.2651463 0.509055 0.7988374 0.3958295 0.4529657 0.8018496 0.3357216 0.4942959 0.7612233 0.4968982 0.4166911 0.7663434 0.4718567 0.4359692 0.736288 0.5232058 0.4291105 0.7269849 0.5572 0.4012745 0.7143238 0.552654 0.4293195 0.7032105 0.5904921 0.3959974 0.6271919 -0.6738218 0.3906337 0.6448497 -0.6624804 0.3811678 0.6728492 -0.6257485 0.3946045 0.6838287 -0.6173269 0.3889549 0.7177644 -0.5699198 0.400007 0.7320783 -0.557748 0.3911248 0.7642088 -0.5020273 0.4049118 0.7737554 -0.4926983 0.3981847 0.8102918 -0.421754 0.4068794 0.8143914 -0.4172261 0.4033474 0.8540039 -0.3282208 0.4036689 0.8551841 -0.3266824 0.4024161 0.8903801 -0.2242166 0.3961694 0.8865786 -0.2305472 0.4010314 0.9165609 -0.1105951 0.3842979 0.9102944 -0.1244099 0.3948246 0.9334235 0.02023148 0.3582055 0.9242256 -0.0107544 0.3816956 0.9293759 0.2240287 0.2933795 0.9255232 0.147013 0.3489901 0.8771836 0.4079648 0.2532067 0.880418 0.3918751 0.2670177 0.8762227 0.385655 0.2889705 0.8702327 0.4223676 0.2535763 0.8960415 0.2831014 0.3419991 0.8948799 0.3501273 0.2767689 0.8856819 0.2111111 0.4135212 0.8980063 0.2785863 0.3405501 0.8727158 0.2104443 0.4405455 0.8779553 0.2361417 0.4164511 0.8592295 0.3150599 0.4030658 0.8575136 0.2769904 0.4335286 0.8181676 0.4544686 0.352222 0.8246421 0.4214833 0.3772495 0.7875517 0.514544 0.3391269 0.7841793 0.5249197 0.3309413 0.7397128 0.6096547 0.2848615 0.7476873 0.5923782 0.3000864 0.6106076 0.7835298 0.1150634 0.677973 0.7045928 0.2095271 0.6495329 -0.6849422 0.3300927 0.6579728 -0.6791697 0.3252698 0.7044218 -0.627924 0.33091 0.716428 -0.618009 0.3237218 0.7473247 -0.5740565 0.3346118 0.7574436 -0.5647757 0.3275784 0.7998412 -0.4992782 0.3331297 0.8035953 -0.4952694 0.3300651 0.8478121 -0.4158226 0.3290994 0.8464718 -0.4175276 0.3303883 0.8897589 -0.3219532 0.3235356 0.8872046 -0.3258209 0.3266633 0.9271593 -0.2099208 0.310337 0.9215774 -0.2208914 0.3192212 0.9547011 -0.08194804 0.2860604 0.9458563 -0.1076178 0.306226 0.968422 0.09138464 0.2319648 0.9591414 0.02494871 0.2818254 0.9349773 0.312999 0.1668803 0.9467981 0.232201 0.2228363 0.907585 0.3724414 0.1938478 0.8994798 0.4053168 0.1632621 0.9101498 0.3171713 0.2665142 0.9080334 0.3713986 0.1937487 0.9208908 0.2123423 0.3269115 0.9260656 0.27449 0.2589556 0.9180492 0.1667417 0.3596983 0.9232305 0.2034875 0.3259422 0.9093902 0.2312305 0.3457483 0.9085588 0.2116525 0.3601726 0.8748662 0.3894879 0.2879381 0.8846459 0.3260282 0.3333274 0.8211917 0.5204838 0.2339679 0.8343772 0.4850528 0.2617988 0.740409 0.6568568 0.142597 0.786927 0.5814241 0.2066203 0.6368941 0.7690621 0.05394083 0.6850328 0.7214803 0.1009772 0.571763 0.8201969 0.01908701 0.5606233 0.8280099 0.01006859 0.678689 -0.6852181 0.2643055 0.6762818 -0.6870672 0.265672 0.7289304 -0.6311384 0.2651885 0.7378922 -0.6231782 0.2591606 0.7778089 -0.5705163 0.2636752 0.7791105 -0.5691893 0.2626984 0.8275307 -0.4967138 0.2616645 0.8285865 -0.4954643 0.2606908 0.8782529 -0.4057303 0.2530907 0.8737432 -0.412226 0.2581526 0.9220979 -0.3040925 0.2392976 0.9138017 -0.3191932 0.2511619 0.9581055 -0.1851706 0.2185081 0.9487513 -0.2087059 0.2373032 0.983448 -0.03077721 0.1785581 0.9730449 -0.07941675 0.2165101 0.9759314 0.1934459 0.1006805 0.9800299 0.09495085 0.1747162 0.937704 0.3379057 0.08081483 0.9432787 0.3180643 0.095187 0.9420378 0.3072029 0.1348757 0.9270045 0.3658249 0.08267289 0.9526518 0.2195578 0.2103544 0.9455464 0.2973833 0.1323074 0.9535829 0.138258 0.2675155 0.9570646 0.2022129 0.2076951 0.9479074 0.1503409 0.2808367 0.9489803 0.1650561 0.2686875 0.9272232 0.2884838 0.2388185 0.9316781 0.2392864 0.2733461 0.8589805 0.4871242 0.1576786 0.8873276 0.4085193 0.21392 0.7612188 0.6444938 0.07192903 0.8157761 0.5627152 0.1336455 0.6741469 0.7383195 0.02025771 0.71473 0.6975365 0.0510286 0.6194017 0.7850543 0.005609393 0.6192317 0.785189 0.005518615 0.5772652 0.8165506 0.003217995 0.5674916 0.8233785 -0.00112617 0.7050879 -0.6814594 0.1961231 0.7015128 -0.6845166 0.198285 0.749572 -0.6320823 0.1965039 0.7533233 -0.6284635 0.1937465 0.804666 -0.5623665 0.1904118 0.8012899 -0.5661966 0.193277 0.8547992 -0.4857279 0.1827208 0.8490103 -0.4935374 0.1886859 0.902463 -0.3945065 0.1729891 0.8971431 -0.4033765 0.1800603 0.9448324 -0.2870696 0.1577424 0.9380431 -0.3020306 0.169861 0.9785925 -0.1570303 0.1330344 0.9706043 -0.184084 0.1550495 0.9958823 0.02539414 0.08702749 0.9910805 -0.02912932 0.1300422 0.9633489 0.267334 0.02216953 0.9776869 0.1945117 0.07933312 0.9446966 0.3267613 0.02784454 0.9409614 0.3380421 0.01786589 0.9661825 0.2392043 0.09629613 0.9552378 0.2945808 0.02726155 0.975996 0.1368539 0.1694196 0.9733417 0.2091898 0.09405189 0.9741511 0.09474521 0.2050685 0.9762114 0.1353946 0.1693506 0.9666496 0.1630619 0.1974828 0.9667773 0.1532196 0.2046105 0.9192008 0.3705777 0.1331995 0.9371795 0.2983196 0.1808323 0.8143624 0.5782106 0.04986423 0.8592295 0.5009449 0.1038212 0.7269535 0.6865956 0.01118689 0.754088 0.6560101 0.0316556 0.6683813 0.7438176 0.001336455 0.6715725 0.7409327 0.003060579 0.6200154 0.7845894 -7.7563e-4 0.6186773 0.7856442 -0.001321911 0.5787 0.8155404 4.8314e-4 0.5771242 0.8166564 -1.31267e-5 0.7242746 -0.677742 0.1268551 0.7212452 -0.6805759 0.1289257 0.7713782 -0.6246027 0.1218497 0.767025 -0.6292629 0.1253032 0.8241978 -0.5544942 0.1150405 0.8203685 -0.559358 0.1188033 0.8770015 -0.4693736 0.1027467 0.8683947 -0.4828291 0.1129902 0.9239525 -0.3726626 0.08622348 0.9141474 -0.3924493 0.1015785 0.9632976 -0.2603788 0.06527346 0.9545531 -0.2855759 0.08529335 0.9930809 -0.1135982 0.02976614 0.9857232 -0.1558319 0.06376773 0.9931491 0.1100375 -0.03932887 0.9992973 0.02773159 0.02521938 0.9526585 0.2966153 -0.06679326 0.9616299 0.2704022 -0.04637515 0.9611349 0.2750741 -0.02353972 0.9436644 0.3242007 -0.06626844 0.9882701 0.1444474 0.04957181 0.9739307 0.2245501 -0.03219324 0.9919009 0.06320387 0.1101716 0.9903677 0.1297759 0.04827004 0.989041 0.07062274 0.1296553 0.9894031 0.09338146 0.1111822 0.9731315 0.2044463 0.1059105 0.9773286 0.1684969 0.1282097 0.8893528 0.4546309 0.04860359 0.9213778 0.3776833 0.09175151 0.7847686 0.619704 0.01027095 0.8136538 0.5803269 0.0344702 0.7198919 0.694085 0.001329123 0.726559 0.6870821 0.005504667 0.6686072 0.7436158 -2.0045e-4 0.6683242 0.7438701 -3.41512e-4 0.6204037 0.7842825 -5.87104e-4 0.6200164 0.7845886 -7.54242e-4 0.5788623 0.8154253 -3.1438e-5 0.5786979 0.815542 -7.95183e-5 0.7376078 -0.6731225 0.05329972 0.7339832 -0.6768414 0.05616468 0.7879258 -0.6140847 0.04552918 0.7817119 -0.6215482 0.05103272 0.8410062 -0.5399615 0.03391605 0.832513 -0.5522989 0.04345381 0.8901962 -0.4550967 0.0209214 0.883704 -0.4670571 0.03041249 0.9355646 -0.3531323 0.004061281 0.9284681 -0.3709618 0.01828712 0.9723143 -0.232985 -0.01796734 0.9658453 -0.2591052 0.00272566 0.996205 -0.06674814 -0.05585861 0.9934681 -0.1123193 -0.02013915 0.9744129 0.1881203 -0.1230059 0.9918032 0.1110717 -0.06316381 0.9495314 0.2896749 -0.120327 0.9463212 0.297314 -0.1268098 0.9794778 0.1963339 -0.04556703 0.9559882 0.2671375 -0.1213436 0.9973544 0.07138419 0.01373416 0.9891543 0.1376181 -0.0513336 0.9986645 0.02229052 0.04660826 0.9981051 0.06010121 0.01319628 0.996794 0.05376619 0.05925464 0.9964729 0.06928932 0.04733735 0.9724902 0.2288774 0.04333585 0.9766479 0.2074921 0.0557326 0.8707259 0.4916546 0.01058864 0.8892058 0.4565485 0.02960693 0.7778788 0.6284134 0.001142561 0.7846602 0.6198957 0.006156802 0.719666 0.6943204 2.37793e-4 0.7198792 0.6940993 3.63223e-4 0.6695132 0.7428002 -7.01493e-5 0.6686069 0.7436159 -5.20809e-4 0.6211652 0.7836797 -2.45985e-4 0.6204025 0.7842834 -5.88908e-4 0.5793691 0.8150653 -9.17003e-5 0.5788611 0.8154261 -2.4771e-4 0.7488369 -0.6621685 -0.02786207 0.740225 -0.6720432 -0.02061212 0.7972128 -0.602469 -0.03850853 0.7899966 -0.6123282 -0.03097665 0.8500555 -0.5241025 -0.05217528 0.8424296 -0.5371609 -0.04207855 0.8974404 -0.4358254 -0.06824284 0.8898869 -0.452876 -0.05481523 0.9393411 -0.3318583 -0.08665204 0.9334079 -0.3518025 -0.07060247 0.9728071 -0.2022039 -0.1129608 0.9687106 -0.2314014 -0.08973944 0.9866415 -0.006447196 -0.162779 0.9908564 -0.06421548 -0.1186593 0.9510811 0.2309163 -0.2052377 0.9661893 0.1905686 -0.173672 0.9530569 0.2501848 -0.1705586 0.9353576 0.2885606 -0.204546 0.9894858 0.1002327 -0.1042657 0.966012 0.1835325 -0.1820347 0.9986181 0.002760887 -0.05248147 0.9920775 0.06465232 -0.1077144 0.9996158 -0.01299446 -0.02448689 0.9984719 0.0192359 -0.05180531 0.9994595 0.03185397 -0.008134603 0.9983751 0.05222576 -0.02279901 0.9753704 0.2205718 -9.37122e-4 0.9733068 0.2294412 -0.005558311 0.8719161 0.4896546 7.7301e-4 0.8706652 0.4918761 -3.86343e-4 0.7785799 0.6275447 0.001001298 0.7778723 0.6284223 4.90015e-4 0.7212617 0.6926618 0.001110672 0.7196685 0.6943178 1.65971e-4 0.6704482 0.7419564 3.02838e-5 0.6695145 0.7427989 -4.5044e-4 0.6224647 0.782648 -2.10992e-4 0.6211637 0.7836804 -8.18517e-4 0.5802803 0.814417 -1.00173e-4 0.5793703 0.8150646 -3.84641e-4 0.7520533 -0.6498968 -0.1097733 0.7456148 -0.6582694 -0.1036351 0.801051 -0.585572 -0.1241881 0.7915499 -0.600623 -0.1126977 0.8499708 -0.5083738 -0.1382231 0.8431416 -0.5224438 -0.1271408 0.8968269 -0.413603 -0.1569529 0.8900598 -0.4334757 -0.1410402 0.9354967 -0.3044914 -0.1792514 0.9303933 -0.3303242 -0.1589162 0.9638788 -0.1541044 -0.2172316 0.9626588 -0.1999386 -0.1825175 0.9560501 0.08317697 -0.281158 0.975085 -0.002782702 -0.2218144 0.9357946 0.2222771 -0.2736449 0.9311841 0.2318707 -0.2813045 0.96487 0.1759644 -0.1950961 0.9312219 0.2412852 -0.2731435 0.9885269 0.03438478 -0.14708 0.9744336 0.09277009 -0.2046294 0.99254 -0.03757983 -0.1159833 0.9887587 -1.47655e-5 -0.1495205 0.9947869 -0.04053926 -0.09357273 0.9932412 -0.01509225 -0.1150841 0.9972635 0.004202723 -0.07380974 0.9954151 0.02881348 -0.0912069 0.9827598 0.1791622 -0.04565411 0.9739346 0.2175334 -0.06427085 0.8943966 0.4472206 -0.0069651 0.8720854 0.4886682 -0.02589231 0.7853513 0.6190453 0.002499222 0.7785971 0.6275206 -0.002141296 0.7219598 0.6919345 8.66804e-4 0.7212651 0.692659 4.54806e-4 0.6715928 0.7409204 1.06102e-4 0.6704483 0.7419561 -4.91678e-4 0.6233556 0.7819385 -1.36299e-4 0.6224635 0.7826486 -5.61251e-4 0.5809165 0.8139632 -8.63202e-5 0.5802801 0.814417 -2.8671e-4 0.7467463 -0.6366565 -0.1924539 0.7411948 -0.6448585 -0.1865147 0.7979539 -0.5647006 -0.2106727 0.7880013 -0.5836451 -0.1959907 0.8446837 -0.4836855 -0.2292554 0.8358591 -0.5063887 -0.2119197 0.8865349 -0.3906445 -0.2478966 0.8813236 -0.4125704 -0.2303352 0.9207981 -0.286062 -0.2651404 0.9191492 -0.3032172 -0.2514441 0.9481081 -0.127432 -0.2912937 0.9500749 -0.151564 -0.2727384 0.929059 0.1339034 -0.344847 0.947146 0.08553653 -0.3091894 0.9290437 0.1892331 -0.317913 0.9105908 0.2228985 -0.3480529 0.9625486 0.1106181 -0.2475156 0.9337096 0.161903 -0.3193336 0.9772494 -0.0112214 -0.2117965 0.9671987 0.02688002 -0.2525951 0.9796805 -0.06712239 -0.1889991 0.9761291 -0.04084509 -0.2133162 0.9836748 -0.06928116 -0.1660843 0.9811866 -0.04380631 -0.1880263 0.989653 -0.03326404 -0.1395732 0.9866288 -8.48046e-4 -0.1629811 0.9876942 0.1198853 -0.1004384 0.9772595 0.1710669 -0.1253006 0.9291085 0.3676519 -0.0398705 0.8952902 0.4404109 -0.06703495 0.8039532 0.5946843 -0.003151774 0.785781 0.61837 -0.01291298 0.7214097 0.6925078 0.001035928 0.7219547 0.6919392 0.001321673 0.669761 0.7425766 4.59636e-4 0.6715931 0.7409189 0.001380383 0.6229259 0.7822808 -4.15057e-5 0.6233563 0.7819381 1.65739e-4 0.581196 0.8137637 -6.0959e-5 0.5809174 0.8139625 -1.51647e-4 0.7407898 -0.6114831 -0.2780628 0.7302451 -0.6292687 -0.2660134 0.7866793 -0.5413632 -0.2967517 0.7776846 -0.5628154 -0.2800814 0.830242 -0.4580738 -0.3175953 0.8238604 -0.4809654 -0.2998775 0.8670054 -0.3674234 -0.3366032 0.8635652 -0.3902512 -0.3193107 0.897278 -0.2666596 -0.3518308 0.8968978 -0.2839863 -0.3390075 0.9188659 -0.08451449 -0.3854126 0.9250038 -0.1218841 -0.3598784 0.9045892 0.1378799 -0.4033703 0.9043497 0.1383723 -0.4037384 0.9201417 0.145921 -0.3633821 0.897886 0.187315 -0.398389 0.9501229 0.02485948 -0.3108837 0.9206236 0.09341371 -0.3791122 0.959259 -0.06696587 -0.2744773 0.9482978 -0.01962012 -0.3167751 0.9623487 -0.09442299 -0.254891 0.9588536 -0.0717805 -0.2746772 0.9672636 -0.0956878 -0.2350424 0.9643778 -0.07322025 -0.2541938 0.9753109 -0.07014119 -0.2094015 0.9719195 -0.03930723 -0.2320079 0.985666 0.04562234 -0.1624232 0.9757559 0.1060605 -0.1914464 0.9628928 0.255453 -0.08707082 0.9293867 0.3502234 -0.1165503 0.8431829 0.5374414 -0.01411992 0.8058918 0.5914112 -0.02776944 0.720692 0.6932551 7.78007e-4 0.7214081 0.6925094 0.001081943 0.6662089 0.745765 6.1213e-4 0.6697568 0.7425771 0.002274036 0.6218401 0.7831444 2.23987e-5 0.6229254 0.7822812 5.42527e-4 0.5814135 0.8136084 2.84981e-6 0.5811956 0.8137639 -6.55473e-5 0.7256219 -0.5846586 -0.3628323 0.7176268 -0.6013863 -0.3512071 0.7681846 -0.5129285 -0.383141 0.7596199 -0.5392134 -0.3636299 0.8060922 -0.4336661 -0.4026778 0.8022045 -0.4566687 -0.3846058 0.8374532 -0.3512562 -0.4186781 0.8368697 -0.3661121 -0.4069534 0.865598 -0.2592277 -0.4284172 0.865774 -0.2617724 -0.42651 0.8940303 -0.08784276 -0.4393102 0.8915405 -0.07676851 -0.446388 0.9268503 0.05656349 -0.3711459 0.8849336 0.1361225 -0.4453797 0.9489644 0.09411454 -0.3010138 0.924508 0.1472505 -0.3515712 0.9619095 -0.0326575 -0.2714103 0.9481959 0.02394044 -0.3167828 0.9619793 -0.08562481 -0.2593535 0.959558 -0.06689578 -0.2734475 0.9604005 -0.0882126 -0.2642905 0.9611672 -0.09453487 -0.2592698 0.9593868 -0.09397256 -0.2659816 0.959656 -0.09618377 -0.2642141 0.9624769 -0.08396911 -0.2580453 0.9612781 -0.07337957 -0.2656311 0.9755915 -0.03683388 -0.2164824 0.9681603 0.02965992 -0.248568 0.9866773 0.09039449 -0.1352655 0.9598715 0.2236049 -0.1692563 0.8996033 0.4347219 -0.0416032 0.8492385 0.525707 -0.04925704 0.7206267 0.6933227 -9.54367e-4 0.7208015 0.6931409 -9.06421e-4 0.6601587 0.7511257 8.91044e-4 0.6661802 0.7457838 0.003268361 0.6193628 0.7851049 2.00296e-4 0.6218353 0.783147 0.001351356 0.5813817 0.813631 1.76801e-4 0.5814114 0.8136097 1.85742e-4 0.7022416 -0.5571314 -0.4432396 0.6951158 -0.5757607 -0.4304808 0.7406238 -0.4844338 -0.4656181 0.735296 -0.5109246 -0.4453042 0.7727608 -0.4070693 -0.4869657 0.7709435 -0.4326747 -0.4673743 0.7998649 -0.3318927 -0.5000636 0.8001672 -0.3484036 -0.4882086 0.8268224 -0.2617293 -0.497858 0.8258591 -0.2524106 -0.5042279 0.872685 -0.1601288 -0.4612805 0.8532421 -0.08606797 -0.5143641 0.947376 -0.0451166 -0.3169278 0.9033259 0.04298108 -0.4267963 0.9821172 -0.001421213 -0.1882653 0.964261 0.1056035 -0.2429994 0.9834903 -0.08212155 -0.1612545 0.9812201 -0.01529717 -0.1922844 0.9826621 -0.06248527 -0.1745595 0.9833977 -0.08310186 -0.1613165 0.9771344 -0.04554265 -0.2076883 0.9807349 -0.09004825 -0.1733504 0.9711424 -0.06371843 -0.2298313 0.9740313 -0.09523475 -0.2054101 0.9690155 -0.07528954 -0.2352456 0.9697171 -0.0837022 -0.2294403 0.9730869 -0.06243938 -0.221818 0.9714496 -0.03920006 -0.2339856 0.9812652 7.09072e-4 -0.1926611 0.9773943 0.05045288 -0.2053169 0.954528 0.276672 -0.1110368 0.911978 0.3962427 -0.1062441 0.7334315 0.6797162 -0.008014619 0.7215704 0.6922875 -0.008618414 0.649773 0.7601273 0.001271843 0.6600499 0.7512112 0.003984034 0.6147214 0.7887442 4.19834e-4 0.6193451 0.7851152 0.002416193 0.5804386 0.8143041 2.68382e-4 0.5813834 0.8136296 5.61187e-4 0.6741839 -0.5252677 -0.5192013 0.6673722 -0.5480427 -0.5042456 0.7079825 -0.4553137 -0.5398613 0.7049922 -0.4829196 -0.5193983 0.7343924 -0.3849155 -0.5590241 0.7356932 -0.4067562 -0.5415765 0.7567248 -0.318553 -0.5708692 0.7581149 -0.3283144 -0.5634461 0.7767207 -0.2578629 -0.5746406 0.7761334 -0.2545871 -0.5768902 0.8103823 -0.2122884 -0.5460898 0.7936414 -0.1890769 -0.5782588 0.9036502 -0.1429833 -0.4036979 0.8419337 -0.1410494 -0.5208194 0.9670452 -0.1168692 -0.2261973 0.9328663 -0.05444836 -0.3560839 0.976557 -0.1358315 -0.1669922 0.971579 -0.09142357 -0.2183489 0.9844617 -0.05643224 -0.1662842 0.9855536 -0.06259584 -0.1573721 0.9853902 -0.04699635 -0.1636998 0.9852346 -0.0462383 -0.1648481 0.984895 -0.07153463 -0.1576858 0.9839537 -0.06398057 -0.1665583 0.9842684 -0.08213031 -0.1564299 0.9841465 -0.07925498 -0.1586645 0.9856454 -0.05621689 -0.1591945 0.9858266 -0.06249701 -0.1556929 0.9886591 -0.01023668 -0.1498286 0.9875084 0.01374351 -0.1569663 0.9891006 0.09051495 -0.1161339 0.9553237 0.2710927 -0.1177521 0.8341332 0.5509318 -0.02638298 0.7389052 0.673489 -0.02077811 0.6398047 0.7685365 0.001258194 0.6495432 0.7603201 0.002690732 0.610139 0.7922943 4.27644e-4 0.6146684 0.7887825 0.002228617 0.5794399 0.815015 2.73585e-4 0.580437 0.814305 5.78613e-4 0.6394214 -0.4958708 -0.587582 0.6361636 -0.5155807 -0.573997 0.6679604 -0.4274395 -0.6091998 0.6686645 -0.4532079 -0.5894832 0.6911403 -0.3597393 -0.6268276 0.6938959 -0.3833639 -0.6095414 0.7090978 -0.3046215 -0.6359137 0.7109773 -0.3141661 -0.6291352 0.723294 -0.249311 -0.6439642 0.7243385 -0.252604 -0.6415021 0.7358016 -0.2367065 -0.634481 0.7319391 -0.2334117 -0.6401439 0.7572888 -0.2454546 -0.605199 0.7320187 -0.2398763 -0.6376584 0.8198233 -0.2404082 -0.5197054 0.7869171 -0.2149184 -0.5784215 0.8572547 -0.1658376 -0.4874551 0.8567619 -0.1653526 -0.488485 0.9127361 -0.09296381 -0.3978323 0.8915334 -0.07982927 -0.4458647 0.9502922 -0.1091196 -0.2916124 0.9164441 -0.08415466 -0.3912141 0.9708056 -0.1404286 -0.1944643 0.951428 -0.1057989 -0.289122 0.9858601 -0.1142074 -0.1226236 0.9842347 -0.08218401 -0.1566143 0.9943636 -0.0673809 -0.08185958 0.9945225 -0.04434853 -0.0946483 0.9978971 -0.02001887 -0.06164926 0.9975624 0.004215836 -0.06965267 0.9982203 0.03861767 -0.04544168 0.992338 0.1123058 -0.05150616 0.8857046 0.4640589 -0.01329714 0.8310858 0.5559501 -0.01469761 0.6332119 0.7739784 3.69508e-4 0.6397932 0.7685459 0.001377999 0.6087424 0.793368 7.36112e-5 0.6101354 0.792297 6.73318e-4 0.5796294 0.8148803 1.66997e-4 0.5794395 0.8150153 1.03569e-4 0.6089862 -0.4597934 -0.6463171 0.6052948 -0.4872519 -0.6294472 0.6287208 -0.4031521 -0.6649651 0.632291 -0.4262986 -0.6468984 0.6478233 -0.3472328 -0.6780518 0.6510581 -0.359258 -0.6686232 0.6659774 -0.2971842 -0.684219 0.6665862 -0.2992594 -0.68272 0.6814544 -0.2536821 -0.6864877 0.6768124 -0.2491707 -0.6927042 0.6950998 -0.2471574 -0.6750922 0.6852176 -0.2452077 -0.6858208 0.6854835 -0.2692509 -0.6764734 0.676365 -0.2663901 -0.6867071 0.6942706 -0.2567948 -0.6723428 0.6940534 -0.2565206 -0.6726716 0.7400286 -0.1864785 -0.646207 0.7293551 -0.1747984 -0.6614278 0.8207074 -0.1704006 -0.5453469 0.7670956 -0.1356403 -0.6270295 0.8676866 -0.2302866 -0.4405544 0.8134341 -0.1831902 -0.5520564 0.8842943 -0.2971838 -0.3601464 0.8610791 -0.2413851 -0.4475223 0.9194114 -0.2970839 -0.2577283 0.9261714 -0.2213269 -0.3053209 0.9781939 -0.1768124 -0.1089684 0.9873107 -0.09405624 -0.1279496 0.9966883 -0.07340478 -0.03498923 0.9988192 -0.01498514 -0.04621297 0.9997779 -0.01208186 -0.0172742 0.9987919 0.04378473 -0.02230995 0.8890344 0.4577995 -0.006132006 0.8852431 0.4650825 -0.006565034 0.6359934 0.7716935 -0.001271009 0.6332547 0.773941 -0.001939415 0.609179 0.7930323 -8.13341e-4 0.6087448 0.7933655 -0.001103222 0.5802861 0.8144127 -4.2431e-4 0.5796263 0.814882 -7.59931e-4 0.5715718 -0.4341729 -0.6962755 0.5718484 -0.4509899 -0.685272 0.5889795 -0.3781455 -0.7142193 0.5937622 -0.4017663 -0.6971588 0.6043674 -0.3394562 -0.7207701 0.6063298 -0.345547 -0.7162133 0.6185655 -0.2797861 -0.734232 0.6213937 -0.2873265 -0.7289125 0.6396738 -0.2592921 -0.7235918 0.62911 -0.251709 -0.7354341 0.6676339 -0.2556704 -0.6992121 0.6464402 -0.2518922 -0.7201843 0.6579763 -0.2764188 -0.7004712 0.6525653 -0.2746307 -0.7062129 0.6448793 -0.2456737 -0.7237231 0.6679845 -0.2598102 -0.6973489 0.7091354 -0.2021882 -0.6754606 0.6862129 -0.1965926 -0.7003308 0.8404374 -0.2235672 -0.4936424 0.6859381 -0.2201296 -0.6935646 0.8900461 -0.2725461 -0.3654268 0.7953559 -0.2690265 -0.5431702 0.8557332 -0.3573499 -0.3741949 0.8566077 -0.3156533 -0.4081499 0.8206562 -0.435329 -0.3701512 0.843329 -0.3746331 -0.3852874 0.829985 -0.4631539 -0.3108268 0.8669075 -0.3652976 -0.3391592 0.8875805 -0.4335358 -0.1557167 0.9543887 -0.1778861 -0.2397889 0.922387 -0.3822081 -0.05584985 0.9875797 -0.01878154 -0.1559932 0.9664997 0.2511733 -0.05282372 0.8778701 0.4683354 -0.100031 0.6626098 0.748663 -0.02126431 0.6348236 0.7714726 -0.04276829 0.6111286 0.7914472 -0.01154655 0.60907 0.7929571 -0.01590347 0.58063 0.8141238 -0.008452177 0.5802429 0.8143929 -0.00908184 0.5335356 -0.4128928 -0.7381459 0.5381977 -0.4269598 -0.7266696 0.5456917 -0.3616363 -0.7559363 0.5527577 -0.3764639 -0.7434608 0.5574759 -0.3207071 -0.7657465 0.5607938 -0.3319951 -0.7584785 0.571348 -0.265874 -0.7764488 0.5742971 -0.2710365 -0.7724779 0.5858491 -0.2598771 -0.7676228 0.579074 -0.2563324 -0.7739297 0.6053414 -0.2624702 -0.751446 0.5883709 -0.258769 -0.7660669 0.5769647 -0.2763934 -0.7685822 0.5794655 -0.2772442 -0.7663913 0.5779075 -0.2439868 -0.778777 0.5977677 -0.2477695 -0.7624199 0.6627681 -0.2213774 -0.7153534 0.5904207 -0.2301962 -0.7735717 0.7829119 -0.2928361 -0.5489043 0.4141705 -0.36389 -0.8342943 0.9003134 -0.2933362 -0.3215426 0.5526134 -0.4470481 -0.7033963 0.8575713 -0.3620187 -0.3653957 0.8500559 -0.3620307 -0.3825423 0.7972832 -0.442518 -0.4105087 0.7959931 -0.4487966 -0.406173 0.775871 -0.4741449 -0.416186 0.7724204 -0.4866724 -0.4080649 0.7952345 -0.4587233 -0.3964534 0.8126891 -0.3558484 -0.4614199 0.853223 -0.180812 -0.489201 0.8079764 0.05603134 -0.5865446 0.7068824 0.4177112 -0.5708193 0.6509316 0.4817723 -0.5866717 0.6268824 0.682084 -0.3765367 0.5784431 0.694485 -0.4278953 0.599757 0.7759134 -0.1955758 0.5966307 0.7752282 -0.2074925 0.5679811 0.8094053 -0.1492002 0.5764606 0.8092218 -0.1133726 -0.6354076 -0.5351808 0.5566318 -0.6197366 -0.5279793 0.5806586 -0.6559264 -0.4920257 0.5724259 -0.6546452 -0.4907574 0.5749756 -0.6747043 -0.4546152 0.5814629 -0.6694626 -0.4484723 0.592193 -0.7033974 -0.3925569 0.5925632 -0.6973447 -0.3852004 0.6044262 -0.7224228 -0.3396074 0.6023057 -0.7165049 -0.3326644 0.6131519 -0.7498666 -0.2664006 0.6055832 -0.7418991 -0.257361 0.6191535 -0.7645687 -0.1974353 0.6135586 -0.759379 -0.1918195 0.6217307 -0.7808861 -0.1167639 0.6136637 -0.776522 -0.1123957 0.6199846 -0.7901088 -0.0340234 0.6120217 -0.7860893 -0.02994501 0.6173872 -0.7873996 0.04666048 0.6146746 -0.787807 0.04625749 0.6141828 -0.7811952 0.1230582 0.6120383 -0.7873818 0.1169095 0.6052786 -0.7710499 0.1620432 0.6158118 -0.7810371 0.1444656 0.607545 -0.762866 0.2969306 0.5743412 -0.7670502 0.2844719 0.5750737 -0.7332905 0.4471159 0.5122232 -0.738388 0.4410282 0.5101739 -0.7314748 0.4315386 0.5279386 -0.7404046 0.4260547 0.519883 -0.6947549 0.4280284 0.5780202 -0.743769 0.4056789 0.5312555 -0.7014217 0.3759344 0.6055419 -0.7171134 0.3679041 0.5919417 -0.6949278 0.3512235 0.6274692 -0.7073969 0.3420303 0.6185507 -0.6725649 0.3838099 0.6327294 -0.6925803 0.3641532 0.6226757 -0.6578926 0.4562697 0.5991623 -0.6671181 0.4459322 0.5967395 0.4881703 -0.4182565 -0.765997 0.4795594 -0.4114615 -0.7750628 0.5050145 -0.3686398 -0.7804262 0.4974212 -0.3611435 -0.7887634 0.5306297 -0.3403263 -0.7762798 0.5150198 -0.3093077 -0.7994269 0.5393341 -0.2706934 -0.7973983 0.5224185 -0.2580011 -0.8127204 0.5209456 -0.2530529 -0.8152177 0.526058 -0.2544639 -0.811487 0.4549393 -0.2423629 -0.8569076 0.5314261 -0.2577244 -0.8069477 0.4166742 -0.2422557 -0.876182 0.4993955 -0.2655856 -0.8246627 0.444355 -0.2493485 -0.8604499 0.4186915 -0.2444627 -0.8746058 0.4702098 -0.2678276 -0.8409348 0.4473801 -0.2691982 -0.8528678 0.5049399 -0.4036473 -0.7629579 0.4131706 -0.4102692 -0.8130002 0.7128631 -0.4587647 -0.5304349 0.3983964 -0.5405271 -0.7410202 0.7784419 -0.4372137 -0.4504139 0.6998513 -0.4719485 -0.5361649 0.7506452 -0.4475985 -0.4859912 0.7629121 -0.4587492 -0.4555376 0.7524394 -0.2680754 -0.6016399 0.7516651 -0.4450101 -0.4867911 0.6104694 0.2955545 -0.7348297 0.7444603 -0.06488943 -0.6645061 0.4706993 0.5217474 -0.7114927 0.5479786 0.4197246 -0.7235682 0.4394811 0.5623313 -0.7004569 0.4588741 0.5425488 -0.703616 0.429615 0.5769485 -0.6946664 0.4391105 0.5701428 -0.6943481 0.3924549 0.5724558 -0.7199123 0.4275724 0.5729779 -0.6991983 0.3649203 0.5904564 -0.7198572 0.3831215 0.5568909 -0.7369468 0.545266 -0.6002076 0.5851802 0.5820412 -0.577216 0.5727562 0.5526422 -0.5751443 0.6031547 0.5869277 -0.5543452 0.5900996 0.5828991 -0.5237938 0.6211833 0.6091039 -0.5050147 0.6115167 0.6190491 -0.462401 0.6347941 0.6362746 -0.4508628 0.6260012 0.6534025 -0.3955208 0.6454678 0.6639685 -0.3868538 0.639914 0.6823115 -0.3190392 0.6577728 0.6929019 -0.3102431 0.6508734 0.7103761 -0.2318672 0.6645326 0.7162485 -0.226161 0.6601813 0.7317727 -0.1388406 0.6672571 0.7312142 -0.1395172 0.6677281 0.7450088 -0.04406261 0.6655978 0.7423183 -0.04741311 0.6683678 0.7480188 0.04760825 0.6619679 0.749445 0.04951488 0.6602125 0.7444995 0.1355718 0.6537131 0.7464935 0.1393671 0.6506339 0.7470977 0.2911955 0.5975368 0.7366458 0.2204993 0.6393225 0.6970174 0.4896194 0.5238699 0.7016579 0.4560572 0.5474377 0.6840786 0.4774143 0.5514636 0.6847046 0.5076354 0.522959 0.6810748 0.4258784 0.5956214 0.7058571 0.4579668 0.5404002 0.6721279 0.370486 0.6410806 0.7220516 0.3934557 0.5690643 0.6582731 0.3291941 0.6769845 0.6848759 0.3559112 0.635824 0.6390417 0.37001 0.674328 0.6389657 0.3697667 0.6745335 0.6099032 0.4653137 0.6414837 0.60504 0.4432221 0.6614235 0.58497 0.542151 0.6032268 0.5816351 0.5228357 0.6231722 -0.6727248 0.5570529 0.4869636 -0.6690014 0.5593617 0.4894402 -0.6863307 0.5052497 0.5231377 -0.7062045 0.4856824 0.5151579 -0.7296753 0.3660038 0.5775944 -0.7294003 0.3663184 0.5777422 -0.744603 0.3373655 0.5759782 -0.7375456 0.3431463 0.581616 -0.7679707 0.3427894 0.541033 -0.7354342 0.363052 0.5721275 -0.8210951 0.35604 0.4461373 -0.7192952 0.4134098 0.558307 -0.7925282 0.4031352 0.4575817 -0.7705025 0.4184149 0.4808897 -0.767695 0.4470788 0.4590916 -0.7618725 0.4529305 0.4630383 -0.7818134 0.3937627 0.4834449 -0.791297 0.3726633 0.4847385 -0.8121284 0.1514801 0.5634726 -0.8073769 0.1661255 0.5661668 -0.8200556 0.1092231 0.5617644 -0.8128393 0.1208391 0.5698159 -0.8227035 0.04909813 0.5663466 -0.82229 0.04976963 0.5668881 -0.8242892 -0.02473157 0.5656287 -0.823639 -0.0236203 0.5666224 -0.814722 -0.1084784 0.5696145 -0.814411 -0.1079068 0.5701674 -0.8005492 -0.1831684 0.5705876 -0.801056 -0.1843843 0.5694839 -0.7833771 -0.2592891 0.56488 -0.7812395 -0.2531211 0.5706089 -0.7599438 -0.3302597 0.559834 -0.7583752 -0.3228514 0.5662455 -0.7370074 -0.3911799 0.5511792 -0.7351531 -0.3813781 0.5604469 -0.7079284 -0.4458146 0.5478019 -0.7076309 -0.4401479 0.5527463 -0.6799126 -0.4991427 0.5371922 -0.6794916 -0.4881616 0.5477131 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 2 1 3 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 9 4 10 4 8 5 10 5 11 5 12 6 13 6 14 6 12 7 14 7 15 7 16 8 17 8 18 8 16 9 18 9 19 9 20 10 15 10 14 10 20 11 14 11 21 11 22 12 23 12 24 12 22 13 24 13 25 13 25 14 24 14 26 14 25 15 26 15 27 15 27 16 26 16 28 16 27 17 28 17 29 17 29 18 28 18 30 18 29 19 30 19 31 19 31 20 30 20 32 20 31 21 32 21 33 21 33 22 32 22 34 22 33 23 34 23 35 23 35 24 34 24 36 24 35 25 36 25 37 25 37 26 36 26 38 26 37 27 38 27 39 27 39 28 38 28 40 28 39 29 40 29 41 29 41 30 40 30 42 30 41 31 42 31 43 31 43 32 42 32 44 32 43 33 44 33 45 33 45 34 44 34 46 34 45 35 46 35 47 35 47 36 46 36 48 36 47 37 48 37 49 37 49 38 48 38 50 38 49 39 50 39 51 39 51 40 50 40 52 40 51 41 52 41 53 41 53 42 52 42 54 42 53 43 54 43 55 43 55 44 54 44 56 44 55 45 56 45 57 45 57 46 56 46 58 46 57 47 58 47 59 47 59 48 58 48 60 48 59 49 60 49 61 49 61 50 60 50 13 50 61 51 13 51 12 51 19 52 18 52 62 52 19 53 62 53 63 53 63 54 62 54 64 54 63 55 64 55 65 55 65 56 64 56 66 56 65 57 66 57 67 57 67 58 66 58 68 58 67 59 68 59 69 59 69 60 68 60 70 60 69 61 70 61 71 61 71 62 70 62 72 62 71 63 72 63 73 63 73 64 72 64 74 64 73 65 74 65 75 65 75 66 74 66 76 66 75 67 76 67 77 67 77 68 76 68 78 68 77 69 78 69 79 69 79 70 78 70 80 70 79 71 80 71 81 71 81 72 80 72 82 72 81 73 82 73 83 73 83 74 82 74 84 74 83 75 84 75 85 75 85 76 84 76 86 76 85 77 86 77 87 77 87 78 86 78 88 78 87 79 88 79 89 79 89 80 88 80 90 80 89 81 90 81 91 81 91 82 90 82 92 82 91 83 92 83 93 83 93 84 92 84 94 84 93 85 94 85 95 85 95 86 94 86 96 86 95 87 96 87 97 87 97 88 96 88 98 88 97 89 98 89 99 89 99 90 98 90 9 90 99 91 9 91 8 91 100 92 101 92 102 92 100 93 102 93 103 93 103 94 102 94 104 94 103 95 104 95 105 95 105 96 104 96 106 96 105 97 106 97 107 97 107 98 106 98 108 98 107 99 108 99 109 99 109 100 108 100 110 100 109 101 110 101 111 101 111 102 110 102 112 102 111 103 112 103 113 103 113 104 112 104 114 104 113 105 114 105 115 105 115 106 114 106 116 106 115 107 116 107 117 107 117 108 116 108 118 108 117 109 118 109 119 109 119 110 118 110 120 110 119 111 120 111 121 111 121 112 120 112 122 112 121 113 122 113 123 113 123 114 122 114 124 114 123 115 124 115 125 115 125 116 124 116 126 116 125 117 126 117 127 117 127 118 126 118 128 118 127 119 128 119 129 119 129 120 128 120 130 120 129 121 130 121 131 121 131 122 130 122 132 122 131 123 132 123 133 123 133 124 132 124 134 124 133 125 134 125 135 125 135 126 134 126 136 126 135 127 136 127 137 127 137 128 136 128 138 128 137 129 138 129 139 129 139 130 138 130 5 130 139 131 5 131 4 131 140 132 141 132 142 132 140 133 142 133 143 133 143 134 142 134 144 134 143 135 144 135 145 135 145 136 144 136 146 136 145 137 146 137 147 137 147 138 146 138 148 138 147 139 148 139 149 139 149 140 148 140 150 140 149 141 150 141 151 141 151 142 150 142 152 142 151 143 152 143 153 143 153 144 152 144 154 144 153 145 154 145 155 145 155 146 154 146 156 146 155 147 156 147 157 147 157 148 156 148 158 148 157 149 158 149 159 149 159 150 158 150 160 150 159 151 160 151 161 151 161 152 160 152 162 152 161 153 162 153 163 153 163 154 162 154 164 154 163 155 164 155 165 155 165 156 164 156 166 156 165 157 166 157 167 157 167 158 166 158 168 158 167 159 168 159 169 159 169 160 168 160 170 160 169 161 170 161 171 161 171 162 170 162 172 162 171 163 172 163 173 163 173 164 172 164 174 164 173 165 174 165 175 165 175 166 174 166 176 166 175 167 176 167 177 167 177 168 176 168 178 168 177 169 178 169 179 169 179 170 178 170 1 170 179 171 1 171 0 171 178 172 180 172 181 172 178 173 181 173 1 173 180 174 182 174 183 174 180 175 183 175 181 175 182 176 184 176 185 176 182 177 185 177 183 177 184 178 186 178 187 178 184 179 187 179 185 179 186 180 188 180 189 180 186 181 189 181 187 181 188 182 190 182 191 182 188 183 191 183 189 183 190 184 192 184 193 184 190 185 193 185 191 185 192 186 194 186 195 186 192 187 195 187 193 187 194 188 196 188 197 188 194 189 197 189 195 189 196 190 198 190 199 190 196 191 199 191 197 191 198 192 200 192 201 192 198 193 201 193 199 193 200 194 202 194 203 194 200 195 203 195 201 195 202 196 204 196 205 196 202 197 205 197 203 197 204 198 206 198 207 198 204 199 207 199 205 199 206 200 208 200 209 200 206 201 209 201 207 201 208 202 210 202 211 202 208 203 211 203 209 203 210 204 212 204 213 204 210 205 213 205 211 205 212 206 214 206 215 206 212 207 215 207 213 207 214 208 216 208 217 208 214 209 217 209 215 209 216 210 139 210 4 210 216 211 4 211 217 211 176 212 218 212 180 212 176 213 180 213 178 213 218 214 219 214 182 214 218 215 182 215 180 215 219 216 220 216 184 216 219 217 184 217 182 217 220 218 221 218 186 218 220 219 186 219 184 219 221 220 222 220 188 220 221 221 188 221 186 221 222 222 223 222 190 222 222 223 190 223 188 223 223 224 224 224 192 224 223 225 192 225 190 225 224 226 225 226 194 226 224 227 194 227 192 227 225 228 226 228 196 228 225 229 196 229 194 229 226 230 227 230 198 230 226 231 198 231 196 231 227 232 228 232 200 232 227 233 200 233 198 233 228 234 229 234 202 234 228 235 202 235 200 235 229 236 230 236 204 236 229 237 204 237 202 237 230 238 231 238 206 238 230 239 206 239 204 239 231 240 232 240 208 240 231 241 208 241 206 241 232 242 233 242 210 242 232 243 210 243 208 243 233 244 234 244 212 244 233 245 212 245 210 245 234 246 235 246 214 246 234 247 214 247 212 247 235 248 236 248 216 248 235 249 216 249 214 249 236 250 137 250 139 250 236 251 139 251 216 251 174 252 237 252 218 252 174 253 218 253 176 253 237 254 238 254 219 254 237 255 219 255 218 255 238 256 239 256 220 256 238 257 220 257 219 257 239 258 240 258 221 258 239 259 221 259 220 259 240 260 241 260 222 260 240 261 222 261 221 261 241 262 242 262 223 262 241 263 223 263 222 263 242 264 243 264 224 264 242 265 224 265 223 265 243 266 244 266 225 266 243 267 225 267 224 267 244 268 245 268 226 268 244 269 226 269 225 269 245 270 246 270 227 270 245 271 227 271 226 271 246 272 247 272 228 272 246 273 228 273 227 273 247 274 248 274 229 274 247 275 229 275 228 275 248 276 249 276 230 276 248 277 230 277 229 277 249 278 250 278 231 278 249 279 231 279 230 279 250 280 251 280 232 280 250 281 232 281 231 281 251 282 252 282 233 282 251 283 233 283 232 283 252 284 253 284 234 284 252 285 234 285 233 285 253 286 254 286 235 286 253 287 235 287 234 287 254 288 255 288 236 288 254 289 236 289 235 289 255 290 135 290 137 290 255 291 137 291 236 291 172 292 256 292 237 292 172 293 237 293 174 293 256 294 257 294 238 294 256 295 238 295 237 295 257 296 258 296 239 296 257 297 239 297 238 297 258 298 259 298 240 298 258 299 240 299 239 299 259 300 260 300 241 300 259 301 241 301 240 301 260 302 261 302 242 302 260 303 242 303 241 303 261 304 262 304 243 304 261 305 243 305 242 305 262 306 263 306 244 306 262 307 244 307 243 307 263 308 264 308 245 308 263 309 245 309 244 309 264 310 265 310 246 310 264 311 246 311 245 311 265 312 266 312 247 312 265 313 247 313 246 313 266 314 267 314 248 314 266 315 248 315 247 315 267 316 268 316 249 316 267 317 249 317 248 317 268 318 269 318 250 318 268 319 250 319 249 319 269 320 270 320 251 320 269 321 251 321 250 321 270 322 271 322 252 322 270 323 252 323 251 323 271 324 272 324 253 324 271 325 253 325 252 325 272 326 273 326 254 326 272 327 254 327 253 327 273 328 274 328 255 328 273 329 255 329 254 329 274 330 133 330 135 330 274 331 135 331 255 331 170 332 275 332 256 332 170 333 256 333 172 333 275 334 276 334 257 334 275 335 257 335 256 335 276 336 277 336 258 336 276 337 258 337 257 337 277 338 278 338 259 338 277 339 259 339 258 339 278 340 279 340 260 340 278 341 260 341 259 341 279 342 280 342 261 342 279 343 261 343 260 343 280 344 281 344 262 344 280 345 262 345 261 345 281 346 282 346 263 346 281 347 263 347 262 347 282 348 283 348 264 348 282 349 264 349 263 349 283 350 284 350 265 350 283 351 265 351 264 351 284 352 285 352 266 352 284 353 266 353 265 353 285 354 286 354 267 354 285 355 267 355 266 355 286 356 287 356 268 356 286 357 268 357 267 357 287 358 288 358 269 358 287 359 269 359 268 359 288 360 289 360 270 360 288 361 270 361 269 361 289 362 290 362 271 362 289 363 271 363 270 363 290 364 291 364 272 364 290 365 272 365 271 365 291 366 292 366 273 366 291 367 273 367 272 367 292 368 293 368 274 368 292 369 274 369 273 369 293 370 131 370 133 370 293 371 133 371 274 371 168 372 294 372 275 372 168 373 275 373 170 373 294 374 295 374 276 374 294 375 276 375 275 375 295 376 296 376 277 376 295 377 277 377 276 377 296 378 297 378 278 378 296 379 278 379 277 379 297 380 298 380 279 380 297 381 279 381 278 381 298 382 299 382 280 382 298 383 280 383 279 383 299 384 300 384 281 384 299 385 281 385 280 385 300 386 301 386 282 386 300 387 282 387 281 387 301 388 302 388 283 388 301 389 283 389 282 389 302 390 303 390 284 390 302 391 284 391 283 391 303 392 304 392 285 392 303 393 285 393 284 393 304 394 305 394 286 394 304 395 286 395 285 395 305 396 306 396 287 396 305 397 287 397 286 397 306 398 307 398 288 398 306 399 288 399 287 399 307 400 308 400 289 400 307 401 289 401 288 401 308 402 309 402 290 402 308 403 290 403 289 403 309 404 310 404 291 404 309 405 291 405 290 405 310 406 311 406 292 406 310 407 292 407 291 407 311 408 312 408 293 408 311 409 293 409 292 409 312 410 129 410 131 410 312 411 131 411 293 411 166 412 313 412 294 412 166 413 294 413 168 413 313 414 314 414 295 414 313 415 295 415 294 415 314 416 315 416 296 416 314 417 296 417 295 417 315 418 316 418 297 418 315 419 297 419 296 419 316 420 317 420 298 420 316 421 298 421 297 421 317 422 318 422 299 422 317 423 299 423 298 423 318 424 319 424 300 424 318 425 300 425 299 425 319 426 320 426 301 426 319 427 301 427 300 427 320 428 321 428 302 428 320 429 302 429 301 429 321 430 322 430 303 430 321 431 303 431 302 431 322 432 323 432 304 432 322 433 304 433 303 433 323 434 324 434 305 434 323 435 305 435 304 435 324 436 325 436 306 436 324 437 306 437 305 437 325 438 326 438 307 438 325 439 307 439 306 439 326 440 327 440 308 440 326 441 308 441 307 441 327 442 328 442 309 442 327 443 309 443 308 443 328 444 329 444 310 444 328 445 310 445 309 445 329 446 330 446 311 446 329 447 311 447 310 447 330 448 331 448 312 448 330 449 312 449 311 449 331 450 127 450 129 450 331 451 129 451 312 451 164 452 332 452 313 452 164 453 313 453 166 453 332 454 333 454 314 454 332 455 314 455 313 455 333 456 334 456 315 456 333 457 315 457 314 457 334 458 335 458 316 458 334 459 316 459 315 459 335 460 336 460 317 460 335 461 317 461 316 461 336 462 337 462 318 462 336 463 318 463 317 463 337 464 338 464 319 464 337 465 319 465 318 465 338 466 339 466 320 466 338 467 320 467 319 467 339 468 340 468 321 468 339 469 321 469 320 469 340 470 341 470 322 470 340 471 322 471 321 471 341 472 342 472 323 472 341 473 323 473 322 473 342 474 343 474 324 474 342 475 324 475 323 475 343 476 344 476 325 476 343 477 325 477 324 477 344 478 345 478 326 478 344 479 326 479 325 479 345 480 346 480 327 480 345 481 327 481 326 481 346 482 347 482 328 482 346 483 328 483 327 483 347 484 348 484 329 484 347 485 329 485 328 485 348 486 349 486 330 486 348 487 330 487 329 487 349 488 350 488 331 488 349 489 331 489 330 489 350 490 125 490 127 490 350 491 127 491 331 491 162 492 351 492 332 492 162 493 332 493 164 493 351 494 352 494 333 494 351 495 333 495 332 495 352 496 353 496 334 496 352 497 334 497 333 497 353 498 354 498 335 498 353 499 335 499 334 499 354 500 355 500 336 500 354 501 336 501 335 501 355 502 356 502 337 502 355 503 337 503 336 503 356 504 357 504 338 504 356 505 338 505 337 505 357 506 358 506 339 506 357 507 339 507 338 507 358 508 359 508 340 508 358 509 340 509 339 509 359 510 360 510 341 510 359 511 341 511 340 511 360 512 361 512 342 512 360 513 342 513 341 513 361 514 362 514 343 514 361 515 343 515 342 515 362 516 363 516 344 516 362 517 344 517 343 517 363 518 364 518 345 518 363 519 345 519 344 519 364 520 365 520 346 520 364 521 346 521 345 521 365 522 366 522 347 522 365 523 347 523 346 523 366 524 367 524 348 524 366 525 348 525 347 525 367 526 368 526 349 526 367 527 349 527 348 527 368 528 369 528 350 528 368 529 350 529 349 529 369 530 123 530 125 530 369 531 125 531 350 531 160 532 370 532 351 532 160 533 351 533 162 533 370 534 371 534 352 534 370 535 352 535 351 535 371 536 372 536 353 536 371 537 353 537 352 537 372 538 373 538 354 538 372 539 354 539 353 539 373 540 374 540 355 540 373 541 355 541 354 541 374 542 375 542 356 542 374 543 356 543 355 543 375 544 376 544 357 544 375 545 357 545 356 545 376 546 377 546 358 546 376 547 358 547 357 547 377 548 378 548 359 548 377 549 359 549 358 549 378 550 379 550 360 550 378 551 360 551 359 551 379 552 380 552 361 552 379 553 361 553 360 553 380 554 381 554 362 554 380 555 362 555 361 555 381 556 382 556 363 556 381 557 363 557 362 557 382 558 383 558 364 558 382 559 364 559 363 559 383 560 384 560 365 560 383 561 365 561 364 561 384 562 385 562 366 562 384 563 366 563 365 563 385 564 386 564 367 564 385 565 367 565 366 565 386 566 387 566 368 566 386 567 368 567 367 567 387 568 388 568 369 568 387 569 369 569 368 569 388 570 121 570 123 570 388 571 123 571 369 571 158 572 389 572 370 572 158 573 370 573 160 573 389 574 390 574 371 574 389 575 371 575 370 575 390 576 391 576 372 576 390 577 372 577 371 577 391 578 392 578 373 578 391 579 373 579 372 579 392 580 393 580 374 580 392 581 374 581 373 581 393 582 394 582 375 582 393 583 375 583 374 583 394 584 395 584 376 584 394 585 376 585 375 585 395 586 396 586 377 586 395 587 377 587 376 587 396 588 397 588 378 588 396 589 378 589 377 589 397 590 398 590 379 590 397 591 379 591 378 591 398 592 399 592 380 592 398 593 380 593 379 593 399 594 400 594 381 594 399 595 381 595 380 595 400 596 401 596 382 596 400 597 382 597 381 597 401 598 402 598 383 598 401 599 383 599 382 599 402 600 403 600 384 600 402 601 384 601 383 601 403 602 404 602 385 602 403 603 385 603 384 603 404 604 405 604 386 604 404 605 386 605 385 605 405 606 406 606 387 606 405 607 387 607 386 607 406 608 407 608 388 608 406 609 388 609 387 609 407 610 119 610 121 610 407 611 121 611 388 611 156 612 408 612 389 612 156 613 389 613 158 613 408 614 409 614 390 614 408 615 390 615 389 615 409 616 410 616 391 616 409 617 391 617 390 617 410 618 411 618 392 618 410 619 392 619 391 619 411 620 412 620 393 620 411 621 393 621 392 621 412 622 413 622 394 622 412 623 394 623 393 623 413 624 414 624 395 624 413 625 395 625 394 625 414 626 415 626 396 626 414 627 396 627 395 627 415 628 416 628 397 628 415 629 397 629 396 629 416 630 417 630 398 630 416 631 398 631 397 631 417 632 418 632 399 632 417 633 399 633 398 633 418 634 419 634 400 634 418 635 400 635 399 635 419 636 420 636 401 636 419 637 401 637 400 637 420 638 421 638 402 638 420 639 402 639 401 639 421 640 422 640 403 640 421 641 403 641 402 641 422 642 423 642 404 642 422 643 404 643 403 643 423 644 424 644 405 644 423 645 405 645 404 645 424 646 425 646 406 646 424 647 406 647 405 647 425 648 426 648 407 648 425 649 407 649 406 649 426 650 117 650 119 650 426 651 119 651 407 651 154 652 427 652 408 652 154 653 408 653 156 653 427 654 428 654 409 654 427 655 409 655 408 655 428 656 429 656 410 656 428 657 410 657 409 657 429 658 430 658 411 658 429 659 411 659 410 659 430 660 431 660 412 660 430 661 412 661 411 661 431 662 432 662 413 662 431 663 413 663 412 663 432 664 433 664 414 664 432 665 414 665 413 665 433 666 434 666 415 666 433 667 415 667 414 667 434 668 435 668 416 668 434 669 416 669 415 669 435 670 436 670 417 670 435 671 417 671 416 671 436 672 437 672 418 672 436 673 418 673 417 673 437 674 438 674 419 674 437 675 419 675 418 675 438 676 439 676 420 676 438 677 420 677 419 677 439 678 440 678 421 678 439 679 421 679 420 679 440 680 441 680 422 680 440 681 422 681 421 681 441 682 442 682 423 682 441 683 423 683 422 683 442 684 443 684 424 684 442 685 424 685 423 685 443 686 444 686 425 686 443 687 425 687 424 687 444 688 445 688 426 688 444 689 426 689 425 689 445 690 115 690 117 690 445 691 117 691 426 691 152 692 446 692 427 692 152 693 427 693 154 693 446 694 447 694 428 694 446 695 428 695 427 695 447 696 448 696 429 696 447 697 429 697 428 697 448 698 449 698 430 698 448 699 430 699 429 699 449 700 450 700 431 700 449 701 431 701 430 701 450 702 451 702 432 702 450 703 432 703 431 703 451 704 452 704 433 704 451 705 433 705 432 705 452 706 453 706 434 706 452 707 434 707 433 707 453 708 454 708 435 708 453 709 435 709 434 709 454 710 455 710 436 710 454 711 436 711 435 711 455 712 456 712 437 712 455 713 437 713 436 713 456 714 457 714 438 714 456 715 438 715 437 715 457 716 458 716 439 716 457 717 439 717 438 717 458 718 459 718 440 718 458 719 440 719 439 719 459 720 460 720 441 720 459 721 441 721 440 721 460 722 461 722 442 722 460 723 442 723 441 723 461 724 462 724 443 724 461 725 443 725 442 725 462 726 463 726 444 726 462 727 444 727 443 727 463 728 464 728 445 728 463 729 445 729 444 729 464 730 113 730 115 730 464 731 115 731 445 731 150 732 465 732 446 732 150 733 446 733 152 733 465 734 466 734 447 734 465 735 447 735 446 735 466 736 467 736 448 736 466 737 448 737 447 737 467 738 468 738 449 738 467 739 449 739 448 739 468 740 469 740 450 740 468 741 450 741 449 741 469 742 470 742 451 742 469 743 451 743 450 743 470 744 471 744 452 744 470 745 452 745 451 745 471 746 472 746 453 746 471 747 453 747 452 747 472 748 473 748 454 748 472 749 454 749 453 749 473 750 474 750 455 750 473 751 455 751 454 751 474 752 475 752 456 752 474 753 456 753 455 753 475 754 476 754 457 754 475 755 457 755 456 755 476 756 477 756 458 756 476 757 458 757 457 757 477 758 478 758 459 758 477 759 459 759 458 759 478 760 479 760 460 760 478 761 460 761 459 761 479 762 480 762 461 762 479 763 461 763 460 763 480 764 481 764 462 764 480 765 462 765 461 765 481 766 482 766 463 766 481 767 463 767 462 767 482 768 483 768 464 768 482 769 464 769 463 769 483 770 111 770 113 770 483 771 113 771 464 771 148 772 484 772 465 772 148 773 465 773 150 773 484 774 485 774 466 774 484 775 466 775 465 775 485 776 486 776 467 776 485 777 467 777 466 777 486 778 487 778 468 778 486 779 468 779 467 779 487 780 488 780 469 780 487 781 469 781 468 781 488 782 489 782 470 782 488 783 470 783 469 783 489 784 490 784 471 784 489 785 471 785 470 785 490 786 491 786 472 786 490 787 472 787 471 787 491 788 492 788 473 788 491 789 473 789 472 789 492 790 493 790 474 790 492 791 474 791 473 791 493 792 494 792 475 792 493 793 475 793 474 793 494 794 495 794 476 794 494 795 476 795 475 795 495 796 496 796 477 796 495 797 477 797 476 797 496 798 497 798 478 798 496 799 478 799 477 799 497 800 498 800 479 800 497 801 479 801 478 801 498 802 499 802 480 802 498 803 480 803 479 803 499 804 500 804 481 804 499 805 481 805 480 805 500 806 501 806 482 806 500 807 482 807 481 807 501 808 502 808 483 808 501 809 483 809 482 809 502 810 109 810 111 810 502 811 111 811 483 811 146 812 503 812 484 812 146 813 484 813 148 813 503 814 504 814 485 814 503 815 485 815 484 815 504 816 505 816 486 816 504 817 486 817 485 817 505 818 506 818 487 818 505 819 487 819 486 819 506 820 507 820 488 820 506 821 488 821 487 821 507 822 508 822 489 822 507 823 489 823 488 823 508 824 509 824 490 824 508 825 490 825 489 825 509 826 510 826 491 826 509 827 491 827 490 827 510 828 511 828 492 828 510 829 492 829 491 829 511 830 512 830 493 830 511 831 493 831 492 831 512 832 513 832 494 832 512 833 494 833 493 833 513 834 514 834 495 834 513 835 495 835 494 835 514 836 515 836 496 836 514 837 496 837 495 837 515 838 516 838 497 838 515 839 497 839 496 839 516 840 517 840 498 840 516 841 498 841 497 841 517 842 518 842 499 842 517 843 499 843 498 843 518 844 519 844 500 844 518 845 500 845 499 845 519 846 520 846 501 846 519 847 501 847 500 847 520 848 521 848 502 848 520 849 502 849 501 849 521 850 107 850 109 850 521 851 109 851 502 851 144 852 522 852 503 852 144 853 503 853 146 853 522 854 523 854 504 854 522 855 504 855 503 855 523 856 524 856 505 856 523 857 505 857 504 857 524 858 525 858 506 858 524 859 506 859 505 859 525 860 526 860 507 860 525 861 507 861 506 861 526 862 527 862 508 862 526 863 508 863 507 863 527 864 528 864 509 864 527 865 509 865 508 865 528 866 529 866 510 866 528 867 510 867 509 867 529 868 530 868 511 868 529 869 511 869 510 869 530 870 531 870 512 870 530 871 512 871 511 871 531 872 532 872 513 872 531 873 513 873 512 873 532 874 533 874 514 874 532 875 514 875 513 875 533 876 534 876 515 876 533 877 515 877 514 877 534 878 535 878 516 878 534 879 516 879 515 879 535 880 536 880 517 880 535 881 517 881 516 881 536 882 537 882 518 882 536 883 518 883 517 883 537 884 538 884 519 884 537 885 519 885 518 885 538 886 539 886 520 886 538 887 520 887 519 887 539 888 540 888 521 888 539 889 521 889 520 889 540 890 105 890 107 890 540 891 107 891 521 891 142 892 541 892 522 892 142 893 522 893 144 893 541 894 542 894 523 894 541 895 523 895 522 895 542 896 543 896 524 896 542 897 524 897 523 897 543 898 544 898 525 898 543 899 525 899 524 899 544 900 545 900 526 900 544 901 526 901 525 901 545 902 546 902 527 902 545 903 527 903 526 903 546 904 547 904 528 904 546 905 528 905 527 905 547 906 548 906 529 906 547 907 529 907 528 907 548 908 549 908 530 908 548 909 530 909 529 909 549 910 550 910 531 910 549 911 531 911 530 911 550 912 551 912 532 912 550 913 532 913 531 913 551 914 552 914 533 914 551 915 533 915 532 915 552 916 553 916 534 916 552 917 534 917 533 917 553 918 554 918 535 918 553 919 535 919 534 919 554 920 555 920 536 920 554 921 536 921 535 921 555 922 556 922 537 922 555 923 537 923 536 923 556 924 557 924 538 924 556 925 538 925 537 925 557 926 558 926 539 926 557 927 539 927 538 927 558 928 559 928 540 928 558 929 540 929 539 929 559 930 103 930 105 930 559 931 105 931 540 931 141 932 560 932 541 932 141 933 541 933 142 933 560 934 561 934 542 934 560 935 542 935 541 935 561 936 562 936 543 936 561 937 543 937 542 937 562 938 563 938 544 938 562 939 544 939 543 939 563 940 564 940 545 940 563 941 545 941 544 941 564 942 565 942 546 942 564 943 546 943 545 943 565 944 566 944 547 944 565 945 547 945 546 945 566 946 567 946 548 946 566 947 548 947 547 947 567 948 568 948 549 948 567 949 549 949 548 949 568 950 569 950 550 950 568 951 550 951 549 951 569 952 570 952 551 952 569 953 551 953 550 953 570 954 571 954 552 954 570 955 552 955 551 955 571 956 572 956 553 956 571 957 553 957 552 957 572 958 573 958 554 958 572 959 554 959 553 959 573 960 574 960 555 960 573 961 555 961 554 961 574 962 575 962 556 962 574 963 556 963 555 963 575 964 576 964 557 964 575 965 557 965 556 965 576 966 577 966 558 966 576 967 558 967 557 967 577 968 578 968 559 968 577 969 559 969 558 969 578 970 100 970 103 970 578 971 103 971 559 971 98 972 579 972 580 972 98 973 580 973 9 973 579 974 581 974 582 974 579 975 582 975 580 975 581 976 583 976 584 976 581 977 584 977 582 977 583 978 585 978 586 978 583 979 586 979 584 979 585 980 587 980 588 980 585 981 588 981 586 981 587 982 589 982 590 982 587 983 590 983 588 983 589 984 591 984 592 984 589 985 592 985 590 985 591 986 593 986 594 986 591 987 594 987 592 987 593 988 595 988 596 988 593 989 596 989 594 989 595 990 597 990 598 990 595 991 598 991 596 991 597 992 599 992 600 992 597 993 600 993 598 993 599 994 601 994 602 994 599 995 602 995 600 995 601 996 603 996 604 996 601 997 604 997 602 997 603 998 605 998 606 998 603 999 606 999 604 999 605 1000 607 1000 608 1000 605 1001 608 1001 606 1001 607 1002 609 1002 610 1002 607 1003 610 1003 608 1003 609 1004 611 1004 612 1004 609 1005 612 1005 610 1005 611 1006 613 1006 614 1006 611 1007 614 1007 612 1007 613 1008 615 1008 616 1008 613 1009 616 1009 614 1009 615 1010 61 1010 12 1010 615 1011 12 1011 616 1011 96 1012 617 1012 579 1012 96 1013 579 1013 98 1013 617 1014 618 1014 581 1014 617 1015 581 1015 579 1015 618 1016 619 1016 583 1016 618 1017 583 1017 581 1017 619 1018 620 1018 585 1018 619 1019 585 1019 583 1019 620 1020 621 1020 587 1020 620 1021 587 1021 585 1021 621 1022 622 1022 589 1022 621 1023 589 1023 587 1023 622 1024 623 1024 591 1024 622 1025 591 1025 589 1025 623 1026 624 1026 593 1026 623 1027 593 1027 591 1027 624 1028 625 1028 595 1028 624 1029 595 1029 593 1029 625 1030 626 1030 597 1030 625 1031 597 1031 595 1031 626 1032 627 1032 599 1032 626 1033 599 1033 597 1033 627 1034 628 1034 601 1034 627 1035 601 1035 599 1035 628 1036 629 1036 603 1036 628 1037 603 1037 601 1037 629 1038 630 1038 605 1038 629 1039 605 1039 603 1039 630 1040 631 1040 607 1040 630 1041 607 1041 605 1041 631 1042 632 1042 609 1042 631 1043 609 1043 607 1043 632 1044 633 1044 611 1044 632 1045 611 1045 609 1045 633 1046 634 1046 613 1046 633 1047 613 1047 611 1047 634 1048 635 1048 615 1048 634 1049 615 1049 613 1049 635 1050 59 1050 61 1050 635 1051 61 1051 615 1051 94 1052 636 1052 617 1052 94 1053 617 1053 96 1053 636 1054 637 1054 618 1054 636 1055 618 1055 617 1055 637 1056 638 1056 619 1056 637 1057 619 1057 618 1057 638 1058 639 1058 620 1058 638 1059 620 1059 619 1059 639 1060 640 1060 621 1060 639 1061 621 1061 620 1061 640 1062 641 1062 622 1062 640 1063 622 1063 621 1063 641 1064 642 1064 623 1064 641 1065 623 1065 622 1065 642 1066 643 1066 624 1066 642 1067 624 1067 623 1067 643 1068 644 1068 625 1068 643 1069 625 1069 624 1069 644 1070 645 1070 626 1070 644 1071 626 1071 625 1071 645 1072 646 1072 627 1072 645 1073 627 1073 626 1073 646 1074 647 1074 628 1074 646 1075 628 1075 627 1075 647 1076 648 1076 629 1076 647 1077 629 1077 628 1077 648 1078 649 1078 630 1078 648 1079 630 1079 629 1079 649 1080 650 1080 631 1080 649 1081 631 1081 630 1081 650 1082 651 1082 632 1082 650 1083 632 1083 631 1083 651 1084 652 1084 633 1084 651 1085 633 1085 632 1085 652 1086 653 1086 634 1086 652 1087 634 1087 633 1087 653 1088 654 1088 635 1088 653 1089 635 1089 634 1089 654 1090 57 1090 59 1090 654 1091 59 1091 635 1091 92 1092 655 1092 636 1092 92 1093 636 1093 94 1093 655 1094 656 1094 637 1094 655 1095 637 1095 636 1095 656 1096 657 1096 638 1096 656 1097 638 1097 637 1097 657 1098 658 1098 639 1098 657 1099 639 1099 638 1099 658 1100 659 1100 640 1100 658 1101 640 1101 639 1101 659 1102 660 1102 641 1102 659 1103 641 1103 640 1103 660 1104 661 1104 642 1104 660 1105 642 1105 641 1105 661 1106 662 1106 643 1106 661 1107 643 1107 642 1107 662 1108 663 1108 644 1108 662 1109 644 1109 643 1109 663 1110 664 1110 645 1110 663 1111 645 1111 644 1111 664 1112 665 1112 646 1112 664 1113 646 1113 645 1113 665 1114 666 1114 647 1114 665 1115 647 1115 646 1115 666 1116 667 1116 648 1116 666 1117 648 1117 647 1117 667 1118 668 1118 649 1118 667 1119 649 1119 648 1119 668 1120 669 1120 650 1120 668 1121 650 1121 649 1121 669 1122 670 1122 651 1122 669 1123 651 1123 650 1123 670 1124 671 1124 652 1124 670 1125 652 1125 651 1125 671 1126 672 1126 653 1126 671 1127 653 1127 652 1127 672 1128 673 1128 654 1128 672 1129 654 1129 653 1129 673 1130 55 1130 57 1130 673 1131 57 1131 654 1131 90 1132 674 1132 655 1132 90 1133 655 1133 92 1133 674 1134 675 1134 656 1134 674 1135 656 1135 655 1135 675 1136 676 1136 657 1136 675 1137 657 1137 656 1137 676 1138 677 1138 658 1138 676 1139 658 1139 657 1139 677 1140 678 1140 659 1140 677 1141 659 1141 658 1141 678 1142 679 1142 660 1142 678 1143 660 1143 659 1143 679 1144 680 1144 661 1144 679 1145 661 1145 660 1145 680 1146 681 1146 662 1146 680 1147 662 1147 661 1147 681 1148 682 1148 663 1148 681 1149 663 1149 662 1149 682 1150 683 1150 664 1150 682 1151 664 1151 663 1151 683 1152 684 1152 665 1152 683 1153 665 1153 664 1153 684 1154 685 1154 666 1154 684 1155 666 1155 665 1155 685 1156 686 1156 667 1156 685 1157 667 1157 666 1157 686 1158 687 1158 668 1158 686 1159 668 1159 667 1159 687 1160 688 1160 669 1160 687 1161 669 1161 668 1161 688 1162 689 1162 670 1162 688 1163 670 1163 669 1163 689 1164 690 1164 671 1164 689 1165 671 1165 670 1165 690 1166 691 1166 672 1166 690 1167 672 1167 671 1167 691 1168 692 1168 673 1168 691 1169 673 1169 672 1169 692 1170 53 1170 55 1170 692 1171 55 1171 673 1171 88 1172 693 1172 674 1172 88 1173 674 1173 90 1173 693 1174 694 1174 675 1174 693 1175 675 1175 674 1175 694 1176 695 1176 676 1176 694 1177 676 1177 675 1177 695 1178 696 1178 677 1178 695 1179 677 1179 676 1179 696 1180 697 1180 678 1180 696 1181 678 1181 677 1181 697 1182 698 1182 679 1182 697 1183 679 1183 678 1183 698 1184 699 1184 680 1184 698 1185 680 1185 679 1185 699 1186 700 1186 681 1186 699 1187 681 1187 680 1187 700 1188 701 1188 682 1188 700 1189 682 1189 681 1189 701 1190 702 1190 683 1190 701 1191 683 1191 682 1191 702 1192 703 1192 684 1192 702 1193 684 1193 683 1193 703 1194 704 1194 685 1194 703 1195 685 1195 684 1195 704 1196 705 1196 686 1196 704 1197 686 1197 685 1197 705 1198 706 1198 687 1198 705 1199 687 1199 686 1199 706 1200 707 1200 688 1200 706 1201 688 1201 687 1201 707 1202 708 1202 689 1202 707 1203 689 1203 688 1203 708 1204 709 1204 690 1204 708 1205 690 1205 689 1205 709 1206 710 1206 691 1206 709 1207 691 1207 690 1207 710 1208 711 1208 692 1208 710 1209 692 1209 691 1209 711 1210 51 1210 53 1210 711 1211 53 1211 692 1211 86 1212 712 1212 693 1212 86 1213 693 1213 88 1213 712 1214 713 1214 694 1214 712 1215 694 1215 693 1215 713 1216 714 1216 695 1216 713 1217 695 1217 694 1217 714 1218 715 1218 696 1218 714 1219 696 1219 695 1219 715 1220 716 1220 697 1220 715 1221 697 1221 696 1221 716 1222 717 1222 698 1222 716 1223 698 1223 697 1223 717 1224 718 1224 699 1224 717 1225 699 1225 698 1225 718 1226 719 1226 700 1226 718 1227 700 1227 699 1227 719 1228 720 1228 701 1228 719 1229 701 1229 700 1229 720 1230 721 1230 702 1230 720 1231 702 1231 701 1231 721 1232 722 1232 703 1232 721 1233 703 1233 702 1233 722 1234 723 1234 704 1234 722 1235 704 1235 703 1235 723 1236 724 1236 705 1236 723 1237 705 1237 704 1237 724 1238 725 1238 706 1238 724 1239 706 1239 705 1239 725 1240 726 1240 707 1240 725 1241 707 1241 706 1241 726 1242 727 1242 708 1242 726 1243 708 1243 707 1243 727 1244 728 1244 709 1244 727 1245 709 1245 708 1245 728 1246 729 1246 710 1246 728 1247 710 1247 709 1247 729 1248 730 1248 711 1248 729 1249 711 1249 710 1249 730 1250 49 1250 51 1250 730 1251 51 1251 711 1251 84 1252 731 1252 712 1252 84 1253 712 1253 86 1253 731 1254 732 1254 713 1254 731 1255 713 1255 712 1255 732 1256 733 1256 714 1256 732 1257 714 1257 713 1257 733 1258 734 1258 715 1258 733 1259 715 1259 714 1259 734 1260 735 1260 716 1260 734 1261 716 1261 715 1261 735 1262 736 1262 717 1262 735 1263 717 1263 716 1263 736 1264 737 1264 718 1264 736 1265 718 1265 717 1265 737 1266 738 1266 719 1266 737 1267 719 1267 718 1267 738 1268 739 1268 720 1268 738 1269 720 1269 719 1269 739 1270 740 1270 721 1270 739 1271 721 1271 720 1271 740 1272 741 1272 722 1272 740 1273 722 1273 721 1273 741 1274 742 1274 723 1274 741 1275 723 1275 722 1275 742 1276 743 1276 724 1276 742 1277 724 1277 723 1277 743 1278 744 1278 725 1278 743 1279 725 1279 724 1279 744 1280 745 1280 726 1280 744 1281 726 1281 725 1281 745 1282 746 1282 727 1282 745 1283 727 1283 726 1283 746 1284 747 1284 728 1284 746 1285 728 1285 727 1285 747 1286 748 1286 729 1286 747 1287 729 1287 728 1287 748 1288 749 1288 730 1288 748 1289 730 1289 729 1289 749 1290 47 1290 49 1290 749 1291 49 1291 730 1291 82 1292 750 1292 731 1292 82 1293 731 1293 84 1293 750 1294 751 1294 732 1294 750 1295 732 1295 731 1295 751 1296 752 1296 733 1296 751 1297 733 1297 732 1297 752 1298 753 1298 734 1298 752 1299 734 1299 733 1299 753 1300 754 1300 735 1300 753 1301 735 1301 734 1301 754 1302 755 1302 736 1302 754 1303 736 1303 735 1303 755 1304 756 1304 737 1304 755 1305 737 1305 736 1305 756 1306 757 1306 738 1306 756 1307 738 1307 737 1307 757 1308 758 1308 739 1308 757 1309 739 1309 738 1309 758 1310 759 1310 740 1310 758 1311 740 1311 739 1311 759 1312 760 1312 741 1312 759 1313 741 1313 740 1313 760 1314 761 1314 742 1314 760 1315 742 1315 741 1315 761 1316 762 1316 743 1316 761 1317 743 1317 742 1317 762 1318 763 1318 744 1318 762 1319 744 1319 743 1319 763 1320 764 1320 745 1320 763 1321 745 1321 744 1321 764 1322 765 1322 746 1322 764 1323 746 1323 745 1323 765 1324 766 1324 747 1324 765 1325 747 1325 746 1325 766 1326 767 1326 748 1326 766 1327 748 1327 747 1327 767 1328 768 1328 749 1328 767 1329 749 1329 748 1329 768 1330 45 1330 47 1330 768 1331 47 1331 749 1331 80 1332 769 1332 750 1332 80 1333 750 1333 82 1333 769 1334 770 1334 751 1334 769 1335 751 1335 750 1335 770 1336 771 1336 752 1336 770 1337 752 1337 751 1337 771 1338 772 1338 753 1338 771 1339 753 1339 752 1339 772 1340 773 1340 754 1340 772 1341 754 1341 753 1341 773 1342 774 1342 755 1342 773 1343 755 1343 754 1343 774 1344 775 1344 756 1344 774 1345 756 1345 755 1345 775 1346 776 1346 757 1346 775 1347 757 1347 756 1347 776 1348 777 1348 758 1348 776 1349 758 1349 757 1349 777 1350 778 1350 759 1350 777 1351 759 1351 758 1351 778 1352 779 1352 760 1352 778 1353 760 1353 759 1353 779 1354 780 1354 761 1354 779 1355 761 1355 760 1355 780 1356 781 1356 762 1356 780 1357 762 1357 761 1357 781 1358 782 1358 763 1358 781 1359 763 1359 762 1359 782 1360 783 1360 764 1360 782 1361 764 1361 763 1361 783 1362 784 1362 765 1362 783 1363 765 1363 764 1363 784 1364 785 1364 766 1364 784 1365 766 1365 765 1365 785 1366 786 1366 767 1366 785 1367 767 1367 766 1367 786 1368 787 1368 768 1368 786 1369 768 1369 767 1369 787 1370 43 1370 45 1370 787 1371 45 1371 768 1371 78 1372 788 1372 769 1372 78 1373 769 1373 80 1373 788 1374 789 1374 770 1374 788 1375 770 1375 769 1375 789 1376 790 1376 771 1376 789 1377 771 1377 770 1377 790 1378 791 1378 772 1378 790 1379 772 1379 771 1379 791 1380 792 1380 773 1380 791 1381 773 1381 772 1381 792 1382 793 1382 774 1382 792 1383 774 1383 773 1383 793 1384 794 1384 775 1384 793 1385 775 1385 774 1385 794 1386 795 1386 776 1386 794 1387 776 1387 775 1387 795 1388 796 1388 777 1388 795 1389 777 1389 776 1389 796 1390 797 1390 778 1390 796 1391 778 1391 777 1391 797 1392 798 1392 779 1392 797 1393 779 1393 778 1393 798 1394 799 1394 780 1394 798 1395 780 1395 779 1395 799 1396 800 1396 781 1396 799 1397 781 1397 780 1397 800 1398 801 1398 782 1398 800 1399 782 1399 781 1399 801 1400 802 1400 783 1400 801 1401 783 1401 782 1401 802 1402 803 1402 784 1402 802 1403 784 1403 783 1403 803 1404 804 1404 785 1404 803 1405 785 1405 784 1405 804 1406 805 1406 786 1406 804 1407 786 1407 785 1407 805 1408 806 1408 787 1408 805 1409 787 1409 786 1409 806 1410 41 1410 43 1410 806 1411 43 1411 787 1411 76 1412 807 1412 788 1412 76 1413 788 1413 78 1413 807 1414 808 1414 789 1414 807 1415 789 1415 788 1415 808 1416 809 1416 790 1416 808 1417 790 1417 789 1417 809 1418 810 1418 791 1418 809 1419 791 1419 790 1419 810 1420 811 1420 792 1420 810 1421 792 1421 791 1421 811 1422 812 1422 793 1422 811 1423 793 1423 792 1423 812 1424 813 1424 794 1424 812 1425 794 1425 793 1425 813 1426 814 1426 795 1426 813 1427 795 1427 794 1427 814 1428 815 1428 796 1428 814 1429 796 1429 795 1429 815 1430 816 1430 797 1430 815 1431 797 1431 796 1431 816 1432 817 1432 798 1432 816 1433 798 1433 797 1433 817 1434 818 1434 799 1434 817 1435 799 1435 798 1435 818 1436 819 1436 800 1436 818 1437 800 1437 799 1437 819 1438 820 1438 801 1438 819 1439 801 1439 800 1439 820 1440 821 1440 802 1440 820 1441 802 1441 801 1441 821 1442 822 1442 803 1442 821 1443 803 1443 802 1443 822 1444 823 1444 804 1444 822 1445 804 1445 803 1445 823 1446 824 1446 805 1446 823 1447 805 1447 804 1447 824 1448 825 1448 806 1448 824 1449 806 1449 805 1449 825 1450 39 1450 41 1450 825 1451 41 1451 806 1451 74 1452 826 1452 807 1452 74 1453 807 1453 76 1453 826 1454 827 1454 808 1454 826 1455 808 1455 807 1455 827 1456 828 1456 809 1456 827 1457 809 1457 808 1457 828 1458 829 1458 810 1458 828 1459 810 1459 809 1459 829 1460 830 1460 811 1460 829 1461 811 1461 810 1461 830 1462 831 1462 812 1462 830 1463 812 1463 811 1463 831 1464 832 1464 813 1464 831 1465 813 1465 812 1465 832 1466 833 1466 814 1466 832 1467 814 1467 813 1467 833 1468 834 1468 815 1468 833 1469 815 1469 814 1469 834 1470 835 1470 816 1470 834 1471 816 1471 815 1471 835 1472 836 1472 817 1472 835 1473 817 1473 816 1473 836 1474 837 1474 818 1474 836 1475 818 1475 817 1475 837 1476 838 1476 819 1476 837 1477 819 1477 818 1477 838 1478 839 1478 820 1478 838 1479 820 1479 819 1479 839 1480 840 1480 821 1480 839 1481 821 1481 820 1481 840 1482 841 1482 822 1482 840 1483 822 1483 821 1483 841 1484 842 1484 823 1484 841 1485 823 1485 822 1485 842 1486 843 1486 824 1486 842 1487 824 1487 823 1487 843 1488 844 1488 825 1488 843 1489 825 1489 824 1489 844 1490 37 1490 39 1490 844 1491 39 1491 825 1491 72 1492 845 1492 826 1492 72 1493 826 1493 74 1493 845 1494 846 1494 827 1494 845 1495 827 1495 826 1495 846 1496 847 1496 828 1496 846 1497 828 1497 827 1497 847 1498 848 1498 829 1498 847 1499 829 1499 828 1499 848 1500 849 1500 830 1500 848 1501 830 1501 829 1501 849 1502 850 1502 831 1502 849 1503 831 1503 830 1503 850 1504 851 1504 832 1504 850 1505 832 1505 831 1505 851 1506 852 1506 833 1506 851 1507 833 1507 832 1507 852 1508 853 1508 834 1508 852 1509 834 1509 833 1509 853 1510 854 1510 835 1510 853 1511 835 1511 834 1511 854 1512 855 1512 836 1512 854 1513 836 1513 835 1513 855 1514 856 1514 837 1514 855 1515 837 1515 836 1515 856 1516 857 1516 838 1516 856 1517 838 1517 837 1517 857 1518 858 1518 839 1518 857 1519 839 1519 838 1519 858 1520 859 1520 840 1520 858 1521 840 1521 839 1521 859 1522 860 1522 841 1522 859 1523 841 1523 840 1523 860 1524 861 1524 842 1524 860 1525 842 1525 841 1525 861 1526 862 1526 843 1526 861 1527 843 1527 842 1527 862 1528 863 1528 844 1528 862 1529 844 1529 843 1529 863 1530 35 1530 37 1530 863 1531 37 1531 844 1531 70 1532 864 1532 845 1532 70 1533 845 1533 72 1533 864 1534 865 1534 846 1534 864 1535 846 1535 845 1535 865 1536 866 1536 847 1536 865 1537 847 1537 846 1537 866 1538 867 1538 848 1538 866 1539 848 1539 847 1539 867 1540 868 1540 849 1540 867 1541 849 1541 848 1541 868 1542 869 1542 850 1542 868 1543 850 1543 849 1543 869 1544 870 1544 851 1544 869 1545 851 1545 850 1545 870 1546 871 1546 852 1546 870 1547 852 1547 851 1547 871 1548 872 1548 853 1548 871 1549 853 1549 852 1549 872 1550 873 1550 854 1550 872 1551 854 1551 853 1551 873 1552 874 1552 855 1552 873 1553 855 1553 854 1553 874 1554 875 1554 856 1554 874 1555 856 1555 855 1555 875 1556 876 1556 857 1556 875 1557 857 1557 856 1557 876 1558 877 1558 858 1558 876 1559 858 1559 857 1559 877 1560 878 1560 859 1560 877 1561 859 1561 858 1561 878 1562 879 1562 860 1562 878 1563 860 1563 859 1563 879 1564 880 1564 861 1564 879 1565 861 1565 860 1565 880 1566 881 1566 862 1566 880 1567 862 1567 861 1567 881 1568 882 1568 863 1568 881 1569 863 1569 862 1569 882 1570 33 1570 35 1570 882 1571 35 1571 863 1571 68 1572 883 1572 864 1572 68 1573 864 1573 70 1573 883 1574 884 1574 865 1574 883 1575 865 1575 864 1575 884 1576 885 1576 866 1576 884 1577 866 1577 865 1577 885 1578 886 1578 867 1578 885 1579 867 1579 866 1579 886 1580 887 1580 868 1580 886 1581 868 1581 867 1581 887 1582 888 1582 869 1582 887 1583 869 1583 868 1583 888 1584 889 1584 870 1584 888 1585 870 1585 869 1585 889 1586 890 1586 871 1586 889 1587 871 1587 870 1587 890 1588 891 1588 872 1588 890 1589 872 1589 871 1589 891 1590 892 1590 873 1590 891 1591 873 1591 872 1591 892 1592 893 1592 874 1592 892 1593 874 1593 873 1593 893 1594 894 1594 875 1594 893 1595 875 1595 874 1595 894 1596 895 1596 876 1596 894 1597 876 1597 875 1597 895 1598 896 1598 877 1598 895 1599 877 1599 876 1599 896 1600 897 1600 878 1600 896 1601 878 1601 877 1601 897 1602 898 1602 879 1602 897 1603 879 1603 878 1603 898 1604 899 1604 880 1604 898 1605 880 1605 879 1605 899 1606 900 1606 881 1606 899 1607 881 1607 880 1607 900 1608 901 1608 882 1608 900 1609 882 1609 881 1609 901 1610 31 1610 33 1610 901 1611 33 1611 882 1611 66 1612 902 1612 883 1612 66 1613 883 1613 68 1613 902 1614 903 1614 884 1614 902 1615 884 1615 883 1615 903 1616 904 1616 885 1616 903 1617 885 1617 884 1617 904 1618 905 1618 886 1618 904 1619 886 1619 885 1619 905 1620 906 1620 887 1620 905 1621 887 1621 886 1621 906 1622 907 1622 888 1622 906 1623 888 1623 887 1623 907 1624 908 1624 889 1624 907 1625 889 1625 888 1625 908 1626 909 1626 890 1626 908 1627 890 1627 889 1627 909 1628 910 1628 891 1628 909 1629 891 1629 890 1629 910 1630 911 1630 892 1630 910 1631 892 1631 891 1631 911 1632 912 1632 893 1632 911 1633 893 1633 892 1633 912 1634 913 1634 894 1634 912 1635 894 1635 893 1635 913 1636 914 1636 895 1636 913 1637 895 1637 894 1637 914 1638 915 1638 896 1638 914 1639 896 1639 895 1639 915 1640 916 1640 897 1640 915 1641 897 1641 896 1641 916 1642 917 1642 898 1642 916 1643 898 1643 897 1643 917 1644 918 1644 899 1644 917 1645 899 1645 898 1645 918 1646 919 1646 900 1646 918 1647 900 1647 899 1647 919 1648 920 1648 901 1648 919 1649 901 1649 900 1649 920 1650 29 1650 31 1650 920 1651 31 1651 901 1651 64 1652 921 1652 902 1652 64 1653 902 1653 66 1653 921 1654 922 1654 903 1654 921 1655 903 1655 902 1655 922 1656 923 1656 904 1656 922 1657 904 1657 903 1657 923 1658 924 1658 905 1658 923 1659 905 1659 904 1659 924 1660 925 1660 906 1660 924 1661 906 1661 905 1661 925 1662 926 1662 907 1662 925 1663 907 1663 906 1663 926 1664 927 1664 908 1664 926 1665 908 1665 907 1665 927 1666 928 1666 909 1666 927 1667 909 1667 908 1667 928 1668 929 1668 910 1668 928 1669 910 1669 909 1669 929 1670 930 1670 911 1670 929 1671 911 1671 910 1671 930 1672 931 1672 912 1672 930 1673 912 1673 911 1673 931 1674 932 1674 913 1674 931 1675 913 1675 912 1675 932 1676 933 1676 914 1676 932 1677 914 1677 913 1677 933 1678 934 1678 915 1678 933 1679 915 1679 914 1679 934 1680 935 1680 916 1680 934 1681 916 1681 915 1681 935 1682 936 1682 917 1682 935 1683 917 1683 916 1683 936 1684 937 1684 918 1684 936 1685 918 1685 917 1685 937 1686 938 1686 919 1686 937 1687 919 1687 918 1687 938 1688 939 1688 920 1688 938 1689 920 1689 919 1689 939 1690 27 1690 29 1690 939 1691 29 1691 920 1691 62 1692 940 1692 921 1692 62 1693 921 1693 64 1693 940 1694 941 1694 922 1694 940 1695 922 1695 921 1695 941 1696 942 1696 923 1696 941 1697 923 1697 922 1697 942 1698 943 1698 924 1698 942 1699 924 1699 923 1699 943 1700 944 1700 925 1700 943 1701 925 1701 924 1701 944 1702 945 1702 926 1702 944 1703 926 1703 925 1703 945 1704 946 1704 927 1704 945 1705 927 1705 926 1705 946 1706 947 1706 928 1706 946 1707 928 1707 927 1707 947 1708 948 1708 929 1708 947 1709 929 1709 928 1709 948 1710 949 1710 930 1710 948 1711 930 1711 929 1711 949 1712 950 1712 931 1712 949 1713 931 1713 930 1713 950 1714 951 1714 932 1714 950 1715 932 1715 931 1715 951 1716 952 1716 933 1716 951 1717 933 1717 932 1717 952 1718 953 1718 934 1718 952 1719 934 1719 933 1719 953 1720 954 1720 935 1720 953 1721 935 1721 934 1721 954 1722 955 1722 936 1722 954 1723 936 1723 935 1723 955 1724 956 1724 937 1724 955 1725 937 1725 936 1725 956 1726 957 1726 938 1726 956 1727 938 1727 937 1727 957 1728 958 1728 939 1728 957 1729 939 1729 938 1729 958 1730 25 1730 27 1730 958 1731 27 1731 939 1731 18 1732 17 1732 940 1732 18 1733 940 1733 62 1733 17 1734 959 1734 941 1734 17 1735 941 1735 940 1735 959 1736 960 1736 942 1736 959 1737 942 1737 941 1737 960 1738 961 1738 943 1738 960 1739 943 1739 942 1739 961 1740 962 1740 944 1740 961 1741 944 1741 943 1741 962 1742 963 1742 945 1742 962 1743 945 1743 944 1743 963 1744 964 1744 946 1744 963 1745 946 1745 945 1745 964 1746 965 1746 947 1746 964 1747 947 1747 946 1747 965 1748 966 1748 948 1748 965 1749 948 1749 947 1749 966 1750 967 1750 949 1750 966 1751 949 1751 948 1751 967 1752 968 1752 950 1752 967 1753 950 1753 949 1753 968 1754 969 1754 951 1754 968 1755 951 1755 950 1755 969 1756 970 1756 952 1756 969 1757 952 1757 951 1757 970 1758 971 1758 953 1758 970 1759 953 1759 952 1759 971 1760 972 1760 954 1760 971 1761 954 1761 953 1761 972 1762 973 1762 955 1762 972 1763 955 1763 954 1763 973 1764 974 1764 956 1764 973 1765 956 1765 955 1765 974 1766 975 1766 957 1766 974 1767 957 1767 956 1767 975 1768 976 1768 958 1768 975 1769 958 1769 957 1769 976 1770 22 1770 25 1770 976 1771 25 1771 958 1771 11 1772 10 1772 977 1772 11 1773 977 1773 978 1773 978 1774 977 1774 979 1774 978 1775 979 1775 980 1775 980 1776 979 1776 981 1776 980 1777 981 1777 982 1777 982 1778 981 1778 983 1778 982 1779 983 1779 984 1779 984 1780 983 1780 985 1780 984 1781 985 1781 986 1781 986 1782 985 1782 987 1782 986 1783 987 1783 988 1783 988 1784 987 1784 989 1784 988 1785 989 1785 990 1785 990 1786 989 1786 991 1786 990 1787 991 1787 992 1787 992 1788 991 1788 993 1788 992 1789 993 1789 994 1789 994 1790 993 1790 995 1790 994 1791 995 1791 996 1791 996 1792 995 1792 997 1792 996 1793 997 1793 998 1793 998 1794 997 1794 999 1794 998 1795 999 1795 1000 1795 1000 1796 999 1796 1001 1796 1000 1797 1001 1797 1002 1797 1002 1798 1001 1798 1003 1798 1002 1799 1003 1799 1004 1799 1004 1800 1003 1800 1005 1800 1004 1801 1005 1801 1006 1801 1006 1802 1005 1802 1007 1802 1006 1803 1007 1803 1008 1803 1008 1804 1007 1804 1009 1804 1008 1805 1009 1805 1010 1805 1010 1806 1009 1806 1011 1806 1010 1807 1011 1807 1012 1807 1012 1808 1011 1808 1013 1808 1012 1809 1013 1809 1014 1809 1014 1810 1013 1810 15 1810 1014 1811 15 1811 20 1811 1015 1812 23 1812 22 1812 1015 1813 22 1813 1016 1813 1016 1814 22 1814 976 1814 1016 1815 976 1815 1017 1815 1017 1816 976 1816 1018 1816 976 1817 975 1817 1018 1817 1018 1818 975 1818 1019 1818 975 1819 974 1819 1019 1819 1019 1820 974 1820 973 1820 1019 1821 973 1821 1020 1821 1020 1822 973 1822 972 1822 1020 1823 972 1823 1021 1823 1021 1824 972 1824 971 1824 1021 1825 971 1825 1022 1825 1022 1826 971 1826 970 1826 1022 1827 970 1827 1023 1827 1023 1828 970 1828 969 1828 1023 1829 969 1829 1024 1829 1024 1830 969 1830 968 1830 1024 1831 968 1831 1025 1831 1025 1832 968 1832 967 1832 1025 1833 967 1833 1026 1833 1026 1834 967 1834 966 1834 1026 1835 966 1835 1027 1835 1027 1836 966 1836 965 1836 1027 1837 965 1837 1028 1837 1028 1838 965 1838 964 1838 1028 1839 964 1839 1029 1839 1029 1840 964 1840 963 1840 1029 1841 963 1841 1030 1841 1030 1842 963 1842 962 1842 1030 1843 962 1843 1031 1843 1031 1844 962 1844 961 1844 1031 1845 961 1845 1032 1845 1032 1846 961 1846 960 1846 1032 1847 960 1847 1033 1847 1033 1848 960 1848 959 1848 1033 1849 959 1849 1034 1849 1034 1850 959 1850 17 1850 1034 1851 17 1851 16 1851 9 1852 580 1852 977 1852 9 1853 977 1853 10 1853 580 1854 582 1854 979 1854 580 1855 979 1855 977 1855 582 1856 584 1856 981 1856 582 1857 981 1857 979 1857 584 1858 586 1858 983 1858 584 1859 983 1859 981 1859 586 1860 588 1860 985 1860 586 1861 985 1861 983 1861 588 1862 590 1862 987 1862 588 1863 987 1863 985 1863 590 1864 592 1864 989 1864 590 1865 989 1865 987 1865 592 1866 594 1866 991 1866 592 1867 991 1867 989 1867 594 1868 596 1868 993 1868 594 1869 993 1869 991 1869 596 1870 598 1870 995 1870 596 1871 995 1871 993 1871 598 1872 600 1872 997 1872 598 1873 997 1873 995 1873 600 1874 602 1874 999 1874 600 1875 999 1875 997 1875 602 1876 604 1876 1001 1876 602 1877 1001 1877 999 1877 604 1878 606 1878 1003 1878 604 1879 1003 1879 1001 1879 606 1880 608 1880 1005 1880 606 1881 1005 1881 1003 1881 608 1882 610 1882 1007 1882 608 1883 1007 1883 1005 1883 610 1884 612 1884 1009 1884 610 1885 1009 1885 1007 1885 612 1886 614 1886 1011 1886 612 1887 1011 1887 1009 1887 614 1888 616 1888 1013 1888 614 1889 1013 1889 1011 1889 616 1890 12 1890 15 1890 616 1891 15 1891 1013 1891 1 1892 181 1892 1035 1892 1 1893 1035 1893 2 1893 181 1894 183 1894 1036 1894 181 1895 1036 1895 1035 1895 183 1896 185 1896 1037 1896 183 1897 1037 1897 1036 1897 185 1898 187 1898 1038 1898 185 1899 1038 1899 1037 1899 187 1900 189 1900 1039 1900 187 1901 1039 1901 1038 1901 189 1902 191 1902 1040 1902 189 1903 1040 1903 1039 1903 191 1904 193 1904 1041 1904 191 1905 1041 1905 1040 1905 193 1906 195 1906 1042 1906 193 1907 1042 1907 1041 1907 195 1908 197 1908 1043 1908 195 1909 1043 1909 1042 1909 197 1910 199 1910 1044 1910 197 1911 1044 1911 1043 1911 199 1912 201 1912 1045 1912 199 1913 1045 1913 1044 1913 201 1914 203 1914 1046 1914 201 1915 1046 1915 1045 1915 203 1916 205 1916 1047 1916 203 1917 1047 1917 1046 1917 205 1918 207 1918 1048 1918 205 1919 1048 1919 1047 1919 207 1920 209 1920 1049 1920 207 1921 1049 1921 1048 1921 209 1922 211 1922 1050 1922 209 1923 1050 1923 1049 1923 211 1924 213 1924 1051 1924 211 1925 1051 1925 1050 1925 213 1926 215 1926 1052 1926 213 1927 1052 1927 1051 1927 215 1928 217 1928 1053 1928 215 1929 1053 1929 1052 1929 217 1930 4 1930 7 1930 217 1931 7 1931 1053 1931 578 1932 1054 1932 1055 1932 578 1933 1055 1933 100 1933 1054 1934 1056 1934 1057 1934 1054 1935 1057 1935 1055 1935 1056 1936 1058 1936 1059 1936 1056 1937 1059 1937 1057 1937 1058 1938 1060 1938 1061 1938 1058 1939 1061 1939 1059 1939 1060 1940 1062 1940 1063 1940 1060 1941 1063 1941 1061 1941 1062 1942 1064 1942 1065 1942 1062 1943 1065 1943 1063 1943 1064 1944 1066 1944 1067 1944 1064 1945 1067 1945 1065 1945 1066 1946 1068 1946 1069 1946 1066 1947 1069 1947 1067 1947 1068 1948 1070 1948 1071 1948 1068 1949 1071 1949 1069 1949 1070 1950 1072 1950 1073 1950 1070 1951 1073 1951 1071 1951 1072 1952 1074 1952 1075 1952 1072 1953 1075 1953 1073 1953 1074 1954 1076 1954 1077 1954 1074 1955 1077 1955 1075 1955 1076 1956 1078 1956 1079 1956 1076 1957 1079 1957 1077 1957 1078 1958 1080 1958 1081 1958 1078 1959 1081 1959 1079 1959 1080 1960 1082 1960 1083 1960 1080 1961 1083 1961 1081 1961 1082 1962 1084 1962 1085 1962 1082 1963 1085 1963 1083 1963 1084 1964 1086 1964 1087 1964 1084 1965 1087 1965 1085 1965 1086 1966 1088 1966 1089 1966 1086 1967 1089 1967 1087 1967 1088 1968 1090 1968 1091 1968 1088 1969 1091 1969 1089 1969 1090 1970 1034 1970 16 1970 1090 1971 16 1971 1091 1971 577 1972 1092 1972 1054 1972 577 1973 1054 1973 578 1973 1092 1974 1093 1974 1056 1974 1092 1975 1056 1975 1054 1975 1093 1976 1094 1976 1058 1976 1093 1977 1058 1977 1056 1977 1094 1978 1095 1978 1060 1978 1094 1979 1060 1979 1058 1979 1095 1980 1096 1980 1062 1980 1095 1981 1062 1981 1060 1981 1096 1982 1097 1982 1064 1982 1096 1983 1064 1983 1062 1983 1097 1984 1098 1984 1066 1984 1097 1985 1066 1985 1064 1985 1098 1986 1099 1986 1068 1986 1098 1987 1068 1987 1066 1987 1099 1988 1100 1988 1070 1988 1099 1989 1070 1989 1068 1989 1100 1990 1101 1990 1072 1990 1100 1991 1072 1991 1070 1991 1101 1992 1102 1992 1074 1992 1101 1993 1074 1993 1072 1993 1102 1994 1103 1994 1076 1994 1102 1995 1076 1995 1074 1995 1103 1996 1104 1996 1078 1996 1103 1997 1078 1997 1076 1997 1104 1998 1105 1998 1080 1998 1104 1999 1080 1999 1078 1999 1105 2000 1106 2000 1082 2000 1105 2001 1082 2001 1080 2001 1106 2002 1107 2002 1084 2002 1106 2003 1084 2003 1082 2003 1107 2004 1108 2004 1086 2004 1107 2005 1086 2005 1084 2005 1108 2006 1109 2006 1088 2006 1108 2007 1088 2007 1086 2007 1109 2008 1110 2008 1090 2008 1109 2009 1090 2009 1088 2009 1110 2010 1033 2010 1034 2010 1110 2011 1034 2011 1090 2011 576 2012 1111 2012 1092 2012 576 2013 1092 2013 577 2013 1111 2014 1112 2014 1093 2014 1111 2015 1093 2015 1092 2015 1112 2016 1113 2016 1094 2016 1112 2017 1094 2017 1093 2017 1113 2018 1114 2018 1095 2018 1113 2019 1095 2019 1094 2019 1114 2020 1115 2020 1096 2020 1114 2021 1096 2021 1095 2021 1115 2022 1116 2022 1097 2022 1115 2023 1097 2023 1096 2023 1116 2024 1117 2024 1098 2024 1116 2025 1098 2025 1097 2025 1117 2026 1118 2026 1099 2026 1117 2027 1099 2027 1098 2027 1118 2028 1119 2028 1100 2028 1118 2029 1100 2029 1099 2029 1119 2030 1120 2030 1101 2030 1119 2031 1101 2031 1100 2031 1120 2032 1121 2032 1102 2032 1120 2033 1102 2033 1101 2033 1121 2034 1122 2034 1103 2034 1121 2035 1103 2035 1102 2035 1122 2036 1123 2036 1104 2036 1122 2037 1104 2037 1103 2037 1123 2038 1124 2038 1105 2038 1123 2039 1105 2039 1104 2039 1124 2040 1125 2040 1106 2040 1124 2041 1106 2041 1105 2041 1125 2042 1126 2042 1107 2042 1125 2043 1107 2043 1106 2043 1126 2044 1127 2044 1108 2044 1126 2045 1108 2045 1107 2045 1127 2046 1128 2046 1109 2046 1127 2047 1109 2047 1108 2047 1128 2048 1129 2048 1110 2048 1128 2049 1110 2049 1109 2049 1129 2050 1032 2050 1033 2050 1129 2051 1033 2051 1110 2051 575 2052 1130 2052 1111 2052 575 2053 1111 2053 576 2053 1130 2054 1131 2054 1112 2054 1130 2055 1112 2055 1111 2055 1131 2056 1132 2056 1113 2056 1131 2057 1113 2057 1112 2057 1132 2058 1133 2058 1114 2058 1132 2059 1114 2059 1113 2059 1133 2060 1134 2060 1115 2060 1133 2061 1115 2061 1114 2061 1134 2062 1135 2062 1116 2062 1134 2063 1116 2063 1115 2063 1135 2064 1136 2064 1117 2064 1135 2065 1117 2065 1116 2065 1136 2066 1137 2066 1118 2066 1136 2067 1118 2067 1117 2067 1137 2068 1138 2068 1119 2068 1137 2069 1119 2069 1118 2069 1138 2070 1139 2070 1120 2070 1138 2071 1120 2071 1119 2071 1139 2072 1140 2072 1121 2072 1139 2073 1121 2073 1120 2073 1140 2074 1141 2074 1122 2074 1140 2075 1122 2075 1121 2075 1141 2076 1142 2076 1123 2076 1141 2077 1123 2077 1122 2077 1142 2078 1143 2078 1124 2078 1142 2079 1124 2079 1123 2079 1143 2080 1144 2080 1125 2080 1143 2081 1125 2081 1124 2081 1144 2082 1145 2082 1126 2082 1144 2083 1126 2083 1125 2083 1145 2084 1146 2084 1127 2084 1145 2085 1127 2085 1126 2085 1146 2086 1147 2086 1128 2086 1146 2087 1128 2087 1127 2087 1147 2088 1148 2088 1129 2088 1147 2089 1129 2089 1128 2089 1148 2090 1031 2090 1032 2090 1148 2091 1032 2091 1129 2091 574 2092 1149 2092 1130 2092 574 2093 1130 2093 575 2093 1149 2094 1150 2094 1131 2094 1149 2095 1131 2095 1130 2095 1150 2096 1151 2096 1132 2096 1150 2097 1132 2097 1131 2097 1151 2098 1152 2098 1133 2098 1151 2099 1133 2099 1132 2099 1152 2100 1153 2100 1134 2100 1152 2101 1134 2101 1133 2101 1153 2102 1154 2102 1135 2102 1153 2103 1135 2103 1134 2103 1154 2104 1155 2104 1136 2104 1154 2105 1136 2105 1135 2105 1155 2106 1156 2106 1137 2106 1155 2107 1137 2107 1136 2107 1156 2108 1157 2108 1138 2108 1156 2109 1138 2109 1137 2109 1157 2110 1158 2110 1139 2110 1157 2111 1139 2111 1138 2111 1158 2112 1159 2112 1140 2112 1158 2113 1140 2113 1139 2113 1159 2114 1160 2114 1141 2114 1159 2115 1141 2115 1140 2115 1160 2116 1161 2116 1142 2116 1160 2117 1142 2117 1141 2117 1161 2118 1162 2118 1143 2118 1161 2119 1143 2119 1142 2119 1162 2120 1163 2120 1144 2120 1162 2121 1144 2121 1143 2121 1163 2122 1164 2122 1145 2122 1163 2123 1145 2123 1144 2123 1164 2124 1165 2124 1146 2124 1164 2125 1146 2125 1145 2125 1165 2126 1166 2126 1147 2126 1165 2127 1147 2127 1146 2127 1166 2128 1167 2128 1148 2128 1166 2129 1148 2129 1147 2129 1167 2130 1030 2130 1031 2130 1167 2131 1031 2131 1148 2131 573 2132 1168 2132 1149 2132 573 2133 1149 2133 574 2133 1168 2134 1169 2134 1150 2134 1168 2135 1150 2135 1149 2135 1169 2136 1170 2136 1151 2136 1169 2137 1151 2137 1150 2137 1170 2138 1171 2138 1152 2138 1170 2139 1152 2139 1151 2139 1171 2140 1172 2140 1153 2140 1171 2141 1153 2141 1152 2141 1172 2142 1173 2142 1154 2142 1172 2143 1154 2143 1153 2143 1173 2144 1174 2144 1155 2144 1173 2145 1155 2145 1154 2145 1174 2146 1175 2146 1156 2146 1174 2147 1156 2147 1155 2147 1175 2148 1176 2148 1157 2148 1175 2149 1157 2149 1156 2149 1176 2150 1177 2150 1158 2150 1176 2151 1158 2151 1157 2151 1177 2152 1178 2152 1159 2152 1177 2153 1159 2153 1158 2153 1178 2154 1179 2154 1160 2154 1178 2155 1160 2155 1159 2155 1179 2156 1180 2156 1161 2156 1179 2157 1161 2157 1160 2157 1180 2158 1181 2158 1162 2158 1180 2159 1162 2159 1161 2159 1181 2160 1182 2160 1163 2160 1181 2161 1163 2161 1162 2161 1182 2162 1183 2162 1164 2162 1182 2163 1164 2163 1163 2163 1183 2164 1184 2164 1165 2164 1183 2165 1165 2165 1164 2165 1184 2166 1185 2166 1166 2166 1184 2167 1166 2167 1165 2167 1185 2168 1186 2168 1167 2168 1185 2169 1167 2169 1166 2169 1186 2170 1029 2170 1030 2170 1186 2171 1030 2171 1167 2171 572 2172 1187 2172 1168 2172 572 2173 1168 2173 573 2173 1187 2174 1188 2174 1169 2174 1187 2175 1169 2175 1168 2175 1188 2176 1189 2176 1170 2176 1188 2177 1170 2177 1169 2177 1189 2178 1190 2178 1171 2178 1189 2179 1171 2179 1170 2179 1190 2180 1191 2180 1172 2180 1190 2181 1172 2181 1171 2181 1191 2182 1192 2182 1173 2182 1191 2183 1173 2183 1172 2183 1192 2184 1193 2184 1174 2184 1192 2185 1174 2185 1173 2185 1193 2186 1194 2186 1175 2186 1193 2187 1175 2187 1174 2187 1194 2188 1195 2188 1176 2188 1194 2189 1176 2189 1175 2189 1195 2190 1196 2190 1177 2190 1195 2191 1177 2191 1176 2191 1196 2192 1197 2192 1178 2192 1196 2193 1178 2193 1177 2193 1197 2194 1198 2194 1179 2194 1197 2195 1179 2195 1178 2195 1198 2196 1199 2196 1180 2196 1198 2197 1180 2197 1179 2197 1199 2198 1200 2198 1181 2198 1199 2199 1181 2199 1180 2199 1200 2200 1201 2200 1182 2200 1200 2201 1182 2201 1181 2201 1201 2202 1202 2202 1183 2202 1201 2203 1183 2203 1182 2203 1202 2204 1203 2204 1184 2204 1202 2205 1184 2205 1183 2205 1203 2206 1204 2206 1185 2206 1203 2207 1185 2207 1184 2207 1204 2208 1205 2208 1186 2208 1204 2209 1186 2209 1185 2209 1205 2210 1028 2210 1029 2210 1205 2211 1029 2211 1186 2211 571 2212 1206 2212 1187 2212 571 2213 1187 2213 572 2213 1206 2214 1207 2214 1188 2214 1206 2215 1188 2215 1187 2215 1207 2216 1208 2216 1189 2216 1207 2217 1189 2217 1188 2217 1208 2218 1209 2218 1190 2218 1208 2219 1190 2219 1189 2219 1209 2220 1210 2220 1191 2220 1209 2221 1191 2221 1190 2221 1210 2222 1211 2222 1192 2222 1210 2223 1192 2223 1191 2223 1211 2224 1212 2224 1193 2224 1211 2225 1193 2225 1192 2225 1212 2226 1213 2226 1194 2226 1212 2227 1194 2227 1193 2227 1213 2228 1214 2228 1195 2228 1213 2229 1195 2229 1194 2229 1214 2230 1215 2230 1196 2230 1214 2231 1196 2231 1195 2231 1215 2232 1216 2232 1197 2232 1215 2233 1197 2233 1196 2233 1216 2234 1217 2234 1198 2234 1216 2235 1198 2235 1197 2235 1217 2236 1218 2236 1199 2236 1217 2237 1199 2237 1198 2237 1218 2238 1219 2238 1200 2238 1218 2239 1200 2239 1199 2239 1219 2240 1220 2240 1201 2240 1219 2241 1201 2241 1200 2241 1220 2242 1221 2242 1202 2242 1220 2243 1202 2243 1201 2243 1221 2244 1222 2244 1203 2244 1221 2245 1203 2245 1202 2245 1222 2246 1223 2246 1204 2246 1222 2247 1204 2247 1203 2247 1223 2248 1224 2248 1205 2248 1223 2249 1205 2249 1204 2249 1224 2250 1027 2250 1028 2250 1224 2251 1028 2251 1205 2251 570 2252 1225 2252 1206 2252 570 2253 1206 2253 571 2253 1225 2254 1226 2254 1207 2254 1225 2255 1207 2255 1206 2255 1226 2256 1227 2256 1208 2256 1226 2257 1208 2257 1207 2257 1227 2258 1228 2258 1209 2258 1227 2259 1209 2259 1208 2259 1228 2260 1229 2260 1210 2260 1228 2261 1210 2261 1209 2261 1229 2262 1230 2262 1211 2262 1229 2263 1211 2263 1210 2263 1230 2264 1231 2264 1212 2264 1230 2265 1212 2265 1211 2265 1231 2266 1232 2266 1213 2266 1231 2267 1213 2267 1212 2267 1232 2268 1233 2268 1214 2268 1232 2269 1214 2269 1213 2269 1233 2270 1234 2270 1215 2270 1233 2271 1215 2271 1214 2271 1234 2272 1235 2272 1216 2272 1234 2273 1216 2273 1215 2273 1235 2274 1236 2274 1217 2274 1235 2275 1217 2275 1216 2275 1236 2276 1237 2276 1218 2276 1236 2277 1218 2277 1217 2277 1237 2278 1238 2278 1219 2278 1237 2279 1219 2279 1218 2279 1238 2280 1239 2280 1220 2280 1238 2281 1220 2281 1219 2281 1239 2282 1240 2282 1221 2282 1239 2283 1221 2283 1220 2283 1240 2284 1241 2284 1222 2284 1240 2285 1222 2285 1221 2285 1241 2286 1242 2286 1223 2286 1241 2287 1223 2287 1222 2287 1242 2288 1243 2288 1224 2288 1242 2289 1224 2289 1223 2289 1243 2290 1026 2290 1027 2290 1243 2291 1027 2291 1224 2291 569 2292 1244 2292 1225 2292 569 2293 1225 2293 570 2293 1244 2294 1245 2294 1226 2294 1244 2295 1226 2295 1225 2295 1245 2296 1246 2296 1227 2296 1245 2297 1227 2297 1226 2297 1246 2298 1247 2298 1228 2298 1246 2299 1228 2299 1227 2299 1247 2300 1248 2300 1229 2300 1247 2301 1229 2301 1228 2301 1248 2302 1249 2302 1230 2302 1248 2303 1230 2303 1229 2303 1249 2304 1250 2304 1231 2304 1249 2305 1231 2305 1230 2305 1250 2306 1251 2306 1232 2306 1250 2307 1232 2307 1231 2307 1251 2308 1252 2308 1233 2308 1251 2309 1233 2309 1232 2309 1252 2310 1253 2310 1234 2310 1252 2311 1234 2311 1233 2311 1253 2312 1254 2312 1235 2312 1253 2313 1235 2313 1234 2313 1254 2314 1255 2314 1236 2314 1254 2315 1236 2315 1235 2315 1255 2316 1256 2316 1237 2316 1255 2317 1237 2317 1236 2317 1256 2318 1257 2318 1238 2318 1256 2319 1238 2319 1237 2319 1257 2320 1258 2320 1239 2320 1257 2321 1239 2321 1238 2321 1258 2322 1259 2322 1240 2322 1258 2323 1240 2323 1239 2323 1259 2324 1260 2324 1241 2324 1259 2325 1241 2325 1240 2325 1260 2326 1261 2326 1242 2326 1260 2327 1242 2327 1241 2327 1261 2328 1262 2328 1243 2328 1261 2329 1243 2329 1242 2329 1262 2330 1025 2330 1026 2330 1262 2331 1026 2331 1243 2331 568 2332 1263 2332 1244 2332 568 2333 1244 2333 569 2333 1263 2334 1264 2334 1245 2334 1263 2335 1245 2335 1244 2335 1264 2336 1265 2336 1246 2336 1264 2337 1246 2337 1245 2337 1265 2338 1266 2338 1247 2338 1265 2339 1247 2339 1246 2339 1266 2340 1267 2340 1248 2340 1266 2341 1248 2341 1247 2341 1267 2342 1268 2342 1249 2342 1267 2343 1249 2343 1248 2343 1268 2344 1269 2344 1250 2344 1268 2345 1250 2345 1249 2345 1269 2346 1270 2346 1251 2346 1269 2347 1251 2347 1250 2347 1270 2348 1271 2348 1252 2348 1270 2349 1252 2349 1251 2349 1271 2350 1272 2350 1253 2350 1271 2351 1253 2351 1252 2351 1272 2352 1273 2352 1254 2352 1272 2353 1254 2353 1253 2353 1273 2354 1274 2354 1255 2354 1273 2355 1255 2355 1254 2355 1274 2356 1275 2356 1256 2356 1274 2357 1256 2357 1255 2357 1275 2358 1276 2358 1257 2358 1275 2359 1257 2359 1256 2359 1276 2360 1277 2360 1258 2360 1276 2361 1258 2361 1257 2361 1277 2362 1278 2362 1259 2362 1277 2363 1259 2363 1258 2363 1278 2364 1279 2364 1260 2364 1278 2365 1260 2365 1259 2365 1279 2366 1280 2366 1261 2366 1279 2367 1261 2367 1260 2367 1280 2368 1281 2368 1262 2368 1280 2369 1262 2369 1261 2369 1281 2370 1024 2370 1025 2370 1281 2371 1025 2371 1262 2371 567 2372 1282 2372 1263 2372 567 2373 1263 2373 568 2373 1282 2374 1283 2374 1264 2374 1282 2375 1264 2375 1263 2375 1283 2376 1284 2376 1265 2376 1283 2377 1265 2377 1264 2377 1284 2378 1285 2378 1266 2378 1284 2379 1266 2379 1265 2379 1285 2380 1286 2380 1267 2380 1285 2381 1267 2381 1266 2381 1286 2382 1287 2382 1268 2382 1286 2383 1268 2383 1267 2383 1287 2384 1288 2384 1269 2384 1287 2385 1269 2385 1268 2385 1288 2386 1289 2386 1270 2386 1288 2387 1270 2387 1269 2387 1289 2388 1290 2388 1271 2388 1289 2389 1271 2389 1270 2389 1290 2390 1291 2390 1272 2390 1290 2391 1272 2391 1271 2391 1291 2392 1292 2392 1273 2392 1291 2393 1273 2393 1272 2393 1292 2394 1293 2394 1274 2394 1292 2395 1274 2395 1273 2395 1293 2396 1294 2396 1275 2396 1293 2397 1275 2397 1274 2397 1294 2398 1295 2398 1276 2398 1294 2399 1276 2399 1275 2399 1295 2400 1296 2400 1277 2400 1295 2401 1277 2401 1276 2401 1296 2402 1297 2402 1278 2402 1296 2403 1278 2403 1277 2403 1297 2404 1298 2404 1279 2404 1297 2405 1279 2405 1278 2405 1298 2406 1299 2406 1280 2406 1298 2407 1280 2407 1279 2407 1299 2408 1300 2408 1281 2408 1299 2409 1281 2409 1280 2409 1300 2410 1023 2410 1024 2410 1300 2411 1024 2411 1281 2411 566 2412 1301 2412 1282 2412 566 2413 1282 2413 567 2413 1301 2414 1302 2414 1283 2414 1301 2415 1283 2415 1282 2415 1302 2416 1303 2416 1284 2416 1302 2417 1284 2417 1283 2417 1303 2418 1304 2418 1285 2418 1303 2419 1285 2419 1284 2419 1304 2420 1305 2420 1286 2420 1304 2421 1286 2421 1285 2421 1305 2422 1306 2422 1287 2422 1305 2423 1287 2423 1286 2423 1306 2424 1307 2424 1288 2424 1306 2425 1288 2425 1287 2425 1307 2426 1308 2426 1289 2426 1307 2427 1289 2427 1288 2427 1308 2428 1309 2428 1290 2428 1308 2429 1290 2429 1289 2429 1309 2430 1310 2430 1291 2430 1309 2431 1291 2431 1290 2431 1310 2432 1311 2432 1292 2432 1310 2433 1292 2433 1291 2433 1311 2434 1312 2434 1293 2434 1311 2435 1293 2435 1292 2435 1312 2436 1313 2436 1294 2436 1312 2437 1294 2437 1293 2437 1313 2438 1314 2438 1295 2438 1313 2439 1295 2439 1294 2439 1314 2440 1315 2440 1296 2440 1314 2441 1296 2441 1295 2441 1315 2442 1316 2442 1297 2442 1315 2443 1297 2443 1296 2443 1316 2444 1317 2444 1298 2444 1316 2445 1298 2445 1297 2445 1317 2446 1318 2446 1299 2446 1317 2447 1299 2447 1298 2447 1318 2448 1319 2448 1300 2448 1318 2449 1300 2449 1299 2449 1319 2450 1022 2450 1023 2450 1319 2451 1023 2451 1300 2451 565 2452 1320 2452 1301 2452 565 2453 1301 2453 566 2453 1320 2454 1321 2454 1302 2454 1320 2455 1302 2455 1301 2455 1321 2456 1322 2456 1303 2456 1321 2457 1303 2457 1302 2457 1322 2458 1323 2458 1304 2458 1322 2459 1304 2459 1303 2459 1323 2460 1324 2460 1305 2460 1323 2461 1305 2461 1304 2461 1324 2462 1325 2462 1306 2462 1324 2463 1306 2463 1305 2463 1325 2464 1326 2464 1307 2464 1325 2465 1307 2465 1306 2465 1326 2466 1327 2466 1308 2466 1326 2467 1308 2467 1307 2467 1327 2468 1328 2468 1309 2468 1327 2469 1309 2469 1308 2469 1328 2470 1329 2470 1310 2470 1328 2471 1310 2471 1309 2471 1329 2472 1330 2472 1311 2472 1329 2473 1311 2473 1310 2473 1330 2474 1331 2474 1312 2474 1330 2475 1312 2475 1311 2475 1331 2476 1332 2476 1313 2476 1331 2477 1313 2477 1312 2477 1332 2478 1333 2478 1314 2478 1332 2479 1314 2479 1313 2479 1333 2480 1334 2480 1315 2480 1333 2481 1315 2481 1314 2481 1334 2482 1335 2482 1316 2482 1334 2483 1316 2483 1315 2483 1335 2484 1336 2484 1317 2484 1335 2485 1317 2485 1316 2485 1336 2486 1337 2486 1318 2486 1336 2487 1318 2487 1317 2487 1337 2488 1338 2488 1319 2488 1337 2489 1319 2489 1318 2489 1338 2490 1021 2490 1022 2490 1338 2491 1022 2491 1319 2491 564 2492 1339 2492 1320 2492 564 2493 1320 2493 565 2493 1339 2494 1340 2494 1321 2494 1339 2495 1321 2495 1320 2495 1340 2496 1341 2496 1322 2496 1340 2497 1322 2497 1321 2497 1341 2498 1342 2498 1323 2498 1341 2499 1323 2499 1322 2499 1342 2500 1343 2500 1324 2500 1342 2501 1324 2501 1323 2501 1343 2502 1344 2502 1325 2502 1343 2503 1325 2503 1324 2503 1344 2504 1345 2504 1326 2504 1344 2505 1326 2505 1325 2505 1345 2506 1346 2506 1327 2506 1345 2507 1327 2507 1326 2507 1346 2508 1347 2508 1328 2508 1346 2509 1328 2509 1327 2509 1347 2510 1348 2510 1329 2510 1347 2511 1329 2511 1328 2511 1348 2512 1349 2512 1330 2512 1348 2513 1330 2513 1329 2513 1349 2514 1350 2514 1331 2514 1349 2515 1331 2515 1330 2515 1350 2516 1351 2516 1332 2516 1350 2517 1332 2517 1331 2517 1351 2518 1352 2518 1333 2518 1351 2519 1333 2519 1332 2519 1352 2520 1353 2520 1334 2520 1352 2521 1334 2521 1333 2521 1353 2522 1354 2522 1335 2522 1353 2523 1335 2523 1334 2523 1354 2524 1355 2524 1336 2524 1354 2525 1336 2525 1335 2525 1355 2526 1356 2526 1337 2526 1355 2527 1337 2527 1336 2527 1356 2528 1357 2528 1338 2528 1356 2529 1338 2529 1337 2529 1357 2530 1020 2530 1021 2530 1357 2531 1021 2531 1338 2531 563 2532 1358 2532 1339 2532 563 2533 1339 2533 564 2533 1358 2534 1359 2534 1340 2534 1358 2535 1340 2535 1339 2535 1359 2536 1360 2536 1341 2536 1359 2537 1341 2537 1340 2537 1360 2538 1361 2538 1342 2538 1360 2539 1342 2539 1341 2539 1361 2540 1362 2540 1343 2540 1361 2541 1343 2541 1342 2541 1362 2542 1363 2542 1344 2542 1362 2543 1344 2543 1343 2543 1363 2544 1364 2544 1345 2544 1363 2545 1345 2545 1344 2545 1364 2546 1365 2546 1346 2546 1364 2547 1346 2547 1345 2547 1365 2548 1366 2548 1347 2548 1365 2549 1347 2549 1346 2549 1366 2550 1367 2550 1348 2550 1366 2551 1348 2551 1347 2551 1367 2552 1368 2552 1349 2552 1367 2553 1349 2553 1348 2553 1368 2554 1369 2554 1350 2554 1368 2555 1350 2555 1349 2555 1369 2556 1370 2556 1351 2556 1369 2557 1351 2557 1350 2557 1370 2558 1371 2558 1352 2558 1370 2559 1352 2559 1351 2559 1371 2560 1372 2560 1353 2560 1371 2561 1353 2561 1352 2561 1372 2562 1373 2562 1354 2562 1372 2563 1354 2563 1353 2563 1373 2564 1374 2564 1355 2564 1373 2565 1355 2565 1354 2565 1374 2566 1375 2566 1356 2566 1374 2567 1356 2567 1355 2567 1375 2568 1376 2568 1357 2568 1375 2569 1357 2569 1356 2569 1376 2570 1019 2570 1020 2570 1376 2571 1020 2571 1357 2571 562 2572 1377 2572 1358 2572 562 2573 1358 2573 563 2573 1377 2574 1378 2574 1359 2574 1377 2575 1359 2575 1358 2575 1378 2576 1379 2576 1360 2576 1378 2577 1360 2577 1359 2577 1379 2578 1380 2578 1361 2578 1379 2579 1361 2579 1360 2579 1380 2580 1381 2580 1362 2580 1380 2581 1362 2581 1361 2581 1381 2582 1382 2582 1363 2582 1381 2583 1363 2583 1362 2583 1382 2584 1383 2584 1364 2584 1382 2585 1364 2585 1363 2585 1383 2586 1384 2586 1365 2586 1383 2587 1365 2587 1364 2587 1384 2588 1385 2588 1366 2588 1384 2589 1366 2589 1365 2589 1385 2590 1386 2590 1367 2590 1385 2591 1367 2591 1366 2591 1386 2592 1387 2592 1368 2592 1386 2593 1368 2593 1367 2593 1387 2594 1388 2594 1369 2594 1387 2595 1369 2595 1368 2595 1388 2596 1389 2596 1370 2596 1388 2597 1370 2597 1369 2597 1389 2598 1390 2598 1371 2598 1389 2599 1371 2599 1370 2599 1390 2600 1391 2600 1372 2600 1390 2601 1372 2601 1371 2601 1391 2602 1392 2602 1373 2602 1391 2603 1373 2603 1372 2603 1392 2604 1393 2604 1374 2604 1392 2605 1374 2605 1373 2605 1393 2606 1394 2606 1375 2606 1393 2607 1375 2607 1374 2607 1394 2608 1395 2608 1376 2608 1394 2609 1376 2609 1375 2609 1395 2610 1018 2610 1376 2610 1018 2611 1019 2611 1376 2611 561 2612 1396 2612 1377 2612 561 2613 1377 2613 562 2613 1396 2614 1397 2614 1378 2614 1396 2615 1378 2615 1377 2615 1397 2616 1398 2616 1379 2616 1397 2617 1379 2617 1378 2617 1398 2618 1399 2618 1380 2618 1398 2619 1380 2619 1379 2619 1399 2620 1400 2620 1381 2620 1399 2621 1381 2621 1380 2621 1400 2622 1401 2622 1382 2622 1400 2623 1382 2623 1381 2623 1401 2624 1402 2624 1383 2624 1401 2625 1383 2625 1382 2625 1402 2626 1403 2626 1384 2626 1402 2627 1384 2627 1383 2627 1403 2628 1404 2628 1385 2628 1403 2629 1385 2629 1384 2629 1404 2630 1405 2630 1386 2630 1404 2631 1386 2631 1385 2631 1405 2632 1406 2632 1387 2632 1405 2633 1387 2633 1386 2633 1406 2634 1407 2634 1388 2634 1406 2635 1388 2635 1387 2635 1407 2636 1408 2636 1389 2636 1407 2637 1389 2637 1388 2637 1408 2638 1409 2638 1390 2638 1408 2639 1390 2639 1389 2639 1409 2640 1410 2640 1391 2640 1409 2641 1391 2641 1390 2641 1410 2642 1411 2642 1392 2642 1410 2643 1392 2643 1391 2643 1411 2644 1412 2644 1393 2644 1411 2645 1393 2645 1392 2645 1412 2646 1413 2646 1394 2646 1412 2647 1394 2647 1393 2647 1413 2648 1414 2648 1395 2648 1413 2649 1395 2649 1394 2649 1414 2650 1017 2650 1395 2650 1017 2651 1018 2651 1395 2651 560 2652 1415 2652 1396 2652 560 2653 1396 2653 561 2653 1415 2654 1416 2654 1397 2654 1415 2655 1397 2655 1396 2655 1416 2656 1417 2656 1398 2656 1416 2657 1398 2657 1397 2657 1417 2658 1418 2658 1399 2658 1417 2659 1399 2659 1398 2659 1418 2660 1419 2660 1400 2660 1418 2661 1400 2661 1399 2661 1419 2662 1420 2662 1401 2662 1419 2663 1401 2663 1400 2663 1420 2664 1421 2664 1402 2664 1420 2665 1402 2665 1401 2665 1421 2666 1422 2666 1403 2666 1421 2667 1403 2667 1402 2667 1422 2668 1423 2668 1404 2668 1422 2669 1404 2669 1403 2669 1423 2670 1424 2670 1405 2670 1423 2671 1405 2671 1404 2671 1424 2672 1425 2672 1406 2672 1424 2673 1406 2673 1405 2673 1425 2674 1426 2674 1407 2674 1425 2675 1407 2675 1406 2675 1426 2676 1427 2676 1408 2676 1426 2677 1408 2677 1407 2677 1427 2678 1428 2678 1409 2678 1427 2679 1409 2679 1408 2679 1428 2680 1429 2680 1410 2680 1428 2681 1410 2681 1409 2681 1429 2682 1430 2682 1411 2682 1429 2683 1411 2683 1410 2683 1430 2684 1431 2684 1412 2684 1430 2685 1412 2685 1411 2685 1431 2686 1432 2686 1413 2686 1431 2687 1413 2687 1412 2687 1432 2688 1433 2688 1414 2688 1432 2689 1414 2689 1413 2689 1433 2690 1016 2690 1017 2690 1433 2691 1017 2691 1414 2691 141 2692 140 2692 1415 2692 141 2693 1415 2693 560 2693 140 2694 1434 2694 1416 2694 140 2695 1416 2695 1415 2695 1434 2696 1435 2696 1417 2696 1434 2697 1417 2697 1416 2697 1435 2698 1436 2698 1418 2698 1435 2699 1418 2699 1417 2699 1436 2700 1437 2700 1419 2700 1436 2701 1419 2701 1418 2701 1437 2702 1438 2702 1420 2702 1437 2703 1420 2703 1419 2703 1438 2704 1439 2704 1421 2704 1438 2705 1421 2705 1420 2705 1439 2706 1440 2706 1422 2706 1439 2707 1422 2707 1421 2707 1440 2708 1441 2708 1423 2708 1440 2709 1423 2709 1422 2709 1441 2710 1442 2710 1424 2710 1441 2711 1424 2711 1423 2711 1442 2712 1443 2712 1425 2712 1442 2713 1425 2713 1424 2713 1443 2714 1444 2714 1426 2714 1443 2715 1426 2715 1425 2715 1444 2716 1445 2716 1427 2716 1444 2717 1427 2717 1426 2717 1445 2718 1446 2718 1428 2718 1445 2719 1428 2719 1427 2719 1446 2720 1447 2720 1429 2720 1446 2721 1429 2721 1428 2721 1447 2722 1448 2722 1430 2722 1447 2723 1430 2723 1429 2723 1448 2724 1449 2724 1431 2724 1448 2725 1431 2725 1430 2725 1449 2726 1450 2726 1432 2726 1449 2727 1432 2727 1431 2727 1450 2728 1451 2728 1433 2728 1450 2729 1433 2729 1432 2729 1451 2730 1015 2730 1016 2730 1451 2731 1016 2731 1433 2731 1036 2732 1452 2732 1453 2732 1036 2733 1453 2733 1035 2733 1452 2734 1454 2734 1455 2734 1452 2735 1455 2735 1453 2735 1454 2736 1456 2736 1457 2736 1454 2737 1457 2737 1455 2737 1456 2738 1458 2738 1459 2738 1456 2739 1459 2739 1457 2739 1458 2740 1460 2740 1461 2740 1458 2741 1461 2741 1459 2741 1460 2742 1462 2742 1463 2742 1460 2743 1463 2743 1461 2743 1462 2744 1464 2744 1465 2744 1462 2745 1465 2745 1463 2745 1464 2746 1466 2746 1467 2746 1464 2747 1467 2747 1465 2747 1466 2748 1468 2748 1469 2748 1466 2749 1469 2749 1467 2749 1468 2750 1470 2750 1471 2750 1468 2751 1471 2751 1469 2751 1470 2752 1472 2752 1473 2752 1470 2753 1473 2753 1471 2753 1472 2754 1474 2754 1475 2754 1472 2755 1475 2755 1473 2755 1474 2756 1476 2756 1477 2756 1474 2757 1477 2757 1475 2757 1476 2758 1478 2758 1479 2758 1476 2759 1479 2759 1477 2759 1478 2760 1480 2760 1481 2760 1478 2761 1481 2761 1479 2761 1480 2762 1482 2762 1483 2762 1480 2763 1483 2763 1481 2763 1482 2764 1484 2764 1485 2764 1482 2765 1485 2765 1483 2765 1484 2766 1486 2766 1487 2766 1484 2767 1487 2767 1485 2767 1486 2768 1488 2768 1489 2768 1486 2769 1489 2769 1487 2769 1488 2770 1014 2770 20 2770 1488 2771 20 2771 1489 2771 1037 2772 1490 2772 1452 2772 1037 2773 1452 2773 1036 2773 1490 2774 1491 2774 1454 2774 1490 2775 1454 2775 1452 2775 1491 2776 1492 2776 1456 2776 1491 2777 1456 2777 1454 2777 1492 2778 1493 2778 1458 2778 1492 2779 1458 2779 1456 2779 1493 2780 1494 2780 1460 2780 1493 2781 1460 2781 1458 2781 1494 2782 1495 2782 1462 2782 1494 2783 1462 2783 1460 2783 1495 2784 1496 2784 1464 2784 1495 2785 1464 2785 1462 2785 1496 2786 1497 2786 1466 2786 1496 2787 1466 2787 1464 2787 1497 2788 1498 2788 1468 2788 1497 2789 1468 2789 1466 2789 1498 2790 1499 2790 1470 2790 1498 2791 1470 2791 1468 2791 1499 2792 1500 2792 1472 2792 1499 2793 1472 2793 1470 2793 1500 2794 1501 2794 1474 2794 1500 2795 1474 2795 1472 2795 1501 2796 1502 2796 1476 2796 1501 2797 1476 2797 1474 2797 1502 2798 1503 2798 1478 2798 1502 2799 1478 2799 1476 2799 1503 2800 1504 2800 1480 2800 1503 2801 1480 2801 1478 2801 1504 2802 1505 2802 1482 2802 1504 2803 1482 2803 1480 2803 1505 2804 1506 2804 1484 2804 1505 2805 1484 2805 1482 2805 1506 2806 1507 2806 1486 2806 1506 2807 1486 2807 1484 2807 1507 2808 1508 2808 1488 2808 1507 2809 1488 2809 1486 2809 1508 2810 1012 2810 1014 2810 1508 2811 1014 2811 1488 2811 1038 2812 1509 2812 1490 2812 1038 2813 1490 2813 1037 2813 1509 2814 1510 2814 1491 2814 1509 2815 1491 2815 1490 2815 1510 2816 1511 2816 1492 2816 1510 2817 1492 2817 1491 2817 1511 2818 1512 2818 1493 2818 1511 2819 1493 2819 1492 2819 1512 2820 1513 2820 1494 2820 1512 2821 1494 2821 1493 2821 1513 2822 1514 2822 1495 2822 1513 2823 1495 2823 1494 2823 1514 2824 1515 2824 1496 2824 1514 2825 1496 2825 1495 2825 1515 2826 1516 2826 1497 2826 1515 2827 1497 2827 1496 2827 1516 2828 1517 2828 1498 2828 1516 2829 1498 2829 1497 2829 1517 2830 1518 2830 1499 2830 1517 2831 1499 2831 1498 2831 1518 2832 1519 2832 1500 2832 1518 2833 1500 2833 1499 2833 1519 2834 1520 2834 1501 2834 1519 2835 1501 2835 1500 2835 1520 2836 1521 2836 1502 2836 1520 2837 1502 2837 1501 2837 1521 2838 1522 2838 1503 2838 1521 2839 1503 2839 1502 2839 1522 2840 1523 2840 1504 2840 1522 2841 1504 2841 1503 2841 1523 2842 1524 2842 1505 2842 1523 2843 1505 2843 1504 2843 1524 2844 1525 2844 1506 2844 1524 2845 1506 2845 1505 2845 1525 2846 1526 2846 1507 2846 1525 2847 1507 2847 1506 2847 1526 2848 1527 2848 1508 2848 1526 2849 1508 2849 1507 2849 1527 2850 1010 2850 1012 2850 1527 2851 1012 2851 1508 2851 1039 2852 1528 2852 1509 2852 1039 2853 1509 2853 1038 2853 1528 2854 1529 2854 1510 2854 1528 2855 1510 2855 1509 2855 1529 2856 1530 2856 1511 2856 1529 2857 1511 2857 1510 2857 1530 2858 1531 2858 1512 2858 1530 2859 1512 2859 1511 2859 1531 2860 1532 2860 1513 2860 1531 2861 1513 2861 1512 2861 1532 2862 1533 2862 1514 2862 1532 2863 1514 2863 1513 2863 1533 2864 1534 2864 1515 2864 1533 2865 1515 2865 1514 2865 1534 2866 1535 2866 1516 2866 1534 2867 1516 2867 1515 2867 1535 2868 1536 2868 1517 2868 1535 2869 1517 2869 1516 2869 1536 2870 1537 2870 1518 2870 1536 2871 1518 2871 1517 2871 1537 2872 1538 2872 1519 2872 1537 2873 1519 2873 1518 2873 1538 2874 1539 2874 1520 2874 1538 2875 1520 2875 1519 2875 1539 2876 1540 2876 1521 2876 1539 2877 1521 2877 1520 2877 1540 2878 1541 2878 1522 2878 1540 2879 1522 2879 1521 2879 1541 2880 1542 2880 1523 2880 1541 2881 1523 2881 1522 2881 1542 2882 1543 2882 1524 2882 1542 2883 1524 2883 1523 2883 1543 2884 1544 2884 1525 2884 1543 2885 1525 2885 1524 2885 1544 2886 1545 2886 1526 2886 1544 2887 1526 2887 1525 2887 1545 2888 1546 2888 1527 2888 1545 2889 1527 2889 1526 2889 1546 2890 1008 2890 1010 2890 1546 2891 1010 2891 1527 2891 1040 2892 1547 2892 1528 2892 1040 2893 1528 2893 1039 2893 1547 2894 1548 2894 1529 2894 1547 2895 1529 2895 1528 2895 1548 2896 1549 2896 1530 2896 1548 2897 1530 2897 1529 2897 1549 2898 1550 2898 1531 2898 1549 2899 1531 2899 1530 2899 1550 2900 1551 2900 1532 2900 1550 2901 1532 2901 1531 2901 1551 2902 1552 2902 1533 2902 1551 2903 1533 2903 1532 2903 1552 2904 1553 2904 1534 2904 1552 2905 1534 2905 1533 2905 1553 2906 1554 2906 1535 2906 1553 2907 1535 2907 1534 2907 1554 2908 1555 2908 1536 2908 1554 2909 1536 2909 1535 2909 1555 2910 1556 2910 1537 2910 1555 2911 1537 2911 1536 2911 1556 2912 1557 2912 1538 2912 1556 2913 1538 2913 1537 2913 1557 2914 1558 2914 1539 2914 1557 2915 1539 2915 1538 2915 1558 2916 1559 2916 1540 2916 1558 2917 1540 2917 1539 2917 1559 2918 1560 2918 1541 2918 1559 2919 1541 2919 1540 2919 1560 2920 1561 2920 1542 2920 1560 2921 1542 2921 1541 2921 1561 2922 1562 2922 1543 2922 1561 2923 1543 2923 1542 2923 1562 2924 1563 2924 1544 2924 1562 2925 1544 2925 1543 2925 1563 2926 1564 2926 1545 2926 1563 2927 1545 2927 1544 2927 1564 2928 1565 2928 1546 2928 1564 2929 1546 2929 1545 2929 1565 2930 1006 2930 1008 2930 1565 2931 1008 2931 1546 2931 1041 2932 1566 2932 1547 2932 1041 2933 1547 2933 1040 2933 1566 2934 1567 2934 1548 2934 1566 2935 1548 2935 1547 2935 1567 2936 1568 2936 1549 2936 1567 2937 1549 2937 1548 2937 1568 2938 1569 2938 1550 2938 1568 2939 1550 2939 1549 2939 1569 2940 1570 2940 1551 2940 1569 2941 1551 2941 1550 2941 1570 2942 1571 2942 1552 2942 1570 2943 1552 2943 1551 2943 1571 2944 1572 2944 1553 2944 1571 2945 1553 2945 1552 2945 1572 2946 1573 2946 1554 2946 1572 2947 1554 2947 1553 2947 1573 2948 1574 2948 1555 2948 1573 2949 1555 2949 1554 2949 1574 2950 1575 2950 1556 2950 1574 2951 1556 2951 1555 2951 1575 2952 1576 2952 1557 2952 1575 2953 1557 2953 1556 2953 1576 2954 1577 2954 1558 2954 1576 2955 1558 2955 1557 2955 1577 2956 1578 2956 1559 2956 1577 2957 1559 2957 1558 2957 1578 2958 1579 2958 1560 2958 1578 2959 1560 2959 1559 2959 1579 2960 1580 2960 1561 2960 1579 2961 1561 2961 1560 2961 1580 2962 1581 2962 1562 2962 1580 2963 1562 2963 1561 2963 1581 2964 1582 2964 1563 2964 1581 2965 1563 2965 1562 2965 1582 2966 1583 2966 1564 2966 1582 2967 1564 2967 1563 2967 1583 2968 1584 2968 1565 2968 1583 2969 1565 2969 1564 2969 1584 2970 1004 2970 1006 2970 1584 2971 1006 2971 1565 2971 1042 2972 1585 2972 1566 2972 1042 2973 1566 2973 1041 2973 1585 2974 1586 2974 1567 2974 1585 2975 1567 2975 1566 2975 1586 2976 1587 2976 1568 2976 1586 2977 1568 2977 1567 2977 1587 2978 1588 2978 1569 2978 1587 2979 1569 2979 1568 2979 1588 2980 1589 2980 1570 2980 1588 2981 1570 2981 1569 2981 1589 2982 1590 2982 1571 2982 1589 2983 1571 2983 1570 2983 1590 2984 1591 2984 1572 2984 1590 2985 1572 2985 1571 2985 1591 2986 1592 2986 1573 2986 1591 2987 1573 2987 1572 2987 1592 2988 1593 2988 1574 2988 1592 2989 1574 2989 1573 2989 1593 2990 1594 2990 1575 2990 1593 2991 1575 2991 1574 2991 1594 2992 1595 2992 1576 2992 1594 2993 1576 2993 1575 2993 1595 2994 1596 2994 1577 2994 1595 2995 1577 2995 1576 2995 1596 2996 1597 2996 1578 2996 1596 2997 1578 2997 1577 2997 1597 2998 1598 2998 1579 2998 1597 2999 1579 2999 1578 2999 1598 3000 1599 3000 1580 3000 1598 3001 1580 3001 1579 3001 1599 3002 1600 3002 1581 3002 1599 3003 1581 3003 1580 3003 1600 3004 1601 3004 1582 3004 1600 3005 1582 3005 1581 3005 1601 3006 1602 3006 1583 3006 1601 3007 1583 3007 1582 3007 1602 3008 1603 3008 1584 3008 1602 3009 1584 3009 1583 3009 1603 3010 1002 3010 1004 3010 1603 3011 1004 3011 1584 3011 1043 3012 1604 3012 1585 3012 1043 3013 1585 3013 1042 3013 1604 3014 1605 3014 1586 3014 1604 3015 1586 3015 1585 3015 1605 3016 1606 3016 1587 3016 1605 3017 1587 3017 1586 3017 1606 3018 1607 3018 1588 3018 1606 3019 1588 3019 1587 3019 1607 3020 1608 3020 1589 3020 1607 3021 1589 3021 1588 3021 1608 3022 1609 3022 1590 3022 1608 3023 1590 3023 1589 3023 1609 3024 1610 3024 1591 3024 1609 3025 1591 3025 1590 3025 1610 3026 1611 3026 1592 3026 1610 3027 1592 3027 1591 3027 1611 3028 1612 3028 1593 3028 1611 3029 1593 3029 1592 3029 1612 3030 1613 3030 1594 3030 1612 3031 1594 3031 1593 3031 1613 3032 1614 3032 1595 3032 1613 3033 1595 3033 1594 3033 1614 3034 1615 3034 1596 3034 1614 3035 1596 3035 1595 3035 1615 3036 1616 3036 1597 3036 1615 3037 1597 3037 1596 3037 1616 3038 1617 3038 1598 3038 1616 3039 1598 3039 1597 3039 1617 3040 1618 3040 1599 3040 1617 3041 1599 3041 1598 3041 1618 3042 1619 3042 1600 3042 1618 3043 1600 3043 1599 3043 1619 3044 1620 3044 1601 3044 1619 3045 1601 3045 1600 3045 1620 3046 1621 3046 1602 3046 1620 3047 1602 3047 1601 3047 1621 3048 1622 3048 1603 3048 1621 3049 1603 3049 1602 3049 1622 3050 1000 3050 1002 3050 1622 3051 1002 3051 1603 3051 1044 3052 1623 3052 1604 3052 1044 3053 1604 3053 1043 3053 1623 3054 1624 3054 1605 3054 1623 3055 1605 3055 1604 3055 1624 3056 1625 3056 1606 3056 1624 3057 1606 3057 1605 3057 1625 3058 1626 3058 1607 3058 1625 3059 1607 3059 1606 3059 1626 3060 1627 3060 1608 3060 1626 3061 1608 3061 1607 3061 1627 3062 1628 3062 1609 3062 1627 3063 1609 3063 1608 3063 1628 3064 1629 3064 1610 3064 1628 3065 1610 3065 1609 3065 1629 3066 1630 3066 1611 3066 1629 3067 1611 3067 1610 3067 1630 3068 1631 3068 1612 3068 1630 3069 1612 3069 1611 3069 1631 3070 1632 3070 1613 3070 1631 3071 1613 3071 1612 3071 1632 3072 1633 3072 1614 3072 1632 3073 1614 3073 1613 3073 1633 3074 1634 3074 1615 3074 1633 3075 1615 3075 1614 3075 1634 3076 1635 3076 1616 3076 1634 3077 1616 3077 1615 3077 1635 3078 1636 3078 1617 3078 1635 3079 1617 3079 1616 3079 1636 3080 1637 3080 1618 3080 1636 3081 1618 3081 1617 3081 1637 3082 1638 3082 1619 3082 1637 3083 1619 3083 1618 3083 1638 3084 1639 3084 1620 3084 1638 3085 1620 3085 1619 3085 1639 3086 1640 3086 1621 3086 1639 3087 1621 3087 1620 3087 1640 3088 1641 3088 1622 3088 1640 3089 1622 3089 1621 3089 1641 3090 998 3090 1000 3090 1641 3091 1000 3091 1622 3091 1045 3092 1642 3092 1623 3092 1045 3093 1623 3093 1044 3093 1642 3094 1643 3094 1624 3094 1642 3095 1624 3095 1623 3095 1643 3096 1644 3096 1625 3096 1643 3097 1625 3097 1624 3097 1644 3098 1645 3098 1626 3098 1644 3099 1626 3099 1625 3099 1645 3100 1646 3100 1627 3100 1645 3101 1627 3101 1626 3101 1646 3102 1647 3102 1628 3102 1646 3103 1628 3103 1627 3103 1647 3104 1648 3104 1629 3104 1647 3105 1629 3105 1628 3105 1648 3106 1649 3106 1630 3106 1648 3107 1630 3107 1629 3107 1649 3108 1650 3108 1631 3108 1649 3109 1631 3109 1630 3109 1650 3110 1651 3110 1632 3110 1650 3111 1632 3111 1631 3111 1651 3112 1652 3112 1633 3112 1651 3113 1633 3113 1632 3113 1652 3114 1653 3114 1634 3114 1652 3115 1634 3115 1633 3115 1653 3116 1654 3116 1635 3116 1653 3117 1635 3117 1634 3117 1654 3118 1655 3118 1636 3118 1654 3119 1636 3119 1635 3119 1655 3120 1656 3120 1637 3120 1655 3121 1637 3121 1636 3121 1656 3122 1657 3122 1638 3122 1656 3123 1638 3123 1637 3123 1657 3124 1658 3124 1639 3124 1657 3125 1639 3125 1638 3125 1658 3126 1659 3126 1640 3126 1658 3127 1640 3127 1639 3127 1659 3128 1660 3128 1641 3128 1659 3129 1641 3129 1640 3129 1660 3130 996 3130 998 3130 1660 3131 998 3131 1641 3131 1046 3132 1661 3132 1642 3132 1046 3133 1642 3133 1045 3133 1661 3134 1662 3134 1643 3134 1661 3135 1643 3135 1642 3135 1662 3136 1663 3136 1644 3136 1662 3137 1644 3137 1643 3137 1663 3138 1664 3138 1645 3138 1663 3139 1645 3139 1644 3139 1664 3140 1665 3140 1646 3140 1664 3141 1646 3141 1645 3141 1665 3142 1666 3142 1647 3142 1665 3143 1647 3143 1646 3143 1666 3144 1667 3144 1648 3144 1666 3145 1648 3145 1647 3145 1667 3146 1668 3146 1649 3146 1667 3147 1649 3147 1648 3147 1668 3148 1669 3148 1650 3148 1668 3149 1650 3149 1649 3149 1669 3150 1670 3150 1651 3150 1669 3151 1651 3151 1650 3151 1670 3152 1671 3152 1652 3152 1670 3153 1652 3153 1651 3153 1671 3154 1672 3154 1653 3154 1671 3155 1653 3155 1652 3155 1672 3156 1673 3156 1654 3156 1672 3157 1654 3157 1653 3157 1673 3158 1674 3158 1655 3158 1673 3159 1655 3159 1654 3159 1674 3160 1675 3160 1656 3160 1674 3161 1656 3161 1655 3161 1675 3162 1676 3162 1657 3162 1675 3163 1657 3163 1656 3163 1676 3164 1677 3164 1658 3164 1676 3165 1658 3165 1657 3165 1677 3166 1678 3166 1659 3166 1677 3167 1659 3167 1658 3167 1678 3168 1679 3168 1660 3168 1678 3169 1660 3169 1659 3169 1679 3170 994 3170 996 3170 1679 3171 996 3171 1660 3171 1047 3172 1680 3172 1661 3172 1047 3173 1661 3173 1046 3173 1680 3174 1681 3174 1662 3174 1680 3175 1662 3175 1661 3175 1681 3176 1682 3176 1663 3176 1681 3177 1663 3177 1662 3177 1682 3178 1683 3178 1664 3178 1682 3179 1664 3179 1663 3179 1683 3180 1684 3180 1665 3180 1683 3181 1665 3181 1664 3181 1684 3182 1685 3182 1666 3182 1684 3183 1666 3183 1665 3183 1685 3184 1686 3184 1667 3184 1685 3185 1667 3185 1666 3185 1686 3186 1687 3186 1668 3186 1686 3187 1668 3187 1667 3187 1687 3188 1688 3188 1669 3188 1687 3189 1669 3189 1668 3189 1688 3190 1689 3190 1670 3190 1688 3191 1670 3191 1669 3191 1689 3192 1690 3192 1671 3192 1689 3193 1671 3193 1670 3193 1690 3194 1691 3194 1672 3194 1690 3195 1672 3195 1671 3195 1691 3196 1692 3196 1673 3196 1691 3197 1673 3197 1672 3197 1692 3198 1693 3198 1674 3198 1692 3199 1674 3199 1673 3199 1693 3200 1694 3200 1675 3200 1693 3201 1675 3201 1674 3201 1694 3202 1695 3202 1676 3202 1694 3203 1676 3203 1675 3203 1695 3204 1696 3204 1677 3204 1695 3205 1677 3205 1676 3205 1696 3206 1697 3206 1678 3206 1696 3207 1678 3207 1677 3207 1697 3208 1698 3208 1679 3208 1697 3209 1679 3209 1678 3209 1698 3210 992 3210 994 3210 1698 3211 994 3211 1679 3211 1048 3212 1699 3212 1680 3212 1048 3213 1680 3213 1047 3213 1699 3214 1700 3214 1681 3214 1699 3215 1681 3215 1680 3215 1700 3216 1701 3216 1682 3216 1700 3217 1682 3217 1681 3217 1701 3218 1702 3218 1683 3218 1701 3219 1683 3219 1682 3219 1702 3220 1703 3220 1684 3220 1702 3221 1684 3221 1683 3221 1703 3222 1704 3222 1685 3222 1703 3223 1685 3223 1684 3223 1704 3224 1705 3224 1686 3224 1704 3225 1686 3225 1685 3225 1705 3226 1706 3226 1687 3226 1705 3227 1687 3227 1686 3227 1706 3228 1707 3228 1688 3228 1706 3229 1688 3229 1687 3229 1707 3230 1708 3230 1689 3230 1707 3231 1689 3231 1688 3231 1708 3232 1709 3232 1690 3232 1708 3233 1690 3233 1689 3233 1709 3234 1710 3234 1691 3234 1709 3235 1691 3235 1690 3235 1710 3236 1711 3236 1692 3236 1710 3237 1692 3237 1691 3237 1711 3238 1712 3238 1693 3238 1711 3239 1693 3239 1692 3239 1712 3240 1713 3240 1694 3240 1712 3241 1694 3241 1693 3241 1713 3242 1714 3242 1695 3242 1713 3243 1695 3243 1694 3243 1714 3244 1715 3244 1696 3244 1714 3245 1696 3245 1695 3245 1715 3246 1716 3246 1697 3246 1715 3247 1697 3247 1696 3247 1716 3248 1717 3248 1698 3248 1716 3249 1698 3249 1697 3249 1717 3250 990 3250 992 3250 1717 3251 992 3251 1698 3251 1049 3252 1718 3252 1699 3252 1049 3253 1699 3253 1048 3253 1718 3254 1719 3254 1700 3254 1718 3255 1700 3255 1699 3255 1719 3256 1720 3256 1701 3256 1719 3257 1701 3257 1700 3257 1720 3258 1721 3258 1702 3258 1720 3259 1702 3259 1701 3259 1721 3260 1722 3260 1703 3260 1721 3261 1703 3261 1702 3261 1722 3262 1723 3262 1704 3262 1722 3263 1704 3263 1703 3263 1723 3264 1724 3264 1705 3264 1723 3265 1705 3265 1704 3265 1724 3266 1725 3266 1706 3266 1724 3267 1706 3267 1705 3267 1725 3268 1726 3268 1707 3268 1725 3269 1707 3269 1706 3269 1726 3270 1727 3270 1708 3270 1726 3271 1708 3271 1707 3271 1727 3272 1728 3272 1709 3272 1727 3273 1709 3273 1708 3273 1728 3274 1729 3274 1710 3274 1728 3275 1710 3275 1709 3275 1729 3276 1730 3276 1711 3276 1729 3277 1711 3277 1710 3277 1730 3278 1731 3278 1712 3278 1730 3279 1712 3279 1711 3279 1731 3280 1732 3280 1713 3280 1731 3281 1713 3281 1712 3281 1732 3282 1733 3282 1714 3282 1732 3283 1714 3283 1713 3283 1733 3284 1734 3284 1715 3284 1733 3285 1715 3285 1714 3285 1734 3286 1735 3286 1716 3286 1734 3287 1716 3287 1715 3287 1735 3288 1736 3288 1717 3288 1735 3289 1717 3289 1716 3289 1736 3290 988 3290 990 3290 1736 3291 990 3291 1717 3291 1050 3292 1737 3292 1718 3292 1050 3293 1718 3293 1049 3293 1737 3294 1738 3294 1719 3294 1737 3295 1719 3295 1718 3295 1738 3296 1739 3296 1720 3296 1738 3297 1720 3297 1719 3297 1739 3298 1740 3298 1721 3298 1739 3299 1721 3299 1720 3299 1740 3300 1741 3300 1722 3300 1740 3301 1722 3301 1721 3301 1741 3302 1742 3302 1723 3302 1741 3303 1723 3303 1722 3303 1742 3304 1743 3304 1724 3304 1742 3305 1724 3305 1723 3305 1743 3306 1744 3306 1725 3306 1743 3307 1725 3307 1724 3307 1744 3308 1745 3308 1726 3308 1744 3309 1726 3309 1725 3309 1745 3310 1746 3310 1727 3310 1745 3311 1727 3311 1726 3311 1746 3312 1747 3312 1728 3312 1746 3313 1728 3313 1727 3313 1747 3314 1748 3314 1729 3314 1747 3315 1729 3315 1728 3315 1748 3316 1749 3316 1730 3316 1748 3317 1730 3317 1729 3317 1749 3318 1750 3318 1731 3318 1749 3319 1731 3319 1730 3319 1750 3320 1751 3320 1732 3320 1750 3321 1732 3321 1731 3321 1751 3322 1752 3322 1733 3322 1751 3323 1733 3323 1732 3323 1752 3324 1753 3324 1734 3324 1752 3325 1734 3325 1733 3325 1753 3326 1754 3326 1735 3326 1753 3327 1735 3327 1734 3327 1754 3328 1755 3328 1736 3328 1754 3329 1736 3329 1735 3329 1755 3330 986 3330 988 3330 1755 3331 988 3331 1736 3331 1051 3332 1756 3332 1737 3332 1051 3333 1737 3333 1050 3333 1756 3334 1757 3334 1738 3334 1756 3335 1738 3335 1737 3335 1757 3336 1758 3336 1739 3336 1757 3337 1739 3337 1738 3337 1758 3338 1759 3338 1740 3338 1758 3339 1740 3339 1739 3339 1759 3340 1760 3340 1741 3340 1759 3341 1741 3341 1740 3341 1760 3342 1761 3342 1742 3342 1760 3343 1742 3343 1741 3343 1761 3344 1762 3344 1743 3344 1761 3345 1743 3345 1742 3345 1762 3346 1763 3346 1744 3346 1762 3347 1744 3347 1743 3347 1763 3348 1764 3348 1745 3348 1763 3349 1745 3349 1744 3349 1764 3350 1765 3350 1746 3350 1764 3351 1746 3351 1745 3351 1765 3352 1766 3352 1747 3352 1765 3353 1747 3353 1746 3353 1766 3354 1767 3354 1748 3354 1766 3355 1748 3355 1747 3355 1767 3356 1768 3356 1749 3356 1767 3357 1749 3357 1748 3357 1768 3358 1769 3358 1750 3358 1768 3359 1750 3359 1749 3359 1769 3360 1770 3360 1751 3360 1769 3361 1751 3361 1750 3361 1770 3362 1771 3362 1752 3362 1770 3363 1752 3363 1751 3363 1771 3364 1772 3364 1753 3364 1771 3365 1753 3365 1752 3365 1772 3366 1773 3366 1754 3366 1772 3367 1754 3367 1753 3367 1773 3368 1774 3368 1755 3368 1773 3369 1755 3369 1754 3369 1774 3370 984 3370 986 3370 1774 3371 986 3371 1755 3371 1052 3372 1775 3372 1756 3372 1052 3373 1756 3373 1051 3373 1775 3374 1776 3374 1757 3374 1775 3375 1757 3375 1756 3375 1776 3376 1777 3376 1758 3376 1776 3377 1758 3377 1757 3377 1777 3378 1778 3378 1759 3378 1777 3379 1759 3379 1758 3379 1778 3380 1779 3380 1760 3380 1778 3381 1760 3381 1759 3381 1779 3382 1780 3382 1761 3382 1779 3383 1761 3383 1760 3383 1780 3384 1781 3384 1762 3384 1780 3385 1762 3385 1761 3385 1781 3386 1782 3386 1763 3386 1781 3387 1763 3387 1762 3387 1782 3388 1783 3388 1764 3388 1782 3389 1764 3389 1763 3389 1783 3390 1784 3390 1765 3390 1783 3391 1765 3391 1764 3391 1784 3392 1785 3392 1766 3392 1784 3393 1766 3393 1765 3393 1785 3394 1786 3394 1767 3394 1785 3395 1767 3395 1766 3395 1786 3396 1787 3396 1768 3396 1786 3397 1768 3397 1767 3397 1787 3398 1788 3398 1769 3398 1787 3399 1769 3399 1768 3399 1788 3400 1789 3400 1770 3400 1788 3401 1770 3401 1769 3401 1789 3402 1790 3402 1771 3402 1789 3403 1771 3403 1770 3403 1790 3404 1791 3404 1772 3404 1790 3405 1772 3405 1771 3405 1791 3406 1792 3406 1773 3406 1791 3407 1773 3407 1772 3407 1792 3408 1793 3408 1774 3408 1792 3409 1774 3409 1773 3409 1793 3410 982 3410 984 3410 1793 3411 984 3411 1774 3411 1053 3412 1794 3412 1775 3412 1053 3413 1775 3413 1052 3413 1794 3414 1795 3414 1776 3414 1794 3415 1776 3415 1775 3415 1795 3416 1796 3416 1777 3416 1795 3417 1777 3417 1776 3417 1796 3418 1797 3418 1778 3418 1796 3419 1778 3419 1777 3419 1797 3420 1798 3420 1779 3420 1797 3421 1779 3421 1778 3421 1798 3422 1799 3422 1780 3422 1798 3423 1780 3423 1779 3423 1799 3424 1800 3424 1781 3424 1799 3425 1781 3425 1780 3425 1800 3426 1801 3426 1782 3426 1800 3427 1782 3427 1781 3427 1801 3428 1802 3428 1783 3428 1801 3429 1783 3429 1782 3429 1802 3430 1803 3430 1784 3430 1802 3431 1784 3431 1783 3431 1803 3432 1804 3432 1785 3432 1803 3433 1785 3433 1784 3433 1804 3434 1805 3434 1786 3434 1804 3435 1786 3435 1785 3435 1805 3436 1806 3436 1787 3436 1805 3437 1787 3437 1786 3437 1806 3438 1807 3438 1788 3438 1806 3439 1788 3439 1787 3439 1807 3440 1808 3440 1789 3440 1807 3441 1789 3441 1788 3441 1808 3442 1809 3442 1790 3442 1808 3443 1790 3443 1789 3443 1809 3444 1810 3444 1791 3444 1809 3445 1791 3445 1790 3445 1810 3446 1811 3446 1792 3446 1810 3447 1792 3447 1791 3447 1811 3448 1812 3448 1793 3448 1811 3449 1793 3449 1792 3449 1812 3450 980 3450 982 3450 1812 3451 982 3451 1793 3451 7 3452 1813 3452 1794 3452 7 3453 1794 3453 1053 3453 1813 3454 1814 3454 1795 3454 1813 3455 1795 3455 1794 3455 1814 3456 1815 3456 1796 3456 1814 3457 1796 3457 1795 3457 1815 3458 1816 3458 1797 3458 1815 3459 1797 3459 1796 3459 1816 3460 1817 3460 1798 3460 1816 3461 1798 3461 1797 3461 1817 3462 1818 3462 1799 3462 1817 3463 1799 3463 1798 3463 1818 3464 1819 3464 1800 3464 1818 3465 1800 3465 1799 3465 1819 3466 1820 3466 1801 3466 1819 3467 1801 3467 1800 3467 1820 3468 1821 3468 1802 3468 1820 3469 1802 3469 1801 3469 1821 3470 1822 3470 1803 3470 1821 3471 1803 3471 1802 3471 1822 3472 1823 3472 1804 3472 1822 3473 1804 3473 1803 3473 1823 3474 1824 3474 1805 3474 1823 3475 1805 3475 1804 3475 1824 3476 1825 3476 1806 3476 1824 3477 1806 3477 1805 3477 1825 3478 1826 3478 1807 3478 1825 3479 1807 3479 1806 3479 1826 3480 1827 3480 1808 3480 1826 3481 1808 3481 1807 3481 1827 3482 1828 3482 1809 3482 1827 3483 1809 3483 1808 3483 1828 3484 1829 3484 1810 3484 1828 3485 1810 3485 1809 3485 1829 3486 1830 3486 1811 3486 1829 3487 1811 3487 1810 3487 1830 3488 1831 3488 1812 3488 1830 3489 1812 3489 1811 3489 1831 3490 978 3490 980 3490 1831 3491 980 3491 1812 3491 6 3492 1832 3492 1813 3492 6 3493 1813 3493 7 3493 1832 3494 1833 3494 1814 3494 1832 3495 1814 3495 1813 3495 1833 3496 1834 3496 1815 3496 1833 3497 1815 3497 1814 3497 1834 3498 1835 3498 1816 3498 1834 3499 1816 3499 1815 3499 1835 3500 1836 3500 1817 3500 1835 3501 1817 3501 1816 3501 1836 3502 1837 3502 1818 3502 1836 3503 1818 3503 1817 3503 1837 3504 1838 3504 1819 3504 1837 3505 1819 3505 1818 3505 1838 3506 1839 3506 1820 3506 1838 3507 1820 3507 1819 3507 1839 3508 1840 3508 1821 3508 1839 3509 1821 3509 1820 3509 1840 3510 1841 3510 1822 3510 1840 3511 1822 3511 1821 3511 1841 3512 1842 3512 1823 3512 1841 3513 1823 3513 1822 3513 1842 3514 1843 3514 1824 3514 1842 3515 1824 3515 1823 3515 1843 3516 1844 3516 1825 3516 1843 3517 1825 3517 1824 3517 1844 3518 1845 3518 1826 3518 1844 3519 1826 3519 1825 3519 1845 3520 1846 3520 1827 3520 1845 3521 1827 3521 1826 3521 1846 3522 1847 3522 1828 3522 1846 3523 1828 3523 1827 3523 1847 3524 1848 3524 1829 3524 1847 3525 1829 3525 1828 3525 1848 3526 1849 3526 1830 3526 1848 3527 1830 3527 1829 3527 1849 3528 1850 3528 1831 3528 1849 3529 1831 3529 1830 3529 1850 3530 11 3530 978 3530 1850 3531 978 3531 1831 3531 60 3532 1851 3532 1852 3532 60 3533 1852 3533 13 3533 1851 3534 1853 3534 1854 3534 1851 3535 1854 3535 1852 3535 1853 3536 1855 3536 1856 3536 1853 3537 1856 3537 1854 3537 1855 3538 1857 3538 1858 3538 1855 3539 1858 3539 1856 3539 1857 3540 1859 3540 1860 3540 1857 3541 1860 3541 1858 3541 1859 3542 1861 3542 1862 3542 1859 3543 1862 3543 1860 3543 1861 3544 1863 3544 1864 3544 1861 3545 1864 3545 1862 3545 1863 3546 1865 3546 1866 3546 1863 3547 1866 3547 1864 3547 1865 3548 1867 3548 1868 3548 1865 3549 1868 3549 1866 3549 1867 3550 1869 3550 1870 3550 1867 3551 1870 3551 1868 3551 1869 3552 1871 3552 1872 3552 1869 3553 1872 3553 1870 3553 1871 3554 1873 3554 1874 3554 1871 3555 1874 3555 1872 3555 1873 3556 1875 3556 1876 3556 1873 3557 1876 3557 1874 3557 1875 3558 1877 3558 1878 3558 1875 3559 1878 3559 1876 3559 1877 3560 1879 3560 1880 3560 1877 3561 1880 3561 1878 3561 1879 3562 1881 3562 1882 3562 1879 3563 1882 3563 1880 3563 1881 3564 1883 3564 1884 3564 1881 3565 1884 3565 1882 3565 1883 3566 1885 3566 1886 3566 1883 3567 1886 3567 1884 3567 1885 3568 1887 3568 1888 3568 1885 3569 1888 3569 1886 3569 1887 3570 179 3570 0 3570 1887 3571 0 3571 1888 3571 58 3572 1889 3572 1851 3572 58 3573 1851 3573 60 3573 1889 3574 1890 3574 1853 3574 1889 3575 1853 3575 1851 3575 1890 3576 1891 3576 1855 3576 1890 3577 1855 3577 1853 3577 1891 3578 1892 3578 1857 3578 1891 3579 1857 3579 1855 3579 1892 3580 1893 3580 1859 3580 1892 3581 1859 3581 1857 3581 1893 3582 1894 3582 1861 3582 1893 3583 1861 3583 1859 3583 1894 3584 1895 3584 1863 3584 1894 3585 1863 3585 1861 3585 1895 3586 1896 3586 1865 3586 1895 3587 1865 3587 1863 3587 1896 3588 1897 3588 1867 3588 1896 3589 1867 3589 1865 3589 1897 3590 1898 3590 1869 3590 1897 3591 1869 3591 1867 3591 1898 3592 1899 3592 1871 3592 1898 3593 1871 3593 1869 3593 1899 3594 1900 3594 1873 3594 1899 3595 1873 3595 1871 3595 1900 3596 1901 3596 1875 3596 1900 3597 1875 3597 1873 3597 1901 3598 1902 3598 1877 3598 1901 3599 1877 3599 1875 3599 1902 3600 1903 3600 1879 3600 1902 3601 1879 3601 1877 3601 1903 3602 1904 3602 1881 3602 1903 3603 1881 3603 1879 3603 1904 3604 1905 3604 1883 3604 1904 3605 1883 3605 1881 3605 1905 3606 1906 3606 1885 3606 1905 3607 1885 3607 1883 3607 1906 3608 1907 3608 1887 3608 1906 3609 1887 3609 1885 3609 1907 3610 177 3610 179 3610 1907 3611 179 3611 1887 3611 56 3612 1908 3612 1889 3612 56 3613 1889 3613 58 3613 1908 3614 1909 3614 1890 3614 1908 3615 1890 3615 1889 3615 1909 3616 1910 3616 1891 3616 1909 3617 1891 3617 1890 3617 1910 3618 1911 3618 1892 3618 1910 3619 1892 3619 1891 3619 1911 3620 1912 3620 1893 3620 1911 3621 1893 3621 1892 3621 1912 3622 1913 3622 1894 3622 1912 3623 1894 3623 1893 3623 1913 3624 1914 3624 1895 3624 1913 3625 1895 3625 1894 3625 1914 3626 1915 3626 1896 3626 1914 3627 1896 3627 1895 3627 1915 3628 1916 3628 1897 3628 1915 3629 1897 3629 1896 3629 1916 3630 1917 3630 1898 3630 1916 3631 1898 3631 1897 3631 1917 3632 1918 3632 1899 3632 1917 3633 1899 3633 1898 3633 1918 3634 1919 3634 1900 3634 1918 3635 1900 3635 1899 3635 1919 3636 1920 3636 1901 3636 1919 3637 1901 3637 1900 3637 1920 3638 1921 3638 1902 3638 1920 3639 1902 3639 1901 3639 1921 3640 1922 3640 1903 3640 1921 3641 1903 3641 1902 3641 1922 3642 1923 3642 1904 3642 1922 3643 1904 3643 1903 3643 1923 3644 1924 3644 1905 3644 1923 3645 1905 3645 1904 3645 1924 3646 1925 3646 1906 3646 1924 3647 1906 3647 1905 3647 1925 3648 1926 3648 1907 3648 1925 3649 1907 3649 1906 3649 1926 3650 175 3650 177 3650 1926 3651 177 3651 1907 3651 54 3652 1927 3652 1908 3652 54 3653 1908 3653 56 3653 1927 3654 1928 3654 1909 3654 1927 3655 1909 3655 1908 3655 1928 3656 1929 3656 1910 3656 1928 3657 1910 3657 1909 3657 1929 3658 1930 3658 1911 3658 1929 3659 1911 3659 1910 3659 1930 3660 1931 3660 1912 3660 1930 3661 1912 3661 1911 3661 1931 3662 1932 3662 1913 3662 1931 3663 1913 3663 1912 3663 1932 3664 1933 3664 1914 3664 1932 3665 1914 3665 1913 3665 1933 3666 1934 3666 1915 3666 1933 3667 1915 3667 1914 3667 1934 3668 1935 3668 1916 3668 1934 3669 1916 3669 1915 3669 1935 3670 1936 3670 1917 3670 1935 3671 1917 3671 1916 3671 1936 3672 1937 3672 1918 3672 1936 3673 1918 3673 1917 3673 1937 3674 1938 3674 1919 3674 1937 3675 1919 3675 1918 3675 1938 3676 1939 3676 1920 3676 1938 3677 1920 3677 1919 3677 1939 3678 1940 3678 1921 3678 1939 3679 1921 3679 1920 3679 1940 3680 1941 3680 1922 3680 1940 3681 1922 3681 1921 3681 1941 3682 1942 3682 1923 3682 1941 3683 1923 3683 1922 3683 1942 3684 1943 3684 1924 3684 1942 3685 1924 3685 1923 3685 1943 3686 1944 3686 1925 3686 1943 3687 1925 3687 1924 3687 1944 3688 1945 3688 1926 3688 1944 3689 1926 3689 1925 3689 1945 3690 173 3690 175 3690 1945 3691 175 3691 1926 3691 52 3692 1946 3692 1927 3692 52 3693 1927 3693 54 3693 1946 3694 1947 3694 1928 3694 1946 3695 1928 3695 1927 3695 1947 3696 1948 3696 1929 3696 1947 3697 1929 3697 1928 3697 1948 3698 1949 3698 1930 3698 1948 3699 1930 3699 1929 3699 1949 3700 1950 3700 1931 3700 1949 3701 1931 3701 1930 3701 1950 3702 1951 3702 1932 3702 1950 3703 1932 3703 1931 3703 1951 3704 1952 3704 1933 3704 1951 3705 1933 3705 1932 3705 1952 3706 1953 3706 1934 3706 1952 3707 1934 3707 1933 3707 1953 3708 1954 3708 1935 3708 1953 3709 1935 3709 1934 3709 1954 3710 1955 3710 1936 3710 1954 3711 1936 3711 1935 3711 1955 3712 1956 3712 1937 3712 1955 3713 1937 3713 1936 3713 1956 3714 1957 3714 1938 3714 1956 3715 1938 3715 1937 3715 1957 3716 1958 3716 1939 3716 1957 3717 1939 3717 1938 3717 1958 3718 1959 3718 1940 3718 1958 3719 1940 3719 1939 3719 1959 3720 1960 3720 1941 3720 1959 3721 1941 3721 1940 3721 1960 3722 1961 3722 1942 3722 1960 3723 1942 3723 1941 3723 1961 3724 1962 3724 1943 3724 1961 3725 1943 3725 1942 3725 1962 3726 1963 3726 1944 3726 1962 3727 1944 3727 1943 3727 1963 3728 1964 3728 1945 3728 1963 3729 1945 3729 1944 3729 1964 3730 171 3730 173 3730 1964 3731 173 3731 1945 3731 50 3732 1965 3732 1946 3732 50 3733 1946 3733 52 3733 1965 3734 1966 3734 1947 3734 1965 3735 1947 3735 1946 3735 1966 3736 1967 3736 1948 3736 1966 3737 1948 3737 1947 3737 1967 3738 1968 3738 1949 3738 1967 3739 1949 3739 1948 3739 1968 3740 1969 3740 1950 3740 1968 3741 1950 3741 1949 3741 1969 3742 1970 3742 1951 3742 1969 3743 1951 3743 1950 3743 1970 3744 1971 3744 1952 3744 1970 3745 1952 3745 1951 3745 1971 3746 1972 3746 1953 3746 1971 3747 1953 3747 1952 3747 1972 3748 1973 3748 1954 3748 1972 3749 1954 3749 1953 3749 1973 3750 1974 3750 1955 3750 1973 3751 1955 3751 1954 3751 1974 3752 1975 3752 1956 3752 1974 3753 1956 3753 1955 3753 1975 3754 1976 3754 1957 3754 1975 3755 1957 3755 1956 3755 1976 3756 1977 3756 1958 3756 1976 3757 1958 3757 1957 3757 1977 3758 1978 3758 1959 3758 1977 3759 1959 3759 1958 3759 1978 3760 1979 3760 1960 3760 1978 3761 1960 3761 1959 3761 1979 3762 1980 3762 1961 3762 1979 3763 1961 3763 1960 3763 1980 3764 1981 3764 1962 3764 1980 3765 1962 3765 1961 3765 1981 3766 1982 3766 1963 3766 1981 3767 1963 3767 1962 3767 1982 3768 1983 3768 1964 3768 1982 3769 1964 3769 1963 3769 1983 3770 169 3770 171 3770 1983 3771 171 3771 1964 3771 48 3772 1984 3772 1965 3772 48 3773 1965 3773 50 3773 1984 3774 1985 3774 1966 3774 1984 3775 1966 3775 1965 3775 1985 3776 1986 3776 1967 3776 1985 3777 1967 3777 1966 3777 1986 3778 1987 3778 1968 3778 1986 3779 1968 3779 1967 3779 1987 3780 1988 3780 1969 3780 1987 3781 1969 3781 1968 3781 1988 3782 1989 3782 1970 3782 1988 3783 1970 3783 1969 3783 1989 3784 1990 3784 1971 3784 1989 3785 1971 3785 1970 3785 1990 3786 1991 3786 1972 3786 1990 3787 1972 3787 1971 3787 1991 3788 1992 3788 1973 3788 1991 3789 1973 3789 1972 3789 1992 3790 1993 3790 1974 3790 1992 3791 1974 3791 1973 3791 1993 3792 1994 3792 1975 3792 1993 3793 1975 3793 1974 3793 1994 3794 1995 3794 1976 3794 1994 3795 1976 3795 1975 3795 1995 3796 1996 3796 1977 3796 1995 3797 1977 3797 1976 3797 1996 3798 1997 3798 1978 3798 1996 3799 1978 3799 1977 3799 1997 3800 1998 3800 1979 3800 1997 3801 1979 3801 1978 3801 1998 3802 1999 3802 1980 3802 1998 3803 1980 3803 1979 3803 1999 3804 2000 3804 1981 3804 1999 3805 1981 3805 1980 3805 2000 3806 2001 3806 1982 3806 2000 3807 1982 3807 1981 3807 2001 3808 2002 3808 1983 3808 2001 3809 1983 3809 1982 3809 2002 3810 167 3810 169 3810 2002 3811 169 3811 1983 3811 46 3812 2003 3812 1984 3812 46 3813 1984 3813 48 3813 2003 3814 2004 3814 1985 3814 2003 3815 1985 3815 1984 3815 2004 3816 2005 3816 1986 3816 2004 3817 1986 3817 1985 3817 2005 3818 2006 3818 1987 3818 2005 3819 1987 3819 1986 3819 2006 3820 2007 3820 1988 3820 2006 3821 1988 3821 1987 3821 2007 3822 2008 3822 1989 3822 2007 3823 1989 3823 1988 3823 2008 3824 2009 3824 1990 3824 2008 3825 1990 3825 1989 3825 2009 3826 2010 3826 1991 3826 2009 3827 1991 3827 1990 3827 2010 3828 2011 3828 1992 3828 2010 3829 1992 3829 1991 3829 2011 3830 2012 3830 1993 3830 2011 3831 1993 3831 1992 3831 2012 3832 2013 3832 1994 3832 2012 3833 1994 3833 1993 3833 2013 3834 2014 3834 1995 3834 2013 3835 1995 3835 1994 3835 2014 3836 2015 3836 1996 3836 2014 3837 1996 3837 1995 3837 2015 3838 2016 3838 1997 3838 2015 3839 1997 3839 1996 3839 2016 3840 2017 3840 1998 3840 2016 3841 1998 3841 1997 3841 2017 3842 2018 3842 1999 3842 2017 3843 1999 3843 1998 3843 2018 3844 2019 3844 2000 3844 2018 3845 2000 3845 1999 3845 2019 3846 2020 3846 2001 3846 2019 3847 2001 3847 2000 3847 2020 3848 2021 3848 2002 3848 2020 3849 2002 3849 2001 3849 2021 3850 165 3850 167 3850 2021 3851 167 3851 2002 3851 44 3852 2022 3852 2003 3852 44 3853 2003 3853 46 3853 2022 3854 2023 3854 2004 3854 2022 3855 2004 3855 2003 3855 2023 3856 2024 3856 2005 3856 2023 3857 2005 3857 2004 3857 2024 3858 2025 3858 2006 3858 2024 3859 2006 3859 2005 3859 2025 3860 2026 3860 2007 3860 2025 3861 2007 3861 2006 3861 2026 3862 2027 3862 2008 3862 2026 3863 2008 3863 2007 3863 2027 3864 2028 3864 2009 3864 2027 3865 2009 3865 2008 3865 2028 3866 2029 3866 2010 3866 2028 3867 2010 3867 2009 3867 2029 3868 2030 3868 2011 3868 2029 3869 2011 3869 2010 3869 2030 3870 2031 3870 2012 3870 2030 3871 2012 3871 2011 3871 2031 3872 2032 3872 2013 3872 2031 3873 2013 3873 2012 3873 2032 3874 2033 3874 2014 3874 2032 3875 2014 3875 2013 3875 2033 3876 2034 3876 2015 3876 2033 3877 2015 3877 2014 3877 2034 3878 2035 3878 2016 3878 2034 3879 2016 3879 2015 3879 2035 3880 2036 3880 2017 3880 2035 3881 2017 3881 2016 3881 2036 3882 2037 3882 2018 3882 2036 3883 2018 3883 2017 3883 2037 3884 2038 3884 2019 3884 2037 3885 2019 3885 2018 3885 2038 3886 2039 3886 2020 3886 2038 3887 2020 3887 2019 3887 2039 3888 2040 3888 2021 3888 2039 3889 2021 3889 2020 3889 2040 3890 163 3890 165 3890 2040 3891 165 3891 2021 3891 42 3892 2041 3892 2022 3892 42 3893 2022 3893 44 3893 2041 3894 2042 3894 2023 3894 2041 3895 2023 3895 2022 3895 2042 3896 2043 3896 2024 3896 2042 3897 2024 3897 2023 3897 2043 3898 2044 3898 2025 3898 2043 3899 2025 3899 2024 3899 2044 3900 2045 3900 2026 3900 2044 3901 2026 3901 2025 3901 2045 3902 2046 3902 2027 3902 2045 3903 2027 3903 2026 3903 2046 3904 2047 3904 2028 3904 2046 3905 2028 3905 2027 3905 2047 3906 2048 3906 2029 3906 2047 3907 2029 3907 2028 3907 2048 3908 2049 3908 2030 3908 2048 3909 2030 3909 2029 3909 2049 3910 2050 3910 2031 3910 2049 3911 2031 3911 2030 3911 2050 3912 2051 3912 2032 3912 2050 3913 2032 3913 2031 3913 2051 3914 2052 3914 2033 3914 2051 3915 2033 3915 2032 3915 2052 3916 2053 3916 2034 3916 2052 3917 2034 3917 2033 3917 2053 3918 2054 3918 2035 3918 2053 3919 2035 3919 2034 3919 2054 3920 2055 3920 2036 3920 2054 3921 2036 3921 2035 3921 2055 3922 2056 3922 2037 3922 2055 3923 2037 3923 2036 3923 2056 3924 2057 3924 2038 3924 2056 3925 2038 3925 2037 3925 2057 3926 2058 3926 2039 3926 2057 3927 2039 3927 2038 3927 2058 3928 2059 3928 2040 3928 2058 3929 2040 3929 2039 3929 2059 3930 161 3930 163 3930 2059 3931 163 3931 2040 3931 40 3932 2060 3932 2041 3932 40 3933 2041 3933 42 3933 2060 3934 2061 3934 2042 3934 2060 3935 2042 3935 2041 3935 2061 3936 2062 3936 2043 3936 2061 3937 2043 3937 2042 3937 2062 3938 2063 3938 2044 3938 2062 3939 2044 3939 2043 3939 2063 3940 2064 3940 2045 3940 2063 3941 2045 3941 2044 3941 2064 3942 2065 3942 2046 3942 2064 3943 2046 3943 2045 3943 2065 3944 2066 3944 2047 3944 2065 3945 2047 3945 2046 3945 2066 3946 2067 3946 2048 3946 2066 3947 2048 3947 2047 3947 2067 3948 2068 3948 2049 3948 2067 3949 2049 3949 2048 3949 2068 3950 2069 3950 2050 3950 2068 3951 2050 3951 2049 3951 2069 3952 2070 3952 2051 3952 2069 3953 2051 3953 2050 3953 2070 3954 2071 3954 2052 3954 2070 3955 2052 3955 2051 3955 2071 3956 2072 3956 2053 3956 2071 3957 2053 3957 2052 3957 2072 3958 2073 3958 2054 3958 2072 3959 2054 3959 2053 3959 2073 3960 2074 3960 2055 3960 2073 3961 2055 3961 2054 3961 2074 3962 2075 3962 2056 3962 2074 3963 2056 3963 2055 3963 2075 3964 2076 3964 2057 3964 2075 3965 2057 3965 2056 3965 2076 3966 2077 3966 2058 3966 2076 3967 2058 3967 2057 3967 2077 3968 2078 3968 2059 3968 2077 3969 2059 3969 2058 3969 2078 3970 159 3970 161 3970 2078 3971 161 3971 2059 3971 38 3972 2079 3972 2060 3972 38 3973 2060 3973 40 3973 2079 3974 2080 3974 2061 3974 2079 3975 2061 3975 2060 3975 2080 3976 2081 3976 2062 3976 2080 3977 2062 3977 2061 3977 2081 3978 2082 3978 2063 3978 2081 3979 2063 3979 2062 3979 2082 3980 2083 3980 2064 3980 2082 3981 2064 3981 2063 3981 2083 3982 2084 3982 2065 3982 2083 3983 2065 3983 2064 3983 2084 3984 2085 3984 2066 3984 2084 3985 2066 3985 2065 3985 2085 3986 2086 3986 2067 3986 2085 3987 2067 3987 2066 3987 2086 3988 2087 3988 2068 3988 2086 3989 2068 3989 2067 3989 2087 3990 2088 3990 2069 3990 2087 3991 2069 3991 2068 3991 2088 3992 2089 3992 2070 3992 2088 3993 2070 3993 2069 3993 2089 3994 2090 3994 2071 3994 2089 3995 2071 3995 2070 3995 2090 3996 2091 3996 2072 3996 2090 3997 2072 3997 2071 3997 2091 3998 2092 3998 2073 3998 2091 3999 2073 3999 2072 3999 2092 4000 2093 4000 2074 4000 2092 4001 2074 4001 2073 4001 2093 4002 2094 4002 2075 4002 2093 4003 2075 4003 2074 4003 2094 4004 2095 4004 2076 4004 2094 4005 2076 4005 2075 4005 2095 4006 2096 4006 2077 4006 2095 4007 2077 4007 2076 4007 2096 4008 2097 4008 2078 4008 2096 4009 2078 4009 2077 4009 2097 4010 157 4010 159 4010 2097 4011 159 4011 2078 4011 36 4012 2098 4012 2079 4012 36 4013 2079 4013 38 4013 2098 4014 2099 4014 2080 4014 2098 4015 2080 4015 2079 4015 2099 4016 2100 4016 2081 4016 2099 4017 2081 4017 2080 4017 2100 4018 2101 4018 2082 4018 2100 4019 2082 4019 2081 4019 2101 4020 2102 4020 2083 4020 2101 4021 2083 4021 2082 4021 2102 4022 2103 4022 2084 4022 2102 4023 2084 4023 2083 4023 2103 4024 2104 4024 2085 4024 2103 4025 2085 4025 2084 4025 2104 4026 2105 4026 2086 4026 2104 4027 2086 4027 2085 4027 2105 4028 2106 4028 2087 4028 2105 4029 2087 4029 2086 4029 2106 4030 2107 4030 2088 4030 2106 4031 2088 4031 2087 4031 2107 4032 2108 4032 2089 4032 2107 4033 2089 4033 2088 4033 2108 4034 2109 4034 2090 4034 2108 4035 2090 4035 2089 4035 2109 4036 2110 4036 2091 4036 2109 4037 2091 4037 2090 4037 2110 4038 2111 4038 2092 4038 2110 4039 2092 4039 2091 4039 2111 4040 2112 4040 2093 4040 2111 4041 2093 4041 2092 4041 2112 4042 2113 4042 2094 4042 2112 4043 2094 4043 2093 4043 2113 4044 2114 4044 2095 4044 2113 4045 2095 4045 2094 4045 2114 4046 2115 4046 2096 4046 2114 4047 2096 4047 2095 4047 2115 4048 2116 4048 2097 4048 2115 4049 2097 4049 2096 4049 2116 4050 155 4050 157 4050 2116 4051 157 4051 2097 4051 34 4052 2117 4052 2098 4052 34 4053 2098 4053 36 4053 2117 4054 2118 4054 2099 4054 2117 4055 2099 4055 2098 4055 2118 4056 2119 4056 2100 4056 2118 4057 2100 4057 2099 4057 2119 4058 2120 4058 2101 4058 2119 4059 2101 4059 2100 4059 2120 4060 2121 4060 2102 4060 2120 4061 2102 4061 2101 4061 2121 4062 2122 4062 2103 4062 2121 4063 2103 4063 2102 4063 2122 4064 2123 4064 2104 4064 2122 4065 2104 4065 2103 4065 2123 4066 2124 4066 2105 4066 2123 4067 2105 4067 2104 4067 2124 4068 2125 4068 2106 4068 2124 4069 2106 4069 2105 4069 2125 4070 2126 4070 2107 4070 2125 4071 2107 4071 2106 4071 2126 4072 2127 4072 2108 4072 2126 4073 2108 4073 2107 4073 2127 4074 2128 4074 2109 4074 2127 4075 2109 4075 2108 4075 2128 4076 2129 4076 2110 4076 2128 4077 2110 4077 2109 4077 2129 4078 2130 4078 2111 4078 2129 4079 2111 4079 2110 4079 2130 4080 2131 4080 2112 4080 2130 4081 2112 4081 2111 4081 2131 4082 2132 4082 2113 4082 2131 4083 2113 4083 2112 4083 2132 4084 2133 4084 2114 4084 2132 4085 2114 4085 2113 4085 2133 4086 2134 4086 2115 4086 2133 4087 2115 4087 2114 4087 2134 4088 2135 4088 2116 4088 2134 4089 2116 4089 2115 4089 2135 4090 153 4090 155 4090 2135 4091 155 4091 2116 4091 32 4092 2136 4092 2117 4092 32 4093 2117 4093 34 4093 2136 4094 2137 4094 2118 4094 2136 4095 2118 4095 2117 4095 2137 4096 2138 4096 2119 4096 2137 4097 2119 4097 2118 4097 2138 4098 2139 4098 2120 4098 2138 4099 2120 4099 2119 4099 2139 4100 2140 4100 2121 4100 2139 4101 2121 4101 2120 4101 2140 4102 2141 4102 2122 4102 2140 4103 2122 4103 2121 4103 2141 4104 2142 4104 2123 4104 2141 4105 2123 4105 2122 4105 2142 4106 2143 4106 2124 4106 2142 4107 2124 4107 2123 4107 2143 4108 2144 4108 2125 4108 2143 4109 2125 4109 2124 4109 2144 4110 2145 4110 2126 4110 2144 4111 2126 4111 2125 4111 2145 4112 2146 4112 2127 4112 2145 4113 2127 4113 2126 4113 2146 4114 2147 4114 2128 4114 2146 4115 2128 4115 2127 4115 2147 4116 2148 4116 2129 4116 2147 4117 2129 4117 2128 4117 2148 4118 2149 4118 2130 4118 2148 4119 2130 4119 2129 4119 2149 4120 2150 4120 2131 4120 2149 4121 2131 4121 2130 4121 2150 4122 2151 4122 2132 4122 2150 4123 2132 4123 2131 4123 2151 4124 2152 4124 2133 4124 2151 4125 2133 4125 2132 4125 2152 4126 2153 4126 2134 4126 2152 4127 2134 4127 2133 4127 2153 4128 2154 4128 2135 4128 2153 4129 2135 4129 2134 4129 2154 4130 151 4130 153 4130 2154 4131 153 4131 2135 4131 30 4132 2155 4132 2136 4132 30 4133 2136 4133 32 4133 2155 4134 2156 4134 2137 4134 2155 4135 2137 4135 2136 4135 2156 4136 2157 4136 2138 4136 2156 4137 2138 4137 2137 4137 2157 4138 2158 4138 2139 4138 2157 4139 2139 4139 2138 4139 2158 4140 2159 4140 2140 4140 2158 4141 2140 4141 2139 4141 2159 4142 2160 4142 2141 4142 2159 4143 2141 4143 2140 4143 2160 4144 2161 4144 2142 4144 2160 4145 2142 4145 2141 4145 2161 4146 2162 4146 2143 4146 2161 4147 2143 4147 2142 4147 2162 4148 2163 4148 2144 4148 2162 4149 2144 4149 2143 4149 2163 4150 2164 4150 2145 4150 2163 4151 2145 4151 2144 4151 2164 4152 2165 4152 2146 4152 2164 4153 2146 4153 2145 4153 2165 4154 2166 4154 2147 4154 2165 4155 2147 4155 2146 4155 2166 4156 2167 4156 2148 4156 2166 4157 2148 4157 2147 4157 2167 4158 2168 4158 2149 4158 2167 4159 2149 4159 2148 4159 2168 4160 2169 4160 2150 4160 2168 4161 2150 4161 2149 4161 2169 4162 2170 4162 2151 4162 2169 4163 2151 4163 2150 4163 2170 4164 2171 4164 2152 4164 2170 4165 2152 4165 2151 4165 2171 4166 2172 4166 2153 4166 2171 4167 2153 4167 2152 4167 2172 4168 2173 4168 2154 4168 2172 4169 2154 4169 2153 4169 2173 4170 149 4170 151 4170 2173 4171 151 4171 2154 4171 28 4172 2174 4172 2155 4172 28 4173 2155 4173 30 4173 2174 4174 2175 4174 2156 4174 2174 4175 2156 4175 2155 4175 2175 4176 2176 4176 2157 4176 2175 4177 2157 4177 2156 4177 2176 4178 2177 4178 2158 4178 2176 4179 2158 4179 2157 4179 2177 4180 2178 4180 2159 4180 2177 4181 2159 4181 2158 4181 2178 4182 2179 4182 2160 4182 2178 4183 2160 4183 2159 4183 2179 4184 2180 4184 2161 4184 2179 4185 2161 4185 2160 4185 2180 4186 2181 4186 2162 4186 2180 4187 2162 4187 2161 4187 2181 4188 2182 4188 2163 4188 2181 4189 2163 4189 2162 4189 2182 4190 2183 4190 2164 4190 2182 4191 2164 4191 2163 4191 2183 4192 2184 4192 2165 4192 2183 4193 2165 4193 2164 4193 2184 4194 2185 4194 2166 4194 2184 4195 2166 4195 2165 4195 2185 4196 2186 4196 2167 4196 2185 4197 2167 4197 2166 4197 2186 4198 2187 4198 2168 4198 2186 4199 2168 4199 2167 4199 2187 4200 2188 4200 2169 4200 2187 4201 2169 4201 2168 4201 2188 4202 2189 4202 2170 4202 2188 4203 2170 4203 2169 4203 2189 4204 2190 4204 2171 4204 2189 4205 2171 4205 2170 4205 2190 4206 2191 4206 2172 4206 2190 4207 2172 4207 2171 4207 2191 4208 2192 4208 2173 4208 2191 4209 2173 4209 2172 4209 2192 4210 147 4210 149 4210 2192 4211 149 4211 2173 4211 26 4212 2193 4212 2174 4212 26 4213 2174 4213 28 4213 2193 4214 2194 4214 2175 4214 2193 4215 2175 4215 2174 4215 2194 4216 2195 4216 2176 4216 2194 4217 2176 4217 2175 4217 2195 4218 2196 4218 2177 4218 2195 4219 2177 4219 2176 4219 2196 4220 2197 4220 2178 4220 2196 4221 2178 4221 2177 4221 2197 4222 2198 4222 2179 4222 2197 4223 2179 4223 2178 4223 2198 4224 2199 4224 2180 4224 2198 4225 2180 4225 2179 4225 2199 4226 2200 4226 2181 4226 2199 4227 2181 4227 2180 4227 2200 4228 2201 4228 2182 4228 2200 4229 2182 4229 2181 4229 2201 4230 2202 4230 2183 4230 2201 4231 2183 4231 2182 4231 2202 4232 2203 4232 2184 4232 2202 4233 2184 4233 2183 4233 2203 4234 2204 4234 2185 4234 2203 4235 2185 4235 2184 4235 2204 4236 2205 4236 2186 4236 2204 4237 2186 4237 2185 4237 2205 4238 2206 4238 2187 4238 2205 4239 2187 4239 2186 4239 2206 4240 2207 4240 2188 4240 2206 4241 2188 4241 2187 4241 2207 4242 2208 4242 2189 4242 2207 4243 2189 4243 2188 4243 2208 4244 2209 4244 2190 4244 2208 4245 2190 4245 2189 4245 2209 4246 2210 4246 2191 4246 2209 4247 2191 4247 2190 4247 2210 4248 2211 4248 2192 4248 2210 4249 2192 4249 2191 4249 2211 4250 145 4250 147 4250 2211 4251 147 4251 2192 4251 24 4252 2212 4252 2193 4252 24 4253 2193 4253 26 4253 2212 4254 2213 4254 2194 4254 2212 4255 2194 4255 2193 4255 2213 4256 2214 4256 2195 4256 2213 4257 2195 4257 2194 4257 2214 4258 2215 4258 2196 4258 2214 4259 2196 4259 2195 4259 2215 4260 2216 4260 2197 4260 2215 4261 2197 4261 2196 4261 2216 4262 2217 4262 2198 4262 2216 4263 2198 4263 2197 4263 2217 4264 2218 4264 2199 4264 2217 4265 2199 4265 2198 4265 2218 4266 2219 4266 2200 4266 2218 4267 2200 4267 2199 4267 2219 4268 2220 4268 2201 4268 2219 4269 2201 4269 2200 4269 2220 4270 2221 4270 2202 4270 2220 4271 2202 4271 2201 4271 2221 4272 2222 4272 2203 4272 2221 4273 2203 4273 2202 4273 2222 4274 2223 4274 2204 4274 2222 4275 2204 4275 2203 4275 2223 4276 2224 4276 2205 4276 2223 4277 2205 4277 2204 4277 2224 4278 2225 4278 2206 4278 2224 4279 2206 4279 2205 4279 2225 4280 2226 4280 2207 4280 2225 4281 2207 4281 2206 4281 2226 4282 2227 4282 2208 4282 2226 4283 2208 4283 2207 4283 2227 4284 2228 4284 2209 4284 2227 4285 2209 4285 2208 4285 2228 4286 2229 4286 2210 4286 2228 4287 2210 4287 2209 4287 2229 4288 2230 4288 2211 4288 2229 4289 2211 4289 2210 4289 2230 4290 143 4290 145 4290 2230 4291 145 4291 2211 4291 23 4292 1015 4292 2212 4292 23 4293 2212 4293 24 4293 1015 4294 1451 4294 2213 4294 1015 4295 2213 4295 2212 4295 1451 4296 1450 4296 2214 4296 1451 4297 2214 4297 2213 4297 1450 4298 1449 4298 2215 4298 1450 4299 2215 4299 2214 4299 1449 4300 1448 4300 2216 4300 1449 4301 2216 4301 2215 4301 1448 4302 1447 4302 2217 4302 1448 4303 2217 4303 2216 4303 1447 4304 1446 4304 2218 4304 1447 4305 2218 4305 2217 4305 1446 4306 1445 4306 2219 4306 1446 4307 2219 4307 2218 4307 1445 4308 1444 4308 2220 4308 1445 4309 2220 4309 2219 4309 1444 4310 1443 4310 2221 4310 1444 4311 2221 4311 2220 4311 1443 4312 1442 4312 2222 4312 1443 4313 2222 4313 2221 4313 1442 4314 1441 4314 2223 4314 1442 4315 2223 4315 2222 4315 1441 4316 1440 4316 2224 4316 1441 4317 2224 4317 2223 4317 1440 4318 1439 4318 2225 4318 1440 4319 2225 4319 2224 4319 1439 4320 1438 4320 2226 4320 1439 4321 2226 4321 2225 4321 1438 4322 1437 4322 2227 4322 1438 4323 2227 4323 2226 4323 1437 4324 1436 4324 2228 4324 1437 4325 2228 4325 2227 4325 1436 4326 1435 4326 2229 4326 1436 4327 2229 4327 2228 4327 1435 4328 1434 4328 2230 4328 1435 4329 2230 4329 2229 4329 1434 4330 140 4330 143 4330 1434 4331 143 4331 2230 4331 138 4332 2231 4332 2232 4332 138 4333 2232 4333 5 4333 2231 4334 2233 4334 2234 4334 2231 4335 2234 4335 2232 4335 2233 4336 2235 4336 2236 4336 2233 4337 2236 4337 2234 4337 2235 4338 2237 4338 2238 4338 2235 4339 2238 4339 2236 4339 2237 4340 2239 4340 2240 4340 2237 4341 2240 4341 2238 4341 2239 4342 2241 4342 2242 4342 2239 4343 2242 4343 2240 4343 2241 4344 2243 4344 2244 4344 2241 4345 2244 4345 2242 4345 2243 4346 2245 4346 2246 4346 2243 4347 2246 4347 2244 4347 2245 4348 2247 4348 2248 4348 2245 4349 2248 4349 2246 4349 2247 4350 2249 4350 2250 4350 2247 4351 2250 4351 2248 4351 2249 4352 2251 4352 2252 4352 2249 4353 2252 4353 2250 4353 2251 4354 2253 4354 2254 4354 2251 4355 2254 4355 2252 4355 2253 4356 2255 4356 2256 4356 2253 4357 2256 4357 2254 4357 2255 4358 2257 4358 2258 4358 2255 4359 2258 4359 2256 4359 2257 4360 2259 4360 2260 4360 2257 4361 2260 4361 2258 4361 2259 4362 2261 4362 2262 4362 2259 4363 2262 4363 2260 4363 2261 4364 2263 4364 2264 4364 2261 4365 2264 4365 2262 4365 2263 4366 2265 4366 2266 4366 2263 4367 2266 4367 2264 4367 2265 4368 2267 4368 2268 4368 2265 4369 2268 4369 2266 4369 2267 4370 99 4370 8 4370 2267 4371 8 4371 2268 4371 136 4372 2269 4372 2231 4372 136 4373 2231 4373 138 4373 2269 4374 2270 4374 2233 4374 2269 4375 2233 4375 2231 4375 2270 4376 2271 4376 2235 4376 2270 4377 2235 4377 2233 4377 2271 4378 2272 4378 2237 4378 2271 4379 2237 4379 2235 4379 2272 4380 2273 4380 2239 4380 2272 4381 2239 4381 2237 4381 2273 4382 2274 4382 2241 4382 2273 4383 2241 4383 2239 4383 2274 4384 2275 4384 2243 4384 2274 4385 2243 4385 2241 4385 2275 4386 2276 4386 2245 4386 2275 4387 2245 4387 2243 4387 2276 4388 2277 4388 2247 4388 2276 4389 2247 4389 2245 4389 2277 4390 2278 4390 2249 4390 2277 4391 2249 4391 2247 4391 2278 4392 2279 4392 2251 4392 2278 4393 2251 4393 2249 4393 2279 4394 2280 4394 2253 4394 2279 4395 2253 4395 2251 4395 2280 4396 2281 4396 2255 4396 2280 4397 2255 4397 2253 4397 2281 4398 2282 4398 2257 4398 2281 4399 2257 4399 2255 4399 2282 4400 2283 4400 2259 4400 2282 4401 2259 4401 2257 4401 2283 4402 2284 4402 2261 4402 2283 4403 2261 4403 2259 4403 2284 4404 2285 4404 2263 4404 2284 4405 2263 4405 2261 4405 2285 4406 2286 4406 2265 4406 2285 4407 2265 4407 2263 4407 2286 4408 2287 4408 2267 4408 2286 4409 2267 4409 2265 4409 2287 4410 97 4410 99 4410 2287 4411 99 4411 2267 4411 134 4412 2288 4412 2269 4412 134 4413 2269 4413 136 4413 2288 4414 2289 4414 2270 4414 2288 4415 2270 4415 2269 4415 2289 4416 2290 4416 2271 4416 2289 4417 2271 4417 2270 4417 2290 4418 2291 4418 2272 4418 2290 4419 2272 4419 2271 4419 2291 4420 2292 4420 2273 4420 2291 4421 2273 4421 2272 4421 2292 4422 2293 4422 2274 4422 2292 4423 2274 4423 2273 4423 2293 4424 2294 4424 2275 4424 2293 4425 2275 4425 2274 4425 2294 4426 2295 4426 2276 4426 2294 4427 2276 4427 2275 4427 2295 4428 2296 4428 2277 4428 2295 4429 2277 4429 2276 4429 2296 4430 2297 4430 2278 4430 2296 4431 2278 4431 2277 4431 2297 4432 2298 4432 2279 4432 2297 4433 2279 4433 2278 4433 2298 4434 2299 4434 2280 4434 2298 4435 2280 4435 2279 4435 2299 4436 2300 4436 2281 4436 2299 4437 2281 4437 2280 4437 2300 4438 2301 4438 2282 4438 2300 4439 2282 4439 2281 4439 2301 4440 2302 4440 2283 4440 2301 4441 2283 4441 2282 4441 2302 4442 2303 4442 2284 4442 2302 4443 2284 4443 2283 4443 2303 4444 2304 4444 2285 4444 2303 4445 2285 4445 2284 4445 2304 4446 2305 4446 2286 4446 2304 4447 2286 4447 2285 4447 2305 4448 2306 4448 2287 4448 2305 4449 2287 4449 2286 4449 2306 4450 95 4450 97 4450 2306 4451 97 4451 2287 4451 132 4452 2307 4452 2288 4452 132 4453 2288 4453 134 4453 2307 4454 2308 4454 2289 4454 2307 4455 2289 4455 2288 4455 2308 4456 2309 4456 2290 4456 2308 4457 2290 4457 2289 4457 2309 4458 2310 4458 2291 4458 2309 4459 2291 4459 2290 4459 2310 4460 2311 4460 2292 4460 2310 4461 2292 4461 2291 4461 2311 4462 2312 4462 2293 4462 2311 4463 2293 4463 2292 4463 2312 4464 2313 4464 2294 4464 2312 4465 2294 4465 2293 4465 2313 4466 2314 4466 2295 4466 2313 4467 2295 4467 2294 4467 2314 4468 2315 4468 2296 4468 2314 4469 2296 4469 2295 4469 2315 4470 2316 4470 2297 4470 2315 4471 2297 4471 2296 4471 2316 4472 2317 4472 2298 4472 2316 4473 2298 4473 2297 4473 2317 4474 2318 4474 2299 4474 2317 4475 2299 4475 2298 4475 2318 4476 2319 4476 2300 4476 2318 4477 2300 4477 2299 4477 2319 4478 2320 4478 2301 4478 2319 4479 2301 4479 2300 4479 2320 4480 2321 4480 2302 4480 2320 4481 2302 4481 2301 4481 2321 4482 2322 4482 2303 4482 2321 4483 2303 4483 2302 4483 2322 4484 2323 4484 2304 4484 2322 4485 2304 4485 2303 4485 2323 4486 2324 4486 2305 4486 2323 4487 2305 4487 2304 4487 2324 4488 2325 4488 2306 4488 2324 4489 2306 4489 2305 4489 2325 4490 93 4490 95 4490 2325 4491 95 4491 2306 4491 130 4492 2326 4492 2307 4492 130 4493 2307 4493 132 4493 2326 4494 2327 4494 2308 4494 2326 4495 2308 4495 2307 4495 2327 4496 2328 4496 2309 4496 2327 4497 2309 4497 2308 4497 2328 4498 2329 4498 2310 4498 2328 4499 2310 4499 2309 4499 2329 4500 2330 4500 2311 4500 2329 4501 2311 4501 2310 4501 2330 4502 2331 4502 2312 4502 2330 4503 2312 4503 2311 4503 2331 4504 2332 4504 2313 4504 2331 4505 2313 4505 2312 4505 2332 4506 2333 4506 2314 4506 2332 4507 2314 4507 2313 4507 2333 4508 2334 4508 2315 4508 2333 4509 2315 4509 2314 4509 2334 4510 2335 4510 2316 4510 2334 4511 2316 4511 2315 4511 2335 4512 2336 4512 2317 4512 2335 4513 2317 4513 2316 4513 2336 4514 2337 4514 2318 4514 2336 4515 2318 4515 2317 4515 2337 4516 2338 4516 2319 4516 2337 4517 2319 4517 2318 4517 2338 4518 2339 4518 2320 4518 2338 4519 2320 4519 2319 4519 2339 4520 2340 4520 2321 4520 2339 4521 2321 4521 2320 4521 2340 4522 2341 4522 2322 4522 2340 4523 2322 4523 2321 4523 2341 4524 2342 4524 2323 4524 2341 4525 2323 4525 2322 4525 2342 4526 2343 4526 2324 4526 2342 4527 2324 4527 2323 4527 2343 4528 2344 4528 2325 4528 2343 4529 2325 4529 2324 4529 2344 4530 91 4530 93 4530 2344 4531 93 4531 2325 4531 128 4532 2345 4532 2326 4532 128 4533 2326 4533 130 4533 2345 4534 2346 4534 2327 4534 2345 4535 2327 4535 2326 4535 2346 4536 2347 4536 2328 4536 2346 4537 2328 4537 2327 4537 2347 4538 2348 4538 2329 4538 2347 4539 2329 4539 2328 4539 2348 4540 2349 4540 2330 4540 2348 4541 2330 4541 2329 4541 2349 4542 2350 4542 2331 4542 2349 4543 2331 4543 2330 4543 2350 4544 2351 4544 2332 4544 2350 4545 2332 4545 2331 4545 2351 4546 2352 4546 2333 4546 2351 4547 2333 4547 2332 4547 2352 4548 2353 4548 2334 4548 2352 4549 2334 4549 2333 4549 2353 4550 2354 4550 2335 4550 2353 4551 2335 4551 2334 4551 2354 4552 2355 4552 2336 4552 2354 4553 2336 4553 2335 4553 2355 4554 2356 4554 2337 4554 2355 4555 2337 4555 2336 4555 2356 4556 2357 4556 2338 4556 2356 4557 2338 4557 2337 4557 2357 4558 2358 4558 2339 4558 2357 4559 2339 4559 2338 4559 2358 4560 2359 4560 2340 4560 2358 4561 2340 4561 2339 4561 2359 4562 2360 4562 2341 4562 2359 4563 2341 4563 2340 4563 2360 4564 2361 4564 2342 4564 2360 4565 2342 4565 2341 4565 2361 4566 2362 4566 2343 4566 2361 4567 2343 4567 2342 4567 2362 4568 2363 4568 2344 4568 2362 4569 2344 4569 2343 4569 2363 4570 89 4570 91 4570 2363 4571 91 4571 2344 4571 126 4572 2364 4572 2345 4572 126 4573 2345 4573 128 4573 2364 4574 2365 4574 2346 4574 2364 4575 2346 4575 2345 4575 2365 4576 2366 4576 2347 4576 2365 4577 2347 4577 2346 4577 2366 4578 2367 4578 2348 4578 2366 4579 2348 4579 2347 4579 2367 4580 2368 4580 2349 4580 2367 4581 2349 4581 2348 4581 2368 4582 2369 4582 2350 4582 2368 4583 2350 4583 2349 4583 2369 4584 2370 4584 2351 4584 2369 4585 2351 4585 2350 4585 2370 4586 2371 4586 2352 4586 2370 4587 2352 4587 2351 4587 2371 4588 2372 4588 2353 4588 2371 4589 2353 4589 2352 4589 2372 4590 2373 4590 2354 4590 2372 4591 2354 4591 2353 4591 2373 4592 2374 4592 2355 4592 2373 4593 2355 4593 2354 4593 2374 4594 2375 4594 2356 4594 2374 4595 2356 4595 2355 4595 2375 4596 2376 4596 2357 4596 2375 4597 2357 4597 2356 4597 2376 4598 2377 4598 2358 4598 2376 4599 2358 4599 2357 4599 2377 4600 2378 4600 2359 4600 2377 4601 2359 4601 2358 4601 2378 4602 2379 4602 2360 4602 2378 4603 2360 4603 2359 4603 2379 4604 2380 4604 2361 4604 2379 4605 2361 4605 2360 4605 2380 4606 2381 4606 2362 4606 2380 4607 2362 4607 2361 4607 2381 4608 2382 4608 2363 4608 2381 4609 2363 4609 2362 4609 2382 4610 87 4610 89 4610 2382 4611 89 4611 2363 4611 124 4612 2383 4612 2364 4612 124 4613 2364 4613 126 4613 2383 4614 2384 4614 2365 4614 2383 4615 2365 4615 2364 4615 2384 4616 2385 4616 2366 4616 2384 4617 2366 4617 2365 4617 2385 4618 2386 4618 2367 4618 2385 4619 2367 4619 2366 4619 2386 4620 2387 4620 2368 4620 2386 4621 2368 4621 2367 4621 2387 4622 2388 4622 2369 4622 2387 4623 2369 4623 2368 4623 2388 4624 2389 4624 2370 4624 2388 4625 2370 4625 2369 4625 2389 4626 2390 4626 2371 4626 2389 4627 2371 4627 2370 4627 2390 4628 2391 4628 2372 4628 2390 4629 2372 4629 2371 4629 2391 4630 2392 4630 2373 4630 2391 4631 2373 4631 2372 4631 2392 4632 2393 4632 2374 4632 2392 4633 2374 4633 2373 4633 2393 4634 2394 4634 2375 4634 2393 4635 2375 4635 2374 4635 2394 4636 2395 4636 2376 4636 2394 4637 2376 4637 2375 4637 2395 4638 2396 4638 2377 4638 2395 4639 2377 4639 2376 4639 2396 4640 2397 4640 2378 4640 2396 4641 2378 4641 2377 4641 2397 4642 2398 4642 2379 4642 2397 4643 2379 4643 2378 4643 2398 4644 2399 4644 2380 4644 2398 4645 2380 4645 2379 4645 2399 4646 2400 4646 2381 4646 2399 4647 2381 4647 2380 4647 2400 4648 2401 4648 2382 4648 2400 4649 2382 4649 2381 4649 2401 4650 85 4650 87 4650 2401 4651 87 4651 2382 4651 122 4652 2402 4652 2383 4652 122 4653 2383 4653 124 4653 2402 4654 2403 4654 2384 4654 2402 4655 2384 4655 2383 4655 2403 4656 2404 4656 2385 4656 2403 4657 2385 4657 2384 4657 2404 4658 2405 4658 2386 4658 2404 4659 2386 4659 2385 4659 2405 4660 2406 4660 2387 4660 2405 4661 2387 4661 2386 4661 2406 4662 2407 4662 2388 4662 2406 4663 2388 4663 2387 4663 2407 4664 2408 4664 2389 4664 2407 4665 2389 4665 2388 4665 2408 4666 2409 4666 2390 4666 2408 4667 2390 4667 2389 4667 2409 4668 2410 4668 2391 4668 2409 4669 2391 4669 2390 4669 2410 4670 2411 4670 2392 4670 2410 4671 2392 4671 2391 4671 2411 4672 2412 4672 2393 4672 2411 4673 2393 4673 2392 4673 2412 4674 2413 4674 2394 4674 2412 4675 2394 4675 2393 4675 2413 4676 2414 4676 2395 4676 2413 4677 2395 4677 2394 4677 2414 4678 2415 4678 2396 4678 2414 4679 2396 4679 2395 4679 2415 4680 2416 4680 2397 4680 2415 4681 2397 4681 2396 4681 2416 4682 2417 4682 2398 4682 2416 4683 2398 4683 2397 4683 2417 4684 2418 4684 2399 4684 2417 4685 2399 4685 2398 4685 2418 4686 2419 4686 2400 4686 2418 4687 2400 4687 2399 4687 2419 4688 2420 4688 2401 4688 2419 4689 2401 4689 2400 4689 2420 4690 83 4690 85 4690 2420 4691 85 4691 2401 4691 120 4692 2421 4692 2402 4692 120 4693 2402 4693 122 4693 2421 4694 2422 4694 2403 4694 2421 4695 2403 4695 2402 4695 2422 4696 2423 4696 2404 4696 2422 4697 2404 4697 2403 4697 2423 4698 2424 4698 2405 4698 2423 4699 2405 4699 2404 4699 2424 4700 2425 4700 2406 4700 2424 4701 2406 4701 2405 4701 2425 4702 2426 4702 2407 4702 2425 4703 2407 4703 2406 4703 2426 4704 2427 4704 2408 4704 2426 4705 2408 4705 2407 4705 2427 4706 2428 4706 2409 4706 2427 4707 2409 4707 2408 4707 2428 4708 2429 4708 2410 4708 2428 4709 2410 4709 2409 4709 2429 4710 2430 4710 2411 4710 2429 4711 2411 4711 2410 4711 2430 4712 2431 4712 2412 4712 2430 4713 2412 4713 2411 4713 2431 4714 2432 4714 2413 4714 2431 4715 2413 4715 2412 4715 2432 4716 2433 4716 2414 4716 2432 4717 2414 4717 2413 4717 2433 4718 2434 4718 2415 4718 2433 4719 2415 4719 2414 4719 2434 4720 2435 4720 2416 4720 2434 4721 2416 4721 2415 4721 2435 4722 2436 4722 2417 4722 2435 4723 2417 4723 2416 4723 2436 4724 2437 4724 2418 4724 2436 4725 2418 4725 2417 4725 2437 4726 2438 4726 2419 4726 2437 4727 2419 4727 2418 4727 2438 4728 2439 4728 2420 4728 2438 4729 2420 4729 2419 4729 2439 4730 81 4730 83 4730 2439 4731 83 4731 2420 4731 118 4732 2440 4732 2421 4732 118 4733 2421 4733 120 4733 2440 4734 2441 4734 2422 4734 2440 4735 2422 4735 2421 4735 2441 4736 2442 4736 2423 4736 2441 4737 2423 4737 2422 4737 2442 4738 2443 4738 2424 4738 2442 4739 2424 4739 2423 4739 2443 4740 2444 4740 2425 4740 2443 4741 2425 4741 2424 4741 2444 4742 2445 4742 2426 4742 2444 4743 2426 4743 2425 4743 2445 4744 2446 4744 2427 4744 2445 4745 2427 4745 2426 4745 2446 4746 2447 4746 2428 4746 2446 4747 2428 4747 2427 4747 2447 4748 2448 4748 2429 4748 2447 4749 2429 4749 2428 4749 2448 4750 2449 4750 2430 4750 2448 4751 2430 4751 2429 4751 2449 4752 2450 4752 2431 4752 2449 4753 2431 4753 2430 4753 2450 4754 2451 4754 2432 4754 2450 4755 2432 4755 2431 4755 2451 4756 2452 4756 2433 4756 2451 4757 2433 4757 2432 4757 2452 4758 2453 4758 2434 4758 2452 4759 2434 4759 2433 4759 2453 4760 2454 4760 2435 4760 2453 4761 2435 4761 2434 4761 2454 4762 2455 4762 2436 4762 2454 4763 2436 4763 2435 4763 2455 4764 2456 4764 2437 4764 2455 4765 2437 4765 2436 4765 2456 4766 2457 4766 2438 4766 2456 4767 2438 4767 2437 4767 2457 4768 2458 4768 2439 4768 2457 4769 2439 4769 2438 4769 2458 4770 79 4770 81 4770 2458 4771 81 4771 2439 4771 116 4772 2459 4772 2440 4772 116 4773 2440 4773 118 4773 2459 4774 2460 4774 2441 4774 2459 4775 2441 4775 2440 4775 2460 4776 2461 4776 2442 4776 2460 4777 2442 4777 2441 4777 2461 4778 2462 4778 2443 4778 2461 4779 2443 4779 2442 4779 2462 4780 2463 4780 2444 4780 2462 4781 2444 4781 2443 4781 2463 4782 2464 4782 2445 4782 2463 4783 2445 4783 2444 4783 2464 4784 2465 4784 2446 4784 2464 4785 2446 4785 2445 4785 2465 4786 2466 4786 2447 4786 2465 4787 2447 4787 2446 4787 2466 4788 2467 4788 2448 4788 2466 4789 2448 4789 2447 4789 2467 4790 2468 4790 2449 4790 2467 4791 2449 4791 2448 4791 2468 4792 2469 4792 2450 4792 2468 4793 2450 4793 2449 4793 2469 4794 2470 4794 2451 4794 2469 4795 2451 4795 2450 4795 2470 4796 2471 4796 2452 4796 2470 4797 2452 4797 2451 4797 2471 4798 2472 4798 2453 4798 2471 4799 2453 4799 2452 4799 2472 4800 2473 4800 2454 4800 2472 4801 2454 4801 2453 4801 2473 4802 2474 4802 2455 4802 2473 4803 2455 4803 2454 4803 2474 4804 2475 4804 2456 4804 2474 4805 2456 4805 2455 4805 2475 4806 2476 4806 2457 4806 2475 4807 2457 4807 2456 4807 2476 4808 2477 4808 2458 4808 2476 4809 2458 4809 2457 4809 2477 4810 77 4810 79 4810 2477 4811 79 4811 2458 4811 114 4812 2478 4812 2459 4812 114 4813 2459 4813 116 4813 2478 4814 2479 4814 2460 4814 2478 4815 2460 4815 2459 4815 2479 4816 2480 4816 2461 4816 2479 4817 2461 4817 2460 4817 2480 4818 2481 4818 2462 4818 2480 4819 2462 4819 2461 4819 2481 4820 2482 4820 2463 4820 2481 4821 2463 4821 2462 4821 2482 4822 2483 4822 2464 4822 2482 4823 2464 4823 2463 4823 2483 4824 2484 4824 2465 4824 2483 4825 2465 4825 2464 4825 2484 4826 2485 4826 2466 4826 2484 4827 2466 4827 2465 4827 2485 4828 2486 4828 2467 4828 2485 4829 2467 4829 2466 4829 2486 4830 2487 4830 2468 4830 2486 4831 2468 4831 2467 4831 2487 4832 2488 4832 2469 4832 2487 4833 2469 4833 2468 4833 2488 4834 2489 4834 2470 4834 2488 4835 2470 4835 2469 4835 2489 4836 2490 4836 2471 4836 2489 4837 2471 4837 2470 4837 2490 4838 2491 4838 2472 4838 2490 4839 2472 4839 2471 4839 2491 4840 2492 4840 2473 4840 2491 4841 2473 4841 2472 4841 2492 4842 2493 4842 2474 4842 2492 4843 2474 4843 2473 4843 2493 4844 2494 4844 2475 4844 2493 4845 2475 4845 2474 4845 2494 4846 2495 4846 2476 4846 2494 4847 2476 4847 2475 4847 2495 4848 2496 4848 2477 4848 2495 4849 2477 4849 2476 4849 2496 4850 75 4850 77 4850 2496 4851 77 4851 2477 4851 112 4852 2497 4852 2478 4852 112 4853 2478 4853 114 4853 2497 4854 2498 4854 2479 4854 2497 4855 2479 4855 2478 4855 2498 4856 2499 4856 2480 4856 2498 4857 2480 4857 2479 4857 2499 4858 2500 4858 2481 4858 2499 4859 2481 4859 2480 4859 2500 4860 2501 4860 2482 4860 2500 4861 2482 4861 2481 4861 2501 4862 2502 4862 2483 4862 2501 4863 2483 4863 2482 4863 2502 4864 2503 4864 2484 4864 2502 4865 2484 4865 2483 4865 2503 4866 2504 4866 2485 4866 2503 4867 2485 4867 2484 4867 2504 4868 2505 4868 2486 4868 2504 4869 2486 4869 2485 4869 2505 4870 2506 4870 2487 4870 2505 4871 2487 4871 2486 4871 2506 4872 2507 4872 2488 4872 2506 4873 2488 4873 2487 4873 2507 4874 2508 4874 2489 4874 2507 4875 2489 4875 2488 4875 2508 4876 2509 4876 2490 4876 2508 4877 2490 4877 2489 4877 2509 4878 2510 4878 2491 4878 2509 4879 2491 4879 2490 4879 2510 4880 2511 4880 2492 4880 2510 4881 2492 4881 2491 4881 2511 4882 2512 4882 2493 4882 2511 4883 2493 4883 2492 4883 2512 4884 2513 4884 2494 4884 2512 4885 2494 4885 2493 4885 2513 4886 2514 4886 2495 4886 2513 4887 2495 4887 2494 4887 2514 4888 2515 4888 2496 4888 2514 4889 2496 4889 2495 4889 2515 4890 73 4890 75 4890 2515 4891 75 4891 2496 4891 110 4892 2516 4892 2497 4892 110 4893 2497 4893 112 4893 2516 4894 2517 4894 2498 4894 2516 4895 2498 4895 2497 4895 2517 4896 2518 4896 2499 4896 2517 4897 2499 4897 2498 4897 2518 4898 2519 4898 2500 4898 2518 4899 2500 4899 2499 4899 2519 4900 2520 4900 2501 4900 2519 4901 2501 4901 2500 4901 2520 4902 2521 4902 2502 4902 2520 4903 2502 4903 2501 4903 2521 4904 2522 4904 2503 4904 2521 4905 2503 4905 2502 4905 2522 4906 2523 4906 2504 4906 2522 4907 2504 4907 2503 4907 2523 4908 2524 4908 2505 4908 2523 4909 2505 4909 2504 4909 2524 4910 2525 4910 2506 4910 2524 4911 2506 4911 2505 4911 2525 4912 2526 4912 2507 4912 2525 4913 2507 4913 2506 4913 2526 4914 2527 4914 2508 4914 2526 4915 2508 4915 2507 4915 2527 4916 2528 4916 2509 4916 2527 4917 2509 4917 2508 4917 2528 4918 2529 4918 2510 4918 2528 4919 2510 4919 2509 4919 2529 4920 2530 4920 2511 4920 2529 4921 2511 4921 2510 4921 2530 4922 2531 4922 2512 4922 2530 4923 2512 4923 2511 4923 2531 4924 2532 4924 2513 4924 2531 4925 2513 4925 2512 4925 2532 4926 2533 4926 2514 4926 2532 4927 2514 4927 2513 4927 2533 4928 2534 4928 2515 4928 2533 4929 2515 4929 2514 4929 2534 4930 71 4930 73 4930 2534 4931 73 4931 2515 4931 108 4932 2535 4932 2516 4932 108 4933 2516 4933 110 4933 2535 4934 2536 4934 2517 4934 2535 4935 2517 4935 2516 4935 2536 4936 2537 4936 2518 4936 2536 4937 2518 4937 2517 4937 2537 4938 2538 4938 2519 4938 2537 4939 2519 4939 2518 4939 2538 4940 2539 4940 2520 4940 2538 4941 2520 4941 2519 4941 2539 4942 2540 4942 2521 4942 2539 4943 2521 4943 2520 4943 2540 4944 2541 4944 2522 4944 2540 4945 2522 4945 2521 4945 2541 4946 2542 4946 2523 4946 2541 4947 2523 4947 2522 4947 2542 4948 2543 4948 2524 4948 2542 4949 2524 4949 2523 4949 2543 4950 2544 4950 2525 4950 2543 4951 2525 4951 2524 4951 2544 4952 2545 4952 2526 4952 2544 4953 2526 4953 2525 4953 2545 4954 2546 4954 2527 4954 2545 4955 2527 4955 2526 4955 2546 4956 2547 4956 2528 4956 2546 4957 2528 4957 2527 4957 2547 4958 2548 4958 2529 4958 2547 4959 2529 4959 2528 4959 2548 4960 2549 4960 2530 4960 2548 4961 2530 4961 2529 4961 2549 4962 2550 4962 2531 4962 2549 4963 2531 4963 2530 4963 2550 4964 2551 4964 2532 4964 2550 4965 2532 4965 2531 4965 2551 4966 2552 4966 2533 4966 2551 4967 2533 4967 2532 4967 2552 4968 2553 4968 2534 4968 2552 4969 2534 4969 2533 4969 2553 4970 69 4970 71 4970 2553 4971 71 4971 2534 4971 106 4972 2554 4972 2535 4972 106 4973 2535 4973 108 4973 2554 4974 2555 4974 2536 4974 2554 4975 2536 4975 2535 4975 2555 4976 2556 4976 2537 4976 2555 4977 2537 4977 2536 4977 2556 4978 2557 4978 2538 4978 2556 4979 2538 4979 2537 4979 2557 4980 2558 4980 2539 4980 2557 4981 2539 4981 2538 4981 2558 4982 2559 4982 2540 4982 2558 4983 2540 4983 2539 4983 2559 4984 2560 4984 2541 4984 2559 4985 2541 4985 2540 4985 2560 4986 2561 4986 2542 4986 2560 4987 2542 4987 2541 4987 2561 4988 2562 4988 2543 4988 2561 4989 2543 4989 2542 4989 2562 4990 2563 4990 2544 4990 2562 4991 2544 4991 2543 4991 2563 4992 2564 4992 2545 4992 2563 4993 2545 4993 2544 4993 2564 4994 2565 4994 2546 4994 2564 4995 2546 4995 2545 4995 2565 4996 2566 4996 2547 4996 2565 4997 2547 4997 2546 4997 2566 4998 2567 4998 2548 4998 2566 4999 2548 4999 2547 4999 2567 5000 2568 5000 2549 5000 2567 5001 2549 5001 2548 5001 2568 5002 2569 5002 2550 5002 2568 5003 2550 5003 2549 5003 2569 5004 2570 5004 2551 5004 2569 5005 2551 5005 2550 5005 2570 5006 2571 5006 2552 5006 2570 5007 2552 5007 2551 5007 2571 5008 2572 5008 2553 5008 2571 5009 2553 5009 2552 5009 2572 5010 67 5010 69 5010 2572 5011 69 5011 2553 5011 104 5012 2573 5012 2554 5012 104 5013 2554 5013 106 5013 2573 5014 2574 5014 2555 5014 2573 5015 2555 5015 2554 5015 2574 5016 2575 5016 2556 5016 2574 5017 2556 5017 2555 5017 2575 5018 2576 5018 2557 5018 2575 5019 2557 5019 2556 5019 2576 5020 2577 5020 2558 5020 2576 5021 2558 5021 2557 5021 2577 5022 2578 5022 2559 5022 2577 5023 2559 5023 2558 5023 2578 5024 2579 5024 2560 5024 2578 5025 2560 5025 2559 5025 2579 5026 2580 5026 2561 5026 2579 5027 2561 5027 2560 5027 2580 5028 2581 5028 2562 5028 2580 5029 2562 5029 2561 5029 2581 5030 2582 5030 2563 5030 2581 5031 2563 5031 2562 5031 2582 5032 2583 5032 2564 5032 2582 5033 2564 5033 2563 5033 2583 5034 2584 5034 2565 5034 2583 5035 2565 5035 2564 5035 2584 5036 2585 5036 2566 5036 2584 5037 2566 5037 2565 5037 2585 5038 2586 5038 2567 5038 2585 5039 2567 5039 2566 5039 2586 5040 2587 5040 2568 5040 2586 5041 2568 5041 2567 5041 2587 5042 2588 5042 2569 5042 2587 5043 2569 5043 2568 5043 2588 5044 2589 5044 2570 5044 2588 5045 2570 5045 2569 5045 2589 5046 2590 5046 2571 5046 2589 5047 2571 5047 2570 5047 2590 5048 2591 5048 2572 5048 2590 5049 2572 5049 2571 5049 2591 5050 65 5050 67 5050 2591 5051 67 5051 2572 5051 102 5052 2592 5052 2573 5052 102 5053 2573 5053 104 5053 2592 5054 2593 5054 2574 5054 2592 5055 2574 5055 2573 5055 2593 5056 2594 5056 2575 5056 2593 5057 2575 5057 2574 5057 2594 5058 2595 5058 2576 5058 2594 5059 2576 5059 2575 5059 2595 5060 2596 5060 2577 5060 2595 5061 2577 5061 2576 5061 2596 5062 2597 5062 2578 5062 2596 5063 2578 5063 2577 5063 2597 5064 2598 5064 2579 5064 2597 5065 2579 5065 2578 5065 2598 5066 2599 5066 2580 5066 2598 5067 2580 5067 2579 5067 2599 5068 2600 5068 2581 5068 2599 5069 2581 5069 2580 5069 2600 5070 2601 5070 2582 5070 2600 5071 2582 5071 2581 5071 2601 5072 2602 5072 2583 5072 2601 5073 2583 5073 2582 5073 2602 5074 2603 5074 2584 5074 2602 5075 2584 5075 2583 5075 2603 5076 2604 5076 2585 5076 2603 5077 2585 5077 2584 5077 2604 5078 2605 5078 2586 5078 2604 5079 2586 5079 2585 5079 2605 5080 2606 5080 2587 5080 2605 5081 2587 5081 2586 5081 2606 5082 2607 5082 2588 5082 2606 5083 2588 5083 2587 5083 2607 5084 2608 5084 2589 5084 2607 5085 2589 5085 2588 5085 2608 5086 2609 5086 2590 5086 2608 5087 2590 5087 2589 5087 2609 5088 2610 5088 2591 5088 2609 5089 2591 5089 2590 5089 2610 5090 63 5090 65 5090 2610 5091 65 5091 2591 5091 101 5092 2611 5092 2592 5092 101 5093 2592 5093 102 5093 2611 5094 2612 5094 2593 5094 2611 5095 2593 5095 2592 5095 2612 5096 2613 5096 2594 5096 2612 5097 2594 5097 2593 5097 2613 5098 2614 5098 2595 5098 2613 5099 2595 5099 2594 5099 2614 5100 2615 5100 2596 5100 2614 5101 2596 5101 2595 5101 2615 5102 2616 5102 2597 5102 2615 5103 2597 5103 2596 5103 2616 5104 2617 5104 2598 5104 2616 5105 2598 5105 2597 5105 2617 5106 2618 5106 2599 5106 2617 5107 2599 5107 2598 5107 2618 5108 2619 5108 2600 5108 2618 5109 2600 5109 2599 5109 2619 5110 2620 5110 2601 5110 2619 5111 2601 5111 2600 5111 2620 5112 2621 5112 2602 5112 2620 5113 2602 5113 2601 5113 2621 5114 2622 5114 2603 5114 2621 5115 2603 5115 2602 5115 2622 5116 2623 5116 2604 5116 2622 5117 2604 5117 2603 5117 2623 5118 2624 5118 2605 5118 2623 5119 2605 5119 2604 5119 2624 5120 2625 5120 2606 5120 2624 5121 2606 5121 2605 5121 2625 5122 2626 5122 2607 5122 2625 5123 2607 5123 2606 5123 2626 5124 2627 5124 2608 5124 2626 5125 2608 5125 2607 5125 2627 5126 2628 5126 2609 5126 2627 5127 2609 5127 2608 5127 2628 5128 2629 5128 2610 5128 2628 5129 2610 5129 2609 5129 2629 5130 19 5130 63 5130 2629 5131 63 5131 2610 5131 1035 5132 1453 5132 3 5132 1035 5133 3 5133 2 5133 1453 5134 1455 5134 2630 5134 1453 5135 2630 5135 3 5135 1455 5136 1457 5136 2631 5136 1455 5137 2631 5137 2630 5137 1457 5138 1459 5138 2632 5138 1457 5139 2632 5139 2631 5139 1459 5140 1461 5140 2633 5140 1459 5141 2633 5141 2632 5141 1461 5142 1463 5142 2634 5142 1461 5143 2634 5143 2633 5143 1463 5144 1465 5144 2635 5144 1463 5145 2635 5145 2634 5145 1465 5146 1467 5146 2636 5146 1465 5147 2636 5147 2635 5147 1467 5148 1469 5148 2637 5148 1467 5149 2637 5149 2636 5149 1469 5150 1471 5150 2638 5150 1469 5151 2638 5151 2637 5151 1471 5152 1473 5152 2639 5152 1471 5153 2639 5153 2638 5153 1473 5154 1475 5154 2640 5154 1473 5155 2640 5155 2639 5155 1475 5156 1477 5156 2641 5156 1475 5157 2641 5157 2640 5157 1477 5158 1479 5158 2642 5158 1477 5159 2642 5159 2641 5159 1479 5160 1481 5160 2643 5160 1479 5161 2643 5161 2642 5161 1481 5162 1483 5162 2644 5162 1481 5163 2644 5163 2643 5163 1483 5164 1485 5164 2645 5164 1483 5165 2645 5165 2644 5165 1485 5166 1487 5166 2646 5166 1485 5167 2646 5167 2645 5167 1487 5168 1489 5168 2647 5168 1487 5169 2647 5169 2646 5169 1489 5170 20 5170 21 5170 1489 5171 21 5171 2647 5171 100 5172 1055 5172 2611 5172 100 5173 2611 5173 101 5173 1055 5174 1057 5174 2612 5174 1055 5175 2612 5175 2611 5175 1057 5176 1059 5176 2613 5176 1057 5177 2613 5177 2612 5177 1059 5178 1061 5178 2614 5178 1059 5179 2614 5179 2613 5179 1061 5180 1063 5180 2615 5180 1061 5181 2615 5181 2614 5181 1063 5182 1065 5182 2616 5182 1063 5183 2616 5183 2615 5183 1065 5184 1067 5184 2617 5184 1065 5185 2617 5185 2616 5185 1067 5186 1069 5186 2618 5186 1067 5187 2618 5187 2617 5187 1069 5188 1071 5188 2619 5188 1069 5189 2619 5189 2618 5189 1071 5190 1073 5190 2620 5190 1071 5191 2620 5191 2619 5191 1073 5192 1075 5192 2621 5192 1073 5193 2621 5193 2620 5193 1075 5194 1077 5194 2622 5194 1075 5195 2622 5195 2621 5195 1077 5196 1079 5196 2623 5196 1077 5197 2623 5197 2622 5197 1079 5198 1081 5198 2624 5198 1079 5199 2624 5199 2623 5199 1081 5200 1083 5200 2625 5200 1081 5201 2625 5201 2624 5201 1083 5202 1085 5202 2626 5202 1083 5203 2626 5203 2625 5203 1085 5204 1087 5204 2627 5204 1085 5205 2627 5205 2626 5205 1087 5206 1089 5206 2628 5206 1087 5207 2628 5207 2627 5207 1089 5208 1091 5208 2629 5208 1089 5209 2629 5209 2628 5209 1091 5210 16 5210 19 5210 1091 5211 19 5211 2629 5211 5 5212 2232 5212 1832 5212 5 5213 1832 5213 6 5213 2232 5214 2234 5214 1833 5214 2232 5215 1833 5215 1832 5215 2234 5216 2236 5216 1834 5216 2234 5217 1834 5217 1833 5217 2236 5218 2238 5218 1835 5218 2236 5219 1835 5219 1834 5219 2238 5220 2240 5220 1836 5220 2238 5221 1836 5221 1835 5221 2240 5222 2242 5222 1837 5222 2240 5223 1837 5223 1836 5223 2242 5224 2244 5224 1838 5224 2242 5225 1838 5225 1837 5225 2244 5226 2246 5226 1839 5226 2244 5227 1839 5227 1838 5227 2246 5228 2248 5228 1840 5228 2246 5229 1840 5229 1839 5229 2248 5230 2250 5230 1841 5230 2248 5231 1841 5231 1840 5231 2250 5232 2252 5232 1842 5232 2250 5233 1842 5233 1841 5233 2252 5234 2254 5234 1843 5234 2252 5235 1843 5235 1842 5235 2254 5236 2256 5236 1844 5236 2254 5237 1844 5237 1843 5237 2256 5238 2258 5238 1845 5238 2256 5239 1845 5239 1844 5239 2258 5240 2260 5240 1846 5240 2258 5241 1846 5241 1845 5241 2260 5242 2262 5242 1847 5242 2260 5243 1847 5243 1846 5243 2262 5244 2264 5244 1848 5244 2262 5245 1848 5245 1847 5245 2264 5246 2266 5246 1849 5246 2264 5247 1849 5247 1848 5247 2266 5248 2268 5248 1850 5248 2266 5249 1850 5249 1849 5249 2268 5250 8 5250 11 5250 2268 5251 11 5251 1850 5251 13 5252 1852 5252 21 5252 13 5253 21 5253 14 5253 1852 5254 1854 5254 2647 5254 1852 5255 2647 5255 21 5255 1854 5256 1856 5256 2646 5256 1854 5257 2646 5257 2647 5257 1856 5258 1858 5258 2645 5258 1856 5259 2645 5259 2646 5259 1858 5260 1860 5260 2644 5260 1858 5261 2644 5261 2645 5261 1860 5262 1862 5262 2643 5262 1860 5263 2643 5263 2644 5263 1862 5264 1864 5264 2642 5264 1862 5265 2642 5265 2643 5265 1864 5266 1866 5266 2641 5266 1864 5267 2641 5267 2642 5267 1866 5268 1868 5268 2640 5268 1866 5269 2640 5269 2641 5269 1868 5270 1870 5270 2639 5270 1868 5271 2639 5271 2640 5271 1870 5272 1872 5272 2638 5272 1870 5273 2638 5273 2639 5273 1872 5274 1874 5274 2637 5274 1872 5275 2637 5275 2638 5275 1874 5276 1876 5276 2636 5276 1874 5277 2636 5277 2637 5277 1876 5278 1878 5278 2635 5278 1876 5279 2635 5279 2636 5279 1878 5280 1880 5280 2634 5280 1878 5281 2634 5281 2635 5281 1880 5282 1882 5282 2633 5282 1880 5283 2633 5283 2634 5283 1882 5284 1884 5284 2632 5284 1882 5285 2632 5285 2633 5285 1884 5286 1886 5286 2631 5286 1884 5287 2631 5287 2632 5287 1886 5288 1888 5288 2630 5288 1886 5289 2630 5289 2631 5289 1888 5290 0 5290 3 5290 1888 5291 3 5291 2630 5291

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_distal/mst/f_distal_mst.dae b/URDFs/sr_description/meshes/components/f_distal/mst/f_distal_mst.dae new file mode 100644 index 0000000..95cc952 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_distal/mst/f_distal_mst.dae @@ -0,0 +1,134 @@ + + + + + + Blender User + Blender 3.4.1 commit date:2022-12-19, commit time:17:00, hash:55485cb379f7 + + 2023-02-02T13:19:49 + 2023-02-02T13:19:49 + + Z_UP + + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + + -6.265552 5.253327 8.419782 -6.268001 5.238142 11.55959 -6.162201 5.599242 8.419817 -6.275555 5.184584 15.85149 -6.279614 5.148108 17.69344 -6.286395 5.04174 21.56192 -6.238833 5.375434 24.16979 -6.286809 5.023198 22.1161 -6.285982 4.943182 24.16975 -5.727032 6.167278 24.16987 -5.727132 6.168904 8.419874 -5.979194 5.910443 8.419849 -6.046765 5.812614 24.16984 6.268013 5.238317 11.55892 6.265519 5.25352 8.419703 6.162149 5.599361 8.419739 6.27563 5.184734 15.85083 6.239033 5.375434 24.16972 6.286185 4.943249 24.16967 6.286982 5.0233 22.11556 6.286558 5.041875 21.56052 6.279717 5.148255 17.69238 5.979155 5.910495 8.419773 6.046965 5.812614 24.16976 5.727131 6.168904 8.419801 5.727231 6.167278 24.1698 1.556324 7.748831 19.73711 2.000072 7.748833 19.72601 2 7.75 8.419988 -2 7.75 8.420013 -1.999928 7.748833 19.72604 -1.556184 7.748831 19.73713 -1.112464 7.74883 19.74942 0.2876734 7.748829 19.76273 1.112608 7.74883 19.74941 -3.119263 7.623115 8.420007 -2.709614 7.698211 19.73069 -2.590025 7.71389 19.72303 -2.842582 7.678494 8.420011 -2.469851 7.726702 19.72083 -2.235139 7.743298 19.72254 -4.18172 7.2489 8.419976 -4.163424 7.25646 20.33826 -3.929839 7.361318 20.15977 -3.591325 7.488793 19.9662 -3.448616 7.534345 19.90408 -3.661064 7.466022 8.419995 -3.119772 7.621807 19.79846 -3.089407 7.628686 19.79113 -5.133445 6.646347 8.419919 -5.133359 6.644954 21.90964 -4.999627 6.748863 21.53757 -4.790502 6.897503 21.10778 -4.71424 6.947806 20.981 -4.459299 7.102067 20.63466 -4.432035 7.118662 8.419963 -5.409958 6.422268 24.1699 -5.409605 6.422587 23.84507 -5.405278 6.426089 23.64811 -5.359803 6.462727 23.03599 -5.221849 6.573755 22.24094 -5.259277 6.543637 22.40924 -5.266342 6.537952 22.44361 -5.265805 6.538384 22.44097 -5.263647 6.540122 22.43039 -5.26687 6.537527 22.44622 5.41882 6.415328 23.91983 5.418822 6.415301 24.16983 5.279756 6.527303 22.49856 5.133531 6.644954 21.90957 5.133445 6.646347 8.419854 5.283987 6.523897 22.51984 5.322376 6.493005 22.73188 5.394569 6.434889 23.32045 3.855171 7.391919 20.11082 4.163576 7.25646 20.33821 4.18172 7.2489 8.419922 4.999806 6.748854 21.53754 4.790663 6.897503 21.10772 4.432035 7.118662 8.419907 4.459454 7.102067 20.6346 4.7144 6.947806 20.98094 2.589999 7.71391 19.72299 2.709758 7.698211 19.73065 3.119264 7.623115 8.419967 2.469995 7.726702 19.7208 2.842582 7.678494 8.419975 2.235283 7.743298 19.72251 3.047862 7.637808 19.78167 3.120488 7.621675 19.79856 3.661064 7.466022 8.419948 3.409567 7.546037 19.88878 3.518921 7.512539 19.93325 -1.260938 5.836726 30.06702 -0.9458001 5.811997 30.14223 -1.148098 5.84722 30.08275 -5.064266 6.148932 26.89106 -5.050098 6.166999 26.87086 -5.102795 6.16701 26.76993 -5.116946 5.610023 27.59311 -5.159529 5.757475 27.38732 -5.387679 5.812331 26.91506 -5.159948 5.917734 27.17643 -5.12627 6.039918 27.02171 -4.990756 5.447917 27.87857 -5.088188 5.557757 27.67495 -5.558812 5.375142 27.00221 -5.103627 5.583106 27.63383 -4.714704 5.289527 28.28548 -5.004023 5.024052 27.97544 -4.5611 5.237273 28.46878 -4.643924 5.03373 28.40709 -4.506127 5.233339 28.52728 -4.445102 5.039719 28.61499 -4.451336 5.23644 28.58253 -3.915538 5.337346 29.03879 -4.144621 5.29789 28.85683 -4.247951 5.046242 28.8035 -4.177798 5.289294 28.8296 -4.431585 5.238932 28.60179 -2.937392 5.556961 29.60586 -3.08142 5.522494 29.54093 -2.832281 5.374861 29.7287 -3.512964 5.421732 29.30989 -3.667021 5.374914 29.21718 -3.933961 5.057915 29.07234 -2.41094 5.670656 29.80324 -1.927799 5.374822 30.10335 -1.852639 5.76496 29.9565 -0.5056722 5.887997 30.14279 1.38472e-4 5.81199 30.21667 0.1413636 5.896996 30.15581 0.7849858 5.87422 30.12268 0.9460761 5.811997 30.14221 0.9197589 5.865409 30.10973 1.928074 5.374822 30.10332 1.878883 5.761155 29.95046 1.503912 5.810717 30.02755 0.9761233 5.374798 30.33187 3.081688 5.522494 29.54089 2.937661 5.556961 29.60582 2.832552 5.374861 29.72867 2.59215 5.63435 29.74171 2.061825 5.732759 29.90517 4.144881 5.29789 28.85678 3.9158 5.337346 29.03874 4.060556 5.053074 28.96842 3.513229 5.421732 29.30985 3.667285 5.374914 29.21714 3.612543 5.071516 29.31318 4.8825 5.368076 28.05676 4.850004 5.028111 28.17 5.09906 5.021697 27.84747 4.729227 5.297951 28.26643 4.714956 5.289527 28.28542 4.473155 5.038899 28.587 4.561414 5.237281 28.46866 4.505065 5.233333 28.52858 4.445363 5.03977 28.61493 4.451592 5.23644 28.58247 4.178057 5.289294 28.82955 5.165822 5.829689 27.29101 5.144503 5.686538 27.48437 5.559048 5.375142 27.00214 5.11719 5.610023 27.59305 5.103871 5.583106 27.63377 5.088432 5.557757 27.67488 5.047526 5.375056 27.83688 5.079044 5.544167 27.69792 4.975644 5.434626 27.90594 5.050333 6.166999 26.8708 5.115898 6.063777 26.99219 5.387914 5.812331 26.91499 5.148813 5.973511 27.10505 6.162228 5.375334 25.1457 6.208902 4.945934 25.15302 6.231123 4.937755 24.99832 6.274685 4.930133 24.54076 5.933691 5.375236 26.09766 5.67462 5.004312 26.87661 5.893043 4.99234 26.36076 6.022844 4.980687 25.97329 6.149472 4.96143 25.47629 5.410019 5.013432 27.37275 1.466004 5.175086 30.27273 1.723213 5.164359 30.20644 2.259925 5.138896 30.02952 2.77351 5.112533 29.80715 3.263608 5.087803 29.54031 0.9111385 5.193676 30.37749 0.3470029 5.204699 30.43289 1.39692e-4 5.374791 30.40869 1.35651e-4 5.206728 30.4422 -1.555873 5.171442 30.25083 -0.975845 5.374798 30.33188 -1.002797 5.19107 30.36365 -0.442961 5.203453 30.427 -3.477708 5.077581 29.40478 -2.997432 5.101005 29.6922 -2.493755 5.126942 29.93499 -2.100767 5.146747 30.08757 -5.675904 5.004188 26.8735 -5.410686 5.013348 27.37128 -5.047279 5.375056 27.83694 -4.89544 5.376219 28.03681 -4.728975 5.297951 28.26649 -5.08609 5.021963 27.8651 -5.326791 5.015707 27.50896 -5.894915 4.992126 26.35518 -5.933466 5.375236 26.09773 -5.979226 4.985118 26.11254 -6.162015 5.375334 25.14578 -6.213572 4.944214 25.12135 -6.108768 4.968893 25.65488 -6.066933 4.975159 25.81789 -6.265874 4.929394 24.66493 5.103028 6.16701 26.76987 5.751022 5.812421 26.03835 5.446937 6.167096 25.93958 5.972524 5.812516 25.1157 5.656727 6.167186 25.06572 -5.446714 6.167096 25.93965 -5.750799 5.812421 26.03842 -5.656515 6.167186 25.06579 -5.972312 5.812516 25.11578 -1.067204 6.954281 30.81184 -1.590085 6.901131 30.7064 -1.671945 6.88886 30.68593 -2.187901 6.814229 30.53127 -2.25374 6.791835 30.50824 -2.770354 6.702172 30.30006 -2.770354 6.672853 30.30005 -5.407767 6.424004 24.18827 -4.961621 6.25293 26.80972 -4.989132 6.228824 26.82183 -4.695404 6.366551 26.99324 -4.791862 6.337689 26.89951 -5.391602 6.435381 24.31793 -5.333665 6.46025 24.72676 -5.284033 6.466324 25.0392 -4.867423 6.329061 26.78514 -4.983892 6.338352 26.52891 -5.106372 6.379819 26.10993 -5.218267 6.454959 25.43377 4.989366 6.228824 26.82176 5.019102 6.284859 26.60969 4.961855 6.25293 26.80966 4.948215 6.286313 26.74647 4.8574 6.298395 26.88313 5.193883 6.310919 26.12123 5.142882 6.298857 26.29152 5.393706 6.398775 24.87251 5.374398 6.38705 25.09729 5.307257 6.352105 25.60249 2.664441 7.507975 19.92976 2.836583 7.462436 19.9531 2.965705 7.460676 19.97669 3.228207 7.353397 20.05996 3.288137 7.383944 20.07553 3.3608 7.362773 20.10563 3.341365 7.320503 20.1056 3.385732 7.355172 20.11668 3.584217 7.24779 20.22795 3.686387 7.249527 20.28161 3.887802 7.152693 20.43305 3.963143 7.128339 20.4941 -3.96299 7.128339 20.49415 -3.887649 7.152693 20.4331 -3.753277 7.222343 20.32724 -3.584067 7.24779 20.228 -3.450375 7.334601 20.14721 -3.341217 7.320503 20.10564 -3.360632 7.36278 20.10566 -3.322962 7.373937 20.08967 -3.228059 7.353397 20.06 -3.002704 7.453237 19.98541 -2.836437 7.462436 19.95313 -2.664295 7.507975 19.9298 -3.975892 6.638319 21.38218 -4.047878 6.613469 21.49121 -3.56523 6.769745 29.51774 -4.257183 6.538354 21.87524 -4.37755 6.493202 22.16067 -4.4649 6.459527 22.41309 -4.538209 6.430669 22.66959 -4.591603 6.409305 22.90018 -4.669451 6.377615 23.40711 -4.695424 6.366868 23.91989 -4.958343 6.254374 26.8121 -4.929045 6.267232 26.83719 -4.904894 6.277762 26.86483 -4.890535 6.283993 26.88577 -4.885298 6.28626 26.89457 -4.868776 6.293392 26.92802 -4.845031 6.303591 26.99924 -4.843744 6.304141 27.00413 -4.843739 6.304063 27.76464 -4.663856 6.379404 28.1821 -4.470764 6.456595 28.52247 -4.186442 6.563463 28.91392 -3.851973 6.679084 29.27154 -2.953148 6.938953 20.53005 -3.156608 6.885811 29.79748 -2.651298 7.009596 20.44579 -2.361526 7.069918 20.41995 -3.231843 6.866537 20.66497 -3.47383 6.797954 20.83316 -3.737187 6.717175 21.08138 -1.086038 7.250714 20.41996 -0.7966129 7.271883 30.54991 -0.2254233 7.296694 20.41766 -0.1846414 7.296323 30.59456 -0.1255347 7.29812 20.41752 -2.712978 6.994811 30.02671 -2.142587 7.109672 30.24761 -1.887559 7.153054 20.41995 -1.889283 7.151753 30.32707 -1.72615 7.177026 20.41995 -1.557153 7.198747 30.41493 -0.9579156 7.260349 30.52876 1.086191 7.250714 20.41994 1.214888 7.237591 30.48686 1.726303 7.177026 20.41993 1.818233 7.162626 30.34745 1.887711 7.153054 20.41993 7.6844e-5 7.298761 20.41745 2.43611e-4 7.29771 30.59708 0.736799 7.276678 20.41922 0.4237846 7.290414 30.58378 1.028815 7.254628 30.51824 3.15688 6.885811 29.79744 3.231999 6.866537 20.66493 2.953302 6.938953 20.53001 2.405463 7.060277 30.15333 2.713252 6.994811 30.02667 2.361678 7.069918 20.41992 2.65145 7.009596 20.44575 4.9083 6.276382 26.86066 4.664107 6.379404 28.18204 4.843985 6.304063 27.76457 4.843981 6.304141 27.00407 4.471019 6.456595 28.52242 4.69564 6.366556 26.9469 4.186703 6.563463 28.91386 3.852238 6.679084 29.27149 4.782788 6.330171 26.92482 4.746288 6.345505 26.93776 4.846206 6.303178 27.00003 4.801238 6.322368 26.91639 4.700629 6.364494 26.9465 4.905375 6.277655 26.86444 4.817837 6.315317 26.90775 4.870801 6.292621 26.92383 4.889718 6.284448 26.88742 3.565498 6.769745 29.5177 4.695621 6.366868 23.91983 4.669641 6.377615 23.40706 4.591787 6.409305 22.90012 4.538391 6.430669 22.66954 4.464618 6.459706 22.41158 4.377778 6.493181 22.16075 4.257189 6.538415 21.87484 4.048044 6.613469 21.49116 3.976057 6.638319 21.38213 3.737348 6.717175 21.08133 3.473988 6.797954 20.83311 0.8754327 6.664931 30.52505 0.9943943 6.655397 30.5156 0.4146515 6.690367 30.58294 -0.9101911 6.662249 30.52885 -0.9941136 6.655397 30.51561 -0.563723 6.684121 30.54386 0.1575311 6.696656 30.55597 -0.1637721 6.696563 30.59483 -0.7406597 6.674239 30.55196 2.770632 6.672853 30.30002 2.770632 6.702172 30.30002 2.456334 6.766041 30.43258 1.347572 6.928098 30.76071 1.623398 6.895403 30.69825 1.396662 6.923289 30.75049 1.277952 6.935246 30.77457 1.24058 6.939027 30.78169 1.208065 6.941991 30.78771 1.154058 6.94694 30.79734 1.067489 6.954281 30.81183 2.206682 6.801118 30.52485 1.856685 6.865891 30.63577 1.551362 6.905828 30.71574 4.837702 5.833734 28.27691 4.926489 5.872355 28.07821 4.819724 6.101794 28.31407 4.951034 5.894242 28.01792 4.985714 5.944778 27.92785 4.991098 5.957423 27.91329 4.995769 5.971857 27.90052 5.002542 5.999581 27.88179 5.00866 6.028295 27.86462 4.549836 5.932272 28.78516 4.651382 5.870583 28.62393 4.616912 6.177099 28.68052 4.677667 5.856093 28.57941 4.775092 5.830079 28.40244 3.721349 6.344857 29.70688 3.665793 6.482601 29.75205 3.410736 6.471173 29.94055 3.236599 6.595833 30.05323 2.987431 6.613542 30.19446 4.500363 5.961049 28.85823 4.500241 6.218761 28.85844 4.441239 5.994548 28.94145 4.318279 6.281356 29.10196 4.103707 6.170331 29.3483 3.966973 6.394154 29.48698 3.733554 6.463356 29.69675 -3.210839 6.543255 30.06875 -3.236324 6.595833 30.05327 -3.410462 6.471173 29.9406 -3.665522 6.482601 29.7521 -3.733407 6.339573 29.69668 -3.733283 6.463356 29.6968 -3.828145 6.298238 29.6153 -3.966705 6.394154 29.48704 -4.199521 6.12267 29.24278 -4.318016 6.281356 29.10201 -4.440979 5.994548 28.94151 -4.499981 6.218761 28.85849 -4.616655 6.177099 28.68058 -4.549578 5.932272 28.78522 -4.500104 5.961049 28.85829 -4.877926 5.845402 28.18979 -4.774838 5.830079 28.4025 -4.819471 6.101794 28.31413 -4.742587 5.834342 28.46334 -4.651126 5.870583 28.62399 -5.008413 6.028295 27.86468 -5.002294 5.999581 27.88185 -4.995522 5.971857 27.90059 -4.99085 5.957423 27.91335 -4.985466 5.944778 27.92791 -4.969701 5.91751 27.96962 -4.917593 5.8662 28.09889 -4.90166 6.271289 27.01139 -4.908401 6.266264 26.95082 -4.916998 6.259403 26.95618 -4.872451 6.289989 26.96282 -4.888013 6.280624 26.95145 -4.899337 6.272963 26.94893 -4.928183 6.249659 26.9689 -4.950903 6.226471 27.01865 -4.958535 6.217436 27.04286 -5.020573 5.973632 27.7646 -5.015219 6.10653 27.76462 -5.025524 6.021674 27.6155 -5.016463 6.101817 27.37531 -4.993732 6.16292 27.19659 -4.951344 6.225886 27.76463 4.872687 6.289989 26.96275 4.902876 6.270576 27.00931 4.888249 6.280624 26.95139 4.899573 6.272963 26.94886 4.908637 6.266264 26.95076 4.951139 6.226471 27.01858 4.928419 6.249659 26.96883 4.917233 6.259403 26.95611 4.95159 6.225886 27.76457 5.015465 6.10653 27.76455 5.020818 5.973632 27.76454 5.022872 5.986199 27.725 5.024391 6.057787 27.50623 5.008199 6.129711 27.29319 4.987645 6.174851 27.16218 -5.002145 6.106569 27.85061 -4.94607 6.225996 27.81267 -4.991909 6.143075 27.84145 -4.806679 6.218883 28.28435 -4.751808 6.316771 28.2378 -4.93402 6.24002 27.80628 -4.607568 6.296634 28.64603 -4.313853 6.404422 29.06281 -3.669915 6.612983 29.70818 -3.967523 6.521236 29.44462 -3.24473 6.730633 30.00857 -2.781753 6.841307 30.25567 -4.555963 6.395499 28.5901 -4.267104 6.504657 28.99598 -3.926555 6.622977 29.36767 -3.633961 6.715922 29.62417 -3.216005 6.835125 29.9164 -2.760976 6.947275 30.15669 3.96779 6.521236 29.44456 4.946316 6.225996 27.81261 4.934266 6.24002 27.80622 4.752059 6.316771 28.23774 4.806931 6.218883 28.28429 4.992156 6.143075 27.84139 5.002392 6.106569 27.85054 4.607826 6.296634 28.64597 4.314116 6.404422 29.06276 4.556219 6.395499 28.59004 4.267366 6.504657 28.99592 3.926821 6.622977 29.36762 3.634231 6.715922 29.62412 3.216278 6.835125 29.91636 2.761253 6.947275 30.15665 3.670185 6.612983 29.70814 3.245004 6.730633 30.00853 2.782031 6.841307 30.25564 -2.181895 7.064718 30.385 2.448903 7.014185 30.28751 1.866164 7.01086 30.59335 2.467365 6.907399 30.38886 1.247498 7.08675 30.74043 1.048594 7.213272 30.66529 1.238115 7.195791 30.63276 1.852159 7.118941 30.48833 -0.1882424 7.256077 30.74446 0.4320273 7.250009 30.73327 -0.812018 7.230982 30.69813 -0.9763694 7.219143 30.6762 1.056545 7.104012 30.77357 0.4353066 7.140285 30.84281 -0.1896719 7.146276 30.85421 -0.818179 7.121498 30.80702 -0.9837747 7.109808 30.78468 -0.8134611 6.972482 30.84768 -0.1885474 6.996325 30.89441 0.4327459 6.990561 30.88313 1.050572 6.955649 30.81453 -0.9781751 6.96123 30.82554 -2.198369 6.95731 30.48813 -1.598563 7.047415 30.66451 -1.586552 7.155958 30.55821 -4.994606 6.190226 26.94342 -5.007149 5.912666 27.81633 -5.014347 5.942834 27.78992 -5.018214 5.775109 27.70602 -5.058668 5.880108 27.49249 -5.067301 5.998919 27.27084 -5.047355 6.091924 27.10624 -5.004678 6.176181 26.96544 -4.999114 5.887864 27.84385 -5.015625 5.735192 27.72432 -4.991502 5.86961 27.86638 -5.004939 5.712256 27.75784 -4.971534 5.832516 27.91961 -4.909403 5.758296 28.06241 -4.698317 5.507511 28.30935 -4.84131 5.557996 28.09445 -4.924536 5.614493 27.94384 -4.861579 5.721427 28.15868 -4.730123 5.668028 28.38532 -4.46367 5.476432 28.57427 -4.685684 5.661726 28.45239 -4.608922 5.46421 28.4118 -4.658027 5.66044 28.49213 -4.545776 5.675648 28.63981 -4.153633 5.432051 28.83746 -4.425579 5.721392 28.79169 -4.348762 5.580186 28.72723 -4.304714 5.410007 28.70598 -4.300019 5.770799 28.93694 -4.207593 5.619708 28.86001 -4.031696 5.750615 29.06595 -4.030621 5.879241 29.21064 -3.12333 6.103056 29.66855 -3.210085 6.198237 29.81327 -3.635225 6.03708 29.53813 -3.113397 5.710035 29.48966 -2.971781 5.751095 29.55008 -3.536669 5.588209 29.27184 -3.176606 5.895606 29.50944 -3.037436 5.94392 29.57221 -3.261233 6.050388 29.59722 -3.665847 5.892729 29.34894 -3.589733 5.751687 29.28539 -3.969939 5.623858 29.02206 -3.93006 5.481976 29.01273 -2.438174 5.868124 29.73743 2.80621 6.330424 30.01828 2.835949 6.30423 29.95811 3.210357 6.198237 29.81323 0.8555075 6.618578 30.31247 1.002556 6.607007 30.30093 1.640918 6.535234 30.22671 1.514794 6.598235 30.42614 2.252543 6.43306 30.11342 2.064862 6.50788 30.28737 2.602794 6.386246 30.10331 3.038476 5.945708 29.57278 3.124955 6.105016 29.67043 2.755349 6.197988 29.79772 2.972305 5.752079 29.54996 2.679581 6.030575 29.69903 2.621831 5.831126 29.67921 2.084583 5.931278 29.8334 0.153987 6.648503 30.34176 -0.5509746 6.636677 30.33029 -1.251896 6.583127 30.27675 -1.560377 6.591924 30.41637 -1.375197 6.569354 30.26257 -2.109476 6.499038 30.27394 -2.022994 6.475248 30.16129 -2.602519 6.386246 30.10335 -2.636403 6.351745 30.01703 -3.01816 6.264859 29.91696 -2.561801 6.241582 29.85466 -1.966592 6.354768 29.99414 -1.337434 6.44088 30.09215 -1.217607 6.453473 30.10588 -0.5360461 6.502408 30.15773 0.1498292 6.513209 30.16885 0.8322446 6.485874 30.14047 0.9752292 6.4753 30.12929 1.595595 6.409671 30.05743 2.189392 6.316126 29.94784 -2.4916 6.070313 29.75564 -1.913305 6.173293 29.89481 -1.301583 6.251421 29.99317 -1.185024 6.262829 30.00699 -0.5218054 6.307106 30.05935 0.1458595 6.316868 30.0706 0.8100858 6.292155 30.0419 0.9492213 6.282588 30.03061 1.552652 6.223131 29.95826 2.129825 6.138169 29.84852 -1.872859 5.963952 29.88145 -1.27438 6.03658 29.98423 -1.1603 6.047177 29.99877 -0.5109881 6.088291 30.05402 0.1428438 6.097351 30.06595 0.7932621 6.074412 30.03556 0.9294795 6.065529 30.02364 1.520072 6.01029 29.94765 3.524793 6.08011 29.61666 3.261502 6.050388 29.59718 3.176874 5.895606 29.5094 3.113664 5.710035 29.48962 3.666113 5.892729 29.34889 3.589998 5.751687 29.28534 3.536934 5.588209 29.27179 3.930321 5.481976 29.01268 3.9702 5.623858 29.02201 4.031959 5.750615 29.0659 3.926675 5.921274 29.30466 4.30028 5.770799 28.93688 4.234823 5.67485 28.87991 4.184082 5.55739 28.84544 4.153383 5.428724 28.83754 4.304972 5.410007 28.70593 4.349021 5.580186 28.72718 4.425837 5.721392 28.79164 4.546033 5.675648 28.63975 4.483217 5.544736 28.58776 4.463898 5.476308 28.5742 4.450062 5.391246 28.5676 4.698632 5.467565 28.29661 4.65354 5.46473 28.35618 4.591626 5.464419 28.43288 4.589336 5.665868 28.58528 4.693796 5.662456 28.44077 4.730377 5.668028 28.38526 4.830069 5.55207 28.11337 4.811634 5.694065 28.25078 4.911417 5.603491 27.96984 4.919944 5.76804 28.0403 4.998206 5.699733 27.77745 4.949076 5.800399 27.97474 4.99175 5.86961 27.86632 5.005207 5.712181 27.75773 5.01587 5.735192 27.72425 5.007396 5.912666 27.81627 4.999361 5.887864 27.84379 5.018459 5.775109 27.70595 5.023909 5.758583 27.69364 5.014593 5.942834 27.78985 5.043428 5.828984 27.59353 5.067358 5.933133 27.39163 5.061563 6.041155 27.19514 5.040548 6.110279 27.07462 4.994842 6.190226 26.94335 4.992547 5.906689 27.89808 4.763021 5.745635 28.39933 4.832477 5.761783 28.26737 4.92804 5.819278 28.06095 4.954267 5.846609 27.99769 4.647997 5.75457 28.59272 4.614369 5.765658 28.64424 4.363928 5.832879 28.95604 4.505758 5.816788 28.80447 4.390377 5.869908 28.95907 4.4124 5.909819 28.95761 3.675538 6.233684 29.71339 3.361578 6.352529 29.94081 3.606301 6.140426 29.68161 3.29044 6.255631 29.89561 4.065148 6.070824 29.36116 4.003499 5.984094 29.34596 2.941698 6.486154 30.18368 2.651063 6.420713 30.1891 2.876864 6.384865 30.12065 2.727565 6.542138 30.28438 2.69885 6.485659 30.25526 2.667339 6.439294 30.21379 1.054215 6.838953 30.79043 1.545054 6.623557 30.5338 2.104904 6.537858 30.3852 1.576183 6.688596 30.62295 2.145398 6.603157 30.46375 1.603634 6.783849 30.68058 2.180912 6.695019 30.51248 1.014601 6.676971 30.62988 1.035627 6.741486 30.72648 -1.014319 6.676971 30.6299 -1.035343 6.741486 30.72649 -0.9286834 6.684026 30.64322 -1.053931 6.838953 30.79044 -0.9479245 6.748623 30.73993 -0.7556974 6.696371 30.66648 -0.1670945 6.719353 30.70962 0.4230589 6.712975 30.69766 -0.7713432 6.761112 30.7634 -0.170551 6.784361 30.80693 0.4318055 6.777909 30.79487 -0.9649434 6.846066 30.80406 -0.7851927 6.858514 30.82784 -0.1736152 6.881685 30.87195 0.4395557 6.875255 30.85972 -2.227535 6.686238 30.49636 -2.650786 6.420713 30.18914 -2.150261 6.529403 30.37085 -2.667062 6.439294 30.21383 -2.191441 6.5947 30.44844 -2.740102 6.573234 30.29382 -2.727287 6.542138 30.28441 -2.698572 6.485659 30.2553 -1.65164 6.777707 30.66865 -1.623459 6.682694 30.61169 -1.59149 6.617618 30.52332 -3.094285 6.320865 30.00947 -3.16296 6.420091 30.06357 -3.290167 6.255631 29.89565 -3.361305 6.352529 29.94085 -4.390117 5.869908 28.95912 -4.363667 5.832879 28.95609 -4.104758 5.942284 29.2457 -4.163381 6.026775 29.25686 -4.412139 5.909819 28.95766 -3.784002 6.189992 29.62379 -3.716248 6.098273 29.59668 -4.505499 5.816788 28.80453 -4.614112 5.765658 28.6443 -4.725788 5.743762 28.46465 -4.762767 5.745635 28.39939 -4.992299 5.906689 27.89814 -4.974493 5.874427 27.94575 -4.918567 5.811243 28.08248 -4.876092 5.781933 28.17681 5.177202 6.42217 24.16983 5.1772 6.422195 23.91983 5.028094 6.34947 23.91983 4.900701 6.32893 26.5549 4.986872 6.338937 26.24373 4.860367 6.329684 23.91982 5.022255 6.347558 26.07715 5.100609 6.37699 25.56983 5.160014 6.410346 24.85632 4.749331 6.347882 26.88343 4.767975 6.342953 26.85517 4.85118 6.329965 26.68859 5.004239 6.362966 23.37101 5.03555 6.518155 22.56792 4.932664 6.403304 22.82633 5.075777 6.490965 22.77232 5.151648 6.439571 23.34049 4.883508 6.430977 22.5773 4.710107 6.398004 22.62016 4.761139 6.375015 22.86075 4.835542 6.341125 23.38791 5.03112 6.521147 22.54741 4.813335 6.468281 22.29811 4.607625 6.472013 22.06729 4.638442 6.429406 22.35059 4.879456 6.623335 21.98314 4.824599 6.572002 21.99702 4.731655 6.512655 22.02464 2.388481 7.206965 20.07335 2.374538 7.135685 20.16992 2.705044 7.063357 20.20438 4.68767 6.625523 21.68042 3.776612 6.944108 20.49741 4.08761 6.842341 20.78587 4.235278 7.000936 20.77186 4.36527 6.745495 21.12868 4.473865 6.873981 21.09807 4.448274 6.715399 21.25164 4.546184 6.832568 21.21791 4.747357 6.709942 21.62578 4.478341 6.522341 21.764 3.486253 7.033068 20.29741 3.1464 7.130125 20.13243 2.772515 7.228393 20.02483 2.409675 7.315312 19.98693 2.558831 7.523576 19.92265 2.453049 7.537024 19.92054 3.046537 6.979572 20.30318 3.35854 6.894827 20.45585 3.626677 6.815578 20.64236 3.915645 6.72332 20.91345 4.175199 6.634197 21.23797 4.25307 6.606274 21.35485 1.090268 7.296746 20.21005 1.770202 7.486798 19.95632 1.101749 7.42629 20.03895 1.745894 7.315289 20.07336 1.730428 7.206154 20.251 2.004194 7.574668 19.92427 1.561736 7.592442 19.9322 1.117675 7.605954 19.94099 2.22884 7.560204 19.92177 -1.101602 7.42629 20.03896 -1.090118 7.296746 20.21006 -0.2265213 7.337503 20.21983 0.7400374 7.319698 20.2161 0.2888816 7.619287 19.94989 -1.117528 7.605954 19.941 -0.228936 7.453241 20.0543 -0.232156 7.619624 19.95009 -0.127497 7.454094 20.05472 0.7478823 7.441377 20.04803 -0.1261509 7.338775 20.22007 -2.228694 7.560204 19.9218 -2.452903 7.537024 19.92057 -2.409529 7.315312 19.98696 -1.561593 7.592442 19.93222 -2.004047 7.574668 19.9243 -1.770056 7.486798 19.95634 -1.745746 7.315289 20.07339 -1.730278 7.206154 20.25103 -2.374389 7.135685 20.16995 -2.388333 7.206965 20.07338 -2.558834 7.523555 19.92269 -2.772367 7.228393 20.02486 -4.74866 6.52157 22.01907 -4.607381 6.472041 22.06716 -4.478349 6.522273 21.76443 -4.747178 6.709949 21.62582 -4.879347 6.62352 21.98297 -4.824353 6.572031 21.99689 -4.087453 6.842341 20.78592 -4.473704 6.873981 21.09813 -4.365108 6.745495 21.12874 -4.546021 6.832568 21.21796 -4.448111 6.715399 21.25169 -4.68769 6.625451 21.68087 -3.486102 7.033068 20.29745 -3.776459 6.944108 20.49745 -4.235121 7.000936 20.77191 -3.146251 7.130125 20.13247 -4.252906 6.606274 21.35491 -4.175037 6.634197 21.23802 -3.915486 6.72332 20.91349 -3.626522 6.815578 20.64241 -3.358387 6.894827 20.4559 -3.046386 6.979572 20.30322 -2.704894 7.063357 20.20441 -5.037208 6.546986 22.48882 -5.037869 6.546663 22.49136 -4.898572 6.437232 22.57395 -5.038518 6.546345 22.49386 -5.011827 6.559382 22.39477 -5.029189 6.550907 22.4584 -5.034553 6.548285 22.47867 -5.051301 6.540086 22.54404 -4.891903 6.617643 22.01733 -4.647942 6.429531 22.34918 -4.830747 6.475877 22.29512 -4.718056 6.398081 22.61805 -4.966531 6.416917 22.82025 -5.037762 6.374771 23.36802 -4.853173 6.340666 23.38607 -5.203755 6.462793 23.5086 -5.133697 6.498976 22.93362 -4.779134 6.37504 22.8569 -4.877871 6.329072 23.91989 -5.061487 6.360696 23.91989 -5.218277 6.455116 23.9199 4.769062 6.339862 26.90499 4.811147 6.321887 26.89739 4.918841 6.308535 26.72858 4.790461 6.334815 26.87656 4.983095 6.309696 26.59318 5.095042 6.327934 26.27798 5.141022 6.341666 26.10916 5.242764 6.386518 25.59441 5.319722 6.436079 24.86896 4.886037 6.323291 26.70901 4.942896 6.324659 26.57458 5.04156 6.341674 26.2616 5.081898 6.354288 26.09398 5.170631 6.395205 25.58301 5.237088 6.44017 24.86324 5.346125 6.452396 24.16983 5.341939 6.453489 24.16983 5.25613 6.455928 24.16983 5.251889 6.455074 24.16983 5.346123 6.452422 23.91983 5.251887 6.455101 23.91983 5.256128 6.455954 23.91983 5.341938 6.453515 23.91983 5.200191 6.56489 22.52057 5.111212 6.562687 22.53806 5.115613 6.559454 22.55868 5.204501 6.561508 22.54148 5.155562 6.530087 22.76435 5.243602 6.530816 22.74991 5.230813 6.474664 23.33636 5.317198 6.472999 23.32923 4.937829 6.664775 21.97428 4.959889 6.673595 21.96981 5.005798 6.683044 21.95836 5.051858 6.68119 21.94415 5.074129 6.676027 21.93626 4.871359 6.779487 21.59739 4.939651 6.776962 21.56965 4.804218 6.756086 21.61699 4.731256 6.92021 21.1487 4.655608 6.968515 21.02479 4.40383 7.116186 20.68687 4.113387 7.263419 20.39827 4.664377 6.915917 21.18382 4.589588 6.961827 21.06228 4.341767 7.10195 20.73126 4.057586 7.24147 20.44906 4.599596 6.88524 21.20804 4.525926 6.928712 21.08794 4.282613 7.061502 20.76108 4.004789 7.194001 20.48274 3.414813 7.42308 20.10027 2.67655 7.581907 19.91313 2.984896 7.531774 19.95925 2.680837 7.604381 19.90138 3.007102 7.590053 19.91638 2.701008 7.684584 19.80566 3.029142 7.62717 19.85422 2.697371 7.673789 19.82873 2.689368 7.643815 19.86963 3.486541 7.50783 20.00148 3.380321 7.539763 19.95812 3.450099 7.476516 20.05995 3.347208 7.507028 20.01758 3.314947 7.452497 20.05866 3.722238 7.3159 20.26737 3.766742 7.36611 20.23007 3.813341 7.392758 20.17518 2.582849 7.688985 19.82077 2.571491 7.619625 19.89353 2.46192 7.632513 19.8907 2.468087 7.701541 19.81801 2.232854 7.652858 19.88981 2.235189 7.71921 19.8176 2.003479 7.663394 19.8899 2.001993 7.726187 19.81841 1.56067 7.673046 19.89378 1.558737 7.728887 19.82412 1.116594 7.680205 19.90013 1.114797 7.730863 19.83221 0.2886059 7.687131 19.90718 0.2881803 7.732755 19.84127 -1.114652 7.730863 19.83222 -1.116448 7.680205 19.90015 -1.560527 7.673046 19.8938 -1.558596 7.728887 19.82414 -2.003333 7.663394 19.88992 -2.001848 7.726187 19.81844 -2.232708 7.652858 19.88984 -2.235044 7.71921 19.81763 -2.461775 7.632513 19.89073 -2.467942 7.701541 19.81804 -2.5715 7.619606 19.89357 -2.582866 7.688965 19.82081 -2.697227 7.673789 19.82876 -2.689222 7.643815 19.86966 -2.676403 7.581907 19.91316 -2.680691 7.604381 19.90141 -4.113234 7.263419 20.39833 -4.057434 7.24147 20.44911 -3.837109 7.338002 20.27713 -3.885951 7.363549 20.22316 -3.790576 7.288478 20.31363 -4.004635 7.194001 20.48278 -3.350588 7.442251 20.07296 -3.480947 7.402119 20.13117 -3.556879 7.485185 20.03366 -3.418244 7.528618 19.97303 -3.518235 7.45484 20.09142 -3.383935 7.496387 20.03213 -3.046142 7.581852 19.92524 -3.069463 7.618488 19.86335 -3.022776 7.524013 19.96796 -4.959316 6.673878 21.96866 -4.937261 6.665054 21.97313 -4.804039 6.756094 21.61702 -5.051304 6.681491 21.94297 -5.005228 6.683339 21.9572 -4.87118 6.779496 21.59743 -4.939472 6.776971 21.56968 -5.073561 6.676335 21.93507 -4.599433 6.88524 21.2081 -4.525764 6.928712 21.088 -4.282456 7.061502 20.76114 -4.664215 6.915917 21.18388 -4.589427 6.961827 21.06233 -4.34161 7.10195 20.73131 -4.731095 6.92021 21.14876 -4.655447 6.968515 21.02485 -4.403675 7.116186 20.68692 -5.097424 6.5726 22.48622 -5.194168 6.501455 23.05865 -5.241679 6.466424 23.65488 -5.246206 6.463069 23.84693 -5.332375 6.460859 23.8461 -5.096877 6.573003 22.4837 -5.096319 6.573412 22.48114 -5.094078 6.575059 22.47089 -5.089542 6.57839 22.45043 -5.050734 6.606875 22.28776 -5.141086 6.611095 22.26717 -5.179136 6.581245 22.43225 -5.18358 6.577757 22.453 -5.185777 6.576034 22.46339 -5.186324 6.575605 22.46598 -5.186861 6.575184 22.46854 -5.281537 6.500848 23.04854 -5.327954 6.46435 23.65184 -7.48618 -3.183963 16.47788 -7.876131 -2.246289 17.31835 -8.143911 -1.766994 14.29485 -8.431494 -0.3004291 15.05968 -8.367394 -0.8058593 14.81214 -8.149436 -1.186195 18.09487 -0.5623908 -6.787895 21.83287 -1.115531 -6.761717 21.75491 -1.035956 -6.904783 20.66539 -5.181681 -2.470676 27.88527 -5.7509 -2.394588 27.32892 -5.597725 -3.110108 26.58241 -6.261733 -2.311696 26.71796 -6.708969 -2.222786 26.05702 -6.541614 -2.913898 25.36083 -6.912824 -1.063879 27.01887 -6.851691 -1.484643 26.70795 -6.400738 -1.558947 27.39185 -7.000656 -0.07115685 27.51132 -6.963613 -0.5816798 27.29642 -6.511037 -0.6321283 28.00005 -8.505248 1.378948 8.422971 -8.483577 1.314265 11.85257 -8.336036 1.921644 11.83846 -1.829037 -5.916794 8.368462 -1.53543 -5.967684 8.604724 -2.563614 -5.862059 9.332693 -0.03729039 -6.075885 8.332571 1.40708e-4 -6.076116 8.33276 1.40708e-4 -6.423439 11.69553 -4.024098 4.565499 29.21929 -4.351165 4.544961 28.94293 -4.241851 4.398131 29.19129 -5.472006 4.488798 27.61267 -5.558603 4.484683 27.47161 -5.733524 4.389343 27.29984 -6.270261 4.420731 25.72481 -6.374197 4.387981 25.18645 -6.741053 3.855355 25.33494 -6.386403 4.381809 25.09941 -6.44381 4.348575 24.68091 -5.831284 4.469803 26.96267 -6.054702 4.452197 26.43472 -6.062026 4.385905 26.56202 -6.228381 4.429082 25.88971 -6.583223 3.862061 26.15086 -3.549576 4.598431 29.56063 1.40708e-4 4.587928 30.78252 1.40708e-4 4.741593 30.65419 -0.7479088 4.405885 30.86807 -0.4478834 4.739904 30.63643 -2.900871 -6.089908 11.77534 -2.062491 -6.095017 10.55941 -1.905692 -6.156695 10.80786 -1.21495 -6.074337 9.320796 -2.59958 -5.794514 8.377744 -2.71568 -5.779656 8.551241 -3.322721 -5.633994 8.382243 -3.739284 -5.543757 8.939589 -6.436492 -4.168388 8.966117 -5.943614 -4.508626 8.397814 -5.659684 -4.698023 8.766016 -5.320159 -4.87663 8.393659 -4.773083 -5.145553 8.563013 -4.784402 -5.134743 8.390295 -4.68493 -5.177611 8.389692 -7.101222 -3.559731 9.162866 -6.927411 -3.72015 8.405848 -6.45741 -4.135625 8.401482 -8.086996 -2.112313 9.528643 -7.773655 -2.681198 8.416188 -7.653882 -2.871554 9.350782 -7.424526 -3.17047 8.411629 -7.350121 -3.262014 8.410702 -7.132511 -3.509802 8.408108 -8.393101 -1.293793 9.696678 -8.298944 -1.61616 8.423271 -8.065869 -2.162048 8.420169 -8.622941 0.1537913 8.425876 -8.581398 -0.4432631 8.426231 -8.566256 -0.4303542 9.855269 -8.530912 -0.7672723 8.425909 -8.389712 -1.344096 8.4244 -8.560858 1.069279 8.423622 -8.618585 0.4716587 8.425151 -8.603737 0.4349363 10.00614 -8.345938 1.979719 8.422294 -8.105512 2.539909 11.80773 -8.122356 2.564722 8.422256 -7.792292 3.155253 11.76103 -7.86635 3.077299 8.422419 -7.399607 3.75393 11.69507 -7.515199 3.636351 8.422538 -6.936536 4.320412 11.60449 -7.107852 4.159731 8.422371 -6.646226 4.646214 8.421727 -6.537617 4.727872 11.55266 -6.542728 4.743482 8.421512 -6.495312 4.491343 21.53281 -6.597991 4.362329 21.63677 -6.492174 4.466375 22.08551 -7.008599 3.827188 21.95001 -6.477006 4.356834 24.12338 -7.629847 2.654089 24.21497 -7.210655 3.277467 24.82422 -7.294882 3.268423 23.96342 -6.909221 3.84147 23.653 -7.731902 2.63548 22.44171 -7.398392 3.249971 22.22303 -7.075312 3.286388 25.66555 -7.534107 2.663214 25.08843 -7.875005 1.997871 24.38302 -7.975651 1.985449 22.58773 -6.315843 3.868458 26.92934 -6.869652 3.295089 26.48026 -7.366649 2.672224 25.93457 -7.771118 2.003962 25.26504 -7.992028 1.289199 24.43236 -8.097222 1.293287 22.63283 -8.011795 0.5161751 24.3514 -8.123476 0.5671131 22.5643 -7.998458 0.08714157 24.23665 -8.114279 0.1716409 22.46316 -7.968477 -0.3554926 24.05549 -8.08944 -0.2346442 22.30183 -7.869333 -1.151448 23.55896 -5.137771 4.504058 28.09141 -5.313112 4.392547 27.98846 -5.948798 3.874494 27.66378 -6.558656 3.303392 27.25535 -7.118089 2.681292 26.74767 -7.580101 2.00998 26.11454 -7.88302 1.287196 25.31622 -6.548144 -0.1064726 28.22217 -7.021663 0.4206513 27.64854 -6.570141 0.3993728 28.36421 -6.574782 1.284859 28.46649 -6.057919 1.286457 29.13188 -1.015345 4.732306 30.56438 -1.490635 4.638324 30.52971 -1.494636 4.405164 30.71157 -2.217699 4.637615 30.27577 -2.228718 4.403997 30.45894 -2.917915 4.636653 29.9321 -2.938829 4.402416 30.11688 1.40708e-4 3.349325 31.51493 1.40708e-4 3.761249 31.32289 -0.7745465 3.348799 31.46345 -0.7622344 3.903492 31.19275 -1.551876 3.347186 31.31297 -1.525276 3.902228 31.03896 -2.320955 3.344554 31.06939 -2.277836 3.900186 30.79039 -3.070894 3.340972 30.73865 -3.008767 3.897417 30.45338 -3.790802 3.33651 30.32667 -3.70692 3.893973 30.03428 -4.469785 3.331236 29.83936 -5.462402 0.3613705 29.62889 -5.440395 -0.1696076 29.47816 -4.795924 -0.1968039 30.01329 1.40708e-4 1.929437 31.87307 1.40708e-4 2.912347 31.67212 -0.8254131 2.071663 31.80949 -0.7901012 2.739437 31.67284 -1.644655 2.083252 31.66453 -1.582726 2.740503 31.52554 -2.448902 2.088266 31.42933 -2.367397 2.739288 31.2868 -3.229472 2.087748 31.10911 -3.133778 2.736075 30.96213 -3.977684 2.082747 30.70911 -3.871533 2.731145 30.55707 -4.684854 2.074306 30.23456 -4.570326 2.724781 30.07713 -5.342303 2.063474 29.69068 -5.21982 2.717262 29.52784 -5.941346 2.051295 29.08271 -4.816926 0.3450056 30.16778 -4.098231 -0.2206708 30.47984 -4.117536 0.3306374 30.63764 -3.352701 -0.2408967 30.87278 -3.369605 0.3184453 31.03341 -2.564715 -0.2571702 31.18712 -2.578502 0.3086088 31.35004 -1.739658 -0.2691798 31.41785 -1.749597 0.3013074 31.58245 -0.8829118 -0.276614 31.55996 -0.8882592 0.2967203 31.72561 1.40708e-4 0.09826177 31.72611 1.40708e-4 0.2950272 31.77445 -6.026263 -0.1393933 28.87945 -6.048598 0.3795527 29.02601 -5.479971 0.8471463 29.70853 -4.836689 0.840152 30.24962 -4.138435 0.83393 30.72144 -3.390274 0.8284848 31.11889 -2.59727 0.8238208 31.43688 -1.76449 0.8199425 31.67033 -0.8969979 0.8168544 31.81412 1.40708e-4 0.9570177 31.87821 -5.475585 1.288235 29.73816 -4.832944 1.289784 30.2802 -4.135162 1.290693 30.75289 -3.387402 1.290552 31.15111 -2.594827 1.288953 31.46974 -1.762602 1.285484 31.70368 -0.8958919 1.279737 31.84779 1.40708e-4 1.271301 31.89696 -4.76352 4.522139 28.53518 -4.812113 4.395486 28.62118 -5.493234 3.880115 28.34784 -6.15228 3.311228 27.98473 -6.76915 2.690606 27.51912 -7.301223 2.017137 26.92656 -7.680888 1.285222 26.16679 -7.899611 0.4912647 25.22968 -7.884468 0.04583263 25.10853 -7.852363 -0.4145591 24.91796 -7.805866 -0.851508 24.67171 -7.748253 -1.238495 24.39617 -7.533697 -1.323588 25.20445 -7.593284 -0.9249219 25.49247 -7.641825 -0.4723221 25.74979 -7.675955 0.005409061 25.94898 -7.693098 0.4668622 26.07585 -7.391443 1.283843 26.97883 -6.929488 2.02708 27.69542 -6.329569 2.699893 28.24331 -5.661416 3.318526 28.66247 -4.960302 3.885271 28.97517 -7.231158 -1.405969 25.97721 -7.292141 -0.9959994 26.27699 -7.342363 -0.5282606 26.54468 -7.378415 -0.03375762 26.75191 -7.397792 0.4432088 26.88407 -7.021012 1.283851 27.7471 -6.473301 2.038815 28.41588 -5.80968 2.708873 28.91472 -5.096954 3.325218 29.28265 -4.361147 3.889907 29.53943 -3.613648 4.400451 29.6921 -3.052145 4.634617 29.85571 -6.460786 -1.127987 27.71324 -7.163765 -3.594617 21.19408 -7.349329 -3.306362 19.76644 -6.919741 -4.088486 20.53258 -7.117192 -3.786285 19.18463 -6.652082 -4.52862 19.85017 -6.860496 -4.218416 18.58493 -6.362701 -4.912664 19.15107 -5.085741 -5.815374 20.46154 -5.373163 -5.496295 21.33665 -5.710617 -5.358513 20.83028 -5.645193 -5.108673 22.19622 -5.993346 -4.971731 21.65226 -5.900024 -4.653633 23.03425 -6.25741 -4.520205 22.45388 -6.13571 -4.133743 23.84485 -6.500798 -4.006453 23.22965 -6.350207 -3.552571 24.62221 -6.721407 -3.433952 23.97414 -6.917277 -2.806384 24.68223 -7.087401 -2.128646 25.35071 -5.941359 -1.187755 28.35521 -5.989995 -0.6791599 28.65061 -5.359878 -1.242617 28.9399 -5.405843 -0.7223287 29.24316 -4.721673 -1.292005 29.46245 -4.763941 -0.7611887 29.77276 -4.032078 -1.335352 29.91798 -4.069649 -0.7952938 30.23445 -3.296423 -1.372089 30.30162 -3.328323 -0.8241981 30.62329 -2.520041 -1.401651 30.60848 -2.545322 -0.8474556 30.93433 -1.708265 -1.423468 30.83371 -1.726006 -0.8646203 31.16263 -0.8664273 -1.436975 30.97242 -0.875732 -0.8752461 31.30323 1.40708e-4 -1.603234 30.90476 1.40708e-4 -0.847021 31.36711 -5.883599 -1.628223 28.02411 -5.305575 -1.691812 28.59994 -4.671966 -1.749056 29.11454 -3.988073 -1.799299 29.56313 -3.259195 -1.841881 29.94091 -2.490635 -1.876146 30.24308 -1.687692 -1.901435 30.46485 -0.8556664 -1.917091 30.60143 1.40708e-4 -2.306323 30.2975 -1.409791 -5.360565 26.00344 -0.7457708 -4.833461 27.11098 -1.474897 -4.808127 26.99684 -0.7769488 -4.204593 28.06723 -1.535592 -4.180987 27.94668 -0.8056969 -3.504862 28.97183 -1.59138 -3.483468 28.84533 -0.8319382 -2.740233 29.81846 -1.642092 -2.7215 29.68659 -2.472391 -6.122015 23.56026 -1.986569 -5.790217 24.81137 -2.610116 -5.730561 24.58904 -2.08747 -5.317667 25.82898 -2.740931 -5.259545 25.59105 -2.182505 -4.767206 26.81138 -2.863862 -4.711761 26.55852 -2.270869 -4.142856 27.75085 -2.977859 -4.091193 27.48391 -2.351829 -3.448909 28.63988 -3.081963 -3.402084 28.35988 -2.425113 -2.69124 29.47243 -3.175791 -2.650241 29.18061 -1.340821 -5.834248 24.97433 -0.6771563 -5.861507 25.07457 -0.7124141 -5.387122 26.11079 -7.246736 -3.181448 22.57148 -7.024221 -3.735483 21.8976 -6.77658 -4.236164 21.19658 -6.5059 -4.680205 20.47304 -6.214188 -5.065196 19.73161 -5.90333 -5.389974 18.97694 -5.687876 -5.537062 19.49682 -5.364198 -5.795799 18.6914 -5.096681 -5.933474 19.14749 -5.382689 -5.718202 16.9958 -5.959534 -5.209998 16.71198 -5.025965 -5.871124 16.27322 -5.267438 -5.610714 15.43743 -4.279621 -6.062557 14.86065 -7.221786 -2.693806 23.96434 -7.024746 -3.309747 23.28833 -6.801555 -3.873169 22.57838 -6.554193 -4.380496 21.8392 -6.28479 -4.828346 21.07583 -5.99538 -5.21425 20.29333 -5.411099 -5.679415 19.99349 -4.784746 -6.064965 19.57693 -4.042173 -6.304956 20.34586 -4.304978 -6.063517 21.30057 -4.556979 -5.747763 22.24527 -4.987273 -5.62643 21.80933 -4.796581 -5.358604 23.17314 -5.244843 -5.238013 22.7043 -5.022206 -4.897148 24.07734 -5.486783 -4.779653 23.57662 -5.232129 -4.366051 24.95125 -5.711243 -4.253964 24.42002 -5.424531 -3.769049 25.78835 -5.916275 -3.6646 25.22834 -6.100069 -3.015439 25.99569 -3.164543 -6.506953 20.97836 -4.151336 -6.357949 17.80347 -4.472414 -6.245368 18.68887 -5.026675 -5.990628 17.88242 -3.770558 -6.472498 19.38788 -3.492476 -6.567699 18.43326 -2.925148 -6.620815 16.57455 -3.725231 -6.013825 12.97911 -2.704272 -6.196717 12.15236 -1.720504 -6.216273 11.03342 -0.4222189 -6.053604 8.321862 -0.4817883 -6.048425 8.321469 -4.51873 -5.853875 14.18902 -3.501178 -6.170587 13.49763 -2.462412 -6.299901 12.50201 -1.494022 -6.271971 11.22987 -0.3060724 -6.063001 8.324529 -3.212827 -6.322039 13.98599 -2.150647 -6.396384 12.81151 -1.236593 -6.321635 11.39376 -0.2681532 -6.065746 8.325829 -4.87678 -5.998369 16.68143 -3.955627 -6.264171 15.50032 -2.821227 -6.463667 14.42325 -1.787411 -6.48241 13.07334 -0.9533585 -6.363438 11.52368 -0.1787205 -6.071219 8.329106 -3.375907 -6.272371 21.99169 -3.579304 -5.959412 22.99464 -4.086312 -5.859141 22.6414 -3.773462 -5.568956 23.97969 -4.304693 -5.469301 23.59939 -3.957122 -5.102095 24.93931 -4.510812 -5.005 24.53279 -4.128893 -4.561563 25.86623 -4.703102 -4.468939 25.43462 -4.287294 -3.951234 26.75335 -4.879898 -3.864924 26.29807 -4.430959 -3.275234 27.59383 -5.039661 -3.197005 27.11659 -4.559284 -2.539172 28.38241 -2.179711 -6.662143 21.45464 -2.328629 -6.43283 22.51276 -3.039987 -6.047421 23.30195 -3.207175 -5.656425 24.31069 -3.365655 -5.187315 25.29328 -3.514235 -4.642858 26.24217 -3.651641 -4.026988 27.15002 -3.7767 -3.343893 28.00973 -3.888917 -2.599289 28.81573 -2.94684 -6.66367 19.96194 -2.724739 -6.744241 18.94951 -2.274375 -6.7623 16.9799 -1.824845 -6.696227 15.09958 -1.193246 -6.535784 22.84165 -0.601922 -6.56285 22.9271 -1.268492 -6.226345 23.9176 -0.6402516 -6.253773 24.01051 -2.026795 -6.810544 20.39359 -1.871283 -6.879876 19.33705 -1.5577 -6.871001 17.28289 -1.247106 -6.777881 15.32457 -0.9426205 -6.610446 13.4386 -6.280064 -4.931396 17.34529 -5.726004 -5.507951 17.71951 -5.23217 -5.855992 17.44679 -4.677977 -6.122702 17.07536 -3.491716 -6.452712 16.07772 -2.354041 -6.589944 14.7968 -1.381746 -6.554817 13.28365 -0.649423 -6.395555 11.61821 -0.1357594 -6.073217 8.330515 -1.880549 -6.182041 23.76649 -1.77007 -6.492064 22.70262 -1.655798 -6.719432 21.62801 -0.9552703 -6.966903 19.5807 -0.7934271 -6.940746 17.47267 -0.6342885 -6.830273 15.46472 -0.4790021 -6.64614 13.53438 -0.3298889 -6.416164 11.67596 1.40708e-4 -4.610962 27.52073 1.40708e-4 -5.49893 25.9396 1.40708e-4 -6.114188 24.47717 1.40708e-4 -6.62697 22.72366 1.40708e-4 -6.796866 21.8594 1.40708e-4 -6.924439 20.90183 1.40708e-4 -6.99959 19.19613 1.40708e-4 -6.965365 17.53834 1.40708e-4 -6.883122 15.98222 1.40708e-4 -6.590498 13.01283 -7.577854 -3.00431 10.64174 -7.020677 -3.686442 10.31798 -6.354633 -4.279132 9.981368 -5.580692 -4.786773 9.641553 -4.701701 -5.212222 9.299621 -4.018926 -5.429101 8.385804 -0.8421596 -6.017934 8.336684 -1.394777 -6.018059 8.999979 -2.341526 -5.972099 9.996677 -3.541105 -5.686469 10.01152 -3.255101 -5.877039 10.9498 -4.467728 -5.421688 10.65483 -4.13364 -5.701395 11.87315 -5.323303 -5.065617 11.27837 -4.959047 -5.437966 12.78524 -6.088993 -4.627083 11.90722 -5.715413 -5.091718 13.71666 -6.760008 -4.084558 12.53812 -6.394943 -4.616178 14.6605 -7.332189 -3.421417 13.15197 -6.988973 -3.978391 15.58686 -7.79638 -2.644702 13.73967 -6.522816 4.669171 15.83628 -6.859916 4.331375 14.96572 -7.312089 3.773101 15.13108 -7.706282 3.180049 15.2606 -8.026393 2.564934 15.35747 -8.261112 1.938352 15.42173 -8.40152 1.308775 15.44695 -8.455752 0.7596839 15.42007 -8.519804 -0.5210165 11.51381 -8.571534 0.3835135 11.77098 -8.018325 -2.240851 10.94956 -8.334389 -1.408043 11.24045 -6.514664 4.626504 17.6741 -6.745495 4.346004 18.30511 -7.180243 3.798672 18.54512 -7.574136 3.213114 18.74453 -7.901824 2.598298 18.89965 -8.141389 1.960627 19.00302 -8.272627 1.301452 19.03868 -8.313088 0.6686933 18.99273 -8.299678 0.006253898 18.79673 -8.548664 0.8278501 11.84065 -8.462569 0.2219585 15.28881 -8.241094 -0.6183007 18.46033 -7.882489 -1.610985 21.37322 -8.002861 -0.973329 21.85821 -7.735678 -1.824101 23.01424 -7.573112 -2.458567 22.43777 -7.609556 -1.928253 23.82259 -7.39165 -2.030071 24.60368 -7.44218 -2.577522 23.21389 -7.382171 -3.050194 21.83045 -7.555178 -2.781616 20.32686 -6.580921 -4.600516 17.97071 -6.053402 -5.239447 18.43945 -5.575228 -5.653541 18.21368 -1.576879 4.717229 30.44012 -2.131738 4.693244 30.26579 -2.533778 4.670026 30.10631 1.40708e-4 -3.538067 28.98393 0.5629016 -6.787845 21.83311 2.151629 -6.396208 12.81103 1.494803 -6.271871 11.22957 1.721302 -6.216138 11.03297 2.705154 -6.196428 12.15142 3.502151 -6.170156 13.49632 3.213978 -6.321689 13.98499 3.493075 -6.452354 16.0768 4.152858 -6.357492 17.80231 3.493944 -6.56738 18.43255 4.878022 -5.997701 16.67953 4.679389 -6.122101 17.0737 3.956923 -6.263698 15.499 0.712984 -5.386958 26.11107 8.00359 -0.9725056 21.85304 8.090113 -0.2339321 22.29646 7.969162 -0.354807 24.05083 2.598533 0.8242477 31.43661 2.596029 1.289352 31.46943 1.763521 1.285882 31.70354 3.391791 0.8289109 31.11837 3.388854 1.290948 31.15055 4.140162 0.8343544 30.72063 4.136826 1.291082 30.75204 4.838576 0.840574 30.24847 4.834773 1.290165 30.27901 5.48196 0.8475655 29.70699 5.477523 1.288607 29.73658 0.3303033 -6.416165 11.67601 0.9540016 -6.363399 11.5236 0.64996 -6.395541 11.61821 0.137462 -6.073159 8.330471 8.594668 0.8045309 8.424175 8.583473 0.9038793 8.423924 8.604157 0.435338 9.995726 6.598313 4.362573 21.63134 6.495483 4.491546 21.5314 6.49235 4.466533 22.08497 1.747047 4.710934 30.3922 1.485563 4.720308 30.46393 1.491508 4.638567 30.52935 0.7484787 4.406137 30.86784 0.92238 4.734045 30.57993 0.3507493 4.740573 30.64328 2.294334 4.68447 30.20483 2.218833 4.637858 30.27521 2.821244 4.651025 29.97405 2.91927 4.636897 29.93129 3.327491 4.614671 29.6997 4.813799 4.395734 28.61932 4.155938 4.557068 29.11249 4.243491 4.39838 29.18983 3.689655 4.588508 29.46661 3.615169 4.400701 29.69099 2.940169 4.402667 30.11609 5.236328 4.499663 27.95996 4.977824 4.511644 28.29136 4.585737 4.531658 28.72024 5.314757 4.392795 27.98618 5.735027 4.38959 27.2971 5.557909 4.484824 27.47311 5.829965 4.47 26.96584 6.063272 4.386151 26.55883 6.052801 4.45251 26.44039 6.58428 3.86231 26.14722 6.184071 4.436522 26.0471 6.741692 3.855601 25.33084 6.386617 4.381912 25.09933 6.310825 4.410847 25.54438 6.47721 4.356942 24.12329 6.45694 4.345491 24.54095 6.393582 4.376887 25.05788 6.909595 3.841713 23.64813 7.002872 4.279176 8.422187 6.542712 4.743755 8.421437 6.537644 4.728121 11.55199 8.549112 0.8281877 11.83078 8.477655 1.50555 8.422657 8.483975 1.314524 11.84265 8.307717 2.094848 8.422158 8.336376 1.921891 11.82856 8.075595 2.668316 8.422191 8.105819 2.54015 11.7979 7.768558 3.246826 8.422385 7.79257 3.155501 11.75132 7.412483 3.779094 8.422446 7.399845 3.754188 11.68552 6.936712 4.320676 11.59512 8.623131 0.3213635 8.425439 8.566766 -0.4297756 9.845476 8.600007 -0.2755178 8.426157 8.393689 -1.293129 9.687545 8.087644 -2.111605 9.520215 8.117819 -2.054336 8.42078 8.254867 -1.733904 8.422603 8.439759 -1.17006 8.424886 8.562187 -0.5842167 8.426039 7.10194 -3.559076 9.155964 7.309659 -3.310579 8.41012 7.654574 -2.870849 9.343098 7.680671 -2.823016 8.414855 7.995869 -2.299575 8.419118 6.419773 -4.165741 8.401114 6.921658 -3.726038 8.405707 7.132876 -3.50971 8.408029 6.437216 -4.167825 8.960025 5.660392 -4.697576 8.760736 5.867261 -4.558397 8.397223 3.512159 -5.583635 8.383089 4.296694 -5.331492 8.387343 4.702527 -5.21175 9.295696 4.784523 -5.134812 8.390239 4.773749 -5.145222 8.558548 5.033828 -5.020659 8.391781 5.263933 -4.906169 8.393238 3.740022 -5.543439 8.936449 2.716306 -5.779474 8.548922 2.673661 -5.780301 8.378305 1.536008 -5.967576 8.603706 1.942491 -5.901619 8.370286 0.9943157 -6.005021 8.344033 1.395391 -6.017951 8.999293 1.215555 -6.074248 9.320364 0.5412621 -6.043305 8.322781 0.482067 -6.048425 8.321464 0.4236875 -6.053502 8.321842 0.2972015 -6.063682 8.324827 7.211327 3.277713 24.81971 7.295297 3.268666 23.95848 7.008973 3.827427 21.94449 7.398802 3.250207 22.21743 7.732347 2.635721 22.43603 7.999118 0.08773809 24.23189 8.012431 0.5166667 24.34655 7.900716 0.491757 25.22533 7.992619 1.289533 24.42741 7.884079 1.287535 25.31178 7.885597 0.04642343 25.10427 7.694579 0.4673545 26.07201 7.682317 1.285566 26.16286 8.114923 0.1722464 22.45768 8.124094 0.5676019 22.55873 7.39314 1.284188 26.9754 7.399541 0.4436997 26.88074 7.022886 1.284199 27.74417 6.576751 1.285213 28.46404 6.572163 0.3998593 28.36186 7.677461 0.005993187 25.94522 7.853514 -0.4138885 24.9138 2.22983 4.404248 30.4584 1.495487 4.405415 30.71122 1.526141 3.902496 31.03865 2.278972 3.900453 30.78989 3.010143 3.897683 30.45263 3.708491 3.894237 30.03322 4.362855 3.890169 29.53801 4.962075 3.88553 28.97335 5.494988 3.880373 28.34559 5.950435 3.874749 27.66109 6.317252 3.86871 26.92618 1.552755 3.347471 31.31269 2.322116 3.344837 31.06893 3.072308 3.341253 30.73794 3.792425 3.336788 30.32565 4.471564 3.331511 29.83799 5.098819 3.325489 29.28089 5.663288 3.318793 28.66028 6.154064 3.31149 27.98208 6.560244 3.303651 27.25224 6.870923 3.295343 26.47666 7.076189 3.286638 25.66147 1.58361 2.740802 31.52531 2.368569 2.739583 31.28638 3.135212 2.736366 30.96146 3.873191 2.731431 30.5561 4.572155 2.725062 30.07581 5.221758 2.71754 29.52613 5.811649 2.709146 28.91259 6.33148 2.700163 28.24073 6.770901 2.690872 27.51606 7.119565 2.681555 26.74413 7.367759 2.672485 25.93053 7.53493 2.66347 25.08391 7.630306 2.654341 24.20998 7.976144 1.985716 22.58203 6.059906 1.286819 29.12989 6.050641 0.3800365 29.02411 0.8259953 2.071996 31.80941 0.7906844 2.73974 31.67272 0.7751285 3.349086 31.4633 0.7628101 3.903761 31.19256 7.023588 0.4211401 27.64571 7.0026 -0.07059097 27.50857 7.380186 -0.0331822 26.74867 7.344152 -0.5276249 26.54152 7.643354 -0.4716677 25.74612 7.594833 -0.924238 25.4889 7.807038 -0.8507969 24.66764 7.749442 -1.237774 24.39216 7.870067 -1.150691 23.55448 7.883271 -1.610075 21.36824 7.736455 -1.823277 23.00993 7.610774 -1.927475 23.81873 7.443423 -2.576695 23.2102 7.573932 -2.457687 22.43364 7.248002 -3.180586 22.56797 7.38303 -3.049271 21.82652 7.55606 -2.780577 20.32231 5.464399 0.3618516 29.62741 6.028317 -0.1388472 28.87763 6.55018 -0.1059166 28.21989 6.513083 -0.6315318 27.99785 6.965571 -0.5810636 27.29376 6.91479 -1.063256 27.01628 7.293945 -0.9953455 26.27391 7.232971 -1.405325 25.97418 7.535261 -1.322905 25.20093 7.089223 -2.127966 25.3478 7.393235 -2.02934 24.60029 6.9191 -2.805674 24.67945 7.223386 -2.693036 23.9611 6.723224 -3.433221 23.9715 7.026353 -3.308949 23.28524 4.11926 0.3311131 30.63689 4.818813 0.345484 30.16669 4.797815 -0.1962767 30.01227 5.442399 -0.1690712 29.47676 5.40785 -0.7217703 29.24184 5.992054 -0.6785828 28.64887 5.943421 -1.187193 28.35353 6.462836 -1.127395 27.71111 6.402788 -1.558386 27.38977 6.853662 -1.484041 26.70541 6.263771 -2.311119 26.71597 6.710937 -2.222158 26.05458 6.102088 -3.014849 25.99378 6.543571 -2.913249 25.35849 5.918266 -3.664005 25.22654 6.352146 -3.551908 24.62 5.024094 -4.89664 24.07611 4.798413 -5.358117 23.17199 5.488694 -4.77907 23.57503 5.246703 -5.237447 22.70282 5.901901 -4.652972 23.03229 5.647027 -5.108026 22.19439 6.259189 -4.519464 22.45153 5.995095 -4.971002 21.65007 6.555795 -4.379677 21.83645 6.286376 -4.827535 21.07326 6.777874 -4.235271 21.19345 6.5072 -4.679317 20.4701 6.920673 -4.087522 20.52908 6.653046 -4.527658 19.84689 6.861501 -4.217313 18.58111 6.581958 -4.599427 17.96715 5.234066 -4.36553 24.94992 5.713198 -4.253372 24.41832 6.137622 -4.133077 23.84276 6.5026 -4.005712 23.22715 6.803163 -3.872355 22.57545 7.025504 -3.734599 21.89428 7.164663 -3.593666 21.19036 7.11816 -3.785185 19.18056 3.371114 0.3189186 31.03295 4.099955 -0.2201521 30.47916 4.765834 -0.7606478 29.77181 5.361884 -1.242084 28.93863 5.885656 -1.627701 28.02246 5.752939 -2.394061 27.32735 5.599738 -3.109576 26.58091 5.42651 -3.768519 25.78694 0.8965009 1.280128 31.84776 0.8976367 0.8172797 31.81414 1.765457 0.8203693 31.67022 1.750554 0.3017765 31.58241 2.579754 0.3090798 31.34981 2.565964 -0.2566655 31.18698 3.354208 -0.2403856 30.8724 3.329829 -0.8236873 30.62297 4.071372 -0.7947689 30.23384 4.033797 -1.334869 29.91742 4.723563 -1.291498 29.46156 4.673847 -1.748606 29.11368 0.8888906 0.297188 31.72568 1.740612 -0.2686799 31.41788 2.54657 -0.8469565 30.93425 3.297924 -1.371628 30.30135 3.989783 -1.79888 29.5626 3.890602 -2.598891 28.81523 4.56114 -2.538735 28.3816 5.183657 -2.470195 27.88409 5.307574 -1.691327 28.5987 4.432784 -3.274808 27.59306 5.041608 -3.196529 27.11548 0.8835411 -0.2761172 31.56011 1.726958 -0.86413 31.16272 2.521284 -1.401206 30.60845 3.260689 -1.84149 29.94066 3.17726 -2.649877 29.18038 3.083403 -3.401744 28.35968 0.8763605 -0.8747615 31.30344 1.709214 -1.423037 30.83385 2.49187 -1.875777 30.24306 2.426327 -2.690904 29.47243 2.35302 -3.448601 28.6399 2.272033 -4.142579 27.75089 0.8670536 -1.436553 30.97267 0.8562894 -1.91675 30.60168 1.688635 -1.901084 30.465 0.8325527 -2.739931 29.81873 1.64302 -2.721185 29.68675 0.8063018 -3.504595 28.97211 1.59229 -3.483185 28.84551 0.7775432 -4.204361 28.06752 1.536483 -4.180738 27.94687 1.475765 -4.80791 26.99703 3.958812 -5.101726 24.9387 4.512625 -5.004564 24.53188 4.704966 -4.468485 25.43364 4.28908 -3.950824 26.75264 3.653258 -4.026629 27.1496 3.51581 -4.642523 26.24178 2.865231 -4.711475 26.55838 2.742259 -5.259286 25.59093 2.088568 -5.317451 25.82905 1.987632 -5.790031 24.81144 1.341639 -5.834095 24.97453 1.269283 -6.226221 23.91779 0.6407935 -6.25367 24.01077 1.194008 -6.535688 22.84184 3.778353 -3.343513 28.00927 2.979267 -4.090879 27.48374 2.183637 -4.766959 26.81143 1.410635 -5.36038 26.00364 0.6777124 -5.861375 25.07485 0.7463535 -4.833263 27.11127 3.775097 -5.568612 23.97913 3.20865 -5.656142 24.31038 3.041405 -6.047165 23.30167 2.473625 -6.121814 23.56017 2.329812 -6.432656 22.51269 4.558748 -5.7473 22.24421 4.989075 -5.625887 21.80797 5.374947 -5.495671 21.33495 5.712328 -5.357806 20.82824 5.996946 -5.213459 20.29094 6.215488 -5.064326 19.72888 6.363692 -4.911718 19.14802 5.365701 -5.795082 18.68938 5.233438 -5.855256 17.44468 5.576512 -5.652748 18.21137 5.38373 -5.717394 16.99344 5.727033 -5.507084 17.71691 5.960617 -5.208992 16.70894 5.027009 -5.87039 16.27108 5.098297 -5.932838 19.14577 4.474009 -6.244858 18.68758 5.028136 -5.989964 17.88058 4.280648 -6.061977 14.85893 1.906448 -6.156529 10.80725 2.063277 -6.094822 10.55863 2.901796 -6.089567 11.77418 3.726255 -6.013319 12.97753 4.519814 -5.853195 14.18698 5.268539 -5.609856 15.4349 0.2692791 -6.065687 8.325797 1.237319 -6.321567 11.39358 1.788329 -6.482292 13.07305 2.355149 -6.589764 14.79638 4.306448 -5.468887 23.59855 3.580877 -5.959094 22.99413 4.088003 -5.858753 22.64062 3.377415 -6.272082 21.99122 4.30668 -6.063084 21.2996 2.180838 -6.661996 21.45458 2.948205 -6.663442 19.96156 3.165981 -6.506693 20.97794 3.772108 -6.472137 19.38708 4.043801 -6.304557 20.34498 4.786411 -6.06441 19.57551 1.771051 -6.491935 22.70269 1.881572 -6.181884 23.76657 2.611398 -5.730331 24.58894 3.367182 -5.187005 25.29293 4.130634 -4.561172 25.86557 4.881806 -3.864456 26.29703 2.463396 -6.299667 12.5013 2.822403 -6.463404 14.42255 2.926442 -6.620568 16.57398 2.726028 -6.744046 18.94918 2.027866 -6.810424 20.39355 1.656737 -6.719329 21.62809 5.087469 -5.81478 20.45998 5.412766 -5.678739 19.99161 5.689413 -5.536302 19.49461 5.904625 -5.389136 18.97442 6.054415 -5.238533 18.43663 6.281126 -4.930339 17.34199 0.6024486 -6.562776 22.92736 1.38255 -6.554749 13.28352 1.825813 -6.696122 15.09939 2.275506 -6.762154 16.97964 0.9432736 -6.61042 13.4386 1.247879 -6.777837 15.32455 1.558594 -6.870934 17.28287 1.872297 -6.879781 19.33701 0.4794774 -6.646142 13.53445 0.634827 -6.830269 15.46481 0.79403 -6.940733 17.47279 0.9559382 -6.966875 19.58085 1.036656 -6.904735 20.66555 1.116262 -6.761646 21.75509 5.581576 -4.78614 9.636864 6.355539 -4.278336 9.975905 7.021574 -3.685519 10.31174 7.578715 -3.003324 10.63474 2.342335 -5.971862 9.995506 3.256064 -5.876627 10.94812 4.134718 -5.700785 11.87093 4.960197 -5.437148 12.78246 5.716587 -5.090688 13.71329 6.396099 -4.614981 14.65651 6.990079 -3.977108 15.58225 8.019127 -2.23987 10.94182 8.335109 -1.407132 11.23202 8.520422 -0.5202406 11.50473 8.572032 0.3840366 11.7613 6.522902 4.669389 15.83562 6.860174 4.331627 14.95771 7.312414 3.773342 15.12292 7.706645 3.180278 15.25229 8.026782 2.565159 15.34906 8.261536 1.938594 15.41325 8.402011 1.309054 15.43845 8.4563 0.7601043 15.41165 6.514777 4.62672 17.67303 6.745801 4.34625 18.29841 7.180612 3.798908 18.5383 7.574542 3.21334 18.73759 7.902259 2.598526 18.89262 8.141864 1.960878 18.99593 8.273176 1.301754 19.0316 7.487208 -3.182682 16.47266 7.877057 -2.245099 17.31255 7.350256 -3.305284 19.76212 2.564376 -5.861821 9.331013 3.542013 -5.686054 10.00918 4.46875 -5.421074 10.65184 5.324399 -5.064795 11.27472 6.090115 -4.62605 11.90288 6.761116 -4.08336 12.53307 7.333249 -3.42014 13.14622 7.797363 -2.643433 13.73324 8.144792 -1.765822 14.28777 8.15024 -1.185177 18.08855 8.368149 -0.8048675 14.80447 8.241831 -0.6173973 18.45377 8.432179 -0.2995555 15.05173 8.300345 0.006982862 18.78994 8.46318 0.2226335 15.28059 8.313692 0.6691613 18.98575 8.097789 1.293611 22.62717 7.875521 1.998149 24.37802 7.772076 2.004245 25.26054 7.581406 2.010268 26.11056 7.302854 2.017418 26.92308 6.931346 2.027356 27.69243 6.475282 2.039091 28.41337 5.943356 2.051574 29.08065 5.344262 2.06376 29.68904 4.686692 2.074602 30.23331 3.979341 2.083052 30.7082 3.230903 2.088063 31.1085 2.45007 2.088589 31.42896 1.645536 2.083582 31.66434 -5.483368 4.497922 7.419699 5.669556 4.218009 7.4196 -5.638864 4.25716 7.419675 5.327927 -3.716474 7.418782 4.804231 -4.018356 7.418755 1.80518 -4.91217 7.418681 0.904848 -5.011729 7.418677 -5.86507 4.008215 7.419651 -5.349495 4.806507 7.41973 5.365848 4.75948 7.419657 5.483384 4.498079 7.41963 -0.2345986 -5.069909 7.418678 -0.3387013 -5.061709 7.41868 4.602602 -4.118712 7.418745 3.950033 -4.393921 7.418721 -5.827806 4.043498 7.419654 3.245846 -4.620302 7.418702 2.481407 -4.799682 7.418689 -5.459465 4.54334 7.419703 5.508473 4.453387 7.419625 7.600024 0.7013321 7.419224 7.623265 0.3059017 7.419183 -0.1303638 -5.07631 7.418677 5.865083 4.008451 7.419577 6.260408 3.609392 7.419533 6.609344 3.183405 7.419486 6.547025 -2.663698 7.418883 6.22368 -3.009929 7.418849 7.573516 -0.4341238 7.419107 7.604375 -0.1822305 7.419133 5.800724 -3.380479 7.418814 0.4530324 -5.051728 7.418675 0.3400653 -5.061616 7.418675 0.2270104 -5.070469 7.418675 5.28924 5.03422 7.419686 -5.279922 5.084546 7.419758 -5.245472 5.199851 7.41977 7.323252 -1.370355 7.419012 7.111932 -1.831854 7.418966 6.853526 -2.26093 7.418923 1.34356e-4 -5.07971 7.418675 -0.02597129 -5.079561 7.418676 -0.7547823 -5.025037 7.418686 -1.699276 -4.926419 7.418702 -5.954284 3.924373 7.419643 -2.413321 -4.812766 7.418718 -5.18447 5.303585 7.41978 -5.100449 5.389738 7.419789 -4.506762 5.867181 7.419834 -3.945635 6.245032 7.41987 -3.328857 6.522921 7.419895 -2.674072 6.692899 7.419908 -2.000006 6.750103 7.419909 1.999994 6.750103 7.419884 3.328845 6.522921 7.419852 3.945622 6.245032 7.419819 4.50675 5.867181 7.419777 6.910823 2.732835 7.419438 7.16893 2.246563 7.419386 7.362645 1.768081 7.419336 2.674059 6.692899 7.419874 7.50352 1.279682 7.419284 7.590763 0.7834892 7.419232 7.473807 -0.9112703 7.419058 -7.619469 0.4302814 7.419293 -7.571772 0.9221416 7.419343 -7.433039 -1.052896 7.419138 5.184444 5.303602 7.419714 5.245442 5.19989 7.419703 5.279899 5.08461 7.419691 -7.20806 2.159801 7.419469 -6.993112 2.590129 7.419512 -6.642143 -2.547621 7.418979 5.100436 5.389738 7.419724 -3.074343 -4.665916 7.418738 -3.701805 -4.481187 7.418761 -4.294937 -4.257152 7.418787 -6.929913 -2.144363 7.419023 -7.169054 -1.71955 7.419068 -7.359126 -1.274424 7.419115 -7.394371 1.67241 7.41942 -7.526411 1.174471 7.419369 -6.696594 3.062115 7.419559 -6.349888 3.50755 7.419602 -7.547985 -0.5833309 7.419188 -7.589148 -0.3191529 7.419215 -7.623077 0.1686581 7.419266 -4.853338 -3.992537 7.418818 -5.39364 -3.673611 7.418855 -5.832594 -3.354949 7.41889 -6.228464 -3.004998 7.418929 -6.580533 -2.623432 7.418971 6.361907 4.975687 8.420617 6.306232 5.09951 8.420202 6.269944 5.229651 8.419779 6.450094 4.843021 8.421077 6.360822 4.961021 11.55526 6.373792 4.954517 8.420689 6.357233 4.906906 15.84281 6.354652 4.86831 17.68218 6.344631 4.749144 21.54511 6.342319 4.727502 22.09936 6.329599 4.63324 24.14498 6.314658 4.621864 24.53749 6.265508 4.643208 25.02296 6.185485 4.671993 25.50179 6.060681 4.694288 25.99808 5.931711 4.70805 26.3858 5.713405 4.722819 26.90308 5.447669 4.734957 27.40177 5.134303 4.746783 27.87997 4.882786 4.756233 28.2054 4.501657 4.77204 28.6267 4.083983 4.792283 29.0125 3.630446 4.817673 29.36143 3.277493 4.839168 29.59142 2.782572 4.869866 29.8619 2.26524 4.899536 30.08802 1.725939 4.924796 30.26914 1.467849 4.934388 30.33749 0.9116306 4.94949 30.44636 0.3468531 4.957443 30.5046 1.38071e-4 4.958794 30.51448 -0.442851 4.956587 30.49837 -1.003463 4.947488 30.43191 -1.558 4.931193 30.31487 -2.105185 4.907685 30.14727 -2.500602 4.886499 29.99176 -3.008555 4.855865 29.74532 -3.494013 4.825781 29.45417 -3.955807 4.799051 29.11765 -4.273708 4.782609 28.84564 -4.674427 4.764508 28.44486 -5.038369 4.750251 28.00904 -5.363885 4.738147 27.53888 -5.448335 4.734842 27.4003 -5.714686 4.722657 26.89995 -5.933569 4.707786 26.38021 -6.104275 4.687846 25.84279 -6.145515 4.680593 25.68 -6.247874 4.652122 25.148 -6.329389 4.633152 24.14506 -6.304491 4.623451 24.669 -6.525076 4.760194 8.421451 -6.435577 4.861403 8.421088 -6.298508 5.121623 8.420207 -6.350599 4.996964 8.42062 -6.360792 4.96081 11.55593 -6.361921 4.97545 8.420694 -6.357142 4.90672 15.84347 -6.354534 4.868127 17.68324 -6.344453 4.748974 21.54651 -6.342136 4.72737 22.0999 -5.340272 5.687943 7.495942 -5.4886 5.535851 7.495927 -5.918702 5.86428 8.03716 -5.643175 6.064554 7.919862 -5.746428 5.732741 7.712721 -5.543583 5.940734 7.712742 -5.413793 5.779359 7.553805 -5.67943 6.109625 8.037184 -5.596291 5.352722 7.495909 -5.8937 5.482305 7.712697 -6.092422 5.568871 8.037131 -5.657108 5.149168 7.495888 -5.97687 5.203935 7.712668 -6.190527 5.240511 8.037097 -5.085744 6.587069 8.037229 -5.049488 6.541996 7.919908 -4.949897 6.418177 7.712787 -4.820106 6.256802 7.553851 -4.746585 6.165387 7.495987 -6.491493 4.687921 8.038276 -6.344677 4.528633 7.713231 -6.472346 4.706025 8.038234 -6.12468 4.289924 7.495973 -6.321277 4.550758 7.713211 -6.094919 4.318082 7.495969 -6.37524 4.815673 8.037986 -6.295284 4.939261 8.037717 -6.282989 4.962578 8.037668 -6.226389 5.097708 8.037386 -6.202607 4.684755 7.713091 -6.104893 4.835787 7.712963 -6.089867 4.864282 7.71294 -6.020698 5.02942 7.712805 -5.944002 4.488613 7.49595 -5.819768 4.680799 7.495931 -5.800667 4.717057 7.495927 -5.712764 4.927161 7.495907 -2.829756 7.603502 8.03732 -2.000006 7.25009 7.553936 -2.000006 7.132779 7.496069 -2.738559 7.070101 7.496068 -4.131774 6.579387 7.496026 -3.455989 6.883862 7.496053 -2.000003 7.616077 7.919999 -2.000005 7.45718 7.712876 -2.793229 7.389863 7.712874 -3.563765 7.189837 7.712858 -4.289574 6.862824 7.712829 -3.635778 7.394265 8.037303 -4.395012 7.052192 8.037273 -2.000002 7.673919 8.037322 -0.1738725 -5.971411 7.974734 -0.2988229 -5.962223 7.971649 -6.219402 4.200976 7.495985 -6.444055 4.435347 7.713301 -7.289739 -3.211878 8.030551 -7.363344 -3.121731 8.031195 -7.708757 -2.639874 8.034364 -7.997897 -2.128478 8.037138 -8.228539 -1.590527 8.039306 -8.318348 -1.322341 8.040099 -8.458002 -0.7535957 8.041163 -8.50788 -0.4340351 8.041398 -8.548737 0.1549266 8.041169 -8.544218 0.4686107 8.040675 -8.486782 1.058291 8.039631 -8.431747 1.363625 8.03919 -8.274282 1.956609 8.038738 -8.053482 2.53425 8.038728 -7.800597 3.040647 8.038857 -7.453574 3.593153 8.038956 -7.050745 4.110624 8.038855 -6.593955 4.591715 8.038422 -5.281326 -4.803051 8.018749 -5.898491 -4.440084 8.021621 -6.40678 -4.072332 8.024159 -6.871622 -3.663035 8.027184 -6.640423 3.757568 7.496009 -7.010415 3.282285 7.495983 -7.327864 2.776914 7.495926 -7.558528 2.315046 7.49587 -7.759147 1.790246 7.495826 -7.901807 1.252922 7.495842 -7.951256 0.9786257 7.49588 -8.003172 0.4462039 7.495978 -8.007244 0.162978 7.496021 -7.970486 -0.3668182 7.496006 -7.925673 -0.6539777 7.495949 -7.800316 -1.164658 7.495756 -7.719692 -1.4055 7.495625 -7.512489 -1.888972 7.495282 -7.252259 -2.349425 7.494858 -6.940239 -2.784901 7.494381 -6.873594 -2.866573 7.494285 -6.493862 -3.276516 7.493783 -6.069234 -3.650587 7.493332 -5.601488 -3.989149 7.492951 -5.029333 -4.325813 7.492525 -4.441627 -4.603335 7.492123 -3.820816 -4.836892 7.491732 -3.167364 -5.028439 7.491377 -2.482897 -5.17945 7.490938 -1.747489 -5.29435 7.490059 -0.7866673 -5.38731 7.48712 -6.886576 3.969377 7.7135 -7.276283 3.468797 7.713529 -7.611469 2.935145 7.713453 -7.855455 2.446559 7.713365 -8.068189 1.890062 7.713343 -8.219796 1.31936 7.713546 -8.272658 1.026449 7.713758 -8.328028 0.4596686 7.714264 -8.332436 0.158154 7.714501 -8.293254 -0.4071785 7.714591 -8.245374 -0.7137939 7.714456 -8.111306 -1.259308 7.713886 -8.025075 -1.516532 7.713469 -7.803562 -2.032579 7.712337 -7.525702 -2.523392 7.710896 -7.193368 -2.986403 7.709258 -7.122497 -3.073094 7.708925 -6.719512 -3.507387 7.707188 -6.270629 -3.902206 7.705628 -5.77852 -4.257923 7.704319 -5.179372 -4.609952 7.702841 -4.566792 -4.898736 7.701435 -3.922449 -5.140674 7.700063 -3.246864 -5.338283 7.698809 -2.542417 -5.493159 7.697236 -1.788816 -5.609758 7.694015 -0.814185 -5.699987 7.683124 -4.652063 -5.100005 8.016012 -3.991864 -5.348176 8.013334 -3.301286 -5.550412 8.010885 -2.58328 -5.708556 8.007799 -1.817357 -5.827609 8.001449 -0.8335673 -5.920249 7.979856 -0.4136912 -5.952279 7.969852 -0.3950953 -5.731409 7.678099 -0.3689277 -5.420645 7.485767 -0.2829194 -5.741234 7.678998 -0.2605047 -5.429811 7.486008 -0.1631253 -5.750275 7.680546 -0.1479361 -5.437787 7.486421 -0.0361669 -5.976817 7.977074 -0.03365391 -5.755561 7.68172 -0.03009378 -5.442252 7.486735 1.38395e-4 -5.977088 7.977201 1.36397e-4 -5.755825 7.681784 1.34987e-4 -5.44247 7.486752 1.999994 7.132779 7.496044 1.999995 7.25009 7.55391 1.999995 7.45718 7.71285 1.999997 7.616077 7.919973 1.999998 7.673919 8.037297 8.184925 -1.706579 8.038808 7.983201 -1.627848 7.71316 8.158845 -1.094757 7.714003 7.680548 -1.509754 7.495464 7.844772 -1.010625 7.495728 0.2524525 -5.430474 7.486032 0.2744661 -5.741969 7.679097 0.2900841 -5.962967 7.971848 0.4151456 -5.952174 7.969837 4.267259 -5.251858 8.014378 3.489237 -5.500695 8.011453 2.656863 -5.694601 8.008172 1.930196 -5.813007 8.002688 0.9856843 -5.909184 7.984828 0.5322705 -5.942244 7.97047 0.370326 -5.420547 7.485762 0.4849771 -5.410733 7.485846 0.9376277 -5.375648 7.487782 1.856248 -5.280148 7.490209 2.553243 -5.166072 7.490963 3.345632 -4.981234 7.491423 4.080247 -4.746071 7.49184 4.765002 -4.458359 7.49228 4.977502 -4.352965 7.492425 5.531688 -4.034526 7.492828 6.035138 -3.677803 7.493226 6.488698 -3.281801 7.493695 0.3965252 -5.731305 7.678089 0.5126287 -5.721495 7.678406 0.9658752 -5.689256 7.685619 1.900008 -5.595472 7.694631 2.614691 -5.479487 7.69741 3.430898 -5.289659 7.699079 4.191411 -5.046712 7.700572 4.903507 -4.748045 7.702135 5.125232 -4.638263 7.70265 5.705262 -4.305472 7.704062 6.23465 -3.930874 7.705447 6.714029 -3.512977 7.707084 4.997737 -4.945146 8.017434 5.225643 -4.832194 8.018438 5.82293 -4.489168 8.021189 6.369557 -4.102014 8.02388 6.865932 -3.668835 8.02706 7.249714 -3.259703 8.030119 7.083958 -3.119095 7.70866 6.837349 -2.909928 7.494147 7.616758 -2.779554 8.033408 7.437235 -2.657549 7.710357 7.169296 -2.475481 7.494637 7.45024 -2.010833 7.495085 7.737031 -2.162574 7.711894 7.928633 -2.263968 8.036375 7.953458 -0.4917722 7.495886 7.987012 -0.2180505 7.495922 8.007349 0.3118731 7.495902 7.981797 0.7409749 7.49582 7.971732 0.8297231 7.495804 7.87706 1.366326 7.495733 7.724917 1.893372 7.495734 7.516475 2.408263 7.495786 7.239637 2.929908 7.495854 6.917229 3.411797 7.495906 6.54498 3.866141 7.495926 6.124679 4.290176 7.495895 8.275053 -0.5405832 7.714447 8.310882 -0.2483847 7.714508 8.332498 0.3169125 7.71429 8.305088 0.774529 7.713871 8.294363 0.868861 7.713788 8.193493 1.439707 7.713377 8.031845 1.999506 7.713237 7.810925 2.545243 7.713285 7.518211 3.096853 7.713391 7.178072 3.605277 7.713447 6.786088 4.083659 7.713388 6.344666 4.528898 7.713153 8.367859 -1.150766 8.04041 8.488909 -0.5730606 8.041228 8.526238 -0.2685741 8.041318 8.548824 0.3202465 8.040838 8.520371 0.7968543 8.039975 8.509244 0.8949094 8.039804 8.404441 1.488607 8.038943 8.236535 2.070269 8.038616 8.007299 2.636579 8.038656 7.703979 3.208161 8.038808 7.352015 3.734279 8.038867 6.946907 4.228723 8.038704 6.491477 4.688193 8.038199 4.395007 7.052192 8.037217 4.820096 6.256802 7.55379 4.746574 6.165387 7.495927 4.131762 6.579387 7.495974 2.738548 7.070101 7.496033 3.455977 6.883862 7.496009 5.049481 6.541996 7.919843 4.949888 6.418177 7.712724 4.289566 6.862824 7.712774 3.563756 7.189837 7.712813 2.79322 7.389863 7.712838 3.635773 7.394265 8.037258 2.829752 7.603502 8.037284 5.085739 6.587069 8.037165 6.190491 5.240694 8.037018 5.976834 5.20409 7.712593 6.195312 5.214811 8.037071 5.657077 5.149281 7.495816 5.982728 5.172459 7.712617 5.664556 5.109044 7.49582 6.234786 5.073709 8.037359 6.295269 4.939492 8.03764 6.308174 4.916549 8.03769 6.390995 4.795731 8.037954 6.030969 5.000022 7.712753 6.104884 4.836001 7.712887 6.120655 4.807962 7.712911 6.221869 4.660315 7.713036 5.725828 4.889676 7.495838 5.81977 4.680987 7.495857 5.839818 4.645311 7.49586 5.968509 4.457427 7.495878 5.679425 6.109625 8.037112 5.643168 6.064554 7.91979 5.543574 5.940734 7.712671 5.413782 5.779359 7.553737 5.34026 5.687943 7.495873 5.488565 5.535881 7.495857 5.746387 5.732782 7.712648 5.596249 5.352793 7.495837 5.89365 5.482401 7.712622 6.092367 5.568985 8.037054 5.918659 5.864329 8.037085 + + + + + + + + + + -0.9581485 0.2862712 6.36985e-4 -0.9547525 0.2973951 0.002030849 -0.9918311 0.1275457 0.00176841 -0.9931496 0.1168075 0.003166556 -0.9940932 0.1084314 0.004625022 -0.7159135 0.6981891 7.66479e-5 -0.7427363 0.6695834 9.725e-4 -0.861997 0.5069132 -5.49534e-4 -0.9155389 0.4022275 0.001261055 -0.9701926 0.2423318 -0.00127691 -0.9882246 0.1530085 8.52253e-4 0.9581182 0.2863725 6.25541e-4 0.9547218 0.2974934 0.002019703 0.9940906 0.108456 0.004612207 0.9931449 0.1168477 0.003152489 0.9918261 0.1275851 0.001754701 0.9882166 0.15306 8.38908e-4 0.9701691 0.2424259 -0.001289188 0.8619612 0.5069654 0.00300014 0.9155386 0.4022275 -0.001442015 0.7158963 0.6982056 0.001256823 0.7427375 0.6695827 6.43792e-5 -6.40803e-7 1 1.03248e-4 6.42928e-7 1 1.03313e-4 -7.11465e-7 1 1.03235e-4 0 1 1.03484e-4 0 1 1.03206e-4 0 1 1.03089e-4 7.12547e-7 1 1.03426e-4 -0.1301106 0.9914978 -0.001870334 -0.196263 0.9805504 0.00131452 -0.1060263 0.9943631 -7.44698e-4 -0.08456075 0.9964173 -0.001461386 -0.07052481 0.9975097 -8.7574e-4 -0.02352756 0.9997233 1.03433e-4 -0.4095047 0.912308 5.00232e-5 -0.3531045 0.9355829 -0.001383066 -0.3057161 0.9521138 -0.004149258 -0.3848909 0.9229607 0.001629114 -0.2573296 0.9663233 -9.88411e-4 -0.2784762 0.9604431 9.78871e-5 -0.2209175 0.9752925 1.02214e-4 -0.1800686 0.9836541 -9.11926e-6 -0.6134033 0.7897699 8.54824e-5 -0.5799538 0.8146494 -4.5021e-4 -0.5524321 0.8335565 -0.001568377 -0.5207763 0.8536876 -0.003107905 -0.4625048 0.8866168 1.47598e-4 -0.4615575 0.8871104 1.74942e-4 -0.5585491 0.8294715 -1.19846e-4 -0.6266862 0.7792719 8.22833e-5 -0.6266979 0.7792623 9.11994e-5 -0.6266878 0.7792705 8.44645e-5 -0.6266887 0.7792698 8.44165e-5 -0.6266831 0.7792743 8.44141e-5 -0.6267051 0.7792566 8.45008e-5 -0.6253501 0.7803443 1.03329e-4 -0.6269178 0.7790855 8.18198e-5 -0.6266759 0.7792802 8.43217e-5 -0.6267483 0.7792218 7.20926e-5 -0.6266908 0.7792682 8.44642e-5 -0.6266891 0.7792695 8.44599e-5 0.6266883 0.7792701 7.71095e-5 0.626688 0.7792703 7.63281e-5 0.6266888 0.7792696 7.65565e-5 0.6267626 0.7792103 8.06658e-5 0.626684 0.7792735 7.61899e-5 0.6266889 0.7792696 7.65158e-5 0.6266931 0.7792661 7.46071e-5 0.6266884 0.7792701 7.7416e-5 0.4021253 0.9155846 3.13889e-5 0.6134074 0.7897667 7.75954e-5 0.579954 0.8146491 -4.57534e-4 0.4615576 0.8871102 1.39946e-4 0.462485 0.8866271 1.6637e-4 0.5585487 0.8294717 -1.26955e-4 0.520776 0.8536878 -0.003114521 0.5524322 0.8335564 -0.00157535 0.130093 0.9915001 -0.001872718 0.1060505 0.9943562 -0.003021061 0.1962624 0.9805487 0.002287745 0.07051688 0.9975087 -0.001930356 0.08456075 0.9964177 -0.001169323 0.02352756 0.9997233 1.03106e-4 0.1758919 0.9844096 -1.67645e-4 0.2168219 0.9762112 1.00128e-4 0.2784766 0.9604431 9.15219e-5 0.2534802 0.9673399 -0.001190125 0.3848898 0.9229604 0.002000987 0.2947146 0.9555727 -0.00491482 0.3386132 0.9409235 -0.002052545 -0.1649124 0.4941949 0.8535662 -0.5639439 0.7715088 0.2945191 -0.8166308 0.3756837 0.4381508 -0.7286921 0.5445628 0.4152823 -0.692313 0.6319442 0.3483521 -0.6226759 0.7203489 0.3055688 -0.8260061 0.225206 0.5167166 -0.8181976 0.2985719 0.4913327 -0.8149223 0.3238656 0.4806379 -0.7560229 0.06304264 0.6515021 -0.7637785 0.1184595 0.6345156 -0.7230561 0.08648687 0.6853538 -0.7213796 0.0840674 0.6874185 -0.7095736 0.09278565 0.6984957 -0.6291406 0.0948199 0.7714865 -0.6470808 0.1056585 0.7550648 -0.6880291 0.1217567 0.715396 -0.6753056 0.0942946 0.7314854 -0.7012158 0.09440261 0.7066714 -0.4511283 0.3053281 0.8386048 -0.4999461 0.2212694 0.8373134 -0.5222451 0.03084045 0.8522376 -0.552598 0.5041895 0.6636479 -0.5911849 0.1344594 0.7952492 -0.647462 0.1327905 0.7504397 -0.3940181 0.3467666 0.8511773 -0.365269 0.2980855 0.8818864 -0.304273 0.3863614 0.870714 -0.1116641 0.6410084 0.7593679 -0.07161456 0.4080247 0.9101578 -0.02443438 0.6084452 0.7932198 0.06220573 0.5105736 0.857581 0.06972831 0.4585661 0.8859205 0.1154535 0.5570735 0.8223988 0.2343143 0.3833211 0.8933991 0.2170321 0.36833 0.9040079 0.4511095 0.3053335 0.838613 0.4089592 0.3362373 0.8483495 0.3657204 0.2944305 0.8829266 0.3350345 0.357415 0.8717835 0.2776266 0.3838024 0.8806926 0.6303654 0.1317613 0.765035 0.4999564 0.221269 0.8373073 0.5222499 0.03087651 0.8522334 0.5525842 0.5042335 0.663626 0.5913583 0.1444438 0.7933672 0.6087419 0.1158379 0.7848663 0.7863609 0.1262637 0.6047265 0.7793073 0.1297166 0.6130692 0.767866 0.1186475 0.6295273 0.7401767 0.08803439 0.6666247 0.7584114 0.05021327 0.6498391 0.7228382 0.08730578 0.6854799 0.7071757 0.09444844 0.7007012 0.7094511 0.0928297 0.6986142 0.6750246 0.09928059 0.731085 0.677208 0.09230041 0.7299795 0.6481577 0.1196957 0.7520403 0.8024606 0.433848 0.4096741 0.8093999 0.3647698 0.4602335 0.8149151 0.3238941 0.4806308 0.818209 0.298564 0.4913182 0.822656 0.26282 0.5041457 0.8402882 0.2420196 0.485121 0.7790353 0.3049447 0.5478255 0.6951472 0.6877139 0.209332 0.6906532 0.6494957 0.3180466 0.7075338 0.5888496 0.3907074 0.9847037 0.1093459 0.1356549 0.9885307 0.1294341 0.07780653 0.9837604 0.1546579 0.09108424 0.9935059 0.1083865 0.0346179 0.9125005 0.1564427 0.3779796 0.9095371 0.1654375 0.3812779 0.942997 0.1145936 0.3124503 0.9621496 0.1445948 0.2309992 0.9579549 0.1604578 0.2378565 0.9785397 0.1093432 0.1746546 0.7705342 0.2501666 0.586254 0.7906424 0.1332162 0.5976103 0.8443996 0.1386584 0.5174584 0.819755 0.2087064 0.5333324 0.8773068 0.1157594 0.4657604 0.2520887 0.2167335 0.9431214 0.3159296 0.1514077 0.9366239 0.3713144 0.2418839 0.8964474 0.3986253 0.1793706 0.8994021 0.5176282 0.1362212 0.8446923 0.4697859 0.2813299 0.8367524 0.5435865 0.1625838 0.8234564 0.185072 0.3505207 0.918087 0.2304791 0.159084 0.9599853 0.09961134 0.2092532 0.9727748 0.07511788 0.2889658 0.9543879 0.02748787 0.1954876 0.9803209 -0.2248924 0.268081 0.9367796 -0.2026613 0.195652 0.9595045 -0.07716012 0.1808658 0.9804764 -0.1120966 0.3876394 0.91497 -0.03508484 0.1954446 0.980087 -0.5875501 0.1298303 0.7987046 -0.5101323 0.2025963 0.8358947 -0.5121937 0.1974708 0.8358606 -0.4357051 0.1443274 0.8884428 -0.3715693 0.2390846 0.8970924 -0.3629394 0.2124711 0.9072657 -0.2899978 0.1545797 0.9444609 -0.877524 0.1155048 0.4654141 -0.8385572 0.1809141 0.5138989 -0.8014854 0.3411145 0.4911845 -0.76885 0.2636054 0.5825651 -0.7712293 0.1078039 0.6273626 -0.7801289 0.1340357 0.611092 -0.7954574 0.1426326 0.5889853 -0.7894292 0.134534 0.5989176 -0.8220867 0.1344862 0.5532512 -0.8399695 0.1891436 0.5086022 -0.9112608 0.155292 0.3814292 -0.9116605 0.1620424 0.3776473 -0.9385948 0.122342 0.3226024 -0.9766156 0.1062017 0.1869313 -0.959385 0.1628471 0.2303501 -0.9587713 0.1518227 0.2402237 -0.9523664 0.1223133 0.2793524 -0.9876624 0.1119076 0.1095433 -0.986237 0.1459748 0.07763999 -0.9931694 0.1083312 0.0433464 0.6584087 0.6695389 0.3438253 0.6871477 0.6684154 0.2846909 0.6871505 0.6684131 0.2846899 0.7232139 0.6684254 0.173693 0.7232148 0.6684245 0.1736924 0.7414716 0.6684364 0.05841875 0.7414715 0.6684363 0.05842 -0.6926136 0.6678418 0.2725321 -0.6871465 0.6684135 0.2846985 -0.6871426 0.668417 0.2846994 -0.7232131 0.6684239 0.1737015 -0.7232108 0.6684265 0.1737017 -0.7414709 0.6684363 0.05842894 -0.7414674 0.6684401 0.058429 0.7964558 0.4018444 0.4518623 0.8462706 0.4011532 0.3505743 0.846273 0.4011512 0.3505707 0.8906874 0.4011678 0.2138704 0.8906888 0.401165 0.2138696 0.9131724 0.4011809 0.07190382 0.9131729 0.4011797 0.07190406 -0.2141675 0.379974 0.8998622 -0.2157167 0.382102 0.8985903 -0.1826165 0.4018102 0.8973293 -0.07186484 0.401091 0.9132149 -0.07186061 0.4010974 0.9132125 0.07187688 0.401095 0.9132123 0.07187318 0.4010926 0.9132137 0.185259 0.4017669 0.8968069 0.1665499 0.5709713 0.8038986 -0.8027286 0.4020234 0.4404588 -0.8462679 0.4011502 0.3505842 -0.8462675 0.4011527 0.3505823 -0.8906845 0.4011676 0.2138829 -0.890687 0.4011626 0.2138815 -0.9131724 0.4011789 0.07191491 -0.9131717 0.4011805 0.07191538 -0.07037323 -0.7057135 0.7049938 -0.1729664 0.9794308 0.1039131 -0.2466409 -0.2401905 0.93887 -0.4001775 0.2787541 0.8730144 -0.3737533 -1.19012e-4 0.9275283 -0.6266821 0.7792742 0.001148223 -0.5760532 0.7800756 0.2442228 -0.542766 0.8092106 0.2249073 -0.5560913 0.7787249 0.2904308 -0.5582022 0.7561119 0.3416215 -0.6269615 0.7789884 0.009815454 -0.6353188 0.7710447 0.04313033 -0.6416251 0.7653489 0.05058008 -0.6203572 0.7798747 0.08338117 -0.549459 0.7781233 0.3043337 -0.5575651 0.7808541 0.2817592 -0.6197984 0.7357554 0.2729724 -0.6001645 0.7595974 0.2506285 -0.573619 0.8074482 0.1377997 -0.6449453 0.7404853 0.1890165 -0.6158065 0.777911 0.1250483 0.558076 0.7795901 0.2842368 0.5671194 0.7724961 0.2857019 0.5481854 0.7825629 0.2951069 0.6020581 0.7632766 0.2343823 0.6348536 0.7206203 0.2786886 0.6355728 0.7197497 0.2792985 0.5427613 0.8092169 0.224896 0.5561149 0.7787144 0.2904139 0.6259269 0.7783197 0.0493381 0.6431618 0.7646334 0.0409711 0.6182249 0.7803827 0.0938127 0.617888 0.7721315 0.148417 0.6527972 0.7448058 0.1382761 0.5848288 0.7884899 0.1904182 -0.1791302 -0.1818155 0.9668793 -0.1662696 0.3178054 0.9334635 -0.2794687 0.05999022 0.9582789 -0.3316509 0.1786932 0.9263242 -0.3314352 0.1517662 0.9311917 -0.3574751 0.1637439 0.9194561 -0.3887011 0.2109037 0.8969008 -0.4649895 0.05610233 0.8835368 -0.4363732 0.3729165 0.8188478 -0.6571763 -0.2618678 0.7067848 0.6440243 -0.08735018 0.7600018 0.4045331 0.4389415 0.8022989 0.5022365 0.03076225 0.864183 0.3726922 0.2560609 0.8919268 0.369747 0.169422 0.9135554 0.3456619 0.1583687 0.9248985 0.3268496 0.1664133 0.9303096 0.3035008 0.02655225 0.9524613 0.1624748 0.3284466 0.9304434 0.1979033 -0.264387 0.9438928 -0.3247993 0.9457823 0.001116693 -0.3348726 0.9422618 0.001790821 -0.3452927 0.9384908 0.002848029 -0.3507998 0.9364438 0.003532469 -0.3541138 0.9351938 0.004007518 -0.3556239 0.9346196 0.004250466 -0.3543825 0.9350919 0.004033088 -0.3453261 0.9384803 0.002176165 -0.3362086 0.9417876 9.98044e-5 -0.1435463 0.9222851 -0.3588658 -0.3511366 0.9338268 -0.06834244 -0.3791829 0.9250785 -0.02121829 -0.3844234 0.9230924 -0.01090925 -0.3862175 0.9223715 -0.008197486 -0.3870096 0.9220601 -0.005385458 -0.387934 0.9216834 -0.002655386 -0.3878968 0.9217011 -0.001795291 -0.3877906 0.9217476 9.74001e-5 -0.3869028 0.9221206 2.96878e-4 -0.3708997 0.928673 -1.97308e-4 -0.3466235 0.9379944 -0.00431329 -0.3128248 0.9497007 -0.0144692 -0.2791541 0.9598286 -0.02832597 -0.2277196 0.9737266 5.84178e-4 -0.203635 0.979045 0.001956105 -0.2514778 0.9678632 2.90778e-5 -0.2725371 0.9621453 2.14573e-4 -0.2733904 0.9619032 2.47251e-4 -0.2932267 0.956043 1.94272e-5 -0.3131492 0.9497039 4.64798e-4 -0.05335229 0.9985757 -5.62194e-4 -0.03991943 0.9992029 1.96364e-4 -0.01427173 0.9998982 9.36869e-5 -0.2380592 0.9712501 -0.00111556 -0.197572 0.9802884 4.36211e-4 -0.1727671 0.9849627 -1.35365e-4 -0.1639163 0.9864743 1.00932e-4 -0.1469066 0.9891504 1.04415e-4 -0.1401529 0.9901298 2.18009e-4 -0.1143621 0.9934391 -2.25307e-4 -0.1023266 0.9947509 3.48824e-4 -0.0713154 0.9974538 -4.67481e-5 0.1143621 0.9934392 -1.67093e-4 0.1233685 0.992361 2.97041e-4 0.1469065 0.9891505 7.44707e-5 -0.005105614 0.9999871 1.46964e-4 -0.00750637 0.9999719 1.03494e-4 0.02996134 0.9995511 1.02829e-4 0.01719915 0.9998518 -8.21632e-4 0.07410508 0.9972501 9.34546e-4 0.05903887 0.9982557 -5.16074e-5 0.091201 0.9958325 1.32421e-4 0.2514775 0.9678632 2.58269e-5 0.1717833 0.9851348 2.52471e-4 0.2073732 0.9782605 -0.001706242 0.1727672 0.9849618 0.001378059 0.2380588 0.9712501 -0.001118779 0.2036343 0.9790451 0.001953542 0.2277199 0.9737266 5.8134e-4 0.3934067 0.9193128 -0.009756445 0.3865075 0.9222863 9.15366e-5 0.3468196 0.9379227 -0.004154086 0.3132883 0.949555 -0.01399832 0.3882607 0.9215451 0.002921938 0.3938089 0.9191894 -0.002328693 0.3901388 0.9207549 0.001513242 0.3709192 0.9286651 -1.92239e-4 0.3877172 0.9217783 3.1001e-4 0.3833057 0.9235051 0.01466888 0.3851938 0.9228011 0.007994115 0.3960036 0.918244 -0.003026187 0.3913059 0.9202605 7.25441e-4 0.3939148 0.919147 -1.7926e-4 0.3936567 0.9192572 7.69578e-4 0.3962468 0.9181441 -2.17539e-4 0.3963975 0.9180782 -0.001301109 0.279807 0.9596624 -0.02749764 0.3362087 0.9417876 9.5214e-5 0.3453232 0.9384814 0.002172708 0.3543837 0.9350914 0.004027962 0.355623 0.9346199 0.004246771 0.3541029 0.9351979 0.004000544 0.35079 0.9364476 0.003528237 0.345293 0.9384906 0.002843737 0.3348656 0.9422643 0.001785635 0.3248 0.9457821 0.001112401 0.3131487 0.9497041 4.60851e-4 0.2729609 0.9620252 -4.34548e-4 0.2924041 0.9562944 9.71505e-4 0.2725366 0.9621455 2.1096e-4 -0.1075715 -0.8748527 -0.4722934 0.05528634 -0.98562 0.1596769 -0.03808671 -0.9905093 0.1320639 -0.01288419 -0.9939716 -0.1088784 0.01517814 -0.9922763 0.1231155 0.04876083 -0.9887746 -0.1412344 0.05927854 -0.9949292 0.08125287 0.3886069 -1.25165e-4 0.9214037 0.09051454 -0.6584693 0.7471448 0.1763416 0.8784426 0.4441196 0.1078093 0.9935607 0.03484743 0.1175962 -0.4745275 0.8723502 0.1007581 0.9925286 0.0688104 0.01739484 -0.8460747 0.5327805 0.2924619 -0.3036233 0.906796 0.3269703 0.7211931 0.6107135 0.122979 -0.6378045 0.7603169 0.2517712 0.7820116 0.5701485 0.1377563 -0.492291 0.8594607 0.9126617 0.004558742 0.4086905 0.9216912 0.03138709 0.3866527 0.9240882 0.04275071 0.3797808 0.9241724 0.04342436 0.3794993 0.9236971 0.03822511 0.381212 0.9233021 0.03308647 0.382647 0.9232517 0.03217172 0.3828464 0.8455549 -0.003480672 0.5338772 0.8615645 0.003169059 0.5076385 0.8760664 0.01399016 0.4819876 0.8767171 0.01237785 0.4808472 0.8948908 -0.001843929 0.4462814 0.594871 -0.02359503 0.8034749 0.5887193 0.09707033 0.8024881 0.4844228 -0.1079999 0.8681421 0.4938508 0.2002218 0.8461812 0.4377458 -1.12632e-4 0.8990989 0.8300151 0.01092571 0.5576339 0.836231 -3.47922e-5 0.5483775 0.8151884 -6.79898e-5 0.5791959 0.8022458 0.009899914 0.5969119 0.7614986 -0.0357058 0.6471825 0.7440967 0.04142165 0.6667866 0.6715516 -0.0478906 0.7394086 0.6675602 -0.005162537 0.744538 0.6324401 0.001030683 0.7746086 -0.464857 -1.14416e-4 0.8853858 -0.4731495 0.02991896 0.880474 -0.5371248 -0.01200467 0.8434174 -0.5887183 0.09708714 0.8024867 -0.5949249 -0.02884125 0.8032638 -0.6322891 -8.53581e-5 0.7747326 -0.6515611 -5.01462e-5 0.7585963 -0.671594 0.02027976 0.7406419 -0.6960949 -0.04757302 0.716372 -0.7435744 0.03700089 0.6676287 -0.7759565 -0.02014714 0.6304647 -0.8022378 0.009896755 0.5969227 -0.8367323 0.004792809 0.5475912 -0.8280693 -5.50533e-5 0.5606258 -0.8151928 -7.25208e-5 0.5791897 -0.9000506 -0.006130278 0.4357423 -0.8837026 0.007044196 0.4679957 -0.8762616 0.01674139 0.4815449 -0.8696608 0.006671786 0.4936048 -0.8455449 -0.003478527 0.533893 -0.923242 0.03217786 0.3828693 -0.9232986 0.03306657 0.3826569 -0.9237079 0.03823518 0.3811849 -0.9241483 0.04348063 0.3795517 -0.9243302 0.0451585 0.3789122 -0.9224274 0.03263229 0.3847895 -0.9153203 0.01346194 0.4025017 -0.6221458 0.7828896 0.004295706 -0.4882252 0.8717052 0.04202812 -0.5228755 0.8522992 0.01369291 -0.5605982 0.828087 0.001332283 -0.5943852 0.8041803 -5.54583e-4 -0.6467616 0.7625344 0.01552021 -0.6693078 0.7419013 0.04011899 -0.6661021 0.7428252 0.06722158 -0.9981275 0.04020655 0.04609817 -0.9930693 0.1175174 0.00175184 -0.9383723 0.3456243 -0.001184225 -0.8816007 0.4718033 0.01348763 -0.8376057 0.5462719 0.001948297 -0.587773 0.8090178 -0.003614723 -0.6813864 0.7316352 0.02055883 -0.4933855 0.8698108 9.25844e-5 -0.4904136 0.8709415 0.03091329 0.4929611 0.869002 0.04272001 0.5746636 0.8096551 0.1192494 0.5364826 0.843902 0.004003584 0.5944488 0.8041332 -7.19082e-4 0.6698738 0.7414169 0.03962504 0.647326 0.7620729 0.01463359 0.6223769 0.7827096 0.003592014 0.4898842 0.869542 0.06253397 0.4951477 0.8688088 8.69544e-5 0.6724052 0.7399232 0.0196188 0.5877768 0.8090233 2.79942e-4 0.9971053 0.04015994 0.06456291 0.9982732 0.05342829 0.02441465 0.9786275 0.2055808 -0.004974842 0.8816391 0.4718265 0.009612381 0.892569 0.4506532 0.01524335 0.8165119 0.5773286 -3.98989e-5 -0.9208043 0.13927 0.3643122 -0.809145 0.5330997 0.2471624 -0.8900017 0.3287518 0.3159419 -0.7056438 0.6863977 0.1758548 -0.5502569 0.8306984 0.0846033 -0.9124401 0.1916331 0.361566 -0.8733282 0.2075127 0.4407225 -0.8764009 0.1940254 0.4407673 -0.8395051 0.2088097 0.5016272 -0.819678 0.2600776 0.51038 -0.8086825 0.2031979 0.5520358 -0.7517524 0.2230991 0.6205604 -0.6872704 0.2388759 0.6860013 -0.6839859 0.2270182 0.6932719 -0.7553582 0.2031154 0.6230395 -0.6535599 0.2217269 0.7236689 -0.5991653 0.2373529 0.7646336 -0.6026011 0.2170524 0.7679584 -0.4968544 0.2450529 0.8325171 -0.5001549 0.2257182 0.8360003 -0.7924502 0.5596035 0.2426247 -0.7649763 0.5707386 0.2984442 -0.7661774 0.5689491 0.2987798 -0.7270061 0.5838684 0.3613306 -0.7286095 0.5813232 0.3622038 -0.675019 0.6005664 0.4285668 -0.6768 0.5976286 0.4298627 -0.6198853 0.6166306 0.4852926 -0.6215008 0.6140946 0.4864408 -0.5556761 0.6335185 0.5384037 -0.5576019 0.6300371 0.5404936 -0.4722577 0.6525396 0.5925915 -0.4741847 0.6488386 0.5951113 -0.5426709 0.8358357 0.08298957 -0.5307995 0.8406901 0.107201 -0.5231539 0.8457471 0.104986 -0.506688 0.8520517 0.1314357 -0.4970169 0.8584505 0.1266379 -0.4725769 0.867206 0.1569236 -0.4629896 0.8734734 0.1506155 -0.4356263 0.8825265 0.1771348 -0.428238 0.88713 0.1720834 -0.3947736 0.8970333 0.1987084 -0.3870595 0.9020269 0.1911346 -0.3410704 0.9141115 0.2192513 -0.3350956 0.9180266 0.2119863 0.7522034 0.2042883 0.6264634 0.705615 0.6864317 0.175838 0.5494703 0.8309937 0.08678686 0.8091464 0.5331025 0.2471517 0.9208083 0.1392611 0.3643053 0.8395095 0.2088185 0.5016161 0.8745875 0.1948295 0.4440024 0.8751847 0.2068538 0.4373366 0.9124426 0.1916469 0.3615522 0.8900117 0.3287379 0.3159284 0.7983381 0.308372 0.517265 0.8246853 0.1967933 0.5302515 0.7550358 0.2220506 0.6169397 0.543644 0.8354018 0.08096271 0.5295755 0.8411454 0.1096559 0.5245348 0.8451703 0.1027159 0.5050272 0.8526318 0.1340396 0.4988356 0.8577337 0.1243221 0.4705066 0.8678724 0.1594403 0.4651994 0.8726747 0.1484197 0.4332746 0.8832329 0.1793679 0.4306657 0.8863362 0.1701039 0.3923171 0.8976848 0.2006223 0.3895823 0.9012761 0.189545 0.3387355 0.9146451 0.2206413 0.3374786 0.9174088 0.2108773 0.792455 0.5596016 0.2426133 0.7652692 0.57064 0.297881 0.765883 0.5690783 0.2992877 0.7274319 0.5837304 0.3606961 0.728181 0.5815097 0.3627657 0.6756115 0.6003937 0.4278744 0.6762173 0.5978531 0.4304671 0.6206492 0.6164146 0.4845904 0.6207626 0.6143449 0.4870669 0.5566002 0.6332857 0.5377225 0.5567003 0.6303247 0.5410875 0.4733782 0.6522952 0.5919663 0.4730952 0.6491416 0.5956478 0.6873391 0.2260074 0.6902795 0.6840469 0.2372122 0.68979 0.6535418 0.2217243 0.723686 0.6034448 0.2361893 0.7616227 0.5984858 0.2182506 0.7708317 0.5013777 0.2439644 0.8301216 0.4957583 0.2268094 0.8383206 -0.2323594 0.9421032 0.2417659 0.4052191 0.6652215 0.6271187 0.3501944 0.2517606 0.9022087 0.4181652 0.2385024 0.8765013 0.4211096 0.2441552 0.8735302 0.2141411 0.2534346 0.9433529 0.2401785 0.276421 0.9305406 0.2554782 0.3038426 0.9178293 0.2759749 0.2533069 0.9271858 0.3473238 0.2424047 0.9058732 0.08497595 0.9620927 0.2591463 0.1316742 0.9587492 0.2519164 0.1305473 0.9584062 0.2538012 0.1769181 0.9532577 0.2449485 0.176549 0.9513547 0.2524971 0.2437457 0.9413801 0.2332202 0.2440782 0.938706 0.2434272 0.2930868 0.9293881 0.2243613 0.2925267 0.9278619 0.2313019 0.02591401 0.9528486 0.3023379 0.01413369 0.9654636 0.2601547 0.08555942 0.9630047 0.2555419 -0.01078921 0.9658054 0.2590441 -0.0573132 0.9645541 0.2575862 -0.05808043 0.9638769 0.2599386 -0.1021602 0.9616048 0.2547147 -0.1033639 0.9612126 0.2557076 0.4052279 0.6652371 0.6270964 0.3386102 0.6778756 0.6525548 0.3386097 0.6778928 0.6525372 0.2462581 0.6916234 0.6789801 0.2462545 0.6916379 0.6789667 0.1831442 0.6986764 0.6915993 0.1831645 0.6986929 0.6915773 0.1191886 0.7032489 0.7008816 0.1191911 0.7032564 0.7008738 0.01966291 0.7066659 0.7072741 0.01967036 0.7066734 0.7072665 -0.08068484 0.7051621 0.7044405 -0.08068633 0.7051517 0.7044508 -0.1436681 0.7019061 0.6976298 -0.1436694 0.7019046 0.697631 -0.1469652 0.2560124 0.9554366 -0.0818786 0.2599062 0.9621564 -0.08243346 0.2575045 0.9627544 0.01994258 0.259051 0.9656578 0.02009981 0.2596327 0.9654983 0.1209597 0.2561659 0.9590348 0.1219428 0.2595747 0.9579932 0.171941 0.255709 0.9513407 0.1876968 0.2560459 0.9482671 0.1810727 0.2645468 0.9472211 0.1946708 0.255375 0.9470412 -0.2170339 0.2797709 0.9352137 -0.1664204 0.2556319 0.9523428 -0.1459722 0.2572093 0.9552673 -0.2135546 0.9257257 0.312132 -0.2984319 0.684439 0.6651929 -0.29842 0.6844545 0.6651823 -0.2146127 0.9470573 0.2387971 -0.386102 0.6689628 0.6351488 -0.3860892 0.6690012 0.6351162 -0.2816988 0.930006 0.2360818 -0.2758922 0.9340739 0.2266929 -0.1457806 0.9573872 0.2493147 -0.1482455 0.9555271 0.2549343 -0.205101 0.6963102 0.6878122 -0.2051082 0.6963043 0.6878162 -0.2104844 0.2578076 0.9429908 -0.3072491 0.2454547 0.9194291 -0.3057463 0.2542776 0.9175304 -0.3999722 0.2376334 0.8851852 -0.3983318 0.2489885 0.8828004 -0.6740217 0.7378305 0.03606903 -0.5547186 0.7792159 0.291736 -0.5754355 0.8102207 0.111429 -0.4652184 0.8804001 0.09201884 -0.5057638 0.8589957 0.07955867 -0.4949973 0.865011 0.08205854 -0.4751457 0.8761351 0.08138835 -0.4809023 0.8760806 0.03487038 -0.4601284 0.8870333 0.03812932 -0.5449539 0.8365358 0.05686241 -0.5677925 0.8213815 0.05425989 -0.6039345 0.7671162 0.2163238 -0.6940729 0.6945843 0.1892499 -0.6057081 0.7832639 0.1400554 -0.5611385 0.8170492 0.1324923 -0.5658754 0.8135289 0.1339992 -0.9799443 -0.07060128 0.1863456 -0.983955 -0.06116122 0.1676062 -0.9857055 -0.05835741 0.1580477 -0.6200932 0.7486227 0.2346242 -0.9839333 0.1577994 0.08351355 -0.9787977 0.2025227 0.03065341 -0.9426686 0.2774625 0.1854467 -0.9072227 0.4197109 0.02810376 -0.8732084 0.461968 0.155219 -0.8108762 0.5848143 0.02173012 -0.7758193 0.6165988 0.1338304 -0.7044517 0.7084877 0.04234319 -0.7297128 0.6767195 0.09782654 -0.6099778 0.7644727 0.208587 -0.6595792 0.7008029 0.2717179 -0.6848227 0.6977953 0.2099989 -0.7340553 0.6015011 0.3152132 -0.7673051 0.5936717 0.2424803 -0.7959466 0.4812232 0.3672782 -0.8450754 0.4568173 0.2777867 -0.8442941 0.3373184 0.4163938 -0.8930529 0.3130992 0.3231495 -0.9726054 -0.06868362 0.2220841 -0.9933487 -0.01194369 0.1145242 -0.839316 0.1806078 0.5127667 -0.8724091 0.224888 0.4339675 -0.9635345 -0.09126645 0.2515386 -0.9649775 -0.08887487 0.2468191 -0.8686769 0.2337164 0.4367806 -0.8592151 0.2233005 0.4603109 -0.9535134 -0.1116459 0.2799064 -0.9328901 -0.1688195 0.3181449 -0.8316279 0.008103668 0.5552742 -0.8006877 0.04912066 0.5970649 -0.8560844 0.09376937 0.5082588 -0.827513 0.1134992 0.5498548 -0.8440485 0.1846604 0.5034708 -0.8708817 0.1647629 0.4630532 -0.9339617 -0.1636645 0.3176941 -0.885226 -0.236907 0.4003126 -0.9018577 -0.2502577 0.3521701 -0.8265157 -0.2917244 0.4814236 -0.8418354 -0.357985 0.4039306 -0.7626069 0.02558469 0.6463561 -0.7288605 -0.005069792 0.6846436 -0.7096657 -0.01224344 0.7044323 -0.7855874 -0.3849555 0.484419 -0.7674645 -0.4010373 0.5001673 -0.758166 -0.4003909 0.5146569 -0.6804506 -0.4663886 0.5652158 -0.6606398 -0.4200181 0.6222056 -0.7439374 -0.03218805 0.6674738 -0.7564682 -0.01472955 0.6538647 -0.8006104 -0.005424797 0.5991607 -0.6432834 0.06690329 0.7626995 -0.6742359 0.07367134 0.7348323 -0.5481391 -0.5753203 0.6070833 -0.5359912 -0.4548715 0.7112 -0.6782532 -0.2613232 0.6867917 -0.4821745 -0.6134331 0.6254659 -0.4751625 -0.5660141 0.6736829 -0.6195819 -0.266843 0.7381823 -0.6140266 -0.2523214 0.7478671 -0.658702 0.03066909 0.7517786 -0.6372261 0.003216147 0.7706704 -0.6974377 -0.01119846 0.716558 -0.3842691 -0.5946565 0.7062018 -0.3521872 -0.6981998 0.6232827 -0.02827578 -0.8428652 0.5373814 -0.4381052 0.1668046 0.883312 -0.4294255 0.1783071 0.885325 -0.4910718 0.1270666 0.8618019 -0.4865314 0.1522541 0.8602941 -0.3926075 -0.2287031 0.8908166 -0.3312423 -0.210884 0.9196774 -0.3366813 -0.2197499 0.9156177 -0.08372932 -0.7174275 0.6915831 -0.06867778 -0.7877506 0.6121539 -0.2909025 -0.5190898 0.8036925 -0.3516337 -0.5356674 0.7677332 -0.511954 -0.1988205 0.8356875 -0.5692229 0.09006792 0.817235 -0.5667657 0.1060541 0.8170246 -0.4914925 -0.2291845 0.8401843 -0.4098109 -0.2066777 0.8884477 -0.2282443 -0.571698 0.7880774 -0.1736567 -0.5559207 0.8128933 -0.1878291 -0.5808626 0.7920348 -0.6277868 0.06975305 0.7752537 -0.625743 0.07700628 0.776219 -0.5604243 -0.2557843 0.7877176 -0.5486487 -0.20744 0.8099095 -0.4859439 -0.4878582 0.7251571 -0.4172412 -0.4721541 0.7765181 -0.2191786 -0.7284018 0.6491467 -0.204776 -0.7619048 0.6144655 -0.28411 -0.2042699 0.9367793 -0.1319937 -0.9310768 0.3401085 -0.05960536 -0.9742727 0.217348 -0.08424705 -0.9727348 0.2160778 -0.05994677 -0.9621032 0.2660148 -0.1187546 -0.9659079 0.2300417 -0.07215696 -0.9421357 0.327374 -0.112394 -0.9302124 0.349389 -0.1151023 -0.934117 0.3379007 -0.1191738 -0.952272 0.2810261 0.1356101 -0.5702222 0.8102202 0.2808597 -0.2064839 0.9372739 0.3995573 0.2222133 0.8893679 0.377468 0.1923384 0.9058278 0.3041298 -0.180992 0.9352792 0.243425 -0.1654534 0.9557037 0.3093922 0.2451601 0.9187889 0.2325242 0.3446914 0.9094617 0.2728092 0.2993118 0.9143236 0.3304179 0.2871958 0.8990788 -0.06074357 -0.9740378 0.2180843 -0.0338205 -0.975818 0.2159522 -0.0324186 -0.975026 0.2197122 0.01327717 -0.9756141 0.2190912 0.0128321 -0.9759597 0.2175728 0.05062174 -0.9743077 0.2194588 0.05638641 -0.9708661 0.2328942 0.07090222 -0.9733744 0.2179798 0.0805909 -0.9676603 0.2390373 0.09606647 -0.9616829 0.2567827 0.09586632 -0.9564791 0.2756039 0.1168378 -0.9497771 0.290297 0.1108221 -0.9370776 0.3310653 0.1282957 -0.9372271 0.3242619 0.1050504 -0.9136704 0.3926457 0.01883232 -0.8233309 0.5672493 0.03093302 -0.8204642 0.5708606 0.01594173 -0.8085764 0.5881754 0.02497202 -0.8069703 0.5900639 0.01497238 -0.796834 0.6040129 0.01938259 -0.7963023 0.6045883 0.01411056 -0.7951877 0.6061993 0.01444214 -0.7951498 0.6062412 0.009871482 -0.7887652 0.6146153 0.003237068 -0.7890738 0.6142899 0.002414762 -0.7875828 0.6162041 -0.007857859 -0.7874413 0.6163398 -0.006267189 -0.7913076 0.6113863 -0.01420533 -0.7907219 0.6120107 -0.01090401 -0.7924582 0.6098288 -0.01804709 -0.7918299 0.6104751 -0.0154317 -0.8010905 0.5983443 -0.02261185 -0.8000602 0.5994934 -0.02065944 -0.8129412 0.5819792 -0.0242061 -0.8122367 0.5828256 -0.02413916 -0.8278229 0.56047 -0.01858758 -0.8292242 0.558607 -0.01843994 -0.8321442 0.5542526 0.01987153 -0.8298246 0.5576705 -0.1424022 -0.5385211 0.8304919 -0.09736818 -0.5277581 0.8437955 -0.11655 -0.5029468 0.8564232 -0.06738573 -0.4941674 0.8667514 -0.08055311 -0.4734795 0.8771137 -0.05157083 -0.4700838 0.881114 -0.05885952 -0.4675469 0.8820065 -0.03394997 -0.4647363 0.8847981 -0.04017686 -0.4518824 0.8911724 -0.007377803 -0.4503296 0.8928319 -0.008539319 -0.4473543 0.8943161 0.01923871 -0.4477375 0.8939581 0.02152711 -0.4553746 0.8900397 0.03575456 -0.4564792 0.8890155 0.04036861 -0.4597451 0.887133 0.05385333 -0.4608902 0.8858218 0.05782359 -0.4789646 0.8759278 0.08478993 -0.4828606 0.8715827 0.08819299 -0.5077642 0.85697 0.1181438 -0.5137655 0.8497571 -0.1412557 -0.5673479 0.8112726 -0.2810778 -0.1595003 0.9463377 -0.2076312 -0.1420284 0.9678416 -0.2285879 -0.105929 0.967743 -0.1467217 -0.0912103 0.9849637 -0.161688 -0.06143093 0.9849281 -0.1123002 -0.05547082 0.9921249 -0.121477 -0.05174034 0.9912448 -0.07550883 -0.04665392 0.9960532 -0.08297795 -0.02832823 0.9961488 -0.01648277 -0.02512341 0.9995485 -0.01794189 -0.02092015 0.9996202 0.04235208 -0.02173244 0.9988664 0.0455057 -0.03255236 0.9984336 0.07842838 -0.03503441 0.996304 0.08454918 -0.03962177 0.9956313 0.1148229 -0.04227513 0.9924861 0.1210789 -0.06792992 0.9903159 0.1754636 -0.07581752 0.9815621 0.1569417 -0.5532826 0.8180756 0.1194661 -0.5437635 0.830692 0.23803 -0.122507 0.9635007 0.1821499 -0.1112729 0.9769544 0.2323526 0.3452461 0.9092951 0.151978 0.3567444 0.9217571 0.1637552 0.3830989 0.9090762 0.1054552 0.3886244 0.9153416 0.1133854 0.3925167 0.9127291 0.05679666 0.3964145 0.9163132 0.0613265 0.4080797 0.9108843 -0.02231574 0.409259 0.9121453 -0.0240283 0.4045134 0.9142164 -0.102845 0.4007319 0.9104048 -0.1099382 0.3791705 0.9187728 -0.1513655 0.3749024 0.9146238 -0.1618239 0.3683524 0.9154942 -0.2003575 0.3634144 0.909828 -0.2116429 0.3259722 0.9213846 -0.2839469 0.3129494 0.9063315 -0.2966141 0.2648632 0.9175334 -0.3688606 0.2476821 0.895877 -0.3806698 0.1924446 0.9044643 0.05008333 -0.8186637 0.5720852 -0.03126877 -0.8282954 0.5594186 0.2031913 -0.5647029 0.79989 0.1580786 -0.5769763 0.8013174 0.3417165 -0.2139396 0.9151282 0.3268491 -0.2200582 0.9190996 0.4936609 0.1500353 0.8566146 0.4290844 0.1694138 0.8872348 0.439058 0.1743962 0.8813706 0.04742419 -0.8064626 0.5893802 0.2513535 -0.5777872 0.7765201 0.265185 -0.5113916 0.8174079 0.4004594 -0.2309491 0.8867328 0.4008489 -0.2041521 0.8931082 0.4829065 0.1292098 0.8660868 0.570533 0.1049501 0.8145414 0.5648173 0.0910415 0.8201786 0.5018098 -0.1963978 0.8423864 0.5001137 -0.2315065 0.8344406 0.3926005 -0.4658706 0.7929878 0.3729823 -0.5409378 0.7538374 0.1890575 -0.7575293 0.6248253 0.1893102 -0.7547649 0.6280859 0.3832299 -0.6506953 0.6555384 0.3283087 -0.6939661 0.6408 0.5130242 -0.4382161 0.7380874 0.4632914 -0.4830005 0.7430152 0.5895949 -0.1888833 0.7853031 0.5715069 -0.2127093 0.7925494 0.6266605 0.07331758 0.7758359 0.628186 0.07641386 0.7743018 0.6744399 0.04558295 0.7369214 0.5144828 -0.5716444 0.6391637 0.6436743 0.07019728 0.7620733 0.6590148 0.07369524 0.7485109 0.6289309 -0.1962416 0.7522866 0.5869024 -0.248157 0.7706905 0.5612675 -0.4468842 0.6966156 0.3625869 -0.6461485 0.6715825 0.5828397 -0.5257425 0.6195907 0.5137504 -0.571548 0.6398387 0.6408826 -0.3192859 0.6980874 0.6782569 -0.2613244 0.6867876 0.6693056 -0.1651317 0.7244043 0.6931864 0.07573533 0.7167683 0.7959383 0.03606134 0.6043028 0.7922728 0.03164321 0.6093462 0.7779484 0.01907426 0.6280387 0.7665982 -8.05781e-4 0.6421267 0.7281177 0.01113116 0.6853618 0.6739662 0.05271953 0.7368787 0.7100132 0.07431155 0.7002565 0.5473071 -0.5223245 0.6539359 0.6884258 -0.3230615 0.6493853 0.7239909 -0.1696932 0.6686116 0.6582401 -0.4494207 0.603938 0.7062632 -0.4220049 0.5684226 0.7435624 -0.3852122 0.5465589 0.74463 -0.3848853 0.5453342 0.7994505 -0.3442981 0.4922782 0.8326377 -0.3289064 0.445573 0.8369046 -0.3206374 0.4436017 0.8756961 -0.272242 0.398799 0.8972588 -0.212271 0.3871274 0.9271472 -0.1870706 0.3246579 0.9288169 -0.1806914 0.3234964 0.9476677 -0.1223897 0.2948675 0.9549893 -0.08864897 0.2830846 0.8646435 0.2250885 0.4491401 0.8580893 0.2052586 0.4706927 0.8532307 0.1963956 0.4831418 0.8562917 0.1372442 0.4979244 0.8437629 0.1232299 0.5223779 0.834694 0.06977987 0.5462754 0.8017779 0.0451247 0.5959163 0.8006205 0.03801381 0.5979648 0.8653774 0.2385197 0.4407157 0.9746428 -0.08695673 0.2061794 0.9904289 -9.67581e-4 0.1380208 0.9471103 0.08091676 0.3105395 0.8679921 0.2574799 0.4246102 0.861585 0.2184834 0.458188 0.8655858 0.2390588 0.4400138 0.9650254 -0.08787226 0.2469908 0.9636185 -0.09220916 0.2508725 0.8715279 0.2701344 0.409227 0.9829306 -0.05420476 0.1758111 0.9564754 0.1157158 0.2678895 0.9803872 -0.06961983 0.184375 0.9799476 -0.07061886 0.186322 0.8652111 0.3149132 0.3901787 0.8692399 0.3466643 0.3524854 0.823364 0.4586821 0.3341892 0.8197338 0.4869003 0.3016035 0.7575062 0.5812496 0.2972093 0.7476828 0.6076167 0.2679042 0.697498 0.6673161 0.261124 0.6790645 0.6981384 0.2268791 0.6225421 0.7457096 0.2373998 0.9949299 0.06865012 0.07349663 0.9914275 0.02191805 0.128807 0.9639942 0.2506842 0.08872765 0.965704 0.2384974 0.1026399 0.8914011 0.4456083 0.08268839 0.8952273 0.4356333 0.09376472 0.8159337 0.5739245 0.0697354 0.8145682 0.5761534 0.06727415 0.7078105 0.7026577 0.0726397 0.6039234 0.7671249 0.2163242 0.4851904 0.8736856 0.03554975 0.532078 0.8461122 0.03142046 0.495783 0.8661475 0.06314867 0.568738 0.8201724 0.0620833 0.4956462 0.8646329 0.08212709 0.580672 0.8096981 0.08490735 0.4976548 0.8621617 0.09495854 0.5872607 0.8045822 0.088162 0.4841005 0.8681807 0.109129 0.5596475 0.8177649 0.1343706 0.6151724 0.7749183 0.1451366 0.5680375 0.8141983 0.1200613 0.7773541 0.6088297 0.1582633 0.9932572 0.0921716 0.0703175 0.9878604 0.03978103 0.1501649 0.9430323 0.3002966 0.14322 0.8808658 0.4714084 0.04300814 0.5875169 0.8086544 -0.03003287 0.7378795 0.6702356 0.07948702 0.8573631 0.506249 0.09295529 0.980059 -0.07143622 0.1854223 0.9751508 -0.1070986 0.1939352 0.9840233 -0.06163716 0.1670302 0.978998 -0.1036373 0.1755635 0.9669882 -0.1773999 0.1829294 0.9901658 0.1103404 0.08600515 0.9612942 -0.1290369 0.2434397 0.9748055 -0.08869487 0.2046642 0.9684385 -0.120396 0.2182471 0.8117974 -0.4157797 0.4100151 0.8829302 -0.1427369 0.4472812 0.8436706 -0.3577314 0.4003102 0.8772 -0.3504071 0.3282306 0.898797 -0.2784638 0.3385586 0.9235572 -0.2596309 0.282195 0.9286997 -0.2433012 0.2798601 0.9472962 -0.2214123 0.2315313 0.9477084 -0.2191026 0.2320405 0.8894953 -0.1229531 0.4400919 0.9132589 -0.1180081 0.3899132 0.9155277 -0.09991073 0.3896498 0.9329627 -0.08634078 0.3494653 0.9332094 -0.08500653 0.3491333 0.9447693 -0.07174003 0.3197882 0.944438 -0.07982665 0.318849 0.7788894 -0.413134 0.4718598 0.8234362 -0.1696951 0.5414392 0.8067244 -0.1753544 0.5643109 0.7545678 -0.3521292 0.5537441 0.8583804 -0.140913 0.4932816 0.8418829 -0.1793031 0.5090026 0.7247474 -0.5174355 0.4549744 0.6761656 -0.4930444 0.5474554 0.6283583 -0.5064655 0.5904733 0.4507977 -0.6507002 0.6110407 0.5738688 -0.5610486 0.5965728 0.6110658 -0.487538 0.6236228 0.7747735 -0.1951258 0.6013752 0.7579026 -0.2027301 0.6200679 0.7966374 -0.1600205 0.5828914 0.6863717 -0.3555228 0.6344269 0.8023772 -0.1724666 0.5713548 0.7806193 -0.1988307 0.5925369 0.6295465 -0.5072292 0.5885489 0.5632533 -0.5543604 0.6127237 0.5449218 -0.1764791 0.8197045 0.518897 -0.2132158 0.8278195 0.3578804 -0.5281223 0.7700704 0.3035355 -0.5766792 0.7584903 0.6389877 -0.1501544 0.7544193 0.6076698 -0.2054334 0.7671601 0.4763768 -0.4689491 0.7437419 0.4029722 -0.5487679 0.7324393 0.2887854 -0.7468979 0.5989546 0.2523769 -0.727821 0.6376382 0.1325972 -0.8037606 0.5799889 0.1136245 -0.7950922 0.5957499 0.03104585 -0.8340086 0.5508772 0.7366966 -0.1239988 0.6647574 0.7069305 -0.1857909 0.6824449 0.6458497 -0.3312171 0.6878761 0.5344766 -0.4993996 0.6818612 0.558565 -0.4557226 0.6930527 0.4275432 -0.6364069 0.6420227 0.3800992 -0.2126152 0.9001775 -0.07836431 -0.9090324 0.4092913 0.001793384 -0.8834222 0.4685747 0.3648141 -0.2281946 0.9026838 0.2392871 -0.5382659 0.8080914 0.2242247 -0.6142959 0.7565473 0.125455 -0.7073816 0.6956093 0.04701817 -0.8127518 0.5807098 0.45798 -0.1878799 0.8688818 0.4318302 -0.228835 0.8724433 0.2718831 -0.563515 0.7800836 0.2209892 -0.6133116 0.758296 0.03645139 -0.8362227 0.5471774 -0.03694415 -0.8715113 0.4889819 0.1804376 -0.2794566 0.9430516 0.1670907 -0.2303066 0.9586655 0.1605294 -0.2142192 0.9635043 0.149057 -0.1969824 0.9690098 0.03014832 -0.8124896 0.5821956 0.05631679 -0.7818413 0.6209288 0.1495955 -0.5430004 0.8263001 0.1667113 -0.511568 0.8429149 -0.09989672 -0.9391514 0.328657 -0.06129181 -0.9470251 0.3152565 -0.0943377 -0.9628588 0.2529886 0.1976659 -0.526718 0.8267384 0.202686 -0.5188766 0.830473 0.1144105 -0.7043284 0.7005938 0.05272102 -0.7811073 0.6221672 0.03649729 -0.8098774 0.5854628 -0.05351495 -0.9158143 0.3980207 -0.07343214 -0.9775472 0.1975077 -0.05353277 -0.9685816 0.2428667 0.01626014 -0.8331006 0.5528824 0.03190225 -0.81273 0.5817666 0.1028135 -0.5592978 0.8225665 0.1130702 -0.5379455 0.8353621 0.1749138 -0.1842359 0.967193 0.2465945 -0.1941322 0.9494755 0.2549124 -0.1727934 0.9514001 0.3328316 -0.1885176 0.9239504 0.3189366 -0.2155005 0.9229513 0.04944467 -0.9798158 0.1936913 -0.01732814 -0.833192 0.5527124 -0.08150899 -0.5575621 0.826124 0.0504173 -0.9795721 0.1946708 0.04293596 -0.9801486 0.1935597 0.04369002 -0.9798079 0.1951097 0.02364051 -0.9809756 0.1926865 0.02396583 -0.9804415 0.1953463 -0.006510853 -0.9808717 0.1945468 -0.006674945 -0.981015 0.193817 -0.01700371 -0.8330165 0.552987 -0.01497244 -0.8328647 0.5532742 -0.01470357 -0.8325611 0.5537381 -0.008154034 -0.8321446 0.5544989 -0.008043825 -0.8316342 0.5552656 0.00226432 -0.8314902 0.5555348 0.002214014 -0.8316243 0.5553343 -0.08179122 -0.5578243 0.8259191 -0.07060837 -0.5569389 0.8275467 -0.07085806 -0.5573491 0.8272492 -0.03871279 -0.5551525 0.8308472 -0.03881531 -0.5559079 0.8303371 0.01070868 -0.5552093 0.8316417 0.01076883 -0.555006 0.8317767 0.09754562 -0.1924559 0.9764454 0.01595425 -0.1980069 0.9800708 0.01758313 -0.1900497 0.981617 -0.06547617 -0.2000781 0.9775897 -0.06365042 -0.1864122 0.9804077 -0.117183 -0.1984301 0.9730846 -0.1153685 -0.194913 0.9740119 -0.1340913 -0.1965568 0.9712802 -0.1331201 -0.1956211 0.9716026 0.1389188 -0.196124 0.9706889 0.0982294 -0.1983258 0.9752016 0.06065762 -0.5556169 0.8292229 0.06025356 -0.5567575 0.8284869 0.01245146 -0.8327692 0.5534803 0.01291042 -0.8319956 0.5546321 -0.03771352 -0.9807108 0.1917917 -0.03636986 -0.9799714 0.1957889 -0.330083 -0.1860361 0.9254383 0.06850516 -0.9118042 0.4048706 0.08434188 -0.9401884 0.330049 -0.03668957 -0.809936 0.5853697 -0.05451482 -0.7780156 0.6258752 -0.3322908 -0.1590928 0.9296625 -0.2669107 -0.3781586 0.8864281 -0.2040503 -0.5159872 0.831938 -0.200901 -0.527602 0.8253939 -0.1151835 -0.7045646 0.7002297 -0.2567967 -0.1941167 0.9467704 -0.2574002 -0.1708834 0.9510753 -0.1606591 -0.5421377 0.8247882 -0.1644565 -0.5075978 0.8457534 -0.04171335 -0.8116595 0.5826396 -0.04869985 -0.7767608 0.6279101 0.08239287 -0.9633194 0.2553966 0.07466024 -0.9422025 0.3266196 -0.1790157 -0.1993921 0.9634295 -0.1782619 -0.1828889 0.9668373 -0.1099792 -0.5598196 0.8212836 -0.1100525 -0.5348936 0.8377216 -0.02431976 -0.8337631 0.5515866 -0.02514588 -0.8092826 0.5868812 0.0644114 -0.9784687 0.1960871 0.06432318 -0.9659073 0.2507702 -0.05121618 -0.8138862 0.5787628 -0.4699999 -0.2186895 0.8551462 -0.01590639 -0.8275767 0.5611274 0.08115643 -0.9082263 0.4105345 -0.01299977 -0.8600592 0.5100287 -0.01091539 -0.8593348 0.5112971 -0.2677776 -0.5617467 0.7827746 -0.1341031 -0.7097083 0.6916145 -0.2370168 -0.5863536 0.7746048 -0.2653756 -0.5966014 0.7573919 -0.4681867 -0.1921418 0.8624864 -0.4147214 -0.1817477 0.8916131 -0.4125532 -0.1977873 0.8892019 -0.3252929 -0.3941054 0.8595729 -0.2541491 -0.5420913 0.8009652 -0.5677285 -0.4613071 0.6818212 -0.415169 -0.6285606 0.6576827 -0.6551346 -0.3367516 0.6763113 -0.7383459 -0.1249781 0.6627412 -0.7295265 -0.1780059 0.6603825 -0.6569706 -0.1388357 0.7410225 -0.6433335 -0.2045477 0.7377549 -0.3459309 -0.7327157 0.5860542 -0.2747711 -0.6934953 0.6660069 -0.1928175 -0.7995593 0.5687937 -0.1199272 -0.7646504 0.6331882 -0.06008875 -0.8454623 0.5306439 -0.5593321 -0.4775504 0.6775642 -0.4964878 -0.443037 0.7464703 -0.4514598 -0.54278 0.7082189 -0.365122 -0.5015014 0.7843356 -0.3292468 -0.5868171 0.7397583 -0.5305357 -0.2180838 0.8191285 -0.5291099 -0.2203944 0.8194321 -0.5942357 -0.1809327 0.7836756 -0.7747628 -0.1951128 0.6013931 -0.7907665 -0.2053669 0.5766394 -0.6052501 -0.4907209 0.6267897 -0.450789 -0.6507143 0.6110322 -0.573853 -0.5610587 0.5965785 -0.5854383 -0.5683119 0.5781727 -0.7911497 -0.1650958 0.5889192 -0.7771694 -0.1479125 0.6116615 -0.781865 -0.1918039 0.5932103 -0.6863645 -0.3555192 0.6344367 -0.6110891 -0.4875043 0.6236263 -0.6520859 -0.5224245 0.5494149 -0.8684495 -0.1542344 0.4711764 -0.8630568 -0.1412453 0.4849566 -0.7835137 -0.4474925 0.4311114 -0.7766129 -0.4128817 0.4758162 -0.8331507 -0.1936423 0.5180374 -0.8320032 -0.1465432 0.5350662 -0.7408085 -0.4332193 0.5133458 -0.744093 -0.4390166 0.5035772 -0.9547812 -0.2049648 0.2153657 -0.9489995 -0.07005459 0.3073962 -0.9542569 -0.2038253 0.2187443 -0.9295926 -0.2401023 0.279658 -0.929946 -0.2596376 0.2603632 -0.8976916 -0.2833107 0.3374685 -0.8995859 -0.3084032 0.3092455 -0.8486803 -0.3278945 0.4150023 -0.8358707 -0.4164051 0.3576688 -0.9471633 -0.06827974 0.3134001 -0.9354335 -0.08592313 0.3429014 -0.935404 -0.08580571 0.3430114 -0.9184652 -0.09809011 0.3831449 -0.9200761 -0.1038245 0.3777306 -0.8926908 -0.1149324 0.4357678 -0.8945968 -0.1434828 0.4232133 -0.9752382 -0.09361898 0.2003648 -0.9669735 -0.1774685 0.1829406 -0.9673634 -0.1121395 0.2272288 -0.9917228 -0.01008439 0.1280015 -0.9524454 -0.06230294 0.298272 -0.9850403 -0.0695402 0.15767 -0.9775433 -0.09617453 0.1875089 -0.9810035 -0.07881939 0.1772564 -0.9737896 -0.09971082 0.2044299 -0.5875063 0.8086624 -0.03002482 -0.9942876 0.04004418 0.09893852 -0.9831192 0.1056003 0.1494169 -0.9430232 0.3003165 0.1432384 -0.8808811 0.4713788 0.0430181 -0.8573638 0.506243 0.09298104 -0.737881 0.6702311 0.0795105 -0.438373 0.8987933 9.48511e-5 -0.1084252 0.9941028 0.001944124 -0.204441 0.9788523 0.007231712 -0.277528 0.9606314 0.01286703 -0.117145 0.9930492 -0.0114144 -0.4462265 0.8949078 0.004685819 -0.4440799 0.8959769 0.004311621 0.328589 0.9444731 9.55967e-5 0.2577689 0.9662054 0.001518845 0.2201679 0.9754588 0.002520501 0.1550334 0.9879091 4.14268e-4 0.02080261 0.9997837 -3.24523e-5 -0.1171002 0.9926819 0.02949953 -0.4539496 0.8671982 0.2046875 -0.4826112 0.8664916 0.1275893 -0.4339619 0.8902256 0.1384754 -0.4539346 0.8900627 0.04161691 -0.4379109 0.8978284 0.04624378 -0.1550412 0.9797747 0.1265066 0.2158583 0.9763783 0.009527266 0.2182233 0.9753772 0.03190547 0.2049848 0.9783153 0.02967399 0.2091316 0.976661 0.04896128 0.1990609 0.9789715 0.04460662 0.2201551 0.9754062 0.0107041 -0.1256723 0.991699 0.02719354 -0.1200386 0.9894958 0.08055323 -0.1440601 0.9852924 0.09190094 -0.1346666 0.9815612 0.135656 -0.4795258 0.8567431 0.1898585 -0.4739464 0.8509132 0.2265432 -0.1667831 0.9721986 0.1643577 0.1439412 0.9807637 0.1318475 0.193066 0.979108 0.0638206 -0.6330453 0.7388902 0.2308574 -0.4583586 0.8454474 0.2740916 -0.2333498 0.9464118 0.2232774 -0.4596077 0.844021 0.2763863 -0.5941219 0.7640725 0.2514206 -0.1443054 0.9754078 0.1665999 -0.1687787 0.9728756 0.1581987 0.2031257 0.9773219 0.0598495 0.1904506 0.9801061 0.0558623 0.110704 0.7919221 0.6005033 -0.4363013 0.8370214 0.3302066 -0.4900076 0.5088433 0.7077932 -0.4836596 0.5129994 0.7091581 -0.5531258 0.5688034 0.6086991 -0.5250061 0.5898678 0.6135346 -0.5755753 0.6149082 0.5390743 -0.5557316 0.6228731 0.5506284 -0.6048269 0.6413229 0.4721118 -0.5430005 0.6919047 0.4758344 -0.6186972 0.6856655 0.3835058 -0.5757947 0.7200171 0.3873447 0.1339915 0.9852565 0.1063761 -0.4560011 0.4752575 0.7524582 -0.3953813 0.4566499 0.7969595 -0.4115127 0.445017 0.7953724 -0.3064389 0.4166492 0.8558613 -0.2951096 0.4229499 0.856752 -0.2487576 0.3802595 0.8907988 -0.1527377 0.3552737 0.9221996 -0.1789935 0.3327677 0.9258655 -0.04829508 0.3047577 0.9512047 -0.02406632 0.3134792 0.9492901 -0.0187177 0.3070581 0.9515067 0.01700842 0.2837434 0.9587495 0.06506276 0.6144425 0.7862744 0.04604256 0.7267749 0.6853308 -0.001125812 0.7364435 0.6764982 -0.006273686 0.7518828 0.6592671 -0.08560079 0.7716255 0.6302909 -0.08738034 0.7844576 0.6139959 -0.1519517 0.8021869 0.5774139 -0.1517298 0.8122285 0.563261 -0.2095447 0.8290701 0.5183955 -0.2058319 0.8383811 0.5047281 -0.2576875 0.8549158 0.4502402 -0.2526057 0.8623208 0.4388545 -0.2794146 0.8719449 0.4020445 -0.2799277 0.8747799 0.3954753 -0.3056222 0.8831948 0.3557556 -0.2994399 0.8887107 0.3471728 -0.3072146 0.8919528 0.331722 -0.2223538 0.9420718 0.2511167 0.1238046 0.9868512 0.1039105 0.1351523 0.9826309 0.1271632 0.1193535 0.9846245 0.1275514 0.1317609 0.9804063 0.1464334 0.1233944 0.9820917 0.1423715 0.1359272 0.9777453 0.1598061 0.1190587 0.9795319 0.162303 0.1389047 0.9732232 0.183145 0.1220185 0.9746154 0.1877138 0.1438491 0.9682183 0.2045992 0.129202 0.9692673 0.2093512 0.1525868 0.9628859 0.2226395 0.1391105 0.9632747 0.2296743 0.1654853 0.9567285 0.2393431 0.1547882 0.9564695 0.2474 0.1817294 0.9504977 0.252049 0.1746711 0.9499788 0.2589022 0.1668846 0.9513877 0.2588649 0.1116892 0.9702171 0.2149523 0.05188256 0.5578984 0.8282859 0.1037559 0.7896013 0.6047849 0.08594268 0.8455381 0.5269529 0.1272779 0.976918 0.1715562 0.1447299 0.9744843 0.1715627 0.02827876 0.2751747 0.9609783 0.02734667 0.2734501 0.9614975 0.06575816 0.4731687 0.8785142 0.03423374 0.2805092 0.9592407 0.1298876 0.9740682 0.1852579 0.1612972 0.7827702 0.6010442 0.141273 0.8379709 0.527112 0.1025036 0.6079527 0.7873288 0.1078373 0.5499243 0.8282237 0.02813529 0.2763754 0.9606379 0.02840143 0.2748554 0.961066 -0.04436784 0.7950468 0.6049234 0.07206034 0.975521 0.2077651 0.01710933 0.477468 0.8784826 -0.01688849 0.5305115 0.8475095 -0.007970988 0.5306949 0.8475255 6.82433e-4 0.5346232 0.8450903 0.01399362 0.5104094 0.8598176 0.0453425 0.5696655 0.820625 0.04940253 0.7946965 0.6049932 -0.03016167 0.4764267 0.8786968 -0.03536206 0.8187877 0.5730065 -0.009262263 0.8194428 0.5730863 -0.01171666 0.820111 0.5720847 0.01628941 0.8201689 0.5718896 0.02051383 0.8093889 0.5869147 0.06302946 0.8070033 0.5871738 0.06756603 0.9742788 0.2149786 0.02881115 0.9777985 0.2075576 0.02248394 0.9825189 0.1848007 -0.004895985 0.9794392 0.2016804 -0.01287883 0.9793647 0.2016904 -0.01368194 0.9792721 0.2020868 -0.0484507 0.9781746 0.2020568 -0.05153244 0.975279 0.2148844 -0.03421813 0.2805118 0.9592405 -0.02826309 0.2751765 0.9609782 -0.02733457 0.2734307 0.9615033 -0.08166491 0.5538698 0.8285886 -0.03506296 0.4760185 0.8787361 -0.1168553 0.8416395 0.5272456 -0.07346469 0.7927331 0.6051259 -0.1116896 0.9702159 0.2149568 -0.1272697 0.9769206 0.1715481 -0.1447297 0.9744843 0.1715624 -0.1708922 0.974244 0.1471206 -0.1371622 0.9561936 0.2586122 -0.1576855 0.8352059 0.5268458 -0.1328696 0.7881789 0.6009323 -0.09309035 0.5521931 0.828503 -0.1242264 0.6037745 0.7874162 -0.02798062 0.2758744 0.9607864 -0.02850067 0.2766308 0.9605536 -0.01696294 0.2837472 0.9587491 0.01879262 0.3070942 0.9514936 0.02407616 0.3134807 0.9492893 -0.06505656 0.6144398 0.7862771 0.2403541 0.9358446 0.2577303 -0.1339913 0.9852567 0.1063747 0.5759561 0.7198827 0.3873545 0.5342909 0.5946797 0.6007408 0.5667152 0.6107121 0.5530504 0.5658535 0.6269756 0.5354543 0.5965952 0.6384964 0.4862064 0.5592527 0.6915715 0.4571273 0.61883 0.6855474 0.3835027 0.4040766 0.4594315 0.7909772 0.4560377 0.4752428 0.7524455 0.4900192 0.5088416 0.7077863 0.4836741 0.5129972 0.7091498 0.5466658 0.5637072 0.6191856 0.04828953 0.3047617 0.9512038 0.1621113 0.3294665 0.9301462 0.1694661 0.3598685 0.9174836 0.2487568 0.3802574 0.8907999 0.2951247 0.4229465 0.8567484 0.3064515 0.4166468 0.855858 0.4025649 0.4428122 0.801161 -0.1238134 0.986851 0.1039001 -0.131935 0.983902 0.1205408 -0.1234274 0.9832996 0.1337454 -0.1273474 0.9819671 0.1397262 -0.1280892 0.9805205 0.1489052 -0.1309384 0.9795324 0.152877 -0.1249985 0.9777373 0.1685388 -0.1326807 0.9752958 0.1766185 -0.1292004 0.9725993 0.1932823 -0.1366764 0.9704093 0.1990615 -0.1371071 0.9671947 0.2138598 -0.1450341 0.9650309 0.2183589 -0.1472571 0.9613392 0.2326853 -0.1582657 0.9586016 0.2367173 -0.1623126 0.9548795 0.2487165 -0.1757643 0.9518857 0.2510392 -0.1806569 0.9488551 0.2589157 -0.1107039 0.7919225 0.6005028 -0.04602622 0.7267736 0.6853333 0.01372098 0.738725 0.6738674 -0.005808234 0.7483755 0.6632499 0.09617698 0.7738316 0.626047 0.07747632 0.7813515 0.6192636 0.1604186 0.8041809 0.5723277 0.1439065 0.8096213 0.5690382 0.2161007 0.8307058 0.513058 0.1999924 0.8362309 0.5106084 0.2624464 0.8561944 0.4450316 0.2484746 0.8606841 0.444391 0.2829216 0.8730925 0.3970705 0.276557 0.8735556 0.4005208 0.3085215 0.8840238 0.3511645 0.2970569 0.8876667 0.3518593 0.3082304 0.8923628 0.3296706 0.4525372 0.8262723 0.3353865 0.5097917 0.8267219 0.2379993 0.5090256 0.8274306 0.2371743 0.5022219 0.8285857 0.2474249 0.506913 0.8275836 0.2411321 0.5082083 0.8274417 0.2388819 0.5112751 0.8271135 0.2334119 0.5946094 0.7444002 0.3038222 0.5947167 0.7276707 0.3417709 -0.1841271 0.9806097 0.06709569 -0.1422455 0.9815854 0.1275005 0.1935449 0.9656474 0.1733942 0.2511925 0.9401385 0.2303084 -0.1932613 0.9796057 0.05498015 -0.1840049 0.9806583 0.06672126 0.1721103 0.972226 0.1586022 0.1913065 0.9648361 0.1802589 0.5119689 0.8251152 0.2388993 0.5274875 0.7988667 0.289083 0.4836777 0.8374212 0.2545226 0.171571 0.9803118 0.09773665 0.5510255 0.8234941 0.1350125 0.4994379 0.8586981 0.1148895 0.5448457 0.8099338 0.2171415 0.5206207 0.8305698 0.1977574 -0.1899983 0.9806649 0.04687207 -0.1908005 0.98056 0.04579859 -0.200429 0.9792354 0.03043556 -0.187973 0.9814599 0.03745275 0.2001231 0.9755014 0.09136652 0.1893118 0.9715743 0.1421421 0.1797149 0.9750893 0.1300138 -0.2028487 0.9791566 0.01024836 -0.1984857 0.9800292 0.01209831 0.1696587 0.985069 0.02924406 0.1784933 0.9833959 0.03275191 0.5153892 0.8558267 0.04398429 0.4902552 0.8709324 0.03356486 -0.2028577 0.9792081 7.43586e-4 -0.1220601 0.992506 0.005768656 -0.2867488 0.9580058 1.00932e-4 0.5158838 0.8566586 8.60486e-5 0.5417135 0.8405549 0.003763079 0.1697285 0.9854776 -0.005126476 0.294277 0.9556819 0.008559167 0.08015143 0.9967827 -2.88595e-4 0.4010093 0.9078701 0.1223255 0.4789286 0.8476101 0.2284396 0.494136 0.8423389 0.2151628 0.498986 0.8289308 0.2527583 0.4257903 0.893607 0.1420187 0.4368941 0.8897024 0.1324889 0.4261908 0.8898696 0.1627681 0.3849968 0.9212912 0.0547735 0.4841288 0.839255 0.2475287 0.486571 0.8390894 0.2432647 0.477209 0.8471397 0.2337218 0.4814488 0.8472123 0.2245851 0.46241 0.8604531 0.2140036 0.4666788 0.861333 0.2007895 0.4593082 0.866478 0.1955808 0.4659684 0.8681667 0.1707633 0.4481486 0.8785753 0.1651316 0.4573416 0.8826089 0.1088131 0.3617839 0.925498 0.1120976 0.4453551 0.8913338 0.08475202 0.3858907 0.9051287 0.1784114 0.3880658 0.904672 0.1759936 0.340984 0.9309695 0.130483 0.3232038 0.9324677 0.16138 0.291193 0.9474018 0.1328029 0.2810134 0.9471687 0.1546062 0.212482 0.9698046 0.1197101 0.2074604 0.9688411 0.135304 0.1786398 0.9769921 0.1165088 0.1776336 0.9767262 0.1202175 0.1038262 0.9898253 0.09729373 0.1068722 0.9911258 0.07904493 0.04475718 0.9967886 0.06640255 0.4541953 0.8901266 0.0371679 0.4484534 0.8930075 0.03777784 0.2525966 0.9670385 0.03211945 0.04761487 0.9985174 0.02637881 0.02840507 0.9993205 0.02349108 -0.1974188 0.9801744 0.01685267 0.3522531 0.9355546 0.0256018 0.3121804 0.9476737 0.06676751 0.3083594 0.9505282 0.03755867 0.2659829 0.9601578 0.08573293 0.1804254 0.9834971 0.01342886 0.1466554 0.9865593 0.07206314 0.08900421 0.9957111 0.02525418 0.06581145 0.9950219 0.07483607 -0.05543696 0.9983217 0.01674771 -0.06890934 0.9959141 0.05836701 -0.1193236 0.9925147 0.02601134 -0.1278213 0.9901523 0.05709832 -0.2546786 0.9668805 0.01675891 -0.2580275 0.9654484 0.03648656 -0.3618867 0.9321252 0.01344829 -0.3618085 0.9321712 0.01231354 -0.4031608 0.9151117 0.005665898 0.4544919 0.890751 8.76371e-5 -0.4031782 0.9151216 1.02245e-4 -0.4031782 0.9151216 9.6401e-5 -0.1973063 0.980342 1.06781e-4 -0.1974089 0.9803212 9.98894e-5 0.02841216 0.9995964 1.05538e-4 0.02841216 0.9995964 9.99843e-5 0.2527944 0.9675201 1.03356e-4 0.2527944 0.9675201 9.30202e-5 0.4545124 0.8907405 9.05601e-5 0.005728065 0.9881093 0.1536469 0.4388247 0.896913 0.05458992 0.007767975 0.9874048 0.1580237 0.004311919 0.9900666 0.1405332 0.01524937 0.9896242 0.1428693 0.007426977 0.9954045 0.09547173 0.02708458 0.995026 0.09586387 -0.4028589 0.9141461 0.04518562 -0.3951451 0.9078955 0.1399508 -0.4249396 0.8946909 0.1376755 -0.4139686 0.8864466 0.2069843 -0.4305391 0.8797353 0.2017474 -0.4254808 0.8757626 0.2280482 -0.4287033 0.876126 0.2204919 -0.4027709 0.9141843 0.04519766 -0.1970798 0.9795727 0.03996139 0.02182602 0.9992781 0.03109526 0.02839839 0.9990918 0.03176826 0.2527384 0.9672997 0.02132093 0.4395039 0.8964914 0.05603164 0.4382458 0.8974667 0.0499432 0.4415585 0.8958064 0.05056679 0.4387761 0.8979577 0.03387796 0.4446956 0.8950427 0.03382951 0.4427168 0.8966106 0.00955677 0.4544828 0.8906915 0.01068037 -0.5253677 0.8012583 0.2863109 -0.4150739 0.8642751 0.284152 -0.312195 0.9133459 0.2614068 -0.1419937 0.9637435 0.2259122 0.01516169 0.9795517 0.200621 0.09309518 0.9803627 0.173846 0.2657485 0.9559721 0.1244791 0.4427329 0.8935583 0.07443922 0.4820885 0.874396 0.0549767 -0.1206235 0.9469376 0.2979251 0.1058516 0.9705318 0.2164801 0.2762982 0.9477317 0.159574 0.484494 0.872558 0.06251519 -0.2934687 0.8988971 0.3253615 -0.4949317 0.7793493 0.3842622 0.4577744 0.8852156 0.08268034 0.4579846 0.8850543 0.08324104 0.4156803 0.9037982 0.1017776 0.4182053 0.9021021 0.1063777 0.4017013 0.9092373 0.1091957 0.4017455 0.9092125 0.1092402 0.3606991 0.9229249 0.1345577 0.3551633 0.9260241 0.1278223 0.317785 0.9350384 0.1572133 0.122501 0.9692673 0.213341 0.1395222 0.9564467 0.256405 0.08271282 0.9579854 0.2746319 0.100683 0.9462328 0.3074193 0.07946413 0.9477134 0.309071 0.09658557 0.9364456 0.3372549 0.0445289 0.9315086 0.3609836 0.07218742 0.9159767 0.3946843 0.02678143 0.906559 0.4212288 -0.227151 0.9197808 0.3200092 -0.1974666 0.8972846 0.3948256 -0.261972 0.8748789 0.407379 -0.230911 0.8547074 0.4649254 -0.2546296 0.8487641 0.4634259 -0.2220317 0.8271023 0.5163369 -0.278403 0.7996017 0.5320988 -0.2210817 0.7672885 0.6019895 -0.2684723 0.7378903 0.6192258 -0.5458629 0.7454934 0.3824569 -0.5069579 0.7160857 0.4798074 -0.568897 0.6669884 0.4811266 -0.529033 0.6406983 0.5564439 -0.5520467 0.626868 0.5498009 -0.5075867 0.5976483 0.6206226 -0.55925 0.54779 0.6222264 -0.4801014 0.5030517 0.7186388 -0.522204 0.4559006 0.7207341 -0.291951 0.3409665 0.893592 -0.1133397 0.2356744 0.9652004 -0.100814 0.2626138 0.95962 -0.0550884 0.4711015 0.8803571 -0.01081126 0.5951659 0.8035302 0.1413577 0.9709897 0.1928656 0.09259063 0.8961235 0.4340389 0.07771933 0.8436149 0.5312944 0.04780936 0.8012129 0.5964666 -0.008205235 0.628102 0.7780878 0.1856554 0.959928 0.2099295 0.1715938 0.9674271 0.1861195 0.1465213 0.9726127 0.1804333 -0.2779306 0.3291701 0.9024422 0.05652266 0.8650156 0.4985513 0.04901081 0.8631486 0.502566 -0.1184664 0.6467636 0.753434 -0.1252377 0.6432336 0.7553582 -0.2783135 0.330676 0.9017733 -0.3489382 0.3586359 0.8658074 -0.3409798 0.3696019 0.8643653 -0.1666694 0.6616759 0.731031 -0.1536556 0.6734599 0.723078 0.03970074 0.8703097 0.4909021 0.05691587 0.8782683 0.4747689 0.05397516 0.8936461 0.4455148 0.03406316 0.8873676 0.4598028 -0.2054446 0.7079092 0.675764 -0.2176258 0.6990309 0.6811718 -0.4326418 0.4130336 0.8013892 -0.4368838 0.407956 0.8016886 -0.2175095 0.2875151 0.9327512 -0.2055283 0.3088428 0.9286411 -0.08966714 0.6120766 0.7856986 -0.07680743 0.6285923 0.7739332 0.0510534 0.8493955 0.5252817 0.06341361 0.8588842 0.5082292 0.1909739 0.9671026 0.1680526 0.215984 0.9600438 0.1779518 0.2237551 0.9592797 0.1723841 0.2402562 0.9539023 0.1798542 0.2594309 0.9530547 0.1561487 0.2806968 0.944602 0.1701069 0.3054546 0.940912 0.1462266 0.1155883 0.9748412 0.1905884 0.06806576 0.9655669 0.2510929 0.0888158 0.8966742 0.4336902 -0.0211203 0.2926549 0.9559849 -0.0967856 0.2334755 0.9675338 0.001004934 0.4633963 0.8861507 0.0504533 0.7189462 0.6932322 -0.08246064 0.6356907 0.767527 0.06444346 0.7988898 0.5980153 0.01870983 0.2966447 0.9548047 0.00933212 0.2890266 0.9572756 0.06696367 0.7206854 0.6900206 0.0618304 0.7175975 0.6937081 0.09930628 0.9628404 0.2511503 0.09800642 0.9626128 0.2525305 0.03870314 0.3243355 0.9451501 0.02257508 0.2962862 0.9548324 0.06253081 0.7338993 0.676374 0.05355209 0.7218434 0.6899814 0.07291257 0.966785 0.2449708 0.07009196 0.9653854 0.2512335 0.03365689 0.361324 0.9318327 0.01528507 0.3254527 0.9454349 0.03474646 0.7511932 0.6591672 0.02438896 0.7357375 0.6768276 0.02988076 0.9709675 0.237338 0.02645969 0.9690353 0.2455007 0.03346103 0.4304109 0.9020127 0.0160644 0.3613572 0.9322891 0.02249842 0.7803586 0.6249275 0.0130738 0.7513654 0.6597569 0.008810877 0.9747366 0.2231841 0.005948007 0.9712678 0.2379153 0.03198975 0.4821848 0.8754853 0.01984602 0.4304214 0.90241 0.02146029 0.8017002 0.597341 0.01485902 0.7803795 0.6251296 0.008207798 0.9772676 0.2118509 0.006184697 0.974738 0.2232655 6.79248e-4 0.5326922 0.8463088 0.01765304 0.5326668 0.846141 0.01148724 0.4821742 0.8760002 0.01171976 0.8222234 0.5690443 0.008388757 0.8016985 0.5976699 0.004439532 0.9796849 0.2004939 0.003422498 0.9772709 0.2119669 -0.001904964 0.979688 0.2005189 -0.00268495 0.9772664 0.2119985 -0.004778742 0.822223 0.5691456 -0.006942212 0.801693 0.5976959 -0.006928265 0.573942 0.8188668 -0.01643657 0.4821722 0.8759223 -0.03092837 0.430419 0.9020993 -0.02028882 0.4821861 0.8758339 -0.02150774 0.7803555 0.6249662 -0.014445 0.8017365 0.5975031 -0.00840187 0.9747344 0.2232091 -0.005868256 0.9772723 0.2119069 -0.03121215 0.3613324 0.9319145 -0.01730036 0.4304081 0.9024686 -0.02215796 0.7513375 0.659546 -0.01279377 0.780359 0.6252009 -0.008978724 0.97126 0.2378515 -0.005577147 0.9747402 0.2232725 -0.0314216 0.3247041 0.9452936 -0.01694566 0.3613586 0.9322729 -0.03401106 0.7353779 0.6768032 -0.02477842 0.7513173 0.6594758 -0.02984249 0.9689395 0.2454912 -0.02637755 0.9710468 0.2374289 -0.03570228 0.295061 0.9548112 -0.02516752 0.3249991 0.9453794 -0.061347 0.7211836 0.6900224 -0.05450868 0.7343723 0.6765547 -0.07277423 0.9651876 0.2512307 -0.07015514 0.9669755 0.2450239 -0.01747089 0.2879897 0.9574741 -0.09807431 0.9629655 0.2511555 -0.06231272 0.7210909 0.6900327 -0.0992434 0.96247 0.252591 -0.1097981 0.9612079 0.2530292 -0.1099393 0.9611402 0.2532256 -0.06441694 0.7988649 0.5980514 0.009023249 0.7244914 0.6892249 -0.06640034 0.7170203 0.6938825 -0.01033639 0.2973871 0.9547011 0.03248047 0.2244235 0.9739503 0.07075524 0.2979544 0.9519543 -9.85479e-4 0.4633469 0.8861765 -0.03066504 0.6227402 0.7818276 -0.04860484 0.8962909 0.4407951 -0.3035181 0.9418056 0.1444953 0.3642386 0.3804047 0.8500721 0.4447106 0.4142611 0.7941161 0.4433763 0.4183573 0.7927135 0.3100702 0.3280323 0.8923292 0.2924337 0.3442897 0.8921588 0.3675221 0.3691416 0.853617 -0.2928296 0.9410015 0.1696089 -0.2654725 0.9523349 0.1502757 -0.2544158 0.9500601 0.1807166 -0.2273351 0.9593223 0.1673901 -0.2273031 0.9571129 0.1796337 -0.03963661 0.888772 0.4566328 -0.05246651 0.883391 0.4656906 -0.04226541 0.8725513 0.4866908 -0.05196964 0.8693373 0.4914792 -0.05153042 0.8639143 0.500996 -0.05857813 0.8617609 0.5039216 -0.05436599 0.8501496 0.5237271 -0.2022116 0.9646196 0.1691732 -0.1870334 0.9629547 0.1942597 -0.1745157 0.9671632 0.184769 0.2826694 0.3342844 0.899084 0.2221904 0.3155831 0.9225177 0.2246562 0.2928382 0.9293953 0.1138228 0.2681269 0.956636 0.1132977 0.2356901 0.9652014 0.02601081 0.6006962 0.7990542 0.09201622 0.6153763 0.7828442 0.08805418 0.6337839 0.7684819 0.1312997 0.6471733 0.7509509 0.1311579 0.6543416 0.7447381 0.1755876 0.6688838 0.7223321 0.1685583 0.6825179 0.7111663 0.2190633 0.7038632 0.6757129 0.2139709 0.7122294 0.6685401 -0.134611 0.9574159 0.255411 -0.1289284 0.9763631 0.1734725 -0.0631619 0.7990531 0.5979337 -0.06520348 0.8477428 0.5263847 0.01194977 0.6286028 0.7776347 0.02878367 0.4676085 0.8834669 0.2898873 0.8956131 0.3374058 0.4978373 0.7826601 0.3736326 -0.1066507 0.9697757 0.2194557 0.1207689 0.9468748 0.2980654 -0.276268 0.9477244 0.1596707 -0.4844972 0.8725562 0.06251603 0.5421301 0.7428684 0.392736 0.5117554 0.7199208 0.4688501 0.5637261 0.6636902 0.4916586 0.5351159 0.6448146 0.5457703 0.5458818 0.622928 0.5603337 0.5143637 0.6022176 0.6105441 0.5521036 0.543903 0.6319424 0.4876016 0.5074424 0.7104555 0.5143384 0.4522767 0.7286301 0.2286003 0.9207274 0.3162327 0.201425 0.9005782 0.3852105 0.2572504 0.8720278 0.416401 0.2361331 0.8583294 0.4555348 0.2491453 0.8453226 0.4726062 0.2277963 0.8311635 0.507224 0.2718411 0.7961929 0.5405364 0.2276577 0.7712981 0.5943663 0.2611308 0.7346399 0.6261909 -0.1217859 0.9697499 0.21155 -0.1362807 0.9590789 0.2481838 -0.08682411 0.9554333 0.2821506 -0.09623193 0.9492834 0.2993334 -0.08421593 0.9447134 0.316898 -0.09166193 0.9398012 0.3291988 -0.05037856 0.9283945 0.3681653 -0.06638056 0.9193903 0.3877052 -0.03347373 0.9035153 0.4272466 -0.457758 0.8852236 0.08268636 -0.4552977 0.887049 0.07647311 -0.4190199 0.9015435 0.1078976 -0.4144813 0.9045917 0.09959506 -0.4056671 0.9066664 0.1157168 -0.3974896 0.9118838 0.1023231 -0.3656849 0.9200549 0.1406193 -0.3500179 0.9288172 0.121598 -0.3236634 0.9321209 0.162458 0.1696995 0.9854959 1.00665e-4 0.4055922 0.8960866 0.1803441 0.4095996 0.8942589 0.180359 0.2221031 0.9710289 0.0881657 0.4203683 0.903215 0.08656436 0.1905639 0.9813553 0.02504527 0.2197257 0.9753088 0.02221333 0.2602773 0.9655176 0.005621075 -0.5114256 0.8590914 -0.02014619 -0.4928525 0.8699855 -0.01489257 -0.3947808 0.9187754 5.73661e-5 0.5144753 0.7940264 0.3237862 0.1742185 0.7554842 0.6315787 0.4861969 0.8270492 0.2821388 0.375519 0.9031012 0.2083122 0.3744543 0.9027554 0.2116995 0.3727065 0.9001811 0.2253084 0.3749309 0.9023869 0.2124259 0.3728601 0.9001883 0.2250255 0.3754429 0.9018885 0.2136351 0.3746773 0.8990248 0.2266524 0.3769193 0.9006679 0.2161701 0.3780947 0.8967921 0.2298008 0.3794133 0.8979189 0.223131 0.3946666 0.8844341 0.2490277 0.3246934 0.9026307 0.2825459 -0.001037955 0.9787186 0.2052047 0.005154967 0.9838197 0.1790875 -0.003459393 0.9851471 0.1716784 -0.002120792 0.9862483 0.1652571 -0.002264976 0.9870786 0.1602214 -0.002875566 0.9866067 0.1630921 -0.002462804 0.987398 0.1582373 -0.003203153 0.9866862 0.1626044 -0.002432286 0.9876505 0.1566545 -0.003339707 0.9867872 0.1619874 -0.002566933 0.9874718 0.1577751 0.003413677 0.9918098 0.127678 -0.02075737 0.9925747 0.1198524 -0.01379382 0.9981436 0.05932253 -0.0259816 0.9980607 0.05656868 -0.02463835 0.9995449 0.01740783 -0.02580523 0.999525 0.01685106 -0.02565234 0.9996708 6.54966e-4 -0.08735352 0.9961622 -0.005493223 0.126967 0.9522747 0.2775832 -0.0965138 0.9778719 0.185612 -0.2682136 0.9541506 0.1328841 -0.4440242 0.8960148 3.95967e-4 -0.4440805 0.8959669 0.005996644 -0.443717 0.8961457 0.006190538 -0.4441807 0.8957136 0.02001184 -0.4405199 0.8974974 0.02099299 -0.4429927 0.8955192 0.04245984 -0.4357373 0.8989307 0.04535114 -0.4376993 0.8973627 0.05621004 -0.4382941 0.896974 0.05775964 -0.4380016 0.897257 0.05553799 -0.4379919 0.8971193 0.05779391 -0.4378627 0.8972761 0.05631989 -0.4380674 0.8970684 0.05801105 -0.4378013 0.8972643 0.05698043 -0.4379145 0.8970991 0.05868649 -0.438341 0.8967285 0.06111729 -0.4357966 0.897785 0.06374734 -0.4409496 0.8934166 0.08585071 -0.4833146 0.8734815 0.05862551 -0.9173014 -0.3977782 0.01818478 -0.9876676 -0.1489217 0.04832208 -0.06451082 -0.9900208 0.1252882 -0.5759888 -0.6459665 0.5009632 -0.7100229 -0.5776385 0.4027423 -0.7674642 -0.4493737 0.4572329 -0.8179686 -0.2725884 0.5065798 -0.9716297 0.23627 0.01059544 -0.1343944 -0.9898506 -0.04619526 -0.005622088 -0.9946927 -0.1027367 -0.5377103 0.6005964 0.5917361 -0.7177311 0.5519495 0.4245161 -0.801849 0.5855195 0.1191862 -0.8117821 0.5794108 0.07275396 -0.8136934 0.5775639 0.06575083 -0.723932 0.6280637 0.2854095 -0.8083028 0.5399734 0.2346816 -0.7740637 0.5900747 0.2294284 -0.5108634 0.5548034 0.6566671 -0.06804347 0.6394948 0.7657785 -0.03420108 0.59009 0.8066127 -0.1863041 -0.97459 -0.1243594 -0.1718071 -0.9759942 -0.1338577 -0.2166535 -0.9743067 -0.061544 -0.2296081 -0.9731819 -0.01404869 -0.5619331 -0.8271455 0.007851183 -0.5079145 -0.8599166 -0.05065953 -0.4465007 -0.8945145 0.0219354 -0.4340058 -0.9004776 -0.02791327 -0.3957316 -0.9178255 -0.03151106 -0.6751019 -0.7377232 0.001327872 -0.6622905 -0.7490082 -0.0189253 -0.5874128 -0.8088958 -0.02517491 -0.867563 -0.4972287 0.009908914 -0.8139925 -0.5807077 -0.01395952 -0.7759588 -0.6307435 0.007113039 -0.7513845 -0.6597464 -0.01249462 -0.7159725 -0.6979338 -0.01648885 -0.9350646 -0.3538871 0.02044802 -0.919679 -0.3926713 9.00711e-5 -0.8714079 -0.4905295 0.005400478 -0.9975262 -0.06939822 0.01119691 -0.9880061 -0.1539591 0.01185989 -0.9793914 -0.2006488 0.0230773 -0.9712952 -0.2377797 0.006813645 -0.9485387 -0.3165042 0.009986698 -0.9952979 0.09616696 0.011581 -0.9665666 0.2563161 0.007159113 -0.9368126 0.3497246 0.008660793 -0.9340772 0.3569971 0.007263839 -0.8909258 0.4540828 0.007760703 -0.8945857 0.4467973 0.009411573 -0.8358713 0.5488957 0.005725085 -0.8467611 0.5318638 0.01079994 -0.7738678 0.6333307 0.004579544 -0.7890986 0.6141595 0.01147085 -0.7253866 0.6883284 0.004295468 -0.7141268 0.6999861 0.006515979 -0.684823 0.728694 0.004750609 -0.7687941 0.6386334 0.03321307 -0.7813399 0.6228332 0.03983432 -0.7813022 0.6229147 0.03929847 -0.8612774 0.5019567 0.07899922 -0.8044298 0.5896051 0.07251602 -0.8076861 0.5847034 0.07592952 -0.8064066 0.5864853 0.075787 -0.8712039 0.4888539 0.04500913 -0.8689051 0.4927942 0.04645413 -0.818519 0.5728973 0.04260784 -0.8179296 0.5737152 0.04291892 -0.7834824 0.6200916 0.04051965 -0.7896113 0.6110407 0.05606657 -0.7970619 0.5785471 0.1731343 -0.8084938 0.5686115 0.1517199 -0.810994 0.5649015 0.1522336 -0.8215329 0.5560048 0.1262633 -0.8526099 0.5056541 0.1317969 -0.8648489 0.4939654 0.08963745 -0.9238736 0.3700955 0.09740138 -0.9313496 0.3607026 0.04981547 -0.9314535 0.3604467 0.04972451 -0.6898571 0.6331079 0.3511008 -0.789829 0.5041345 0.3493118 -0.73697 0.592465 0.3253622 -0.7792319 0.5689009 0.2629628 -0.7890969 0.5534589 0.2664757 -0.8220049 0.5325216 0.2018142 -0.8452748 0.4921346 0.2081202 -0.8610737 0.480865 0.1652906 -0.9103437 0.3744819 0.1761754 -0.9262378 0.3615531 0.1065975 -0.9788847 0.1695893 0.1141244 -0.9845847 0.166349 0.05404615 -0.9826257 0.1763555 0.057841 -0.9970192 -0.04729467 0.06095898 -0.997221 -0.03936761 0.06324946 -0.99391 -0.09208869 0.06052094 -0.9943487 -0.08568292 0.0626831 -0.9857258 -0.1583883 0.05707782 -0.6509829 0.6223341 0.4346511 -0.7280429 0.5239774 0.4420421 -0.6925088 0.5864986 0.4200606 -0.738875 0.5666809 0.3646046 -0.7549272 0.5395081 0.3728488 -0.7937449 0.5216001 0.3128936 -0.8195504 0.4727694 0.323769 -0.8523625 0.4563007 0.2554758 -0.8929753 0.3609138 0.268954 -0.9144735 0.3499573 0.2031461 -0.9624164 0.1656224 0.2152301 -0.9793981 0.1615564 0.1211567 -0.9923986 0.01255315 0.1224232 -0.9981053 0.01940655 0.05838912 -0.997547 0.03009921 0.06319814 -0.8336722 -0.1811738 0.521696 -0.8339833 -0.1824914 0.520739 -0.8447937 -0.06576544 0.5310355 -0.787436 -0.07479929 0.6118412 -0.1061832 0.6292828 0.7698885 -0.1742244 0.5904393 0.7880529 -0.1633329 0.6085023 0.7765612 -0.2653436 0.5958001 0.7580336 -0.2603762 0.6033132 0.7538021 -0.3574662 0.5866345 0.7266898 -0.3484203 0.5995107 0.7205487 -0.0604003 0.4217715 0.9046882 -0.07105821 0.4387429 0.8957988 -0.1720024 0.4351233 0.883789 -0.1778917 0.4424454 0.8789748 -0.2730243 0.4363352 0.8573619 -0.2815031 0.4479493 0.8485856 -0.3640512 0.4403543 0.8207039 -0.3740998 0.4558182 0.807638 -0.4463422 0.447205 0.7751041 -0.4570496 0.4660938 0.757537 -0.5210773 0.4566155 0.7210969 -0.04076582 0.5466895 0.8363425 -0.03624302 0.5431618 0.8388455 -0.1673467 0.5384963 0.8258431 -0.1725172 0.5447304 0.8206745 -0.2658446 0.5372414 0.8004365 -0.2731624 0.5471533 0.7912052 -0.3546863 0.5377669 0.7648559 -0.3631619 0.5509602 0.7513696 -0.4350706 0.5402311 0.7203222 -0.6265572 -0.2367466 0.7425478 -0.04091161 0.2001354 0.9789137 -0.0434162 0.2024919 0.9783211 -0.1676569 0.2061423 0.9640522 -0.1779632 0.2196164 0.9592173 -0.2723082 0.2235698 0.9358766 -0.2829969 0.2388041 0.9289162 -0.3683435 0.2426043 0.8974778 -0.3778495 0.2573993 0.889368 -0.4565635 0.2602687 0.8507702 -0.4643273 0.2735457 0.8423615 -0.5380091 0.274934 0.7968423 -0.5441628 0.2866483 0.7884922 -0.6135565 0.286157 0.7359774 -0.6185994 0.2970666 0.7273832 -0.6836858 0.294408 0.6677557 -0.6262822 -0.236123 0.7429782 -0.5441759 -0.2494896 0.8010167 -0.5436707 -0.2485085 0.8016644 -0.4557793 -0.2596608 0.8513762 -0.4551092 -0.2584593 0.8521 -0.3617842 -0.2674096 0.893087 -0.3610349 -0.2661487 0.8937667 -0.2627748 -0.2728816 0.9254648 -0.2620447 -0.2717419 0.926007 -0.1595959 -0.2762303 0.9477479 -0.1590397 -0.2754058 0.9480812 -0.06255143 -0.2775647 0.9586685 -0.05376631 -0.2382332 0.9697186 -0.7025739 -0.2212479 0.6763427 -0.7025352 -0.2211245 0.6764232 -0.7121207 -0.1385995 0.6882401 -0.6360964 -0.1471948 0.7574398 -0.6373485 -0.1503563 0.7557644 -0.5529365 -0.1573142 0.8182381 -0.5537176 -0.1590767 0.8173686 -0.4634509 -0.1642204 0.8707726 -0.4636735 -0.1646858 0.8705661 -0.3680867 -0.1681668 0.9144574 -0.3677728 -0.1675834 0.9146906 -0.2674416 -0.1696321 0.9485251 -0.2667878 -0.1684354 0.9489225 -0.1624684 -0.1693617 0.9720703 -0.1617885 -0.1681845 0.9723881 -0.05442661 -0.1683936 0.9842162 -0.04632455 -0.1546683 0.9868799 -0.7718077 -0.2027878 0.6026525 -0.7719661 -0.2033155 0.6022717 -0.7840694 -0.07991254 0.6155073 -0.7356917 -0.08599102 0.6718358 -0.7205846 -0.03932785 0.6922509 -0.6433382 -0.04493343 0.7642624 -0.6439762 -0.04656147 0.7636273 -0.5594454 -0.05159562 0.8272599 -0.5600155 -0.0529145 0.8267907 -0.4687007 -0.05733513 0.8814945 -0.469254 -0.05852299 0.8811219 -0.3717817 -0.06227284 0.9262292 -0.3723649 -0.0634604 0.9259143 -0.2696054 -0.06645572 0.9606751 -0.2702442 -0.06770896 0.960408 -0.1633777 -0.0698387 0.9840886 -0.164061 -0.07116794 0.9838796 -0.05982279 -0.07226872 0.9955896 -0.05526793 -0.05949032 0.9966978 -0.05442136 0.036224 0.9978608 -0.0673902 0.05417692 0.9962548 -0.1633059 0.06214964 0.9846159 -0.1727487 0.07373219 0.9822024 -0.2692533 0.08686769 0.9591437 -0.278735 0.09918403 0.9552326 -0.3703737 0.1142237 0.9218331 -0.3767248 0.1229967 0.9181233 -0.465517 0.1382709 0.8741711 -0.4674763 0.1411749 0.8726601 -0.5541698 0.1553801 0.8177732 -0.5520094 0.1518929 0.8198868 -0.6362453 0.1639533 0.7538642 -0.6312239 0.1550619 0.7599422 -0.7116574 0.164183 0.6830723 -0.7055562 0.1520327 0.6921536 -0.7800231 0.1578134 0.6055238 -0.07299464 0.3375803 0.9384622 -0.06291425 0.3257614 0.9433565 -0.1724289 0.3240363 0.9301983 -0.1798591 0.3334218 0.9254624 -0.2752104 0.3303462 0.9028459 -0.2846413 0.3433333 0.8950428 -0.368157 0.3391954 0.8656829 -0.3786363 0.3551333 0.8547016 -0.4526315 0.3500469 0.8201171 -0.4634529 0.3685119 0.8058601 -0.5298831 0.3624697 0.766707 -0.5405167 0.3832501 0.7489734 -0.6008617 0.3761408 0.705325 -0.6306179 0.5868146 0.5079073 -0.6544434 0.5530154 0.5156335 -0.6405348 0.5789642 0.5044955 -0.6905511 0.562022 0.4552697 -0.7108384 0.5240803 0.4690936 -0.7543188 0.5088585 0.4148088 -0.7807158 0.4533092 0.4301088 -0.8204851 0.4392987 0.3658152 -0.8583367 0.3401463 0.3841337 -0.8941761 0.328499 0.3041998 -0.9350436 0.1530809 0.319781 -0.9617828 0.1502476 0.2289092 -0.972896 -0.00485754 0.2311921 -0.9918929 0.006878614 0.12689 -0.9899159 -0.06752473 0.1245267 -0.9898812 -0.064565 0.1263598 -0.9851494 -0.1196647 0.1231301 -0.9852025 -0.1177176 0.1245743 -0.9778405 -0.1716213 0.1198921 -0.9764003 -0.1879655 0.1063557 -0.9669871 -0.2267521 0.1162734 -0.9313785 -0.2927464 0.2164106 -0.9312133 -0.2944129 0.2148551 -0.947392 -0.2276285 0.2250195 -0.9473575 -0.2288867 0.2238855 -0.9591423 -0.162695 0.2314657 -0.9591813 -0.1644479 0.2300615 -0.96709 -0.09686654 0.2352741 -0.9672727 -0.1000466 0.2331832 -0.9714964 -0.01181721 0.23676 -0.9417088 -0.02324706 0.3356253 -0.9328008 0.1384799 0.3327251 -0.8920909 0.1403674 0.4295007 -0.8558518 0.3156784 0.4097133 -0.8101806 0.3253424 0.4876061 -0.7771465 0.422612 0.4663074 -0.7317116 0.4343775 0.5252756 -0.7062068 0.4950606 0.5061492 -0.6584165 0.5082119 0.5551652 -0.6356552 0.556106 0.5354332 -0.581796 0.570898 0.5793005 -0.5667495 0.600481 0.564108 -0.6081078 0.5366969 0.5849457 -0.8829436 -0.3544167 0.307895 -0.8828933 -0.3555865 0.3066882 -0.9044624 -0.2799623 0.3218213 -0.90449 -0.2808257 0.3209906 -0.9206983 -0.2043974 0.3324704 -0.9208238 -0.2059225 0.3311788 -0.9320084 -0.1278663 0.3391322 -0.932379 -0.1312052 0.3368303 -0.9390988 -0.03148066 0.3422023 -0.8999631 -0.04211646 0.4339273 -0.8919255 0.1397356 0.43005 -0.8375978 0.1398614 0.5280804 -0.8062596 0.3072612 0.5055057 -0.7525503 0.3146419 0.5785056 -0.7250682 0.4063822 0.5559943 -0.674655 0.4162834 0.609548 -0.6508727 0.481204 0.5872031 -0.5985851 0.4927914 0.6315477 -0.5748514 0.5499646 0.6058753 -0.5163884 0.5631427 0.6451461 -0.5070407 0.5846515 0.6333187 -0.442923 0.5910289 0.6741693 -0.7959203 -0.362796 0.4846545 -0.884851 -0.4653987 0.02104359 -0.8869188 -0.4611629 0.02652883 -0.849962 -0.5268053 0.0063982 -0.8522046 -0.5230681 0.01213485 -0.8082848 -0.5886854 -0.01118731 -0.5345555 -0.8352349 0.1289702 -0.5836268 -0.793365 0.1730659 -0.5828022 -0.7939561 0.1731345 -0.6290056 -0.7472319 0.2144682 -0.6278345 -0.7481765 0.2146063 -0.6704869 -0.6976358 0.2524911 -0.6693635 -0.6986475 0.2526742 -0.7082483 -0.645065 0.2868372 -0.7074658 -0.6458474 0.2870076 -0.7426393 -0.589678 0.3174379 -0.7423906 -0.5899527 0.3175091 -0.7730966 -0.5332297 0.3434938 -0.7734248 -0.5328296 0.3433759 -0.7956944 -0.3616704 0.4858652 -0.7317295 -0.3953163 0.5552451 -0.7312077 -0.3935492 0.5571843 -0.6621027 -0.4227314 0.6188038 -0.6612406 -0.4205171 0.6212297 -0.5875369 -0.4456076 0.6754511 -0.5863167 -0.4431228 0.6781409 -0.5082628 -0.4644373 0.7252358 -0.5067628 -0.4618252 0.7279486 -0.42446 -0.4795766 0.7680105 -0.4227628 -0.4770076 0.7705423 -0.3362799 -0.4912967 0.8034572 -0.3345466 -0.4889347 0.8056187 -0.2440127 -0.499772 0.8310751 -0.2424571 -0.4977995 0.8327126 -0.1481931 -0.5051183 0.850232 -0.1470658 -0.5037513 0.8512381 -0.03015923 -0.5076016 0.861064 -0.04536586 -0.5210961 0.8522917 -0.7673727 -0.4485916 0.4581536 -0.7017876 -0.4861289 0.5207427 -0.701488 -0.4847196 0.5224573 -0.6320423 -0.5168859 0.5773661 -0.6314533 -0.5150367 0.5796586 -0.558627 -0.5424178 0.6274701 -0.557724 -0.5402884 0.6301051 -0.4816933 -0.5633535 0.6712708 -0.4805033 -0.5610927 0.6740115 -0.4012632 -0.5801759 0.7087904 -0.3998607 -0.5779187 0.7114221 -0.3173338 -0.5932151 0.7398616 -0.3158551 -0.5911156 0.7421711 -0.2300255 -0.6026878 0.7641045 -0.2286499 -0.6009181 0.765909 -0.1396536 -0.6087273 0.7809916 -0.1386207 -0.6074792 0.7821466 0.002961456 -0.6113949 0.7913203 -0.06617718 -0.6522168 0.7551383 -0.1051316 -0.8720197 0.4780471 -0.1139535 -0.8317753 0.5432904 -0.1121116 -0.8325284 0.5425198 -0.1206288 -0.7870554 0.6049732 -0.1187341 -0.7879307 0.6042081 -0.1267926 -0.7380941 0.6626769 -0.1248355 -0.7391049 0.6619215 -0.2039662 -0.9237449 0.3241809 -0.2250834 -0.8920403 0.3919205 -0.2218031 -0.8932866 0.3909507 -0.2423018 -0.856197 0.4563075 -0.238765 -0.8577232 0.4553045 -0.2584918 -0.8155776 0.5177019 -0.2548295 -0.8173472 0.5167257 -0.2738282 -0.7700935 0.5761722 -0.2701247 -0.7720729 0.5752707 -0.2880339 -0.7207249 0.6305491 -0.2842911 -0.7229152 0.6297398 -0.1606808 -0.9011846 0.402552 -0.175672 -0.8652062 0.4696357 -0.1729279 -0.8662826 0.4686689 -0.1873823 -0.8251922 0.5328657 -0.1845237 -0.8264624 0.5318938 -0.1984587 -0.7801789 0.5932412 -0.1955448 -0.7816265 0.5923024 -0.2087233 -0.7310729 0.64959 -0.2057362 -0.7327088 0.6486992 -0.09935098 -0.9060232 0.4114018 -0.8178347 -0.2720129 0.507105 -0.7551006 -0.2996985 0.5830985 -0.7546914 -0.2984246 0.5842806 -0.68569 -0.322691 0.6524567 -0.6849719 -0.3209177 0.6540836 -0.6102702 -0.3419679 0.7145826 -0.6092422 -0.3398718 0.7164574 -0.5291779 -0.3578768 0.7693472 -0.527908 -0.3556205 0.7712635 -0.4427049 -0.3706829 0.8164598 -0.4412724 -0.3684319 0.8182523 -0.3511369 -0.3805902 0.8554847 -0.3496865 -0.3785064 0.857002 -0.2549481 -0.3877325 0.8858132 -0.2536527 -0.3859909 0.8869451 -0.1548467 -0.3922134 0.9067476 -0.153914 -0.391005 0.9074279 -0.05421185 -0.3941125 0.9174619 -0.02516824 -0.354927 0.9345553 -0.885178 -0.4576166 0.0839473 -0.8558992 -0.5127719 0.0670951 -0.8526892 -0.5178868 0.0686621 -0.8179576 -0.573199 0.04887157 -0.8142267 -0.5783607 0.05033934 -0.7736406 -0.6330273 0.0275104 -0.7690577 -0.6385223 0.0289731 -0.7201616 -0.6938037 0.001939415 -0.6523787 -0.7557817 0.05653458 -0.5948004 -0.8036457 0.01912999 -0.5324056 -0.8445446 0.05734753 -0.6150887 -0.7760329 -0.1394239 -0.5995479 -0.7968129 -0.07504475 -0.4756401 -0.8694538 -0.1334784 -0.8611055 -0.4748604 0.1816728 -0.8314161 -0.5314006 0.1623602 -0.8294178 -0.5342481 0.1632338 -0.7949566 -0.590135 0.1406591 -0.7930114 -0.592585 0.141337 -0.7534664 -0.6472859 0.1153665 -0.751358 -0.6496272 0.1159554 -0.7066432 -0.7022479 0.08662122 -0.7040148 -0.7048103 0.08720993 -0.6531135 -0.7553339 0.05397844 -0.5885882 -0.8024716 0.09799546 -0.5333322 -0.8440983 0.05527245 -0.4818341 -0.8723332 0.08289074 -0.8312727 -0.4819121 0.2770317 -0.8029955 -0.5380948 0.2562273 -0.8016024 -0.5399081 0.2567744 -0.7683911 -0.5965139 0.2318328 -0.7674673 -0.5975911 0.2321184 -0.7299475 -0.6524887 0.2035562 -0.7293441 -0.6531178 0.2037016 -0.6873787 -0.7057678 0.1714718 -0.6868272 -0.7062793 0.1715747 -0.6405315 -0.7558211 0.1358447 -0.6396553 -0.75654 0.1359723 -0.5890315 -0.8022875 0.09683412 -0.5345536 -0.835236 0.1289702 -0.4823432 -0.8721402 0.08195489 -0.4114137 -0.9041499 0.1151167 -0.4317862 -0.8837893 0.1802144 -0.4753431 -0.8483681 0.2330681 -0.4723589 -0.8500568 0.2329818 -0.5148863 -0.8087553 0.2842658 -0.5114569 -0.8109339 0.28425 -0.5516945 -0.7649615 0.3323662 -0.5481652 -0.7674531 0.3324618 -0.5858314 -0.7174107 0.3769928 -0.5825101 -0.7199959 0.3772107 -0.6176173 -0.6661478 0.4180861 -0.6147036 -0.6686313 0.4184159 -0.6464565 -0.6127063 0.4546262 -0.6440152 -0.6149666 0.4550392 -0.7111892 -0.5764137 0.4024391 -0.6793629 -0.6329556 0.3712592 -0.6810954 -0.631289 0.3709222 -0.6453474 -0.6864488 0.3351342 -0.6475716 -0.6845012 0.3348269 -0.6087148 -0.7363845 0.2953038 -0.6112303 -0.734391 0.295072 -0.5692402 -0.7826417 0.2518687 -0.5717401 -0.7808619 0.2517299 -0.526876 -0.8247999 0.2051999 -0.5289842 -0.8234632 0.2051441 -0.4819417 -0.8621899 0.1560794 -0.4476245 -0.8804849 0.1561368 -0.4113727 -0.9041312 0.1154095 -0.3218351 -0.9351716 0.1479066 -0.3886614 -0.9210726 -0.02382487 -0.3115121 -0.9502337 0.004018425 -0.3105032 -0.9505365 0.008263409 -0.2581608 -0.9647429 -0.05122852 -0.2738401 -0.9533164 -0.1272776 -0.2188366 -0.9627792 -0.1586406 -0.1621159 -0.9787678 -0.1254272 -0.1589677 -0.9789438 -0.1280562 -0.1228243 -0.9853977 -0.1179221 -0.08569228 -0.9923729 -0.08861631 -0.3682506 -0.921999 -0.1196224 -0.2959175 -0.9422242 -0.1569927 -0.2361578 -0.9641304 -0.1211696 -0.1928706 -0.969281 -0.152628 -0.1343509 -0.9831626 -0.1238601 -0.1346884 -0.9831656 -0.1234688 -0.07786357 -0.9916126 -0.1031593 -0.4648161 -0.8788467 -0.1075857 -0.3835194 -0.9117963 -0.1467671 -0.3160555 -0.9428255 -0.1057789 -0.2573267 -0.9554782 -0.1443763 -0.1913136 -0.9751992 -0.1112919 -0.1600279 -0.9766616 -0.1432595 -0.1114042 -0.9860321 -0.1238139 -0.1151441 -0.9863128 -0.1180218 -0.06824249 -0.9922012 -0.1043068 -0.5187318 -0.8515642 -0.07586592 -0.4445302 -0.8884193 -0.1144731 -0.3854774 -0.9179102 -0.09406512 -0.3313914 -0.9349308 -0.1268245 -0.2518138 -0.9638858 -0.08668434 -0.2085954 -0.9696857 -0.1272695 -0.1561841 -0.9820261 -0.1059775 -0.1332296 -0.9814808 -0.1376417 -0.08907252 -0.9882995 -0.1238156 -0.09447085 -0.9891704 -0.1123263 -0.05692839 -0.9928814 -0.1046223 -0.3335984 -0.9170443 0.2184997 -0.3694257 -0.8865187 0.2785845 -0.3657013 -0.8882189 0.2780824 -0.401319 -0.851508 0.337457 -0.3970979 -0.8536822 0.3369568 -0.4312914 -0.8118696 0.3935168 -0.4268445 -0.8144221 0.393091 -0.4593685 -0.7679656 0.4463288 -0.4549329 -0.7707733 0.4460322 -0.485805 -0.7197859 0.4958848 -0.4815662 -0.7227201 0.4957516 -0.5101335 -0.6685977 0.5410554 -0.5061143 -0.6716108 0.5410984 -0.5793897 -0.6431486 0.5006672 -0.5487679 -0.6982219 0.4597172 -0.5525223 -0.6953526 0.4595692 -0.519088 -0.7477722 0.4139861 -0.5231465 -0.7449358 0.413991 -0.4876416 -0.7931398 0.3648766 -0.4918022 -0.7905002 0.3650207 -0.4542151 -0.8343064 0.3124445 -0.4582116 -0.8320254 0.3126916 -0.4188085 -0.8709118 0.2571225 -0.4223139 -0.8691324 0.25741 -0.3817108 -0.9024278 0.199802 -0.3521596 -0.9149944 0.1968976 -0.3213698 -0.9350884 0.1494362 -0.2342427 -0.9567303 0.1726198 -0.2357481 -0.9400143 0.2465689 -0.2621355 -0.9130881 0.3123385 -0.2587594 -0.9143314 0.3115151 -0.2851772 -0.8812161 0.3770042 -0.2813402 -0.8828313 0.3761073 -0.3069191 -0.8443906 0.439096 -0.3028129 -0.8463373 0.4381983 -0.3273648 -0.8029341 0.4981257 -0.3231524 -0.805154 0.4972922 -0.3467143 -0.7567818 0.5541396 -0.3425163 -0.7592156 0.5534206 -0.3646332 -0.706995 0.605971 -0.3604501 -0.7096329 0.60539 -0.2333728 -0.9566076 0.1744673 -0.2569386 -0.939355 0.2271451 -0.2843018 -0.930099 0.2325695 -0.3161889 -0.901057 0.2968518 -0.3125187 -0.9025639 0.2961598 -0.3437866 -0.8677778 0.3588489 -0.3396297 -0.8697135 0.3581202 -0.3697958 -0.8296939 0.4181618 -0.3653755 -0.8319974 0.41747 -0.3942155 -0.787153 0.4743251 -0.3897405 -0.7897321 0.4737359 -0.4172939 -0.7401059 0.5273605 -0.4129088 -0.7428762 0.5269169 -0.4386069 -0.6897213 0.5761152 -0.4343288 -0.6926509 0.5758414 -0.2419297 -0.969994 0.02412098 -0.2409533 -0.9701732 0.02656131 -0.2003589 -0.9790298 -0.0368365 -0.1937921 -0.9805486 -0.03112912 -0.1673032 -0.9830835 -0.07454311 -0.07414686 -0.9774135 0.197902 -0.07340294 -0.9773768 0.1983597 -0.0829364 -0.9592592 0.2700805 -0.08191382 -0.9591625 0.2707352 -0.09136587 -0.9353735 0.341656 -0.1752334 -0.9837635 0.0387637 -0.1745243 -0.9838398 0.04000979 -0.1451808 -0.9890519 -0.02643603 -0.1403956 -0.9898277 -0.02302652 -0.122105 -0.99029 -0.06645482 -0.1157633 -0.9913079 -0.06251084 -0.09940242 -0.9896075 -0.103905 -0.7052827 -0.7074493 -0.04573804 -0.6367427 -0.7669947 -0.0792334 -0.5928964 -0.8038636 -0.04772257 -0.5225297 -0.8483922 -0.08481347 -0.4592062 -0.8870201 -0.04822093 -0.3861905 -0.9175449 -0.09470176 -0.3127579 -0.948043 -0.05828505 -0.2643685 -0.959141 -0.1007862 -0.2031864 -0.9761955 -0.07587867 -0.1707409 -0.9783236 -0.1171768 -0.1232511 -0.9871081 -0.1021119 -0.1068418 -0.9853203 -0.1331499 -0.06613296 -0.9901059 -0.123762 -0.07120275 -0.991601 -0.1079706 -0.04280769 -0.9936444 -0.1041083 -0.08994281 -0.9357348 0.3410437 -0.1500146 -0.930238 0.3348925 -0.1345782 -0.9547621 0.2651754 -0.1360342 -0.9548473 0.2641236 -0.1205069 -0.9736122 0.1937977 -0.1215524 -0.9736254 0.1930769 -0.1058631 -0.9868861 0.1218559 -0.1239815 -0.9861631 0.11005 -0.1078408 -0.9929676 0.04884481 -0.1074647 -0.9929837 0.04934406 -0.08949315 -0.9958018 -0.01922792 -0.08655017 -0.9960936 -0.0175153 -0.07573741 -0.9952749 -0.06075966 -0.07169616 -0.9956967 -0.05871737 -0.06209439 -0.9930758 -0.09972447 -0.05639493 -0.993654 -0.09732061 -0.05011427 -0.9906852 -0.1266157 -0.01917177 -0.8717483 0.4895789 -0.04300606 -0.9089582 0.4146632 -0.001837968 -0.9217471 0.3877874 -0.04635047 -0.937786 0.3441063 0.004672229 -0.9597918 0.280674 -0.009834706 -0.9616784 0.2740038 -0.03929114 -0.9804632 0.1927387 -0.02507877 -0.9793696 0.2005149 -0.0220322 -0.9910013 0.1320268 -0.04571563 -0.9919775 0.1178598 -0.02898555 -0.9986111 0.04399687 -0.01148504 -0.9983466 0.05632197 -0.04247456 -0.9988847 -0.02062177 -0.02979111 -0.9994482 -0.0146889 -0.0266034 -0.9982529 -0.05275911 -0.0360074 -0.997682 -0.05774378 -0.002903819 -0.9951752 -0.09807103 0.01341462 -0.9954931 -0.09388029 -0.0217393 -0.9918197 -0.125782 -0.01452374 -0.9921827 -0.1239464 -0.01584178 -0.9945952 -0.1026127 -0.7777965 -0.6283446 -0.01469159 -0.6802289 -0.7322614 -0.03289425 -0.6719913 -0.7400832 -0.026546 -0.5704202 -0.8202016 -0.04347509 -0.5584357 -0.8288657 -0.03363537 -0.4589184 -0.8871526 -0.04852145 -0.4471593 -0.8936657 -0.03755277 -0.413724 -0.909423 -0.04221731 -0.3394197 -0.939697 -0.04199963 -0.3533018 -0.9353851 -0.01525777 -0.2821496 -0.9577454 -0.05581599 -0.1042647 -0.9910055 -0.08388823 -0.1060079 -0.990419 -0.08850306 -0.1519428 -0.9857947 -0.07157039 -0.1617786 -0.9808506 -0.108443 -0.2318046 -0.9692073 -0.0830897 -0.2312707 -0.9647669 -0.1254545 -0.3308672 -0.9393817 -0.08993881 -0.3213931 -0.9383504 -0.1272987 -0.4357089 -0.895949 -0.08621633 -0.4203112 -0.8993269 -0.1206228 -0.541759 -0.8371009 -0.07588952 -0.5220003 -0.8458954 -0.1094388 -0.659265 -0.7497909 -0.05642068 -0.6436627 -0.7611235 -0.07993376 -0.7693094 -0.6382821 -0.02755254 -0.7602462 -0.6483312 -0.04114103 -0.8573467 -0.5147301 0.003106772 -0.08713376 -0.9935341 -0.07278525 -0.1140599 -0.9874449 -0.1092838 -0.1445051 -0.9852337 -0.09183138 -0.1670565 -0.9772558 -0.130627 -0.2124905 -0.971309 -0.1068028 -0.2254689 -0.9624124 -0.1514143 -0.3067644 -0.9451628 -0.1120841 -0.3080272 -0.9392248 -0.1515786 -0.4068082 -0.9073323 -0.1060915 -0.4001005 -0.9052906 -0.1427193 -0.5080527 -0.8561484 -0.09429979 -0.4956277 -0.8587543 -0.1299781 -0.63338 -0.7708815 -0.06761318 -0.6217632 -0.7776483 -0.09313386 -0.753072 -0.6572352 -0.03040951 -0.7317985 -0.67768 -0.07225483 -0.7230311 0.6907119 0.01196366 -0.7135973 0.7004166 0.01398205 -0.774724 0.6321072 0.01559853 -0.7728673 0.6343623 0.01614588 -0.8308528 0.5561992 0.01805913 -0.8352168 0.5496695 0.01663273 -0.8857217 0.4638487 0.01848214 -0.8905559 0.4545692 0.01664459 -0.9356731 0.3523894 0.01837044 -0.9365444 0.3500894 0.01795017 -0.9756729 0.218373 0.01938253 -0.9713742 0.2364835 0.02253699 -0.995007 0.09715139 0.02286362 -0.9893215 -0.1418568 0.03346401 -0.9974498 -0.06525981 0.02890133 -0.9979575 -0.06173783 0.01641118 -0.7783645 -0.6277375 0.009710013 -0.7819669 -0.6230595 -0.01802039 -0.8685866 -0.4955373 1.94552e-4 -0.866738 -0.4987534 -0.003230392 -0.9356609 -0.352649 0.01331764 -0.933843 -0.357569 0.009052813 -0.979431 -0.2005315 0.02240854 -0.7510282 0.6600066 0.01865422 -0.7357394 0.6768994 0.02224385 -0.7776871 0.6281974 0.02389478 -0.7731872 0.6336805 0.02511298 -0.8250405 0.5643976 0.02763462 -0.8298796 0.5573277 0.02618801 -0.8790767 0.4758079 0.02882772 -0.8850199 0.4647842 0.02674591 -0.9341264 0.3557216 0.02950018 -0.9350738 0.3532599 0.02906221 -0.9799354 0.1968053 0.03153508 -0.9751061 0.2188887 0.03543895 -0.9974806 0.06117331 0.03592026 -0.9944729 0.09615719 0.04216045 -0.998731 -0.03177773 0.03907209 -0.9956645 0.09246915 0.01008641 -0.9986391 0.04831975 0.01963049 -0.9983851 0.04620736 0.03304696 -0.9970643 -0.07142043 0.02760428 -0.9955972 -0.08037602 0.04822963 -0.9823909 -0.1829526 0.03790253 -0.9796087 -0.1933207 0.05471742 -0.9842071 0.1767634 0.009552597 -0.9911252 0.1323066 0.01288503 -0.990862 0.1318921 0.02823173 -0.9996403 0.006310522 0.02606803 -0.998919 0.001319527 0.04646599 -0.9926935 -0.1141609 0.03907573 -0.9907429 -0.1234035 0.05656951 -0.9747509 -0.2186106 0.04550039 -0.9721468 -0.2272199 0.05746275 -0.9562215 -0.2886711 0.04805719 -0.9369733 -0.3338192 0.1031789 -0.8901748 -0.4119527 0.1946376 -0.9345253 -0.3398811 0.1055626 -0.9150748 -0.3921099 0.09427654 -0.9461217 -0.323337 0.01752173 -0.9483395 -0.3127564 0.05325227 -0.9528666 -0.3009243 0.0385974 -0.9572854 -0.2845218 0.05149745 -0.9618383 -0.2716957 0.03238308 -0.9672262 -0.2497005 0.04608035 -0.9707741 -0.2387685 0.02423781 -0.7718119 0.6353141 0.02612429 -0.7383778 0.6737467 0.0293892 -0.7839313 0.6200393 0.03166919 -0.7753208 0.6306625 0.03380304 -0.8200747 0.5710877 0.03655809 -0.8235565 0.5661154 0.03560978 -0.8723602 0.4873128 0.03891056 -0.8779563 0.4773005 0.03710758 -0.9324885 0.3588689 0.04096692 -0.933155 0.3571663 0.04067105 -0.9834634 0.1756172 0.04425412 -0.9791069 0.1975437 0.04823201 -0.9983125 0.03148961 0.04879212 -0.9967172 0.05976748 0.05461478 -0.9979831 -0.03649312 0.05194407 -0.9980082 -0.03561145 0.05207222 -0.9951424 -0.08229202 0.05403327 -0.9881435 -0.1454111 0.04927587 -0.986386 -0.1525266 0.06146776 -0.9706986 -0.2346879 0.05163168 -0.9543642 -0.2779967 0.1091189 -0.9521223 -0.2845032 0.1118976 -0.9125332 -0.3539374 0.2049669 -0.9100494 -0.3590675 0.2070764 -0.8591243 -0.4206277 0.2915099 -0.15694 -0.9873962 -0.02045786 -0.1667922 -0.9834148 -0.07124412 -0.2438773 -0.9682654 -0.0546444 -0.2335484 -0.9685549 -0.08577108 -0.3453631 -0.9364956 -0.06083077 -0.3298843 -0.9398811 -0.08831745 -0.4534605 -0.8893105 -0.05916613 -0.434665 -0.8966291 -0.08439636 -0.5635383 -0.8244619 -0.05183708 -0.5420627 -0.8368552 -0.0764293 -0.6754146 -0.7363592 -0.0398786 -0.6595436 -0.7495048 -0.05696368 -0.779136 -0.6265077 -0.02086603 -0.7705144 -0.6366978 -0.03038901 -0.8658947 -0.5002238 0.0016222 -0.8601666 -0.5099847 -0.005392909 -0.9321568 -0.3613958 0.02184039 -0.9998587 0.01372665 0.009708821 -0.9986932 -0.04682868 0.02046716 -0.998541 -0.04767483 0.02536058 -0.9777242 -0.2092877 0.0159431 -0.9759695 -0.21498 0.03559917 -0.9266961 -0.3755637 0.01365441 -0.9229694 -0.3837809 0.02897763 -0.8511351 -0.5249008 -0.006952404 -0.8450619 -0.5346441 0.005123317 -0.7707085 -0.6362734 -0.03412669 -0.7620843 -0.6470221 -0.0242927 -0.7020663 -0.7100258 -0.05446451 -0.6598758 -0.7511098 -0.01995384 -0.595192 -0.8017264 -0.05460202 -0.5290527 -0.8484945 -0.01266986 -0.4627624 -0.8847652 -0.05515164 -0.3881868 -0.9214252 -0.01693159 -0.3227051 -0.9437937 -0.07152009 -0.2498543 -0.9673556 -0.04238045 -0.2137116 -0.9731433 -0.08555406 -0.1588345 -0.9849519 -0.06812977 -0.1350465 -0.9847549 -0.1096374 -0.09051126 -0.9909375 -0.09925073 -0.07951974 -0.988388 -0.1294828 -0.04158073 -0.9914439 -0.1237339 -0.04519474 -0.9935009 -0.1044679 -0.02478194 -0.9943343 -0.1033687 -0.181624 0.6446658 0.7425758 -0.2666431 0.5813961 0.7686874 -0.2731973 0.5621598 0.7806022 -0.3195102 0.6219478 0.7149085 -0.4106625 0.3646447 0.8356977 -0.2985643 0.8111187 0.5029373 -0.406827 0.5878838 0.6992027 -0.4396219 0.5680231 0.6957604 -0.4438214 0.5563511 0.7024928 -0.5081563 0.5444527 0.6673445 -0.5315833 0.4785602 0.6988558 -0.5891203 0.4681452 0.6586179 -0.6107938 0.3992059 0.6837878 -0.6659861 0.3908377 0.6353806 -0.6881902 0.3058699 0.6579043 -0.7482463 0.3008707 0.5912734 -0.7747293 0.1455777 0.6153063 -0.8405146 0.1481102 0.5211513 -0.8482547 -0.0594443 0.5262418 -0.8967529 -0.04953271 0.4397508 -0.8877805 -0.1584905 0.4321187 -0.8873936 -0.1562272 0.4337347 -0.8735748 -0.2412962 0.4226622 -0.8735147 -0.2409477 0.4229852 -0.853853 -0.3242893 0.4071505 -0.8538818 -0.3245452 0.406886 -0.8282716 -0.4058319 0.3863505 -0.8282653 -0.4057708 0.3864284 -0.8006854 -0.4753568 0.3646078 -0.856781 -0.4243921 0.2929468 -0.8331663 -0.4791707 0.2760968 -0.8878239 -0.4162424 0.1962418 -0.863274 -0.4713618 0.1804884 -0.9124325 -0.3977319 0.09631335 -0.8880568 -0.4523278 0.08218806 -0.9137613 -0.4049246 0.03281015 -0.9156927 -0.4000552 0.03824579 -0.9198302 -0.3912798 0.02850598 -0.8986026 -0.4387506 0.003380954 -0.9118983 -0.4090644 0.03328388 -0.8580924 -0.5134883 0.002711772 -0.8282205 -0.5596606 -0.02882474 -0.8107701 -0.5853444 -0.004903674 -0.759276 -0.6500048 -0.03152328 -0.7193507 -0.6946184 0.006318032 -0.6612403 -0.7497459 -0.02534663 -0.5935648 -0.8044676 0.02264416 -0.5311691 -0.8470829 -0.01760905 -0.475553 -0.8795848 0.01342177 -0.4371926 -0.8992178 0.01643162 -0.426934 -0.9036651 0.03341966 -0.3622547 -0.9300463 0.06152784 -0.3625589 -0.9300366 0.05985885 -0.2823683 -0.9553509 0.08702284 -0.2824438 -0.9553483 0.08680522 -0.205097 -0.972975 0.1060899 -0.2048557 -0.9729744 0.1065598 -0.1459389 -0.9824252 0.1163731 -0.1674937 -0.9681235 0.1862334 -0.1662856 -0.9681526 0.1871621 -0.1874817 -0.9484072 0.2556842 -0.1857652 -0.9483698 0.2570723 -0.2068586 -0.9227945 0.3250537 -0.1477855 -0.9308859 0.3340825 -0.1632088 -0.9003211 0.4034661 -0.097736 -0.9065146 0.4107055 -0.1068859 -0.871394 0.4787984 -0.004973173 -0.8749597 0.4841703 -0.05165767 -0.8351734 0.5475555 -0.005857348 -0.806423 0.5913103 -0.04174965 -0.7909317 0.6104785 -0.04029345 -0.728869 0.6834666 0.001111388 -0.7421143 0.6702725 -0.05672353 -0.6889511 0.7225848 -0.1324436 -0.6851333 0.7162758 -0.1303684 -0.686307 0.7155326 -0.2181461 -0.6781536 0.7017976 -0.2150207 -0.6800195 0.7009562 -0.3011026 -0.6678037 0.680717 -0.2972383 -0.6702501 0.6800105 -0.3810961 -0.6539787 0.6535118 -0.376869 -0.6568551 0.6530783 -0.4581511 -0.6364757 0.6204807 -0.4539185 -0.6395922 0.6203869 -0.5323419 -0.6149703 0.5817419 -0.5285043 -0.6180619 0.5819646 -0.6037793 -0.5889585 0.5371953 -0.6006882 -0.5917136 0.5376327 -0.6724156 -0.557791 0.4865456 -0.6704155 -0.5597875 0.4870124 -0.737984 -0.5206274 0.429333 -0.7373411 -0.5213614 0.4295468 -0.7998028 -0.4765307 0.3650122 0.02205568 -0.9910009 0.1320264 0.1284856 -0.9830671 -0.1306545 0.2659478 -0.953918 -0.1389681 0.2619374 -0.9639317 -0.04716306 0.3864406 -0.9174292 -0.09480297 0.05144274 -0.9205283 0.3872742 0.9869621 -0.1502584 0.0576905 0.2703728 -0.06632322 0.9604685 0.3725388 -0.06212311 0.925935 0.4694576 -0.05716234 0.8811029 0.5602499 -0.05140948 0.8267267 0.6442354 -0.04473978 0.7635177 0.0158385 -0.9945837 -0.1027255 0.07111895 -0.9915693 -0.1083165 0.9934999 0.1120054 0.02031373 0.7687683 0.6386645 0.03321027 0.2284369 0.6183835 0.7519431 0.09273767 0.6287264 0.7720771 0.304625 0.4816198 0.8217335 0.2470362 0.6646139 0.7051678 0.3647544 0.54698 0.7535032 0.4170435 0.3258522 0.8484663 0.3430314 0.775348 0.53025 0.5712767 0.5921614 0.5683204 0.5139788 0.5879754 0.6245885 0.5157957 0.5649257 0.6440604 0.4641138 0.5973511 0.6540414 0.4410269 0.5645516 0.697694 0.6925804 0.4975827 0.522249 0.5953954 0.6162008 0.515559 0.587256 0.5332218 0.6089376 0.635206 0.5887765 0.4998555 0.6826675 0.6024364 0.4135643 0.7316336 0.495516 0.4681628 0.6896211 0.6332254 0.3513522 0.7898324 0.5044742 0.3488132 0.725134 0.6260972 0.2866759 0.7780761 0.5748419 0.253287 0.7774958 0.5830065 0.2358044 0.788733 0.5968577 0.1471771 0.8373828 0.5358883 0.1077674 0.7942016 0.5832557 0.1704604 0.8218131 0.5670545 0.05542999 0.813902 0.5773898 0.06468856 0.813326 0.5779836 0.06660324 0.78292 0.6208865 0.03919744 0.7104667 0.7037154 0.004664659 0.991152 0.132615 0.005575537 0.9607529 0.2770672 0.0137003 0.9716917 0.2362217 0.003818988 0.9268855 0.3751757 0.01125091 0.9368802 0.3496166 0.004885733 0.8832615 0.4687766 0.009889841 0.8909743 0.4540137 0.006028473 0.8311289 0.5560028 0.00925821 0.8357539 0.5490539 0.007427811 0.7735881 0.6336404 0.007832765 0.7735596 0.6336751 0.007841706 0.7140972 0.7000232 0.005734205 0.998238 0.05882412 0.007792294 0.99883 -0.04584461 0.01539659 0.9990673 -0.03868263 0.01919376 0.9361405 -0.351549 0.0073812 0.918759 -0.393159 0.03616774 0.9502035 -0.3116006 0.004298448 0.9797825 -0.1994 0.01631349 0.9786677 -0.2045601 0.01909923 0.9925288 -0.1215981 0.01002866 0.7786682 -0.6273871 0.007831692 0.7958083 -0.6054843 -0.008827984 0.8687392 -0.4952687 -0.001097679 0.8564941 -0.5158873 0.01668077 0.8953977 -0.4452652 0.001381516 0.6589015 -0.7521747 0.009059548 0.715497 -0.6984208 -0.01650261 0.7478278 -0.6637679 -0.01287865 0.6790086 -0.7337403 -0.02392876 0.5669168 -0.8235134 -0.02076458 0.5791191 -0.815055 0.01750361 0.3060136 -0.951961 -0.0112316 0.3738917 -0.926871 -0.03339368 0.4162837 -0.9087544 -0.02955478 0.4456752 -0.8947966 0.02669686 0.4451427 -0.8950283 0.02779376 0.4990738 -0.865269 -0.047275 0.3502252 -0.9335443 -0.0764026 0.2338182 -0.9719411 -0.02568018 0.2283188 -0.9721776 -0.05235773 0.1557429 -0.9872075 -0.03413915 0.1636169 -0.9865046 0.00616908 0.1103895 -0.9900282 -0.08751237 0.1101191 -0.9901089 -0.08693915 0.1309381 -0.9863737 -0.09961092 0.08806353 -0.9920141 -0.09029328 0.08779972 -0.9920524 -0.09012979 0.1278417 -0.9845904 -0.1193253 0.0855537 -0.9912607 -0.1004143 0.1347434 -0.9831579 -0.1234703 0.07738739 -0.9916686 -0.1029793 0.7966567 0.5998182 0.07454091 0.8054767 0.587796 0.07552021 0.8087079 0.5836983 0.07271772 0.7813302 0.6228496 0.03976988 0.7813748 0.6227557 0.04035753 0.818414 0.5730228 0.04293543 0.8180118 0.5736258 0.04254889 0.8708782 0.4892863 0.04658567 0.9902141 -0.06389987 0.1240686 0.9918992 0.0121963 0.1264409 0.9925225 0.007512509 0.1218304 0.9855321 -0.1169154 0.1227093 0.9897668 -0.06774127 0.1255894 0.9677494 -0.09615594 0.2328414 0.9716399 -0.005370497 0.2364048 0.9729779 -0.01102626 0.2306353 0.9937555 -0.09268534 0.06212568 0.9945279 -0.08490657 0.06086945 0.9968846 -0.04772889 0.06279432 0.9973728 -0.03877282 0.06118941 0.9978412 0.01899844 0.0628646 0.9416917 -0.03056973 0.3350855 0.8481578 -0.06507468 0.5257315 0.9393929 -0.02389687 0.3420088 0.9330046 -0.1271365 0.3366583 0.9669283 -0.100316 0.2344919 0.9596838 -0.1619533 0.229735 0.9850386 -0.1198861 0.1237998 0.4244186 0.5838713 0.6920716 0.3537181 0.5985939 0.7187274 0.3522983 0.5877215 0.7283334 0.2636911 0.6028863 0.7529908 0.2621622 0.5963345 0.7587202 0.2755346 0.5362232 0.797838 0.2637827 0.5480195 0.7937842 0.3674798 0.5359531 0.7600743 0.3508399 0.5524957 0.7560819 0.4504979 0.5374937 0.712848 0.4290392 0.5586748 0.7097942 0.5257957 0.5406293 0.6567031 0.4995627 0.5663952 0.6554645 0.5942919 0.5448625 0.5915591 0.5633266 0.5752523 0.5930836 0.6564804 0.549438 0.5168669 0.6208379 0.5846637 0.5222343 0.7122373 0.5533944 0.4318249 0.6720703 0.5938844 0.4422928 0.7607202 0.5555673 0.3356335 0.7164105 0.6019981 0.3526392 0.779381 0.5689116 0.2624972 0.2835081 0.4354529 0.8544027 0.2713199 0.4487096 0.851496 0.3777411 0.438809 0.8153272 0.3608427 0.4571374 0.8129071 0.4627159 0.444876 0.7667981 0.4412499 0.4680853 0.7656335 0.5396528 0.4533905 0.7093743 0.5137196 0.4813305 0.7102205 0.6094685 0.4638466 0.6429576 0.5790884 0.4964938 0.6466457 0.6725336 0.4755889 0.5670219 0.637738 0.5130575 0.5745106 0.7286328 0.4877807 0.4807955 0.6895015 0.5303699 0.4932499 0.7767872 0.4994416 0.3836142 0.7335948 0.5476554 0.4023834 0.8152781 0.5094469 0.2752918 0.7686327 0.5639925 0.3018549 0.8412318 0.5170873 0.1579558 0.7925515 0.5783275 0.1933894 0.8214726 0.5561573 0.1259843 0.286166 0.3298385 0.8996197 0.2739357 0.3437293 0.8982257 0.3812049 0.3383537 0.8603485 0.3659408 0.3558272 0.8599269 0.4672758 0.3488017 0.8123982 0.4492556 0.3695762 0.8133774 0.5458492 0.3607189 0.7562611 0.5251039 0.3847759 0.7590873 0.6179335 0.3737539 0.6917126 0.594359 0.4013146 0.6969104 0.6840254 0.3876004 0.6179605 0.6573348 0.4191615 0.6262704 0.74384 0.4019995 0.5339462 0.7137243 0.4382852 0.546355 0.7962304 0.4166598 0.4386475 0.7624416 0.4586242 0.4564502 0.8391411 0.4312028 0.3315212 0.8016549 0.4800034 0.3562951 0.869314 0.4454644 0.2141372 0.8288687 0.501836 0.2472603 0.8709366 0.4725415 0.1348115 0.8429543 0.5133357 0.1609804 0.8674446 0.4911547 0.07941627 0.858832 0.5045621 0.08845824 0.8692309 0.4923695 0.04483175 0.9314175 0.3605302 0.04979246 0.720802 -0.0391736 0.6920333 0.7359066 -0.08586412 0.6716166 0.7873609 -0.07936257 0.6113628 0.07059991 0.03618729 0.9968482 0.04048478 0.2024329 0.978459 0.04294806 0.2001185 0.97883 0.07041662 0.3258281 0.942803 0.06267404 0.3378183 0.9391224 0.05986863 0.4389213 0.8965289 0.07570731 0.4213304 0.9037417 0.04179286 0.5432069 0.8385582 0.03745472 0.5467603 0.8364512 0.05505436 0.6009205 0.7974106 0.02575659 0.6407674 0.7673029 0.8452381 -0.05989521 0.5310229 0.8344273 -0.1808117 0.5206134 0.8872882 -0.1586528 0.4330692 0.8738916 -0.2406427 0.4223798 0.9205672 -0.2060881 0.3317888 0.9050194 -0.2793532 0.3207832 0.9472317 -0.2290268 0.2242743 0.9321116 -0.2916195 0.2147704 0.9671485 -0.2263366 0.1157391 0.9731751 -0.223896 0.05292326 0.9851947 -0.1604037 0.06051546 0.9765298 -0.1875884 0.1058312 0.9779716 -0.1712623 0.1193349 0.9479225 -0.2268151 0.2236024 0.9589921 -0.1646387 0.2307124 0.9213804 -0.2037469 0.3309764 0.931784 -0.1315235 0.3383494 0.8883375 -0.1556958 0.4319899 0.8971513 -0.04268604 0.4396561 0.8998835 -0.04871392 0.4334014 0.9359889 -0.3369166 0.1020395 0.9359384 -0.3358902 0.1058167 0.9140347 -0.3948056 0.09310799 0.9139641 -0.3941181 0.09664642 0.9361421 -0.3486787 0.04540032 0.9531052 -0.3002631 0.03785192 0.956242 -0.2886068 0.04803603 0.9696988 -0.2378382 0.05583238 0.9534006 -0.2801245 0.1120609 0.9534559 -0.2815159 0.1080307 0.6435111 -0.0464465 0.7640264 0.6378605 -0.1469382 0.7560048 0.7123419 -0.1384945 0.6880323 0.70274 -0.2211283 0.6762091 0.7719564 -0.2032436 0.6023083 0.754587 -0.2998281 0.5836967 0.8183525 -0.2716944 0.5064399 0.7954946 -0.3629882 0.4852092 0.8542203 -0.3239608 0.4066414 0.8285679 -0.4054796 0.3860847 0.8826516 -0.3558038 0.3071316 0.8584696 -0.4226198 0.2905557 0.8579352 -0.4218323 0.2932658 0.8326864 -0.4804854 0.2752586 0.8322796 -0.4800298 0.2772761 0.8027206 -0.5388324 0.2555374 0.8024299 -0.5386125 0.2569103 0.4688427 -0.05840575 0.8813487 0.4638791 -0.1641302 0.8705616 0.5529934 -0.159062 0.8178617 0.5437293 -0.2494676 0.8013267 0.6268615 -0.2359362 0.7425488 0.6089484 -0.342224 0.7155869 0.6863568 -0.3204096 0.6528798 0.6606331 -0.4232156 0.6200424 0.7326502 -0.3928049 0.555813 0.7009875 -0.4864869 0.5214856 0.7681376 -0.4480547 0.4573968 0.7378017 -0.5207352 0.4295154 0.7380285 -0.5209041 0.4289205 0.7106596 -0.5767424 0.4029033 0.7110607 -0.5769743 0.4018625 0.6801888 -0.6318484 0.3716328 0.6807744 -0.6320782 0.3701667 0.5596068 -0.05278789 0.8270754 0.5540713 -0.1571618 0.8174995 0.6360369 -0.1504151 0.756857 0.6264036 -0.2366928 0.7426944 0.7028206 -0.2209826 0.676173 0.6847419 -0.3229162 0.6533404 0.7556636 -0.2979769 0.5832515 0.7307512 -0.3957112 0.5562512 0.7966035 -0.361075 0.4848173 0.7672133 -0.4494848 0.457545 0.8284968 -0.4056065 0.3861042 0.8006333 -0.4758426 0.3640881 0.8003693 -0.4755905 0.3649969 0.7735702 -0.5328452 0.3430236 0.773476 -0.5327729 0.3433485 0.7427466 -0.5895869 0.3173561 0.7428176 -0.5896178 0.3171325 0.7845084 -0.07511144 0.6155526 0.7722886 -0.2025694 0.6021096 0.8336939 -0.1825266 0.5211896 0.8179199 -0.2725467 0.5066808 0.8736569 -0.2411873 0.4225547 0.8539996 -0.3244034 0.406752 0.9043999 -0.280867 0.3212078 0.8837013 -0.353574 0.3066883 0.9309479 -0.294775 0.2155085 0.91171 -0.3566632 0.2039026 0.9113544 -0.3556013 0.2073187 0.8894227 -0.4140633 0.1935948 0.8891108 -0.4133669 0.1964939 0.8626232 -0.4729269 0.1795035 0.862341 -0.4725208 0.1819126 0.5126737 -0.8097773 0.2853531 0.5140665 -0.8097463 0.2829248 0.5702843 -0.7816563 0.2525655 0.5711483 -0.7816093 0.2507518 0.6285045 -0.7475551 0.2148105 0.6288414 -0.7475225 0.2139363 0.6874555 -0.7057818 0.1711052 0.6873274 -0.7058005 0.171542 0.7529295 -0.6480637 0.1145021 0.7525915 -0.6481426 0.1162643 0.8165818 -0.5752654 0.04758107 0.8162807 -0.5753993 0.0510044 0.8477394 -0.5303265 0.00958395 0.813564 -0.5814123 -0.008568823 0.5494374 -0.7660545 0.3335856 0.5508477 -0.7661735 0.3309759 0.6097789 -0.7352266 0.2959926 0.6106364 -0.7352879 0.2940664 0.6700316 -0.6979473 0.2528386 0.6703404 -0.6979722 0.2519496 0.7300008 -0.6525576 0.2031438 0.7298702 -0.6525436 0.2036575 0.7944585 -0.5910102 0.1397951 0.7941751 -0.5909679 0.1415731 0.8546968 -0.5149316 0.06587153 0.8545112 -0.5148058 0.06917929 0.8830221 -0.4687054 0.0242325 0.8544303 -0.5194939 0.008658885 0.371901 -0.06335186 0.9261081 0.3678852 -0.1680967 0.9145513 0.4635835 -0.16462 0.8706266 0.4551336 -0.2596415 0.8517275 0.5444968 -0.2483029 0.8011673 0.527611 -0.3581085 0.7703149 0.6109634 -0.3393619 0.7152324 0.585662 -0.4461033 0.6767511 0.6631507 -0.4197213 0.61973 0.6307401 -0.5173717 0.5783542 0.7027767 -0.4840046 0.5213871 0.6712456 -0.5583963 0.4874659 0.6720772 -0.5589122 0.4857258 0.6449788 -0.6134759 0.4556862 0.645972 -0.6139478 0.4536391 0.6158176 -0.6670721 0.4192655 0.6169753 -0.6674728 0.4169192 0.1634308 -0.07108324 0.9839907 0.1618279 -0.1692737 0.9721925 0.2675997 -0.1683373 0.9487112 0.2620679 -0.2728256 0.9256818 0.362045 -0.2659739 0.89341 0.3495205 -0.380685 0.8561043 0.443268 -0.3680317 0.8173533 0.4222604 -0.4799059 0.7690166 0.5092413 -0.4611381 0.7266533 0.4797551 -0.5638108 0.6722742 0.1625453 -0.1680983 0.9722767 0.1590672 -0.2761488 0.9478605 0.2629538 -0.2715947 0.9257925 0.2535697 -0.3877475 0.8862022 0.3515778 -0.3781936 0.856366 0.3342011 -0.4914986 0.8042008 0.4252712 -0.4764401 0.7695123 0.3992394 -0.5805307 0.7096423 0.4828045 -0.5603967 0.6729452 0.4549694 -0.6373747 0.6218974 0.5316544 -0.6169661 0.5802555 0.5093734 -0.6704719 0.5394501 0.1597036 -0.2752788 0.9480066 0.1538959 -0.3921628 0.9069313 0.2552228 -0.3857697 0.8865907 0.242269 -0.4998486 0.831539 0.3368896 -0.4885067 0.8049016 0.3154125 -0.5934453 0.7404983 0.402194 -0.5773472 0.7105704 0.3777493 -0.6547252 0.6547064 0.3805192 -0.6560509 0.6517688 0.3613341 -0.7077479 0.6070672 0.1549812 -0.3908631 0.9073075 0.1470021 -0.505092 0.8504543 0.2443941 -0.4975123 0.832318 0.2284028 -0.6027898 0.7645106 0.3180304 -0.5906897 0.7415811 0.2978976 -0.6683413 0.6815989 0.300685 -0.6696755 0.6790605 0.2849385 -0.7212617 0.631341 0.2876144 -0.7223513 0.6288773 0.2707678 -0.7706313 0.5768988 0.1398516 -0.6073213 0.7820501 0.1305603 -0.6852536 0.7165064 0.1323577 -0.6861616 0.7153067 0.1250202 -0.7382161 0.6628779 0.1267157 -0.7389664 0.6617188 0.1189131 -0.7871775 0.605154 0.120544 -0.7877969 0.6040243 0.1849067 -0.8255003 0.5332531 0.1982219 -0.7813035 0.5918386 0.195941 -0.7804893 0.5936698 0.208492 -0.7323797 0.6481907 0.2061418 -0.7313851 0.6500627 0.2179161 -0.679678 0.700393 0.2154311 -0.6784694 0.702331 0.2304629 -0.6006336 0.7655887 0.1385425 -0.6087192 0.7811959 0.1483777 -0.5035756 0.8511144 0.4303829 -0.8132483 0.3916603 0.482773 -0.7208572 0.497288 0.4165334 -0.7418534 0.5255032 0.3908401 -0.7881193 0.4755125 0.3267355 -0.804359 0.4962365 0.3036656 -0.8451243 0.4399458 0.2418792 -0.8572032 0.4546395 0.2223564 -0.8925018 0.3924262 0.1630003 -0.900916 0.4022207 0.1480758 -0.9304634 0.3351292 0.09130489 -0.9356412 0.3409383 0.08187413 -0.9593187 0.2701929 0.5072705 -0.6696121 0.542491 0.4378901 -0.6916441 0.5743525 0.4139926 -0.741059 0.5286225 0.3461017 -0.7584123 0.5522904 0.3240342 -0.8036977 0.499071 0.2580625 -0.8167992 0.5159874 0.239373 -0.8567057 0.4568982 0.1754375 -0.8659847 0.4682866 0.1610113 -0.9005857 0.4037583 0.09927982 -0.9064057 0.4105758 0.09007555 -0.9354629 0.3417539 0.008944451 -0.8718739 0.4896491 0.02110135 -0.8749918 0.4836779 0.105296 -0.8715097 0.4789401 0.3982594 -0.8525115 0.3385465 0.3430496 -0.8688118 0.3570477 0.3133884 -0.901784 0.2976129 0.2616505 -0.9137424 0.3108277 0.2358419 -0.9399914 0.246566 0.4734153 -0.8492079 0.2339317 0.4746595 -0.8490675 0.2319115 0.5277639 -0.8240877 0.2057783 0.5285214 -0.8239638 0.2043253 0.5833367 -0.7935382 0.1732503 0.5835763 -0.7934879 0.1726726 0.6404898 -0.7559331 0.1354179 0.6402734 -0.7560005 0.1360636 0.7059196 -0.7030913 0.08567476 0.7054516 -0.7033135 0.08768266 0.7719599 -0.6351355 0.02609515 0.7714728 -0.6355614 0.02985757 0.805468 -0.5925874 -0.007836163 0.1138712 -0.8323996 0.5423508 0.112282 -0.8318958 0.543454 0.05166745 -0.8351583 0.5475776 -0.01703321 -0.7905871 0.6121128 0.04211384 -0.8057214 0.5907958 0.04062259 -0.7421272 0.669027 0.01343202 -0.7293955 0.6839604 0.05674606 -0.6889268 0.7226063 0.02853178 -0.6533835 0.7564893 0.05566912 -0.6112011 0.7895151 0.03344702 -0.5213413 0.8526926 0.04646575 -0.5073913 0.8604622 0.05660444 -0.3544703 0.9333525 0.005692183 -0.3941059 0.9190474 0.08114409 -0.2377915 0.9679209 0.0533173 -0.2775294 0.9592366 0.05451369 -0.1546044 0.9864714 0.04411524 -0.1682295 0.9847602 0.06187319 -0.05946719 0.996311 0.05537307 -0.07220995 0.9958512 0.05421596 0.05311822 0.9971154 0.5344316 -0.8450616 -0.01593655 0.5887652 -0.8067331 -0.05037254 0.5998823 -0.798359 -0.05257767 0.6368139 -0.7669352 -0.07923603 0.4212241 -0.8981206 -0.1262922 0.4503602 -0.8928294 -0.00561738 0.4501509 -0.8925387 0.02718371 0.5263388 -0.8501457 -0.01482945 0.3292535 -0.9419066 -0.06636416 0.3057625 -0.9499075 -0.06469202 0.2701937 -0.9580186 -0.09589415 0.3049189 -0.9456021 -0.1134081 0.3414278 -0.9320783 -0.1210677 0.3980733 -0.9132673 -0.08648997 0.1740608 -0.975795 -0.1323903 0.2283082 -0.9614381 -0.1533372 0.2599127 -0.9560992 -0.1353504 0.3075221 -0.9394563 -0.1511692 0.3526639 -0.926969 -0.1278932 0.3970932 -0.9069653 -0.1404669 0.4475093 -0.8866947 -0.1162244 0.4911726 -0.8618068 -0.1266438 0.06763476 -0.9922628 -0.1041157 0.1151047 -0.9863023 -0.1181471 0.1076595 -0.9856976 -0.1296531 0.1361483 -0.9816219 -0.1337237 0.1523733 -0.9820292 -0.11136 0.3686876 -0.8873065 0.27705 0.3337325 -0.9170017 0.2184734 0.352295 -0.9149512 0.1968573 0.2047715 -0.9730328 0.1061876 0.2823755 -0.9553658 0.08683472 0.2826644 -0.9552702 0.08694732 0.3613704 -0.9304715 0.06028425 0.3637228 -0.9295123 0.06093037 0.4271338 -0.9035732 0.03334891 0.257036 -0.9393327 0.227127 0.2844141 -0.9300676 0.2325571 0.3155559 -0.9017956 0.2952782 0.3667113 -0.8873667 0.2794696 0.4004633 -0.852605 0.3356991 0.2431886 -0.9696337 0.02588105 0.3079949 -0.9513739 0.005172371 0.3141849 -0.9493374 0.006808757 0.3831062 -0.9234544 -0.02148807 0.3939116 -0.9189358 -0.01976817 0.455185 -0.8889257 -0.05116492 0.4671962 -0.8825813 -0.05270797 0.5131034 -0.8546624 -0.07922995 0.5285854 -0.8449026 -0.08207923 0.5531952 -0.8272712 -0.09796702 0.6297511 -0.7703724 -0.09969961 0.1878878 -0.9480329 0.2567722 0.1855198 -0.9486925 0.2560567 0.2065282 -0.9233418 0.3237068 0.2594403 -0.9136539 0.3129338 0.2846056 -0.8821392 0.3752737 0.340625 -0.8686357 0.3597871 0.3690066 -0.8310089 0.4162433 0.4280853 -0.8129596 0.3947658 0.4584689 -0.7695691 0.4444884 0.1362821 -0.9545642 0.265018 0.1344451 -0.9550079 0.2643568 0.1498341 -0.9306562 0.3338096 0.2044547 -0.9231853 0.3254649 0.2246992 -0.8928152 0.3903735 0.2821274 -0.8818848 0.3777348 0.3063008 -0.8455769 0.4372409 0.3664441 -0.8306341 0.4192444 0.3934245 -0.7887065 0.4723973 0.4561817 -0.7690778 0.4476805 0.4849757 -0.7215374 0.4941481 0.2000174 -0.9686108 -0.1476014 0.2260733 -0.9655709 -0.1287004 0.2138081 -0.9691585 -0.1225482 0.2453041 -0.9649744 -0.0930075 0.2171999 -0.9727138 -0.0815609 0.2458515 -0.9681497 -0.04736322 0.2024218 -0.978715 -0.03379964 0.2398448 -0.9704988 0.02463352 0.1757469 -0.9836328 0.03974652 0.2053548 -0.972877 0.1064887 0.1459994 -0.9824154 0.1163799 0.1204279 -0.973733 0.1932393 0.1677835 -0.9679305 0.1869737 0.1661394 -0.9683085 0.1864841 0.2350192 -0.9562581 0.1741738 0.232805 -0.9570116 0.1730051 0.3227205 -0.9346813 0.1490715 0.3207704 -0.9354751 0.1482996 0.4117687 -0.9039686 0.1152706 0.4113756 -0.9041615 0.1151613 0.4815524 -0.8725399 0.08234894 0.4830417 -0.8717221 0.0822879 0.5314976 -0.8451868 0.05630147 0.5347287 -0.843166 0.0560038 0.5918015 -0.8058089 0.02105396 0.5971921 -0.8018435 0.02022033 0.6568593 -0.7536901 -0.02207314 0.6648903 -0.7465594 -0.02387654 0.6969132 -0.7154057 -0.05006861 0.710284 -0.7020966 -0.05056822 0.02473467 -0.9809207 0.1928287 0.03669732 -0.9790965 0.2000582 0.007376909 -0.9597762 0.2806692 0.05261689 -0.9932125 -0.103733 0.09450608 -0.9891672 -0.112326 0.08686643 -0.9878896 -0.1285626 0.1085882 -0.9855574 -0.1299439 0.1210517 -0.9869289 -0.1063852 0.1369398 -0.9848423 -0.1064586 0.156665 -0.9850195 -0.07206213 0.06501507 -0.9897307 -0.1273037 0.08042991 -0.9886269 -0.127075 0.08941078 -0.9907182 -0.1023874 0.100376 -0.9897528 -0.1015585 0.114705 -0.9912495 -0.06532305 0.1231014 -0.990314 -0.06422102 0.1393957 -0.9899072 -0.02555119 0.01969903 -0.9944765 -0.1030954 0.04521155 -0.9935003 -0.104466 0.04117488 -0.9911804 -0.1259608 0.050462 -0.990861 -0.1250922 0.05600064 -0.9934835 -0.09927046 0.06246447 -0.9931989 -0.09825527 0.07132649 -0.995621 -0.06042677 0.07611167 -0.9953289 -0.0593937 0.08622193 -0.9960952 -0.01897472 0.08985149 -0.9957924 -0.01801025 0.1073914 -0.9930138 0.04889601 0.01441651 -0.9919509 -0.1257997 0.02019661 -0.992029 -0.1243811 -0.008800029 -0.9951409 -0.09806752 0.005151391 -0.9954292 -0.09536308 0.04010045 -0.9978031 -0.05273598 0.02626091 -0.9980295 -0.05698627 0.0293039 -0.9993577 -0.02063125 0.04043263 -0.9990621 -0.01549494 0.01647537 -0.9988953 0.04400974 0.03147113 -0.9979996 0.05483067 0.045726 -0.9919762 0.1178666 0.06453794 -0.9900171 0.1253032 0.07423281 -0.977319 0.1983361 0.3778874 -0.9246609 -0.04694062 0.4569416 -0.8887654 -0.03606271 0.4507565 -0.8912709 -0.04954582 0.5686984 -0.8219265 -0.03192448 0.5616455 -0.8261688 -0.04471665 0.6791883 -0.7335318 -0.02518868 0.6739509 -0.7379992 -0.03387492 0.7814997 -0.6237509 -0.01389819 0.7786833 -0.627142 -0.01858896 0.1832389 -0.9754456 -0.1221857 0.2470808 -0.9586585 -0.141156 0.2747233 -0.9529871 -0.127839 0.3337058 -0.9322077 -0.1401053 0.3722479 -0.9200221 -0.1224378 0.4292002 -0.8937787 -0.1301796 0.4706255 -0.8752344 -0.1116986 0.5282328 -0.8411147 -0.1161739 0.6065812 -0.7909206 -0.08064794 0.6459339 -0.7589128 -0.08258962 0.7115585 -0.7007133 -0.05182141 0.7617188 -0.6464592 -0.04330283 0.8662695 -0.4995771 -3.6146e-4 0.8689056 -0.4949702 -0.002780735 0.9334118 -0.3585842 0.0126338 0.9359784 -0.3519289 0.009522914 0.9772897 -0.2108133 0.02150595 0.9797723 -0.199435 0.01649212 0.9976612 -0.06385678 0.02438348 0.9987954 -0.04609304 0.01683372 0.9986325 0.04847526 0.01957845 0.9963981 0.08395749 0.01191473 0.9847858 0.1732256 0.01378095 0.7137209 0.7003265 0.01205837 0.7258643 0.6876897 0.01428204 0.7728887 0.6343517 0.01552629 0.7745961 0.6322494 0.01617872 0.8350962 0.5498037 0.01817709 0.8310208 0.5559979 0.01646101 0.8904486 0.4547019 0.01863652 0.8858721 0.463638 0.01645129 0.9365145 0.3501471 0.01837772 0.9356771 0.3524038 0.01789253 0.9714381 0.236517 0.01917916 0.9755555 0.2185912 0.02256953 0.9909657 0.132165 0.02278935 0.9948968 0.09704148 0.02763152 0.9985198 0.0473392 0.02678042 0.7318216 0.6812298 0.01905578 0.7463092 0.6652144 0.02263897 0.7733829 0.633496 0.02370476 0.7773237 0.6285923 0.02529215 0.8296571 0.5575786 0.02784323 0.8253324 0.5640516 0.02593183 0.8847939 0.4650713 0.02912461 0.879374 0.475398 0.02642536 0.9350247 0.3533511 0.02953028 0.9341449 0.3557148 0.02899056 0.9752556 0.2188659 0.03121501 0.9797378 0.197108 0.03552985 0.9946754 0.0966171 0.03586131 0.740953 0.6710053 0.02721291 0.7697035 0.6376515 0.03093808 0.7759039 0.6300768 0.0312494 0.7830844 0.6209711 0.03426021 0.8233239 0.5663812 0.03674513 0.8203539 0.5707607 0.03538286 0.8776385 0.4777125 0.03926163 0.8727427 0.4867963 0.03673934 0.9331017 0.3572689 0.04099339 0.9325023 0.3588741 0.04060685 0.9793246 0.1974772 0.0438885 0.9155892 -0.4014477 0.023157 0.2002419 -0.9751708 -0.09457904 0.2540876 -0.9600209 -0.1174708 0.2972662 -0.9493147 -0.102149 0.347833 -0.9300891 -0.1180953 0.4005192 -0.9108967 -0.09925562 0.4494464 -0.8864645 -0.1103571 0.5043939 -0.8587455 -0.09023815 0.5540043 -0.8267402 -0.09787738 0.6331727 -0.7710827 -0.06725889 0.6667805 -0.7418537 -0.07111114 0.755502 -0.6542671 -0.03393191 0.7729028 -0.6335046 -0.03596222 0.8484518 -0.5292708 -0.001487374 0.8595134 -0.5111027 -0.003296256 0.9151474 -0.4023801 0.02440434 0.9248099 -0.3798115 0.02167737 0.9598737 -0.2774186 0.04100513 0.9689664 -0.2445611 0.03597265 0.9815188 -0.1863451 0.04354727 0.9884567 -0.145653 0.04169708 0.9921332 -0.11698 0.04458165 0.9961441 -0.07731306 0.04147046 0.9984663 -0.03322136 0.04428774 0.917268 -0.3967613 0.03464102 0.919856 -0.3912196 0.02850091 0.9504353 -0.3073995 0.04667502 0.9596186 -0.2781392 0.04207944 0.9737079 -0.2221365 0.05048155 0.9806318 -0.1896538 0.0489161 0.9875311 -0.1479622 0.05375528 0.9913995 -0.120455 0.05116313 0.995149 -0.08222538 0.0540145 0.9980129 -0.03550565 0.05205428 0.9979867 -0.03642565 0.0519219 0.9980652 0.03108829 0.05384498 0.9978248 0.03065299 0.05836182 0.9843086 0.1666935 0.0578804 0.9780552 0.1700196 0.1204223 0.9803174 0.1613353 0.113793 0.9594087 0.16622 0.227829 0.9649528 0.1499104 0.2153899 0.9308607 0.1535457 0.331545 0.9372437 0.1382505 0.3200954 0.8920177 0.140497 0.4296103 0.8923713 0.139797 0.429104 0.8417174 0.1399881 0.5214551 0.8368736 0.1480618 0.5269919 0.7816553 0.1459679 0.6063897 0.7736364 0.1574192 0.6137639 0.7131739 0.1527368 0.684145 0.7045799 0.1634779 0.6905376 0.6372833 0.1558451 0.7547069 0.6306564 0.1632521 0.7586971 0.5546257 0.1523547 0.8180332 0.5519313 0.1551035 0.8193382 0.4655089 0.1409281 0.873751 0.467782 0.1387457 0.872886 0.3701585 0.1219348 0.9209315 0.3772042 0.1154162 0.9189103 0.2690352 0.09765028 0.9581673 0.279197 0.08827954 0.9561673 0.2841154 0.2239885 0.9322595 0.2713503 0.2382146 0.9325357 0.3793798 0.243026 0.8927539 0.3670749 0.2569389 0.8940014 0.4661526 0.2605543 0.8454664 0.4550897 0.2733122 0.8474632 0.5461894 0.275034 0.7912229 0.5363686 0.2866497 0.7938141 0.6208922 0.2860441 0.7298437 0.6116901 0.2972934 0.7331112 0.6910076 0.2940237 0.6603474 0.6813305 0.3063613 0.6647794 0.7564042 0.3000466 0.5812269 0.7448683 0.3155583 0.5878725 0.8158859 0.305661 0.4908174 0.8010389 0.3269842 0.501416 0.867042 0.3127537 0.3878445 0.8476012 0.3430126 0.4048637 0.9060357 0.3235514 0.2727889 0.8814352 0.3656443 0.2989586 0.9212718 0.3456761 0.1782312 0.9036598 0.3786705 0.2000194 0.9278768 0.3599131 0.09750407 0.9223345 0.3716985 0.1055437 0.9313358 0.3607566 0.04968231 0.9828695 0.1762617 0.05384671 0.9832082 0.1759639 0.04835784 0.9969871 0.06031882 0.0487681 0.9972888 0.06087666 0.04134148 0.9991973 0.003050625 0.03994613 0.9995011 0.005196869 0.03115314 0.9970756 -0.07127487 0.02757078 0.9974599 -0.06512057 0.02886664 0.989342 -0.1417211 0.03343069 0.9768308 -0.2123336 0.02676242 0.9696177 -0.2425341 0.03192025 0.9329848 -0.3595646 0.01590174 0.9254974 -0.3782855 0.01883578 0.8667659 -0.4987047 -0.003239274 0.8587859 -0.5123335 -0.001093327 0.78054 -0.6245071 -0.02735739 0.7680726 -0.6398922 -0.02454584 0.6783908 -0.7328789 -0.05171573 0.6540289 -0.7550599 -0.04616004 0.5683895 -0.8198071 -0.06963998 0.5328304 -0.8440963 -0.05994367 0.4589516 -0.8849865 -0.0785008 0.4242747 -0.9031062 -0.06625849 0.3522812 -0.9321924 -0.08315891 0.3171123 -0.9460019 -0.06723248 0.2530984 -0.9640064 -0.08144342 0.2170718 -0.9742844 -0.06041461 0.1536054 -0.9853642 -0.07391047 0.1742137 -0.9792065 -0.1039445 0.1313578 -0.9881706 -0.07914561 0.1785955 -0.9760001 -0.1246089 0.1258267 -0.9867392 -0.1025354 0.171827 -0.9759915 -0.1338512 0.1590404 -0.97893 -0.128072 0.1530538 -0.9792193 -0.1330571 0.164577 -0.9765594 -0.1387306 0.1851409 -0.975633 -0.1177417 0.1739746 -0.9782218 -0.1132034 0.1993127 -0.9765843 -0.08097934 0.169288 -0.9829741 -0.07144039 0.1916457 -0.9808464 -0.0348199 0.1461752 -0.9889592 -0.02434396 0.1741331 -0.9839515 0.03895229 0.107998 -0.9929291 0.04927927 0.1240303 -0.9861566 0.1100532 0.105906 -0.98688 0.1218677 0.1217342 -0.973479 0.1936994 0.07338029 -0.9774544 0.1979857 0.08304852 -0.9590773 0.2706912 -0.009386837 -0.9614977 0.2746526 0.04635459 -0.9377784 0.3441265 -0.02878201 -0.9084887 0.4169173 0.09788912 -0.9061266 0.4115244 0.1068046 -0.8718981 0.4778981 0.1732981 -0.8654988 0.4699785 0.1871428 -0.8261474 0.5314678 0.2554634 -0.8161092 0.5183668 0.2734001 -0.7715144 0.574472 0.3434053 -0.7575432 0.5551588 0.364039 -0.7088312 0.6041805 0.4353975 -0.690645 0.5774413 0.457467 -0.6385982 0.6188023 0.5296112 -0.6159232 0.5832243 0.5598214 -0.5395156 0.6289062 0.1723338 0.6230919 0.7629269 0.1699188 0.5977802 0.7834452 0.1633931 0.6085368 0.7765215 0.1734544 0.5380971 0.8248425 0.1665786 0.5450924 0.8216605 0.1786851 0.4347779 0.8826324 0.171375 0.4427674 0.8801066 0.1805527 0.323805 0.9287362 0.1718738 0.3335936 0.9269168 0.1785774 0.2063744 0.9620394 0.1670649 0.219102 0.9612928 0.1730901 0.06301397 0.9828882 0.1631896 0.07248538 0.9839284 0.1641397 -0.06973338 0.9839693 0.2696819 -0.0676198 0.9605723 0.2668351 -0.1695591 0.9487091 0.3682482 -0.1674955 0.9145156 0.3610427 -0.267376 0.893397 0.4560807 -0.2582619 0.8516403 0.4410281 -0.3708552 0.8172886 0.5298342 -0.3551509 0.7701581 0.5061466 -0.4648667 0.7264397 0.5885915 -0.4423452 0.6766763 0.5569428 -0.5429217 0.6285307 0.6332009 -0.5142481 0.578451 0.6017323 -0.5898333 0.5385305 0.6031935 -0.5906394 0.5360063 0.5771237 -0.644123 0.5020299 0.5787008 -0.6448085 0.4993269 0.5499996 -0.6964302 0.4609615 0.551714 -0.6969813 0.4580708 0.5203934 -0.7460899 0.4153801 0.5222436 -0.7464733 0.4123583 0.4889568 -0.7916582 0.3663315 0.4908649 -0.791855 0.3633421 0.4554623 -0.8330994 0.3138465 0.457314 -0.8331201 0.3110868 0.4198896 -0.8700301 0.2583419 0.4215517 -0.8699142 0.2560151 0.3818622 -0.9023725 0.1997628 0.4319645 -0.8837143 0.1801552 0.4477983 -0.8804106 0.1560581 0.4821467 -0.8620901 0.155998 0.5347845 -0.835105 0.1288618 0.534788 -0.8351026 0.1288622 0.5882267 -0.8028162 0.09734326 0.5899326 -0.8015868 0.09715038 0.651259 -0.7568364 0.05532252 0.6549063 -0.7537311 0.05465364 0.7171179 -0.696937 0.004567801 0.7230597 -0.6907792 0.002997756 0.7555472 -0.6545045 -0.02779227 0.7657452 -0.6425176 -0.02838265 0.7707494 -0.6362242 -0.03412097 0.8156425 -0.5784448 -0.01136159 0.8505291 -0.5258976 -0.005656719 0.8581232 -0.5134367 0.002711355 0.8902919 -0.4549463 0.02010965 0.8887661 -0.4577806 0.02305835 0.9122105 -0.4081258 0.0361309 0.8868395 -0.4543111 0.08436322 0.8869519 -0.4547041 0.08099687 0.8305973 -0.5323442 0.1634567 0.8308656 -0.5325389 0.1614464 0.7681192 -0.5967432 0.2321432 0.7683103 -0.5968246 0.2313002 0.7082314 -0.6452853 0.286383 0.7080118 -0.645233 0.2870432 0.6470815 -0.6854129 0.3339083 0.6463316 -0.6852446 0.3357014 0.5850545 -0.7187369 0.3756709 0.5837336 -0.7184631 0.3782406 -6.42195e-6 1.03126e-4 -1 -6.29124e-6 1.03279e-4 -1 -8.91708e-6 1.02989e-4 -1 -3.4699e-6 1.03029e-4 -1 -6.22602e-6 1.02944e-4 -1 -1.69752e-5 1.00765e-4 -1 2.80842e-6 1.03168e-4 -1 -7.3675e-6 1.03308e-4 -1 -4.14266e-6 1.03564e-4 -1 -4.85313e-6 1.03448e-4 -1 -4.74615e-5 1.02289e-4 -1 -6.45996e-6 1.02915e-4 -1 -5.41151e-6 1.03609e-4 -1 -5.57455e-6 9.79003e-5 -1 -6.27297e-6 1.04099e-4 -1 -6.48798e-6 1.0302e-4 -1 -7.00617e-6 1.03126e-4 -1 -1.23837e-5 1.0333e-4 -1 0 1.05551e-4 -1 0 1.0328e-4 -1 -5.83606e-6 1.03303e-4 -1 -8.55682e-6 1.03275e-4 -1 -1.04364e-5 1.02757e-4 -1 0 1.03827e-4 -1 -1.59166e-5 1.02941e-4 -1 0 1.0257e-4 -1 -6.47359e-6 1.03988e-4 -1 -1.05326e-5 1.03502e-4 -1 -2.06512e-5 1.01489e-4 -1 2.0414e-5 1.04836e-4 -1 -6.40575e-6 1.02362e-4 -1 -6.48288e-6 1.02779e-4 -1 -6.34914e-6 1.05285e-4 -1 5.00507e-5 1.00879e-4 -1 -7.21103e-6 1.03281e-4 -1 -1.0274e-4 9.59197e-5 -1 2.9571e-6 1.03502e-4 -1 -8.54556e-6 1.03577e-4 -1 -4.75181e-6 1.03227e-4 -1 0 1.03305e-4 -1 -8.19067e-6 1.03283e-4 -1 -6.70132e-6 1.00315e-4 -1 -6.44394e-6 1.05765e-4 -1 -6.45425e-6 1.02831e-4 -1 -1.23664e-5 1.05607e-4 -1 -4.16174e-6 1.04411e-4 -1 -8.84011e-6 1.04479e-4 -1 -6.21742e-6 1.03359e-4 -1 -6.6695e-6 1.03493e-4 -1 -1.23664e-5 1.00015e-4 -1 -5.7417e-6 1.03119e-4 -1 -4.50524e-6 1.03364e-4 -1 -7.49444e-6 1.03185e-4 -1 -4.16171e-6 1.0498e-4 -1 -1.29576e-5 1.03474e-4 -1 -3.14663e-7 1.03526e-4 -1 -6.28568e-6 9.8916e-5 -1 7.0661e-6 1.03431e-4 -1 -1.47726e-5 1.03264e-4 -1 -5.84623e-6 1.01779e-4 -1 0 1.02825e-4 -1 -7.88059e-6 1.01517e-4 -1 0 1.06041e-4 -1 -2.78685e-6 1.02861e-4 -1 -6.07734e-6 1.03195e-4 -1 -4.22213e-6 1.01876e-4 -1 -7.79776e-6 1.02555e-4 -1 -1.17041e-5 1.05437e-4 -1 -5.80684e-6 1.03121e-4 -1 -4.0243e-6 1.03325e-4 -1 -6.65087e-6 1.03344e-4 -1 -8.28097e-6 1.03229e-4 -1 1.47696e-6 1.03096e-4 -1 -2.27562e-5 1.03066e-4 -1 -6.61775e-6 1.0325e-4 -1 -1.22342e-5 1.03205e-4 -1 1.21652e-6 1.03174e-4 -1 -4.60577e-6 1.03626e-4 -1 -9.03375e-6 1.03212e-4 -1 -5.56944e-6 1.03218e-4 -1 -5.24313e-6 1.03229e-4 -1 0 1.04843e-4 -1 -1.86059e-5 1.03125e-4 -1 0 1.03919e-4 -1 -7.39016e-6 1.03222e-4 -1 -4.9792e-6 1.03289e-4 -1 -9.51707e-6 1.0326e-4 -1 -5.37455e-6 1.03263e-4 -1 -6.93449e-6 1.033e-4 -1 -1.03112e-5 1.03065e-4 -1 0.9120343 0.4100539 -0.007028996 0.963255 0.2685887 -1.48899e-4 0.9832348 0.1823443 1.01679e-4 0.7311611 0.6821876 -0.004857778 0.8252468 0.5647681 0.002242565 0.8719782 0.4895378 0.002591907 0.9483014 0.3173663 0.001812875 0.9483029 0.3173586 0.002279043 0.9594941 0.2816954 0.004358649 0.9594914 0.2817168 0.003451347 0.9660302 0.2583405 0.006776154 0.9660266 0.2583865 0.005397558 0.9809347 0.1941507 0.008533954 0.9809257 0.1942979 0.005754232 0.9829972 0.1832757 0.01125741 0.9829936 0.1834859 0.007531821 0.9903954 0.1376975 0.01250344 0.7964834 0.6046451 0.004309237 0.7964932 0.6045907 0.008297562 0.8202984 0.5718364 0.01066344 0.8203085 0.5717701 0.01314878 0.8337112 0.551954 0.01650387 0.8337177 0.5518576 0.01918697 0.8632233 0.5043434 0.02198553 0.8632275 0.5042775 0.0232926 0.8672697 0.4970859 0.02737039 0.8672695 0.4970343 0.02829569 0.8826103 0.4690304 0.03177338 0.8874384 0.4575592 0.05561292 0.8825684 0.4678136 0.04715335 0.9909025 0.1280466 0.04142892 0.9900966 0.1358298 0.03548204 0.987623 0.1270952 0.09191071 0.9878588 0.1232358 0.09459471 0.8865803 0.4573006 0.06965476 0.8864389 0.4464961 0.1219322 0.8920117 0.4416232 0.09635525 0.893828 0.4407015 0.08278834 0.9754439 0.1365925 0.1727764 0.9607016 0.1406232 0.2393273 0.9607758 0.1472707 0.2349922 0.9387181 0.1508457 0.3099257 0.9390802 0.1547559 0.306886 0.9106663 0.1575015 0.3819426 0.9109035 0.1612165 0.379821 0.8717219 0.1635376 0.4619053 0.8719658 0.1658943 0.4606025 0.8259966 0.1677542 0.5381339 0.8262343 0.1694417 0.5372397 0.781453 0.1711242 0.6000397 0.7818102 0.1722975 0.5992382 0.7328373 0.1740132 0.6577758 0.733276 0.1760336 0.6567485 0.7003802 0.1776603 0.6913064 0.6727877 0.17309 0.7193028 0.6686202 0.1819134 0.7210095 0.6040719 0.1852536 0.7750989 0.6053512 0.1896319 0.7730392 0.5415471 0.193687 0.8180539 0.5435656 0.1980254 0.8156729 0.4761467 0.2024934 0.8557341 0.4788513 0.2101655 0.8523684 0.397275 0.216039 0.8919081 0.4010094 0.2258827 0.8877885 0.3144372 0.2319568 0.9205027 0.3190031 0.2433391 0.9159821 0.2514558 0.2477122 0.9356328 0.2564514 0.2529422 0.9328736 0.1875976 0.2565266 0.9481568 0.1921181 0.2667804 0.9444146 0.09932196 0.270322 0.9576332 0.1024286 0.2770379 0.955384 0.02741724 0.2784413 0.9600619 0.02843654 0.2797616 0.9596483 0.9828698 0.1259895 0.1345128 0.9807763 0.1159666 0.1569386 0.886992 0.4455275 0.121452 0.8705319 0.4502184 0.1986897 0.8694385 0.4534724 0.1960598 0.8487761 0.4569034 0.2661177 0.8483935 0.4585327 0.2645304 0.8222397 0.4609421 0.3338478 0.8220453 0.461727 0.3332413 0.7864772 0.4638461 0.4077997 0.786611 0.4631406 0.408343 0.7458041 0.4647946 0.4772236 0.746033 0.4629434 0.4786629 0.7071606 0.4645022 0.5330681 0.7070488 0.4626888 0.5347906 0.6654906 0.4640523 0.5846176 0.6655005 0.4611572 0.5868927 0.6132743 0.4634145 0.6396418 0.6130845 0.4604625 0.6419516 0.5564982 0.4634117 0.6896082 0.5561954 0.4610538 0.6914305 0.5031494 0.4644837 0.7287631 0.5029271 0.4638068 0.7293474 0.446094 0.467477 0.7631944 0.4465377 0.4693245 0.7617997 0.3752754 0.4744163 0.7963023 0.3771888 0.4808946 0.791498 0.2985507 0.4863703 0.8211647 0.3023954 0.4976564 0.8129547 0.2387951 0.5019309 0.8312896 0.2447571 0.5080271 0.8258343 0.1784417 0.5113028 0.8406712 0.18401 0.5245251 0.8312724 0.09446573 0.5279515 0.8440044 0.09896016 0.5373315 0.8375452 0.02609586 0.5388643 0.8419884 0.02774238 0.5407697 0.8407132 -0.03500401 0.2797023 0.9594485 -0.03630089 0.277558 0.9600228 -0.1140857 0.2758961 0.954393 -0.1177021 0.2682486 0.9561323 -0.2017441 0.2647874 0.9429672 -0.2068867 0.2536774 0.9449052 -0.2883281 0.2489839 0.924594 -0.2938068 0.2367352 0.9260854 -0.3621781 0.2321656 0.9027326 -0.3670898 0.2236225 0.9029054 -0.4328165 0.2187941 0.874528 -0.4370335 0.2093651 0.8747388 -0.510014 0.2041904 0.835579 -0.5131911 0.1970847 0.8353399 -0.5832794 0.1925557 0.7891182 -0.5855515 0.1874738 0.7886591 -0.6431796 0.1843782 0.7431855 -0.6447355 0.1816736 0.7425032 -0.6828976 0.1798899 0.7080188 -0.7020677 0.1554005 0.6949473 -0.7139726 0.1759874 0.6776958 -0.758069 0.1740798 0.6285123 -0.7588533 0.1722739 0.6280632 -0.7920794 0.1712661 0.5858995 -0.8142746 0.1535502 0.559803 -0.8180285 0.168598 0.5499129 -0.843124 0.1677462 0.5108849 -0.843681 0.1671957 0.5101453 -0.8715856 0.1658809 0.4613265 -0.8724918 0.1634573 0.4604778 -0.9104362 0.1612107 0.3809422 -0.9117296 0.1573438 0.379463 -0.9345314 0.1552301 0.3202417 -0.9464042 0.1296913 0.2958028 -0.9493171 0.1474357 0.2775966 -0.9596236 0.1455776 0.2406859 -0.960896 0.1431282 0.2370512 -0.9727786 0.1400762 0.184609 -0.9748106 0.1309451 0.1805483 -0.8818565 0.4484516 0.145672 -0.8698846 0.4517471 0.1980541 -0.8688284 0.4529534 0.1999264 -0.8537174 0.4552856 0.2527483 -0.852042 0.4579136 0.2536527 -0.8227074 0.4608809 0.3327782 -0.822137 0.4617204 0.3330239 -0.7864775 0.4638274 0.4078204 -0.7869857 0.4631096 0.4076558 -0.7606528 0.464557 0.4534249 -0.7612757 0.4641077 0.4528393 -0.7328689 0.4648171 0.4968384 -0.7344221 0.4626531 0.4965646 -0.6862611 0.4643706 0.5598264 -0.6882799 0.4615712 0.5596633 -0.635818 0.4636665 0.6170485 -0.6379902 0.460591 0.6171097 -0.5888184 0.4631173 0.6624314 -0.5906033 0.460941 0.6623603 -0.5383653 0.4636582 0.7036931 -0.5397393 0.4615688 0.704014 -0.4763205 0.4656565 0.7458438 -0.4761497 0.4659295 0.7457823 -0.4098769 0.4706225 0.7813549 -0.4071121 0.4751601 0.7800529 -0.3473505 0.4796243 0.8057966 -0.3422064 0.4866166 0.8038029 -0.2804115 0.4906736 0.8249902 -0.2726803 0.5038479 0.8196235 -0.1990739 0.5080983 0.8379773 -0.1907858 0.5222176 0.8311977 -0.1140983 0.5253674 0.8431909 -0.1079691 0.535987 0.8372938 -0.03542488 0.5375954 0.8424585 -0.03325903 0.5406768 0.8405728 -0.8928272 0.4418412 0.08738559 -0.8927574 0.440634 0.09394723 -0.884463 0.443916 0.14375 -0.9896597 0.1346155 0.04952085 -0.991106 0.1256788 0.04374581 -0.986067 0.1257383 0.1089121 -0.9860339 0.1259109 0.1090127 -0.8879031 0.4534021 0.07781153 -0.8899394 0.4532541 0.05068165 -0.8823952 0.4667382 0.0594514 -0.6874812 0.7261868 0.004742145 -0.7491031 0.6624423 0.003837883 -0.9700889 0.24275 4.1711e-4 -0.9226829 0.3855571 0.001446187 -0.8849241 0.4657285 0.00249356 -0.84003 0.5425328 0.002835929 -0.7965027 0.604635 -1.71586e-4 -0.796531 0.6044971 0.01103609 -0.820309 0.5718659 0.007912456 -0.8203446 0.5716195 0.01690989 -0.8337175 0.5520437 0.01276242 -0.8337419 0.5516539 0.02350425 -0.8632164 0.5045199 0.0178132 -0.863249 0.5040194 0.02766942 -0.8672716 0.4973016 0.02304518 -0.8672668 0.4967385 0.03315627 -0.8825822 0.4693751 0.02712452 -0.9483137 0.3173241 -0.002562284 -0.9483346 0.3172357 0.0048092 -0.9595074 0.2816775 0.001826286 -0.9595246 0.281531 0.007265985 -0.9660357 0.2583917 0.002988219 -0.9660558 0.2581211 0.01048219 -0.9809282 0.1943371 0.003623843 -0.9809486 0.1939164 0.01167786 -0.9829965 0.1835449 0.005406618 -0.9829965 0.1830462 0.01455974 -0.9903876 0.1381999 0.005783379 -0.1406592 0.1372715 -0.9804956 -0.1406568 0.13727 -0.9804962 -0.6306327 0.542618 -0.5548586 -0.5695049 0.5554658 -0.6059061 -0.3997499 0.3899354 -0.8295484 -0.5234679 0.3458948 -0.7786773 -0.3185016 0.3107066 -0.8955547 -0.702354 0.6849804 -0.1936512 -0.7023493 0.6849854 -0.1936504 -0.6429991 0.6271207 -0.4396269 -0.1693633 0.09969049 -0.9804989 -0.169355 0.09969073 -0.9805003 -0.4813227 0.2831295 -0.8295579 -0.4813236 0.2831329 -0.8295562 -0.7183343 0.4224854 -0.5527224 -0.7183374 0.4224827 -0.5527204 -0.8456692 0.4973288 -0.1936694 -0.8456675 0.4973314 -0.19367 -0.1882428 0.05634397 -0.9805051 -0.1882501 0.05634492 -0.9805036 -0.5350032 0.1599338 -0.8295738 -0.5350135 0.1599322 -0.8295675 -0.7984599 0.2386172 -0.5527421 -0.7984625 0.2386143 -0.5527394 -0.9399998 0.2808624 -0.1936922 -0.9399986 0.2808684 -0.19369 -0.6146457 0.7643177 -0.1950107 -0.6146487 0.7643166 -0.1950056 -0.5620692 0.6989524 -0.4422034 -0.5620616 0.6989498 -0.4422174 -0.4971861 0.6182987 -0.6086976 -0.4971893 0.6182989 -0.6086948 -0.3815118 0.4744718 -0.7933002 -0.3815101 0.4744725 -0.7933007 -0.2771793 0.3447533 -0.8968371 -0.2771899 0.3447535 -0.8968337 -0.1222684 0.1521289 -0.9807687 -0.1222668 0.1521289 -0.9807689 -0.6748871 0.7121086 -0.1934651 -0.572371 0.6040519 -0.5545384 -0.382537 0.4038012 -0.8310297 -0.134359 0.1418817 -0.9807228 -0.674257 0.7126908 -0.1935184 -0.7353719 0.6495964 -0.1930098 -0.7347223 0.6502349 -0.193333 -0.8244906 0.5318236 -0.1933369 -0.8239018 0.5326089 -0.1936848 -0.8683585 0.4563275 -0.1942132 -0.8678623 0.4572439 -0.1942754 -0.9054255 0.3777009 -0.1937696 -0.9049538 0.3786427 -0.1941348 -0.9517821 0.237528 -0.1941424 -0.9514489 0.2385544 -0.194517 -0.5719674 0.6043994 -0.5545762 -0.624107 0.5514616 -0.5535167 -0.6236197 0.5518083 -0.5537202 -0.6996995 0.45147 -0.5537107 -0.699241 0.451915 -0.5539268 -0.736308 0.3870677 -0.5550038 -0.7359604 0.3876639 -0.5550487 -0.7682984 0.3206515 -0.5539858 -0.7679109 0.3211909 -0.5542106 -0.8075748 0.2016879 -0.5542067 -0.8072608 0.2023038 -0.5544396 -0.3823189 0.4039669 -0.8310493 -0.4175451 0.3690502 -0.8303361 -0.4172658 0.3691801 -0.8304188 -0.4681027 0.3021444 -0.8304149 -0.4678248 0.3023294 -0.830504 -0.4920591 0.2587847 -0.831209 -0.4918769 0.2590457 -0.8312355 -0.5139691 0.2146031 -0.8305307 -0.5137155 0.2148517 -0.8306234 -0.5402214 0.1350193 -0.8306207 -0.5400086 0.1353009 -0.8307132 -0.1342985 0.1419323 -0.9807239 -0.146761 0.1297721 -0.9806225 -0.1466732 0.1297989 -0.9806321 -0.1645293 0.1062576 -0.9806323 -0.1644334 0.1062981 -0.9806439 -0.1728063 0.09093272 -0.9807494 -0.1727681 0.09101325 -0.9807487 -0.1806381 0.07548451 -0.9806488 -0.1805539 0.07554757 -0.9806594 -0.1898621 0.04751145 -0.9806606 -0.1897791 0.04758757 -0.980673 -0.1924975 0.9617447 -0.1949151 -0.03751444 0.4420723 -0.8961946 -0.1093519 0.1624829 -0.9806333 -0.08041971 0.178587 -0.9806322 -0.08042353 0.1785866 -0.9806319 -0.04919683 0.189585 -0.9806311 -0.04919332 0.1895855 -0.9806312 -0.01655888 0.1951642 -0.9806308 -0.01656144 0.1951652 -0.9806306 -0.06718093 0.7916254 -0.6073023 -0.05160015 0.6080332 -0.7922331 -0.06932634 0.5516936 -0.8311607 -0.139946 0.5391656 -0.8304911 -0.139948 0.5391663 -0.8304904 -0.2287876 0.5078747 -0.8304936 -0.2287914 0.5078735 -0.8304933 -0.1093482 0.1624829 -0.9806336 -0.2477591 0.3680195 -0.8962015 -0.2916702 0.4733793 -0.8311682 -0.3407958 0.5061729 -0.7922419 -0.4437171 0.6590021 -0.6073149 -0.09097629 0.8269959 -0.5547984 -0.209154 0.805742 -0.5541069 -0.2091544 0.8057405 -0.554109 -0.3419297 0.758975 -0.5541128 -0.3419352 0.7589737 -0.5541113 -0.4473447 0.7014768 -0.5548091 -0.5012997 0.7444934 -0.4409403 -0.08294802 0.9774252 -0.1943187 -0.08295017 0.9774256 -0.1943153 -0.07589638 0.8943283 -0.4409273 -0.269517 0.9295653 -0.2515331 -0.2464705 0.9494695 -0.1943196 -0.3775195 0.9053028 -0.1946949 -0.3994593 0.8866239 -0.2330891 -0.4526979 0.8700972 -0.1949244 -0.5478923 0.8136648 -0.1943288 -0.5478921 0.8136649 -0.1943287 -0.0358473 -0.9618043 -0.2713809 -0.06000798 -0.9594972 -0.2752531 -0.1337543 0.1424314 -0.9807258 -0.3808091 0.4054124 -0.8310385 -0.5697341 0.6065188 -0.5545613 -0.7594333 -0.6186299 -0.2013908 -0.7982623 -0.5677409 -0.2011159 -0.7973953 -0.570308 -0.1972551 -0.8549663 -0.4797199 -0.1972346 -0.8544313 -0.4820386 -0.1938714 -0.9026312 -0.3842872 -0.1938566 -0.9024041 -0.3861243 -0.1912455 -0.9312893 -0.3099124 -0.1914541 -0.9310463 -0.3112217 -0.1905095 -0.9536897 -0.2329543 -0.1902848 -0.9537221 -0.2338303 -0.1890443 -0.9702535 -0.1509926 -0.1892336 -0.9702531 -0.1513051 -0.1889859 -0.9796419 -0.06827306 -0.1887877 -0.9795894 -0.06802976 -0.1891473 -0.9818254 0.01302415 -0.1893393 -0.9816879 0.01384067 -0.1899931 -0.977324 0.09391689 -0.1897832 -0.9769635 0.09482377 -0.191183 -0.9661415 0.1730957 -0.1913336 -0.9658937 0.1738218 -0.1919255 -0.9487141 0.2513583 -0.1917305 -0.94849 0.2517195 -0.192364 -0.9166619 0.3503267 -0.1923593 -0.9166251 0.3503754 -0.1924466 -0.8778689 0.4385131 -0.1924904 -0.8779166 0.4384587 -0.1923965 -0.8309782 0.5219987 -0.1923347 -0.8310039 0.5219749 -0.1922885 -0.7744551 0.602696 -0.192294 -0.7743541 0.6027649 -0.1924845 -0.7119601 0.6753244 -0.1924833 -0.711624 0.675506 -0.1930878 -0.6721351 0.7147553 -0.1932853 -0.6717112 0.7151022 -0.1934761 -0.4960607 -0.8417891 -0.2128733 -0.5750092 -0.7899607 -0.2129009 -0.5738179 -0.7916576 -0.2097886 -0.6486697 -0.7315936 -0.2097581 -0.6474167 -0.7337511 -0.2060604 -0.701695 -0.6819729 -0.2062456 -0.7156457 -0.6615671 -0.2240093 -0.7369185 -0.6450555 -0.2021248 -0.760977 -0.6164736 -0.2021743 -0.1338523 0.1423913 -0.9807183 -0.1418443 0.1347162 -0.9806793 -0.1419544 0.1347348 -0.9806607 -0.1544014 0.1202735 -0.9806603 -0.15443 0.1202753 -0.9806556 -0.1657127 0.1042024 -0.9806535 -0.1657109 0.1042022 -0.9806538 -0.1750269 0.08752208 -0.9806659 -0.1750113 0.08752399 -0.9806685 -0.1827863 0.06997108 -0.9806596 -0.182808 0.06996506 -0.980656 -0.1891704 0.05026322 -0.9806571 -0.1892734 0.05022329 -0.9806392 -0.1925238 0.03471022 -0.9806783 -0.1926382 0.03459399 -0.9806599 -0.1949482 0.01900476 -0.9806295 -0.1951932 0.01885247 -0.9805837 -0.195865 0.002803325 -0.980627 -0.1959639 0.002666056 -0.9806075 -0.1957164 -0.0135104 -0.9805675 -0.1957649 -0.01355546 -0.9805573 -0.1937054 -0.03007894 -0.9805986 -0.1936799 -0.03002786 -0.9806051 -0.190583 -0.04655045 -0.9805667 -0.1904513 -0.04638016 -0.9806004 -0.1857461 -0.06186962 -0.9806481 -0.1856904 -0.06162875 -0.9806738 -0.1801574 -0.07682389 -0.9806331 -0.1799379 -0.07642078 -0.980705 -0.1703722 -0.09580492 -0.9807114 -0.1701453 -0.09525603 -0.9808043 -0.1587467 -0.1131788 -0.9808109 -0.1585481 -0.1125262 -0.9809182 -0.1507161 -0.1223781 -0.9809731 -0.1509059 -0.121981 -0.9809934 -0.1428383 -0.1316872 -0.9809463 -0.1427004 -0.1309839 -0.9810606 -0.128315 -0.1450453 -0.9810695 -0.1282517 -0.1444023 -0.9811725 -0.1134886 -0.1562212 -0.9811806 -0.1134828 -0.1556766 -0.9812678 -0.09798401 -0.1658843 -0.9812653 -0.09798967 -0.1652908 -0.9813649 -0.0823062 -0.1735739 -0.9813755 -0.08237236 -0.173011 -0.9814693 -0.06773406 -0.1792128 -0.9814759 -0.06783473 -0.1786682 -0.9815682 -0.05400121 -0.1832993 -0.9815729 -0.05412149 -0.1828079 -0.9816579 -0.0413677 -0.1860817 -0.9816631 -0.04155254 -0.1854789 -0.9817694 -0.02989643 -0.1876912 -0.981773 -0.03030943 -0.1864761 -0.9819918 -0.01963323 -0.1878762 -0.9819965 -0.02078974 -0.1838116 -0.9827417 -0.3810293 0.4052844 -0.8310001 -0.4037185 0.3832933 -0.8307212 -0.4040092 0.3833264 -0.8305645 -0.4394469 0.3421397 -0.8305583 -0.4395405 0.3421403 -0.8305085 -0.471649 0.2963584 -0.8304932 -0.4716442 0.2963586 -0.8304958 -0.4981857 0.2489037 -0.8305769 -0.4981511 0.248914 -0.8305945 -0.5202357 0.1989421 -0.8305281 -0.5202914 0.1989249 -0.8304973 -0.5383785 0.1429147 -0.8304963 -0.5386447 0.1427962 -0.8303441 -0.5480396 0.09868377 -0.8306107 -0.5483298 0.09835898 -0.8304578 -0.5547937 0.05394327 -0.8302374 -0.5554051 0.05351752 -0.829856 -0.5574882 0.007885456 -0.8301474 -0.5577355 0.007503211 -0.8299849 -0.5568634 -0.03861373 -0.8297061 -0.5569862 -0.0387333 -0.8296182 -0.5512822 -0.08586364 -0.8298889 -0.5512126 -0.08571165 -0.8299508 -0.5422203 -0.1327849 -0.8296779 -0.5418812 -0.1323095 -0.8299754 -0.5286452 -0.1765165 -0.8302869 -0.5285171 -0.1758308 -0.830514 -0.5125748 -0.2190875 -0.8302216 -0.5120317 -0.2179656 -0.8308517 -0.4847847 -0.2732145 -0.8308657 -0.4842324 -0.2716948 -0.8316855 -0.4517549 -0.3227728 -0.8317063 -0.4513036 -0.3209816 -0.832644 -0.429138 -0.3492063 -0.8330039 -0.4296897 -0.3480775 -0.8331919 -0.4065699 -0.3755891 -0.8328469 -0.406287 -0.373665 -0.8338499 -0.3653429 -0.4137164 -0.8338844 -0.3652578 -0.411974 -0.834784 -0.3232392 -0.4456356 -0.8348206 -0.3232886 -0.4441717 -0.8355813 -0.2790939 -0.4732556 -0.8355453 -0.2791923 -0.4716704 -0.8364082 -0.2344707 -0.495327 -0.8364656 -0.2347195 -0.4938221 -0.8372853 -0.1929722 -0.5115342 -0.8373139 -0.1933147 -0.5100927 -0.838114 -0.1538547 -0.5233123 -0.8381367 -0.1542506 -0.522023 -0.8388677 -0.1177771 -0.5313997 -0.838894 -0.118359 -0.5298129 -0.8398152 -0.08477807 -0.5361932 -0.8398271 -0.08606463 -0.5330128 -0.8417187 -0.05454456 -0.537148 -0.8417227 -0.05822485 -0.5265441 -0.8481518 -0.5700728 0.6063084 -0.5544431 -0.603772 0.5731522 -0.554036 -0.6041431 0.5731287 -0.5536559 -0.6571159 0.5115413 -0.5536465 -0.6572326 0.5115209 -0.5535266 -0.7052339 0.4430329 -0.5535043 -0.7052184 0.4430388 -0.5535194 -0.7449851 0.3721253 -0.5536425 -0.7449364 0.3721494 -0.553692 -0.7778813 0.2973836 -0.5535916 -0.7779378 0.2973529 -0.5535289 -0.8049637 0.2136389 -0.5535268 -0.8052839 0.2134218 -0.5531448 -0.8196532 0.1475194 -0.5535404 -0.8199995 0.1469971 -0.5531662 -0.8293852 0.08053225 -0.5528424 -0.8300449 0.07987397 -0.5519472 -0.833512 0.01174706 -0.5523765 -0.8337855 0.01114726 -0.551976 -0.8321329 -0.05775892 -0.5515605 -0.8322651 -0.0579518 -0.5513406 -0.8240639 -0.1284358 -0.5517454 -0.8239988 -0.1282128 -0.5518946 -0.8102089 -0.1985459 -0.55149 -0.8098736 -0.1978255 -0.5522408 -0.790428 -0.2640874 -0.552704 -0.7903764 -0.2630443 -0.5532746 -0.7661699 -0.3276618 -0.5528306 -0.7657104 -0.3260605 -0.5544115 -0.7249264 -0.4087679 -0.5544281 -0.7245571 -0.4066417 -0.5564707 -0.6759064 -0.4831753 -0.5565001 -0.675731 -0.4807139 -0.5588397 -0.6428052 -0.5233468 -0.5593833 -0.6437823 -0.5216419 -0.559852 -0.6087598 -0.5626384 -0.5593296 -0.6088404 -0.5600569 -0.5618272 -0.547429 -0.6201735 -0.5618776 -0.547719 -0.6178767 -0.564121 -0.4846723 -0.6684315 -0.5641739 -0.4850746 -0.66654 -0.5660627 -0.4186642 -0.7101821 -0.5660051 -0.4191416 -0.708185 -0.5681501 -0.351949 -0.7438025 -0.5682339 -0.3526027 -0.7419285 -0.570275 -0.2898097 -0.7686021 -0.5703166 -0.2905741 -0.7668275 -0.5723132 -0.231186 -0.7867475 -0.5723474 -0.2319769 -0.7851828 -0.574173 -0.1770218 -0.7993385 -0.5742136 -0.1781162 -0.7974368 -0.5765147 -0.1273394 -0.8070927 -0.5765293 -0.1296823 -0.8033086 -0.5812726 -0.08144801 -0.8096255 -0.5812685 -0.08817017 -0.7970691 -0.597417 -0.09239602 -0.9598165 -0.2649816 -0.1067472 -0.9583426 -0.2649235 -0.09623497 -0.9665035 -0.2379286 -0.1550256 -0.9588301 -0.2379326 -0.1513345 -0.9613432 -0.2300375 -0.2122538 -0.9497556 -0.2300277 -0.2104513 -0.9510739 -0.2262049 -0.2760741 -0.9341434 -0.2261838 -0.2746879 -0.9352784 -0.2231612 -0.3454958 -0.9115051 -0.2231397 -0.3440374 -0.9128571 -0.2198418 -0.3871942 -0.8953654 -0.2200037 -0.4162622 -0.8799726 -0.2288535 -0.4248343 -0.8789971 -0.2165181 -0.4973464 -0.8401303 -0.216397 -0.08139538 -0.9572666 -0.2775165 -0.07964491 -0.9574932 -0.2772426 -0.07488638 -0.792755 -0.6049228 -0.06707483 -0.7990499 -0.5975117 -0.04938942 -0.5226106 -0.8511399 -0.04485982 -0.5277584 -0.8482092 -0.01772928 -0.1822533 -0.9830918 -0.01625144 -0.1842134 -0.982752 -0.07125174 -0.9587249 -0.275263 -0.07855427 -0.957503 -0.2775198 -0.05938917 -0.7950682 -0.6036055 -0.06465721 -0.7936399 -0.6049424 -0.03910183 -0.524319 -0.8506237 -0.0423398 -0.5232125 -0.8511499 -0.01327705 -0.1829479 -0.983033 -0.01439452 -0.1825349 -0.9830941 -0.04888015 -0.9612258 -0.271396 -0.06375735 -0.9593595 -0.2748897 -0.04382586 -0.7978174 -0.6013043 -0.05224472 -0.7955737 -0.6036 -0.02876114 -0.5264636 -0.8497112 -0.03405058 -0.5246809 -0.8506178 -0.009412705 -0.1837526 -0.9829275 -0.01125824 -0.1830935 -0.983031 -0.02048695 -0.9630761 -0.2684492 -0.03313797 -0.9618194 -0.2716715 -0.02121454 -0.8000701 -0.5995313 -0.02715408 -0.7985812 -0.6012742 -0.01387578 -0.5282102 -0.8490003 -0.01769256 -0.5269857 -0.8496901 -0.004373192 -0.1843827 -0.9828449 -0.005729556 -0.1839303 -0.9829226 -0.004590392 -0.9633237 -0.2683029 -0.006254613 -0.9632713 -0.2684574 -0.00386089 -0.8003836 -0.599476 -0.005123734 -0.8003062 -0.5995697 -0.002485156 -0.5284081 -0.8489869 -0.00329113 -0.5283433 -0.8490246 -7.6929e-4 -0.1844459 -0.9828424 -0.001088857 -0.1844195 -0.9828471 -6.11047e-6 0.1951917 -0.9807652 -6.416e-6 0.1951918 -0.9807651 -5.69589e-6 0.4423806 -0.8968274 -5.69586e-6 0.4423778 -0.8968288 -5.02315e-6 0.6088447 -0.7932894 -5.02313e-6 0.6088431 -0.7932907 -3.88151e-6 0.793416 -0.6086797 -3.88153e-6 0.7934201 -0.6086745 -2.84793e-6 0.8969154 -0.4422022 -2.73404e-6 0.8969174 -0.4421982 -1.29847e-6 0.9808053 -0.1949898 -1.06933e-6 0.980806 -0.1949866 0.7915059 -0.2599118 -0.5531402 0.529461 -0.1737655 -0.8303472 0.007511377 -0.1844392 -0.9828153 0.02268522 -0.5282754 -0.84877 0.03453212 -0.7999116 -0.5991235 0.01627135 -0.9632072 -0.2682672 0.04162943 -0.9599031 -0.277224 0.07827949 -0.9582529 -0.2749977 0.05934321 -0.9596103 -0.2750028 0.04463529 -0.9601172 -0.2760123 0.2975607 -0.9277141 -0.2253981 0.2236898 -0.9482348 -0.2254192 0.221682 -0.9477274 -0.2294995 0.1617649 -0.9597569 -0.2295623 0.1580029 -0.9587253 -0.2363919 0.1118037 -0.9651998 -0.2364093 0.1026948 -0.9604762 -0.2587263 0.09337967 -0.9614198 -0.2587516 0.07859331 -0.9577275 -0.2767332 0.0889123 -0.956823 -0.2767388 0.08263903 -0.9571016 -0.2777183 0.08145612 -0.9572566 -0.2775332 0.07057106 -0.9581254 -0.2775167 0.00591439 -0.1835009 -0.9830018 0.01432549 -0.1829109 -0.9830251 0.01313614 -0.1826387 -0.9830924 0.01596421 -0.1824005 -0.9830947 0.01635497 -0.1824818 -0.9830733 0.01615917 -0.1824986 -0.9830734 0.01853746 -0.1849151 -0.9825797 0.02043205 -0.1847431 -0.9825745 0.02211791 -0.1878041 -0.9819574 0.03104466 -0.1865647 -0.9819521 0.03174197 -0.1874395 -0.9817633 0.04346215 -0.1851396 -0.9817507 0.04387557 -0.1856506 -0.9816359 0.05841481 -0.18163 -0.9816305 0.05883276 -0.1820451 -0.9815286 0.07438349 -0.1762931 -0.9815233 0.07486814 -0.1766825 -0.9814164 0.08546233 -0.1716215 -0.9814491 0.08580148 -0.1716462 -0.9814152 0.09595674 -0.1663798 -0.9813818 0.09647154 -0.1666486 -0.9812856 0.1116036 -0.1569513 -0.9812803 0.1121315 -0.1571577 -0.9811871 0.1272943 -0.1452023 -0.9811792 0.1279371 -0.1453726 -0.9810703 0.01822388 -0.5258003 -0.8504129 0.04220157 -0.5241921 -0.8505537 0.03871595 -0.523506 -0.851142 0.04537886 -0.5229502 -0.8511546 0.0465359 -0.5231499 -0.8509693 0.04420328 -0.5233559 -0.8509669 0.05114245 -0.5295489 -0.8467364 0.0572288 -0.5289798 -0.8467026 0.0620163 -0.5368596 -0.8413893 0.08818084 -0.5332168 -0.8413703 0.09016513 -0.5354567 -0.8397359 0.1238397 -0.5288031 -0.8396613 0.1250022 -0.530101 -0.83867 0.1664911 -0.518612 -0.8386432 0.1676501 -0.5196598 -0.8377632 0.2119882 -0.5032477 -0.8377367 0.2133155 -0.5042183 -0.8368157 0.2435651 -0.4899235 -0.837049 0.2445243 -0.4899497 -0.836754 0.2734398 -0.4748142 -0.8365297 0.2748315 -0.4754655 -0.8357034 0.3179642 -0.447816 -0.8356791 0.3194044 -0.4482989 -0.8348706 0.3625522 -0.4142548 -0.8348346 0.3643003 -0.4146318 -0.8338861 0.02768373 -0.7971016 -0.6032103 0.06445109 -0.7948035 -0.6034348 0.05881416 -0.7941032 -0.6049305 0.06867122 -0.7932978 -0.6049488 0.07054328 -0.7934901 -0.6044809 0.06608802 -0.7938786 -0.6044743 0.07719719 -0.8009001 -0.5938012 0.08604949 -0.8000358 -0.5937492 0.09334909 -0.8089631 -0.5804007 0.13265 -0.803472 -0.5803765 0.1356706 -0.8059166 -0.5762745 0.186268 -0.7958312 -0.5761572 0.1879748 -0.7972089 -0.573693 0.2502758 -0.7799273 -0.5736511 0.251936 -0.7809998 -0.571461 0.3184778 -0.7563387 -0.5714225 0.3203444 -0.7572757 -0.5691335 0.3657932 -0.7361235 -0.569489 0.3672565 -0.7359706 -0.5687443 0.4104868 -0.7130295 -0.5684096 0.4124086 -0.7135598 -0.5663495 0.4770565 -0.6720895 -0.5663151 0.4790046 -0.6723923 -0.5643079 0.5436084 -0.6213722 -0.5642575 0.5459445 -0.621469 -0.5618905 0.7012204 -0.6824453 -0.2062972 0.645892 -0.7350811 -0.2061051 0.6436174 -0.7359719 -0.210005 0.5673479 -0.7962425 -0.2100341 0.5653713 -0.7967692 -0.2133408 0.4889575 -0.8458118 -0.2133613 0.4869285 -0.8461214 -0.2167469 0.4359569 -0.8734319 -0.2169292 0.4341366 -0.8740303 -0.2181661 0.4074026 -0.886807 -0.2181661 0.3766971 -0.8947671 -0.2397732 0.3657394 -0.9038876 -0.2218601 0.2994499 -0.9279807 -0.2217692 0.7333734 -0.6489436 -0.2025731 0.7121846 -0.6664043 -0.2206771 0.6064727 -0.5647084 -0.5597279 0.6040439 -0.5650597 -0.5619953 0.4049033 -0.3769479 -0.8330449 0.4030786 -0.3768961 -0.8339526 0.1422269 -0.1321533 -0.9809725 0.1415584 -0.1321026 -0.981076 0.7809161 -0.592312 -0.1983345 0.778695 -0.5938765 -0.2023484 0.6615508 -0.5018976 -0.5571799 0.6590894 -0.5024269 -0.5596146 0.4420164 -0.3352741 -0.8319934 0.4401276 -0.3353465 -0.8329648 0.1553041 -0.1175598 -0.9808468 0.1546028 -0.1175549 -0.9809581 0.166939 -0.1004378 -0.9808383 0.1675641 -0.1003703 -0.9807386 0.4751451 -0.2864894 -0.8319621 0.4768393 -0.2862298 -0.8310817 0.7110559 -0.4289442 -0.5571413 0.7132048 -0.4282191 -0.554948 0.839151 -0.5064579 -0.1983081 0.8947438 -0.381358 -0.2323787 0.8787593 -0.4356563 -0.1948997 0.8409807 -0.5048212 -0.1946974 0.1860664 -0.06092035 -0.9806468 0.18638 -0.06080418 -0.9805945 0.1919471 -0.04001116 -0.9805894 0.1920911 -0.03994005 -0.980564 0.194554 -0.02373516 -0.9806046 0.1945727 -0.02372187 -0.9806013 0.1960868 -0.007486283 -0.980558 0.1959791 -0.007559061 -0.980579 0.19569 0.01160305 -0.9805973 0.195555 0.01145857 -0.9806258 0.1944664 0.02201598 -0.9806622 0.1944515 0.02187967 -0.9806681 0.1929658 0.03403079 -0.9806153 0.1928387 0.03389084 -0.980645 0.1880912 0.05435723 -0.9806462 0.1880323 0.05428266 -0.9806616 0.1813751 0.0735343 -0.980661 0.1813656 0.07352203 -0.9806636 0.1728401 0.09184718 -0.9806581 0.1728479 0.0918585 -0.9806558 0.1626253 0.1089182 -0.9806579 0.1626186 0.1089062 -0.9806604 0.1513582 0.1240883 -0.9806594 0.1513458 0.1240414 -0.9806672 0.1389614 0.1377687 -0.980668 0.1389375 0.1376428 -0.9806889 0.5303004 -0.1734131 -0.8298851 0.5461632 -0.1141543 -0.8298643 0.5465453 -0.113942 -0.8296418 0.5537488 -0.06777137 -0.8299214 0.5537744 -0.06773287 -0.8299075 0.5579184 -0.02144151 -0.8296188 0.5576656 -0.02164709 -0.8297835 0.5569074 0.0330066 -0.8299186 0.5565529 0.03257799 -0.8301732 0.5535994 0.06263744 -0.8304242 0.5535653 0.06220352 -0.8304795 0.5491251 0.09677082 -0.8301187 0.5487954 0.09637498 -0.8303829 0.5353149 0.1545326 -0.830396 0.5351794 0.1543307 -0.830521 0.5162526 0.2090767 -0.830524 0.5162349 0.2090499 -0.8305419 0.4919611 0.2611929 -0.8305135 0.4919761 0.2612277 -0.8304936 0.4628955 0.309789 -0.8305171 0.4628891 0.3097659 -0.8305293 0.4308122 0.3530072 -0.8305341 0.4307855 0.3528823 -0.8306011 0.3955233 0.3919798 -0.8306101 0.3954769 0.3916483 -0.8307887 0.7925288 -0.2592552 -0.5519827 0.8162123 -0.1707123 -0.5519556 0.816673 -0.1703438 -0.5513876 0.827785 -0.1013862 -0.5518087 0.8278226 -0.1013268 -0.5517634 0.8336647 -0.03208822 -0.5513381 0.8333787 -0.03241831 -0.5517509 0.8324163 0.04935497 -0.5519486 0.8320186 0.04867023 -0.5526086 0.8279161 0.09365677 -0.5529769 0.8279017 0.092965 -0.5531152 0.8208187 0.144643 -0.5525714 0.8204692 0.1440286 -0.5532504 0.8003423 0.2309707 -0.5532675 0.8002136 0.2306843 -0.553573 0.7719295 0.3125348 -0.5535765 0.7719216 0.3124998 -0.5536073 0.7355986 0.3904572 -0.5535684 0.7356136 0.3905128 -0.5535092 0.6921691 0.4631289 -0.5535464 0.6921668 0.4631121 -0.5535635 0.6442064 0.5277895 -0.5535671 0.6441996 0.5276243 -0.5537324 0.5914726 0.5861084 -0.5537482 0.5914944 0.585679 -0.5541793 0.1776697 -0.08125895 -0.9807296 0.178175 -0.08115112 -0.9806468 0.5056226 -0.2317681 -0.8310411 0.5069537 -0.2314158 -0.8303281 0.7561875 -0.3468093 -0.5548908 0.7578414 -0.3460466 -0.5531079 0.8920233 -0.4093212 -0.1917046 0.9324156 -0.3063331 -0.1917321 0.9331676 -0.305229 -0.1898254 0.9610071 -0.2010952 -0.1898055 0.9613116 -0.2005186 -0.1888708 0.9746736 -0.1194429 -0.1890634 0.9747003 -0.1193389 -0.1889911 0.9812914 -0.03779572 -0.1887827 0.9811452 -0.03823882 -0.1894521 0.9801483 0.05817186 -0.18954 0.9799878 0.05723017 -0.1906535 0.9754025 0.1103391 -0.1908278 0.9754585 0.1094463 -0.1910558 0.9667316 0.170377 -0.1907922 0.9666433 0.1696028 -0.1919265 0.9429379 0.2720872 -0.1919288 0.9429348 0.2717539 -0.1924161 0.9096118 0.3682162 -0.1924143 0.9096161 0.3681912 -0.1924421 0.8668013 0.4600333 -0.192419 0.8667883 0.4601035 -0.1923097 0.8156331 0.5456687 -0.1923236 0.8156369 0.5456618 -0.1923278 0.7591149 0.6218965 -0.1923266 0.7591779 0.6217367 -0.1925944 0.6970301 0.6906924 -0.1925957 0.6972373 0.6902881 -0.193294 0.452695 0.8700978 -0.1949284 0.247742 0.3680157 -0.8962078 0.01654881 0.1951655 -0.9806307 0.04918128 0.1895859 -0.9806317 0.04918235 0.1895849 -0.9806318 0.08041125 0.1785859 -0.9806331 0.0804091 0.1785877 -0.9806329 0.1093404 0.1624845 -0.9806342 0.1093387 0.1624823 -0.9806348 0.4437116 0.6590012 -0.60732 0.3407888 0.5061734 -0.7922447 0.291661 0.4733799 -0.8311711 0.2287771 0.5078722 -0.830498 0.2287777 0.5078747 -0.8304963 0.1399366 0.539168 -0.8304912 0.1399351 0.5391645 -0.8304938 0.01654732 0.195165 -0.9806309 0.03750175 0.4420677 -0.8961974 0.06931602 0.5516943 -0.8311611 0.05158871 0.6080322 -0.7922346 0.0671724 0.7916269 -0.6073012 0.4473372 0.7014771 -0.5548147 0.3419272 0.7589754 -0.5541138 0.3419256 0.7589744 -0.5541163 0.2091476 0.8057422 -0.5541092 0.2091466 0.8057433 -0.5541078 0.09097087 0.8269959 -0.5547994 0.07589155 0.8943309 -0.4409225 0.5478909 0.813664 -0.1943362 0.547888 0.8136655 -0.1943386 0.5012925 0.7444955 -0.4409449 0.3725059 0.8932897 -0.251541 0.4029423 0.8943561 -0.1943319 0.273141 0.9420655 -0.1946966 0.2443366 0.9412591 -0.2330904 0.1924924 0.9617452 -0.1949179 0.08294671 0.9774261 -0.1943145 0.08294588 0.977425 -0.1943204 0.9644603 0.178228 -0.1950668 0.8176391 0.1511679 -0.555531 0.546323 0.101154 -0.8314441 0.1918507 0.0355786 -0.9807791 0.964302 0.1791643 -0.194992 0.9450262 0.2628744 -0.1944808 0.9448112 0.2639217 -0.1941065 0.8949476 0.401744 -0.1940894 0.8945832 0.4027335 -0.1937178 0.8556648 0.479705 -0.1942186 0.8551914 0.4805714 -0.1941621 0.8099454 0.5536143 -0.1936481 0.8094537 0.5544556 -0.1932969 0.7177206 0.6689679 -0.1932855 0.7171605 0.6696614 -0.1929628 0.8175483 0.1518675 -0.5554739 0.8017433 0.223163 -0.5544421 0.8017137 0.2238528 -0.5542068 0.7593274 0.3410207 -0.5541903 0.7591999 0.3416778 -0.5539602 0.7255529 0.4068573 -0.5550138 0.7252426 0.4074495 -0.5549848 0.6872696 0.4699193 -0.5539281 0.6870416 0.4705067 -0.5537122 0.6090685 0.5678526 -0.5536959 0.6087812 0.5683543 -0.5534969 0.5462941 0.101483 -0.831423 0.536274 0.1493705 -0.8307218 0.536319 0.14973 -0.830628 0.5079329 0.2282164 -0.8306152 0.5079237 0.2285721 -0.8305229 0.4848411 0.2720137 -0.8312265 0.4847123 0.2722991 -0.8312083 0.4597516 0.3144603 -0.8305078 0.4596866 0.3147816 -0.8304222 0.4074636 0.3799983 -0.8304064 0.4073586 0.3802806 -0.8303287 0.1918472 0.03566986 -0.9807764 0.1884558 0.05255407 -0.9806745 0.188486 0.05265957 -0.9806631 0.1785037 0.08026725 -0.9806598 0.178516 0.08037203 -0.980649 0.1702758 0.09558868 -0.9807492 0.1702399 0.09567129 -0.9807474 0.1615735 0.1105775 -0.980646 0.1615743 0.1106795 -0.9806344 0.143204 0.1336156 -0.9806323 0.1431859 0.1337082 -0.9806222 0.614645 0.7643168 -0.1950163 0.6146474 0.7643154 -0.1950143 0.5620551 0.6989515 -0.4422227 0.5620593 0.6989529 -0.4422152 0.4971821 0.6183009 -0.6086986 0.4971807 0.6182979 -0.6087028 0.3815019 0.4744731 -0.7933044 0.3814982 0.474471 -0.7933073 0.2771705 0.3447537 -0.8968398 0.2771717 0.3447538 -0.8968394 0.1222542 0.1521296 -0.9807704 0.1222558 0.1521288 -0.9807703 0.1406348 0.1372753 -0.9804986 0.1406443 0.1372711 -0.9804978 0.3184865 0.310714 -0.8955575 0.4440162 0.3340258 -0.8314303 0.188231 0.05636608 -0.980506 0.1882262 0.05636096 -0.9805072 0.5349829 0.1599854 -0.829577 0.534982 0.159988 -0.829577 0.7984274 0.2387034 -0.5527517 0.7984271 0.2387033 -0.5527522 0.9399658 0.2809694 -0.1937022 0.939965 0.2809714 -0.1937031 0.1693359 0.09969854 -0.9805028 0.1693389 0.09970349 -0.9805018 0.4812924 0.2831652 -0.8295633 0.4812909 0.283163 -0.8295649 0.7182984 0.4225323 -0.552733 0.7183009 0.4225322 -0.55273 0.8456354 0.4973824 -0.1936792 0.8456335 0.4973849 -0.1936807 0.4378082 0.4270718 -0.7911596 0.5694851 0.5554781 -0.6059134 0.6306207 0.5426238 -0.5548667 0.6429775 0.6271322 -0.4396421 0.7023327 0.6849992 -0.1936619 0.7023369 0.6849956 -0.1936594 + + + + + + + + + + + + + + +

0 0 1 0 2 0 2 1 1 1 3 1 4 2 5 2 6 2 6 3 5 3 7 3 6 4 7 4 8 4 9 5 10 5 11 5 9 6 11 6 12 6 12 7 11 7 2 7 12 8 2 8 6 8 6 9 2 9 3 9 6 10 3 10 4 10 13 11 14 11 15 11 13 12 15 12 16 12 17 13 18 13 19 13 19 14 20 14 17 14 17 15 20 15 21 15 17 16 21 16 16 16 16 17 15 17 17 17 17 18 15 18 22 18 17 19 22 19 23 19 23 20 22 20 24 20 23 21 24 21 25 21 26 22 27 22 28 22 29 23 30 23 31 23 31 24 32 24 29 24 29 25 32 25 33 25 29 26 33 26 28 26 28 27 33 27 34 27 28 28 34 28 26 28 35 29 36 29 37 29 35 30 37 30 38 30 38 31 37 31 39 31 38 32 39 32 29 32 29 33 39 33 40 33 29 34 40 34 30 34 41 35 42 35 43 35 43 36 44 36 41 36 41 37 44 37 45 37 41 38 45 38 46 38 46 39 45 39 47 39 46 40 47 40 35 40 35 41 47 41 48 41 35 42 48 42 36 42 49 43 50 43 51 43 51 44 52 44 49 44 49 45 52 45 53 45 49 46 53 46 54 46 42 47 41 47 54 47 54 48 41 48 55 48 54 49 55 49 49 49 9 50 56 50 57 50 57 51 58 51 9 51 9 52 58 52 59 52 9 53 59 53 10 53 60 54 50 54 49 54 60 55 49 55 61 55 62 56 63 56 49 56 49 57 63 57 64 57 49 58 64 58 61 58 49 59 65 59 62 59 59 60 65 60 10 60 10 61 65 61 49 61 66 62 67 62 25 62 68 63 24 63 69 63 69 64 24 64 70 64 68 65 71 65 24 65 24 66 71 66 72 66 24 67 72 67 25 67 25 68 72 68 73 68 25 69 73 69 66 69 74 70 75 70 76 70 77 71 69 71 70 71 77 72 70 72 78 72 76 73 75 73 79 73 79 74 75 74 80 74 79 75 80 75 70 75 70 76 80 76 81 76 70 77 81 77 78 77 82 78 83 78 84 78 82 79 84 79 85 79 85 80 84 80 86 80 85 81 86 81 87 81 87 82 86 82 28 82 87 83 28 83 27 83 83 84 88 84 84 84 84 85 88 85 89 85 84 86 89 86 90 86 90 87 89 87 91 87 90 88 91 88 76 88 76 89 91 89 92 89 76 90 92 90 74 90 93 91 94 91 95 91 96 92 97 92 98 92 99 93 100 93 101 93 101 94 100 94 102 94 101 95 102 95 103 95 96 96 98 96 103 96 104 97 105 97 106 97 106 98 105 98 107 98 106 99 107 99 99 99 108 100 109 100 110 100 110 101 109 101 111 101 110 102 111 102 112 102 112 103 111 103 113 103 112 104 113 104 114 104 115 105 116 105 117 105 117 106 116 106 118 106 117 107 118 107 113 107 113 108 118 108 119 108 113 109 119 109 114 109 120 110 121 110 122 110 122 111 121 111 123 111 122 112 123 112 124 112 124 113 123 113 115 113 124 114 115 114 125 114 125 115 115 115 117 115 120 116 122 116 126 116 126 117 122 117 127 117 126 118 127 118 128 118 95 119 94 119 129 119 129 120 94 120 130 120 129 121 130 121 131 121 131 122 130 122 132 122 132 123 130 123 133 123 132 124 133 124 134 124 135 125 136 125 137 125 135 126 137 126 138 126 139 127 140 127 141 127 141 128 140 128 142 128 141 129 142 129 135 129 135 130 142 130 143 130 135 131 143 131 136 131 144 132 145 132 146 132 139 133 141 133 147 133 147 134 141 134 148 134 147 135 148 135 145 135 145 136 148 136 149 136 145 137 149 137 146 137 150 138 151 138 152 138 150 139 153 139 151 139 151 140 153 140 154 140 151 141 154 141 155 141 154 142 156 142 155 142 155 143 156 143 157 143 155 144 157 144 158 144 158 145 157 145 159 145 158 146 159 146 146 146 146 147 159 147 160 147 146 148 160 148 144 148 161 149 162 149 163 149 163 150 162 150 164 150 164 151 165 151 163 151 163 152 165 152 166 152 163 153 166 153 167 153 167 154 166 154 168 154 167 155 168 155 169 155 170 156 171 156 172 156 172 157 171 157 173 157 172 158 173 158 161 158 174 159 175 159 176 159 174 160 176 160 17 160 17 161 176 161 177 161 17 162 177 162 18 162 178 163 163 163 179 163 179 164 180 164 178 164 178 165 180 165 181 165 178 166 181 166 174 166 174 167 181 167 182 167 174 168 182 168 175 168 169 169 150 169 167 169 167 170 150 170 152 170 167 171 152 171 163 171 163 172 152 172 183 172 163 173 183 173 179 173 184 174 185 174 135 174 135 175 185 175 186 175 135 176 186 176 141 176 141 177 186 177 187 177 141 178 187 178 148 178 148 179 187 179 188 179 148 180 188 180 149 180 184 181 135 181 189 181 189 182 135 182 138 182 189 183 138 183 190 183 190 184 138 184 191 184 190 185 191 185 192 185 127 186 193 186 194 186 194 187 193 187 195 187 194 188 195 188 191 188 191 189 195 189 196 189 191 190 196 190 192 190 125 191 197 191 124 191 124 192 197 192 198 192 124 193 198 193 122 193 122 194 198 194 199 194 122 195 199 195 127 195 127 196 199 196 200 196 127 197 200 197 193 197 201 198 202 198 106 198 106 199 202 199 203 199 106 200 203 200 104 200 104 201 203 201 204 201 108 202 205 202 109 202 109 203 205 203 204 203 109 204 204 204 206 204 206 205 204 205 203 205 206 206 203 206 207 206 207 207 203 207 202 207 201 208 106 208 208 208 208 209 106 209 209 209 208 210 209 210 210 210 211 211 212 211 213 211 211 212 213 212 209 212 209 213 213 213 214 213 209 214 214 214 210 214 212 215 211 215 215 215 215 216 211 216 6 216 215 217 6 217 8 217 170 218 172 218 216 218 216 219 172 219 217 219 216 220 217 220 218 220 218 221 217 221 219 221 218 222 219 222 220 222 220 223 219 223 23 223 220 224 23 224 25 224 103 225 98 225 101 225 101 226 98 226 221 226 101 227 221 227 222 227 222 228 221 228 223 228 222 229 223 229 224 229 224 230 223 230 9 230 224 231 9 231 12 231 161 232 163 232 172 232 172 233 163 233 178 233 172 234 178 234 217 234 217 235 178 235 174 235 217 236 174 236 219 236 219 237 174 237 17 237 219 238 17 238 23 238 128 239 127 239 93 239 93 240 127 240 194 240 93 241 194 241 94 241 94 242 194 242 191 242 94 243 191 243 130 243 130 244 191 244 138 244 130 245 138 245 133 245 133 246 138 246 137 246 133 247 137 247 134 247 99 248 101 248 106 248 106 249 101 249 222 249 106 250 222 250 209 250 209 251 222 251 224 251 209 252 224 252 211 252 211 253 224 253 12 253 211 254 12 254 6 254 225 255 226 255 227 255 227 256 226 256 228 256 227 257 228 257 229 257 229 258 228 258 230 258 229 259 230 259 231 259 232 260 56 260 9 260 233 261 221 261 234 261 234 262 221 262 98 262 234 263 98 263 97 263 233 264 235 264 236 264 232 265 9 265 237 265 237 266 9 266 238 266 238 267 9 267 223 267 238 268 223 268 239 268 236 269 240 269 233 269 233 270 240 270 241 270 233 271 241 271 221 271 221 272 241 272 242 272 221 273 242 273 223 273 223 274 242 274 243 274 223 275 243 275 239 275 244 276 245 276 246 276 246 277 245 277 247 277 246 278 247 278 248 278 218 279 249 279 250 279 250 280 245 280 218 280 218 281 245 281 244 281 218 282 244 282 216 282 216 283 244 283 170 283 220 284 25 284 67 284 67 285 251 285 220 285 220 286 251 286 252 286 220 287 252 287 218 287 218 288 252 288 253 288 218 289 253 289 249 289 254 290 255 290 256 290 256 291 255 291 257 291 256 292 257 292 258 292 258 293 257 293 259 293 259 294 257 294 260 294 259 295 260 295 261 295 261 296 260 296 262 296 261 297 262 297 263 297 263 298 262 298 264 298 263 299 264 299 265 299 266 300 267 300 268 300 268 301 267 301 269 301 268 302 269 302 270 302 270 303 269 303 271 303 270 304 271 304 272 304 272 305 271 305 273 305 273 306 271 306 274 306 273 307 274 307 275 307 275 308 274 308 276 308 275 309 276 309 277 309 278 310 279 310 280 310 280 311 279 311 281 311 280 312 281 312 282 312 282 313 283 313 280 313 280 314 283 314 284 314 280 315 284 315 285 315 285 316 286 316 280 316 280 317 286 317 287 317 280 318 287 318 235 318 233 319 288 319 235 319 235 320 288 320 289 320 235 321 289 321 290 321 290 322 291 322 235 322 235 323 291 323 292 323 235 324 292 324 293 324 293 325 294 325 235 325 235 326 294 326 295 326 295 327 296 327 235 327 235 328 296 328 297 328 235 329 297 329 298 329 298 330 299 330 235 330 235 331 299 331 300 331 235 332 300 332 280 332 301 333 302 333 303 333 303 334 302 334 304 334 301 335 305 335 302 335 302 336 305 336 306 336 302 337 306 337 280 337 280 338 306 338 307 338 280 339 307 339 278 339 308 340 309 340 310 340 310 341 309 341 311 341 310 342 311 342 312 342 302 343 313 343 304 343 304 344 313 344 314 344 304 345 314 345 315 345 315 346 314 346 316 346 315 347 316 347 317 347 317 348 316 348 318 348 317 349 318 349 308 349 308 350 318 350 319 350 308 351 319 351 309 351 320 352 321 352 322 352 322 353 321 353 323 353 322 354 323 354 324 354 312 355 311 355 325 355 325 356 311 356 326 356 325 357 326 357 327 357 327 358 326 358 328 358 327 359 328 359 320 359 320 360 328 360 329 360 320 361 329 361 321 361 330 362 331 362 332 362 323 363 333 363 324 363 324 364 333 364 334 364 324 365 334 365 335 365 335 366 334 366 330 366 335 367 330 367 336 367 336 368 330 368 332 368 337 369 246 369 248 369 338 370 339 370 340 370 341 371 342 371 343 371 343 372 342 372 344 372 345 373 346 373 340 373 340 374 347 374 345 374 345 375 347 375 348 375 341 376 338 376 342 376 342 377 338 377 340 377 342 378 340 378 349 378 349 379 340 379 346 379 337 380 248 380 350 380 348 381 347 381 351 381 351 382 347 382 352 382 351 383 352 383 248 383 248 384 352 384 353 384 248 385 353 385 350 385 344 386 342 386 354 386 354 387 342 387 355 387 354 388 355 388 356 388 356 389 357 389 354 389 354 390 357 390 358 390 354 391 358 391 359 391 359 392 360 392 354 392 354 393 360 393 361 393 354 394 361 394 362 394 362 395 363 395 354 395 354 396 363 396 364 396 354 397 364 397 330 397 330 398 364 398 365 398 330 399 365 399 331 399 366 400 367 400 368 400 369 401 370 401 371 401 366 402 368 402 372 402 372 403 368 403 373 403 372 404 373 404 371 404 371 405 373 405 374 405 371 406 374 406 369 406 375 407 376 407 377 407 378 408 379 408 380 408 378 409 380 409 381 409 381 410 380 410 382 410 381 411 382 411 383 411 383 412 382 412 384 412 383 413 384 413 385 413 375 414 377 414 386 414 386 415 377 415 387 415 386 416 387 416 379 416 379 417 387 417 388 417 379 418 388 418 380 418 389 419 390 419 391 419 390 420 392 420 391 420 391 421 392 421 393 421 391 422 393 422 394 422 394 423 395 423 391 423 391 424 395 424 396 424 391 425 396 425 397 425 398 426 399 426 400 426 400 427 399 427 401 427 400 428 401 428 391 428 391 429 401 429 402 429 391 430 402 430 389 430 403 431 404 431 405 431 405 432 404 432 406 432 405 433 406 433 407 433 407 434 406 434 376 434 407 435 376 435 375 435 398 436 400 436 408 436 408 437 400 437 409 437 408 438 409 438 410 438 410 439 409 439 411 439 410 440 411 440 412 440 412 441 411 441 413 441 412 442 413 442 403 442 403 443 413 443 414 443 403 444 414 444 404 444 231 445 230 445 415 445 415 446 230 446 416 446 415 447 416 447 417 447 417 448 416 448 418 448 417 449 418 449 419 449 419 450 418 450 420 450 419 451 420 451 421 451 421 452 420 452 422 452 421 453 422 453 423 453 423 454 422 454 424 454 423 455 424 455 425 455 425 456 424 456 426 456 427 457 428 457 426 457 426 458 428 458 429 458 426 459 429 459 425 459 430 460 431 460 432 460 432 461 431 461 433 461 432 462 433 462 427 462 427 463 433 463 434 463 427 464 434 464 428 464 432 465 435 465 436 465 436 466 437 466 432 466 432 467 437 467 438 467 432 468 438 468 439 468 439 469 440 469 432 469 432 470 440 470 441 470 432 471 441 471 430 471 442 472 443 472 444 472 442 473 294 473 445 473 445 474 446 474 442 474 442 475 446 475 447 475 442 476 447 476 443 476 444 477 448 477 442 477 442 478 448 478 449 478 442 479 449 479 450 479 451 480 452 480 453 480 453 481 452 481 454 481 454 482 452 482 455 482 455 483 452 483 456 483 455 484 456 484 450 484 450 485 456 485 296 485 450 486 296 486 442 486 442 487 296 487 295 487 442 488 295 488 294 488 457 489 347 489 458 489 459 490 457 490 460 490 460 491 457 491 458 491 460 492 458 492 461 492 462 493 463 493 458 493 458 494 463 494 464 494 458 495 464 495 461 495 347 496 340 496 458 496 458 497 340 497 339 497 458 498 339 498 462 498 462 499 339 499 465 499 466 500 467 500 468 500 468 501 469 501 466 501 466 502 469 502 470 502 466 503 470 503 465 503 465 504 470 504 471 504 465 505 471 505 462 505 472 506 435 506 432 506 473 507 474 507 475 507 475 508 474 508 472 508 476 509 477 509 473 509 477 510 476 510 296 510 472 511 432 511 475 511 475 512 432 512 427 512 475 513 427 513 478 513 478 514 427 514 426 514 478 515 426 515 479 515 479 516 426 516 424 516 479 517 424 517 422 517 420 518 480 518 422 518 422 519 480 519 481 519 422 520 481 520 479 520 420 521 418 521 480 521 480 522 418 522 416 522 480 523 416 523 482 523 482 524 416 524 230 524 482 525 230 525 483 525 473 526 475 526 476 526 476 527 475 527 478 527 476 528 478 528 484 528 484 529 478 529 479 529 484 530 479 530 485 530 485 531 479 531 481 531 485 532 481 532 486 532 486 533 481 533 480 533 486 534 480 534 487 534 487 535 480 535 482 535 487 536 482 536 488 536 488 537 482 537 483 537 488 538 483 538 489 538 296 539 476 539 297 539 297 540 476 540 484 540 297 541 484 541 298 541 298 542 484 542 485 542 298 543 485 543 299 543 299 544 485 544 486 544 299 545 486 545 300 545 300 546 486 546 487 546 300 547 487 547 280 547 280 548 487 548 488 548 280 549 488 549 302 549 302 550 488 550 489 550 302 551 489 551 313 551 490 552 413 552 411 552 491 553 492 553 493 553 492 554 339 554 338 554 494 555 495 555 491 555 391 556 397 556 496 556 409 557 400 557 497 557 497 558 400 558 391 558 497 559 391 559 494 559 494 560 391 560 496 560 494 561 496 561 495 561 409 562 497 562 411 562 411 563 497 563 498 563 411 564 498 564 490 564 492 565 338 565 493 565 493 566 338 566 341 566 493 567 341 567 499 567 499 568 341 568 343 568 499 569 343 569 500 569 500 570 343 570 344 570 500 571 344 571 501 571 501 572 344 572 354 572 501 573 354 573 502 573 502 574 354 574 330 574 502 575 330 575 503 575 503 576 330 576 334 576 503 577 334 577 504 577 491 578 493 578 494 578 494 579 493 579 499 579 494 580 499 580 497 580 497 581 499 581 500 581 497 582 500 582 498 582 498 583 500 583 501 583 498 584 501 584 490 584 490 585 501 585 502 585 490 586 502 586 505 586 505 587 502 587 503 587 505 588 503 588 506 588 506 589 503 589 504 589 506 590 504 590 507 590 413 591 490 591 414 591 414 592 490 592 505 592 414 593 505 593 404 593 404 594 505 594 506 594 404 595 506 595 406 595 406 596 506 596 507 596 406 597 507 597 376 597 316 598 314 598 508 598 507 599 504 599 509 599 510 600 377 600 511 600 511 601 377 601 376 601 511 602 376 602 507 602 382 603 380 603 512 603 512 604 380 604 388 604 512 605 388 605 510 605 510 606 388 606 387 606 510 607 387 607 377 607 328 608 513 608 329 608 329 609 513 609 514 609 329 610 514 610 321 610 321 611 514 611 515 611 321 612 515 612 323 612 323 613 515 613 509 613 323 614 509 614 333 614 333 615 509 615 504 615 333 616 504 616 334 616 326 617 516 617 328 617 328 618 516 618 517 618 328 619 517 619 513 619 326 620 311 620 516 620 516 621 311 621 309 621 516 622 309 622 518 622 518 623 309 623 319 623 518 624 319 624 519 624 507 625 509 625 511 625 511 626 509 626 515 626 511 627 515 627 510 627 510 628 515 628 514 628 510 629 514 629 512 629 512 630 514 630 513 630 512 631 513 631 520 631 520 632 513 632 517 632 520 633 517 633 521 633 521 634 517 634 516 634 521 635 516 635 522 635 522 636 516 636 518 636 522 637 518 637 523 637 523 638 518 638 519 638 523 639 519 639 524 639 524 640 525 640 523 640 523 641 525 641 526 641 523 642 526 642 522 642 522 643 526 643 527 643 522 644 527 644 521 644 521 645 527 645 528 645 521 646 528 646 520 646 520 647 528 647 385 647 520 648 385 648 512 648 512 649 385 649 384 649 512 650 384 650 382 650 226 651 225 651 524 651 524 652 225 652 529 652 524 653 529 653 525 653 316 654 508 654 318 654 530 655 531 655 508 655 508 656 531 656 532 656 508 657 532 657 318 657 483 658 530 658 489 658 489 659 530 659 508 659 489 660 508 660 313 660 313 661 508 661 314 661 319 662 318 662 519 662 519 663 318 663 532 663 519 664 532 664 524 664 524 665 532 665 531 665 524 666 531 666 226 666 226 667 531 667 530 667 226 668 530 668 228 668 228 669 530 669 483 669 228 670 483 670 230 670 533 671 449 671 448 671 288 672 233 672 234 672 447 673 289 673 443 673 443 674 289 674 288 674 292 675 291 675 447 675 447 676 291 676 290 676 447 677 290 677 289 677 294 678 293 678 445 678 445 679 293 679 292 679 445 680 292 680 446 680 446 681 292 681 447 681 97 682 533 682 234 682 234 683 533 683 448 683 234 684 448 684 288 684 288 685 448 685 444 685 288 686 444 686 443 686 534 687 535 687 536 687 536 688 535 688 451 688 536 689 451 689 537 689 533 690 97 690 96 690 451 691 453 691 537 691 537 692 453 692 454 692 537 693 454 693 538 693 538 694 454 694 455 694 538 695 455 695 539 695 539 696 455 696 450 696 539 697 450 697 540 697 540 698 450 698 449 698 540 699 449 699 533 699 533 700 96 700 540 700 540 701 96 701 103 701 540 702 103 702 539 702 539 703 103 703 102 703 539 704 102 704 538 704 538 705 102 705 100 705 538 706 100 706 537 706 537 707 100 707 99 707 537 708 99 708 536 708 541 709 534 709 542 709 542 710 534 710 536 710 542 711 536 711 107 711 107 712 536 712 99 712 543 713 541 713 544 713 544 714 541 714 542 714 544 715 542 715 105 715 105 716 542 716 107 716 545 717 543 717 544 717 545 718 544 718 546 718 205 719 547 719 548 719 205 720 548 720 204 720 204 721 548 721 549 721 204 722 549 722 104 722 105 723 104 723 544 723 544 724 104 724 549 724 544 725 549 725 546 725 546 726 549 726 548 726 546 727 548 727 550 727 550 728 548 728 547 728 550 729 547 729 551 729 108 730 110 730 552 730 552 731 110 731 112 731 552 732 112 732 114 732 551 733 547 733 553 733 553 734 547 734 554 734 553 735 554 735 555 735 556 736 555 736 552 736 552 737 555 737 554 737 552 738 554 738 108 738 108 739 554 739 547 739 108 740 547 740 205 740 118 741 116 741 557 741 118 742 557 742 119 742 558 743 556 743 559 743 559 744 556 744 552 744 559 745 552 745 560 745 561 746 558 746 562 746 562 747 558 747 559 747 562 748 559 748 557 748 557 749 559 749 560 749 557 750 560 750 119 750 119 751 560 751 552 751 119 752 552 752 114 752 562 753 563 753 561 753 561 754 563 754 564 754 565 755 566 755 567 755 121 756 120 756 568 756 568 757 120 757 569 757 123 758 121 758 570 758 570 759 121 759 568 759 570 760 568 760 571 760 571 761 568 761 569 761 571 762 569 762 572 762 565 763 567 763 573 763 573 764 567 764 574 764 573 765 574 765 575 765 575 766 574 766 576 766 575 767 576 767 577 767 115 768 123 768 577 768 577 769 123 769 570 769 577 770 570 770 575 770 575 771 570 771 571 771 575 772 571 772 573 772 573 773 571 773 572 773 573 774 572 774 565 774 116 775 115 775 557 775 557 776 115 776 577 776 557 777 577 777 562 777 562 778 577 778 576 778 562 779 576 779 563 779 563 780 576 780 574 780 563 781 574 781 564 781 564 782 574 782 567 782 572 783 569 783 578 783 579 784 580 784 581 784 582 785 583 785 367 785 367 786 583 786 584 786 367 787 584 787 585 787 585 788 584 788 586 788 585 789 586 789 587 789 580 790 579 790 586 790 586 791 579 791 588 791 586 792 588 792 587 792 589 793 590 793 591 793 592 794 589 794 593 794 142 795 140 795 594 795 594 796 140 796 592 796 592 797 593 797 594 797 594 798 593 798 595 798 594 799 595 799 142 799 137 800 136 800 595 800 595 801 136 801 143 801 595 802 143 802 142 802 367 803 366 803 582 803 582 804 366 804 372 804 582 805 372 805 596 805 596 806 372 806 371 806 596 807 371 807 597 807 597 808 371 808 370 808 597 809 370 809 598 809 598 810 370 810 599 810 598 811 599 811 600 811 600 812 599 812 601 812 600 813 601 813 602 813 602 814 601 814 603 814 602 815 603 815 604 815 604 816 603 816 605 816 605 817 566 817 604 817 604 818 566 818 606 818 604 819 606 819 602 819 602 820 606 820 607 820 602 821 607 821 600 821 600 822 607 822 608 822 600 823 608 823 598 823 598 824 608 824 609 824 598 825 609 825 597 825 597 826 609 826 610 826 597 827 610 827 596 827 596 828 610 828 611 828 596 829 611 829 582 829 582 830 611 830 612 830 582 831 612 831 583 831 583 832 612 832 613 832 583 833 613 833 584 833 584 834 613 834 614 834 584 835 614 835 586 835 586 836 614 836 615 836 586 837 615 837 580 837 580 838 615 838 591 838 580 839 591 839 581 839 581 840 591 840 590 840 566 841 565 841 606 841 606 842 565 842 616 842 606 843 616 843 607 843 607 844 616 844 617 844 607 845 617 845 608 845 608 846 617 846 618 846 608 847 618 847 609 847 609 848 618 848 619 848 609 849 619 849 610 849 610 850 619 850 620 850 610 851 620 851 611 851 611 852 620 852 621 852 611 853 621 853 612 853 612 854 621 854 622 854 612 855 622 855 613 855 613 856 622 856 623 856 613 857 623 857 614 857 614 858 623 858 624 858 614 859 624 859 615 859 615 860 624 860 625 860 615 861 625 861 591 861 565 862 572 862 616 862 616 863 572 863 578 863 616 864 578 864 617 864 617 865 578 865 626 865 617 866 626 866 618 866 618 867 626 867 627 867 618 868 627 868 619 868 619 869 627 869 628 869 619 870 628 870 620 870 620 871 628 871 629 871 620 872 629 872 621 872 621 873 629 873 630 873 621 874 630 874 622 874 622 875 630 875 631 875 622 876 631 876 623 876 623 877 631 877 632 877 623 878 632 878 624 878 624 879 632 879 633 879 624 880 633 880 625 880 589 881 591 881 593 881 593 882 591 882 625 882 593 883 625 883 595 883 595 884 625 884 633 884 595 885 633 885 137 885 137 886 633 886 632 886 137 887 632 887 134 887 134 888 632 888 631 888 134 889 631 889 132 889 132 890 631 890 630 890 132 891 630 891 131 891 131 892 630 892 629 892 131 893 629 893 129 893 129 894 629 894 628 894 129 895 628 895 95 895 95 896 628 896 627 896 95 897 627 897 93 897 93 898 627 898 626 898 93 899 626 899 128 899 128 900 626 900 578 900 128 901 578 901 126 901 126 902 578 902 569 902 126 903 569 903 120 903 634 904 581 904 635 904 635 905 581 905 590 905 635 906 590 906 636 906 636 907 590 907 589 907 636 908 589 908 637 908 637 909 589 909 592 909 147 910 637 910 139 910 139 911 637 911 592 911 139 912 592 912 140 912 634 913 635 913 638 913 638 914 635 914 636 914 638 915 636 915 639 915 639 916 636 916 637 916 639 917 637 917 640 917 640 918 637 918 147 918 640 919 147 919 145 919 145 920 641 920 640 920 640 921 641 921 642 921 640 922 642 922 639 922 639 923 642 923 643 923 639 924 643 924 638 924 638 925 643 925 644 925 638 926 644 926 634 926 645 927 644 927 646 927 646 928 644 928 643 928 646 929 643 929 647 929 647 930 643 930 642 930 647 931 642 931 648 931 648 932 642 932 641 932 648 933 641 933 144 933 144 934 641 934 145 934 649 935 160 935 159 935 650 936 651 936 645 936 144 937 160 937 648 937 648 938 160 938 649 938 648 939 649 939 647 939 647 940 649 940 650 940 647 941 650 941 646 941 646 942 650 942 645 942 652 943 651 943 653 943 653 944 651 944 650 944 653 945 650 945 654 945 654 946 650 946 649 946 654 947 649 947 655 947 655 948 649 948 159 948 153 949 656 949 657 949 153 950 657 950 154 950 154 951 657 951 658 951 154 952 658 952 156 952 156 953 658 953 157 953 157 954 658 954 655 954 157 955 655 955 159 955 652 956 653 956 658 956 658 957 653 957 654 957 658 958 654 958 655 958 652 959 658 959 659 959 659 960 658 960 657 960 659 961 657 961 660 961 660 962 657 962 656 962 660 963 656 963 661 963 661 964 656 964 662 964 661 965 662 965 663 965 663 966 662 966 664 966 663 967 664 967 665 967 665 968 664 968 666 968 665 969 666 969 667 969 668 970 667 970 669 970 669 971 667 971 666 971 669 972 666 972 166 972 166 973 666 973 168 973 168 974 666 974 664 974 168 975 664 975 169 975 169 976 664 976 662 976 169 977 662 977 150 977 150 978 662 978 656 978 150 979 656 979 153 979 670 980 165 980 164 980 671 981 672 981 673 981 673 982 672 982 670 982 673 983 670 983 674 983 674 984 670 984 164 984 166 985 165 985 669 985 669 986 165 986 670 986 669 987 670 987 668 987 668 988 670 988 672 988 674 989 164 989 162 989 467 990 675 990 676 990 674 991 676 991 673 991 673 992 676 992 675 992 673 993 675 993 671 993 674 994 162 994 676 994 676 995 162 995 161 995 676 996 161 996 677 996 677 997 161 997 173 997 677 998 173 998 678 998 678 999 173 999 171 999 678 1000 171 1000 679 1000 679 1001 171 1001 170 1001 679 1002 170 1002 680 1002 467 1003 676 1003 468 1003 468 1004 676 1004 677 1004 468 1005 677 1005 469 1005 469 1006 677 1006 678 1006 469 1007 678 1007 470 1007 470 1008 678 1008 679 1008 470 1009 679 1009 471 1009 471 1010 679 1010 680 1010 471 1011 680 1011 462 1011 680 1012 170 1012 244 1012 347 1013 457 1013 352 1013 352 1014 457 1014 459 1014 352 1015 459 1015 353 1015 353 1016 459 1016 460 1016 353 1017 460 1017 350 1017 350 1018 460 1018 461 1018 350 1019 461 1019 337 1019 337 1020 461 1020 464 1020 337 1021 464 1021 246 1021 246 1022 464 1022 463 1022 246 1023 463 1023 244 1023 244 1024 463 1024 462 1024 244 1025 462 1025 680 1025 397 1026 467 1026 496 1026 496 1027 467 1027 466 1027 496 1028 466 1028 495 1028 495 1029 466 1029 465 1029 339 1030 492 1030 465 1030 465 1031 492 1031 491 1031 465 1032 491 1032 495 1032 395 1033 671 1033 675 1033 395 1034 675 1034 396 1034 396 1035 675 1035 467 1035 396 1036 467 1036 397 1036 681 1037 668 1037 672 1037 681 1038 672 1038 393 1038 393 1039 672 1039 394 1039 394 1040 672 1040 671 1040 394 1041 671 1041 395 1041 682 1042 661 1042 663 1042 402 1043 682 1043 683 1043 682 1044 663 1044 683 1044 683 1045 663 1045 665 1045 683 1046 665 1046 684 1046 684 1047 665 1047 667 1047 684 1048 667 1048 685 1048 685 1049 667 1049 668 1049 685 1050 668 1050 681 1050 402 1051 683 1051 389 1051 389 1052 683 1052 684 1052 389 1053 684 1053 390 1053 390 1054 684 1054 685 1054 390 1055 685 1055 392 1055 392 1056 685 1056 681 1056 392 1057 681 1057 393 1057 660 1058 661 1058 682 1058 401 1059 399 1059 686 1059 686 1060 399 1060 687 1060 660 1061 682 1061 659 1061 402 1062 401 1062 682 1062 682 1063 401 1063 686 1063 682 1064 686 1064 659 1064 659 1065 686 1065 687 1065 659 1066 687 1066 652 1066 645 1067 651 1067 688 1067 688 1068 651 1068 689 1068 688 1069 689 1069 690 1069 689 1070 398 1070 408 1070 408 1071 410 1071 689 1071 689 1072 410 1072 691 1072 689 1073 691 1073 690 1073 399 1074 398 1074 687 1074 687 1075 398 1075 689 1075 687 1076 689 1076 652 1076 652 1077 689 1077 651 1077 403 1078 405 1078 692 1078 692 1079 405 1079 693 1079 692 1080 693 1080 694 1080 694 1081 693 1081 695 1081 412 1082 403 1082 696 1082 696 1083 403 1083 692 1083 696 1084 692 1084 697 1084 697 1085 692 1085 694 1085 645 1086 697 1086 644 1086 644 1087 697 1087 694 1087 644 1088 694 1088 634 1088 634 1089 694 1089 695 1089 634 1090 695 1090 581 1090 410 1091 412 1091 691 1091 691 1092 412 1092 696 1092 691 1093 696 1093 690 1093 690 1094 696 1094 697 1094 690 1095 697 1095 688 1095 688 1096 697 1096 645 1096 698 1097 407 1097 375 1097 588 1098 579 1098 699 1098 699 1099 579 1099 700 1099 375 1100 701 1100 698 1100 698 1101 701 1101 702 1101 698 1102 702 1102 700 1102 700 1103 702 1103 703 1103 700 1104 703 1104 699 1104 405 1105 407 1105 693 1105 693 1106 407 1106 698 1106 693 1107 698 1107 695 1107 695 1108 698 1108 700 1108 695 1109 700 1109 581 1109 581 1110 700 1110 579 1110 379 1111 378 1111 704 1111 378 1112 381 1112 704 1112 704 1113 381 1113 383 1113 704 1114 383 1114 385 1114 705 1115 706 1115 707 1115 707 1116 706 1116 708 1116 707 1117 708 1117 709 1117 709 1118 708 1118 710 1118 588 1119 706 1119 587 1119 587 1120 706 1120 705 1120 587 1121 705 1121 585 1121 701 1122 710 1122 702 1122 702 1123 710 1123 708 1123 702 1124 708 1124 703 1124 703 1125 708 1125 706 1125 703 1126 706 1126 699 1126 699 1127 706 1127 588 1127 367 1128 585 1128 711 1128 711 1129 585 1129 705 1129 711 1130 705 1130 712 1130 712 1131 705 1131 707 1131 712 1132 707 1132 704 1132 704 1133 707 1133 709 1133 704 1134 709 1134 379 1134 379 1135 709 1135 710 1135 379 1136 710 1136 386 1136 386 1137 710 1137 701 1137 386 1138 701 1138 375 1138 713 1139 370 1139 369 1139 714 1140 713 1140 715 1140 716 1141 714 1141 717 1141 713 1142 369 1142 715 1142 715 1143 369 1143 374 1143 715 1144 374 1144 718 1144 718 1145 374 1145 373 1145 718 1146 373 1146 719 1146 719 1147 373 1147 368 1147 719 1148 368 1148 720 1148 714 1149 715 1149 717 1149 717 1150 715 1150 718 1150 717 1151 718 1151 721 1151 721 1152 718 1152 719 1152 721 1153 719 1153 722 1153 722 1154 719 1154 720 1154 722 1155 720 1155 723 1155 716 1156 717 1156 724 1156 724 1157 717 1157 721 1157 724 1158 721 1158 725 1158 725 1159 721 1159 722 1159 725 1160 722 1160 726 1160 726 1161 722 1161 723 1161 726 1162 723 1162 727 1162 528 1163 527 1163 727 1163 727 1164 527 1164 526 1164 727 1165 526 1165 726 1165 726 1166 526 1166 525 1166 726 1167 525 1167 725 1167 725 1168 525 1168 529 1168 725 1169 529 1169 724 1169 724 1170 529 1170 225 1170 724 1171 225 1171 716 1171 385 1172 528 1172 704 1172 704 1173 528 1173 727 1173 704 1174 727 1174 712 1174 712 1175 727 1175 723 1175 712 1176 723 1176 711 1176 711 1177 723 1177 720 1177 711 1178 720 1178 367 1178 367 1179 720 1179 368 1179 728 1180 229 1180 231 1180 603 1181 601 1181 729 1181 729 1182 601 1182 730 1182 729 1183 730 1183 731 1183 731 1184 730 1184 732 1184 231 1185 733 1185 728 1185 728 1186 733 1186 734 1186 728 1187 734 1187 732 1187 732 1188 734 1188 735 1188 732 1189 735 1189 731 1189 227 1190 229 1190 736 1190 736 1191 229 1191 728 1191 736 1192 728 1192 737 1192 737 1193 728 1193 732 1193 737 1194 732 1194 738 1194 738 1195 732 1195 730 1195 738 1196 730 1196 599 1196 599 1197 730 1197 601 1197 225 1198 227 1198 716 1198 716 1199 227 1199 736 1199 716 1200 736 1200 714 1200 714 1201 736 1201 737 1201 714 1202 737 1202 713 1202 713 1203 737 1203 738 1203 713 1204 738 1204 370 1204 370 1205 738 1205 599 1205 729 1206 731 1206 739 1206 740 1207 415 1207 417 1207 741 1208 566 1208 605 1208 603 1209 729 1209 605 1209 605 1210 729 1210 739 1210 605 1211 739 1211 741 1211 741 1212 739 1212 742 1212 731 1213 735 1213 739 1213 739 1214 735 1214 740 1214 739 1215 740 1215 742 1215 742 1216 740 1216 417 1216 231 1217 415 1217 733 1217 733 1218 415 1218 740 1218 733 1219 740 1219 734 1219 734 1220 740 1220 735 1220 743 1221 744 1221 745 1221 744 1222 561 1222 564 1222 746 1223 747 1223 743 1223 747 1224 746 1224 425 1224 425 1225 746 1225 423 1225 423 1226 746 1226 748 1226 423 1227 748 1227 421 1227 744 1228 564 1228 745 1228 745 1229 564 1229 567 1229 745 1230 567 1230 749 1230 749 1231 567 1231 566 1231 749 1232 566 1232 741 1232 743 1233 745 1233 746 1233 746 1234 745 1234 749 1234 746 1235 749 1235 748 1235 748 1236 749 1236 741 1236 748 1237 741 1237 742 1237 742 1238 417 1238 748 1238 748 1239 417 1239 419 1239 748 1240 419 1240 421 1240 429 1241 428 1241 750 1241 750 1242 428 1242 434 1242 751 1243 556 1243 558 1243 561 1244 744 1244 558 1244 558 1245 744 1245 750 1245 558 1246 750 1246 751 1246 751 1247 750 1247 434 1247 425 1248 429 1248 747 1248 747 1249 429 1249 750 1249 747 1250 750 1250 743 1250 743 1251 750 1251 744 1251 555 1252 556 1252 751 1252 433 1253 431 1253 752 1253 752 1254 431 1254 753 1254 752 1255 753 1255 553 1255 553 1256 753 1256 551 1256 434 1257 433 1257 751 1257 751 1258 433 1258 752 1258 751 1259 752 1259 555 1259 555 1260 752 1260 553 1260 754 1261 543 1261 545 1261 439 1262 754 1262 755 1262 754 1263 545 1263 755 1263 755 1264 545 1264 546 1264 755 1265 546 1265 756 1265 756 1266 546 1266 550 1266 756 1267 550 1267 757 1267 757 1268 550 1268 551 1268 757 1269 551 1269 753 1269 439 1270 755 1270 440 1270 440 1271 755 1271 756 1271 440 1272 756 1272 441 1272 441 1273 756 1273 757 1273 441 1274 757 1274 430 1274 430 1275 757 1275 753 1275 430 1276 753 1276 431 1276 437 1277 534 1277 541 1277 541 1278 543 1278 754 1278 437 1279 541 1279 438 1279 438 1280 541 1280 754 1280 438 1281 754 1281 439 1281 435 1282 451 1282 535 1282 435 1283 535 1283 436 1283 436 1284 535 1284 534 1284 436 1285 534 1285 437 1285 477 1286 296 1286 456 1286 452 1287 451 1287 435 1287 435 1288 472 1288 452 1288 452 1289 472 1289 474 1289 452 1290 474 1290 456 1290 456 1291 474 1291 473 1291 456 1292 473 1292 477 1292 758 1293 759 1293 760 1293 761 1294 762 1294 763 1294 762 1295 764 1295 763 1295 763 1296 764 1296 765 1296 763 1297 765 1297 760 1297 760 1298 765 1298 766 1298 760 1299 766 1299 758 1299 342 1300 767 1300 355 1300 355 1301 767 1301 768 1301 355 1302 768 1302 763 1302 763 1303 768 1303 769 1303 763 1304 769 1304 761 1304 763 1305 760 1305 770 1305 771 1306 772 1306 773 1306 773 1307 772 1307 770 1307 773 1308 770 1308 774 1308 774 1309 770 1309 760 1309 774 1310 760 1310 759 1310 775 1311 776 1311 777 1311 355 1312 778 1312 356 1312 356 1313 778 1313 777 1313 356 1314 777 1314 357 1314 357 1315 777 1315 776 1315 357 1316 776 1316 358 1316 355 1317 763 1317 778 1317 778 1318 763 1318 770 1318 778 1319 770 1319 777 1319 777 1320 770 1320 772 1320 777 1321 772 1321 775 1321 775 1322 772 1322 771 1322 775 1323 771 1323 779 1323 780 1324 781 1324 782 1324 782 1325 781 1325 360 1325 782 1326 360 1326 359 1326 783 1327 784 1327 780 1327 780 1328 784 1328 785 1328 780 1329 785 1329 781 1329 779 1330 783 1330 775 1330 775 1331 783 1331 780 1331 775 1332 780 1332 776 1332 776 1333 780 1333 782 1333 776 1334 782 1334 358 1334 358 1335 782 1335 359 1335 786 1336 787 1336 788 1336 785 1337 784 1337 789 1337 265 1338 790 1338 791 1338 265 1339 791 1339 792 1339 792 1340 791 1340 793 1340 792 1341 793 1341 794 1341 794 1342 793 1342 795 1342 794 1343 795 1343 796 1343 796 1344 795 1344 789 1344 796 1345 789 1345 797 1345 797 1346 789 1346 784 1346 797 1347 784 1347 783 1347 360 1348 781 1348 798 1348 265 1349 264 1349 790 1349 790 1350 264 1350 262 1350 790 1351 262 1351 799 1351 799 1352 262 1352 260 1352 799 1353 260 1353 800 1353 260 1354 257 1354 800 1354 800 1355 257 1355 255 1355 800 1356 255 1356 801 1356 801 1357 255 1357 254 1357 801 1358 254 1358 802 1358 802 1359 254 1359 803 1359 802 1360 803 1360 804 1360 802 1361 786 1361 801 1361 801 1362 786 1362 788 1362 801 1363 788 1363 800 1363 800 1364 788 1364 805 1364 800 1365 805 1365 799 1365 799 1366 805 1366 806 1366 799 1367 806 1367 790 1367 790 1368 806 1368 807 1368 790 1369 807 1369 791 1369 791 1370 807 1370 808 1370 791 1371 808 1371 793 1371 793 1372 808 1372 809 1372 793 1373 809 1373 795 1373 795 1374 809 1374 810 1374 795 1375 810 1375 789 1375 789 1376 810 1376 798 1376 789 1377 798 1377 785 1377 785 1378 798 1378 781 1378 360 1379 798 1379 361 1379 361 1380 798 1380 810 1380 361 1381 810 1381 362 1381 362 1382 810 1382 809 1382 362 1383 809 1383 363 1383 363 1384 809 1384 808 1384 363 1385 808 1385 364 1385 364 1386 808 1386 807 1386 364 1387 807 1387 365 1387 365 1388 807 1388 806 1388 365 1389 806 1389 331 1389 331 1390 806 1390 805 1390 331 1391 805 1391 332 1391 332 1392 805 1392 788 1392 332 1393 788 1393 336 1393 336 1394 788 1394 787 1394 336 1395 787 1395 335 1395 324 1396 335 1396 787 1396 811 1397 320 1397 322 1397 812 1398 813 1398 814 1398 814 1399 813 1399 811 1399 814 1400 811 1400 815 1400 815 1401 811 1401 322 1401 815 1402 322 1402 324 1402 816 1403 817 1403 812 1403 812 1404 817 1404 818 1404 812 1405 818 1405 813 1405 802 1406 804 1406 819 1406 324 1407 787 1407 815 1407 815 1408 787 1408 786 1408 815 1409 786 1409 814 1409 814 1410 786 1410 802 1410 814 1411 802 1411 812 1411 812 1412 802 1412 819 1412 812 1413 819 1413 816 1413 820 1414 821 1414 822 1414 823 1415 327 1415 320 1415 813 1416 818 1416 824 1416 825 1417 826 1417 827 1417 827 1418 826 1418 828 1418 827 1419 828 1419 824 1419 824 1420 828 1420 829 1420 824 1421 829 1421 813 1421 813 1422 829 1422 811 1422 825 1423 820 1423 826 1423 826 1424 820 1424 822 1424 826 1425 822 1425 828 1425 828 1426 822 1426 830 1426 828 1427 830 1427 829 1427 829 1428 830 1428 823 1428 829 1429 823 1429 811 1429 811 1430 823 1430 320 1430 327 1431 823 1431 325 1431 325 1432 823 1432 830 1432 325 1433 830 1433 312 1433 312 1434 830 1434 822 1434 312 1435 822 1435 310 1435 310 1436 822 1436 821 1436 310 1437 821 1437 308 1437 831 1438 832 1438 833 1438 834 1439 835 1439 836 1439 834 1440 836 1440 825 1440 825 1441 836 1441 837 1441 825 1442 837 1442 820 1442 820 1443 837 1443 838 1443 820 1444 838 1444 821 1444 308 1445 821 1445 317 1445 317 1446 821 1446 838 1446 317 1447 838 1447 315 1447 315 1448 838 1448 304 1448 304 1449 838 1449 839 1449 839 1450 838 1450 837 1450 839 1451 837 1451 840 1451 840 1452 837 1452 836 1452 840 1453 836 1453 833 1453 833 1454 836 1454 835 1454 833 1455 835 1455 831 1455 833 1456 832 1456 841 1456 841 1457 277 1457 833 1457 833 1458 277 1458 842 1458 833 1459 842 1459 840 1459 843 1460 844 1460 845 1460 845 1461 844 1461 282 1461 846 1462 847 1462 848 1462 849 1463 850 1463 851 1463 851 1464 850 1464 852 1464 851 1465 852 1465 853 1465 853 1466 852 1466 846 1466 853 1467 846 1467 854 1467 854 1468 846 1468 848 1468 855 1469 267 1469 856 1469 856 1470 267 1470 266 1470 856 1471 266 1471 849 1471 849 1472 266 1472 857 1472 849 1473 857 1473 850 1473 277 1474 276 1474 842 1474 842 1475 276 1475 274 1475 842 1476 274 1476 858 1476 858 1477 274 1477 271 1477 858 1478 271 1478 855 1478 855 1479 271 1479 269 1479 855 1480 269 1480 267 1480 282 1481 281 1481 845 1481 845 1482 281 1482 279 1482 845 1483 279 1483 859 1483 859 1484 279 1484 278 1484 859 1485 278 1485 860 1485 860 1486 278 1486 307 1486 860 1487 307 1487 861 1487 861 1488 307 1488 306 1488 861 1489 306 1489 862 1489 862 1490 306 1490 305 1490 862 1491 305 1491 863 1491 863 1492 305 1492 301 1492 863 1493 301 1493 864 1493 864 1494 301 1494 303 1494 864 1495 303 1495 865 1495 865 1496 303 1496 304 1496 865 1497 304 1497 839 1497 839 1498 840 1498 865 1498 865 1499 840 1499 842 1499 865 1500 842 1500 864 1500 864 1501 842 1501 858 1501 864 1502 858 1502 863 1502 863 1503 858 1503 855 1503 863 1504 855 1504 862 1504 862 1505 855 1505 856 1505 862 1506 856 1506 861 1506 861 1507 856 1507 849 1507 861 1508 849 1508 860 1508 860 1509 849 1509 851 1509 860 1510 851 1510 859 1510 859 1511 851 1511 853 1511 859 1512 853 1512 845 1512 845 1513 853 1513 854 1513 845 1514 854 1514 843 1514 843 1515 854 1515 848 1515 866 1516 867 1516 868 1516 868 1517 867 1517 869 1517 870 1518 871 1518 868 1518 868 1519 871 1519 872 1519 868 1520 872 1520 866 1520 868 1521 869 1521 873 1521 870 1522 848 1522 874 1522 874 1523 848 1523 847 1523 283 1524 282 1524 875 1524 875 1525 282 1525 844 1525 875 1526 844 1526 876 1526 876 1527 844 1527 843 1527 284 1528 283 1528 877 1528 877 1529 283 1529 875 1529 877 1530 875 1530 868 1530 868 1531 875 1531 876 1531 868 1532 876 1532 870 1532 870 1533 876 1533 843 1533 870 1534 843 1534 848 1534 878 1535 879 1535 880 1535 879 1536 878 1536 881 1536 881 1537 878 1537 882 1537 882 1538 878 1538 868 1538 882 1539 868 1539 873 1539 285 1540 284 1540 883 1540 883 1541 284 1541 877 1541 286 1542 285 1542 880 1542 880 1543 285 1543 883 1543 880 1544 883 1544 878 1544 878 1545 883 1545 877 1545 878 1546 877 1546 868 1546 287 1547 286 1547 884 1547 884 1548 286 1548 880 1548 884 1549 880 1549 885 1549 885 1550 880 1550 879 1550 885 1551 879 1551 886 1551 886 1552 879 1552 881 1552 884 1553 240 1553 287 1553 287 1554 240 1554 236 1554 287 1555 236 1555 235 1555 886 1556 243 1556 885 1556 885 1557 243 1557 242 1557 885 1558 242 1558 884 1558 884 1559 242 1559 241 1559 884 1560 241 1560 240 1560 349 1561 346 1561 887 1561 348 1562 351 1562 888 1562 888 1563 351 1563 248 1563 888 1564 248 1564 889 1564 346 1565 345 1565 887 1565 887 1566 345 1566 348 1566 887 1567 348 1567 890 1567 767 1568 342 1568 349 1568 248 1569 247 1569 889 1569 889 1570 247 1570 245 1570 889 1571 245 1571 891 1571 891 1572 245 1572 250 1572 891 1573 250 1573 892 1573 892 1574 250 1574 249 1574 892 1575 249 1575 893 1575 893 1576 249 1576 253 1576 893 1577 253 1577 894 1577 894 1578 253 1578 895 1578 895 1579 253 1579 252 1579 895 1580 252 1580 251 1580 348 1581 888 1581 890 1581 890 1582 888 1582 889 1582 890 1583 889 1583 896 1583 896 1584 889 1584 891 1584 896 1585 891 1585 897 1585 897 1586 891 1586 892 1586 897 1587 892 1587 898 1587 898 1588 892 1588 893 1588 898 1589 893 1589 899 1589 899 1590 893 1590 894 1590 899 1591 894 1591 900 1591 900 1592 894 1592 895 1592 900 1593 895 1593 901 1593 251 1594 67 1594 902 1594 251 1595 902 1595 895 1595 895 1596 902 1596 903 1596 895 1597 903 1597 901 1597 901 1598 903 1598 904 1598 901 1599 904 1599 905 1599 349 1600 887 1600 767 1600 767 1601 887 1601 890 1601 767 1602 890 1602 768 1602 768 1603 890 1603 896 1603 768 1604 896 1604 769 1604 769 1605 896 1605 897 1605 769 1606 897 1606 761 1606 761 1607 897 1607 898 1607 761 1608 898 1608 762 1608 762 1609 898 1609 899 1609 762 1610 899 1610 764 1610 764 1611 899 1611 900 1611 764 1612 900 1612 765 1612 765 1613 900 1613 901 1613 765 1614 901 1614 766 1614 766 1615 901 1615 905 1615 766 1616 905 1616 758 1616 67 1617 66 1617 906 1617 759 1618 758 1618 907 1618 907 1619 758 1619 905 1619 907 1620 905 1620 908 1620 908 1621 905 1621 904 1621 908 1622 904 1622 909 1622 909 1623 904 1623 903 1623 909 1624 903 1624 906 1624 906 1625 903 1625 902 1625 906 1626 902 1626 67 1626 910 1627 911 1627 912 1627 68 1628 910 1628 913 1628 910 1629 912 1629 913 1629 913 1630 912 1630 914 1630 913 1631 914 1631 915 1631 915 1632 914 1632 916 1632 915 1633 916 1633 917 1633 759 1634 916 1634 774 1634 774 1635 916 1635 914 1635 774 1636 914 1636 773 1636 773 1637 914 1637 912 1637 773 1638 912 1638 771 1638 771 1639 912 1639 911 1639 771 1640 911 1640 779 1640 759 1641 907 1641 916 1641 916 1642 907 1642 908 1642 916 1643 908 1643 917 1643 917 1644 908 1644 909 1644 917 1645 909 1645 906 1645 68 1646 913 1646 71 1646 71 1647 913 1647 915 1647 71 1648 915 1648 72 1648 72 1649 915 1649 917 1649 72 1650 917 1650 73 1650 73 1651 917 1651 906 1651 73 1652 906 1652 66 1652 783 1653 779 1653 918 1653 918 1654 779 1654 911 1654 918 1655 911 1655 919 1655 919 1656 911 1656 920 1656 920 1657 911 1657 910 1657 920 1658 910 1658 921 1658 921 1659 910 1659 922 1659 922 1660 910 1660 68 1660 922 1661 68 1661 69 1661 919 1662 920 1662 923 1662 920 1663 921 1663 924 1663 924 1664 921 1664 922 1664 924 1665 922 1665 69 1665 919 1666 923 1666 918 1666 783 1667 918 1667 925 1667 69 1668 77 1668 924 1668 924 1669 77 1669 78 1669 924 1670 78 1670 926 1670 926 1671 78 1671 81 1671 926 1672 81 1672 927 1672 927 1673 81 1673 80 1673 927 1674 80 1674 928 1674 928 1675 80 1675 75 1675 928 1676 75 1676 929 1676 920 1677 924 1677 923 1677 923 1678 924 1678 926 1678 923 1679 926 1679 930 1679 930 1680 926 1680 927 1680 930 1681 927 1681 931 1681 931 1682 927 1682 928 1682 931 1683 928 1683 932 1683 932 1684 928 1684 929 1684 932 1685 929 1685 933 1685 918 1686 923 1686 925 1686 925 1687 923 1687 930 1687 925 1688 930 1688 934 1688 934 1689 930 1689 931 1689 934 1690 931 1690 935 1690 935 1691 931 1691 932 1691 935 1692 932 1692 936 1692 936 1693 932 1693 933 1693 936 1694 933 1694 937 1694 783 1695 925 1695 797 1695 797 1696 925 1696 934 1696 797 1697 934 1697 796 1697 796 1698 934 1698 935 1698 796 1699 935 1699 794 1699 794 1700 935 1700 936 1700 794 1701 936 1701 792 1701 792 1702 936 1702 937 1702 792 1703 937 1703 265 1703 259 1704 261 1704 938 1704 254 1705 256 1705 939 1705 939 1706 256 1706 940 1706 939 1707 940 1707 941 1707 941 1708 940 1708 942 1708 83 1709 943 1709 944 1709 944 1710 943 1710 945 1710 944 1711 945 1711 942 1711 942 1712 945 1712 946 1712 942 1713 946 1713 941 1713 91 1714 89 1714 944 1714 944 1715 89 1715 88 1715 944 1716 88 1716 83 1716 259 1717 938 1717 258 1717 947 1718 948 1718 949 1718 949 1719 948 1719 950 1719 949 1720 950 1720 938 1720 938 1721 950 1721 951 1721 938 1722 951 1722 258 1722 261 1723 263 1723 938 1723 938 1724 263 1724 952 1724 938 1725 952 1725 949 1725 949 1726 952 1726 953 1726 949 1727 953 1727 947 1727 947 1728 953 1728 954 1728 929 1729 954 1729 933 1729 933 1730 954 1730 953 1730 933 1731 953 1731 937 1731 937 1732 953 1732 952 1732 937 1733 952 1733 265 1733 265 1734 952 1734 263 1734 256 1735 258 1735 940 1735 940 1736 258 1736 951 1736 940 1737 951 1737 942 1737 942 1738 951 1738 950 1738 942 1739 950 1739 944 1739 944 1740 950 1740 948 1740 944 1741 948 1741 91 1741 91 1742 948 1742 947 1742 91 1743 947 1743 92 1743 92 1744 947 1744 954 1744 92 1745 954 1745 74 1745 74 1746 954 1746 929 1746 74 1747 929 1747 75 1747 83 1748 82 1748 943 1748 943 1749 82 1749 955 1749 943 1750 955 1750 945 1750 956 1751 803 1751 254 1751 254 1752 939 1752 956 1752 956 1753 939 1753 941 1753 956 1754 941 1754 955 1754 955 1755 941 1755 946 1755 955 1756 946 1756 945 1756 804 1757 803 1757 957 1757 957 1758 803 1758 956 1758 957 1759 956 1759 958 1759 958 1760 956 1760 955 1760 958 1761 955 1761 85 1761 85 1762 955 1762 82 1762 819 1763 804 1763 959 1763 959 1764 804 1764 957 1764 959 1765 957 1765 960 1765 960 1766 957 1766 958 1766 960 1767 958 1767 87 1767 87 1768 958 1768 85 1768 816 1769 819 1769 961 1769 961 1770 819 1770 959 1770 961 1771 959 1771 962 1771 962 1772 959 1772 960 1772 962 1773 960 1773 27 1773 27 1774 960 1774 87 1774 817 1775 816 1775 963 1775 963 1776 816 1776 961 1776 963 1777 961 1777 964 1777 964 1778 961 1778 962 1778 964 1779 962 1779 26 1779 26 1780 962 1780 27 1780 818 1781 817 1781 965 1781 965 1782 817 1782 963 1782 965 1783 963 1783 966 1783 966 1784 963 1784 964 1784 966 1785 964 1785 34 1785 34 1786 964 1786 26 1786 827 1787 824 1787 967 1787 824 1788 818 1788 967 1788 967 1789 818 1789 965 1789 967 1790 965 1790 968 1790 968 1791 965 1791 966 1791 968 1792 966 1792 33 1792 33 1793 966 1793 34 1793 33 1794 32 1794 968 1794 968 1795 32 1795 969 1795 968 1796 969 1796 967 1796 967 1797 969 1797 970 1797 967 1798 970 1798 827 1798 827 1799 970 1799 825 1799 834 1800 825 1800 971 1800 971 1801 825 1801 970 1801 971 1802 970 1802 972 1802 972 1803 970 1803 969 1803 972 1804 969 1804 31 1804 31 1805 969 1805 32 1805 835 1806 834 1806 973 1806 973 1807 834 1807 971 1807 973 1808 971 1808 974 1808 974 1809 971 1809 972 1809 974 1810 972 1810 30 1810 30 1811 972 1811 31 1811 831 1812 835 1812 975 1812 975 1813 835 1813 973 1813 975 1814 973 1814 976 1814 976 1815 973 1815 974 1815 976 1816 974 1816 40 1816 40 1817 974 1817 30 1817 832 1818 831 1818 977 1818 977 1819 831 1819 975 1819 977 1820 975 1820 978 1820 978 1821 975 1821 976 1821 978 1822 976 1822 39 1822 39 1823 976 1823 40 1823 979 1824 841 1824 832 1824 978 1825 39 1825 37 1825 977 1826 978 1826 980 1826 978 1827 37 1827 980 1827 980 1828 37 1828 36 1828 980 1829 36 1829 981 1829 981 1830 982 1830 980 1830 980 1831 982 1831 979 1831 980 1832 979 1832 977 1832 977 1833 979 1833 832 1833 277 1834 841 1834 983 1834 983 1835 841 1835 979 1835 983 1836 979 1836 984 1836 984 1837 979 1837 982 1837 985 1838 986 1838 987 1838 42 1839 985 1839 988 1839 270 1840 989 1840 268 1840 268 1841 989 1841 990 1841 268 1842 990 1842 266 1842 272 1843 991 1843 270 1843 270 1844 991 1844 992 1844 270 1845 992 1845 989 1845 42 1846 988 1846 43 1846 43 1847 988 1847 993 1847 43 1848 993 1848 44 1848 44 1849 993 1849 994 1849 44 1850 994 1850 45 1850 985 1851 987 1851 988 1851 988 1852 987 1852 995 1852 988 1853 995 1853 993 1853 993 1854 995 1854 996 1854 993 1855 996 1855 994 1855 994 1856 996 1856 997 1856 994 1857 997 1857 998 1857 45 1858 994 1858 47 1858 47 1859 994 1859 998 1859 47 1860 998 1860 48 1860 272 1861 273 1861 991 1861 991 1862 273 1862 275 1862 991 1863 275 1863 999 1863 999 1864 275 1864 277 1864 999 1865 277 1865 983 1865 983 1866 997 1866 999 1866 999 1867 997 1867 996 1867 999 1868 996 1868 991 1868 991 1869 996 1869 995 1869 991 1870 995 1870 992 1870 992 1871 995 1871 987 1871 992 1872 987 1872 989 1872 989 1873 987 1873 986 1873 989 1874 986 1874 990 1874 36 1875 48 1875 981 1875 981 1876 48 1876 998 1876 981 1877 998 1877 982 1877 982 1878 998 1878 997 1878 982 1879 997 1879 984 1879 984 1880 997 1880 983 1880 1000 1881 1001 1881 1002 1881 1001 1882 847 1882 846 1882 1003 1883 1004 1883 1005 1883 1005 1884 1004 1884 1000 1884 1006 1885 1007 1885 1003 1885 1007 1886 1006 1886 50 1886 1001 1887 846 1887 1002 1887 1002 1888 846 1888 852 1888 1002 1889 852 1889 1008 1889 1008 1890 852 1890 850 1890 1008 1891 850 1891 1009 1891 1009 1892 850 1892 857 1892 1009 1893 857 1893 1010 1893 1010 1894 857 1894 266 1894 1010 1895 266 1895 990 1895 1000 1896 1002 1896 1005 1896 1005 1897 1002 1897 1008 1897 1005 1898 1008 1898 1011 1898 1011 1899 1008 1899 1009 1899 1011 1900 1009 1900 1012 1900 1012 1901 1009 1901 1010 1901 1012 1902 1010 1902 1013 1902 1013 1903 1010 1903 990 1903 1013 1904 990 1904 986 1904 1003 1905 1005 1905 1006 1905 1006 1906 1005 1906 1011 1906 1006 1907 1011 1907 1014 1907 1014 1908 1011 1908 1012 1908 1014 1909 1012 1909 1015 1909 1015 1910 1012 1910 1013 1910 1015 1911 1013 1911 1016 1911 1016 1912 1013 1912 986 1912 1016 1913 986 1913 985 1913 50 1914 1006 1914 51 1914 51 1915 1006 1915 1014 1915 51 1916 1014 1916 52 1916 52 1917 1014 1917 1015 1917 52 1918 1015 1918 53 1918 53 1919 1015 1919 1016 1919 53 1920 1016 1920 54 1920 54 1921 1016 1921 985 1921 54 1922 985 1922 42 1922 239 1923 243 1923 886 1923 873 1924 1017 1924 882 1924 882 1925 1017 1925 1018 1925 882 1926 1018 1926 881 1926 881 1927 1018 1927 1019 1927 881 1928 1019 1928 886 1928 886 1929 1019 1929 1020 1929 886 1930 1020 1930 239 1930 56 1931 232 1931 1021 1931 1021 1932 232 1932 237 1932 1021 1933 237 1933 238 1933 847 1934 1001 1934 874 1934 874 1935 1001 1935 1000 1935 874 1936 1000 1936 870 1936 873 1937 869 1937 1017 1937 1017 1938 869 1938 867 1938 1017 1939 867 1939 1022 1939 1022 1940 867 1940 866 1940 1022 1941 866 1941 1023 1941 1023 1942 866 1942 872 1942 1023 1943 872 1943 1024 1943 1024 1944 872 1944 871 1944 1024 1945 871 1945 1025 1945 1025 1946 871 1946 870 1946 1025 1947 870 1947 1026 1947 1026 1948 870 1948 1000 1948 1000 1949 1027 1949 1026 1949 1026 1950 1027 1950 1028 1950 1026 1951 1028 1951 1025 1951 1025 1952 1028 1952 1029 1952 1025 1953 1029 1953 1024 1953 1024 1954 1029 1954 1030 1954 1024 1955 1030 1955 1023 1955 1023 1956 1030 1956 1031 1956 1023 1957 1031 1957 1022 1957 1022 1958 1031 1958 1032 1958 1022 1959 1032 1959 1017 1959 1017 1960 1032 1960 1033 1960 1017 1961 1033 1961 1018 1961 1018 1962 1033 1962 1034 1962 1018 1963 1034 1963 1019 1963 1019 1964 1034 1964 1021 1964 1019 1965 1021 1965 1020 1965 1020 1966 1021 1966 238 1966 1020 1967 238 1967 239 1967 1000 1968 1004 1968 1027 1968 1027 1969 1004 1969 1003 1969 1027 1970 1003 1970 1007 1970 56 1971 1021 1971 57 1971 57 1972 1021 1972 1034 1972 57 1973 1034 1973 58 1973 58 1974 1034 1974 1033 1974 58 1975 1033 1975 59 1975 59 1976 1033 1976 1032 1976 59 1977 1032 1977 65 1977 65 1978 1032 1978 1031 1978 65 1979 1031 1979 62 1979 62 1980 1031 1980 1030 1980 62 1981 1030 1981 63 1981 63 1982 1030 1982 1029 1982 63 1983 1029 1983 64 1983 64 1984 1029 1984 1028 1984 64 1985 1028 1985 61 1985 61 1986 1028 1986 1027 1986 61 1987 1027 1987 60 1987 60 1988 1027 1988 1007 1988 60 1989 1007 1989 50 1989 1035 1990 1036 1990 1037 1990 1038 1991 1039 1991 1040 1991 1041 1992 1042 1992 1043 1992 1044 1993 1045 1993 1046 1993 1047 1994 1048 1994 1049 1994 1050 1995 1051 1995 1052 1995 1053 1996 1054 1996 1055 1996 1056 1997 1057 1997 1058 1997 1059 1998 1060 1998 1061 1998 1062 1999 1063 1999 1064 1999 1065 2000 1066 2000 1067 2000 1068 2001 1069 2001 1070 2001 1071 2002 1072 2002 1073 2002 1073 2003 1072 2003 1074 2003 1073 2004 1074 2004 1075 2004 1076 2005 1077 2005 1078 2005 1078 2006 1077 2006 1079 2006 1078 2007 1079 2007 1080 2007 1065 2008 1067 2008 1081 2008 1082 2009 1083 2009 1084 2009 1084 2010 1083 2010 1085 2010 1086 2011 1087 2011 1088 2011 1088 2012 1087 2012 1089 2012 1090 2013 1091 2013 1092 2013 1092 2014 1091 2014 1093 2014 1094 2015 1095 2015 1096 2015 1096 2016 1095 2016 1097 2016 1096 2017 1097 2017 1098 2017 1098 2018 1097 2018 1099 2018 1098 2019 1099 2019 1100 2019 1101 2020 1102 2020 1094 2020 1094 2021 1102 2021 1103 2021 1094 2022 1103 2022 1095 2022 1104 2023 1105 2023 1106 2023 1106 2024 1105 2024 1107 2024 1107 2025 1108 2025 1101 2025 1101 2026 1108 2026 1109 2026 1101 2027 1109 2027 1102 2027 1110 2028 1111 2028 1104 2028 1104 2029 1111 2029 1112 2029 1104 2030 1112 2030 1105 2030 1113 2031 1114 2031 1115 2031 1115 2032 1114 2032 1116 2032 1115 2033 1116 2033 1110 2033 1110 2034 1116 2034 1117 2034 1110 2035 1117 2035 1111 2035 1118 2036 1119 2036 1120 2036 1056 2037 1058 2037 1121 2037 1121 2038 1058 2038 1122 2038 1121 2039 1122 2039 1123 2039 1123 2040 1122 2040 1124 2040 1123 2041 1124 2041 1125 2041 1125 2042 1124 2042 1126 2042 1125 2043 1126 2043 1127 2043 1127 2044 1126 2044 1128 2044 1127 2045 1128 2045 1129 2045 1129 2046 1128 2046 1130 2046 1130 2047 1128 2047 1131 2047 1130 2048 1131 2048 1132 2048 1133 2049 1134 2049 1135 2049 1135 2050 1134 2050 1136 2050 1135 2051 1136 2051 1137 2051 1138 2052 1139 2052 1140 2052 1140 2053 1139 2053 1073 2053 1140 2054 1073 2054 1141 2054 1141 2055 1073 2055 1075 2055 1142 2056 1138 2056 1143 2056 1143 2057 1138 2057 1140 2057 1143 2058 1140 2058 1136 2058 1136 2059 1140 2059 1141 2059 1136 2060 1141 2060 1137 2060 1137 2061 1141 2061 1075 2061 1079 2062 1071 2062 1080 2062 1080 2063 1071 2063 1073 2063 1080 2064 1073 2064 1144 2064 1144 2065 1073 2065 1139 2065 1144 2066 1139 2066 1145 2066 1145 2067 1139 2067 1138 2067 1145 2068 1138 2068 1146 2068 1146 2069 1138 2069 1142 2069 1146 2070 1142 2070 1147 2070 1069 2071 1076 2071 1070 2071 1070 2072 1076 2072 1078 2072 1070 2073 1078 2073 1148 2073 1148 2074 1078 2074 1080 2074 1148 2075 1080 2075 1149 2075 1149 2076 1080 2076 1144 2076 1149 2077 1144 2077 1150 2077 1150 2078 1144 2078 1145 2078 1150 2079 1145 2079 1151 2079 1151 2080 1145 2080 1146 2080 1151 2081 1146 2081 1152 2081 1152 2082 1146 2082 1147 2082 1152 2083 1147 2083 1153 2083 1154 2084 1155 2084 1156 2084 1156 2085 1155 2085 1157 2085 1156 2086 1157 2086 1158 2086 1158 2087 1157 2087 1159 2087 1158 2088 1159 2088 1160 2088 1161 2089 1068 2089 1162 2089 1162 2090 1068 2090 1070 2090 1162 2091 1070 2091 1163 2091 1163 2092 1070 2092 1148 2092 1163 2093 1148 2093 1164 2093 1164 2094 1148 2094 1149 2094 1164 2095 1149 2095 1165 2095 1165 2096 1149 2096 1150 2096 1165 2097 1150 2097 1166 2097 1166 2098 1150 2098 1151 2098 1166 2099 1151 2099 1167 2099 1167 2100 1151 2100 1152 2100 1167 2101 1152 2101 1154 2101 1154 2102 1152 2102 1153 2102 1154 2103 1153 2103 1155 2103 1053 2104 1168 2104 1169 2104 1169 2105 1168 2105 1170 2105 1169 2106 1170 2106 1171 2106 1171 2107 1170 2107 1172 2107 1085 2108 1173 2108 1084 2108 1084 2109 1173 2109 1174 2109 1084 2110 1174 2110 1175 2110 1175 2111 1174 2111 1176 2111 1175 2112 1176 2112 1177 2112 1177 2113 1176 2113 1178 2113 1177 2114 1178 2114 1179 2114 1180 2115 1181 2115 1182 2115 1182 2116 1181 2116 1183 2116 1182 2117 1183 2117 1184 2117 1184 2118 1183 2118 1185 2118 1184 2119 1185 2119 1186 2119 1186 2120 1185 2120 1187 2120 1186 2121 1187 2121 1188 2121 1188 2122 1187 2122 1189 2122 1188 2123 1189 2123 1190 2123 1190 2124 1189 2124 1191 2124 1190 2125 1191 2125 1192 2125 1181 2126 1082 2126 1183 2126 1183 2127 1082 2127 1084 2127 1183 2128 1084 2128 1185 2128 1185 2129 1084 2129 1175 2129 1185 2130 1175 2130 1187 2130 1187 2131 1175 2131 1177 2131 1187 2132 1177 2132 1189 2132 1189 2133 1177 2133 1179 2133 1189 2134 1179 2134 1191 2134 1193 2135 1194 2135 1195 2135 1196 2136 1197 2136 1198 2136 1198 2137 1197 2137 1199 2137 1198 2138 1199 2138 1200 2138 1200 2139 1199 2139 1201 2139 1200 2140 1201 2140 1202 2140 1202 2141 1201 2141 1203 2141 1202 2142 1203 2142 1204 2142 1204 2143 1203 2143 1205 2143 1204 2144 1205 2144 1206 2144 1206 2145 1205 2145 1207 2145 1206 2146 1207 2146 1208 2146 1208 2147 1207 2147 1209 2147 1208 2148 1209 2148 1210 2148 1210 2149 1209 2149 1211 2149 1210 2150 1211 2150 1212 2150 1193 2151 1195 2151 1213 2151 1213 2152 1195 2152 1214 2152 1213 2153 1214 2153 1215 2153 1215 2154 1214 2154 1216 2154 1215 2155 1216 2155 1217 2155 1217 2156 1216 2156 1218 2156 1217 2157 1218 2157 1219 2157 1219 2158 1218 2158 1220 2158 1219 2159 1220 2159 1221 2159 1221 2160 1220 2160 1222 2160 1221 2161 1222 2161 1223 2161 1223 2162 1222 2162 1224 2162 1223 2163 1224 2163 1225 2163 1226 2164 1194 2164 1227 2164 1227 2165 1194 2165 1193 2165 1227 2166 1193 2166 1228 2166 1228 2167 1193 2167 1213 2167 1228 2168 1213 2168 1229 2168 1229 2169 1213 2169 1215 2169 1229 2170 1215 2170 1230 2170 1230 2171 1215 2171 1217 2171 1230 2172 1217 2172 1231 2172 1231 2173 1217 2173 1219 2173 1231 2174 1219 2174 1232 2174 1232 2175 1219 2175 1221 2175 1232 2176 1221 2176 1233 2176 1233 2177 1221 2177 1223 2177 1233 2178 1223 2178 1234 2178 1234 2179 1223 2179 1225 2179 1234 2180 1225 2180 1235 2180 1168 2181 1226 2181 1170 2181 1170 2182 1226 2182 1227 2182 1170 2183 1227 2183 1172 2183 1172 2184 1227 2184 1228 2184 1172 2185 1228 2185 1236 2185 1236 2186 1228 2186 1229 2186 1236 2187 1229 2187 1237 2187 1237 2188 1229 2188 1230 2188 1237 2189 1230 2189 1238 2189 1238 2190 1230 2190 1231 2190 1238 2191 1231 2191 1239 2191 1239 2192 1231 2192 1232 2192 1239 2193 1232 2193 1240 2193 1240 2194 1232 2194 1233 2194 1240 2195 1233 2195 1241 2195 1241 2196 1233 2196 1234 2196 1241 2197 1234 2197 1242 2197 1242 2198 1234 2198 1235 2198 1242 2199 1235 2199 1243 2199 1243 2200 1196 2200 1242 2200 1242 2201 1196 2201 1198 2201 1242 2202 1198 2202 1241 2202 1241 2203 1198 2203 1200 2203 1241 2204 1200 2204 1240 2204 1240 2205 1200 2205 1202 2205 1240 2206 1202 2206 1239 2206 1239 2207 1202 2207 1204 2207 1239 2208 1204 2208 1238 2208 1238 2209 1204 2209 1206 2209 1238 2210 1206 2210 1237 2210 1237 2211 1206 2211 1208 2211 1237 2212 1208 2212 1236 2212 1236 2213 1208 2213 1210 2213 1236 2214 1210 2214 1172 2214 1172 2215 1210 2215 1212 2215 1172 2216 1212 2216 1171 2216 1197 2217 1180 2217 1199 2217 1199 2218 1180 2218 1182 2218 1199 2219 1182 2219 1201 2219 1201 2220 1182 2220 1184 2220 1201 2221 1184 2221 1203 2221 1203 2222 1184 2222 1186 2222 1203 2223 1186 2223 1205 2223 1205 2224 1186 2224 1188 2224 1205 2225 1188 2225 1207 2225 1207 2226 1188 2226 1190 2226 1207 2227 1190 2227 1209 2227 1209 2228 1190 2228 1192 2228 1209 2229 1192 2229 1211 2229 1244 2230 1161 2230 1245 2230 1245 2231 1161 2231 1162 2231 1245 2232 1162 2232 1246 2232 1246 2233 1162 2233 1163 2233 1246 2234 1163 2234 1247 2234 1247 2235 1163 2235 1164 2235 1247 2236 1164 2236 1248 2236 1248 2237 1164 2237 1165 2237 1248 2238 1165 2238 1249 2238 1249 2239 1165 2239 1166 2239 1249 2240 1166 2240 1250 2240 1250 2241 1166 2241 1167 2241 1250 2242 1167 2242 1251 2242 1251 2243 1167 2243 1154 2243 1251 2244 1154 2244 1252 2244 1252 2245 1154 2245 1156 2245 1252 2246 1156 2246 1253 2246 1253 2247 1156 2247 1158 2247 1253 2248 1158 2248 1254 2248 1254 2249 1158 2249 1160 2249 1254 2250 1160 2250 1255 2250 1255 2251 1256 2251 1254 2251 1254 2252 1256 2252 1257 2252 1254 2253 1257 2253 1253 2253 1253 2254 1257 2254 1258 2254 1253 2255 1258 2255 1252 2255 1252 2256 1258 2256 1259 2256 1252 2257 1259 2257 1251 2257 1251 2258 1259 2258 1260 2258 1251 2259 1260 2259 1250 2259 1250 2260 1260 2260 1261 2260 1250 2261 1261 2261 1249 2261 1249 2262 1261 2262 1262 2262 1249 2263 1262 2263 1248 2263 1248 2264 1262 2264 1263 2264 1248 2265 1263 2265 1247 2265 1247 2266 1263 2266 1264 2266 1247 2267 1264 2267 1246 2267 1246 2268 1264 2268 1265 2268 1246 2269 1265 2269 1245 2269 1245 2270 1265 2270 1067 2270 1245 2271 1067 2271 1244 2271 1244 2272 1067 2272 1066 2272 1256 2273 1266 2273 1257 2273 1257 2274 1266 2274 1267 2274 1257 2275 1267 2275 1258 2275 1258 2276 1267 2276 1268 2276 1258 2277 1268 2277 1259 2277 1259 2278 1268 2278 1269 2278 1259 2279 1269 2279 1260 2279 1260 2280 1269 2280 1270 2280 1260 2281 1270 2281 1261 2281 1261 2282 1270 2282 1271 2282 1261 2283 1271 2283 1262 2283 1262 2284 1271 2284 1272 2284 1262 2285 1272 2285 1263 2285 1263 2286 1272 2286 1273 2286 1263 2287 1273 2287 1264 2287 1264 2288 1273 2288 1274 2288 1264 2289 1274 2289 1265 2289 1265 2290 1274 2290 1275 2290 1265 2291 1275 2291 1067 2291 1067 2292 1275 2292 1276 2292 1067 2293 1276 2293 1081 2293 1081 2294 1276 2294 1277 2294 1054 2295 1050 2295 1278 2295 1279 2296 1280 2296 1281 2296 1281 2297 1280 2297 1282 2297 1281 2298 1282 2298 1283 2298 1283 2299 1282 2299 1284 2299 1283 2300 1284 2300 1285 2300 1286 2301 1287 2301 1288 2301 1288 2302 1287 2302 1289 2302 1288 2303 1289 2303 1290 2303 1290 2304 1289 2304 1291 2304 1290 2305 1291 2305 1292 2305 1292 2306 1291 2306 1293 2306 1292 2307 1293 2307 1294 2307 1294 2308 1293 2308 1295 2308 1294 2309 1295 2309 1296 2309 1296 2310 1295 2310 1049 2310 1296 2311 1049 2311 1297 2311 1297 2312 1049 2312 1048 2312 1297 2313 1048 2313 1298 2313 1054 2314 1278 2314 1055 2314 1055 2315 1278 2315 1299 2315 1055 2316 1299 2316 1300 2316 1300 2317 1299 2317 1301 2317 1300 2318 1301 2318 1302 2318 1302 2319 1301 2319 1303 2319 1302 2320 1303 2320 1304 2320 1304 2321 1303 2321 1305 2321 1304 2322 1305 2322 1306 2322 1306 2323 1305 2323 1307 2323 1306 2324 1307 2324 1308 2324 1308 2325 1307 2325 1309 2325 1308 2326 1309 2326 1310 2326 1310 2327 1309 2327 1311 2327 1310 2328 1311 2328 1312 2328 1312 2329 1311 2329 1313 2329 1312 2330 1313 2330 1314 2330 1314 2331 1313 2331 1315 2331 1314 2332 1315 2332 1316 2332 1050 2333 1052 2333 1278 2333 1278 2334 1052 2334 1317 2334 1278 2335 1317 2335 1299 2335 1299 2336 1317 2336 1318 2336 1299 2337 1318 2337 1301 2337 1301 2338 1318 2338 1319 2338 1301 2339 1319 2339 1303 2339 1303 2340 1319 2340 1320 2340 1303 2341 1320 2341 1305 2341 1305 2342 1320 2342 1321 2342 1305 2343 1321 2343 1307 2343 1307 2344 1321 2344 1322 2344 1307 2345 1322 2345 1309 2345 1309 2346 1322 2346 1323 2346 1309 2347 1323 2347 1311 2347 1311 2348 1323 2348 1324 2348 1311 2349 1324 2349 1313 2349 1313 2350 1324 2350 1325 2350 1313 2351 1325 2351 1315 2351 1326 2352 1327 2352 1328 2352 1328 2353 1327 2353 1329 2353 1328 2354 1329 2354 1330 2354 1330 2355 1329 2355 1331 2355 1330 2356 1331 2356 1332 2356 1332 2357 1331 2357 1333 2357 1332 2358 1333 2358 1334 2358 1335 2359 1336 2359 1337 2359 1337 2360 1336 2360 1338 2360 1337 2361 1338 2361 1339 2361 1339 2362 1338 2362 1340 2362 1339 2363 1340 2363 1341 2363 1341 2364 1340 2364 1342 2364 1341 2365 1342 2365 1343 2365 1343 2366 1342 2366 1344 2366 1343 2367 1344 2367 1345 2367 1345 2368 1344 2368 1346 2368 1345 2369 1346 2369 1347 2369 1336 2370 1326 2370 1338 2370 1338 2371 1326 2371 1328 2371 1338 2372 1328 2372 1340 2372 1340 2373 1328 2373 1330 2373 1340 2374 1330 2374 1342 2374 1342 2375 1330 2375 1332 2375 1342 2376 1332 2376 1344 2376 1344 2377 1332 2377 1334 2377 1344 2378 1334 2378 1346 2378 1348 2379 1349 2379 1350 2379 1053 2380 1055 2380 1168 2380 1168 2381 1055 2381 1300 2381 1168 2382 1300 2382 1226 2382 1226 2383 1300 2383 1302 2383 1226 2384 1302 2384 1194 2384 1194 2385 1302 2385 1304 2385 1194 2386 1304 2386 1195 2386 1195 2387 1304 2387 1306 2387 1195 2388 1306 2388 1214 2388 1214 2389 1306 2389 1308 2389 1214 2390 1308 2390 1216 2390 1216 2391 1308 2391 1310 2391 1216 2392 1310 2392 1218 2392 1218 2393 1310 2393 1312 2393 1218 2394 1312 2394 1220 2394 1220 2395 1312 2395 1314 2395 1220 2396 1314 2396 1222 2396 1222 2397 1314 2397 1316 2397 1222 2398 1316 2398 1224 2398 1351 2399 1279 2399 1352 2399 1352 2400 1279 2400 1281 2400 1352 2401 1281 2401 1353 2401 1353 2402 1281 2402 1283 2402 1353 2403 1283 2403 1354 2403 1354 2404 1283 2404 1285 2404 1354 2405 1285 2405 1355 2405 1355 2406 1285 2406 1356 2406 1355 2407 1356 2407 1357 2407 1357 2408 1356 2408 1358 2408 1357 2409 1358 2409 1359 2409 1360 2410 1361 2410 1362 2410 1362 2411 1361 2411 1363 2411 1362 2412 1363 2412 1364 2412 1365 2413 1351 2413 1366 2413 1366 2414 1351 2414 1352 2414 1366 2415 1352 2415 1367 2415 1367 2416 1352 2416 1353 2416 1367 2417 1353 2417 1368 2417 1368 2418 1353 2418 1354 2418 1368 2419 1354 2419 1369 2419 1369 2420 1354 2420 1355 2420 1369 2421 1355 2421 1370 2421 1370 2422 1355 2422 1357 2422 1370 2423 1357 2423 1371 2423 1371 2424 1357 2424 1359 2424 1371 2425 1359 2425 1372 2425 1298 2426 1365 2426 1297 2426 1297 2427 1365 2427 1366 2427 1297 2428 1366 2428 1296 2428 1296 2429 1366 2429 1367 2429 1296 2430 1367 2430 1294 2430 1294 2431 1367 2431 1368 2431 1294 2432 1368 2432 1292 2432 1292 2433 1368 2433 1369 2433 1292 2434 1369 2434 1290 2434 1290 2435 1369 2435 1370 2435 1290 2436 1370 2436 1288 2436 1288 2437 1370 2437 1371 2437 1288 2438 1371 2438 1286 2438 1286 2439 1371 2439 1372 2439 1286 2440 1372 2440 1373 2440 1374 2441 1375 2441 1376 2441 1376 2442 1375 2442 1377 2442 1376 2443 1377 2443 1378 2443 1378 2444 1377 2444 1379 2444 1378 2445 1379 2445 1380 2445 1380 2446 1379 2446 1381 2446 1380 2447 1381 2447 1382 2447 1382 2448 1381 2448 1383 2448 1382 2449 1383 2449 1384 2449 1384 2450 1383 2450 1046 2450 1384 2451 1046 2451 1385 2451 1385 2452 1046 2452 1045 2452 1385 2453 1045 2453 1047 2453 1047 2454 1049 2454 1385 2454 1385 2455 1049 2455 1295 2455 1385 2456 1295 2456 1384 2456 1384 2457 1295 2457 1293 2457 1384 2458 1293 2458 1382 2458 1382 2459 1293 2459 1291 2459 1382 2460 1291 2460 1380 2460 1380 2461 1291 2461 1289 2461 1380 2462 1289 2462 1378 2462 1378 2463 1289 2463 1287 2463 1378 2464 1287 2464 1376 2464 1376 2465 1287 2465 1286 2465 1376 2466 1286 2466 1374 2466 1374 2467 1286 2467 1373 2467 1374 2468 1373 2468 1386 2468 1387 2469 1388 2469 1389 2469 1390 2470 1388 2470 1391 2470 1391 2471 1388 2471 1387 2471 1391 2472 1387 2472 1392 2472 1393 2473 1086 2473 1394 2473 1394 2474 1086 2474 1088 2474 1394 2475 1088 2475 1395 2475 1395 2476 1088 2476 1089 2476 1395 2477 1089 2477 1396 2477 1396 2478 1089 2478 1397 2478 1398 2479 1393 2479 1399 2479 1399 2480 1393 2480 1394 2480 1399 2481 1394 2481 1400 2481 1400 2482 1394 2482 1395 2482 1400 2483 1395 2483 1401 2483 1401 2484 1395 2484 1396 2484 1401 2485 1396 2485 1402 2485 1363 2486 1398 2486 1364 2486 1364 2487 1398 2487 1399 2487 1364 2488 1399 2488 1403 2488 1403 2489 1399 2489 1400 2489 1403 2490 1400 2490 1404 2490 1404 2491 1400 2491 1401 2491 1404 2492 1401 2492 1405 2492 1405 2493 1401 2493 1402 2493 1405 2494 1402 2494 1406 2494 1360 2495 1362 2495 1407 2495 1407 2496 1362 2496 1364 2496 1407 2497 1364 2497 1408 2497 1408 2498 1364 2498 1403 2498 1408 2499 1403 2499 1409 2499 1409 2500 1403 2500 1404 2500 1409 2501 1404 2501 1410 2501 1410 2502 1404 2502 1405 2502 1410 2503 1405 2503 1411 2503 1411 2504 1405 2504 1406 2504 1411 2505 1406 2505 1412 2505 1413 2506 1414 2506 1415 2506 1415 2507 1414 2507 1416 2507 1415 2508 1416 2508 1417 2508 1417 2509 1416 2509 1418 2509 1417 2510 1418 2510 1419 2510 1419 2511 1418 2511 1420 2511 1419 2512 1420 2512 1421 2512 1421 2513 1420 2513 1422 2513 1421 2514 1422 2514 1423 2514 1423 2515 1422 2515 1424 2515 1423 2516 1424 2516 1425 2516 1425 2517 1424 2517 1426 2517 1425 2518 1426 2518 1044 2518 1044 2519 1046 2519 1425 2519 1425 2520 1046 2520 1383 2520 1425 2521 1383 2521 1423 2521 1423 2522 1383 2522 1381 2522 1423 2523 1381 2523 1421 2523 1421 2524 1381 2524 1379 2524 1421 2525 1379 2525 1419 2525 1419 2526 1379 2526 1377 2526 1419 2527 1377 2527 1417 2527 1417 2528 1377 2528 1375 2528 1417 2529 1375 2529 1415 2529 1415 2530 1375 2530 1374 2530 1415 2531 1374 2531 1413 2531 1413 2532 1374 2532 1386 2532 1413 2533 1386 2533 1427 2533 1428 2534 1335 2534 1429 2534 1429 2535 1335 2535 1337 2535 1429 2536 1337 2536 1430 2536 1430 2537 1337 2537 1339 2537 1430 2538 1339 2538 1431 2538 1431 2539 1339 2539 1341 2539 1431 2540 1341 2540 1432 2540 1432 2541 1341 2541 1343 2541 1432 2542 1343 2542 1433 2542 1433 2543 1343 2543 1345 2543 1433 2544 1345 2544 1434 2544 1434 2545 1345 2545 1347 2545 1434 2546 1347 2546 1435 2546 1427 2547 1428 2547 1413 2547 1413 2548 1428 2548 1429 2548 1413 2549 1429 2549 1414 2549 1414 2550 1429 2550 1430 2550 1414 2551 1430 2551 1416 2551 1416 2552 1430 2552 1431 2552 1416 2553 1431 2553 1418 2553 1418 2554 1431 2554 1432 2554 1418 2555 1432 2555 1420 2555 1420 2556 1432 2556 1433 2556 1420 2557 1433 2557 1422 2557 1422 2558 1433 2558 1434 2558 1422 2559 1434 2559 1424 2559 1424 2560 1434 2560 1435 2560 1424 2561 1435 2561 1426 2561 1436 2562 1390 2562 1437 2562 1437 2563 1390 2563 1391 2563 1437 2564 1391 2564 1438 2564 1438 2565 1391 2565 1392 2565 1438 2566 1392 2566 1439 2566 1042 2567 1041 2567 1440 2567 1440 2568 1041 2568 1441 2568 1440 2569 1441 2569 1442 2569 1442 2570 1441 2570 1443 2570 1442 2571 1443 2571 1349 2571 1444 2572 1436 2572 1445 2572 1445 2573 1436 2573 1437 2573 1445 2574 1437 2574 1446 2574 1446 2575 1437 2575 1438 2575 1446 2576 1438 2576 1447 2576 1447 2577 1438 2577 1439 2577 1447 2578 1439 2578 1448 2578 1449 2579 1361 2579 1450 2579 1450 2580 1361 2580 1360 2580 1450 2581 1360 2581 1451 2581 1451 2582 1360 2582 1407 2582 1451 2583 1407 2583 1452 2583 1452 2584 1407 2584 1408 2584 1452 2585 1408 2585 1453 2585 1453 2586 1408 2586 1409 2586 1453 2587 1409 2587 1454 2587 1454 2588 1409 2588 1410 2588 1454 2589 1410 2589 1455 2589 1455 2590 1410 2590 1411 2590 1455 2591 1411 2591 1456 2591 1456 2592 1411 2592 1412 2592 1456 2593 1412 2593 1457 2593 1349 2594 1348 2594 1442 2594 1442 2595 1348 2595 1458 2595 1442 2596 1458 2596 1440 2596 1440 2597 1458 2597 1459 2597 1440 2598 1459 2598 1042 2598 1042 2599 1459 2599 1460 2599 1042 2600 1460 2600 1043 2600 1043 2601 1460 2601 1444 2601 1043 2602 1444 2602 1461 2602 1461 2603 1444 2603 1445 2603 1461 2604 1445 2604 1462 2604 1462 2605 1445 2605 1446 2605 1462 2606 1446 2606 1463 2606 1463 2607 1446 2607 1447 2607 1463 2608 1447 2608 1464 2608 1464 2609 1447 2609 1448 2609 1464 2610 1448 2610 1465 2610 1466 2611 1350 2611 1467 2611 1467 2612 1350 2612 1349 2612 1467 2613 1349 2613 1468 2613 1468 2614 1349 2614 1443 2614 1468 2615 1443 2615 1469 2615 1469 2616 1443 2616 1441 2616 1469 2617 1441 2617 1470 2617 1470 2618 1441 2618 1041 2618 1470 2619 1041 2619 1471 2619 1471 2620 1041 2620 1043 2620 1471 2621 1043 2621 1472 2621 1472 2622 1043 2622 1461 2622 1472 2623 1461 2623 1473 2623 1473 2624 1461 2624 1462 2624 1473 2625 1462 2625 1474 2625 1474 2626 1462 2626 1463 2626 1474 2627 1463 2627 1475 2627 1475 2628 1463 2628 1464 2628 1475 2629 1464 2629 1064 2629 1064 2630 1464 2630 1465 2630 1064 2631 1465 2631 1062 2631 1476 2632 1101 2632 1477 2632 1477 2633 1101 2633 1094 2633 1477 2634 1094 2634 1478 2634 1478 2635 1094 2635 1096 2635 1478 2636 1096 2636 1479 2636 1479 2637 1096 2637 1098 2637 1479 2638 1098 2638 1480 2638 1480 2639 1098 2639 1100 2639 1480 2640 1100 2640 1093 2640 1093 2641 1100 2641 1481 2641 1093 2642 1481 2642 1092 2642 1059 2643 1482 2643 1060 2643 1060 2644 1482 2644 1483 2644 1060 2645 1483 2645 1061 2645 1061 2646 1483 2646 1484 2646 1061 2647 1484 2647 1485 2647 1485 2648 1484 2648 1486 2648 1485 2649 1486 2649 1487 2649 1487 2650 1486 2650 1488 2650 1487 2651 1488 2651 1489 2651 1489 2652 1488 2652 1490 2652 1489 2653 1490 2653 1491 2653 1491 2654 1490 2654 1492 2654 1491 2655 1492 2655 1493 2655 1493 2656 1492 2656 1494 2656 1493 2657 1494 2657 1495 2657 1495 2658 1494 2658 1496 2658 1495 2659 1496 2659 1497 2659 1482 2660 1397 2660 1483 2660 1483 2661 1397 2661 1089 2661 1483 2662 1089 2662 1484 2662 1484 2663 1089 2663 1087 2663 1484 2664 1087 2664 1486 2664 1486 2665 1087 2665 1086 2665 1486 2666 1086 2666 1488 2666 1488 2667 1086 2667 1393 2667 1488 2668 1393 2668 1490 2668 1490 2669 1393 2669 1398 2669 1490 2670 1398 2670 1492 2670 1492 2671 1398 2671 1363 2671 1492 2672 1363 2672 1494 2672 1494 2673 1363 2673 1361 2673 1494 2674 1361 2674 1496 2674 1496 2675 1361 2675 1449 2675 1498 2676 1131 2676 1499 2676 1499 2677 1131 2677 1128 2677 1499 2678 1128 2678 1500 2678 1500 2679 1128 2679 1126 2679 1500 2680 1126 2680 1501 2680 1501 2681 1126 2681 1124 2681 1501 2682 1124 2682 1502 2682 1502 2683 1124 2683 1122 2683 1502 2684 1122 2684 1503 2684 1503 2685 1122 2685 1058 2685 1503 2686 1058 2686 1504 2686 1504 2687 1058 2687 1057 2687 1504 2688 1057 2688 1505 2688 1039 2689 1038 2689 1506 2689 1506 2690 1038 2690 1507 2690 1506 2691 1507 2691 1120 2691 1107 2692 1101 2692 1106 2692 1106 2693 1101 2693 1476 2693 1106 2694 1476 2694 1104 2694 1104 2695 1476 2695 1508 2695 1104 2696 1508 2696 1110 2696 1110 2697 1508 2697 1509 2697 1110 2698 1509 2698 1115 2698 1510 2699 1498 2699 1511 2699 1511 2700 1498 2700 1499 2700 1511 2701 1499 2701 1512 2701 1512 2702 1499 2702 1500 2702 1512 2703 1500 2703 1513 2703 1513 2704 1500 2704 1501 2704 1513 2705 1501 2705 1514 2705 1514 2706 1501 2706 1502 2706 1514 2707 1502 2707 1515 2707 1515 2708 1502 2708 1503 2708 1515 2709 1503 2709 1516 2709 1516 2710 1503 2710 1504 2710 1516 2711 1504 2711 1517 2711 1517 2712 1504 2712 1505 2712 1517 2713 1505 2713 1518 2713 1118 2714 1120 2714 1519 2714 1519 2715 1120 2715 1507 2715 1519 2716 1507 2716 1520 2716 1520 2717 1507 2717 1038 2717 1520 2718 1038 2718 1521 2718 1521 2719 1038 2719 1040 2719 1521 2720 1040 2720 1522 2720 1056 2721 1118 2721 1057 2721 1057 2722 1118 2722 1519 2722 1057 2723 1519 2723 1505 2723 1505 2724 1519 2724 1520 2724 1505 2725 1520 2725 1518 2725 1518 2726 1520 2726 1521 2726 1518 2727 1521 2727 1523 2727 1523 2728 1521 2728 1522 2728 1523 2729 1522 2729 1524 2729 1524 2730 1522 2730 1525 2730 1524 2731 1525 2731 1526 2731 1527 2732 1526 2732 1528 2732 1528 2733 1526 2733 1525 2733 1528 2734 1525 2734 1529 2734 1529 2735 1525 2735 1522 2735 1529 2736 1522 2736 1530 2736 1530 2737 1522 2737 1040 2737 1530 2738 1040 2738 1036 2738 1036 2739 1040 2739 1039 2739 1036 2740 1039 2740 1037 2740 1037 2741 1039 2741 1506 2741 1133 2742 1510 2742 1134 2742 1134 2743 1510 2743 1511 2743 1134 2744 1511 2744 1136 2744 1136 2745 1511 2745 1512 2745 1136 2746 1512 2746 1143 2746 1143 2747 1512 2747 1513 2747 1143 2748 1513 2748 1142 2748 1142 2749 1513 2749 1514 2749 1142 2750 1514 2750 1147 2750 1147 2751 1514 2751 1515 2751 1147 2752 1515 2752 1153 2752 1153 2753 1515 2753 1516 2753 1153 2754 1516 2754 1155 2754 1155 2755 1516 2755 1517 2755 1155 2756 1517 2756 1157 2756 1157 2757 1517 2757 1518 2757 1157 2758 1518 2758 1159 2758 1159 2759 1518 2759 1523 2759 1159 2760 1523 2760 1160 2760 1160 2761 1523 2761 1524 2761 1160 2762 1524 2762 1255 2762 1255 2763 1524 2763 1526 2763 1255 2764 1526 2764 1256 2764 1256 2765 1526 2765 1527 2765 1256 2766 1527 2766 1266 2766 1090 2767 1059 2767 1091 2767 1091 2768 1059 2768 1061 2768 1091 2769 1061 2769 1093 2769 1093 2770 1061 2770 1485 2770 1093 2771 1485 2771 1480 2771 1480 2772 1485 2772 1487 2772 1480 2773 1487 2773 1479 2773 1479 2774 1487 2774 1489 2774 1479 2775 1489 2775 1478 2775 1478 2776 1489 2776 1491 2776 1478 2777 1491 2777 1477 2777 1477 2778 1491 2778 1493 2778 1477 2779 1493 2779 1476 2779 1476 2780 1493 2780 1495 2780 1476 2781 1495 2781 1508 2781 1508 2782 1495 2782 1497 2782 1508 2783 1497 2783 1509 2783 1119 2784 1113 2784 1120 2784 1120 2785 1113 2785 1115 2785 1120 2786 1115 2786 1506 2786 1506 2787 1115 2787 1509 2787 1506 2788 1509 2788 1037 2788 1037 2789 1509 2789 1497 2789 1037 2790 1497 2790 1035 2790 1035 2791 1497 2791 1496 2791 1035 2792 1496 2792 1531 2792 1531 2793 1496 2793 1449 2793 1531 2794 1449 2794 1532 2794 1532 2795 1449 2795 1450 2795 1532 2796 1450 2796 1533 2796 1533 2797 1450 2797 1451 2797 1533 2798 1451 2798 1389 2798 1389 2799 1451 2799 1452 2799 1389 2800 1452 2800 1387 2800 1387 2801 1452 2801 1453 2801 1387 2802 1453 2802 1392 2802 1392 2803 1453 2803 1454 2803 1392 2804 1454 2804 1439 2804 1439 2805 1454 2805 1455 2805 1439 2806 1455 2806 1448 2806 1448 2807 1455 2807 1456 2807 1448 2808 1456 2808 1465 2808 1465 2809 1456 2809 1457 2809 1465 2810 1457 2810 1062 2810 1173 2811 1534 2811 1174 2811 1174 2812 1534 2812 1535 2812 1174 2813 1535 2813 1176 2813 1176 2814 1535 2814 1536 2814 1176 2815 1536 2815 1178 2815 1178 2816 1536 2816 1277 2816 1178 2817 1277 2817 1179 2817 1179 2818 1277 2818 1276 2818 1179 2819 1276 2819 1191 2819 1191 2820 1276 2820 1275 2820 1191 2821 1275 2821 1192 2821 1192 2822 1275 2822 1274 2822 1192 2823 1274 2823 1211 2823 1211 2824 1274 2824 1273 2824 1211 2825 1273 2825 1212 2825 1212 2826 1273 2826 1272 2826 1212 2827 1272 2827 1171 2827 1171 2828 1272 2828 1271 2828 1171 2829 1271 2829 1169 2829 1169 2830 1271 2830 1270 2830 1169 2831 1270 2831 1053 2831 1053 2832 1270 2832 1269 2832 1053 2833 1269 2833 1054 2833 1054 2834 1269 2834 1268 2834 1054 2835 1268 2835 1050 2835 1050 2836 1268 2836 1267 2836 1050 2837 1267 2837 1051 2837 1051 2838 1267 2838 1266 2838 1051 2839 1266 2839 1298 2839 1298 2840 1266 2840 1527 2840 1298 2841 1527 2841 1365 2841 1365 2842 1527 2842 1528 2842 1365 2843 1528 2843 1351 2843 1351 2844 1528 2844 1529 2844 1351 2845 1529 2845 1279 2845 1279 2846 1529 2846 1530 2846 1279 2847 1530 2847 1280 2847 1280 2848 1530 2848 1036 2848 1280 2849 1036 2849 1282 2849 1282 2850 1036 2850 1035 2850 1282 2851 1035 2851 1284 2851 1284 2852 1035 2852 1531 2852 1284 2853 1531 2853 1285 2853 1285 2854 1531 2854 1532 2854 1285 2855 1532 2855 1356 2855 1356 2856 1532 2856 1533 2856 1356 2857 1533 2857 1358 2857 1358 2858 1533 2858 1389 2858 1358 2859 1389 2859 1359 2859 1359 2860 1389 2860 1388 2860 1359 2861 1388 2861 1372 2861 1372 2862 1388 2862 1390 2862 1372 2863 1390 2863 1373 2863 1373 2864 1390 2864 1436 2864 1373 2865 1436 2865 1386 2865 1386 2866 1436 2866 1444 2866 1386 2867 1444 2867 1427 2867 1427 2868 1444 2868 1460 2868 1427 2869 1460 2869 1428 2869 1428 2870 1460 2870 1459 2870 1428 2871 1459 2871 1335 2871 1335 2872 1459 2872 1458 2872 1335 2873 1458 2873 1336 2873 1336 2874 1458 2874 1348 2874 1336 2875 1348 2875 1326 2875 1326 2876 1348 2876 1350 2876 1326 2877 1350 2877 1327 2877 1327 2878 1350 2878 1466 2878 1327 2879 1466 2879 1329 2879 1329 2880 1466 2880 1537 2880 1329 2881 1537 2881 1331 2881 1331 2882 1537 2882 1325 2882 1331 2883 1325 2883 1333 2883 1333 2884 1325 2884 1324 2884 1333 2885 1324 2885 1334 2885 1334 2886 1324 2886 1323 2886 1334 2887 1323 2887 1346 2887 1346 2888 1323 2888 1322 2888 1346 2889 1322 2889 1347 2889 1347 2890 1322 2890 1321 2890 1347 2891 1321 2891 1435 2891 1435 2892 1321 2892 1320 2892 1435 2893 1320 2893 1426 2893 1426 2894 1320 2894 1319 2894 1426 2895 1319 2895 1044 2895 1044 2896 1319 2896 1318 2896 1044 2897 1318 2897 1045 2897 1045 2898 1318 2898 1317 2898 1045 2899 1317 2899 1047 2899 1047 2900 1317 2900 1052 2900 1047 2901 1052 2901 1048 2901 1048 2902 1052 2902 1051 2902 1048 2903 1051 2903 1298 2903 1538 2904 1470 2904 1471 2904 1539 2905 1540 2905 1541 2905 1542 2906 1543 2906 1544 2906 1545 2907 1546 2907 1547 2907 1548 2908 1549 2908 1550 2908 1551 2909 1467 2909 1468 2909 1552 2910 1553 2910 1554 2910 1555 2911 1556 2911 1557 2911 1558 2912 1559 2912 1556 2912 1560 2913 1561 2913 1559 2913 1562 2914 1563 2914 1561 2914 1564 2915 1565 2915 1563 2915 1566 2916 1064 2916 1063 2916 1567 2917 1568 2917 1569 2917 1570 2918 1571 2918 1572 2918 1573 2919 1574 2919 1575 2919 1576 2920 1577 2920 1578 2920 1579 2921 1580 2921 1581 2921 1576 2922 1578 2922 1582 2922 1582 2923 1578 2923 1583 2923 1582 2924 1583 2924 1584 2924 1584 2925 1583 2925 1585 2925 1584 2926 1585 2926 1586 2926 1587 2927 1588 2927 1589 2927 1589 2928 1588 2928 1590 2928 1589 2929 1590 2929 1591 2929 1591 2930 1590 2930 1586 2930 1591 2931 1586 2931 1592 2931 1593 2932 1594 2932 1587 2932 1587 2933 1594 2933 1595 2933 1587 2934 1595 2934 1588 2934 1587 2935 1596 2935 1593 2935 1593 2936 1596 2936 1597 2936 1593 2937 1597 2937 1598 2937 1598 2938 1597 2938 1599 2938 1599 2939 1597 2939 1600 2939 1599 2940 1600 2940 1601 2940 1601 2941 1600 2941 1602 2941 1601 2942 1602 2942 1603 2942 1604 2943 1605 2943 1602 2943 1602 2944 1605 2944 1606 2944 1602 2945 1606 2945 1603 2945 1607 2946 1608 2946 1604 2946 1604 2947 1608 2947 1609 2947 1604 2948 1609 2948 1605 2948 1575 2949 1607 2949 1610 2949 1611 2950 1612 2950 1613 2950 1614 2951 1615 2951 1616 2951 1616 2952 1615 2952 1617 2952 1616 2953 1617 2953 1618 2953 1618 2954 1617 2954 1619 2954 1618 2955 1619 2955 1620 2955 1620 2956 1619 2956 1621 2956 1620 2957 1621 2957 1622 2957 1622 2958 1621 2958 1623 2958 1622 2959 1623 2959 1624 2959 1624 2960 1623 2960 1611 2960 1624 2961 1611 2961 1625 2961 1625 2962 1611 2962 1613 2962 1570 2963 1572 2963 1626 2963 1626 2964 1572 2964 1627 2964 1626 2965 1627 2965 1628 2965 1629 2966 1630 2966 1631 2966 1631 2967 1632 2967 1629 2967 1629 2968 1632 2968 1633 2968 1629 2969 1633 2969 1627 2969 1627 2970 1633 2970 1634 2970 1627 2971 1634 2971 1628 2971 1635 2972 1636 2972 1637 2972 1637 2973 1636 2973 1638 2973 1637 2974 1638 2974 1630 2974 1630 2975 1638 2975 1639 2975 1630 2976 1639 2976 1631 2976 1640 2977 1641 2977 1635 2977 1635 2978 1641 2978 1642 2978 1635 2979 1642 2979 1636 2979 1635 2980 1643 2980 1640 2980 1640 2981 1643 2981 1644 2981 1640 2982 1644 2982 1645 2982 1646 2983 1647 2983 1648 2983 1647 2984 1649 2984 1650 2984 1650 2985 1649 2985 1651 2985 1650 2986 1651 2986 1644 2986 1644 2987 1651 2987 1652 2987 1644 2988 1652 2988 1645 2988 1648 2989 1653 2989 1646 2989 1646 2990 1653 2990 1654 2990 1646 2991 1654 2991 1655 2991 1655 2992 1654 2992 1656 2992 1655 2993 1656 2993 1657 2993 1657 2994 1656 2994 1658 2994 1656 2995 1659 2995 1658 2995 1658 2996 1659 2996 1660 2996 1658 2997 1660 2997 1661 2997 1661 2998 1660 2998 1662 2998 1662 2999 1660 2999 1541 2999 1662 3000 1541 3000 1663 3000 1663 3001 1541 3001 1540 3001 1663 3002 1540 3002 1664 3002 1607 3003 1604 3003 1610 3003 1610 3004 1604 3004 1665 3004 1610 3005 1665 3005 1666 3005 1573 3006 1575 3006 1667 3006 1667 3007 1575 3007 1610 3007 1667 3008 1610 3008 1668 3008 1668 3009 1610 3009 1666 3009 1668 3010 1666 3010 1669 3010 1670 3011 1671 3011 1672 3011 1672 3012 1671 3012 1673 3012 1672 3013 1673 3013 1674 3013 1554 3014 1670 3014 1675 3014 1675 3015 1670 3015 1672 3015 1675 3016 1672 3016 1676 3016 1676 3017 1672 3017 1674 3017 1676 3018 1674 3018 1677 3018 1554 3019 1553 3019 1670 3019 1670 3020 1553 3020 1678 3020 1670 3021 1678 3021 1671 3021 1671 3022 1678 3022 1679 3022 1671 3023 1679 3023 1673 3023 1677 3024 1680 3024 1681 3024 1682 3025 1683 3025 1684 3025 1677 3026 1681 3026 1676 3026 1676 3027 1681 3027 1685 3027 1676 3028 1685 3028 1675 3028 1675 3029 1685 3029 1686 3029 1675 3030 1686 3030 1554 3030 1586 3031 1585 3031 1592 3031 1592 3032 1585 3032 1583 3032 1592 3033 1583 3033 1687 3033 1687 3034 1583 3034 1578 3034 1687 3035 1578 3035 1688 3035 1688 3036 1689 3036 1687 3036 1687 3037 1689 3037 1690 3037 1687 3038 1690 3038 1592 3038 1592 3039 1690 3039 1691 3039 1592 3040 1691 3040 1591 3040 1591 3041 1691 3041 1692 3041 1591 3042 1692 3042 1589 3042 1589 3043 1692 3043 1693 3043 1589 3044 1693 3044 1587 3044 1587 3045 1693 3045 1694 3045 1587 3046 1694 3046 1596 3046 1596 3047 1694 3047 1695 3047 1596 3048 1695 3048 1597 3048 1597 3049 1695 3049 1696 3049 1597 3050 1696 3050 1600 3050 1600 3051 1696 3051 1697 3051 1600 3052 1697 3052 1602 3052 1689 3053 1698 3053 1690 3053 1690 3054 1698 3054 1699 3054 1690 3055 1699 3055 1691 3055 1691 3056 1699 3056 1700 3056 1691 3057 1700 3057 1692 3057 1692 3058 1700 3058 1701 3058 1692 3059 1701 3059 1693 3059 1693 3060 1701 3060 1702 3060 1693 3061 1702 3061 1694 3061 1694 3062 1702 3062 1703 3062 1694 3063 1703 3063 1695 3063 1695 3064 1703 3064 1704 3064 1695 3065 1704 3065 1696 3065 1696 3066 1704 3066 1705 3066 1696 3067 1705 3067 1697 3067 1697 3068 1705 3068 1706 3068 1697 3069 1706 3069 1602 3069 1602 3070 1706 3070 1707 3070 1602 3071 1707 3071 1604 3071 1604 3072 1707 3072 1708 3072 1604 3073 1708 3073 1665 3073 1698 3074 1709 3074 1699 3074 1699 3075 1709 3075 1710 3075 1699 3076 1710 3076 1700 3076 1700 3077 1710 3077 1711 3077 1700 3078 1711 3078 1701 3078 1701 3079 1711 3079 1712 3079 1701 3080 1712 3080 1702 3080 1702 3081 1712 3081 1713 3081 1702 3082 1713 3082 1703 3082 1703 3083 1713 3083 1714 3083 1703 3084 1714 3084 1704 3084 1704 3085 1714 3085 1715 3085 1704 3086 1715 3086 1705 3086 1705 3087 1715 3087 1716 3087 1705 3088 1716 3088 1706 3088 1706 3089 1716 3089 1717 3089 1706 3090 1717 3090 1707 3090 1707 3091 1717 3091 1718 3091 1707 3092 1718 3092 1708 3092 1708 3093 1718 3093 1719 3093 1708 3094 1719 3094 1665 3094 1665 3095 1719 3095 1720 3095 1665 3096 1720 3096 1666 3096 1666 3097 1720 3097 1721 3097 1666 3098 1721 3098 1669 3098 1669 3099 1721 3099 1722 3099 1565 3100 1564 3100 1723 3100 1723 3101 1564 3101 1724 3101 1723 3102 1724 3102 1683 3102 1243 3103 1725 3103 1196 3103 1196 3104 1725 3104 1726 3104 1196 3105 1726 3105 1197 3105 1197 3106 1726 3106 1727 3106 1197 3107 1727 3107 1180 3107 1180 3108 1727 3108 1728 3108 1180 3109 1728 3109 1181 3109 1181 3110 1728 3110 1579 3110 1181 3111 1579 3111 1082 3111 1082 3112 1579 3112 1581 3112 1082 3113 1581 3113 1083 3113 1682 3114 1684 3114 1729 3114 1729 3115 1684 3115 1730 3115 1729 3116 1730 3116 1731 3116 1731 3117 1730 3117 1732 3117 1731 3118 1732 3118 1733 3118 1733 3119 1732 3119 1734 3119 1733 3120 1734 3120 1735 3120 1735 3121 1734 3121 1736 3121 1735 3122 1736 3122 1737 3122 1738 3123 1552 3123 1737 3123 1737 3124 1552 3124 1554 3124 1737 3125 1554 3125 1735 3125 1735 3126 1554 3126 1686 3126 1735 3127 1686 3127 1733 3127 1733 3128 1686 3128 1685 3128 1733 3129 1685 3129 1731 3129 1731 3130 1685 3130 1681 3130 1731 3131 1681 3131 1729 3131 1729 3132 1681 3132 1680 3132 1729 3133 1680 3133 1682 3133 1739 3134 1740 3134 1741 3134 1739 3135 1741 3135 1742 3135 1742 3136 1741 3136 1743 3136 1742 3137 1743 3137 1744 3137 1744 3138 1745 3138 1742 3138 1742 3139 1745 3139 1738 3139 1742 3140 1738 3140 1739 3140 1739 3141 1738 3141 1737 3141 1739 3142 1737 3142 1740 3142 1740 3143 1737 3143 1736 3143 1563 3144 1562 3144 1564 3144 1564 3145 1562 3145 1746 3145 1564 3146 1746 3146 1724 3146 1724 3147 1746 3147 1747 3147 1724 3148 1747 3148 1748 3148 1748 3149 1747 3149 1749 3149 1748 3150 1749 3150 1750 3150 1750 3151 1749 3151 1751 3151 1750 3152 1751 3152 1752 3152 1752 3153 1751 3153 1753 3153 1752 3154 1753 3154 1754 3154 1754 3155 1753 3155 1755 3155 1754 3156 1755 3156 1756 3156 1756 3157 1755 3157 1757 3157 1756 3158 1757 3158 1758 3158 1758 3159 1757 3159 1759 3159 1758 3160 1759 3160 1760 3160 1559 3161 1558 3161 1560 3161 1560 3162 1558 3162 1761 3162 1560 3163 1761 3163 1762 3163 1762 3164 1761 3164 1763 3164 1762 3165 1763 3165 1764 3165 1764 3166 1763 3166 1765 3166 1764 3167 1765 3167 1766 3167 1766 3168 1765 3168 1767 3168 1766 3169 1767 3169 1768 3169 1768 3170 1767 3170 1769 3170 1768 3171 1769 3171 1770 3171 1770 3172 1769 3172 1771 3172 1770 3173 1771 3173 1772 3173 1772 3174 1771 3174 1773 3174 1772 3175 1773 3175 1774 3175 1774 3176 1773 3176 1775 3176 1774 3177 1775 3177 1776 3177 1561 3178 1560 3178 1562 3178 1562 3179 1560 3179 1762 3179 1562 3180 1762 3180 1746 3180 1746 3181 1762 3181 1764 3181 1746 3182 1764 3182 1747 3182 1747 3183 1764 3183 1766 3183 1747 3184 1766 3184 1749 3184 1749 3185 1766 3185 1768 3185 1749 3186 1768 3186 1751 3186 1751 3187 1768 3187 1770 3187 1751 3188 1770 3188 1753 3188 1753 3189 1770 3189 1772 3189 1753 3190 1772 3190 1755 3190 1755 3191 1772 3191 1774 3191 1755 3192 1774 3192 1757 3192 1757 3193 1774 3193 1776 3193 1757 3194 1776 3194 1759 3194 1683 3195 1724 3195 1684 3195 1684 3196 1724 3196 1748 3196 1684 3197 1748 3197 1730 3197 1730 3198 1748 3198 1750 3198 1730 3199 1750 3199 1732 3199 1732 3200 1750 3200 1752 3200 1732 3201 1752 3201 1734 3201 1734 3202 1752 3202 1754 3202 1734 3203 1754 3203 1736 3203 1736 3204 1754 3204 1756 3204 1736 3205 1756 3205 1740 3205 1740 3206 1756 3206 1758 3206 1740 3207 1758 3207 1741 3207 1741 3208 1758 3208 1760 3208 1741 3209 1760 3209 1743 3209 1777 3210 1778 3210 1779 3210 1779 3211 1778 3211 1780 3211 1779 3212 1780 3212 1781 3212 1781 3213 1780 3213 1782 3213 1781 3214 1782 3214 1783 3214 1783 3215 1782 3215 1784 3215 1783 3216 1784 3216 1785 3216 1785 3217 1784 3217 1786 3217 1785 3218 1786 3218 1787 3218 1787 3219 1786 3219 1788 3219 1787 3220 1788 3220 1789 3220 1789 3221 1788 3221 1790 3221 1789 3222 1790 3222 1791 3222 1791 3223 1790 3223 1792 3223 1793 3224 1777 3224 1794 3224 1794 3225 1777 3225 1779 3225 1794 3226 1779 3226 1795 3226 1795 3227 1779 3227 1781 3227 1795 3228 1781 3228 1796 3228 1796 3229 1781 3229 1783 3229 1796 3230 1783 3230 1797 3230 1797 3231 1783 3231 1785 3231 1797 3232 1785 3232 1798 3232 1798 3233 1785 3233 1787 3233 1798 3234 1787 3234 1799 3234 1799 3235 1787 3235 1789 3235 1799 3236 1789 3236 1800 3236 1800 3237 1789 3237 1791 3237 1556 3238 1555 3238 1558 3238 1558 3239 1555 3239 1801 3239 1558 3240 1801 3240 1761 3240 1761 3241 1801 3241 1802 3241 1761 3242 1802 3242 1763 3242 1763 3243 1802 3243 1803 3243 1763 3244 1803 3244 1765 3244 1765 3245 1803 3245 1804 3245 1765 3246 1804 3246 1767 3246 1767 3247 1804 3247 1805 3247 1767 3248 1805 3248 1769 3248 1769 3249 1805 3249 1806 3249 1769 3250 1806 3250 1771 3250 1771 3251 1806 3251 1807 3251 1771 3252 1807 3252 1773 3252 1773 3253 1807 3253 1808 3253 1773 3254 1808 3254 1775 3254 1809 3255 1810 3255 1811 3255 1811 3256 1810 3256 1812 3256 1811 3257 1812 3257 1813 3257 1813 3258 1812 3258 1814 3258 1813 3259 1814 3259 1815 3259 1815 3260 1814 3260 1816 3260 1815 3261 1816 3261 1817 3261 1817 3262 1816 3262 1818 3262 1817 3263 1818 3263 1819 3263 1819 3264 1818 3264 1820 3264 1810 3265 1821 3265 1812 3265 1812 3266 1821 3266 1822 3266 1812 3267 1822 3267 1814 3267 1814 3268 1822 3268 1823 3268 1814 3269 1823 3269 1816 3269 1816 3270 1823 3270 1824 3270 1816 3271 1824 3271 1818 3271 1818 3272 1824 3272 1825 3272 1818 3273 1825 3273 1820 3273 1820 3274 1825 3274 1826 3274 1827 3275 1828 3275 1829 3275 1830 3276 1831 3276 1828 3276 1821 3277 1832 3277 1822 3277 1822 3278 1832 3278 1833 3278 1822 3279 1833 3279 1823 3279 1823 3280 1833 3280 1834 3280 1823 3281 1834 3281 1824 3281 1824 3282 1834 3282 1835 3282 1824 3283 1835 3283 1825 3283 1825 3284 1835 3284 1836 3284 1825 3285 1836 3285 1826 3285 1826 3286 1836 3286 1837 3286 1832 3287 1838 3287 1833 3287 1833 3288 1838 3288 1839 3288 1833 3289 1839 3289 1834 3289 1834 3290 1839 3290 1840 3290 1834 3291 1840 3291 1835 3291 1835 3292 1840 3292 1841 3292 1835 3293 1841 3293 1836 3293 1836 3294 1841 3294 1842 3294 1836 3295 1842 3295 1837 3295 1837 3296 1842 3296 1843 3296 1844 3297 1845 3297 1846 3297 1846 3298 1845 3298 1847 3298 1846 3299 1847 3299 1848 3299 1848 3300 1847 3300 1849 3300 1848 3301 1849 3301 1850 3301 1850 3302 1849 3302 1851 3302 1850 3303 1851 3303 1852 3303 1853 3304 1843 3304 1852 3304 1852 3305 1843 3305 1842 3305 1852 3306 1842 3306 1850 3306 1850 3307 1842 3307 1841 3307 1850 3308 1841 3308 1848 3308 1848 3309 1841 3309 1840 3309 1848 3310 1840 3310 1846 3310 1846 3311 1840 3311 1839 3311 1846 3312 1839 3312 1844 3312 1844 3313 1839 3313 1838 3313 1854 3314 1855 3314 1856 3314 1831 3315 1830 3315 1857 3315 1857 3316 1830 3316 1858 3316 1857 3317 1858 3317 1859 3317 1859 3318 1858 3318 1860 3318 1859 3319 1860 3319 1861 3319 1861 3320 1860 3320 1862 3320 1861 3321 1862 3321 1863 3321 1863 3322 1862 3322 1864 3322 1863 3323 1864 3323 1865 3323 1865 3324 1864 3324 1866 3324 1865 3325 1866 3325 1867 3325 1828 3326 1827 3326 1830 3326 1830 3327 1827 3327 1868 3327 1830 3328 1868 3328 1858 3328 1858 3329 1868 3329 1869 3329 1858 3330 1869 3330 1860 3330 1860 3331 1869 3331 1870 3331 1860 3332 1870 3332 1862 3332 1862 3333 1870 3333 1871 3333 1862 3334 1871 3334 1864 3334 1864 3335 1871 3335 1872 3335 1864 3336 1872 3336 1866 3336 1466 3337 1467 3337 1873 3337 1873 3338 1467 3338 1551 3338 1873 3339 1551 3339 1853 3339 1855 3340 1854 3340 1874 3340 1874 3341 1854 3341 1875 3341 1874 3342 1875 3342 1876 3342 1876 3343 1875 3343 1877 3343 1876 3344 1877 3344 1878 3344 1778 3345 1879 3345 1780 3345 1780 3346 1879 3346 1880 3346 1780 3347 1880 3347 1782 3347 1782 3348 1880 3348 1881 3348 1782 3349 1881 3349 1784 3349 1784 3350 1881 3350 1882 3350 1784 3351 1882 3351 1786 3351 1786 3352 1882 3352 1883 3352 1786 3353 1883 3353 1788 3353 1788 3354 1883 3354 1884 3354 1788 3355 1884 3355 1790 3355 1790 3356 1884 3356 1885 3356 1790 3357 1885 3357 1792 3357 1853 3358 1852 3358 1873 3358 1873 3359 1852 3359 1851 3359 1873 3360 1851 3360 1466 3360 1466 3361 1851 3361 1849 3361 1466 3362 1849 3362 1537 3362 1537 3363 1849 3363 1847 3363 1537 3364 1847 3364 1325 3364 1325 3365 1847 3365 1845 3365 1325 3366 1845 3366 1315 3366 1315 3367 1845 3367 1844 3367 1315 3368 1844 3368 1316 3368 1316 3369 1844 3369 1838 3369 1316 3370 1838 3370 1224 3370 1224 3371 1838 3371 1832 3371 1224 3372 1832 3372 1225 3372 1225 3373 1832 3373 1821 3373 1225 3374 1821 3374 1235 3374 1235 3375 1821 3375 1810 3375 1235 3376 1810 3376 1243 3376 1243 3377 1810 3377 1809 3377 1243 3378 1809 3378 1725 3378 1886 3379 1887 3379 1888 3379 1888 3380 1887 3380 1889 3380 1888 3381 1889 3381 1890 3381 1890 3382 1889 3382 1891 3382 1548 3383 1550 3383 1892 3383 1893 3384 1894 3384 1886 3384 1886 3385 1894 3385 1895 3385 1886 3386 1895 3386 1887 3386 1549 3387 1546 3387 1550 3387 1550 3388 1546 3388 1545 3388 1550 3389 1545 3389 1544 3389 1544 3390 1543 3390 1550 3390 1550 3391 1543 3391 1896 3391 1550 3392 1896 3392 1892 3392 1897 3393 1898 3393 1542 3393 1542 3394 1898 3394 1899 3394 1542 3395 1899 3395 1543 3395 1543 3396 1899 3396 1900 3396 1543 3397 1900 3397 1896 3397 1896 3398 1900 3398 1901 3398 1896 3399 1901 3399 1892 3399 1892 3400 1901 3400 1902 3400 1903 3401 1664 3401 1904 3401 1904 3402 1664 3402 1540 3402 1904 3403 1540 3403 1905 3403 1905 3404 1540 3404 1539 3404 1905 3405 1539 3405 1906 3405 1907 3406 1908 3406 1909 3406 1909 3407 1908 3407 1910 3407 1909 3408 1910 3408 1911 3408 1912 3409 1913 3409 1914 3409 1914 3410 1913 3410 1915 3410 1914 3411 1915 3411 1916 3411 1916 3412 1915 3412 1894 3412 1916 3413 1894 3413 1917 3413 1917 3414 1894 3414 1893 3414 1878 3415 1910 3415 1876 3415 1876 3416 1910 3416 1908 3416 1876 3417 1908 3417 1874 3417 1874 3418 1908 3418 1907 3418 1874 3419 1907 3419 1855 3419 1913 3420 1547 3420 1915 3420 1915 3421 1547 3421 1546 3421 1915 3422 1546 3422 1894 3422 1894 3423 1546 3423 1549 3423 1894 3424 1549 3424 1895 3424 1895 3425 1549 3425 1548 3425 1895 3426 1548 3426 1887 3426 1887 3427 1548 3427 1892 3427 1887 3428 1892 3428 1889 3428 1889 3429 1892 3429 1902 3429 1889 3430 1902 3430 1891 3430 1918 3431 1878 3431 1919 3431 1919 3432 1878 3432 1877 3432 1919 3433 1877 3433 1920 3433 1920 3434 1877 3434 1875 3434 1920 3435 1875 3435 1921 3435 1921 3436 1875 3436 1854 3436 1921 3437 1854 3437 1922 3437 1922 3438 1854 3438 1856 3438 1922 3439 1856 3439 1923 3439 1867 3440 1918 3440 1865 3440 1865 3441 1918 3441 1919 3441 1865 3442 1919 3442 1863 3442 1863 3443 1919 3443 1920 3443 1863 3444 1920 3444 1861 3444 1861 3445 1920 3445 1921 3445 1861 3446 1921 3446 1859 3446 1859 3447 1921 3447 1922 3447 1859 3448 1922 3448 1857 3448 1857 3449 1922 3449 1923 3449 1857 3450 1923 3450 1831 3450 1897 3451 1542 3451 1924 3451 1924 3452 1542 3452 1544 3452 1924 3453 1544 3453 1925 3453 1925 3454 1544 3454 1545 3454 1925 3455 1545 3455 1926 3455 1926 3456 1545 3456 1547 3456 1926 3457 1547 3457 1927 3457 1927 3458 1547 3458 1913 3458 1927 3459 1913 3459 1928 3459 1928 3460 1913 3460 1912 3460 1928 3461 1912 3461 1929 3461 1867 3462 1929 3462 1918 3462 1918 3463 1929 3463 1912 3463 1918 3464 1912 3464 1878 3464 1878 3465 1912 3465 1914 3465 1878 3466 1914 3466 1910 3466 1910 3467 1914 3467 1916 3467 1910 3468 1916 3468 1911 3468 1911 3469 1916 3469 1917 3469 1911 3470 1917 3470 1930 3470 1930 3471 1917 3471 1893 3471 1930 3472 1893 3472 1931 3472 1931 3473 1893 3473 1886 3473 1931 3474 1886 3474 1932 3474 1932 3475 1886 3475 1888 3475 1932 3476 1888 3476 1933 3476 1933 3477 1888 3477 1890 3477 1933 3478 1890 3478 1934 3478 1934 3479 1890 3479 1891 3479 1934 3480 1891 3480 1935 3480 1470 3481 1538 3481 1469 3481 1469 3482 1538 3482 1936 3482 1469 3483 1936 3483 1468 3483 1569 3484 1903 3484 1567 3484 1567 3485 1903 3485 1904 3485 1567 3486 1904 3486 1937 3486 1937 3487 1904 3487 1905 3487 1937 3488 1905 3488 1938 3488 1938 3489 1905 3489 1906 3489 1938 3490 1906 3490 1939 3490 1568 3491 1567 3491 1940 3491 1940 3492 1567 3492 1937 3492 1940 3493 1937 3493 1941 3493 1941 3494 1937 3494 1938 3494 1941 3495 1938 3495 1942 3495 1942 3496 1938 3496 1939 3496 1942 3497 1939 3497 1943 3497 1063 3498 1569 3498 1566 3498 1566 3499 1569 3499 1568 3499 1566 3500 1568 3500 1944 3500 1944 3501 1568 3501 1940 3501 1944 3502 1940 3502 1945 3502 1945 3503 1940 3503 1941 3503 1945 3504 1941 3504 1946 3504 1946 3505 1941 3505 1942 3505 1946 3506 1942 3506 1947 3506 1947 3507 1942 3507 1943 3507 1947 3508 1943 3508 1948 3508 1064 3509 1566 3509 1475 3509 1475 3510 1566 3510 1944 3510 1475 3511 1944 3511 1474 3511 1474 3512 1944 3512 1945 3512 1474 3513 1945 3513 1473 3513 1473 3514 1945 3514 1946 3514 1473 3515 1946 3515 1472 3515 1472 3516 1946 3516 1947 3516 1472 3517 1947 3517 1471 3517 1471 3518 1947 3518 1948 3518 1471 3519 1948 3519 1538 3519 1538 3520 1948 3520 1949 3520 1538 3521 1949 3521 1936 3521 1647 3522 1650 3522 1648 3522 1648 3523 1650 3523 1644 3523 1648 3524 1644 3524 1950 3524 1950 3525 1644 3525 1643 3525 1950 3526 1643 3526 1951 3526 1951 3527 1643 3527 1635 3527 1951 3528 1635 3528 1952 3528 1952 3529 1635 3529 1637 3529 1952 3530 1637 3530 1953 3530 1898 3531 1954 3531 1899 3531 1899 3532 1954 3532 1955 3532 1899 3533 1955 3533 1900 3533 1900 3534 1955 3534 1956 3534 1900 3535 1956 3535 1901 3535 1901 3536 1956 3536 1957 3536 1901 3537 1957 3537 1902 3537 1902 3538 1957 3538 1958 3538 1902 3539 1958 3539 1891 3539 1891 3540 1958 3540 1959 3540 1891 3541 1959 3541 1935 3541 1935 3542 1959 3542 1960 3542 1953 3543 1637 3543 1961 3543 1961 3544 1637 3544 1630 3544 1961 3545 1630 3545 1962 3545 1962 3546 1630 3546 1629 3546 1962 3547 1629 3547 1963 3547 1963 3548 1629 3548 1627 3548 1963 3549 1627 3549 1964 3549 1964 3550 1627 3550 1572 3550 1964 3551 1572 3551 1614 3551 1614 3552 1572 3552 1571 3552 1614 3553 1571 3553 1615 3553 1613 3554 1965 3554 1625 3554 1625 3555 1965 3555 1966 3555 1625 3556 1966 3556 1624 3556 1624 3557 1966 3557 1967 3557 1624 3558 1967 3558 1622 3558 1622 3559 1967 3559 1968 3559 1622 3560 1968 3560 1620 3560 1620 3561 1968 3561 1969 3561 1620 3562 1969 3562 1618 3562 1618 3563 1969 3563 1970 3563 1618 3564 1970 3564 1616 3564 1616 3565 1970 3565 1971 3565 1616 3566 1971 3566 1614 3566 1614 3567 1971 3567 1972 3567 1614 3568 1972 3568 1964 3568 1965 3569 1973 3569 1966 3569 1966 3570 1973 3570 1974 3570 1966 3571 1974 3571 1967 3571 1967 3572 1974 3572 1975 3572 1967 3573 1975 3573 1968 3573 1968 3574 1975 3574 1976 3574 1968 3575 1976 3575 1969 3575 1969 3576 1976 3576 1977 3576 1969 3577 1977 3577 1970 3577 1970 3578 1977 3578 1978 3578 1970 3579 1978 3579 1971 3579 1971 3580 1978 3580 1979 3580 1971 3581 1979 3581 1972 3581 1973 3582 1574 3582 1974 3582 1974 3583 1574 3583 1573 3583 1974 3584 1573 3584 1975 3584 1975 3585 1573 3585 1667 3585 1975 3586 1667 3586 1976 3586 1976 3587 1667 3587 1668 3587 1976 3588 1668 3588 1977 3588 1977 3589 1668 3589 1669 3589 1977 3590 1669 3590 1978 3590 1978 3591 1669 3591 1722 3591 1978 3592 1722 3592 1979 3592 1980 3593 1981 3593 1982 3593 1954 3594 1983 3594 1955 3594 1955 3595 1983 3595 1984 3595 1955 3596 1984 3596 1956 3596 1956 3597 1984 3597 1985 3597 1956 3598 1985 3598 1957 3598 1957 3599 1985 3599 1986 3599 1957 3600 1986 3600 1958 3600 1958 3601 1986 3601 1987 3601 1958 3602 1987 3602 1959 3602 1959 3603 1987 3603 1988 3603 1959 3604 1988 3604 1960 3604 1960 3605 1988 3605 1989 3605 1960 3606 1989 3606 1980 3606 1980 3607 1989 3607 1990 3607 1980 3608 1990 3608 1981 3608 1981 3609 1990 3609 1991 3609 1981 3610 1991 3610 1992 3610 1992 3611 1991 3611 1993 3611 1992 3612 1993 3612 1994 3612 1994 3613 1993 3613 1995 3613 1994 3614 1995 3614 1996 3614 1996 3615 1995 3615 1997 3615 1996 3616 1997 3616 1998 3616 1744 3617 1982 3617 1745 3617 1745 3618 1982 3618 1981 3618 1745 3619 1981 3619 1738 3619 1738 3620 1981 3620 1992 3620 1738 3621 1992 3621 1552 3621 1552 3622 1992 3622 1994 3622 1552 3623 1994 3623 1553 3623 1553 3624 1994 3624 1996 3624 1553 3625 1996 3625 1678 3625 1678 3626 1996 3626 1998 3626 1678 3627 1998 3627 1679 3627 1679 3628 1998 3628 1999 3628 1679 3629 1999 3629 1673 3629 1673 3630 1999 3630 2000 3630 1673 3631 2000 3631 1674 3631 1674 3632 2000 3632 2001 3632 1674 3633 2001 3633 1677 3633 1677 3634 2001 3634 2002 3634 1677 3635 2002 3635 1680 3635 1680 3636 2002 3636 2003 3636 1680 3637 2003 3637 1682 3637 1682 3638 2003 3638 2004 3638 1682 3639 2004 3639 1683 3639 1683 3640 2004 3640 2005 3640 1683 3641 2005 3641 1723 3641 1723 3642 2005 3642 2006 3642 1723 3643 2006 3643 1565 3643 1565 3644 2006 3644 2007 3644 1565 3645 2007 3645 1563 3645 1563 3646 2007 3646 2008 3646 1563 3647 2008 3647 1561 3647 1561 3648 2008 3648 2009 3648 1561 3649 2009 3649 1559 3649 1559 3650 2009 3650 2010 3650 1559 3651 2010 3651 1556 3651 1556 3652 2010 3652 2011 3652 1556 3653 2011 3653 1557 3653 1557 3654 2011 3654 2012 3654 1709 3655 2012 3655 1710 3655 1710 3656 2012 3656 2011 3656 1710 3657 2011 3657 1711 3657 1711 3658 2011 3658 2010 3658 1711 3659 2010 3659 1712 3659 1712 3660 2010 3660 2009 3660 1712 3661 2009 3661 1713 3661 1713 3662 2009 3662 2008 3662 1713 3663 2008 3663 1714 3663 1714 3664 2008 3664 2007 3664 1714 3665 2007 3665 1715 3665 1715 3666 2007 3666 2006 3666 1715 3667 2006 3667 1716 3667 1716 3668 2006 3668 2005 3668 1716 3669 2005 3669 1717 3669 1717 3670 2005 3670 2004 3670 1717 3671 2004 3671 1718 3671 1718 3672 2004 3672 2003 3672 1718 3673 2003 3673 1719 3673 1719 3674 2003 3674 2002 3674 1719 3675 2002 3675 1720 3675 1720 3676 2002 3676 2001 3676 1720 3677 2001 3677 1721 3677 1721 3678 2001 3678 2000 3678 1721 3679 2000 3679 1722 3679 1722 3680 2000 3680 1999 3680 1722 3681 1999 3681 1979 3681 1979 3682 1999 3682 1998 3682 1979 3683 1998 3683 1972 3683 1972 3684 1998 3684 1997 3684 1972 3685 1997 3685 1964 3685 1964 3686 1997 3686 1995 3686 1964 3687 1995 3687 1963 3687 1963 3688 1995 3688 1993 3688 1963 3689 1993 3689 1962 3689 1962 3690 1993 3690 1991 3690 1962 3691 1991 3691 1961 3691 1961 3692 1991 3692 1990 3692 1961 3693 1990 3693 1953 3693 1953 3694 1990 3694 1989 3694 1953 3695 1989 3695 1952 3695 1952 3696 1989 3696 1988 3696 1952 3697 1988 3697 1951 3697 1951 3698 1988 3698 1987 3698 1951 3699 1987 3699 1950 3699 1950 3700 1987 3700 1986 3700 1950 3701 1986 3701 1648 3701 1648 3702 1986 3702 1985 3702 1648 3703 1985 3703 1653 3703 1653 3704 1985 3704 1984 3704 1653 3705 1984 3705 1654 3705 1654 3706 1984 3706 1983 3706 1654 3707 1983 3707 1656 3707 1656 3708 1983 3708 1954 3708 1656 3709 1954 3709 1659 3709 1659 3710 1954 3710 1898 3710 1659 3711 1898 3711 1660 3711 1660 3712 1898 3712 1897 3712 1660 3713 1897 3713 1541 3713 1541 3714 1897 3714 1924 3714 1541 3715 1924 3715 1539 3715 1539 3716 1924 3716 1925 3716 1539 3717 1925 3717 1906 3717 1906 3718 1925 3718 1926 3718 1906 3719 1926 3719 1939 3719 1939 3720 1926 3720 1927 3720 1939 3721 1927 3721 1943 3721 1943 3722 1927 3722 1928 3722 1943 3723 1928 3723 1948 3723 1948 3724 1928 3724 1929 3724 1948 3725 1929 3725 1949 3725 1949 3726 1929 3726 1867 3726 1949 3727 1867 3727 1936 3727 1936 3728 1867 3728 1866 3728 1936 3729 1866 3729 1468 3729 1468 3730 1866 3730 1872 3730 1468 3731 1872 3731 1551 3731 1551 3732 1872 3732 1871 3732 1551 3733 1871 3733 1853 3733 1853 3734 1871 3734 1870 3734 1853 3735 1870 3735 1843 3735 1843 3736 1870 3736 1869 3736 1843 3737 1869 3737 1837 3737 1837 3738 1869 3738 1868 3738 1837 3739 1868 3739 1826 3739 1826 3740 1868 3740 1827 3740 1826 3741 1827 3741 1820 3741 1820 3742 1827 3742 1829 3742 1820 3743 1829 3743 1819 3743 1577 3744 1580 3744 1578 3744 1578 3745 1580 3745 1579 3745 1578 3746 1579 3746 1688 3746 1688 3747 1579 3747 1728 3747 1688 3748 1728 3748 1689 3748 1689 3749 1728 3749 1727 3749 1689 3750 1727 3750 1698 3750 1698 3751 1727 3751 1726 3751 1698 3752 1726 3752 1709 3752 1709 3753 1726 3753 1725 3753 1709 3754 1725 3754 2012 3754 2012 3755 1725 3755 1809 3755 2012 3756 1809 3756 1557 3756 1557 3757 1809 3757 1811 3757 1557 3758 1811 3758 1555 3758 1555 3759 1811 3759 1813 3759 1555 3760 1813 3760 1801 3760 1801 3761 1813 3761 1815 3761 1801 3762 1815 3762 1802 3762 1802 3763 1815 3763 1817 3763 1802 3764 1817 3764 1803 3764 1803 3765 1817 3765 1819 3765 1803 3766 1819 3766 1804 3766 1804 3767 1819 3767 1829 3767 1804 3768 1829 3768 1805 3768 1805 3769 1829 3769 1828 3769 1805 3770 1828 3770 1806 3770 1806 3771 1828 3771 1831 3771 1806 3772 1831 3772 1807 3772 1807 3773 1831 3773 1923 3773 1807 3774 1923 3774 1808 3774 1808 3775 1923 3775 1856 3775 1808 3776 1856 3776 1793 3776 1793 3777 1856 3777 1855 3777 1793 3778 1855 3778 1777 3778 1777 3779 1855 3779 1907 3779 1777 3780 1907 3780 1778 3780 1778 3781 1907 3781 1909 3781 1778 3782 1909 3782 1879 3782 1879 3783 1909 3783 1911 3783 1879 3784 1911 3784 1880 3784 1880 3785 1911 3785 1930 3785 1880 3786 1930 3786 1881 3786 1881 3787 1930 3787 1931 3787 1881 3788 1931 3788 1882 3788 1882 3789 1931 3789 1932 3789 1882 3790 1932 3790 1883 3790 1883 3791 1932 3791 1933 3791 1883 3792 1933 3792 1884 3792 1884 3793 1933 3793 1934 3793 1884 3794 1934 3794 1885 3794 1885 3795 1934 3795 1935 3795 1885 3796 1935 3796 1792 3796 1792 3797 1935 3797 1960 3797 1792 3798 1960 3798 1791 3798 1791 3799 1960 3799 1980 3799 1791 3800 1980 3800 1800 3800 1800 3801 1980 3801 1982 3801 1800 3802 1982 3802 1799 3802 1799 3803 1982 3803 1744 3803 1799 3804 1744 3804 1798 3804 1798 3805 1744 3805 1743 3805 1798 3806 1743 3806 1797 3806 1797 3807 1743 3807 1760 3807 1797 3808 1760 3808 1796 3808 1796 3809 1760 3809 1759 3809 1796 3810 1759 3810 1795 3810 1795 3811 1759 3811 1776 3811 1795 3812 1776 3812 1794 3812 1794 3813 1776 3813 1775 3813 1794 3814 1775 3814 1793 3814 1793 3815 1775 3815 1808 3815 2013 3816 2014 3816 2015 3816 2015 3817 2014 3817 2016 3817 2015 3818 2016 3818 2017 3818 2018 3819 2019 3819 2020 3819 2021 3820 2022 3820 2023 3820 2024 3821 2025 3821 2020 3821 2017 3822 2026 3822 2015 3822 2015 3823 2026 3823 2027 3823 2015 3824 2027 3824 2028 3824 2028 3825 2027 3825 2029 3825 2028 3826 2029 3826 2020 3826 2020 3827 2029 3827 2030 3827 2020 3828 2030 3828 2018 3828 2013 3829 2031 3829 2014 3829 2014 3830 2031 3830 2021 3830 2014 3831 2021 3831 2032 3831 2032 3832 2021 3832 2023 3832 2016 3833 2033 3833 2034 3833 2024 3834 2020 3834 2035 3834 2014 3835 2036 3835 2016 3835 2016 3836 2036 3836 2037 3836 2016 3837 2037 3837 2038 3837 2039 3838 2040 3838 2041 3838 2034 3839 2042 3839 2016 3839 2016 3840 2042 3840 2041 3840 2016 3841 2041 3841 2043 3841 2043 3842 2041 3842 2040 3842 2019 3843 2044 3843 2020 3843 2020 3844 2044 3844 2045 3844 2020 3845 2045 3845 2046 3845 2022 3846 2021 3846 2047 3846 2047 3847 2021 3847 2048 3847 2047 3848 2048 3848 2049 3848 2050 3849 2051 3849 2052 3849 2046 3850 2053 3850 2020 3850 2020 3851 2053 3851 2054 3851 2020 3852 2054 3852 2035 3852 2025 3853 2055 3853 2020 3853 2020 3854 2055 3854 2056 3854 2020 3855 2056 3855 2057 3855 2057 3856 2056 3856 2058 3856 2049 3857 2059 3857 2047 3857 2047 3858 2059 3858 2060 3858 2047 3859 2060 3859 2061 3859 2061 3860 2062 3860 2063 3860 2063 3861 2064 3861 2061 3861 2061 3862 2064 3862 2065 3862 2061 3863 2065 3863 2047 3863 2047 3864 2065 3864 2066 3864 2067 3865 2068 3865 2069 3865 2038 3866 2070 3866 2016 3866 2016 3867 2070 3867 2071 3867 2016 3868 2071 3868 2072 3868 2067 3869 2069 3869 2073 3869 2072 3870 2074 3870 2016 3870 2016 3871 2074 3871 2075 3871 2016 3872 2075 3872 2033 3872 2039 3873 2041 3873 2052 3873 2052 3874 2041 3874 2076 3874 2052 3875 2076 3875 2050 3875 2077 3876 2078 3876 2079 3876 2080 3877 2081 3877 2066 3877 2066 3878 2081 3878 2082 3878 2066 3879 2082 3879 2047 3879 2083 3880 2084 3880 2085 3880 2073 3881 2069 3881 2066 3881 2066 3882 2069 3882 2086 3882 2066 3883 2086 3883 2080 3883 2058 3884 2087 3884 2057 3884 2057 3885 2087 3885 2088 3885 2057 3886 2088 3886 2089 3886 2090 3887 2091 3887 2078 3887 2078 3888 2091 3888 2092 3888 2078 3889 2092 3889 2079 3889 2083 3890 2085 3890 2093 3890 2090 3891 2078 3891 2085 3891 2085 3892 2078 3892 2094 3892 2085 3893 2094 3893 2093 3893 2084 3894 2095 3894 2085 3894 2085 3895 2095 3895 2096 3895 2085 3896 2096 3896 2057 3896 2097 3897 2098 3897 2079 3897 2079 3898 2098 3898 2099 3898 2079 3899 2099 3899 2077 3899 2089 3900 2100 3900 2057 3900 2057 3901 2100 3901 2101 3901 2057 3902 2101 3902 2102 3902 2102 3903 2103 3903 2057 3903 2057 3904 2103 3904 2104 3904 2057 3905 2104 3905 2085 3905 2105 3906 2106 3906 13 3906 13 3907 2106 3907 2107 3907 13 3908 2107 3908 14 3908 1612 3909 2108 3909 2109 3909 2109 3910 2108 3910 2110 3910 2109 3911 2110 3911 2105 3911 2105 3912 13 3912 2109 3912 2109 3913 13 3913 16 3913 2109 3914 16 3914 2111 3914 2111 3915 16 3915 21 3915 2111 3916 21 3916 2112 3916 2112 3917 21 3917 20 3917 2112 3918 20 3918 2113 3918 2113 3919 20 3919 19 3919 2113 3920 19 3920 2114 3920 2114 3921 19 3921 18 3921 2114 3922 18 3922 2115 3922 1612 3923 2109 3923 1613 3923 1613 3924 2109 3924 2111 3924 1613 3925 2111 3925 1965 3925 1965 3926 2111 3926 2112 3926 1965 3927 2112 3927 1973 3927 1973 3928 2112 3928 2113 3928 1973 3929 2113 3929 1574 3929 1574 3930 2113 3930 2114 3930 1574 3931 2114 3931 1575 3931 1575 3932 2114 3932 2115 3932 1575 3933 2115 3933 1607 3933 1608 3934 1607 3934 2116 3934 2116 3935 1607 3935 2115 3935 2116 3936 2115 3936 177 3936 177 3937 2115 3937 18 3937 177 3938 176 3938 2116 3938 2116 3939 176 3939 2117 3939 2116 3940 2117 3940 1608 3940 1606 3941 1605 3941 2117 3941 2117 3942 1605 3942 1609 3942 2117 3943 1609 3943 1608 3943 175 3944 182 3944 2118 3944 2118 3945 182 3945 181 3945 2118 3946 181 3946 2119 3946 2119 3947 181 3947 180 3947 2119 3948 180 3948 2120 3948 2120 3949 180 3949 179 3949 2120 3950 179 3950 2121 3950 2121 3951 179 3951 183 3951 2121 3952 183 3952 2122 3952 2122 3953 183 3953 152 3953 2122 3954 152 3954 2123 3954 2123 3955 152 3955 151 3955 2123 3956 151 3956 2124 3956 2124 3957 151 3957 155 3957 2124 3958 155 3958 2125 3958 2125 3959 155 3959 158 3959 2125 3960 158 3960 2126 3960 158 3961 146 3961 2126 3961 2126 3962 146 3962 149 3962 2126 3963 149 3963 2127 3963 2127 3964 149 3964 188 3964 2127 3965 188 3965 2128 3965 2128 3966 188 3966 187 3966 2128 3967 187 3967 2129 3967 2129 3968 187 3968 186 3968 2129 3969 186 3969 2130 3969 2130 3970 186 3970 185 3970 2130 3971 185 3971 2131 3971 2131 3972 185 3972 184 3972 2131 3973 184 3973 2132 3973 2132 3974 184 3974 189 3974 2132 3975 189 3975 2133 3975 2133 3976 189 3976 190 3976 2133 3977 190 3977 2134 3977 2134 3978 190 3978 192 3978 2134 3979 192 3979 2135 3979 176 3980 175 3980 2117 3980 2117 3981 175 3981 2118 3981 2117 3982 2118 3982 1606 3982 1606 3983 2118 3983 2119 3983 1606 3984 2119 3984 1603 3984 1603 3985 2119 3985 2120 3985 1603 3986 2120 3986 1601 3986 1601 3987 2120 3987 2121 3987 1601 3988 2121 3988 1599 3988 1599 3989 2121 3989 2122 3989 1599 3990 2122 3990 1598 3990 1598 3991 2122 3991 2123 3991 1598 3992 2123 3992 1593 3992 1593 3993 2123 3993 2124 3993 1593 3994 2124 3994 1594 3994 1594 3995 2124 3995 2125 3995 1594 3996 2125 3996 1595 3996 1595 3997 2125 3997 2126 3997 1595 3998 2126 3998 1588 3998 1588 3999 2126 3999 2127 3999 1588 4000 2127 4000 1590 4000 1590 4001 2127 4001 2128 4001 1590 4002 2128 4002 1586 4002 1586 4003 2128 4003 2129 4003 1586 4004 2129 4004 1584 4004 1584 4005 2129 4005 2130 4005 1584 4006 2130 4006 1582 4006 1582 4007 2130 4007 2131 4007 1582 4008 2131 4008 1576 4008 1576 4009 2131 4009 2132 4009 1576 4010 2132 4010 1577 4010 1577 4011 2132 4011 2133 4011 1577 4012 2133 4012 1580 4012 1580 4013 2133 4013 2134 4013 1580 4014 2134 4014 1581 4014 1581 4015 2134 4015 2135 4015 1581 4016 2135 4016 1083 4016 2135 4017 192 4017 196 4017 2135 4018 196 4018 2136 4018 2136 4019 196 4019 195 4019 2136 4020 195 4020 2137 4020 2137 4021 195 4021 193 4021 2137 4022 193 4022 2138 4022 2138 4023 193 4023 200 4023 2138 4024 200 4024 2139 4024 2139 4025 200 4025 199 4025 2139 4026 199 4026 2140 4026 2140 4027 199 4027 198 4027 2140 4028 198 4028 2141 4028 2141 4029 198 4029 197 4029 2141 4030 197 4030 2142 4030 2142 4031 197 4031 125 4031 2142 4032 125 4032 2143 4032 2143 4033 125 4033 117 4033 2143 4034 117 4034 2144 4034 2144 4035 117 4035 113 4035 2144 4036 113 4036 2145 4036 113 4037 111 4037 2145 4037 2145 4038 111 4038 109 4038 2145 4039 109 4039 2146 4039 2146 4040 109 4040 206 4040 2146 4041 206 4041 2147 4041 206 4042 207 4042 2147 4042 2147 4043 207 4043 202 4043 2147 4044 202 4044 2148 4044 2148 4045 202 4045 201 4045 2148 4046 201 4046 2149 4046 2149 4047 201 4047 208 4047 2149 4048 208 4048 2150 4048 2150 4049 208 4049 210 4049 2150 4050 210 4050 2151 4050 210 4051 214 4051 2151 4051 2151 4052 214 4052 213 4052 2151 4053 213 4053 2152 4053 2152 4054 213 4054 212 4054 2152 4055 212 4055 2153 4055 2153 4056 1071 4056 2152 4056 2152 4057 1071 4057 1079 4057 2152 4058 1079 4058 2151 4058 2151 4059 1079 4059 1077 4059 2151 4060 1077 4060 2150 4060 2150 4061 1077 4061 1076 4061 2150 4062 1076 4062 2149 4062 2149 4063 1076 4063 1069 4063 2149 4064 1069 4064 2148 4064 2148 4065 1069 4065 1068 4065 2148 4066 1068 4066 2147 4066 2147 4067 1068 4067 1161 4067 2147 4068 1161 4068 2146 4068 2146 4069 1161 4069 1244 4069 2146 4070 1244 4070 2145 4070 2145 4071 1244 4071 1066 4071 2145 4072 1066 4072 2144 4072 2144 4073 1066 4073 1065 4073 2144 4074 1065 4074 2143 4074 2143 4075 1065 4075 1081 4075 2143 4076 1081 4076 2142 4076 2142 4077 1081 4077 1277 4077 2142 4078 1277 4078 2141 4078 2141 4079 1277 4079 1536 4079 2141 4080 1536 4080 2140 4080 2140 4081 1536 4081 1535 4081 2140 4082 1535 4082 2139 4082 2139 4083 1535 4083 1534 4083 2139 4084 1534 4084 2138 4084 2138 4085 1534 4085 1173 4085 2138 4086 1173 4086 2137 4086 2137 4087 1173 4087 1085 4087 2137 4088 1085 4088 2136 4088 2136 4089 1085 4089 1083 4089 2136 4090 1083 4090 2135 4090 1075 4091 1074 4091 2153 4091 2153 4092 1074 4092 1072 4092 2153 4093 1072 4093 1071 4093 2154 4094 2155 4094 8 4094 8 4095 2155 4095 215 4095 212 4096 215 4096 2153 4096 2153 4097 215 4097 2155 4097 2153 4098 2155 4098 1075 4098 1075 4099 2155 4099 2154 4099 1075 4100 2154 4100 1137 4100 2156 4101 1132 4101 1131 4101 2156 4102 1131 4102 2157 4102 1 4103 0 4103 2158 4103 2158 4104 2159 4104 2160 4104 2160 4105 2159 4105 2161 4105 2160 4106 2161 4106 2157 4106 2157 4107 1131 4107 2160 4107 2160 4108 1131 4108 1498 4108 2160 4109 1498 4109 2162 4109 2162 4110 1498 4110 1510 4110 2162 4111 1510 4111 2163 4111 2163 4112 1510 4112 1133 4112 2163 4113 1133 4113 2164 4113 2164 4114 1133 4114 1135 4114 2164 4115 1135 4115 2165 4115 2165 4116 1135 4116 1137 4116 2165 4117 1137 4117 2154 4117 2158 4118 2160 4118 1 4118 1 4119 2160 4119 2162 4119 1 4120 2162 4120 3 4120 3 4121 2162 4121 2163 4121 3 4122 2163 4122 4 4122 4 4123 2163 4123 2164 4123 4 4124 2164 4124 5 4124 5 4125 2164 4125 2165 4125 5 4126 2165 4126 7 4126 7 4127 2165 4127 2154 4127 7 4128 2154 4128 8 4128 2060 4129 2059 4129 2166 4129 2166 4130 2059 4130 2167 4130 2168 4131 2169 4131 2170 4131 2170 4132 2169 4132 2171 4132 2170 4133 2171 4133 2167 4133 2167 4134 2171 4134 2172 4134 2167 4135 2172 4135 2166 4135 11 4136 10 4136 2168 4136 2168 4137 10 4137 2173 4137 2168 4138 2173 4138 2169 4138 2059 4139 2049 4139 2167 4139 2167 4140 2049 4140 2174 4140 2167 4141 2174 4141 2170 4141 2170 4142 2174 4142 2175 4142 2170 4143 2175 4143 2168 4143 2168 4144 2175 4144 2176 4144 2168 4145 2176 4145 11 4145 11 4146 2176 4146 2 4146 2049 4147 2048 4147 2174 4147 2174 4148 2048 4148 2177 4148 2174 4149 2177 4149 2175 4149 2175 4150 2177 4150 2178 4150 2175 4151 2178 4151 2176 4151 2176 4152 2178 4152 2179 4152 2176 4153 2179 4153 2 4153 2 4154 2179 4154 0 4154 10 4155 49 4155 2173 4155 2173 4156 49 4156 2180 4156 2173 4157 2180 4157 2169 4157 2169 4158 2180 4158 2181 4158 2169 4159 2181 4159 2171 4159 2171 4160 2181 4160 2182 4160 2171 4161 2182 4161 2172 4161 2172 4162 2182 4162 2183 4162 2172 4163 2183 4163 2166 4163 2166 4164 2183 4164 2184 4164 2166 4165 2184 4165 2060 4165 2060 4166 2184 4166 2061 4166 2185 4167 1132 4167 2156 4167 2186 4168 2185 4168 2187 4168 2188 4169 2186 4169 2189 4169 2020 4170 2188 4170 2190 4170 2185 4171 2156 4171 2187 4171 2187 4172 2156 4172 2157 4172 2187 4173 2157 4173 2191 4173 2191 4174 2157 4174 2161 4174 2191 4175 2161 4175 2192 4175 2192 4176 2161 4176 2159 4176 2192 4177 2159 4177 2193 4177 2193 4178 2159 4178 2158 4178 2193 4179 2158 4179 2194 4179 2194 4180 2158 4180 0 4180 2194 4181 0 4181 2179 4181 2186 4182 2187 4182 2189 4182 2189 4183 2187 4183 2191 4183 2189 4184 2191 4184 2195 4184 2195 4185 2191 4185 2192 4185 2195 4186 2192 4186 2196 4186 2196 4187 2192 4187 2193 4187 2196 4188 2193 4188 2197 4188 2197 4189 2193 4189 2194 4189 2197 4190 2194 4190 2198 4190 2198 4191 2194 4191 2179 4191 2198 4192 2179 4192 2178 4192 2188 4193 2189 4193 2190 4193 2190 4194 2189 4194 2195 4194 2190 4195 2195 4195 2199 4195 2199 4196 2195 4196 2196 4196 2199 4197 2196 4197 2200 4197 2200 4198 2196 4198 2197 4198 2200 4199 2197 4199 2201 4199 2201 4200 2197 4200 2198 4200 2201 4201 2198 4201 2202 4201 2202 4202 2198 4202 2178 4202 2202 4203 2178 4203 2177 4203 2020 4204 2190 4204 2028 4204 2028 4205 2190 4205 2199 4205 2028 4206 2199 4206 2015 4206 2015 4207 2199 4207 2200 4207 2015 4208 2200 4208 2013 4208 2013 4209 2200 4209 2201 4209 2013 4210 2201 4210 2031 4210 2031 4211 2201 4211 2202 4211 2031 4212 2202 4212 2021 4212 2021 4213 2202 4213 2177 4213 2021 4214 2177 4214 2048 4214 35 4215 38 4215 2203 4215 2204 4216 2205 4216 2206 4216 2061 4217 2207 4217 2062 4217 2062 4218 2207 4218 2208 4218 2062 4219 2208 4219 2063 4219 2063 4220 2208 4220 2206 4220 2063 4221 2206 4221 2064 4221 2064 4222 2206 4222 2205 4222 2064 4223 2205 4223 2065 4223 2209 4224 2210 4224 2211 4224 2211 4225 2210 4225 2204 4225 2204 4226 2206 4226 2211 4226 2211 4227 2206 4227 2208 4227 2211 4228 2208 4228 2212 4228 2212 4229 2208 4229 2207 4229 2212 4230 2207 4230 2213 4230 2061 4231 2184 4231 2207 4231 2207 4232 2184 4232 2183 4232 2207 4233 2183 4233 2213 4233 2213 4234 2183 4234 2182 4234 2213 4235 2182 4235 2181 4235 2209 4236 2211 4236 2203 4236 2203 4237 2211 4237 2212 4237 2203 4238 2212 4238 2214 4238 2214 4239 2212 4239 2213 4239 2214 4240 2213 4240 2215 4240 2215 4241 2213 4241 2181 4241 2215 4242 2181 4242 2180 4242 38 4243 29 4243 2203 4243 2203 4244 29 4244 2216 4244 2203 4245 2216 4245 2209 4245 35 4246 2203 4246 46 4246 46 4247 2203 4247 2214 4247 46 4248 2214 4248 41 4248 41 4249 2214 4249 2215 4249 41 4250 2215 4250 55 4250 55 4251 2215 4251 2180 4251 55 4252 2180 4252 49 4252 1457 4253 1412 4253 2217 4253 1406 4254 1402 4254 2218 4254 2188 4255 2020 4255 2057 4255 2186 4256 2188 4256 2219 4256 2185 4257 2186 4257 2220 4257 2221 4258 1107 4258 2222 4258 2222 4259 1107 4259 1105 4259 2222 4260 1105 4260 2223 4260 2223 4261 1105 4261 1112 4261 2223 4262 1112 4262 2224 4262 2224 4263 1112 4263 1111 4263 2224 4264 1111 4264 2225 4264 2225 4265 1111 4265 1117 4265 2225 4266 1117 4266 2226 4266 2226 4267 1117 4267 1116 4267 2226 4268 1116 4268 2227 4268 2227 4269 1116 4269 1114 4269 2227 4270 1114 4270 2228 4270 2228 4271 1114 4271 1113 4271 2228 4272 1113 4272 2229 4272 2229 4273 1113 4273 1119 4273 2229 4274 1119 4274 2230 4274 2230 4275 1119 4275 1118 4275 2230 4276 1118 4276 2231 4276 2231 4277 1118 4277 1056 4277 2231 4278 1056 4278 2232 4278 2232 4279 1056 4279 1121 4279 2232 4280 1121 4280 2233 4280 2233 4281 1121 4281 1123 4281 2233 4282 1123 4282 2234 4282 2234 4283 1123 4283 1125 4283 2234 4284 1125 4284 2235 4284 2235 4285 1125 4285 1127 4285 2235 4286 1127 4286 2236 4286 2236 4287 1127 4287 1129 4287 2236 4288 1129 4288 2237 4288 2237 4289 1129 4289 1130 4289 2237 4290 1130 4290 2238 4290 2238 4291 1130 4291 1132 4291 2238 4292 1132 4292 2185 4292 2239 4293 1095 4293 2240 4293 2240 4294 1095 4294 1103 4294 2240 4295 1103 4295 2241 4295 2241 4296 1103 4296 1102 4296 2241 4297 1102 4297 2242 4297 2242 4298 1102 4298 1109 4298 2242 4299 1109 4299 2221 4299 2221 4300 1109 4300 1108 4300 2221 4301 1108 4301 1107 4301 2188 4302 2057 4302 2219 4302 2219 4303 2057 4303 2096 4303 2219 4304 2096 4304 2243 4304 2243 4305 2096 4305 2095 4305 2243 4306 2095 4306 2244 4306 2244 4307 2095 4307 2084 4307 2244 4308 2084 4308 2245 4308 2245 4309 2084 4309 2083 4309 2245 4310 2083 4310 2246 4310 2246 4311 2083 4311 2093 4311 2246 4312 2093 4312 2247 4312 2247 4313 2093 4313 2094 4313 2247 4314 2094 4314 2248 4314 2248 4315 2094 4315 2078 4315 2248 4316 2078 4316 2249 4316 2249 4317 2078 4317 2077 4317 2249 4318 2077 4318 2250 4318 2250 4319 2077 4319 2099 4319 2250 4320 2099 4320 2251 4320 2251 4321 2099 4321 2098 4321 2251 4322 2098 4322 2252 4322 2252 4323 2098 4323 2097 4323 2252 4324 2097 4324 2253 4324 2253 4325 2097 4325 2079 4325 2253 4326 2079 4326 2254 4326 2254 4327 2079 4327 2092 4327 2254 4328 2092 4328 2255 4328 2255 4329 2092 4329 2091 4329 2255 4330 2091 4330 2256 4330 2256 4331 2091 4331 2090 4331 2256 4332 2090 4332 2257 4332 2257 4333 2090 4333 2085 4333 2257 4334 2085 4334 2258 4334 2258 4335 2085 4335 2104 4335 2258 4336 2104 4336 2259 4336 2259 4337 2104 4337 2103 4337 2259 4338 2103 4338 2260 4338 2260 4339 2103 4339 2102 4339 2260 4340 2102 4340 2261 4340 2261 4341 2102 4341 2101 4341 2261 4342 2101 4342 2262 4342 2262 4343 2101 4343 2100 4343 2262 4344 2100 4344 2263 4344 2263 4345 2100 4345 2089 4345 2263 4346 2089 4346 2264 4346 2264 4347 2089 4347 2088 4347 2264 4348 2088 4348 2265 4348 2265 4349 2088 4349 2087 4349 2265 4350 2087 4350 2266 4350 2266 4351 2087 4351 2058 4351 2266 4352 2058 4352 2267 4352 2267 4353 2058 4353 2056 4353 2267 4354 2056 4354 2268 4354 2268 4355 2056 4355 2055 4355 2268 4356 2055 4356 2269 4356 2186 4357 2219 4357 2220 4357 2220 4358 2219 4358 2243 4358 2220 4359 2243 4359 2270 4359 2270 4360 2243 4360 2244 4360 2270 4361 2244 4361 2271 4361 2271 4362 2244 4362 2245 4362 2271 4363 2245 4363 2272 4363 2272 4364 2245 4364 2246 4364 2272 4365 2246 4365 2273 4365 2273 4366 2246 4366 2247 4366 2273 4367 2247 4367 2274 4367 2274 4368 2247 4368 2248 4368 2274 4369 2248 4369 2275 4369 2275 4370 2248 4370 2249 4370 2275 4371 2249 4371 2276 4371 2276 4372 2249 4372 2250 4372 2276 4373 2250 4373 2277 4373 2277 4374 2250 4374 2251 4374 2277 4375 2251 4375 2278 4375 2278 4376 2251 4376 2252 4376 2278 4377 2252 4377 2279 4377 2279 4378 2252 4378 2253 4378 2279 4379 2253 4379 2280 4379 2280 4380 2253 4380 2254 4380 2280 4381 2254 4381 2281 4381 2281 4382 2254 4382 2255 4382 2281 4383 2255 4383 2282 4383 2282 4384 2255 4384 2256 4384 2282 4385 2256 4385 2283 4385 2283 4386 2256 4386 2257 4386 2283 4387 2257 4387 2284 4387 2284 4388 2257 4388 2258 4388 2284 4389 2258 4389 2285 4389 2285 4390 2258 4390 2259 4390 2285 4391 2259 4391 2286 4391 2286 4392 2259 4392 2260 4392 2286 4393 2260 4393 2287 4393 2287 4394 2260 4394 2261 4394 2287 4395 2261 4395 2288 4395 2288 4396 2261 4396 2262 4396 2288 4397 2262 4397 2289 4397 2289 4398 2262 4398 2263 4398 2289 4399 2263 4399 2290 4399 2290 4400 2263 4400 2264 4400 2290 4401 2264 4401 2291 4401 2291 4402 2264 4402 2265 4402 2291 4403 2265 4403 2292 4403 2292 4404 2265 4404 2266 4404 2292 4405 2266 4405 2293 4405 2293 4406 2266 4406 2267 4406 2293 4407 2267 4407 2294 4407 2294 4408 2267 4408 2268 4408 2294 4409 2268 4409 2295 4409 2295 4410 2268 4410 2269 4410 2295 4411 2269 4411 2296 4411 2185 4412 2220 4412 2238 4412 2238 4413 2220 4413 2270 4413 2238 4414 2270 4414 2237 4414 2237 4415 2270 4415 2271 4415 2237 4416 2271 4416 2236 4416 2236 4417 2271 4417 2272 4417 2236 4418 2272 4418 2235 4418 2235 4419 2272 4419 2273 4419 2235 4420 2273 4420 2234 4420 2234 4421 2273 4421 2274 4421 2234 4422 2274 4422 2233 4422 2233 4423 2274 4423 2275 4423 2233 4424 2275 4424 2232 4424 2232 4425 2275 4425 2276 4425 2232 4426 2276 4426 2231 4426 2231 4427 2276 4427 2277 4427 2231 4428 2277 4428 2230 4428 2230 4429 2277 4429 2278 4429 2230 4430 2278 4430 2229 4430 2229 4431 2278 4431 2279 4431 2229 4432 2279 4432 2228 4432 2228 4433 2279 4433 2280 4433 2228 4434 2280 4434 2227 4434 2227 4435 2280 4435 2281 4435 2227 4436 2281 4436 2226 4436 2226 4437 2281 4437 2282 4437 2226 4438 2282 4438 2225 4438 2225 4439 2282 4439 2283 4439 2225 4440 2283 4440 2224 4440 2224 4441 2283 4441 2284 4441 2224 4442 2284 4442 2223 4442 2223 4443 2284 4443 2285 4443 2223 4444 2285 4444 2222 4444 2222 4445 2285 4445 2286 4445 2222 4446 2286 4446 2221 4446 2221 4447 2286 4447 2287 4447 2221 4448 2287 4448 2242 4448 2242 4449 2287 4449 2288 4449 2242 4450 2288 4450 2241 4450 2241 4451 2288 4451 2289 4451 2241 4452 2289 4452 2240 4452 2240 4453 2289 4453 2290 4453 2240 4454 2290 4454 2239 4454 2239 4455 2290 4455 2291 4455 2239 4456 2291 4456 2297 4456 2297 4457 2291 4457 2292 4457 2297 4458 2292 4458 2298 4458 2298 4459 2292 4459 2293 4459 2298 4460 2293 4460 2299 4460 2299 4461 2293 4461 2294 4461 2299 4462 2294 4462 2300 4462 2300 4463 2294 4463 2295 4463 2300 4464 2295 4464 2301 4464 2301 4465 2295 4465 2296 4465 2301 4466 2296 4466 2302 4466 1397 4467 1482 4467 2302 4467 2302 4468 1482 4468 1059 4468 2302 4469 1059 4469 2301 4469 2301 4470 1059 4470 1090 4470 2301 4471 1090 4471 2300 4471 2300 4472 1090 4472 1092 4472 2300 4473 1092 4473 2299 4473 2299 4474 1092 4474 1481 4474 2299 4475 1481 4475 2298 4475 2298 4476 1481 4476 1100 4476 2298 4477 1100 4477 2297 4477 2297 4478 1100 4478 1099 4478 2297 4479 1099 4479 2239 4479 2239 4480 1099 4480 1097 4480 2239 4481 1097 4481 1095 4481 1396 4482 1397 4482 2303 4482 2303 4483 1397 4483 2302 4483 2303 4484 2302 4484 2304 4484 2304 4485 2302 4485 2296 4485 2304 4486 2296 4486 2305 4486 2305 4487 2296 4487 2269 4487 2305 4488 2269 4488 2025 4488 2025 4489 2269 4489 2055 4489 1402 4490 1396 4490 2218 4490 2218 4491 1396 4491 2303 4491 2218 4492 2303 4492 2306 4492 2306 4493 2303 4493 2304 4493 2306 4494 2304 4494 2307 4494 2307 4495 2304 4495 2305 4495 2307 4496 2305 4496 2024 4496 2024 4497 2305 4497 2025 4497 1412 4498 1406 4498 2217 4498 2217 4499 1406 4499 2218 4499 2217 4500 2218 4500 2308 4500 2308 4501 2218 4501 2306 4501 2308 4502 2306 4502 2309 4502 2309 4503 2306 4503 2307 4503 2309 4504 2307 4504 2035 4504 2035 4505 2307 4505 2024 4505 1062 4506 1457 4506 2310 4506 2310 4507 1457 4507 2217 4507 2310 4508 2217 4508 2311 4508 2311 4509 2217 4509 2308 4509 2311 4510 2308 4510 2312 4510 2312 4511 2308 4511 2309 4511 2312 4512 2309 4512 2054 4512 2054 4513 2309 4513 2035 4513 1063 4514 1062 4514 2313 4514 2313 4515 1062 4515 2310 4515 2313 4516 2310 4516 2314 4516 2314 4517 2310 4517 2311 4517 2314 4518 2311 4518 2315 4518 2315 4519 2311 4519 2312 4519 2315 4520 2312 4520 2053 4520 2053 4521 2312 4521 2054 4521 2066 4522 2065 4522 2316 4522 2316 4523 2065 4523 2205 4523 2316 4524 2205 4524 2317 4524 2317 4525 2205 4525 2204 4525 2317 4526 2204 4526 2318 4526 2318 4527 2204 4527 2210 4527 2318 4528 2210 4528 2319 4528 2319 4529 2210 4529 2209 4529 2319 4530 2209 4530 2320 4530 2320 4531 2209 4531 2216 4531 2320 4532 2216 4532 28 4532 28 4533 2216 4533 29 4533 2321 4534 2322 4534 2323 4534 2322 4535 2324 4535 2325 4535 2315 4536 2053 4536 2046 4536 2314 4537 2315 4537 2326 4537 2313 4538 2314 4538 2327 4538 1063 4539 2313 4539 1569 4539 1569 4540 2313 4540 2328 4540 2329 4541 1664 4541 2328 4541 2328 4542 1664 4542 1903 4542 2328 4543 1903 4543 1569 4543 2330 4544 1646 4544 2331 4544 2331 4545 1646 4545 1655 4545 2331 4546 1655 4546 2332 4546 2332 4547 1655 4547 1657 4547 2332 4548 1657 4548 2333 4548 2333 4549 1657 4549 1658 4549 2333 4550 1658 4550 2334 4550 2334 4551 1658 4551 1661 4551 2334 4552 1661 4552 2335 4552 2335 4553 1661 4553 1662 4553 2335 4554 1662 4554 2329 4554 2329 4555 1662 4555 1663 4555 2329 4556 1663 4556 1664 4556 2315 4557 2046 4557 2326 4557 2326 4558 2046 4558 2045 4558 2326 4559 2045 4559 2336 4559 2336 4560 2045 4560 2044 4560 2336 4561 2044 4561 2337 4561 2337 4562 2044 4562 2019 4562 2337 4563 2019 4563 2338 4563 2338 4564 2019 4564 2018 4564 2338 4565 2018 4565 2339 4565 2339 4566 2018 4566 2030 4566 2339 4567 2030 4567 2340 4567 2340 4568 2030 4568 2029 4568 2340 4569 2029 4569 2341 4569 2341 4570 2029 4570 2027 4570 2341 4571 2027 4571 2342 4571 2342 4572 2027 4572 2026 4572 2342 4573 2026 4573 2343 4573 2343 4574 2026 4574 2017 4574 2343 4575 2017 4575 2344 4575 2344 4576 2017 4576 2016 4576 2344 4577 2016 4577 2345 4577 2345 4578 2016 4578 2043 4578 2345 4579 2043 4579 2346 4579 2346 4580 2043 4580 2040 4580 2346 4581 2040 4581 2347 4581 2314 4582 2326 4582 2327 4582 2327 4583 2326 4583 2336 4583 2327 4584 2336 4584 2348 4584 2348 4585 2336 4585 2337 4585 2348 4586 2337 4586 2349 4586 2349 4587 2337 4587 2338 4587 2349 4588 2338 4588 2350 4588 2350 4589 2338 4589 2339 4589 2350 4590 2339 4590 2351 4590 2351 4591 2339 4591 2340 4591 2351 4592 2340 4592 2352 4592 2352 4593 2340 4593 2341 4593 2352 4594 2341 4594 2353 4594 2353 4595 2341 4595 2342 4595 2353 4596 2342 4596 2354 4596 2354 4597 2342 4597 2343 4597 2354 4598 2343 4598 2355 4598 2355 4599 2343 4599 2344 4599 2355 4600 2344 4600 2356 4600 2356 4601 2344 4601 2345 4601 2356 4602 2345 4602 2357 4602 2357 4603 2345 4603 2346 4603 2357 4604 2346 4604 2358 4604 2358 4605 2346 4605 2347 4605 2358 4606 2347 4606 2359 4606 2313 4607 2327 4607 2328 4607 2328 4608 2327 4608 2348 4608 2328 4609 2348 4609 2329 4609 2329 4610 2348 4610 2349 4610 2329 4611 2349 4611 2335 4611 2335 4612 2349 4612 2350 4612 2335 4613 2350 4613 2334 4613 2334 4614 2350 4614 2351 4614 2334 4615 2351 4615 2333 4615 2333 4616 2351 4616 2352 4616 2333 4617 2352 4617 2332 4617 2332 4618 2352 4618 2353 4618 2332 4619 2353 4619 2331 4619 2331 4620 2353 4620 2354 4620 2331 4621 2354 4621 2330 4621 2330 4622 2354 4622 2355 4622 2330 4623 2355 4623 2360 4623 2360 4624 2355 4624 2356 4624 2360 4625 2356 4625 2361 4625 2361 4626 2356 4626 2357 4626 2361 4627 2357 4627 2362 4627 2362 4628 2357 4628 2358 4628 2362 4629 2358 4629 2363 4629 2363 4630 2358 4630 2359 4630 2363 4631 2359 4631 2364 4631 1642 4632 1641 4632 2364 4632 2364 4633 1641 4633 1640 4633 2364 4634 1640 4634 2363 4634 2363 4635 1640 4635 1645 4635 2363 4636 1645 4636 2362 4636 2362 4637 1645 4637 1652 4637 2362 4638 1652 4638 2361 4638 2361 4639 1652 4639 1651 4639 2361 4640 1651 4640 2360 4640 2360 4641 1651 4641 1649 4641 2360 4642 1649 4642 2330 4642 2330 4643 1649 4643 1647 4643 2330 4644 1647 4644 1646 4644 1636 4645 1642 4645 2365 4645 2365 4646 1642 4646 2364 4646 2365 4647 2364 4647 2366 4647 2366 4648 2364 4648 2359 4648 2366 4649 2359 4649 2367 4649 2367 4650 2359 4650 2347 4650 2367 4651 2347 4651 2039 4651 2039 4652 2347 4652 2040 4652 1638 4653 1636 4653 2368 4653 2368 4654 1636 4654 2365 4654 2368 4655 2365 4655 2369 4655 2369 4656 2365 4656 2366 4656 2369 4657 2366 4657 2370 4657 2370 4658 2366 4658 2367 4658 2370 4659 2367 4659 2052 4659 2052 4660 2367 4660 2039 4660 2052 4661 2051 4661 2370 4661 2370 4662 2051 4662 2371 4662 2370 4663 2371 4663 2369 4663 2369 4664 2371 4664 2372 4664 2369 4665 2372 4665 2368 4665 2368 4666 2372 4666 2373 4666 2368 4667 2373 4667 1638 4667 1632 4668 1631 4668 2373 4668 2373 4669 1631 4669 1639 4669 2373 4670 1639 4670 1638 4670 2324 4671 2050 4671 2076 4671 2324 4672 2076 4672 2325 4672 2325 4673 2076 4673 2041 4673 2325 4674 2041 4674 2374 4674 2374 4675 2041 4675 2042 4675 2374 4676 2042 4676 2375 4676 2375 4677 2042 4677 2034 4677 2375 4678 2034 4678 2376 4678 2376 4679 2034 4679 2033 4679 2376 4680 2033 4680 2377 4680 2377 4681 2033 4681 2075 4681 2377 4682 2075 4682 2378 4682 2378 4683 2075 4683 2074 4683 2378 4684 2074 4684 2379 4684 2379 4685 2074 4685 2072 4685 2379 4686 2072 4686 2380 4686 2380 4687 2072 4687 2071 4687 2380 4688 2071 4688 2381 4688 2381 4689 2071 4689 2070 4689 2381 4690 2070 4690 2382 4690 2382 4691 2070 4691 2038 4691 2382 4692 2038 4692 2383 4692 2383 4693 2038 4693 2037 4693 2383 4694 2037 4694 2384 4694 2384 4695 2037 4695 2036 4695 2384 4696 2036 4696 2385 4696 2322 4697 2325 4697 2323 4697 2323 4698 2325 4698 2374 4698 2323 4699 2374 4699 2386 4699 2386 4700 2374 4700 2375 4700 2386 4701 2375 4701 2387 4701 2387 4702 2375 4702 2376 4702 2387 4703 2376 4703 2388 4703 2388 4704 2376 4704 2377 4704 2388 4705 2377 4705 2389 4705 2389 4706 2377 4706 2378 4706 2389 4707 2378 4707 2390 4707 2390 4708 2378 4708 2379 4708 2390 4709 2379 4709 2391 4709 2391 4710 2379 4710 2380 4710 2391 4711 2380 4711 2392 4711 2392 4712 2380 4712 2381 4712 2392 4713 2381 4713 2393 4713 2393 4714 2381 4714 2382 4714 2393 4715 2382 4715 2394 4715 2394 4716 2382 4716 2383 4716 2394 4717 2383 4717 2395 4717 2395 4718 2383 4718 2384 4718 2395 4719 2384 4719 2396 4719 2396 4720 2384 4720 2385 4720 2396 4721 2385 4721 2397 4721 2321 4722 2323 4722 2398 4722 2398 4723 2323 4723 2386 4723 2398 4724 2386 4724 2399 4724 2399 4725 2386 4725 2387 4725 2399 4726 2387 4726 2400 4726 2400 4727 2387 4727 2388 4727 2400 4728 2388 4728 2401 4728 2401 4729 2388 4729 2389 4729 2401 4730 2389 4730 2402 4730 2402 4731 2389 4731 2390 4731 2402 4732 2390 4732 2403 4732 2403 4733 2390 4733 2391 4733 2403 4734 2391 4734 2404 4734 2404 4735 2391 4735 2392 4735 2404 4736 2392 4736 2405 4736 2405 4737 2392 4737 2393 4737 2405 4738 2393 4738 2406 4738 2406 4739 2393 4739 2394 4739 2406 4740 2394 4740 2407 4740 2407 4741 2394 4741 2395 4741 2407 4742 2395 4742 2408 4742 2408 4743 2395 4743 2396 4743 2408 4744 2396 4744 2409 4744 2409 4745 2396 4745 2397 4745 2409 4746 2397 4746 2410 4746 2051 4747 2050 4747 2371 4747 2371 4748 2050 4748 2324 4748 2371 4749 2324 4749 2372 4749 2372 4750 2324 4750 2322 4750 2372 4751 2322 4751 2373 4751 2373 4752 2322 4752 2321 4752 2373 4753 2321 4753 1632 4753 1632 4754 2321 4754 2398 4754 1632 4755 2398 4755 1633 4755 1633 4756 2398 4756 2399 4756 1633 4757 2399 4757 1634 4757 1634 4758 2399 4758 2400 4758 1634 4759 2400 4759 1628 4759 1628 4760 2400 4760 2401 4760 1628 4761 2401 4761 1626 4761 1626 4762 2401 4762 2402 4762 1626 4763 2402 4763 1570 4763 1570 4764 2402 4764 2403 4764 1570 4765 2403 4765 1571 4765 1571 4766 2403 4766 2404 4766 1571 4767 2404 4767 1615 4767 1615 4768 2404 4768 2405 4768 1615 4769 2405 4769 1617 4769 1617 4770 2405 4770 2406 4770 1617 4771 2406 4771 1619 4771 1619 4772 2406 4772 2407 4772 1619 4773 2407 4773 1621 4773 1621 4774 2407 4774 2408 4774 1621 4775 2408 4775 1623 4775 1623 4776 2408 4776 2409 4776 1623 4777 2409 4777 1611 4777 1611 4778 2409 4778 2410 4778 1611 4779 2410 4779 1612 4779 76 4780 79 4780 2411 4780 2412 4781 2413 4781 2414 4781 2066 4782 2415 4782 2073 4782 2073 4783 2415 4783 2416 4783 2073 4784 2416 4784 2067 4784 2067 4785 2416 4785 2414 4785 2067 4786 2414 4786 2068 4786 2068 4787 2414 4787 2413 4787 2068 4788 2413 4788 2069 4788 2417 4789 2418 4789 2419 4789 2419 4790 2418 4790 2412 4790 2412 4791 2414 4791 2419 4791 2419 4792 2414 4792 2416 4792 2419 4793 2416 4793 2420 4793 2420 4794 2416 4794 2415 4794 2420 4795 2415 4795 2421 4795 2066 4796 2316 4796 2415 4796 2415 4797 2316 4797 2317 4797 2415 4798 2317 4798 2421 4798 2421 4799 2317 4799 2318 4799 2421 4800 2318 4800 2319 4800 2417 4801 2419 4801 2411 4801 2411 4802 2419 4802 2420 4802 2411 4803 2420 4803 2422 4803 2422 4804 2420 4804 2421 4804 2422 4805 2421 4805 2423 4805 2423 4806 2421 4806 2319 4806 2423 4807 2319 4807 2320 4807 79 4808 70 4808 2411 4808 2411 4809 70 4809 2424 4809 2411 4810 2424 4810 2417 4810 76 4811 2411 4811 90 4811 90 4812 2411 4812 2422 4812 90 4813 2422 4813 84 4813 84 4814 2422 4814 2423 4814 84 4815 2423 4815 86 4815 86 4816 2423 4816 2320 4816 86 4817 2320 4817 28 4817 2425 4818 14 4818 2107 4818 2426 4819 2425 4819 2427 4819 2428 4820 2426 4820 2429 4820 2082 4821 2428 4821 2430 4821 2425 4822 2107 4822 2427 4822 2427 4823 2107 4823 2106 4823 2427 4824 2106 4824 2431 4824 2431 4825 2106 4825 2105 4825 2431 4826 2105 4826 2432 4826 2432 4827 2105 4827 2110 4827 2432 4828 2110 4828 2433 4828 2433 4829 2110 4829 2108 4829 2433 4830 2108 4830 2434 4830 2434 4831 2108 4831 1612 4831 2434 4832 1612 4832 2410 4832 2426 4833 2427 4833 2429 4833 2429 4834 2427 4834 2431 4834 2429 4835 2431 4835 2435 4835 2435 4836 2431 4836 2432 4836 2435 4837 2432 4837 2436 4837 2436 4838 2432 4838 2433 4838 2436 4839 2433 4839 2437 4839 2437 4840 2433 4840 2434 4840 2437 4841 2434 4841 2438 4841 2438 4842 2434 4842 2410 4842 2438 4843 2410 4843 2397 4843 2428 4844 2429 4844 2430 4844 2430 4845 2429 4845 2435 4845 2430 4846 2435 4846 2439 4846 2439 4847 2435 4847 2436 4847 2439 4848 2436 4848 2440 4848 2440 4849 2436 4849 2437 4849 2440 4850 2437 4850 2441 4850 2441 4851 2437 4851 2438 4851 2441 4852 2438 4852 2442 4852 2442 4853 2438 4853 2397 4853 2442 4854 2397 4854 2385 4854 2082 4855 2430 4855 2047 4855 2047 4856 2430 4856 2439 4856 2047 4857 2439 4857 2022 4857 2022 4858 2439 4858 2440 4858 2022 4859 2440 4859 2023 4859 2023 4860 2440 4860 2441 4860 2023 4861 2441 4861 2032 4861 2032 4862 2441 4862 2442 4862 2032 4863 2442 4863 2014 4863 2014 4864 2442 4864 2385 4864 2014 4865 2385 4865 2036 4865 70 4866 24 4866 2424 4866 2424 4867 24 4867 2443 4867 2424 4868 2443 4868 2417 4868 2417 4869 2443 4869 2444 4869 2417 4870 2444 4870 2418 4870 2418 4871 2444 4871 2445 4871 2418 4872 2445 4872 2412 4872 2412 4873 2445 4873 2446 4873 2412 4874 2446 4874 2413 4874 2413 4875 2446 4875 2447 4875 2413 4876 2447 4876 2069 4876 2069 4877 2447 4877 2086 4877 2448 4878 2080 4878 2086 4878 2086 4879 2447 4879 2448 4879 2448 4880 2447 4880 2446 4880 2448 4881 2446 4881 2449 4881 2082 4882 2081 4882 2428 4882 2428 4883 2081 4883 2450 4883 2428 4884 2450 4884 2426 4884 2426 4885 2450 4885 2451 4885 2426 4886 2451 4886 2425 4886 2425 4887 2451 4887 2452 4887 2425 4888 2452 4888 14 4888 14 4889 2452 4889 15 4889 2081 4890 2080 4890 2450 4890 2450 4891 2080 4891 2448 4891 2450 4892 2448 4892 2451 4892 2451 4893 2448 4893 2449 4893 2451 4894 2449 4894 2452 4894 2452 4895 2449 4895 2453 4895 2452 4896 2453 4896 15 4896 15 4897 2453 4897 22 4897 2446 4898 2445 4898 2449 4898 2449 4899 2445 4899 2444 4899 2449 4900 2444 4900 2453 4900 2453 4901 2444 4901 2443 4901 2453 4902 2443 4902 22 4902 22 4903 2443 4903 24 4903

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_distal/mst/f_distal_mstXL.dae b/URDFs/sr_description/meshes/components/f_distal/mst/f_distal_mstXL.dae new file mode 100644 index 0000000..d4feec1 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_distal/mst/f_distal_mstXL.dae @@ -0,0 +1,134 @@ + + + + + + Blender User + Blender 2.81.16 commit date:2019-11-20, commit time:14:27, hash:26bd5ebd42e3 + + 2023-06-06T16:24:22 + 2023-06-06T16:24:22 + + Z_UP + + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + + -0.3852578 4.659123 30.62976 -0.4077195 4.544668 31.01401 -0.1994276 4.546315 31.0238 -0.1910614 4.660678 30.63852 0 4.547132 31.02775 0 4.661406 30.64153 -6.995942 3.554601 7.515748 -6.739554 3.615183 7.514828 -4.552856 -5.488432 7.460766 -8.624077 0.3256195 7.507933 -8.623839 0.3294724 7.507951 -4.145488 -5.640344 7.45811 -6.200851 3.754677 7.512952 -3.380938 -5.870325 7.453392 -5.697324 3.991578 7.51171 0 3.990212 7.484765 0 1.7027 7.473789 0 1.679777 7.473679 -0.1691622 -6.335631 7.435978 -0.02423286 -6.338644 7.435279 0 -6.338672 7.435163 -7.704483 -3.056009 7.487344 -8.001416 -2.559956 7.49113 -8.22521 2.116654 7.514651 -8.195309 2.193601 7.51488 -7.659863 -3.121376 7.486819 -5.214056 -5.189775 7.465325 -5.823405 -4.845697 7.469858 -8.245077 -2.035943 7.494799 -8.432944 -1.487819 7.49832 -8.466485 -1.364124 7.499072 -8.556266 0.9215645 7.510475 -8.422959 1.514728 7.512695 -0.8276574 -6.283894 7.439339 -1.625497 -6.197403 7.443524 -2.494235 -6.064588 7.448269 -8.578139 -0.8112064 7.502256 -8.630726 -0.2472804 7.505213 -6.382268 -4.455299 7.474374 -6.869163 -4.038049 7.47868 -7.291973 -3.595682 7.482802 -8.01532 2.589718 7.515932 -7.842585 2.878582 7.516503 -7.651945 3.121139 7.516767 -7.433705 3.323333 7.516706 -7.217143 3.461803 7.516348 -6.194423 4.246432 7.626105 -6.136058 4.199361 7.594026 -6.329173 4.110642 7.590629 -5.780876 3.963184 7.512105 -5.77704 3.964515 7.512087 -6.50862 4.61199 8.129681 -6.883635 4.534511 8.182246 -6.532425 4.681048 8.508993 -6.890853 4.586133 8.443367 -6.890849 4.587999 8.519728 -6.859588 4.376798 7.890617 -6.872302 4.45945 8.014522 -6.8801 4.510851 8.119771 -6.852962 4.334054 7.839582 -6.437247 4.41169 7.807196 -6.821488 4.132681 7.668234 -6.81688 4.103363 7.650176 -6.754728 3.7105 7.520076 -6.773653 3.829679 7.540168 -6.812523 4.075673 7.634392 -5.821072 3.965092 7.512883 -5.798767 3.955842 7.512198 -5.840595 3.977452 7.514004 -5.961359 4.06512 7.531941 -5.792663 3.955805 7.512117 -5.789486 3.956521 7.512091 -5.786397 3.957751 7.512077 -6.475083 4.539914 7.975389 -6.45263 4.501259 7.911191 -6.367914 4.401417 7.774181 -6.333549 4.367826 7.736061 -6.476868 4.70205 8.508831 -6.477283 4.699042 8.430096 -6.47989 4.682714 8.320495 -6.490156 4.617287 8.126259 -6.498351 4.485724 25.31396 -6.369133 4.51342 25.48177 -6.503545 4.485597 25.28116 -6.431876 4.508247 25.14949 -6.515617 4.486702 25.15674 -6.480821 4.504714 24.80005 -6.537915 4.490764 24.80217 -6.407636 4.491379 25.78687 -6.295811 4.495054 26.24455 -6.193591 4.528015 26.14358 -6.23874 4.495465 26.43492 -6.003794 4.53513 26.65713 -6.035607 4.495077 26.98235 -5.772828 4.539599 27.15004 -5.80465 4.493168 27.46871 -5.501148 4.542653 27.62225 -5.504621 4.49035 27.98035 -5.188168 4.545464 28.0734 -5.241287 4.488285 28.35715 -4.859444 4.486639 28.82021 -4.649793 4.551382 28.69667 -4.435687 4.486954 29.25025 -4.039853 4.562277 29.2439 -3.965154 4.490604 29.64681 -3.773055 4.49278 29.78938 -3.593666 4.5729 29.5665 -3.253636 4.499728 30.12851 -2.87907 4.594678 29.97431 -2.725655 4.508023 30.40979 -2.183125 4.517264 30.63883 -2.12481 4.619101 30.28639 -1.624246 4.526882 30.81653 -1.599989 4.6347 30.44199 -1.513299 4.52875 30.8451 -0.996412 4.649472 30.56431 -0.9608784 4.537595 30.95536 -6.476877 4.70198 8.51883 -6.866467 4.581164 11.84543 -6.484518 4.655061 15.7332 -6.785133 4.557948 17.33661 -6.488827 4.635888 17.3324 -6.70733 4.535815 20.6697 -6.500632 4.586265 20.66652 -6.66163 4.523605 22.07334 -6.507496 4.559619 22.06871 -6.608373 4.51401 23.15483 -6.515387 4.53902 22.94535 -6.567428 4.502006 24.00927 -6.51842 4.509323 24.16161 -6.560411 4.498241 24.23535 -6.507563 4.505027 24.48369 -6.476873 4.702015 8.513859 -9.591644 -0.4273777 10.02411 -9.473944 -1.322612 9.882324 -9.416841 -1.441257 11.49658 -9.518495 0.2993904 13.72925 -9.460441 0.2114446 15.51617 -9.437433 0.7569615 15.58599 -5.425392 -6.294974 10.18628 -5.541988 -6.184171 9.447391 -4.649769 -6.552901 9.137316 -5.218687 -7.262873 18.56287 -4.878103 -7.405579 17.78322 -4.545988 -7.538215 18.15952 -4.721236 -7.30918 15.59906 -4.480757 -7.435667 15.95343 -5.176546 -7.263447 17.38041 -8.242352 1.248183 27.51428 -8.583829 1.250017 26.60383 -8.607059 0.4522818 26.56599 -7.758169 1.675135 28.35441 -7.693757 2.063664 28.30056 -8.128836 2.060617 27.43542 -1.266512 2.499809 32.65171 -1.659837 2.499973 32.57558 -1.694456 2.029254 32.66672 -3.29395 2.500046 32.04115 -3.530043 2.500002 31.93368 -3.487191 2.080714 32.06733 -7.946135 2.499999 27.50725 -8.022262 2.5 27.32973 -0.861419 -7.284003 8.437583 -1.316086 -7.311907 9.205207 -1.494789 -7.258043 8.904948 -1.079268 -7.368261 9.45376 -0.6269387 -7.306148 8.434605 -0.3919047 -7.324201 8.432576 -0.3055659 -7.627554 11.29237 -0.6310725 -7.608762 11.24153 0 -7.49332 10.04633 0 -8.228553 20.23387 0 -8.141331 21.26795 -0.465334 -8.153451 21.08721 -0.7613016 1.997612 32.81473 -1.30019e-4 1.798137 32.87407 0 2.499991 32.75782 -0.808685 1.200192 32.87021 2.39599e-4 1.1117 32.90667 -0.8222302 0.73775 32.85518 -9.26249e-6 0.4024347 32.85872 -0.8156329 0.2358542 32.79879 -0.8094603 -0.3194938 32.68709 -4.69057e-5 -0.2468729 32.7413 -0.8035609 -0.9246494 32.5001 -9.82361e-6 -0.8665786 32.55774 -0.7957666 -1.541163 32.23429 0 -1.420626 32.32912 -0.7856566 -2.134045 31.89728 0 -2.025738 32.00276 -0.7741558 -2.654766 31.51922 0 -2.553005 31.63708 0 -2.805042 31.43103 -0.763546 -3.075607 31.15095 0 -2.810116 31.42665 -0.7438845 -3.824804 30.41549 0 -3.565846 30.71832 -0.7224712 -4.526594 29.62985 0 -4.27321 29.96336 -0.6993019 -5.176815 28.79752 0 -4.95605 29.13104 -0.674458 -5.770873 27.92318 0 -5.585276 28.24834 -0.6480974 -6.305493 27.01237 0 -6.148558 27.33326 -0.6203293 -6.778194 26.07 0 -6.648547 26.38423 -0.5912975 -7.186314 25.10156 0 -7.080824 25.41092 -0.5611847 -7.52829 24.11352 0 -7.443078 24.42364 0 -7.722224 23.4824 -0.5300741 -7.803684 23.11129 0 -7.729709 23.4539 0 -7.792471 23.20591 -0.4980552 -8.011978 22.10039 0 -8.000519 22.2217 -0.6852314 -8.139379 16.29756 0 -8.186342 16.85948 -0.3689144 -8.230053 18.15055 0 -8.247663 18.91818 0 -8.23528 20.09197 0 -7.633377 11.30745 0 -7.85686 13.08662 -0.5539324 -8.008416 14.55904 0 -8.0224 14.59405 0 -8.056954 14.97362 0 -7.337812 8.431448 -1.491523 -7.492717 10.88732 -1.726791 -7.439855 10.70616 -1.227964 -7.539582 11.0377 -0.939854 -7.578835 11.15618 -0.3512001 -7.326706 8.432293 -0.1953149 -7.334146 8.431363 -1.629291 -7.210931 8.540122 -1.167431 -7.253106 8.439887 -1.088074 -7.261226 8.441682 -2.584971 -7.115419 9.171056 -2.721509 -7.038443 8.469098 -1.938586 -7.163971 8.458686 -3.708634 -6.837252 8.813295 -3.747188 -6.805824 8.477575 -3.313093 -6.914957 8.474513 -4.720898 -6.492514 8.483174 -4.550251 -6.555076 8.482218 -4.763256 -6.476435 8.483412 -5.623918 -6.104545 8.669816 -6.671559 -5.475899 8.495901 -5.663363 -6.078186 8.4888 -5.637038 -6.091498 8.488632 -9.043797 -2.679994 8.52003 -8.91559 -2.945402 8.518482 -8.883622 -3.007945 9.569665 -8.519438 -3.618191 8.513792 -9.500641 -1.264764 8.52502 -9.405961 -1.67226 8.52419 -9.594248 -0.6118859 8.525337 -9.611204 -0.3767178 8.525202 -9.558512 0.8807568 8.51504 -9.602169 0.4623083 8.513236 -9.591907 0.4324343 10.14367 -9.451779 1.461397 8.517326 -9.441379 1.371175 11.97287 -9.278673 2.003922 11.95594 -9.306818 1.996351 8.519208 -9.105241 2.499712 11.60816 -9.131299 2.500642 8.515961 -9.082827 2.036301 19.16194 -8.915924 2.057432 22.7683 -8.848814 2.50005 20.8673 -8.680941 2.5 24.25906 -8.810562 2.070766 24.594 -8.679738 2.078666 25.5725 -8.59538 2.499995 25.15443 -8.434517 2.5 26.02232 -8.457985 2.069258 26.5155 -8.337365 2.499559 26.4093 -8.212797 2.500083 26.81993 -7.195494 2.499808 28.84321 -7.424633 2.499899 28.49292 -7.604228 2.5 28.1887 -7.864122 2.499997 27.68617 -6.684694 1.307391 29.91198 -5.872738 2.09433 30.51451 -6.554801 2.084937 29.84438 -5.599078 2.500089 30.59944 -6.1805 2.500057 30.06237 -6.297779 2.500029 29.94221 -6.476703 2.500001 29.75003 -6.719381 2.499958 29.47036 -2.760452 2.50013 32.25505 -2.018017 2.500014 32.48875 -2.435658 2.500097 32.36629 -2.605854 2.058395 32.415 -0.5847228 2.49969 32.73559 -9.070445 1.282405 22.82509 -9.112306 0.5702427 22.7974 -8.997868 0.5241138 24.62324 -8.995043 0.1284058 24.55995 -8.850131 0.07127863 25.54513 -8.855781 0.4886006 25.6126 -8.597678 0.01470124 26.49498 -8.825457 1.261243 25.65006 -8.96303 1.269174 24.65871 -8.24714 -0.03865969 27.39622 -8.260543 0.4160197 27.47147 -7.828924 0.8201069 28.36293 -7.807102 1.263193 28.373 -7.312742 0.8043482 29.16387 -7.285467 1.2856 29.174 -6.717905 0.7908788 29.90293 -7.823579 0.380956 28.3261 -7.806554 -0.08787792 28.24632 -7.282386 -0.1326725 29.03962 -7.302365 0.348421 29.12405 -6.680936 -0.172865 29.77066 -6.703045 0.319429 29.8597 -7.165268 2.073343 29.10506 -6.899524 2.499882 29.24664 -9.043079 -0.2351925 23.53777 -9.015275 -0.6433091 23.38624 -8.947793 -0.716773 24.28992 -8.939009 -1.627365 21.91078 -8.817547 -2.222274 21.48052 -8.869259 -1.729539 22.7572 -8.74172 -2.338781 22.30016 -8.790682 -1.844844 23.62391 -8.656485 -2.469053 23.13951 -8.618019 -2.013392 24.55021 -9.038627 -0.9583041 22.32346 -8.975459 -1.038495 23.19485 -8.904538 -1.129418 24.08723 -8.744467 -1.264699 25.04231 -8.475517 -1.394524 25.96274 -8.978425 -0.2906367 24.45059 -8.79399 -0.8261894 25.25789 -8.829566 -0.3735286 25.42867 -8.531538 -0.9318225 26.19122 -8.572484 -0.4542604 26.37184 -8.172715 -1.028253 27.07374 -8.217942 -0.528799 27.26525 -7.726491 -1.116565 27.90503 -7.774506 -0.5971118 28.10743 -7.19952 -1.196746 28.67986 -7.248731 -0.6591417 28.89292 -8.475498 -2.654298 24.03681 -8.337108 -2.17401 25.44193 -8.038908 -1.948964 26.55774 -8.111726 -1.511887 26.83143 -7.586752 -2.070891 27.35973 -7.662403 -1.619134 27.64885 -7.058072 -2.181216 28.10602 -7.134325 -1.716358 28.41014 -6.459213 -2.280203 28.79217 -6.533848 -1.803694 29.11055 -6.646928 -0.714888 29.61644 -6.598133 -1.268834 29.39321 -8.188235 -2.830298 24.90071 -7.814029 -2.986673 25.71183 -7.965297 -2.317381 26.28078 -7.512028 -2.44802 27.06881 -7.361881 -3.129511 26.47344 -6.984145 -2.566261 27.80176 -6.838366 -3.259213 27.18158 -6.387916 -2.672421 28.47539 -8.671477 -2.793444 21.02888 -8.589613 -2.922598 21.81957 -8.497635 -3.066026 22.62916 -8.308428 -3.265547 23.49435 -8.015689 -3.454457 24.32725 -7.640492 -3.621643 25.10797 -7.191097 -3.774622 25.84068 -9.075537 -0.5784108 22.50392 -9.100876 -0.1861228 22.64658 -1.783451 1.23493 32.72644 -1.809149 0.7431504 32.71256 -1.796374 0.2376083 32.6562 -1.784019 -0.3131555 32.54583 -1.771396 -0.9150438 32.36053 -1.754557 -1.5286 32.09676 -1.732688 -2.118721 31.7624 -1.707792 -2.637314 31.38725 -8.830416 -2.779909 17.51534 -8.657453 -3.260958 17.14869 -8.304785 -3.853174 20.06167 -8.085213 -4.335319 19.54869 -8.211114 -4.00206 20.78898 -7.985858 -4.491079 20.24203 -8.105613 -4.165707 21.53291 -7.873782 -4.661486 20.95062 -7.900848 -4.385326 22.32588 -7.662216 -4.886377 21.70428 -7.600301 -4.591684 23.08872 -1.103734 -7.986411 22.02826 -1.174201 -7.777069 23.03282 -1.242605 -7.500996 24.02872 -1.308745 -7.158719 25.01046 -1.372434 -6.750683 25.97271 -1.43327 -6.278459 26.90903 -1.490936 -5.744702 27.81401 -1.545192 -5.151884 28.68278 -1.595688 -4.503284 29.50983 -1.642236 -3.803507 30.29054 -1.684835 -3.056708 31.0215 -5.066554 -7.052162 14.8653 -4.922716 -7.174747 15.2281 -5.661072 -6.937183 16.49736 -5.443068 -7.106013 16.94863 -6.032726 -6.749757 17.15191 -5.809585 -6.935453 17.64682 -6.388274 -6.515115 17.80619 -6.162295 -6.715247 18.34509 -6.499646 -6.444968 19.03958 -6.205955 -6.641574 19.59874 -6.520627 -6.330359 20.32773 -6.171973 -6.510875 20.889 -6.461391 -6.152986 21.64542 -6.0508 -6.323101 22.2079 -6.313118 -5.914024 22.98472 -5.8383 -6.071048 23.54075 -6.071457 -5.607819 24.32954 -5.531149 -5.749313 24.87041 -5.733928 -5.230309 25.66242 -5.127781 -5.3543 26.17864 -5.299765 -4.778394 26.9649 -4.628315 -4.883443 27.44626 -4.769342 -4.251198 28.21687 -4.034036 -4.336429 28.65255 -4.145126 -3.650337 29.39825 -3.348253 -3.715544 29.77687 -3.431462 -2.978254 30.48935 -2.576041 -3.024057 30.7992 -3.47597 -2.56466 30.84471 -2.610348 -2.607106 31.1606 -3.524053 -2.054752 31.20775 -2.647512 -2.092147 31.5307 -3.56616 -1.475991 31.53111 -2.680118 -1.506766 31.86048 -3.598497 -0.8746756 31.78631 -2.705193 -0.898311 32.12068 -3.622251 -0.285897 31.96476 -2.723809 -0.3019768 32.3031 -3.642781 0.2482167 32.06995 -2.740939 0.2413267 32.41124 -3.662741 0.7547896 32.12465 -2.758146 0.7487091 32.46712 -3.623636 1.30063 32.13413 -2.724158 1.270791 32.47897 -5.198221 -6.933233 14.50403 -5.806146 -6.788526 16.0595 -6.175362 -6.590497 16.67468 -6.527475 -6.347683 17.28944 -6.726255 -6.23321 18.45655 -6.81931 -6.125743 19.72605 -6.818548 -5.96844 21.04481 -6.734778 -5.742777 22.38577 -6.559482 -5.452146 23.74034 -6.289135 -5.092181 25.09199 -5.922056 -4.659313 26.42294 -5.457699 -4.152173 27.71374 -4.897682 -3.57178 28.9449 -4.24564 -2.919838 30.09714 -4.299065 -2.510444 30.44487 -4.356521 -2.006938 30.79903 -4.406705 -1.436586 31.11429 -4.445173 -0.8443574 31.36314 -4.473113 -0.2649113 31.53667 -4.495742 0.259119 31.63835 -4.516781 0.7617302 31.69107 -4.475354 1.320186 31.69873 -5.531982 -7.108149 18.12076 -5.875627 -6.901095 18.86155 -3.920593 -7.659834 16.5916 -2.73953 -7.855153 15.53619 -3.305297 -7.701333 15.10384 -3.790283 -7.524902 14.59493 -4.181653 -7.322941 14.01408 -5.774077 -6.677609 21.41442 -5.867474 -6.815681 20.12029 -5.483855 -6.97686 20.60832 -5.548964 -7.066532 19.34328 -5.181146 -7.220068 19.79383 -4.868062 -7.406855 18.97613 -4.482529 -7.540216 19.35897 -4.182327 -7.661333 18.50788 -3.78944 -7.774577 18.8267 -3.25825 -7.854104 17.13623 -1.929803 -7.381883 10.49484 -3.912407 -4.974025 27.863 -4.475239 -5.463865 26.63702 -3.780771 -5.558485 27.03379 -4.311176 -5.989132 25.79418 -3.640024 -6.086491 26.17012 -4.136831 -6.456868 24.92219 -3.490766 -6.555636 25.27656 -3.9531 -6.864493 24.02597 -3.333766 -6.963316 24.35821 -3.761127 -7.21037 23.11123 -3.170012 -7.307913 23.42101 -3.561506 -7.493979 22.18286 -2.999998 -7.588933 22.46999 -3.354881 -7.71472 21.24588 -2.82426 -7.805801 21.51034 -2.643958 -7.958652 20.54816 -2.123964 -8.030776 20.7495 -1.974983 -8.115693 19.77087 -1.473547 -8.168795 19.91453 -5.314599 -6.214018 24.05103 -5.590828 -6.479374 22.72989 -5.085374 -6.621903 23.20879 -5.330532 -6.831071 21.90184 -4.844875 -6.971274 22.34885 -5.058257 -7.125509 21.06087 -4.593872 -7.261548 21.47573 -4.774939 -7.361969 20.21144 -4.333212 -7.492055 20.59411 -4.064667 -7.662679 19.70958 -3.617125 -7.773725 20.02603 -3.369739 -7.877387 19.11427 -2.925715 -7.969063 19.36876 -2.509257 -8.014591 17.57724 -2.105371 -7.982631 15.88475 -1.416045 -8.079113 16.14141 -3.256668 -4.407337 29.01635 -3.156729 -5.049513 28.21094 -3.048851 -5.637443 27.36499 -2.933756 -6.167824 26.48384 -2.811931 -6.638222 25.5722 -2.684006 -7.046011 24.63529 -2.55079 -7.389593 23.67925 -2.412676 -7.668493 22.70924 -2.270089 -7.882156 21.7306 -1.585544 -8.088013 20.90802 -0.9583241 -8.207094 20.0172 -2.512196 -3.766831 30.07596 -2.442189 -4.463229 29.3037 -2.366029 -5.109109 28.4857 -2.284018 -5.699854 27.62649 -2.196692 -6.232175 26.73149 -2.10442 -6.703616 25.80549 -2.007679 -7.111533 24.85386 -1.907083 -7.454345 23.88288 -1.802922 -7.731592 22.89782 -1.69551 -7.942737 21.90411 -1.031659 -8.129287 21.02138 -0.4320698 -8.229516 20.07677 -4.942962 -5.876539 25.35975 -4.746107 -6.342772 24.51257 -4.538218 -6.750446 23.64179 -4.320582 -7.097898 22.7529 -4.093884 -7.384581 21.85056 -3.858872 -7.609862 20.93968 -3.142627 -7.872659 20.30627 -2.459926 -8.048794 19.58828 -1.690318 -8.135831 17.90333 -1.26003 -8.17978 18.01955 -0.8188123 -8.211485 18.10249 -1.145224 -7.963145 14.44256 -6.822399 -5.586069 12.0117 -7.496156 -5.016303 12.5887 -6.982068 -5.378784 11.05137 -7.649097 -4.787122 11.49304 -7.108852 -5.210576 10.06074 -7.770527 -4.60136 10.37124 -7.19828 -5.089711 9.0361 -7.856139 -4.468043 9.219854 -7.227371 -5.048713 8.500577 -7.043547 -5.199028 8.498964 -6.454244 -5.634036 8.85259 -6.365863 -5.734955 9.752407 -6.240403 -5.87536 10.61509 -6.082145 -6.048351 11.44438 -5.683178 -6.46526 13.01812 -6.421288 -6.085622 13.85657 -5.936944 -6.646123 15.62558 -6.776717 -5.844275 14.28645 -6.302978 -6.439302 16.20296 -7.112413 -5.569303 14.71555 -6.651321 -6.190032 16.77983 -4.251388 2.500045 31.55342 -4.330642 2.094058 31.63078 -5.273341 1.327513 31.17939 -5.314404 0.7698538 31.17233 -5.293937 0.2745384 31.12234 -5.270414 -0.2390469 31.02459 -5.239323 -0.8075418 30.85682 -5.19599 -1.388815 30.61551 -5.139322 -1.949028 30.30987 -5.074216 -2.444829 29.96624 -5.013279 -2.849234 29.62758 -5.600845 -3.480286 28.42143 -6.094187 -4.039689 27.14735 -6.490386 -4.526405 25.82416 -6.788687 -4.939934 24.47075 -6.99057 -5.282069 23.10587 -7.098756 -5.556676 21.74648 -7.120276 -5.758745 20.40114 -7.044544 -5.905556 19.09911 -6.86116 -6.060126 17.9003 -4.443558 -7.132038 13.42793 -4.903494 -6.761184 12.2074 -5.277845 -6.431562 10.89013 -4.546511 -6.635418 9.753232 -1.704543 -7.890759 14.25012 -2.221827 -7.795297 13.98738 -1.709082 -7.678233 12.4752 -2.68729 -7.68047 13.65964 -2.072129 -7.60038 12.24354 -3.091694 -7.549489 13.27167 -2.392031 -7.512043 11.96719 -3.425366 -7.401857 12.8265 -2.662014 -7.413941 11.64793 -3.663668 -7.259645 12.37039 -2.867544 -7.317634 11.3138 -4.080297 -6.982787 11.40268 -3.225521 -7.129592 10.58755 -4.415374 -6.73714 10.33382 -3.510562 -6.962676 9.761919 -2.091148 -7.324772 10.26921 -2.368533 -7.213617 9.764197 -2.906119 -7.002798 8.470974 -9.446412 -0.3225691 15.35251 -9.515446 -0.1868253 13.60431 -9.402807 -0.8299177 15.14077 -9.607918 0.3845321 8.51371 -9.605139 0.01349538 10.09227 -9.568719 -0.07212162 11.85131 -9.54754 -0.5277512 11.73649 -9.484009 -0.6647737 13.44157 -9.335749 -1.604927 13.10025 -9.233595 -1.804439 14.6952 -8.954894 -2.725703 14.21486 -9.01638 2.499984 16.10078 -9.203248 2.017673 15.55964 -9.364894 1.344401 15.59032 -9.52522 0.837639 11.97376 -9.562447 0.3750269 11.93872 -9.074309 -2.501656 12.73386 -9.169438 -2.319043 11.24016 -9.236643 -2.187442 9.731491 -9.266428 -2.125338 8.522672 -8.56923 -3.576602 13.69902 -8.702548 -3.339204 12.34055 -8.80868 -3.146428 10.965 -9.468975 1.3846 8.517038 -8.197319 1.665972 27.49255 -8.535965 1.671793 26.57673 -8.769765 1.681988 25.62672 -8.904258 1.680928 24.63948 -9.009287 1.679273 22.80742 -9.241703 1.312717 19.20609 -9.266243 -0.6318339 18.83986 -9.304669 0.01574921 19.08301 -9.299101 0.6630939 19.19197 -8.45944 -3.717227 16.76843 -8.236835 -4.147069 16.37601 -7.842356 -4.782815 19.01899 -8.977653 -2.276602 17.86715 -8.500493 -3.338257 20.55575 -8.412672 -3.478246 21.31559 -8.313905 -3.632859 22.09327 -8.116687 -3.843954 22.92355 -7.819451 -4.043058 23.72261 -7.44471 -4.218698 24.47057 -7.737528 -4.943364 19.67714 -7.576829 -5.193575 18.47486 -7.99016 -4.548638 15.97297 -8.081027 -4.34376 13.15465 -8.22527 -4.104622 11.92535 -8.339903 -3.910764 10.67438 -8.420752 -3.771666 9.398651 -7.845768 -4.462212 8.506494 -7.619117 -5.118174 20.34903 -7.466777 -5.356751 19.09679 -7.289464 -5.56578 17.91872 -7.720175 -4.920243 15.56088 -9.19491 -1.214329 18.52797 -5.0046 2.500006 31.0641 -5.128488 2.098178 31.11145 -6.011803 1.32263 30.58205 -6.049957 0.7794712 30.57434 -6.03162 0.2946728 30.52761 -6.008301 -0.208347 30.4341 -5.975166 -0.7643612 30.27282 -5.928356 -1.332864 30.0401 -5.866947 -1.881246 29.74539 -5.796066 -2.368052 29.41377 -5.729136 -2.766725 29.08546 -6.249498 -3.376086 27.83225 -6.673756 -3.913872 26.52172 -6.999732 -4.379628 25.17221 -7.227556 -4.773306 23.80197 -7.359732 -5.096951 22.42893 -7.401688 -5.344975 21.06167 -7.342371 -5.533508 19.73088 -7.174481 -5.729369 18.50367 -6.980754 -5.898362 17.35288 -7.427389 -5.260854 15.1412 -3.06227 4.304554 30.851 -2.273611 4.313243 31.19863 -6.135102 4.301513 27.90786 -5.668271 4.298001 28.62859 -6.949011 4.301378 25.50298 -7.124711 4.315168 23.81519 -6.785403 4.300594 26.3247 -6.509988 4.303389 27.13824 -5.118463 4.294921 29.29185 -4.494649 4.294341 29.88905 -3.805966 4.2978 30.41162 -1.450043 4.322506 31.44598 -0.5998766 4.330926 31.58456 0 4.310249 31.6574 0 3.273673 32.50933 -0.6309801 3.29538 32.46728 -1.523433 3.292702 32.33426 -2.393127 3.289793 32.09536 -3.232275 3.287098 31.75887 -4.032562 3.285049 31.3331 -4.785675 3.284081 30.82632 -5.483233 3.284426 30.2464 -6.1166 3.28558 29.59963 -6.677084 3.286865 28.89194 -7.15599 3.287604 28.12927 -7.544889 3.286804 27.31668 -7.832471 3.287176 26.47132 -8.464855 3.301554 19.3165 -8.585982 3.3061 15.72364 -8.817128 2.917103 15.80171 -8.295942 3.295497 22.9119 -8.167611 3.291929 24.70754 -8.028655 3.289797 25.59697 -7.084046 4.550505 8.520973 -7.266661 4.499995 8.521593 -7.635361 4.352612 8.522626 -7.465746 4.355044 15.33398 -7.231858 4.325336 22.11664 -7.006501 3.616985 27.91246 -7.368267 3.615731 27.09826 -7.182812 3.894339 26.86012 -7.410059 3.894976 26.02473 0 3.910372 32.12145 -0.6165846 3.9132 32.08376 -1.489545 3.907711 31.94612 -2.337828 3.901684 31.70116 -3.153381 3.896051 31.35725 -3.927024 3.891709 30.92284 -4.649573 3.889555 30.40632 -5.311911 3.890076 29.81592 -5.905149 3.892253 29.15906 -6.420458 3.89471 28.44301 -6.849005 3.896077 27.67502 -8.228994 3.93566 8.523429 -8.064993 3.931981 15.54428 -7.789821 3.911352 22.54448 -7.668779 3.904366 24.29526 -7.554617 3.900165 25.16552 -8.949592 2.921332 8.521965 -8.722071 3.330932 8.522855 -9.527616 1.082456 8.505863 -9.451826 1.461445 8.507325 -9.372043 1.7753 8.508456 -9.14589 2.463714 8.510692 -0.02523338 -7.23062 7.986043 0 -7.169497 7.879528 0 -7.329617 8.338355 -9.001757 0.3493063 7.585172 -9.00172 0.3513675 7.58522 -9.321327 0.368667 7.801411 -9.321248 0.3708374 7.801481 -9.117315 0.3585029 7.643061 0 -6.810336 7.552173 0 -7.010308 7.693464 -0.02572846 -7.010307 7.693616 -0.0239616 -7.329585 8.338543 -0.2006235 -7.325987 8.340023 -0.1987732 -7.22724 7.987303 -0.9226842 -7.270146 8.346724 -0.9146584 -7.172571 7.992993 -1.744689 -7.181197 8.35452 -1.73442 -7.084749 7.999649 -1.938632 -7.155798 8.356415 -2.651893 -6.945812 8.007493 -2.667161 -7.040428 8.363743 -3.624586 -6.83092 8.374051 -3.602872 -6.738961 8.016221 -4.464048 -6.578641 8.383936 -4.435673 -6.48995 8.024553 -4.916317 -6.410162 8.389672 -4.884037 -6.323693 8.029365 -5.65603 -6.076298 8.399748 -5.617098 -5.994254 8.037804 -6.345085 -5.687454 8.410098 -6.671692 -5.471166 8.415398 -6.93228 -5.170747 8.055288 -6.299645 -5.610662 8.046438 -6.983984 -5.241389 8.420743 -7.545015 -4.760835 8.431118 -7.487793 -4.696833 8.063897 -8.036555 -4.246749 8.441288 -7.974494 -4.189916 8.072319 -8.468626 -3.689843 8.451452 -8.402338 -3.640894 8.080716 -8.521315 -3.612688 8.452795 -8.45452 -3.564836 8.081827 -8.871421 -3.028041 8.462388 -9.043931 -2.677724 8.4677 -9.086302 -2.379022 8.097375 -8.801453 -2.988243 8.089764 -9.158576 -2.41066 8.471556 -9.380566 -1.763045 8.480285 -9.306784 -1.739777 8.104641 -9.42033 -1.616441 8.48215 -9.34632 -1.595058 8.106193 -9.552957 -0.9597634 8.489964 -9.594346 -0.6107967 8.493734 -9.54094 -0.2873402 8.11859 -9.478426 -0.9467466 8.112719 -9.615229 -0.2922498 8.496942 -9.534005 0.380753 8.123732 -9.533883 0.3829909 8.123792 -9.47722 0.3798904 8.007239 -0.192229 -7.007092 7.694631 -0.8940315 -6.953503 7.699233 -1.708463 -6.866423 7.704688 -2.614082 -6.729485 7.711054 -3.549489 -6.526274 7.718084 -4.365832 -6.282448 7.724727 -4.804351 -6.12 7.728537 -5.520238 -5.798586 7.735176 -6.185405 -5.425116 7.741915 -6.800652 -4.997701 7.748772 -7.340122 -4.537924 7.755407 -7.812015 -4.046944 7.761865 -8.226099 -3.516191 7.768268 -8.276555 -3.442733 7.769112 -8.612162 -2.885646 7.775167 -8.887817 -2.296904 7.780996 -9.101153 -1.679408 7.786575 -9.139395 -1.539688 7.787768 -9.267207 -0.9139755 7.792798 -9.327846 -0.2770744 7.797371 -0.025379 -6.698779 7.501258 -0.1818868 -6.695679 7.50207 -0.8636388 -6.643054 7.505821 -1.670404 -6.556369 7.510369 -2.558979 -6.421486 7.5156 -3.471896 -6.222581 7.521308 -4.264346 -5.985319 7.526627 -4.688507 -5.827833 7.529646 -5.379212 -5.517095 7.534863 -6.018709 -5.157359 7.540099 -6.608065 -4.747186 7.545365 -7.123431 -4.307168 7.55042 -7.572859 -3.838723 7.555298 -7.965839 -3.334085 7.560091 -8.013631 -3.264367 7.56072 -8.331617 -2.73546 7.565248 -8.59273 -2.176559 7.569625 -8.794532 -1.590999 7.573825 -8.830655 -1.458651 7.574724 -8.951199 -0.8664002 7.578522 -9.008281 -0.2630099 7.582022 -7.148424 4.02468 7.651365 -7.258795 4.367528 8.015908 -7.080578 4.551367 8.510958 -7.297481 4.491278 8.511695 -7.611764 4.219337 8.016863 -7.670834 4.334519 8.512706 -7.954683 4.000058 8.017433 -8.033303 4.102739 8.513306 -8.229042 3.935708 8.513429 -8.28306 3.696497 8.017524 -8.378714 3.783495 8.513406 -8.547963 3.360128 8.017163 -8.655106 3.432614 8.513029 -8.722119 3.330981 8.512856 -8.772282 2.985469 8.016423 -8.887408 3.044682 8.512263 -8.989757 2.507732 8.015155 -9.110681 2.554319 8.510961 -9.024254 2.418957 8.014891 -9.246603 1.74213 8.012691 -7.445701 3.899901 7.65217 -7.735216 3.714776 7.65265 -8.017045 3.454058 7.652729 -8.250558 3.157339 7.652408 -8.453078 2.81894 7.651739 -8.654707 2.375701 7.650563 -8.687261 2.291925 7.650315 -8.899213 1.646755 7.648217 -9.043656 1.003751 7.645812 -9.399192 1.062641 8.010149 -6.287097 5 8.012142 -6.287097 4.877247 8.012142 -6.287097 4.957409 8.265275 -6.287097 4.977352 8.4081 -6.287097 4.98106 8.51069 -6.287097 4.981026 8.515722 -6.287097 4.980999 8.519338 -6.287097 4.936964 15.73608 -6.287098 5 24.16808 -6.287098 4.830243 22.9522 -6.287098 4.801285 24.16808 -0.1872687 4.938236 30.45239 0 4.939046 30.45518 0 5 30.45518 -6.129469 5 25.56709 -6.247567 5 24.87201 -6.257475 4.795038 24.77768 -6.279591 4.796274 24.47523 6.129468 5 25.56709 6.15851 4.801402 25.43313 6.247567 5 24.87201 6.257475 4.795038 24.77768 6.287098 5 24.16808 6.279591 4.796274 24.47523 6.287098 4.801285 24.16808 5.934288 5 26.24457 5.66448 5 26.89595 5.664481 4.824823 26.89594 5.808732 4.821984 26.57354 5.991114 4.815363 26.07443 6.129468 4.804257 25.56709 4.915452 5 28.08802 5.023782 4.830565 27.94819 5.323438 5 27.51301 5.325065 4.828385 27.51043 5.586575 4.825906 27.05213 1.399011 5 30.29755 1.560214 4.912767 30.25851 2.076497 5 30.10236 2.069614 4.89797 30.10477 2.72787 5 29.83256 2.799507 4.875131 29.7975 3.344938 5 29.49151 3.488571 4.854992 29.39851 3.919942 5 29.08353 3.918426 4.845142 29.08474 4.44565 5 28.61373 4.505574 4.835451 28.55298 4.915451 4.831399 28.08802 0.1872687 4.938236 30.45239 0.3768224 4.936629 30.44387 0.7039317 5 30.41564 0.9729845 4.927027 30.37943 1.399019 4.91704 30.29754 -0.3768224 4.936629 30.44387 -0.7039317 5 30.41564 -0.9729845 4.927027 30.37943 -1.399011 5 30.29754 -1.399019 4.91704 30.29754 -5.664481 5 26.89595 -5.586575 4.825906 27.05213 -5.323439 5 27.51301 -5.325065 4.828385 27.51043 -4.915452 5 28.08802 -5.023782 4.830565 27.94819 -4.915451 4.831399 28.08802 -4.44565 5 28.61373 -4.505574 4.835451 28.55298 -3.919942 5 29.08353 -3.918426 4.845142 29.08474 -3.344938 5 29.49151 -3.488571 4.854992 29.39851 -2.72787 5 29.83256 -2.799507 4.875131 29.7975 -2.076497 5 30.10236 -2.069614 4.89797 30.10477 -1.560214 4.912767 30.25851 -6.15851 4.801402 25.43313 -6.129468 4.804257 25.56709 -5.934288 5 26.24457 -5.991114 4.815363 26.07443 -5.808732 4.821984 26.57354 -5.664481 4.824823 26.89594 -5.792825 3.959592 7.512167 -5.796983 3.962312 7.512238 -5.812585 3.97658 7.51279 -5.789461 4.896141 7.512146 -5.789461 3.962678 7.512146 -5.79039 3.960148 7.512145 -6.046786 4.914702 7.584868 -5.930305 4.904067 7.533087 -5.913114 4.118309 7.528281 -5.890488 4.901372 7.522947 -5.826548 3.994339 7.513699 -5.803693 4.89686 7.512415 -6.036521 4.307681 7.578796 -6.077197 4.373933 7.604903 -6.07994 4.918709 7.606871 -6.172883 4.934013 7.69407 -6.173159 4.543784 7.694404 -6.196732 4.590354 7.725436 -6.1974 4.939797 7.726393 -6.255605 4.962582 7.837499 -6.287064 4.998859 8.006452 -6.255414 4.726725 7.836986 -6.271763 4.778231 7.889263 -6.281268 4.984545 7.936019 -6.286704 4.996021 7.992332 -5.784363 3.962486 7.512121 -5.763058 4.895692 7.512021 -4.813383 4.898519 7.507531 -1.014686 4.910339 7.48957 0 4.913667 7.484773 -4.992423 5.908701 27.89637 -4.991626 5.871617 27.86462 -4.974183 5.83864 27.91142 -4.98559 5.946793 27.92615 -4.976886 5.880029 27.93807 -4.909527 5.760324 28.06067 -4.918692 5.813274 28.08073 -4.866984 5.726953 28.14676 -4.880874 5.786657 28.16505 -4.73025 5.670089 28.38358 -4.762895 5.747697 28.39764 -4.971888 5.922567 27.96247 -4.917718 5.868232 28.09713 -4.882382 5.849207 28.17838 -4.774966 5.832143 28.40075 -4.995645 5.973868 27.89882 -5.007272 5.914668 27.81457 -4.999238 5.889869 27.84209 -4.990974 5.959435 27.91159 -5.008536 6.030302 27.86291 -5.020695 5.97563 27.76283 -5.01447 5.944834 27.78815 -5.002418 6.001591 27.88008 -6.138139 5.651678 7.918077 -6.138139 5.651678 24.16808 -6.006244 5.873888 7.918077 -6.028762 5.84159 24.16808 -5.72713 6.168904 7.918077 -5.727133 6.168904 24.16808 -6.195986 5.51481 7.918077 -6.281857 5.125258 7.918077 -6.287094 5.00286 8.01005 -6.221062 5.440174 24.16808 -5.018336 5.7771 27.70427 -4.970671 5.663197 27.84409 -4.87686 5.580954 28.03174 -4.789171 5.536065 28.17637 -4.698447 5.509659 28.30766 -5.117068 5.612002 27.59138 -5.044762 5.503681 27.7723 -4.936127 5.405794 27.97098 -4.835371 5.344034 28.12353 -4.729101 5.3 28.26479 -4.658137 5.662513 28.49041 -4.545905 5.677735 28.63807 -4.61424 5.767746 28.64255 -4.746765 5.835645 28.45407 -4.730608 5.745818 28.4548 -4.691493 5.664305 28.4423 -4.651255 5.872669 28.62223 -4.500234 5.963159 28.85652 -4.549707 5.934374 28.78345 -4.505628 5.818893 28.80278 -4.425708 5.723496 28.78995 -4.300149 5.772917 28.9352 -4.363797 5.834999 28.95434 -4.441109 5.996667 28.93974 -4.412269 5.91194 28.9559 -4.390247 5.872029 28.95737 -5.059897 5.887024 27.48116 -4.952718 6.226445 27.02202 -4.951021 6.228391 27.01685 -4.994723 6.192138 26.94162 -5.050215 6.168904 26.86907 -5.124124 6.047218 27.01326 -4.992485 6.167548 27.18704 -5.045984 6.097987 27.09732 -5.067421 6.000865 27.26906 -5.016583 6.103774 27.37352 -5.025702 6.027051 27.60337 -5.160067 5.91967 27.17467 -5.165787 5.839604 27.27883 -5.160624 5.766225 27.37642 -5.284139 6.468039 25.03738 -5.218375 6.456716 25.43195 -5.218375 6.456716 23.91808 -5.05139 6.541545 22.54221 -5.097452 6.574097 22.4841 -5.133789 6.500474 22.93178 -5.197439 6.500627 23.08299 -5.205646 6.46341 23.53296 -5.243577 6.466669 23.70731 -5.246304 6.464662 23.8451 -5.410057 6.423894 24.16808 -5.407973 6.425547 24.18647 -5.332471 6.462451 23.84427 -5.395863 6.434315 24.28377 -5.333819 6.46192 24.72463 -4.87943 6.624922 21.98112 -4.937346 6.666453 21.97128 -4.891986 6.619048 22.01548 -4.959401 6.675277 21.96681 -5.011913 6.560826 22.39293 -5.038535 6.547834 22.49175 -5.037958 6.548116 22.48952 -5.096965 6.574455 22.48186 -5.037297 6.548439 22.48699 -5.096407 6.574864 22.4793 -5.034642 6.549736 22.47684 -5.094165 6.576509 22.46906 -5.029277 6.552357 22.45656 -5.08963 6.579838 22.4486 -5.050821 6.608306 22.28592 -5.141173 6.612525 22.26533 -5.179224 6.582691 22.43041 -5.183668 6.579206 22.45116 -5.185865 6.577483 22.46155 -5.186411 6.577055 22.46414 -5.18682 6.576734 22.46609 -5.284737 6.499919 23.0732 -5.32981 6.46454 23.7049 -5.005314 6.684736 21.95535 -5.051389 6.682887 21.94112 -5.073645 6.67773 21.93323 -5.409703 6.424179 23.84325 -5.407097 6.426275 23.70193 -5.362941 6.461785 23.06107 -5.266832 6.539076 22.44376 -5.26643 6.539399 22.44178 -5.265893 6.539831 22.43913 -5.263734 6.541567 22.42855 -5.259365 6.545081 22.40741 -5.221935 6.575182 22.2391 -5.133444 6.646347 21.90779 -3.963062 7.129587 20.49226 -3.887726 7.153933 20.43121 -3.766314 7.21816 20.33457 -3.599416 7.244338 20.23497 -3.450451 7.335811 20.14531 -3.323098 7.327039 20.09593 -3.351216 7.366833 20.09965 -3.342544 7.369414 20.09594 -3.228133 7.354598 20.0581 -3.017654 7.451351 19.98716 -2.853323 7.4591 19.95425 -2.66437 7.509163 19.92788 -4.934142 6.242021 27.80449 -4.843862 6.30606 27.76283 -4.951467 6.227883 27.76283 -5.015342 6.108527 27.76283 -5.002268 6.108575 27.84882 -4.992032 6.145081 27.83967 -4.946193 6.227998 27.81088 -4.13812 5.9306 29.20962 -4.065021 5.867538 29.17661 -4.195645 6.014287 29.21947 -4.23094 6.10892 29.20503 -3.802237 6.184777 29.60647 -3.846077 6.292514 29.59767 -3.653888 6.031994 29.52269 -3.734774 6.093329 29.58016 -3.210222 6.200446 29.81149 -3.290305 6.257847 29.89386 -3.361443 6.35475 29.93905 -3.4106 6.473395 29.93878 -3.733566 6.341759 29.69486 -2.770497 6.675111 30.29822 -2.770497 6.70443 30.29822 -3.230079 6.539001 30.05535 -3.256652 6.59307 30.039 -3.702619 6.474349 29.72041 -4.500092 6.220878 28.85673 -4.332848 6.27854 29.08185 -3.966841 6.396327 29.48523 -4.641327 6.17027 28.63873 -4.819599 6.103848 28.31235 -2.228766 7.561391 19.91988 -2.004119 7.575856 19.92238 -2.23278 7.654042 19.88791 -2.003404 7.664578 19.88799 -2.235116 7.720387 19.81569 -2.001919 7.727364 19.8165 -2.235211 7.744465 19.7206 -1.999998 7.75 19.7241 -2.452976 7.538211 19.91866 -2.461847 7.633697 19.88881 -2.468015 7.702718 19.81611 -2.469923 7.727868 19.71889 -2.571574 7.62079 19.89164 -2.558908 7.524743 19.92077 -2.590097 7.715056 19.72109 -2.582939 7.690142 19.81887 -2.709688 7.699378 19.72875 -2.697301 7.674967 19.82683 -2.689297 7.644997 19.86773 -2.676478 7.583093 19.91124 -2.680766 7.605565 19.89948 -3.06191 7.579657 19.92704 -3.038079 7.521998 19.96971 -4.004707 7.195247 20.48089 -4.057505 7.242713 20.44721 -3.80389 7.284252 20.32107 -4.113305 7.264657 20.39642 -3.850812 7.333641 20.28473 -4.163494 7.257692 20.33636 -3.900087 7.358967 20.23095 -3.481022 7.403327 20.12927 -3.379498 7.43496 20.08306 -3.51831 7.456044 20.0895 -3.413718 7.488775 20.04245 -3.556954 7.486383 20.03174 -3.448988 7.52059 19.98363 -3.085743 7.616092 19.86526 -3.94437 7.356454 20.16774 -3.591399 7.489983 19.96428 -3.480265 7.525857 19.91499 -3.106176 7.626102 19.79318 -4.812244 6.752068 21.63436 -4.755259 6.70621 21.6431 -4.879454 6.775164 21.61496 -4.947769 6.772363 21.58754 -4.546098 6.833891 21.2161 -4.59951 6.886562 21.20623 -4.493452 6.864168 21.12773 -4.545884 6.918352 21.11766 -4.246518 6.996518 20.78352 -4.294084 7.056837 20.77276 -4.664291 6.917237 21.182 -4.609863 6.950811 21.09237 -4.353477 7.096958 20.74311 -4.731171 6.921526 21.14689 -4.676134 6.956847 21.05552 -4.415764 7.110847 20.69902 -5.007922 6.744045 21.55582 -4.790578 6.898815 21.10591 -4.735111 6.935589 21.01243 -4.471574 7.096414 20.64712 -5.133444 6.646347 7.918077 -5.703278 6.139245 7.726735 -5.091464 6.594146 7.668076 -5.68515 6.116703 7.668076 -5.635354 6.054783 7.564523 -4.976771 6.45153 7.485063 -5.570458 5.974087 7.485063 -5.533697 5.928376 7.456136 -4.820099 6.256713 7.418076 -5.413786 5.77927 7.418076 -5.97531 5.851714 7.726735 -6.272061 5.159377 7.837675 -6.223413 5.199346 7.700305 -6.160238 5.501747 7.726735 -6.058435 5.464548 7.564523 -6.117644 5.224514 7.560376 -5.906076 5.408876 7.456136 -5.966848 5.231051 7.460769 -5.726357 5.343207 7.418076 -5.763036 5.218041 7.418076 -5.824494 5.22451 7.421862 -5.599861 5.582592 7.418076 -5.755377 5.694066 7.456136 -5.887217 5.788569 7.564523 -4.714831 5.291578 28.28378 -4.553734 5.238383 28.47525 -4.463797 5.478513 28.57256 -4.506256 5.235414 28.52559 -4.451463 5.238521 28.58084 -4.60905 5.466274 28.41008 -4.177926 5.291401 28.82791 -4.14475 5.3 28.85513 -4.153762 5.434158 28.83575 -4.348891 5.582283 28.72551 -4.304843 5.412102 28.70427 -4.207722 5.621818 28.85828 -4.901778 6.273209 27.00959 -4.908242 6.26839 26.94891 -4.91659 6.261751 26.95394 -4.872569 6.291904 26.96101 -4.887618 6.282867 26.94988 -4.899455 6.274876 26.94713 -4.928301 6.251574 26.9671 -4.843862 6.30606 27.00233 -4.956461 6.257153 26.81178 -4.961738 6.254828 26.80793 -4.989249 6.230724 26.82003 -4.928329 6.269497 26.83622 -4.905011 6.279666 26.86303 -4.890652 6.285899 26.88397 -4.845149 6.305509 26.99744 -5.405745 6.168904 26.05963 -5.159969 6.168904 26.65299 -4.695522 6.368468 26.99143 -4.791979 6.339597 26.8977 -4.86754 6.330957 26.78334 -4.984008 6.340222 26.5271 -5.106485 6.381645 26.10812 -5.583542 6.168904 25.44248 -5.691122 6.168904 24.80931 -4.877969 6.330672 23.91808 -4.695522 6.368468 23.91808 -5.061585 6.362297 23.91808 -4.957759 6.423642 22.76882 -5.035656 6.377615 23.34124 -4.850977 6.343278 23.36012 -4.89866 6.438693 22.57212 -4.582021 6.414687 22.85262 -4.538299 6.432141 22.66777 -4.770024 6.380768 22.80722 -4.718145 6.399547 22.61623 -4.667137 6.380151 23.38214 -4.824436 6.573434 21.99505 -4.464986 6.460973 22.41126 -4.377634 6.494621 22.15884 -4.648028 6.430969 22.34736 -4.607465 6.473451 22.06533 -4.830833 6.477311 22.29329 -4.748743 6.522975 22.01723 -2.388407 7.208168 20.0715 -2.409602 7.316506 19.98506 -2.788508 7.22555 20.02613 -4.487491 6.520178 21.78186 -4.100512 6.839219 20.79809 -4.388078 6.738565 21.15971 -4.448193 6.716724 21.24985 -4.697378 6.623119 21.69916 -3.50077 7.029959 20.30425 -3.776536 6.945355 20.49559 -3.146325 7.131334 20.13059 -2.664263 7.007985 20.44629 -2.361602 7.071157 20.41808 -2.367247 7.100012 20.24915 -4.265704 6.536627 21.89153 -4.047961 6.614819 21.48938 -4.252988 6.607609 21.35307 -3.995798 6.632867 21.4094 -4.196579 6.627883 21.26736 -3.748354 6.714941 21.09173 -3.927668 6.720589 20.92488 -3.473909 6.799235 20.83131 -3.6266 6.816839 20.64055 -3.243994 6.864506 20.67032 -3.371903 6.892242 20.46209 -2.953225 6.940204 20.52819 -3.046461 6.980799 20.30135 -2.719617 7.06117 20.20542 -2.374463 7.136898 20.16808 -1.067346 6.956593 30.80999 -1.535175 6.910027 30.7177 -1.698961 6.887456 30.67714 -1.850766 6.869008 30.63561 -2.00522 6.840055 30.5894 -2.161217 6.821017 30.53859 -2.305537 6.783685 30.48779 -4.806807 6.220933 28.28255 -4.751935 6.318816 28.23599 -4.631807 6.289507 28.60465 -4.328458 6.401429 29.04282 -3.967659 6.523406 29.44279 -3.706607 6.604331 29.67662 -3.264896 6.727666 29.9943 -2.781896 6.84356 30.25382 -4.579804 6.388249 28.54975 -4.281468 6.501592 28.97645 -3.926691 6.625139 29.36583 -3.670034 6.707118 29.59339 -3.235829 6.83208 29.90246 -2.761119 6.949518 30.15483 -4.663983 6.381444 28.18029 -4.494258 6.449526 28.48344 -4.200568 6.560503 28.89503 -3.852108 6.681236 29.2697 -3.600553 6.761208 29.48815 -3.175966 6.882897 29.78407 -2.713119 6.99704 30.02484 -2.116458 7.116543 30.25449 -1.887635 7.154293 20.41808 -1.889455 7.15401 30.32519 -1.503381 7.207778 30.42562 -1.086114 7.251953 20.41808 1.844924 7.160849 30.33803 1.887635 7.154293 20.41808 1.214745 7.239869 30.485 1.086114 7.251953 20.41808 -0.8752659 7.268819 30.53823 -0.7967574 7.274167 30.54803 -0.125611 7.299358 20.41564 -0.157146 7.298996 30.59338 0.7757468 7.275513 20.41747 0.4786156 7.290685 30.57822 1.110679 7.249751 30.50321 3.175966 6.882897 29.78407 3.243994 6.864506 20.67032 2.953225 6.940204 20.52819 2.457479 7.052004 30.13128 2.713119 6.99704 30.02484 2.361602 7.071157 20.41808 2.664263 7.007985 20.44629 4.695522 6.368468 26.99143 3.852108 6.681236 29.2697 4.200568 6.560503 28.89503 4.843862 6.30606 27.76283 4.843862 6.30606 27.00233 4.663983 6.381444 28.18029 4.494258 6.449526 28.48344 4.845149 6.305509 26.99744 4.890652 6.285899 26.88397 4.905011 6.279666 26.86303 4.928329 6.269497 26.83622 4.956461 6.257153 26.81178 4.961738 6.254828 26.80793 3.600553 6.761208 29.48815 4.695522 6.368468 23.91808 4.667137 6.380151 23.38214 4.582021 6.414687 22.85262 4.538299 6.432141 22.66777 4.464986 6.460973 22.41126 4.377634 6.494621 22.15884 4.265704 6.536627 21.89153 4.047961 6.614819 21.48938 3.995798 6.632867 21.4094 3.748354 6.714941 21.09173 3.473909 6.799235 20.83131 -1.090193 7.297962 20.20818 -1.101676 7.42749 20.03706 -1.117601 7.607143 19.93909 -1.561665 7.593631 19.93031 -1.560599 7.674231 19.89188 -1.116521 7.68139 19.89822 -1.558668 7.730064 19.82221 -1.114725 7.732041 19.83029 -1.556255 7.75 19.7352 -1.112536 7.75 19.74749 -1.999998 7.75 7.918077 -1.999998 7.683013 7.668076 -2.555669 7.651616 7.668076 -1.999998 7.5 7.485063 -2.535054 7.469769 7.485063 -1.999998 7.25 7.418076 -2.506893 7.22136 7.418076 -3.007336 7.135803 7.418076 -3.063299 7.379459 7.485063 -3.494956 6.99442 7.418076 -3.578009 7.230221 7.485063 -3.963546 6.79901 7.418076 -4.072633 7.023955 7.485063 -4.407143 6.552059 7.418076 -4.540873 6.763285 7.485063 -3.104267 7.557828 7.668076 -3.638808 7.40284 7.668076 -4.152489 7.188626 7.668076 -4.638771 6.917913 7.668076 -2.563215 7.718178 7.918077 -3.119262 7.623115 7.918077 -3.661062 7.466022 7.918077 -4.181718 7.248899 7.918077 -4.674604 6.97451 7.918077 -2.717429 5.203472 7.418076 4.407143 6.552059 7.418076 4.820099 6.256713 7.418076 2.717429 5.203472 7.418076 5.413786 5.77927 7.418076 2.506893 7.22136 7.418076 3.007336 7.135803 7.418076 3.494956 6.99442 7.418076 3.963546 6.79901 7.418076 5.599861 5.582592 7.418076 5.726357 5.343207 7.418076 5.763036 5.218041 7.418076 0 5.188602 7.418076 1.999998 7.25 7.418076 1.556255 7.75 19.7352 1.999998 7.75 19.7241 1.999998 7.75 7.918077 0.2876013 7.75 19.76081 1.112536 7.75 19.74749 1.999998 7.683013 7.668076 1.999998 7.5 7.485063 0.7873697 7.441165 20.04535 -0.1275709 7.455295 20.05283 -0.1262259 7.339993 20.21819 0.2888083 7.620478 19.94798 1.101676 7.42749 20.03706 1.117601 7.607143 19.93909 0.7791134 7.318784 20.21373 1.090193 7.297962 20.20818 0.2885329 7.688317 19.90527 1.116521 7.68139 19.89822 0.2881078 7.733934 19.83935 1.114725 7.732041 19.83029 -5.431727 5.84159 26.78386 -5.604983 5.440174 26.86729 -5.267523 5.440174 27.47788 -3.915669 5.339475 29.03709 -3.494436 5.428098 29.31938 -3.309804 5.440174 29.4356 -3.041558 5.534235 29.55783 -2.699217 5.440174 29.77306 -2.937527 5.559148 29.60414 0.6750072 5.84159 30.15893 0.1989673 5.898491 30.153 0 5.84159 30.19684 -0.477348 5.891308 30.14261 -0.6750072 5.84159 30.15893 -1.148237 5.849456 30.08101 0.9196203 5.867648 30.108 0.6965379 5.440174 30.35002 1.384316 5.440174 30.23316 1.530132 5.809837 30.02107 2.054686 5.440174 30.04003 2.11157 5.726746 29.89019 2.699217 5.440174 29.77306 2.662819 5.621558 29.71422 3.309804 5.440174 29.4356 3.041558 5.534235 29.55783 2.937527 5.559148 29.60414 4.14475 5.3 28.85513 3.915669 5.339475 29.03709 3.494436 5.428098 29.31938 4.553734 5.238383 28.47525 4.714831 5.291578 28.28378 4.729101 5.3 28.26479 4.835371 5.344034 28.12353 4.506256 5.235414 28.52559 4.451463 5.238521 28.58084 4.177926 5.291401 28.82791 4.936127 5.405794 27.97098 5.267523 5.440174 27.47788 5.044762 5.503681 27.7723 5.117068 5.612002 27.59138 5.160624 5.766225 27.37642 5.604983 5.440174 26.86729 5.165787 5.839604 27.27883 5.050215 6.168904 26.86907 5.124124 6.047218 27.01326 5.431727 5.84159 26.78386 5.160067 5.91967 27.17467 6.181945 5.440174 24.86461 6.221059 5.440173 24.16808 6.139881 5.648055 24.16808 5.159969 6.168904 26.65299 5.690448 5.84159 26.15925 5.405745 6.168904 26.05963 5.877608 5.84159 25.5096 5.583542 6.168904 25.44248 5.990854 5.84159 24.84308 5.691122 6.168904 24.80931 6.02876 5.841589 24.16808 5.727133 6.168904 24.16808 5.871956 5.440174 26.22276 6.065086 5.440174 25.55239 -2.386779 5.677522 29.8093 -2.054686 5.440174 30.04003 -1.801212 5.774574 29.96639 -1.384316 5.440174 30.23316 -0.6965379 5.440174 30.35002 0 5.440174 30.38914 -5.690448 5.84159 26.15925 -5.877608 5.84159 25.5096 -5.990854 5.84159 24.84308 -5.871956 5.440174 26.22276 -6.065086 5.440174 25.55239 -6.181945 5.440174 24.86461 -4.031828 5.752746 29.06421 -3.123466 6.10525 29.66678 -3.074224 5.723623 29.50528 -2.971917 5.753276 29.54834 -3.51853 5.595526 29.28075 -3.138162 5.911215 29.52569 -3.037571 5.946104 29.57046 -3.223221 6.067225 29.61581 -3.648747 5.901646 29.35905 -3.572118 5.759977 29.29452 -3.97007 5.625985 29.02033 -3.930191 5.484102 29.01102 -2.650929 6.422959 30.18733 -2.667204 6.441543 30.21202 -3.113096 6.317206 29.9974 -3.182049 6.416237 30.05068 -3.03655 6.261056 29.90582 -2.602661 6.388484 30.10155 -2.698715 6.487912 30.25348 -2.740245 6.575491 30.292 -2.72743 6.544394 30.28259 -1.999726 6.522535 30.30448 -1.585772 6.590627 30.40904 -1.617354 6.616538 30.51558 -2.278869 6.678645 30.47646 -2.158651 6.49137 30.25705 -2.200239 6.522167 30.35294 -2.242155 6.587463 30.42944 -1.678362 6.776526 30.66008 -1.649781 6.681645 30.6035 -1.054073 6.841262 30.78861 -1.035485 6.743789 30.72467 -1.01446 6.679264 30.62808 -0.9942539 6.657678 30.5138 -2.155342 7.071712 30.39219 2.761119 6.949518 30.15483 2.781896 6.84356 30.25382 2.501712 7.005689 30.26479 1.893514 7.009062 30.58353 2.50945 6.758053 30.40963 2.520567 6.899045 30.36577 2.770497 6.70443 30.29822 1.140565 7.099065 30.75781 1.240435 6.941336 30.77986 1.247353 7.089055 30.73859 1.564864 6.9065 30.71067 1.883941 6.864243 30.62602 0.4887376 6.990912 30.87743 1.067346 6.956593 30.80999 1.134168 6.950976 30.79891 0.4916243 7.140554 30.83706 -0.1614261 7.148982 30.85308 -0.1604695 6.99902 30.8933 -0.8183251 7.123809 30.80516 -0.8136076 6.974797 30.84583 -0.8989278 7.118388 30.7948 -0.8937764 6.969579 30.83557 1.879305 7.11708 30.47864 1.23797 7.198085 30.6309 1.131983 7.208223 30.64977 0.4879207 7.250241 30.72758 -0.1602097 7.258777 30.74331 -0.8121635 7.233282 30.69626 -0.8921602 7.227791 30.6861 -1.531825 7.165173 30.56935 -1.543424 7.056556 30.6759 -2.171617 6.964256 30.49549 -0.910332 6.664531 30.52703 -0.5321171 6.687894 30.54349 0.9942539 6.657678 30.5138 0.3882457 6.693556 30.58286 0.2217468 6.697898 30.55315 -0.2163105 6.698 30.59138 -0.8192005 6.671286 30.54005 -0.9650861 6.848377 30.80222 -0.9480668 6.750928 30.73811 -0.928825 6.686321 30.6414 -0.8358356 6.693275 30.65451 -0.8531437 6.757963 30.75133 -0.8684593 6.855389 30.81563 -0.2206961 6.720778 30.70616 0.3961193 6.716203 30.69759 -0.2252586 6.785785 30.80345 0.4043106 6.781158 30.7948 -0.2293028 6.883119 30.86843 0.4115693 6.878507 30.85967 1.054073 6.841262 30.78861 1.035485 6.743789 30.72467 1.01446 6.679264 30.62808 -2.413691 5.875069 29.74304 -2.609799 6.360072 30.02266 -1.966589 6.487178 30.17026 2.307195 6.424519 30.09918 1.585772 6.590627 30.40904 1.669628 6.533407 30.22057 1.002416 6.609266 30.29913 0.2167535 6.649782 30.339 3.210222 6.200446 29.81149 3.03655 6.261056 29.90582 2.913852 6.286836 29.9315 2.602661 6.388484 30.10155 2.158651 6.49137 30.25705 3.038343 5.947892 29.57106 3.124821 6.10721 29.66869 2.830898 6.182189 29.77196 -0.5200916 6.640343 30.32984 -1.252036 6.585384 30.27494 -2.535998 6.249388 29.86005 -1.911839 6.365863 30.00276 -1.217745 6.455712 30.10408 -0.5060068 6.505934 30.15726 0.2108958 6.514555 30.16614 0.9750904 6.477541 30.12751 1.623477 6.408174 30.05144 2.242421 6.30847 29.93402 -2.466541 6.07761 29.76101 -1.860091 6.183565 29.90347 -1.185163 6.265057 30.00522 -0.4925696 6.3105 30.05891 0.2053033 6.318292 30.06789 0.9490832 6.284819 30.02884 1.57976 6.22197 29.95228 2.181347 6.131396 29.83475 2.752944 6.016348 29.67345 2.972171 5.75426 29.54826 -1.820819 5.973659 29.89056 -1.160438 6.049405 29.99701 -0.4823629 6.091601 30.05369 0.201054 6.098832 30.06321 0.9293414 6.06776 30.0219 1.546592 6.009367 29.94149 2.134949 5.925128 29.81921 2.693486 5.818025 29.65303 -5.763756 5.056866 7.46505 -5.763415 5.133247 7.430309 -4.814067 5.056114 7.462805 -2.717827 5.125623 7.428353 -1.015315 5.052363 7.453825 0 5.088577 7.435242 0 5.051134 7.451425 -5.783743 5.056916 7.46533 -5.801065 5.056788 7.466086 -5.813813 5.136679 7.431576 -6.259808 5.031394 7.825396 -6.278039 5.076819 7.86961 -6.261628 5.097235 7.794115 -6.204532 5.120485 7.668322 -6.183345 5.044708 7.673231 -6.206845 5.042149 7.708177 -5.893575 5.055797 7.479786 -5.935694 5.055137 7.492013 -5.947629 5.136626 7.46133 -6.057066 5.052051 7.552012 -6.09498 5.134186 7.54465 -6.090927 5.050702 7.57689 -6.165468 5.046265 7.650284 -6.287069 5.000965 8.00619 -6.286758 5.003362 7.991406 -6.282074 5.013043 7.932194 -1.014966 4.983566 7.480497 0 5.012969 7.467862 -4.813683 4.980429 7.496133 -5.763363 4.979632 7.500039 -5.786425 4.979859 7.500197 -5.801918 4.980094 7.500564 -5.889748 4.9815 7.511634 -5.930009 4.982315 7.522139 -6.047546 4.985373 7.575414 -6.080899 4.986464 7.59796 -6.173982 4.990371 7.686945 -6.198383 4.991766 7.719799 -6.255789 4.997225 7.832127 -6.310624 4.861254 8.417276 -6.310987 4.842391 8.288395 -6.378855 4.745692 8.307834 -6.310567 4.864738 8.509916 -6.377517 4.763366 8.425012 -6.377305 4.766617 8.509262 -6.384155 4.674941 8.100951 -6.312431 4.766764 8.060643 -6.306075 4.680785 7.936858 -6.37726 4.597348 7.967011 -6.361512 4.55814 7.90794 -6.296203 4.454292 7.777201 -6.268337 4.418489 7.739729 -6.15097 4.286097 7.629313 -6.100208 4.233769 7.596542 -5.944963 4.082659 7.532607 -5.835903 3.983075 7.51408 -5.818241 3.96892 7.512928 -5.798172 3.957998 7.512228 -6.292836 4.636654 7.882101 -6.237412 4.51918 7.76046 -6.213486 4.478664 7.725483 -6.111386 4.329151 7.622153 -6.066721 4.270209 7.591418 -5.928846 4.100427 7.531384 -5.83122 3.988705 7.513979 -5.815411 3.972749 7.512896 -5.797578 3.960155 7.512241 -0.1872261 4.82311 30.47537 0 4.839744 30.47209 -0.1885583 4.725614 30.54075 0 4.751638 30.52091 -0.3800348 4.724069 30.53215 -0.3770718 4.821543 30.46685 -5.102253 4.60793 28.00842 -4.574022 4.614275 28.62219 -4.523073 4.714631 28.57143 -6.184695 4.676602 25.44084 -6.285726 4.667626 24.7807 -6.365177 4.56433 24.78866 -6.259419 4.574432 25.4581 -6.016143 4.691249 26.08443 -5.832915 4.698403 26.58476 -6.087924 4.589381 26.10895 -5.902027 4.596768 26.61438 -5.67566 4.601512 27.0995 -5.409249 4.604838 27.56429 -5.60971 4.702891 27.06483 -5.346937 4.705952 27.52471 -5.044119 4.708754 27.96414 -3.975404 4.625619 29.16151 -3.537269 4.636499 29.47959 -2.835409 4.658784 29.88267 -2.093728 4.683657 30.19184 -3.932556 4.725435 29.10535 -3.500209 4.735975 29.42036 -2.807392 4.757541 29.82041 -2.074318 4.781724 30.12797 -1.563145 4.797193 30.28168 -0.982531 4.714386 30.46743 -1.577123 4.699472 30.34616 -0.9743015 4.811884 30.40249 -6.389782 4.563943 24.47847 -6.308566 4.667701 24.47546 -6.316524 4.671744 24.16521 -6.399025 4.567614 24.1629 -6.316075 4.701645 22.94918 -6.397409 4.597889 22.94674 -6.377306 4.766551 8.518947 -6.381239 4.71875 15.73385 -6.310568 4.864675 8.519126 -6.311636 4.818137 15.73487 -6.310567 4.864703 8.514945 -6.377307 4.766582 8.51429 0.1994276 4.546315 31.0238 0.1910614 4.660678 30.63852 0.4077195 4.544668 31.01401 0.3852578 4.659123 30.62976 0.02423286 -6.338644 7.435279 5.697324 3.991578 7.51171 6.200851 3.754677 7.512952 0.1691622 -6.335631 7.435978 4.552856 -5.488432 7.460766 4.145488 -5.640344 7.45811 3.380938 -5.870325 7.453392 2.494235 -6.064588 7.448269 1.625497 -6.197403 7.443524 0.8276574 -6.283894 7.439339 8.01532 2.589718 7.515932 8.195309 2.193601 7.51488 5.823405 -4.845697 7.469858 5.214056 -5.189775 7.465325 7.659863 -3.121376 7.486819 7.704483 -3.056009 7.487344 7.842585 2.878582 7.516503 8.22521 2.116654 7.514651 8.422959 1.514728 7.512695 8.556266 0.9215645 7.510475 8.623839 0.3294724 7.507951 8.624077 0.3256195 7.507933 8.630726 -0.2472804 7.505213 8.432944 -1.487819 7.49832 8.245077 -2.035943 7.494799 8.001416 -2.559956 7.49113 8.578139 -0.8112064 7.502256 8.466485 -1.364124 7.499072 7.291973 -3.595682 7.482802 6.869163 -4.038049 7.47868 6.382268 -4.455299 7.474374 6.739554 3.615183 7.514828 6.995942 3.554601 7.515748 7.217143 3.461803 7.516348 7.433705 3.323333 7.516706 7.651945 3.121139 7.516767 6.477283 4.699042 8.430096 6.476868 4.70205 8.508831 6.532425 4.681048 8.508993 6.81688 4.103363 7.650176 6.812523 4.075673 7.634392 6.329173 4.110642 7.590629 6.754728 3.7105 7.520076 6.367914 4.401417 7.774181 6.437247 4.41169 7.807196 6.333549 4.367826 7.736061 6.194423 4.246432 7.626105 5.789486 3.956521 7.512091 5.786397 3.957751 7.512077 5.779757 3.962127 7.512076 5.77704 3.964515 7.512087 5.792663 3.955805 7.512117 5.798767 3.955842 7.512198 5.821072 3.965092 7.512883 5.840595 3.977452 7.514004 5.961359 4.06512 7.531941 6.136058 4.199361 7.594026 6.773653 3.829679 7.540168 6.50862 4.61199 8.129681 6.8801 4.510851 8.119771 6.872302 4.45945 8.014522 6.859588 4.376798 7.890617 6.852962 4.334054 7.839582 6.821488 4.132681 7.668234 6.890849 4.587999 8.519728 6.890853 4.586133 8.443367 6.883635 4.534511 8.182246 6.45263 4.501259 7.911191 6.475083 4.539914 7.975389 6.490156 4.617287 8.126259 6.47989 4.682714 8.320495 0.9608784 4.537595 30.95536 0.996412 4.649472 30.56431 1.513299 4.52875 30.8451 1.624246 4.526882 30.81653 1.599989 4.6347 30.44199 2.183125 4.517264 30.63883 2.12481 4.619101 30.28639 2.725655 4.508023 30.40979 2.87907 4.594678 29.97431 3.253636 4.499728 30.12851 3.773055 4.49278 29.78938 3.593666 4.5729 29.5665 3.965154 4.490604 29.64681 4.039853 4.562277 29.2439 4.435687 4.486954 29.25025 4.859444 4.486639 28.82021 4.649793 4.551382 28.69667 5.241287 4.488285 28.35715 5.188168 4.545464 28.0734 5.504621 4.49035 27.98035 5.80465 4.493168 27.46871 5.501148 4.542653 27.62225 6.035607 4.495077 26.98235 5.772828 4.539599 27.15004 6.23874 4.495465 26.43492 6.003794 4.53513 26.65713 6.295811 4.495054 26.24455 6.193591 4.528015 26.14358 6.407636 4.491379 25.78687 6.369133 4.51342 25.48177 6.498351 4.485724 25.31396 6.431876 4.508247 25.14949 6.503545 4.485597 25.28116 6.515617 4.486702 25.15674 6.537915 4.490764 24.80217 6.480821 4.504714 24.80005 6.507563 4.505027 24.48369 6.560411 4.498241 24.23535 6.51842 4.509323 24.16161 6.567428 4.502006 24.00927 6.515387 4.53902 22.94535 6.785133 4.557948 17.33661 6.500632 4.586265 20.66652 6.70733 4.535815 20.6697 6.507496 4.559619 22.06871 6.66163 4.523605 22.07334 6.608373 4.51401 23.15483 6.476877 4.70198 8.51883 6.866467 4.581164 11.84543 6.484518 4.655061 15.7332 6.488827 4.635888 17.3324 6.476873 4.702015 8.513859 9.112306 0.5702427 22.7974 9.100876 -0.1861228 22.64658 9.304669 0.01574921 19.08301 9.038627 -0.9583041 22.32346 8.939009 -1.627365 21.91078 9.19491 -1.214329 18.52797 8.22527 -4.104622 11.92535 8.702548 -3.339204 12.34055 8.56923 -3.576602 13.69902 1.929803 -7.381883 10.49484 1.726791 -7.439855 10.70616 1.079268 -7.368261 9.45376 6.527475 -6.347683 17.28944 6.651321 -6.190032 16.77983 6.980754 -5.898362 17.35288 9.015275 -0.6433091 23.38624 8.975459 -1.038495 23.19485 7.758169 1.675135 28.35441 7.693757 2.063664 28.30056 7.165268 2.073343 29.10506 8.197319 1.665972 27.49255 8.242352 1.248183 27.51428 8.583829 1.250017 26.60383 7.872759 2.499937 27.66794 7.599072 2.500012 28.19786 9.591907 0.4324343 10.14367 9.602169 0.4623083 8.513236 9.558512 0.8807568 8.51504 9.451779 1.461397 8.517326 9.306818 1.996351 8.519208 9.278673 2.003922 11.95594 9.131299 2.500642 8.515961 9.085397 2.499788 12.609 9.52522 0.837639 11.97376 9.562447 0.3750269 11.93872 9.605139 0.01349538 10.09227 9.607918 0.3845321 8.51371 9.611204 -0.3767178 8.525202 9.500641 -1.264764 8.52502 9.594248 -0.6118859 8.525337 9.591644 -0.4273777 10.02411 9.266428 -2.125338 8.522672 9.405961 -1.67226 8.52419 9.473944 -1.322612 9.882324 7.043547 -5.199028 8.498964 7.227371 -5.048713 8.500577 7.19828 -5.089711 9.0361 7.845768 -4.462212 8.506494 7.856139 -4.468043 9.219854 8.519438 -3.618191 8.513792 8.420752 -3.771666 9.398651 8.91559 -2.945402 8.518482 8.883622 -3.007945 9.569665 9.043797 -2.679994 8.52003 6.671559 -5.475899 8.495901 6.454244 -5.634036 8.85259 5.663363 -6.078186 8.4888 5.623918 -6.104545 8.669816 5.637038 -6.091498 8.488632 5.541988 -6.184171 9.447391 4.649769 -6.552901 9.137316 4.763256 -6.476435 8.483412 3.747188 -6.805824 8.477575 4.550251 -6.555076 8.482218 4.720898 -6.492514 8.483174 2.584971 -7.115419 9.171056 2.721509 -7.038443 8.469098 2.906119 -7.002798 8.470974 3.510562 -6.962676 9.761919 1.938586 -7.163971 8.458686 1.629291 -7.210931 8.540122 1.167431 -7.253106 8.439887 1.491523 -7.492717 10.88732 1.227964 -7.539582 11.0377 0.6269387 -7.306148 8.434605 0.3919047 -7.324201 8.432576 0.939854 -7.578835 11.15618 0.3512001 -7.326706 8.432293 0.1953149 -7.334146 8.431363 0.6310725 -7.608762 11.24153 0.5539324 -8.008416 14.55904 0.4320698 -8.229516 20.07677 0.465334 -8.153451 21.08721 0.4980552 -8.011978 22.10039 0.5300741 -7.803684 23.11129 0.7741558 -2.654766 31.51922 0.7957666 -1.541163 32.23429 0.8094603 -0.3194938 32.68709 0.808685 1.200192 32.87021 0.7311891 2.499666 32.72273 0.7613016 1.997612 32.81473 1.694456 2.029254 32.66672 1.466927 2.499632 32.62126 2.22539 2.499642 32.44044 2.605854 2.058395 32.415 2.561779 2.499658 32.33521 3.487191 2.080714 32.06733 4.330642 2.094058 31.63078 4.120578 2.499784 31.63611 3.736857 2.499747 31.84196 3.434759 2.49972 31.98802 2.984644 2.499684 32.18062 5.128488 2.098178 31.11145 4.900331 2.499859 31.14238 4.473602 2.499819 31.42564 5.872738 2.09433 30.51451 5.629053 2.500123 30.57616 5.184771 2.499884 30.93465 6.554801 2.084937 29.84438 6.298325 2.500403 29.94271 5.857278 2.500548 30.37382 6.899736 2.500216 29.2468 6.471069 2.500348 29.75714 7.48385 2.500045 28.39583 7.424633 2.500062 28.49293 7.01519 2.500182 29.09504 8.177846 2.499859 26.92162 8.022308 2.499897 27.3298 8.128836 2.060617 27.43542 8.563692 2.499773 25.36604 8.398365 2.499806 26.17233 8.457985 2.069258 26.5155 8.336589 2.49982 26.40915 8.668115 2.499759 24.46892 8.915924 2.057432 22.7683 8.816123 2.499827 21.68003 9.082827 2.036301 19.16194 8.96303 1.269174 24.65871 8.997868 0.5241138 24.62324 8.217942 -0.528799 27.26525 8.24714 -0.03865969 27.39622 7.806554 -0.08787792 28.24632 8.904538 -1.129418 24.08723 8.947793 -0.716773 24.28992 8.978425 -0.2906367 24.45059 8.744467 -1.264699 25.04231 8.79399 -0.8261894 25.25789 8.829566 -0.3735286 25.42867 8.850131 0.07127863 25.54513 8.869259 -1.729539 22.7572 8.790682 -1.844844 23.62391 8.618019 -2.013392 24.55021 8.337108 -2.17401 25.44193 8.111726 -1.511887 26.83143 8.172715 -1.028253 27.07374 7.726491 -1.116565 27.90503 1.783451 1.23493 32.72644 2.724158 1.270791 32.47897 3.623636 1.30063 32.13413 4.475354 1.320186 31.69873 5.273341 1.327513 31.17939 6.011803 1.32263 30.58205 6.684694 1.307391 29.91198 7.285467 1.2856 29.174 7.807102 1.263193 28.373 0.8222302 0.73775 32.85518 1.809149 0.7431504 32.71256 2.758146 0.7487091 32.46712 3.662741 0.7547896 32.12465 4.516781 0.7617302 31.69107 5.314404 0.7698538 31.17233 6.049957 0.7794712 30.57434 6.717905 0.7908788 29.90293 7.312742 0.8043482 29.16387 7.828924 0.8201069 28.36293 8.260543 0.4160197 27.47147 7.823579 0.380956 28.3261 7.302365 0.348421 29.12405 6.703045 0.319429 29.8597 6.03162 0.2946728 30.52761 5.293937 0.2745384 31.12234 4.495742 0.259119 31.63835 3.642781 0.2482167 32.06995 2.740939 0.2413267 32.41124 1.796374 0.2376083 32.6562 0.8156329 0.2358542 32.79879 1.784019 -0.3131555 32.54583 2.723809 -0.3019768 32.3031 3.622251 -0.285897 31.96476 4.473113 -0.2649113 31.53667 5.270414 -0.2390469 31.02459 6.008301 -0.208347 30.4341 6.680936 -0.172865 29.77066 7.282386 -0.1326725 29.03962 7.774506 -0.5971118 28.10743 7.248731 -0.6591417 28.89292 6.646928 -0.714888 29.61644 5.975166 -0.7643612 30.27282 5.239323 -0.8075418 30.85682 4.445173 -0.8443574 31.36314 3.598497 -0.8746756 31.78631 2.705193 -0.898311 32.12068 1.771396 -0.9150438 32.36053 0.8035609 -0.9246494 32.5001 1.754557 -1.5286 32.09676 2.680118 -1.506766 31.86048 3.56616 -1.475991 31.53111 4.406705 -1.436586 31.11429 5.19599 -1.388815 30.61551 5.928356 -1.332864 30.0401 6.598133 -1.268834 29.39321 7.19952 -1.196746 28.67986 7.662403 -1.619134 27.64885 7.134325 -1.716358 28.41014 6.533848 -1.803694 29.11055 5.866947 -1.881246 29.74539 5.139322 -1.949028 30.30987 4.356521 -2.006938 30.79903 3.524053 -2.054752 31.20775 2.647512 -2.092147 31.5307 1.732688 -2.118721 31.7624 0.7856566 -2.134045 31.89728 1.707792 -2.637314 31.38725 2.610348 -2.607106 31.1606 3.47597 -2.56466 30.84471 4.299065 -2.510444 30.44487 5.074216 -2.444829 29.96624 5.796066 -2.368052 29.41377 6.459213 -2.280203 28.79217 7.058072 -2.181216 28.10602 7.586752 -2.070891 27.35973 8.038908 -1.948964 26.55774 8.475517 -1.394524 25.96274 8.531538 -0.9318225 26.19122 8.572484 -0.4542604 26.37184 8.597678 0.01470124 26.49498 8.607059 0.4522818 26.56599 0.763546 -3.075607 31.15095 1.684835 -3.056708 31.0215 2.576041 -3.024057 30.7992 3.431462 -2.978254 30.48935 4.24564 -2.919838 30.09714 5.013279 -2.849234 29.62758 5.729136 -2.766725 29.08546 6.387916 -2.672421 28.47539 6.984145 -2.566261 27.80176 7.512028 -2.44802 27.06881 7.965297 -2.317381 26.28078 0.7438845 -3.824804 30.41549 0.7224712 -4.526594 29.62985 1.642236 -3.803507 30.29054 1.595688 -4.503284 29.50983 2.512196 -3.766831 30.07596 2.442189 -4.463229 29.3037 3.348253 -3.715544 29.77687 3.256668 -4.407337 29.01635 4.145126 -3.650337 29.39825 4.034036 -4.336429 28.65255 4.897682 -3.57178 28.9449 4.769342 -4.251198 28.21687 5.600845 -3.480286 28.42143 5.457699 -4.152173 27.71374 6.249498 -3.376086 27.83225 6.094187 -4.039689 27.14735 6.838366 -3.259213 27.18158 6.673756 -3.913872 26.52172 7.361881 -3.129511 26.47344 7.191097 -3.774622 25.84068 7.814029 -2.986673 25.71183 7.640492 -3.621643 25.10797 8.188235 -2.830298 24.90071 8.015689 -3.454457 24.32725 8.475498 -2.654298 24.03681 8.308428 -3.265547 23.49435 8.656485 -2.469053 23.13951 8.497635 -3.066026 22.62916 8.74172 -2.338781 22.30016 8.589613 -2.922598 21.81957 8.817547 -2.222274 21.48052 8.671477 -2.793444 21.02888 8.977653 -2.276602 17.86715 8.830416 -2.779909 17.51534 0.6993019 -5.176815 28.79752 0.674458 -5.770873 27.92318 1.545192 -5.151884 28.68278 1.490936 -5.744702 27.81401 2.366029 -5.109109 28.4857 2.284018 -5.699854 27.62649 3.156729 -5.049513 28.21094 3.048851 -5.637443 27.36499 3.912407 -4.974025 27.863 3.780771 -5.558485 27.03379 4.628315 -4.883443 27.44626 4.475239 -5.463865 26.63702 5.299765 -4.778394 26.9649 5.127781 -5.3543 26.17864 5.922056 -4.659313 26.42294 5.733928 -5.230309 25.66242 6.490386 -4.526405 25.82416 6.289135 -5.092181 25.09199 6.999732 -4.379628 25.17221 6.788687 -4.939934 24.47075 7.44471 -4.218698 24.47057 7.227556 -4.773306 23.80197 7.819451 -4.043058 23.72261 7.600301 -4.591684 23.08872 8.116687 -3.843954 22.92355 7.900848 -4.385326 22.32588 8.313905 -3.632859 22.09327 8.105613 -4.165707 21.53291 8.412672 -3.478246 21.31559 8.211114 -4.00206 20.78898 8.500493 -3.338257 20.55575 8.304785 -3.853174 20.06167 8.657453 -3.260958 17.14869 0.6480974 -6.305493 27.01237 1.43327 -6.278459 26.90903 2.196692 -6.232175 26.73149 2.933756 -6.167824 26.48384 3.640024 -6.086491 26.17012 4.311176 -5.989132 25.79418 4.942962 -5.876539 25.35975 5.531149 -5.749313 24.87041 6.071457 -5.607819 24.32954 6.559482 -5.452146 23.74034 6.99057 -5.282069 23.10587 7.359732 -5.096951 22.42893 7.662216 -4.886377 21.70428 7.873782 -4.661486 20.95062 7.985858 -4.491079 20.24203 1.174201 -7.777069 23.03282 6.726255 -6.23321 18.45655 6.499646 -6.444968 19.03958 6.162295 -6.715247 18.34509 5.875627 -6.901095 18.86155 5.809585 -6.935453 17.64682 5.531982 -7.108149 18.12076 5.443068 -7.106013 16.94863 5.176546 -7.263447 17.38041 4.480757 -7.435667 15.95343 6.302978 -6.439302 16.20296 6.175362 -6.590497 16.67468 5.936944 -6.646123 15.62558 5.806146 -6.788526 16.0595 5.066554 -7.052162 14.8653 4.922716 -7.174747 15.2281 4.181653 -7.322941 14.01408 6.86116 -6.060126 17.9003 6.388274 -6.515115 17.80619 6.032726 -6.749757 17.15191 5.661072 -6.937183 16.49736 4.721236 -7.30918 15.59906 3.790283 -7.524902 14.59493 6.205955 -6.641574 19.59874 5.867474 -6.815681 20.12029 5.548964 -7.066532 19.34328 5.181146 -7.220068 19.79383 5.218687 -7.262873 18.56287 4.868062 -7.406855 18.97613 4.878103 -7.405579 17.78322 4.545988 -7.538215 18.15952 3.920593 -7.659834 16.5916 5.483855 -6.97686 20.60832 5.058257 -7.125509 21.06087 4.774939 -7.361969 20.21144 4.333212 -7.492055 20.59411 4.482529 -7.540216 19.35897 4.064667 -7.662679 19.70958 4.182327 -7.661333 18.50788 3.78944 -7.774577 18.8267 3.25825 -7.854104 17.13623 2.662014 -7.413941 11.64793 2.867544 -7.317634 11.3138 3.425366 -7.401857 12.8265 3.663668 -7.259645 12.37039 4.443558 -7.132038 13.42793 5.198221 -6.933233 14.50403 3.091694 -7.549489 13.27167 2.392031 -7.512043 11.96719 2.091148 -7.324772 10.26921 1.316086 -7.311907 9.205207 0.861419 -7.284003 8.437583 3.305297 -7.701333 15.10384 2.68729 -7.68047 13.65964 2.072129 -7.60038 12.24354 1.709082 -7.678233 12.4752 2.221827 -7.795297 13.98738 2.73953 -7.855153 15.53619 4.593872 -7.261548 21.47573 4.093884 -7.384581 21.85056 3.858872 -7.609862 20.93968 3.354881 -7.71472 21.24588 3.617125 -7.773725 20.02603 3.142627 -7.872659 20.30627 3.369739 -7.877387 19.11427 2.925715 -7.969063 19.36876 2.509257 -8.014591 17.57724 2.105371 -7.982631 15.88475 1.704543 -7.890759 14.25012 2.412676 -7.668493 22.70924 1.802922 -7.731592 22.89782 1.69551 -7.942737 21.90411 1.103734 -7.986411 22.02826 1.585544 -8.088013 20.90802 1.031659 -8.129287 21.02138 1.473547 -8.168795 19.91453 0.9583241 -8.207094 20.0172 0.8188123 -8.211485 18.10249 0.3689144 -8.230053 18.15055 2.999998 -7.588933 22.46999 2.270089 -7.882156 21.7306 2.123964 -8.030776 20.7495 1.974983 -8.115693 19.77087 1.26003 -8.17978 18.01955 0.6852314 -8.139379 16.29756 0.3055659 -7.627554 11.29237 1.145224 -7.963145 14.44256 1.416045 -8.079113 16.14141 1.690318 -8.135831 17.90333 2.459926 -8.048794 19.58828 2.643958 -7.958652 20.54816 2.82426 -7.805801 21.51034 3.561506 -7.493979 22.18286 7.108852 -5.210576 10.06074 6.365863 -5.734955 9.752407 1.088074 -7.261226 8.441682 1.494789 -7.258043 8.904948 2.368533 -7.213617 9.764197 3.225521 -7.129592 10.58755 4.080297 -6.982787 11.40268 4.903494 -6.761184 12.2074 5.683178 -6.46526 13.01812 6.421288 -6.085622 13.85657 6.776717 -5.844275 14.28645 7.112413 -5.569303 14.71555 9.468975 1.3846 8.517038 9.441379 1.371175 11.97287 9.203248 2.017673 15.55964 8.982567 2.499913 17.20587 9.233595 -1.804439 14.6952 8.954894 -2.725703 14.21486 9.074309 -2.501656 12.73386 8.80868 -3.146428 10.965 8.339903 -3.910764 10.67438 7.770527 -4.60136 10.37124 9.364894 1.344401 15.59032 9.54754 -0.5277512 11.73649 9.568719 -0.07212162 11.85131 9.515446 -0.1868253 13.60431 9.518495 0.2993904 13.72925 9.460441 0.2114446 15.51617 9.437433 0.7569615 15.58599 9.299101 0.6630939 19.19197 9.241703 1.312717 19.20609 9.070445 1.282405 22.82509 9.009287 1.679273 22.80742 8.904258 1.680928 24.63948 8.810562 2.070766 24.594 8.679738 2.078666 25.5725 8.610838 2.499766 25.04454 8.535965 1.671793 26.57673 8.769765 1.681988 25.62672 8.825457 1.261243 25.65006 8.855781 0.4886006 25.6126 8.995043 0.1284058 24.55995 9.043079 -0.2351925 23.53777 9.075537 -0.5784108 22.50392 9.266243 -0.6318339 18.83986 9.446412 -0.3225691 15.35251 9.402807 -0.8299177 15.14077 9.484009 -0.6647737 13.44157 9.335749 -1.604927 13.10025 9.416841 -1.441257 11.49658 9.169438 -2.319043 11.24016 9.236643 -2.187442 9.731491 0.6203293 -6.778194 26.07 0.5912975 -7.186314 25.10156 1.372434 -6.750683 25.97271 1.308745 -7.158719 25.01046 2.10442 -6.703616 25.80549 2.007679 -7.111533 24.85386 2.811931 -6.638222 25.5722 2.684006 -7.046011 24.63529 3.490766 -6.555636 25.27656 3.333766 -6.963316 24.35821 4.136831 -6.456868 24.92219 3.9531 -6.864493 24.02597 4.746107 -6.342772 24.51257 4.538218 -6.750446 23.64179 5.314599 -6.214018 24.05103 5.085374 -6.621903 23.20879 5.8383 -6.071048 23.54075 5.590828 -6.479374 22.72989 6.313118 -5.914024 22.98472 6.0508 -6.323101 22.2079 6.734778 -5.742777 22.38577 6.461391 -6.152986 21.64542 7.098756 -5.556676 21.74648 6.818548 -5.96844 21.04481 7.401688 -5.344975 21.06167 7.120276 -5.758745 20.40114 7.619117 -5.118174 20.34903 7.342371 -5.533508 19.73088 7.737528 -4.943364 19.67714 7.466777 -5.356751 19.09679 7.842356 -4.782815 19.01899 7.576829 -5.193575 18.47486 7.99016 -4.548638 15.97297 7.720175 -4.920243 15.56088 8.081027 -4.34376 13.15465 8.085213 -4.335319 19.54869 8.236835 -4.147069 16.37601 8.45944 -3.717227 16.76843 0.5611847 -7.52829 24.11352 1.242605 -7.500996 24.02872 1.907083 -7.454345 23.88288 2.55079 -7.389593 23.67925 3.170012 -7.307913 23.42101 3.761127 -7.21037 23.11123 4.320582 -7.097898 22.7529 4.844875 -6.971274 22.34885 5.330532 -6.831071 21.90184 5.774077 -6.677609 21.41442 6.171973 -6.510875 20.889 6.520627 -6.330359 20.32773 6.81931 -6.125743 19.72605 7.044544 -5.905556 19.09911 7.174481 -5.729369 18.50367 7.289464 -5.56578 17.91872 7.427389 -5.260854 15.1412 7.496156 -5.016303 12.5887 7.649097 -4.787122 11.49304 6.822399 -5.586069 12.0117 6.982068 -5.378784 11.05137 6.082145 -6.048351 11.44438 6.240403 -5.87536 10.61509 5.277845 -6.431562 10.89013 5.425392 -6.294974 10.18628 4.415374 -6.73714 10.33382 4.546511 -6.635418 9.753232 3.708634 -6.837252 8.813295 3.313093 -6.914957 8.474513 7.465746 4.355044 15.33398 8.464855 3.301554 19.3165 8.167611 3.291929 24.70754 8.295942 3.295497 22.9119 8.028655 3.289797 25.59697 7.832471 3.287176 26.47132 7.544889 3.286804 27.31668 7.15599 3.287604 28.12927 6.677084 3.286865 28.89194 6.1166 3.28558 29.59963 5.483233 3.284426 30.2464 4.785675 3.284081 30.82632 4.032562 3.285049 31.3331 3.232275 3.287098 31.75887 2.393127 3.289793 32.09536 1.523433 3.292702 32.33426 0.6309801 3.29538 32.46728 1.450043 4.322506 31.44598 0.5998766 4.330926 31.58456 2.273611 4.313243 31.19863 3.06227 4.304554 30.851 3.805966 4.2978 30.41162 4.494649 4.294341 29.88905 5.118463 4.294921 29.29185 5.668271 4.298001 28.62859 6.135102 4.301513 27.90786 6.509988 4.303389 27.13824 6.785403 4.300594 26.3247 6.949011 4.301378 25.50298 7.124711 4.315168 23.81519 7.231858 4.325336 22.11664 7.084046 4.550505 8.520973 7.266661 4.499995 8.521593 7.006501 3.616985 27.91246 6.420458 3.89471 28.44301 7.368267 3.615731 27.09826 6.849005 3.896077 27.67502 0.6165846 3.9132 32.08376 1.489545 3.907711 31.94612 2.337828 3.901684 31.70116 3.153381 3.896051 31.35725 3.927024 3.891709 30.92284 4.649573 3.889555 30.40632 5.311911 3.890076 29.81592 5.905149 3.892253 29.15906 7.182812 3.894339 26.86012 7.789821 3.911352 22.54448 7.668779 3.904366 24.29526 7.554617 3.900165 25.16552 7.410059 3.894976 26.02473 7.635361 4.352612 8.522626 8.064993 3.931981 15.54428 8.817128 2.917103 15.80171 8.949592 2.921332 8.521965 8.585982 3.3061 15.72364 8.722071 3.330932 8.522855 8.228994 3.93566 8.523429 9.451826 1.461445 8.507325 9.372043 1.7753 8.508456 9.14589 2.463714 8.510692 9.527616 1.082456 8.505863 0.025379 -6.698779 7.501258 9.507753 0.3095692 8.056339 9.477331 0.3781827 8.00723 9.321379 0.3684355 7.801448 9.067171 0.2853657 7.613262 9.117325 0.358331 7.64306 0.02572846 -7.010307 7.693616 1.73442 -7.084749 7.999649 0.9226842 -7.270146 8.346724 0.9146584 -7.172571 7.992993 0.2006235 -7.325987 8.340023 0.1987732 -7.22724 7.987303 0.0239616 -7.329585 8.338543 0.02523338 -7.23062 7.986043 6.299645 -5.610662 8.046438 5.65603 -6.076298 8.399748 5.617098 -5.994254 8.037804 4.916317 -6.410162 8.389672 4.884037 -6.323693 8.029365 4.464048 -6.578641 8.383936 4.435673 -6.48995 8.024553 3.624586 -6.83092 8.374051 3.602872 -6.738961 8.016221 2.667161 -7.040428 8.363743 2.651893 -6.945812 8.007493 1.938632 -7.155798 8.356415 1.744689 -7.181197 8.35452 8.801453 -2.988243 8.089764 8.521315 -3.612688 8.452795 8.45452 -3.564836 8.081827 8.468626 -3.689843 8.451452 8.402338 -3.640894 8.080716 8.036555 -4.246749 8.441288 7.974494 -4.189916 8.072319 7.545015 -4.760835 8.431118 7.487793 -4.696833 8.063897 6.983984 -5.241389 8.420743 6.93228 -5.170747 8.055288 6.671692 -5.471166 8.415398 6.345085 -5.687454 8.410098 0.1818868 -6.695679 7.50207 0.8636388 -6.643054 7.505821 1.670404 -6.556369 7.510369 2.558979 -6.421486 7.5156 3.471896 -6.222581 7.521308 4.264346 -5.985319 7.526627 4.688507 -5.827833 7.529646 5.379212 -5.517095 7.534863 6.018709 -5.157359 7.540099 6.608065 -4.747186 7.545365 7.123431 -4.307168 7.55042 7.572859 -3.838723 7.555298 7.965839 -3.334085 7.560091 8.013631 -3.264367 7.56072 8.331617 -2.73546 7.565248 8.59273 -2.176559 7.569625 8.794532 -1.590999 7.573825 8.830655 -1.458651 7.574724 8.951199 -0.8664002 7.578522 0.192229 -7.007092 7.694631 0.8940315 -6.953503 7.699233 1.708463 -6.866423 7.704688 2.614082 -6.729485 7.711054 3.549489 -6.526274 7.718084 4.365832 -6.282448 7.724727 4.804351 -6.12 7.728537 5.520238 -5.798586 7.735176 6.185405 -5.425116 7.741915 6.800652 -4.997701 7.748772 7.340122 -4.537924 7.755407 7.812015 -4.046944 7.761865 8.226099 -3.516191 7.768268 8.276555 -3.442733 7.769112 8.612162 -2.885646 7.775167 8.887817 -2.296904 7.780996 9.101153 -1.679408 7.786575 9.139395 -1.539688 7.787768 9.267207 -0.9139755 7.792798 9.086302 -2.379022 8.097375 9.306784 -1.739777 8.104641 9.34632 -1.595058 8.106193 9.478426 -0.9467466 8.112719 9.594346 -0.6107967 8.493734 9.552957 -0.9597634 8.489964 9.42033 -1.616441 8.48215 9.380566 -1.763045 8.480285 9.158576 -2.41066 8.471556 9.043931 -2.677724 8.4677 8.871421 -3.028041 8.462388 9.615229 -0.2922498 8.496942 9.54094 -0.2873402 8.11859 9.327846 -0.2770744 7.797371 9.008281 -0.2630099 7.582022 7.080578 4.551367 8.510958 7.258795 4.367528 8.015908 7.148424 4.02468 7.651365 7.297481 4.491278 8.511695 7.670834 4.334519 8.512706 7.611764 4.219337 8.016863 8.033303 4.102739 8.513306 7.954683 4.000058 8.017433 8.229042 3.935708 8.513429 8.28306 3.696497 8.017524 8.378714 3.783495 8.513406 8.655106 3.432614 8.513029 8.547963 3.360128 8.017163 8.722119 3.330981 8.512856 8.772282 2.985469 8.016423 8.887408 3.044682 8.512263 9.110681 2.554319 8.510961 8.989757 2.507732 8.015155 9.024254 2.418957 8.014891 9.399192 1.062641 8.010149 9.246603 1.74213 8.012691 7.445701 3.899901 7.65217 7.735216 3.714776 7.65265 8.017045 3.454058 7.652729 8.250558 3.157339 7.652408 8.453078 2.81894 7.651739 8.654707 2.375701 7.650563 8.687261 2.291925 7.650315 8.899213 1.646755 7.648217 9.043656 1.003751 7.645812 6.287097 4.957409 8.265275 6.287097 4.877247 8.012142 6.287097 5 8.012142 6.287097 4.981026 8.515722 6.287097 4.98106 8.51069 6.287097 4.977352 8.4081 6.287098 4.830243 22.9522 6.287097 4.936964 15.73608 6.287097 4.980999 8.519338 5.79039 3.960148 7.512145 5.788051 3.961305 7.512134 5.789461 4.896141 7.512146 5.812585 3.97658 7.51279 5.796983 3.962312 7.512238 5.792825 3.959592 7.512167 5.826548 3.994339 7.513699 5.803693 4.89686 7.512415 5.913114 4.118309 7.528281 5.890488 4.901372 7.522947 5.930305 4.904067 7.533087 6.036521 4.307681 7.578796 6.046786 4.914702 7.584868 6.077197 4.373933 7.604903 6.173159 4.543784 7.694404 6.07994 4.918709 7.606871 6.196732 4.590354 7.725436 6.172883 4.934013 7.69407 6.219849 4.639384 7.761689 6.287064 4.998859 8.006452 6.220591 4.946635 7.762977 6.255605 4.962582 7.837499 6.271763 4.778231 7.889263 6.281268 4.984545 7.936019 6.286704 4.996021 7.992332 6.1974 4.939797 7.726393 6.255414 4.726725 7.836986 5.763058 4.895692 7.512021 1.014686 4.910339 7.48957 5.784363 3.962486 7.512121 4.813383 4.898519 7.507531 4.992423 5.908701 27.89637 4.98559 5.946793 27.92615 4.971888 5.922567 27.96247 4.991626 5.871617 27.86462 4.976886 5.880029 27.93807 4.917718 5.868232 28.09713 4.918692 5.813274 28.08073 4.882382 5.849207 28.17838 4.880874 5.786657 28.16505 4.774966 5.832143 28.40075 4.762895 5.747697 28.39764 4.974183 5.83864 27.91142 4.909527 5.760324 28.06067 4.866984 5.726953 28.14676 4.73025 5.670089 28.38358 4.999238 5.889869 27.84209 5.007272 5.914668 27.81457 4.995645 5.973868 27.89882 4.990974 5.959435 27.91159 5.020695 5.97563 27.76283 5.008536 6.030302 27.86291 5.002418 6.001591 27.88008 5.01447 5.944834 27.78815 6.287094 5.00286 8.01005 6.281857 5.125258 7.918077 5.72713 6.168904 7.918077 6.006244 5.873888 7.918077 6.139881 5.648055 7.918077 6.195986 5.51481 7.918077 4.970671 5.663197 27.84409 4.789171 5.536065 28.17637 4.87686 5.580954 28.03174 5.018336 5.7771 27.70427 5.023786 5.760572 27.69195 4.698447 5.509659 28.30766 4.698502 5.469728 28.29498 4.746765 5.835645 28.45407 4.691493 5.664305 28.4423 4.730608 5.745818 28.4548 4.651255 5.872669 28.62223 4.61424 5.767746 28.64255 4.545905 5.677735 28.63807 4.658137 5.662513 28.49041 4.425708 5.723496 28.78995 4.505628 5.818893 28.80278 4.500234 5.963159 28.85652 4.549707 5.934374 28.78345 4.300149 5.772917 28.9352 4.363797 5.834999 28.95434 4.390247 5.872029 28.95737 4.441109 5.996667 28.93974 5.059897 5.887024 27.48116 5.025702 6.027051 27.60337 4.994723 6.192138 26.94162 4.951021 6.228391 27.01685 4.952718 6.226445 27.02202 5.045984 6.097987 27.09732 5.067421 6.000865 27.26906 4.992485 6.167548 27.18704 5.016583 6.103774 27.37352 4.959401 6.675277 21.96681 4.87943 6.624922 21.98112 4.891986 6.619048 22.01548 5.050821 6.608306 22.28592 5.333819 6.46192 24.72463 5.395863 6.434315 24.28377 5.332471 6.462451 23.84427 5.407973 6.425547 24.18647 5.410057 6.423894 24.16808 5.218375 6.456716 23.91808 5.218375 6.456716 25.43195 5.284139 6.468039 25.03738 5.097452 6.574097 22.4841 5.133789 6.500474 22.93178 5.197439 6.500627 23.08299 5.205646 6.46341 23.53296 5.243577 6.466669 23.70731 5.246304 6.464662 23.8451 5.011913 6.560826 22.39293 5.029277 6.552357 22.45656 5.08963 6.579838 22.4486 5.034642 6.549736 22.47684 5.094165 6.576509 22.46906 5.037297 6.548439 22.48699 5.096407 6.574864 22.4793 5.037958 6.548116 22.48952 5.096965 6.574455 22.48186 5.038535 6.547834 22.49175 5.05139 6.541545 22.54221 5.409703 6.424179 23.84325 5.407097 6.426275 23.70193 5.32981 6.46454 23.7049 5.362941 6.461785 23.06107 5.284737 6.499919 23.0732 5.266832 6.539076 22.44376 5.18682 6.576734 22.46609 5.26643 6.539399 22.44178 5.186411 6.577055 22.46414 5.265893 6.539831 22.43913 5.185865 6.577483 22.46155 5.263734 6.541567 22.42855 5.183668 6.579206 22.45116 5.259365 6.545081 22.40741 5.179224 6.582691 22.43041 5.221935 6.575182 22.2391 5.141173 6.612525 22.26533 5.133444 6.646347 21.90779 5.051389 6.682887 21.94112 5.005314 6.684736 21.95535 2.66437 7.509163 19.92788 2.853323 7.4591 19.95425 3.017654 7.451351 19.98716 3.228133 7.354598 20.0581 3.342544 7.369414 20.09594 3.323098 7.327039 20.09593 3.351216 7.366833 20.09965 3.450451 7.335811 20.14531 3.599416 7.244338 20.23497 3.766314 7.21816 20.33457 3.887726 7.153933 20.43121 3.963062 7.129587 20.49226 5.002268 6.108575 27.84882 5.015342 6.108527 27.76283 4.992032 6.145081 27.83967 4.951467 6.227883 27.76283 4.934142 6.242021 27.80449 4.946193 6.227998 27.81088 3.733566 6.341759 29.69486 3.4106 6.473395 29.93878 3.361443 6.35475 29.93905 4.065021 5.867538 29.17661 4.13812 5.9306 29.20962 4.195645 6.014287 29.21947 4.23094 6.10892 29.20503 3.653888 6.031994 29.52269 3.734774 6.093329 29.58016 3.802237 6.184777 29.60647 3.846077 6.292514 29.59767 3.290305 6.257847 29.89386 4.819599 6.103848 28.31235 4.641327 6.17027 28.63873 4.500092 6.220878 28.85673 3.256652 6.59307 30.039 2.770497 6.675111 30.29822 3.230079 6.539001 30.05535 3.702619 6.474349 29.72041 3.966841 6.396327 29.48523 4.332848 6.27854 29.08185 2.235211 7.744465 19.7206 2.235116 7.720387 19.81569 2.001919 7.727364 19.8165 2.23278 7.654042 19.88791 2.003404 7.664578 19.88799 2.228766 7.561391 19.91988 2.004119 7.575856 19.92238 2.469923 7.727868 19.71889 2.468015 7.702718 19.81611 2.461847 7.633697 19.88881 2.452976 7.538211 19.91866 2.590097 7.715056 19.72109 2.582939 7.690142 19.81887 2.571574 7.62079 19.89164 2.558908 7.524743 19.92077 2.676478 7.583093 19.91124 2.680766 7.605565 19.89948 2.689297 7.644997 19.86773 2.709688 7.699378 19.72875 2.700938 7.685759 19.80376 2.697301 7.674967 19.82683 3.80389 7.284252 20.32107 4.004707 7.195247 20.48089 3.850812 7.333641 20.28473 4.057505 7.242713 20.44721 3.900087 7.358967 20.23095 4.113305 7.264657 20.39642 3.94437 7.356454 20.16774 4.163494 7.257692 20.33636 3.481022 7.403327 20.12927 3.51831 7.456044 20.0895 3.556954 7.486383 20.03174 3.591399 7.489983 19.96428 3.480265 7.525857 19.91499 3.448988 7.52059 19.98363 3.413718 7.488775 20.04245 3.379498 7.43496 20.08306 3.085743 7.616092 19.86526 3.106176 7.626102 19.79318 3.06191 7.579657 19.92704 3.038079 7.521998 19.96971 4.812244 6.752068 21.63436 5.007922 6.744045 21.55582 4.947769 6.772363 21.58754 4.879454 6.775164 21.61496 4.790578 6.898815 21.10591 4.731171 6.921526 21.14689 4.735111 6.935589 21.01243 4.676134 6.956847 21.05552 4.471574 7.096414 20.64712 4.415764 7.110847 20.69902 4.664291 6.917237 21.182 4.609863 6.950811 21.09237 4.353477 7.096958 20.74311 4.59951 6.886562 21.20623 4.545884 6.918352 21.11766 4.294084 7.056837 20.77276 4.755259 6.70621 21.6431 4.546098 6.833891 21.2161 4.493452 6.864168 21.12773 4.246518 6.996518 20.78352 5.133444 6.646347 7.918077 5.533697 5.928376 7.456136 4.976771 6.45153 7.485063 5.570458 5.974087 7.485063 5.635354 6.054783 7.564523 5.091464 6.594146 7.668076 5.68515 6.116703 7.668076 5.703278 6.139245 7.726735 5.755377 5.694066 7.456136 6.272061 5.159377 7.837675 6.223413 5.199346 7.700305 6.160238 5.501747 7.726735 6.117644 5.224514 7.560376 6.058435 5.464548 7.564523 5.966848 5.231051 7.460769 5.906076 5.408876 7.456136 5.824494 5.22451 7.421862 5.887217 5.788569 7.564523 5.97531 5.851714 7.726735 4.60905 5.466274 28.41008 4.483088 5.546818 28.5861 4.463797 5.478513 28.57256 4.449933 5.393326 28.56595 4.348891 5.582283 28.72551 4.304843 5.412102 28.70427 4.153252 5.430833 28.83589 4.183952 5.559499 28.84377 4.234692 5.676963 28.87823 4.901778 6.273209 27.00959 4.872569 6.291904 26.96101 4.899455 6.274876 26.94713 4.887618 6.282867 26.94988 4.928301 6.251574 26.9671 4.91659 6.261751 26.95394 4.908242 6.26839 26.94891 4.989249 6.230724 26.82003 5.106485 6.381645 26.10812 4.791979 6.339597 26.8977 4.984008 6.340222 26.5271 4.86754 6.330957 26.78334 5.061585 6.362297 23.91808 4.877969 6.330672 23.91808 5.035656 6.377615 23.34124 4.728437 6.399847 22.61351 4.770024 6.380768 22.80722 4.917668 6.447354 22.56796 4.957759 6.423642 22.76882 4.850977 6.343278 23.36012 4.830833 6.477311 22.29329 4.748735 6.522978 22.01721 4.563871 6.467946 22.08164 4.648028 6.430969 22.34736 4.607465 6.47345 22.06533 2.388407 7.208168 20.0715 2.374463 7.136898 20.16808 2.719617 7.06117 20.20542 4.487491 6.520178 21.78186 3.776536 6.945355 20.49559 4.100512 6.839219 20.79809 4.388078 6.738565 21.15971 4.448193 6.716724 21.24985 4.697378 6.623119 21.69916 3.50077 7.029959 20.30425 3.146325 7.131334 20.13059 2.788508 7.22555 20.02613 2.409602 7.316506 19.98506 3.046461 6.980799 20.30135 3.371903 6.892242 20.46209 3.6266 6.816839 20.64055 3.927668 6.720589 20.92488 4.196579 6.627883 21.26736 4.252988 6.607609 21.35307 2.305537 6.783685 30.48779 1.698961 6.887456 30.67714 2.00522 6.840055 30.5894 4.328458 6.401429 29.04282 4.281468 6.501592 28.97645 3.926691 6.625139 29.36583 4.751935 6.318816 28.23599 4.806807 6.220933 28.28255 4.579804 6.388249 28.54975 4.631807 6.289507 28.60465 3.670034 6.707118 29.59339 3.235829 6.83208 29.90246 3.967659 6.523406 29.44279 3.706607 6.604331 29.67662 3.264896 6.727666 29.9943 1.561665 7.593631 19.93031 1.558668 7.730064 19.82221 1.560599 7.674231 19.89188 4.638771 6.917913 7.668076 4.540873 6.763285 7.485063 4.072633 7.023955 7.485063 3.578009 7.230221 7.485063 3.063299 7.379459 7.485063 2.535054 7.469769 7.485063 4.152489 7.188626 7.668076 3.638808 7.40284 7.668076 3.104267 7.557828 7.668076 2.555669 7.651616 7.668076 4.674604 6.97451 7.918077 4.181718 7.248899 7.918077 3.661062 7.466022 7.918077 3.119262 7.623115 7.918077 2.563215 7.718178 7.918077 4.031828 5.752746 29.06421 3.138162 5.911215 29.52569 3.074224 5.723623 29.50528 3.648747 5.901646 29.35905 3.223221 6.067225 29.61581 3.572118 5.759977 29.29452 3.51853 5.595526 29.28075 3.930191 5.484102 29.01102 3.97007 5.625985 29.02033 3.113096 6.317206 29.9974 3.182049 6.416237 30.05068 2.667204 6.441543 30.21202 2.698715 6.487912 30.25348 2.72743 6.544394 30.28259 1.678362 6.776526 30.66008 2.200239 6.522167 30.35294 2.242155 6.587463 30.42944 2.278869 6.678645 30.47646 1.617354 6.616538 30.51558 1.649781 6.681645 30.6035 1.015315 5.052363 7.453825 4.814067 5.056114 7.462805 2.717827 5.125623 7.428353 5.763418 5.132645 7.430487 5.763756 5.056866 7.46505 5.783743 5.056916 7.46533 5.801065 5.056788 7.466086 5.81313 5.131833 7.432907 5.893575 5.055797 7.479786 5.947629 5.136626 7.46133 5.935694 5.055137 7.492013 6.09498 5.134186 7.54465 6.057066 5.052051 7.552012 6.206845 5.042149 7.708177 6.183345 5.044708 7.673231 6.204532 5.120485 7.668322 6.165468 5.046265 7.650284 6.090927 5.050702 7.57689 6.261628 5.097235 7.794115 6.278039 5.076819 7.86961 6.259808 5.031394 7.825396 6.287069 5.000965 8.00619 6.286758 5.003362 7.991406 6.282074 5.013043 7.932194 1.014966 4.983566 7.480497 4.813683 4.980429 7.496133 5.763363 4.979632 7.500039 5.786425 4.979859 7.500197 5.801918 4.980094 7.500564 5.889748 4.9815 7.511634 6.047546 4.985373 7.575414 5.930009 4.982315 7.522139 6.173982 4.990371 7.686945 6.080899 4.986464 7.59796 6.198383 4.991766 7.719799 6.255789 4.997225 7.832127 6.377517 4.763366 8.425012 6.378855 4.745692 8.307834 6.310987 4.842391 8.288395 6.377305 4.766617 8.509262 6.310624 4.861254 8.417276 6.310567 4.864738 8.509916 6.312431 4.766764 8.060643 6.384155 4.674941 8.100951 6.37726 4.597348 7.967011 6.213486 4.478664 7.725483 6.111386 4.329151 7.622153 6.066721 4.270209 7.591418 5.928846 4.100427 7.531384 5.83122 3.988705 7.513979 5.815411 3.972749 7.512896 5.797578 3.960155 7.512241 6.292836 4.636654 7.882101 6.237412 4.51918 7.76046 6.306075 4.680785 7.936858 6.361512 4.55814 7.90794 6.296203 4.454292 7.777201 6.268337 4.418489 7.739729 6.15097 4.286097 7.629313 6.100208 4.233769 7.596542 5.944963 4.082659 7.532607 5.835903 3.983075 7.51408 5.818241 3.96892 7.512928 5.798172 3.957998 7.512228 0.1885583 4.725614 30.54075 0.1872261 4.82311 30.47537 0.3770718 4.821543 30.46685 0.3800348 4.724069 30.53215 0.982531 4.714386 30.46743 6.285726 4.667626 24.7807 6.365177 4.56433 24.78866 6.184695 4.676602 25.44084 6.016143 4.691249 26.08443 5.60971 4.702891 27.06483 5.832915 4.698403 26.58476 5.346937 4.705952 27.52471 5.044119 4.708754 27.96414 4.523073 4.714631 28.57143 3.932556 4.725435 29.10535 3.500209 4.735975 29.42036 2.807392 4.757541 29.82041 2.074318 4.781724 30.12797 1.563145 4.797193 30.28168 0.9743015 4.811884 30.40249 1.577123 4.699472 30.34616 2.093728 4.683657 30.19184 2.835409 4.658784 29.88267 3.537269 4.636499 29.47959 3.975404 4.625619 29.16151 4.574022 4.614275 28.62219 5.102253 4.60793 28.00842 5.409249 4.604838 27.56429 5.67566 4.601512 27.0995 5.902027 4.596768 26.61438 6.087924 4.589381 26.10895 6.259419 4.574432 25.4581 6.389782 4.563943 24.47847 6.308566 4.667701 24.47546 6.399025 4.567614 24.1629 6.316524 4.671744 24.16521 6.381239 4.71875 15.73385 6.310567 4.864674 8.519126 6.377306 4.766551 8.518947 6.311636 4.818137 15.73487 6.316075 4.701645 22.94918 6.397409 4.597889 22.94674 6.377307 4.766582 8.51429 6.310567 4.864703 8.514945 + + + + + + + + + + -0.02093791 0.9585114 0.2842841 -0.02049434 0.9585786 0.28409 -0.009558439 0.9586713 0.2843555 -0.008123159 0.9588753 0.2837119 -0.004726231 0.004804015 -0.9999773 -0.004530906 0.00486803 -0.999978 -0.004722595 0.004802525 -0.9999774 -0.004728674 0.004803121 -0.9999774 -0.004727423 0.004803299 -0.9999773 -0.004728019 0.00480616 -0.9999774 -0.004727721 0.004797995 -0.9999774 -0.004743695 0.004805028 -0.9999772 -0.004706799 0.004803121 -0.9999774 -0.004868626 0.004803299 -0.9999767 -0.00472337 0.004803597 -0.9999774 -0.00472337 0.004807353 -0.9999773 -0.004735112 0.004807889 -0.9999772 -0.004725813 0.004804313 -0.9999773 -0.004728078 0.004798352 -0.9999774 -0.004726648 0.004805564 -0.9999773 -0.004720449 0.004802584 -0.9999774 -0.004733264 0.004800856 -0.9999773 -0.004726886 0.004802823 -0.9999773 -0.00472337 0.004803836 -0.9999774 -0.004728436 0.004802465 -0.9999773 -0.004728853 0.00480318 -0.9999773 -0.004723906 0.004802942 -0.9999774 -0.004725813 0.004803299 -0.9999774 -0.004729509 0.004802584 -0.9999774 -0.00472325 0.004803478 -0.9999774 -0.004725039 0.004803895 -0.9999773 -0.004729151 0.004802405 -0.9999774 -0.004723846 0.004803121 -0.9999774 -0.004723608 0.004806637 -0.9999773 -0.004727065 0.004795789 -0.9999774 -0.004717886 0.004810452 -0.9999774 -0.004725158 0.004803597 -0.9999773 -0.0047279 0.004802703 -0.9999774 -0.004716038 0.004803299 -0.9999774 -0.004731774 0.004802167 -0.9999773 -0.0047248 0.004803478 -0.9999773 -0.004729747 0.004802942 -0.9999773 -0.1693226 0.402997 -0.8994017 0.0128194 0.001001477 -0.9999173 -0.2239407 0.9562683 -0.1881532 -0.2175319 0.9563595 -0.1950809 -0.2518761 0.9674712 -0.02362102 -0.1639106 0.8128033 -0.5590028 -0.2248 0.8688966 -0.4410033 -0.2366583 0.9041035 -0.3557947 -0.1755968 0.6219138 -0.7631441 -0.1051392 0.5555861 -0.8247848 -0.11184 0.5083488 -0.8538579 -0.01701021 0.05226266 -0.9984886 -0.02562659 0.1622273 -0.9864206 -0.01944661 0.2064626 -0.9782612 -0.1091884 0.3404606 -0.9338976 -0.1134529 0.478499 -0.8707281 -0.01765263 0.03150361 -0.9993478 -0.02682954 0.04812371 -0.998481 -0.06947547 0.188717 -0.9795709 -0.1861414 0.2024112 -0.9614475 -0.06618362 0.1117058 -0.991535 -0.01323413 0.02251845 -0.9996588 -0.01216053 0.02265065 -0.9996695 -0.01121616 0.01855438 -0.999765 0.01502192 -0.02749061 -0.9995093 -0.01005423 0.01525431 -0.9998331 -0.1885622 0.7406897 -0.6448436 -0.1756892 0.8183652 -0.5471853 -0.9792503 -0.02517187 -0.2010855 -0.6627672 0.5160945 -0.5425738 -0.2047481 0.7264772 -0.6559796 -0.3200159 0.4748709 -0.8198095 -0.4433706 0.4354779 -0.7834421 -0.2542968 0.4727653 -0.8436979 -0.3534895 0.934826 -0.03384518 -0.4591906 0.8801679 -0.1202021 -0.6520733 0.737631 -0.1752172 -0.3130511 0.9049258 -0.2882853 -0.3225195 0.8287938 -0.4572549 -0.2546548 0.9663401 0.03657472 -0.247758 0.968303 0.03170788 -0.2464062 0.9686213 0.03250974 -0.2470707 0.9686797 0.02481132 -0.2363646 0.9713168 0.02599066 -0.2557653 0.9660109 0.03751111 -0.2115255 0.9763887 0.04384201 -0.2628501 0.9636186 0.04846829 -0.2423176 0.967628 0.07055753 -0.2322174 0.9699668 0.07238465 -0.251554 0.9632652 0.09402543 -0.2262545 0.9692032 0.09723234 -0.2378699 0.9642557 0.1167425 -0.2182869 0.9685622 0.1193245 -0.2272743 0.9639196 0.1385836 -0.2095256 0.9678259 0.1393277 -0.213422 0.9646754 0.154442 -0.1895395 0.9687922 0.159739 -0.2011919 0.9656204 0.1646183 -0.1886812 0.9644139 0.1852169 -0.1809692 0.9664137 0.1824688 -0.1798178 0.9622079 0.2045029 -0.1605985 0.9662009 0.201653 -0.1727046 0.9629435 0.2071545 -0.1565746 0.962832 0.2200886 -0.1541973 0.9635228 0.2187397 -0.1437978 0.959658 0.241617 -0.114632 0.9658008 0.2325692 -0.1361626 0.9575325 0.2541484 -0.09950685 0.960201 0.2609837 -0.1080703 0.9571849 0.2685477 -0.08578902 0.9588953 0.2704815 -0.07802718 0.9599499 0.2690873 -0.07128095 0.9572502 0.2803409 -0.041781 0.9595773 0.2783269 -0.04540908 0.9581217 0.2827386 -0.2654471 0.9641175 0.003927409 -0.2488179 0.9685316 0.006035387 -0.2682762 0.9633085 0.008046329 -0.2542243 0.9670838 0.01090967 -0.2542023 0.9670723 0.01235526 -0.2368968 0.9714394 0.01361989 -0.2368509 0.9714117 0.01616126 -0.2269955 0.9737405 0.01739346 -0.2269186 0.9737122 0.0198124 -0.2152795 0.9763267 0.02100384 -0.2093852 0.9775444 0.02376699 -0.2180264 0.9756652 0.02327829 -0.217167 0.9758637 0.0229938 -0.2213693 0.9749752 0.02046984 -0.2278209 0.9734572 0.02188217 -0.2365669 0.9713891 0.02095961 -0.3536136 0.9353699 0.006385743 -0.200374 0.6919398 -0.6935917 -0.2654747 0.9640946 0.006702482 -0.9906305 -0.1342288 0.02517718 -0.9986991 0.03773009 0.03430306 -0.4025669 -0.9124508 -0.07330417 -0.3760677 -0.926577 0.005317687 -0.3779912 -0.9229331 -0.0729202 -0.9362504 0.01060694 0.3511734 -0.874547 0.2058448 0.4390848 -0.1861256 0.1999363 0.9619681 -0.4021773 0.240489 0.883413 -0.875904 0.3028129 0.3756282 -0.1189156 -0.9871956 -0.1063199 -0.07705348 -0.9925204 -0.0946896 -0.03909856 -0.992421 -0.1164985 -0.006691217 -0.9964393 0.08404815 -0.03406715 0.1633165 0.9859854 -0.0398032 0.04737973 0.9980837 -0.04839646 -0.03102993 0.9983461 -0.03178244 -0.06740707 0.9972193 -0.05001175 -0.1121587 0.9924311 -0.03166425 -0.1974288 0.9798058 -0.04988574 -0.1777284 0.9828144 -0.03743863 -0.295347 0.9546563 -0.04820388 -0.2836797 0.9577068 -0.03719049 -0.3960393 0.9174801 -0.05230641 -0.3809151 0.9231293 -0.02865678 -0.4943384 0.8687971 -0.05265313 -0.4740422 0.8789265 -0.02754974 -0.5876915 0.8086159 -0.05013102 -0.5691754 0.8206865 -0.03464514 -0.6325609 0.7737355 -0.04224509 -0.6585533 0.7513474 -0.04616487 -0.6526756 0.7562297 -0.01396304 -0.7006528 0.7133658 -0.05885541 -0.6826701 0.7283527 -0.01145529 -0.7458907 0.66597 -0.05959129 -0.7284375 0.6825158 -0.00770539 -0.7881217 0.6154712 -0.0583378 -0.771798 0.6331861 -0.006813049 -0.8272142 0.5618454 -0.05568301 -0.8130254 0.5795596 -0.006636917 -0.8624752 0.5060558 -0.05326008 -0.8503849 0.5234587 -0.00547266 -0.8939022 0.448229 -0.05114126 -0.8835691 0.4654999 -0.004060864 -0.9215499 0.3882388 -0.04925686 -0.912809 0.4054056 -0.002490162 -0.9450178 0.3270094 -0.04775398 -0.9377278 0.3440731 -0.01154822 -0.9586625 0.2843112 -0.03650915 -0.9639054 0.2637301 -0.02918809 -0.9667768 0.2539502 -0.02328211 -0.9691717 0.245284 -0.01521819 -0.979407 0.2013217 -0.02785557 -0.9780004 0.2067355 -0.03298258 -0.9985206 -0.04323101 0.01423764 -0.9994555 -0.02976989 -0.06951177 -0.9975257 0.01052308 -0.05971223 -0.9904328 -0.1244081 -0.01819324 -0.9938596 -0.1091425 -0.01940912 -0.9956946 -0.09064102 5.48644e-4 -0.9953953 -0.0958535 -0.1271991 -0.9843412 -0.122036 -0.108784 -0.987158 -0.1169847 -0.1107766 -0.9869171 -0.1171453 -0.0894069 -0.9898434 -0.1105284 -0.06180649 -0.9925253 -0.1052305 -0.0667814 -0.992093 -0.1062624 -0.04803448 -0.993362 -0.1045219 -0.01862823 -0.9948028 -0.1001027 -0.1094109 -0.9901359 -0.08752286 -0.0996527 -0.9917462 -0.08067786 -0.1011174 -0.9914927 -0.08196109 -0.1588382 -0.9842943 -0.07704102 -0.2437542 -0.9678144 -0.06260466 -0.3440393 -0.937668 -0.04915058 -0.3547168 -0.9337599 -0.04762822 -0.3932436 -0.9185996 -0.03917032 -0.405384 -0.9127367 -0.05075275 -0.5128709 -0.8583638 -0.01323443 -0.4511972 -0.8918662 -0.03156036 -0.4030677 -0.9144355 -0.03666502 -0.9004416 -0.4349744 0.001503705 -0.8617203 -0.5073681 -0.003981113 -0.9740055 -0.2263248 0.009511947 -0.9897875 -0.1419186 0.01341986 -0.9909306 -0.1331481 0.01811349 -0.9973552 -0.07190662 0.01058471 -0.9945716 0.1037344 0.00816071 -0.9683883 0.2492695 0.009422659 -0.9651733 0.261509 0.007328331 -0.9423553 0.3345412 0.006980597 -0.9443843 0.3287453 0.008057236 -0.9454275 0.3231325 0.04186129 -0.9386044 0.3418529 0.04646068 -0.9440249 0.3257339 0.05210107 -0.9205596 0.3716879 0.1200761 -0.9551212 0.2818028 0.09127223 -0.9198304 0.3533356 0.1704875 -0.9268479 0.3035123 0.2209826 -0.9204003 0.3151241 0.2314308 -0.8984884 0.2959287 0.3242602 -0.9006671 0.2746958 0.3366618 -0.9061644 0.3217545 0.2744818 -0.8069018 0.26502 0.5278957 -0.8231729 0.2935039 0.4860473 -0.8564991 0.2859076 0.4297283 -0.85689 0.2633461 0.4431573 -0.868317 0.2959849 0.3980185 -0.6910855 0.1763879 0.7009195 -0.6686148 0.3094053 0.6761825 -0.6618379 0.2205179 0.7164792 -0.6894012 0.2683189 0.6728529 -0.7024675 0.2808293 0.6539683 -0.7252113 0.2794915 0.629248 -0.3627578 0.223645 0.904649 -0.2750725 0.2094737 0.9383261 -0.1208552 0.1412485 0.9825696 -0.9963811 0.05608612 0.06386721 -0.9979233 -0.017053 0.06211584 -0.9891569 -0.03005546 0.1437546 -0.9893788 -0.03615736 0.1407918 -0.9658291 -0.0540533 0.2534807 -0.9663648 -0.06125456 0.2497738 -0.9673369 0.01616883 0.2529785 -0.9689724 0.02611291 0.2457861 -0.9891795 0.03187751 0.1432055 -0.9896828 0.03972309 0.1376591 -0.9973106 0.04383403 0.05873924 -0.9307008 -0.07794553 0.35738 -0.9316393 -0.08589917 0.3530859 -0.933919 0.002025246 0.3574789 -0.8995497 -0.002806127 0.4368094 -0.8917012 0.03365361 0.4513719 -0.8399458 0.02904802 0.5418925 -0.8378893 0.03602021 0.5446504 -0.7783716 0.0309143 0.6270422 -0.8312088 -0.1224676 0.5423042 -0.8326184 -0.1290985 0.538591 -0.7682663 -0.1414694 0.6243023 -0.7696979 -0.1469349 0.6212691 -0.8856714 -0.1011083 0.4531705 -0.8869026 -0.1086132 0.4490067 -0.8901181 -0.04883325 0.4531061 -0.836955 -0.05584257 0.5444152 -0.839309 -0.06623089 0.5396054 -0.7746427 -0.07249999 0.6282298 -0.7771407 -0.08171248 0.6239995 -0.7754915 0.03882062 0.6301634 -0.7652472 0.1815332 0.6176103 -0.7610724 0.1708962 0.6257503 -0.7473493 0.256142 0.6130746 -0.7506291 0.2670732 0.604341 -0.9934839 -0.09243744 0.06667369 -0.970521 -0.2354379 0.05155616 -0.968248 -0.2438871 0.05490893 -0.9681588 -0.2441542 0.05529272 -0.9656282 -0.2531983 0.05876004 -0.9466152 -0.2983191 0.1221694 -0.9821593 -0.179938 0.05463916 -0.9805366 -0.1875228 0.05816495 -0.9804291 -0.1878949 0.05877435 -0.9785486 -0.1962741 0.0626049 -0.9632442 -0.2361789 0.1279851 -0.9591119 -0.2496412 0.1333561 -0.9247225 -0.3054589 0.2271196 -0.9933122 -0.09573692 0.06453949 -0.9820507 -0.1241372 0.1420089 -0.9818751 -0.1294125 0.1384692 -0.9536488 -0.1689071 0.249047 -0.9536955 -0.1744417 0.2450206 -0.9134753 -0.2101073 0.3484507 -0.9137815 -0.2149149 0.3446955 -0.864621 -0.2462221 0.4379557 -0.8650432 -0.2495435 0.4352337 -0.807527 -0.2774516 0.5205005 -0.807946 -0.2795386 0.5187308 -0.9422156 -0.310425 0.1259605 -0.9017229 -0.3740934 0.2166801 -0.9191003 -0.3183394 0.2321956 -0.8797374 -0.3620936 0.3081402 -0.880513 -0.3481412 0.3217059 -0.8256706 -0.3917582 0.4059479 -0.8257761 -0.3955708 0.402017 -0.7643231 -0.4335063 0.4773706 -0.7645922 -0.4359694 0.474689 -0.6979045 -0.4687361 0.5414941 -0.6981747 -0.4701194 0.5399444 -0.7435489 -0.3052475 0.5949446 -0.7432553 -0.3041829 0.595856 -0.7234672 -0.3885269 0.5706507 -0.8418679 -0.4471492 0.3021854 -0.7869325 -0.4931352 0.370884 -0.7836482 -0.4975693 0.3719142 -0.7227197 -0.5381249 0.4337025 -0.7209755 -0.5401625 0.4340724 -0.6552053 -0.5756638 0.4892008 -0.8965398 -0.3846046 0.2197629 -0.8465979 -0.4395449 0.3001209 -0.8592294 -0.4058369 0.3114825 -0.8036521 -0.4517716 0.3873576 -0.8034297 -0.4552243 0.3837597 -0.7404467 -0.4963226 0.4532138 -0.7404603 -0.4984364 0.4508656 -0.673249 -0.5336745 0.5117884 -0.673348 -0.5347446 0.5105398 -0.9578437 -0.2831907 0.04835844 -0.9552951 -0.2911612 0.05134695 -0.9551787 -0.2914699 0.05175942 -0.9522358 -0.3003755 0.05496913 -0.9306872 -0.3469025 0.1161038 -0.9255925 -0.3591308 0.1195985 -0.8815799 -0.4243805 0.2066836 -0.8760042 -0.4345039 0.2093394 -0.8236343 -0.4900103 0.2855108 -0.8189272 -0.4968931 0.2871509 -0.7630473 -0.542575 0.3512427 -0.7599294 -0.5464449 0.3520019 -0.6989369 -0.5864891 0.4092895 -0.9943401 -0.08660531 0.06154173 -0.9941757 -0.08983749 0.05953013 -0.9976188 -0.02767097 0.06317615 -0.9973527 -0.0220189 0.06930273 -0.9971694 -0.05336803 0.05296397 -0.9866551 -0.07661962 0.1436706 -0.9866693 -0.08236557 0.1403552 -0.9612472 -0.1105627 0.2525466 -0.9615252 -0.1169289 0.2485902 -0.9239876 -0.1427947 0.3547631 -0.9245527 -0.1488139 0.3507945 -0.8773377 -0.1719769 0.4479985 -0.8780306 -0.1765821 0.4448384 -0.8217875 -0.1974898 0.5344748 -0.8225007 -0.2008537 0.5321187 -0.7583073 -0.2195174 0.6138259 -0.7589417 -0.2218086 0.6122161 -0.05855762 0.0727508 0.9956296 -0.1427814 0.07713776 0.9867438 -0.1468226 -0.02783554 0.9887712 -0.1431135 -0.02045297 0.989495 -0.1427124 -0.1123589 0.983366 -0.1431531 -0.1132258 0.9832025 -0.141412 -0.1967182 0.9702086 -0.1418835 -0.1975601 0.9699687 -0.1389915 -0.293592 0.9457723 -0.1392919 -0.2940331 0.945591 -0.13503 -0.3937296 0.9092546 -0.1355374 -0.3944472 0.9088681 -0.1299456 -0.4916557 0.8610394 -0.1305231 -0.4924064 0.8605229 -0.123642 -0.5847941 0.8017036 -0.1241816 -0.5854883 0.8011133 -0.117675 -0.6556407 0.7458472 -0.9305768 -0.364051 0.03865015 -0.9012078 -0.4328731 0.02110391 -0.8989267 -0.4373121 0.02625244 -0.8954145 -0.4443207 0.02849411 -0.8951313 -0.4448529 0.02908647 -0.8905752 -0.453727 0.03174483 -0.8613678 -0.5010457 0.0836597 -0.8536297 -0.5136735 0.08634883 -0.8002589 -0.5782263 0.1588717 -0.03094822 -0.9888023 0.1459872 -0.01081216 -0.9903817 0.137939 -0.05796778 -0.9889809 0.1362229 -0.06501698 -0.9777578 0.1994054 -0.06467348 -0.9778161 0.1992315 -0.07170534 -0.9623436 0.2622081 -0.07114577 -0.962464 0.2619187 -0.07808041 -0.9428458 0.3239529 -0.07735961 -0.9430364 0.3235706 -0.08421617 -0.9191414 0.3848204 -0.08334934 -0.9194149 0.3843556 -0.09009039 -0.8912774 0.444419 -0.08912473 -0.891635 0.4438962 -0.09564632 -0.8596622 0.5018295 -0.09459102 -0.8601084 0.5012646 -0.1009196 -0.8242508 0.5571588 -0.09980279 -0.8247843 0.55657 -0.1059234 -0.7850362 0.6103265 -0.1047782 -0.7856491 0.6097353 -0.1106031 -0.742704 0.6604224 -0.1093954 -0.7434145 0.659824 -0.1149187 -0.6974276 0.7073815 -0.1136323 -0.6982601 0.7067677 -0.1181709 -0.6563226 0.7451687 -0.4700909 -0.875794 -0.1095417 -0.4637249 -0.8797232 -0.105102 -0.5311713 -0.845166 -0.05959457 -0.5344583 -0.8418692 -0.07490378 -0.5934832 -0.8041224 -0.03413099 -0.5956333 -0.8018208 -0.04800474 -0.6432591 -0.7655104 -0.01454859 -0.5908383 -0.8063444 0.02681016 -0.6300154 -0.774366 0.05863517 -0.5766924 -0.81114 0.09735447 -0.6152872 -0.7771272 0.1322686 -0.5638318 -0.8088383 0.1669563 -0.6003662 -0.7731587 0.204416 -0.5454304 -0.8033916 0.2388882 -0.5794584 -0.7659327 0.2785234 -0.5208798 -0.7943599 0.3125329 -0.5518092 -0.7552736 0.3536503 -0.489355 -0.7815751 0.386875 -0.5170753 -0.7405035 0.4292876 -0.4503529 -0.7643992 0.4613853 -0.4746544 -0.7210723 0.5047355 -0.4031717 -0.7422862 0.5352233 -0.4235169 -0.6972107 0.5783863 -0.3467493 -0.7154213 0.6065785 -0.3631465 -0.6683338 0.6491954 -0.2807705 -0.6831492 0.6741477 -0.2914482 -0.6412491 0.7098292 -0.2908604 -0.6402096 0.7110077 -0.3059664 -0.5711514 0.7616894 -0.3053233 -0.5701721 0.7626806 -0.321305 -0.4795922 0.8165505 -0.3205307 -0.4784232 0.8175399 -0.3334698 -0.3834522 0.8612563 -0.3327746 -0.3823452 0.862017 -0.3426047 -0.2851361 0.8951646 -0.3423164 -0.2846078 0.8954429 -0.3487617 -0.1939866 0.9169158 -0.3485406 -0.1935278 0.9170968 -0.3523918 -0.1141817 0.9288609 -0.3524177 -0.1142447 0.9288433 -0.3539918 0.00911957 0.9352042 -0.3579257 0.002102315 0.9337478 -0.3513057 0.1280978 0.9274563 -0.2609219 0.1170187 0.9582414 -0.2563142 0.1826627 0.9491773 -0.2307421 0.2012833 0.951968 -0.4850581 -0.8676806 -0.1088536 -0.503864 -0.8549357 -0.1233134 -0.5768688 -0.812434 -0.08469575 -0.5791146 -0.8094502 -0.09704065 -0.6400644 -0.7656343 -0.06420058 -0.6413354 -0.7636198 -0.07465928 -0.6917493 -0.7205976 -0.04713904 -0.6592784 -0.7517119 -0.0167787 -0.6960167 -0.7179594 0.00975883 -0.6406982 -0.7656231 0.05768281 -0.676995 -0.730761 0.08755683 -0.6210433 -0.7725949 0.1319178 -0.657202 -0.7354719 0.1648237 -0.6033244 -0.770874 0.2043358 -0.6376652 -0.732104 0.2395973 -0.5803734 -0.7652371 0.27853 -0.6122151 -0.725006 0.3155298 -0.551318 -0.755641 0.3536316 -0.580474 -0.7136099 0.3921873 -0.515682 -0.7415361 0.4291811 -0.5418838 -0.6974515 0.4689601 -0.472697 -0.7225129 0.5045124 -0.4953129 -0.6769487 0.5444316 -0.4211689 -0.698934 0.5780207 -0.440176 -0.6516112 0.6177767 -0.3605692 -0.6702265 0.6486805 -0.3737612 -0.6283063 0.6823004 -0.3733123 -0.627362 0.6834142 -0.3918484 -0.5588072 0.7308826 -0.391353 -0.5579336 0.7318148 -0.4109035 -0.4684638 0.7821127 -0.4102441 -0.4673786 0.7831074 -0.4260638 -0.3738467 0.8238376 -0.4254835 -0.3728401 0.8245933 -0.4374636 -0.2772702 0.855422 -0.4373101 -0.2769646 0.8555995 -0.4450528 -0.1890618 0.8753193 -0.4452481 -0.1894661 0.8751325 -0.4498022 -0.1117726 0.8861067 -0.4504996 -0.1133702 0.8855491 -0.4524423 0.02133423 0.8915386 -0.4547942 0.01711809 0.8904321 -0.4469739 0.1536424 0.8812538 -0.3601331 0.141946 0.9220388 -0.3545575 0.2061526 0.9120253 -0.31582 0.22338 0.9221493 -0.4184708 -0.9081708 -0.01040619 -0.4218064 -0.9065005 -0.01833838 -0.4728298 -0.8807452 0.02683126 -0.358961 -0.9312485 -0.06263649 -0.3179026 -0.9466146 -0.05346775 -0.3177017 -0.946692 -0.0532903 -0.217028 -0.9741572 -0.06258356 -0.2805958 -0.9556545 -0.08939039 -0.2708396 -0.9597283 -0.07461631 -0.3334885 -0.9365499 -0.1079801 -0.3297114 -0.9383251 -0.1040986 -0.5177829 -0.8459393 0.1276233 -0.477481 -0.8743685 0.08655446 -0.4721332 -0.8772745 0.08648532 -0.4284031 -0.9026041 0.04215252 -0.382493 -0.9217323 0.06409949 -0.3393834 -0.940542 0.0141372 -0.2993343 -0.9536725 0.03013366 -0.2515738 -0.9672566 -0.0335471 -0.1441544 -0.9808985 -0.1306049 -0.1191188 -0.9867424 -0.1102278 -0.1171327 -0.9867663 -0.1121263 -0.09478569 -0.9912213 -0.09217357 -0.386255 -0.7816955 0.4896522 -0.3636067 -0.8207156 0.4406995 -0.3660237 -0.8193401 0.441258 -0.3424609 -0.8547546 0.3900197 -0.3447251 -0.8535893 0.3905763 -0.3202175 -0.8853618 0.3370389 -0.3222008 -0.8844484 0.3375468 -0.2970933 -0.9120935 0.2825262 -0.2986818 -0.9114464 0.2829395 -0.2731477 -0.934841 0.2268537 -0.274166 -0.934478 0.2271211 -0.2481785 -0.9536904 0.1699477 -0.2484217 -0.9536156 0.170012 -0.2221812 -0.9685254 0.1122232 -0.1821507 -0.9758117 0.1208835 -0.1602938 -0.9851775 0.06108379 -0.1240449 -0.9900107 0.06702017 -0.4887923 -0.8299272 0.2688922 -0.4546798 -0.8622135 0.2232807 -0.4544383 -0.862347 0.2232562 -0.4192107 -0.8906456 0.1761051 -0.4182789 -0.8911032 0.1760055 -0.381968 -0.915351 0.1274099 -0.3800041 -0.9161978 0.1271946 -0.3422572 -0.9364679 0.07673358 -0.3005255 -0.9493374 0.09188592 -0.2655388 -0.9633713 0.03748178 -0.2285664 -0.9723181 0.04852819 -0.1914005 -0.9813173 -0.01955568 -0.5212516 -0.8512104 0.06113606 -0.4752376 -0.8796262 0.0201779 -0.4262405 -0.9033938 0.04689413 -0.3791636 -0.9253295 -6.94315e-4 -0.3366219 -0.9414548 0.01867687 -0.2859929 -0.9574046 -0.03980994 -0.2542936 -0.9664758 -0.03548842 -0.2254039 -0.9715688 -0.0724371 -0.1682347 -0.9842725 -0.05389499 -0.506911 -0.8391682 0.1970738 -0.4696504 -0.8693788 0.1536526 -0.4673361 -0.8706478 0.1535237 -0.4286538 -0.8969287 0.1085121 -0.4252458 -0.8985747 0.1083039 -0.3843063 -0.9212016 0.0607981 -0.3408165 -0.936807 0.07897466 -0.3017286 -0.9530192 0.02672791 -0.2635122 -0.963826 0.04001051 -0.2223115 -0.9746802 -0.02400338 -0.1967056 -0.9802016 -0.02262437 -0.1750434 -0.9827107 -0.0603286 -0.1210501 -0.9915041 -0.04760915 -0.3342827 -0.7566899 0.56185 -0.3157914 -0.7984271 0.5126305 -0.3182624 -0.7969991 0.513324 -0.2990474 -0.8350612 0.4617831 -0.3014593 -0.8337962 0.4625 -0.2815433 -0.8681275 0.4087641 -0.2838109 -0.8670569 0.4094676 -0.2631609 -0.8976538 0.3535028 -0.2651531 -0.8968178 0.3541353 -0.2440693 -0.9232192 0.296811 -0.2456982 -0.9226183 0.2973345 -0.2243161 -0.9447389 0.2390624 -0.2254603 -0.9443744 0.2394261 -0.2037451 -0.9623051 0.1801579 -0.2042363 -0.9621726 0.1803099 -0.1824002 -0.975794 0.1206489 -0.1419088 -0.9816259 0.1275637 -0.1247953 -0.9899566 0.06642526 -0.0879805 -0.9935977 0.07087469 -0.272362 -0.7267155 0.6306374 -0.258378 -0.7707109 0.5824479 -0.2606464 -0.7693675 0.5832127 -0.2458881 -0.8103615 0.5318396 -0.2481413 -0.8091474 0.5326412 -0.2328409 -0.8463577 0.4790239 -0.2350212 -0.8452985 0.4798285 -0.2192116 -0.8786838 0.4241003 -0.2212271 -0.8778102 0.4248622 -0.2048723 -0.9073927 0.3669685 -0.2066557 -0.9067106 0.3676539 -0.1899936 -0.9320604 0.3084898 -0.1914772 -0.931568 0.3090593 -0.1746063 -0.9526236 0.24904 -0.1756984 -0.9523144 0.2494542 -0.1585885 -0.9691855 0.1884921 -0.159156 -0.9690517 0.1887013 -0.1419975 -0.9816228 0.1274886 -0.100636 -0.9860339 0.1327016 -0.08847337 -0.993579 0.07052153 -0.05075371 -0.9960055 0.0734651 -0.2004156 -0.6911106 0.6944061 -0.1908676 -0.737532 0.6477778 -0.1927682 -0.7363683 0.6485386 -0.182698 -0.779833 0.5987336 -0.1845229 -0.7788112 0.5995035 -0.17392 -0.819138 0.5465938 -0.1756941 -0.818243 0.5473666 -0.1647295 -0.8547057 0.4922828 -0.1664337 -0.8539354 0.4930458 -0.1551147 -0.8865319 0.4358906 -0.156705 -0.8858973 0.4366115 -0.1450127 -0.9146562 0.3773268 -0.1464017 -0.9141733 0.3779602 -0.1345027 -0.9386799 0.3174729 -0.1356716 -0.9383319 0.3180038 -0.1236383 -0.9585477 0.2567102 -0.1245251 -0.9583269 0.2571054 -0.1123277 -0.9743709 0.1948944 -0.1128367 -0.974268 0.1951153 -0.1006117 -0.9860346 0.1327143 -0.05802887 -0.9889827 0.1361833 -0.05101877 -0.9960042 0.0733 -0.02476847 -0.9969332 0.07423388 -0.4290215 -0.8017305 0.4161356 -0.4023529 -0.838324 0.3678655 -0.4043449 -0.8372035 0.3682331 -0.3764806 -0.8702957 0.3175657 -0.3781955 -0.8694274 0.3179059 -0.3495302 -0.8984838 0.2656232 -0.3508147 -0.8979051 0.2658866 -0.3215468 -0.9227666 0.2123904 -0.3222216 -0.9224987 0.2125309 -0.2923437 -0.9431964 0.1578472 -0.2921253 -0.9432715 0.1578025 -0.2617586 -0.9597084 0.1021878 -0.2217046 -0.9685764 0.1127251 -0.1953065 -0.9792261 0.05451333 -0.1592644 -0.9852877 0.06199228 -0.1331025 -0.9910558 -0.009601175 -0.1038637 -0.9945785 -0.005106449 -0.1001342 -0.9949588 -0.005515038 -0.07363075 -0.9972825 -0.002515196 -0.07113116 -0.9974628 -0.002895236 -0.04247879 -0.9990971 -8.02816e-4 -0.4630777 -0.8175427 0.34232 -0.4324366 -0.852059 0.2949478 -0.4335612 -0.8514321 0.295107 -0.4018658 -0.8820466 0.2459628 -0.4025766 -0.8816921 0.2460715 -0.3700488 -0.9081973 0.1955545 -0.3700856 -0.9081808 0.1955615 -0.3367432 -0.9305605 0.1437402 -0.335815 -0.9309182 0.1435955 -0.3016045 -0.9491356 0.09042352 -0.2610052 -0.9598179 0.1030829 -0.2302369 -0.9720143 0.0466817 -0.1939645 -0.9794183 0.05583554 -0.1628496 -0.986568 -0.01278495 -0.1412245 -0.9898874 -0.01337116 -0.1261471 -0.9906724 -0.05152821 -0.08922159 -0.9949528 -0.04591768 -0.072025 -0.9962751 -0.04741692 -0.06327503 -0.997003 -0.04451352 -0.03665584 -0.9984197 -0.04259979 -0.04112249 -0.9991536 -0.001070082 -0.01333367 -0.9999112 -1.5908e-4 -0.01498997 -0.9987662 0.04734498 -0.01349186 -0.9937992 -0.1103689 -0.01316154 -0.9930702 -0.1167837 -0.0387519 -0.9921827 -0.118625 -0.0526278 -0.9915906 -0.1182311 -0.06291472 -0.990803 -0.1197966 -0.6690116 -0.7416449 -0.0488494 -0.6833171 -0.7279033 -0.05687439 -0.6771072 -0.7348961 -0.03812617 -0.6880986 -0.7241932 -0.04543781 -0.6837688 -0.7292232 -0.02634012 -0.6912118 -0.7219348 -0.0321955 -0.6893714 -0.7241847 -0.01799273 -0.5970073 -0.8021953 0.008079171 -0.5039896 -0.860496 -0.07443851 -0.5003871 -0.864481 -0.04780727 -0.4890947 -0.8714156 -0.03770136 -0.4970189 -0.8650314 -0.06850457 -0.4799908 -0.8755131 -0.05554848 -0.4917724 -0.8663787 -0.08688002 -0.632953 -0.7737912 -0.024854 -0.5914415 -0.8063237 -0.006274938 -0.5967116 -0.8013325 -0.04244476 -0.5854974 -0.8099886 -0.03333574 -0.5922363 -0.8034798 -0.06063389 -0.5754896 -0.8163298 -0.04916793 -0.5855233 -0.8070058 -0.07683861 -0.5635568 -0.8235749 -0.06425237 -0.5680103 -0.8197627 -0.07316809 -0.621903 -0.7793337 -0.07665425 -0.6016395 -0.792804 -0.09742641 -0.6774214 -0.7331305 -0.06016677 -0.6611464 -0.746322 -0.07674032 -0.4540119 0.2281391 0.8612931 -0.441889 0.2504029 0.8614131 -0.4516094 0.1614956 0.8774783 -0.5361464 0.1728059 0.8262477 -0.5450474 0.02894014 0.8379058 -0.54475 0.02950024 0.8380795 -0.5426764 -0.1100582 0.8327002 -0.5412588 -0.1065461 0.8340786 -0.5362224 -0.1830384 0.8239918 -0.5355904 -0.1815032 0.8247421 -0.5269005 -0.2670461 0.8068842 -0.5268496 -0.2669543 0.806948 -0.5132581 -0.36059 0.7788075 -0.5136415 -0.361354 0.7782004 -0.4956516 -0.453158 0.7409301 -0.4960833 -0.4539821 0.7401363 -0.4737573 -0.5421869 0.6939651 -0.474044 -0.5427695 0.6933135 -0.4527758 -0.6108013 0.6495505 -0.4530465 -0.6115065 0.6486979 -0.4378143 -0.6534687 0.6174928 -0.514424 -0.6309782 0.5807191 -0.4934644 -0.6784176 0.5442817 -0.5648636 -0.6524614 0.5051963 -0.540694 -0.6984091 0.468908 -0.6074539 -0.6691692 0.4280331 -0.5801414 -0.7138833 0.3921819 -0.6428092 -0.6814484 0.3498921 -0.6130987 -0.7242668 0.3155117 -0.6720979 -0.688678 0.2720424 -0.6403501 -0.7298042 0.2394528 -0.6958939 -0.6911628 0.1950018 -0.6624104 -0.7308847 0.1643778 -0.7198009 -0.6846967 0.1143553 -0.6863979 -0.7220606 0.086524 -0.7430256 -0.66849 0.03215891 -0.7097691 -0.7043935 0.007601976 -0.7435062 -0.6681599 -0.02758586 -0.7031167 -0.7093014 -0.05018419 -0.7021112 -0.7103706 -0.04912871 -0.6516596 -0.7547818 -0.07512992 -0.6509281 -0.7562396 -0.06628948 -0.5909156 -0.8009 -0.09684044 -0.5894168 -0.8032451 -0.08593761 -0.5158684 -0.8478293 -0.1227416 -0.5192977 -0.845306 -0.1256497 -0.4446226 -0.8897979 -0.1028127 -0.4570089 -0.8816401 -0.1177018 -0.4752434 -0.8758258 -0.0841012 -0.4692347 -0.8800985 -0.07242548 -0.3992704 -0.9120738 -0.09329754 -0.3856101 -0.9207916 -0.05871647 -0.3118697 -0.9471907 -0.07461285 -0.3024265 -0.9522122 -0.04278129 -0.2978876 -0.9530149 -0.05500692 -0.1220934 -0.9855161 -0.1176915 -0.1520608 -0.9801214 -0.1274346 -0.1373815 -0.9837822 -0.1153208 -0.185234 -0.973306 -0.1355137 -0.1680919 -0.9786533 -0.1182492 -0.2267314 -0.9624562 -0.1492351 -0.2063844 -0.9706174 -0.1237232 -0.2619359 -0.9517475 -0.159895 -0.2411491 -0.9618883 -0.1289104 -0.2734401 -0.9494937 -0.1539227 -0.2721386 -0.9555675 -0.1132761 -0.2857812 -0.9496197 -0.1286538 -0.2944516 -0.9513548 -0.09067672 -0.1632778 -0.977876 -0.1307629 -0.1593657 -0.9788965 -0.1279233 -0.1412943 -0.9856162 -0.09271866 -0.1544446 -0.9822703 -0.1062643 -0.1469232 -0.9864344 -0.07321816 -0.1355565 -0.9892097 -0.0555756 -0.1169194 -0.9853513 -0.1241489 -0.08633583 -0.9888866 -0.1210356 -0.0750209 -0.9901322 -0.1183645 -0.08394402 -0.9887918 -0.1234679 -0.1238358 -0.9829041 -0.1362507 -0.1050983 -0.9867852 -0.123327 -0.1483126 -0.9788089 -0.1411974 -0.1264211 -0.9843167 -0.1230382 -0.1771343 -0.9728217 -0.1491355 -0.1515186 -0.9807114 -0.1234798 -0.2014864 -0.9671765 -0.154832 -0.1741585 -0.9770349 -0.1227672 -0.2078695 -0.9669116 -0.1478933 -0.1974452 -0.9745603 -0.1060555 -0.2127618 -0.9693916 -0.1225253 -0.2137111 -0.9733511 -0.08315914 -0.2023529 -0.9771947 -0.06437361 -0.1898001 -0.9792904 -0.07047146 -0.2111122 -0.9772064 -0.02234989 -0.2337371 -0.9690589 -0.07932162 -0.3001449 -0.9517994 -0.06317454 -0.2990042 -0.949128 -0.09875583 -0.3765674 -0.9232091 -0.07669454 -0.3840855 -0.918826 -0.09075915 -0.3701409 -0.9205069 -0.1251509 -0.3581135 -0.9270509 -0.1110467 -0.3520823 -0.9241728 -0.148131 -0.3221297 -0.9384979 -0.1243159 -0.3362991 -0.9293408 -0.1524098 -0.2742765 -0.9552009 -0.1111926 -0.2888894 -0.9478104 -0.1349024 -0.2201401 -0.9705142 -0.09818696 -0.2324089 -0.9659838 -0.113408 -0.1780962 -0.9798551 -0.09036457 -0.1885728 -0.9768739 -0.1007857 -0.1390987 -0.986656 -0.08462649 -0.1476421 -0.9847945 -0.09155189 -0.1006692 -0.9916644 -0.08042067 -0.1071174 -0.9906321 -0.08469963 -0.06089437 -0.9951203 -0.07763743 -0.06496721 -0.9946888 -0.07983577 -0.02947223 -0.9965724 -0.07729673 -0.01224315 -0.9975799 -0.06844383 -0.9988927 -0.03565067 0.0306977 -0.9991405 -0.01608079 0.03820621 -0.994617 -0.0986796 0.03161424 -0.9972468 0.07376182 0.007628381 -0.9994958 0.03047341 0.008922517 -0.9993395 0.02885359 0.02209502 -0.9985332 -0.05099755 0.01819169 -0.9979671 -0.05464845 0.03279203 -0.9861677 -0.1640681 0.02355951 -0.9844896 -0.1704056 0.04173886 -0.9534409 -0.3006665 0.02345597 -0.9391348 0.3430476 0.01855474 -0.939671 0.3415862 0.01836353 -0.9719819 0.23425 0.01944935 -0.9681078 0.2495385 0.02231585 -0.9922443 0.1223618 0.02188491 -0.9874975 0.1552239 0.02746587 -0.9970841 0.07180505 0.02583569 -0.9965598 0.07808941 0.02776122 -0.9996343 -0.01243823 0.02401244 -0.960052 -0.2785068 0.02709394 -0.9613491 -0.2749868 0.01379603 -0.9632956 -0.2677296 0.01955711 -0.9632183 -0.2679173 0.02076005 -0.9556627 -0.2943431 0.008425474 -0.9108299 -0.4124187 0.01731544 -0.9125555 -0.4088723 0.008130669 -0.9148461 -0.4035591 0.01402968 -0.9159314 -0.4012931 0.005796313 -0.9178295 -0.3968511 0.009909152 -0.9184183 -0.395604 0.002305269 -0.9276965 -0.3724851 0.02518713 -0.9758073 0.2184619 0.008640646 -0.9845446 0.1749255 0.008541285 -0.9878087 0.1552517 0.01144343 -0.9934328 0.1138892 0.01098209 -0.9967132 0.07878154 0.01887714 -0.999802 0.01074761 0.0167523 -0.9994908 0.007982075 0.03089642 -0.9969163 -0.07423514 0.02543866 -0.996067 -0.07910472 0.03991246 -0.9825158 -0.1838945 0.02908033 -0.8710712 0.2150831 0.4415589 -0.9203981 0.2076707 0.3312709 -0.9120575 0.2311214 0.3387242 -0.9489097 0.2208831 0.2253465 -0.940696 0.2454962 0.2341424 -0.9634328 0.2359936 0.1269034 -0.9604167 0.2460694 0.1305749 -0.9694266 0.2393215 0.0541979 -0.9680191 0.2447116 0.05527406 -0.9688794 0.2436968 0.04341208 -0.9753904 0.216659 0.04089534 -0.9954704 -0.07895445 0.05296313 -0.9951599 -0.08326244 0.05219435 -0.9983716 -0.001012265 0.05703729 -0.9983751 -0.02527189 0.05107432 -0.9947797 0.08672928 0.05377238 -0.997249 0.05676662 0.04766708 -0.9868714 0.1542124 0.04799234 -0.986221 0.1545974 0.05888867 -0.9880115 0.1436661 0.05651128 -0.9796987 0.1462427 0.1371266 -0.9814811 0.1373196 0.1335601 -0.9593565 0.1405622 0.2446985 -0.9631457 0.1246203 0.2383698 -0.9285514 0.1277643 0.3485234 -0.9310992 0.1183079 0.3450469 -0.8864858 0.118811 0.4472436 -0.8845127 0.1253473 0.4493612 -0.8331535 0.123297 0.5391226 -0.8002127 0.2104922 0.5615627 -0.8241492 0.1729551 0.5393188 -0.8070656 0.2663581 0.5269712 -0.7710239 0.2926253 0.5655906 -0.9999867 0.004358053 0.002784729 -0.9994024 -0.0324406 0.01194518 -0.9991316 -0.03425216 0.02372562 -0.9891451 -0.1459655 0.01692026 -0.9880121 -0.1504479 0.03460568 -0.9577271 -0.2870416 0.01913332 -0.9558218 -0.2921022 0.03287982 -0.9084643 -0.4178421 0.01003926 -0.9076871 -0.4194386 0.0132507 -0.8841021 -0.467182 0.01021933 -0.8811053 -0.4725838 0.01783347 -0.9496076 -0.3100312 0.04611039 -0.9242849 -0.380489 0.03042268 -0.9223079 -0.3848031 0.03570431 -0.9191665 -0.3920193 0.03813117 -0.9189456 -0.3924834 0.03867638 -0.915005 -0.401304 0.04148471 -0.8882505 -0.4490399 0.0968213 -0.8814663 -0.4615858 0.09977757 -0.8308504 -0.5273775 0.1776532 -0.8243802 -0.5367933 0.1795834 -0.7681429 -0.5911169 0.2460435 -0.8392031 -0.5438173 0.001006245 -0.8422009 -0.5391492 -0.003984034 -0.8499901 -0.5267783 0.004631817 -0.8541836 -0.5199502 -0.004739403 -0.8472135 -0.5311325 -0.01129555 -0.846765 -0.5318762 -0.009847044 -0.849287 -0.5279227 -0.003044605 -0.850486 -0.5259355 -0.008086442 -0.8529076 -0.5220549 -0.002744197 -0.8534274 -0.5211786 -0.005888938 -0.8554159 -0.517937 -0.002261161 -0.8546571 -0.5191661 0.005271255 -0.7814832 -0.6235728 -0.02099901 -0.8342379 -0.5513932 0.003562986 -0.8345285 -0.550956 0.003116548 -0.8020009 -0.5971405 -0.01475703 -0.8053829 -0.5924288 -0.01966059 -0.8142942 -0.5803637 -0.0101456 -0.8170449 -0.5763643 -0.01555603 -0.9357128 0.3512265 0.03288978 -0.9428547 0.3318688 0.02980262 -0.9758442 0.2161842 0.03150361 -0.9714012 0.2348275 0.03515404 -0.995586 0.08721059 0.03468453 -0.9916554 0.1221497 0.0412212 -0.9992607 0.002133071 0.03838878 -0.9983015 0.03627437 0.04558807 -0.9964812 -0.07394683 0.03946167 -0.9980126 -0.04090952 0.04793268 -0.9891498 -0.141768 0.03853076 -0.993183 -0.1057878 0.04895281 -0.9746649 -0.2209546 0.03474634 -0.979879 -0.1931469 0.05031466 -0.9530202 -0.3012056 0.03206211 -0.9521211 -0.3041543 0.03091382 -0.9332937 -0.3579153 0.02932077 -0.9117645 -0.4103375 0.01757442 -0.9078316 -0.4183176 0.02919703 -0.874036 -0.4857655 0.009653449 -0.871409 -0.4903364 0.01471692 -0.8674122 -0.4973049 0.01684778 -0.8670935 -0.497841 0.01742035 -0.8617773 -0.5068927 0.01999437 -0.8304724 -0.5528752 0.06815147 -0.7231993 -0.3874926 0.5716927 -0.7888305 -0.3582154 0.4994279 -0.7884785 -0.3561576 0.5014513 -0.8478295 -0.3226289 0.4208274 -0.8475224 -0.3192961 0.4239763 -0.8993049 -0.2812085 0.3349217 -0.8991892 -0.276378 0.3392256 -0.9429013 -0.2321172 0.2388699 -0.9430924 -0.2262936 0.2436559 -0.9750084 -0.1764664 0.1349748 -0.9754294 -0.1706796 0.1393054 -0.9889058 -0.1345666 0.06290733 -0.9891986 -0.1312625 0.06524127 -0.9900713 -0.1279469 0.05820995 -0.9903396 -0.1248654 0.06030082 -0.9911383 -0.1216451 0.05336016 -0.9832553 -0.1758628 0.04776436 -0.9869387 -0.1509661 0.05622607 -0.9718558 -0.2311818 0.0452916 -0.9725843 -0.2278506 0.04652023 -0.9582772 -0.2819997 0.04670035 -0.943641 -0.328825 0.03762739 -0.9419191 -0.3330606 0.04311817 -0.9390987 -0.340583 0.04579228 -0.9389364 -0.3409659 0.04626768 -0.9355242 -0.3498104 0.04926568 -0.9113782 -0.3972281 0.1077023 -0.905478 -0.4096388 0.1109313 -0.8580642 -0.4756073 0.1937099 -0.8520392 -0.4854024 0.1959946 -0.7975534 -0.5406956 0.2675012 -0.792845 -0.5469431 0.2687939 -0.7363606 -0.591718 0.3280898 -0.5925732 0.2720404 0.7581893 -0.6064247 0.2510805 0.7544586 -0.6162264 0.1781885 0.7671467 -0.6954091 0.1860654 0.694108 -0.7055176 0.03951531 0.7075899 -0.7082601 0.03318554 0.7051713 -0.706573 -0.09432822 0.701325 -0.7041931 -0.0868119 0.7046814 -0.6989389 -0.1619005 0.6966152 -0.6976404 -0.1577346 0.6988688 -0.6881323 -0.2396636 0.6848616 -0.687666 -0.2382762 0.6858133 -0.6726404 -0.3270932 0.6637507 -0.6725409 -0.3268166 0.6639877 -0.6525162 -0.4141194 0.6346085 -0.6524376 -0.4139071 0.6348277 -0.6273222 -0.4987651 0.5980805 -0.6271736 -0.4982391 0.5986745 -0.6028426 -0.5650673 0.5632759 -0.6027895 -0.5647857 0.5636151 -0.5850876 -0.6068181 0.5380002 -0.6548985 -0.575982 0.489237 -0.6323499 -0.6230419 0.4603831 -0.6974139 -0.5881372 0.4095225 -0.6726791 -0.6341032 0.3813344 -0.733401 -0.5950834 0.3286316 -0.706732 -0.6400685 0.3014005 -0.7634626 -0.5967407 0.2470334 -0.7358796 -0.6398063 0.2216513 -0.7933127 -0.5872808 0.1604881 -0.7661715 -0.6277779 0.1373912 -0.8215777 -0.5657047 0.07062792 -0.7950448 -0.6044701 0.05019766 -0.8279419 -0.5607805 0.006117284 -0.7962303 -0.6048667 -0.01239264 -0.7963618 -0.6046902 -0.01256984 -0.7594489 -0.6497583 -0.03243064 -0.7631863 -0.6451067 -0.03720629 -0.7737919 -0.6328993 -0.02616828 -0.7780151 -0.6273452 -0.03362327 -0.7704713 -0.6362062 -0.04019665 -0.7682153 -0.6392765 -0.03421884 -0.7716905 -0.6354986 -0.02520972 -0.7723663 -0.6345791 -0.02756232 -0.7757995 -0.630648 -0.02045333 -0.7756384 -0.6308723 -0.01963096 -0.7785311 -0.6274325 -0.01476097 -0.7787221 -0.6271535 -0.01644742 -0.6881404 -0.7254027 -0.01593363 -0.5264613 0.2571866 0.8103665 -0.526169 0.2577157 0.8103881 -0.5366072 0.1736601 0.8257694 -0.6189441 0.1836591 0.7636607 -0.6286305 0.03645181 0.7768495 -0.6302075 0.03325808 0.7757141 -0.628228 -0.1037794 0.7710768 -0.6262276 -0.09823656 0.7734266 -0.6209464 -0.1739115 0.7643169 -0.6199295 -0.171095 0.7657768 -0.6106523 -0.2546805 0.7498278 -0.6103693 -0.2540053 0.7502871 -0.5957441 -0.3454294 0.7250983 -0.5958902 -0.3457719 0.724815 -0.5764795 -0.4355117 0.6913761 -0.5766528 -0.4359174 0.6909759 -0.552447 -0.522611 0.6493691 -0.5525001 -0.5227187 0.6492371 -0.5292834 -0.5901943 0.6095324 -0.5293692 -0.5905125 0.6091498 -0.5126233 -0.6325069 0.5806484 -0.5859881 -0.6059787 0.5379664 -0.5638278 -0.6533618 0.5051897 -0.6322544 -0.6231355 0.4603874 -0.6073412 -0.6692695 0.4280364 -0.6713741 -0.635405 0.3814674 -0.6438663 -0.6804805 0.349832 -0.7039631 -0.642941 0.3017664 -0.6747321 -0.6861901 0.2718083 -0.7311993 -0.6448922 0.2224 -0.7007338 -0.686418 0.1944286 -0.7585868 -0.6366245 0.1387634 -0.728217 -0.6759378 0.1131736 -0.7847687 -0.6175605 0.05251085 -0.7548835 -0.655174 0.02996683 -0.78868 -0.6147261 -0.009787023 -0.7526995 -0.6576646 -0.0303452 -0.7524446 -0.6579699 -0.0300467 -0.7110612 -0.7012145 -0.051867 -0.7150717 -0.6967692 -0.05643731 -0.7281202 -0.6840951 -0.04306918 -0.7297748 -0.6821589 -0.04569548 -0.6817203 -0.7285901 -0.06643801 -0.6781616 -0.7316261 -0.06942796 -0.6214386 -0.7797649 -0.07603102 -0.5472494 -0.8302515 -0.1058328 -0.5346044 -0.8402795 -0.09015923 -0.4330284 -0.8905749 -0.1391504 -0.430278 -0.8922537 -0.1369097 -0.3945575 -0.9109504 -0.1203902 -0.411346 -0.9004799 -0.1411747 -0.3842774 -0.9150041 -0.1228765 -0.4277839 -0.8990359 -0.0934627 -0.4068607 -0.9099248 -0.08063125 -0.4701877 -0.882009 -0.03136551 -0.4738154 -0.8795753 -0.04297101 -0.5288583 -0.84871 5.13431e-4 -0.5314694 -0.8470208 -0.009798884 -0.5785095 -0.8152032 0.02775979 -0.529123 -0.84636 0.06085914 -0.5700774 -0.8157675 0.0976485 -0.5219607 -0.8433639 0.1276494 -0.5604214 -0.8112001 0.1669805 -0.5084984 -0.8381902 0.1971462 -0.5442751 -0.8041852 0.2388536 -0.4885897 -0.8300521 0.2688747 -0.5213303 -0.7940531 0.3125613 -0.4616686 -0.8184126 0.3421446 -0.490826 -0.7805761 0.3870282 -0.4269031 -0.8030431 0.4157831 -0.4524198 -0.7630009 0.4616774 -0.383836 -0.7832044 0.489143 -0.4055323 -0.7406826 0.5356612 -0.3318068 -0.7582538 0.561209 -0.3492438 -0.7137127 0.6071598 -0.2700144 -0.7282274 0.6299024 -0.2832231 -0.6814443 0.674847 -0.1983896 -0.6924567 0.6936464 -0.206159 -0.650535 0.7309602 -0.2055527 -0.6495937 0.7319673 -0.216606 -0.5800129 0.7852815 -0.2159392 -0.5790735 0.7861579 -0.2276425 -0.4875383 0.8429029 -0.2268692 -0.4864628 0.8437324 -0.23637 -0.3902708 0.8898414 -0.2357014 -0.3892794 0.890453 -0.2429203 -0.2906898 0.9254671 -0.2425411 -0.2900919 0.925754 -0.2473881 -0.1966394 0.948753 -0.2468935 -0.1957282 0.9490701 -0.2498074 -0.1143631 0.9615183 -0.2493966 -0.1135163 0.9617252 -0.2504168 -0.005675613 0.9681216 -0.2548809 -0.01397311 0.9668715 -0.2495395 0.1003754 0.9631485 -0.1529909 0.0911259 0.9840173 -0.1466071 0.2041243 0.9679048 -0.0375331 0.1684607 0.9849936 -0.1501584 0.936376 0.3172578 -0.2890639 0.9378984 0.1918037 -0.363206 0.9306926 0.0435065 -0.369931 0.9284406 0.0338993 -0.3543943 0.9340355 0.04452478 -0.3255468 0.9451851 0.02538812 -0.3258484 0.9450685 0.02585232 -0.3643268 0.9283722 0.07342487 -0.357269 0.9322371 0.05738365 -0.3588797 0.9318652 0.05322247 -0.3261208 0.9314957 0.1611245 -0.3248872 0.9324712 0.1579426 -0.3360121 0.9334799 0.125344 -0.3542831 0.9278215 0.1167516 -0.352453 0.9300718 0.1036511 -0.3566686 0.9308276 0.0796712 -0.2719871 0.9349966 0.2276059 -0.286495 0.9358157 0.2053529 -0.3217428 0.9267864 0.1937751 -0.2724171 0.934247 0.2301553 -0.2387375 0.9382748 0.2502899 -0.2610106 0.9306308 0.2565149 -0.1821024 0.9383602 0.2938005 -0.1809546 0.9326343 0.3121678 -0.1977032 0.9383485 0.2835762 -0.2181353 0.9345013 0.2812904 -0.2184027 0.9348257 0.2800022 -0.2278752 0.9378482 0.261751 -0.08115833 0.9400613 0.331207 -0.1013983 0.9376351 0.3325039 -0.11101 0.9358097 0.3345698 -0.1188536 0.9389142 0.3229767 -0.1498159 0.9364883 0.317088 -0.04996597 0.9320741 0.3588055 -0.0633307 0.9413844 0.3313378 -0.02358293 0.9387671 0.3437442 -0.01048099 0.9359375 0.3520101 -0.0108112 0.9359003 0.3520991 -0.0363366 0.3055908 0.9514694 -0.0522471 0.3163627 0.9471985 -0.1159822 0.3113103 0.9432041 -0.1402027 0.3285292 0.9340299 -0.1802555 0.3147073 0.9319159 -0.223249 0.318831 0.9211443 -0.2507565 0.3335646 0.9087661 -0.2659587 0.3256129 0.9073271 -0.3065643 0.3236196 0.8951473 -0.3509905 0.3397256 0.8725779 -0.3499584 0.3404285 0.8727185 -0.3900045 0.3377906 0.8566179 -0.4406338 0.3502647 0.8265329 -0.4361444 0.353801 0.8274074 -0.520713 0.362137 0.7731202 -0.504701 0.3765128 0.7768623 -0.5910404 0.3806926 0.7111572 -0.5624716 0.4070206 0.7196944 -0.6231687 0.3956893 0.6746042 -0.6461126 0.425731 0.6334758 -0.6477914 0.4251049 0.6321805 -0.7227904 0.4432567 0.5301864 -0.6959438 0.4492143 0.56024 -0.701077 0.4464187 0.556059 -0.6831398 0.4266226 0.5927169 -0.6634482 0.4223605 0.6176149 -0.7368686 0.4738867 0.4821372 -0.7696567 0.4991943 0.3980374 -0.8189811 0.5015221 0.278829 -0.8004671 0.4913479 0.3432636 -0.7916124 0.4915996 0.3628772 -0.8566896 0.5149863 0.02953338 -0.897193 0.4412834 0.0177192 -0.8929555 0.4490496 0.0313853 -0.873686 0.4852662 0.034487 -0.8661723 0.4979028 0.04287797 -0.8698329 0.4915816 0.04169315 -0.8373553 0.5407708 0.08001983 -0.8629031 0.501469 0.06266671 -0.8304398 0.5354241 0.1539183 -0.850206 0.5090981 0.1340482 -0.8205459 0.5329331 0.2066075 -0.8334493 0.5194283 0.1885644 -0.8240842 0.5086382 0.2493443 -0.800466 0.5193276 0.2992542 -0.1904932 0.9816826 0.003414154 -0.2665485 0.9637836 0.008556663 -0.3710367 0.9283576 0.02200263 -0.3145359 0.949216 0.007493615 -0.3267886 0.9446547 0.02893054 -0.3316009 0.9430965 0.02469646 -0.3265224 0.9448248 0.02625346 -0.327079 0.9448087 0.0188679 -0.3348262 0.9421496 0.0156725 -0.3227928 0.9463689 0.01381939 -0.3088265 0.9510797 0.008595108 -0.7497096 0.4646378 0.471219 -0.682263 0.5920182 0.4289892 -0.7554417 0.5632262 0.3347895 -0.6613895 0.6905277 0.2928065 -0.728916 0.6551085 0.1987822 -0.03899109 0.5198707 0.8533547 -0.0494216 0.5275927 0.8480586 -0.1269941 0.5252699 0.8414061 -0.1349384 0.5341368 0.8345595 -0.2264742 0.5287374 0.8180136 -0.2368402 0.5412041 0.8068488 -0.316195 0.5338202 0.7842556 -0.3278874 0.5493665 0.7685612 -0.3961766 0.5407344 0.7420583 -0.4083337 0.5590393 0.7216223 -0.4668571 0.5496886 0.6927388 -0.4787468 0.570514 0.6673195 -0.5291731 0.560714 0.6368483 -0.5400194 0.5837245 0.6063373 -0.5848937 0.5732874 0.5737953 -0.5938687 0.5979289 0.5383318 -0.6343159 0.5866819 0.503436 -0.6406072 0.6124939 0.4631132 -0.6737073 0.6015074 0.4293104 -0.6459901 0.672231 0.3616659 -0.7077411 0.6448645 0.288535 -0.03640568 0.7570412 0.6523522 -0.0512669 0.7667518 0.6398933 -0.1051039 0.7643966 0.6361218 -0.1102018 0.7692949 0.6293178 -0.1841154 0.763662 0.6188069 -0.1910458 0.7712327 0.6072081 -0.2552838 0.7637594 0.592876 -0.2627758 0.7734491 0.5768235 -0.3186519 0.7648738 0.5598475 -0.3258221 0.7763562 0.5395473 -0.3745324 0.7671838 0.5207251 -0.3806502 0.7801339 0.4964842 -0.423764 0.7705651 0.4760815 -0.428266 0.7847189 0.4481123 -0.4682182 0.7744532 0.4254341 -0.4706196 0.7895865 0.3937898 -0.5082565 0.7784137 0.3684392 -0.5080536 0.7943723 0.332948 -0.5435546 0.7821161 0.304701 -0.5400835 0.7987935 0.265026 -0.5737555 0.7850803 0.233353 -0.5659576 0.8025154 0.1888416 -0.5907949 0.7905311 0.1613132 -0.5795518 0.8066142 0.1161613 -0.5746962 0.8182468 0.01401883 -0.573444 0.8191281 0.01382428 -0.5711185 0.8205373 0.02328813 -0.5830749 0.8120239 0.02531307 -0.5748112 0.8172506 0.04115188 -0.5774734 0.815267 0.04317706 -0.5638785 0.823262 0.06542694 -0.5811663 0.8098284 0.08014804 -0.5888994 0.8014975 0.1039196 -0.9180378 0.3964154 0.007855594 -0.892691 0.450367 0.0165053 -0.8740894 0.4854955 0.01618719 -0.8579523 0.5134145 0.01798516 -0.7749233 0.6318314 0.01682436 -0.7658689 0.6427384 0.01822674 -0.7645388 0.6440291 0.02658998 -0.7484534 0.662445 0.03137314 -0.7611585 0.6475182 0.03685027 -0.7551299 0.6532798 0.05481344 -0.7556158 0.6526767 0.05529958 -0.737457 0.6679552 0.09996569 -0.74234 0.6596301 0.1175565 -0.7373897 0.6632158 0.1280682 -0.7465775 0.6433594 0.1694425 -0.7304861 0.6534684 0.1984163 -0.7673588 0.5855597 0.2613055 -0.7146652 0.610473 0.341433 -0.7918743 0.4792311 0.378514 -0.761312 0.467198 0.4495891 -0.1241437 0.003138005 -0.9922593 -0.711735 0.07728135 -0.6981841 -0.7183752 0.1410397 0.6812085 -0.9310343 0.1667383 -0.3246132 -0.9758286 0.2184656 0.005612432 -0.96916 0.2463668 0.005705654 -0.8583087 0.2309845 0.4582057 -0.7779736 0.2574011 -0.5731508 -0.9045245 0.31676 0.2854799 0.6673918 -0.7031214 -0.2453743 -0.1988421 0.02621269 -0.979681 -0.6109703 0.04799211 -0.7901976 -0.004827141 -0.5770407 -0.8167011 -0.003859996 -0.759844 -0.650094 -0.003383338 -0.9627735 -0.2702888 -0.02186924 -0.9625664 -0.2701624 -0.02071142 -0.9627388 -0.2696388 -0.07674235 -0.9600301 -0.2691704 -0.07549166 -0.9608057 -0.2667459 -0.1061862 -0.9579262 -0.2666494 -0.1048693 -0.958902 -0.2636466 -0.1277933 -0.9561397 -0.2635638 -0.1463184 -0.9507921 -0.2731029 -0.1535889 -0.9533737 -0.2597869 -0.2091154 -0.9428655 -0.2593753 -0.2077375 -0.9442873 -0.2552779 -0.2810574 -0.9252388 -0.2548332 -0.2796205 -0.9267762 -0.2507954 -0.3407407 -0.9061621 -0.2505317 -0.3391402 -0.9074156 -0.2481551 -0.4013743 -0.8818167 -0.2475842 -0.3999198 -0.8836635 -0.243317 -0.4795256 -0.8432896 -0.2427302 -0.5331831 -0.7982776 -0.2801226 -0.556792 -0.7959315 -0.2376464 -0.4781122 -0.8453661 -0.2382542 -0.5789225 -0.7813983 -0.2329499 -0.6352201 -0.7365827 -0.2322532 -0.6340255 -0.7390596 -0.2276017 -0.7061616 -0.6707006 -0.2269285 -0.7051354 -0.6733198 -0.2223165 -0.7724019 -0.5952211 -0.2216015 -0.7716005 -0.5979805 -0.2169149 -0.807926 -0.547952 -0.2168045 -0.8065688 -0.5501863 -0.2161991 -0.8393303 -0.4990818 -0.2155041 -0.8715814 -0.4255113 -0.2434871 -0.8865889 -0.4119017 -0.2104689 -0.8388218 -0.501811 -0.2111015 -0.9002182 -0.383466 -0.2063037 -0.9266048 -0.3148537 -0.2055989 -0.9266327 -0.3173105 -0.2016585 -0.9459702 -0.2540143 -0.2015373 -0.9455659 -0.2561632 -0.2007127 -0.9608519 -0.1916829 -0.2000536 -0.9657463 -0.1120148 -0.2340658 -0.9763831 -0.0908147 -0.196033 -0.9611308 -0.1938713 -0.1965748 -0.9792074 -0.0622493 -0.193075 -0.9811853 0.01536726 -0.1924557 -0.9824215 0.01163214 -0.1863136 -0.9807271 0.05842244 -0.1864436 -0.8970633 0.06072223 -0.4377104 -0.5153871 -0.6848686 -0.5151031 -0.01992166 -0.7985563 -0.6015903 -0.01909053 -0.7988035 -0.601289 -0.06561625 -0.7967263 -0.6007677 -0.064848 -0.7977635 -0.5994732 -0.09007209 -0.7953363 -0.5994393 -0.08919751 -0.7967975 -0.5976266 -0.1250678 -0.7921658 -0.5973538 -0.1242299 -0.7939121 -0.5952063 -0.1760634 -0.784337 -0.5948254 -0.175285 -0.7863649 -0.5923727 -0.2363113 -0.7705211 -0.5919917 -0.2355597 -0.7726035 -0.5895724 -0.2864062 -0.7553225 -0.589457 -0.2854586 -0.7567853 -0.5880387 -0.3373433 -0.7356005 -0.5874448 -0.3367298 -0.7379168 -0.5848863 -0.4031744 -0.7042407 -0.5843761 -0.4027001 -0.7067337 -0.5816874 -0.4700803 -0.6643229 -0.5811195 -0.4697995 -0.6669785 -0.5782977 -0.5348986 -0.616505 -0.5777588 -0.5347982 -0.6191993 -0.5749638 -0.5952253 -0.5619405 -0.5743952 -0.5953242 -0.5646645 -0.5716146 -0.6517623 -0.4991747 -0.5709909 -0.6521238 -0.5019216 -0.5681632 -0.6822972 -0.4597992 -0.5683794 -0.6814324 -0.4615358 -0.5680094 -0.7091487 -0.4188848 -0.5671365 -0.7097446 -0.4214404 -0.5644916 -0.750775 -0.3439903 -0.5639216 -0.7515794 -0.3463375 -0.5614079 -0.7846245 -0.2642507 -0.5608352 -0.7856042 -0.2663714 -0.5584554 -0.8015882 -0.2129884 -0.5586522 -0.8014976 -0.2146102 -0.5581613 -0.8146731 -0.1603978 -0.5572973 -0.8157563 -0.1621674 -0.5551967 -0.8287745 -0.07362979 -0.5547177 -0.8298507 -0.07504284 -0.5529162 -0.8334284 0.01290255 -0.5524769 -0.83441 0.01187205 -0.5510164 -0.1714797 -0.9822276 -0.07631248 -0.7949553 0.04845279 -0.6047302 -0.5142846 -0.4501602 -0.7299776 -0.01532566 -0.5253083 -0.8507741 -0.01482921 -0.5255093 -0.8506586 -0.04560881 -0.5242798 -0.8503238 -0.04520398 -0.5250521 -0.8498688 -0.06165695 -0.5234206 -0.8498408 -0.06115984 -0.5246551 -0.8491151 -0.08484351 -0.5216383 -0.8489377 -0.08439785 -0.5230915 -0.8480876 -0.1186437 -0.5168076 -0.8478407 -0.1182647 -0.5185002 -0.8468595 -0.1586279 -0.5080254 -0.8466095 -0.1582925 -0.5097359 -0.8456434 -0.1919025 -0.4982016 -0.8455583 -0.1914116 -0.4993351 -0.8450008 -0.2257835 -0.4854437 -0.8446102 -0.2255977 -0.4872923 -0.8435947 -0.2696225 -0.4649941 -0.8432582 -0.2695716 -0.4669554 -0.84219 -0.314256 -0.4388526 -0.8418144 -0.314377 -0.4409204 -0.8406881 -0.3575714 -0.4074218 -0.8403275 -0.357837 -0.4094718 -0.8392173 -0.3979638 -0.371458 -0.8388347 -0.3983887 -0.3734939 -0.8377283 -0.4359108 -0.3299875 -0.8373113 -0.4365411 -0.3320076 -0.8361836 -0.4563447 -0.3038514 -0.8363156 -0.455866 -0.304945 -0.8361787 -0.4745225 -0.2767867 -0.8355941 -0.4753022 -0.278611 -0.8345441 -0.502606 -0.2270665 -0.8341631 -0.5035178 -0.2287135 -0.8331627 -0.5255395 -0.1740434 -0.8327768 -0.5265601 -0.1755019 -0.8318255 -0.5369295 -0.1398596 -0.8319532 -0.5369607 -0.140907 -0.8317563 -0.5460274 -0.1048524 -0.83118 -0.5470726 -0.1060239 -0.8303436 -0.5557501 -0.04695314 -0.8300225 -0.5567445 -0.04785847 -0.8293041 -0.55913 0.01083087 -0.8290092 -0.5599583 0.01022982 -0.8284577 -0.1318184 -0.9855287 -0.10657 -0.4458842 0.02906239 -0.8946188 -0.1993087 0.01679062 -0.9797929 -0.199941 0.00697267 -0.9797832 -0.1996383 0.007168173 -0.9798435 -0.1988028 -0.01340109 -0.9799479 -0.1984142 -0.01308572 -0.980031 -0.195375 -0.03380948 -0.9801456 -0.1949643 -0.03339588 -0.9802416 -0.1917144 -0.04602211 -0.9803712 -0.1916934 -0.0456587 -0.9803923 -0.1881264 -0.05818158 -0.98042 -0.1877187 -0.05766028 -0.980529 -0.1799926 -0.07682901 -0.9806631 -0.1796281 -0.07623976 -0.9807758 -0.1700535 -0.09430587 -0.980912 -0.1697313 -0.09364622 -0.9810309 -0.1631329 -0.1034759 -0.9811629 -0.1632961 -0.1030896 -0.9811763 -0.1564093 -0.1130074 -0.9812061 -0.1561388 -0.1122689 -0.981334 -0.1429817 -0.1275148 -0.9814766 -0.1427861 -0.1267657 -0.9816021 -0.1287262 -0.140082 -0.9817366 -0.1285894 -0.1393286 -0.9818617 -0.1134622 -0.1510631 -0.9819911 -0.1133778 -0.1502975 -0.9821182 -0.0977289 -0.1601318 -0.9822459 -0.09770983 -0.1593995 -0.9823669 -0.08229821 -0.1672001 -0.9824821 -0.08233118 -0.1665081 -0.9825969 -0.07030057 -0.1713372 -0.9827011 -0.07045322 -0.1709175 -0.9827633 -0.05870056 -0.1749795 -0.9828208 -0.0587933 -0.1743307 -0.9829304 -0.04467517 -0.177993 -0.9830171 -0.04478693 -0.1773477 -0.9831286 -0.03281867 -0.1795335 -0.9832044 -0.03295713 -0.1789827 -0.9833002 -0.02467399 -0.1800278 -0.983352 -0.0248354 -0.179549 -0.9834355 -0.01917195 -0.18012 -0.9834578 -0.01929545 -0.1798539 -0.9835041 -0.008483231 -0.180251 -0.9835842 -0.008678376 -0.1801729 -0.9835968 -0.004925251 -0.1801902 -0.9836195 0.664335 -0.1799678 -0.7254452 -0.04800957 -0.995129 -0.08610206 -0.06180852 -0.9921676 -0.1085511 -0.07703208 -0.9871271 -0.140165 -0.07763183 -0.9866787 -0.1429635 -0.09476459 -0.9916606 -0.08734422 -0.1011273 -0.9914039 -0.08301603 -0.09966427 -0.9917681 -0.08039253 -0.1079746 -0.9888247 -0.1027984 -0.1159121 -0.9919118 -0.05172479 -0.01865482 -0.9959555 -0.08789014 -0.02098721 -0.9963431 -0.08282524 -0.002021133 -0.9961469 -0.08767789 -0.1588151 -0.9852738 -0.06335049 -0.1566988 -0.9845134 -0.07860773 -0.1302098 -0.9883406 -0.07891917 -0.4109345 -0.9112733 0.02671843 -0.1897606 -0.9786108 -0.07944726 -0.2103016 -0.9691514 -0.1285259 -0.2129375 -0.9658375 -0.1477015 -0.243821 -0.9683139 -0.0540328 -0.287265 -0.9515691 -0.109522 -0.2980629 -0.9539862 -0.03269517 -0.3488193 -0.9335857 -0.08211565 -0.3428166 -0.9334429 -0.1056464 -0.3541229 -0.9317262 -0.08052027 -0.4025055 -0.9127314 -0.07007747 -0.4508387 -0.8908465 -0.05600923 -0.4912735 -0.8690121 -0.05889219 -0.5047252 -0.8468599 0.1675734 -0.5520437 -0.8324315 -0.04801738 -0.5925267 -0.8042187 -0.04630875 -0.5970553 -0.8019422 -0.02034002 -0.64909 -0.7559623 -0.0848729 -0.8257538 -0.5634573 -0.02542561 -0.7880429 -0.6125198 0.06171059 -0.7625862 -0.6105083 0.2138741 -0.715372 -0.6809175 -0.1568255 -0.6813805 -0.7197707 0.1328564 -0.6076716 -0.7400467 -0.2882122 -0.8579123 -0.5134101 -0.01991868 -0.8594068 -0.5065444 0.06951791 -0.8960189 -0.4403728 -0.05676424 -0.9003632 -0.4348241 -0.01656019 -0.9188793 -0.3942626 -0.01476186 -0.9207258 -0.3701609 0.1234706 -0.9281862 -0.315494 -0.1973174 -0.9541468 -0.2940363 0.05609595 -0.9650394 -0.2615256 -0.01741963 -0.9735318 -0.226257 0.03230524 -0.9546593 -0.1900816 -0.2291175 -0.9622157 -0.1380788 0.234681 -0.9930431 -0.1177475 -0.001002728 -0.997857 -0.06542837 8.16342e-4 -0.9947608 -0.0717712 -0.07280153 -0.987003 0.00668466 0.1605628 -0.01596921 0.0524286 -0.998497 -0.9763777 0.1102518 -0.1858253 -0.08129119 0.1531238 -0.9848578 -0.09916651 0.3422253 -0.9343703 -0.1666471 0.623745 -0.7636563 -0.123225 0.5063248 -0.8534934 -0.116549 0.4779639 -0.8706129 -0.1938906 0.8068108 -0.5580886 -0.2188696 0.7338726 -0.6430608 -0.2434422 0.9501978 -0.1945764 -0.1884493 0.98179 -0.02398478 -0.487156 0.8072243 -0.3332689 -0.6090947 0.6939202 -0.3840293 -0.2702124 0.9200495 -0.2837153 -0.2248717 0.9417214 -0.2501875 -0.1877269 0.9494443 -0.251623 -0.3751999 0.8920497 -0.2519372 -0.3752241 0.8920447 -0.2519189 -0.5217032 0.8152075 -0.2515206 -0.5217016 0.8152089 -0.2515192 -0.628259 0.736053 -0.2520251 -0.6536755 0.7070294 -0.2698477 -0.6899759 0.678501 -0.2521303 -0.7601918 0.5989532 -0.251721 -0.7601137 0.5990169 -0.2518056 -0.8076309 0.5329345 -0.2524147 -0.8278488 0.4961758 -0.2616792 -0.8377822 0.4841954 -0.252341 -0.8804235 0.4014574 -0.2523618 -0.8803712 0.40152 -0.2524446 -0.9108293 0.3263103 -0.2528076 -0.9022411 0.351352 -0.2500258 -0.8870537 0.3864891 -0.2525115 -0.9189516 0.3027107 -0.2527732 -0.9189521 0.3027121 -0.2527696 -0.1693437 0.2220868 -0.9602085 -0.1050063 0.2440676 -0.9640564 -0.1050586 0.2440711 -0.9640498 -0.1444828 0.2234706 -0.9639428 -0.1444888 0.2234712 -0.9639417 -0.1811404 0.1952231 -0.9638859 -0.1809097 0.1952643 -0.963921 -0.2085573 0.1649686 -0.9639965 -0.2083806 0.1650329 -0.9640238 -0.2270829 0.1376933 -0.9640924 -0.2269704 0.1377422 -0.9641118 -0.2405458 0.1118603 -0.9641707 -0.2404103 0.1119225 -0.9641972 -0.2458109 0.09838694 -0.9643117 -0.2458193 0.09837329 -0.964311 -0.2506954 0.0854932 -0.9642835 -0.2506933 0.08549416 -0.964284 -0.2573783 0.06145262 -0.9643548 -0.257417 0.06143283 -0.9643456 -0.8933923 0.1039617 -0.4370839 -0.956072 0.1470717 -0.2535675 -0.9437539 0.2128772 -0.2530059 -0.9403416 0.1891413 -0.2828132 -0.9373804 0.2392002 -0.2531824 -0.1987663 0.02686119 -0.9796788 -0.2553712 0.07312589 -0.9640737 -0.4441325 0.05451023 -0.8943015 -0.6090798 0.07289737 -0.7897517 -0.25023 0.6663189 -0.7024273 -0.2774614 0.6565048 -0.701439 -0.2775284 0.6565074 -0.7014101 -0.3849815 0.6002507 -0.7010624 -0.3849905 0.6002511 -0.7010571 -0.4844783 0.5234916 -0.7008832 -0.4841892 0.5235573 -0.701034 -0.5597269 0.4412615 -0.7014229 -0.5594833 0.441362 -0.701554 -0.6106322 0.3668332 -0.7018275 -0.6104962 0.3669083 -0.7019066 -0.6474775 0.2964018 -0.7020819 -0.6472843 0.2965158 -0.7022119 -0.6624396 0.2595031 -0.7027317 -0.662431 0.2595062 -0.7027388 -0.6754695 0.2241888 -0.7024817 -0.6754724 0.2241907 -0.7024781 -0.6936844 0.1584542 -0.7026337 -0.6937375 0.1584178 -0.7025896 -0.6984404 0.1333913 -0.7031272 -0.7914821 0.09302723 -0.6040714 -0.3511597 0.880698 0.3178962 -0.8660305 0.4999482 0.006563007 -0.7646164 0.4236465 0.4856803 -0.7983251 0.3647573 -0.4791963 -0.8515225 0.3623867 0.3789267 -0.3720213 0.8842112 -0.2824371 -0.5017869 0.7858475 0.3614606 -0.2152962 0.3082944 0.9266079 -0.6491893 0.7605971 0.00673747 -0.7129901 0.7011411 0.006812691 -0.3449823 0.2804418 0.8957341 -0.5451277 0.4286535 0.7204804 -0.834837 0.5504567 0.006683588 -0.2665705 0.9637695 -0.009412705 -0.1903231 0.9815452 0.01860803 -1 0 0 -1 4.28374e-5 0 -1 -3.14401e-5 0 -0.9999998 -6.65147e-4 0 -1 0 0 -1 0 -1.19501e-7 -0.01489049 0 0.9998892 -0.9854444 -0.02941948 0.1674329 -0.9972264 0.01461577 0.0729798 -0.9972909 0.04769116 0.05600529 -0.9997016 0 0.02443313 0.9853924 0.03116196 0.1674241 0.9885444 -0.02099913 0.149463 0.9981752 0.02245587 0.05605483 0.9946214 0.07345163 0.07302975 0.9997015 0 0.02443307 0.9238802 -1.3207e-5 0.382682 0.9077602 0.1085535 0.4052008 0.9387822 -0.02751445 0.3434108 0.9601243 0.04060417 0.2766093 0.9647694 0 0.2630972 0.977297 0 0.2118742 0.814781 0.04384148 0.5781089 0.8237558 -7.1636e-4 0.5669443 0.8752185 0.001024603 0.4837269 0.8673385 0.05559277 0.4946043 0.8948652 -1.55949e-5 0.4463366 0.2759321 0.0812909 0.9577335 0.289016 0.003105223 0.9573193 0.3826746 -0.004003703 0.9238745 0.3867528 -0.03684419 0.9214471 0.4834848 0.03175318 0.8747767 0.498857 -0.06036263 0.8645797 0.577938 0.05006438 0.8145437 0.5895986 5.43747e-4 0.8076963 0.6663398 -6.90055e-4 0.745648 0.6707296 -0.02936172 0.7411206 0.7454003 0.02551996 0.6661285 0.7501432 -4.56288e-6 0.6612755 0.7905179 -3.99725e-6 0.612439 0.01489049 0 0.9998892 0.04550361 0.0930072 0.9946252 0.0554136 0.1534313 0.9866043 0.1052664 -0.1027292 0.9891237 0.1661314 0.127303 0.9778519 0.188759 -9.43986e-5 0.9820235 0.2353062 -8.98892e-5 0.9719213 -0.0455088 0.0930072 0.9946249 -0.0554136 0.1534313 0.9866043 -0.1052684 -0.1027297 0.9891235 -0.1661394 0.1273514 0.9778443 -0.1887572 1.86313e-5 0.9820239 -0.8744392 0.04225283 0.4832918 -0.8685513 7.79401e-4 0.4955988 -0.8155632 -9.81286e-4 0.5786673 -0.8224619 0.05894768 0.5657578 -0.7905179 -3.99725e-6 0.612439 -0.7456448 -4.01139e-6 0.6663436 -0.7499489 0.0291242 0.6608543 -0.6659909 -0.0326094 0.7452468 -0.6712734 -7.73413e-4 0.7412095 -0.5786663 7.1189e-4 0.8155641 -0.5892562 0.06729918 0.8051385 -0.4821081 -0.0818876 0.8722765 -0.5015661 0.04516714 0.8639395 -0.3823701 -0.03983783 0.9231501 -0.3878777 -0.004408001 0.9217004 -0.2768325 0.004011988 0.9609099 -0.2901031 0.1107952 0.9505602 -0.2353389 2.22014e-5 0.9719134 -0.9878924 0.04413604 0.1487307 -0.9772967 -8.88608e-6 0.2118752 -0.9609163 0 0.2768394 -0.9635881 0.05553978 0.2615596 -0.9387822 -0.02751445 0.3434108 -0.9224582 0.05547767 0.3820905 -0.9127967 -2.31206e-5 0.4084143 -0.8948652 -2.33923e-5 0.4463366 0.02904236 0.07002079 -0.9971227 7.56165e-4 0 -0.9999998 -0.4064634 -0.003305196 -0.9136612 -0.2467724 5.28106e-4 -0.9690734 -0.1686629 -0.001840949 -0.9856721 -0.1203877 0.00163573 -0.9927256 -0.06467425 2.1884e-4 -0.9979064 -0.01891887 -2.24554e-4 -0.9998211 -0.03142589 9.0476e-5 -0.9995062 -0.009206473 9.96689e-6 -0.9999576 -0.3749648 0.002931833 -0.9270344 -0.5409916 -7.35928e-4 -0.8410278 -0.5529251 2.27078e-4 -0.8332309 -0.6842824 -8.11022e-4 -0.7292168 -0.682196 -1.42515e-4 -0.7311694 -0.7962707 4.30573e-5 -0.6049406 -0.7967329 1.32634e-4 -0.6043317 -0.8858445 -4.2182e-4 -0.463982 -0.9999834 0 -0.005783379 -0.8848622 2.9517e-4 -0.4658529 -0.9544509 -1.24845e-4 -0.2983685 -0.9669024 0.01320219 -0.254805 -0.9940649 -0.02163368 -0.106616 -0.9955345 -0.01231461 -0.09359103 -0.9996795 -9.23815e-4 -0.02530318 -0.004735827 3.80755e-7 -0.9999889 -0.004781067 4.78252e-7 -0.9999886 -0.004688739 1.1699e-6 -0.9999891 -0.004735887 0 -0.9999889 -0.004719913 3.71091e-7 -0.9999889 -0.004727721 6.63674e-7 -0.9999889 -0.004729211 2.14072e-6 -0.9999889 -0.004728257 7.40529e-6 -0.9999888 -0.004727959 8.77773e-6 -0.9999889 -0.9556939 -0.2030251 0.2131435 -0.9494457 -0.06910681 0.3062307 -0.9550508 -0.2020361 0.2169317 -0.930437 -0.2393867 0.2774549 -0.9306585 -0.2590125 0.2584324 -0.8989706 -0.282444 0.3347796 -0.9013742 -0.3041388 0.30826 -0.8508032 -0.3245501 0.4132813 -0.837071 -0.4164028 0.3548535 -0.94756 -0.06777727 0.3123081 -0.9359202 -0.08595597 0.3415628 -0.9358196 -0.08547532 0.3419585 -0.9192146 -0.09756183 0.3814789 -0.9207522 -0.1024352 0.3764604 -0.8935858 -0.1140612 0.4341595 -0.8954011 -0.1434969 0.421504 -0.9752389 -0.09360456 0.2003685 -0.9669826 -0.1774199 0.1829395 -0.9673935 -0.1120396 0.22715 -0.9917228 -0.01003843 0.1280053 -0.9524742 -0.06225836 0.2981894 -0.985046 -0.06950873 0.1576485 -0.9775369 -0.09619289 0.1875327 -0.9809995 -0.07882124 0.1772777 -0.9737846 -0.09971028 0.2044541 -0.8599262 0.5104184 0 -0.8665561 0.4990798 -2.08808e-4 -0.7264134 0.687258 3.59314e-4 -0.7353706 0.6776651 -1.31853e-7 -0.951525 0.2097491 0.2249569 -0.9999999 6.60452e-4 0 -0.9211084 0.3893064 0 -0.9844663 0.1755623 0.002025783 -0.9309855 0.3650059 -0.00607419 -0.988933 0.1483628 2.60249e-5 -0.974644 -0.08692759 0.2061858 -0.9658591 -0.1181936 0.2305356 -0.956412 -0.1523694 0.2491177 -0.9647744 -0.1108706 0.2385754 -0.9333812 -0.1447284 0.3284102 -0.9075226 -0.2227108 0.3560936 -0.9054871 -0.2231283 0.3609806 -0.8566741 -0.2822324 0.4318035 -0.8188558 -0.2539451 0.514769 -0.8434848 -0.3571015 0.4012631 -0.8631874 0.1988896 0.4640588 -0.8674952 0.1974484 0.4565811 -0.8347899 0.1492208 0.5299615 -0.8648062 0.1238207 0.4865992 -0.8169936 0.07826668 0.5713106 -0.8456819 0.05746519 0.5305845 -0.7951807 0.02459514 0.6058735 -0.8223133 0.003882348 0.5690218 -0.6520677 -0.5223898 0.5494694 -0.8694387 -0.1525779 0.4698897 -0.8639206 -0.1412887 0.4834032 -0.7866213 -0.4433556 0.4297242 -0.7782643 -0.4130429 0.4729698 -0.8340092 -0.1941968 0.5164458 -0.8332318 -0.1455305 0.5334284 -0.7444862 -0.42901 0.5115573 -0.7472647 -0.4355585 0.5018807 -0.7747828 -0.1950523 0.601387 -0.7907614 -0.2053039 0.5766686 -0.6052486 -0.4906842 0.6268199 -0.4508579 -0.6506118 0.6110905 -0.5738647 -0.5609936 0.5966286 -0.585446 -0.5682382 0.5782375 -0.7911348 -0.1650465 0.5889528 -0.7771498 -0.1478693 0.6116967 -0.7818652 -0.1917454 0.5932289 -0.686368 -0.3554167 0.6344903 -0.611083 -0.4874864 0.6236463 -0.8932319 0.3144618 0.3213262 -0.6856578 0.7263075 0.04848575 -0.9799444 -0.07060837 0.1863427 -0.9839597 -0.06113034 0.16759 -0.9861815 -0.05753982 0.1553552 -0.6488629 0.7120367 0.2682921 -0.7141898 0.695789 0.0762273 -0.8288449 0.5558914 0.06325381 -0.8699291 0.467857 0.1559916 -0.9067578 0.4208036 0.02673631 -0.9424895 0.2794188 0.1834092 -0.9769831 0.2109548 0.03165578 -0.9824667 0.1662167 0.08444684 -0.6780676 0.7061812 0.2037953 -0.7315965 0.6046552 0.3148947 -0.7668002 0.5950157 0.2407779 -0.7922084 0.5040791 0.3439626 -0.8055645 0.509683 0.3021411 -0.8460927 0.4035726 0.348219 -0.842635 0.3418895 0.4160262 0.1696813 0.985499 0 0.4057666 0.8960171 0.1802963 0.4306505 0.884309 0.1803826 0.2028274 0.9755716 0.08438771 0.4519267 0.8883047 0.08171504 0.1918308 0.9811492 0.02339202 0.2281115 0.9734557 0.01869219 0.2602585 0.9655233 0.005524098 -0.5094007 0.8603059 -0.01961672 -0.497509 0.867307 -0.0162394 -0.4060874 0.9138343 -7.00406e-5 0.5143576 0.7941324 0.3237129 0.1745908 0.7555165 0.6314373 0.486198 0.8270763 0.2820575 0.375529 0.9031227 0.2082007 0.3750751 0.9025102 0.2116463 0.3725962 0.9004078 0.2245839 0.374726 0.9022176 0.2135037 0.373656 0.8998422 0.2250898 0.3753107 0.9019978 0.2134056 0.3746882 0.8990402 0.2265735 0.3768882 0.9006949 0.2161108 0.3781146 0.896813 0.2296867 0.3794378 0.8979327 0.2230337 0.3946819 0.8844535 0.2489342 0.324679 0.902664 0.2824558 -0.001041769 0.9787386 0.205109 0.005147337 0.9838383 0.1789856 -0.003450691 0.9851636 0.1715837 -0.002136528 0.9862578 0.1652002 -0.002265036 0.9870984 0.1600991 -0.002873957 0.9866218 0.1630006 -0.002455115 0.9874377 0.15799 -0.003311872 0.9866797 0.1626415 -0.002464532 0.9875574 0.1572402 -0.003365218 0.9868161 0.1618108 -0.002534031 0.9875776 0.1571114 0.00385034 0.9920061 0.1261317 -0.02130883 0.992757 0.1182349 -0.01425307 0.9983903 0.05489706 -0.02611184 0.9982865 0.05236685 -0.02508401 0.9995802 0.01450872 -0.02578562 0.9995689 0.01404798 -0.02565747 0.9996707 5.63624e-4 -0.08746457 0.9961519 -0.00559616 0.1269356 0.9523121 0.2774695 -0.09651517 0.9778924 0.1855027 -0.2682253 0.9541586 0.1328028 -0.4440245 0.8960146 3.02295e-4 -0.4440714 0.8959777 0.004959046 -0.4438498 0.8960868 0.005096673 -0.4441981 0.8957381 0.01847344 -0.4406343 0.8974778 0.01937049 -0.4431403 0.8954758 0.04183006 -0.4356238 0.8990162 0.04474389 -0.4386287 0.8969726 0.05518341 -0.4371338 0.8975143 0.05815666 -0.4385308 0.8969918 0.05564707 -0.437862 0.8971879 0.0577138 -0.4378402 0.8972964 0.05617111 -0.4381641 0.8970368 0.05776935 -0.4378923 0.897224 0.05691647 -0.4378359 0.8971406 0.0586403 -0.4383562 0.8967279 0.06101667 -0.4357908 0.8977947 0.06364995 -0.4409504 0.8934258 0.08575171 -0.4833125 0.8734887 0.05853623 0.6391203 -0.05375391 0.7672261 0.4119849 0.430006 0.8033451 0.5113461 0.009624898 0.859321 0.3638008 0.2787059 0.8888037 0.366385 0.1734473 0.9141543 0.3476009 0.1594191 0.9239909 0.3279479 0.1502687 0.932668 0.3151923 0.01015621 0.9489735 0.1725968 0.3099924 0.9349413 0.2013625 -0.2629546 0.9435614 -0.5874962 0.8086675 -0.03008443 -0.9942893 0.04004746 0.09891897 -0.983116 0.1056373 0.1494112 -0.9430257 0.3003173 0.1432209 -0.8808672 0.4714098 0.04296368 -0.8574002 0.5062011 0.09287303 -0.7378495 0.6702796 0.07939523 -0.5707651 -0.4631434 0.6780305 -0.4180355 -0.6302831 0.6542091 -0.6582558 -0.3384678 0.6724128 -0.7416061 -0.1267837 0.658746 -0.7347264 -0.1739671 0.6556772 -0.6643132 -0.1356004 0.7350514 -0.6495545 -0.204497 0.7322977 -0.3590326 -0.7242987 0.5886314 -0.2889488 -0.6850182 0.6687741 -0.2007125 -0.797626 0.568777 -0.1251564 -0.7612321 0.6362874 -0.06102716 -0.8457751 0.5300379 -0.5674912 -0.4696816 0.6762787 -0.5070675 -0.4360517 0.7434659 -0.4587478 -0.5411847 0.704748 -0.369306 -0.4981517 0.7845113 -0.3308349 -0.5873249 0.738646 -0.5325435 -0.2187884 0.8176363 -0.5242699 -0.2319962 0.8193405 -0.5970641 -0.1790899 0.7819471 -0.4671875 0 0.8841583 -0.4759424 0.03183859 0.8789 -0.539683 -0.01072072 0.8418002 -0.5957399 0.09882605 0.7970744 -0.8037729 0.008794248 0.5948712 -0.7805923 -0.01522088 0.6248553 -0.745285 0.03573226 0.6657878 -0.702173 -0.04737424 0.7104286 -0.6689562 0.02636009 0.7428343 -0.655574 0.007496893 0.7550937 -0.598834 -0.01453697 0.8007413 -0.8399431 0.006670057 0.5426337 -0.8280708 0 0.5606236 -0.8152062 -2.26624e-5 0.5791708 -0.9006255 -0.006567299 0.4345465 -0.8841481 0.006752312 0.4671581 -0.8786901 0.01353365 0.4772008 -0.869689 0.001644253 0.4935975 -0.8459116 -0.001352727 0.5333216 -0.9232552 0.03227001 0.3828297 -0.923293 0.03309917 0.3826677 -0.9237017 0.03829085 0.3811942 -0.9241691 0.043509 0.3794977 -0.9243298 0.04521846 0.3789058 -0.9225571 0.03302711 0.3844448 -0.9156926 0.01446747 0.4016193 -0.03143149 0.3248117 0.9452563 -0.01693469 0.3614999 0.9322183 -0.03400981 0.7354505 0.6767245 -0.02477794 0.751384 0.6593998 -0.02984589 0.9689667 0.2453831 -0.02638107 0.9710676 0.2373435 -0.03571289 0.2951575 0.9547809 -0.0251674 0.3251156 0.9453393 -0.06134104 0.7212518 0.6899516 -0.05450689 0.7344494 0.6764711 -0.07277584 0.9652159 0.2511216 -0.07016187 0.9669998 0.2449262 -0.01755362 0.2880609 0.9574512 -0.09806573 0.9629944 0.251048 -0.06233805 0.7211606 0.6899575 -0.09926217 0.9624894 0.2525103 -0.109815 0.9612248 0.2529578 -0.1099249 0.9611687 0.2531233 -0.06440156 0.7989084 0.5979949 0.009022831 0.7245801 0.6891316 -0.06646162 0.717104 0.6937901 -0.01033622 0.2974746 0.9546738 0.0325092 0.2245266 0.9739256 0.07075482 0.2980304 0.9519305 -0.001027345 0.463541 0.8860749 -0.03071767 0.6228132 0.7817673 0.01346629 0.628863 0.7773995 0.1161004 0.2361537 0.964755 0.4452593 0.4193983 0.7911064 0.2151827 0.7129262 0.6674075 -0.0482462 0.8965315 0.4403449 -0.3040507 0.9415757 0.1448741 0.446426 0.4156631 0.792419 0.3663236 0.3816117 0.848634 0.3698578 0.3699576 0.8522539 0.300304 0.3470612 0.8884628 0.2992619 0.3412253 0.8910711 0.2837932 0.3365326 0.8978906 0.2275462 0.3097028 0.9232048 0.2351161 0.2966015 0.9256069 0.1162583 0.2697291 0.9558924 0.219891 0.7050077 0.6742493 0.1696266 0.6835372 0.7099323 0.1771211 0.6694847 0.7214003 0.1340447 0.6554724 0.7432281 0.1334006 0.649634 0.7484517 0.09201365 0.6364208 0.7658343 0.0965386 0.6175444 0.7805891 0.02734875 0.6019082 0.798097 0.03202348 0.4682313 0.8830255 -0.03994971 0.8893771 0.4554257 -0.0526632 0.8839832 0.4645432 -0.04173743 0.8727638 0.4863551 -0.05124324 0.869622 0.4910516 -0.05174541 0.865077 0.4989631 -0.05834496 0.8630292 0.5017735 -0.05346268 0.8509682 0.5224891 -0.06512188 0.8483418 0.5254288 -0.06199234 0.7992474 0.5977965 -0.2941948 0.9407402 0.1686933 -0.2669444 0.9521018 0.1491407 -0.2550449 0.9498519 0.1809238 -0.2289078 0.9588367 0.1680276 -0.2298309 0.956785 0.1781574 -0.2000488 0.9657489 0.165256 -0.1962145 0.9621298 0.1892256 -0.1308822 0.9762422 0.1726875 -0.1354321 0.9573146 0.2553563 0.2905228 0.8960885 0.335592 0.4985425 0.7832289 0.3714939 -0.106357 0.9700511 0.2183786 0.1211516 0.9473263 0.2964712 -0.2760712 0.9478972 0.1589829 -0.4844742 0.8725729 0.06246107 0.5402304 0.7456514 0.3900705 0.5102144 0.722818 0.4660639 0.5648118 0.6644484 0.4893833 0.5373747 0.6464292 0.5416252 0.5438061 0.6293683 0.5551311 0.5141652 0.6096704 0.6032713 0.5546457 0.5489199 0.6253441 0.4876542 0.5108329 0.7079854 0.5161824 0.4532359 0.7267276 0.2265018 0.9222542 0.3132798 0.1995775 0.9021191 0.3825573 0.2581118 0.8726211 0.4146211 0.2377554 0.8595176 0.4524402 0.2459833 0.8491041 0.4674552 0.2260825 0.8356419 0.5005892 0.2730288 0.7995344 0.5349766 0.2269973 0.773436 0.5918353 0.2625187 0.7353374 0.6247903 -0.1237375 0.9700126 0.2092006 -0.1381205 0.9593392 0.2461528 -0.08628594 0.9557836 0.2811272 -0.09544479 0.9498361 0.2978281 -0.08775395 0.9457733 0.3127495 -0.09463554 0.9411854 0.3243674 -0.05075287 0.9297865 0.3645839 -0.06770128 0.9202056 0.3855366 -0.03286129 0.9038438 0.4265989 -0.4594486 0.8844437 0.0816493 -0.4569981 0.8862679 0.07537919 -0.4189735 0.9015831 0.1077455 -0.4146654 0.9044782 0.09985983 -0.4092062 0.9053707 0.113377 -0.4013531 0.9104294 0.10017 -0.3675884 0.9194512 0.1396002 -0.3518187 0.9283212 0.1201799 -0.3239168 0.9320107 0.1625856 -0.6266834 0.7792739 -4.26311e-7 -0.6266925 0.7792667 0 -0.6266872 0.779271 1.76212e-6 -0.6266868 0.7792713 -1.25576e-7 -0.626693 0.7792664 0 -0.6266898 0.7792689 0 -0.6268588 0.7791329 0 -0.6265056 0.779417 2.22953e-6 -0.6267411 0.7792276 -7.1797e-7 -0.626765 0.7792084 -1.02849e-5 -0.6266871 0.779271 -2.21155e-7 -0.6266898 0.779269 0 -0.6146486 0.7642957 -0.1950882 -0.5922003 0.7631068 -0.25878 -0.5620654 0.6989058 -0.4422817 -0.4971836 0.6182367 -0.6087626 -0.4256067 0.5648994 -0.7069283 -0.3815064 0.4743902 -0.7933517 -0.2771745 0.3446601 -0.8968744 -0.1491249 0.2121563 -0.9657906 -0.1222625 0.1520262 -0.9807854 -0.8435217 0.5006811 -0.1943957 -0.976182 0.2151876 -0.0276243 -0.9320406 0.2572172 -0.2552247 -0.9568302 0.2168138 -0.1935663 -0.8038429 0.2163614 -0.5540981 -0.7980473 0.2066296 -0.5660607 -0.5371993 0.1468577 -0.830572 -0.5485019 0.1660993 -0.8194857 -0.1876026 0.05497407 -0.9807054 -0.04345971 0.1639806 -0.9855058 -0.2603616 0.0638802 -0.9633957 -0.1429799 0.1352744 -0.9804375 -0.1429736 0.1352729 -0.9804386 -0.3236745 0.3062358 -0.89524 -0.4216214 0.364213 -0.8304122 -0.6199623 0.5563714 -0.553261 -0.5782692 0.5471003 -0.6052159 -0.4447903 0.4208084 -0.7906213 -0.7127087 0.6742838 -0.193359 -0.7127019 0.6742901 -0.1933625 -0.6526669 0.6174935 -0.4390077 -0.9034524 0.381843 -0.1948581 -0.85487 0.4517253 -0.2552283 -0.7372347 0.3895666 -0.5520173 -0.7372339 0.389566 -0.5520185 -0.4943513 0.261224 -0.8290831 -0.4943494 0.2612245 -0.8290842 -0.1740287 0.09195989 -0.9804373 -0.1740322 0.09195947 -0.9804369 -0.761826 0.02298593 0.6473739 -0.7276369 -0.005443572 0.685941 -0.7096477 -0.01216375 0.7044517 -0.7875128 -0.3841591 0.4819186 -0.7675521 -0.4009174 0.5001291 -0.7601824 -0.3997935 0.5121408 -0.6804626 -0.4663153 0.5652616 -0.6606484 -0.4199609 0.6222352 -0.7439412 -0.03210777 0.6674733 -0.756384 -0.01478207 0.6539608 -0.8005601 -0.005467236 0.5992277 -0.6432491 0.06698334 0.7627214 -0.6763026 0.07423341 0.7328739 -0.5481693 -0.5752387 0.6071334 -0.5359943 -0.4547959 0.711246 -0.6782491 -0.2612733 0.6868147 -0.6396008 -0.006352961 0.7686811 -0.6580414 0.0206145 0.7526997 -0.6140251 -0.2522736 0.7478845 -0.6195915 -0.2667812 0.7381966 -0.4751761 -0.5659368 0.6737384 -0.4821606 -0.6133874 0.6255215 -0.6210425 0.7837672 0.003921568 -0.5222917 0.8526514 0.0140376 -0.5597117 0.8286865 0.001291513 -0.5939562 0.8044973 -6.16228e-4 -0.6462716 0.7629625 0.01487839 -0.6693195 0.7418949 0.04004222 -0.6670932 0.7425089 0.06055861 -0.9982086 0.0402041 0.04430878 -0.9924136 0.1229323 0.00166279 -0.9366846 0.3501722 -0.001288592 -0.881607 0.4717951 0.01336479 -0.8283617 0.5601935 3.11342e-4 -0.5877702 0.8090279 -5.78309e-4 -0.6735413 0.7388907 0.01956468 -0.4933748 0.8698168 0 -0.4890117 0.8713017 0.04124337 -0.674014 0.7378413 0.03599059 -0.55503 0.7794504 0.290515 -0.4658175 0.8801199 0.09166932 -0.5757157 0.8101429 0.1105443 -0.4754806 0.8759597 0.08131891 -0.5708957 0.8166913 0.08422398 -0.472369 0.879203 0.0622071 -0.5479312 0.8341039 0.06357806 -0.4949407 0.8675691 0.04855495 -0.4704478 0.8820897 0.02442705 -0.603908 0.7671543 0.2162625 -0.6940883 0.6945897 0.1891735 -0.6005018 0.7877712 0.1371651 -0.5621094 0.8165846 0.1312359 -0.5667403 0.813141 0.1326927 -0.6266667 0.7792869 9.8773e-4 -0.5732802 0.7800978 0.2505942 -0.5084024 0.8349731 0.2105872 -0.5601091 0.7780388 0.2844882 -0.5581659 0.7561782 0.3415343 -0.5494438 0.7781654 0.3042534 -0.5575765 0.7808825 0.2816575 -0.6073879 0.7453573 0.2748136 -0.5876817 0.7701686 0.2479327 -0.5891377 0.7866116 0.1848218 -0.6063828 0.7757459 0.174695 -0.6119865 0.7810208 0.1244144 -0.6269376 0.7717531 0.1065204 -0.6200475 0.7801374 0.08322799 -0.6287013 0.776845 0.03530794 -0.6333713 0.7727745 0.04074949 -0.6269116 0.7790512 0.007820367 -0.2028548 0.9792086 6.40867e-4 -0.1220614 0.9925065 0.005665242 -0.2867444 0.9580072 0 0.5158823 0.8566596 0 0.5417146 0.8405545 0.003680527 0.1697336 0.9854762 -0.005226373 0.2942774 0.9556826 0.008462131 0.0801531 0.9967826 -3.90893e-4 0.1717377 0.9798319 0.1021558 0.5694161 0.8095887 0.1425886 0.4822275 0.8689585 0.1112103 0.5596935 0.7964029 0.2290975 0.5206243 0.8305848 0.1976845 -0.1885651 0.9808865 0.04801017 -0.1905311 0.9806645 0.04466849 -0.2002006 0.9792425 0.03168588 -0.1865881 0.9816542 0.03924435 0.2029567 0.9744909 0.09579259 0.191461 0.970367 0.1474136 0.1800265 0.9752042 0.1287145 -0.2028442 0.9791537 0.01060271 -0.1980843 0.9801046 0.01255917 0.1696575 0.9850322 0.03046274 0.1793115 0.9831988 0.03416979 0.5153372 0.8557581 0.04588901 0.4780507 0.8777832 0.0310536 0.5097886 0.8271677 0.2364516 0.5081242 0.8275201 0.2387893 0.5022242 0.8286125 0.2473306 0.5069116 0.8275972 0.241088 0.5083779 0.8274004 0.2386644 0.5113114 0.8271133 0.2333328 0.594586 0.7444474 0.3037527 0.594723 0.7276837 0.3417325 -0.1841309 0.9806153 0.06700384 -0.1422494 0.9815983 0.1273974 0.1935443 0.9656646 0.1732989 0.2511868 0.9401643 0.2302093 -0.1932593 0.9796122 0.05487197 -0.1840048 0.9806653 0.06661748 0.1721019 0.9722437 0.1585034 0.1913108 0.9648525 0.1801664 0.5119668 0.8251382 0.238824 0.5274837 0.7988997 0.2889987 0.4836902 0.8374375 0.254445 -0.06242442 0.6149739 0.7860729 0.01643127 0.3208558 0.9469856 0.02776312 0.313004 0.949346 -0.01697981 0.2838161 0.9587285 0.2408918 0.9361094 0.2562624 -0.1338019 0.9853447 0.1057969 0.5768733 0.7203409 0.3851316 0.5358812 0.6006517 0.5933372 0.5666714 0.6150165 0.5483049 0.5685215 0.6280788 0.5313195 0.597889 0.6390035 0.4839457 0.5576995 0.6948431 0.4540532 0.618155 0.687599 0.3809097 0.4064201 0.4602838 0.7892791 0.4560874 0.4753462 0.7523499 0.4915685 0.5104404 0.7055573 0.4845318 0.5152287 0.706943 0.5500882 0.5673615 0.6127839 0.05133116 0.3067561 0.950403 0.1649116 0.3316401 0.9288805 0.1725695 0.3608189 0.9165313 0.2452393 0.3795095 0.8920932 0.2988626 0.4215853 0.8561233 0.305761 0.4172549 0.8558087 0.40462 0.4444572 0.7992124 -0.1859524 0.9674805 0.1714741 -0.1241692 0.9868915 0.1030883 -0.1321876 0.9839649 0.1197473 -0.1231293 0.9834135 0.1331812 -0.1268788 0.9821482 0.1388764 -0.1285781 0.980692 0.1473457 -0.1311401 0.9797976 0.150994 -0.1245499 0.9780651 0.166961 -0.1328226 0.9754306 0.175765 -0.1288149 0.9727307 0.1928775 -0.1363745 0.9705207 0.1987248 -0.1370956 0.9673707 0.21307 -0.1449255 0.9652218 0.2175856 -0.1468346 0.9614687 0.2324168 -0.1578696 0.9587298 0.2364624 -0.1620306 0.9550824 0.2481205 -0.1360591 0.9603567 0.2433164 -0.1508086 0.8946777 0.4204862 -0.1088864 0.7922746 0.6003705 -0.04602563 0.7274369 0.6846293 0.01542097 0.7399528 0.672482 -0.003797113 0.7490185 0.6625382 0.09811472 0.7742735 0.6251993 0.07903742 0.7822263 0.6179606 0.1614826 0.8051536 0.5706584 0.1454465 0.8101821 0.5678471 0.2176073 0.831113 0.5117599 0.2010639 0.8369573 0.5089951 0.2654329 0.8575875 0.4405555 0.2511782 0.8622819 0.4397494 0.2839778 0.8742741 0.3937023 0.2784947 0.8742905 0.3975636 0.3094722 0.8843251 0.3495659 0.2976583 0.8881582 0.3501065 0.3073858 0.8923157 0.3305855 0.4533141 0.8266233 0.333467 -0.04005879 -0.7955825 0.6045197 -0.2406842 0.8220719 0.5160124 -0.2065712 -0.3541409 0.9120924 -0.3285092 0.3550409 0.8752301 -0.284438 -0.181144 0.9414256 -0.3995288 0.4895148 0.775082 -0.3775157 0 0.9260032 -0.9208037 0.1393063 0.3642999 -0.8091477 0.5331245 0.2470999 -0.8900175 0.3287197 0.3159308 -0.7056033 0.6864627 0.1757643 -0.5502524 0.8307107 0.0845105 -0.9124379 0.1917061 0.3615326 -0.8757473 0.2067227 0.4362711 -0.8786613 0.1947468 0.4359222 -0.8421294 0.2092919 0.4970062 -0.82317 0.2648809 0.5022245 -0.8101555 0.2035429 0.5497441 -0.7534387 0.2233328 0.6184275 -0.7570605 0.2025697 0.6211481 -0.6840547 0.2270995 0.6931775 -0.6876904 0.2127545 0.6941308 -0.6057239 0.2372819 0.7594709 -0.6091375 0.2161136 0.7630507 -0.4992761 0.2454012 0.8309643 -0.502537 0.2252098 0.8347078 -0.7924578 0.5596196 0.2425631 -0.7666662 0.5701839 0.2951498 -0.7677733 0.568571 0.2953831 -0.7301667 0.582815 0.3566277 -0.7317939 0.580218 0.357526 -0.6763004 0.6002321 0.4270119 -0.6781378 0.597164 0.4283973 -0.6229822 0.6157898 0.4823859 -0.6244805 0.6135479 0.4833044 -0.5608943 0.6323007 0.5344094 -0.5628862 0.6286678 0.5365967 -0.4742438 0.6521886 0.5913907 -0.4761977 0.648348 0.5940375 -0.5426754 0.8358415 0.0829007 -0.5315393 0.8404216 0.1056299 -0.5246499 0.844945 0.1039738 -0.5089429 0.8509584 0.1297968 -0.4989299 0.8576135 0.1247727 -0.4736055 0.8667163 0.1565271 -0.4636723 0.8732439 0.1498442 -0.4372881 0.8820423 0.1754434 -0.4304754 0.8862016 0.1712827 -0.3983089 0.8957531 0.1974248 -0.3902545 0.9010129 0.1894133 -0.3424624 0.9136494 0.2190075 -0.3362671 0.9177467 0.2113422 -0.1727672 0.9849627 -2.38957e-4 -0.2041461 0.9789386 0.001926779 -0.2388253 0.9710618 -0.001246809 -0.1965242 0.980499 3.73856e-4 -0.3144698 0.9492674 3.04663e-4 -0.2282248 0.9736083 5.35759e-4 -0.2519733 0.9677342 -7.20024e-5 -0.2755883 0.9612758 1.1717e-4 -0.2729492 0.9620285 2.32865e-4 -0.2936906 0.9559006 -9.76659e-5 -0.3257188 0.9454663 9.16551e-4 -0.3354769 0.9420473 0.001523673 -0.3459979 0.9382319 0.00255829 -0.3513842 0.936226 0.003200411 -0.3548172 0.9349285 0.003676474 -0.3563973 0.9343264 0.003923356 -0.3556275 0.9346202 0.003792941 -0.3469318 0.9378881 0.002071797 -0.337617 0.9412837 0 -0.1809716 0.9304302 -0.3186674 -0.3544964 0.9329372 -0.0629338 -0.3793526 0.925011 -0.02113121 -0.3843856 0.9231052 -0.01116293 -0.387973 0.9216634 -0.003700256 -0.3876861 0.9217899 -0.001708865 -0.3877881 0.9217485 0 -0.3869081 0.9221183 1.99381e-4 -0.3718832 0.9282796 -2.65971e-4 -0.3487166 0.9372202 -0.003877282 -0.3136601 0.9494288 -0.01422351 -0.2809282 0.959329 -0.02770298 -0.1628469 0.9866514 -1.61383e-6 -0.1379384 0.9904409 2.96327e-6 -0.1209489 0.9926586 -6.61152e-4 0.1243911 0.9922333 -1.20157e-4 0.1209489 0.9926587 -3.5385e-4 -0.09678894 0.995305 3.57848e-4 -0.06793421 0.9976898 -2.47338e-4 -0.04929608 0.998784 -7.82036e-4 -0.03878349 0.9992477 -8.45937e-5 0.02644473 0.9996503 1.17637e-4 0.01304453 0.9999143 -0.001111567 0.07569104 0.9971311 7.24569e-4 0.06463432 0.9979091 6.05968e-5 0.09453141 0.9955219 -1.28852e-5 0.2519733 0.9677342 -7.20024e-5 0.1749836 0.9845713 1.02752e-4 0.2094104 0.9778259 -0.001987874 0.1727669 0.9849619 0.001277446 0.2388253 0.9710618 -0.001246809 0.2041461 0.9789386 0.0019266 0.2282248 0.9736083 5.35759e-4 0.3136601 0.9494288 -0.01422351 0.386516 0.9222827 0 0.387772 0.9217554 2.26356e-4 0.3718837 0.9282793 -2.6597e-4 0.3487166 0.9372202 -0.003877282 0.3875697 0.9218388 -0.001783251 0.387973 0.9216634 -0.003700256 0.3843657 0.9231137 -0.01114165 0.379313 0.9250276 -0.02111029 0.3544964 0.9329372 -0.0629338 0.17873 0.9305526 -0.3195738 0.2809258 0.9593297 -0.02770292 0.337617 0.9412837 0 0.3469318 0.9378881 0.002071797 0.3556275 0.9346202 0.003792941 0.3563973 0.9343264 0.003923356 0.3548172 0.9349285 0.003676474 0.3513832 0.9362263 0.003201484 0.3459979 0.9382319 0.00255829 0.3354769 0.9420473 0.001523673 0.3257188 0.9454663 9.16551e-4 0.3144696 0.9492675 3.04663e-4 0.2752212 0.9613809 -4.52919e-4 0.2929009 0.9561426 8.12688e-4 0.2730373 0.9620035 9.66945e-5 -0.1181266 0.9694881 0.2148001 -0.03421813 0.280588 0.9592182 -0.02851414 0.2767121 0.9605298 -0.1181255 0.7879193 0.6043424 -0.05728644 0.4740641 0.8786248 -0.1085209 0.6069386 0.7873048 -0.02733737 0.2735881 0.9614584 -0.02832043 0.2764358 0.9606151 -0.1702103 0.9703805 0.1714355 -0.1489418 0.9830403 0.1069961 -0.1258292 0.8987082 0.4201077 -0.1179295 0.7908138 0.6005884 -0.03093993 0.430498 0.9020611 -0.02028155 0.4823412 0.8757486 -0.02150458 0.7804549 0.6248422 -0.01444524 0.8017715 0.5974562 -0.008402109 0.9747605 0.2230948 -0.005866765 0.977289 0.2118299 -0.03121751 0.3614695 0.9318612 -0.01731866 0.4304975 0.9024256 -0.02217465 0.7514055 0.6594682 -0.0127995 0.7804476 0.6250903 -0.008979141 0.9712824 0.2377604 -0.005581796 0.9747614 0.2231793 -0.05449563 0.9644908 -0.2584333 -0.03992062 0.7065425 -0.7065438 -0.01462107 0.2587902 -0.9658229 -0.01462203 0.2587899 -0.965823 -0.04368114 0.2554953 -0.9658231 -0.04367876 0.2554963 -0.9658229 -0.0721805 0.2489491 -0.9658232 -0.07218277 0.2489497 -0.9658229 -0.09976327 0.2392361 -0.9658228 -0.09976565 0.2392343 -0.9658228 -0.1260778 0.2264746 -0.9658229 -0.1260764 0.2264729 -0.9658234 -0.1507874 0.210831 -0.9658227 -0.1507886 0.2108309 -0.9658226 -0.03992223 0.7065443 -0.7065418 -0.119255 0.6975525 -0.7065401 -0.119253 0.6975489 -0.7065439 -0.1970694 0.6796759 -0.706544 -0.19707 0.6796771 -0.7065427 -0.2723745 0.653152 -0.7065442 -0.2723761 0.6531541 -0.7065417 -0.3442183 0.6183153 -0.7065409 -0.3442128 0.6183138 -0.7065448 -0.4116721 0.5756049 -0.7065445 -0.4116746 0.5756062 -0.706542 -0.0544942 0.9644902 -0.258436 -0.1627913 0.9522138 -0.2584334 -0.1627913 0.9522131 -0.258436 -0.2690175 0.9278156 -0.2584335 -0.2690178 0.9278162 -0.2584308 -0.3718167 0.8916079 -0.2584331 -0.3718168 0.8916087 -0.2584306 -0.4698835 0.8440518 -0.2584306 -0.4698829 0.8440521 -0.2584301 -0.561969 0.7857508 -0.2584308 -0.5619685 0.7857499 -0.2584348 0 0 -1 -9.03138e-7 0 -1 -2.92682e-7 0 -1 -2.40384e-7 0 -1 1.93988e-6 0 -1 -1.20273e-6 0 -1 1.64345e-6 0 -1 7.48033e-7 0 -1 3.12278e-7 0 -1 0 0 -1 0 0 -1 -3.12278e-7 0 -1 4.51569e-7 0 -1 -7.48032e-7 0 -1 2.92682e-7 0 -1 -1.87823e-6 0 -1 1.20273e-6 0 -1 -9.6994e-7 0 -1 -0.1685165 0.9856989 -1.23054e-4 -0.1060127 0.9943649 2.14786e-5 -0.05641078 0.9984077 -3.73833e-4 -0.07052826 0.9975094 -9.37702e-4 -0.02352583 0.9997233 0 -0.4109308 0.9116665 -4.25265e-5 -0.3545053 0.9350532 -0.001341044 -0.3087548 0.9511337 -0.003904759 -0.3848921 0.9229608 0.001197099 -0.2591155 0.9658459 -9.1223e-4 -0.2784771 0.9604429 6.53354e-5 -0.1817425 0.9833462 -4.70969e-5 -0.1301034 0.9914987 -0.001890242 -0.6142151 0.7891387 0 -0.5807248 0.8140998 -4.86949e-4 -0.554352 0.8322811 -0.001520991 -0.5238237 0.8518219 -0.00288105 -0.4637454 0.8859685 5.3256e-5 -0.4864069 0.8737323 -6.09341e-4 -0.58173 0.8133808 0.001488983 0 1 0 0 1 2.30482e-7 0 1 0 0 0.9659264 -0.2588174 0 0.7071065 -0.7071072 0 0.2588179 -0.9659262 0 0.2588188 -0.9659259 0.01734238 0.8202244 0.5717791 0.0148943 0.5088133 0.8607481 0.0465207 0.5734887 0.8178916 0.0171054 0.477532 0.8784479 0.07362639 0.9752789 0.2083514 0.06903988 0.9741972 0.2148798 0.0254935 0.9791712 0.2014298 0.02393203 0.9778218 0.2080671 0.0218327 0.80821 0.5884896 0.0644356 0.8057261 0.5887731 0.05052804 0.7946828 0.6049183 -0.04759937 0.9755083 0.2147505 -0.04475522 0.9784649 0.2015033 -0.04095613 0.7953389 0.6047798 -0.03265666 0.8197167 0.5718376 -0.0278325 0.4766829 0.8786348 -0.01051664 0.5546423 0.8320224 0.01764607 0.5327436 0.8460927 0.01149362 0.482312 0.8759242 0.01172685 0.8222867 0.5689527 0.008385479 0.8017549 0.5975943 0.004440248 0.9797076 0.2003831 0.003419995 0.9772886 0.2118858 -0.01011121 0.4823015 0.8759469 -0.006870865 0.5327545 0.8462421 -0.006950497 0.8017437 0.5976276 -0.004786133 0.8222838 0.5690575 -0.002687036 0.9772828 0.2119227 -0.001906454 0.9797145 0.20039 -0.6063144 0.7331728 0.3079621 -0.7645158 0.4951323 0.4127465 -0.7270483 0.5630652 0.3928846 -0.6868863 0.6367996 0.3502479 -0.8018515 0.4007966 0.4431662 -0.7986978 0.2365841 0.553272 -0.783161 0.3432452 0.5184994 -0.7978298 0.4015144 0.4497266 -0.7758618 0.1166008 0.6200345 -0.8032807 0.1269126 0.5819222 -0.8092311 0.1243729 0.5741747 -0.7236039 0.07077956 0.6865767 -0.7447499 0.04895693 0.6655457 -0.7520614 0.07806885 0.6544533 -0.7708488 0.1090141 0.627621 -0.6298466 0.1130507 0.7684484 -0.6458377 0.09297692 0.7577922 -0.6649779 0.06402176 0.744114 -0.6768355 0.08434641 0.7312862 -0.7100225 0.07917815 0.6997134 -0.4962214 0.4517363 0.7414167 -0.4701339 0.2353494 0.850638 -0.4470364 0.3006994 0.8424597 0.04864203 0.4972487 0.8662436 -0.01857161 0.6501429 0.759585 -0.04912263 0.4823797 0.8745838 -0.1091309 0.6737861 0.7308233 0.1515584 0.4259116 0.8919807 0.1673001 0.4401615 0.8821953 0.2531964 0.4043621 0.8788532 0.2555773 0.407639 0.8766474 0.3544325 0.3770601 0.8556889 0.3449066 0.3515362 0.8703228 0.4701352 0.2353501 0.850637 0.44703 0.3006988 0.8424633 0.4161318 0.3550575 0.8371193 0.6298467 0.1130504 0.7684484 0.5698622 0.1184141 0.8131637 0.574137 0.1248581 0.8091831 0.7603903 0.03206968 0.6486743 0.7440416 0.06552928 0.6649121 0.7708173 0.109026 0.6276575 0.7758618 0.1166008 0.6200345 0.7236019 0.07078307 0.6865786 0.7100225 0.07917815 0.6997134 0.6638604 0.08625662 0.7428655 0.6746729 0.04876565 0.7365042 0.6458377 0.09297692 0.7577922 0.7986978 0.2365841 0.553272 0.7831615 0.3432454 0.5184986 0.7978299 0.4015145 0.4497262 0.8018513 0.400797 0.4431665 0.7924395 0.4666389 0.3927949 0.6617648 0.7047964 0.2555964 0.6868863 0.6367996 0.3502479 0.7270483 0.5630652 0.3928846 0.9302256 0.3632517 0.05223667 0.6557103 0.6775822 0.3330562 0.6798843 0.6770886 0.2816177 0.6798886 0.6770855 0.2816146 0.7071394 0.6770896 0.2037242 0.7071418 0.6770876 0.203723 0.7255043 0.6770883 0.123268 0.7255067 0.6770858 0.1232681 0.7347471 0.6770853 0.04125881 0.7347471 0.6770851 0.04126292 0.7938847 0.4316599 0.4282721 0.8334529 0.4314789 0.345228 0.8334515 0.4314818 0.3452277 0.8668645 0.4314829 0.2497369 0.8668637 0.4314832 0.2497393 0.8893761 0.4314809 0.1511116 0.8893735 0.4314866 0.1511098 0.8988375 0.4318837 0.07461643 0.866189 0.4973436 0.04864209 0.8032785 0.1269133 0.581925 0.8092321 0.1243698 0.5741738 0.8159877 0.1482502 0.5587362 0.8655663 0.1481318 0.4783848 0.865567 0.148145 0.4783793 0.9136866 0.1481419 0.3784584 0.9136847 0.1481395 0.3784639 0.950315 0.1481379 0.273782 0.9503152 0.1481394 0.2737805 0.9749931 0.1481401 0.165659 0.9749935 0.1481394 0.1656579 0.987411 0.1481381 0.05545032 0.9874104 0.1481425 0.05544865 -0.39394 0.3915895 0.8315461 -0.359745 0.3409522 0.8685247 -0.2993065 0.4159788 0.8587067 -0.2551048 0.3883689 0.8854892 -0.2040293 0.4423474 0.8733275 -0.1519995 0.4202405 0.8945916 -0.1395505 0.4317092 0.8911525 -0.05058598 0.4314829 0.9007018 -0.05058258 0.4314858 0.9007006 0.05057972 0.4314866 0.9007004 0.05058902 0.4314821 0.9007021 0.1395385 0.4317089 0.8911547 0.07437801 0.6965518 0.7136411 -0.5698623 0.1184134 0.8131638 -0.5741373 0.1248585 0.8091828 -0.5337522 0.1483485 0.8325272 -0.4783925 0.1481274 0.8655627 -0.4783852 0.1481415 0.8655644 -0.3784526 0.1481415 0.9136891 -0.3784526 0.1481338 0.9136904 -0.2737848 0.1481338 0.9503148 -0.2737803 0.1481311 0.9503166 -0.1656607 0.1481307 0.9749944 -0.1656562 0.1481331 0.9749947 -0.05546337 0.1481333 0.9874109 -0.0554561 0.1481426 0.98741 0.05546331 0.1481428 0.9874095 0.05545616 0.148133 0.9874114 0.1656488 0.1481332 0.974996 0.1656558 0.1481513 0.974992 0.2737953 0.1481508 0.9503092 0.2737802 0.1481344 0.950316 0.378453 0.1481344 0.9136901 0.3784523 0.1481412 0.9136893 0.4783915 0.1481415 0.865561 0.4783866 0.1481272 0.8655661 0.5337523 0.1483482 0.8325271 0.4962221 0.4517338 0.7414178 -0.6734739 0.6774379 0.2958223 -0.6798855 0.6770877 0.2816169 -0.679888 0.6770856 0.2816158 -0.7071421 0.6770872 0.2037231 -0.7071393 0.6770901 0.2037234 -0.7255064 0.6770862 0.1232672 -0.7255046 0.6770879 0.1232688 -0.7347447 0.6770877 0.04126298 -0.7347476 0.6770845 0.04126393 -0.8655302 0.4984926 0.04860824 -0.7981644 0.4318091 0.420089 -0.8334517 0.4314813 0.3452278 -0.8334527 0.4314795 0.3452279 -0.8668656 0.43148 0.249738 -0.8668626 0.431486 0.2497382 -0.8893747 0.4314838 0.1511107 -0.8893747 0.4314836 0.151111 -0.8988354 0.4318885 0.07461464 -0.9297329 0.3645142 0.05221414 -0.8159875 0.148252 0.5587359 -0.8655681 0.1481363 0.4783802 -0.8655644 0.1481465 0.478384 -0.9136848 0.1481452 0.3784614 -0.9136867 0.1481392 0.3784595 -0.9503155 0.1481368 0.2737808 -0.9503144 0.1481405 0.273783 -0.974993 0.1481424 0.1656578 -0.9749938 0.1481373 0.1656574 -0.9874106 0.1481395 0.05545353 -0.987412 0.1481312 0.05545026 -0.3842685 -0.5945914 0.7062569 -0.3496137 -0.7051302 0.6168969 -0.02942883 -0.8430872 0.5369711 -0.4345335 0.1704449 0.8843806 -0.425382 0.1796011 0.8870139 -0.4855725 0.1296018 0.8645362 -0.4810301 0.1563891 0.8626428 -0.3857312 -0.2287251 0.89381 -0.3264535 -0.2114987 0.9212472 -0.3325479 -0.218464 0.9174342 -0.0962339 -0.6982975 0.7093093 -0.07017797 -0.781332 0.6201575 -0.2835955 -0.5203009 0.8055189 -0.3479105 -0.5379379 0.7678419 -0.5099484 -0.1982628 0.8370451 -0.5674886 0.09053581 0.8183887 -0.5650684 0.1074295 0.8180199 -0.4891059 -0.2298325 0.841399 -0.403158 -0.2060436 0.8916332 -0.219488 -0.5749644 0.7881885 -0.1670238 -0.5598636 0.8115761 -0.1844416 -0.579847 0.7935734 -0.627797 0.06981825 0.7752397 -0.625748 0.07708668 0.7762069 -0.5604196 -0.2557271 0.7877396 -0.5486388 -0.2073501 0.8099392 -0.4859417 -0.4877898 0.7252048 -0.4153739 -0.471624 0.7778402 -0.2311452 -0.7139825 0.6609092 -0.2026739 -0.7690438 0.6062137 -0.05154448 -0.81394 0.5786578 -0.4725239 -0.2173531 0.8540955 -0.01597595 -0.8275575 0.5611537 0.08137685 -0.9080991 0.4107723 -0.01476907 -0.8578838 0.5136314 -0.0134055 -0.8573936 0.5144869 -0.2687501 -0.5620698 0.7822091 -0.1348505 -0.7098048 0.6913701 -0.2389727 -0.5838471 0.7758961 -0.267988 -0.5944922 0.7581304 -0.469953 -0.192758 0.8613877 -0.4167119 -0.1821354 0.8906053 -0.4146928 -0.196043 0.8885927 -0.326837 -0.3946112 0.8587548 -0.255415 -0.5423555 0.8003835 0.09214603 -0.960929 0.2610068 -0.2860851 -0.1742581 0.9422258 -0.3338229 -0.1844589 0.9244118 0.0692709 -0.9115467 0.4053199 0.08259499 -0.9378622 0.3370351 -0.03682267 -0.8099142 0.5853915 -0.05643647 -0.7744586 0.6301023 -0.3354498 -0.1598137 0.9284036 -0.2692219 -0.3789613 0.8853858 -0.2066338 -0.5128677 0.8332282 -0.2026827 -0.5280616 0.824664 -0.116085 -0.7047237 0.6999206 -0.2428352 -0.1913444 0.9510092 -0.2489185 -0.2353818 0.9394866 -0.1639666 -0.5412179 0.8247413 -0.1685849 -0.5045353 0.8467723 -0.04285281 -0.8103896 0.5843222 -0.05115151 -0.7732807 0.6319972 0.07257574 -0.9533348 0.2930628 0.08322238 -0.9377198 0.3372768 -0.1807533 -0.1993539 0.9631129 -0.1801328 -0.1821043 0.9666387 -0.1110009 -0.5598149 0.8211493 -0.1113992 -0.5335341 0.8384101 -0.02446538 -0.8337295 0.551631 -0.02580535 -0.8079028 0.5887506 0.06515616 -0.97837 0.1963337 0.06444597 -0.9651038 0.2538137 -0.2308213 0.9425055 0.2416712 0.2951608 0.9273436 0.2300308 0.4090031 0.664492 0.6254335 0.3566128 0.2517653 0.8996898 0.4222617 0.2387461 0.8744688 0.4251299 0.2433884 0.8717952 0.1943907 0.2554977 0.9470656 0.2276573 0.2521152 0.9405371 0.2579081 0.308544 0.9155785 0.2792552 0.2532889 0.9262081 0.3536388 0.2417438 0.9036037 0.1275764 0.2826402 0.9507044 0.1790156 0.2559273 0.9499762 0.1930034 0.2546606 0.9475747 0.1332898 0.2557516 0.9575099 0.02703183 0.2598904 0.9652597 0.02683299 0.2591137 0.9654741 -0.08011597 0.2577391 0.9628874 -0.07959318 0.2601204 0.9622901 -0.1400882 0.2565743 0.9563185 -0.1391256 0.2571845 0.9562951 0.4090121 0.6645043 0.6254145 0.3446186 0.6768527 0.6504679 0.3446361 0.6769012 0.6504082 0.2483967 0.6914249 0.6784031 0.2483908 0.6914297 0.6784004 0.1897019 0.6981716 0.6903403 0.1896701 0.6981816 0.690339 0.130349 0.7026162 0.6995282 0.1303455 0.7026106 0.6995345 0.02647209 0.7066367 0.7070813 0.02646553 0.7066291 0.707089 -0.07842844 0.7052818 0.7045755 -0.07842671 0.7052917 0.7045657 -0.1369646 0.7024662 0.6984139 -0.1369503 0.7024333 0.6984499 -0.194186 0.6974315 0.6898415 -0.1941775 0.6974371 0.6898382 -0.209468 0.9278815 0.3084788 -0.3282811 0.3494101 0.8775786 -0.2740305 0.249525 0.9287866 -0.1991773 0.2584407 0.9452708 -0.213603 0.3093347 0.926653 -0.1596512 0.2556992 0.9534828 -0.3841874 0.66938 0.6358699 -0.3841649 0.6694269 0.6358341 -0.2803472 0.9302898 0.2365722 -0.2744447 0.9344895 0.2267366 0.2960196 0.9285393 0.2240255 0.2486028 0.9376549 0.2428989 0.2480753 0.9405214 0.2321168 0.1781423 0.951061 0.2524845 0.1784364 0.9530773 0.2445486 0.1352139 0.9580124 0.2528427 0.1364589 0.9581459 0.2516656 0.09299409 0.961416 0.2589046 0.09356856 0.9624598 0.2547863 0.01882749 0.9653626 0.260232 0.01900947 0.9655823 0.2594023 -0.05571192 0.9646374 0.2576255 -0.0564602 0.9639546 0.2600073 -0.0973767 0.9619691 0.2552126 -0.09849673 0.9617535 0.2555947 -0.1379737 0.9583299 0.2501346 -0.1403121 0.9565029 0.2557629 -0.2101144 0.947912 0.239405 -0.2922304 0.6854383 0.666915 -0.292242 0.6854046 0.6669446 -0.3013086 0.2546216 0.918902 -0.3979135 0.237731 0.8860863 -0.3963176 0.2495035 0.8835613 0.05329132 -0.983748 0.1714647 -0.04594731 -0.9925914 0.1124778 -0.008681297 -0.9952632 -0.09682941 0.0114355 -0.9909538 0.1337163 0.05896097 -0.9815801 -0.1817255 0.05585461 -0.9907986 0.123282 -0.08170652 -0.5576969 0.8260136 -0.08153373 -0.5574914 0.8261693 -0.01702648 -0.832964 0.5530651 -0.01735138 -0.8331412 0.5527882 0.05042809 -0.9795497 0.1947809 0.04944384 -0.9797919 0.193812 0.04492247 -0.9799794 0.1939647 0.0457974 -0.9797569 0.1948822 -0.01570034 -0.8328599 0.5532613 -0.01540648 -0.8326593 0.5535715 -0.07391691 -0.5570738 0.8271669 -0.07429307 -0.5574331 0.8268911 -0.06273066 -0.2175275 0.9740363 -0.1120299 -0.194976 0.974389 -0.1207564 -0.1966766 0.9730038 -0.1290381 -0.1917924 0.9729157 -0.132991 -0.1954399 0.9716566 -0.004471302 -0.9808952 0.1944855 -0.004581332 -0.981 0.1939542 0.001560151 -0.8314306 0.5556265 0.001514256 -0.8315203 0.5554924 0.007348835 -0.5550108 0.8318108 0.007377862 -0.5548831 0.8318957 0.05952638 -0.555442 0.8294221 0.05913537 -0.5566036 0.8286709 0.01221579 -0.8326947 0.5535976 0.01266938 -0.8318893 0.5547971 -0.0370264 -0.9807335 0.1918092 -0.03569442 -0.9799758 0.1958917 0.02708661 -0.9809477 0.1923751 0.02740687 -0.9803023 0.1955918 -0.009337902 -0.8322274 0.5543559 -0.009240508 -0.8316327 0.5552492 -0.0443505 -0.5551411 0.8305729 -0.04444676 -0.5559626 0.8300182 -0.07396316 -0.1670379 0.9831723 0.01178252 -0.2164775 0.9762166 0.02194797 -0.17072 0.9850751 0.09474635 -0.2185078 0.9712248 0.1023201 -0.1926999 0.9759085 -0.282504 -0.2037153 0.9373855 -0.005234241 -0.8368682 0.5473796 0.1023665 -0.938813 0.3288637 0.116948 -0.9453231 0.3044461 -0.1189417 -0.9635544 0.239616 -0.06225407 -0.9623793 0.2644817 -0.08513849 -0.972649 0.2161138 -0.03919947 -0.9750697 0.218409 -0.1128959 -0.9173848 0.3816539 -0.1291415 -0.9372136 0.3239648 -0.1163982 -0.9317462 0.3439484 -0.1181097 -0.9494364 0.2908961 -0.07646995 -0.9419509 0.3269266 0.138605 -0.5710647 0.8091193 -0.03954446 -0.9747168 0.2199169 0.01014125 -0.9756768 0.2189796 0.009795546 -0.9759518 0.2177663 0.04959225 -0.9743196 0.2196406 0.05532562 -0.9706439 0.2340717 0.07191467 -0.973512 0.2170316 0.09256488 -0.9590009 0.2678605 0.08828699 -0.9576473 0.2740749 0.1045028 -0.9550604 0.2773784 0.0307461 -0.8197326 0.5719206 0.01578104 -0.8073338 0.5898841 0.02409529 -0.8058997 0.5915614 0.01441758 -0.7950931 0.6063162 0.01422262 -0.7951137 0.6062937 0.009696543 -0.7885327 0.6149164 0.002464413 -0.7888542 0.6145756 0.001840412 -0.7876564 0.6161121 -0.009334266 -0.7874414 0.6163188 -0.007576227 -0.7926652 0.6096101 -0.01812368 -0.791746 0.6105815 -0.01562249 -0.8015255 0.5977566 -0.02267956 -0.8004924 0.5989137 -0.02105563 -0.8141273 0.5803047 -0.02403247 -0.8135191 0.5810415 -0.0246542 -0.829991 0.5572317 -0.01778227 -0.8317745 0.5548288 -0.01767522 -0.8323238 0.554008 0.1281675 -0.9367255 0.3257584 0.05025851 -0.8449587 0.5324649 0.01535421 -0.8233196 0.5673705 -0.1418862 -0.5368574 0.8316565 -0.09514677 -0.5258083 0.8452649 -0.1142953 -0.5000064 0.8584463 -0.06324762 -0.4911425 0.8687801 -0.07599174 -0.4691988 0.8798169 -0.03333097 -0.4645515 0.8849186 -0.03949612 -0.4513449 0.8914752 -0.005654871 -0.4498302 0.8930962 -0.006515681 -0.4474861 0.8942672 0.02347654 -0.4480543 0.8936982 0.02601385 -0.4583526 0.8883897 0.05462157 -0.4608778 0.8857812 0.05843961 -0.4798868 0.875382 0.08718657 -0.4841126 0.8706512 0.09020322 -0.5105091 0.8551281 0.1223279 -0.5171051 0.8471354 0.1228455 -0.5488818 0.826824 0.158304 -0.5582057 0.8144608 0.2857797 -0.2078134 0.9354911 -0.1402874 -0.566977 0.8116997 -0.2798814 -0.1570548 0.9471009 -0.2033649 -0.1390514 0.9691788 -0.224274 -0.1015657 0.9692191 -0.1382852 -0.08654755 0.9866036 -0.1527433 -0.05507326 0.9867302 -0.07416689 -0.04642575 0.9961647 -0.08157235 -0.02755433 0.9962866 -0.01259285 -0.02441787 0.9996226 -0.01370352 -0.02105587 0.9996844 0.05142307 -0.02229017 0.9984283 0.05502176 -0.03690195 0.9978031 0.1162398 -0.04229509 0.9923202 0.1224179 -0.0693444 0.9900532 0.179863 -0.07782769 0.9806081 0.186256 -0.1154016 0.9757004 0.2454932 -0.127615 0.9609618 0.2502277 -0.1731013 0.9525871 0.3075724 -0.1882473 0.9327176 0.3833748 0.1907407 0.9036823 0.404831 0.2137181 0.889065 0.3184441 0.2362263 0.9180363 0.340092 0.2810143 0.8974233 0.2352871 0.3027227 0.9235795 0.2525215 0.3404036 0.9057364 0.1537181 0.3550823 0.9221103 0.1656706 0.3829704 0.9087833 0.06874805 0.3914778 0.9176159 0.07426989 0.4072248 0.9103032 -0.01703655 0.4090831 0.9123381 -0.0183534 0.4053043 0.9139977 -0.1010777 0.4015622 0.9102368 -0.1080383 0.3794376 0.9188879 -0.18908 0.3704998 0.9093838 -0.1998689 0.3315061 0.9220391 -0.2783725 0.317807 0.9063705 -0.2908496 0.268402 0.9183501 -0.3670933 0.2504603 0.8958305 -0.3786773 0.1930919 0.9051625 -0.002480208 -0.4140084 -0.9102697 -0.001601099 -0.4049223 -0.9143498 -0.002561748 -0.3809993 -0.9245718 -9.25459e-4 -0.1691457 -0.9855907 -0.002649545 -0.3967318 -0.9179307 -0.002971947 -0.3893287 -0.9210942 7.28883e-4 -0.1308758 -0.9913985 -9.64285e-4 -0.1308671 -0.9913995 -6.83022e-4 -0.142785 -0.9897536 -0.03701007 -0.4012448 -0.915223 -0.07347887 -0.1184534 -0.9902372 -0.03453654 -0.1425494 -0.989185 -0.0505619 -0.4053219 -0.9127748 -0.01371729 -0.4139353 -0.910203 -0.9582095 -0.1439321 -0.2472206 -0.8576077 -0.2682096 -0.4388313 -0.8305163 0.04068702 -0.5555065 -0.8804914 -0.2230681 -0.4183008 -0.2532153 -0.3731732 -0.8925379 -0.4034184 -0.3735857 -0.8352769 -0.4673203 -0.2905651 -0.8349754 -0.5518301 -0.3236089 -0.7686097 -0.7012786 -0.2861908 -0.6529189 -0.6833485 -0.1882299 -0.7054108 -0.7554137 -0.2504462 -0.6054974 -0.2150693 -0.1331502 -0.9674793 -0.197308 -0.4151217 -0.8881125 -0.1362622 -0.3062369 -0.9421526 -0.2657258 -0.05979835 -0.9621923 -0.4882046 -0.1045133 -0.8664486 -0.5513474 0.006905615 -0.8342472 -0.7428026 -0.0704559 -0.665793 -0.8010554 0.05012845 -0.5964877 -0.9063257 -0.04665666 -0.4199966 -0.9463961 0.06316882 -0.3167716 -0.97638 -0.01274311 -0.2156848 -0.9936623 0.03006047 -0.1083135 -0.9999814 -0.003228545 -0.005180418 -0.9996067 0.02198088 -0.01741611 -0.9994065 0.02983939 -0.01721757 -0.9967468 -0.00815922 -0.08018273 -0.9974151 -0.007059216 -0.07150906 -0.9598559 -0.1631753 -0.2281458 -0.007407248 -0.1678774 -0.9857801 -0.00264889 -0.395563 -0.918435 -0.00428611 -0.1229755 -0.9924005 -0.004310071 -0.1229738 -0.9924006 -0.003963053 -0.1378414 -0.9904465 -0.004271566 -0.1378401 -0.9904453 -0.003952682 -0.1413261 -0.9899552 -0.001136302 -0.3614771 -0.9323803 -0.003538846 -0.3614932 -0.9323682 -0.00256139 -0.4030191 -0.915188 -0.003425121 -0.4030176 -0.9151859 -0.002479672 -0.412668 -0.9108781 -0.007082343 -0.1413348 -0.9899366 -0.008187592 -0.141 -0.9899758 -0.01030254 -0.4126663 -0.9108241 -0.0137512 -0.4118143 -0.911164 -0.02579998 -0.1403431 -0.9897667 -0.02570199 -0.1403779 -0.9897643 -0.02791404 -0.4113009 -0.9110722 -0.03673213 -0.409412 -0.91161 -0.1263342 -0.1371818 -0.9824566 -0.1206815 -0.405911 -0.9059097 -0.1303327 -0.3962953 -0.9088253 -0.2396066 -0.3928955 -0.8878186 -0.2515263 -0.3867006 -0.8872413 -0.3903747 -0.3777975 -0.8395695 -0.4072663 -0.3536824 -0.8420469 -0.5330056 -0.3469392 -0.7717114 -0.5487925 -0.3366501 -0.7651755 -0.1260071 -0.1375463 -0.9824476 -0.2530496 -0.1329578 -0.9582736 -0.2527388 -0.133123 -0.9583326 -0.4125364 -0.1246958 -0.9023662 -0.4122916 -0.1251458 -0.9024158 -0.5589483 -0.1158452 -0.8210706 -0.5588205 -0.1159162 -0.8211475 -0.6895635 -0.1040209 -0.7167161 -0.6895369 -0.1040522 -0.7167371 -0.801203 -0.09040325 -0.5915245 -0.8013681 -0.0901817 -0.5913346 -0.8895395 -0.07404881 -0.4508174 -0.8894306 -0.07465332 -0.4509325 -0.6533133 -0.3261089 -0.683253 -0.6570608 -0.3409112 -0.6723472 -0.7478321 -0.280687 -0.6016327 -0.7770789 -0.2765796 -0.5653781 -0.7922603 -0.2603765 -0.5518404 -0.8680239 -0.2453269 -0.4316818 -0.888658 -0.1870332 -0.4186952 -0.9609139 -0.1578171 -0.2274608 -0.9999828 -0.002748608 -0.005196988 -0.9997495 -0.004883348 -0.02184545 -0.9996737 -0.01020449 -0.0234183 -0.9965006 -0.01757973 -0.08171623 -0.9953238 -0.03997474 -0.0879355 -0.9677299 -0.06025159 -0.2446806 -0.9691058 -0.04281139 -0.2429014 -0.8233854 0.5618284 -0.07990938 -0.9802141 0.1978116 -0.007149696 -0.5427026 0.8394169 -0.02920907 -0.543751 0.8386743 -0.0309897 -0.9801596 0.1980919 -0.006845593 -0.9801294 0.1964534 -0.02743154 -0.9798026 0.1982361 -0.02625441 -0.535726 0.8369387 -0.111943 -0.5422946 0.8316819 -0.1192554 -0.8260659 0.5585847 -0.07482075 -0.826193 0.5630449 -0.01964223 -0.8266262 0.5623726 -0.02064585 -0.5080503 0.8240328 -0.2507091 -0.5339708 0.8041081 -0.2613147 -0.8114489 0.5590327 -0.1703915 -0.8221026 0.541868 -0.1747185 -0.9783521 0.1981789 -0.05960279 -0.9796597 0.1913028 -0.06058245 -0.8044968 0.4676749 -0.366149 -0.007466495 0.01243001 -0.999895 -0.4828874 0.7586574 -0.4373312 -0.4506067 0.6837554 -0.5739619 -0.4493288 0.6871531 -0.5708978 -0.4036307 0.607473 -0.6841483 -0.411037 0.5968357 -0.6890833 -0.3570985 0.5283019 -0.7703103 -0.3576999 0.5167377 -0.7778387 -0.2964686 0.4428696 -0.8461518 -0.3144384 0.4135774 -0.8544486 -0.2403477 0.3369437 -0.9103308 -0.2439728 0.321104 -0.915079 -0.1619362 0.2387403 -0.9574862 -0.1824543 0.2070776 -0.9611604 -0.07232725 0.1052939 -0.9918075 -0.08577823 0.08501613 -0.9926804 -0.0325936 0.04069149 -0.9986401 -0.0340774 0.03684192 -0.99874 -0.02032047 0.02672249 -0.9994364 -0.02237039 0.02010601 -0.9995477 -0.01299488 0.01755899 -0.9997614 -0.5071147 0.7341966 -0.4514313 -0.7715533 0.5324329 -0.3481679 -0.7404633 0.4519902 -0.4974123 -0.7152352 0.4494741 -0.5351744 -0.6721314 0.3784792 -0.6363906 -0.6283057 0.3965871 -0.6692911 -0.5778198 0.3310561 -0.7460069 -0.5580908 0.3283066 -0.7620692 -0.4948361 0.2543332 -0.8309344 -0.4534914 0.2759931 -0.8474511 -0.3791406 0.1982584 -0.9038506 -0.3596692 0.2024326 -0.9108563 -0.2761901 0.1197128 -0.9536184 -0.2360308 0.1479608 -0.9604151 -0.1261713 0.04620969 -0.9909316 -0.1011409 0.06631517 -0.9926595 -0.04759013 0.02175229 -0.9986302 -0.04407221 0.02418339 -0.9987357 -0.02819454 0.01243013 -0.9995253 -0.02690964 0.01345479 -0.9995474 -0.01638108 0.01039701 -0.9998118 -0.01388353 0.0126096 -0.9998241 -0.01103794 0.0127483 -0.9998579 -0.01137113 0.01192909 -0.9998642 -0.009980559 0.01246154 -0.9998726 -0.01359319 0.005448043 -0.9998928 -0.00425142 0.01126921 -0.9999275 -0.0151357 0.002871632 -0.9998813 -0.03175997 0.007362723 -0.9994684 -0.036116 -9.91471e-4 -0.9993472 -0.05505198 0.01304137 -0.9983983 -0.06229794 0.002092003 -0.9980555 -0.1195293 0.0499233 -0.9915747 -0.1814203 -0.01101309 -0.983344 -0.2960916 0.09558349 -0.950365 -0.3825976 -0.002856314 -0.9239107 -0.4790984 0.09209722 -0.8729164 -0.4920148 0.040627 -0.8696385 -0.5906811 0.1451982 -0.7937338 -0.6463075 0.03648364 -0.7622044 -0.7352106 0.138638 -0.6635096 -0.7296243 0.08299726 -0.678793 -0.8105877 0.190852 -0.5536456 -0.8391384 0.07909798 -0.5381359 -0.9080635 0.1904347 -0.3730356 -0.906677 0.1220347 -0.4037876 -0.9498208 0.2319373 -0.2098705 -0.967229 0.1246954 -0.2211765 -0.01546263 0.1957147 0.980539 0.002351343 0.1678783 0.985805 -0.03496384 0.5569436 0.8298141 0.02514827 0.4845091 0.8744248 -0.05685889 0.8323298 0.5513566 -0.0124852 0.800686 0.5989543 -0.03160381 0.8329188 0.5524922 -0.03153383 0.8329654 0.5524258 -0.04175871 0.5569599 0.8294889 -0.04180651 0.5568634 0.8295513 -0.04558205 0.1957015 0.9796036 -0.04570084 0.195523 0.9796338 -0.6196883 0.5813112 0.5273174 -0.9557857 0.2130666 0.2026733 -0.966679 0.2117169 0.1439018 -0.7831569 0.6111913 0.1145012 -0.452906 0.8896616 0.05812436 -0.4379701 0.8974686 0.05227214 -0.9534087 0.1587675 0.2565245 -0.9468563 0.2105389 0.2431802 -0.9186211 0.2121148 0.3333808 -0.4721325 0.8782908 0.07547473 -0.4660832 0.8785774 0.1042515 -0.4735639 0.874515 0.1046935 -0.4570618 0.8755059 0.1567922 -0.4624194 0.8725919 0.1573267 -0.4445878 0.8730292 0.2004039 -0.4497262 0.8701763 0.2013447 -0.4291201 0.8704311 0.2412584 -0.4340689 0.8676007 0.2425969 -0.9652717 0.2174659 0.144773 -0.7927668 0.5989242 0.1131848 -0.776929 0.600292 0.189818 -0.7799288 0.5957486 0.1918199 -0.7558847 0.5972147 0.268278 -0.7577906 0.5939997 0.270033 -0.7311558 0.5946418 0.3343836 -0.7327789 0.5916451 0.3361417 -0.7014341 0.5920263 0.3968566 -0.7028334 0.5891629 0.3986384 -0.6669332 0.58942 0.4558335 -0.8059245 0.2085929 0.554053 -0.8499866 0.2082805 0.4838823 -0.8495442 0.2097454 0.4840264 -0.8755638 0.2095978 0.4352665 -0.8938943 0.1719093 0.4140052 -0.8929684 0.2108424 0.3976848 -0.9191873 0.2101051 0.3330929 -0.3840536 0.8647717 0.3235319 -0.7452979 0.1193383 0.6559646 -0.7738953 0.2075582 0.5983358 -0.8063673 0.2071743 0.553941 -0.3913528 0.8598306 0.3279244 -0.3488116 0.8603516 0.3716527 -0.3566442 0.8544016 0.3778927 -0.3167161 0.8553903 0.4098764 -0.3218358 0.8513936 0.4141867 -0.2786716 0.8522148 0.4428004 -0.2871916 0.8437638 0.4534133 -0.2272925 0.845508 0.4831711 -0.2342038 0.8370234 0.4945104 -0.5511427 0.5821518 0.5977801 -0.5531314 0.576058 0.6018331 -0.4898373 0.577658 0.6529706 -0.4905831 0.5734397 0.6561214 -0.4225569 0.5747137 0.7008209 -0.4240047 0.5660055 0.7070062 -0.3341177 0.5686588 0.7516598 -0.3347268 0.5598934 0.757943 -0.2536337 0.5626507 0.7868254 -0.4108433 0.8677718 0.279607 -0.4158743 0.8647752 0.2814471 -0.6682488 0.5863729 0.4578323 -0.6175979 0.5863191 0.5242164 -0.7438219 0.2048922 0.6361982 -0.6583575 0.2059234 0.7239897 -0.6592122 0.2024897 0.7241804 -0.5797156 0.2042303 0.7888092 -0.580486 0.2015914 0.7889214 -0.4943253 0.2034833 0.8451256 -0.4954997 0.1980095 0.8457378 -0.3845939 0.2013116 0.9008669 -0.3856988 0.1955681 0.9016593 -0.2877292 0.1986323 0.936887 -0.1901027 0.1315768 0.9729073 -0.2356221 0.1967782 0.9517146 -0.2885736 0.1952384 0.9373406 -0.072429 0.8321455 0.5498072 -0.07185918 0.8333372 0.5480743 -0.1286886 0.8355911 0.5340663 -0.1307754 0.8321782 0.5388667 -0.179499 0.5558102 0.811699 -0.09752225 0.5574087 0.8244907 -0.09794265 0.5559503 0.8254251 -0.1774688 0.8389443 0.514468 -0.1810839 0.8343139 0.5207005 -0.2531903 0.5577707 0.7904344 -0.1799367 0.5595585 0.8090223 -0.20179 0.194552 0.9599117 -0.1081954 0.1964073 0.9745347 -0.1085042 0.1948804 0.974807 -0.4456707 0.8943663 0.03855621 -0.4552016 0.8897004 0.03499668 -0.7888258 0.6115012 0.06180799 -0.7852545 0.6163647 0.05890768 -0.9733279 0.2175335 0.07288306 -0.9729713 0.2194005 0.07204347 -0.9751568 0.2198126 0.02741879 -0.974912 0.2208372 0.02788478 -0.7867389 0.6166406 0.02821707 -0.7837786 0.6203071 0.03017199 -0.4464071 0.8945218 0.02348506 -0.4388065 0.8981828 0.02676731 -0.975551 0.2197493 0.003249645 -0.4465819 0.8945813 0.01700037 -0.5440983 0.8390073 0.004880249 -0.8268688 0.5623856 0.003275096 -0.819119 0.5736125 0.003578245 -0.9802457 0.1977805 0.001130461 -0.4330081 0.9012652 0.01500731 -0.5249093 0.8511414 0.005352973 -0.5249112 0.8511117 0.008789598 -0.5013816 0.8651551 0.01110106 -0.4178491 0.9084041 0.01428472 -0.7870773 0.6167949 0.008570492 -0.8191221 0.5735525 0.008757472 -0.9793384 0.2022112 0.002662718 -0.9793367 0.2022329 0.001233935 -0.9751673 0.2214072 0.005273044 -0.9755548 0.2196984 0.005041956 -0.7838854 0.620725 0.01497346 -0.7870898 0.6166726 0.01430529 -0.4388143 0.8983138 0.02177959 -0.4465857 0.8945008 0.02072751 -0.9802479 0.1977674 0.001492977 -0.9802463 0.1977781 0.001101553 -0.8268269 0.5624457 0.003484129 -0.826817 0.5624573 0.003934085 -0.5441965 0.8389375 0.005823731 -0.5441074 0.8389979 0.005465149 -0.9802539 0.1977387 0.001322329 -0.9802467 0.1977738 0.001373052 -0.8269175 0.5623092 0.003993749 -0.8268483 0.5624136 0.003595829 -0.543991 0.8390731 0.005493819 -0.5441357 0.8389812 0.00519365 0.009547114 0.9588631 0.2837084 0.008132278 0.9586752 0.2843869 0.02093642 0.9585726 0.2840783 0.02049559 0.9585132 0.2843102 0.004868626 0.004803299 -0.9999767 0.0047279 0.004797995 -0.9999774 0.004727244 0.004802405 -0.9999774 0.004750013 0.004805028 -0.9999772 0.004706799 0.004803121 -0.9999774 0.004727244 0.004802703 -0.9999773 0.004726529 0.004803299 -0.9999773 0.004722654 0.004803478 -0.9999774 0.004729509 0.004802584 -0.9999774 0.004725813 0.004803299 -0.9999774 0.004723906 0.004802942 -0.9999774 0.004729211 0.00480318 -0.9999773 0.004725158 0.004803597 -0.9999773 0.004726946 0.004798352 -0.9999774 0.004725813 0.004804313 -0.9999773 0.004735112 0.004807889 -0.9999772 0.00472933 0.004802703 -0.9999773 0.004727363 0.004807412 -0.9999774 0.004728436 0.004802465 -0.9999773 0.00472337 0.004803836 -0.9999774 0.004729568 0.004802823 -0.9999773 0.004530906 0.00486803 -0.999978 0.004723846 0.004803121 -0.9999774 0.004721105 0.004802584 -0.9999774 0.004727542 0.004805564 -0.9999774 0.00472337 0.004803597 -0.9999774 0.004730522 0.004802405 -0.9999773 0.004726767 0.004803895 -0.9999773 0.004733264 0.004800856 -0.9999773 0.004717886 0.004810333 -0.9999774 0.004727065 0.004795789 -0.9999774 0.004725515 0.004806697 -0.9999773 0.004724681 0.004803001 -0.9999773 0.004725277 0.004804015 -0.9999773 0.004729747 0.004802942 -0.9999773 0.004721939 0.004803478 -0.9999774 0.004733622 0.004802167 -0.9999773 0.004716038 0.004803299 -0.9999774 0.3534865 0.9348272 -0.03384488 0.1134533 0.4785016 -0.8707265 0.01700907 0.05226272 -0.9984886 0.2772613 0.5830206 -0.763684 0.365769 0.4533981 -0.8127997 0.2542942 0.4727657 -0.8436985 0.01828271 0.02747958 -0.9994552 0.0110135 0.01824027 -0.999773 0.009565353 0.01424932 -0.9998527 0.01020216 0.01625573 -0.9998158 0.01236701 0.022646 -0.9996671 0.01327854 0.02251839 -0.9996583 0.01765078 0.03150355 -0.9993479 0.02682954 0.04812371 -0.998481 0.06618362 0.1117058 -0.991535 0.1355563 0.164339 -0.9770452 0.1159172 0.2886962 -0.9503777 0.1693226 0.4029968 -0.8994018 0.1014449 0.1770551 -0.9789589 -0.002516627 0.3580378 -0.9337038 0.02562659 0.1622273 -0.9864206 0.2248 0.8688966 -0.4410033 0.1706265 0.819651 -0.5468627 0.1772829 0.8102284 -0.5586598 0.1885621 0.7406896 -0.6448436 0.164655 0.5363666 -0.8277679 0.0921449 0.6368952 -0.765424 0.1118409 0.5083497 -0.8538572 0.2518761 0.9674712 -0.02362102 0.2190971 0.9574081 -0.1880592 0.2245808 0.9547544 -0.1949554 0.2366583 0.9041035 -0.3557947 0.2047481 0.7264772 -0.6559796 0.6627594 0.5161111 -0.5425674 0.9792503 -0.02517187 -0.2010855 0.3225195 0.8287938 -0.4572549 0.3030335 0.9340344 -0.1890782 0.7083392 0.6794233 -0.1914151 0.4591906 0.8801679 -0.1202021 0.04225349 0.9582043 0.2829475 0.04498159 0.9593661 0.2785562 0.07128101 0.9572505 0.2803401 0.08324116 0.9619204 0.2603461 0.07841646 0.9593543 0.2710912 0.1020394 0.9576961 0.269084 0.1055794 0.959852 0.2598794 0.1245535 0.9585234 0.2563583 0.129294 0.9628329 0.2371416 0.1437979 0.959658 0.241617 0.1548148 0.9637341 0.2173684 0.1554537 0.9628082 0.2209852 0.1676636 0.9629527 0.2112134 0.1697447 0.9643499 0.2030178 0.1798177 0.962208 0.2045025 0.1811991 0.9672322 0.1778448 0.1865372 0.9641524 0.188717 0.1992896 0.9654729 0.1677672 0.1943457 0.9680134 0.1586823 0.2134218 0.9646755 0.1544418 0.2061112 0.9703556 0.1262075 0.2362024 0.9587899 0.1578935 0.211112 0.9719061 0.1040684 0.25031 0.9583074 0.1378113 0.2165521 0.9729014 0.08104342 0.274573 0.9540477 0.1200108 0.2262361 0.9718527 0.06572318 0.2384346 0.9682809 0.07470673 0.2568085 0.9648962 0.05499947 0.2340012 0.9713863 0.04064548 0.2557653 0.9660109 0.03751111 0.2489529 0.9679889 0.03193891 0.242677 0.9694873 0.03467398 0.2464062 0.9686213 0.03250974 0.2469167 0.9686709 0.02662527 0.2364666 0.9713603 0.0232976 0.236565 0.9713897 0.02095782 0.2278209 0.9734572 0.02188217 0.221373 0.9749744 0.02046996 0.217167 0.9758637 0.0229938 0.2180286 0.9756648 0.02327847 0.2369269 0.9714537 0.01198124 0.2368301 0.9713971 0.01729989 0.2270446 0.9737553 0.01586341 0.2268813 0.9736996 0.02083605 0.2186528 0.9756094 0.01942396 0.2093845 0.9775445 0.02376699 0.2654472 0.9641175 0.00392735 0.2488182 0.9685314 0.006035327 0.2682762 0.9633085 0.008046329 0.2542246 0.9670837 0.01090967 0.2541825 0.9670622 0.01349312 0.2654747 0.9640946 0.006702482 0.200374 0.6919398 -0.6935917 0.3536118 0.9353705 0.006385743 0.9981104 -0.02616542 0.05559724 0.9825065 -0.1786729 0.05250799 0.8505628 -0.5258064 -0.00841391 0.1441544 -0.9808985 -0.1306049 0.7065211 -0.7061461 -0.04675 0.989866 -0.1287495 0.05990898 0.8183441 0.2098243 0.5350579 0.9296504 0.1183519 0.3489167 0.8508559 0.2880504 0.439399 0.9945717 0.1037332 0.00816071 0.9651733 0.261509 0.007328331 0.9443929 0.3287444 0.007010042 0.9363072 0.3510228 0.01057368 0.9934328 0.1138892 0.01098209 0.9967133 0.07878047 0.01887714 0.9994162 0.02943557 0.01734364 0.9972468 0.07376182 0.007628381 0.9994959 0.03047221 0.008922517 0.9999867 0.004358053 0.002784729 0.9896944 -0.1419042 0.01918947 0.9553056 -0.2942963 0.027947 0.6329528 -0.7737916 -0.02485352 0.6881254 -0.7253647 -0.01815116 0.6890933 -0.7244973 -0.01593971 0.7815315 -0.6236488 -0.01645976 0.7793011 -0.6262736 -0.02171039 0.8616606 -0.5074207 0.008089661 0.8556575 -0.5175207 -0.004769563 0.9004414 -0.4349748 0.001503586 0.597094 -0.8021235 -0.008761227 0.5901759 -0.807273 0.001668274 0.5120235 -0.8563006 -0.06768548 0.4959729 -0.8681445 -0.01833915 0.4512059 -0.8918617 -0.03156095 0.3932436 -0.9185997 -0.03917032 0.2980058 -0.953635 -0.04210454 0.3440393 -0.937668 -0.04915058 0.3547164 -0.9337601 -0.04762822 0.1898001 -0.9792904 -0.07047146 0.2023529 -0.9771947 -0.06437361 0.1588382 -0.9842941 -0.07704269 0.1355566 -0.9892098 -0.05557566 0.1169195 -0.9853521 -0.1241421 0.1271991 -0.9843413 -0.1220349 0.108784 -0.987158 -0.1169847 0.1327615 -0.9839913 -0.1188927 0.07706367 -0.9913015 -0.1066894 0.0894069 -0.9898434 -0.1105284 0.06180715 -0.9925252 -0.1052321 0.01863718 -0.9952226 -0.09583622 0.003027379 -0.995209 -0.09772372 0.01819324 -0.9938596 -0.1091425 0.0137096 -0.9998505 0.01054757 0.01498979 -0.9987662 0.04734498 0.02476847 -0.9969334 0.07423365 0.006691217 -0.9964393 0.08404815 0.02756464 -0.9901371 0.1373643 0.0128135 -0.9891951 0.1460445 0.05165898 -0.9574463 0.2839508 0.02918809 -0.9667768 0.2539502 0.02328211 -0.9691717 0.245284 0.03464514 -0.6325609 0.7737355 0.03296935 -0.4744428 0.8796687 0.03870868 -0.2837921 0.9581043 0.05230742 -0.06737816 0.9963554 0.04736471 0.1632132 0.9854533 0.02895963 0.1818488 0.9829 0.1477149 0.1868316 0.9712231 0.1348772 0.1597512 0.9778997 0.2271314 0.2019369 0.9526977 0.2575019 0.1671698 0.9517074 0.292611 0.1983767 0.935428 0.4457213 0.2193722 0.8678758 0.4642135 0.1888369 0.8653592 0.4246724 0.2193949 0.8783617 0.3535081 0.2164873 0.9100359 0.3889852 0.1489666 0.9091203 0.3364119 0.2000033 0.9202313 0.5290216 0.2377578 0.8146211 0.539384 0.2207877 0.8125994 0.4963212 0.2460383 0.8325447 0.6066539 0.2496405 0.7547522 0.6084699 0.2467128 0.7542529 0.5689719 0.2631843 0.7791054 0.6791837 0.2565192 0.6876828 0.6741578 0.2644926 0.6896049 0.6377923 0.2736269 0.7199648 0.7463799 0.2610024 0.612205 0.7355682 0.2780029 0.6177815 0.702908 0.2790793 0.654244 0.8264787 0.2925527 0.4809846 0.8184484 0.2847216 0.4990751 0.8072639 0.2654784 0.5271113 0.7912061 0.2908183 0.5379756 0.7635832 0.2821045 0.5808252 0.8919985 0.2980381 0.3398706 0.8712961 0.3039393 0.3853103 0.9394007 0.2835993 0.1926079 0.9174662 0.3177847 0.239309 0.9037202 0.323942 0.2799137 0.9408593 0.3350967 0.04993975 0.9474818 0.3170408 0.04199218 0.9970237 0.04358786 0.06359183 0.8787238 -0.1713894 0.4454999 0.9886633 -0.1354609 0.064772 0.9894475 -0.1303389 0.06329053 0.9931311 -0.09639364 0.06632518 0.9743067 -0.177925 0.1380913 0.976168 -0.1691241 0.1359889 0.981357 -0.1303974 0.1411917 0.9825971 -0.1230855 0.1391153 0.9862235 -0.08304959 0.1430602 0.9814552 -0.1824334 0.05885541 0.9812377 -0.1850557 0.05410099 0.9795926 -0.1907202 0.06343847 0.9793773 -0.1935005 0.05811947 0.9611312 -0.2406268 0.1353722 0.9611623 -0.2453702 0.1263347 0.9214524 -0.3097463 0.2344841 0.8489127 -0.3184103 0.4218556 0.0652734 0.04737263 0.9967424 0.03712034 0.07155489 0.9967458 0.1536085 0.07766485 0.9850749 0.1421811 0.09004408 0.9857366 0.2618241 0.1014968 0.9597638 0.2485992 0.1154491 0.9617016 0.3610501 0.129242 0.9235472 0.3503395 0.1405753 0.9260134 0.4522268 0.1543211 0.8784509 0.4463279 0.160757 0.8803117 0.5366905 0.1728746 0.82588 0.5360603 0.1735908 0.8261391 0.6156583 0.1832833 0.7664022 0.6195131 0.1785416 0.7644125 0.6899648 0.1855706 0.6996514 0.6965094 0.1768141 0.6954218 0.7597316 0.1812091 0.6244769 0.7665396 0.1711376 0.6189742 0.8154549 0.1727759 0.5524327 0.8331535 0.123297 0.5391226 0.01734292 -0.03197175 0.9993384 0.1431226 -0.02796167 0.9893099 0.1465911 -0.02025663 0.9889898 0.2504441 -0.01423758 0.9680264 0.2545908 -0.005378842 0.967034 0.3540546 0.001817822 0.9352231 0.3576914 0.009407937 0.9337925 0.4525136 0.01693367 0.8915967 0.4546725 0.02151566 0.8903989 0.544768 0.02891534 0.8380882 0.5450322 0.02952468 0.8378951 0.6301062 0.0365765 0.7756471 0.6286917 0.03313326 0.7769485 0.7080356 0.03972876 0.7050584 0.7056084 0.03296792 0.7078347 0.7780789 0.03904527 0.6269519 0.7755926 0.03068119 0.6304879 0.8396872 0.03617942 0.5418639 0.8379912 0.02888423 0.5449187 0.8917012 0.03365433 0.4513718 0.8858092 0.1253865 0.446789 0.8852024 0.1188057 0.4497799 0.8727706 0.2060284 0.4425202 0.9363051 0.002402722 0.3511797 0.8995497 -0.002806127 0.4368094 0.8901181 -0.04883325 0.4531061 0.8397613 -0.05551689 0.54011 0.8366057 -0.06653022 0.5437506 0.7776263 -0.07224786 0.6245619 0.7742578 -0.08194619 0.6275426 0.7070022 -0.08664673 0.7018834 0.7038428 -0.09448426 0.7040441 0.6285413 -0.09814602 0.771559 0.6259647 -0.1038686 0.7729033 0.542859 -0.1065053 0.8330432 0.5411002 -0.1101011 0.8337197 0.4505754 -0.1117635 0.8857149 0.4497307 -0.1133824 0.8859384 0.3524186 -0.114182 0.9288507 0.3523927 -0.1142445 0.9288528 0.2493719 -0.1143611 0.9616316 0.2498338 -0.1135146 0.9616119 0.1427114 -0.1132219 0.9832672 0.1431605 -0.1123574 0.9833011 0.05000829 -0.1121587 0.9924312 0.0359407 -0.1778398 0.9834029 0.04784208 -0.1974748 0.9791399 0.1419059 -0.1967094 0.9701382 0.1413888 -0.1975634 0.9700402 0.2474078 -0.1957136 0.9489392 0.2468653 -0.1966494 0.9488871 0.3487927 -0.193517 0.9170032 0.348508 -0.1939953 0.9170105 0.4450331 -0.189479 0.875239 0.4452735 -0.1890498 0.8752095 0.5354681 -0.1830987 0.8244688 0.5363625 -0.181445 0.824253 0.6196806 -0.1740434 0.7653136 0.621222 -0.1709653 0.7647576 0.6972557 -0.1621262 0.6982476 0.6993585 -0.1575109 0.6972001 0.7677683 -0.1472666 0.6235739 0.7702411 -0.141135 0.6219402 0.830644 -0.129534 0.541527 0.8332344 -0.1220264 0.5392866 0.8851073 -0.1091281 0.4524117 0.8875218 -0.1005814 0.4496538 0.876696 -0.1771525 0.4472373 0.8230435 -0.197081 0.5326898 0.821285 -0.2012571 0.5338416 0.7593193 -0.2192575 0.6126666 0.7579585 -0.2220664 0.6133397 0.688363 -0.2381348 0.6851629 0.6874524 -0.239807 0.6854939 0.610756 -0.2539421 0.7499937 0.6102739 -0.2547454 0.7501137 0.5269068 -0.2669467 0.8069132 0.5268421 -0.2670549 0.8069195 0.4372752 -0.2772877 0.8555127 0.4374941 -0.276946 0.8555114 0.3422588 -0.2851595 0.8952894 0.342656 -0.2845817 0.8953213 0.2425014 -0.290709 0.9255709 0.2429578 -0.2900688 0.925652 0.1389947 -0.2940397 0.9456327 0.1392843 -0.2935825 0.9457322 0.04710352 -0.2953123 0.954239 0.03870964 -0.3811501 0.9237024 0.04929333 -0.3959608 0.9169434 0.1355696 -0.3937064 0.9091845 0.1349942 -0.3944637 0.9089417 0.2364584 -0.389224 0.8902764 0.2356063 -0.3903174 0.8900236 0.333609 -0.3822582 0.861733 0.3326287 -0.38353 0.8615468 0.4262223 -0.3727365 0.8242585 0.4253136 -0.3739437 0.8241811 0.5137847 -0.3604968 0.7785033 0.5131078 -0.361443 0.7785111 0.5959615 -0.3453812 0.7249426 0.5956656 -0.3458195 0.7249767 0.6724789 -0.3271396 0.6638914 0.6727094 -0.3267695 0.6638402 0.7430096 -0.3054312 0.5955238 0.7438117 -0.3039972 0.5952562 0.8070468 -0.2799272 0.5199193 0.8084565 -0.2770561 0.5192667 0.8638947 -0.2501819 0.4371445 0.8658138 -0.2455661 0.4359629 0.8464887 -0.3234922 0.422859 0.7895296 -0.3556355 0.5001665 0.7878119 -0.3587307 0.5006644 0.7238172 -0.3872504 0.5710743 0.7228641 -0.3887704 0.5712488 0.6525837 -0.4138612 0.6347075 0.6523739 -0.4141659 0.6347244 0.5763559 -0.4359921 0.6911763 0.5767689 -0.4354355 0.6911827 0.4954289 -0.4541131 0.7404941 0.4962962 -0.4530208 0.7405824 0.4100057 -0.4686006 0.7825018 0.4111323 -0.467231 0.7827294 0.3203215 -0.4797006 0.8168731 0.3215035 -0.4783021 0.8172286 0.2267317 -0.4876044 0.8431101 0.227776 -0.4863836 0.8435337 0.1298965 -0.492429 0.8606048 0.1305716 -0.4916236 0.8609631 0.04840481 -0.4942163 0.8679903 0.03174996 -0.5696049 0.8213052 0.04576748 -0.5875619 0.8078839 0.124235 -0.5847599 0.8016368 0.1235861 -0.5855123 0.8011878 0.2167568 -0.5789931 0.785992 0.2157841 -0.5800801 0.785458 0.3061853 -0.5700503 0.7624259 0.3050984 -0.5712604 0.7619558 0.3921001 -0.5577951 0.7315205 0.3910973 -0.5589346 0.7311874 0.4742377 -0.5420715 0.693727 0.4735575 -0.5428791 0.6935601 0.5525351 -0.5225845 0.6493154 0.5524099 -0.522745 0.6492928 0.6269538 -0.4988984 0.5983555 0.62755 -0.4981071 0.5983899 0.6973096 -0.4705064 0.5407246 0.6987878 -0.4683527 0.540686 0.7632658 -0.4367053 0.4761448 0.7656841 -0.4327658 0.4758591 0.8240942 -0.3967501 0.4042997 0.8274033 -0.3905577 0.4035698 0.880513 -0.3481412 0.321706 0.8978191 -0.282478 0.3378271 0.9007374 -0.2750589 0.336177 0.912522 -0.2158531 0.3474351 0.9147894 -0.2091325 0.3455779 0.9232448 -0.1495674 0.3539048 0.9253514 -0.1420133 0.351507 0.9302152 -0.08645004 0.3566876 0.9321786 -0.07737118 0.3536337 0.9337634 0.01022142 0.357745 0.04224509 -0.6585533 0.7513474 0.1182366 -0.6556054 0.7457893 0.1176096 -0.6563485 0.7452347 0.2063378 -0.6495097 0.731821 0.2053704 -0.6506066 0.7311185 0.2917311 -0.6400758 0.7107715 0.2905753 -0.6413695 0.7100782 0.3740878 -0.6272053 0.6831339 0.3729821 -0.628452 0.6825926 0.4533345 -0.6106581 0.6492955 0.4524834 -0.6116431 0.6489618 0.5295212 -0.5901196 0.6093983 0.5291298 -0.5905843 0.6092881 0.6026483 -0.5651433 0.5634077 0.6029883 -0.5647103 0.5634781 0.6726909 -0.5350592 0.5110761 0.6739161 -0.5333632 0.5112347 0.7393425 -0.4990951 0.45197 0.7415835 -0.4956664 0.4520717 0.8019125 -0.4563421 0.3856011 0.8051983 -0.4506479 0.3854508 0.8592298 -0.4058365 0.3114822 0.8797371 -0.362094 0.3081405 0.922266 -0.3142052 0.2251676 0.9416792 -0.233615 0.2422072 0.9443762 -0.2247061 0.2401267 0.9527207 -0.1754962 0.2480415 0.954674 -0.1677876 0.2458556 0.9606049 -0.1177107 0.2517588 0.9622144 -0.1097325 0.2492033 0.9655105 -0.06174343 0.2529375 0.1094828 -0.7427821 0.6605213 0.1105139 -0.7433546 0.6597051 0.1910852 -0.736564 0.6488142 0.1925527 -0.7373625 0.6474721 0.2703791 -0.7270434 0.6311126 0.2720013 -0.727929 0.6293923 0.3472258 -0.7141506 0.607802 0.3487744 -0.7150118 0.6058998 0.4216925 -0.6977106 0.5791161 0.4229996 -0.6984598 0.5772567 0.4939438 -0.6774091 0.5451024 0.4948418 -0.6779747 0.5435826 0.5641271 -0.652762 0.5056307 0.5645681 -0.6530705 0.5047393 0.6323237 -0.6231009 0.4603392 0.6322805 -0.6230757 0.4604326 0.6983962 -0.5875477 0.4086937 0.6979466 -0.5870686 0.4101477 0.7618311 -0.5450427 0.35006 0.7611286 -0.5439627 0.3532534 0.821627 -0.4943898 0.2837392 0.8209111 -0.4925015 0.2890458 0.8789453 -0.4308591 0.2044891 0.8786104 -0.4280399 0.2117207 0.9279891 -0.3547593 0.1139389 0.9282818 -0.3512992 0.1219916 0.9535042 -0.2970817 0.05071878 0.9539201 -0.2947592 0.0561552 0.9563701 -0.2882705 0.04750061 0.9567797 -0.2860664 0.05233234 0.9582772 -0.2819997 0.04670035 0.95068 -0.3073414 0.04182124 0.09988313 -0.824324 0.5572372 0.1008369 -0.824728 0.5564673 0.1741256 -0.8184276 0.5475916 0.1754859 -0.818978 0.546333 0.2462383 -0.8094654 0.5330409 0.2477887 -0.8100724 0.5313977 0.3162654 -0.7974349 0.5138813 0.3177867 -0.7980216 0.5120284 0.3843856 -0.7822059 0.4903079 0.3857065 -0.7827218 0.4884435 0.4508957 -0.7635071 0.4623314 0.45188 -0.7639143 0.4606945 0.5160889 -0.7408991 0.4297918 0.5166672 -0.7411561 0.4286522 0.5802488 -0.7137187 0.3923227 0.5803683 -0.7137769 0.3920398 0.6434895 -0.681056 0.3494052 0.6431857 -0.6808632 0.3503394 0.7056482 -0.641769 0.3003221 0.7050443 -0.6412186 0.3029047 0.7661424 -0.5944432 0.2442604 0.7654598 -0.5933843 0.2489309 0.8277966 -0.5329977 0.1751178 0.8274279 -0.5311558 0.1823096 0.8847015 -0.4565688 0.09406483 0.8850283 -0.4540491 0.1027834 0.9167684 -0.397667 0.0373696 0.9172028 -0.3960999 0.04294103 0.9205397 -0.3891041 0.03470748 0.9209537 -0.3876906 0.03924751 0.9230173 -0.3832687 0.03382688 0.09466505 -0.8597307 0.5018981 0.09557187 -0.8600547 0.5011708 0.1649243 -0.8541115 0.4932478 0.1662376 -0.8545522 0.4920423 0.2331777 -0.8456044 0.480189 0.2346802 -0.8460798 0.478617 0.2995081 -0.8342172 0.4630083 0.3009944 -0.8346697 0.4612255 0.3641515 -0.8198449 0.4418689 0.3654749 -0.820239 0.440041 0.4274559 -0.8022427 0.416759 0.4284693 -0.8025529 0.4151181 0.4897812 -0.7809864 0.3875238 0.4903975 -0.7811807 0.3863511 0.5514769 -0.7554296 0.3538354 0.5516475 -0.7554911 0.3534379 0.612785 -0.724689 0.3151514 0.6125274 -0.7245768 0.3159093 0.6737044 -0.6876037 0.2707834 0.6731258 -0.6872439 0.2731255 0.7338942 -0.6426923 0.219877 0.7331935 -0.641968 0.2242861 0.797011 -0.5834208 0.1561853 0.7965711 -0.5820525 0.1633688 0.8573768 -0.5083379 0.08060795 0.8576517 -0.5063538 0.08966296 0.8926654 -0.4498724 0.02763229 0.8930717 -0.4486766 0.03335362 0.8969861 -0.4413414 0.02517765 0.01621931 -0.9782512 0.2067884 0.02641308 -0.9792485 0.2009347 0.06469404 -0.9777765 0.199419 0.6520692 -0.7578458 -0.02180993 0.583819 -0.811248 0.03212857 0.5371757 -0.8434535 -0.005349457 0.5228935 -0.8523871 -0.004319131 0.4802324 -0.8763166 -0.03802645 0.463423 -0.8853741 -0.03676724 0.4006959 -0.9122336 -0.08528119 0.6569987 -0.7503998 -0.07247638 0.6454081 -0.7606959 -0.06921237 0.5975703 -0.796337 -0.09357994 0.5825003 -0.8078834 -0.0895434 0.507972 -0.8520345 -0.1264986 0.4792616 -0.8714368 -0.1044331 0.411346 -0.9004799 -0.1411747 0.6978249 -0.7143031 -0.05302309 0.6507463 -0.7592409 -0.009080946 0.6036472 -0.7961168 -0.04252493 0.5850944 -0.8099728 -0.04010933 0.5433554 -0.836667 -0.06894385 0.5217713 -0.8505182 -0.06613421 0.455334 -0.8834312 -0.1105456 0.3849461 -0.9204806 -0.06732106 0.3334884 -0.9365499 -0.1079805 0.52613 -0.8484081 0.05823248 0.4740671 -0.8760309 0.08848911 0.4307427 -0.901378 0.04448002 0.4238057 -0.9046651 0.04438477 0.382107 -0.9241155 0.002227544 0.3729814 -0.9278364 0.002147793 0.3177017 -0.946692 -0.0532903 0.4275603 -0.897601 0.1072607 0.3805952 -0.9158399 0.1280028 0.3432127 -0.9360144 0.07798856 0.3398236 -0.93728 0.07762867 0.3031638 -0.9525086 0.02861708 0.2978319 -0.954205 0.0280922 0.251574 -0.9672565 -0.0335471 0.2278358 -0.9639159 -0.1376851 0.2729225 -0.9497082 -0.1535184 0.307416 -0.9422121 -0.1331613 0.3489205 -0.9257715 -0.1456073 0.3945575 -0.9109505 -0.1203899 0.430278 -0.8922537 -0.1369097 0.4937896 -0.8633115 -0.1042363 0.7067759 -0.7053712 -0.05403095 0.697201 -0.7155226 -0.04402661 0.6476534 -0.7585893 -0.07132762 0.633522 -0.7707432 -0.06786018 0.5866472 -0.8044704 -0.09312683 0.5690244 -0.8174889 -0.08901196 0.495586 -0.8591515 -0.1274882 0.4373117 -0.8951057 -0.08685922 0.3842774 -0.9150041 -0.1228765 0.3297113 -0.9383251 -0.1040986 0.2988522 -0.9457476 -0.1274719 0.2624552 -0.9573569 -0.1207691 0.2352495 -0.9614303 -0.1425117 0.1958442 -0.9715835 -0.1329309 0.1632777 -0.977876 -0.1307629 0.1191187 -0.9867424 -0.1102278 0.1215758 -0.9867024 -0.1078789 0.09482055 -0.9902105 -0.1024319 0.5857177 -0.8101954 0.02276611 0.5243462 -0.8490995 0.06396245 0.4787364 -0.8776515 0.02322739 0.4691842 -0.8827868 0.02353525 0.425957 -0.9046234 -0.01474261 0.4141137 -0.9101126 -0.01431787 0.358961 -0.9312485 -0.06263649 0.3179026 -0.9466146 -0.05346775 0.2870727 -0.9542866 -0.08322507 0.2634589 -0.9611666 -0.0821489 0.2380763 -0.9652508 -0.1077527 0.2134748 -0.9712483 -0.1053814 0.1903936 -0.9730556 -0.1300507 0.1617597 -0.9788011 -0.1256275 0.1334616 -0.9835908 -0.121397 0.1552795 -0.9801969 -0.1228917 0.1741191 -0.9800267 -0.09607446 0.1919748 -0.9766677 -0.09626001 0.2127769 -0.9747079 -0.06834113 0.2291542 -0.9710339 -0.06768602 0.2542936 -0.9664758 -0.03548842 0.2859929 -0.9574046 -0.03980994 0.3344531 -0.9422745 0.01612204 0.3414547 -0.9397535 0.01649725 0.3809101 -0.9225152 0.06223553 0.385829 -0.9204487 0.06253099 0.4263768 -0.8978761 0.1096423 0.4756102 -0.8755702 0.08468645 0.336498 -0.9307069 0.1433662 0.2921775 -0.943239 0.1579006 0.2620717 -0.9595623 0.1027562 0.2606789 -0.9599716 0.102475 0.230881 -0.971805 0.04784351 0.2278927 -0.9725379 0.04727774 0.1914003 -0.9813172 -0.01955515 0.3813967 -0.9156941 0.1266529 0.3360681 -0.9307653 0.1439945 0.3021742 -0.9488709 0.09129482 0.2999326 -0.9496147 0.09095215 0.2665133 -0.9630429 0.03897577 0.2624923 -0.9641698 0.03839951 0.2223119 -0.9746801 -0.0240029 0.1967056 -0.9802016 -0.02262437 0.1771038 -0.9825534 -0.05677151 0.1659094 -0.9844233 -0.05818057 0.1495697 -0.9848224 -0.08805495 0.1368592 -0.9865835 -0.08900886 0.1220934 -0.9855161 -0.1176919 0.158667 -0.9691189 0.1887684 0.1127816 -0.9743302 0.1948362 0.1006109 -0.9860362 0.1327033 0.1006374 -0.9860321 0.1327134 0.08852857 -0.9935539 0.0708059 0.08792263 -0.9936245 0.07056933 0.07352077 -0.997289 -0.003069937 0.04116106 -0.9991524 -7.06861e-4 0.03647941 -0.9983555 -0.04422372 0.1123807 -0.9743124 0.1951563 0.064996 -0.9777998 0.1992058 0.0579639 -0.9889859 0.1361885 0.05803227 -0.9889775 0.1362203 0.05103474 -0.9959927 0.0734449 0.05073726 -0.9960179 0.07330846 0.04244387 -0.9990983 -0.001113533 0.04518169 -0.998978 -0.001203596 -0.01423764 -0.9994555 -0.02976989 0.2038297 -0.9622447 0.1803851 0.1590756 -0.9691221 0.1884077 0.1420128 -0.9816133 0.1275454 0.1418933 -0.9816359 0.1275033 0.124924 -0.9899099 0.06687724 0.12391 -0.9900603 0.06653428 0.1036353 -0.9945979 -0.005911529 0.07125264 -0.9974558 -0.002246022 0.06327503 -0.997003 -0.04451352 0.03367865 -0.9985336 -0.04238379 0.006348669 -0.9971187 -0.07559269 0.03616708 -0.9970021 -0.06840312 0.01940912 -0.9956946 -0.09064102 0.01349186 -0.9937992 -0.1103689 0.03909856 -0.992421 -0.1164985 0.03915494 -0.9924582 -0.1161622 0.08556491 -0.9886863 -0.1231997 0.09957146 -0.991516 -0.08355683 0.1080694 -0.9907407 -0.08218348 0.1199389 -0.9914917 -0.05058676 0.1271357 -0.9906721 -0.04904633 0.1412245 -0.9898874 -0.01337099 0.1628496 -0.986568 -0.01278495 0.1935399 -0.9795562 0.05488264 0.1957119 -0.9790954 0.05539834 0.2215442 -0.968655 0.1123649 0.2223351 -0.9684509 0.1125611 0.2483708 -0.9536493 0.1698975 0.292293 -0.9432275 0.157755 0.04803407 -0.993362 -0.1045219 0.0667814 -0.992093 -0.1062624 0.06406807 -0.991208 -0.1157668 0.0850951 -0.9890298 -0.1207438 0.06839627 -0.9906032 -0.1184378 0.1016916 -0.9863937 -0.1291756 0.1264746 -0.9831228 -0.1321891 0.1210545 -0.9841035 -0.1299478 0.1524277 -0.9788508 -0.1364445 0.143086 -0.980917 -0.1316368 0.1835564 -0.9724647 -0.1435955 0.1632003 -0.9778817 -0.1308172 0.2098869 -0.9662444 -0.1493966 0.2482277 -0.9536582 0.1700558 0.2041484 -0.9622361 0.1800696 0.1824626 -0.9757617 0.1208169 0.1820868 -0.9758459 0.120703 0.1605359 -0.9850977 0.06173175 0.1590114 -0.9853721 0.06129533 0.1331024 -0.9910558 -0.009601652 0.1003865 -0.994938 -0.00457257 0.08922159 -0.9949528 -0.04591768 0.072025 -0.9962751 -0.04741692 0.06529992 -0.9947878 -0.07831603 0.06051313 -0.9949946 -0.07952338 0.05235117 -0.9914442 -0.1195732 0.04513829 -0.991859 -0.1190729 0.01275694 -0.9921224 -0.1246213 0.6903041 -0.7230857 -0.02504622 0.5881671 -0.8075459 -0.04392349 0.5952153 -0.802945 -0.03159189 0.4920976 -0.8691517 -0.04914671 0.4986933 -0.8660249 -0.03613764 0.4053842 -0.9127365 -0.05075329 0.4030677 -0.9144355 -0.03666502 0.1012433 -0.9902229 -0.09596043 0.1247801 -0.9868479 -0.1027677 0.1247357 -0.9868509 -0.1027933 0.1697188 -0.9779093 -0.1220206 0.1716629 -0.9777081 -0.1209086 0.2269077 -0.9641203 -0.1377867 0.2420908 -0.9615538 -0.129639 0.2975515 -0.9440875 -0.1419935 0.3261981 -0.9366586 -0.1275364 0.3788303 -0.9155052 -0.1354174 0.4097775 -0.9042148 -0.1203248 0.4631573 -0.8773933 -0.1251656 0.4985221 -0.8601008 -0.1081775 0.5513787 -0.8268357 -0.1110144 0.5942872 -0.7991458 -0.0904926 0.6280014 -0.7735632 -0.08493709 0.6557924 -0.7515726 -0.07123959 0.6819054 -0.7283919 -0.06671124 0.7111546 -0.7011117 -0.05197596 0.9758073 0.2184619 0.008640646 0.9683883 0.2492699 0.009422659 0.9681882 0.249477 0.01931184 0.9395137 0.342019 0.01835858 0.9341793 0.3561924 0.02088749 0.9521466 -0.304089 0.03077036 0.8536301 -0.520831 -0.007128715 0.8494961 -0.5275806 -0.003913283 0.7769388 -0.6290273 -0.0262826 0.8557169 -0.5174164 -0.005392968 0.8529269 -0.5220228 -0.002864122 0.779002 -0.6267347 -0.01896655 0.7748236 -0.6319859 -0.01556378 0.6853716 -0.7274333 -0.03326624 0.9845147 0.1749139 0.01165688 0.9878396 0.1552451 0.008491158 0.9876317 0.1552359 0.02203071 0.9718946 0.2343593 0.02228355 0.9715685 0.2346854 0.03126496 0.9435337 0.3299306 0.02983528 0.9362992 0.3494713 0.03483819 0.9740058 -0.2263237 0.009511947 0.9910868 -0.1324966 0.01384699 0.9909457 -0.1330888 0.01772129 0.9983841 -0.05211544 0.02265912 0.9982244 -0.05316811 0.02685678 0.9994698 -0.01384437 0.02946799 0.9993916 -0.01442074 0.03175848 0.998699 0.03773093 0.03430306 0.9985402 0.03708618 0.03927111 0.9953806 0.08706939 0.04045104 0.9950702 0.08688485 0.04781621 0.9868718 0.1542106 0.04799234 0.9863795 0.1545113 0.05640774 0.9693335 0.2394337 0.05535405 0.9610458 0.2457385 0.126506 0.9429308 0.3092114 0.1235715 0.9356649 0.325124 0.1372063 0.9973552 -0.07190662 0.01058471 0.9994023 -0.0324406 0.01194518 0.9992558 -0.03353518 0.01905679 0.999727 0.009879469 0.02117979 0.9996475 0.009154915 0.02492475 0.9965598 0.07808941 0.02776122 0.9970839 0.0718072 0.02583569 0.9921288 0.1223111 0.02684336 0.9918901 0.1222241 0.03486537 0.9756781 0.2163737 0.03513807 0.9753907 0.2166576 0.04089534 0.9688794 0.2436968 0.04341208 0.9681117 0.2446115 0.0540834 0.9431275 0.3283343 0.05203032 0.9364795 0.3381182 0.09317934 0.9029768 0.2802523 0.3257174 0.915522 0.2304145 0.3297404 0.9462645 0.2218939 0.2352589 0.9610549 0.1404191 0.2380256 0.9809564 0.1374498 0.1372302 0.9899598 0.03217858 0.137638 0.9888752 0.0394113 0.1434317 0.9895586 -0.02962899 0.1410527 0.9979233 -0.01705235 0.06211584 0.99778 -0.03215003 0.0583238 0.9976188 -0.02767103 0.06317633 0.9945027 -0.08598029 0.05976396 0.9951598 -0.08326333 0.05219429 0.9954704 -0.07895445 0.05296313 0.9961118 -0.07589811 0.04473137 0.9937823 -0.1030316 0.04220551 0.9941554 -0.101171 0.03767681 0.9855346 -0.1666334 0.03090214 0.9853653 -0.1672796 0.03275376 0.9607345 -0.276723 0.02033865 0.9608918 -0.2762921 0.01870328 0.9085499 0.3568701 0.2172119 0.9432972 0.2447358 0.2242652 0.9627966 0.2364016 0.1309087 0.98023 0.1461464 0.1333808 0.9878585 0.1437561 0.05890655 0.9966813 0.05630284 0.05879229 0.9969869 0.05653995 0.05310928 0.9986608 -1.23515e-4 0.05173695 0.999044 0.001242876 0.04369837 0.9983808 -0.03894317 0.04146528 0.9986314 -0.03743398 0.03652846 0.9964794 -0.07690823 0.03337812 0.9966166 -0.07611393 0.03101712 0.9886721 -0.1480047 0.02494388 0.9887243 -0.1477935 0.02411276 0.9636079 -0.2669282 0.01446819 0.9638572 -0.2662292 0.01007151 0.8598755 0.2728503 0.4314706 0.8728193 0.2148969 0.4381845 0.9169094 0.2083839 0.3403723 0.92999 0.1276838 0.3446964 0.96144 0.124853 0.2450406 0.969196 0.01656347 0.2457333 0.9670562 0.02567845 0.2532646 0.9667228 -0.05353558 0.2501617 0.988996 -0.03656405 0.1433527 0.9871254 -0.07589054 0.1407985 0.9961171 -0.05700653 0.06708979 0.9936702 -0.09175926 0.06480675 0.9940166 -0.09044915 0.06123673 0.9905489 -0.124045 0.05852949 0.9911386 -0.1216424 0.05336022 0.9876777 -0.1480766 0.05065697 0.9884803 -0.1447389 0.04424357 0.981366 -0.1881738 0.03887766 0.9813144 -0.1883565 0.03929013 0.956925 -0.2892479 0.02510732 0.9568625 -0.2894151 0.02555686 0.1048546 -0.7851109 0.610415 0.1058478 -0.785592 0.609624 0.1829025 -0.7790018 0.5997524 0.1843194 -0.7796679 0.5984517 0.2587276 -0.7696883 0.5836439 0.2602989 -0.7704192 0.5819783 0.3322846 -0.7571266 0.5624467 0.3338084 -0.7578469 0.5605713 0.4037023 -0.741185 0.5363482 0.4050042 -0.7418108 0.5344982 0.4732076 -0.721558 0.5053996 0.4741481 -0.7220476 0.5038164 0.5410436 -0.6977924 0.4694227 0.5415382 -0.6980788 0.4684255 0.6073797 -0.6692051 0.4280823 0.6074169 -0.6692333 0.4279854 0.6722101 -0.6349117 0.3808159 0.6718379 -0.6345875 0.3820112 0.7351998 -0.5937898 0.3269481 0.7345517 -0.592993 0.3298382 0.795538 -0.5445339 0.2657105 0.7948472 -0.5430819 0.2707031 0.855211 -0.4816701 0.1913326 0.8548732 -0.4793386 0.1985605 0.9082642 -0.404945 0.1052426 0.908592 -0.4019315 0.1136296 0.9370192 -0.3463547 0.04509502 0.9374563 -0.344408 0.05058521 0.9403074 -0.337701 0.04219239 0.9407258 -0.3359185 0.04684036 0.942477 -0.331703 0.04135632 0.9317342 -0.3614771 0.0347231 0.08340847 -0.9191956 0.3848668 0.08415544 -0.919371 0.3842847 0.1451683 -0.9143121 0.3781002 0.1462432 -0.9145334 0.3771492 0.205141 -0.9069501 0.3679114 0.2063824 -0.9071729 0.3666658 0.2635336 -0.8971501 0.3545022 0.2647743 -0.8973422 0.3530886 0.320657 -0.8848418 0.3379853 0.3217535 -0.8849894 0.3365538 0.376916 -0.8698217 0.3183464 0.3777527 -0.8699191 0.3170862 0.4327566 -0.8517268 0.2954375 0.4332359 -0.8517757 0.2945929 0.4886548 -0.8299864 0.2689593 0.4887263 -0.8299951 0.2688028 0.5450299 -0.8037996 0.2384297 0.5446798 -0.8037671 0.2393379 0.6022031 -0.7720471 0.2032111 0.6015012 -0.7719594 0.2056088 0.6602615 -0.7332533 0.1624634 0.6593802 -0.7330582 0.1668636 0.7244069 -0.6805285 0.1100712 0.7236664 -0.6800426 0.117682 0.7899587 -0.6113991 0.04643911 0.7899426 -0.610565 0.05657815 0.8309981 -0.5562725 0.001720607 0.8312411 -0.5558525 0.008139371 0.8367415 -0.5475982 -3.07508e-4 0.8370351 -0.5471304 0.004563987 0.8403502 -0.5420433 -8.95244e-4 0.8162681 -0.5775033 -0.01401603 0.8170447 -0.5763646 -0.01555609 0.8825139 -0.4700696 0.01428359 0.8841021 -0.467182 0.01021933 0.9076872 -0.4194383 0.0132507 0.9071311 -0.4205617 0.01552873 0.911936 -0.4101719 0.01148003 0.9116912 -0.4106771 0.01278847 0.9155002 -0.4022141 0.009132385 0.9154844 -0.4022474 0.00924766 0.9181138 -0.3962665 0.00633198 0.9173448 -0.3977839 0.01570278 0.9280195 -0.3725134 0.00372821 0.07740473 -0.942889 0.323989 0.07803273 -0.9430011 0.323512 0.1346293 -0.9384451 0.318113 0.1355408 -0.938579 0.3173297 0.1902132 -0.9317606 0.3092588 0.191254 -0.931882 0.3082498 0.2443651 -0.9228821 0.2976148 0.2453948 -0.9229714 0.2964881 0.2974424 -0.9117496 0.283268 0.2983266 -0.911805 0.2821577 0.3498515 -0.8981889 0.2661969 0.350488 -0.8982114 0.265282 0.4020627 -0.8818722 0.2462663 0.4023733 -0.8818741 0.2457519 0.454605 -0.8622785 0.2231821 0.4545145 -0.86228 0.2233605 0.5079563 -0.8386636 0.1965296 0.5074641 -0.83868 0.1977272 0.5625675 -0.8099789 0.1656864 0.5617119 -0.8100275 0.1683306 0.6187212 -0.7748041 0.129857 0.6176571 -0.7748664 0.1344687 0.6822425 -0.7263805 0.08316582 0.6812399 -0.7263621 0.09116196 0.7491703 -0.6618741 0.02582126 0.7488725 -0.6617002 0.03664541 0.7924582 -0.609754 -0.01449608 0.7925338 -0.6097823 -0.007482945 0.7991125 -0.6009615 -0.01626956 0.7993138 -0.600815 -0.01090729 0.8031097 -0.5956066 -0.0163607 0.7762969 -0.6296257 -0.03057348 0.7780154 -0.6273448 -0.03362339 0.7704708 -0.6362068 -0.04019659 0.7656551 -0.6426612 -0.02755033 0.6739892 -0.736306 -0.05993342 0.6794518 -0.7323326 -0.0451039 0.5719208 -0.8162899 -0.08110308 0.5791485 -0.813078 -0.05908799 0.4786664 -0.8732869 -0.09082198 0.4846076 -0.8721116 -0.06765353 0.387259 -0.9168809 -0.09674715 0.391085 -0.9175011 -0.0724169 0.2990042 -0.949128 -0.09875583 0.3001449 -0.9517995 -0.06317406 0.2337371 -0.9690589 -0.07932162 0.2111121 -0.9772064 -0.02234649 0.1137172 -0.6975084 0.7074959 0.114835 -0.6981983 0.7066344 0.1986206 -0.6913143 0.6947189 0.2001881 -0.6922799 0.6933061 0.281144 -0.6817803 0.6753767 0.2828557 -0.6828431 0.6735859 0.3610563 -0.6687804 0.6499009 0.3626677 -0.6698082 0.6479423 0.438344 -0.6521065 0.6185562 0.4396568 -0.6529966 0.6166825 0.5130881 -0.6314231 0.5814168 0.5139696 -0.6320773 0.5799255 0.5853473 -0.6062391 0.5383705 0.5857333 -0.6065647 0.5375832 0.6551047 -0.5758796 0.4890813 0.6549978 -0.575764 0.4893606 0.7221037 -0.5394802 0.4330445 0.7215771 -0.5388014 0.434764 0.7856661 -0.4960559 0.3696724 0.78489 -0.494641 0.3731997 0.8446025 -0.4445381 0.2983833 0.8438303 -0.4421569 0.3040526 0.8992972 -0.3810284 0.214667 0.8989289 -0.3777029 0.2219623 0.9442944 -0.3063353 0.1202779 0.9445227 -0.3024474 0.1280721 0.9667097 -0.2500307 0.05437946 0.9670845 -0.2473243 0.0598194 0.9691992 -0.2409865 0.05077737 0.9695783 -0.2383317 0.05582189 0.9718558 -0.2311818 0.0452916 0.9725841 -0.2278509 0.04652023 0.9729099 -0.2268141 0.04474103 0.9530202 -0.3012056 0.03206211 0.9521209 -0.3041549 0.03091382 0.9332934 -0.3579161 0.02932077 0.9117645 -0.4103373 0.01757442 0.9090945 -0.4158073 0.02552747 0.8998089 -0.4356086 0.02427393 0.8973793 -0.4402601 0.02968883 0.08918952 -0.8913397 0.4444761 0.09002494 -0.8915858 0.4438135 0.1552938 -0.8860597 0.4367862 0.1565237 -0.8863894 0.4356769 0.2195206 -0.8780878 0.4251736 0.2209144 -0.87843 0.4237422 0.2819747 -0.8674454 0.4099131 0.2833752 -0.8677655 0.4082668 0.3429695 -0.8540509 0.3911126 0.344212 -0.8543176 0.3894352 0.4028707 -0.8376741 0.3687782 0.4038248 -0.837874 0.3672776 0.4620761 -0.817924 0.3427627 0.4626668 -0.8180459 0.341673 0.521026 -0.7941907 0.3127192 0.5211836 -0.7942262 0.3123659 0.5800492 -0.7656167 0.2781622 0.5797849 -0.7655443 0.2789111 0.6393143 -0.731051 0.2384151 0.6387084 -0.7308331 0.2406963 0.6987041 -0.6889935 0.192615 0.6979405 -0.688547 0.1969317 0.7626718 -0.6326429 0.1345171 0.7621169 -0.6317107 0.1418434 0.8259682 -0.559984 0.06476658 0.8261369 -0.5585502 0.0742948 0.8642835 -0.5027572 0.0157935 0.8646285 -0.5019393 0.02178579 0.869251 -0.4941857 0.01354354 0.8696055 -0.4934137 0.01814478 0.8724567 -0.4885262 0.01270812 0.8516185 -0.5241611 0.001026272 0.8541836 -0.5199499 -0.004739403 0.8472139 -0.5311319 -0.01129561 0.8451843 -0.5344535 -0.004796206 0.7737106 -0.6327155 -0.0322979 0.7707616 -0.6367434 -0.02200841 0.6802453 -0.7314447 -0.04748791 0.6859086 -0.7268151 -0.03562873 0.5807479 -0.8116044 -0.06348478 0.5886238 -0.8071113 -0.04575604 0.4859111 -0.8711107 -0.07111018 0.4929524 -0.8684741 -0.05244678 0.3923304 -0.9167159 -0.07555842 0.3978964 -0.9157211 -0.0559774 0.3118697 -0.9471907 -0.07461285 0.3057548 -0.9505847 -0.05387759 0.2437543 -0.9678143 -0.06260466 0.04616487 -0.6526756 0.7562297 0.02565687 -0.6836308 0.729377 0.04613429 -0.7004045 0.7122536 0.02430069 -0.7295196 0.6835281 0.04538631 -0.7456296 0.6648133 0.02164328 -0.7729339 0.6341174 0.04423028 -0.7878665 0.6142557 0.01977276 -0.81413 0.5803461 0.04272741 -0.8269514 0.5606477 0.01837718 -0.8514499 0.5241139 0.04120939 -0.8621977 0.504893 0.01654976 -0.8846046 0.4660481 0.03970468 -0.8936155 0.4470739 0.0146014 -0.91382 0.405857 0.03816682 -0.9212525 0.3870881 0.01273131 -0.9387224 0.344439 0.03662908 -0.9447079 0.325861 6.42975e-6 -0.9642593 0.2649604 0.07118207 -0.9623755 0.262234 0.07166862 -0.9624373 0.2618741 0.1237336 -0.9584091 0.2571812 0.124427 -0.9584733 0.2566067 0.1747625 -0.9524507 0.2495911 0.1755363 -0.9524968 0.2488714 0.2245199 -0.9445513 0.2396119 0.2252494 -0.9445714 0.2388463 0.2733645 -0.9346645 0.2273195 0.2739433 -0.9346631 0.2266278 0.3217104 -0.9226416 0.2126847 0.322053 -0.9226294 0.2122192 0.3700598 -0.9081895 0.1955701 0.3700743 -0.9081889 0.1955458 0.4189248 -0.8908529 0.1757365 0.4185707 -0.8908886 0.1763973 0.4688816 -0.869948 0.1527771 0.4681237 -0.8700596 0.154456 0.5204477 -0.844526 0.1261362 0.5193344 -0.8447422 0.1292378 0.5740937 -0.8132529 0.09505969 0.5727479 -0.8135961 0.1001065 0.6361081 -0.769707 0.05401641 0.6347393 -0.770188 0.06258219 0.7033498 -0.7108376 0.003032207 0.7026307 -0.7114026 0.0147106 0.7482571 -0.6625988 -0.03277403 0.7480633 -0.6631593 -0.02492487 0.755977 -0.6537035 -0.03421652 0.7560055 -0.6539626 -0.02808433 0.7602643 -0.6487511 -0.03346908 0.7314383 -0.6801913 -0.04835307 0.7297742 -0.6821595 -0.04569554 0.6817203 -0.7285901 -0.06643801 0.6781616 -0.731626 -0.06942802 0.6214388 -0.7797649 -0.07603102 0.578081 -0.8105704 -0.09379923 0.5327696 -0.8416819 -0.08790975 0.4864912 -0.8671827 -0.1063978 0.4406366 -0.8923134 -0.0980618 0.3968721 -0.9106308 -0.1150829 0.3516947 -0.9303682 -0.1035661 0.3105244 -0.9430388 -0.1193848 0.2630724 -0.9592508 -0.1031061 0.2327136 -0.9657344 -0.1148981 0.1861803 -0.978011 -0.09397697 0.1654039 -0.9809325 -0.1020445 0.1290052 -0.9884055 -0.08007812 0.1094109 -0.9901359 -0.08752286 0.09965288 -0.9917467 -0.0806716 0.3088266 0.9510796 0.008595049 0.8765474 0.4802092 0.03261798 0.852094 0.519712 0.06193029 0.8672662 0.4957116 0.04603815 0.8382345 0.5290363 0.1322261 0.8426748 0.524053 0.1235626 0.8536952 0.5137994 0.08494079 0.796503 0.5229671 0.3034611 0.8233433 0.5070301 0.2550026 0.8337474 0.5189265 0.1886288 0.8162455 0.5370488 0.21289 0.8382655 0.5174697 0.1718613 0.7702581 0.498501 0.3977429 0.7974199 0.489677 0.352616 0.7538692 0.4694337 0.4596881 0.7636733 0.4683225 0.4443842 0.7123684 0.4460421 0.5418281 0.6830517 0.4520964 0.5736282 0.7068013 0.4315084 0.5605645 0.6632239 0.4232175 0.6172691 0.6316584 0.4284899 0.6460682 0.6500645 0.4137926 0.6373318 0.6072361 0.4012307 0.6857685 0.5738047 0.4057886 0.7113957 0.5868538 0.3962082 0.7061315 0.5453445 0.3806983 0.7467718 0.5104793 0.3845964 0.7690882 0.5166139 0.3805582 0.7669978 0.4772511 0.3624033 0.8005594 0.4399362 0.3657837 0.8201577 0.4376357 0.3670795 0.8208091 0.4076677 0.350261 0.8432819 0.3690696 0.3459587 0.8626125 0.3489466 0.3548348 0.8673687 0.3232088 0.3373736 0.8841466 0.2814626 0.3332343 0.899852 0.2499297 0.3424736 0.9056749 0.2198594 0.3180716 0.9222215 0.1402157 0.3280758 0.9341874 0.1295578 0.3178462 0.939249 0.05253231 0.3112385 0.9488788 0.04578578 0.3054717 0.9510998 0.06553006 0.9362662 0.3451254 0.04768478 0.9405491 0.336294 0.009927988 0.9374916 0.3478663 0.02409934 0.9342955 0.3556841 0.01081007 0.9359003 0.3520991 0.1232679 0.9333422 0.3371608 0.1013983 0.9376351 0.3325039 0.08115744 0.9400612 0.3312075 0.1081569 0.9395327 0.3249316 0.1500642 0.9364647 0.3170406 0.1499482 0.9363583 0.3174094 0.1743303 0.9380117 0.2995713 0.1869347 0.9347883 0.3020369 0.1977026 0.9383487 0.2835763 0.21925 0.9342799 0.2811597 0.2178951 0.934653 0.2809727 0.2278754 0.9378483 0.2617507 0.2468802 0.9338508 0.2587912 0.2487114 0.9372386 0.2443901 0.2739544 0.9340267 0.229223 0.2710492 0.9349224 0.2290255 0.2864966 0.935815 0.2053536 0.3021664 0.9319826 0.2002597 0.3012604 0.9360473 0.1818184 0.3280994 0.9310874 0.1594591 0.3241184 0.9323619 0.1601521 0.3360123 0.9334799 0.1253446 0.3566686 0.9308276 0.0796712 0.363206 0.9306926 0.0435065 0.3588797 0.9318652 0.05322247 0.3369764 0.9405415 0.04276442 0.3795511 0.924769 0.02726203 0.369931 0.9284406 0.0338993 0.3270788 0.9448087 0.01886808 0.326658 0.944826 0.02446818 0.3296179 0.9437442 0.0264424 0.3267878 0.944655 0.02893078 0.3258484 0.9450685 0.02585232 0.1904937 0.9816825 0.003414213 0.2665485 0.9637836 0.008556663 0.7921675 0.4786341 0.3786557 0.7415094 0.5697563 0.3543184 0.6761623 0.5938794 0.4360182 0.818979 0.5015264 0.2788277 0.767358 0.5855606 0.2613055 0.7279499 0.6050416 0.3225116 0.6930777 0.652249 0.306944 0.6459901 0.672231 0.3616659 0.04975342 0.5196217 0.8529466 0.03840577 0.5276633 0.8485851 0.1357954 0.5248026 0.8403224 0.1261706 0.5344085 0.8357563 0.2391355 0.5276153 0.8151297 0.2242805 0.5420233 0.8098822 0.3321602 0.531858 0.7789717 0.3121301 0.5509116 0.773997 0.4150811 0.5377623 0.7338389 0.3897891 0.56145 0.7299579 0.4884656 0.5455278 0.6810292 0.4576908 0.5739287 0.679062 0.5531905 0.5551826 0.6210897 0.5167966 0.5882724 0.6219782 0.610786 0.5661916 0.553505 0.5690097 0.6037638 0.5582987 0.6615507 0.5777547 0.4780692 0.6146246 0.6198304 0.4879005 0.6770643 0.60028 0.4257321 0.7568941 0.4481176 0.4757121 0.7271322 0.4763198 0.4943667 0.6221921 0.7728826 0.1246182 0.3520068 0.9333025 0.07097631 0.3786878 0.9234725 0.06159764 0.5738645 0.8178239 0.04293781 0.5785583 0.8145912 0.04137235 0.5566205 0.8271898 0.07701134 0.5766189 0.8142877 0.06667977 0.5889008 0.8014965 0.1039195 0.552132 0.8200025 0.150819 0.05307096 0.7564755 0.6518653 0.03564453 0.7670161 0.6406372 0.1111682 0.7639907 0.6355785 0.1041764 0.7695627 0.6300164 0.193926 0.7625834 0.617138 0.1813821 0.7720589 0.6091189 0.2682873 0.7618169 0.5896244 0.2500883 0.7750068 0.5803624 0.3345713 0.7619035 0.5545855 0.3104542 0.7787688 0.5451032 0.3931258 0.7630487 0.5130388 0.3629226 0.7834866 0.5044167 0.4449074 0.7651063 0.465478 0.4083819 0.7891068 0.4588407 0.4918459 0.7674219 0.41128 0.4486898 0.7951869 0.4078668 0.5343949 0.7694169 0.3498853 0.4840902 0.801477 0.3511286 0.5722521 0.7705701 0.2806231 0.5140848 0.8078348 0.2883054 0.3710371 0.9283574 0.02200245 0.3145361 0.949216 0.007493555 0.5734055 0.8191525 0.01398634 0.8581655 0.5131265 0.01591348 0.8740611 0.4854752 0.01819324 0.7661066 0.6424968 0.01669448 0.7749018 0.6318129 0.01843202 0.5746973 0.8182489 0.01385301 0.8644686 0.5009743 0.04145693 0.7611584 0.6475183 0.03685027 0.7549777 0.6534184 0.05525541 0.7557865 0.6525164 0.05485576 0.7305626 0.6729639 0.1157491 0.7496748 0.6539766 0.1015002 0.7198135 0.6746304 0.1635313 0.7655919 0.6295109 0.132609 0.7304862 0.6534686 0.1984159 0.728916 0.6551085 0.1987822 0.6751078 0.6845131 0.2750841 0.5378435 0.8142153 0.2185819 0.6050684 0.7700718 0.2021924 0.3502969 0.9295032 0.1153957 0.3704249 0.9224379 0.1090578 0.9180301 0.396375 0.01037818 0.8938037 0.448154 0.01652425 0.9042098 0.4266099 0.02021515 0.8537225 0.5179919 0.05331343 0.8738919 0.485189 0.0300756 0.7645391 0.6440289 0.02658998 0.748453 0.6624454 0.03137314 0.5707286 0.8207626 0.02485358 0.5839103 0.8114724 0.02368938 0.3270493 0.9448816 0.01541638 0.3385078 0.9408572 0.0141493 0.9691598 0.2463673 0.005705654 0.8583178 0.2309766 0.4581925 0.7779949 0.2573899 -0.5731269 0.9045501 0.3167202 0.2854426 0.1241433 0.003138005 -0.9922595 0.711735 0.07728075 -0.6981841 0.980569 0.1960976 0.005520939 0.7338643 0.1667827 -0.6585035 0.8850234 0.1555108 0.4388054 -0.664335 -0.1799678 -0.7254452 0.9390726 0.24093 -0.2451438 0.7964019 -0.07627296 -0.5999386 0.6131321 -0.101509 -0.7834317 0.2444055 0.2178702 -0.9448802 0.2628869 0.02068752 -0.9646049 0.003877043 -0.759844 -0.650094 0.004844248 -0.5770407 -0.8167012 0.1048054 -0.9580767 -0.2666549 0.07677221 -0.9607042 -0.2667462 0.07545894 -0.9601259 -0.2691921 0.02186793 -0.9627143 -0.2696352 0.02071231 -0.9625884 -0.270175 0.003388881 -0.9627729 -0.2702903 -0.6673918 -0.7031214 -0.2453743 0.4776072 -0.8443657 -0.2427715 0.4017696 -0.8828207 -0.2433286 0.3995144 -0.8826519 -0.2476164 0.3409296 -0.9067459 -0.2481509 0.3389465 -0.9068278 -0.2505572 0.2813177 -0.9262608 -0.2508013 0.2793521 -0.9257473 -0.2548612 0.2093059 -0.9439402 -0.2552799 0.2075404 -0.9432061 -0.2594018 0.1535889 -0.9533734 -0.2597876 0.1463181 -0.9507923 -0.2731029 0.1277933 -0.9561397 -0.2635638 0.1062468 -0.9587491 -0.2636508 0.8380169 -0.5012646 -0.2155492 0.8080373 -0.5480332 -0.2161836 0.8064547 -0.5501057 -0.2168282 0.7731903 -0.5959185 -0.216929 0.7707969 -0.5972812 -0.221647 0.7068824 -0.6714825 -0.2223256 0.7044 -0.6725348 -0.2269755 0.6358843 -0.7374573 -0.2276138 0.633347 -0.7381808 -0.2322943 0.5789228 -0.7813982 -0.2329491 0.5538215 -0.7912272 -0.2593092 0.5389549 -0.8080204 -0.2379725 0.4800184 -0.8442834 -0.2382603 0.004944384 -0.1801902 -0.9836193 0.008486926 -0.1801736 -0.9835983 0.00867486 -0.1802443 -0.9835836 0.01915174 -0.1798592 -0.9835059 0.01931464 -0.1801059 -0.9834576 0.02462518 -0.17957 -0.983437 0.02488327 -0.180002 -0.9833515 0.0327382 -0.1790107 -0.9833024 0.03303599 -0.1794942 -0.9832042 0.04454571 -0.1773928 -0.9831315 0.04491126 -0.1779311 -0.9830176 0.05852711 -0.1744009 -0.9829339 0.0589599 -0.1748892 -0.9828212 0.07017713 -0.1710119 -0.9827666 0.07057005 -0.1712304 -0.9827004 0.08203715 -0.1666256 -0.9826015 0.0825802 -0.1670585 -0.9824826 0.09740096 -0.1595551 -0.9823722 0.09802156 -0.1599501 -0.9822463 0.1130656 -0.1504944 -0.9821241 0.1137533 -0.1508382 -0.981992 0.1282842 -0.1395652 -0.981868 0.1290066 -0.1398184 -0.9817373 0.1424935 -0.127044 -0.9816086 0.1432454 -0.1272103 -0.9814777 0.1558672 -0.1125844 -0.981341 0.1566468 -0.112667 -0.9812074 0.1630653 -0.1034284 -0.9811791 0.1633664 -0.103134 -0.98116 0.1695083 -0.09397888 -0.9810377 0.1702404 -0.09395366 -0.9809134 0.1794509 -0.07657521 -0.9807822 0.1801351 -0.07647848 -0.9806643 0.187583 -0.0579952 -0.9805352 0.1882253 -0.05783563 -0.9804216 0.1915991 -0.04599028 -0.9803952 0.191801 -0.04568868 -0.9803699 0.194886 -0.03370964 -0.9802464 0.1954187 -0.03348982 -0.980148 0.5142846 -0.4501602 -0.7299776 0.01482164 -0.5253126 -0.8507803 0.01533889 -0.5254932 -0.8506596 0.04514956 -0.5243022 -0.8503345 0.04566085 -0.5250084 -0.8498715 0.06103956 -0.5234842 -0.8498463 0.06177514 -0.5245807 -0.8491166 0.08419281 -0.5217261 -0.8489485 0.08504295 -0.5229783 -0.8480928 0.1179314 -0.5169434 -0.8478571 0.1189675 -0.5183277 -0.8468667 0.1578487 -0.5082355 -0.8466289 0.1590559 -0.5094829 -0.8456528 0.1911023 -0.498484 -0.845573 0.1922003 -0.4990255 -0.8450045 0.2249343 -0.485797 -0.8446335 0.2264212 -0.4868879 -0.8436076 0.268737 -0.4654561 -0.843286 0.2704225 -0.4664379 -0.8422039 0.3133561 -0.4394365 -0.8418453 0.3152316 -0.4402768 -0.8407053 0.3566974 -0.4081209 -0.8403596 0.358658 -0.4087161 -0.8392351 0.3971301 -0.3722712 -0.8388694 0.3991622 -0.3726266 -0.8377465 0.435142 -0.3309069 -0.8373482 0.4372393 -0.3310356 -0.8362042 0.4556717 -0.3048272 -0.8363275 0.4565266 -0.3039662 -0.8361746 0.4738943 -0.2777547 -0.8356294 0.4758567 -0.2776018 -0.8345643 0.5021069 -0.228047 -0.8341963 0.5039436 -0.2277024 -0.8331822 0.5251637 -0.1750159 -0.8328101 0.5268637 -0.1745064 -0.8318426 0.5366603 -0.1408259 -0.8319638 0.5372136 -0.1399364 -0.8317568 0.545808 -0.1057605 -0.831209 0.5472236 -0.1051041 -0.8303611 0.5153871 -0.6848686 -0.5151031 0.019082 -0.7985683 -0.6016017 0.01992875 -0.7987821 -0.6012904 0.06478136 -0.7967818 -0.6007845 0.06567996 -0.7976887 -0.5994821 0.08906573 -0.7954453 -0.5994448 0.09020113 -0.7966798 -0.597633 0.1240056 -0.7923181 -0.5973731 0.1252864 -0.7937395 -0.595215 0.1749147 -0.7845718 -0.5948546 0.1764242 -0.7861014 -0.5923845 0.2350645 -0.7708773 -0.5920245 0.2367931 -0.772214 -0.5895885 0.2851053 -0.7557958 -0.5894808 0.2867496 -0.7562906 -0.588047 0.3359814 -0.7361941 -0.5874817 0.3380702 -0.7372853 -0.5849093 0.4017593 -0.7050094 -0.584424 0.4040877 -0.7059237 -0.5817085 0.4686541 -0.6652837 -0.581172 0.4711889 -0.6659742 -0.5783247 0.533515 -0.6176543 -0.5778106 0.53614 -0.6180082 -0.5749956 0.5939134 -0.5632689 -0.5744519 0.5965881 -0.5632975 -0.5716455 0.6505621 -0.5006684 -0.5710518 0.6532692 -0.5003914 -0.568197 0.6812191 -0.4613713 -0.5683987 0.682503 -0.4599589 -0.5680031 0.7081698 -0.4204599 -0.5671939 0.7106688 -0.4198362 -0.5645242 0.7500071 -0.3455768 -0.5639734 0.7522927 -0.3447302 -0.5614418 0.784058 -0.2658163 -0.5608876 0.786117 -0.2647907 -0.5584855 0.8011666 -0.2145105 -0.5586746 0.8019075 -0.2130858 -0.5581566 0.8143509 -0.1618648 -0.5573441 0.8160289 -0.1606946 -0.5552245 0.973959 -0.1133875 -0.1963344 0.9615319 -0.1918609 -0.1965852 0.9604414 -0.1936951 -0.2000865 0.9461351 -0.2540594 -0.2007047 0.9453989 -0.2561181 -0.2015551 0.9273619 -0.3151652 -0.2016701 0.9258636 -0.3170018 -0.2056366 0.9002193 -0.3834637 -0.2063034 0.8827692 -0.4098795 -0.2296029 0.8782373 -0.4292792 -0.2107573 0.8401213 -0.4996276 -0.2111124 0.9792075 -0.06224924 -0.1930748 0.972169 -0.09023934 -0.2162045 0.8299505 -0.07375997 -0.5529391 0.8286326 -0.07491159 -0.5547578 0.5567891 -0.04705822 -0.82932 0.5556448 -0.04774945 -0.8300475 0.1988129 -0.01312428 -0.9799496 0.1983761 -0.01336067 -0.980035 0.9761769 0.0159083 -0.2163926 0.9807644 0.03448951 -0.1921246 0.8052325 -0.01704382 -0.5927143 0.8334227 0.01183837 -0.5525093 0.5926249 0.01102346 -0.8054032 0.5584065 -0.01271229 -0.8294702 0.2337629 0.0302596 -0.9718226 0.1996294 0.006969571 -0.9798467 0.64909 -0.7559623 -0.0848729 0.987003 0.00668466 0.1605628 0.9965537 -0.06481635 -0.05176532 0.9974107 -0.07191389 5.91483e-4 0.9930426 -0.1177518 -0.00100249 0.9622157 -0.1380788 0.234681 0.9546592 -0.1900815 -0.2291178 0.9735318 -0.226257 0.03230524 0.96504 -0.2615233 -0.01741951 0.9541468 -0.2940363 0.05609595 0.9281862 -0.315494 -0.1973174 0.9207258 -0.3701609 0.1234706 0.9188814 -0.3942579 -0.01476055 0.8971015 -0.4415026 -0.01686537 0.8984775 -0.4336197 -0.06864559 0.8543699 -0.5129917 0.08301562 0.8616136 -0.5071997 -0.01924967 0.8257538 -0.5634573 -0.02542561 0.7880423 -0.6125204 0.06171053 0.762584 -0.6105111 0.2138737 0.7153771 -0.6809135 -0.1568198 0.6813802 -0.7197703 0.1328601 0.6076708 -0.7400448 -0.2882185 0.5927326 -0.8052543 -0.01528131 0.5966838 -0.8011507 -0.04610919 0.5520435 -0.8324319 -0.04801392 0.5047252 -0.8468599 0.1675734 0.4912754 -0.8690112 -0.05889087 0.4508387 -0.8908465 -0.05600923 0.4112105 -0.9090312 -0.06758958 0.4030643 -0.9151034 0.01117694 0.3541229 -0.9317262 -0.08052027 0.3486135 -0.9326571 -0.09284067 0.3435715 -0.9359697 -0.07693755 0.2879855 -0.9573575 -0.02304553 0.2964833 -0.9472808 -0.1214779 0.243821 -0.9683139 -0.0540328 0.2129384 -0.9658365 -0.147706 0.2103015 -0.9691514 -0.1285258 0.1897604 -0.9786108 -0.0794472 0.1567184 -0.9856792 -0.06225705 0.15884 -0.984172 -0.0785833 0.1302084 -0.9883409 -0.07891923 0.1078482 -0.9934989 -0.0364511 0.116949 -0.9849736 -0.1270822 0.09966427 -0.9917681 -0.08039253 0.07703208 -0.9871271 -0.140165 0.07763183 -0.9866787 -0.1429635 0.09476524 -0.9916602 -0.08734697 0.1011273 -0.9914039 -0.08301603 0.06180852 -0.9921676 -0.1085511 0.04800969 -0.995129 -0.08610206 0.02101999 -0.995921 -0.08774799 0.0186637 -0.9963393 -0.08342528 0.002022922 -0.9961469 -0.08767789 0.6090947 0.6939202 -0.3840293 0.487156 0.8072243 -0.3332689 0.2434425 0.9501979 -0.194576 0.1884512 0.9817895 -0.0239883 0.2702124 0.9200495 -0.2837153 0.2248722 0.9417213 -0.2501873 0.1938906 0.8068108 -0.5580886 0.2188699 0.7338715 -0.6430619 0.1232305 0.5063266 -0.8534914 0.1666472 0.6237457 -0.7636557 0.01596921 0.05242836 -0.9984971 0.2202844 0.1280435 -0.9669952 0.09916651 0.3422253 -0.9343703 0.116549 0.4779639 -0.8706129 0.1877269 0.9494443 -0.251623 0.3752235 0.8920404 -0.2519353 0.3752006 0.8920544 -0.2519195 0.5217022 0.8152083 -0.2515199 0.5217026 0.815208 -0.2515199 0.6282587 0.7360537 -0.252024 0.6536757 0.7070293 -0.2698478 0.6899759 0.678501 -0.2521303 0.7601314 0.5990292 -0.2517229 0.7601727 0.5989414 -0.251807 0.8076295 0.5329372 -0.2524139 0.8278497 0.4961742 -0.2616797 0.8377822 0.4841954 -0.252341 0.8803905 0.4015298 -0.252362 0.8804032 0.4014484 -0.252447 0.9108264 0.326319 -0.2528069 0.9022418 0.35135 -0.250026 0.9484113 0.1906394 -0.2533231 0.939393 0.2119587 -0.2694703 0.9373804 0.2391996 -0.2531824 0.9189527 0.3027111 -0.252769 0.9189511 0.3027119 -0.2527737 0.8870537 0.3864891 -0.2525115 0.7914187 0.09292674 -0.6041697 0.960998 0.1107898 -0.2533938 0.9623482 0.107919 -0.2494784 0.25023 0.6663189 -0.7024273 0.2775182 0.6564835 -0.7014364 0.277472 0.6565341 -0.7014074 0.3849881 0.6002467 -0.7010622 0.3849856 0.6002547 -0.7010567 0.4842811 0.5236595 -0.7008942 0.4843718 0.5233733 -0.7010453 0.559577 0.4414417 -0.7014291 0.5596199 0.4411715 -0.701565 0.6105583 0.3669475 -0.7018319 0.6105629 0.3667899 -0.7019104 0.6473969 0.2965673 -0.7020863 0.647356 0.2963452 -0.7022178 0.6624296 0.259521 -0.7027347 0.6624415 0.2594834 -0.7027373 0.6754695 0.2241882 -0.7024818 0.6754727 0.224191 -0.7024778 0.6936948 0.1584064 -0.7026344 0.6937295 0.1584661 -0.7025865 0.6984933 0.1330893 -0.7031318 0.6092776 0.07291263 -0.7895978 0.1341399 0.2342746 -0.9628717 0.1050496 0.2440529 -0.9640555 0.1050173 0.2440921 -0.964049 0.1444888 0.2234664 -0.9639429 0.1444848 0.2234773 -0.963941 0.180985 0.1953447 -0.9638906 0.1810432 0.1951199 -0.9639251 0.2084506 0.1650907 -0.9639987 0.2084702 0.1648981 -0.9640275 0.227025 0.1377725 -0.9640946 0.2270187 0.1376581 -0.9641124 0.2404943 0.1119589 -0.9641721 0.2404508 0.1118191 -0.9641991 0.2458187 0.09836709 -0.9643117 0.2458119 0.0983901 -0.9643112 0.2506938 0.0854935 -0.964284 0.2506936 0.0854935 -0.9642841 0.2573857 0.06142574 -0.9643545 0.2574107 0.06145977 -0.9643456 0.2620677 0.0340256 -0.9644495 0.2620615 0.03401935 -0.9644514 0.3511586 0.8806962 0.3179023 0.8660305 0.4999482 0.006563007 0.7646306 0.4236302 0.4856721 0.7983251 0.3647573 -0.4791963 0.8515176 0.3623934 0.3789312 0.8348384 0.5504547 0.006683588 0.5451277 0.4286535 0.7204804 0.3449944 0.2804405 0.89573 0.7130164 0.7011146 0.00678718 0.6492135 0.7605767 0.00671631 0.2152962 0.3082944 0.9266079 0.5017869 0.7858475 0.3614606 0.3720105 0.8842172 -0.2824326 0.2665705 0.9637695 -0.009412705 0.1903228 0.9815452 0.01860797 1 0 0 1 -3.14401e-5 0 1 2.14187e-5 0 1 0 -1.19501e-7 1 0 0 0.9999964 -0.002712905 0 0.00479418 5.67943e-6 -0.9999885 0.03519588 1.84792e-4 -0.9993805 0.01676046 3.88902e-5 -0.9998596 0.009133756 9.96131e-6 -0.9999583 0.06385213 9.06787e-4 -0.997959 0.01890522 -9.43043e-4 -0.9998209 0.1623517 0.002707064 -0.9867292 0.120612 -0.003277122 -0.9926943 0.2467724 5.28106e-4 -0.9690734 0.3823885 -0.00271511 -0.9239977 0.4060398 0.002274513 -0.9138526 0.5410034 -7.35399e-4 -0.8410202 0.6721429 0.01037102 -0.7403489 0.5567402 -0.05508881 -0.8288581 0.7655063 0.04040932 -0.6421582 0.6857349 -0.01882106 -0.7276081 0.8379789 0.008350372 -0.5456387 0.9999833 0 -0.005783379 0.9075217 -0.03791117 -0.4182908 0.9669023 0.01320517 -0.254805 0.9940649 -0.02163654 -0.1066158 0.9955346 -0.01231253 -0.09359169 0.9996795 -9.28114e-4 -0.02530318 0.7976586 -0.01123815 -0.6030046 0.8445757 2.03933e-4 -0.5354362 0.9043906 -3.95697e-4 -0.4267056 0.9425942 0.03759688 -0.3318172 0.004719913 3.71091e-7 -0.9999889 0.004729807 3.81535e-7 -0.9999889 0.004727959 8.77773e-6 -0.9999889 0.003317415 7.48334e-6 -0.9999945 0.0101189 -2.71635e-5 -0.9999488 -0.004283964 1.15907e-4 -0.9999908 0.004729092 6.31197e-6 -0.9999889 0.004728376 1.15182e-6 -0.9999889 0.004727721 6.63674e-7 -0.9999889 0.9481242 -0.07197642 0.3096451 0.9549059 -0.2046806 0.2150831 0.9489495 -0.06550669 0.3085512 0.9358474 -0.08609783 0.3417264 0.9358844 -0.08539789 0.3418008 0.9208144 -0.09645861 0.3778843 0.9193156 -0.1030993 0.3797756 0.8980994 -0.1122676 0.425222 0.8921099 -0.1432819 0.4284976 0.9558073 -0.2007216 0.21481 0.9334771 -0.235252 0.2706976 0.9281952 -0.2611023 0.2651027 0.9062528 -0.277616 0.3188029 0.895043 -0.3072848 0.3232247 0.8656053 -0.3195024 0.3855459 0.8271018 -0.4163296 0.3775875 0.9669793 -0.1774241 0.182953 0.9684594 -0.120333 0.2181891 0.974804 -0.08867663 0.2046793 0.9612967 -0.1289888 0.2434557 0.9901601 0.1103746 0.08602696 0.9789955 -0.1036601 0.175563 0.9840264 -0.06159096 0.1670287 0.975142 -0.1071137 0.1939716 0.9800528 -0.07143074 0.1854567 0.988932 0.1483694 0 0.9999853 0.00370723 0.003980278 0.9314812 0.3637394 -0.006037771 0.9988147 0.04814308 0.007178127 0.7264123 0.6872592 -1.44506e-7 0.7353748 0.6776605 3.28017e-4 0.8606073 0.5092691 -1.80232e-4 0.8672187 0.4979275 0 0.9216322 0.3880646 0 0.976554 0.2152664 0.001606464 0.9551385 -0.1225796 0.2696014 0.8566786 -0.2822278 0.4317979 0.909219 -0.1649041 0.3822663 0.932143 -0.2165718 0.290183 0.9054906 -0.2231243 0.3609742 0.974644 -0.08692759 0.2061858 0.8305168 0.4818691 -0.2793638 0.9644604 -0.1005985 0.244328 0.9587622 -0.121694 0.2568379 0.8609302 0.2351873 0.4510946 0.8583759 -0.2835947 0.4275104 0.7946708 -0.381124 0.4724857 0.8264039 -0.1693817 0.5369976 0.8653832 0.1940199 0.4620262 0.8496372 0.169946 0.4992344 0.848975 0.1078132 0.5173181 0.8374793 0.09681117 0.5378253 0.8253982 0.04370397 0.5628569 0.788689 0.02066928 0.614445 0.7933519 0.0349369 0.60776 0.871149 -0.1418259 0.4700902 0.7687777 -0.4400479 0.4640461 0.7980133 -0.4148663 0.437105 0.8627803 -0.151278 0.4824159 0.8456305 -0.1479287 0.5128608 0.8249001 -0.1877413 0.5331914 0.6836941 -0.5433083 0.487215 0.7188968 -0.3752916 0.5851015 0.7472624 -0.4355611 0.501882 0.5632593 -0.5542996 0.6127732 0.6295102 -0.5072017 0.5886114 0.7747828 -0.1950523 0.601387 0.7806041 -0.1987601 0.5925806 0.802369 -0.1724103 0.5713831 0.4508579 -0.6506118 0.6110905 0.5738663 -0.5609903 0.5966302 0.6110839 -0.4874923 0.6236408 0.7487241 -0.2066291 0.6298545 0.7517286 -0.2187532 0.6221343 0.9799424 -0.07060468 0.1863545 0.9824667 0.1662167 0.0844472 0.6857397 0.726234 0.04842936 0.7645305 0.631332 0.1300501 0.7922096 0.5040768 0.3439631 0.776721 0.5667034 0.2748668 0.7140753 0.6438153 0.2749517 0.6901074 0.6873931 0.2263682 0.6264468 0.7409989 0.2418369 0.803896 0.5944839 0.01844835 0.8361676 0.5429523 0.07763087 0.9264232 0.3653306 0.09095948 0.9252915 0.36925 0.086546 0.983445 0.1428108 0.1115396 0.8424562 0.4616877 0.277691 0.7669486 0.4927496 0.4110811 0.8762729 0.2894241 0.3852008 0.8456432 0.3812275 0.3735681 0.9602241 0.1340935 0.2449261 0.9861815 -0.05753982 0.1553552 0.9839597 -0.06113034 0.16759 -0.46577 0.8281714 0.3117541 -0.4683646 0.8281217 0.3079761 0.4060874 0.9138343 -7.00406e-5 0.497509 0.867307 -0.0162394 0.5094175 0.8602958 -0.01962447 -0.1696813 0.985499 0 -0.4306559 0.8843063 0.180383 -0.2028274 0.9755716 0.08438688 -0.4519239 0.888306 0.08171457 -0.1918344 0.9811486 0.02339243 -0.2281066 0.9734567 0.01869463 -0.2602585 0.9655233 0.005524933 0.08746457 0.9961519 -0.00559616 -0.3778517 0.889411 0.2572475 -0.4265183 0.8740253 0.2327272 -0.3746473 0.8939888 0.2458117 -0.3806667 0.8989194 0.2168802 -0.374316 0.8985476 0.2291285 -0.3771055 0.9011464 0.213838 -0.3728851 0.8998717 0.2262468 -0.375918 0.9017599 0.213342 -0.3724674 0.9002879 0.2252771 -0.375974 0.9022263 0.211261 -0.3716816 0.9006854 0.224986 -0.3755445 0.9031155 0.208204 -0.4057672 0.8960173 0.1802945 0.4440245 0.8960146 3.02295e-4 0.4440758 0.8959748 0.005096614 0.4438428 0.8960911 0.004959881 0.4442113 0.8957201 0.01902669 0.4405708 0.8975204 0.01883095 0.443282 0.895346 0.04308944 0.4353706 0.8991971 0.0435571 0.4390169 0.8966945 0.05659532 0.4368512 0.8977648 0.05638879 0.4386041 0.8968605 0.05716466 0.4375715 0.8974359 0.05603641 0.4382569 0.8969939 0.05773311 0.4376614 0.8973757 0.05630016 0.4382476 0.896947 0.05852562 0.4374436 0.8974352 0.05703675 0.4387078 0.8964359 0.06275576 0.4353934 0.8981063 0.06194931 0.4385203 0.8955666 0.07523721 0.4311528 0.8990952 0.0757302 0.09651517 0.9778924 0.1855027 0.02565729 0.9996708 5.63964e-4 0.02578938 0.9995625 0.01448506 0.02507227 0.9995867 0.01407247 0.02615702 0.9981963 0.05403739 0.01407074 0.9984811 0.05326789 0.02173382 0.9922867 0.1220442 -0.004593372 0.9924556 0.1225188 0.002534031 0.9875776 0.1571114 0.003365218 0.9868161 0.1618108 0.003495037 0.9867556 0.1621768 0.0022794 0.9874827 0.1577113 0.003430485 0.9866569 0.1627775 0.001891613 0.987402 0.1582205 0.003278434 0.9862902 0.1649882 0.001113295 0.9870642 0.1603222 0.00454694 0.9842321 0.1768231 -0.006364762 0.9847527 0.1738442 0.00565648 0.9744535 0.2245188 -0.1377313 0.9606846 0.2410712 -0.2013665 -0.2629544 0.9435607 -0.1725968 0.3099924 0.9349413 -0.3151935 0.01015615 0.9489732 -0.3279479 0.1502687 0.932668 -0.347601 0.1594188 0.923991 -0.3663949 0.1734445 0.9141508 -0.3638008 0.2787059 0.8888037 -0.5113527 0.009624838 0.859317 -0.4119849 0.430006 0.8033451 -0.6391059 -0.05375474 0.767238 0.9932555 0.09219741 0.07030743 0.987859 0.03979194 0.1501711 0.9430257 0.3003173 0.1432209 0.8808672 0.4714098 0.04296368 0.5874962 0.8086676 -0.03008711 0.7378495 0.6702796 0.07939523 0.8574002 0.5062011 0.09287303 0.5301359 -0.2177886 0.8194659 0.3402363 -0.7144413 0.6114024 0.4382141 -0.6429344 0.6281749 0.566925 -0.4693797 0.6769629 0.5719988 -0.463886 0.6764815 0.7414533 -0.1778071 0.6470175 0.7241764 -0.2022597 0.6592872 0.1798518 -0.7883955 0.5882907 0.3109144 -0.6980559 0.6450195 0.4445131 -0.5346952 0.7186858 0.5226506 -0.4448584 0.7272809 0.6414778 -0.2005468 0.7404642 0.6734529 -0.1404303 0.7257689 0.03788506 -0.8367553 0.546265 0.1486366 -0.7734194 0.616222 0.3146864 -0.5810329 0.750582 0.3862015 -0.5066684 0.7708021 0.5284373 -0.2291144 0.8174721 0.5970544 -0.17909 0.7819547 0.9006256 -0.006566345 0.4345465 0.9156926 0.01446747 0.4016193 0.9225562 0.03302729 0.3844466 0.9243335 0.0452212 0.3788965 0.9241691 0.043509 0.3794977 0.9236952 0.03828275 0.3812112 0.923291 0.03309541 0.3826727 0.9232552 0.03227001 0.3828297 0.884144 0.006752431 0.4671658 0.8786901 0.01353371 0.4772008 0.8696871 0.001644253 0.4936009 0.8459103 -0.001352787 0.5333235 0.8399441 0.006669163 0.5426321 0.8280705 3.89154e-7 0.560624 0.4704936 0 0.8824034 0.4745437 0.03273731 0.879623 0.539683 -0.01072072 0.8418002 0.5957371 0.09882563 0.7970765 0.598834 -0.01453697 0.8007413 0.6668018 0.01203662 0.7451379 0.6628546 0.0387634 0.7477442 0.7223743 -0.09907907 0.6843674 0.7267816 0.06023365 0.6842226 0.7969635 -0.04119706 0.602621 0.7878878 0.02059805 0.6154744 0.8152062 -2.26624e-5 0.5791708 0.0264554 0.9690577 0.2454125 0.02987933 0.970991 0.2372421 0.02435696 0.7358151 0.6767445 0.03474581 0.7512621 0.6590889 0.01528501 0.3255686 0.9453949 0.03365588 0.3614547 0.9317821 0.07009506 0.9654138 0.2511236 0.0729078 0.966809 0.2448772 0.05352175 0.7219059 0.6899183 0.06253963 0.7339779 0.6762879 0.02258539 0.2963852 0.9548014 0.03868126 0.3244506 0.9451114 0.09800797 0.9626319 0.2524567 0.09933221 0.9628683 0.2510332 0.06186276 0.7176722 0.6936278 0.06697666 0.7207514 0.6899505 -0.02121025 0.2927203 0.9559629 0.009308338 0.2890898 0.9572567 0.01870548 0.296733 0.9547774 -0.09679621 0.2336164 0.9674988 0.001027345 0.4635475 0.8860715 0.05052131 0.7190276 0.6931428 -0.08273249 0.6357926 0.7674134 0.1156032 0.9748603 0.1904816 0.06800937 0.9655914 0.2510144 0.08882987 0.8967604 0.4335092 0.06440156 0.7989084 0.5979949 -0.4473015 0.4160251 0.7917352 -0.4444342 0.4189927 0.791785 -0.2222497 0.7059768 0.6724596 -0.213019 0.7118147 0.6692854 0.03612518 0.8909546 0.4526534 0.05169653 0.8948314 0.4434008 0.2890487 0.9429854 0.1650133 0.3087255 0.9394032 0.1490311 -0.371883 0.3706047 0.8510907 -0.3644291 0.3807728 0.8498257 -0.1802709 0.670447 0.7197244 -0.1668115 0.682249 0.7118359 0.03749054 0.8741374 0.4842299 0.05641037 0.882346 0.4672081 0.2498485 0.9517177 0.1783509 0.2715883 0.950257 0.1524847 0.2334966 0.9573264 0.1703099 0.2251216 0.9582833 0.1761066 0.05535888 0.8682147 0.4930908 0.0475316 0.8663874 0.4971052 -0.130373 0.6542193 0.7449833 -0.1371425 0.6507576 0.7467975 -0.2972232 0.3460133 0.8899064 -0.230295 0.3110278 0.922077 -0.2837932 0.3365326 0.8978906 -0.3023949 0.3421764 0.8896475 0.1508319 0.9724393 0.177797 0.1448336 0.9704346 0.19308 0.09289795 0.8961741 0.4338687 0.07594364 0.8457788 0.5281011 -0.06240665 0.4720835 0.8793423 -0.01714378 0.5993359 0.8003141 -0.01346629 0.628863 0.7773995 0.04563874 0.8015119 0.5962347 0.2041059 0.9645972 0.1670127 0.1919116 0.9632062 0.1881589 0.06245148 0.8617041 0.5035533 0.04906719 0.8519392 0.5213369 -0.0877496 0.6349771 0.7675313 -0.1010603 0.6184622 0.7792891 -0.2321504 0.2959846 0.9265524 -0.1094877 0.2680798 0.9571551 -0.1229076 0.2370319 0.9636958 -0.4421433 0.8110364 0.3830525 0.4362758 0.8950102 0.0928446 0.1052968 0.9709562 0.2148414 -0.1211561 0.9473251 0.2964732 0.4618897 0.8825629 0.08798152 0.4596436 0.8842949 0.08215993 0.4156318 0.903835 0.1016499 0.4183749 0.9019977 0.1065962 0.4053195 0.9079121 0.1068267 0.4054822 0.9078024 0.10714 0.3626921 0.9222936 0.133526 0.3569446 0.925527 0.1264532 0.3180307 0.9349347 0.1573328 0.1246203 0.9694104 0.2114555 0.1413214 0.9567201 0.2543912 0.0821821 0.9583209 0.2736189 0.09985804 0.9468205 0.305875 0.08311998 0.9487521 0.3048943 0.09945487 0.9378482 0.33249 0.04495668 0.9328811 0.3573678 0.07344537 0.9167835 0.3925734 0.02616751 0.9068878 0.4205592 -0.2265018 0.9222542 0.3132798 -0.1956627 0.8988379 0.3921821 -0.2628282 0.8754416 0.4056149 -0.2325335 0.8559405 0.4618378 -0.2513988 0.85255 0.4582108 -0.2204189 0.8315951 0.5097696 -0.279539 0.8029182 0.5264792 -0.2204496 0.7694157 0.5995011 -0.2698793 0.7385677 0.617805 -0.5439299 0.748279 0.3797615 -0.5054634 0.7189959 0.4770237 -0.5699664 0.667707 0.4788589 -0.5314106 0.6423323 0.552279 -0.5498664 0.633314 0.5445737 -0.5074859 0.6050874 0.6134552 -0.5617451 0.5527744 0.6155347 -0.4801642 0.5064122 0.7162327 -0.524076 0.4568517 0.7187705 0.6266868 0.7792713 -1.2389e-7 0.6266895 0.7792692 0 0.6266862 0.7792717 2.01385e-6 0.6266877 0.7792705 -1.97874e-6 0.6266834 0.7792739 -4.26311e-7 0.6266947 0.7792649 2.59006e-7 0.6266734 0.779282 -7.85261e-7 0.6267701 0.7792043 1.08274e-5 0.6266422 0.7793072 -2.05167e-5 0.62691 0.7790917 -8.77003e-6 0.6270029 0.7790169 5.50776e-5 0.6266873 0.779271 0 0.1222589 0.1520258 -0.9807859 0.1491249 0.2121563 -0.9657906 0.2771745 0.3446601 -0.8968744 0.3815038 0.4743928 -0.7933514 0.4256067 0.5648994 -0.7069283 0.4971799 0.6182382 -0.6087641 0.5620654 0.6989058 -0.4422817 0.5922003 0.7631068 -0.25878 0.6146486 0.7642957 -0.1950882 0.1429797 0.1352736 -0.9804376 0.9380038 0.2194123 -0.2683414 0.797227 0.215822 -0.5637819 0.8061773 0.2084265 -0.5537476 0.5494565 0.1497325 -0.8219963 0.5325935 0.1603619 -0.8310405 0.2603616 0.0638802 -0.9633957 0.1681383 0.1077564 -0.9798562 0.05964744 0.01747894 -0.9980665 0.142977 0.135273 -0.9804381 0.3236817 0.3062345 -0.8952377 0.4216199 0.3642133 -0.8304128 0.6526708 0.6174918 -0.4390042 0.6199618 0.5563717 -0.5532613 0.5782721 0.5470994 -0.6052137 0.4447906 0.4208087 -0.7906208 0.976182 0.2151876 -0.0276243 0.9493184 0.2471221 -0.1942302 0.9039646 0.3806229 -0.1948694 0.8247993 0.4880797 -0.2854546 0.1740322 0.09195894 -0.9804369 0.1740283 0.09196013 -0.9804374 0.4943497 0.2612238 -0.8290841 0.4943512 0.2612248 -0.829083 0.7372361 0.389566 -0.5520158 0.7372334 0.389567 -0.5520188 0.8674654 0.4583825 -0.1933636 0.7127032 0.6742878 -0.1933653 0.7127074 0.674286 -0.1933563 0.7601824 -0.3997935 0.5121408 0.704191 -0.412658 0.5777788 0.7654322 -0.001771807 0.6435142 0.7875128 -0.3841591 0.4819186 0.767549 -0.400919 0.5001325 0.7780742 -0.1891298 0.5990245 0.7886493 0.03369015 0.6139196 0.7916267 0.03420734 0.6100469 0.5610168 -0.5236871 0.6411023 0.6932213 -0.3234509 0.6440682 0.7282667 -0.1700485 0.6638608 0.7267422 0.01993376 0.6866211 0.6847535 0.05856847 0.7264176 0.7101612 0.07436352 0.7001009 0.5144909 -0.5715704 0.6392234 0.6744393 0.04567992 0.7369159 0.6434816 0.07026368 0.76223 0.6590142 0.07377523 0.7485035 0.6289552 -0.1961309 0.7522952 0.5868856 -0.2480968 0.7707227 0.5612531 -0.4468098 0.696675 0.3625478 -0.6460986 0.6716516 0.5828631 -0.5256476 0.6196492 0.5137326 -0.5714786 0.639915 0.640803 -0.3193793 0.6981178 0.6782486 -0.261274 0.6868151 0.6692723 -0.1651403 0.7244331 0.6931594 0.07579618 0.7167881 0.4933748 0.8698168 0 0.5877711 0.8090271 -5.78082e-4 0.4890117 0.8713017 0.04124337 0.5359803 0.8442267 0.002591788 0.574316 0.8099264 0.1190817 0.6462847 0.7629511 0.01489216 0.6210425 0.7837672 0.003921568 0.5939562 0.8044973 -6.16228e-4 0.6735445 0.7388878 0.01956468 0.6670932 0.7425089 0.06055861 0.6693195 0.7418949 0.04004222 0.9982086 0.0402041 0.04430878 0.9924128 0.1229397 0.00166285 0.8816766 0.4718449 -0.002949535 0.9121499 0.4092611 0.02209275 0.8283602 0.5601959 3.11201e-4 0.6039097 0.7671535 0.2162608 0.4704478 0.8820897 0.02442705 0.4949618 0.8675571 0.04855525 0.555112 0.7794215 0.2904357 0.5479192 0.8341116 0.06357991 0.5685657 0.8201516 0.06390941 0.4950138 0.8650102 0.08196878 0.5806509 0.8097581 0.08447617 0.4881866 0.8674941 0.09554117 0.5767933 0.8093431 0.1107851 0.4745652 0.8739556 0.1048312 0.5621094 0.8165846 0.1312359 0.6004962 0.7877753 0.1371658 0.5680377 0.81421 0.1199814 0.7773809 0.6088119 0.1582002 0.589139 0.7866107 0.1848216 0.6063826 0.7757462 0.1746941 0.6266667 0.7792869 9.55867e-4 0.6269116 0.7790512 0.007820367 0.6323908 0.773835 0.03551471 0.62797 0.7772237 0.03971135 0.6156935 0.7810111 0.104611 0.6425959 0.7612296 0.08717918 0.6119865 0.7810208 0.1244144 0.5581743 0.7561729 0.3415319 0.5593085 0.779721 0.2814416 0.5575765 0.7808825 0.2816575 0.5494484 0.7781642 0.3042482 0.5876825 0.7701684 0.2479315 0.6036588 0.7502567 0.2696496 0.5084031 0.8349727 0.2105875 0.5601071 0.7780398 0.2844896 -0.5158823 0.8566596 0 -0.5417154 0.8405539 0.003680348 -0.3255358 0.9455283 -0.001679062 -0.1697352 0.9854843 0.003291428 -0.08015328 0.9967825 -3.90939e-4 0.1140756 0.9934721 3.16832e-4 0.2028543 0.9792046 0.002921104 0.2867448 0.9580071 0 -0.5492167 0.8274967 0.1166638 -0.2091987 0.9677658 0.1402329 -0.1902998 0.9698145 0.1524661 -0.5372335 0.818429 0.2038482 0.1854515 0.9820567 0.03424185 0.1902816 0.9801491 0.05568516 0.1810621 0.9822043 0.0499131 0.2007758 0.9789389 0.03698253 -0.1729441 0.980643 0.09181362 -0.2008146 0.9739169 0.1056387 -0.4999075 0.8552075 0.1367948 -0.5419672 0.8160901 0.2006708 -0.5156225 0.8562212 0.03192085 -0.4902296 0.8704231 0.04514956 -0.169641 0.9849269 0.0337792 -0.1796532 0.9832444 0.03090769 0.2028386 0.9791348 0.0123099 0.1978956 0.9801627 0.01088398 -0.5154538 0.8197076 0.2497736 -0.5238738 0.7869682 0.325941 -0.5287349 0.8152337 0.2362914 -0.5269491 0.8154625 0.2394699 -0.5263803 0.8152344 0.2414883 -0.5254353 0.8157846 0.241688 0.1705881 0.9827111 0.07196331 0.1873758 0.9792709 0.07693427 -0.06534367 0.985305 0.1578112 -0.1935469 0.9656656 0.1732905 -0.2511996 0.9401601 0.2302128 -0.5274817 0.7989019 0.2889962 -0.5303919 0.7961229 0.2913295 -0.5239989 0.8159858 0.2441157 -0.5171549 0.8177432 0.2526795 -0.2015483 0.9647976 0.1689494 -0.1941018 0.96586 0.1715785 0.1835708 0.9812177 0.05927634 0.1813412 0.9816783 0.05850708 0.1088864 0.7922746 0.6003707 -0.0547018 0.9812334 0.1849026 -0.4915689 0.5104407 0.7055568 -0.4845319 0.5152282 0.7069432 -0.5566624 0.572462 0.6020087 -0.5261968 0.5959168 0.6066302 -0.5758275 0.6190595 0.53403 -0.5584738 0.6240582 0.5464965 -0.6060928 0.6417945 0.4698419 -0.5407049 0.695712 0.472888 -0.6622736 0.677386 0.3202217 -0.5045726 0.7788085 0.3726444 0.1742426 0.9813446 0.08125543 -0.4560778 0.4753488 0.7523541 -0.3978149 0.4575319 0.7952408 -0.4134823 0.4466667 0.7934237 -0.305761 0.4172549 0.8558087 -0.2988668 0.4215851 0.856122 -0.2452521 0.3795082 0.8920903 -0.1559373 0.356261 0.9212827 -0.1817121 0.3349721 0.9245401 -0.05133837 0.3067561 0.9504027 -0.02673465 0.3167526 0.9481313 -0.01875007 0.3072054 0.9514585 0.01696556 0.2838163 0.9587286 0.06242334 0.6149739 0.7860729 0.04602748 0.7274369 0.6846292 -0.002886295 0.7376372 0.6751912 -0.008247315 0.7524998 0.6585409 -0.08756846 0.7720978 0.6294416 -0.08888703 0.785342 0.6126476 -0.1530944 0.8031521 0.5757681 -0.1532226 0.8127639 0.5620833 -0.2110651 0.8294963 0.5170952 -0.2068657 0.8391069 0.5030966 -0.2607801 0.8563386 0.445733 -0.2552095 0.8638924 0.4342328 -0.2805449 0.8731307 0.3986696 -0.2818136 0.875494 0.3925446 -0.3066155 0.8835122 0.3541091 -0.3000257 0.8892067 0.3453929 -0.3073859 0.8923147 0.3305884 -0.2408983 0.9361059 0.2562689 0.1396585 0.9809098 0.1353209 0.1353597 0.9827076 0.126348 0.1190652 0.9847306 0.1270014 0.1312591 0.9806026 0.1455668 0.123982 0.9822466 0.1407835 0.1360156 0.978035 0.1579473 0.1186801 0.9798399 0.1607131 0.1389873 0.9733653 0.1823251 0.1216403 0.9747385 0.1873194 0.1435496 0.9683324 0.204269 0.1292185 0.9694474 0.2085052 0.1524488 0.9630729 0.2219233 0.1386764 0.9634012 0.2294058 0.165113 0.9568523 0.2391055 0.1544778 0.9566907 0.2467378 0.1813712 0.9506869 0.251593 0.1741808 0.9500959 0.2588031 0.3270573 -0.2087156 0.9216677 0.3925132 0 0.9197465 0.009036362 -0.8685839 0.4954599 0.01425743 -0.8578855 0.5136432 0.3584857 0.5479673 0.7557908 0.3169204 0.786375 0.5302603 0.2150521 -0.3192708 0.9229403 0.245515 0.8208941 0.5156116 0.06809449 -0.726319 0.6839765 0.6768855 0.6000539 0.4263348 0.5494585 0.8310109 0.08669728 0.5436449 0.8354091 0.08088248 0.7056237 0.6864388 0.1757758 0.7924578 0.5596196 0.2425631 0.8091477 0.5331245 0.2470999 0.8900148 0.3287281 0.3159298 0.9124379 0.1917061 0.3615326 0.9208037 0.1393063 0.3642999 0.5303251 0.8408786 0.1080678 0.5259938 0.8443847 0.1017103 0.7669508 0.5700847 0.2946015 0.7674749 0.5687038 0.2959027 0.8775627 0.2060708 0.4329187 0.7959186 0.3319903 0.5062569 0.8421294 0.2092919 0.4970062 0.8768739 0.1955264 0.4391604 0.4715445 0.8673785 0.159061 0.4658796 0.8724405 0.1476622 0.4349417 0.8827533 0.1776863 0.4328928 0.8854096 0.169274 0.395861 0.8964067 0.1993718 0.3927819 0.9002489 0.1878149 0.3401113 0.9141874 0.2204214 0.3386535 0.917123 0.2102358 0.6775491 0.5973935 0.4290086 0.6237133 0.6155812 0.4817069 0.6237516 0.6137908 0.4839367 0.5618152 0.6320683 0.5337165 0.5619784 0.6289571 0.5372089 0.4753471 0.6519504 0.5907673 0.4751167 0.6486414 0.5945826 0.5073113 0.8515306 0.132404 0.5007296 0.8568961 0.122471 0.7305694 0.5826905 0.3560058 0.7313797 0.5803902 0.3580936 0.8289657 0.1959887 0.5238362 0.7567038 0.2222967 0.6148038 0.753912 0.2037424 0.6245846 0.6878874 0.2259324 0.6897575 0.6839486 0.2139846 0.6974416 0.6099642 0.2361241 0.7564319 0.6050493 0.2173318 0.7659519 0.5038037 0.2443194 0.8285469 0.4981496 0.2263137 0.8370359 0.1668837 0.9514141 0.2587686 0.03421813 0.280588 0.9592182 0.02850657 0.2767133 0.9605296 0.02832043 0.2764358 0.9606151 0.02733433 0.2735881 0.9614585 0.07499229 0.4722884 0.8782482 0.08317637 0.6115272 0.7868394 0.1181256 0.7879202 0.6043412 0.117928 0.7908139 0.6005885 0.1281338 0.9682331 0.2147241 0.1193073 0.9791864 0.164195 0.006181657 0.974762 0.2231612 0.008206307 0.9772866 0.2117629 0.01485216 0.7804488 0.6250433 0.02145451 0.8017703 0.5972471 0.01982772 0.4305022 0.9023718 0.03198188 0.4823213 0.8754104 0.005946934 0.9712905 0.2378227 0.008812487 0.9747577 0.2230916 0.01307362 0.7514292 0.6596842 0.02249819 0.7804484 0.6248153 0.01607573 0.3614946 0.9322357 0.03345501 0.430493 0.9019738 0.5619673 0.7857502 -0.2584367 0.4116721 0.5756049 -0.7065445 0.1507874 0.210831 -0.9658227 0.1507903 0.2108308 -0.9658223 0.1260756 0.2264734 -0.9658234 0.1260785 0.226474 -0.9658229 0.09976404 0.2392335 -0.9658232 0.09976494 0.2392368 -0.9658223 0.07218229 0.2489488 -0.9658231 0.07218295 0.2489504 -0.9658227 0.04367947 0.2554965 -0.9658229 0.04368042 0.2554959 -0.965823 0.01462107 0.2587906 -0.9658229 0.01462209 0.2587898 -0.9658231 0.411676 0.5756058 -0.7065415 0.3442159 0.6183142 -0.706543 0.3442153 0.6183153 -0.7065424 0.2723745 0.653152 -0.7065442 0.2723759 0.6531535 -0.7065423 0.1970692 0.6796763 -0.7065436 0.19707 0.6796762 -0.7065435 0.1192551 0.6975468 -0.7065456 0.1192538 0.6975547 -0.7065381 0.03992062 0.7065427 -0.7065436 0.03992217 0.7065427 -0.7065435 0.5619697 0.7857505 -0.2584302 0.4698827 0.8440522 -0.2584302 0.4698836 0.8440518 -0.2584299 0.371817 0.8916078 -0.2584334 0.371817 0.8916089 -0.2584296 0.269018 0.9278172 -0.2584273 0.2690173 0.9278147 -0.2584366 0.1627904 0.9522141 -0.2584332 0.1627922 0.9522129 -0.2584365 0.05449551 0.9644892 -0.2584395 0.05449426 0.9644911 -0.2584329 0.4109308 0.9116666 -4.25066e-5 0.6142139 0.7891396 0 0.5807248 0.8140998 -4.86949e-4 0.486406 0.8737329 9.51585e-5 0.464635 0.8855017 -0.001069366 0.58173 0.8133808 0.001489043 0.5238237 0.8518219 -0.00288105 0.554352 0.8322811 -0.001520991 0.1301034 0.9914987 -0.001890301 0.1817425 0.9833462 -4.70969e-5 0.2784771 0.9604429 6.53443e-5 0.2591155 0.9658459 -9.1223e-4 0.3848921 0.9229609 0.00119704 0.3087548 0.9511337 -0.003904759 0.3545051 0.9350532 -0.001341104 0.1060655 0.9943546 -0.002990603 0.1685169 0.9856987 5.22895e-4 0.07053303 0.9975094 -2.61383e-4 0.05641084 0.9984075 -6.55886e-4 0.02352583 0.9997233 0 0.2624127 -0.7127816 0.6504476 0.3376441 -0.2147879 0.9164402 0.3222811 -0.2185937 0.9210601 0.4883561 0.1540949 0.8589314 0.4259354 0.1729457 0.8880702 0.4351486 0.1756386 0.8830611 0.2426518 -0.5810453 0.7768568 0.1978097 -0.5689377 0.7982365 0.153563 -0.5755704 0.8032043 0.257735 -0.5124992 0.8190954 0.3935266 -0.2309449 0.8898323 0.3942122 -0.2035124 0.8962028 0.4771239 0.1318254 0.8688929 0.5688855 0.1063027 0.8155177 0.5629705 0.09153026 0.8213931 0.4998018 -0.1958394 0.8437092 0.4976578 -0.2321503 0.8357291 0.390627 -0.4652749 0.794311 0.3692378 -0.5431898 0.7540613 0.1694384 -0.7734593 0.6107792 0.07017809 -0.781333 0.6201563 0.05465233 -0.823686 0.5644066 -0.03473246 -0.8271885 0.5608502 0.3979042 -0.6536479 0.6437521 0.3139656 -0.7090467 0.63141 0.5130062 -0.4381493 0.7381395 0.4632808 -0.4829346 0.7430647 0.5895981 -0.1887766 0.7853264 0.5715063 -0.2126286 0.7925716 0.626658 0.07337033 0.7758328 0.6282016 0.07648938 0.7742817 -0.00933057 -0.8489861 0.5283329 0.0385372 -0.8370184 0.5458161 0.2516984 -0.5885949 0.7682474 0.2849962 -0.56896 0.7714025 0.412434 -0.1952033 0.889828 0.4623122 -0.2136066 0.8606042 0.4802968 -0.1970535 0.8546842 -0.05407696 -0.8874004 0.4578168 0.009920358 -0.8561501 0.516632 0.1348505 -0.7098048 0.6913701 0.2389732 -0.5838482 0.775895 0.255415 -0.5423555 0.8003835 0.3884499 -0.2345407 0.8911214 0.2428297 -0.1913453 0.9510104 -0.09676331 -0.9346524 0.3421429 -0.02110594 -0.8963428 0.4428592 0.05643665 -0.7744605 0.6300999 0.116085 -0.7047237 0.6999206 0.2088798 -0.5133321 0.8323818 0.1992915 -0.5270878 0.8261123 0.2562964 -0.2942424 0.9207245 -0.09678924 -0.9601466 0.2622031 -0.06076776 -0.9423683 0.3290125 0.03281337 -0.8089541 0.5869554 0.06133222 -0.7755182 0.6283391 0.157006 -0.5402907 0.8267015 0.1756795 -0.5061491 0.8443637 0.262872 -0.1691941 0.9498798 0.3423087 -0.1862372 0.9209455 0.3246463 -0.2170458 0.9205954 -0.07570743 -0.9772757 0.1979917 -0.05372595 -0.9664992 0.2509837 0.01649951 -0.8330742 0.5529153 0.03387171 -0.8091122 0.5866773 0.1055706 -0.559427 0.8221291 0.1169109 -0.5344138 0.8370985 0.1777625 -0.1991238 0.9637169 0.1831963 -0.1825693 0.965975 0.002649545 -0.3967318 -0.9179307 0.002561748 -0.3809993 -0.9245718 0.002971947 -0.3893333 -0.9210922 -1.92758e-4 -0.1691457 -0.9855911 7.16384e-4 -0.1308689 -0.9913995 6.25556e-4 -0.1308711 -0.9913992 0.001025557 -0.143821 -0.9896032 0.001575171 -0.405541 -0.9140756 0.002480685 -0.4149644 -0.9098344 0.01374793 -0.414891 -0.9097673 0.03685295 -0.4095328 -0.9115508 0.07585853 -0.1430791 -0.9867998 0.04622852 -0.123804 -0.9912293 0.03765648 -0.4091368 -0.9116958 0.1286862 -0.4182341 -0.8991775 0.205759 -0.3465535 -0.9151853 0.2532153 -0.3731732 -0.8925379 0.4523199 -0.3715265 -0.8107866 0.420883 -0.2718639 -0.8654175 0.7930001 -0.2574883 -0.5521328 0.7554137 -0.2504462 -0.6054974 0.718514 -0.2176205 -0.6605899 0.6606172 -0.2981541 -0.6889769 0.5518301 -0.3236089 -0.7686097 0.8789469 -0.1953907 -0.4350576 0.8672974 -0.3997484 -0.2966422 0.9119288 0.03219068 -0.4090841 0.2670621 -0.1462666 -0.9525145 0.2081595 -0.04816913 -0.9769082 0.5439627 -0.1156449 -0.8311023 0.4923717 0.027911 -0.8699375 0.7864962 -0.09097874 -0.6108573 0.7504798 0.08606827 -0.6552652 0.9320859 -0.07985228 -0.3533263 0.9121163 0.1213392 -0.3915618 0.9871578 -0.06275475 -0.1469061 0.9772022 0.1066545 -0.1835772 0.9999818 -0.003103971 -0.005180001 0.9994106 0.02781254 -0.02012264 0.9994053 0.03051251 -0.01606667 0.9967468 -0.008161425 -0.08018195 0.997415 -0.007059276 -0.07150971 0.9598571 -0.1631662 -0.2281473 -2.54376e-5 -0.3955482 -0.9184452 0.004108846 -0.1678819 -0.9857986 0.002643048 -0.3614912 -0.9323718 0.002560913 -0.3614899 -0.9323725 0.003434121 -0.4030218 -0.915184 0.002481818 -0.4030148 -0.9151901 0.003400444 -0.4126709 -0.9108739 0.008788347 -0.1229875 -0.9923694 0.003983676 -0.1229723 -0.9924021 0.00425446 -0.1378427 -0.9904451 0.003957569 -0.1378419 -0.9904464 0.00425899 -0.1413244 -0.9899543 0.0137856 -0.4126724 -0.9107753 0.01026481 -0.4119229 -0.911161 0.008229792 -0.1413323 -0.9899281 0.007043182 -0.1410437 -0.9899784 0.03670072 -0.4109098 -0.910937 0.02780556 -0.4096298 -0.911828 0.0255481 -0.1403441 -0.9897732 0.02586948 -0.1403795 -0.9897599 0.1260128 -0.1371968 -0.9824957 0.5465846 -0.3457298 -0.7627033 0.3937329 -0.3539646 -0.8483417 0.4028187 -0.3765617 -0.8342294 0.2401162 -0.3870456 -0.8902472 0.2507916 -0.3922725 -0.8850006 0.1210324 -0.3963533 -0.9100854 0.1296768 -0.4053655 -0.9049104 0.6475847 -0.3464837 -0.6786628 0.6605727 -0.3251028 -0.6767215 0.5347327 -0.3375569 -0.7746717 0.1263512 -0.1375334 -0.9824052 0.2527685 -0.1329744 -0.9583454 0.2530326 -0.1331097 -0.958257 0.4123187 -0.1247077 -0.9024641 0.4125294 -0.125137 -0.9023083 0.5588808 -0.1158512 -0.8211156 0.5589076 -0.1159034 -0.8210899 0.6895405 -0.1040245 -0.7167378 0.6895668 -0.1040476 -0.716709 0.8013503 -0.09038335 -0.5913277 0.8012101 -0.09020316 -0.5915454 0.7478321 -0.280687 -0.6016327 0.7884559 -0.2747696 -0.5503082 0.7800301 -0.2620776 -0.5682151 0.8753154 -0.2433883 -0.4178341 0.8779755 -0.1898195 -0.4394629 0.8894273 -0.07466709 -0.450937 0.9019787 0.03185772 -0.4306039 0.848622 -0.08235532 -0.5225498 0.9609159 -0.1578052 -0.2274603 0.9999828 -0.002748608 -0.005196988 0.9996895 -0.004887223 -0.02443629 0.9996908 -0.01020252 -0.02267599 0.9955568 -0.01889234 -0.09224885 0.9955736 -0.03962075 -0.08522588 0.9691433 -0.05957072 -0.2391919 0.9679437 -0.04348647 -0.2473742 0.8232481 0.5626441 -0.07546013 0.5437814 0.8387197 -0.02917367 0.9801635 0.1980615 -0.00715816 0.9802151 0.1978177 -0.006835818 0.542744 0.8393256 -0.03101205 0.5425205 0.8326577 -0.1111428 0.5359462 0.8356897 -0.1199352 0.9798209 0.1979573 -0.02764075 0.980144 0.1965739 -0.02601063 0.8259468 0.5581337 -0.07936584 0.8262149 0.5629761 -0.02066189 0.8266453 0.5623811 -0.01962637 0.9784234 0.1969691 -0.06237715 0.9797196 0.1919395 -0.05752187 0.8119528 0.5554995 -0.1793125 0.8225919 0.5441612 -0.1650196 0.5088678 0.8184388 -0.2668551 0.5348117 0.8089124 -0.2442072 0.8092072 0.4893513 -0.325145 0.008925914 0.01315355 -0.9998737 0.7087231 0.1060234 -0.6974745 0.6667057 0.05824744 -0.7430416 0.5623574 0.1138479 -0.8190194 0.5110517 0.0598545 -0.8574635 0.4565766 0.06920188 -0.8869888 0.3924528 0.006502509 -0.9197493 0.2755258 0.07609629 -0.9582771 0.1845297 -0.008163869 -0.982793 0.108748 0.0408622 -0.9932292 0.06435257 0.003874301 -0.9979197 0.05170285 0.01044213 -0.998608 0.03711766 -4.25456e-4 -0.9993109 0.02889108 0.006725609 -0.9995599 0.01522165 0.002870559 -0.99988 0.8548033 -0.01958996 -0.5185824 0.8105877 0.190852 -0.5536456 0.7543123 0.1128828 -0.6467383 0.8521482 0.09642523 -0.51434 0.8895326 0.1541601 -0.4300774 0.9243333 0.1552187 -0.3485902 0.9408899 0.1965909 -0.2758226 0.9753651 0.1545351 -0.1574226 0.7647141 0.5101715 -0.3936209 0.7313272 0.4337113 -0.5263602 0.7253619 0.4684972 -0.5043418 0.6628276 0.3645289 -0.6540477 0.6402049 0.4129111 -0.647798 0.5682398 0.3191785 -0.7584382 0.5685464 0.3410212 -0.7486385 0.4875153 0.2460446 -0.8377297 0.464101 0.2873584 -0.8378756 0.3724028 0.1913648 -0.9081277 0.3677281 0.2105436 -0.9057856 0.272678 0.1162735 -0.9550535 0.2434774 0.1549421 -0.9574506 0.1250247 0.04517149 -0.9911248 0.1050864 0.06956499 -0.9920271 0.04698878 0.02118241 -0.9986709 0.04505491 0.02500647 -0.9986715 0.02808707 0.01235079 -0.9995292 0.02723288 0.01354163 -0.9995374 0.01460009 0.00992763 -0.9998441 0.01507425 0.01257133 -0.9998074 0.01279789 0.01270729 -0.9998375 0.01025271 0.01215362 -0.9998736 0.01016288 0.01217836 -0.9998743 0.009589493 0.01176768 -0.9998848 0.00717169 0.01259297 -0.9998951 0.01299673 0.01756149 -0.9997614 0.0236411 0.02046149 -0.9995112 0.01985591 0.02633726 -0.9994559 0.03509944 0.03757816 -0.9986771 0.03188937 0.04017078 -0.9986838 0.08867359 0.08745568 -0.992214 0.07147264 0.1044995 -0.9919535 0.1882045 0.212373 -0.9588936 0.1592838 0.236045 -0.9585987 0.2504637 0.3275709 -0.9110243 0.234988 0.3313469 -0.9137779 0.3221119 0.4214465 -0.8477185 0.2914806 0.4367925 -0.8510296 0.3634355 0.5236024 -0.7705551 0.3519921 0.5217593 -0.77709 0.4140741 0.6006428 -0.6839378 0.4015912 0.6039685 -0.6884378 0.4481837 0.6851248 -0.574226 0.4515194 0.6857718 -0.5708304 0.478858 0.7487142 -0.4583908 0.5082885 0.7446125 -0.4326606 0.01188278 0.8330952 0.5530021 0.04743105 0.7998418 0.5983339 -0.01053291 0.556826 0.8305624 0.02772653 0.4844744 0.8743659 1.95243e-4 0.195744 0.980655 0.01544392 0.1678582 0.9856902 0.04569464 0.1956998 0.9795987 0.04558831 0.195525 0.9796386 0.0418182 0.55696 0.829486 0.04174715 0.5568642 0.8295538 0.03154414 0.8329156 0.5525004 0.03159356 0.8329681 0.5524186 0.09760308 0.5559625 0.8254572 0.9654373 0.2174704 0.1436581 0.7835253 0.6112554 0.1116021 0.9665014 0.2117509 0.1450402 0.9557846 0.21307 0.2026748 0.954316 0.1695013 0.2460698 0.9442539 0.2107909 0.252887 0.9187889 0.2121038 0.332925 0.9026772 0.1520922 0.4025442 0.8871428 0.2108714 0.4105007 0.9190176 0.2101216 0.3335502 0.8755643 0.2095983 0.4352654 0.8497188 0.2097321 0.4837256 0.8498113 0.2082954 0.4841836 0.8061193 0.208604 0.5537652 0.8061709 0.2071655 0.5542302 0.7738953 0.2075582 0.5983358 0.7522755 0.1386401 0.6440968 0.735075 0.2051569 0.6462008 0.6587572 0.205928 0.7236247 0.6588057 0.2025023 0.7245466 0.5802064 0.2042277 0.7884489 0.579992 0.2016074 0.7892805 0.4950497 0.2034772 0.8447028 0.4947651 0.1980416 0.8461601 0.3854036 0.2013 0.9005234 0.3848783 0.1956021 0.9020025 0.2884628 0.1986177 0.9366644 0.287832 0.1952636 0.9375634 0.2356221 0.1967782 0.9517146 0.2023072 0.1489566 0.9679275 0.1895409 0.1948963 0.9623355 0.1085 0.1964045 0.9745015 0.1082007 0.1948865 0.9748395 0.09786075 0.5574086 0.8244508 0.180366 0.5557674 0.811536 0.1790745 0.5595653 0.8092089 0.2544545 0.5577095 0.7900717 0.2523866 0.5626614 0.7872188 0.336214 0.559803 0.7573512 0.3326698 0.5686543 0.7523052 0.4254152 0.5659167 0.7062296 0.4212 0.5746992 0.701649 0.4915409 0.5733911 0.6554466 0.4889035 0.5776514 0.653676 0.5540044 0.5760055 0.6010797 0.5503119 0.5821305 0.5985657 0.6203249 0.5812759 0.5266075 0.6169986 0.5862948 0.5249487 0.6687589 0.5863546 0.4571103 0.6664486 0.5894022 0.4565647 0.7032541 0.5891476 0.3979181 0.7010354 0.5920085 0.3975868 0.7331643 0.5916196 0.3353453 0.7307944 0.5946338 0.3351867 0.7581337 0.5939648 0.2691454 0.7555673 0.5972154 0.2691692 0.7802198 0.5957018 0.190779 0.7766776 0.6002857 0.1908636 0.7922531 0.5990414 0.1161223 0.453288 0.8896967 0.0544967 0.4446204 0.8939195 0.05675143 0.4721325 0.8782908 0.07547473 0.4664214 0.8785784 0.1027179 0.4731057 0.8745812 0.106202 0.4574981 0.875513 0.1554753 0.4619009 0.8726326 0.1586189 0.4451196 0.8730415 0.1991661 0.4491173 0.8702099 0.2025552 0.4297378 0.8704477 0.2400966 0.4333763 0.8676306 0.2437258 0.4115826 0.8677923 0.2784537 0.4150623 0.8648032 0.2825579 0.3849578 0.8648045 0.3223673 0.3903325 0.8598815 0.3290051 0.3500376 0.8603802 0.3704319 0.3552966 0.8544729 0.3789993 0.3180572 0.8553942 0.4088282 0.3204245 0.8514566 0.4151505 0.280636 0.8522273 0.4415338 0.2850968 0.8438892 0.4545006 0.2293571 0.8455096 0.4821918 0.2320403 0.837154 0.4953085 0.1791961 0.8389291 0.5138937 0.17932 0.8343984 0.5211753 0.1298324 0.8355827 0.5338026 0.1296096 0.8322369 0.5390576 0.07226121 0.8333334 0.548027 0.07202428 0.8321654 0.5498302 0.4547889 0.8897308 0.03932297 0.4458931 0.8944306 0.0342518 0.7850977 0.6163105 0.06150603 0.7890464 0.6114758 0.05919039 0.9729152 0.2193819 0.0728535 0.9733879 0.2175377 0.07206583 0.4462469 0.8945034 0.02697539 0.4388115 0.8982772 0.02329838 0.7866675 0.6166372 0.03021639 0.7838 0.6203734 0.02818781 0.9751448 0.219808 0.02787595 0.9749215 0.2208523 0.02743101 0.5249099 0.8511434 0.00497967 0.9802477 0.1977699 0.001206755 0.8268628 0.562393 0.003504574 0.9793367 0.2022331 0.001159131 0.9793366 0.202215 0.002990424 0.9755521 0.2197484 0.002948105 0.7870829 0.6167744 0.009474933 0.8191227 0.5735657 0.007774531 0.819116 0.5736181 0.003353774 0.544097 0.8390058 0.005262017 0.4465814 0.8945815 0.01700037 0.4330078 0.9012653 0.01500731 0.4178509 0.9084034 0.01428472 0.5013816 0.8651551 0.01110106 0.5249112 0.8511117 0.008789598 0.4388126 0.8983369 0.02084076 0.4465861 0.8944782 0.02167361 0.78388 0.6207451 0.01441085 0.7870955 0.6166519 0.01487225 0.9751687 0.2214055 0.005084037 0.9755536 0.2196999 0.005232393 0.5440593 0.8390291 0.005456745 0.5441215 0.8389867 0.005773067 0.8267861 0.562504 0.003775715 0.826854 0.5624036 0.00384432 0.9802485 0.1977652 0.001381456 0.9802486 0.1977635 0.001527726 0.5439919 0.8390746 0.005194187 0.5441377 0.8389781 0.005493283 0.8269049 0.5623303 0.003595232 0.8268609 0.5623924 0.003994464 0.980254 0.1977381 0.001347839 0.9802467 0.1977744 0.001347541 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 2 1 3 1 3 2 2 2 4 2 3 3 4 3 5 3 6 4 7 4 8 4 8 5 9 5 10 5 8 6 7 6 11 6 11 7 7 7 12 7 11 8 12 8 13 8 14 9 15 9 12 9 12 10 15 10 16 10 12 11 16 11 17 11 18 12 17 12 19 12 19 13 17 13 20 13 8 14 21 14 22 14 8 15 23 15 24 15 21 16 8 16 25 16 25 17 8 17 26 17 25 18 26 18 27 18 22 19 28 19 8 19 8 20 28 20 29 20 8 21 29 21 30 21 10 22 31 22 8 22 8 23 31 23 32 23 8 24 32 24 23 24 18 25 33 25 17 25 17 26 33 26 34 26 17 27 34 27 12 27 12 28 34 28 35 28 12 29 35 29 13 29 30 30 36 30 8 30 8 31 36 31 37 31 8 32 37 32 9 32 27 33 38 33 25 33 25 34 38 34 39 34 25 35 39 35 40 35 24 36 41 36 8 36 8 37 41 37 42 37 8 38 42 38 43 38 43 39 44 39 8 39 8 40 44 40 45 40 8 41 45 41 6 41 46 42 47 42 48 42 49 43 50 43 14 43 51 44 52 44 53 44 53 45 52 45 54 45 53 46 54 46 55 46 56 47 57 47 51 47 51 48 57 48 58 48 51 49 58 49 52 49 59 50 60 50 61 50 61 51 60 51 48 51 61 52 48 52 62 52 7 53 63 53 12 53 12 54 63 54 64 54 12 55 64 55 48 55 48 56 64 56 65 56 48 57 65 57 62 57 66 58 67 58 12 58 66 59 12 59 68 59 48 60 47 60 12 60 12 61 47 61 69 61 12 62 69 62 68 62 67 63 70 63 12 63 12 64 70 64 71 64 12 65 71 65 14 65 14 66 71 66 72 66 14 67 72 67 49 67 59 68 56 68 60 68 60 69 56 69 51 69 60 70 51 70 73 70 73 71 74 71 60 71 60 72 74 72 75 72 60 73 75 73 48 73 48 74 75 74 76 74 48 75 76 75 46 75 77 76 78 76 53 76 53 77 78 77 79 77 53 78 79 78 51 78 51 79 79 79 80 79 51 80 80 80 73 80 81 81 82 81 83 81 83 82 82 82 84 82 83 83 84 83 85 83 85 84 84 84 86 84 85 85 86 85 87 85 81 86 88 86 82 86 82 87 88 87 89 87 82 88 89 88 90 88 90 89 89 89 91 89 90 90 91 90 92 90 92 91 91 91 93 91 92 92 93 92 94 92 94 93 93 93 95 93 94 94 95 94 96 94 96 95 95 95 97 95 96 96 97 96 98 96 97 97 99 97 98 97 98 98 99 98 100 98 98 99 100 99 101 99 101 100 100 100 102 100 101 101 102 101 103 101 102 102 104 102 103 102 103 103 104 103 105 103 103 104 105 104 106 104 106 105 105 105 107 105 106 106 107 106 108 106 107 107 109 107 108 107 108 108 109 108 110 108 108 109 110 109 111 109 111 110 110 110 112 110 111 111 112 111 113 111 113 112 112 112 114 112 113 113 114 113 115 113 114 114 116 114 115 114 115 115 116 115 1 115 115 116 1 116 0 116 117 117 55 117 118 117 117 118 118 118 119 118 119 119 118 119 120 119 119 120 120 120 121 120 121 121 120 121 122 121 121 122 122 122 123 122 123 123 122 123 124 123 123 124 124 124 125 124 125 125 124 125 126 125 125 126 126 126 127 126 127 127 126 127 128 127 127 128 128 128 129 128 129 129 128 129 130 129 129 130 130 130 131 130 131 131 130 131 87 131 131 132 87 132 86 132 77 133 53 133 132 133 132 134 53 134 55 134 132 135 55 135 117 135 133 136 134 136 135 136 136 137 137 137 138 137 139 138 140 138 141 138 142 139 143 139 144 139 145 140 146 140 147 140 148 141 149 141 150 141 151 142 152 142 153 142 154 143 155 143 156 143 157 144 158 144 159 144 160 145 161 145 153 145 162 146 163 146 164 146 165 147 166 147 167 147 168 148 169 148 170 148 171 149 172 149 173 149 174 150 175 150 176 150 175 151 177 151 178 151 178 152 177 152 179 152 178 153 179 153 180 153 179 154 181 154 180 154 180 155 181 155 182 155 180 156 182 156 183 156 183 157 182 157 184 157 183 158 184 158 185 158 185 159 184 159 186 159 185 160 186 160 187 160 187 161 186 161 188 161 187 162 188 162 189 162 189 163 188 163 190 163 189 164 190 164 191 164 191 165 190 165 192 165 192 166 190 166 193 166 192 167 193 167 194 167 194 168 193 168 195 168 194 169 195 169 196 169 196 170 195 170 197 170 196 171 197 171 198 171 198 172 197 172 199 172 198 173 199 173 200 173 200 174 199 174 201 174 200 175 201 175 202 175 202 176 201 176 203 176 202 177 203 177 204 177 204 178 203 178 205 178 204 179 205 179 206 179 206 180 205 180 207 180 206 181 207 181 208 181 208 182 207 182 209 182 208 183 209 183 210 183 210 184 209 184 211 184 211 185 209 185 212 185 211 186 212 186 213 186 213 187 212 187 214 187 214 188 212 188 215 188 214 189 215 189 216 189 217 190 218 190 219 190 219 191 218 191 220 191 219 192 220 192 221 192 222 193 223 193 224 193 224 194 223 194 225 194 224 195 225 195 226 195 170 196 169 196 227 196 228 197 229 197 165 197 228 198 165 198 230 198 230 199 165 199 167 199 230 200 167 200 231 200 231 201 167 201 232 201 231 202 232 202 169 202 169 203 232 203 233 203 169 204 233 204 227 204 234 205 235 205 164 205 164 206 235 206 236 206 164 207 236 207 162 207 237 208 238 208 239 208 240 209 241 209 242 209 141 210 243 210 244 210 243 211 141 211 245 211 245 212 141 212 140 212 245 213 140 213 246 213 247 214 248 214 246 214 246 215 248 215 249 215 246 216 249 216 245 216 250 217 251 217 252 217 252 218 251 218 253 218 134 219 254 219 255 219 254 220 134 220 256 220 256 221 134 221 133 221 256 222 133 222 257 222 258 223 259 223 260 223 261 224 262 224 263 224 261 225 263 225 264 225 264 226 263 226 265 226 264 227 265 227 266 227 267 228 268 228 269 228 269 229 268 229 270 229 268 230 271 230 270 230 270 231 271 231 272 231 270 232 272 232 273 232 273 233 272 233 274 233 274 234 272 234 275 234 274 235 275 235 276 235 153 236 161 236 275 236 275 237 161 237 277 237 275 238 277 238 276 238 278 239 279 239 152 239 152 240 279 240 280 240 152 241 280 241 153 241 153 242 280 242 281 242 153 243 281 243 160 243 282 244 283 244 284 244 284 245 283 245 285 245 284 246 285 246 286 246 286 247 287 247 284 247 284 248 287 248 288 248 284 249 288 249 289 249 157 250 159 250 290 250 291 251 292 251 293 251 154 252 156 252 294 252 295 253 296 253 297 253 296 254 298 254 297 254 297 255 298 255 299 255 297 256 299 256 300 256 300 257 299 257 301 257 300 258 301 258 150 258 150 259 149 259 300 259 300 260 149 260 302 260 300 261 302 261 297 261 297 262 302 262 303 262 297 263 303 263 295 263 301 264 304 264 150 264 150 265 304 265 305 265 150 266 305 266 148 266 148 267 305 267 306 267 148 268 306 268 307 268 307 269 306 269 308 269 307 270 308 270 309 270 309 271 308 271 310 271 311 272 312 272 313 272 311 273 313 273 314 273 314 274 313 274 315 274 314 275 315 275 316 275 304 276 312 276 305 276 305 277 312 277 311 277 305 278 311 278 306 278 306 279 311 279 314 279 306 280 314 280 308 280 308 281 314 281 316 281 308 282 316 282 310 282 310 283 282 283 309 283 309 284 282 284 284 284 309 285 284 285 317 285 317 286 284 286 289 286 317 287 289 287 318 287 319 288 320 288 321 288 322 289 323 289 324 289 324 290 323 290 325 290 324 291 325 291 326 291 326 292 325 292 327 292 326 293 327 293 328 293 329 294 322 294 330 294 330 295 322 295 324 295 330 296 324 296 331 296 331 297 324 297 326 297 331 298 326 298 332 298 332 299 326 299 328 299 332 300 328 300 333 300 319 301 321 301 334 301 334 302 321 302 335 302 334 303 335 303 336 303 336 304 335 304 337 304 336 305 337 305 338 305 338 306 337 306 339 306 338 307 339 307 340 307 340 308 339 308 341 308 340 309 341 309 342 309 342 310 341 310 343 310 342 311 343 311 344 311 327 312 345 312 328 312 328 313 345 313 346 313 328 314 346 314 333 314 333 315 346 315 347 315 333 316 347 316 348 316 348 317 347 317 349 317 348 318 349 318 350 318 350 319 349 319 351 319 350 320 351 320 352 320 352 321 351 321 353 321 352 322 353 322 354 322 355 323 344 323 356 323 356 324 344 324 343 324 356 325 343 325 354 325 357 326 358 326 359 326 359 327 358 327 360 327 360 328 358 328 361 328 360 329 361 329 362 329 362 330 361 330 363 330 362 331 363 331 364 331 345 332 357 332 346 332 346 333 357 333 359 333 346 334 359 334 347 334 347 335 359 335 360 335 347 336 360 336 349 336 349 337 360 337 362 337 349 338 362 338 351 338 351 339 362 339 364 339 351 340 364 340 353 340 323 341 365 341 325 341 325 342 365 342 366 342 325 343 366 343 327 343 327 344 366 344 367 344 327 345 367 345 345 345 345 346 367 346 368 346 345 347 368 347 357 347 357 348 368 348 369 348 357 349 369 349 358 349 358 350 369 350 370 350 358 351 370 351 361 351 361 352 370 352 371 352 361 353 371 353 363 353 372 354 320 354 373 354 373 355 320 355 319 355 373 356 319 356 296 356 296 357 319 357 334 357 296 358 334 358 298 358 298 359 334 359 336 359 298 360 336 360 299 360 299 361 336 361 338 361 299 362 338 362 301 362 301 363 338 363 340 363 301 364 340 364 304 364 304 365 340 365 342 365 304 366 342 366 312 366 312 367 342 367 344 367 312 368 344 368 313 368 313 369 344 369 355 369 313 370 355 370 315 370 175 371 174 371 177 371 177 372 174 372 374 372 177 373 374 373 179 373 179 374 374 374 375 374 179 375 375 375 181 375 181 376 375 376 376 376 181 377 376 377 182 377 182 378 376 378 377 378 182 379 377 379 184 379 184 380 377 380 378 380 184 381 378 381 186 381 186 382 378 382 379 382 186 383 379 383 188 383 188 384 379 384 380 384 188 385 380 385 190 385 190 386 380 386 381 386 190 387 381 387 193 387 382 388 383 388 384 388 384 389 383 389 385 389 384 390 385 390 386 390 386 391 385 391 387 391 386 392 387 392 388 392 388 393 387 393 389 393 388 394 389 394 390 394 390 395 389 395 391 395 390 396 391 396 392 396 172 397 216 397 173 397 173 398 216 398 215 398 173 399 215 399 393 399 393 400 215 400 212 400 393 401 212 401 394 401 394 402 212 402 209 402 394 403 209 403 395 403 395 404 209 404 207 404 395 405 207 405 396 405 396 406 207 406 205 406 396 407 205 407 397 407 397 408 205 408 203 408 397 409 203 409 398 409 398 410 203 410 201 410 398 411 201 411 399 411 399 412 201 412 199 412 399 413 199 413 400 413 400 414 199 414 197 414 400 415 197 415 401 415 401 416 197 416 195 416 401 417 195 417 402 417 402 418 195 418 193 418 402 419 193 419 403 419 403 420 193 420 381 420 404 421 405 421 406 421 406 422 405 422 407 422 406 423 407 423 408 423 408 424 407 424 409 424 408 425 409 425 410 425 410 426 409 426 411 426 410 427 411 427 412 427 412 428 411 428 413 428 412 429 413 429 414 429 414 430 413 430 415 430 414 431 415 431 416 431 416 432 415 432 417 432 416 433 417 433 418 433 418 434 417 434 419 434 418 435 419 435 420 435 420 436 419 436 421 436 420 437 421 437 422 437 422 438 421 438 423 438 422 439 423 439 424 439 424 440 423 440 425 440 424 441 425 441 426 441 426 442 425 442 427 442 426 443 427 443 428 443 428 444 427 444 429 444 428 445 429 445 430 445 430 446 429 446 431 446 430 447 431 447 432 447 432 448 431 448 433 448 432 449 433 449 434 449 434 450 433 450 435 450 434 451 435 451 436 451 436 452 435 452 437 452 436 453 437 453 438 453 438 454 437 454 439 454 438 455 439 455 440 455 440 456 439 456 441 456 440 457 441 457 442 457 442 458 441 458 443 458 442 459 443 459 444 459 444 460 443 460 445 460 444 461 445 461 446 461 446 462 445 462 447 462 446 463 447 463 293 463 293 464 447 464 156 464 293 465 156 465 291 465 291 466 156 466 155 466 448 467 404 467 449 467 449 468 404 468 406 468 449 469 406 469 450 469 450 470 406 470 408 470 450 471 408 471 451 471 451 472 408 472 410 472 451 473 410 473 452 473 452 474 410 474 412 474 452 475 412 475 453 475 453 476 412 476 414 476 453 477 414 477 454 477 454 478 414 478 416 478 454 479 416 479 455 479 455 480 416 480 418 480 455 481 418 481 456 481 456 482 418 482 420 482 456 483 420 483 457 483 457 484 420 484 422 484 457 485 422 485 458 485 458 486 422 486 424 486 458 487 424 487 459 487 459 488 424 488 426 488 459 489 426 489 460 489 460 490 426 490 428 490 460 491 428 491 461 491 461 492 428 492 430 492 461 493 430 493 462 493 462 494 430 494 432 494 462 495 432 495 463 495 463 496 432 496 434 496 463 497 434 497 464 497 464 498 434 498 436 498 464 499 436 499 465 499 465 500 436 500 438 500 465 501 438 501 466 501 466 502 438 502 440 502 466 503 440 503 467 503 467 504 440 504 442 504 467 505 442 505 468 505 468 506 442 506 444 506 468 507 444 507 469 507 469 508 444 508 446 508 469 509 446 509 159 509 159 510 446 510 293 510 159 511 293 511 290 511 290 512 293 512 292 512 147 513 143 513 470 513 470 514 143 514 142 514 470 515 142 515 471 515 147 516 146 516 143 516 143 517 146 517 472 517 143 518 472 518 144 518 473 519 472 519 474 519 474 520 472 520 146 520 474 521 146 521 475 521 475 522 146 522 145 522 475 523 145 523 476 523 477 524 478 524 479 524 479 525 478 525 480 525 479 526 480 526 481 526 481 527 480 527 482 527 481 528 482 528 483 528 483 529 482 529 484 529 483 530 484 530 485 530 485 531 484 531 486 531 229 532 487 532 165 532 165 533 487 533 163 533 165 534 163 534 166 534 166 535 163 535 162 535 488 536 489 536 490 536 490 537 489 537 491 537 490 538 491 538 492 538 492 539 491 539 493 539 492 540 493 540 494 540 494 541 493 541 495 541 494 542 495 542 496 542 496 543 495 543 497 543 496 544 497 544 498 544 498 545 497 545 499 545 498 546 499 546 500 546 500 547 499 547 501 547 500 548 501 548 502 548 502 549 501 549 503 549 502 550 503 550 504 550 504 551 503 551 505 551 504 552 505 552 506 552 507 553 508 553 509 553 509 554 508 554 510 554 509 555 510 555 511 555 511 556 510 556 512 556 511 557 512 557 513 557 513 558 512 558 514 558 513 559 514 559 515 559 515 560 514 560 516 560 515 561 516 561 517 561 517 562 516 562 518 562 517 563 518 563 519 563 519 564 518 564 520 564 478 565 471 565 480 565 480 566 471 566 142 566 480 567 142 567 482 567 482 568 142 568 144 568 482 569 144 569 484 569 484 570 144 570 472 570 484 571 472 571 486 571 486 572 472 572 473 572 486 573 473 573 521 573 508 574 477 574 510 574 510 575 477 575 479 575 510 576 479 576 512 576 512 577 479 577 481 577 512 578 481 578 514 578 514 579 481 579 483 579 514 580 483 580 516 580 516 581 483 581 485 581 516 582 485 582 518 582 518 583 485 583 486 583 518 584 486 584 520 584 520 585 486 585 521 585 520 586 521 586 522 586 523 587 488 587 524 587 524 588 488 588 490 588 524 589 490 589 525 589 525 590 490 590 492 590 525 591 492 591 526 591 526 592 492 592 494 592 526 593 494 593 527 593 527 594 494 594 496 594 527 595 496 595 528 595 528 596 496 596 498 596 528 597 498 597 529 597 529 598 498 598 500 598 529 599 500 599 530 599 530 600 500 600 502 600 530 601 502 601 531 601 531 602 502 602 504 602 531 603 504 603 532 603 532 604 504 604 506 604 532 605 506 605 533 605 534 606 523 606 535 606 535 607 523 607 524 607 535 608 524 608 536 608 536 609 524 609 525 609 536 610 525 610 537 610 537 611 525 611 526 611 537 612 526 612 538 612 538 613 526 613 527 613 538 614 527 614 539 614 539 615 527 615 528 615 539 616 528 616 540 616 540 617 528 617 529 617 540 618 529 618 541 618 541 619 529 619 530 619 541 620 530 620 542 620 542 621 530 621 531 621 542 622 531 622 543 622 543 623 531 623 532 623 543 624 532 624 544 624 544 625 532 625 533 625 544 626 533 626 545 626 403 627 534 627 402 627 402 628 534 628 535 628 402 629 535 629 401 629 401 630 535 630 536 630 401 631 536 631 400 631 400 632 536 632 537 632 400 633 537 633 399 633 399 634 537 634 538 634 399 635 538 635 398 635 398 636 538 636 539 636 398 637 539 637 397 637 397 638 539 638 540 638 397 639 540 639 396 639 396 640 540 640 541 640 396 641 541 641 395 641 395 642 541 642 542 642 395 643 542 643 394 643 394 644 542 644 543 644 394 645 543 645 393 645 393 646 543 646 544 646 393 647 544 647 173 647 173 648 544 648 545 648 173 649 545 649 171 649 489 650 546 650 491 650 491 651 546 651 547 651 491 652 547 652 493 652 493 653 547 653 548 653 493 654 548 654 495 654 495 655 548 655 549 655 495 656 549 656 497 656 497 657 549 657 550 657 497 658 550 658 499 658 499 659 550 659 551 659 499 660 551 660 501 660 501 661 551 661 552 661 501 662 552 662 503 662 503 663 552 663 553 663 503 664 553 664 505 664 505 665 553 665 554 665 505 666 554 666 506 666 506 667 554 667 555 667 506 668 555 668 533 668 533 669 555 669 556 669 533 670 556 670 545 670 546 671 507 671 547 671 547 672 507 672 509 672 547 673 509 673 548 673 548 674 509 674 511 674 548 675 511 675 549 675 549 676 511 676 513 676 549 677 513 677 550 677 550 678 513 678 515 678 550 679 515 679 551 679 551 680 515 680 517 680 551 681 517 681 552 681 552 682 517 682 519 682 552 683 519 683 553 683 553 684 519 684 520 684 553 685 520 685 554 685 554 686 520 686 522 686 554 687 522 687 555 687 555 688 522 688 217 688 555 689 217 689 556 689 556 690 217 690 219 690 556 691 219 691 545 691 545 692 219 692 221 692 545 693 221 693 171 693 170 694 222 694 168 694 168 695 222 695 224 695 168 696 224 696 169 696 169 697 224 697 557 697 169 698 557 698 231 698 558 699 559 699 560 699 560 700 559 700 561 700 560 701 561 701 562 701 562 702 561 702 563 702 562 703 563 703 564 703 564 704 563 704 565 704 564 705 565 705 566 705 567 706 247 706 568 706 568 707 247 707 246 707 568 708 246 708 569 708 569 709 246 709 140 709 569 710 140 710 570 710 570 711 140 711 139 711 570 712 139 712 571 712 566 713 567 713 564 713 564 714 567 714 568 714 564 715 568 715 562 715 562 716 568 716 569 716 562 717 569 717 560 717 560 718 569 718 570 718 560 719 570 719 558 719 558 720 570 720 571 720 558 721 571 721 572 721 573 722 574 722 575 722 575 723 574 723 576 723 575 724 576 724 577 724 577 725 576 725 578 725 158 726 579 726 159 726 159 727 579 727 580 727 159 728 580 728 469 728 469 729 580 729 581 729 469 730 581 730 468 730 468 731 581 731 582 731 468 732 582 732 467 732 467 733 582 733 583 733 467 734 583 734 466 734 466 735 583 735 584 735 466 736 584 736 465 736 465 737 584 737 585 737 465 738 585 738 464 738 464 739 585 739 586 739 464 740 586 740 463 740 463 741 586 741 587 741 463 742 587 742 462 742 462 743 587 743 588 743 462 744 588 744 461 744 461 745 588 745 589 745 461 746 589 746 460 746 460 747 589 747 590 747 460 748 590 748 459 748 459 749 590 749 591 749 459 750 591 750 458 750 458 751 591 751 592 751 458 752 592 752 457 752 457 753 592 753 593 753 457 754 593 754 456 754 456 755 593 755 594 755 456 756 594 756 455 756 455 757 594 757 595 757 455 758 595 758 454 758 454 759 595 759 596 759 454 760 596 760 453 760 453 761 596 761 597 761 453 762 597 762 452 762 452 763 597 763 598 763 452 764 598 764 451 764 451 765 598 765 578 765 451 766 578 766 450 766 450 767 578 767 576 767 450 768 576 768 449 768 449 769 576 769 574 769 449 770 574 770 448 770 448 771 574 771 573 771 599 772 572 772 600 772 600 773 572 773 571 773 600 774 571 774 601 774 601 775 571 775 139 775 601 776 139 776 602 776 602 777 139 777 141 777 602 778 141 778 240 778 240 779 141 779 244 779 240 780 244 780 241 780 603 781 604 781 605 781 605 782 604 782 606 782 605 783 606 783 607 783 607 784 606 784 608 784 607 785 608 785 609 785 609 786 608 786 610 786 609 787 610 787 611 787 611 788 610 788 612 788 611 789 612 789 613 789 613 790 612 790 614 790 613 791 614 791 615 791 615 792 614 792 616 792 615 793 616 793 617 793 487 794 618 794 163 794 163 795 618 795 619 795 163 796 619 796 164 796 164 797 619 797 237 797 164 798 237 798 234 798 234 799 237 799 239 799 234 800 239 800 235 800 557 801 603 801 231 801 231 802 603 802 605 802 231 803 605 803 230 803 230 804 605 804 607 804 230 805 607 805 228 805 228 806 607 806 609 806 228 807 609 807 229 807 229 808 609 808 611 808 229 809 611 809 487 809 487 810 611 810 613 810 487 811 613 811 618 811 618 812 613 812 615 812 618 813 615 813 619 813 619 814 615 814 617 814 619 815 617 815 237 815 237 816 617 816 620 816 237 817 620 817 238 817 242 818 620 818 240 818 240 819 620 819 617 819 240 820 617 820 602 820 602 821 617 821 616 821 602 822 616 822 601 822 601 823 616 823 614 823 601 824 614 824 600 824 600 825 614 825 612 825 600 826 612 826 599 826 599 827 612 827 610 827 599 828 610 828 476 828 476 829 610 829 608 829 476 830 608 830 475 830 475 831 608 831 606 831 475 832 606 832 474 832 474 833 606 833 604 833 474 834 604 834 473 834 473 835 604 835 603 835 473 836 603 836 521 836 521 837 603 837 557 837 521 838 557 838 522 838 522 839 557 839 224 839 522 840 224 840 217 840 217 841 224 841 226 841 217 842 226 842 218 842 137 843 136 843 621 843 621 844 136 844 622 844 621 845 622 845 623 845 259 846 624 846 260 846 260 847 624 847 625 847 260 848 625 848 626 848 626 849 625 849 627 849 626 850 627 850 628 850 628 851 627 851 629 851 628 852 629 852 630 852 630 853 629 853 631 853 632 854 265 854 633 854 633 855 265 855 263 855 633 856 263 856 634 856 634 857 263 857 262 857 634 858 262 858 138 858 138 859 262 859 635 859 138 860 635 860 136 860 136 861 635 861 636 861 136 862 636 862 622 862 637 863 135 863 638 863 638 864 135 864 134 864 638 865 134 865 639 865 639 866 134 866 255 866 639 867 255 867 640 867 641 868 637 868 642 868 642 869 637 869 638 869 642 870 638 870 643 870 643 871 638 871 639 871 643 872 639 872 252 872 252 873 639 873 640 873 252 874 640 874 250 874 261 875 644 875 262 875 262 876 644 876 258 876 262 877 258 877 635 877 635 878 258 878 260 878 635 879 260 879 636 879 636 880 260 880 626 880 636 881 626 881 622 881 622 882 626 882 628 882 622 883 628 883 623 883 623 884 628 884 630 884 151 885 153 885 645 885 645 886 153 886 275 886 645 887 275 887 646 887 646 888 275 888 272 888 646 889 272 889 647 889 647 890 272 890 271 890 647 891 271 891 648 891 648 892 271 892 268 892 648 893 268 893 649 893 649 894 268 894 267 894 649 895 267 895 650 895 651 896 372 896 652 896 652 897 372 897 373 897 652 898 373 898 653 898 653 899 373 899 296 899 653 900 296 900 650 900 650 901 296 901 295 901 650 902 295 902 649 902 649 903 295 903 303 903 649 904 303 904 648 904 648 905 303 905 302 905 648 906 302 906 647 906 647 907 302 907 149 907 647 908 149 908 646 908 646 909 149 909 148 909 646 910 148 910 645 910 645 911 148 911 307 911 645 912 307 912 151 912 151 913 307 913 309 913 151 914 309 914 152 914 152 915 309 915 317 915 152 916 317 916 278 916 278 917 317 917 318 917 624 918 257 918 625 918 625 919 257 919 133 919 625 920 133 920 627 920 627 921 133 921 135 921 627 922 135 922 629 922 629 923 135 923 637 923 629 924 637 924 631 924 631 925 637 925 641 925 631 926 641 926 654 926 654 927 641 927 655 927 654 928 655 928 656 928 657 929 382 929 658 929 658 930 382 930 384 930 658 931 384 931 659 931 659 932 384 932 386 932 659 933 386 933 660 933 660 934 386 934 388 934 660 935 388 935 661 935 661 936 388 936 390 936 661 937 390 937 662 937 662 938 390 938 392 938 662 939 392 939 663 939 664 940 656 940 665 940 665 941 656 941 655 941 665 942 655 942 666 942 666 943 655 943 641 943 666 944 641 944 667 944 667 945 641 945 642 945 667 946 642 946 668 946 668 947 642 947 643 947 668 948 643 948 669 948 669 949 643 949 252 949 669 950 252 950 670 950 670 951 252 951 253 951 670 952 253 952 671 952 672 953 664 953 673 953 673 954 664 954 665 954 673 955 665 955 674 955 674 956 665 956 666 956 674 957 666 957 675 957 675 958 666 958 667 958 269 959 632 959 267 959 267 960 632 960 633 960 267 961 633 961 650 961 650 962 633 962 634 962 650 963 634 963 653 963 653 964 634 964 138 964 653 965 138 965 652 965 652 966 138 966 137 966 652 967 137 967 651 967 651 968 137 968 621 968 651 969 621 969 676 969 676 970 621 970 623 970 676 971 623 971 657 971 657 972 623 972 630 972 657 973 630 973 382 973 382 974 630 974 631 974 382 975 631 975 383 975 383 976 631 976 654 976 383 977 654 977 385 977 385 978 654 978 656 978 385 979 656 979 387 979 387 980 656 980 664 980 387 981 664 981 389 981 389 982 664 982 672 982 389 983 672 983 391 983 354 984 343 984 352 984 352 985 343 985 341 985 352 986 341 986 350 986 350 987 341 987 339 987 350 988 339 988 348 988 348 989 339 989 337 989 348 990 337 990 333 990 333 991 337 991 335 991 333 992 335 992 332 992 332 993 335 993 321 993 332 994 321 994 331 994 331 995 321 995 320 995 331 996 320 996 330 996 330 997 320 997 372 997 330 998 372 998 329 998 329 999 372 999 651 999 329 1000 651 1000 322 1000 322 1001 651 1001 676 1001 322 1002 676 1002 323 1002 323 1003 676 1003 657 1003 323 1004 657 1004 365 1004 365 1005 657 1005 658 1005 365 1006 658 1006 366 1006 366 1007 658 1007 659 1007 366 1008 659 1008 367 1008 367 1009 659 1009 660 1009 367 1010 660 1010 368 1010 368 1011 660 1011 661 1011 368 1012 661 1012 369 1012 369 1013 661 1013 662 1013 369 1014 662 1014 370 1014 370 1015 662 1015 663 1015 370 1016 663 1016 371 1016 677 1017 285 1017 678 1017 678 1018 285 1018 283 1018 678 1019 283 1019 679 1019 679 1020 283 1020 282 1020 679 1021 282 1021 680 1021 680 1022 282 1022 310 1022 680 1023 310 1023 681 1023 681 1024 310 1024 316 1024 681 1025 316 1025 682 1025 682 1026 316 1026 315 1026 682 1027 315 1027 683 1027 683 1028 315 1028 355 1028 683 1029 355 1029 684 1029 684 1030 355 1030 356 1030 684 1031 356 1031 685 1031 685 1032 356 1032 354 1032 685 1033 354 1033 686 1033 686 1034 354 1034 353 1034 686 1035 353 1035 687 1035 687 1036 353 1036 364 1036 687 1037 364 1037 688 1037 688 1038 364 1038 363 1038 688 1039 363 1039 689 1039 689 1040 363 1040 371 1040 689 1041 371 1041 690 1041 690 1042 371 1042 663 1042 690 1043 663 1043 691 1043 691 1044 663 1044 392 1044 691 1045 392 1045 692 1045 692 1046 392 1046 391 1046 692 1047 391 1047 693 1047 693 1048 391 1048 672 1048 693 1049 672 1049 694 1049 694 1050 672 1050 673 1050 694 1051 673 1051 695 1051 695 1052 673 1052 674 1052 695 1053 674 1053 696 1053 696 1054 674 1054 675 1054 696 1055 675 1055 697 1055 697 1056 675 1056 667 1056 697 1057 667 1057 559 1057 559 1058 667 1058 668 1058 559 1059 668 1059 561 1059 561 1060 668 1060 669 1060 561 1061 669 1061 563 1061 563 1062 669 1062 670 1062 563 1063 670 1063 565 1063 565 1064 670 1064 671 1064 565 1065 671 1065 566 1065 579 1066 677 1066 580 1066 580 1067 677 1067 678 1067 580 1068 678 1068 581 1068 581 1069 678 1069 679 1069 581 1070 679 1070 582 1070 582 1071 679 1071 680 1071 582 1072 680 1072 583 1072 583 1073 680 1073 681 1073 583 1074 681 1074 584 1074 584 1075 681 1075 682 1075 584 1076 682 1076 585 1076 585 1077 682 1077 683 1077 585 1078 683 1078 586 1078 586 1079 683 1079 684 1079 586 1080 684 1080 587 1080 587 1081 684 1081 685 1081 587 1082 685 1082 588 1082 588 1083 685 1083 686 1083 588 1084 686 1084 589 1084 589 1085 686 1085 687 1085 589 1086 687 1086 590 1086 590 1087 687 1087 688 1087 590 1088 688 1088 591 1088 591 1089 688 1089 689 1089 591 1090 689 1090 592 1090 592 1091 689 1091 690 1091 592 1092 690 1092 593 1092 593 1093 690 1093 691 1093 593 1094 691 1094 594 1094 594 1095 691 1095 692 1095 594 1096 692 1096 595 1096 595 1097 692 1097 693 1097 595 1098 693 1098 596 1098 596 1099 693 1099 694 1099 596 1100 694 1100 597 1100 597 1101 694 1101 695 1101 597 1102 695 1102 598 1102 598 1103 695 1103 696 1103 598 1104 696 1104 578 1104 578 1105 696 1105 697 1105 578 1106 697 1106 577 1106 577 1107 697 1107 559 1107 577 1108 559 1108 575 1108 575 1109 559 1109 558 1109 575 1110 558 1110 573 1110 573 1111 558 1111 572 1111 573 1112 572 1112 448 1112 448 1113 572 1113 599 1113 448 1114 599 1114 404 1114 404 1115 599 1115 476 1115 404 1116 476 1116 405 1116 405 1117 476 1117 145 1117 405 1118 145 1118 407 1118 407 1119 145 1119 147 1119 407 1120 147 1120 409 1120 409 1121 147 1121 470 1121 409 1122 470 1122 411 1122 411 1123 470 1123 471 1123 411 1124 471 1124 413 1124 413 1125 471 1125 478 1125 413 1126 478 1126 415 1126 415 1127 478 1127 477 1127 415 1128 477 1128 417 1128 417 1129 477 1129 508 1129 417 1130 508 1130 419 1130 419 1131 508 1131 507 1131 419 1132 507 1132 421 1132 421 1133 507 1133 546 1133 421 1134 546 1134 423 1134 423 1135 546 1135 489 1135 423 1136 489 1136 425 1136 425 1137 489 1137 488 1137 425 1138 488 1138 427 1138 427 1139 488 1139 523 1139 427 1140 523 1140 429 1140 429 1141 523 1141 534 1141 429 1142 534 1142 431 1142 431 1143 534 1143 403 1143 431 1144 403 1144 433 1144 433 1145 403 1145 381 1145 433 1146 381 1146 435 1146 435 1147 381 1147 380 1147 435 1148 380 1148 437 1148 437 1149 380 1149 379 1149 437 1150 379 1150 439 1150 439 1151 379 1151 378 1151 439 1152 378 1152 441 1152 441 1153 378 1153 377 1153 441 1154 377 1154 443 1154 443 1155 377 1155 376 1155 443 1156 376 1156 445 1156 445 1157 376 1157 375 1157 445 1158 375 1158 447 1158 447 1159 375 1159 374 1159 447 1160 374 1160 156 1160 156 1161 374 1161 174 1161 156 1162 174 1162 294 1162 294 1163 174 1163 176 1163 109 1164 698 1164 699 1164 95 1165 700 1165 701 1165 83 1166 85 1166 702 1166 702 1167 85 1167 87 1167 702 1168 87 1168 703 1168 703 1169 87 1169 130 1169 703 1170 130 1170 128 1170 704 1171 88 1171 702 1171 702 1172 88 1172 81 1172 702 1173 81 1173 83 1173 700 1174 95 1174 705 1174 95 1175 93 1175 705 1175 705 1176 93 1176 91 1176 705 1177 91 1177 704 1177 704 1178 91 1178 89 1178 704 1179 89 1179 88 1179 100 1180 99 1180 701 1180 701 1181 99 1181 97 1181 701 1182 97 1182 95 1182 701 1183 706 1183 100 1183 100 1184 706 1184 707 1184 100 1185 707 1185 102 1185 698 1186 109 1186 708 1186 109 1187 107 1187 708 1187 708 1188 107 1188 105 1188 708 1189 105 1189 707 1189 707 1190 105 1190 104 1190 707 1191 104 1191 102 1191 116 1192 114 1192 709 1192 709 1193 114 1193 112 1193 709 1194 112 1194 699 1194 699 1195 112 1195 110 1195 699 1196 110 1196 109 1196 116 1197 709 1197 1 1197 1 1198 709 1198 710 1198 1 1199 710 1199 2 1199 2 1200 710 1200 711 1200 2 1201 711 1201 4 1201 176 1202 712 1202 294 1202 294 1203 712 1203 713 1203 294 1204 713 1204 154 1204 154 1205 713 1205 714 1205 154 1206 714 1206 155 1206 155 1207 714 1207 291 1207 291 1208 714 1208 715 1208 291 1209 715 1209 292 1209 292 1210 715 1210 290 1210 290 1211 715 1211 716 1211 290 1212 716 1212 157 1212 157 1213 716 1213 158 1213 158 1214 716 1214 717 1214 158 1215 717 1215 579 1215 579 1216 717 1216 718 1216 579 1217 718 1217 677 1217 677 1218 718 1218 719 1218 677 1219 719 1219 285 1219 285 1220 719 1220 286 1220 286 1221 719 1221 720 1221 286 1222 720 1222 287 1222 278 1223 318 1223 721 1223 721 1224 318 1224 289 1224 721 1225 289 1225 720 1225 720 1226 289 1226 288 1226 720 1227 288 1227 287 1227 722 1228 279 1228 278 1228 723 1229 281 1229 280 1229 724 1230 161 1230 723 1230 723 1231 161 1231 160 1231 723 1232 160 1232 281 1232 725 1233 726 1233 727 1233 265 1234 632 1234 727 1234 727 1235 632 1235 269 1235 727 1236 269 1236 725 1236 725 1237 269 1237 270 1237 725 1238 270 1238 728 1238 728 1239 270 1239 273 1239 728 1240 273 1240 729 1240 729 1241 273 1241 274 1241 729 1242 274 1242 730 1242 730 1243 274 1243 276 1243 730 1244 276 1244 724 1244 724 1245 276 1245 277 1245 724 1246 277 1246 161 1246 118 1247 55 1247 731 1247 731 1248 732 1248 118 1248 118 1249 732 1249 733 1249 118 1250 733 1250 734 1250 128 1251 126 1251 703 1251 703 1252 126 1252 124 1252 703 1253 124 1253 735 1253 735 1254 124 1254 122 1254 735 1255 122 1255 734 1255 734 1256 122 1256 120 1256 734 1257 120 1257 118 1257 278 1258 721 1258 722 1258 722 1259 721 1259 736 1259 722 1260 736 1260 737 1260 737 1261 736 1261 738 1261 737 1262 738 1262 739 1262 712 1263 740 1263 713 1263 713 1264 740 1264 741 1264 713 1265 741 1265 714 1265 714 1266 741 1266 742 1266 714 1267 742 1267 715 1267 715 1268 742 1268 743 1268 715 1269 743 1269 716 1269 716 1270 743 1270 744 1270 716 1271 744 1271 717 1271 717 1272 744 1272 745 1272 717 1273 745 1273 718 1273 718 1274 745 1274 746 1274 718 1275 746 1275 719 1275 719 1276 746 1276 747 1276 719 1277 747 1277 720 1277 720 1278 747 1278 748 1278 720 1279 748 1279 721 1279 721 1280 748 1280 749 1280 721 1281 749 1281 736 1281 736 1282 749 1282 750 1282 736 1283 750 1283 738 1283 740 1284 711 1284 741 1284 741 1285 711 1285 710 1285 741 1286 710 1286 742 1286 742 1287 710 1287 709 1287 742 1288 709 1288 743 1288 743 1289 709 1289 699 1289 743 1290 699 1290 744 1290 744 1291 699 1291 698 1291 744 1292 698 1292 745 1292 745 1293 698 1293 708 1293 745 1294 708 1294 746 1294 746 1295 708 1295 707 1295 746 1296 707 1296 747 1296 747 1297 707 1297 706 1297 747 1298 706 1298 748 1298 748 1299 706 1299 701 1299 748 1300 701 1300 749 1300 749 1301 701 1301 700 1301 749 1302 700 1302 750 1302 750 1303 700 1303 705 1303 750 1304 705 1304 738 1304 738 1305 705 1305 704 1305 738 1306 704 1306 739 1306 739 1307 704 1307 702 1307 733 1308 751 1308 734 1308 734 1309 751 1309 752 1309 734 1310 752 1310 735 1310 735 1311 752 1311 753 1311 735 1312 753 1312 703 1312 703 1313 753 1313 754 1313 703 1314 754 1314 702 1314 702 1315 754 1315 755 1315 702 1316 755 1316 739 1316 266 1317 265 1317 756 1317 756 1318 265 1318 727 1318 756 1319 727 1319 757 1319 757 1320 727 1320 726 1320 757 1321 726 1321 751 1321 751 1322 726 1322 752 1322 752 1323 726 1323 725 1323 752 1324 725 1324 753 1324 753 1325 725 1325 728 1325 753 1326 728 1326 754 1326 754 1327 728 1327 729 1327 754 1328 729 1328 755 1328 755 1329 729 1329 730 1329 755 1330 730 1330 739 1330 739 1331 730 1331 724 1331 739 1332 724 1332 737 1332 737 1333 724 1333 723 1333 737 1334 723 1334 722 1334 722 1335 723 1335 280 1335 722 1336 280 1336 279 1336 624 1337 259 1337 758 1337 758 1338 259 1338 258 1338 758 1339 258 1339 759 1339 258 1340 644 1340 759 1340 759 1341 644 1341 261 1341 759 1342 261 1342 760 1342 760 1343 261 1343 264 1343 760 1344 264 1344 761 1344 761 1345 264 1345 266 1345 762 1346 763 1346 764 1346 765 1347 766 1347 10 1347 767 1348 768 1348 769 1348 770 1349 771 1349 772 1349 772 1350 771 1350 763 1350 764 1351 773 1351 762 1351 762 1352 773 1352 774 1352 762 1353 774 1353 775 1353 775 1354 774 1354 776 1354 775 1355 776 1355 777 1355 777 1356 776 1356 778 1356 777 1357 778 1357 779 1357 779 1358 778 1358 780 1358 779 1359 780 1359 781 1359 780 1360 782 1360 781 1360 781 1361 782 1361 783 1361 781 1362 783 1362 784 1362 784 1363 783 1363 785 1363 784 1364 785 1364 786 1364 786 1365 785 1365 787 1365 786 1366 787 1366 788 1366 788 1367 787 1367 789 1367 788 1368 789 1368 790 1368 790 1369 789 1369 791 1369 792 1370 793 1370 791 1370 791 1371 793 1371 794 1371 791 1372 794 1372 790 1372 792 1373 795 1373 793 1373 793 1374 795 1374 796 1374 793 1375 796 1375 797 1375 797 1376 796 1376 798 1376 797 1377 798 1377 799 1377 799 1378 798 1378 800 1378 799 1379 800 1379 801 1379 801 1380 800 1380 802 1380 801 1381 802 1381 803 1381 803 1382 802 1382 804 1382 805 1383 806 1383 804 1383 804 1384 806 1384 807 1384 804 1385 807 1385 803 1385 805 1386 808 1386 806 1386 806 1387 808 1387 809 1387 806 1388 809 1388 810 1388 810 1389 809 1389 811 1389 810 1390 811 1390 812 1390 812 1391 811 1391 813 1391 814 1392 815 1392 813 1392 813 1393 815 1393 816 1393 813 1394 816 1394 812 1394 814 1395 817 1395 815 1395 815 1396 817 1396 624 1396 815 1397 624 1397 818 1397 818 1398 624 1398 819 1398 818 1399 819 1399 820 1399 763 1400 762 1400 772 1400 772 1401 762 1401 775 1401 772 1402 775 1402 821 1402 821 1403 775 1403 777 1403 821 1404 777 1404 822 1404 822 1405 777 1405 779 1405 822 1406 779 1406 823 1406 823 1407 779 1407 781 1407 823 1408 781 1408 824 1408 824 1409 781 1409 784 1409 824 1410 784 1410 825 1410 825 1411 784 1411 786 1411 825 1412 786 1412 826 1412 826 1413 786 1413 788 1413 826 1414 788 1414 827 1414 827 1415 788 1415 790 1415 827 1416 790 1416 828 1416 828 1417 790 1417 794 1417 828 1418 794 1418 829 1418 829 1419 794 1419 793 1419 829 1420 793 1420 830 1420 830 1421 793 1421 797 1421 830 1422 797 1422 831 1422 831 1423 797 1423 799 1423 831 1424 799 1424 832 1424 832 1425 799 1425 801 1425 832 1426 801 1426 833 1426 833 1427 801 1427 803 1427 833 1428 803 1428 834 1428 834 1429 803 1429 807 1429 834 1430 807 1430 835 1430 835 1431 807 1431 806 1431 835 1432 806 1432 836 1432 836 1433 806 1433 810 1433 836 1434 810 1434 837 1434 837 1435 810 1435 812 1435 837 1436 812 1436 838 1436 838 1437 812 1437 816 1437 838 1438 816 1438 839 1438 839 1439 816 1439 815 1439 839 1440 815 1440 840 1440 840 1441 815 1441 818 1441 840 1442 818 1442 767 1442 767 1443 818 1443 820 1443 767 1444 820 1444 768 1444 770 1445 772 1445 841 1445 841 1446 772 1446 821 1446 841 1447 821 1447 842 1447 842 1448 821 1448 822 1448 842 1449 822 1449 843 1449 843 1450 822 1450 823 1450 843 1451 823 1451 844 1451 844 1452 823 1452 824 1452 844 1453 824 1453 845 1453 845 1454 824 1454 825 1454 845 1455 825 1455 846 1455 846 1456 825 1456 826 1456 846 1457 826 1457 847 1457 847 1458 826 1458 827 1458 847 1459 827 1459 848 1459 848 1460 827 1460 828 1460 848 1461 828 1461 849 1461 849 1462 828 1462 829 1462 849 1463 829 1463 850 1463 850 1464 829 1464 830 1464 850 1465 830 1465 851 1465 851 1466 830 1466 831 1466 851 1467 831 1467 852 1467 852 1468 831 1468 832 1468 852 1469 832 1469 853 1469 853 1470 832 1470 833 1470 853 1471 833 1471 854 1471 854 1472 833 1472 834 1472 854 1473 834 1473 855 1473 855 1474 834 1474 835 1474 855 1475 835 1475 856 1475 856 1476 835 1476 836 1476 856 1477 836 1477 857 1477 857 1478 836 1478 837 1478 857 1479 837 1479 858 1479 858 1480 837 1480 838 1480 858 1481 838 1481 859 1481 859 1482 838 1482 839 1482 859 1483 839 1483 860 1483 860 1484 839 1484 840 1484 860 1485 840 1485 861 1485 861 1486 840 1486 767 1486 861 1487 767 1487 765 1487 765 1488 767 1488 769 1488 765 1489 769 1489 766 1489 10 1490 9 1490 765 1490 765 1491 9 1491 37 1491 765 1492 37 1492 861 1492 861 1493 37 1493 36 1493 861 1494 36 1494 860 1494 860 1495 36 1495 30 1495 860 1496 30 1496 859 1496 859 1497 30 1497 29 1497 859 1498 29 1498 858 1498 858 1499 29 1499 28 1499 858 1500 28 1500 857 1500 857 1501 28 1501 22 1501 857 1502 22 1502 856 1502 856 1503 22 1503 21 1503 856 1504 21 1504 855 1504 855 1505 21 1505 25 1505 855 1506 25 1506 854 1506 854 1507 25 1507 40 1507 854 1508 40 1508 853 1508 853 1509 40 1509 39 1509 853 1510 39 1510 852 1510 852 1511 39 1511 38 1511 852 1512 38 1512 851 1512 851 1513 38 1513 27 1513 851 1514 27 1514 850 1514 850 1515 27 1515 26 1515 850 1516 26 1516 849 1516 849 1517 26 1517 8 1517 849 1518 8 1518 848 1518 848 1519 8 1519 11 1519 848 1520 11 1520 847 1520 847 1521 11 1521 13 1521 847 1522 13 1522 846 1522 846 1523 13 1523 35 1523 846 1524 35 1524 845 1524 845 1525 35 1525 34 1525 845 1526 34 1526 844 1526 844 1527 34 1527 33 1527 844 1528 33 1528 843 1528 843 1529 33 1529 18 1529 843 1530 18 1530 842 1530 842 1531 18 1531 19 1531 842 1532 19 1532 841 1532 841 1533 19 1533 20 1533 841 1534 20 1534 770 1534 233 1535 232 1535 774 1535 232 1536 167 1536 774 1536 774 1537 167 1537 166 1537 774 1538 166 1538 776 1538 776 1539 166 1539 162 1539 162 1540 236 1540 776 1540 776 1541 236 1541 235 1541 776 1542 235 1542 778 1542 778 1543 235 1543 239 1543 233 1544 774 1544 227 1544 227 1545 774 1545 773 1545 227 1546 773 1546 764 1546 238 1547 782 1547 239 1547 239 1548 782 1548 780 1548 239 1549 780 1549 778 1549 789 1550 787 1550 245 1550 238 1551 620 1551 782 1551 782 1552 620 1552 242 1552 782 1553 242 1553 783 1553 783 1554 242 1554 241 1554 783 1555 241 1555 785 1555 785 1556 241 1556 244 1556 785 1557 244 1557 787 1557 787 1558 244 1558 243 1558 787 1559 243 1559 245 1559 245 1560 249 1560 789 1560 789 1561 249 1561 248 1561 789 1562 248 1562 791 1562 791 1563 248 1563 247 1563 791 1564 247 1564 792 1564 792 1565 247 1565 795 1565 795 1566 247 1566 567 1566 795 1567 567 1567 796 1567 802 1568 800 1568 253 1568 253 1569 800 1569 798 1569 253 1570 798 1570 671 1570 671 1571 798 1571 796 1571 671 1572 796 1572 566 1572 566 1573 796 1573 567 1573 802 1574 253 1574 804 1574 804 1575 253 1575 251 1575 804 1576 251 1576 805 1576 805 1577 251 1577 250 1577 805 1578 250 1578 808 1578 808 1579 250 1579 640 1579 808 1580 640 1580 809 1580 809 1581 640 1581 255 1581 809 1582 255 1582 811 1582 811 1583 255 1583 254 1583 811 1584 254 1584 813 1584 813 1585 254 1585 256 1585 813 1586 256 1586 814 1586 814 1587 256 1587 817 1587 817 1588 256 1588 257 1588 817 1589 257 1589 624 1589 63 1590 7 1590 6 1590 819 1591 624 1591 758 1591 63 1592 6 1592 64 1592 862 1593 65 1593 64 1593 59 1594 61 1594 862 1594 862 1595 61 1595 62 1595 862 1596 62 1596 65 1596 57 1597 56 1597 863 1597 863 1598 56 1598 59 1598 52 1599 864 1599 54 1599 54 1600 864 1600 55 1600 52 1601 58 1601 864 1601 864 1602 58 1602 57 1602 864 1603 57 1603 732 1603 732 1604 57 1604 863 1604 732 1605 863 1605 865 1605 865 1606 863 1606 866 1606 865 1607 866 1607 867 1607 867 1608 866 1608 868 1608 867 1609 868 1609 869 1609 869 1610 868 1610 870 1610 870 1611 868 1611 871 1611 870 1612 871 1612 872 1612 872 1613 871 1613 873 1613 872 1614 873 1614 874 1614 874 1615 873 1615 875 1615 875 1616 873 1616 876 1616 875 1617 876 1617 877 1617 877 1618 876 1618 878 1618 877 1619 878 1619 879 1619 879 1620 878 1620 266 1620 266 1621 878 1621 880 1621 266 1622 880 1622 761 1622 761 1623 880 1623 881 1623 761 1624 881 1624 760 1624 64 1625 6 1625 862 1625 862 1626 6 1626 45 1626 862 1627 45 1627 882 1627 882 1628 45 1628 44 1628 882 1629 44 1629 883 1629 883 1630 44 1630 43 1630 883 1631 43 1631 884 1631 884 1632 43 1632 42 1632 884 1633 42 1633 885 1633 885 1634 42 1634 41 1634 885 1635 41 1635 886 1635 886 1636 41 1636 24 1636 886 1637 24 1637 887 1637 887 1638 24 1638 23 1638 887 1639 23 1639 888 1639 888 1640 23 1640 32 1640 888 1641 32 1641 889 1641 889 1642 32 1642 31 1642 889 1643 31 1643 890 1643 820 1644 819 1644 891 1644 891 1645 819 1645 758 1645 891 1646 758 1646 881 1646 881 1647 758 1647 759 1647 881 1648 759 1648 760 1648 31 1649 10 1649 766 1649 31 1650 766 1650 890 1650 890 1651 766 1651 769 1651 890 1652 769 1652 768 1652 59 1653 862 1653 863 1653 863 1654 862 1654 882 1654 863 1655 882 1655 866 1655 866 1656 882 1656 883 1656 866 1657 883 1657 868 1657 868 1658 883 1658 884 1658 868 1659 884 1659 871 1659 871 1660 884 1660 885 1660 871 1661 885 1661 873 1661 873 1662 885 1662 886 1662 873 1663 886 1663 876 1663 876 1664 886 1664 887 1664 876 1665 887 1665 878 1665 878 1666 887 1666 888 1666 878 1667 888 1667 880 1667 880 1668 888 1668 889 1668 880 1669 889 1669 881 1669 881 1670 889 1670 890 1670 881 1671 890 1671 891 1671 891 1672 890 1672 768 1672 891 1673 768 1673 820 1673 733 1674 732 1674 865 1674 757 1675 875 1675 877 1675 757 1676 877 1676 756 1676 756 1677 877 1677 879 1677 756 1678 879 1678 266 1678 865 1679 867 1679 733 1679 733 1680 867 1680 869 1680 733 1681 869 1681 751 1681 869 1682 870 1682 751 1682 751 1683 870 1683 872 1683 751 1684 872 1684 757 1684 757 1685 872 1685 874 1685 757 1686 874 1686 875 1686 732 1687 731 1687 864 1687 864 1688 731 1688 55 1688 892 1689 893 1689 894 1689 894 1690 895 1690 892 1690 892 1691 895 1691 896 1691 892 1692 896 1692 897 1692 897 1689 898 1689 892 1689 892 1689 898 1689 899 1689 892 1693 899 1693 900 1693 900 1694 899 1694 901 1694 900 1689 901 1689 902 1689 903 1695 904 1695 905 1695 906 1696 907 1696 908 1696 908 1697 907 1697 909 1697 909 1698 907 1698 900 1698 909 1699 900 1699 902 1699 910 1700 911 1700 912 1700 912 1701 911 1701 913 1701 912 1702 913 1702 914 1702 914 1703 913 1703 915 1703 914 1704 915 1704 916 1704 917 1705 918 1705 919 1705 919 1706 920 1706 917 1706 917 1707 920 1707 921 1707 917 1708 921 1708 910 1708 910 1709 921 1709 922 1709 910 1710 922 1710 911 1710 923 1711 924 1711 925 1711 925 1712 924 1712 926 1712 925 1713 926 1713 918 1713 918 1714 926 1714 927 1714 918 1715 927 1715 919 1715 928 1716 929 1716 930 1716 930 1717 929 1717 931 1717 930 1718 931 1718 932 1718 932 1719 931 1719 933 1719 932 1720 933 1720 934 1720 934 1721 933 1721 935 1721 934 1722 935 1722 936 1722 936 1723 935 1723 937 1723 936 1724 937 1724 938 1724 938 1725 937 1725 939 1725 938 1726 939 1726 923 1726 923 1727 939 1727 940 1727 923 1728 940 1728 924 1728 904 1729 941 1729 905 1729 905 1730 941 1730 942 1730 905 1731 942 1731 943 1731 943 1732 942 1732 944 1732 943 1733 944 1733 928 1733 928 1734 944 1734 945 1734 928 1735 945 1735 929 1735 903 1736 905 1736 946 1736 946 1737 905 1737 947 1737 946 1738 947 1738 948 1738 948 1739 947 1739 949 1739 948 1740 949 1740 950 1740 951 1741 952 1741 953 1741 953 1742 952 1742 954 1742 953 1743 954 1743 955 1743 954 1744 956 1744 955 1744 955 1745 956 1745 957 1745 955 1746 957 1746 958 1746 958 1747 957 1747 959 1747 958 1748 959 1748 960 1748 960 1749 959 1749 961 1749 960 1750 961 1750 962 1750 962 1751 961 1751 963 1751 962 1752 963 1752 964 1752 964 1753 963 1753 965 1753 964 1754 965 1754 966 1754 966 1755 965 1755 967 1755 966 1756 967 1756 949 1756 949 1757 967 1757 968 1757 949 1758 968 1758 950 1758 908 1759 969 1759 906 1759 906 1760 969 1760 970 1760 906 1761 970 1761 971 1761 970 1762 972 1762 971 1762 971 1763 972 1763 973 1763 971 1764 973 1764 951 1764 951 1765 973 1765 974 1765 951 1766 974 1766 952 1766 975 1767 976 1767 977 1767 978 1768 979 1768 980 1768 981 1769 982 1769 983 1769 983 1770 982 1770 984 1770 983 1771 984 1771 985 1771 985 1772 984 1772 986 1772 985 1773 986 1773 977 1773 977 1774 986 1774 978 1774 977 1775 978 1775 975 1775 975 1776 978 1776 980 1776 983 1777 987 1777 981 1777 981 1778 987 1778 988 1778 981 1779 988 1779 989 1779 989 1780 988 1780 990 1780 988 1781 991 1781 990 1781 990 1782 991 1782 992 1782 990 1783 992 1783 993 1783 993 1784 992 1784 994 1784 893 1785 892 1785 995 1785 992 1786 996 1786 994 1786 994 1787 996 1787 997 1787 994 1788 997 1788 998 1788 998 1789 997 1789 893 1789 998 1790 893 1790 999 1790 999 1791 893 1791 995 1791 978 1792 14 1792 50 1792 50 1793 49 1793 978 1793 978 1794 49 1794 1000 1794 978 1795 1000 1795 979 1795 978 1796 1001 1796 14 1796 14 1797 1001 1797 1002 1797 14 1798 1002 1798 15 1798 15 1799 1002 1799 1003 1799 15 1800 1003 1800 1004 1800 1005 1801 1006 1801 1007 1801 1008 1802 1005 1802 1009 1802 1005 1803 1007 1803 1009 1803 1009 1804 1007 1804 1010 1804 1009 1805 1010 1805 1011 1805 1011 1806 1010 1806 1012 1806 1011 1807 1012 1807 1013 1807 1013 1808 1012 1808 1014 1808 1013 1809 1014 1809 1015 1809 1008 1810 1009 1810 1016 1810 1016 1811 1009 1811 1011 1811 1016 1812 1011 1812 1017 1812 1017 1813 1011 1813 1013 1813 1017 1814 1013 1814 1018 1814 1018 1815 1013 1815 1015 1815 1018 1816 1015 1816 1019 1816 1020 1817 1021 1817 1022 1817 1022 1818 1006 1818 1005 1818 1020 1819 1022 1819 1023 1819 1023 1820 1022 1820 1005 1820 1023 1821 1005 1821 1008 1821 1024 1822 1025 1822 1026 1822 1024 1823 1026 1823 1027 1823 1027 1824 1026 1824 1021 1824 1027 1825 1021 1825 1020 1825 1028 1826 1029 1826 1030 1826 1030 1827 1029 1827 1031 1827 1030 1828 1031 1828 1032 1828 1032 1829 1031 1829 1033 1829 1034 1830 1035 1830 1036 1830 1036 1831 892 1831 900 1831 1028 1832 1034 1832 1029 1832 1029 1833 1034 1833 1036 1833 1029 1834 1036 1834 1037 1834 1037 1835 1036 1835 900 1835 1021 1836 1038 1836 1022 1836 1022 1837 1038 1837 1006 1837 1006 1838 1038 1838 1007 1838 1007 1839 1038 1839 1039 1839 1007 1840 1039 1840 1010 1840 1010 1841 1039 1841 1040 1841 1010 1842 1040 1842 1012 1842 1040 1843 1041 1843 1012 1843 1012 1844 1041 1844 1042 1844 1012 1845 1042 1845 1014 1845 1038 1846 1043 1846 1044 1846 1038 1847 1044 1847 1039 1847 1039 1848 1044 1848 1045 1848 1039 1849 1045 1849 1040 1849 1040 1850 1045 1850 1046 1850 1040 1851 1046 1851 1041 1851 1041 1852 1046 1852 1047 1852 1041 1853 1047 1853 1042 1853 1048 1854 1049 1854 1050 1854 1051 1855 1019 1855 1052 1855 1052 1856 1019 1856 1015 1856 1052 1857 1015 1857 1053 1857 1053 1858 1015 1858 1014 1858 1054 1859 1051 1859 1050 1859 1050 1860 1051 1860 1052 1860 1050 1861 1052 1861 1048 1861 1048 1862 1052 1862 1053 1862 1055 1863 1056 1863 1057 1863 1057 1864 1056 1864 1054 1864 1050 1865 1049 1865 1058 1865 1059 1866 1060 1866 1058 1866 1058 1867 1060 1867 1057 1867 1058 1868 1057 1868 1050 1868 1050 1869 1057 1869 1054 1869 1061 1870 1055 1870 1062 1870 1062 1871 1055 1871 1057 1871 1062 1872 1057 1872 1063 1872 1063 1873 1057 1873 1060 1873 1043 1874 1038 1874 1064 1874 1065 1875 1066 1875 1067 1875 1021 1876 1026 1876 1038 1876 1038 1877 1026 1877 1025 1877 1038 1878 1025 1878 1064 1878 1067 1879 1068 1879 1069 1879 1065 1880 1067 1880 1070 1880 1067 1881 1071 1881 1070 1881 1070 1882 1071 1882 1072 1882 1070 1883 1072 1883 1073 1883 1073 1884 1072 1884 1064 1884 1073 1885 1064 1885 1074 1885 1074 1886 1064 1886 1025 1886 1067 1887 1069 1887 1071 1887 1071 1888 1069 1888 1075 1888 1071 1889 1075 1889 1072 1889 1072 1890 1075 1890 1076 1890 1072 1891 1076 1891 1064 1891 1064 1892 1076 1892 1077 1892 1064 1893 1077 1893 1043 1893 1078 1894 1079 1894 1080 1894 1081 1895 1082 1895 1083 1895 1083 1896 1082 1896 1084 1896 1083 1897 1084 1897 1085 1897 1085 1898 1084 1898 1086 1898 1085 1899 1086 1899 1080 1899 1080 1900 1086 1900 1087 1900 1080 1901 1087 1901 1078 1901 1088 1902 1089 1902 1090 1902 1090 1903 1089 1903 1091 1903 1090 1904 1091 1904 1092 1904 1093 1905 1094 1905 1095 1905 1095 1906 1094 1906 1096 1906 1095 1907 1096 1907 1097 1907 1081 1908 1098 1908 1082 1908 1082 1909 1098 1909 1099 1909 1082 1910 1099 1910 1100 1910 1100 1911 1099 1911 1101 1911 1100 1912 1101 1912 1102 1912 1102 1913 1101 1913 1103 1913 1102 1914 1103 1914 1104 1914 1104 1915 1103 1915 1105 1915 1104 1916 1105 1916 1106 1916 1106 1917 1105 1917 1097 1917 1106 1918 1097 1918 1107 1918 1107 1919 1097 1919 1096 1919 1096 1920 1108 1920 1107 1920 1107 1921 1108 1921 1109 1921 1107 1922 1109 1922 1106 1922 1106 1923 1109 1923 1110 1923 1106 1924 1110 1924 1104 1924 1104 1925 1110 1925 1111 1925 1104 1926 1111 1926 1102 1926 1102 1927 1111 1927 1112 1927 1102 1928 1112 1928 1100 1928 1100 1929 1112 1929 1113 1929 1100 1930 1113 1930 1082 1930 1082 1931 1113 1931 1114 1931 1082 1932 1114 1932 1084 1932 1084 1933 1114 1933 1115 1933 1084 1934 1115 1934 1086 1934 1086 1935 1115 1935 1090 1935 1086 1936 1090 1936 1087 1936 1087 1937 1090 1937 1092 1937 1087 1938 1092 1938 1078 1938 1096 1939 1116 1939 1108 1939 1108 1940 1116 1940 1117 1940 1108 1941 1117 1941 1118 1941 1088 1942 1090 1942 1119 1942 1119 1943 1090 1943 1115 1943 1119 1944 1115 1944 1120 1944 1120 1945 1115 1945 1114 1945 1120 1946 1114 1946 1121 1946 1121 1947 1114 1947 1113 1947 1121 1948 1113 1948 1122 1948 1122 1949 1113 1949 1112 1949 1122 1950 1112 1950 1123 1950 1123 1951 1112 1951 1111 1951 1123 1952 1111 1952 1124 1952 1124 1953 1111 1953 1110 1953 1124 1954 1110 1954 1125 1954 1125 1955 1110 1955 1109 1955 1125 1956 1109 1956 1126 1956 1126 1957 1109 1957 1108 1957 1126 1958 1108 1958 1127 1958 1127 1959 1108 1959 1118 1959 1127 1960 1118 1960 1128 1960 1129 1961 1130 1961 1131 1961 1131 1962 1130 1962 1132 1962 1131 1963 1132 1963 1133 1963 1133 1964 1132 1964 1134 1964 1133 1965 1134 1965 1135 1965 1135 1966 1134 1966 1136 1966 1136 1967 1134 1967 1137 1967 1136 1968 1137 1968 1138 1968 1138 1969 1137 1969 1139 1969 1138 1970 1139 1970 1140 1970 1141 1971 1142 1971 1143 1971 1144 1972 1025 1972 1024 1972 1024 1973 1145 1973 1144 1973 1144 1974 1145 1974 1146 1974 1144 1975 1146 1975 1143 1975 1143 1976 1146 1976 1147 1976 1143 1977 1147 1977 1141 1977 1063 1978 1060 1978 1148 1978 1060 1979 1059 1979 1149 1979 1150 1980 1062 1980 1063 1980 1062 1981 1150 1981 1061 1981 1061 1982 1150 1982 1151 1982 1151 1983 1150 1983 1152 1983 1151 1984 1152 1984 1153 1984 1060 1985 1149 1985 1148 1985 1148 1986 1149 1986 1154 1986 1148 1987 1154 1987 1155 1987 1155 1988 1154 1988 1156 1988 1155 1989 1156 1989 1157 1989 1063 1990 1148 1990 1150 1990 1150 1991 1148 1991 1155 1991 1150 1992 1155 1992 1152 1992 1152 1993 1155 1993 1157 1993 1152 1994 1157 1994 1158 1994 1158 1995 1159 1995 1152 1995 1152 1996 1159 1996 1160 1996 1152 1997 1160 1997 1153 1997 1161 1998 1162 1998 1163 1998 1163 1999 1162 1999 1164 1999 1163 2000 1164 2000 1159 2000 1159 2001 1164 2001 1165 2001 1166 2002 1061 2002 1167 2002 1167 2003 1061 2003 1151 2003 1167 2004 1151 2004 1168 2004 1168 2005 1151 2005 1153 2005 1168 2006 1153 2006 1165 2006 1165 2007 1153 2007 1160 2007 1165 2008 1160 2008 1159 2008 1169 2009 1056 2009 1166 2009 1166 2010 1056 2010 1055 2010 1166 2011 1055 2011 1061 2011 1018 2012 1019 2012 1170 2012 1170 2013 1019 2013 1051 2013 1170 2014 1051 2014 1169 2014 1169 2015 1051 2015 1054 2015 1169 2016 1054 2016 1056 2016 1170 2017 1024 2017 1027 2017 1027 2018 1020 2018 1170 2018 1170 2019 1020 2019 1023 2019 1170 2020 1023 2020 1008 2020 1008 2021 1016 2021 1170 2021 1170 2022 1016 2022 1017 2022 1170 2023 1017 2023 1018 2023 1171 2024 1172 2024 1173 2024 1173 2025 1172 2025 1174 2025 1173 2026 1174 2026 1175 2026 1175 2027 1174 2027 1176 2027 1175 2028 1176 2028 1177 2028 1177 2029 1176 2029 1178 2029 1179 2030 1171 2030 1180 2030 1180 2031 1171 2031 1173 2031 1180 2032 1173 2032 1181 2032 1181 2033 1173 2033 1175 2033 1181 2034 1175 2034 1182 2034 1182 2035 1175 2035 1177 2035 1183 2036 1184 2036 1179 2036 1181 2037 1182 2037 1185 2037 1180 2038 1181 2038 1186 2038 1181 2039 1185 2039 1186 2039 1186 2040 1185 2040 1187 2040 1186 2041 1187 2041 1188 2041 1188 2042 1189 2042 1186 2042 1186 2043 1189 2043 1183 2043 1186 2044 1183 2044 1180 2044 1180 2045 1183 2045 1179 2045 1140 2046 1184 2046 1190 2046 1190 2047 1184 2047 1183 2047 1190 2048 1183 2048 1191 2048 1191 2049 1183 2049 1189 2049 1191 2050 1189 2050 1192 2050 1140 2051 1190 2051 1193 2051 1194 2052 1129 2052 1131 2052 1195 2053 1194 2053 1196 2053 1197 2054 1195 2054 1198 2054 1199 2055 1197 2055 1200 2055 1194 2056 1131 2056 1196 2056 1196 2057 1131 2057 1133 2057 1196 2058 1133 2058 1201 2058 1201 2059 1133 2059 1135 2059 1201 2060 1135 2060 1202 2060 1202 2061 1135 2061 1136 2061 1202 2062 1136 2062 1193 2062 1193 2063 1136 2063 1138 2063 1193 2064 1138 2064 1140 2064 1195 2065 1196 2065 1198 2065 1198 2066 1196 2066 1201 2066 1198 2067 1201 2067 1203 2067 1203 2068 1201 2068 1202 2068 1203 2069 1202 2069 1204 2069 1204 2070 1202 2070 1193 2070 1204 2071 1193 2071 1192 2071 1192 2072 1193 2072 1190 2072 1192 2073 1190 2073 1191 2073 1197 2074 1198 2074 1200 2074 1200 2075 1198 2075 1203 2075 1200 2076 1203 2076 1205 2076 1205 2077 1203 2077 1204 2077 1205 2078 1204 2078 1206 2078 1206 2079 1204 2079 1192 2079 1206 2080 1192 2080 1207 2080 1207 2081 1192 2081 1189 2081 1207 2082 1189 2082 1188 2082 1199 2083 1200 2083 1208 2083 1208 2084 1200 2084 1205 2084 1208 2085 1205 2085 1209 2085 1209 2086 1205 2086 1206 2086 1209 2087 1206 2087 1210 2087 1210 2088 1206 2088 1207 2088 1210 2089 1207 2089 1211 2089 1211 2090 1207 2090 1188 2090 1211 2091 1188 2091 1187 2091 1096 2092 1094 2092 1212 2092 1094 2093 1093 2093 1213 2093 1117 2094 1116 2094 1214 2094 1214 2095 1116 2095 1096 2095 1215 2096 1118 2096 1117 2096 1118 2097 1215 2097 1128 2097 1094 2098 1213 2098 1212 2098 1212 2099 1213 2099 1216 2099 1212 2100 1216 2100 1217 2100 1217 2101 1216 2101 1218 2101 1217 2102 1218 2102 1219 2102 1219 2103 1218 2103 1220 2103 1219 2104 1220 2104 1221 2104 1221 2105 1220 2105 1129 2105 1221 2106 1129 2106 1194 2106 1096 2107 1212 2107 1214 2107 1214 2108 1212 2108 1217 2108 1214 2109 1217 2109 1222 2109 1222 2110 1217 2110 1219 2110 1222 2111 1219 2111 1223 2111 1223 2112 1219 2112 1221 2112 1223 2113 1221 2113 1224 2113 1224 2114 1221 2114 1194 2114 1224 2115 1194 2115 1195 2115 1117 2116 1214 2116 1215 2116 1215 2117 1214 2117 1222 2117 1215 2118 1222 2118 1225 2118 1225 2119 1222 2119 1223 2119 1225 2120 1223 2120 1226 2120 1226 2121 1223 2121 1224 2121 1226 2122 1224 2122 1227 2122 1227 2123 1224 2123 1195 2123 1227 2124 1195 2124 1197 2124 1128 2125 1215 2125 1228 2125 1228 2126 1215 2126 1225 2126 1228 2127 1225 2127 1229 2127 1229 2128 1225 2128 1226 2128 1229 2129 1226 2129 1230 2129 1230 2130 1226 2130 1227 2130 1230 2131 1227 2131 1231 2131 1231 2132 1227 2132 1197 2132 1231 2133 1197 2133 1199 2133 1033 2134 1088 2134 1119 2134 1119 2135 1120 2135 1033 2135 1033 2136 1120 2136 1121 2136 1033 2137 1121 2137 1032 2137 1127 2138 1128 2138 1232 2138 1127 2139 1232 2139 1126 2139 1123 2140 1124 2140 1232 2140 1232 2141 1124 2141 1125 2141 1232 2142 1125 2142 1126 2142 1232 2143 1122 2143 1123 2143 1121 2144 1122 2144 1032 2144 1032 2145 1122 2145 1232 2145 1032 2146 1232 2146 1233 2146 1233 2147 1232 2147 1234 2147 1233 2148 1234 2148 1235 2148 1235 2149 1234 2149 1236 2149 1236 2150 1234 2150 1237 2150 1236 2151 1237 2151 1238 2151 1238 2152 1237 2152 1239 2152 1239 2153 1237 2153 1240 2153 1239 2154 1240 2154 1241 2154 1028 2155 1030 2155 1242 2155 1243 2156 1035 2156 1034 2156 1243 2157 1034 2157 1244 2157 1034 2158 1245 2158 1244 2158 1244 2159 1245 2159 1246 2159 1244 2160 1246 2160 1247 2160 1247 2161 1246 2161 1248 2161 1247 2162 1248 2162 1249 2162 1250 2163 1251 2163 1248 2163 1248 2164 1251 2164 1252 2164 1248 2165 1252 2165 1249 2165 1241 2166 1253 2166 1239 2166 1239 2167 1253 2167 1254 2167 1239 2168 1254 2168 1238 2168 1238 2169 1254 2169 1255 2169 1242 2170 1235 2170 1255 2170 1255 2171 1235 2171 1236 2171 1255 2172 1236 2172 1238 2172 1030 2173 1032 2173 1242 2173 1242 2174 1032 2174 1233 2174 1242 2175 1233 2175 1235 2175 1034 2176 1028 2176 1245 2176 1245 2177 1028 2177 1242 2177 1245 2178 1242 2178 1246 2178 1246 2179 1242 2179 1255 2179 1246 2180 1255 2180 1248 2180 1248 2181 1255 2181 1254 2181 1248 2182 1254 2182 1250 2182 1250 2183 1254 2183 1253 2183 1256 2184 1257 2184 1258 2184 1258 2185 1257 2185 1259 2185 1258 2186 1259 2186 1260 2186 1014 2187 1042 2187 1053 2187 1053 2188 1042 2188 1261 2188 1053 2189 1261 2189 1048 2189 1049 2190 1048 2190 1258 2190 1258 2191 1048 2191 1261 2191 1258 2192 1261 2192 1256 2192 1256 2193 1261 2193 1042 2193 1256 2194 1042 2194 1047 2194 1262 2195 1263 2195 1264 2195 1262 2196 1264 2196 1260 2196 1058 2197 1049 2197 1265 2197 1265 2198 1049 2198 1258 2198 1265 2199 1258 2199 1266 2199 1258 2200 1260 2200 1266 2200 1266 2201 1260 2201 1264 2201 1266 2202 1264 2202 1265 2202 1265 2203 1264 2203 1267 2203 1265 2204 1267 2204 1058 2204 1058 2205 1267 2205 1059 2205 1268 2206 1269 2206 1270 2206 1271 2207 1272 2207 1268 2207 1268 2208 1272 2208 1273 2208 1268 2209 1273 2209 1269 2209 1270 2210 1274 2210 1268 2210 1268 2211 1274 2211 1066 2211 1268 2212 1066 2212 1065 2212 1025 2213 1144 2213 1074 2213 1074 2214 1144 2214 1073 2214 1073 2215 1144 2215 1070 2215 1070 2216 1144 2216 1143 2216 1070 2217 1143 2217 1065 2217 1065 2218 1143 2218 1142 2218 1065 2219 1142 2219 1268 2219 1268 2220 1142 2220 1275 2220 1268 2221 1275 2221 1271 2221 1067 2222 1066 2222 1274 2222 1276 2223 1277 2223 1278 2223 1276 2224 1269 2224 1279 2224 1279 2225 1269 2225 1273 2225 1279 2226 1273 2226 1280 2226 1280 2227 1273 2227 1272 2227 1280 2228 1272 2228 1281 2228 1281 2229 1272 2229 1271 2229 1281 2230 1271 2230 1282 2230 1282 2231 1271 2231 1275 2231 1068 2232 1067 2232 1278 2232 1278 2233 1067 2233 1274 2233 1278 2234 1274 2234 1276 2234 1276 2235 1274 2235 1270 2235 1276 2236 1270 2236 1269 2236 1089 2237 1088 2237 1033 2237 1277 2238 1283 2238 1278 2238 1278 2239 1283 2239 1284 2239 1278 2240 1284 2240 1068 2240 1277 2241 1285 2241 1286 2241 1286 2242 1287 2242 1277 2242 1277 2243 1287 2243 1288 2243 1277 2244 1288 2244 1283 2244 1288 2245 1289 2245 1283 2245 1283 2246 1289 2246 1079 2246 1283 2247 1079 2247 1290 2247 1290 2248 1079 2248 1078 2248 1290 2249 1078 2249 1291 2249 1291 2250 1078 2250 1092 2250 1291 2251 1092 2251 1033 2251 1033 2252 1092 2252 1091 2252 1033 2253 1091 2253 1089 2253 1292 2254 1287 2254 1293 2254 1293 2255 1287 2255 1286 2255 1293 2256 1286 2256 1285 2256 1080 2257 1079 2257 1294 2257 1294 2258 1079 2258 1289 2258 1294 2259 1289 2259 1292 2259 1292 2260 1289 2260 1288 2260 1292 2261 1288 2261 1287 2261 1295 2262 1296 2262 1297 2262 1296 2263 1295 2263 1085 2263 1085 2264 1295 2264 1083 2264 1083 2265 1295 2265 1298 2265 1083 2266 1298 2266 1081 2266 1299 2267 1300 2267 1301 2267 1301 2268 1300 2268 1302 2268 1303 2269 1299 2269 1297 2269 1297 2270 1299 2270 1301 2270 1297 2271 1301 2271 1295 2271 1295 2272 1301 2272 1302 2272 1295 2273 1302 2273 1298 2273 1293 2274 1303 2274 1292 2274 1292 2275 1303 2275 1297 2275 1292 2276 1297 2276 1294 2276 1294 2277 1297 2277 1296 2277 1294 2278 1296 2278 1080 2278 1080 2279 1296 2279 1085 2279 1098 2280 1298 2280 1099 2280 1101 2281 1099 2281 1298 2281 1097 2282 1105 2282 1298 2282 1298 2283 1105 2283 1103 2283 1298 2284 1103 2284 1101 2284 1298 2285 1098 2285 1081 2285 1097 2286 1304 2286 1095 2286 1095 2287 1304 2287 1093 2287 1305 2288 1306 2288 1307 2288 1307 2289 1306 2289 1308 2289 1307 2290 1308 2290 1309 2290 1309 2291 1308 2291 1310 2291 1300 2292 1305 2292 1302 2292 1302 2293 1305 2293 1307 2293 1302 2294 1307 2294 1298 2294 1298 2295 1307 2295 1309 2295 1298 2296 1309 2296 1097 2296 1097 2297 1309 2297 1310 2297 1097 2298 1310 2298 1304 2298 1311 2299 1312 2299 1313 2299 1140 2300 1313 2300 1184 2300 1184 2301 1313 2301 1312 2301 1184 2302 1312 2302 1179 2302 1310 2303 1308 2303 1314 2303 1314 2304 1308 2304 1306 2304 1213 2305 1093 2305 1304 2305 1315 2306 1218 2306 1316 2306 1316 2307 1218 2307 1216 2307 1316 2308 1216 2308 1317 2308 1317 2309 1216 2309 1213 2309 1317 2310 1213 2310 1318 2310 1318 2311 1213 2311 1304 2311 1319 2312 1130 2312 1320 2312 1320 2313 1130 2313 1129 2313 1320 2314 1129 2314 1315 2314 1315 2315 1129 2315 1220 2315 1315 2316 1220 2316 1218 2316 1140 2317 1139 2317 1313 2317 1313 2318 1139 2318 1137 2318 1313 2319 1137 2319 1321 2319 1321 2320 1137 2320 1134 2320 1321 2321 1134 2321 1319 2321 1319 2322 1134 2322 1132 2322 1319 2323 1132 2323 1130 2323 1322 2324 1323 2324 1324 2324 1306 2325 1325 2325 1314 2325 1314 2326 1325 2326 1326 2326 1314 2327 1326 2327 1327 2327 1327 2328 1326 2328 1328 2328 1327 2329 1328 2329 1329 2329 1329 2330 1328 2330 1330 2330 1329 2331 1330 2331 1331 2331 1331 2332 1330 2332 1332 2332 1331 2333 1332 2333 1333 2333 1333 2334 1332 2334 1334 2334 1333 2335 1334 2335 1335 2335 1335 2336 1334 2336 1336 2336 1335 2337 1336 2337 1337 2337 1337 2338 1336 2338 1322 2338 1337 2339 1322 2339 1338 2339 1338 2340 1322 2340 1324 2340 1338 2341 1324 2341 1339 2341 1339 2342 1311 2342 1338 2342 1338 2343 1311 2343 1313 2343 1338 2344 1313 2344 1337 2344 1337 2345 1313 2345 1321 2345 1337 2346 1321 2346 1335 2346 1335 2347 1321 2347 1319 2347 1335 2348 1319 2348 1333 2348 1333 2349 1319 2349 1320 2349 1333 2350 1320 2350 1331 2350 1331 2351 1320 2351 1315 2351 1331 2352 1315 2352 1329 2352 1329 2353 1315 2353 1316 2353 1329 2354 1316 2354 1327 2354 1327 2355 1316 2355 1317 2355 1327 2356 1317 2356 1314 2356 1314 2357 1317 2357 1318 2357 1314 2358 1318 2358 1310 2358 1310 2359 1318 2359 1304 2359 1340 2360 1341 2360 1342 2360 1342 2361 1341 2361 1343 2361 1342 2362 1343 2362 1344 2362 1344 2363 1343 2363 1345 2363 1344 2364 1345 2364 1346 2364 1346 2365 1345 2365 1162 2365 1346 2366 1162 2366 1161 2366 1145 2367 1024 2367 1170 2367 1147 2368 1146 2368 1347 2368 1347 2369 1146 2369 1145 2369 1348 2370 1141 2370 1147 2370 1141 2371 1348 2371 1142 2371 1145 2372 1170 2372 1347 2372 1347 2373 1170 2373 1169 2373 1347 2374 1169 2374 1349 2374 1349 2375 1169 2375 1166 2375 1349 2376 1166 2376 1350 2376 1166 2377 1167 2377 1350 2377 1350 2378 1167 2378 1168 2378 1350 2379 1168 2379 1351 2379 1351 2380 1168 2380 1165 2380 1351 2381 1165 2381 1352 2381 1352 2382 1165 2382 1164 2382 1352 2383 1164 2383 1353 2383 1353 2384 1164 2384 1162 2384 1353 2385 1162 2385 1354 2385 1147 2386 1347 2386 1348 2386 1348 2387 1347 2387 1349 2387 1348 2388 1349 2388 1355 2388 1355 2389 1349 2389 1350 2389 1355 2390 1350 2390 1356 2390 1356 2391 1350 2391 1351 2391 1356 2392 1351 2392 1357 2392 1357 2393 1351 2393 1352 2393 1357 2394 1352 2394 1358 2394 1358 2395 1352 2395 1353 2395 1358 2396 1353 2396 1359 2396 1359 2397 1353 2397 1354 2397 1359 2398 1354 2398 1360 2398 1142 2399 1348 2399 1361 2399 1361 2400 1348 2400 1355 2400 1361 2401 1355 2401 1362 2401 1362 2402 1355 2402 1356 2402 1362 2403 1356 2403 1363 2403 1363 2404 1356 2404 1357 2404 1363 2405 1357 2405 1364 2405 1364 2406 1357 2406 1358 2406 1364 2407 1358 2407 1365 2407 1365 2408 1358 2408 1359 2408 1365 2409 1359 2409 1366 2409 1366 2410 1359 2410 1360 2410 1366 2411 1360 2411 1367 2411 1368 2412 1369 2412 1323 2412 1322 2413 1366 2413 1323 2413 1323 2414 1366 2414 1367 2414 1323 2415 1367 2415 1368 2415 1330 2416 1328 2416 1365 2416 1322 2417 1336 2417 1366 2417 1366 2418 1336 2418 1334 2418 1366 2419 1334 2419 1365 2419 1365 2420 1334 2420 1332 2420 1365 2421 1332 2421 1330 2421 1328 2422 1326 2422 1365 2422 1365 2423 1326 2423 1325 2423 1365 2424 1325 2424 1306 2424 1306 2425 1305 2425 1365 2425 1365 2426 1305 2426 1300 2426 1365 2427 1300 2427 1299 2427 1299 2428 1303 2428 1365 2428 1365 2429 1303 2429 1293 2429 1365 2430 1293 2430 1285 2430 1277 2431 1276 2431 1285 2431 1285 2432 1276 2432 1279 2432 1285 2433 1279 2433 1280 2433 1280 2434 1281 2434 1285 2434 1285 2435 1281 2435 1282 2435 1285 2436 1282 2436 1275 2436 1275 2437 1142 2437 1285 2437 1285 2438 1142 2438 1361 2438 1285 2439 1361 2439 1362 2439 1362 2440 1363 2440 1285 2440 1285 2441 1363 2441 1364 2441 1285 2442 1364 2442 1365 2442 1368 2443 1370 2443 1369 2443 1369 2444 1370 2444 1371 2444 1369 2445 1371 2445 1372 2445 1373 2446 1374 2446 1375 2446 1375 2447 1374 2447 1376 2447 1371 2448 1377 2448 1372 2448 1372 2449 1377 2449 1378 2449 1372 2450 1378 2450 1379 2450 1379 2451 1378 2451 1380 2451 1379 2452 1380 2452 1381 2452 1381 2453 1380 2453 1382 2453 1381 2454 1382 2454 1376 2454 1376 2455 1382 2455 1383 2455 1376 2456 1383 2456 1375 2456 1384 2457 1385 2457 1386 2457 1373 2458 1387 2458 1374 2458 1374 2459 1387 2459 1388 2459 1374 2460 1388 2460 1389 2460 1389 2461 1388 2461 1384 2461 1389 2462 1384 2462 1390 2462 1390 2463 1384 2463 1386 2463 1391 2464 1392 2464 1393 2464 1394 2465 1395 2465 1396 2465 1396 2466 1395 2466 1391 2466 1396 2467 1391 2467 1397 2467 1397 2468 1391 2468 1393 2468 1395 2469 1398 2469 1391 2469 1391 2470 1398 2470 1399 2470 1391 2471 1399 2471 1400 2471 1400 2472 1401 2472 1391 2472 1391 2473 1401 2473 1402 2473 1391 2474 1402 2474 1403 2474 1392 2475 1391 2475 1404 2475 1404 2476 1391 2476 1405 2476 1404 2477 1405 2477 1406 2477 1406 2478 1407 2478 1404 2478 1404 2479 1407 2479 1408 2479 1404 2480 1408 2480 1409 2480 1409 2481 1410 2481 1404 2481 1404 2482 1410 2482 1411 2482 1404 2483 1411 2483 1412 2483 1412 2484 1413 2484 1404 2484 1404 2485 1413 2485 1414 2485 1404 2486 1414 2486 1384 2486 1384 2487 1414 2487 1415 2487 1384 2488 1415 2488 1385 2488 1369 2489 1372 2489 1416 2489 1179 2490 1312 2490 1171 2490 1171 2491 1312 2491 1172 2491 1416 2492 1417 2492 1311 2492 1311 2493 1417 2493 1418 2493 1311 2494 1418 2494 1312 2494 1312 2495 1418 2495 1419 2495 1312 2496 1419 2496 1172 2496 1323 2497 1369 2497 1324 2497 1324 2498 1369 2498 1416 2498 1324 2499 1416 2499 1339 2499 1339 2500 1416 2500 1311 2500 1419 2501 1418 2501 1420 2501 1420 2502 1418 2502 1421 2502 1420 2503 1421 2503 1422 2503 1422 2504 1421 2504 1423 2504 1422 2505 1423 2505 1424 2505 1424 2506 1423 2506 1425 2506 1172 2507 1419 2507 1174 2507 1174 2508 1419 2508 1420 2508 1174 2509 1420 2509 1176 2509 1176 2510 1420 2510 1422 2510 1176 2511 1422 2511 1178 2511 1178 2512 1422 2512 1424 2512 1426 2513 1427 2513 1428 2513 1427 2514 1429 2514 1430 2514 1429 2515 1431 2515 1432 2515 1429 2516 1432 2516 1430 2516 1430 2517 1432 2517 1433 2517 1430 2518 1433 2518 1434 2518 1434 2519 1433 2519 1435 2519 1434 2520 1435 2520 1436 2520 1436 2521 1435 2521 1437 2521 1436 2522 1437 2522 1438 2522 1438 2523 1437 2523 1439 2523 1438 2524 1439 2524 1440 2524 1440 2525 1439 2525 1240 2525 1440 2526 1240 2526 1237 2526 1427 2527 1430 2527 1428 2527 1428 2528 1430 2528 1434 2528 1428 2529 1434 2529 1441 2529 1441 2530 1434 2530 1436 2530 1441 2531 1436 2531 1442 2531 1442 2532 1436 2532 1438 2532 1442 2533 1438 2533 1443 2533 1443 2534 1438 2534 1440 2534 1443 2535 1440 2535 1444 2535 1444 2536 1440 2536 1237 2536 1444 2537 1237 2537 1234 2537 1426 2538 1428 2538 1445 2538 1445 2539 1428 2539 1441 2539 1445 2540 1441 2540 1446 2540 1446 2541 1441 2541 1442 2541 1446 2542 1442 2542 1447 2542 1447 2543 1442 2543 1443 2543 1447 2544 1443 2544 1448 2544 1448 2545 1443 2545 1444 2545 1448 2546 1444 2546 1449 2546 1449 2547 1444 2547 1234 2547 1449 2548 1234 2548 1232 2548 1433 2549 1432 2549 1450 2549 1451 2550 1452 2550 1453 2550 1453 2551 1452 2551 1454 2551 1453 2552 1455 2552 1456 2552 1456 2553 1457 2553 1453 2553 1453 2554 1457 2554 1458 2554 1453 2555 1458 2555 1451 2555 1454 2556 1459 2556 1453 2556 1453 2549 1459 2549 1460 2549 1453 2557 1460 2557 1461 2557 1450 2549 1432 2549 1462 2549 1462 2558 1432 2558 1431 2558 1462 2549 1431 2549 1453 2549 1453 2549 1431 2549 1463 2549 1453 2559 1463 2559 1455 2559 1450 2560 1251 2560 1250 2560 1450 2561 1240 2561 1439 2561 1250 2549 1253 2549 1450 2549 1450 2562 1253 2562 1241 2562 1450 2563 1241 2563 1240 2563 1439 2564 1437 2564 1450 2564 1450 2565 1437 2565 1435 2565 1450 2566 1435 2566 1433 2566 1446 2567 1185 2567 1445 2567 1445 2568 1185 2568 1182 2568 1445 2569 1182 2569 1426 2569 1426 2570 1182 2570 1177 2570 1426 2571 1177 2571 1178 2571 1448 2572 1199 2572 1208 2572 1208 2573 1209 2573 1448 2573 1448 2574 1209 2574 1210 2574 1448 2575 1210 2575 1447 2575 1447 2576 1210 2576 1211 2576 1447 2577 1211 2577 1446 2577 1446 2578 1211 2578 1187 2578 1446 2579 1187 2579 1185 2579 1232 2580 1128 2580 1228 2580 1228 2581 1229 2581 1232 2581 1232 2582 1229 2582 1230 2582 1232 2583 1230 2583 1231 2583 1199 2584 1448 2584 1231 2584 1231 2585 1448 2585 1449 2585 1231 2586 1449 2586 1232 2586 1464 2587 1465 2587 1466 2587 1426 2587 1178 2587 1424 2587 1424 2587 1425 2587 1426 2587 1426 2588 1425 2588 1467 2588 1426 2587 1467 2587 1466 2587 1466 2587 1467 2587 1468 2587 1466 2589 1468 2589 1464 2589 1426 2590 1466 2590 1469 2590 1426 2590 1469 2590 1427 2590 1427 2591 1469 2591 1470 2591 1427 2591 1470 2591 1429 2591 1429 2592 1470 2592 1463 2592 1429 2593 1463 2593 1431 2593 1471 2594 1472 2594 1473 2594 1472 2595 1471 2595 1474 2595 1474 2596 1471 2596 1475 2596 1474 2597 1475 2597 1476 2597 1381 2598 1376 2598 1477 2598 1477 2599 1376 2599 1478 2599 1379 2600 1381 2600 1473 2600 1473 2601 1381 2601 1477 2601 1473 2602 1477 2602 1471 2602 1471 2603 1477 2603 1478 2603 1471 2604 1478 2604 1475 2604 1372 2605 1379 2605 1416 2605 1416 2606 1379 2606 1473 2606 1416 2607 1473 2607 1417 2607 1417 2608 1473 2608 1472 2608 1417 2609 1472 2609 1418 2609 1418 2610 1472 2610 1474 2610 1474 2611 1476 2611 1479 2611 1479 2612 1476 2612 1480 2612 1479 2613 1480 2613 1481 2613 1481 2614 1480 2614 1482 2614 1481 2615 1482 2615 1467 2615 1467 2616 1482 2616 1468 2616 1418 2617 1474 2617 1421 2617 1421 2618 1474 2618 1479 2618 1421 2619 1479 2619 1423 2619 1423 2620 1479 2620 1481 2620 1423 2621 1481 2621 1425 2621 1425 2622 1481 2622 1467 2622 1069 2623 1068 2623 1284 2623 1077 2624 1076 2624 1483 2624 1483 2625 1076 2625 1075 2625 1483 2626 1075 2626 1069 2626 1484 2627 1485 2627 1077 2627 1045 2628 1044 2628 1485 2628 1485 2629 1044 2629 1043 2629 1485 2630 1043 2630 1077 2630 1047 2631 1046 2631 955 2631 955 2632 1046 2632 1045 2632 955 2633 1045 2633 953 2633 1259 2634 1257 2634 958 2634 958 2635 1257 2635 955 2635 955 2636 1257 2636 1256 2636 955 2637 1256 2637 1047 2637 1486 2638 1263 2638 960 2638 960 2639 1263 2639 1262 2639 960 2640 1262 2640 958 2640 958 2641 1262 2641 1260 2641 958 2642 1260 2642 1259 2642 1487 2643 1488 2643 1489 2643 1489 2644 1488 2644 1490 2644 1489 2645 1490 2645 1491 2645 1492 2646 1493 2646 1494 2646 1494 2647 1493 2647 1495 2647 1494 2648 1495 2648 1496 2648 1496 2649 1495 2649 1497 2649 1498 2650 1499 2650 1500 2650 1498 2651 1500 2651 1501 2651 1501 2652 1500 2652 1502 2652 1501 2653 1502 2653 1503 2653 1503 2654 1502 2654 1504 2654 1503 2655 1504 2655 1505 2655 1506 2656 1507 2656 1504 2656 1504 2657 1507 2657 1508 2657 1504 2658 1508 2658 1505 2658 1509 2659 1510 2659 936 2659 936 2660 1510 2660 1511 2660 936 2661 1511 2661 934 2661 1512 2662 938 2662 1513 2662 1513 2663 938 2663 923 2663 1513 2664 923 2664 1514 2664 1514 2665 923 2665 1515 2665 1512 2666 1516 2666 938 2666 938 2667 1516 2667 1517 2667 938 2668 1517 2668 936 2668 936 2669 1517 2669 1518 2669 936 2670 1518 2670 1509 2670 1519 2671 1520 2671 1521 2671 1521 2672 1520 2672 1522 2672 1522 2673 1520 2673 1523 2673 1523 2674 1520 2674 1524 2674 1523 2675 1524 2675 1525 2675 1526 2676 1527 2676 1528 2676 1528 2677 1527 2677 1529 2677 1528 2678 1529 2678 1525 2678 1530 2679 1531 2679 1532 2679 1526 2680 1528 2680 1533 2680 1533 2681 1528 2681 1534 2681 1533 2682 1534 2682 1535 2682 1535 2683 1534 2683 1536 2683 1535 2684 1536 2684 1537 2684 1537 2685 1536 2685 1538 2685 1537 2686 1538 2686 1539 2686 1539 2687 1538 2687 1540 2687 1539 2688 1540 2688 1541 2688 1525 2689 1524 2689 1528 2689 1528 2690 1524 2690 1542 2690 1528 2691 1542 2691 1534 2691 1534 2692 1542 2692 1543 2692 1534 2693 1543 2693 1536 2693 1536 2694 1543 2694 1530 2694 1536 2695 1530 2695 1538 2695 1538 2696 1530 2696 1532 2696 1538 2697 1532 2697 1540 2697 1515 2698 923 2698 1519 2698 1519 2699 923 2699 925 2699 1519 2700 925 2700 1520 2700 1520 2701 925 2701 918 2701 1520 2702 918 2702 1524 2702 1524 2703 918 2703 917 2703 1524 2704 917 2704 1542 2704 1542 2705 917 2705 910 2705 1542 2706 910 2706 1543 2706 1543 2707 910 2707 912 2707 1543 2708 912 2708 1530 2708 1530 2709 912 2709 914 2709 1530 2710 914 2710 1531 2710 1491 2711 1490 2711 1544 2711 1544 2712 1490 2712 1545 2712 1544 2713 1545 2713 1546 2713 1546 2714 1545 2714 1547 2714 1546 2715 1547 2715 1497 2715 1497 2716 1547 2716 1548 2716 1497 2717 1548 2717 1496 2717 1496 2718 1548 2718 1549 2718 1496 2719 1549 2719 1494 2719 1494 2720 1549 2720 1499 2720 1494 2721 1499 2721 1492 2721 1492 2722 1499 2722 1498 2722 1492 2723 1498 2723 1493 2723 1486 2724 960 2724 1487 2724 1487 2725 960 2725 962 2725 1487 2726 962 2726 1488 2726 1488 2727 962 2727 964 2727 1488 2728 964 2728 1490 2728 1490 2729 964 2729 966 2729 1490 2730 966 2730 1545 2730 1545 2731 966 2731 949 2731 1545 2732 949 2732 1547 2732 1547 2733 949 2733 947 2733 1547 2734 947 2734 1548 2734 1548 2735 947 2735 905 2735 1548 2736 905 2736 1549 2736 1549 2737 905 2737 943 2737 1549 2738 943 2738 1499 2738 1499 2739 943 2739 928 2739 1499 2740 928 2740 1500 2740 1500 2741 928 2741 930 2741 1500 2742 930 2742 1502 2742 1502 2743 930 2743 932 2743 1502 2744 932 2744 1504 2744 1504 2745 932 2745 934 2745 1504 2746 934 2746 1506 2746 1506 2747 934 2747 1511 2747 1506 2748 1511 2748 1507 2748 1069 2749 1284 2749 1483 2749 1483 2750 1284 2750 1283 2750 1483 2751 1283 2751 1550 2751 1550 2752 1283 2752 1290 2752 1550 2753 1290 2753 1551 2753 1551 2754 1290 2754 1291 2754 1551 2755 1291 2755 1552 2755 1291 2756 1033 2756 1552 2756 1552 2757 1033 2757 1031 2757 1552 2758 1031 2758 1029 2758 1077 2759 1483 2759 1484 2759 1484 2760 1483 2760 1550 2760 1484 2761 1550 2761 1553 2761 1553 2762 1550 2762 1551 2762 1553 2763 1551 2763 1554 2763 1554 2764 1551 2764 1552 2764 1554 2765 1552 2765 1555 2765 1555 2766 1552 2766 1029 2766 1555 2767 1029 2767 1037 2767 1045 2768 1485 2768 953 2768 953 2769 1485 2769 1484 2769 953 2770 1484 2770 951 2770 951 2771 1484 2771 1553 2771 951 2772 1553 2772 971 2772 971 2773 1553 2773 1554 2773 971 2774 1554 2774 906 2774 906 2775 1554 2775 1555 2775 906 2776 1555 2776 907 2776 907 2777 1555 2777 1037 2777 907 2778 1037 2778 900 2778 1267 2779 1556 2779 1059 2779 1059 2780 1556 2780 1149 2780 1557 2781 1156 2781 1154 2781 1489 2782 1491 2782 1558 2782 1558 2783 1491 2783 1559 2783 1487 2784 1489 2784 1560 2784 1560 2785 1489 2785 1558 2785 1560 2786 1558 2786 1561 2786 1561 2787 1558 2787 1559 2787 1561 2788 1559 2788 1562 2788 1557 2789 1154 2789 1563 2789 1563 2790 1154 2790 1564 2790 1563 2791 1564 2791 1565 2791 1565 2792 1564 2792 1566 2792 1565 2793 1566 2793 1567 2793 1486 2794 1487 2794 1567 2794 1567 2795 1487 2795 1560 2795 1567 2796 1560 2796 1565 2796 1565 2797 1560 2797 1561 2797 1565 2798 1561 2798 1563 2798 1563 2799 1561 2799 1562 2799 1563 2800 1562 2800 1557 2800 1263 2801 1486 2801 1264 2801 1264 2802 1486 2802 1567 2802 1264 2803 1567 2803 1267 2803 1267 2804 1567 2804 1566 2804 1267 2805 1566 2805 1556 2805 1556 2806 1566 2806 1564 2806 1556 2807 1564 2807 1149 2807 1149 2808 1564 2808 1154 2808 1568 2809 1569 2809 1570 2809 1571 2810 1163 2810 1159 2810 1157 2811 1156 2811 1572 2811 1573 2812 1568 2812 1572 2812 1572 2813 1568 2813 1570 2813 1572 2814 1570 2814 1157 2814 1157 2815 1570 2815 1158 2815 1569 2816 1574 2816 1570 2816 1570 2817 1574 2817 1571 2817 1570 2818 1571 2818 1158 2818 1158 2819 1571 2819 1159 2819 1161 2820 1163 2820 1575 2820 1575 2821 1163 2821 1571 2821 1575 2822 1571 2822 1576 2822 1576 2823 1571 2823 1574 2823 1577 2824 1578 2824 1579 2824 1344 2825 1346 2825 1580 2825 1580 2826 1346 2826 1161 2826 1573 2827 1581 2827 1568 2827 1568 2828 1581 2828 1582 2828 1568 2829 1582 2829 1569 2829 1569 2830 1582 2830 1583 2830 1161 2831 1575 2831 1580 2831 1580 2832 1575 2832 1576 2832 1580 2833 1576 2833 1583 2833 1583 2834 1576 2834 1574 2834 1583 2835 1574 2835 1569 2835 1342 2836 1344 2836 1584 2836 1584 2837 1344 2837 1580 2837 1584 2838 1580 2838 1585 2838 1585 2839 1580 2839 1583 2839 1585 2840 1583 2840 1579 2840 1579 2841 1583 2841 1582 2841 1579 2842 1582 2842 1577 2842 1577 2843 1582 2843 1581 2843 1340 2844 1342 2844 1586 2844 1586 2845 1342 2845 1584 2845 1586 2846 1584 2846 1587 2846 1587 2847 1584 2847 1585 2847 1587 2848 1585 2848 1588 2848 1588 2849 1585 2849 1579 2849 1588 2850 1579 2850 1589 2850 1589 2851 1579 2851 1578 2851 1370 2852 1368 2852 1590 2852 1591 2853 1388 2853 1387 2853 1592 2854 1591 2854 1593 2854 1594 2855 1595 2855 1596 2855 1596 2856 1595 2856 1597 2856 1596 2857 1597 2857 1592 2857 1598 2858 1599 2858 1600 2858 1600 2859 1599 2859 1601 2859 1600 2860 1601 2860 1594 2860 1594 2861 1601 2861 1602 2861 1594 2862 1602 2862 1595 2862 1603 2863 1604 2863 1598 2863 1598 2864 1604 2864 1605 2864 1598 2865 1605 2865 1599 2865 1598 2866 1606 2866 1603 2866 1603 2867 1606 2867 1607 2867 1603 2868 1607 2868 1608 2868 1608 2869 1607 2869 1609 2869 1608 2870 1609 2870 1610 2870 1610 2871 1609 2871 1611 2871 1610 2872 1611 2872 1612 2872 1592 2873 1593 2873 1596 2873 1596 2874 1593 2874 1613 2874 1596 2875 1613 2875 1594 2875 1594 2876 1613 2876 1614 2876 1594 2877 1614 2877 1600 2877 1600 2878 1614 2878 1615 2878 1600 2879 1615 2879 1598 2879 1598 2880 1615 2880 1616 2880 1598 2881 1616 2881 1606 2881 1606 2882 1616 2882 1617 2882 1606 2883 1617 2883 1607 2883 1607 2884 1617 2884 1618 2884 1607 2885 1618 2885 1609 2885 1609 2886 1618 2886 1619 2886 1609 2887 1619 2887 1611 2887 1611 2888 1619 2888 1620 2888 1611 2889 1620 2889 1621 2889 1370 2890 1590 2890 1371 2890 1345 2891 1343 2891 1621 2891 1621 2892 1343 2892 1341 2892 1621 2893 1341 2893 1611 2893 1611 2894 1341 2894 1340 2894 1611 2895 1340 2895 1612 2895 1354 2896 1622 2896 1360 2896 1360 2897 1622 2897 1590 2897 1360 2898 1590 2898 1367 2898 1367 2899 1590 2899 1368 2899 1591 2900 1387 2900 1593 2900 1593 2901 1387 2901 1373 2901 1593 2902 1373 2902 1613 2902 1613 2903 1373 2903 1375 2903 1613 2904 1375 2904 1614 2904 1614 2905 1375 2905 1383 2905 1614 2906 1383 2906 1615 2906 1615 2907 1383 2907 1382 2907 1615 2908 1382 2908 1616 2908 1616 2909 1382 2909 1380 2909 1616 2910 1380 2910 1617 2910 1617 2911 1380 2911 1378 2911 1617 2912 1378 2912 1618 2912 1618 2913 1378 2913 1377 2913 1618 2914 1377 2914 1619 2914 1619 2915 1377 2915 1371 2915 1619 2916 1371 2916 1620 2916 1620 2917 1371 2917 1590 2917 1620 2918 1590 2918 1621 2918 1621 2919 1590 2919 1622 2919 1621 2920 1622 2920 1345 2920 1345 2921 1622 2921 1354 2921 1345 2922 1354 2922 1162 2922 1623 2923 1589 2923 1624 2923 1625 2924 1626 2924 1627 2924 1627 2925 1626 2925 1628 2925 1627 2926 1628 2926 1624 2926 1624 2927 1628 2927 1629 2927 1624 2928 1629 2928 1623 2928 1630 2929 1586 2929 1631 2929 1631 2930 1586 2930 1587 2930 1631 2931 1587 2931 1632 2931 1632 2932 1587 2932 1588 2932 1632 2933 1588 2933 1623 2933 1623 2934 1588 2934 1589 2934 1623 2935 1629 2935 1632 2935 1632 2936 1629 2936 1633 2936 1632 2937 1633 2937 1631 2937 1631 2938 1633 2938 1634 2938 1631 2939 1634 2939 1630 2939 1630 2940 1634 2940 1635 2940 1608 2941 1610 2941 1635 2941 1635 2942 1610 2942 1612 2942 1635 2943 1612 2943 1630 2943 1630 2944 1612 2944 1340 2944 1630 2945 1340 2945 1586 2945 1628 2946 1626 2946 1636 2946 1636 2947 1626 2947 1637 2947 1636 2948 1637 2948 1638 2948 1638 2949 1637 2949 1639 2949 1638 2950 1639 2950 1640 2950 1640 2951 1639 2951 1641 2951 1642 2952 1641 2952 1643 2952 1643 2953 1641 2953 1639 2953 1643 2954 1639 2954 1644 2954 1644 2955 1639 2955 1637 2955 1644 2956 1637 2956 1625 2956 1625 2957 1637 2957 1626 2957 1629 2958 1628 2958 1633 2958 1633 2959 1628 2959 1636 2959 1633 2960 1636 2960 1634 2960 1634 2961 1636 2961 1638 2961 1634 2962 1638 2962 1635 2962 1635 2963 1638 2963 1640 2963 1635 2964 1640 2964 1608 2964 1608 2965 1640 2965 1641 2965 1608 2966 1641 2966 1603 2966 1603 2967 1641 2967 1642 2967 1603 2968 1642 2968 1604 2968 1562 2969 1559 2969 1645 2969 1572 2970 1156 2970 1557 2970 1573 2971 1646 2971 1581 2971 1581 2972 1646 2972 1647 2972 1648 2973 1649 2973 1650 2973 1650 2974 1649 2974 1625 2974 1650 2975 1625 2975 1651 2975 1651 2976 1625 2976 1652 2976 1653 2977 1654 2977 1655 2977 1655 2978 1654 2978 1656 2978 1655 2979 1656 2979 1648 2979 1648 2980 1656 2980 1657 2980 1648 2981 1657 2981 1649 2981 1658 2982 1659 2982 1660 2982 1625 2983 1627 2983 1652 2983 1652 2984 1627 2984 1624 2984 1652 2985 1624 2985 1661 2985 1661 2986 1624 2986 1589 2986 1661 2987 1589 2987 1662 2987 1662 2988 1589 2988 1578 2988 1662 2989 1578 2989 1647 2989 1647 2990 1578 2990 1577 2990 1647 2991 1577 2991 1581 2991 1646 2992 1663 2992 1647 2992 1647 2993 1663 2993 1664 2993 1647 2994 1664 2994 1662 2994 1662 2995 1664 2995 1665 2995 1662 2996 1665 2996 1661 2996 1661 2997 1665 2997 1666 2997 1661 2998 1666 2998 1652 2998 1652 2999 1666 2999 1667 2999 1652 3000 1667 3000 1651 3000 1651 3001 1667 3001 1668 3001 1651 3002 1668 3002 1650 3002 1650 3003 1668 3003 1669 3003 1650 3004 1669 3004 1648 3004 1648 3005 1669 3005 1670 3005 1648 3006 1670 3006 1655 3006 1655 3007 1670 3007 1660 3007 1655 3008 1660 3008 1653 3008 1653 3009 1660 3009 1659 3009 1573 3010 1572 3010 1646 3010 1646 3011 1572 3011 1557 3011 1646 3012 1557 3012 1663 3012 1663 3013 1557 3013 1671 3013 1663 3014 1671 3014 1664 3014 1664 3015 1671 3015 1672 3015 1664 3016 1672 3016 1665 3016 1665 3017 1672 3017 1673 3017 1665 3018 1673 3018 1666 3018 1666 3019 1673 3019 1674 3019 1666 3020 1674 3020 1667 3020 1667 3021 1674 3021 1675 3021 1667 3022 1675 3022 1668 3022 1668 3023 1675 3023 1676 3023 1668 3024 1676 3024 1669 3024 1669 3025 1676 3025 1677 3025 1669 3026 1677 3026 1670 3026 1670 3027 1677 3027 1678 3027 1670 3028 1678 3028 1660 3028 1660 3029 1678 3029 1679 3029 1660 3030 1679 3030 1658 3030 1658 3031 1679 3031 1680 3031 1557 3032 1562 3032 1671 3032 1671 3033 1562 3033 1645 3033 1671 3034 1645 3034 1672 3034 1672 3035 1645 3035 1681 3035 1672 3036 1681 3036 1673 3036 1673 3037 1681 3037 1682 3037 1673 3038 1682 3038 1674 3038 1674 3039 1682 3039 1683 3039 1674 3040 1683 3040 1675 3040 1675 3041 1683 3041 1684 3041 1675 3042 1684 3042 1676 3042 1676 3043 1684 3043 1685 3043 1676 3044 1685 3044 1677 3044 1677 3045 1685 3045 1686 3045 1677 3046 1686 3046 1678 3046 1678 3047 1686 3047 1687 3047 1678 3048 1687 3048 1679 3048 1679 3049 1687 3049 1688 3049 1679 3050 1688 3050 1680 3050 1680 3051 1688 3051 1508 3051 1508 3052 1688 3052 1505 3052 1505 3053 1688 3053 1687 3053 1505 3054 1687 3054 1503 3054 1503 3055 1687 3055 1686 3055 1503 3056 1686 3056 1501 3056 1501 3057 1686 3057 1685 3057 1501 3058 1685 3058 1498 3058 1498 3059 1685 3059 1684 3059 1498 3060 1684 3060 1493 3060 1493 3061 1684 3061 1683 3061 1493 3062 1683 3062 1495 3062 1495 3063 1683 3063 1682 3063 1495 3064 1682 3064 1497 3064 1497 3065 1682 3065 1681 3065 1497 3066 1681 3066 1546 3066 1546 3067 1681 3067 1645 3067 1546 3068 1645 3068 1544 3068 1544 3069 1645 3069 1559 3069 1544 3070 1559 3070 1491 3070 1689 3071 1690 3071 1691 3071 1691 3072 1690 3072 1692 3072 1691 3073 1692 3073 1693 3073 1450 3074 1462 3074 1694 3074 1695 3075 1693 3075 1694 3075 1694 3076 1693 3076 1692 3076 1694 3077 1692 3077 1450 3077 1450 3078 1692 3078 1690 3078 1450 3079 1690 3079 1251 3079 1696 3080 1697 3080 1698 3080 1252 3081 1251 3081 1698 3081 1698 3082 1251 3082 1690 3082 1698 3083 1690 3083 1696 3083 1696 3084 1690 3084 1689 3084 1699 3085 1700 3085 1701 3085 1702 3086 1703 3086 1701 3086 1701 3087 1703 3087 1704 3087 1701 3088 1704 3088 1699 3088 1705 3089 1706 3089 1707 3089 1707 3090 1706 3090 1708 3090 1707 3091 1708 3091 1709 3091 1709 3092 1708 3092 1710 3092 1709 3093 1710 3093 1702 3093 1702 3094 1710 3094 1711 3094 1702 3095 1711 3095 1703 3095 1252 3096 1698 3096 1707 3096 1707 3097 1698 3097 1697 3097 1707 3098 1697 3098 1705 3098 1252 3099 1707 3099 1249 3099 1249 3100 1707 3100 1709 3100 1249 3101 1709 3101 1247 3101 1247 3102 1709 3102 1702 3102 1247 3103 1702 3103 1244 3103 1244 3104 1702 3104 1701 3104 1244 3105 1701 3105 1243 3105 1243 3106 1701 3106 1700 3106 1243 3107 1700 3107 1035 3107 892 3108 1036 3108 1712 3108 1712 3109 1036 3109 1713 3109 1713 3110 1036 3110 1035 3110 1713 3111 1035 3111 1714 3111 1714 3112 1035 3112 1700 3112 1714 3113 1700 3113 1699 3113 1715 3114 1716 3114 1004 3114 1693 3115 1695 3115 1716 3115 1004 3116 1003 3116 1715 3116 1715 3117 1003 3117 1002 3117 1715 3118 1002 3118 1717 3118 1717 3119 1002 3119 1001 3119 1717 3120 1001 3120 1718 3120 1716 3121 1715 3121 1693 3121 1693 3122 1715 3122 1717 3122 1693 3123 1717 3123 1691 3123 1691 3124 1717 3124 1718 3124 1691 3125 1718 3125 1689 3125 1001 3126 978 3126 1718 3126 1718 3127 978 3127 1719 3127 1718 3128 1719 3128 1689 3128 1689 3129 1719 3129 1696 3129 978 3130 986 3130 1719 3130 1719 3131 986 3131 1720 3131 1719 3132 1720 3132 1696 3132 1696 3133 1720 3133 1697 3133 1720 3134 986 3134 984 3134 1697 3135 1720 3135 1721 3135 1697 3136 1721 3136 1705 3136 1705 3137 1721 3137 1722 3137 1705 3138 1722 3138 1706 3138 1706 3139 1722 3139 1723 3139 1706 3140 1723 3140 1708 3140 1708 3141 1723 3141 1724 3141 1708 3142 1724 3142 1710 3142 1720 3143 984 3143 1721 3143 1721 3144 984 3144 982 3144 1721 3145 982 3145 1722 3145 1722 3146 982 3146 981 3146 1722 3147 981 3147 1723 3147 1723 3148 981 3148 989 3148 1723 3149 989 3149 1724 3149 1724 3150 989 3150 990 3150 1724 3151 990 3151 1725 3151 1725 3152 990 3152 993 3152 1725 3153 993 3153 1726 3153 1726 3154 993 3154 994 3154 1726 3155 994 3155 1727 3155 1710 3156 1724 3156 1711 3156 1711 3157 1724 3157 1725 3157 1711 3158 1725 3158 1703 3158 1703 3159 1725 3159 1726 3159 1703 3160 1726 3160 1704 3160 1704 3161 1726 3161 1727 3161 1704 3162 1727 3162 1699 3162 1714 3163 1699 3163 1727 3163 892 3164 1712 3164 995 3164 995 3165 1712 3165 1713 3165 995 3166 1713 3166 999 3166 999 3167 1713 3167 1714 3167 999 3168 1714 3168 998 3168 998 3169 1714 3169 1727 3169 998 3170 1727 3170 994 3170 1728 3171 1729 3171 1730 3171 1731 3172 896 3172 895 3172 78 3173 77 3173 1732 3173 1732 3174 77 3174 1733 3174 1731 3175 895 3175 1728 3175 1728 3176 895 3176 894 3176 1728 3177 894 3177 1729 3177 79 3178 78 3178 1730 3178 1730 3179 78 3179 1732 3179 1730 3180 1732 3180 1728 3180 1728 3181 1732 3181 1733 3181 1728 3182 1733 3182 1731 3182 80 3183 79 3183 1734 3183 1734 3184 79 3184 1730 3184 1734 3185 1730 3185 1735 3185 1735 3186 1730 3186 1729 3186 1735 3187 1729 3187 893 3187 893 3188 1729 3188 894 3188 1734 3189 1735 3189 1736 3189 72 3190 1000 3190 49 3190 80 3191 1737 3191 73 3191 73 3192 1737 3192 1738 3192 73 3193 1738 3193 74 3193 74 3194 1738 3194 1739 3194 74 3195 1739 3195 75 3195 75 3196 1739 3196 1740 3196 75 3197 1740 3197 76 3197 76 3198 1740 3198 1741 3198 76 3199 1741 3199 46 3199 46 3200 1741 3200 1742 3200 46 3201 1742 3201 47 3201 47 3202 1742 3202 1743 3202 47 3203 1743 3203 69 3203 69 3204 1743 3204 1744 3204 69 3205 1744 3205 68 3205 68 3206 1744 3206 1745 3206 68 3207 1745 3207 66 3207 66 3208 1745 3208 1746 3208 66 3209 1746 3209 67 3209 67 3210 1746 3210 70 3210 80 3211 1734 3211 1737 3211 1737 3212 1734 3212 1736 3212 1737 3213 1736 3213 1738 3213 1738 3214 1736 3214 1747 3214 1738 3215 1747 3215 1739 3215 1739 3216 1747 3216 1748 3216 1739 3217 1748 3217 1740 3217 1740 3218 1748 3218 1749 3218 1740 3219 1749 3219 1741 3219 1741 3220 1749 3220 1750 3220 1741 3221 1750 3221 1742 3221 1742 3222 1750 3222 1751 3222 1742 3223 1751 3223 1743 3223 1743 3224 1751 3224 1752 3224 1743 3225 1752 3225 1744 3225 1744 3226 1752 3226 1753 3226 1744 3227 1753 3227 1745 3227 1745 3228 1753 3228 1754 3228 1745 3229 1754 3229 1746 3229 1746 3230 1754 3230 1755 3230 1746 3231 1755 3231 70 3231 70 3232 1755 3232 975 3232 70 3233 975 3233 71 3233 71 3234 975 3234 980 3234 71 3235 980 3235 72 3235 72 3236 980 3236 979 3236 1000 3237 72 3237 979 3237 975 3238 1755 3238 976 3238 976 3239 1755 3239 1754 3239 976 3240 1754 3240 977 3240 977 3241 1754 3241 1753 3241 977 3242 1753 3242 985 3242 985 3243 1753 3243 1752 3243 985 3244 1752 3244 983 3244 983 3245 1752 3245 1751 3245 983 3246 1751 3246 987 3246 987 3247 1751 3247 1750 3247 987 3248 1750 3248 988 3248 988 3249 1750 3249 1749 3249 988 3250 1749 3250 991 3250 991 3251 1749 3251 1748 3251 991 3252 1748 3252 992 3252 992 3253 1748 3253 1747 3253 992 3254 1747 3254 996 3254 996 3255 1747 3255 1736 3255 996 3256 1736 3256 997 3256 997 3257 1736 3257 1735 3257 997 3258 1735 3258 893 3258 904 3259 903 3259 1756 3259 904 3260 1756 3260 1757 3260 1757 3261 1756 3261 1758 3261 1757 3262 1758 3262 1759 3262 1759 3263 1758 3263 3 3263 1759 3264 3 3264 5 3264 0 3265 3 3265 1760 3265 1760 3266 3 3266 1758 3266 1760 3267 1758 3267 1761 3267 1761 3268 1758 3268 1756 3268 1761 3269 1756 3269 946 3269 946 3270 1756 3270 903 3270 1762 3271 1763 3271 1764 3271 970 3272 969 3272 1765 3272 1765 3273 969 3273 908 3273 1766 3274 1767 3274 1768 3274 1768 3275 1767 3275 86 3275 1768 3276 86 3276 84 3276 970 3277 1765 3277 972 3277 972 3278 1765 3278 1769 3278 972 3279 1769 3279 1770 3279 84 3280 82 3280 1768 3280 1768 3281 82 3281 90 3281 1768 3282 90 3282 1771 3282 1771 3283 90 3283 92 3283 1771 3284 92 3284 1772 3284 1772 3285 92 3285 94 3285 1772 3286 94 3286 1773 3286 1773 3287 94 3287 96 3287 1773 3288 96 3288 1774 3288 908 3289 1766 3289 1765 3289 1765 3290 1766 3290 1768 3290 1765 3291 1768 3291 1769 3291 1769 3292 1768 3292 1771 3292 1769 3293 1771 3293 1770 3293 1770 3294 1771 3294 1772 3294 1770 3295 1772 3295 1775 3295 1775 3296 1772 3296 1773 3296 1775 3297 1773 3297 1776 3297 1776 3298 1773 3298 1774 3298 1776 3299 1774 3299 1777 3299 1777 3300 954 3300 1776 3300 1776 3301 954 3301 952 3301 1776 3302 952 3302 1775 3302 1775 3303 952 3303 974 3303 1775 3304 974 3304 1770 3304 1770 3305 974 3305 973 3305 1770 3306 973 3306 972 3306 1762 3307 98 3307 101 3307 959 3308 957 3308 1777 3308 1777 3309 957 3309 956 3309 1777 3310 956 3310 954 3310 1762 3311 101 3311 1763 3311 1763 3312 101 3312 103 3312 1763 3313 103 3313 1778 3313 1778 3314 103 3314 106 3314 1778 3315 106 3315 1779 3315 1779 3316 106 3316 108 3316 1779 3317 108 3317 1780 3317 1780 3318 108 3318 111 3318 1780 3319 111 3319 1781 3319 1764 3320 1763 3320 1782 3320 1782 3321 1763 3321 1778 3321 1782 3322 1778 3322 1783 3322 1783 3323 1778 3323 1779 3323 1783 3324 1779 3324 1784 3324 1784 3325 1779 3325 1780 3325 1784 3326 1780 3326 1785 3326 1785 3327 1780 3327 1781 3327 1785 3328 1781 3328 1786 3328 96 3329 98 3329 1774 3329 1774 3330 98 3330 1762 3330 1774 3331 1762 3331 1777 3331 1777 3332 1762 3332 1764 3332 1777 3333 1764 3333 959 3333 959 3334 1764 3334 1782 3334 959 3335 1782 3335 961 3335 961 3336 1782 3336 1783 3336 961 3337 1783 3337 963 3337 963 3338 1783 3338 1784 3338 963 3339 1784 3339 965 3339 965 3340 1784 3340 1785 3340 965 3341 1785 3341 967 3341 967 3342 1785 3342 1786 3342 948 3343 950 3343 1786 3343 1786 3344 950 3344 968 3344 1786 3345 968 3345 967 3345 1760 3346 1787 3346 0 3346 0 3347 1787 3347 115 3347 113 3348 115 3348 1788 3348 1788 3349 115 3349 1787 3349 1788 3350 1787 3350 1789 3350 1789 3351 1787 3351 1760 3351 1789 3352 1760 3352 1761 3352 111 3353 113 3353 1781 3353 1781 3354 113 3354 1788 3354 1781 3355 1788 3355 1786 3355 1786 3356 1788 3356 1789 3356 1786 3357 1789 3357 948 3357 948 3358 1789 3358 1761 3358 948 3359 1761 3359 946 3359 1790 3360 131 3360 86 3360 86 3361 1767 3361 1790 3361 1790 3362 1767 3362 1766 3362 1790 3363 1766 3363 1791 3363 1791 3364 1766 3364 908 3364 1791 3365 908 3365 909 3365 909 3366 902 3366 1791 3366 1791 3367 902 3367 1792 3367 1791 3368 1792 3368 1790 3368 1790 3369 1792 3369 1793 3369 1790 3370 1793 3370 131 3370 131 3371 1793 3371 129 3371 1794 3372 901 3372 899 3372 125 3373 127 3373 1795 3373 1796 3374 117 3374 119 3374 1796 3375 1797 3375 1798 3375 1798 3376 1797 3376 1799 3376 1798 3377 1799 3377 898 3377 125 3378 1795 3378 123 3378 1796 3379 119 3379 1797 3379 1797 3380 119 3380 121 3380 1797 3381 121 3381 123 3381 123 3382 1795 3382 1797 3382 1797 3383 1795 3383 1794 3383 1797 3384 1794 3384 1799 3384 1799 3385 1794 3385 899 3385 1799 3386 899 3386 898 3386 902 3387 901 3387 1792 3387 1792 3388 901 3388 1794 3388 1792 3389 1794 3389 1793 3389 1793 3390 1794 3390 1795 3390 1793 3391 1795 3391 129 3391 129 3392 1795 3392 127 3392 898 3393 897 3393 1800 3393 898 3394 1800 3394 1798 3394 1798 3395 1800 3395 1801 3395 1798 3396 1801 3396 1796 3396 1796 3397 1801 3397 132 3397 1796 3398 132 3398 117 3398 897 3399 896 3399 1800 3399 1800 3400 896 3400 1731 3400 1800 3401 1731 3401 1801 3401 1801 3402 1731 3402 1733 3402 1801 3403 1733 3403 132 3403 132 3404 1733 3404 77 3404 5 3405 4 3405 1802 3405 5 3406 1802 3406 1803 3406 1803 3407 1802 3407 1804 3407 1803 3408 1804 3408 1805 3408 1806 3409 20 3409 17 3409 15 3410 1807 3410 16 3410 16 3411 1807 3411 1808 3411 16 3412 1808 3412 17 3412 1806 3413 17 3413 1809 3413 1810 3414 1811 3414 1808 3414 1808 3415 1811 3415 1812 3415 1812 3416 1813 3416 1808 3416 1808 3417 1813 3417 1814 3417 1808 3418 1814 3418 17 3418 17 3419 1814 3419 1815 3419 17 3420 1815 3420 1809 3420 1816 3421 1817 3421 1810 3421 1818 3422 1819 3422 1820 3422 1820 3423 1819 3423 1810 3423 1820 3424 1810 3424 1821 3424 1816 3425 1810 3425 1822 3425 1817 3426 1823 3426 1810 3426 1810 3427 1823 3427 1824 3427 1810 3428 1824 3428 1825 3428 1825 3429 1826 3429 1810 3429 1810 3430 1826 3430 1827 3430 1810 3431 1827 3431 1828 3431 1829 3432 1830 3432 1810 3432 1810 3433 1830 3433 1831 3433 1810 3434 1831 3434 1821 3434 1828 3435 1832 3435 1810 3435 1810 3436 1832 3436 1833 3436 1810 3437 1833 3437 1829 3437 1834 3438 1835 3438 1820 3438 1820 3439 1835 3439 1836 3439 1820 3440 1836 3440 1818 3440 1808 3441 1837 3441 1810 3441 1810 3442 1837 3442 1838 3442 1810 3443 1838 3443 1839 3443 1839 3444 1840 3444 1810 3444 1810 3445 1840 3445 1841 3445 1810 3446 1841 3446 1822 3446 1842 3447 1843 3447 1844 3447 1845 3448 1846 3448 1847 3448 1848 3449 1837 3449 1808 3449 1849 3450 1850 3450 1851 3450 1851 3451 1850 3451 1847 3451 1851 3452 1847 3452 1852 3452 1853 3453 1808 3453 1854 3453 1854 3454 1808 3454 1807 3454 1854 3455 1807 3455 1855 3455 1855 3456 1807 3456 1856 3456 1853 3457 1857 3457 1808 3457 1808 3458 1857 3458 1858 3458 1808 3459 1858 3459 1859 3459 1859 3460 1860 3460 1808 3460 1808 3461 1860 3461 1861 3461 1808 3462 1861 3462 1847 3462 1847 3463 1861 3463 1862 3463 1847 3464 1862 3464 1852 3464 1847 3465 1846 3465 1808 3465 1808 3466 1846 3466 1863 3466 1808 3467 1863 3467 1848 3467 1864 3468 1865 3468 1866 3468 1864 3469 1866 3469 1850 3469 1866 3470 1867 3470 1850 3470 1850 3471 1867 3471 1868 3471 1850 3472 1868 3472 1847 3472 1847 3473 1868 3473 1869 3473 1847 3474 1869 3474 1845 3474 1844 3475 1870 3475 1871 3475 1844 3476 1871 3476 1864 3476 1864 3477 1871 3477 1872 3477 1864 3478 1872 3478 1865 3478 1849 3479 1873 3479 1850 3479 1850 3480 1873 3480 1874 3480 1850 3481 1874 3481 1864 3481 1864 3482 1874 3482 1875 3482 1864 3483 1875 3483 1844 3483 1844 3484 1875 3484 1876 3484 1844 3485 1876 3485 1842 3485 1804 3486 1877 3486 1805 3486 1805 3487 1877 3487 1878 3487 1877 3488 1879 3488 1878 3488 1878 3489 1879 3489 1880 3489 1878 3490 1880 3490 1881 3490 1881 3491 1880 3491 1882 3491 1881 3492 1882 3492 1883 3492 1883 3493 1882 3493 1884 3493 1883 3494 1884 3494 1885 3494 1884 3495 1886 3495 1885 3495 1885 3496 1886 3496 1887 3496 1885 3497 1887 3497 1888 3497 1888 3498 1887 3498 1889 3498 1888 3499 1889 3499 1890 3499 1889 3500 1891 3500 1890 3500 1890 3501 1891 3501 1892 3501 1890 3502 1892 3502 1893 3502 1893 3503 1892 3503 1894 3503 1893 3504 1894 3504 1895 3504 1894 3505 1896 3505 1895 3505 1895 3506 1896 3506 1897 3506 1895 3507 1897 3507 1898 3507 1898 3508 1897 3508 1899 3508 1898 3509 1899 3509 1900 3509 1900 3510 1899 3510 1901 3510 1900 3511 1901 3511 1902 3511 1902 3512 1901 3512 1903 3512 1902 3513 1903 3513 1904 3513 1904 3514 1903 3514 1905 3514 1904 3515 1905 3515 1906 3515 1906 3516 1905 3516 1907 3516 1906 3517 1907 3517 1908 3517 1908 3518 1907 3518 1909 3518 1909 3519 1910 3519 1908 3519 1908 3520 1910 3520 1911 3520 1908 3521 1911 3521 1912 3521 1912 3522 1911 3522 1913 3522 1913 3523 1911 3523 1914 3523 1913 3524 1914 3524 1915 3524 1915 3525 1914 3525 1916 3525 1915 3526 1916 3526 1917 3526 1918 3527 1919 3527 1920 3527 1920 3528 1919 3528 1921 3528 1920 3529 1921 3529 1922 3529 1922 3530 1921 3530 1917 3530 1922 3531 1917 3531 1923 3531 1923 3532 1917 3532 1916 3532 1870 3533 1924 3533 1925 3533 1925 3534 1924 3534 1926 3534 1925 3535 1926 3535 1918 3535 1918 3536 1926 3536 1927 3536 1918 3537 1927 3537 1919 3537 1924 3538 1870 3538 1928 3538 1928 3539 1870 3539 1844 3539 1928 3540 1844 3540 1843 3540 1929 3541 1930 3541 1931 3541 1932 3542 1933 3542 1934 3542 1935 3543 1936 3543 1937 3543 1938 3544 1939 3544 1940 3544 1941 3545 1942 3545 1943 3545 1944 3546 1945 3546 1932 3546 1946 3547 1947 3547 1948 3547 1949 3548 1950 3548 1951 3548 1952 3549 1953 3549 1947 3549 1954 3550 1955 3550 1956 3550 1957 3551 1958 3551 1959 3551 1959 3552 1958 3552 1960 3552 1959 3553 1960 3553 1961 3553 1956 3554 1962 3554 1954 3554 1954 3555 1962 3555 1963 3555 1954 3556 1963 3556 1964 3556 1955 3557 1954 3557 1965 3557 1965 3558 1954 3558 1964 3558 1965 3559 1964 3559 1966 3559 1967 3560 1968 3560 1969 3560 1970 3561 1971 3561 1972 3561 1973 3562 1974 3562 1975 3562 1975 3563 1974 3563 1976 3563 1975 3564 1976 3564 1977 3564 1977 3565 1976 3565 1978 3565 1977 3566 1978 3566 1979 3566 1979 3567 1978 3567 1980 3567 1979 3568 1980 3568 1981 3568 1981 3569 1980 3569 1982 3569 1973 3570 1975 3570 1983 3570 1983 3571 1975 3571 1984 3571 1983 3572 1984 3572 1985 3572 1985 3573 1984 3573 1986 3573 1985 3574 1986 3574 1987 3574 1988 3575 1989 3575 1990 3575 1991 3576 1992 3576 1989 3576 1989 3577 1992 3577 1993 3577 1989 3578 1993 3578 1990 3578 1994 3579 1995 3579 1996 3579 1994 3580 1996 3580 1997 3580 1995 3581 1994 3581 1998 3581 1998 3582 1994 3582 1999 3582 1998 3583 1999 3583 2000 3583 1939 3584 2001 3584 1940 3584 1940 3585 2001 3585 2002 3585 1940 3586 2002 3586 2003 3586 2003 3587 2002 3587 2004 3587 2004 3588 2002 3588 2005 3588 2004 3589 2005 3589 2006 3589 227 3590 2007 3590 170 3590 170 3591 2007 3591 2008 3591 2009 3592 225 3592 223 3592 2010 3593 221 3593 220 3593 221 3594 2010 3594 171 3594 171 3595 2010 3595 2011 3595 171 3596 2011 3596 172 3596 172 3597 2011 3597 2012 3597 172 3598 2012 3598 216 3598 210 3599 211 3599 2013 3599 2013 3600 211 3600 213 3600 2013 3601 213 3601 214 3601 2014 3602 191 3602 192 3602 2015 3603 187 3603 189 3603 2016 3604 183 3604 185 3604 2017 3605 178 3605 180 3605 2018 3606 176 3606 175 3606 175 3607 2019 3607 2018 3607 2018 3608 2019 3608 2020 3608 2018 3609 2020 3609 2021 3609 2021 3610 2020 3610 2022 3610 2022 3611 2020 3611 2023 3611 2022 3612 2023 3612 2024 3612 2025 3613 2026 3613 2027 3613 2027 3614 2028 3614 2025 3614 2025 3615 2028 3615 2029 3615 2025 3616 2029 3616 2023 3616 2023 3617 2029 3617 2030 3617 2023 3618 2030 3618 2024 3618 2031 3619 2032 3619 2026 3619 2026 3620 2032 3620 2033 3620 2026 3621 2033 3621 2027 3621 2034 3622 2035 3622 2031 3622 2031 3623 2035 3623 2036 3623 2031 3624 2036 3624 2032 3624 2037 3625 2038 3625 2034 3625 2034 3626 2038 3626 2039 3626 2034 3627 2039 3627 2035 3627 1948 3628 2040 3628 2037 3628 2037 3629 2040 3629 2041 3629 2037 3630 2041 3630 2038 3630 1953 3631 2042 3631 1947 3631 1947 3632 2042 3632 2043 3632 1947 3633 2043 3633 1948 3633 1948 3634 2043 3634 2044 3634 1948 3635 2044 3635 2040 3635 2045 3636 2046 3636 2047 3636 2047 3637 2046 3637 1952 3637 2048 3638 2049 3638 2050 3638 2050 3639 2049 3639 2051 3639 2050 3640 2051 3640 2045 3640 2052 3641 2053 3641 2054 3641 2054 3642 2053 3642 2055 3642 2056 3643 2057 3643 1929 3643 2058 3644 2059 3644 2060 3644 2061 3645 1945 3645 2062 3645 2062 3646 1945 3646 1944 3646 2062 3647 1944 3647 2063 3647 2064 3648 2061 3648 2065 3648 2065 3649 2061 3649 2062 3649 2065 3650 2062 3650 2066 3650 2066 3651 2062 3651 2063 3651 2066 3652 2063 3652 2067 3652 1933 3653 1932 3653 2068 3653 2068 3654 1932 3654 1945 3654 2068 3655 1945 3655 2069 3655 2069 3656 1945 3656 2061 3656 2069 3657 2061 3657 2070 3657 2070 3658 2061 3658 2064 3658 2070 3659 2064 3659 2071 3659 2072 3660 2073 3660 2074 3660 175 3661 178 3661 2019 3661 2019 3662 178 3662 2017 3662 2019 3663 2017 3663 2020 3663 2020 3664 2017 3664 2075 3664 2020 3665 2075 3665 2023 3665 2023 3666 2075 3666 2076 3666 2023 3667 2076 3667 2025 3667 2025 3668 2076 3668 2077 3668 2025 3669 2077 3669 2026 3669 2026 3670 2077 3670 2078 3670 2026 3671 2078 3671 2031 3671 2031 3672 2078 3672 2079 3672 2031 3673 2079 3673 2034 3673 2034 3674 2079 3674 2080 3674 2034 3675 2080 3675 2037 3675 2037 3676 2080 3676 2081 3676 2037 3677 2081 3677 1948 3677 1948 3678 2081 3678 2082 3678 1948 3679 2082 3679 1946 3679 1946 3680 2082 3680 2083 3680 180 3681 2084 3681 2017 3681 2017 3682 2084 3682 2085 3682 2017 3683 2085 3683 2075 3683 2075 3684 2085 3684 2086 3684 2075 3685 2086 3685 2076 3685 2076 3686 2086 3686 2087 3686 2076 3687 2087 3687 2077 3687 2077 3688 2087 3688 2088 3688 2077 3689 2088 3689 2078 3689 2078 3690 2088 3690 2089 3690 2078 3691 2089 3691 2079 3691 2079 3692 2089 3692 2090 3692 2079 3693 2090 3693 2080 3693 2080 3694 2090 3694 2091 3694 2080 3695 2091 3695 2081 3695 2081 3696 2091 3696 2092 3696 2081 3697 2092 3697 2082 3697 2082 3698 2092 3698 2093 3698 2082 3699 2093 3699 2083 3699 2083 3700 2093 3700 1950 3700 2083 3701 1950 3701 1946 3701 1946 3702 1950 3702 1949 3702 1946 3703 1949 3703 1947 3703 1951 3704 1950 3704 2094 3704 2094 3705 1950 3705 2093 3705 2094 3706 2093 3706 2095 3706 2095 3707 2093 3707 2092 3707 2095 3708 2092 3708 2096 3708 2096 3709 2092 3709 2091 3709 2096 3710 2091 3710 2097 3710 2097 3711 2091 3711 2090 3711 2097 3712 2090 3712 2098 3712 2098 3713 2090 3713 2089 3713 2098 3714 2089 3714 2099 3714 2099 3715 2089 3715 2088 3715 2099 3716 2088 3716 2100 3716 2100 3717 2088 3717 2087 3717 2100 3718 2087 3718 2101 3718 2101 3719 2087 3719 2086 3719 2101 3720 2086 3720 2102 3720 2102 3721 2086 3721 2085 3721 2102 3722 2085 3722 2103 3722 2103 3723 2085 3723 2084 3723 2103 3724 2084 3724 2104 3724 2104 3725 2084 3725 180 3725 2104 3726 180 3726 183 3726 183 3727 2016 3727 2104 3727 2104 3728 2016 3728 2105 3728 2104 3729 2105 3729 2103 3729 2103 3730 2105 3730 2106 3730 2103 3731 2106 3731 2102 3731 2102 3732 2106 3732 2107 3732 2102 3733 2107 3733 2101 3733 2101 3734 2107 3734 2108 3734 2101 3735 2108 3735 2100 3735 2100 3736 2108 3736 2109 3736 2100 3737 2109 3737 2099 3737 2099 3738 2109 3738 2110 3738 2099 3739 2110 3739 2098 3739 2098 3740 2110 3740 2111 3740 2098 3741 2111 3741 2097 3741 2097 3742 2111 3742 2112 3742 2097 3743 2112 3743 2096 3743 2096 3744 2112 3744 2060 3744 2096 3745 2060 3745 2095 3745 2095 3746 2060 3746 2059 3746 2095 3747 2059 3747 2094 3747 2058 3748 2060 3748 2113 3748 2113 3749 2060 3749 2112 3749 2113 3750 2112 3750 2114 3750 2114 3751 2112 3751 2111 3751 2114 3752 2111 3752 2115 3752 2115 3753 2111 3753 2110 3753 2115 3754 2110 3754 2116 3754 2116 3755 2110 3755 2109 3755 2116 3756 2109 3756 2117 3756 2117 3757 2109 3757 2108 3757 2117 3758 2108 3758 2118 3758 2118 3759 2108 3759 2107 3759 2118 3760 2107 3760 2119 3760 2119 3761 2107 3761 2106 3761 2119 3762 2106 3762 2120 3762 2120 3763 2106 3763 2105 3763 2120 3764 2105 3764 2121 3764 2121 3765 2105 3765 2016 3765 2121 3766 2016 3766 2122 3766 2122 3767 2016 3767 185 3767 2122 3768 185 3768 187 3768 187 3769 2015 3769 2122 3769 2122 3770 2015 3770 2123 3770 2122 3771 2123 3771 2121 3771 2121 3772 2123 3772 2124 3772 2121 3773 2124 3773 2120 3773 2120 3774 2124 3774 2125 3774 2120 3775 2125 3775 2119 3775 2119 3776 2125 3776 2126 3776 2119 3777 2126 3777 2118 3777 2118 3778 2126 3778 2127 3778 2118 3779 2127 3779 2117 3779 2117 3780 2127 3780 2128 3780 2117 3781 2128 3781 2116 3781 2116 3782 2128 3782 2129 3782 2116 3783 2129 3783 2115 3783 2115 3784 2129 3784 2130 3784 2115 3785 2130 3785 2114 3785 2114 3786 2130 3786 2074 3786 2114 3787 2074 3787 2113 3787 2113 3788 2074 3788 2073 3788 2113 3789 2073 3789 2058 3789 2072 3790 2074 3790 2131 3790 2131 3791 2074 3791 2130 3791 2131 3792 2130 3792 2132 3792 2132 3793 2130 3793 2129 3793 2132 3794 2129 3794 2133 3794 2133 3795 2129 3795 2128 3795 2133 3796 2128 3796 2134 3796 2134 3797 2128 3797 2127 3797 2134 3798 2127 3798 2135 3798 2135 3799 2127 3799 2126 3799 2135 3800 2126 3800 2136 3800 2136 3801 2126 3801 2125 3801 2136 3802 2125 3802 2137 3802 2137 3803 2125 3803 2124 3803 2137 3804 2124 3804 2138 3804 2138 3805 2124 3805 2123 3805 2138 3806 2123 3806 2139 3806 2139 3807 2123 3807 2015 3807 2139 3808 2015 3808 2140 3808 2140 3809 2015 3809 189 3809 2140 3810 189 3810 191 3810 191 3811 2014 3811 2140 3811 2140 3812 2014 3812 2141 3812 2140 3813 2141 3813 2139 3813 2139 3814 2141 3814 2142 3814 2139 3815 2142 3815 2138 3815 2138 3816 2142 3816 2143 3816 2138 3817 2143 3817 2137 3817 2137 3818 2143 3818 2144 3818 2137 3819 2144 3819 2136 3819 2136 3820 2144 3820 2145 3820 2136 3821 2145 3821 2135 3821 2135 3822 2145 3822 2146 3822 2135 3823 2146 3823 2134 3823 2134 3824 2146 3824 2147 3824 2134 3825 2147 3825 2133 3825 2133 3826 2147 3826 2148 3826 2133 3827 2148 3827 2132 3827 2132 3828 2148 3828 2149 3828 2132 3829 2149 3829 2131 3829 2131 3830 2149 3830 2150 3830 2131 3831 2150 3831 2072 3831 2072 3832 2150 3832 2151 3832 2072 3833 2151 3833 2073 3833 2073 3834 2151 3834 2152 3834 2073 3835 2152 3835 2058 3835 2058 3836 2152 3836 2153 3836 2058 3837 2153 3837 2059 3837 2059 3838 2153 3838 2154 3838 2059 3839 2154 3839 2094 3839 2094 3840 2154 3840 2155 3840 2094 3841 2155 3841 1951 3841 192 3842 2156 3842 2014 3842 2014 3843 2156 3843 2157 3843 2014 3844 2157 3844 2141 3844 2141 3845 2157 3845 2158 3845 2141 3846 2158 3846 2142 3846 2142 3847 2158 3847 2159 3847 2142 3848 2159 3848 2143 3848 2143 3849 2159 3849 2160 3849 2143 3850 2160 3850 2144 3850 2144 3851 2160 3851 2161 3851 2144 3852 2161 3852 2145 3852 2145 3853 2161 3853 2162 3853 2145 3854 2162 3854 2146 3854 2146 3855 2162 3855 2163 3855 2146 3856 2163 3856 2147 3856 2147 3857 2163 3857 2164 3857 2147 3858 2164 3858 2148 3858 2148 3859 2164 3859 2165 3859 2148 3860 2165 3860 2149 3860 2149 3861 2165 3861 2166 3861 2149 3862 2166 3862 2150 3862 2150 3863 2166 3863 2071 3863 2150 3864 2071 3864 2151 3864 2151 3865 2071 3865 2064 3865 2151 3866 2064 3866 2152 3866 2152 3867 2064 3867 2065 3867 2152 3868 2065 3868 2153 3868 2153 3869 2065 3869 2066 3869 2153 3870 2066 3870 2154 3870 2154 3871 2066 3871 2067 3871 2154 3872 2067 3872 2155 3872 2167 3873 2168 3873 2169 3873 2169 3874 2168 3874 2170 3874 2169 3875 2170 3875 2171 3875 2171 3876 2170 3876 2172 3876 2171 3877 2172 3877 2173 3877 2173 3878 2172 3878 2174 3878 2173 3879 2174 3879 2175 3879 2175 3880 2174 3880 2176 3880 2175 3881 2176 3881 2177 3881 2177 3882 2176 3882 2178 3882 2177 3883 2178 3883 2179 3883 2179 3884 2178 3884 2180 3884 2179 3885 2180 3885 2181 3885 2181 3886 2180 3886 2182 3886 2181 3887 2182 3887 2183 3887 2183 3888 2182 3888 2184 3888 2183 3889 2184 3889 2185 3889 2185 3890 2184 3890 2186 3890 2185 3891 2186 3891 2187 3891 2187 3892 2186 3892 2188 3892 2187 3893 2188 3893 2189 3893 2189 3894 2188 3894 2190 3894 2189 3895 2190 3895 2191 3895 2191 3896 2190 3896 2192 3896 2191 3897 2192 3897 2193 3897 2193 3898 2192 3898 2194 3898 2193 3899 2194 3899 2195 3899 2195 3900 2194 3900 2196 3900 2195 3901 2196 3901 2197 3901 2197 3902 2196 3902 2198 3902 2197 3903 2198 3903 2199 3903 2199 3904 2198 3904 2200 3904 2201 3905 2202 3905 2203 3905 2203 3906 2202 3906 2204 3906 2203 3907 2204 3907 2205 3907 2205 3908 2204 3908 2206 3908 2205 3909 2206 3909 2207 3909 2207 3910 2206 3910 2208 3910 2207 3911 2208 3911 2209 3911 2209 3912 2208 3912 2210 3912 2209 3913 2210 3913 2211 3913 2211 3914 2210 3914 2212 3914 2211 3915 2212 3915 2213 3915 2213 3916 2212 3916 2214 3916 2213 3917 2214 3917 2215 3917 2215 3918 2214 3918 2216 3918 2215 3919 2216 3919 2217 3919 2217 3920 2216 3920 2218 3920 2217 3921 2218 3921 2219 3921 2219 3922 2218 3922 2220 3922 2219 3923 2220 3923 2221 3923 2221 3924 2220 3924 2222 3924 2221 3925 2222 3925 2223 3925 2223 3926 2222 3926 2224 3926 2223 3927 2224 3927 2225 3927 2225 3928 2224 3928 2226 3928 2225 3929 2226 3929 2227 3929 2227 3930 2226 3930 2228 3930 2227 3931 2228 3931 2229 3931 2229 3932 2228 3932 2230 3932 2229 3933 2230 3933 2231 3933 2231 3934 2230 3934 2232 3934 2231 3935 2232 3935 2233 3935 2202 3936 2234 3936 2204 3936 2204 3937 2234 3937 2235 3937 2204 3938 2235 3938 2206 3938 2206 3939 2235 3939 2236 3939 2206 3940 2236 3940 2208 3940 2208 3941 2236 3941 2237 3941 2208 3942 2237 3942 2210 3942 2210 3943 2237 3943 2238 3943 2210 3944 2238 3944 2212 3944 2212 3945 2238 3945 2239 3945 2212 3946 2239 3946 2214 3946 2214 3947 2239 3947 2240 3947 2214 3948 2240 3948 2216 3948 2216 3949 2240 3949 2241 3949 2216 3950 2241 3950 2218 3950 2218 3951 2241 3951 2242 3951 2218 3952 2242 3952 2220 3952 2220 3953 2242 3953 2243 3953 2220 3954 2243 3954 2222 3954 2222 3955 2243 3955 2244 3955 2222 3956 2244 3956 2224 3956 2224 3957 2244 3957 2245 3957 2224 3958 2245 3958 2226 3958 2226 3959 2245 3959 2246 3959 2226 3960 2246 3960 2228 3960 2228 3961 2246 3961 2247 3961 2228 3962 2247 3962 2230 3962 2230 3963 2247 3963 2248 3963 2230 3964 2248 3964 2232 3964 214 3965 216 3965 2013 3965 2013 3966 216 3966 2012 3966 2013 3967 2012 3967 2249 3967 2250 3968 2251 3968 2252 3968 2252 3969 2251 3969 2253 3969 2252 3970 2253 3970 2254 3970 2254 3971 2253 3971 2255 3971 2254 3972 2255 3972 2256 3972 2256 3973 2255 3973 2257 3973 2256 3974 2257 3974 2258 3974 1942 3975 1941 3975 2259 3975 2259 3976 1941 3976 2260 3976 2259 3977 2260 3977 2261 3977 2261 3978 2260 3978 2262 3978 2261 3979 2262 3979 2263 3979 2263 3980 2262 3980 2264 3980 2263 3981 2264 3981 2265 3981 2266 3982 2250 3982 2267 3982 2267 3983 2250 3983 2252 3983 2267 3984 2252 3984 2268 3984 2268 3985 2252 3985 2254 3985 2268 3986 2254 3986 2269 3986 2269 3987 2254 3987 2256 3987 2269 3988 2256 3988 2270 3988 2270 3989 2256 3989 2258 3989 2270 3990 2258 3990 2271 3990 2272 3991 2273 3991 2274 3991 2274 3992 2273 3992 2275 3992 2274 3993 2275 3993 2276 3993 2276 3994 2275 3994 2277 3994 2276 3995 2277 3995 2278 3995 2278 3996 2277 3996 2279 3996 2278 3997 2279 3997 2280 3997 2281 3998 2282 3998 2283 3998 2283 3999 2282 3999 2284 3999 2283 4000 2284 4000 2285 4000 2285 4001 2284 4001 2286 4001 2285 4002 2286 4002 2287 4002 2287 4003 2286 4003 2288 4003 2287 4004 2288 4004 2289 4004 2290 4005 2291 4005 2292 4005 2292 4006 2291 4006 2293 4006 2292 4007 2293 4007 2265 4007 2265 4008 2293 4008 2294 4008 2265 4009 2294 4009 2263 4009 2263 4010 2294 4010 2295 4010 2263 4011 2295 4011 2261 4011 1943 4012 2266 4012 1941 4012 1941 4013 2266 4013 2267 4013 1941 4014 2267 4014 2260 4014 2260 4015 2267 4015 2268 4015 2260 4016 2268 4016 2262 4016 2262 4017 2268 4017 2269 4017 2262 4018 2269 4018 2264 4018 2264 4019 2269 4019 2270 4019 2264 4020 2270 4020 2265 4020 2265 4021 2270 4021 2271 4021 2265 4022 2271 4022 2292 4022 2292 4023 2271 4023 2296 4023 2292 4024 2296 4024 2290 4024 2290 4025 2296 4025 2297 4025 2298 4026 1938 4026 2299 4026 2299 4027 1938 4027 1940 4027 2299 4028 1940 4028 2300 4028 2300 4029 1940 4029 2003 4029 2251 4030 2272 4030 2253 4030 2253 4031 2272 4031 2274 4031 2253 4032 2274 4032 2255 4032 2255 4033 2274 4033 2276 4033 2255 4034 2276 4034 2257 4034 2257 4035 2276 4035 2278 4035 2257 4036 2278 4036 2258 4036 2258 4037 2278 4037 2280 4037 2258 4038 2280 4038 2271 4038 2271 4039 2280 4039 2301 4039 2271 4040 2301 4040 2296 4040 2296 4041 2301 4041 2302 4041 2296 4042 2302 4042 2297 4042 2297 4043 2302 4043 2303 4043 2304 4044 2303 4044 2305 4044 2305 4045 2303 4045 2302 4045 2305 4046 2302 4046 2306 4046 2306 4047 2302 4047 2301 4047 2306 4048 2301 4048 2289 4048 2289 4049 2301 4049 2280 4049 2289 4050 2280 4050 2287 4050 2287 4051 2280 4051 2279 4051 2287 4052 2279 4052 2285 4052 2285 4053 2279 4053 2277 4053 2285 4054 2277 4054 2283 4054 2283 4055 2277 4055 2275 4055 2283 4056 2275 4056 2281 4056 2281 4057 2275 4057 2273 4057 2307 4058 2308 4058 2309 4058 2309 4059 2308 4059 2310 4059 2309 4060 2310 4060 2311 4060 2311 4061 2310 4061 2312 4061 2311 4062 2312 4062 2313 4062 2313 4063 2312 4063 2314 4063 2313 4064 2314 4064 2315 4064 2282 4065 2307 4065 2284 4065 2284 4066 2307 4066 2309 4066 2284 4067 2309 4067 2286 4067 2286 4068 2309 4068 2311 4068 2286 4069 2311 4069 2288 4069 2288 4070 2311 4070 2313 4070 2288 4071 2313 4071 2289 4071 2289 4072 2313 4072 2315 4072 2289 4073 2315 4073 2306 4073 2306 4074 2315 4074 2316 4074 2306 4075 2316 4075 2305 4075 2305 4076 2316 4076 2317 4076 2305 4077 2317 4077 2304 4077 2318 4078 2319 4078 2320 4078 2320 4079 2319 4079 2321 4079 2320 4080 2321 4080 2322 4080 2322 4081 2321 4081 2323 4081 2322 4082 2323 4082 2324 4082 2324 4083 2323 4083 2325 4083 2324 4084 2325 4084 2326 4084 2326 4085 2325 4085 2327 4085 2326 4086 2327 4086 218 4086 2319 4087 2249 4087 2321 4087 2321 4088 2249 4088 2012 4088 2321 4089 2012 4089 2323 4089 2323 4090 2012 4090 2011 4090 2323 4091 2011 4091 2325 4091 2325 4092 2011 4092 2010 4092 2325 4093 2010 4093 2327 4093 2327 4094 2010 4094 220 4094 2327 4095 220 4095 218 4095 2328 4096 2318 4096 2329 4096 2329 4097 2318 4097 2320 4097 2329 4098 2320 4098 2330 4098 2330 4099 2320 4099 2322 4099 2330 4100 2322 4100 2331 4100 2331 4101 2322 4101 2324 4101 2331 4102 2324 4102 2332 4102 2332 4103 2324 4103 2326 4103 2332 4104 2326 4104 2333 4104 2333 4105 2326 4105 218 4105 2333 4106 218 4106 2009 4106 2009 4107 218 4107 226 4107 2009 4108 226 4108 225 4108 222 4109 170 4109 2334 4109 2334 4110 170 4110 2008 4110 2334 4111 2008 4111 2335 4111 2335 4112 2008 4112 2317 4112 2335 4113 2317 4113 2336 4113 2336 4114 2317 4114 2316 4114 2336 4115 2316 4115 2337 4115 2337 4116 2316 4116 2315 4116 2337 4117 2315 4117 2338 4117 2338 4118 2315 4118 2314 4118 2338 4119 2314 4119 2339 4119 2339 4120 2314 4120 2312 4120 2339 4121 2312 4121 2340 4121 2340 4122 2312 4122 2310 4122 2340 4123 2310 4123 2341 4123 2341 4124 2310 4124 2308 4124 2007 4125 2006 4125 2008 4125 2008 4126 2006 4126 2005 4126 2008 4127 2005 4127 2317 4127 2317 4128 2005 4128 2002 4128 2317 4129 2002 4129 2304 4129 2304 4130 2002 4130 2001 4130 2304 4131 2001 4131 2303 4131 2303 4132 2001 4132 1939 4132 2303 4133 1939 4133 2297 4133 2297 4134 1939 4134 1938 4134 2297 4135 1938 4135 2290 4135 2290 4136 1938 4136 2298 4136 2290 4137 2298 4137 2291 4137 2341 4138 2328 4138 2340 4138 2340 4139 2328 4139 2329 4139 2340 4140 2329 4140 2339 4140 2339 4141 2329 4141 2330 4141 2339 4142 2330 4142 2338 4142 2338 4143 2330 4143 2331 4143 2338 4144 2331 4144 2337 4144 2337 4145 2331 4145 2332 4145 2337 4146 2332 4146 2336 4146 2336 4147 2332 4147 2333 4147 2336 4148 2333 4148 2335 4148 2335 4149 2333 4149 2009 4149 2335 4150 2009 4150 2334 4150 2334 4151 2009 4151 223 4151 2334 4152 223 4152 222 4152 1977 4153 2342 4153 1975 4153 1975 4154 2342 4154 2343 4154 1975 4155 2343 4155 1984 4155 1984 4156 2343 4156 1988 4156 1984 4157 1988 4157 1986 4157 1986 4158 1988 4158 1990 4158 1986 4159 1990 4159 1987 4159 2300 4160 2344 4160 2299 4160 2299 4161 2344 4161 2345 4161 2299 4162 2345 4162 2298 4162 2298 4163 2345 4163 2346 4163 2298 4164 2346 4164 2291 4164 2291 4165 2346 4165 2347 4165 2291 4166 2347 4166 2293 4166 2293 4167 2347 4167 2348 4167 2293 4168 2348 4168 2294 4168 2294 4169 2348 4169 2349 4169 2294 4170 2349 4170 2295 4170 2295 4171 2349 4171 2350 4171 2295 4172 2350 4172 2261 4172 2261 4173 2350 4173 2351 4173 2261 4174 2351 4174 2259 4174 2259 4175 2351 4175 2352 4175 2259 4176 2352 4176 1942 4176 1942 4177 2352 4177 2353 4177 1942 4178 2353 4178 1943 4178 2354 4179 1957 4179 2355 4179 2355 4180 1957 4180 1959 4180 2355 4181 1959 4181 2356 4181 2356 4182 1959 4182 1961 4182 2356 4183 1961 4183 2357 4183 2358 4184 2359 4184 2360 4184 2361 4185 1936 4185 2362 4185 2362 4186 1936 4186 1935 4186 2362 4187 1935 4187 2363 4187 1981 4188 2361 4188 1979 4188 1979 4189 2361 4189 2362 4189 1979 4190 2362 4190 1977 4190 1977 4191 2362 4191 2363 4191 1977 4192 2363 4192 2342 4192 1956 4193 2354 4193 1962 4193 1962 4194 2354 4194 2355 4194 1962 4195 2355 4195 2364 4195 2364 4196 2355 4196 2356 4196 2364 4197 2356 4197 2055 4197 2055 4198 2356 4198 2357 4198 2055 4199 2357 4199 2054 4199 1971 4200 1967 4200 1972 4200 1972 4201 1967 4201 1969 4201 1972 4202 1969 4202 2365 4202 2365 4203 1969 4203 2366 4203 2365 4204 2366 4204 2367 4204 2367 4205 2366 4205 2368 4205 2367 4206 2368 4206 2369 4206 2369 4207 2368 4207 2370 4207 2369 4208 2370 4208 2371 4208 2371 4209 2370 4209 2372 4209 2371 4210 2372 4210 2373 4210 2373 4211 2372 4211 2374 4211 2373 4212 2374 4212 2375 4212 2375 4213 2374 4213 2376 4213 2375 4214 2376 4214 2377 4214 2377 4215 2376 4215 2378 4215 2377 4216 2378 4216 2048 4216 1968 4217 1966 4217 1969 4217 1969 4218 1966 4218 1964 4218 1969 4219 1964 4219 2366 4219 2366 4220 1964 4220 1963 4220 2366 4221 1963 4221 2368 4221 2368 4222 1963 4222 1962 4222 2368 4223 1962 4223 2370 4223 2370 4224 1962 4224 2364 4224 2370 4225 2364 4225 2372 4225 2372 4226 2364 4226 2055 4226 2372 4227 2055 4227 2374 4227 2374 4228 2055 4228 2053 4228 2374 4229 2053 4229 2376 4229 2376 4230 2053 4230 2052 4230 2376 4231 2052 4231 2378 4231 2045 4232 2047 4232 2050 4232 2050 4233 2047 4233 2379 4233 2050 4234 2379 4234 2380 4234 2380 4235 2379 4235 2381 4235 2380 4236 2381 4236 2056 4236 2056 4237 2381 4237 2382 4237 2056 4238 2382 4238 2057 4238 2057 4239 2382 4239 2383 4239 2057 4240 2383 4240 1929 4240 1929 4241 2383 4241 2384 4241 1929 4242 2384 4242 1930 4242 1930 4243 2384 4243 2385 4243 1930 4244 2385 4244 1931 4244 1931 4245 2385 4245 2386 4245 1931 4246 2386 4246 2387 4246 2387 4247 2386 4247 2388 4247 2387 4248 2388 4248 2389 4248 2389 4249 2388 4249 2390 4249 2389 4250 2390 4250 2391 4250 2391 4251 2390 4251 2392 4251 2391 4252 2392 4252 2393 4252 2048 4253 2050 4253 2377 4253 2377 4254 2050 4254 2380 4254 2377 4255 2380 4255 2375 4255 2375 4256 2380 4256 2056 4256 2375 4257 2056 4257 2373 4257 2373 4258 2056 4258 1929 4258 2373 4259 1929 4259 2371 4259 2371 4260 1929 4260 1931 4260 2371 4261 1931 4261 2369 4261 2369 4262 1931 4262 2387 4262 2369 4263 2387 4263 2367 4263 2367 4264 2387 4264 2389 4264 2367 4265 2389 4265 2365 4265 2365 4266 2389 4266 2391 4266 2365 4267 2391 4267 1972 4267 1972 4268 2391 4268 2393 4268 1972 4269 2393 4269 1970 4269 1952 4270 1947 4270 2047 4270 2047 4271 1947 4271 1949 4271 2047 4272 1949 4272 2379 4272 2379 4273 1949 4273 1951 4273 2379 4274 1951 4274 2381 4274 2381 4275 1951 4275 2155 4275 2381 4276 2155 4276 2382 4276 2382 4277 2155 4277 2067 4277 2382 4278 2067 4278 2383 4278 2383 4279 2067 4279 2063 4279 2383 4280 2063 4280 2384 4280 2384 4281 2063 4281 1944 4281 2384 4282 1944 4282 2385 4282 2385 4283 1944 4283 1932 4283 2385 4284 1932 4284 2386 4284 2386 4285 1932 4285 1934 4285 2386 4286 1934 4286 2388 4286 2388 4287 1934 4287 2358 4287 2388 4288 2358 4288 2390 4288 2390 4289 2358 4289 2360 4289 2390 4290 2360 4290 2392 4290 2168 4291 2201 4291 2170 4291 2170 4292 2201 4292 2203 4292 2170 4293 2203 4293 2172 4293 2172 4294 2203 4294 2205 4294 2172 4295 2205 4295 2174 4295 2174 4296 2205 4296 2207 4296 2174 4297 2207 4297 2176 4297 2176 4298 2207 4298 2209 4298 2176 4299 2209 4299 2178 4299 2178 4300 2209 4300 2211 4300 2178 4301 2211 4301 2180 4301 2180 4302 2211 4302 2213 4302 2180 4303 2213 4303 2182 4303 2182 4304 2213 4304 2215 4304 2182 4305 2215 4305 2184 4305 2184 4306 2215 4306 2217 4306 2184 4307 2217 4307 2186 4307 2186 4308 2217 4308 2219 4308 2186 4309 2219 4309 2188 4309 2188 4310 2219 4310 2221 4310 2188 4311 2221 4311 2190 4311 2190 4312 2221 4312 2223 4312 2190 4313 2223 4313 2192 4313 2192 4314 2223 4314 2225 4314 2192 4315 2225 4315 2194 4315 2194 4316 2225 4316 2227 4316 2194 4317 2227 4317 2196 4317 2196 4318 2227 4318 2229 4318 2196 4319 2229 4319 2198 4319 2198 4320 2229 4320 2231 4320 2198 4321 2231 4321 2200 4321 2200 4322 2231 4322 2233 4322 2394 4323 2395 4323 2396 4323 2396 4324 2395 4324 2397 4324 2396 4325 2397 4325 2398 4325 2398 4326 2397 4326 2399 4326 2398 4327 2399 4327 2400 4327 2400 4328 2399 4328 2401 4328 2400 4329 2401 4329 2402 4329 2402 4330 2401 4330 2403 4330 2402 4331 2403 4331 2404 4331 2404 4332 2403 4332 2405 4332 2404 4333 2405 4333 2406 4333 2406 4334 2405 4334 2407 4334 2406 4335 2407 4335 2408 4335 2408 4336 2407 4336 2409 4336 2408 4337 2409 4337 2410 4337 2410 4338 2409 4338 2411 4338 2410 4339 2411 4339 2412 4339 2412 4340 2411 4340 2413 4340 2412 4341 2413 4341 2414 4341 2414 4342 2413 4342 2415 4342 2414 4343 2415 4343 2416 4343 2416 4344 2415 4344 2417 4344 2416 4345 2417 4345 2418 4345 2418 4346 2417 4346 2419 4346 2418 4347 2419 4347 2420 4347 2420 4348 2419 4348 2421 4348 2420 4349 2421 4349 2422 4349 2422 4350 2421 4350 2423 4350 2422 4351 2423 4351 2424 4351 2424 4352 2423 4352 2425 4352 2424 4353 2425 4353 2426 4353 2426 4354 2425 4354 2427 4354 2426 4355 2427 4355 2428 4355 2429 4356 2430 4356 2431 4356 2431 4357 2430 4357 1937 4357 2431 4358 1937 4358 2359 4358 2359 4359 1937 4359 1936 4359 2359 4360 1936 4360 2360 4360 2360 4361 1936 4361 2361 4361 2360 4362 2361 4362 2392 4362 2392 4363 2361 4363 1981 4363 2392 4364 1981 4364 2393 4364 2393 4365 1981 4365 1982 4365 2393 4366 1982 4366 1970 4366 2395 4367 2432 4367 2397 4367 2397 4368 2432 4368 2433 4368 2397 4369 2433 4369 2399 4369 2399 4370 2433 4370 2434 4370 2399 4371 2434 4371 2401 4371 2401 4372 2434 4372 2435 4372 2401 4373 2435 4373 2403 4373 2403 4374 2435 4374 2436 4374 2403 4375 2436 4375 2405 4375 2405 4376 2436 4376 2437 4376 2405 4377 2437 4377 2407 4377 2407 4378 2437 4378 2438 4378 2407 4379 2438 4379 2409 4379 2409 4380 2438 4380 2439 4380 2409 4381 2439 4381 2411 4381 2411 4382 2439 4382 2440 4382 2411 4383 2440 4383 2413 4383 2413 4384 2440 4384 2441 4384 2413 4385 2441 4385 2415 4385 2415 4386 2441 4386 2442 4386 2415 4387 2442 4387 2417 4387 2417 4388 2442 4388 2443 4388 2417 4389 2443 4389 2419 4389 2419 4390 2443 4390 2444 4390 2419 4391 2444 4391 2421 4391 2421 4392 2444 4392 2445 4392 2421 4393 2445 4393 2423 4393 2423 4394 2445 4394 2446 4394 2423 4395 2446 4395 2425 4395 2425 4396 2446 4396 2447 4396 2425 4397 2447 4397 2427 4397 2427 4398 2447 4398 2448 4398 2427 4399 2448 4399 2428 4399 2428 4400 2448 4400 2449 4400 2428 4401 2449 4401 2450 4401 2450 4402 2449 4402 2451 4402 2450 4403 2451 4403 2452 4403 2452 4404 2451 4404 2453 4404 2452 4405 2453 4405 2454 4405 2454 4406 2453 4406 2455 4406 2454 4407 2455 4407 2456 4407 2456 4408 2455 4408 2457 4408 2456 4409 2457 4409 2458 4409 2458 4410 2457 4410 1997 4410 2458 4411 1997 4411 2459 4411 2459 4412 1997 4412 1996 4412 2459 4413 1996 4413 2460 4413 2156 4414 2167 4414 2157 4414 2157 4415 2167 4415 2169 4415 2157 4416 2169 4416 2158 4416 2158 4417 2169 4417 2171 4417 2158 4418 2171 4418 2159 4418 2159 4419 2171 4419 2173 4419 2159 4420 2173 4420 2160 4420 2160 4421 2173 4421 2175 4421 2160 4422 2175 4422 2161 4422 2161 4423 2175 4423 2177 4423 2161 4424 2177 4424 2162 4424 2162 4425 2177 4425 2179 4425 2162 4426 2179 4426 2163 4426 2163 4427 2179 4427 2181 4427 2163 4428 2181 4428 2164 4428 2164 4429 2181 4429 2183 4429 2164 4430 2183 4430 2165 4430 2165 4431 2183 4431 2185 4431 2165 4432 2185 4432 2166 4432 2166 4433 2185 4433 2187 4433 2166 4434 2187 4434 2071 4434 2071 4435 2187 4435 2189 4435 2071 4436 2189 4436 2070 4436 2070 4437 2189 4437 2191 4437 2070 4438 2191 4438 2069 4438 2069 4439 2191 4439 2193 4439 2069 4440 2193 4440 2068 4440 2068 4441 2193 4441 2195 4441 2068 4442 2195 4442 1933 4442 1933 4443 2195 4443 2197 4443 1933 4444 2197 4444 1934 4444 1934 4445 2197 4445 2199 4445 1934 4446 2199 4446 2358 4446 2358 4447 2199 4447 2200 4447 2358 4448 2200 4448 2359 4448 2359 4449 2200 4449 2233 4449 2359 4450 2233 4450 2431 4450 2431 4451 2233 4451 2232 4451 2431 4452 2232 4452 2429 4452 2429 4453 2232 4453 2248 4453 2234 4454 2394 4454 2235 4454 2235 4455 2394 4455 2396 4455 2235 4456 2396 4456 2236 4456 2236 4457 2396 4457 2398 4457 2236 4458 2398 4458 2237 4458 2237 4459 2398 4459 2400 4459 2237 4460 2400 4460 2238 4460 2238 4461 2400 4461 2402 4461 2238 4462 2402 4462 2239 4462 2239 4463 2402 4463 2404 4463 2239 4464 2404 4464 2240 4464 2240 4465 2404 4465 2406 4465 2240 4466 2406 4466 2241 4466 2241 4467 2406 4467 2408 4467 2241 4468 2408 4468 2242 4468 2242 4469 2408 4469 2410 4469 2242 4470 2410 4470 2243 4470 2243 4471 2410 4471 2412 4471 2243 4472 2412 4472 2244 4472 2244 4473 2412 4473 2414 4473 2244 4474 2414 4474 2245 4474 2245 4475 2414 4475 2416 4475 2245 4476 2416 4476 2246 4476 2246 4477 2416 4477 2418 4477 2246 4478 2418 4478 2247 4478 2247 4479 2418 4479 2420 4479 2247 4480 2420 4480 2248 4480 2248 4481 2420 4481 2422 4481 2248 4482 2422 4482 2429 4482 2429 4483 2422 4483 2424 4483 2429 4484 2424 4484 2430 4484 2430 4485 2424 4485 2426 4485 2430 4486 2426 4486 1937 4486 1937 4487 2426 4487 2428 4487 1937 4488 2428 4488 1935 4488 1935 4489 2428 4489 2450 4489 1935 4490 2450 4490 2363 4490 2363 4491 2450 4491 2452 4491 2363 4492 2452 4492 2342 4492 2342 4493 2452 4493 2454 4493 2342 4494 2454 4494 2343 4494 2343 4495 2454 4495 2456 4495 2343 4496 2456 4496 1988 4496 1988 4497 2456 4497 2458 4497 1988 4498 2458 4498 1989 4498 1989 4499 2458 4499 2459 4499 1989 4500 2459 4500 1991 4500 1991 4501 2459 4501 2460 4501 192 4502 194 4502 2156 4502 2156 4503 194 4503 196 4503 2156 4504 196 4504 2167 4504 2167 4505 196 4505 198 4505 2167 4506 198 4506 2168 4506 2168 4507 198 4507 200 4507 2168 4508 200 4508 2201 4508 2201 4509 200 4509 202 4509 2201 4510 202 4510 2202 4510 2202 4511 202 4511 204 4511 2202 4512 204 4512 2234 4512 2234 4513 204 4513 206 4513 2234 4514 206 4514 2394 4514 2394 4515 206 4515 208 4515 2394 4516 208 4516 2395 4516 2395 4517 208 4517 210 4517 2395 4518 210 4518 2432 4518 2432 4519 210 4519 2013 4519 2432 4520 2013 4520 2433 4520 2433 4521 2013 4521 2249 4521 2433 4522 2249 4522 2434 4522 2434 4523 2249 4523 2319 4523 2434 4524 2319 4524 2435 4524 2435 4525 2319 4525 2318 4525 2435 4526 2318 4526 2436 4526 2436 4527 2318 4527 2328 4527 2436 4528 2328 4528 2437 4528 2437 4529 2328 4529 2341 4529 2437 4530 2341 4530 2438 4530 2438 4531 2341 4531 2308 4531 2438 4532 2308 4532 2439 4532 2439 4533 2308 4533 2307 4533 2439 4534 2307 4534 2440 4534 2440 4535 2307 4535 2282 4535 2440 4536 2282 4536 2441 4536 2441 4537 2282 4537 2281 4537 2441 4538 2281 4538 2442 4538 2442 4539 2281 4539 2273 4539 2442 4540 2273 4540 2443 4540 2443 4541 2273 4541 2272 4541 2443 4542 2272 4542 2444 4542 2444 4543 2272 4543 2251 4543 2444 4544 2251 4544 2445 4544 2445 4545 2251 4545 2250 4545 2445 4546 2250 4546 2446 4546 2446 4547 2250 4547 2266 4547 2446 4548 2266 4548 2447 4548 2447 4549 2266 4549 1943 4549 2447 4550 1943 4550 2448 4550 2448 4551 1943 4551 2353 4551 2448 4552 2353 4552 2449 4552 2449 4553 2353 4553 2352 4553 2449 4554 2352 4554 2451 4554 2451 4555 2352 4555 2351 4555 2451 4556 2351 4556 2453 4556 2453 4557 2351 4557 2350 4557 2453 4558 2350 4558 2455 4558 2455 4559 2350 4559 2349 4559 2455 4560 2349 4560 2457 4560 2457 4561 2349 4561 2348 4561 2457 4562 2348 4562 1997 4562 1997 4563 2348 4563 2347 4563 1997 4564 2347 4564 1994 4564 1994 4565 2347 4565 2346 4565 1994 4566 2346 4566 1999 4566 1999 4567 2346 4567 2345 4567 1999 4568 2345 4568 2000 4568 2000 4569 2345 4569 2344 4569 1925 4570 1918 4570 2461 4570 2462 4571 2054 4571 2357 4571 2463 4572 2052 4572 2464 4572 2464 4573 2052 4573 2054 4573 2465 4574 2048 4574 2463 4574 2463 4575 2048 4575 2378 4575 2463 4576 2378 4576 2052 4576 2046 4577 2045 4577 2466 4577 2466 4578 2045 4578 2051 4578 2466 4579 2051 4579 2465 4579 2465 4580 2051 4580 2049 4580 2465 4581 2049 4581 2048 4581 1953 4582 1952 4582 2467 4582 2467 4583 1952 4583 2046 4583 2043 4584 2042 4584 2468 4584 2468 4585 2042 4585 1953 4585 2469 4586 2040 4586 2044 4586 2040 4587 2469 4587 2041 4587 2041 4588 2469 4588 2470 4588 2041 4589 2470 4589 2038 4589 2038 4590 2470 4590 2039 4590 2039 4591 2470 4591 2471 4591 2039 4592 2471 4592 2035 4592 2035 4593 2471 4593 2036 4593 2036 4594 2471 4594 2472 4594 2036 4595 2472 4595 2032 4595 2032 4596 2472 4596 2033 4596 2033 4597 2472 4597 2473 4597 2033 4598 2473 4598 2027 4598 2027 4599 2473 4599 2028 4599 2028 4600 2473 4600 2474 4600 2028 4601 2474 4601 2029 4601 2029 4602 2474 4602 2030 4602 2030 4603 2474 4603 2475 4603 2030 4604 2475 4604 2024 4604 2024 4605 2475 4605 2022 4605 2022 4606 2475 4606 2476 4606 2022 4607 2476 4607 2021 4607 2021 4608 2476 4608 2477 4608 2021 4609 2477 4609 2018 4609 2018 4610 2477 4610 712 4610 2018 4611 712 4611 176 4611 2478 4612 1877 4612 2479 4612 2479 4613 1877 4613 1804 4613 2479 4614 1804 4614 711 4614 711 4615 1804 4615 1802 4615 711 4616 1802 4616 4 4616 1882 4617 1880 4617 2478 4617 2478 4618 1880 4618 1879 4618 2478 4619 1879 4619 1877 4619 2478 4620 2480 4620 1882 4620 1882 4621 2480 4621 2481 4621 1882 4622 2481 4622 1884 4622 1884 4623 2481 4623 1886 4623 1886 4624 2481 4624 2482 4624 1886 4625 2482 4625 1887 4625 1887 4626 2482 4626 1889 4626 1889 4627 2482 4627 2483 4627 1889 4628 2483 4628 1891 4628 1891 4629 2483 4629 2484 4629 1891 4630 2484 4630 1892 4630 1892 4631 2484 4631 1894 4631 1894 4632 2484 4632 2485 4632 1894 4633 2485 4633 1896 4633 1896 4634 2485 4634 2486 4634 1896 4635 2486 4635 1897 4635 1897 4636 2486 4636 1899 4636 1899 4637 2486 4637 2487 4637 1899 4638 2487 4638 1901 4638 2488 4639 1905 4639 1903 4639 1910 4640 1909 4640 2489 4640 2489 4641 1909 4641 1907 4641 2490 4642 1914 4642 2489 4642 2489 4643 1914 4643 1911 4643 2489 4644 1911 4644 1910 4644 1920 4645 1922 4645 2491 4645 2491 4646 1922 4646 1923 4646 2491 4647 1923 4647 2490 4647 2490 4648 1923 4648 1916 4648 2490 4649 1916 4649 1914 4649 2492 4650 1870 4650 1925 4650 2492 4651 1925 4651 2493 4651 1953 4652 2467 4652 2468 4652 2468 4653 2467 4653 2494 4653 2468 4654 2494 4654 2495 4654 2046 4655 2466 4655 2467 4655 2467 4656 2466 4656 2496 4656 2467 4657 2496 4657 2494 4657 2494 4658 2496 4658 2497 4658 2494 4659 2497 4659 2495 4659 740 4660 712 4660 2498 4660 2498 4661 712 4661 2477 4661 2498 4662 2477 4662 2499 4662 2499 4663 2477 4663 2476 4663 2499 4664 2476 4664 2500 4664 2500 4665 2476 4665 2475 4665 2500 4666 2475 4666 2501 4666 2501 4667 2475 4667 2474 4667 2501 4668 2474 4668 2502 4668 2502 4669 2474 4669 2473 4669 2502 4670 2473 4670 2503 4670 2503 4671 2473 4671 2472 4671 2503 4672 2472 4672 2504 4672 2504 4673 2472 4673 2471 4673 2504 4674 2471 4674 2505 4674 2505 4675 2471 4675 2470 4675 2505 4676 2470 4676 2495 4676 2495 4677 2470 4677 2469 4677 2495 4678 2469 4678 2468 4678 2468 4679 2469 4679 2044 4679 2468 4680 2044 4680 2043 4680 2506 4681 2489 4681 2488 4681 2488 4682 2489 4682 1907 4682 2488 4683 1907 4683 1905 4683 2507 4684 2491 4684 2508 4684 2508 4685 2491 4685 2490 4685 2508 4686 2490 4686 2509 4686 2509 4687 2490 4687 2489 4687 2509 4688 2489 4688 2510 4688 2510 4689 2489 4689 2506 4689 711 4690 740 4690 2479 4690 2479 4691 740 4691 2498 4691 2479 4692 2498 4692 2478 4692 2478 4693 2498 4693 2499 4693 2478 4694 2499 4694 2480 4694 2480 4695 2499 4695 2500 4695 2480 4696 2500 4696 2481 4696 2481 4697 2500 4697 2501 4697 2481 4698 2501 4698 2482 4698 2482 4699 2501 4699 2502 4699 2482 4700 2502 4700 2483 4700 2483 4701 2502 4701 2503 4701 2483 4702 2503 4702 2484 4702 2484 4703 2503 4703 2504 4703 2484 4704 2504 4704 2485 4704 2485 4705 2504 4705 2505 4705 2485 4706 2505 4706 2486 4706 2486 4707 2505 4707 2495 4707 2486 4708 2495 4708 2487 4708 2487 4709 2495 4709 2497 4709 2493 4710 1925 4710 2511 4710 2511 4711 1925 4711 2461 4711 2511 4712 2461 4712 2512 4712 2513 4713 2514 4713 2515 4713 2515 4714 2514 4714 2516 4714 2515 4715 2516 4715 2512 4715 2512 4716 2516 4716 2517 4716 2512 4717 2517 4717 2511 4717 2054 4718 2462 4718 2464 4718 2464 4719 2462 4719 2507 4719 2464 4720 2507 4720 2463 4720 2463 4721 2507 4721 2508 4721 2463 4722 2508 4722 2465 4722 2465 4723 2508 4723 2509 4723 2465 4724 2509 4724 2466 4724 2466 4725 2509 4725 2510 4725 2466 4726 2510 4726 2496 4726 2496 4727 2510 4727 2506 4727 2496 4728 2506 4728 2497 4728 2497 4729 2506 4729 2488 4729 2497 4730 2488 4730 2487 4730 2487 4731 2488 4731 1903 4731 2487 4732 1903 4732 1901 4732 1960 4733 2514 4733 1961 4733 1961 4734 2514 4734 2513 4734 1961 4735 2513 4735 2357 4735 2357 4736 2513 4736 2515 4736 2357 4737 2515 4737 2462 4737 2462 4738 2515 4738 2512 4738 2462 4739 2512 4739 2507 4739 2507 4740 2512 4740 2461 4740 2507 4741 2461 4741 2491 4741 2491 4742 2461 4742 1918 4742 2491 4743 1918 4743 1920 4743 1957 4744 2518 4744 2519 4744 1957 4745 2519 4745 1958 4745 1958 4746 2519 4746 2520 4746 1958 4747 2520 4747 1960 4747 1955 4748 1965 4748 2521 4748 1955 4749 2521 4749 1956 4749 2518 4750 1957 4750 2521 4750 2521 4751 1957 4751 2354 4751 2521 4752 2354 4752 1956 4752 2522 4753 770 4753 20 4753 1965 4754 2523 4754 2524 4754 2524 4755 2523 4755 2525 4755 2525 4756 2526 4756 2527 4756 2527 4757 2526 4757 1827 4757 2527 4758 1827 4758 1826 4758 763 4759 771 4759 2528 4759 2528 4760 771 4760 770 4760 2529 4761 2530 4761 2531 4761 2531 4762 2530 4762 2532 4762 2531 4763 2532 4763 2533 4763 2533 4764 2532 4764 2534 4764 2533 4765 2534 4765 2535 4765 2535 4766 2534 4766 764 4766 2535 4767 764 4767 763 4767 2536 4768 2537 4768 2538 4768 2538 4769 2537 4769 2539 4769 2538 4770 2539 4770 2540 4770 2540 4771 2539 4771 2541 4771 2540 4772 2541 4772 2542 4772 2542 4773 2541 4773 2543 4773 2542 4774 2543 4774 2544 4774 2544 4775 2543 4775 2545 4775 2544 4776 2545 4776 2546 4776 2546 4777 2545 4777 2547 4777 2546 4778 2547 4778 2529 4778 2529 4779 2547 4779 2548 4779 2529 4780 2548 4780 2530 4780 2549 4781 2550 4781 2551 4781 2551 4782 2550 4782 2552 4782 2551 4783 2552 4783 2553 4783 2553 4784 2552 4784 2554 4784 2553 4785 2554 4785 2555 4785 2555 4786 2554 4786 2556 4786 2555 4787 2556 4787 2557 4787 2557 4788 2556 4788 2558 4788 2557 4789 2558 4789 2559 4789 2559 4790 2558 4790 2560 4790 2559 4791 2560 4791 2536 4791 2536 4792 2560 4792 2561 4792 2536 4793 2561 4793 2537 4793 20 4794 1806 4794 2522 4794 2522 4795 1806 4795 1809 4795 2522 4796 1809 4796 2562 4796 2562 4797 1809 4797 1815 4797 2562 4798 1815 4798 2563 4798 2563 4799 1815 4799 1814 4799 2563 4800 1814 4800 2564 4800 2564 4801 1814 4801 1813 4801 2564 4802 1813 4802 2565 4802 2565 4803 1813 4803 1812 4803 2565 4804 1812 4804 2566 4804 2566 4805 1812 4805 1811 4805 2566 4806 1811 4806 2567 4806 2567 4807 1811 4807 1810 4807 2567 4808 1810 4808 2568 4808 2568 4809 1810 4809 1819 4809 2568 4810 1819 4810 2569 4810 2569 4811 1819 4811 1818 4811 2569 4812 1818 4812 2570 4812 2570 4813 1818 4813 1836 4813 2570 4814 1836 4814 2571 4814 2571 4815 1836 4815 1835 4815 2571 4816 1835 4816 2572 4816 2572 4817 1835 4817 1834 4817 2572 4818 1834 4818 2573 4818 2573 4819 1834 4819 1820 4819 2573 4820 1820 4820 2574 4820 2574 4821 1820 4821 1821 4821 2574 4822 1821 4822 2575 4822 2575 4823 1821 4823 1831 4823 2575 4824 1831 4824 2576 4824 2576 4825 1831 4825 1830 4825 2576 4826 1830 4826 2577 4826 2577 4827 1830 4827 1829 4827 2577 4828 1829 4828 2578 4828 2578 4829 1829 4829 1833 4829 2578 4830 1833 4830 2579 4830 2579 4831 1833 4831 1832 4831 2579 4832 1832 4832 2580 4832 770 4833 2522 4833 2528 4833 2528 4834 2522 4834 2562 4834 2528 4835 2562 4835 2581 4835 2581 4836 2562 4836 2563 4836 2581 4837 2563 4837 2582 4837 2582 4838 2563 4838 2564 4838 2582 4839 2564 4839 2583 4839 2583 4840 2564 4840 2565 4840 2583 4841 2565 4841 2584 4841 2584 4842 2565 4842 2566 4842 2584 4843 2566 4843 2585 4843 2585 4844 2566 4844 2567 4844 2585 4845 2567 4845 2586 4845 2586 4846 2567 4846 2568 4846 2586 4847 2568 4847 2587 4847 2587 4848 2568 4848 2569 4848 2587 4849 2569 4849 2588 4849 2588 4850 2569 4850 2570 4850 2588 4851 2570 4851 2589 4851 2589 4852 2570 4852 2571 4852 2589 4853 2571 4853 2590 4853 2590 4854 2571 4854 2572 4854 2590 4855 2572 4855 2591 4855 2591 4856 2572 4856 2573 4856 2591 4857 2573 4857 2592 4857 2592 4858 2573 4858 2574 4858 2592 4859 2574 4859 2593 4859 2593 4860 2574 4860 2575 4860 2593 4861 2575 4861 2594 4861 2594 4862 2575 4862 2576 4862 2594 4863 2576 4863 2595 4863 2595 4864 2576 4864 2577 4864 2595 4865 2577 4865 2596 4865 2596 4866 2577 4866 2578 4866 2596 4867 2578 4867 2597 4867 2597 4868 2578 4868 2579 4868 2597 4869 2579 4869 2598 4869 2598 4870 2579 4870 2580 4870 2598 4871 2580 4871 2599 4871 763 4872 2528 4872 2535 4872 2535 4873 2528 4873 2581 4873 2535 4874 2581 4874 2533 4874 2533 4875 2581 4875 2582 4875 2533 4876 2582 4876 2531 4876 2531 4877 2582 4877 2583 4877 2531 4878 2583 4878 2529 4878 2529 4879 2583 4879 2584 4879 2529 4880 2584 4880 2546 4880 2546 4881 2584 4881 2585 4881 2546 4882 2585 4882 2544 4882 2544 4883 2585 4883 2586 4883 2544 4884 2586 4884 2542 4884 2542 4885 2586 4885 2587 4885 2542 4886 2587 4886 2540 4886 2540 4887 2587 4887 2588 4887 2540 4888 2588 4888 2538 4888 2538 4889 2588 4889 2589 4889 2538 4890 2589 4890 2536 4890 2536 4891 2589 4891 2590 4891 2536 4892 2590 4892 2559 4892 2559 4893 2590 4893 2591 4893 2559 4894 2591 4894 2557 4894 2557 4895 2591 4895 2592 4895 2557 4896 2592 4896 2555 4896 2555 4897 2592 4897 2593 4897 2555 4898 2593 4898 2553 4898 2553 4899 2593 4899 2594 4899 2553 4900 2594 4900 2551 4900 2551 4901 2594 4901 2595 4901 2551 4902 2595 4902 2549 4902 2549 4903 2595 4903 2596 4903 2549 4904 2596 4904 2600 4904 2600 4905 2596 4905 2597 4905 2600 4906 2597 4906 2601 4906 2601 4907 2597 4907 2598 4907 2601 4908 2598 4908 2602 4908 2602 4909 2598 4909 2599 4909 2602 4910 2599 4910 2603 4910 2604 4911 2605 4911 2603 4911 2603 4912 2605 4912 2606 4912 2603 4913 2606 4913 2602 4913 2602 4914 2606 4914 2607 4914 2602 4915 2607 4915 2601 4915 2601 4916 2607 4916 2608 4916 2601 4917 2608 4917 2600 4917 2600 4918 2608 4918 2609 4918 2600 4919 2609 4919 2549 4919 2549 4920 2609 4920 2610 4920 2549 4921 2610 4921 2550 4921 2611 4922 2604 4922 2612 4922 2612 4923 2604 4923 2603 4923 2612 4924 2603 4924 2613 4924 2613 4925 2603 4925 2599 4925 2613 4926 2599 4926 2614 4926 2614 4927 2599 4927 2580 4927 2614 4928 2580 4928 1828 4928 1828 4929 2580 4929 1832 4929 1965 4930 2611 4930 2523 4930 2523 4931 2611 4931 2612 4931 2523 4932 2612 4932 2525 4932 2525 4933 2612 4933 2613 4933 2525 4934 2613 4934 2526 4934 2526 4935 2613 4935 2614 4935 2526 4936 2614 4936 1827 4936 1827 4937 2614 4937 1828 4937 2558 4938 2556 4938 1973 4938 2611 4939 1965 4939 1966 4939 2611 4940 1966 4940 2604 4940 2604 4941 1966 4941 1968 4941 2604 4942 1968 4942 2605 4942 2605 4943 1968 4943 1967 4943 2605 4944 1967 4944 2606 4944 2606 4945 1967 4945 1971 4945 2606 4946 1971 4946 2607 4946 2607 4947 1971 4947 1970 4947 2607 4948 1970 4948 2608 4948 2608 4949 1970 4949 1982 4949 2608 4950 1982 4950 2609 4950 2609 4951 1982 4951 2610 4951 2610 4952 1982 4952 1980 4952 2610 4953 1980 4953 2550 4953 2550 4954 1980 4954 1978 4954 2550 4955 1978 4955 2552 4955 2552 4956 1978 4956 2554 4956 2554 4957 1978 4957 1976 4957 2554 4958 1976 4958 2556 4958 2556 4959 1976 4959 1974 4959 2556 4960 1974 4960 1973 4960 2558 4961 1973 4961 2560 4961 2560 4962 1973 4962 1983 4962 2560 4963 1983 4963 2561 4963 2561 4964 1983 4964 1985 4964 2561 4965 1985 4965 2537 4965 2537 4966 1985 4966 1987 4966 2537 4967 1987 4967 2539 4967 1987 4968 1990 4968 2539 4968 2539 4969 1990 4969 1993 4969 2539 4970 1993 4970 2541 4970 2541 4971 1993 4971 1992 4971 2541 4972 1992 4972 2543 4972 1992 4973 1991 4973 2543 4973 2543 4974 1991 4974 2460 4974 2543 4975 2460 4975 2545 4975 2460 4976 1996 4976 2545 4976 2545 4977 1996 4977 1995 4977 2545 4978 1995 4978 2547 4978 2547 4979 1995 4979 1998 4979 2547 4980 1998 4980 2548 4980 2548 4981 1998 4981 2530 4981 2530 4982 1998 4982 2000 4982 2530 4983 2000 4983 2344 4983 2004 4984 2532 4984 2003 4984 2003 4985 2532 4985 2530 4985 2003 4986 2530 4986 2300 4986 2300 4987 2530 4987 2344 4987 2004 4988 2006 4988 2532 4988 2532 4989 2006 4989 2007 4989 2532 4990 2007 4990 2534 4990 2534 4991 2007 4991 227 4991 2534 4992 227 4992 764 4992 2615 4993 1866 4993 1865 4993 1865 4994 1872 4994 2615 4994 2615 4995 1872 4995 1871 4995 2615 4996 1871 4996 1870 4996 2615 4997 2493 4997 1866 4997 1866 4998 2493 4998 2616 4998 1866 4999 2616 4999 1867 4999 1867 5000 2616 5000 1868 5000 1845 5001 1869 5001 2617 5001 2617 5002 1869 5002 1868 5002 1838 5003 1837 5003 1848 5003 1848 5004 1863 5004 2617 5004 2617 5005 1863 5005 1846 5005 2617 5006 1846 5006 1845 5006 2493 5007 2618 5007 2616 5007 2616 5008 2618 5008 2619 5008 2616 5009 2619 5009 2620 5009 2620 5010 2619 5010 2621 5010 2620 5011 2621 5011 2622 5011 2622 5012 2621 5012 2623 5012 2622 5013 2623 5013 2624 5013 2623 5014 2625 5014 2624 5014 2624 5015 2625 5015 2626 5015 2624 5016 2626 5016 2627 5016 2627 5017 2626 5017 2628 5017 2627 5018 2628 5018 2629 5018 2628 5019 2630 5019 2629 5019 2629 5020 2630 5020 2631 5020 2629 5021 2631 5021 2632 5021 2632 5022 2631 5022 1960 5022 2632 5023 1960 5023 2633 5023 2521 5024 2634 5024 2518 5024 2518 5025 2634 5025 2635 5025 2518 5026 2635 5026 2519 5026 2519 5027 2635 5027 2633 5027 2519 5028 2633 5028 2520 5028 2520 5029 2633 5029 1960 5029 2525 5030 2634 5030 2524 5030 2524 5031 2634 5031 2521 5031 2524 5032 2521 5032 1965 5032 1868 5033 2616 5033 2617 5033 2617 5034 2616 5034 2620 5034 2617 5035 2620 5035 2636 5035 2636 5036 2620 5036 2622 5036 2636 5037 2622 5037 2637 5037 2637 5038 2622 5038 2624 5038 2637 5039 2624 5039 2638 5039 2638 5040 2624 5040 2627 5040 2638 5041 2627 5041 2639 5041 2639 5042 2627 5042 2629 5042 2639 5043 2629 5043 2640 5043 2640 5044 2629 5044 2632 5044 2640 5045 2632 5045 2641 5045 2641 5046 2632 5046 2633 5046 2641 5047 2633 5047 2642 5047 2642 5048 2633 5048 2635 5048 2642 5049 2635 5049 2643 5049 2643 5050 2635 5050 2634 5050 2643 5051 2634 5051 2644 5051 2644 5052 2634 5052 2525 5052 2644 5053 2525 5053 2527 5053 1848 5054 2617 5054 1838 5054 1838 5055 2617 5055 2636 5055 1838 5056 2636 5056 1839 5056 1839 5057 2636 5057 2637 5057 1839 5058 2637 5058 1840 5058 1840 5059 2637 5059 2638 5059 1840 5060 2638 5060 1841 5060 1841 5061 2638 5061 2639 5061 1841 5062 2639 5062 1822 5062 1822 5063 2639 5063 2640 5063 1822 5064 2640 5064 1816 5064 1816 5065 2640 5065 2641 5065 1816 5066 2641 5066 1817 5066 1817 5067 2641 5067 2642 5067 1817 5068 2642 5068 1823 5068 1823 5069 2642 5069 2643 5069 1823 5070 2643 5070 1824 5070 1824 5071 2643 5071 2644 5071 1824 5072 2644 5072 1825 5072 1825 5073 2644 5073 2527 5073 1825 5074 2527 5074 1826 5074 2618 5075 2493 5075 2511 5075 2628 5076 2516 5076 2630 5076 2630 5077 2516 5077 2514 5077 2630 5078 2514 5078 2631 5078 2631 5079 2514 5079 1960 5079 2628 5080 2626 5080 2516 5080 2516 5081 2626 5081 2625 5081 2516 5082 2625 5082 2517 5082 2625 5083 2623 5083 2517 5083 2517 5084 2623 5084 2621 5084 2517 5085 2621 5085 2511 5085 2511 5086 2621 5086 2619 5086 2511 5087 2619 5087 2618 5087 2493 5088 2615 5088 2492 5088 2492 5089 2615 5089 1870 5089 2645 5090 2646 5090 2647 5090 2648 5090 2649 5090 2647 5090 2647 5091 2649 5091 2650 5091 2647 5092 2650 5092 2645 5092 916 5090 2651 5090 914 5090 914 5093 2651 5093 2652 5093 914 5094 2652 5094 2647 5094 2647 5090 2652 5090 2653 5090 2647 5095 2653 5095 2648 5095 2654 5096 2655 5096 2656 5096 2657 5097 2658 5097 2656 5097 2656 5098 2658 5098 2659 5098 2656 5099 2659 5099 2654 5099 2657 5100 2656 5100 2660 5100 2660 5101 2656 5101 2661 5101 2660 5102 2661 5102 2662 5102 2661 5103 2663 5103 2662 5103 2662 5104 2663 5104 2664 5104 2662 5105 2664 5105 2665 5105 2665 5106 2664 5106 2666 5106 2665 5107 2666 5107 2667 5107 2667 5108 2666 5108 2668 5108 2668 5109 2666 5109 2669 5109 2668 5110 2669 5110 2670 5110 2670 5111 2669 5111 2671 5111 2670 5112 2671 5112 2672 5112 2673 5113 2647 5113 2646 5113 2674 5114 2675 5114 2676 5114 2676 5115 2675 5115 2677 5115 2676 5116 2677 5116 2646 5116 2646 5117 2677 5117 2678 5117 2646 5118 2678 5118 2673 5118 2671 5119 2679 5119 2672 5119 2672 5120 2679 5120 2674 5120 2672 5121 2674 5121 2680 5121 2680 5122 2674 5122 2676 5122 2681 5123 2656 5123 1807 5123 1807 5124 2656 5124 1856 5124 15 5125 1004 5125 2682 5125 2655 5126 2683 5126 2656 5126 2656 5127 2683 5127 1855 5127 2656 5128 1855 5128 1856 5128 15 5129 2682 5129 1807 5129 1807 5130 2682 5130 2684 5130 1807 5131 2684 5131 2681 5131 2685 5132 2686 5132 2687 5132 2688 5133 2685 5133 2689 5133 2685 5134 2687 5134 2689 5134 2689 5135 2687 5135 2690 5135 2689 5136 2690 5136 2691 5136 2691 5137 2690 5137 2692 5137 2691 5138 2692 5138 2693 5138 2693 5139 2692 5139 2694 5139 2693 5140 2694 5140 2695 5140 2688 5141 2689 5141 2696 5141 2696 5142 2689 5142 2691 5142 2696 5143 2691 5143 2697 5143 2697 5144 2691 5144 2693 5144 2697 5145 2693 5145 2698 5145 2698 5146 2693 5146 2695 5146 2698 5147 2695 5147 2699 5147 2685 5148 2688 5148 2700 5148 2701 5149 2702 5149 2703 5149 2701 5150 2703 5150 2700 5150 2700 5151 2703 5151 2686 5151 2700 5152 2686 5152 2685 5152 2704 5153 2705 5153 2706 5153 2704 5154 2706 5154 2707 5154 2707 5155 2706 5155 2702 5155 2707 5156 2702 5156 2701 5156 914 5157 2647 5157 1531 5157 1531 5158 2647 5158 2708 5158 1531 5159 2708 5159 1532 5159 1532 5160 2708 5160 2709 5160 2710 5161 1541 5161 2711 5161 2711 5162 1541 5162 1540 5162 2711 5163 1540 5163 2712 5163 2712 5164 1540 5164 1532 5164 2712 5165 1532 5165 2713 5165 2713 5166 1532 5166 2709 5166 2688 5167 2696 5167 2714 5167 2698 5168 2715 5168 2716 5168 2714 5169 2696 5169 2716 5169 2716 5170 2696 5170 2697 5170 2716 5171 2697 5171 2698 5171 2701 5172 2700 5172 2717 5172 2717 5173 2700 5173 2718 5173 2700 5174 2688 5174 2718 5174 2718 5175 2688 5175 2714 5175 2718 5176 2714 5176 1522 5176 2698 5177 2699 5177 2715 5177 2715 5178 2699 5178 2719 5178 2715 5179 2719 5179 2720 5179 1522 5180 2714 5180 1521 5180 1521 5181 2714 5181 2716 5181 1521 5182 2716 5182 1519 5182 1519 5183 2716 5183 2715 5183 1519 5184 2715 5184 1515 5184 1515 5185 2715 5185 2720 5185 1515 5186 2720 5186 1514 5186 2695 5187 2694 5187 2721 5187 2722 5188 2699 5188 2723 5188 2723 5189 2699 5189 2695 5189 2695 5190 2721 5190 2723 5190 2723 5191 2721 5191 2724 5191 2723 5192 2724 5192 2725 5192 2725 5193 2726 5193 2723 5193 2723 5194 2726 5194 2727 5194 2723 5195 2727 5195 2722 5195 2728 5196 2726 5196 2729 5196 2729 5197 2726 5197 2725 5197 2730 5198 2729 5198 2731 5198 2731 5199 2729 5199 2725 5199 2731 5200 2725 5200 2724 5200 2732 5201 2728 5201 2733 5201 2733 5202 2728 5202 2729 5202 2733 5203 2729 5203 2734 5203 2734 5204 2729 5204 2730 5204 2734 5205 2730 5205 2735 5205 2707 5206 2701 5206 2717 5206 2736 5207 2737 5207 2704 5207 2738 5208 2739 5208 2740 5208 2738 5209 2740 5209 2741 5209 1525 5210 1529 5210 2742 5210 2742 5211 1529 5211 1527 5211 2742 5212 1527 5212 2741 5212 2741 5213 1527 5213 1526 5213 2741 5214 1526 5214 2738 5214 2740 5215 2743 5215 2741 5215 2741 5216 2743 5216 2744 5216 2741 5217 2744 5217 2742 5217 2742 5218 2744 5218 2737 5218 2737 5219 2736 5219 2742 5219 2742 5220 2736 5220 1523 5220 2742 5221 1523 5221 1525 5221 1522 5222 1523 5222 2718 5222 2718 5223 1523 5223 2736 5223 2718 5224 2736 5224 2717 5224 2717 5225 2736 5225 2704 5225 2717 5226 2704 5226 2707 5226 2745 5227 2746 5227 2747 5227 2745 5228 2747 5228 2748 5228 2749 5229 2750 5229 2751 5229 2751 5230 2750 5230 2752 5230 2751 5231 2752 5231 2753 5231 2754 5232 2755 5232 2756 5232 2757 5233 2758 5233 2759 5233 2759 5234 2758 5234 2760 5234 2759 5235 2760 5235 2761 5235 2761 5236 2760 5236 2754 5236 2761 5237 2754 5237 2762 5237 2762 5238 2754 5238 2756 5238 2762 5239 2756 5239 2749 5239 2747 5240 2763 5240 2748 5240 2748 5241 2763 5241 2764 5241 2748 5242 2764 5242 2765 5242 2765 5243 2764 5243 2766 5243 2765 5244 2766 5244 2767 5244 2767 5245 2766 5245 2768 5245 2767 5246 2768 5246 2769 5246 2769 5247 2768 5247 2770 5247 2769 5248 2770 5248 2771 5248 2771 5249 2770 5249 2772 5249 2771 5250 2772 5250 2757 5250 2757 5251 2772 5251 2773 5251 2757 5252 2773 5252 2758 5252 2753 5253 2774 5253 2751 5253 2751 5254 2774 5254 2775 5254 2751 5255 2775 5255 2776 5255 2776 5256 2775 5256 2777 5256 2776 5257 2777 5257 2778 5257 2778 5258 2777 5258 2779 5258 2778 5259 2779 5259 2780 5259 2780 5260 2779 5260 2781 5260 2780 5261 2781 5261 2782 5261 2782 5262 2781 5262 2783 5262 2782 5263 2783 5263 2784 5263 2784 5264 2783 5264 2785 5264 2784 5265 2785 5265 2786 5265 2786 5266 2785 5266 2787 5266 2786 5267 2787 5267 2788 5267 2788 5268 2787 5268 2789 5268 2788 5269 2789 5269 2790 5269 2789 5270 2791 5270 2790 5270 2790 5271 2791 5271 2792 5271 2790 5272 2792 5272 2793 5272 2749 5273 2751 5273 2762 5273 2762 5274 2751 5274 2776 5274 2762 5275 2776 5275 2761 5275 2761 5276 2776 5276 2778 5276 2761 5277 2778 5277 2759 5277 2759 5278 2778 5278 2780 5278 2759 5279 2780 5279 2757 5279 2757 5280 2780 5280 2771 5280 2771 5281 2780 5281 2782 5281 2771 5282 2782 5282 2784 5282 2771 5283 2784 5283 2769 5283 2769 5284 2784 5284 2786 5284 2769 5285 2786 5285 2767 5285 2767 5286 2786 5286 2788 5286 2767 5287 2788 5287 2765 5287 2765 5288 2788 5288 2790 5288 2765 5289 2790 5289 2748 5289 2748 5290 2790 5290 2793 5290 2748 5291 2793 5291 2745 5291 2794 5292 2795 5292 2796 5292 2796 5293 2795 5293 2797 5293 2796 5294 2797 5294 2798 5294 2798 5295 2797 5295 2799 5295 2798 5296 2799 5296 2800 5296 2800 5297 2799 5297 2801 5297 2801 5298 2799 5298 2802 5298 2801 5299 2802 5299 2803 5299 2803 5300 2802 5300 2804 5300 2803 5301 2804 5301 2805 5301 2705 5302 2704 5302 2806 5302 2806 5303 2704 5303 2807 5303 2806 5304 2807 5304 2808 5304 2808 5305 2807 5305 2809 5305 1394 5306 2810 5306 2809 5306 2809 5307 2810 5307 2811 5307 2809 5308 2811 5308 2808 5308 2812 5309 2813 5309 2814 5309 2815 5310 2732 5310 2816 5310 2816 5311 2732 5311 2733 5311 2816 5312 2733 5312 2817 5312 2817 5313 2733 5313 2734 5313 2817 5314 2734 5314 2818 5314 2818 5315 2734 5315 2735 5315 2819 5316 2815 5316 2820 5316 2820 5317 2815 5317 2816 5317 2820 5318 2816 5318 2821 5318 2821 5319 2816 5319 2817 5319 2821 5320 2817 5320 2822 5320 2822 5321 2817 5321 2818 5321 1653 5322 2819 5322 2823 5322 2823 5323 2819 5323 2820 5323 2823 5324 2820 5324 2814 5324 2814 5325 2820 5325 2821 5325 2814 5326 2821 5326 2812 5326 2812 5327 2821 5327 2822 5327 2694 5328 2692 5328 2824 5328 2824 5329 2692 5329 2690 5329 2690 5330 2687 5330 2824 5330 2824 5331 2687 5331 2686 5331 2824 5332 2686 5332 2703 5332 2703 5333 2702 5333 2824 5333 2824 5334 2702 5334 2706 5334 2824 5335 2706 5335 2705 5335 2694 5336 2824 5336 2721 5336 2721 5337 2824 5337 2825 5337 2721 5338 2825 5338 2724 5338 2724 5339 2825 5339 2731 5339 2731 5340 2825 5340 2826 5340 2731 5341 2826 5341 2730 5341 2827 5342 1597 5342 2828 5342 2828 5343 2829 5343 2827 5343 2827 5344 2829 5344 2813 5344 2827 5345 2813 5345 2830 5345 2830 5346 2813 5346 2812 5346 2830 5347 2812 5347 2831 5347 2831 5348 2812 5348 2822 5348 2831 5349 2822 5349 2832 5349 2832 5350 2822 5350 2818 5350 2832 5351 2818 5351 2826 5351 2826 5352 2818 5352 2735 5352 2826 5353 2735 5353 2730 5353 2833 5354 1465 5354 2834 5354 2834 5355 1465 5355 2835 5355 2834 5356 2835 5356 2836 5356 2836 5357 2835 5357 2837 5357 2836 5358 2837 5358 2838 5358 2838 5359 2837 5359 2839 5359 2840 5360 2833 5360 2841 5360 2841 5361 2833 5361 2834 5361 2841 5362 2834 5362 2842 5362 2842 5363 2834 5363 2836 5363 2842 5364 2836 5364 2843 5364 2843 5365 2836 5365 2838 5365 2844 5366 2840 5366 2845 5366 2845 5367 2840 5367 2841 5367 2845 5368 2841 5368 2846 5368 2846 5369 2841 5369 2842 5369 2794 5370 2846 5370 2847 5370 2847 5371 2846 5371 2842 5371 2847 5372 2842 5372 2843 5372 2794 5373 2848 5373 2846 5373 2846 5374 2848 5374 2849 5374 2846 5375 2849 5375 2845 5375 2845 5376 2849 5376 2850 5376 2851 5377 2844 5377 2852 5377 2852 5378 2844 5378 2845 5378 2852 5379 2845 5379 2853 5379 2853 5380 2845 5380 2850 5380 2803 5381 2805 5381 2854 5381 2854 5382 2805 5382 2855 5382 2854 5383 2855 5383 2856 5383 2856 5384 2855 5384 2857 5384 2856 5385 2857 5385 2858 5385 2858 5386 2857 5386 2859 5386 2858 5387 2859 5387 2860 5387 2860 5388 2859 5388 2861 5388 2801 5389 2803 5389 2862 5389 2862 5390 2803 5390 2854 5390 2862 5391 2854 5391 2863 5391 2863 5392 2854 5392 2856 5392 2863 5393 2856 5393 2864 5393 2864 5394 2856 5394 2858 5394 2864 5395 2858 5395 2865 5395 2865 5396 2858 5396 2860 5396 2865 5397 2866 5397 2864 5397 2864 5398 2866 5398 2867 5398 2864 5399 2867 5399 2863 5399 2863 5400 2867 5400 2868 5400 2863 5401 2868 5401 2862 5401 2862 5402 2868 5402 2869 5402 2862 5403 2869 5403 2801 5403 2796 5404 2798 5404 2869 5404 2869 5405 2798 5405 2800 5405 2869 5406 2800 5406 2801 5406 2870 5407 2871 5407 2851 5407 2851 5408 2852 5408 2870 5408 2870 5409 2852 5409 2853 5409 2870 5410 2853 5410 2872 5410 2848 5411 2873 5411 2849 5411 2849 5412 2873 5412 2872 5412 2849 5413 2872 5413 2850 5413 2850 5414 2872 5414 2853 5414 2866 5415 2871 5415 2867 5415 2867 5416 2871 5416 2870 5416 2867 5417 2870 5417 2868 5417 2868 5418 2870 5418 2872 5418 2868 5419 2872 5419 2869 5419 2869 5420 2872 5420 2873 5420 2869 5421 2873 5421 2796 5421 2796 5422 2873 5422 2848 5422 2796 5423 2848 5423 2794 5423 2746 5424 2745 5424 2874 5424 2792 5425 2791 5425 2875 5425 2793 5426 2792 5426 2876 5426 2745 5427 2793 5427 2877 5427 2792 5428 2875 5428 2876 5428 2876 5429 2875 5429 2878 5429 2876 5430 2878 5430 2879 5430 2879 5431 2878 5431 2880 5431 2879 5432 2880 5432 2881 5432 2881 5433 2880 5433 2882 5433 2881 5434 2882 5434 2883 5434 2883 5435 2882 5435 2861 5435 2883 5436 2861 5436 2859 5436 2793 5437 2876 5437 2877 5437 2877 5438 2876 5438 2879 5438 2877 5439 2879 5439 2884 5439 2884 5440 2879 5440 2881 5440 2884 5441 2881 5441 2885 5441 2885 5442 2881 5442 2883 5442 2885 5443 2883 5443 2886 5443 2886 5444 2883 5444 2859 5444 2886 5445 2859 5445 2857 5445 2745 5446 2877 5446 2874 5446 2874 5447 2877 5447 2884 5447 2874 5448 2884 5448 2887 5448 2887 5449 2884 5449 2885 5449 2887 5450 2885 5450 2888 5450 2888 5451 2885 5451 2886 5451 2888 5452 2886 5452 2889 5452 2889 5453 2886 5453 2857 5453 2889 5454 2857 5454 2855 5454 2746 5455 2874 5455 2890 5455 2890 5456 2874 5456 2887 5456 2890 5457 2887 5457 2891 5457 2891 5458 2887 5458 2888 5458 2891 5459 2888 5459 2892 5459 2892 5460 2888 5460 2889 5460 2892 5461 2889 5461 2893 5461 2893 5462 2889 5462 2855 5462 2893 5463 2855 5463 2805 5463 2777 5464 1541 5464 2710 5464 2710 5465 2894 5465 2791 5465 2777 5466 2775 5466 1541 5466 1541 5467 2775 5467 2774 5467 1541 5468 2774 5468 2753 5468 2791 5469 2789 5469 2710 5469 2710 5470 2789 5470 2787 5470 2710 5471 2787 5471 2785 5471 2785 5472 2783 5472 2710 5472 2710 5473 2783 5473 2781 5473 2781 5474 2779 5474 2710 5474 2710 5475 2779 5475 2777 5475 1454 5476 1452 5476 2895 5476 2895 5477 1452 5477 2896 5477 2895 5478 2896 5478 2897 5478 2897 5479 2896 5479 2898 5479 2898 5480 2896 5480 2899 5480 2898 5481 2899 5481 2900 5481 2900 5482 2899 5482 2901 5482 2901 5483 2899 5483 2894 5483 2901 5484 2894 5484 2710 5484 2902 5485 1459 5485 1454 5485 2903 5486 2904 5486 2905 5486 2905 5487 2904 5487 2906 5487 2905 5488 2906 5488 2907 5488 2907 5489 2906 5489 2908 5489 2907 5490 2908 5490 2909 5490 2909 5491 2908 5491 2910 5491 2909 5492 2910 5492 1460 5492 1460 5493 2910 5493 1461 5493 1454 5494 2895 5494 2902 5494 2902 5495 2895 5495 2897 5495 2902 5496 2897 5496 2911 5496 2901 5497 2912 5497 2900 5497 2900 5498 2912 5498 2911 5498 2900 5499 2911 5499 2898 5499 2898 5500 2911 5500 2897 5500 2709 5501 2903 5501 2713 5501 2713 5502 2903 5502 2905 5502 2713 5503 2905 5503 2712 5503 2712 5504 2905 5504 2711 5504 1460 5505 1459 5505 2909 5505 2909 5506 1459 5506 2902 5506 2909 5507 2902 5507 2907 5507 2907 5508 2902 5508 2911 5508 2907 5509 2911 5509 2905 5509 2905 5510 2911 5510 2912 5510 2905 5511 2912 5511 2711 5511 2711 5512 2912 5512 2901 5512 2711 5513 2901 5513 2710 5513 2722 5514 2727 5514 2913 5514 2913 5515 2727 5515 2726 5515 2913 5516 1512 5516 1513 5516 2699 5517 2722 5517 2719 5517 2719 5518 2722 5518 2913 5518 2719 5519 2913 5519 2720 5519 2720 5520 2913 5520 1513 5520 2720 5521 1513 5521 1514 5521 2726 5522 2914 5522 2913 5522 2913 5523 2914 5523 2915 5523 2913 5524 2915 5524 2916 5524 1512 5525 2913 5525 1516 5525 1516 5526 2913 5526 2916 5526 1516 5527 2916 5527 1517 5527 2917 5528 2728 5528 2732 5528 2918 5529 1518 5529 1517 5529 1509 5530 1518 5530 2919 5530 2919 5531 1518 5531 2918 5531 2919 5532 2918 5532 2920 5532 2920 5533 2918 5533 2917 5533 2920 5534 2917 5534 2921 5534 2921 5535 2917 5535 2732 5535 2726 5536 2728 5536 2914 5536 2914 5537 2728 5537 2917 5537 2914 5538 2917 5538 2915 5538 2915 5539 2917 5539 2918 5539 2915 5540 2918 5540 2916 5540 2916 5541 2918 5541 1517 5541 2922 5542 1395 5542 1394 5542 1394 5543 2809 5543 2740 5543 1395 5544 2922 5544 2923 5544 2923 5545 2922 5545 2924 5545 2923 5546 2924 5546 2925 5546 2926 5547 2927 5547 2922 5547 2922 5548 2927 5548 2928 5548 2922 5549 2928 5549 2924 5549 1394 5550 2740 5550 2922 5550 2922 5551 2740 5551 2739 5551 2922 5552 2739 5552 2926 5552 2704 5553 2737 5553 2807 5553 2807 5554 2737 5554 2744 5554 2807 5555 2744 5555 2809 5555 2809 5556 2744 5556 2743 5556 2809 5557 2743 5557 2740 5557 2738 5558 1526 5558 2929 5558 1395 5559 2923 5559 1398 5559 1398 5560 2923 5560 1399 5560 2929 5561 1403 5561 1402 5561 2923 5562 2925 5562 1399 5562 1399 5563 2925 5563 2924 5563 1399 5564 2924 5564 1400 5564 1400 5565 2924 5565 2928 5565 1400 5566 2928 5566 1401 5566 1401 5567 2928 5567 2927 5567 1401 5568 2927 5568 1402 5568 1402 5569 2927 5569 2926 5569 1402 5570 2926 5570 2929 5570 2929 5571 2926 5571 2739 5571 2929 5572 2739 5572 2738 5572 2930 5573 1535 5573 2755 5573 2755 5574 1535 5574 1537 5574 2753 5575 2752 5575 1541 5575 1541 5576 2752 5576 2750 5576 1541 5577 2750 5577 1539 5577 1539 5578 2750 5578 2749 5578 1539 5579 2749 5579 1537 5579 1537 5580 2749 5580 2756 5580 1537 5581 2756 5581 2755 5581 2931 5582 1391 5582 1403 5582 2929 5583 2932 5583 1403 5583 1403 5584 2932 5584 2933 5584 1403 5585 2933 5585 2931 5585 2930 5586 2932 5586 1535 5586 1535 5587 2932 5587 2929 5587 1535 5588 2929 5588 1533 5588 1533 5589 2929 5589 1526 5589 2754 5590 2934 5590 2755 5590 2755 5591 2934 5591 2930 5591 2930 5592 2934 5592 2932 5592 2932 5593 2934 5593 2935 5593 2932 5594 2935 5594 2933 5594 2933 5595 2935 5595 2931 5595 2931 5596 2935 5596 1405 5596 2931 5597 1405 5597 1391 5597 2936 5598 2760 5598 2758 5598 2937 5599 2938 5599 2939 5599 2939 5600 2938 5600 2940 5600 2939 5601 2940 5601 2773 5601 1406 5602 2938 5602 1407 5602 1407 5603 2938 5603 2937 5603 1407 5604 2937 5604 1408 5604 1406 5605 2941 5605 2938 5605 2938 5606 2941 5606 2936 5606 2938 5607 2936 5607 2940 5607 2940 5608 2936 5608 2758 5608 2940 5609 2758 5609 2773 5609 2754 5610 2760 5610 2934 5610 2934 5611 2760 5611 2936 5611 2934 5612 2936 5612 2935 5612 2935 5613 2936 5613 2941 5613 2935 5614 2941 5614 1405 5614 1405 5615 2941 5615 1406 5615 2764 5616 2763 5616 2942 5616 2747 5617 2746 5617 2943 5617 2773 5618 2772 5618 2939 5618 2939 5619 2772 5619 2770 5619 2939 5620 2770 5620 2768 5620 2939 5621 2768 5621 2766 5621 1410 5622 1409 5622 2944 5622 2944 5623 1409 5623 2945 5623 2944 5624 2945 5624 2946 5624 2946 5625 2945 5625 2942 5625 2946 5626 2942 5626 2943 5626 2943 5627 2942 5627 2763 5627 2943 5628 2763 5628 2747 5628 2766 5629 2764 5629 2939 5629 2939 5630 2764 5630 2942 5630 2939 5631 2942 5631 2937 5631 2937 5632 2942 5632 2945 5632 2937 5633 2945 5633 1408 5633 1408 5634 2945 5634 1409 5634 2947 5635 2948 5635 2949 5635 2944 5636 2946 5636 2950 5636 2805 5637 2951 5637 2952 5637 2805 5638 2952 5638 2893 5638 2893 5639 2952 5639 2953 5639 2893 5640 2953 5640 2892 5640 2892 5641 2953 5641 2954 5641 2892 5642 2954 5642 2891 5642 2891 5643 2954 5643 2955 5643 2891 5644 2955 5644 2890 5644 2890 5645 2955 5645 2943 5645 2890 5646 2943 5646 2746 5646 1411 5647 1410 5647 2944 5647 2805 5648 2804 5648 2951 5648 2951 5649 2804 5649 2802 5649 2951 5650 2802 5650 2956 5650 2956 5651 2802 5651 2799 5651 2956 5652 2799 5652 2957 5652 2799 5653 2797 5653 2957 5653 2957 5654 2797 5654 2795 5654 2957 5655 2795 5655 2958 5655 2958 5656 2795 5656 2794 5656 2958 5657 2794 5657 2959 5657 2959 5658 2794 5658 2847 5658 2959 5659 2847 5659 2843 5659 2959 5660 2947 5660 2958 5660 2958 5661 2947 5661 2949 5661 2958 5662 2949 5662 2957 5662 2957 5663 2949 5663 2960 5663 2957 5664 2960 5664 2956 5664 2956 5665 2960 5665 2961 5665 2956 5666 2961 5666 2951 5666 2951 5667 2961 5667 2962 5667 2951 5668 2962 5668 2952 5668 2952 5669 2962 5669 2963 5669 2952 5670 2963 5670 2953 5670 2953 5671 2963 5671 2964 5671 2953 5672 2964 5672 2954 5672 2954 5673 2964 5673 2965 5673 2954 5674 2965 5674 2955 5674 2955 5675 2965 5675 2950 5675 2955 5676 2950 5676 2943 5676 2943 5677 2950 5677 2946 5677 2944 5678 2950 5678 1411 5678 1411 5679 2950 5679 2965 5679 1411 5680 2965 5680 1412 5680 1412 5681 2965 5681 2964 5681 1412 5682 2964 5682 1413 5682 1413 5683 2964 5683 2963 5683 1413 5684 2963 5684 1414 5684 1414 5685 2963 5685 2962 5685 1414 5686 2962 5686 1415 5686 1415 5687 2962 5687 2961 5687 1415 5688 2961 5688 1385 5688 1385 5689 2961 5689 2960 5689 1385 5690 2960 5690 1386 5690 1386 5691 2960 5691 2949 5691 1386 5692 2949 5692 1390 5692 1390 5693 2949 5693 2948 5693 1390 5694 2948 5694 1389 5694 2966 5695 2828 5695 1595 5695 1595 5696 2828 5696 1597 5696 1605 5697 1604 5697 2967 5697 1605 5698 2967 5698 1599 5698 2966 5699 1595 5699 2968 5699 2968 5700 1595 5700 1602 5700 2968 5701 1602 5701 2967 5701 2967 5702 1602 5702 1601 5702 2967 5703 1601 5703 1599 5703 2969 5704 2970 5704 2971 5704 1394 5705 1396 5705 2810 5705 2810 5706 1396 5706 2972 5706 2810 5707 2972 5707 2811 5707 2811 5708 2972 5708 2973 5708 2811 5709 2973 5709 2808 5709 2808 5710 2973 5710 2806 5710 2806 5711 2973 5711 2824 5711 2806 5712 2824 5712 2705 5712 1396 5713 1397 5713 2972 5713 2972 5714 1397 5714 2974 5714 2972 5715 2974 5715 2973 5715 2973 5716 2974 5716 2975 5716 2973 5717 2975 5717 2824 5717 2832 5718 2826 5718 2975 5718 2975 5719 2826 5719 2825 5719 2975 5720 2825 5720 2824 5720 2970 5721 1393 5721 1392 5721 2970 5722 1392 5722 2971 5722 2971 5723 1392 5723 1404 5723 2971 5724 1404 5724 2976 5724 2976 5725 1404 5725 1384 5725 2976 5726 1384 5726 2977 5726 2977 5727 1384 5727 1388 5727 2977 5728 1388 5728 1591 5728 2969 5729 2971 5729 2978 5729 2978 5730 2971 5730 2976 5730 2978 5731 2976 5731 2979 5731 2979 5732 2976 5732 2977 5732 2979 5733 2977 5733 2980 5733 2980 5734 2977 5734 1591 5734 2980 5735 1591 5735 1592 5735 1397 5736 1393 5736 2974 5736 2974 5737 1393 5737 2970 5737 2974 5738 2970 5738 2975 5738 2975 5739 2970 5739 2969 5739 2975 5740 2969 5740 2832 5740 2832 5741 2969 5741 2978 5741 2832 5742 2978 5742 2831 5742 2831 5743 2978 5743 2979 5743 2831 5744 2979 5744 2830 5744 2830 5745 2979 5745 2980 5745 2830 5746 2980 5746 2827 5746 2827 5747 2980 5747 1592 5747 2827 5748 1592 5748 1597 5748 1374 5749 1389 5749 2948 5749 2843 5750 2838 5750 2959 5750 2959 5751 2838 5751 2839 5751 2959 5752 2839 5752 2981 5752 2981 5753 1476 5753 2959 5753 2959 5754 1476 5754 1475 5754 2959 5755 1475 5755 2947 5755 2947 5756 1475 5756 1478 5756 2947 5757 1478 5757 2948 5757 2948 5758 1478 5758 1376 5758 2948 5759 1376 5759 1374 5759 1464 5760 1468 5760 2982 5760 2982 5761 1468 5761 1482 5761 2982 5762 1482 5762 2983 5762 2983 5763 1482 5763 1480 5763 2983 5764 1480 5764 2981 5764 2981 5765 1480 5765 1476 5765 1465 5766 1464 5766 2835 5766 2835 5767 1464 5767 2982 5767 2835 5768 2982 5768 2837 5768 2837 5769 2982 5769 2983 5769 2837 5770 2983 5770 2839 5770 2839 5771 2983 5771 2981 5771 2894 5772 2899 5772 2984 5772 2899 5773 2896 5773 2985 5773 2896 5774 1452 5774 1451 5774 2896 5775 1451 5775 2985 5775 2985 5776 1451 5776 1458 5776 2985 5777 1458 5777 2986 5777 2986 5778 1458 5778 1457 5778 2986 5779 1457 5779 2987 5779 2987 5780 1457 5780 1456 5780 2987 5781 1456 5781 2988 5781 2988 5782 1456 5782 1455 5782 2988 5783 1455 5783 2989 5783 2989 5784 1455 5784 1463 5784 2989 5785 1463 5785 1470 5785 2899 5786 2985 5786 2984 5786 2984 5787 2985 5787 2986 5787 2984 5788 2986 5788 2990 5788 2990 5789 2986 5789 2987 5789 2990 5790 2987 5790 2991 5790 2991 5791 2987 5791 2988 5791 2991 5792 2988 5792 2992 5792 2992 5793 2988 5793 2989 5793 2992 5794 2989 5794 2993 5794 2993 5795 2989 5795 1470 5795 2993 5796 1470 5796 1469 5796 2894 5797 2984 5797 2994 5797 2994 5798 2984 5798 2990 5798 2994 5799 2990 5799 2995 5799 2995 5800 2990 5800 2991 5800 2995 5801 2991 5801 2996 5801 2996 5802 2991 5802 2992 5802 2996 5803 2992 5803 2997 5803 2997 5804 2992 5804 2993 5804 2997 5805 2993 5805 2998 5805 2998 5806 2993 5806 1469 5806 2998 5807 1469 5807 1466 5807 2860 5808 2861 5808 2995 5808 2875 5809 2791 5809 2894 5809 2875 5810 2894 5810 2878 5810 2995 5811 2861 5811 2994 5811 2994 5812 2861 5812 2882 5812 2994 5813 2882 5813 2894 5813 2894 5814 2882 5814 2880 5814 2894 5815 2880 5815 2878 5815 2844 5816 2851 5816 2997 5816 2997 5817 2851 5817 2871 5817 2997 5818 2871 5818 2996 5818 2996 5819 2871 5819 2866 5819 2996 5820 2866 5820 2995 5820 2995 5821 2866 5821 2865 5821 2995 5822 2865 5822 2860 5822 2844 5823 2997 5823 2840 5823 2840 5824 2997 5824 2998 5824 2840 5825 2998 5825 2833 5825 2833 5826 2998 5826 1466 5826 2833 5827 1466 5827 1465 5827 2999 5828 2815 5828 2819 5828 3000 5829 1658 5829 3001 5829 3001 5830 1658 5830 1680 5830 1511 5831 3001 5831 1507 5831 1507 5832 3001 5832 1680 5832 1507 5833 1680 5833 1508 5833 3002 5834 3003 5834 3000 5834 3000 5835 3003 5835 1659 5835 3000 5836 1659 5836 1658 5836 3002 5837 3000 5837 3004 5837 3004 5838 3000 5838 3001 5838 3004 5839 3001 5839 3005 5839 3005 5840 3001 5840 1511 5840 3005 5841 1511 5841 1510 5841 1510 5842 3006 5842 3005 5842 3005 5843 3006 5843 3007 5843 3005 5844 3007 5844 3004 5844 3004 5845 3007 5845 2999 5845 3004 5846 2999 5846 3002 5846 3002 5847 2999 5847 2819 5847 3002 5848 2819 5848 3003 5848 3003 5849 2819 5849 1653 5849 3003 5850 1653 5850 1659 5850 2732 5851 2815 5851 2921 5851 2921 5852 2815 5852 2999 5852 2921 5853 2999 5853 2920 5853 2920 5854 2999 5854 3007 5854 2920 5855 3007 5855 2919 5855 2919 5856 3007 5856 3006 5856 2919 5857 3006 5857 1509 5857 1509 5858 3006 5858 1510 5858 1654 5859 1653 5859 3008 5859 3008 5860 1653 5860 2823 5860 3008 5861 2823 5861 3009 5861 3009 5862 2823 5862 2814 5862 2828 5863 3009 5863 2829 5863 2829 5864 3009 5864 2814 5864 2829 5865 2814 5865 2813 5865 1656 5866 1654 5866 3010 5866 3010 5867 1654 5867 3008 5867 3010 5868 3008 5868 3011 5868 3011 5869 3008 5869 3009 5869 3011 5870 3009 5870 3012 5870 3012 5871 3009 5871 2828 5871 2968 5872 2967 5872 3013 5872 1657 5873 1656 5873 3014 5873 3014 5874 1656 5874 3010 5874 3014 5875 3010 5875 3015 5875 3015 5876 3010 5876 3011 5876 3015 5877 3011 5877 3016 5877 3016 5878 3011 5878 3012 5878 2968 5879 3013 5879 2966 5879 1649 5880 1657 5880 3017 5880 3017 5881 1657 5881 3014 5881 3017 5882 3014 5882 3018 5882 3018 5883 3014 5883 3015 5883 3018 5884 3015 5884 3013 5884 3013 5885 3015 5885 3016 5885 3013 5886 3016 5886 2966 5886 2966 5887 3016 5887 3012 5887 2966 5888 3012 5888 2828 5888 1625 5889 1649 5889 1644 5889 1644 5890 1649 5890 3017 5890 1644 5891 3017 5891 1643 5891 1643 5892 3017 5892 3018 5892 1643 5893 3018 5893 1642 5893 1642 5894 3018 5894 3013 5894 1642 5895 3013 5895 1604 5895 1604 5896 3013 5896 2967 5896 3019 5897 1695 5897 1694 5897 3020 5898 3019 5898 3021 5898 3019 5899 1694 5899 3021 5899 3021 5900 1694 5900 1462 5900 3021 5901 1462 5901 1453 5901 1453 5902 1461 5902 3021 5902 3021 5903 1461 5903 3022 5903 3021 5904 3022 5904 3020 5904 3020 5905 3022 5905 3023 5905 3024 5906 3023 5906 3022 5906 3024 5907 3022 5907 3025 5907 1461 5908 2910 5908 3022 5908 3022 5909 2910 5909 3026 5909 3022 5910 3026 5910 3025 5910 3025 5911 3026 5911 3027 5911 3027 5912 3026 5912 3028 5912 3027 5913 3028 5913 3029 5913 3029 5914 3028 5914 3030 5914 3029 5915 3030 5915 3031 5915 3032 5916 3033 5916 3034 5916 3034 5917 3033 5917 3035 5917 3034 5918 3035 5918 3030 5918 3030 5919 3035 5919 3036 5919 3030 5920 3036 5920 3031 5920 3034 5921 3037 5921 3032 5921 3032 5922 3037 5922 3038 5922 3032 5923 3038 5923 3039 5923 3026 5924 2910 5924 2908 5924 3026 5925 2908 5925 3028 5925 3028 5926 2908 5926 2906 5926 3028 5927 2906 5927 3030 5927 3030 5928 2906 5928 2904 5928 3030 5929 2904 5929 3034 5929 3034 5930 2904 5930 2903 5930 3034 5931 2903 5931 3037 5931 3037 5932 2903 5932 2709 5932 3037 5933 2709 5933 3038 5933 3040 5934 2708 5934 2647 5934 2708 5935 3040 5935 2709 5935 3040 5936 3041 5936 2709 5936 2709 5937 3041 5937 3042 5937 2709 5938 3042 5938 3038 5938 3038 5939 3042 5939 3039 5939 3043 5940 1716 5940 1695 5940 2682 5941 1004 5941 1716 5941 1695 5942 3019 5942 3043 5942 3043 5943 3019 5943 3020 5943 3043 5944 3020 5944 3044 5944 3044 5945 3020 5945 3023 5945 3044 5946 3023 5946 3045 5946 1716 5947 3043 5947 2682 5947 2682 5948 3043 5948 3044 5948 2682 5949 3044 5949 2684 5949 2684 5950 3044 5950 3045 5950 2684 5951 3045 5951 2681 5951 3023 5952 3024 5952 3045 5952 3045 5953 3024 5953 3046 5953 3045 5954 3046 5954 2681 5954 2681 5955 3046 5955 2656 5955 3024 5956 3025 5956 3046 5956 3046 5957 3025 5957 3047 5957 3046 5958 3047 5958 2656 5958 2656 5959 3047 5959 2661 5959 2661 5960 3047 5960 3048 5960 3036 5961 3049 5961 3031 5961 3031 5962 3049 5962 3050 5962 3031 5963 3050 5963 3029 5963 3029 5964 3050 5964 3048 5964 3029 5965 3048 5965 3027 5965 3027 5966 3048 5966 3047 5966 3027 5967 3047 5967 3025 5967 3035 5968 3051 5968 3036 5968 3036 5969 3051 5969 3052 5969 3036 5970 3052 5970 3049 5970 2661 5971 3048 5971 2663 5971 2663 5972 3048 5972 3050 5972 2663 5973 3050 5973 2664 5973 2664 5974 3050 5974 3049 5974 2664 5975 3049 5975 2666 5975 2666 5976 3049 5976 3052 5976 2666 5977 3052 5977 2669 5977 2669 5978 3052 5978 3051 5978 2669 5979 3051 5979 2671 5979 2671 5980 3051 5980 3053 5980 2671 5981 3053 5981 2679 5981 3035 5982 3033 5982 3051 5982 3051 5983 3033 5983 3032 5983 3051 5984 3032 5984 3053 5984 3053 5985 3032 5985 3039 5985 3053 5986 3039 5986 3054 5986 3054 5987 2675 5987 3053 5987 3053 5988 2675 5988 2674 5988 3053 5989 2674 5989 2679 5989 3054 5990 3039 5990 3042 5990 2647 5991 2673 5991 3040 5991 3040 5992 2673 5992 2678 5992 3040 5993 2678 5993 3041 5993 3041 5994 2678 5994 2677 5994 3041 5995 2677 5995 3042 5995 3042 5996 2677 5996 2675 5996 3042 5997 2675 5997 3054 5997 3055 5998 3056 5998 3057 5998 3058 5999 1843 5999 1842 5999 2650 6000 2649 6000 3059 6000 3059 6001 2649 6001 3060 6001 3058 6002 1842 6002 3055 6002 3055 6003 1842 6003 1876 6003 3055 6004 1876 6004 3056 6004 2645 6005 2650 6005 3057 6005 3057 6006 2650 6006 3059 6006 3057 6007 3059 6007 3055 6007 3055 6008 3059 6008 3060 6008 3055 6009 3060 6009 3058 6009 2646 6010 2645 6010 3061 6010 3061 6011 2645 6011 3057 6011 3061 6012 3057 6012 3062 6012 3062 6013 3057 6013 3056 6013 3062 6014 3056 6014 1875 6014 1875 6015 3056 6015 1876 6015 3061 6016 3062 6016 3063 6016 2683 6017 1854 6017 1855 6017 2670 6018 3064 6018 2668 6018 2668 6019 3064 6019 3065 6019 2668 6020 3065 6020 2667 6020 2667 6021 3065 6021 3066 6021 2667 6022 3066 6022 2665 6022 2665 6023 3066 6023 3067 6023 2665 6024 3067 6024 2662 6024 2662 6025 3067 6025 3068 6025 2662 6026 3068 6026 2660 6026 2660 6027 3068 6027 3069 6027 2660 6028 3069 6028 2657 6028 2657 6029 3069 6029 3070 6029 2657 6030 3070 6030 2658 6030 2658 6031 3070 6031 2659 6031 2672 6032 3071 6032 2670 6032 2670 6033 3071 6033 3072 6033 2670 6034 3072 6034 3064 6034 2672 6035 2680 6035 3071 6035 3071 6036 2680 6036 2676 6036 3071 6037 2676 6037 3073 6037 3073 6038 2676 6038 2646 6038 2646 6039 3061 6039 3073 6039 3073 6040 3061 6040 3063 6040 3073 6041 3063 6041 3071 6041 3071 6042 3063 6042 3074 6042 3071 6043 3074 6043 3072 6043 3072 6044 3074 6044 3075 6044 3072 6045 3075 6045 3064 6045 3064 6046 3075 6046 3076 6046 3064 6047 3076 6047 3065 6047 3065 6048 3076 6048 3077 6048 3065 6049 3077 6049 3066 6049 3066 6050 3077 6050 3078 6050 3066 6051 3078 6051 3067 6051 3067 6052 3078 6052 3079 6052 3067 6053 3079 6053 3068 6053 3068 6054 3079 6054 3080 6054 3068 6055 3080 6055 3069 6055 3069 6056 3080 6056 3081 6056 3069 6057 3081 6057 3070 6057 3070 6058 3081 6058 3082 6058 3070 6059 3082 6059 2659 6059 2659 6060 3082 6060 1857 6060 2659 6061 1857 6061 2654 6061 2654 6062 1857 6062 1853 6062 2654 6063 1853 6063 2655 6063 2655 6064 1853 6064 1854 6064 2683 6065 2655 6065 1854 6065 1857 6066 3082 6066 1858 6066 1858 6067 3082 6067 3081 6067 1858 6068 3081 6068 1859 6068 1859 6069 3081 6069 3080 6069 1859 6070 3080 6070 1860 6070 1860 6071 3080 6071 3079 6071 1860 6072 3079 6072 1861 6072 1861 6073 3079 6073 3078 6073 1861 6074 3078 6074 1862 6074 1862 6075 3078 6075 3077 6075 1862 6076 3077 6076 1852 6076 1852 6077 3077 6077 3076 6077 1852 6078 3076 6078 1851 6078 1851 6079 3076 6079 3075 6079 1851 6080 3075 6080 1849 6080 1849 6081 3075 6081 3074 6081 1849 6082 3074 6082 1873 6082 1873 6083 3074 6083 3063 6083 1873 6084 3063 6084 1874 6084 1874 6085 3063 6085 3062 6085 1874 6086 3062 6086 1875 6086 5 6087 1803 6087 3083 6087 5 6088 3083 6088 1759 6088 1759 6089 3083 6089 3084 6089 1759 6090 3084 6090 1757 6090 1757 6091 3084 6091 941 6091 1757 6092 941 6092 904 6092 942 6093 941 6093 3085 6093 3085 6094 941 6094 3084 6094 3085 6095 3084 6095 3086 6095 3086 6096 3084 6096 3083 6096 3086 6097 3083 6097 1805 6097 1805 6098 3083 6098 1803 6098 3085 6099 3086 6099 3087 6099 3088 6100 913 6100 911 6100 3089 6101 3088 6101 3090 6101 3088 6102 911 6102 3090 6102 3090 6103 911 6103 922 6103 3090 6104 922 6104 3091 6104 3091 6105 922 6105 921 6105 3091 6106 921 6106 920 6106 919 6107 3092 6107 920 6107 920 6108 3092 6108 3093 6108 920 6109 3093 6109 3091 6109 919 6110 927 6110 3092 6110 3092 6111 927 6111 926 6111 3092 6112 926 6112 3094 6112 3094 6113 926 6113 924 6113 3094 6114 924 6114 3095 6114 3095 6115 924 6115 940 6115 3095 6116 940 6116 3096 6116 940 6117 939 6117 3096 6117 3096 6118 939 6118 937 6118 3096 6119 937 6119 3097 6119 3097 6120 937 6120 935 6120 3097 6121 935 6121 3098 6121 3098 6122 935 6122 933 6122 3098 6123 933 6123 3099 6123 3099 6124 933 6124 931 6124 3099 6125 931 6125 3100 6125 3100 6126 931 6126 929 6126 3100 6127 929 6127 3101 6127 3101 6128 929 6128 945 6128 3101 6129 945 6129 3102 6129 3102 6130 945 6130 944 6130 3102 6131 944 6131 942 6131 942 6132 3085 6132 3102 6132 3102 6133 3085 6133 3087 6133 3102 6134 3087 6134 3101 6134 3101 6135 3087 6135 3103 6135 3101 6136 3103 6136 3100 6136 3100 6137 3103 6137 3104 6137 3100 6138 3104 6138 3099 6138 3099 6139 3104 6139 3105 6139 3099 6140 3105 6140 3098 6140 3098 6141 3105 6141 3106 6141 3098 6142 3106 6142 3097 6142 3097 6143 3106 6143 3107 6143 3097 6144 3107 6144 3096 6144 3096 6145 3107 6145 3108 6145 3096 6146 3108 6146 3095 6146 3095 6147 3108 6147 3109 6147 3095 6148 3109 6148 3094 6148 3094 6149 3109 6149 3110 6149 3094 6150 3110 6150 3092 6150 3092 6151 3110 6151 3111 6151 3092 6152 3111 6152 3093 6152 3093 6153 3111 6153 3112 6153 3093 6154 3112 6154 3091 6154 3091 6155 3112 6155 3113 6155 3091 6156 3113 6156 3090 6156 3090 6157 3113 6157 3114 6157 3090 6158 3114 6158 3089 6158 1912 6159 3089 6159 1908 6159 1908 6160 3089 6160 3114 6160 1908 6161 3114 6161 1906 6161 1906 6162 3114 6162 3113 6162 1906 6163 3113 6163 1904 6163 1904 6164 3113 6164 3112 6164 1904 6165 3112 6165 1902 6165 1902 6166 3112 6166 3111 6166 1902 6167 3111 6167 1900 6167 1900 6168 3111 6168 3110 6168 1900 6169 3110 6169 1898 6169 1898 6170 3110 6170 3109 6170 1898 6171 3109 6171 1895 6171 1895 6172 3109 6172 3108 6172 1895 6173 3108 6173 1893 6173 1893 6174 3108 6174 3107 6174 1893 6175 3107 6175 1890 6175 1890 6176 3107 6176 3106 6176 1890 6177 3106 6177 1888 6177 1888 6178 3106 6178 3105 6178 1888 6179 3105 6179 1885 6179 1885 6180 3105 6180 3104 6180 1885 6181 3104 6181 1883 6181 1883 6182 3104 6182 3103 6182 1883 6183 3103 6183 1881 6183 1881 6184 3103 6184 3087 6184 1881 6185 3087 6185 1878 6185 1878 6186 3087 6186 3086 6186 1878 6187 3086 6187 1805 6187 3089 6188 1912 6188 1913 6188 1913 6189 3115 6189 3089 6189 3089 6190 3115 6190 3116 6190 3089 6191 3116 6191 3088 6191 3088 6192 3116 6192 915 6192 3088 6193 915 6193 913 6193 1913 6194 1915 6194 3115 6194 3115 6195 1915 6195 3117 6195 3115 6196 3117 6196 3116 6196 3116 6197 3117 6197 3118 6197 3116 6198 3118 6198 915 6198 915 6199 3118 6199 916 6199 3119 6200 1926 6200 1924 6200 3120 6201 2653 6201 2652 6201 3121 6202 3120 6202 3122 6202 3120 6203 2652 6203 3122 6203 3122 6204 2652 6204 2651 6204 3122 6205 2651 6205 3123 6205 3123 6206 3124 6206 3122 6206 3122 6207 3124 6207 3119 6207 3122 6208 3119 6208 3121 6208 3121 6209 3119 6209 1924 6209 1917 6210 1921 6210 3124 6210 3124 6211 1921 6211 1919 6211 3124 6212 1919 6212 3119 6212 3119 6213 1919 6213 1927 6213 3119 6214 1927 6214 1926 6214 1915 6215 1917 6215 3117 6215 3117 6216 1917 6216 3124 6216 3117 6217 3124 6217 3118 6217 3118 6218 3124 6218 3123 6218 3118 6219 3123 6219 916 6219 916 6220 3123 6220 2651 6220 1924 6221 1928 6221 3125 6221 1924 6222 3125 6222 3121 6222 3121 6223 3125 6223 3126 6223 3121 6224 3126 6224 3120 6224 3120 6225 3126 6225 2648 6225 3120 6226 2648 6226 2653 6226 1928 6227 1843 6227 3125 6227 3125 6228 1843 6228 3058 6228 3125 6229 3058 6229 3126 6229 3126 6230 3058 6230 3060 6230 3126 6231 3060 6231 2648 6231 2648 6232 3060 6232 2649 6232

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
diff --git a/URDFs/sr_description/meshes/components/f_distal/pst/f_distal_pst.dae b/URDFs/sr_description/meshes/components/f_distal/pst/f_distal_pst.dae new file mode 100644 index 0000000..8bd625f --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_distal/pst/f_distal_pst.dae @@ -0,0 +1,132 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:39:01 + 2022-02-10T09:39:01 + + Z_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + 5.945692 0.8807764 9.412342 5.382925 0.898676 9.58211 5.382925 1.933097 9.394129 6.223668 4.060254 8.074911 6.403651 4.060254 7.945047 6.464344 3.625828 8.188947 6.597695 -0.08824235 9.073799 6.464349 -0.08824235 9.168315 6.464344 0.851709 9.136651 6.211555 -0.08824235 9.319918 5.790171 -0.08824235 9.505182 5.347561 -0.006456792 9.625772 5.347561 0.8993905 9.588886 5.347561 1.934813 9.400725 5.347561 2.399235 9.262717 5.154873 -0.08824235 9.652867 5.017525 -0.07535904 9.666588 5.0406 -0.08824235 9.664362 4.809813 -0.08822762 9.674206 5.752034 -0.08824235 9.518274 5.713805 -0.08824235 9.530824 5.382926 -0.08824235 9.616543 5.268408 -0.08824235 9.637036 6.918948 0.8125907 8.765637 6.918948 -0.08824235 8.794965 6.670776 -0.08824235 9.017166 6.634411 -0.08824235 9.045797 6.705648 4.160254 7.593876 6.918948 4.160254 7.34358 6.732038 4.060254 7.644284 6.918948 3.429767 7.871547 4.930185 4.060254 8.508027 5.345967 4.060254 8.450965 5.382925 3.861227 8.570034 5.450549 4.060254 8.425292 4.797667 3.891519 8.619072 4.797667 4.060254 8.511529 4.954567 2.949046 9.103474 4.954567 3.575116 8.798735 4.797667 3.583639 8.798735 5.945692 2.860914 8.897274 5.945692 3.771514 8.424798 5.848971 4.060254 8.282501 5.945692 1.890123 9.228919 5.382925 2.928006 9.054245 4.954567 2.423588 9.303826 6.464344 1.820336 8.960628 6.464344 2.751964 8.642363 6.918948 3.132077 8.044244 6.918948 2.605341 8.299311 6.918948 1.989594 8.5249 6.918948 1.726419 8.599573 4.954567 2.124374 8.798735 5.347561 1.933508 8.476542 4.751871 2.124374 8.798735 4.751871 1.933508 8.476542 4.751871 3.583639 8.798735 4.751871 4.060254 8.511529 4.751871 5.899752 6.126949 4.751871 6.066366 6.408202 4.751871 4.060254 8.303975 4.751871 5.288287 7.316349 -1.327033 7 19.49808 -3.060204 7 9.41948 -1.775689 7 19.53072 -2.622437 7 15.36004 -2.214897 7 19.62794 2.214897 7 19.62794 2.622437 7 15.36004 1.775689 7 19.53072 3.060204 7 9.41948 1.327033 7 19.49808 3.301439 7 4.690659 -3.301439 7 4.690659 7.409198 -5.044097 10.95987 7.675558 -4.636781 10.97141 7.56628 -4.593151 12.54953 4.544294 -3.48954 27.95967 4.425046 -3.572317 27.9699 4.613974 -4.464362 25.25258 4.860114 -3.24747 27.92537 4.666408 -3.400033 27.9477 5.025582 -4.176249 25.2269 6.768665 -5.870833 9.578129 6.853719 -5.790407 9.578129 6.768332 -5.785943 10.92859 3.37807 -7.005693 15.61588 2.639572 -7.080649 15.37719 2.792885 -7.239518 13.26165 2.353519 -5.300773 25.19717 1.650072 -5.169334 25.82216 1.876208 -5.699678 23.75961 6.849242 -0.8382434 26.02167 6.564346 -0.8382444 27.39294 6.538761 -0.9085474 27.41168 7.056926 -1.039119 24.64834 7.184607 -0.8382434 24.05127 7.134574 -0.8382434 24.37563 6.906937 -0.8382434 25.71376 6.775689 -1.91429 24.84456 6.434336 -1.168257 27.4796 7.40628 -1.72615 21.65596 7.52238 -0.8382434 21.48734 7.295902 -0.8382434 23.28368 7.721099 -2.253849 18.63151 7.831041 -1.348024 18.50573 7.532857 -0.8382434 21.39535 7.597508 -0.8382434 20.80796 7.687474 -0.9937543 19.9516 7.834091 -1.228641 18.48804 8.105918 -1.588751 15.49647 8.078191 -1.55735 15.82151 8.10363 -1.708951 15.5078 7.891332 -1.313322 17.89093 8.399656 -1.818454 11.66296 8.341572 -1.790805 12.48858 8.339889 -1.911478 12.49349 8.247733 -1.725787 13.74503 8.532424 -1.956052 9.578129 8.533742 -1.835226 9.578129 8.240139 -2.826638 12.52445 8.434974 -2.872103 9.578129 8.418226 -2.955714 9.578129 7.982685 -3.730448 12.54358 8.179078 -3.776905 9.578129 8.074432 -4.034098 9.578129 7.763466 -4.640661 9.578129 7.518364 -5.017387 9.578129 7.496384 -5.04809 9.578129 4.640649 -7.065033 10.80736 3.749466 -7.273374 10.75177 4.718754 -7.070525 9.578129 3.824205 -7.279222 9.578129 5.396618 -2.744528 27.83822 5.043921 -3.089547 27.90004 5.400794 -3.861563 25.18977 3.819394 -3.929961 28.00212 3.443062 -4.105739 28.00751 3.718538 -4.928741 25.26568 1.409256 -4.561158 27.88089 2.251762 -4.466187 27.96284 2.40792 -4.434545 27.97361 3.246242 -5.099187 25.25296 2.881237 -4.310656 27.99744 3.156627 -4.218401 28.00496 4.04141 -3.810268 27.9939 4.182221 -4.713344 25.2655 3.913126 -5.317681 23.69151 3.441285 -5.489255 23.67715 3.627042 -5.837088 22.09021 2.54886 -5.692175 23.62144 2.734884 -6.0412 22.03456 2.088848 -6.156466 21.6806 2.169224 -6.316998 20.85289 4.837169 -7.030786 9.578129 5.651069 -6.67137 9.578129 5.110165 -6.888877 10.83567 5.569636 -6.666262 10.86264 5.457154 -6.621098 12.48206 5.883829 -6.36397 12.50209 5.760965 -6.275982 14.11485 6.166787 -5.97888 14.12623 6.033937 -5.848636 15.72965 6.403193 -5.524847 15.72984 6.260737 -5.352935 17.32281 6.601002 -4.998525 17.31007 6.449534 -4.785802 18.88946 6.757449 -4.405199 18.86202 6.597112 -4.151852 20.42952 6.86956 -3.750757 20.38613 6.701252 -3.458119 21.93614 7.132586 -2.612286 21.80884 4.807035 -4.850229 23.68531 4.376136 -5.100858 23.69424 4.560845 -5.44641 22.11191 4.09846 -5.664507 22.10625 4.273945 -5.968455 20.51344 3.802912 -6.141921 20.49569 3.968875 -6.404008 18.89231 2.910992 -6.347079 20.4401 3.07716 -6.610067 18.83675 2.287267 -6.539055 19.58867 2.4709 -6.847066 17.48731 5.860761 -6.551706 9.578129 6.485106 -6.115911 9.578129 5.995974 -6.408939 10.88691 6.400855 -6.111172 10.90918 6.28914 -6.066428 12.5189 6.657116 -5.741445 12.53187 6.535357 -5.654378 14.13279 6.873948 -5.298146 14.13483 6.742569 -5.169398 15.72447 7.048396 -4.786285 15.71361 6.907818 -4.61653 17.29089 7.177757 -4.212202 17.26562 7.028584 -4.002343 18.82767 7.453918 -3.148439 18.74034 5.568453 -2.552519 27.80057 5.746962 -3.516109 25.14101 5.591603 -4.243442 23.63373 5.217593 -4.560209 23.66477 5.400527 -4.902585 22.0917 4.99095 -5.194309 22.10702 5.165127 -5.495847 20.52125 4.735755 -5.74924 20.52207 4.900845 -6.009603 18.92341 4.439558 -6.229781 18.91178 4.594707 -6.44778 17.30628 4.124334 -6.622643 17.28507 4.269471 -6.798275 15.67142 3.232792 -6.829456 17.22953 2.526677 -6.930149 16.81096 7.191922 -5.433094 9.578129 7.105661 -5.428914 10.94554 6.995024 -5.384685 12.54136 7.299209 -5.000159 12.54725 7.178896 -4.914188 14.13233 7.446801 -4.507781 14.12538 7.317257 -4.380773 15.69748 7.737605 -3.521239 15.65062 6.135067 -1.757671 27.62549 6.087799 -1.836681 27.64409 6.337395 -2.749656 25.01114 6.060335 -3.143767 25.08115 6.24826 -3.520895 23.54018 5.936403 -3.8957 23.59204 6.116937 -4.234175 22.03226 5.773415 -4.583958 22.0668 5.945647 -4.882367 20.49249 5.573798 -5.202628 20.51119 5.737386 -5.46059 18.92195 5.329545 -5.755096 18.92671 5.483617 -5.971362 17.32837 5.055521 -6.226797 17.32093 5.199967 -6.401269 15.71208 4.739571 -6.622899 15.69438 4.873851 -6.754849 14.07827 4.403986 -6.930613 14.05354 4.52776 -7.019569 12.43168 3.512691 -7.138488 13.998 3.636538 -7.227751 12.37612 2.93051 -7.323558 11.14468 7.999361 -2.620749 15.58641 4.997429 -6.843545 12.45819 5.333884 -6.532732 14.09904 5.627523 -6.145085 15.72369 5.890705 -5.675778 17.32895 6.108282 -5.138922 18.90951 6.287987 -4.530791 20.46516 6.427376 -3.857168 21.98848 6.523675 -3.124176 23.47895 3.022275 -7.337747 9.578129 3.731443 -7.292057 9.578129 3.008818 -7.338223 9.817255 -3.072391 -7.338224 9.817255 -3.085847 -7.337748 9.578129 -2.993602 -7.323429 11.15198 -2.85483 -7.238256 13.28362 -2.700413 -7.077454 15.4117 -2.590202 -6.930182 16.81097 -2.530801 -6.841482 17.53088 -2.347622 -6.533279 19.62374 -2.15005 -6.151819 21.70368 -1.938422 -5.696867 23.77142 -1.713384 -5.168828 25.82398 -1.472827 -4.561158 27.88089 -8.597314 -1.83523 9.578129 -8.597314 -1.83523 7.078129 -8.551948 -2.540075 7.078129 -3.085847 -7.337758 7.078129 -4.208706 -7.222321 7.078129 -3.887715 -7.27923 9.578129 -4.208706 -7.222321 9.578129 -4.782263 -7.070545 9.578129 -5.28894 -6.878933 7.078129 -5.28894 -6.878933 9.578129 -5.714605 -6.671461 9.578129 -6.274815 -6.322885 7.078129 -6.274815 -6.322885 9.578129 -6.548485 -6.115791 9.578129 -7.12938 -5.574058 7.078129 -7.811481 -4.666581 9.578129 -7.811481 -4.666581 7.078129 -7.255558 -5.433313 9.578129 -7.12938 -5.574058 9.578129 -7.826932 -4.640722 9.578129 -8.242614 -3.777038 9.578129 -8.290878 -3.644159 7.078129 -8.290878 -3.644159 9.578129 -8.498515 -2.872271 9.578129 -8.551948 -2.540075 9.578129 3.022275 -7.337758 7.078129 8.418226 -2.955714 7.078129 8.533742 -1.835226 7.078129 8.074432 -4.034098 7.078129 7.518364 -5.017387 7.078129 6.768665 -5.870833 7.078129 5.860761 -6.551706 7.078129 4.837169 -7.030786 7.078129 3.731443 -7.292057 7.078129 8.173969 -0.6977844 7.482397 8.173969 -0.08824235 7.550877 8.481558 -0.08824253 7.189874 8.173969 -1.969029 7.078129 8.173969 -1.782742 7.161715 8.362394 -1.427725 7.078129 8.173969 -1.399552 7.306003 8.490324 -0.8233345 7.078129 8.533749 -0.4703438 7.078129 8.533751 -0.08824235 7.115426 8.533754 -0.08824235 9.578129 6.931097 -2.969094 7.954782 7.337186 -3.522063 7.078289 6.931097 -3.664423 7.484299 6.931097 -4.134725 7.078129 6.931097 -2.21675 8.327363 7.810259 -2.717897 7.07829 6.931097 -0.08824235 8.79496 6.931097 -0.5966123 8.753588 6.931097 -1.421093 8.595258 4.809815 -1.106446 9.564442 4.809815 -0.7037166 9.625678 5.337192 -0.6980218 9.579307 5.697256 -0.08824235 9.540188 5.957461 -0.08824235 9.445881 5.95784 -0.6758812 9.399029 6.147774 -0.08824235 9.359308 6.560995 -0.08824235 9.11024 6.525144 -0.6380416 9.090924 6.751517 -0.08824235 8.960837 5.337192 -4.885377 7.505612 5.452544 -5.240106 7.078131 5.031429 -5.319861 7.078127 6.525144 -3.873445 7.752293 6.525144 -4.533277 7.161894 6.613018 -4.525976 7.077945 6.276119 -4.825913 7.07801 6.525144 -1.507564 8.923944 6.525144 -2.346687 8.641415 6.525144 -3.14013 8.248479 5.226351 -0.08824235 9.645574 5.463801 -0.08824235 9.602568 5.019552 -0.08824235 9.66702 4.809815 -1.644639 9.444987 5.337192 -1.632753 9.399806 4.809815 -2.381929 9.207324 5.337192 -2.534805 9.096087 4.809815 -2.552666 9.139258 4.809815 -3.411262 8.714056 5.337192 -3.387752 8.673686 4.809815 -3.568886 8.619509 5.337192 -4.176061 8.14029 4.809815 -4.204793 8.177126 4.809815 -4.626007 7.821457 4.809815 -4.918807 7.538246 4.809815 -5.330459 7.078129 5.878339 -5.073657 7.078112 5.95784 -4.755406 7.378734 5.95784 -4.064356 7.997066 5.95784 -3.296347 8.516729 5.95784 -2.465364 8.928254 5.95784 -1.586541 9.22415 7.979336 -0.08824235 16.94112 7.855496 -0.08824235 18.26673 7.72437 -0.08824235 19.59165 7.656075 -0.08824235 20.25383 7.58596 -0.08824235 20.91583 7.514027 -0.08824235 21.57762 7.495759 -0.08824235 21.74304 7.477377 -0.08824235 21.90845 7.370319 -0.411726 22.85186 7.440274 -0.08824235 22.23922 7.211302 -0.08824235 24.19634 6.955816 -0.08824235 26.06418 6.770204 -0.08824282 27.18408 6.976333 -0.5193955 25.63024 7.091054 -0.08824235 25.13136 6.438498 -0.4972802 28.16033 6.410623 -0.2977833 28.36717 5.954716 -0.8969662 28.96951 6.503186 -0.8052113 27.67819 1.83966 -2.19501 31.02784 1.905184 -2.808226 30.54377 2.825188 -2.633377 30.47324 5.842165 -0.08824235 29.55855 5.892456 -0.2292674 29.42948 6.16076 -0.08824235 29.02445 4.956505 -0.08824235 30.57374 5.233312 -0.1310495 30.29548 5.391071 -0.08824235 30.13862 3.296534 -0.08824235 31.58801 3.5921 -0.5696616 31.32991 4.036254 -0.477996 31.12729 1.381365 -3.066587 30.33552 1.384732 -3.361448 30.02076 1.980662 -3.350085 29.98466 1.386974 -3.530325 29.81816 1.393729 -3.943052 29.23156 2.064654 -3.811831 29.36057 1.407971 -4.521831 28.00122 2.155622 -4.185884 28.68231 1.401165 -4.281672 28.60204 1.397963 -4.147402 28.87361 1.372302 -1.999091 31.17849 1.374066 -2.235394 31.02416 1.37483 -2.332438 30.95607 1.376745 -2.564413 30.78123 1.379346 -2.860252 30.53094 1.363771 -0.08824336 31.94696 1.365578 -0.748411 31.76638 1.507744 -0.08824235 31.94503 1.743553 -0.7982292 31.73569 2.722634 -0.08824235 31.77261 2.646364 -0.08824235 31.79192 2.670627 -0.7118836 31.61309 2.119141 -0.08824235 31.8937 4.862172 -0.2574213 30.60717 4.475513 -0.08824235 30.95683 4.461473 -0.3735435 30.88557 4.38639 -0.08824235 31.01855 3.855502 -0.08824235 31.33561 5.595377 -0.4232168 29.77233 6.419332 -0.08824235 28.45645 6.619069 -0.08824235 27.85546 6.681744 -0.08824235 27.61163 1.368475 -1.390035 31.50889 1.785401 -1.521119 31.42778 2.762529 -2.047154 30.93617 3.734981 -2.345379 30.27609 6.390044 -0.08824235 28.5298 6.366811 -0.08824235 28.58602 5.920653 -0.5788114 29.22142 5.666288 -1.183909 29.24859 5.627494 -0.8214558 29.53541 5.340101 -1.457193 29.5075 5.296802 -1.05255 29.82756 4.979365 -1.713095 29.74255 4.93185 -1.268946 30.09372 4.588224 -1.948241 29.95056 4.536836 -1.46779 30.33031 4.171598 -2.159757 30.12899 4.116727 -1.646651 30.53445 3.677056 -1.803617 30.70409 2.710644 -1.402936 31.31863 5.260955 -0.6079341 30.09195 4.89251 -0.7809022 30.38383 4.494287 -0.9398416 30.64404 4.071294 -1.082808 30.86942 3.629092 -1.208273 31.05768 5.777426 -0.08824235 29.65231 6.085017 -1.612097 28.00027 5.814654 -1.998507 28.14518 5.505668 -2.366524 28.27635 5.161035 -2.711132 28.39181 4.784684 -3.027791 28.48997 3.064685 -3.950425 28.69303 3.956403 -3.562594 28.63012 4.381356 -3.312627 28.56965 6.46954 -0.6673668 27.92935 6.037669 -1.417876 28.35352 5.99397 -1.178177 28.67847 5.760747 -1.777287 28.5473 5.710989 -1.504251 28.91724 5.445515 -2.11959 28.725 5.389988 -1.814805 29.13777 5.095035 -2.440121 28.88403 5.034108 -2.105605 29.33689 4.713314 -2.734654 29.0222 4.647426 -2.37282 29.51189 4.305158 -2.999589 29.13785 4.23481 -2.613181 29.66066 3.875969 -3.23209 29.22988 3.801709 -2.824117 29.78173 2.977689 -3.592824 29.34169 2.897367 -3.151391 29.93855 -1.439573 -2.468902 30.85548 -1.444087 -2.982178 30.41772 -1.468582 -4.432047 28.24873 -1.46429 -4.27236 28.62232 -1.461421 -4.148274 28.87211 -1.454993 -3.815833 29.42879 -1.448811 -3.400176 29.9759 -1.44832 -3.361458 30.02077 -1.427342 -0.08824336 31.94696 -1.429411 -0.7756451 31.75722 -1.432222 -1.368595 31.51897 -1.435664 -1.935867 31.21718 -1.437776 -2.235427 31.02424 -5.878225 -1.998507 28.14518 -5.56924 -2.366524 28.27635 -5.509087 -2.11959 28.725 -5.042937 -1.713095 29.74255 -5.403673 -1.457193 29.5075 -5.45356 -1.814805 29.13777 -2.593111 -4.406774 27.98101 -2.315334 -4.466189 27.96284 -2.219194 -4.185884 28.68231 -2.128225 -3.811831 29.36057 -1.903231 -2.19501 31.02784 -1.848973 -1.521119 31.42778 -5.295664 -0.08824235 30.30964 -5.296883 -0.1310493 30.29548 -4.925743 -0.2574212 30.60717 -6.793591 -0.08824235 27.39324 -6.833776 -0.08824199 27.18408 -6.786545 -0.3048996 27.24604 -6.45019 -0.08824235 28.5381 -6.662793 -0.08824235 27.92501 -6.474194 -0.2977831 28.36717 -6.683126 -0.08824235 27.85304 -6.502069 -0.4972799 28.16033 -6.743535 -0.08824235 27.61834 -6.533112 -0.6673664 27.92935 -6.566757 -0.805211 27.67819 -5.324527 -0.6079339 30.09195 -5.369163 -0.08824235 30.23261 -5.658949 -0.4232167 29.77233 -5.787003 -0.08824235 29.72795 -5.956027 -0.2292672 29.42948 -4.894724 -0.08824235 30.68247 -4.525045 -0.3735434 30.88557 -4.370967 -0.08824235 31.07191 -4.099826 -0.477996 31.12729 -3.809436 -0.08824235 31.3917 -3.655672 -0.5696616 31.32991 -3.209251 -0.08824235 31.64354 -2.734199 -0.7118836 31.61309 -2.710185 -0.08824235 31.79248 -2.584069 -0.08824235 31.82191 -1.807124 -0.7982292 31.73569 -1.946775 -0.08824235 31.92227 -2.044233 -3.350085 29.98466 -1.968756 -2.808226 30.54377 -2.888759 -2.633377 30.47324 -2.960938 -3.151391 29.93855 -3.798552 -2.345379 30.27609 -3.04126 -3.592824 29.34169 -3.865281 -2.824117 29.78173 -4.298381 -2.61318 29.66066 -4.23517 -2.159757 30.12899 -4.710998 -2.372819 29.51189 -4.651795 -1.948241 29.95056 -5.097679 -2.105605 29.33689 -3.417923 -4.142513 28.00731 -3.2202 -4.218403 28.00496 -3.128257 -3.950424 28.69303 -5.824318 -1.777287 28.5473 -5.77456 -1.504251 28.91724 -5.72986 -1.183909 29.24859 -3.939541 -3.23209 29.22988 -4.368729 -2.999589 29.13785 -4.776885 -2.734654 29.0222 -5.158607 -2.440121 28.88403 -6.148588 -1.612097 28.00027 -6.101241 -1.417875 28.35352 -6.057542 -1.178176 28.67847 -6.018288 -0.896966 28.96951 -5.224606 -2.711132 28.39181 -4.848255 -3.027791 28.48997 -4.444927 -3.312627 28.56965 -4.019974 -3.562594 28.63012 -3.597235 -4.066393 28.00715 -6.052672 -1.9926 27.68009 -5.935208 -2.164308 27.71857 -5.772458 -2.381446 27.76534 -5.454616 -2.750471 27.83935 -5.295188 -2.913428 27.8695 -4.60576 -3.491044 27.95986 -4.316299 -3.684341 27.9823 -4.104982 -3.81027 27.9939 -6.602612 -0.9077997 27.41148 -6.497852 -1.168388 27.47964 -6.198198 -1.758424 27.62566 -6.130749 -1.870232 27.65192 -5.984224 -0.5788112 29.22142 -5.691065 -0.8214557 29.53541 -5.360374 -1.05255 29.82756 -4.956081 -0.7809022 30.38383 -4.995421 -1.268946 30.09372 -4.557858 -0.9398415 30.64404 -4.600407 -1.46779 30.33031 -4.134865 -1.082808 30.86942 -4.180299 -1.646651 30.53445 -3.692663 -1.208273 31.05768 -3.740627 -1.803617 30.70409 -2.774215 -1.402936 31.31863 -2.8261 -2.047154 30.93617 -6.148711 -0.08824235 29.16411 -4.093137 -4.392574 26.44602 -3.336335 -6.881042 16.79677 -8.582077 -1.837235 9.829775 -3.73251 -7.244814 11.92506 -4.62372 -7.036583 11.98063 -7.661159 -4.609586 12.1113 -8.077126 -3.746648 12.11106 -8.433338 -1.927168 12.07391 -8.434952 -1.80632 12.06989 -8.453423 -1.814544 11.80518 -8.334095 -2.842586 12.09822 -7.932721 -1.404987 18.1102 -8.128832 -1.542247 15.97136 -8.201543 -1.74602 15.09803 -8.203745 -1.625598 15.08756 -8.300066 -1.716514 13.88981 -7.62803 -0.9044427 21.10304 -7.734696 -0.9660899 20.10943 -7.940246 -1.292045 18.04531 -7.289168 -0.2453325 24.06692 -7.512574 -0.5644667 22.16166 -7.631871 -0.7859132 21.07985 -6.979023 -0.08824235 26.32166 -7.274873 -0.08824235 24.19634 -7.294049 -0.1282604 24.0375 -2.263277 -4.976768 26.38102 -5.976007 -2.831667 26.23902 -6.254391 -2.439718 26.16242 -6.447891 -2.846451 24.63213 -3.628911 -4.606789 26.44837 -4.294675 -4.813399 24.87682 -4.726213 -4.563998 24.86488 -4.917817 -4.941013 23.28819 -5.328124 -4.650548 23.26897 -5.509453 -4.983685 21.68669 -5.88204 -4.664649 21.66338 -6.052439 -4.953313 20.08093 -6.394466 -4.601348 20.05549 -6.554065 -4.846302 18.47192 -6.861689 -4.465312 18.44668 -7.010024 -4.66633 16.86788 -7.279674 -4.261662 16.84505 -7.417037 -4.419623 15.26957 -3.156245 -4.776296 26.43689 -3.47931 -7.046191 15.17552 -3.611348 -7.167404 13.55213 -4.370681 -6.838644 15.23106 -4.502622 -6.95944 13.60767 -4.972431 -6.783598 13.63289 -5.093346 -6.860517 12.00764 -5.552997 -6.638012 12.03236 -6.384762 -6.083195 12.0719 -5.979575 -6.380816 12.05358 -5.859344 -6.304513 13.67149 -5.432377 -6.56138 13.65452 -5.301011 -6.441383 15.27303 -4.840715 -6.663156 15.2545 -4.698136 -6.499056 16.87398 -4.227839 -6.674064 16.85231 -4.074536 -6.466094 18.46742 -3.182868 -6.672356 18.41186 -4.525575 -4.144959 26.43012 -4.938028 -3.858426 26.40058 -5.137558 -4.275397 24.84047 -5.512439 -3.960207 24.80486 -5.701817 -4.333323 23.23948 -6.046267 -3.98508 23.19958 -6.22523 -4.314418 21.63069 -6.535332 -3.936897 21.58899 -6.703276 -4.221957 20.02198 -6.975383 -3.820382 19.98094 -7.132507 -4.062044 18.41472 -7.402845 -2.969191 19.87876 -7.557147 -3.207264 18.33272 -7.090282 -5.40133 12.09821 -6.752565 -5.758153 12.08666 -6.633393 -5.682648 13.69268 -6.265021 -6.007273 13.68435 -6.134683 -5.888389 15.29322 -5.728434 -6.185032 15.28579 -5.586785 -6.02224 16.89801 -5.158837 -6.277889 16.88945 -5.006295 -6.071292 18.49977 -4.545135 -6.291693 18.48734 -4.381554 -6.04067 20.09702 -3.910614 -6.214341 20.07883 -3.736644 -5.91946 21.68161 -3.018748 -6.419736 20.02324 -2.844548 -6.123843 21.62597 -8.097937 -2.658431 15.17018 -7.823572 -2.311751 18.22977 -7.512199 -1.802949 21.26948 -7.165569 -1.133007 24.2795 -5.314175 -3.545494 26.35891 -5.661413 -3.201965 26.30485 -5.858239 -3.614198 24.75785 -6.171237 -3.241229 24.69997 -6.357767 -3.609702 23.14976 -6.632795 -3.212375 23.09077 -6.808842 -3.537302 21.53894 -7.066647 -2.370187 22.9487 -7.239375 -2.690307 21.41675 -7.394287 -5.016703 12.10645 -7.276504 -4.942149 13.69657 -6.971766 -5.326282 13.69676 -6.84285 -5.208765 15.29179 -6.503717 -5.564415 15.29515 -6.363477 -5.403321 16.89559 -5.993689 -5.726408 16.90003 -5.842471 -5.52172 18.50082 -5.434833 -5.816527 18.50416 -5.27242 -5.567501 20.10668 -4.843226 -5.821196 20.10643 -4.670198 -5.528253 21.70451 -4.207962 -5.746646 21.69809 -4.024269 -5.409178 23.29264 -3.552536 -5.581011 23.27785 -3.358977 -5.19989 24.86315 -2.660179 -5.784235 23.22216 -2.466329 -5.401809 24.80738 -6.885296 -2.009667 24.47039 -7.836809 -3.55952 15.22826 -3.83116 -5.02916 24.87628 -4.487121 -5.192025 23.2961 -5.100112 -5.275808 21.70066 -5.680871 -5.27393 20.09799 -6.213103 -5.199751 18.49004 -6.703474 -5.048644 16.88483 -7.148437 -4.825402 15.28321 -7.544178 -4.535553 13.69215 -7.686217 -0.08824235 20.57162 -8.042908 -0.08824235 16.94112 -8.34818 -0.08824235 13.26174 -8.597324 -0.08824235 9.578129 -8.597324 -0.08824235 7.078129 -8.483146 -0.08824235 7.180051 -8.168597 -0.08824235 7.550877 -8.168597 -0.6977844 7.482397 -8.553288 -0.08824235 7.078129 -8.547693 -0.2113939 7.078094 -8.477173 -0.8719551 7.078065 -8.168597 -1.399552 7.306003 -8.35389 -1.438309 7.078017 -8.168597 -1.782742 7.161715 -8.168597 -1.969029 7.078129 -7.983261 -2.371874 7.078199 -6.925724 -2.26816 8.305824 -6.925724 -2.969094 7.954782 -7.562965 -3.145075 7.078345 -6.925724 -3.664423 7.484299 -6.925724 -4.134725 7.078129 -6.925724 -2.21675 8.327364 -6.925724 -1.421093 8.595258 -6.925724 -0.5966123 8.753589 -6.925724 -0.08824235 8.79496 -5.635664 -5.17794 7.077909 -5.228152 -5.291707 7.077913 -4.804443 -5.330459 7.078129 -6.376843 -4.741667 7.077982 -6.012434 -4.997968 7.078129 -8.565428 -0.08824318 7.078129 -8.590537 -0.08824235 7.078129 -6.699427 -4.425756 7.078042 5.201682 4.642155 28.68221 5.181868 4.679427 28.62958 5.169682 4.684452 28.64187 4.739017 5.01578 27.63524 4.897146 5.099009 27.61245 4.89678 5.155955 27.32065 4.53694 5.014604 27.35438 4.345454 5.05861 27.37851 4.39187 5.037373 27.70315 4.730847 5.048841 27.33403 4.562975 4.994306 27.66684 4.474855 4.998719 28.05454 4.618334 4.958541 28.00355 4.59036 4.943442 28.36084 4.702819 4.908709 28.29702 4.661199 4.908678 28.4949 4.75675 4.877892 28.42596 4.785756 4.845937 28.6679 4.853727 4.823091 28.59372 4.831528 4.822357 28.71547 4.889817 4.802753 28.6404 4.768718 4.96722 27.95762 4.822889 4.908712 28.23777 4.859799 4.87551 28.36111 4.928508 4.82017 28.52269 4.954577 4.800608 28.56817 5.019492 4.754338 28.65289 4.911089 5.023894 27.9213 4.941959 4.943452 28.18735 4.964234 4.901674 28.3042 5.006915 4.837297 28.45784 5.023369 4.816004 28.50148 5.064728 4.768656 28.58413 5.07559 4.75751 28.60025 5.113153 4.795145 28.52141 5.0936 4.848359 28.44285 5.085608 4.873744 28.40194 5.06386 4.954831 28.2586 5.051491 5.010436 28.14937 5.031324 5.122941 27.8982 5.016834 5.233189 27.60144 5.00873 5.319158 27.31634 5.134445 4.751601 28.575 5.125858 4.767263 28.55738 5.118205 4.783413 28.53711 5.257574 4.58889 28.79248 5.200693 4.626662 28.75678 5.22352 4.608504 28.81632 5.178712 4.639107 28.76806 5.1954 4.624573 28.83039 5.155438 4.652315 28.77562 5.165807 4.641359 28.8405 5.123942 4.670212 28.77968 5.125971 4.663755 28.84749 5.075865 4.69753 28.77413 5.065459 4.697343 28.84537 5.001754 4.739552 28.74149 4.972445 4.747961 28.81595 4.978706 4.75259 28.72579 4.943511 4.763461 28.80077 5.227071 4.611792 28.73684 5.182641 4.652127 28.69828 5.166646 4.66099 28.70683 5.149621 4.670804 28.71189 5.126484 4.684654 28.71313 5.091057 4.706794 28.70437 5.036435 4.742763 28.66897 5.15941 4.689836 28.64776 5.148456 4.696497 28.65044 5.133551 4.706814 28.64908 5.11072 4.724943 28.63753 5.145011 4.736279 28.58871 5.151966 4.728938 28.59236 5.157133 4.725144 28.59188 5.162043 4.723067 28.58852 5.167989 4.72293 28.57993 4.332 5.132484 24.55431 4.094648 5.168705 24.59378 4.219744 5.114768 25.63669 4.89309 5.319283 26.01085 4.857601 5.335042 25.58508 4.72647 5.138697 26.01705 4.69164 5.154637 25.59336 4.49429 5.059292 26.03116 4.46048 5.074809 25.61206 4.252655 5.100257 26.04975 4.783641 5.62912 24.51662 4.918426 5.572614 25.58922 4.953886 5.557412 26.01405 4.722769 5.393612 24.51055 4.559319 5.213879 24.52419 3.908841 5.245305 23.55397 4.141263 5.214398 23.50046 4.362976 5.298004 23.45933 4.522687 5.476781 23.44009 4.583445 5.709367 23.44721 4.998527 5.415966 26.90835 4.981938 5.489044 26.48268 4.902853 5.219899 26.90889 4.903032 5.269927 26.48153 4.733062 5.083126 26.91665 4.733634 5.110213 26.48747 4.521479 5.031687 26.93016 4.510495 5.044552 26.49918 4.308386 5.075375 26.94685 4.282028 5.087191 26.51415 7.991858 -0.08824235 16.8177 8.16182 -0.08824235 7.550899 8.234888 -0.08824604 7.475131 8.540534 -0.08824235 7.087223 8.540536 -0.08824235 9.518077 8.134236 -0.08824235 15.18051 7.838373 -0.08824235 18.45389 7.757468 -0.08824235 19.27159 7.673789 -0.08824235 20.089 7.587337 -0.08824235 20.90613 7.543072 -0.08824235 21.31458 7.498113 -0.08824235 21.72296 7.469332 -0.08824235 21.98111 7.79917 4.160254 6.118076 8.16346 3.659591 6.117929 7.067784 4.160254 7.147513 8.163154 3.357546 6.392996 8.162043 0.5348055 7.542771 8.162267 1.152223 7.456823 8.162442 1.623969 7.336422 8.16249 1.754045 7.29439 8.162714 2.330835 7.058022 8.162796 2.537936 6.951521 8.16293 2.85587 6.762875 1.841035 0.4365516 9.673192 1.841035 0.3006758 9.443826 1.841035 -0.08824235 9.674221 -4.804443 -0.7037166 9.625678 -4.804659 -0.08824235 9.674221 4.797667 -0.08824235 9.674221 -4.804443 -4.918807 7.538246 -4.804443 -4.626007 7.821457 -4.804443 -4.204793 8.177126 -4.804443 -3.568886 8.619509 -4.804443 -3.411262 8.714056 -4.804443 -2.552666 9.139258 -4.804443 -2.381929 9.207324 -4.804443 -1.644639 9.444987 -4.804443 -1.106446 9.564442 -6.698826 -0.08824235 9.000344 -6.505729 -0.08824235 9.145461 -6.519772 -0.6380416 9.090924 -6.087677 -0.08824235 9.385869 -5.863162 -0.08824235 9.481109 -5.952467 -0.6758812 9.399029 -4.816591 -0.08824241 9.674196 -5.952467 -4.755406 7.378734 -5.33182 -4.885377 7.505612 -5.33182 -4.176061 8.14029 -5.33182 -3.387752 8.673686 -5.33182 -2.534805 9.096087 -5.33182 -1.632753 9.399806 -5.221461 -0.08824235 9.645471 -5.161636 -0.08824235 9.653193 -5.33182 -0.6980218 9.579307 -4.919915 -0.08824068 9.672239 -5.633261 -0.08824235 9.55772 -5.399477 -0.08824235 9.615075 -5.281043 -0.08824235 9.636545 -6.301778 -0.08824235 9.274079 -6.519772 -1.507564 8.923946 -6.519772 -2.346687 8.641415 -6.519772 -3.14013 8.248479 -6.519772 -3.873445 7.752293 -6.519772 -4.533277 7.161894 -5.952467 -1.586541 9.22415 -5.952467 -2.465364 8.928254 -5.952467 -3.296347 8.516729 -5.952467 -4.064356 7.997066 -4.722769 5.393612 24.51055 -4.783641 5.62912 24.51662 -4.918426 5.572614 25.58922 -4.49429 5.059292 26.03116 -4.46048 5.074809 25.61206 -4.72647 5.138697 26.01705 -4.69164 5.154637 25.59336 -4.89309 5.319283 26.01085 -4.857601 5.335042 25.58508 -4.953886 5.557412 26.01405 -4.094648 5.168705 24.59378 -4.219744 5.114768 25.63669 -4.252655 5.100257 26.04975 -4.332 5.132484 24.55431 -4.559319 5.213879 24.52419 -4.583445 5.709367 23.44721 -4.522687 5.476781 23.44009 -4.362976 5.298004 23.45933 -4.141263 5.214398 23.50046 -3.908841 5.245305 23.55397 -4.308386 5.075375 26.94685 -4.282028 5.087191 26.51415 -4.521479 5.031687 26.93016 -4.510494 5.044552 26.49918 -4.733062 5.083126 26.91665 -4.733632 5.110211 26.48746 -4.902853 5.219899 26.90889 -4.90303 5.269923 26.48152 -4.998527 5.415966 26.90835 -4.981938 5.489044 26.48268 -4.345454 5.05861 27.37851 -4.53694 5.014604 27.35438 -4.730847 5.048841 27.33403 -4.89678 5.155955 27.32065 -5.00873 5.319158 27.31634 -5.201682 4.642155 28.68221 -5.227071 4.611792 28.73684 -5.200693 4.626662 28.75678 -5.016834 5.233189 27.60144 -4.897146 5.099009 27.61245 -5.031324 5.122941 27.8982 -4.911089 5.023894 27.9213 -5.051491 5.010436 28.14937 -4.941959 4.943452 28.18735 -5.06386 4.954831 28.2586 -4.964234 4.901674 28.3042 -5.085608 4.873744 28.40194 -5.006915 4.837297 28.45784 -5.0936 4.848359 28.44285 -5.023369 4.816004 28.50148 -5.113153 4.795145 28.52141 -5.064728 4.768656 28.58413 -5.118205 4.783413 28.53711 -5.07559 4.75751 28.60025 -5.125858 4.767263 28.55738 -5.11072 4.724943 28.63753 -5.134445 4.751601 28.575 -5.145011 4.736279 28.58871 -5.133551 4.706814 28.64908 -5.151966 4.728938 28.59236 -5.148456 4.696497 28.65044 -5.157133 4.725144 28.59188 -5.15941 4.689836 28.64776 -5.162043 4.723067 28.58852 -5.169682 4.684452 28.64187 -5.167989 4.72293 28.57993 -5.181868 4.679427 28.62958 -5.182641 4.652127 28.69828 -5.166646 4.66099 28.70683 -5.149621 4.670804 28.71189 -5.126484 4.684654 28.71313 -5.091057 4.706794 28.70437 -5.036435 4.742763 28.66897 -5.019492 4.754338 28.65289 -4.954577 4.800608 28.56817 -4.928508 4.82017 28.52269 -4.859799 4.87551 28.36111 -4.822889 4.908712 28.23777 -4.768718 4.96722 27.95762 -4.739017 5.01578 27.63524 -5.178712 4.639107 28.76806 -5.155438 4.652315 28.77562 -5.123942 4.670212 28.77968 -5.075865 4.69753 28.77413 -5.001754 4.739552 28.74149 -4.978706 4.75259 28.72579 -4.889817 4.802753 28.6404 -4.853727 4.823091 28.59372 -4.75675 4.877892 28.42596 -4.702819 4.908709 28.29702 -4.618334 4.958541 28.00355 -4.562975 4.994306 27.66684 -4.39187 5.037373 27.70315 -4.474855 4.998719 28.05454 -4.59036 4.943442 28.36084 -4.661199 4.908678 28.4949 -4.785756 4.845937 28.6679 -4.831528 4.822357 28.71547 -4.943511 4.763461 28.80077 -4.972445 4.747961 28.81595 -5.065459 4.697343 28.84537 -5.125971 4.663755 28.84749 -5.165807 4.641359 28.8405 -5.1954 4.624573 28.83039 -5.22352 4.608504 28.81632 -5.257574 4.58889 28.79248 2.526369 5.175535 30.80623 3.236579 4.961684 30.60563 2.490624 5.184874 30.99587 -3.236579 4.961684 30.60563 -2.527187 5.175398 30.80634 -2.490624 5.184874 30.99587 -2.241199 5.245616 30.8704 -1.688473 5.356421 31.28484 -1.782504 5.339851 30.95498 -0.844855 5.464247 31.46221 -1.026139 5.447213 31.05001 0 5.5 31.52036 -0.2612221 5.496588 31.09336 0 5.499998 31.09634 0.2077975 5.497796 31.09444 0.844855 5.464247 31.46221 0.9954622 5.450113 31.05261 1.688473 5.356421 31.28484 1.771881 5.341753 30.95639 2.145709 5.26707 30.88941 2.241125 5.245602 30.87003 -4.862604 4.771477 29.5275 -4.857738 4.741702 29.56633 -4.484885 4.928907 29.93561 -4.857101 4.737802 29.57141 -4.854477 4.704528 29.59206 -4.481842 4.854943 29.96969 -4.853491 4.667412 29.59977 -4.869098 4.789956 29.47452 -4.867965 4.786733 29.48376 -4.464345 4.988085 29.88337 -4.867126 4.784344 29.49061 -0.6869285 5.963276 31.55916 0 5.971604 31.62304 0 5.995923 31.56044 0 5.800218 31.72035 0 5.863906 31.70985 -0.3042767 5.795938 31.71332 -0.6912292 5.849408 31.67096 -3.362143 5.269895 30.8022 -3.283374 5.295079 30.84795 -3.377178 5.307687 30.78828 -2.672056 5.468787 31.15659 -2.756599 5.499691 31.111 -2.095444 5.597734 31.37967 -2.097005 5.658424 31.36921 -1.523992 5.693407 31.54236 -1.405415 5.776831 31.55739 -0.9627055 5.757641 31.64992 -0.7042499 5.777435 31.68275 -3.825206 5.108747 30.50217 -3.953422 5.090054 30.40627 -4.364194 4.890416 30.07639 -4.491527 4.833758 29.96164 -4.853475 4.661661 29.5999 0 5.927935 31.67405 -0.6910601 5.917913 31.62682 -1.405192 5.845813 31.51399 -2.09695 5.728148 31.32702 -2.756983 5.570348 31.0704 -3.37826 5.379398 30.74958 -3.955417 5.16288 30.36975 -1.396975 5.892302 31.44748 -2.085107 5.77642 31.26235 -2.742103 5.620921 31.00816 -3.360955 5.432637 30.69025 -3.936259 5.21902 30.31377 -4.880895 4.796605 29.37473 -4.427344 5.020947 29.82654 -3.9025 5.247827 30.25286 -3.331103 5.457592 30.62572 -2.716922 5.642364 30.94045 -2.065386 5.794856 31.19199 -1.383456 5.908421 31.37512 -0.9215472 5.959476 31.45633 -0.6801823 5.977941 31.48555 0 5.999992 31.52039 4.869098 4.789956 29.47452 4.880895 4.796605 29.37473 4.427344 5.020947 29.82654 0.1745681 5.798753 31.71805 0.7040879 5.777324 31.68277 0.6912292 5.849408 31.67096 0.6910601 5.917913 31.62682 0.6869285 5.963276 31.55916 4.867965 4.786733 29.48376 4.464345 4.988085 29.88337 4.862604 4.771477 29.5275 4.867853 4.785053 29.49094 4.481842 4.854943 29.96969 4.853491 4.667412 29.59977 4.854477 4.704528 29.59206 4.858353 4.742086 29.5667 4.484885 4.928907 29.93561 4.85723 4.737891 29.5715 4.491496 4.833662 29.96167 4.853475 4.661661 29.5999 3.377178 5.307687 30.78828 3.835165 5.105014 30.49508 3.953422 5.090054 30.40627 4.368214 4.888658 30.07286 0.8088719 5.770055 31.67071 1.462036 5.701877 31.55676 1.405415 5.776831 31.55739 2.094635 5.597291 31.37995 2.097005 5.658424 31.36921 2.723239 5.455326 31.13378 2.756599 5.499691 31.111 3.308234 5.287176 30.83365 3.362041 5.269875 30.80223 0.6801823 5.977941 31.48555 0.9215472 5.959476 31.45633 1.396975 5.892302 31.44748 3.936259 5.21902 30.31377 3.9025 5.247827 30.25286 3.360955 5.432637 30.69025 3.331103 5.457592 30.62572 2.742103 5.620921 31.00816 2.716922 5.642364 30.94045 2.085107 5.77642 31.26235 2.065386 5.794856 31.19199 1.383456 5.908421 31.37512 1.405192 5.845813 31.51399 2.09695 5.728148 31.32702 2.756983 5.570348 31.0704 3.37826 5.379398 30.74958 3.955417 5.16288 30.36975 2.792432 5.333982 31.10204 2.619654 5.378622 31.17951 2.600548 5.31233 31.17475 2.080372 5.498623 31.38469 1.775961 5.553703 31.47749 1.764552 5.496403 31.47177 1.519437 5.593165 31.54347 0.8721687 5.664968 31.6626 0.8834546 5.612333 31.65432 0.8567354 5.479485 31.54032 0 5.511063 31.58596 0 5.544246 31.64582 0.8710479 5.53231 31.61285 0 5.570029 31.67237 0 5.594555 31.6903 0 5.656752 31.71562 0.7041797 5.677179 31.68276 0.225416 5.697659 31.71651 0 5.699971 31.72035 2.161832 5.482349 31.35711 2.524075 5.192985 31.0686 3.278663 4.964453 30.67417 3.330292 5.003701 30.73781 2.564809 5.238107 31.13614 3.375991 5.07345 30.7742 3.404237 5.150934 30.7771 1.711784 5.36885 31.36084 1.739987 5.418649 31.43142 -2.798155 5.332206 31.09937 -3.404237 5.150934 30.7771 -3.375991 5.07345 30.7742 -2.600548 5.31233 31.17475 -2.619599 5.378365 31.17953 -1.603521 5.580633 31.52305 -1.77593 5.553504 31.47749 -1.764552 5.496403 31.47177 -2.080402 5.498466 31.38468 -2.189546 5.476486 31.34746 -0.3218585 5.695013 31.71252 -0.7042607 5.676735 31.68276 -0.8834546 5.612333 31.65432 -0.8885903 5.663136 31.6604 -0.9801338 5.655222 31.64734 -0.8710479 5.53231 31.61285 -0.8567354 5.479485 31.54032 -1.711784 5.36885 31.36084 -3.278663 4.964453 30.67417 -3.330292 5.003701 30.73781 -2.564809 5.238107 31.13614 -2.524075 5.192985 31.0686 -1.739987 5.418649 31.43142 7.078166 -0.0881949 25.21474 7.21737 -0.08824235 24.14222 7.126508 0.104874 24.88275 6.936469 -0.08819967 26.17299 6.868191 0.6833459 26.89267 6.777283 -0.08824288 27.12359 6.821067 1.229964 27.24561 6.820416 1.147903 27.25045 6.878383 1.171799 26.81583 6.824418 0.9916682 27.22065 6.825277 0.9751179 27.21424 6.830754 0.8961049 27.17338 6.839698 0.8124499 27.10655 6.857073 0.7173075 26.97631 7.498113 1.660254 21.72296 6.888547 1.660253 26.73899 6.876612 1.652412 26.8292 6.855988 1.598946 26.98446 6.854128 1.591204 26.99842 6.844299 1.539742 27.07211 6.834512 1.464074 27.14532 6.829036 1.403115 27.1862 6.821642 1.255054 27.24133 8.156448 1.660254 14.91285 8.540538 1.660254 9.518077 7.548333 1.660254 21.26637 -6.827284 -0.08824199 27.12359 -6.918191 0.6833459 26.89267 -6.965495 -0.08820617 26.30521 -7.014231 0.4634659 26.16081 -7.267369 -0.08824235 24.14222 -8.206447 1.660254 14.91285 -8.590538 1.660254 9.518077 -8.590538 -0.08824235 9.518077 -7.598332 1.660254 21.26637 -7.548123 -0.08824235 21.72287 -6.928382 1.171799 26.81583 -6.871068 1.229964 27.24561 -6.871642 1.255054 27.24133 -6.879036 1.403115 27.1862 -6.884512 1.464074 27.14532 -6.894299 1.539742 27.07211 -6.905987 1.598946 26.98446 -6.926611 1.652412 26.8292 -6.938547 1.660253 26.73899 -6.907073 0.7173075 26.97631 -6.889698 0.8124498 27.10655 -6.888045 0.8253765 27.11891 -6.880754 0.8961049 27.17338 -6.874417 0.9916682 27.22065 -6.870417 1.147903 27.25045 -8.403983 -0.08824235 12.35046 -8.18424 -0.08824235 15.18046 -7.88838 -0.08824235 18.45382 2.629096 -0.08823424 31.73804 2.012854 -0.08822983 31.84878 -5.496989 -0.08827412 30.02316 -5.877294 -0.08834075 29.53081 6.372452 -0.08868765 28.52919 6.583096 -0.08839291 27.94366 6.646917 -0.08840274 27.71839 -1.658438 -0.08823788 31.88197 -2.330564 -0.08822673 31.80976 1.370553 -0.0882436 31.88723 -1.420553 -0.0882436 31.88723 -5.030616 -0.08824324 30.49855 -4.583862 -0.08837145 30.86019 -4.069788 -0.08839207 31.19031 -3.521233 -0.08825957 31.46045 -2.955893 -0.08823734 31.66363 3.220599 -0.08824259 31.55933 3.785817 -0.08833342 31.31503 4.322384 -0.08841729 31.006 -6.192836 -0.08824419 29.01168 -6.340804 -0.08850139 28.71448 -6.347731 -0.08851891 28.69943 4.798526 -0.08828061 30.65551 5.297482 -0.08828628 30.18852 5.710959 -0.08826524 29.69405 5.723942 -0.08827233 29.67645 6.077955 -0.08829718 29.12942 6.296866 -0.08852732 28.70131 -6.464773 -0.08860945 28.4257 -6.576221 -0.08825534 28.12175 6.754339 -0.08819949 27.24699 6.729796 -0.0881868 27.36835 6.723718 -0.08819717 27.39693 -6.672878 -0.08834409 27.80695 -6.700274 -0.08833581 27.70567 -6.772356 -0.0881803 27.40328 -6.785202 -0.08816838 27.34247 -8.590537 -0.08824217 7.039315 -8.488288 -0.08824789 7.189965 -8.180745 -0.08824235 7.550899 -5.079227 -0.08824235 9.662714 -5.237448 -0.08824235 9.644564 -6.937872 -0.08824235 8.794965 -6.760029 -0.08824235 8.959172 -6.569722 -0.08824235 9.108301 -6.368845 -0.08824235 9.24116 -6.159196 -0.08824235 9.356839 -5.93816 -0.08824235 9.456551 -5.70931 -0.08824235 9.538264 -5.475869 -0.08824235 9.600838 -5.356972 -0.08824235 9.625136 -8.180745 3.661355 6.118076 -7.818094 4.160254 6.118076 -8.180745 3.138208 6.568257 -7.739268 4.160254 6.235899 -6.937872 0.5037307 8.790441 -8.180745 0.5734549 7.539928 -8.180745 1.484004 7.377892 -6.937872 1.348743 8.685356 -6.937872 0.7745007 8.769534 -6.937872 4.160254 7.34358 -6.937872 3.689247 7.702195 -8.180745 2.538403 6.95238 -6.937872 2.956561 8.136088 -8.180745 2.34887 7.050233 -6.937872 2.171491 8.465867 -6.937872 1.989594 8.5249 -3.753912 5.306026 22.81137 -3.984991 5.278536 22.75857 -4.257845 5.834012 21.9575 -4.421139 5.772979 22.70461 -4.36148 5.542019 22.69833 -4.199274 5.604687 21.95202 -4.204152 5.363664 22.71779 -4.044318 5.426777 21.9717 -3.82772 5.34017 22.01214 -3.598041 5.364284 22.06426 1.97963 5.811696 20.21224 2.058671 5.796206 20.23976 2.393667 5.72352 20.39441 4.267955 5.093464 26.28191 2.701267 5.646584 20.60023 3.152815 5.515476 21.33225 3.460846 5.413251 21.61504 3.296425 5.469131 21.28333 3.246172 5.485608 21.20176 3.021617 5.555836 20.90396 2.754859 5.632164 20.64373 3.753912 5.306026 22.81137 3.598041 5.364284 22.06426 3.575647 5.372424 21.96641 5.5045 4.441503 28.56866 5.383459 4.514897 28.68372 5.459979 4.468759 28.63583 5.314891 4.555492 28.84282 4.894917 4.789229 29.35917 1.628095 5.873009 20.12691 1.266713 5.923312 20.09808 0.9202471 5.959596 20.09808 0 6 20.09808 -0.9202471 5.959596 20.09808 -1.266713 5.923312 20.09808 -1.628095 5.873009 20.12691 -1.97963 5.811696 20.21224 -2.058671 5.796206 20.23976 -2.393667 5.72352 20.39441 -2.701267 5.646584 20.60023 -3.021617 5.555836 20.90396 -3.246172 5.485608 21.20176 -2.754859 5.632164 20.64373 -3.296425 5.469131 21.28333 -3.460846 5.413251 21.61504 -3.575647 5.372424 21.96641 -4.267955 5.093464 26.28191 -4.894917 4.789229 29.35917 -5.314891 4.555492 28.84282 -5.383459 4.514897 28.68372 -5.459979 4.468759 28.63583 -5.5045 4.441503 28.56866 4.421139 5.772979 22.70461 4.36148 5.542019 22.69833 3.984991 5.278536 22.75857 3.82772 5.34017 22.01214 4.204152 5.363664 22.71779 4.044318 5.426777 21.9717 4.199274 5.604687 21.95202 4.257845 5.834012 21.9575 5.76482 4.326274 28.0084 5.760289 4.340973 27.99444 5.589877 4.463058 28.18681 5.666759 4.338495 28.33933 5.813889 4.239004 28.11041 5.774084 4.302325 28.03277 5.443775 4.499101 28.46762 5.620469 4.393008 28.26068 5.40528 4.582051 28.37353 5.325086 4.570333 28.57795 5.288954 4.652186 28.47966 5.167984 4.734011 28.56429 5.16792 4.877598 28.34787 5.126662 4.897109 28.36002 5.098462 4.910253 28.34567 5.036774 5.148636 27.85477 5.07934 5.167117 27.86332 5.126507 5.165829 27.86273 5.167772 5.145057 27.85311 5.167623 5.350407 27.32632 5.126352 5.372122 27.33326 5.079224 5.373411 27.33367 5.036714 5.353987 27.32746 5.014306 5.329329 27.31959 4.502925 5.051588 26.26507 4.730629 5.123912 26.25209 4.898923 5.293875 26.24594 4.96927 5.522555 26.24803 4.846287 5.758402 24.9525 4.583445 6.071684 23.44721 5.013043 5.396394 27.09445 5.043406 5.427001 27.10249 5.084385 5.442181 27.10615 5.128102 5.439013 27.10474 5.166149 5.418107 27.09853 4.995734 5.528698 26.48847 5.025964 5.559997 26.49216 5.066718 5.575678 26.49283 5.11022 5.572749 26.49038 5.148177 5.551774 26.48525 7.988296 4.060254 6.118076 7.965324 4.060254 6.118076 7.894696 4.160254 6.118076 8.350758 3.091142 6.34324 8.540536 1.362086 6.931185 8.540536 0.5370756 7.07831 8.478466 2.482197 6.555866 8.53752 1.837497 6.775895 8.540535 1.660256 6.83764 7.128403 4.160254 7.149258 7.029446 4.160254 7.270226 -4.751871 0.3006758 9.443826 -4.751871 0.4365516 9.673192 -4.816591 0.5522398 9.667741 -4.751871 0.8952908 9.64042 -4.816591 1.516593 9.547814 -4.751871 2.076326 9.41514 -4.816591 2.076326 9.41514 -4.816591 2.455538 9.297327 -4.751871 3.202414 8.993807 -4.816591 3.351483 8.920972 -4.816591 4.060254 8.511529 -4.751871 4.060254 8.511529 -4.751871 5.899752 6.126949 -7.894696 4.160254 6.118076 -7.128403 4.160254 7.149258 -6.809328 4.160254 7.500751 -6.53192 0.5224947 9.129794 -6.836282 4.060254 7.549577 -6.53192 2.281364 8.787487 -6.53192 3.109322 8.43969 -6.53192 3.882034 7.982096 -6.53192 1.41367 9.018964 -5.964616 0.5396327 9.439741 -5.343967 0.5496606 9.621095 -5.343967 1.507668 9.501955 -5.343967 2.440434 9.253117 -5.343967 3.330484 8.87924 -5.236988 4.060254 8.476075 -5.964616 3.248846 8.716988 -5.964616 4.058115 8.237744 -5.674119 4.060254 8.361153 -6.764874 4.060254 7.629373 -6.432842 4.060254 7.936964 -6.067822 4.060254 8.181486 -5.964616 1.47297 9.323668 -5.964616 2.381716 9.081237 -4.583445 6.071684 23.44721 -4.846287 5.758402 24.9525 -4.96927 5.522555 26.24803 -4.898923 5.293875 26.24594 -4.730629 5.123912 26.25209 -4.502925 5.051588 26.26507 -4.991941 5.52192 26.48754 -5.043406 5.427001 27.10249 -5.036714 5.353987 27.32746 -5.013043 5.396394 27.09445 -5.014306 5.329329 27.31959 -5.084385 5.442181 27.10615 -5.079224 5.373411 27.33367 -5.04467 5.35958 27.32925 -5.166149 5.418107 27.09853 -5.167623 5.350407 27.32632 -5.128102 5.439013 27.10474 -5.129518 5.371245 27.33298 -5.085715 5.374513 27.33402 -5.148177 5.551774 26.48525 -5.108346 5.573289 26.49054 -5.06286 5.575027 26.4929 -5.021172 5.55663 26.49182 -5.126507 5.165829 27.86273 -5.167772 5.145057 27.85311 -5.16792 4.877598 28.34787 -5.036774 5.148636 27.85477 -5.126662 4.897109 28.36002 -5.167984 4.734011 28.56429 -5.07934 5.167117 27.86332 -5.098462 4.910253 28.34567 -5.288954 4.652186 28.47966 -5.325086 4.570333 28.57795 -5.443775 4.499101 28.46762 -5.40528 4.582051 28.37353 -5.666759 4.338495 28.33933 -5.620469 4.393008 28.26068 -5.81352 4.239407 28.10998 -5.774084 4.302325 28.03277 -5.76482 4.326274 28.0084 -5.589877 4.463058 28.18681 -5.760289 4.340973 27.99444 -5.916116 4.160254 27.92228 -5.94347 4.164105 27.81063 -5.946388 4.160254 27.80893 -5.778436 4.326303 27.97407 -5.894656 4.220409 27.85016 -5.91156 4.164116 27.93057 -5.878001 4.191195 27.99254 -5.847614 4.266384 27.89797 -5.826169 4.230121 28.0881 -5.889699 4.160254 28.03945 -5.832523 4.215263 28.12692 -5.855132 4.160254 28.15528 -4.936623 4.748984 29.4149 -4.956518 4.686646 29.46163 -4.951388 4.612292 29.49179 -5.524203 4.367189 28.71891 -5.749685 4.160254 28.37608 -5.502192 4.426884 28.68045 -5.357065 4.514 28.89051 -5.378537 4.453598 28.93131 -5.522969 4.297925 28.74589 -5.376207 4.383007 28.95934 -4.884935 4.160254 29.38854 -4.942455 4.196611 29.41331 -4.961331 4.160254 29.36911 -4.868174 4.233678 29.48214 -4.866108 4.250311 29.49908 -4.862219 4.286174 29.5306 -4.855311 4.375949 29.58552 -4.993801 4.254925 29.42022 -4.853467 4.445475 29.59991 -5.027012 4.323826 29.40491 -4.864107 4.267703 29.51535 -4.879299 4.160254 29.38852 -4.870297 4.217743 29.46459 -5.03129 4.160254 29.33371 -5.083475 4.160254 29.29819 -5.24367 4.160254 29.13783 -4.876535 4.178646 29.41177 -4.866533 4.247304 29.4956 -4.865052 4.259867 29.50768 -4.863612 4.272814 29.51936 -4.86291 4.279441 29.52504 -4.542396 4.392253 29.7512 -4.152264 4.607017 30.08823 -4.215758 4.653997 30.13332 -4.318521 4.473818 29.84751 -3.289247 4.943379 30.57592 -3.880444 4.972028 30.46257 -3.73039 4.798548 30.39679 -3.777636 4.749293 30.26791 -3.734452 4.768381 30.29766 -3.61287 4.820035 30.37869 -4.80833 4.160254 29.37333 -4.827728 4.160254 29.38247 -4.609642 4.442515 29.78614 -4.492198 4.669648 29.96102 -4.662049 4.516836 29.79082 -4.638838 4.478043 29.79252 -4.3745 4.735149 30.06732 -4.267765 4.727201 30.14848 -4.24431 4.688661 30.1451 -3.838321 4.913533 30.47766 -3.815567 4.875414 30.46895 -3.788594 4.841814 30.45166 -0.4727192 4.938261 30.25515 -0.9703766 4.89265 30.21341 0 4.892761 30.2451 0 5.15796 30.38998 0 5.197507 30.42311 -0.4973149 5.213336 30.43752 0 5.360254 30.61448 0 5.386605 30.65883 -0.5222783 5.40614 30.71275 -4.756264 4.160254 29.3456 -3.597848 4.727859 30.03135 -4.016624 4.531044 29.79619 -4.391366 4.327251 29.53807 -4.605744 4.160254 29.30066 -3.15085 4.90656 30.23564 -3.273525 4.946891 30.5299 -2.767203 5.108952 30.71598 -1.086082 5.393558 30.75595 -0.5290414 5.441569 30.80486 0 5.476834 30.89328 0 4.941045 30.26327 -0.9283816 4.585113 30.14671 -0.8897718 4.236011 30.14986 -0.4628742 4.262429 30.1837 -8.1061e-7 4.287819 30.19615 0 4.594561 30.19615 0 4.646092 30.19734 -2.606362 4.160254 29.77175 -2.169393 4.160254 29.90907 -1.847707 4.41048 29.99197 -1.767024 4.160255 30.0091 -1.260514 4.210036 30.10248 -3.763357 4.319658 29.51467 -4.035978 4.160254 29.33269 -3.915362 4.160254 29.35896 -3.388282 4.160254 29.5085 -3.025472 4.160254 29.62866 -2.812695 4.427487 29.77212 -2.709273 4.160254 29.7367 -2.380656 4.582309 29.92244 -1.929537 4.71246 30.04594 -1.455896 4.817185 30.14369 -2.666093 5.06806 30.41368 -2.160349 5.204318 30.55928 -1.629723 5.314234 30.67415 -1.0208 5.166414 30.39239 -1.531383 5.08884 30.317 -2.029265 4.981277 30.21125 -2.503163 4.847789 30.07753 -2.956571 4.689318 29.91454 -3.373677 4.51363 29.72822 -3.644037 4.160254 29.43049 -3.705286 4.160254 29.41312 -1.072141 5.358298 30.6646 -1.608659 5.279245 30.58406 -2.132151 5.169695 30.47101 -2.630849 5.033867 30.32781 -3.108528 4.872837 30.15284 -3.548608 4.694604 29.95227 -3.96044 4.498231 29.72166 -4.328477 4.294788 29.46894 -4.238685 4.160254 29.29971 -4.514537 4.160254 29.28977 -0.8733401 4.160254 30.15157 0 4.160254 30.19615 0.5501995 4.256436 30.17853 0.8733401 4.160254 30.15157 1.767024 4.160255 30.0091 1.328946 4.20443 30.09195 0.8897062 4.236254 30.1499 2.156117 4.160254 29.91276 2.607232 4.160254 29.77145 1.847707 4.41048 29.99197 4.787979 4.160254 29.36145 4.80833 4.160254 29.37333 4.333321 4.464817 29.83464 0.4973149 5.213336 30.43752 0.9283816 4.585113 30.14671 0.4727192 4.938261 30.25515 0.9703766 4.89265 30.21341 0.5290414 5.441569 30.80486 1.086082 5.393558 30.75595 1.629723 5.314234 30.67415 2.160349 5.204318 30.55928 3.840975 4.720393 30.22362 3.336953 4.926525 30.54849 3.273525 4.946891 30.5299 2.767203 5.108952 30.71598 4.016624 4.531044 29.79619 4.096965 4.594695 30.03104 4.391366 4.327251 29.53807 4.614952 4.160254 29.30233 3.96044 4.498231 29.72166 4.280185 4.160254 29.29516 4.328477 4.294788 29.46894 4.346382 4.160254 29.28983 2.709099 4.160254 29.73676 2.99432 4.160254 29.63926 2.812695 4.427487 29.77212 3.122883 4.160254 29.59573 3.385815 4.160254 29.50929 2.380656 4.582309 29.92244 1.929537 4.71246 30.04594 1.455896 4.817185 30.14369 2.666093 5.06806 30.41368 3.15085 4.90656 30.23564 3.597848 4.727859 30.03135 1.0208 5.166414 30.39239 1.531383 5.08884 30.317 2.029265 4.981277 30.21125 2.503163 4.847789 30.07753 2.956571 4.689318 29.91454 3.373677 4.51363 29.72822 3.763357 4.319658 29.51467 3.646888 4.160254 29.42967 3.847904 4.160254 29.37532 0.5222783 5.40614 30.71275 1.072141 5.358298 30.6646 1.608659 5.279245 30.58406 2.132151 5.169695 30.47101 2.630849 5.033867 30.32781 3.108528 4.872837 30.15284 3.548608 4.694604 29.95227 4.492267 4.670331 29.96097 4.393274 4.725656 30.05071 4.267765 4.727201 30.14848 4.609642 4.442515 29.78614 4.862219 4.286174 29.5306 4.638838 4.478043 29.79252 4.855311 4.375949 29.58552 4.662049 4.516836 29.79082 4.853467 4.445475 29.59991 4.876535 4.178646 29.41177 4.868174 4.233678 29.48214 4.542396 4.392253 29.7512 4.866533 4.247304 29.4956 4.865052 4.259867 29.50768 4.863612 4.272814 29.51936 4.86291 4.279441 29.52504 4.879299 4.160254 29.38852 4.841014 4.160254 29.38608 4.152264 4.607017 30.08823 3.73039 4.798548 30.39679 3.966667 4.935084 30.39901 3.838321 4.913533 30.47766 3.815567 4.875414 30.46895 3.788594 4.841814 30.45166 4.24431 4.688661 30.1451 4.215758 4.653997 30.13332 4.864107 4.267703 29.51535 4.870297 4.217743 29.46459 4.866108 4.250311 29.49908 4.993801 4.254925 29.42022 4.942455 4.196611 29.41331 5.119185 4.160254 29.26951 4.973123 4.160254 29.36419 5.24367 4.160254 29.13783 5.027012 4.323826 29.40491 4.951388 4.612292 29.49179 5.376207 4.383007 28.95934 5.417393 4.160254 28.90123 5.522969 4.297925 28.74589 5.749685 4.160254 28.37608 -5.417393 4.160254 28.90123 4.936623 4.748984 29.4149 4.956518 4.686646 29.46163 5.502192 4.426884 28.68045 5.832523 4.215263 28.12692 5.855132 4.160254 28.15528 5.378537 4.453598 28.93131 5.524203 4.367189 28.71891 5.357065 4.514 28.89051 5.826169 4.230121 28.0881 5.878001 4.191195 27.99254 5.889699 4.160254 28.03945 5.91156 4.164116 27.93057 5.916116 4.160254 27.92228 5.778436 4.326303 27.97407 5.946388 4.160254 27.80893 5.94347 4.164105 27.81063 5.894656 4.220409 27.85016 5.847614 4.266384 27.89797 7.487408 2.479025 21.25973 6.82779 2.479025 26.73097 7.266562 3.403098 21.23565 6.607549 3.403098 26.70187 8.345944 3.109136 9.518077 7.938435 4.160254 9.518077 7.557458 4.160254 14.86348 8.530434 1.99198 9.518077 8.479029 2.479023 9.518077 8.09537 2.479025 14.90782 7.873964 3.403098 14.88957 6.950853 4.160254 21.20123 6.292704 4.160254 26.66027 6.274278 4.160254 26.78869 6.197446 4.160254 27.19179 6.303894 3.958141 27.16633 5.207242 4.160254 29.31656 5.525559 4.002905 29.0091 5.464178 4.160254 28.95336 4.817178 4.160254 29.76299 4.692435 4.03205 29.9802 5.095435 3.792023 29.74 4.376169 4.160254 30.16042 6.669672 0.202739 27.78673 6.494049 0.152161 28.3239 5.722518 -0.06864362 29.68484 4.979751 0.322695 30.59265 4.566229 0.2462767 30.91026 4.124121 0.1774356 31.18704 3.65978 0.1170202 31.4197 3.180003 0.06563186 31.6062 2.201644 -0.008973538 31.83913 2.190609 0.50093 31.92017 1.369785 0.20115 31.94135 2.185745 1.016253 31.95587 1.368984 0.8914989 32.0125 2.187126 1.532747 31.94574 1.369377 1.592178 32.00297 2.194738 2.046181 31.88985 1.370477 2.277692 31.91352 2.208483 2.55234 31.7889 2.228251 3.047021 31.64362 1.372021 2.925819 31.75292 1.373278 3.285306 31.62958 2.253855 3.526238 31.45531 1.37445 3.552845 31.5208 2.285028 3.986209 31.22577 1.378015 4.160255 31.21472 1.95862 4.160254 31.17926 2.772783 3.907472 31.14944 2.526652 4.160254 31.07443 3.258092 3.80592 31.03173 2.967043 4.160254 30.94254 3.734216 3.681736 30.87206 3.505752 4.160254 30.71488 5.463336 3.531532 29.47003 5.846668 3.670788 28.76707 5.910223 4.007658 28.2943 5.766892 4.160254 28.41697 6.179452 3.614169 28.09868 6.239833 3.827617 27.64742 6.007483 4.160254 27.84598 6.1424 4.160254 27.41381 3.20492 2.926637 31.42309 3.186407 2.463516 31.55916 3.653615 1.950714 31.46498 3.683532 2.843717 31.24514 4.118312 1.904937 31.22971 4.146501 2.74623 31.02255 4.560826 1.852775 30.94996 4.587045 2.635148 30.75724 4.974799 1.794872 30.62904 4.998831 2.511839 30.45237 4.010489 4.160254 30.42539 4.19426 3.535738 30.67098 4.631469 3.369379 30.43019 5.03955 3.184709 30.15254 3.228898 3.375286 31.24671 6.619654 1.124845 28.15664 6.621873 1.378111 28.14028 6.457852 1.450803 28.59093 6.630146 1.624316 28.07925 6.468874 1.779121 28.50972 6.644175 1.855533 27.9756 6.487561 2.087372 28.37183 6.663453 2.064417 27.83286 6.513228 2.365751 28.182 6.6873 2.24452 27.65576 6.544961 2.605679 27.94658 6.714905 2.390372 27.45003 6.581672 2.799901 27.67321 6.745349 2.497652 27.22223 6.622136 2.942708 27.37062 6.777678 2.563285 26.97925 6.665086 3.030056 27.04794 5.99783 0.5860308 29.44353 6.0176 0.1013197 29.29803 6.268157 0.2760452 28.8933 5.699584 0.4938511 29.85358 5.690508 1.078182 29.92028 5.348802 1.067316 30.31412 5.354613 1.732032 30.27143 5.37627 2.378017 30.11219 5.412967 2.984293 29.84192 6.694649 0.03170961 27.60107 6.649046 0.4042226 27.93957 6.473339 0.4530344 28.4768 6.251643 0.6807931 29.01491 5.990009 1.089535 29.50104 5.695641 1.665184 29.88256 5.714772 2.235661 29.74186 5.747189 2.771097 29.50305 5.79169 3.254429 29.17441 6.633497 0.6299256 28.05451 6.623577 0.87272 28.12771 6.460123 0.7767831 28.5742 6.454895 1.113029 28.6127 6.245109 1.101206 29.06297 6.248805 1.523536 29.03579 5.994433 1.595339 29.46852 6.262579 1.93401 28.93439 6.010922 2.086919 29.3472 6.285925 2.319339 28.76226 6.038868 2.548339 29.14126 6.317983 2.667252 28.52532 6.077233 2.964896 28.85783 6.357604 2.967037 28.23156 6.12464 3.323774 28.50649 6.403425 3.209655 27.89053 6.453913 3.38801 27.51312 6.507487 3.497085 27.11072 2.691711 0.02360862 31.74584 2.680981 0.5193035 31.82463 2.676252 1.020266 31.85934 2.677595 1.522367 31.84949 2.684996 2.021493 31.79515 2.698359 2.513548 31.697 2.71758 2.994446 31.55574 2.742474 3.460313 31.37263 3.645588 1.03177 31.52392 3.165113 1.025441 31.71553 3.169669 0.5430007 31.6821 3.166406 1.508978 31.70604 3.64682 1.492607 31.51487 3.173535 1.989651 31.6537 5.359076 0.4056286 30.23863 4.968351 1.057102 30.6764 4.553791 1.04769 31.00162 4.110748 1.039211 31.28525 -1.419464 0.4112927 31.97164 -1.41911 1.019908 32.01693 -1.419518 1.658381 31.99786 -1.420535 2.302662 31.90881 -1.422121 2.928183 31.75219 -1.424422 3.532037 31.52989 -1.428015 4.160255 31.21472 -6.795349 2.497652 27.22223 -5.513337 3.531532 29.47003 -5.575559 4.002905 29.0091 -5.896667 3.670788 28.76707 -6.544048 0.152161 28.3239 -6.699047 0.4042226 27.93957 -6.719673 0.202739 27.78673 -6.657549 3.403098 26.70187 -6.353893 3.958141 27.16633 -6.342704 4.160254 26.66027 -6.227078 4.160254 27.27841 -6.744649 0.03170961 27.60107 -2.244738 2.046181 31.88985 -2.258483 2.55234 31.7889 -2.278252 3.047021 31.64362 -2.303854 3.526238 31.45531 -2.335028 3.986209 31.22577 -1.658354 4.160254 31.20916 -2.139228 4.160254 31.16142 -2.240609 0.50093 31.92017 -2.251644 -0.008973538 31.83913 -2.741711 0.02360862 31.74584 -3.230003 0.06563192 31.6062 -3.70978 0.1170202 31.4197 -4.174121 0.1774356 31.18704 -4.61623 0.2462767 30.91026 -5.029751 0.322695 30.59265 -5.749583 0.4938511 29.85358 -5.772518 -0.06864362 29.68484 -6.0676 0.1013197 29.29803 -4.481766 4.160254 30.11541 -4.703868 4.160254 29.92151 -4.742434 4.03205 29.9802 -4.76502 4.160254 29.86384 -5.165934 4.160254 29.43094 -4.681469 3.369379 30.43019 -4.24426 3.535738 30.67098 -4.250673 4.160254 30.29403 -3.784216 3.681736 30.87206 -3.76132 4.160254 30.60665 -3.695588 1.03177 31.52392 -3.219669 0.5430007 31.6821 -3.215113 1.025441 31.71553 -2.730981 0.5193035 31.82463 -2.726252 1.020266 31.85934 -2.235745 1.016253 31.95587 -2.727594 1.522367 31.84949 -3.216407 1.508978 31.70604 -3.69682 1.492607 31.51487 -4.160748 1.039211 31.28525 -3.223535 1.989651 31.6537 -3.703615 1.950714 31.46498 -4.168312 1.904937 31.22971 -4.610826 1.852775 30.94996 -4.603791 1.04769 31.00162 -5.024799 1.794872 30.62904 -5.018351 1.057102 30.6764 -6.680146 1.624316 28.07925 -6.671873 1.378111 28.14028 -6.507852 1.450803 28.59093 -6.669654 1.124845 28.15664 -6.504895 1.113029 28.6127 -6.673577 0.87272 28.12771 -6.510123 0.7767831 28.5742 -6.683497 0.6299256 28.05451 -6.523339 0.4530344 28.4768 -5.960224 4.007658 28.2943 -6.229452 3.614169 28.09868 -6.557487 3.497085 27.11072 -6.289833 3.827617 27.64742 -6.048019 4.160254 27.87231 -5.08955 3.184709 30.15254 -5.145435 3.792023 29.74 -5.048831 2.511839 30.45237 -5.462967 2.984293 29.84192 -5.84169 3.254429 29.17441 -6.17464 3.323774 28.50649 -6.453424 3.209655 27.89053 -6.503912 3.38801 27.51312 -6.672136 2.942708 27.37062 -6.715086 3.030056 27.04794 -6.827679 2.563285 26.97925 -6.87779 2.479025 26.73097 -5.409075 0.4056286 30.23863 -5.398801 1.067316 30.31412 -5.404613 1.732032 30.27143 -5.42627 2.378017 30.11219 -5.764772 2.235661 29.74186 -5.79719 2.771097 29.50305 -6.088868 2.548339 29.14126 -6.127233 2.964896 28.85783 -6.367983 2.667252 28.52532 -6.407604 2.967037 28.23156 -6.594961 2.605679 27.94658 -6.631672 2.799901 27.67321 -6.764905 2.390372 27.45003 -6.737301 2.24452 27.65576 -6.563228 2.365751 28.182 -6.335925 2.319339 28.76226 -6.060923 2.086919 29.3472 -5.745641 1.665184 29.88256 -5.740509 1.078182 29.92028 -6.713453 2.064417 27.83286 -6.694175 1.855533 27.9756 -6.537561 2.087372 28.37183 -6.518875 1.779121 28.50972 -6.312579 1.93401 28.93439 -6.298805 1.523536 29.03579 -6.044433 1.595339 29.46852 -6.29511 1.101206 29.06297 -6.040009 1.089535 29.50104 -6.301643 0.6807931 29.01491 -6.047831 0.5860308 29.44353 -6.318157 0.2760453 28.8933 -2.703758 4.160254 31.04107 -2.822783 3.907472 31.14944 -2.792474 3.460313 31.37263 -2.76758 2.994446 31.55574 -2.74836 2.513548 31.697 -3.254218 4.160254 30.8518 -3.308092 3.80592 31.03173 -3.278898 3.375286 31.24671 -3.25492 2.926637 31.42309 -3.733532 2.843717 31.24514 -4.196501 2.74623 31.02255 -4.637045 2.635148 30.75724 -5.394089 4.160254 29.13146 -5.514393 4.160254 28.95303 -5.809773 4.160254 28.43144 -3.236407 2.463516 31.55916 -2.734996 2.021493 31.79515 -2.237126 1.532747 31.94574 -7.316562 3.403098 21.23565 -7.000853 4.160254 21.20123 -7.607458 4.160254 14.86348 -7.537408 2.479025 21.25973 -8.145369 2.479025 14.90782 -8.529255 2.479046 9.518077 -8.47493 2.781136 9.518077 -7.923964 3.403098 14.88957 -8.306472 3.403093 9.518077 -8.130843 3.859392 9.518077 -7.988434 4.160254 9.518077 -8.590537 0.5310543 7.030819 -8.590537 1.348167 6.885411 -8.590538 1.660254 6.786891 -8.254039 3.552575 6.118065 -8.437327 2.947818 6.345674 -8.474883 2.78123 6.403094 -8.5517 2.312997 6.561108 -7.965324 4.060254 6.118076 -8.038207 4.060254 6.118075 -1.296873 6.171486 19.66506 -1.303949 6.229716 19.63614 -1.745999 6.175205 19.66691 -1.274795 5.98981 19.84808 -1.28438 6.068689 19.74452 -1.704328 6.01351 19.77326 -3.802445 5.349552 21.90502 -4.170489 5.614096 21.83393 -4.229693 5.842539 21.84008 -4.023488 5.661116 21.41142 -4.085371 5.885311 21.41843 -3.814402 5.725039 21.01538 -3.87867 5.943852 21.02037 -3.750799 5.743797 20.91849 -3.815495 5.961113 20.9225 -3.468066 5.823338 20.56664 -3.533198 6.034685 20.56514 -3.673307 5.396424 21.52166 -3.489462 5.460107 21.16212 -3.433501 5.478787 21.07414 -3.18454 5.557952 20.75442 -2.890708 5.643219 20.47719 -2.831882 5.659241 20.43107 -2.495301 5.744285 20.21378 -2.130342 5.823929 20.0518 -2.044414 5.840806 20.02315 -1.662859 5.907224 19.93504 -1.271305 5.961094 19.90674 -2.114009 5.945304 19.86491 -2.20636 5.92795 19.89484 -2.599078 5.845935 20.0645 -2.962134 5.758161 20.29293 -3.025693 5.7416 20.34151 -3.343739 5.65334 20.63413 -3.614093 5.571186 20.97276 -3.674993 5.551768 21.06615 -3.875447 5.485475 21.44851 -4.016642 5.436576 21.85731 -2.177058 6.108137 19.76337 -2.274188 6.091112 19.79477 -2.686988 6.010831 19.97248 -3.068142 5.925207 20.21113 -3.134809 5.909085 20.26181 -3.208287 6.112278 20.26122 -3.197844 6.114648 20.25286 -3.130471 6.129754 20.20066 -2.743775 6.210354 19.95368 -2.322638 6.286502 19.7681 -2.223271 6.302729 19.73508 -1.781341 6.366961 19.63268 -1.327033 6.419661 19.59808 -4.257845 6.3481 21.9575 -4.420988 6.218749 22.70392 0 6.5 19.59808 0 6.25 19.66506 0 6.066987 19.84808 1.274795 5.98981 19.84808 1.28438 6.068689 19.74452 1.296873 6.171486 19.66506 1.303949 6.229716 19.63614 1.327033 6.419661 19.59808 1.271305 5.961094 19.90674 1.662859 5.907224 19.93504 1.704328 6.01351 19.77326 4.229693 5.842539 21.84008 4.170489 5.614096 21.83393 4.085371 5.885311 21.41843 4.023488 5.661116 21.41142 3.878178 5.943988 21.01958 3.814402 5.725039 21.01538 3.750799 5.743797 20.91849 3.815495 5.961113 20.9225 3.533198 6.034685 20.56514 3.468066 5.823338 20.56664 3.208287 6.112278 20.26122 3.134809 5.909085 20.26181 3.197844 6.114648 20.25286 3.130471 6.129754 20.20066 3.068142 5.925207 20.21113 2.743775 6.210354 19.95368 2.686988 6.010831 19.97248 2.322638 6.286502 19.7681 2.274188 6.091112 19.79477 2.223271 6.302729 19.73508 2.177058 6.108137 19.76337 1.781341 6.366961 19.63268 1.745999 6.175205 19.66691 2.114009 5.945304 19.86491 2.20636 5.92795 19.89484 2.599078 5.845935 20.0645 2.962134 5.758161 20.29293 3.025693 5.7416 20.34151 3.343739 5.65334 20.63413 3.614093 5.571186 20.97276 3.674993 5.551768 21.06615 3.875447 5.485475 21.44851 4.016642 5.436576 21.85731 2.044414 5.840806 20.02315 2.130342 5.823929 20.0518 2.495301 5.744285 20.21378 2.831882 5.659241 20.43107 2.890708 5.643219 20.47719 3.18454 5.557952 20.75442 3.433501 5.478787 21.07414 3.489462 5.460107 21.16212 3.673307 5.396424 21.52166 3.802445 5.349552 21.90502 4.420988 6.218749 22.70392 4.257845 6.3481 21.9575 5.555075 4.619215 28.00914 5.618107 4.775323 27.53662 5.497139 5.19792 26.53135 5.683008 4.869236 27.04824 5.747063 4.89976 26.56436 5.905928 4.685451 26.58535 6.189651 4.160254 26.90612 6.233298 4.160254 26.6286 6.042635 4.160254 27.51796 4.856874 5.800333 24.95945 4.884453 5.834219 24.96257 4.923732 5.853559 24.96126 4.967175 5.854642 24.95577 5.006447 5.837261 24.94715 4.593673 6.111577 23.45339 4.61907 6.144552 23.4548 4.655232 6.164889 23.45118 4.695887 6.169061 23.44318 4.733984 6.156345 23.43217 4.529117 6.316924 22.69847 4.489531 6.311464 22.70611 4.430587 6.257947 22.70908 4.454769 6.290657 22.70985 4.3993 6.437879 21.94111 4.566976 6.306133 22.68819 4.323294 6.440178 21.95809 4.352016 6.44663 21.95286 4.36179 6.446829 21.95076 4.305596 6.431237 21.96052 4.266862 6.386579 21.96175 4.271414 6.395473 21.9622 4.289891 6.418979 21.96197 8.069151 4.160254 5.866152 8.121812 4.060254 5.895327 7.128403 4.829033 6.528289 7.128403 4.291558 7.040389 7.977837 4.322231 5.82349 7.128403 4.936932 6.410456 7.725702 4.710577 5.753076 7.128403 5.406076 5.821259 7.406833 5.112723 5.752132 7.667192 4.790782 5.745914 7.988296 4.060254 8.531866 7.938435 4.160254 8.457828 6.720095 4.060254 7.654565 5.007121 4.060254 8.303975 5.044208 4.060254 8.303703 5.465343 4.060254 8.262065 5.884425 4.060254 8.147418 6.156127 4.060254 8.030099 6.279934 4.060254 7.964125 6.644125 4.060254 7.717393 6.673798 4.53336 7.324492 7.023329 5.506052 5.853134 6.673798 5.215098 6.659066 6.721626 5.767977 5.896427 6.673798 5.800088 5.907174 6.155146 6.02997 6.062107 6.592266 5.869802 5.897552 6.238537 6.119658 5.858643 5.867277 6.341554 5.761216 5.592378 6.171529 6.157515 5.77802 6.38929 5.729837 5.007121 6.282838 6.093921 5.007121 6.7205 5.327472 5.388804 6.574004 5.557203 6.155146 4.713036 7.5356 5.592378 4.823679 7.665599 5.007121 6.219328 6.18973 5.007121 5.592053 6.99597 5.007121 4.86104 7.709494 5.007121 5.288287 7.316349 5.592378 5.549075 6.957559 6.155146 5.421793 6.8438 3.470556 6.838388 20.33849 3.784348 6.739926 20.67284 4.174486 6.774768 15.49407 4.075222 6.620805 21.10024 4.269321 6.520918 21.51173 4.451726 6.433351 21.5578 5.249684 5.948446 21.64699 7.589188 4.608353 9.695969 6.544638 4.608353 21.79173 6.81935 4.160254 21.82244 7.418426 4.160254 15.7742 5.954151 5.334158 21.72573 4.310128 6.496845 21.62439 5.044893 6.433351 15.56923 3.819936 6.726931 20.71763 3.258939 6.962769 15.41501 2.629584 6.983281 19.78225 3.019167 6.935785 19.99243 3.112391 6.919569 20.05376 3.697886 6.962769 9.45841 3.68076 6.986829 4.724651 4.926863 6.747146 5.273137 4.615134 6.774768 9.514408 4.477431 6.870142 5.006588 4.04258 6.9492 4.81918 5.487156 6.433351 9.567644 6.288591 5.948446 9.616569 6.996127 5.334158 9.659765 5.844841 5.948446 15.63832 6.551067 5.334158 15.6993 7.143028 4.608353 15.75042 7.865097 4.160254 9.712814 -4.751871 4.060254 8.303975 -5.007121 4.060254 8.303975 -5.044208 4.060254 8.303703 -5.465343 4.060254 8.262065 -5.884425 4.060254 8.147418 -6.720095 4.060254 7.654565 -6.644125 4.060254 7.717393 -6.279934 4.060254 7.964125 -6.156127 4.060254 8.030099 -4.751871 6.066366 6.408202 -4.751871 5.288287 7.316349 -3.133275 6.496527 5.745761 -2.994066 6.498435 5.742452 -2.994066 6.498435 7.137559 -2.515682 6.345283 6.879032 -2.745102 6.452385 7.059824 -2.650032 6.416529 6.330822 -2.815052 6.472008 5.787946 -3.266476 6.476288 5.780627 -3.251122 6.479566 7.105708 -3.494817 6.395622 5.915476 -3.494817 6.395622 6.964005 -3.672225 6.282838 6.093921 -3.705495 6.255199 6.726964 -3.874154 6.066366 6.408202 2.815052 6.472008 5.787946 2.650141 6.416576 6.330413 2.515682 6.345283 6.879032 3.494817 6.395622 6.964005 3.715751 6.246174 6.14962 3.705495 6.255199 6.726964 3.874154 6.066366 6.408202 2.994066 6.498435 5.742452 3.133275 6.496527 5.745761 2.994066 6.498435 7.137559 3.266476 6.476288 5.780627 3.251122 6.479566 7.105708 3.494817 6.395622 5.915476 3.668856 6.285504 6.089828 2.745102 6.452385 7.059824 -8.038269 4.060254 7.609943 -8.121812 4.060254 5.895327 -7.725702 4.710577 5.753076 -7.667192 4.790782 5.745914 -7.128403 4.936932 6.410456 -7.406833 5.112723 5.752132 -7.128403 5.406076 5.821259 -7.128403 4.291558 7.040389 -8.069151 4.160254 5.866152 -7.977837 4.322231 5.82349 -5.007121 5.288287 7.316349 -5.007121 4.86104 7.709494 -5.592378 4.823679 7.665599 -5.388804 6.574004 5.557203 -5.007121 6.7205 5.327472 -5.007121 6.282838 6.093921 -5.77802 6.38929 5.729837 -5.592378 6.171529 6.157515 -5.867277 6.341554 5.761216 -6.238537 6.119658 5.858643 -6.155146 6.02997 6.062107 -6.592266 5.869802 5.897552 -6.673798 5.800088 5.907174 -6.721626 5.767977 5.896427 -6.673798 5.215098 6.659066 -7.023329 5.506052 5.853134 -6.673798 4.53336 7.324492 -6.155146 4.713036 7.5356 -5.007121 6.219328 6.18973 -5.007121 5.592053 6.99597 -5.592378 5.549075 6.957559 -6.155146 5.421793 6.8438 -3.68076 6.986829 4.724651 -4.04258 6.9492 4.81918 -4.477431 6.870142 5.006588 -4.926863 6.747146 5.273137 -1.327033 6.9 19.59808 -4.173714 6.405993 21.65129 -3.208652 6.784899 20.26152 -3.378256 6.741327 20.4089 -3.675844 6.644655 20.73177 -3.709581 6.631896 20.77504 -3.878172 6.561824 21.01957 -3.951471 6.5277 21.14469 -4.135149 6.429629 21.54239 -3.038401 6.821031 20.13409 -1.761216 6.9 19.62966 -2.186256 6.9 19.72375 -2.324527 6.898 19.76877 -2.580067 6.883585 19.87229 -2.949918 6.836953 20.07494 -4.323294 6.440178 21.95809 -4.305596 6.431237 21.96052 -4.220706 6.487536 21.65224 -4.271414 6.395473 21.9622 -4.187691 6.452201 21.65604 -4.264993 6.503684 21.64079 -4.352016 6.44663 21.95286 -4.3993 6.437879 21.94111 -4.149245 6.475387 21.547 -3.965716 6.571727 21.14819 -3.723289 6.67428 20.77661 -3.689426 6.686849 20.73306 -3.390347 6.782136 20.40781 -3.048146 6.860731 20.13061 -2.95897 6.876426 20.07091 -2.585953 6.922323 19.86635 -2.188437 6.938269 19.71646 -4.181736 6.510558 21.54241 -3.995733 6.606273 21.1405 -3.750051 6.708244 20.76579 -3.715734 6.720746 20.72187 -3.412642 6.815547 20.39369 -3.065853 6.893749 20.1139 -2.975483 6.909361 20.05362 -2.597474 6.954978 19.84708 -2.194646 6.970711 19.69569 -4.225107 6.527003 21.52967 -4.035058 6.623898 21.12328 -3.784552 6.727039 20.74474 -3.749594 6.739679 20.70038 -3.441097 6.835504 20.3691 -3.088541 6.914527 20.08675 -2.996721 6.930304 20.02593 -2.612821 6.976419 19.81749 -2.203937 6.992388 19.66461 -4.310128 6.496845 21.62439 -4.269321 6.520918 21.51173 -4.075222 6.620805 21.10024 -3.819936 6.726931 20.71763 -3.784348 6.739926 20.67284 -3.470556 6.838388 20.33849 -3.112391 6.919569 20.05376 -3.019167 6.935785 19.99243 -2.629584 6.983281 19.78225 -1.762111 6.934612 19.62355 -1.765455 6.970711 19.60068 -1.77068 6.993819 19.56496 -1.327033 6.993819 19.53269 -1.327033 6.934612 19.5919 -1.327033 6.938269 19.59046 -1.327033 6.970711 19.56879 -1.327033 6.992388 19.53635 1.327033 6.9 19.59808 4.187691 6.452201 21.65604 4.220706 6.487536 21.65224 4.264993 6.503684 21.64079 3.965716 6.571727 21.14819 4.135149 6.429629 21.54239 4.149245 6.475387 21.547 4.173714 6.405993 21.65129 3.390347 6.782136 20.40781 3.675844 6.644655 20.73177 3.689426 6.686849 20.73306 3.709581 6.631896 20.77504 3.723289 6.67428 20.77661 3.878172 6.561824 21.01957 3.951471 6.5277 21.14469 4.225107 6.527003 21.52967 4.035058 6.623898 21.12328 3.784552 6.727039 20.74474 3.749594 6.739679 20.70038 3.441097 6.835504 20.3691 3.088541 6.914527 20.08675 2.996721 6.930304 20.02593 2.612821 6.976419 19.81749 4.181736 6.510558 21.54241 3.995733 6.606273 21.1405 3.750051 6.708244 20.76579 3.715734 6.720746 20.72187 3.412642 6.815547 20.39369 3.065853 6.893749 20.1139 2.975483 6.909361 20.05362 2.597474 6.954978 19.84708 3.048146 6.860731 20.13061 2.95897 6.876426 20.07091 2.585953 6.922323 19.86635 2.324527 6.898 19.76877 2.580067 6.883585 19.87229 2.949918 6.836953 20.07494 3.038401 6.821031 20.13409 3.208652 6.784899 20.26152 3.378256 6.741327 20.4089 2.186256 6.9 19.72375 2.188437 6.938269 19.71646 2.194646 6.970711 19.69569 2.203937 6.992388 19.66461 1.761216 6.9 19.62966 1.327033 6.993819 19.53269 1.327033 6.992388 19.53635 1.327033 6.970711 19.56879 1.327033 6.934612 19.5919 1.327033 6.938269 19.59046 1.77068 6.993819 19.56496 1.765455 6.970711 19.60068 1.762111 6.934612 19.62355 -4.566976 6.306133 22.68819 -4.733984 6.156345 23.43217 -4.529117 6.316924 22.69847 -4.695887 6.169061 23.44318 -4.489531 6.311464 22.70611 -4.655232 6.164889 23.45118 -4.454769 6.290657 22.70985 -4.61907 6.144552 23.4548 -4.430587 6.257947 22.70908 -4.593673 6.111577 23.45339 -4.856874 5.800333 24.95945 -5.006447 5.837261 24.94715 -4.967175 5.854642 24.95577 -4.923732 5.853559 24.96126 -4.884453 5.834219 24.96257 -5.683008 4.869236 27.04824 -5.47567 5.221631 26.52851 -5.555075 4.619215 28.00914 -5.618107 4.775323 27.53662 -6.111206 4.160254 27.26889 -5.747066 4.899764 26.56437 -5.885955 4.713625 26.58271 -6.233298 4.160254 26.6286 -7.988434 4.160254 7.53011 -7.865097 4.160254 9.712814 -7.418426 4.160254 15.7742 -6.81935 4.160254 21.82244 -4.451726 6.433351 21.5578 -6.996127 5.334158 9.659765 -7.589188 4.608353 9.695969 -5.487156 6.433351 9.567644 -6.288591 5.948446 9.616569 -4.615134 6.774768 9.514408 -3.697886 6.962769 9.45841 -3.258939 6.962769 15.41501 -4.174486 6.774768 15.49407 -5.044893 6.433351 15.56923 -5.249684 5.948446 21.64699 -5.954151 5.334158 21.72573 -6.544638 4.608353 21.79173 -7.143028 4.608353 15.75042 -6.551067 5.334158 15.6993 -5.844841 5.948446 15.63832 -4.05 5.5 17.75362 -4.05 5.187492 17.75362 -4.05 5.5 10.76767 -4.05 5.187492 8.798735 -4.05 5.5 8.107208 -4.05 4.332663 8.798735 4.05 5.5 8.107208 4.05 4.332663 8.798735 4.05 5.187492 8.798735 4.05 5.5 10.76767 4.05 5.187492 17.75362 4.05 5.5 17.75362 3.69899 5.5 19.44157 3.201562 5.5 19.47867 3.973879 5.5 11.15035 3.757107 5.5 11.47477 4.126976 5.5 19.15728 4.357304 5.5 18.698 4.329169 5.5 18.18497 3.201562 5.5 11.75611 3.432683 5.5 11.69155 2.348197 6.212371 7.6852 3.93944 5.957052 7.836451 3.632207 6.31304 7.625564 3.424727 6.427135 7.557974 3.196237 6.489249 7.521178 2.959548 6.495901 7.517238 2.727931 6.446716 7.546375 -2.348197 6.212371 7.6852 -3.424727 6.427135 7.557974 -3.632207 6.31304 7.625564 -2.727931 6.446716 7.546375 -2.959548 6.495901 7.517238 -3.196237 6.489249 7.521178 -3.93944 5.957052 7.836451 -2.092771 5.78933 9.673161 -2.092771 5.78933 10.76767 -2.126121 5.882683 10.76767 -2.155398 5.946863 8.949193 -2.330841 6.194845 10.76767 -2.243734 6.091553 8.284241 -2.727931 6.446716 10.76767 -3.05 6.5 10.76767 -3.196237 6.489249 10.76767 -3.432683 6.42388 10.76767 -3.632207 6.31304 10.76767 -3.757107 6.207107 10.76767 -3.973879 5.882683 10.76767 -3.93944 5.957052 10.76767 2.243734 6.091553 8.284241 3.973879 5.882683 10.76767 3.93944 5.957052 10.76767 3.757107 6.207107 10.76767 3.632207 6.31304 10.76767 3.432683 6.42388 10.76767 3.196237 6.489249 10.76767 3.05 6.5 10.76767 2.727931 6.446716 10.76767 2.330841 6.194845 10.76767 2.092771 5.78933 10.76767 2.092771 5.78933 9.673161 2.126121 5.882683 10.76767 2.155398 5.946863 8.949193 3.453406 5.415845 19.49157 3.69899 5.326875 19.44157 3.930431 5.236617 19.32813 4.126976 5.154951 19.15728 4.27108 5.092074 18.94479 4.357304 5.053214 18.698 4.376731 5.04433 18.43933 4.329169 5.065997 18.18497 4.216358 5.116253 17.9489 -3.69899 5.5 19.44157 -4.126976 5.5 19.15728 -4.357304 5.5 18.698 -3.973879 5.5 11.15035 -3.757107 5.5 11.47477 -3.432683 5.5 11.69155 -4.329169 5.5 18.18497 -3.201562 5.5 19.47867 -3.201562 5.5 11.75611 3.903553 5.882683 11.12122 3.320598 6.42388 11.03826 3.403553 6.42388 10.91411 3.703281 6.207107 11.03826 3.196447 6.42388 11.12122 2.779402 6.42388 11.03826 2.696447 6.42388 10.91411 2.903553 6.42388 11.12122 2.115037 5.784776 10.9792 2.196446 5.882683 11.12122 2.18104 5.770982 11.18176 2.287066 5.747894 11.36473 2.396718 5.882683 11.42095 2.428882 5.715211 11.52125 2.598953 5.673271 11.64318 2.696447 5.882683 11.62122 2.672118 5.654299 11.68057 2.788852 5.62286 11.72511 3.05 5.882683 11.69155 2.99103 5.564976 11.76381 3.403553 5.882683 11.62122 3.194513 5.502254 11.75717 3.050123 5.547226 11.76655 2.396718 6.207107 11.03826 2.55 6.207107 11.26767 2.779402 6.207107 11.42095 3.05 6.207107 11.47477 3.55 6.207107 11.26767 3.703281 5.882683 11.42095 3.320598 6.207107 11.42095 3.05 6.42388 11.15035 1.927662 5.821537 9.52515 1.293337 5.920042 9.07245 0.6541778 5.979602 8.798735 -0.6541778 5.979602 8.798735 -1.291425 5.920279 9.071361 -3.703281 6.207107 11.03826 -2.903553 6.42388 11.12122 -2.779402 6.42388 11.03826 -2.55 6.207107 11.26767 -3.403553 6.42388 10.91411 -3.320598 6.42388 11.03826 -3.196447 6.42388 11.12122 -2.255919 5.754796 11.31949 -2.436224 5.713462 11.52774 -2.396718 5.882683 11.42095 -3.187105 5.504617 11.75821 -3.403553 5.882683 11.62122 -3.05 5.882683 11.69155 -3.050625 5.547074 11.76656 -2.790266 5.622471 11.72555 -2.696447 5.882683 11.62122 -2.67267 5.654153 11.68082 -2.16186 5.775036 11.13585 -3.55 6.207107 11.26767 -3.320598 6.207107 11.42095 -3.05 6.207107 11.47477 -2.196446 5.882683 11.12122 -2.396718 6.207107 11.03826 -2.696447 6.42388 10.91411 -3.903553 5.882683 11.12122 -3.703281 5.882683 11.42095 -2.779402 6.207107 11.42095 -3.05 6.42388 11.15035 -2.114915 5.784801 10.97863 -4.216795 5.116062 17.94957 -4.376728 5.044331 18.43928 -4.329169 5.065997 18.18497 -4.271001 5.092109 18.94495 -4.357304 5.053214 18.698 -3.93079 5.236472 19.32789 -4.126976 5.154951 19.15728 -3.453079 5.415959 19.4916 -3.69899 5.326875 19.44157 3.194513 5.502254 8.798735 -3.187105 5.504617 8.798735 -1.923875 5.822243 8.798735 1.927662 5.821537 8.798735 -2.643773 5.661716 11.26294 -3.629146 5.352883 18.61615 3.629146 5.352883 18.61615 + + + + + + + + + + -0.2895382 -0.1711384 -0.9417427 -0.5154939 -0.4731221 -0.714438 -0.5780622 -0.02747631 -0.8155301 -0.4023695 -0.0231052 -0.9151858 -0.1887641 -0.03995555 -0.9812093 -0.1886367 -0.1755824 -0.9662231 -0.1887887 -0.1755823 -0.9661935 -0.1891111 -0.2797041 -0.9412772 -0.1063323 -0.07787227 -0.9912767 -0.1000905 -0.007371544 -0.994951 -0.04241001 0.09586173 -0.9944908 -0.3244353 -0.03847819 -0.9451249 -0.3116405 -0.04149246 -0.9492937 -0.2898741 -0.04751062 -0.9558848 -0.2506396 -0.03375577 -0.9674918 -0.3231226 -0.03299814 -0.9457816 -0.1760374 0.03488594 -0.9837651 -0.1381115 -0.002746462 -0.9904129 -0.6668553 -0.024248 -0.7447926 -0.6338672 -0.04102861 -0.7723529 -0.6182159 -0.03595417 -0.7851857 -0.6060837 -0.03284561 -0.7947224 -0.6731097 -0.4667845 -0.5736162 -0.7037252 -0.4161781 -0.5758184 -0.6121894 -0.422422 -0.668419 -0.1156636 -0.5256741 -0.8427864 -0.2021556 -0.5301657 -0.8234425 -0.02227544 -0.5373346 -0.843075 -0.1845051 -0.4301425 -0.8837055 -0.09795033 -0.4922781 -0.8649093 -0.09801375 -0.5277088 -0.8437517 -0.02736699 -0.5038189 -0.8633758 -0.2895401 -0.4408304 -0.8496088 -0.290266 -0.4963694 -0.8181462 -0.2922318 -0.4997345 -0.8153932 -0.5140997 -0.0288794 -0.8572441 -0.470852 -0.04515254 -0.881056 -0.4703629 -0.1577818 -0.8682532 -0.2895312 -0.1711373 -0.9417451 -0.2895324 -0.3094325 -0.9057718 -0.5972849 -0.2592781 -0.7589637 -0.1239342 -0.3567675 -0.9259359 -0.1189702 -0.3537405 -0.9277466 -0.4703671 -0.2852842 -0.8350855 -0.4703614 -0.4064298 -0.7833104 -0.4703646 -0.4064301 -0.7833082 -0.4706029 -0.5118405 -0.7187157 -0.4337831 -0.4458498 -0.7829753 -0.6337385 -0.4441217 -0.6333495 -0.6342358 -0.3879602 -0.6687539 -0.6163799 -0.3626668 -0.6989626 -0.6339625 -0.3370549 -0.69605 -0.6333215 -0.2501819 -0.732334 -0.6110349 -0.2723152 -0.7432905 -0.6342889 -0.211025 -0.7437379 -0.1236755 -0.4570213 -0.8808155 -0.2895354 -0.4408295 -0.8496109 -0.2895314 -0.3094334 -0.9057719 -0.4703654 -0.285285 -0.8350862 -0.4703665 -0.1577828 -0.8682511 -0.6333199 -0.1383686 -0.7614198 -0.6333213 -0.138368 -0.7614188 0 0.8603653 -0.509678 0 0.8603653 -0.5096779 0 0.8603657 -0.5096774 0 0.8603659 -0.5096769 0 -0.5040147 -0.8636951 0.1089965 -0.5130465 -0.8514124 0 -0.5374646 -0.8432863 1 0 0 1 6.32833e-7 0 1 -2.45797e-7 0 1 5.04988e-7 0 0 1 0 0 1 -2.97617e-7 0 1 2.49116e-7 0 1 4.98233e-7 0 1 0 0 1 1.94133e-7 0 1 0 0.8337618 -0.5472953 0.07286518 0.5620495 -0.7734696 0.2929936 0.6124846 -0.7351361 0.2905813 0.6863391 -0.7258385 0.04579466 0.07500314 -0.9939628 0.08007812 0.04453909 -0.9663461 0.2533602 0.9372626 -0.2891719 0.1947264 0.9735082 -0.1724321 0.1501631 0.9744394 -0.1516211 0.1657679 0.9551157 -0.2360618 0.1789657 0.9473245 -0.2636582 0.1818257 0.9402145 -0.2785891 0.1959207 0.9249437 -0.3170945 0.2095959 0.9866212 -0.1053836 0.1243907 0.9873881 -0.103165 0.1200903 0.9936239 -0.0274074 0.1093633 0.9920728 -0.05636543 0.1123152 0.9947988 -0.01040452 0.1013266 0.9962332 -0.01085638 0.08603304 0.9953659 -0.0250709 0.09283488 0.9974479 -0.01103323 0.07054167 0.9971219 -0.01086497 0.07503312 0.9978736 -0.01088017 0.06426626 0.9967068 -0.0463581 0.06653302 0.9921112 -0.1058672 0.06713932 0.9921388 -0.1055449 0.06723725 0.9782733 -0.1959491 0.06771582 0.9597771 -0.2719167 0.06992501 0.9579054 -0.2789611 0.06780916 0.8983007 -0.4330749 0.07417684 0.9241785 -0.3760216 0.06709635 0.9001332 -0.4296499 0.07184273 0.8884093 -0.4554594 0.05732166 0.8369721 -0.5445428 0.05432438 0.8349301 -0.5475628 0.05537992 0.8119769 -0.5812863 0.05291551 0.226494 -0.9738323 0.01874136 0.227155 -0.9736671 0.01931679 0.6959427 -0.6612604 0.2799975 0.407242 -0.8626903 0.2998658 0.07918012 -0.9534631 0.2909272 0.08009546 -0.9534649 0.2906708 0.1707518 -0.9415448 0.2904089 0.1936797 -0.9376146 0.2887336 0.2278028 -0.9273868 0.2967485 0.29565 -0.9069965 0.2999142 0.4612503 -0.834954 0.3001671 0.4018763 -0.8648592 0.3008556 0.4061846 -0.8741597 0.2661936 0.3224507 -0.9089025 0.2644277 0.3254393 -0.9149543 0.2386379 0.2018582 -0.9514963 0.2321814 0.2030521 -0.9510468 0.2329806 0.05300313 -0.9739616 0.2204306 0.06702214 -0.9782627 0.1962404 0.3466777 -0.8882254 0.3014469 0.3168649 -0.9002887 0.2984579 0.3210182 -0.9092962 0.2648164 0.1973795 -0.9456299 0.2585064 0.198706 -0.9451091 0.2593932 0.06168633 -0.966844 0.2478051 0.05599462 -0.973955 0.2197186 0.4039139 -0.9146652 0.01553189 0.4343306 -0.9002161 0.03111481 0.4327354 -0.8998324 0.05515235 0.5131856 -0.8562112 0.05952417 0.5113065 -0.8551243 0.08560562 0.5867728 -0.8048885 0.0886141 0.5848094 -0.8031636 0.113694 0.6548961 -0.7469283 0.1149322 0.6528836 -0.7446422 0.138748 0.7169381 -0.6833693 0.137863 0.7149041 -0.6806159 0.1602317 0.7733084 -0.6143094 0.1569018 0.7712912 -0.6111801 0.1776765 0.8234686 -0.5407786 0.171634 0.8215004 -0.5373882 0.1906594 0.8873381 -0.4258959 0.1767594 0.5837424 -0.7571979 0.2930806 0.560436 -0.7745132 0.2933276 0.5643038 -0.7828094 0.2622421 0.4889171 -0.8311498 0.2648586 0.491779 -0.8369393 0.240179 0.4117251 -0.8791248 0.2400457 0.4145313 -0.8844094 0.2144387 0.3306868 -0.9196384 0.2119237 0.33341 -0.9243323 0.1856007 0.2099492 -0.9612148 0.1788504 0.210864 -0.9609002 0.1794639 0.07224023 -0.9830123 0.1687253 0.05344814 -0.9873327 0.1493905 0.5163818 -0.8023526 0.2992998 0.4836179 -0.8231948 0.2974293 0.4876057 -0.8317746 0.2653146 0.4075556 -0.8736526 0.2657624 0.4104893 -0.8795977 0.2404301 0.3267139 -0.9145901 0.2382919 0.3295715 -0.919969 0.2122259 0.2060503 -0.9566937 0.2056223 0.2071087 -0.9563119 0.2063338 0.06901133 -0.9783125 0.1952999 0.05925643 -0.9822341 0.1780586 0.5720998 -0.8196241 0.03030264 0.5905495 -0.8059971 0.04024928 0.5890206 -0.8056374 0.06327223 0.6591765 -0.7490361 0.06656783 0.6574398 -0.7480303 0.09068399 0.7214753 -0.6862751 0.09219515 0.7196934 -0.6847123 0.114937 0.7779806 -0.6177977 0.1143341 0.7761939 -0.6157725 0.1354526 0.8281607 -0.544622 0.1324267 0.8264029 -0.5422404 0.1517686 0.8916772 -0.4295377 0.1428612 0.7430229 -0.6117206 0.2715049 0.6976853 -0.6596997 0.2793413 0.7013812 -0.6675663 0.2498393 0.6369769 -0.7269527 0.2565158 0.6396129 -0.7322913 0.2337625 0.5694215 -0.7869883 0.237505 0.5720599 -0.7919574 0.2134266 0.4967213 -0.8409925 0.2144754 0.4993267 -0.8454893 0.1892641 0.419219 -0.8882177 0.1879491 0.42175 -0.8921421 0.1618937 0.3377511 -0.9277747 0.158614 0.3401764 -0.9310604 0.1319341 0.2168142 -0.9681923 0.1248805 0.2174345 -0.9679994 0.1252974 0.07322716 -0.990687 0.1147921 0.06535816 -0.9918623 0.1092594 0.6467713 -0.7068272 0.2865 0.632144 -0.7199189 0.28655 0.6358211 -0.7277805 0.2570354 0.5655525 -0.7820747 0.2617434 0.5683094 -0.7876605 0.2379401 0.4929516 -0.8363646 0.239777 0.4956854 -0.8415144 0.2148246 0.4156144 -0.8839821 0.2141037 0.4182859 -0.8885972 0.1882342 0.33437 -0.9240379 0.1853395 0.3369469 -0.9280296 0.1588325 0.2135385 -0.9650482 0.1519318 0.2143085 -0.964796 0.1524487 0.07074141 -0.9873887 0.1416307 0.06584817 -0.9897136 0.1270084 0.7254194 -0.686622 0.04813647 0.7249107 -0.6871803 0.04783052 0.7234917 -0.6868563 0.06919604 0.7817439 -0.6195026 0.07136738 0.7802005 -0.6186119 0.09277176 0.8320404 -0.5468947 0.09281748 0.8304969 -0.5455427 0.1125084 0.8953353 -0.4319314 0.1086728 0.8569855 -0.4563228 0.2394689 0.8112484 -0.5243465 0.2587214 0.8149437 -0.5321143 0.2296106 0.762299 -0.6010572 0.240064 0.7646265 -0.6057771 0.2199556 0.7059167 -0.6708397 0.227279 0.7083048 -0.675333 0.2054986 0.6440923 -0.7355877 0.2098947 0.6464992 -0.739738 0.1866188 0.576393 -0.7951586 0.1883987 0.5787709 -0.7988539 0.1638804 0.5034216 -0.8484634 0.16333 0.5057431 -0.8516138 0.1377597 0.4255386 -0.8947777 0.1352401 0.4277744 -0.8973129 0.1088057 0.3435932 -0.9332589 0.1047456 0.345715 -0.9351193 0.07767289 0.2224131 -0.9724142 0.07030832 0.2227304 -0.972326 0.07052212 0.05952745 -0.9972802 0.04345971 0.07758659 -0.9951365 0.06069344 0.05170553 -0.9949553 0.08596873 0.2202443 -0.9705109 0.09798562 0.2197729 -0.9706497 0.09766852 0.3431024 -0.9334245 0.1048783 0.3408271 -0.9308472 0.1317592 0.4249127 -0.8950468 0.1354266 0.4225295 -0.891816 0.1616574 0.5026811 -0.8488559 0.163571 0.5002146 -0.8450303 0.1889684 0.5755494 -0.7956945 0.1887153 0.5730344 -0.7913538 0.2130514 0.6431795 -0.7362746 0.2102853 0.6406552 -0.7315248 0.2333072 0.7049573 -0.6716841 0.2277629 0.7024672 -0.6666336 0.2492779 0.7613199 -0.6020622 0.2406513 0.758099 -0.5951886 0.2665268 0.8075776 -0.528839 0.2610511 0.7833426 -0.6194689 0.05130946 0.7831877 -0.6196732 0.05120885 0.7818557 -0.619367 0.07131814 0.8336611 -0.5474418 0.0729171 0.8322347 -0.5466171 0.09271091 0.8970553 -0.4323555 0.09143573 0.9022188 -0.4196621 0.09942346 0.9580231 -0.2709091 0.09380924 0.9578082 -0.2717437 0.09358942 0.9908216 -0.1051231 0.08498173 0.9907472 -0.1059871 0.08477514 0.9949437 -0.05814689 0.08189004 0.996603 -0.01129359 0.08157819 0.6532715 -0.7558418 0.04404062 0.6606065 -0.7492434 0.04725986 0.6593097 -0.748923 0.06652116 0.723365 -0.6869848 0.0692448 0.7217176 -0.6860336 0.09209579 0.7799816 -0.6188725 0.09287554 0.7783122 -0.6174098 0.1141721 0.8302036 -0.5459548 0.1126748 0.8285503 -0.5440856 0.1321944 0.8938854 -0.4302904 0.1257743 0.8988492 -0.417616 0.1329179 0.9555548 -0.2691902 0.1202156 0.9551713 -0.2706883 0.1198986 0.9892087 -0.1042434 0.1029545 0.9890743 -0.1057894 0.1026683 0.9946401 -0.04017394 0.09527379 0.9952255 -0.01105827 0.09697395 0.4953387 -0.8680005 0.03485387 0.5146392 -0.8564613 0.04025763 0.5133391 -0.8561223 0.0594778 0.5888738 -0.8057408 0.06331986 0.5870599 -0.8046897 0.08851778 0.6571711 -0.7482547 0.09078103 0.6552932 -0.7466027 0.1147834 0.7193327 -0.6850652 0.115092 0.7174249 -0.682902 0.1376462 0.7757585 -0.6162721 0.1356745 0.7738583 -0.6136908 0.1566114 0.8259125 -0.5429024 0.1520711 0.8240507 -0.5400095 0.1712608 0.8900322 -0.426993 0.1597487 0.8948506 -0.4143106 0.1661002 0.9526013 -0.2667033 0.1463563 0.952048 -0.2688601 0.1460102 0.9870542 -0.1051689 0.1210932 0.9877876 -0.1077942 0.1124999 0.3180594 -0.9477557 0.02444213 0.3495446 -0.936446 0.02979314 0.348169 -0.936079 0.05034464 0.4325715 -0.8999084 0.05519855 0.4306429 -0.8987944 0.08194833 0.5110076 -0.8552937 0.08569693 0.5089746 -0.8535088 0.1116586 0.5843857 -0.8034512 0.1138405 0.582282 -0.8010628 0.1387301 0.6523561 -0.7450661 0.1389538 0.6502102 -0.7421563 0.1625757 0.7143035 -0.6811809 0.1605091 0.7121472 -0.6778365 0.1827131 0.7706296 -0.6119087 0.1780388 0.7685002 -0.6082333 0.1986451 0.8208126 -0.5382761 0.1911163 0.818754 -0.534397 0.209909 0.8855127 -0.4224656 0.1933654 0.890167 -0.4099256 0.1989065 0.9491815 -0.2634627 0.1721687 0.9484581 -0.266254 0.1718609 0.9772047 -0.1513825 0.1488428 0.969955 -0.1985156 0.140637 0.06429404 -0.9979298 0.00163871 0.133777 -0.9668325 0.2175743 0.07669436 -0.9969336 0.01553803 0.06553089 -0.9978086 0.009145557 0.07705932 -0.9964688 0.03334456 0.2248892 -0.9734362 0.04297626 0.2247243 -0.9734792 0.04286509 0.3480051 -0.9361376 0.05038851 0.3460444 -0.9350048 0.07758533 0.430329 -0.8989363 0.08204019 0.4282428 -0.8971062 0.1086673 0.5085223 -0.8537599 0.1117992 0.5063434 -0.851288 0.1375696 0.5817192 -0.8014368 0.1389315 0.5794773 -0.7983946 0.1636226 0.6495588 -0.7426686 0.1628394 0.6472795 -0.739137 0.1862948 0.7114233 -0.6785034 0.1830575 0.7091462 -0.6745754 0.205085 0.7677341 -0.6090583 0.1990793 0.7655044 -0.6048539 0.219442 0.8179733 -0.5353808 0.2104451 0.8158252 -0.531031 0.2289879 0.8823549 -0.4210344 0.2101902 0.8803866 -0.4167928 0.2262812 0.8898715 -0.3955713 0.2272711 1.56909e-7 -0.9999981 -0.001993656 1.56213e-7 -0.999998 -0.001990079 1.57874e-7 -0.9999386 0.01108515 -8.12165e-6 -0.9999391 0.01104563 2.74841e-5 -0.9992028 0.03992295 -6.90197e-5 -0.9992132 0.03966271 7.02415e-5 -0.9971578 0.07534188 -1.1273e-4 -0.9971928 0.07487756 8.15114e-5 -0.9945075 0.1046655 6.58774e-6 -0.9945359 0.1043953 6.5642e-6 -0.9925398 0.121922 -4.26849e-5 -0.9924948 0.1222873 1.58757e-4 -0.9894256 0.1450413 -1.30442e-4 -0.9893282 0.145704 8.18118e-5 -0.9849207 0.1730067 -0.00204426 -0.9835586 0.1805776 -3.93798e-5 -0.9817075 0.1903957 9.91954e-5 -0.9766417 0.2148742 -5.52191e-5 -0.9767044 0.2145893 5.77811e-5 -0.9684672 0.2491411 -1.09181e-5 -0.9684962 0.2490287 8.98897e-6 -0.959025 0.2833216 0 -0.9590287 0.2833092 -0.9979352 -0.06423002 0 -0.1022673 -0.994757 4.05539e-6 -0.0727775 -0.9972589 -0.01335638 -0.1745682 -0.9846451 0 -0.2558171 -0.9667252 0 -0.3029242 -0.9529435 -0.01164436 -0.3537254 -0.9353494 0 -0.4381347 -0.8989093 0 -0.4912313 -0.8709552 -0.01136034 -0.5283027 -0.8490561 0 -0.6034287 -0.7974171 0 -0.6590127 -0.7520676 -0.009841144 -0.8095896 -0.5869963 0 -0.7993505 -0.6008298 -0.006518721 -0.7445928 -0.667519 0 -0.6820243 -0.7313296 0 -0.8584371 -0.512919 0 -0.9010689 -0.4336748 -0.001083195 -0.9054006 -0.424528 -0.005085051 -0.9399209 -0.3413925 0 -0.9656725 -0.259763 0 -0.9731174 -0.230102 -0.009776711 -0.9873089 -0.1588116 0 0 -1 3.49736e-6 1.56132e-7 -1 4.99623e-6 0.9943841 -0.1057851 -0.003123879 0.9947181 -0.102549 -0.004431903 0.9999405 -0.01091057 0 0.9805223 -0.1964075 0 0.9601151 -0.2796055 0 0.952719 -0.3037303 -0.008632183 0.9262635 -0.3768767 0 0.8898718 -0.4562107 0 0.8703969 -0.4922245 -0.01116067 0.8382099 -0.545348 0 0.8131127 -0.5821063 0 0.7843759 -0.6202854 -7.21607e-4 0.7261232 -0.6872889 -0.01946943 0.7512883 -0.65996 -0.004329025 0.6870611 -0.7265996 0 0.6539049 -0.7565768 0 0.5999369 -0.7999802 -0.01037615 0.5723632 -0.8200003 0 0.4956392 -0.8685286 0 0.4238925 -0.9056789 -0.00779581 0.2271959 -0.973843 -0.00342977 0.2299542 -0.9731908 -0.004577219 0.3181542 -0.9480391 0 0.4039624 -0.9147757 0 0.1370593 -0.9905629 0 0.06429433 -0.9979311 0 0.06430977 -0.99793 4.29439e-6 -0.7591591 0.07267004 -0.6468358 -0.7618209 0.2651893 -0.5910192 -0.7334764 0.2395258 -0.6361131 -0.7511158 0.1589857 -0.6407408 -0.7525035 0.1605464 -0.63872 -0.7695149 0.09467035 -0.631573 -0.7668483 0.08143937 -0.6366408 -0.8175421 0.0559464 -0.5731448 1 -8.10773e-6 -1.16174e-6 1 -6.98749e-6 -9.06124e-7 1 -4.47183e-6 0 -0.7156162 0.3914381 -0.5785065 -0.7020357 0.46547 -0.5389654 -0.7032474 0.315509 -0.6371006 -0.7103037 0.3448476 -0.6136358 -0.6997327 0.4116376 -0.5838911 -0.7062837 0.05742061 -0.7055964 -0.7096747 0.07865661 -0.700125 -0.7032144 0.1340829 -0.6982202 -0.7107034 0.1714934 -0.6822689 -0.7030498 0.2269209 -0.6739644 -0.7073749 0.2490831 -0.6614971 -0.7066231 0.2896704 -0.645581 -0.08820462 0.1497371 -0.9847837 -0.3397942 0.07452988 -0.9375422 -0.515176 0.06362289 -0.8547198 -0.6773189 0.05967301 -0.7332656 -0.1406913 0.7429089 -0.6544406 -0.6286816 0.5185526 -0.5795368 -0.618483 0.5030917 -0.603637 -0.5623709 0.6315605 -0.5337326 -0.6156625 0.06772816 -0.785094 -0.6419083 0.08396267 -0.7621706 -0.6410769 0.1447382 -0.753705 -0.6410781 0.1447384 -0.7537041 -0.6410784 0.244897 -0.7273542 -0.6410779 0.2448971 -0.7273544 -0.6410771 0.3405983 -0.6877594 -0.6410781 0.3405961 -0.6877596 -0.6410781 0.4300952 -0.6356391 -0.6410769 0.4300941 -0.6356409 -0.6414679 0.5014249 -0.5805964 -0.1777294 0.07433259 -0.981268 -0.1027452 0.08898985 -0.9907191 -0.08821594 0.09665548 -0.9914008 -0.03412288 0.07855588 -0.9963256 -0.1389329 0.2145818 -0.9667742 -0.08803969 0.1878562 -0.9782429 -0.08810621 0.3056076 -0.9480724 -0.1067866 0.3172723 -0.9423031 -0.08823525 0.3688755 -0.9252814 -0.088045 0.4420667 -0.8926506 -0.08803784 0.4420639 -0.8926527 -0.08823102 0.5123801 -0.8542143 -0.1067811 0.5571981 -0.8234854 -0.08810645 0.5688547 -0.8177051 -0.08817076 0.642643 -0.7610756 -0.1175519 0.6621868 -0.740061 -0.0882039 0.6925303 -0.7159762 -0.08821582 0.7294611 -0.67831 -0.03562325 0.7447947 -0.6663421 -0.3088135 0.4955157 -0.8118489 -0.4793857 0.6629521 -0.5750511 -0.4791787 0.5852697 -0.6541003 -0.4791783 0.5852708 -0.6540996 -0.4791773 0.4918754 -0.7269442 -0.4791802 0.4918754 -0.7269422 -0.47918 0.3895215 -0.7865491 -0.4791794 0.3895207 -0.7865501 -0.4791775 0.2800744 -0.8318337 -0.479182 0.2800748 -0.8318311 -0.4791798 0.1655288 -0.861967 -0.4791799 0.1655282 -0.8619671 -0.4799925 0.09619939 -0.8719822 -0.4129971 0.07211828 -0.9078724 -0.2720407 0.6958305 -0.6646907 -0.2808187 0.6999835 -0.6566308 -0.2802801 0.6400821 -0.7153587 -0.2802819 0.6400834 -0.7153568 -0.280281 0.5379409 -0.7950235 -0.2802823 0.5379394 -0.795024 -0.2802814 0.4259996 -0.8602132 -0.2802777 0.4260008 -0.8602138 -0.2802786 0.3063049 -0.9097369 -0.2802792 0.306307 -0.909736 -0.2802816 0.1810306 -0.9426931 -0.2802792 0.1810297 -0.942694 -0.280851 0.1046319 -0.9540309 -0.2570863 0.09008461 -0.9621806 0.9959292 -0.00166887 0.09012454 0.9963986 0.002443432 0.08475869 0.9971074 0.01183074 0.07508003 0.9965612 0.02607542 0.07865154 0.997183 0.01355159 0.07377457 0.9975265 0.006968379 0.06994438 0.9979382 -6.27126e-6 0.06418269 0.9954642 0.002233207 0.09511142 0.9956644 -6.38167e-4 0.09301602 0.9950298 6.4842e-4 0.09957677 0.9951374 -0.001398503 0.09848743 0.9947235 2.4839e-4 0.1025928 0.9945191 -4.10135e-4 0.104555 0.9944378 1.62361e-4 0.1053258 0.9941447 -2.34947e-4 0.1080573 0.9939553 -0.002009391 0.1097669 0.9938777 -0.002884149 0.1104482 0.9937739 -0.004189074 0.111337 0.9937604 -0.003790915 0.1114714 0.9932118 0.005287349 0.1162 0.9797877 -0.1168155 0.1623899 0.9717916 -0.1682013 0.1653167 0.9939841 0.005191206 0.1094027 0.9862517 -0.06452983 0.1521307 0.9876946 -0.06285578 0.1432088 0.9908557 -0.04360824 0.1276847 0.9910766 -0.04641371 0.1249524 0.9935464 -0.007824301 0.1131566 0.9595036 -0.2115672 0.18599 0.9695639 -0.1391716 0.2014381 0.9696764 -0.1634479 0.181693 0.9876359 -0.06718045 0.141641 0.9851898 -0.1155346 0.1266998 0.9850013 -0.09684973 0.142803 0.8786404 -0.2789913 0.3874983 0.9205101 -0.3068655 0.2418571 0.1737242 -0.5986813 0.7819211 0.8476794 -0.1604934 0.5056496 0.7074398 -0.01816499 0.7065402 0.4404329 -0.1989514 0.8754641 0.05525726 -0.7283889 0.6829322 0.04912942 -0.8165953 0.5751161 0.07660889 -0.9474856 0.3104869 0.07789605 -0.9253858 0.3709357 0.07804262 -0.9254296 0.3707959 0.06640291 -0.8941296 0.4428579 0.04075109 -0.5461485 0.8366967 0.04328078 -0.5735892 0.817999 0.0602284 -0.6145083 0.786608 0.08121204 -0.5994768 0.7962614 0.04521143 -0.644997 0.7628466 0.01292914 -0.263789 0.9644938 0.04257959 -0.2695155 0.9620543 0.2370525 -0.259255 0.9362655 0.1828095 -0.2644208 0.9469226 0.6707865 -0.2350226 0.7034273 0.6117364 -0.1893296 0.7680709 0.5988967 -0.2216805 0.7695328 0.5544311 -0.2272532 0.8006012 0.5237839 -0.2427424 0.8165333 0.5006585 -0.2158794 0.8382942 0.3945809 -0.2840736 0.8738468 0.7960522 -0.2289025 0.5602721 0.9349454 -0.1712532 0.3107244 0.934249 -0.1853435 0.3046749 0.9413447 -0.2352101 0.2419633 0.02111303 -0.4766266 0.8788523 0.06550043 -0.5053658 0.8604157 0.1639257 -0.4936689 0.8540606 0.1736057 -0.5988379 0.7818276 0.340889 -0.5599126 0.7551773 0.9112563 -0.1929125 0.363864 0.9052495 -0.2014424 0.3740915 0.8752897 -0.2495996 0.4142079 0.8720888 -0.2429587 0.4247734 0.8029365 -0.3147993 0.5061565 0.8028362 -0.3147566 0.5063421 0.7464541 -0.3619669 0.5583783 0.7463619 -0.361917 0.5585339 0.683444 -0.4064814 0.6063639 0.6833363 -0.4064413 0.6065122 0.614577 -0.4477586 0.649467 0.6144515 -0.4477292 0.6496061 0.5406562 -0.4852975 0.6871516 0.5405572 -0.4852645 0.6872529 0.4627219 -0.518641 0.7189576 0.4625861 -0.5186142 0.7190643 0.3407719 -0.5600997 0.7550914 0.3317195 -0.4616923 0.8226801 0.1638233 -0.4938088 0.8539994 0.1560509 -0.3794133 0.9119724 0.05679303 -0.3884575 0.9197149 0.02628034 -0.372205 0.9277784 0.8732635 -0.262628 0.4104114 0.8467735 -0.2199866 0.4843355 0.7977598 -0.2595924 0.5442345 0.7976877 -0.2595265 0.5443716 0.7405222 -0.2984839 0.6021083 0.7404276 -0.2984315 0.6022505 0.6767764 -0.3351982 0.6554509 0.6766726 -0.3351536 0.6555808 0.6072331 -0.3692436 0.7035107 0.6071327 -0.3691944 0.7036231 0.53272 -0.4001894 0.7456929 0.532618 -0.400145 0.7457897 0.4542281 -0.4276843 0.7815133 0.4540932 -0.4276384 0.7816169 0.3316134 -0.4618627 0.8226272 0.3243427 -0.3548518 0.8768593 0.1559475 -0.3795484 0.9119339 0.1519947 -0.2906512 0.9446797 0.08085328 -0.2570881 0.9629998 0.7995018 -0.2367163 0.5520528 0.7673801 -0.1986129 0.6096564 0.7368442 -0.2412011 0.6315715 0.7165188 -0.2382736 0.6556116 0.6714111 -0.2576397 0.694859 0.6713435 -0.2575877 0.6949436 0.6013185 -0.2838144 0.746904 0.6012322 -0.2837586 0.7469946 0.5263274 -0.3075919 0.7926958 0.5262134 -0.307532 0.792795 0.447373 -0.3287091 0.8317498 0.4472993 -0.328673 0.8318037 0.3242537 -0.3549952 0.876834 0.3215673 -0.2864395 0.9025225 0.2956924 -0.2598003 0.9192769 0.8506065 -0.441744 0.285186 0.8306272 -0.4680657 0.3016174 0.8064895 -0.5261558 0.2696943 0.7791987 -0.5420343 0.3147196 0.7348598 -0.5931583 0.328853 0.7192075 -0.6044955 0.3425286 0.6887142 -0.6445673 0.3319725 0.6541349 -0.6666974 0.3572427 0.158928 -0.9125717 0.3767691 0.2146614 -0.8952162 0.3905233 0.225319 -0.8881487 0.400529 0.5095431 -0.7766327 0.3704153 0.5056979 -0.7776415 0.3735551 0.2843619 -0.8798974 0.3806824 0.335571 -0.8617655 0.3804633 0.3888506 -0.8287774 0.4023968 0.3927242 -0.8285826 0.3990221 0.4505596 -0.8099361 0.3754991 0.5518438 -0.749879 0.3648973 0.5732674 -0.733191 0.3657808 0.5836778 -0.7232212 0.3691495 0.6028527 -0.7130385 0.3579732 0.6374299 -0.6854723 0.3518678 0.9323046 -0.2774398 0.2320244 0.9577488 -0.177942 0.2259513 0.8896965 -0.3393427 0.3054286 0.8839321 -0.3115662 0.3486986 0.8158895 -0.4074371 0.4102673 0.8158022 -0.4074395 0.4104388 0.7613525 -0.4684891 0.4481746 0.7612571 -0.4684896 0.448336 0.7001602 -0.5261184 0.4826751 0.7000578 -0.5261241 0.4828174 0.6329779 -0.5795634 0.5132694 0.6328588 -0.5795751 0.5134028 0.560617 -0.6281476 0.5395732 0.5604996 -0.6281539 0.5396878 0.484026 -0.6713155 0.5612971 0.4838956 -0.6713162 0.5614088 0.3639095 -0.724904 0.5848796 0.3637647 -0.7248441 0.5850439 0.1983202 -0.7750804 0.5999329 0.1981656 -0.7750092 0.6000762 0.07379293 -0.7969255 0.5995535 0.05337268 -0.7667557 0.6397165 0.07411193 -0.8656789 0.4950835 0.07950109 -0.8683452 0.4895471 0.2124944 -0.8433352 0.4935908 0.2126272 -0.8433768 0.4934625 0.3771691 -0.7887446 0.4854125 0.3772912 -0.7887781 0.4852634 0.4963188 -0.7304865 0.4691025 0.4964176 -0.7304772 0.4690126 0.5721131 -0.683526 0.4532978 0.572228 -0.683503 0.4531872 0.6435859 -0.6306664 0.4336556 0.6436955 -0.6306391 0.4335325 0.7097991 -0.5725077 0.4103903 0.7098909 -0.5724826 0.4102666 0.7699363 -0.5097897 0.3838135 0.7700228 -0.5097677 0.3836692 0.8233504 -0.4433665 0.3542886 0.8234362 -0.44334 0.3541225 0.8897097 -0.3390787 0.3056833 0.8958356 -0.3606026 0.2597007 0.8679989 -0.3547047 0.3475089 0.05022525 -0.6865143 0.7253796 0.07285749 -0.7112574 0.6991457 0.1851277 -0.6930783 0.6966851 0.185281 -0.6931661 0.6965571 0.3515636 -0.6482074 0.6754482 0.3517145 -0.6482967 0.6752839 0.4725898 -0.6003488 0.6451668 0.4727149 -0.6003655 0.6450596 0.5499038 -0.5617511 0.618095 0.5500532 -0.5617635 0.6179508 0.623098 -0.5183089 0.5857515 0.6232182 -0.5183171 0.5856163 0.6911775 -0.4705126 0.5485359 0.6913018 -0.4705198 0.5483732 0.7533507 -0.4189654 0.5068833 0.7534638 -0.4189781 0.5067049 0.8089176 -0.3643693 0.4613972 0.8090243 -0.3643878 0.4611955 0.8786664 -0.2786125 0.3877122 0.883906 -0.3119022 0.3484643 0.942243 -0.1964362 0.2712767 0.9470199 -0.2172194 0.2365775 0.9578986 -0.2077298 0.198189 -0.002489149 -0.6489019 0.760868 0 -0.9435645 0.331189 -0.00293976 -0.9505258 0.3106318 0.00511378 -0.9195315 0.3929833 -3.90438e-4 -0.9285676 0.3711632 2.38636e-4 -0.8955856 0.4448894 4.12843e-5 -0.896418 0.4432096 -7.20148e-6 -0.8585579 0.5127165 -0.004461944 -0.8684592 0.4957406 0.006319403 -0.7962834 0.6048909 -0.005532622 -0.8178662 0.575382 0.00159353 -0.7571074 0.6532886 3.82885e-6 -0.7681429 0.6402785 4.90509e-6 -0.7230152 0.6908322 -0.001913249 -0.7298083 0.6836492 5.79769e-4 -0.6876387 0.7260529 0 -0.2638441 0.9645653 -5.66539e-4 -0.2660722 0.963953 5.88264e-4 -0.3724339 0.9280586 4.83822e-4 -0.3728367 0.9278969 -4.85556e-4 -0.4768378 0.8789912 0.001587569 -0.4696803 0.8828352 -7.77499e-4 -0.5468201 0.8372498 3.23632e-5 -0.5414836 0.8407114 3.00403e-5 -0.5743541 0.818607 -5.63635e-4 -0.5858054 0.8104517 6.42493e-4 -0.6018889 0.7985796 -0.001777887 -0.645897 0.7634226 -0.770007 -0.5097098 0.3837776 -0.6911925 -0.4706031 0.5484393 -0.1700254 -0.910317 0.3773782 -0.05701017 -0.8568716 0.5123682 -0.04452532 -0.585003 0.8098081 -0.02131927 -0.4694654 0.8826935 -0.6700171 -0.2158685 0.7102661 -0.9696868 -0.1581151 0.1862988 -0.9330795 -0.157059 0.3235663 -0.9236334 -0.2807131 0.260963 -0.9344295 -0.1849791 0.3043426 -0.9413924 -0.2346677 0.2423046 -0.9421787 -0.196588 0.2713902 -0.9496064 -0.2316372 0.2111679 -0.9489743 -0.2049981 0.2396323 -0.9473417 -0.2004684 0.249712 -0.7362787 -0.2349904 0.6345654 -0.7538162 -0.2054772 0.6241316 -0.7961341 -0.2302038 0.5596221 -0.6676014 -0.1971365 0.7179455 -0.5994251 -0.2311722 0.7663217 -0.5848865 -0.1978917 0.7866046 -0.5241221 -0.248896 0.8144611 -0.4832401 -0.215604 0.8485245 -0.4442287 -0.2522267 0.859676 -0.3760721 -0.2351523 0.8962551 -0.3217006 -0.289076 0.901634 -0.2764552 -0.2558194 0.9263525 -0.2193045 -0.2619013 0.9398475 -0.1514925 -0.2808653 0.9477155 -0.1493987 -0.278696 0.9486879 -0.03934979 -0.2612023 0.9644818 -0.04577183 -0.265667 0.9629777 -0.0995236 -0.6451882 0.7575139 -0.05397617 -0.7557108 0.6526774 -0.05595052 -0.7131884 0.6987359 -0.1851267 -0.6930785 0.6966853 -0.07380861 -0.9167069 0.3926844 -0.08827751 -0.9240972 0.3718219 -0.07384043 -0.9407207 0.3310472 -0.06593304 -0.7941729 0.6041045 -0.05838346 -0.7987474 0.5988272 -0.1981657 -0.7750095 0.6000757 -0.185281 -0.6931658 0.6965574 -0.3515613 -0.648208 0.6754488 -0.06700038 -0.8932629 0.4445136 -0.07952046 -0.8683429 0.4895479 -0.2124919 -0.8433357 0.4935911 -0.1983203 -0.7750803 0.599933 -0.3637644 -0.7248443 0.5850439 -0.3517164 -0.6482959 0.6752836 -0.4727031 -0.6002972 0.6451319 -0.4725964 -0.6004189 0.6450968 -0.5500362 -0.5616812 0.6180408 -0.5499167 -0.5618384 0.6180044 -0.6232008 -0.5182422 0.5857011 -0.3274274 -0.8648423 0.3805776 -0.2527251 -0.8896774 0.3802684 -0.7612638 -0.4685817 0.4482284 -0.7534412 -0.4188845 0.5068158 -0.7533631 -0.4190694 0.5067793 -0.2253845 -0.8883776 0.399984 -0.2126309 -0.8433763 0.4934618 -0.3771643 -0.7887467 0.4854131 -0.3639092 -0.724904 0.5848798 -0.4840088 -0.6712576 0.5613811 -0.4839033 -0.6713783 0.5613279 -0.5606046 -0.628088 0.5396554 -0.5605103 -0.6282131 0.5396078 -0.6329575 -0.5795027 0.5133629 -0.6328715 -0.5796427 0.513311 -0.7001442 -0.5260455 0.4827778 -0.8233619 -0.4434418 0.3541674 -0.8158702 -0.4073553 0.4103869 -0.8158122 -0.4075319 0.4103271 -0.8090007 -0.3642826 0.4613201 -0.8089321 -0.3644873 0.4612787 -0.7098087 -0.5725616 0.4102987 -0.7098743 -0.5724363 0.4103597 -0.643593 -0.6307211 0.4335656 -0.6436784 -0.6305932 0.4336248 -0.5721224 -0.6835741 0.4532135 -0.5722142 -0.6834583 0.4532722 -0.4963221 -0.7305319 0.4690284 -0.4964125 -0.7304337 0.4690856 -0.3772943 -0.7887777 0.4852616 -0.3884794 -0.8274245 0.4055272 -0.3601768 -0.8476378 0.3895933 -0.8172842 -0.4917985 0.3003017 -0.7915499 -0.5264451 0.3103294 -0.7781183 -0.5374199 0.3251338 -0.7494418 -0.582311 0.3150411 -0.7192113 -0.6045181 0.3424807 -0.7033416 -0.6256876 0.3373806 -0.6550365 -0.6705668 0.3482348 -0.6319305 -0.703333 0.3255559 -0.5839966 -0.7245502 0.366026 -0.536557 -0.7612075 0.3642387 -0.5087568 -0.7734511 0.378074 -0.4901085 -0.7881508 0.3723066 -0.4249464 -0.822916 0.3771336 -0.8743129 -0.2427135 0.420318 -0.8786374 -0.2789933 0.3875038 -0.8786649 -0.2786139 0.3877143 -0.8839102 -0.3118911 0.3484633 -0.8839324 -0.311567 0.3486971 -0.8896954 -0.3393471 0.3054271 -0.8897119 -0.3390759 0.3056801 -0.9488504 -0.2301828 0.216099 -0.9205422 -0.3068335 0.2417757 -0.8892007 -0.3375514 0.3088388 -0.8843453 -0.3831077 0.266762 -0.8486946 -0.4447966 0.2861354 -0.8339495 -0.4629485 0.3003451 -0.8302001 -0.46632 0.3054728 -0.8234171 -0.4432759 0.3542468 -0.7699472 -0.5098541 0.3837059 -0.7613403 -0.4684044 0.4482839 -0.7000649 -0.5262034 0.4827206 -0.6912792 -0.4704375 0.5484722 -0.6231055 -0.5183908 0.5856709 -0.7976887 -0.2596468 0.5443128 -0.7977513 -0.2594792 0.544301 -0.7404336 -0.2985398 0.6021896 -0.7405116 -0.298379 0.6021733 -0.6766806 -0.3352497 0.6555235 -0.6767579 -0.3351079 0.6555162 -0.6071316 -0.3692898 0.703574 -0.607219 -0.3691534 0.7035701 -0.5326231 -0.4002269 0.745742 -0.5327201 -0.400105 0.7457382 -0.4540967 -0.427726 0.7815669 -0.4542145 -0.4275998 0.7815675 -0.3316134 -0.4618626 0.8226273 -0.3317195 -0.4616924 0.82268 -0.1638208 -0.493809 0.8539997 -0.1639258 -0.4936691 0.8540605 -0.06845688 -0.5050876 0.8603488 -0.04047304 -0.5408377 0.8401527 -0.7083833 -0.2034085 0.6758831 -0.7140209 -0.2393994 0.6579225 -0.6713432 -0.2576655 0.6949151 -0.6714016 -0.2575648 0.6948959 -0.6012333 -0.2838448 0.7469611 -0.6013169 -0.2837306 0.7469371 -0.5262106 -0.3076248 0.7927606 -0.5263176 -0.3075035 0.7927367 -0.4472978 -0.3287283 0.8317827 -0.4473654 -0.3286566 0.8317748 -0.3242525 -0.3549962 0.8768342 -0.3243429 -0.354852 0.8768591 -0.1559492 -0.3795483 0.9119336 -0.1560485 -0.3794134 0.9119728 -0.02911806 -0.3902806 0.9202354 -0.06656092 -0.3717365 0.9259491 -0.8342381 -0.1327869 0.5351772 -0.8322887 -0.3829371 0.4008176 -0.8701947 -0.1982827 0.4510489 -0.8736335 -0.2411078 0.4226482 -0.8028482 -0.3148809 0.5062459 -0.8029158 -0.3146805 0.5062634 -0.7463641 -0.3620374 0.558453 -0.7464439 -0.3618524 0.5584662 -0.6833376 -0.4065515 0.6064368 -0.6834335 -0.4063762 0.6064463 -0.6144585 -0.4478238 0.6495342 -0.6145597 -0.4476702 0.6495442 -0.5405561 -0.4853433 0.6871979 -0.5406506 -0.4852209 0.68721 -0.4625921 -0.518691 0.7190051 -0.4627035 -0.5185679 0.7190221 -0.3407717 -0.5600999 0.7550912 -0.340889 -0.5599125 0.7551773 -0.1736057 -0.5988379 0.7818276 -0.1737245 -0.5986815 0.7819209 -0.0162881 -0.6184509 0.7856547 -0.07332414 -0.7206787 0.6893807 -0.3727718 -0.877488 0.301755 -0.06759637 -0.9895329 0.1274967 -0.9961493 -0.06411111 0.05980467 -0.07278412 -0.9973455 0.002111256 -0.1745092 -0.984313 0.02597481 -0.2252205 -0.973629 0.03636598 -0.2556974 -0.9662746 0.03053319 -0.8989574 -0.4333127 0.06415468 -0.8992254 -0.4327877 0.06394302 -0.9974904 -0.01099133 0.06994384 -0.9379096 -0.3406658 0.06536567 -0.9597997 -0.2718178 0.06999808 -0.9635719 -0.2591986 0.06591975 -0.9921947 -0.1058125 0.06598049 -0.9836845 -0.1582292 0.08560532 -0.9975131 -0.04085046 0.0574373 -0.9956493 -0.06617015 0.06560486 -0.9943043 -0.04957211 0.09434902 -0.9962829 -0.01077616 0.08546441 -0.9966515 -0.01118153 0.08099788 -0.9925755 -0.05232137 0.1098011 -0.994907 -0.008582293 0.1004314 -0.9956551 -0.01338964 0.09215098 -0.9907459 -0.05283707 0.1250243 -0.9936884 -0.01036036 0.111697 -0.9941508 -0.01119875 0.1074186 -0.9901775 -0.02345794 0.137835 -0.992415 -0.01060175 0.1224752 -0.9929006 -0.01164269 0.1183766 -0.04277074 -0.9567767 0.2876614 -0.07792085 -0.9967636 0.01976966 -0.08891695 -0.9959059 0.01628881 -0.06030255 -0.99722 0.04377108 -0.7549278 -0.5948385 0.2761366 -0.7979853 -0.540825 0.2659471 -0.8106153 -0.52509 0.2591978 -0.8125786 -0.5295526 0.2434954 -0.3374242 -0.8887254 0.310342 -0.3995212 -0.8623925 0.3109051 -0.4028046 -0.8697865 0.2849912 -0.4856433 -0.82671 0.2840794 -0.4887097 -0.833231 0.2586295 -0.5664821 -0.7832587 0.2561323 -0.5693161 -0.7888987 0.2313402 -0.6414995 -0.7325367 0.2277464 -0.6440799 -0.7372968 0.2038493 -0.7098948 -0.6754183 0.1996486 -0.7122136 -0.6793175 0.1768604 -0.7719354 -0.6118648 0.1724454 -0.7739831 -0.6149348 0.1510144 -0.8269584 -0.5427607 0.1468021 -0.8287343 -0.5450639 0.1269052 -0.07747024 -0.949536 0.3039406 -0.1811453 -0.9376366 0.2966886 -0.191814 -0.9363509 0.2940316 -0.06402921 -0.9947777 0.07948309 -0.2204953 -0.9711852 0.09044933 -0.2209685 -0.9710993 0.09021854 -0.3442726 -0.9337972 0.09746474 -0.3463745 -0.9354779 0.07004314 -0.4312367 -0.8991464 0.07463729 -0.4335109 -0.9001819 0.04172426 -0.4377648 -0.8981512 0.04106724 -0.3535019 -0.9347583 0.03554511 -0.3489863 -0.9364259 0.03626757 -0.3466417 -0.9353709 0.07014858 -0.2233626 -0.972714 0.06274354 -0.2230615 -0.9727736 0.06289148 -0.07447952 -0.9958172 0.05292326 -0.06481254 -0.9946965 0.07986485 -0.6026735 -0.7964214 0.04997706 -0.5896927 -0.805986 0.05146902 -0.5876133 -0.8050135 0.08163231 -0.511634 -0.8556216 0.07837319 -0.5096184 -0.854009 0.1046795 -0.4285039 -0.8978384 0.1013453 -0.4262719 -0.8954556 0.1282643 -0.3410059 -0.9317886 0.124439 -0.3385742 -0.9286286 0.1517119 -0.2152022 -0.965777 0.1447857 -0.2143876 -0.9658998 0.1451747 -0.07425671 -0.9880962 0.1347284 -0.05332916 -0.9872388 0.1500524 -0.5278109 -0.8482677 0.04309952 -0.514142 -0.8564959 0.04552888 -0.5118799 -0.8554652 0.07847499 -0.4309751 -0.8992808 0.07452881 -0.4289058 -0.8976279 0.1015083 -0.3438473 -0.9339712 0.09729778 -0.3415789 -0.9315492 0.1246603 -0.2182466 -0.9687852 0.1175745 -0.2176002 -0.9688926 0.117886 -0.0723623 -0.9915803 0.1073895 -0.06739932 -0.991679 0.1096822 -0.4994936 -0.8098428 0.3076701 -0.5580826 -0.7719634 0.3043292 -0.5611684 -0.7789204 0.279952 -0.6339846 -0.7230524 0.2743334 -0.6368157 -0.729078 0.2508209 -0.7032839 -0.6676441 0.2442196 -0.7058516 -0.6727591 0.2217404 -0.766227 -0.6056936 0.2145497 -0.7685203 -0.6099218 0.1933186 -0.8221269 -0.5380653 0.1859926 -0.8241401 -0.5414459 0.1662211 -0.8901414 -0.4283699 0.1553952 -0.890626 -0.4276011 0.1547344 -0.7433661 -0.6664338 0.05721068 -0.7241036 -0.6872196 0.05833631 -0.7222138 -0.6863206 0.08585715 -0.6577468 -0.7485408 0.08399927 -0.6558827 -0.7470484 0.1083358 -0.5850698 -0.8039199 0.1068004 -0.5829638 -0.8016766 0.1321672 -0.5065279 -0.8522813 0.1305619 -0.5041955 -0.8492509 0.1567164 -0.4226296 -0.8930183 0.1546045 -0.4200764 -0.889183 0.1813549 -0.3343853 -0.9254171 0.1782968 -0.3316258 -0.9207794 0.2054013 -0.2081621 -0.9576803 0.1987892 -0.2070075 -0.9578181 0.1993301 -0.0604813 -0.9803873 0.1875705 -0.06389689 -0.9732515 0.2206781 -0.6812151 -0.7304603 0.04872107 -0.6600731 -0.7493203 0.05312967 -0.657962 -0.7483408 0.08409547 -0.5873833 -0.8051915 0.08153218 -0.5854326 -0.803635 0.1069557 -0.5092299 -0.85426 0.1045224 -0.5070537 -0.8519369 0.1307681 -0.4257184 -0.8957501 0.1280459 -0.4233275 -0.8926408 0.1548753 -0.3378475 -0.9289385 0.1514348 -0.335252 -0.9250405 0.1786236 -0.2118396 -0.9620757 0.1718563 -0.2108533 -0.9622086 0.1723238 -0.07040697 -0.9843595 0.161491 -0.05572551 -0.981114 0.1852298 -0.9894778 -0.1044389 0.1001306 -0.989275 -0.1058031 0.1007004 -0.9876411 -0.1033463 0.1178328 -0.9873257 -0.1052815 0.1187595 -0.9855354 -0.1019777 0.1353542 -0.9850946 -0.104431 0.1366851 -0.9844176 -0.1029229 0.14258 -0.975408 -0.1469442 0.1642764 -0.6347811 -0.7099355 0.3050322 -0.6962568 -0.6590061 0.284495 -0.6985877 -0.6642854 0.2658951 -0.7596797 -0.5978083 0.2559535 -0.7621934 -0.6031584 0.2350775 -0.8165097 -0.5318275 0.2246586 -0.818735 -0.536265 0.2051661 -0.8855381 -0.4242533 0.1892919 -0.8861978 -0.4232853 0.1883696 -0.8567742 -0.5119073 0.06236058 -0.834391 -0.5476934 0.06183695 -0.8326594 -0.5468586 0.08731693 -0.7804771 -0.6191239 0.08683961 -0.7788199 -0.6177986 0.1084644 -0.7199384 -0.685474 0.1086923 -0.718028 -0.6834386 0.1317104 -0.6530743 -0.7456511 0.1322814 -0.6509148 -0.74285 0.1564736 -0.579592 -0.7996407 0.1569969 -0.5771851 -0.7960287 0.1821975 -0.5002501 -0.8464859 0.1822409 -0.4976055 -0.8420386 0.2082304 -0.4155504 -0.8856239 0.2073362 -0.4126883 -0.8803409 0.233855 -0.3265388 -0.9163805 0.2315586 -0.32348 -0.9102871 0.2583374 -0.1999055 -0.9468446 0.2520377 -0.1984189 -0.9469763 0.2527174 -0.04300928 -0.9664216 0.2533366 -0.06675189 -0.9680523 0.2417001 -0.04373115 -0.976131 0.2127342 -0.2028627 -0.9527374 0.2261376 -0.2041794 -0.9526005 0.2255285 -0.3276976 -0.9158589 0.2319847 -0.3306097 -0.9212292 0.2050223 -0.4165244 -0.8850812 0.2076988 -0.4192364 -0.8896446 0.1810342 -0.5010469 -0.8459507 0.1825362 -0.5035356 -0.8496888 0.1564642 -0.5802165 -0.7991388 0.1572447 -0.5824727 -0.8020663 0.1319667 -0.6535316 -0.7452167 0.1324713 -0.6555444 -0.7473665 0.1081898 -0.7202476 -0.6851267 0.108834 -0.7220147 -0.6865419 0.08576148 -0.780656 -0.6188853 0.08693271 -0.7825409 -0.6197797 0.05918741 -0.8084841 -0.5861959 0.05222982 -0.946538 -0.2614746 0.1889365 -0.9525882 -0.2389158 0.1884019 -0.9718589 -0.1633149 0.1697608 -0.8233425 -0.5053521 0.2583145 -0.8409889 -0.4784028 0.2527224 -0.9167875 -0.3416988 0.2067434 -0.8553115 -0.4599483 0.2385165 -0.8806855 -0.4168692 0.2249737 -0.8900549 -0.396245 0.2253717 -0.9251706 -0.3175526 0.2078937 -0.71099 -0.642873 0.2849697 -0.7560972 -0.5932117 0.276436 -0.7587262 -0.5991336 0.2556827 -0.813421 -0.528149 0.2437316 -0.8157476 -0.5330973 0.2244173 -0.8829976 -0.4217347 0.2060462 -0.8837459 -0.4206802 0.204991 -0.9481373 -0.2648566 0.175746 -0.9555174 -0.2480422 0.1595671 -0.949727 -0.2640926 0.1681485 -0.5456684 -0.7822391 0.3005798 -0.6291367 -0.715916 0.3027399 -0.6328336 -0.7241892 0.2739924 -0.6996421 -0.663052 0.2662011 -0.7023246 -0.6687636 0.2439168 -0.7630515 -0.6019671 0.2353471 -0.7654587 -0.6067585 0.2142832 -0.8194134 -0.5351353 0.2054068 -0.8215366 -0.5390467 0.1857592 -0.8879222 -0.4264651 0.1724001 -0.8884927 -0.4255949 0.1716091 -0.9517757 -0.267782 0.1497196 -0.9589183 -0.2499365 0.1341916 -0.953073 -0.2671855 0.1423509 -0.9555092 -0.2708468 0.1168083 -0.9559475 -0.2695313 0.1162635 -0.4340778 -0.8442738 0.3142901 -0.4816052 -0.8214737 0.305348 -0.4843301 -0.8276269 0.2836514 -0.5624042 -0.7778873 0.2803444 -0.5653665 -0.7841861 0.2557597 -0.6378582 -0.7280523 0.2511509 -0.6405673 -0.7334496 0.227432 -0.7067023 -0.6717705 0.2220279 -0.7091481 -0.6762821 0.1993781 -0.7691901 -0.6089966 0.1935712 -0.7713637 -0.612651 0.1722118 -0.8246462 -0.5406072 0.166441 -0.82654 -0.5434505 0.1466056 -0.8921907 -0.429955 0.1383273 -0.9054221 -0.4072652 0.1197748 -0.8935741 -0.4298987 0.1292766 -0.2621229 -0.9125312 0.3139721 -0.3146815 -0.8982639 0.3067535 -0.3175583 -0.9047333 0.2839273 -0.4041758 -0.8689937 0.285468 -0.4073209 -0.8756893 0.2593417 -0.489892 -0.8324124 0.2590279 -0.4928241 -0.8382502 0.2333689 -0.5703107 -0.7880783 0.2316863 -0.5730097 -0.7930512 0.2067121 -0.6448897 -0.7365086 0.2041381 -0.6473358 -0.7406215 0.1801005 -0.7128484 -0.6785869 0.1771075 -0.7150316 -0.6818639 0.1542456 -0.7744625 -0.6142796 0.1512235 -0.77638 -0.61677 0.1297262 -0.8290664 -0.5445192 0.1270743 -0.8307238 -0.5462844 0.1071054 -0.8957716 -0.4321865 0.1039627 -0.064318 -0.9612855 0.2679429 -0.1936935 -0.9405438 0.2790346 -0.1953399 -0.9404234 0.2782917 -0.3189824 -0.9040726 0.2844349 -0.3221815 -0.9108809 0.2578667 -0.4085648 -0.8749787 0.2597833 -0.4115716 -0.8809708 0.233451 -0.4938876 -0.8375208 0.2337394 -0.4966771 -0.842669 0.2078963 -0.5738865 -0.7923337 0.2070308 -0.5764436 -0.7966302 0.1819156 -0.648037 -0.7399435 0.1803655 -0.6503387 -0.743402 0.1562471 -0.715563 -0.6812563 0.1544649 -0.7176058 -0.6839175 0.1315254 -0.7767539 -0.6162625 0.1298996 -0.7785453 -0.6181688 0.1083266 -0.8309687 -0.5458855 0.1072396 -0.8325009 -0.5471143 0.08722573 -0.908717 -0.4083796 0.08636873 -0.8967366 -0.4322307 0.09507989 -0.958108 -0.2718389 0.09018266 -0.9583362 -0.2711184 0.08992534 -0.9909356 -0.1059954 0.08253288 -0.9910365 -0.105256 0.08226639 -0.9951403 -0.05777472 0.0797367 -0.9971664 -0.01085245 0.07444161 -0.9940194 0.002107322 0.109184 -0.9935497 0.01361 0.1125783 -0.9932171 0.02855896 0.1127132 -0.9951968 0.004814028 0.09777647 -0.9951209 0.003034412 0.09861743 -0.9944209 -6.20637e-4 0.1054841 -0.9972608 -9.3981e-4 0.0739597 -0.9967897 0.001423478 0.08005195 -0.9965655 0.00457108 0.08268338 -0.9964449 0.002723276 0.08420449 -0.9958716 -0.00168097 0.09075808 -0.9981721 -6.49596e-6 0.0604375 -0.9977201 0.001011371 0.06748145 -0.9978722 0.006059646 0.06492 -0.9975768 0.002140045 0.06954109 -1 -5.24061e-6 0 -1 -6.11404e-6 0 0.7605957 0.07248133 -0.6451673 0.8231933 0.03756642 -0.5665171 0.7925138 0.08463162 -0.6039533 0.773329 0.08760643 -0.6279231 0.7497985 0.1612966 -0.6417053 0.7517499 0.1636951 -0.6388083 0.7330616 0.2396822 -0.6365321 0.7610178 0.2655754 -0.5918799 0.6648942 0.3057781 -0.6814805 0.7417854 0.3003118 -0.5996394 0.7015056 0.3993782 -0.5902432 0.7122926 0.4587647 -0.5312007 0.6870316 0.373337 -0.6233837 0.706543 0.3122953 -0.6350345 0.7070872 0.2732778 -0.6521863 0.7073761 0.2490819 -0.6614964 0.7030493 0.226921 -0.6739649 0.710703 0.1714938 -0.6822692 0.7032142 0.1340829 -0.6982204 0.7096748 0.07865697 -0.7001249 0.7062834 0.05742061 -0.7055966 -1.29862e-6 1.47378e-6 -1 -8.22481e-5 -1.46019e-4 -1 9.78308e-6 4.7118e-6 -1 2.87559e-7 -1.17737e-6 -1 -1.01157e-5 -1.38354e-7 -1 -2.73804e-5 -4.93981e-5 -1 -1.44113e-4 -1.82108e-4 -1 8.45739e-5 -7.42448e-5 -1 -2.62588e-5 -1.35006e-4 -1 4.94146e-4 -1.55072e-4 -0.9999999 0 0 -1 -8.67758e-5 -9.84478e-5 -1 3.53688e-4 -7.00557e-5 -1 -5.29712e-4 1.05556e-4 -0.9999999 1.60908e-5 0 -1 -9.18803e-6 0 -1 -4.17521e-4 -2.68135e-5 -1 1.01065e-6 0 -1 -5.21951e-7 0 -1 0 2.82688e-4 -1 5.45453e-5 -2.76184e-4 -1 3.17564e-4 2.11727e-4 -1 4.46363e-7 0 -1 -2.45787e-5 2.7771e-4 -1 -1.76776e-4 5.6723e-5 -1 -2.15659e-4 1.27742e-4 -1 -2.5568e-4 2.62708e-5 -1 9.93602e-5 -2.62664e-4 -1 -2.81262e-6 0 -1 -4.39062e-4 -1.1196e-5 -1 -5.27057e-4 0 -1 -8.16169e-4 -4.19509e-5 -0.9999997 0 2.82658e-4 -1 8.05902e-6 2.82652e-4 -1 2.09692e-4 -1.38902e-4 -1 1.5573e-4 -1.03245e-4 -1 1.16407e-4 2.72402e-5 -1 3.09833e-4 -1.99643e-5 -1 2.24966e-4 1.05291e-4 -1 -9.49352e-5 1.57407e-4 -1 -3.25747e-4 4.59085e-5 -1 -1.90263e-4 -4.27269e-6 -1 0.6039803 0.7397885 0.2965146 -0.4391851 0.8816588 0.1726106 0.2275894 0.9732597 0.03112554 -0.1654416 0.9831578 0.07765251 0.2522053 0.9667711 0.04178988 0.2530975 0.9663214 0.04652637 0.2871287 0.9563476 0.05437254 0.2898349 0.9549977 0.06304955 0.3282204 0.942326 0.06552177 0.3302281 0.9413313 0.06960606 0.3542086 0.9321829 0.07464277 0.3575398 0.9304628 0.08002734 0.3898075 0.9178783 0.07449471 0.3921636 0.9166654 0.07702243 0.4087932 0.9091122 0.0800203 -0.533169 0.8392686 0.1065801 -0.1006301 0.9886848 0.1112474 -0.09184688 0.9833837 0.1565908 -0.02391058 0.993701 0.1094834 0.005613625 0.9790807 0.2033948 0.07236373 0.9865337 0.1466796 0.1119624 0.9674538 0.2269309 0.1339398 0.9750512 0.1770179 0.1791564 0.9515975 0.2497302 0.2160688 0.9580928 0.1880757 0.269822 0.9310127 0.2457873 0.2626605 0.9423127 0.2075006 0.3163138 0.9133318 0.2564579 -0.4266855 0.8741711 0.2318711 -0.3266818 0.9296949 0.1701366 -0.2831695 0.9084292 0.3075248 -0.179566 0.9554466 0.2342601 -0.1204334 0.9272727 0.3544874 -0.08529776 0.9554036 0.2827162 -0.01774573 0.9203958 0.3905852 0.04560524 0.9508537 0.3062636 0.1283363 0.9094986 0.3954013 0.1160894 0.9348405 0.3355545 0.1986984 0.8899826 0.4104265 0.2176199 0.9170637 0.3341192 0.3144931 0.8666345 0.3873485 0.1599326 0.8590335 0.4862953 0.2080332 0.8331003 0.5125098 0.01078742 0.8699645 0.4929963 0.04203367 0.8526199 0.5208383 -0.08121728 0.8833531 0.4616181 -0.04793238 0.8662456 0.4973139 -0.2614445 0.8621961 0.433895 -0.2436999 0.8528696 0.4617615 -0.3855722 0.8430672 0.374929 -0.3710678 0.8359952 0.4042532 -0.572355 0.7641528 0.2974565 -0.5680354 0.7620468 0.3108384 -0.7241795 0.6618603 0.1936624 -0.7190937 0.6594098 0.2192783 -0.8181555 0.5641571 0.1111236 0.3109595 0.7805895 0.5422033 0.2932724 0.7986189 0.5255466 0.2740551 0.8105629 0.5175729 0.5275928 0.8476336 0.05624431 0.5158932 0.8543506 0.06276351 0.517842 0.8533453 0.06034451 0.5082734 0.858801 0.06417936 0.50875 0.8585566 0.06367272 0.499331 0.8638885 0.06607049 0.4979223 0.8645961 0.0674318 0.4869118 0.8707726 0.06835263 0.4820489 0.8731224 0.07270711 0.4682788 0.880746 0.07072198 0.4568731 0.8859462 0.07978945 0.4506937 0.8893547 0.07696479 0.4393571 0.8950524 0.07646226 0.5249819 0.8488849 0.06155216 0.5779249 0.7983601 0.1691865 0.5537536 0.8123778 0.1827553 0.5495244 0.8151805 0.1830401 0.5306479 0.8258817 0.1906105 0.5321964 0.8248598 0.1907176 0.5034161 0.8410407 0.1980476 0.5110321 0.8357602 0.200876 0.4656323 0.8609974 0.2046214 0.4781541 0.8510109 0.2171382 0.4117571 0.8873549 0.2075028 0.4206665 0.8749213 0.2399013 0.36575 0.9055333 0.2150267 0.5711838 0.8009032 0.179731 0.6194583 0.7340288 0.27834 0.5801237 0.7570471 0.3005599 0.5726184 0.7621694 0.3020035 0.5425124 0.7791487 0.3140187 0.5481463 0.7752906 0.3137841 0.4983175 0.803202 0.3264143 0.5165448 0.7899925 0.3302927 0.4377309 0.8336704 0.3367274 0.4636636 0.8110632 0.3566409 0.3531529 0.8713937 0.3405233 0.4130358 0.9068429 0.08389031 0.4351625 0.8972931 0.07415401 0.3250952 0.9234087 0.2040335 0.38481 0.892135 0.2366785 0.2783128 0.8942732 0.3504536 0.3677905 0.8438951 0.3906037 0.2837111 0.8385294 0.4651629 0.3826299 0.7885769 0.4813949 0.487991 0.7443203 0.4559081 0.4776346 0.7503727 0.4569534 0.5347473 0.7235851 0.4364287 0.5431616 0.7186461 0.4341927 0.5607931 0.7100458 0.4258477 0.5969201 0.6890057 0.4110446 0.5821482 0.6959527 0.4204204 0.6532904 0.6546671 0.3802928 0.6152803 0.6701197 0.4151744 0.1560317 0.9872225 0.03234183 -0.7307631 0.6771954 0.08597499 -0.7312958 0.6766709 0.08557498 -0.3196104 0.9455285 0.06184661 -0.3214079 0.9449794 0.06091839 0.1688162 0.9853823 0.02286678 -0.9606323 0.2436188 0.1335493 -0.9652346 0.2455694 0.0895431 -0.9653326 0.2452539 0.08935046 -0.9603016 0.2447608 0.13384 -0.7288672 0.6725614 0.128117 -0.7270424 0.6746762 0.1273631 -0.3247959 0.9412646 0.09235185 -0.3185693 0.9436033 0.09014624 0.1669843 0.9853921 0.03344649 0.1658413 0.9859198 0.02142035 0.1423841 0.9886764 0.0473904 0.1584745 0.9861971 0.04797142 -0.3281956 0.9353272 0.1321011 -0.3184688 0.9385753 0.1328693 -0.7227371 0.6656661 0.1858488 -0.7197601 0.6687059 0.1864879 -0.9501421 0.2421847 0.1964095 -0.9506106 0.2406613 0.1960145 -0.8931677 0.4361432 0.1096835 -0.9402002 0.3383577 0.03921604 -0.6222114 0.7775701 0.09076297 -0.6844716 0.7276487 0.04501247 -0.2321252 0.970774 0.06095755 -0.2803823 0.9592213 0.03578042 0.2025904 0.978968 0.02406018 0.1844276 0.9827223 0.01560145 -0.8129501 0.5617079 0.1536116 -0.8973006 0.4380071 0.0547862 -0.5312799 0.8383153 0.1223496 -0.624485 0.7786784 0.0606504 -0.1651854 0.9830229 0.07987344 -0.2330945 0.9712881 0.04760831 0.2275623 0.9732732 0.03090047 0.2023535 0.9790949 0.020648 0 -1 -3.13202e-7 0 -1 0 0 -1 -5.8324e-6 0 -1 1.61374e-6 0 -1 6.19671e-6 0 -1 -7.85571e-6 0 -1 5.37866e-6 0 -1 4.71655e-7 0 -1 5.07717e-5 -9.63621e-5 -0.9999997 -7.61727e-4 0 -1 -3.75601e-5 0 -1 -1.60648e-5 0 -1 -3.34891e-7 0 -1 0 0 -1 2.62379e-7 0 -1 4.96579e-5 0.001008629 -0.9999992 8.61085e-4 3.63883e-5 -1 1.9289e-5 5.21495e-6 -1 9.6305e-7 0 -1 0 0 -1 0 0 -1 -5.32187e-7 0 -1 0 0 -1 -9.83117e-7 0 -1 8.16524e-7 0 -1 2.47106e-7 0 -1 -3.42654e-6 0 -1 -6.9233e-7 0 -1 -3.50022e-6 0 -1 1.55133e-6 0 -1 3.85993e-6 -0.701191 -0.5100499 -0.4981769 -0.7080391 -0.4750872 -0.522468 -0.7074178 -0.008966684 -0.7067388 -0.7037158 -0.02311903 -0.7101055 -0.7089068 -0.09699183 -0.6986013 -0.7024197 -0.1272594 -0.700294 -0.7087599 -0.17421 -0.683601 -0.7070086 -0.1930392 -0.680349 -0.7070606 -0.2172006 -0.6729705 -0.7026518 -0.2695769 -0.6584898 -0.7116658 -0.2416704 -0.6596418 -0.7030249 -0.32501 -0.6325541 -0.706703 -0.3083546 -0.6367797 -0.7068496 -0.3607366 -0.6084676 -0.7079525 -0.3544014 -0.6109034 -0.703963 -0.4212722 -0.5718094 -0.706088 -0.4148032 -0.5739147 -0.7070885 -0.4603514 -0.5367518 -1 0 0 -0.003055572 0.07862675 -0.9968996 0 0.1071954 -0.994238 0 0.1071954 -0.994238 0.9647356 0.03956586 -0.2602303 -0.001251697 0.07860195 -0.9969053 0 0.7452666 -0.6667666 0 0.7452673 -0.6667659 0 0.6952387 -0.718779 0 0.6952386 -0.718779 0 0.6451568 -0.7640503 0 0.5710754 -0.8208977 0 0.5710759 -0.8208974 0 0.5143882 -0.8575575 0 0.5143862 -0.8575586 0 0.4437899 -0.8961309 0 0.4437896 -0.896131 0 0.3703207 -0.9289039 0 0.3703193 -0.9289045 0 0.3068004 -0.9517739 0 0.3068003 -0.9517739 0 0.2166831 -0.9762421 0 0.1503233 -0.988637 1 -2.49087e-7 0 1 0 0 0.5995559 0.0638225 -0.7977841 0.3895902 0.06907248 -0.9183945 0.002071321 0.07862627 -0.9969021 0.3339489 0.6998932 -0.6313698 0.6433302 0.5004048 -0.5794147 0.06834173 0.7435251 -0.6652067 0.08820426 0.7327481 -0.6747595 0.08820331 0.6925303 -0.7159762 0.1389358 0.6388998 -0.75664 0.08803766 0.6642209 -0.7423343 0.08810627 0.5688552 -0.8177049 0.1067811 0.5571975 -0.8234859 0.08823192 0.5123801 -0.8542141 0.08803945 0.4420661 -0.8926514 0.08804345 0.4420645 -0.8926519 0.08823645 0.3688757 -0.9252811 0.1067866 0.3172723 -0.9423031 0.08810555 0.3056076 -0.9480725 0.1275492 0.08414417 -0.9882565 0.07817 0.09839159 -0.9920729 0.08817106 0.215839 -0.97244 0.11755 0.187281 -0.9752476 0.08820462 0.1497372 -0.9847837 0.0882039 0.09158492 -0.9918832 0.01887893 0.07894259 -0.9967005 0.2374442 0.08311504 -0.967839 0.1778302 0.07727462 -0.9810225 0.1476969 0.08023476 -0.9857728 0.4611147 0.08631968 -0.8831321 0.6698698 0.06022214 -0.7400322 0.6419036 0.08347457 -0.7622281 0.6410777 0.1447393 -0.7537043 0.6410827 0.1447352 -0.7537007 0.6410789 0.244897 -0.7273536 0.6410813 0.2448973 -0.7273514 0.6419378 0.2963038 -0.7071915 0.6367428 0.345289 -0.6894448 0.6410772 0.3405973 -0.6877598 0.6410779 0.4300962 -0.6356387 0.6410782 0.4300941 -0.6356397 0.6414892 0.5007743 -0.581134 0.5984086 0.5342418 -0.5970703 0.6044701 0.6173337 -0.503503 0.5321067 0.07010412 -0.84377 0.4800096 0.1000161 -0.8715433 0.4791792 0.1655273 -0.8619676 0.4791769 0.165529 -0.8619685 0.4791751 0.2800775 -0.8318341 0.4791792 0.2800747 -0.8318326 0.4791779 0.3895225 -0.7865499 0.4791802 0.38952 -0.7865499 0.4791803 0.4918738 -0.7269433 0.4791762 0.491877 -0.7269437 0.4791784 0.5852708 -0.6540995 0.479178 0.5852705 -0.6541 0.4793635 0.5902897 -0.6494373 0.4549512 0.6464948 -0.6124247 0.3150191 0.0841701 -0.9453457 0.2808505 0.1050637 -0.9539836 0.2802791 0.1810299 -0.942694 0.2802824 0.1810294 -0.9426931 0.2802835 0.3063046 -0.9097356 0.2802768 0.3063066 -0.9097369 0.2802817 0.426 -0.8602129 0.2802784 0.4260002 -0.8602138 0.2802814 0.537941 -0.7950232 0.2802827 0.5379387 -0.7950243 0.2802833 0.6400822 -0.7153573 0.2802795 0.6400825 -0.7153586 0.28087 0.687421 -0.6697496 0.2048979 0.7339227 -0.6475912 0.9603351 0.2447752 0.1335723 0.3196887 0.9455699 0.06080085 0.3213126 0.9449437 0.06196504 0.7307941 0.6772154 0.0855531 0.7312623 0.6766535 0.08599758 0.9653164 0.2452496 0.08953809 -0.1667497 0.9855129 0.03096669 -0.1660025 0.9858546 0.02310806 -0.1686952 0.9854408 0.02117812 -0.1564225 0.9870762 0.03482228 0.3250295 0.9413341 0.09080708 0.3184092 0.9435092 0.09168535 0.7289557 0.6725859 0.1274831 0.7269653 0.6746402 0.1279923 0.9605988 0.2436049 0.1338156 0.9652508 0.2455741 0.08935517 0.9502065 0.2422193 0.1960551 0.9505464 0.2406294 0.1963648 0.7225584 0.6656028 0.1867684 0.7199203 0.6687868 0.1855775 0.3277349 0.9351744 0.1343088 0.3188224 0.9387637 0.1306718 -0.1431557 0.9883896 0.05091607 -0.1579289 0.9864496 0.04444736 -0.2019066 0.9792984 0.01444309 -0.1849657 0.9824368 0.02461332 0.2339841 0.9716114 0.03496724 0.2788677 0.9584462 0.06011408 0.6252498 0.7789271 0.04832625 0.6819595 0.7264631 0.08475089 0.8974908 0.4380855 0.05090719 0.9368172 0.3368584 0.09434032 -0.2261371 0.9739217 0.01840633 -0.2031461 0.9786253 0.03200376 0.1690272 0.9845463 0.04580748 0.2307727 0.9698408 0.07844078 0.5373798 0.8407374 0.06620824 0.6203174 0.7763963 0.1114229 0.8213364 0.5654003 0.07569086 0.8914566 0.435352 0.1255937 -0.5797215 0.7962123 0.1731158 0.8070266 0.5586392 0.1913908 0.5256942 0.8347991 0.1635727 0.7344791 0.6658923 0.1308742 0.7057166 0.6522045 0.2767553 0.5959927 0.7736538 0.2150642 0.5439236 0.7486618 0.3790155 0.4167648 0.8555858 0.3070505 0.3435125 0.8206456 0.4566618 0.2990732 0.8790306 0.3712957 0.2146373 0.8357809 0.5053723 0.1247066 0.9022845 0.4127119 0.01665729 0.8481301 0.5295262 0.03623348 0.8926855 0.4492213 -0.07236337 0.834037 0.5469425 -0.1046499 0.8846242 0.4544101 -0.2414679 0.8129803 0.5298646 -0.1796562 0.8615792 0.4747684 -0.2932724 0.7986189 0.5255466 -0.2548447 0.8343956 0.488711 -0.4116744 0.7714924 0.4851018 -0.4493514 0.7475106 0.4891945 -0.3960225 0.7933284 0.462381 -0.5245027 0.7216279 0.4518297 -0.4801928 0.7531375 0.4496651 -0.5599933 0.7084695 0.4295097 -0.5433627 0.7195116 0.4325044 -0.5814512 0.6982451 0.4175744 -0.597167 0.6879591 0.4124367 -0.60508 0.6836137 0.4081062 -0.6561134 0.6489443 0.3852097 -0.5997676 0.7459026 0.289669 -0.5733455 0.7607269 0.3042527 -0.5797531 0.7579139 0.2990866 -0.5480871 0.7761097 0.3118564 -0.5425735 0.7786067 0.315255 -0.5189143 0.7921086 0.3213906 -0.4974559 0.8013824 0.3321506 -0.476771 0.8131288 0.3339328 -0.4317268 0.83029 0.3524633 -0.4101638 0.8424265 0.3494044 -0.3290125 0.8672888 0.3735789 -0.3319102 0.8656182 0.3748877 -0.2670285 0.8932625 0.3616322 -0.2791829 0.8867878 0.3683266 -0.1600661 0.9127526 0.3758478 -0.1659891 0.9094755 0.3811852 -0.08685255 0.9322595 0.3512107 -0.09661352 0.9272751 0.3617001 0.04869705 0.9384034 0.3420931 0.04729795 0.9376782 0.3442711 0.1487571 0.9428054 0.2983106 0.1469977 0.9419505 0.3018626 0.3022133 0.9197331 0.2505158 0.3061981 0.9217365 0.2380011 0.4390476 0.8816029 0.1732445 0.4505661 0.8860059 0.1094704 0.1613707 0.9805184 0.1119966 -0.6215178 0.7303955 0.2832634 -0.5683861 0.8040218 0.1746034 -0.5500525 0.8144358 0.184761 -0.5533906 0.8129089 0.1814883 -0.5321729 0.8250418 0.1899949 -0.5306878 0.8257373 0.1911243 -0.5112751 0.8367543 0.1960617 -0.5034487 0.8401847 0.2015668 -0.4822311 0.8521209 0.2033305 -0.4635996 0.8595402 0.2150958 -0.4382988 0.8736038 0.2114492 -0.4009224 0.8865153 0.2309802 -0.3928825 0.8910391 0.2273604 -0.3602449 0.9057419 0.2232832 -0.3573895 0.9072641 0.2216858 -0.2948506 0.9257183 0.2368732 -0.2903652 0.9281694 0.2327871 -0.2464454 0.9437089 0.2206312 -0.2450996 0.9443889 0.2192168 -0.1612997 0.9618504 0.2209664 -0.1562663 0.9645017 0.2128784 -0.09544175 0.9764555 0.1934575 -0.09200453 0.9781396 0.1864885 0.005300462 0.9856217 0.1688843 0.0112546 0.9886287 0.149956 0.09873604 0.9877118 0.1211476 0.1077652 0.9914641 0.07338678 -0.2290327 0.9724199 0.04408705 -0.249503 0.9679794 0.02764594 -0.2556893 0.9648674 0.06044888 -0.2822108 0.9585677 0.03879654 -0.2941603 0.9526431 0.07707679 -0.3204579 0.9459491 0.04987078 -0.3368952 0.9378556 0.08323925 -0.3453224 0.9365389 0.06039214 -0.3647682 0.9265617 0.09180229 -0.3785083 0.9234916 0.06240838 -0.4013409 0.9117912 0.0869624 -0.3981279 0.9146352 0.07026195 -0.421306 0.902292 0.09149128 -0.4234811 0.9033645 0.06779861 -0.4482261 0.8902171 0.08128255 -0.4410942 0.8945167 0.07263535 -0.4636749 0.8821192 0.08289301 -0.4597981 0.8853009 0.06948512 -0.4862481 0.8707396 0.07331717 -0.482334 0.873287 0.06872934 -0.4994517 0.8637244 0.06729388 -0.4978155 0.864732 0.06647026 -0.5081943 0.8588752 0.06381434 -0.5088152 0.8584969 0.06395453 -0.5153961 0.8547558 0.06131464 -0.518221 0.8530339 0.06148427 -0.5234664 0.8500325 0.05854851 -0.5287107 0.8467726 0.05866324 -0.2902837 -0.9569106 -0.007589697 0.2905793 -0.9568156 -0.008216142 0.2378837 -0.97129 0.002674698 0.2205403 -0.9748024 -0.03350216 0.2027554 -0.9791917 -0.008605241 0.1237555 -0.992206 0.01456266 0.1432244 -0.9894435 -0.0220983 0.04066252 -0.9988991 0.02339607 0.06621724 -0.9972745 -0.03254151 0.01305407 -0.9999149 4.30463e-6 -0.01059639 -0.9999439 5.41151e-6 -0.04337459 -0.9989309 -0.0159927 -0.05976194 -0.9981349 0.01247012 -0.1295458 -0.9914826 -0.01342254 -0.1370731 -0.9905161 0.009424686 -0.1969778 -0.9803882 -0.006236553 -0.2212553 -0.9745652 -0.03562158 -0.2243074 -0.9741889 -0.02533978 -0.2379215 -0.9712798 0.002989947 -0.7226864 0.5017691 0.4753443 -0.7229784 0.5012534 0.4754441 -0.7353024 0.3145799 0.6003083 -0.73017 0.1202957 0.6725926 -0.6567914 0.6833455 0.3188481 -0.656512 0.6835927 0.3188935 -0.04493051 0.931189 0.3617574 -0.02509641 0.1626212 0.9863694 -0.05990159 0.3165035 0.9466982 -0.5239604 0.1029537 0.8454976 -0.4930782 0.2603182 0.8301256 -0.4673419 0.0251255 0.8837196 -0.3954516 0.2299283 0.8892419 -0.3909749 0.1465525 0.9086589 -0.2944185 0.1549586 0.9430301 -0.2939907 0.2517532 0.9220574 -0.1989468 0.1072857 0.9741201 -0.1804466 0.3206367 0.9298555 -0.1377267 0.1843228 0.9731683 -0.08310663 0.1757122 0.9809274 -0.561491 0.07998347 0.8236083 -0.6012051 0.275086 0.7502535 -0.5816245 -0.1300951 0.8029871 -0.6842345 0.3577855 0.6354626 -0.6763876 0.02960419 0.7359507 -0.7206774 0.06738018 0.6899883 -0.7102007 0.01389718 0.7038621 -0.0592336 0.4871497 0.8713074 -0.06516772 0.5406033 0.8387499 -0.1854401 0.5325628 0.8258262 -0.1842859 0.5238291 0.8316501 -0.3060553 0.5076792 0.8053522 -0.30417 0.4933456 0.8149177 -0.4175506 0.4706593 0.7772589 -0.4150378 0.4516062 0.7898073 -0.5176591 0.4241776 0.7430359 -0.5146086 0.4011883 0.757777 -0.606384 0.3705379 0.7035624 -0.602822 0.3444021 0.7197172 -0.6837903 0.3120433 0.6595907 -0.6798682 0.283618 0.6762693 -0.7400137 0.2561091 0.6219227 -0.05537879 0.7584963 0.6493202 -0.06151813 0.8307583 0.5532236 -0.1687324 0.8234214 0.5417625 -0.1683301 0.8175738 0.5506705 -0.27895 0.8029339 0.5267677 -0.2791497 0.7933087 0.5410516 -0.3818439 0.7728052 0.5069196 -0.383133 0.7595692 0.525608 -0.4755565 0.7349115 0.4834781 -0.4781047 0.7184351 0.5052396 -0.5599609 0.6911618 0.4568799 -0.5638788 0.6716352 0.4805693 -0.6350035 0.6432622 0.4277667 -0.6400995 0.6212257 0.4520526 -0.6895972 0.5988474 0.4072316 -0.6566801 0.683446 0.3188617 -0.5327947 0.8378635 0.1188057 -0.5389638 0.8321895 0.1303023 -0.5011833 0.8494809 0.1649174 -0.4884127 0.8618111 0.1368749 -0.4376992 0.8820145 0.174556 -0.4275094 0.8919506 0.1471729 -0.3678166 0.9118196 0.1824716 -0.3604683 0.919443 0.1571218 -0.2921409 0.9376586 0.1882821 -0.287642 0.9431526 0.1665096 -0.2111602 0.9584213 0.1919381 -0.209158 0.9620541 0.1752281 -0.1408202 0.9716103 0.1901133 -0.1393539 0.9489769 0.2828839 -0.09730416 0.9777441 0.1858724 -0.04695779 0.9804604 0.1910299 -0.03740155 0.994183 0.1010021 0.5327947 0.8378635 0.1188057 0.0724554 0.1738354 0.9821057 0.06657826 0.486921 0.8709049 0.04493182 0.931189 0.3617574 0.0695216 0.7578119 0.6487588 0.6281042 0.7075333 0.3238548 0.666021 0.6629978 0.3418335 0.73017 0.1202957 0.6725926 0.7359888 0.4148731 0.5349774 0.7100015 0.01381903 0.7040646 0.6002373 0.2646303 0.7547754 0.5867674 -0.1178545 0.8011332 0.6842253 0.3522485 0.6385584 0.6767824 0.02987897 0.7355766 0.72064 0.06690573 0.6900737 0.1249342 0.1820719 0.975316 0.1934688 0.283871 0.9391418 0.1676651 0.1184407 0.9787034 0.2957382 0.215593 0.9306227 0.2840312 0.1552204 0.9461675 0.388965 0.1447595 0.9098083 0.3941023 0.1676176 0.9036526 0.4753128 0.09183108 0.8750113 0.4989272 0.1922052 0.8450614 0.5256935 0.1011489 0.8446392 0.5620092 0.07880258 0.8233686 0.03740155 0.994183 0.1010021 0.04695779 0.9804604 0.1910299 0.09730499 0.9777448 0.1858685 0.1393539 0.9489769 0.2828839 0.5846914 0.7878591 0.1934273 0.5413388 0.8309943 0.1280658 0.5036348 0.8484569 0.1627054 0.4858316 0.8629511 0.1388635 0.4402217 0.8811166 0.1727381 0.424879 0.8929421 0.1487697 0.3702302 0.9111199 0.1810804 0.3579533 0.9202231 0.1583006 0.2942977 0.9371737 0.1873346 0.2854419 0.9436872 0.1672651 0.2128489 0.9581546 0.1914034 0.2074259 0.962358 0.1756178 0.1408202 0.9716103 0.1901133 0.04991716 0.8309788 0.5540601 0.1687245 0.8234226 0.5417633 0.1683339 0.8175729 0.5506708 0.2789498 0.8029341 0.5267674 0.2791495 0.7933077 0.541053 0.3818439 0.7728052 0.5069196 0.3831331 0.7595682 0.5256093 0.4755565 0.7349115 0.4834781 0.4781054 0.7184367 0.5052367 0.5599609 0.6911618 0.4568799 0.563875 0.6716383 0.4805696 0.6350051 0.6432598 0.4277678 0.640099 0.6212242 0.452055 0.695146 0.5960395 0.4018819 0.7075611 0.5264268 0.4714151 0.01438653 0.1626521 0.9865787 0.05978101 0.2807573 0.9579153 0.05855184 0.5408127 0.8391027 0.1854401 0.5325628 0.8258262 0.1842864 0.5238307 0.8316491 0.3060553 0.5076792 0.8053522 0.3041691 0.4933441 0.8149189 0.417551 0.4706577 0.7772597 0.4150374 0.4516063 0.7898073 0.5176591 0.4241776 0.7430359 0.5146026 0.4011904 0.75778 0.606384 0.3705379 0.7035624 0.6028273 0.3444021 0.7197127 0.6837903 0.3120433 0.6595907 0.6798663 0.2836178 0.6762713 0.7371042 0.257541 0.6247799 0.7412217 0.3067891 0.5970519 0.3659521 -0.1711603 0.9147586 0.2638488 -0.1476911 0.95319 0.1670534 -0.1181596 0.9788419 -0.02802962 -0.980304 0.195496 -0.02747911 -0.985702 0.1662423 -0.006407856 -0.87459 0.484821 0.0111382 -0.8093215 0.5872604 0.01653522 -0.7173161 0.6965516 0.02959948 -0.5899167 0.8069215 0.0453633 -0.4651892 0.8840483 0.0452609 -0.3766641 0.9252436 0.1087113 -0.131697 0.9853111 0.05644971 -0.2659363 0.9623364 0.05092936 -0.3012807 0.9521744 0.01579374 -0.1087385 0.993945 0.2569315 -0.2810003 0.9246757 -0.1869839 -0.9631336 0.1934182 -0.205733 -0.9645487 0.1652866 0.01170998 -0.8553144 0.5179771 0.02645307 -0.8385064 0.5442492 0.2369492 -0.5668752 0.7889916 0.2496636 -0.5387696 0.804609 0.4065244 -0.1817196 0.895386 0.3670125 -0.3223057 0.8725944 -0.1353932 -0.9703524 0.2002124 -0.1472887 -0.9732576 0.1762833 0.02682042 -0.8218072 0.5691342 0.01393592 -0.8352898 0.5496334 0.1930796 -0.4993113 0.8446353 0.1815181 -0.521203 0.8339057 0.2511617 -0.3284924 0.9105002 0.325117 -0.1606256 0.9319326 -0.0820648 -0.9757637 0.2028563 -0.08740121 -0.9784964 0.1868309 0.01828598 -0.8099138 0.586264 0.01248908 -0.8193635 0.5731383 0.1207305 -0.4714484 0.8735907 0.1155272 -0.4860451 0.8662642 0.1546235 -0.3046932 0.9398157 0.2261622 -0.141246 0.9637947 -0.4175049 -0.185502 0.8895385 -0.3661546 -0.1718312 0.9145517 -0.231868 -0.1425873 0.9622402 -0.2637776 -0.1480445 0.9531549 -0.2561774 -0.2895762 0.9222357 -0.0631864 -0.2507312 0.9659925 -0.1100146 -0.129044 0.9855174 -0.1289918 -0.1306557 0.9830007 -0.02248412 -0.1087262 0.9938175 -0.04862481 -0.3326699 0.941789 -0.0452609 -0.3766641 0.9252436 -0.0453633 -0.4651892 0.8840483 -0.02959948 -0.5899167 0.8069215 -0.01653522 -0.7173161 0.6965516 -0.0111382 -0.8093215 0.5872604 0.00640583 -0.87459 0.484821 0.08590465 -0.9787108 0.1864014 0.2031629 -0.9653544 0.1637555 -0.3663754 -0.2920346 0.8834506 -0.2340804 -0.5658212 0.7906028 -0.2527215 -0.5395005 0.8031633 -0.008852124 -0.8543041 0.5196981 -0.02956569 -0.8392921 0.5428764 0.1897534 -0.9623565 0.1945865 0.1450857 -0.9737628 0.1753182 0.1377189 -0.9698918 0.2008569 -0.0268265 -0.8218086 0.5691319 -0.01393598 -0.8352916 0.5496305 -0.1930803 -0.4993125 0.8446342 -0.1815189 -0.5212048 0.8339045 -0.2507688 -0.3297382 0.910158 -0.3267288 -0.1616645 0.931189 0.03026962 -0.9856258 0.1662095 0.02574294 -0.9804279 0.1951885 0.08361679 -0.9755893 0.2030616 -0.01827996 -0.8099125 0.5862659 -0.01248908 -0.8193653 0.5731357 -0.1207249 -0.4714496 0.8735908 -0.1155276 -0.4860469 0.8662632 -0.1691725 -0.2251681 0.9595207 -0.1554328 -0.2796219 0.9474451 0.9913212 -0.02696692 0.1286665 0.9892359 0.003844857 0.1462793 0.9893309 -0.0424447 0.1393662 0.9840762 -0.06662416 0.1647885 0.991223 -5.31822e-5 0.1322005 0.9912211 1.692e-4 0.1322146 0.9912199 2.69829e-4 0.1322233 0.9912124 2.99034e-4 0.1322793 0.9912136 3.05568e-4 0.132271 0.991235 1.76146e-4 0.132111 0.9926955 -0.001678705 0.1206359 0.9913615 2.71924e-6 0.1311586 0.9912932 -9.41149e-6 0.1316733 0.9912458 -1.30085e-4 0.1320299 0.9912381 -1.81777e-4 0.1320866 0.9912203 -2.75444e-4 0.1322211 0.9912125 -3.39365e-4 0.1322787 0.9912188 -2.56988e-4 0.1322315 0.9912212 -2.12208e-4 0.132214 0.9912825 4.07832e-5 0.1317538 0.9918196 -6.13865e-4 0.1276463 0.9925076 0.01022046 0.1217544 0.9927443 0.006715357 0.1200574 0.9932087 0.001495599 0.1163374 0.9974736 -0.001799881 0.0710169 0.9974356 -2.30584e-6 0.07156968 0.9937225 1.60115e-4 0.1118738 0.9938426 0 0.1108018 0.9940056 0 0.1093298 0.9939947 2.68002e-5 0.1094291 0.9941787 -1.99139e-5 0.1077442 0.9944497 5.05801e-4 0.1052117 0.9947971 0.002803802 0.1018375 0.9951184 0.006697416 0.09846055 0.9953807 0.01186859 0.09527075 0.995597 0.008027553 0.09339326 0.9962397 6.06039e-4 0.08663743 -0.9838752 -0.06619042 0.166158 -0.9882601 -0.0494703 0.1445503 -0.9890998 -0.05124491 0.1380423 -0.9974751 0 0.07101714 -0.9933329 0.001570224 0.1152715 -0.9912226 -1.09786e-4 0.1322034 -0.9912191 -2.65731e-4 0.1322294 -0.9912126 -3.31993e-4 0.1322779 -0.9912205 -2.77994e-4 0.1322187 -0.9912409 -1.59472e-4 0.1320667 -0.9912932 -9.41149e-6 0.1316733 -0.9913594 5.43847e-6 0.131174 -0.9927712 0.008944511 0.1196895 -0.9923261 0.003037393 0.1236114 -0.9914975 -1.61646e-4 0.1301265 -0.9914914 -2.09632e-4 0.1301724 -0.9912824 4.62219e-5 0.1317551 -0.9912353 1.71384e-4 0.1321085 -0.9912143 2.93623e-4 0.1322664 -0.9912133 3.09283e-4 0.1322728 -0.9912135 3.0041e-4 0.1322717 -0.991222 1.59298e-4 0.1322086 -0.9912237 -6.0661e-5 0.1321953 -0.9977036 0.01641207 0.06571406 -0.9969987 -8.13954e-4 0.07741457 -0.9954489 0.001939475 0.09527736 -0.9957328 0.02040815 0.08999854 -0.9946257 -0.001532673 0.1035248 4.01769e-5 1 1.83895e-4 0.001157045 0.9999988 -0.001029133 0.002719879 0.9999948 -0.001744985 -0.01972693 0.9997838 -0.006593286 -0.02259945 0.9997165 -0.007511556 -0.01405376 0.9998931 -0.004025101 -0.02170902 0.9997488 -0.005580246 -2.48895e-6 1 9.32252e-5 2.64382e-6 1 1.29547e-4 1.95296e-5 1 2.32438e-4 -1.9916e-5 1 2.56559e-5 -7.05205e-6 1 -4.89457e-6 0 1 -4.11167e-6 0 1 -4.11168e-6 2.40832e-5 1 -1.04612e-6 6.96836e-4 0.9999996 -5.76979e-4 4.41075e-4 0.9999999 -4.20995e-4 1.65059e-4 1 -2.26869e-4 1.43246e-5 1 -1.54976e-5 7.23779e-4 0.9999997 -5.39676e-4 0.001796841 0.9999955 -0.002416491 0.001218438 0.9999976 -0.001834869 0.001605153 0.9999948 -0.002818524 3.42781e-4 0.9999993 -0.00118649 1.38457e-4 1 -3.30203e-4 -1.42597e-5 1 -6.95482e-5 -2.69531e-5 1 9.00784e-5 -4.70088e-5 1 1.28769e-4 -5.11329e-5 1 2.19134e-4 -4.72503e-5 1 2.99955e-4 2.73761e-5 1 1.41661e-4 3.52553e-5 1 1.39397e-4 4.67852e-5 1 1.08056e-4 -1.44414e-6 1 -4.40046e-6 7.32635e-5 1 -2.02335e-4 -7.90094e-4 0.9999982 -0.001749932 -8.10849e-4 0.9999983 -0.00167936 6.22198e-4 0.9999999 -1.92092e-4 -0.004094421 0.9999909 0.001173436 0.01059663 0.9999309 -0.005103528 0.0164569 0.9998264 -0.008735358 -9.21229e-4 0.9999996 -1.08578e-4 0.03252321 0.9994565 0.005390286 0.01327306 0.9999101 0.001967847 0.05923801 0.9982069 0.008587419 0.02190923 0.999756 0.002817213 0.002504348 0.9999969 2.79276e-4 -0.002057731 0.999992 -0.003445565 -0.002130329 0.9999931 -0.003075838 -0.001804292 0.9999963 -0.002061128 -6.91681e-4 0.9999994 -8.68475e-4 -5.55882e-4 0.9999998 -6.06106e-4 -0.00100398 0.9999991 -0.001002609 -8.06086e-4 0.9999995 -6.31479e-4 -6.87199e-4 0.9999996 -5.4647e-4 -0.001113057 0.9999986 -0.001223564 -8.14313e-4 0.9999995 -5.62526e-4 -8.42885e-4 0.9999995 -5.9079e-4 -0.002715647 0.9999951 -0.001620233 -0.003819406 0.9999896 -0.002490699 -0.01807761 0.9998006 -0.008495986 -0.02030766 0.9997453 -0.009849429 -0.02494484 0.9996358 -0.01030921 -0.02496135 0.9996389 -0.009966135 0.009854257 0.9999412 -0.004544258 0.01869875 0.999809 -0.005691051 7.07776e-4 0.9999998 -2.45558e-4 4.19135e-4 1 -1.18612e-4 0.005087852 0.9999869 5.93782e-4 0.01169604 0.9999291 0.002261281 0.02444243 0.9996885 0.005056321 -0.008890748 0.9999594 -0.001525461 -0.009881675 0.9999498 -0.001721441 0.003637075 0.9999924 -0.001398503 0.004644751 0.9999886 -0.001174807 0.004496812 0.9999893 -0.001157283 0.002163171 0.9999977 -1.50947e-6 -0.003265082 0.9999945 7.26191e-4 -0.003349184 0.999994 9.0364e-4 -0.00407207 0.9999915 7.84139e-4 -0.001122474 0.9999994 -1.20324e-4 -1.53521e-6 1 -1.29483e-7 -0.002174556 0.9999976 4.11058e-4 -0.002287328 0.9999973 3.18372e-4 0 1 0 0 1 0 0 1 0 0 1 0 -6.01201e-5 1 -8.23572e-6 -3.29364e-5 -1 -4.77799e-6 -6.8133e-5 1 4.7426e-5 -4.27246e-4 1 3.3644e-4 -4.08488e-4 1 3.46926e-4 0 1 -1.52671e-5 -2.17085e-5 1 1.88299e-4 0 1 -8.65651e-5 0 1 0 0 1 -5.77005e-7 0 1 8.82394e-7 0 1 -4.34752e-6 0 1 -1.14333e-6 0 1 7.32966e-6 0 1 8.8423e-7 0 1 2.62558e-6 0.6678634 -0.4854717 -0.5641592 0.7313795 -0.4750397 -0.489307 0.707436 -0.005401253 -0.7067568 0.7088956 -0.01169306 -0.7052166 0.7129139 -0.12286 -0.6904051 0.7079277 -0.1024404 -0.6988165 0.7066971 -0.05446559 -0.7054167 0.712719 -0.4755435 -0.5156453 0.7051457 -0.4295349 -0.5641537 0.7097112 -0.3799334 -0.5932627 0.7038736 -0.3619455 -0.6111935 0.7073227 -0.3242908 -0.6281164 0.7052769 -0.2745557 -0.6536083 0.712199 -0.2486979 -0.6564465 0.708295 -0.2179127 -0.6714404 0.7049885 -0.1722569 -0.6879817 -0.1300773 0.9900423 0.05381703 0.9446606 0.2378724 0.2259048 0.9452716 0.2360419 0.2252689 0.7212649 0.659377 0.2121295 0.7254574 0.6551792 0.2108359 0.333558 0.9306897 0.1501858 0.3430457 0.9274484 0.1488601 -0.1301852 0.9900008 0.05431628 -0.1161795 0.9918078 0.0531004 -0.1440649 0.9880348 0.05507057 0.3334486 0.9306465 0.1506956 0.3239141 0.9337869 0.1520589 0.7211187 0.6593121 0.2128272 0.716885 0.6634858 0.2141555 0.9445951 0.2378458 0.2262071 0.9439843 0.23965 0.2268516 0.1917342 0.9814454 0.001736581 0.1642777 0.9864142 2.07792e-5 0.2120465 0.9772596 -9.46492e-6 0.3568791 0.9340962 0.0100786 0.3497138 0.9368351 0.006355464 0.3457439 0.9383179 0.004562735 0.3453779 0.9384533 0.004418253 0.3460025 0.9382221 0.004650175 0.3476564 0.9376074 0.005239307 0.3510282 0.9363436 0.006320595 0.3508755 0.9364011 0.006282746 0.2420443 0.9702648 9.48551e-4 0.2279105 0.9736822 5.23454e-5 0.2788823 0.9603254 -3.02812e-5 0.3092436 0.9509577 0.006916105 0.3078863 0.95142 0.002496778 0.3015193 0.9534568 -0.002511858 0.2669099 0.9636791 0.009048879 0.2403859 0.9703421 0.02551436 0.3439318 0.9389813 0.005023837 0.3345491 0.9423711 0.003686726 0.3186877 0.9478579 0.001940131 0.3092082 0.9509579 0.008339941 0.3062114 0.9519051 0.01056009 0.512198 0.85882 -0.009019911 0.5188522 0.8548464 0.005501866 0.5051167 0.8630474 -0.00252074 0.5010377 0.8654177 0.003683567 0.498845 0.8665866 0.01347529 0.5021759 0.8646157 0.01609539 0.4964064 0.8680102 0.01179993 0.4911261 0.8710501 0.008188009 0.4851833 0.8744 0.004671216 0.460366 0.8877093 -0.005953371 0.4775748 0.8785893 0.001759707 0.4381757 0.8988662 -0.006461322 0.4668536 0.8842393 0.01298785 0.4602366 0.8877533 0.00874871 0.4533446 0.8913177 0.005607664 0.4465508 0.8947533 0.002985477 0.2685715 0.9623912 -0.04089623 0.3371051 0.9413774 -0.0130009 0.4101848 0.9119959 0.003451347 0.3961814 0.9181719 -8.95589e-4 0.4311578 0.9022765 2.42371e-4 0.438628 0.8986679 0.001263201 0.1716726 0.9851539 6.32251e-4 0.1378762 0.9904495 -1.19464e-4 0.1098917 0.9939436 1.74923e-4 0.1041563 0.994561 -1.44614e-6 0.07627993 0.9970865 1.82096e-6 0.04386311 0.9990374 -6.84613e-4 0.03240203 0.999475 7.36112e-7 -0.03240203 0.999475 7.36112e-7 -0.04386311 0.9990374 -6.84613e-4 -0.07627993 0.9970865 1.79488e-6 -0.1041563 0.994561 -1.44614e-6 -0.1098917 0.9939436 1.749e-4 -0.1378763 0.9904495 -1.19464e-4 -0.1716725 0.9851539 6.32251e-4 -0.1917338 0.9814454 0.001736342 -0.2107504 0.9775356 0.002928197 -0.2390816 0.9709832 0.005644917 -0.1632225 0.9865812 -0.004011869 -0.2975184 0.9547159 8.01562e-4 -0.2279105 0.9736822 5.23777e-5 -0.2598295 0.9656545 6.23963e-7 -0.2750369 0.9614337 6.0869e-5 -0.3093553 0.9509454 0.001504421 -0.3180247 0.9480802 0.002077102 -0.3272148 0.9449456 0.002887308 -0.3460035 0.9382218 0.004650473 -0.3453779 0.9384533 0.004418253 -0.3457419 0.9383187 0.004561603 -0.3295083 0.9441475 0.003127813 -0.3345491 0.9423711 0.003686726 -0.3439318 0.9389812 0.005023717 -0.3508754 0.9364012 0.006282627 -0.3510282 0.9363436 0.006320595 -0.3476558 0.9376076 0.005238592 -0.3961812 0.9181721 -8.95588e-4 -0.4101848 0.9119959 0.003451347 -0.3497145 0.9368348 0.006355643 -0.3568768 0.9340971 0.01007932 -0.2685715 0.9623912 -0.04089623 -0.3371052 0.9413773 -0.0130009 -0.4311578 0.9022765 2.42371e-4 -0.4386287 0.8986675 0.001263201 -0.4465508 0.8947533 0.002985477 -0.453343 0.8913186 0.005606591 -0.4602395 0.8877517 0.00874871 -0.4403044 0.8978405 -0.003812253 -0.4719817 0.8816083 5.82121e-4 -0.4647253 0.8854545 -9.46772e-4 -0.4776545 0.8785467 0.001426935 -0.4851833 0.8744 0.004671216 -0.4997611 0.8661106 0.009557962 -0.4993586 0.8662821 0.01401507 -0.4964154 0.868005 0.01179987 -0.4911261 0.8710501 0.008188009 -0.5010395 0.8654167 0.003683567 -0.5051045 0.8630546 -0.00252074 -0.5188547 0.8548448 0.005501925 -0.5121905 0.8588245 -0.009019792 -0.9444662 0.2377958 0.2267966 0.1292941 0.9903323 0.05024957 0.1170747 0.9914745 0.05720037 -0.3341914 0.9309266 0.1472817 -0.3424034 0.9272114 0.1517859 -0.7216427 0.6595221 0.2103869 -0.7250726 0.6550376 0.2125921 -0.9447876 0.2379205 0.225323 -0.9451428 0.2359959 0.2258563 -0.9441115 0.2397018 0.2262668 -0.7207222 0.6591679 0.2146096 -0.7172725 0.6636353 0.2123875 -0.3327994 0.9303936 0.1536634 -0.3245544 0.9340393 0.1491141 0.1309815 0.9896885 0.05797016 0.1431663 0.9883863 0.05095028 0.766982 0.5500981 0.3303494 0.7231496 0.6683318 0.1743198 0.7120684 0.6450228 0.277316 0.7137072 0.6314195 0.3032024 0.7554171 0.5874795 0.2901945 0.7500323 0.6062909 0.2643163 0.6475396 0.7493795 0.1382855 0.633865 0.7582631 0.1524866 0.6125295 0.7863732 0.08015561 0.6620281 0.677379 0.3207437 0.642503 0.6563475 0.3954718 0.6430107 0.7180226 0.2664225 0.5692172 0.8144253 0.1127091 0.5624123 0.8055825 0.1863579 0.5384662 0.8411015 0.05101394 0.6810728 0.664619 0.3072808 0.6817418 0.6655915 0.3036708 0.5835419 0.8048552 0.1081064 0.5837572 0.8057295 0.100138 0.5229299 0.7475202 0.4095827 0.5231251 0.7396 0.4234763 0.5349768 0.7236597 0.4360235 0.5565447 0.7018494 0.444596 0.5905624 0.671252 0.4479475 0.6492353 0.6207489 0.4395045 0.4933214 0.7248917 0.4807974 0.486529 0.7289521 0.4815792 0.2906571 0.798808 0.5267108 0.2318115 0.8135113 0.5333506 0.009044706 0.8915573 0.4528178 -0.1843649 0.8432139 0.5049752 0.1003255 0.8240532 0.5575582 0.0457201 0.8528111 0.5202144 0.114503 0.8354969 0.5374329 -0.7570319 0.5995528 0.2596909 -0.5293636 0.7575904 0.3818784 -0.4313678 0.8082947 0.4007263 -0.09736883 0.8768448 0.4708105 0.02999383 0.8827484 0.4688879 0.1658347 0.8676036 0.4687888 0.4843869 0.7697359 0.4157837 0.4859496 0.7688976 0.415511 0.4844045 0.8151485 0.3176245 0.4828148 0.8160231 0.317799 0.02994686 0.9313588 0.3628692 0.02865749 0.9314387 0.3627684 -0.4309015 0.8408342 0.3276002 -0.4318528 0.8404456 0.3273446 -0.5507909 0.7777262 0.3029378 -0.7558948 0.6175371 0.217419 -0.8863109 0.435805 0.1566115 0.1765321 0.9841668 0.01588374 0.1849019 0.9824748 0.0235508 -0.3005041 0.9530089 0.03835856 -0.2789304 0.958476 0.0593453 -0.7087914 0.703644 0.05000025 -0.6818996 0.7264043 0.08573186 -0.9548848 0.2933183 0.04647004 -0.9364314 0.3366994 0.09864014 0.1684455 0.9855515 0.01773679 0.1771935 0.9838362 0.02586245 -0.3209572 0.9461167 0.04300808 -0.2986962 0.9521201 0.06517732 -0.7328642 0.6780974 0.0556249 -0.7057795 0.7022467 0.09340798 -0.9678395 0.2464174 0.05064767 -0.9506943 0.291478 0.1059289 -0.9902129 -0.1153814 0.07852101 -0.9905568 0.05122584 0.1271741 -0.9853534 -0.06031066 0.1595038 -0.9829251 0 0.184006 -0.9224115 0.3699555 0.1108607 -0.8863614 0.4423459 0.1367248 -0.7213277 0.6626521 0.2014412 -0.7559061 0.6289754 0.1816479 -0.3554167 0.8921085 0.2789651 -0.432376 0.865795 0.2518932 0.07847511 0.9537819 0.290072 0.02868682 0.959277 0.2810066 0.4972941 0.8316092 0.2472343 0.4833967 0.8399742 0.246518 -0.944608 0.3153465 0.09095251 -0.9104902 0.3978334 0.1128554 -0.7189018 0.6745519 0.1678093 -0.7215447 0.6719168 0.1670362 -0.3541825 0.9115767 0.2087649 -0.3560553 0.9109007 0.2085297 0.07743972 0.974649 0.2099106 0.07740134 0.9746508 0.209917 0.4941347 0.8523706 0.1711586 0.4957666 0.8514447 0.1710481 0 3.66548e-4 -1 3.16136e-4 5.21888e-4 -0.9999998 -0.755023 -0.4410725 -0.4851755 -0.7765973 -0.1934447 -0.5995631 -0.7854401 -0.008819401 -0.618875 -0.7707247 -0.1573048 -0.6174454 -0.7858175 -0.108577 -0.6088531 -0.7720263 -0.08735835 -0.6295587 -0.7749593 -0.02203232 -0.6316271 -0.7197888 -0.008795559 -0.6941375 -0.7585069 -0.2716384 -0.5923513 -0.773167 -0.2203359 -0.5946975 -0.7751796 -0.1891083 -0.6027724 -0.790407 -0.2320275 -0.5669392 -0.7670542 -0.2931636 -0.5706864 -0.7553182 -0.3515349 -0.5530982 -0.7887767 -0.3134136 -0.5287752 -0.726028 -0.4078702 -0.5536472 1 0 -1.17696e-6 1 -7.45231e-6 1.31589e-6 1 1.31355e-6 -7.22463e-7 1 -3.43059e-6 -1.06737e-6 0 1 -3.97065e-6 0 -0.8603655 0.5096776 0 -0.8603657 0.5096773 0 -0.001960754 -0.9999982 0 -0.001960754 -0.9999981 0.002132177 -0.002177834 -0.9999954 0.0660656 -0.01005476 -0.9977647 -0.04330945 -0.07119208 -0.996522 0.2289932 -0.1201296 -0.9659872 -0.3659203 -0.1743758 -0.9141639 0 -0.2306409 -0.973039 0 -0.2966872 -0.9549748 -0.3289687 -0.3309246 -0.8844596 0.1440168 -0.3832467 -0.9123492 -0.1749254 -0.4924951 -0.8525549 0 -0.4900677 -0.8716844 0 -0.509678 -0.8603653 0 -0.5096801 -0.860364 -4.00945e-4 -0.509701 -0.8603515 4.85093e-7 -0.5096778 -0.8603655 0 -0.509678 -0.8603652 2.3405e-5 -0.5096762 -0.8603664 0 -0.5096778 -0.8603655 5.12611e-6 -0.5096779 -0.8603653 0 1 -6.8132e-6 0 1 -2.1549e-6 0.5516436 -0.004793167 -0.8340663 0.6783643 -0.005615651 -0.7347043 0.6874084 -0.459786 -0.562198 0.6418952 -0.2367004 -0.7293445 0.6410524 -0.2972378 -0.7076027 0.6410546 -0.2972384 -0.7076004 0.6410519 -0.3910772 -0.6603871 0.6410533 -0.3910754 -0.6603868 0.6256617 -0.1894711 -0.7567352 0.6410537 -0.1978286 -0.7415619 0.6415306 -0.1112597 -0.7589861 0.6266173 -0.09617882 -0.7733695 0.6418504 -0.05903351 -0.7645542 0.6416595 -0.01272881 -0.766884 0.6163358 -0.03902071 -0.7865161 0.4828248 -0.03409248 -0.8750531 0.258627 -0.04623562 -0.9648701 0.336253 -0.01104599 -0.941707 0.411198 -0.007077932 -0.9115186 0.1604295 -0.009522795 -0.9870014 0.2002285 -0.01028805 -0.9796953 0.0189315 -0.01007515 -0.9997701 0.05966359 -0.0166347 -0.99808 0.1138843 -0.03890669 -0.9927319 0.08818995 -0.02191233 -0.9958627 0.08803319 -0.1229321 -0.9885029 0.08802998 -0.1229308 -0.9885033 0.08816683 -0.2297425 -0.9692498 0.1180478 -0.2559577 -0.9594532 0.08821195 -0.2955308 -0.951252 0.08803689 -0.3857773 -0.9183819 0.08803528 -0.3857799 -0.918381 0.08812689 -0.4915544 -0.8663763 0.0728358 -0.4988859 -0.8636016 0.3464202 -0.4779971 -0.8071628 0.7130521 -0.4247199 -0.5578259 0.6722324 -0.431533 -0.6015671 0.6418909 -0.4246307 -0.6384864 0.5920404 -0.4909749 -0.6390867 0.4938237 -0.4612089 -0.7371734 0.2807769 -0.02759176 -0.9593765 0.2802615 -0.1184667 -0.9525855 0.280262 -0.1184653 -0.9525856 0.2802643 -0.2474303 -0.927486 0.2802638 -0.2474296 -0.9274863 0.2802615 -0.3717611 -0.8850126 0.2802626 -0.3717604 -0.8850125 0.2806296 -0.4679686 -0.8380051 0.2207452 -0.4962325 -0.8396577 0.4799559 -0.03171223 -0.8767193 0.4791522 -0.1083232 -0.871022 0.4791578 -0.1083223 -0.8710191 0.4791538 -0.2262427 -0.8480719 0.4791524 -0.2262444 -0.8480722 0.4791533 -0.3399314 -0.8092334 0.4791564 -0.3399286 -0.8092328 0.479155 -0.4472446 -0.7552369 0.4791547 -0.4472472 -0.7552356 0.4602894 -0.2435783 -0.8536999 0.1032243 -0.9686022 -0.2261736 0.9829251 0 0.184006 0.9853534 -0.06031066 0.1595038 0.9905568 0.05122572 0.1271737 0.9902129 -0.1153814 0.07852101 0.9518866 0.2919703 0.09308785 0.9397251 0.3381424 0.05076068 0.7065787 0.7026599 0.08375954 0.684152 0.7275486 0.05107831 0.2991169 0.9523748 0.05925774 0.2802522 0.9591785 0.03788584 -0.1770551 0.9839121 0.02384698 -0.1844176 0.982728 0.0153681 0.9643964 0.2448716 0.0998882 0.9544749 0.2931088 0.05536144 0.7303212 0.6769768 0.09128808 0.7084036 0.7035193 0.05678904 0.3193663 0.9453913 0.06511926 0.300243 0.9529169 0.04246801 -0.1690486 0.9852592 0.02620828 -0.176621 0.9841294 0.01715821 0.956657 0.2785074 0.08509463 0.7214482 0.6646632 0.1942561 0.7560183 0.6261367 0.1907594 0.8863614 0.4423459 0.1367248 0.3557094 0.8968263 0.2630086 0.3873336 0.883116 0.2647243 0.5938844 0.7702648 0.2323651 -0.4973033 0.8324992 0.244202 -0.4977732 0.8322681 0.244032 -0.07839 0.9558192 0.2833104 -0.07805335 0.9558255 0.2833823 0.1754208 0.9434809 0.2811964 -0.4857575 0.8568986 0.1725243 -0.4957484 0.8516181 0.1702363 -0.04828405 0.9761101 0.2118437 -0.07737642 0.9749596 0.2084864 0.3994576 0.8929699 0.2074576 0.3560577 0.9113788 0.206426 0.764645 0.6241877 0.1603361 0.7215136 0.6726467 0.164209 0.9144358 0.3888602 0.1122264 0.9224115 0.3699555 0.1108607 -0.4843843 0.7696621 0.4159233 0.5292977 0.7576312 0.3818888 0.7569974 0.5995919 0.2597009 0.8863223 0.435784 0.1566052 0.7558948 0.6175371 0.217419 0.550791 0.7777265 0.3029374 -0.2906571 0.798808 0.5267108 -0.2317203 0.8135343 0.5333551 -0.114503 0.8354969 0.5374329 -0.5350236 0.7236229 0.436027 -0.5704203 0.7265638 0.3830481 -0.5713343 0.686285 0.4501002 -0.6492701 0.6207427 0.4394621 -0.1736146 0.8720797 0.4575316 -0.1157053 0.8351615 0.5376967 0.05667829 0.8433991 0.5342897 -0.02999734 0.879381 0.475173 -0.4859234 0.7689856 0.415379 -0.4865136 0.7289584 0.4815851 -0.4933501 0.7248781 0.4807885 -0.5229299 0.7475202 0.4095827 -0.5231369 0.7395895 0.4234799 0.593172 0.750163 0.292237 0.4309442 0.839654 0.3305578 0.4313678 0.8082947 0.4007263 0.09736835 0.8768461 0.4708082 -0.009044706 0.8915573 0.4528178 0.1843624 0.8432187 0.5049682 -0.4971704 0.808454 0.3149982 -0.4844236 0.8147261 0.3186774 -0.07785141 0.9293852 0.3608079 -0.03000664 0.9305347 0.3649725 0.1748386 0.9174571 0.3573571 0.3868266 0.8592441 0.334761 -0.6775901 0.6365582 0.3683277 -0.644385 0.6872156 0.3354142 -0.6430109 0.7180228 0.2664213 -0.5946835 0.7876011 0.1613563 -0.5531148 0.8234701 0.1263367 -0.5384733 0.8410973 0.05100882 -0.5867569 0.8029166 0.1050776 -0.5804886 0.8077303 0.1029801 -0.68262 0.6636983 0.3058341 -0.6801856 0.6665558 0.3050426 -0.6711095 0.7327154 0.1128725 -0.7008652 0.6846883 0.1999748 -0.7624592 0.5822161 0.2822772 -0.747677 0.6080382 0.2669622 -0.766982 0.5500981 0.3303494 -0.70558 0.6493328 0.2837671 -0.7216076 0.6262771 0.2950585 -0.5941534 0.7983575 0.09801602 -0.6556107 0.7438712 0.1297317 -0.821855 0.5257061 0.2195165 -0.7837789 0.5373415 0.3113759 -0.7487323 0.5923797 0.2974665 -0.8078063 0.5481222 0.2168203 -0.8205851 0.5347018 0.2018268 -0.8162333 0.5396675 0.2062093 -0.7845374 0.5829395 0.2113828 -0.7959619 0.5717614 0.1988311 -0.7592855 0.6181107 0.2035307 -0.7720568 0.606881 0.1887429 -0.5337603 0.7682521 0.3533959 -0.8071554 0.5616011 0.1819462 -0.7293466 0.6702533 0.1371646 -0.926207 0.376944 -0.007343649 -0.7952617 0.5578816 0.2373332 -0.7885171 0.585148 0.1893221 -0.7977196 0.5753569 0.1805765 -0.5640544 0.8168077 0.1211105 -0.6796746 0.6627306 0.3143734 -0.6796283 0.6626766 0.3145874 -0.7509216 0.475262 0.4585227 -0.7440161 0.01313465 0.6680327 -0.7727108 0.2896052 0.5648425 -0.750946 0.4748945 0.4588631 -0.8713372 0.2600317 0.4161192 -0.7273861 0.6623951 0.1792827 -0.7145677 0.6794106 0.1667162 -0.8177811 0.4909557 0.3003274 -0.5946896 0.793684 0.1281023 -0.5963591 0.792737 0.1261901 -0.6098804 0.7801373 0.1393983 -0.6266087 0.7706047 0.116318 -0.6325775 0.7651934 0.1196859 -0.6370892 0.7624825 0.1128624 -0.6410123 0.7592374 0.1125251 -0.8169308 0.4935066 0.2984549 -0.7923802 0.5088965 0.3363897 -0.7923631 0.5089212 0.3363928 -0.7630659 0.5254552 0.3763343 -0.7630185 0.5255768 0.3762601 -0.7526648 0.5315014 0.3885896 -0.6797192 0.6626497 0.3144477 -0.8670552 0.1673403 0.4692681 -0.8426267 0.1823507 0.506684 -0.8437044 0.1738188 0.5078878 -0.8059107 0.1953178 0.5588909 -0.8063529 0.1736845 0.5653572 -0.7738209 0.191504 0.6037611 -0.7901872 0.1044409 0.603901 -0.1700319 -0.724206 0.6682924 -0.3057293 -0.6604501 0.68581 -0.5251752 -0.4143208 0.7433232 -0.7142316 -0.1236339 0.6889035 -0.6810629 -0.1700268 0.7122108 -0.4683939 -0.4988288 0.7292305 -0.4411761 -0.5854808 0.6801294 -0.4647759 -0.5350242 0.7055016 0.003855824 -0.5599405 0.8285239 -0.2050653 -0.7690224 0.605436 -0.2687026 -0.6967287 0.6651076 -0.3439455 -0.6478129 0.6797353 -0.460152 -0.4926933 0.7385889 -0.4966334 -0.4700834 0.7296416 -0.7127579 -0.1937655 0.6741151 -0.6914024 -0.2119643 0.6906765 0.9942559 -0.01423072 -0.1060785 0.9943476 -0.01713079 -0.1047834 0.992406 0.00268507 -0.1229767 0.992986 -0.003971934 -0.1181653 0.991816 0.005009114 -0.1275773 0.992554 -9.54379e-4 -0.1218026 0.9922502 0.00747174 -0.1240313 -0.7298693 0.3193178 -0.604423 -0.1210872 -0.7676507 0.6293253 0.1629234 -0.9066461 0.3891645 0.2306523 -0.9561944 0.1802546 -0.4834419 -0.208064 0.8502902 0.2235834 -0.934978 0.2753666 0.2547859 -0.9507547 0.1764929 0.1881191 -0.8973831 0.3991429 0.1235483 -0.8802239 0.4581941 0.05852407 -0.8647411 0.4987965 -0.1433306 -0.7678159 0.6244317 -0.2925397 -0.6224609 0.7259222 -0.3098765 -0.5997083 0.7377849 -0.2687082 -0.6508845 0.7100319 -0.257583 -0.6631633 0.7027556 -0.1363205 -0.7724528 0.620269 -0.5016059 -0.4230342 0.7546083 -0.7049524 -0.006332099 0.7092264 -0.6747866 -0.1323692 0.7260452 -0.5758698 -0.3114762 0.7558814 -0.4582813 -0.5076059 0.7295989 -0.6041082 -0.1758787 0.7772517 -0.597009 -0.2013701 0.7765504 -0.5048214 -0.3754029 0.7773211 -0.5458055 -0.2921769 0.7853209 -0.3684095 -0.5565277 0.7446821 -0.4189745 -0.4824488 0.7692229 -0.196002 -0.7228274 0.6626491 -0.207163 -0.7299418 0.651359 -0.3211124 -0.5831708 0.7461894 -0.4999635 -0.1395296 0.8547328 -0.383913 -0.4173876 0.8236495 -0.2724714 -0.5793096 0.7682186 -0.261018 -0.5990369 0.7569839 -0.01812738 -0.8575109 0.5141464 -0.05754661 -0.8127256 0.579798 0.2090389 -0.9508783 0.2283268 0.213881 -0.9369502 0.2763681 -0.5555818 -0.1913354 0.8091475 -0.6056964 -0.009612262 0.7956377 -0.4220029 -0.4338182 0.7960625 -0.4615473 -0.3522722 0.8141736 -0.2897813 -0.6114878 0.7362809 -0.337317 -0.5399135 0.771175 -0.06750768 -0.8170317 0.5726273 -0.1160941 -0.764948 0.6335432 0.2229083 -0.9350575 0.2756437 0.1549296 -0.9058575 0.3942321 -0.02843469 -0.4880706 0.8723409 0.001777172 -0.6421841 0.7665484 0.02057397 -0.8595176 0.5106919 0.2045716 -0.9003495 0.3840849 0.2698604 -0.9187155 0.2883356 0.2278212 -0.9225602 0.3114169 0.2334293 -0.898894 0.3708104 0.2138795 -0.9013564 0.3765796 0.1431952 -0.865705 0.4796354 0.2545045 -0.9319314 0.2583242 0.2263333 -0.9389921 0.2589732 0.2333091 -0.9363957 0.2621643 0.3110375 -0.9497972 0.03378075 0.289276 -0.9561566 0.04565298 0.3411754 -0.909501 -0.2375022 0.1918351 -0.9613707 0.1973974 0.1197902 -0.9807006 0.1545211 0.07028734 -0.9837568 0.1651735 0.05610364 -0.9890456 0.1365337 0.04066842 -0.9877549 0.15062 0.01167953 -0.9934883 0.113335 0.02637243 -0.504215 0.8631754 -0.07903188 2.50784e-4 0.9968721 -0.03065353 0.07005798 0.9970719 -0.05318534 1.43694e-7 0.9985847 -0.05293262 -0.02305811 0.9983319 -0.2990888 0.06918519 0.951714 -0.2412354 -0.01135659 0.9704003 -0.1684049 0.01317429 0.9856299 -0.1857226 0.04872697 0.9813933 -0.1264131 -0.005033195 0.991965 -0.1701247 -0.600774 0.7811071 -0.3043397 -0.250979 0.9189054 -0.313633 -0.2430425 0.9179132 -0.248792 -0.2212632 0.942945 -0.3180765 -0.1633398 0.9338883 -0.1922739 -0.2371721 0.9522501 -0.2023856 -0.2251699 0.953068 -0.1519142 -0.2136347 0.9650297 -0.1147391 -0.248288 0.961867 -0.1042646 -0.2243775 0.9689085 -0.03894942 -0.2168727 0.9754226 -0.03202742 -0.1899927 0.981263 0.3333746 -0.9418577 0.04201811 0.2480587 -0.9404771 0.2323143 0.2220138 -0.9492798 0.2226606 0.2394106 -0.9482991 0.2083541 0.1927602 -0.9617616 0.1945723 0.2068147 -0.9614234 0.1813634 0.1676236 -0.9706587 0.1724069 0.1627284 -0.9706519 0.1770722 0.1198245 -0.9806773 0.1546425 -0.01399797 -0.3521643 0.9358336 -0.01105141 -0.5532236 0.8329595 -0.01908743 -0.5536544 0.8325278 -0.02267748 -0.5499911 0.8348626 -0.03402805 -0.5512739 0.8336302 -0.04074275 -0.5454213 0.8371713 -0.05141609 -0.54725 0.8353884 -0.06184488 -0.539376 0.839791 -0.07286077 -0.5419156 0.8372688 -0.08763378 -0.532323 0.8419933 -0.09972083 -0.5358112 0.8384284 -0.1197635 -0.5243702 0.8430259 -0.1369639 -0.530343 0.8366464 -0.1582498 -0.5166488 0.8414458 -0.2520799 -0.5034425 0.826439 -0.1690165 -0.5562207 0.8136658 -0.2222732 -0.5801571 0.7835894 -0.2037736 -0.5777489 0.7903686 -0.005473136 -0.7617681 0.6478268 0.03652679 -0.8169239 0.5755878 0.0237292 -0.8177893 0.5750285 0.02027547 -0.8153671 0.5785893 0.03786832 -0.8133774 0.5805027 0.03128325 -0.8095398 0.5862309 0.04907888 -0.806489 0.5892087 0.03885382 -0.8014863 0.5967497 0.05525368 -0.7977077 0.6005077 0.04065334 -0.7917962 0.609431 0.054744 -0.7877255 0.6135891 0.03483587 -0.7809423 0.623631 0.04666239 -0.7768139 0.6279991 0.020931 -0.7697008 0.6380617 0.0295754 -0.766169 0.6419584 -0.003099918 -0.7586197 0.6515263 0.004089176 -0.7552395 0.6554361 -0.03799611 -0.7506424 0.6596153 -0.09565353 -0.8032929 0.5878528 -0.02214622 -0.7882843 0.6149125 0.00217694 -0.9332701 0.3591687 0.002183258 -0.933282 0.3591379 0.04932785 -0.9309841 0.3617118 0.04795664 -0.9293608 0.3660448 0.08090049 -0.925647 0.3696386 0.07799279 -0.923036 0.376725 0.1095363 -0.9176447 0.382008 0.104512 -0.9140476 0.3919113 0.132785 -0.9075531 0.3983913 0.1249991 -0.9030693 0.4109028 0.1490093 -0.8961458 0.4179942 0.1376693 -0.8907448 0.4331524 0.1572723 -0.883925 0.4403887 0.1418694 -0.877832 0.4574759 0.1560366 -0.8720468 0.4638826 0.1353908 -0.8651179 0.4829498 0.1422666 -0.8619025 0.4867077 0.1157509 -0.8544169 0.506531 0.1228117 -0.850647 0.5111917 0.06387245 -0.8424749 0.534936 -0.1527141 -0.2430913 0.9579066 -0.02689224 -1.65554e-7 0.9996384 -0.05068051 -0.1085993 0.992793 -0.07933437 0.005302011 0.996834 -0.1264094 -0.005016922 0.9919655 0.03200978 2.12199e-7 0.9994876 0.05068004 -0.108031 0.9928549 0.1511618 -0.2793018 0.9482303 0.1303455 -0.006272792 0.9914489 0.08426284 0.003762602 0.9964365 0.2982673 0.06620401 0.9521836 -0.2172327 -0.9023973 0.3721412 0.005475521 -0.7617681 0.6478268 0.03201192 0 0.9994876 0.05350047 0.0350545 0.9979524 0.05293262 -0.02305811 0.9983319 0.01187074 -0.5043554 0.8634147 0.01399856 -0.3521643 0.9358336 0.04102241 -0.1899295 0.9809404 0.0318402 -0.2160008 0.9758739 0.02843624 -0.4880706 0.8723407 -0.009492814 -0.9935115 0.1133357 -0.04150664 -0.9884313 0.1458794 -0.07592856 -0.9912228 0.1082231 -0.05041354 -0.98378 0.1721499 -0.1205714 -0.9812704 0.1502368 -0.1176987 -0.9808906 0.1549215 -0.1623403 -0.9708345 0.1764257 -0.1626805 -0.9706214 0.1772834 -0.1819501 -0.9674599 0.1758282 -0.3278915 -0.9405916 0.08817487 -0.3140691 -0.948857 0.03210943 -0.289276 -0.9561566 0.04565298 -0.3418005 -0.9079573 -0.2424584 -0.192312 -0.961516 0.1962219 -0.2107726 -0.922899 0.3222302 -0.2616299 -0.9052238 0.3348429 -0.1774268 -0.9055625 0.3853266 -0.2887769 -0.8888369 0.3557764 -0.1473639 -0.8900923 0.4313001 -0.01404964 -0.7887679 0.6145307 0.04855543 -0.7962894 0.6029642 0.3137628 -0.2430855 0.9178575 0.3108958 -0.245226 0.9182637 0.3019284 -0.2557314 0.9183904 0.08402985 -2.05704e-4 0.9964632 0.130411 -0.005394339 0.9914454 0.1733937 0.04090631 0.9840027 0.1865245 0.007115125 0.9824246 0.2403215 -0.01104509 0.9706305 0.3127313 -0.2427421 0.9183003 0.2572119 -0.2001313 0.9454045 0.1994233 -0.2334161 0.9517076 0.196725 -0.2239001 0.9545513 0.1240127 -0.2070377 0.9704413 0.1320924 -0.2879195 0.9485009 0.1042617 -0.2243778 0.9689088 -0.1977746 -0.9636852 0.1794328 -0.2016973 -0.9593824 0.1972402 -0.2290924 -0.9515011 0.2053345 -0.2320197 -0.9460006 0.2263841 -0.249502 -0.9399634 0.2328467 -0.2459455 -0.9294808 0.2749116 -0.2638171 -0.917392 0.2979809 -0.001774847 -0.6421841 0.7665484 -0.01834768 -0.551338 0.8340802 0.02212089 -0.5538105 0.8323488 0.01967191 -0.549637 0.835172 0.03916072 -0.5518282 0.833038 0.03569471 -0.544537 0.8379769 0.05867928 -0.5484588 0.8341162 0.05475586 -0.5377047 0.8413534 0.08236354 -0.5440464 0.835003 0.07841902 -0.5296027 0.8446133 0.1116362 -0.5391733 0.8347633 0.1082885 -0.5202786 0.8471032 0.1471316 -0.533793 0.8327168 0.1454465 -0.5174425 0.8432667 0.2036644 -0.5105553 0.8353767 0.2363693 -0.5860067 0.775065 0.2132648 -0.5764579 0.7888057 -0.02057838 -0.8595176 0.5106918 -0.03652954 -0.8169238 0.5755877 -0.02082866 -0.8179645 0.5748915 -0.02314627 -0.8150601 0.5789139 -0.03287142 -0.8139687 0.5799781 -0.03619503 -0.8087262 0.5870708 -0.04203712 -0.8077288 0.5880536 -0.04572558 -0.7999326 0.5983452 -0.04601979 -0.799865 0.5984133 -0.04959905 -0.7892322 0.6120887 -0.04317653 -0.7910826 0.6101837 -0.04593813 -0.7770733 0.6277314 -0.03271424 -0.78167 0.6228337 -0.0342139 -0.7642362 0.6440284 -0.01318705 -0.7727955 0.6345182 -0.01233345 -0.7512703 0.6598796 0.03186988 -0.7715879 0.6353241 0.1449574 -0.6065142 0.7817468 -0.00218141 -0.9332699 0.3591696 -0.002169549 -0.9332832 0.3591347 -0.04848796 -0.9310396 0.3616827 -0.04878926 -0.9292836 0.3661306 -0.07949542 -0.9258258 0.3694956 -0.07938545 -0.9228204 0.3769624 -0.1075366 -0.918015 0.3816863 -0.1064597 -0.9136262 0.3923693 -0.1301462 -0.908193 0.3978033 -0.1275632 -0.9023618 0.4116684 -0.1457285 -0.8971299 0.4170385 -0.1408295 -0.8896753 0.4343328 -0.1533405 -0.8853351 0.4389401 -0.1456226 -0.8763196 0.459193 -0.1514173 -0.8739621 0.4618043 -0.1397652 -0.863079 0.4853457 -0.1368926 -0.8644215 0.4837726 -0.1207376 -0.8517614 0.5098286 -0.1101873 -0.8573302 0.5028359 -0.0278688 -0.8005925 0.5985609 0.6029697 -0.1812489 0.7769019 0.4442251 -0.4987505 0.7442527 0.5176157 -0.4171618 0.7470275 0.5758922 -0.3114702 0.7558668 0.6747866 -0.1323692 0.7260452 0.136321 -0.7724534 0.620268 0.257583 -0.6631633 0.7027556 0.2687082 -0.6508845 0.7100319 0.2925284 -0.6224477 0.725938 0.3098732 -0.5996945 0.7377976 -0.03927725 -0.7859635 0.6170241 0.03041326 -0.8321753 0.5536781 -0.1669382 -0.8882786 0.4278935 -0.1251837 -0.8823589 0.4536208 -0.1600314 -0.9217123 0.353322 -0.2712633 -0.9303634 0.2466581 -0.1875466 -0.9346607 0.3020523 -0.2427548 -0.9541063 0.1753603 -0.2317905 -0.9557898 0.1809396 -0.1864633 -0.9077171 0.375874 -0.1560347 -0.9048878 0.3960193 0.1863139 -0.7165178 0.6722273 0.2048323 -0.7284893 0.6537178 0.3900249 -0.5622062 0.7292494 0.531374 -0.09075915 0.8422615 0.4768958 -0.2058386 0.8545179 0.3839145 -0.4173851 0.8236502 0.2724712 -0.5793104 0.7682181 0.2610365 -0.599038 0.7569766 0.6128925 -0.06163811 0.7877586 0.5362247 -0.2089085 0.8178144 0.4667633 -0.3551031 0.8099592 0.4165424 -0.4314731 0.800202 0.3426854 -0.5428508 0.7667333 0.2840655 -0.609054 0.7405135 0.7049146 -0.00643444 0.709263 0.5980067 -0.1991764 0.7763484 0.5506587 -0.295283 0.7807579 0.4997631 -0.3727109 0.7818717 0.4239313 -0.4856537 0.7644755 0.3631421 -0.553767 0.7493129 0.1316094 -0.7732319 0.6203156 0.1266406 -0.7706145 0.6245923 0.05612444 -0.8120953 0.5808196 0.06840193 -0.8174104 0.5719803 0.006524741 -0.8534845 0.5210773 0.7187383 0.3593691 -0.5952051 -0.9942622 -0.01423084 -0.1060198 -0.9943425 -0.01732766 -0.1047992 -0.9924718 0.002138912 -0.1224547 -0.9928771 -0.003002643 -0.1191052 -0.99163 0.005059301 -0.1290131 -0.992554 -9.54379e-4 -0.1218026 -0.9924414 0.005907356 -0.1225783 0.4789924 -0.5067138 0.7168037 0.450871 -0.5593964 0.6955509 0.2687337 -0.6967344 0.6650891 0.2050653 -0.7690224 0.605436 0.1691764 -0.7387305 0.6524237 0.5251752 -0.4143208 0.7433232 0.4647759 -0.5350242 0.7055016 0.4773627 -0.5055091 0.7187388 0.355944 -0.61628 0.7024976 0.3057933 -0.6604359 0.6857952 0.7205135 -0.1300804 0.6811311 0.7037765 -0.1869236 0.6853892 0.6878386 -0.1750248 0.7044462 0.7003872 -0.1268005 0.7024096 -0.7069564 7.07641e-6 0.7072572 -0.7411896 0 0.6712958 -0.7453276 -0.005398094 0.6666767 -0.4309198 -0.08046305 0.8987958 -0.5010052 -0.005328834 0.8654279 -0.5566841 0.02177089 0.830439 -0.5368306 -0.02734774 0.8432468 -0.6337433 0.03218245 0.7728737 -0.6186667 -0.004823267 0.7856388 -0.6706442 0.001180708 0.7417783 -0.6694162 -6.79309e-5 0.7428877 -0.7069574 2.16171e-4 0.7072561 -0.4877352 0.08637058 0.8687087 -0.4084228 -0.00535506 0.9127771 -0.365384 0.02409636 0.930545 -0.3717506 0.04216271 0.9273748 -0.3226205 -0.001101493 0.9465278 -0.2748708 0.006878852 0.9614566 -0.3091469 0.1192577 0.9435072 -0.257841 0.01643234 0.9660477 -0.1838157 -0.03855568 0.9822043 0.2811042 0.08412224 0.9559832 -0.196525 0.00873804 0.9804599 -0.1411655 -9.25401e-4 0.9899857 -0.1267881 0.01054233 0.9918739 -0.1204291 1.06789e-4 0.9927219 -0.07622164 1.02644e-4 0.9970909 -0.07785189 0.005650043 0.996949 -0.02303087 -0.003921926 0.9997271 -0.02431833 0 0.9997044 0.01315957 0 0.9999135 0.01697832 -0.006710946 0.9998334 0.06722265 0.01860141 0.9975646 0.07031565 -4.95279e-5 0.9975249 0.1143092 -8.81754e-6 0.9934453 0.1187818 -0.005082964 0.9929075 0.1747612 0.02930855 0.9841746 0.1781448 -0.02619642 0.9836555 0.2511323 0.01427674 0.9678476 0.2922022 0.003699898 0.9563494 0.3205441 -8.32083e-4 0.9472333 0.3707844 0.03232699 0.9281563 0.371283 0.05134487 0.9270991 0.4077782 -0.00630927 0.9130593 0.4636791 0.0328074 0.8853957 0.4578185 -0.04591441 0.8878593 0.5033761 -0.004014909 0.8640582 0.5488665 0.01815235 0.835713 0.5427811 -0.05380219 0.8381492 0.633289 0.0535987 0.7720572 0.6298422 -0.008710026 0.7766743 0.670286 0.00220251 0.7420997 0.671622 -2.73845e-6 0.740894 0.7069789 3.0871e-4 0.7072347 0.7069773 2.15934e-6 0.7072364 0.7411896 0 0.6712958 0.7453276 -0.005399107 0.6666767 0.7856576 0.01973587 0.6183468 0.7848836 0.02896672 0.618966 0.8060399 -0.00535649 0.5918369 0.824953 0.005089879 0.5651786 0.8441945 -0.04466539 0.5341728 -0.7815842 0.01709759 0.6235656 -0.7868356 0.02592694 0.616618 -0.8060398 -0.00535649 0.5918372 -0.8249534 0.005092144 0.5651778 -0.8441945 -0.04466539 0.5341728 0.6122077 0.7677115 0.1892638 0.7735168 0.2850303 0.5660649 0.7639309 0.1117156 0.6355544 0.7440207 0.01310938 0.668028 0.7516804 0.4859676 0.4458834 0.76713 0.3831768 0.5144774 0.6796317 0.6626623 0.3146101 0.71548 0.678207 0.1677014 0.6410073 0.7592418 0.1125242 0.7265259 0.6635299 0.1785727 0.8573248 0.312024 0.4094328 0.7861764 0.1849386 0.5896818 0.8049542 0.1744804 0.5671028 0.8073925 0.1945356 0.5570219 0.8424694 0.1745707 0.5096767 0.8438907 0.1816063 0.5048443 0.8757736 0.1615772 0.4548774 0.8179451 0.4908648 0.3000293 0.8167756 0.4936136 0.2987025 0.7923735 0.5089057 0.3363914 0.7923696 0.508912 0.3363912 0.7630556 0.5254671 0.3763383 0.7630285 0.5255649 0.3762569 0.7352764 0.5408647 0.4084535 0.7490209 0.5787874 0.3224483 0.6370803 0.7624896 0.1128642 0.631315 0.7659382 0.1215739 0.6278865 0.7698333 0.1145213 0.6084489 0.7809006 0.1413657 0.5978165 0.7919113 0.1244674 0.5809487 0.8011433 0.1437641 0.5919571 0.7965215 0.1230466 0.7310847 0.6685501 0.1362206 0.9262126 0.3769301 -0.007343709 0.8099102 0.5447824 0.2173887 0.7497649 0.6227259 0.2237523 0.7977243 0.5753521 0.1805713 0.8071554 0.5616011 0.1819462 0.748731 0.5923755 0.297478 0.7837975 0.5373261 0.3113554 0.8218739 0.5256761 0.219518 0.8078043 0.5481246 0.2168216 0.8205851 0.5347018 0.2018268 0.7900028 0.5677639 0.2313868 0.8042685 0.5632721 0.1894116 0.7686274 0.5976192 0.2281744 0.7801771 0.5994009 0.1790038 0.6236156 0.7064059 0.3348049 0.743756 0.6514085 0.1499804 0.9912326 0.07464289 0.1090255 0.9926743 0.0746361 0.09501171 0.989928 0.07463759 0.1202996 0.9895938 0.08043664 0.1193065 0.9653106 0.2337339 0.1163789 0.9653106 0.2337337 0.1163787 0.93033 0.3606791 0.06630641 0.9919937 0.1047008 0.07061332 0.9760509 0.2061495 0.06947839 0.9695991 0.2337417 0.07240432 0.9202539 0.3867418 0.05969548 0.9179838 0.3867635 0.0878629 0.9155455 0.3867725 0.1103793 0.9155462 0.3867707 0.1103792 0.9179839 0.3867633 0.0878629 0.9678784 0.2337296 0.09263843 0.9678782 0.2337305 0.09263861 0.9926744 0.07463473 0.095012 0.9944959 0.07463991 0.07353174 0.9970152 0.03036546 0.07098418 0.8807892 0.4427483 0.1678821 0.723401 0.4634743 0.5117448 0.6388361 0.443497 0.6286485 0.5722241 0.5190207 0.6349623 0.9813143 -0.06101268 0.182482 0.9845 -0.07178848 0.1600193 0.9784889 -0.05829429 0.1978922 0.9529472 -0.1378525 0.2699785 0.9468293 -0.1208382 0.2981818 0.9250224 -0.1834527 0.3326843 0.7898166 -0.1917819 0.5825886 0.8274785 -0.1688207 0.5355174 0.671366 -0.1863301 0.7173205 0.6196284 -0.1555663 0.7693243 0.5417458 -0.2377388 0.8062207 0.5895095 -0.105687 0.8008176 0.4596675 -0.2395483 0.855174 0.4945443 -0.1341651 0.858735 0.3738961 -0.2286638 0.8988407 0.3907984 -0.1723144 0.9042037 0.05974721 -0.02078288 0.9979972 0.07180839 -0.1550433 0.9852945 0.0920251 -0.182806 0.9788327 0.05074626 -0.06854528 0.9963566 0.08431506 -0.1020613 0.9911985 0.06619751 0.01938909 0.9976181 0.07079052 0.01353019 0.9973995 0.07712954 0.1067654 0.9912882 0.0646581 0.1290149 0.9895325 0.08222299 0.1927813 0.9777908 0.05096632 0.2795401 0.9587805 0.08953279 0.2393485 0.9667969 0.07464176 0.3233926 0.9433164 0.08520609 0.3604542 0.9288772 0.08012717 0.3751394 0.9234989 0.07991939 0.44075 0.894065 0.07518696 0.4483793 0.8906756 0.1643336 0.4242642 0.8905023 0.3030111 0.5300457 0.7919822 0.25897 0.4303683 0.8647068 0.3901955 0.5129701 0.7645974 0.3497809 0.4388654 0.8276779 0.7284415 0.4274147 0.5354341 0.8057068 0.4258146 0.4117264 0.8563063 0.4131016 0.3099787 0.8722603 0.4300624 0.2328266 0.8840225 0.4128722 0.2191823 0.8575681 0.4392092 0.267717 0.4358116 0.237633 0.8681008 0.4582819 0.1980048 0.8664709 0.5406395 0.1840202 0.820881 0.5407274 0.184068 0.8208124 0.6185396 0.1683312 0.7675111 0.6186035 0.1683745 0.7674502 0.440966 0.4630756 0.7688369 0.4731951 0.4394891 0.7635022 0.5266688 0.44081 0.7268471 0.5553197 0.4234154 0.715779 0.5720022 0.4241307 0.7020874 0.632227 0.3946043 0.6667657 0.6323643 0.394633 0.6666185 0.2951719 0.4106605 0.8626887 0.4427739 0.3762779 0.8138588 0.379378 0.3570597 0.8535695 0.4646551 0.336533 0.819049 0.4647743 0.3365725 0.8189652 0.5466528 0.3128138 0.7767357 0.546767 0.312857 0.776638 0.6240179 0.2861343 0.7271375 0.6241523 0.2861827 0.7270031 0.9403138 0.01372087 0.3400321 0.9410878 0.05123883 0.3342581 0.9411123 0.05107128 0.3342146 0.9427654 0.08709365 0.3218821 0.9428012 0.08681613 0.3218521 0.945276 0.1200706 0.303375 0.9453105 0.1197316 0.3034013 0.9485222 0.1491501 0.2793921 0.9485504 0.1487826 0.2794922 0.9523901 0.1734343 0.2507464 0.9524085 0.1731169 0.2508956 0.9567369 0.1922444 0.2183957 0.9567489 0.1920016 0.2185566 0.961432 0.2050514 0.1833097 0.9614345 0.2049215 0.1834416 0.9687711 0.215678 0.1223343 0.9680816 0.2335917 0.09084576 0.8657519 -0.1111661 0.4879711 0.8154903 -0.1356374 0.5626528 0.8132367 -0.05351209 0.5794675 0.7546954 -0.06282377 0.6530606 0.7543666 0.03550356 0.6554926 0.6884905 0.04048568 0.7241145 0.6907692 0.1511488 0.7071011 0.6908289 0.1510722 0.7070591 0.6956905 0.2569318 0.670821 0.6957916 0.2567912 0.67077 0.7030533 0.3543065 0.6165899 0.7031727 0.3541157 0.6165633 0.7116193 0.4261986 0.5585274 0.6659334 0.4668886 0.5818486 0.9812191 -0.06794798 0.1805336 0.9812877 -0.06848239 0.1799577 0.9767456 -0.05325925 0.2076815 0.9461109 -0.1286056 0.2972118 0.9434195 -0.0963096 0.317308 0.910411 -0.1359052 0.3907449 0.9077604 -0.08630543 0.4105149 0.8657012 -0.1113129 0.4880275 0.8638493 -0.04389989 0.5018339 0.8132101 -0.05355906 0.5795004 0.8129371 0.03026217 0.5815649 0.7543845 0.03552174 0.655471 0.7563905 0.1326128 0.6405367 0.7564429 0.1325268 0.6404926 0.7607145 0.2254227 0.6086856 0.7607988 0.2252708 0.6086365 0.7671763 0.3108671 0.5610724 0.7672852 0.310648 0.5610448 0.775533 0.3861867 0.4994083 0.7756341 0.3859683 0.4994202 0.7845119 0.4402401 0.4367262 0.7746058 0.4570349 0.4371556 0.9414682 -0.06146162 0.3314518 0.9404441 -0.02419984 0.3390862 0.9062613 -0.03415375 0.4213361 0.9060825 0.01927214 0.4226622 0.8636147 0.02484571 0.5035399 0.8650183 0.0927838 0.4930869 0.865063 0.09266304 0.4930312 0.86805 0.1577028 0.4707643 0.8681102 0.1575096 0.4707181 0.8725767 0.2174746 0.4373955 0.8726472 0.2172264 0.437378 0.8784257 0.2701636 0.3941827 0.8784981 0.2698854 0.3942118 0.8854019 0.3142367 0.3425187 0.8854644 0.3139801 0.3425921 0.8932536 0.3483788 0.2841306 0.893298 0.3481903 0.2842225 0.901726 0.3716695 0.220799 0.9017532 0.3715549 0.2208806 0.940431 -0.02427518 0.3391168 0.940307 0.01368534 0.3400524 0.9060971 0.01930582 0.422629 0.9071834 0.07207566 0.414516 0.9072161 0.07194399 0.4144673 0.9095389 0.1225202 0.3971496 0.9095902 0.1222817 0.3971056 0.9130633 0.1689268 0.371186 0.9131161 0.1686482 0.3711829 0.9176166 0.2098508 0.3375539 0.9176685 0.2095398 0.3376061 0.9230412 0.2440702 0.2973629 0.9230839 0.2437851 0.2974641 0.9291499 0.2705663 0.2519415 0.9291783 0.2703546 0.2520637 0.9357404 0.2886345 0.2026822 0.9357549 0.288513 0.2027881 0.94134 0.2958249 0.1623783 0.9123705 0.386672 0.134406 0.9123513 0.3867571 0.134291 0.9157333 0.3796937 0.1313969 0.9433844 -0.09661245 0.3173201 0.9414951 -0.06127083 0.3314104 0.9077209 -0.08646792 0.4105681 0.906282 -0.03407466 0.4212981 0.8638289 -0.04394662 0.5018649 0.863604 0.02482342 0.5035594 0.8129413 0.03027993 0.5815579 0.8146504 0.1130586 0.5688255 0.8147034 0.1129568 0.5687701 0.8183427 0.1921832 0.5416465 0.8184181 0.1920069 0.5415951 0.823856 0.2650233 0.5010229 0.8239455 0.2647901 0.5009992 0.8309848 0.3292253 0.4484138 0.8310692 0.3289847 0.448434 0.839475 0.3829535 0.3855234 0.8395479 0.3827363 0.3855807 0.8478816 0.4179584 0.3262019 0.8062902 0.4842259 0.3397376 0.169336 -0.288622 0.9423496 0.1953817 -0.1766704 0.9646831 0.1945036 -0.1498599 0.9693867 0.194479 -0.1498708 0.9693899 0.1931959 -0.0659942 0.9789384 0.1931879 -0.06600344 0.9789392 0.1929243 0.01872515 0.981035 0.1929084 0.01872855 0.981038 0.1936464 0.103332 0.9756145 0.1936494 0.1033443 0.9756126 0.1953819 0.1867164 0.9627891 0.1953935 0.1867327 0.9627836 0.1981223 0.2688995 0.9425714 0.1981719 0.2689524 0.9425457 0.2018395 0.3488427 0.9151883 0.2019323 0.3489071 0.9151434 0.2065163 0.4256541 0.881005 0.3704349 -0.06072819 0.9268712 0.3701789 0.01723736 0.9288007 0.370186 0.01725059 0.9287975 0.3708494 0.09509181 0.9238118 0.7585662 -0.1491259 0.6343018 0.7576053 -0.1587114 0.6331232 0.6919717 -0.1577651 0.7044754 0.6888706 -0.0715664 0.7213429 0.6164091 -0.07976531 0.7833756 0.6163854 -0.0797401 0.7833968 0.5383335 -0.08720004 0.8382083 0.5382968 -0.08717525 0.8382346 0.4557245 -0.09380459 0.8851643 0.3724513 0.1718381 0.9120042 0.3708608 0.09510684 0.9238058 0.508054 0.08580011 0.8570411 0.4562417 0.0162537 0.8897075 0.4556868 -0.09378331 0.885186 0.4025936 -0.09745407 0.9101765 0.3716483 -0.1379232 0.9180713 0.2819386 -0.222927 0.9331743 0.2854667 -0.2095404 0.9352015 0.2835494 -0.1445434 0.9480016 0.2835043 -0.1445907 0.9480079 0.2822784 -0.06365764 0.9572182 0.2822586 -0.06366395 0.9572236 0.2819895 0.01806318 0.9592475 0.2819945 0.01807016 0.9592459 0.2826867 0.09967315 0.9540197 0.2827197 0.09968715 0.9540085 0.2843683 0.1801 0.9416468 0.2844172 0.180139 0.9416246 0.2870381 0.2594029 0.9221276 0.2870805 0.2594448 0.9221027 0.2906186 0.3365277 0.8957065 0.9877325 0.07463932 0.1371632 0.9820423 0.07839369 0.1716027 0.9840452 0.08076661 0.1585304 0.9849364 0.08080691 0.1528741 0.9821207 0.07523101 0.1725672 0.9829011 0.07661271 0.1674396 0.9813045 0.06954705 0.1794574 0.9811359 0.06901651 0.1805805 0.9795941 0.05914419 0.192087 0.9795976 0.0591582 0.1920644 0.9782521 0.04752272 0.2019022 0.9782683 0.04761707 0.2018016 0.9769003 0.02998858 0.2115808 0.977458 0.03409731 0.2083585 0.9761388 0.01457905 0.2166578 0.9766054 0.02025008 0.2140837 0.9762635 0.005035996 0.2165278 0.9762834 0.005424022 0.2164286 0.9762863 -0.01616489 0.2158794 0.9765704 -0.009477794 0.2149894 0.9767333 -0.0314151 0.2121444 0.9767606 -0.02429729 0.2129515 0.9775567 -0.03927272 0.2069799 0.9775323 -0.0382201 0.2072917 0.9787781 -0.05340641 0.1978414 0.9786651 -0.05082678 0.1990763 0.9799692 -0.06224179 0.1891729 0.958246 -0.1341675 0.252515 0.9604855 -0.1576571 0.2293725 0.909097 -0.1185951 0.399347 0.9108223 -0.1339076 0.3904759 0.8777691 -0.1672903 0.4489269 0.8680991 -0.1456511 0.4745417 0.8196823 -0.2122125 0.5320591 0.8155435 -0.1355201 0.5626041 0.7573742 -0.1591012 0.6333017 0.7547247 -0.06278401 0.6530305 0.688836 -0.07160562 0.721372 0.6884666 0.04046791 0.7241383 0.6159638 0.04510319 0.7864823 0.6159847 0.04508298 0.7864671 0.537841 0.0493043 0.8416033 0.537859 0.04929184 0.8415926 0.4552078 0.05304306 0.888804 0.4582101 0.1979684 0.8665172 0.3724837 0.210056 0.9039537 0.3784047 0.3210837 0.8681678 0.2906945 0.3365812 0.8956617 0.2951081 0.4106127 0.8627332 0.2065759 0.4257125 0.8809627 0.2177689 0.6116408 0.7605738 0.05696612 0.3560887 0.9327142 0 -0.1666142 0.9860222 -0.003175675 -0.1838291 0.9829531 0.005241215 -0.07421165 0.9972288 -0.003142654 -0.1025263 0.9947254 0.00296241 0.02985602 0.9995499 -0.001508831 0.01360481 0.9999063 0.001434266 0.136917 0.9905816 -5.16001e-4 0.1293885 0.9915938 5.36269e-4 0.2428866 0.9700546 -4.96697e-5 0.2405155 0.9706454 2.69415e-5 0.3245308 0.9458752 -0.002971291 0.3454574 0.9384298 2.07651e-4 0.3766499 0.9263557 -4.3048e-4 0.448419 0.8938233 0 0.4500046 0.8930264 -0.9842351 0.0793479 0.1580675 -0.7756344 0.3859698 0.4994183 -0.94611 -0.1286035 0.2972154 -0.912351 0.3867573 0.1342926 -0.8739503 0.4576968 0.1634767 -0.9609029 -0.1556823 0.2289735 -0.9110123 -0.1352389 0.3895729 -0.08248353 0.1927703 0.9777711 -0.06635403 0.242192 0.9679568 -0.08281135 0.2777657 0.957073 -0.07092469 0.3443608 0.9361546 -0.08117145 0.360764 0.9291182 -0.07852572 0.4466781 0.8912421 -0.07378721 0.4412947 0.8943235 -0.02373099 0.1859221 0.9822779 -0.08909046 0.4320479 0.8974395 -0.07043677 -0.07398462 0.9947689 -0.02067023 0.3510938 0.9361122 -0.07275408 -0.1660184 0.9834352 -0.1033398 -0.2535175 0.9617952 -0.1949867 -0.16417 0.9669687 -0.2191215 -0.2696304 0.9377021 -0.2838358 -0.1523041 0.9467 -0.3721337 -0.3406407 0.863412 -0.3356419 -0.1228904 0.9339392 -0.4595017 -0.2530422 0.8513683 -0.4360451 -0.1602473 0.8855425 -0.5420982 -0.2027291 0.8154941 -0.5319818 -0.1753966 0.828391 -0.6198569 -0.1744265 0.7650836 -0.6196177 -0.1739618 0.7653831 -0.7704873 -0.1541364 0.6185398 -0.8345883 -0.2148578 0.5072462 -0.9582442 -0.1341837 0.2525132 -0.9849382 -0.06853073 0.1587468 -0.5780227 0.4769849 0.6620991 -0.6038528 0.4747611 0.6402841 -0.659513 0.4381681 0.6107795 -0.5725148 0.4238961 0.7018111 -0.555372 0.4247861 0.7149257 -0.5531883 0.4263127 0.7157097 -0.4737727 0.4515045 0.7560973 -0.4828349 0.4423068 0.755801 -0.3704348 -0.06072801 0.9268712 -0.2822684 -0.06366354 0.9572208 -0.2822657 -0.06365799 0.9572219 -0.1931976 -0.06600326 0.9789373 -0.1931961 -0.06599408 0.9789383 -0.07409083 -0.06822502 0.9949151 -0.1929087 0.0187292 0.981038 -0.2820026 0.01806372 0.9592437 -0.2819802 0.0180698 0.9592501 -0.3701867 0.01723593 0.9287975 -0.3701788 0.01725113 0.9288004 -0.4562415 0.01625305 0.8897076 -0.2826982 0.0996887 0.9540147 -0.3708654 0.09509199 0.9238055 -0.3708482 0.09510761 0.9238107 -0.4568923 0.08960455 0.8849976 -0.4832295 0.05184555 0.8739573 -0.537859 0.04929238 0.8415926 -0.5378414 0.04930388 0.8416031 -0.6159849 0.04508358 0.7864668 -0.6159634 0.04510265 0.7864826 -0.07862699 -0.1548186 0.9848091 -0.1944804 -0.1498609 0.9693911 -0.1944999 -0.1498701 0.9693858 -0.2835052 -0.1445465 0.9480144 -0.2835467 -0.1445879 0.9479956 -0.4324458 -0.1324433 0.8918797 -0.3697547 -0.09951394 0.9237848 -0.4556876 -0.09378284 0.8851857 -0.4557247 -0.09380537 0.8851642 -0.5382972 -0.08717477 0.8382343 -0.5383322 -0.08719927 0.8382093 -0.6163849 -0.07973951 0.7833973 -0.6164105 -0.07976472 0.7833746 -0.9410877 0.05124121 0.334258 -0.9403136 0.01372122 0.3400323 -0.9403071 0.01368826 0.3400518 -0.9404311 -0.02428102 0.3391163 -0.9404441 -0.0242027 0.3390858 -0.9414681 -0.06146013 0.3314521 -0.9414948 -0.06127083 0.3314113 -0.956369 -0.1357811 0.2586929 -0.9475618 -0.1321223 0.2909818 -0.9465662 -0.1237494 0.2978234 -0.92661 -0.161518 0.3395674 -0.9800843 -0.06262016 0.1884508 -0.9769814 -0.05400621 0.206375 -0.9811532 -0.06827563 0.180768 -0.9814021 -0.06882786 0.1792002 -0.979346 -0.05952095 0.1932322 -0.9799863 -0.06217253 0.1891074 -0.97875 -0.05189818 0.1983816 -0.9786038 -0.05102413 0.1993269 -0.9774962 -0.0378316 0.2075335 -0.8395482 0.382734 0.3855824 -0.9123681 0.3866783 0.1344045 -0.9017529 0.3715569 0.2208787 -0.8766831 0.4218723 0.2311938 -0.8560602 0.447824 0.2580986 -0.7031713 0.3541163 0.6165646 -0.6957922 0.2567896 0.6707699 -0.703051 0.3543074 0.6165921 -0.7672854 0.3106488 0.5610443 -0.7755337 0.3861871 0.4994068 -0.8310692 0.3289855 0.4484336 -0.8394737 0.3829545 0.3855257 -0.8854658 0.3139768 0.3425917 -0.8932541 0.348379 0.2841294 -0.9291775 0.2703567 0.2520647 -0.9357392 0.288637 0.2026843 -0.9614344 0.2049207 0.1834434 -0.968771 0.215681 0.1223298 -0.9821107 0.07456982 0.17291 -0.6919873 -0.1597551 0.7040113 -0.6888716 -0.07156604 0.7213421 -0.6888374 -0.0716058 0.7213707 -0.6884679 0.04046845 0.7241369 -0.68849 0.0404843 0.724115 -0.690769 0.151147 0.7071018 -0.7564429 0.1325268 0.6404926 -0.7607143 0.2254243 0.6086853 -0.8184189 0.1920039 0.5415951 -0.8238565 0.2650225 0.5010225 -0.8726475 0.2172265 0.4373777 -0.8784259 0.2701619 0.3941833 -0.9176685 0.2095398 0.3376061 -0.9230415 0.2440702 0.297362 -0.9524088 0.1731169 0.2508946 -0.9523898 0.1734382 0.2507445 -0.9485494 0.1487882 0.279493 -0.9176157 0.2098534 0.3375545 -0.9131165 0.1686458 0.3711832 -0.8725756 0.2174766 0.4373966 -0.8681099 0.1575132 0.4707174 -0.818342 0.192184 0.5416471 -0.814702 0.1129598 0.5687713 -0.7563902 0.1326118 0.6405373 -0.7543871 0.03552454 0.6554679 -0.7543647 0.03550201 0.6554949 -0.7546936 -0.06282514 0.6530624 -0.7547271 -0.06278514 0.6530277 -0.7574384 -0.1430888 0.6370344 -0.7027353 -0.1756782 0.6894204 -0.9452766 0.1200668 0.3033748 -0.942802 0.08682173 0.3218488 -0.9095383 0.1225237 0.39715 -0.9072151 0.07194393 0.4144694 -0.8650193 0.09278202 0.4930855 -0.8636157 0.02485042 0.503538 -0.8636046 0.0248233 0.5035584 -0.8638295 -0.04394757 0.5018639 -0.8638504 -0.04389995 0.501832 -0.8657025 -0.111312 0.4880256 -0.8657518 -0.111168 0.487971 -0.8691237 -0.1732491 0.4632588 -0.8921658 -0.08167129 0.4442635 -0.9427663 0.08709174 0.32188 -0.9411128 0.05106842 0.3342138 -0.9071843 0.0720703 0.414515 -0.9060956 0.01930856 0.4226322 -0.9060821 0.01927447 0.4226629 -0.9062608 -0.03415286 0.4213374 -0.906282 -0.03407919 0.4212977 -0.9077211 -0.08646506 0.4105682 -0.9077599 -0.08630585 0.4105161 -0.948523 0.1491385 0.2793955 -0.9453108 0.1197317 0.3034005 -0.9130634 0.1689269 0.3711859 -0.90959 0.122284 0.3971055 -0.8680502 0.1577014 0.4707645 -0.865063 0.09265792 0.4930319 -0.8146513 0.1130555 0.5688249 -0.8129397 0.03028172 0.5815603 -0.8129368 0.03026229 0.5815653 -0.8132123 -0.05355578 0.5794977 -0.813234 -0.05351674 0.5794708 -0.8154877 -0.1356391 0.5626562 -0.8155449 -0.1355167 0.5626028 -0.8138891 -0.1185524 0.5687969 -0.687178 -0.4959563 0.5308613 -0.1790916 0.5120745 0.840063 -0.2098218 0.4670447 0.8589785 -0.206579 0.4256446 0.8809949 -0.2065037 0.4257234 0.8809744 -0.2019232 0.3488337 0.9151733 -0.2018535 0.3489173 0.9151568 -0.1981784 0.2688943 0.9425611 -0.1981068 0.2689582 0.9425578 -0.1953883 0.1867162 0.9627879 -0.2838791 0.4876167 0.8256165 -0.2995584 0.4677938 0.831525 -0.2951675 0.410601 0.8627185 -0.2951102 0.4106727 0.8627038 -0.2906852 0.3365184 0.8956882 -0.2906323 0.3365906 0.8956784 -0.2870777 0.2593982 0.9221165 -0.4646574 0.3365325 0.8190478 -0.4647746 0.3365724 0.8189651 -0.5466549 0.3128138 0.7767343 -0.5467683 0.3128564 0.7766373 -0.6240152 0.2861347 0.7271396 -0.6241508 0.2861831 0.7270042 -0.6322251 0.3946068 0.666766 -0.6323652 0.3946332 0.6666175 -0.6415295 0.4718868 0.6047833 -0.7117441 0.4279179 0.5570517 -0.7179026 0.4306839 0.5469254 -0.729902 0.4262132 0.5344021 -0.7351741 0.4624149 0.4956729 -0.7860004 0.4547779 0.4187847 -0.7806568 0.4417356 0.4420913 -0.8062212 0.425199 0.4113554 -0.8044705 0.4851011 0.342789 -0.8477677 0.4173383 0.3272901 -0.856367 0.4130045 0.3099404 -0.8932996 0.3481863 0.2842221 -0.9017256 0.3716694 0.2208004 -0.935755 0.2885107 0.2027913 -0.9413411 0.295822 0.162377 -0.9680815 0.2335923 0.09084504 -0.3856295 0.4636871 0.7976742 -0.387909 0.4611819 0.7980212 -0.3827676 0.3917387 0.8366779 -0.411809 0.3497205 0.8414921 -0.3784096 0.3210829 0.868166 -0.3750321 0.2474845 0.8933658 -0.2870415 0.25945 0.9221133 -0.2844083 0.1800965 0.9416354 -0.1953919 0.1867328 0.9627839 -0.193646 0.1033318 0.9756146 -0.05620378 0.1072234 0.9926451 -0.08386904 0.1363027 0.9871108 -0.9567371 0.1922425 0.2183963 -0.9828886 0.07669299 0.1674757 -0.9811835 0.06877917 0.1804118 -0.9813763 0.07068938 0.1786156 -0.9795963 0.05915719 0.1920717 -0.979596 0.05914264 0.1920779 -0.9782657 0.04762268 0.201813 -0.9782599 0.04749459 0.2018711 -0.9772841 0.03444612 0.2091157 -0.9771874 0.02951008 0.2103191 -0.9765702 0.02029228 0.2142408 -0.976501 0.01433438 0.215036 -0.9762755 0.00542736 0.2164644 -0.9762873 0.005025506 0.2164211 -0.9763333 -0.009601891 0.216058 -0.976667 -0.01584804 0.214174 -0.9767322 -0.02433139 0.2130784 -0.977543 -0.03819322 0.2072464 -0.9433842 -0.09660482 0.3173229 -0.9434181 -0.09631252 0.3173109 -0.9104117 -0.1359053 0.3907433 -0.9108546 -0.1337486 0.3904553 -0.8984934 -0.1470592 0.4136222 -0.9868362 0.08446359 0.1379139 -0.9848216 0.08174139 0.1531173 -0.9614312 0.205052 0.1833136 -0.9567485 0.192003 0.2185568 -0.9291485 0.2705696 0.2519428 -0.9230837 0.2437884 0.2974624 -0.8854017 0.3142389 0.3425171 -0.8784978 0.2698878 0.3942111 -0.830985 0.3292254 0.4484136 -0.8239443 0.2647923 0.501 -0.7671744 0.3108669 0.5610751 -0.7607977 0.2252719 0.6086374 -0.6956933 0.2569315 0.6708182 -0.6908263 0.1510733 0.7070614 -0.6186031 0.1683747 0.7674505 -0.6185404 0.1683303 0.7675109 -0.5407274 0.1840683 0.8208124 -0.5406395 0.1840202 0.820881 -0.4582823 0.1980054 0.8664706 -0.4582104 0.1979681 0.8665172 -0.4053235 0.2057006 0.8907303 -0.3724513 0.1718385 0.9120042 -0.2843755 0.1801424 0.9416365 -0.2827134 0.0996713 0.9540119 -0.1936472 0.103344 0.975613 -0.1929244 0.01872509 0.981035 -0.06655955 0.01938766 0.9975942 -0.07466101 0.02972328 0.996766 -0.9179837 0.3867636 0.0878629 -0.9155461 0.386771 0.1103795 -0.9155457 0.3867722 0.1103791 -0.9653106 0.2337335 0.1163787 -0.9653109 0.2337322 0.1163789 -0.9926743 0.07463622 0.09501194 -0.994707 0.0744487 0.07082009 -0.9946909 0.07463771 0.07084745 -0.9818026 0.17656 0.06992995 -0.9696002 0.2337419 0.07238912 -0.9629502 0.260816 0.0685721 -0.9312018 0.3584216 0.06631124 -0.9019904 0.4269433 0.06428658 -0.9196416 0.3867788 0.06827509 -0.917984 0.3867631 0.0878629 -0.9678784 0.2337297 0.09263843 -0.9678788 0.2337281 0.09263861 -0.9926745 0.07463318 0.09501183 -0.9900416 0.07463735 0.1193605 -0.9900417 0.0746352 0.1193605 -1 0 -7.81717e-7 -1 0 -7.41144e-7 -1 0 -7.09525e-7 -1 -4.47541e-6 0 0.7605209 -0.04096215 -0.64802 0.8231305 -0.009999573 -0.5677644 0.8396217 -0.00744903 -0.5431205 0.6423586 -0.432743 -0.6325417 0.7522016 -0.4298014 -0.4994634 0.7493363 -0.360409 -0.5555183 0.7481053 -0.3578702 -0.5588089 0.7726895 -0.3131124 -0.5521882 0.7723648 -0.2913932 -0.564396 0.7810342 -0.2451404 -0.5743622 0.7672412 -0.2272226 -0.5997591 0.779848 -0.1884323 -0.5969341 0.7787273 -0.1099153 -0.6176589 0.7787273 -0.1099149 -0.6176591 0.7793762 -0.01038742 -0.6264702 1.64016e-5 -7.06645e-6 -1 3.29887e-4 -1.18934e-4 -1 0.007368922 0.4455323 0.8952356 -0.06231558 0.7911817 0.6083982 -0.1167683 0.9915923 0.05576592 0.3402796 0.9263653 0.161423 0.9406309 0.2372433 0.2427533 0.9116842 0.2270521 0.3424608 0.9105259 0.2408133 0.3360831 0.8478449 0.2189192 0.4829425 0.8472204 0.23801 0.4749412 0.7952141 0.220686 0.5647409 0.7993014 0.2277021 0.5561198 0.7389296 0.2081559 0.640823 0.7393881 0.2323445 0.6319189 -0.1160768 0.9914597 0.05944681 -0.120316 0.989845 0.07570272 -0.1146326 0.9899825 0.08242672 -0.1241595 0.9867251 0.1046809 -0.1179494 0.9864073 0.1144053 -0.1232605 0.9847242 0.1229836 -0.1242582 0.9837205 0.129823 -0.1279186 0.9825205 0.135242 -0.1226402 0.9814274 0.1475118 -0.1293089 0.9794571 0.1547359 -0.1257398 0.9778246 0.1674772 -0.1265656 0.9776066 0.168127 -0.129957 0.9762401 0.1733974 -0.128807 0.9765465 0.1725274 -0.1275792 0.9746432 0.1838321 -0.126833 0.9748168 0.1834275 -0.1271393 0.9731227 0.19201 -0.1243184 0.9736824 0.1910178 -0.1266822 0.9729492 0.1931881 -0.1231887 0.9736145 0.192092 -0.1240777 0.9727344 0.1959402 -0.1199125 0.9733858 0.1952977 -0.1198252 0.9734375 0.1950937 -0.09080564 0.8923056 0.442205 -0.05140316 0.8285657 0.5575273 -0.01759344 0.8335638 0.5521432 -0.01419055 0.8314992 0.5553448 0.01734769 0.8378364 0.5456458 0.01946884 0.8377194 0.5457539 0.05272966 0.8439747 0.533785 0.05530714 0.8427718 0.5354222 0.1103742 0.855543 0.5058299 0.1120356 0.8549035 0.5065453 0.1435419 0.8636991 0.4831353 0.1440706 0.8637169 0.4829461 0.177215 0.8721235 0.4560654 0.1777508 0.8719499 0.4561886 0.2302565 0.887542 0.3990628 0.2301124 0.8875852 0.3990499 0.259638 0.8977882 0.3557589 0.2594612 0.8977957 0.3558689 0.2885081 0.9065538 0.3080962 0.2879319 0.9067171 0.3081548 0.324769 0.9194142 0.2218166 0.3241671 0.9195914 0.2219626 0.3403178 0.9263041 0.1616929 0.72103 0.6534675 0.2304257 -0.02584636 0.6093991 0.7924423 0.008000433 0.5509354 0.8345096 0.08995097 0.5633623 0.8212989 0.09883224 0.5538221 0.8267487 0.1562155 0.5654824 0.809831 0.1627826 0.5641425 0.8094721 0.2203646 0.5748988 0.7879917 0.2310432 0.5651397 0.7919825 0.3247084 0.5869805 0.7416323 0.3360648 0.5775681 0.7439595 0.3865451 0.5917114 0.7074323 0.3926489 0.5910984 0.7045775 0.4424846 0.6037943 0.6630533 0.4536437 0.595121 0.6633539 0.5336419 0.6190295 0.5762195 0.5436449 0.6113601 0.5750557 0.5870486 0.6262335 0.5130358 0.5914697 0.62512 0.5093021 0.6314513 0.6374194 0.4415494 0.6390373 0.6313932 0.4392881 0.6913375 0.6495349 0.316476 0.6965745 0.645058 0.3141403 0.7207626 0.6546617 0.2278584 0.9400781 0.2341852 0.2478113 0.64253 0.2032552 0.7388116 0.6245649 0.2280229 0.7469433 0.5805007 0.2124078 0.7860675 0.5599969 0.2066398 0.8023114 0.5679119 0.2137461 0.7948514 0.4892953 0.19264 0.8505763 0.4922441 0.2194635 0.8423369 0.3573105 0.1878969 0.9148901 0.3613764 0.213499 0.9076482 0.2704076 0.1957275 0.9426403 0.2788478 0.2026883 0.938702 0.1871582 0.18471 0.9648078 0.1922463 0.2066877 0.959334 0.0457049 0.1837085 0.9819177 0.05103218 0.2021679 0.9780205 0.9769374 0 0.213526 0.9769374 0 0.213526 0.9769377 0 0.2135248 0.976938 0 0.2135237 -0.01180899 0.1950703 0.9807182 -0.02544087 0.2587106 0.9656199 0.0427702 0.7064726 0.7064469 0.07387304 0.7900378 0.6085911 0.03682875 0.6083549 0.7928102 0.01566469 0.258762 0.9658142 0.06452876 0.4376008 0.896851 0.01180899 0.1950703 0.9807182 -0.04797798 0.7924594 0.6080349 -0.05598568 0.7060097 0.7059858 -0.03683024 0.6083555 0.7928096 -0.02676367 0.4420556 0.8965883 -0.1021548 0.975455 0.195069 0.1021541 0.9754551 0.1950691 0.2353377 0.8673297 0.4385834 0.0431472 0.9827281 0.1799557 0.0583781 0.9642787 0.258377 -0.04237282 0.9650596 0.2585816 -0.05918264 0.9775792 0.2020803 -0.2353377 0.8673297 0.4385834 0.09080564 0.8923056 0.4422051 0.02584636 0.6093989 0.7924424 -0.9413 0.2346105 0.2427183 -0.7216072 0.6536901 0.2279745 -0.9394112 0.2367951 0.2478601 -0.9139255 0.2278085 0.3359218 -0.9082697 0.2399831 0.3427163 -0.8519685 0.2203081 0.4749884 -0.8430216 0.2362856 0.4832017 -0.7951854 0.2207911 0.5647403 -0.7992395 0.2276741 0.5562202 -0.7456288 0.2103094 0.6323034 -0.7324863 0.230277 0.6406532 -0.6425315 0.2032549 0.7388104 -0.6245681 0.2280225 0.7469407 -0.5805007 0.2124078 0.7860675 -0.5692177 0.209158 0.795138 -0.5586258 0.2112825 0.8020581 -0.4986982 0.1951929 0.8445116 -0.4824811 0.217269 0.8485318 -0.3668839 0.1902168 0.9106118 -0.3514481 0.211629 0.9119744 -0.2798868 0.1976439 0.9394682 -0.2692807 0.2008829 0.9418779 -0.1959583 0.1864974 0.9627145 -0.1831797 0.2053821 0.9613863 -0.05326855 0.1849942 0.9812949 -0.04329782 0.2013356 0.978565 -0.007369399 0.4455323 0.8952356 -0.008000612 0.5509353 0.8345096 -0.09575718 0.5640971 0.8201373 -0.09328627 0.5525885 0.8282172 -0.1618942 0.5665369 0.8079767 -0.1571769 0.5629777 0.8113887 -0.226212 0.5758748 0.7856185 -0.2255626 0.5636762 0.7946009 -0.3301896 0.588067 0.7383442 -0.3309907 0.5760393 0.7474115 -0.3915005 0.5929921 0.7036248 -0.387766 0.5897448 0.7084058 -0.4471181 0.6048612 0.6589601 -0.4494023 0.5936788 0.6675201 -0.5372545 0.6199472 0.5718594 -0.5403634 0.610135 0.5794332 -0.5898768 0.6271336 0.5086738 -0.5887043 0.6241561 0.5136696 -0.6336576 0.6380136 0.437512 -0.6370651 0.630574 0.4433109 -0.6925127 0.6498427 0.3132582 -0.6955529 0.6445936 0.3173411 -0.7201551 0.6544705 0.230315 -0.3402108 0.9263474 0.1616705 0.06231772 0.7911816 0.6083981 0.05140465 0.8285657 0.5575273 0.01538312 0.8338558 0.5517681 0.01627475 0.8310464 0.5559649 -0.01914978 0.838165 0.5450806 -0.01770508 0.8373609 0.5463637 -0.05407953 0.8442074 0.5332818 -0.05407422 0.8424465 0.5360598 -0.1111271 0.8556912 0.5054142 -0.111369 0.8547063 0.507025 -0.1439387 0.8638058 0.4828264 -0.143667 0.8636074 0.4832621 -0.1774178 0.8721709 0.4558957 -0.1775773 0.871888 0.4563744 -0.2302114 0.887529 0.3991177 -0.2301506 0.8876015 0.3989917 -0.2595424 0.8977596 0.3559011 -0.2595508 0.8978277 0.3557229 -0.2883619 0.906513 0.308353 -0.2880489 0.9067693 0.3078917 -0.3246504 0.9193871 0.2221028 -0.3242525 0.9196319 0.2216699 -0.3403921 0.9263195 0.1614485 0.1174961 0.991313 0.0591036 0.1152077 0.9917539 0.05613648 0.1214432 0.9893648 0.08005499 0.1128334 0.9905297 0.07822918 0.1264203 0.9858616 0.1099767 0.1148483 0.9873405 0.1094015 0.1265668 0.9836207 0.1283405 0.1207211 0.9848396 0.1245688 0.1314981 0.9812984 0.1405767 0.1181659 0.9826954 0.1426417 0.1335325 0.9781546 0.1593198 0.1207073 0.9791381 0.1634581 0.1312034 0.97635 0.1718328 0.1251869 0.9774945 0.1698025 0.1330273 0.9754145 0.1756997 0.1227654 0.975744 0.181252 0.1303151 0.9740037 0.1852971 0.1232913 0.9738841 0.190654 0.12712 0.9731258 0.1920071 0.1238278 0.9734943 0.1922903 0.1249322 0.9732841 0.1926395 0.1222232 0.9730269 0.1956532 0.1198052 0.9733998 0.1952937 0.1199358 0.9734264 0.1950812 -0.9769382 0 0.2135222 -0.9769374 0 0.213526 -0.9769374 0 0.2135261 -0.9769374 0 0.2135259 0.7674964 0.5485235 0.3317702 0.7057688 0.5995849 0.377344 0.6888915 0.6041085 0.4006013 0.691147 0.5898222 0.4176428 0.7141098 0.6522988 0.2540737 0.7262234 0.6048418 0.3267506 0.6992506 0.6457791 0.3066235 0.713624 0.6039417 0.3549582 0.73498 0.5741951 0.3607 0.6969416 0.7046568 0.1331588 0.7256153 0.6682668 0.1640182 0.751123 0.6451192 0.1401268 0.7884801 0.5984138 0.1421274 0.8172741 0.5488143 0.1756871 0.8363626 0.5321611 0.1315384 0.723147 0.6633358 0.1924687 0.7266687 0.6502634 0.2216083 0.814717 0.5396959 0.2120485 0.8100123 0.5531713 0.1946319 0.7773546 0.5578867 0.2906583 0.7815545 0.5641286 0.2663301 0.7798509 0.5559374 0.2876917 0.7971615 0.5445854 0.2606922 0.7988919 0.5435981 0.2574352 0.8131492 0.5163079 0.2687277 0.8209257 0.502347 0.2715299 -0.9443817 0.3145556 0.09590691 -0.9643764 0.2449492 0.09989112 -0.9653163 0.2206196 0.1396118 -0.9960036 -0.0221911 0.08651351 -0.7711018 0.6111504 0.1785978 -0.7175416 0.6710302 0.1866885 -0.4277024 0.8820359 0.1976953 -0.3547803 0.913554 0.1988722 -0.001937329 0.9839029 0.178694 0.07587629 0.9819414 0.1733035 0.4243564 0.8968014 0.1251757 0.4923219 0.8628118 0.1147832 -0.9542683 0.2120302 0.2107493 -0.9557026 0.2065333 0.2097058 -0.7712345 0.5831164 0.2552896 -0.7610704 0.5957676 0.2565791 -0.4543406 0.8533684 0.2556115 -0.4203517 0.8709951 0.2543071 -0.05852776 0.9756148 0.2115428 0.001309037 0.9791165 0.2032958 0.3476593 0.9284744 0.1306461 0.4227944 0.8991107 0.1133362 -0.05943709 0.9764919 0.2071976 -0.09325581 0.9727856 0.2121124 -0.4517552 0.8509746 0.2678798 -0.9482622 0.1997504 0.2467762 -0.9470253 0.2044169 0.2477034 -0.7748494 0.5661978 0.2811201 0.2978979 0.9492874 0.1005513 0.3021547 0.9456638 0.1200944 0.3433171 0.9326721 0.1107084 -0.17878 0.9622306 0.2053045 -0.09742659 0.9763531 0.192984 0.01595497 0.9857123 0.1676809 0.2572153 0.9601585 0.1092517 -0.4106948 0.8789281 0.2425185 -0.4767088 0.8419129 0.252847 -0.4732037 0.8389104 0.2689007 -0.7658399 0.5777854 0.2822291 -0.9503572 0.1959946 0.2416763 -0.9492109 0.2005219 0.2424659 -0.8641238 0.4289889 0.2631705 -0.777226 0.5682184 0.2702734 -0.7559252 0.5968165 0.2690491 -0.5790572 0.7726399 0.2602314 -0.7020828 -0.5136143 -0.4932344 -0.7034005 -0.4903125 -0.5146082 -0.7194683 -0.4432998 -0.5346501 -0.7109566 -0.5021454 -0.492332 -0.7072017 -0.5099306 -0.4897311 -0.7069118 -0.5237232 -0.4753839 -0.7072376 -0.5214021 -0.4774462 -0.706619 -0.5413864 -0.4556208 -0.6995221 -0.5590392 -0.4451339 -0.7004296 -0.5578507 -0.4451978 -0.7026702 -0.5526242 -0.4481754 0.916263 0.4005772 0 0.9477631 0.3185788 0.01589578 0.8949241 0.4462184 0 0.9323298 0.3614571 0.01048588 0.9362076 0.3514473 -5.72319e-4 0.9784151 0.2066493 3.1236e-4 0.9787068 0.2052638 3.37203e-5 0.9944759 0.1049664 -7.67481e-5 0.9959058 0.09036189 -0.002517342 0.9995361 0.03044378 8.67638e-4 0.9998552 0.0170201 -1.05332e-6 0 -0.9999994 0.00110495 0 -1 2.22648e-6 0 -1 4.46393e-7 0 -1 -3.7892e-6 0 -1 5.93106e-6 -0.6337845 -0.5335752 -0.5600133 -0.6823045 -0.5719165 -0.4553813 -0.6340495 -0.5976277 -0.4907367 -0.6106411 -0.6224592 -0.4895529 -0.4649944 -0.629719 -0.6222815 -0.4585403 -0.7284397 -0.5090348 -0.3470222 -0.7973819 -0.4937184 -0.2902706 -0.7898681 -0.5402327 -0.2512999 -0.8140689 -0.523584 -0.03481918 -0.8678679 -0.4955735 -0.2900209 -0.5876655 -0.7553393 -0.2151862 -0.5787602 -0.7865949 -0.07829099 -0.6056577 -0.7918645 -0.6343489 -0.4934186 -0.5950964 -0.6502348 -0.5424486 -0.531925 -0.6139138 -0.4958572 -0.614195 -0.5706683 -0.4847207 -0.6628602 -0.556113 -0.4884296 -0.6724395 -0.4993169 -0.5347941 -0.681673 -0.4697593 -0.5463799 -0.693394 -0.4711113 -0.5452353 -0.6933778 -0.3908238 -0.5561788 -0.7334317 -0.3253592 -0.5712875 -0.7535065 -0.1462421 -0.8222272 -0.5500506 -0.1114265 -0.8651946 -0.4888992 -0.09801256 -0.8294905 -0.5498538 -0.0977894 -0.7854746 -0.6111195 -0.1477541 -0.6696962 -0.7277883 -0.09797215 -0.7221801 -0.6847316 -0.09778827 -0.7854756 -0.6111183 -0.2896623 -0.7554216 -0.5877363 -0.2896598 -0.7554216 -0.5877376 -0.4705345 -0.6964264 -0.5418373 -0.4705355 -0.696426 -0.5418368 -0.5553972 -0.6563404 -0.5106381 -0.572283 -0.7227761 -0.3874104 -0.6343519 -0.570127 -0.5220662 -0.6242407 -0.5456849 -0.559063 -0.4705325 -0.6163393 -0.6314468 -0.4705368 -0.6163376 -0.6314453 -0.2896625 -0.6685503 -0.6849351 -0.2896592 -0.6685485 -0.6849383 -0.09779179 -0.6951465 -0.7121855 -0.09782326 -0.5959565 -0.7970361 -0.005878508 -0.5960568 -0.8029208 0.2729454 0.9616497 0.02703166 0.4292862 0.9030141 0.01670175 0.570864 0.8180862 0.06963682 0.8804655 0.4720092 0.04458725 0.8785521 0.4755866 0.04431122 0.8653226 0.4993116 0.04364407 0.8339773 0.5498545 0.04628294 0.8422429 0.5373732 0.04309254 0.8469637 0.5249904 0.08389133 0.65077 0.7557163 0.07342553 0.8403582 0.5322573 0.1024715 0.8447142 0.524995 0.104107 0.7950766 0.5988143 0.0963065 0.768568 0.6334398 0.08976209 0.7582874 0.6456202 0.09041595 0.6773028 0.7307627 0.085128 0.7061704 0.7049797 0.06577986 0.4242894 0.9046592 0.03962618 0.4273115 0.9028412 0.04777717 0.5134637 0.8560031 0.06011551 0.5082255 0.8604001 0.03766387 0.5256145 0.849073 0.05295681 0.3624431 0.9314011 0.03357064 0.31862 0.9476326 0.02176719 0.3464007 0.9376398 0.028952 0.0579164 0.9983062 0.005530178 0.03989183 0.9992035 0.001055657 0.114702 0.9933292 0.01186412 0.1997737 0.9797075 0.01624017 0.1665809 0.9859994 0.007487654 0.2078703 0.9780023 0.01736164 0.05802488 0.998306 0.004276096 0.05798894 0.9983054 0.004864394 0.03454434 0.9994017 0.001761853 0.3051371 0.9521703 0.0162267 0.2569861 0.9663332 0.01259499 0.1999099 0.9797052 0.01462125 0.1746492 0.984579 0.01009672 0.1022291 0.9947499 0.004686057 0.5070203 0.8614169 0.02985823 0.4645915 0.8851708 0.02504819 0.3636315 0.9313902 0.01686614 0.4157088 0.9088177 0.03516739 0.3475359 0.9374451 0.02038627 0.5728611 0.8183128 0.04684281 0.5164409 0.8559846 0.02406877 0.6183463 0.7851749 0.03388738 0.653711 0.7557162 0.03943276 0.6582393 0.7518159 0.03865301 0.805284 0.5913127 0.04321175 0.7772055 0.6276831 0.04433673 0.7724618 0.633444 0.04529291 0.7292422 0.6832036 0.03793048 0.6947579 0.7182707 0.03739905 0.4057672 0.9130925 0.04019093 0.5144743 0.8559904 0.05095869 0.5144751 0.8559899 0.05095857 0.6517389 0.7556912 0.06455463 0.6517393 0.7556908 0.06455463 0.7700452 0.6334137 0.07627266 0.7700443 0.6334148 0.07627254 0.8469644 0.5249893 0.08389157 0.8488072 0.5249896 0.06254965 0.0580247 0.998306 0.004275798 0.1999033 0.979705 0.01473098 0.1999034 0.9797049 0.01473098 0.3630287 0.9313939 0.02675205 0.3630288 0.9313938 0.02675187 0.5155946 0.85599 0.0379945 0.515594 0.8559903 0.03799474 0.6531575 0.7556908 0.04813182 0.6531578 0.7556906 0.04813188 0.7717204 0.6334144 0.05686897 0.771719 0.6334158 0.05686885 0.8488072 0.5249894 0.06254982 0.8496425 0.5250169 0.04965078 0 -1 -8.87453e-6 0 -1 1.82106e-6 0 -1 1.67971e-5 0 -1 1.50593e-5 0 -1 4.33885e-6 -1 4.12261e-7 0 -1 -2.95131e-7 0 0.0137034 -0.9999061 0 -0.4305806 -0.9024755 -0.01176351 -0.1740507 -0.9844008 0.02571904 -0.2686166 -0.9631013 -0.01676994 -0.1460441 -0.9892781 0 0.1467983 -0.9890767 -0.01332759 0.07300692 -0.9973302 0.001621127 0.3322988 -0.9431731 -0.001516878 0.325685 -0.9454784 0 0.5364957 -0.8439032 0 0.5598568 -0.828562 -0.006751954 0.7379249 -0.6748185 0.009319663 0 -0.9948198 -0.1016542 0 -0.991662 -0.1288672 -1.20019e-6 -0.9916607 -0.1288763 9.27332e-7 -0.9948188 -0.101665 -0.5521038 -0.8337692 0.003226101 -0.748266 -0.6633925 -0.002921938 -0.0137034 -0.9999061 0 -0.1467985 -0.9890766 -0.01332765 -0.07300686 -0.9973301 0.001621186 -0.3322988 -0.9431729 -0.001516878 -0.325685 -0.9454784 0 -0.5346815 -0.8450537 0 -0.6230529 -0.7817618 -0.02556705 0.1304654 -0.9895463 -0.06145709 0.231546 -0.972824 0 0.3255945 -0.9445339 -0.04294282 -7.54785e-6 -0.8603576 0.5096911 0 0.8603631 -0.5096817 0 0.8603658 -0.5096772 0 0.8603634 -0.5096811 0 0.8603656 -0.5096775 0 0.8603678 -0.5096738 -4.47269e-6 0.8603644 -0.5096794 1.83728e-6 0.860367 -0.5096751 1.2374e-6 0.8603678 -0.5096737 -3.25544e-7 0.8603594 -0.5096879 -4.10259e-7 0.8603646 -0.5096791 -5.8008e-7 0.8603666 -0.5096758 2.9004e-7 0.8603662 -0.5096765 4.10259e-7 0.8603646 -0.5096791 3.25545e-7 0.8603616 -0.509684 -1.24873e-6 0.8603687 -0.5096724 0.7026683 -0.5526267 -0.4481753 0.7004296 -0.5578507 -0.4451978 0.6995216 -0.55904 -0.4451335 0.7194683 -0.4432998 -0.5346501 0.7002944 -0.498623 -0.5108452 0.7084594 -0.5003633 -0.4977168 0.7052609 -0.5138938 -0.4883854 0.7059561 -0.5124804 -0.4888659 0.7071968 -0.5237616 -0.4749174 0.7066189 -0.5413866 -0.4556208 0.09794312 -0.6738736 -0.7323261 0.03481918 -0.8678679 -0.4955735 0.1462421 -0.8222272 -0.5500506 0.1114267 -0.8651948 -0.4888988 0.2512999 -0.8140689 -0.523584 0.316832 -0.7720245 -0.5509952 0.2897306 -0.8263013 -0.4829931 0.4585406 -0.7284402 -0.5090339 0.4649944 -0.629719 -0.6222815 0.572283 -0.7227761 -0.3874104 0.6334992 -0.5404548 -0.5537034 0.6337665 -0.6051296 -0.481828 0.6739417 -0.5516318 -0.4914316 0.5891906 -0.4771728 -0.6520434 0.5560656 -0.5114745 -0.6551221 0.5464859 -0.5144965 -0.6607924 0.4697591 -0.5463806 -0.6933937 0.4711118 -0.5452348 -0.6933778 0.3908238 -0.5561783 -0.7334321 0.3253594 -0.5712872 -0.7535067 0.2900207 -0.5876653 -0.7553393 0.2151863 -0.5787599 -0.7865951 0.07829099 -0.605658 -0.7918643 0.09782385 -0.5959569 -0.7970358 0.005878508 -0.5960546 -0.8029224 0.09778654 -0.7854753 -0.611119 0.09801256 -0.8294905 -0.5498538 0.09779077 -0.7854748 -0.6111189 0.2896608 -0.755422 -0.5877366 0.2896621 -0.7554211 -0.5877372 0.4705349 -0.6964265 -0.5418369 0.470534 -0.6964269 -0.5418371 0.5553978 -0.6563404 -0.5106376 0.610641 -0.6224591 -0.4895531 0.09797215 -0.7221801 -0.6847317 0.1264386 -0.6928883 -0.7098727 0.2896621 -0.6685487 -0.6849369 0.2896595 -0.6685501 -0.6849366 0.4705342 -0.6163392 -0.6314457 0.4705352 -0.6163377 -0.6314464 0.6335001 -0.5404541 -0.553703 0.6343656 -0.5063659 -0.584101 0.6467676 -0.4868063 -0.5871212 0.04735082 -0.8674175 -0.495323 -0.03760099 -0.8843355 -0.4653354 0.02645248 -0.8975953 -0.4400262 -0.04552352 -0.864502 -0.5005638 -0.02338647 -0.9008133 -0.4335764 0.007491469 -0.9014214 -0.4328778 0.01827442 -0.9029386 -0.429381 0 -0.9011076 -0.4335955 0 -0.9011084 -0.4335941 0.0258516 -0.9052363 -0.4241216 -0.002121686 -0.9023807 -0.4309347 -0.0258516 -0.9052363 -0.4241216 0.0021227 -0.9023809 -0.4309343 -0.007155001 -0.902934 -0.4297197 0.02065163 -0.8969064 -0.441738 -0.01827454 -0.902939 -0.4293803 0.03760081 -0.8843356 -0.4653354 -0.02645248 -0.8975955 -0.4400257 -0.01961213 -0.8948287 -0.4459788 0.02248829 -0.8550466 -0.5180633 -0.02215218 -0.8843044 -0.4663853 0 -0.6267048 -0.7792568 -0.2324249 -0.5797486 -0.780942 0 -0.8235486 -0.5672459 0 -0.6771295 -0.7358639 0 -0.7256712 -0.6880418 -0.08676159 -0.7565308 -0.6481772 0.05254465 -0.7881665 -0.6132151 -0.002024412 -0.820284 -0.5719529 0 -0.8335066 -0.5525096 0 -0.8683935 -0.4958759 -0.1012864 -0.755488 -0.6472858 0.1661816 -0.7782828 -0.6055244 0 -0.8191789 -0.5735381 6.76883e-4 -0.820824 -0.5711809 -1.66439e-4 -0.8334991 -0.5525211 1.65313e-5 -0.8354543 -0.54956 -2.2791e-4 -0.870397 -0.4923504 0.02858597 -0.888415 -0.4581503 0 -0.5960724 -0.8029307 0.1495363 -0.6196582 -0.7704951 0.07593518 0 0.9971128 0.9455407 0.01500976 0.325158 0.9646009 -0.007509708 0.2636072 0.972441 0 0.233149 0.6559192 1.7745e-5 0.7548313 0.6814934 0.01235687 0.73172 0.7370775 -0.01221543 0.6756978 0.7863554 0.01518547 0.6175878 0.7833392 0.01293063 0.6214601 0.824023 -0.005569458 0.5665291 0.8401718 2.37969e-5 0.5423204 0.8628403 -4.12542e-5 0.5054767 0.8866852 0.01214247 0.4622143 0.9088943 -0.01181429 0.4168593 0.9419292 0.009696781 0.3356717 0.6247581 -1.03515e-5 0.7808184 0.6125196 -3.3787e-4 0.7904554 0.5996063 -0.002792656 0.8002904 0.5368003 0.009746611 0.8436531 0.07253801 0.002910554 0.9973615 0.2161424 -0.002629697 0.9763583 0.2250949 0.004531562 0.9743263 0.3096327 -0.001151025 0.9508556 0.3153588 -6.7615e-5 0.9489725 0.3754525 1.42096e-4 0.9268417 0.4012231 0.01316243 0.9158858 0.4815652 -0.01115781 0.8763392 0.5530624 0.02076441 0.8328812 0.404183 0.8736636 0.2708287 0.9249196 0.2352848 0.298605 0.6802062 0.664638 0.3091534 0.1746379 0.9588196 0.2239792 -0.2092374 0.9705847 0.1191012 0.9217303 0.248166 0.2980386 0.8993458 0.2340741 0.3693053 0.8984863 0.2397293 0.3677666 0.8637058 0.2203761 0.4532623 0.8580402 0.2415928 0.4532109 0.8141095 0.2207068 0.5371353 0.8272256 0.06613147 0.5579646 0.7701878 0.2270226 0.5960466 0.7383934 0.2151373 0.6391331 0.7388385 0.2183497 0.6375274 0.6896564 0.2007421 0.6957562 0.6846514 0.2213877 0.694435 0.6123688 0.2018291 0.7643753 0.6268857 0.01784324 0.778907 0.5576071 0.2073503 0.8037912 0.5193216 0.2003211 0.8307687 0.5195833 0.2038632 0.8297427 0.4527211 0.1927037 0.8705797 0.4517217 0.2018779 0.8690184 0.358846 0.1945009 0.9129069 0.3517502 0.02676415 0.9357112 0.3011273 0.1949716 0.933439 0.6782398 0.6669209 0.308557 0.6581878 0.6549054 0.3713325 0.6575582 0.6558428 0.3707932 0.6287015 0.6386987 0.4436199 0.6257844 0.6422838 0.4425668 0.5706251 0.6165493 0.5424519 0.568074 0.6200119 0.5411813 0.5325644 0.6074245 0.5894156 0.5325359 0.6077598 0.5890957 0.497475 0.5945881 0.6316515 0.4958089 0.5972742 0.6304262 0.4286833 0.5791112 0.6934413 0.4281479 0.580253 0.6928173 0.3841236 0.5725681 0.724303 0.3841058 0.5727538 0.7241656 0.3420003 0.5654824 0.7505102 0.3424188 0.5641663 0.7513094 0.272952 0.558515 0.7832998 0.2735078 0.5552032 0.7854571 0.2780008 0.9307875 0.2373824 0.2620663 0.9216443 0.2861698 0.2643555 0.9204072 0.2880396 0.2477848 0.9103456 0.3314722 0.2583706 0.9054617 0.3367249 0.2278596 0.8913258 0.3919417 0.2387005 0.8852541 0.3991835 0.2208495 0.8789147 0.4227701 0.2214012 0.8778837 0.4246195 0.2067037 0.8724133 0.4429095 0.2164521 0.8654198 0.4518817 0.1905663 0.8584608 0.4761614 0.19827 0.8512754 0.4858179 0.1840543 0.8487457 0.4957366 0.1848285 0.8468115 0.4987474 0.1742401 0.8450419 0.5055141 0.1788043 0.8384567 0.5148004 0.1634324 0.837213 0.5218852 0.1658158 0.831429 0.5303122 -0.1934401 0.972901 0.1266674 -0.1957384 0.971512 0.1336075 -0.1901015 0.9718999 0.1388244 -0.1912887 0.9711962 0.14208 -0.1656873 0.9734153 0.1581466 -0.1646942 0.9738744 0.1563477 -0.1389569 0.9742563 0.1775265 -0.1346881 0.9758592 0.1719243 -0.1333192 0.9751418 0.1769871 -0.125002 0.9780837 0.166514 -0.1028613 0.9761933 0.1909613 -0.08242982 0.9816744 0.1718165 -0.06532585 0.9782754 0.1967486 -0.04687148 0.9818257 0.1839065 -0.04513603 0.9806136 0.1906826 -0.0225805 0.9841045 0.1761493 -0.01315093 0.9802915 0.1971187 0.02818429 0.9836022 0.1781358 0.03258103 0.9805021 0.1937889 0.07142746 0.1751652 0.9819447 0.2120057 0.1945182 0.9577142 0.2110583 0.1751917 0.9616457 0.1838772 0.5381683 0.8225353 0.1798565 0.5545653 0.812471 0.1167433 0.8415965 0.5273391 0.1221327 0.8308297 0.5429602 0.04226708 0.9806935 0.1909288 0.03639513 0.9843561 0.1723906 0.01279073 0.984342 0.1758049 0.01278871 0.984343 0.175799 0.0714361 0.1753211 0.9819162 0.06754106 0.3655342 0.9283443 0.05941516 0.5381705 0.8407393 0.06037735 0.5544133 0.8300486 0.03917962 0.8415923 0.5386903 0.0384835 0.8308421 0.555176 0.02647483 0.9309685 0.3641384 0 0 1 -0.8523606 0.4204131 0.3110214 -0.5703482 0.7658583 0.2969245 -0.1746333 0.9588209 0.2239773 0.2566197 0.9606163 0.1065953 0.01200556 0.988673 0.1496051 -0.4087927 0.8775054 0.2507444 -0.7489716 0.5916802 0.2982551 -0.8646364 0.2208812 0.4512376 -0.8977445 0.2392899 0.3698585 -0.9000835 0.2345046 0.3672291 -0.9212107 0.2478051 0.2999393 -0.9400281 0.188931 0.2839937 -0.6909613 0.2012084 0.6943254 -0.7375081 0.2178545 0.6392349 -0.7397134 0.2156399 0.637435 -0.7701869 0.2270221 0.596048 -0.8272256 0.06613147 0.5579646 -0.8141095 0.2207068 0.5371353 -0.8570704 0.2410918 0.4553079 0.1926478 0.9733712 0.1242392 0.1966328 0.9709635 0.1362549 0.1890878 0.9724694 0.1361955 0.1923347 0.9705772 0.1448702 0.1642006 0.9740993 0.1554632 0.1661916 0.9731822 0.1590504 0.137009 0.9749926 0.1749795 0.1365759 0.975158 0.1743959 0.1313772 0.9758466 0.1745382 0.1268607 0.9774492 0.168818 0.1006073 0.976835 0.1888692 0.08436959 0.9811916 0.1736233 0.0630536 0.9787365 0.19519 0.04881584 0.9814665 0.185312 0.04312002 0.9809621 0.1893516 0.02432322 0.9838671 0.1772395 0.01120907 0.9804856 0.1962711 -0.2754201 0.9294284 0.2455742 -0.2616775 0.9214063 0.2872897 -0.2647827 0.9206341 0.2869201 -0.2473274 0.9100419 0.3326452 -0.2590007 0.9057116 0.3355672 -0.2271875 0.8909811 0.3931137 -0.2395526 0.885537 0.3980437 -0.2200781 0.8786141 0.423796 -0.222193 0.8781775 0.4235972 -0.2058702 0.8720738 0.4439648 -0.2174617 0.8656793 0.4508991 -0.1896752 0.858193 0.4769992 -0.1993137 0.8514578 0.4850709 -0.1830169 0.8485396 0.496473 -0.1858983 0.8469896 0.4980466 -0.1733115 0.8448776 0.5061078 -0.1798327 0.8385345 0.5143152 -0.6781259 0.6668342 0.3089944 -0.6583435 0.6550023 0.3708852 -0.6574025 0.655748 0.3712365 -0.6288905 0.6388199 0.443177 -0.6255628 0.6421867 0.4430209 -0.5708366 0.616666 0.5420967 -0.5678201 0.6199258 0.5415463 -0.5326967 0.6075069 0.5892111 -0.5323976 0.6076751 0.5893079 -0.497683 0.5946587 0.6314211 -0.4955685 0.5972235 0.6306632 -0.4288002 0.5791493 0.6933373 -0.4280191 0.5802261 0.6929194 -0.3841924 0.5725679 0.7242667 -0.384024 0.5727592 0.7242048 -0.3418539 0.5654554 0.7505971 -0.3425762 0.5641779 0.751229 -0.3588527 0.1944992 0.9129046 -0.4509664 0.2018247 0.8694229 -0.4534443 0.1928286 0.8701756 -0.5185062 0.2036882 0.8304592 -0.5203849 0.2005174 0.8300558 -0.5576114 0.2073541 0.8037872 -0.6268841 0.0178433 0.7789083 -0.6123688 0.2018291 0.7643753 -0.6832613 0.2210071 0.6959238 -0.3011178 0.1949722 0.9334421 -0.3517538 0.02676308 0.93571 -0.2738556 0.555182 0.7853509 -0.2726223 0.5584952 0.7834285 -0.1667241 0.831411 0.5300557 -0.1625842 0.8371484 0.5222537 -0.03400522 0.9805318 0.1933941 -0.02686035 0.983533 0.1787216 -0.972441 0 0.233149 -0.9646009 -0.007509708 0.2636072 -0.9455406 0.01500976 0.3251582 -0.9419292 0.009696781 0.3356717 -0.8885558 -0.02308493 0.4581875 -0.9054573 0.0228542 0.4238215 -0.8628453 0 0.5054682 -0.8400856 0 0.542454 -0.824023 -0.005569458 0.5665291 -0.7833392 0.01293063 0.6214601 -0.5996095 -0.002792835 0.800288 -0.5368003 0.009746611 0.8436531 -0.7863459 0.01518571 0.6176 -0.7370768 -0.01221507 0.6756987 -0.6814934 0.01235711 0.73172 -0.6559192 1.7745e-5 0.7548313 -0.6247581 -1.03515e-5 0.7808184 -0.6125169 -3.37871e-4 0.7904573 -0.07253372 0 0.9973661 -0.07561767 0.002793192 0.997133 -0.2161424 -0.002629697 0.9763583 -0.2250975 0.004531562 0.9743258 -0.3096345 -0.001151025 0.950855 -0.3153548 -6.76879e-5 0.9489738 -0.3754504 1.42096e-4 0.9268426 -0.4012202 0.01316255 0.9158872 -0.4815666 -0.01115804 0.8763385 -0.5530628 0.02076351 0.8328809 0 0.984421 0.1758278 0 0.9844281 0.1757882 0 0.9313032 0.3642451 0 0.555442 0.8315554 0 0.8314511 0.555598 0 0.9314272 0.3639279 0 0.1757672 0.9844319 0 0.3664385 0.9304423 0 0.3663138 0.9304914 -0.01279342 0.9843416 0.1758067 -0.04226708 0.9806933 0.1909297 -0.03639507 0.9843538 0.1724038 -0.1184486 0.841535 0.5270568 -0.1203047 0.8307704 0.5434586 -0.1821611 0.5382214 0.8228822 -0.1817218 0.5546348 0.8120083 -0.2120071 0.1945192 0.9577136 -0.2110539 0.1751916 0.9616466 -0.07144576 0.1751698 0.9819425 -0.07141774 0.1753166 0.9819183 -0.01278603 0.9843434 0.175797 -0.02647483 0.9309685 0.3641384 -0.03746348 0.8415284 0.5389123 -0.04038095 0.830786 0.5551252 -0.061136 0.538223 0.8405823 -0.0584793 0.554482 0.8301386 -0.06754106 0.3655342 0.9283443 -0.3026579 0.9452119 0.1223632 -0.3428111 0.9331185 0.1084924 0.09283232 0.9724402 0.2138747 0.05983847 0.9768318 0.2054728 0.4729177 0.8386667 0.2701611 0.452018 0.851223 0.2666443 0.7746655 0.5660681 0.2818872 0.7660034 0.577932 0.2814847 0.9482082 0.1996935 0.2470299 0.9470766 0.2044782 0.2474564 -0.2102587 0.9697716 0.1238329 -0.2966237 0.950272 0.09485578 0.1778402 0.9614992 0.2095052 0.09810483 0.9768908 0.1898941 0.4106948 0.8789281 0.2425185 0.4767024 0.8419163 0.2528476 0.691088 0.6729011 0.263821 0.777226 0.5682184 0.2702734 0.9382197 0.2444204 0.2449543 0.9492617 0.2005652 0.242231 0.9653185 0.2206106 0.1396116 0.9563845 0.2774872 0.09126669 -0.4246457 0.8963725 0.1272501 -0.483866 0.8676137 0.1145439 0.001710474 0.98358 0.1804648 -0.04664969 0.9835307 0.1746177 0.4275389 0.8817791 0.199189 0.4000133 0.8948236 0.1981928 0.770996 0.6109243 0.1798242 0.7631774 0.6204672 0.1805015 0.9944547 -0.07437652 0.07435053 0.9767773 0.1930355 0.09297126 -0.3481251 0.9279885 0.1328389 -0.4225119 0.899509 0.1112083 0.05814576 0.9752864 0.2131562 -0.001075148 0.9794386 0.2017403 0.4540953 0.853191 0.2566373 0.4205225 0.8711979 0.2533277 0.7711555 0.5830259 0.2557346 0.7611283 0.5958744 0.2561597 0.9543013 0.2120343 0.2105959 0.9556718 0.2065281 0.2098514 -0.7231468 0.663336 0.1924686 -0.6947666 0.706705 0.133669 -0.7186266 0.5860514 0.3743256 -0.7081763 0.6211813 0.3355894 -0.7226586 0.6218224 0.3018304 -0.7228823 0.6089051 0.3266128 -0.7057688 0.5995849 0.377344 -0.6888908 0.6041092 0.4006016 -0.6911033 0.589853 0.4176716 -0.7815494 0.5641327 0.2663362 -0.7773349 0.5579091 0.2906679 -0.7674964 0.5485235 0.3317702 -0.7841507 0.5839712 0.2099654 -0.7828058 0.5522043 0.2868546 -0.8101084 0.5368363 0.2356507 -0.8056932 0.539003 0.2456308 -0.8216553 0.5118655 0.2507519 -0.7256436 0.668323 0.1636636 -0.7492188 0.6473507 0.1400291 -0.786589 0.6009165 0.1420467 -0.7141098 0.6522988 0.2540737 -0.7266687 0.6502634 0.2216083 -0.8054816 0.552882 0.2133567 -0.8181968 0.5481456 0.1734657 -0.8303255 0.5343144 0.1583282 0 1 -1.6006e-6 0 1 2.0933e-6 0 1 -5.48282e-6 0 1 4.13462e-6 0 1 -1.70763e-6 0 1 1.41306e-6 0 1 1.22932e-6 1.67557e-6 1 5.21176e-7 0 1 -3.86741e-6 0 1 2.79278e-6 0 1 -3.70359e-6 0 1 1.71477e-6 0 1 5.16036e-6 0 1 -3.61821e-6 0 1 3.11981e-6 0 1 -2.21767e-6 0 1 1.63915e-6 0 1 2.0508e-6 0 1 -1.81538e-6 0 1 9.55872e-7 0 1 1.12669e-6 2.54946e-6 1 2.51624e-7 0 1 3.10222e-7 -1.125e-6 1 0 0 1 -1.50423e-6 0 1 -1.00101e-6 0 1 -5.00238e-7 -4.06745e-6 1 -3.84594e-6 9.54218e-7 1 9.02253e-7 0 1 8.33792e-7 0 1 -4.07485e-7 0 1 -1.6131e-7 0 1 1.64285e-7 0 1 0 0 1 -1.61272e-6 0 1 2.01878e-7 0 1 -6.8523e-7 -1.65064e-7 1 6.85787e-7 -2.12122e-6 1 0 0 1 -4.25055e-7 0 1 -2.55289e-7 0 1 7.35185e-7 0 1 -7.28317e-7 0 1 2.89717e-7 0 1 -7.15762e-7 0 1 4.29115e-7 0 1 -1.46546e-6 0 1 1.14033e-5 0 1 -4.68188e-6 0 1 -4.82407e-7 0 1 7.71143e-7 0 1 1.13977e-6 0 1 -2.67128e-6 0 1 9.92827e-7 0 1 2.77982e-6 -0.9038598 0.427829 0 -0.8937809 0.4484874 0.003849506 -0.9982347 0.05939328 0 -0.9972051 0.07463699 0.003377974 -0.9868911 0.1613802 -0.001571238 -0.9842127 0.1769899 -9.74975e-6 -0.9652218 0.2614328 -6.82997e-6 -0.9748681 0.2226294 0.008262097 -0.9331781 0.3591775 -0.01305478 -0.9561172 0.2928695 0.008215606 -0.9175023 0.3977218 -0.002645671 -0.9202856 0.3912472 -3.89103e-5 -0.4242894 0.9046592 0.03962618 -0.8788016 0.4752626 0.04281878 -0.880176 0.4727234 0.04269647 -0.8655689 0.4990268 0.04198789 -0.8338876 0.5499283 0.04701703 -0.6947575 0.718271 0.03739881 -0.7292422 0.6832036 0.03793048 -0.7724619 0.633444 0.04529297 -0.7772055 0.6276831 0.04433673 -0.8052833 0.5913135 0.04321169 -0.4645906 0.8851714 0.02504789 -0.5070204 0.8614168 0.02985823 -0.515963 0.8560082 0.03212755 -0.5745092 0.8179622 0.02961444 -0.6538329 0.7557138 0.03740775 -0.6181265 0.784768 0.04537773 -0.6582386 0.7518165 0.03865301 -0.4208542 0.906874 0.02148455 -0.3632155 0.9314022 0.02375853 -0.3475356 0.9374452 0.02038627 -0.1022292 0.9947499 0.004686057 -0.1746492 0.984579 0.01009672 -0.19991 0.9797052 0.01462119 -0.2569861 0.9663332 0.01259499 -0.3051372 0.9521703 0.01622635 -0.05802464 0.998306 0.004276096 -0.05807608 0.9983054 0.003680169 -0.03890365 0.9992361 0.003714799 -0.2729453 0.9616498 0.02703189 -0.2078703 0.9780023 0.01736164 -0.1998426 0.9797065 0.01543736 -0.1622059 0.9866531 0.01431292 -0.114702 0.9933292 0.01186412 -0.3096292 0.9503929 0.02971887 -0.3624811 0.9314021 0.03313302 -0.346401 0.9376397 0.02895218 -0.5152379 0.8559273 0.0437982 -0.4613527 0.885654 0.05263751 -0.4273115 0.9028412 0.04777717 -0.7016034 0.7073017 0.08646982 -0.6605991 0.7467047 0.07772445 -0.6507702 0.7557162 0.07342547 -0.570864 0.8180862 0.06963682 -0.5256145 0.849073 0.05295681 -0.7563672 0.6478523 0.09053248 -0.7685684 0.6334396 0.08976089 -0.7932371 0.6013224 0.09584534 -0.8403236 0.5403688 0.04310387 -0.8497358 0.5250178 0.04801535 -0.8488072 0.5249896 0.06254971 -0.8386938 0.534915 0.1022683 -0.8446558 0.5249929 0.104591 -0.8469632 0.5249911 0.08389145 -0.7700446 0.6334144 0.07627254 -0.7700449 0.6334142 0.07627266 -0.6517388 0.7556914 0.06455445 -0.6517394 0.7556907 0.06455463 -0.5144743 0.8559904 0.05095845 -0.5144751 0.85599 0.05095869 -0.4237647 0.9047992 0.04197406 -0.3928522 0.9188272 0.03773182 -0.03454434 0.9994017 0.001761853 -0.05798894 0.9983054 0.004864394 -0.05802494 0.998306 0.004275798 -0.1999031 0.979705 0.01473098 -0.1999036 0.9797049 0.01473098 -0.3630288 0.9313938 0.02675187 -0.3630288 0.9313939 0.02675199 -0.5155942 0.8559902 0.03799462 -0.5155946 0.8559899 0.03799474 -0.6531583 0.7556903 0.04813188 -0.6531571 0.7556914 0.04813188 -0.7717195 0.6334155 0.05686891 -0.7717204 0.6334143 0.05686897 -0.8488072 0.5249894 0.06254971 -0.8469648 0.5249885 0.08389139 1 -5.73524e-7 0 -1 -1.14705e-6 0 0 -1 -3.30924e-7 -8.26053e-7 0.5096783 0.8603651 -1.17375e-6 0.509679 0.8603647 0 0.5096775 0.8603657 -1.83821e-6 0.5096817 0.8603631 0 0.5096773 0.8603657 6.12431e-6 0.5096725 0.8603685 -4.3214e-6 0.5096836 0.8603621 1.83821e-6 0.5096817 0.8603631 0 0.5096833 0.8603621 -6.12431e-6 0.5096725 0.8603685 -4.42315e-7 0.5096759 0.8603666 0 0.5096783 0.860365 0 0.5096787 0.8603649 4.13026e-7 0.5096783 0.8603651 0 0.5096781 0.8603652 8.11873e-6 0.5096774 0.8603657 -0.9417109 -0.3364234 0 -0.9328474 -0.3602646 0.002303481 -0.8362013 -0.5483912 -0.005892157 -0.8392381 -0.5437214 -0.006821572 -0.7578157 -0.6524685 5.56975e-4 -0.5356282 -0.8444522 -0.001785278 -0.5251742 -0.8509948 0 -0.2077239 -0.9781875 0 -0.1632236 -0.9865837 -0.003297984 0.02812874 -0.9996022 0.002043426 0.07332098 -0.9973084 0 0.2623252 -0.9649795 0 0.266469 -0.9638435 -3.17027e-4 0.4819348 -0.8762071 3.05472e-4 0.4856194 -0.8741703 0 0.6468252 -0.7626384 0 0.7594329 -0.6505334 0.00825572 0.9807854 -0.1950897 0 0.9726976 -0.2320106 0.005541801 0.9074223 -0.4202201 0 0.8080069 -0.589173 0 0 -0.9802616 -0.197705 0 -0.9802619 -0.1977037 -0.9807854 -0.1950897 0 -0.9726976 -0.2320106 0.005541861 -0.9074223 -0.4202201 0 -0.8080069 -0.589173 0 -0.7594329 -0.6505334 0.00825572 -0.6468252 -0.7626384 0 -0.4818578 -0.8762495 0 -0.4856199 -0.8741701 3.16658e-4 -0.262275 -0.9649932 -3.28589e-4 -0.26647 -0.9638432 0 -0.02809476 -0.9996052 0 -0.07332092 -0.997303 0.003298223 0.2071768 -0.9782931 -0.004531502 0.1632242 -0.9865891 0 0.5356296 -0.8444531 0 0.5246731 -0.8513017 -0.00188589 0.9417109 -0.3364234 0 0.9328472 -0.3602647 0.002303481 0.8362013 -0.5483912 -0.005892157 0.8392376 -0.5437222 -0.006821572 0.7578153 -0.6524691 5.56881e-4 -0.06963008 -0.351483 -0.9336014 -0.1994985 0 -0.9798982 -0.4401341 0 -0.8979321 -0.5488655 -0.1264105 -0.8262972 -0.6560487 0 -0.7547187 -0.8276308 0 -0.5612729 -0.8908813 -0.0819863 -0.4467762 -0.9440417 0 -0.3298262 -0.9971917 0 -0.0748918 -0.9958021 -0.0734573 0.05461078 -0.9829633 0 0.1838022 -0.9022704 0 0.4311707 -0.8363221 -0.08711564 0.5412727 -0.7612313 0 0.6484806 0 -1 0 -0.9626362 -0.1914836 -0.1914827 -0.4681395 -0.8264366 -0.3128064 -0.1652663 -0.9800469 -0.1104319 -0.1104331 -0.9800472 -0.165264 0.1652666 -0.9800471 -0.11043 0.1104331 -0.9800472 -0.165264 0.936428 -0.3345375 -0.1057713 0.9024685 -0.2947322 -0.3141396 0.7794748 -0.3781713 -0.4994052 0.7597385 -0.4063222 -0.5076416 0.6835675 -0.2739004 -0.6765458 0.4736586 -0.3837776 -0.7926932 0.5250564 -0.3268484 -0.7858027 0.3815886 -0.2703518 -0.8839118 0.2791705 -0.2692666 -0.9217154 0.1856729 -0.3071742 -0.9333647 0.1155779 -0.2406425 -0.9637079 -0.18957 -0.2363938 -0.9529855 -0.1302604 -0.2163772 -0.9675811 -0.02029657 -0.2181536 -0.9757034 -0.06938862 -0.9438263 -0.3230746 0.4681442 -0.8264389 -0.3127937 0.4681316 -0.8264433 -0.312801 0.3127945 -0.826444 -0.4681345 0.3128145 -0.8264384 -0.4681311 0.109831 -0.8264396 -0.5522089 0.6954386 -0.5481277 -0.4646733 0.6954465 -0.5481225 -0.4646676 0.4646742 -0.5481196 -0.6954444 0.4646765 -0.5481209 -0.6954419 0.1631812 -0.5481193 -0.8203276 0.1631544 -0.5481367 -0.8203212 -0.1631795 -0.5481346 -0.8203176 0.8656882 -0.4700359 -0.1721928 0.8248825 -0.5409687 -0.1640787 0.8174037 -0.5491212 -0.1741185 0.5333715 -0.8408908 -0.09174811 0.5859182 -0.8103702 -3.98048e-4 0.1620858 -0.9797045 -0.1179292 -0.2660944 -0.9624926 -0.05293154 -0.4833719 -0.8701191 -0.09614896 -0.5232814 -0.8311758 -0.1879454 -0.6415351 -0.7564039 -0.1276165 -0.7977666 -0.5817089 -0.1586925 -0.3128076 -0.8264468 -0.4681207 -0.4681414 -0.8264407 -0.312793 -0.6954429 -0.5481309 -0.464663 -0.8105831 -0.5510668 -0.1981931 -0.8929957 -0.413529 -0.1776298 -0.5452982 -0.1914882 -0.8160774 -0.2639464 -0.1937416 -0.9448792 -0.2139595 -0.2222275 -0.9512288 -0.8160819 -0.1914762 -0.5452955 -0.545289 -0.1914691 -0.8160879 -0.464675 -0.5481187 -0.6954446 -0.1631568 -0.5481178 -0.8203334 -0.1098274 -0.8264364 -0.5522145 0.1098361 -0.826438 -0.5522104 0.03877526 -0.9800474 -0.1949458 -0.9626368 -0.1914807 -0.1914825 -0.8160868 -0.1914809 -0.5452865 -0.6954434 -0.5481203 -0.4646747 -0.4646776 -0.5481206 -0.6954413 -0.3127982 -0.8264395 -0.4681402 -0.1098431 -0.8264427 -0.5522019 -0.03877508 -0.9800475 -0.194945 -1.80871e-6 -0.977135 -0.2126205 1.24331e-6 -0.9771351 -0.2126196 8.28562e-7 -0.9771352 -0.212619 -7.62398e-7 -0.9771343 -0.2126229 0 -0.9771348 -0.2126207 0 -0.9771354 -0.2126182 3.06047e-7 -0.9771346 -0.2126216 -7.23233e-7 -0.9771349 -0.2126206 -7.54136e-7 -0.9771351 -0.2126197 0.7977666 -0.5817087 -0.1586933 0.4833717 -0.8701189 -0.09615069 -0.110433 -0.9800468 -0.1652659 0.1652664 -0.9800472 -0.1104298 -0.7061166 -0.2526046 -0.6615061 0.249413 -0.3748177 -0.8929194 0.1905618 -0.214464 -0.9579622 -0.09023576 -0.2170733 -0.9719758 -0.1856653 -0.3072736 -0.9333335 -0.2781147 -0.2693914 -0.9219981 -0.7564811 -0.483214 -0.4407274 0.6415352 -0.756404 -0.1276152 0.5232814 -0.8311758 -0.1879454 0.4681454 -0.8264378 -0.3127946 0.4681323 -0.8264427 -0.3128015 -0.4681402 -0.8264409 -0.3127945 -0.4681393 -0.8264393 -0.3127999 -0.1652667 -0.9800468 -0.1104322 0.8929957 -0.413529 -0.1776298 0.8105831 -0.5510668 -0.1981931 0.695439 -0.5481271 -0.4646735 0.6954488 -0.5481221 -0.4646647 0.4646754 -0.5481184 -0.6954445 0.4646769 -0.5481197 -0.6954424 0.1631544 -0.5481365 -0.8203214 -0.1631795 -0.5481349 -0.8203174 0.2660944 -0.9624925 -0.05293321 0.06938809 -0.9438279 -0.3230699 -0.4200596 -0.4121534 -0.8085045 -0.5357292 -0.2648419 -0.8017812 -0.464674 -0.5481192 -0.6954448 -0.1631569 -0.548117 -0.8203338 -0.1098273 -0.8264367 -0.552214 0.03877508 -0.9800475 -0.194945 -0.1620846 -0.979705 -0.1179274 -0.5355587 -0.8443365 -0.01651984 -0.5562264 -0.8252297 -0.09802281 -0.8231724 -0.539844 -0.1759423 -0.8203247 -0.5481262 -0.1631724 -0.9256116 -0.3306735 -0.1841145 -0.8307349 -0.5478022 -0.09895616 0.1408092 -0.2650275 -0.9539043 0.260399 -0.1936557 -0.9458805 0.5452823 -0.1914886 -0.8160879 0.5453044 -0.1914697 -0.8160776 0.8160856 -0.1914754 -0.5452903 0.8160833 -0.1914815 -0.5452916 0.962637 -0.1914807 -0.191482 0.9626363 -0.1914829 -0.1914832 -0.8993306 -0.3282167 -0.2889259 -0.7865772 -0.3241485 -0.5255705 -0.6954412 -0.5481215 -0.4646766 -0.4646772 -0.5481218 -0.6954407 -0.3127979 -0.8264397 -0.4681397 -0.1098433 -0.8264421 -0.5522028 -0.03877526 -0.9800474 -0.1949458 0.7614855 0 0.648182 0.8363261 -0.08707964 0.5412725 0.9958023 -0.07345485 0.05461102 0.982959 0 0.1838251 0.902446 0 0.4308031 0.8908799 -0.08199822 -0.4467767 0.9440137 0 -0.3299065 0.9971936 0 -0.07486641 0.5488792 -0.1263413 -0.8262987 0.6562046 0 -0.7545831 0.827579 0 -0.5613495 0.0696147 -0.351957 -0.9334239 0.1993613 0 -0.9799261 0.4403086 0 -0.8978465 -6.46447e-7 0 -1 2.52352e-7 0 -1 -1.68413e-7 0 -1 7.63875e-7 0 -1 -7.89103e-7 0 -1 -0.3042206 0.9526017 0 -0.2317613 0.9727048 -0.01149487 -0.2310287 0.9729093 -0.008560538 -0.2282356 0.9736012 -0.003056347 -0.2256314 0.9742128 0 -0.2791629 0.9602187 -0.006941795 -0.2957717 0.9550158 -0.02154093 -0.2603244 0.965521 -5.23796e-4 -0.2428312 0.9700683 7.64549e-4 -0.2322485 0.9726234 -0.008032441 -0.3407418 0.9401566 7.90325e-4 -0.3171215 0.948374 -0.004553318 -0.3253466 0.9455949 0 -0.3825 0.9238498 -0.01397329 -0.3773996 0.9260116 -0.008491575 -0.3627815 0.9318733 -0.001333415 -0.3829374 0.9237471 0.007086455 -0.3808771 0.9246203 -0.003152787 -0.3817186 0.9241986 -0.01216107 -0.3449554 0.9386191 -2.21338e-4 -0.345633 0.9383698 0 -0.3612775 0.932455 -0.002521038 -0.3835996 0.9234443 0.0101006 -0.3855823 0.9225935 0.01214736 -0.2777621 0.9606499 0 -0.2461525 0.969202 -0.007514655 -0.2438359 0.9697588 -0.01059544 -0.1561313 0.9877114 0.007018923 -0.1226789 0.9898776 -0.07136082 0.3657593 0.9307096 0 0.3835909 0.923448 0.01009744 0.3808701 0.9246233 -0.003152132 0.3829423 0.9237451 0.00708419 0.3855829 0.9225933 0.01214504 0.3171368 0.9483689 -0.004545807 0.3407567 0.9401513 7.90276e-4 0.3627631 0.9318805 -0.001332163 0.3773936 0.9260142 -0.008482336 0.3824989 0.9238503 -0.01397055 0.3817191 0.9241984 -0.01216119 0.3253466 0.9455949 0 0.3420463 0.9396824 -0.001167535 0.302659 0.9529976 -0.01389807 0.3453025 0.9384915 0 0.2973707 0.9547622 0 0.2349745 0.9719507 -0.009946525 0.2442576 0.969684 -0.00715959 0.253445 0.9673365 -0.005094707 0.2440767 0.969744 -0.004812896 0.2340912 0.9721626 -0.010073 0.2313512 0.9728046 -0.01130902 0.2613167 0.9652466 -0.003556132 0.2754948 0.9613016 -0.001428306 0.2877038 0.9577193 -5.15403e-4 0.1228603 0.9898447 -0.07150363 0.1534515 0.9881563 0 0.2443861 0.9696781 0 0.2238112 0.9739015 -0.03774142 0.2521463 0.9676892 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 0 3 11 4 12 4 1 4 1 5 12 5 13 5 1 6 13 6 2 6 2 7 13 7 14 7 11 8 15 8 16 8 16 9 15 9 17 9 16 10 17 10 18 10 10 11 19 11 0 11 0 12 19 12 20 12 0 13 20 13 1 13 1 14 20 14 21 14 1 15 21 15 11 15 11 16 21 16 22 16 11 17 22 17 15 17 23 18 24 18 25 18 23 19 25 19 8 19 8 20 25 20 26 20 8 21 26 21 6 21 27 22 28 22 29 22 29 23 28 23 30 23 29 24 30 24 4 24 31 25 32 25 33 25 33 26 32 26 34 26 35 27 36 27 31 27 37 28 38 28 33 28 31 29 33 29 35 29 35 30 33 30 38 30 35 31 38 31 39 31 40 32 33 32 41 32 41 33 33 33 34 33 41 34 34 34 42 34 7 35 9 35 8 35 8 36 9 36 0 36 8 37 0 37 43 37 43 38 0 38 2 38 43 39 2 39 44 39 44 40 2 40 14 40 44 41 14 41 37 41 37 42 14 42 45 42 46 43 40 43 47 43 47 44 40 44 41 44 47 45 41 45 5 45 5 46 41 46 42 46 5 47 42 47 3 47 4 48 30 48 5 48 5 49 30 49 48 49 5 50 48 50 47 50 47 51 48 51 49 51 47 52 49 52 46 52 46 53 49 53 50 53 46 54 50 54 51 54 37 55 33 55 44 55 44 56 33 56 40 56 44 57 40 57 43 57 43 58 40 58 46 58 43 59 46 59 8 59 8 60 46 60 51 60 8 61 51 61 23 61 45 62 14 62 52 62 52 63 14 63 53 63 52 64 53 64 54 64 54 65 53 65 55 65 39 66 56 66 35 66 35 67 56 67 57 67 35 68 57 68 36 68 56 69 54 69 55 69 55 70 58 70 59 70 57 69 56 69 60 69 60 71 56 71 55 71 60 72 55 72 61 72 61 69 55 69 59 69 62 73 63 73 64 73 64 74 63 74 65 74 64 75 65 75 66 75 67 76 68 76 69 76 69 74 68 74 70 74 69 73 70 73 71 73 71 77 70 77 72 77 71 78 72 78 62 78 62 79 72 79 73 79 62 77 73 77 63 77 74 80 75 80 76 80 77 81 78 81 79 81 80 82 81 82 82 82 83 83 84 83 85 83 86 84 87 84 88 84 89 85 90 85 91 85 92 86 93 86 94 86 95 87 96 87 97 87 97 88 98 88 95 88 95 89 98 89 92 89 95 90 92 90 99 90 99 91 92 91 94 91 99 92 94 92 100 92 101 93 102 93 103 93 104 94 105 94 106 94 107 95 106 95 108 95 108 96 106 96 105 96 108 97 105 97 109 97 110 98 111 98 112 98 112 99 111 99 113 99 114 100 115 100 116 100 116 101 115 101 117 101 118 102 119 102 114 102 114 103 116 103 118 103 118 104 116 104 120 104 118 105 120 105 121 105 121 106 120 106 122 106 122 107 120 107 123 107 122 108 123 108 124 108 76 109 75 109 123 109 124 110 123 110 125 110 125 111 123 111 75 111 125 112 75 112 126 112 126 113 75 113 127 113 127 114 75 114 74 114 127 115 74 115 128 115 129 116 130 116 131 116 131 117 130 117 132 117 133 118 134 118 135 118 136 119 137 119 138 119 139 120 90 120 140 120 140 121 90 121 89 121 140 122 89 122 141 122 141 123 89 123 142 123 141 124 142 124 143 124 143 125 142 125 144 125 145 126 136 126 146 126 146 127 136 127 138 127 146 128 138 128 147 128 147 129 138 129 148 129 147 130 148 130 149 130 149 131 148 131 150 131 149 132 150 132 151 132 151 133 150 133 152 133 151 134 152 134 153 134 137 135 144 135 138 135 138 136 144 136 142 136 138 137 142 137 148 137 148 138 142 138 89 138 148 139 89 139 150 139 150 140 89 140 91 140 150 141 91 141 152 141 154 142 155 142 156 142 156 143 155 143 157 143 156 144 157 144 158 144 158 145 157 145 159 145 158 146 159 146 160 146 160 147 159 147 161 147 160 148 161 148 162 148 162 149 161 149 163 149 162 150 163 150 164 150 164 151 163 151 165 151 164 152 165 152 166 152 166 153 165 153 167 153 166 154 167 154 168 154 168 155 167 155 169 155 168 156 169 156 170 156 170 157 169 157 171 157 81 158 77 158 82 158 82 159 77 159 79 159 82 160 79 160 172 160 172 161 79 161 173 161 172 162 173 162 174 162 174 163 173 163 175 163 174 164 175 164 176 164 176 165 175 165 177 165 176 166 177 166 178 166 178 167 177 167 179 167 178 168 179 168 180 168 180 169 179 169 181 169 180 170 181 170 182 170 78 171 145 171 79 171 79 172 145 172 146 172 79 173 146 173 173 173 173 174 146 174 147 174 173 175 147 175 175 175 175 176 147 176 149 176 175 177 149 177 177 177 177 178 149 178 151 178 177 179 151 179 179 179 179 180 151 180 153 180 179 181 153 181 181 181 183 182 184 182 185 182 185 183 184 183 186 183 185 184 186 184 187 184 187 185 186 185 188 185 187 186 188 186 189 186 189 187 188 187 190 187 189 188 190 188 191 188 191 189 190 189 192 189 191 190 192 190 193 190 193 191 192 191 194 191 193 192 194 192 195 192 195 193 194 193 196 193 197 194 133 194 198 194 198 195 133 195 135 195 198 196 135 196 199 196 199 197 135 197 200 197 199 198 200 198 201 198 201 199 200 199 202 199 201 200 202 200 203 200 203 201 202 201 204 201 203 202 204 202 205 202 205 203 204 203 206 203 205 204 206 204 207 204 207 205 206 205 208 205 207 206 208 206 209 206 209 207 208 207 210 207 209 208 210 208 86 208 86 209 210 209 211 209 86 210 211 210 87 210 134 211 80 211 135 211 135 212 80 212 82 212 135 213 82 213 200 213 200 214 82 214 172 214 200 215 172 215 202 215 202 216 172 216 174 216 202 217 174 217 204 217 204 218 174 218 176 218 204 219 176 219 206 219 206 220 176 220 178 220 206 221 178 221 208 221 208 222 178 222 180 222 208 223 180 223 210 223 210 224 180 224 182 224 210 225 182 225 211 225 84 226 212 226 85 226 85 227 212 227 213 227 85 228 213 228 214 228 214 229 213 229 215 229 214 230 215 230 216 230 216 231 215 231 217 231 216 232 217 232 218 232 218 233 217 233 219 233 220 234 221 234 222 234 222 235 221 235 223 235 222 236 223 236 224 236 224 237 223 237 225 237 224 238 225 238 226 238 226 239 225 239 227 239 226 240 227 240 228 240 228 241 227 241 229 241 228 242 229 242 230 242 230 243 229 243 231 243 230 244 231 244 232 244 232 245 231 245 233 245 232 246 233 246 234 246 234 247 233 247 235 247 234 248 235 248 236 248 236 249 235 249 237 249 236 250 237 250 238 250 238 251 237 251 239 251 238 252 239 252 240 252 241 253 240 253 88 253 88 254 240 254 239 254 88 255 239 255 86 255 86 256 239 256 237 256 86 257 237 257 209 257 209 258 237 258 235 258 209 259 235 259 207 259 207 260 235 260 233 260 207 261 233 261 205 261 205 262 233 262 231 262 205 263 231 263 203 263 203 264 231 264 229 264 203 265 229 265 201 265 201 266 229 266 227 266 201 267 227 267 199 267 199 268 227 268 225 268 199 269 225 269 198 269 198 270 225 270 223 270 198 271 223 271 197 271 197 272 223 272 221 272 212 273 128 273 213 273 213 274 128 274 74 274 213 275 74 275 215 275 215 276 74 276 76 276 215 277 76 277 217 277 217 278 76 278 123 278 217 279 123 279 219 279 219 280 123 280 120 280 219 281 120 281 242 281 242 282 120 282 116 282 242 283 116 283 112 283 112 284 116 284 117 284 112 285 117 285 110 285 184 286 83 286 186 286 186 287 83 287 85 287 186 288 85 288 188 288 188 289 85 289 214 289 188 290 214 290 190 290 190 291 214 291 216 291 190 292 216 292 192 292 192 293 216 293 218 293 192 294 218 294 194 294 194 295 218 295 219 295 194 296 219 296 196 296 196 297 219 297 242 297 196 298 242 298 104 298 104 299 242 299 112 299 104 300 112 300 105 300 105 301 112 301 113 301 105 302 113 302 109 302 155 303 183 303 157 303 157 304 183 304 185 304 157 305 185 305 159 305 159 306 185 306 187 306 159 307 187 307 161 307 161 308 187 308 189 308 161 309 189 309 163 309 163 310 189 310 191 310 163 311 191 311 165 311 165 312 191 312 193 312 165 313 193 313 167 313 167 314 193 314 195 314 167 315 195 315 169 315 169 316 195 316 196 316 169 317 196 317 171 317 171 318 196 318 104 318 171 319 104 319 101 319 101 320 104 320 106 320 101 321 106 321 102 321 131 322 154 322 129 322 129 323 154 323 156 323 129 324 156 324 243 324 243 325 156 325 158 325 243 326 158 326 244 326 244 327 158 327 160 327 244 328 160 328 245 328 245 329 160 329 162 329 245 330 162 330 246 330 246 331 162 331 164 331 246 332 164 332 247 332 247 333 164 333 166 333 247 334 166 334 248 334 248 335 166 335 168 335 248 336 168 336 249 336 249 337 168 337 170 337 249 338 170 338 250 338 250 339 170 339 171 339 250 340 171 340 99 340 99 341 171 341 101 341 99 342 101 342 95 342 95 343 101 343 103 343 95 344 103 344 96 344 251 345 252 345 253 345 253 346 252 346 132 346 253 347 132 347 241 347 241 348 132 348 130 348 241 349 130 349 240 349 240 350 130 350 129 350 240 351 129 351 238 351 238 352 129 352 243 352 238 353 243 353 236 353 236 354 243 354 244 354 236 355 244 355 234 355 234 356 244 356 245 356 234 357 245 357 232 357 232 358 245 358 246 358 232 359 246 359 230 359 230 360 246 360 247 360 230 361 247 361 228 361 228 362 247 362 248 362 228 363 248 363 226 363 226 364 248 364 249 364 226 365 249 365 224 365 224 366 249 366 250 366 224 367 250 367 222 367 222 368 250 368 99 368 222 369 99 369 220 369 220 370 99 370 100 370 254 371 255 371 253 371 253 372 255 372 251 372 254 373 253 373 256 373 256 374 253 374 241 374 256 375 241 375 257 375 257 376 241 376 88 376 257 377 88 377 258 377 258 378 88 378 87 378 258 379 87 379 259 379 87 380 211 380 259 380 259 381 211 381 182 381 259 382 182 382 260 382 260 383 182 383 181 383 260 384 181 384 261 384 261 385 181 385 153 385 261 386 153 386 262 386 262 387 153 387 152 387 262 388 152 388 263 388 263 389 152 389 91 389 263 390 91 390 264 390 264 391 91 391 90 391 264 392 90 392 265 392 265 393 90 393 139 393 266 394 267 394 268 394 269 395 255 395 270 395 270 396 255 396 271 396 271 397 272 397 270 397 270 398 272 398 273 398 270 399 273 399 274 399 273 400 275 400 274 400 274 401 275 401 276 401 274 402 276 402 277 402 276 403 278 403 277 403 277 404 278 404 279 404 277 405 279 405 280 405 281 406 282 406 283 406 283 407 282 407 280 407 283 408 280 408 284 408 284 409 280 409 279 409 281 410 285 410 282 410 282 411 285 411 286 411 282 412 286 412 287 412 286 413 288 413 287 413 287 414 288 414 289 414 287 415 289 415 268 415 268 416 289 416 290 416 268 394 290 394 266 394 269 417 291 417 255 417 255 418 291 418 251 418 121 419 292 419 118 419 118 420 292 420 293 420 118 421 293 421 119 421 121 422 122 422 292 422 292 423 122 423 124 423 292 424 124 424 294 424 124 425 125 425 294 425 294 426 125 426 126 426 294 427 126 427 295 427 295 428 126 428 127 428 295 429 127 429 128 429 128 430 212 430 295 430 295 431 212 431 84 431 295 432 84 432 296 432 84 433 83 433 296 433 296 434 83 434 184 434 296 435 184 435 297 435 184 436 183 436 297 436 297 437 183 437 155 437 297 438 155 438 298 438 132 439 299 439 131 439 131 440 299 440 298 440 131 441 298 441 154 441 154 442 298 442 155 442 132 443 252 443 299 443 299 444 252 444 251 444 299 445 251 445 291 445 300 446 301 446 302 446 303 447 304 447 305 447 305 448 304 448 306 448 305 449 306 449 307 449 307 450 306 450 300 450 307 451 300 451 308 451 308 452 300 452 302 452 308 453 302 453 309 453 309 454 310 454 308 454 308 455 310 455 119 455 308 456 119 456 293 456 311 457 312 457 313 457 313 458 312 458 314 458 315 459 303 459 311 459 311 460 303 460 316 460 311 461 316 461 312 461 317 462 301 462 318 462 318 463 301 463 300 463 318 464 300 464 319 464 319 465 300 465 306 465 319 466 306 466 315 466 315 467 306 467 304 467 315 468 304 468 303 468 320 469 321 469 322 469 323 470 324 470 325 470 326 471 327 471 328 471 329 472 317 472 318 472 330 473 331 473 332 473 333 474 314 474 334 474 334 475 314 475 335 475 334 476 335 476 336 476 327 477 329 477 328 477 328 478 329 478 318 478 328 479 318 479 337 479 337 480 318 480 319 480 337 481 319 481 338 481 338 482 319 482 315 482 338 483 315 483 339 483 339 484 315 484 311 484 339 485 311 485 333 485 333 486 311 486 313 486 333 487 313 487 314 487 322 488 340 488 341 488 340 489 322 489 342 489 342 490 322 490 321 490 342 491 321 491 18 491 320 492 322 492 343 492 343 493 322 493 344 493 343 494 344 494 345 494 345 495 344 495 346 495 345 496 346 496 347 496 347 497 346 497 348 497 348 498 346 498 349 498 348 499 349 499 350 499 350 500 349 500 351 500 350 501 351 501 352 501 352 502 351 502 353 502 353 503 351 503 330 503 353 504 330 504 354 504 354 505 330 505 332 505 354 506 332 506 355 506 336 507 356 507 334 507 334 508 356 508 357 508 334 509 357 509 333 509 333 510 357 510 358 510 333 511 358 511 339 511 339 512 358 512 359 512 339 513 359 513 338 513 338 514 359 514 360 514 338 515 360 515 337 515 337 516 360 516 361 516 337 517 361 517 328 517 328 518 361 518 325 518 328 519 325 519 326 519 326 520 325 520 324 520 356 521 331 521 357 521 357 522 331 522 330 522 357 523 330 523 358 523 358 524 330 524 351 524 358 525 351 525 359 525 359 526 351 526 349 526 359 527 349 527 360 527 360 528 349 528 346 528 360 529 346 529 361 529 361 530 346 530 344 530 361 531 344 531 325 531 325 532 344 532 322 532 325 533 322 533 323 533 323 534 322 534 341 534 113 535 111 535 362 535 362 536 111 536 110 536 362 537 110 537 310 537 310 538 110 538 117 538 117 539 115 539 310 539 310 540 115 540 114 540 310 541 114 541 119 541 113 542 362 542 109 542 109 543 362 543 363 543 109 544 363 544 108 544 363 545 364 545 108 545 108 546 364 546 365 546 108 547 365 547 107 547 107 548 365 548 366 548 107 549 366 549 367 549 367 550 368 550 107 550 107 551 368 551 369 551 107 552 369 552 370 552 370 553 369 553 371 553 370 554 371 554 372 554 373 555 374 555 375 555 97 556 375 556 98 556 106 557 107 557 370 557 97 558 96 558 372 558 372 559 96 559 103 559 372 560 103 560 370 560 370 561 103 561 102 561 370 562 102 562 106 562 374 563 93 563 375 563 375 564 93 564 92 564 375 565 92 565 98 565 97 566 372 566 375 566 375 567 372 567 376 567 375 568 376 568 373 568 377 569 378 569 379 569 100 570 94 570 380 570 381 571 382 571 383 571 384 572 385 572 386 572 387 573 388 573 389 573 390 574 391 574 392 574 393 575 394 575 395 575 396 576 397 576 398 576 139 577 140 577 399 577 399 578 140 578 400 578 399 579 400 579 401 579 401 580 400 580 402 580 403 581 404 581 381 581 381 582 404 582 405 582 381 583 405 583 382 583 382 584 405 584 406 584 382 585 406 585 407 585 408 586 409 586 410 586 410 587 409 587 411 587 412 588 413 588 414 588 414 589 413 589 415 589 388 590 387 590 416 590 416 591 387 591 417 591 416 592 417 592 418 592 418 593 417 593 419 593 418 594 419 594 392 594 392 595 419 595 420 595 392 596 420 596 390 596 385 597 384 597 421 597 422 598 378 598 423 598 423 599 378 599 377 599 423 600 377 600 424 600 425 601 403 601 426 601 426 602 403 602 381 602 426 603 381 603 427 603 427 604 381 604 383 604 427 605 383 605 428 605 422 606 429 606 378 606 378 607 429 607 430 607 378 608 430 608 379 608 379 609 430 609 431 609 379 610 431 610 432 610 432 611 431 611 433 611 432 612 433 612 434 612 434 613 433 613 435 613 434 614 435 614 436 614 436 615 435 615 437 615 436 616 437 616 438 616 438 617 437 617 439 617 438 618 439 618 440 618 440 619 439 619 441 619 440 620 441 620 428 620 428 621 441 621 442 621 428 622 442 622 427 622 427 623 442 623 443 623 427 624 443 624 426 624 426 625 443 625 411 625 426 626 411 626 425 626 425 627 411 627 409 627 430 628 386 628 431 628 431 629 386 629 385 629 431 630 385 630 433 630 433 631 385 631 421 631 433 632 421 632 435 632 435 633 421 633 444 633 435 634 444 634 437 634 437 635 444 635 445 635 437 636 445 636 439 636 439 637 445 637 446 637 439 638 446 638 441 638 441 639 446 639 447 639 441 640 447 640 442 640 442 641 447 641 448 641 442 642 448 642 443 642 443 643 448 643 414 643 443 644 414 644 411 644 411 645 414 645 415 645 411 646 415 646 410 646 384 647 449 647 421 647 421 648 449 648 389 648 421 649 389 649 444 649 444 650 389 650 388 650 444 651 388 651 445 651 445 652 388 652 416 652 445 653 416 653 446 653 446 654 416 654 418 654 446 655 418 655 447 655 447 656 418 656 392 656 447 657 392 657 448 657 448 658 392 658 391 658 448 659 391 659 414 659 414 660 391 660 390 660 414 661 390 661 412 661 220 662 450 662 221 662 221 663 450 663 451 663 221 664 451 664 197 664 197 665 451 665 452 665 197 666 452 666 133 666 133 667 452 667 453 667 133 668 453 668 134 668 134 669 453 669 454 669 140 670 141 670 400 670 400 671 141 671 143 671 400 672 143 672 455 672 456 673 145 673 457 673 457 674 145 674 78 674 143 675 144 675 455 675 455 676 144 676 137 676 455 677 137 677 456 677 456 678 137 678 136 678 456 679 136 679 145 679 78 680 77 680 457 680 457 681 77 681 81 681 457 682 81 682 454 682 454 683 81 683 80 683 454 684 80 684 134 684 94 685 93 685 380 685 380 686 93 686 458 686 380 687 458 687 459 687 459 688 458 688 460 688 459 689 460 689 461 689 461 690 460 690 462 690 461 691 462 691 463 691 463 692 462 692 464 692 463 693 464 693 465 693 465 694 464 694 466 694 465 695 466 695 467 695 467 696 466 696 468 696 467 697 468 697 469 697 469 698 468 698 470 698 469 699 470 699 471 699 471 700 470 700 472 700 471 701 472 701 473 701 473 702 472 702 474 702 473 703 474 703 398 703 398 704 474 704 395 704 398 705 395 705 396 705 396 706 395 706 394 706 397 707 402 707 398 707 398 708 402 708 400 708 398 709 400 709 473 709 473 710 400 710 455 710 473 711 455 711 471 711 471 712 455 712 456 712 471 713 456 713 469 713 469 714 456 714 457 714 469 715 457 715 467 715 467 716 457 716 454 716 467 717 454 717 465 717 465 718 454 718 453 718 465 719 453 719 463 719 463 720 453 720 452 720 463 721 452 721 461 721 461 722 452 722 451 722 461 723 451 723 459 723 459 724 451 724 450 724 459 725 450 725 380 725 380 726 450 726 220 726 380 727 220 727 100 727 407 728 393 728 382 728 382 729 393 729 395 729 382 730 395 730 383 730 383 731 395 731 474 731 383 732 474 732 428 732 428 733 474 733 472 733 428 734 472 734 440 734 440 735 472 735 470 735 440 736 470 736 438 736 438 737 470 737 468 737 438 738 468 738 436 738 436 739 468 739 466 739 436 740 466 740 434 740 434 741 466 741 464 741 434 742 464 742 432 742 432 743 464 743 462 743 432 744 462 744 379 744 379 745 462 745 460 745 379 746 460 746 377 746 377 747 460 747 458 747 377 748 458 748 424 748 424 749 458 749 93 749 424 750 93 750 374 750 475 751 476 751 407 751 265 752 139 752 477 752 477 753 139 753 399 753 477 754 399 754 478 754 478 755 399 755 401 755 478 756 401 756 479 756 479 757 401 757 402 757 479 758 402 758 480 758 480 759 402 759 397 759 480 760 397 760 481 760 481 761 397 761 396 761 481 762 396 762 482 762 482 763 396 763 394 763 482 764 394 764 476 764 476 765 394 765 393 765 476 766 393 766 407 766 408 767 483 767 409 767 409 768 483 768 484 768 409 769 484 769 425 769 425 770 484 770 485 770 425 771 485 771 403 771 403 772 485 772 486 772 403 773 486 773 404 773 404 774 486 774 487 774 404 775 487 775 405 775 405 776 487 776 475 776 405 777 475 777 406 777 406 778 475 778 407 778 488 779 489 779 490 779 491 780 492 780 493 780 494 781 495 781 496 781 479 782 480 782 497 782 475 783 487 783 498 783 486 784 485 784 499 784 500 785 501 785 502 785 503 786 504 786 505 786 506 787 507 787 508 787 508 788 507 788 509 788 508 789 509 789 510 789 510 790 509 790 511 790 510 791 511 791 512 791 512 792 511 792 503 792 512 793 503 793 513 793 513 794 503 794 505 794 514 795 515 795 516 795 516 796 515 796 517 796 516 797 517 797 518 797 500 798 502 798 519 798 519 799 502 799 520 799 519 800 520 800 521 800 521 801 520 801 522 801 521 802 522 802 523 802 523 803 522 803 524 803 523 804 524 804 525 804 525 805 524 805 526 805 525 806 526 806 527 806 527 807 526 807 528 807 528 808 526 808 529 808 528 809 529 809 530 809 530 810 529 810 484 810 530 811 484 811 483 811 475 812 498 812 476 812 481 813 482 813 531 813 531 814 482 814 532 814 531 815 532 815 533 815 478 816 496 816 477 816 477 817 496 817 495 817 477 818 495 818 265 818 480 819 481 819 497 819 497 820 481 820 531 820 497 821 531 821 534 821 534 822 531 822 533 822 534 823 533 823 535 823 478 824 479 824 496 824 496 825 479 825 497 825 496 826 497 826 536 826 536 827 497 827 534 827 536 828 534 828 537 828 537 829 534 829 535 829 537 830 535 830 538 830 538 831 535 831 539 831 538 832 539 832 540 832 540 833 539 833 541 833 540 834 541 834 542 834 543 835 544 835 545 835 545 836 544 836 494 836 546 837 493 837 547 837 547 838 493 838 492 838 547 839 492 839 548 839 494 840 496 840 545 840 545 841 496 841 536 841 545 842 536 842 549 842 549 843 536 843 537 843 549 844 537 844 550 844 550 845 537 845 538 845 550 846 538 846 551 846 551 847 538 847 540 847 551 848 540 848 552 848 552 849 540 849 542 849 552 850 542 850 490 850 553 851 546 851 554 851 554 852 546 852 547 852 554 853 547 853 555 853 555 854 547 854 548 854 555 855 548 855 556 855 490 856 489 856 552 856 552 857 489 857 557 857 552 858 557 858 551 858 551 859 557 859 558 859 551 860 558 860 550 860 550 861 558 861 559 861 550 862 559 862 549 862 549 863 559 863 560 863 549 864 560 864 545 864 545 865 560 865 561 865 545 866 561 866 543 866 562 867 563 867 488 867 488 868 563 868 564 868 488 869 564 869 489 869 489 870 564 870 565 870 489 871 565 871 557 871 557 872 565 872 566 872 557 873 566 873 558 873 558 874 566 874 567 874 558 875 567 875 559 875 559 876 567 876 568 876 559 877 568 877 560 877 560 878 568 878 569 878 560 879 569 879 561 879 506 880 508 880 556 880 556 881 508 881 510 881 556 882 510 882 555 882 555 883 510 883 512 883 555 884 512 884 554 884 554 885 512 885 513 885 554 886 513 886 553 886 505 887 570 887 513 887 513 888 570 888 571 888 513 889 571 889 553 889 553 890 571 890 572 890 553 891 572 891 573 891 573 892 562 892 553 892 553 893 562 893 488 893 553 894 488 894 546 894 546 895 488 895 490 895 546 896 490 896 493 896 493 897 490 897 542 897 493 898 542 898 491 898 491 899 542 899 541 899 518 900 574 900 516 900 516 901 574 901 575 901 516 902 575 902 514 902 514 903 575 903 576 903 514 904 576 904 577 904 577 905 576 905 578 905 577 906 578 906 579 906 579 907 578 907 580 907 579 908 580 908 581 908 581 909 580 909 582 909 581 910 582 910 583 910 583 911 582 911 584 911 583 912 584 912 585 912 585 913 584 913 586 913 585 914 586 914 499 914 499 915 586 915 498 915 499 916 498 916 486 916 486 917 498 917 487 917 500 918 515 918 501 918 501 919 515 919 514 919 501 920 514 920 502 920 502 921 514 921 577 921 502 922 577 922 520 922 520 923 577 923 579 923 520 924 579 924 522 924 522 925 579 925 581 925 522 926 581 926 524 926 524 927 581 927 583 927 524 928 583 928 526 928 526 929 583 929 585 929 526 930 585 930 529 930 529 931 585 931 499 931 529 932 499 932 484 932 484 933 499 933 485 933 517 934 587 934 518 934 518 935 587 935 506 935 518 936 506 936 574 936 574 937 506 937 556 937 574 938 556 938 575 938 575 939 556 939 548 939 575 940 548 940 576 940 576 941 548 941 492 941 576 942 492 942 578 942 578 943 492 943 491 943 578 944 491 944 580 944 580 945 491 945 541 945 580 946 541 946 582 946 582 947 541 947 539 947 582 948 539 948 584 948 584 949 539 949 535 949 584 950 535 950 586 950 586 951 535 951 533 951 586 952 533 952 498 952 498 953 533 953 532 953 498 954 532 954 476 954 476 955 532 955 482 955 543 956 561 956 588 956 259 957 260 957 589 957 590 958 266 958 290 958 271 959 255 959 254 959 271 960 591 960 272 960 272 961 591 961 592 961 272 962 592 962 273 962 593 963 594 963 285 963 285 964 594 964 286 964 595 965 596 965 597 965 286 966 594 966 288 966 288 967 594 967 598 967 288 968 598 968 289 968 289 969 598 969 595 969 289 970 595 970 290 970 290 971 595 971 597 971 290 972 597 972 590 972 599 973 600 973 601 973 601 974 600 974 602 974 601 975 602 975 603 975 604 976 605 976 599 976 599 977 605 977 606 977 599 978 606 978 600 978 607 979 608 979 604 979 604 980 608 980 609 980 604 981 609 981 605 981 610 982 611 982 607 982 607 983 611 983 612 983 607 984 612 984 608 984 613 985 264 985 265 985 271 986 254 986 591 986 591 987 254 987 256 987 591 988 256 988 257 988 565 989 564 989 614 989 564 990 563 990 614 990 614 991 563 991 615 991 614 992 615 992 616 992 544 993 543 993 617 993 617 994 543 994 588 994 617 995 588 995 618 995 618 996 588 996 619 996 618 997 619 997 620 997 620 998 619 998 621 998 620 999 621 999 622 999 622 1000 621 1000 623 1000 622 1001 623 1001 624 1001 624 1002 623 1002 625 1002 624 1003 625 1003 626 1003 626 1004 625 1004 627 1004 626 1005 627 1005 628 1005 628 1006 627 1006 629 1006 628 1007 629 1007 630 1007 265 1008 495 1008 613 1008 613 1009 495 1009 494 1009 613 1010 494 1010 631 1010 258 1011 632 1011 633 1011 633 1012 632 1012 634 1012 633 1013 634 1013 635 1013 635 1014 634 1014 636 1014 635 1015 636 1015 637 1015 637 1016 636 1016 638 1016 637 1017 638 1017 275 1017 275 1018 638 1018 276 1018 275 1019 273 1019 637 1019 637 1020 273 1020 592 1020 637 1021 592 1021 635 1021 635 1022 592 1022 591 1022 635 1023 591 1023 633 1023 633 1024 591 1024 257 1024 633 1025 257 1025 258 1025 279 1026 278 1026 639 1026 639 1027 278 1027 640 1027 639 1028 640 1028 641 1028 641 1029 640 1029 642 1029 641 1030 642 1030 643 1030 643 1031 642 1031 644 1031 643 1032 644 1032 645 1032 645 1033 644 1033 646 1033 645 1034 646 1034 647 1034 647 1035 646 1035 589 1035 647 1036 589 1036 648 1036 648 1037 589 1037 260 1037 648 1038 260 1038 261 1038 278 1039 276 1039 640 1039 640 1040 276 1040 638 1040 640 1041 638 1041 642 1041 642 1042 638 1042 636 1042 642 1043 636 1043 644 1043 644 1044 636 1044 634 1044 644 1045 634 1045 646 1045 646 1046 634 1046 632 1046 646 1047 632 1047 589 1047 589 1048 632 1048 258 1048 589 1049 258 1049 259 1049 569 1050 568 1050 649 1050 649 1051 568 1051 650 1051 649 1052 650 1052 651 1052 651 1053 650 1053 652 1053 651 1054 652 1054 653 1054 653 1055 652 1055 654 1055 653 1056 654 1056 655 1056 655 1057 654 1057 656 1057 655 1058 656 1058 657 1058 657 1059 656 1059 658 1059 657 1060 658 1060 659 1060 659 1061 658 1061 660 1061 659 1062 660 1062 661 1062 283 1063 284 1063 662 1063 662 1064 284 1064 663 1064 662 1065 663 1065 664 1065 664 1066 663 1066 665 1066 664 1067 665 1067 666 1067 666 1068 665 1068 667 1068 666 1069 667 1069 668 1069 668 1070 667 1070 669 1070 668 1071 669 1071 670 1071 670 1072 669 1072 671 1072 670 1073 671 1073 672 1073 672 1074 671 1074 673 1074 672 1075 673 1075 674 1075 674 1076 673 1076 675 1076 674 1077 675 1077 676 1077 676 1078 675 1078 262 1078 676 1079 262 1079 263 1079 284 1080 279 1080 663 1080 663 1081 279 1081 639 1081 663 1082 639 1082 665 1082 665 1083 639 1083 641 1083 665 1084 641 1084 667 1084 667 1085 641 1085 643 1085 667 1086 643 1086 669 1086 669 1087 643 1087 645 1087 669 1088 645 1088 671 1088 671 1089 645 1089 647 1089 671 1090 647 1090 673 1090 673 1091 647 1091 648 1091 673 1092 648 1092 675 1092 675 1093 648 1093 261 1093 675 1094 261 1094 262 1094 601 1095 677 1095 599 1095 599 1096 677 1096 678 1096 599 1097 678 1097 604 1097 604 1098 678 1098 679 1098 604 1099 679 1099 607 1099 607 1100 679 1100 680 1100 607 1101 680 1101 610 1101 610 1102 680 1102 504 1102 567 1103 566 1103 681 1103 681 1104 566 1104 682 1104 681 1105 682 1105 683 1105 683 1106 682 1106 684 1106 683 1107 684 1107 685 1107 685 1108 684 1108 686 1108 685 1109 686 1109 687 1109 687 1110 686 1110 688 1110 687 1111 688 1111 689 1111 285 1112 281 1112 593 1112 593 1113 281 1113 690 1113 593 1114 690 1114 691 1114 691 1115 690 1115 692 1115 691 1116 692 1116 693 1116 693 1117 692 1117 694 1117 693 1118 694 1118 695 1118 695 1119 694 1119 696 1119 695 1120 696 1120 697 1120 697 1121 696 1121 698 1121 697 1122 698 1122 699 1122 699 1123 698 1123 700 1123 699 1124 700 1124 701 1124 701 1125 700 1125 702 1125 701 1126 702 1126 703 1126 703 1127 702 1127 704 1127 703 1128 704 1128 705 1128 705 1129 704 1129 706 1129 705 1130 706 1130 707 1130 264 1131 707 1131 263 1131 263 1132 707 1132 706 1132 263 1133 706 1133 676 1133 676 1134 706 1134 704 1134 676 1135 704 1135 674 1135 674 1136 704 1136 702 1136 674 1137 702 1137 672 1137 672 1138 702 1138 700 1138 672 1139 700 1139 670 1139 670 1140 700 1140 698 1140 670 1141 698 1141 668 1141 668 1142 698 1142 696 1142 668 1143 696 1143 666 1143 666 1144 696 1144 694 1144 666 1145 694 1145 664 1145 664 1146 694 1146 692 1146 664 1147 692 1147 662 1147 662 1148 692 1148 690 1148 662 1149 690 1149 283 1149 283 1150 690 1150 281 1150 708 1151 570 1151 680 1151 680 1152 570 1152 505 1152 680 1153 505 1153 504 1153 563 1154 562 1154 615 1154 615 1155 562 1155 573 1155 615 1156 573 1156 616 1156 616 1157 573 1157 572 1157 616 1158 572 1158 708 1158 708 1159 572 1159 571 1159 708 1160 571 1160 570 1160 566 1161 565 1161 682 1161 682 1162 565 1162 614 1162 682 1163 614 1163 684 1163 684 1164 614 1164 616 1164 684 1165 616 1165 686 1165 686 1166 616 1166 708 1166 686 1167 708 1167 688 1167 688 1168 708 1168 680 1168 688 1169 680 1169 689 1169 689 1170 680 1170 679 1170 568 1171 567 1171 650 1171 650 1172 567 1172 681 1172 650 1173 681 1173 652 1173 652 1174 681 1174 683 1174 652 1175 683 1175 654 1175 654 1176 683 1176 685 1176 654 1177 685 1177 656 1177 656 1178 685 1178 687 1178 656 1179 687 1179 658 1179 658 1180 687 1180 689 1180 658 1181 689 1181 660 1181 660 1182 689 1182 679 1182 660 1183 679 1183 661 1183 661 1184 679 1184 678 1184 661 1185 678 1185 709 1185 709 1186 678 1186 677 1186 561 1187 569 1187 588 1187 588 1188 569 1188 649 1188 588 1189 649 1189 619 1189 619 1190 649 1190 651 1190 619 1191 651 1191 621 1191 621 1192 651 1192 653 1192 621 1193 653 1193 623 1193 623 1194 653 1194 655 1194 623 1195 655 1195 625 1195 625 1196 655 1196 657 1196 625 1197 657 1197 627 1197 627 1198 657 1198 659 1198 627 1199 659 1199 629 1199 629 1200 659 1200 661 1200 629 1201 661 1201 630 1201 630 1202 661 1202 709 1202 494 1203 544 1203 631 1203 631 1204 544 1204 617 1204 631 1205 617 1205 710 1205 710 1206 617 1206 618 1206 710 1207 618 1207 711 1207 711 1208 618 1208 620 1208 711 1209 620 1209 712 1209 712 1210 620 1210 622 1210 712 1211 622 1211 713 1211 713 1212 622 1212 624 1212 713 1213 624 1213 714 1213 714 1214 624 1214 626 1214 714 1215 626 1215 715 1215 715 1216 626 1216 628 1216 715 1217 628 1217 716 1217 716 1218 628 1218 630 1218 716 1219 630 1219 717 1219 717 1220 630 1220 709 1220 264 1221 613 1221 707 1221 707 1222 613 1222 631 1222 707 1223 631 1223 705 1223 705 1224 631 1224 710 1224 705 1225 710 1225 703 1225 703 1226 710 1226 711 1226 703 1227 711 1227 701 1227 701 1228 711 1228 712 1228 701 1229 712 1229 699 1229 699 1230 712 1230 713 1230 699 1231 713 1231 697 1231 697 1232 713 1232 714 1232 697 1233 714 1233 695 1233 695 1234 714 1234 715 1234 695 1235 715 1235 693 1235 693 1236 715 1236 716 1236 693 1237 716 1237 691 1237 691 1238 716 1238 717 1238 691 1239 717 1239 593 1239 593 1240 717 1240 709 1240 593 1241 709 1241 594 1241 594 1242 709 1242 677 1242 594 1243 677 1243 598 1243 598 1244 677 1244 601 1244 598 1245 601 1245 595 1245 595 1246 601 1246 603 1246 595 1247 603 1247 596 1247 609 1248 608 1248 718 1248 718 1249 608 1249 612 1249 718 1250 612 1250 611 1250 719 1251 606 1251 718 1251 718 1252 606 1252 605 1252 718 1253 605 1253 609 1253 596 1254 603 1254 720 1254 720 1255 603 1255 602 1255 720 1256 602 1256 719 1256 719 1257 602 1257 600 1257 719 1258 600 1258 606 1258 721 1259 266 1259 590 1259 721 1260 590 1260 720 1260 720 1261 590 1261 597 1261 720 1262 597 1262 596 1262 721 1263 722 1263 266 1263 266 1264 722 1264 267 1264 723 1265 724 1265 725 1265 726 1266 723 1266 727 1266 727 1267 723 1267 728 1267 723 1268 725 1268 728 1268 728 1269 725 1269 729 1269 728 1270 729 1270 730 1270 730 1271 729 1271 731 1271 730 1272 731 1272 732 1272 733 1273 732 1273 731 1273 734 1274 735 1274 736 1274 736 1275 735 1275 737 1275 736 1276 737 1276 738 1276 736 1277 733 1277 734 1277 734 1278 733 1278 731 1278 734 1279 731 1279 739 1279 739 1280 731 1280 729 1280 739 1281 729 1281 740 1281 740 1282 729 1282 725 1282 740 1283 725 1283 741 1283 741 1284 725 1284 724 1284 741 1285 724 1285 742 1285 296 1286 297 1286 331 1286 274 1287 277 1287 743 1287 331 1288 297 1288 332 1288 332 1289 297 1289 298 1289 332 1290 298 1290 355 1290 331 1291 356 1291 296 1291 296 1292 356 1292 336 1292 296 1293 336 1293 295 1293 743 1294 744 1294 274 1294 274 1295 744 1295 745 1295 274 1296 745 1296 270 1296 280 1297 746 1297 277 1297 277 1298 746 1298 747 1298 277 1299 747 1299 743 1299 308 1300 293 1300 307 1300 307 1301 293 1301 305 1301 268 1302 267 1302 730 1302 298 1303 299 1303 355 1303 355 1296 299 1296 291 1296 355 1296 291 1296 745 1296 745 1296 291 1296 269 1296 745 1304 269 1304 270 1304 748 1305 726 1305 727 1305 336 1306 335 1306 295 1306 295 1307 335 1307 314 1307 295 1308 314 1308 294 1308 294 1309 314 1309 312 1309 294 1310 312 1310 292 1310 292 1311 312 1311 316 1311 292 1312 316 1312 293 1312 293 1313 316 1313 303 1313 293 1314 303 1314 305 1314 730 1315 267 1315 728 1315 728 1316 267 1316 722 1316 728 1317 722 1317 727 1317 727 1318 722 1318 749 1318 727 1319 749 1319 748 1319 730 1320 732 1320 268 1320 268 1321 732 1321 733 1321 268 1322 733 1322 287 1322 287 1323 733 1323 736 1323 287 1324 736 1324 282 1324 282 1325 736 1325 738 1325 282 1296 738 1296 280 1296 280 1326 738 1326 750 1326 280 1327 750 1327 746 1327 751 1328 752 1328 753 1328 754 1329 755 1329 756 1329 757 1330 758 1330 759 1330 760 1331 757 1331 761 1331 757 1332 759 1332 761 1332 761 1333 759 1333 762 1333 761 1334 762 1334 763 1334 763 1335 762 1335 764 1335 763 1336 764 1336 765 1336 765 1337 764 1337 766 1337 765 1338 766 1338 767 1338 767 1339 766 1339 768 1339 767 1340 768 1340 769 1340 769 1341 768 1341 770 1341 769 1342 770 1342 771 1342 756 1343 760 1343 754 1343 754 1344 760 1344 761 1344 754 1345 761 1345 772 1345 772 1346 761 1346 763 1346 772 1347 763 1347 773 1347 773 1348 763 1348 765 1348 773 1349 765 1349 774 1349 774 1350 765 1350 767 1350 774 1351 767 1351 775 1351 775 1352 767 1352 769 1352 775 1353 769 1353 776 1353 776 1354 769 1354 771 1354 776 1355 771 1355 777 1355 755 1356 754 1356 778 1356 778 1357 754 1357 772 1357 778 1358 772 1358 779 1358 779 1359 772 1359 773 1359 779 1360 773 1360 780 1360 780 1361 773 1361 774 1361 780 1362 774 1362 781 1362 781 1363 774 1363 775 1363 781 1364 775 1364 782 1364 782 1365 775 1365 776 1365 782 1366 776 1366 783 1366 783 1367 776 1367 777 1367 783 1368 777 1368 784 1368 784 1369 785 1369 783 1369 783 1370 785 1370 786 1370 783 1371 786 1371 782 1371 782 1372 786 1372 787 1372 782 1373 787 1373 781 1373 781 1374 787 1374 788 1374 781 1375 788 1375 780 1375 780 1376 788 1376 789 1376 780 1377 789 1377 779 1377 779 1378 789 1378 790 1378 779 1379 790 1379 778 1379 778 1380 790 1380 791 1380 778 1381 791 1381 755 1381 755 1382 791 1382 792 1382 755 1383 792 1383 756 1383 793 1384 794 1384 784 1384 784 1385 794 1385 795 1385 784 1386 795 1386 785 1386 796 1387 797 1387 798 1387 798 1388 797 1388 799 1388 798 1389 799 1389 800 1389 800 1390 799 1390 801 1390 800 1391 801 1391 802 1391 802 1392 801 1392 803 1392 802 1393 803 1393 804 1393 804 1394 803 1394 805 1394 804 1395 805 1395 806 1395 806 1396 805 1396 807 1396 806 1397 807 1397 808 1397 808 1398 807 1398 809 1398 808 1399 809 1399 810 1399 796 1400 811 1400 797 1400 797 1401 811 1401 812 1401 797 1402 812 1402 799 1402 799 1403 812 1403 813 1403 799 1404 813 1404 801 1404 801 1405 813 1405 814 1405 801 1406 814 1406 803 1406 803 1407 814 1407 815 1407 803 1408 815 1408 805 1408 805 1409 815 1409 816 1409 805 1410 816 1410 807 1410 807 1411 816 1411 817 1411 807 1412 817 1412 809 1412 811 1413 751 1413 812 1413 812 1414 751 1414 753 1414 812 1415 753 1415 813 1415 813 1416 753 1416 818 1416 813 1417 818 1417 814 1417 814 1418 818 1418 819 1418 814 1419 819 1419 815 1419 815 1420 819 1420 820 1420 815 1421 820 1421 816 1421 816 1422 820 1422 821 1422 816 1423 821 1423 817 1423 770 1424 810 1424 771 1424 771 1425 810 1425 809 1425 771 1426 809 1426 777 1426 777 1427 809 1427 817 1427 777 1428 817 1428 784 1428 784 1429 817 1429 821 1429 784 1430 821 1430 793 1430 793 1431 821 1431 820 1431 793 1432 820 1432 822 1432 822 1433 820 1433 819 1433 822 1434 819 1434 823 1434 823 1435 819 1435 818 1435 823 1436 818 1436 824 1436 824 1437 818 1437 753 1437 824 1438 753 1438 825 1438 825 1439 753 1439 752 1439 825 1440 752 1440 826 1440 827 1441 828 1441 829 1441 830 1442 831 1442 832 1442 832 1443 831 1443 833 1443 832 1444 833 1444 834 1444 834 1445 833 1445 835 1445 834 1446 835 1446 836 1446 837 1447 831 1447 838 1447 838 1448 831 1448 830 1448 838 1449 830 1449 839 1449 837 1450 840 1450 831 1450 831 1451 840 1451 841 1451 831 1452 841 1452 833 1452 833 1453 841 1453 827 1453 833 1454 827 1454 835 1454 835 1455 827 1455 829 1455 835 1456 829 1456 836 1456 842 1457 828 1457 843 1457 843 1458 828 1458 827 1458 843 1459 827 1459 844 1459 844 1460 827 1460 841 1460 844 1461 841 1461 845 1461 845 1462 841 1462 840 1462 845 1463 840 1463 846 1463 846 1464 840 1464 837 1464 847 1465 848 1465 849 1465 849 1466 848 1466 850 1466 849 1467 850 1467 851 1467 851 1468 850 1468 852 1468 851 1469 852 1469 853 1469 853 1470 852 1470 854 1470 853 1471 854 1471 855 1471 855 1472 854 1472 856 1472 792 1473 847 1473 756 1473 756 1474 847 1474 849 1474 756 1475 849 1475 760 1475 760 1476 849 1476 851 1476 760 1477 851 1477 757 1477 757 1478 851 1478 853 1478 757 1479 853 1479 758 1479 758 1480 853 1480 855 1480 857 1481 362 1481 310 1481 362 1482 857 1482 363 1482 340 1483 21 1483 341 1483 341 1484 21 1484 20 1484 341 1482 20 1482 323 1482 20 1485 19 1485 323 1485 323 1486 19 1486 10 1486 323 1487 10 1487 324 1487 324 1482 10 1482 9 1482 324 1488 9 1488 326 1488 326 1482 9 1482 7 1482 326 1489 7 1489 327 1489 18 1490 17 1490 342 1490 342 1482 17 1482 15 1482 342 1491 15 1491 340 1491 340 1482 15 1482 22 1482 340 1492 22 1492 21 1492 7 1493 6 1493 327 1493 327 1482 6 1482 26 1482 327 1482 26 1482 329 1482 26 1482 25 1482 329 1482 329 1482 25 1482 24 1482 329 1494 24 1494 317 1494 317 1482 24 1482 301 1482 24 1495 858 1495 301 1495 301 1496 858 1496 859 1496 301 1497 859 1497 302 1497 302 1498 859 1498 860 1498 302 1499 860 1499 309 1499 309 1500 860 1500 861 1500 309 1501 861 1501 310 1501 310 1502 861 1502 862 1502 310 1503 862 1503 857 1503 857 1504 863 1504 363 1504 363 1505 863 1505 864 1505 363 1506 864 1506 364 1506 364 1507 864 1507 865 1507 364 1482 865 1482 365 1482 365 1482 865 1482 866 1482 365 1508 866 1508 366 1508 366 1509 866 1509 867 1509 366 1510 867 1510 367 1510 367 1482 867 1482 868 1482 367 1511 868 1511 368 1511 368 1482 868 1482 369 1482 369 1482 868 1482 869 1482 369 1482 869 1482 371 1482 870 1512 871 1512 872 1512 872 1513 871 1513 873 1513 858 1514 24 1514 874 1514 874 1515 24 1515 23 1515 874 1516 23 1516 875 1516 875 1517 23 1517 51 1517 875 1518 51 1518 876 1518 876 1519 51 1519 50 1519 876 1520 50 1520 877 1520 877 1521 50 1521 878 1521 878 1522 50 1522 49 1522 878 1523 49 1523 879 1523 879 1524 49 1524 48 1524 879 1525 48 1525 880 1525 880 1526 48 1526 30 1526 880 1527 30 1527 873 1527 873 1528 30 1528 28 1528 873 1529 28 1529 872 1529 881 1530 882 1530 883 1530 320 1531 884 1531 885 1531 885 1532 883 1532 320 1532 320 1533 883 1533 886 1533 320 1534 886 1534 321 1534 321 1535 886 1535 18 1535 355 1536 745 1536 354 1536 354 1537 745 1537 887 1537 354 1538 887 1538 353 1538 353 1539 887 1539 888 1539 353 1540 888 1540 352 1540 352 1540 888 1540 889 1540 352 1541 889 1541 350 1541 350 1542 889 1542 890 1542 350 1543 890 1543 348 1543 348 1544 890 1544 891 1544 348 1545 891 1545 347 1545 347 1546 891 1546 892 1546 347 1547 892 1547 345 1547 345 1548 892 1548 893 1548 345 1549 893 1549 343 1549 343 1550 893 1550 894 1550 343 1551 894 1551 320 1551 320 1551 894 1551 895 1551 320 1552 895 1552 884 1552 14 69 13 69 53 69 53 1553 13 1553 12 1553 53 1554 12 1554 11 1554 896 1555 897 1555 898 1555 899 1556 900 1556 901 1556 902 1557 885 1557 884 1557 743 1558 747 1558 903 1558 750 1559 738 1559 737 1559 745 1560 744 1560 887 1560 887 1561 744 1561 904 1561 887 1562 904 1562 888 1562 888 1563 904 1563 889 1563 889 1564 904 1564 905 1564 889 1565 905 1565 890 1565 890 1566 905 1566 906 1566 890 1567 906 1567 891 1567 891 1568 906 1568 892 1568 892 1569 906 1569 907 1569 892 1570 907 1570 893 1570 893 1571 907 1571 908 1571 893 1572 908 1572 894 1572 909 1573 910 1573 911 1573 911 1574 910 1574 912 1574 894 1575 908 1575 895 1575 895 1576 908 1576 911 1576 895 1577 911 1577 884 1577 884 1578 911 1578 912 1578 884 1579 912 1579 902 1579 913 1580 914 1580 911 1580 911 1581 914 1581 915 1581 911 1582 915 1582 909 1582 899 1583 901 1583 916 1583 742 1584 896 1584 741 1584 741 1585 896 1585 898 1585 741 1586 898 1586 740 1586 740 1587 898 1587 917 1587 740 1588 917 1588 739 1588 739 1589 917 1589 918 1589 739 1590 918 1590 734 1590 734 1591 918 1591 735 1591 735 1592 918 1592 919 1592 735 1593 919 1593 737 1593 737 1594 919 1594 920 1594 737 1595 920 1595 750 1595 750 1596 920 1596 921 1596 750 1597 921 1597 746 1597 897 1598 916 1598 898 1598 898 1599 916 1599 901 1599 898 1600 901 1600 917 1600 917 1601 901 1601 922 1601 917 1602 922 1602 918 1602 918 1603 922 1603 923 1603 918 1604 923 1604 919 1604 919 1605 923 1605 924 1605 919 1606 924 1606 920 1606 920 1607 924 1607 925 1607 920 1608 925 1608 921 1608 921 1609 925 1609 903 1609 921 1610 903 1610 746 1610 746 1611 903 1611 747 1611 900 1612 913 1612 901 1612 901 1613 913 1613 911 1613 901 1614 911 1614 922 1614 922 1615 911 1615 908 1615 922 1616 908 1616 923 1616 923 1617 908 1617 907 1617 923 1618 907 1618 924 1618 924 1619 907 1619 906 1619 924 1620 906 1620 925 1620 925 1621 906 1621 905 1621 925 1622 905 1622 903 1622 903 1623 905 1623 904 1623 903 1624 904 1624 743 1624 743 1625 904 1625 744 1625 926 1626 927 1626 928 1626 929 1627 930 1627 931 1627 931 1628 930 1628 932 1628 931 1629 932 1629 933 1629 933 1630 932 1630 934 1630 933 1631 934 1631 935 1631 936 1632 930 1632 937 1632 937 1633 930 1633 929 1633 937 1634 929 1634 938 1634 936 1635 939 1635 930 1635 930 1636 939 1636 940 1636 930 1637 940 1637 932 1637 932 1638 940 1638 926 1638 932 1639 926 1639 934 1639 934 1640 926 1640 928 1640 934 1641 928 1641 935 1641 941 1642 927 1642 942 1642 942 1643 927 1643 926 1643 942 1644 926 1644 943 1644 943 1645 926 1645 940 1645 943 1646 940 1646 944 1646 944 1647 940 1647 939 1647 944 1648 939 1648 945 1648 945 1649 939 1649 936 1649 946 1650 947 1650 948 1650 948 1651 947 1651 949 1651 948 1652 949 1652 950 1652 950 1653 949 1653 951 1653 950 1654 951 1654 952 1654 952 1655 951 1655 953 1655 952 1656 953 1656 954 1656 954 1657 953 1657 955 1657 956 1658 946 1658 957 1658 957 1659 946 1659 948 1659 957 1660 948 1660 958 1660 958 1661 948 1661 950 1661 958 1662 950 1662 959 1662 959 1663 950 1663 952 1663 959 1664 952 1664 960 1664 960 1665 952 1665 954 1665 961 1666 962 1666 963 1666 959 1667 960 1667 964 1667 958 1668 959 1668 965 1668 959 1669 964 1669 965 1669 965 1670 964 1670 966 1670 965 1671 966 1671 967 1671 967 1672 966 1672 968 1672 967 1673 968 1673 969 1673 969 1674 968 1674 970 1674 969 1675 970 1675 971 1675 971 1676 970 1676 972 1676 971 1677 972 1677 973 1677 973 1678 972 1678 974 1678 973 1679 974 1679 975 1679 975 1680 974 1680 976 1680 975 1681 976 1681 977 1681 977 1682 976 1682 978 1682 977 1683 978 1683 979 1683 979 1684 978 1684 980 1684 979 1685 980 1685 981 1685 980 1686 982 1686 981 1686 981 1687 982 1687 983 1687 981 1688 983 1688 984 1688 984 1689 983 1689 985 1689 984 1690 985 1690 986 1690 986 1691 985 1691 987 1691 986 1692 987 1692 988 1692 988 1693 987 1693 989 1693 988 1694 989 1694 990 1694 990 1695 989 1695 991 1695 991 1696 992 1696 990 1696 990 1697 992 1697 993 1697 990 1698 993 1698 988 1698 988 1699 993 1699 994 1699 988 1700 994 1700 986 1700 986 1701 994 1701 995 1701 986 1702 995 1702 984 1702 984 1703 995 1703 996 1703 984 1704 996 1704 981 1704 981 1705 996 1705 997 1705 981 1706 997 1706 979 1706 979 1707 997 1707 998 1707 979 1708 998 1708 977 1708 977 1709 998 1709 999 1709 977 1710 999 1710 975 1710 975 1711 999 1711 1000 1711 975 1712 1000 1712 973 1712 973 1713 1000 1713 1001 1713 973 1714 1001 1714 971 1714 971 1715 1001 1715 1002 1715 971 1716 1002 1716 969 1716 969 1717 1002 1717 1003 1717 969 1718 1003 1718 967 1718 967 1719 1003 1719 1004 1719 967 1720 1004 1720 965 1720 965 1721 1004 1721 1005 1721 965 1722 1005 1722 958 1722 958 1723 1005 1723 957 1723 992 1724 961 1724 993 1724 993 1725 961 1725 963 1725 993 1726 963 1726 994 1726 994 1727 963 1727 1006 1727 994 1728 1006 1728 995 1728 995 1729 1006 1729 1007 1729 995 1730 1007 1730 996 1730 996 1731 1007 1731 1008 1731 996 1732 1008 1732 997 1732 997 1733 1008 1733 1009 1733 997 1734 1009 1734 998 1734 998 1735 1009 1735 1010 1735 998 1736 1010 1736 999 1736 999 1737 1010 1737 1011 1737 999 1738 1011 1738 1000 1738 1000 1739 1011 1739 1012 1739 1000 1740 1012 1740 1001 1740 1001 1741 1012 1741 1013 1741 1001 1742 1013 1742 1002 1742 1002 1743 1013 1743 1014 1743 1002 1744 1014 1744 1003 1744 1003 1745 1014 1745 1015 1745 1003 1746 1015 1746 1004 1746 1004 1747 1015 1747 1016 1747 1004 1748 1016 1748 1005 1748 1005 1749 1016 1749 1017 1749 1005 1750 1017 1750 957 1750 957 1751 1017 1751 956 1751 956 1752 1017 1752 1018 1752 1018 1753 1017 1753 1016 1753 1018 1754 1016 1754 1019 1754 1019 1755 1016 1755 1015 1755 1019 1756 1015 1756 1020 1756 1020 1757 1015 1757 1014 1757 1020 1758 1014 1758 1021 1758 1021 1759 1014 1759 1013 1759 1021 1760 1013 1760 1022 1760 1022 1761 1013 1761 1012 1761 1022 1762 1012 1762 1023 1762 1023 1763 1012 1763 1011 1763 1023 1764 1011 1764 1024 1764 1024 1765 1011 1765 1010 1765 1024 1766 1010 1766 1025 1766 1025 1767 1010 1767 1009 1767 1025 1768 1009 1768 1026 1768 1026 1769 1009 1769 1008 1769 1026 1770 1008 1770 1027 1770 1027 1771 1008 1771 1007 1771 1027 1772 1007 1772 1028 1772 1028 1773 1007 1773 1006 1773 1028 1774 1006 1774 1029 1774 1029 1775 1006 1775 963 1775 1029 1776 963 1776 1030 1776 1030 1777 963 1777 962 1777 1030 1778 962 1778 1031 1778 1032 1779 1033 1779 1034 1779 1035 1780 1036 1780 1037 1780 1037 1781 1036 1781 1038 1781 1037 1782 1038 1782 1039 1782 1039 1783 1038 1783 1040 1783 1039 1784 1040 1784 1041 1784 1041 1785 1040 1785 1042 1785 1041 1786 1042 1786 1043 1786 1043 1787 1042 1787 1044 1787 1044 1788 1045 1788 1043 1788 1043 1789 1045 1789 1046 1789 1043 1790 1046 1790 1047 1790 1047 1791 1046 1791 1048 1791 1047 1792 1048 1792 1049 1792 1048 1793 1050 1793 1049 1793 1049 1794 1050 1794 1051 1794 1049 1795 1051 1795 1034 1795 1034 1796 1051 1796 1052 1796 1034 1797 1052 1797 1032 1797 1053 1798 1054 1798 1055 1798 1055 1799 1054 1799 1056 1799 1056 1800 1057 1800 1058 1800 1058 1801 1057 1801 1059 1801 1060 1802 1061 1802 1062 1802 1062 1803 1061 1803 1063 1803 1064 1804 1065 1804 1066 1804 1067 1805 1068 1805 1069 1805 1069 1806 1068 1806 1070 1806 1071 1807 1072 1807 1073 1807 1073 1808 1072 1808 1074 1808 1073 1809 1074 1809 1075 1809 1075 1810 1074 1810 1076 1810 1075 1811 1076 1811 1077 1811 1077 1812 1076 1812 1078 1812 1077 1813 1078 1813 1079 1813 1079 1814 1078 1814 1080 1814 1079 1815 1080 1815 1070 1815 1070 1816 1080 1816 1081 1816 1070 1817 1081 1817 1069 1817 1071 1818 1073 1818 1082 1818 1082 1819 1073 1819 1083 1819 1082 1820 1083 1820 1084 1820 1084 1821 1083 1821 1058 1821 1084 1822 1058 1822 1085 1822 1085 1823 1058 1823 1059 1823 1085 1824 1059 1824 1086 1824 1068 1825 1087 1825 1070 1825 1070 1826 1087 1826 1088 1826 1070 1827 1088 1827 1079 1827 1079 1828 1088 1828 1089 1828 1079 1829 1089 1829 1077 1829 1077 1830 1089 1830 1090 1830 1077 1831 1090 1831 1075 1831 1075 1832 1090 1832 1091 1832 1075 1833 1091 1833 1073 1833 1073 1834 1091 1834 1092 1834 1073 1835 1092 1835 1083 1835 1083 1836 1092 1836 1093 1836 1083 1837 1093 1837 1058 1837 1058 1838 1093 1838 1055 1838 1058 1839 1055 1839 1056 1839 1087 1840 1065 1840 1088 1840 1088 1841 1065 1841 1064 1841 1088 1842 1064 1842 1089 1842 1089 1843 1064 1843 1094 1843 1089 1844 1094 1844 1090 1844 1090 1845 1094 1845 1095 1845 1090 1846 1095 1846 1091 1846 1091 1847 1095 1847 1096 1847 1091 1848 1096 1848 1092 1848 1092 1849 1096 1849 1097 1849 1092 1850 1097 1850 1093 1850 1093 1851 1097 1851 1098 1851 1093 1852 1098 1852 1055 1852 1055 1853 1098 1853 1062 1853 1055 1854 1062 1854 1053 1854 1053 1855 1062 1855 1063 1855 1099 1856 1060 1856 1100 1856 1100 1857 1060 1857 1062 1857 1100 1858 1062 1858 1101 1858 1101 1859 1062 1859 1098 1859 1101 1860 1098 1860 1102 1860 1102 1861 1098 1861 1097 1861 1102 1862 1097 1862 1103 1862 1103 1863 1097 1863 1096 1863 1103 1864 1096 1864 1104 1864 1104 1865 1096 1865 1095 1865 1104 1866 1095 1866 1105 1866 1105 1867 1095 1867 1094 1867 1105 1868 1094 1868 1106 1868 1106 1869 1094 1869 1064 1869 1106 1870 1064 1870 1107 1870 1107 1871 1064 1871 1066 1871 1107 1872 1066 1872 1108 1872 1109 1873 1110 1873 1111 1873 1112 1874 1113 1874 1114 1874 1115 1875 1087 1875 1068 1875 1066 1876 1065 1876 1116 1876 1116 1877 1065 1877 1087 1877 1109 1878 1111 1878 1117 1878 1118 1879 1119 1879 1120 1879 1121 1880 1122 1880 1123 1880 1124 1881 1125 1881 1126 1881 1127 1882 1128 1882 1122 1882 1129 1883 1130 1883 1131 1883 1131 1884 1130 1884 1132 1884 1131 1885 1132 1885 1121 1885 1121 1886 1132 1886 1127 1886 1121 1887 1127 1887 1122 1887 1113 1888 1133 1888 1114 1888 1114 1889 1133 1889 1134 1889 1114 1890 1134 1890 1135 1890 1135 1891 1134 1891 1136 1891 1135 1892 1136 1892 1137 1892 1137 1893 1136 1893 1138 1893 1137 1894 1138 1894 1139 1894 1139 1895 1138 1895 1140 1895 1139 1896 1140 1896 1129 1896 1129 1897 1140 1897 1141 1897 1129 1898 1141 1898 1130 1898 1108 1899 1066 1899 1142 1899 1142 1900 1066 1900 1116 1900 1142 1901 1116 1901 1143 1901 1143 1902 1116 1902 1144 1902 1120 1903 1117 1903 1118 1903 1118 1904 1117 1904 1111 1904 1118 1905 1111 1905 1145 1905 1145 1906 1111 1906 1146 1906 1145 1907 1146 1907 1147 1907 1147 1908 1146 1908 1148 1908 1147 1909 1148 1909 1149 1909 1149 1910 1148 1910 1150 1910 1149 1911 1150 1911 1151 1911 1151 1912 1150 1912 1152 1912 1151 1913 1152 1913 1144 1913 1144 1914 1152 1914 1153 1914 1144 1915 1153 1915 1143 1915 1087 1916 1115 1916 1116 1916 1116 1917 1115 1917 1154 1917 1116 1918 1154 1918 1144 1918 1144 1919 1154 1919 1155 1919 1144 1920 1155 1920 1151 1920 1151 1921 1155 1921 1156 1921 1151 1922 1156 1922 1149 1922 1149 1923 1156 1923 1157 1923 1149 1924 1157 1924 1147 1924 1147 1925 1157 1925 1158 1925 1147 1926 1158 1926 1145 1926 1145 1927 1158 1927 1125 1927 1145 1928 1125 1928 1118 1928 1118 1929 1125 1929 1124 1929 1118 1930 1124 1930 1119 1930 1067 1931 1112 1931 1068 1931 1068 1932 1112 1932 1114 1932 1068 1933 1114 1933 1115 1933 1115 1934 1114 1934 1135 1934 1115 1935 1135 1935 1154 1935 1154 1936 1135 1936 1137 1936 1154 1937 1137 1937 1155 1937 1155 1938 1137 1938 1139 1938 1155 1939 1139 1939 1156 1939 1156 1940 1139 1940 1129 1940 1156 1941 1129 1941 1157 1941 1157 1942 1129 1942 1131 1942 1157 1943 1131 1943 1158 1943 1158 1944 1131 1944 1121 1944 1158 1945 1121 1945 1125 1945 1125 1946 1121 1946 1123 1946 1125 1947 1123 1947 1126 1947 1159 1948 1160 1948 1161 1948 1162 1949 1163 1949 1164 1949 1165 1950 1166 1950 1167 1950 1047 1951 1168 1951 1043 1951 1043 1952 1168 1952 1169 1952 1169 1953 1168 1953 1170 1953 1170 1954 1168 1954 1171 1954 1170 1955 1171 1955 1172 1955 1172 1956 1171 1956 1173 1956 1173 1957 1171 1957 1167 1957 1173 1958 1167 1958 1174 1958 1166 1959 1175 1959 1167 1959 1167 1960 1175 1960 1176 1960 1167 1961 1176 1961 1174 1961 1174 1962 1176 1962 1177 1962 1162 1963 1164 1963 1178 1963 1179 1964 1034 1964 1033 1964 1033 1965 1180 1965 1179 1965 1179 1966 1180 1966 1181 1966 1179 1967 1181 1967 1182 1967 1182 1968 1181 1968 1183 1968 1182 1969 1183 1969 1161 1969 1161 1970 1183 1970 1184 1970 1161 1971 1184 1971 1159 1971 1049 1972 1034 1972 1185 1972 1185 1973 1034 1973 1179 1973 1185 1974 1179 1974 1186 1974 1186 1975 1179 1975 1182 1975 1186 1976 1182 1976 1164 1976 1164 1977 1182 1977 1161 1977 1164 1978 1161 1978 1178 1978 1178 1979 1161 1979 1160 1979 1047 1980 1049 1980 1168 1980 1168 1981 1049 1981 1185 1981 1168 1982 1185 1982 1171 1982 1171 1983 1185 1983 1186 1983 1171 1984 1186 1984 1167 1984 1167 1985 1186 1985 1164 1985 1167 1986 1164 1986 1165 1986 1165 1987 1164 1987 1163 1987 1187 1988 1188 1988 1189 1988 1190 1989 1191 1989 1187 1989 1192 1990 1193 1990 1194 1990 1194 1991 1193 1991 1195 1991 1194 1992 1195 1992 1196 1992 1197 1993 1198 1993 1199 1993 1199 1994 1198 1994 1200 1994 1199 1995 1200 1995 1201 1995 1177 1996 1197 1996 1174 1996 1174 1997 1197 1997 1199 1997 1174 1998 1199 1998 1173 1998 1173 1999 1199 1999 1202 1999 1173 2000 1202 2000 1172 2000 1172 2001 1202 2001 1170 2001 1170 2002 1202 2002 1203 2002 1170 2003 1203 2003 1169 2003 1204 2004 1039 2004 1041 2004 1205 2005 1035 2005 1037 2005 1187 2006 1189 2006 1190 2006 1190 2007 1189 2007 1206 2007 1190 2008 1206 2008 1207 2008 1207 2009 1206 2009 1205 2009 1207 2010 1205 2010 1208 2010 1208 2011 1205 2011 1037 2011 1208 2012 1037 2012 1039 2012 1039 2013 1204 2013 1208 2013 1208 2014 1204 2014 1209 2014 1208 2015 1209 2015 1207 2015 1207 2016 1209 2016 1194 2016 1207 2017 1194 2017 1190 2017 1190 2018 1194 2018 1196 2018 1190 2019 1196 2019 1191 2019 1043 2020 1169 2020 1041 2020 1041 2021 1169 2021 1203 2021 1041 2022 1203 2022 1204 2022 1204 2023 1203 2023 1202 2023 1204 2024 1202 2024 1209 2024 1209 2025 1202 2025 1199 2025 1209 2026 1199 2026 1194 2026 1194 2027 1199 2027 1201 2027 1194 2028 1201 2028 1192 2028 1210 2029 1211 2029 1212 2029 1210 2030 1212 2030 1213 2030 1213 2031 1212 2031 1214 2031 1213 2032 1214 2032 1215 2032 1216 2033 1217 2033 1218 2033 1218 2034 1217 2034 1219 2034 1218 2035 1219 2035 1220 2035 1220 2036 1221 2036 1218 2036 1218 2037 1221 2037 1222 2037 1218 2038 1222 2038 1223 2038 1224 2039 1225 2039 1218 2039 1218 2040 1225 2040 1226 2040 1218 2041 1226 2041 1227 2041 1227 2042 1228 2042 1218 2042 1218 2043 1228 2043 1229 2043 1218 2044 1229 2044 1230 2044 1230 2045 1231 2045 1218 2045 1218 2046 1231 2046 1232 2046 1218 2047 1232 2047 1216 2047 1223 2048 1214 2048 1218 2048 1218 2049 1214 2049 1212 2049 1218 2050 1212 2050 1224 2050 1224 2051 1212 2051 1211 2051 1224 2052 1211 2052 371 2052 1233 2053 862 2053 1234 2053 1234 2054 862 2054 861 2054 371 2055 869 2055 1224 2055 1224 2056 869 2056 868 2056 1224 2057 868 2057 1235 2057 868 2058 867 2058 1235 2058 1235 2059 867 2059 866 2059 1235 2060 866 2060 865 2060 865 2061 864 2061 1235 2061 1235 2062 864 2062 863 2062 1235 2063 863 2063 1233 2063 1233 2064 863 2064 857 2064 1233 2065 857 2065 862 2065 1236 2066 1237 2066 1238 2066 1238 2067 1237 2067 1239 2067 1238 2068 1239 2068 1240 2068 1241 2069 1242 2069 1243 2069 1244 2070 1245 2070 1240 2070 1246 2071 1247 2071 1248 2071 1248 2072 1249 2072 1246 2072 1246 2073 1249 2073 1250 2073 1246 2074 1250 2074 1251 2074 1251 2075 1252 2075 1246 2075 1246 2076 1252 2076 1253 2076 1246 2077 1253 2077 1254 2077 1244 2078 1240 2078 1254 2078 1254 2079 1240 2079 1239 2079 1254 2080 1239 2080 1246 2080 1246 2081 1239 2081 1237 2081 1246 2082 1237 2082 1255 2082 1255 2083 1256 2083 1246 2083 1246 2084 1256 2084 1257 2084 1246 2085 1257 2085 1258 2085 1258 2086 1259 2086 1246 2086 1246 2087 1259 2087 1260 2087 1246 2088 1260 2088 1247 2088 1243 2089 1261 2089 1241 2089 1241 2090 1261 2090 1262 2090 1241 2091 1262 2091 1244 2091 1244 2092 1262 2092 1263 2092 1244 2093 1263 2093 1245 2093 1264 2094 1265 2094 415 2094 1266 2095 1267 2095 517 2095 517 2096 1267 2096 587 2096 1268 2097 422 2097 1269 2097 1269 2098 422 2098 423 2098 1269 2099 423 2099 1270 2099 1270 2100 423 2100 424 2100 483 2101 1271 2101 530 2101 530 2102 1271 2102 1272 2102 415 2103 1265 2103 410 2103 410 2104 1265 2104 1273 2104 410 2105 1273 2105 408 2105 408 2106 1273 2106 483 2106 483 2107 1273 2107 1274 2107 483 2108 1274 2108 1271 2108 517 2109 515 2109 1266 2109 1266 2110 515 2110 500 2110 1266 2111 500 2111 1275 2111 1275 2112 500 2112 519 2112 1275 2113 519 2113 1276 2113 1276 2114 519 2114 521 2114 1276 2115 521 2115 1277 2115 1277 2116 521 2116 523 2116 1277 2117 523 2117 1278 2117 1278 2118 523 2118 525 2118 1278 2119 525 2119 1279 2119 1279 2120 525 2120 527 2120 1279 2121 527 2121 1272 2121 1272 2122 527 2122 528 2122 1272 2123 528 2123 530 2123 415 2124 413 2124 1264 2124 1264 2125 413 2125 412 2125 1264 2126 412 2126 1280 2126 1280 2127 412 2127 390 2127 1280 2128 390 2128 1281 2128 1281 2129 390 2129 420 2129 1281 2130 420 2130 1282 2130 1267 2131 1283 2131 587 2131 587 2132 1283 2132 1284 2132 587 2133 1284 2133 506 2133 506 2134 1284 2134 1285 2134 1215 2135 374 2135 1213 2135 1213 2136 374 2136 373 2136 1213 2137 373 2137 1210 2137 373 2138 376 2138 1210 2138 1210 2139 376 2139 372 2139 1210 2140 372 2140 1211 2140 1211 73 372 73 371 73 420 2141 419 2141 1282 2141 1282 2142 419 2142 417 2142 1282 2143 417 2143 1286 2143 1286 2144 417 2144 387 2144 1286 2145 387 2145 1287 2145 1287 2146 387 2146 389 2146 1287 2147 389 2147 1288 2147 1288 2148 389 2148 449 2148 1288 2149 449 2149 1289 2149 1289 2150 449 2150 384 2150 1289 2151 384 2151 1290 2151 1290 2152 384 2152 386 2152 1290 2153 386 2153 1291 2153 1291 2154 386 2154 430 2154 1291 2155 430 2155 1268 2155 1268 2156 430 2156 429 2156 1268 2157 429 2157 422 2157 1285 2158 1292 2158 506 2158 506 2159 1292 2159 1293 2159 506 2160 1293 2160 507 2160 507 2161 1293 2161 509 2161 1215 2162 1294 2162 374 2162 374 2163 1294 2163 1295 2163 374 2164 1295 2164 424 2164 424 2165 1295 2165 1296 2165 424 2166 1296 2166 1270 2166 1293 2167 1297 2167 509 2167 509 2168 1297 2168 1298 2168 509 2169 1298 2169 511 2169 511 2170 1298 2170 1299 2170 511 2171 1299 2171 503 2171 503 2172 1299 2172 1300 2172 503 2173 1300 2173 504 2173 504 2174 1300 2174 1236 2174 504 2175 1236 2175 610 2175 610 2176 1236 2176 1238 2176 610 2177 1238 2177 611 2177 749 2178 722 2178 1243 2178 1243 73 722 73 721 73 1243 73 721 73 1261 73 1261 73 721 73 720 73 1261 73 720 73 1262 73 1262 73 720 73 719 73 1262 2179 719 2179 1263 2179 1263 73 719 73 718 73 1263 2180 718 2180 1245 2180 1245 73 718 73 611 73 1245 2181 611 2181 1240 2181 1240 2182 611 2182 1238 2182 749 2183 1301 2183 748 2183 726 2184 748 2184 723 2184 723 2185 748 2185 1302 2185 723 2186 1302 2186 724 2186 724 2187 1302 2187 1303 2187 724 73 1303 73 742 73 1304 2188 912 2188 910 2188 1304 2189 910 2189 1305 2189 1303 2190 1306 2190 742 2190 742 73 1306 73 1307 73 742 2191 1307 2191 896 2191 896 73 1307 73 1308 73 896 2192 1308 2192 897 2192 897 73 1308 73 1309 73 897 73 1309 73 916 73 916 2193 1309 2193 1310 2193 916 73 1310 73 899 73 899 73 1310 73 1311 73 899 2194 1311 2194 900 2194 900 2195 1311 2195 1312 2195 900 73 1312 73 913 73 913 73 1312 73 1313 73 913 2196 1313 2196 914 2196 914 73 1313 73 1314 73 914 73 1314 73 915 73 915 73 1314 73 1305 73 915 2197 1305 2197 909 2197 909 73 1305 73 910 73 1315 2198 1316 2198 1317 2198 1317 2199 1316 2199 1318 2199 1306 2200 1303 2200 1319 2200 1319 2201 1303 2201 1320 2201 1321 2202 1322 2202 1320 2202 1320 2203 1322 2203 1323 2203 1320 2204 1323 2204 1319 2204 1318 2205 1324 2205 1317 2205 1317 2206 1324 2206 1325 2206 1317 2207 1325 2207 1326 2207 1326 2208 1325 2208 1327 2208 1326 2209 1327 2209 1328 2209 1328 2210 1327 2210 1329 2210 1328 2211 1329 2211 1321 2211 1321 2212 1329 2212 1330 2212 1321 2213 1330 2213 1322 2213 945 2214 1331 2214 1332 2214 1333 2215 1334 2215 1335 2215 1333 2216 1335 2216 1336 2216 1336 2217 1335 2217 1337 2217 1336 2218 1337 2218 1338 2218 1338 2219 1337 2219 1332 2219 1338 2220 1332 2220 1339 2220 1339 2221 1332 2221 1331 2221 1339 2222 1331 2222 1340 2222 945 2223 1332 2223 944 2223 944 2224 1332 2224 1337 2224 944 2225 1337 2225 943 2225 943 2226 1337 2226 1335 2226 943 2227 1335 2227 942 2227 942 2228 1335 2228 1334 2228 942 2229 1334 2229 941 2229 1341 2230 1153 2230 1342 2230 1342 2231 1153 2231 1152 2231 1342 2232 1152 2232 1343 2232 759 2233 758 2233 1150 2233 1150 2234 758 2234 855 2234 855 2235 856 2235 1150 2235 1150 2236 856 2236 1344 2236 1150 2237 1344 2237 836 2237 836 2238 829 2238 1150 2238 1150 2239 829 2239 828 2239 1150 2240 828 2240 842 2240 1343 2241 1152 2241 1345 2241 1345 2242 1152 2242 1150 2242 1345 2243 1150 2243 1346 2243 1347 2244 1348 2244 1346 2244 1346 2245 1348 2245 1349 2245 1349 2246 1350 2246 1346 2246 1346 2247 1350 2247 1351 2247 1346 2248 1351 2248 1345 2248 842 2249 1352 2249 1150 2249 1150 2250 1352 2250 1353 2250 1150 2251 1353 2251 1346 2251 1346 2252 1353 2252 1354 2252 1346 2253 1354 2253 1347 2253 1355 2254 1356 2254 1357 2254 1357 2255 1356 2255 1358 2255 1356 2256 796 2256 1358 2256 1358 2257 796 2257 798 2257 1358 2258 798 2258 1359 2258 1359 2259 798 2259 800 2259 1359 2260 800 2260 802 2260 802 2261 804 2261 1359 2261 1359 2262 804 2262 806 2262 1359 2263 806 2263 1110 2263 1110 2264 806 2264 808 2264 1110 2265 808 2265 1111 2265 1111 2266 808 2266 810 2266 810 2267 770 2267 1111 2267 1111 2268 770 2268 768 2268 1111 2269 768 2269 766 2269 1150 2270 1148 2270 759 2270 759 2271 1148 2271 1146 2271 759 2272 1146 2272 762 2272 762 2273 1146 2273 1111 2273 762 2274 1111 2274 764 2274 764 2275 1111 2275 766 2275 1341 2276 1360 2276 1153 2276 1153 2277 1360 2277 1361 2277 1153 2278 1361 2278 1143 2278 1143 2279 1361 2279 1362 2279 1143 2280 1362 2280 1142 2280 1142 2281 1362 2281 1363 2281 1142 2282 1363 2282 1108 2282 1108 2283 1363 2283 1107 2283 1107 2284 1363 2284 1364 2284 1107 2285 1364 2285 1106 2285 1106 2286 1364 2286 1365 2286 1106 2287 1365 2287 1105 2287 1365 2288 1366 2288 1105 2288 1105 2289 1366 2289 1367 2289 1105 2290 1367 2290 1368 2290 1368 2291 1369 2291 1105 2291 1105 2292 1369 2292 1370 2292 1105 2293 1370 2293 1104 2293 1371 2294 1372 2294 1103 2294 1104 2295 1370 2295 1103 2295 1103 2296 1370 2296 1373 2296 1103 2297 1373 2297 1371 2297 1372 2298 1374 2298 1103 2298 1103 2299 1374 2299 1375 2299 1103 2300 1375 2300 1376 2300 938 2301 1377 2301 1103 2301 1103 2302 1377 2302 947 2302 1103 2303 947 2303 946 2303 1376 2304 1340 2304 1103 2304 1103 2305 1340 2305 1331 2305 1103 2306 1331 2306 945 2306 945 2307 936 2307 1103 2307 1103 2308 936 2308 937 2308 1103 2309 937 2309 938 2309 1100 2310 1101 2310 1019 2310 1019 2311 1101 2311 1018 2311 946 2312 956 2312 1103 2312 1103 2313 956 2313 1018 2313 1103 2314 1018 2314 1102 2314 1102 2315 1018 2315 1101 2315 1019 2316 1020 2316 1100 2316 1100 2317 1020 2317 1021 2317 1100 2318 1021 2318 1022 2318 1022 2319 1023 2319 1100 2319 1100 2320 1023 2320 1024 2320 1100 2321 1024 2321 1099 2321 1099 2322 1024 2322 1025 2322 1099 2323 1025 2323 1378 2323 1378 2324 1025 2324 1026 2324 1378 2325 1026 2325 1027 2325 1030 2326 1379 2326 1029 2326 1029 2327 1379 2327 1378 2327 1029 2328 1378 2328 1028 2328 1028 2329 1378 2329 1027 2329 1030 2330 1031 2330 1379 2330 1379 2331 1031 2331 1380 2331 1379 2332 1380 2332 1381 2332 1381 2333 1380 2333 1382 2333 846 2334 1383 2334 1384 2334 1353 2335 1352 2335 1385 2335 1353 2336 1385 2336 1386 2336 1386 2337 1385 2337 1387 2337 1386 2338 1387 2338 1388 2338 1388 2339 1387 2339 1384 2339 1388 2340 1384 2340 1389 2340 1389 2341 1384 2341 1383 2341 1389 2342 1383 2342 1390 2342 846 2343 1384 2343 845 2343 845 2344 1384 2344 1387 2344 845 2345 1387 2345 844 2345 844 2346 1387 2346 1385 2346 844 2347 1385 2347 843 2347 843 2348 1385 2348 1352 2348 843 2349 1352 2349 842 2349 1391 2350 1392 2350 1393 2350 1394 2351 1395 2351 1396 2351 1397 2352 1398 2352 1399 2352 1399 2353 1398 2353 1393 2353 1391 2354 1393 2354 1396 2354 1396 2355 1393 2355 1398 2355 1396 2356 1398 2356 1394 2356 1394 2357 1398 2357 1397 2357 1394 2358 1397 2358 1355 2358 1400 2359 1401 2359 826 2359 826 2360 752 2360 1400 2360 1400 2361 752 2361 751 2361 1400 2362 751 2362 1356 2362 1356 2363 751 2363 811 2363 1356 2364 811 2364 796 2364 1399 2365 1401 2365 1397 2365 1397 2366 1401 2366 1400 2366 1397 2367 1400 2367 1355 2367 1355 2368 1400 2368 1356 2368 794 2369 793 2369 1402 2369 1402 2370 793 2370 822 2370 1402 2371 822 2371 823 2371 823 2372 824 2372 1402 2372 1402 2373 824 2373 825 2373 1402 2374 825 2374 826 2374 1402 2375 1403 2375 794 2375 794 2376 1403 2376 1404 2376 794 2377 1404 2377 795 2377 795 2378 1404 2378 785 2378 789 2379 788 2379 1405 2379 1405 2380 788 2380 787 2380 1405 2381 787 2381 1404 2381 1404 2382 787 2382 786 2382 1404 2383 786 2383 785 2383 791 2384 790 2384 1406 2384 1406 2385 790 2385 789 2385 1406 2386 789 2386 1407 2386 1407 2387 789 2387 1405 2387 1407 2388 1405 2388 1408 2388 1408 2389 1405 2389 1404 2389 1408 2390 1404 2390 1409 2390 1409 2391 1404 2391 1403 2391 1409 2392 1410 2392 1408 2392 1408 2393 1410 2393 1411 2393 1408 2394 1411 2394 1407 2394 1407 2395 1411 2395 1412 2395 1407 2396 1412 2396 1406 2396 1406 2397 1412 2397 1413 2397 1406 2398 1413 2398 791 2398 791 2399 1413 2399 1414 2399 791 2400 1414 2400 792 2400 1344 2401 856 2401 1415 2401 1415 2402 856 2402 854 2402 1415 2403 854 2403 1416 2403 1416 2404 854 2404 852 2404 1416 2405 852 2405 1417 2405 1417 2406 852 2406 850 2406 1417 2407 850 2407 1418 2407 1418 2408 850 2408 848 2408 836 2409 1344 2409 834 2409 834 2410 1344 2410 1415 2410 834 2411 1415 2411 832 2411 832 2412 1415 2412 1416 2412 832 2413 1416 2413 830 2413 830 2414 1416 2414 1417 2414 830 2415 1417 2415 839 2415 839 2416 1417 2416 1418 2416 838 2417 839 2417 1419 2417 838 2418 1419 2418 837 2418 837 2419 1419 2419 1420 2419 837 2420 1420 2420 846 2420 847 2421 792 2421 1421 2421 1421 2422 792 2422 1414 2422 1421 2423 1414 2423 1422 2423 1422 2424 1414 2424 1413 2424 1422 2425 1413 2425 1423 2425 1423 2426 1413 2426 1412 2426 1423 2427 1412 2427 1424 2427 1424 2428 1412 2428 1411 2428 1424 2429 1411 2429 1425 2429 1425 2430 1411 2430 1410 2430 848 2431 847 2431 1426 2431 1426 2432 847 2432 1421 2432 1426 2433 1421 2433 1427 2433 1427 2434 1421 2434 1422 2434 1427 2435 1422 2435 1428 2435 1428 2436 1422 2436 1423 2436 1428 2437 1423 2437 1429 2437 1429 2438 1423 2438 1424 2438 1429 2439 1424 2439 1430 2439 1430 2440 1424 2440 1425 2440 1431 2441 871 2441 1432 2441 1432 2442 871 2442 870 2442 1432 1296 870 1296 1433 1296 873 2443 871 2443 1434 2443 876 2444 877 2444 1435 2444 1436 2445 860 2445 859 2445 876 2446 1435 2446 875 2446 875 2447 1435 2447 1436 2447 875 2448 1436 2448 874 2448 874 2449 1436 2449 859 2449 874 2450 859 2450 858 2450 1437 2451 1438 2451 877 2451 877 2452 1438 2452 1439 2452 877 2453 1439 2453 1435 2453 877 2454 878 2454 1437 2454 1437 2455 878 2455 879 2455 1437 2456 879 2456 1434 2456 1434 2457 879 2457 880 2457 1434 2458 880 2458 873 2458 1234 2459 861 2459 860 2459 860 2460 1436 2460 1234 2460 1234 2461 1436 2461 1435 2461 1234 2462 1435 2462 1439 2462 1433 73 870 73 1440 73 1440 73 870 73 872 73 1440 2463 872 2463 1441 2463 1441 73 872 73 28 73 1441 73 28 73 27 73 1442 2464 882 2464 1443 2464 1443 2465 882 2465 881 2465 881 2466 883 2466 1443 2466 1443 2467 883 2467 885 2467 885 2468 902 2468 1443 2468 1443 2469 902 2469 1444 2469 1443 2470 1444 2470 1445 2470 1445 2471 1444 2471 1446 2471 1445 2472 1446 2472 1447 2472 1446 2473 1448 2473 1447 2473 1447 2474 1448 2474 1449 2474 1447 2475 1449 2475 1450 2475 1449 2476 1451 2476 1450 2476 1450 2477 1451 2477 1452 2477 1450 2478 1452 2478 1453 2478 882 2479 1442 2479 1454 2479 886 2480 883 2480 882 2480 18 2481 886 2481 55 2481 886 2479 882 2479 55 2479 55 2482 882 2482 1454 2482 55 2483 1454 2483 58 2483 18 2484 55 2484 16 2484 16 2485 55 2485 53 2485 16 2486 53 2486 11 2486 1316 73 1455 73 1318 73 1318 2487 1455 2487 1456 2487 1318 2488 1456 2488 1324 2488 1324 73 1456 73 1457 73 1309 2489 1308 2489 1458 2489 1307 2490 1306 2490 1319 2490 1324 2491 1457 2491 1459 2491 1330 2492 1329 2492 1460 2492 1460 2493 1329 2493 1327 2493 1460 2494 1327 2494 1461 2494 1461 2495 1327 2495 1325 2495 1461 2496 1325 2496 1462 2496 1330 2497 1460 2497 1322 2497 1322 2498 1460 2498 1463 2498 1322 2499 1463 2499 1323 2499 1323 2500 1463 2500 1458 2500 1323 2501 1458 2501 1319 2501 1319 2502 1458 2502 1308 2502 1319 2503 1308 2503 1307 2503 1464 2504 1310 2504 1309 2504 1313 2505 1312 2505 1464 2505 1464 2506 1312 2506 1311 2506 1464 2507 1311 2507 1310 2507 1305 2508 1314 2508 1465 2508 1465 2509 1314 2509 1313 2509 902 2510 912 2510 1444 2510 1444 2511 912 2511 1304 2511 1444 2512 1304 2512 1305 2512 1305 2513 1465 2513 1444 2513 1444 2514 1465 2514 1466 2514 1444 2515 1466 2515 1446 2515 1446 2516 1466 2516 1448 2516 1448 2517 1466 2517 1467 2517 1448 2518 1467 2518 1449 2518 1449 2519 1467 2519 1468 2519 1449 2520 1468 2520 1451 2520 1451 2521 1468 2521 1469 2521 1451 2522 1469 2522 1452 2522 1470 2523 1471 2523 1472 2523 1324 2524 1459 2524 1325 2524 1325 2525 1459 2525 1473 2525 1325 2526 1473 2526 1462 2526 1462 2527 1473 2527 1474 2527 1462 2528 1474 2528 1475 2528 1313 2529 1464 2529 1465 2529 1465 2530 1464 2530 1476 2530 1465 2531 1476 2531 1466 2531 1466 2532 1476 2532 1477 2532 1466 2533 1477 2533 1467 2533 1467 2534 1477 2534 1470 2534 1467 2535 1470 2535 1468 2535 1468 2536 1470 2536 1472 2536 1468 2537 1472 2537 1469 2537 1309 2538 1458 2538 1464 2538 1464 2539 1458 2539 1463 2539 1464 2540 1463 2540 1476 2540 1476 2541 1463 2541 1460 2541 1476 2542 1460 2542 1477 2542 1477 2543 1460 2543 1461 2543 1477 2544 1461 2544 1470 2544 1470 2545 1461 2545 1462 2545 1470 2546 1462 2546 1471 2546 1471 2547 1462 2547 1475 2547 1471 2548 1475 2548 1472 2548 941 2549 1478 2549 927 2549 927 2550 1478 2550 1479 2550 927 2551 1479 2551 928 2551 928 2552 1479 2552 935 2552 1480 2553 955 2553 1481 2553 1481 2554 955 2554 953 2554 1481 2555 953 2555 1482 2555 1482 2556 953 2556 951 2556 1482 2557 951 2557 1483 2557 1483 2558 951 2558 949 2558 1483 2559 949 2559 1377 2559 1377 2560 949 2560 947 2560 935 2561 1480 2561 933 2561 933 2562 1480 2562 1481 2562 933 2563 1481 2563 931 2563 931 2564 1481 2564 1482 2564 931 2565 1482 2565 929 2565 929 2566 1482 2566 1483 2566 929 2567 1483 2567 938 2567 938 2568 1483 2568 1377 2568 954 2569 955 2569 1484 2569 1485 2570 1486 2570 1487 2570 1487 2571 1486 2571 1488 2571 1487 2572 1488 2572 960 2572 1489 2573 1490 2573 1485 2573 1485 2574 1490 2574 1491 2574 1485 2575 1491 2575 1486 2575 1492 2576 1493 2576 1494 2576 1494 2577 1493 2577 1495 2577 1494 2578 1495 2578 1489 2578 1489 2579 1495 2579 1496 2579 1489 2580 1496 2580 1490 2580 1497 2581 1492 2581 1498 2581 1498 2582 1492 2582 1494 2582 1498 2583 1494 2583 1499 2583 1499 2584 1494 2584 1489 2584 1499 2585 1489 2585 1500 2585 1500 2586 1489 2586 1485 2586 1500 2587 1485 2587 1484 2587 1484 2588 1485 2588 1487 2588 1484 2589 1487 2589 954 2589 954 2590 1487 2590 960 2590 1501 2591 1502 2591 1503 2591 968 2592 966 2592 1504 2592 1504 2593 966 2593 964 2593 960 2594 1488 2594 964 2594 964 2595 1488 2595 1486 2595 964 2596 1486 2596 1504 2596 980 2597 978 2597 1505 2597 1505 2598 978 2598 976 2598 1505 2599 976 2599 974 2599 985 2600 983 2600 1506 2600 987 2601 985 2601 989 2601 989 2602 985 2602 1506 2602 989 2603 1506 2603 991 2603 1507 2604 1505 2604 1508 2604 1508 2605 1505 2605 974 2605 1508 2606 974 2606 972 2606 1507 2607 1501 2607 1505 2607 1505 2608 1501 2608 1503 2608 1505 2609 1503 2609 980 2609 980 2610 1503 2610 1506 2610 980 2611 1506 2611 982 2611 982 2612 1506 2612 983 2612 1486 2613 1491 2613 1504 2613 1504 2614 1491 2614 1507 2614 1504 2615 1507 2615 968 2615 968 2616 1507 2616 1508 2616 968 2617 1508 2617 970 2617 970 2618 1508 2618 972 2618 1493 2619 1502 2619 1495 2619 1495 2620 1502 2620 1501 2620 1495 2621 1501 2621 1496 2621 1496 2622 1501 2622 1507 2622 1496 2623 1507 2623 1490 2623 1490 2624 1507 2624 1491 2624 991 2625 1509 2625 992 2625 992 2626 1509 2626 1510 2626 992 2627 1510 2627 961 2627 961 2628 1510 2628 962 2628 962 2629 1510 2629 1380 2629 962 2630 1380 2630 1031 2630 1382 2631 1380 2631 1511 2631 1511 2632 1380 2632 1510 2632 1511 2633 1510 2633 1512 2633 1512 2634 1510 2634 1509 2634 1513 2635 1514 2635 1515 2635 1515 2636 1514 2636 1516 2636 1516 2637 1514 2637 1517 2637 1517 2638 1514 2638 1518 2638 1517 2639 1518 2639 1519 2639 1512 2640 1518 2640 1511 2640 1511 2641 1518 2641 1514 2641 1511 2642 1514 2642 1382 2642 1382 2643 1514 2643 1513 2643 1520 2644 1521 2644 1522 2644 1519 2645 1523 2645 1517 2645 1517 2646 1523 2646 1516 2646 1521 2647 1520 2647 1524 2647 1520 2648 1525 2648 1524 2648 1524 2649 1525 2649 1526 2649 1524 2650 1526 2650 1527 2650 1527 2651 1526 2651 1528 2651 1527 2652 1528 2652 1523 2652 1523 2653 1528 2653 1515 2653 1523 2654 1515 2654 1516 2654 1525 2655 1520 2655 1529 2655 1515 2656 1528 2656 1530 2656 1530 2657 1528 2657 1531 2657 1531 2658 1528 2658 1529 2658 1529 2659 1528 2659 1526 2659 1529 2660 1526 2660 1525 2660 1060 2661 1099 2661 1378 2661 1063 2662 1061 2662 1532 2662 1532 2663 1061 2663 1060 2663 1533 2664 1054 2664 1053 2664 1059 2665 1534 2665 1086 2665 1057 2666 1056 2666 1533 2666 1533 2667 1056 2667 1054 2667 1535 2668 1531 2668 1536 2668 1513 2669 1515 2669 1537 2669 1537 2670 1515 2670 1530 2670 1537 2671 1530 2671 1531 2671 1060 2672 1378 2672 1532 2672 1532 2673 1378 2673 1379 2673 1532 2674 1379 2674 1538 2674 1538 2675 1379 2675 1381 2675 1538 2676 1381 2676 1537 2676 1537 2677 1381 2677 1382 2677 1537 2678 1382 2678 1513 2678 1531 2679 1535 2679 1537 2679 1537 2680 1535 2680 1539 2680 1537 2681 1539 2681 1538 2681 1538 2682 1539 2682 1533 2682 1538 2683 1533 2683 1532 2683 1532 2684 1533 2684 1053 2684 1532 2685 1053 2685 1063 2685 1536 2686 1540 2686 1535 2686 1535 2687 1540 2687 1541 2687 1535 2688 1541 2688 1539 2688 1539 2689 1541 2689 1534 2689 1539 2690 1534 2690 1533 2690 1533 2691 1534 2691 1059 2691 1533 2692 1059 2692 1057 2692 1542 2693 1543 2693 1544 2693 1545 2694 1546 2694 1543 2694 1547 2695 1548 2695 1549 2695 1549 2696 1548 2696 1550 2696 1549 2697 1550 2697 1551 2697 1543 2698 1546 2698 1549 2698 1549 2699 1546 2699 1552 2699 1549 2700 1552 2700 1547 2700 1542 2701 1553 2701 1543 2701 1543 2702 1553 2702 1554 2702 1543 2703 1554 2703 1545 2703 1544 2704 1543 2704 1555 2704 1555 2705 1543 2705 1549 2705 1555 2706 1549 2706 1556 2706 1556 2707 1549 2707 1551 2707 1556 2708 1551 2708 1557 2708 1553 2709 1558 2709 1554 2709 1554 2710 1558 2710 1545 2710 1545 2711 1559 2711 1546 2711 1546 2712 1559 2712 1560 2712 1546 2713 1560 2713 1552 2713 1560 2714 1561 2714 1552 2714 1552 2715 1561 2715 1562 2715 1552 2716 1562 2716 1547 2716 1563 2717 1564 2717 1565 2717 1564 2718 1563 2718 1566 2718 1567 2719 1035 2719 1205 2719 1189 2720 1188 2720 1568 2720 1569 2721 1570 2721 1571 2721 1567 2722 1205 2722 1572 2722 1573 2723 1566 2723 1574 2723 1574 2724 1566 2724 1563 2724 1574 2725 1563 2725 1553 2725 1553 2726 1563 2726 1558 2726 1561 2727 1560 2727 1563 2727 1561 2728 1563 2728 1562 2728 1560 2729 1559 2729 1563 2729 1563 2730 1559 2730 1545 2730 1563 2731 1545 2731 1558 2731 1548 2732 1547 2732 1575 2732 1576 2733 1550 2733 1577 2733 1577 2734 1550 2734 1548 2734 1577 2735 1548 2735 1578 2735 1578 2736 1548 2736 1575 2736 1579 2737 1576 2737 1580 2737 1580 2738 1576 2738 1577 2738 1580 2739 1577 2739 1581 2739 1581 2740 1577 2740 1578 2740 1581 2741 1578 2741 1565 2741 1565 2742 1578 2742 1575 2742 1565 2743 1575 2743 1563 2743 1563 2744 1575 2744 1547 2744 1563 2745 1547 2745 1562 2745 1568 2746 1582 2746 1189 2746 1189 2747 1582 2747 1583 2747 1189 2748 1583 2748 1206 2748 1206 2749 1583 2749 1584 2749 1206 2750 1584 2750 1205 2750 1205 2751 1584 2751 1569 2751 1205 2752 1569 2752 1572 2752 1572 2753 1569 2753 1571 2753 1568 2754 1579 2754 1582 2754 1582 2755 1579 2755 1580 2755 1582 2756 1580 2756 1583 2756 1583 2757 1580 2757 1581 2757 1583 2758 1581 2758 1584 2758 1584 2759 1581 2759 1565 2759 1584 2760 1565 2760 1569 2760 1569 2761 1565 2761 1564 2761 1569 2762 1564 2762 1570 2762 1570 2763 1564 2763 1566 2763 1585 2764 1586 2764 1587 2764 1588 2765 1589 2765 1590 2765 1591 2766 1592 2766 1593 2766 1566 2767 1573 2767 1594 2767 1595 2768 1570 2768 1596 2768 1596 2769 1570 2769 1566 2769 1596 2770 1566 2770 1597 2770 1597 2771 1566 2771 1594 2771 1597 2772 1594 2772 1598 2772 1599 2773 1572 2773 1595 2773 1595 2774 1572 2774 1571 2774 1595 2775 1571 2775 1570 2775 1567 2776 1600 2776 1035 2776 1035 2777 1600 2777 1601 2777 1035 2778 1601 2778 1036 2778 1036 2779 1601 2779 1038 2779 1040 2780 1602 2780 1042 2780 1042 2781 1602 2781 1603 2781 1042 2782 1603 2782 1044 2782 1044 2783 1603 2783 1604 2783 1044 2784 1604 2784 1045 2784 1588 2785 1590 2785 1605 2785 1606 2786 1607 2786 1608 2786 1608 2787 1609 2787 1606 2787 1606 2788 1609 2788 1610 2788 1606 2789 1610 2789 1611 2789 1612 2790 1613 2790 1614 2790 1614 2791 1613 2791 1615 2791 1614 2792 1615 2792 1606 2792 1606 2793 1615 2793 1616 2793 1606 2794 1616 2794 1607 2794 1617 2795 1618 2795 1619 2795 1620 2796 1621 2796 1622 2796 1622 2797 1621 2797 1623 2797 1622 2798 1623 2798 1624 2798 1624 2799 1623 2799 1612 2799 1624 2800 1612 2800 1625 2800 1625 2801 1612 2801 1614 2801 1625 2802 1614 2802 1626 2802 1626 2803 1614 2803 1606 2803 1626 2804 1606 2804 1586 2804 1586 2805 1606 2805 1611 2805 1586 2806 1611 2806 1587 2806 1567 2807 1572 2807 1600 2807 1600 2808 1572 2808 1599 2808 1600 2809 1599 2809 1601 2809 1601 2810 1599 2810 1627 2810 1601 2811 1627 2811 1038 2811 1038 2812 1627 2812 1628 2812 1038 2813 1628 2813 1040 2813 1040 2814 1628 2814 1629 2814 1040 2815 1629 2815 1602 2815 1587 2816 1605 2816 1585 2816 1585 2817 1605 2817 1590 2817 1585 2818 1590 2818 1586 2818 1586 2819 1590 2819 1630 2819 1586 2820 1630 2820 1626 2820 1626 2821 1630 2821 1631 2821 1626 2822 1631 2822 1625 2822 1625 2823 1631 2823 1632 2823 1625 2824 1632 2824 1624 2824 1624 2825 1632 2825 1633 2825 1624 2826 1633 2826 1622 2826 1622 2827 1633 2827 1634 2827 1622 2828 1634 2828 1620 2828 1620 2829 1634 2829 1635 2829 1620 2830 1635 2830 1636 2830 1636 2831 1635 2831 1617 2831 1636 2832 1617 2832 1637 2832 1637 2833 1617 2833 1619 2833 1589 2834 1591 2834 1590 2834 1590 2835 1591 2835 1593 2835 1590 2836 1593 2836 1630 2836 1630 2837 1593 2837 1638 2837 1630 2838 1638 2838 1631 2838 1631 2839 1638 2839 1639 2839 1631 2840 1639 2840 1632 2840 1632 2841 1639 2841 1640 2841 1632 2842 1640 2842 1633 2842 1633 2843 1640 2843 1641 2843 1633 2844 1641 2844 1634 2844 1634 2845 1641 2845 1642 2845 1634 2846 1642 2846 1635 2846 1635 2847 1642 2847 1643 2847 1635 2848 1643 2848 1617 2848 1617 2849 1643 2849 1644 2849 1617 2850 1644 2850 1618 2850 1618 2851 1644 2851 1645 2851 1618 2852 1645 2852 1646 2852 1646 2853 1645 2853 1647 2853 1592 2854 1604 2854 1593 2854 1593 2855 1604 2855 1603 2855 1593 2856 1603 2856 1638 2856 1638 2857 1603 2857 1602 2857 1638 2858 1602 2858 1639 2858 1639 2859 1602 2859 1629 2859 1639 2860 1629 2860 1640 2860 1640 2861 1629 2861 1628 2861 1640 2862 1628 2862 1641 2862 1641 2863 1628 2863 1627 2863 1641 2864 1627 2864 1642 2864 1642 2865 1627 2865 1599 2865 1642 2866 1599 2866 1643 2866 1643 2867 1599 2867 1595 2867 1643 2868 1595 2868 1644 2868 1644 2869 1595 2869 1596 2869 1644 2870 1596 2870 1645 2870 1645 2871 1596 2871 1597 2871 1645 2872 1597 2872 1647 2872 1647 2873 1597 2873 1598 2873 1616 2874 1615 2874 1648 2874 1649 2875 1609 2875 1608 2875 1649 2876 1608 2876 1648 2876 1648 2877 1608 2877 1607 2877 1648 2878 1607 2878 1616 2878 1609 2879 1649 2879 1650 2879 1650 2880 1649 2880 1651 2880 1652 2881 1653 2881 1651 2881 1651 2882 1653 2882 1654 2882 1651 2883 1654 2883 1650 2883 1655 2884 1656 2884 1657 2884 1658 2885 1659 2885 1660 2885 1591 2886 1589 2886 1661 2886 1609 2887 1650 2887 1610 2887 1610 2888 1650 2888 1662 2888 1610 2889 1662 2889 1611 2889 1588 2890 1605 2890 1663 2890 1663 2891 1605 2891 1587 2891 1611 2892 1662 2892 1587 2892 1587 2893 1662 2893 1664 2893 1587 2894 1664 2894 1663 2894 1046 2895 1045 2895 1604 2895 1604 2896 1665 2896 1046 2896 1046 2897 1665 2897 1666 2897 1046 2898 1666 2898 1048 2898 1048 2899 1666 2899 1667 2899 1048 2900 1667 2900 1050 2900 1050 2901 1667 2901 1051 2901 1051 2902 1667 2902 1668 2902 1051 2903 1668 2903 1052 2903 1669 2904 1670 2904 1671 2904 1671 2905 1670 2905 1033 2905 1671 2906 1033 2906 1672 2906 1672 2907 1033 2907 1032 2907 1672 2908 1032 2908 1052 2908 1669 2909 1673 2909 1674 2909 1674 2910 1673 2910 1675 2910 1674 2911 1675 2911 1660 2911 1660 2912 1675 2912 1676 2912 1660 2913 1676 2913 1658 2913 1677 2914 1678 2914 1679 2914 1679 2915 1678 2915 1680 2915 1681 2916 1682 2916 1683 2916 1683 2917 1682 2917 1684 2917 1683 2918 1684 2918 1685 2918 1650 2919 1654 2919 1662 2919 1662 2920 1654 2920 1653 2920 1662 2921 1653 2921 1657 2921 1657 2922 1653 2922 1652 2922 1657 2923 1652 2923 1655 2923 1681 2924 1683 2924 1656 2924 1656 2925 1683 2925 1686 2925 1656 2926 1686 2926 1657 2926 1657 2927 1686 2927 1687 2927 1657 2928 1687 2928 1662 2928 1662 2929 1687 2929 1688 2929 1662 2930 1688 2930 1664 2930 1052 2931 1668 2931 1672 2931 1672 2932 1668 2932 1689 2932 1672 2933 1689 2933 1671 2933 1671 2934 1689 2934 1690 2934 1671 2935 1690 2935 1669 2935 1669 2936 1690 2936 1691 2936 1669 2937 1691 2937 1673 2937 1589 2938 1588 2938 1661 2938 1661 2939 1588 2939 1663 2939 1661 2940 1663 2940 1692 2940 1692 2941 1663 2941 1664 2941 1692 2942 1664 2942 1693 2942 1693 2943 1664 2943 1688 2943 1693 2944 1688 2944 1694 2944 1694 2945 1688 2945 1687 2945 1694 2946 1687 2946 1695 2946 1695 2947 1687 2947 1686 2947 1695 2948 1686 2948 1696 2948 1696 2949 1686 2949 1683 2949 1696 2950 1683 2950 1697 2950 1697 2951 1683 2951 1685 2951 1697 2952 1685 2952 1698 2952 1698 2953 1685 2953 1699 2953 1698 2954 1699 2954 1700 2954 1592 2955 1591 2955 1701 2955 1701 2956 1591 2956 1661 2956 1701 2957 1661 2957 1702 2957 1702 2958 1661 2958 1692 2958 1702 2959 1692 2959 1703 2959 1703 2960 1692 2960 1693 2960 1703 2961 1693 2961 1704 2961 1704 2962 1693 2962 1694 2962 1704 2963 1694 2963 1705 2963 1705 2964 1694 2964 1695 2964 1705 2965 1695 2965 1706 2965 1706 2966 1695 2966 1696 2966 1706 2967 1696 2967 1707 2967 1707 2968 1696 2968 1697 2968 1707 2969 1697 2969 1677 2969 1677 2970 1697 2970 1698 2970 1677 2971 1698 2971 1678 2971 1678 2972 1698 2972 1700 2972 1604 2973 1592 2973 1665 2973 1665 2974 1592 2974 1701 2974 1665 2975 1701 2975 1666 2975 1666 2976 1701 2976 1702 2976 1666 2977 1702 2977 1667 2977 1667 2978 1702 2978 1703 2978 1667 2979 1703 2979 1668 2979 1668 2980 1703 2980 1704 2980 1668 2981 1704 2981 1689 2981 1689 2982 1704 2982 1705 2982 1689 2983 1705 2983 1690 2983 1690 2984 1705 2984 1706 2984 1690 2985 1706 2985 1691 2985 1691 2986 1706 2986 1707 2986 1691 2987 1707 2987 1673 2987 1673 2988 1707 2988 1677 2988 1673 2989 1677 2989 1675 2989 1675 2990 1677 2990 1679 2990 1675 2991 1679 2991 1676 2991 1676 2992 1679 2992 1680 2992 1708 2993 1709 2993 1710 2993 1711 2994 1712 2994 1713 2994 1713 2995 1712 2995 1714 2995 1713 2996 1714 2996 1715 2996 1715 2997 1714 2997 1716 2997 1717 2998 1718 2998 1719 2998 1719 2999 1718 2999 1720 2999 1720 3000 1721 3000 1719 3000 1719 3001 1721 3001 1722 3001 1719 3002 1722 3002 1723 3002 1724 3003 1717 3003 1725 3003 1725 3004 1717 3004 1719 3004 1725 3005 1719 3005 1659 3005 1659 3006 1719 3006 1660 3006 1726 3007 1727 3007 1674 3007 1674 3008 1727 3008 1669 3008 1669 3009 1727 3009 1670 3009 1670 3010 1727 3010 1180 3010 1670 3011 1180 3011 1033 3011 1674 3012 1660 3012 1726 3012 1726 3013 1660 3013 1719 3013 1726 3014 1719 3014 1711 3014 1711 3015 1719 3015 1723 3015 1711 3016 1723 3016 1712 3016 1728 3017 1184 3017 1729 3017 1729 3018 1184 3018 1183 3018 1729 3019 1183 3019 1730 3019 1730 3020 1183 3020 1181 3020 1730 3021 1181 3021 1731 3021 1709 3022 1728 3022 1710 3022 1710 3023 1728 3023 1729 3023 1710 3024 1729 3024 1732 3024 1732 3025 1729 3025 1730 3025 1732 3026 1730 3026 1733 3026 1733 3027 1730 3027 1731 3027 1716 3028 1708 3028 1715 3028 1715 3029 1708 3029 1710 3029 1715 3030 1710 3030 1713 3030 1713 3031 1710 3031 1732 3031 1713 3032 1732 3032 1711 3032 1711 3033 1732 3033 1733 3033 1711 3034 1733 3034 1726 3034 1726 3035 1733 3035 1731 3035 1726 3036 1731 3036 1727 3036 1727 3037 1731 3037 1181 3037 1727 3038 1181 3038 1180 3038 1712 3039 1723 3039 1734 3039 1717 3040 1724 3040 1735 3040 1717 3041 1735 3041 1718 3041 1720 3042 1718 3042 1736 3042 1720 3043 1736 3043 1721 3043 1721 3044 1736 3044 1734 3044 1721 3045 1734 3045 1722 3045 1722 3046 1734 3046 1723 3046 1737 3047 1738 3047 1739 3047 1739 3048 1738 3048 1740 3048 1718 3049 1735 3049 1738 3049 1738 3050 1735 3050 1724 3050 1738 3051 1724 3051 1740 3051 1714 3052 1712 3052 1737 3052 1737 3053 1712 3053 1734 3053 1737 3054 1734 3054 1738 3054 1738 3055 1734 3055 1736 3055 1738 3056 1736 3056 1718 3056 1739 3057 1741 3057 1737 3057 1737 3058 1741 3058 1742 3058 1737 3059 1742 3059 1714 3059 1714 3060 1742 3060 1716 3060 1576 3061 1086 3061 1550 3061 1550 3062 1086 3062 1534 3062 1550 3063 1534 3063 1551 3063 1074 3064 1072 3064 1188 3064 1188 3065 1072 3065 1071 3065 1188 3066 1071 3066 1568 3066 1568 3067 1071 3067 1082 3067 1568 3068 1082 3068 1579 3068 1579 3069 1082 3069 1084 3069 1579 3070 1084 3070 1576 3070 1576 3071 1084 3071 1085 3071 1576 3072 1085 3072 1086 3072 1188 3073 1187 3073 1074 3073 1074 3074 1187 3074 1191 3074 1074 3075 1191 3075 1076 3075 1191 3076 1196 3076 1076 3076 1076 3077 1196 3077 1195 3077 1076 3078 1195 3078 1078 3078 1195 3079 1193 3079 1078 3079 1078 3080 1193 3080 1192 3080 1078 3081 1192 3081 1080 3081 1163 3082 1136 3082 1134 3082 1192 3083 1201 3083 1080 3083 1080 3084 1201 3084 1200 3084 1080 3085 1200 3085 1081 3085 1081 3086 1200 3086 1198 3086 1081 3087 1198 3087 1069 3087 1069 3088 1198 3088 1197 3088 1069 3089 1197 3089 1067 3089 1067 3090 1197 3090 1177 3090 1067 3091 1177 3091 1112 3091 1112 3092 1177 3092 1176 3092 1112 3093 1176 3093 1113 3093 1113 3094 1176 3094 1175 3094 1113 3095 1175 3095 1133 3095 1133 3096 1175 3096 1166 3096 1133 3097 1166 3097 1134 3097 1134 3098 1166 3098 1165 3098 1134 3099 1165 3099 1163 3099 1163 3100 1162 3100 1136 3100 1136 3101 1162 3101 1178 3101 1136 3102 1178 3102 1138 3102 1178 3103 1160 3103 1138 3103 1138 3104 1160 3104 1159 3104 1138 3105 1159 3105 1140 3105 1140 3106 1159 3106 1184 3106 1140 3107 1184 3107 1141 3107 1141 3108 1184 3108 1130 3108 1130 3109 1184 3109 1728 3109 1130 3110 1728 3110 1132 3110 1132 3111 1728 3111 1709 3111 1132 3112 1709 3112 1127 3112 1127 3113 1709 3113 1708 3113 1127 3114 1708 3114 1128 3114 1128 3115 1708 3115 1716 3115 1128 3116 1716 3116 1743 3116 1743 3117 1716 3117 1742 3117 1743 3118 1742 3118 1744 3118 1742 3119 1741 3119 1744 3119 1744 3120 1741 3120 1745 3120 1744 3121 1745 3121 1746 3121 1746 3122 1745 3122 1747 3122 1551 3123 1534 3123 1557 3123 1557 3124 1534 3124 1541 3124 1557 3125 1541 3125 1748 3125 1748 3126 1541 3126 1540 3126 1748 3127 1540 3127 1536 3127 1117 3128 1120 3128 1749 3128 1126 3129 1123 3129 1750 3129 1123 3130 1122 3130 1743 3130 1743 3131 1122 3131 1128 3131 1119 3132 1124 3132 1750 3132 1750 3133 1124 3133 1126 3133 1117 3134 1749 3134 1109 3134 1751 3135 1752 3135 1395 3135 1355 3136 1751 3136 1394 3136 1394 3137 1751 3137 1395 3137 1746 3138 1747 3138 1753 3138 1123 3139 1743 3139 1750 3139 1750 3140 1743 3140 1744 3140 1750 3141 1744 3141 1754 3141 1754 3142 1744 3142 1746 3142 1754 3143 1746 3143 1755 3143 1755 3144 1746 3144 1753 3144 1755 3145 1753 3145 1752 3145 1752 3146 1751 3146 1755 3146 1755 3147 1751 3147 1756 3147 1755 3148 1756 3148 1754 3148 1754 3149 1756 3149 1749 3149 1754 3150 1749 3150 1750 3150 1750 3151 1749 3151 1120 3151 1750 3152 1120 3152 1119 3152 1355 3153 1357 3153 1751 3153 1751 3154 1357 3154 1358 3154 1751 3155 1358 3155 1756 3155 1756 3156 1358 3156 1359 3156 1756 3157 1359 3157 1749 3157 1749 3158 1359 3158 1110 3158 1749 3159 1110 3159 1109 3159 1395 3160 1752 3160 1757 3160 1757 3161 1752 3161 1753 3161 1757 3162 1753 3162 1758 3162 1758 3163 1753 3163 1759 3163 1758 3164 1759 3164 1760 3164 1760 3165 1759 3165 1761 3165 1396 3166 1762 3166 1391 3166 1391 3167 1762 3167 1392 3167 1763 3168 1764 3168 1761 3168 1761 3169 1764 3169 1765 3169 1761 3170 1765 3170 1760 3170 1760 3171 1765 3171 1766 3171 1760 3172 1766 3172 1758 3172 1758 3173 1766 3173 1762 3173 1758 3174 1762 3174 1757 3174 1757 3175 1762 3175 1396 3175 1757 3176 1396 3176 1395 3176 1224 3177 1235 3177 1767 3177 1767 3178 1235 3178 1233 3178 1768 3179 1225 3179 1224 3179 1224 3180 1767 3180 1768 3180 1768 3181 1767 3181 1769 3181 1768 3182 1769 3182 1770 3182 1771 3183 1772 3183 1773 3183 1774 3184 1775 3184 1776 3184 1776 3185 1775 3185 1771 3185 1776 3186 1771 3186 1777 3186 1777 3187 1771 3187 1773 3187 1777 3188 1773 3188 1778 3188 1779 3189 1770 3189 1778 3189 1778 3190 1770 3190 1769 3190 1778 3191 1769 3191 1777 3191 1777 3192 1769 3192 1767 3192 1777 3193 1767 3193 1776 3193 1776 3194 1767 3194 1233 3194 1776 3195 1233 3195 1774 3195 1774 3196 1233 3196 1234 3196 1780 3197 1781 3197 1782 3197 1783 3198 1784 3198 1785 3198 1786 3199 1787 3199 1788 3199 1787 3200 1786 3200 1789 3200 1215 3201 1214 3201 1294 3201 1294 3202 1214 3202 1223 3202 1294 3203 1223 3203 1295 3203 1270 3204 1790 3204 1269 3204 1269 3205 1790 3205 1791 3205 1269 3206 1791 3206 1268 3206 1288 3207 1289 3207 1792 3207 1792 3208 1289 3208 1290 3208 1793 3209 1286 3209 1287 3209 1793 3210 1794 3210 1286 3210 1286 3211 1794 3211 1795 3211 1286 3212 1795 3212 1282 3212 1282 3213 1795 3213 1796 3213 1282 3214 1796 3214 1281 3214 1281 3215 1796 3215 1797 3215 1281 3216 1797 3216 1280 3216 1265 3217 1798 3217 1273 3217 1273 3218 1798 3218 1799 3218 1273 3219 1799 3219 1800 3219 1800 3220 1799 3220 1801 3220 1800 3221 1801 3221 1802 3221 1802 3222 1801 3222 1803 3222 1802 3223 1803 3223 1804 3223 1804 3224 1803 3224 1805 3224 1804 3225 1805 3225 1806 3225 1805 3226 1807 3226 1806 3226 1806 3227 1807 3227 1808 3227 1806 3228 1808 3228 1809 3228 1809 3229 1808 3229 1810 3229 1810 3230 1808 3230 1811 3230 1810 3231 1811 3231 1812 3231 1812 3232 1811 3232 1813 3232 1812 3233 1813 3233 1814 3233 1815 3234 1816 3234 1817 3234 1817 3235 1816 3235 1818 3235 1817 3236 1818 3236 1819 3236 1819 3237 1818 3237 1820 3237 1819 3238 1820 3238 1821 3238 1784 3239 1783 3239 1822 3239 1823 3240 1824 3240 1825 3240 1826 3241 1827 3241 1828 3241 1782 3242 1781 3242 1827 3242 1827 3243 1781 3243 1829 3243 1827 3244 1829 3244 1828 3244 1830 3245 1831 3245 1832 3245 1833 3246 1834 3246 1835 3246 1835 3247 1834 3247 1836 3247 1835 3248 1836 3248 1837 3248 1837 3249 1836 3249 1838 3249 1837 3250 1838 3250 1839 3250 1821 3251 1820 3251 1840 3251 1840 3252 1820 3252 1841 3252 1840 3253 1841 3253 1789 3253 1789 3254 1841 3254 1842 3254 1789 3255 1842 3255 1787 3255 1787 3256 1842 3256 1843 3256 1787 3257 1843 3257 1788 3257 1816 3258 1844 3258 1818 3258 1818 3259 1844 3259 1833 3259 1818 3260 1833 3260 1820 3260 1820 3261 1833 3261 1835 3261 1820 3262 1835 3262 1841 3262 1841 3263 1835 3263 1837 3263 1841 3264 1837 3264 1842 3264 1842 3265 1837 3265 1839 3265 1842 3266 1839 3266 1843 3266 1845 3267 1846 3267 1847 3267 1847 3268 1846 3268 1848 3268 1847 3269 1848 3269 1849 3269 1849 3270 1848 3270 1850 3270 1849 3271 1850 3271 1851 3271 1851 3272 1850 3272 1852 3272 1851 3273 1852 3273 1853 3273 1853 3274 1852 3274 1854 3274 1853 3275 1854 3275 1855 3275 1855 3276 1854 3276 1856 3276 1855 3277 1856 3277 1857 3277 1857 3278 1856 3278 1858 3278 1857 3279 1858 3279 1859 3279 1859 3280 1858 3280 1860 3280 1859 3281 1860 3281 1861 3281 1861 3282 1860 3282 1768 3282 1861 3283 1768 3283 1770 3283 1862 3284 1863 3284 1864 3284 1863 3285 1862 3285 1865 3285 1865 3286 1862 3286 1866 3286 1865 3287 1866 3287 1867 3287 1867 3288 1866 3288 1868 3288 1867 3289 1868 3289 1838 3289 1838 3290 1868 3290 1869 3290 1838 3291 1869 3291 1839 3291 1839 3292 1869 3292 1870 3292 1839 3293 1870 3293 1843 3293 1843 3294 1870 3294 1822 3294 1843 3295 1822 3295 1788 3295 1788 3296 1822 3296 1783 3296 1788 3297 1783 3297 1786 3297 1222 3298 1871 3298 1223 3298 1223 3299 1871 3299 1296 3299 1223 3300 1296 3300 1295 3300 1790 3301 1872 3301 1791 3301 1791 3302 1872 3302 1873 3302 1791 3303 1873 3303 1864 3303 1864 3304 1873 3304 1874 3304 1864 3305 1874 3305 1862 3305 1862 3306 1874 3306 1875 3306 1862 3307 1875 3307 1866 3307 1866 3308 1875 3308 1876 3308 1866 3309 1876 3309 1868 3309 1868 3310 1876 3310 1877 3310 1868 3311 1877 3311 1869 3311 1869 3312 1877 3312 1878 3312 1869 3313 1878 3313 1870 3313 1870 3314 1878 3314 1879 3314 1870 3315 1879 3315 1822 3315 1822 3316 1879 3316 1823 3316 1822 3317 1823 3317 1784 3317 1784 3318 1823 3318 1825 3318 1784 3319 1825 3319 1785 3319 1880 3320 1881 3320 1882 3320 1882 3321 1881 3321 1883 3321 1882 3322 1883 3322 1884 3322 1884 3323 1883 3323 1885 3323 1884 3324 1885 3324 1886 3324 1886 3325 1885 3325 1887 3325 1886 3326 1887 3326 1888 3326 1888 3327 1887 3327 1889 3327 1888 3328 1889 3328 1890 3328 1890 3329 1889 3329 1891 3329 1890 3330 1891 3330 1892 3330 1892 3331 1891 3331 1893 3331 1892 3332 1893 3332 1894 3332 1894 3333 1893 3333 1895 3333 1894 3334 1895 3334 1826 3334 1826 3335 1895 3335 1896 3335 1826 3336 1896 3336 1827 3336 1827 3337 1896 3337 1897 3337 1827 3338 1897 3338 1782 3338 1881 3339 1845 3339 1883 3339 1883 3340 1845 3340 1847 3340 1883 3341 1847 3341 1885 3341 1885 3342 1847 3342 1849 3342 1885 3343 1849 3343 1887 3343 1887 3344 1849 3344 1851 3344 1887 3345 1851 3345 1889 3345 1889 3346 1851 3346 1853 3346 1889 3347 1853 3347 1891 3347 1891 3348 1853 3348 1855 3348 1891 3349 1855 3349 1893 3349 1893 3350 1855 3350 1857 3350 1893 3351 1857 3351 1895 3351 1895 3352 1857 3352 1859 3352 1895 3353 1859 3353 1896 3353 1896 3354 1859 3354 1861 3354 1896 3355 1861 3355 1897 3355 1897 3356 1861 3356 1770 3356 1897 3357 1770 3357 1782 3357 1782 3358 1770 3358 1779 3358 1782 3359 1779 3359 1780 3359 1872 3360 1880 3360 1873 3360 1873 3361 1880 3361 1882 3361 1873 3362 1882 3362 1874 3362 1874 3363 1882 3363 1884 3363 1874 3364 1884 3364 1875 3364 1875 3365 1884 3365 1886 3365 1875 3366 1886 3366 1876 3366 1876 3367 1886 3367 1888 3367 1876 3368 1888 3368 1877 3368 1877 3369 1888 3369 1890 3369 1877 3370 1890 3370 1878 3370 1878 3371 1890 3371 1892 3371 1878 3372 1892 3372 1879 3372 1879 3373 1892 3373 1894 3373 1879 3374 1894 3374 1823 3374 1823 3375 1894 3375 1826 3375 1823 3376 1826 3376 1824 3376 1824 3377 1826 3377 1828 3377 1824 3378 1828 3378 1825 3378 1265 3379 1264 3379 1798 3379 1798 3380 1264 3380 1898 3380 1798 3381 1898 3381 1799 3381 1799 3382 1898 3382 1899 3382 1799 3383 1899 3383 1801 3383 1801 3384 1899 3384 1900 3384 1801 3385 1900 3385 1803 3385 1803 3386 1900 3386 1901 3386 1803 3387 1901 3387 1805 3387 1805 3388 1901 3388 1902 3388 1805 3389 1902 3389 1807 3389 1807 3390 1902 3390 1903 3390 1807 3391 1903 3391 1808 3391 1808 3392 1903 3392 1904 3392 1808 3393 1904 3393 1811 3393 1811 3394 1904 3394 1905 3394 1811 3395 1905 3395 1813 3395 1906 3396 1907 3396 1908 3396 1907 3397 1906 3397 1909 3397 1909 3398 1906 3398 1910 3398 1909 3399 1910 3399 1911 3399 1288 3400 1792 3400 1287 3400 1287 3401 1792 3401 1912 3401 1287 3402 1912 3402 1793 3402 1793 3403 1912 3403 1913 3403 1793 3404 1913 3404 1794 3404 1794 3405 1913 3405 1914 3405 1794 3406 1914 3406 1795 3406 1795 3407 1914 3407 1915 3407 1795 3408 1915 3408 1796 3408 1831 3409 1911 3409 1832 3409 1832 3410 1911 3410 1910 3410 1832 3411 1910 3411 1915 3411 1915 3412 1910 3412 1906 3412 1915 3413 1906 3413 1796 3413 1796 3414 1906 3414 1908 3414 1796 3415 1908 3415 1797 3415 1264 3416 1280 3416 1898 3416 1898 3417 1280 3417 1797 3417 1898 3418 1797 3418 1899 3418 1899 3419 1797 3419 1908 3419 1899 3420 1908 3420 1900 3420 1900 3421 1908 3421 1907 3421 1900 3422 1907 3422 1901 3422 1901 3423 1907 3423 1909 3423 1901 3424 1909 3424 1902 3424 1902 3425 1909 3425 1911 3425 1902 3426 1911 3426 1903 3426 1903 3427 1911 3427 1831 3427 1903 3428 1831 3428 1904 3428 1904 3429 1831 3429 1830 3429 1904 3430 1830 3430 1905 3430 1225 3431 1768 3431 1226 3431 1226 3432 1768 3432 1860 3432 1226 3433 1860 3433 1227 3433 1227 3434 1860 3434 1858 3434 1227 3435 1858 3435 1228 3435 1228 3436 1858 3436 1856 3436 1228 3437 1856 3437 1229 3437 1229 3438 1856 3438 1854 3438 1229 3439 1854 3439 1230 3439 1230 3440 1854 3440 1852 3440 1230 3441 1852 3441 1231 3441 1231 3442 1852 3442 1850 3442 1231 3443 1850 3443 1232 3443 1232 3444 1850 3444 1848 3444 1232 3445 1848 3445 1216 3445 1216 3446 1848 3446 1846 3446 1216 3447 1846 3447 1217 3447 1217 3448 1846 3448 1845 3448 1217 3449 1845 3449 1219 3449 1219 3450 1845 3450 1881 3450 1219 3451 1881 3451 1220 3451 1220 3452 1881 3452 1880 3452 1220 3453 1880 3453 1221 3453 1221 3454 1880 3454 1872 3454 1221 3455 1872 3455 1222 3455 1222 3456 1872 3456 1790 3456 1222 3457 1790 3457 1871 3457 1871 3458 1790 3458 1270 3458 1871 3459 1270 3459 1296 3459 1268 3460 1791 3460 1291 3460 1291 3461 1791 3461 1864 3461 1291 3462 1864 3462 1290 3462 1290 3463 1864 3463 1863 3463 1290 3464 1863 3464 1792 3464 1792 3465 1863 3465 1865 3465 1792 3466 1865 3466 1912 3466 1912 3467 1865 3467 1867 3467 1912 3468 1867 3468 1913 3468 1913 3469 1867 3469 1838 3469 1913 3470 1838 3470 1914 3470 1914 3471 1838 3471 1836 3471 1914 3472 1836 3472 1915 3472 1915 3473 1836 3473 1834 3473 1915 3474 1834 3474 1832 3474 1832 3475 1834 3475 1833 3475 1832 3476 1833 3476 1830 3476 1830 3477 1833 3477 1844 3477 1830 3478 1844 3478 1905 3478 1905 3479 1844 3479 1816 3479 1905 3480 1816 3480 1813 3480 1813 3481 1816 3481 1815 3481 1813 3482 1815 3482 1814 3482 1274 3483 1273 3483 1916 3483 1916 3484 1273 3484 1800 3484 1916 3485 1800 3485 1917 3485 1917 3486 1800 3486 1802 3486 1917 3487 1802 3487 1918 3487 1918 3488 1802 3488 1804 3488 1918 3489 1804 3489 1919 3489 1919 3490 1804 3490 1806 3490 1919 3491 1806 3491 1920 3491 1806 3492 1809 3492 1920 3492 1920 3493 1809 3493 1810 3493 1920 3494 1810 3494 1921 3494 1921 3495 1810 3495 1812 3495 1921 3496 1812 3496 1922 3496 1922 3497 1812 3497 1814 3497 1253 3498 1252 3498 1923 3498 1924 3499 1925 3499 1926 3499 1927 3500 1928 3500 1929 3500 1930 3501 1931 3501 1932 3501 1932 3502 1931 3502 1933 3502 1298 3503 1934 3503 1299 3503 1292 3504 1285 3504 1927 3504 1935 3505 1919 3505 1936 3505 1936 3506 1919 3506 1920 3506 1936 3507 1920 3507 1937 3507 1937 3508 1920 3508 1921 3508 1937 3509 1921 3509 1938 3509 1938 3510 1921 3510 1922 3510 1938 3511 1922 3511 1939 3511 1939 3512 1922 3512 1940 3512 1939 3513 1940 3513 1941 3513 1942 3514 1916 3514 1917 3514 1271 3515 1274 3515 1943 3515 1943 3516 1274 3516 1916 3516 1271 3517 1943 3517 1272 3517 1272 3518 1943 3518 1944 3518 1272 3519 1944 3519 1279 3519 1944 3520 1945 3520 1279 3520 1279 3521 1945 3521 1946 3521 1279 3522 1946 3522 1278 3522 1278 3523 1946 3523 1947 3523 1278 3524 1947 3524 1277 3524 1277 3525 1947 3525 1948 3525 1277 3526 1948 3526 1276 3526 1276 3527 1948 3527 1949 3527 1276 3528 1949 3528 1275 3528 1950 3529 1951 3529 1266 3529 1952 3530 1283 3530 1267 3530 1934 3531 1298 3531 1929 3531 1255 3532 1237 3532 1236 3532 1953 3533 1954 3533 1955 3533 1955 3534 1954 3534 1956 3534 1955 3535 1956 3535 1957 3535 1955 3536 1958 3536 1953 3536 1953 3537 1958 3537 1959 3537 1953 3538 1959 3538 1960 3538 1960 3539 1959 3539 1961 3539 1960 3540 1961 3540 1962 3540 1963 3541 1964 3541 1965 3541 1965 3542 1964 3542 1966 3542 1965 3543 1966 3543 1967 3543 1967 3544 1966 3544 1942 3544 1967 3545 1942 3545 1968 3545 1968 3546 1942 3546 1917 3546 1968 3547 1969 3547 1967 3547 1967 3548 1969 3548 1970 3548 1967 3549 1970 3549 1965 3549 1965 3550 1970 3550 1971 3550 1965 3551 1971 3551 1963 3551 1963 3552 1971 3552 1972 3552 1969 3553 1973 3553 1970 3553 1970 3554 1973 3554 1974 3554 1970 3555 1974 3555 1971 3555 1971 3556 1974 3556 1975 3556 1971 3557 1975 3557 1972 3557 1972 3558 1975 3558 1976 3558 1972 3559 1976 3559 1977 3559 1977 3560 1976 3560 1978 3560 1977 3561 1978 3561 1979 3561 1916 3562 1942 3562 1943 3562 1943 3563 1942 3563 1966 3563 1943 3564 1966 3564 1944 3564 1944 3565 1966 3565 1964 3565 1944 3566 1964 3566 1945 3566 1945 3567 1964 3567 1963 3567 1945 3568 1963 3568 1946 3568 1946 3569 1963 3569 1972 3569 1946 3570 1972 3570 1947 3570 1947 3571 1972 3571 1977 3571 1947 3572 1977 3572 1948 3572 1948 3573 1977 3573 1979 3573 1948 3574 1979 3574 1949 3574 1980 3575 1981 3575 1982 3575 1982 3576 1981 3576 1983 3576 1982 3577 1983 3577 1984 3577 1984 3578 1983 3578 1985 3578 1984 3579 1985 3579 1986 3579 1986 3580 1985 3580 1987 3580 1986 3581 1987 3581 1988 3581 1298 3582 1297 3582 1929 3582 1929 3583 1297 3583 1293 3583 1929 3584 1293 3584 1927 3584 1927 3585 1293 3585 1292 3585 1236 3586 1300 3586 1255 3586 1255 3587 1300 3587 1299 3587 1255 3588 1299 3588 1256 3588 1256 3589 1299 3589 1934 3589 1256 3590 1934 3590 1257 3590 1257 3591 1934 3591 1929 3591 1257 3592 1929 3592 1258 3592 1258 3593 1929 3593 1928 3593 1258 3594 1928 3594 1259 3594 1926 3595 1989 3595 1990 3595 1930 3596 1991 3596 1931 3596 1931 3597 1991 3597 1992 3597 1931 3598 1992 3598 1933 3598 1933 3599 1992 3599 1993 3599 1994 3600 1995 3600 1924 3600 1996 3601 1994 3601 1997 3601 1997 3602 1994 3602 1924 3602 1997 3603 1924 3603 1998 3603 1998 3604 1924 3604 1926 3604 1998 3605 1926 3605 1999 3605 1999 3606 1926 3606 1990 3606 1999 3607 1990 3607 2000 3607 2000 3608 1990 3608 2001 3608 2000 3609 2001 3609 2002 3609 2002 3610 2001 3610 2003 3610 2002 3611 2003 3611 2004 3611 2004 3612 2003 3612 2005 3612 2004 3613 2005 3613 1254 3613 1275 3614 1949 3614 2006 3614 2006 3615 1949 3615 1979 3615 2006 3616 1979 3616 2007 3616 2007 3617 1979 3617 1978 3617 2007 3618 1978 3618 2008 3618 2008 3619 1978 3619 2009 3619 2008 3620 2009 3620 2010 3620 2010 3621 2009 3621 2011 3621 2010 3622 2011 3622 2012 3622 2012 3623 2011 3623 2013 3623 2012 3624 2013 3624 2014 3624 2014 3625 2013 3625 2015 3625 2014 3626 2015 3626 2016 3626 2016 3627 2015 3627 2017 3627 2016 3628 2017 3628 2018 3628 2018 3629 2019 3629 2016 3629 2016 3630 2019 3630 2020 3630 2016 3631 2020 3631 2014 3631 2014 3632 2020 3632 2021 3632 2014 3633 2021 3633 2012 3633 2012 3634 2021 3634 2022 3634 2012 3635 2022 3635 2010 3635 2010 3636 2022 3636 2023 3636 2010 3637 2023 3637 2008 3637 2008 3638 2023 3638 2024 3638 2008 3639 2024 3639 2007 3639 2007 3640 2024 3640 1950 3640 2007 3641 1950 3641 2006 3641 2006 3642 1950 3642 1266 3642 2006 3643 1266 3643 1275 3643 2025 3644 2026 3644 2027 3644 2027 3645 2026 3645 2028 3645 2027 3646 2028 3646 2029 3646 2029 3647 2028 3647 2030 3647 2029 3648 2030 3648 2031 3648 2031 3649 2030 3649 2032 3649 2031 3650 2032 3650 2033 3650 2033 3651 2032 3651 2034 3651 2033 3652 2034 3652 2035 3652 2035 3653 2034 3653 2036 3653 2035 3654 2036 3654 1952 3654 1952 3655 2036 3655 1284 3655 1952 3656 1284 3656 1283 3656 2026 3657 1980 3657 2028 3657 2028 3658 1980 3658 1982 3658 2028 3659 1982 3659 2030 3659 2030 3660 1982 3660 1984 3660 2030 3661 1984 3661 2032 3661 2032 3662 1984 3662 1986 3662 2032 3663 1986 3663 2034 3663 2034 3664 1986 3664 1988 3664 2034 3665 1988 3665 2036 3665 2019 3666 2025 3666 2020 3666 2020 3667 2025 3667 2027 3667 2020 3668 2027 3668 2021 3668 2021 3669 2027 3669 2029 3669 2021 3670 2029 3670 2022 3670 2022 3671 2029 3671 2031 3671 2022 3672 2031 3672 2023 3672 2023 3673 2031 3673 2033 3673 2023 3674 2033 3674 2024 3674 2024 3675 2033 3675 2035 3675 2024 3676 2035 3676 1950 3676 1950 3677 2035 3677 1952 3677 1950 3678 1952 3678 1951 3678 1951 3679 1952 3679 1267 3679 1951 3680 1267 3680 1266 3680 1941 3681 2037 3681 1939 3681 1939 3682 2037 3682 2038 3682 1939 3683 2038 3683 1938 3683 1938 3684 2038 3684 2039 3684 1938 3685 2039 3685 1937 3685 1937 3686 2039 3686 2040 3686 1937 3687 2040 3687 1936 3687 1936 3688 2040 3688 2041 3688 1936 3689 2041 3689 1935 3689 2037 3690 2042 3690 2038 3690 2038 3691 2042 3691 2043 3691 2038 3692 2043 3692 2039 3692 2039 3693 2043 3693 2044 3693 2039 3694 2044 3694 2040 3694 2040 3695 2044 3695 2045 3695 2040 3696 2045 3696 2041 3696 2046 3697 1961 3697 2047 3697 2047 3698 1961 3698 1959 3698 2047 3699 1959 3699 2048 3699 2048 3700 1959 3700 1958 3700 2048 3701 1958 3701 1996 3701 1996 3702 1958 3702 1994 3702 1994 3703 1958 3703 1955 3703 1994 3704 1955 3704 1995 3704 1995 3705 1955 3705 1957 3705 1995 3706 1957 3706 1924 3706 1924 3707 1957 3707 2049 3707 1924 3708 2049 3708 1925 3708 1925 3709 2049 3709 2050 3709 1925 3710 2050 3710 1926 3710 1926 3711 2050 3711 2051 3711 1926 3712 2051 3712 1989 3712 1989 3713 2051 3713 1993 3713 1989 3714 1993 3714 1990 3714 1990 3715 1993 3715 1992 3715 1990 3716 1992 3716 2001 3716 2001 3717 1992 3717 1991 3717 2001 3718 1991 3718 2003 3718 2003 3719 1991 3719 1930 3719 2003 3720 1930 3720 2005 3720 2042 3721 1962 3721 2043 3721 2043 3722 1962 3722 1961 3722 2043 3723 1961 3723 2044 3723 2044 3724 1961 3724 2046 3724 2044 3725 2046 3725 2045 3725 2045 3726 2046 3726 2052 3726 2045 3727 2052 3727 2041 3727 2041 3728 2052 3728 2053 3728 2041 3729 2053 3729 1935 3729 1935 3730 2053 3730 2054 3730 1935 3731 2054 3731 1919 3731 1919 3732 2054 3732 1918 3732 2017 3733 1923 3733 2018 3733 2018 3734 1923 3734 1252 3734 2018 3735 1252 3735 2019 3735 2019 3736 1252 3736 1251 3736 2019 3737 1251 3737 2025 3737 2025 3738 1251 3738 1250 3738 2025 3739 1250 3739 2026 3739 2026 3740 1250 3740 1249 3740 2026 3741 1249 3741 1980 3741 1980 3742 1249 3742 1248 3742 1980 3743 1248 3743 1981 3743 1981 3744 1248 3744 1247 3744 1981 3745 1247 3745 1983 3745 1983 3746 1247 3746 1260 3746 1983 3747 1260 3747 1985 3747 1985 3748 1260 3748 1259 3748 1985 3749 1259 3749 1987 3749 1987 3750 1259 3750 1928 3750 1987 3751 1928 3751 1988 3751 1988 3752 1928 3752 1927 3752 1988 3753 1927 3753 2036 3753 2036 3754 1927 3754 1285 3754 2036 3755 1285 3755 1284 3755 1254 3756 1253 3756 2004 3756 2004 3757 1253 3757 1923 3757 2004 3758 1923 3758 2002 3758 2002 3759 1923 3759 2017 3759 2002 3760 2017 3760 2000 3760 2000 3761 2017 3761 2015 3761 2000 3762 2015 3762 1999 3762 1999 3763 2015 3763 2013 3763 1999 3764 2013 3764 1998 3764 1998 3765 2013 3765 2011 3765 1998 3766 2011 3766 1997 3766 1997 3767 2011 3767 2009 3767 1997 3768 2009 3768 1996 3768 1996 3769 2009 3769 1978 3769 1996 3770 1978 3770 2048 3770 2048 3771 1978 3771 1976 3771 2048 3772 1976 3772 2047 3772 2047 3773 1976 3773 1975 3773 2047 3774 1975 3774 2046 3774 2046 3775 1975 3775 1974 3775 2046 3776 1974 3776 2052 3776 2052 3777 1974 3777 1973 3777 2052 3778 1973 3778 2053 3778 2053 3779 1973 3779 1969 3779 2053 3780 1969 3780 2054 3780 2054 3781 1969 3781 1968 3781 2054 3782 1968 3782 1918 3782 1918 3783 1968 3783 1917 3783 2055 3784 2056 3784 2057 3784 1930 3785 1932 3785 2056 3785 2056 3786 2055 3786 1930 3786 1930 3787 2055 3787 2058 3787 1930 3788 2058 3788 2005 3788 2059 3789 1241 3789 1244 3789 1242 3790 1241 3790 2060 3790 2060 3791 1241 3791 2059 3791 2060 3792 2059 3792 2061 3792 2061 3793 2059 3793 2062 3793 2061 3794 2062 3794 2063 3794 2063 3795 2062 3795 2064 3795 2065 3796 2064 3796 2057 3796 2057 3797 2064 3797 2062 3797 2057 3798 2062 3798 2055 3798 2055 3799 2062 3799 2059 3799 2055 3800 2059 3800 2058 3800 2058 3801 2059 3801 1244 3801 2058 3802 1244 3802 2005 3802 2005 3803 1244 3803 1254 3803 749 3804 1243 3804 1242 3804 1301 1530 749 1530 2066 1530 2066 3805 749 3805 1242 3805 2066 3806 1242 3806 2067 3806 2067 3807 1242 3807 2068 3807 1303 3808 1302 3808 2066 3808 2066 3809 1302 3809 748 3809 2066 3810 748 3810 1301 3810 2069 3811 1315 3811 2070 3811 2070 3812 1315 3812 1317 3812 2070 3813 1317 3813 2071 3813 2071 3814 1317 3814 1326 3814 2071 3815 1326 3815 2072 3815 2072 3816 1326 3816 1328 3816 2072 3817 1328 3817 2068 3817 2068 3818 1328 3818 1321 3818 2068 3819 1321 3819 2067 3819 2067 3820 1321 3820 2066 3820 2066 3821 1321 3821 1320 3821 2066 3822 1320 3822 1303 3822 1455 1296 1316 1296 2073 1296 2073 1296 1316 1296 1315 1296 2073 3823 1315 3823 2074 3823 2074 3824 1315 3824 2069 3824 2075 3825 2076 3825 2077 3825 2078 3826 2079 3826 2080 3826 1339 3827 1340 3827 1376 3827 1338 3828 1339 3828 2081 3828 1333 3829 2082 3829 2083 3829 2083 3830 2082 3830 2084 3830 2083 3831 2084 3831 2085 3831 2085 3832 2084 3832 2086 3832 2085 3833 2086 3833 2087 3833 2087 3834 2086 3834 2088 3834 2087 3835 2088 3835 2089 3835 2089 3836 2088 3836 2090 3836 2089 3837 2090 3837 2091 3837 1339 3838 1376 3838 2081 3838 2081 3839 1376 3839 1375 3839 2081 3840 1375 3840 2092 3840 2092 3841 1375 3841 1374 3841 2092 3842 1374 3842 2093 3842 2093 3843 1374 3843 1372 3843 2093 3844 1372 3844 2094 3844 2094 3845 1372 3845 1371 3845 2094 3846 1371 3846 2095 3846 2095 3847 1371 3847 1373 3847 2095 3848 1373 3848 2096 3848 2096 3849 1373 3849 1370 3849 2096 3850 1370 3850 2097 3850 2097 3851 1370 3851 1369 3851 2097 3852 1369 3852 2098 3852 2098 3853 1369 3853 1368 3853 2098 3854 1368 3854 2099 3854 2099 3855 1368 3855 1367 3855 2099 3856 1367 3856 2100 3856 2100 3857 1367 3857 1366 3857 2100 3858 1366 3858 2101 3858 2101 3859 1366 3859 1365 3859 2101 3860 1365 3860 2102 3860 2102 3861 2078 3861 2101 3861 2101 3862 2078 3862 2080 3862 2101 3863 2080 3863 2100 3863 2100 3864 2080 3864 2103 3864 2100 3865 2103 3865 2099 3865 2099 3866 2103 3866 2104 3866 2099 3867 2104 3867 2098 3867 2098 3868 2104 3868 2105 3868 2098 3869 2105 3869 2097 3869 2097 3870 2105 3870 2106 3870 2097 3871 2106 3871 2096 3871 2096 3872 2106 3872 2107 3872 2096 3873 2107 3873 2095 3873 2095 3874 2107 3874 2108 3874 2095 3875 2108 3875 2094 3875 2094 3876 2108 3876 2109 3876 2094 3877 2109 3877 2093 3877 2093 3878 2109 3878 2110 3878 2093 3879 2110 3879 2092 3879 2092 3880 2110 3880 2111 3880 2092 3881 2111 3881 2081 3881 2081 3882 2111 3882 2112 3882 2081 3883 2112 3883 1338 3883 1338 3884 2112 3884 1336 3884 2079 3885 2075 3885 2080 3885 2080 3886 2075 3886 2077 3886 2080 3887 2077 3887 2103 3887 2103 3888 2077 3888 2113 3888 2103 3889 2113 3889 2104 3889 2104 3890 2113 3890 2114 3890 2104 3891 2114 3891 2105 3891 2105 3892 2114 3892 2115 3892 2105 3893 2115 3893 2106 3893 2106 3894 2115 3894 2116 3894 2106 3895 2116 3895 2107 3895 2107 3896 2116 3896 2117 3896 2107 3897 2117 3897 2108 3897 2108 3898 2117 3898 2090 3898 2108 3899 2090 3899 2109 3899 2109 3900 2090 3900 2088 3900 2109 3901 2088 3901 2110 3901 2110 3902 2088 3902 2086 3902 2110 3903 2086 3903 2111 3903 2111 3904 2086 3904 2084 3904 2111 3905 2084 3905 2112 3905 2112 3906 2084 3906 2082 3906 2112 3907 2082 3907 1336 3907 1336 3908 2082 3908 1333 3908 2091 3909 2090 3909 2118 3909 2118 3910 2090 3910 2117 3910 2118 3911 2117 3911 2119 3911 2119 3912 2117 3912 2116 3912 2119 3913 2116 3913 2120 3913 2120 3914 2116 3914 2115 3914 2120 3915 2115 3915 2121 3915 2121 3916 2115 3916 2114 3916 2121 3917 2114 3917 2122 3917 2122 3918 2114 3918 2113 3918 2122 3919 2113 3919 2123 3919 2123 3920 2113 3920 2077 3920 2123 3921 2077 3921 2124 3921 2124 3922 2077 3922 2076 3922 2124 3923 2076 3923 2125 3923 1333 3924 2126 3924 1334 3924 1334 3925 2126 3925 2127 3925 1334 3926 2127 3926 941 3926 941 3927 2127 3927 1478 3927 2128 3928 2125 3928 2076 3928 2128 3929 2076 3929 2129 3929 2129 3930 2130 3930 2131 3930 2131 3931 2132 3931 2129 3931 2129 3932 2132 3932 2133 3932 2129 3933 2133 3933 2128 3933 2128 3934 2133 3934 2134 3934 2128 3935 2134 3935 2135 3935 2078 3936 2130 3936 2079 3936 2079 3937 2130 3937 2129 3937 2079 3938 2129 3938 2075 3938 2075 3939 2129 3939 2076 3939 2102 3940 1365 3940 1364 3940 1361 3941 2136 3941 1362 3941 1362 3942 2136 3942 2131 3942 1362 3943 2131 3943 1363 3943 1363 3944 2131 3944 2130 3944 1363 3945 2130 3945 1364 3945 1364 3946 2130 3946 2078 3946 1364 3947 2078 3947 2102 3947 2131 3948 2136 3948 2137 3948 2133 3949 2132 3949 2138 3949 1389 3950 1390 3950 2139 3950 1388 3951 1389 3951 2140 3951 1389 3952 2139 3952 2140 3952 2140 3953 2139 3953 2141 3953 2140 3954 2141 3954 2142 3954 2142 3955 2141 3955 2143 3955 2142 3956 2143 3956 2144 3956 2144 3957 2143 3957 2145 3957 2143 3958 2146 3958 2145 3958 2145 3959 2146 3959 2147 3959 2145 3960 2147 3960 2148 3960 2148 3961 2147 3961 2149 3961 2148 3962 2149 3962 2150 3962 2149 3963 2151 3963 2150 3963 2150 3964 2151 3964 2152 3964 2150 3965 2152 3965 2153 3965 2153 3966 2152 3966 2154 3966 2153 3967 2154 3967 2155 3967 2155 3968 2154 3968 2156 3968 2155 3969 2156 3969 2157 3969 2157 3970 2156 3970 2158 3970 2157 3971 2158 3971 2159 3971 2159 3972 2158 3972 2160 3972 2159 3973 2160 3973 2161 3973 2161 3974 2160 3974 2135 3974 2161 3975 2135 3975 2134 3975 2134 3976 2133 3976 2161 3976 2161 3977 2133 3977 2138 3977 2161 3978 2138 3978 2159 3978 2159 3979 2138 3979 2162 3979 2159 3980 2162 3980 2157 3980 2157 3981 2162 3981 2163 3981 2157 3982 2163 3982 2155 3982 2155 3983 2163 3983 2164 3983 2155 3984 2164 3984 2153 3984 2153 3985 2164 3985 2165 3985 2153 3986 2165 3986 2150 3986 2150 3987 2165 3987 2166 3987 2150 3988 2166 3988 2148 3988 2148 3989 2166 3989 2167 3989 2148 3990 2167 3990 2145 3990 2145 3991 2167 3991 2168 3991 2145 3992 2168 3992 2144 3992 2144 3993 2168 3993 2169 3993 2144 3994 2169 3994 2142 3994 2142 3995 2169 3995 2170 3995 2142 3996 2170 3996 2140 3996 2140 3997 2170 3997 2171 3997 2140 3998 2171 3998 1388 3998 1388 3999 2171 3999 1386 3999 2132 4000 2131 4000 2138 4000 2138 4001 2131 4001 2137 4001 2138 4002 2137 4002 2162 4002 2162 4003 2137 4003 2172 4003 2162 4004 2172 4004 2163 4004 2163 4005 2172 4005 2173 4005 2163 4006 2173 4006 2164 4006 2164 4007 2173 4007 2174 4007 2164 4008 2174 4008 2165 4008 2165 4009 2174 4009 2175 4009 2165 4010 2175 4010 2166 4010 2166 4011 2175 4011 2176 4011 2166 4012 2176 4012 2167 4012 2167 4013 2176 4013 2177 4013 2167 4014 2177 4014 2168 4014 2168 4015 2177 4015 2178 4015 2168 4016 2178 4016 2169 4016 2169 4017 2178 4017 2179 4017 2169 4018 2179 4018 2170 4018 2170 4019 2179 4019 2180 4019 2170 4020 2180 4020 2171 4020 2171 4021 2180 4021 2181 4021 2171 4022 2181 4022 1386 4022 1386 4023 2181 4023 1353 4023 1353 4024 2181 4024 1354 4024 1354 4025 2181 4025 2180 4025 1354 4026 2180 4026 1347 4026 1347 4027 2180 4027 2179 4027 1347 4028 2179 4028 1348 4028 1348 4029 2179 4029 2178 4029 1348 4030 2178 4030 1349 4030 1349 4031 2178 4031 2177 4031 1349 4032 2177 4032 1350 4032 1350 4033 2177 4033 2176 4033 1350 4034 2176 4034 1351 4034 1351 4035 2176 4035 2175 4035 1351 4036 2175 4036 1345 4036 1345 4037 2175 4037 2174 4037 1345 4038 2174 4038 1343 4038 1343 4039 2174 4039 2173 4039 1343 4040 2173 4040 1342 4040 1342 4041 2173 4041 2172 4041 1342 4042 2172 4042 1341 4042 1341 4043 2172 4043 2137 4043 1341 4044 2137 4044 1360 4044 1360 4045 2137 4045 2136 4045 1360 4046 2136 4046 1361 4046 846 4047 1420 4047 1383 4047 1383 4048 1420 4048 2182 4048 1383 4049 2182 4049 1390 4049 1390 4050 2182 4050 2183 4050 2184 4051 1393 4051 1392 4051 1399 4052 1403 4052 1401 4052 1401 4053 1403 4053 1402 4053 1401 4054 1402 4054 826 4054 1410 4055 1409 4055 2185 4055 2185 4056 1409 4056 1403 4056 2185 4057 1403 4057 2184 4057 2184 4058 1403 4058 1399 4058 2184 4059 1399 4059 1393 4059 1430 4060 1425 4060 2186 4060 2186 4061 1425 4061 2187 4061 2186 4062 2187 4062 2188 4062 2188 4063 2187 4063 2189 4063 2189 4064 2187 4064 2190 4064 2189 4065 2190 4065 2191 4065 1425 4066 1410 4066 2187 4066 2187 4067 1410 4067 2185 4067 2187 4068 2185 4068 2190 4068 2190 4069 2185 4069 2192 4069 1392 4070 1762 4070 2184 4070 2184 4071 1762 4071 1766 4071 2184 4072 1766 4072 2185 4072 2185 4073 1766 4073 1765 4073 2185 4074 1765 4074 2192 4074 2192 4075 1765 4075 1764 4075 2192 4076 1764 4076 1763 4076 1418 4077 848 4077 1426 4077 1418 4078 1426 4078 839 4078 1419 4079 839 4079 2193 4079 2193 4080 839 4080 1426 4080 2193 4081 1426 4081 2194 4081 2194 4082 1426 4082 1427 4082 2194 4083 1427 4083 2195 4083 2195 4084 1427 4084 1428 4084 2195 4085 1428 4085 2196 4085 2196 4086 1428 4086 1429 4086 2196 4087 1429 4087 2197 4087 2197 4088 1429 4088 1430 4088 1420 4089 1419 4089 2198 4089 2198 4090 1419 4090 2193 4090 2198 4091 2193 4091 2199 4091 2199 4092 2193 4092 2194 4092 2199 4093 2194 4093 2200 4093 2200 4094 2194 4094 2195 4094 2200 4095 2195 4095 2201 4095 2201 4096 2195 4096 2196 4096 2201 4097 2196 4097 2202 4097 2202 4098 2196 4098 2197 4098 2201 4099 2203 4099 2200 4099 2200 4100 2203 4100 2204 4100 2200 4101 2204 4101 2199 4101 2182 4102 1420 4102 2205 4102 2205 4103 1420 4103 2198 4103 2205 4104 2198 4104 2206 4104 2207 4105 2203 4105 2208 4105 2208 4106 2203 4106 2201 4106 2208 4107 2201 4107 2202 4107 2209 4108 2204 4108 2210 4108 2210 4109 2204 4109 2203 4109 2210 4110 2203 4110 2211 4110 2211 4111 2203 4111 2207 4111 2209 4112 2212 4112 2204 4112 2204 4113 2212 4113 2206 4113 2204 4114 2206 4114 2199 4114 2199 4115 2206 4115 2198 4115 2183 4116 2182 4116 2213 4116 2213 4117 2182 4117 2205 4117 2213 4118 2205 4118 2214 4118 2214 4119 2205 4119 2206 4119 2214 4120 2206 4120 2215 4120 2215 4121 2206 4121 2212 4121 2216 4122 2217 4122 1432 4122 2218 4123 1433 4123 2219 4123 2219 4124 1433 4124 1440 4124 1432 4125 1433 4125 2216 4125 2216 4126 1433 4126 2218 4126 2216 4127 2218 4127 2220 4127 2220 4128 2218 4128 2221 4128 2220 4129 2221 4129 2222 4129 2223 4130 2224 4130 2221 4130 2221 4131 2224 4131 2225 4131 2221 4132 2225 4132 2222 4132 1432 1482 2217 1482 1431 1482 1431 1482 2217 1482 2226 1482 871 4133 1431 4133 2226 4133 871 4134 2226 4134 1434 4134 2227 4135 1772 4135 2226 4135 2226 4136 1772 4136 1771 4136 2226 4137 1771 4137 1434 4137 1434 4138 1771 4138 1775 4138 1434 4139 1775 4139 1437 4139 1437 4140 1775 4140 1774 4140 1437 4141 1774 4141 1438 4141 1438 4142 1774 4142 1234 4142 1438 4143 1234 4143 1439 4143 2228 4144 29 4144 4 4144 57 1482 60 1482 36 1482 36 1482 60 1482 2229 1482 36 4145 2229 4145 31 4145 31 1482 2229 1482 2230 1482 31 1482 2230 1482 32 1482 32 1482 2230 1482 2231 1482 32 4146 2231 4146 34 4146 34 4147 2231 4147 42 4147 42 1482 2231 1482 2232 1482 42 1482 2232 1482 3 1482 2232 4148 2233 4148 3 4148 3 1482 2233 1482 2234 1482 3 1482 2234 1482 4 1482 4 1482 2234 1482 2235 1482 4 1482 2235 1482 2228 1482 2218 4149 2219 4149 2236 4149 2223 4150 2221 4150 2237 4150 2237 4151 2221 4151 2238 4151 2237 4152 2238 4152 2239 4152 2240 4153 2241 4153 2242 4153 2242 4154 2241 4154 2243 4154 2243 4155 2241 4155 2244 4155 2244 4156 2241 4156 2245 4156 2244 4157 2245 4157 2246 4157 2247 4158 2248 4158 2249 4158 2250 4159 2232 4159 2251 4159 2251 4160 2232 4160 2231 4160 2251 4161 2231 4161 2230 4161 2219 4162 1440 4162 2236 4162 2236 4163 1440 4163 1441 4163 2236 4164 1441 4164 27 4164 29 4165 2228 4165 27 4165 27 4166 2228 4166 2235 4166 27 4167 2235 4167 2236 4167 2236 4168 2235 4168 2234 4168 2236 4169 2234 4169 2250 4169 2250 4170 2234 4170 2233 4170 2250 4171 2233 4171 2232 4171 2249 4172 2246 4172 2247 4172 2247 4173 2246 4173 2245 4173 2247 4174 2245 4174 2252 4174 2252 4175 2245 4175 2253 4175 2254 4176 2255 4176 2256 4176 2255 4177 2253 4177 2256 4177 2256 4178 2253 4178 2245 4178 2256 4179 2245 4179 2257 4179 2257 4180 2245 4180 2241 4180 2257 4181 2241 4181 2238 4181 2238 4182 2241 4182 2240 4182 2238 4183 2240 4183 2239 4183 2239 4184 2240 4184 2242 4184 2221 4185 2218 4185 2238 4185 2238 4186 2218 4186 2236 4186 2238 4187 2236 4187 2257 4187 2257 4188 2236 4188 2250 4188 2257 4189 2250 4189 2256 4189 2256 4190 2250 4190 2251 4190 2256 4191 2251 4191 2254 4191 2254 4192 2251 4192 2230 4192 2254 4193 2230 4193 2229 4193 2258 4194 2259 4194 2260 4194 2261 4195 2262 4195 2263 4195 2202 4196 2197 4196 2264 4196 2226 4197 2217 4197 2227 4197 2227 4198 2217 4198 2216 4198 2216 4199 2220 4199 2227 4199 2227 4200 2220 4200 2222 4200 2227 4201 2222 4201 2265 4201 2266 4202 2267 4202 2268 4202 2264 4203 2197 4203 2269 4203 2191 4204 2267 4204 2189 4204 2189 4205 2267 4205 2266 4205 2189 4206 2266 4206 2188 4206 2188 4207 2266 4207 2269 4207 2188 4208 2269 4208 2186 4208 2186 4209 2269 4209 2197 4209 2186 4210 2197 4210 1430 4210 2262 4211 2270 4211 2263 4211 2263 4212 2270 4212 2207 4212 2263 4213 2207 4213 2264 4213 2264 4214 2207 4214 2208 4214 2264 4215 2208 4215 2202 4215 2260 4216 2259 4216 2271 4216 2271 4217 2259 4217 2272 4217 2271 4218 2272 4218 2261 4218 2273 4219 68 4219 67 4219 67 4220 2274 4220 2273 4220 2273 4221 2274 4221 2275 4221 2273 4222 2275 4222 2260 4222 2260 4223 2275 4223 2276 4223 2260 4224 2276 4224 2258 4224 68 4225 2277 4225 70 4225 70 4226 2277 4226 2278 4226 70 4227 2278 4227 72 4227 2248 4228 2279 4228 2280 4228 2280 4229 2279 4229 2281 4229 2280 4230 2281 4230 2277 4230 2277 4231 2281 4231 2282 4231 2277 4232 2282 4232 2278 4232 2243 4233 2244 4233 2283 4233 2283 4234 2244 4234 2246 4234 2283 4235 2246 4235 2280 4235 2280 4236 2246 4236 2249 4236 2280 4237 2249 4237 2248 4237 2243 4238 2283 4238 2242 4238 2242 4239 2283 4239 2284 4239 2242 4240 2284 4240 2239 4240 2239 4241 2284 4241 2285 4241 2239 4242 2285 4242 2237 4242 2222 4243 2225 4243 2265 4243 2265 4244 2225 4244 2224 4244 2265 4245 2224 4245 2285 4245 2285 4246 2224 4246 2223 4246 2285 4247 2223 4247 2237 4247 2261 4248 2263 4248 2271 4248 2271 4249 2263 4249 2264 4249 2271 4250 2264 4250 2286 4250 2286 4251 2264 4251 2269 4251 2286 4252 2269 4252 2287 4252 2287 4253 2269 4253 2266 4253 2287 4254 2266 4254 2288 4254 2288 4255 2266 4255 2268 4255 2288 4256 2268 4256 2289 4256 68 4257 2273 4257 2277 4257 2277 4258 2273 4258 2260 4258 2277 4259 2260 4259 2280 4259 2280 4260 2260 4260 2271 4260 2280 4261 2271 4261 2283 4261 2283 4262 2271 4262 2286 4262 2283 4263 2286 4263 2284 4263 2284 4264 2286 4264 2287 4264 2284 4265 2287 4265 2285 4265 2285 4266 2287 4266 2288 4266 2285 4267 2288 4267 2265 4267 2265 4268 2288 4268 2289 4268 2265 4269 2289 4269 2227 4269 2290 1482 1453 1482 2291 1482 2291 4270 1453 4270 1452 4270 2291 1482 1452 1482 2292 1482 2292 1482 1452 1482 1469 1482 2292 1482 1469 1482 2293 1482 2293 1482 1469 1482 1472 1482 2293 4271 1472 4271 2294 4271 2294 1482 1472 1482 1475 1482 1459 4272 2295 4272 1473 4272 1473 1482 2295 1482 2296 1482 1473 4273 2296 4273 1474 4273 1474 1482 2296 1482 2297 1482 1474 4274 2297 4274 1475 4274 1475 1482 2297 1482 2298 1482 1475 1482 2298 1482 2294 1482 1443 1530 1445 1530 1442 1530 1442 1530 1445 1530 1447 1530 1442 1530 1447 1530 1450 1530 2299 1530 1454 1530 2300 1530 2300 1530 1454 1530 1442 1530 2300 4275 1442 4275 2290 4275 2290 4276 1442 4276 1450 4276 2290 1530 1450 1530 1453 1530 2301 4277 2302 4277 2303 4277 2304 4278 2305 4278 2306 4278 2306 4279 2305 4279 2303 4279 2306 4280 2303 4280 2307 4280 2307 4281 2303 4281 2302 4281 2301 4282 2303 4282 2308 4282 2308 4283 2303 4283 2309 4283 2308 4284 2309 4284 2310 4284 2310 4285 2309 4285 2311 4285 2310 4286 2311 4286 2312 4286 2312 4287 2311 4287 2313 4287 2312 4288 2313 4288 2314 4288 2307 4289 2315 4289 2316 4289 2317 4290 2304 4290 2316 4290 2316 4291 2304 4291 2306 4291 2316 4292 2306 4292 2307 4292 2318 4293 2319 4293 2320 4293 2320 4294 2319 4294 2321 4294 2322 4295 2323 4295 2324 4295 2324 4296 2323 4296 2325 4296 2324 4297 2325 4297 2326 4297 2326 4298 2325 4298 2327 4298 2326 4299 2327 4299 2318 4299 2318 4300 2327 4300 2328 4300 2318 4301 2328 4301 2319 4301 2315 4302 2322 4302 2316 4302 2316 4303 2322 4303 2324 4303 2316 4304 2324 4304 2317 4304 2317 4305 2324 4305 2329 4305 59 4306 58 4306 2321 4306 2321 4307 58 4307 1454 4307 1454 4306 2299 4306 2314 4306 1454 4308 2314 4308 2321 4308 2321 4309 2314 4309 2304 4309 2321 4310 2304 4310 2317 4310 2311 4311 2309 4311 2303 4311 2324 4312 2326 4312 2329 4312 2329 4313 2326 4313 2318 4313 2329 4314 2318 4314 2317 4314 2317 4315 2318 4315 2320 4315 2317 4316 2320 4316 2321 4316 2314 4317 2313 4317 2304 4317 2304 4318 2313 4318 2311 4318 2304 4319 2311 4319 2305 4319 2305 4320 2311 4320 2303 4320 2330 1482 2331 1482 2074 1482 2074 1482 2331 1482 2073 1482 2332 4321 2333 4321 2334 4321 2334 4322 2333 4322 2335 4322 2334 4323 2335 4323 2336 4323 1456 4324 1455 4324 2337 4324 2337 4325 1455 4325 2334 4325 2073 4326 2331 4326 1455 4326 1455 4327 2331 4327 2338 4327 1455 4328 2338 4328 2334 4328 2334 4329 2338 4329 2339 4329 2334 4330 2339 4330 2332 4330 2340 4331 2341 4331 2342 4331 2343 4332 2344 4332 2345 4332 2343 4333 2345 4333 2346 4333 2346 4334 2345 4334 2347 4334 2346 4335 2347 4335 2348 4335 2348 4336 2347 4336 2349 4336 2349 4337 2347 4337 2350 4337 2349 4338 2350 4338 2351 4338 2351 4339 2350 4339 2352 4339 2351 4340 2352 4340 2353 4340 2337 4341 2334 4341 2354 4341 2354 4342 2334 4342 2336 4342 2354 4343 2336 4343 2355 4343 1459 4344 1457 4344 2295 4344 2295 4345 1457 4345 2356 4345 2295 4346 2356 4346 2296 4346 2296 4347 2356 4347 2297 4347 2297 4348 2356 4348 2357 4348 2297 4349 2357 4349 2298 4349 2298 4350 2357 4350 2294 4350 2294 4351 2357 4351 2342 4351 2294 4352 2342 4352 2293 4352 2293 4353 2342 4353 2292 4353 2292 4354 2342 4354 2341 4354 2292 4355 2341 4355 2291 4355 2358 4356 2359 4356 2360 4356 2345 4357 2358 4357 2347 4357 2347 4358 2358 4358 2360 4358 2347 4359 2360 4359 2350 4359 2350 4360 2360 4360 2361 4360 2350 4361 2361 4361 2352 4361 2352 4362 2361 4362 2354 4362 2352 4363 2354 4363 2353 4363 2353 4364 2354 4364 2355 4364 2359 4365 2340 4365 2360 4365 2360 4366 2340 4366 2342 4366 2360 4367 2342 4367 2361 4367 2361 4368 2342 4368 2357 4368 2361 4369 2357 4369 2354 4369 2354 4370 2357 4370 2356 4370 2354 4371 2356 4371 2337 4371 2337 4372 2356 4372 1457 4372 2337 4373 1457 4373 1456 4373 2279 4374 2248 4374 2247 4374 2325 4375 2282 4375 2327 4375 2327 4376 2282 4376 2281 4376 2327 4377 2281 4377 2328 4377 2323 4378 72 4378 2325 4378 2325 4379 72 4379 2278 4379 2325 4380 2278 4380 2282 4380 2307 4381 73 4381 2315 4381 2315 4382 73 4382 72 4382 2315 4383 72 4383 2322 4383 2322 4384 72 4384 2323 4384 2307 4385 2302 4385 73 4385 73 4386 2302 4386 2301 4386 73 4387 2301 4387 2362 4387 2362 4388 2301 4388 2308 4388 2362 4389 2308 4389 2363 4389 2363 4390 2308 4390 2310 4390 2363 4391 2310 4391 2364 4391 2364 4392 2310 4392 2365 4392 2365 4393 2310 4393 2312 4393 2365 4394 2312 4394 2344 4394 2290 4395 2291 4395 2300 4395 2300 4396 2291 4396 2341 4396 2312 4397 2314 4397 2299 4397 2341 4398 2340 4398 2300 4398 2300 4399 2340 4399 2359 4399 2300 4400 2359 4400 2299 4400 2299 4401 2359 4401 2358 4401 2299 4402 2358 4402 2312 4402 2312 4403 2358 4403 2345 4403 2312 4404 2345 4404 2344 4404 59 4405 2252 4405 61 4405 61 4406 2252 4406 2253 4406 59 4407 2321 4407 2252 4407 2252 4408 2321 4408 2319 4408 2252 4409 2319 4409 2247 4409 2247 4410 2319 4410 2328 4410 2247 4411 2328 4411 2279 4411 2279 4412 2328 4412 2281 4412 2229 4413 60 4413 2254 4413 2254 4414 60 4414 61 4414 2254 4398 61 4398 2255 4398 2255 4399 61 4399 2253 4399 2124 4415 2125 4415 2366 4415 2085 4416 2367 4416 2083 4416 2083 4417 2367 4417 2126 4417 2083 4418 2126 4418 1333 4418 2118 4419 2368 4419 2369 4419 2118 4420 2369 4420 2091 4420 2369 4421 2370 4421 2091 4421 2091 4422 2370 4422 2371 4422 2091 4423 2371 4423 2089 4423 2089 4424 2371 4424 2372 4424 2089 4425 2372 4425 2087 4425 2087 4426 2372 4426 2373 4426 2087 4427 2373 4427 2085 4427 2085 4428 2373 4428 2374 4428 2085 4429 2374 4429 2367 4429 2118 4430 2119 4430 2368 4430 2368 4431 2119 4431 2120 4431 2368 4432 2120 4432 2375 4432 2375 4433 2120 4433 2121 4433 2366 4434 2376 4434 2124 4434 2124 4435 2376 4435 2377 4435 2124 4436 2377 4436 2123 4436 2123 4437 2377 4437 2378 4437 2123 4438 2378 4438 2122 4438 2122 4439 2378 4439 2379 4439 2122 4440 2379 4440 2121 4440 2121 4441 2379 4441 2380 4441 2121 4442 2380 4442 2375 4442 2381 4443 2382 4443 2383 4443 2384 4444 2126 4444 2367 4444 2382 4445 2384 4445 2385 4445 2386 4446 2387 4446 2381 4446 2387 4447 2386 4447 2388 4447 2384 4448 2367 4448 2385 4448 2385 4449 2367 4449 2374 4449 2385 4450 2374 4450 2389 4450 2389 4451 2374 4451 2373 4451 2389 4452 2373 4452 2390 4452 2390 4453 2373 4453 2372 4453 2390 4454 2372 4454 2391 4454 2372 4455 2371 4455 2391 4455 2391 4456 2371 4456 2370 4456 2391 4457 2370 4457 2392 4457 2392 4458 2370 4458 2369 4458 2392 4459 2369 4459 2393 4459 2393 4460 2369 4460 2368 4460 2393 4461 2368 4461 2394 4461 2368 4462 2375 4462 2394 4462 2394 4463 2375 4463 2380 4463 2394 4464 2380 4464 2395 4464 2395 4465 2380 4465 2379 4465 2395 4466 2379 4466 2396 4466 2396 4467 2379 4467 2378 4467 2396 4468 2378 4468 2397 4468 2397 4469 2378 4469 2377 4469 2382 4470 2385 4470 2383 4470 2383 4471 2385 4471 2389 4471 2383 4472 2389 4472 2398 4472 2398 4473 2389 4473 2390 4473 2398 4474 2390 4474 2399 4474 2399 4475 2390 4475 2391 4475 2399 4476 2391 4476 2400 4476 2400 4477 2391 4477 2392 4477 2400 4478 2392 4478 2401 4478 2401 4479 2392 4479 2393 4479 2401 4480 2393 4480 2402 4480 2402 4481 2393 4481 2394 4481 2402 4482 2394 4482 2403 4482 2403 4483 2394 4483 2395 4483 2403 4484 2395 4484 2404 4484 2404 4485 2395 4485 2396 4485 2404 4486 2396 4486 2405 4486 2405 4487 2396 4487 2397 4487 2405 4488 2397 4488 2406 4488 2381 4489 2383 4489 2386 4489 2386 4490 2383 4490 2398 4490 2386 4491 2398 4491 2407 4491 2407 4492 2398 4492 2399 4492 2407 4493 2399 4493 2408 4493 2408 4494 2399 4494 2400 4494 2408 4495 2400 4495 2409 4495 2409 4496 2400 4496 2401 4496 2409 4497 2401 4497 2410 4497 2410 4498 2401 4498 2402 4498 2410 4499 2402 4499 2411 4499 2411 4500 2402 4500 2403 4500 2411 4501 2403 4501 2412 4501 2412 4502 2403 4502 2404 4502 2412 4503 2404 4503 2413 4503 2413 4504 2404 4504 2405 4504 2413 4505 2405 4505 2414 4505 2414 4506 2405 4506 2406 4506 2414 4507 2406 4507 2415 4507 2388 4508 2386 4508 2416 4508 2416 4509 2386 4509 2407 4509 2416 4510 2407 4510 2417 4510 2417 4511 2407 4511 2408 4511 2417 4512 2408 4512 2418 4512 2418 4513 2408 4513 2409 4513 2418 4514 2409 4514 2419 4514 2419 4515 2409 4515 2410 4515 2419 4516 2410 4516 2420 4516 2420 4517 2410 4517 2411 4517 2420 4518 2411 4518 2421 4518 2421 4519 2411 4519 2412 4519 2421 4520 2412 4520 2422 4520 2422 4521 2412 4521 2413 4521 2422 4522 2413 4522 2423 4522 2423 4523 2413 4523 2414 4523 2423 4524 2414 4524 2424 4524 2424 4525 2414 4525 2415 4525 2424 4526 2415 4526 66 4526 2425 4527 2376 4527 2366 4527 2397 4528 2377 4528 2376 4528 2376 4529 2425 4529 2397 4529 2397 4530 2425 4530 2426 4530 2397 4531 2426 4531 2406 4531 2406 4532 2426 4532 2427 4532 2406 4533 2427 4533 2415 4533 64 4534 66 4534 2415 4534 2415 4535 2427 4535 64 4535 64 4536 2427 4536 2428 4536 64 4537 2428 4537 62 4537 2366 4538 2429 4538 2425 4538 2425 4539 2429 4539 2430 4539 2425 4540 2430 4540 2426 4540 2426 4541 2430 4541 2431 4541 2426 4542 2431 4542 2427 4542 2427 4543 2431 4543 2432 4543 2427 4544 2432 4544 2428 4544 2135 4545 2433 4545 2128 4545 2128 4545 2433 4545 2366 4545 2128 4545 2366 4545 2125 4545 2213 4546 2214 4546 2434 4546 2215 4547 2212 4547 2435 4547 2209 4548 2210 4548 2436 4548 2211 4549 2207 4549 2270 4549 2211 4550 2270 4550 2210 4550 2209 4551 2436 4551 2212 4551 2215 4552 2435 4552 2214 4552 2437 4553 2438 4553 2439 4553 2439 4554 2438 4554 2440 4554 2439 4555 2440 4555 2434 4555 2434 4556 2440 4556 2183 4556 2434 4557 2183 4557 2213 4557 2441 4558 2442 4558 2443 4558 2443 4559 2442 4559 2444 4559 2443 4560 2444 4560 2445 4560 2445 4561 2444 4561 2446 4561 2445 4562 2446 4562 2437 4562 2437 4563 2446 4563 2447 4563 2437 4564 2447 4564 2438 4564 2210 4565 2270 4565 2436 4565 2436 4566 2270 4566 2262 4566 2436 4567 2262 4567 2448 4567 2448 4568 2262 4568 2261 4568 2448 4569 2261 4569 2449 4569 2449 4570 2261 4570 2272 4570 2449 4571 2272 4571 2450 4571 2450 4572 2272 4572 2259 4572 2450 4573 2259 4573 2451 4573 2451 4574 2259 4574 2258 4574 2451 4575 2258 4575 2452 4575 2452 4576 2258 4576 2276 4576 2452 4577 2276 4577 2453 4577 2453 4578 2276 4578 2275 4578 2453 4579 2275 4579 2454 4579 2454 4580 2275 4580 2274 4580 2454 4581 2274 4581 2455 4581 2212 4582 2436 4582 2435 4582 2435 4583 2436 4583 2448 4583 2435 4584 2448 4584 2456 4584 2456 4585 2448 4585 2449 4585 2456 4586 2449 4586 2457 4586 2457 4587 2449 4587 2450 4587 2457 4588 2450 4588 2458 4588 2458 4589 2450 4589 2451 4589 2458 4590 2451 4590 2459 4590 2459 4591 2451 4591 2452 4591 2459 4592 2452 4592 2460 4592 2460 4593 2452 4593 2453 4593 2460 4594 2453 4594 2461 4594 2461 4595 2453 4595 2454 4595 2461 4596 2454 4596 2462 4596 2462 4597 2454 4597 2455 4597 2462 4598 2455 4598 2463 4598 2214 4599 2435 4599 2434 4599 2434 4600 2435 4600 2456 4600 2434 4601 2456 4601 2439 4601 2439 4602 2456 4602 2457 4602 2439 4603 2457 4603 2437 4603 2437 4604 2457 4604 2458 4604 2437 4605 2458 4605 2445 4605 2445 4606 2458 4606 2459 4606 2445 4607 2459 4607 2443 4607 2443 4608 2459 4608 2460 4608 2443 4609 2460 4609 2441 4609 2441 4610 2460 4610 2461 4610 2441 4611 2461 4611 2464 4611 2464 4612 2461 4612 2462 4612 2464 4613 2462 4613 2465 4613 2465 4614 2462 4614 2463 4614 2465 4615 2463 4615 2466 4615 2467 4616 2468 4616 2466 4616 2466 4617 2468 4617 2469 4617 2466 4618 2469 4618 2465 4618 2465 4619 2469 4619 2470 4619 2465 4620 2470 4620 2464 4620 2464 4621 2470 4621 2471 4621 2464 4622 2471 4622 2441 4622 2441 4623 2471 4623 2472 4623 2441 4624 2472 4624 2442 4624 2473 4625 2467 4625 2474 4625 2474 4626 2467 4626 2466 4626 2474 4627 2466 4627 2475 4627 2475 4628 2466 4628 2463 4628 2475 4629 2463 4629 2476 4629 2476 4630 2463 4630 2455 4630 2476 4631 2455 4631 67 4631 67 4632 2455 4632 2274 4632 1390 4633 2183 4633 2139 4633 2139 4634 2183 4634 2440 4634 2139 4635 2440 4635 2141 4635 2141 4636 2440 4636 2438 4636 2141 4637 2438 4637 2143 4637 2143 4638 2438 4638 2447 4638 2143 4639 2447 4639 2446 4639 2143 4640 2446 4640 2146 4640 2146 4641 2446 4641 2444 4641 2146 4642 2444 4642 2147 4642 2152 4643 2471 4643 2470 4643 2152 4644 2470 4644 2154 4644 2444 4645 2442 4645 2147 4645 2147 4646 2442 4646 2472 4646 2147 4647 2472 4647 2149 4647 2149 4648 2472 4648 2471 4648 2149 4649 2471 4649 2151 4649 2151 4650 2471 4650 2152 4650 2433 4651 2135 4651 2477 4651 2477 4652 2135 4652 2160 4652 2477 4653 2160 4653 2473 4653 2473 4654 2160 4654 2158 4654 2473 4655 2158 4655 2467 4655 2467 4656 2158 4656 2156 4656 2467 4657 2156 4657 2468 4657 2468 4658 2156 4658 2154 4658 2468 4659 2154 4659 2469 4659 2469 4660 2154 4660 2470 4660 71 4661 62 4661 2478 4661 2478 4662 62 4662 2428 4662 2478 4663 2428 4663 2479 4663 2430 4664 2480 4664 2431 4664 2431 4665 2480 4665 2479 4665 2431 4665 2479 4665 2432 4665 2432 4666 2479 4666 2428 4666 2366 4667 2433 4667 2429 4667 2429 4667 2433 4667 2481 4667 2429 4668 2481 4668 2430 4668 2430 4669 2481 4669 2482 4669 2430 4664 2482 4664 2480 4664 2483 4670 69 4670 71 4670 2476 4671 67 4671 69 4671 69 4672 2483 4672 2476 4672 2476 4673 2483 4673 2484 4673 2476 4674 2484 4674 2475 4674 2475 4675 2484 4675 2485 4675 2475 4676 2485 4676 2474 4676 2477 4677 2473 4677 2474 4677 2474 4678 2485 4678 2477 4678 2477 4679 2485 4679 2481 4679 2477 4680 2481 4680 2433 4680 71 4681 2478 4681 2483 4681 2483 4682 2478 4682 2479 4682 2483 4683 2479 4683 2484 4683 2484 4684 2479 4684 2480 4684 2484 4685 2480 4685 2485 4685 2485 4686 2480 4686 2482 4686 2485 4687 2482 4687 2481 4687 2486 4688 2487 4688 2488 4688 2488 4689 2487 4689 2489 4689 2488 4690 2489 4690 2490 4690 2490 4691 2489 4691 2491 4691 2490 4692 2491 4692 2492 4692 2492 4693 2491 4693 2493 4693 2492 4694 2493 4694 2494 4694 2494 4695 2493 4695 2495 4695 2494 4696 2495 4696 2127 4696 2127 4697 2495 4697 1478 4697 2388 4698 2486 4698 2387 4698 2387 4699 2486 4699 2488 4699 2387 4700 2488 4700 2381 4700 2381 4701 2488 4701 2490 4701 2381 4702 2490 4702 2382 4702 2382 4703 2490 4703 2492 4703 2382 4704 2492 4704 2384 4704 2384 4705 2492 4705 2494 4705 2384 4706 2494 4706 2126 4706 2126 4707 2494 4707 2127 4707 935 4708 1479 4708 2496 4708 1484 4709 955 4709 1480 4709 2497 4710 1497 4710 2498 4710 2498 4711 1497 4711 1498 4711 2498 4712 1498 4712 2499 4712 2499 4713 1498 4713 1499 4713 2499 4714 1499 4714 2500 4714 2500 4715 1499 4715 1500 4715 2500 4716 1500 4716 2496 4716 2496 4717 1500 4717 1484 4717 2496 4718 1484 4718 935 4718 935 4719 1484 4719 1480 4719 2487 4720 2497 4720 2489 4720 2489 4721 2497 4721 2498 4721 2489 4722 2498 4722 2491 4722 2491 4723 2498 4723 2499 4723 2491 4724 2499 4724 2493 4724 2493 4725 2499 4725 2500 4725 2493 4726 2500 4726 2495 4726 2495 4727 2500 4727 2496 4727 2495 4728 2496 4728 1478 4728 1478 4729 2496 4729 1479 4729 1493 4730 1492 4730 2501 4730 1492 4731 1497 4731 2502 4731 1518 4732 1503 4732 2503 4732 2503 4733 1503 4733 1502 4733 2503 4734 1502 4734 2504 4734 1518 4735 1512 4735 1503 4735 1503 4736 1512 4736 1509 4736 1503 4737 1509 4737 1506 4737 1506 4738 1509 4738 991 4738 1527 4739 1523 4739 2503 4739 2503 4740 1523 4740 1519 4740 2503 4741 1519 4741 1518 4741 1527 4742 2503 4742 1524 4742 1524 4743 2503 4743 2504 4743 1524 4744 2504 4744 1521 4744 1521 4745 2504 4745 2505 4745 1521 4746 2505 4746 1522 4746 1492 4747 2502 4747 2501 4747 2501 4748 2502 4748 2506 4748 2501 4749 2506 4749 2507 4749 1502 4750 1493 4750 2504 4750 2504 4751 1493 4751 2501 4751 2504 4752 2501 4752 2505 4752 2505 4753 2501 4753 2507 4753 2505 4754 2507 4754 2508 4754 1724 4755 1840 4755 1789 4755 1724 73 1789 73 1740 73 1740 4756 1789 4756 1786 4756 1740 4757 1786 4757 1739 4757 1739 4758 1786 4758 1783 4758 1739 4759 1783 4759 1741 4759 1553 73 1542 73 1956 73 1956 73 1542 73 1544 73 1956 73 1544 73 1957 73 1956 73 1954 73 1553 73 1553 4760 1954 4760 1953 4760 1553 4761 1953 4761 1960 4761 2051 73 1531 73 1993 73 1993 73 1531 73 1529 73 1741 73 1783 73 1745 73 1745 73 1783 73 1785 73 1745 73 1785 73 1747 73 1747 73 1785 73 1825 73 1747 73 1825 73 1753 73 1753 73 1825 73 1828 73 1753 73 1828 73 1759 73 1814 4762 1815 4762 1652 4762 1960 4763 1962 4763 1553 4763 1553 73 1962 73 2042 73 1553 73 2042 73 1574 73 2192 4764 1763 4764 1828 4764 1828 4765 1763 4765 1761 4765 1828 4766 1761 4766 1759 4766 1544 73 1555 73 1957 73 1957 73 1555 73 1556 73 1957 73 1556 73 2049 73 2049 4767 1556 4767 1557 4767 2049 73 1557 73 2050 73 2050 73 1557 73 1748 73 2050 4768 1748 4768 2051 4768 2051 73 1748 73 1536 73 2051 4769 1536 4769 1531 4769 1529 73 1520 73 1993 73 1993 4770 1520 4770 1522 4770 1993 73 1522 73 1933 73 1933 73 1522 73 2505 73 1933 4771 2505 4771 1932 4771 1828 4772 1829 4772 2192 4772 2192 4773 1829 4773 1781 4773 2192 4774 1781 4774 2190 4774 2190 73 1781 73 1780 73 2190 73 1780 73 2191 73 2191 73 1780 73 1779 73 2191 73 1779 73 2267 73 2267 73 1779 73 1778 73 2267 4775 1778 4775 2268 4775 2268 73 1778 73 1773 73 2268 73 1773 73 2289 73 2289 73 1773 73 1772 73 2289 73 1772 73 2227 73 1652 4776 1815 4776 1655 4776 1655 73 1815 73 1817 73 1655 4777 1817 4777 1656 4777 1656 73 1817 73 1819 73 1656 73 1819 73 1681 73 1652 4778 1651 4778 1814 4778 1814 4779 1651 4779 1649 4779 1814 4780 1649 4780 1922 4780 1922 4781 1649 4781 1648 4781 1922 4782 1648 4782 1940 4782 1940 4783 1648 4783 1615 4783 1940 4784 1615 4784 1941 4784 2509 73 2065 73 2510 73 2510 4785 2065 4785 2057 4785 2510 4786 2057 4786 2511 4786 2511 73 2057 73 2056 73 2511 4787 2056 4787 2512 4787 2512 73 2056 73 1932 73 2512 4788 1932 4788 2508 4788 2508 4789 1932 4789 2505 4789 1681 4790 1819 4790 1682 4790 1682 4791 1819 4791 1821 4791 1682 73 1821 73 1684 73 1941 4792 1615 4792 2037 4792 2037 4793 1615 4793 1613 4793 2037 73 1613 73 2042 73 2042 4794 1613 4794 1612 4794 2042 73 1612 73 1623 73 1678 4795 1700 4795 1840 4795 1840 73 1700 73 1699 73 1840 73 1699 73 1821 73 1821 4796 1699 4796 1685 4796 1821 4797 1685 4797 1684 4797 1623 4798 1621 4798 2042 4798 2042 73 1621 73 1620 73 2042 4799 1620 4799 1636 4799 1636 73 1637 73 2042 73 2042 4800 1637 4800 1619 4800 2042 4801 1619 4801 1618 4801 1724 4802 1725 4802 1840 4802 1840 4803 1725 4803 1659 4803 1840 4804 1659 4804 1658 4804 1658 73 1676 73 1840 73 1840 4805 1676 4805 1680 4805 1840 73 1680 73 1678 73 1618 73 1646 73 2042 73 2042 4806 1646 4806 1647 4806 2042 4807 1647 4807 1598 4807 1598 73 1594 73 2042 73 2042 4808 1594 4808 1573 4808 2042 4809 1573 4809 1574 4809 2065 4810 2509 4810 2064 4810 2064 4811 2509 4811 2330 4811 2068 4812 1242 4812 2072 4812 2072 4813 1242 4813 2060 4813 2072 4814 2060 4814 2071 4814 2060 4815 2061 4815 2071 4815 2071 4816 2061 4816 2063 4816 2071 4817 2063 4817 2070 4817 2070 4818 2063 4818 2064 4818 2070 4819 2064 4819 2069 4819 2069 4820 2064 4820 2330 4820 2069 4821 2330 4821 2074 4821 2416 4822 2417 4822 2513 4822 2331 4823 2330 4823 2338 4823 2338 4824 2330 4824 2509 4824 2338 4825 2509 4825 2339 4825 2339 4826 2509 4826 2332 4826 2355 4827 2336 4827 2514 4827 2514 4828 2336 4828 2335 4828 2514 4829 2335 4829 2515 4829 2515 4830 2335 4830 2333 4830 2515 4831 2333 4831 2332 4831 2346 4832 2348 4832 2516 4832 2516 4833 2348 4833 2349 4833 2516 4834 2349 4834 2517 4834 2517 4835 2349 4835 2351 4835 2517 4836 2351 4836 2514 4836 2514 4837 2351 4837 2353 4837 2514 4838 2353 4838 2355 4838 2346 4839 2516 4839 2343 4839 2343 4840 2516 4840 2518 4840 2343 4841 2518 4841 2344 4841 2362 4842 2363 4842 2519 4842 2519 4843 2363 4843 2364 4843 2519 4844 2364 4844 2518 4844 2518 4845 2364 4845 2365 4845 2518 4846 2365 4846 2344 4846 63 4847 2520 4847 65 4847 65 4848 2520 4848 2424 4848 65 4849 2424 4849 66 4849 2420 4850 2421 4850 2521 4850 2521 4851 2421 4851 2422 4851 2521 4852 2422 4852 2520 4852 2520 4853 2422 4853 2423 4853 2520 4854 2423 4854 2424 4854 2420 4855 2521 4855 2419 4855 2419 4856 2521 4856 2522 4856 2419 4857 2522 4857 2418 4857 2523 4858 2486 4858 2513 4858 2513 4859 2486 4859 2388 4859 2513 4860 2388 4860 2416 4860 2502 4861 1497 4861 2524 4861 2524 4862 1497 4862 2497 4862 2524 4863 2497 4863 2523 4863 2523 4864 2497 4864 2487 4864 2523 4865 2487 4865 2486 4865 2502 4866 2524 4866 2506 4866 2506 4867 2524 4867 2525 4867 2506 4868 2525 4868 2507 4868 2332 4869 2509 4869 2515 4869 2515 4870 2509 4870 2510 4870 2515 4871 2510 4871 2511 4871 2508 4872 2507 4872 2512 4872 2512 4873 2507 4873 2525 4873 2512 4874 2525 4874 2526 4874 2526 4875 2525 4875 2524 4875 2526 4876 2524 4876 2527 4876 2527 4877 2524 4877 2523 4877 2527 4878 2523 4878 2528 4878 2528 4879 2523 4879 2513 4879 2528 4880 2513 4880 2522 4880 2522 4881 2513 4881 2417 4881 2522 4882 2417 4882 2418 4882 73 4883 2362 4883 63 4883 63 4884 2362 4884 2519 4884 63 4885 2519 4885 2520 4885 2520 4886 2519 4886 2518 4886 2520 4887 2518 4887 2521 4887 2521 4888 2518 4888 2516 4888 2521 4889 2516 4889 2522 4889 2522 4890 2516 4890 2517 4890 2522 4891 2517 4891 2528 4891 2528 4892 2517 4892 2514 4892 2528 4893 2514 4893 2527 4893 2527 4894 2514 4894 2515 4894 2527 4895 2515 4895 2526 4895 2526 4896 2515 4896 2511 4896 2526 4897 2511 4897 2512 4897 45 69 52 69 37 69 37 69 52 69 38 69 38 1296 52 1296 39 1296 39 1296 52 1296 54 1296 39 1296 54 1296 56 1296 2529 69 2530 69 2531 69 2531 69 2530 69 2532 69 2531 4898 2532 4898 2533 4898 2533 69 2532 69 2534 69 2535 1530 2536 1530 2537 1530 2535 4899 2537 4899 2538 4899 2538 1530 2537 1530 2539 1530 2538 1530 2539 1530 2540 1530 2541 1482 2542 1482 2540 1482 2543 1482 2538 1482 2540 1482 2543 1482 2540 1482 2544 1482 2545 1482 2541 1482 2546 1482 2546 1482 2541 1482 2540 1482 2546 1482 2540 1482 2547 1482 2542 1482 2548 1482 2540 1482 2540 4900 2548 4900 2549 4900 2540 1482 2549 1482 2544 1482 2550 4901 2536 4901 2535 4901 2535 4902 2551 4902 2550 4902 2550 4903 2551 4903 2552 4903 2550 4904 2552 4904 2553 4904 2553 4905 2554 4905 2550 4905 2550 4906 2554 4906 2555 4906 2550 4907 2555 4907 2556 4907 2557 4908 2558 4908 2559 4908 2560 4909 2561 4909 2557 4909 2557 4910 2561 4910 2562 4910 2557 4911 2562 4911 2558 4911 2536 4912 2550 4912 2534 4912 2534 4913 2550 4913 2557 4913 2534 4914 2557 4914 2533 4914 2533 4915 2557 4915 2559 4915 2533 4916 2559 4916 2563 4916 2564 4917 2565 4917 2566 4917 2564 4918 2566 4918 2567 4918 2567 4919 2566 4919 2568 4919 2567 4920 2568 4920 2569 4920 2569 4921 2568 4921 2557 4921 2557 4922 2568 4922 2570 4922 2557 4923 2570 4923 2560 4923 2560 4924 2570 4924 2561 4924 2561 4925 2570 4925 2571 4925 2561 4926 2571 4926 2562 4926 2562 4927 2571 4927 2572 4927 2562 4928 2572 4928 2558 4928 2558 4929 2572 4929 2573 4929 2558 4930 2573 4930 2559 4930 2573 4931 2574 4931 2559 4931 2559 4932 2574 4932 2575 4932 2559 4933 2575 4933 2563 4933 2531 4934 2533 4934 2576 4934 2576 4935 2533 4935 2563 4935 2576 4936 2563 4936 2577 4936 2577 4937 2563 4937 2575 4937 2569 4938 2557 4938 2578 4938 2578 4939 2557 4939 2550 4939 2538 4940 2579 4940 2535 4940 2535 4941 2579 4941 2551 4941 2579 4942 2580 4942 2551 4942 2551 4943 2580 4943 2581 4943 2551 4944 2581 4944 2552 4944 2552 4945 2581 4945 2582 4945 2552 4946 2582 4946 2553 4946 2553 4947 2582 4947 2583 4947 2553 4948 2583 4948 2554 4948 2554 4949 2583 4949 2584 4949 2554 4950 2584 4950 2555 4950 2555 4951 2584 4951 2585 4951 2555 4952 2585 4952 2556 4952 2585 4953 2586 4953 2556 4953 2556 4954 2586 4954 2587 4954 2556 4955 2587 4955 2550 4955 2588 4956 2589 4956 2590 4956 2590 4957 2589 4957 2591 4957 2590 4958 2591 4958 2587 4958 2587 4959 2591 4959 2578 4959 2587 4960 2578 4960 2550 4960 2542 4961 2541 4961 2592 4961 2592 4962 2541 4962 2593 4962 2593 4963 2541 4963 2594 4963 2594 4964 2541 4964 2545 4964 2594 4965 2545 4965 2595 4965 2595 4966 2545 4966 2596 4966 2596 4967 2545 4967 2546 4967 2596 4968 2546 4968 2597 4968 2597 4969 2546 4969 2598 4969 2598 4970 2546 4970 2547 4970 2598 4971 2547 4971 2599 4971 2599 4972 2547 4972 2600 4972 2600 4973 2547 4973 2540 4973 2600 4974 2540 4974 2539 4974 2601 1482 2602 1482 2603 1482 2531 1482 2604 1482 2529 1482 2529 1482 2604 1482 2605 1482 2529 1482 2605 1482 2606 1482 2603 1482 2607 1482 2601 1482 2601 1482 2607 1482 2529 1482 2601 1482 2529 1482 2608 1482 2608 4975 2529 4975 2606 4975 2608 1482 2606 1482 2609 1482 2610 4976 2579 4976 2538 4976 2611 4977 2612 4977 2613 4977 2612 4978 2611 4978 2585 4978 2614 4979 2585 4979 2611 4979 2585 4980 2615 4980 2616 4980 2617 4981 2615 4981 2585 4981 2618 4982 2588 4982 2590 4982 2619 4983 2620 4983 2618 4983 2620 4984 2619 4984 2621 4984 2621 4985 2619 4985 2622 4985 2621 4986 2622 4986 2623 4986 2623 4987 2622 4987 2624 4987 2624 4988 2622 4988 2625 4988 2624 4989 2625 4989 2626 4989 2626 4990 2625 4990 2627 4990 2627 4991 2625 4991 2628 4991 2627 4992 2628 4992 2629 4992 2630 4993 2631 4993 2628 4993 2628 4994 2631 4994 2632 4994 2628 4995 2632 4995 2629 4995 2584 4996 2612 4996 2585 4996 2633 4997 2616 4997 2634 4997 2634 4998 2616 4998 2615 4998 2634 4999 2615 4999 2635 4999 2635 5000 2615 5000 2617 5000 2635 5001 2617 5001 2636 5001 2619 5002 2633 5002 2622 5002 2622 5003 2633 5003 2634 5003 2622 5004 2634 5004 2625 5004 2625 5005 2634 5005 2635 5005 2625 5006 2635 5006 2628 5006 2628 5007 2635 5007 2636 5007 2628 5008 2636 5008 2630 5008 2618 5009 2590 5009 2619 5009 2619 5010 2590 5010 2587 5010 2619 5011 2587 5011 2633 5011 2633 5012 2587 5012 2586 5012 2633 5013 2586 5013 2616 5013 2616 5014 2586 5014 2585 5014 2584 5015 2583 5015 2612 5015 2612 5016 2583 5016 2582 5016 2612 5017 2582 5017 2613 5017 2613 5018 2582 5018 2581 5018 2613 5019 2581 5019 2580 5019 2614 5020 2611 5020 2637 5020 2637 5021 2611 5021 2613 5021 2637 5022 2613 5022 2610 5022 2610 5023 2613 5023 2580 5023 2610 5024 2580 5024 2579 5024 2544 5025 2549 5025 2630 5025 2630 5026 2549 5026 2548 5026 2630 5027 2548 5027 2631 5027 2543 5028 2544 5028 2638 5028 2638 5029 2544 5029 2630 5029 2638 5030 2630 5030 2639 5030 2639 5031 2630 5031 2636 5031 2639 5032 2636 5032 2640 5032 2640 5033 2636 5033 2617 5033 2640 5034 2617 5034 2585 5034 2538 5035 2543 5035 2610 5035 2610 5036 2543 5036 2638 5036 2610 5037 2638 5037 2637 5037 2637 5038 2638 5038 2639 5038 2637 5039 2639 5039 2614 5039 2614 5040 2639 5040 2640 5040 2614 5041 2640 5041 2585 5041 2589 5042 2641 5042 2591 5042 2591 5043 2641 5043 2642 5043 2591 5044 2642 5044 2578 5044 2578 5045 2642 5045 2643 5045 2578 5046 2643 5046 2569 5046 2643 5047 2644 5047 2569 5047 2569 5048 2644 5048 2645 5048 2569 5049 2645 5049 2567 5049 2567 5050 2645 5050 2564 5050 2577 5051 2575 5051 2646 5051 2647 5020 2648 5020 2649 5020 2574 5052 2573 5052 2650 5052 2648 5053 2647 5053 2571 5053 2571 5054 2651 5054 2650 5054 2652 4981 2651 4981 2571 4981 2653 5055 2654 5055 2655 5055 2656 5056 2609 5056 2606 5056 2657 5057 2658 5057 2659 5057 2659 5058 2658 5058 2660 5058 2660 5059 2658 5059 2661 5059 2660 5060 2661 5060 2662 5060 2653 5061 2655 5061 2663 5061 2575 5062 2574 5062 2646 5062 2646 5063 2574 5063 2650 5063 2646 5064 2650 5064 2664 5064 2664 5065 2650 5065 2651 5065 2664 4999 2651 4999 2665 4999 2665 5000 2651 5000 2652 5000 2665 5001 2652 5001 2666 5001 2667 5022 2649 5022 2668 5022 2668 5066 2649 5066 2648 5066 2668 5067 2648 5067 2669 5067 2669 5068 2648 5068 2571 5068 2576 5069 2577 5069 2670 5069 2670 5070 2577 5070 2646 5070 2670 5071 2646 5071 2671 5071 2671 5072 2646 5072 2664 5072 2671 5073 2664 5073 2657 5073 2657 5074 2664 5074 2665 5074 2657 5006 2665 5006 2658 5006 2658 5075 2665 5075 2666 5075 2658 5076 2666 5076 2661 5076 2573 5077 2572 5077 2650 5077 2650 5078 2572 5078 2571 5078 2654 5079 2662 5079 2655 5079 2655 5080 2662 5080 2661 5080 2655 5081 2661 5081 2672 5081 2672 5082 2661 5082 2666 5082 2672 5083 2666 5083 2673 5083 2673 5033 2666 5033 2652 5033 2673 5084 2652 5084 2571 5084 2571 5085 2570 5085 2669 5085 2669 5086 2570 5086 2568 5086 2669 5087 2568 5087 2668 5087 2668 5088 2568 5088 2566 5088 2668 5089 2566 5089 2667 5089 2667 5090 2566 5090 2565 5090 2667 5091 2565 5091 2674 5091 2659 5092 2656 5092 2657 5092 2657 5093 2656 5093 2606 5093 2657 5094 2606 5094 2671 5094 2671 5095 2606 5095 2605 5095 2671 5096 2605 5096 2670 5096 2670 5097 2605 5097 2604 5097 2670 5098 2604 5098 2576 5098 2576 5099 2604 5099 2531 5099 2674 5100 2663 5100 2667 5100 2667 5101 2663 5101 2655 5101 2667 5102 2655 5102 2649 5102 2649 5103 2655 5103 2672 5103 2649 5104 2672 5104 2647 5104 2647 5105 2672 5105 2673 5105 2647 5106 2673 5106 2571 5106 2530 5107 2529 5107 2675 5107 2675 5108 2529 5108 2607 5108 2603 5109 2676 5109 2607 5109 2607 5110 2676 5110 2677 5110 2607 5111 2677 5111 2675 5111 2602 5112 2678 5112 2603 5112 2603 5113 2678 5113 2679 5113 2603 5114 2679 5114 2676 5114 2601 5115 2680 5115 2602 5115 2602 5116 2680 5116 2681 5116 2602 5117 2681 5117 2678 5117 2608 5118 2682 5118 2601 5118 2601 5119 2682 5119 2683 5119 2601 5120 2683 5120 2680 5120 2684 1296 2537 1296 2536 1296 2534 5121 2532 5121 2685 5121 2534 1296 2685 1296 2536 1296 2536 5122 2685 5122 2686 5122 2536 5123 2686 5123 2644 5123 2644 1296 2643 1296 2536 1296 2536 5124 2643 5124 2687 5124 2536 5125 2687 5125 2684 5125 2609 5126 2656 5126 2685 5126 2653 5127 2663 5127 2688 5127 2663 5128 2674 5128 2688 5128 2688 5129 2674 5129 2565 5129 2688 5130 2565 5130 2564 5130 2660 5131 2688 5131 2659 5131 2659 5132 2688 5132 2656 5132 2660 5133 2662 5133 2688 5133 2688 5134 2662 5134 2654 5134 2688 5135 2654 5135 2653 5135 2683 5136 2682 5136 2689 5136 2689 5137 2682 5137 2608 5137 2689 5138 2608 5138 2609 5138 2678 5139 2681 5139 2689 5139 2689 5140 2681 5140 2680 5140 2689 5141 2680 5141 2683 5141 2677 5142 2676 5142 2689 5142 2689 5143 2676 5143 2679 5143 2689 5144 2679 5144 2678 5144 2685 5145 2532 5145 2609 5145 2609 5146 2532 5146 2530 5146 2609 5147 2530 5147 2689 5147 2689 5148 2530 5148 2675 5148 2689 5149 2675 5149 2677 5149 2656 5150 2688 5150 2685 5150 2685 5151 2688 5151 2564 5151 2685 5152 2564 5152 2686 5152 2686 5153 2564 5153 2645 5153 2686 5154 2645 5154 2644 5154 2690 5155 2539 5155 2537 5155 2539 5156 2690 5156 2600 5156 2597 5157 2598 5157 2690 5157 2690 5158 2598 5158 2599 5158 2690 5159 2599 5159 2600 5159 2542 5160 2592 5160 2690 5160 2690 5161 2592 5161 2593 5161 2690 5162 2593 5162 2594 5162 2594 5163 2595 5163 2690 5163 2690 5164 2595 5164 2596 5164 2690 5165 2596 5165 2597 5165 2542 5166 2690 5166 2548 5166 2548 5167 2690 5167 2537 5167 2548 5168 2537 5168 2631 5168 2631 5169 2537 5169 2684 5169 2631 5170 2684 5170 2632 5170 2621 5171 2623 5171 2684 5171 2684 5172 2623 5172 2624 5172 2684 5173 2624 5173 2626 5173 2588 5174 2618 5174 2684 5174 2684 5175 2618 5175 2620 5175 2684 5176 2620 5176 2621 5176 2626 5177 2627 5177 2684 5177 2684 5178 2627 5178 2629 5178 2684 5179 2629 5179 2632 5179 2643 5180 2642 5180 2687 5180 2687 5181 2642 5181 2641 5181 2687 5182 2641 5182 2684 5182 2684 5183 2641 5183 2589 5183 2684 5184 2589 5184 2588 5184

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_distal/pst/f_distal_pst_scaled.dae b/URDFs/sr_description/meshes/components/f_distal/pst/f_distal_pst_scaled.dae new file mode 100644 index 0000000..eb347e8 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_distal/pst/f_distal_pst_scaled.dae @@ -0,0 +1,210 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:57:59 + 2025-02-20T09:57:59 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + 5.945692 0.8807764 9.412343 5.382925 0.898676 9.58211 5.382925 1.933097 9.394129 6.223668 4.060254 8.074912 6.403651 4.060254 7.945047 6.464344 3.625828 8.188947 6.597695 -0.08824235 9.0738 6.464349 -0.08824235 9.168315 6.464344 0.851709 9.136651 6.211555 -0.08824235 9.319918 5.790171 -0.08824235 9.505183 5.347561 -0.006456792 9.625772 5.347561 0.8993905 9.588887 5.347561 1.934813 9.400726 5.347561 2.399235 9.262718 5.154873 -0.08824235 9.652868 5.017525 -0.07535904 9.666588 5.0406 -0.08824235 9.664362 4.809813 -0.08822762 9.674206 5.752034 -0.08824235 9.518275 5.713805 -0.08824235 9.530824 5.382926 -0.08824235 9.616543 5.268408 -0.08824235 9.637037 6.918948 0.8125907 8.765638 6.918948 -0.08824235 8.794965 6.670776 -0.08824235 9.017167 6.634411 -0.08824235 9.045798 6.705648 4.160254 7.593876 6.918948 4.160254 7.34358 6.732038 4.060254 7.644284 6.918948 3.429767 7.871547 4.930185 4.060254 8.508028 5.345967 4.060254 8.450965 5.382925 3.861227 8.570034 5.450549 4.060254 8.425292 4.797667 3.891519 8.619072 4.797667 4.060254 8.511529 4.954567 2.949046 9.103474 4.954567 3.575116 8.798735 4.797667 3.583639 8.798735 5.945692 2.860914 8.897274 5.945692 3.771514 8.424798 5.848971 4.060254 8.282502 5.945692 1.890123 9.228919 5.382925 2.928006 9.054245 4.954567 2.423588 9.303827 6.464344 1.820336 8.960628 6.464344 2.751964 8.642363 6.918948 3.132077 8.044244 6.918948 2.605341 8.299311 6.918948 1.989594 8.5249 6.918948 1.726419 8.599574 4.954567 2.124374 8.798735 5.347561 1.933508 8.476542 4.751871 2.124374 8.798735 4.751871 1.933508 8.476542 4.751871 3.583639 8.798735 4.751871 4.060254 8.511529 4.751871 5.899752 6.126949 4.751871 6.066366 6.408202 4.751871 4.060254 8.303976 4.751871 5.288287 7.316349 -1.327033 7 19.49808 -3.060204 7 9.41948 -1.775689 7 19.53072 -2.622437 7 15.36004 -2.214897 7 19.62794 2.214897 7 19.62794 2.622437 7 15.36004 1.775689 7 19.53072 3.060204 7 9.41948 1.327033 7 19.49808 3.301439 7 4.690659 -3.301439 7 4.690659 7.409198 -5.044097 10.95987 7.675558 -4.636781 10.97141 7.56628 -4.593151 12.54953 4.544294 -3.48954 27.95967 4.425046 -3.572317 27.9699 4.613974 -4.464362 25.25258 4.860114 -3.24747 27.92537 4.666408 -3.400033 27.9477 5.025582 -4.176249 25.2269 6.768665 -5.870833 9.578129 6.853719 -5.790407 9.578129 6.768332 -5.785943 10.92859 3.37807 -7.005693 15.61588 2.639572 -7.080649 15.37719 2.792885 -7.239518 13.26165 2.353519 -5.300773 25.19717 1.650072 -5.169334 25.82216 1.876208 -5.699678 23.75961 6.849242 -0.8382434 26.02167 6.564346 -0.8382444 27.39294 6.538761 -0.9085474 27.41168 7.056926 -1.039119 24.64834 7.184607 -0.8382434 24.05127 7.134574 -0.8382434 24.37563 6.906937 -0.8382434 25.71376 6.775689 -1.91429 24.84456 6.434336 -1.168257 27.4796 7.40628 -1.72615 21.65596 7.52238 -0.8382434 21.48734 7.295902 -0.8382434 23.28368 7.721099 -2.253849 18.63151 7.831041 -1.348024 18.50573 7.532857 -0.8382434 21.39535 7.597508 -0.8382434 20.80796 7.687474 -0.9937543 19.9516 7.834091 -1.228641 18.48804 8.105918 -1.588751 15.49647 8.078191 -1.55735 15.82151 8.103631 -1.708951 15.5078 7.891332 -1.313322 17.89093 8.399657 -1.818454 11.66296 8.341572 -1.790805 12.48858 8.339889 -1.911478 12.49349 8.247734 -1.725787 13.74503 8.532424 -1.956052 9.578129 8.533742 -1.835226 9.578129 8.240139 -2.826638 12.52445 8.434974 -2.872103 9.578129 8.418227 -2.955714 9.578129 7.982685 -3.730448 12.54358 8.179079 -3.776905 9.578129 8.074433 -4.034098 9.578129 7.763466 -4.640661 9.578129 7.518364 -5.017387 9.578129 7.496384 -5.04809 9.578129 4.640649 -7.065033 10.80736 3.749466 -7.273374 10.75177 4.718754 -7.070525 9.578129 3.824205 -7.279222 9.578129 5.396618 -2.744528 27.83822 5.043921 -3.089547 27.90004 5.400794 -3.861563 25.18977 3.819394 -3.929961 28.00212 3.443062 -4.105739 28.00751 3.718538 -4.928741 25.26568 1.409256 -4.561158 27.88089 2.251762 -4.466187 27.96284 2.40792 -4.434545 27.97361 3.246242 -5.099187 25.25296 2.881237 -4.310656 27.99744 3.156627 -4.218401 28.00496 4.04141 -3.810268 27.9939 4.182221 -4.713344 25.2655 3.913126 -5.317681 23.69151 3.441285 -5.489255 23.67715 3.627042 -5.837088 22.09021 2.54886 -5.692175 23.62144 2.734884 -6.0412 22.03456 2.088848 -6.156466 21.6806 2.169224 -6.316998 20.85289 4.837169 -7.030786 9.578129 5.651069 -6.67137 9.578129 5.110165 -6.888877 10.83567 5.569636 -6.666262 10.86264 5.457154 -6.621098 12.48206 5.883829 -6.36397 12.50209 5.760965 -6.275982 14.11485 6.166787 -5.97888 14.12623 6.033937 -5.848636 15.72965 6.403193 -5.524847 15.72984 6.260737 -5.352935 17.32281 6.601002 -4.998525 17.31007 6.449534 -4.785802 18.88946 6.757449 -4.405199 18.86202 6.597112 -4.151852 20.42952 6.86956 -3.750757 20.38613 6.701252 -3.458119 21.93614 7.132586 -2.612286 21.80884 4.807035 -4.850229 23.68531 4.376136 -5.100858 23.69424 4.560845 -5.44641 22.11191 4.09846 -5.664507 22.10625 4.273945 -5.968455 20.51344 3.802912 -6.141921 20.49569 3.968875 -6.404008 18.89231 2.910992 -6.347079 20.4401 3.07716 -6.610067 18.83675 2.287267 -6.539055 19.58867 2.4709 -6.847066 17.48731 5.860761 -6.551706 9.578129 6.485106 -6.115911 9.578129 5.995974 -6.408939 10.88691 6.400855 -6.111172 10.90918 6.28914 -6.066428 12.5189 6.657116 -5.741445 12.53187 6.535357 -5.654378 14.13279 6.873948 -5.298146 14.13483 6.742569 -5.169398 15.72447 7.048396 -4.786285 15.71361 6.907818 -4.61653 17.29089 7.177757 -4.212202 17.26562 7.028584 -4.002343 18.82767 7.453918 -3.148439 18.74034 5.568453 -2.552519 27.80057 5.746962 -3.516109 25.14101 5.591603 -4.243442 23.63373 5.217593 -4.560209 23.66477 5.400527 -4.902585 22.0917 4.99095 -5.194309 22.10702 5.165127 -5.495847 20.52125 4.735755 -5.74924 20.52207 4.900845 -6.009603 18.92341 4.439558 -6.229781 18.91178 4.594707 -6.44778 17.30628 4.124334 -6.622643 17.28507 4.269471 -6.798275 15.67142 3.232792 -6.829456 17.22953 2.526677 -6.930149 16.81096 7.191922 -5.433094 9.578129 7.105661 -5.428914 10.94554 6.995024 -5.384685 12.54136 7.299209 -5.000159 12.54725 7.178896 -4.914188 14.13233 7.446801 -4.507781 14.12538 7.317257 -4.380773 15.69748 7.737605 -3.521239 15.65062 6.135067 -1.757671 27.62549 6.087799 -1.836681 27.64409 6.337395 -2.749656 25.01114 6.060335 -3.143767 25.08115 6.24826 -3.520895 23.54018 5.936403 -3.8957 23.59204 6.116937 -4.234175 22.03226 5.773415 -4.583958 22.0668 5.945647 -4.882367 20.49249 5.573798 -5.202628 20.51119 5.737386 -5.46059 18.92195 5.329545 -5.755096 18.92671 5.483617 -5.971362 17.32837 5.055521 -6.226797 17.32093 5.199967 -6.401269 15.71208 4.739571 -6.622899 15.69438 4.873851 -6.754849 14.07827 4.403986 -6.930613 14.05354 4.52776 -7.019569 12.43168 3.512691 -7.138488 13.998 3.636538 -7.227751 12.37612 2.93051 -7.323558 11.14468 7.999361 -2.620749 15.58641 4.997429 -6.843545 12.45819 5.333884 -6.532732 14.09904 5.627523 -6.145085 15.72369 5.890705 -5.675778 17.32895 6.108282 -5.138922 18.90951 6.287987 -4.530791 20.46516 6.427376 -3.857168 21.98848 6.523675 -3.124176 23.47895 3.022275 -7.337747 9.578129 3.731443 -7.292057 9.578129 3.008818 -7.338223 9.817255 -3.072391 -7.338224 9.817255 -3.085847 -7.337748 9.578129 -2.993602 -7.323429 11.15198 -2.85483 -7.238256 13.28362 -2.700413 -7.077454 15.4117 -2.590202 -6.930182 16.81097 -2.530801 -6.841482 17.53088 -2.347622 -6.533279 19.62374 -2.15005 -6.151819 21.70368 -1.938422 -5.696867 23.77142 -1.713384 -5.168828 25.82398 -1.472827 -4.561158 27.88089 -8.597314 -1.83523 9.578129 -8.597314 -1.83523 7.078129 -8.551948 -2.540075 7.078129 -3.085847 -7.337758 7.078129 -4.208706 -7.222321 7.078129 -3.887715 -7.27923 9.578129 -4.208706 -7.222321 9.578129 -4.782263 -7.070545 9.578129 -5.28894 -6.878933 7.078129 -5.28894 -6.878933 9.578129 -5.714605 -6.671461 9.578129 -6.274815 -6.322885 7.078129 -6.274815 -6.322885 9.578129 -6.548485 -6.115791 9.578129 -7.12938 -5.574058 7.078129 -7.811481 -4.666581 9.578129 -7.811481 -4.666581 7.078129 -7.255558 -5.433313 9.578129 -7.12938 -5.574058 9.578129 -7.826932 -4.640722 9.578129 -8.242614 -3.777038 9.578129 -8.290879 -3.644159 7.078129 -8.290879 -3.644159 9.578129 -8.498516 -2.872271 9.578129 -8.551948 -2.540075 9.578129 3.022275 -7.337758 7.078129 8.418227 -2.955714 7.078129 8.533742 -1.835226 7.078129 8.074433 -4.034098 7.078129 7.518364 -5.017387 7.078129 6.768665 -5.870833 7.078129 5.860761 -6.551706 7.078129 4.837169 -7.030786 7.078129 3.731443 -7.292057 7.078129 8.17397 -0.6977844 7.482397 8.17397 -0.08824235 7.550877 8.481558 -0.08824253 7.189874 8.17397 -1.969029 7.078129 8.17397 -1.782742 7.161715 8.362395 -1.427725 7.078129 8.17397 -1.399552 7.306003 8.490324 -0.8233345 7.078129 8.533749 -0.4703438 7.078129 8.533751 -0.08824235 7.115426 8.533755 -0.08824235 9.578129 6.931097 -2.969094 7.954782 7.337186 -3.522063 7.078289 6.931097 -3.664423 7.484299 6.931097 -4.134725 7.078129 6.931097 -2.21675 8.327363 7.810259 -2.717897 7.07829 6.931097 -0.08824235 8.79496 6.931097 -0.5966123 8.753588 6.931097 -1.421093 8.595258 4.809815 -1.106446 9.564442 4.809815 -0.7037166 9.625679 5.337192 -0.6980218 9.579307 5.697256 -0.08824235 9.540188 5.957461 -0.08824235 9.445881 5.95784 -0.6758812 9.399029 6.147774 -0.08824235 9.359309 6.560995 -0.08824235 9.11024 6.525144 -0.6380416 9.090925 6.751517 -0.08824235 8.960838 5.337192 -4.885377 7.505612 5.452544 -5.240106 7.078131 5.031429 -5.319861 7.078127 6.525144 -3.873445 7.752293 6.525144 -4.533277 7.161894 6.613018 -4.525976 7.077945 6.276119 -4.825913 7.07801 6.525144 -1.507564 8.923944 6.525144 -2.346687 8.641415 6.525144 -3.14013 8.248479 5.226351 -0.08824235 9.645574 5.463801 -0.08824235 9.602568 5.019552 -0.08824235 9.66702 4.809815 -1.644639 9.444988 5.337192 -1.632753 9.399806 4.809815 -2.381929 9.207324 5.337192 -2.534805 9.096087 4.809815 -2.552666 9.139259 4.809815 -3.411262 8.714056 5.337192 -3.387752 8.673686 4.809815 -3.568886 8.619509 5.337192 -4.176061 8.140291 4.809815 -4.204793 8.177126 4.809815 -4.626007 7.821457 4.809815 -4.918807 7.538246 4.809815 -5.330459 7.078129 5.878339 -5.073657 7.078112 5.95784 -4.755406 7.378734 5.95784 -4.064356 7.997066 5.95784 -3.296347 8.51673 5.95784 -2.465364 8.928255 5.95784 -1.586541 9.22415 7.979336 -0.08824235 16.94112 7.855496 -0.08824235 18.26673 7.72437 -0.08824235 19.59165 7.656075 -0.08824235 20.25383 7.58596 -0.08824235 20.91583 7.514027 -0.08824235 21.57762 7.495759 -0.08824235 21.74304 7.477377 -0.08824235 21.90845 7.370319 -0.411726 22.85186 7.440274 -0.08824235 22.23922 7.211302 -0.08824235 24.19634 6.955816 -0.08824235 26.06418 6.770204 -0.08824282 27.18408 6.976333 -0.5193955 25.63024 7.091054 -0.08824235 25.13136 6.438498 -0.4972802 28.16033 6.410623 -0.2977833 28.36717 5.954716 -0.8969662 28.96951 6.503186 -0.8052113 27.67819 1.83966 -2.19501 31.02784 1.905184 -2.808226 30.54377 2.825188 -2.633377 30.47324 5.842165 -0.08824235 29.55855 5.892456 -0.2292674 29.42948 6.16076 -0.08824235 29.02445 4.956505 -0.08824235 30.57374 5.233312 -0.1310495 30.29548 5.391071 -0.08824235 30.13862 3.296534 -0.08824235 31.58801 3.5921 -0.5696616 31.32991 4.036254 -0.477996 31.12729 1.381365 -3.066587 30.33552 1.384732 -3.361448 30.02076 1.980662 -3.350085 29.98466 1.386974 -3.530325 29.81816 1.393729 -3.943052 29.23156 2.064654 -3.811831 29.36057 1.407971 -4.521831 28.00122 2.155622 -4.185884 28.68231 1.401165 -4.281672 28.60204 1.397963 -4.147402 28.87361 1.372302 -1.999091 31.17849 1.374066 -2.235394 31.02416 1.37483 -2.332438 30.95607 1.376745 -2.564413 30.78123 1.379346 -2.860252 30.53094 1.363771 -0.08824336 31.94696 1.365578 -0.748411 31.76638 1.507744 -0.08824235 31.94503 1.743553 -0.7982292 31.73569 2.722634 -0.08824235 31.77261 2.646364 -0.08824235 31.79192 2.670627 -0.7118836 31.61309 2.119141 -0.08824235 31.8937 4.862172 -0.2574213 30.60717 4.475513 -0.08824235 30.95683 4.461473 -0.3735435 30.88557 4.38639 -0.08824235 31.01855 3.855502 -0.08824235 31.33561 5.595377 -0.4232168 29.77233 6.419332 -0.08824235 28.45645 6.619069 -0.08824235 27.85546 6.681744 -0.08824235 27.61163 1.368475 -1.390035 31.50889 1.785401 -1.521119 31.42778 2.762529 -2.047154 30.93617 3.734981 -2.345379 30.27609 6.390044 -0.08824235 28.5298 6.366811 -0.08824235 28.58602 5.920653 -0.5788114 29.22142 5.666288 -1.183909 29.24859 5.627494 -0.8214558 29.53541 5.340101 -1.457193 29.5075 5.296802 -1.05255 29.82756 4.979365 -1.713095 29.74255 4.93185 -1.268946 30.09372 4.588224 -1.948241 29.95056 4.536836 -1.46779 30.33031 4.171598 -2.159757 30.12899 4.116727 -1.646651 30.53445 3.677056 -1.803617 30.70409 2.710644 -1.402936 31.31863 5.260955 -0.6079341 30.09195 4.89251 -0.7809022 30.38383 4.494287 -0.9398416 30.64404 4.071294 -1.082808 30.86942 3.629092 -1.208273 31.05768 5.777426 -0.08824235 29.65231 6.085017 -1.612097 28.00027 5.814654 -1.998507 28.14518 5.505668 -2.366524 28.27635 5.161035 -2.711132 28.39181 4.784684 -3.027791 28.48997 3.064685 -3.950425 28.69303 3.956403 -3.562594 28.63012 4.381356 -3.312627 28.56965 6.46954 -0.6673668 27.92935 6.037669 -1.417876 28.35352 5.99397 -1.178177 28.67847 5.760747 -1.777287 28.5473 5.710989 -1.504251 28.91724 5.445515 -2.11959 28.725 5.389988 -1.814805 29.13777 5.095035 -2.440121 28.88403 5.034108 -2.105605 29.33689 4.713314 -2.734654 29.0222 4.647426 -2.37282 29.51189 4.305158 -2.999589 29.13785 4.23481 -2.613181 29.66066 3.875969 -3.23209 29.22988 3.801709 -2.824117 29.78173 2.977689 -3.592824 29.34169 2.897367 -3.151391 29.93855 -1.439573 -2.468902 30.85548 -1.444087 -2.982178 30.41772 -1.468582 -4.432047 28.24873 -1.46429 -4.27236 28.62232 -1.461421 -4.148274 28.87211 -1.454993 -3.815833 29.42879 -1.448811 -3.400176 29.9759 -1.44832 -3.361458 30.02077 -1.427342 -0.08824336 31.94696 -1.429411 -0.7756451 31.75722 -1.432222 -1.368595 31.51897 -1.435664 -1.935867 31.21718 -1.437776 -2.235427 31.02424 -5.878225 -1.998507 28.14518 -5.56924 -2.366524 28.27635 -5.509087 -2.11959 28.725 -5.042937 -1.713095 29.74255 -5.403673 -1.457193 29.5075 -5.45356 -1.814805 29.13777 -2.593111 -4.406774 27.98101 -2.315334 -4.466189 27.96284 -2.219194 -4.185884 28.68231 -2.128225 -3.811831 29.36057 -1.903231 -2.19501 31.02784 -1.848973 -1.521119 31.42778 -5.295664 -0.08824235 30.30964 -5.296883 -0.1310493 30.29548 -4.925743 -0.2574212 30.60717 -6.793591 -0.08824235 27.39324 -6.833776 -0.08824199 27.18408 -6.786545 -0.3048996 27.24604 -6.45019 -0.08824235 28.5381 -6.662793 -0.08824235 27.92501 -6.474194 -0.2977831 28.36717 -6.683126 -0.08824235 27.85304 -6.502069 -0.4972799 28.16033 -6.743535 -0.08824235 27.61834 -6.533112 -0.6673664 27.92935 -6.566757 -0.805211 27.67819 -5.324527 -0.6079339 30.09195 -5.369163 -0.08824235 30.23261 -5.658949 -0.4232167 29.77233 -5.787003 -0.08824235 29.72795 -5.956027 -0.2292672 29.42948 -4.894724 -0.08824235 30.68247 -4.525045 -0.3735434 30.88557 -4.370967 -0.08824235 31.07191 -4.099826 -0.477996 31.12729 -3.809436 -0.08824235 31.3917 -3.655672 -0.5696616 31.32991 -3.209251 -0.08824235 31.64354 -2.734199 -0.7118836 31.61309 -2.710185 -0.08824235 31.79248 -2.584069 -0.08824235 31.82191 -1.807124 -0.7982292 31.73569 -1.946775 -0.08824235 31.92227 -2.044233 -3.350085 29.98466 -1.968756 -2.808226 30.54377 -2.888759 -2.633377 30.47324 -2.960938 -3.151391 29.93855 -3.798552 -2.345379 30.27609 -3.04126 -3.592824 29.34169 -3.865281 -2.824117 29.78173 -4.298381 -2.61318 29.66066 -4.23517 -2.159757 30.12899 -4.710998 -2.372819 29.51189 -4.651795 -1.948241 29.95056 -5.097679 -2.105605 29.33689 -3.417923 -4.142513 28.00731 -3.2202 -4.218403 28.00496 -3.128257 -3.950424 28.69303 -5.824318 -1.777287 28.5473 -5.77456 -1.504251 28.91724 -5.72986 -1.183909 29.24859 -3.939541 -3.23209 29.22988 -4.368729 -2.999589 29.13785 -4.776885 -2.734654 29.0222 -5.158607 -2.440121 28.88403 -6.148588 -1.612097 28.00027 -6.101241 -1.417875 28.35352 -6.057542 -1.178176 28.67847 -6.018288 -0.896966 28.96951 -5.224606 -2.711132 28.39181 -4.848255 -3.027791 28.48997 -4.444927 -3.312627 28.56965 -4.019974 -3.562594 28.63012 -3.597235 -4.066393 28.00715 -6.052672 -1.9926 27.68009 -5.935208 -2.164308 27.71857 -5.772458 -2.381446 27.76534 -5.454616 -2.750471 27.83935 -5.295188 -2.913428 27.8695 -4.60576 -3.491044 27.95986 -4.316299 -3.684341 27.9823 -4.104982 -3.81027 27.9939 -6.602612 -0.9077997 27.41148 -6.497852 -1.168388 27.47964 -6.198198 -1.758424 27.62566 -6.130749 -1.870232 27.65192 -5.984224 -0.5788112 29.22142 -5.691065 -0.8214557 29.53541 -5.360374 -1.05255 29.82756 -4.956081 -0.7809022 30.38383 -4.995421 -1.268946 30.09372 -4.557858 -0.9398415 30.64404 -4.600407 -1.46779 30.33031 -4.134865 -1.082808 30.86942 -4.180299 -1.646651 30.53445 -3.692663 -1.208273 31.05768 -3.740627 -1.803617 30.70409 -2.774215 -1.402936 31.31863 -2.8261 -2.047154 30.93617 -6.148711 -0.08824235 29.16411 -4.093137 -4.392574 26.44602 -3.336335 -6.881042 16.79677 -8.582077 -1.837235 9.829775 -3.73251 -7.244814 11.92506 -4.62372 -7.036583 11.98063 -7.661159 -4.609586 12.1113 -8.077126 -3.746648 12.11106 -8.433339 -1.927168 12.07391 -8.434952 -1.80632 12.06989 -8.453423 -1.814544 11.80518 -8.334095 -2.842586 12.09822 -7.932721 -1.404987 18.1102 -8.128832 -1.542247 15.97136 -8.201543 -1.74602 15.09803 -8.203745 -1.625598 15.08756 -8.300066 -1.716514 13.88981 -7.62803 -0.9044427 21.10304 -7.734696 -0.9660899 20.10943 -7.940246 -1.292045 18.04531 -7.289168 -0.2453325 24.06692 -7.512574 -0.5644667 22.16166 -7.631871 -0.7859132 21.07985 -6.979023 -0.08824235 26.32166 -7.274873 -0.08824235 24.19634 -7.294049 -0.1282604 24.0375 -2.263277 -4.976768 26.38102 -5.976007 -2.831667 26.23902 -6.254391 -2.439718 26.16242 -6.447891 -2.846451 24.63213 -3.628911 -4.606789 26.44837 -4.294675 -4.813399 24.87682 -4.726213 -4.563998 24.86488 -4.917817 -4.941013 23.28819 -5.328124 -4.650548 23.26897 -5.509453 -4.983685 21.68669 -5.88204 -4.664649 21.66338 -6.052439 -4.953313 20.08093 -6.394466 -4.601348 20.05549 -6.554065 -4.846302 18.47192 -6.861689 -4.465312 18.44668 -7.010024 -4.66633 16.86788 -7.279674 -4.261662 16.84505 -7.417037 -4.419623 15.26957 -3.156245 -4.776296 26.43689 -3.47931 -7.046191 15.17552 -3.611348 -7.167404 13.55213 -4.370681 -6.838644 15.23106 -4.502622 -6.95944 13.60767 -4.972431 -6.783598 13.63289 -5.093346 -6.860517 12.00764 -5.552997 -6.638012 12.03236 -6.384762 -6.083195 12.0719 -5.979575 -6.380816 12.05358 -5.859344 -6.304513 13.67149 -5.432377 -6.56138 13.65452 -5.301011 -6.441383 15.27303 -4.840715 -6.663156 15.2545 -4.698136 -6.499056 16.87398 -4.227839 -6.674064 16.85231 -4.074536 -6.466094 18.46742 -3.182868 -6.672356 18.41186 -4.525575 -4.144959 26.43012 -4.938028 -3.858426 26.40058 -5.137558 -4.275397 24.84047 -5.512439 -3.960207 24.80486 -5.701817 -4.333323 23.23948 -6.046267 -3.98508 23.19958 -6.22523 -4.314418 21.63069 -6.535332 -3.936897 21.58899 -6.703276 -4.221957 20.02198 -6.975383 -3.820382 19.98094 -7.132507 -4.062044 18.41472 -7.402845 -2.969191 19.87876 -7.557147 -3.207264 18.33272 -7.090282 -5.40133 12.09821 -6.752565 -5.758153 12.08666 -6.633393 -5.682648 13.69268 -6.265021 -6.007273 13.68435 -6.134683 -5.888389 15.29322 -5.728434 -6.185032 15.28579 -5.586785 -6.02224 16.89801 -5.158837 -6.277889 16.88945 -5.006295 -6.071292 18.49977 -4.545135 -6.291693 18.48734 -4.381554 -6.04067 20.09702 -3.910614 -6.214341 20.07883 -3.736644 -5.91946 21.68161 -3.018748 -6.419736 20.02324 -2.844548 -6.123843 21.62597 -8.097937 -2.658431 15.17018 -7.823572 -2.311751 18.22977 -7.512199 -1.802949 21.26948 -7.165569 -1.133007 24.2795 -5.314175 -3.545494 26.35891 -5.661413 -3.201965 26.30485 -5.858239 -3.614198 24.75785 -6.171237 -3.241229 24.69997 -6.357767 -3.609702 23.14976 -6.632795 -3.212375 23.09077 -6.808842 -3.537302 21.53894 -7.066647 -2.370187 22.9487 -7.239375 -2.690307 21.41675 -7.394287 -5.016703 12.10645 -7.276504 -4.942149 13.69657 -6.971766 -5.326282 13.69676 -6.84285 -5.208765 15.29179 -6.503717 -5.564415 15.29515 -6.363477 -5.403321 16.89559 -5.993689 -5.726408 16.90003 -5.842471 -5.52172 18.50082 -5.434833 -5.816527 18.50416 -5.27242 -5.567501 20.10668 -4.843226 -5.821196 20.10643 -4.670198 -5.528253 21.70451 -4.207962 -5.746646 21.69809 -4.024269 -5.409178 23.29264 -3.552536 -5.581011 23.27785 -3.358977 -5.19989 24.86315 -2.660179 -5.784235 23.22216 -2.466329 -5.401809 24.80738 -6.885296 -2.009667 24.47039 -7.836809 -3.55952 15.22826 -3.83116 -5.02916 24.87628 -4.487121 -5.192025 23.2961 -5.100112 -5.275808 21.70066 -5.680871 -5.27393 20.09799 -6.213103 -5.199751 18.49004 -6.703474 -5.048644 16.88483 -7.148437 -4.825402 15.28321 -7.544178 -4.535553 13.69215 -7.686217 -0.08824235 20.57162 -8.042908 -0.08824235 16.94112 -8.34818 -0.08824235 13.26174 -8.597325 -0.08824235 9.578129 -8.597325 -0.08824235 7.078129 -8.483146 -0.08824235 7.180051 -8.168598 -0.08824235 7.550877 -8.168598 -0.6977844 7.482397 -8.553288 -0.08824235 7.078129 -8.547694 -0.2113939 7.078094 -8.477173 -0.8719551 7.078065 -8.168598 -1.399552 7.306003 -8.35389 -1.438309 7.078017 -8.168598 -1.782742 7.161715 -8.168598 -1.969029 7.078129 -7.983261 -2.371874 7.078199 -6.925724 -2.26816 8.305825 -6.925724 -2.969094 7.954782 -7.562965 -3.145075 7.078345 -6.925724 -3.664423 7.484299 -6.925724 -4.134725 7.078129 -6.925724 -2.21675 8.327364 -6.925724 -1.421093 8.595258 -6.925724 -0.5966123 8.753589 -6.925724 -0.08824235 8.79496 -5.635664 -5.17794 7.077909 -5.228152 -5.291707 7.077913 -4.804443 -5.330459 7.078129 -6.376843 -4.741667 7.077982 -6.012434 -4.997968 7.078129 -8.565428 -0.08824318 7.078129 -8.590538 -0.08824235 7.078129 -6.699427 -4.425756 7.078042 5.201682 4.642155 28.68221 5.181868 4.679427 28.62958 5.169682 4.684452 28.64187 4.739017 5.01578 27.63524 4.897146 5.099009 27.61245 4.89678 5.155955 27.32065 4.53694 5.014604 27.35438 4.345454 5.05861 27.37851 4.39187 5.037373 27.70315 4.730847 5.048841 27.33403 4.562975 4.994306 27.66684 4.474855 4.998719 28.05454 4.618334 4.958541 28.00355 4.59036 4.943442 28.36084 4.702819 4.908709 28.29702 4.661199 4.908678 28.4949 4.75675 4.877892 28.42596 4.785756 4.845937 28.6679 4.853727 4.823091 28.59372 4.831528 4.822357 28.71547 4.889817 4.802753 28.6404 4.768718 4.96722 27.95762 4.822889 4.908712 28.23777 4.859799 4.87551 28.36111 4.928508 4.82017 28.52269 4.954577 4.800608 28.56817 5.019492 4.754338 28.65289 4.911089 5.023894 27.9213 4.941959 4.943452 28.18735 4.964234 4.901674 28.3042 5.006915 4.837297 28.45784 5.023369 4.816004 28.50148 5.064728 4.768656 28.58413 5.07559 4.75751 28.60025 5.113153 4.795145 28.52141 5.0936 4.848359 28.44285 5.085608 4.873744 28.40194 5.06386 4.954831 28.2586 5.051491 5.010436 28.14937 5.031324 5.122941 27.8982 5.016834 5.233189 27.60144 5.00873 5.319158 27.31634 5.134445 4.751601 28.575 5.125858 4.767263 28.55738 5.118205 4.783413 28.53711 5.257574 4.58889 28.79248 5.200693 4.626662 28.75678 5.22352 4.608504 28.81632 5.178712 4.639107 28.76806 5.1954 4.624573 28.83039 5.155438 4.652315 28.77562 5.165807 4.641359 28.8405 5.123942 4.670212 28.77968 5.125971 4.663755 28.84749 5.075865 4.69753 28.77413 5.065459 4.697343 28.84537 5.001754 4.739552 28.74149 4.972445 4.747961 28.81595 4.978706 4.75259 28.72579 4.943511 4.763461 28.80077 5.227071 4.611792 28.73684 5.182641 4.652127 28.69828 5.166646 4.66099 28.70683 5.149621 4.670804 28.71189 5.126484 4.684654 28.71313 5.091057 4.706794 28.70437 5.036435 4.742763 28.66897 5.15941 4.689836 28.64776 5.148456 4.696497 28.65044 5.133551 4.706814 28.64908 5.11072 4.724943 28.63753 5.145011 4.736279 28.58871 5.151966 4.728938 28.59236 5.157133 4.725144 28.59188 5.162043 4.723067 28.58852 5.167989 4.72293 28.57993 4.332 5.132484 24.55431 4.094648 5.168705 24.59378 4.219744 5.114768 25.63669 4.89309 5.319283 26.01085 4.857601 5.335042 25.58508 4.72647 5.138697 26.01705 4.69164 5.154637 25.59336 4.49429 5.059292 26.03116 4.46048 5.074809 25.61206 4.252655 5.100257 26.04975 4.783641 5.62912 24.51662 4.918426 5.572614 25.58922 4.953886 5.557412 26.01405 4.722769 5.393612 24.51055 4.559319 5.213879 24.52419 3.908841 5.245305 23.55397 4.141263 5.214398 23.50046 4.362976 5.298004 23.45933 4.522687 5.476781 23.44009 4.583445 5.709367 23.44721 4.998527 5.415966 26.90835 4.981938 5.489044 26.48268 4.902853 5.219899 26.90889 4.903032 5.269927 26.48153 4.733062 5.083126 26.91665 4.733634 5.110213 26.48747 4.521479 5.031687 26.93016 4.510495 5.044552 26.49918 4.308386 5.075375 26.94685 4.282028 5.087191 26.51415 7.991858 -0.08824235 16.8177 8.16182 -0.08824235 7.550899 8.234889 -0.08824604 7.475131 8.540534 -0.08824235 7.087223 8.540536 -0.08824235 9.518077 8.134237 -0.08824235 15.18051 7.838373 -0.08824235 18.45389 7.757468 -0.08824235 19.27159 7.673789 -0.08824235 20.089 7.587337 -0.08824235 20.90613 7.543072 -0.08824235 21.31458 7.498113 -0.08824235 21.72296 7.469332 -0.08824235 21.98111 7.79917 4.160254 6.118076 8.16346 3.659591 6.117929 7.067784 4.160254 7.147513 8.163154 3.357546 6.392996 8.162043 0.5348055 7.542771 8.162267 1.152223 7.456823 8.162443 1.623969 7.336422 8.16249 1.754045 7.29439 8.162714 2.330835 7.058022 8.162796 2.537936 6.951521 8.16293 2.85587 6.762875 1.841035 0.4365516 9.673192 1.841035 0.3006758 9.443826 1.841035 -0.08824235 9.674221 -4.804443 -0.7037166 9.625679 -4.804659 -0.08824235 9.674221 4.797667 -0.08824235 9.674221 -4.804443 -4.918807 7.538246 -4.804443 -4.626007 7.821457 -4.804443 -4.204793 8.177126 -4.804443 -3.568886 8.619509 -4.804443 -3.411262 8.714056 -4.804443 -2.552666 9.139259 -4.804443 -2.381929 9.207324 -4.804443 -1.644639 9.444988 -4.804443 -1.106446 9.564442 -6.698826 -0.08824235 9.000345 -6.505729 -0.08824235 9.145462 -6.519772 -0.6380416 9.090925 -6.087677 -0.08824235 9.385869 -5.863162 -0.08824235 9.481109 -5.952467 -0.6758812 9.399029 -4.816591 -0.08824241 9.674197 -5.952467 -4.755406 7.378734 -5.33182 -4.885377 7.505612 -5.33182 -4.176061 8.140291 -5.33182 -3.387752 8.673686 -5.33182 -2.534805 9.096087 -5.33182 -1.632753 9.399806 -5.221461 -0.08824235 9.645471 -5.161636 -0.08824235 9.653193 -5.33182 -0.6980218 9.579307 -4.919915 -0.08824068 9.67224 -5.633261 -0.08824235 9.557721 -5.399477 -0.08824235 9.615076 -5.281043 -0.08824235 9.636546 -6.301778 -0.08824235 9.27408 -6.519772 -1.507564 8.923947 -6.519772 -2.346687 8.641415 -6.519772 -3.14013 8.248479 -6.519772 -3.873445 7.752293 -6.519772 -4.533277 7.161894 -5.952467 -1.586541 9.22415 -5.952467 -2.465364 8.928255 -5.952467 -3.296347 8.51673 -5.952467 -4.064356 7.997066 -4.722769 5.393612 24.51055 -4.783641 5.62912 24.51662 -4.918426 5.572614 25.58922 -4.49429 5.059292 26.03116 -4.46048 5.074809 25.61206 -4.72647 5.138697 26.01705 -4.69164 5.154637 25.59336 -4.89309 5.319283 26.01085 -4.857601 5.335042 25.58508 -4.953886 5.557412 26.01405 -4.094648 5.168705 24.59378 -4.219744 5.114768 25.63669 -4.252655 5.100257 26.04975 -4.332 5.132484 24.55431 -4.559319 5.213879 24.52419 -4.583445 5.709367 23.44721 -4.522687 5.476781 23.44009 -4.362976 5.298004 23.45933 -4.141263 5.214398 23.50046 -3.908841 5.245305 23.55397 -4.308386 5.075375 26.94685 -4.282028 5.087191 26.51415 -4.521479 5.031687 26.93016 -4.510494 5.044552 26.49918 -4.733062 5.083126 26.91665 -4.733632 5.110211 26.48746 -4.902853 5.219899 26.90889 -4.90303 5.269923 26.48152 -4.998527 5.415966 26.90835 -4.981938 5.489044 26.48268 -4.345454 5.05861 27.37851 -4.53694 5.014604 27.35438 -4.730847 5.048841 27.33403 -4.89678 5.155955 27.32065 -5.00873 5.319158 27.31634 -5.201682 4.642155 28.68221 -5.227071 4.611792 28.73684 -5.200693 4.626662 28.75678 -5.016834 5.233189 27.60144 -4.897146 5.099009 27.61245 -5.031324 5.122941 27.8982 -4.911089 5.023894 27.9213 -5.051491 5.010436 28.14937 -4.941959 4.943452 28.18735 -5.06386 4.954831 28.2586 -4.964234 4.901674 28.3042 -5.085608 4.873744 28.40194 -5.006915 4.837297 28.45784 -5.0936 4.848359 28.44285 -5.023369 4.816004 28.50148 -5.113153 4.795145 28.52141 -5.064728 4.768656 28.58413 -5.118205 4.783413 28.53711 -5.07559 4.75751 28.60025 -5.125858 4.767263 28.55738 -5.11072 4.724943 28.63753 -5.134445 4.751601 28.575 -5.145011 4.736279 28.58871 -5.133551 4.706814 28.64908 -5.151966 4.728938 28.59236 -5.148456 4.696497 28.65044 -5.157133 4.725144 28.59188 -5.15941 4.689836 28.64776 -5.162043 4.723067 28.58852 -5.169682 4.684452 28.64187 -5.167989 4.72293 28.57993 -5.181868 4.679427 28.62958 -5.182641 4.652127 28.69828 -5.166646 4.66099 28.70683 -5.149621 4.670804 28.71189 -5.126484 4.684654 28.71313 -5.091057 4.706794 28.70437 -5.036435 4.742763 28.66897 -5.019492 4.754338 28.65289 -4.954577 4.800608 28.56817 -4.928508 4.82017 28.52269 -4.859799 4.87551 28.36111 -4.822889 4.908712 28.23777 -4.768718 4.96722 27.95762 -4.739017 5.01578 27.63524 -5.178712 4.639107 28.76806 -5.155438 4.652315 28.77562 -5.123942 4.670212 28.77968 -5.075865 4.69753 28.77413 -5.001754 4.739552 28.74149 -4.978706 4.75259 28.72579 -4.889817 4.802753 28.6404 -4.853727 4.823091 28.59372 -4.75675 4.877892 28.42596 -4.702819 4.908709 28.29702 -4.618334 4.958541 28.00355 -4.562975 4.994306 27.66684 -4.39187 5.037373 27.70315 -4.474855 4.998719 28.05454 -4.59036 4.943442 28.36084 -4.661199 4.908678 28.4949 -4.785756 4.845937 28.6679 -4.831528 4.822357 28.71547 -4.943511 4.763461 28.80077 -4.972445 4.747961 28.81595 -5.065459 4.697343 28.84537 -5.125971 4.663755 28.84749 -5.165807 4.641359 28.8405 -5.1954 4.624573 28.83039 -5.22352 4.608504 28.81632 -5.257574 4.58889 28.79248 2.526369 5.175535 30.80623 3.236579 4.961684 30.60563 2.490624 5.184874 30.99587 -3.236579 4.961684 30.60563 -2.527187 5.175398 30.80634 -2.490624 5.184874 30.99587 -2.241199 5.245616 30.8704 -1.688473 5.356421 31.28484 -1.782504 5.339851 30.95498 -0.844855 5.464247 31.46221 -1.026139 5.447213 31.05001 0 5.5 31.52036 -0.2612221 5.496588 31.09336 0 5.499998 31.09634 0.2077975 5.497796 31.09444 0.844855 5.464247 31.46221 0.9954622 5.450113 31.05261 1.688473 5.356421 31.28484 1.771881 5.341753 30.95639 2.145709 5.26707 30.88941 2.241125 5.245602 30.87003 -4.862604 4.771477 29.5275 -4.857738 4.741702 29.56633 -4.484885 4.928907 29.93561 -4.857101 4.737802 29.57141 -4.854477 4.704528 29.59206 -4.481842 4.854943 29.96969 -4.853491 4.667412 29.59977 -4.869098 4.789956 29.47452 -4.867965 4.786733 29.48376 -4.464345 4.988085 29.88337 -4.867126 4.784344 29.49061 -0.6869285 5.963276 31.55916 0 5.971604 31.62304 0 5.995923 31.56044 0 5.800218 31.72035 0 5.863906 31.70985 -0.3042767 5.795938 31.71332 -0.6912292 5.849408 31.67096 -3.362143 5.269895 30.8022 -3.283374 5.295079 30.84795 -3.377178 5.307687 30.78828 -2.672056 5.468787 31.15659 -2.756599 5.499691 31.111 -2.095444 5.597734 31.37967 -2.097005 5.658424 31.36921 -1.523992 5.693407 31.54236 -1.405415 5.776831 31.55739 -0.9627055 5.757641 31.64992 -0.7042499 5.777435 31.68275 -3.825206 5.108747 30.50217 -3.953422 5.090054 30.40627 -4.364194 4.890416 30.07639 -4.491527 4.833758 29.96164 -4.853475 4.661661 29.5999 0 5.927935 31.67405 -0.6910601 5.917913 31.62682 -1.405192 5.845813 31.51399 -2.09695 5.728148 31.32702 -2.756983 5.570348 31.0704 -3.37826 5.379398 30.74958 -3.955417 5.16288 30.36975 -1.396975 5.892302 31.44748 -2.085107 5.77642 31.26235 -2.742103 5.620921 31.00816 -3.360955 5.432637 30.69025 -3.936259 5.21902 30.31377 -4.880895 4.796605 29.37473 -4.427344 5.020947 29.82654 -3.9025 5.247827 30.25286 -3.331103 5.457592 30.62572 -2.716922 5.642364 30.94045 -2.065386 5.794856 31.19199 -1.383456 5.908421 31.37512 -0.9215472 5.959476 31.45633 -0.6801823 5.977941 31.48555 0 5.999992 31.52039 4.869098 4.789956 29.47452 4.880895 4.796605 29.37473 4.427344 5.020947 29.82654 0.1745681 5.798753 31.71805 0.7040879 5.777324 31.68277 0.6912292 5.849408 31.67096 0.6910601 5.917913 31.62682 0.6869285 5.963276 31.55916 4.867965 4.786733 29.48376 4.464345 4.988085 29.88337 4.862604 4.771477 29.5275 4.867853 4.785053 29.49094 4.481842 4.854943 29.96969 4.853491 4.667412 29.59977 4.854477 4.704528 29.59206 4.858353 4.742086 29.5667 4.484885 4.928907 29.93561 4.85723 4.737891 29.5715 4.491496 4.833662 29.96167 4.853475 4.661661 29.5999 3.377178 5.307687 30.78828 3.835165 5.105014 30.49508 3.953422 5.090054 30.40627 4.368214 4.888658 30.07286 0.8088719 5.770055 31.67071 1.462036 5.701877 31.55676 1.405415 5.776831 31.55739 2.094635 5.597291 31.37995 2.097005 5.658424 31.36921 2.723239 5.455326 31.13378 2.756599 5.499691 31.111 3.308234 5.287176 30.83365 3.362041 5.269875 30.80223 0.6801823 5.977941 31.48555 0.9215472 5.959476 31.45633 1.396975 5.892302 31.44748 3.936259 5.21902 30.31377 3.9025 5.247827 30.25286 3.360955 5.432637 30.69025 3.331103 5.457592 30.62572 2.742103 5.620921 31.00816 2.716922 5.642364 30.94045 2.085107 5.77642 31.26235 2.065386 5.794856 31.19199 1.383456 5.908421 31.37512 1.405192 5.845813 31.51399 2.09695 5.728148 31.32702 2.756983 5.570348 31.0704 3.37826 5.379398 30.74958 3.955417 5.16288 30.36975 2.792432 5.333982 31.10204 2.619654 5.378622 31.17951 2.600548 5.31233 31.17475 2.080372 5.498623 31.38469 1.775961 5.553703 31.47749 1.764552 5.496403 31.47177 1.519437 5.593165 31.54347 0.8721687 5.664968 31.6626 0.8834546 5.612333 31.65432 0.8567354 5.479485 31.54032 0 5.511063 31.58596 0 5.544246 31.64582 0.8710479 5.53231 31.61285 0 5.570029 31.67237 0 5.594555 31.6903 0 5.656752 31.71562 0.7041797 5.677179 31.68276 0.225416 5.697659 31.71651 0 5.699971 31.72035 2.161832 5.482349 31.35711 2.524075 5.192985 31.0686 3.278663 4.964453 30.67417 3.330292 5.003701 30.73781 2.564809 5.238107 31.13614 3.375991 5.07345 30.7742 3.404237 5.150934 30.7771 1.711784 5.36885 31.36084 1.739987 5.418649 31.43142 -2.798155 5.332206 31.09937 -3.404237 5.150934 30.7771 -3.375991 5.07345 30.7742 -2.600548 5.31233 31.17475 -2.619599 5.378365 31.17953 -1.603521 5.580633 31.52305 -1.77593 5.553504 31.47749 -1.764552 5.496403 31.47177 -2.080402 5.498466 31.38468 -2.189546 5.476486 31.34746 -0.3218585 5.695013 31.71252 -0.7042607 5.676735 31.68276 -0.8834546 5.612333 31.65432 -0.8885903 5.663136 31.6604 -0.9801338 5.655222 31.64734 -0.8710479 5.53231 31.61285 -0.8567354 5.479485 31.54032 -1.711784 5.36885 31.36084 -3.278663 4.964453 30.67417 -3.330292 5.003701 30.73781 -2.564809 5.238107 31.13614 -2.524075 5.192985 31.0686 -1.739987 5.418649 31.43142 7.078166 -0.0881949 25.21474 7.21737 -0.08824235 24.14222 7.126508 0.104874 24.88275 6.936469 -0.08819967 26.17299 6.868191 0.6833459 26.89267 6.777283 -0.08824288 27.12359 6.821067 1.229964 27.24561 6.820416 1.147903 27.25045 6.878383 1.171799 26.81583 6.824418 0.9916682 27.22065 6.825277 0.9751179 27.21424 6.830754 0.8961049 27.17338 6.839698 0.8124499 27.10655 6.857073 0.7173075 26.97631 7.498113 1.660254 21.72296 6.888547 1.660253 26.73899 6.876612 1.652412 26.8292 6.855988 1.598946 26.98446 6.854128 1.591204 26.99842 6.844299 1.539742 27.07211 6.834512 1.464074 27.14532 6.829036 1.403115 27.1862 6.821642 1.255054 27.24133 8.156449 1.660254 14.91285 8.540538 1.660254 9.518077 7.548333 1.660254 21.26637 -6.827284 -0.08824199 27.12359 -6.918191 0.6833459 26.89267 -6.965495 -0.08820617 26.30521 -7.014231 0.4634659 26.16081 -7.267369 -0.08824235 24.14222 -8.206447 1.660254 14.91285 -8.590538 1.660254 9.518077 -8.590538 -0.08824235 9.518077 -7.598332 1.660254 21.26637 -7.548123 -0.08824235 21.72287 -6.928382 1.171799 26.81583 -6.871068 1.229964 27.24561 -6.871642 1.255054 27.24133 -6.879036 1.403115 27.1862 -6.884512 1.464074 27.14532 -6.894299 1.539742 27.07211 -6.905987 1.598946 26.98446 -6.926611 1.652412 26.8292 -6.938547 1.660253 26.73899 -6.907073 0.7173075 26.97631 -6.889698 0.8124498 27.10655 -6.888045 0.8253765 27.11891 -6.880754 0.8961049 27.17338 -6.874417 0.9916682 27.22065 -6.870417 1.147903 27.25045 -8.403984 -0.08824235 12.35046 -8.18424 -0.08824235 15.18046 -7.88838 -0.08824235 18.45382 2.629096 -0.08823424 31.73804 2.012854 -0.08822983 31.84878 -5.496989 -0.08827412 30.02316 -5.877294 -0.08834075 29.53081 6.372452 -0.08868765 28.52919 6.583096 -0.08839291 27.94366 6.646917 -0.08840274 27.71839 -1.658438 -0.08823788 31.88197 -2.330564 -0.08822673 31.80976 1.370553 -0.0882436 31.88723 -1.420553 -0.0882436 31.88723 -5.030616 -0.08824324 30.49855 -4.583862 -0.08837145 30.86019 -4.069788 -0.08839207 31.19031 -3.521233 -0.08825957 31.46045 -2.955893 -0.08823734 31.66363 3.220599 -0.08824259 31.55933 3.785817 -0.08833342 31.31503 4.322384 -0.08841729 31.006 -6.192836 -0.08824419 29.01168 -6.340804 -0.08850139 28.71448 -6.347731 -0.08851891 28.69943 4.798526 -0.08828061 30.65551 5.297482 -0.08828628 30.18852 5.710959 -0.08826524 29.69405 5.723942 -0.08827233 29.67645 6.077955 -0.08829718 29.12942 6.296866 -0.08852732 28.70131 -6.464773 -0.08860945 28.4257 -6.576221 -0.08825534 28.12175 6.754339 -0.08819949 27.24699 6.729796 -0.0881868 27.36835 6.723718 -0.08819717 27.39693 -6.672878 -0.08834409 27.80695 -6.700274 -0.08833581 27.70567 -6.772356 -0.0881803 27.40328 -6.785202 -0.08816838 27.34247 -8.590538 -0.08824217 7.039315 -8.488288 -0.08824789 7.189965 -8.180746 -0.08824235 7.550899 -5.079227 -0.08824235 9.662714 -5.237448 -0.08824235 9.644564 -6.937872 -0.08824235 8.794965 -6.760029 -0.08824235 8.959173 -6.569722 -0.08824235 9.108302 -6.368845 -0.08824235 9.24116 -6.159196 -0.08824235 9.35684 -5.93816 -0.08824235 9.456551 -5.70931 -0.08824235 9.538265 -5.475869 -0.08824235 9.600838 -5.356972 -0.08824235 9.625137 -8.180746 3.661355 6.118076 -7.818094 4.160254 6.118076 -8.180746 3.138208 6.568257 -7.739268 4.160254 6.235899 -6.937872 0.5037307 8.790441 -8.180746 0.5734549 7.539928 -8.180746 1.484004 7.377892 -6.937872 1.348743 8.685357 -6.937872 0.7745007 8.769535 -6.937872 4.160254 7.34358 -6.937872 3.689247 7.702195 -8.180746 2.538403 6.95238 -6.937872 2.956561 8.136089 -8.180746 2.34887 7.050233 -6.937872 2.171491 8.465867 -6.937872 1.989594 8.5249 -3.753912 5.306026 22.81137 -3.984991 5.278536 22.75857 -4.257845 5.834012 21.9575 -4.421139 5.772979 22.70461 -4.36148 5.542019 22.69833 -4.199274 5.604687 21.95202 -4.204152 5.363664 22.71779 -4.044318 5.426777 21.9717 -3.82772 5.34017 22.01214 -3.598041 5.364284 22.06426 1.97963 5.811696 20.21224 2.058671 5.796206 20.23976 2.393667 5.72352 20.39441 4.267955 5.093464 26.28191 2.701267 5.646584 20.60023 3.152815 5.515476 21.33225 3.460846 5.413251 21.61504 3.296425 5.469131 21.28333 3.246172 5.485608 21.20176 3.021617 5.555836 20.90396 2.754859 5.632164 20.64373 3.753912 5.306026 22.81137 3.598041 5.364284 22.06426 3.575647 5.372424 21.96641 5.5045 4.441503 28.56866 5.383459 4.514897 28.68372 5.459979 4.468759 28.63583 5.314891 4.555492 28.84282 4.894917 4.789229 29.35917 1.628095 5.873009 20.12691 1.266713 5.923312 20.09808 0.9202471 5.959596 20.09808 0 6 20.09808 -0.9202471 5.959596 20.09808 -1.266713 5.923312 20.09808 -1.628095 5.873009 20.12691 -1.97963 5.811696 20.21224 -2.058671 5.796206 20.23976 -2.393667 5.72352 20.39441 -2.701267 5.646584 20.60023 -3.021617 5.555836 20.90396 -3.246172 5.485608 21.20176 -2.754859 5.632164 20.64373 -3.296425 5.469131 21.28333 -3.460846 5.413251 21.61504 -3.575647 5.372424 21.96641 -4.267955 5.093464 26.28191 -4.894917 4.789229 29.35917 -5.314891 4.555492 28.84282 -5.383459 4.514897 28.68372 -5.459979 4.468759 28.63583 -5.5045 4.441503 28.56866 4.421139 5.772979 22.70461 4.36148 5.542019 22.69833 3.984991 5.278536 22.75857 3.82772 5.34017 22.01214 4.204152 5.363664 22.71779 4.044318 5.426777 21.9717 4.199274 5.604687 21.95202 4.257845 5.834012 21.9575 5.76482 4.326274 28.0084 5.760289 4.340973 27.99444 5.589877 4.463058 28.18681 5.666759 4.338495 28.33933 5.813889 4.239004 28.11041 5.774084 4.302325 28.03277 5.443775 4.499101 28.46762 5.620469 4.393008 28.26068 5.40528 4.582051 28.37353 5.325086 4.570333 28.57795 5.288954 4.652186 28.47966 5.167984 4.734011 28.56429 5.16792 4.877598 28.34787 5.126662 4.897109 28.36002 5.098462 4.910253 28.34567 5.036774 5.148636 27.85477 5.07934 5.167117 27.86332 5.126507 5.165829 27.86273 5.167772 5.145057 27.85311 5.167623 5.350407 27.32632 5.126352 5.372122 27.33326 5.079224 5.373411 27.33367 5.036714 5.353987 27.32746 5.014306 5.329329 27.31959 4.502925 5.051588 26.26507 4.730629 5.123912 26.25209 4.898923 5.293875 26.24594 4.96927 5.522555 26.24803 4.846287 5.758402 24.9525 4.583445 6.071684 23.44721 5.013043 5.396394 27.09445 5.043406 5.427001 27.10249 5.084385 5.442181 27.10615 5.128102 5.439013 27.10474 5.166149 5.418107 27.09853 4.995734 5.528698 26.48847 5.025964 5.559997 26.49216 5.066718 5.575678 26.49283 5.11022 5.572749 26.49038 5.148177 5.551774 26.48525 7.988296 4.060254 6.118076 7.965324 4.060254 6.118076 7.894696 4.160254 6.118076 8.350758 3.091142 6.34324 8.540536 1.362086 6.931185 8.540536 0.5370756 7.07831 8.478466 2.482197 6.555866 8.53752 1.837497 6.775895 8.540535 1.660256 6.83764 7.128403 4.160254 7.149258 7.029446 4.160254 7.270226 -4.751871 0.3006758 9.443826 -4.751871 0.4365516 9.673192 -4.816591 0.5522398 9.667741 -4.751871 0.8952908 9.64042 -4.816591 1.516593 9.547815 -4.751871 2.076326 9.415141 -4.816591 2.076326 9.415141 -4.816591 2.455538 9.297327 -4.751871 3.202414 8.993807 -4.816591 3.351483 8.920972 -4.816591 4.060254 8.511529 -4.751871 4.060254 8.511529 -4.751871 5.899752 6.126949 -7.894696 4.160254 6.118076 -7.128403 4.160254 7.149258 -6.809328 4.160254 7.500751 -6.53192 0.5224947 9.129795 -6.836282 4.060254 7.549577 -6.53192 2.281364 8.787487 -6.53192 3.109322 8.43969 -6.53192 3.882034 7.982096 -6.53192 1.41367 9.018964 -5.964616 0.5396327 9.439742 -5.343967 0.5496606 9.621095 -5.343967 1.507668 9.501955 -5.343967 2.440434 9.253117 -5.343967 3.330484 8.87924 -5.236988 4.060254 8.476076 -5.964616 3.248846 8.716988 -5.964616 4.058115 8.237745 -5.674119 4.060254 8.361153 -6.764874 4.060254 7.629373 -6.432842 4.060254 7.936964 -6.067822 4.060254 8.181487 -5.964616 1.47297 9.323668 -5.964616 2.381716 9.081237 -4.583445 6.071684 23.44721 -4.846287 5.758402 24.9525 -4.96927 5.522555 26.24803 -4.898923 5.293875 26.24594 -4.730629 5.123912 26.25209 -4.502925 5.051588 26.26507 -4.991941 5.52192 26.48754 -5.043406 5.427001 27.10249 -5.036714 5.353987 27.32746 -5.013043 5.396394 27.09445 -5.014306 5.329329 27.31959 -5.084385 5.442181 27.10615 -5.079224 5.373411 27.33367 -5.04467 5.35958 27.32925 -5.166149 5.418107 27.09853 -5.167623 5.350407 27.32632 -5.128102 5.439013 27.10474 -5.129518 5.371245 27.33298 -5.085715 5.374513 27.33402 -5.148177 5.551774 26.48525 -5.108346 5.573289 26.49054 -5.06286 5.575027 26.4929 -5.021172 5.55663 26.49182 -5.126507 5.165829 27.86273 -5.167772 5.145057 27.85311 -5.16792 4.877598 28.34787 -5.036774 5.148636 27.85477 -5.126662 4.897109 28.36002 -5.167984 4.734011 28.56429 -5.07934 5.167117 27.86332 -5.098462 4.910253 28.34567 -5.288954 4.652186 28.47966 -5.325086 4.570333 28.57795 -5.443775 4.499101 28.46762 -5.40528 4.582051 28.37353 -5.666759 4.338495 28.33933 -5.620469 4.393008 28.26068 -5.81352 4.239407 28.10998 -5.774084 4.302325 28.03277 -5.76482 4.326274 28.0084 -5.589877 4.463058 28.18681 -5.760289 4.340973 27.99444 -5.916116 4.160254 27.92228 -5.94347 4.164105 27.81063 -5.946388 4.160254 27.80893 -5.778436 4.326303 27.97407 -5.894656 4.220409 27.85016 -5.91156 4.164116 27.93057 -5.878001 4.191195 27.99254 -5.847614 4.266384 27.89797 -5.826169 4.230121 28.0881 -5.889699 4.160254 28.03945 -5.832523 4.215263 28.12692 -5.855132 4.160254 28.15528 -4.936623 4.748984 29.4149 -4.956518 4.686646 29.46163 -4.951388 4.612292 29.49179 -5.524203 4.367189 28.71891 -5.749685 4.160254 28.37608 -5.502192 4.426884 28.68045 -5.357065 4.514 28.89051 -5.378537 4.453598 28.93131 -5.522969 4.297925 28.74589 -5.376207 4.383007 28.95934 -4.884935 4.160254 29.38854 -4.942455 4.196611 29.41331 -4.961331 4.160254 29.36911 -4.868174 4.233678 29.48214 -4.866108 4.250311 29.49908 -4.862219 4.286174 29.5306 -4.855311 4.375949 29.58552 -4.993801 4.254925 29.42022 -4.853467 4.445475 29.59991 -5.027012 4.323826 29.40491 -4.864107 4.267703 29.51535 -4.879299 4.160254 29.38852 -4.870297 4.217743 29.46459 -5.03129 4.160254 29.33371 -5.083475 4.160254 29.29819 -5.24367 4.160254 29.13783 -4.876535 4.178646 29.41177 -4.866533 4.247304 29.4956 -4.865052 4.259867 29.50768 -4.863612 4.272814 29.51936 -4.86291 4.279441 29.52504 -4.542396 4.392253 29.7512 -4.152264 4.607017 30.08823 -4.215758 4.653997 30.13332 -4.318521 4.473818 29.84751 -3.289247 4.943379 30.57592 -3.880444 4.972028 30.46257 -3.73039 4.798548 30.39679 -3.777636 4.749293 30.26791 -3.734452 4.768381 30.29766 -3.61287 4.820035 30.37869 -4.80833 4.160254 29.37333 -4.827728 4.160254 29.38247 -4.609642 4.442515 29.78614 -4.492198 4.669648 29.96102 -4.662049 4.516836 29.79082 -4.638838 4.478043 29.79252 -4.3745 4.735149 30.06732 -4.267765 4.727201 30.14848 -4.24431 4.688661 30.1451 -3.838321 4.913533 30.47766 -3.815567 4.875414 30.46895 -3.788594 4.841814 30.45166 -0.4727192 4.938261 30.25515 -0.9703766 4.89265 30.21341 0 4.892761 30.2451 0 5.15796 30.38998 0 5.197507 30.42311 -0.4973149 5.213336 30.43752 0 5.360254 30.61448 0 5.386605 30.65883 -0.5222783 5.40614 30.71275 -4.756264 4.160254 29.3456 -3.597848 4.727859 30.03135 -4.016624 4.531044 29.79619 -4.391366 4.327251 29.53807 -4.605744 4.160254 29.30066 -3.15085 4.90656 30.23564 -3.273525 4.946891 30.5299 -2.767203 5.108952 30.71598 -1.086082 5.393558 30.75595 -0.5290414 5.441569 30.80486 0 5.476834 30.89328 0 4.941045 30.26327 -0.9283816 4.585113 30.14671 -0.8897718 4.236011 30.14986 -0.4628742 4.262429 30.1837 -8.1061e-7 4.287819 30.19615 0 4.594561 30.19615 0 4.646092 30.19734 -2.606362 4.160254 29.77175 -2.169393 4.160254 29.90907 -1.847707 4.41048 29.99197 -1.767024 4.160255 30.0091 -1.260514 4.210036 30.10248 -3.763357 4.319658 29.51467 -4.035978 4.160254 29.33269 -3.915362 4.160254 29.35896 -3.388282 4.160254 29.5085 -3.025472 4.160254 29.62866 -2.812695 4.427487 29.77212 -2.709273 4.160254 29.7367 -2.380656 4.582309 29.92244 -1.929537 4.71246 30.04594 -1.455896 4.817185 30.14369 -2.666093 5.06806 30.41368 -2.160349 5.204318 30.55928 -1.629723 5.314234 30.67415 -1.0208 5.166414 30.39239 -1.531383 5.08884 30.317 -2.029265 4.981277 30.21125 -2.503163 4.847789 30.07753 -2.956571 4.689318 29.91454 -3.373677 4.51363 29.72822 -3.644037 4.160254 29.43049 -3.705286 4.160254 29.41312 -1.072141 5.358298 30.6646 -1.608659 5.279245 30.58406 -2.132151 5.169695 30.47101 -2.630849 5.033867 30.32781 -3.108528 4.872837 30.15284 -3.548608 4.694604 29.95227 -3.96044 4.498231 29.72166 -4.328477 4.294788 29.46894 -4.238685 4.160254 29.29971 -4.514537 4.160254 29.28977 -0.8733401 4.160254 30.15157 0 4.160254 30.19615 0.5501995 4.256436 30.17853 0.8733401 4.160254 30.15157 1.767024 4.160255 30.0091 1.328946 4.20443 30.09195 0.8897062 4.236254 30.1499 2.156117 4.160254 29.91276 2.607232 4.160254 29.77145 1.847707 4.41048 29.99197 4.787979 4.160254 29.36145 4.80833 4.160254 29.37333 4.333321 4.464817 29.83464 0.4973149 5.213336 30.43752 0.9283816 4.585113 30.14671 0.4727192 4.938261 30.25515 0.9703766 4.89265 30.21341 0.5290414 5.441569 30.80486 1.086082 5.393558 30.75595 1.629723 5.314234 30.67415 2.160349 5.204318 30.55928 3.840975 4.720393 30.22362 3.336953 4.926525 30.54849 3.273525 4.946891 30.5299 2.767203 5.108952 30.71598 4.016624 4.531044 29.79619 4.096965 4.594695 30.03104 4.391366 4.327251 29.53807 4.614952 4.160254 29.30233 3.96044 4.498231 29.72166 4.280185 4.160254 29.29516 4.328477 4.294788 29.46894 4.346382 4.160254 29.28983 2.709099 4.160254 29.73676 2.99432 4.160254 29.63926 2.812695 4.427487 29.77212 3.122883 4.160254 29.59573 3.385815 4.160254 29.50929 2.380656 4.582309 29.92244 1.929537 4.71246 30.04594 1.455896 4.817185 30.14369 2.666093 5.06806 30.41368 3.15085 4.90656 30.23564 3.597848 4.727859 30.03135 1.0208 5.166414 30.39239 1.531383 5.08884 30.317 2.029265 4.981277 30.21125 2.503163 4.847789 30.07753 2.956571 4.689318 29.91454 3.373677 4.51363 29.72822 3.763357 4.319658 29.51467 3.646888 4.160254 29.42967 3.847904 4.160254 29.37532 0.5222783 5.40614 30.71275 1.072141 5.358298 30.6646 1.608659 5.279245 30.58406 2.132151 5.169695 30.47101 2.630849 5.033867 30.32781 3.108528 4.872837 30.15284 3.548608 4.694604 29.95227 4.492267 4.670331 29.96097 4.393274 4.725656 30.05071 4.267765 4.727201 30.14848 4.609642 4.442515 29.78614 4.862219 4.286174 29.5306 4.638838 4.478043 29.79252 4.855311 4.375949 29.58552 4.662049 4.516836 29.79082 4.853467 4.445475 29.59991 4.876535 4.178646 29.41177 4.868174 4.233678 29.48214 4.542396 4.392253 29.7512 4.866533 4.247304 29.4956 4.865052 4.259867 29.50768 4.863612 4.272814 29.51936 4.86291 4.279441 29.52504 4.879299 4.160254 29.38852 4.841014 4.160254 29.38608 4.152264 4.607017 30.08823 3.73039 4.798548 30.39679 3.966667 4.935084 30.39901 3.838321 4.913533 30.47766 3.815567 4.875414 30.46895 3.788594 4.841814 30.45166 4.24431 4.688661 30.1451 4.215758 4.653997 30.13332 4.864107 4.267703 29.51535 4.870297 4.217743 29.46459 4.866108 4.250311 29.49908 4.993801 4.254925 29.42022 4.942455 4.196611 29.41331 5.119185 4.160254 29.26951 4.973123 4.160254 29.36419 5.24367 4.160254 29.13783 5.027012 4.323826 29.40491 4.951388 4.612292 29.49179 5.376207 4.383007 28.95934 5.417393 4.160254 28.90123 5.522969 4.297925 28.74589 5.749685 4.160254 28.37608 -5.417393 4.160254 28.90123 4.936623 4.748984 29.4149 4.956518 4.686646 29.46163 5.502192 4.426884 28.68045 5.832523 4.215263 28.12692 5.855132 4.160254 28.15528 5.378537 4.453598 28.93131 5.524203 4.367189 28.71891 5.357065 4.514 28.89051 5.826169 4.230121 28.0881 5.878001 4.191195 27.99254 5.889699 4.160254 28.03945 5.91156 4.164116 27.93057 5.916116 4.160254 27.92228 5.778436 4.326303 27.97407 5.946388 4.160254 27.80893 5.94347 4.164105 27.81063 5.894656 4.220409 27.85016 5.847614 4.266384 27.89797 7.487408 2.479025 21.25973 6.82779 2.479025 26.73097 7.266562 3.403098 21.23565 6.607549 3.403098 26.70187 8.345945 3.109136 9.518077 7.938435 4.160254 9.518077 7.557458 4.160254 14.86348 8.530434 1.99198 9.518077 8.479029 2.479023 9.518077 8.09537 2.479025 14.90782 7.873964 3.403098 14.88957 6.950853 4.160254 21.20123 6.292704 4.160254 26.66027 6.274278 4.160254 26.78869 6.197446 4.160254 27.19179 6.303894 3.958141 27.16633 5.207242 4.160254 29.31656 5.525559 4.002905 29.0091 5.464178 4.160254 28.95336 4.817178 4.160254 29.76299 4.692435 4.03205 29.9802 5.095435 3.792023 29.74 4.376169 4.160254 30.16042 6.669672 0.202739 27.78673 6.494049 0.152161 28.3239 5.722518 -0.06864362 29.68484 4.979751 0.322695 30.59265 4.566229 0.2462767 30.91026 4.124121 0.1774356 31.18704 3.65978 0.1170202 31.4197 3.180003 0.06563186 31.6062 2.201644 -0.008973538 31.83913 2.190609 0.50093 31.92017 1.369785 0.20115 31.94135 2.185745 1.016253 31.95587 1.368984 0.8914989 32.0125 2.187126 1.532747 31.94574 1.369377 1.592178 32.00297 2.194738 2.046181 31.88985 1.370477 2.277692 31.91352 2.208483 2.55234 31.7889 2.228251 3.047021 31.64362 1.372021 2.925819 31.75292 1.373278 3.285306 31.62958 2.253855 3.526238 31.45531 1.37445 3.552845 31.5208 2.285028 3.986209 31.22577 1.378015 4.160255 31.21472 1.95862 4.160254 31.17926 2.772783 3.907472 31.14944 2.526652 4.160254 31.07443 3.258092 3.80592 31.03173 2.967043 4.160254 30.94254 3.734216 3.681736 30.87206 3.505752 4.160254 30.71488 5.463336 3.531532 29.47003 5.846668 3.670788 28.76707 5.910223 4.007658 28.2943 5.766892 4.160254 28.41697 6.179452 3.614169 28.09868 6.239833 3.827617 27.64742 6.007483 4.160254 27.84598 6.1424 4.160254 27.41381 3.20492 2.926637 31.42309 3.186407 2.463516 31.55916 3.653615 1.950714 31.46498 3.683532 2.843717 31.24514 4.118312 1.904937 31.22971 4.146501 2.74623 31.02255 4.560826 1.852775 30.94996 4.587045 2.635148 30.75724 4.974799 1.794872 30.62904 4.998831 2.511839 30.45237 4.010489 4.160254 30.42539 4.19426 3.535738 30.67098 4.631469 3.369379 30.43019 5.03955 3.184709 30.15254 3.228898 3.375286 31.24671 6.619654 1.124845 28.15664 6.621873 1.378111 28.14028 6.457852 1.450803 28.59093 6.630146 1.624316 28.07925 6.468874 1.779121 28.50972 6.644175 1.855533 27.9756 6.487561 2.087372 28.37183 6.663453 2.064417 27.83286 6.513228 2.365751 28.182 6.6873 2.24452 27.65576 6.544961 2.605679 27.94658 6.714905 2.390372 27.45003 6.581672 2.799901 27.67321 6.745349 2.497652 27.22223 6.622136 2.942708 27.37062 6.777678 2.563285 26.97925 6.665086 3.030056 27.04794 5.99783 0.5860308 29.44353 6.0176 0.1013197 29.29803 6.268157 0.2760452 28.8933 5.699584 0.4938511 29.85358 5.690508 1.078182 29.92028 5.348802 1.067316 30.31412 5.354613 1.732032 30.27143 5.37627 2.378017 30.11219 5.412967 2.984293 29.84192 6.694649 0.03170961 27.60107 6.649046 0.4042226 27.93957 6.473339 0.4530344 28.4768 6.251643 0.6807931 29.01491 5.990009 1.089535 29.50104 5.695641 1.665184 29.88256 5.714772 2.235661 29.74186 5.747189 2.771097 29.50305 5.79169 3.254429 29.17441 6.633497 0.6299256 28.05451 6.623577 0.87272 28.12771 6.460123 0.7767831 28.5742 6.454895 1.113029 28.6127 6.245109 1.101206 29.06297 6.248805 1.523536 29.03579 5.994433 1.595339 29.46852 6.262579 1.93401 28.93439 6.010922 2.086919 29.3472 6.285925 2.319339 28.76226 6.038868 2.548339 29.14126 6.317983 2.667252 28.52532 6.077233 2.964896 28.85783 6.357604 2.967037 28.23156 6.12464 3.323774 28.50649 6.403425 3.209655 27.89053 6.453913 3.38801 27.51312 6.507487 3.497085 27.11072 2.691711 0.02360862 31.74584 2.680981 0.5193035 31.82463 2.676252 1.020266 31.85934 2.677595 1.522367 31.84949 2.684996 2.021493 31.79515 2.698359 2.513548 31.697 2.71758 2.994446 31.55574 2.742474 3.460313 31.37263 3.645588 1.03177 31.52392 3.165113 1.025441 31.71553 3.169669 0.5430007 31.6821 3.166406 1.508978 31.70604 3.64682 1.492607 31.51487 3.173535 1.989651 31.6537 5.359076 0.4056286 30.23863 4.968351 1.057102 30.6764 4.553791 1.04769 31.00162 4.110748 1.039211 31.28525 -1.419464 0.4112927 31.97164 -1.41911 1.019908 32.01693 -1.419518 1.658381 31.99786 -1.420535 2.302662 31.90881 -1.422121 2.928183 31.75219 -1.424422 3.532037 31.52989 -1.428015 4.160255 31.21472 -6.795349 2.497652 27.22223 -5.513337 3.531532 29.47003 -5.575559 4.002905 29.0091 -5.896667 3.670788 28.76707 -6.544048 0.152161 28.3239 -6.699047 0.4042226 27.93957 -6.719673 0.202739 27.78673 -6.657549 3.403098 26.70187 -6.353893 3.958141 27.16633 -6.342704 4.160254 26.66027 -6.227078 4.160254 27.27841 -6.744649 0.03170961 27.60107 -2.244738 2.046181 31.88985 -2.258483 2.55234 31.7889 -2.278252 3.047021 31.64362 -2.303854 3.526238 31.45531 -2.335028 3.986209 31.22577 -1.658354 4.160254 31.20916 -2.139228 4.160254 31.16142 -2.240609 0.50093 31.92017 -2.251644 -0.008973538 31.83913 -2.741711 0.02360862 31.74584 -3.230003 0.06563192 31.6062 -3.70978 0.1170202 31.4197 -4.174121 0.1774356 31.18704 -4.61623 0.2462767 30.91026 -5.029751 0.322695 30.59265 -5.749583 0.4938511 29.85358 -5.772518 -0.06864362 29.68484 -6.0676 0.1013197 29.29803 -4.481766 4.160254 30.11541 -4.703868 4.160254 29.92151 -4.742434 4.03205 29.9802 -4.76502 4.160254 29.86384 -5.165934 4.160254 29.43094 -4.681469 3.369379 30.43019 -4.24426 3.535738 30.67098 -4.250673 4.160254 30.29403 -3.784216 3.681736 30.87206 -3.76132 4.160254 30.60665 -3.695588 1.03177 31.52392 -3.219669 0.5430007 31.6821 -3.215113 1.025441 31.71553 -2.730981 0.5193035 31.82463 -2.726252 1.020266 31.85934 -2.235745 1.016253 31.95587 -2.727594 1.522367 31.84949 -3.216407 1.508978 31.70604 -3.69682 1.492607 31.51487 -4.160748 1.039211 31.28525 -3.223535 1.989651 31.6537 -3.703615 1.950714 31.46498 -4.168312 1.904937 31.22971 -4.610826 1.852775 30.94996 -4.603791 1.04769 31.00162 -5.024799 1.794872 30.62904 -5.018351 1.057102 30.6764 -6.680146 1.624316 28.07925 -6.671873 1.378111 28.14028 -6.507852 1.450803 28.59093 -6.669654 1.124845 28.15664 -6.504895 1.113029 28.6127 -6.673577 0.87272 28.12771 -6.510123 0.7767831 28.5742 -6.683497 0.6299256 28.05451 -6.523339 0.4530344 28.4768 -5.960224 4.007658 28.2943 -6.229452 3.614169 28.09868 -6.557487 3.497085 27.11072 -6.289833 3.827617 27.64742 -6.048019 4.160254 27.87231 -5.08955 3.184709 30.15254 -5.145435 3.792023 29.74 -5.048831 2.511839 30.45237 -5.462967 2.984293 29.84192 -5.84169 3.254429 29.17441 -6.17464 3.323774 28.50649 -6.453424 3.209655 27.89053 -6.503912 3.38801 27.51312 -6.672136 2.942708 27.37062 -6.715086 3.030056 27.04794 -6.827679 2.563285 26.97925 -6.87779 2.479025 26.73097 -5.409075 0.4056286 30.23863 -5.398801 1.067316 30.31412 -5.404613 1.732032 30.27143 -5.42627 2.378017 30.11219 -5.764772 2.235661 29.74186 -5.79719 2.771097 29.50305 -6.088868 2.548339 29.14126 -6.127233 2.964896 28.85783 -6.367983 2.667252 28.52532 -6.407604 2.967037 28.23156 -6.594961 2.605679 27.94658 -6.631672 2.799901 27.67321 -6.764905 2.390372 27.45003 -6.737301 2.24452 27.65576 -6.563228 2.365751 28.182 -6.335925 2.319339 28.76226 -6.060923 2.086919 29.3472 -5.745641 1.665184 29.88256 -5.740509 1.078182 29.92028 -6.713453 2.064417 27.83286 -6.694175 1.855533 27.9756 -6.537561 2.087372 28.37183 -6.518875 1.779121 28.50972 -6.312579 1.93401 28.93439 -6.298805 1.523536 29.03579 -6.044433 1.595339 29.46852 -6.29511 1.101206 29.06297 -6.040009 1.089535 29.50104 -6.301643 0.6807931 29.01491 -6.047831 0.5860308 29.44353 -6.318157 0.2760453 28.8933 -2.703758 4.160254 31.04107 -2.822783 3.907472 31.14944 -2.792474 3.460313 31.37263 -2.76758 2.994446 31.55574 -2.74836 2.513548 31.697 -3.254218 4.160254 30.8518 -3.308092 3.80592 31.03173 -3.278898 3.375286 31.24671 -3.25492 2.926637 31.42309 -3.733532 2.843717 31.24514 -4.196501 2.74623 31.02255 -4.637045 2.635148 30.75724 -5.394089 4.160254 29.13146 -5.514393 4.160254 28.95303 -5.809773 4.160254 28.43144 -3.236407 2.463516 31.55916 -2.734996 2.021493 31.79515 -2.237126 1.532747 31.94574 -7.316562 3.403098 21.23565 -7.000853 4.160254 21.20123 -7.607458 4.160254 14.86348 -7.537408 2.479025 21.25973 -8.145369 2.479025 14.90782 -8.529255 2.479046 9.518077 -8.47493 2.781136 9.518077 -7.923964 3.403098 14.88957 -8.306472 3.403093 9.518077 -8.130844 3.859392 9.518077 -7.988434 4.160254 9.518077 -8.590538 0.5310543 7.030819 -8.590538 1.348167 6.885411 -8.590538 1.660254 6.786891 -8.254039 3.552575 6.118065 -8.437328 2.947818 6.345674 -8.474884 2.78123 6.403094 -8.5517 2.312997 6.561108 -7.965324 4.060254 6.118076 -8.038208 4.060254 6.118075 -1.296873 6.171486 19.66506 -1.303949 6.229716 19.63614 -1.745999 6.175205 19.66691 -1.274795 5.98981 19.84808 -1.28438 6.068689 19.74452 -1.704328 6.01351 19.77326 -3.802445 5.349552 21.90502 -4.170489 5.614096 21.83393 -4.229693 5.842539 21.84008 -4.023488 5.661116 21.41142 -4.085371 5.885311 21.41843 -3.814402 5.725039 21.01538 -3.87867 5.943852 21.02037 -3.750799 5.743797 20.91849 -3.815495 5.961113 20.9225 -3.468066 5.823338 20.56664 -3.533198 6.034685 20.56514 -3.673307 5.396424 21.52166 -3.489462 5.460107 21.16212 -3.433501 5.478787 21.07414 -3.18454 5.557952 20.75442 -2.890708 5.643219 20.47719 -2.831882 5.659241 20.43107 -2.495301 5.744285 20.21378 -2.130342 5.823929 20.0518 -2.044414 5.840806 20.02315 -1.662859 5.907224 19.93504 -1.271305 5.961094 19.90674 -2.114009 5.945304 19.86491 -2.20636 5.92795 19.89484 -2.599078 5.845935 20.0645 -2.962134 5.758161 20.29293 -3.025693 5.7416 20.34151 -3.343739 5.65334 20.63413 -3.614093 5.571186 20.97276 -3.674993 5.551768 21.06615 -3.875447 5.485475 21.44851 -4.016642 5.436576 21.85731 -2.177058 6.108137 19.76337 -2.274188 6.091112 19.79477 -2.686988 6.010831 19.97248 -3.068142 5.925207 20.21113 -3.134809 5.909085 20.26181 -3.208287 6.112278 20.26122 -3.197844 6.114648 20.25286 -3.130471 6.129754 20.20066 -2.743775 6.210354 19.95368 -2.322638 6.286502 19.7681 -2.223271 6.302729 19.73508 -1.781341 6.366961 19.63268 -1.327033 6.419661 19.59808 -4.257845 6.3481 21.9575 -4.420988 6.218749 22.70392 0 6.5 19.59808 0 6.25 19.66506 0 6.066987 19.84808 1.274795 5.98981 19.84808 1.28438 6.068689 19.74452 1.296873 6.171486 19.66506 1.303949 6.229716 19.63614 1.327033 6.419661 19.59808 1.271305 5.961094 19.90674 1.662859 5.907224 19.93504 1.704328 6.01351 19.77326 4.229693 5.842539 21.84008 4.170489 5.614096 21.83393 4.085371 5.885311 21.41843 4.023488 5.661116 21.41142 3.878178 5.943988 21.01958 3.814402 5.725039 21.01538 3.750799 5.743797 20.91849 3.815495 5.961113 20.9225 3.533198 6.034685 20.56514 3.468066 5.823338 20.56664 3.208287 6.112278 20.26122 3.134809 5.909085 20.26181 3.197844 6.114648 20.25286 3.130471 6.129754 20.20066 3.068142 5.925207 20.21113 2.743775 6.210354 19.95368 2.686988 6.010831 19.97248 2.322638 6.286502 19.7681 2.274188 6.091112 19.79477 2.223271 6.302729 19.73508 2.177058 6.108137 19.76337 1.781341 6.366961 19.63268 1.745999 6.175205 19.66691 2.114009 5.945304 19.86491 2.20636 5.92795 19.89484 2.599078 5.845935 20.0645 2.962134 5.758161 20.29293 3.025693 5.7416 20.34151 3.343739 5.65334 20.63413 3.614093 5.571186 20.97276 3.674993 5.551768 21.06615 3.875447 5.485475 21.44851 4.016642 5.436576 21.85731 2.044414 5.840806 20.02315 2.130342 5.823929 20.0518 2.495301 5.744285 20.21378 2.831882 5.659241 20.43107 2.890708 5.643219 20.47719 3.18454 5.557952 20.75442 3.433501 5.478787 21.07414 3.489462 5.460107 21.16212 3.673307 5.396424 21.52166 3.802445 5.349552 21.90502 4.420988 6.218749 22.70392 4.257845 6.3481 21.9575 5.555075 4.619215 28.00914 5.618107 4.775323 27.53662 5.497139 5.19792 26.53135 5.683008 4.869236 27.04824 5.747063 4.89976 26.56436 5.905928 4.685451 26.58535 6.189651 4.160254 26.90612 6.233298 4.160254 26.6286 6.042635 4.160254 27.51796 4.856874 5.800333 24.95945 4.884453 5.834219 24.96257 4.923732 5.853559 24.96126 4.967175 5.854642 24.95577 5.006447 5.837261 24.94715 4.593673 6.111577 23.45339 4.61907 6.144552 23.4548 4.655232 6.164889 23.45118 4.695887 6.169061 23.44318 4.733984 6.156345 23.43217 4.529117 6.316924 22.69847 4.489531 6.311464 22.70611 4.430587 6.257947 22.70908 4.454769 6.290657 22.70985 4.3993 6.437879 21.94111 4.566976 6.306133 22.68819 4.323294 6.440178 21.95809 4.352016 6.44663 21.95286 4.36179 6.446829 21.95076 4.305596 6.431237 21.96052 4.266862 6.386579 21.96175 4.271414 6.395473 21.9622 4.289891 6.418979 21.96197 8.069151 4.160254 5.866152 8.121812 4.060254 5.895327 7.128403 4.829033 6.528289 7.128403 4.291558 7.040389 7.977837 4.322231 5.82349 7.128403 4.936932 6.410456 7.725702 4.710577 5.753076 7.128403 5.406076 5.821259 7.406833 5.112723 5.752132 7.667192 4.790782 5.745914 7.988296 4.060254 8.531867 7.938435 4.160254 8.457828 6.720095 4.060254 7.654565 5.007121 4.060254 8.303976 5.044208 4.060254 8.303704 5.465343 4.060254 8.262065 5.884425 4.060254 8.147418 6.156127 4.060254 8.030099 6.279934 4.060254 7.964125 6.644125 4.060254 7.717393 6.673798 4.53336 7.324492 7.023329 5.506052 5.853134 6.673798 5.215098 6.659066 6.721626 5.767977 5.896427 6.673798 5.800088 5.907174 6.155146 6.02997 6.062107 6.592266 5.869802 5.897552 6.238537 6.119658 5.858643 5.867277 6.341554 5.761216 5.592378 6.171529 6.157515 5.77802 6.38929 5.729837 5.007121 6.282838 6.093921 5.007121 6.7205 5.327472 5.388804 6.574004 5.557203 6.155146 4.713036 7.5356 5.592378 4.823679 7.665599 5.007121 6.219328 6.18973 5.007121 5.592053 6.99597 5.007121 4.86104 7.709494 5.007121 5.288287 7.316349 5.592378 5.549075 6.957559 6.155146 5.421793 6.8438 3.470556 6.838388 20.33849 3.784348 6.739926 20.67284 4.174486 6.774768 15.49407 4.075222 6.620805 21.10024 4.269321 6.520918 21.51173 4.451726 6.433351 21.5578 5.249684 5.948446 21.64699 7.589188 4.608353 9.695969 6.544638 4.608353 21.79173 6.81935 4.160254 21.82244 7.418426 4.160254 15.7742 5.954151 5.334158 21.72573 4.310128 6.496845 21.62439 5.044893 6.433351 15.56923 3.819936 6.726931 20.71763 3.258939 6.962769 15.41501 2.629584 6.983281 19.78225 3.019167 6.935785 19.99243 3.112391 6.919569 20.05376 3.697886 6.962769 9.45841 3.68076 6.986829 4.724651 4.926863 6.747146 5.273137 4.615134 6.774768 9.514409 4.477431 6.870142 5.006588 4.04258 6.9492 4.81918 5.487156 6.433351 9.567645 6.288591 5.948446 9.616569 6.996127 5.334158 9.659766 5.844841 5.948446 15.63832 6.551067 5.334158 15.6993 7.143028 4.608353 15.75042 7.865097 4.160254 9.712815 -4.751871 4.060254 8.303976 -5.007121 4.060254 8.303976 -5.044208 4.060254 8.303704 -5.465343 4.060254 8.262065 -5.884425 4.060254 8.147418 -6.720095 4.060254 7.654565 -6.644125 4.060254 7.717393 -6.279934 4.060254 7.964125 -6.156127 4.060254 8.030099 -4.751871 6.066366 6.408202 -4.751871 5.288287 7.316349 -3.133275 6.496527 5.745761 -2.994066 6.498435 5.742452 -2.994066 6.498435 7.137559 -2.515682 6.345283 6.879032 -2.745102 6.452385 7.059824 -2.650032 6.416529 6.330822 -2.815052 6.472008 5.787946 -3.266476 6.476288 5.780627 -3.251122 6.479566 7.105708 -3.494817 6.395622 5.915476 -3.494817 6.395622 6.964005 -3.672225 6.282838 6.093921 -3.705495 6.255199 6.726964 -3.874154 6.066366 6.408202 2.815052 6.472008 5.787946 2.650141 6.416576 6.330413 2.515682 6.345283 6.879032 3.494817 6.395622 6.964005 3.715751 6.246174 6.14962 3.705495 6.255199 6.726964 3.874154 6.066366 6.408202 2.994066 6.498435 5.742452 3.133275 6.496527 5.745761 2.994066 6.498435 7.137559 3.266476 6.476288 5.780627 3.251122 6.479566 7.105708 3.494817 6.395622 5.915476 3.668856 6.285504 6.089828 2.745102 6.452385 7.059824 -8.038269 4.060254 7.609943 -8.121812 4.060254 5.895327 -7.725702 4.710577 5.753076 -7.667192 4.790782 5.745914 -7.128403 4.936932 6.410456 -7.406833 5.112723 5.752132 -7.128403 5.406076 5.821259 -7.128403 4.291558 7.040389 -8.069151 4.160254 5.866152 -7.977837 4.322231 5.82349 -5.007121 5.288287 7.316349 -5.007121 4.86104 7.709494 -5.592378 4.823679 7.665599 -5.388804 6.574004 5.557203 -5.007121 6.7205 5.327472 -5.007121 6.282838 6.093921 -5.77802 6.38929 5.729837 -5.592378 6.171529 6.157515 -5.867277 6.341554 5.761216 -6.238537 6.119658 5.858643 -6.155146 6.02997 6.062107 -6.592266 5.869802 5.897552 -6.673798 5.800088 5.907174 -6.721626 5.767977 5.896427 -6.673798 5.215098 6.659066 -7.023329 5.506052 5.853134 -6.673798 4.53336 7.324492 -6.155146 4.713036 7.5356 -5.007121 6.219328 6.18973 -5.007121 5.592053 6.99597 -5.592378 5.549075 6.957559 -6.155146 5.421793 6.8438 -3.68076 6.986829 4.724651 -4.04258 6.9492 4.81918 -4.477431 6.870142 5.006588 -4.926863 6.747146 5.273137 -1.327033 6.9 19.59808 -4.173714 6.405993 21.65129 -3.208652 6.784899 20.26152 -3.378256 6.741327 20.4089 -3.675844 6.644655 20.73177 -3.709581 6.631896 20.77504 -3.878172 6.561824 21.01957 -3.951471 6.5277 21.14469 -4.135149 6.429629 21.54239 -3.038401 6.821031 20.13409 -1.761216 6.9 19.62966 -2.186256 6.9 19.72375 -2.324527 6.898 19.76877 -2.580067 6.883585 19.87229 -2.949918 6.836953 20.07494 -4.323294 6.440178 21.95809 -4.305596 6.431237 21.96052 -4.220706 6.487536 21.65224 -4.271414 6.395473 21.9622 -4.187691 6.452201 21.65604 -4.264993 6.503684 21.64079 -4.352016 6.44663 21.95286 -4.3993 6.437879 21.94111 -4.149245 6.475387 21.547 -3.965716 6.571727 21.14819 -3.723289 6.67428 20.77661 -3.689426 6.686849 20.73306 -3.390347 6.782136 20.40781 -3.048146 6.860731 20.13061 -2.95897 6.876426 20.07091 -2.585953 6.922323 19.86635 -2.188437 6.938269 19.71646 -4.181736 6.510558 21.54241 -3.995733 6.606273 21.1405 -3.750051 6.708244 20.76579 -3.715734 6.720746 20.72187 -3.412642 6.815547 20.39369 -3.065853 6.893749 20.1139 -2.975483 6.909361 20.05362 -2.597474 6.954978 19.84708 -2.194646 6.970711 19.69569 -4.225107 6.527003 21.52967 -4.035058 6.623898 21.12328 -3.784552 6.727039 20.74474 -3.749594 6.739679 20.70038 -3.441097 6.835504 20.3691 -3.088541 6.914527 20.08675 -2.996721 6.930304 20.02593 -2.612821 6.976419 19.81749 -2.203937 6.992388 19.66461 -4.310128 6.496845 21.62439 -4.269321 6.520918 21.51173 -4.075222 6.620805 21.10024 -3.819936 6.726931 20.71763 -3.784348 6.739926 20.67284 -3.470556 6.838388 20.33849 -3.112391 6.919569 20.05376 -3.019167 6.935785 19.99243 -2.629584 6.983281 19.78225 -1.762111 6.934612 19.62355 -1.765455 6.970711 19.60068 -1.77068 6.993819 19.56496 -1.327033 6.993819 19.53269 -1.327033 6.934612 19.5919 -1.327033 6.938269 19.59046 -1.327033 6.970711 19.56879 -1.327033 6.992388 19.53635 1.327033 6.9 19.59808 4.187691 6.452201 21.65604 4.220706 6.487536 21.65224 4.264993 6.503684 21.64079 3.965716 6.571727 21.14819 4.135149 6.429629 21.54239 4.149245 6.475387 21.547 4.173714 6.405993 21.65129 3.390347 6.782136 20.40781 3.675844 6.644655 20.73177 3.689426 6.686849 20.73306 3.709581 6.631896 20.77504 3.723289 6.67428 20.77661 3.878172 6.561824 21.01957 3.951471 6.5277 21.14469 4.225107 6.527003 21.52967 4.035058 6.623898 21.12328 3.784552 6.727039 20.74474 3.749594 6.739679 20.70038 3.441097 6.835504 20.3691 3.088541 6.914527 20.08675 2.996721 6.930304 20.02593 2.612821 6.976419 19.81749 4.181736 6.510558 21.54241 3.995733 6.606273 21.1405 3.750051 6.708244 20.76579 3.715734 6.720746 20.72187 3.412642 6.815547 20.39369 3.065853 6.893749 20.1139 2.975483 6.909361 20.05362 2.597474 6.954978 19.84708 3.048146 6.860731 20.13061 2.95897 6.876426 20.07091 2.585953 6.922323 19.86635 2.324527 6.898 19.76877 2.580067 6.883585 19.87229 2.949918 6.836953 20.07494 3.038401 6.821031 20.13409 3.208652 6.784899 20.26152 3.378256 6.741327 20.4089 2.186256 6.9 19.72375 2.188437 6.938269 19.71646 2.194646 6.970711 19.69569 2.203937 6.992388 19.66461 1.761216 6.9 19.62966 1.327033 6.993819 19.53269 1.327033 6.992388 19.53635 1.327033 6.970711 19.56879 1.327033 6.934612 19.5919 1.327033 6.938269 19.59046 1.77068 6.993819 19.56496 1.765455 6.970711 19.60068 1.762111 6.934612 19.62355 -4.566976 6.306133 22.68819 -4.733984 6.156345 23.43217 -4.529117 6.316924 22.69847 -4.695887 6.169061 23.44318 -4.489531 6.311464 22.70611 -4.655232 6.164889 23.45118 -4.454769 6.290657 22.70985 -4.61907 6.144552 23.4548 -4.430587 6.257947 22.70908 -4.593673 6.111577 23.45339 -4.856874 5.800333 24.95945 -5.006447 5.837261 24.94715 -4.967175 5.854642 24.95577 -4.923732 5.853559 24.96126 -4.884453 5.834219 24.96257 -5.683008 4.869236 27.04824 -5.47567 5.221631 26.52851 -5.555075 4.619215 28.00914 -5.618107 4.775323 27.53662 -6.111206 4.160254 27.26889 -5.747066 4.899764 26.56437 -5.885955 4.713625 26.58271 -6.233298 4.160254 26.6286 -7.988434 4.160254 7.53011 -7.865097 4.160254 9.712815 -7.418426 4.160254 15.7742 -6.81935 4.160254 21.82244 -4.451726 6.433351 21.5578 -6.996127 5.334158 9.659766 -7.589188 4.608353 9.695969 -5.487156 6.433351 9.567645 -6.288591 5.948446 9.616569 -4.615134 6.774768 9.514409 -3.697886 6.962769 9.45841 -3.258939 6.962769 15.41501 -4.174486 6.774768 15.49407 -5.044893 6.433351 15.56923 -5.249684 5.948446 21.64699 -5.954151 5.334158 21.72573 -6.544638 4.608353 21.79173 -7.143028 4.608353 15.75042 -6.551067 5.334158 15.6993 -5.844841 5.948446 15.63832 -4.05 5.5 17.75362 -4.05 5.187492 17.75362 -4.05 5.5 10.76767 -4.05 5.187492 8.798735 -4.05 5.5 8.107209 -4.05 4.332663 8.798735 4.05 5.5 8.107209 4.05 4.332663 8.798735 4.05 5.187492 8.798735 4.05 5.5 10.76767 4.05 5.187492 17.75362 4.05 5.5 17.75362 3.69899 5.5 19.44157 3.201562 5.5 19.47867 3.973879 5.5 11.15035 3.757107 5.5 11.47477 4.126976 5.5 19.15728 4.357304 5.5 18.698 4.329169 5.5 18.18497 3.201562 5.5 11.75611 3.432683 5.5 11.69155 2.348197 6.212371 7.6852 3.93944 5.957052 7.836451 3.632207 6.31304 7.625564 3.424727 6.427135 7.557974 3.196237 6.489249 7.521178 2.959548 6.495901 7.517238 2.727931 6.446716 7.546375 -2.348197 6.212371 7.6852 -3.424727 6.427135 7.557974 -3.632207 6.31304 7.625564 -2.727931 6.446716 7.546375 -2.959548 6.495901 7.517238 -3.196237 6.489249 7.521178 -3.93944 5.957052 7.836451 -2.092771 5.78933 9.673161 -2.092771 5.78933 10.76767 -2.126121 5.882683 10.76767 -2.155398 5.946863 8.949193 -2.330841 6.194845 10.76767 -2.243734 6.091553 8.284241 -2.727931 6.446716 10.76767 -3.05 6.5 10.76767 -3.196237 6.489249 10.76767 -3.432683 6.42388 10.76767 -3.632207 6.31304 10.76767 -3.757107 6.207107 10.76767 -3.973879 5.882683 10.76767 -3.93944 5.957052 10.76767 2.243734 6.091553 8.284241 3.973879 5.882683 10.76767 3.93944 5.957052 10.76767 3.757107 6.207107 10.76767 3.632207 6.31304 10.76767 3.432683 6.42388 10.76767 3.196237 6.489249 10.76767 3.05 6.5 10.76767 2.727931 6.446716 10.76767 2.330841 6.194845 10.76767 2.092771 5.78933 10.76767 2.092771 5.78933 9.673161 2.126121 5.882683 10.76767 2.155398 5.946863 8.949193 3.453406 5.415845 19.49157 3.69899 5.326875 19.44157 3.930431 5.236617 19.32813 4.126976 5.154951 19.15728 4.27108 5.092074 18.94479 4.357304 5.053214 18.698 4.376731 5.04433 18.43933 4.329169 5.065997 18.18497 4.216358 5.116253 17.9489 -3.69899 5.5 19.44157 -4.126976 5.5 19.15728 -4.357304 5.5 18.698 -3.973879 5.5 11.15035 -3.757107 5.5 11.47477 -3.432683 5.5 11.69155 -4.329169 5.5 18.18497 -3.201562 5.5 19.47867 -3.201562 5.5 11.75611 3.903553 5.882683 11.12122 3.320598 6.42388 11.03826 3.403553 6.42388 10.91411 3.703281 6.207107 11.03826 3.196447 6.42388 11.12122 2.779402 6.42388 11.03826 2.696447 6.42388 10.91411 2.903553 6.42388 11.12122 2.115037 5.784776 10.9792 2.196446 5.882683 11.12122 2.18104 5.770982 11.18176 2.287066 5.747894 11.36473 2.396718 5.882683 11.42095 2.428882 5.715211 11.52125 2.598953 5.673271 11.64318 2.696447 5.882683 11.62122 2.672118 5.654299 11.68057 2.788852 5.62286 11.72511 3.05 5.882683 11.69155 2.99103 5.564976 11.76381 3.403553 5.882683 11.62122 3.194513 5.502254 11.75717 3.050123 5.547226 11.76655 2.396718 6.207107 11.03826 2.55 6.207107 11.26767 2.779402 6.207107 11.42095 3.05 6.207107 11.47477 3.55 6.207107 11.26767 3.703281 5.882683 11.42095 3.320598 6.207107 11.42095 3.05 6.42388 11.15035 1.927662 5.821537 9.52515 1.293337 5.920042 9.07245 0.6541778 5.979602 8.798735 -0.6541778 5.979602 8.798735 -1.291425 5.920279 9.071361 -3.703281 6.207107 11.03826 -2.903553 6.42388 11.12122 -2.779402 6.42388 11.03826 -2.55 6.207107 11.26767 -3.403553 6.42388 10.91411 -3.320598 6.42388 11.03826 -3.196447 6.42388 11.12122 -2.255919 5.754796 11.31949 -2.436224 5.713462 11.52774 -2.396718 5.882683 11.42095 -3.187105 5.504617 11.75821 -3.403553 5.882683 11.62122 -3.05 5.882683 11.69155 -3.050625 5.547074 11.76656 -2.790266 5.622471 11.72555 -2.696447 5.882683 11.62122 -2.67267 5.654153 11.68082 -2.16186 5.775036 11.13585 -3.55 6.207107 11.26767 -3.320598 6.207107 11.42095 -3.05 6.207107 11.47477 -2.196446 5.882683 11.12122 -2.396718 6.207107 11.03826 -2.696447 6.42388 10.91411 -3.903553 5.882683 11.12122 -3.703281 5.882683 11.42095 -2.779402 6.207107 11.42095 -3.05 6.42388 11.15035 -2.114915 5.784801 10.97863 -4.216795 5.116062 17.94957 -4.376728 5.044331 18.43928 -4.329169 5.065997 18.18497 -4.271001 5.092109 18.94495 -4.357304 5.053214 18.698 -3.93079 5.236472 19.32789 -4.126976 5.154951 19.15728 -3.453079 5.415959 19.4916 -3.69899 5.326875 19.44157 3.194513 5.502254 8.798735 -3.187105 5.504617 8.798735 -1.923875 5.822243 8.798735 1.927662 5.821537 8.798735 -2.643773 5.661716 11.26294 -3.629146 5.352883 18.61615 3.629146 5.352883 18.61615 + + + + + + + + + + -0.2895353 -0.171139 -0.9417435 -0.5154998 -0.4731217 -0.714434 -0.5780622 -0.02747595 -0.8155301 -0.4023695 -0.0231049 -0.9151858 -0.188764 -0.03995418 -0.9812093 -0.1887338 -0.175579 -0.9662048 -0.1887887 -0.1755827 -0.9661933 -0.1891638 -0.2797012 -0.9412674 -0.1063235 -0.07789486 -0.9912759 -0.1000905 -0.007356464 -0.9949511 -0.04241001 0.09586173 -0.9944908 -0.3244353 -0.03847819 -0.9451249 -0.3115963 -0.04149687 -0.949308 -0.2898741 -0.04750996 -0.9558849 -0.2506396 -0.03375577 -0.9674918 -0.3231226 -0.03299814 -0.9457816 -0.1760616 0.03488266 -0.983761 -0.1380991 -0.002757549 -0.9904146 -0.6668519 -0.02424812 -0.7447957 -0.6338672 -0.04102927 -0.7723529 -0.6182429 -0.03595596 -0.7851643 -0.6060559 -0.03284513 -0.7947437 -0.6731097 -0.4667845 -0.5736162 -0.7037252 -0.4161781 -0.5758184 -0.6121894 -0.422422 -0.668419 -0.1156609 -0.5256778 -0.8427844 -0.2021372 -0.5301694 -0.8234446 -0.02227544 -0.537334 -0.8430753 -0.1845081 -0.4301429 -0.8837047 -0.09795051 -0.4922756 -0.8649107 -0.09800934 -0.527709 -0.843752 -0.02736699 -0.5038189 -0.8633758 -0.2895401 -0.4408307 -0.8496087 -0.2902707 -0.4963681 -0.8181453 -0.2922323 -0.499732 -0.8153946 -0.5140997 -0.0288794 -0.8572441 -0.4708547 -0.04515182 -0.8810546 -0.4703653 -0.1577828 -0.8682518 -0.2895312 -0.1711379 -0.9417449 -0.2895324 -0.3094325 -0.9057718 -0.5972981 -0.2592748 -0.7589544 -0.1239342 -0.3567693 -0.9259353 -0.118966 -0.3537421 -0.9277466 -0.4703671 -0.2852842 -0.8350855 -0.4703614 -0.4064298 -0.7833104 -0.4703646 -0.4064301 -0.7833082 -0.4706035 -0.5118387 -0.7187167 -0.4337796 -0.4458498 -0.7829772 -0.6337385 -0.4441217 -0.6333495 -0.6342358 -0.3879602 -0.6687539 -0.6163799 -0.3626668 -0.6989626 -0.6339625 -0.3370549 -0.69605 -0.6333215 -0.2501819 -0.732334 -0.6110349 -0.2723152 -0.7432905 -0.6342868 -0.2110275 -0.743739 -0.1236757 -0.4570197 -0.8808164 -0.2895355 -0.4408288 -0.8496112 -0.2895314 -0.3094334 -0.9057719 -0.4703654 -0.285285 -0.8350862 -0.4703665 -0.1577828 -0.8682511 -0.6333188 -0.1383696 -0.7614206 -0.6333192 -0.1383683 -0.7614205 -2.0668e-6 0.8603659 -0.5096771 0 0.8603653 -0.5096779 0 0.8603657 -0.5096774 0 0.8603659 -0.5096769 0 -0.5040147 -0.8636951 0.1089965 -0.5130465 -0.8514124 0 -0.5374646 -0.8432863 1 0 0 1 6.32833e-7 0 1 -2.45798e-7 0 0 1 0 0 1 -2.97617e-7 0 1 2.49116e-7 0 1 4.98233e-7 0 1 0 0 1 1.94133e-7 0 1 0 0.8337618 -0.5472953 0.07286518 0.5620495 -0.7734696 0.2929936 0.6124846 -0.7351361 0.2905813 0.6863391 -0.7258385 0.04579466 0.07500314 -0.9939628 0.08007812 0.04453909 -0.9663461 0.2533602 0.9372626 -0.2891719 0.1947264 0.9735082 -0.1724321 0.1501631 0.9744394 -0.1516211 0.1657679 0.9551157 -0.2360618 0.1789657 0.9473245 -0.2636582 0.1818257 0.9402145 -0.2785891 0.1959207 0.9249437 -0.3170945 0.2095959 0.9866212 -0.1053836 0.1243907 0.9873881 -0.103165 0.1200903 0.9936239 -0.0274074 0.1093633 0.9920728 -0.05636543 0.1123152 0.9947988 -0.01040452 0.1013266 0.9962333 -0.01085638 0.08603227 0.9953664 -0.02505493 0.09283393 0.9974476 -0.01105231 0.07054287 0.9971219 -0.01086497 0.07503253 0.9978733 -0.01089525 0.0642659 0.9967068 -0.0463581 0.06653302 0.9921115 -0.1058644 0.06713938 0.9921388 -0.1055449 0.06723695 0.9782704 -0.1959636 0.06771469 0.9597774 -0.2719154 0.06992512 0.9579045 -0.2789638 0.06780946 0.8983007 -0.4330749 0.07417684 0.9241785 -0.3760216 0.06709647 0.9001334 -0.4296492 0.07184314 0.8884085 -0.4554609 0.05732166 0.8369721 -0.5445428 0.05432438 0.8349301 -0.5475628 0.05537992 0.8119769 -0.5812863 0.05291551 0.226494 -0.9738323 0.01874136 0.227155 -0.9736671 0.01931679 0.6959427 -0.6612604 0.2799975 0.407242 -0.8626903 0.2998658 0.07918012 -0.9534631 0.2909272 0.08009546 -0.9534649 0.2906708 0.1707518 -0.9415448 0.2904089 0.1936797 -0.9376146 0.2887336 0.2278028 -0.9273868 0.2967485 0.29565 -0.9069965 0.2999142 0.4612503 -0.834954 0.3001671 0.4018763 -0.8648592 0.3008556 0.4061846 -0.8741597 0.2661936 0.3224507 -0.9089025 0.2644277 0.3254393 -0.9149543 0.2386379 0.2018582 -0.9514963 0.2321814 0.2030521 -0.9510468 0.2329806 0.05300313 -0.9739616 0.2204306 0.06702214 -0.9782627 0.1962404 0.3466777 -0.8882254 0.3014469 0.3168649 -0.9002887 0.2984579 0.3210182 -0.9092962 0.2648164 0.1973795 -0.9456299 0.2585064 0.198706 -0.9451091 0.2593932 0.06168633 -0.966844 0.2478051 0.05599462 -0.973955 0.2197186 0.4039139 -0.9146652 0.01553189 0.4343306 -0.9002161 0.03111481 0.4327354 -0.8998324 0.05515235 0.5131856 -0.8562112 0.05952417 0.5113065 -0.8551243 0.08560562 0.5867728 -0.8048885 0.0886141 0.5848094 -0.8031636 0.113694 0.6548961 -0.7469283 0.1149322 0.6528836 -0.7446422 0.138748 0.7169381 -0.6833693 0.137863 0.7149041 -0.6806159 0.1602317 0.7733084 -0.6143094 0.1569018 0.7712912 -0.6111801 0.1776765 0.8234686 -0.5407786 0.171634 0.8215004 -0.5373882 0.1906594 0.8873381 -0.4258959 0.1767594 0.5837424 -0.7571979 0.2930806 0.560436 -0.7745132 0.2933276 0.5643038 -0.7828094 0.2622421 0.4889171 -0.8311498 0.2648586 0.491779 -0.8369393 0.240179 0.4117251 -0.8791248 0.2400457 0.4145313 -0.8844094 0.2144387 0.3306868 -0.9196384 0.2119237 0.33341 -0.9243323 0.1856007 0.2099492 -0.9612148 0.1788504 0.210864 -0.9609002 0.1794639 0.07224023 -0.9830123 0.1687253 0.05344814 -0.9873327 0.1493905 0.5163818 -0.8023526 0.2992998 0.4836179 -0.8231948 0.2974293 0.4876057 -0.8317746 0.2653146 0.4075556 -0.8736526 0.2657624 0.4104893 -0.8795977 0.2404301 0.3267139 -0.9145901 0.2382919 0.3295715 -0.919969 0.2122259 0.2060503 -0.9566937 0.2056223 0.2071087 -0.9563119 0.2063338 0.06901133 -0.9783125 0.1952999 0.05925643 -0.9822341 0.1780586 0.5720998 -0.8196241 0.03030264 0.5905495 -0.8059971 0.04024928 0.5890206 -0.8056374 0.06327223 0.6591765 -0.7490361 0.06656783 0.6574398 -0.7480303 0.09068399 0.7214753 -0.6862751 0.09219515 0.7196934 -0.6847123 0.114937 0.7779806 -0.6177977 0.1143341 0.7761939 -0.6157725 0.1354526 0.8281607 -0.544622 0.1324267 0.8264029 -0.5422404 0.1517686 0.8916772 -0.4295377 0.1428612 0.7430229 -0.6117206 0.2715049 0.6976853 -0.6596997 0.2793413 0.7013812 -0.6675663 0.2498393 0.6369769 -0.7269527 0.2565158 0.6396129 -0.7322913 0.2337625 0.5694215 -0.7869883 0.237505 0.5720599 -0.7919574 0.2134266 0.4967213 -0.8409925 0.2144754 0.4993267 -0.8454893 0.1892641 0.419219 -0.8882177 0.1879491 0.42175 -0.8921421 0.1618937 0.3377511 -0.9277747 0.158614 0.3401764 -0.9310604 0.1319341 0.2168142 -0.9681923 0.1248805 0.2174345 -0.9679994 0.1252974 0.07322716 -0.990687 0.1147921 0.06535816 -0.9918623 0.1092594 0.6467713 -0.7068272 0.2865 0.632144 -0.7199189 0.28655 0.6358211 -0.7277805 0.2570354 0.5655525 -0.7820747 0.2617434 0.5683094 -0.7876605 0.2379401 0.4929516 -0.8363646 0.239777 0.4956854 -0.8415144 0.2148246 0.4156144 -0.8839821 0.2141037 0.4182859 -0.8885972 0.1882342 0.33437 -0.9240379 0.1853395 0.3369469 -0.9280296 0.1588325 0.2135385 -0.9650482 0.1519318 0.2143085 -0.964796 0.1524487 0.07074141 -0.9873887 0.1416307 0.06584817 -0.9897136 0.1270084 0.7254194 -0.686622 0.04813647 0.7249107 -0.6871803 0.04783052 0.7234917 -0.6868563 0.06919604 0.7817439 -0.6195026 0.07136738 0.7802005 -0.6186119 0.09277176 0.8320404 -0.5468947 0.09281748 0.8304969 -0.5455427 0.1125084 0.8953353 -0.4319314 0.1086728 0.8569855 -0.4563228 0.2394689 0.8112484 -0.5243465 0.2587214 0.8149437 -0.5321143 0.2296106 0.762299 -0.6010572 0.240064 0.7646265 -0.6057771 0.2199556 0.7059167 -0.6708397 0.227279 0.7083048 -0.675333 0.2054986 0.6440923 -0.7355877 0.2098947 0.6464992 -0.739738 0.1866188 0.576393 -0.7951586 0.1883987 0.5787709 -0.7988539 0.1638804 0.5034216 -0.8484634 0.16333 0.5057431 -0.8516138 0.1377597 0.4255386 -0.8947777 0.1352401 0.4277744 -0.8973129 0.1088057 0.3435932 -0.9332589 0.1047456 0.345715 -0.9351193 0.07767289 0.2224131 -0.9724142 0.07030832 0.2227304 -0.972326 0.07052212 0.05952745 -0.9972802 0.04345971 0.07758659 -0.9951365 0.06069344 0.05170553 -0.9949553 0.08596873 0.2202443 -0.9705109 0.09798562 0.2197729 -0.9706497 0.09766852 0.3431024 -0.9334245 0.1048783 0.3408271 -0.9308472 0.1317592 0.4249127 -0.8950468 0.1354266 0.4225295 -0.891816 0.1616574 0.5026811 -0.8488559 0.163571 0.5002146 -0.8450303 0.1889684 0.5755494 -0.7956945 0.1887153 0.5730344 -0.7913538 0.2130514 0.6431795 -0.7362746 0.2102853 0.6406552 -0.7315248 0.2333072 0.7049573 -0.6716841 0.2277629 0.7024672 -0.6666336 0.2492779 0.7613199 -0.6020622 0.2406513 0.758099 -0.5951886 0.2665268 0.8075776 -0.528839 0.2610511 0.7833426 -0.6194689 0.05130946 0.7831877 -0.6196732 0.05120885 0.7818557 -0.619367 0.07131814 0.8336611 -0.5474418 0.0729171 0.8322347 -0.5466171 0.09271091 0.8970553 -0.4323555 0.09143573 0.9022188 -0.4196621 0.09942346 0.9580227 -0.2709103 0.09380924 0.9578078 -0.2717449 0.09358972 0.9908218 -0.1051204 0.08498197 0.990747 -0.1059898 0.08477491 0.9949437 -0.05814689 0.08189004 0.9966032 -0.01127564 0.08157825 0.6532715 -0.7558418 0.04404062 0.6606065 -0.7492434 0.04725986 0.6593097 -0.748923 0.06652116 0.723365 -0.6869848 0.0692448 0.7217176 -0.6860336 0.09209579 0.7799816 -0.6188725 0.09287554 0.7783122 -0.6174098 0.1141721 0.8302036 -0.5459548 0.1126748 0.8285503 -0.5440856 0.1321944 0.8938854 -0.4302904 0.1257743 0.8988492 -0.417616 0.1329179 0.9555548 -0.2691902 0.1202156 0.9551713 -0.2706883 0.1198986 0.9892085 -0.1042446 0.1029545 0.989074 -0.1057908 0.1026686 0.9946407 -0.04016232 0.09527403 0.9952255 -0.01105827 0.09697395 0.4953387 -0.8680005 0.03485387 0.5146392 -0.8564613 0.04025763 0.5133391 -0.8561223 0.0594778 0.5888738 -0.8057408 0.06331986 0.5870599 -0.8046897 0.08851778 0.6571711 -0.7482547 0.09078103 0.6552932 -0.7466027 0.1147834 0.7193327 -0.6850652 0.115092 0.7174249 -0.682902 0.1376462 0.7757585 -0.6162721 0.1356745 0.7738583 -0.6136908 0.1566114 0.8259125 -0.5429024 0.1520711 0.8240507 -0.5400095 0.1712608 0.8900322 -0.426993 0.1597487 0.8948506 -0.4143106 0.1661002 0.9526013 -0.2667033 0.1463563 0.952048 -0.2688601 0.1460102 0.9870542 -0.1051689 0.1210932 0.9877876 -0.1077942 0.1124999 0.3180594 -0.9477557 0.02444213 0.3495446 -0.936446 0.02979314 0.348169 -0.936079 0.05034464 0.4325715 -0.8999084 0.05519855 0.4306429 -0.8987944 0.08194833 0.5110076 -0.8552937 0.08569693 0.5089746 -0.8535088 0.1116586 0.5843857 -0.8034512 0.1138405 0.582282 -0.8010628 0.1387301 0.6523561 -0.7450661 0.1389538 0.6502102 -0.7421563 0.1625757 0.7143035 -0.6811809 0.1605091 0.7121472 -0.6778365 0.1827131 0.7706296 -0.6119087 0.1780388 0.7685002 -0.6082333 0.1986451 0.8208126 -0.5382761 0.1911163 0.818754 -0.534397 0.209909 0.8855127 -0.4224656 0.1933654 0.890167 -0.4099256 0.1989065 0.9491815 -0.2634627 0.1721687 0.9484581 -0.266254 0.1718609 0.9772047 -0.1513825 0.1488428 0.969955 -0.1985156 0.140637 0.06429404 -0.9979298 0.00163871 0.133777 -0.9668325 0.2175743 0.07669436 -0.9969336 0.01553803 0.06553089 -0.9978086 0.009145557 0.07705932 -0.9964688 0.03334456 0.2248892 -0.9734362 0.04297626 0.2247243 -0.9734792 0.04286509 0.3480051 -0.9361376 0.05038851 0.3460444 -0.9350048 0.07758533 0.430329 -0.8989363 0.08204019 0.4282428 -0.8971062 0.1086673 0.5085223 -0.8537599 0.1117992 0.5063434 -0.851288 0.1375696 0.5817192 -0.8014368 0.1389315 0.5794773 -0.7983946 0.1636226 0.6495588 -0.7426686 0.1628394 0.6472795 -0.739137 0.1862948 0.7114233 -0.6785034 0.1830575 0.7091462 -0.6745754 0.205085 0.7677341 -0.6090583 0.1990793 0.7655044 -0.6048539 0.219442 0.8179733 -0.5353808 0.2104451 0.8158252 -0.531031 0.2289879 0.8823549 -0.4210344 0.2101902 0.8803866 -0.4167928 0.2262812 0.8898715 -0.3955713 0.2272711 1.56909e-7 -0.9999981 -0.001993656 1.56213e-7 -0.999998 -0.001990079 1.57874e-7 -0.9999386 0.01108515 -8.12165e-6 -0.9999391 0.01104563 2.74841e-5 -0.9992028 0.03992295 -6.90197e-5 -0.9992132 0.03966271 7.02415e-5 -0.9971578 0.07534188 -1.1273e-4 -0.9971928 0.07487756 8.15114e-5 -0.9945075 0.1046655 6.58774e-6 -0.9945359 0.1043953 6.5642e-6 -0.9925398 0.121922 -4.26849e-5 -0.9924948 0.1222873 1.58757e-4 -0.9894256 0.1450413 -1.30442e-4 -0.9893282 0.145704 8.18118e-5 -0.9849207 0.1730067 -0.00204426 -0.9835586 0.1805776 -3.93798e-5 -0.9817075 0.1903957 9.91954e-5 -0.9766417 0.2148742 -5.52191e-5 -0.9767044 0.2145893 5.77811e-5 -0.9684672 0.2491411 -1.09181e-5 -0.9684962 0.2490287 8.98897e-6 -0.959025 0.2833216 0 -0.9590287 0.2833092 -0.9979352 -0.06423002 0 -0.1022673 -0.994757 4.05539e-6 -0.0727775 -0.9972589 -0.01335638 -0.1745682 -0.9846451 0 -0.2558171 -0.9667252 0 -0.3029242 -0.9529435 -0.01164436 -0.3537254 -0.9353494 0 -0.4381347 -0.8989093 0 -0.4912313 -0.8709552 -0.01136034 -0.5283027 -0.8490561 0 -0.6034287 -0.7974171 0 -0.6590127 -0.7520676 -0.009841144 -0.8095896 -0.5869963 0 -0.7993505 -0.6008298 -0.006518721 -0.7445928 -0.667519 0 -0.6820243 -0.7313296 0 -0.8584371 -0.512919 0 -0.9010689 -0.4336748 -0.001083195 -0.9054001 -0.4245291 -0.005084693 -0.9399209 -0.3413925 0 -0.9656715 -0.2597665 0 -0.9731181 -0.2300995 -0.009777009 -0.9873097 -0.1588072 0 0 -1 3.49736e-6 1.56132e-7 -1 4.99623e-6 0.9943841 -0.1057851 -0.003123462 0.9947181 -0.102549 -0.004431843 0.9999405 -0.01091057 0 0.9805293 -0.1963731 0 0.9601151 -0.2796055 0 0.9527182 -0.3037327 -0.008632183 0.9262654 -0.376872 0 0.8898718 -0.4562107 0 0.8703963 -0.4922255 -0.01116055 0.8382099 -0.545348 0 0.8131127 -0.5821063 0 0.7843759 -0.6202854 -7.21607e-4 0.7261232 -0.6872889 -0.01946943 0.7512883 -0.65996 -0.004329025 0.6870611 -0.7265996 0 0.6539049 -0.7565768 0 0.5999369 -0.7999802 -0.01037615 0.5723632 -0.8200003 0 0.4956392 -0.8685286 0 0.4238925 -0.9056789 -0.00779581 0.2271959 -0.973843 -0.00342977 0.2299542 -0.9731908 -0.004577219 0.3181542 -0.9480391 0 0.4039624 -0.9147757 0 0.1370593 -0.9905629 0 0.06429433 -0.9979311 0 0.06430977 -0.99793 4.29439e-6 -0.7591602 0.07266849 -0.6468347 -0.7618213 0.2651875 -0.5910195 -0.7334767 0.2395238 -0.6361134 -0.7511156 0.1589869 -0.6407406 -0.7525035 0.1605471 -0.63872 -0.7695157 0.09466528 -0.6315729 -0.7668489 0.08144146 -0.6366398 -0.8175421 0.0559464 -0.5731448 1 -4.05387e-6 -1.54899e-6 1 -7.86092e-6 -1.20416e-6 1 -4.47183e-6 0 -0.7156162 0.3914381 -0.5785065 -0.7020357 0.46547 -0.5389654 -0.703247 0.3155101 -0.6371005 -0.7103036 0.3448476 -0.6136359 -0.6997327 0.4116376 -0.5838911 -0.7062839 0.05742269 -0.705596 -0.7096744 0.07865667 -0.7001253 -0.703214 0.1340841 -0.6982203 -0.7107032 0.171492 -0.6822693 -0.7030496 0.2269214 -0.6739645 -0.7073743 0.2490845 -0.6614972 -0.7066241 0.2896661 -0.6455819 -0.08820682 0.1497394 -0.9847831 -0.3397942 0.07452988 -0.9375422 -0.5151813 0.06362152 -0.8547167 -0.6773146 0.05967426 -0.7332693 -0.1406913 0.7429089 -0.6544406 -0.6286816 0.5185526 -0.5795368 -0.618483 0.5030917 -0.603637 -0.5623709 0.6315605 -0.5337326 -0.6156538 0.06772613 -0.7851011 -0.6419123 0.08396315 -0.7621673 -0.6410768 0.1447392 -0.7537049 -0.6410781 0.1447384 -0.7537041 -0.6410784 0.244897 -0.7273542 -0.6410779 0.2448971 -0.7273544 -0.6410771 0.3405983 -0.6877594 -0.6410781 0.3405961 -0.6877596 -0.6410781 0.4300952 -0.6356391 -0.6410769 0.4300941 -0.6356409 -0.6414679 0.5014249 -0.5805964 -0.1777294 0.07433259 -0.981268 -0.1027452 0.08898985 -0.9907191 -0.08821588 0.09665471 -0.991401 -0.03413021 0.07855427 -0.9963254 -0.1389266 0.2145801 -0.9667755 -0.08804339 0.1878564 -0.9782425 -0.0881108 0.3056082 -0.9480718 -0.1067866 0.3172723 -0.9423031 -0.08824026 0.3688705 -0.9252828 -0.088045 0.4420667 -0.8926506 -0.08803784 0.4420639 -0.8926527 -0.08823102 0.5123799 -0.8542143 -0.1067811 0.5571975 -0.8234859 -0.08810395 0.5688551 -0.8177052 -0.08817076 0.642643 -0.7610756 -0.1175499 0.662188 -0.7400603 -0.0882039 0.6925303 -0.7159762 -0.08821582 0.7294611 -0.67831 -0.03562325 0.7447947 -0.6663421 -0.3088135 0.4955157 -0.8118489 -0.4793857 0.6629521 -0.5750511 -0.4791787 0.5852697 -0.6541003 -0.4791783 0.5852708 -0.6540996 -0.4791773 0.4918754 -0.7269442 -0.4791837 0.4918749 -0.7269403 -0.4791826 0.3895208 -0.7865478 -0.4791806 0.3895204 -0.7865495 -0.4791802 0.280074 -0.8318324 -0.4791809 0.2800743 -0.8318319 -0.4791823 0.1655293 -0.8619654 -0.4791774 0.1655284 -0.8619684 -0.4799906 0.09620052 -0.8719832 -0.4129907 0.07211804 -0.9078754 -0.2720407 0.6958305 -0.6646907 -0.2808187 0.6999835 -0.6566308 -0.2802801 0.6400821 -0.7153587 -0.2802832 0.6400836 -0.7153562 -0.2802838 0.537941 -0.7950224 -0.280278 0.5379401 -0.795025 -0.2802785 0.426 -0.860214 -0.2802779 0.4259995 -0.8602143 -0.2802787 0.306304 -0.9097371 -0.2802792 0.306307 -0.909736 -0.2802816 0.1810306 -0.9426931 -0.2802792 0.1810297 -0.942694 -0.280851 0.1046319 -0.9540309 -0.2570863 0.09008461 -0.9621806 0.9959292 -0.00166887 0.09012454 0.9963986 0.002443432 0.08475869 0.9971073 0.01182937 0.07508015 0.9965611 0.02607595 0.07865202 0.997183 0.0135532 0.07377392 0.9975265 0.00696969 0.06994545 0.9979382 -6.27126e-6 0.06418222 0.9954642 0.002233207 0.09511142 0.9956644 -6.38167e-4 0.09301602 0.9950298 6.4842e-4 0.09957677 0.9951374 -0.001398503 0.09848743 0.9947235 2.4839e-4 0.1025928 0.9945191 -4.10135e-4 0.104555 0.9944378 1.62361e-4 0.1053258 0.9941447 -2.34947e-4 0.1080573 0.9939553 -0.002009391 0.1097669 0.9938777 -0.002884149 0.1104482 0.9937739 -0.004189074 0.111337 0.9937604 -0.003790915 0.1114714 0.9932118 0.005287349 0.1162 0.9797877 -0.1168155 0.1623899 0.9717916 -0.1682013 0.1653167 0.9939841 0.005191206 0.1094027 0.9862517 -0.06452983 0.1521307 0.9876946 -0.06285578 0.1432088 0.9908557 -0.04360824 0.1276847 0.9910766 -0.04641371 0.1249524 0.9935464 -0.007824301 0.1131566 0.9595036 -0.2115672 0.18599 0.9695639 -0.1391716 0.2014381 0.9696764 -0.1634479 0.181693 0.9876359 -0.06718045 0.141641 0.9851898 -0.1155346 0.1266998 0.9850013 -0.09684973 0.142803 0.8786404 -0.2789913 0.3874983 0.9205101 -0.3068655 0.2418571 0.1737242 -0.5986813 0.7819211 0.8476794 -0.1604934 0.5056496 0.7074398 -0.01816499 0.7065402 0.4404329 -0.1989514 0.8754641 0.05525726 -0.7283889 0.6829322 0.04912942 -0.8165953 0.5751161 0.07660889 -0.9474856 0.3104869 0.07789605 -0.9253858 0.3709357 0.07804262 -0.9254296 0.3707959 0.06640291 -0.8941296 0.4428579 0.04075109 -0.5461485 0.8366967 0.04328078 -0.5735892 0.817999 0.0602284 -0.6145083 0.786608 0.08121204 -0.5994768 0.7962614 0.04521143 -0.644997 0.7628466 0.01292914 -0.263789 0.9644938 0.04257959 -0.2695155 0.9620543 0.2370525 -0.259255 0.9362655 0.1828095 -0.2644208 0.9469226 0.6707865 -0.2350226 0.7034273 0.6117364 -0.1893296 0.7680709 0.5988967 -0.2216805 0.7695328 0.5544311 -0.2272532 0.8006012 0.5237839 -0.2427424 0.8165333 0.5006585 -0.2158794 0.8382942 0.3945809 -0.2840736 0.8738468 0.7960522 -0.2289025 0.5602721 0.9349454 -0.1712532 0.3107244 0.934249 -0.1853435 0.3046749 0.9413447 -0.2352101 0.2419633 0.02111303 -0.4766266 0.8788523 0.06550043 -0.5053658 0.8604157 0.1639257 -0.4936689 0.8540606 0.1736057 -0.5988379 0.7818276 0.340889 -0.5599126 0.7551773 0.9112563 -0.1929125 0.363864 0.9052495 -0.2014424 0.3740915 0.8752897 -0.2495996 0.4142079 0.8720888 -0.2429587 0.4247734 0.8029365 -0.3147993 0.5061565 0.8028362 -0.3147566 0.5063421 0.7464541 -0.3619669 0.5583783 0.7463619 -0.361917 0.5585339 0.683444 -0.4064814 0.6063639 0.6833363 -0.4064413 0.6065122 0.614577 -0.4477586 0.649467 0.6144515 -0.4477292 0.6496061 0.5406562 -0.4852975 0.6871516 0.5405572 -0.4852645 0.6872529 0.4627219 -0.518641 0.7189576 0.4625861 -0.5186142 0.7190643 0.3407719 -0.5600997 0.7550914 0.3317195 -0.4616923 0.8226801 0.1638233 -0.4938088 0.8539994 0.1560509 -0.3794133 0.9119724 0.05679303 -0.3884575 0.9197149 0.02628034 -0.372205 0.9277784 0.8732635 -0.262628 0.4104114 0.8467735 -0.2199866 0.4843355 0.7977598 -0.2595924 0.5442345 0.7976877 -0.2595265 0.5443716 0.7405222 -0.2984839 0.6021083 0.7404276 -0.2984315 0.6022505 0.6767764 -0.3351982 0.6554509 0.6766726 -0.3351536 0.6555808 0.6072331 -0.3692436 0.7035107 0.6071327 -0.3691944 0.7036231 0.53272 -0.4001894 0.7456929 0.532618 -0.400145 0.7457897 0.4542281 -0.4276843 0.7815133 0.4540932 -0.4276384 0.7816169 0.3316134 -0.4618627 0.8226272 0.3243427 -0.3548518 0.8768593 0.1559475 -0.3795484 0.9119339 0.1519947 -0.2906512 0.9446797 0.08085328 -0.2570881 0.9629998 0.7995018 -0.2367163 0.5520528 0.7673801 -0.1986129 0.6096564 0.7368442 -0.2412011 0.6315715 0.7165188 -0.2382736 0.6556116 0.6714111 -0.2576397 0.694859 0.6713435 -0.2575877 0.6949436 0.6013185 -0.2838144 0.746904 0.6012322 -0.2837586 0.7469946 0.5263274 -0.3075919 0.7926958 0.5262134 -0.307532 0.792795 0.447373 -0.3287091 0.8317498 0.4472993 -0.328673 0.8318037 0.3242537 -0.3549952 0.876834 0.3215673 -0.2864395 0.9025225 0.2956924 -0.2598003 0.9192769 0.8506065 -0.441744 0.285186 0.8306272 -0.4680657 0.3016174 0.8064895 -0.5261558 0.2696943 0.7791987 -0.5420343 0.3147196 0.7348598 -0.5931583 0.328853 0.7192075 -0.6044955 0.3425286 0.6887142 -0.6445673 0.3319725 0.6541349 -0.6666974 0.3572427 0.158928 -0.9125717 0.3767691 0.2146614 -0.8952162 0.3905233 0.225319 -0.8881487 0.400529 0.5095431 -0.7766327 0.3704153 0.5056979 -0.7776415 0.3735551 0.2843619 -0.8798974 0.3806824 0.335571 -0.8617655 0.3804633 0.3888506 -0.8287774 0.4023968 0.3927242 -0.8285826 0.3990221 0.4505596 -0.8099361 0.3754991 0.5518438 -0.749879 0.3648973 0.5732674 -0.733191 0.3657808 0.5836778 -0.7232212 0.3691495 0.6028527 -0.7130385 0.3579732 0.6374299 -0.6854723 0.3518678 0.9323046 -0.2774398 0.2320244 0.9577488 -0.177942 0.2259513 0.8896965 -0.3393427 0.3054286 0.8839321 -0.3115662 0.3486986 0.8158895 -0.4074371 0.4102673 0.8158022 -0.4074395 0.4104388 0.7613525 -0.4684891 0.4481746 0.7612571 -0.4684896 0.448336 0.7001602 -0.5261184 0.4826751 0.7000578 -0.5261241 0.4828174 0.6329779 -0.5795634 0.5132694 0.6328588 -0.5795751 0.5134028 0.560617 -0.6281476 0.5395732 0.5604996 -0.6281539 0.5396878 0.484026 -0.6713155 0.5612971 0.4838956 -0.6713162 0.5614088 0.3639095 -0.724904 0.5848796 0.3637647 -0.7248441 0.5850439 0.1983202 -0.7750804 0.5999329 0.1981656 -0.7750092 0.6000762 0.07379293 -0.7969255 0.5995535 0.05337268 -0.7667557 0.6397165 0.07411193 -0.8656789 0.4950835 0.07950109 -0.8683452 0.4895471 0.2124944 -0.8433352 0.4935908 0.2126272 -0.8433768 0.4934625 0.3771691 -0.7887446 0.4854125 0.3772912 -0.7887781 0.4852634 0.4963188 -0.7304865 0.4691025 0.4964176 -0.7304772 0.4690126 0.5721131 -0.683526 0.4532978 0.572228 -0.683503 0.4531872 0.6435859 -0.6306664 0.4336556 0.6436955 -0.6306391 0.4335325 0.7097991 -0.5725077 0.4103903 0.7098909 -0.5724826 0.4102666 0.7699363 -0.5097897 0.3838135 0.7700228 -0.5097677 0.3836692 0.8233504 -0.4433665 0.3542886 0.8234362 -0.44334 0.3541225 0.8897097 -0.3390787 0.3056833 0.8958356 -0.3606026 0.2597007 0.8679989 -0.3547047 0.3475089 0.05022525 -0.6865143 0.7253796 0.07285749 -0.7112574 0.6991457 0.1851277 -0.6930783 0.6966851 0.185281 -0.6931661 0.6965571 0.3515636 -0.6482074 0.6754482 0.3517145 -0.6482967 0.6752839 0.4725898 -0.6003488 0.6451668 0.4727149 -0.6003655 0.6450596 0.5499038 -0.5617511 0.618095 0.5500532 -0.5617635 0.6179508 0.623098 -0.5183089 0.5857515 0.6232182 -0.5183171 0.5856163 0.6911775 -0.4705126 0.5485359 0.6913018 -0.4705198 0.5483732 0.7533507 -0.4189654 0.5068833 0.7534638 -0.4189781 0.5067049 0.8089176 -0.3643693 0.4613972 0.8090243 -0.3643878 0.4611955 0.8786664 -0.2786125 0.3877122 0.883906 -0.3119022 0.3484643 0.942243 -0.1964362 0.2712767 0.9470199 -0.2172194 0.2365775 0.9578986 -0.2077298 0.198189 -0.002489149 -0.6489019 0.760868 0 -0.9435645 0.331189 -0.00293976 -0.9505258 0.3106318 0.00511378 -0.9195315 0.3929833 -3.90438e-4 -0.9285676 0.3711632 2.38636e-4 -0.8955856 0.4448894 4.12843e-5 -0.896418 0.4432096 -7.20148e-6 -0.8585579 0.5127165 -0.004461944 -0.8684592 0.4957406 0.006319403 -0.7962834 0.6048909 -0.005532622 -0.8178662 0.575382 0.00159353 -0.7571074 0.6532886 3.82885e-6 -0.7681429 0.6402785 4.90509e-6 -0.7230152 0.6908322 -0.001913249 -0.7298083 0.6836492 5.79769e-4 -0.6876387 0.7260529 0 -0.2638441 0.9645653 -5.66539e-4 -0.2660722 0.963953 5.88264e-4 -0.3724339 0.9280586 4.83822e-4 -0.3728367 0.9278969 -4.85556e-4 -0.4768378 0.8789912 0.001587569 -0.4696803 0.8828352 -7.77499e-4 -0.5468201 0.8372498 3.23632e-5 -0.5414836 0.8407114 3.00403e-5 -0.5743541 0.818607 -5.63635e-4 -0.5858054 0.8104517 6.42493e-4 -0.6018889 0.7985796 -0.001777887 -0.645897 0.7634226 -0.770007 -0.5097098 0.3837776 -0.6911925 -0.4706031 0.5484393 -0.1700254 -0.910317 0.3773782 -0.05701017 -0.8568716 0.5123682 -0.04452532 -0.585003 0.8098081 -0.02131927 -0.4694654 0.8826935 -0.6700171 -0.2158685 0.7102661 -0.9696868 -0.1581151 0.1862988 -0.9330795 -0.157059 0.3235663 -0.9236334 -0.2807131 0.260963 -0.9344295 -0.1849791 0.3043426 -0.9413924 -0.2346677 0.2423046 -0.9421787 -0.196588 0.2713902 -0.9496064 -0.2316372 0.2111679 -0.9489743 -0.2049981 0.2396323 -0.9473417 -0.2004684 0.249712 -0.7362787 -0.2349904 0.6345654 -0.7538162 -0.2054772 0.6241316 -0.7961341 -0.2302038 0.5596221 -0.6676014 -0.1971365 0.7179455 -0.5994251 -0.2311722 0.7663217 -0.5848865 -0.1978917 0.7866046 -0.5241221 -0.248896 0.8144611 -0.4832401 -0.215604 0.8485245 -0.4442287 -0.2522267 0.859676 -0.3760721 -0.2351523 0.8962551 -0.3217006 -0.289076 0.901634 -0.2764552 -0.2558194 0.9263525 -0.2193045 -0.2619013 0.9398475 -0.1514925 -0.2808653 0.9477155 -0.1493987 -0.278696 0.9486879 -0.03934979 -0.2612023 0.9644818 -0.04577183 -0.265667 0.9629777 -0.0995236 -0.6451882 0.7575139 -0.05397617 -0.7557108 0.6526774 -0.05595052 -0.7131884 0.6987359 -0.1851267 -0.6930785 0.6966853 -0.07380861 -0.9167069 0.3926844 -0.08827751 -0.9240972 0.3718219 -0.07384043 -0.9407207 0.3310472 -0.06593304 -0.7941729 0.6041045 -0.05838346 -0.7987474 0.5988272 -0.1981657 -0.7750095 0.6000757 -0.185281 -0.6931658 0.6965574 -0.3515613 -0.648208 0.6754488 -0.06700038 -0.8932629 0.4445136 -0.07952046 -0.8683429 0.4895479 -0.2124919 -0.8433357 0.4935911 -0.1983203 -0.7750803 0.599933 -0.3637644 -0.7248443 0.5850439 -0.3517164 -0.6482959 0.6752836 -0.4727031 -0.6002972 0.6451319 -0.4725964 -0.6004189 0.6450968 -0.5500362 -0.5616812 0.6180408 -0.5499167 -0.5618384 0.6180044 -0.6232008 -0.5182422 0.5857011 -0.3274274 -0.8648423 0.3805776 -0.2527251 -0.8896774 0.3802684 -0.7612638 -0.4685817 0.4482284 -0.7534412 -0.4188845 0.5068158 -0.7533631 -0.4190694 0.5067793 -0.2253845 -0.8883776 0.399984 -0.2126309 -0.8433763 0.4934618 -0.3771643 -0.7887467 0.4854131 -0.3639092 -0.724904 0.5848798 -0.4840088 -0.6712576 0.5613811 -0.4839033 -0.6713783 0.5613279 -0.5606046 -0.628088 0.5396554 -0.5605103 -0.6282131 0.5396078 -0.6329575 -0.5795027 0.5133629 -0.6328715 -0.5796427 0.513311 -0.7001442 -0.5260455 0.4827778 -0.8233619 -0.4434418 0.3541674 -0.8158702 -0.4073553 0.4103869 -0.8158122 -0.4075319 0.4103271 -0.8090007 -0.3642826 0.4613201 -0.8089321 -0.3644873 0.4612787 -0.7098087 -0.5725616 0.4102987 -0.7098743 -0.5724363 0.4103597 -0.643593 -0.6307211 0.4335656 -0.6436784 -0.6305932 0.4336248 -0.5721224 -0.6835741 0.4532135 -0.5722142 -0.6834583 0.4532722 -0.4963221 -0.7305319 0.4690284 -0.4964125 -0.7304337 0.4690856 -0.3772943 -0.7887777 0.4852616 -0.3884794 -0.8274245 0.4055272 -0.3601768 -0.8476378 0.3895933 -0.8172842 -0.4917985 0.3003017 -0.7915499 -0.5264451 0.3103294 -0.7781183 -0.5374199 0.3251338 -0.7494418 -0.582311 0.3150411 -0.7192113 -0.6045181 0.3424807 -0.7033416 -0.6256876 0.3373806 -0.6550365 -0.6705668 0.3482348 -0.6319305 -0.703333 0.3255559 -0.5839966 -0.7245502 0.366026 -0.536557 -0.7612075 0.3642387 -0.5087568 -0.7734511 0.378074 -0.4901085 -0.7881508 0.3723066 -0.4249464 -0.822916 0.3771336 -0.8743129 -0.2427135 0.420318 -0.8786374 -0.2789933 0.3875038 -0.8786649 -0.2786139 0.3877143 -0.8839102 -0.3118911 0.3484633 -0.8839324 -0.311567 0.3486971 -0.8896954 -0.3393471 0.3054271 -0.8897119 -0.3390759 0.3056801 -0.9488504 -0.2301828 0.216099 -0.9205422 -0.3068335 0.2417757 -0.8892007 -0.3375514 0.3088388 -0.8843453 -0.3831077 0.266762 -0.8486946 -0.4447966 0.2861354 -0.8339495 -0.4629485 0.3003451 -0.8302001 -0.46632 0.3054728 -0.8234171 -0.4432759 0.3542468 -0.7699472 -0.5098541 0.3837059 -0.7613403 -0.4684044 0.4482839 -0.7000649 -0.5262034 0.4827206 -0.6912792 -0.4704375 0.5484722 -0.6231055 -0.5183908 0.5856709 -0.7976887 -0.2596468 0.5443128 -0.7977513 -0.2594792 0.544301 -0.7404336 -0.2985398 0.6021896 -0.7405116 -0.298379 0.6021733 -0.6766806 -0.3352497 0.6555235 -0.6767579 -0.3351079 0.6555162 -0.6071316 -0.3692898 0.703574 -0.607219 -0.3691534 0.7035701 -0.5326231 -0.4002269 0.745742 -0.5327201 -0.400105 0.7457382 -0.4540967 -0.427726 0.7815669 -0.4542145 -0.4275998 0.7815675 -0.3316134 -0.4618626 0.8226273 -0.3317195 -0.4616924 0.82268 -0.1638208 -0.493809 0.8539997 -0.1639258 -0.4936691 0.8540605 -0.06845688 -0.5050876 0.8603488 -0.04047304 -0.5408377 0.8401527 -0.7083833 -0.2034085 0.6758831 -0.7140209 -0.2393994 0.6579225 -0.6713432 -0.2576655 0.6949151 -0.6714016 -0.2575648 0.6948959 -0.6012333 -0.2838448 0.7469611 -0.6013169 -0.2837306 0.7469371 -0.5262106 -0.3076248 0.7927606 -0.5263176 -0.3075035 0.7927367 -0.4472978 -0.3287283 0.8317827 -0.4473654 -0.3286566 0.8317748 -0.3242525 -0.3549962 0.8768342 -0.3243429 -0.354852 0.8768591 -0.1559492 -0.3795483 0.9119336 -0.1560485 -0.3794134 0.9119728 -0.02911806 -0.3902806 0.9202354 -0.06656092 -0.3717365 0.9259491 -0.8342381 -0.1327869 0.5351772 -0.8322887 -0.3829371 0.4008176 -0.8701947 -0.1982827 0.4510489 -0.8736335 -0.2411078 0.4226482 -0.8028482 -0.3148809 0.5062459 -0.8029158 -0.3146805 0.5062634 -0.7463641 -0.3620374 0.558453 -0.7464439 -0.3618524 0.5584662 -0.6833376 -0.4065515 0.6064368 -0.6834335 -0.4063762 0.6064463 -0.6144585 -0.4478238 0.6495342 -0.6145597 -0.4476702 0.6495442 -0.5405561 -0.4853433 0.6871979 -0.5406506 -0.4852209 0.68721 -0.4625921 -0.518691 0.7190051 -0.4627035 -0.5185679 0.7190221 -0.3407717 -0.5600999 0.7550912 -0.340889 -0.5599125 0.7551773 -0.1736057 -0.5988379 0.7818276 -0.1737245 -0.5986815 0.7819209 -0.0162881 -0.6184509 0.7856547 -0.07332414 -0.7206787 0.6893807 -0.3727718 -0.877488 0.301755 -0.06759637 -0.9895329 0.1274967 -0.9961493 -0.06411111 0.05980467 -0.07278412 -0.9973455 0.002111256 -0.1745092 -0.984313 0.02597481 -0.2252205 -0.973629 0.03636598 -0.2556974 -0.9662746 0.03053319 -0.8989574 -0.4333127 0.06415468 -0.8992254 -0.4327877 0.06394302 -0.9974904 -0.01099133 0.0699436 -0.9379095 -0.3406658 0.06536537 -0.9597997 -0.2718178 0.0699985 -0.9635714 -0.2592003 0.06592005 -0.9921946 -0.1058141 0.06598085 -0.9836854 -0.1582248 0.08560436 -0.9975135 -0.04084193 0.05743569 -0.9956493 -0.06617015 0.06560486 -0.9943043 -0.04957211 0.09434902 -0.9962829 -0.01077616 0.08546441 -0.9966515 -0.01118153 0.08099788 -0.9925755 -0.05232137 0.1098011 -0.994907 -0.008582293 0.1004314 -0.9956551 -0.01338964 0.09215098 -0.9907459 -0.05283707 0.1250243 -0.9936884 -0.01036036 0.111697 -0.9941508 -0.01119875 0.1074186 -0.9901775 -0.02345794 0.137835 -0.992415 -0.01060175 0.1224752 -0.9929006 -0.01164269 0.1183766 -0.04277074 -0.9567767 0.2876614 -0.07792085 -0.9967636 0.01976966 -0.08891695 -0.9959059 0.01628881 -0.06030255 -0.99722 0.04377108 -0.7549278 -0.5948385 0.2761366 -0.7979853 -0.540825 0.2659471 -0.8106153 -0.52509 0.2591978 -0.8125786 -0.5295526 0.2434954 -0.3374242 -0.8887254 0.310342 -0.3995212 -0.8623925 0.3109051 -0.4028046 -0.8697865 0.2849912 -0.4856433 -0.82671 0.2840794 -0.4887097 -0.833231 0.2586295 -0.5664821 -0.7832587 0.2561323 -0.5693161 -0.7888987 0.2313402 -0.6414995 -0.7325367 0.2277464 -0.6440799 -0.7372968 0.2038493 -0.7098948 -0.6754183 0.1996486 -0.7122136 -0.6793175 0.1768604 -0.7719354 -0.6118648 0.1724454 -0.7739831 -0.6149348 0.1510144 -0.8269584 -0.5427607 0.1468021 -0.8287343 -0.5450639 0.1269052 -0.07747024 -0.949536 0.3039406 -0.1811453 -0.9376366 0.2966886 -0.191814 -0.9363509 0.2940316 -0.06402921 -0.9947777 0.07948309 -0.2204953 -0.9711852 0.09044933 -0.2209685 -0.9710993 0.09021854 -0.3442726 -0.9337972 0.09746474 -0.3463745 -0.9354779 0.07004314 -0.4312367 -0.8991464 0.07463729 -0.4335109 -0.9001819 0.04172426 -0.4377648 -0.8981512 0.04106724 -0.3535019 -0.9347583 0.03554511 -0.3489863 -0.9364259 0.03626757 -0.3466417 -0.9353709 0.07014858 -0.2233626 -0.972714 0.06274354 -0.2230615 -0.9727736 0.06289148 -0.07447952 -0.9958172 0.05292326 -0.06481254 -0.9946965 0.07986485 -0.6026735 -0.7964214 0.04997706 -0.5896927 -0.805986 0.05146902 -0.5876133 -0.8050135 0.08163231 -0.511634 -0.8556216 0.07837319 -0.5096184 -0.854009 0.1046795 -0.4285039 -0.8978384 0.1013453 -0.4262719 -0.8954556 0.1282643 -0.3410059 -0.9317886 0.124439 -0.3385742 -0.9286286 0.1517119 -0.2152022 -0.965777 0.1447857 -0.2143876 -0.9658998 0.1451747 -0.07425671 -0.9880962 0.1347284 -0.05332916 -0.9872388 0.1500524 -0.5278109 -0.8482677 0.04309952 -0.514142 -0.8564959 0.04552888 -0.5118799 -0.8554652 0.07847499 -0.4309751 -0.8992808 0.07452881 -0.4289058 -0.8976279 0.1015083 -0.3438473 -0.9339712 0.09729778 -0.3415789 -0.9315492 0.1246603 -0.2182466 -0.9687852 0.1175745 -0.2176002 -0.9688926 0.117886 -0.0723623 -0.9915803 0.1073895 -0.06739932 -0.991679 0.1096822 -0.4994936 -0.8098428 0.3076701 -0.5580826 -0.7719634 0.3043292 -0.5611684 -0.7789204 0.279952 -0.6339846 -0.7230524 0.2743334 -0.6368157 -0.729078 0.2508209 -0.7032839 -0.6676441 0.2442196 -0.7058516 -0.6727591 0.2217404 -0.766227 -0.6056936 0.2145497 -0.7685203 -0.6099218 0.1933186 -0.8221269 -0.5380653 0.1859926 -0.8241401 -0.5414459 0.1662211 -0.8901414 -0.4283699 0.1553952 -0.890626 -0.4276011 0.1547344 -0.7433661 -0.6664338 0.05721068 -0.7241036 -0.6872196 0.05833631 -0.7222138 -0.6863206 0.08585715 -0.6577468 -0.7485408 0.08399927 -0.6558827 -0.7470484 0.1083358 -0.5850698 -0.8039199 0.1068004 -0.5829638 -0.8016766 0.1321672 -0.5065279 -0.8522813 0.1305619 -0.5041955 -0.8492509 0.1567164 -0.4226296 -0.8930183 0.1546045 -0.4200764 -0.889183 0.1813549 -0.3343853 -0.9254171 0.1782968 -0.3316258 -0.9207794 0.2054013 -0.2081621 -0.9576803 0.1987892 -0.2070075 -0.9578181 0.1993301 -0.0604813 -0.9803873 0.1875705 -0.06389689 -0.9732515 0.2206781 -0.6812151 -0.7304603 0.04872107 -0.6600731 -0.7493203 0.05312967 -0.657962 -0.7483408 0.08409547 -0.5873833 -0.8051915 0.08153218 -0.5854326 -0.803635 0.1069557 -0.5092299 -0.85426 0.1045224 -0.5070537 -0.8519369 0.1307681 -0.4257184 -0.8957501 0.1280459 -0.4233275 -0.8926408 0.1548753 -0.3378475 -0.9289385 0.1514348 -0.335252 -0.9250405 0.1786236 -0.2118396 -0.9620757 0.1718563 -0.2108533 -0.9622086 0.1723238 -0.07040697 -0.9843595 0.161491 -0.05572551 -0.981114 0.1852298 -0.9894778 -0.1044389 0.1001306 -0.989275 -0.1058031 0.1007004 -0.9876411 -0.1033463 0.1178328 -0.9873257 -0.1052815 0.1187595 -0.9855354 -0.1019777 0.1353542 -0.9850946 -0.104431 0.1366851 -0.9844176 -0.1029229 0.14258 -0.975408 -0.1469442 0.1642764 -0.6347811 -0.7099355 0.3050322 -0.6962568 -0.6590061 0.284495 -0.6985877 -0.6642854 0.2658951 -0.7596797 -0.5978083 0.2559535 -0.7621934 -0.6031584 0.2350775 -0.8165097 -0.5318275 0.2246586 -0.818735 -0.536265 0.2051661 -0.8855381 -0.4242533 0.1892919 -0.8861978 -0.4232853 0.1883696 -0.8567742 -0.5119073 0.06236058 -0.834391 -0.5476934 0.06183695 -0.8326594 -0.5468586 0.08731693 -0.7804771 -0.6191239 0.08683961 -0.7788199 -0.6177986 0.1084644 -0.7199384 -0.685474 0.1086923 -0.718028 -0.6834386 0.1317104 -0.6530743 -0.7456511 0.1322814 -0.6509148 -0.74285 0.1564736 -0.579592 -0.7996407 0.1569969 -0.5771851 -0.7960287 0.1821975 -0.5002501 -0.8464859 0.1822409 -0.4976055 -0.8420386 0.2082304 -0.4155504 -0.8856239 0.2073362 -0.4126883 -0.8803409 0.233855 -0.3265388 -0.9163805 0.2315586 -0.32348 -0.9102871 0.2583374 -0.1999055 -0.9468446 0.2520377 -0.1984189 -0.9469763 0.2527174 -0.04300928 -0.9664216 0.2533366 -0.06675189 -0.9680523 0.2417001 -0.04373115 -0.976131 0.2127342 -0.2028627 -0.9527374 0.2261376 -0.2041794 -0.9526005 0.2255285 -0.3276976 -0.9158589 0.2319847 -0.3306097 -0.9212292 0.2050223 -0.4165244 -0.8850812 0.2076988 -0.4192364 -0.8896446 0.1810342 -0.5010469 -0.8459507 0.1825362 -0.5035356 -0.8496888 0.1564642 -0.5802165 -0.7991388 0.1572447 -0.5824727 -0.8020663 0.1319667 -0.6535316 -0.7452167 0.1324713 -0.6555444 -0.7473665 0.1081898 -0.7202476 -0.6851267 0.108834 -0.7220147 -0.6865419 0.08576148 -0.780656 -0.6188853 0.08693271 -0.7825409 -0.6197797 0.05918741 -0.8084841 -0.5861959 0.05222982 -0.946538 -0.2614746 0.1889365 -0.9525882 -0.2389158 0.1884019 -0.9718589 -0.1633149 0.1697608 -0.8233425 -0.5053521 0.2583145 -0.8409889 -0.4784028 0.2527224 -0.9167875 -0.3416988 0.2067434 -0.8553115 -0.4599483 0.2385165 -0.8806855 -0.4168692 0.2249737 -0.8900549 -0.396245 0.2253717 -0.9251706 -0.3175526 0.2078937 -0.71099 -0.642873 0.2849697 -0.7560972 -0.5932117 0.276436 -0.7587262 -0.5991336 0.2556827 -0.813421 -0.528149 0.2437316 -0.8157476 -0.5330973 0.2244173 -0.8829976 -0.4217347 0.2060462 -0.8837459 -0.4206802 0.204991 -0.9481373 -0.2648566 0.175746 -0.9555174 -0.2480422 0.1595671 -0.949727 -0.2640926 0.1681485 -0.5456684 -0.7822391 0.3005798 -0.6291367 -0.715916 0.3027399 -0.6328336 -0.7241892 0.2739924 -0.6996421 -0.663052 0.2662011 -0.7023246 -0.6687636 0.2439168 -0.7630515 -0.6019671 0.2353471 -0.7654587 -0.6067585 0.2142832 -0.8194134 -0.5351353 0.2054068 -0.8215366 -0.5390467 0.1857592 -0.8879222 -0.4264651 0.1724001 -0.8884927 -0.4255949 0.1716091 -0.9517757 -0.267782 0.1497196 -0.9589183 -0.2499365 0.1341916 -0.953073 -0.2671855 0.1423509 -0.9555092 -0.2708468 0.1168083 -0.9559475 -0.2695313 0.1162635 -0.4340778 -0.8442738 0.3142901 -0.4816052 -0.8214737 0.305348 -0.4843301 -0.8276269 0.2836514 -0.5624042 -0.7778873 0.2803444 -0.5653665 -0.7841861 0.2557597 -0.6378582 -0.7280523 0.2511509 -0.6405673 -0.7334496 0.227432 -0.7067023 -0.6717705 0.2220279 -0.7091481 -0.6762821 0.1993781 -0.7691901 -0.6089966 0.1935712 -0.7713637 -0.612651 0.1722118 -0.8246462 -0.5406072 0.166441 -0.82654 -0.5434505 0.1466056 -0.8921907 -0.429955 0.1383273 -0.9054221 -0.4072652 0.1197748 -0.8935741 -0.4298987 0.1292766 -0.2621229 -0.9125312 0.3139721 -0.3146815 -0.8982639 0.3067535 -0.3175583 -0.9047333 0.2839273 -0.4041758 -0.8689937 0.285468 -0.4073209 -0.8756893 0.2593417 -0.489892 -0.8324124 0.2590279 -0.4928241 -0.8382502 0.2333689 -0.5703107 -0.7880783 0.2316863 -0.5730097 -0.7930512 0.2067121 -0.6448897 -0.7365086 0.2041381 -0.6473358 -0.7406215 0.1801005 -0.7128484 -0.6785869 0.1771075 -0.7150316 -0.6818639 0.1542456 -0.7744625 -0.6142796 0.1512235 -0.77638 -0.61677 0.1297262 -0.8290664 -0.5445192 0.1270743 -0.8307238 -0.5462844 0.1071054 -0.8957716 -0.4321865 0.1039627 -0.064318 -0.9612855 0.2679429 -0.1936935 -0.9405438 0.2790346 -0.1953399 -0.9404234 0.2782917 -0.3189824 -0.9040726 0.2844349 -0.3221815 -0.9108809 0.2578667 -0.4085648 -0.8749787 0.2597833 -0.4115716 -0.8809708 0.233451 -0.4938876 -0.8375208 0.2337394 -0.4966771 -0.842669 0.2078963 -0.5738865 -0.7923337 0.2070308 -0.5764436 -0.7966302 0.1819156 -0.648037 -0.7399435 0.1803655 -0.6503387 -0.743402 0.1562471 -0.715563 -0.6812563 0.1544649 -0.7176058 -0.6839175 0.1315254 -0.7767539 -0.6162625 0.1298996 -0.7785453 -0.6181688 0.1083266 -0.8309687 -0.5458855 0.1072396 -0.8325009 -0.5471143 0.08722573 -0.908717 -0.4083796 0.08636873 -0.8967366 -0.4322307 0.09507989 -0.958108 -0.2718389 0.09018266 -0.9583362 -0.2711184 0.08992534 -0.9909356 -0.1059954 0.08253288 -0.9910365 -0.105256 0.08226674 -0.9951396 -0.057787 0.07973676 -0.9971665 -0.01083517 0.07444131 -0.9940194 0.002107322 0.109184 -0.9935497 0.01361 0.1125783 -0.9932171 0.02855896 0.1127132 -0.9951968 0.004814028 0.09777647 -0.9951209 0.003034412 0.09861743 -0.9944209 -6.20637e-4 0.1054841 -0.9972608 -9.3981e-4 0.0739597 -0.9967897 0.001423478 0.08005195 -0.9965655 0.00457108 0.08268338 -0.9964449 0.002723276 0.08420449 -0.9958716 -0.00168097 0.09075808 -0.9981721 -6.49596e-6 0.0604375 -0.9977201 0.001011371 0.06748175 -0.9978722 0.006059646 0.06492 -0.9975768 0.002140045 0.06954109 -1 -6.11404e-6 0 -1 -6.11404e-6 0 0.7605966 0.07248264 -0.6451661 0.8231934 0.03756642 -0.5665171 0.7925095 0.08463114 -0.6039589 0.77333 0.08760529 -0.627922 0.7497994 0.1612976 -0.6417041 0.7517514 0.1636954 -0.6388065 0.7330628 0.2396847 -0.6365299 0.7610197 0.265576 -0.5918772 0.6648926 0.3057773 -0.6814824 0.741786 0.3003115 -0.5996388 0.7015056 0.3993782 -0.5902432 0.7122926 0.4587647 -0.5312007 0.6870312 0.3733382 -0.6233834 0.7065429 0.3122954 -0.6350346 0.707091 0.2732598 -0.6521898 0.7073758 0.2490834 -0.6614961 0.7030488 0.2269209 -0.6739654 0.710703 0.1714925 -0.6822695 0.7032138 0.1340841 -0.6982206 0.7096745 0.07865703 -0.7001251 0.7062838 0.05742055 -0.7055964 -1.29862e-6 1.47378e-6 -1 -8.22481e-5 -1.46019e-4 -1 9.78308e-6 4.7118e-6 -1 2.87559e-7 -1.17737e-6 -1 -1.01157e-5 -1.38354e-7 -1 -2.73804e-5 -4.93981e-5 -1 -1.44113e-4 -1.82108e-4 -1 8.45739e-5 -7.42448e-5 -1 -2.62588e-5 -1.35006e-4 -1 4.94146e-4 -1.55072e-4 -0.9999999 0 0 -1 -8.67758e-5 -9.84478e-5 -1 3.53688e-4 -7.00557e-5 -1 -5.29712e-4 1.05556e-4 -0.9999999 1.60911e-5 0 -1 -9.18807e-6 0 -1 -4.17521e-4 -2.68135e-5 -1 1.01065e-6 0 -1 -5.21951e-7 0 -1 0 2.82649e-4 -1 5.45453e-5 -2.76184e-4 -1 3.17564e-4 2.11727e-4 -1 4.46362e-7 0 -1 -2.45787e-5 2.7771e-4 -1 -1.76776e-4 5.67227e-5 -1 -2.15659e-4 1.27742e-4 -1 -2.5568e-4 2.62707e-5 -1 9.93605e-5 -2.62665e-4 -1 -2.81262e-6 0 -1 -4.39062e-4 -1.1196e-5 -1 -5.27055e-4 0 -1 -8.16173e-4 -4.19559e-5 -0.9999997 0 2.82728e-4 -1 8.05871e-6 2.82642e-4 -1 2.09692e-4 -1.38901e-4 -1 1.5573e-4 -1.03244e-4 -1 1.16407e-4 2.72402e-5 -1 3.09832e-4 -1.99642e-5 -1 2.24966e-4 1.05291e-4 -1 -9.49352e-5 1.57407e-4 -1 -3.25747e-4 4.59085e-5 -1 -1.90263e-4 -4.27269e-6 -1 0.6039803 0.7397885 0.2965146 -0.4391851 0.8816588 0.1726106 0.2275894 0.9732597 0.03112554 -0.1654416 0.9831578 0.07765251 0.2522053 0.9667711 0.04178988 0.2530975 0.9663214 0.04652637 0.2871287 0.9563476 0.05437254 0.2898349 0.9549977 0.06304955 0.3282204 0.942326 0.06552177 0.3302281 0.9413313 0.06960606 0.3542086 0.9321829 0.07464277 0.3575398 0.9304628 0.08002734 0.3898075 0.9178783 0.07449471 0.3921636 0.9166654 0.07702243 0.4087932 0.9091122 0.0800203 -0.533169 0.8392686 0.1065801 -0.1006301 0.9886848 0.1112474 -0.09184688 0.9833837 0.1565908 -0.02391058 0.993701 0.1094834 0.005613625 0.9790807 0.2033948 0.07236373 0.9865337 0.1466796 0.1119624 0.9674538 0.2269309 0.1339398 0.9750512 0.1770179 0.1791564 0.9515975 0.2497302 0.2160688 0.9580928 0.1880757 0.269822 0.9310127 0.2457873 0.2626605 0.9423127 0.2075006 0.3163138 0.9133318 0.2564579 -0.4266855 0.8741711 0.2318711 -0.3266818 0.9296949 0.1701366 -0.2831695 0.9084292 0.3075248 -0.179566 0.9554466 0.2342601 -0.1204334 0.9272727 0.3544874 -0.08529776 0.9554036 0.2827162 -0.01774573 0.9203958 0.3905852 0.04560524 0.9508537 0.3062636 0.1283363 0.9094986 0.3954013 0.1160894 0.9348405 0.3355545 0.1986984 0.8899826 0.4104265 0.2176199 0.9170637 0.3341192 0.3144931 0.8666345 0.3873485 0.1599326 0.8590335 0.4862953 0.2080332 0.8331003 0.5125098 0.01078742 0.8699645 0.4929963 0.04203367 0.8526199 0.5208383 -0.08121728 0.8833531 0.4616181 -0.04793238 0.8662456 0.4973139 -0.2614445 0.8621961 0.433895 -0.2436999 0.8528696 0.4617615 -0.3855722 0.8430672 0.374929 -0.3710678 0.8359952 0.4042532 -0.572355 0.7641528 0.2974565 -0.5680354 0.7620468 0.3108384 -0.7241795 0.6618603 0.1936624 -0.7190937 0.6594098 0.2192783 -0.8181555 0.5641571 0.1111236 0.3109595 0.7805895 0.5422033 0.2932724 0.7986189 0.5255466 0.2740551 0.8105629 0.5175729 0.5275928 0.8476336 0.05624431 0.5158932 0.8543506 0.06276351 0.517842 0.8533453 0.06034451 0.5082734 0.858801 0.06417936 0.50875 0.8585566 0.06367272 0.499331 0.8638885 0.06607049 0.4979223 0.8645961 0.0674318 0.4869118 0.8707726 0.06835263 0.4820489 0.8731224 0.07270711 0.4682788 0.880746 0.07072198 0.4568731 0.8859462 0.07978945 0.4506937 0.8893547 0.07696479 0.4393571 0.8950524 0.07646226 0.5249819 0.8488849 0.06155216 0.5779249 0.7983601 0.1691865 0.5537536 0.8123778 0.1827553 0.5495244 0.8151805 0.1830401 0.5306479 0.8258817 0.1906105 0.5321964 0.8248598 0.1907176 0.5034161 0.8410407 0.1980476 0.5110321 0.8357602 0.200876 0.4656323 0.8609974 0.2046214 0.4781541 0.8510109 0.2171382 0.4117571 0.8873549 0.2075028 0.4206665 0.8749213 0.2399013 0.36575 0.9055333 0.2150267 0.5711838 0.8009032 0.179731 0.6194583 0.7340288 0.27834 0.5801237 0.7570471 0.3005599 0.5726184 0.7621694 0.3020035 0.5425124 0.7791487 0.3140187 0.5481463 0.7752906 0.3137841 0.4983175 0.803202 0.3264143 0.5165448 0.7899925 0.3302927 0.4377309 0.8336704 0.3367274 0.4636636 0.8110632 0.3566409 0.3531529 0.8713937 0.3405233 0.4130358 0.9068429 0.08389031 0.4351625 0.8972931 0.07415401 0.3250952 0.9234087 0.2040335 0.38481 0.892135 0.2366785 0.2783128 0.8942732 0.3504536 0.3677905 0.8438951 0.3906037 0.2837111 0.8385294 0.4651629 0.3826299 0.7885769 0.4813949 0.487991 0.7443203 0.4559081 0.4776346 0.7503727 0.4569534 0.5347473 0.7235851 0.4364287 0.5431616 0.7186461 0.4341927 0.5607931 0.7100458 0.4258477 0.5969201 0.6890057 0.4110446 0.5821482 0.6959527 0.4204204 0.6532904 0.6546671 0.3802928 0.6152803 0.6701197 0.4151744 0.1560317 0.9872225 0.03234183 -0.7307631 0.6771954 0.08597499 -0.7312958 0.6766709 0.08557498 -0.3196104 0.9455285 0.06184661 -0.3214079 0.9449794 0.06091839 0.1688162 0.9853823 0.02286678 -0.9606323 0.2436188 0.1335493 -0.9652346 0.2455694 0.0895431 -0.9653326 0.2452539 0.08935046 -0.9603016 0.2447608 0.13384 -0.7288672 0.6725614 0.128117 -0.7270424 0.6746762 0.1273631 -0.3247959 0.9412646 0.09235185 -0.3185693 0.9436033 0.09014624 0.1669843 0.9853921 0.03344649 0.1658413 0.9859198 0.02142035 0.1423841 0.9886764 0.0473904 0.1584745 0.9861971 0.04797142 -0.3281956 0.9353272 0.1321011 -0.3184688 0.9385753 0.1328693 -0.7227371 0.6656661 0.1858488 -0.7197601 0.6687059 0.1864879 -0.9501421 0.2421847 0.1964095 -0.9506106 0.2406613 0.1960145 -0.8931677 0.4361432 0.1096835 -0.9402002 0.3383577 0.03921604 -0.6222114 0.7775701 0.09076297 -0.6844716 0.7276487 0.04501247 -0.2321252 0.970774 0.06095755 -0.2803823 0.9592213 0.03578042 0.2025904 0.978968 0.02406018 0.1844276 0.9827223 0.01560145 -0.8129501 0.5617079 0.1536116 -0.8973006 0.4380071 0.0547862 -0.5312799 0.8383153 0.1223496 -0.624485 0.7786784 0.0606504 -0.1651854 0.9830229 0.07987344 -0.2330945 0.9712881 0.04760831 0.2275623 0.9732732 0.03090047 0.2023535 0.9790949 0.020648 0 -1 0 0 -1 -5.8324e-6 0 -1 1.61374e-6 0 -1 6.19671e-6 0 -1 -7.85571e-6 0 -1 5.38236e-6 0 -1 4.71606e-7 0 -1 5.06073e-5 -9.63621e-5 -0.9999997 -7.61727e-4 0 -1 -3.78673e-5 0 -1 -1.60875e-5 0 -1 -3.34898e-7 0 -1 0 0 -1 5.55557e-7 0 -1 4.96579e-5 0.001008272 -0.9999991 8.63621e-4 3.63883e-5 -1 1.9289e-5 5.21495e-6 -1 1.20381e-6 0 -1 0 0 -1 -9.83117e-7 0 -1 8.16524e-7 0 -1 2.47106e-7 0 -1 -3.42654e-6 0 -1 -6.9233e-7 0 -1 -3.50022e-6 0 -1 1.55133e-6 0 -1 3.85993e-6 -0.701191 -0.5100499 -0.4981769 -0.7080391 -0.4750872 -0.522468 -0.7074178 -0.008966684 -0.7067388 -0.703716 -0.02311766 -0.7101052 -0.708907 -0.09699183 -0.6986011 -0.7024207 -0.1272603 -0.7002928 -0.7087604 -0.1742076 -0.6836012 -0.7070085 -0.1930432 -0.680348 -0.7070606 -0.2172006 -0.6729705 -0.7026518 -0.2695769 -0.6584898 -0.7116658 -0.2416704 -0.6596418 -0.7030249 -0.32501 -0.6325541 -0.706703 -0.3083546 -0.6367797 -0.7068496 -0.3607366 -0.6084676 -0.7079525 -0.3544014 -0.6109034 -0.703963 -0.4212722 -0.5718094 -0.706088 -0.4148032 -0.5739147 -0.7070885 -0.4603514 -0.5367518 -1 0 0 -0.003056049 0.0786252 -0.9968996 0 0.1071954 -0.994238 0 0.1071954 -0.994238 0.9647461 0.03956162 -0.2601921 -0.001043319 0.07860189 -0.9969056 -0.00104326 0.07860237 -0.9969055 -0.001043319 0.07860183 -0.9969056 0 0.7452666 -0.6667666 0 0.7452673 -0.6667659 0 0.6952387 -0.718779 0 0.6952386 -0.718779 0 0.6451568 -0.7640503 0 0.5710754 -0.8208977 0 0.5710759 -0.8208974 0 0.5143882 -0.8575575 0 0.5143862 -0.8575586 0 0.4437908 -0.8961306 0 0.4437904 -0.8961307 0 0.3703163 -0.9289057 0 0.3703148 -0.9289063 0 0.3068016 -0.9517736 0 0.3068014 -0.9517737 0 0.2166814 -0.9762424 0 0.1503255 -0.9886366 1 2.22099e-6 0 1 -2.49087e-7 0 1 -2.15187e-7 0 0.5995513 0.0638228 -0.7977876 0.3895903 0.0690729 -0.9183946 0.001994669 0.07862633 -0.9969022 0.001994669 0.07862627 -0.9969022 0.001994669 0.07862627 -0.9969022 0.3339489 0.6998932 -0.6313698 0.6433302 0.5004048 -0.5794147 0.06834173 0.7435251 -0.6652067 0.08820426 0.7327481 -0.6747595 0.08820331 0.6925303 -0.7159762 0.1389358 0.6388998 -0.75664 0.08803576 0.6642209 -0.7423343 0.08810395 0.5688553 -0.817705 0.1067811 0.5571981 -0.8234854 0.08823192 0.5123801 -0.8542141 0.08803564 0.4420678 -0.892651 0.08804726 0.4420636 -0.892652 0.08824145 0.3688713 -0.9252824 0.1067866 0.3172723 -0.9423031 0.08811014 0.3056082 -0.9480718 0.1275492 0.08414417 -0.9882565 0.07817 0.09839057 -0.9920731 0.08817434 0.2158374 -0.97244 0.11755 0.187281 -0.9752476 0.08820682 0.1497395 -0.9847831 0.0882039 0.09158509 -0.9918832 0.01887893 0.07894259 -0.9967005 0.237438 0.08311659 -0.9678403 0.1778302 0.07727664 -0.9810223 0.1476968 0.08023637 -0.9857727 0.4611147 0.08632135 -0.883132 0.6698664 0.06022542 -0.7400351 0.6419075 0.08347421 -0.7622249 0.641079 0.1447391 -0.7537032 0.6410815 0.1447353 -0.7537017 0.6410815 0.2448964 -0.7273517 0.641079 0.244898 -0.7273533 0.6419331 0.2963054 -0.7071952 0.6367414 0.3452895 -0.6894459 0.6410772 0.3405973 -0.6877598 0.6410779 0.4300962 -0.6356387 0.6410782 0.4300941 -0.6356397 0.6414892 0.5007743 -0.581134 0.5984086 0.5342418 -0.5970703 0.6044701 0.6173337 -0.503503 0.5321067 0.07010412 -0.84377 0.4800076 0.1000169 -0.8715443 0.4791793 0.1655265 -0.8619678 0.4791769 0.165529 -0.8619685 0.4791751 0.2800775 -0.8318341 0.4791806 0.2800737 -0.8318322 0.4791808 0.3895205 -0.7865493 0.4791802 0.38952 -0.7865499 0.4791812 0.4918746 -0.7269421 0.4791787 0.4918763 -0.7269427 0.4791784 0.5852708 -0.6540995 0.479178 0.5852705 -0.6541 0.4793635 0.5902897 -0.6494373 0.4549512 0.6464948 -0.6124247 0.3150191 0.08416926 -0.9453457 0.2808527 0.1050652 -0.9539828 0.2802791 0.1810299 -0.942694 0.2802824 0.1810294 -0.9426931 0.280282 0.3063047 -0.9097359 0.2802768 0.3063066 -0.9097369 0.2802773 0.4260006 -0.860214 0.2802786 0.425999 -0.8602144 0.2802783 0.5379427 -0.7950233 0.2802841 0.5379384 -0.795024 0.2802833 0.6400822 -0.7153573 0.2802808 0.6400827 -0.7153578 0.28087 0.687421 -0.6697496 0.2048979 0.7339227 -0.6475912 0.9603351 0.2447752 0.1335723 0.3196887 0.9455699 0.06080085 0.3213126 0.9449437 0.06196504 0.7307941 0.6772154 0.0855531 0.7312623 0.6766535 0.08599758 0.9653164 0.2452496 0.08953809 -0.1667497 0.9855129 0.03096669 -0.1660025 0.9858546 0.02310806 -0.1686952 0.9854408 0.02117812 -0.1564225 0.9870762 0.03482228 0.3250295 0.9413341 0.09080708 0.3184092 0.9435092 0.09168535 0.7289557 0.6725859 0.1274831 0.7269653 0.6746402 0.1279923 0.9605988 0.2436049 0.1338156 0.9652508 0.2455741 0.08935517 0.9502065 0.2422193 0.1960551 0.9505464 0.2406294 0.1963648 0.7225584 0.6656028 0.1867684 0.7199203 0.6687868 0.1855775 0.3277349 0.9351744 0.1343088 0.3188224 0.9387637 0.1306718 -0.1431557 0.9883896 0.05091607 -0.1579289 0.9864496 0.04444736 -0.2019066 0.9792984 0.01444309 -0.1849657 0.9824368 0.02461332 0.2339841 0.9716114 0.03496724 0.2788677 0.9584462 0.06011408 0.6252498 0.7789271 0.04832625 0.6819595 0.7264631 0.08475089 0.8974908 0.4380855 0.05090719 0.9368172 0.3368584 0.09434032 -0.2261371 0.9739217 0.01840633 -0.2031461 0.9786253 0.03200376 0.1690272 0.9845463 0.04580748 0.2307727 0.9698408 0.07844078 0.5373798 0.8407374 0.06620824 0.6203174 0.7763963 0.1114229 0.8213364 0.5654003 0.07569086 0.8914566 0.435352 0.1255937 -0.5797215 0.7962123 0.1731158 0.8070266 0.5586392 0.1913908 0.5256942 0.8347991 0.1635727 0.7344791 0.6658923 0.1308742 0.7057166 0.6522045 0.2767553 0.5959927 0.7736538 0.2150642 0.5439236 0.7486618 0.3790155 0.4167648 0.8555858 0.3070505 0.3435125 0.8206456 0.4566618 0.2990732 0.8790306 0.3712957 0.2146373 0.8357809 0.5053723 0.1247066 0.9022845 0.4127119 0.01665729 0.8481301 0.5295262 0.03623348 0.8926855 0.4492213 -0.07236337 0.834037 0.5469425 -0.1046499 0.8846242 0.4544101 -0.2414679 0.8129803 0.5298646 -0.1796562 0.8615792 0.4747684 -0.2932724 0.7986189 0.5255466 -0.2548447 0.8343956 0.488711 -0.4116744 0.7714924 0.4851018 -0.4493514 0.7475106 0.4891945 -0.3960225 0.7933284 0.462381 -0.5245027 0.7216279 0.4518297 -0.4801928 0.7531375 0.4496651 -0.5599933 0.7084695 0.4295097 -0.5433627 0.7195116 0.4325044 -0.5814512 0.6982451 0.4175744 -0.597167 0.6879591 0.4124367 -0.60508 0.6836137 0.4081062 -0.6561134 0.6489443 0.3852097 -0.5997676 0.7459026 0.289669 -0.5733455 0.7607269 0.3042527 -0.5797531 0.7579139 0.2990866 -0.5480871 0.7761097 0.3118564 -0.5425735 0.7786067 0.315255 -0.5189143 0.7921086 0.3213906 -0.4974559 0.8013824 0.3321506 -0.476771 0.8131288 0.3339328 -0.4317268 0.83029 0.3524633 -0.4101638 0.8424265 0.3494044 -0.3290125 0.8672888 0.3735789 -0.3319102 0.8656182 0.3748877 -0.2670285 0.8932625 0.3616322 -0.2791829 0.8867878 0.3683266 -0.1600661 0.9127526 0.3758478 -0.1659891 0.9094755 0.3811852 -0.08685255 0.9322595 0.3512107 -0.09661352 0.9272751 0.3617001 0.04869705 0.9384034 0.3420931 0.04729795 0.9376782 0.3442711 0.1487571 0.9428054 0.2983106 0.1469977 0.9419505 0.3018626 0.3022133 0.9197331 0.2505158 0.3061981 0.9217365 0.2380011 0.4390476 0.8816029 0.1732445 0.4505661 0.8860059 0.1094704 0.1613707 0.9805184 0.1119966 -0.6215178 0.7303955 0.2832634 -0.5683861 0.8040218 0.1746034 -0.5500525 0.8144358 0.184761 -0.5533906 0.8129089 0.1814883 -0.5321729 0.8250418 0.1899949 -0.5306878 0.8257373 0.1911243 -0.5112751 0.8367543 0.1960617 -0.5034487 0.8401847 0.2015668 -0.4822311 0.8521209 0.2033305 -0.4635996 0.8595402 0.2150958 -0.4382988 0.8736038 0.2114492 -0.4009224 0.8865153 0.2309802 -0.3928825 0.8910391 0.2273604 -0.3602449 0.9057419 0.2232832 -0.3573895 0.9072641 0.2216858 -0.2948506 0.9257183 0.2368732 -0.2903652 0.9281694 0.2327871 -0.2464454 0.9437089 0.2206312 -0.2450996 0.9443889 0.2192168 -0.1612997 0.9618504 0.2209664 -0.1562663 0.9645017 0.2128784 -0.09544175 0.9764555 0.1934575 -0.09200453 0.9781396 0.1864885 0.005300462 0.9856217 0.1688843 0.0112546 0.9886287 0.149956 0.09873604 0.9877118 0.1211476 0.1077652 0.9914641 0.07338678 -0.2290327 0.9724199 0.04408705 -0.249503 0.9679794 0.02764594 -0.2556893 0.9648674 0.06044888 -0.2822108 0.9585677 0.03879654 -0.2941603 0.9526431 0.07707679 -0.3204579 0.9459491 0.04987078 -0.3368952 0.9378556 0.08323925 -0.3453224 0.9365389 0.06039214 -0.3647682 0.9265617 0.09180229 -0.3785083 0.9234916 0.06240838 -0.4013409 0.9117912 0.0869624 -0.3981279 0.9146352 0.07026195 -0.421306 0.902292 0.09149128 -0.4234811 0.9033645 0.06779861 -0.4482261 0.8902171 0.08128255 -0.4410942 0.8945167 0.07263535 -0.4636749 0.8821192 0.08289301 -0.4597981 0.8853009 0.06948512 -0.4862481 0.8707396 0.07331717 -0.482334 0.873287 0.06872934 -0.4994517 0.8637244 0.06729388 -0.4978155 0.864732 0.06647026 -0.5081943 0.8588752 0.06381434 -0.5088152 0.8584969 0.06395453 -0.5153961 0.8547558 0.06131464 -0.518221 0.8530339 0.06148427 -0.5234664 0.8500325 0.05854851 -0.5287107 0.8467726 0.05866324 -0.2902837 -0.9569106 -0.007589697 0.2905793 -0.9568156 -0.008216142 0.2378837 -0.97129 0.002674698 0.2205403 -0.9748024 -0.03350216 0.2027554 -0.9791917 -0.008605241 0.1237555 -0.992206 0.01456266 0.1432244 -0.9894435 -0.0220983 0.04066252 -0.9988991 0.02339607 0.06621724 -0.9972745 -0.03254151 0.01305407 -0.9999149 4.30463e-6 -0.01059639 -0.9999439 5.41151e-6 -0.04337459 -0.9989309 -0.0159927 -0.05976194 -0.9981349 0.01247012 -0.1295458 -0.9914826 -0.01342254 -0.1370731 -0.9905161 0.009424686 -0.1969778 -0.9803882 -0.006236553 -0.2212553 -0.9745652 -0.03562158 -0.2243074 -0.9741889 -0.02533978 -0.2379215 -0.9712798 0.002989947 -0.7226864 0.5017691 0.4753443 -0.7229784 0.5012534 0.4754441 -0.7353024 0.3145799 0.6003083 -0.73017 0.1202957 0.6725926 -0.6567914 0.6833455 0.3188481 -0.656512 0.6835927 0.3188935 -0.04493051 0.931189 0.3617574 -0.02509641 0.1626212 0.9863694 -0.05990159 0.3165035 0.9466982 -0.5239604 0.1029537 0.8454976 -0.4930782 0.2603182 0.8301256 -0.4673419 0.0251255 0.8837196 -0.3954516 0.2299283 0.8892419 -0.3909749 0.1465525 0.9086589 -0.2944185 0.1549586 0.9430301 -0.2939907 0.2517532 0.9220574 -0.1989468 0.1072857 0.9741201 -0.1804466 0.3206367 0.9298555 -0.1377267 0.1843228 0.9731683 -0.08310663 0.1757122 0.9809274 -0.561491 0.07998347 0.8236083 -0.6012051 0.275086 0.7502535 -0.5816245 -0.1300951 0.8029871 -0.6842345 0.3577855 0.6354626 -0.6763876 0.02960419 0.7359507 -0.7206774 0.06738018 0.6899883 -0.7102007 0.01389718 0.7038621 -0.0592336 0.4871497 0.8713074 -0.06516772 0.5406033 0.8387499 -0.1854401 0.5325628 0.8258262 -0.1842859 0.5238291 0.8316501 -0.3060553 0.5076792 0.8053522 -0.30417 0.4933456 0.8149177 -0.4175506 0.4706593 0.7772589 -0.4150378 0.4516062 0.7898073 -0.5176591 0.4241776 0.7430359 -0.5146086 0.4011883 0.757777 -0.606384 0.3705379 0.7035624 -0.602822 0.3444021 0.7197172 -0.6837903 0.3120433 0.6595907 -0.6798682 0.283618 0.6762693 -0.7400137 0.2561091 0.6219227 -0.05537879 0.7584963 0.6493202 -0.06151813 0.8307583 0.5532236 -0.1687324 0.8234214 0.5417625 -0.1683301 0.8175738 0.5506705 -0.27895 0.8029339 0.5267677 -0.2791497 0.7933087 0.5410516 -0.3818439 0.7728052 0.5069196 -0.383133 0.7595692 0.525608 -0.4755565 0.7349115 0.4834781 -0.4781047 0.7184351 0.5052396 -0.5599609 0.6911618 0.4568799 -0.5638788 0.6716352 0.4805693 -0.6350035 0.6432622 0.4277667 -0.6400995 0.6212257 0.4520526 -0.6895972 0.5988474 0.4072316 -0.6566801 0.683446 0.3188617 -0.5327947 0.8378635 0.1188057 -0.5389638 0.8321895 0.1303023 -0.5011833 0.8494809 0.1649174 -0.4884127 0.8618111 0.1368749 -0.4376992 0.8820145 0.174556 -0.4275094 0.8919506 0.1471729 -0.3678166 0.9118196 0.1824716 -0.3604683 0.919443 0.1571218 -0.2921409 0.9376586 0.1882821 -0.287642 0.9431526 0.1665096 -0.2111602 0.9584213 0.1919381 -0.209158 0.9620541 0.1752281 -0.1408202 0.9716103 0.1901133 -0.1393539 0.9489769 0.2828839 -0.09730416 0.9777441 0.1858724 -0.04695779 0.9804604 0.1910299 -0.03740155 0.994183 0.1010021 0.5327947 0.8378635 0.1188057 0.0724554 0.1738354 0.9821057 0.06657826 0.486921 0.8709049 0.04493182 0.931189 0.3617574 0.0695216 0.7578119 0.6487588 0.6281042 0.7075333 0.3238548 0.666021 0.6629978 0.3418335 0.73017 0.1202957 0.6725926 0.7359888 0.4148731 0.5349774 0.7100015 0.01381903 0.7040646 0.6002373 0.2646303 0.7547754 0.5867674 -0.1178545 0.8011332 0.6842253 0.3522485 0.6385584 0.6767824 0.02987897 0.7355766 0.72064 0.06690573 0.6900737 0.1249342 0.1820719 0.975316 0.1934688 0.283871 0.9391418 0.1676651 0.1184407 0.9787034 0.2957382 0.215593 0.9306227 0.2840312 0.1552204 0.9461675 0.388965 0.1447595 0.9098083 0.3941023 0.1676176 0.9036526 0.4753128 0.09183108 0.8750113 0.4989272 0.1922052 0.8450614 0.5256935 0.1011489 0.8446392 0.5620092 0.07880258 0.8233686 0.03740155 0.994183 0.1010021 0.04695779 0.9804604 0.1910299 0.09730499 0.9777448 0.1858685 0.1393539 0.9489769 0.2828839 0.5846914 0.7878591 0.1934273 0.5413388 0.8309943 0.1280658 0.5036348 0.8484569 0.1627054 0.4858316 0.8629511 0.1388635 0.4402217 0.8811166 0.1727381 0.424879 0.8929421 0.1487697 0.3702302 0.9111199 0.1810804 0.3579533 0.9202231 0.1583006 0.2942977 0.9371737 0.1873346 0.2854419 0.9436872 0.1672651 0.2128489 0.9581546 0.1914034 0.2074259 0.962358 0.1756178 0.1408202 0.9716103 0.1901133 0.04991716 0.8309788 0.5540601 0.1687245 0.8234226 0.5417633 0.1683339 0.8175729 0.5506708 0.2789498 0.8029341 0.5267674 0.2791495 0.7933077 0.541053 0.3818439 0.7728052 0.5069196 0.3831331 0.7595682 0.5256093 0.4755565 0.7349115 0.4834781 0.4781054 0.7184367 0.5052367 0.5599609 0.6911618 0.4568799 0.563875 0.6716383 0.4805696 0.6350051 0.6432598 0.4277678 0.640099 0.6212242 0.452055 0.695146 0.5960395 0.4018819 0.7075611 0.5264268 0.4714151 0.01438653 0.1626521 0.9865787 0.05978101 0.2807573 0.9579153 0.05855184 0.5408127 0.8391027 0.1854401 0.5325628 0.8258262 0.1842864 0.5238307 0.8316491 0.3060553 0.5076792 0.8053522 0.3041691 0.4933441 0.8149189 0.417551 0.4706577 0.7772597 0.4150374 0.4516063 0.7898073 0.5176591 0.4241776 0.7430359 0.5146026 0.4011904 0.75778 0.606384 0.3705379 0.7035624 0.6028273 0.3444021 0.7197127 0.6837903 0.3120433 0.6595907 0.6798663 0.2836178 0.6762713 0.7371042 0.257541 0.6247799 0.7412217 0.3067891 0.5970519 0.3659521 -0.1711603 0.9147586 0.2638488 -0.1476911 0.95319 0.1670534 -0.1181596 0.9788419 -0.02802962 -0.980304 0.195496 -0.02747911 -0.985702 0.1662423 -0.006407856 -0.87459 0.484821 0.0111382 -0.8093215 0.5872604 0.01653522 -0.7173161 0.6965516 0.02959948 -0.5899167 0.8069215 0.0453633 -0.4651892 0.8840483 0.0452609 -0.3766641 0.9252436 0.1087113 -0.131697 0.9853111 0.05644971 -0.2659363 0.9623364 0.05092936 -0.3012807 0.9521744 0.01579374 -0.1087385 0.993945 0.2569315 -0.2810003 0.9246757 -0.1869839 -0.9631336 0.1934182 -0.205733 -0.9645487 0.1652866 0.01170998 -0.8553144 0.5179771 0.02645307 -0.8385064 0.5442492 0.2369492 -0.5668752 0.7889916 0.2496636 -0.5387696 0.804609 0.4065244 -0.1817196 0.895386 0.3670125 -0.3223057 0.8725944 -0.1353932 -0.9703524 0.2002124 -0.1472887 -0.9732576 0.1762833 0.02682042 -0.8218072 0.5691342 0.01393592 -0.8352898 0.5496334 0.1930796 -0.4993113 0.8446353 0.1815181 -0.521203 0.8339057 0.2511617 -0.3284924 0.9105002 0.325117 -0.1606256 0.9319326 -0.0820648 -0.9757637 0.2028563 -0.08740121 -0.9784964 0.1868309 0.01828598 -0.8099138 0.586264 0.01248908 -0.8193635 0.5731383 0.1207305 -0.4714484 0.8735907 0.1155272 -0.4860451 0.8662642 0.1546235 -0.3046932 0.9398157 0.2261622 -0.141246 0.9637947 -0.4175049 -0.185502 0.8895385 -0.3661546 -0.1718312 0.9145517 -0.231868 -0.1425873 0.9622402 -0.2637776 -0.1480445 0.9531549 -0.2561774 -0.2895762 0.9222357 -0.0631864 -0.2507312 0.9659925 -0.1100146 -0.129044 0.9855174 -0.1289918 -0.1306557 0.9830007 -0.02248412 -0.1087262 0.9938175 -0.04862481 -0.3326699 0.941789 -0.0452609 -0.3766641 0.9252436 -0.0453633 -0.4651892 0.8840483 -0.02959948 -0.5899167 0.8069215 -0.01653522 -0.7173161 0.6965516 -0.0111382 -0.8093215 0.5872604 0.00640583 -0.87459 0.484821 0.08590465 -0.9787108 0.1864014 0.2031629 -0.9653544 0.1637555 -0.3663754 -0.2920346 0.8834506 -0.2340804 -0.5658212 0.7906028 -0.2527215 -0.5395005 0.8031633 -0.008852124 -0.8543041 0.5196981 -0.02956569 -0.8392921 0.5428764 0.1897534 -0.9623565 0.1945865 0.1450857 -0.9737628 0.1753182 0.1377189 -0.9698918 0.2008569 -0.0268265 -0.8218086 0.5691319 -0.01393598 -0.8352916 0.5496305 -0.1930803 -0.4993125 0.8446342 -0.1815189 -0.5212048 0.8339045 -0.2507688 -0.3297382 0.910158 -0.3267288 -0.1616645 0.931189 0.03026962 -0.9856258 0.1662095 0.02574294 -0.9804279 0.1951885 0.08361679 -0.9755893 0.2030616 -0.01827996 -0.8099125 0.5862659 -0.01248908 -0.8193653 0.5731357 -0.1207249 -0.4714496 0.8735908 -0.1155276 -0.4860469 0.8662632 -0.1691725 -0.2251681 0.9595207 -0.1554328 -0.2796219 0.9474451 0.9913212 -0.02696692 0.1286665 0.9892359 0.003844857 0.1462793 0.9893309 -0.0424447 0.1393662 0.9840762 -0.06662416 0.1647885 0.991223 -5.31822e-5 0.1322005 0.9912211 1.692e-4 0.1322146 0.9912199 2.69829e-4 0.1322233 0.9912124 2.99034e-4 0.1322793 0.9912136 3.05568e-4 0.132271 0.991235 1.76146e-4 0.132111 0.9926955 -0.001678705 0.1206359 0.9913615 2.71924e-6 0.1311586 0.9912932 -9.41149e-6 0.1316733 0.9912458 -1.30085e-4 0.1320299 0.9912381 -1.81777e-4 0.1320866 0.9912203 -2.75444e-4 0.1322211 0.9912125 -3.39365e-4 0.1322787 0.9912188 -2.56988e-4 0.1322315 0.9912212 -2.12208e-4 0.132214 0.9912825 4.07832e-5 0.1317538 0.9918196 -6.13865e-4 0.1276463 0.9925076 0.01022046 0.1217544 0.9927443 0.006715357 0.1200574 0.9932087 0.001495599 0.1163374 0.9974736 -0.001800715 0.07101672 0.9974356 -7.68612e-7 0.0715695 0.9937225 1.60115e-4 0.1118738 0.9938426 0 0.1108018 0.9940056 0 0.1093298 0.9939947 2.68002e-5 0.1094291 0.9941787 -1.99139e-5 0.1077442 0.9944497 5.05801e-4 0.1052117 0.9947971 0.002803802 0.1018375 0.9951184 0.006697416 0.09846055 0.9953807 0.01186889 0.09527093 0.995597 0.008026242 0.0933932 0.9962397 6.07367e-4 0.08663803 -0.9838752 -0.06619042 0.166158 -0.9882601 -0.0494703 0.1445503 -0.9890998 -0.05124491 0.1380423 -0.9974751 0 0.07101714 -0.9933329 0.001570224 0.1152715 -0.9912226 -1.09786e-4 0.1322034 -0.9912191 -2.65731e-4 0.1322294 -0.9912126 -3.31993e-4 0.1322779 -0.9912205 -2.77994e-4 0.1322187 -0.9912409 -1.59472e-4 0.1320667 -0.9912932 -9.41149e-6 0.1316733 -0.9913594 5.43847e-6 0.131174 -0.9927712 0.008944511 0.1196895 -0.9923261 0.003037393 0.1236114 -0.9914975 -1.61646e-4 0.1301265 -0.9914914 -2.09632e-4 0.1301724 -0.9912824 4.62219e-5 0.1317551 -0.9912353 1.71384e-4 0.1321085 -0.9912143 2.93623e-4 0.1322664 -0.9912133 3.09283e-4 0.1322728 -0.9912135 3.0041e-4 0.1322717 -0.991222 1.59298e-4 0.1322086 -0.9912237 -6.0661e-5 0.1321953 -0.9977036 0.01641362 0.0657137 -0.9969987 -8.14722e-4 0.07741492 -0.9954489 0.001939475 0.09527736 -0.9957328 0.02040815 0.08999854 -0.9946257 -0.001532673 0.1035248 4.01769e-5 1 1.83895e-4 0.001157045 0.9999988 -0.001029133 0.002719879 0.9999948 -0.001744985 -0.01972693 0.9997838 -0.006593286 -0.02259945 0.9997165 -0.007511556 -0.01405376 0.9998931 -0.004025101 -0.02170902 0.9997488 -0.005580246 -2.48895e-6 1 9.32252e-5 2.64382e-6 1 1.29547e-4 1.95296e-5 1 2.32438e-4 -1.9916e-5 1 2.56559e-5 -7.05205e-6 1 -4.89457e-6 0 1 -4.11167e-6 0 1 -4.11168e-6 2.40832e-5 1 -1.04612e-6 6.96836e-4 0.9999996 -5.76979e-4 4.41075e-4 0.9999999 -4.20995e-4 1.65059e-4 1 -2.26869e-4 1.43246e-5 1 -1.54976e-5 7.23779e-4 0.9999997 -5.39676e-4 0.001796841 0.9999955 -0.002416491 0.001218438 0.9999976 -0.001834869 0.001605153 0.9999948 -0.002818524 3.42781e-4 0.9999993 -0.00118649 1.38457e-4 1 -3.30203e-4 -1.42597e-5 1 -6.95482e-5 -2.69531e-5 1 9.00784e-5 -4.70088e-5 1 1.28769e-4 -5.11329e-5 1 2.19134e-4 -4.72503e-5 1 2.99955e-4 2.73761e-5 1 1.41661e-4 3.52553e-5 1 1.39397e-4 4.67852e-5 1 1.08056e-4 -1.44414e-6 1 -4.40046e-6 7.32635e-5 1 -2.02335e-4 -7.90094e-4 0.9999982 -0.001749932 -8.10849e-4 0.9999983 -0.00167936 6.22198e-4 0.9999999 -1.92092e-4 -0.004094421 0.9999909 0.001173436 0.01059663 0.9999309 -0.005103528 0.0164569 0.9998264 -0.008735358 -9.21229e-4 0.9999996 -1.08578e-4 0.03252321 0.9994565 0.005390286 0.01327306 0.9999101 0.001967847 0.05923801 0.9982069 0.008587419 0.02190923 0.999756 0.002817213 0.002504348 0.9999969 2.79276e-4 -0.002057731 0.999992 -0.003445565 -0.002130329 0.9999931 -0.003075838 -0.001804292 0.9999963 -0.002061128 -6.91681e-4 0.9999994 -8.68475e-4 -5.55882e-4 0.9999998 -6.06106e-4 -0.00100398 0.9999991 -0.001002609 -8.06086e-4 0.9999995 -6.31479e-4 -6.87199e-4 0.9999996 -5.4647e-4 -0.001113057 0.9999986 -0.001223564 -8.14313e-4 0.9999995 -5.62526e-4 -8.42885e-4 0.9999995 -5.9079e-4 -0.002715647 0.9999951 -0.001620233 -0.003819406 0.9999896 -0.002490699 -0.01807761 0.9998006 -0.008495986 -0.02030766 0.9997453 -0.009849429 -0.02494484 0.9996358 -0.01030921 -0.02496135 0.9996389 -0.009966135 0.009854257 0.9999412 -0.004544258 0.01869875 0.999809 -0.005691051 7.07776e-4 0.9999998 -2.45558e-4 4.19135e-4 1 -1.18612e-4 0.005087852 0.9999869 5.93782e-4 0.01169604 0.9999291 0.002261281 0.02444243 0.9996885 0.005056321 -0.008890748 0.9999594 -0.001525461 -0.009881675 0.9999498 -0.001721441 0.003637075 0.9999924 -0.001398503 0.004644751 0.9999886 -0.001174807 0.004496812 0.9999893 -0.001157283 0.002163171 0.9999977 -1.50947e-6 -0.003265082 0.9999945 7.26191e-4 -0.003349184 0.999994 9.0364e-4 -0.00407207 0.9999915 7.84139e-4 -0.001122474 0.9999994 -1.20324e-4 -1.53521e-6 1 -1.29483e-7 -0.002174556 0.9999976 4.11058e-4 -0.002287328 0.9999973 3.18372e-4 0 1 -1.73457e-7 0 1 0 0 1 0 0 1 0 0 1 0 -6.01201e-5 1 -8.23572e-6 -3.29344e-5 -1 -4.7777e-6 -6.8133e-5 1 4.7426e-5 -4.27246e-4 1 3.3644e-4 -4.08527e-4 1 3.46959e-4 0 1 -1.52687e-5 -2.17111e-5 1 1.88322e-4 0 1 -8.65651e-5 0 1 0 0 1 -5.77005e-7 0 1 8.82394e-7 0 1 -4.34813e-6 0 1 -1.14337e-6 0 1 7.32966e-6 0 1 8.84405e-7 0 1 2.62624e-6 0.667862 -0.4854735 -0.5641594 0.7313805 -0.4750375 -0.4893077 0.7074358 -0.005401253 -0.7067571 0.7088952 -0.01169306 -0.7052169 0.7129144 -0.1228598 -0.6904048 0.7079274 -0.1024403 -0.6988168 0.7066969 -0.05446535 -0.705417 0.712719 -0.4755441 -0.5156447 0.7051451 -0.4295354 -0.5641541 0.709711 -0.3799333 -0.593263 0.7038734 -0.3619459 -0.6111934 0.7073227 -0.3242908 -0.6281164 0.7052763 -0.2745567 -0.6536085 0.7121995 -0.2486976 -0.656446 0.7082934 -0.2179126 -0.6714423 0.7049882 -0.172257 -0.687982 -0.1300773 0.9900423 0.05381703 0.9446606 0.2378724 0.2259048 0.9452716 0.2360419 0.2252689 0.7212649 0.659377 0.2121295 0.7254574 0.6551792 0.2108359 0.333558 0.9306897 0.1501858 0.3430457 0.9274484 0.1488601 -0.1301852 0.9900008 0.05431628 -0.1161795 0.9918078 0.0531004 -0.1440649 0.9880348 0.05507057 0.3334486 0.9306465 0.1506956 0.3239141 0.9337869 0.1520589 0.7211187 0.6593121 0.2128272 0.716885 0.6634858 0.2141555 0.9445951 0.2378458 0.2262071 0.9439843 0.23965 0.2268516 0.1917342 0.9814454 0.001736581 0.1642777 0.9864142 2.07792e-5 0.2120465 0.9772596 -9.46492e-6 0.3568791 0.9340962 0.0100786 0.3497138 0.9368351 0.006355464 0.3457439 0.9383179 0.004562735 0.3453779 0.9384533 0.004418253 0.3460025 0.9382221 0.004650175 0.3476564 0.9376074 0.005239307 0.3510282 0.9363436 0.006320595 0.3508755 0.9364011 0.006282746 0.2420443 0.9702648 9.48551e-4 0.2279105 0.9736822 5.23454e-5 0.2788823 0.9603254 -3.02812e-5 0.3092436 0.9509577 0.006916105 0.3078863 0.95142 0.002496778 0.3015193 0.9534568 -0.002511858 0.2669099 0.9636791 0.009048879 0.2403859 0.9703421 0.02551436 0.3439318 0.9389813 0.005023837 0.3345491 0.9423711 0.003686726 0.3186877 0.9478579 0.001940131 0.3092082 0.9509579 0.008339941 0.3062114 0.9519051 0.01056009 0.512198 0.85882 -0.009019911 0.5188522 0.8548464 0.005501866 0.5051167 0.8630474 -0.00252074 0.5010377 0.8654177 0.003683567 0.498845 0.8665866 0.01347529 0.5021759 0.8646157 0.01609539 0.4964064 0.8680102 0.01179993 0.4911261 0.8710501 0.008188009 0.4851833 0.8744 0.004671216 0.460366 0.8877093 -0.005953371 0.4775748 0.8785893 0.001759707 0.4381757 0.8988662 -0.006461322 0.4668536 0.8842393 0.01298785 0.4602366 0.8877533 0.00874871 0.4533446 0.8913177 0.005607664 0.4465508 0.8947533 0.002985477 0.2685715 0.9623912 -0.04089623 0.3371051 0.9413774 -0.0130009 0.4101848 0.9119959 0.003451347 0.3961814 0.9181719 -8.95589e-4 0.4311578 0.9022765 2.42371e-4 0.438628 0.8986679 0.001263201 0.1716726 0.9851539 6.32251e-4 0.1378762 0.9904495 -1.19464e-4 0.1098917 0.9939436 1.74923e-4 0.1041563 0.994561 -1.44614e-6 0.07627993 0.9970865 1.82096e-6 0.04386311 0.9990374 -6.84613e-4 0.03240203 0.999475 7.36112e-7 -0.03240203 0.999475 7.36112e-7 -0.04386311 0.9990374 -6.84613e-4 -0.07627993 0.9970865 1.79488e-6 -0.1041563 0.994561 -1.44614e-6 -0.1098917 0.9939436 1.749e-4 -0.1378763 0.9904495 -1.19464e-4 -0.1716725 0.9851539 6.32251e-4 -0.1917338 0.9814454 0.001736342 -0.2107504 0.9775356 0.002928197 -0.2390816 0.9709832 0.005644917 -0.1632225 0.9865812 -0.004011869 -0.2975184 0.9547159 8.01562e-4 -0.2279105 0.9736822 5.23777e-5 -0.2598295 0.9656545 6.23963e-7 -0.2750369 0.9614337 6.0869e-5 -0.3093553 0.9509454 0.001504421 -0.3180247 0.9480802 0.002077102 -0.3272148 0.9449456 0.002887308 -0.3460035 0.9382218 0.004650473 -0.3453779 0.9384533 0.004418253 -0.3457419 0.9383187 0.004561603 -0.3295083 0.9441475 0.003127813 -0.3345491 0.9423711 0.003686726 -0.3439318 0.9389812 0.005023717 -0.3508754 0.9364012 0.006282627 -0.3510282 0.9363436 0.006320595 -0.3476558 0.9376076 0.005238592 -0.3961812 0.9181721 -8.95588e-4 -0.4101848 0.9119959 0.003451347 -0.3497145 0.9368348 0.006355643 -0.3568768 0.9340971 0.01007932 -0.2685715 0.9623912 -0.04089623 -0.3371052 0.9413773 -0.0130009 -0.4311578 0.9022765 2.42371e-4 -0.4386287 0.8986675 0.001263201 -0.4465508 0.8947533 0.002985477 -0.453343 0.8913186 0.005606591 -0.4602395 0.8877517 0.00874871 -0.4403044 0.8978405 -0.003812253 -0.4719817 0.8816083 5.82121e-4 -0.4647253 0.8854545 -9.46772e-4 -0.4776545 0.8785467 0.001426935 -0.4851833 0.8744 0.004671216 -0.4997611 0.8661106 0.009557962 -0.4993586 0.8662821 0.01401507 -0.4964154 0.868005 0.01179987 -0.4911261 0.8710501 0.008188009 -0.5010395 0.8654167 0.003683567 -0.5051045 0.8630546 -0.00252074 -0.5188547 0.8548448 0.005501925 -0.5121905 0.8588245 -0.009019792 -0.9444662 0.2377958 0.2267966 0.1292941 0.9903323 0.05024957 0.1170747 0.9914745 0.05720037 -0.3341914 0.9309266 0.1472817 -0.3424034 0.9272114 0.1517859 -0.7216427 0.6595221 0.2103869 -0.7250726 0.6550376 0.2125921 -0.9447876 0.2379205 0.225323 -0.9451428 0.2359959 0.2258563 -0.9441115 0.2397018 0.2262668 -0.7207222 0.6591679 0.2146096 -0.7172725 0.6636353 0.2123875 -0.3327994 0.9303936 0.1536634 -0.3245544 0.9340393 0.1491141 0.1309815 0.9896885 0.05797016 0.1431663 0.9883863 0.05095028 0.766982 0.5500981 0.3303494 0.7231496 0.6683318 0.1743198 0.7120684 0.6450228 0.277316 0.7137072 0.6314195 0.3032024 0.7554171 0.5874795 0.2901945 0.7500323 0.6062909 0.2643163 0.6475396 0.7493795 0.1382855 0.633865 0.7582631 0.1524866 0.6125295 0.7863732 0.08015561 0.6620281 0.677379 0.3207437 0.642503 0.6563475 0.3954718 0.6430107 0.7180226 0.2664225 0.5692172 0.8144253 0.1127091 0.5624123 0.8055825 0.1863579 0.5384662 0.8411015 0.05101394 0.6810728 0.664619 0.3072808 0.6817418 0.6655915 0.3036708 0.5835419 0.8048552 0.1081064 0.5837572 0.8057295 0.100138 0.5229299 0.7475202 0.4095827 0.5231251 0.7396 0.4234763 0.5349768 0.7236597 0.4360235 0.5565447 0.7018494 0.444596 0.5905624 0.671252 0.4479475 0.6492353 0.6207489 0.4395045 0.4933214 0.7248917 0.4807974 0.486529 0.7289521 0.4815792 0.2906571 0.798808 0.5267108 0.2318115 0.8135113 0.5333506 0.009044706 0.8915573 0.4528178 -0.1843649 0.8432139 0.5049752 0.1003255 0.8240532 0.5575582 0.0457201 0.8528111 0.5202144 0.114503 0.8354969 0.5374329 -0.7570319 0.5995528 0.2596909 -0.5293636 0.7575904 0.3818784 -0.4313678 0.8082947 0.4007263 -0.09736883 0.8768448 0.4708105 0.02999383 0.8827484 0.4688879 0.1658347 0.8676036 0.4687888 0.4843869 0.7697359 0.4157837 0.4859496 0.7688976 0.415511 0.4844045 0.8151485 0.3176245 0.4828148 0.8160231 0.317799 0.02994686 0.9313588 0.3628692 0.02865749 0.9314387 0.3627684 -0.4309015 0.8408342 0.3276002 -0.4318528 0.8404456 0.3273446 -0.5507909 0.7777262 0.3029378 -0.7558948 0.6175371 0.217419 -0.8863109 0.435805 0.1566115 0.1765321 0.9841668 0.01588374 0.1849019 0.9824748 0.0235508 -0.3005041 0.9530089 0.03835856 -0.2789304 0.958476 0.0593453 -0.7087914 0.703644 0.05000025 -0.6818996 0.7264043 0.08573186 -0.9548848 0.2933183 0.04647004 -0.9364314 0.3366994 0.09864014 0.1684455 0.9855515 0.01773679 0.1771935 0.9838362 0.02586245 -0.3209572 0.9461167 0.04300808 -0.2986962 0.9521201 0.06517732 -0.7328642 0.6780974 0.0556249 -0.7057795 0.7022467 0.09340798 -0.9678395 0.2464174 0.05064767 -0.9506943 0.291478 0.1059289 -0.9902129 -0.1153814 0.07852101 -0.9905568 0.05122584 0.1271741 -0.9853534 -0.06031066 0.1595038 -0.9829251 0 0.184006 -0.9224115 0.3699555 0.1108607 -0.8863614 0.4423459 0.1367248 -0.7213277 0.6626521 0.2014412 -0.7559061 0.6289754 0.1816479 -0.3554167 0.8921085 0.2789651 -0.432376 0.865795 0.2518932 0.07847511 0.9537819 0.290072 0.02868682 0.959277 0.2810066 0.4972941 0.8316092 0.2472343 0.4833967 0.8399742 0.246518 -0.944608 0.3153465 0.09095251 -0.9104902 0.3978334 0.1128554 -0.7189018 0.6745519 0.1678093 -0.7215447 0.6719168 0.1670362 -0.3541825 0.9115767 0.2087649 -0.3560553 0.9109007 0.2085297 0.07743972 0.974649 0.2099106 0.07740134 0.9746508 0.209917 0.4941347 0.8523706 0.1711586 0.4957666 0.8514447 0.1710481 0 3.66548e-4 -1 3.16136e-4 5.21888e-4 -0.9999998 -0.755023 -0.4410725 -0.4851755 -0.7765982 -0.1934565 -0.599558 -0.78544 -0.008816361 -0.618875 -0.770725 -0.1573016 -0.6174457 -0.7858175 -0.108577 -0.6088531 -0.7720263 -0.08735835 -0.6295587 -0.7749593 -0.02203488 -0.6316271 -0.7197843 -0.008799135 -0.6941421 -0.7585069 -0.2716384 -0.5923513 -0.773167 -0.2203359 -0.5946975 -0.7751796 -0.1891083 -0.6027724 -0.7904067 -0.2320244 -0.5669409 -0.7670519 -0.2931711 -0.5706857 -0.7553176 -0.3515346 -0.5530995 -0.7887767 -0.3134136 -0.5287752 -0.726028 -0.4078702 -0.5536472 1 -8.97504e-7 -7.84642e-7 1 -4.96821e-6 6.18369e-7 1 1.31355e-6 -7.22463e-7 1 -3.43059e-6 -1.06737e-6 0 1 -3.97065e-6 0 -0.8603655 0.5096776 0 -0.8603657 0.5096773 0 -0.001960754 -0.9999982 0 -0.001960754 -0.9999981 0.001979887 -0.002169787 -0.9999957 0.06604272 -0.01005643 -0.9977661 -0.04330945 -0.07119208 -0.996522 0.2289932 -0.1201296 -0.9659872 -0.3659301 -0.1743751 -0.9141601 0 -0.2306409 -0.973039 0 -0.2966872 -0.9549748 -0.3289687 -0.3309246 -0.8844596 0.1440168 -0.3832467 -0.9123492 -0.1749254 -0.4924951 -0.8525549 0 -0.4900677 -0.8716844 0 -0.509678 -0.8603653 0 -0.5096801 -0.860364 -4.00945e-4 -0.509701 -0.8603515 4.85093e-7 -0.5096778 -0.8603655 0 -0.509678 -0.8603652 2.3405e-5 -0.5096762 -0.8603664 0 -0.5096778 -0.8603655 5.12611e-6 -0.5096779 -0.8603653 0 1 -6.8132e-6 0 1 -2.1549e-6 0.5516436 -0.004792332 -0.8340663 0.6783679 -0.005613982 -0.734701 0.6874084 -0.459786 -0.562198 0.6418939 -0.2367008 -0.7293456 0.6410549 -0.2972369 -0.7076008 0.6410503 -0.2972406 -0.7076033 0.6410507 -0.3910778 -0.660388 0.6410533 -0.3910754 -0.6603868 0.625665 -0.1894711 -0.7567325 0.6410515 -0.1978282 -0.741564 0.6415269 -0.1112601 -0.758989 0.6266173 -0.0961796 -0.7733695 0.6418525 -0.05903005 -0.7645528 0.6416577 -0.01272881 -0.7668855 0.6163358 -0.03902238 -0.7865161 0.4828345 -0.03409308 -0.8750478 0.2586328 -0.04623711 -0.9648685 0.3362475 -0.01104402 -0.9417091 0.4111928 -0.007076382 -0.911521 0.1604295 -0.009524166 -0.9870014 0.2002285 -0.01028919 -0.9796953 0.01894587 -0.01007658 -0.9997698 0.05967289 -0.01663714 -0.9980794 0.1138843 -0.03890669 -0.9927319 0.08818995 -0.02191233 -0.9958627 0.08803319 -0.1229321 -0.9885029 0.08803361 -0.1229298 -0.9885032 0.08817303 -0.2297422 -0.9692492 0.1180515 -0.255958 -0.9594527 0.08820968 -0.2955329 -0.9512515 0.08803689 -0.3857773 -0.9183819 0.08803528 -0.3857799 -0.918381 0.0881291 -0.4915535 -0.8663766 0.07283031 -0.4988862 -0.8636019 0.3464201 -0.4779974 -0.8071627 0.7130521 -0.4247199 -0.5578259 0.6722324 -0.431533 -0.6015671 0.6418909 -0.4246307 -0.6384864 0.5920404 -0.4909749 -0.6390867 0.4938237 -0.4612089 -0.7371734 0.2807748 -0.02759176 -0.9593771 0.2802615 -0.1184677 -0.9525855 0.280262 -0.1184653 -0.9525856 0.2802643 -0.2474303 -0.927486 0.2802638 -0.2474296 -0.9274863 0.2802615 -0.3717611 -0.8850126 0.2802626 -0.3717604 -0.8850125 0.2806296 -0.4679686 -0.8380051 0.2207477 -0.4962312 -0.8396577 0.4799559 -0.03171163 -0.8767194 0.4791547 -0.1083241 -0.8710206 0.4791554 -0.1083236 -0.8710203 0.4791564 -0.2262416 -0.8480707 0.4791497 -0.2262448 -0.8480736 0.4791532 -0.3399322 -0.8092332 0.4791564 -0.3399286 -0.8092328 0.479155 -0.4472446 -0.7552369 0.4791544 -0.4472461 -0.7552364 0.460306 -0.2435759 -0.8536916 0.1032224 -0.9686024 -0.2261737 0.9829251 0 0.184006 0.9853534 -0.06031066 0.1595038 0.9905568 0.05122572 0.1271737 0.9902129 -0.1153814 0.07852101 0.9518866 0.2919703 0.09308785 0.9397251 0.3381424 0.05076068 0.7065787 0.7026599 0.08375954 0.684152 0.7275486 0.05107831 0.2991169 0.9523748 0.05925774 0.2802522 0.9591785 0.03788584 -0.1770551 0.9839121 0.02384698 -0.1844176 0.982728 0.0153681 0.9643964 0.2448716 0.0998882 0.9544749 0.2931088 0.05536144 0.7303212 0.6769768 0.09128808 0.7084036 0.7035193 0.05678904 0.3193663 0.9453913 0.06511926 0.300243 0.9529169 0.04246801 -0.1690486 0.9852592 0.02620828 -0.176621 0.9841294 0.01715821 0.956657 0.2785074 0.08509463 0.7214482 0.6646632 0.1942561 0.7560183 0.6261367 0.1907594 0.8863614 0.4423459 0.1367248 0.3557094 0.8968263 0.2630086 0.3873336 0.883116 0.2647243 0.5938844 0.7702648 0.2323651 -0.4973033 0.8324992 0.244202 -0.4977732 0.8322681 0.244032 -0.07839 0.9558192 0.2833104 -0.07805335 0.9558255 0.2833823 0.1754208 0.9434809 0.2811964 -0.4857575 0.8568986 0.1725243 -0.4957484 0.8516181 0.1702363 -0.04828405 0.9761101 0.2118437 -0.07737642 0.9749596 0.2084864 0.3994576 0.8929699 0.2074576 0.3560577 0.9113788 0.206426 0.764645 0.6241877 0.1603361 0.7215136 0.6726467 0.164209 0.9144358 0.3888602 0.1122264 0.9224115 0.3699555 0.1108607 -0.4843843 0.7696621 0.4159233 0.5292977 0.7576312 0.3818888 0.7569974 0.5995919 0.2597009 0.8863223 0.435784 0.1566052 0.7558948 0.6175371 0.217419 0.550791 0.7777265 0.3029374 -0.2906571 0.798808 0.5267108 -0.2317203 0.8135343 0.5333551 -0.114503 0.8354969 0.5374329 -0.5350236 0.7236229 0.436027 -0.5704203 0.7265638 0.3830481 -0.5713343 0.686285 0.4501002 -0.6492701 0.6207427 0.4394621 -0.1736146 0.8720797 0.4575316 -0.1157053 0.8351615 0.5376967 0.05667829 0.8433991 0.5342897 -0.02999734 0.879381 0.475173 -0.4859234 0.7689856 0.415379 -0.4865136 0.7289584 0.4815851 -0.4933501 0.7248781 0.4807885 -0.5229299 0.7475202 0.4095827 -0.5231369 0.7395895 0.4234799 0.593172 0.750163 0.292237 0.4309442 0.839654 0.3305578 0.4313678 0.8082947 0.4007263 0.09736835 0.8768461 0.4708082 -0.009044706 0.8915573 0.4528178 0.1843624 0.8432187 0.5049682 -0.4971704 0.808454 0.3149982 -0.4844236 0.8147261 0.3186774 -0.07785141 0.9293852 0.3608079 -0.03000664 0.9305347 0.3649725 0.1748386 0.9174571 0.3573571 0.3868266 0.8592441 0.334761 -0.6775901 0.6365582 0.3683277 -0.644385 0.6872156 0.3354142 -0.6430109 0.7180228 0.2664213 -0.5946835 0.7876011 0.1613563 -0.5531148 0.8234701 0.1263367 -0.5384733 0.8410973 0.05100882 -0.5867569 0.8029166 0.1050776 -0.5804886 0.8077303 0.1029801 -0.68262 0.6636983 0.3058341 -0.6801856 0.6665558 0.3050426 -0.6711095 0.7327154 0.1128725 -0.7008652 0.6846883 0.1999748 -0.7624592 0.5822161 0.2822772 -0.747677 0.6080382 0.2669622 -0.766982 0.5500981 0.3303494 -0.70558 0.6493328 0.2837671 -0.7216076 0.6262771 0.2950585 -0.5941534 0.7983575 0.09801602 -0.6556107 0.7438712 0.1297317 -0.821855 0.5257061 0.2195165 -0.7837789 0.5373415 0.3113759 -0.7487323 0.5923797 0.2974665 -0.8078063 0.5481222 0.2168203 -0.8205851 0.5347018 0.2018268 -0.8162333 0.5396675 0.2062093 -0.7845374 0.5829395 0.2113828 -0.7959619 0.5717614 0.1988311 -0.7592855 0.6181107 0.2035307 -0.7720568 0.606881 0.1887429 -0.5337603 0.7682521 0.3533959 -0.8071554 0.5616011 0.1819462 -0.7293466 0.6702533 0.1371646 -0.926207 0.376944 -0.007343649 -0.7952617 0.5578816 0.2373332 -0.7885171 0.585148 0.1893221 -0.7977196 0.5753569 0.1805765 -0.5640544 0.8168077 0.1211105 -0.6796746 0.6627306 0.3143734 -0.6796283 0.6626766 0.3145874 -0.7509216 0.475262 0.4585227 -0.7440161 0.01313465 0.6680327 -0.7727108 0.2896052 0.5648425 -0.750946 0.4748945 0.4588631 -0.8713372 0.2600317 0.4161192 -0.7273861 0.6623951 0.1792827 -0.7145677 0.6794106 0.1667162 -0.8177811 0.4909557 0.3003274 -0.5946896 0.793684 0.1281023 -0.5963591 0.792737 0.1261901 -0.6098804 0.7801373 0.1393983 -0.6266087 0.7706047 0.116318 -0.6325775 0.7651934 0.1196859 -0.6370892 0.7624825 0.1128624 -0.6410123 0.7592374 0.1125251 -0.8169308 0.4935066 0.2984549 -0.7923802 0.5088965 0.3363897 -0.7923631 0.5089212 0.3363928 -0.7630659 0.5254552 0.3763343 -0.7630185 0.5255768 0.3762601 -0.7526648 0.5315014 0.3885896 -0.6797192 0.6626497 0.3144477 -0.8670552 0.1673403 0.4692681 -0.8426267 0.1823507 0.506684 -0.8437044 0.1738188 0.5078878 -0.8059107 0.1953178 0.5588909 -0.8063529 0.1736845 0.5653572 -0.7738209 0.191504 0.6037611 -0.7901872 0.1044409 0.603901 -0.1700319 -0.724206 0.6682924 -0.3057293 -0.6604501 0.68581 -0.5251752 -0.4143208 0.7433232 -0.7142316 -0.1236339 0.6889035 -0.6810629 -0.1700268 0.7122108 -0.4683939 -0.4988288 0.7292305 -0.4411761 -0.5854808 0.6801294 -0.4647759 -0.5350242 0.7055016 0.003855824 -0.5599405 0.8285239 -0.2050653 -0.7690224 0.605436 -0.2687026 -0.6967287 0.6651076 -0.3439455 -0.6478129 0.6797353 -0.460152 -0.4926933 0.7385889 -0.4966334 -0.4700834 0.7296416 -0.7127579 -0.1937655 0.6741151 -0.6914024 -0.2119643 0.6906765 0.9942559 -0.01423072 -0.1060785 0.9943476 -0.01713079 -0.1047834 0.992406 0.00268507 -0.1229767 0.992986 -0.003971934 -0.1181653 0.991816 0.005009114 -0.1275773 0.992554 -9.54379e-4 -0.1218026 0.9922502 0.00747174 -0.1240313 -0.7298693 0.3193178 -0.604423 -0.1210872 -0.7676507 0.6293253 0.1629234 -0.9066461 0.3891645 0.2306523 -0.9561944 0.1802546 -0.4834419 -0.208064 0.8502902 0.2235834 -0.934978 0.2753666 0.2547859 -0.9507547 0.1764929 0.1881191 -0.8973831 0.3991429 0.1235483 -0.8802239 0.4581941 0.05852407 -0.8647411 0.4987965 -0.1433306 -0.7678159 0.6244317 -0.2925397 -0.6224609 0.7259222 -0.3098765 -0.5997083 0.7377849 -0.2687082 -0.6508845 0.7100319 -0.257583 -0.6631633 0.7027556 -0.1363205 -0.7724528 0.620269 -0.5016059 -0.4230342 0.7546083 -0.7049524 -0.006332099 0.7092264 -0.6747866 -0.1323692 0.7260452 -0.5758698 -0.3114762 0.7558814 -0.4582813 -0.5076059 0.7295989 -0.6041082 -0.1758787 0.7772517 -0.597009 -0.2013701 0.7765504 -0.5048214 -0.3754029 0.7773211 -0.5458055 -0.2921769 0.7853209 -0.3684095 -0.5565277 0.7446821 -0.4189745 -0.4824488 0.7692229 -0.196002 -0.7228274 0.6626491 -0.207163 -0.7299418 0.651359 -0.3211124 -0.5831708 0.7461894 -0.4999635 -0.1395296 0.8547328 -0.383913 -0.4173876 0.8236495 -0.2724714 -0.5793096 0.7682186 -0.261018 -0.5990369 0.7569839 -0.01812738 -0.8575109 0.5141464 -0.05754661 -0.8127256 0.579798 0.2090389 -0.9508783 0.2283268 0.213881 -0.9369502 0.2763681 -0.5555818 -0.1913354 0.8091475 -0.6056964 -0.009612262 0.7956377 -0.4220029 -0.4338182 0.7960625 -0.4615473 -0.3522722 0.8141736 -0.2897813 -0.6114878 0.7362809 -0.337317 -0.5399135 0.771175 -0.06750768 -0.8170317 0.5726273 -0.1160941 -0.764948 0.6335432 0.2229083 -0.9350575 0.2756437 0.1549296 -0.9058575 0.3942321 -0.02843469 -0.4880706 0.8723409 0.001777172 -0.6421841 0.7665484 0.02057397 -0.8595176 0.5106919 0.2045716 -0.9003495 0.3840849 0.2698604 -0.9187155 0.2883356 0.2278212 -0.9225602 0.3114169 0.2334293 -0.898894 0.3708104 0.2138795 -0.9013564 0.3765796 0.1431952 -0.865705 0.4796354 0.2545045 -0.9319314 0.2583242 0.2263333 -0.9389921 0.2589732 0.2333091 -0.9363957 0.2621643 0.3110375 -0.9497972 0.03378075 0.289276 -0.9561566 0.04565298 0.3411754 -0.909501 -0.2375022 0.1918351 -0.9613707 0.1973974 0.1197902 -0.9807006 0.1545211 0.07028734 -0.9837568 0.1651735 0.05610364 -0.9890456 0.1365337 0.04066842 -0.9877549 0.15062 0.01167953 -0.9934883 0.113335 0.02637243 -0.504215 0.8631754 -0.07903188 2.50784e-4 0.9968721 -0.03065353 0.07005798 0.9970719 -0.05318534 1.43694e-7 0.9985847 -0.05293262 -0.02305811 0.9983319 -0.2990888 0.06918519 0.951714 -0.2412354 -0.01135659 0.9704003 -0.1684049 0.01317429 0.9856299 -0.1857226 0.04872697 0.9813933 -0.1264131 -0.005033195 0.991965 -0.1701247 -0.600774 0.7811071 -0.3043397 -0.250979 0.9189054 -0.313633 -0.2430425 0.9179132 -0.248792 -0.2212632 0.942945 -0.3180765 -0.1633398 0.9338883 -0.1922739 -0.2371721 0.9522501 -0.2023856 -0.2251699 0.953068 -0.1519142 -0.2136347 0.9650297 -0.1147391 -0.248288 0.961867 -0.1042646 -0.2243775 0.9689085 -0.03894942 -0.2168727 0.9754226 -0.03202742 -0.1899927 0.981263 0.3333746 -0.9418577 0.04201811 0.2480587 -0.9404771 0.2323143 0.2220138 -0.9492798 0.2226606 0.2394106 -0.9482991 0.2083541 0.1927602 -0.9617616 0.1945723 0.2068147 -0.9614234 0.1813634 0.1676236 -0.9706587 0.1724069 0.1627284 -0.9706519 0.1770722 0.1198245 -0.9806773 0.1546425 -0.01399797 -0.3521643 0.9358336 -0.01105141 -0.5532236 0.8329595 -0.01908743 -0.5536544 0.8325278 -0.02267748 -0.5499911 0.8348626 -0.03402805 -0.5512739 0.8336302 -0.04074275 -0.5454213 0.8371713 -0.05141609 -0.54725 0.8353884 -0.06184488 -0.539376 0.839791 -0.07286077 -0.5419156 0.8372688 -0.08763378 -0.532323 0.8419933 -0.09972083 -0.5358112 0.8384284 -0.1197635 -0.5243702 0.8430259 -0.1369639 -0.530343 0.8366464 -0.1582498 -0.5166488 0.8414458 -0.2520799 -0.5034425 0.826439 -0.1690165 -0.5562207 0.8136658 -0.2222732 -0.5801571 0.7835894 -0.2037736 -0.5777489 0.7903686 -0.005473136 -0.7617681 0.6478268 0.03652679 -0.8169239 0.5755878 0.0237292 -0.8177893 0.5750285 0.02027547 -0.8153671 0.5785893 0.03786832 -0.8133774 0.5805027 0.03128325 -0.8095398 0.5862309 0.04907888 -0.806489 0.5892087 0.03885382 -0.8014863 0.5967497 0.05525368 -0.7977077 0.6005077 0.04065334 -0.7917962 0.609431 0.054744 -0.7877255 0.6135891 0.03483587 -0.7809423 0.623631 0.04666239 -0.7768139 0.6279991 0.020931 -0.7697008 0.6380617 0.0295754 -0.766169 0.6419584 -0.003099918 -0.7586197 0.6515263 0.004089176 -0.7552395 0.6554361 -0.03799611 -0.7506424 0.6596153 -0.09565353 -0.8032929 0.5878528 -0.02214622 -0.7882843 0.6149125 0.00217694 -0.9332701 0.3591687 0.002183258 -0.933282 0.3591379 0.04932785 -0.9309841 0.3617118 0.04795664 -0.9293608 0.3660448 0.08090049 -0.925647 0.3696386 0.07799279 -0.923036 0.376725 0.1095363 -0.9176447 0.382008 0.104512 -0.9140476 0.3919113 0.132785 -0.9075531 0.3983913 0.1249991 -0.9030693 0.4109028 0.1490093 -0.8961458 0.4179942 0.1376693 -0.8907448 0.4331524 0.1572723 -0.883925 0.4403887 0.1418694 -0.877832 0.4574759 0.1560366 -0.8720468 0.4638826 0.1353908 -0.8651179 0.4829498 0.1422666 -0.8619025 0.4867077 0.1157509 -0.8544169 0.506531 0.1228117 -0.850647 0.5111917 0.06387245 -0.8424749 0.534936 -0.1527141 -0.2430913 0.9579066 -0.02689224 -1.65554e-7 0.9996384 -0.05068051 -0.1085993 0.992793 -0.07933437 0.005302011 0.996834 -0.1264094 -0.005016922 0.9919655 0.03200978 2.12199e-7 0.9994876 0.05068004 -0.108031 0.9928549 0.1511618 -0.2793018 0.9482303 0.1303455 -0.006272792 0.9914489 0.08426284 0.003762602 0.9964365 0.2982673 0.06620401 0.9521836 -0.2172327 -0.9023973 0.3721412 0.005475521 -0.7617681 0.6478268 0.03201192 0 0.9994876 0.05350047 0.0350545 0.9979524 0.05293262 -0.02305811 0.9983319 0.01187074 -0.5043554 0.8634147 0.01399856 -0.3521643 0.9358336 0.04102241 -0.1899295 0.9809404 0.0318402 -0.2160008 0.9758739 0.02843624 -0.4880706 0.8723407 -0.009492814 -0.9935115 0.1133357 -0.04150664 -0.9884313 0.1458794 -0.07592856 -0.9912228 0.1082231 -0.05041354 -0.98378 0.1721499 -0.1205714 -0.9812704 0.1502368 -0.1176987 -0.9808906 0.1549215 -0.1623403 -0.9708345 0.1764257 -0.1626805 -0.9706214 0.1772834 -0.1819501 -0.9674599 0.1758282 -0.3278915 -0.9405916 0.08817487 -0.3140691 -0.948857 0.03210943 -0.289276 -0.9561566 0.04565298 -0.3418005 -0.9079573 -0.2424584 -0.192312 -0.961516 0.1962219 -0.2107726 -0.922899 0.3222302 -0.2616299 -0.9052238 0.3348429 -0.1774268 -0.9055625 0.3853266 -0.2887769 -0.8888369 0.3557764 -0.1473639 -0.8900923 0.4313001 -0.01404964 -0.7887679 0.6145307 0.04855543 -0.7962894 0.6029642 0.3137628 -0.2430855 0.9178575 0.3108958 -0.245226 0.9182637 0.3019284 -0.2557314 0.9183904 0.08402985 -2.05704e-4 0.9964632 0.130411 -0.005394339 0.9914454 0.1733937 0.04090631 0.9840027 0.1865245 0.007115125 0.9824246 0.2403215 -0.01104509 0.9706305 0.3127313 -0.2427421 0.9183003 0.2572119 -0.2001313 0.9454045 0.1994233 -0.2334161 0.9517076 0.196725 -0.2239001 0.9545513 0.1240127 -0.2070377 0.9704413 0.1320924 -0.2879195 0.9485009 0.1042617 -0.2243778 0.9689088 -0.1977746 -0.9636852 0.1794328 -0.2016973 -0.9593824 0.1972402 -0.2290924 -0.9515011 0.2053345 -0.2320197 -0.9460006 0.2263841 -0.249502 -0.9399634 0.2328467 -0.2459455 -0.9294808 0.2749116 -0.2638171 -0.917392 0.2979809 -0.001774847 -0.6421841 0.7665484 -0.01834768 -0.551338 0.8340802 0.02212089 -0.5538105 0.8323488 0.01967191 -0.549637 0.835172 0.03916072 -0.5518282 0.833038 0.03569471 -0.544537 0.8379769 0.05867928 -0.5484588 0.8341162 0.05475586 -0.5377047 0.8413534 0.08236354 -0.5440464 0.835003 0.07841902 -0.5296027 0.8446133 0.1116362 -0.5391733 0.8347633 0.1082885 -0.5202786 0.8471032 0.1471316 -0.533793 0.8327168 0.1454465 -0.5174425 0.8432667 0.2036644 -0.5105553 0.8353767 0.2363693 -0.5860067 0.775065 0.2132648 -0.5764579 0.7888057 -0.02057838 -0.8595176 0.5106918 -0.03652954 -0.8169238 0.5755877 -0.02082866 -0.8179645 0.5748915 -0.02314627 -0.8150601 0.5789139 -0.03287142 -0.8139687 0.5799781 -0.03619503 -0.8087262 0.5870708 -0.04203712 -0.8077288 0.5880536 -0.04572558 -0.7999326 0.5983452 -0.04601979 -0.799865 0.5984133 -0.04959905 -0.7892322 0.6120887 -0.04317653 -0.7910826 0.6101837 -0.04593813 -0.7770733 0.6277314 -0.03271424 -0.78167 0.6228337 -0.0342139 -0.7642362 0.6440284 -0.01318705 -0.7727955 0.6345182 -0.01233345 -0.7512703 0.6598796 0.03186988 -0.7715879 0.6353241 0.1449574 -0.6065142 0.7817468 -0.00218141 -0.9332699 0.3591696 -0.002169549 -0.9332832 0.3591347 -0.04848796 -0.9310396 0.3616827 -0.04878926 -0.9292836 0.3661306 -0.07949542 -0.9258258 0.3694956 -0.07938545 -0.9228204 0.3769624 -0.1075366 -0.918015 0.3816863 -0.1064597 -0.9136262 0.3923693 -0.1301462 -0.908193 0.3978033 -0.1275632 -0.9023618 0.4116684 -0.1457285 -0.8971299 0.4170385 -0.1408295 -0.8896753 0.4343328 -0.1533405 -0.8853351 0.4389401 -0.1456226 -0.8763196 0.459193 -0.1514173 -0.8739621 0.4618043 -0.1397652 -0.863079 0.4853457 -0.1368926 -0.8644215 0.4837726 -0.1207376 -0.8517614 0.5098286 -0.1101873 -0.8573302 0.5028359 -0.0278688 -0.8005925 0.5985609 0.6029697 -0.1812489 0.7769019 0.4442251 -0.4987505 0.7442527 0.5176157 -0.4171618 0.7470275 0.5758922 -0.3114702 0.7558668 0.6747866 -0.1323692 0.7260452 0.136321 -0.7724534 0.620268 0.257583 -0.6631633 0.7027556 0.2687082 -0.6508845 0.7100319 0.2925284 -0.6224477 0.725938 0.3098732 -0.5996945 0.7377976 -0.03927725 -0.7859635 0.6170241 0.03041326 -0.8321753 0.5536781 -0.1669382 -0.8882786 0.4278935 -0.1251837 -0.8823589 0.4536208 -0.1600314 -0.9217123 0.353322 -0.2712633 -0.9303634 0.2466581 -0.1875466 -0.9346607 0.3020523 -0.2427548 -0.9541063 0.1753603 -0.2317905 -0.9557898 0.1809396 -0.1864633 -0.9077171 0.375874 -0.1560347 -0.9048878 0.3960193 0.1863139 -0.7165178 0.6722273 0.2048323 -0.7284893 0.6537178 0.3900249 -0.5622062 0.7292494 0.531374 -0.09075915 0.8422615 0.4768958 -0.2058386 0.8545179 0.3839145 -0.4173851 0.8236502 0.2724712 -0.5793104 0.7682181 0.2610365 -0.599038 0.7569766 0.6128925 -0.06163811 0.7877586 0.5362247 -0.2089085 0.8178144 0.4667633 -0.3551031 0.8099592 0.4165424 -0.4314731 0.800202 0.3426854 -0.5428508 0.7667333 0.2840655 -0.609054 0.7405135 0.7049146 -0.00643444 0.709263 0.5980067 -0.1991764 0.7763484 0.5506587 -0.295283 0.7807579 0.4997631 -0.3727109 0.7818717 0.4239313 -0.4856537 0.7644755 0.3631421 -0.553767 0.7493129 0.1316094 -0.7732319 0.6203156 0.1266406 -0.7706145 0.6245923 0.05612444 -0.8120953 0.5808196 0.06840193 -0.8174104 0.5719803 0.006524741 -0.8534845 0.5210773 0.7187383 0.3593691 -0.5952051 -0.9942622 -0.01423084 -0.1060198 -0.9943425 -0.01732766 -0.1047992 -0.9924718 0.002138912 -0.1224547 -0.9928771 -0.003002643 -0.1191052 -0.99163 0.005059301 -0.1290131 -0.992554 -9.54379e-4 -0.1218026 -0.9924414 0.005907356 -0.1225783 0.4789924 -0.5067138 0.7168037 0.450871 -0.5593964 0.6955509 0.2687337 -0.6967344 0.6650891 0.2050653 -0.7690224 0.605436 0.1691764 -0.7387305 0.6524237 0.5251752 -0.4143208 0.7433232 0.4647759 -0.5350242 0.7055016 0.4773627 -0.5055091 0.7187388 0.355944 -0.61628 0.7024976 0.3057933 -0.6604359 0.6857952 0.7205135 -0.1300804 0.6811311 0.7037765 -0.1869236 0.6853892 0.6878386 -0.1750248 0.7044462 0.7003872 -0.1268005 0.7024096 -0.7069564 7.07641e-6 0.7072572 -0.7411896 0 0.6712958 -0.7453276 -0.005398094 0.6666767 -0.4309198 -0.08046305 0.8987958 -0.5010052 -0.005328834 0.8654279 -0.5566841 0.02177089 0.830439 -0.5368306 -0.02734774 0.8432468 -0.6337433 0.03218245 0.7728737 -0.6186667 -0.004823267 0.7856388 -0.6706442 0.001180708 0.7417783 -0.6694162 -6.79309e-5 0.7428877 -0.7069574 2.16171e-4 0.7072561 -0.4877352 0.08637058 0.8687087 -0.4084228 -0.00535506 0.9127771 -0.365384 0.02409636 0.930545 -0.3717506 0.04216271 0.9273748 -0.3226205 -0.001101493 0.9465278 -0.2748708 0.006878852 0.9614566 -0.3091469 0.1192577 0.9435072 -0.257841 0.01643234 0.9660477 -0.1838157 -0.03855568 0.9822043 0.2811042 0.08412224 0.9559832 -0.196525 0.00873804 0.9804599 -0.1411655 -9.25401e-4 0.9899857 -0.1267881 0.01054233 0.9918739 -0.1204291 1.06789e-4 0.9927219 -0.07622164 1.02644e-4 0.9970909 -0.07785189 0.005650043 0.996949 -0.02303087 -0.003921926 0.9997271 -0.02431833 0 0.9997044 0.01315957 0 0.9999135 0.01697832 -0.006710946 0.9998334 0.06722265 0.01860141 0.9975646 0.07031565 -4.95279e-5 0.9975249 0.1143092 -8.81754e-6 0.9934453 0.1187818 -0.005082964 0.9929075 0.1747612 0.02930855 0.9841746 0.1781448 -0.02619642 0.9836555 0.2511323 0.01427674 0.9678476 0.2922022 0.003699898 0.9563494 0.3205441 -8.32083e-4 0.9472333 0.3707844 0.03232699 0.9281563 0.371283 0.05134487 0.9270991 0.4077782 -0.00630927 0.9130593 0.4636791 0.0328074 0.8853957 0.4578185 -0.04591441 0.8878593 0.5033761 -0.004014909 0.8640582 0.5488665 0.01815235 0.835713 0.5427811 -0.05380219 0.8381492 0.633289 0.0535987 0.7720572 0.6298422 -0.008710026 0.7766743 0.670286 0.00220251 0.7420997 0.671622 -2.73845e-6 0.740894 0.7069789 3.0871e-4 0.7072347 0.7069773 2.15934e-6 0.7072364 0.7411896 0 0.6712958 0.7453276 -0.005399107 0.6666767 0.7856576 0.01973587 0.6183468 0.7848836 0.02896672 0.618966 0.8060399 -0.00535649 0.5918369 0.824953 0.005089879 0.5651786 0.8441945 -0.04466539 0.5341728 -0.7815842 0.01709759 0.6235656 -0.7868356 0.02592694 0.616618 -0.8060398 -0.00535649 0.5918372 -0.8249534 0.005092144 0.5651778 -0.8441945 -0.04466539 0.5341728 0.6122077 0.7677115 0.1892638 0.7735168 0.2850303 0.5660649 0.7639309 0.1117156 0.6355544 0.7440207 0.01310938 0.668028 0.7516804 0.4859676 0.4458834 0.76713 0.3831768 0.5144774 0.6796317 0.6626623 0.3146101 0.71548 0.678207 0.1677014 0.6410073 0.7592418 0.1125242 0.7265259 0.6635299 0.1785727 0.8573248 0.312024 0.4094328 0.7861764 0.1849386 0.5896818 0.8049542 0.1744804 0.5671028 0.8073925 0.1945356 0.5570219 0.8424694 0.1745707 0.5096767 0.8438907 0.1816063 0.5048443 0.8757736 0.1615772 0.4548774 0.8179451 0.4908648 0.3000293 0.8167756 0.4936136 0.2987025 0.7923735 0.5089057 0.3363914 0.7923696 0.508912 0.3363912 0.7630556 0.5254671 0.3763383 0.7630285 0.5255649 0.3762569 0.7352764 0.5408647 0.4084535 0.7490209 0.5787874 0.3224483 0.6370803 0.7624896 0.1128642 0.631315 0.7659382 0.1215739 0.6278865 0.7698333 0.1145213 0.6084489 0.7809006 0.1413657 0.5978165 0.7919113 0.1244674 0.5809487 0.8011433 0.1437641 0.5919571 0.7965215 0.1230466 0.7310847 0.6685501 0.1362206 0.9262126 0.3769301 -0.007343709 0.8099102 0.5447824 0.2173887 0.7497649 0.6227259 0.2237523 0.7977243 0.5753521 0.1805713 0.8071554 0.5616011 0.1819462 0.748731 0.5923755 0.297478 0.7837975 0.5373261 0.3113554 0.8218739 0.5256761 0.219518 0.8078043 0.5481246 0.2168216 0.8205851 0.5347018 0.2018268 0.7900028 0.5677639 0.2313868 0.8042685 0.5632721 0.1894116 0.7686274 0.5976192 0.2281744 0.7801771 0.5994009 0.1790038 0.6236156 0.7064059 0.3348049 0.743756 0.6514085 0.1499804 0.9912326 0.07464289 0.1090255 0.9926743 0.0746361 0.09501188 0.989928 0.07463759 0.1202996 0.9895938 0.08043664 0.1193065 0.9653106 0.2337339 0.1163789 0.9653106 0.2337337 0.1163787 0.9303296 0.3606802 0.06630635 0.9919937 0.1047008 0.07061332 0.9760513 0.2061474 0.06947839 0.9695988 0.2337431 0.0724045 0.9202545 0.3867403 0.05969572 0.9179838 0.3867635 0.0878629 0.9155455 0.3867725 0.1103793 0.9155462 0.3867707 0.1103792 0.9179839 0.3867633 0.0878629 0.9678784 0.2337296 0.09263843 0.9678782 0.2337305 0.09263861 0.9926744 0.07463473 0.095012 0.9944959 0.07463991 0.07353168 0.9970151 0.03036975 0.07098406 0.8807892 0.4427483 0.1678821 0.723401 0.4634743 0.5117448 0.6388361 0.443497 0.6286485 0.5722241 0.5190207 0.6349623 0.9813143 -0.06101268 0.182482 0.9845 -0.07178848 0.1600193 0.9784889 -0.05829429 0.1978922 0.9529472 -0.1378525 0.2699785 0.9468293 -0.1208382 0.2981818 0.9250224 -0.1834527 0.3326843 0.7898166 -0.1917819 0.5825886 0.8274785 -0.1688207 0.5355174 0.671366 -0.1863301 0.7173205 0.6196284 -0.1555663 0.7693243 0.5417458 -0.2377388 0.8062207 0.5895095 -0.105687 0.8008176 0.4596675 -0.2395483 0.855174 0.4945443 -0.1341651 0.858735 0.3738961 -0.2286638 0.8988407 0.3907984 -0.1723144 0.9042037 0.05974721 -0.02078288 0.9979972 0.07180839 -0.1550433 0.9852945 0.0920251 -0.182806 0.9788327 0.05074626 -0.06854528 0.9963566 0.08431506 -0.1020613 0.9911985 0.06619751 0.01938909 0.9976181 0.07079052 0.01353019 0.9973995 0.07712954 0.1067654 0.9912882 0.0646581 0.1290149 0.9895325 0.08222299 0.1927813 0.9777908 0.05096632 0.2795401 0.9587805 0.08953279 0.2393485 0.9667969 0.07464176 0.3233926 0.9433164 0.08520609 0.3604542 0.9288772 0.08012717 0.3751394 0.9234989 0.07991939 0.44075 0.894065 0.07518696 0.4483793 0.8906756 0.1643336 0.4242642 0.8905023 0.3030111 0.5300457 0.7919822 0.25897 0.4303683 0.8647068 0.3901955 0.5129701 0.7645974 0.3497809 0.4388654 0.8276779 0.7284415 0.4274147 0.5354341 0.8057068 0.4258146 0.4117264 0.8563063 0.4131016 0.3099787 0.8722603 0.4300624 0.2328266 0.8840225 0.4128722 0.2191823 0.8575681 0.4392092 0.267717 0.4358116 0.237633 0.8681008 0.4582819 0.1980048 0.8664709 0.5406395 0.1840202 0.820881 0.5407274 0.184068 0.8208124 0.6185396 0.1683312 0.7675111 0.6186035 0.1683745 0.7674502 0.440966 0.4630756 0.7688369 0.4731951 0.4394891 0.7635022 0.5266688 0.44081 0.7268471 0.5553197 0.4234154 0.715779 0.5720022 0.4241307 0.7020874 0.632227 0.3946043 0.6667657 0.6323643 0.394633 0.6666185 0.2951719 0.4106605 0.8626887 0.4427739 0.3762779 0.8138588 0.379378 0.3570597 0.8535695 0.4646551 0.336533 0.819049 0.4647743 0.3365725 0.8189652 0.5466528 0.3128138 0.7767357 0.546767 0.312857 0.776638 0.6240179 0.2861343 0.7271375 0.6241523 0.2861827 0.7270031 0.9403138 0.01372087 0.3400321 0.9410878 0.05123883 0.3342581 0.9411123 0.05107128 0.3342146 0.9427654 0.08709365 0.3218821 0.9428012 0.08681613 0.3218521 0.945276 0.1200706 0.303375 0.9453105 0.1197316 0.3034013 0.9485222 0.1491501 0.2793921 0.9485504 0.1487826 0.2794922 0.9523901 0.1734343 0.2507464 0.9524085 0.1731169 0.2508956 0.9567369 0.1922444 0.2183957 0.9567489 0.1920016 0.2185566 0.961432 0.2050514 0.1833097 0.9614345 0.2049215 0.1834416 0.9687711 0.215678 0.1223343 0.9680816 0.2335917 0.09084576 0.8657519 -0.1111661 0.4879711 0.8154903 -0.1356374 0.5626528 0.8132367 -0.05351209 0.5794675 0.7546954 -0.06282377 0.6530606 0.7543666 0.03550356 0.6554926 0.6884905 0.04048568 0.7241145 0.6907692 0.1511488 0.7071011 0.6908289 0.1510722 0.7070591 0.6956905 0.2569318 0.670821 0.6957916 0.2567912 0.67077 0.7030533 0.3543065 0.6165899 0.7031727 0.3541157 0.6165633 0.7116193 0.4261986 0.5585274 0.6659334 0.4668886 0.5818486 0.9812191 -0.06794798 0.1805336 0.9812877 -0.06848239 0.1799577 0.9767456 -0.05325925 0.2076815 0.9461109 -0.1286056 0.2972118 0.9434195 -0.0963096 0.317308 0.910411 -0.1359052 0.3907449 0.9077604 -0.08630543 0.4105149 0.8657012 -0.1113129 0.4880275 0.8638493 -0.04389989 0.5018339 0.8132101 -0.05355906 0.5795004 0.8129371 0.03026217 0.5815649 0.7543845 0.03552174 0.655471 0.7563905 0.1326128 0.6405367 0.7564429 0.1325268 0.6404926 0.7607145 0.2254227 0.6086856 0.7607988 0.2252708 0.6086365 0.7671763 0.3108671 0.5610724 0.7672852 0.310648 0.5610448 0.775533 0.3861867 0.4994083 0.7756341 0.3859683 0.4994202 0.7845119 0.4402401 0.4367262 0.7746058 0.4570349 0.4371556 0.9414682 -0.06146162 0.3314518 0.9404441 -0.02419984 0.3390862 0.9062613 -0.03415375 0.4213361 0.9060825 0.01927214 0.4226622 0.8636147 0.02484571 0.5035399 0.8650183 0.0927838 0.4930869 0.865063 0.09266304 0.4930312 0.86805 0.1577028 0.4707643 0.8681102 0.1575096 0.4707181 0.8725767 0.2174746 0.4373955 0.8726472 0.2172264 0.437378 0.8784257 0.2701636 0.3941827 0.8784981 0.2698854 0.3942118 0.8854019 0.3142367 0.3425187 0.8854644 0.3139801 0.3425921 0.8932536 0.3483788 0.2841306 0.893298 0.3481903 0.2842225 0.901726 0.3716695 0.220799 0.9017532 0.3715549 0.2208806 0.940431 -0.02427518 0.3391168 0.940307 0.01368534 0.3400524 0.9060971 0.01930582 0.422629 0.9071834 0.07207566 0.414516 0.9072161 0.07194399 0.4144673 0.9095389 0.1225202 0.3971496 0.9095902 0.1222817 0.3971056 0.9130633 0.1689268 0.371186 0.9131161 0.1686482 0.3711829 0.9176166 0.2098508 0.3375539 0.9176685 0.2095398 0.3376061 0.9230412 0.2440702 0.2973629 0.9230839 0.2437851 0.2974641 0.9291499 0.2705663 0.2519415 0.9291783 0.2703546 0.2520637 0.9357404 0.2886345 0.2026822 0.9357549 0.288513 0.2027881 0.94134 0.2958249 0.1623783 0.9123705 0.386672 0.134406 0.9123513 0.3867571 0.134291 0.9157333 0.3796937 0.1313969 0.9433844 -0.09661245 0.3173201 0.9414951 -0.06127083 0.3314104 0.9077209 -0.08646792 0.4105681 0.906282 -0.03407466 0.4212981 0.8638289 -0.04394662 0.5018649 0.863604 0.02482342 0.5035594 0.8129413 0.03027993 0.5815579 0.8146504 0.1130586 0.5688255 0.8147034 0.1129568 0.5687701 0.8183427 0.1921832 0.5416465 0.8184181 0.1920069 0.5415951 0.823856 0.2650233 0.5010229 0.8239455 0.2647901 0.5009992 0.8309848 0.3292253 0.4484138 0.8310692 0.3289847 0.448434 0.839475 0.3829535 0.3855234 0.8395479 0.3827363 0.3855807 0.8478816 0.4179584 0.3262019 0.8062902 0.4842259 0.3397376 0.169336 -0.288622 0.9423496 0.1953817 -0.1766704 0.9646831 0.1945036 -0.1498599 0.9693867 0.194479 -0.1498708 0.9693899 0.1931959 -0.0659942 0.9789384 0.1931879 -0.06600344 0.9789392 0.1929243 0.01872515 0.981035 0.1929084 0.01872855 0.981038 0.1936464 0.103332 0.9756145 0.1936494 0.1033443 0.9756126 0.1953819 0.1867164 0.9627891 0.1953935 0.1867327 0.9627836 0.1981223 0.2688995 0.9425714 0.1981719 0.2689524 0.9425457 0.2018395 0.3488427 0.9151883 0.2019323 0.3489071 0.9151434 0.2065163 0.4256541 0.881005 0.3704349 -0.06072819 0.9268712 0.3701789 0.01723736 0.9288007 0.370186 0.01725059 0.9287975 0.3708494 0.09509181 0.9238118 0.7585662 -0.1491259 0.6343018 0.7576053 -0.1587114 0.6331232 0.6919717 -0.1577651 0.7044754 0.6888706 -0.0715664 0.7213429 0.6164091 -0.07976531 0.7833756 0.6163854 -0.0797401 0.7833968 0.5383335 -0.08720004 0.8382083 0.5382968 -0.08717525 0.8382346 0.4557245 -0.09380459 0.8851643 0.3724513 0.1718381 0.9120042 0.3708608 0.09510684 0.9238058 0.508054 0.08580011 0.8570411 0.4562417 0.0162537 0.8897075 0.4556868 -0.09378331 0.885186 0.4025936 -0.09745407 0.9101765 0.3716483 -0.1379232 0.9180713 0.2819386 -0.222927 0.9331743 0.2854667 -0.2095404 0.9352015 0.2835494 -0.1445434 0.9480016 0.2835043 -0.1445907 0.9480079 0.2822784 -0.06365764 0.9572182 0.2822586 -0.06366395 0.9572236 0.2819895 0.01806318 0.9592475 0.2819945 0.01807016 0.9592459 0.2826867 0.09967315 0.9540197 0.2827197 0.09968715 0.9540085 0.2843683 0.1801 0.9416468 0.2844172 0.180139 0.9416246 0.2870381 0.2594029 0.9221276 0.2870805 0.2594448 0.9221027 0.2906186 0.3365277 0.8957065 0.9877325 0.07463932 0.1371632 0.9820423 0.07839369 0.1716027 0.9840452 0.08076661 0.1585304 0.9849364 0.08080691 0.1528741 0.9821207 0.07523101 0.1725672 0.9829011 0.07661271 0.1674396 0.9813045 0.06954705 0.1794574 0.9811359 0.06901651 0.1805805 0.9795941 0.05914419 0.192087 0.9795976 0.0591582 0.1920644 0.9782521 0.04752272 0.2019022 0.9782683 0.04761707 0.2018016 0.9769003 0.02998858 0.2115808 0.977458 0.03409731 0.2083585 0.9761388 0.01457905 0.2166578 0.9766054 0.02025008 0.2140837 0.9762635 0.005035996 0.2165278 0.9762834 0.005424022 0.2164286 0.9762863 -0.01616489 0.2158794 0.9765704 -0.009477794 0.2149894 0.9767333 -0.0314151 0.2121444 0.9767606 -0.02429729 0.2129515 0.9775567 -0.03927272 0.2069799 0.9775323 -0.0382201 0.2072917 0.9787781 -0.05340641 0.1978414 0.9786651 -0.05082678 0.1990763 0.9799692 -0.06224179 0.1891729 0.958246 -0.1341675 0.252515 0.9604855 -0.1576571 0.2293725 0.909097 -0.1185951 0.399347 0.9108223 -0.1339076 0.3904759 0.8777691 -0.1672903 0.4489269 0.8680991 -0.1456511 0.4745417 0.8196823 -0.2122125 0.5320591 0.8155435 -0.1355201 0.5626041 0.7573742 -0.1591012 0.6333017 0.7547247 -0.06278401 0.6530305 0.688836 -0.07160562 0.721372 0.6884666 0.04046791 0.7241383 0.6159638 0.04510319 0.7864823 0.6159847 0.04508298 0.7864671 0.537841 0.0493043 0.8416033 0.537859 0.04929184 0.8415926 0.4552078 0.05304306 0.888804 0.4582101 0.1979684 0.8665172 0.3724837 0.210056 0.9039537 0.3784047 0.3210837 0.8681678 0.2906945 0.3365812 0.8956617 0.2951081 0.4106127 0.8627332 0.2065759 0.4257125 0.8809627 0.2177689 0.6116408 0.7605738 0.05696612 0.3560887 0.9327142 0 -0.1666142 0.9860222 -0.003175675 -0.1838291 0.9829531 0.005241215 -0.07421165 0.9972288 -0.003142654 -0.1025263 0.9947254 0.00296241 0.02985602 0.9995499 -0.001508831 0.01360481 0.9999063 0.001434266 0.136917 0.9905816 -5.16001e-4 0.1293885 0.9915938 5.36269e-4 0.2428866 0.9700546 -4.96697e-5 0.2405155 0.9706454 2.69415e-5 0.3245308 0.9458752 -0.002971291 0.3454574 0.9384298 2.07651e-4 0.3766499 0.9263557 -4.3048e-4 0.448419 0.8938233 0 0.4500046 0.8930264 -0.9842351 0.0793479 0.1580675 -0.7756344 0.3859698 0.4994183 -0.94611 -0.1286035 0.2972154 -0.912351 0.3867573 0.1342926 -0.8739503 0.4576968 0.1634767 -0.9609029 -0.1556823 0.2289735 -0.9110123 -0.1352389 0.3895729 -0.08248353 0.1927703 0.9777711 -0.06635403 0.242192 0.9679568 -0.08281135 0.2777657 0.957073 -0.07092469 0.3443608 0.9361546 -0.08117145 0.360764 0.9291182 -0.07852572 0.4466781 0.8912421 -0.07378721 0.4412947 0.8943235 -0.02373099 0.1859221 0.9822779 -0.08909046 0.4320479 0.8974395 -0.07043677 -0.07398462 0.9947689 -0.02067023 0.3510938 0.9361122 -0.07275408 -0.1660184 0.9834352 -0.1033398 -0.2535175 0.9617952 -0.1949867 -0.16417 0.9669687 -0.2191215 -0.2696304 0.9377021 -0.2838358 -0.1523041 0.9467 -0.3721337 -0.3406407 0.863412 -0.3356419 -0.1228904 0.9339392 -0.4595017 -0.2530422 0.8513683 -0.4360451 -0.1602473 0.8855425 -0.5420982 -0.2027291 0.8154941 -0.5319818 -0.1753966 0.828391 -0.6198569 -0.1744265 0.7650836 -0.6196177 -0.1739618 0.7653831 -0.7704873 -0.1541364 0.6185398 -0.8345883 -0.2148578 0.5072462 -0.9582442 -0.1341837 0.2525132 -0.9849382 -0.06853073 0.1587468 -0.5780227 0.4769849 0.6620991 -0.6038528 0.4747611 0.6402841 -0.659513 0.4381681 0.6107795 -0.5725148 0.4238961 0.7018111 -0.555372 0.4247861 0.7149257 -0.5531883 0.4263127 0.7157097 -0.4737727 0.4515045 0.7560973 -0.4828349 0.4423068 0.755801 -0.3704348 -0.06072801 0.9268712 -0.2822684 -0.06366354 0.9572208 -0.2822657 -0.06365799 0.9572219 -0.1931976 -0.06600326 0.9789373 -0.1931961 -0.06599408 0.9789383 -0.07409083 -0.06822502 0.9949151 -0.1929087 0.0187292 0.981038 -0.2820026 0.01806372 0.9592437 -0.2819802 0.0180698 0.9592501 -0.3701867 0.01723593 0.9287975 -0.3701788 0.01725113 0.9288004 -0.4562415 0.01625305 0.8897076 -0.2826982 0.0996887 0.9540147 -0.3708654 0.09509199 0.9238055 -0.3708482 0.09510761 0.9238107 -0.4568923 0.08960455 0.8849976 -0.4832295 0.05184555 0.8739573 -0.537859 0.04929238 0.8415926 -0.5378414 0.04930388 0.8416031 -0.6159849 0.04508358 0.7864668 -0.6159634 0.04510265 0.7864826 -0.07862699 -0.1548186 0.9848091 -0.1944804 -0.1498609 0.9693911 -0.1944999 -0.1498701 0.9693858 -0.2835052 -0.1445465 0.9480144 -0.2835467 -0.1445879 0.9479956 -0.4324458 -0.1324433 0.8918797 -0.3697547 -0.09951394 0.9237848 -0.4556876 -0.09378284 0.8851857 -0.4557247 -0.09380537 0.8851642 -0.5382972 -0.08717477 0.8382343 -0.5383322 -0.08719927 0.8382093 -0.6163849 -0.07973951 0.7833973 -0.6164105 -0.07976472 0.7833746 -0.9410877 0.05124121 0.334258 -0.9403136 0.01372122 0.3400323 -0.9403071 0.01368826 0.3400518 -0.9404311 -0.02428102 0.3391163 -0.9404441 -0.0242027 0.3390858 -0.9414681 -0.06146013 0.3314521 -0.9414948 -0.06127083 0.3314113 -0.956369 -0.1357811 0.2586929 -0.9475618 -0.1321223 0.2909818 -0.9465662 -0.1237494 0.2978234 -0.92661 -0.161518 0.3395674 -0.9800843 -0.06262016 0.1884508 -0.9769814 -0.05400621 0.206375 -0.9811532 -0.06827563 0.180768 -0.9814021 -0.06882786 0.1792002 -0.979346 -0.05952095 0.1932322 -0.9799863 -0.06217253 0.1891074 -0.97875 -0.05189818 0.1983816 -0.9786038 -0.05102413 0.1993269 -0.9774962 -0.0378316 0.2075335 -0.8395482 0.382734 0.3855824 -0.9123681 0.3866783 0.1344045 -0.9017529 0.3715569 0.2208787 -0.8766831 0.4218723 0.2311938 -0.8560602 0.447824 0.2580986 -0.7031713 0.3541163 0.6165646 -0.6957922 0.2567896 0.6707699 -0.703051 0.3543074 0.6165921 -0.7672854 0.3106488 0.5610443 -0.7755337 0.3861871 0.4994068 -0.8310692 0.3289855 0.4484336 -0.8394737 0.3829545 0.3855257 -0.8854658 0.3139768 0.3425917 -0.8932541 0.348379 0.2841294 -0.9291775 0.2703567 0.2520647 -0.9357392 0.288637 0.2026843 -0.9614344 0.2049207 0.1834434 -0.968771 0.215681 0.1223298 -0.9821107 0.07456982 0.17291 -0.6919873 -0.1597551 0.7040113 -0.6888716 -0.07156604 0.7213421 -0.6888374 -0.0716058 0.7213707 -0.6884679 0.04046845 0.7241369 -0.68849 0.0404843 0.724115 -0.690769 0.151147 0.7071018 -0.7564429 0.1325268 0.6404926 -0.7607143 0.2254243 0.6086853 -0.8184189 0.1920039 0.5415951 -0.8238565 0.2650225 0.5010225 -0.8726475 0.2172265 0.4373777 -0.8784259 0.2701619 0.3941833 -0.9176685 0.2095398 0.3376061 -0.9230415 0.2440702 0.297362 -0.9524088 0.1731169 0.2508946 -0.9523898 0.1734382 0.2507445 -0.9485494 0.1487882 0.279493 -0.9176157 0.2098534 0.3375545 -0.9131165 0.1686458 0.3711832 -0.8725756 0.2174766 0.4373966 -0.8681099 0.1575132 0.4707174 -0.818342 0.192184 0.5416471 -0.814702 0.1129598 0.5687713 -0.7563902 0.1326118 0.6405373 -0.7543871 0.03552454 0.6554679 -0.7543647 0.03550201 0.6554949 -0.7546936 -0.06282514 0.6530624 -0.7547271 -0.06278514 0.6530277 -0.7574384 -0.1430888 0.6370344 -0.7027353 -0.1756782 0.6894204 -0.9452766 0.1200668 0.3033748 -0.942802 0.08682173 0.3218488 -0.9095383 0.1225237 0.39715 -0.9072151 0.07194393 0.4144694 -0.8650193 0.09278202 0.4930855 -0.8636157 0.02485042 0.503538 -0.8636046 0.0248233 0.5035584 -0.8638295 -0.04394757 0.5018639 -0.8638504 -0.04389995 0.501832 -0.8657025 -0.111312 0.4880256 -0.8657518 -0.111168 0.487971 -0.8691237 -0.1732491 0.4632588 -0.8921658 -0.08167129 0.4442635 -0.9427663 0.08709174 0.32188 -0.9411128 0.05106842 0.3342138 -0.9071843 0.0720703 0.414515 -0.9060956 0.01930856 0.4226322 -0.9060821 0.01927447 0.4226629 -0.9062608 -0.03415286 0.4213374 -0.906282 -0.03407919 0.4212977 -0.9077211 -0.08646506 0.4105682 -0.9077599 -0.08630585 0.4105161 -0.948523 0.1491385 0.2793955 -0.9453108 0.1197317 0.3034005 -0.9130634 0.1689269 0.3711859 -0.90959 0.122284 0.3971055 -0.8680502 0.1577014 0.4707645 -0.865063 0.09265792 0.4930319 -0.8146513 0.1130555 0.5688249 -0.8129397 0.03028172 0.5815603 -0.8129368 0.03026229 0.5815653 -0.8132123 -0.05355578 0.5794977 -0.813234 -0.05351674 0.5794708 -0.8154877 -0.1356391 0.5626562 -0.8155449 -0.1355167 0.5626028 -0.8138891 -0.1185524 0.5687969 -0.687178 -0.4959563 0.5308613 -0.1790916 0.5120745 0.840063 -0.2098218 0.4670447 0.8589785 -0.206579 0.4256446 0.8809949 -0.2065037 0.4257234 0.8809744 -0.2019232 0.3488337 0.9151733 -0.2018535 0.3489173 0.9151568 -0.1981784 0.2688943 0.9425611 -0.1981068 0.2689582 0.9425578 -0.1953883 0.1867162 0.9627879 -0.2838791 0.4876167 0.8256165 -0.2995584 0.4677938 0.831525 -0.2951675 0.410601 0.8627185 -0.2951102 0.4106727 0.8627038 -0.2906852 0.3365184 0.8956882 -0.2906323 0.3365906 0.8956784 -0.2870777 0.2593982 0.9221165 -0.4646574 0.3365325 0.8190478 -0.4647746 0.3365724 0.8189651 -0.5466549 0.3128138 0.7767343 -0.5467683 0.3128564 0.7766373 -0.6240152 0.2861347 0.7271396 -0.6241508 0.2861831 0.7270042 -0.6322251 0.3946068 0.666766 -0.6323652 0.3946332 0.6666175 -0.6415295 0.4718868 0.6047833 -0.7117441 0.4279179 0.5570517 -0.7179026 0.4306839 0.5469254 -0.729902 0.4262132 0.5344021 -0.7351741 0.4624149 0.4956729 -0.7860004 0.4547779 0.4187847 -0.7806568 0.4417356 0.4420913 -0.8062212 0.425199 0.4113554 -0.8044705 0.4851011 0.342789 -0.8477677 0.4173383 0.3272901 -0.856367 0.4130045 0.3099404 -0.8932996 0.3481863 0.2842221 -0.9017256 0.3716694 0.2208004 -0.935755 0.2885107 0.2027913 -0.9413411 0.295822 0.162377 -0.9680815 0.2335923 0.09084504 -0.3856295 0.4636871 0.7976742 -0.387909 0.4611819 0.7980212 -0.3827676 0.3917387 0.8366779 -0.411809 0.3497205 0.8414921 -0.3784096 0.3210829 0.868166 -0.3750321 0.2474845 0.8933658 -0.2870415 0.25945 0.9221133 -0.2844083 0.1800965 0.9416354 -0.1953919 0.1867328 0.9627839 -0.193646 0.1033318 0.9756146 -0.05620378 0.1072234 0.9926451 -0.08386904 0.1363027 0.9871108 -0.9567371 0.1922425 0.2183963 -0.9828886 0.07669299 0.1674757 -0.9811835 0.06877917 0.1804118 -0.9813763 0.07068938 0.1786156 -0.9795963 0.05915719 0.1920717 -0.979596 0.05914264 0.1920779 -0.9782657 0.04762268 0.201813 -0.9782599 0.04749459 0.2018711 -0.9772841 0.03444612 0.2091157 -0.9771874 0.02951008 0.2103191 -0.9765702 0.02029228 0.2142408 -0.976501 0.01433438 0.215036 -0.9762755 0.00542736 0.2164644 -0.9762873 0.005025506 0.2164211 -0.9763333 -0.009601891 0.216058 -0.976667 -0.01584804 0.214174 -0.9767322 -0.02433139 0.2130784 -0.977543 -0.03819322 0.2072464 -0.9433842 -0.09660482 0.3173229 -0.9434181 -0.09631252 0.3173109 -0.9104117 -0.1359053 0.3907433 -0.9108546 -0.1337486 0.3904553 -0.8984934 -0.1470592 0.4136222 -0.9868362 0.08446359 0.1379139 -0.9848216 0.08174139 0.1531173 -0.9614312 0.205052 0.1833136 -0.9567485 0.192003 0.2185568 -0.9291485 0.2705696 0.2519428 -0.9230837 0.2437884 0.2974624 -0.8854017 0.3142389 0.3425171 -0.8784978 0.2698878 0.3942111 -0.830985 0.3292254 0.4484136 -0.8239443 0.2647923 0.501 -0.7671744 0.3108669 0.5610751 -0.7607977 0.2252719 0.6086374 -0.6956933 0.2569315 0.6708182 -0.6908263 0.1510733 0.7070614 -0.6186031 0.1683747 0.7674505 -0.6185404 0.1683303 0.7675109 -0.5407274 0.1840683 0.8208124 -0.5406395 0.1840202 0.820881 -0.4582823 0.1980054 0.8664706 -0.4582104 0.1979681 0.8665172 -0.4053235 0.2057006 0.8907303 -0.3724513 0.1718385 0.9120042 -0.2843755 0.1801424 0.9416365 -0.2827134 0.0996713 0.9540119 -0.1936472 0.103344 0.975613 -0.1929244 0.01872509 0.981035 -0.06655955 0.01938766 0.9975942 -0.07466101 0.02972328 0.996766 -0.9179837 0.3867636 0.0878629 -0.9155461 0.386771 0.1103795 -0.9155457 0.3867722 0.1103791 -0.9653106 0.2337335 0.1163787 -0.9653109 0.2337322 0.1163789 -0.9926743 0.07463622 0.09501194 -0.994707 0.0744487 0.07082009 -0.9946909 0.07463771 0.07084745 -0.9818026 0.17656 0.06992995 -0.9696002 0.2337419 0.07238912 -0.9629502 0.260816 0.0685721 -0.9312028 0.3584191 0.06631129 -0.9019904 0.4269433 0.06428658 -0.919641 0.3867803 0.06827521 -0.917984 0.3867631 0.0878629 -0.9678784 0.2337297 0.09263843 -0.9678788 0.2337281 0.09263861 -0.9926745 0.07463318 0.09501183 -0.9900416 0.07463735 0.1193605 -0.9900417 0.0746352 0.1193605 -1 0 -3.90859e-7 -1 0 -3.70572e-7 -1 0 -3.54762e-7 0.7605221 -0.04095977 -0.648019 0.8231305 -0.009996771 -0.5677644 0.8396123 -0.007448911 -0.5431351 0.6423661 -0.4327481 -0.6325305 0.7522016 -0.4298014 -0.4994634 0.7493363 -0.360409 -0.5555183 0.7481061 -0.3578675 -0.5588096 0.7726902 -0.3131111 -0.5521879 0.772366 -0.2913918 -0.564395 0.7810348 -0.2451406 -0.5743612 0.767242 -0.227222 -0.5997583 0.779847 -0.188441 -0.5969328 0.7787274 -0.1099144 -0.617659 0.7787272 -0.1099153 -0.617659 0.7793762 -0.01038736 -0.6264702 1.64013e-5 -7.06639e-6 -1 3.29895e-4 -1.18935e-4 -1 0.007368922 0.4455323 0.8952356 -0.06231558 0.7911817 0.6083982 -0.1167683 0.9915923 0.05576592 0.3402796 0.9263653 0.161423 0.9406309 0.2372433 0.2427533 0.9116842 0.2270521 0.3424608 0.9105259 0.2408133 0.3360831 0.8478449 0.2189192 0.4829425 0.8472204 0.23801 0.4749412 0.7952141 0.220686 0.5647409 0.7993014 0.2277021 0.5561198 0.7389296 0.2081559 0.640823 0.7393881 0.2323445 0.6319189 -0.1160768 0.9914597 0.05944681 -0.120316 0.989845 0.07570272 -0.1146326 0.9899825 0.08242672 -0.1241595 0.9867251 0.1046809 -0.1179494 0.9864073 0.1144053 -0.1232605 0.9847242 0.1229836 -0.1242582 0.9837205 0.129823 -0.1279186 0.9825205 0.135242 -0.1226402 0.9814274 0.1475118 -0.1293089 0.9794571 0.1547359 -0.1257398 0.9778246 0.1674772 -0.1265656 0.9776066 0.168127 -0.129957 0.9762401 0.1733974 -0.128807 0.9765465 0.1725274 -0.1275792 0.9746432 0.1838321 -0.126833 0.9748168 0.1834275 -0.1271393 0.9731227 0.19201 -0.1243184 0.9736824 0.1910178 -0.1266822 0.9729492 0.1931881 -0.1231887 0.9736145 0.192092 -0.1240777 0.9727344 0.1959402 -0.1199125 0.9733858 0.1952977 -0.1198252 0.9734375 0.1950937 -0.09080564 0.8923056 0.442205 -0.05140316 0.8285657 0.5575273 -0.01759344 0.8335638 0.5521432 -0.01419055 0.8314992 0.5553448 0.01734769 0.8378364 0.5456458 0.01946884 0.8377194 0.5457539 0.05272966 0.8439747 0.533785 0.05530714 0.8427718 0.5354222 0.1103742 0.855543 0.5058299 0.1120356 0.8549035 0.5065453 0.1435419 0.8636991 0.4831353 0.1440706 0.8637169 0.4829461 0.177215 0.8721235 0.4560654 0.1777508 0.8719499 0.4561886 0.2302565 0.887542 0.3990628 0.2301124 0.8875852 0.3990499 0.259638 0.8977882 0.3557589 0.2594612 0.8977957 0.3558689 0.2885081 0.9065538 0.3080962 0.2879319 0.9067171 0.3081548 0.324769 0.9194142 0.2218166 0.3241671 0.9195914 0.2219626 0.3403178 0.9263041 0.1616929 0.72103 0.6534675 0.2304257 -0.02584636 0.6093991 0.7924423 0.008000433 0.5509354 0.8345096 0.08995097 0.5633623 0.8212989 0.09883224 0.5538221 0.8267487 0.1562155 0.5654824 0.809831 0.1627826 0.5641425 0.8094721 0.2203646 0.5748988 0.7879917 0.2310432 0.5651397 0.7919825 0.3247084 0.5869805 0.7416323 0.3360648 0.5775681 0.7439595 0.3865451 0.5917114 0.7074323 0.3926489 0.5910984 0.7045775 0.4424846 0.6037943 0.6630533 0.4536437 0.595121 0.6633539 0.5336419 0.6190295 0.5762195 0.5436449 0.6113601 0.5750557 0.5870486 0.6262335 0.5130358 0.5914697 0.62512 0.5093021 0.6314513 0.6374194 0.4415494 0.6390373 0.6313932 0.4392881 0.6913375 0.6495349 0.316476 0.6965745 0.645058 0.3141403 0.7207626 0.6546617 0.2278584 0.9400781 0.2341852 0.2478113 0.64253 0.2032552 0.7388116 0.6245649 0.2280229 0.7469433 0.5805007 0.2124078 0.7860675 0.5599969 0.2066398 0.8023114 0.5679119 0.2137461 0.7948514 0.4892953 0.19264 0.8505763 0.4922441 0.2194635 0.8423369 0.3573105 0.1878969 0.9148901 0.3613764 0.213499 0.9076482 0.2704076 0.1957275 0.9426403 0.2788478 0.2026883 0.938702 0.1871582 0.18471 0.9648078 0.1922463 0.2066877 0.959334 0.0457049 0.1837085 0.9819177 0.05103218 0.2021679 0.9780205 0.9769374 0 0.213526 0.9769374 0 0.213526 0.9769377 0 0.2135248 0.976938 0 0.2135237 -0.01180899 0.1950703 0.9807182 -0.02544087 0.2587106 0.9656199 0.0427702 0.7064726 0.7064469 0.07387304 0.7900378 0.6085911 0.03682875 0.6083549 0.7928102 0.01566469 0.258762 0.9658142 0.06452876 0.4376008 0.896851 0.01180899 0.1950703 0.9807182 -0.04797798 0.7924594 0.6080349 -0.05598568 0.7060097 0.7059858 -0.03683024 0.6083555 0.7928096 -0.02676367 0.4420556 0.8965883 -0.1021548 0.975455 0.195069 0.1021541 0.9754551 0.1950691 0.2353377 0.8673297 0.4385834 0.0431472 0.9827281 0.1799557 0.0583781 0.9642787 0.258377 -0.04237282 0.9650596 0.2585816 -0.05918264 0.9775792 0.2020803 -0.2353377 0.8673297 0.4385834 0.09080564 0.8923056 0.4422051 0.02584636 0.6093989 0.7924424 -0.9413 0.2346105 0.2427183 -0.7216072 0.6536901 0.2279745 -0.9394112 0.2367951 0.2478601 -0.9139255 0.2278085 0.3359218 -0.9082697 0.2399831 0.3427163 -0.8519685 0.2203081 0.4749884 -0.8430216 0.2362856 0.4832017 -0.7951854 0.2207911 0.5647403 -0.7992395 0.2276741 0.5562202 -0.7456288 0.2103094 0.6323034 -0.7324863 0.230277 0.6406532 -0.6425315 0.2032549 0.7388104 -0.6245681 0.2280225 0.7469407 -0.5805007 0.2124078 0.7860675 -0.5692177 0.209158 0.795138 -0.5586258 0.2112825 0.8020581 -0.4986982 0.1951929 0.8445116 -0.4824811 0.217269 0.8485318 -0.3668839 0.1902168 0.9106118 -0.3514481 0.211629 0.9119744 -0.2798868 0.1976439 0.9394682 -0.2692807 0.2008829 0.9418779 -0.1959583 0.1864974 0.9627145 -0.1831797 0.2053821 0.9613863 -0.05326855 0.1849942 0.9812949 -0.04329782 0.2013356 0.978565 -0.007369399 0.4455323 0.8952356 -0.008000612 0.5509353 0.8345096 -0.09575718 0.5640971 0.8201373 -0.09328627 0.5525885 0.8282172 -0.1618942 0.5665369 0.8079767 -0.1571769 0.5629777 0.8113887 -0.226212 0.5758748 0.7856185 -0.2255626 0.5636762 0.7946009 -0.3301896 0.588067 0.7383442 -0.3309907 0.5760393 0.7474115 -0.3915005 0.5929921 0.7036248 -0.387766 0.5897448 0.7084058 -0.4471181 0.6048612 0.6589601 -0.4494023 0.5936788 0.6675201 -0.5372545 0.6199472 0.5718594 -0.5403634 0.610135 0.5794332 -0.5898768 0.6271336 0.5086738 -0.5887043 0.6241561 0.5136696 -0.6336576 0.6380136 0.437512 -0.6370651 0.630574 0.4433109 -0.6925127 0.6498427 0.3132582 -0.6955529 0.6445936 0.3173411 -0.7201551 0.6544705 0.230315 -0.3402108 0.9263474 0.1616705 0.06231772 0.7911816 0.6083981 0.05140465 0.8285657 0.5575273 0.01538312 0.8338558 0.5517681 0.01627475 0.8310464 0.5559649 -0.01914978 0.838165 0.5450806 -0.01770508 0.8373609 0.5463637 -0.05407953 0.8442074 0.5332818 -0.05407422 0.8424465 0.5360598 -0.1111271 0.8556912 0.5054142 -0.111369 0.8547063 0.507025 -0.1439387 0.8638058 0.4828264 -0.143667 0.8636074 0.4832621 -0.1774178 0.8721709 0.4558957 -0.1775773 0.871888 0.4563744 -0.2302114 0.887529 0.3991177 -0.2301506 0.8876015 0.3989917 -0.2595424 0.8977596 0.3559011 -0.2595508 0.8978277 0.3557229 -0.2883619 0.906513 0.308353 -0.2880489 0.9067693 0.3078917 -0.3246504 0.9193871 0.2221028 -0.3242525 0.9196319 0.2216699 -0.3403921 0.9263195 0.1614485 0.1174961 0.991313 0.0591036 0.1152077 0.9917539 0.05613648 0.1214432 0.9893648 0.08005499 0.1128334 0.9905297 0.07822918 0.1264203 0.9858616 0.1099767 0.1148483 0.9873405 0.1094015 0.1265668 0.9836207 0.1283405 0.1207211 0.9848396 0.1245688 0.1314981 0.9812984 0.1405767 0.1181659 0.9826954 0.1426417 0.1335325 0.9781546 0.1593198 0.1207073 0.9791381 0.1634581 0.1312034 0.97635 0.1718328 0.1251869 0.9774945 0.1698025 0.1330273 0.9754145 0.1756997 0.1227654 0.975744 0.181252 0.1303151 0.9740037 0.1852971 0.1232913 0.9738841 0.190654 0.12712 0.9731258 0.1920071 0.1238278 0.9734943 0.1922903 0.1249322 0.9732841 0.1926395 0.1222232 0.9730269 0.1956532 0.1198052 0.9733998 0.1952937 0.1199358 0.9734264 0.1950812 -0.9769382 0 0.2135222 -0.9769374 0 0.213526 -0.9769374 0 0.2135261 -0.9769374 0 0.2135259 0.7674964 0.5485235 0.3317702 0.7057688 0.5995849 0.377344 0.6888915 0.6041085 0.4006013 0.691147 0.5898222 0.4176428 0.7141098 0.6522988 0.2540737 0.7262234 0.6048418 0.3267506 0.6992506 0.6457791 0.3066235 0.713624 0.6039417 0.3549582 0.73498 0.5741951 0.3607 0.6969416 0.7046568 0.1331588 0.7256153 0.6682668 0.1640182 0.751123 0.6451192 0.1401268 0.7884801 0.5984138 0.1421274 0.8172741 0.5488143 0.1756871 0.8363626 0.5321611 0.1315384 0.723147 0.6633358 0.1924687 0.7266687 0.6502634 0.2216083 0.814717 0.5396959 0.2120485 0.8100123 0.5531713 0.1946319 0.7773546 0.5578867 0.2906583 0.7815545 0.5641286 0.2663301 0.7798509 0.5559374 0.2876917 0.7971615 0.5445854 0.2606922 0.7988919 0.5435981 0.2574352 0.8131492 0.5163079 0.2687277 0.8209257 0.502347 0.2715299 -0.9443817 0.3145556 0.09590691 -0.9643764 0.2449492 0.09989112 -0.9653163 0.2206196 0.1396118 -0.9960036 -0.0221911 0.08651351 -0.7711018 0.6111504 0.1785978 -0.7175416 0.6710302 0.1866885 -0.4277024 0.8820359 0.1976953 -0.3547803 0.913554 0.1988722 -0.001937329 0.9839029 0.178694 0.07587629 0.9819414 0.1733035 0.4243564 0.8968014 0.1251757 0.4923219 0.8628118 0.1147832 -0.9542683 0.2120302 0.2107493 -0.9557026 0.2065333 0.2097058 -0.7712345 0.5831164 0.2552896 -0.7610704 0.5957676 0.2565791 -0.4543406 0.8533684 0.2556115 -0.4203517 0.8709951 0.2543071 -0.05852776 0.9756148 0.2115428 0.001309037 0.9791165 0.2032958 0.3476593 0.9284744 0.1306461 0.4227944 0.8991107 0.1133362 -0.05943709 0.9764919 0.2071976 -0.09325581 0.9727856 0.2121124 -0.4517552 0.8509746 0.2678798 -0.9482622 0.1997504 0.2467762 -0.9470253 0.2044169 0.2477034 -0.7748494 0.5661978 0.2811201 0.2978979 0.9492874 0.1005513 0.3021547 0.9456638 0.1200944 0.3433171 0.9326721 0.1107084 -0.17878 0.9622306 0.2053045 -0.09742659 0.9763531 0.192984 0.01595497 0.9857123 0.1676809 0.2572153 0.9601585 0.1092517 -0.4106948 0.8789281 0.2425185 -0.4767088 0.8419129 0.252847 -0.4732037 0.8389104 0.2689007 -0.7658399 0.5777854 0.2822291 -0.9503572 0.1959946 0.2416763 -0.9492109 0.2005219 0.2424659 -0.8641238 0.4289889 0.2631705 -0.777226 0.5682184 0.2702734 -0.7559252 0.5968165 0.2690491 -0.5790572 0.7726399 0.2602314 -0.7020828 -0.5136143 -0.4932344 -0.7034005 -0.4903125 -0.5146082 -0.7194683 -0.4432998 -0.5346501 -0.7109566 -0.5021454 -0.492332 -0.7072017 -0.5099306 -0.4897311 -0.7069118 -0.5237232 -0.4753839 -0.7072376 -0.5214021 -0.4774462 -0.706619 -0.5413864 -0.4556208 -0.6995221 -0.5590392 -0.4451339 -0.7004296 -0.5578507 -0.4451978 -0.7026702 -0.5526242 -0.4481754 0.9162632 0.4005769 0 0.9477632 0.318579 0.01589578 0.8949241 0.4462184 0 0.9323298 0.3614571 0.01048588 0.9362075 0.3514474 -5.72628e-4 0.9784151 0.2066493 3.12098e-4 0.9787063 0.2052658 3.40639e-5 0.9944761 0.1049638 -7.644e-5 0.9959058 0.09036189 -0.002517282 0.9995361 0.03044378 8.67638e-4 0.9998552 0.0170201 -1.05332e-6 0 -0.9999994 0.00110495 0 -1 2.22648e-6 0 -1 4.46387e-7 0 -1 -3.78918e-6 0 -1 5.93097e-6 -0.6337845 -0.5335752 -0.5600133 -0.6823045 -0.5719165 -0.4553813 -0.6340495 -0.5976277 -0.4907367 -0.6106411 -0.6224592 -0.4895529 -0.4649944 -0.629719 -0.6222815 -0.4585403 -0.7284397 -0.5090348 -0.3470222 -0.7973819 -0.4937184 -0.2902706 -0.7898681 -0.5402327 -0.2512999 -0.8140689 -0.523584 -0.03481918 -0.8678679 -0.4955735 -0.2900209 -0.5876655 -0.7553393 -0.2151862 -0.5787602 -0.7865949 -0.07829332 -0.6056576 -0.7918643 -0.6343489 -0.4934186 -0.5950964 -0.6502348 -0.5424486 -0.531925 -0.6139138 -0.4958572 -0.614195 -0.5706683 -0.4847207 -0.6628602 -0.556113 -0.4884296 -0.6724395 -0.4993169 -0.5347941 -0.681673 -0.4697593 -0.5463799 -0.693394 -0.4711113 -0.5452353 -0.6933778 -0.3908238 -0.5561788 -0.7334317 -0.3253592 -0.5712875 -0.7535065 -0.1462421 -0.8222272 -0.5500506 -0.1114265 -0.8651946 -0.4888992 -0.09801256 -0.8294905 -0.5498538 -0.0977894 -0.7854746 -0.6111195 -0.1477541 -0.6696962 -0.7277883 -0.09797215 -0.7221801 -0.6847316 -0.09778827 -0.7854756 -0.6111183 -0.2896623 -0.7554216 -0.5877363 -0.2896598 -0.7554216 -0.5877376 -0.4705345 -0.6964264 -0.5418373 -0.4705355 -0.696426 -0.5418368 -0.5553972 -0.6563404 -0.5106381 -0.572283 -0.7227761 -0.3874104 -0.6343519 -0.570127 -0.5220662 -0.6242407 -0.5456849 -0.559063 -0.4705325 -0.6163393 -0.6314468 -0.4705368 -0.6163376 -0.6314453 -0.2896625 -0.6685503 -0.6849351 -0.2896592 -0.6685485 -0.6849383 -0.09779179 -0.6951465 -0.7121855 -0.09782159 -0.5959571 -0.7970359 -0.005904316 -0.5960566 -0.8029206 0.2729454 0.9616497 0.02703166 0.4292862 0.9030141 0.01670175 0.570864 0.8180862 0.06963682 0.8804655 0.4720092 0.04458725 0.8785521 0.4755866 0.04431122 0.8653226 0.4993116 0.04364407 0.8339773 0.5498545 0.04628294 0.8422429 0.5373732 0.04309254 0.8469637 0.5249904 0.08389133 0.65077 0.7557163 0.07342553 0.8403582 0.5322573 0.1024715 0.8447142 0.524995 0.104107 0.7950766 0.5988143 0.0963065 0.768568 0.6334398 0.08976209 0.7582874 0.6456202 0.09041595 0.6773028 0.7307627 0.085128 0.7061704 0.7049797 0.06577986 0.4242894 0.9046592 0.03962618 0.4273115 0.9028412 0.04777717 0.5134637 0.8560031 0.06011551 0.5082255 0.8604001 0.03766387 0.5256145 0.849073 0.05295681 0.3624431 0.9314011 0.03357064 0.31862 0.9476326 0.02176719 0.3464007 0.9376398 0.028952 0.0579164 0.9983062 0.005530178 0.03989183 0.9992035 0.001055657 0.114702 0.9933292 0.01186412 0.1997737 0.9797075 0.01624017 0.1665809 0.9859994 0.007487654 0.2078703 0.9780023 0.01736164 0.05802488 0.998306 0.004276096 0.05798894 0.9983054 0.004864394 0.03454434 0.9994017 0.001761853 0.3051403 0.9521692 0.01622682 0.2569857 0.9663332 0.01259493 0.1999099 0.9797052 0.01462125 0.1746492 0.984579 0.01009672 0.1022291 0.9947499 0.004686057 0.5070192 0.8614175 0.02985817 0.4645956 0.8851688 0.02504843 0.3636312 0.9313904 0.01686614 0.4157084 0.9088179 0.03516733 0.347536 0.9374451 0.02038627 0.5728616 0.8183127 0.04684281 0.5164406 0.8559847 0.02406877 0.6183463 0.7851749 0.03388738 0.653711 0.7557162 0.03943276 0.6582369 0.751818 0.03865283 0.805284 0.5913127 0.04321175 0.7772055 0.6276831 0.04433673 0.772462 0.6334438 0.04529291 0.7292411 0.6832048 0.03793042 0.6947616 0.7182672 0.03739923 0.4057672 0.9130925 0.04019093 0.5144743 0.8559904 0.05095869 0.5144751 0.8559899 0.05095857 0.6517389 0.7556912 0.06455463 0.6517393 0.7556908 0.06455463 0.7700452 0.6334137 0.07627266 0.7700443 0.6334148 0.07627254 0.8469644 0.5249893 0.08389157 0.8488072 0.5249896 0.06254965 0.0580247 0.998306 0.004275798 0.1999033 0.979705 0.01473098 0.1999034 0.9797049 0.01473098 0.3630287 0.9313939 0.02675205 0.3630287 0.9313939 0.02675187 0.5155951 0.8559896 0.0379945 0.515594 0.8559903 0.03799474 0.6531575 0.7556908 0.04813182 0.6531584 0.75569 0.04813194 0.7717202 0.6334146 0.05686897 0.771719 0.6334158 0.05686885 0.8488072 0.5249894 0.06254982 0.8496412 0.5250189 0.04965066 0 -1 -8.87453e-6 0 -1 1.82106e-6 0 -1 1.67971e-5 0 -1 1.50593e-5 0 -1 4.33881e-6 0.0137034 -0.9999061 0 -0.4305806 -0.9024755 -0.01176351 -0.1740507 -0.9844008 0.02571904 -0.2686166 -0.9631013 -0.01676994 -0.1460441 -0.9892781 0 0.1467983 -0.9890767 -0.01332759 0.07300692 -0.9973302 0.001621127 0.3322988 -0.9431731 -0.001516878 0.325685 -0.9454784 0 0.5364957 -0.8439032 0 0.5598568 -0.828562 -0.006751954 0.7379249 -0.6748185 0.009319663 0 -0.9948198 -0.1016542 0 -0.991662 -0.1288672 -1.20019e-6 -0.9916607 -0.1288763 9.27332e-7 -0.9948188 -0.101665 -0.5521038 -0.8337692 0.003226101 -0.748266 -0.6633925 -0.002921938 -0.0137034 -0.9999061 0 -0.1467985 -0.9890766 -0.01332765 -0.07300686 -0.9973301 0.001621186 -0.3322988 -0.9431729 -0.001516878 -0.325685 -0.9454784 0 -0.5346815 -0.8450537 0 -0.6230529 -0.7817618 -0.02556705 0.1304654 -0.9895463 -0.06145709 0.231546 -0.972824 0 0.3255945 -0.9445339 -0.04294282 -7.54785e-6 -0.8603576 0.5096911 0 0.8603631 -0.5096817 0 0.8603658 -0.5096772 0 0.8603634 -0.5096811 0 0.8603656 -0.5096775 0 0.8603678 -0.5096738 -4.47269e-6 0.8603644 -0.5096794 1.83728e-6 0.860367 -0.5096751 1.2374e-6 0.8603678 -0.5096737 -3.25544e-7 0.8603594 -0.5096879 -4.10259e-7 0.8603646 -0.5096791 -5.8008e-7 0.8603666 -0.5096758 2.9004e-7 0.8603662 -0.5096765 4.10259e-7 0.8603646 -0.5096791 3.25545e-7 0.8603616 -0.509684 -1.24873e-6 0.8603687 -0.5096724 0 -1 -4.77841e-7 0 -1 7.3429e-6 0.7026683 -0.5526267 -0.4481753 0.7004296 -0.5578507 -0.4451978 0.6995216 -0.55904 -0.4451335 0.7194683 -0.4432998 -0.5346501 0.7002944 -0.498623 -0.5108452 0.7084594 -0.5003633 -0.4977168 0.7052609 -0.5138938 -0.4883854 0.7059561 -0.5124804 -0.4888659 0.7071968 -0.5237616 -0.4749174 0.7066189 -0.5413866 -0.4556208 0.09794312 -0.6738736 -0.7323261 0.03481918 -0.8678679 -0.4955735 0.1462421 -0.8222272 -0.5500506 0.1114267 -0.8651948 -0.4888988 0.2512999 -0.8140689 -0.523584 0.316832 -0.7720245 -0.5509952 0.2897306 -0.8263013 -0.4829931 0.4585406 -0.7284402 -0.5090339 0.4649944 -0.629719 -0.6222815 0.572283 -0.7227761 -0.3874104 0.6334992 -0.5404548 -0.5537034 0.6337665 -0.6051296 -0.481828 0.6739417 -0.5516318 -0.4914316 0.5891906 -0.4771728 -0.6520434 0.5560656 -0.5114745 -0.6551221 0.5464859 -0.5144965 -0.6607924 0.4697591 -0.5463806 -0.6933937 0.4711118 -0.5452348 -0.6933778 0.3908238 -0.5561783 -0.7334321 0.3253594 -0.5712872 -0.7535067 0.2900207 -0.5876653 -0.7553393 0.2151863 -0.5787599 -0.7865951 0.07829332 -0.6056578 -0.7918641 0.09782218 -0.5959575 -0.7970355 0.005904316 -0.5960545 -0.8029223 0.09778654 -0.7854753 -0.611119 0.09801256 -0.8294905 -0.5498538 0.09779077 -0.7854748 -0.6111189 0.2896608 -0.755422 -0.5877366 0.2896621 -0.7554211 -0.5877372 0.4705349 -0.6964265 -0.5418369 0.470534 -0.6964269 -0.5418371 0.5553978 -0.6563404 -0.5106376 0.610641 -0.6224591 -0.4895531 0.09797215 -0.7221801 -0.6847317 0.1264386 -0.6928883 -0.7098727 0.2896621 -0.6685487 -0.6849369 0.2896595 -0.6685501 -0.6849366 0.4705342 -0.6163392 -0.6314457 0.4705352 -0.6163377 -0.6314464 0.6335001 -0.5404541 -0.553703 0.6343656 -0.5063659 -0.584101 0.6467676 -0.4868063 -0.5871212 0.04735082 -0.8674175 -0.495323 -0.03760099 -0.8843355 -0.4653354 0.02645248 -0.8975953 -0.4400262 -0.04552352 -0.864502 -0.5005638 -0.02338647 -0.9008133 -0.4335764 0.007491469 -0.9014214 -0.4328778 0.01827442 -0.9029386 -0.429381 0 -0.9011076 -0.4335955 0 -0.9011084 -0.4335941 0.0258516 -0.9052363 -0.4241216 -0.002121686 -0.9023807 -0.4309347 -0.0258516 -0.9052363 -0.4241216 0.0021227 -0.9023809 -0.4309343 -0.007155001 -0.902934 -0.4297197 0.02065163 -0.8969064 -0.441738 -0.01827454 -0.902939 -0.4293803 0.03760081 -0.8843356 -0.4653354 -0.02645248 -0.8975955 -0.4400257 -0.01961213 -0.8948287 -0.4459788 0.02248829 -0.8550466 -0.5180633 -0.02215218 -0.8843044 -0.4663853 0 -0.6267048 -0.7792568 -0.2324283 -0.5797482 -0.7809413 0 -0.8235486 -0.5672459 0 -0.6771295 -0.7358639 0 -0.7256712 -0.6880418 -0.08676159 -0.7565308 -0.6481772 0.05254465 -0.7881665 -0.6132151 -0.002024412 -0.820284 -0.5719529 0 -0.8335066 -0.5525096 0 -0.8683935 -0.4958759 -0.1012864 -0.755488 -0.6472858 0.1661816 -0.7782828 -0.6055244 0 -0.8191789 -0.5735381 6.76883e-4 -0.820824 -0.5711809 -1.66439e-4 -0.8334991 -0.5525211 1.65313e-5 -0.8354543 -0.54956 -2.2791e-4 -0.870397 -0.4923504 0.02858597 -0.888415 -0.4581503 0 -0.5960737 -0.8029299 0.1495363 -0.6196582 -0.7704951 0.07593518 0 0.9971128 0.9455407 0.01500976 0.325158 0.9646009 -0.007509708 0.2636072 0.972441 0 0.233149 0.6559192 1.7745e-5 0.7548313 0.6814934 0.01235687 0.73172 0.7370775 -0.01221543 0.6756978 0.7863554 0.01518547 0.6175878 0.7833392 0.01293063 0.6214601 0.824023 -0.005569458 0.5665291 0.8401718 2.37969e-5 0.5423204 0.8628403 -4.12542e-5 0.5054767 0.8866852 0.01214247 0.4622143 0.9088943 -0.01181429 0.4168593 0.9419292 0.009696781 0.3356717 0.6247581 -1.03515e-5 0.7808184 0.6125196 -3.3787e-4 0.7904554 0.5996063 -0.002792656 0.8002904 0.5368003 0.009746611 0.8436531 0.07253801 0.002910554 0.9973615 0.2161424 -0.002629697 0.9763583 0.2250949 0.004531562 0.9743263 0.3096327 -0.001151025 0.9508556 0.3153588 -6.7615e-5 0.9489725 0.3754525 1.42096e-4 0.9268417 0.4012231 0.01316243 0.9158858 0.4815652 -0.01115781 0.8763392 0.5530624 0.02076441 0.8328812 0.404183 0.8736636 0.2708287 0.9249196 0.2352848 0.298605 0.6802062 0.664638 0.3091534 0.1746379 0.9588196 0.2239792 -0.2092374 0.9705847 0.1191012 0.9217303 0.248166 0.2980386 0.8993458 0.2340741 0.3693053 0.8984863 0.2397293 0.3677666 0.8637058 0.2203761 0.4532623 0.8580402 0.2415928 0.4532109 0.8141095 0.2207068 0.5371353 0.8272256 0.06613147 0.5579646 0.7701878 0.2270226 0.5960466 0.7383934 0.2151373 0.6391331 0.7388385 0.2183497 0.6375274 0.6896564 0.2007421 0.6957562 0.6846514 0.2213877 0.694435 0.6123688 0.2018291 0.7643753 0.6268857 0.01784324 0.778907 0.5576071 0.2073503 0.8037912 0.5193216 0.2003211 0.8307687 0.5195833 0.2038632 0.8297427 0.4527211 0.1927037 0.8705797 0.4517217 0.2018779 0.8690184 0.358846 0.1945009 0.9129069 0.3517502 0.02676415 0.9357112 0.3011273 0.1949716 0.933439 0.6782398 0.6669209 0.308557 0.6581878 0.6549054 0.3713325 0.6575582 0.6558428 0.3707932 0.6287015 0.6386987 0.4436199 0.6257844 0.6422838 0.4425668 0.5706251 0.6165493 0.5424519 0.568074 0.6200119 0.5411813 0.5325644 0.6074245 0.5894156 0.5325359 0.6077598 0.5890957 0.497475 0.5945881 0.6316515 0.4958089 0.5972742 0.6304262 0.4286833 0.5791112 0.6934413 0.4281479 0.580253 0.6928173 0.3841236 0.5725681 0.724303 0.3841058 0.5727538 0.7241656 0.3420003 0.5654824 0.7505102 0.3424188 0.5641663 0.7513094 0.272952 0.558515 0.7832998 0.2735078 0.5552032 0.7854571 0.2780008 0.9307875 0.2373824 0.2620663 0.9216443 0.2861698 0.2643555 0.9204072 0.2880396 0.2477848 0.9103456 0.3314722 0.2583706 0.9054617 0.3367249 0.2278596 0.8913258 0.3919417 0.2387005 0.8852541 0.3991835 0.2208495 0.8789147 0.4227701 0.2214012 0.8778837 0.4246195 0.2067037 0.8724133 0.4429095 0.2164521 0.8654198 0.4518817 0.1905663 0.8584608 0.4761614 0.19827 0.8512754 0.4858179 0.1840543 0.8487457 0.4957366 0.1848285 0.8468115 0.4987474 0.1742401 0.8450419 0.5055141 0.1788043 0.8384567 0.5148004 0.1634324 0.837213 0.5218852 0.1658158 0.831429 0.5303122 -0.1934401 0.972901 0.1266674 -0.1957384 0.971512 0.1336075 -0.1901015 0.9718999 0.1388244 -0.1912887 0.9711962 0.14208 -0.1656873 0.9734153 0.1581466 -0.1646942 0.9738744 0.1563477 -0.1389569 0.9742563 0.1775265 -0.1346881 0.9758592 0.1719243 -0.1333192 0.9751418 0.1769871 -0.125002 0.9780837 0.166514 -0.1028613 0.9761933 0.1909613 -0.08242982 0.9816744 0.1718165 -0.06532585 0.9782754 0.1967486 -0.04687148 0.9818257 0.1839065 -0.04513603 0.9806136 0.1906826 -0.0225805 0.9841045 0.1761493 -0.01315093 0.9802915 0.1971187 0.02818429 0.9836022 0.1781358 0.03258103 0.9805021 0.1937889 0.07142746 0.1751652 0.9819447 0.2120057 0.1945182 0.9577142 0.2110583 0.1751917 0.9616457 0.1838772 0.5381683 0.8225353 0.1798565 0.5545653 0.812471 0.1167433 0.8415965 0.5273391 0.1221327 0.8308297 0.5429602 0.04226708 0.9806935 0.1909288 0.03639513 0.9843561 0.1723906 0.01279073 0.984342 0.1758049 0.01278871 0.984343 0.175799 0.0714361 0.1753211 0.9819162 0.06754106 0.3655342 0.9283443 0.05941516 0.5381705 0.8407393 0.06037735 0.5544133 0.8300486 0.03917962 0.8415923 0.5386903 0.0384835 0.8308421 0.555176 0.02647483 0.9309685 0.3641384 0 0 1 -0.8523606 0.4204131 0.3110214 -0.5703482 0.7658583 0.2969245 -0.1746333 0.9588209 0.2239773 0.2566197 0.9606163 0.1065953 0.01200556 0.988673 0.1496051 -0.4087927 0.8775054 0.2507444 -0.7489716 0.5916802 0.2982551 -0.8646364 0.2208812 0.4512376 -0.8977445 0.2392899 0.3698585 -0.9000835 0.2345046 0.3672291 -0.9212107 0.2478051 0.2999393 -0.9400281 0.188931 0.2839937 -0.6909613 0.2012084 0.6943254 -0.7375081 0.2178545 0.6392349 -0.7397134 0.2156399 0.637435 -0.7701869 0.2270221 0.596048 -0.8272256 0.06613147 0.5579646 -0.8141095 0.2207068 0.5371353 -0.8570704 0.2410918 0.4553079 0.1926478 0.9733712 0.1242392 0.1966328 0.9709635 0.1362549 0.1890878 0.9724694 0.1361955 0.1923347 0.9705772 0.1448702 0.1642006 0.9740993 0.1554632 0.1661916 0.9731822 0.1590504 0.137009 0.9749926 0.1749795 0.1365759 0.975158 0.1743959 0.1313772 0.9758466 0.1745382 0.1268607 0.9774492 0.168818 0.1006073 0.976835 0.1888692 0.08436959 0.9811916 0.1736233 0.0630536 0.9787365 0.19519 0.04881584 0.9814665 0.185312 0.04312002 0.9809621 0.1893516 0.02432322 0.9838671 0.1772395 0.01120907 0.9804856 0.1962711 -0.2754201 0.9294284 0.2455742 -0.2616775 0.9214063 0.2872897 -0.2647827 0.9206341 0.2869201 -0.2473274 0.9100419 0.3326452 -0.2590007 0.9057116 0.3355672 -0.2271875 0.8909811 0.3931137 -0.2395526 0.885537 0.3980437 -0.2200781 0.8786141 0.423796 -0.222193 0.8781775 0.4235972 -0.2058702 0.8720738 0.4439648 -0.2174617 0.8656793 0.4508991 -0.1896752 0.858193 0.4769992 -0.1993137 0.8514578 0.4850709 -0.1830169 0.8485396 0.496473 -0.1858983 0.8469896 0.4980466 -0.1733115 0.8448776 0.5061078 -0.1798327 0.8385345 0.5143152 -0.6781259 0.6668342 0.3089944 -0.6583435 0.6550023 0.3708852 -0.6574025 0.655748 0.3712365 -0.6288905 0.6388199 0.443177 -0.6255628 0.6421867 0.4430209 -0.5708366 0.616666 0.5420967 -0.5678201 0.6199258 0.5415463 -0.5326967 0.6075069 0.5892111 -0.5323976 0.6076751 0.5893079 -0.497683 0.5946587 0.6314211 -0.4955685 0.5972235 0.6306632 -0.4288002 0.5791493 0.6933373 -0.4280191 0.5802261 0.6929194 -0.3841924 0.5725679 0.7242667 -0.384024 0.5727592 0.7242048 -0.3418539 0.5654554 0.7505971 -0.3425762 0.5641779 0.751229 -0.3588527 0.1944992 0.9129046 -0.4509664 0.2018247 0.8694229 -0.4534443 0.1928286 0.8701756 -0.5185062 0.2036882 0.8304592 -0.5203849 0.2005174 0.8300558 -0.5576114 0.2073541 0.8037872 -0.6268841 0.0178433 0.7789083 -0.6123688 0.2018291 0.7643753 -0.6832613 0.2210071 0.6959238 -0.3011178 0.1949722 0.9334421 -0.3517538 0.02676308 0.93571 -0.2738556 0.555182 0.7853509 -0.2726223 0.5584952 0.7834285 -0.1667241 0.831411 0.5300557 -0.1625842 0.8371484 0.5222537 -0.03400522 0.9805318 0.1933941 -0.02686035 0.983533 0.1787216 -0.972441 0 0.233149 -0.9646009 -0.007509708 0.2636072 -0.9455406 0.01500976 0.3251582 -0.9419292 0.009696781 0.3356717 -0.8885558 -0.02308493 0.4581875 -0.9054573 0.0228542 0.4238215 -0.8628453 0 0.5054682 -0.8400856 0 0.542454 -0.824023 -0.005569458 0.5665291 -0.7833392 0.01293063 0.6214601 -0.5996095 -0.002792835 0.800288 -0.5368003 0.009746611 0.8436531 -0.7863459 0.01518571 0.6176 -0.7370768 -0.01221507 0.6756987 -0.6814934 0.01235711 0.73172 -0.6559192 1.7745e-5 0.7548313 -0.6247581 -1.03515e-5 0.7808184 -0.6125169 -3.37871e-4 0.7904573 -0.07253372 0 0.9973661 -0.07561767 0.002793192 0.997133 -0.2161424 -0.002629697 0.9763583 -0.2250975 0.004531562 0.9743258 -0.3096345 -0.001151025 0.950855 -0.3153548 -6.76879e-5 0.9489738 -0.3754504 1.42096e-4 0.9268426 -0.4012202 0.01316255 0.9158872 -0.4815666 -0.01115804 0.8763385 -0.5530628 0.02076351 0.8328809 0 0.984421 0.1758278 0 0.9844281 0.1757882 0 0.9313032 0.3642451 0 0.555442 0.8315554 0 0.8314511 0.555598 0 0.9314272 0.3639279 0 0.1757672 0.9844319 0 0.3664385 0.9304423 0 0.3663138 0.9304914 -0.01279342 0.9843416 0.1758067 -0.04226708 0.9806933 0.1909297 -0.03639507 0.9843538 0.1724038 -0.1184486 0.841535 0.5270568 -0.1203047 0.8307704 0.5434586 -0.1821611 0.5382214 0.8228822 -0.1817218 0.5546348 0.8120083 -0.2120071 0.1945192 0.9577136 -0.2110539 0.1751916 0.9616466 -0.07144576 0.1751698 0.9819425 -0.07141774 0.1753166 0.9819183 -0.01278603 0.9843434 0.175797 -0.02647483 0.9309685 0.3641384 -0.03746348 0.8415284 0.5389123 -0.04038095 0.830786 0.5551252 -0.061136 0.538223 0.8405823 -0.0584793 0.554482 0.8301386 -0.06754106 0.3655342 0.9283443 -0.3026579 0.9452119 0.1223632 -0.3428111 0.9331185 0.1084924 0.09283232 0.9724402 0.2138747 0.05983847 0.9768318 0.2054728 0.4729177 0.8386667 0.2701611 0.452018 0.851223 0.2666443 0.7746655 0.5660681 0.2818872 0.7660034 0.577932 0.2814847 0.9482082 0.1996935 0.2470299 0.9470766 0.2044782 0.2474564 -0.2102587 0.9697716 0.1238329 -0.2966237 0.950272 0.09485578 0.1778402 0.9614992 0.2095052 0.09810483 0.9768908 0.1898941 0.4106948 0.8789281 0.2425185 0.4767024 0.8419163 0.2528476 0.691088 0.6729011 0.263821 0.777226 0.5682184 0.2702734 0.9382197 0.2444204 0.2449543 0.9492617 0.2005652 0.242231 0.9653185 0.2206106 0.1396116 0.9563845 0.2774872 0.09126669 -0.4246457 0.8963725 0.1272501 -0.483866 0.8676137 0.1145439 0.001710474 0.98358 0.1804648 -0.04664969 0.9835307 0.1746177 0.4275389 0.8817791 0.199189 0.4000133 0.8948236 0.1981928 0.770996 0.6109243 0.1798242 0.7631774 0.6204672 0.1805015 0.9944547 -0.07437652 0.07435053 0.9767773 0.1930355 0.09297126 -0.3481251 0.9279885 0.1328389 -0.4225119 0.899509 0.1112083 0.05814576 0.9752864 0.2131562 -0.001075148 0.9794386 0.2017403 0.4540953 0.853191 0.2566373 0.4205225 0.8711979 0.2533277 0.7711555 0.5830259 0.2557346 0.7611283 0.5958744 0.2561597 0.9543013 0.2120343 0.2105959 0.9556718 0.2065281 0.2098514 -0.7231468 0.663336 0.1924686 -0.6947666 0.706705 0.133669 -0.7186266 0.5860514 0.3743256 -0.7081763 0.6211813 0.3355894 -0.7226586 0.6218224 0.3018304 -0.7228823 0.6089051 0.3266128 -0.7057688 0.5995849 0.377344 -0.6888908 0.6041092 0.4006016 -0.6911033 0.589853 0.4176716 -0.7815494 0.5641327 0.2663362 -0.7773349 0.5579091 0.2906679 -0.7674964 0.5485235 0.3317702 -0.7841507 0.5839712 0.2099654 -0.7828058 0.5522043 0.2868546 -0.8101084 0.5368363 0.2356507 -0.8056932 0.539003 0.2456308 -0.8216553 0.5118655 0.2507519 -0.7256436 0.668323 0.1636636 -0.7492188 0.6473507 0.1400291 -0.786589 0.6009165 0.1420467 -0.7141098 0.6522988 0.2540737 -0.7266687 0.6502634 0.2216083 -0.8054816 0.552882 0.2133567 -0.8181968 0.5481456 0.1734657 -0.8303255 0.5343144 0.1583282 0 1 -1.6006e-6 0 1 2.0933e-6 0 1 -5.48282e-6 0 1 4.13462e-6 0 1 -1.70763e-6 0 1 1.41306e-6 0 1 1.22932e-6 1.67557e-6 1 5.21176e-7 0 1 -3.86741e-6 0 1 2.79278e-6 0 1 -3.70359e-6 0 1 1.71477e-6 0 1 5.16036e-6 0 1 -3.61821e-6 0 1 3.11981e-6 0 1 -2.21767e-6 0 1 1.63915e-6 0 1 2.0508e-6 0 1 -1.81538e-6 0 1 9.55872e-7 0 1 1.12669e-6 2.54946e-6 1 2.51624e-7 0 1 3.10222e-7 -1.125e-6 1 0 0 1 -1.50423e-6 0 1 -1.00101e-6 0 1 -5.00238e-7 -4.06745e-6 1 -3.84594e-6 9.54218e-7 1 9.02253e-7 0 1 8.33792e-7 0 1 -4.07485e-7 0 1 -1.6131e-7 0 1 1.64285e-7 0 1 0 0 1 -1.61272e-6 0 1 2.01878e-7 0 1 -6.8523e-7 -1.65064e-7 1 6.85787e-7 -2.12122e-6 1 0 0 1 -4.25055e-7 0 1 -2.55289e-7 0 1 7.35185e-7 0 1 -7.28317e-7 0 1 2.89717e-7 0 1 -7.15762e-7 0 1 4.29115e-7 0 1 -1.46546e-6 0 1 1.14033e-5 0 1 -4.68188e-6 0 1 -4.82407e-7 0 1 7.71143e-7 0 1 1.13977e-6 0 1 -2.67128e-6 0 1 9.92827e-7 0 1 2.77982e-6 -0.9038575 0.4278337 0 -0.8937809 0.4484874 0.003849208 -0.9982347 0.05939328 0 -0.9972051 0.07463699 0.003377974 -0.986892 0.1613751 -0.001571059 -0.9842121 0.1769938 -9.46935e-6 -0.9652218 0.2614328 -6.59241e-6 -0.9748697 0.2226231 0.008262574 -0.9331781 0.3591775 -0.01305425 -0.9561172 0.2928695 0.008215188 -0.9175013 0.3977242 -0.002645969 -0.9202873 0.3912433 -3.83361e-5 -0.4242894 0.9046592 0.03962618 -0.8788016 0.4752626 0.04281878 -0.880176 0.4727234 0.04269647 -0.8655689 0.4990268 0.04198789 -0.8338876 0.5499283 0.04701703 -0.6947612 0.7182675 0.03739899 -0.7292411 0.6832048 0.03793042 -0.772462 0.6334439 0.04529297 -0.7772055 0.6276831 0.04433673 -0.8052833 0.5913135 0.04321169 -0.4645944 0.8851693 0.02504807 -0.5070192 0.8614175 0.02985817 -0.515963 0.8560082 0.03212755 -0.5745092 0.8179622 0.02961444 -0.6538325 0.7557141 0.03740775 -0.6181278 0.7847667 0.04537767 -0.6582375 0.7518174 0.03865289 -0.4208543 0.9068738 0.02148455 -0.3632152 0.9314024 0.02375853 -0.3475356 0.9374452 0.02038627 -0.1022292 0.9947499 0.004686057 -0.1746492 0.984579 0.01009672 -0.1999099 0.9797052 0.01462119 -0.2569857 0.9663332 0.01259493 -0.3051404 0.9521692 0.01622653 -0.05802464 0.998306 0.004276096 -0.05807608 0.9983054 0.003680169 -0.03890365 0.9992361 0.003714799 -0.2729453 0.9616498 0.02703189 -0.2078703 0.9780023 0.01736164 -0.1998426 0.9797065 0.01543736 -0.1622059 0.9866531 0.01431292 -0.114702 0.9933292 0.01186412 -0.3096292 0.9503929 0.02971887 -0.3624811 0.9314021 0.03313302 -0.346401 0.9376397 0.02895218 -0.5152379 0.8559273 0.0437982 -0.4613527 0.885654 0.05263751 -0.4273115 0.9028412 0.04777717 -0.7016034 0.7073017 0.08646982 -0.6605991 0.7467047 0.07772445 -0.6507702 0.7557162 0.07342547 -0.570864 0.8180862 0.06963682 -0.5256145 0.849073 0.05295681 -0.7563672 0.6478523 0.09053248 -0.7685684 0.6334396 0.08976089 -0.7932371 0.6013224 0.09584534 -0.8403236 0.5403688 0.04310387 -0.8497358 0.5250178 0.04801535 -0.8488072 0.5249896 0.06254971 -0.8386938 0.534915 0.1022683 -0.8446558 0.5249929 0.104591 -0.8469632 0.5249911 0.08389145 -0.7700446 0.6334144 0.07627254 -0.7700449 0.6334142 0.07627266 -0.6517388 0.7556914 0.06455445 -0.6517394 0.7556907 0.06455463 -0.5144743 0.8559904 0.05095845 -0.5144751 0.85599 0.05095869 -0.4237647 0.9047992 0.04197406 -0.3928522 0.9188272 0.03773182 -0.03454434 0.9994017 0.001761853 -0.05798894 0.9983054 0.004864394 -0.05802494 0.998306 0.004275798 -0.1999031 0.979705 0.01473098 -0.1999036 0.9797049 0.01473098 -0.3630287 0.9313939 0.02675187 -0.3630288 0.9313939 0.02675199 -0.5155945 0.85599 0.03799462 -0.5155946 0.8559899 0.03799474 -0.6531578 0.7556907 0.04813182 -0.6531577 0.7556908 0.04813194 -0.7717192 0.6334158 0.05686891 -0.7717204 0.6334143 0.05686897 -0.8488072 0.5249894 0.06254971 -0.8469648 0.5249885 0.08389139 1 -5.73524e-7 0 -1 -1.14705e-6 0 0 -1 -3.30924e-7 -1.65211e-6 0.5096777 0.8603655 0 0.5096803 0.860364 0 0.5096775 0.8603657 -1.83821e-6 0.5096817 0.8603631 0 0.5096773 0.8603657 6.12431e-6 0.5096725 0.8603685 -4.3214e-6 0.5096836 0.8603621 1.83821e-6 0.5096817 0.8603631 0 0.5096833 0.8603621 -6.12431e-6 0.5096725 0.8603685 -4.42315e-7 0.5096759 0.8603666 0 0.5096783 0.860365 0 0.5096787 0.8603649 1.65211e-6 0.5096778 0.8603655 7.55524e-7 0.5096788 0.8603648 -8.11872e-6 0.5096789 0.8603649 -0.9417109 -0.3364234 0 -0.9328474 -0.3602646 0.002303481 -0.8362013 -0.5483912 -0.005892157 -0.8392381 -0.5437214 -0.006821572 -0.7578157 -0.6524685 5.56975e-4 -0.5356282 -0.8444522 -0.001785278 -0.5251742 -0.8509948 0 -0.2077239 -0.9781875 0 -0.1632236 -0.9865837 -0.003297984 0.02812874 -0.9996022 0.002043426 0.07332098 -0.9973084 0 0.2623252 -0.9649795 0 0.266469 -0.9638435 -3.17027e-4 0.4819348 -0.8762071 3.05472e-4 0.4856194 -0.8741703 0 0.6468252 -0.7626384 0 0.7594329 -0.6505334 0.00825572 0.9807854 -0.1950897 0 0.9726976 -0.2320106 0.005541801 0.9074223 -0.4202201 0 0.8080069 -0.589173 0 0 -0.9802616 -0.197705 0 -0.9802619 -0.1977037 -0.9807854 -0.1950897 0 -0.9726976 -0.2320106 0.005541861 -0.9074223 -0.4202201 0 -0.8080069 -0.589173 0 -0.7594329 -0.6505334 0.00825572 -0.6468252 -0.7626384 0 -0.4818578 -0.8762495 0 -0.4856199 -0.8741701 3.16658e-4 -0.262275 -0.9649932 -3.28589e-4 -0.26647 -0.9638432 0 -0.02809476 -0.9996052 0 -0.07332092 -0.997303 0.003298223 0.2071768 -0.9782931 -0.004531502 0.1632242 -0.9865891 0 0.5356296 -0.8444531 0 0.5246731 -0.8513017 -0.00188589 0.9417109 -0.3364234 0 0.9328469 -0.3602656 0.002303481 0.8362013 -0.5483912 -0.005892157 0.8392378 -0.5437218 -0.006821572 0.7578153 -0.6524691 5.56881e-4 -0.06963008 -0.351483 -0.9336014 -0.1994985 0 -0.9798982 -0.4401341 0 -0.8979321 -0.5488655 -0.1264105 -0.8262972 -0.6560487 0 -0.7547187 -0.8276308 0 -0.5612729 -0.8908813 -0.0819863 -0.4467762 -0.9440417 0 -0.3298262 -0.9971917 0 -0.0748918 -0.9958021 -0.0734573 0.05461078 -0.9829633 0 0.1838022 -0.9022704 0 0.4311707 -0.8363221 -0.08711564 0.5412727 -0.7612313 0 0.6484806 0 -1 0 -0.9626362 -0.1914836 -0.1914827 -0.4681395 -0.8264366 -0.3128064 -0.1652663 -0.9800469 -0.1104319 -0.1104331 -0.9800472 -0.165264 0.1652666 -0.9800471 -0.11043 0.1104331 -0.9800472 -0.165264 0.936428 -0.3345375 -0.1057713 0.9024685 -0.2947322 -0.3141396 0.7794748 -0.3781713 -0.4994052 0.7597385 -0.4063222 -0.5076416 0.6835675 -0.2739004 -0.6765458 0.4736586 -0.3837776 -0.7926932 0.5250564 -0.3268484 -0.7858027 0.3815886 -0.2703518 -0.8839118 0.2791705 -0.2692666 -0.9217154 0.1856729 -0.3071742 -0.9333647 0.1155779 -0.2406425 -0.9637079 -0.18957 -0.2363938 -0.9529855 -0.1302604 -0.2163772 -0.9675811 -0.02029657 -0.2181536 -0.9757034 -0.06938862 -0.9438263 -0.3230746 0.4681442 -0.8264389 -0.3127937 0.4681316 -0.8264433 -0.312801 0.3127945 -0.826444 -0.4681345 0.3128145 -0.8264384 -0.4681311 0.109831 -0.8264396 -0.5522089 0.6954386 -0.5481277 -0.4646733 0.6954465 -0.5481225 -0.4646676 0.4646742 -0.5481196 -0.6954444 0.4646765 -0.5481209 -0.6954419 0.1631812 -0.5481193 -0.8203276 0.1631544 -0.5481367 -0.8203212 -0.1631795 -0.5481346 -0.8203176 0.8656882 -0.4700359 -0.1721928 0.8248825 -0.5409687 -0.1640787 0.8174037 -0.5491212 -0.1741185 0.5333715 -0.8408908 -0.09174811 0.5859182 -0.8103702 -3.98048e-4 0.1620858 -0.9797045 -0.1179292 -0.2660944 -0.9624926 -0.05293154 -0.4833719 -0.8701191 -0.09614896 -0.5232814 -0.8311758 -0.1879454 -0.6415351 -0.7564039 -0.1276165 -0.7977666 -0.5817089 -0.1586925 -0.3128076 -0.8264468 -0.4681207 -0.4681414 -0.8264407 -0.312793 -0.6954429 -0.5481309 -0.464663 -0.8105831 -0.5510668 -0.1981931 -0.8929957 -0.413529 -0.1776298 -0.5452982 -0.1914882 -0.8160774 -0.2639464 -0.1937416 -0.9448792 -0.2139595 -0.2222275 -0.9512288 -0.8160819 -0.1914762 -0.5452955 -0.545289 -0.1914691 -0.8160879 -0.464675 -0.5481187 -0.6954446 -0.1631568 -0.5481178 -0.8203334 -0.1098274 -0.8264364 -0.5522145 0.1098361 -0.826438 -0.5522104 0.03877526 -0.9800474 -0.1949458 -0.9626368 -0.1914807 -0.1914825 -0.8160868 -0.1914809 -0.5452865 -0.6954434 -0.5481203 -0.4646747 -0.4646776 -0.5481206 -0.6954413 -0.3127982 -0.8264395 -0.4681402 -0.1098431 -0.8264427 -0.5522019 -0.03877508 -0.9800475 -0.194945 -1.80871e-6 -0.9771349 -0.2126209 9.94652e-7 -0.9771351 -0.2126197 1.24284e-6 -0.9771353 -0.2126188 -7.62398e-7 -0.9771343 -0.2126229 0 -0.9771348 -0.2126207 0 -0.9771354 -0.2126182 3.06047e-7 -0.9771346 -0.2126216 -7.23232e-7 -0.977135 -0.2126203 -7.54138e-7 -0.9771351 -0.21262 0.7977666 -0.5817087 -0.1586933 0.4833717 -0.8701189 -0.09615069 -0.110433 -0.9800468 -0.1652659 0.1652664 -0.9800472 -0.1104298 -0.7061166 -0.2526046 -0.6615061 0.249413 -0.3748177 -0.8929194 0.1905618 -0.214464 -0.9579622 -0.09023576 -0.2170733 -0.9719758 -0.1856653 -0.3072736 -0.9333335 -0.2781147 -0.2693914 -0.9219981 -0.7564811 -0.483214 -0.4407274 0.6415352 -0.756404 -0.1276152 0.5232814 -0.8311758 -0.1879454 0.4681454 -0.8264378 -0.3127946 0.4681323 -0.8264427 -0.3128015 -0.4681402 -0.8264409 -0.3127945 -0.4681393 -0.8264393 -0.3127999 -0.1652667 -0.9800468 -0.1104322 0.8929957 -0.413529 -0.1776298 0.8105831 -0.5510668 -0.1981931 0.695439 -0.5481271 -0.4646735 0.6954488 -0.5481221 -0.4646647 0.4646754 -0.5481184 -0.6954445 0.4646769 -0.5481197 -0.6954424 0.1631544 -0.5481365 -0.8203214 -0.1631795 -0.5481349 -0.8203174 0.2660944 -0.9624925 -0.05293321 0.06938809 -0.9438279 -0.3230699 -0.4200596 -0.4121534 -0.8085045 -0.5357292 -0.2648419 -0.8017812 -0.464674 -0.5481192 -0.6954448 -0.1631569 -0.548117 -0.8203338 -0.1098273 -0.8264367 -0.552214 0.03877508 -0.9800475 -0.194945 -0.1620846 -0.979705 -0.1179274 -0.5355587 -0.8443365 -0.01651984 -0.5562264 -0.8252297 -0.09802281 -0.8231724 -0.539844 -0.1759423 -0.8203247 -0.5481262 -0.1631724 -0.9256116 -0.3306735 -0.1841145 -0.8307349 -0.5478022 -0.09895616 0.1408092 -0.2650275 -0.9539043 0.260399 -0.1936557 -0.9458805 0.5452823 -0.1914886 -0.8160879 0.5453044 -0.1914697 -0.8160776 0.8160856 -0.1914754 -0.5452903 0.8160833 -0.1914815 -0.5452916 0.962637 -0.1914807 -0.191482 0.9626363 -0.1914829 -0.1914832 -0.8993306 -0.3282167 -0.2889259 -0.7865772 -0.3241485 -0.5255705 -0.6954412 -0.5481215 -0.4646766 -0.4646772 -0.5481218 -0.6954407 -0.3127979 -0.8264397 -0.4681397 -0.1098433 -0.8264421 -0.5522028 -0.03877526 -0.9800474 -0.1949458 0.7614855 0 0.648182 0.8363261 -0.08707964 0.5412725 0.9958023 -0.07345485 0.05461102 0.982959 0 0.1838251 0.902446 0 0.4308031 0.8908799 -0.08199822 -0.4467767 0.9440137 0 -0.3299065 0.9971936 0 -0.07486641 0.5488792 -0.1263413 -0.8262987 0.6562046 0 -0.7545831 0.827579 0 -0.5613495 0.0696147 -0.351957 -0.9334239 0.1993613 0 -0.9799261 0.4403086 0 -0.8978465 -6.46447e-7 0 -1 2.52352e-7 0 -1 -1.68413e-7 0 -1 7.63875e-7 0 -1 -7.89103e-7 0 -1 -0.3042206 0.9526017 0 -0.2317613 0.9727048 -0.01149487 -0.2310287 0.9729093 -0.008560538 -0.2282356 0.9736012 -0.003056347 -0.2256314 0.9742128 0 -0.2791629 0.9602187 -0.006941795 -0.2957717 0.9550158 -0.02154093 -0.2603244 0.965521 -5.23796e-4 -0.2428312 0.9700683 7.64549e-4 -0.2322485 0.9726234 -0.008032441 -0.3407418 0.9401566 7.90325e-4 -0.3171215 0.948374 -0.004553318 -0.3253466 0.9455949 0 -0.3825 0.9238498 -0.01397329 -0.3773996 0.9260116 -0.008491575 -0.3627815 0.9318733 -0.001333415 -0.3829374 0.9237471 0.007086455 -0.3808771 0.9246203 -0.003152787 -0.3817186 0.9241986 -0.01216107 -0.3449554 0.9386191 -2.21338e-4 -0.345633 0.9383698 0 -0.3612775 0.932455 -0.002521038 -0.3835996 0.9234443 0.0101006 -0.3855823 0.9225935 0.01214736 -0.2777621 0.9606499 0 -0.2461525 0.969202 -0.007514655 -0.2438359 0.9697588 -0.01059544 -0.1561313 0.9877114 0.007018923 -0.1226789 0.9898776 -0.07136082 0.3657593 0.9307096 0 0.3835909 0.923448 0.01009744 0.3808701 0.9246233 -0.003152132 0.3829423 0.9237451 0.00708419 0.3855829 0.9225933 0.01214504 0.3171368 0.9483689 -0.004545807 0.3407567 0.9401513 7.90276e-4 0.3627631 0.9318805 -0.001332163 0.3773936 0.9260142 -0.008482336 0.3824989 0.9238503 -0.01397055 0.3817191 0.9241984 -0.01216119 0.3253466 0.9455949 0 0.3420463 0.9396824 -0.001167535 0.302659 0.9529976 -0.01389807 0.3453025 0.9384915 0 0.2973707 0.9547622 0 0.2349745 0.9719507 -0.009946525 0.2442576 0.969684 -0.00715959 0.253445 0.9673365 -0.005094707 0.2440767 0.969744 -0.004812896 0.2340912 0.9721626 -0.010073 0.2313512 0.9728046 -0.01130902 0.2613167 0.9652466 -0.003556132 0.2754948 0.9613016 -0.001428306 0.2877038 0.9577193 -5.15403e-4 0.1228603 0.9898447 -0.07150363 0.1534515 0.9881563 0 0.2443861 0.9696781 0 0.2238112 0.9739015 -0.03774142 0.2521463 0.9676892 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 0 3 11 4 12 4 1 4 1 5 12 5 13 5 1 6 13 6 2 6 2 7 13 7 14 7 11 8 15 8 16 8 16 9 15 9 17 9 16 10 17 10 18 10 10 11 19 11 0 11 0 12 19 12 20 12 0 13 20 13 1 13 1 14 20 14 21 14 1 15 21 15 11 15 11 16 21 16 22 16 11 17 22 17 15 17 23 18 24 18 25 18 23 19 25 19 8 19 8 20 25 20 26 20 8 21 26 21 6 21 27 22 28 22 29 22 29 23 28 23 30 23 29 24 30 24 4 24 31 25 32 25 33 25 33 26 32 26 34 26 35 27 36 27 31 27 37 28 38 28 33 28 31 29 33 29 35 29 35 30 33 30 38 30 35 31 38 31 39 31 40 32 33 32 41 32 41 33 33 33 34 33 41 34 34 34 42 34 7 35 9 35 8 35 8 36 9 36 0 36 8 37 0 37 43 37 43 38 0 38 2 38 43 39 2 39 44 39 44 40 2 40 14 40 44 41 14 41 37 41 37 42 14 42 45 42 46 43 40 43 47 43 47 44 40 44 41 44 47 45 41 45 5 45 5 46 41 46 42 46 5 47 42 47 3 47 4 48 30 48 5 48 5 49 30 49 48 49 5 50 48 50 47 50 47 51 48 51 49 51 47 52 49 52 46 52 46 53 49 53 50 53 46 54 50 54 51 54 37 55 33 55 44 55 44 56 33 56 40 56 44 57 40 57 43 57 43 58 40 58 46 58 43 59 46 59 8 59 8 60 46 60 51 60 8 61 51 61 23 61 45 62 14 62 52 62 52 63 14 63 53 63 52 64 53 64 54 64 54 65 53 65 55 65 39 66 56 66 35 66 35 67 56 67 57 67 35 68 57 68 36 68 56 69 54 69 55 69 55 70 58 70 59 70 57 69 56 69 60 69 60 71 56 71 55 71 60 69 55 69 61 69 61 69 55 69 59 69 62 72 63 72 64 72 64 73 63 73 65 73 64 74 65 74 66 74 67 75 68 75 69 75 69 73 68 73 70 73 69 72 70 72 71 72 71 76 70 76 72 76 71 77 72 77 62 77 62 78 72 78 73 78 62 76 73 76 63 76 74 79 75 79 76 79 77 80 78 80 79 80 80 81 81 81 82 81 83 82 84 82 85 82 86 83 87 83 88 83 89 84 90 84 91 84 92 85 93 85 94 85 95 86 96 86 97 86 97 87 98 87 95 87 95 88 98 88 92 88 95 89 92 89 99 89 99 90 92 90 94 90 99 91 94 91 100 91 101 92 102 92 103 92 104 93 105 93 106 93 107 94 106 94 108 94 108 95 106 95 105 95 108 96 105 96 109 96 110 97 111 97 112 97 112 98 111 98 113 98 114 99 115 99 116 99 116 100 115 100 117 100 118 101 119 101 114 101 114 102 116 102 118 102 118 103 116 103 120 103 118 104 120 104 121 104 121 105 120 105 122 105 122 106 120 106 123 106 122 107 123 107 124 107 76 108 75 108 123 108 124 109 123 109 125 109 125 110 123 110 75 110 125 111 75 111 126 111 126 112 75 112 127 112 127 113 75 113 74 113 127 114 74 114 128 114 129 115 130 115 131 115 131 116 130 116 132 116 133 117 134 117 135 117 136 118 137 118 138 118 139 119 90 119 140 119 140 120 90 120 89 120 140 121 89 121 141 121 141 122 89 122 142 122 141 123 142 123 143 123 143 124 142 124 144 124 145 125 136 125 146 125 146 126 136 126 138 126 146 127 138 127 147 127 147 128 138 128 148 128 147 129 148 129 149 129 149 130 148 130 150 130 149 131 150 131 151 131 151 132 150 132 152 132 151 133 152 133 153 133 137 134 144 134 138 134 138 135 144 135 142 135 138 136 142 136 148 136 148 137 142 137 89 137 148 138 89 138 150 138 150 139 89 139 91 139 150 140 91 140 152 140 154 141 155 141 156 141 156 142 155 142 157 142 156 143 157 143 158 143 158 144 157 144 159 144 158 145 159 145 160 145 160 146 159 146 161 146 160 147 161 147 162 147 162 148 161 148 163 148 162 149 163 149 164 149 164 150 163 150 165 150 164 151 165 151 166 151 166 152 165 152 167 152 166 153 167 153 168 153 168 154 167 154 169 154 168 155 169 155 170 155 170 156 169 156 171 156 81 157 77 157 82 157 82 158 77 158 79 158 82 159 79 159 172 159 172 160 79 160 173 160 172 161 173 161 174 161 174 162 173 162 175 162 174 163 175 163 176 163 176 164 175 164 177 164 176 165 177 165 178 165 178 166 177 166 179 166 178 167 179 167 180 167 180 168 179 168 181 168 180 169 181 169 182 169 78 170 145 170 79 170 79 171 145 171 146 171 79 172 146 172 173 172 173 173 146 173 147 173 173 174 147 174 175 174 175 175 147 175 149 175 175 176 149 176 177 176 177 177 149 177 151 177 177 178 151 178 179 178 179 179 151 179 153 179 179 180 153 180 181 180 183 181 184 181 185 181 185 182 184 182 186 182 185 183 186 183 187 183 187 184 186 184 188 184 187 185 188 185 189 185 189 186 188 186 190 186 189 187 190 187 191 187 191 188 190 188 192 188 191 189 192 189 193 189 193 190 192 190 194 190 193 191 194 191 195 191 195 192 194 192 196 192 197 193 133 193 198 193 198 194 133 194 135 194 198 195 135 195 199 195 199 196 135 196 200 196 199 197 200 197 201 197 201 198 200 198 202 198 201 199 202 199 203 199 203 200 202 200 204 200 203 201 204 201 205 201 205 202 204 202 206 202 205 203 206 203 207 203 207 204 206 204 208 204 207 205 208 205 209 205 209 206 208 206 210 206 209 207 210 207 86 207 86 208 210 208 211 208 86 209 211 209 87 209 134 210 80 210 135 210 135 211 80 211 82 211 135 212 82 212 200 212 200 213 82 213 172 213 200 214 172 214 202 214 202 215 172 215 174 215 202 216 174 216 204 216 204 217 174 217 176 217 204 218 176 218 206 218 206 219 176 219 178 219 206 220 178 220 208 220 208 221 178 221 180 221 208 222 180 222 210 222 210 223 180 223 182 223 210 224 182 224 211 224 84 225 212 225 85 225 85 226 212 226 213 226 85 227 213 227 214 227 214 228 213 228 215 228 214 229 215 229 216 229 216 230 215 230 217 230 216 231 217 231 218 231 218 232 217 232 219 232 220 233 221 233 222 233 222 234 221 234 223 234 222 235 223 235 224 235 224 236 223 236 225 236 224 237 225 237 226 237 226 238 225 238 227 238 226 239 227 239 228 239 228 240 227 240 229 240 228 241 229 241 230 241 230 242 229 242 231 242 230 243 231 243 232 243 232 244 231 244 233 244 232 245 233 245 234 245 234 246 233 246 235 246 234 247 235 247 236 247 236 248 235 248 237 248 236 249 237 249 238 249 238 250 237 250 239 250 238 251 239 251 240 251 241 252 240 252 88 252 88 253 240 253 239 253 88 254 239 254 86 254 86 255 239 255 237 255 86 256 237 256 209 256 209 257 237 257 235 257 209 258 235 258 207 258 207 259 235 259 233 259 207 260 233 260 205 260 205 261 233 261 231 261 205 262 231 262 203 262 203 263 231 263 229 263 203 264 229 264 201 264 201 265 229 265 227 265 201 266 227 266 199 266 199 267 227 267 225 267 199 268 225 268 198 268 198 269 225 269 223 269 198 270 223 270 197 270 197 271 223 271 221 271 212 272 128 272 213 272 213 273 128 273 74 273 213 274 74 274 215 274 215 275 74 275 76 275 215 276 76 276 217 276 217 277 76 277 123 277 217 278 123 278 219 278 219 279 123 279 120 279 219 280 120 280 242 280 242 281 120 281 116 281 242 282 116 282 112 282 112 283 116 283 117 283 112 284 117 284 110 284 184 285 83 285 186 285 186 286 83 286 85 286 186 287 85 287 188 287 188 288 85 288 214 288 188 289 214 289 190 289 190 290 214 290 216 290 190 291 216 291 192 291 192 292 216 292 218 292 192 293 218 293 194 293 194 294 218 294 219 294 194 295 219 295 196 295 196 296 219 296 242 296 196 297 242 297 104 297 104 298 242 298 112 298 104 299 112 299 105 299 105 300 112 300 113 300 105 301 113 301 109 301 155 302 183 302 157 302 157 303 183 303 185 303 157 304 185 304 159 304 159 305 185 305 187 305 159 306 187 306 161 306 161 307 187 307 189 307 161 308 189 308 163 308 163 309 189 309 191 309 163 310 191 310 165 310 165 311 191 311 193 311 165 312 193 312 167 312 167 313 193 313 195 313 167 314 195 314 169 314 169 315 195 315 196 315 169 316 196 316 171 316 171 317 196 317 104 317 171 318 104 318 101 318 101 319 104 319 106 319 101 320 106 320 102 320 131 321 154 321 129 321 129 322 154 322 156 322 129 323 156 323 243 323 243 324 156 324 158 324 243 325 158 325 244 325 244 326 158 326 160 326 244 327 160 327 245 327 245 328 160 328 162 328 245 329 162 329 246 329 246 330 162 330 164 330 246 331 164 331 247 331 247 332 164 332 166 332 247 333 166 333 248 333 248 334 166 334 168 334 248 335 168 335 249 335 249 336 168 336 170 336 249 337 170 337 250 337 250 338 170 338 171 338 250 339 171 339 99 339 99 340 171 340 101 340 99 341 101 341 95 341 95 342 101 342 103 342 95 343 103 343 96 343 251 344 252 344 253 344 253 345 252 345 132 345 253 346 132 346 241 346 241 347 132 347 130 347 241 348 130 348 240 348 240 349 130 349 129 349 240 350 129 350 238 350 238 351 129 351 243 351 238 352 243 352 236 352 236 353 243 353 244 353 236 354 244 354 234 354 234 355 244 355 245 355 234 356 245 356 232 356 232 357 245 357 246 357 232 358 246 358 230 358 230 359 246 359 247 359 230 360 247 360 228 360 228 361 247 361 248 361 228 362 248 362 226 362 226 363 248 363 249 363 226 364 249 364 224 364 224 365 249 365 250 365 224 366 250 366 222 366 222 367 250 367 99 367 222 368 99 368 220 368 220 369 99 369 100 369 254 370 255 370 253 370 253 371 255 371 251 371 254 372 253 372 256 372 256 373 253 373 241 373 256 374 241 374 257 374 257 375 241 375 88 375 257 376 88 376 258 376 258 377 88 377 87 377 258 378 87 378 259 378 87 379 211 379 259 379 259 380 211 380 182 380 259 381 182 381 260 381 260 382 182 382 181 382 260 383 181 383 261 383 261 384 181 384 153 384 261 385 153 385 262 385 262 386 153 386 152 386 262 387 152 387 263 387 263 388 152 388 91 388 263 389 91 389 264 389 264 390 91 390 90 390 264 391 90 391 265 391 265 392 90 392 139 392 266 393 267 393 268 393 269 394 255 394 270 394 270 395 255 395 271 395 271 396 272 396 270 396 270 397 272 397 273 397 270 398 273 398 274 398 273 399 275 399 274 399 274 400 275 400 276 400 274 401 276 401 277 401 276 402 278 402 277 402 277 403 278 403 279 403 277 404 279 404 280 404 281 405 282 405 283 405 283 406 282 406 280 406 283 407 280 407 284 407 284 408 280 408 279 408 281 409 285 409 282 409 282 410 285 410 286 410 282 411 286 411 287 411 286 412 288 412 287 412 287 413 288 413 289 413 287 414 289 414 268 414 268 415 289 415 290 415 268 393 290 393 266 393 269 416 291 416 255 416 255 417 291 417 251 417 121 418 292 418 118 418 118 419 292 419 293 419 118 420 293 420 119 420 121 421 122 421 292 421 292 422 122 422 124 422 292 423 124 423 294 423 124 424 125 424 294 424 294 425 125 425 126 425 294 426 126 426 295 426 295 427 126 427 127 427 295 428 127 428 128 428 128 429 212 429 295 429 295 430 212 430 84 430 295 431 84 431 296 431 84 432 83 432 296 432 296 433 83 433 184 433 296 434 184 434 297 434 184 435 183 435 297 435 297 436 183 436 155 436 297 437 155 437 298 437 132 438 299 438 131 438 131 439 299 439 298 439 131 440 298 440 154 440 154 441 298 441 155 441 132 442 252 442 299 442 299 443 252 443 251 443 299 444 251 444 291 444 300 445 301 445 302 445 303 446 304 446 305 446 305 447 304 447 306 447 305 448 306 448 307 448 307 449 306 449 300 449 307 450 300 450 308 450 308 451 300 451 302 451 308 452 302 452 309 452 309 453 310 453 308 453 308 454 310 454 119 454 308 455 119 455 293 455 311 456 312 456 313 456 313 457 312 457 314 457 315 458 303 458 311 458 311 459 303 459 316 459 311 460 316 460 312 460 317 461 301 461 318 461 318 462 301 462 300 462 318 463 300 463 319 463 319 464 300 464 306 464 319 465 306 465 315 465 315 466 306 466 304 466 315 467 304 467 303 467 320 468 321 468 322 468 323 469 324 469 325 469 326 470 327 470 328 470 329 471 317 471 318 471 330 472 331 472 332 472 333 473 314 473 334 473 334 474 314 474 335 474 334 475 335 475 336 475 327 476 329 476 328 476 328 477 329 477 318 477 328 478 318 478 337 478 337 479 318 479 319 479 337 480 319 480 338 480 338 481 319 481 315 481 338 482 315 482 339 482 339 483 315 483 311 483 339 484 311 484 333 484 333 485 311 485 313 485 333 486 313 486 314 486 322 487 340 487 341 487 340 488 322 488 342 488 342 489 322 489 321 489 342 490 321 490 18 490 320 491 322 491 343 491 343 492 322 492 344 492 343 493 344 493 345 493 345 494 344 494 346 494 345 495 346 495 347 495 347 496 346 496 348 496 348 497 346 497 349 497 348 498 349 498 350 498 350 499 349 499 351 499 350 500 351 500 352 500 352 501 351 501 353 501 353 502 351 502 330 502 353 503 330 503 354 503 354 504 330 504 332 504 354 505 332 505 355 505 336 506 356 506 334 506 334 507 356 507 357 507 334 508 357 508 333 508 333 509 357 509 358 509 333 510 358 510 339 510 339 511 358 511 359 511 339 512 359 512 338 512 338 513 359 513 360 513 338 514 360 514 337 514 337 515 360 515 361 515 337 516 361 516 328 516 328 517 361 517 325 517 328 518 325 518 326 518 326 519 325 519 324 519 356 520 331 520 357 520 357 521 331 521 330 521 357 522 330 522 358 522 358 523 330 523 351 523 358 524 351 524 359 524 359 525 351 525 349 525 359 526 349 526 360 526 360 527 349 527 346 527 360 528 346 528 361 528 361 529 346 529 344 529 361 530 344 530 325 530 325 531 344 531 322 531 325 532 322 532 323 532 323 533 322 533 341 533 113 534 111 534 362 534 362 535 111 535 110 535 362 536 110 536 310 536 310 537 110 537 117 537 117 538 115 538 310 538 310 539 115 539 114 539 310 540 114 540 119 540 113 541 362 541 109 541 109 542 362 542 363 542 109 543 363 543 108 543 363 544 364 544 108 544 108 545 364 545 365 545 108 546 365 546 107 546 107 547 365 547 366 547 107 548 366 548 367 548 367 549 368 549 107 549 107 550 368 550 369 550 107 551 369 551 370 551 370 552 369 552 371 552 370 553 371 553 372 553 373 554 374 554 375 554 97 555 375 555 98 555 106 556 107 556 370 556 97 557 96 557 372 557 372 558 96 558 103 558 372 559 103 559 370 559 370 560 103 560 102 560 370 561 102 561 106 561 374 562 93 562 375 562 375 563 93 563 92 563 375 564 92 564 98 564 97 565 372 565 375 565 375 566 372 566 376 566 375 567 376 567 373 567 377 568 378 568 379 568 100 569 94 569 380 569 381 570 382 570 383 570 384 571 385 571 386 571 387 572 388 572 389 572 390 573 391 573 392 573 393 574 394 574 395 574 396 575 397 575 398 575 139 576 140 576 399 576 399 577 140 577 400 577 399 578 400 578 401 578 401 579 400 579 402 579 403 580 404 580 381 580 381 581 404 581 405 581 381 582 405 582 382 582 382 583 405 583 406 583 382 584 406 584 407 584 408 585 409 585 410 585 410 586 409 586 411 586 412 587 413 587 414 587 414 588 413 588 415 588 388 589 387 589 416 589 416 590 387 590 417 590 416 591 417 591 418 591 418 592 417 592 419 592 418 593 419 593 392 593 392 594 419 594 420 594 392 595 420 595 390 595 385 596 384 596 421 596 422 597 378 597 423 597 423 598 378 598 377 598 423 599 377 599 424 599 425 600 403 600 426 600 426 601 403 601 381 601 426 602 381 602 427 602 427 603 381 603 383 603 427 604 383 604 428 604 422 605 429 605 378 605 378 606 429 606 430 606 378 607 430 607 379 607 379 608 430 608 431 608 379 609 431 609 432 609 432 610 431 610 433 610 432 611 433 611 434 611 434 612 433 612 435 612 434 613 435 613 436 613 436 614 435 614 437 614 436 615 437 615 438 615 438 616 437 616 439 616 438 617 439 617 440 617 440 618 439 618 441 618 440 619 441 619 428 619 428 620 441 620 442 620 428 621 442 621 427 621 427 622 442 622 443 622 427 623 443 623 426 623 426 624 443 624 411 624 426 625 411 625 425 625 425 626 411 626 409 626 430 627 386 627 431 627 431 628 386 628 385 628 431 629 385 629 433 629 433 630 385 630 421 630 433 631 421 631 435 631 435 632 421 632 444 632 435 633 444 633 437 633 437 634 444 634 445 634 437 635 445 635 439 635 439 636 445 636 446 636 439 637 446 637 441 637 441 638 446 638 447 638 441 639 447 639 442 639 442 640 447 640 448 640 442 641 448 641 443 641 443 642 448 642 414 642 443 643 414 643 411 643 411 644 414 644 415 644 411 645 415 645 410 645 384 646 449 646 421 646 421 647 449 647 389 647 421 648 389 648 444 648 444 649 389 649 388 649 444 650 388 650 445 650 445 651 388 651 416 651 445 652 416 652 446 652 446 653 416 653 418 653 446 654 418 654 447 654 447 655 418 655 392 655 447 656 392 656 448 656 448 657 392 657 391 657 448 658 391 658 414 658 414 659 391 659 390 659 414 660 390 660 412 660 220 661 450 661 221 661 221 662 450 662 451 662 221 663 451 663 197 663 197 664 451 664 452 664 197 665 452 665 133 665 133 666 452 666 453 666 133 667 453 667 134 667 134 668 453 668 454 668 140 669 141 669 400 669 400 670 141 670 143 670 400 671 143 671 455 671 456 672 145 672 457 672 457 673 145 673 78 673 143 674 144 674 455 674 455 675 144 675 137 675 455 676 137 676 456 676 456 677 137 677 136 677 456 678 136 678 145 678 78 679 77 679 457 679 457 680 77 680 81 680 457 681 81 681 454 681 454 682 81 682 80 682 454 683 80 683 134 683 94 684 93 684 380 684 380 685 93 685 458 685 380 686 458 686 459 686 459 687 458 687 460 687 459 688 460 688 461 688 461 689 460 689 462 689 461 690 462 690 463 690 463 691 462 691 464 691 463 692 464 692 465 692 465 693 464 693 466 693 465 694 466 694 467 694 467 695 466 695 468 695 467 696 468 696 469 696 469 697 468 697 470 697 469 698 470 698 471 698 471 699 470 699 472 699 471 700 472 700 473 700 473 701 472 701 474 701 473 702 474 702 398 702 398 703 474 703 395 703 398 704 395 704 396 704 396 705 395 705 394 705 397 706 402 706 398 706 398 707 402 707 400 707 398 708 400 708 473 708 473 709 400 709 455 709 473 710 455 710 471 710 471 711 455 711 456 711 471 712 456 712 469 712 469 713 456 713 457 713 469 714 457 714 467 714 467 715 457 715 454 715 467 716 454 716 465 716 465 717 454 717 453 717 465 718 453 718 463 718 463 719 453 719 452 719 463 720 452 720 461 720 461 721 452 721 451 721 461 722 451 722 459 722 459 723 451 723 450 723 459 724 450 724 380 724 380 725 450 725 220 725 380 726 220 726 100 726 407 727 393 727 382 727 382 728 393 728 395 728 382 729 395 729 383 729 383 730 395 730 474 730 383 731 474 731 428 731 428 732 474 732 472 732 428 733 472 733 440 733 440 734 472 734 470 734 440 735 470 735 438 735 438 736 470 736 468 736 438 737 468 737 436 737 436 738 468 738 466 738 436 739 466 739 434 739 434 740 466 740 464 740 434 741 464 741 432 741 432 742 464 742 462 742 432 743 462 743 379 743 379 744 462 744 460 744 379 745 460 745 377 745 377 746 460 746 458 746 377 747 458 747 424 747 424 748 458 748 93 748 424 749 93 749 374 749 475 750 476 750 407 750 265 751 139 751 477 751 477 752 139 752 399 752 477 753 399 753 478 753 478 754 399 754 401 754 478 755 401 755 479 755 479 756 401 756 402 756 479 757 402 757 480 757 480 758 402 758 397 758 480 759 397 759 481 759 481 760 397 760 396 760 481 761 396 761 482 761 482 762 396 762 394 762 482 763 394 763 476 763 476 764 394 764 393 764 476 765 393 765 407 765 408 766 483 766 409 766 409 767 483 767 484 767 409 768 484 768 425 768 425 769 484 769 485 769 425 770 485 770 403 770 403 771 485 771 486 771 403 772 486 772 404 772 404 773 486 773 487 773 404 774 487 774 405 774 405 775 487 775 475 775 405 776 475 776 406 776 406 777 475 777 407 777 488 778 489 778 490 778 491 779 492 779 493 779 494 780 495 780 496 780 479 781 480 781 497 781 475 782 487 782 498 782 486 783 485 783 499 783 500 784 501 784 502 784 503 785 504 785 505 785 506 786 507 786 508 786 508 787 507 787 509 787 508 788 509 788 510 788 510 789 509 789 511 789 510 790 511 790 512 790 512 791 511 791 503 791 512 792 503 792 513 792 513 793 503 793 505 793 514 794 515 794 516 794 516 795 515 795 517 795 516 796 517 796 518 796 500 797 502 797 519 797 519 798 502 798 520 798 519 799 520 799 521 799 521 800 520 800 522 800 521 801 522 801 523 801 523 802 522 802 524 802 523 803 524 803 525 803 525 804 524 804 526 804 525 805 526 805 527 805 527 806 526 806 528 806 528 807 526 807 529 807 528 808 529 808 530 808 530 809 529 809 484 809 530 810 484 810 483 810 475 811 498 811 476 811 481 812 482 812 531 812 531 813 482 813 532 813 531 814 532 814 533 814 478 815 496 815 477 815 477 816 496 816 495 816 477 817 495 817 265 817 480 818 481 818 497 818 497 819 481 819 531 819 497 820 531 820 534 820 534 821 531 821 533 821 534 822 533 822 535 822 478 823 479 823 496 823 496 824 479 824 497 824 496 825 497 825 536 825 536 826 497 826 534 826 536 827 534 827 537 827 537 828 534 828 535 828 537 829 535 829 538 829 538 830 535 830 539 830 538 831 539 831 540 831 540 832 539 832 541 832 540 833 541 833 542 833 543 834 544 834 545 834 545 835 544 835 494 835 546 836 493 836 547 836 547 837 493 837 492 837 547 838 492 838 548 838 494 839 496 839 545 839 545 840 496 840 536 840 545 841 536 841 549 841 549 842 536 842 537 842 549 843 537 843 550 843 550 844 537 844 538 844 550 845 538 845 551 845 551 846 538 846 540 846 551 847 540 847 552 847 552 848 540 848 542 848 552 849 542 849 490 849 553 850 546 850 554 850 554 851 546 851 547 851 554 852 547 852 555 852 555 853 547 853 548 853 555 854 548 854 556 854 490 855 489 855 552 855 552 856 489 856 557 856 552 857 557 857 551 857 551 858 557 858 558 858 551 859 558 859 550 859 550 860 558 860 559 860 550 861 559 861 549 861 549 862 559 862 560 862 549 863 560 863 545 863 545 864 560 864 561 864 545 865 561 865 543 865 562 866 563 866 488 866 488 867 563 867 564 867 488 868 564 868 489 868 489 869 564 869 565 869 489 870 565 870 557 870 557 871 565 871 566 871 557 872 566 872 558 872 558 873 566 873 567 873 558 874 567 874 559 874 559 875 567 875 568 875 559 876 568 876 560 876 560 877 568 877 569 877 560 878 569 878 561 878 506 879 508 879 556 879 556 880 508 880 510 880 556 881 510 881 555 881 555 882 510 882 512 882 555 883 512 883 554 883 554 884 512 884 513 884 554 885 513 885 553 885 505 886 570 886 513 886 513 887 570 887 571 887 513 888 571 888 553 888 553 889 571 889 572 889 553 890 572 890 573 890 573 891 562 891 553 891 553 892 562 892 488 892 553 893 488 893 546 893 546 894 488 894 490 894 546 895 490 895 493 895 493 896 490 896 542 896 493 897 542 897 491 897 491 898 542 898 541 898 518 899 574 899 516 899 516 900 574 900 575 900 516 901 575 901 514 901 514 902 575 902 576 902 514 903 576 903 577 903 577 904 576 904 578 904 577 905 578 905 579 905 579 906 578 906 580 906 579 907 580 907 581 907 581 908 580 908 582 908 581 909 582 909 583 909 583 910 582 910 584 910 583 911 584 911 585 911 585 912 584 912 586 912 585 913 586 913 499 913 499 914 586 914 498 914 499 915 498 915 486 915 486 916 498 916 487 916 500 917 515 917 501 917 501 918 515 918 514 918 501 919 514 919 502 919 502 920 514 920 577 920 502 921 577 921 520 921 520 922 577 922 579 922 520 923 579 923 522 923 522 924 579 924 581 924 522 925 581 925 524 925 524 926 581 926 583 926 524 927 583 927 526 927 526 928 583 928 585 928 526 929 585 929 529 929 529 930 585 930 499 930 529 931 499 931 484 931 484 932 499 932 485 932 517 933 587 933 518 933 518 934 587 934 506 934 518 935 506 935 574 935 574 936 506 936 556 936 574 937 556 937 575 937 575 938 556 938 548 938 575 939 548 939 576 939 576 940 548 940 492 940 576 941 492 941 578 941 578 942 492 942 491 942 578 943 491 943 580 943 580 944 491 944 541 944 580 945 541 945 582 945 582 946 541 946 539 946 582 947 539 947 584 947 584 948 539 948 535 948 584 949 535 949 586 949 586 950 535 950 533 950 586 951 533 951 498 951 498 952 533 952 532 952 498 953 532 953 476 953 476 954 532 954 482 954 543 955 561 955 588 955 259 956 260 956 589 956 590 957 266 957 290 957 271 958 255 958 254 958 271 959 591 959 272 959 272 960 591 960 592 960 272 961 592 961 273 961 593 962 594 962 285 962 285 963 594 963 286 963 595 964 596 964 597 964 286 965 594 965 288 965 288 966 594 966 598 966 288 967 598 967 289 967 289 968 598 968 595 968 289 969 595 969 290 969 290 970 595 970 597 970 290 971 597 971 590 971 599 972 600 972 601 972 601 973 600 973 602 973 601 974 602 974 603 974 604 975 605 975 599 975 599 976 605 976 606 976 599 977 606 977 600 977 607 978 608 978 604 978 604 979 608 979 609 979 604 980 609 980 605 980 610 981 611 981 607 981 607 982 611 982 612 982 607 983 612 983 608 983 613 984 264 984 265 984 271 985 254 985 591 985 591 986 254 986 256 986 591 987 256 987 257 987 565 988 564 988 614 988 564 989 563 989 614 989 614 990 563 990 615 990 614 991 615 991 616 991 544 992 543 992 617 992 617 993 543 993 588 993 617 994 588 994 618 994 618 995 588 995 619 995 618 996 619 996 620 996 620 997 619 997 621 997 620 998 621 998 622 998 622 999 621 999 623 999 622 1000 623 1000 624 1000 624 1001 623 1001 625 1001 624 1002 625 1002 626 1002 626 1003 625 1003 627 1003 626 1004 627 1004 628 1004 628 1005 627 1005 629 1005 628 1006 629 1006 630 1006 265 1007 495 1007 613 1007 613 1008 495 1008 494 1008 613 1009 494 1009 631 1009 258 1010 632 1010 633 1010 633 1011 632 1011 634 1011 633 1012 634 1012 635 1012 635 1013 634 1013 636 1013 635 1014 636 1014 637 1014 637 1015 636 1015 638 1015 637 1016 638 1016 275 1016 275 1017 638 1017 276 1017 275 1018 273 1018 637 1018 637 1019 273 1019 592 1019 637 1020 592 1020 635 1020 635 1021 592 1021 591 1021 635 1022 591 1022 633 1022 633 1023 591 1023 257 1023 633 1024 257 1024 258 1024 279 1025 278 1025 639 1025 639 1026 278 1026 640 1026 639 1027 640 1027 641 1027 641 1028 640 1028 642 1028 641 1029 642 1029 643 1029 643 1030 642 1030 644 1030 643 1031 644 1031 645 1031 645 1032 644 1032 646 1032 645 1033 646 1033 647 1033 647 1034 646 1034 589 1034 647 1035 589 1035 648 1035 648 1036 589 1036 260 1036 648 1037 260 1037 261 1037 278 1038 276 1038 640 1038 640 1039 276 1039 638 1039 640 1040 638 1040 642 1040 642 1041 638 1041 636 1041 642 1042 636 1042 644 1042 644 1043 636 1043 634 1043 644 1044 634 1044 646 1044 646 1045 634 1045 632 1045 646 1046 632 1046 589 1046 589 1047 632 1047 258 1047 589 1048 258 1048 259 1048 569 1049 568 1049 649 1049 649 1050 568 1050 650 1050 649 1051 650 1051 651 1051 651 1052 650 1052 652 1052 651 1053 652 1053 653 1053 653 1054 652 1054 654 1054 653 1055 654 1055 655 1055 655 1056 654 1056 656 1056 655 1057 656 1057 657 1057 657 1058 656 1058 658 1058 657 1059 658 1059 659 1059 659 1060 658 1060 660 1060 659 1061 660 1061 661 1061 283 1062 284 1062 662 1062 662 1063 284 1063 663 1063 662 1064 663 1064 664 1064 664 1065 663 1065 665 1065 664 1066 665 1066 666 1066 666 1067 665 1067 667 1067 666 1068 667 1068 668 1068 668 1069 667 1069 669 1069 668 1070 669 1070 670 1070 670 1071 669 1071 671 1071 670 1072 671 1072 672 1072 672 1073 671 1073 673 1073 672 1074 673 1074 674 1074 674 1075 673 1075 675 1075 674 1076 675 1076 676 1076 676 1077 675 1077 262 1077 676 1078 262 1078 263 1078 284 1079 279 1079 663 1079 663 1080 279 1080 639 1080 663 1081 639 1081 665 1081 665 1082 639 1082 641 1082 665 1083 641 1083 667 1083 667 1084 641 1084 643 1084 667 1085 643 1085 669 1085 669 1086 643 1086 645 1086 669 1087 645 1087 671 1087 671 1088 645 1088 647 1088 671 1089 647 1089 673 1089 673 1090 647 1090 648 1090 673 1091 648 1091 675 1091 675 1092 648 1092 261 1092 675 1093 261 1093 262 1093 601 1094 677 1094 599 1094 599 1095 677 1095 678 1095 599 1096 678 1096 604 1096 604 1097 678 1097 679 1097 604 1098 679 1098 607 1098 607 1099 679 1099 680 1099 607 1100 680 1100 610 1100 610 1101 680 1101 504 1101 567 1102 566 1102 681 1102 681 1103 566 1103 682 1103 681 1104 682 1104 683 1104 683 1105 682 1105 684 1105 683 1106 684 1106 685 1106 685 1107 684 1107 686 1107 685 1108 686 1108 687 1108 687 1109 686 1109 688 1109 687 1110 688 1110 689 1110 285 1111 281 1111 593 1111 593 1112 281 1112 690 1112 593 1113 690 1113 691 1113 691 1114 690 1114 692 1114 691 1115 692 1115 693 1115 693 1116 692 1116 694 1116 693 1117 694 1117 695 1117 695 1118 694 1118 696 1118 695 1119 696 1119 697 1119 697 1120 696 1120 698 1120 697 1121 698 1121 699 1121 699 1122 698 1122 700 1122 699 1123 700 1123 701 1123 701 1124 700 1124 702 1124 701 1125 702 1125 703 1125 703 1126 702 1126 704 1126 703 1127 704 1127 705 1127 705 1128 704 1128 706 1128 705 1129 706 1129 707 1129 264 1130 707 1130 263 1130 263 1131 707 1131 706 1131 263 1132 706 1132 676 1132 676 1133 706 1133 704 1133 676 1134 704 1134 674 1134 674 1135 704 1135 702 1135 674 1136 702 1136 672 1136 672 1137 702 1137 700 1137 672 1138 700 1138 670 1138 670 1139 700 1139 698 1139 670 1140 698 1140 668 1140 668 1141 698 1141 696 1141 668 1142 696 1142 666 1142 666 1143 696 1143 694 1143 666 1144 694 1144 664 1144 664 1145 694 1145 692 1145 664 1146 692 1146 662 1146 662 1147 692 1147 690 1147 662 1148 690 1148 283 1148 283 1149 690 1149 281 1149 708 1150 570 1150 680 1150 680 1151 570 1151 505 1151 680 1152 505 1152 504 1152 563 1153 562 1153 615 1153 615 1154 562 1154 573 1154 615 1155 573 1155 616 1155 616 1156 573 1156 572 1156 616 1157 572 1157 708 1157 708 1158 572 1158 571 1158 708 1159 571 1159 570 1159 566 1160 565 1160 682 1160 682 1161 565 1161 614 1161 682 1162 614 1162 684 1162 684 1163 614 1163 616 1163 684 1164 616 1164 686 1164 686 1165 616 1165 708 1165 686 1166 708 1166 688 1166 688 1167 708 1167 680 1167 688 1168 680 1168 689 1168 689 1169 680 1169 679 1169 568 1170 567 1170 650 1170 650 1171 567 1171 681 1171 650 1172 681 1172 652 1172 652 1173 681 1173 683 1173 652 1174 683 1174 654 1174 654 1175 683 1175 685 1175 654 1176 685 1176 656 1176 656 1177 685 1177 687 1177 656 1178 687 1178 658 1178 658 1179 687 1179 689 1179 658 1180 689 1180 660 1180 660 1181 689 1181 679 1181 660 1182 679 1182 661 1182 661 1183 679 1183 678 1183 661 1184 678 1184 709 1184 709 1185 678 1185 677 1185 561 1186 569 1186 588 1186 588 1187 569 1187 649 1187 588 1188 649 1188 619 1188 619 1189 649 1189 651 1189 619 1190 651 1190 621 1190 621 1191 651 1191 653 1191 621 1192 653 1192 623 1192 623 1193 653 1193 655 1193 623 1194 655 1194 625 1194 625 1195 655 1195 657 1195 625 1196 657 1196 627 1196 627 1197 657 1197 659 1197 627 1198 659 1198 629 1198 629 1199 659 1199 661 1199 629 1200 661 1200 630 1200 630 1201 661 1201 709 1201 494 1202 544 1202 631 1202 631 1203 544 1203 617 1203 631 1204 617 1204 710 1204 710 1205 617 1205 618 1205 710 1206 618 1206 711 1206 711 1207 618 1207 620 1207 711 1208 620 1208 712 1208 712 1209 620 1209 622 1209 712 1210 622 1210 713 1210 713 1211 622 1211 624 1211 713 1212 624 1212 714 1212 714 1213 624 1213 626 1213 714 1214 626 1214 715 1214 715 1215 626 1215 628 1215 715 1216 628 1216 716 1216 716 1217 628 1217 630 1217 716 1218 630 1218 717 1218 717 1219 630 1219 709 1219 264 1220 613 1220 707 1220 707 1221 613 1221 631 1221 707 1222 631 1222 705 1222 705 1223 631 1223 710 1223 705 1224 710 1224 703 1224 703 1225 710 1225 711 1225 703 1226 711 1226 701 1226 701 1227 711 1227 712 1227 701 1228 712 1228 699 1228 699 1229 712 1229 713 1229 699 1230 713 1230 697 1230 697 1231 713 1231 714 1231 697 1232 714 1232 695 1232 695 1233 714 1233 715 1233 695 1234 715 1234 693 1234 693 1235 715 1235 716 1235 693 1236 716 1236 691 1236 691 1237 716 1237 717 1237 691 1238 717 1238 593 1238 593 1239 717 1239 709 1239 593 1240 709 1240 594 1240 594 1241 709 1241 677 1241 594 1242 677 1242 598 1242 598 1243 677 1243 601 1243 598 1244 601 1244 595 1244 595 1245 601 1245 603 1245 595 1246 603 1246 596 1246 609 1247 608 1247 718 1247 718 1248 608 1248 612 1248 718 1249 612 1249 611 1249 719 1250 606 1250 718 1250 718 1251 606 1251 605 1251 718 1252 605 1252 609 1252 596 1253 603 1253 720 1253 720 1254 603 1254 602 1254 720 1255 602 1255 719 1255 719 1256 602 1256 600 1256 719 1257 600 1257 606 1257 721 1258 266 1258 590 1258 721 1259 590 1259 720 1259 720 1260 590 1260 597 1260 720 1261 597 1261 596 1261 721 1262 722 1262 266 1262 266 1263 722 1263 267 1263 723 1264 724 1264 725 1264 726 1265 723 1265 727 1265 727 1266 723 1266 728 1266 723 1267 725 1267 728 1267 728 1268 725 1268 729 1268 728 1269 729 1269 730 1269 730 1270 729 1270 731 1270 730 1271 731 1271 732 1271 733 1272 732 1272 731 1272 734 1273 735 1273 736 1273 736 1274 735 1274 737 1274 736 1275 737 1275 738 1275 736 1276 733 1276 734 1276 734 1277 733 1277 731 1277 734 1278 731 1278 739 1278 739 1279 731 1279 729 1279 739 1280 729 1280 740 1280 740 1281 729 1281 725 1281 740 1282 725 1282 741 1282 741 1283 725 1283 724 1283 741 1284 724 1284 742 1284 296 1285 297 1285 331 1285 274 1286 277 1286 743 1286 331 1287 297 1287 332 1287 332 1288 297 1288 298 1288 332 1289 298 1289 355 1289 331 1290 356 1290 296 1290 296 1291 356 1291 336 1291 296 1292 336 1292 295 1292 743 1293 744 1293 274 1293 274 1294 744 1294 745 1294 274 1295 745 1295 270 1295 280 1296 746 1296 277 1296 277 1297 746 1297 747 1297 277 1298 747 1298 743 1298 308 1299 293 1299 307 1299 307 1300 293 1300 305 1300 268 1301 267 1301 730 1301 298 1302 299 1302 355 1302 355 1295 299 1295 291 1295 355 1295 291 1295 745 1295 745 1295 291 1295 269 1295 745 1303 269 1303 270 1303 748 1304 726 1304 727 1304 336 1305 335 1305 295 1305 295 1306 335 1306 314 1306 295 1307 314 1307 294 1307 294 1308 314 1308 312 1308 294 1309 312 1309 292 1309 292 1310 312 1310 316 1310 292 1311 316 1311 293 1311 293 1312 316 1312 303 1312 293 1313 303 1313 305 1313 730 1314 267 1314 728 1314 728 1315 267 1315 722 1315 728 1316 722 1316 727 1316 727 1317 722 1317 749 1317 727 1318 749 1318 748 1318 730 1319 732 1319 268 1319 268 1320 732 1320 733 1320 268 1321 733 1321 287 1321 287 1322 733 1322 736 1322 287 1323 736 1323 282 1323 282 1324 736 1324 738 1324 282 1295 738 1295 280 1295 280 1325 738 1325 750 1325 280 1326 750 1326 746 1326 751 1327 752 1327 753 1327 754 1328 755 1328 756 1328 757 1329 758 1329 759 1329 760 1330 757 1330 761 1330 757 1331 759 1331 761 1331 761 1332 759 1332 762 1332 761 1333 762 1333 763 1333 763 1334 762 1334 764 1334 763 1335 764 1335 765 1335 765 1336 764 1336 766 1336 765 1337 766 1337 767 1337 767 1338 766 1338 768 1338 767 1339 768 1339 769 1339 769 1340 768 1340 770 1340 769 1341 770 1341 771 1341 756 1342 760 1342 754 1342 754 1343 760 1343 761 1343 754 1344 761 1344 772 1344 772 1345 761 1345 763 1345 772 1346 763 1346 773 1346 773 1347 763 1347 765 1347 773 1348 765 1348 774 1348 774 1349 765 1349 767 1349 774 1350 767 1350 775 1350 775 1351 767 1351 769 1351 775 1352 769 1352 776 1352 776 1353 769 1353 771 1353 776 1354 771 1354 777 1354 755 1355 754 1355 778 1355 778 1356 754 1356 772 1356 778 1357 772 1357 779 1357 779 1358 772 1358 773 1358 779 1359 773 1359 780 1359 780 1360 773 1360 774 1360 780 1361 774 1361 781 1361 781 1362 774 1362 775 1362 781 1363 775 1363 782 1363 782 1364 775 1364 776 1364 782 1365 776 1365 783 1365 783 1366 776 1366 777 1366 783 1367 777 1367 784 1367 784 1368 785 1368 783 1368 783 1369 785 1369 786 1369 783 1370 786 1370 782 1370 782 1371 786 1371 787 1371 782 1372 787 1372 781 1372 781 1373 787 1373 788 1373 781 1374 788 1374 780 1374 780 1375 788 1375 789 1375 780 1376 789 1376 779 1376 779 1377 789 1377 790 1377 779 1378 790 1378 778 1378 778 1379 790 1379 791 1379 778 1380 791 1380 755 1380 755 1381 791 1381 792 1381 755 1382 792 1382 756 1382 793 1383 794 1383 784 1383 784 1384 794 1384 795 1384 784 1385 795 1385 785 1385 796 1386 797 1386 798 1386 798 1387 797 1387 799 1387 798 1388 799 1388 800 1388 800 1389 799 1389 801 1389 800 1390 801 1390 802 1390 802 1391 801 1391 803 1391 802 1392 803 1392 804 1392 804 1393 803 1393 805 1393 804 1394 805 1394 806 1394 806 1395 805 1395 807 1395 806 1396 807 1396 808 1396 808 1397 807 1397 809 1397 808 1398 809 1398 810 1398 796 1399 811 1399 797 1399 797 1400 811 1400 812 1400 797 1401 812 1401 799 1401 799 1402 812 1402 813 1402 799 1403 813 1403 801 1403 801 1404 813 1404 814 1404 801 1405 814 1405 803 1405 803 1406 814 1406 815 1406 803 1407 815 1407 805 1407 805 1408 815 1408 816 1408 805 1409 816 1409 807 1409 807 1410 816 1410 817 1410 807 1411 817 1411 809 1411 811 1412 751 1412 812 1412 812 1413 751 1413 753 1413 812 1414 753 1414 813 1414 813 1415 753 1415 818 1415 813 1416 818 1416 814 1416 814 1417 818 1417 819 1417 814 1418 819 1418 815 1418 815 1419 819 1419 820 1419 815 1420 820 1420 816 1420 816 1421 820 1421 821 1421 816 1422 821 1422 817 1422 770 1423 810 1423 771 1423 771 1424 810 1424 809 1424 771 1425 809 1425 777 1425 777 1426 809 1426 817 1426 777 1427 817 1427 784 1427 784 1428 817 1428 821 1428 784 1429 821 1429 793 1429 793 1430 821 1430 820 1430 793 1431 820 1431 822 1431 822 1432 820 1432 819 1432 822 1433 819 1433 823 1433 823 1434 819 1434 818 1434 823 1435 818 1435 824 1435 824 1436 818 1436 753 1436 824 1437 753 1437 825 1437 825 1438 753 1438 752 1438 825 1439 752 1439 826 1439 827 1440 828 1440 829 1440 830 1441 831 1441 832 1441 832 1442 831 1442 833 1442 832 1443 833 1443 834 1443 834 1444 833 1444 835 1444 834 1445 835 1445 836 1445 837 1446 831 1446 838 1446 838 1447 831 1447 830 1447 838 1448 830 1448 839 1448 837 1449 840 1449 831 1449 831 1450 840 1450 841 1450 831 1451 841 1451 833 1451 833 1452 841 1452 827 1452 833 1453 827 1453 835 1453 835 1454 827 1454 829 1454 835 1455 829 1455 836 1455 842 1456 828 1456 843 1456 843 1457 828 1457 827 1457 843 1458 827 1458 844 1458 844 1459 827 1459 841 1459 844 1460 841 1460 845 1460 845 1461 841 1461 840 1461 845 1462 840 1462 846 1462 846 1463 840 1463 837 1463 847 1464 848 1464 849 1464 849 1465 848 1465 850 1465 849 1466 850 1466 851 1466 851 1467 850 1467 852 1467 851 1468 852 1468 853 1468 853 1469 852 1469 854 1469 853 1470 854 1470 855 1470 855 1471 854 1471 856 1471 792 1472 847 1472 756 1472 756 1473 847 1473 849 1473 756 1474 849 1474 760 1474 760 1475 849 1475 851 1475 760 1476 851 1476 757 1476 757 1477 851 1477 853 1477 757 1478 853 1478 758 1478 758 1479 853 1479 855 1479 857 1480 362 1480 310 1480 362 1480 857 1480 363 1480 340 1481 21 1481 341 1481 341 1482 21 1482 20 1482 341 1480 20 1480 323 1480 20 1483 19 1483 323 1483 323 1484 19 1484 10 1484 323 1485 10 1485 324 1485 324 1480 10 1480 9 1480 324 1486 9 1486 326 1486 326 1480 9 1480 7 1480 326 1487 7 1487 327 1487 18 1488 17 1488 342 1488 342 1480 17 1480 15 1480 342 1489 15 1489 340 1489 340 1480 15 1480 22 1480 340 1490 22 1490 21 1490 7 1491 6 1491 327 1491 327 1480 6 1480 26 1480 327 1480 26 1480 329 1480 26 1480 25 1480 329 1480 329 1480 25 1480 24 1480 329 1492 24 1492 317 1492 317 1480 24 1480 301 1480 24 1493 858 1493 301 1493 301 1494 858 1494 859 1494 301 1495 859 1495 302 1495 302 1496 859 1496 860 1496 302 1497 860 1497 309 1497 309 1498 860 1498 861 1498 309 1480 861 1480 310 1480 310 1480 861 1480 862 1480 310 1480 862 1480 857 1480 857 1499 863 1499 363 1499 363 1500 863 1500 864 1500 363 1501 864 1501 364 1501 364 1502 864 1502 865 1502 364 1480 865 1480 365 1480 365 1480 865 1480 866 1480 365 1503 866 1503 366 1503 366 1504 866 1504 867 1504 366 1505 867 1505 367 1505 367 1480 867 1480 868 1480 367 1506 868 1506 368 1506 368 1480 868 1480 369 1480 369 1480 868 1480 869 1480 369 1480 869 1480 371 1480 870 1507 871 1507 872 1507 872 1508 871 1508 873 1508 858 1509 24 1509 874 1509 874 1510 24 1510 23 1510 874 1511 23 1511 875 1511 875 1512 23 1512 51 1512 875 1513 51 1513 876 1513 876 1514 51 1514 50 1514 876 1515 50 1515 877 1515 877 1516 50 1516 878 1516 878 1517 50 1517 49 1517 878 1518 49 1518 879 1518 879 1519 49 1519 48 1519 879 1520 48 1520 880 1520 880 1521 48 1521 30 1521 880 1522 30 1522 873 1522 873 1523 30 1523 28 1523 873 1524 28 1524 872 1524 881 1525 882 1525 883 1525 320 1526 884 1526 885 1526 885 1527 883 1527 320 1527 320 1528 883 1528 886 1528 320 1529 886 1529 321 1529 321 1530 886 1531 18 1532 355 1533 745 1533 354 1533 354 1534 745 1534 887 1534 354 1535 887 1535 353 1535 353 1536 887 1536 888 1536 353 1537 888 1537 352 1537 352 1537 888 1537 889 1537 352 1538 889 1538 350 1538 350 1539 889 1539 890 1539 350 1540 890 1540 348 1540 348 1541 890 1541 891 1541 348 1542 891 1542 347 1542 347 1543 891 1543 892 1543 347 1544 892 1544 345 1544 345 1545 892 1545 893 1545 345 1546 893 1546 343 1546 343 1547 893 1547 894 1547 343 1548 894 1548 320 1548 320 1548 894 1548 895 1548 320 1549 895 1549 884 1549 14 1550 13 1550 53 1550 53 1551 13 1551 12 1551 53 1552 12 1552 11 1552 896 1553 897 1553 898 1553 899 1554 900 1554 901 1554 902 1555 885 1556 884 1557 743 1558 747 1558 903 1558 750 1559 738 1559 737 1559 745 1560 744 1560 887 1560 887 1561 744 1561 904 1561 887 1562 904 1562 888 1562 888 1563 904 1563 889 1563 889 1564 904 1564 905 1564 889 1565 905 1565 890 1565 890 1566 905 1566 906 1566 890 1567 906 1567 891 1567 891 1568 906 1568 892 1568 892 1569 906 1569 907 1569 892 1570 907 1570 893 1570 893 1571 907 1571 908 1571 893 1572 908 1572 894 1572 909 1573 910 1573 911 1573 911 1574 910 1574 912 1574 894 1575 908 1575 895 1575 895 1576 908 1576 911 1576 895 1577 911 1577 884 1577 884 1578 911 1578 912 1578 884 1579 912 1579 902 1579 913 1580 914 1580 911 1580 911 1581 914 1581 915 1581 911 1582 915 1582 909 1582 899 1583 901 1583 916 1583 742 1584 896 1584 741 1584 741 1585 896 1585 898 1585 741 1586 898 1586 740 1586 740 1587 898 1587 917 1587 740 1588 917 1588 739 1588 739 1589 917 1589 918 1589 739 1590 918 1590 734 1590 734 1591 918 1591 735 1591 735 1592 918 1592 919 1592 735 1593 919 1593 737 1593 737 1594 919 1594 920 1594 737 1595 920 1595 750 1595 750 1596 920 1596 921 1596 750 1597 921 1597 746 1597 897 1598 916 1598 898 1598 898 1599 916 1599 901 1599 898 1600 901 1600 917 1600 917 1601 901 1601 922 1601 917 1602 922 1602 918 1602 918 1603 922 1603 923 1603 918 1604 923 1604 919 1604 919 1605 923 1605 924 1605 919 1606 924 1606 920 1606 920 1607 924 1607 925 1607 920 1608 925 1608 921 1608 921 1609 925 1609 903 1609 921 1610 903 1610 746 1610 746 1611 903 1611 747 1611 900 1612 913 1612 901 1612 901 1613 913 1613 911 1613 901 1614 911 1614 922 1614 922 1615 911 1615 908 1615 922 1616 908 1616 923 1616 923 1617 908 1617 907 1617 923 1618 907 1618 924 1618 924 1619 907 1619 906 1619 924 1620 906 1620 925 1620 925 1621 906 1621 905 1621 925 1622 905 1622 903 1622 903 1623 905 1623 904 1623 903 1624 904 1624 743 1624 743 1625 904 1625 744 1625 926 1626 927 1626 928 1626 929 1627 930 1627 931 1627 931 1628 930 1628 932 1628 931 1629 932 1629 933 1629 933 1630 932 1630 934 1630 933 1631 934 1631 935 1631 936 1632 930 1632 937 1632 937 1633 930 1633 929 1633 937 1634 929 1634 938 1634 936 1635 939 1635 930 1635 930 1636 939 1636 940 1636 930 1637 940 1637 932 1637 932 1638 940 1638 926 1638 932 1639 926 1639 934 1639 934 1640 926 1640 928 1640 934 1641 928 1641 935 1641 941 1642 927 1642 942 1642 942 1643 927 1643 926 1643 942 1644 926 1644 943 1644 943 1645 926 1645 940 1645 943 1646 940 1646 944 1646 944 1647 940 1647 939 1647 944 1648 939 1648 945 1648 945 1649 939 1649 936 1649 946 1650 947 1650 948 1650 948 1651 947 1651 949 1651 948 1652 949 1652 950 1652 950 1653 949 1653 951 1653 950 1654 951 1654 952 1654 952 1655 951 1655 953 1655 952 1656 953 1656 954 1656 954 1657 953 1657 955 1657 956 1658 946 1658 957 1658 957 1659 946 1659 948 1659 957 1660 948 1660 958 1660 958 1661 948 1661 950 1661 958 1662 950 1662 959 1662 959 1663 950 1663 952 1663 959 1664 952 1664 960 1664 960 1665 952 1665 954 1665 961 1666 962 1666 963 1666 959 1667 960 1667 964 1667 958 1668 959 1668 965 1668 959 1669 964 1669 965 1669 965 1670 964 1670 966 1670 965 1671 966 1671 967 1671 967 1672 966 1672 968 1672 967 1673 968 1673 969 1673 969 1674 968 1674 970 1674 969 1675 970 1675 971 1675 971 1676 970 1676 972 1676 971 1677 972 1677 973 1677 973 1678 972 1678 974 1678 973 1679 974 1679 975 1679 975 1680 974 1680 976 1680 975 1681 976 1681 977 1681 977 1682 976 1682 978 1682 977 1683 978 1683 979 1683 979 1684 978 1684 980 1684 979 1685 980 1685 981 1685 980 1686 982 1686 981 1686 981 1687 982 1687 983 1687 981 1688 983 1688 984 1688 984 1689 983 1689 985 1689 984 1690 985 1690 986 1690 986 1691 985 1691 987 1691 986 1692 987 1692 988 1692 988 1693 987 1693 989 1693 988 1694 989 1694 990 1694 990 1695 989 1695 991 1695 991 1696 992 1696 990 1696 990 1697 992 1697 993 1697 990 1698 993 1698 988 1698 988 1699 993 1699 994 1699 988 1700 994 1700 986 1700 986 1701 994 1701 995 1701 986 1702 995 1702 984 1702 984 1703 995 1703 996 1703 984 1704 996 1704 981 1704 981 1705 996 1705 997 1705 981 1706 997 1706 979 1706 979 1707 997 1707 998 1707 979 1708 998 1708 977 1708 977 1709 998 1709 999 1709 977 1710 999 1710 975 1710 975 1711 999 1711 1000 1711 975 1712 1000 1712 973 1712 973 1713 1000 1713 1001 1713 973 1714 1001 1714 971 1714 971 1715 1001 1715 1002 1715 971 1716 1002 1716 969 1716 969 1717 1002 1717 1003 1717 969 1718 1003 1718 967 1718 967 1719 1003 1719 1004 1719 967 1720 1004 1720 965 1720 965 1721 1004 1721 1005 1721 965 1722 1005 1722 958 1722 958 1723 1005 1723 957 1723 992 1724 961 1724 993 1724 993 1725 961 1725 963 1725 993 1726 963 1726 994 1726 994 1727 963 1727 1006 1727 994 1728 1006 1728 995 1728 995 1729 1006 1729 1007 1729 995 1730 1007 1730 996 1730 996 1731 1007 1731 1008 1731 996 1732 1008 1732 997 1732 997 1733 1008 1733 1009 1733 997 1734 1009 1734 998 1734 998 1735 1009 1735 1010 1735 998 1736 1010 1736 999 1736 999 1737 1010 1737 1011 1737 999 1738 1011 1738 1000 1738 1000 1739 1011 1739 1012 1739 1000 1740 1012 1740 1001 1740 1001 1741 1012 1741 1013 1741 1001 1742 1013 1742 1002 1742 1002 1743 1013 1743 1014 1743 1002 1744 1014 1744 1003 1744 1003 1745 1014 1745 1015 1745 1003 1746 1015 1746 1004 1746 1004 1747 1015 1747 1016 1747 1004 1748 1016 1748 1005 1748 1005 1749 1016 1749 1017 1749 1005 1750 1017 1750 957 1750 957 1751 1017 1751 956 1751 956 1752 1017 1752 1018 1752 1018 1753 1017 1753 1016 1753 1018 1754 1016 1754 1019 1754 1019 1755 1016 1755 1015 1755 1019 1756 1015 1756 1020 1756 1020 1757 1015 1757 1014 1757 1020 1758 1014 1758 1021 1758 1021 1759 1014 1759 1013 1759 1021 1760 1013 1760 1022 1760 1022 1761 1013 1761 1012 1761 1022 1762 1012 1762 1023 1762 1023 1763 1012 1763 1011 1763 1023 1764 1011 1764 1024 1764 1024 1765 1011 1765 1010 1765 1024 1766 1010 1766 1025 1766 1025 1767 1010 1767 1009 1767 1025 1768 1009 1768 1026 1768 1026 1769 1009 1769 1008 1769 1026 1770 1008 1770 1027 1770 1027 1771 1008 1771 1007 1771 1027 1772 1007 1772 1028 1772 1028 1773 1007 1773 1006 1773 1028 1774 1006 1774 1029 1774 1029 1775 1006 1775 963 1775 1029 1776 963 1776 1030 1776 1030 1777 963 1777 962 1777 1030 1778 962 1778 1031 1778 1032 1779 1033 1779 1034 1779 1035 1780 1036 1780 1037 1780 1037 1781 1036 1781 1038 1781 1037 1782 1038 1782 1039 1782 1039 1783 1038 1783 1040 1783 1039 1784 1040 1784 1041 1784 1041 1785 1040 1785 1042 1785 1041 1786 1042 1786 1043 1786 1043 1787 1042 1787 1044 1787 1044 1788 1045 1788 1043 1788 1043 1789 1045 1789 1046 1789 1043 1790 1046 1790 1047 1790 1047 1791 1046 1791 1048 1791 1047 1792 1048 1792 1049 1792 1048 1793 1050 1793 1049 1793 1049 1794 1050 1794 1051 1794 1049 1795 1051 1795 1034 1795 1034 1796 1051 1796 1052 1796 1034 1797 1052 1797 1032 1797 1053 1798 1054 1798 1055 1798 1055 1799 1054 1799 1056 1799 1056 1800 1057 1800 1058 1800 1058 1801 1057 1801 1059 1801 1060 1802 1061 1802 1062 1802 1062 1803 1061 1803 1063 1803 1064 1804 1065 1804 1066 1804 1067 1805 1068 1805 1069 1805 1069 1806 1068 1806 1070 1806 1071 1807 1072 1807 1073 1807 1073 1808 1072 1808 1074 1808 1073 1809 1074 1809 1075 1809 1075 1810 1074 1810 1076 1810 1075 1811 1076 1811 1077 1811 1077 1812 1076 1812 1078 1812 1077 1813 1078 1813 1079 1813 1079 1814 1078 1814 1080 1814 1079 1815 1080 1815 1070 1815 1070 1816 1080 1816 1081 1816 1070 1817 1081 1817 1069 1817 1071 1818 1073 1818 1082 1818 1082 1819 1073 1819 1083 1819 1082 1820 1083 1820 1084 1820 1084 1821 1083 1821 1058 1821 1084 1822 1058 1822 1085 1822 1085 1823 1058 1823 1059 1823 1085 1824 1059 1824 1086 1824 1068 1825 1087 1825 1070 1825 1070 1826 1087 1826 1088 1826 1070 1827 1088 1827 1079 1827 1079 1828 1088 1828 1089 1828 1079 1829 1089 1829 1077 1829 1077 1830 1089 1830 1090 1830 1077 1831 1090 1831 1075 1831 1075 1832 1090 1832 1091 1832 1075 1833 1091 1833 1073 1833 1073 1834 1091 1834 1092 1834 1073 1835 1092 1835 1083 1835 1083 1836 1092 1836 1093 1836 1083 1837 1093 1837 1058 1837 1058 1838 1093 1838 1055 1838 1058 1839 1055 1839 1056 1839 1087 1840 1065 1840 1088 1840 1088 1841 1065 1841 1064 1841 1088 1842 1064 1842 1089 1842 1089 1843 1064 1843 1094 1843 1089 1844 1094 1844 1090 1844 1090 1845 1094 1845 1095 1845 1090 1846 1095 1846 1091 1846 1091 1847 1095 1847 1096 1847 1091 1848 1096 1848 1092 1848 1092 1849 1096 1849 1097 1849 1092 1850 1097 1850 1093 1850 1093 1851 1097 1851 1098 1851 1093 1852 1098 1852 1055 1852 1055 1853 1098 1853 1062 1853 1055 1854 1062 1854 1053 1854 1053 1855 1062 1855 1063 1855 1099 1856 1060 1856 1100 1856 1100 1857 1060 1857 1062 1857 1100 1858 1062 1858 1101 1858 1101 1859 1062 1859 1098 1859 1101 1860 1098 1860 1102 1860 1102 1861 1098 1861 1097 1861 1102 1862 1097 1862 1103 1862 1103 1863 1097 1863 1096 1863 1103 1864 1096 1864 1104 1864 1104 1865 1096 1865 1095 1865 1104 1866 1095 1866 1105 1866 1105 1867 1095 1867 1094 1867 1105 1868 1094 1868 1106 1868 1106 1869 1094 1869 1064 1869 1106 1870 1064 1870 1107 1870 1107 1871 1064 1871 1066 1871 1107 1872 1066 1872 1108 1872 1109 1873 1110 1873 1111 1873 1112 1874 1113 1874 1114 1874 1115 1875 1087 1875 1068 1875 1066 1876 1065 1876 1116 1876 1116 1877 1065 1877 1087 1877 1109 1878 1111 1878 1117 1878 1118 1879 1119 1879 1120 1879 1121 1880 1122 1880 1123 1880 1124 1881 1125 1881 1126 1881 1127 1882 1128 1882 1122 1882 1129 1883 1130 1883 1131 1883 1131 1884 1130 1884 1132 1884 1131 1885 1132 1885 1121 1885 1121 1886 1132 1886 1127 1886 1121 1887 1127 1887 1122 1887 1113 1888 1133 1888 1114 1888 1114 1889 1133 1889 1134 1889 1114 1890 1134 1890 1135 1890 1135 1891 1134 1891 1136 1891 1135 1892 1136 1892 1137 1892 1137 1893 1136 1893 1138 1893 1137 1894 1138 1894 1139 1894 1139 1895 1138 1895 1140 1895 1139 1896 1140 1896 1129 1896 1129 1897 1140 1897 1141 1897 1129 1898 1141 1898 1130 1898 1108 1899 1066 1899 1142 1899 1142 1900 1066 1900 1116 1900 1142 1901 1116 1901 1143 1901 1143 1902 1116 1902 1144 1902 1120 1903 1117 1903 1118 1903 1118 1904 1117 1904 1111 1904 1118 1905 1111 1905 1145 1905 1145 1906 1111 1906 1146 1906 1145 1907 1146 1907 1147 1907 1147 1908 1146 1908 1148 1908 1147 1909 1148 1909 1149 1909 1149 1910 1148 1910 1150 1910 1149 1911 1150 1911 1151 1911 1151 1912 1150 1912 1152 1912 1151 1913 1152 1913 1144 1913 1144 1914 1152 1914 1153 1914 1144 1915 1153 1915 1143 1915 1087 1916 1115 1916 1116 1916 1116 1917 1115 1917 1154 1917 1116 1918 1154 1918 1144 1918 1144 1919 1154 1919 1155 1919 1144 1920 1155 1920 1151 1920 1151 1921 1155 1921 1156 1921 1151 1922 1156 1922 1149 1922 1149 1923 1156 1923 1157 1923 1149 1924 1157 1924 1147 1924 1147 1925 1157 1925 1158 1925 1147 1926 1158 1926 1145 1926 1145 1927 1158 1927 1125 1927 1145 1928 1125 1928 1118 1928 1118 1929 1125 1929 1124 1929 1118 1930 1124 1930 1119 1930 1067 1931 1112 1931 1068 1931 1068 1932 1112 1932 1114 1932 1068 1933 1114 1933 1115 1933 1115 1934 1114 1934 1135 1934 1115 1935 1135 1935 1154 1935 1154 1936 1135 1936 1137 1936 1154 1937 1137 1937 1155 1937 1155 1938 1137 1938 1139 1938 1155 1939 1139 1939 1156 1939 1156 1940 1139 1940 1129 1940 1156 1941 1129 1941 1157 1941 1157 1942 1129 1942 1131 1942 1157 1943 1131 1943 1158 1943 1158 1944 1131 1944 1121 1944 1158 1945 1121 1945 1125 1945 1125 1946 1121 1946 1123 1946 1125 1947 1123 1947 1126 1947 1159 1948 1160 1948 1161 1948 1162 1949 1163 1949 1164 1949 1165 1950 1166 1950 1167 1950 1047 1951 1168 1951 1043 1951 1043 1952 1168 1952 1169 1952 1169 1953 1168 1953 1170 1953 1170 1954 1168 1954 1171 1954 1170 1955 1171 1955 1172 1955 1172 1956 1171 1956 1173 1956 1173 1957 1171 1957 1167 1957 1173 1958 1167 1958 1174 1958 1166 1959 1175 1959 1167 1959 1167 1960 1175 1960 1176 1960 1167 1961 1176 1961 1174 1961 1174 1962 1176 1962 1177 1962 1162 1963 1164 1963 1178 1963 1179 1964 1034 1964 1033 1964 1033 1965 1180 1965 1179 1965 1179 1966 1180 1966 1181 1966 1179 1967 1181 1967 1182 1967 1182 1968 1181 1968 1183 1968 1182 1969 1183 1969 1161 1969 1161 1970 1183 1970 1184 1970 1161 1971 1184 1971 1159 1971 1049 1972 1034 1972 1185 1972 1185 1973 1034 1973 1179 1973 1185 1974 1179 1974 1186 1974 1186 1975 1179 1975 1182 1975 1186 1976 1182 1976 1164 1976 1164 1977 1182 1977 1161 1977 1164 1978 1161 1978 1178 1978 1178 1979 1161 1979 1160 1979 1047 1980 1049 1980 1168 1980 1168 1981 1049 1981 1185 1981 1168 1982 1185 1982 1171 1982 1171 1983 1185 1983 1186 1983 1171 1984 1186 1984 1167 1984 1167 1985 1186 1985 1164 1985 1167 1986 1164 1986 1165 1986 1165 1987 1164 1987 1163 1987 1187 1988 1188 1988 1189 1988 1190 1989 1191 1989 1187 1989 1192 1990 1193 1990 1194 1990 1194 1991 1193 1991 1195 1991 1194 1992 1195 1992 1196 1992 1197 1993 1198 1993 1199 1993 1199 1994 1198 1994 1200 1994 1199 1995 1200 1995 1201 1995 1177 1996 1197 1996 1174 1996 1174 1997 1197 1997 1199 1997 1174 1998 1199 1998 1173 1998 1173 1999 1199 1999 1202 1999 1173 2000 1202 2000 1172 2000 1172 2001 1202 2001 1170 2001 1170 2002 1202 2002 1203 2002 1170 2003 1203 2003 1169 2003 1204 2004 1039 2004 1041 2004 1205 2005 1035 2005 1037 2005 1187 2006 1189 2006 1190 2006 1190 2007 1189 2007 1206 2007 1190 2008 1206 2008 1207 2008 1207 2009 1206 2009 1205 2009 1207 2010 1205 2010 1208 2010 1208 2011 1205 2011 1037 2011 1208 2012 1037 2012 1039 2012 1039 2013 1204 2013 1208 2013 1208 2014 1204 2014 1209 2014 1208 2015 1209 2015 1207 2015 1207 2016 1209 2016 1194 2016 1207 2017 1194 2017 1190 2017 1190 2018 1194 2018 1196 2018 1190 2019 1196 2019 1191 2019 1043 2020 1169 2020 1041 2020 1041 2021 1169 2021 1203 2021 1041 2022 1203 2022 1204 2022 1204 2023 1203 2023 1202 2023 1204 2024 1202 2024 1209 2024 1209 2025 1202 2025 1199 2025 1209 2026 1199 2026 1194 2026 1194 2027 1199 2027 1201 2027 1194 2028 1201 2028 1192 2028 1210 2029 1211 2029 1212 2029 1210 2030 1212 2030 1213 2030 1213 2031 1212 2031 1214 2031 1213 2032 1214 2032 1215 2032 1216 2033 1217 2033 1218 2033 1218 2034 1217 2034 1219 2034 1218 2035 1219 2035 1220 2035 1220 2036 1221 2036 1218 2036 1218 2037 1221 2037 1222 2037 1218 2038 1222 2038 1223 2038 1224 2039 1225 2039 1218 2039 1218 2040 1225 2040 1226 2040 1218 2041 1226 2041 1227 2041 1227 2042 1228 2042 1218 2042 1218 2043 1228 2043 1229 2043 1218 2044 1229 2044 1230 2044 1230 2045 1231 2045 1218 2045 1218 2046 1231 2046 1232 2046 1218 2047 1232 2047 1216 2047 1223 2048 1214 2048 1218 2048 1218 2049 1214 2049 1212 2049 1218 2050 1212 2050 1224 2050 1224 2051 1212 2051 1211 2051 1224 2052 1211 2052 371 2052 1233 2053 862 2053 1234 2053 1234 2054 862 2054 861 2054 371 2055 869 2055 1224 2055 1224 2056 869 2056 868 2056 1224 2057 868 2057 1235 2057 868 2058 867 2058 1235 2058 1235 2059 867 2059 866 2059 1235 2060 866 2060 865 2060 865 2061 864 2061 1235 2061 1235 2062 864 2062 863 2062 1235 2063 863 2063 1233 2063 1233 2064 863 2064 857 2064 1233 2065 857 2065 862 2065 1236 2066 1237 2066 1238 2066 1238 2067 1237 2067 1239 2067 1238 2068 1239 2068 1240 2068 1241 2069 1242 2069 1243 2069 1244 2070 1245 2070 1240 2070 1246 2071 1247 2071 1248 2071 1248 2072 1249 2072 1246 2072 1246 2073 1249 2073 1250 2073 1246 2074 1250 2074 1251 2074 1251 2075 1252 2075 1246 2075 1246 2076 1252 2076 1253 2076 1246 2077 1253 2077 1254 2077 1244 2078 1240 2078 1254 2078 1254 2079 1240 2079 1239 2079 1254 2080 1239 2080 1246 2080 1246 2081 1239 2081 1237 2081 1246 2082 1237 2082 1255 2082 1255 2083 1256 2083 1246 2083 1246 2084 1256 2084 1257 2084 1246 2085 1257 2085 1258 2085 1258 2086 1259 2086 1246 2086 1246 2087 1259 2087 1260 2087 1246 2088 1260 2088 1247 2088 1243 2089 1261 2089 1241 2089 1241 2090 1261 2090 1262 2090 1241 2091 1262 2091 1244 2091 1244 2092 1262 2092 1263 2092 1244 2093 1263 2093 1245 2093 1264 2094 1265 2094 415 2094 1266 2095 1267 2095 517 2095 517 2096 1267 2096 587 2096 1268 2097 422 2097 1269 2097 1269 2098 422 2098 423 2098 1269 2099 423 2099 1270 2099 1270 2100 423 2100 424 2100 483 2101 1271 2101 530 2101 530 2102 1271 2102 1272 2102 415 2103 1265 2103 410 2103 410 2104 1265 2104 1273 2104 410 2105 1273 2105 408 2105 408 2106 1273 2106 483 2106 483 2107 1273 2107 1274 2107 483 2108 1274 2108 1271 2108 517 2109 515 2109 1266 2109 1266 2110 515 2110 500 2110 1266 2111 500 2111 1275 2111 1275 2112 500 2112 519 2112 1275 2113 519 2113 1276 2113 1276 2114 519 2114 521 2114 1276 2115 521 2115 1277 2115 1277 2116 521 2116 523 2116 1277 2117 523 2117 1278 2117 1278 2118 523 2118 525 2118 1278 2119 525 2119 1279 2119 1279 2120 525 2120 527 2120 1279 2121 527 2121 1272 2121 1272 2122 527 2122 528 2122 1272 2123 528 2123 530 2123 415 2124 413 2124 1264 2124 1264 2125 413 2125 412 2125 1264 2126 412 2126 1280 2126 1280 2127 412 2127 390 2127 1280 2128 390 2128 1281 2128 1281 2129 390 2129 420 2129 1281 2130 420 2130 1282 2130 1267 2131 1283 2131 587 2131 587 2132 1283 2132 1284 2132 587 2133 1284 2133 506 2133 506 2134 1284 2134 1285 2134 1215 2135 374 2135 1213 2135 1213 2136 374 2136 373 2136 1213 2137 373 2137 1210 2137 373 2138 376 2138 1210 2138 1210 2139 376 2139 372 2139 1210 2140 372 2140 1211 2140 1211 72 372 72 371 72 420 2141 419 2141 1282 2141 1282 2142 419 2142 417 2142 1282 2143 417 2143 1286 2143 1286 2144 417 2144 387 2144 1286 2145 387 2145 1287 2145 1287 2146 387 2146 389 2146 1287 2147 389 2147 1288 2147 1288 2148 389 2148 449 2148 1288 2149 449 2149 1289 2149 1289 2150 449 2150 384 2150 1289 2151 384 2151 1290 2151 1290 2152 384 2152 386 2152 1290 2153 386 2153 1291 2153 1291 2154 386 2154 430 2154 1291 2155 430 2155 1268 2155 1268 2156 430 2156 429 2156 1268 2157 429 2157 422 2157 1285 2158 1292 2158 506 2158 506 2159 1292 2159 1293 2159 506 2160 1293 2160 507 2160 507 2161 1293 2161 509 2161 1215 2162 1294 2162 374 2162 374 2163 1294 2163 1295 2163 374 2164 1295 2164 424 2164 424 2165 1295 2165 1296 2165 424 2166 1296 2166 1270 2166 1293 2167 1297 2167 509 2167 509 2168 1297 2168 1298 2168 509 2169 1298 2169 511 2169 511 2170 1298 2170 1299 2170 511 2171 1299 2171 503 2171 503 2172 1299 2172 1300 2172 503 2173 1300 2173 504 2173 504 2174 1300 2174 1236 2174 504 2175 1236 2175 610 2175 610 2176 1236 2176 1238 2176 610 2177 1238 2177 611 2177 749 72 722 72 1243 72 1243 72 722 72 721 72 1243 72 721 72 1261 72 1261 2178 721 2178 720 2178 1261 2179 720 2179 1262 2179 1262 72 720 72 719 72 1262 2180 719 2180 1263 2180 1263 72 719 72 718 72 1263 2181 718 2181 1245 2181 1245 72 718 72 611 72 1245 2182 611 2182 1240 2182 1240 2183 611 2183 1238 2183 749 2184 1301 2184 748 2184 726 2185 748 2185 723 2185 723 2186 748 2186 1302 2186 723 2187 1302 2187 724 2187 724 2188 1302 2188 1303 2188 724 72 1303 72 742 72 1304 2189 912 2189 910 2189 1304 2190 910 2190 1305 2190 1303 2191 1306 2191 742 2191 742 72 1306 72 1307 72 742 2192 1307 2192 896 2192 896 72 1307 72 1308 72 896 2193 1308 2193 897 2193 897 72 1308 72 1309 72 897 72 1309 72 916 72 916 2194 1309 2194 1310 2194 916 72 1310 72 899 72 899 72 1310 72 1311 72 899 2195 1311 2195 900 2195 900 2196 1311 2196 1312 2196 900 72 1312 72 913 72 913 72 1312 72 1313 72 913 2197 1313 2197 914 2197 914 72 1313 72 1314 72 914 72 1314 72 915 72 915 72 1314 72 1305 72 915 2198 1305 2198 909 2198 909 72 1305 72 910 72 1315 2199 1316 2199 1317 2199 1317 2200 1316 2200 1318 2200 1306 2201 1303 2201 1319 2201 1319 2202 1303 2202 1320 2202 1321 2203 1322 2203 1320 2203 1320 2204 1322 2204 1323 2204 1320 2205 1323 2205 1319 2205 1318 2206 1324 2206 1317 2206 1317 2207 1324 2207 1325 2207 1317 2208 1325 2208 1326 2208 1326 2209 1325 2209 1327 2209 1326 2210 1327 2210 1328 2210 1328 2211 1327 2211 1329 2211 1328 2212 1329 2212 1321 2212 1321 2213 1329 2213 1330 2213 1321 2214 1330 2214 1322 2214 945 2215 1331 2215 1332 2215 1333 2216 1334 2216 1335 2216 1333 2217 1335 2217 1336 2217 1336 2218 1335 2218 1337 2218 1336 2219 1337 2219 1338 2219 1338 2220 1337 2220 1332 2220 1338 2221 1332 2221 1339 2221 1339 2222 1332 2222 1331 2222 1339 2223 1331 2223 1340 2223 945 2224 1332 2224 944 2224 944 2225 1332 2225 1337 2225 944 2226 1337 2226 943 2226 943 2227 1337 2227 1335 2227 943 2228 1335 2228 942 2228 942 2229 1335 2229 1334 2229 942 2230 1334 2230 941 2230 1341 2231 1153 2231 1342 2231 1342 2232 1153 2232 1152 2232 1342 2233 1152 2233 1343 2233 759 2234 758 2234 1150 2234 1150 2235 758 2235 855 2235 855 2236 856 2236 1150 2236 1150 2237 856 2237 1344 2237 1150 2238 1344 2238 836 2238 836 2239 829 2239 1150 2239 1150 2240 829 2240 828 2240 1150 2241 828 2241 842 2241 1343 2242 1152 2242 1345 2242 1345 2243 1152 2243 1150 2243 1345 2244 1150 2244 1346 2244 1347 2245 1348 2245 1346 2245 1346 2246 1348 2246 1349 2246 1349 2247 1350 2247 1346 2247 1346 2248 1350 2248 1351 2248 1346 2249 1351 2249 1345 2249 842 2250 1352 2250 1150 2250 1150 2251 1352 2251 1353 2251 1150 2252 1353 2252 1346 2252 1346 2253 1353 2253 1354 2253 1346 2254 1354 2254 1347 2254 1355 2255 1356 2255 1357 2255 1357 2256 1356 2256 1358 2256 1356 2257 796 2257 1358 2257 1358 2258 796 2258 798 2258 1358 2259 798 2259 1359 2259 1359 2260 798 2260 800 2260 1359 2261 800 2261 802 2261 802 2262 804 2262 1359 2262 1359 2263 804 2263 806 2263 1359 2264 806 2264 1110 2264 1110 2265 806 2265 808 2265 1110 2266 808 2266 1111 2266 1111 2267 808 2267 810 2267 810 2268 770 2268 1111 2268 1111 2269 770 2269 768 2269 1111 2270 768 2270 766 2270 1150 2271 1148 2271 759 2271 759 2272 1148 2272 1146 2272 759 2273 1146 2273 762 2273 762 2274 1146 2274 1111 2274 762 2275 1111 2275 764 2275 764 2276 1111 2276 766 2276 1341 2277 1360 2277 1153 2277 1153 2278 1360 2278 1361 2278 1153 2279 1361 2279 1143 2279 1143 2280 1361 2280 1362 2280 1143 2281 1362 2281 1142 2281 1142 2282 1362 2282 1363 2282 1142 2283 1363 2283 1108 2283 1108 2284 1363 2284 1107 2284 1107 2285 1363 2285 1364 2285 1107 2286 1364 2286 1106 2286 1106 2287 1364 2287 1365 2287 1106 2288 1365 2288 1105 2288 1365 2289 1366 2289 1105 2289 1105 2290 1366 2290 1367 2290 1105 2291 1367 2291 1368 2291 1368 2292 1369 2292 1105 2292 1105 2293 1369 2293 1370 2293 1105 2294 1370 2294 1104 2294 1371 2295 1372 2295 1103 2295 1104 2296 1370 2296 1103 2296 1103 2297 1370 2297 1373 2297 1103 2298 1373 2298 1371 2298 1372 2299 1374 2299 1103 2299 1103 2300 1374 2300 1375 2300 1103 2301 1375 2301 1376 2301 938 2302 1377 2302 1103 2302 1103 2303 1377 2303 947 2303 1103 2304 947 2304 946 2304 1376 2305 1340 2305 1103 2305 1103 2306 1340 2306 1331 2306 1103 2307 1331 2307 945 2307 945 2308 936 2308 1103 2308 1103 2309 936 2309 937 2309 1103 2310 937 2310 938 2310 1100 2311 1101 2311 1019 2311 1019 2312 1101 2312 1018 2312 946 2313 956 2313 1103 2313 1103 2314 956 2314 1018 2314 1103 2315 1018 2315 1102 2315 1102 2316 1018 2316 1101 2316 1019 2317 1020 2317 1100 2317 1100 2318 1020 2318 1021 2318 1100 2319 1021 2319 1022 2319 1022 2320 1023 2320 1100 2320 1100 2321 1023 2321 1024 2321 1100 2322 1024 2322 1099 2322 1099 2323 1024 2323 1025 2323 1099 2324 1025 2324 1378 2324 1378 2325 1025 2325 1026 2325 1378 2326 1026 2326 1027 2326 1030 2327 1379 2327 1029 2327 1029 2328 1379 2328 1378 2328 1029 2329 1378 2329 1028 2329 1028 2330 1378 2330 1027 2330 1030 2331 1031 2331 1379 2331 1379 2332 1031 2332 1380 2332 1379 2333 1380 2333 1381 2333 1381 2334 1380 2334 1382 2334 846 2335 1383 2335 1384 2335 1353 2336 1352 2336 1385 2336 1353 2337 1385 2337 1386 2337 1386 2338 1385 2338 1387 2338 1386 2339 1387 2339 1388 2339 1388 2340 1387 2340 1384 2340 1388 2341 1384 2341 1389 2341 1389 2342 1384 2342 1383 2342 1389 2343 1383 2343 1390 2343 846 2344 1384 2344 845 2344 845 2345 1384 2345 1387 2345 845 2346 1387 2346 844 2346 844 2347 1387 2347 1385 2347 844 2348 1385 2348 843 2348 843 2349 1385 2349 1352 2349 843 2350 1352 2350 842 2350 1391 2351 1392 2351 1393 2351 1394 2352 1395 2352 1396 2352 1397 2353 1398 2353 1399 2353 1399 2354 1398 2354 1393 2354 1391 2355 1393 2355 1396 2355 1396 2356 1393 2356 1398 2356 1396 2357 1398 2357 1394 2357 1394 2358 1398 2358 1397 2358 1394 2359 1397 2359 1355 2359 1400 2360 1401 2360 826 2360 826 2361 752 2361 1400 2361 1400 2362 752 2362 751 2362 1400 2363 751 2363 1356 2363 1356 2364 751 2364 811 2364 1356 2365 811 2365 796 2365 1399 2366 1401 2366 1397 2366 1397 2367 1401 2367 1400 2367 1397 2368 1400 2368 1355 2368 1355 2369 1400 2369 1356 2369 794 2370 793 2370 1402 2370 1402 2371 793 2371 822 2371 1402 2372 822 2372 823 2372 823 2373 824 2373 1402 2373 1402 2374 824 2374 825 2374 1402 2375 825 2375 826 2375 1402 2376 1403 2376 794 2376 794 2377 1403 2377 1404 2377 794 2378 1404 2378 795 2378 795 2379 1404 2379 785 2379 789 2380 788 2380 1405 2380 1405 2381 788 2381 787 2381 1405 2382 787 2382 1404 2382 1404 2383 787 2383 786 2383 1404 2384 786 2384 785 2384 791 2385 790 2385 1406 2385 1406 2386 790 2386 789 2386 1406 2387 789 2387 1407 2387 1407 2388 789 2388 1405 2388 1407 2389 1405 2389 1408 2389 1408 2390 1405 2390 1404 2390 1408 2391 1404 2391 1409 2391 1409 2392 1404 2392 1403 2392 1409 2393 1410 2393 1408 2393 1408 2394 1410 2394 1411 2394 1408 2395 1411 2395 1407 2395 1407 2396 1411 2396 1412 2396 1407 2397 1412 2397 1406 2397 1406 2398 1412 2398 1413 2398 1406 2399 1413 2399 791 2399 791 2400 1413 2400 1414 2400 791 2401 1414 2401 792 2401 1344 2402 856 2402 1415 2402 1415 2403 856 2403 854 2403 1415 2404 854 2404 1416 2404 1416 2405 854 2405 852 2405 1416 2406 852 2406 1417 2406 1417 2407 852 2407 850 2407 1417 2408 850 2408 1418 2408 1418 2409 850 2409 848 2409 836 2410 1344 2410 834 2410 834 2411 1344 2411 1415 2411 834 2412 1415 2412 832 2412 832 2413 1415 2413 1416 2413 832 2414 1416 2414 830 2414 830 2415 1416 2415 1417 2415 830 2416 1417 2416 839 2416 839 2417 1417 2417 1418 2417 838 2418 839 2418 1419 2418 838 2419 1419 2419 837 2419 837 2420 1419 2420 1420 2420 837 2421 1420 2421 846 2421 847 2422 792 2422 1421 2422 1421 2423 792 2423 1414 2423 1421 2424 1414 2424 1422 2424 1422 2425 1414 2425 1413 2425 1422 2426 1413 2426 1423 2426 1423 2427 1413 2427 1412 2427 1423 2428 1412 2428 1424 2428 1424 2429 1412 2429 1411 2429 1424 2430 1411 2430 1425 2430 1425 2431 1411 2431 1410 2431 848 2432 847 2432 1426 2432 1426 2433 847 2433 1421 2433 1426 2434 1421 2434 1427 2434 1427 2435 1421 2435 1422 2435 1427 2436 1422 2436 1428 2436 1428 2437 1422 2437 1423 2437 1428 2438 1423 2438 1429 2438 1429 2439 1423 2439 1424 2439 1429 2440 1424 2440 1430 2440 1430 2441 1424 2441 1425 2441 1431 2442 871 2442 1432 2442 1432 2443 871 2443 870 2443 1432 1295 870 1295 1433 1295 873 2444 871 2444 1434 2444 876 2445 877 2445 1435 2445 1436 2446 860 2446 859 2446 876 2447 1435 2447 875 2447 875 2448 1435 2448 1436 2448 875 2449 1436 2449 874 2449 874 2450 1436 2450 859 2450 874 2451 859 2451 858 2451 1437 2452 1438 2452 877 2452 877 2453 1438 2453 1439 2453 877 2454 1439 2454 1435 2454 877 2455 878 2455 1437 2455 1437 2456 878 2456 879 2456 1437 2457 879 2457 1434 2457 1434 2458 879 2458 880 2458 1434 2459 880 2459 873 2459 1234 2460 861 2460 860 2460 860 2461 1436 2461 1234 2461 1234 2462 1436 2462 1435 2462 1234 2463 1435 2463 1439 2463 1433 72 870 72 1440 72 1440 72 870 72 872 72 1440 2464 872 2464 1441 2464 1441 72 872 72 28 72 1441 72 28 72 27 72 1442 2465 882 2465 1443 2465 1443 2466 882 2466 881 2466 881 2467 883 2467 1443 2467 1443 2468 883 2468 885 2468 885 2469 902 2469 1443 2469 1443 2470 902 2470 1444 2470 1443 2471 1444 2471 1445 2471 1445 2472 1444 2472 1446 2472 1445 2473 1446 2473 1447 2473 1446 2474 1448 2474 1447 2474 1447 2475 1448 2475 1449 2475 1447 2476 1449 2476 1450 2476 1449 2477 1451 2477 1450 2477 1450 2478 1451 2478 1452 2478 1450 2479 1452 2479 1453 2479 882 2480 1442 2480 1454 2480 886 2481 883 2481 882 2481 18 2482 886 2482 55 2482 886 2480 882 2480 55 2480 55 2483 882 2483 1454 2483 55 2484 1454 2484 58 2484 18 2485 55 2485 16 2485 16 2486 55 2486 53 2486 16 2487 53 2487 11 2487 1316 72 1455 72 1318 72 1318 2488 1455 2488 1456 2488 1318 2489 1456 2489 1324 2489 1324 72 1456 72 1457 72 1309 2490 1308 2490 1458 2490 1307 2491 1306 2491 1319 2491 1324 2492 1457 2492 1459 2492 1330 2493 1329 2493 1460 2493 1460 2494 1329 2494 1327 2494 1460 2495 1327 2495 1461 2495 1461 2496 1327 2496 1325 2496 1461 2497 1325 2497 1462 2497 1330 2498 1460 2498 1322 2498 1322 2499 1460 2499 1463 2499 1322 2500 1463 2500 1323 2500 1323 2501 1463 2501 1458 2501 1323 2502 1458 2502 1319 2502 1319 2503 1458 2503 1308 2503 1319 2504 1308 2504 1307 2504 1464 2505 1310 2505 1309 2505 1313 2506 1312 2506 1464 2506 1464 2507 1312 2507 1311 2507 1464 2508 1311 2508 1310 2508 1305 2509 1314 2509 1465 2509 1465 2510 1314 2510 1313 2510 902 2511 912 2511 1444 2511 1444 2512 912 2512 1304 2512 1444 2513 1304 2513 1305 2513 1305 2514 1465 2514 1444 2514 1444 2515 1465 2515 1466 2515 1444 2516 1466 2516 1446 2516 1446 2517 1466 2517 1448 2517 1448 2518 1466 2518 1467 2518 1448 2519 1467 2519 1449 2519 1449 2520 1467 2520 1468 2520 1449 2521 1468 2521 1451 2521 1451 2522 1468 2522 1469 2522 1451 2523 1469 2523 1452 2523 1470 2524 1471 2524 1472 2524 1324 2525 1459 2525 1325 2525 1325 2526 1459 2526 1473 2526 1325 2527 1473 2527 1462 2527 1462 2528 1473 2528 1474 2528 1462 2529 1474 2529 1475 2529 1313 2530 1464 2530 1465 2530 1465 2531 1464 2531 1476 2531 1465 2532 1476 2532 1466 2532 1466 2533 1476 2533 1477 2533 1466 2534 1477 2534 1467 2534 1467 2535 1477 2535 1470 2535 1467 2536 1470 2536 1468 2536 1468 2537 1470 2537 1472 2537 1468 2538 1472 2538 1469 2538 1309 2539 1458 2539 1464 2539 1464 2540 1458 2540 1463 2540 1464 2541 1463 2541 1476 2541 1476 2542 1463 2542 1460 2542 1476 2543 1460 2543 1477 2543 1477 2544 1460 2544 1461 2544 1477 2545 1461 2545 1470 2545 1470 2546 1461 2546 1462 2546 1470 2547 1462 2547 1471 2547 1471 2548 1462 2548 1475 2548 1471 2549 1475 2549 1472 2549 941 2550 1478 2550 927 2550 927 2551 1478 2551 1479 2551 927 2552 1479 2552 928 2552 928 2553 1479 2553 935 2553 1480 2554 955 2554 1481 2554 1481 2555 955 2555 953 2555 1481 2556 953 2556 1482 2556 1482 2557 953 2557 951 2557 1482 2558 951 2558 1483 2558 1483 2559 951 2559 949 2559 1483 2560 949 2560 1377 2560 1377 2561 949 2561 947 2561 935 2562 1480 2562 933 2562 933 2563 1480 2563 1481 2563 933 2564 1481 2564 931 2564 931 2565 1481 2565 1482 2565 931 2566 1482 2566 929 2566 929 2567 1482 2567 1483 2567 929 2568 1483 2568 938 2568 938 2569 1483 2569 1377 2569 954 2570 955 2570 1484 2570 1485 2571 1486 2571 1487 2571 1487 2572 1486 2572 1488 2572 1487 2573 1488 2573 960 2573 1489 2574 1490 2574 1485 2574 1485 2575 1490 2575 1491 2575 1485 2576 1491 2576 1486 2576 1492 2577 1493 2577 1494 2577 1494 2578 1493 2578 1495 2578 1494 2579 1495 2579 1489 2579 1489 2580 1495 2580 1496 2580 1489 2581 1496 2581 1490 2581 1497 2582 1492 2582 1498 2582 1498 2583 1492 2583 1494 2583 1498 2584 1494 2584 1499 2584 1499 2585 1494 2585 1489 2585 1499 2586 1489 2586 1500 2586 1500 2587 1489 2587 1485 2587 1500 2588 1485 2588 1484 2588 1484 2589 1485 2589 1487 2589 1484 2590 1487 2590 954 2590 954 2591 1487 2591 960 2591 1501 2592 1502 2592 1503 2592 968 2593 966 2593 1504 2593 1504 2594 966 2594 964 2594 960 2595 1488 2595 964 2595 964 2596 1488 2596 1486 2596 964 2597 1486 2597 1504 2597 980 2598 978 2598 1505 2598 1505 2599 978 2599 976 2599 1505 2600 976 2600 974 2600 985 2601 983 2601 1506 2601 987 2602 985 2602 989 2602 989 2603 985 2603 1506 2603 989 2604 1506 2604 991 2604 1507 2605 1505 2605 1508 2605 1508 2606 1505 2606 974 2606 1508 2607 974 2607 972 2607 1507 2608 1501 2608 1505 2608 1505 2609 1501 2609 1503 2609 1505 2610 1503 2610 980 2610 980 2611 1503 2611 1506 2611 980 2612 1506 2612 982 2612 982 2613 1506 2613 983 2613 1486 2614 1491 2614 1504 2614 1504 2615 1491 2615 1507 2615 1504 2616 1507 2616 968 2616 968 2617 1507 2617 1508 2617 968 2618 1508 2618 970 2618 970 2619 1508 2619 972 2619 1493 2620 1502 2620 1495 2620 1495 2621 1502 2621 1501 2621 1495 2622 1501 2622 1496 2622 1496 2623 1501 2623 1507 2623 1496 2624 1507 2624 1490 2624 1490 2625 1507 2625 1491 2625 991 2626 1509 2626 992 2626 992 2627 1509 2627 1510 2627 992 2628 1510 2628 961 2628 961 2629 1510 2629 962 2629 962 2630 1510 2630 1380 2630 962 2631 1380 2631 1031 2631 1382 2632 1380 2632 1511 2632 1511 2633 1380 2633 1510 2633 1511 2634 1510 2634 1512 2634 1512 2635 1510 2635 1509 2635 1513 2636 1514 2636 1515 2636 1515 2637 1514 2637 1516 2637 1516 2638 1514 2638 1517 2638 1517 2639 1514 2639 1518 2639 1517 2640 1518 2640 1519 2640 1512 2641 1518 2641 1511 2641 1511 2642 1518 2642 1514 2642 1511 2643 1514 2643 1382 2643 1382 2644 1514 2644 1513 2644 1520 2645 1521 2645 1522 2645 1519 2646 1523 2646 1517 2646 1517 2647 1523 2647 1516 2647 1521 2648 1520 2648 1524 2648 1520 2649 1525 2649 1524 2649 1524 2650 1525 2650 1526 2650 1524 2651 1526 2651 1527 2651 1527 2652 1526 2652 1528 2652 1527 2653 1528 2653 1523 2653 1523 2654 1528 2654 1515 2654 1523 2655 1515 2655 1516 2655 1525 2656 1520 2656 1529 2656 1515 2657 1528 2657 1530 2657 1530 2658 1528 2658 1531 2658 1531 2659 1528 2659 1529 2659 1529 2660 1528 2660 1526 2660 1529 2661 1526 2661 1525 2661 1060 2662 1099 2662 1378 2662 1063 2663 1061 2663 1532 2663 1532 2664 1061 2664 1060 2664 1533 2665 1054 2665 1053 2665 1059 2666 1534 2666 1086 2666 1057 2667 1056 2667 1533 2667 1533 2668 1056 2668 1054 2668 1535 2669 1531 2669 1536 2669 1513 2670 1515 2670 1537 2670 1537 2671 1515 2671 1530 2671 1537 2672 1530 2672 1531 2672 1060 2673 1378 2673 1532 2673 1532 2674 1378 2674 1379 2674 1532 2675 1379 2675 1538 2675 1538 2676 1379 2676 1381 2676 1538 2677 1381 2677 1537 2677 1537 2678 1381 2678 1382 2678 1537 2679 1382 2679 1513 2679 1531 2680 1535 2680 1537 2680 1537 2681 1535 2681 1539 2681 1537 2682 1539 2682 1538 2682 1538 2683 1539 2683 1533 2683 1538 2684 1533 2684 1532 2684 1532 2685 1533 2685 1053 2685 1532 2686 1053 2686 1063 2686 1536 2687 1540 2687 1535 2687 1535 2688 1540 2688 1541 2688 1535 2689 1541 2689 1539 2689 1539 2690 1541 2690 1534 2690 1539 2691 1534 2691 1533 2691 1533 2692 1534 2692 1059 2692 1533 2693 1059 2693 1057 2693 1542 2694 1543 2694 1544 2694 1545 2695 1546 2695 1543 2695 1547 2696 1548 2696 1549 2696 1549 2697 1548 2697 1550 2697 1549 2698 1550 2698 1551 2698 1543 2699 1546 2699 1549 2699 1549 2700 1546 2700 1552 2700 1549 2701 1552 2701 1547 2701 1542 2702 1553 2702 1543 2702 1543 2703 1553 2703 1554 2703 1543 2704 1554 2704 1545 2704 1544 2705 1543 2705 1555 2705 1555 2706 1543 2706 1549 2706 1555 2707 1549 2707 1556 2707 1556 2708 1549 2708 1551 2708 1556 2709 1551 2709 1557 2709 1553 2710 1558 2710 1554 2710 1554 2711 1558 2711 1545 2711 1545 2712 1559 2712 1546 2712 1546 2713 1559 2713 1560 2713 1546 2714 1560 2714 1552 2714 1560 2715 1561 2715 1552 2715 1552 2716 1561 2716 1562 2716 1552 2717 1562 2717 1547 2717 1563 2718 1564 2718 1565 2718 1564 2719 1563 2719 1566 2719 1567 2720 1035 2720 1205 2720 1189 2721 1188 2721 1568 2721 1569 2722 1570 2722 1571 2722 1567 2723 1205 2723 1572 2723 1573 2724 1566 2724 1574 2724 1574 2725 1566 2725 1563 2725 1574 2726 1563 2726 1553 2726 1553 2727 1563 2727 1558 2727 1561 2728 1560 2728 1563 2728 1561 2729 1563 2729 1562 2729 1560 2730 1559 2730 1563 2730 1563 2731 1559 2731 1545 2731 1563 2732 1545 2732 1558 2732 1548 2733 1547 2733 1575 2733 1576 2734 1550 2734 1577 2734 1577 2735 1550 2735 1548 2735 1577 2736 1548 2736 1578 2736 1578 2737 1548 2737 1575 2737 1579 2738 1576 2738 1580 2738 1580 2739 1576 2739 1577 2739 1580 2740 1577 2740 1581 2740 1581 2741 1577 2741 1578 2741 1581 2742 1578 2742 1565 2742 1565 2743 1578 2743 1575 2743 1565 2744 1575 2744 1563 2744 1563 2745 1575 2745 1547 2745 1563 2746 1547 2746 1562 2746 1568 2747 1582 2747 1189 2747 1189 2748 1582 2748 1583 2748 1189 2749 1583 2749 1206 2749 1206 2750 1583 2750 1584 2750 1206 2751 1584 2751 1205 2751 1205 2752 1584 2752 1569 2752 1205 2753 1569 2753 1572 2753 1572 2754 1569 2754 1571 2754 1568 2755 1579 2755 1582 2755 1582 2756 1579 2756 1580 2756 1582 2757 1580 2757 1583 2757 1583 2758 1580 2758 1581 2758 1583 2759 1581 2759 1584 2759 1584 2760 1581 2760 1565 2760 1584 2761 1565 2761 1569 2761 1569 2762 1565 2762 1564 2762 1569 2763 1564 2763 1570 2763 1570 2764 1564 2764 1566 2764 1585 2765 1586 2765 1587 2765 1588 2766 1589 2766 1590 2766 1591 2767 1592 2767 1593 2767 1566 2768 1573 2768 1594 2768 1595 2769 1570 2769 1596 2769 1596 2770 1570 2770 1566 2770 1596 2771 1566 2771 1597 2771 1597 2772 1566 2772 1594 2772 1597 2773 1594 2773 1598 2773 1599 2774 1572 2774 1595 2774 1595 2775 1572 2775 1571 2775 1595 2776 1571 2776 1570 2776 1567 2777 1600 2777 1035 2777 1035 2778 1600 2778 1601 2778 1035 2779 1601 2779 1036 2779 1036 2780 1601 2780 1038 2780 1040 2781 1602 2781 1042 2781 1042 2782 1602 2782 1603 2782 1042 2783 1603 2783 1044 2783 1044 2784 1603 2784 1604 2784 1044 2785 1604 2785 1045 2785 1588 2786 1590 2786 1605 2786 1606 2787 1607 2787 1608 2787 1608 2788 1609 2788 1606 2788 1606 2789 1609 2789 1610 2789 1606 2790 1610 2790 1611 2790 1612 2791 1613 2791 1614 2791 1614 2792 1613 2792 1615 2792 1614 2793 1615 2793 1606 2793 1606 2794 1615 2794 1616 2794 1606 2795 1616 2795 1607 2795 1617 2796 1618 2796 1619 2796 1620 2797 1621 2797 1622 2797 1622 2798 1621 2798 1623 2798 1622 2799 1623 2799 1624 2799 1624 2800 1623 2800 1612 2800 1624 2801 1612 2801 1625 2801 1625 2802 1612 2802 1614 2802 1625 2803 1614 2803 1626 2803 1626 2804 1614 2804 1606 2804 1626 2805 1606 2805 1586 2805 1586 2806 1606 2806 1611 2806 1586 2807 1611 2807 1587 2807 1567 2808 1572 2808 1600 2808 1600 2809 1572 2809 1599 2809 1600 2810 1599 2810 1601 2810 1601 2811 1599 2811 1627 2811 1601 2812 1627 2812 1038 2812 1038 2813 1627 2813 1628 2813 1038 2814 1628 2814 1040 2814 1040 2815 1628 2815 1629 2815 1040 2816 1629 2816 1602 2816 1587 2817 1605 2817 1585 2817 1585 2818 1605 2818 1590 2818 1585 2819 1590 2819 1586 2819 1586 2820 1590 2820 1630 2820 1586 2821 1630 2821 1626 2821 1626 2822 1630 2822 1631 2822 1626 2823 1631 2823 1625 2823 1625 2824 1631 2824 1632 2824 1625 2825 1632 2825 1624 2825 1624 2826 1632 2826 1633 2826 1624 2827 1633 2827 1622 2827 1622 2828 1633 2828 1634 2828 1622 2829 1634 2829 1620 2829 1620 2830 1634 2830 1635 2830 1620 2831 1635 2831 1636 2831 1636 2832 1635 2832 1617 2832 1636 2833 1617 2833 1637 2833 1637 2834 1617 2834 1619 2834 1589 2835 1591 2835 1590 2835 1590 2836 1591 2836 1593 2836 1590 2837 1593 2837 1630 2837 1630 2838 1593 2838 1638 2838 1630 2839 1638 2839 1631 2839 1631 2840 1638 2840 1639 2840 1631 2841 1639 2841 1632 2841 1632 2842 1639 2842 1640 2842 1632 2843 1640 2843 1633 2843 1633 2844 1640 2844 1641 2844 1633 2845 1641 2845 1634 2845 1634 2846 1641 2846 1642 2846 1634 2847 1642 2847 1635 2847 1635 2848 1642 2848 1643 2848 1635 2849 1643 2849 1617 2849 1617 2850 1643 2850 1644 2850 1617 2851 1644 2851 1618 2851 1618 2852 1644 2852 1645 2852 1618 2853 1645 2853 1646 2853 1646 2854 1645 2854 1647 2854 1592 2855 1604 2855 1593 2855 1593 2856 1604 2856 1603 2856 1593 2857 1603 2857 1638 2857 1638 2858 1603 2858 1602 2858 1638 2859 1602 2859 1639 2859 1639 2860 1602 2860 1629 2860 1639 2861 1629 2861 1640 2861 1640 2862 1629 2862 1628 2862 1640 2863 1628 2863 1641 2863 1641 2864 1628 2864 1627 2864 1641 2865 1627 2865 1642 2865 1642 2866 1627 2866 1599 2866 1642 2867 1599 2867 1643 2867 1643 2868 1599 2868 1595 2868 1643 2869 1595 2869 1644 2869 1644 2870 1595 2870 1596 2870 1644 2871 1596 2871 1645 2871 1645 2872 1596 2872 1597 2872 1645 2873 1597 2873 1647 2873 1647 2874 1597 2874 1598 2874 1616 2875 1615 2875 1648 2875 1649 2876 1609 2876 1608 2876 1649 2877 1608 2877 1648 2877 1648 2878 1608 2878 1607 2878 1648 2879 1607 2879 1616 2879 1609 2880 1649 2880 1650 2880 1650 2881 1649 2881 1651 2881 1652 2882 1653 2882 1651 2882 1651 2883 1653 2883 1654 2883 1651 2884 1654 2884 1650 2884 1655 2885 1656 2885 1657 2885 1658 2886 1659 2886 1660 2886 1591 2887 1589 2887 1661 2887 1609 2888 1650 2888 1610 2888 1610 2889 1650 2889 1662 2889 1610 2890 1662 2890 1611 2890 1588 2891 1605 2891 1663 2891 1663 2892 1605 2892 1587 2892 1611 2893 1662 2893 1587 2893 1587 2894 1662 2894 1664 2894 1587 2895 1664 2895 1663 2895 1046 2896 1045 2896 1604 2896 1604 2897 1665 2897 1046 2897 1046 2898 1665 2898 1666 2898 1046 2899 1666 2899 1048 2899 1048 2900 1666 2900 1667 2900 1048 2901 1667 2901 1050 2901 1050 2902 1667 2902 1051 2902 1051 2903 1667 2903 1668 2903 1051 2904 1668 2904 1052 2904 1669 2905 1670 2905 1671 2905 1671 2906 1670 2906 1033 2906 1671 2907 1033 2907 1672 2907 1672 2908 1033 2908 1032 2908 1672 2909 1032 2909 1052 2909 1669 2910 1673 2910 1674 2910 1674 2911 1673 2911 1675 2911 1674 2912 1675 2912 1660 2912 1660 2913 1675 2913 1676 2913 1660 2914 1676 2914 1658 2914 1677 2915 1678 2915 1679 2915 1679 2916 1678 2916 1680 2916 1681 2917 1682 2917 1683 2917 1683 2918 1682 2918 1684 2918 1683 2919 1684 2919 1685 2919 1650 2920 1654 2920 1662 2920 1662 2921 1654 2921 1653 2921 1662 2922 1653 2922 1657 2922 1657 2923 1653 2923 1652 2923 1657 2924 1652 2924 1655 2924 1681 2925 1683 2925 1656 2925 1656 2926 1683 2926 1686 2926 1656 2927 1686 2927 1657 2927 1657 2928 1686 2928 1687 2928 1657 2929 1687 2929 1662 2929 1662 2930 1687 2930 1688 2930 1662 2931 1688 2931 1664 2931 1052 2932 1668 2932 1672 2932 1672 2933 1668 2933 1689 2933 1672 2934 1689 2934 1671 2934 1671 2935 1689 2935 1690 2935 1671 2936 1690 2936 1669 2936 1669 2937 1690 2937 1691 2937 1669 2938 1691 2938 1673 2938 1589 2939 1588 2939 1661 2939 1661 2940 1588 2940 1663 2940 1661 2941 1663 2941 1692 2941 1692 2942 1663 2942 1664 2942 1692 2943 1664 2943 1693 2943 1693 2944 1664 2944 1688 2944 1693 2945 1688 2945 1694 2945 1694 2946 1688 2946 1687 2946 1694 2947 1687 2947 1695 2947 1695 2948 1687 2948 1686 2948 1695 2949 1686 2949 1696 2949 1696 2950 1686 2950 1683 2950 1696 2951 1683 2951 1697 2951 1697 2952 1683 2952 1685 2952 1697 2953 1685 2953 1698 2953 1698 2954 1685 2954 1699 2954 1698 2955 1699 2955 1700 2955 1592 2956 1591 2956 1701 2956 1701 2957 1591 2957 1661 2957 1701 2958 1661 2958 1702 2958 1702 2959 1661 2959 1692 2959 1702 2960 1692 2960 1703 2960 1703 2961 1692 2961 1693 2961 1703 2962 1693 2962 1704 2962 1704 2963 1693 2963 1694 2963 1704 2964 1694 2964 1705 2964 1705 2965 1694 2965 1695 2965 1705 2966 1695 2966 1706 2966 1706 2967 1695 2967 1696 2967 1706 2968 1696 2968 1707 2968 1707 2969 1696 2969 1697 2969 1707 2970 1697 2970 1677 2970 1677 2971 1697 2971 1698 2971 1677 2972 1698 2972 1678 2972 1678 2973 1698 2973 1700 2973 1604 2974 1592 2974 1665 2974 1665 2975 1592 2975 1701 2975 1665 2976 1701 2976 1666 2976 1666 2977 1701 2977 1702 2977 1666 2978 1702 2978 1667 2978 1667 2979 1702 2979 1703 2979 1667 2980 1703 2980 1668 2980 1668 2981 1703 2981 1704 2981 1668 2982 1704 2982 1689 2982 1689 2983 1704 2983 1705 2983 1689 2984 1705 2984 1690 2984 1690 2985 1705 2985 1706 2985 1690 2986 1706 2986 1691 2986 1691 2987 1706 2987 1707 2987 1691 2988 1707 2988 1673 2988 1673 2989 1707 2989 1677 2989 1673 2990 1677 2990 1675 2990 1675 2991 1677 2991 1679 2991 1675 2992 1679 2992 1676 2992 1676 2993 1679 2993 1680 2993 1708 2994 1709 2994 1710 2994 1711 2995 1712 2995 1713 2995 1713 2996 1712 2996 1714 2996 1713 2997 1714 2997 1715 2997 1715 2998 1714 2998 1716 2998 1717 2999 1718 2999 1719 2999 1719 3000 1718 3000 1720 3000 1720 3001 1721 3001 1719 3001 1719 3002 1721 3002 1722 3002 1719 3003 1722 3003 1723 3003 1724 3004 1717 3004 1725 3004 1725 3005 1717 3005 1719 3005 1725 3006 1719 3006 1659 3006 1659 3007 1719 3007 1660 3007 1726 3008 1727 3008 1674 3008 1674 3009 1727 3009 1669 3009 1669 3010 1727 3010 1670 3010 1670 3011 1727 3011 1180 3011 1670 3012 1180 3012 1033 3012 1674 3013 1660 3013 1726 3013 1726 3014 1660 3014 1719 3014 1726 3015 1719 3015 1711 3015 1711 3016 1719 3016 1723 3016 1711 3017 1723 3017 1712 3017 1728 3018 1184 3018 1729 3018 1729 3019 1184 3019 1183 3019 1729 3020 1183 3020 1730 3020 1730 3021 1183 3021 1181 3021 1730 3022 1181 3022 1731 3022 1709 3023 1728 3023 1710 3023 1710 3024 1728 3024 1729 3024 1710 3025 1729 3025 1732 3025 1732 3026 1729 3026 1730 3026 1732 3027 1730 3027 1733 3027 1733 3028 1730 3028 1731 3028 1716 3029 1708 3029 1715 3029 1715 3030 1708 3030 1710 3030 1715 3031 1710 3031 1713 3031 1713 3032 1710 3032 1732 3032 1713 3033 1732 3033 1711 3033 1711 3034 1732 3034 1733 3034 1711 3035 1733 3035 1726 3035 1726 3036 1733 3036 1731 3036 1726 3037 1731 3037 1727 3037 1727 3038 1731 3038 1181 3038 1727 3039 1181 3039 1180 3039 1712 3040 1723 3040 1734 3040 1717 3041 1724 3041 1735 3041 1717 3042 1735 3042 1718 3042 1720 3043 1718 3043 1736 3043 1720 3044 1736 3044 1721 3044 1721 3045 1736 3045 1734 3045 1721 3046 1734 3046 1722 3046 1722 3047 1734 3047 1723 3047 1737 3048 1738 3048 1739 3048 1739 3049 1738 3049 1740 3049 1718 3050 1735 3050 1738 3050 1738 3051 1735 3051 1724 3051 1738 3052 1724 3052 1740 3052 1714 3053 1712 3053 1737 3053 1737 3054 1712 3054 1734 3054 1737 3055 1734 3055 1738 3055 1738 3056 1734 3056 1736 3056 1738 3057 1736 3057 1718 3057 1739 3058 1741 3058 1737 3058 1737 3059 1741 3059 1742 3059 1737 3060 1742 3060 1714 3060 1714 3061 1742 3061 1716 3061 1576 3062 1086 3062 1550 3062 1550 3063 1086 3063 1534 3063 1550 3064 1534 3064 1551 3064 1074 3065 1072 3065 1188 3065 1188 3066 1072 3066 1071 3066 1188 3067 1071 3067 1568 3067 1568 3068 1071 3068 1082 3068 1568 3069 1082 3069 1579 3069 1579 3070 1082 3070 1084 3070 1579 3071 1084 3071 1576 3071 1576 3072 1084 3072 1085 3072 1576 3073 1085 3073 1086 3073 1188 3074 1187 3074 1074 3074 1074 3075 1187 3075 1191 3075 1074 3076 1191 3076 1076 3076 1191 3077 1196 3077 1076 3077 1076 3078 1196 3078 1195 3078 1076 3079 1195 3079 1078 3079 1195 3080 1193 3080 1078 3080 1078 3081 1193 3081 1192 3081 1078 3082 1192 3082 1080 3082 1163 3083 1136 3083 1134 3083 1192 3084 1201 3084 1080 3084 1080 3085 1201 3085 1200 3085 1080 3086 1200 3086 1081 3086 1081 3087 1200 3087 1198 3087 1081 3088 1198 3088 1069 3088 1069 3089 1198 3089 1197 3089 1069 3090 1197 3090 1067 3090 1067 3091 1197 3091 1177 3091 1067 3092 1177 3092 1112 3092 1112 3093 1177 3093 1176 3093 1112 3094 1176 3094 1113 3094 1113 3095 1176 3095 1175 3095 1113 3096 1175 3096 1133 3096 1133 3097 1175 3097 1166 3097 1133 3098 1166 3098 1134 3098 1134 3099 1166 3099 1165 3099 1134 3100 1165 3100 1163 3100 1163 3101 1162 3101 1136 3101 1136 3102 1162 3102 1178 3102 1136 3103 1178 3103 1138 3103 1178 3104 1160 3104 1138 3104 1138 3105 1160 3105 1159 3105 1138 3106 1159 3106 1140 3106 1140 3107 1159 3107 1184 3107 1140 3108 1184 3108 1141 3108 1141 3109 1184 3109 1130 3109 1130 3110 1184 3110 1728 3110 1130 3111 1728 3111 1132 3111 1132 3112 1728 3112 1709 3112 1132 3113 1709 3113 1127 3113 1127 3114 1709 3114 1708 3114 1127 3115 1708 3115 1128 3115 1128 3116 1708 3116 1716 3116 1128 3117 1716 3117 1743 3117 1743 3118 1716 3118 1742 3118 1743 3119 1742 3119 1744 3119 1742 3120 1741 3120 1744 3120 1744 3121 1741 3121 1745 3121 1744 3122 1745 3122 1746 3122 1746 3123 1745 3123 1747 3123 1551 3124 1534 3124 1557 3124 1557 3125 1534 3125 1541 3125 1557 3126 1541 3126 1748 3126 1748 3127 1541 3127 1540 3127 1748 3128 1540 3128 1536 3128 1117 3129 1120 3129 1749 3129 1126 3130 1123 3130 1750 3130 1123 3131 1122 3131 1743 3131 1743 3132 1122 3132 1128 3132 1119 3133 1124 3133 1750 3133 1750 3134 1124 3134 1126 3134 1117 3135 1749 3135 1109 3135 1751 3136 1752 3136 1395 3136 1355 3137 1751 3137 1394 3137 1394 3138 1751 3138 1395 3138 1746 3139 1747 3139 1753 3139 1123 3140 1743 3140 1750 3140 1750 3141 1743 3141 1744 3141 1750 3142 1744 3142 1754 3142 1754 3143 1744 3143 1746 3143 1754 3144 1746 3144 1755 3144 1755 3145 1746 3145 1753 3145 1755 3146 1753 3146 1752 3146 1752 3147 1751 3147 1755 3147 1755 3148 1751 3148 1756 3148 1755 3149 1756 3149 1754 3149 1754 3150 1756 3150 1749 3150 1754 3151 1749 3151 1750 3151 1750 3152 1749 3152 1120 3152 1750 3153 1120 3153 1119 3153 1355 3154 1357 3154 1751 3154 1751 3155 1357 3155 1358 3155 1751 3156 1358 3156 1756 3156 1756 3157 1358 3157 1359 3157 1756 3158 1359 3158 1749 3158 1749 3159 1359 3159 1110 3159 1749 3160 1110 3160 1109 3160 1395 3161 1752 3161 1757 3161 1757 3162 1752 3162 1753 3162 1757 3163 1753 3163 1758 3163 1758 3164 1753 3164 1759 3164 1758 3165 1759 3165 1760 3165 1760 3166 1759 3166 1761 3166 1396 3167 1762 3167 1391 3167 1391 3168 1762 3168 1392 3168 1763 3169 1764 3169 1761 3169 1761 3170 1764 3170 1765 3170 1761 3171 1765 3171 1760 3171 1760 3172 1765 3172 1766 3172 1760 3173 1766 3173 1758 3173 1758 3174 1766 3174 1762 3174 1758 3175 1762 3175 1757 3175 1757 3176 1762 3176 1396 3176 1757 3177 1396 3177 1395 3177 1224 3178 1235 3178 1767 3178 1767 3179 1235 3179 1233 3179 1768 3180 1225 3180 1224 3180 1224 3181 1767 3181 1768 3181 1768 3182 1767 3182 1769 3182 1768 3183 1769 3183 1770 3183 1771 3184 1772 3184 1773 3184 1774 3185 1775 3185 1776 3185 1776 3186 1775 3186 1771 3186 1776 3187 1771 3187 1777 3187 1777 3188 1771 3188 1773 3188 1777 3189 1773 3189 1778 3189 1779 3190 1770 3190 1778 3190 1778 3191 1770 3191 1769 3191 1778 3192 1769 3192 1777 3192 1777 3193 1769 3193 1767 3193 1777 3194 1767 3194 1776 3194 1776 3195 1767 3195 1233 3195 1776 3196 1233 3196 1774 3196 1774 3197 1233 3197 1234 3197 1780 3198 1781 3198 1782 3198 1783 3199 1784 3199 1785 3199 1786 3200 1787 3200 1788 3200 1787 3201 1786 3201 1789 3201 1215 3202 1214 3202 1294 3202 1294 3203 1214 3203 1223 3203 1294 3204 1223 3204 1295 3204 1270 3205 1790 3205 1269 3205 1269 3206 1790 3206 1791 3206 1269 3207 1791 3207 1268 3207 1288 3208 1289 3208 1792 3208 1792 3209 1289 3209 1290 3209 1793 3210 1286 3210 1287 3210 1793 3211 1794 3211 1286 3211 1286 3212 1794 3212 1795 3212 1286 3213 1795 3213 1282 3213 1282 3214 1795 3214 1796 3214 1282 3215 1796 3215 1281 3215 1281 3216 1796 3216 1797 3216 1281 3217 1797 3217 1280 3217 1265 3218 1798 3218 1273 3218 1273 3219 1798 3219 1799 3219 1273 3220 1799 3220 1800 3220 1800 3221 1799 3221 1801 3221 1800 3222 1801 3222 1802 3222 1802 3223 1801 3223 1803 3223 1802 3224 1803 3224 1804 3224 1804 3225 1803 3225 1805 3225 1804 3226 1805 3226 1806 3226 1805 3227 1807 3227 1806 3227 1806 3228 1807 3228 1808 3228 1806 3229 1808 3229 1809 3229 1809 3230 1808 3230 1810 3230 1810 3231 1808 3231 1811 3231 1810 3232 1811 3232 1812 3232 1812 3233 1811 3233 1813 3233 1812 3234 1813 3234 1814 3234 1815 3235 1816 3235 1817 3235 1817 3236 1816 3236 1818 3236 1817 3237 1818 3237 1819 3237 1819 3238 1818 3238 1820 3238 1819 3239 1820 3239 1821 3239 1784 3240 1783 3240 1822 3240 1823 3241 1824 3241 1825 3241 1826 3242 1827 3242 1828 3242 1782 3243 1781 3243 1827 3243 1827 3244 1781 3244 1829 3244 1827 3245 1829 3245 1828 3245 1830 3246 1831 3246 1832 3246 1833 3247 1834 3247 1835 3247 1835 3248 1834 3248 1836 3248 1835 3249 1836 3249 1837 3249 1837 3250 1836 3250 1838 3250 1837 3251 1838 3251 1839 3251 1821 3252 1820 3252 1840 3252 1840 3253 1820 3253 1841 3253 1840 3254 1841 3254 1789 3254 1789 3255 1841 3255 1842 3255 1789 3256 1842 3256 1787 3256 1787 3257 1842 3257 1843 3257 1787 3258 1843 3258 1788 3258 1816 3259 1844 3259 1818 3259 1818 3260 1844 3260 1833 3260 1818 3261 1833 3261 1820 3261 1820 3262 1833 3262 1835 3262 1820 3263 1835 3263 1841 3263 1841 3264 1835 3264 1837 3264 1841 3265 1837 3265 1842 3265 1842 3266 1837 3266 1839 3266 1842 3267 1839 3267 1843 3267 1845 3268 1846 3268 1847 3268 1847 3269 1846 3269 1848 3269 1847 3270 1848 3270 1849 3270 1849 3271 1848 3271 1850 3271 1849 3272 1850 3272 1851 3272 1851 3273 1850 3273 1852 3273 1851 3274 1852 3274 1853 3274 1853 3275 1852 3275 1854 3275 1853 3276 1854 3276 1855 3276 1855 3277 1854 3277 1856 3277 1855 3278 1856 3278 1857 3278 1857 3279 1856 3279 1858 3279 1857 3280 1858 3280 1859 3280 1859 3281 1858 3281 1860 3281 1859 3282 1860 3282 1861 3282 1861 3283 1860 3283 1768 3283 1861 3284 1768 3284 1770 3284 1862 3285 1863 3285 1864 3285 1863 3286 1862 3286 1865 3286 1865 3287 1862 3287 1866 3287 1865 3288 1866 3288 1867 3288 1867 3289 1866 3289 1868 3289 1867 3290 1868 3290 1838 3290 1838 3291 1868 3291 1869 3291 1838 3292 1869 3292 1839 3292 1839 3293 1869 3293 1870 3293 1839 3294 1870 3294 1843 3294 1843 3295 1870 3295 1822 3295 1843 3296 1822 3296 1788 3296 1788 3297 1822 3297 1783 3297 1788 3298 1783 3298 1786 3298 1222 3299 1871 3299 1223 3299 1223 3300 1871 3300 1296 3300 1223 3301 1296 3301 1295 3301 1790 3302 1872 3302 1791 3302 1791 3303 1872 3303 1873 3303 1791 3304 1873 3304 1864 3304 1864 3305 1873 3305 1874 3305 1864 3306 1874 3306 1862 3306 1862 3307 1874 3307 1875 3307 1862 3308 1875 3308 1866 3308 1866 3309 1875 3309 1876 3309 1866 3310 1876 3310 1868 3310 1868 3311 1876 3311 1877 3311 1868 3312 1877 3312 1869 3312 1869 3313 1877 3313 1878 3313 1869 3314 1878 3314 1870 3314 1870 3315 1878 3315 1879 3315 1870 3316 1879 3316 1822 3316 1822 3317 1879 3317 1823 3317 1822 3318 1823 3318 1784 3318 1784 3319 1823 3319 1825 3319 1784 3320 1825 3320 1785 3320 1880 3321 1881 3321 1882 3321 1882 3322 1881 3322 1883 3322 1882 3323 1883 3323 1884 3323 1884 3324 1883 3324 1885 3324 1884 3325 1885 3325 1886 3325 1886 3326 1885 3326 1887 3326 1886 3327 1887 3327 1888 3327 1888 3328 1887 3328 1889 3328 1888 3329 1889 3329 1890 3329 1890 3330 1889 3330 1891 3330 1890 3331 1891 3331 1892 3331 1892 3332 1891 3332 1893 3332 1892 3333 1893 3333 1894 3333 1894 3334 1893 3334 1895 3334 1894 3335 1895 3335 1826 3335 1826 3336 1895 3336 1896 3336 1826 3337 1896 3337 1827 3337 1827 3338 1896 3338 1897 3338 1827 3339 1897 3339 1782 3339 1881 3340 1845 3340 1883 3340 1883 3341 1845 3341 1847 3341 1883 3342 1847 3342 1885 3342 1885 3343 1847 3343 1849 3343 1885 3344 1849 3344 1887 3344 1887 3345 1849 3345 1851 3345 1887 3346 1851 3346 1889 3346 1889 3347 1851 3347 1853 3347 1889 3348 1853 3348 1891 3348 1891 3349 1853 3349 1855 3349 1891 3350 1855 3350 1893 3350 1893 3351 1855 3351 1857 3351 1893 3352 1857 3352 1895 3352 1895 3353 1857 3353 1859 3353 1895 3354 1859 3354 1896 3354 1896 3355 1859 3355 1861 3355 1896 3356 1861 3356 1897 3356 1897 3357 1861 3357 1770 3357 1897 3358 1770 3358 1782 3358 1782 3359 1770 3359 1779 3359 1782 3360 1779 3360 1780 3360 1872 3361 1880 3361 1873 3361 1873 3362 1880 3362 1882 3362 1873 3363 1882 3363 1874 3363 1874 3364 1882 3364 1884 3364 1874 3365 1884 3365 1875 3365 1875 3366 1884 3366 1886 3366 1875 3367 1886 3367 1876 3367 1876 3368 1886 3368 1888 3368 1876 3369 1888 3369 1877 3369 1877 3370 1888 3370 1890 3370 1877 3371 1890 3371 1878 3371 1878 3372 1890 3372 1892 3372 1878 3373 1892 3373 1879 3373 1879 3374 1892 3374 1894 3374 1879 3375 1894 3375 1823 3375 1823 3376 1894 3376 1826 3376 1823 3377 1826 3377 1824 3377 1824 3378 1826 3378 1828 3378 1824 3379 1828 3379 1825 3379 1265 3380 1264 3380 1798 3380 1798 3381 1264 3381 1898 3381 1798 3382 1898 3382 1799 3382 1799 3383 1898 3383 1899 3383 1799 3384 1899 3384 1801 3384 1801 3385 1899 3385 1900 3385 1801 3386 1900 3386 1803 3386 1803 3387 1900 3387 1901 3387 1803 3388 1901 3388 1805 3388 1805 3389 1901 3389 1902 3389 1805 3390 1902 3390 1807 3390 1807 3391 1902 3391 1903 3391 1807 3392 1903 3392 1808 3392 1808 3393 1903 3393 1904 3393 1808 3394 1904 3394 1811 3394 1811 3395 1904 3395 1905 3395 1811 3396 1905 3396 1813 3396 1906 3397 1907 3397 1908 3397 1907 3398 1906 3398 1909 3398 1909 3399 1906 3399 1910 3399 1909 3400 1910 3400 1911 3400 1288 3401 1792 3401 1287 3401 1287 3402 1792 3402 1912 3402 1287 3403 1912 3403 1793 3403 1793 3404 1912 3404 1913 3404 1793 3405 1913 3405 1794 3405 1794 3406 1913 3406 1914 3406 1794 3407 1914 3407 1795 3407 1795 3408 1914 3408 1915 3408 1795 3409 1915 3409 1796 3409 1831 3410 1911 3410 1832 3410 1832 3411 1911 3411 1910 3411 1832 3412 1910 3412 1915 3412 1915 3413 1910 3413 1906 3413 1915 3414 1906 3414 1796 3414 1796 3415 1906 3415 1908 3415 1796 3416 1908 3416 1797 3416 1264 3417 1280 3417 1898 3417 1898 3418 1280 3418 1797 3418 1898 3419 1797 3419 1899 3419 1899 3420 1797 3420 1908 3420 1899 3421 1908 3421 1900 3421 1900 3422 1908 3422 1907 3422 1900 3423 1907 3423 1901 3423 1901 3424 1907 3424 1909 3424 1901 3425 1909 3425 1902 3425 1902 3426 1909 3426 1911 3426 1902 3427 1911 3427 1903 3427 1903 3428 1911 3428 1831 3428 1903 3429 1831 3429 1904 3429 1904 3430 1831 3430 1830 3430 1904 3431 1830 3431 1905 3431 1225 3432 1768 3432 1226 3432 1226 3433 1768 3433 1860 3433 1226 3434 1860 3434 1227 3434 1227 3435 1860 3435 1858 3435 1227 3436 1858 3436 1228 3436 1228 3437 1858 3437 1856 3437 1228 3438 1856 3438 1229 3438 1229 3439 1856 3439 1854 3439 1229 3440 1854 3440 1230 3440 1230 3441 1854 3441 1852 3441 1230 3442 1852 3442 1231 3442 1231 3443 1852 3443 1850 3443 1231 3444 1850 3444 1232 3444 1232 3445 1850 3445 1848 3445 1232 3446 1848 3446 1216 3446 1216 3447 1848 3447 1846 3447 1216 3448 1846 3448 1217 3448 1217 3449 1846 3449 1845 3449 1217 3450 1845 3450 1219 3450 1219 3451 1845 3451 1881 3451 1219 3452 1881 3452 1220 3452 1220 3453 1881 3453 1880 3453 1220 3454 1880 3454 1221 3454 1221 3455 1880 3455 1872 3455 1221 3456 1872 3456 1222 3456 1222 3457 1872 3457 1790 3457 1222 3458 1790 3458 1871 3458 1871 3459 1790 3459 1270 3459 1871 3460 1270 3460 1296 3460 1268 3461 1791 3461 1291 3461 1291 3462 1791 3462 1864 3462 1291 3463 1864 3463 1290 3463 1290 3464 1864 3464 1863 3464 1290 3465 1863 3465 1792 3465 1792 3466 1863 3466 1865 3466 1792 3467 1865 3467 1912 3467 1912 3468 1865 3468 1867 3468 1912 3469 1867 3469 1913 3469 1913 3470 1867 3470 1838 3470 1913 3471 1838 3471 1914 3471 1914 3472 1838 3472 1836 3472 1914 3473 1836 3473 1915 3473 1915 3474 1836 3474 1834 3474 1915 3475 1834 3475 1832 3475 1832 3476 1834 3476 1833 3476 1832 3477 1833 3477 1830 3477 1830 3478 1833 3478 1844 3478 1830 3479 1844 3479 1905 3479 1905 3480 1844 3480 1816 3480 1905 3481 1816 3481 1813 3481 1813 3482 1816 3482 1815 3482 1813 3483 1815 3483 1814 3483 1274 3484 1273 3484 1916 3484 1916 3485 1273 3485 1800 3485 1916 3486 1800 3486 1917 3486 1917 3487 1800 3487 1802 3487 1917 3488 1802 3488 1918 3488 1918 3489 1802 3489 1804 3489 1918 3490 1804 3490 1919 3490 1919 3491 1804 3491 1806 3491 1919 3492 1806 3492 1920 3492 1806 3493 1809 3493 1920 3493 1920 3494 1809 3494 1810 3494 1920 3495 1810 3495 1921 3495 1921 3496 1810 3496 1812 3496 1921 3497 1812 3497 1922 3497 1922 3498 1812 3498 1814 3498 1253 3499 1252 3499 1923 3499 1924 3500 1925 3500 1926 3500 1927 3501 1928 3501 1929 3501 1930 3502 1931 3502 1932 3502 1932 3503 1931 3503 1933 3503 1298 3504 1934 3504 1299 3504 1292 3505 1285 3505 1927 3505 1935 3506 1919 3506 1936 3506 1936 3507 1919 3507 1920 3507 1936 3508 1920 3508 1937 3508 1937 3509 1920 3509 1921 3509 1937 3510 1921 3510 1938 3510 1938 3511 1921 3511 1922 3511 1938 3512 1922 3512 1939 3512 1939 3513 1922 3513 1940 3513 1939 3514 1940 3514 1941 3514 1942 3515 1916 3515 1917 3515 1271 3516 1274 3516 1943 3516 1943 3517 1274 3517 1916 3517 1271 3518 1943 3518 1272 3518 1272 3519 1943 3519 1944 3519 1272 3520 1944 3520 1279 3520 1944 3521 1945 3521 1279 3521 1279 3522 1945 3522 1946 3522 1279 3523 1946 3523 1278 3523 1278 3524 1946 3524 1947 3524 1278 3525 1947 3525 1277 3525 1277 3526 1947 3526 1948 3526 1277 3527 1948 3527 1276 3527 1276 3528 1948 3528 1949 3528 1276 3529 1949 3529 1275 3529 1950 3530 1951 3530 1266 3530 1952 3531 1283 3531 1267 3531 1934 3532 1298 3532 1929 3532 1255 3533 1237 3533 1236 3533 1953 3534 1954 3534 1955 3534 1955 3535 1954 3535 1956 3535 1955 3536 1956 3536 1957 3536 1955 3537 1958 3537 1953 3537 1953 3538 1958 3538 1959 3538 1953 3539 1959 3539 1960 3539 1960 3540 1959 3540 1961 3540 1960 3541 1961 3541 1962 3541 1963 3542 1964 3542 1965 3542 1965 3543 1964 3543 1966 3543 1965 3544 1966 3544 1967 3544 1967 3545 1966 3545 1942 3545 1967 3546 1942 3546 1968 3546 1968 3547 1942 3547 1917 3547 1968 3548 1969 3548 1967 3548 1967 3549 1969 3549 1970 3549 1967 3550 1970 3550 1965 3550 1965 3551 1970 3551 1971 3551 1965 3552 1971 3552 1963 3552 1963 3553 1971 3553 1972 3553 1969 3554 1973 3554 1970 3554 1970 3555 1973 3555 1974 3555 1970 3556 1974 3556 1971 3556 1971 3557 1974 3557 1975 3557 1971 3558 1975 3558 1972 3558 1972 3559 1975 3559 1976 3559 1972 3560 1976 3560 1977 3560 1977 3561 1976 3561 1978 3561 1977 3562 1978 3562 1979 3562 1916 3563 1942 3563 1943 3563 1943 3564 1942 3564 1966 3564 1943 3565 1966 3565 1944 3565 1944 3566 1966 3566 1964 3566 1944 3567 1964 3567 1945 3567 1945 3568 1964 3568 1963 3568 1945 3569 1963 3569 1946 3569 1946 3570 1963 3570 1972 3570 1946 3571 1972 3571 1947 3571 1947 3572 1972 3572 1977 3572 1947 3573 1977 3573 1948 3573 1948 3574 1977 3574 1979 3574 1948 3575 1979 3575 1949 3575 1980 3576 1981 3576 1982 3576 1982 3577 1981 3577 1983 3577 1982 3578 1983 3578 1984 3578 1984 3579 1983 3579 1985 3579 1984 3580 1985 3580 1986 3580 1986 3581 1985 3581 1987 3581 1986 3582 1987 3582 1988 3582 1298 3583 1297 3583 1929 3583 1929 3584 1297 3584 1293 3584 1929 3585 1293 3585 1927 3585 1927 3586 1293 3586 1292 3586 1236 3587 1300 3587 1255 3587 1255 3588 1300 3588 1299 3588 1255 3589 1299 3589 1256 3589 1256 3590 1299 3590 1934 3590 1256 3591 1934 3591 1257 3591 1257 3592 1934 3592 1929 3592 1257 3593 1929 3593 1258 3593 1258 3594 1929 3594 1928 3594 1258 3595 1928 3595 1259 3595 1926 3596 1989 3596 1990 3596 1930 3597 1991 3597 1931 3597 1931 3598 1991 3598 1992 3598 1931 3599 1992 3599 1933 3599 1933 3600 1992 3600 1993 3600 1994 3601 1995 3601 1924 3601 1996 3602 1994 3602 1997 3602 1997 3603 1994 3603 1924 3603 1997 3604 1924 3604 1998 3604 1998 3605 1924 3605 1926 3605 1998 3606 1926 3606 1999 3606 1999 3607 1926 3607 1990 3607 1999 3608 1990 3608 2000 3608 2000 3609 1990 3609 2001 3609 2000 3610 2001 3610 2002 3610 2002 3611 2001 3611 2003 3611 2002 3612 2003 3612 2004 3612 2004 3613 2003 3613 2005 3613 2004 3614 2005 3614 1254 3614 1275 3615 1949 3615 2006 3615 2006 3616 1949 3616 1979 3616 2006 3617 1979 3617 2007 3617 2007 3618 1979 3618 1978 3618 2007 3619 1978 3619 2008 3619 2008 3620 1978 3620 2009 3620 2008 3621 2009 3621 2010 3621 2010 3622 2009 3622 2011 3622 2010 3623 2011 3623 2012 3623 2012 3624 2011 3624 2013 3624 2012 3625 2013 3625 2014 3625 2014 3626 2013 3626 2015 3626 2014 3627 2015 3627 2016 3627 2016 3628 2015 3628 2017 3628 2016 3629 2017 3629 2018 3629 2018 3630 2019 3630 2016 3630 2016 3631 2019 3631 2020 3631 2016 3632 2020 3632 2014 3632 2014 3633 2020 3633 2021 3633 2014 3634 2021 3634 2012 3634 2012 3635 2021 3635 2022 3635 2012 3636 2022 3636 2010 3636 2010 3637 2022 3637 2023 3637 2010 3638 2023 3638 2008 3638 2008 3639 2023 3639 2024 3639 2008 3640 2024 3640 2007 3640 2007 3641 2024 3641 1950 3641 2007 3642 1950 3642 2006 3642 2006 3643 1950 3643 1266 3643 2006 3644 1266 3644 1275 3644 2025 3645 2026 3645 2027 3645 2027 3646 2026 3646 2028 3646 2027 3647 2028 3647 2029 3647 2029 3648 2028 3648 2030 3648 2029 3649 2030 3649 2031 3649 2031 3650 2030 3650 2032 3650 2031 3651 2032 3651 2033 3651 2033 3652 2032 3652 2034 3652 2033 3653 2034 3653 2035 3653 2035 3654 2034 3654 2036 3654 2035 3655 2036 3655 1952 3655 1952 3656 2036 3656 1284 3656 1952 3657 1284 3657 1283 3657 2026 3658 1980 3658 2028 3658 2028 3659 1980 3659 1982 3659 2028 3660 1982 3660 2030 3660 2030 3661 1982 3661 1984 3661 2030 3662 1984 3662 2032 3662 2032 3663 1984 3663 1986 3663 2032 3664 1986 3664 2034 3664 2034 3665 1986 3665 1988 3665 2034 3666 1988 3666 2036 3666 2019 3667 2025 3667 2020 3667 2020 3668 2025 3668 2027 3668 2020 3669 2027 3669 2021 3669 2021 3670 2027 3670 2029 3670 2021 3671 2029 3671 2022 3671 2022 3672 2029 3672 2031 3672 2022 3673 2031 3673 2023 3673 2023 3674 2031 3674 2033 3674 2023 3675 2033 3675 2024 3675 2024 3676 2033 3676 2035 3676 2024 3677 2035 3677 1950 3677 1950 3678 2035 3678 1952 3678 1950 3679 1952 3679 1951 3679 1951 3680 1952 3680 1267 3680 1951 3681 1267 3681 1266 3681 1941 3682 2037 3682 1939 3682 1939 3683 2037 3683 2038 3683 1939 3684 2038 3684 1938 3684 1938 3685 2038 3685 2039 3685 1938 3686 2039 3686 1937 3686 1937 3687 2039 3687 2040 3687 1937 3688 2040 3688 1936 3688 1936 3689 2040 3689 2041 3689 1936 3690 2041 3690 1935 3690 2037 3691 2042 3691 2038 3691 2038 3692 2042 3692 2043 3692 2038 3693 2043 3693 2039 3693 2039 3694 2043 3694 2044 3694 2039 3695 2044 3695 2040 3695 2040 3696 2044 3696 2045 3696 2040 3697 2045 3697 2041 3697 2046 3698 1961 3698 2047 3698 2047 3699 1961 3699 1959 3699 2047 3700 1959 3700 2048 3700 2048 3701 1959 3701 1958 3701 2048 3702 1958 3702 1996 3702 1996 3703 1958 3703 1994 3703 1994 3704 1958 3704 1955 3704 1994 3705 1955 3705 1995 3705 1995 3706 1955 3706 1957 3706 1995 3707 1957 3707 1924 3707 1924 3708 1957 3708 2049 3708 1924 3709 2049 3709 1925 3709 1925 3710 2049 3710 2050 3710 1925 3711 2050 3711 1926 3711 1926 3712 2050 3712 2051 3712 1926 3713 2051 3713 1989 3713 1989 3714 2051 3714 1993 3714 1989 3715 1993 3715 1990 3715 1990 3716 1993 3716 1992 3716 1990 3717 1992 3717 2001 3717 2001 3718 1992 3718 1991 3718 2001 3719 1991 3719 2003 3719 2003 3720 1991 3720 1930 3720 2003 3721 1930 3721 2005 3721 2042 3722 1962 3722 2043 3722 2043 3723 1962 3723 1961 3723 2043 3724 1961 3724 2044 3724 2044 3725 1961 3725 2046 3725 2044 3726 2046 3726 2045 3726 2045 3727 2046 3727 2052 3727 2045 3728 2052 3728 2041 3728 2041 3729 2052 3729 2053 3729 2041 3730 2053 3730 1935 3730 1935 3731 2053 3731 2054 3731 1935 3732 2054 3732 1919 3732 1919 3733 2054 3733 1918 3733 2017 3734 1923 3734 2018 3734 2018 3735 1923 3735 1252 3735 2018 3736 1252 3736 2019 3736 2019 3737 1252 3737 1251 3737 2019 3738 1251 3738 2025 3738 2025 3739 1251 3739 1250 3739 2025 3740 1250 3740 2026 3740 2026 3741 1250 3741 1249 3741 2026 3742 1249 3742 1980 3742 1980 3743 1249 3743 1248 3743 1980 3744 1248 3744 1981 3744 1981 3745 1248 3745 1247 3745 1981 3746 1247 3746 1983 3746 1983 3747 1247 3747 1260 3747 1983 3748 1260 3748 1985 3748 1985 3749 1260 3749 1259 3749 1985 3750 1259 3750 1987 3750 1987 3751 1259 3751 1928 3751 1987 3752 1928 3752 1988 3752 1988 3753 1928 3753 1927 3753 1988 3754 1927 3754 2036 3754 2036 3755 1927 3755 1285 3755 2036 3756 1285 3756 1284 3756 1254 3757 1253 3757 2004 3757 2004 3758 1253 3758 1923 3758 2004 3759 1923 3759 2002 3759 2002 3760 1923 3760 2017 3760 2002 3761 2017 3761 2000 3761 2000 3762 2017 3762 2015 3762 2000 3763 2015 3763 1999 3763 1999 3764 2015 3764 2013 3764 1999 3765 2013 3765 1998 3765 1998 3766 2013 3766 2011 3766 1998 3767 2011 3767 1997 3767 1997 3768 2011 3768 2009 3768 1997 3769 2009 3769 1996 3769 1996 3770 2009 3770 1978 3770 1996 3771 1978 3771 2048 3771 2048 3772 1978 3772 1976 3772 2048 3773 1976 3773 2047 3773 2047 3774 1976 3774 1975 3774 2047 3775 1975 3775 2046 3775 2046 3776 1975 3776 1974 3776 2046 3777 1974 3777 2052 3777 2052 3778 1974 3778 1973 3778 2052 3779 1973 3779 2053 3779 2053 3780 1973 3780 1969 3780 2053 3781 1969 3781 2054 3781 2054 3782 1969 3782 1968 3782 2054 3783 1968 3783 1918 3783 1918 3784 1968 3784 1917 3784 2055 3785 2056 3785 2057 3785 1930 3786 1932 3786 2056 3786 2056 3787 2055 3787 1930 3787 1930 3788 2055 3788 2058 3788 1930 3789 2058 3789 2005 3789 2059 3790 1241 3790 1244 3790 1242 3791 1241 3791 2060 3791 2060 3792 1241 3792 2059 3792 2060 3793 2059 3793 2061 3793 2061 3794 2059 3794 2062 3794 2061 3795 2062 3795 2063 3795 2063 3796 2062 3796 2064 3796 2065 3797 2064 3797 2057 3797 2057 3798 2064 3798 2062 3798 2057 3799 2062 3799 2055 3799 2055 3800 2062 3800 2059 3800 2055 3801 2059 3801 2058 3801 2058 3802 2059 3802 1244 3802 2058 3803 1244 3803 2005 3803 2005 3804 1244 3804 1254 3804 749 3805 1243 3805 1242 3805 1301 1525 749 1525 2066 1525 2066 3806 749 3806 1242 3806 2066 3807 1242 3807 2067 3807 2067 1525 1242 1525 2068 1525 1303 3808 1302 3808 2066 3808 2066 3809 1302 3809 748 3809 2066 3810 748 3810 1301 3810 2069 3811 1315 3811 2070 3811 2070 3812 1315 3812 1317 3812 2070 3813 1317 3813 2071 3813 2071 3814 1317 3814 1326 3814 2071 3815 1326 3815 2072 3815 2072 3816 1326 3816 1328 3816 2072 3817 1328 3817 2068 3817 2068 3818 1328 3818 1321 3818 2068 3819 1321 3819 2067 3819 2067 3820 1321 3820 2066 3820 2066 3821 1321 3821 1320 3821 2066 3822 1320 3822 1303 3822 1455 1295 1316 1295 2073 1295 2073 1295 1316 1295 1315 1295 2073 3823 1315 3823 2074 3823 2074 3824 1315 3824 2069 3824 2075 3825 2076 3825 2077 3825 2078 3826 2079 3826 2080 3826 1339 3827 1340 3827 1376 3827 1338 3828 1339 3828 2081 3828 1333 3829 2082 3829 2083 3829 2083 3830 2082 3830 2084 3830 2083 3831 2084 3831 2085 3831 2085 3832 2084 3832 2086 3832 2085 3833 2086 3833 2087 3833 2087 3834 2086 3834 2088 3834 2087 3835 2088 3835 2089 3835 2089 3836 2088 3836 2090 3836 2089 3837 2090 3837 2091 3837 1339 3838 1376 3838 2081 3838 2081 3839 1376 3839 1375 3839 2081 3840 1375 3840 2092 3840 2092 3841 1375 3841 1374 3841 2092 3842 1374 3842 2093 3842 2093 3843 1374 3843 1372 3843 2093 3844 1372 3844 2094 3844 2094 3845 1372 3845 1371 3845 2094 3846 1371 3846 2095 3846 2095 3847 1371 3847 1373 3847 2095 3848 1373 3848 2096 3848 2096 3849 1373 3849 1370 3849 2096 3850 1370 3850 2097 3850 2097 3851 1370 3851 1369 3851 2097 3852 1369 3852 2098 3852 2098 3853 1369 3853 1368 3853 2098 3854 1368 3854 2099 3854 2099 3855 1368 3855 1367 3855 2099 3856 1367 3856 2100 3856 2100 3857 1367 3857 1366 3857 2100 3858 1366 3858 2101 3858 2101 3859 1366 3859 1365 3859 2101 3860 1365 3860 2102 3860 2102 3861 2078 3861 2101 3861 2101 3862 2078 3862 2080 3862 2101 3863 2080 3863 2100 3863 2100 3864 2080 3864 2103 3864 2100 3865 2103 3865 2099 3865 2099 3866 2103 3866 2104 3866 2099 3867 2104 3867 2098 3867 2098 3868 2104 3868 2105 3868 2098 3869 2105 3869 2097 3869 2097 3870 2105 3870 2106 3870 2097 3871 2106 3871 2096 3871 2096 3872 2106 3872 2107 3872 2096 3873 2107 3873 2095 3873 2095 3874 2107 3874 2108 3874 2095 3875 2108 3875 2094 3875 2094 3876 2108 3876 2109 3876 2094 3877 2109 3877 2093 3877 2093 3878 2109 3878 2110 3878 2093 3879 2110 3879 2092 3879 2092 3880 2110 3880 2111 3880 2092 3881 2111 3881 2081 3881 2081 3882 2111 3882 2112 3882 2081 3883 2112 3883 1338 3883 1338 3884 2112 3884 1336 3884 2079 3885 2075 3885 2080 3885 2080 3886 2075 3886 2077 3886 2080 3887 2077 3887 2103 3887 2103 3888 2077 3888 2113 3888 2103 3889 2113 3889 2104 3889 2104 3890 2113 3890 2114 3890 2104 3891 2114 3891 2105 3891 2105 3892 2114 3892 2115 3892 2105 3893 2115 3893 2106 3893 2106 3894 2115 3894 2116 3894 2106 3895 2116 3895 2107 3895 2107 3896 2116 3896 2117 3896 2107 3897 2117 3897 2108 3897 2108 3898 2117 3898 2090 3898 2108 3899 2090 3899 2109 3899 2109 3900 2090 3900 2088 3900 2109 3901 2088 3901 2110 3901 2110 3902 2088 3902 2086 3902 2110 3903 2086 3903 2111 3903 2111 3904 2086 3904 2084 3904 2111 3905 2084 3905 2112 3905 2112 3906 2084 3906 2082 3906 2112 3907 2082 3907 1336 3907 1336 3908 2082 3908 1333 3908 2091 3909 2090 3909 2118 3909 2118 3910 2090 3910 2117 3910 2118 3911 2117 3911 2119 3911 2119 3912 2117 3912 2116 3912 2119 3913 2116 3913 2120 3913 2120 3914 2116 3914 2115 3914 2120 3915 2115 3915 2121 3915 2121 3916 2115 3916 2114 3916 2121 3917 2114 3917 2122 3917 2122 3918 2114 3918 2113 3918 2122 3919 2113 3919 2123 3919 2123 3920 2113 3920 2077 3920 2123 3921 2077 3921 2124 3921 2124 3922 2077 3922 2076 3922 2124 3923 2076 3923 2125 3923 1333 3924 2126 3924 1334 3924 1334 3925 2126 3925 2127 3925 1334 3926 2127 3926 941 3926 941 3927 2127 3927 1478 3927 2128 3928 2125 3928 2076 3928 2128 3929 2076 3929 2129 3929 2129 3930 2130 3930 2131 3930 2131 3931 2132 3931 2129 3931 2129 3932 2132 3932 2133 3932 2129 3933 2133 3933 2128 3933 2128 3934 2133 3934 2134 3934 2128 3935 2134 3935 2135 3935 2078 3936 2130 3936 2079 3936 2079 3937 2130 3937 2129 3937 2079 3938 2129 3938 2075 3938 2075 3939 2129 3939 2076 3939 2102 3940 1365 3940 1364 3940 1361 3941 2136 3941 1362 3941 1362 3942 2136 3942 2131 3942 1362 3943 2131 3943 1363 3943 1363 3944 2131 3944 2130 3944 1363 3945 2130 3945 1364 3945 1364 3946 2130 3946 2078 3946 1364 3947 2078 3947 2102 3947 2131 3948 2136 3948 2137 3948 2133 3949 2132 3949 2138 3949 1389 3950 1390 3950 2139 3950 1388 3951 1389 3951 2140 3951 1389 3952 2139 3952 2140 3952 2140 3953 2139 3953 2141 3953 2140 3954 2141 3954 2142 3954 2142 3955 2141 3955 2143 3955 2142 3956 2143 3956 2144 3956 2144 3957 2143 3957 2145 3957 2143 3958 2146 3958 2145 3958 2145 3959 2146 3959 2147 3959 2145 3960 2147 3960 2148 3960 2148 3961 2147 3961 2149 3961 2148 3962 2149 3962 2150 3962 2149 3963 2151 3963 2150 3963 2150 3964 2151 3964 2152 3964 2150 3965 2152 3965 2153 3965 2153 3966 2152 3966 2154 3966 2153 3967 2154 3967 2155 3967 2155 3968 2154 3968 2156 3968 2155 3969 2156 3969 2157 3969 2157 3970 2156 3970 2158 3970 2157 3971 2158 3971 2159 3971 2159 3972 2158 3972 2160 3972 2159 3973 2160 3973 2161 3973 2161 3974 2160 3974 2135 3974 2161 3975 2135 3975 2134 3975 2134 3976 2133 3976 2161 3976 2161 3977 2133 3977 2138 3977 2161 3978 2138 3978 2159 3978 2159 3979 2138 3979 2162 3979 2159 3980 2162 3980 2157 3980 2157 3981 2162 3981 2163 3981 2157 3982 2163 3982 2155 3982 2155 3983 2163 3983 2164 3983 2155 3984 2164 3984 2153 3984 2153 3985 2164 3985 2165 3985 2153 3986 2165 3986 2150 3986 2150 3987 2165 3987 2166 3987 2150 3988 2166 3988 2148 3988 2148 3989 2166 3989 2167 3989 2148 3990 2167 3990 2145 3990 2145 3991 2167 3991 2168 3991 2145 3992 2168 3992 2144 3992 2144 3993 2168 3993 2169 3993 2144 3994 2169 3994 2142 3994 2142 3995 2169 3995 2170 3995 2142 3996 2170 3996 2140 3996 2140 3997 2170 3997 2171 3997 2140 3998 2171 3998 1388 3998 1388 3999 2171 3999 1386 3999 2132 4000 2131 4000 2138 4000 2138 4001 2131 4001 2137 4001 2138 4002 2137 4002 2162 4002 2162 4003 2137 4003 2172 4003 2162 4004 2172 4004 2163 4004 2163 4005 2172 4005 2173 4005 2163 4006 2173 4006 2164 4006 2164 4007 2173 4007 2174 4007 2164 4008 2174 4008 2165 4008 2165 4009 2174 4009 2175 4009 2165 4010 2175 4010 2166 4010 2166 4011 2175 4011 2176 4011 2166 4012 2176 4012 2167 4012 2167 4013 2176 4013 2177 4013 2167 4014 2177 4014 2168 4014 2168 4015 2177 4015 2178 4015 2168 4016 2178 4016 2169 4016 2169 4017 2178 4017 2179 4017 2169 4018 2179 4018 2170 4018 2170 4019 2179 4019 2180 4019 2170 4020 2180 4020 2171 4020 2171 4021 2180 4021 2181 4021 2171 4022 2181 4022 1386 4022 1386 4023 2181 4023 1353 4023 1353 4024 2181 4024 1354 4024 1354 4025 2181 4025 2180 4025 1354 4026 2180 4026 1347 4026 1347 4027 2180 4027 2179 4027 1347 4028 2179 4028 1348 4028 1348 4029 2179 4029 2178 4029 1348 4030 2178 4030 1349 4030 1349 4031 2178 4031 2177 4031 1349 4032 2177 4032 1350 4032 1350 4033 2177 4033 2176 4033 1350 4034 2176 4034 1351 4034 1351 4035 2176 4035 2175 4035 1351 4036 2175 4036 1345 4036 1345 4037 2175 4037 2174 4037 1345 4038 2174 4038 1343 4038 1343 4039 2174 4039 2173 4039 1343 4040 2173 4040 1342 4040 1342 4041 2173 4041 2172 4041 1342 4042 2172 4042 1341 4042 1341 4043 2172 4043 2137 4043 1341 4044 2137 4044 1360 4044 1360 4045 2137 4045 2136 4045 1360 4046 2136 4046 1361 4046 846 4047 1420 4047 1383 4047 1383 4048 1420 4048 2182 4048 1383 4049 2182 4049 1390 4049 1390 4050 2182 4050 2183 4050 2184 4051 1393 4051 1392 4051 1399 4052 1403 4052 1401 4052 1401 4053 1403 4053 1402 4053 1401 4054 1402 4054 826 4054 1410 4055 1409 4055 2185 4055 2185 4056 1409 4056 1403 4056 2185 4057 1403 4057 2184 4057 2184 4058 1403 4058 1399 4058 2184 4059 1399 4059 1393 4059 1430 4060 1425 4060 2186 4060 2186 4061 1425 4061 2187 4061 2186 4062 2187 4062 2188 4062 2188 4063 2187 4063 2189 4063 2189 4064 2187 4064 2190 4064 2189 4065 2190 4065 2191 4065 1425 4066 1410 4066 2187 4066 2187 4067 1410 4067 2185 4067 2187 4068 2185 4068 2190 4068 2190 4069 2185 4069 2192 4069 1392 4070 1762 4070 2184 4070 2184 4071 1762 4071 1766 4071 2184 4072 1766 4072 2185 4072 2185 4073 1766 4073 1765 4073 2185 4074 1765 4074 2192 4074 2192 4075 1765 4075 1764 4075 2192 4076 1764 4076 1763 4076 1418 4077 848 4077 1426 4077 1418 4078 1426 4078 839 4078 1419 4079 839 4079 2193 4079 2193 4080 839 4080 1426 4080 2193 4081 1426 4081 2194 4081 2194 4082 1426 4082 1427 4082 2194 4083 1427 4083 2195 4083 2195 4084 1427 4084 1428 4084 2195 4085 1428 4085 2196 4085 2196 4086 1428 4086 1429 4086 2196 4087 1429 4087 2197 4087 2197 4088 1429 4088 1430 4088 1420 4089 1419 4089 2198 4089 2198 4090 1419 4090 2193 4090 2198 4091 2193 4091 2199 4091 2199 4092 2193 4092 2194 4092 2199 4093 2194 4093 2200 4093 2200 4094 2194 4094 2195 4094 2200 4095 2195 4095 2201 4095 2201 4096 2195 4096 2196 4096 2201 4097 2196 4097 2202 4097 2202 4098 2196 4098 2197 4098 2201 4099 2203 4099 2200 4099 2200 4100 2203 4100 2204 4100 2200 4101 2204 4101 2199 4101 2182 4102 1420 4102 2205 4102 2205 4103 1420 4103 2198 4103 2205 4104 2198 4104 2206 4104 2207 4105 2203 4105 2208 4105 2208 4106 2203 4106 2201 4106 2208 4107 2201 4107 2202 4107 2209 4108 2204 4108 2210 4108 2210 4109 2204 4109 2203 4109 2210 4110 2203 4110 2211 4110 2211 4111 2203 4111 2207 4111 2209 4112 2212 4112 2204 4112 2204 4113 2212 4113 2206 4113 2204 4114 2206 4114 2199 4114 2199 4115 2206 4115 2198 4115 2183 4116 2182 4116 2213 4116 2213 4117 2182 4117 2205 4117 2213 4118 2205 4118 2214 4118 2214 4119 2205 4119 2206 4119 2214 4120 2206 4120 2215 4120 2215 4121 2206 4121 2212 4121 2216 4122 2217 4122 1432 4122 2218 4123 1433 4123 2219 4123 2219 4124 1433 4124 1440 4124 1432 4125 1433 4125 2216 4125 2216 4126 1433 4126 2218 4126 2216 4127 2218 4127 2220 4127 2220 4128 2218 4128 2221 4128 2220 4129 2221 4129 2222 4129 2223 4130 2224 4130 2221 4130 2221 4131 2224 4131 2225 4131 2221 4132 2225 4132 2222 4132 1432 1480 2217 1480 1431 1480 1431 1480 2217 1480 2226 1480 871 4133 1431 4133 2226 4133 871 4134 2226 4134 1434 4134 2227 4135 1772 4135 2226 4135 2226 4136 1772 4136 1771 4136 2226 4137 1771 4137 1434 4137 1434 4138 1771 4138 1775 4138 1434 4139 1775 4139 1437 4139 1437 4140 1775 4140 1774 4140 1437 4141 1774 4141 1438 4141 1438 4142 1774 4142 1234 4142 1438 4143 1234 4143 1439 4143 2228 4144 29 4144 4 4144 57 1480 60 1480 36 1480 36 1480 60 1480 2229 1480 36 4145 2229 4145 31 4145 31 1480 2229 1480 2230 1480 31 1480 2230 1480 32 1480 32 1480 2230 1480 2231 1480 32 4146 2231 4146 34 4146 34 4147 2231 4147 42 4147 42 1480 2231 1480 2232 1480 42 1480 2232 1480 3 1480 2232 4148 2233 4148 3 4148 3 1480 2233 1480 2234 1480 3 1480 2234 1480 4 1480 4 1480 2234 1480 2235 1480 4 1480 2235 1480 2228 1480 2218 4149 2219 4149 2236 4149 2223 4150 2221 4150 2237 4150 2237 4151 2221 4151 2238 4151 2237 4152 2238 4152 2239 4152 2240 4153 2241 4153 2242 4153 2242 4154 2241 4154 2243 4154 2243 4155 2241 4155 2244 4155 2244 4156 2241 4156 2245 4156 2244 4157 2245 4157 2246 4157 2247 4158 2248 4158 2249 4158 2250 4159 2232 4159 2251 4159 2251 4160 2232 4160 2231 4160 2251 4161 2231 4161 2230 4161 2219 4162 1440 4162 2236 4162 2236 4163 1440 4163 1441 4163 2236 4164 1441 4164 27 4164 29 4165 2228 4165 27 4165 27 4166 2228 4166 2235 4166 27 4167 2235 4167 2236 4167 2236 4168 2235 4168 2234 4168 2236 4169 2234 4169 2250 4169 2250 4170 2234 4170 2233 4170 2250 4171 2233 4171 2232 4171 2249 4172 2246 4172 2247 4172 2247 4173 2246 4173 2245 4173 2247 4174 2245 4174 2252 4174 2252 4175 2245 4175 2253 4175 2254 4176 2255 4176 2256 4176 2255 4177 2253 4177 2256 4177 2256 4178 2253 4178 2245 4178 2256 4179 2245 4179 2257 4179 2257 4180 2245 4180 2241 4180 2257 4181 2241 4181 2238 4181 2238 4182 2241 4182 2240 4182 2238 4183 2240 4183 2239 4183 2239 4184 2240 4184 2242 4184 2221 4185 2218 4185 2238 4185 2238 4186 2218 4186 2236 4186 2238 4187 2236 4187 2257 4187 2257 4188 2236 4188 2250 4188 2257 4189 2250 4189 2256 4189 2256 4190 2250 4190 2251 4190 2256 4191 2251 4191 2254 4191 2254 4192 2251 4192 2230 4192 2254 4193 2230 4193 2229 4193 2258 4194 2259 4194 2260 4194 2261 4195 2262 4195 2263 4195 2202 4196 2197 4196 2264 4196 2226 4197 2217 4197 2227 4197 2227 4198 2217 4198 2216 4198 2216 4199 2220 4199 2227 4199 2227 4200 2220 4200 2222 4200 2227 4201 2222 4201 2265 4201 2266 4202 2267 4202 2268 4202 2264 4203 2197 4203 2269 4203 2191 4204 2267 4204 2189 4204 2189 4205 2267 4205 2266 4205 2189 4206 2266 4206 2188 4206 2188 4207 2266 4207 2269 4207 2188 4208 2269 4208 2186 4208 2186 4209 2269 4209 2197 4209 2186 4210 2197 4210 1430 4210 2262 4211 2270 4211 2263 4211 2263 4212 2270 4212 2207 4212 2263 4213 2207 4213 2264 4213 2264 4214 2207 4214 2208 4214 2264 4215 2208 4215 2202 4215 2260 4216 2259 4216 2271 4216 2271 4217 2259 4217 2272 4217 2271 4218 2272 4218 2261 4218 2273 4219 68 4219 67 4219 67 4220 2274 4220 2273 4220 2273 4221 2274 4221 2275 4221 2273 4222 2275 4222 2260 4222 2260 4223 2275 4223 2276 4223 2260 4224 2276 4224 2258 4224 68 4225 2277 4225 70 4225 70 4226 2277 4226 2278 4226 70 4227 2278 4227 72 4227 2248 4228 2279 4228 2280 4228 2280 4229 2279 4229 2281 4229 2280 4230 2281 4230 2277 4230 2277 4231 2281 4231 2282 4231 2277 4232 2282 4232 2278 4232 2243 4233 2244 4233 2283 4233 2283 4234 2244 4234 2246 4234 2283 4235 2246 4235 2280 4235 2280 4236 2246 4236 2249 4236 2280 4237 2249 4237 2248 4237 2243 4238 2283 4238 2242 4238 2242 4239 2283 4239 2284 4239 2242 4240 2284 4240 2239 4240 2239 4241 2284 4241 2285 4241 2239 4242 2285 4242 2237 4242 2222 4243 2225 4243 2265 4243 2265 4244 2225 4244 2224 4244 2265 4245 2224 4245 2285 4245 2285 4246 2224 4246 2223 4246 2285 4247 2223 4247 2237 4247 2261 4248 2263 4248 2271 4248 2271 4249 2263 4249 2264 4249 2271 4250 2264 4250 2286 4250 2286 4251 2264 4251 2269 4251 2286 4252 2269 4252 2287 4252 2287 4253 2269 4253 2266 4253 2287 4254 2266 4254 2288 4254 2288 4255 2266 4255 2268 4255 2288 4256 2268 4256 2289 4256 68 4257 2273 4257 2277 4257 2277 4258 2273 4258 2260 4258 2277 4259 2260 4259 2280 4259 2280 4260 2260 4260 2271 4260 2280 4261 2271 4261 2283 4261 2283 4262 2271 4262 2286 4262 2283 4263 2286 4263 2284 4263 2284 4264 2286 4264 2287 4264 2284 4265 2287 4265 2285 4265 2285 4266 2287 4266 2288 4266 2285 4267 2288 4267 2265 4267 2265 4268 2288 4268 2289 4268 2265 4269 2289 4269 2227 4269 2290 1480 1453 1480 2291 1480 2291 4270 1453 4270 1452 4270 2291 1480 1452 1480 2292 1480 2292 1480 1452 1480 1469 1480 2292 1480 1469 1480 2293 1480 2293 1480 1469 1480 1472 1480 2293 4271 1472 4271 2294 4271 2294 1480 1472 1480 1475 1480 1459 4272 2295 4272 1473 4272 1473 1480 2295 1480 2296 1480 1473 4273 2296 4273 1474 4273 1474 1480 2296 1480 2297 1480 1474 4274 2297 4274 1475 4274 1475 1480 2297 1480 2298 1480 1475 1480 2298 1480 2294 1480 1443 1525 1445 1525 1442 1525 1442 1525 1445 1525 1447 1525 1442 1525 1447 1525 1450 1525 2299 1525 1454 1525 2300 1525 2300 1525 1454 1525 1442 1525 2300 1525 1442 1525 2290 1525 2290 1525 1442 1525 1450 1525 2290 1525 1450 1525 1453 1525 2301 4275 2302 4275 2303 4275 2304 4276 2305 4276 2306 4276 2306 4277 2305 4277 2303 4277 2306 4278 2303 4278 2307 4278 2307 4279 2303 4279 2302 4279 2301 4280 2303 4280 2308 4280 2308 4281 2303 4281 2309 4281 2308 4282 2309 4282 2310 4282 2310 4283 2309 4283 2311 4283 2310 4284 2311 4284 2312 4284 2312 4285 2311 4285 2313 4285 2312 4286 2313 4286 2314 4286 2307 4287 2315 4287 2316 4287 2317 4288 2304 4288 2316 4288 2316 4289 2304 4289 2306 4289 2316 4290 2306 4290 2307 4290 2318 4291 2319 4291 2320 4291 2320 4292 2319 4292 2321 4292 2322 4293 2323 4293 2324 4293 2324 4294 2323 4294 2325 4294 2324 4295 2325 4295 2326 4295 2326 4296 2325 4296 2327 4296 2326 4297 2327 4297 2318 4297 2318 4298 2327 4298 2328 4298 2318 4299 2328 4299 2319 4299 2315 4300 2322 4300 2316 4300 2316 4301 2322 4301 2324 4301 2316 4302 2324 4302 2317 4302 2317 4303 2324 4303 2329 4303 59 4304 58 4304 2321 4304 2321 4305 58 4305 1454 4305 1454 4304 2299 4304 2314 4304 1454 4306 2314 4306 2321 4306 2321 4307 2314 4307 2304 4307 2321 4308 2304 4308 2317 4308 2311 4309 2309 4309 2303 4309 2324 4310 2326 4310 2329 4310 2329 4311 2326 4311 2318 4311 2329 4312 2318 4312 2317 4312 2317 4313 2318 4313 2320 4313 2317 4314 2320 4314 2321 4314 2314 4315 2313 4315 2304 4315 2304 4316 2313 4316 2311 4316 2304 4317 2311 4317 2305 4317 2305 4318 2311 4318 2303 4318 2330 4319 2331 4319 2074 4319 2074 4320 2331 4320 2073 4320 2332 4321 2333 4321 2334 4321 2334 4322 2333 4322 2335 4322 2334 4323 2335 4323 2336 4323 1456 4324 1455 4324 2337 4324 2337 4325 1455 4325 2334 4325 2073 4326 2331 4326 1455 4326 1455 4327 2331 4327 2338 4327 1455 4328 2338 4328 2334 4328 2334 4329 2338 4329 2339 4329 2334 4330 2339 4330 2332 4330 2340 4331 2341 4331 2342 4331 2343 4332 2344 4332 2345 4332 2343 4333 2345 4333 2346 4333 2346 4334 2345 4334 2347 4334 2346 4335 2347 4335 2348 4335 2348 4336 2347 4336 2349 4336 2349 4337 2347 4337 2350 4337 2349 4338 2350 4338 2351 4338 2351 4339 2350 4339 2352 4339 2351 4340 2352 4340 2353 4340 2337 4341 2334 4341 2354 4341 2354 4342 2334 4342 2336 4342 2354 4343 2336 4343 2355 4343 1459 4344 1457 4344 2295 4344 2295 4345 1457 4345 2356 4345 2295 4346 2356 4346 2296 4346 2296 4347 2356 4347 2297 4347 2297 4348 2356 4348 2357 4348 2297 4349 2357 4349 2298 4349 2298 4350 2357 4350 2294 4350 2294 4351 2357 4351 2342 4351 2294 4352 2342 4352 2293 4352 2293 4353 2342 4353 2292 4353 2292 4354 2342 4354 2341 4354 2292 4355 2341 4355 2291 4355 2358 4356 2359 4356 2360 4356 2345 4357 2358 4357 2347 4357 2347 4358 2358 4358 2360 4358 2347 4359 2360 4359 2350 4359 2350 4360 2360 4360 2361 4360 2350 4361 2361 4361 2352 4361 2352 4362 2361 4362 2354 4362 2352 4363 2354 4363 2353 4363 2353 4364 2354 4364 2355 4364 2359 4365 2340 4365 2360 4365 2360 4366 2340 4366 2342 4366 2360 4367 2342 4367 2361 4367 2361 4368 2342 4368 2357 4368 2361 4369 2357 4369 2354 4369 2354 4370 2357 4370 2356 4370 2354 4371 2356 4371 2337 4371 2337 4372 2356 4372 1457 4372 2337 4373 1457 4373 1456 4373 2279 4374 2248 4374 2247 4374 2325 4375 2282 4375 2327 4375 2327 4376 2282 4376 2281 4376 2327 4377 2281 4377 2328 4377 2323 4378 72 4378 2325 4378 2325 4379 72 4379 2278 4379 2325 4380 2278 4380 2282 4380 2307 4381 73 4381 2315 4381 2315 4382 73 4382 72 4382 2315 4383 72 4383 2322 4383 2322 4384 72 4384 2323 4384 2307 4385 2302 4385 73 4385 73 4386 2302 4386 2301 4386 73 4387 2301 4387 2362 4387 2362 4388 2301 4388 2308 4388 2362 4389 2308 4389 2363 4389 2363 4390 2308 4390 2310 4390 2363 4391 2310 4391 2364 4391 2364 4392 2310 4392 2365 4392 2365 4393 2310 4393 2312 4393 2365 4394 2312 4394 2344 4394 2290 4395 2291 4395 2300 4395 2300 4396 2291 4396 2341 4396 2312 4397 2314 4397 2299 4397 2341 4398 2340 4398 2300 4398 2300 4399 2340 4399 2359 4399 2300 4400 2359 4400 2299 4400 2299 4401 2359 4401 2358 4401 2299 4402 2358 4402 2312 4402 2312 4403 2358 4403 2345 4403 2312 4404 2345 4404 2344 4404 59 4405 2252 4405 61 4405 61 4406 2252 4406 2253 4406 59 4407 2321 4407 2252 4407 2252 4408 2321 4408 2319 4408 2252 4409 2319 4409 2247 4409 2247 4410 2319 4410 2328 4410 2247 4411 2328 4411 2279 4411 2279 4412 2328 4412 2281 4412 2229 4413 60 4413 2254 4413 2254 4414 60 4414 61 4414 2254 4398 61 4398 2255 4398 2255 4399 61 4399 2253 4399 2124 4415 2125 4415 2366 4415 2085 4416 2367 4416 2083 4416 2083 4417 2367 4417 2126 4417 2083 4418 2126 4418 1333 4418 2118 4419 2368 4419 2369 4419 2118 4420 2369 4420 2091 4420 2369 4421 2370 4421 2091 4421 2091 4422 2370 4422 2371 4422 2091 4423 2371 4423 2089 4423 2089 4424 2371 4424 2372 4424 2089 4425 2372 4425 2087 4425 2087 4426 2372 4426 2373 4426 2087 4427 2373 4427 2085 4427 2085 4428 2373 4428 2374 4428 2085 4429 2374 4429 2367 4429 2118 4430 2119 4430 2368 4430 2368 4431 2119 4431 2120 4431 2368 4432 2120 4432 2375 4432 2375 4433 2120 4433 2121 4433 2366 4434 2376 4434 2124 4434 2124 4435 2376 4435 2377 4435 2124 4436 2377 4436 2123 4436 2123 4437 2377 4437 2378 4437 2123 4438 2378 4438 2122 4438 2122 4439 2378 4439 2379 4439 2122 4440 2379 4440 2121 4440 2121 4441 2379 4441 2380 4441 2121 4442 2380 4442 2375 4442 2381 4443 2382 4443 2383 4443 2384 4444 2126 4444 2367 4444 2382 4445 2384 4445 2385 4445 2386 4446 2387 4446 2381 4446 2387 4447 2386 4447 2388 4447 2384 4448 2367 4448 2385 4448 2385 4449 2367 4449 2374 4449 2385 4450 2374 4450 2389 4450 2389 4451 2374 4451 2373 4451 2389 4452 2373 4452 2390 4452 2390 4453 2373 4453 2372 4453 2390 4454 2372 4454 2391 4454 2372 4455 2371 4455 2391 4455 2391 4456 2371 4456 2370 4456 2391 4457 2370 4457 2392 4457 2392 4458 2370 4458 2369 4458 2392 4459 2369 4459 2393 4459 2393 4460 2369 4460 2368 4460 2393 4461 2368 4461 2394 4461 2368 4462 2375 4462 2394 4462 2394 4463 2375 4463 2380 4463 2394 4464 2380 4464 2395 4464 2395 4465 2380 4465 2379 4465 2395 4466 2379 4466 2396 4466 2396 4467 2379 4467 2378 4467 2396 4468 2378 4468 2397 4468 2397 4469 2378 4469 2377 4469 2382 4470 2385 4470 2383 4470 2383 4471 2385 4471 2389 4471 2383 4472 2389 4472 2398 4472 2398 4473 2389 4473 2390 4473 2398 4474 2390 4474 2399 4474 2399 4475 2390 4475 2391 4475 2399 4476 2391 4476 2400 4476 2400 4477 2391 4477 2392 4477 2400 4478 2392 4478 2401 4478 2401 4479 2392 4479 2393 4479 2401 4480 2393 4480 2402 4480 2402 4481 2393 4481 2394 4481 2402 4482 2394 4482 2403 4482 2403 4483 2394 4483 2395 4483 2403 4484 2395 4484 2404 4484 2404 4485 2395 4485 2396 4485 2404 4486 2396 4486 2405 4486 2405 4487 2396 4487 2397 4487 2405 4488 2397 4488 2406 4488 2381 4489 2383 4489 2386 4489 2386 4490 2383 4490 2398 4490 2386 4491 2398 4491 2407 4491 2407 4492 2398 4492 2399 4492 2407 4493 2399 4493 2408 4493 2408 4494 2399 4494 2400 4494 2408 4495 2400 4495 2409 4495 2409 4496 2400 4496 2401 4496 2409 4497 2401 4497 2410 4497 2410 4498 2401 4498 2402 4498 2410 4499 2402 4499 2411 4499 2411 4500 2402 4500 2403 4500 2411 4501 2403 4501 2412 4501 2412 4502 2403 4502 2404 4502 2412 4503 2404 4503 2413 4503 2413 4504 2404 4504 2405 4504 2413 4505 2405 4505 2414 4505 2414 4506 2405 4506 2406 4506 2414 4507 2406 4507 2415 4507 2388 4508 2386 4508 2416 4508 2416 4509 2386 4509 2407 4509 2416 4510 2407 4510 2417 4510 2417 4511 2407 4511 2408 4511 2417 4512 2408 4512 2418 4512 2418 4513 2408 4513 2409 4513 2418 4514 2409 4514 2419 4514 2419 4515 2409 4515 2410 4515 2419 4516 2410 4516 2420 4516 2420 4517 2410 4517 2411 4517 2420 4518 2411 4518 2421 4518 2421 4519 2411 4519 2412 4519 2421 4520 2412 4520 2422 4520 2422 4521 2412 4521 2413 4521 2422 4522 2413 4522 2423 4522 2423 4523 2413 4523 2414 4523 2423 4524 2414 4524 2424 4524 2424 4525 2414 4525 2415 4525 2424 4526 2415 4526 66 4526 2425 4527 2376 4527 2366 4527 2397 4528 2377 4528 2376 4528 2376 4529 2425 4529 2397 4529 2397 4530 2425 4530 2426 4530 2397 4531 2426 4531 2406 4531 2406 4532 2426 4532 2427 4532 2406 4533 2427 4533 2415 4533 64 4534 66 4534 2415 4534 2415 4535 2427 4535 64 4535 64 4536 2427 4536 2428 4536 64 4537 2428 4537 62 4537 2366 4538 2429 4538 2425 4538 2425 4539 2429 4539 2430 4539 2425 4540 2430 4540 2426 4540 2426 4541 2430 4541 2431 4541 2426 4542 2431 4542 2427 4542 2427 4543 2431 4543 2432 4543 2427 4544 2432 4544 2428 4544 2135 4545 2433 4545 2128 4545 2128 4545 2433 4545 2366 4545 2128 4545 2366 4545 2125 4545 2213 4546 2214 4546 2434 4546 2215 4547 2212 4547 2435 4547 2209 4548 2210 4548 2436 4548 2211 4549 2207 4549 2270 4549 2211 4550 2270 4550 2210 4550 2209 4551 2436 4551 2212 4551 2215 4552 2435 4552 2214 4552 2437 4553 2438 4553 2439 4553 2439 4554 2438 4554 2440 4554 2439 4555 2440 4555 2434 4555 2434 4556 2440 4556 2183 4556 2434 4557 2183 4557 2213 4557 2441 4558 2442 4558 2443 4558 2443 4559 2442 4559 2444 4559 2443 4560 2444 4560 2445 4560 2445 4561 2444 4561 2446 4561 2445 4562 2446 4562 2437 4562 2437 4563 2446 4563 2447 4563 2437 4564 2447 4564 2438 4564 2210 4565 2270 4565 2436 4565 2436 4566 2270 4566 2262 4566 2436 4567 2262 4567 2448 4567 2448 4568 2262 4568 2261 4568 2448 4569 2261 4569 2449 4569 2449 4570 2261 4570 2272 4570 2449 4571 2272 4571 2450 4571 2450 4572 2272 4572 2259 4572 2450 4573 2259 4573 2451 4573 2451 4574 2259 4574 2258 4574 2451 4575 2258 4575 2452 4575 2452 4576 2258 4576 2276 4576 2452 4577 2276 4577 2453 4577 2453 4578 2276 4578 2275 4578 2453 4579 2275 4579 2454 4579 2454 4580 2275 4580 2274 4580 2454 4581 2274 4581 2455 4581 2212 4582 2436 4582 2435 4582 2435 4583 2436 4583 2448 4583 2435 4584 2448 4584 2456 4584 2456 4585 2448 4585 2449 4585 2456 4586 2449 4586 2457 4586 2457 4587 2449 4587 2450 4587 2457 4588 2450 4588 2458 4588 2458 4589 2450 4589 2451 4589 2458 4590 2451 4590 2459 4590 2459 4591 2451 4591 2452 4591 2459 4592 2452 4592 2460 4592 2460 4593 2452 4593 2453 4593 2460 4594 2453 4594 2461 4594 2461 4595 2453 4595 2454 4595 2461 4596 2454 4596 2462 4596 2462 4597 2454 4597 2455 4597 2462 4598 2455 4598 2463 4598 2214 4599 2435 4599 2434 4599 2434 4600 2435 4600 2456 4600 2434 4601 2456 4601 2439 4601 2439 4602 2456 4602 2457 4602 2439 4603 2457 4603 2437 4603 2437 4604 2457 4604 2458 4604 2437 4605 2458 4605 2445 4605 2445 4606 2458 4606 2459 4606 2445 4607 2459 4607 2443 4607 2443 4608 2459 4608 2460 4608 2443 4609 2460 4609 2441 4609 2441 4610 2460 4610 2461 4610 2441 4611 2461 4611 2464 4611 2464 4612 2461 4612 2462 4612 2464 4613 2462 4613 2465 4613 2465 4614 2462 4614 2463 4614 2465 4615 2463 4615 2466 4615 2467 4616 2468 4616 2466 4616 2466 4617 2468 4617 2469 4617 2466 4618 2469 4618 2465 4618 2465 4619 2469 4619 2470 4619 2465 4620 2470 4620 2464 4620 2464 4621 2470 4621 2471 4621 2464 4622 2471 4622 2441 4622 2441 4623 2471 4623 2472 4623 2441 4624 2472 4624 2442 4624 2473 4625 2467 4625 2474 4625 2474 4626 2467 4626 2466 4626 2474 4627 2466 4627 2475 4627 2475 4628 2466 4628 2463 4628 2475 4629 2463 4629 2476 4629 2476 4630 2463 4630 2455 4630 2476 4631 2455 4631 67 4631 67 4632 2455 4632 2274 4632 1390 4633 2183 4633 2139 4633 2139 4634 2183 4634 2440 4634 2139 4635 2440 4635 2141 4635 2141 4636 2440 4636 2438 4636 2141 4637 2438 4637 2143 4637 2143 4638 2438 4638 2447 4638 2143 4639 2447 4639 2446 4639 2143 4640 2446 4640 2146 4640 2146 4641 2446 4641 2444 4641 2146 4642 2444 4642 2147 4642 2152 4643 2471 4643 2470 4643 2152 4644 2470 4644 2154 4644 2444 4645 2442 4645 2147 4645 2147 4646 2442 4646 2472 4646 2147 4647 2472 4647 2149 4647 2149 4648 2472 4648 2471 4648 2149 4649 2471 4649 2151 4649 2151 4650 2471 4650 2152 4650 2433 4651 2135 4651 2477 4651 2477 4652 2135 4652 2160 4652 2477 4653 2160 4653 2473 4653 2473 4654 2160 4654 2158 4654 2473 4655 2158 4655 2467 4655 2467 4656 2158 4656 2156 4656 2467 4657 2156 4657 2468 4657 2468 4658 2156 4658 2154 4658 2468 4659 2154 4659 2469 4659 2469 4660 2154 4660 2470 4660 71 4661 62 4661 2478 4661 2478 4662 62 4662 2428 4662 2478 4663 2428 4663 2479 4663 2430 4664 2480 4664 2431 4664 2431 4665 2480 4665 2479 4665 2431 4665 2479 4665 2432 4665 2432 4666 2479 4666 2428 4666 2366 4667 2433 4667 2429 4667 2429 4667 2433 4667 2481 4667 2429 4668 2481 4668 2430 4668 2430 4669 2481 4669 2482 4669 2430 4664 2482 4664 2480 4664 2483 4670 69 4670 71 4670 2476 4671 67 4671 69 4671 69 4672 2483 4672 2476 4672 2476 4673 2483 4673 2484 4673 2476 4674 2484 4674 2475 4674 2475 4675 2484 4675 2485 4675 2475 4676 2485 4676 2474 4676 2477 4677 2473 4677 2474 4677 2474 4678 2485 4678 2477 4678 2477 4679 2485 4679 2481 4679 2477 4680 2481 4680 2433 4680 71 4681 2478 4681 2483 4681 2483 4682 2478 4682 2479 4682 2483 4683 2479 4683 2484 4683 2484 4684 2479 4684 2480 4684 2484 4685 2480 4685 2485 4685 2485 4686 2480 4686 2482 4686 2485 4687 2482 4687 2481 4687 2486 4688 2487 4688 2488 4688 2488 4689 2487 4689 2489 4689 2488 4690 2489 4690 2490 4690 2490 4691 2489 4691 2491 4691 2490 4692 2491 4692 2492 4692 2492 4693 2491 4693 2493 4693 2492 4694 2493 4694 2494 4694 2494 4695 2493 4695 2495 4695 2494 4696 2495 4696 2127 4696 2127 4697 2495 4697 1478 4697 2388 4698 2486 4698 2387 4698 2387 4699 2486 4699 2488 4699 2387 4700 2488 4700 2381 4700 2381 4701 2488 4701 2490 4701 2381 4702 2490 4702 2382 4702 2382 4703 2490 4703 2492 4703 2382 4704 2492 4704 2384 4704 2384 4705 2492 4705 2494 4705 2384 4706 2494 4706 2126 4706 2126 4707 2494 4707 2127 4707 935 4708 1479 4708 2496 4708 1484 4709 955 4709 1480 4709 2497 4710 1497 4710 2498 4710 2498 4711 1497 4711 1498 4711 2498 4712 1498 4712 2499 4712 2499 4713 1498 4713 1499 4713 2499 4714 1499 4714 2500 4714 2500 4715 1499 4715 1500 4715 2500 4716 1500 4716 2496 4716 2496 4717 1500 4717 1484 4717 2496 4718 1484 4718 935 4718 935 4719 1484 4719 1480 4719 2487 4720 2497 4720 2489 4720 2489 4721 2497 4721 2498 4721 2489 4722 2498 4722 2491 4722 2491 4723 2498 4723 2499 4723 2491 4724 2499 4724 2493 4724 2493 4725 2499 4725 2500 4725 2493 4726 2500 4726 2495 4726 2495 4727 2500 4727 2496 4727 2495 4728 2496 4728 1478 4728 1478 4729 2496 4729 1479 4729 1493 4730 1492 4730 2501 4730 1492 4731 1497 4731 2502 4731 1518 4732 1503 4732 2503 4732 2503 4733 1503 4733 1502 4733 2503 4734 1502 4734 2504 4734 1518 4735 1512 4735 1503 4735 1503 4736 1512 4736 1509 4736 1503 4737 1509 4737 1506 4737 1506 4738 1509 4738 991 4738 1527 4739 1523 4739 2503 4739 2503 4740 1523 4740 1519 4740 2503 4741 1519 4741 1518 4741 1527 4742 2503 4742 1524 4742 1524 4743 2503 4743 2504 4743 1524 4744 2504 4744 1521 4744 1521 4745 2504 4745 2505 4745 1521 4746 2505 4746 1522 4746 1492 4747 2502 4747 2501 4747 2501 4748 2502 4748 2506 4748 2501 4749 2506 4749 2507 4749 1502 4750 1493 4750 2504 4750 2504 4751 1493 4751 2501 4751 2504 4752 2501 4752 2505 4752 2505 4753 2501 4753 2507 4753 2505 4754 2507 4754 2508 4754 1724 4755 1840 4755 1789 4755 1724 72 1789 72 1740 72 1740 4756 1789 4756 1786 4756 1740 4757 1786 4757 1739 4757 1739 4758 1786 4758 1783 4758 1739 4759 1783 4759 1741 4759 1553 72 1542 72 1956 72 1956 72 1542 72 1544 72 1956 72 1544 72 1957 72 1956 72 1954 72 1553 72 1553 4760 1954 4760 1953 4760 1553 4761 1953 4761 1960 4761 2051 72 1531 72 1993 72 1993 72 1531 72 1529 72 1741 72 1783 72 1745 72 1745 72 1783 72 1785 72 1745 72 1785 72 1747 72 1747 72 1785 72 1825 72 1747 72 1825 72 1753 72 1753 72 1825 72 1828 72 1753 72 1828 72 1759 72 1814 4762 1815 4762 1652 4762 1960 4763 1962 4763 1553 4763 1553 72 1962 72 2042 72 1553 72 2042 72 1574 72 2192 4764 1763 4764 1828 4764 1828 4765 1763 4765 1761 4765 1828 4766 1761 4766 1759 4766 1544 72 1555 72 1957 72 1957 72 1555 72 1556 72 1957 72 1556 72 2049 72 2049 4767 1556 4767 1557 4767 2049 72 1557 72 2050 72 2050 72 1557 72 1748 72 2050 4768 1748 4768 2051 4768 2051 72 1748 72 1536 72 2051 4769 1536 4769 1531 4769 1529 72 1520 72 1993 72 1993 4770 1520 4770 1522 4770 1993 72 1522 72 1933 72 1933 72 1522 72 2505 72 1933 4771 2505 4771 1932 4771 1828 4772 1829 4772 2192 4772 2192 4773 1829 4773 1781 4773 2192 4774 1781 4774 2190 4774 2190 72 1781 72 1780 72 2190 72 1780 72 2191 72 2191 72 1780 72 1779 72 2191 72 1779 72 2267 72 2267 72 1779 72 1778 72 2267 4775 1778 4775 2268 4775 2268 72 1778 72 1773 72 2268 72 1773 72 2289 72 2289 72 1773 72 1772 72 2289 72 1772 72 2227 72 1652 4776 1815 4776 1655 4776 1655 72 1815 72 1817 72 1655 4777 1817 4777 1656 4777 1656 72 1817 72 1819 72 1656 72 1819 72 1681 72 1652 4778 1651 4778 1814 4778 1814 4779 1651 4779 1649 4779 1814 4780 1649 4780 1922 4780 1922 4781 1649 4781 1648 4781 1922 4782 1648 4782 1940 4782 1940 4783 1648 4783 1615 4783 1940 4784 1615 4784 1941 4784 2509 72 2065 72 2510 72 2510 4785 2065 4785 2057 4785 2510 4786 2057 4786 2511 4786 2511 72 2057 72 2056 72 2511 4787 2056 4787 2512 4787 2512 72 2056 72 1932 72 2512 4788 1932 4788 2508 4788 2508 4789 1932 4789 2505 4789 1681 4790 1819 4790 1682 4790 1682 4791 1819 4791 1821 4791 1682 72 1821 72 1684 72 1941 4792 1615 4792 2037 4792 2037 4793 1615 4793 1613 4793 2037 72 1613 72 2042 72 2042 4794 1613 4794 1612 4794 2042 72 1612 72 1623 72 1678 4795 1700 4795 1840 4795 1840 72 1700 72 1699 72 1840 72 1699 72 1821 72 1821 4796 1699 4796 1685 4796 1821 4797 1685 4797 1684 4797 1623 4798 1621 4798 2042 4798 2042 72 1621 72 1620 72 2042 4799 1620 4799 1636 4799 1636 72 1637 72 2042 72 2042 4800 1637 4800 1619 4800 2042 4801 1619 4801 1618 4801 1724 4802 1725 4802 1840 4802 1840 4803 1725 4803 1659 4803 1840 4804 1659 4804 1658 4804 1658 72 1676 72 1840 72 1840 4805 1676 4805 1680 4805 1840 72 1680 72 1678 72 1618 72 1646 72 2042 72 2042 4806 1646 4806 1647 4806 2042 4807 1647 4807 1598 4807 1598 72 1594 72 2042 72 2042 4808 1594 4808 1573 4808 2042 4809 1573 4809 1574 4809 2065 4810 2509 4810 2064 4810 2064 4811 2509 4811 2330 4811 2068 4812 1242 4812 2072 4812 2072 4813 1242 4813 2060 4813 2072 4814 2060 4814 2071 4814 2060 4815 2061 4815 2071 4815 2071 4816 2061 4816 2063 4816 2071 4817 2063 4817 2070 4817 2070 4818 2063 4818 2064 4818 2070 4819 2064 4819 2069 4819 2069 4820 2064 4820 2330 4820 2069 4821 2330 4821 2074 4821 2416 4822 2417 4822 2513 4822 2331 4823 2330 4823 2338 4823 2338 4824 2330 4824 2509 4824 2338 4825 2509 4825 2339 4825 2339 4826 2509 4826 2332 4826 2355 4827 2336 4827 2514 4827 2514 4828 2336 4828 2335 4828 2514 4829 2335 4829 2515 4829 2515 4830 2335 4830 2333 4830 2515 4831 2333 4831 2332 4831 2346 4832 2348 4832 2516 4832 2516 4833 2348 4833 2349 4833 2516 4834 2349 4834 2517 4834 2517 4835 2349 4835 2351 4835 2517 4836 2351 4836 2514 4836 2514 4837 2351 4837 2353 4837 2514 4838 2353 4838 2355 4838 2346 4839 2516 4839 2343 4839 2343 4840 2516 4840 2518 4840 2343 4841 2518 4841 2344 4841 2362 4842 2363 4842 2519 4842 2519 4843 2363 4843 2364 4843 2519 4844 2364 4844 2518 4844 2518 4845 2364 4845 2365 4845 2518 4846 2365 4846 2344 4846 63 4847 2520 4847 65 4847 65 4848 2520 4848 2424 4848 65 4849 2424 4849 66 4849 2420 4850 2421 4850 2521 4850 2521 4851 2421 4851 2422 4851 2521 4852 2422 4852 2520 4852 2520 4853 2422 4853 2423 4853 2520 4854 2423 4854 2424 4854 2420 4855 2521 4855 2419 4855 2419 4856 2521 4856 2522 4856 2419 4857 2522 4857 2418 4857 2523 4858 2486 4858 2513 4858 2513 4859 2486 4859 2388 4859 2513 4860 2388 4860 2416 4860 2502 4861 1497 4861 2524 4861 2524 4862 1497 4862 2497 4862 2524 4863 2497 4863 2523 4863 2523 4864 2497 4864 2487 4864 2523 4865 2487 4865 2486 4865 2502 4866 2524 4866 2506 4866 2506 4867 2524 4867 2525 4867 2506 4868 2525 4868 2507 4868 2332 4869 2509 4869 2515 4869 2515 4870 2509 4870 2510 4870 2515 4871 2510 4871 2511 4871 2508 4872 2507 4872 2512 4872 2512 4873 2507 4873 2525 4873 2512 4874 2525 4874 2526 4874 2526 4875 2525 4875 2524 4875 2526 4876 2524 4876 2527 4876 2527 4877 2524 4877 2523 4877 2527 4878 2523 4878 2528 4878 2528 4879 2523 4879 2513 4879 2528 4880 2513 4880 2522 4880 2522 4881 2513 4881 2417 4881 2522 4882 2417 4882 2418 4882 73 4883 2362 4883 63 4883 63 4884 2362 4884 2519 4884 63 4885 2519 4885 2520 4885 2520 4886 2519 4886 2518 4886 2520 4887 2518 4887 2521 4887 2521 4888 2518 4888 2516 4888 2521 4889 2516 4889 2522 4889 2522 4890 2516 4890 2517 4890 2522 4891 2517 4891 2528 4891 2528 4892 2517 4892 2514 4892 2528 4893 2514 4893 2527 4893 2527 4894 2514 4894 2515 4894 2527 4895 2515 4895 2526 4895 2526 4896 2515 4896 2511 4896 2526 4897 2511 4897 2512 4897 45 69 52 69 37 69 37 69 52 69 38 69 38 1295 52 1295 39 1295 39 1295 52 1295 54 1295 39 1295 54 1295 56 1295 2529 69 2530 69 2531 69 2531 69 2530 69 2532 69 2531 4898 2532 4898 2533 4898 2533 69 2532 69 2534 69 2535 1525 2536 1525 2537 1525 2535 4899 2537 4899 2538 4899 2538 1525 2537 1525 2539 1525 2538 1525 2539 1525 2540 1525 2541 1480 2542 1480 2540 1480 2543 1480 2538 1480 2540 1480 2543 1480 2540 1480 2544 1480 2545 1480 2541 1480 2546 1480 2546 1480 2541 1480 2540 1480 2546 1480 2540 1480 2547 1480 2542 1480 2548 1480 2540 1480 2540 4900 2548 4900 2549 4900 2540 1480 2549 1480 2544 1480 2550 4901 2536 4901 2535 4901 2535 4902 2551 4902 2550 4902 2550 4903 2551 4903 2552 4903 2550 4904 2552 4904 2553 4904 2553 4905 2554 4905 2550 4905 2550 4906 2554 4906 2555 4906 2550 4907 2555 4907 2556 4907 2557 4908 2558 4908 2559 4908 2560 4909 2561 4909 2557 4909 2557 4910 2561 4910 2562 4910 2557 4911 2562 4911 2558 4911 2536 4912 2550 4912 2534 4912 2534 4913 2550 4913 2557 4913 2534 4914 2557 4914 2533 4914 2533 4915 2557 4915 2559 4915 2533 4916 2559 4916 2563 4916 2564 4917 2565 4917 2566 4917 2564 4918 2566 4918 2567 4918 2567 4919 2566 4919 2568 4919 2567 4920 2568 4920 2569 4920 2569 4921 2568 4921 2557 4921 2557 4922 2568 4922 2570 4922 2557 4923 2570 4923 2560 4923 2560 4924 2570 4924 2561 4924 2561 4925 2570 4925 2571 4925 2561 4926 2571 4926 2562 4926 2562 4927 2571 4927 2572 4927 2562 4928 2572 4928 2558 4928 2558 4929 2572 4929 2573 4929 2558 4930 2573 4930 2559 4930 2573 4931 2574 4931 2559 4931 2559 4932 2574 4932 2575 4932 2559 4933 2575 4933 2563 4933 2531 4934 2533 4934 2576 4934 2576 4935 2533 4935 2563 4935 2576 4936 2563 4936 2577 4936 2577 4937 2563 4937 2575 4937 2569 4938 2557 4938 2578 4938 2578 4939 2557 4939 2550 4939 2538 4940 2579 4940 2535 4940 2535 4941 2579 4941 2551 4941 2579 4942 2580 4942 2551 4942 2551 4943 2580 4943 2581 4943 2551 4944 2581 4944 2552 4944 2552 4945 2581 4945 2582 4945 2552 4946 2582 4946 2553 4946 2553 4947 2582 4947 2583 4947 2553 4948 2583 4948 2554 4948 2554 4949 2583 4949 2584 4949 2554 4950 2584 4950 2555 4950 2555 4951 2584 4951 2585 4951 2555 4952 2585 4952 2556 4952 2585 4953 2586 4953 2556 4953 2556 4954 2586 4954 2587 4954 2556 4955 2587 4955 2550 4955 2588 4956 2589 4956 2590 4956 2590 4957 2589 4957 2591 4957 2590 4958 2591 4958 2587 4958 2587 4959 2591 4959 2578 4959 2587 4960 2578 4960 2550 4960 2542 4961 2541 4961 2592 4961 2592 4962 2541 4962 2593 4962 2593 4963 2541 4963 2594 4963 2594 4964 2541 4964 2545 4964 2594 4965 2545 4965 2595 4965 2595 4966 2545 4966 2596 4966 2596 4967 2545 4967 2546 4967 2596 4968 2546 4968 2597 4968 2597 4969 2546 4969 2598 4969 2598 4970 2546 4970 2547 4970 2598 4971 2547 4971 2599 4971 2599 4972 2547 4972 2600 4972 2600 4973 2547 4973 2540 4973 2600 4974 2540 4974 2539 4974 2601 1480 2602 1480 2603 1480 2531 1480 2604 1480 2529 1480 2529 1480 2604 1480 2605 1480 2529 1480 2605 1480 2606 1480 2603 1480 2607 1480 2601 1480 2601 1480 2607 1480 2529 1480 2601 1480 2529 1480 2608 1480 2608 4975 2529 4975 2606 4975 2608 1480 2606 1480 2609 1480 2610 4976 2579 4976 2538 4976 2611 4977 2612 4977 2613 4977 2612 4978 2611 4978 2585 4978 2614 4979 2585 4979 2611 4979 2585 4980 2615 4980 2616 4980 2617 4981 2615 4981 2585 4981 2618 4982 2588 4982 2590 4982 2619 4983 2620 4983 2618 4983 2620 4984 2619 4984 2621 4984 2621 4985 2619 4985 2622 4985 2621 4986 2622 4986 2623 4986 2623 4987 2622 4987 2624 4987 2624 4988 2622 4988 2625 4988 2624 4989 2625 4989 2626 4989 2626 4990 2625 4990 2627 4990 2627 4991 2625 4991 2628 4991 2627 4992 2628 4992 2629 4992 2630 4993 2631 4993 2628 4993 2628 4994 2631 4994 2632 4994 2628 4995 2632 4995 2629 4995 2584 4996 2612 4996 2585 4996 2633 4997 2616 4997 2634 4997 2634 4998 2616 4998 2615 4998 2634 4999 2615 4999 2635 4999 2635 5000 2615 5000 2617 5000 2635 5001 2617 5001 2636 5001 2619 5002 2633 5002 2622 5002 2622 5003 2633 5003 2634 5003 2622 5004 2634 5004 2625 5004 2625 5005 2634 5005 2635 5005 2625 5006 2635 5006 2628 5006 2628 5007 2635 5007 2636 5007 2628 5008 2636 5008 2630 5008 2618 5009 2590 5009 2619 5009 2619 5010 2590 5010 2587 5010 2619 5011 2587 5011 2633 5011 2633 5012 2587 5012 2586 5012 2633 5013 2586 5013 2616 5013 2616 5014 2586 5014 2585 5014 2584 5015 2583 5015 2612 5015 2612 5016 2583 5016 2582 5016 2612 5017 2582 5017 2613 5017 2613 5018 2582 5018 2581 5018 2613 5019 2581 5019 2580 5019 2614 5020 2611 5020 2637 5020 2637 5021 2611 5021 2613 5021 2637 5022 2613 5022 2610 5022 2610 5023 2613 5023 2580 5023 2610 5024 2580 5024 2579 5024 2544 5025 2549 5025 2630 5025 2630 5026 2549 5026 2548 5026 2630 5027 2548 5027 2631 5027 2543 5028 2544 5028 2638 5028 2638 5029 2544 5029 2630 5029 2638 5030 2630 5030 2639 5030 2639 5031 2630 5031 2636 5031 2639 5032 2636 5032 2640 5032 2640 5033 2636 5033 2617 5033 2640 5034 2617 5034 2585 5034 2538 5035 2543 5035 2610 5035 2610 5036 2543 5036 2638 5036 2610 5037 2638 5037 2637 5037 2637 5038 2638 5038 2639 5038 2637 5039 2639 5039 2614 5039 2614 5040 2639 5040 2640 5040 2614 5041 2640 5041 2585 5041 2589 5042 2641 5042 2591 5042 2591 5043 2641 5043 2642 5043 2591 5044 2642 5044 2578 5044 2578 5045 2642 5045 2643 5045 2578 5046 2643 5046 2569 5046 2643 5047 2644 5047 2569 5047 2569 5048 2644 5048 2645 5048 2569 5049 2645 5049 2567 5049 2567 5050 2645 5050 2564 5050 2577 5051 2575 5051 2646 5051 2647 5020 2648 5020 2649 5020 2574 5052 2573 5052 2650 5052 2648 5053 2647 5053 2571 5053 2571 5054 2651 5054 2650 5054 2652 4981 2651 4981 2571 4981 2653 5055 2654 5055 2655 5055 2656 5056 2609 5056 2606 5056 2657 5057 2658 5057 2659 5057 2659 5058 2658 5058 2660 5058 2660 5059 2658 5059 2661 5059 2660 5060 2661 5060 2662 5060 2653 5061 2655 5061 2663 5061 2575 5062 2574 5062 2646 5062 2646 5063 2574 5063 2650 5063 2646 5064 2650 5064 2664 5064 2664 5065 2650 5065 2651 5065 2664 4999 2651 4999 2665 4999 2665 5000 2651 5000 2652 5000 2665 5001 2652 5001 2666 5001 2667 5022 2649 5022 2668 5022 2668 5066 2649 5066 2648 5066 2668 5067 2648 5067 2669 5067 2669 5068 2648 5068 2571 5068 2576 5069 2577 5069 2670 5069 2670 5070 2577 5070 2646 5070 2670 5071 2646 5071 2671 5071 2671 5072 2646 5072 2664 5072 2671 5073 2664 5073 2657 5073 2657 5074 2664 5074 2665 5074 2657 5006 2665 5006 2658 5006 2658 5075 2665 5075 2666 5075 2658 5076 2666 5076 2661 5076 2573 5077 2572 5077 2650 5077 2650 5078 2572 5078 2571 5078 2654 5079 2662 5079 2655 5079 2655 5080 2662 5080 2661 5080 2655 5081 2661 5081 2672 5081 2672 5082 2661 5082 2666 5082 2672 5083 2666 5083 2673 5083 2673 5033 2666 5033 2652 5033 2673 5084 2652 5084 2571 5084 2571 5085 2570 5085 2669 5085 2669 5086 2570 5086 2568 5086 2669 5087 2568 5087 2668 5087 2668 5088 2568 5088 2566 5088 2668 5089 2566 5089 2667 5089 2667 5090 2566 5090 2565 5090 2667 5091 2565 5091 2674 5091 2659 5092 2656 5092 2657 5092 2657 5093 2656 5093 2606 5093 2657 5094 2606 5094 2671 5094 2671 5095 2606 5095 2605 5095 2671 5096 2605 5096 2670 5096 2670 5097 2605 5097 2604 5097 2670 5098 2604 5098 2576 5098 2576 5099 2604 5099 2531 5099 2674 5100 2663 5100 2667 5100 2667 5101 2663 5101 2655 5101 2667 5102 2655 5102 2649 5102 2649 5103 2655 5103 2672 5103 2649 5104 2672 5104 2647 5104 2647 5105 2672 5105 2673 5105 2647 5106 2673 5106 2571 5106 2530 5107 2529 5107 2675 5107 2675 5108 2529 5108 2607 5108 2603 5109 2676 5109 2607 5109 2607 5110 2676 5110 2677 5110 2607 5111 2677 5111 2675 5111 2602 5112 2678 5112 2603 5112 2603 5113 2678 5113 2679 5113 2603 5114 2679 5114 2676 5114 2601 5115 2680 5115 2602 5115 2602 5116 2680 5116 2681 5116 2602 5117 2681 5117 2678 5117 2608 5118 2682 5118 2601 5118 2601 5119 2682 5119 2683 5119 2601 5120 2683 5120 2680 5120 2684 1295 2537 1295 2536 1295 2534 5121 2532 5121 2685 5121 2534 1295 2685 1295 2536 1295 2536 5122 2685 5122 2686 5122 2536 5123 2686 5123 2644 5123 2644 1295 2643 1295 2536 1295 2536 5124 2643 5124 2687 5124 2536 5125 2687 5125 2684 5125 2609 5126 2656 5126 2685 5126 2653 5127 2663 5127 2688 5127 2663 5128 2674 5128 2688 5128 2688 5129 2674 5129 2565 5129 2688 5130 2565 5130 2564 5130 2660 5131 2688 5131 2659 5131 2659 5132 2688 5132 2656 5132 2660 5133 2662 5133 2688 5133 2688 5134 2662 5134 2654 5134 2688 5135 2654 5135 2653 5135 2683 5136 2682 5136 2689 5136 2689 5137 2682 5137 2608 5137 2689 5138 2608 5138 2609 5138 2678 5139 2681 5139 2689 5139 2689 5140 2681 5140 2680 5140 2689 5141 2680 5141 2683 5141 2677 5142 2676 5142 2689 5142 2689 5143 2676 5143 2679 5143 2689 5144 2679 5144 2678 5144 2685 5145 2532 5145 2609 5145 2609 5146 2532 5146 2530 5146 2609 5147 2530 5147 2689 5147 2689 5148 2530 5148 2675 5148 2689 5149 2675 5149 2677 5149 2656 5150 2688 5150 2685 5150 2685 5151 2688 5151 2564 5151 2685 5152 2564 5152 2686 5152 2686 5153 2564 5153 2645 5153 2686 5154 2645 5154 2644 5154 2690 5155 2539 5155 2537 5155 2539 5156 2690 5156 2600 5156 2597 5157 2598 5157 2690 5157 2690 5158 2598 5158 2599 5158 2690 5159 2599 5159 2600 5159 2542 5160 2592 5160 2690 5160 2690 5161 2592 5161 2593 5161 2690 5162 2593 5162 2594 5162 2594 5163 2595 5163 2690 5163 2690 5164 2595 5164 2596 5164 2690 5165 2596 5165 2597 5165 2542 5166 2690 5166 2548 5166 2548 5167 2690 5167 2537 5167 2548 5168 2537 5168 2631 5168 2631 5169 2537 5169 2684 5169 2631 5170 2684 5170 2632 5170 2621 5171 2623 5171 2684 5171 2684 5172 2623 5172 2624 5172 2684 5173 2624 5173 2626 5173 2588 5174 2618 5174 2684 5174 2684 5175 2618 5175 2620 5175 2684 5176 2620 5176 2621 5176 2626 5177 2627 5177 2684 5177 2684 5178 2627 5178 2629 5178 2684 5179 2629 5179 2632 5179 2643 5180 2642 5180 2687 5180 2687 5181 2642 5181 2641 5181 2687 5182 2641 5182 2684 5182 2684 5183 2641 5183 2589 5183 2684 5184 2589 5184 2588 5184

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + -0.2908648 -0.7711008 0.5663932 4.076245 0.9551711 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054209 -0.6141704 -6.925791 -4.01133e-9 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_C6M2.dae b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_C6M2.dae new file mode 100644 index 0000000..53e75da --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_C6M2.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:15.508647 + 2012-07-23T02:15:15.508662 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.00000 -7.45454 5.04167 -2.00000 -8.46762 3.04968 -2.00000 -8.95760 0.87927 -2.00000 -6.00089 1.26557 -2.00000 -5.98181 6.72267 -2.00000 -5.87041 2.08118 -2.00000 -5.49317 2.70207 -2.00000 -4.91993 3.14687 -2.00000 -4.22507 3.35807 -2.00000 -4.14030 7.98967 -2.00000 -3.50089 3.30717 -1.99580 1.04911 2.95447 -2.00000 -2.04357 8.76267 -2.00000 0.17909 8.99567 -2.00000 2.39064 8.67368 -1.86600 4.77932 3.43247 -2.00000 4.45473 7.81767 -2.00000 5.04250 4.35527 -2.00000 5.85836 4.74957 -2.00000 6.24414 6.47868 -2.00000 6.75372 4.88217 -2.00000 7.64707 4.74197 -6.00000 7.99883 -0.06943 -6.00000 7.70889 -2.13763 -6.00000 7.74360 2.00337 -6.00000 6.96060 3.93948 -6.00000 6.89354 -4.06023 -6.00000 5.70319 5.60667 -6.00000 5.60834 -5.70643 -6.00000 4.05705 6.89167 -6.00000 3.94089 -6.96383 -6.00000 2.13437 7.70767 -6.00000 2.00481 -7.74683 -6.00000 -0.00089 -0.00233 -6.00000 0.06618 7.99767 -6.00000 -0.06795 -8.00203 -6.00000 -2.00659 7.74168 -6.00000 -2.13615 -7.71213 -6.00000 -3.94267 6.95867 -6.00000 -4.05883 -6.89673 -6.00000 -5.61012 5.70168 -6.00000 -5.70497 -5.61153 -6.00000 -6.89532 4.05557 -6.00000 -6.96238 -3.94413 -6.00000 -7.71067 2.13297 -6.00000 -7.74538 -2.00803 -6.00000 -8.00061 0.06477 -3.60560 4.59911 -7.73793 -3.60560 5.87471 -6.81972 3.60550 4.59911 -7.73793 3.60550 5.87471 -6.81973 -3.60560 6.97112 -5.69363 3.60550 6.97111 -5.69363 -3.60560 7.85490 -4.39393 3.60550 7.85490 -4.39393 -3.60560 8.49911 -2.96033 3.60550 8.49911 -2.96033 -3.60560 -5.00089 -7.48563 -3.60560 -3.44530 -8.31712 3.60550 -5.00089 -7.48563 3.60550 -3.44496 -8.31723 -3.60560 -1.75737 -8.82922 3.60550 -1.75665 -8.82943 -3.60560 -0.00089 -9.00233 3.60550 -0.00089 -9.00233 -3.60560 7.49365 4.98087 -1.89600 8.00920 4.10117 -1.70680 8.23875 3.61787 -1.34180 8.49911 2.95567 -3.60560 8.49911 2.95567 -3.60560 6.01519 6.69167 -3.60560 4.15704 7.97968 -3.60560 2.03647 8.76367 -3.60560 -0.21260 8.99567 -3.60560 -2.44848 8.65868 -3.60560 -4.52976 7.77467 -3.60560 -6.32525 6.40067 -3.60560 -7.72158 4.62267 -3.60560 -8.63065 2.55248 -3.60560 -8.99508 0.32108 -3.60560 -8.79186 -1.93072 -2.67480 -8.87480 -1.50352 -2.18090 -8.99973 -0.14673 -3.15220 -8.54995 -2.81543 -3.60560 -8.03383 -4.06093 -1.00000 -3.75089 2.33887 1.00000 -3.75089 2.33887 -3.60560 2.09911 -8.75393 3.60550 2.09911 -8.75393 -1.00000 5.17159 3.12238 1.00000 5.17159 3.12238 0.00000 -5.00089 -0.00233 -1.00000 -5.00089 0.93118 1.00000 -5.00089 1.10617 1.00000 -5.00089 1.37067 -1.00000 -5.00089 1.37067 1.37480 -5.00089 -0.58433 -1.25900 -5.00089 -0.53753 -2.31300 -6.00089 -0.50973 -4.17820 -6.95020 -5.63412 -4.34790 -6.49255 -6.10052 -4.54170 -5.78034 -6.70483 -1.00000 -4.74733 2.03607 1.00000 -4.74552 2.03817 1.00000 5.57884 3.51017 -1.00000 5.57893 3.51017 1.00000 6.07904 3.76957 -1.00000 6.07915 3.76968 1.00000 6.63105 3.87917 -1.00000 6.63115 3.87917 1.00000 7.19123 3.83077 -1.00000 7.19131 3.83077 1.00000 7.71590 3.62837 -1.00000 7.71601 3.62827 1.00000 8.16394 3.28727 -1.00000 8.16406 3.28717 1.00000 8.49911 2.83508 -1.00000 8.49911 2.83508 -1.67330 -5.07965 -0.53843 -4.11050 -5.05836 -7.39513 -4.32460 -5.19024 -7.24833 -2.01210 -5.29806 -0.52692 -4.45570 -5.35820 -7.08053 -1.71140 -5.29806 1.17887 -1.70710 -4.79262 2.39278 -1.68300 -3.67164 2.64587 -5.15080 0.02667 -8.57373 -1.50000 5.06648 3.20547 -1.70710 5.92460 4.02497 -1.70710 7.13800 4.14037 -5.15080 2.04048 -8.32713 5.25480 8.49911 -0.00233 5.15080 8.49911 -1.10663 5.15080 8.49911 1.10197 4.97780 8.49911 -1.69952 5.07200 8.49911 1.41367 4.96590 8.49911 1.72547 4.72950 8.49911 -2.20792 4.82350 8.49911 2.03877 4.63240 8.49911 2.34737 4.40720 8.49911 -2.60963 4.36760 8.49911 2.64117 4.01370 8.49911 -2.87433 4.00940 8.49911 2.87157 3.60550 8.49911 2.95567 -0.00000 8.49911 -0.00233 1.34180 8.49911 2.95567 -4.01250 8.49911 -2.87492 -4.01070 8.49911 2.87097 -4.40320 8.49911 2.60887 -4.40880 8.49911 -2.60823 -4.72670 8.49911 2.20777 -4.72850 8.49911 -2.20963 -4.97660 8.49911 -1.70243 -4.97670 8.49911 1.69757 -5.15080 8.49911 -1.10663 -5.15080 8.49911 1.10197 -5.25480 8.49911 -0.00234 -5.15080 -1.16784 -8.49393 -5.15080 -2.39342 -8.23302 -5.15080 -3.69770 -7.73553 -5.15080 -5.03250 -6.94153 -5.15080 -6.33935 -5.77232 -5.15080 -7.48297 -4.18423 -5.15080 -8.26608 -2.27303 -5.15080 -8.57061 -0.17332 -5.15080 -8.34856 1.94337 -5.15080 -7.65831 3.84908 -5.15080 -6.65255 5.40367 -5.15080 -5.48446 6.58567 -5.15080 -4.27482 7.42767 -5.15080 -3.07933 7.99767 -5.15080 -1.92971 8.34967 -5.15080 -0.86492 8.52567 -5.15080 0.07097 8.56867 -5.15080 5.86632 -6.25092 -5.15080 4.29269 -7.42083 -5.15080 7.13263 -4.75442 -5.15080 8.02585 -3.00912 -5.15080 8.01546 3.03207 -5.15080 7.13700 4.74317 -5.15080 5.98916 6.12867 -5.15080 4.73707 7.14067 -5.15080 3.47752 7.83167 -5.15080 2.25250 8.26767 -5.15080 1.10237 8.49767 2.00000 6.26146 6.46167 2.00000 7.64707 4.74197 2.00000 6.75408 4.88217 2.00000 5.85895 4.74967 2.00000 5.04316 4.35577 2.00000 4.49639 7.79367 2.00000 4.38705 3.74247 2.00000 2.45995 8.65467 1.99160 1.03584 2.94627 2.00000 0.27493 8.99368 2.00000 -1.92679 8.78967 2.00000 -3.50089 3.30717 2.00000 -4.01233 8.05467 2.00000 -4.21819 3.35877 2.00000 -4.91452 3.14967 2.00000 -5.48962 2.70607 2.00000 -5.85578 6.83267 2.00000 -5.86839 2.08647 2.00000 -6.00089 1.26557 2.00000 -7.34581 5.19867 2.00000 -8.93237 1.10617 2.00000 -8.39242 3.25067 6.00000 -7.47839 2.84148 6.00000 -7.95962 0.80917 6.00000 -7.89848 -1.27833 6.00000 -7.29913 -3.27893 6.00000 -6.48758 4.67987 6.00000 -6.20241 -5.05613 6.00000 -5.05471 6.19968 6.00000 -4.68308 -6.48903 6.00000 -3.27744 7.29567 6.00000 -2.84466 -7.47983 6.00000 -0.00089 -0.00233 6.00000 -1.27687 7.89568 6.00000 -0.81243 -7.96103 6.00000 0.81066 7.95667 6.00549 1.09911 -7.99241 6.00000 2.84287 7.47567 6.00000 3.27565 -7.30053 6.00000 4.68129 6.48467 6.00000 5.05293 -6.20383 6.00000 6.20063 5.05167 6.00000 6.48580 -4.68453 6.00000 7.29735 3.27417 6.00000 7.47661 -2.84613 6.00000 7.89670 1.27367 6.00000 7.95784 -0.81383 1.65760 8.28299 3.51577 1.89880 8.00438 4.11057 3.60550 7.44183 5.05767 3.60550 5.87572 6.81467 3.60550 3.90805 8.10468 3.60550 1.67290 8.84068 3.60550 -0.67658 8.97267 3.60550 -2.97980 8.49067 3.60550 -5.07941 7.42767 3.60550 -6.83185 5.85767 3.60550 -8.11732 3.88657 3.60550 -8.84796 1.64977 2.28110 -8.99948 -0.16173 3.60550 -8.97381 -0.70003 2.95600 -8.85632 -1.60902 3.60550 -8.48627 -3.00203 2.34850 -6.00089 -0.30623 5.12570 -5.84850 -6.28963 4.91560 -6.47571 -5.81152 4.52990 -7.32036 -4.98423 4.08970 -8.00021 -4.04023 5.15080 0.02667 -8.57373 5.15080 2.04048 -8.32713 1.68300 -3.67164 2.64577 1.68300 -5.31788 1.37067 1.70710 -4.79262 2.39278 4.76790 -5.04422 -7.17183 1.81460 -5.12653 -0.37923 4.94330 -5.14915 -6.99723 2.10240 -5.35301 -0.34243 5.12360 -5.46303 -6.62893 1.50000 5.06648 3.20547 1.70710 5.92717 4.02597 1.70710 7.14342 4.13947 5.15080 4.83180 7.07667 5.15080 3.91347 7.62267 5.15080 3.04600 8.00967 5.15080 5.75663 6.34767 5.15080 6.64504 5.41067 5.15080 7.45116 4.23277 5.15080 8.10373 2.78777 5.15080 8.02586 -3.00913 5.15080 7.13271 -4.75433 5.15080 5.86657 -6.25073 5.15080 4.29269 -7.42083 5.15080 -1.14221 -8.49743 5.15080 -2.17531 -8.29333 5.15080 -3.04778 -8.01392 5.15080 -4.76167 -7.13003 5.15080 -3.88059 -7.64542 5.15080 -6.67612 -5.37923 5.15080 -7.55419 -4.05413 5.15080 -8.22952 -2.40213 5.15080 -8.55833 -0.49193 5.15080 -8.43597 1.52047 5.15080 -7.83186 3.48267 5.15080 -6.79325 5.22567 5.15080 -5.46640 6.60067 5.15080 -4.02045 7.56867 5.15080 -2.57937 8.17168 5.15080 -1.22172 8.48167 5.15080 0.03365 8.56867 5.15080 1.17758 8.48767 5.15080 2.18956 8.28468 + + + + + + + + + + 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00093 -0.00013 1.00000 -0.00022 0.00060 1.00000 -0.00007 0.00068 1.00000 0.00010 0.00071 0.99931 -0.03595 0.00917 0.99942 0.01307 0.03151 0.95139 0.30366 0.05155 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00000 0.58421 -0.81160 -0.00000 0.58421 -0.81160 -0.00000 0.71649 -0.69760 0.00000 0.71649 -0.69760 0.00000 0.82693 -0.56230 -0.00000 0.82693 -0.56231 -0.00000 0.91214 -0.40988 -0.00000 0.91214 -0.40988 -0.00000 -0.47140 -0.88192 0.00001 -0.47137 -0.88194 -0.00000 -0.29032 -0.95693 0.00000 -0.29031 -0.95693 -0.00002 -0.09808 -0.99518 0.00000 -0.09800 -0.99519 -0.01024 0.87126 0.49071 -0.06521 0.91102 0.40717 -0.17235 0.94537 0.27670 0.00000 0.89569 0.44469 0.01917 0.77775 0.62828 -0.02114 0.75645 0.65371 0.02078 0.59899 0.80048 -0.02269 0.56954 0.82165 0.02217 0.38298 0.92349 -0.02391 0.34667 0.93768 0.02368 0.14404 0.98929 -0.02502 0.10258 0.99441 0.02543 -0.10423 0.99423 -0.02645 -0.14899 0.98849 0.02645 -0.34579 0.93794 -0.02841 -0.39078 0.92005 0.02716 -0.56661 0.82354 -0.02926 -0.60746 0.79381 0.02872 -0.75185 0.65870 -0.03036 -0.78610 0.61735 0.02994 -0.89095 0.45311 -0.03152 -0.91516 0.40187 0.03084 -0.97499 0.22011 -0.03298 -0.98639 0.16110 -0.05601 -0.99588 -0.07131 0.02851 -0.96782 -0.25002 -0.14979 -0.93150 -0.33147 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.93971 -0.00005 -0.34197 0.93968 0.00004 -0.34206 0.93969 -0.00001 -0.34203 0.93969 -0.00011 -0.34201 0.94011 -0.03212 -0.33935 0.93968 -0.00001 -0.34206 0.00000 -0.93445 0.35609 0.00047 -0.93398 0.35732 -0.00074 -0.29076 0.95680 0.00000 -0.28939 0.95721 0.00000 -0.68960 0.72419 -0.00003 -0.68952 0.72427 -0.00002 -0.46037 0.88773 0.00002 -0.46050 0.88766 0.00004 -0.19475 0.98085 -0.00001 -0.19457 0.98089 0.00000 0.08608 0.99629 0.00000 0.08608 0.99629 0.00001 0.35991 0.93299 -0.00003 0.36005 0.93293 -0.00001 0.60575 0.79565 -0.00000 0.60574 0.79566 0.00002 0.80338 0.59547 0.00000 0.80342 0.59542 0.98456 0.02268 -0.17359 0.98441 0.02224 -0.17448 0.10580 -0.99355 -0.04069 0.18652 -0.98043 -0.06299 0.43702 -0.88545 -0.15809 0.52681 -0.82743 -0.19452 0.64060 -0.73194 -0.23214 0.83438 -0.45143 -0.31624 0.86804 -0.37946 -0.32018 0.38545 -0.92273 -0.00000 0.93299 -0.30758 0.18688 0.96080 -0.27377 0.04380 0.92127 -0.36020 0.14671 0.28236 -0.89643 0.34160 0.24497 -0.89535 0.37193 0.44814 -0.25993 0.85534 0.91710 -0.24439 0.31495 0.38019 -0.21147 0.90041 0.93592 -0.10243 0.33699 0.93313 -0.09815 0.34587 0.90433 0.02992 0.42578 0.25645 -0.66646 0.70005 0.94919 -0.23814 0.20575 0.69006 -0.40578 0.59930 0.21665 -0.64639 0.73160 0.38812 -0.42440 0.81807 0.91868 -0.17188 0.35564 0.93764 -0.05092 0.34385 0.92766 -0.03536 0.37175 0.36872 -0.18086 0.91177 0.28723 -0.09069 0.95356 0.39482 0.07909 0.91535 0.91698 0.06185 0.39411 0.93728 0.21555 0.27393 0.87281 0.20909 0.44100 0.35631 0.33642 0.87170 0.29069 0.41024 0.86441 0.31632 0.81048 0.49301 0.39989 0.55520 0.72927 0.20559 0.78625 0.58270 0.18566 -0.97527 -0.11992 0.36546 -0.92859 -0.06445 0.53712 -0.83817 -0.09468 0.90609 -0.39177 -0.15973 0.90607 -0.39182 -0.15975 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.60175 -0.11087 -0.79095 -0.55260 -0.17354 -0.81518 -0.56293 -0.29456 -0.77224 -0.59656 -0.31335 -0.73887 -0.53395 -0.43226 -0.72667 -0.59855 -0.49298 -0.63143 -0.53858 -0.56180 -0.62794 -0.57917 -0.65088 -0.49084 -0.55240 -0.67644 -0.48712 -0.55917 -0.76715 -0.31434 -0.56537 -0.76467 -0.30925 -0.54593 -0.82915 -0.12026 -0.57371 -0.81292 -0.10010 -0.53804 -0.83832 0.08794 -0.58049 -0.80638 0.11305 -0.53318 -0.79543 0.28811 -0.59078 -0.74279 0.31501 -0.52834 -0.71286 0.46119 -0.60082 -0.63008 0.49194 -0.53089 -0.60277 0.59568 -0.61001 -0.45269 0.65035 -0.56030 -0.49860 0.66141 -0.55481 -0.35806 0.75098 -0.60158 -0.29950 0.74055 -0.54973 -0.24456 0.79874 -0.56882 -0.13413 0.81145 -0.65227 -0.03479 0.75718 -0.55468 -0.10199 0.82579 -0.25225 0.69332 -0.67504 -0.29856 0.72856 -0.61649 -0.24741 0.80122 -0.54482 -0.29593 0.85032 -0.43518 -0.25744 0.88139 -0.39607 -0.16263 0.61088 -0.77484 -0.29884 0.84469 -0.44406 -0.38652 0.86862 -0.31001 -0.48835 0.83932 -0.23888 -0.63668 0.74832 -0.18615 -0.15915 0.62871 0.76118 -0.29618 0.84591 0.44353 -0.38577 0.86855 0.31114 -0.48964 0.83827 0.23993 -0.63937 0.74584 0.18689 -0.24788 0.86185 0.44246 -0.26528 0.86359 0.42875 -0.26594 0.74233 0.61500 -0.24343 0.73385 0.63419 -0.28203 0.60308 0.74616 -0.22637 0.55490 0.80053 -0.28338 0.46127 0.84079 -0.23125 0.32622 0.91657 -0.24490 0.33621 0.90939 -0.27617 0.18847 0.94245 -0.20856 0.06716 0.97570 -0.24805 0.09940 0.96363 -0.27362 -0.04414 0.96083 -0.22530 -0.15889 0.96125 -0.24051 -0.14466 0.95981 -0.27809 -0.28122 0.91847 -0.20592 -0.42115 0.88331 -0.26174 -0.37731 0.88833 -0.26835 -0.55035 0.79064 -0.22932 -0.59153 0.77299 -0.28987 -0.68074 0.67273 -0.22593 -0.76613 0.60167 -0.29289 -0.80279 0.51937 -0.23225 -0.89057 0.39107 -0.29251 -0.89910 0.32566 -0.23678 -0.95886 0.15660 -0.29312 -0.95086 0.09975 -0.23781 -0.96738 -0.08730 -0.29169 -0.94661 -0.13729 -0.23916 -0.91479 -0.32553 -0.28702 -0.88640 -0.36320 -0.44935 -0.80371 -0.39005 -0.23582 -0.78860 -0.56789 -0.37426 -0.72633 -0.57653 -0.40666 -0.55975 -0.72202 -0.54778 -0.62292 -0.55849 -0.39647 -0.61212 -0.68419 -0.38431 -0.48490 -0.78561 -0.12955 -0.33273 -0.93408 -0.30457 -0.44371 -0.84283 -0.38468 -0.47189 -0.79331 -0.24704 -0.45679 -0.85458 -0.28159 -0.34197 -0.89653 -0.24228 -0.28167 -0.92842 -0.28001 -0.19989 -0.93896 -0.23516 -0.06479 -0.96980 -0.55730 0.05702 0.82835 -0.63252 0.15189 0.75951 -0.55797 0.11524 0.82182 -0.55541 0.27883 0.78343 -0.60120 0.31219 0.73559 -0.54039 0.40471 0.73770 -0.59035 0.50737 0.62774 -0.56890 0.50605 0.64828 -0.54586 0.64522 0.53454 -0.59262 0.64309 0.48502 -0.52512 0.75709 0.38868 -0.60049 0.74131 0.29980 -0.51763 0.82995 0.20797 -0.62777 0.77615 0.05912 -0.56078 0.82176 0.10119 -0.55339 0.83129 -0.05212 -0.60152 0.79112 -0.11091 -0.52072 0.82848 -0.20609 -0.59707 0.73852 -0.31320 -0.52881 0.75554 -0.38667 -0.58696 0.63817 -0.49822 -0.54267 0.64119 -0.54257 -0.57115 0.48974 -0.65874 -0.56180 0.49809 -0.66052 -0.54455 0.31446 -0.77755 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00229 0.00090 -1.00000 0.00022 0.00142 -1.00000 -0.00013 0.00137 -1.00000 -0.00181 0.00052 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00287 0.00029 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00221 0.00099 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 0.00000 0.93296 0.35999 0.01931 0.90839 0.41767 0.07329 0.87296 0.48226 0.02584 0.89306 0.44920 -0.02382 0.77847 0.62723 0.03304 0.74609 0.66503 -0.03076 0.60209 0.79784 0.03889 0.54786 0.83567 -0.03569 0.38917 0.92047 0.04324 0.31247 0.94894 -0.03930 0.15320 0.98741 0.04626 0.05603 0.99736 -0.04162 -0.09218 0.99487 0.04789 -0.20460 0.97767 -0.04232 -0.33209 0.94230 0.04815 -0.45117 0.89114 -0.04168 -0.55204 0.83278 0.04659 -0.66655 0.74400 -0.04000 -0.73832 0.67327 0.04388 -0.83681 0.54573 -0.03649 -0.88032 0.47297 0.03987 -0.94982 0.31025 -0.03167 -0.96925 0.24404 0.03216 -0.99768 0.05994 0.04106 -0.99773 0.05344 -0.02553 -0.99358 -0.11018 0.11229 -0.97211 -0.20588 -0.90630 0.00000 -0.42263 -0.86964 -0.08004 -0.48716 -0.89996 -0.02187 -0.43542 -0.90429 -0.01077 -0.42679 -0.90564 -0.00650 -0.42399 -0.90705 -0.00088 -0.42103 -0.97622 0.01177 -0.21645 -0.97610 0.01148 -0.21702 -0.90078 -0.42872 0.06920 -0.23467 -0.90790 0.34734 -0.38011 -0.81899 0.42985 -0.93601 -0.30030 0.18358 -0.93307 -0.31049 0.18157 -0.44672 -0.25891 0.85639 -0.91709 -0.24350 0.31568 -0.93310 -0.10343 0.34443 -0.96004 0.02008 0.27915 -0.88250 -0.12152 0.45434 -0.38009 -0.21140 0.90047 -0.42098 -0.90707 0.00000 -0.90018 -0.38708 -0.19959 -0.03426 -0.99935 -0.01107 -0.22538 -0.96807 -0.10972 -0.37293 -0.91155 -0.17319 -0.57419 -0.77333 -0.26881 -0.63800 -0.71164 -0.29416 -0.84456 -0.35638 -0.39964 -0.84810 -0.34464 -0.40243 -0.86355 -0.34435 0.36838 -0.18530 -0.67765 0.71165 -0.25467 -0.63445 0.72981 -0.90722 -0.15464 0.39121 -0.38784 -0.42433 0.81824 -0.91871 -0.17172 0.35564 -0.92735 -0.05479 0.37016 -0.93552 -0.03282 0.35174 -0.21482 -0.19021 0.95795 -0.35603 -0.08683 0.93043 -0.39435 0.07911 0.91555 -0.91700 0.06187 0.39407 -0.93692 0.21779 0.27341 -0.86845 0.20847 0.44981 -0.14894 0.35590 0.92258 -0.33379 0.44138 0.83293 -0.36021 0.56509 0.74224 -0.31768 0.81062 0.49191 -0.20561 0.78621 0.58275 -0.25026 -0.96659 -0.05548 -0.57845 -0.77595 -0.25159 -0.39474 -0.91549 -0.07787 -0.90888 -0.35726 -0.21519 0.56781 0.42068 0.70755 0.65005 0.30960 0.69397 0.55491 0.39474 0.73229 0.54922 0.51733 0.65630 0.60076 0.54852 0.58157 0.55698 0.60269 0.57144 0.61845 0.64850 0.44381 0.55510 0.70789 0.43677 0.53284 0.77122 0.34829 0.59756 0.76810 0.23012 0.54172 0.81835 0.19193 0.62801 0.77595 0.05914 0.57520 0.81767 0.02395 0.54939 0.83396 -0.05174 0.55890 0.80471 -0.20017 0.57329 0.79731 -0.18879 0.55270 0.74187 -0.37967 0.57870 0.71791 -0.38692 0.53584 0.64455 -0.54537 0.59220 0.58621 -0.55286 0.52446 0.50799 -0.68329 0.59974 0.42021 -0.68098 0.61231 0.29515 -0.73346 0.44660 0.27208 -0.85236 0.64151 0.09324 -0.76143 0.34890 -0.01639 -0.93702 0.54828 -0.05448 -0.83452 0.61846 -0.15230 -0.77092 0.57573 -0.18840 -0.79564 0.55772 -0.25315 -0.79049 0.57251 -0.41398 -0.70771 0.65330 -0.30635 -0.69235 0.55497 -0.39466 -0.73229 0.54445 -0.52093 -0.65742 0.59931 -0.54924 -0.58237 0.55510 -0.60780 -0.56784 0.60235 -0.66540 -0.44092 0.55920 -0.70551 -0.43537 0.52905 -0.78549 -0.32111 0.60164 -0.76517 -0.22923 0.51993 -0.84183 -0.14491 0.59979 -0.79982 -0.02343 0.52122 -0.85185 0.05180 0.59424 -0.78264 0.18532 0.52693 -0.81228 0.25008 0.58678 -0.71281 0.38417 0.53799 -0.72414 0.43150 0.56047 -0.59595 0.57508 0.57500 -0.59530 0.56124 0.55205 -0.46385 0.69288 0.59113 -0.42336 0.68653 0.53564 -0.32596 0.77900 0.60099 -0.22961 0.76557 0.54985 -0.18593 0.81431 0.61611 -0.05445 0.78577 0.56673 -0.02406 0.82355 0.54749 0.05911 0.83473 0.61638 0.15487 0.77207 0.57784 0.18798 0.79421 0.55768 0.25377 0.79031 0.28615 0.57168 -0.76896 0.25221 0.69333 -0.67504 0.29853 0.72859 -0.61648 0.24738 0.80123 -0.54483 0.29591 0.85033 -0.43518 0.25742 0.88140 -0.39607 0.16302 0.61210 -0.77379 0.29884 0.84459 -0.44426 0.38634 0.86871 -0.30997 0.48872 0.83916 -0.23869 0.63744 0.74772 -0.18600 0.24869 -0.19671 -0.94840 0.44640 -0.49462 -0.74571 0.51486 -0.51149 -0.68796 0.94330 -0.21642 -0.25171 0.22684 -0.49176 -0.84067 0.26598 -0.45439 -0.85017 0.27274 -0.38929 -0.87981 0.24050 -0.29604 -0.92441 0.25385 -0.28080 -0.92559 0.27661 -0.18625 -0.94276 0.24507 -0.09501 -0.96484 0.31691 0.81044 0.49270 0.37341 0.86446 0.33655 0.43085 0.86208 0.26680 0.49637 0.83828 0.22561 0.57492 0.79448 0.19563 0.67028 0.72250 0.16945 0.19049 0.35601 0.91486 0.26776 0.87810 0.39655 0.22828 0.86977 0.43748 0.28427 0.79120 0.54147 0.25513 0.70166 0.66527 0.22684 0.72704 0.64805 0.27413 0.59534 0.75526 0.25735 0.49384 0.83060 0.22285 0.53449 0.81527 0.27268 0.39198 0.87863 0.23370 0.29726 0.92575 0.22680 0.30461 0.92508 0.27588 0.18904 0.94242 0.22259 0.06886 0.97248 0.23893 0.05447 0.96951 0.28081 -0.06635 0.95747 0.25066 -0.21550 0.94378 0.23221 -0.19924 0.95204 0.27893 -0.37069 0.88588 0.22242 -0.44038 0.86983 0.29208 -0.53205 0.79474 0.22553 -0.65008 0.72562 0.28908 -0.68887 0.66475 0.23735 -0.81368 0.53065 0.28072 -0.82451 0.49130 0.24869 -0.92071 0.30075 0.26912 -0.92047 0.28339 0.25181 -0.96599 0.05874 0.26130 -0.96388 0.05162 0.27659 -0.94706 -0.16302 0.23611 -0.95064 -0.20134 0.26933 -0.91432 -0.30245 0.35858 -0.86409 -0.35323 0.34344 -0.83072 -0.43812 0.48520 -0.71482 -0.50361 0.29171 -0.79734 -0.52835 0.53345 -0.61850 -0.57697 0.26348 0.11725 -0.95751 0.26850 0.11315 -0.95661 -0.00000 0.11747 -0.99308 0.00000 0.11747 -0.99308 -0.26852 0.11315 -0.95661 -0.26350 0.11725 -0.95751 -0.25596 0.36395 -0.89556 -0.26103 0.36037 -0.89554 -0.00000 0.37650 -0.92642 -0.00000 0.37650 -0.92642 0.26081 0.36347 -0.89436 0.25561 0.36091 -0.89689 -0.56332 0.10097 -0.82004 -0.56422 0.10035 -0.81950 -0.28904 0.55927 -0.77696 -0.27231 0.57408 -0.77219 -0.54728 0.31244 -0.77644 -0.55333 -0.05552 -0.83111 -0.26765 -0.09450 -0.95887 0.26778 -0.06276 -0.96143 0.27176 0.56222 -0.78106 0.00965 -0.99918 0.03933 -0.03275 -0.99542 -0.08983 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 0.00000 -0.08748 0.99617 0.00000 -0.08748 0.99617 0.40091 -0.08014 0.91261 0.17719 -0.06659 0.98192 0.90449 0.03213 0.42528 0.01521 -0.06422 0.99782 0.59085 -0.12274 0.79739 -0.80470 -0.13532 0.57805 -0.18092 -0.08603 0.97973 -0.40248 -0.06691 0.91298 0.00252 -0.06387 0.99796 -0.90452 0.03215 0.42522 + + + + + + + + + + + + + + +

3 0 0 0 1 0 2 1 3 1 1 1 4 2 0 2 3 2 3 3 5 3 4 3 4 4 5 4 6 4 4 5 6 5 7 5 4 6 7 6 8 6 9 7 4 7 8 7 8 8 10 8 9 8 9 9 10 9 11 9 12 10 9 10 11 10 13 11 12 11 11 11 14 12 13 12 11 12 14 13 11 13 15 13 16 14 14 14 15 14 15 15 17 15 16 15 16 16 17 16 18 16 19 17 16 17 18 17 18 18 20 18 19 18 21 19 19 19 20 19 22 20 23 20 24 20 25 21 24 21 23 21 23 22 26 22 25 22 27 23 25 23 26 23 26 24 28 24 27 24 29 25 27 25 28 25 28 26 30 26 29 26 31 27 29 27 30 27 30 28 32 28 31 28 31 29 32 29 33 29 34 30 31 30 33 30 32 31 35 31 33 31 35 32 37 32 33 32 47 33 48 33 49 33 50 34 49 34 48 34 48 35 51 35 50 35 52 36 50 36 51 36 51 37 53 37 52 37 54 38 52 38 53 38 53 39 55 39 54 39 56 40 54 40 55 40 57 41 58 41 59 41 60 42 59 42 58 42 58 43 61 43 60 43 62 44 60 44 61 44 61 45 63 45 62 45 64 46 62 46 63 46 65 47 21 47 66 47 65 48 66 48 67 48 65 49 67 49 68 49 69 50 65 50 68 50 19 51 21 51 65 51 65 52 70 52 19 52 16 53 19 53 70 53 70 54 71 54 16 54 14 55 16 55 71 55 71 56 72 56 14 56 13 57 14 57 72 57 72 58 73 58 13 58 12 59 13 59 73 59 73 60 74 60 12 60 9 61 12 61 74 61 74 62 75 62 9 62 4 63 9 63 75 63 75 64 76 64 4 64 0 65 4 65 76 65 77 66 0 66 76 66 1 67 0 67 77 67 77 68 78 68 1 68 2 69 1 69 78 69 78 70 79 70 2 70 80 71 81 71 82 71 83 72 81 72 80 72 80 73 84 73 83 73 96 74 93 74 91 74 91 75 92 75 97 75 59 76 96 76 91 76 57 77 59 77 91 77 97 78 57 78 91 78 98 79 81 79 83 79 98 80 83 80 84 80 98 81 84 81 99 81 98 82 99 82 100 82 101 83 98 83 100 83 82 84 81 84 98 84 102 85 95 85 94 85 94 86 103 86 102 86 85 87 102 87 103 87 103 88 86 88 85 88 90 89 104 89 89 89 105 90 89 90 104 90 104 91 106 91 105 91 107 92 105 92 106 92 106 93 108 93 107 93 109 94 107 94 108 94 108 95 110 95 109 95 111 96 109 96 110 96 110 97 112 97 111 97 113 98 111 98 112 98 112 99 114 99 113 99 115 100 113 100 114 100 114 101 116 101 115 101 117 102 115 102 116 102 2 103 98 103 3 103 2 104 82 104 98 104 118 105 119 105 57 105 97 106 118 106 57 106 120 107 119 107 118 107 118 108 121 108 120 108 122 109 120 109 121 109 98 110 101 110 122 110 121 111 98 111 122 111 95 112 123 112 92 112 124 113 6 113 5 113 124 114 5 114 3 114 124 115 3 115 123 115 123 116 95 116 102 116 124 117 123 117 102 117 102 118 85 118 124 118 7 119 6 119 124 119 124 120 85 120 125 120 125 121 8 121 7 121 124 122 125 122 7 122 10 123 8 123 125 123 89 124 105 124 127 124 128 125 17 125 15 125 127 126 128 126 15 126 128 127 127 127 105 127 105 128 107 128 128 128 18 129 17 129 128 129 129 130 20 130 18 130 128 131 129 131 18 131 128 132 107 132 109 132 129 133 128 133 109 133 109 134 111 134 129 134 21 135 20 135 129 135 66 136 21 136 129 136 67 137 66 137 129 137 129 138 111 138 113 138 67 139 129 139 113 139 115 140 68 140 67 140 113 141 115 141 67 141 115 142 117 142 68 142 123 143 118 143 97 143 123 144 97 144 92 144 121 145 118 145 123 145 123 146 3 146 121 146 98 147 121 147 3 147 133 148 131 148 132 148 134 149 135 149 133 149 132 150 134 150 133 150 136 151 135 151 134 151 137 152 138 152 136 152 134 153 137 153 136 153 139 154 138 154 137 154 137 155 140 155 139 155 141 156 139 156 140 156 140 157 142 157 141 157 143 158 141 158 142 158 142 159 56 159 143 159 144 160 143 160 56 160 117 161 116 161 145 161 55 162 68 162 117 162 55 163 117 163 145 163 145 164 116 164 146 164 145 165 146 165 144 165 145 166 144 166 56 166 56 167 55 167 145 167 69 168 68 168 55 168 147 169 148 169 69 169 55 170 147 170 69 170 149 171 148 171 147 171 147 172 150 172 149 172 151 173 149 173 150 173 150 174 152 174 151 174 151 175 152 175 153 175 154 176 151 176 153 176 153 177 155 177 154 177 156 178 154 178 155 178 155 179 157 179 156 179 37 180 35 180 158 180 158 181 159 181 37 181 37 182 159 182 160 182 39 183 37 183 160 183 160 184 161 184 39 184 41 185 39 185 161 185 161 186 162 186 41 186 43 187 41 187 162 187 162 188 163 188 43 188 43 189 163 189 164 189 45 190 43 190 164 190 164 191 165 191 45 191 46 192 45 192 165 192 165 193 166 193 46 193 44 194 46 194 166 194 166 195 167 195 44 195 42 196 44 196 167 196 167 197 168 197 42 197 40 198 42 198 168 198 168 199 169 199 40 199 40 200 169 200 170 200 38 201 40 201 170 201 170 202 171 202 38 202 36 203 38 203 171 203 171 204 172 204 36 204 36 205 172 205 173 205 36 206 173 206 174 206 34 207 36 207 174 207 51 208 48 208 175 208 175 209 177 209 51 209 53 210 51 210 177 210 177 211 178 211 53 211 55 212 53 212 178 212 147 213 55 213 178 213 150 214 147 214 178 214 152 215 150 215 178 215 153 216 152 216 178 216 178 217 155 217 153 217 179 218 69 218 148 218 179 219 148 219 149 219 179 220 149 220 151 220 179 221 151 221 154 221 156 222 179 222 154 222 69 223 179 223 180 223 65 224 69 224 180 224 180 225 181 225 65 225 70 226 65 226 181 226 181 227 182 227 70 227 71 228 70 228 182 228 182 229 183 229 71 229 71 230 183 230 184 230 72 231 71 231 184 231 184 232 185 232 72 232 72 233 185 233 174 233 73 234 72 234 174 234 174 235 173 235 73 235 73 236 173 236 172 236 74 237 73 237 172 237 172 238 171 238 74 238 74 239 171 239 170 239 75 240 74 240 170 240 170 241 169 241 75 241 76 242 75 242 169 242 169 243 168 243 76 243 77 244 76 244 168 244 168 245 167 245 77 245 78 246 77 246 167 246 167 247 166 247 78 247 79 248 78 248 166 248 166 249 165 249 79 249 80 250 79 250 165 250 165 251 164 251 80 251 84 252 80 252 164 252 164 253 163 253 84 253 162 254 99 254 84 254 163 255 162 255 84 255 100 256 99 256 162 256 161 257 122 257 101 257 161 258 101 258 100 258 162 259 161 259 100 259 120 260 122 260 161 260 160 261 57 261 119 261 160 262 119 262 120 262 161 263 160 263 120 263 58 264 57 264 160 264 160 265 159 265 58 265 61 266 58 266 159 266 159 267 158 267 61 267 61 268 158 268 126 268 185 269 34 269 174 269 34 270 185 270 184 270 31 271 34 271 184 271 184 272 183 272 31 272 29 273 31 273 183 273 183 274 182 274 29 274 29 275 182 275 181 275 27 276 29 276 181 276 181 277 180 277 27 277 25 278 27 278 180 278 180 279 179 279 25 279 24 280 25 280 179 280 179 281 156 281 24 281 24 282 156 282 157 282 22 283 24 283 157 283 22 284 157 284 155 284 23 285 22 285 155 285 155 286 178 286 23 286 26 287 23 287 178 287 178 288 177 288 26 288 28 289 26 289 177 289 177 290 175 290 28 290 28 291 175 291 176 291 30 292 28 292 176 292 32 293 30 293 130 293 186 294 187 294 188 294 188 295 189 295 186 295 186 296 189 296 190 296 191 297 186 297 190 297 190 298 192 298 191 298 193 299 191 299 192 299 192 300 194 300 193 300 195 301 193 301 194 301 196 302 195 302 194 302 194 303 197 303 196 303 198 304 196 304 197 304 197 305 199 305 198 305 198 306 199 306 200 306 198 307 200 307 201 307 202 308 198 308 201 308 201 309 203 309 202 309 202 310 203 310 204 310 205 311 202 311 204 311 206 312 207 312 205 312 204 313 206 313 205 313 208 314 209 314 210 314 210 315 211 315 208 315 212 316 208 316 211 316 211 317 213 317 212 317 214 318 212 318 213 318 213 319 215 319 214 319 216 320 214 320 215 320 215 321 217 321 216 321 216 322 217 322 218 322 219 323 216 323 218 323 217 324 220 324 218 324 221 325 219 325 218 325 220 326 222 326 218 326 223 327 221 327 218 327 224 328 223 328 218 328 222 329 224 329 218 329 225 330 223 330 224 330 224 331 226 331 225 331 227 332 225 332 226 332 226 333 228 333 227 333 229 334 227 334 228 334 228 335 230 335 229 335 231 336 229 336 230 336 230 337 232 337 231 337 146 338 233 338 144 338 144 339 233 339 234 339 144 340 234 340 187 340 235 341 144 341 187 341 187 342 186 342 235 342 236 343 235 343 186 343 186 344 191 344 236 344 237 345 236 345 191 345 191 346 193 346 237 346 238 347 237 347 193 347 193 348 195 348 238 348 239 349 238 349 195 349 195 350 196 350 239 350 240 351 239 351 196 351 196 352 198 352 240 352 241 353 240 353 198 353 198 354 202 354 241 354 242 355 241 355 202 355 202 356 205 356 242 356 243 357 242 357 205 357 205 358 207 358 243 358 244 359 243 359 207 359 207 360 206 360 244 360 244 361 206 361 245 361 246 362 244 362 245 362 245 363 247 363 246 363 248 364 246 364 247 364 247 365 245 365 249 365 250 366 251 366 252 366 250 367 252 367 253 367 250 368 253 368 248 368 250 369 248 369 247 369 249 370 250 370 247 370 206 371 204 371 249 371 245 372 206 372 249 372 204 373 203 373 257 373 258 374 103 374 94 374 258 375 94 375 257 375 257 376 203 376 201 376 258 377 257 377 201 377 86 378 103 378 258 378 201 379 200 379 258 379 258 380 200 380 199 380 258 381 199 381 197 381 258 382 197 382 256 382 258 383 256 383 86 383 93 384 257 384 94 384 257 385 249 385 204 385 59 386 259 386 96 386 260 387 96 387 259 387 259 388 261 388 260 388 262 389 260 389 261 389 261 390 263 390 262 390 262 391 263 391 250 391 249 392 262 392 250 392 190 393 264 393 192 393 265 394 104 394 90 394 265 395 90 395 264 395 265 396 264 396 190 396 106 397 104 397 265 397 190 398 189 398 265 398 265 399 189 399 188 399 266 400 265 400 188 400 266 401 108 401 106 401 265 402 266 402 106 402 110 403 108 403 266 403 188 404 187 404 266 404 266 405 187 405 234 405 233 406 266 406 234 406 233 407 112 407 110 407 266 408 233 408 110 408 114 409 112 409 233 409 233 410 146 410 114 410 116 411 114 411 146 411 93 412 96 412 260 412 262 413 93 413 260 413 262 414 257 414 93 414 262 415 249 415 257 415 225 416 267 416 268 416 225 417 268 417 269 417 225 418 269 418 223 418 270 419 267 419 225 419 225 420 227 420 270 420 271 421 270 421 227 421 229 422 272 422 271 422 227 423 229 423 271 423 273 424 272 424 229 424 229 425 231 425 273 425 133 426 273 426 231 426 232 427 131 427 133 427 231 428 232 428 133 428 132 429 131 429 232 429 230 430 274 430 132 430 232 431 230 431 132 431 275 432 274 432 230 432 230 433 228 433 275 433 276 434 275 434 228 434 228 435 226 435 276 435 277 436 276 436 226 436 226 437 224 437 277 437 222 438 255 438 277 438 224 439 222 439 277 439 220 440 254 440 255 440 220 441 255 441 222 441 278 442 254 442 220 442 217 443 279 443 278 443 220 444 217 444 278 444 279 445 217 445 280 445 215 446 281 446 282 446 215 447 282 447 280 447 217 448 215 448 280 448 250 449 281 449 215 449 215 450 213 450 250 450 283 451 250 451 213 451 211 452 284 452 283 452 213 453 211 453 283 453 285 454 284 454 211 454 211 455 210 455 285 455 286 456 285 456 210 456 210 457 209 457 286 457 287 458 286 458 209 458 209 459 208 459 287 459 288 460 287 460 208 460 208 461 212 461 288 461 289 462 288 462 212 462 214 463 290 463 289 463 212 464 214 464 289 464 291 465 290 465 214 465 214 466 216 466 291 466 292 467 291 467 216 467 216 468 219 468 292 468 293 469 292 469 219 469 221 470 294 470 293 470 219 471 221 471 293 471 295 472 294 472 221 472 223 473 296 473 295 473 221 474 223 474 295 474 269 475 296 475 223 475 276 476 277 476 50 476 50 477 52 477 276 477 275 478 276 478 52 478 52 479 54 479 275 479 274 480 275 480 54 480 54 481 56 481 274 481 274 482 56 482 142 482 274 483 142 483 140 483 274 484 140 484 137 484 274 485 137 485 134 485 132 486 274 486 134 486 259 487 59 487 281 487 261 488 259 488 281 488 263 489 261 489 281 489 281 490 250 490 263 490 60 491 282 491 281 491 59 492 60 492 281 492 280 493 282 493 60 493 62 494 279 494 280 494 60 495 62 495 280 495 278 496 279 496 62 496 62 497 64 497 278 497 141 498 143 498 273 498 139 499 141 499 273 499 138 500 139 500 273 500 136 501 138 501 273 501 135 502 136 502 273 502 273 503 133 503 135 503 143 504 144 504 273 504 272 505 273 505 144 505 144 506 235 506 272 506 271 507 272 507 235 507 236 508 270 508 271 508 235 509 236 509 271 509 267 510 270 510 236 510 237 511 268 511 267 511 236 512 237 512 267 512 269 513 268 513 237 513 238 514 296 514 269 514 237 515 238 515 269 515 295 516 296 516 238 516 239 517 294 517 295 517 238 518 239 518 295 518 293 519 294 519 239 519 240 520 292 520 293 520 239 521 240 521 293 521 291 522 292 522 240 522 240 523 241 523 291 523 290 524 291 524 241 524 241 525 242 525 290 525 289 526 290 526 242 526 242 527 243 527 289 527 288 528 289 528 243 528 243 529 244 529 288 529 287 530 288 530 244 530 246 531 286 531 287 531 244 532 246 532 287 532 285 533 286 533 246 533 246 534 248 534 285 534 285 535 248 535 253 535 284 536 285 536 253 536 253 537 252 537 284 537 284 538 252 538 251 538 283 539 284 539 251 539 283 540 251 540 250 540 64 541 255 541 254 541 64 542 88 542 255 542 64 543 87 543 88 543 63 544 87 544 64 544 63 545 130 545 87 545 63 546 126 546 130 546 47 547 87 547 176 547 87 548 130 548 176 548 47 549 88 549 87 549 47 550 49 550 88 550 49 551 255 551 88 551 49 552 277 552 255 552 32 553 126 553 35 553 32 554 130 554 126 554 47 555 175 555 48 555 47 556 176 556 175 556 30 557 176 557 130 557 35 558 126 558 158 558 61 559 126 559 63 559 64 560 254 560 278 560 49 561 50 561 277 561 2 562 79 562 82 562 79 563 80 563 82 563 91 564 93 564 94 564 91 565 95 565 92 565 91 566 94 566 95 566 33 567 45 567 46 567 33 568 46 568 44 568 33 569 44 569 42 569 33 570 42 570 40 570 33 571 40 571 38 571 33 572 38 572 36 572 34 573 33 573 36 573 33 574 43 574 45 574 33 575 39 575 41 575 33 576 41 576 43 576 37 577 39 577 33 577 86 578 90 578 89 578 85 579 86 579 89 579 85 580 89 580 125 580 89 581 127 581 125 581 10 582 125 582 11 582 11 583 125 583 127 583 11 584 127 584 15 584 192 585 264 585 194 585 86 586 264 586 90 586 86 587 256 587 264 587 194 588 264 588 256 588 194 589 256 589 197 589

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E2M3.dae b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E2M3.dae new file mode 100644 index 0000000..53e75da --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E2M3.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:15.508647 + 2012-07-23T02:15:15.508662 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.00000 -7.45454 5.04167 -2.00000 -8.46762 3.04968 -2.00000 -8.95760 0.87927 -2.00000 -6.00089 1.26557 -2.00000 -5.98181 6.72267 -2.00000 -5.87041 2.08118 -2.00000 -5.49317 2.70207 -2.00000 -4.91993 3.14687 -2.00000 -4.22507 3.35807 -2.00000 -4.14030 7.98967 -2.00000 -3.50089 3.30717 -1.99580 1.04911 2.95447 -2.00000 -2.04357 8.76267 -2.00000 0.17909 8.99567 -2.00000 2.39064 8.67368 -1.86600 4.77932 3.43247 -2.00000 4.45473 7.81767 -2.00000 5.04250 4.35527 -2.00000 5.85836 4.74957 -2.00000 6.24414 6.47868 -2.00000 6.75372 4.88217 -2.00000 7.64707 4.74197 -6.00000 7.99883 -0.06943 -6.00000 7.70889 -2.13763 -6.00000 7.74360 2.00337 -6.00000 6.96060 3.93948 -6.00000 6.89354 -4.06023 -6.00000 5.70319 5.60667 -6.00000 5.60834 -5.70643 -6.00000 4.05705 6.89167 -6.00000 3.94089 -6.96383 -6.00000 2.13437 7.70767 -6.00000 2.00481 -7.74683 -6.00000 -0.00089 -0.00233 -6.00000 0.06618 7.99767 -6.00000 -0.06795 -8.00203 -6.00000 -2.00659 7.74168 -6.00000 -2.13615 -7.71213 -6.00000 -3.94267 6.95867 -6.00000 -4.05883 -6.89673 -6.00000 -5.61012 5.70168 -6.00000 -5.70497 -5.61153 -6.00000 -6.89532 4.05557 -6.00000 -6.96238 -3.94413 -6.00000 -7.71067 2.13297 -6.00000 -7.74538 -2.00803 -6.00000 -8.00061 0.06477 -3.60560 4.59911 -7.73793 -3.60560 5.87471 -6.81972 3.60550 4.59911 -7.73793 3.60550 5.87471 -6.81973 -3.60560 6.97112 -5.69363 3.60550 6.97111 -5.69363 -3.60560 7.85490 -4.39393 3.60550 7.85490 -4.39393 -3.60560 8.49911 -2.96033 3.60550 8.49911 -2.96033 -3.60560 -5.00089 -7.48563 -3.60560 -3.44530 -8.31712 3.60550 -5.00089 -7.48563 3.60550 -3.44496 -8.31723 -3.60560 -1.75737 -8.82922 3.60550 -1.75665 -8.82943 -3.60560 -0.00089 -9.00233 3.60550 -0.00089 -9.00233 -3.60560 7.49365 4.98087 -1.89600 8.00920 4.10117 -1.70680 8.23875 3.61787 -1.34180 8.49911 2.95567 -3.60560 8.49911 2.95567 -3.60560 6.01519 6.69167 -3.60560 4.15704 7.97968 -3.60560 2.03647 8.76367 -3.60560 -0.21260 8.99567 -3.60560 -2.44848 8.65868 -3.60560 -4.52976 7.77467 -3.60560 -6.32525 6.40067 -3.60560 -7.72158 4.62267 -3.60560 -8.63065 2.55248 -3.60560 -8.99508 0.32108 -3.60560 -8.79186 -1.93072 -2.67480 -8.87480 -1.50352 -2.18090 -8.99973 -0.14673 -3.15220 -8.54995 -2.81543 -3.60560 -8.03383 -4.06093 -1.00000 -3.75089 2.33887 1.00000 -3.75089 2.33887 -3.60560 2.09911 -8.75393 3.60550 2.09911 -8.75393 -1.00000 5.17159 3.12238 1.00000 5.17159 3.12238 0.00000 -5.00089 -0.00233 -1.00000 -5.00089 0.93118 1.00000 -5.00089 1.10617 1.00000 -5.00089 1.37067 -1.00000 -5.00089 1.37067 1.37480 -5.00089 -0.58433 -1.25900 -5.00089 -0.53753 -2.31300 -6.00089 -0.50973 -4.17820 -6.95020 -5.63412 -4.34790 -6.49255 -6.10052 -4.54170 -5.78034 -6.70483 -1.00000 -4.74733 2.03607 1.00000 -4.74552 2.03817 1.00000 5.57884 3.51017 -1.00000 5.57893 3.51017 1.00000 6.07904 3.76957 -1.00000 6.07915 3.76968 1.00000 6.63105 3.87917 -1.00000 6.63115 3.87917 1.00000 7.19123 3.83077 -1.00000 7.19131 3.83077 1.00000 7.71590 3.62837 -1.00000 7.71601 3.62827 1.00000 8.16394 3.28727 -1.00000 8.16406 3.28717 1.00000 8.49911 2.83508 -1.00000 8.49911 2.83508 -1.67330 -5.07965 -0.53843 -4.11050 -5.05836 -7.39513 -4.32460 -5.19024 -7.24833 -2.01210 -5.29806 -0.52692 -4.45570 -5.35820 -7.08053 -1.71140 -5.29806 1.17887 -1.70710 -4.79262 2.39278 -1.68300 -3.67164 2.64587 -5.15080 0.02667 -8.57373 -1.50000 5.06648 3.20547 -1.70710 5.92460 4.02497 -1.70710 7.13800 4.14037 -5.15080 2.04048 -8.32713 5.25480 8.49911 -0.00233 5.15080 8.49911 -1.10663 5.15080 8.49911 1.10197 4.97780 8.49911 -1.69952 5.07200 8.49911 1.41367 4.96590 8.49911 1.72547 4.72950 8.49911 -2.20792 4.82350 8.49911 2.03877 4.63240 8.49911 2.34737 4.40720 8.49911 -2.60963 4.36760 8.49911 2.64117 4.01370 8.49911 -2.87433 4.00940 8.49911 2.87157 3.60550 8.49911 2.95567 -0.00000 8.49911 -0.00233 1.34180 8.49911 2.95567 -4.01250 8.49911 -2.87492 -4.01070 8.49911 2.87097 -4.40320 8.49911 2.60887 -4.40880 8.49911 -2.60823 -4.72670 8.49911 2.20777 -4.72850 8.49911 -2.20963 -4.97660 8.49911 -1.70243 -4.97670 8.49911 1.69757 -5.15080 8.49911 -1.10663 -5.15080 8.49911 1.10197 -5.25480 8.49911 -0.00234 -5.15080 -1.16784 -8.49393 -5.15080 -2.39342 -8.23302 -5.15080 -3.69770 -7.73553 -5.15080 -5.03250 -6.94153 -5.15080 -6.33935 -5.77232 -5.15080 -7.48297 -4.18423 -5.15080 -8.26608 -2.27303 -5.15080 -8.57061 -0.17332 -5.15080 -8.34856 1.94337 -5.15080 -7.65831 3.84908 -5.15080 -6.65255 5.40367 -5.15080 -5.48446 6.58567 -5.15080 -4.27482 7.42767 -5.15080 -3.07933 7.99767 -5.15080 -1.92971 8.34967 -5.15080 -0.86492 8.52567 -5.15080 0.07097 8.56867 -5.15080 5.86632 -6.25092 -5.15080 4.29269 -7.42083 -5.15080 7.13263 -4.75442 -5.15080 8.02585 -3.00912 -5.15080 8.01546 3.03207 -5.15080 7.13700 4.74317 -5.15080 5.98916 6.12867 -5.15080 4.73707 7.14067 -5.15080 3.47752 7.83167 -5.15080 2.25250 8.26767 -5.15080 1.10237 8.49767 2.00000 6.26146 6.46167 2.00000 7.64707 4.74197 2.00000 6.75408 4.88217 2.00000 5.85895 4.74967 2.00000 5.04316 4.35577 2.00000 4.49639 7.79367 2.00000 4.38705 3.74247 2.00000 2.45995 8.65467 1.99160 1.03584 2.94627 2.00000 0.27493 8.99368 2.00000 -1.92679 8.78967 2.00000 -3.50089 3.30717 2.00000 -4.01233 8.05467 2.00000 -4.21819 3.35877 2.00000 -4.91452 3.14967 2.00000 -5.48962 2.70607 2.00000 -5.85578 6.83267 2.00000 -5.86839 2.08647 2.00000 -6.00089 1.26557 2.00000 -7.34581 5.19867 2.00000 -8.93237 1.10617 2.00000 -8.39242 3.25067 6.00000 -7.47839 2.84148 6.00000 -7.95962 0.80917 6.00000 -7.89848 -1.27833 6.00000 -7.29913 -3.27893 6.00000 -6.48758 4.67987 6.00000 -6.20241 -5.05613 6.00000 -5.05471 6.19968 6.00000 -4.68308 -6.48903 6.00000 -3.27744 7.29567 6.00000 -2.84466 -7.47983 6.00000 -0.00089 -0.00233 6.00000 -1.27687 7.89568 6.00000 -0.81243 -7.96103 6.00000 0.81066 7.95667 6.00549 1.09911 -7.99241 6.00000 2.84287 7.47567 6.00000 3.27565 -7.30053 6.00000 4.68129 6.48467 6.00000 5.05293 -6.20383 6.00000 6.20063 5.05167 6.00000 6.48580 -4.68453 6.00000 7.29735 3.27417 6.00000 7.47661 -2.84613 6.00000 7.89670 1.27367 6.00000 7.95784 -0.81383 1.65760 8.28299 3.51577 1.89880 8.00438 4.11057 3.60550 7.44183 5.05767 3.60550 5.87572 6.81467 3.60550 3.90805 8.10468 3.60550 1.67290 8.84068 3.60550 -0.67658 8.97267 3.60550 -2.97980 8.49067 3.60550 -5.07941 7.42767 3.60550 -6.83185 5.85767 3.60550 -8.11732 3.88657 3.60550 -8.84796 1.64977 2.28110 -8.99948 -0.16173 3.60550 -8.97381 -0.70003 2.95600 -8.85632 -1.60902 3.60550 -8.48627 -3.00203 2.34850 -6.00089 -0.30623 5.12570 -5.84850 -6.28963 4.91560 -6.47571 -5.81152 4.52990 -7.32036 -4.98423 4.08970 -8.00021 -4.04023 5.15080 0.02667 -8.57373 5.15080 2.04048 -8.32713 1.68300 -3.67164 2.64577 1.68300 -5.31788 1.37067 1.70710 -4.79262 2.39278 4.76790 -5.04422 -7.17183 1.81460 -5.12653 -0.37923 4.94330 -5.14915 -6.99723 2.10240 -5.35301 -0.34243 5.12360 -5.46303 -6.62893 1.50000 5.06648 3.20547 1.70710 5.92717 4.02597 1.70710 7.14342 4.13947 5.15080 4.83180 7.07667 5.15080 3.91347 7.62267 5.15080 3.04600 8.00967 5.15080 5.75663 6.34767 5.15080 6.64504 5.41067 5.15080 7.45116 4.23277 5.15080 8.10373 2.78777 5.15080 8.02586 -3.00913 5.15080 7.13271 -4.75433 5.15080 5.86657 -6.25073 5.15080 4.29269 -7.42083 5.15080 -1.14221 -8.49743 5.15080 -2.17531 -8.29333 5.15080 -3.04778 -8.01392 5.15080 -4.76167 -7.13003 5.15080 -3.88059 -7.64542 5.15080 -6.67612 -5.37923 5.15080 -7.55419 -4.05413 5.15080 -8.22952 -2.40213 5.15080 -8.55833 -0.49193 5.15080 -8.43597 1.52047 5.15080 -7.83186 3.48267 5.15080 -6.79325 5.22567 5.15080 -5.46640 6.60067 5.15080 -4.02045 7.56867 5.15080 -2.57937 8.17168 5.15080 -1.22172 8.48167 5.15080 0.03365 8.56867 5.15080 1.17758 8.48767 5.15080 2.18956 8.28468 + + + + + + + + + + 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00093 -0.00013 1.00000 -0.00022 0.00060 1.00000 -0.00007 0.00068 1.00000 0.00010 0.00071 0.99931 -0.03595 0.00917 0.99942 0.01307 0.03151 0.95139 0.30366 0.05155 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00000 0.58421 -0.81160 -0.00000 0.58421 -0.81160 -0.00000 0.71649 -0.69760 0.00000 0.71649 -0.69760 0.00000 0.82693 -0.56230 -0.00000 0.82693 -0.56231 -0.00000 0.91214 -0.40988 -0.00000 0.91214 -0.40988 -0.00000 -0.47140 -0.88192 0.00001 -0.47137 -0.88194 -0.00000 -0.29032 -0.95693 0.00000 -0.29031 -0.95693 -0.00002 -0.09808 -0.99518 0.00000 -0.09800 -0.99519 -0.01024 0.87126 0.49071 -0.06521 0.91102 0.40717 -0.17235 0.94537 0.27670 0.00000 0.89569 0.44469 0.01917 0.77775 0.62828 -0.02114 0.75645 0.65371 0.02078 0.59899 0.80048 -0.02269 0.56954 0.82165 0.02217 0.38298 0.92349 -0.02391 0.34667 0.93768 0.02368 0.14404 0.98929 -0.02502 0.10258 0.99441 0.02543 -0.10423 0.99423 -0.02645 -0.14899 0.98849 0.02645 -0.34579 0.93794 -0.02841 -0.39078 0.92005 0.02716 -0.56661 0.82354 -0.02926 -0.60746 0.79381 0.02872 -0.75185 0.65870 -0.03036 -0.78610 0.61735 0.02994 -0.89095 0.45311 -0.03152 -0.91516 0.40187 0.03084 -0.97499 0.22011 -0.03298 -0.98639 0.16110 -0.05601 -0.99588 -0.07131 0.02851 -0.96782 -0.25002 -0.14979 -0.93150 -0.33147 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.93971 -0.00005 -0.34197 0.93968 0.00004 -0.34206 0.93969 -0.00001 -0.34203 0.93969 -0.00011 -0.34201 0.94011 -0.03212 -0.33935 0.93968 -0.00001 -0.34206 0.00000 -0.93445 0.35609 0.00047 -0.93398 0.35732 -0.00074 -0.29076 0.95680 0.00000 -0.28939 0.95721 0.00000 -0.68960 0.72419 -0.00003 -0.68952 0.72427 -0.00002 -0.46037 0.88773 0.00002 -0.46050 0.88766 0.00004 -0.19475 0.98085 -0.00001 -0.19457 0.98089 0.00000 0.08608 0.99629 0.00000 0.08608 0.99629 0.00001 0.35991 0.93299 -0.00003 0.36005 0.93293 -0.00001 0.60575 0.79565 -0.00000 0.60574 0.79566 0.00002 0.80338 0.59547 0.00000 0.80342 0.59542 0.98456 0.02268 -0.17359 0.98441 0.02224 -0.17448 0.10580 -0.99355 -0.04069 0.18652 -0.98043 -0.06299 0.43702 -0.88545 -0.15809 0.52681 -0.82743 -0.19452 0.64060 -0.73194 -0.23214 0.83438 -0.45143 -0.31624 0.86804 -0.37946 -0.32018 0.38545 -0.92273 -0.00000 0.93299 -0.30758 0.18688 0.96080 -0.27377 0.04380 0.92127 -0.36020 0.14671 0.28236 -0.89643 0.34160 0.24497 -0.89535 0.37193 0.44814 -0.25993 0.85534 0.91710 -0.24439 0.31495 0.38019 -0.21147 0.90041 0.93592 -0.10243 0.33699 0.93313 -0.09815 0.34587 0.90433 0.02992 0.42578 0.25645 -0.66646 0.70005 0.94919 -0.23814 0.20575 0.69006 -0.40578 0.59930 0.21665 -0.64639 0.73160 0.38812 -0.42440 0.81807 0.91868 -0.17188 0.35564 0.93764 -0.05092 0.34385 0.92766 -0.03536 0.37175 0.36872 -0.18086 0.91177 0.28723 -0.09069 0.95356 0.39482 0.07909 0.91535 0.91698 0.06185 0.39411 0.93728 0.21555 0.27393 0.87281 0.20909 0.44100 0.35631 0.33642 0.87170 0.29069 0.41024 0.86441 0.31632 0.81048 0.49301 0.39989 0.55520 0.72927 0.20559 0.78625 0.58270 0.18566 -0.97527 -0.11992 0.36546 -0.92859 -0.06445 0.53712 -0.83817 -0.09468 0.90609 -0.39177 -0.15973 0.90607 -0.39182 -0.15975 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.60175 -0.11087 -0.79095 -0.55260 -0.17354 -0.81518 -0.56293 -0.29456 -0.77224 -0.59656 -0.31335 -0.73887 -0.53395 -0.43226 -0.72667 -0.59855 -0.49298 -0.63143 -0.53858 -0.56180 -0.62794 -0.57917 -0.65088 -0.49084 -0.55240 -0.67644 -0.48712 -0.55917 -0.76715 -0.31434 -0.56537 -0.76467 -0.30925 -0.54593 -0.82915 -0.12026 -0.57371 -0.81292 -0.10010 -0.53804 -0.83832 0.08794 -0.58049 -0.80638 0.11305 -0.53318 -0.79543 0.28811 -0.59078 -0.74279 0.31501 -0.52834 -0.71286 0.46119 -0.60082 -0.63008 0.49194 -0.53089 -0.60277 0.59568 -0.61001 -0.45269 0.65035 -0.56030 -0.49860 0.66141 -0.55481 -0.35806 0.75098 -0.60158 -0.29950 0.74055 -0.54973 -0.24456 0.79874 -0.56882 -0.13413 0.81145 -0.65227 -0.03479 0.75718 -0.55468 -0.10199 0.82579 -0.25225 0.69332 -0.67504 -0.29856 0.72856 -0.61649 -0.24741 0.80122 -0.54482 -0.29593 0.85032 -0.43518 -0.25744 0.88139 -0.39607 -0.16263 0.61088 -0.77484 -0.29884 0.84469 -0.44406 -0.38652 0.86862 -0.31001 -0.48835 0.83932 -0.23888 -0.63668 0.74832 -0.18615 -0.15915 0.62871 0.76118 -0.29618 0.84591 0.44353 -0.38577 0.86855 0.31114 -0.48964 0.83827 0.23993 -0.63937 0.74584 0.18689 -0.24788 0.86185 0.44246 -0.26528 0.86359 0.42875 -0.26594 0.74233 0.61500 -0.24343 0.73385 0.63419 -0.28203 0.60308 0.74616 -0.22637 0.55490 0.80053 -0.28338 0.46127 0.84079 -0.23125 0.32622 0.91657 -0.24490 0.33621 0.90939 -0.27617 0.18847 0.94245 -0.20856 0.06716 0.97570 -0.24805 0.09940 0.96363 -0.27362 -0.04414 0.96083 -0.22530 -0.15889 0.96125 -0.24051 -0.14466 0.95981 -0.27809 -0.28122 0.91847 -0.20592 -0.42115 0.88331 -0.26174 -0.37731 0.88833 -0.26835 -0.55035 0.79064 -0.22932 -0.59153 0.77299 -0.28987 -0.68074 0.67273 -0.22593 -0.76613 0.60167 -0.29289 -0.80279 0.51937 -0.23225 -0.89057 0.39107 -0.29251 -0.89910 0.32566 -0.23678 -0.95886 0.15660 -0.29312 -0.95086 0.09975 -0.23781 -0.96738 -0.08730 -0.29169 -0.94661 -0.13729 -0.23916 -0.91479 -0.32553 -0.28702 -0.88640 -0.36320 -0.44935 -0.80371 -0.39005 -0.23582 -0.78860 -0.56789 -0.37426 -0.72633 -0.57653 -0.40666 -0.55975 -0.72202 -0.54778 -0.62292 -0.55849 -0.39647 -0.61212 -0.68419 -0.38431 -0.48490 -0.78561 -0.12955 -0.33273 -0.93408 -0.30457 -0.44371 -0.84283 -0.38468 -0.47189 -0.79331 -0.24704 -0.45679 -0.85458 -0.28159 -0.34197 -0.89653 -0.24228 -0.28167 -0.92842 -0.28001 -0.19989 -0.93896 -0.23516 -0.06479 -0.96980 -0.55730 0.05702 0.82835 -0.63252 0.15189 0.75951 -0.55797 0.11524 0.82182 -0.55541 0.27883 0.78343 -0.60120 0.31219 0.73559 -0.54039 0.40471 0.73770 -0.59035 0.50737 0.62774 -0.56890 0.50605 0.64828 -0.54586 0.64522 0.53454 -0.59262 0.64309 0.48502 -0.52512 0.75709 0.38868 -0.60049 0.74131 0.29980 -0.51763 0.82995 0.20797 -0.62777 0.77615 0.05912 -0.56078 0.82176 0.10119 -0.55339 0.83129 -0.05212 -0.60152 0.79112 -0.11091 -0.52072 0.82848 -0.20609 -0.59707 0.73852 -0.31320 -0.52881 0.75554 -0.38667 -0.58696 0.63817 -0.49822 -0.54267 0.64119 -0.54257 -0.57115 0.48974 -0.65874 -0.56180 0.49809 -0.66052 -0.54455 0.31446 -0.77755 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00229 0.00090 -1.00000 0.00022 0.00142 -1.00000 -0.00013 0.00137 -1.00000 -0.00181 0.00052 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00287 0.00029 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00221 0.00099 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 0.00000 0.93296 0.35999 0.01931 0.90839 0.41767 0.07329 0.87296 0.48226 0.02584 0.89306 0.44920 -0.02382 0.77847 0.62723 0.03304 0.74609 0.66503 -0.03076 0.60209 0.79784 0.03889 0.54786 0.83567 -0.03569 0.38917 0.92047 0.04324 0.31247 0.94894 -0.03930 0.15320 0.98741 0.04626 0.05603 0.99736 -0.04162 -0.09218 0.99487 0.04789 -0.20460 0.97767 -0.04232 -0.33209 0.94230 0.04815 -0.45117 0.89114 -0.04168 -0.55204 0.83278 0.04659 -0.66655 0.74400 -0.04000 -0.73832 0.67327 0.04388 -0.83681 0.54573 -0.03649 -0.88032 0.47297 0.03987 -0.94982 0.31025 -0.03167 -0.96925 0.24404 0.03216 -0.99768 0.05994 0.04106 -0.99773 0.05344 -0.02553 -0.99358 -0.11018 0.11229 -0.97211 -0.20588 -0.90630 0.00000 -0.42263 -0.86964 -0.08004 -0.48716 -0.89996 -0.02187 -0.43542 -0.90429 -0.01077 -0.42679 -0.90564 -0.00650 -0.42399 -0.90705 -0.00088 -0.42103 -0.97622 0.01177 -0.21645 -0.97610 0.01148 -0.21702 -0.90078 -0.42872 0.06920 -0.23467 -0.90790 0.34734 -0.38011 -0.81899 0.42985 -0.93601 -0.30030 0.18358 -0.93307 -0.31049 0.18157 -0.44672 -0.25891 0.85639 -0.91709 -0.24350 0.31568 -0.93310 -0.10343 0.34443 -0.96004 0.02008 0.27915 -0.88250 -0.12152 0.45434 -0.38009 -0.21140 0.90047 -0.42098 -0.90707 0.00000 -0.90018 -0.38708 -0.19959 -0.03426 -0.99935 -0.01107 -0.22538 -0.96807 -0.10972 -0.37293 -0.91155 -0.17319 -0.57419 -0.77333 -0.26881 -0.63800 -0.71164 -0.29416 -0.84456 -0.35638 -0.39964 -0.84810 -0.34464 -0.40243 -0.86355 -0.34435 0.36838 -0.18530 -0.67765 0.71165 -0.25467 -0.63445 0.72981 -0.90722 -0.15464 0.39121 -0.38784 -0.42433 0.81824 -0.91871 -0.17172 0.35564 -0.92735 -0.05479 0.37016 -0.93552 -0.03282 0.35174 -0.21482 -0.19021 0.95795 -0.35603 -0.08683 0.93043 -0.39435 0.07911 0.91555 -0.91700 0.06187 0.39407 -0.93692 0.21779 0.27341 -0.86845 0.20847 0.44981 -0.14894 0.35590 0.92258 -0.33379 0.44138 0.83293 -0.36021 0.56509 0.74224 -0.31768 0.81062 0.49191 -0.20561 0.78621 0.58275 -0.25026 -0.96659 -0.05548 -0.57845 -0.77595 -0.25159 -0.39474 -0.91549 -0.07787 -0.90888 -0.35726 -0.21519 0.56781 0.42068 0.70755 0.65005 0.30960 0.69397 0.55491 0.39474 0.73229 0.54922 0.51733 0.65630 0.60076 0.54852 0.58157 0.55698 0.60269 0.57144 0.61845 0.64850 0.44381 0.55510 0.70789 0.43677 0.53284 0.77122 0.34829 0.59756 0.76810 0.23012 0.54172 0.81835 0.19193 0.62801 0.77595 0.05914 0.57520 0.81767 0.02395 0.54939 0.83396 -0.05174 0.55890 0.80471 -0.20017 0.57329 0.79731 -0.18879 0.55270 0.74187 -0.37967 0.57870 0.71791 -0.38692 0.53584 0.64455 -0.54537 0.59220 0.58621 -0.55286 0.52446 0.50799 -0.68329 0.59974 0.42021 -0.68098 0.61231 0.29515 -0.73346 0.44660 0.27208 -0.85236 0.64151 0.09324 -0.76143 0.34890 -0.01639 -0.93702 0.54828 -0.05448 -0.83452 0.61846 -0.15230 -0.77092 0.57573 -0.18840 -0.79564 0.55772 -0.25315 -0.79049 0.57251 -0.41398 -0.70771 0.65330 -0.30635 -0.69235 0.55497 -0.39466 -0.73229 0.54445 -0.52093 -0.65742 0.59931 -0.54924 -0.58237 0.55510 -0.60780 -0.56784 0.60235 -0.66540 -0.44092 0.55920 -0.70551 -0.43537 0.52905 -0.78549 -0.32111 0.60164 -0.76517 -0.22923 0.51993 -0.84183 -0.14491 0.59979 -0.79982 -0.02343 0.52122 -0.85185 0.05180 0.59424 -0.78264 0.18532 0.52693 -0.81228 0.25008 0.58678 -0.71281 0.38417 0.53799 -0.72414 0.43150 0.56047 -0.59595 0.57508 0.57500 -0.59530 0.56124 0.55205 -0.46385 0.69288 0.59113 -0.42336 0.68653 0.53564 -0.32596 0.77900 0.60099 -0.22961 0.76557 0.54985 -0.18593 0.81431 0.61611 -0.05445 0.78577 0.56673 -0.02406 0.82355 0.54749 0.05911 0.83473 0.61638 0.15487 0.77207 0.57784 0.18798 0.79421 0.55768 0.25377 0.79031 0.28615 0.57168 -0.76896 0.25221 0.69333 -0.67504 0.29853 0.72859 -0.61648 0.24738 0.80123 -0.54483 0.29591 0.85033 -0.43518 0.25742 0.88140 -0.39607 0.16302 0.61210 -0.77379 0.29884 0.84459 -0.44426 0.38634 0.86871 -0.30997 0.48872 0.83916 -0.23869 0.63744 0.74772 -0.18600 0.24869 -0.19671 -0.94840 0.44640 -0.49462 -0.74571 0.51486 -0.51149 -0.68796 0.94330 -0.21642 -0.25171 0.22684 -0.49176 -0.84067 0.26598 -0.45439 -0.85017 0.27274 -0.38929 -0.87981 0.24050 -0.29604 -0.92441 0.25385 -0.28080 -0.92559 0.27661 -0.18625 -0.94276 0.24507 -0.09501 -0.96484 0.31691 0.81044 0.49270 0.37341 0.86446 0.33655 0.43085 0.86208 0.26680 0.49637 0.83828 0.22561 0.57492 0.79448 0.19563 0.67028 0.72250 0.16945 0.19049 0.35601 0.91486 0.26776 0.87810 0.39655 0.22828 0.86977 0.43748 0.28427 0.79120 0.54147 0.25513 0.70166 0.66527 0.22684 0.72704 0.64805 0.27413 0.59534 0.75526 0.25735 0.49384 0.83060 0.22285 0.53449 0.81527 0.27268 0.39198 0.87863 0.23370 0.29726 0.92575 0.22680 0.30461 0.92508 0.27588 0.18904 0.94242 0.22259 0.06886 0.97248 0.23893 0.05447 0.96951 0.28081 -0.06635 0.95747 0.25066 -0.21550 0.94378 0.23221 -0.19924 0.95204 0.27893 -0.37069 0.88588 0.22242 -0.44038 0.86983 0.29208 -0.53205 0.79474 0.22553 -0.65008 0.72562 0.28908 -0.68887 0.66475 0.23735 -0.81368 0.53065 0.28072 -0.82451 0.49130 0.24869 -0.92071 0.30075 0.26912 -0.92047 0.28339 0.25181 -0.96599 0.05874 0.26130 -0.96388 0.05162 0.27659 -0.94706 -0.16302 0.23611 -0.95064 -0.20134 0.26933 -0.91432 -0.30245 0.35858 -0.86409 -0.35323 0.34344 -0.83072 -0.43812 0.48520 -0.71482 -0.50361 0.29171 -0.79734 -0.52835 0.53345 -0.61850 -0.57697 0.26348 0.11725 -0.95751 0.26850 0.11315 -0.95661 -0.00000 0.11747 -0.99308 0.00000 0.11747 -0.99308 -0.26852 0.11315 -0.95661 -0.26350 0.11725 -0.95751 -0.25596 0.36395 -0.89556 -0.26103 0.36037 -0.89554 -0.00000 0.37650 -0.92642 -0.00000 0.37650 -0.92642 0.26081 0.36347 -0.89436 0.25561 0.36091 -0.89689 -0.56332 0.10097 -0.82004 -0.56422 0.10035 -0.81950 -0.28904 0.55927 -0.77696 -0.27231 0.57408 -0.77219 -0.54728 0.31244 -0.77644 -0.55333 -0.05552 -0.83111 -0.26765 -0.09450 -0.95887 0.26778 -0.06276 -0.96143 0.27176 0.56222 -0.78106 0.00965 -0.99918 0.03933 -0.03275 -0.99542 -0.08983 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 0.00000 -0.08748 0.99617 0.00000 -0.08748 0.99617 0.40091 -0.08014 0.91261 0.17719 -0.06659 0.98192 0.90449 0.03213 0.42528 0.01521 -0.06422 0.99782 0.59085 -0.12274 0.79739 -0.80470 -0.13532 0.57805 -0.18092 -0.08603 0.97973 -0.40248 -0.06691 0.91298 0.00252 -0.06387 0.99796 -0.90452 0.03215 0.42522 + + + + + + + + + + + + + + +

3 0 0 0 1 0 2 1 3 1 1 1 4 2 0 2 3 2 3 3 5 3 4 3 4 4 5 4 6 4 4 5 6 5 7 5 4 6 7 6 8 6 9 7 4 7 8 7 8 8 10 8 9 8 9 9 10 9 11 9 12 10 9 10 11 10 13 11 12 11 11 11 14 12 13 12 11 12 14 13 11 13 15 13 16 14 14 14 15 14 15 15 17 15 16 15 16 16 17 16 18 16 19 17 16 17 18 17 18 18 20 18 19 18 21 19 19 19 20 19 22 20 23 20 24 20 25 21 24 21 23 21 23 22 26 22 25 22 27 23 25 23 26 23 26 24 28 24 27 24 29 25 27 25 28 25 28 26 30 26 29 26 31 27 29 27 30 27 30 28 32 28 31 28 31 29 32 29 33 29 34 30 31 30 33 30 32 31 35 31 33 31 35 32 37 32 33 32 47 33 48 33 49 33 50 34 49 34 48 34 48 35 51 35 50 35 52 36 50 36 51 36 51 37 53 37 52 37 54 38 52 38 53 38 53 39 55 39 54 39 56 40 54 40 55 40 57 41 58 41 59 41 60 42 59 42 58 42 58 43 61 43 60 43 62 44 60 44 61 44 61 45 63 45 62 45 64 46 62 46 63 46 65 47 21 47 66 47 65 48 66 48 67 48 65 49 67 49 68 49 69 50 65 50 68 50 19 51 21 51 65 51 65 52 70 52 19 52 16 53 19 53 70 53 70 54 71 54 16 54 14 55 16 55 71 55 71 56 72 56 14 56 13 57 14 57 72 57 72 58 73 58 13 58 12 59 13 59 73 59 73 60 74 60 12 60 9 61 12 61 74 61 74 62 75 62 9 62 4 63 9 63 75 63 75 64 76 64 4 64 0 65 4 65 76 65 77 66 0 66 76 66 1 67 0 67 77 67 77 68 78 68 1 68 2 69 1 69 78 69 78 70 79 70 2 70 80 71 81 71 82 71 83 72 81 72 80 72 80 73 84 73 83 73 96 74 93 74 91 74 91 75 92 75 97 75 59 76 96 76 91 76 57 77 59 77 91 77 97 78 57 78 91 78 98 79 81 79 83 79 98 80 83 80 84 80 98 81 84 81 99 81 98 82 99 82 100 82 101 83 98 83 100 83 82 84 81 84 98 84 102 85 95 85 94 85 94 86 103 86 102 86 85 87 102 87 103 87 103 88 86 88 85 88 90 89 104 89 89 89 105 90 89 90 104 90 104 91 106 91 105 91 107 92 105 92 106 92 106 93 108 93 107 93 109 94 107 94 108 94 108 95 110 95 109 95 111 96 109 96 110 96 110 97 112 97 111 97 113 98 111 98 112 98 112 99 114 99 113 99 115 100 113 100 114 100 114 101 116 101 115 101 117 102 115 102 116 102 2 103 98 103 3 103 2 104 82 104 98 104 118 105 119 105 57 105 97 106 118 106 57 106 120 107 119 107 118 107 118 108 121 108 120 108 122 109 120 109 121 109 98 110 101 110 122 110 121 111 98 111 122 111 95 112 123 112 92 112 124 113 6 113 5 113 124 114 5 114 3 114 124 115 3 115 123 115 123 116 95 116 102 116 124 117 123 117 102 117 102 118 85 118 124 118 7 119 6 119 124 119 124 120 85 120 125 120 125 121 8 121 7 121 124 122 125 122 7 122 10 123 8 123 125 123 89 124 105 124 127 124 128 125 17 125 15 125 127 126 128 126 15 126 128 127 127 127 105 127 105 128 107 128 128 128 18 129 17 129 128 129 129 130 20 130 18 130 128 131 129 131 18 131 128 132 107 132 109 132 129 133 128 133 109 133 109 134 111 134 129 134 21 135 20 135 129 135 66 136 21 136 129 136 67 137 66 137 129 137 129 138 111 138 113 138 67 139 129 139 113 139 115 140 68 140 67 140 113 141 115 141 67 141 115 142 117 142 68 142 123 143 118 143 97 143 123 144 97 144 92 144 121 145 118 145 123 145 123 146 3 146 121 146 98 147 121 147 3 147 133 148 131 148 132 148 134 149 135 149 133 149 132 150 134 150 133 150 136 151 135 151 134 151 137 152 138 152 136 152 134 153 137 153 136 153 139 154 138 154 137 154 137 155 140 155 139 155 141 156 139 156 140 156 140 157 142 157 141 157 143 158 141 158 142 158 142 159 56 159 143 159 144 160 143 160 56 160 117 161 116 161 145 161 55 162 68 162 117 162 55 163 117 163 145 163 145 164 116 164 146 164 145 165 146 165 144 165 145 166 144 166 56 166 56 167 55 167 145 167 69 168 68 168 55 168 147 169 148 169 69 169 55 170 147 170 69 170 149 171 148 171 147 171 147 172 150 172 149 172 151 173 149 173 150 173 150 174 152 174 151 174 151 175 152 175 153 175 154 176 151 176 153 176 153 177 155 177 154 177 156 178 154 178 155 178 155 179 157 179 156 179 37 180 35 180 158 180 158 181 159 181 37 181 37 182 159 182 160 182 39 183 37 183 160 183 160 184 161 184 39 184 41 185 39 185 161 185 161 186 162 186 41 186 43 187 41 187 162 187 162 188 163 188 43 188 43 189 163 189 164 189 45 190 43 190 164 190 164 191 165 191 45 191 46 192 45 192 165 192 165 193 166 193 46 193 44 194 46 194 166 194 166 195 167 195 44 195 42 196 44 196 167 196 167 197 168 197 42 197 40 198 42 198 168 198 168 199 169 199 40 199 40 200 169 200 170 200 38 201 40 201 170 201 170 202 171 202 38 202 36 203 38 203 171 203 171 204 172 204 36 204 36 205 172 205 173 205 36 206 173 206 174 206 34 207 36 207 174 207 51 208 48 208 175 208 175 209 177 209 51 209 53 210 51 210 177 210 177 211 178 211 53 211 55 212 53 212 178 212 147 213 55 213 178 213 150 214 147 214 178 214 152 215 150 215 178 215 153 216 152 216 178 216 178 217 155 217 153 217 179 218 69 218 148 218 179 219 148 219 149 219 179 220 149 220 151 220 179 221 151 221 154 221 156 222 179 222 154 222 69 223 179 223 180 223 65 224 69 224 180 224 180 225 181 225 65 225 70 226 65 226 181 226 181 227 182 227 70 227 71 228 70 228 182 228 182 229 183 229 71 229 71 230 183 230 184 230 72 231 71 231 184 231 184 232 185 232 72 232 72 233 185 233 174 233 73 234 72 234 174 234 174 235 173 235 73 235 73 236 173 236 172 236 74 237 73 237 172 237 172 238 171 238 74 238 74 239 171 239 170 239 75 240 74 240 170 240 170 241 169 241 75 241 76 242 75 242 169 242 169 243 168 243 76 243 77 244 76 244 168 244 168 245 167 245 77 245 78 246 77 246 167 246 167 247 166 247 78 247 79 248 78 248 166 248 166 249 165 249 79 249 80 250 79 250 165 250 165 251 164 251 80 251 84 252 80 252 164 252 164 253 163 253 84 253 162 254 99 254 84 254 163 255 162 255 84 255 100 256 99 256 162 256 161 257 122 257 101 257 161 258 101 258 100 258 162 259 161 259 100 259 120 260 122 260 161 260 160 261 57 261 119 261 160 262 119 262 120 262 161 263 160 263 120 263 58 264 57 264 160 264 160 265 159 265 58 265 61 266 58 266 159 266 159 267 158 267 61 267 61 268 158 268 126 268 185 269 34 269 174 269 34 270 185 270 184 270 31 271 34 271 184 271 184 272 183 272 31 272 29 273 31 273 183 273 183 274 182 274 29 274 29 275 182 275 181 275 27 276 29 276 181 276 181 277 180 277 27 277 25 278 27 278 180 278 180 279 179 279 25 279 24 280 25 280 179 280 179 281 156 281 24 281 24 282 156 282 157 282 22 283 24 283 157 283 22 284 157 284 155 284 23 285 22 285 155 285 155 286 178 286 23 286 26 287 23 287 178 287 178 288 177 288 26 288 28 289 26 289 177 289 177 290 175 290 28 290 28 291 175 291 176 291 30 292 28 292 176 292 32 293 30 293 130 293 186 294 187 294 188 294 188 295 189 295 186 295 186 296 189 296 190 296 191 297 186 297 190 297 190 298 192 298 191 298 193 299 191 299 192 299 192 300 194 300 193 300 195 301 193 301 194 301 196 302 195 302 194 302 194 303 197 303 196 303 198 304 196 304 197 304 197 305 199 305 198 305 198 306 199 306 200 306 198 307 200 307 201 307 202 308 198 308 201 308 201 309 203 309 202 309 202 310 203 310 204 310 205 311 202 311 204 311 206 312 207 312 205 312 204 313 206 313 205 313 208 314 209 314 210 314 210 315 211 315 208 315 212 316 208 316 211 316 211 317 213 317 212 317 214 318 212 318 213 318 213 319 215 319 214 319 216 320 214 320 215 320 215 321 217 321 216 321 216 322 217 322 218 322 219 323 216 323 218 323 217 324 220 324 218 324 221 325 219 325 218 325 220 326 222 326 218 326 223 327 221 327 218 327 224 328 223 328 218 328 222 329 224 329 218 329 225 330 223 330 224 330 224 331 226 331 225 331 227 332 225 332 226 332 226 333 228 333 227 333 229 334 227 334 228 334 228 335 230 335 229 335 231 336 229 336 230 336 230 337 232 337 231 337 146 338 233 338 144 338 144 339 233 339 234 339 144 340 234 340 187 340 235 341 144 341 187 341 187 342 186 342 235 342 236 343 235 343 186 343 186 344 191 344 236 344 237 345 236 345 191 345 191 346 193 346 237 346 238 347 237 347 193 347 193 348 195 348 238 348 239 349 238 349 195 349 195 350 196 350 239 350 240 351 239 351 196 351 196 352 198 352 240 352 241 353 240 353 198 353 198 354 202 354 241 354 242 355 241 355 202 355 202 356 205 356 242 356 243 357 242 357 205 357 205 358 207 358 243 358 244 359 243 359 207 359 207 360 206 360 244 360 244 361 206 361 245 361 246 362 244 362 245 362 245 363 247 363 246 363 248 364 246 364 247 364 247 365 245 365 249 365 250 366 251 366 252 366 250 367 252 367 253 367 250 368 253 368 248 368 250 369 248 369 247 369 249 370 250 370 247 370 206 371 204 371 249 371 245 372 206 372 249 372 204 373 203 373 257 373 258 374 103 374 94 374 258 375 94 375 257 375 257 376 203 376 201 376 258 377 257 377 201 377 86 378 103 378 258 378 201 379 200 379 258 379 258 380 200 380 199 380 258 381 199 381 197 381 258 382 197 382 256 382 258 383 256 383 86 383 93 384 257 384 94 384 257 385 249 385 204 385 59 386 259 386 96 386 260 387 96 387 259 387 259 388 261 388 260 388 262 389 260 389 261 389 261 390 263 390 262 390 262 391 263 391 250 391 249 392 262 392 250 392 190 393 264 393 192 393 265 394 104 394 90 394 265 395 90 395 264 395 265 396 264 396 190 396 106 397 104 397 265 397 190 398 189 398 265 398 265 399 189 399 188 399 266 400 265 400 188 400 266 401 108 401 106 401 265 402 266 402 106 402 110 403 108 403 266 403 188 404 187 404 266 404 266 405 187 405 234 405 233 406 266 406 234 406 233 407 112 407 110 407 266 408 233 408 110 408 114 409 112 409 233 409 233 410 146 410 114 410 116 411 114 411 146 411 93 412 96 412 260 412 262 413 93 413 260 413 262 414 257 414 93 414 262 415 249 415 257 415 225 416 267 416 268 416 225 417 268 417 269 417 225 418 269 418 223 418 270 419 267 419 225 419 225 420 227 420 270 420 271 421 270 421 227 421 229 422 272 422 271 422 227 423 229 423 271 423 273 424 272 424 229 424 229 425 231 425 273 425 133 426 273 426 231 426 232 427 131 427 133 427 231 428 232 428 133 428 132 429 131 429 232 429 230 430 274 430 132 430 232 431 230 431 132 431 275 432 274 432 230 432 230 433 228 433 275 433 276 434 275 434 228 434 228 435 226 435 276 435 277 436 276 436 226 436 226 437 224 437 277 437 222 438 255 438 277 438 224 439 222 439 277 439 220 440 254 440 255 440 220 441 255 441 222 441 278 442 254 442 220 442 217 443 279 443 278 443 220 444 217 444 278 444 279 445 217 445 280 445 215 446 281 446 282 446 215 447 282 447 280 447 217 448 215 448 280 448 250 449 281 449 215 449 215 450 213 450 250 450 283 451 250 451 213 451 211 452 284 452 283 452 213 453 211 453 283 453 285 454 284 454 211 454 211 455 210 455 285 455 286 456 285 456 210 456 210 457 209 457 286 457 287 458 286 458 209 458 209 459 208 459 287 459 288 460 287 460 208 460 208 461 212 461 288 461 289 462 288 462 212 462 214 463 290 463 289 463 212 464 214 464 289 464 291 465 290 465 214 465 214 466 216 466 291 466 292 467 291 467 216 467 216 468 219 468 292 468 293 469 292 469 219 469 221 470 294 470 293 470 219 471 221 471 293 471 295 472 294 472 221 472 223 473 296 473 295 473 221 474 223 474 295 474 269 475 296 475 223 475 276 476 277 476 50 476 50 477 52 477 276 477 275 478 276 478 52 478 52 479 54 479 275 479 274 480 275 480 54 480 54 481 56 481 274 481 274 482 56 482 142 482 274 483 142 483 140 483 274 484 140 484 137 484 274 485 137 485 134 485 132 486 274 486 134 486 259 487 59 487 281 487 261 488 259 488 281 488 263 489 261 489 281 489 281 490 250 490 263 490 60 491 282 491 281 491 59 492 60 492 281 492 280 493 282 493 60 493 62 494 279 494 280 494 60 495 62 495 280 495 278 496 279 496 62 496 62 497 64 497 278 497 141 498 143 498 273 498 139 499 141 499 273 499 138 500 139 500 273 500 136 501 138 501 273 501 135 502 136 502 273 502 273 503 133 503 135 503 143 504 144 504 273 504 272 505 273 505 144 505 144 506 235 506 272 506 271 507 272 507 235 507 236 508 270 508 271 508 235 509 236 509 271 509 267 510 270 510 236 510 237 511 268 511 267 511 236 512 237 512 267 512 269 513 268 513 237 513 238 514 296 514 269 514 237 515 238 515 269 515 295 516 296 516 238 516 239 517 294 517 295 517 238 518 239 518 295 518 293 519 294 519 239 519 240 520 292 520 293 520 239 521 240 521 293 521 291 522 292 522 240 522 240 523 241 523 291 523 290 524 291 524 241 524 241 525 242 525 290 525 289 526 290 526 242 526 242 527 243 527 289 527 288 528 289 528 243 528 243 529 244 529 288 529 287 530 288 530 244 530 246 531 286 531 287 531 244 532 246 532 287 532 285 533 286 533 246 533 246 534 248 534 285 534 285 535 248 535 253 535 284 536 285 536 253 536 253 537 252 537 284 537 284 538 252 538 251 538 283 539 284 539 251 539 283 540 251 540 250 540 64 541 255 541 254 541 64 542 88 542 255 542 64 543 87 543 88 543 63 544 87 544 64 544 63 545 130 545 87 545 63 546 126 546 130 546 47 547 87 547 176 547 87 548 130 548 176 548 47 549 88 549 87 549 47 550 49 550 88 550 49 551 255 551 88 551 49 552 277 552 255 552 32 553 126 553 35 553 32 554 130 554 126 554 47 555 175 555 48 555 47 556 176 556 175 556 30 557 176 557 130 557 35 558 126 558 158 558 61 559 126 559 63 559 64 560 254 560 278 560 49 561 50 561 277 561 2 562 79 562 82 562 79 563 80 563 82 563 91 564 93 564 94 564 91 565 95 565 92 565 91 566 94 566 95 566 33 567 45 567 46 567 33 568 46 568 44 568 33 569 44 569 42 569 33 570 42 570 40 570 33 571 40 571 38 571 33 572 38 572 36 572 34 573 33 573 36 573 33 574 43 574 45 574 33 575 39 575 41 575 33 576 41 576 43 576 37 577 39 577 33 577 86 578 90 578 89 578 85 579 86 579 89 579 85 580 89 580 125 580 89 581 127 581 125 581 10 582 125 582 11 582 11 583 125 583 127 583 11 584 127 584 15 584 192 585 264 585 194 585 86 586 264 586 90 586 86 587 256 587 264 587 194 588 264 588 256 588 194 589 256 589 197 589

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5.dae b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5.dae new file mode 100644 index 0000000..53e75da --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:15.508647 + 2012-07-23T02:15:15.508662 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.00000 -7.45454 5.04167 -2.00000 -8.46762 3.04968 -2.00000 -8.95760 0.87927 -2.00000 -6.00089 1.26557 -2.00000 -5.98181 6.72267 -2.00000 -5.87041 2.08118 -2.00000 -5.49317 2.70207 -2.00000 -4.91993 3.14687 -2.00000 -4.22507 3.35807 -2.00000 -4.14030 7.98967 -2.00000 -3.50089 3.30717 -1.99580 1.04911 2.95447 -2.00000 -2.04357 8.76267 -2.00000 0.17909 8.99567 -2.00000 2.39064 8.67368 -1.86600 4.77932 3.43247 -2.00000 4.45473 7.81767 -2.00000 5.04250 4.35527 -2.00000 5.85836 4.74957 -2.00000 6.24414 6.47868 -2.00000 6.75372 4.88217 -2.00000 7.64707 4.74197 -6.00000 7.99883 -0.06943 -6.00000 7.70889 -2.13763 -6.00000 7.74360 2.00337 -6.00000 6.96060 3.93948 -6.00000 6.89354 -4.06023 -6.00000 5.70319 5.60667 -6.00000 5.60834 -5.70643 -6.00000 4.05705 6.89167 -6.00000 3.94089 -6.96383 -6.00000 2.13437 7.70767 -6.00000 2.00481 -7.74683 -6.00000 -0.00089 -0.00233 -6.00000 0.06618 7.99767 -6.00000 -0.06795 -8.00203 -6.00000 -2.00659 7.74168 -6.00000 -2.13615 -7.71213 -6.00000 -3.94267 6.95867 -6.00000 -4.05883 -6.89673 -6.00000 -5.61012 5.70168 -6.00000 -5.70497 -5.61153 -6.00000 -6.89532 4.05557 -6.00000 -6.96238 -3.94413 -6.00000 -7.71067 2.13297 -6.00000 -7.74538 -2.00803 -6.00000 -8.00061 0.06477 -3.60560 4.59911 -7.73793 -3.60560 5.87471 -6.81972 3.60550 4.59911 -7.73793 3.60550 5.87471 -6.81973 -3.60560 6.97112 -5.69363 3.60550 6.97111 -5.69363 -3.60560 7.85490 -4.39393 3.60550 7.85490 -4.39393 -3.60560 8.49911 -2.96033 3.60550 8.49911 -2.96033 -3.60560 -5.00089 -7.48563 -3.60560 -3.44530 -8.31712 3.60550 -5.00089 -7.48563 3.60550 -3.44496 -8.31723 -3.60560 -1.75737 -8.82922 3.60550 -1.75665 -8.82943 -3.60560 -0.00089 -9.00233 3.60550 -0.00089 -9.00233 -3.60560 7.49365 4.98087 -1.89600 8.00920 4.10117 -1.70680 8.23875 3.61787 -1.34180 8.49911 2.95567 -3.60560 8.49911 2.95567 -3.60560 6.01519 6.69167 -3.60560 4.15704 7.97968 -3.60560 2.03647 8.76367 -3.60560 -0.21260 8.99567 -3.60560 -2.44848 8.65868 -3.60560 -4.52976 7.77467 -3.60560 -6.32525 6.40067 -3.60560 -7.72158 4.62267 -3.60560 -8.63065 2.55248 -3.60560 -8.99508 0.32108 -3.60560 -8.79186 -1.93072 -2.67480 -8.87480 -1.50352 -2.18090 -8.99973 -0.14673 -3.15220 -8.54995 -2.81543 -3.60560 -8.03383 -4.06093 -1.00000 -3.75089 2.33887 1.00000 -3.75089 2.33887 -3.60560 2.09911 -8.75393 3.60550 2.09911 -8.75393 -1.00000 5.17159 3.12238 1.00000 5.17159 3.12238 0.00000 -5.00089 -0.00233 -1.00000 -5.00089 0.93118 1.00000 -5.00089 1.10617 1.00000 -5.00089 1.37067 -1.00000 -5.00089 1.37067 1.37480 -5.00089 -0.58433 -1.25900 -5.00089 -0.53753 -2.31300 -6.00089 -0.50973 -4.17820 -6.95020 -5.63412 -4.34790 -6.49255 -6.10052 -4.54170 -5.78034 -6.70483 -1.00000 -4.74733 2.03607 1.00000 -4.74552 2.03817 1.00000 5.57884 3.51017 -1.00000 5.57893 3.51017 1.00000 6.07904 3.76957 -1.00000 6.07915 3.76968 1.00000 6.63105 3.87917 -1.00000 6.63115 3.87917 1.00000 7.19123 3.83077 -1.00000 7.19131 3.83077 1.00000 7.71590 3.62837 -1.00000 7.71601 3.62827 1.00000 8.16394 3.28727 -1.00000 8.16406 3.28717 1.00000 8.49911 2.83508 -1.00000 8.49911 2.83508 -1.67330 -5.07965 -0.53843 -4.11050 -5.05836 -7.39513 -4.32460 -5.19024 -7.24833 -2.01210 -5.29806 -0.52692 -4.45570 -5.35820 -7.08053 -1.71140 -5.29806 1.17887 -1.70710 -4.79262 2.39278 -1.68300 -3.67164 2.64587 -5.15080 0.02667 -8.57373 -1.50000 5.06648 3.20547 -1.70710 5.92460 4.02497 -1.70710 7.13800 4.14037 -5.15080 2.04048 -8.32713 5.25480 8.49911 -0.00233 5.15080 8.49911 -1.10663 5.15080 8.49911 1.10197 4.97780 8.49911 -1.69952 5.07200 8.49911 1.41367 4.96590 8.49911 1.72547 4.72950 8.49911 -2.20792 4.82350 8.49911 2.03877 4.63240 8.49911 2.34737 4.40720 8.49911 -2.60963 4.36760 8.49911 2.64117 4.01370 8.49911 -2.87433 4.00940 8.49911 2.87157 3.60550 8.49911 2.95567 -0.00000 8.49911 -0.00233 1.34180 8.49911 2.95567 -4.01250 8.49911 -2.87492 -4.01070 8.49911 2.87097 -4.40320 8.49911 2.60887 -4.40880 8.49911 -2.60823 -4.72670 8.49911 2.20777 -4.72850 8.49911 -2.20963 -4.97660 8.49911 -1.70243 -4.97670 8.49911 1.69757 -5.15080 8.49911 -1.10663 -5.15080 8.49911 1.10197 -5.25480 8.49911 -0.00234 -5.15080 -1.16784 -8.49393 -5.15080 -2.39342 -8.23302 -5.15080 -3.69770 -7.73553 -5.15080 -5.03250 -6.94153 -5.15080 -6.33935 -5.77232 -5.15080 -7.48297 -4.18423 -5.15080 -8.26608 -2.27303 -5.15080 -8.57061 -0.17332 -5.15080 -8.34856 1.94337 -5.15080 -7.65831 3.84908 -5.15080 -6.65255 5.40367 -5.15080 -5.48446 6.58567 -5.15080 -4.27482 7.42767 -5.15080 -3.07933 7.99767 -5.15080 -1.92971 8.34967 -5.15080 -0.86492 8.52567 -5.15080 0.07097 8.56867 -5.15080 5.86632 -6.25092 -5.15080 4.29269 -7.42083 -5.15080 7.13263 -4.75442 -5.15080 8.02585 -3.00912 -5.15080 8.01546 3.03207 -5.15080 7.13700 4.74317 -5.15080 5.98916 6.12867 -5.15080 4.73707 7.14067 -5.15080 3.47752 7.83167 -5.15080 2.25250 8.26767 -5.15080 1.10237 8.49767 2.00000 6.26146 6.46167 2.00000 7.64707 4.74197 2.00000 6.75408 4.88217 2.00000 5.85895 4.74967 2.00000 5.04316 4.35577 2.00000 4.49639 7.79367 2.00000 4.38705 3.74247 2.00000 2.45995 8.65467 1.99160 1.03584 2.94627 2.00000 0.27493 8.99368 2.00000 -1.92679 8.78967 2.00000 -3.50089 3.30717 2.00000 -4.01233 8.05467 2.00000 -4.21819 3.35877 2.00000 -4.91452 3.14967 2.00000 -5.48962 2.70607 2.00000 -5.85578 6.83267 2.00000 -5.86839 2.08647 2.00000 -6.00089 1.26557 2.00000 -7.34581 5.19867 2.00000 -8.93237 1.10617 2.00000 -8.39242 3.25067 6.00000 -7.47839 2.84148 6.00000 -7.95962 0.80917 6.00000 -7.89848 -1.27833 6.00000 -7.29913 -3.27893 6.00000 -6.48758 4.67987 6.00000 -6.20241 -5.05613 6.00000 -5.05471 6.19968 6.00000 -4.68308 -6.48903 6.00000 -3.27744 7.29567 6.00000 -2.84466 -7.47983 6.00000 -0.00089 -0.00233 6.00000 -1.27687 7.89568 6.00000 -0.81243 -7.96103 6.00000 0.81066 7.95667 6.00549 1.09911 -7.99241 6.00000 2.84287 7.47567 6.00000 3.27565 -7.30053 6.00000 4.68129 6.48467 6.00000 5.05293 -6.20383 6.00000 6.20063 5.05167 6.00000 6.48580 -4.68453 6.00000 7.29735 3.27417 6.00000 7.47661 -2.84613 6.00000 7.89670 1.27367 6.00000 7.95784 -0.81383 1.65760 8.28299 3.51577 1.89880 8.00438 4.11057 3.60550 7.44183 5.05767 3.60550 5.87572 6.81467 3.60550 3.90805 8.10468 3.60550 1.67290 8.84068 3.60550 -0.67658 8.97267 3.60550 -2.97980 8.49067 3.60550 -5.07941 7.42767 3.60550 -6.83185 5.85767 3.60550 -8.11732 3.88657 3.60550 -8.84796 1.64977 2.28110 -8.99948 -0.16173 3.60550 -8.97381 -0.70003 2.95600 -8.85632 -1.60902 3.60550 -8.48627 -3.00203 2.34850 -6.00089 -0.30623 5.12570 -5.84850 -6.28963 4.91560 -6.47571 -5.81152 4.52990 -7.32036 -4.98423 4.08970 -8.00021 -4.04023 5.15080 0.02667 -8.57373 5.15080 2.04048 -8.32713 1.68300 -3.67164 2.64577 1.68300 -5.31788 1.37067 1.70710 -4.79262 2.39278 4.76790 -5.04422 -7.17183 1.81460 -5.12653 -0.37923 4.94330 -5.14915 -6.99723 2.10240 -5.35301 -0.34243 5.12360 -5.46303 -6.62893 1.50000 5.06648 3.20547 1.70710 5.92717 4.02597 1.70710 7.14342 4.13947 5.15080 4.83180 7.07667 5.15080 3.91347 7.62267 5.15080 3.04600 8.00967 5.15080 5.75663 6.34767 5.15080 6.64504 5.41067 5.15080 7.45116 4.23277 5.15080 8.10373 2.78777 5.15080 8.02586 -3.00913 5.15080 7.13271 -4.75433 5.15080 5.86657 -6.25073 5.15080 4.29269 -7.42083 5.15080 -1.14221 -8.49743 5.15080 -2.17531 -8.29333 5.15080 -3.04778 -8.01392 5.15080 -4.76167 -7.13003 5.15080 -3.88059 -7.64542 5.15080 -6.67612 -5.37923 5.15080 -7.55419 -4.05413 5.15080 -8.22952 -2.40213 5.15080 -8.55833 -0.49193 5.15080 -8.43597 1.52047 5.15080 -7.83186 3.48267 5.15080 -6.79325 5.22567 5.15080 -5.46640 6.60067 5.15080 -4.02045 7.56867 5.15080 -2.57937 8.17168 5.15080 -1.22172 8.48167 5.15080 0.03365 8.56867 5.15080 1.17758 8.48767 5.15080 2.18956 8.28468 + + + + + + + + + + 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00093 -0.00013 1.00000 -0.00022 0.00060 1.00000 -0.00007 0.00068 1.00000 0.00010 0.00071 0.99931 -0.03595 0.00917 0.99942 0.01307 0.03151 0.95139 0.30366 0.05155 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00000 0.58421 -0.81160 -0.00000 0.58421 -0.81160 -0.00000 0.71649 -0.69760 0.00000 0.71649 -0.69760 0.00000 0.82693 -0.56230 -0.00000 0.82693 -0.56231 -0.00000 0.91214 -0.40988 -0.00000 0.91214 -0.40988 -0.00000 -0.47140 -0.88192 0.00001 -0.47137 -0.88194 -0.00000 -0.29032 -0.95693 0.00000 -0.29031 -0.95693 -0.00002 -0.09808 -0.99518 0.00000 -0.09800 -0.99519 -0.01024 0.87126 0.49071 -0.06521 0.91102 0.40717 -0.17235 0.94537 0.27670 0.00000 0.89569 0.44469 0.01917 0.77775 0.62828 -0.02114 0.75645 0.65371 0.02078 0.59899 0.80048 -0.02269 0.56954 0.82165 0.02217 0.38298 0.92349 -0.02391 0.34667 0.93768 0.02368 0.14404 0.98929 -0.02502 0.10258 0.99441 0.02543 -0.10423 0.99423 -0.02645 -0.14899 0.98849 0.02645 -0.34579 0.93794 -0.02841 -0.39078 0.92005 0.02716 -0.56661 0.82354 -0.02926 -0.60746 0.79381 0.02872 -0.75185 0.65870 -0.03036 -0.78610 0.61735 0.02994 -0.89095 0.45311 -0.03152 -0.91516 0.40187 0.03084 -0.97499 0.22011 -0.03298 -0.98639 0.16110 -0.05601 -0.99588 -0.07131 0.02851 -0.96782 -0.25002 -0.14979 -0.93150 -0.33147 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.93971 -0.00005 -0.34197 0.93968 0.00004 -0.34206 0.93969 -0.00001 -0.34203 0.93969 -0.00011 -0.34201 0.94011 -0.03212 -0.33935 0.93968 -0.00001 -0.34206 0.00000 -0.93445 0.35609 0.00047 -0.93398 0.35732 -0.00074 -0.29076 0.95680 0.00000 -0.28939 0.95721 0.00000 -0.68960 0.72419 -0.00003 -0.68952 0.72427 -0.00002 -0.46037 0.88773 0.00002 -0.46050 0.88766 0.00004 -0.19475 0.98085 -0.00001 -0.19457 0.98089 0.00000 0.08608 0.99629 0.00000 0.08608 0.99629 0.00001 0.35991 0.93299 -0.00003 0.36005 0.93293 -0.00001 0.60575 0.79565 -0.00000 0.60574 0.79566 0.00002 0.80338 0.59547 0.00000 0.80342 0.59542 0.98456 0.02268 -0.17359 0.98441 0.02224 -0.17448 0.10580 -0.99355 -0.04069 0.18652 -0.98043 -0.06299 0.43702 -0.88545 -0.15809 0.52681 -0.82743 -0.19452 0.64060 -0.73194 -0.23214 0.83438 -0.45143 -0.31624 0.86804 -0.37946 -0.32018 0.38545 -0.92273 -0.00000 0.93299 -0.30758 0.18688 0.96080 -0.27377 0.04380 0.92127 -0.36020 0.14671 0.28236 -0.89643 0.34160 0.24497 -0.89535 0.37193 0.44814 -0.25993 0.85534 0.91710 -0.24439 0.31495 0.38019 -0.21147 0.90041 0.93592 -0.10243 0.33699 0.93313 -0.09815 0.34587 0.90433 0.02992 0.42578 0.25645 -0.66646 0.70005 0.94919 -0.23814 0.20575 0.69006 -0.40578 0.59930 0.21665 -0.64639 0.73160 0.38812 -0.42440 0.81807 0.91868 -0.17188 0.35564 0.93764 -0.05092 0.34385 0.92766 -0.03536 0.37175 0.36872 -0.18086 0.91177 0.28723 -0.09069 0.95356 0.39482 0.07909 0.91535 0.91698 0.06185 0.39411 0.93728 0.21555 0.27393 0.87281 0.20909 0.44100 0.35631 0.33642 0.87170 0.29069 0.41024 0.86441 0.31632 0.81048 0.49301 0.39989 0.55520 0.72927 0.20559 0.78625 0.58270 0.18566 -0.97527 -0.11992 0.36546 -0.92859 -0.06445 0.53712 -0.83817 -0.09468 0.90609 -0.39177 -0.15973 0.90607 -0.39182 -0.15975 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.60175 -0.11087 -0.79095 -0.55260 -0.17354 -0.81518 -0.56293 -0.29456 -0.77224 -0.59656 -0.31335 -0.73887 -0.53395 -0.43226 -0.72667 -0.59855 -0.49298 -0.63143 -0.53858 -0.56180 -0.62794 -0.57917 -0.65088 -0.49084 -0.55240 -0.67644 -0.48712 -0.55917 -0.76715 -0.31434 -0.56537 -0.76467 -0.30925 -0.54593 -0.82915 -0.12026 -0.57371 -0.81292 -0.10010 -0.53804 -0.83832 0.08794 -0.58049 -0.80638 0.11305 -0.53318 -0.79543 0.28811 -0.59078 -0.74279 0.31501 -0.52834 -0.71286 0.46119 -0.60082 -0.63008 0.49194 -0.53089 -0.60277 0.59568 -0.61001 -0.45269 0.65035 -0.56030 -0.49860 0.66141 -0.55481 -0.35806 0.75098 -0.60158 -0.29950 0.74055 -0.54973 -0.24456 0.79874 -0.56882 -0.13413 0.81145 -0.65227 -0.03479 0.75718 -0.55468 -0.10199 0.82579 -0.25225 0.69332 -0.67504 -0.29856 0.72856 -0.61649 -0.24741 0.80122 -0.54482 -0.29593 0.85032 -0.43518 -0.25744 0.88139 -0.39607 -0.16263 0.61088 -0.77484 -0.29884 0.84469 -0.44406 -0.38652 0.86862 -0.31001 -0.48835 0.83932 -0.23888 -0.63668 0.74832 -0.18615 -0.15915 0.62871 0.76118 -0.29618 0.84591 0.44353 -0.38577 0.86855 0.31114 -0.48964 0.83827 0.23993 -0.63937 0.74584 0.18689 -0.24788 0.86185 0.44246 -0.26528 0.86359 0.42875 -0.26594 0.74233 0.61500 -0.24343 0.73385 0.63419 -0.28203 0.60308 0.74616 -0.22637 0.55490 0.80053 -0.28338 0.46127 0.84079 -0.23125 0.32622 0.91657 -0.24490 0.33621 0.90939 -0.27617 0.18847 0.94245 -0.20856 0.06716 0.97570 -0.24805 0.09940 0.96363 -0.27362 -0.04414 0.96083 -0.22530 -0.15889 0.96125 -0.24051 -0.14466 0.95981 -0.27809 -0.28122 0.91847 -0.20592 -0.42115 0.88331 -0.26174 -0.37731 0.88833 -0.26835 -0.55035 0.79064 -0.22932 -0.59153 0.77299 -0.28987 -0.68074 0.67273 -0.22593 -0.76613 0.60167 -0.29289 -0.80279 0.51937 -0.23225 -0.89057 0.39107 -0.29251 -0.89910 0.32566 -0.23678 -0.95886 0.15660 -0.29312 -0.95086 0.09975 -0.23781 -0.96738 -0.08730 -0.29169 -0.94661 -0.13729 -0.23916 -0.91479 -0.32553 -0.28702 -0.88640 -0.36320 -0.44935 -0.80371 -0.39005 -0.23582 -0.78860 -0.56789 -0.37426 -0.72633 -0.57653 -0.40666 -0.55975 -0.72202 -0.54778 -0.62292 -0.55849 -0.39647 -0.61212 -0.68419 -0.38431 -0.48490 -0.78561 -0.12955 -0.33273 -0.93408 -0.30457 -0.44371 -0.84283 -0.38468 -0.47189 -0.79331 -0.24704 -0.45679 -0.85458 -0.28159 -0.34197 -0.89653 -0.24228 -0.28167 -0.92842 -0.28001 -0.19989 -0.93896 -0.23516 -0.06479 -0.96980 -0.55730 0.05702 0.82835 -0.63252 0.15189 0.75951 -0.55797 0.11524 0.82182 -0.55541 0.27883 0.78343 -0.60120 0.31219 0.73559 -0.54039 0.40471 0.73770 -0.59035 0.50737 0.62774 -0.56890 0.50605 0.64828 -0.54586 0.64522 0.53454 -0.59262 0.64309 0.48502 -0.52512 0.75709 0.38868 -0.60049 0.74131 0.29980 -0.51763 0.82995 0.20797 -0.62777 0.77615 0.05912 -0.56078 0.82176 0.10119 -0.55339 0.83129 -0.05212 -0.60152 0.79112 -0.11091 -0.52072 0.82848 -0.20609 -0.59707 0.73852 -0.31320 -0.52881 0.75554 -0.38667 -0.58696 0.63817 -0.49822 -0.54267 0.64119 -0.54257 -0.57115 0.48974 -0.65874 -0.56180 0.49809 -0.66052 -0.54455 0.31446 -0.77755 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00229 0.00090 -1.00000 0.00022 0.00142 -1.00000 -0.00013 0.00137 -1.00000 -0.00181 0.00052 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00287 0.00029 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00221 0.00099 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 0.00000 0.93296 0.35999 0.01931 0.90839 0.41767 0.07329 0.87296 0.48226 0.02584 0.89306 0.44920 -0.02382 0.77847 0.62723 0.03304 0.74609 0.66503 -0.03076 0.60209 0.79784 0.03889 0.54786 0.83567 -0.03569 0.38917 0.92047 0.04324 0.31247 0.94894 -0.03930 0.15320 0.98741 0.04626 0.05603 0.99736 -0.04162 -0.09218 0.99487 0.04789 -0.20460 0.97767 -0.04232 -0.33209 0.94230 0.04815 -0.45117 0.89114 -0.04168 -0.55204 0.83278 0.04659 -0.66655 0.74400 -0.04000 -0.73832 0.67327 0.04388 -0.83681 0.54573 -0.03649 -0.88032 0.47297 0.03987 -0.94982 0.31025 -0.03167 -0.96925 0.24404 0.03216 -0.99768 0.05994 0.04106 -0.99773 0.05344 -0.02553 -0.99358 -0.11018 0.11229 -0.97211 -0.20588 -0.90630 0.00000 -0.42263 -0.86964 -0.08004 -0.48716 -0.89996 -0.02187 -0.43542 -0.90429 -0.01077 -0.42679 -0.90564 -0.00650 -0.42399 -0.90705 -0.00088 -0.42103 -0.97622 0.01177 -0.21645 -0.97610 0.01148 -0.21702 -0.90078 -0.42872 0.06920 -0.23467 -0.90790 0.34734 -0.38011 -0.81899 0.42985 -0.93601 -0.30030 0.18358 -0.93307 -0.31049 0.18157 -0.44672 -0.25891 0.85639 -0.91709 -0.24350 0.31568 -0.93310 -0.10343 0.34443 -0.96004 0.02008 0.27915 -0.88250 -0.12152 0.45434 -0.38009 -0.21140 0.90047 -0.42098 -0.90707 0.00000 -0.90018 -0.38708 -0.19959 -0.03426 -0.99935 -0.01107 -0.22538 -0.96807 -0.10972 -0.37293 -0.91155 -0.17319 -0.57419 -0.77333 -0.26881 -0.63800 -0.71164 -0.29416 -0.84456 -0.35638 -0.39964 -0.84810 -0.34464 -0.40243 -0.86355 -0.34435 0.36838 -0.18530 -0.67765 0.71165 -0.25467 -0.63445 0.72981 -0.90722 -0.15464 0.39121 -0.38784 -0.42433 0.81824 -0.91871 -0.17172 0.35564 -0.92735 -0.05479 0.37016 -0.93552 -0.03282 0.35174 -0.21482 -0.19021 0.95795 -0.35603 -0.08683 0.93043 -0.39435 0.07911 0.91555 -0.91700 0.06187 0.39407 -0.93692 0.21779 0.27341 -0.86845 0.20847 0.44981 -0.14894 0.35590 0.92258 -0.33379 0.44138 0.83293 -0.36021 0.56509 0.74224 -0.31768 0.81062 0.49191 -0.20561 0.78621 0.58275 -0.25026 -0.96659 -0.05548 -0.57845 -0.77595 -0.25159 -0.39474 -0.91549 -0.07787 -0.90888 -0.35726 -0.21519 0.56781 0.42068 0.70755 0.65005 0.30960 0.69397 0.55491 0.39474 0.73229 0.54922 0.51733 0.65630 0.60076 0.54852 0.58157 0.55698 0.60269 0.57144 0.61845 0.64850 0.44381 0.55510 0.70789 0.43677 0.53284 0.77122 0.34829 0.59756 0.76810 0.23012 0.54172 0.81835 0.19193 0.62801 0.77595 0.05914 0.57520 0.81767 0.02395 0.54939 0.83396 -0.05174 0.55890 0.80471 -0.20017 0.57329 0.79731 -0.18879 0.55270 0.74187 -0.37967 0.57870 0.71791 -0.38692 0.53584 0.64455 -0.54537 0.59220 0.58621 -0.55286 0.52446 0.50799 -0.68329 0.59974 0.42021 -0.68098 0.61231 0.29515 -0.73346 0.44660 0.27208 -0.85236 0.64151 0.09324 -0.76143 0.34890 -0.01639 -0.93702 0.54828 -0.05448 -0.83452 0.61846 -0.15230 -0.77092 0.57573 -0.18840 -0.79564 0.55772 -0.25315 -0.79049 0.57251 -0.41398 -0.70771 0.65330 -0.30635 -0.69235 0.55497 -0.39466 -0.73229 0.54445 -0.52093 -0.65742 0.59931 -0.54924 -0.58237 0.55510 -0.60780 -0.56784 0.60235 -0.66540 -0.44092 0.55920 -0.70551 -0.43537 0.52905 -0.78549 -0.32111 0.60164 -0.76517 -0.22923 0.51993 -0.84183 -0.14491 0.59979 -0.79982 -0.02343 0.52122 -0.85185 0.05180 0.59424 -0.78264 0.18532 0.52693 -0.81228 0.25008 0.58678 -0.71281 0.38417 0.53799 -0.72414 0.43150 0.56047 -0.59595 0.57508 0.57500 -0.59530 0.56124 0.55205 -0.46385 0.69288 0.59113 -0.42336 0.68653 0.53564 -0.32596 0.77900 0.60099 -0.22961 0.76557 0.54985 -0.18593 0.81431 0.61611 -0.05445 0.78577 0.56673 -0.02406 0.82355 0.54749 0.05911 0.83473 0.61638 0.15487 0.77207 0.57784 0.18798 0.79421 0.55768 0.25377 0.79031 0.28615 0.57168 -0.76896 0.25221 0.69333 -0.67504 0.29853 0.72859 -0.61648 0.24738 0.80123 -0.54483 0.29591 0.85033 -0.43518 0.25742 0.88140 -0.39607 0.16302 0.61210 -0.77379 0.29884 0.84459 -0.44426 0.38634 0.86871 -0.30997 0.48872 0.83916 -0.23869 0.63744 0.74772 -0.18600 0.24869 -0.19671 -0.94840 0.44640 -0.49462 -0.74571 0.51486 -0.51149 -0.68796 0.94330 -0.21642 -0.25171 0.22684 -0.49176 -0.84067 0.26598 -0.45439 -0.85017 0.27274 -0.38929 -0.87981 0.24050 -0.29604 -0.92441 0.25385 -0.28080 -0.92559 0.27661 -0.18625 -0.94276 0.24507 -0.09501 -0.96484 0.31691 0.81044 0.49270 0.37341 0.86446 0.33655 0.43085 0.86208 0.26680 0.49637 0.83828 0.22561 0.57492 0.79448 0.19563 0.67028 0.72250 0.16945 0.19049 0.35601 0.91486 0.26776 0.87810 0.39655 0.22828 0.86977 0.43748 0.28427 0.79120 0.54147 0.25513 0.70166 0.66527 0.22684 0.72704 0.64805 0.27413 0.59534 0.75526 0.25735 0.49384 0.83060 0.22285 0.53449 0.81527 0.27268 0.39198 0.87863 0.23370 0.29726 0.92575 0.22680 0.30461 0.92508 0.27588 0.18904 0.94242 0.22259 0.06886 0.97248 0.23893 0.05447 0.96951 0.28081 -0.06635 0.95747 0.25066 -0.21550 0.94378 0.23221 -0.19924 0.95204 0.27893 -0.37069 0.88588 0.22242 -0.44038 0.86983 0.29208 -0.53205 0.79474 0.22553 -0.65008 0.72562 0.28908 -0.68887 0.66475 0.23735 -0.81368 0.53065 0.28072 -0.82451 0.49130 0.24869 -0.92071 0.30075 0.26912 -0.92047 0.28339 0.25181 -0.96599 0.05874 0.26130 -0.96388 0.05162 0.27659 -0.94706 -0.16302 0.23611 -0.95064 -0.20134 0.26933 -0.91432 -0.30245 0.35858 -0.86409 -0.35323 0.34344 -0.83072 -0.43812 0.48520 -0.71482 -0.50361 0.29171 -0.79734 -0.52835 0.53345 -0.61850 -0.57697 0.26348 0.11725 -0.95751 0.26850 0.11315 -0.95661 -0.00000 0.11747 -0.99308 0.00000 0.11747 -0.99308 -0.26852 0.11315 -0.95661 -0.26350 0.11725 -0.95751 -0.25596 0.36395 -0.89556 -0.26103 0.36037 -0.89554 -0.00000 0.37650 -0.92642 -0.00000 0.37650 -0.92642 0.26081 0.36347 -0.89436 0.25561 0.36091 -0.89689 -0.56332 0.10097 -0.82004 -0.56422 0.10035 -0.81950 -0.28904 0.55927 -0.77696 -0.27231 0.57408 -0.77219 -0.54728 0.31244 -0.77644 -0.55333 -0.05552 -0.83111 -0.26765 -0.09450 -0.95887 0.26778 -0.06276 -0.96143 0.27176 0.56222 -0.78106 0.00965 -0.99918 0.03933 -0.03275 -0.99542 -0.08983 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 0.00000 -0.08748 0.99617 0.00000 -0.08748 0.99617 0.40091 -0.08014 0.91261 0.17719 -0.06659 0.98192 0.90449 0.03213 0.42528 0.01521 -0.06422 0.99782 0.59085 -0.12274 0.79739 -0.80470 -0.13532 0.57805 -0.18092 -0.08603 0.97973 -0.40248 -0.06691 0.91298 0.00252 -0.06387 0.99796 -0.90452 0.03215 0.42522 + + + + + + + + + + + + + + +

3 0 0 0 1 0 2 1 3 1 1 1 4 2 0 2 3 2 3 3 5 3 4 3 4 4 5 4 6 4 4 5 6 5 7 5 4 6 7 6 8 6 9 7 4 7 8 7 8 8 10 8 9 8 9 9 10 9 11 9 12 10 9 10 11 10 13 11 12 11 11 11 14 12 13 12 11 12 14 13 11 13 15 13 16 14 14 14 15 14 15 15 17 15 16 15 16 16 17 16 18 16 19 17 16 17 18 17 18 18 20 18 19 18 21 19 19 19 20 19 22 20 23 20 24 20 25 21 24 21 23 21 23 22 26 22 25 22 27 23 25 23 26 23 26 24 28 24 27 24 29 25 27 25 28 25 28 26 30 26 29 26 31 27 29 27 30 27 30 28 32 28 31 28 31 29 32 29 33 29 34 30 31 30 33 30 32 31 35 31 33 31 35 32 37 32 33 32 47 33 48 33 49 33 50 34 49 34 48 34 48 35 51 35 50 35 52 36 50 36 51 36 51 37 53 37 52 37 54 38 52 38 53 38 53 39 55 39 54 39 56 40 54 40 55 40 57 41 58 41 59 41 60 42 59 42 58 42 58 43 61 43 60 43 62 44 60 44 61 44 61 45 63 45 62 45 64 46 62 46 63 46 65 47 21 47 66 47 65 48 66 48 67 48 65 49 67 49 68 49 69 50 65 50 68 50 19 51 21 51 65 51 65 52 70 52 19 52 16 53 19 53 70 53 70 54 71 54 16 54 14 55 16 55 71 55 71 56 72 56 14 56 13 57 14 57 72 57 72 58 73 58 13 58 12 59 13 59 73 59 73 60 74 60 12 60 9 61 12 61 74 61 74 62 75 62 9 62 4 63 9 63 75 63 75 64 76 64 4 64 0 65 4 65 76 65 77 66 0 66 76 66 1 67 0 67 77 67 77 68 78 68 1 68 2 69 1 69 78 69 78 70 79 70 2 70 80 71 81 71 82 71 83 72 81 72 80 72 80 73 84 73 83 73 96 74 93 74 91 74 91 75 92 75 97 75 59 76 96 76 91 76 57 77 59 77 91 77 97 78 57 78 91 78 98 79 81 79 83 79 98 80 83 80 84 80 98 81 84 81 99 81 98 82 99 82 100 82 101 83 98 83 100 83 82 84 81 84 98 84 102 85 95 85 94 85 94 86 103 86 102 86 85 87 102 87 103 87 103 88 86 88 85 88 90 89 104 89 89 89 105 90 89 90 104 90 104 91 106 91 105 91 107 92 105 92 106 92 106 93 108 93 107 93 109 94 107 94 108 94 108 95 110 95 109 95 111 96 109 96 110 96 110 97 112 97 111 97 113 98 111 98 112 98 112 99 114 99 113 99 115 100 113 100 114 100 114 101 116 101 115 101 117 102 115 102 116 102 2 103 98 103 3 103 2 104 82 104 98 104 118 105 119 105 57 105 97 106 118 106 57 106 120 107 119 107 118 107 118 108 121 108 120 108 122 109 120 109 121 109 98 110 101 110 122 110 121 111 98 111 122 111 95 112 123 112 92 112 124 113 6 113 5 113 124 114 5 114 3 114 124 115 3 115 123 115 123 116 95 116 102 116 124 117 123 117 102 117 102 118 85 118 124 118 7 119 6 119 124 119 124 120 85 120 125 120 125 121 8 121 7 121 124 122 125 122 7 122 10 123 8 123 125 123 89 124 105 124 127 124 128 125 17 125 15 125 127 126 128 126 15 126 128 127 127 127 105 127 105 128 107 128 128 128 18 129 17 129 128 129 129 130 20 130 18 130 128 131 129 131 18 131 128 132 107 132 109 132 129 133 128 133 109 133 109 134 111 134 129 134 21 135 20 135 129 135 66 136 21 136 129 136 67 137 66 137 129 137 129 138 111 138 113 138 67 139 129 139 113 139 115 140 68 140 67 140 113 141 115 141 67 141 115 142 117 142 68 142 123 143 118 143 97 143 123 144 97 144 92 144 121 145 118 145 123 145 123 146 3 146 121 146 98 147 121 147 3 147 133 148 131 148 132 148 134 149 135 149 133 149 132 150 134 150 133 150 136 151 135 151 134 151 137 152 138 152 136 152 134 153 137 153 136 153 139 154 138 154 137 154 137 155 140 155 139 155 141 156 139 156 140 156 140 157 142 157 141 157 143 158 141 158 142 158 142 159 56 159 143 159 144 160 143 160 56 160 117 161 116 161 145 161 55 162 68 162 117 162 55 163 117 163 145 163 145 164 116 164 146 164 145 165 146 165 144 165 145 166 144 166 56 166 56 167 55 167 145 167 69 168 68 168 55 168 147 169 148 169 69 169 55 170 147 170 69 170 149 171 148 171 147 171 147 172 150 172 149 172 151 173 149 173 150 173 150 174 152 174 151 174 151 175 152 175 153 175 154 176 151 176 153 176 153 177 155 177 154 177 156 178 154 178 155 178 155 179 157 179 156 179 37 180 35 180 158 180 158 181 159 181 37 181 37 182 159 182 160 182 39 183 37 183 160 183 160 184 161 184 39 184 41 185 39 185 161 185 161 186 162 186 41 186 43 187 41 187 162 187 162 188 163 188 43 188 43 189 163 189 164 189 45 190 43 190 164 190 164 191 165 191 45 191 46 192 45 192 165 192 165 193 166 193 46 193 44 194 46 194 166 194 166 195 167 195 44 195 42 196 44 196 167 196 167 197 168 197 42 197 40 198 42 198 168 198 168 199 169 199 40 199 40 200 169 200 170 200 38 201 40 201 170 201 170 202 171 202 38 202 36 203 38 203 171 203 171 204 172 204 36 204 36 205 172 205 173 205 36 206 173 206 174 206 34 207 36 207 174 207 51 208 48 208 175 208 175 209 177 209 51 209 53 210 51 210 177 210 177 211 178 211 53 211 55 212 53 212 178 212 147 213 55 213 178 213 150 214 147 214 178 214 152 215 150 215 178 215 153 216 152 216 178 216 178 217 155 217 153 217 179 218 69 218 148 218 179 219 148 219 149 219 179 220 149 220 151 220 179 221 151 221 154 221 156 222 179 222 154 222 69 223 179 223 180 223 65 224 69 224 180 224 180 225 181 225 65 225 70 226 65 226 181 226 181 227 182 227 70 227 71 228 70 228 182 228 182 229 183 229 71 229 71 230 183 230 184 230 72 231 71 231 184 231 184 232 185 232 72 232 72 233 185 233 174 233 73 234 72 234 174 234 174 235 173 235 73 235 73 236 173 236 172 236 74 237 73 237 172 237 172 238 171 238 74 238 74 239 171 239 170 239 75 240 74 240 170 240 170 241 169 241 75 241 76 242 75 242 169 242 169 243 168 243 76 243 77 244 76 244 168 244 168 245 167 245 77 245 78 246 77 246 167 246 167 247 166 247 78 247 79 248 78 248 166 248 166 249 165 249 79 249 80 250 79 250 165 250 165 251 164 251 80 251 84 252 80 252 164 252 164 253 163 253 84 253 162 254 99 254 84 254 163 255 162 255 84 255 100 256 99 256 162 256 161 257 122 257 101 257 161 258 101 258 100 258 162 259 161 259 100 259 120 260 122 260 161 260 160 261 57 261 119 261 160 262 119 262 120 262 161 263 160 263 120 263 58 264 57 264 160 264 160 265 159 265 58 265 61 266 58 266 159 266 159 267 158 267 61 267 61 268 158 268 126 268 185 269 34 269 174 269 34 270 185 270 184 270 31 271 34 271 184 271 184 272 183 272 31 272 29 273 31 273 183 273 183 274 182 274 29 274 29 275 182 275 181 275 27 276 29 276 181 276 181 277 180 277 27 277 25 278 27 278 180 278 180 279 179 279 25 279 24 280 25 280 179 280 179 281 156 281 24 281 24 282 156 282 157 282 22 283 24 283 157 283 22 284 157 284 155 284 23 285 22 285 155 285 155 286 178 286 23 286 26 287 23 287 178 287 178 288 177 288 26 288 28 289 26 289 177 289 177 290 175 290 28 290 28 291 175 291 176 291 30 292 28 292 176 292 32 293 30 293 130 293 186 294 187 294 188 294 188 295 189 295 186 295 186 296 189 296 190 296 191 297 186 297 190 297 190 298 192 298 191 298 193 299 191 299 192 299 192 300 194 300 193 300 195 301 193 301 194 301 196 302 195 302 194 302 194 303 197 303 196 303 198 304 196 304 197 304 197 305 199 305 198 305 198 306 199 306 200 306 198 307 200 307 201 307 202 308 198 308 201 308 201 309 203 309 202 309 202 310 203 310 204 310 205 311 202 311 204 311 206 312 207 312 205 312 204 313 206 313 205 313 208 314 209 314 210 314 210 315 211 315 208 315 212 316 208 316 211 316 211 317 213 317 212 317 214 318 212 318 213 318 213 319 215 319 214 319 216 320 214 320 215 320 215 321 217 321 216 321 216 322 217 322 218 322 219 323 216 323 218 323 217 324 220 324 218 324 221 325 219 325 218 325 220 326 222 326 218 326 223 327 221 327 218 327 224 328 223 328 218 328 222 329 224 329 218 329 225 330 223 330 224 330 224 331 226 331 225 331 227 332 225 332 226 332 226 333 228 333 227 333 229 334 227 334 228 334 228 335 230 335 229 335 231 336 229 336 230 336 230 337 232 337 231 337 146 338 233 338 144 338 144 339 233 339 234 339 144 340 234 340 187 340 235 341 144 341 187 341 187 342 186 342 235 342 236 343 235 343 186 343 186 344 191 344 236 344 237 345 236 345 191 345 191 346 193 346 237 346 238 347 237 347 193 347 193 348 195 348 238 348 239 349 238 349 195 349 195 350 196 350 239 350 240 351 239 351 196 351 196 352 198 352 240 352 241 353 240 353 198 353 198 354 202 354 241 354 242 355 241 355 202 355 202 356 205 356 242 356 243 357 242 357 205 357 205 358 207 358 243 358 244 359 243 359 207 359 207 360 206 360 244 360 244 361 206 361 245 361 246 362 244 362 245 362 245 363 247 363 246 363 248 364 246 364 247 364 247 365 245 365 249 365 250 366 251 366 252 366 250 367 252 367 253 367 250 368 253 368 248 368 250 369 248 369 247 369 249 370 250 370 247 370 206 371 204 371 249 371 245 372 206 372 249 372 204 373 203 373 257 373 258 374 103 374 94 374 258 375 94 375 257 375 257 376 203 376 201 376 258 377 257 377 201 377 86 378 103 378 258 378 201 379 200 379 258 379 258 380 200 380 199 380 258 381 199 381 197 381 258 382 197 382 256 382 258 383 256 383 86 383 93 384 257 384 94 384 257 385 249 385 204 385 59 386 259 386 96 386 260 387 96 387 259 387 259 388 261 388 260 388 262 389 260 389 261 389 261 390 263 390 262 390 262 391 263 391 250 391 249 392 262 392 250 392 190 393 264 393 192 393 265 394 104 394 90 394 265 395 90 395 264 395 265 396 264 396 190 396 106 397 104 397 265 397 190 398 189 398 265 398 265 399 189 399 188 399 266 400 265 400 188 400 266 401 108 401 106 401 265 402 266 402 106 402 110 403 108 403 266 403 188 404 187 404 266 404 266 405 187 405 234 405 233 406 266 406 234 406 233 407 112 407 110 407 266 408 233 408 110 408 114 409 112 409 233 409 233 410 146 410 114 410 116 411 114 411 146 411 93 412 96 412 260 412 262 413 93 413 260 413 262 414 257 414 93 414 262 415 249 415 257 415 225 416 267 416 268 416 225 417 268 417 269 417 225 418 269 418 223 418 270 419 267 419 225 419 225 420 227 420 270 420 271 421 270 421 227 421 229 422 272 422 271 422 227 423 229 423 271 423 273 424 272 424 229 424 229 425 231 425 273 425 133 426 273 426 231 426 232 427 131 427 133 427 231 428 232 428 133 428 132 429 131 429 232 429 230 430 274 430 132 430 232 431 230 431 132 431 275 432 274 432 230 432 230 433 228 433 275 433 276 434 275 434 228 434 228 435 226 435 276 435 277 436 276 436 226 436 226 437 224 437 277 437 222 438 255 438 277 438 224 439 222 439 277 439 220 440 254 440 255 440 220 441 255 441 222 441 278 442 254 442 220 442 217 443 279 443 278 443 220 444 217 444 278 444 279 445 217 445 280 445 215 446 281 446 282 446 215 447 282 447 280 447 217 448 215 448 280 448 250 449 281 449 215 449 215 450 213 450 250 450 283 451 250 451 213 451 211 452 284 452 283 452 213 453 211 453 283 453 285 454 284 454 211 454 211 455 210 455 285 455 286 456 285 456 210 456 210 457 209 457 286 457 287 458 286 458 209 458 209 459 208 459 287 459 288 460 287 460 208 460 208 461 212 461 288 461 289 462 288 462 212 462 214 463 290 463 289 463 212 464 214 464 289 464 291 465 290 465 214 465 214 466 216 466 291 466 292 467 291 467 216 467 216 468 219 468 292 468 293 469 292 469 219 469 221 470 294 470 293 470 219 471 221 471 293 471 295 472 294 472 221 472 223 473 296 473 295 473 221 474 223 474 295 474 269 475 296 475 223 475 276 476 277 476 50 476 50 477 52 477 276 477 275 478 276 478 52 478 52 479 54 479 275 479 274 480 275 480 54 480 54 481 56 481 274 481 274 482 56 482 142 482 274 483 142 483 140 483 274 484 140 484 137 484 274 485 137 485 134 485 132 486 274 486 134 486 259 487 59 487 281 487 261 488 259 488 281 488 263 489 261 489 281 489 281 490 250 490 263 490 60 491 282 491 281 491 59 492 60 492 281 492 280 493 282 493 60 493 62 494 279 494 280 494 60 495 62 495 280 495 278 496 279 496 62 496 62 497 64 497 278 497 141 498 143 498 273 498 139 499 141 499 273 499 138 500 139 500 273 500 136 501 138 501 273 501 135 502 136 502 273 502 273 503 133 503 135 503 143 504 144 504 273 504 272 505 273 505 144 505 144 506 235 506 272 506 271 507 272 507 235 507 236 508 270 508 271 508 235 509 236 509 271 509 267 510 270 510 236 510 237 511 268 511 267 511 236 512 237 512 267 512 269 513 268 513 237 513 238 514 296 514 269 514 237 515 238 515 269 515 295 516 296 516 238 516 239 517 294 517 295 517 238 518 239 518 295 518 293 519 294 519 239 519 240 520 292 520 293 520 239 521 240 521 293 521 291 522 292 522 240 522 240 523 241 523 291 523 290 524 291 524 241 524 241 525 242 525 290 525 289 526 290 526 242 526 242 527 243 527 289 527 288 528 289 528 243 528 243 529 244 529 288 529 287 530 288 530 244 530 246 531 286 531 287 531 244 532 246 532 287 532 285 533 286 533 246 533 246 534 248 534 285 534 285 535 248 535 253 535 284 536 285 536 253 536 253 537 252 537 284 537 284 538 252 538 251 538 283 539 284 539 251 539 283 540 251 540 250 540 64 541 255 541 254 541 64 542 88 542 255 542 64 543 87 543 88 543 63 544 87 544 64 544 63 545 130 545 87 545 63 546 126 546 130 546 47 547 87 547 176 547 87 548 130 548 176 548 47 549 88 549 87 549 47 550 49 550 88 550 49 551 255 551 88 551 49 552 277 552 255 552 32 553 126 553 35 553 32 554 130 554 126 554 47 555 175 555 48 555 47 556 176 556 175 556 30 557 176 557 130 557 35 558 126 558 158 558 61 559 126 559 63 559 64 560 254 560 278 560 49 561 50 561 277 561 2 562 79 562 82 562 79 563 80 563 82 563 91 564 93 564 94 564 91 565 95 565 92 565 91 566 94 566 95 566 33 567 45 567 46 567 33 568 46 568 44 568 33 569 44 569 42 569 33 570 42 570 40 570 33 571 40 571 38 571 33 572 38 572 36 572 34 573 33 573 36 573 33 574 43 574 45 574 33 575 39 575 41 575 33 576 41 576 43 576 37 577 39 577 33 577 86 578 90 578 89 578 85 579 86 579 89 579 85 580 89 580 125 580 89 581 127 581 125 581 10 582 125 582 11 582 11 583 125 583 127 583 11 584 127 584 15 584 192 585 264 585 194 585 86 586 264 586 90 586 86 587 256 587 264 587 194 588 264 588 256 588 194 589 256 589 197 589

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5_no_rot_scaled.dae b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5_no_rot_scaled.dae new file mode 100644 index 0000000..459e2e9 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5_no_rot_scaled.dae @@ -0,0 +1,210 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:50:11 + 2025-02-20T09:50:11 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.9 0.9 0.9 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -2 -7.45454 5.04167 -2 -8.46762 3.04968 -2 -8.9576 0.87927 -2 -6.00089 1.26557 -2 -5.98181 6.72267 -2 -5.87041 2.08118 -2 -5.49317 2.70207 -2 -4.91993 3.14687 -2 -4.22507 3.35807 -2 -4.1403 7.98967 -2 -3.50089 3.30717 -1.9958 1.04911 2.95447 -2 -2.04357 8.76267 -2 0.17909 8.99567 -2 2.39064 8.67368 -1.866 4.77932 3.43247 -2 4.45473 7.81767 -2 5.0425 4.35527 -2 5.85836 4.74957 -2 6.24414 6.47868 -2 6.75372 4.88217 -2 7.64707 4.74197 -6 7.99883 -0.06942999 -6 7.70889 -2.13763 -6 7.7436 2.00337 -6 6.9606 3.93948 -6 6.89354 -4.06023 -6 5.70319 5.60667 -6 5.60834 -5.70643 -6 4.05705 6.89167 -6 3.94089 -6.96383 -6 2.13437 7.70767 -6 2.00481 -7.74683 -6 -8.9e-4 -0.002329885 -6 0.06617999 7.99767 -6 -0.06794995 -8.00203 -6 -2.00659 7.74168 -6 -2.13615 -7.71213 -6 -3.94267 6.95867 -6 -4.05883 -6.89673 -6 -5.61012 5.70168 -6 -5.70497 -5.61153 -6 -6.89532 4.05557 -6 -6.96238 -3.94413 -6 -7.71067 2.13297 -6 -7.74538 -2.00803 -6 -8.00061 0.06476998 -3.6056 4.59911 -7.73793 -3.6056 5.87471 -6.81972 3.6055 4.59911 -7.73793 3.6055 5.87471 -6.81973 -3.6056 6.97112 -5.69363 3.6055 6.97111 -5.69363 -3.6056 7.8549 -4.39393 3.6055 7.8549 -4.39393 -3.6056 8.499112 -2.96033 3.6055 8.499112 -2.96033 -3.6056 -5.00089 -7.48563 -3.6056 -3.4453 -8.31712 3.6055 -5.00089 -7.48563 3.6055 -3.44496 -8.317232 -3.6056 -1.75737 -8.82922 3.6055 -1.75665 -8.82943 -3.6056 -8.9e-4 -9.00233 3.6055 -8.9e-4 -9.00233 -3.6056 7.49365 4.98087 -1.896 8.009202 4.10117 -1.7068 8.23875 3.61787 -1.3418 8.499112 2.95567 -3.6056 8.499112 2.95567 -3.6056 6.01519 6.69167 -3.6056 4.15704 7.97968 -3.6056 2.03647 8.76367 -3.6056 -0.2125999 8.99567 -3.6056 -2.44848 8.65868 -3.6056 -4.52976 7.77467 -3.6056 -6.32525 6.40067 -3.6056 -7.72158 4.62267 -3.6056 -8.63065 2.55248 -3.6056 -8.99508 0.32108 -3.6056 -8.79186 -1.93072 -2.6748 -8.8748 -1.50352 -2.1809 -8.999732 -0.14673 -3.1522 -8.54995 -2.81543 -3.6056 -8.03383 -4.06093 -1 -3.75089 2.33887 1 -3.75089 2.33887 -3.6056 2.09911 -8.753931 3.6055 2.09911 -8.753931 -1 5.17159 3.12238 1 5.17159 3.12238 0 -5.00089 -0.002329885 -1 -5.00089 0.93118 1 -5.00089 1.10617 1 -5.00089 1.37067 -1 -5.00089 1.37067 1.3748 -5.00089 -0.58433 -1.259 -5.00089 -0.53753 -2.313 -6.00089 -0.50973 -4.1782 -6.9502 -5.63412 -4.3479 -6.49255 -6.10052 -4.5417 -5.78034 -6.70483 -1 -4.74733 2.03607 1 -4.74552 2.03817 1 5.57884 3.51017 -1 5.57893 3.51017 1 6.07904 3.76957 -1 6.07915 3.76968 1 6.63105 3.87917 -1 6.63115 3.87917 1 7.19123 3.83077 -1 7.19131 3.83077 1 7.7159 3.62837 -1 7.71601 3.62827 1 8.16394 3.28727 -1 8.16406 3.28717 1 8.499112 2.83508 -1 8.499112 2.83508 -1.6733 -5.07965 -0.53843 -4.1105 -5.05836 -7.39513 -4.3246 -5.19024 -7.24833 -2.0121 -5.29806 -0.52692 -4.4557 -5.3582 -7.08053 -1.7114 -5.29806 1.17887 -1.7071 -4.79262 2.39278 -1.683 -3.67164 2.64587 -5.1508 0.02666991 -8.57373 -1.5 5.06648 3.20547 -1.7071 5.9246 4.02497 -1.7071 7.138 4.14037 -5.1508 2.04048 -8.32713 5.2548 8.499112 -0.002329885 5.1508 8.499112 -1.10663 5.1508 8.499112 1.10197 4.9778 8.499112 -1.69952 5.072 8.499112 1.41367 4.9659 8.499112 1.72547 4.7295 8.499112 -2.20792 4.8235 8.499112 2.03877 4.6324 8.499112 2.34737 4.4072 8.499112 -2.60963 4.3676 8.499112 2.64117 4.0137 8.499112 -2.87433 4.0094 8.499112 2.87157 3.6055 8.499112 2.95567 0 8.499112 -0.002329885 1.3418 8.499112 2.95567 -4.0125 8.499112 -2.87492 -4.0107 8.499112 2.87097 -4.4032 8.499112 2.60887 -4.4088 8.499112 -2.60823 -4.7267 8.499112 2.20777 -4.7285 8.499112 -2.20963 -4.9766 8.499112 -1.70243 -4.9767 8.499112 1.69757 -5.1508 8.499112 -1.10663 -5.1508 8.499112 1.10197 -5.2548 8.499112 -0.002339959 -5.1508 -1.16784 -8.49393 -5.1508 -2.39342 -8.23302 -5.1508 -3.6977 -7.73553 -5.1508 -5.0325 -6.94153 -5.1508 -6.33935 -5.77232 -5.1508 -7.48297 -4.18423 -5.1508 -8.26608 -2.27303 -5.1508 -8.570611 -0.1733199 -5.1508 -8.34856 1.94337 -5.1508 -7.65831 3.84908 -5.1508 -6.65255 5.40367 -5.1508 -5.48446 6.58567 -5.1508 -4.27482 7.42767 -5.1508 -3.07933 7.99767 -5.1508 -1.92971 8.34967 -5.1508 -0.86492 8.525671 -5.1508 0.07096999 8.56867 -5.1508 5.86632 -6.25092 -5.1508 4.29269 -7.42083 -5.1508 7.13263 -4.75442 -5.1508 8.02585 -3.00912 -5.1508 8.01546 3.03207 -5.1508 7.137001 4.74317 -5.1508 5.98916 6.12867 -5.1508 4.73707 7.14067 -5.1508 3.47752 7.83167 -5.1508 2.2525 8.26767 -5.1508 1.10237 8.497672 2 6.26146 6.46167 2 7.64707 4.74197 2 6.75408 4.88217 2 5.85895 4.74967 2 5.04316 4.35577 2 4.49639 7.79367 2 4.38705 3.74247 2 2.45995 8.65467 1.9916 1.03584 2.94627 2 0.27493 8.99368 2 -1.92679 8.78967 2 -3.50089 3.30717 2 -4.01233 8.05467 2 -4.21819 3.35877 2 -4.91452 3.14967 2 -5.48962 2.70607 2 -5.85578 6.83267 2 -5.86839 2.08647 2 -6.00089 1.26557 2 -7.34581 5.19867 2 -8.932372 1.10617 2 -8.39242 3.25067 6 -7.47839 2.84148 6 -7.95962 0.80917 6 -7.89848 -1.27833 6 -7.29913 -3.27893 6 -6.48758 4.67987 6 -6.20241 -5.05613 6 -5.05471 6.19968 6 -4.68308 -6.48903 6 -3.27744 7.29567 6 -2.84466 -7.47983 6 -8.9e-4 -0.002329885 6 -1.27687 7.89568 6 -0.81243 -7.96103 6 0.81066 7.95667 6.00549 1.09911 -7.99241 6 2.84287 7.47567 6 3.27565 -7.30053 6 4.68129 6.48467 6 5.05293 -6.20383 6 6.20063 5.05167 6 6.4858 -4.68453 6 7.29735 3.27417 6 7.47661 -2.84613 6 7.8967 1.27367 6 7.95784 -0.81383 1.6576 8.28299 3.51577 1.8988 8.004382 4.11057 3.6055 7.44183 5.05767 3.6055 5.87572 6.81467 3.6055 3.90805 8.104681 3.6055 1.6729 8.840682 3.6055 -0.67658 8.97267 3.6055 -2.9798 8.490672 3.6055 -5.07941 7.42767 3.6055 -6.83185 5.85767 3.6055 -8.117321 3.88657 3.6055 -8.84796 1.64977 2.2811 -8.999482 -0.1617299 3.6055 -8.973812 -0.70003 2.956 -8.85632 -1.60902 3.6055 -8.48627 -3.00203 2.3485 -6.00089 -0.30623 5.1257 -5.8485 -6.28963 4.9156 -6.47571 -5.81152 4.5299 -7.32036 -4.98423 4.0897 -8.00021 -4.04023 5.1508 0.02666991 -8.57373 5.1508 2.04048 -8.32713 1.683 -3.67164 2.64577 1.683 -5.31788 1.37067 1.7071 -4.79262 2.39278 4.7679 -5.04422 -7.17183 1.8146 -5.12653 -0.37923 4.9433 -5.14915 -6.99723 2.1024 -5.35301 -0.34243 5.1236 -5.46303 -6.62893 1.5 5.06648 3.20547 1.7071 5.92717 4.02597 1.7071 7.14342 4.13947 5.1508 4.8318 7.07667 5.1508 3.91347 7.62267 5.1508 3.046 8.009672 5.1508 5.75663 6.34767 5.1508 6.64504 5.41067 5.1508 7.45116 4.23277 5.1508 8.103732 2.78777 5.1508 8.02586 -3.00913 5.1508 7.13271 -4.75433 5.1508 5.86657 -6.25073 5.1508 4.29269 -7.42083 5.1508 -1.14221 -8.49743 5.1508 -2.17531 -8.293332 5.1508 -3.04778 -8.01392 5.1508 -4.76167 -7.13003 5.1508 -3.88059 -7.64542 5.1508 -6.67612 -5.37923 5.1508 -7.55419 -4.05413 5.1508 -8.22952 -2.40213 5.1508 -8.55833 -0.49193 5.1508 -8.43597 1.52047 5.1508 -7.83186 3.48267 5.1508 -6.79325 5.22567 5.1508 -5.4664 6.60067 5.1508 -4.02045 7.56867 5.1508 -2.57937 8.17168 5.1508 -1.22172 8.48167 5.1508 0.03364998 8.56867 5.1508 1.17758 8.48767 5.1508 2.18956 8.28468 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 -1.04792e-6 0 1 3.78125e-7 0 0.9999996 -9.32949e-4 -1.274e-4 0.9999998 -2.22825e-4 6.04472e-4 0.9999998 -7.17866e-5 6.84903e-4 0.9999998 1.03385e-4 7.10133e-4 0.9993116 -0.03594756 0.009165883 0.9994181 0.01306635 0.03150665 0.9513857 0.3036576 0.05154836 -1 -3.37927e-6 0 -1 0 0 -1 -6.6466e-7 0 -1 1.0234e-6 0 -1 -2.38415e-7 0 -1 -4.60574e-7 0 -1 -4.60589e-7 0 0 0.5842118 -0.8116012 -1.00974e-6 0.5842072 -0.8116046 -9.25605e-7 0.716486 -0.6976015 9.25605e-7 0.7164922 -0.6975952 1.17802e-6 0.8269312 -0.562303 0 0.8269282 -0.5623077 0 0.9121379 -0.4098837 0 -0.471401 -0.881919 8.54575e-6 -0.4713699 -0.8819356 -1.04967e-6 -0.2903223 -0.9569289 1.19935e-6 -0.2903134 -0.9569316 -1.91821e-5 -0.09807986 -0.9951786 0 -0.09800195 -0.9951863 -0.01023805 0.8712627 0.4907104 -0.0652154 0.9110234 0.4071653 -0.1723467 0.945374 0.2767035 0 0.8956865 0.4446864 0.01916551 0.7777537 0.6282771 -0.02114665 0.7564457 0.6537145 0.02077513 0.5989921 0.8004854 -0.02269053 0.5695413 0.8216495 0.02217495 0.3829846 0.9234886 -0.02391427 0.3466683 0.937683 0.02367544 0.1440353 0.9892894 -0.02502387 0.1025769 0.9944103 0.02542603 -0.1042242 0.9942288 -0.02644908 -0.1489835 0.988486 0.02645659 -0.3457894 0.9379392 -0.02841073 -0.390783 0.9200444 0.02716231 -0.5666119 0.823537 -0.02925962 -0.6074627 0.7938091 0.02872163 -0.751855 0.6587027 -0.03036302 -0.7860998 0.6173534 0.02993494 -0.890949 0.4531158 -0.0315212 -0.9151554 0.4018671 0.03083848 -0.9749881 0.2201077 -0.03297954 -0.9863877 0.1610957 -0.05601054 -0.9958804 -0.07131123 0.02851182 -0.9678199 -0.2500237 -0.1497955 -0.9314979 -0.3314707 0 -1 0 0 -1 1.39386e-7 0 -1 -1.41382e-7 0.9397109 -4.90439e-5 -0.34197 0.9396797 3.90088e-5 -0.342056 0.939689 -1.19549e-5 -0.3420303 0.9396948 -1.068e-4 -0.3420144 0.9401111 -0.03212493 -0.3393512 0.939677 -1.23616e-5 -0.3420633 0 -0.9344531 0.3560866 4.69874e-4 -0.933982 0.35732 -7.41456e-4 -0.2907539 0.9567976 0 -0.2893877 0.957212 0 -0.689593 0.7241972 -3.11582e-5 -0.6895117 0.7242745 -2.07335e-5 -0.4603686 0.8877279 2.36926e-5 -0.4605088 0.8876552 4.3635e-5 -0.194746 0.9808538 -9.74427e-6 -0.1945608 0.9808905 4.2403e-6 0.08607983 0.9962882 3.81642e-6 0.08608305 0.996288 1.44148e-5 0.3599148 0.9329852 -2.69186e-5 0.3600512 0.9329326 -6.56268e-6 0.6057468 0.7956575 -3.59884e-6 0.6057386 0.7956638 1.84258e-5 0.8033742 0.5954745 0 0.8034119 0.5954238 0.9845576 0.02267932 -0.1735857 0.9844095 0.02224349 -0.1744802 0.1057979 -0.9935548 -0.04069095 0.1865206 -0.9804294 -0.062994 0.43702 -0.8854503 -0.158087 0.5268017 -0.8274311 -0.1945193 0.6406034 -0.7319418 -0.232139 0.8343838 -0.4514364 -0.316242 0.8680406 -0.3794617 -0.3201786 0.385448 -0.9227296 0 0.9329911 -0.3075781 0.1868781 0.960798 -0.2737683 0.04379695 0.921267 -0.3601977 0.1467135 0.2823632 -0.8964275 0.3415974 0.2449762 -0.8953508 0.3719324 0.4481411 -0.259923 0.8553419 0.9171022 -0.244388 0.3149574 0.3801868 -0.2114647 0.9004115 0.9359216 -0.1024257 0.3369864 0.9331337 -0.09815102 0.3458726 0.9043348 0.02992635 0.4257735 0.256438 -0.6664558 0.7000545 0.9491887 -0.2381357 0.2057478 0.6900651 -0.4057807 0.5992932 0.2166473 -0.6463911 0.7316027 0.388118 -0.424409 0.8180718 0.9186827 -0.1718788 0.3556401 0.9376434 -0.05092275 0.3438487 0.9276595 -0.03535503 0.3717499 0.3687151 -0.1808524 0.9117795 0.2872363 -0.09068757 0.9535571 0.3948174 0.0790894 0.9153491 0.9169796 0.06185048 0.3941105 0.9372816 0.2155544 0.2739335 0.8728131 0.2090928 0.4409961 0.3563076 0.3364213 0.8717027 0.290687 0.4102365 0.8644114 0.3163194 0.81048 0.4930155 0.399887 0.555199 0.7292767 0.2055839 0.7862504 0.5827055 0.185663 -0.9752687 -0.119918 0.365459 -0.9285937 -0.06444686 0.5371193 -0.8381752 -0.0946843 0.9060928 -0.3917691 -0.1597279 0.9060678 -0.3918188 -0.1597472 0 1 0 0 1 -3.3143e-7 0 1 3.75947e-7 0 1 -5.56746e-7 0 1 -1.58189e-7 0 1 -8.31059e-7 0 1 -1.78838e-7 0 1 -1.50347e-7 0 1 2.01655e-7 0 1 0 0 1 0 -0.601754 -0.1108676 -0.7909492 -0.5525991 -0.1735407 -0.8151797 -0.5629219 -0.2945553 -0.7722411 -0.5965633 -0.3133499 -0.7388668 -0.53395 -0.4322572 -0.7266713 -0.5985505 -0.4929815 -0.6314322 -0.5385817 -0.5618031 -0.6279388 -0.5791653 -0.6508806 -0.4908382 -0.5524053 -0.6764356 -0.4871174 -0.5591673 -0.7671522 -0.3143397 -0.5653725 -0.7646697 -0.3092482 -0.5459343 -0.8291528 -0.120256 -0.5737118 -0.8129179 -0.100097 -0.5380409 -0.8383186 0.08794391 -0.5804876 -0.8063838 0.1130469 -0.5331774 -0.795435 0.2881063 -0.5907874 -0.7427918 0.315009 -0.5283427 -0.712853 0.4611883 -0.6008213 -0.6300866 0.4919399 -0.5308853 -0.6027697 0.5956757 -0.6100087 -0.4526932 0.6503524 -0.5603032 -0.4985964 0.6614091 -0.5548086 -0.3580636 0.7509847 -0.6015741 -0.2994999 0.7405461 -0.5497242 -0.2445655 0.7987435 -0.5688192 -0.1341266 0.8114524 -0.6522748 -0.03478777 0.7571839 -0.5546819 -0.1019862 0.8257886 -0.252253 0.6933152 -0.6750426 -0.2985666 0.7285574 -0.6164917 -0.2474089 0.8012231 -0.5448216 -0.2959363 0.8503177 -0.43518 -0.2574458 0.8813923 -0.3960675 -0.1626381 0.6108939 -0.7748275 -0.2988362 0.8446877 -0.4440719 -0.3865234 0.8686146 -0.3100137 -0.4883534 0.8393133 -0.2388811 -0.6366794 0.7483226 -0.1861525 -0.1591504 0.6287053 0.761184 -0.2961778 0.8459082 0.4435292 -0.3857701 0.8685485 0.3111353 -0.4896401 0.8382651 0.2399252 -0.6393707 0.7458389 0.1868941 -0.2478833 0.8618474 0.4424625 -0.2652828 0.8635944 0.4287537 -0.2659437 0.7423306 0.6149955 -0.2434325 0.7338541 0.6341915 -0.2820258 0.6030824 0.7461589 -0.2263724 0.554899 0.8005265 -0.2833836 0.461265 0.8407903 -0.2312546 0.3262191 0.916571 -0.2449038 0.3362074 0.9093881 -0.2761712 0.1884696 0.9424483 -0.2085644 0.06716406 0.9756998 -0.2480476 0.09940224 0.9636346 -0.2736139 -0.04414397 0.9608261 -0.2253051 -0.1588866 0.9612454 -0.2405099 -0.1446608 0.9598064 -0.2780901 -0.2812231 0.9184659 -0.2059204 -0.4211524 0.8833048 -0.2617406 -0.3773119 0.8883286 -0.2683511 -0.550344 0.7906385 -0.2293215 -0.5915274 0.7729858 -0.2898691 -0.6807422 0.6727303 -0.2259318 -0.7661265 0.6016687 -0.2928903 -0.8027874 0.5193725 -0.2322524 -0.8905737 0.391072 -0.292511 -0.8991028 0.3256559 -0.2367796 -0.9588597 0.1565998 -0.2931181 -0.9508585 0.0997501 -0.2378075 -0.9673808 -0.08730423 -0.2916852 -0.9466102 -0.1372915 -0.2391577 -0.9147881 -0.3255249 -0.2870175 -0.8864008 -0.3632007 -0.4493516 -0.8037068 -0.3900495 -0.235819 -0.7886008 -0.5678895 -0.3742555 -0.7263267 -0.5765262 -0.4066606 -0.5597435 -0.722021 -0.5477876 -0.6229245 -0.5584747 -0.3964717 -0.6121266 -0.6841865 -0.3843075 -0.4848958 -0.7856106 -0.1295544 -0.3327332 -0.9340794 -0.3045747 -0.4437152 -0.8428233 -0.3846812 -0.4718955 -0.7933064 -0.2470385 -0.45679 -0.8545847 -0.2815837 -0.3419637 -0.8965331 -0.2422758 -0.2816728 -0.9284195 -0.2800059 -0.1998916 -0.938957 -0.2351534 -0.06478756 -0.9697967 -0.5573028 0.05702131 0.8283491 -0.6325201 0.1518847 0.759506 -0.5579735 0.1152348 0.821819 -0.5554161 0.2788331 0.7834317 -0.6011952 0.3121923 0.7355954 -0.5403859 0.4047064 0.7376963 -0.5903539 0.5073707 0.6277399 -0.5689051 0.5060515 0.6482738 -0.545858 0.6452169 0.5345411 -0.5926147 0.6430875 0.4850221 -0.5251165 0.7570869 0.3886801 -0.6004876 0.7413067 0.2997984 -0.5176272 0.8299462 0.2079702 -0.6277676 0.7761524 0.05912101 -0.5607852 0.8217551 0.1011854 -0.5533866 0.8312925 -0.05211734 -0.6015236 0.791119 -0.1109064 -0.5207245 0.8284761 -0.2060907 -0.5970686 0.738523 -0.313198 -0.5288125 0.7555397 -0.3866744 -0.5869536 0.6381687 -0.4982231 -0.5426716 0.6411941 -0.542566 -0.5711509 0.4897398 -0.6587425 -0.5618041 0.4980878 -0.6605187 -0.5445461 0.3144609 -0.7775501 -0.999997 0.002292871 8.99511e-4 -0.999999 2.19799e-4 0.001416683 -0.9999991 -1.27299e-4 0.001372992 -0.9999982 -0.001810193 5.1974e-4 -1 -2.95543e-7 0 -1 3.93974e-7 0 -1 -7.9964e-7 0 1 -7.50123e-7 0 1 5.30415e-7 0 1 -6.64623e-7 0 1 5.70747e-7 0 1 1.6859e-7 0 1 -4.60589e-7 0 0.9999959 -0.002866685 2.92358e-4 0.9999971 0.002207458 9.90953e-4 1 -5.3041e-7 0 1 7.50113e-7 0 1 -3.37936e-6 0 0 0.9329552 0.3599927 0.0193091 0.9083948 0.4176675 0.07329124 0.8729563 0.4822613 0.02583605 0.8930585 0.4491983 -0.02382081 0.7784674 0.627233 0.03303664 0.7460874 0.665028 -0.03076195 0.6020851 0.7978392 0.03888517 0.5478636 0.8356636 -0.03569686 0.3891729 0.9204729 0.04323643 0.3124719 0.9489426 -0.03929889 0.1531992 0.9874137 0.04625946 0.05602926 0.9973569 -0.04161548 -0.09218424 0.994872 0.04788511 -0.2045993 0.9776739 -0.04232382 -0.332091 0.9422974 0.04815268 -0.45117 0.891138 -0.04168057 -0.5520372 0.8327771 0.04659372 -0.6665487 0.744004 -0.03999751 -0.7383179 0.6732659 0.04387927 -0.8368097 0.5457327 -0.03649228 -0.8803208 0.4729734 0.03986543 -0.9498179 0.3102529 -0.03166919 -0.9692476 0.2440412 0.03216069 -0.9976839 0.05993801 0.04105758 -0.9977269 0.05343717 -0.02552688 -0.993583 -0.1101871 0.1122884 -0.9721127 -0.205884 -0.9063038 5.06537e-6 -0.4226268 -0.8696209 -0.08007216 -0.4871839 -0.8999612 -0.02187561 -0.4354209 -0.9042878 -0.01076936 -0.4267877 -0.9056438 -0.006501197 -0.4239896 -0.9070469 -8.81858e-4 -0.4210289 -0.9762232 0.01176947 -0.2164485 -0.9761009 0.01148211 -0.2170144 -0.9007829 -0.428721 0.06919902 -0.2346664 -0.9079015 0.347342 -0.3801072 -0.8189957 0.4298425 -0.9360152 -0.3002938 0.1835738 -0.9330742 -0.3104956 0.1815634 -0.4467245 -0.258907 0.8563904 -0.9170913 -0.2434972 0.3156784 -0.933097 -0.1034283 0.3444311 -0.9600365 0.02008122 0.2791535 -0.8825021 -0.1215114 0.4543404 -0.3800885 -0.2113952 0.9004692 -0.4209831 -0.9070684 0 -0.9001837 -0.3870835 -0.199589 -0.03426259 -0.9993515 -0.01107466 -0.2253844 -0.9680716 -0.109724 -0.3729253 -0.9115552 -0.1731874 -0.5741918 -0.7733342 -0.2688087 -0.6379976 -0.7116389 -0.2941585 -0.8445578 -0.3563785 -0.3996458 -0.8481017 -0.3446416 -0.4024247 -0.8635532 -0.3443432 0.3683797 -0.1852998 -0.6776499 0.7116563 -0.2546544 -0.6344542 0.7298076 -0.9072185 -0.1546421 0.3912041 -0.3878393 -0.4243337 0.818243 -0.9187127 -0.1717185 0.3556399 -0.9273515 -0.05479204 0.3701584 -0.9355234 -0.03282392 0.3517367 -0.2148243 -0.1901987 0.9579536 -0.3560307 -0.08682781 0.9304317 -0.3943547 0.0791037 0.9155474 -0.9169955 0.06186914 0.3940706 -0.9369161 0.2177893 0.2734158 -0.8684505 0.2084671 0.449817 -0.1489433 0.355899 0.9225789 -0.3337913 0.4413741 0.83293 -0.3602137 0.5650829 0.7422448 -0.3176779 0.810624 0.4919039 -0.2056011 0.7862117 0.5827518 -0.2502555 -0.9665887 -0.05548429 -0.5784512 -0.7759484 -0.2515917 -0.3947367 -0.9154888 -0.07786571 -0.9088774 -0.3572639 -0.2151848 0.5678089 0.4206772 0.7075477 0.650047 0.3095963 0.6939662 0.5549099 0.394743 0.732293 0.5492154 0.5173314 0.6563009 0.6007612 0.5485153 0.5815643 0.5569796 0.6026896 0.5714359 0.6184481 0.6484994 0.4438137 0.5550987 0.7078845 0.4367666 0.5328411 0.7712178 0.3482864 0.5975574 0.7680947 0.2301212 0.5417212 0.8183521 0.1919324 0.628014 0.7759514 0.05914413 0.5751978 0.8176639 0.0239486 0.5493962 0.8339586 -0.05174005 0.5588985 0.8047129 -0.200174 0.5732893 0.7973055 -0.1887947 0.5527049 0.741868 -0.3796698 0.5787001 0.7179126 -0.3869209 0.5358387 0.6445524 -0.5453707 0.5921979 0.5862116 -0.5528631 0.5244586 0.507992 -0.6832915 0.5997346 0.4202129 -0.6809843 0.6123183 0.2951456 -0.7334545 0.4465976 0.2720761 -0.8523645 0.641507 0.09324043 -0.7614297 0.3489122 -0.01638394 -0.9370122 0.5482801 -0.05447381 -0.8345189 0.6184605 -0.1523016 -0.7709156 0.5757296 -0.1883949 -0.7956399 0.5577144 -0.2531554 -0.7904853 0.5725113 -0.4139771 -0.7077103 0.6533015 -0.306349 -0.6923492 0.5549641 -0.3946641 -0.7322945 0.5444505 -0.5209308 -0.657423 0.5993084 -0.549245 -0.5823739 0.5550993 -0.6078014 -0.5678401 0.6023552 -0.665399 -0.4409223 0.5592028 -0.7055088 -0.435373 0.5290488 -0.7854925 -0.3211059 0.6016405 -0.7651672 -0.2292331 0.5199304 -0.8418281 -0.1449069 0.5997847 -0.7998185 -0.02342545 0.5212197 -0.8518494 0.05179518 0.5942429 -0.7826437 0.185322 0.5269285 -0.8122844 0.2500811 0.5867733 -0.7128157 0.3841757 0.5379877 -0.7241406 0.431497 0.5604676 -0.5959509 0.5750814 0.5750018 -0.595297 0.5612437 0.5520504 -0.4638524 0.6928791 0.5911297 -0.4233646 0.6865335 0.5356367 -0.3259662 0.778999 0.6009898 -0.2296084 0.765566 0.5498406 -0.1859306 0.8143127 0.616113 -0.05445587 0.7857731 0.5667286 -0.02406114 0.8235533 0.5474858 0.05910521 0.8347252 0.6163845 0.154867 0.7720664 0.5778371 0.1879794 0.7942091 0.5576751 0.2537752 0.7903142 0.2861521 0.5716817 -0.7689586 0.2522119 0.6933292 -0.6750435 0.298528 0.7285873 -0.6164752 0.2473823 0.8012257 -0.5448298 0.2959051 0.8503297 -0.4351778 0.2574222 0.881398 -0.3960701 0.1630218 0.6121041 -0.7737909 0.2988443 0.844587 -0.4442576 0.3863434 0.8687102 -0.3099704 0.4887149 0.8391587 -0.2386853 0.6374331 0.7477194 -0.1859971 0.2486959 -0.1967171 -0.9483949 0.446396 -0.4946257 -0.7457051 0.5148605 -0.5114942 -0.6879625 0.9432953 -0.2164215 -0.2517058 0.2268489 -0.4917503 -0.8406673 0.2659797 -0.4543905 -0.8501671 0.2727456 -0.3892952 -0.8798063 0.2404901 -0.2960431 -0.9244042 0.2538471 -0.2808042 -0.9255868 0.2766049 -0.1862517 -0.9427619 0.2450701 -0.09501343 -0.9648384 0.316909 0.8104419 0.4926993 0.3734084 0.8644642 0.3365528 0.4308483 0.8620831 0.2668005 0.4963691 0.8382834 0.2256076 0.5749123 0.7944834 0.1956322 0.67028 0.7225034 0.169451 0.1904912 0.356016 0.9148583 0.2677558 0.8780959 0.3965533 0.2282822 0.8697677 0.4374831 0.284268 0.7912001 0.541474 0.2551243 0.7016581 0.6652725 0.2268386 0.7270355 0.6480461 0.2741268 0.5953397 0.7552649 0.2573493 0.4938387 0.8305991 0.2228475 0.5344914 0.8152656 0.2726889 0.3919805 0.8786309 0.2337001 0.2972648 0.9257527 0.2268055 0.3046139 0.9250782 0.2758799 0.1890376 0.9424198 0.2225949 0.0688591 0.9724762 0.2389334 0.05446475 0.9695073 0.2808156 -0.06635427 0.9574653 0.2506625 -0.2154929 0.9437856 0.2322154 -0.1992351 0.9520407 0.2789268 -0.3706912 0.8858826 0.2224156 -0.4403799 0.8698258 0.2920828 -0.5320451 0.7947427 0.2255327 -0.6500817 0.7256231 0.2890774 -0.6888715 0.6647484 0.2373512 -0.8136805 0.530649 0.2807242 -0.8245084 0.4913042 0.2486884 -0.9207099 0.3007448 0.2691174 -0.9204711 0.2833881 0.2518146 -0.9659915 0.05873525 0.2612972 -0.9638769 0.05162435 0.2765877 -0.9470604 -0.1630212 0.2361086 -0.9506401 -0.2013362 0.2693288 -0.9143217 -0.3024532 0.3585809 -0.8640867 -0.3532337 0.3434444 -0.8307222 -0.438117 0.4851975 -0.7148171 -0.503607 0.2916965 -0.7973418 -0.5283553 0.5334392 -0.6185033 -0.5769717 0.263483 0.1172516 -0.9575118 0.268501 0.1131528 -0.9566105 0 0.1174662 -0.9930769 0 0.1174662 -0.993077 -0.2685171 0.1131523 -0.956606 -0.2634989 0.1172511 -0.9575076 -0.2559567 0.3639551 -0.8955574 -0.2610319 0.36037 -0.8955422 0 0.3764968 -0.926418 0 0.3764967 -0.9264181 0.2608057 0.3634667 -0.8943558 0.25561 0.3609113 -0.8968872 -0.5633223 0.1009646 -0.8200454 -0.5642199 0.1003516 -0.8195032 -0.2890417 0.5592756 -0.7769593 -0.2723093 0.5740822 -0.77219 -0.5472813 0.3124441 -0.7764419 -0.5533328 -0.05552214 -0.8311078 -0.2676517 -0.09450155 -0.9588703 0.2677806 -0.06275826 -0.9614338 0.2717589 0.562221 -0.7810599 0.00965178 -0.9991797 0.03932911 -0.03274738 -0.9954183 -0.08983439 -1 0 0 -1 2.30298e-7 0 -1 -3.45495e-7 0 -1 0 0 -1 0 0 -1 4.60585e-7 0 0 -0.08747637 0.9961666 0.4009063 -0.0801388 0.9126072 0.1771755 -0.06659412 0.9819236 0.9044916 0.03213119 0.4252794 0.01521629 -0.06422019 0.9978197 0.5908549 -0.1227393 0.7973867 -0.8047037 -0.1353192 0.5780491 -0.1808972 -0.08603322 0.9797319 -0.4024766 -0.06690788 0.9129819 0.002514302 -0.06386905 0.9979552 -0.9045175 0.03215199 0.4252228 + + + + + + + + + + + + + + +

3 0 0 0 1 0 2 1 3 1 1 1 4 2 0 2 3 2 3 0 5 0 4 0 4 3 5 3 6 3 4 4 6 4 7 4 4 0 7 0 8 0 9 0 4 0 8 0 8 0 10 0 9 0 9 5 10 5 11 5 12 6 9 6 11 6 13 7 12 7 11 7 14 8 13 8 11 8 14 9 11 9 15 9 16 10 14 10 15 10 15 11 17 11 16 11 16 0 17 0 18 0 19 0 16 0 18 0 18 0 20 0 19 0 21 0 19 0 20 0 22 12 23 12 24 12 25 13 24 13 23 13 23 13 26 13 25 13 27 13 25 13 26 13 26 13 28 13 27 13 29 13 27 13 28 13 28 14 30 14 29 14 31 13 29 13 30 13 30 15 32 15 31 15 31 16 32 16 33 16 34 17 31 17 33 17 32 13 35 13 33 13 35 18 37 18 33 18 47 19 48 19 49 19 50 20 49 20 48 20 48 21 51 21 50 21 52 22 50 22 51 22 51 23 53 23 52 23 54 24 52 24 53 24 53 25 55 25 54 25 56 25 54 25 55 25 57 26 58 26 59 26 60 27 59 27 58 27 58 28 61 28 60 28 62 29 60 29 61 29 61 30 63 30 62 30 64 31 62 31 63 31 65 32 21 32 66 32 65 33 66 33 67 33 65 34 67 34 68 34 69 35 65 35 68 35 19 36 21 36 65 36 65 37 70 37 19 37 16 38 19 38 70 38 70 39 71 39 16 39 14 40 16 40 71 40 71 41 72 41 14 41 13 42 14 42 72 42 72 43 73 43 13 43 12 44 13 44 73 44 73 45 74 45 12 45 9 46 12 46 74 46 74 47 75 47 9 47 4 48 9 48 75 48 75 49 76 49 4 49 0 50 4 50 76 50 77 51 0 51 76 51 1 52 0 52 77 52 77 53 78 53 1 53 2 54 1 54 78 54 78 55 79 55 2 55 80 56 81 56 82 56 83 57 81 57 80 57 80 58 84 58 83 58 96 59 93 59 91 59 91 60 92 60 97 60 59 59 96 59 91 59 57 61 59 61 91 61 97 59 57 59 91 59 98 62 81 62 83 62 98 63 83 63 84 63 98 64 84 64 99 64 98 65 99 65 100 65 101 66 98 66 100 66 82 67 81 67 98 67 102 68 95 68 94 68 94 69 103 69 102 69 85 70 102 70 103 70 103 71 86 71 85 71 90 72 104 72 89 72 105 73 89 73 104 73 104 74 106 74 105 74 107 75 105 75 106 75 106 76 108 76 107 76 109 77 107 77 108 77 108 78 110 78 109 78 111 79 109 79 110 79 110 80 112 80 111 80 113 81 111 81 112 81 112 82 114 82 113 82 115 83 113 83 114 83 114 84 116 84 115 84 117 85 115 85 116 85 2 86 98 86 3 86 2 87 82 87 98 87 118 88 119 88 57 88 97 89 118 89 57 89 120 90 119 90 118 90 118 91 121 91 120 91 122 92 120 92 121 92 98 93 101 93 122 93 121 94 98 94 122 94 95 95 123 95 92 95 124 96 6 96 5 96 124 97 5 97 3 97 124 98 3 98 123 98 123 99 95 99 102 99 124 100 123 100 102 100 102 101 85 101 124 101 7 102 6 102 124 102 124 103 85 103 125 103 125 104 8 104 7 104 124 105 125 105 7 105 10 106 8 106 125 106 89 107 105 107 127 107 128 108 17 108 15 108 127 109 128 109 15 109 128 110 127 110 105 110 105 111 107 111 128 111 18 112 17 112 128 112 129 113 20 113 18 113 128 114 129 114 18 114 128 115 107 115 109 115 129 116 128 116 109 116 109 117 111 117 129 117 21 118 20 118 129 118 66 119 21 119 129 119 67 120 66 120 129 120 129 121 111 121 113 121 67 122 129 122 113 122 115 123 68 123 67 123 113 124 115 124 67 124 115 125 117 125 68 125 123 126 118 126 97 126 123 127 97 127 92 127 121 128 118 128 123 128 123 129 3 129 121 129 98 130 121 130 3 130 133 131 131 131 132 131 134 131 135 131 133 131 132 131 134 131 133 131 136 132 135 132 134 132 137 133 138 133 136 133 134 134 137 134 136 134 139 131 138 131 137 131 137 135 140 135 139 135 141 131 139 131 140 131 140 131 142 131 141 131 143 131 141 131 142 131 142 131 56 131 143 131 144 131 143 131 56 131 117 131 116 131 145 131 55 136 68 136 117 136 55 131 117 131 145 131 145 131 116 131 146 131 145 131 146 131 144 131 145 131 144 131 56 131 56 137 55 137 145 137 69 131 68 131 55 131 147 131 148 131 69 131 55 131 147 131 69 131 149 138 148 138 147 138 147 139 150 139 149 139 151 140 149 140 150 140 150 141 152 141 151 141 151 131 152 131 153 131 154 131 151 131 153 131 153 131 155 131 154 131 156 131 154 131 155 131 155 131 157 131 156 131 37 142 35 142 158 142 158 143 159 143 37 143 37 144 159 144 160 144 39 145 37 145 160 145 160 146 161 146 39 146 41 147 39 147 161 147 161 148 162 148 41 148 43 149 41 149 162 149 162 150 163 150 43 150 43 151 163 151 164 151 45 152 43 152 164 152 164 153 165 153 45 153 46 154 45 154 165 154 165 155 166 155 46 155 44 156 46 156 166 156 166 157 167 157 44 157 42 158 44 158 167 158 167 159 168 159 42 159 40 160 42 160 168 160 168 161 169 161 40 161 40 162 169 162 170 162 38 163 40 163 170 163 170 164 171 164 38 164 36 165 38 165 171 165 171 166 172 166 36 166 36 167 172 167 173 167 36 168 173 168 174 168 34 169 36 169 174 169 51 170 48 170 175 170 175 171 177 171 51 171 53 172 51 172 177 172 177 173 178 173 53 173 55 174 53 174 178 174 147 175 55 175 178 175 150 176 147 176 178 176 152 177 150 177 178 177 153 178 152 178 178 178 178 179 155 179 153 179 179 180 69 180 148 180 179 181 148 181 149 181 179 182 149 182 151 182 179 183 151 183 154 183 156 184 179 184 154 184 69 185 179 185 180 185 65 186 69 186 180 186 180 187 181 187 65 187 70 188 65 188 181 188 181 189 182 189 70 189 71 190 70 190 182 190 182 191 183 191 71 191 71 192 183 192 184 192 72 193 71 193 184 193 184 194 185 194 72 194 72 195 185 195 174 195 73 196 72 196 174 196 174 197 173 197 73 197 73 198 173 198 172 198 74 199 73 199 172 199 172 200 171 200 74 200 74 201 171 201 170 201 75 202 74 202 170 202 170 203 169 203 75 203 76 204 75 204 169 204 169 205 168 205 76 205 77 206 76 206 168 206 168 207 167 207 77 207 78 208 77 208 167 208 167 209 166 209 78 209 79 210 78 210 166 210 166 211 165 211 79 211 80 212 79 212 165 212 165 213 164 213 80 213 84 214 80 214 164 214 164 215 163 215 84 215 162 216 99 216 84 216 163 217 162 217 84 217 100 218 99 218 162 218 161 219 122 219 101 219 161 220 101 220 100 220 162 221 161 221 100 221 120 222 122 222 161 222 160 223 57 223 119 223 160 224 119 224 120 224 161 225 160 225 120 225 58 226 57 226 160 226 160 227 159 227 58 227 61 228 58 228 159 228 159 229 158 229 61 229 61 230 158 230 126 230 185 231 34 231 174 231 34 232 185 232 184 232 31 233 34 233 184 233 184 234 183 234 31 234 29 235 31 235 183 235 183 236 182 236 29 236 29 237 182 237 181 237 27 238 29 238 181 238 181 239 180 239 27 239 25 240 27 240 180 240 180 241 179 241 25 241 24 242 25 242 179 242 179 243 156 243 24 243 24 244 156 244 157 244 22 245 24 245 157 245 22 246 157 246 155 246 23 247 22 247 155 247 155 248 178 248 23 248 26 249 23 249 178 249 178 250 177 250 26 250 28 251 26 251 177 251 177 252 175 252 28 252 28 253 175 253 176 253 30 254 28 254 176 254 32 255 30 255 130 255 186 13 187 13 188 13 188 13 189 13 186 13 186 13 189 13 190 13 191 13 186 13 190 13 190 13 192 13 191 13 193 13 191 13 192 13 192 256 194 256 193 256 195 257 193 257 194 257 196 258 195 258 194 258 194 259 197 259 196 259 198 13 196 13 197 13 197 13 199 13 198 13 198 260 199 260 200 260 198 261 200 261 201 261 202 13 198 13 201 13 201 13 203 13 202 13 202 13 203 13 204 13 205 13 202 13 204 13 206 262 207 262 205 262 204 13 206 13 205 13 208 0 209 0 210 0 210 0 211 0 208 0 212 0 208 0 211 0 211 263 213 263 212 263 214 264 212 264 213 264 213 0 215 0 214 0 216 265 214 265 215 265 215 266 217 266 216 266 216 267 217 267 218 267 219 0 216 0 218 0 217 268 220 268 218 268 221 0 219 0 218 0 220 269 222 269 218 269 223 0 221 0 218 0 224 0 223 0 218 0 222 270 224 270 218 270 225 0 223 0 224 0 224 0 226 0 225 0 227 0 225 0 226 0 226 271 228 271 227 271 229 272 227 272 228 272 228 0 230 0 229 0 231 0 229 0 230 0 230 273 232 273 231 273 146 274 233 274 144 274 144 275 233 275 234 275 144 276 234 276 187 276 235 277 144 277 187 277 187 278 186 278 235 278 236 279 235 279 186 279 186 280 191 280 236 280 237 281 236 281 191 281 191 282 193 282 237 282 238 283 237 283 193 283 193 284 195 284 238 284 239 285 238 285 195 285 195 286 196 286 239 286 240 287 239 287 196 287 196 288 198 288 240 288 241 289 240 289 198 289 198 290 202 290 241 290 242 291 241 291 202 291 202 292 205 292 242 292 243 293 242 293 205 293 205 294 207 294 243 294 244 295 243 295 207 295 207 296 206 296 244 296 244 297 206 297 245 297 246 298 244 298 245 298 245 299 247 299 246 299 248 300 246 300 247 300 247 301 245 301 249 301 250 302 251 302 252 302 250 303 252 303 253 303 250 304 253 304 248 304 250 305 248 305 247 305 249 306 250 306 247 306 206 307 204 307 249 307 245 308 206 308 249 308 204 309 203 309 257 309 258 310 103 310 94 310 258 311 94 311 257 311 257 312 203 312 201 312 258 313 257 313 201 313 86 314 103 314 258 314 201 315 200 315 258 315 258 316 200 316 199 316 258 317 199 317 197 317 258 318 197 318 256 318 258 319 256 319 86 319 93 320 257 320 94 320 257 321 249 321 204 321 59 322 259 322 96 322 260 323 96 323 259 323 259 324 261 324 260 324 262 325 260 325 261 325 261 326 263 326 262 326 262 327 263 327 250 327 249 328 262 328 250 328 190 329 264 329 192 329 265 330 104 330 90 330 265 331 90 331 264 331 265 332 264 332 190 332 106 333 104 333 265 333 190 334 189 334 265 334 265 335 189 335 188 335 266 336 265 336 188 336 266 337 108 337 106 337 265 338 266 338 106 338 110 339 108 339 266 339 188 340 187 340 266 340 266 341 187 341 234 341 233 342 266 342 234 342 233 343 112 343 110 343 266 344 233 344 110 344 114 345 112 345 233 345 233 346 146 346 114 346 116 347 114 347 146 347 93 348 96 348 260 348 262 349 93 349 260 349 262 350 257 350 93 350 262 351 249 351 257 351 225 352 267 352 268 352 225 353 268 353 269 353 225 354 269 354 223 354 270 355 267 355 225 355 225 356 227 356 270 356 271 357 270 357 227 357 229 358 272 358 271 358 227 359 229 359 271 359 273 360 272 360 229 360 229 361 231 361 273 361 133 362 273 362 231 362 232 363 131 363 133 363 231 364 232 364 133 364 132 365 131 365 232 365 230 366 274 366 132 366 232 367 230 367 132 367 275 368 274 368 230 368 230 369 228 369 275 369 276 370 275 370 228 370 228 371 226 371 276 371 277 372 276 372 226 372 226 373 224 373 277 373 222 374 255 374 277 374 224 375 222 375 277 375 220 376 254 376 255 376 220 377 255 377 222 377 278 378 254 378 220 378 217 379 279 379 278 379 220 380 217 380 278 380 279 381 217 381 280 381 215 382 281 382 282 382 215 383 282 383 280 383 217 384 215 384 280 384 250 385 281 385 215 385 215 386 213 386 250 386 283 387 250 387 213 387 211 388 284 388 283 388 213 389 211 389 283 389 285 390 284 390 211 390 211 391 210 391 285 391 286 392 285 392 210 392 210 393 209 393 286 393 287 394 286 394 209 394 209 395 208 395 287 395 288 396 287 396 208 396 208 397 212 397 288 397 289 398 288 398 212 398 214 399 290 399 289 399 212 400 214 400 289 400 291 401 290 401 214 401 214 402 216 402 291 402 292 403 291 403 216 403 216 404 219 404 292 404 293 405 292 405 219 405 221 406 294 406 293 406 219 407 221 407 293 407 295 408 294 408 221 408 223 409 296 409 295 409 221 410 223 410 295 410 269 411 296 411 223 411 276 412 277 412 50 412 50 413 52 413 276 413 275 414 276 414 52 414 52 415 54 415 275 415 274 416 275 416 54 416 54 417 56 417 274 417 274 418 56 418 142 418 274 419 142 419 140 419 274 420 140 420 137 420 274 421 137 421 134 421 132 422 274 422 134 422 259 423 59 423 281 423 261 424 259 424 281 424 263 425 261 425 281 425 281 426 250 426 263 426 60 427 282 427 281 427 59 428 60 428 281 428 280 429 282 429 60 429 62 430 279 430 280 430 60 431 62 431 280 431 278 432 279 432 62 432 62 433 64 433 278 433 141 434 143 434 273 434 139 435 141 435 273 435 138 436 139 436 273 436 136 437 138 437 273 437 135 438 136 438 273 438 273 439 133 439 135 439 143 440 144 440 273 440 272 441 273 441 144 441 144 442 235 442 272 442 271 443 272 443 235 443 236 444 270 444 271 444 235 445 236 445 271 445 267 446 270 446 236 446 237 447 268 447 267 447 236 448 237 448 267 448 269 449 268 449 237 449 238 450 296 450 269 450 237 451 238 451 269 451 295 452 296 452 238 452 239 453 294 453 295 453 238 454 239 454 295 454 293 455 294 455 239 455 240 456 292 456 293 456 239 457 240 457 293 457 291 458 292 458 240 458 240 459 241 459 291 459 290 460 291 460 241 460 241 461 242 461 290 461 289 462 290 462 242 462 242 463 243 463 289 463 288 464 289 464 243 464 243 465 244 465 288 465 287 466 288 466 244 466 246 467 286 467 287 467 244 468 246 468 287 468 285 469 286 469 246 469 246 470 248 470 285 470 285 471 248 471 253 471 284 472 285 472 253 472 253 473 252 473 284 473 284 474 252 474 251 474 283 475 284 475 251 475 283 476 251 476 250 476 64 477 255 477 254 477 64 478 88 478 255 478 64 479 87 479 88 479 63 480 87 480 64 480 63 481 130 481 87 481 63 482 126 482 130 482 47 483 87 483 176 483 87 484 130 484 176 484 47 485 88 485 87 485 47 486 49 486 88 486 49 487 255 487 88 487 49 488 277 488 255 488 32 489 126 489 35 489 32 490 130 490 126 490 47 491 175 491 48 491 47 492 176 492 175 492 30 493 176 493 130 493 35 494 126 494 158 494 61 495 126 495 63 495 64 496 254 496 278 496 49 497 50 497 277 497 2 498 79 498 82 498 79 499 80 499 82 499 91 59 93 59 94 59 91 59 95 59 92 59 91 59 94 59 95 59 33 13 45 13 46 13 33 13 46 13 44 13 33 500 44 500 42 500 33 501 42 501 40 501 33 502 40 502 38 502 33 503 38 503 36 503 34 13 33 13 36 13 33 13 43 13 45 13 33 13 39 13 41 13 33 504 41 504 43 504 37 505 39 505 33 505 86 506 90 506 89 506 85 506 86 506 89 506 85 507 89 507 125 507 89 508 127 508 125 508 10 509 125 509 11 509 11 510 125 510 127 510 11 511 127 511 15 511 192 512 264 512 194 512 86 513 264 513 90 513 86 514 256 514 264 514 194 515 264 515 256 515 194 516 256 516 197 516

+
+
+
+
+ + + + -0.2908648 -0.7711008 0.5663932 4.076245 0.9551711 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054209 -0.6141704 -6.925791 -4.01133e-9 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5_scaled.dae b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5_scaled.dae new file mode 100644 index 0000000..d818cc1 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E3M5_scaled.dae @@ -0,0 +1,153 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:35:20 + 2025-02-20T09:35:20 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.9 0.9 0.9 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -2 -7.45454 5.04167 -2 -8.46762 3.04968 -2 -8.9576 0.87927 -2 -6.00089 1.26557 -2 -5.98181 6.72267 -2 -5.87041 2.08118 -2 -5.49317 2.70207 -2 -4.91993 3.14687 -2 -4.22507 3.35807 -2 -4.1403 7.98967 -2 -3.50089 3.30717 -1.9958 1.04911 2.95447 -2 -2.04357 8.76267 -2 0.17909 8.99567 -2 2.39064 8.67368 -1.866 4.77932 3.43247 -2 4.45473 7.81767 -2 5.0425 4.35527 -2 5.85836 4.74957 -2 6.24414 6.47868 -2 6.75372 4.88217 -2 7.64707 4.74197 -6 7.99883 -0.06942999 -6 7.70889 -2.13763 -6 7.7436 2.00337 -6 6.9606 3.93948 -6 6.89354 -4.06023 -6 5.70319 5.60667 -6 5.60834 -5.70643 -6 4.05705 6.89167 -6 3.94089 -6.96383 -6 2.13437 7.70767 -6 2.00481 -7.74683 -6 -8.9e-4 -0.002329945 -6 0.06617999 7.99767 -6 -0.06794995 -8.00203 -6 -2.00659 7.74168 -6 -2.13615 -7.71213 -6 -3.94267 6.95867 -6 -4.05883 -6.89673 -6 -5.61012 5.70168 -6 -5.70497 -5.61153 -6 -6.89532 4.05557 -6 -6.96238 -3.94413 -6 -7.71067 2.13297 -6 -7.74538 -2.00803 -6 -8.00061 0.06476998 -3.6056 4.59911 -7.73793 -3.6056 5.87471 -6.81972 3.6055 4.59911 -7.73793 3.6055 5.87471 -6.81973 -3.6056 6.97112 -5.69363 3.6055 6.97111 -5.69363 -3.6056 7.8549 -4.39393 3.6055 7.8549 -4.39393 -3.6056 8.499111 -2.96033 3.6055 8.499111 -2.96033 -3.6056 -5.00089 -7.48563 -3.6056 -3.4453 -8.31712 3.6055 -5.00089 -7.48563 3.6055 -3.44496 -8.317231 -3.6056 -1.75737 -8.82922 3.6055 -1.75665 -8.82943 -3.6056 -8.9e-4 -9.00233 3.6055 -8.9e-4 -9.00233 -3.6056 7.49365 4.98087 -1.896 8.009201 4.10117 -1.7068 8.23875 3.61787 -1.3418 8.499111 2.95567 -3.6056 8.499111 2.95567 -3.6056 6.01519 6.69167 -3.6056 4.15704 7.97968 -3.6056 2.03647 8.76367 -3.6056 -0.2125999 8.99567 -3.6056 -2.44848 8.65868 -3.6056 -4.52976 7.77467 -3.6056 -6.32525 6.40067 -3.6056 -7.72158 4.62267 -3.6056 -8.63065 2.55248 -3.6056 -8.99508 0.32108 -3.6056 -8.79186 -1.93072 -2.6748 -8.8748 -1.50352 -2.1809 -8.999731 -0.14673 -3.1522 -8.54995 -2.81543 -3.6056 -8.03383 -4.06093 -1 -3.75089 2.33887 1 -3.75089 2.33887 -3.6056 2.09911 -8.753931 3.6055 2.09911 -8.753931 -1 5.17159 3.12238 1 5.17159 3.12238 0 -5.00089 -0.002329945 -1 -5.00089 0.93118 1 -5.00089 1.10617 1 -5.00089 1.37067 -1 -5.00089 1.37067 1.3748 -5.00089 -0.58433 -1.259 -5.00089 -0.53753 -2.313 -6.00089 -0.50973 -4.1782 -6.9502 -5.63412 -4.3479 -6.49255 -6.10052 -4.5417 -5.78034 -6.70483 -1 -4.74733 2.03607 1 -4.74552 2.03817 1 5.57884 3.51017 -1 5.57893 3.51017 1 6.07904 3.76957 -1 6.07915 3.76968 1 6.63105 3.87917 -1 6.63115 3.87917 1 7.19123 3.83077 -1 7.19131 3.83077 1 7.7159 3.62837 -1 7.71601 3.62827 1 8.16394 3.28727 -1 8.16406 3.28717 1 8.499111 2.83508 -1 8.499111 2.83508 -1.6733 -5.07965 -0.53843 -4.1105 -5.05836 -7.39513 -4.3246 -5.19024 -7.24833 -2.0121 -5.29806 -0.52692 -4.4557 -5.3582 -7.08053 -1.7114 -5.29806 1.17887 -1.7071 -4.79262 2.39278 -1.683 -3.67164 2.64587 -5.1508 0.02666997 -8.57373 -1.5 5.06648 3.20547 -1.7071 5.9246 4.02497 -1.7071 7.138 4.14037 -5.1508 2.04048 -8.32713 5.2548 8.499111 -0.002329945 5.1508 8.499111 -1.10663 5.1508 8.499111 1.10197 4.9778 8.499111 -1.69952 5.072 8.499111 1.41367 4.9659 8.499111 1.72547 4.7295 8.499111 -2.20792 4.8235 8.499111 2.03877 4.6324 8.499111 2.34737 4.4072 8.499111 -2.60963 4.3676 8.499111 2.64117 4.0137 8.499111 -2.87433 4.0094 8.499111 2.87157 3.6055 8.499111 2.95567 0 8.499111 -0.002329945 1.3418 8.499111 2.95567 -4.0125 8.499111 -2.87492 -4.0107 8.499111 2.87097 -4.4032 8.499111 2.60887 -4.4088 8.499111 -2.60823 -4.7267 8.499111 2.20777 -4.7285 8.499111 -2.20963 -4.9766 8.499111 -1.70243 -4.9767 8.499111 1.69757 -5.1508 8.499111 -1.10663 -5.1508 8.499111 1.10197 -5.2548 8.499111 -0.002339959 -5.1508 -1.16784 -8.49393 -5.1508 -2.39342 -8.23302 -5.1508 -3.6977 -7.73553 -5.1508 -5.0325 -6.94153 -5.1508 -6.33935 -5.77232 -5.1508 -7.48297 -4.18423 -5.1508 -8.26608 -2.27303 -5.1508 -8.570611 -0.1733199 -5.1508 -8.34856 1.94337 -5.1508 -7.65831 3.84908 -5.1508 -6.65255 5.40367 -5.1508 -5.48446 6.58567 -5.1508 -4.27482 7.42767 -5.1508 -3.07933 7.99767 -5.1508 -1.92971 8.34967 -5.1508 -0.86492 8.525671 -5.1508 0.07096999 8.56867 -5.1508 5.86632 -6.25092 -5.1508 4.29269 -7.42083 -5.1508 7.13263 -4.75442 -5.1508 8.02585 -3.00912 -5.1508 8.01546 3.03207 -5.1508 7.137 4.74317 -5.1508 5.98916 6.12867 -5.1508 4.73707 7.14067 -5.1508 3.47752 7.83167 -5.1508 2.2525 8.26767 -5.1508 1.10237 8.497671 2 6.26146 6.46167 2 7.64707 4.74197 2 6.75408 4.88217 2 5.85895 4.74967 2 5.04316 4.35577 2 4.49639 7.79367 2 4.38705 3.74247 2 2.45995 8.65467 1.9916 1.03584 2.94627 2 0.27493 8.99368 2 -1.92679 8.78967 2 -3.50089 3.30717 2 -4.01233 8.05467 2 -4.21819 3.35877 2 -4.91452 3.14967 2 -5.48962 2.70607 2 -5.85578 6.83267 2 -5.86839 2.08647 2 -6.00089 1.26557 2 -7.34581 5.19867 2 -8.932371 1.10617 2 -8.39242 3.25067 6 -7.47839 2.84148 6 -7.95962 0.80917 6 -7.89848 -1.27833 6 -7.29913 -3.27893 6 -6.48758 4.67987 6 -6.20241 -5.05613 6 -5.05471 6.19968 6 -4.68308 -6.48903 6 -3.27744 7.29567 6 -2.84466 -7.47983 6 -8.9e-4 -0.002329945 6 -1.27687 7.89568 6 -0.81243 -7.96103 6 0.81066 7.95667 6.00549 1.09911 -7.99241 6 2.84287 7.47567 6 3.27565 -7.30053 6 4.68129 6.48467 6 5.05293 -6.20383 6 6.20063 5.05167 6 6.4858 -4.68453 6 7.29735 3.27417 6 7.47661 -2.84613 6 7.8967 1.27367 6 7.95784 -0.81383 1.6576 8.28299 3.51577 1.8988 8.004381 4.11057 3.6055 7.44183 5.05767 3.6055 5.87572 6.81467 3.6055 3.90805 8.104681 3.6055 1.6729 8.840681 3.6055 -0.67658 8.97267 3.6055 -2.9798 8.490671 3.6055 -5.07941 7.42767 3.6055 -6.83185 5.85767 3.6055 -8.117321 3.88657 3.6055 -8.84796 1.64977 2.2811 -8.999481 -0.1617299 3.6055 -8.973811 -0.70003 2.956 -8.85632 -1.60902 3.6055 -8.48627 -3.00203 2.3485 -6.00089 -0.30623 5.1257 -5.8485 -6.28963 4.9156 -6.47571 -5.81152 4.5299 -7.32036 -4.98423 4.0897 -8.00021 -4.04023 5.1508 0.02666997 -8.57373 5.1508 2.04048 -8.32713 1.683 -3.67164 2.64577 1.683 -5.31788 1.37067 1.7071 -4.79262 2.39278 4.7679 -5.04422 -7.17183 1.8146 -5.12653 -0.37923 4.9433 -5.14915 -6.99723 2.1024 -5.35301 -0.34243 5.1236 -5.46303 -6.62893 1.5 5.06648 3.20547 1.7071 5.92717 4.02597 1.7071 7.14342 4.13947 5.1508 4.8318 7.07667 5.1508 3.91347 7.62267 5.1508 3.046 8.009671 5.1508 5.75663 6.34767 5.1508 6.64504 5.41067 5.1508 7.45116 4.23277 5.1508 8.103731 2.78777 5.1508 8.02586 -3.00913 5.1508 7.13271 -4.75433 5.1508 5.86657 -6.25073 5.1508 4.29269 -7.42083 5.1508 -1.14221 -8.49743 5.1508 -2.17531 -8.293331 5.1508 -3.04778 -8.01392 5.1508 -4.76167 -7.13003 5.1508 -3.88059 -7.64542 5.1508 -6.67612 -5.37923 5.1508 -7.55419 -4.05413 5.1508 -8.22952 -2.40213 5.1508 -8.55833 -0.49193 5.1508 -8.43597 1.52047 5.1508 -7.83186 3.48267 5.1508 -6.79325 5.22567 5.1508 -5.4664 6.60067 5.1508 -4.02045 7.56867 5.1508 -2.57937 8.17168 5.1508 -1.22172 8.48167 5.1508 0.03364998 8.56867 5.1508 1.17758 8.48767 5.1508 2.18956 8.28468 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 -1.04792e-6 0 1 3.78125e-7 0 0.9999996 -9.32949e-4 -1.274e-4 0.9999998 -2.22825e-4 6.04472e-4 0.9999998 -7.17866e-5 6.84903e-4 0.9999998 1.03385e-4 7.10133e-4 0.9993116 -0.03594756 0.009165942 0.9994181 0.01306617 0.03150671 0.9513854 0.3036588 0.05154842 -1 -3.37927e-6 0 -1 0 0 -1 -6.6466e-7 0 -1 1.0234e-6 0 -1 -2.38415e-7 0 -1 -4.60574e-7 0 -1 -4.60589e-7 0 0 0.5842118 -0.8116012 -1.00974e-6 0.5842072 -0.8116046 -9.25605e-7 0.716486 -0.6976015 9.25605e-7 0.7164922 -0.6975952 1.17802e-6 0.8269312 -0.562303 0 0.8269282 -0.5623077 0 0.9121384 -0.4098826 0 0.9121379 -0.4098837 0 -0.471401 -0.881919 8.69568e-6 -0.4713695 -0.8819359 -1.04967e-6 -0.2903223 -0.9569289 1.19935e-6 -0.2903138 -0.9569315 -1.91821e-5 -0.09807986 -0.9951786 0 -0.09800195 -0.9951863 -0.01023852 0.8712639 0.4907082 -0.06521272 0.9110214 0.4071699 -0.1723484 0.9453746 0.2767001 0 0.8956867 0.4446858 0.01916551 0.7777537 0.6282771 -0.02114665 0.7564457 0.6537145 0.02077513 0.5989921 0.8004854 -0.02269053 0.5695413 0.8216495 0.02217495 0.3829846 0.9234886 -0.02391427 0.3466683 0.937683 0.02367544 0.1440353 0.9892894 -0.02502423 0.1025769 0.9944103 0.02542644 -0.1042243 0.9942288 -0.02644908 -0.1489835 0.988486 0.02645659 -0.3457894 0.9379392 -0.02841073 -0.390783 0.9200444 0.02716231 -0.5666119 0.823537 -0.02925962 -0.6074627 0.7938091 0.02872163 -0.751855 0.6587027 -0.03036302 -0.7860998 0.6173534 0.02993494 -0.890949 0.4531158 -0.0315212 -0.9151554 0.4018671 0.03083848 -0.9749881 0.2201077 -0.03297954 -0.9863877 0.1610957 -0.0560109 -0.9958804 -0.07130944 0.02851182 -0.9678199 -0.2500237 -0.1497955 -0.9314979 -0.3314707 0 -1 0 0 -1 2.78772e-7 0 -1 -1.41382e-7 0.9397108 -4.91534e-5 -0.3419702 0.9396798 3.92141e-5 -0.3420558 0.939689 -1.19549e-5 -0.3420303 0.9396945 -1.068e-4 -0.3420149 0.9401113 -0.03212493 -0.3393509 0.9396769 -1.24729e-5 -0.3420634 0 -0.9344531 0.3560866 4.69874e-4 -0.933982 0.35732 -7.41456e-4 -0.2907539 0.9567976 0 -0.2893877 0.957212 0 -0.689593 0.7241972 -3.11582e-5 -0.6895117 0.7242745 -2.07335e-5 -0.4603686 0.8877279 2.36926e-5 -0.4605088 0.8876552 4.3635e-5 -0.194746 0.9808538 -9.74427e-6 -0.1945608 0.9808905 4.2403e-6 0.08607983 0.9962882 3.81642e-6 0.08608305 0.996288 1.44148e-5 0.3599148 0.9329852 -2.69186e-5 0.3600512 0.9329326 -6.56268e-6 0.6057468 0.7956575 -3.59884e-6 0.6057386 0.7956638 1.86376e-5 0.8033742 0.5954745 0 0.8034135 0.5954216 0.9845576 0.0226792 -0.1735857 0.9844095 0.02224338 -0.17448 0.1057979 -0.9935548 -0.04069095 0.1865204 -0.9804295 -0.06299328 0.43702 -0.8854503 -0.158087 0.5268017 -0.8274311 -0.1945193 0.6406034 -0.7319418 -0.232139 0.8343831 -0.4514373 -0.3162423 0.8680408 -0.3794611 -0.3201787 0.385448 -0.9227296 0 0.9329911 -0.3075781 0.1868781 0.960798 -0.2737683 0.04379695 0.921267 -0.3601977 0.1467135 0.2823632 -0.8964275 0.3415974 0.2449762 -0.8953508 0.3719324 0.4481411 -0.259923 0.8553419 0.9171022 -0.244388 0.3149574 0.3801868 -0.2114647 0.9004115 0.9359216 -0.1024257 0.3369864 0.9331337 -0.09815102 0.3458728 0.9043348 0.02992635 0.4257735 0.256438 -0.6664558 0.7000545 0.9491888 -0.2381355 0.2057479 0.6900653 -0.4057804 0.5992931 0.2166473 -0.6463911 0.7316027 0.388118 -0.424409 0.8180718 0.9186827 -0.1718788 0.3556401 0.9376432 -0.05092275 0.3438491 0.9276596 -0.03535503 0.3717498 0.3687151 -0.1808524 0.9117795 0.2872363 -0.09068757 0.9535571 0.3948183 0.07908958 0.9153488 0.9169796 0.06185048 0.3941105 0.937282 0.2155543 0.2739322 0.8728134 0.2090926 0.4409958 0.356307 0.3364207 0.8717033 0.290687 0.4102365 0.8644114 0.316319 0.8104812 0.4930139 0.399887 0.555199 0.7292767 0.205583 0.7862517 0.5827041 0.185663 -0.9752687 -0.1199173 0.365459 -0.9285938 -0.0644471 0.5371193 -0.8381752 -0.0946843 0.9060928 -0.3917691 -0.1597279 0.9060681 -0.3918182 -0.159747 0 1 0 0 1 3.75947e-7 0 1 -5.56746e-7 0 1 -1.41823e-7 0 1 -1.7292e-7 0 1 1.03882e-6 0 1 -1.44621e-7 0 1 5.61489e-7 0 1 -1.78838e-7 0 1 0 0 1 0 0 1 0 0 1 0 -0.601754 -0.1108676 -0.7909492 -0.5525991 -0.1735407 -0.8151797 -0.5629219 -0.2945553 -0.7722411 -0.5965633 -0.3133499 -0.7388668 -0.53395 -0.4322572 -0.7266713 -0.5985505 -0.4929815 -0.6314322 -0.5385817 -0.5618031 -0.6279388 -0.5791653 -0.6508806 -0.4908382 -0.5524053 -0.6764356 -0.4871174 -0.5591673 -0.7671522 -0.3143397 -0.5653725 -0.7646697 -0.3092482 -0.5459342 -0.8291529 -0.120256 -0.5737112 -0.8129183 -0.100097 -0.5380399 -0.8383191 0.08794385 -0.5804876 -0.8063838 0.1130469 -0.5331774 -0.795435 0.2881063 -0.5907874 -0.7427918 0.315009 -0.5283427 -0.712853 0.4611883 -0.6008213 -0.6300866 0.4919399 -0.5308853 -0.6027697 0.5956757 -0.6100087 -0.4526932 0.6503524 -0.5603032 -0.4985964 0.6614091 -0.5548086 -0.3580636 0.7509847 -0.6015741 -0.2994999 0.7405461 -0.5497242 -0.2445655 0.7987435 -0.5688204 -0.1341258 0.8114516 -0.6522727 -0.03478848 0.7571858 -0.554682 -0.1019862 0.8257887 -0.252253 0.6933152 -0.6750426 -0.2985666 0.7285574 -0.6164917 -0.2474089 0.8012231 -0.5448216 -0.2959363 0.8503177 -0.43518 -0.2574454 0.8813923 -0.3960675 -0.1626391 0.6108974 -0.7748245 -0.2988357 0.8446897 -0.4440684 -0.386523 0.8686148 -0.3100137 -0.4883527 0.8393138 -0.2388812 -0.6366787 0.7483233 -0.1861522 -0.1591508 0.6287071 0.7611824 -0.2961768 0.8459084 0.4435293 -0.3857697 0.8685486 0.3111354 -0.4896394 0.8382655 0.2399253 -0.63937 0.7458395 0.1868943 -0.2478828 0.8618472 0.442463 -0.2652833 0.8635945 0.4287533 -0.2659444 0.7423307 0.6149949 -0.2434325 0.7338541 0.6341915 -0.2820258 0.6030824 0.7461589 -0.2263724 0.554899 0.8005265 -0.2833836 0.461265 0.8407903 -0.2312546 0.3262191 0.916571 -0.2449038 0.3362074 0.9093881 -0.2761721 0.1884688 0.9424482 -0.2085644 0.06716495 0.9756997 -0.2480476 0.09940224 0.9636346 -0.2736157 -0.04414522 0.9608255 -0.2253041 -0.1588857 0.9612458 -0.2405104 -0.1446608 0.9598063 -0.2780901 -0.2812231 0.9184659 -0.2059204 -0.4211524 0.8833048 -0.2617406 -0.3773119 0.8883286 -0.2683511 -0.550344 0.7906385 -0.2293215 -0.5915274 0.7729858 -0.2898691 -0.6807422 0.6727303 -0.2259318 -0.7661265 0.6016687 -0.2928903 -0.8027874 0.5193725 -0.2322524 -0.8905737 0.391072 -0.292511 -0.8991028 0.3256559 -0.2367796 -0.9588597 0.1565998 -0.2931186 -0.9508585 0.09974896 -0.2378081 -0.9673807 -0.08730423 -0.2916856 -0.9466103 -0.1372905 -0.2391577 -0.9147881 -0.3255249 -0.2870175 -0.8864008 -0.3632007 -0.4493516 -0.8037068 -0.3900495 -0.235819 -0.7886008 -0.5678895 -0.3742555 -0.7263267 -0.5765262 -0.4066606 -0.5597435 -0.722021 -0.5477876 -0.6229245 -0.5584747 -0.3964717 -0.6121266 -0.6841865 -0.3843075 -0.4848958 -0.7856106 -0.1295544 -0.3327332 -0.9340794 -0.3045747 -0.4437152 -0.8428233 -0.3846812 -0.4718955 -0.7933064 -0.2470385 -0.45679 -0.8545847 -0.2815837 -0.3419637 -0.8965331 -0.2422758 -0.2816728 -0.9284195 -0.2800059 -0.1998916 -0.938957 -0.2351534 -0.06478756 -0.9697967 -0.5573003 0.05702191 0.8283508 -0.6325193 0.1518843 0.7595068 -0.5579735 0.1152348 0.821819 -0.5554161 0.2788331 0.7834317 -0.6011952 0.3121923 0.7355954 -0.5403859 0.4047064 0.7376963 -0.5903539 0.5073707 0.6277399 -0.5689051 0.5060515 0.6482738 -0.5458583 0.6452172 0.5345404 -0.5926139 0.6430879 0.4850224 -0.5251159 0.7570869 0.388681 -0.6004876 0.7413067 0.2997984 -0.5176268 0.8299463 0.2079702 -0.6277665 0.7761533 0.05912083 -0.5607845 0.8217557 0.1011855 -0.5533859 0.8312931 -0.05211716 -0.6015238 0.7911188 -0.1109066 -0.5207241 0.8284763 -0.2060907 -0.5970686 0.738523 -0.313198 -0.5288125 0.7555397 -0.3866744 -0.5869536 0.6381687 -0.4982231 -0.5426716 0.6411941 -0.542566 -0.5711509 0.4897398 -0.6587425 -0.5618041 0.4980878 -0.6605187 -0.5445461 0.3144609 -0.7775501 -0.999997 0.002292871 8.99511e-4 -0.999999 2.19799e-4 0.001416683 -0.9999991 -1.27299e-4 0.001372992 -0.9999982 -0.001810193 5.1974e-4 -1 -2.95543e-7 0 -1 3.93974e-7 0 -1 -7.99639e-7 0 1 -7.50123e-7 0 1 5.30415e-7 0 1 -6.64623e-7 0 1 5.70747e-7 0 1 1.6859e-7 0 1 -4.60589e-7 0 0.9999959 -0.002866685 2.92358e-4 0.9999971 0.002207458 9.90953e-4 1 -5.3041e-7 0 1 7.50113e-7 0 1 -3.37936e-6 0 0 0.9329561 0.3599902 0.01930975 0.9083937 0.41767 0.07329028 0.8729568 0.4822602 0.02583616 0.8930586 0.4491978 -0.02382081 0.7784674 0.627233 0.03303664 0.7460874 0.665028 -0.03076195 0.6020851 0.7978392 0.03888517 0.5478633 0.8356638 -0.03569632 0.3891729 0.9204729 0.04323744 0.3124719 0.9489425 -0.03929835 0.1531992 0.9874137 0.04625892 0.05602961 0.9973569 -0.04161548 -0.09218424 0.994872 0.04788458 -0.2045997 0.9776738 -0.04232275 -0.332091 0.9422975 0.0481522 -0.4511698 0.8911382 -0.04168057 -0.5520372 0.8327771 0.04659372 -0.6665487 0.744004 -0.03999751 -0.7383179 0.6732659 0.04387927 -0.8368097 0.5457327 -0.03649181 -0.880321 0.4729731 0.03986585 -0.9498177 0.3102533 -0.03166961 -0.9692477 0.2440413 0.0321601 -0.997684 0.05993694 0.0410574 -0.9977269 0.05343592 -0.02552652 -0.9935834 -0.110184 0.1122891 -0.9721128 -0.2058833 -0.9063037 5.17793e-6 -0.4226269 -0.8696209 -0.08007216 -0.4871839 -0.8999612 -0.02187561 -0.4354209 -0.9042878 -0.01076936 -0.4267877 -0.9056435 -0.006502211 -0.4239901 -0.9070469 -8.81658e-4 -0.4210288 -0.9762231 0.01176947 -0.2164484 -0.9761009 0.01148211 -0.2170143 -0.9007829 -0.428721 0.06919902 -0.2346664 -0.9079015 0.347342 -0.3801073 -0.8189959 0.429842 -0.9360151 -0.3002938 0.1835741 -0.9330742 -0.3104956 0.1815631 -0.4467245 -0.258907 0.8563904 -0.9170913 -0.2434972 0.3156784 -0.933097 -0.1034283 0.3444311 -0.9600365 0.02008122 0.2791535 -0.8825019 -0.1215114 0.4543405 -0.3800885 -0.2113952 0.9004692 -0.4209831 -0.9070684 0 -0.9001836 -0.3870835 -0.1995894 -0.03426259 -0.9993515 -0.01107466 -0.2253844 -0.9680716 -0.109724 -0.3729253 -0.9115552 -0.1731874 -0.5741918 -0.7733342 -0.2688087 -0.6379976 -0.7116389 -0.2941585 -0.8445578 -0.3563785 -0.3996458 -0.8481017 -0.3446416 -0.4024247 -0.8635532 -0.3443432 0.3683797 -0.1852998 -0.6776499 0.7116563 -0.2546544 -0.6344542 0.7298076 -0.9072185 -0.1546421 0.3912041 -0.3878393 -0.4243337 0.818243 -0.9187127 -0.1717185 0.3556399 -0.9273515 -0.05479204 0.3701584 -0.9355234 -0.03282392 0.3517367 -0.2148243 -0.1901987 0.9579536 -0.3560307 -0.08682781 0.9304317 -0.3943547 0.0791037 0.9155474 -0.9169955 0.06186914 0.3940706 -0.9369159 0.2177897 0.273416 -0.8684508 0.2084672 0.4498163 -0.1489433 0.355899 0.9225789 -0.3337913 0.4413741 0.83293 -0.3602137 0.5650829 0.7422448 -0.3176777 0.8106253 0.4919021 -0.2056007 0.7862105 0.5827533 -0.2502555 -0.9665887 -0.05548429 -0.5784512 -0.7759484 -0.2515917 -0.3947369 -0.9154888 -0.07786577 -0.9088773 -0.3572642 -0.2151848 0.5678089 0.4206772 0.7075477 0.650047 0.3095964 0.6939662 0.5549093 0.3947429 0.7322936 0.5492154 0.5173314 0.6563009 0.6007612 0.5485153 0.5815643 0.5569796 0.6026896 0.5714359 0.6184481 0.6484994 0.4438137 0.5550987 0.7078845 0.4367666 0.5328408 0.7712183 0.348286 0.5975568 0.768095 0.2301217 0.5417206 0.8183526 0.191932 0.6280129 0.7759523 0.05914384 0.5751971 0.8176642 0.02394902 0.5493958 0.8339588 -0.0517401 0.5588986 0.8047131 -0.2001731 0.5732886 0.7973058 -0.1887956 0.5527049 0.741868 -0.3796698 0.5787001 0.7179126 -0.3869209 0.5358387 0.6445524 -0.5453707 0.5921979 0.5862116 -0.5528631 0.5244586 0.507992 -0.6832915 0.5997346 0.4202129 -0.6809843 0.6123183 0.2951456 -0.7334545 0.4465976 0.2720761 -0.8523645 0.641507 0.09324043 -0.7614297 0.3489122 -0.01638394 -0.9370122 0.5482801 -0.05447381 -0.8345189 0.6184605 -0.1523022 -0.7709156 0.5757296 -0.1883949 -0.7956399 0.5577152 -0.2531548 -0.790485 0.5725113 -0.4139771 -0.7077103 0.6533015 -0.306349 -0.6923492 0.5549641 -0.3946641 -0.7322945 0.5444505 -0.5209308 -0.657423 0.5993084 -0.549245 -0.5823739 0.5550993 -0.6078014 -0.5678401 0.6023552 -0.665399 -0.4409223 0.5592028 -0.7055088 -0.435373 0.5290488 -0.7854925 -0.3211059 0.6016405 -0.7651672 -0.2292331 0.5199304 -0.8418281 -0.1449069 0.5997847 -0.7998185 -0.02342545 0.5212197 -0.8518494 0.05179518 0.5942429 -0.7826437 0.185322 0.5269285 -0.8122844 0.2500811 0.5867733 -0.7128157 0.3841757 0.5379877 -0.7241406 0.431497 0.5604676 -0.5959509 0.5750814 0.5750018 -0.595297 0.5612437 0.5520504 -0.4638524 0.6928791 0.5911297 -0.4233646 0.6865335 0.5356367 -0.3259662 0.778999 0.6009898 -0.2296084 0.765566 0.5498406 -0.1859306 0.8143127 0.6161139 -0.05445581 0.7857724 0.5667286 -0.02406114 0.8235533 0.5474858 0.05910521 0.8347252 0.6163845 0.154867 0.7720664 0.5778371 0.1879794 0.7942091 0.5576751 0.2537752 0.7903142 0.2861521 0.5716817 -0.7689586 0.2522119 0.6933292 -0.6750435 0.298528 0.7285873 -0.6164752 0.2473823 0.8012257 -0.5448298 0.2959051 0.8503297 -0.4351778 0.2574218 0.8813982 -0.3960701 0.1630223 0.6121059 -0.7737894 0.2988436 0.8445882 -0.4442559 0.3863431 0.8687106 -0.3099696 0.4887143 0.8391591 -0.2386845 0.6374323 0.7477201 -0.1859967 0.2486959 -0.1967171 -0.9483949 0.446396 -0.4946257 -0.7457051 0.5148605 -0.5114942 -0.6879625 0.9432953 -0.2164215 -0.2517058 0.2268477 -0.4917506 -0.8406673 0.2659798 -0.45439 -0.8501674 0.2727456 -0.3892949 -0.8798064 0.2404903 -0.296042 -0.9244045 0.2538471 -0.2808046 -0.9255865 0.2766049 -0.1862525 -0.9427618 0.2450701 -0.09501343 -0.9648384 0.31691 0.8104445 0.4926943 0.3734084 0.8644642 0.3365528 0.4308483 0.8620831 0.2668005 0.4963691 0.8382834 0.2256076 0.5749122 0.7944833 0.1956332 0.67028 0.7225034 0.169451 0.1904931 0.3560196 0.9148565 0.2677555 0.8780957 0.396554 0.2282822 0.869768 0.4374823 0.284268 0.7912001 0.541474 0.2551243 0.7016581 0.6652725 0.2268386 0.7270355 0.6480461 0.2741268 0.5953397 0.7552649 0.2573488 0.4938387 0.8305991 0.2228473 0.534491 0.8152659 0.2726877 0.3919801 0.8786314 0.2336969 0.297266 0.9257531 0.2268069 0.3046138 0.9250779 0.2758794 0.1890376 0.94242 0.2225949 0.0688591 0.9724762 0.2389334 0.05446511 0.9695073 0.2808147 -0.06635433 0.9574655 0.2506625 -0.2154929 0.9437856 0.2322154 -0.1992354 0.9520407 0.2789261 -0.3706914 0.8858827 0.2224162 -0.4403794 0.8698259 0.2920828 -0.5320451 0.7947427 0.2255327 -0.6500817 0.7256231 0.2890774 -0.6888715 0.6647484 0.2373512 -0.8136805 0.530649 0.2807238 -0.8245087 0.4913039 0.2486879 -0.9207099 0.3007453 0.2691174 -0.9204711 0.2833881 0.251814 -0.9659917 0.05873525 0.2612973 -0.963877 0.05162334 0.2765873 -0.9470608 -0.16302 0.2361084 -0.9506401 -0.2013362 0.2693288 -0.9143217 -0.3024532 0.3585809 -0.8640867 -0.3532337 0.3434444 -0.8307222 -0.438117 0.4851975 -0.7148171 -0.503607 0.2916965 -0.7973418 -0.5283553 0.5334392 -0.6185033 -0.5769717 0.2634819 0.1172516 -0.9575121 0.268501 0.1131531 -0.9566105 0 0.1174667 -0.9930769 0 0.1174667 -0.9930769 -0.2685171 0.1131527 -0.956606 -0.2634977 0.1172512 -0.9575078 -0.2559575 0.3639546 -0.8955573 -0.261031 0.3603702 -0.8955423 0 0.3764965 -0.9264181 0 0.3764964 -0.9264182 0.2608049 0.3634666 -0.8943562 0.25561 0.3609113 -0.8968872 -0.5633226 0.1009646 -0.8200451 -0.5642199 0.1003516 -0.8195032 -0.2890417 0.5592756 -0.7769593 -0.2723093 0.5740822 -0.77219 -0.5472813 0.3124441 -0.7764419 -0.5533328 -0.05552214 -0.8311078 -0.2676519 -0.09450155 -0.9588702 0.2677806 -0.06275826 -0.9614338 0.2717589 0.562221 -0.7810599 0.009652137 -0.9991798 0.03932791 -0.03274673 -0.9954183 -0.08983439 -1 0 0 -1 0 0 -1 0 0 -1 2.30298e-7 0 -1 -3.45495e-7 0 -1 0 0 -1 -3.4545e-7 0 -1 4.60585e-7 0 0 -0.08747637 0.9961666 0.4009065 -0.0801388 0.9126073 0.1771755 -0.06659412 0.9819237 0.9044916 0.03213119 0.4252796 0.01521629 -0.06422019 0.9978197 0.5908551 -0.1227393 0.7973866 -0.8047037 -0.1353192 0.5780491 -0.1808972 -0.08603322 0.9797319 -0.4024766 -0.06690788 0.9129819 0.002514302 -0.06386899 0.9979552 -0.9045174 0.03215199 0.4252229 + + + + + + + + + + + + + + +

3 0 0 0 1 0 2 1 3 1 1 1 4 2 0 2 3 2 3 0 5 0 4 0 4 3 5 3 6 3 4 4 6 4 7 4 4 0 7 0 8 0 9 0 4 0 8 0 8 0 10 0 9 0 9 5 10 5 11 5 12 6 9 6 11 6 13 7 12 7 11 7 14 8 13 8 11 8 14 9 11 9 15 9 16 10 14 10 15 10 15 11 17 11 16 11 16 0 17 0 18 0 19 0 16 0 18 0 18 0 20 0 19 0 21 0 19 0 20 0 22 12 23 12 24 12 25 13 24 13 23 13 23 13 26 13 25 13 27 13 25 13 26 13 26 13 28 13 27 13 29 13 27 13 28 13 28 14 30 14 29 14 31 13 29 13 30 13 30 15 32 15 31 15 31 16 32 16 33 16 34 17 31 17 33 17 32 13 35 13 33 13 35 18 37 18 33 18 47 19 48 19 49 19 50 20 49 20 48 20 48 21 51 21 50 21 52 22 50 22 51 22 51 23 53 23 52 23 54 24 52 24 53 24 53 25 55 25 54 25 56 26 54 26 55 26 57 27 58 27 59 27 60 28 59 28 58 28 58 29 61 29 60 29 62 30 60 30 61 30 61 31 63 31 62 31 64 32 62 32 63 32 65 33 21 33 66 33 65 34 66 34 67 34 65 35 67 35 68 35 69 36 65 36 68 36 19 37 21 37 65 37 65 38 70 38 19 38 16 39 19 39 70 39 70 40 71 40 16 40 14 41 16 41 71 41 71 42 72 42 14 42 13 43 14 43 72 43 72 44 73 44 13 44 12 45 13 45 73 45 73 46 74 46 12 46 9 47 12 47 74 47 74 48 75 48 9 48 4 49 9 49 75 49 75 50 76 50 4 50 0 51 4 51 76 51 77 52 0 52 76 52 1 53 0 53 77 53 77 54 78 54 1 54 2 55 1 55 78 55 78 56 79 56 2 56 80 57 81 57 82 57 83 58 81 58 80 58 80 59 84 59 83 59 96 60 93 60 91 60 91 61 92 61 97 61 59 60 96 60 91 60 57 62 59 62 91 62 97 60 57 60 91 60 98 63 81 63 83 63 98 64 83 64 84 64 98 65 84 65 99 65 98 66 99 66 100 66 101 67 98 67 100 67 82 68 81 68 98 68 102 69 95 69 94 69 94 70 103 70 102 70 85 71 102 71 103 71 103 72 86 72 85 72 90 73 104 73 89 73 105 74 89 74 104 74 104 75 106 75 105 75 107 76 105 76 106 76 106 77 108 77 107 77 109 78 107 78 108 78 108 79 110 79 109 79 111 80 109 80 110 80 110 81 112 81 111 81 113 82 111 82 112 82 112 83 114 83 113 83 115 84 113 84 114 84 114 85 116 85 115 85 117 86 115 86 116 86 2 87 98 87 3 87 2 88 82 88 98 88 118 89 119 89 57 89 97 90 118 90 57 90 120 91 119 91 118 91 118 92 121 92 120 92 122 93 120 93 121 93 98 94 101 94 122 94 121 95 98 95 122 95 95 96 123 96 92 96 124 97 6 97 5 97 124 98 5 98 3 98 124 99 3 99 123 99 123 100 95 100 102 100 124 101 123 101 102 101 102 102 85 102 124 102 7 103 6 103 124 103 124 104 85 104 125 104 125 105 8 105 7 105 124 106 125 106 7 106 10 107 8 107 125 107 89 108 105 108 127 108 128 109 17 109 15 109 127 110 128 110 15 110 128 111 127 111 105 111 105 112 107 112 128 112 18 113 17 113 128 113 129 114 20 114 18 114 128 115 129 115 18 115 128 116 107 116 109 116 129 117 128 117 109 117 109 118 111 118 129 118 21 119 20 119 129 119 66 120 21 120 129 120 67 121 66 121 129 121 129 122 111 122 113 122 67 123 129 123 113 123 115 124 68 124 67 124 113 125 115 125 67 125 115 126 117 126 68 126 123 127 118 127 97 127 123 128 97 128 92 128 121 129 118 129 123 129 123 130 3 130 121 130 98 131 121 131 3 131 133 132 131 132 132 132 134 132 135 132 133 132 132 132 134 132 133 132 136 132 135 132 134 132 137 133 138 133 136 133 134 134 137 134 136 134 139 135 138 135 137 135 137 132 140 132 139 132 141 136 139 136 140 136 140 132 142 132 141 132 143 132 141 132 142 132 142 132 56 132 143 132 144 132 143 132 56 132 117 132 116 132 145 132 55 137 68 137 117 137 55 138 117 138 145 138 145 139 116 139 146 139 145 132 146 132 144 132 145 132 144 132 56 132 56 140 55 140 145 140 69 132 68 132 55 132 147 132 148 132 69 132 55 132 147 132 69 132 149 141 148 141 147 141 147 142 150 142 149 142 151 143 149 143 150 143 150 144 152 144 151 144 151 132 152 132 153 132 154 132 151 132 153 132 153 132 155 132 154 132 156 132 154 132 155 132 155 132 157 132 156 132 37 145 35 145 158 145 158 146 159 146 37 146 37 147 159 147 160 147 39 148 37 148 160 148 160 149 161 149 39 149 41 150 39 150 161 150 161 151 162 151 41 151 43 152 41 152 162 152 162 153 163 153 43 153 43 154 163 154 164 154 45 155 43 155 164 155 164 156 165 156 45 156 46 157 45 157 165 157 165 158 166 158 46 158 44 159 46 159 166 159 166 160 167 160 44 160 42 161 44 161 167 161 167 162 168 162 42 162 40 163 42 163 168 163 168 164 169 164 40 164 40 165 169 165 170 165 38 166 40 166 170 166 170 167 171 167 38 167 36 168 38 168 171 168 171 169 172 169 36 169 36 170 172 170 173 170 36 171 173 171 174 171 34 172 36 172 174 172 51 173 48 173 175 173 175 174 177 174 51 174 53 175 51 175 177 175 177 176 178 176 53 176 55 177 53 177 178 177 147 178 55 178 178 178 150 179 147 179 178 179 152 180 150 180 178 180 153 181 152 181 178 181 178 182 155 182 153 182 179 183 69 183 148 183 179 184 148 184 149 184 179 185 149 185 151 185 179 186 151 186 154 186 156 187 179 187 154 187 69 188 179 188 180 188 65 189 69 189 180 189 180 190 181 190 65 190 70 191 65 191 181 191 181 192 182 192 70 192 71 193 70 193 182 193 182 194 183 194 71 194 71 195 183 195 184 195 72 196 71 196 184 196 184 197 185 197 72 197 72 198 185 198 174 198 73 199 72 199 174 199 174 200 173 200 73 200 73 201 173 201 172 201 74 202 73 202 172 202 172 203 171 203 74 203 74 204 171 204 170 204 75 205 74 205 170 205 170 206 169 206 75 206 76 207 75 207 169 207 169 208 168 208 76 208 77 209 76 209 168 209 168 210 167 210 77 210 78 211 77 211 167 211 167 212 166 212 78 212 79 213 78 213 166 213 166 214 165 214 79 214 80 215 79 215 165 215 165 216 164 216 80 216 84 217 80 217 164 217 164 218 163 218 84 218 162 219 99 219 84 219 163 220 162 220 84 220 100 221 99 221 162 221 161 222 122 222 101 222 161 223 101 223 100 223 162 224 161 224 100 224 120 225 122 225 161 225 160 226 57 226 119 226 160 227 119 227 120 227 161 228 160 228 120 228 58 229 57 229 160 229 160 230 159 230 58 230 61 231 58 231 159 231 159 232 158 232 61 232 61 233 158 233 126 233 185 234 34 234 174 234 34 235 185 235 184 235 31 236 34 236 184 236 184 237 183 237 31 237 29 238 31 238 183 238 183 239 182 239 29 239 29 240 182 240 181 240 27 241 29 241 181 241 181 242 180 242 27 242 25 243 27 243 180 243 180 244 179 244 25 244 24 245 25 245 179 245 179 246 156 246 24 246 24 247 156 247 157 247 22 248 24 248 157 248 22 249 157 249 155 249 23 250 22 250 155 250 155 251 178 251 23 251 26 252 23 252 178 252 178 253 177 253 26 253 28 254 26 254 177 254 177 255 175 255 28 255 28 256 175 256 176 256 30 257 28 257 176 257 32 258 30 258 130 258 186 13 187 13 188 13 188 13 189 13 186 13 186 13 189 13 190 13 191 13 186 13 190 13 190 13 192 13 191 13 193 13 191 13 192 13 192 259 194 259 193 259 195 260 193 260 194 260 196 261 195 261 194 261 194 262 197 262 196 262 198 13 196 13 197 13 197 13 199 13 198 13 198 263 199 263 200 263 198 264 200 264 201 264 202 13 198 13 201 13 201 13 203 13 202 13 202 13 203 13 204 13 205 13 202 13 204 13 206 265 207 265 205 265 204 13 206 13 205 13 208 0 209 0 210 0 210 0 211 0 208 0 212 0 208 0 211 0 211 266 213 266 212 266 214 267 212 267 213 267 213 0 215 0 214 0 216 268 214 268 215 268 215 269 217 269 216 269 216 270 217 270 218 270 219 0 216 0 218 0 217 271 220 271 218 271 221 0 219 0 218 0 220 272 222 272 218 272 223 0 221 0 218 0 224 0 223 0 218 0 222 273 224 273 218 273 225 0 223 0 224 0 224 0 226 0 225 0 227 0 225 0 226 0 226 274 228 274 227 274 229 275 227 275 228 275 228 0 230 0 229 0 231 0 229 0 230 0 230 276 232 276 231 276 146 277 233 277 144 277 144 278 233 278 234 278 144 279 234 279 187 279 235 280 144 280 187 280 187 281 186 281 235 281 236 282 235 282 186 282 186 283 191 283 236 283 237 284 236 284 191 284 191 285 193 285 237 285 238 286 237 286 193 286 193 287 195 287 238 287 239 288 238 288 195 288 195 289 196 289 239 289 240 290 239 290 196 290 196 291 198 291 240 291 241 292 240 292 198 292 198 293 202 293 241 293 242 294 241 294 202 294 202 295 205 295 242 295 243 296 242 296 205 296 205 297 207 297 243 297 244 298 243 298 207 298 207 299 206 299 244 299 244 300 206 300 245 300 246 301 244 301 245 301 245 302 247 302 246 302 248 303 246 303 247 303 247 304 245 304 249 304 250 305 251 305 252 305 250 306 252 306 253 306 250 307 253 307 248 307 250 308 248 308 247 308 249 309 250 309 247 309 206 310 204 310 249 310 245 311 206 311 249 311 204 312 203 312 257 312 258 313 103 313 94 313 258 314 94 314 257 314 257 315 203 315 201 315 258 316 257 316 201 316 86 317 103 317 258 317 201 318 200 318 258 318 258 319 200 319 199 319 258 320 199 320 197 320 258 321 197 321 256 321 258 322 256 322 86 322 93 323 257 323 94 323 257 324 249 324 204 324 59 325 259 325 96 325 260 326 96 326 259 326 259 327 261 327 260 327 262 328 260 328 261 328 261 329 263 329 262 329 262 330 263 330 250 330 249 331 262 331 250 331 190 332 264 332 192 332 265 333 104 333 90 333 265 334 90 334 264 334 265 335 264 335 190 335 106 336 104 336 265 336 190 337 189 337 265 337 265 338 189 338 188 338 266 339 265 339 188 339 266 340 108 340 106 340 265 341 266 341 106 341 110 342 108 342 266 342 188 343 187 343 266 343 266 344 187 344 234 344 233 345 266 345 234 345 233 346 112 346 110 346 266 347 233 347 110 347 114 348 112 348 233 348 233 349 146 349 114 349 116 350 114 350 146 350 93 351 96 351 260 351 262 352 93 352 260 352 262 353 257 353 93 353 262 354 249 354 257 354 225 355 267 355 268 355 225 356 268 356 269 356 225 357 269 357 223 357 270 358 267 358 225 358 225 359 227 359 270 359 271 360 270 360 227 360 229 361 272 361 271 361 227 362 229 362 271 362 273 363 272 363 229 363 229 364 231 364 273 364 133 365 273 365 231 365 232 366 131 366 133 366 231 367 232 367 133 367 132 368 131 368 232 368 230 369 274 369 132 369 232 370 230 370 132 370 275 371 274 371 230 371 230 372 228 372 275 372 276 373 275 373 228 373 228 374 226 374 276 374 277 375 276 375 226 375 226 376 224 376 277 376 222 377 255 377 277 377 224 378 222 378 277 378 220 379 254 379 255 379 220 380 255 380 222 380 278 381 254 381 220 381 217 382 279 382 278 382 220 383 217 383 278 383 279 384 217 384 280 384 215 385 281 385 282 385 215 386 282 386 280 386 217 387 215 387 280 387 250 388 281 388 215 388 215 389 213 389 250 389 283 390 250 390 213 390 211 391 284 391 283 391 213 392 211 392 283 392 285 393 284 393 211 393 211 394 210 394 285 394 286 395 285 395 210 395 210 396 209 396 286 396 287 397 286 397 209 397 209 398 208 398 287 398 288 399 287 399 208 399 208 400 212 400 288 400 289 401 288 401 212 401 214 402 290 402 289 402 212 403 214 403 289 403 291 404 290 404 214 404 214 405 216 405 291 405 292 406 291 406 216 406 216 407 219 407 292 407 293 408 292 408 219 408 221 409 294 409 293 409 219 410 221 410 293 410 295 411 294 411 221 411 223 412 296 412 295 412 221 413 223 413 295 413 269 414 296 414 223 414 276 415 277 415 50 415 50 416 52 416 276 416 275 417 276 417 52 417 52 418 54 418 275 418 274 419 275 419 54 419 54 420 56 420 274 420 274 421 56 421 142 421 274 422 142 422 140 422 274 423 140 423 137 423 274 424 137 424 134 424 132 425 274 425 134 425 259 426 59 426 281 426 261 427 259 427 281 427 263 428 261 428 281 428 281 429 250 429 263 429 60 430 282 430 281 430 59 431 60 431 281 431 280 432 282 432 60 432 62 433 279 433 280 433 60 434 62 434 280 434 278 435 279 435 62 435 62 436 64 436 278 436 141 437 143 437 273 437 139 438 141 438 273 438 138 439 139 439 273 439 136 440 138 440 273 440 135 441 136 441 273 441 273 442 133 442 135 442 143 443 144 443 273 443 272 444 273 444 144 444 144 445 235 445 272 445 271 446 272 446 235 446 236 447 270 447 271 447 235 448 236 448 271 448 267 449 270 449 236 449 237 450 268 450 267 450 236 451 237 451 267 451 269 452 268 452 237 452 238 453 296 453 269 453 237 454 238 454 269 454 295 455 296 455 238 455 239 456 294 456 295 456 238 457 239 457 295 457 293 458 294 458 239 458 240 459 292 459 293 459 239 460 240 460 293 460 291 461 292 461 240 461 240 462 241 462 291 462 290 463 291 463 241 463 241 464 242 464 290 464 289 465 290 465 242 465 242 466 243 466 289 466 288 467 289 467 243 467 243 468 244 468 288 468 287 469 288 469 244 469 246 470 286 470 287 470 244 471 246 471 287 471 285 472 286 472 246 472 246 473 248 473 285 473 285 474 248 474 253 474 284 475 285 475 253 475 253 476 252 476 284 476 284 477 252 477 251 477 283 478 284 478 251 478 283 479 251 479 250 479 64 480 255 480 254 480 64 481 88 481 255 481 64 482 87 482 88 482 63 483 87 483 64 483 63 484 130 484 87 484 63 485 126 485 130 485 47 486 87 486 176 486 87 487 130 487 176 487 47 488 88 488 87 488 47 489 49 489 88 489 49 490 255 490 88 490 49 491 277 491 255 491 32 492 126 492 35 492 32 493 130 493 126 493 47 494 175 494 48 494 47 495 176 495 175 495 30 496 176 496 130 496 35 497 126 497 158 497 61 498 126 498 63 498 64 499 254 499 278 499 49 500 50 500 277 500 2 501 79 501 82 501 79 502 80 502 82 502 91 60 93 60 94 60 91 60 95 60 92 60 91 60 94 60 95 60 33 503 45 503 46 503 33 504 46 504 44 504 33 505 44 505 42 505 33 506 42 506 40 506 33 507 40 507 38 507 33 508 38 508 36 508 34 13 33 13 36 13 33 13 43 13 45 13 33 13 39 13 41 13 33 509 41 509 43 509 37 510 39 510 33 510 86 511 90 511 89 511 85 511 86 511 89 511 85 512 89 512 125 512 89 513 127 513 125 513 10 514 125 514 11 514 11 515 125 515 127 515 11 516 127 516 15 516 192 517 264 517 194 517 86 518 264 518 90 518 86 519 256 519 264 519 194 520 264 520 256 520 194 521 256 521 197 521

+
+
+
+
+ + + + 0.001 0 0 0 0 7.54979e-11 -0.001 0 0 0.001 7.54979e-11 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E4.dae b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E4.dae new file mode 100644 index 0000000..77e866d --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_E4.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:15.508647 + 2012-07-23T02:15:15.508662 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.00000 -7.45454 5.04167 -2.00000 -8.46762 3.04968 -2.00000 -8.95760 0.87927 -2.00000 -6.00089 1.26557 -2.00000 -5.98181 6.72267 -2.00000 -5.87041 2.08118 -2.00000 -5.49317 2.70207 -2.00000 -4.91993 3.14687 -2.00000 -4.22507 3.35807 -2.00000 -4.14030 7.98967 -2.00000 -3.50089 3.30717 -1.99580 1.04911 2.95447 -2.00000 -2.04357 8.76267 -2.00000 0.17909 8.99567 -2.00000 2.39064 8.67368 -1.86600 4.77932 3.43247 -2.00000 4.45473 7.81767 -2.00000 5.04250 4.35527 -2.00000 5.85836 4.74957 -2.00000 6.24414 6.47868 -2.00000 6.75372 4.88217 -2.00000 7.64707 4.74197 -6.00000 7.99883 -0.06943 -6.00000 7.70889 -2.13763 -6.00000 7.74360 2.00337 -6.00000 6.96060 3.93948 -6.00000 6.89354 -4.06023 -6.00000 5.70319 5.60667 -6.00000 5.60834 -5.70643 -6.00000 4.05705 6.89167 -6.00000 3.94089 -6.96383 -6.00000 2.13437 7.70767 -6.00000 2.00481 -7.74683 -6.00000 -0.00089 -0.00233 -6.00000 0.06618 7.99767 -6.00000 -0.06795 -8.00203 -6.00000 -2.00659 7.74168 -6.00000 -2.13615 -7.71213 -6.00000 -3.94267 6.95867 -6.00000 -4.05883 -6.89673 -6.00000 -5.61012 5.70168 -6.00000 -5.70497 -5.61153 -6.00000 -6.89532 4.05557 -6.00000 -6.96238 -3.94413 -6.00000 -7.71067 2.13297 -6.00000 -7.74538 -2.00803 -6.00000 -8.00061 0.06477 -3.60560 4.59911 -7.73793 -3.60560 5.87471 -6.81972 3.60550 4.59911 -7.73793 3.60550 5.87471 -6.81973 -3.60560 6.97112 -5.69363 3.60550 6.97111 -5.69363 -3.60560 7.85490 -4.39393 3.60550 7.85490 -4.39393 -3.60560 8.49911 -2.96033 3.60550 8.49911 -2.96033 -3.60560 -5.00089 -7.48563 -3.60560 -3.44530 -8.31712 3.60550 -5.00089 -7.48563 3.60550 -3.44496 -8.31723 -3.60560 -1.75737 -8.82922 3.60550 -1.75665 -8.82943 -3.60560 -0.00089 -9.00233 3.60550 -0.00089 -9.00233 -3.60560 7.49365 4.98087 -1.89600 8.00920 4.10117 -1.70680 8.23875 3.61787 -1.34180 8.49911 2.95567 -3.60560 8.49911 2.95567 -3.60560 6.01519 6.69167 -3.60560 4.15704 7.97968 -3.60560 2.03647 8.76367 -3.60560 -0.21260 8.99567 -3.60560 -2.44848 8.65868 -3.60560 -4.52976 7.77467 -3.60560 -6.32525 6.40067 -3.60560 -7.72158 4.62267 -3.60560 -8.63065 2.55248 -3.60560 -8.99508 0.32108 -3.60560 -8.79186 -1.93072 -2.67480 -8.87480 -1.50352 -2.18090 -8.99973 -0.14673 -3.15220 -8.54995 -2.81543 -3.60560 -8.03383 -4.06093 -1.00000 -3.75089 2.33887 1.00000 -3.75089 2.33887 -3.60560 2.09911 -8.75393 3.60550 2.09911 -8.75393 -1.00000 5.17159 3.12238 1.00000 5.17159 3.12238 0.00000 -5.00089 -0.00233 -1.00000 -5.00089 0.93118 1.00000 -5.00089 1.10617 1.00000 -5.00089 1.37067 -1.00000 -5.00089 1.37067 1.37480 -5.00089 -0.58433 -1.25900 -5.00089 -0.53753 -2.31300 -6.00089 -0.50973 -4.17820 -6.95020 -5.63412 -4.34790 -6.49255 -6.10052 -4.54170 -5.78034 -6.70483 -1.00000 -4.74733 2.03607 1.00000 -4.74552 2.03817 1.00000 5.57884 3.51017 -1.00000 5.57893 3.51017 1.00000 6.07904 3.76957 -1.00000 6.07915 3.76968 1.00000 6.63105 3.87917 -1.00000 6.63115 3.87917 1.00000 7.19123 3.83077 -1.00000 7.19131 3.83077 1.00000 7.71590 3.62837 -1.00000 7.71601 3.62827 1.00000 8.16394 3.28727 -1.00000 8.16406 3.28717 1.00000 8.49911 2.83508 -1.00000 8.49911 2.83508 -1.67330 -5.07965 -0.53843 -4.11050 -5.05836 -7.39513 -4.32460 -5.19024 -7.24833 -2.01210 -5.29806 -0.52692 -4.45570 -5.35820 -7.08053 -1.71140 -5.29806 1.17887 -1.70710 -4.79262 2.39278 -1.68300 -3.67164 2.64587 -5.15080 0.02667 -8.57373 -1.50000 5.06648 3.20547 -1.70710 5.92460 4.02497 -1.70710 7.13800 4.14037 -5.15080 2.04048 -8.32713 5.25480 8.49911 -0.00233 5.15080 8.49911 -1.10663 5.15080 8.49911 1.10197 4.97780 8.49911 -1.69952 5.07200 8.49911 1.41367 4.96590 8.49911 1.72547 4.72950 8.49911 -2.20792 4.82350 8.49911 2.03877 4.63240 8.49911 2.34737 4.40720 8.49911 -2.60963 4.36760 8.49911 2.64117 4.01370 8.49911 -2.87433 4.00940 8.49911 2.87157 3.60550 8.49911 2.95567 -0.00000 8.49911 -0.00233 1.34180 8.49911 2.95567 -4.01250 8.49911 -2.87492 -4.01070 8.49911 2.87097 -4.40320 8.49911 2.60887 -4.40880 8.49911 -2.60823 -4.72670 8.49911 2.20777 -4.72850 8.49911 -2.20963 -4.97660 8.49911 -1.70243 -4.97670 8.49911 1.69757 -5.15080 8.49911 -1.10663 -5.15080 8.49911 1.10197 -5.25480 8.49911 -0.00234 -5.15080 -1.16784 -8.49393 -5.15080 -2.39342 -8.23302 -5.15080 -3.69770 -7.73553 -5.15080 -5.03250 -6.94153 -5.15080 -6.33935 -5.77232 -5.15080 -7.48297 -4.18423 -5.15080 -8.26608 -2.27303 -5.15080 -8.57061 -0.17332 -5.15080 -8.34856 1.94337 -5.15080 -7.65831 3.84908 -5.15080 -6.65255 5.40367 -5.15080 -5.48446 6.58567 -5.15080 -4.27482 7.42767 -5.15080 -3.07933 7.99767 -5.15080 -1.92971 8.34967 -5.15080 -0.86492 8.52567 -5.15080 0.07097 8.56867 -5.15080 5.86632 -6.25092 -5.15080 4.29269 -7.42083 -5.15080 7.13263 -4.75442 -5.15080 8.02585 -3.00912 -5.15080 8.01546 3.03207 -5.15080 7.13700 4.74317 -5.15080 5.98916 6.12867 -5.15080 4.73707 7.14067 -5.15080 3.47752 7.83167 -5.15080 2.25250 8.26767 -5.15080 1.10237 8.49767 2.00000 6.26146 6.46167 2.00000 7.64707 4.74197 2.00000 6.75408 4.88217 2.00000 5.85895 4.74967 2.00000 5.04316 4.35577 2.00000 4.49639 7.79367 2.00000 4.38705 3.74247 2.00000 2.45995 8.65467 1.99160 1.03584 2.94627 2.00000 0.27493 8.99368 2.00000 -1.92679 8.78967 2.00000 -3.50089 3.30717 2.00000 -4.01233 8.05467 2.00000 -4.21819 3.35877 2.00000 -4.91452 3.14967 2.00000 -5.48962 2.70607 2.00000 -5.85578 6.83267 2.00000 -5.86839 2.08647 2.00000 -6.00089 1.26557 2.00000 -7.34581 5.19867 2.00000 -8.93237 1.10617 2.00000 -8.39242 3.25067 6.00000 -7.47839 2.84148 6.00000 -7.95962 0.80917 6.00000 -7.89848 -1.27833 6.00000 -7.29913 -3.27893 6.00000 -6.48758 4.67987 6.00000 -6.20241 -5.05613 6.00000 -5.05471 6.19968 6.00000 -4.68308 -6.48903 6.00000 -3.27744 7.29567 6.00000 -2.84466 -7.47983 6.00000 -0.00089 -0.00233 6.00000 -1.27687 7.89568 6.00000 -0.81243 -7.96103 6.00000 0.81066 7.95667 6.00549 1.09911 -7.99241 6.00000 2.84287 7.47567 6.00000 3.27565 -7.30053 6.00000 4.68129 6.48467 6.00000 5.05293 -6.20383 6.00000 6.20063 5.05167 6.00000 6.48580 -4.68453 6.00000 7.29735 3.27417 6.00000 7.47661 -2.84613 6.00000 7.89670 1.27367 6.00000 7.95784 -0.81383 1.65760 8.28299 3.51577 1.89880 8.00438 4.11057 3.60550 7.44183 5.05767 3.60550 5.87572 6.81467 3.60550 3.90805 8.10468 3.60550 1.67290 8.84068 3.60550 -0.67658 8.97267 3.60550 -2.97980 8.49067 3.60550 -5.07941 7.42767 3.60550 -6.83185 5.85767 3.60550 -8.11732 3.88657 3.60550 -8.84796 1.64977 2.28110 -8.99948 -0.16173 3.60550 -8.97381 -0.70003 2.95600 -8.85632 -1.60902 3.60550 -8.48627 -3.00203 2.34850 -6.00089 -0.30623 5.12570 -5.84850 -6.28963 4.91560 -6.47571 -5.81152 4.52990 -7.32036 -4.98423 4.08970 -8.00021 -4.04023 5.15080 0.02667 -8.57373 5.15080 2.04048 -8.32713 1.68300 -3.67164 2.64577 1.68300 -5.31788 1.37067 1.70710 -4.79262 2.39278 4.76790 -5.04422 -7.17183 1.81460 -5.12653 -0.37923 4.94330 -5.14915 -6.99723 2.10240 -5.35301 -0.34243 5.12360 -5.46303 -6.62893 1.50000 5.06648 3.20547 1.70710 5.92717 4.02597 1.70710 7.14342 4.13947 5.15080 4.83180 7.07667 5.15080 3.91347 7.62267 5.15080 3.04600 8.00967 5.15080 5.75663 6.34767 5.15080 6.64504 5.41067 5.15080 7.45116 4.23277 5.15080 8.10373 2.78777 5.15080 8.02586 -3.00913 5.15080 7.13271 -4.75433 5.15080 5.86657 -6.25073 5.15080 4.29269 -7.42083 5.15080 -1.14221 -8.49743 5.15080 -2.17531 -8.29333 5.15080 -3.04778 -8.01392 5.15080 -4.76167 -7.13003 5.15080 -3.88059 -7.64542 5.15080 -6.67612 -5.37923 5.15080 -7.55419 -4.05413 5.15080 -8.22952 -2.40213 5.15080 -8.55833 -0.49193 5.15080 -8.43597 1.52047 5.15080 -7.83186 3.48267 5.15080 -6.79325 5.22567 5.15080 -5.46640 6.60067 5.15080 -4.02045 7.56867 5.15080 -2.57937 8.17168 5.15080 -1.22172 8.48167 5.15080 0.03365 8.56867 5.15080 1.17758 8.48767 5.15080 2.18956 8.28468 + + + + + + + + + + 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00093 -0.00013 1.00000 -0.00022 0.00060 1.00000 -0.00007 0.00068 1.00000 0.00010 0.00071 0.99931 -0.03595 0.00917 0.99942 0.01307 0.03151 0.95139 0.30366 0.05155 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00000 0.58421 -0.81160 -0.00000 0.58421 -0.81160 -0.00000 0.71649 -0.69760 0.00000 0.71649 -0.69760 0.00000 0.82693 -0.56230 -0.00000 0.82693 -0.56231 -0.00000 0.91214 -0.40988 -0.00000 0.91214 -0.40988 -0.00000 -0.47140 -0.88192 0.00001 -0.47137 -0.88194 -0.00000 -0.29032 -0.95693 0.00000 -0.29031 -0.95693 -0.00002 -0.09808 -0.99518 0.00000 -0.09800 -0.99519 -0.01024 0.87126 0.49071 -0.06521 0.91102 0.40717 -0.17235 0.94537 0.27670 0.00000 0.89569 0.44469 0.01917 0.77775 0.62828 -0.02114 0.75645 0.65371 0.02078 0.59899 0.80048 -0.02269 0.56954 0.82165 0.02217 0.38298 0.92349 -0.02391 0.34667 0.93768 0.02368 0.14404 0.98929 -0.02502 0.10258 0.99441 0.02543 -0.10423 0.99423 -0.02645 -0.14899 0.98849 0.02645 -0.34579 0.93794 -0.02841 -0.39078 0.92005 0.02716 -0.56661 0.82354 -0.02926 -0.60746 0.79381 0.02872 -0.75185 0.65870 -0.03036 -0.78610 0.61735 0.02994 -0.89095 0.45311 -0.03152 -0.91516 0.40187 0.03084 -0.97499 0.22011 -0.03298 -0.98639 0.16110 -0.05601 -0.99588 -0.07131 0.02851 -0.96782 -0.25002 -0.14979 -0.93150 -0.33147 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.93971 -0.00005 -0.34197 0.93968 0.00004 -0.34206 0.93969 -0.00001 -0.34203 0.93969 -0.00011 -0.34201 0.94011 -0.03212 -0.33935 0.93968 -0.00001 -0.34206 0.00000 -0.93445 0.35609 0.00047 -0.93398 0.35732 -0.00074 -0.29076 0.95680 0.00000 -0.28939 0.95721 0.00000 -0.68960 0.72419 -0.00003 -0.68952 0.72427 -0.00002 -0.46037 0.88773 0.00002 -0.46050 0.88766 0.00004 -0.19475 0.98085 -0.00001 -0.19457 0.98089 0.00000 0.08608 0.99629 0.00000 0.08608 0.99629 0.00001 0.35991 0.93299 -0.00003 0.36005 0.93293 -0.00001 0.60575 0.79565 -0.00000 0.60574 0.79566 0.00002 0.80338 0.59547 0.00000 0.80342 0.59542 0.98456 0.02268 -0.17359 0.98441 0.02224 -0.17448 0.10580 -0.99355 -0.04069 0.18652 -0.98043 -0.06299 0.43702 -0.88545 -0.15809 0.52681 -0.82743 -0.19452 0.64060 -0.73194 -0.23214 0.83438 -0.45143 -0.31624 0.86804 -0.37946 -0.32018 0.38545 -0.92273 -0.00000 0.93299 -0.30758 0.18688 0.96080 -0.27377 0.04380 0.92127 -0.36020 0.14671 0.28236 -0.89643 0.34160 0.24497 -0.89535 0.37193 0.44814 -0.25993 0.85534 0.91710 -0.24439 0.31495 0.38019 -0.21147 0.90041 0.93592 -0.10243 0.33699 0.93313 -0.09815 0.34587 0.90433 0.02992 0.42578 0.25645 -0.66646 0.70005 0.94919 -0.23814 0.20575 0.69006 -0.40578 0.59930 0.21665 -0.64639 0.73160 0.38812 -0.42440 0.81807 0.91868 -0.17188 0.35564 0.93764 -0.05092 0.34385 0.92766 -0.03536 0.37175 0.36872 -0.18086 0.91177 0.28723 -0.09069 0.95356 0.39482 0.07909 0.91535 0.91698 0.06185 0.39411 0.93728 0.21555 0.27393 0.87281 0.20909 0.44100 0.35631 0.33642 0.87170 0.29069 0.41024 0.86441 0.31632 0.81048 0.49301 0.39989 0.55520 0.72927 0.20559 0.78625 0.58270 0.18566 -0.97527 -0.11992 0.36546 -0.92859 -0.06445 0.53712 -0.83817 -0.09468 0.90609 -0.39177 -0.15973 0.90607 -0.39182 -0.15975 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.60175 -0.11087 -0.79095 -0.55260 -0.17354 -0.81518 -0.56293 -0.29456 -0.77224 -0.59656 -0.31335 -0.73887 -0.53395 -0.43226 -0.72667 -0.59855 -0.49298 -0.63143 -0.53858 -0.56180 -0.62794 -0.57917 -0.65088 -0.49084 -0.55240 -0.67644 -0.48712 -0.55917 -0.76715 -0.31434 -0.56537 -0.76467 -0.30925 -0.54593 -0.82915 -0.12026 -0.57371 -0.81292 -0.10010 -0.53804 -0.83832 0.08794 -0.58049 -0.80638 0.11305 -0.53318 -0.79543 0.28811 -0.59078 -0.74279 0.31501 -0.52834 -0.71286 0.46119 -0.60082 -0.63008 0.49194 -0.53089 -0.60277 0.59568 -0.61001 -0.45269 0.65035 -0.56030 -0.49860 0.66141 -0.55481 -0.35806 0.75098 -0.60158 -0.29950 0.74055 -0.54973 -0.24456 0.79874 -0.56882 -0.13413 0.81145 -0.65227 -0.03479 0.75718 -0.55468 -0.10199 0.82579 -0.25225 0.69332 -0.67504 -0.29856 0.72856 -0.61649 -0.24741 0.80122 -0.54482 -0.29593 0.85032 -0.43518 -0.25744 0.88139 -0.39607 -0.16263 0.61088 -0.77484 -0.29884 0.84469 -0.44406 -0.38652 0.86862 -0.31001 -0.48835 0.83932 -0.23888 -0.63668 0.74832 -0.18615 -0.15915 0.62871 0.76118 -0.29618 0.84591 0.44353 -0.38577 0.86855 0.31114 -0.48964 0.83827 0.23993 -0.63937 0.74584 0.18689 -0.24788 0.86185 0.44246 -0.26528 0.86359 0.42875 -0.26594 0.74233 0.61500 -0.24343 0.73385 0.63419 -0.28203 0.60308 0.74616 -0.22637 0.55490 0.80053 -0.28338 0.46127 0.84079 -0.23125 0.32622 0.91657 -0.24490 0.33621 0.90939 -0.27617 0.18847 0.94245 -0.20856 0.06716 0.97570 -0.24805 0.09940 0.96363 -0.27362 -0.04414 0.96083 -0.22530 -0.15889 0.96125 -0.24051 -0.14466 0.95981 -0.27809 -0.28122 0.91847 -0.20592 -0.42115 0.88331 -0.26174 -0.37731 0.88833 -0.26835 -0.55035 0.79064 -0.22932 -0.59153 0.77299 -0.28987 -0.68074 0.67273 -0.22593 -0.76613 0.60167 -0.29289 -0.80279 0.51937 -0.23225 -0.89057 0.39107 -0.29251 -0.89910 0.32566 -0.23678 -0.95886 0.15660 -0.29312 -0.95086 0.09975 -0.23781 -0.96738 -0.08730 -0.29169 -0.94661 -0.13729 -0.23916 -0.91479 -0.32553 -0.28702 -0.88640 -0.36320 -0.44935 -0.80371 -0.39005 -0.23582 -0.78860 -0.56789 -0.37426 -0.72633 -0.57653 -0.40666 -0.55975 -0.72202 -0.54778 -0.62292 -0.55849 -0.39647 -0.61212 -0.68419 -0.38431 -0.48490 -0.78561 -0.12955 -0.33273 -0.93408 -0.30457 -0.44371 -0.84283 -0.38468 -0.47189 -0.79331 -0.24704 -0.45679 -0.85458 -0.28159 -0.34197 -0.89653 -0.24228 -0.28167 -0.92842 -0.28001 -0.19989 -0.93896 -0.23516 -0.06479 -0.96980 -0.55730 0.05702 0.82835 -0.63252 0.15189 0.75951 -0.55797 0.11524 0.82182 -0.55541 0.27883 0.78343 -0.60120 0.31219 0.73559 -0.54039 0.40471 0.73770 -0.59035 0.50737 0.62774 -0.56890 0.50605 0.64828 -0.54586 0.64522 0.53454 -0.59262 0.64309 0.48502 -0.52512 0.75709 0.38868 -0.60049 0.74131 0.29980 -0.51763 0.82995 0.20797 -0.62777 0.77615 0.05912 -0.56078 0.82176 0.10119 -0.55339 0.83129 -0.05212 -0.60152 0.79112 -0.11091 -0.52072 0.82848 -0.20609 -0.59707 0.73852 -0.31320 -0.52881 0.75554 -0.38667 -0.58696 0.63817 -0.49822 -0.54267 0.64119 -0.54257 -0.57115 0.48974 -0.65874 -0.56180 0.49809 -0.66052 -0.54455 0.31446 -0.77755 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00229 0.00090 -1.00000 0.00022 0.00142 -1.00000 -0.00013 0.00137 -1.00000 -0.00181 0.00052 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00287 0.00029 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00221 0.00099 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 0.00000 0.93296 0.35999 0.01931 0.90839 0.41767 0.07329 0.87296 0.48226 0.02584 0.89306 0.44920 -0.02382 0.77847 0.62723 0.03304 0.74609 0.66503 -0.03076 0.60209 0.79784 0.03889 0.54786 0.83567 -0.03569 0.38917 0.92047 0.04324 0.31247 0.94894 -0.03930 0.15320 0.98741 0.04626 0.05603 0.99736 -0.04162 -0.09218 0.99487 0.04789 -0.20460 0.97767 -0.04232 -0.33209 0.94230 0.04815 -0.45117 0.89114 -0.04168 -0.55204 0.83278 0.04659 -0.66655 0.74400 -0.04000 -0.73832 0.67327 0.04388 -0.83681 0.54573 -0.03649 -0.88032 0.47297 0.03987 -0.94982 0.31025 -0.03167 -0.96925 0.24404 0.03216 -0.99768 0.05994 0.04106 -0.99773 0.05344 -0.02553 -0.99358 -0.11018 0.11229 -0.97211 -0.20588 -0.90630 0.00000 -0.42263 -0.86964 -0.08004 -0.48716 -0.89996 -0.02187 -0.43542 -0.90429 -0.01077 -0.42679 -0.90564 -0.00650 -0.42399 -0.90705 -0.00088 -0.42103 -0.97622 0.01177 -0.21645 -0.97610 0.01148 -0.21702 -0.90078 -0.42872 0.06920 -0.23467 -0.90790 0.34734 -0.38011 -0.81899 0.42985 -0.93601 -0.30030 0.18358 -0.93307 -0.31049 0.18157 -0.44672 -0.25891 0.85639 -0.91709 -0.24350 0.31568 -0.93310 -0.10343 0.34443 -0.96004 0.02008 0.27915 -0.88250 -0.12152 0.45434 -0.38009 -0.21140 0.90047 -0.42098 -0.90707 0.00000 -0.90018 -0.38708 -0.19959 -0.03426 -0.99935 -0.01107 -0.22538 -0.96807 -0.10972 -0.37293 -0.91155 -0.17319 -0.57419 -0.77333 -0.26881 -0.63800 -0.71164 -0.29416 -0.84456 -0.35638 -0.39964 -0.84810 -0.34464 -0.40243 -0.86355 -0.34435 0.36838 -0.18530 -0.67765 0.71165 -0.25467 -0.63445 0.72981 -0.90722 -0.15464 0.39121 -0.38784 -0.42433 0.81824 -0.91871 -0.17172 0.35564 -0.92735 -0.05479 0.37016 -0.93552 -0.03282 0.35174 -0.21482 -0.19021 0.95795 -0.35603 -0.08683 0.93043 -0.39435 0.07911 0.91555 -0.91700 0.06187 0.39407 -0.93692 0.21779 0.27341 -0.86845 0.20847 0.44981 -0.14894 0.35590 0.92258 -0.33379 0.44138 0.83293 -0.36021 0.56509 0.74224 -0.31768 0.81062 0.49191 -0.20561 0.78621 0.58275 -0.25026 -0.96659 -0.05548 -0.57845 -0.77595 -0.25159 -0.39474 -0.91549 -0.07787 -0.90888 -0.35726 -0.21519 0.56781 0.42068 0.70755 0.65005 0.30960 0.69397 0.55491 0.39474 0.73229 0.54922 0.51733 0.65630 0.60076 0.54852 0.58157 0.55698 0.60269 0.57144 0.61845 0.64850 0.44381 0.55510 0.70789 0.43677 0.53284 0.77122 0.34829 0.59756 0.76810 0.23012 0.54172 0.81835 0.19193 0.62801 0.77595 0.05914 0.57520 0.81767 0.02395 0.54939 0.83396 -0.05174 0.55890 0.80471 -0.20017 0.57329 0.79731 -0.18879 0.55270 0.74187 -0.37967 0.57870 0.71791 -0.38692 0.53584 0.64455 -0.54537 0.59220 0.58621 -0.55286 0.52446 0.50799 -0.68329 0.59974 0.42021 -0.68098 0.61231 0.29515 -0.73346 0.44660 0.27208 -0.85236 0.64151 0.09324 -0.76143 0.34890 -0.01639 -0.93702 0.54828 -0.05448 -0.83452 0.61846 -0.15230 -0.77092 0.57573 -0.18840 -0.79564 0.55772 -0.25315 -0.79049 0.57251 -0.41398 -0.70771 0.65330 -0.30635 -0.69235 0.55497 -0.39466 -0.73229 0.54445 -0.52093 -0.65742 0.59931 -0.54924 -0.58237 0.55510 -0.60780 -0.56784 0.60235 -0.66540 -0.44092 0.55920 -0.70551 -0.43537 0.52905 -0.78549 -0.32111 0.60164 -0.76517 -0.22923 0.51993 -0.84183 -0.14491 0.59979 -0.79982 -0.02343 0.52122 -0.85185 0.05180 0.59424 -0.78264 0.18532 0.52693 -0.81228 0.25008 0.58678 -0.71281 0.38417 0.53799 -0.72414 0.43150 0.56047 -0.59595 0.57508 0.57500 -0.59530 0.56124 0.55205 -0.46385 0.69288 0.59113 -0.42336 0.68653 0.53564 -0.32596 0.77900 0.60099 -0.22961 0.76557 0.54985 -0.18593 0.81431 0.61611 -0.05445 0.78577 0.56673 -0.02406 0.82355 0.54749 0.05911 0.83473 0.61638 0.15487 0.77207 0.57784 0.18798 0.79421 0.55768 0.25377 0.79031 0.28615 0.57168 -0.76896 0.25221 0.69333 -0.67504 0.29853 0.72859 -0.61648 0.24738 0.80123 -0.54483 0.29591 0.85033 -0.43518 0.25742 0.88140 -0.39607 0.16302 0.61210 -0.77379 0.29884 0.84459 -0.44426 0.38634 0.86871 -0.30997 0.48872 0.83916 -0.23869 0.63744 0.74772 -0.18600 0.24869 -0.19671 -0.94840 0.44640 -0.49462 -0.74571 0.51486 -0.51149 -0.68796 0.94330 -0.21642 -0.25171 0.22684 -0.49176 -0.84067 0.26598 -0.45439 -0.85017 0.27274 -0.38929 -0.87981 0.24050 -0.29604 -0.92441 0.25385 -0.28080 -0.92559 0.27661 -0.18625 -0.94276 0.24507 -0.09501 -0.96484 0.31691 0.81044 0.49270 0.37341 0.86446 0.33655 0.43085 0.86208 0.26680 0.49637 0.83828 0.22561 0.57492 0.79448 0.19563 0.67028 0.72250 0.16945 0.19049 0.35601 0.91486 0.26776 0.87810 0.39655 0.22828 0.86977 0.43748 0.28427 0.79120 0.54147 0.25513 0.70166 0.66527 0.22684 0.72704 0.64805 0.27413 0.59534 0.75526 0.25735 0.49384 0.83060 0.22285 0.53449 0.81527 0.27268 0.39198 0.87863 0.23370 0.29726 0.92575 0.22680 0.30461 0.92508 0.27588 0.18904 0.94242 0.22259 0.06886 0.97248 0.23893 0.05447 0.96951 0.28081 -0.06635 0.95747 0.25066 -0.21550 0.94378 0.23221 -0.19924 0.95204 0.27893 -0.37069 0.88588 0.22242 -0.44038 0.86983 0.29208 -0.53205 0.79474 0.22553 -0.65008 0.72562 0.28908 -0.68887 0.66475 0.23735 -0.81368 0.53065 0.28072 -0.82451 0.49130 0.24869 -0.92071 0.30075 0.26912 -0.92047 0.28339 0.25181 -0.96599 0.05874 0.26130 -0.96388 0.05162 0.27659 -0.94706 -0.16302 0.23611 -0.95064 -0.20134 0.26933 -0.91432 -0.30245 0.35858 -0.86409 -0.35323 0.34344 -0.83072 -0.43812 0.48520 -0.71482 -0.50361 0.29171 -0.79734 -0.52835 0.53345 -0.61850 -0.57697 0.26348 0.11725 -0.95751 0.26850 0.11315 -0.95661 -0.00000 0.11747 -0.99308 0.00000 0.11747 -0.99308 -0.26852 0.11315 -0.95661 -0.26350 0.11725 -0.95751 -0.25596 0.36395 -0.89556 -0.26103 0.36037 -0.89554 -0.00000 0.37650 -0.92642 -0.00000 0.37650 -0.92642 0.26081 0.36347 -0.89436 0.25561 0.36091 -0.89689 -0.56332 0.10097 -0.82004 -0.56422 0.10035 -0.81950 -0.28904 0.55927 -0.77696 -0.27231 0.57408 -0.77219 -0.54728 0.31244 -0.77644 -0.55333 -0.05552 -0.83111 -0.26765 -0.09450 -0.95887 0.26778 -0.06276 -0.96143 0.27176 0.56222 -0.78106 0.00965 -0.99918 0.03933 -0.03275 -0.99542 -0.08983 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 0.00000 -0.08748 0.99617 0.00000 -0.08748 0.99617 0.40091 -0.08014 0.91261 0.17719 -0.06659 0.98192 0.90449 0.03213 0.42528 0.01521 -0.06422 0.99782 0.59085 -0.12274 0.79739 -0.80470 -0.13532 0.57805 -0.18092 -0.08603 0.97973 -0.40248 -0.06691 0.91298 0.00252 -0.06387 0.99796 -0.90452 0.03215 0.42522 + + + + + + + + + + + + + + +

3 0 0 0 1 0 2 1 3 1 1 1 4 2 0 2 3 2 3 3 5 3 4 3 4 4 5 4 6 4 4 5 6 5 7 5 4 6 7 6 8 6 9 7 4 7 8 7 8 8 10 8 9 8 9 9 10 9 11 9 12 10 9 10 11 10 13 11 12 11 11 11 14 12 13 12 11 12 14 13 11 13 15 13 16 14 14 14 15 14 15 15 17 15 16 15 16 16 17 16 18 16 19 17 16 17 18 17 18 18 20 18 19 18 21 19 19 19 20 19 22 20 23 20 24 20 25 21 24 21 23 21 23 22 26 22 25 22 27 23 25 23 26 23 26 24 28 24 27 24 29 25 27 25 28 25 28 26 30 26 29 26 31 27 29 27 30 27 30 28 32 28 31 28 31 29 32 29 33 29 34 30 31 30 33 30 32 31 35 31 33 31 35 32 37 32 33 32 47 33 48 33 49 33 50 34 49 34 48 34 48 35 51 35 50 35 52 36 50 36 51 36 51 37 53 37 52 37 54 38 52 38 53 38 53 39 55 39 54 39 56 40 54 40 55 40 57 41 58 41 59 41 60 42 59 42 58 42 58 43 61 43 60 43 62 44 60 44 61 44 61 45 63 45 62 45 64 46 62 46 63 46 65 47 21 47 66 47 65 48 66 48 67 48 65 49 67 49 68 49 69 50 65 50 68 50 19 51 21 51 65 51 65 52 70 52 19 52 16 53 19 53 70 53 70 54 71 54 16 54 14 55 16 55 71 55 71 56 72 56 14 56 13 57 14 57 72 57 72 58 73 58 13 58 12 59 13 59 73 59 73 60 74 60 12 60 9 61 12 61 74 61 74 62 75 62 9 62 4 63 9 63 75 63 75 64 76 64 4 64 0 65 4 65 76 65 77 66 0 66 76 66 1 67 0 67 77 67 77 68 78 68 1 68 2 69 1 69 78 69 78 70 79 70 2 70 80 71 81 71 82 71 83 72 81 72 80 72 80 73 84 73 83 73 96 74 93 74 91 74 91 75 92 75 97 75 59 76 96 76 91 76 57 77 59 77 91 77 97 78 57 78 91 78 98 79 81 79 83 79 98 80 83 80 84 80 98 81 84 81 99 81 98 82 99 82 100 82 101 83 98 83 100 83 82 84 81 84 98 84 102 85 95 85 94 85 94 86 103 86 102 86 85 87 102 87 103 87 103 88 86 88 85 88 90 89 104 89 89 89 105 90 89 90 104 90 104 91 106 91 105 91 107 92 105 92 106 92 106 93 108 93 107 93 109 94 107 94 108 94 108 95 110 95 109 95 111 96 109 96 110 96 110 97 112 97 111 97 113 98 111 98 112 98 112 99 114 99 113 99 115 100 113 100 114 100 114 101 116 101 115 101 117 102 115 102 116 102 2 103 98 103 3 103 2 104 82 104 98 104 118 105 119 105 57 105 97 106 118 106 57 106 120 107 119 107 118 107 118 108 121 108 120 108 122 109 120 109 121 109 98 110 101 110 122 110 121 111 98 111 122 111 95 112 123 112 92 112 124 113 6 113 5 113 124 114 5 114 3 114 124 115 3 115 123 115 123 116 95 116 102 116 124 117 123 117 102 117 102 118 85 118 124 118 7 119 6 119 124 119 124 120 85 120 125 120 125 121 8 121 7 121 124 122 125 122 7 122 10 123 8 123 125 123 89 124 105 124 127 124 128 125 17 125 15 125 127 126 128 126 15 126 128 127 127 127 105 127 105 128 107 128 128 128 18 129 17 129 128 129 129 130 20 130 18 130 128 131 129 131 18 131 128 132 107 132 109 132 129 133 128 133 109 133 109 134 111 134 129 134 21 135 20 135 129 135 66 136 21 136 129 136 67 137 66 137 129 137 129 138 111 138 113 138 67 139 129 139 113 139 115 140 68 140 67 140 113 141 115 141 67 141 115 142 117 142 68 142 123 143 118 143 97 143 123 144 97 144 92 144 121 145 118 145 123 145 123 146 3 146 121 146 98 147 121 147 3 147 133 148 131 148 132 148 134 149 135 149 133 149 132 150 134 150 133 150 136 151 135 151 134 151 137 152 138 152 136 152 134 153 137 153 136 153 139 154 138 154 137 154 137 155 140 155 139 155 141 156 139 156 140 156 140 157 142 157 141 157 143 158 141 158 142 158 142 159 56 159 143 159 144 160 143 160 56 160 117 161 116 161 145 161 55 162 68 162 117 162 55 163 117 163 145 163 145 164 116 164 146 164 145 165 146 165 144 165 145 166 144 166 56 166 56 167 55 167 145 167 69 168 68 168 55 168 147 169 148 169 69 169 55 170 147 170 69 170 149 171 148 171 147 171 147 172 150 172 149 172 151 173 149 173 150 173 150 174 152 174 151 174 151 175 152 175 153 175 154 176 151 176 153 176 153 177 155 177 154 177 156 178 154 178 155 178 155 179 157 179 156 179 37 180 35 180 158 180 158 181 159 181 37 181 37 182 159 182 160 182 39 183 37 183 160 183 160 184 161 184 39 184 41 185 39 185 161 185 161 186 162 186 41 186 43 187 41 187 162 187 162 188 163 188 43 188 43 189 163 189 164 189 45 190 43 190 164 190 164 191 165 191 45 191 46 192 45 192 165 192 165 193 166 193 46 193 44 194 46 194 166 194 166 195 167 195 44 195 42 196 44 196 167 196 167 197 168 197 42 197 40 198 42 198 168 198 168 199 169 199 40 199 40 200 169 200 170 200 38 201 40 201 170 201 170 202 171 202 38 202 36 203 38 203 171 203 171 204 172 204 36 204 36 205 172 205 173 205 36 206 173 206 174 206 34 207 36 207 174 207 51 208 48 208 175 208 175 209 177 209 51 209 53 210 51 210 177 210 177 211 178 211 53 211 55 212 53 212 178 212 147 213 55 213 178 213 150 214 147 214 178 214 152 215 150 215 178 215 153 216 152 216 178 216 178 217 155 217 153 217 179 218 69 218 148 218 179 219 148 219 149 219 179 220 149 220 151 220 179 221 151 221 154 221 156 222 179 222 154 222 69 223 179 223 180 223 65 224 69 224 180 224 180 225 181 225 65 225 70 226 65 226 181 226 181 227 182 227 70 227 71 228 70 228 182 228 182 229 183 229 71 229 71 230 183 230 184 230 72 231 71 231 184 231 184 232 185 232 72 232 72 233 185 233 174 233 73 234 72 234 174 234 174 235 173 235 73 235 73 236 173 236 172 236 74 237 73 237 172 237 172 238 171 238 74 238 74 239 171 239 170 239 75 240 74 240 170 240 170 241 169 241 75 241 76 242 75 242 169 242 169 243 168 243 76 243 77 244 76 244 168 244 168 245 167 245 77 245 78 246 77 246 167 246 167 247 166 247 78 247 79 248 78 248 166 248 166 249 165 249 79 249 80 250 79 250 165 250 165 251 164 251 80 251 84 252 80 252 164 252 164 253 163 253 84 253 162 254 99 254 84 254 163 255 162 255 84 255 100 256 99 256 162 256 161 257 122 257 101 257 161 258 101 258 100 258 162 259 161 259 100 259 120 260 122 260 161 260 160 261 57 261 119 261 160 262 119 262 120 262 161 263 160 263 120 263 58 264 57 264 160 264 160 265 159 265 58 265 61 266 58 266 159 266 159 267 158 267 61 267 61 268 158 268 126 268 185 269 34 269 174 269 34 270 185 270 184 270 31 271 34 271 184 271 184 272 183 272 31 272 29 273 31 273 183 273 183 274 182 274 29 274 29 275 182 275 181 275 27 276 29 276 181 276 181 277 180 277 27 277 25 278 27 278 180 278 180 279 179 279 25 279 24 280 25 280 179 280 179 281 156 281 24 281 24 282 156 282 157 282 22 283 24 283 157 283 22 284 157 284 155 284 23 285 22 285 155 285 155 286 178 286 23 286 26 287 23 287 178 287 178 288 177 288 26 288 28 289 26 289 177 289 177 290 175 290 28 290 28 291 175 291 176 291 30 292 28 292 176 292 32 293 30 293 130 293 186 294 187 294 188 294 188 295 189 295 186 295 186 296 189 296 190 296 191 297 186 297 190 297 190 298 192 298 191 298 193 299 191 299 192 299 192 300 194 300 193 300 195 301 193 301 194 301 196 302 195 302 194 302 194 303 197 303 196 303 198 304 196 304 197 304 197 305 199 305 198 305 198 306 199 306 200 306 198 307 200 307 201 307 202 308 198 308 201 308 201 309 203 309 202 309 202 310 203 310 204 310 205 311 202 311 204 311 206 312 207 312 205 312 204 313 206 313 205 313 208 314 209 314 210 314 210 315 211 315 208 315 212 316 208 316 211 316 211 317 213 317 212 317 214 318 212 318 213 318 213 319 215 319 214 319 216 320 214 320 215 320 215 321 217 321 216 321 216 322 217 322 218 322 219 323 216 323 218 323 217 324 220 324 218 324 221 325 219 325 218 325 220 326 222 326 218 326 223 327 221 327 218 327 224 328 223 328 218 328 222 329 224 329 218 329 225 330 223 330 224 330 224 331 226 331 225 331 227 332 225 332 226 332 226 333 228 333 227 333 229 334 227 334 228 334 228 335 230 335 229 335 231 336 229 336 230 336 230 337 232 337 231 337 146 338 233 338 144 338 144 339 233 339 234 339 144 340 234 340 187 340 235 341 144 341 187 341 187 342 186 342 235 342 236 343 235 343 186 343 186 344 191 344 236 344 237 345 236 345 191 345 191 346 193 346 237 346 238 347 237 347 193 347 193 348 195 348 238 348 239 349 238 349 195 349 195 350 196 350 239 350 240 351 239 351 196 351 196 352 198 352 240 352 241 353 240 353 198 353 198 354 202 354 241 354 242 355 241 355 202 355 202 356 205 356 242 356 243 357 242 357 205 357 205 358 207 358 243 358 244 359 243 359 207 359 207 360 206 360 244 360 244 361 206 361 245 361 246 362 244 362 245 362 245 363 247 363 246 363 248 364 246 364 247 364 247 365 245 365 249 365 250 366 251 366 252 366 250 367 252 367 253 367 250 368 253 368 248 368 250 369 248 369 247 369 249 370 250 370 247 370 206 371 204 371 249 371 245 372 206 372 249 372 204 373 203 373 257 373 258 374 103 374 94 374 258 375 94 375 257 375 257 376 203 376 201 376 258 377 257 377 201 377 86 378 103 378 258 378 201 379 200 379 258 379 258 380 200 380 199 380 258 381 199 381 197 381 258 382 197 382 256 382 258 383 256 383 86 383 93 384 257 384 94 384 257 385 249 385 204 385 59 386 259 386 96 386 260 387 96 387 259 387 259 388 261 388 260 388 262 389 260 389 261 389 261 390 263 390 262 390 262 391 263 391 250 391 249 392 262 392 250 392 190 393 264 393 192 393 265 394 104 394 90 394 265 395 90 395 264 395 265 396 264 396 190 396 106 397 104 397 265 397 190 398 189 398 265 398 265 399 189 399 188 399 266 400 265 400 188 400 266 401 108 401 106 401 265 402 266 402 106 402 110 403 108 403 266 403 188 404 187 404 266 404 266 405 187 405 234 405 233 406 266 406 234 406 233 407 112 407 110 407 266 408 233 408 110 408 114 409 112 409 233 409 233 410 146 410 114 410 116 411 114 411 146 411 93 412 96 412 260 412 262 413 93 413 260 413 262 414 257 414 93 414 262 415 249 415 257 415 225 416 267 416 268 416 225 417 268 417 269 417 225 418 269 418 223 418 270 419 267 419 225 419 225 420 227 420 270 420 271 421 270 421 227 421 229 422 272 422 271 422 227 423 229 423 271 423 273 424 272 424 229 424 229 425 231 425 273 425 133 426 273 426 231 426 232 427 131 427 133 427 231 428 232 428 133 428 132 429 131 429 232 429 230 430 274 430 132 430 232 431 230 431 132 431 275 432 274 432 230 432 230 433 228 433 275 433 276 434 275 434 228 434 228 435 226 435 276 435 277 436 276 436 226 436 226 437 224 437 277 437 222 438 255 438 277 438 224 439 222 439 277 439 220 440 254 440 255 440 220 441 255 441 222 441 278 442 254 442 220 442 217 443 279 443 278 443 220 444 217 444 278 444 279 445 217 445 280 445 215 446 281 446 282 446 215 447 282 447 280 447 217 448 215 448 280 448 250 449 281 449 215 449 215 450 213 450 250 450 283 451 250 451 213 451 211 452 284 452 283 452 213 453 211 453 283 453 285 454 284 454 211 454 211 455 210 455 285 455 286 456 285 456 210 456 210 457 209 457 286 457 287 458 286 458 209 458 209 459 208 459 287 459 288 460 287 460 208 460 208 461 212 461 288 461 289 462 288 462 212 462 214 463 290 463 289 463 212 464 214 464 289 464 291 465 290 465 214 465 214 466 216 466 291 466 292 467 291 467 216 467 216 468 219 468 292 468 293 469 292 469 219 469 221 470 294 470 293 470 219 471 221 471 293 471 295 472 294 472 221 472 223 473 296 473 295 473 221 474 223 474 295 474 269 475 296 475 223 475 276 476 277 476 50 476 50 477 52 477 276 477 275 478 276 478 52 478 52 479 54 479 275 479 274 480 275 480 54 480 54 481 56 481 274 481 274 482 56 482 142 482 274 483 142 483 140 483 274 484 140 484 137 484 274 485 137 485 134 485 132 486 274 486 134 486 259 487 59 487 281 487 261 488 259 488 281 488 263 489 261 489 281 489 281 490 250 490 263 490 60 491 282 491 281 491 59 492 60 492 281 492 280 493 282 493 60 493 62 494 279 494 280 494 60 495 62 495 280 495 278 496 279 496 62 496 62 497 64 497 278 497 141 498 143 498 273 498 139 499 141 499 273 499 138 500 139 500 273 500 136 501 138 501 273 501 135 502 136 502 273 502 273 503 133 503 135 503 143 504 144 504 273 504 272 505 273 505 144 505 144 506 235 506 272 506 271 507 272 507 235 507 236 508 270 508 271 508 235 509 236 509 271 509 267 510 270 510 236 510 237 511 268 511 267 511 236 512 237 512 267 512 269 513 268 513 237 513 238 514 296 514 269 514 237 515 238 515 269 515 295 516 296 516 238 516 239 517 294 517 295 517 238 518 239 518 295 518 293 519 294 519 239 519 240 520 292 520 293 520 239 521 240 521 293 521 291 522 292 522 240 522 240 523 241 523 291 523 290 524 291 524 241 524 241 525 242 525 290 525 289 526 290 526 242 526 242 527 243 527 289 527 288 528 289 528 243 528 243 529 244 529 288 529 287 530 288 530 244 530 246 531 286 531 287 531 244 532 246 532 287 532 285 533 286 533 246 533 246 534 248 534 285 534 285 535 248 535 253 535 284 536 285 536 253 536 253 537 252 537 284 537 284 538 252 538 251 538 283 539 284 539 251 539 283 540 251 540 250 540 64 541 255 541 254 541 64 542 88 542 255 542 64 543 87 543 88 543 63 544 87 544 64 544 63 545 130 545 87 545 63 546 126 546 130 546 47 547 87 547 176 547 87 548 130 548 176 548 47 549 88 549 87 549 47 550 49 550 88 550 49 551 255 551 88 551 49 552 277 552 255 552 32 553 126 553 35 553 32 554 130 554 126 554 47 555 175 555 48 555 47 556 176 556 175 556 30 557 176 557 130 557 35 558 126 558 158 558 61 559 126 559 63 559 64 560 254 560 278 560 49 561 50 561 277 561 2 562 79 562 82 562 79 563 80 563 82 563 91 564 93 564 94 564 91 565 95 565 92 565 91 566 94 566 95 566 33 567 45 567 46 567 33 568 46 568 44 568 33 569 44 569 42 569 33 570 42 570 40 570 33 571 40 571 38 571 33 572 38 572 36 572 34 573 33 573 36 573 33 574 43 574 45 574 33 575 39 575 41 575 33 576 41 576 43 576 37 577 39 577 33 577 86 578 90 578 89 578 85 579 86 579 89 579 85 580 89 580 125 580 89 581 127 581 125 581 10 582 125 582 11 582 11 583 125 583 127 583 11 584 127 584 15 584 192 585 264 585 194 585 86 586 264 586 90 586 86 587 256 587 264 587 194 588 264 588 256 588 194 589 256 589 197 589

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_G1M5.dae b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_G1M5.dae new file mode 100644 index 0000000..53e75da --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_G1M5.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:15.508647 + 2012-07-23T02:15:15.508662 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.00000 -7.45454 5.04167 -2.00000 -8.46762 3.04968 -2.00000 -8.95760 0.87927 -2.00000 -6.00089 1.26557 -2.00000 -5.98181 6.72267 -2.00000 -5.87041 2.08118 -2.00000 -5.49317 2.70207 -2.00000 -4.91993 3.14687 -2.00000 -4.22507 3.35807 -2.00000 -4.14030 7.98967 -2.00000 -3.50089 3.30717 -1.99580 1.04911 2.95447 -2.00000 -2.04357 8.76267 -2.00000 0.17909 8.99567 -2.00000 2.39064 8.67368 -1.86600 4.77932 3.43247 -2.00000 4.45473 7.81767 -2.00000 5.04250 4.35527 -2.00000 5.85836 4.74957 -2.00000 6.24414 6.47868 -2.00000 6.75372 4.88217 -2.00000 7.64707 4.74197 -6.00000 7.99883 -0.06943 -6.00000 7.70889 -2.13763 -6.00000 7.74360 2.00337 -6.00000 6.96060 3.93948 -6.00000 6.89354 -4.06023 -6.00000 5.70319 5.60667 -6.00000 5.60834 -5.70643 -6.00000 4.05705 6.89167 -6.00000 3.94089 -6.96383 -6.00000 2.13437 7.70767 -6.00000 2.00481 -7.74683 -6.00000 -0.00089 -0.00233 -6.00000 0.06618 7.99767 -6.00000 -0.06795 -8.00203 -6.00000 -2.00659 7.74168 -6.00000 -2.13615 -7.71213 -6.00000 -3.94267 6.95867 -6.00000 -4.05883 -6.89673 -6.00000 -5.61012 5.70168 -6.00000 -5.70497 -5.61153 -6.00000 -6.89532 4.05557 -6.00000 -6.96238 -3.94413 -6.00000 -7.71067 2.13297 -6.00000 -7.74538 -2.00803 -6.00000 -8.00061 0.06477 -3.60560 4.59911 -7.73793 -3.60560 5.87471 -6.81972 3.60550 4.59911 -7.73793 3.60550 5.87471 -6.81973 -3.60560 6.97112 -5.69363 3.60550 6.97111 -5.69363 -3.60560 7.85490 -4.39393 3.60550 7.85490 -4.39393 -3.60560 8.49911 -2.96033 3.60550 8.49911 -2.96033 -3.60560 -5.00089 -7.48563 -3.60560 -3.44530 -8.31712 3.60550 -5.00089 -7.48563 3.60550 -3.44496 -8.31723 -3.60560 -1.75737 -8.82922 3.60550 -1.75665 -8.82943 -3.60560 -0.00089 -9.00233 3.60550 -0.00089 -9.00233 -3.60560 7.49365 4.98087 -1.89600 8.00920 4.10117 -1.70680 8.23875 3.61787 -1.34180 8.49911 2.95567 -3.60560 8.49911 2.95567 -3.60560 6.01519 6.69167 -3.60560 4.15704 7.97968 -3.60560 2.03647 8.76367 -3.60560 -0.21260 8.99567 -3.60560 -2.44848 8.65868 -3.60560 -4.52976 7.77467 -3.60560 -6.32525 6.40067 -3.60560 -7.72158 4.62267 -3.60560 -8.63065 2.55248 -3.60560 -8.99508 0.32108 -3.60560 -8.79186 -1.93072 -2.67480 -8.87480 -1.50352 -2.18090 -8.99973 -0.14673 -3.15220 -8.54995 -2.81543 -3.60560 -8.03383 -4.06093 -1.00000 -3.75089 2.33887 1.00000 -3.75089 2.33887 -3.60560 2.09911 -8.75393 3.60550 2.09911 -8.75393 -1.00000 5.17159 3.12238 1.00000 5.17159 3.12238 0.00000 -5.00089 -0.00233 -1.00000 -5.00089 0.93118 1.00000 -5.00089 1.10617 1.00000 -5.00089 1.37067 -1.00000 -5.00089 1.37067 1.37480 -5.00089 -0.58433 -1.25900 -5.00089 -0.53753 -2.31300 -6.00089 -0.50973 -4.17820 -6.95020 -5.63412 -4.34790 -6.49255 -6.10052 -4.54170 -5.78034 -6.70483 -1.00000 -4.74733 2.03607 1.00000 -4.74552 2.03817 1.00000 5.57884 3.51017 -1.00000 5.57893 3.51017 1.00000 6.07904 3.76957 -1.00000 6.07915 3.76968 1.00000 6.63105 3.87917 -1.00000 6.63115 3.87917 1.00000 7.19123 3.83077 -1.00000 7.19131 3.83077 1.00000 7.71590 3.62837 -1.00000 7.71601 3.62827 1.00000 8.16394 3.28727 -1.00000 8.16406 3.28717 1.00000 8.49911 2.83508 -1.00000 8.49911 2.83508 -1.67330 -5.07965 -0.53843 -4.11050 -5.05836 -7.39513 -4.32460 -5.19024 -7.24833 -2.01210 -5.29806 -0.52692 -4.45570 -5.35820 -7.08053 -1.71140 -5.29806 1.17887 -1.70710 -4.79262 2.39278 -1.68300 -3.67164 2.64587 -5.15080 0.02667 -8.57373 -1.50000 5.06648 3.20547 -1.70710 5.92460 4.02497 -1.70710 7.13800 4.14037 -5.15080 2.04048 -8.32713 5.25480 8.49911 -0.00233 5.15080 8.49911 -1.10663 5.15080 8.49911 1.10197 4.97780 8.49911 -1.69952 5.07200 8.49911 1.41367 4.96590 8.49911 1.72547 4.72950 8.49911 -2.20792 4.82350 8.49911 2.03877 4.63240 8.49911 2.34737 4.40720 8.49911 -2.60963 4.36760 8.49911 2.64117 4.01370 8.49911 -2.87433 4.00940 8.49911 2.87157 3.60550 8.49911 2.95567 -0.00000 8.49911 -0.00233 1.34180 8.49911 2.95567 -4.01250 8.49911 -2.87492 -4.01070 8.49911 2.87097 -4.40320 8.49911 2.60887 -4.40880 8.49911 -2.60823 -4.72670 8.49911 2.20777 -4.72850 8.49911 -2.20963 -4.97660 8.49911 -1.70243 -4.97670 8.49911 1.69757 -5.15080 8.49911 -1.10663 -5.15080 8.49911 1.10197 -5.25480 8.49911 -0.00234 -5.15080 -1.16784 -8.49393 -5.15080 -2.39342 -8.23302 -5.15080 -3.69770 -7.73553 -5.15080 -5.03250 -6.94153 -5.15080 -6.33935 -5.77232 -5.15080 -7.48297 -4.18423 -5.15080 -8.26608 -2.27303 -5.15080 -8.57061 -0.17332 -5.15080 -8.34856 1.94337 -5.15080 -7.65831 3.84908 -5.15080 -6.65255 5.40367 -5.15080 -5.48446 6.58567 -5.15080 -4.27482 7.42767 -5.15080 -3.07933 7.99767 -5.15080 -1.92971 8.34967 -5.15080 -0.86492 8.52567 -5.15080 0.07097 8.56867 -5.15080 5.86632 -6.25092 -5.15080 4.29269 -7.42083 -5.15080 7.13263 -4.75442 -5.15080 8.02585 -3.00912 -5.15080 8.01546 3.03207 -5.15080 7.13700 4.74317 -5.15080 5.98916 6.12867 -5.15080 4.73707 7.14067 -5.15080 3.47752 7.83167 -5.15080 2.25250 8.26767 -5.15080 1.10237 8.49767 2.00000 6.26146 6.46167 2.00000 7.64707 4.74197 2.00000 6.75408 4.88217 2.00000 5.85895 4.74967 2.00000 5.04316 4.35577 2.00000 4.49639 7.79367 2.00000 4.38705 3.74247 2.00000 2.45995 8.65467 1.99160 1.03584 2.94627 2.00000 0.27493 8.99368 2.00000 -1.92679 8.78967 2.00000 -3.50089 3.30717 2.00000 -4.01233 8.05467 2.00000 -4.21819 3.35877 2.00000 -4.91452 3.14967 2.00000 -5.48962 2.70607 2.00000 -5.85578 6.83267 2.00000 -5.86839 2.08647 2.00000 -6.00089 1.26557 2.00000 -7.34581 5.19867 2.00000 -8.93237 1.10617 2.00000 -8.39242 3.25067 6.00000 -7.47839 2.84148 6.00000 -7.95962 0.80917 6.00000 -7.89848 -1.27833 6.00000 -7.29913 -3.27893 6.00000 -6.48758 4.67987 6.00000 -6.20241 -5.05613 6.00000 -5.05471 6.19968 6.00000 -4.68308 -6.48903 6.00000 -3.27744 7.29567 6.00000 -2.84466 -7.47983 6.00000 -0.00089 -0.00233 6.00000 -1.27687 7.89568 6.00000 -0.81243 -7.96103 6.00000 0.81066 7.95667 6.00549 1.09911 -7.99241 6.00000 2.84287 7.47567 6.00000 3.27565 -7.30053 6.00000 4.68129 6.48467 6.00000 5.05293 -6.20383 6.00000 6.20063 5.05167 6.00000 6.48580 -4.68453 6.00000 7.29735 3.27417 6.00000 7.47661 -2.84613 6.00000 7.89670 1.27367 6.00000 7.95784 -0.81383 1.65760 8.28299 3.51577 1.89880 8.00438 4.11057 3.60550 7.44183 5.05767 3.60550 5.87572 6.81467 3.60550 3.90805 8.10468 3.60550 1.67290 8.84068 3.60550 -0.67658 8.97267 3.60550 -2.97980 8.49067 3.60550 -5.07941 7.42767 3.60550 -6.83185 5.85767 3.60550 -8.11732 3.88657 3.60550 -8.84796 1.64977 2.28110 -8.99948 -0.16173 3.60550 -8.97381 -0.70003 2.95600 -8.85632 -1.60902 3.60550 -8.48627 -3.00203 2.34850 -6.00089 -0.30623 5.12570 -5.84850 -6.28963 4.91560 -6.47571 -5.81152 4.52990 -7.32036 -4.98423 4.08970 -8.00021 -4.04023 5.15080 0.02667 -8.57373 5.15080 2.04048 -8.32713 1.68300 -3.67164 2.64577 1.68300 -5.31788 1.37067 1.70710 -4.79262 2.39278 4.76790 -5.04422 -7.17183 1.81460 -5.12653 -0.37923 4.94330 -5.14915 -6.99723 2.10240 -5.35301 -0.34243 5.12360 -5.46303 -6.62893 1.50000 5.06648 3.20547 1.70710 5.92717 4.02597 1.70710 7.14342 4.13947 5.15080 4.83180 7.07667 5.15080 3.91347 7.62267 5.15080 3.04600 8.00967 5.15080 5.75663 6.34767 5.15080 6.64504 5.41067 5.15080 7.45116 4.23277 5.15080 8.10373 2.78777 5.15080 8.02586 -3.00913 5.15080 7.13271 -4.75433 5.15080 5.86657 -6.25073 5.15080 4.29269 -7.42083 5.15080 -1.14221 -8.49743 5.15080 -2.17531 -8.29333 5.15080 -3.04778 -8.01392 5.15080 -4.76167 -7.13003 5.15080 -3.88059 -7.64542 5.15080 -6.67612 -5.37923 5.15080 -7.55419 -4.05413 5.15080 -8.22952 -2.40213 5.15080 -8.55833 -0.49193 5.15080 -8.43597 1.52047 5.15080 -7.83186 3.48267 5.15080 -6.79325 5.22567 5.15080 -5.46640 6.60067 5.15080 -4.02045 7.56867 5.15080 -2.57937 8.17168 5.15080 -1.22172 8.48167 5.15080 0.03365 8.56867 5.15080 1.17758 8.48767 5.15080 2.18956 8.28468 + + + + + + + + + + 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00093 -0.00013 1.00000 -0.00022 0.00060 1.00000 -0.00007 0.00068 1.00000 0.00010 0.00071 0.99931 -0.03595 0.00917 0.99942 0.01307 0.03151 0.95139 0.30366 0.05155 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00000 0.58421 -0.81160 -0.00000 0.58421 -0.81160 -0.00000 0.71649 -0.69760 0.00000 0.71649 -0.69760 0.00000 0.82693 -0.56230 -0.00000 0.82693 -0.56231 -0.00000 0.91214 -0.40988 -0.00000 0.91214 -0.40988 -0.00000 -0.47140 -0.88192 0.00001 -0.47137 -0.88194 -0.00000 -0.29032 -0.95693 0.00000 -0.29031 -0.95693 -0.00002 -0.09808 -0.99518 0.00000 -0.09800 -0.99519 -0.01024 0.87126 0.49071 -0.06521 0.91102 0.40717 -0.17235 0.94537 0.27670 0.00000 0.89569 0.44469 0.01917 0.77775 0.62828 -0.02114 0.75645 0.65371 0.02078 0.59899 0.80048 -0.02269 0.56954 0.82165 0.02217 0.38298 0.92349 -0.02391 0.34667 0.93768 0.02368 0.14404 0.98929 -0.02502 0.10258 0.99441 0.02543 -0.10423 0.99423 -0.02645 -0.14899 0.98849 0.02645 -0.34579 0.93794 -0.02841 -0.39078 0.92005 0.02716 -0.56661 0.82354 -0.02926 -0.60746 0.79381 0.02872 -0.75185 0.65870 -0.03036 -0.78610 0.61735 0.02994 -0.89095 0.45311 -0.03152 -0.91516 0.40187 0.03084 -0.97499 0.22011 -0.03298 -0.98639 0.16110 -0.05601 -0.99588 -0.07131 0.02851 -0.96782 -0.25002 -0.14979 -0.93150 -0.33147 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.93971 -0.00005 -0.34197 0.93968 0.00004 -0.34206 0.93969 -0.00001 -0.34203 0.93969 -0.00011 -0.34201 0.94011 -0.03212 -0.33935 0.93968 -0.00001 -0.34206 0.00000 -0.93445 0.35609 0.00047 -0.93398 0.35732 -0.00074 -0.29076 0.95680 0.00000 -0.28939 0.95721 0.00000 -0.68960 0.72419 -0.00003 -0.68952 0.72427 -0.00002 -0.46037 0.88773 0.00002 -0.46050 0.88766 0.00004 -0.19475 0.98085 -0.00001 -0.19457 0.98089 0.00000 0.08608 0.99629 0.00000 0.08608 0.99629 0.00001 0.35991 0.93299 -0.00003 0.36005 0.93293 -0.00001 0.60575 0.79565 -0.00000 0.60574 0.79566 0.00002 0.80338 0.59547 0.00000 0.80342 0.59542 0.98456 0.02268 -0.17359 0.98441 0.02224 -0.17448 0.10580 -0.99355 -0.04069 0.18652 -0.98043 -0.06299 0.43702 -0.88545 -0.15809 0.52681 -0.82743 -0.19452 0.64060 -0.73194 -0.23214 0.83438 -0.45143 -0.31624 0.86804 -0.37946 -0.32018 0.38545 -0.92273 -0.00000 0.93299 -0.30758 0.18688 0.96080 -0.27377 0.04380 0.92127 -0.36020 0.14671 0.28236 -0.89643 0.34160 0.24497 -0.89535 0.37193 0.44814 -0.25993 0.85534 0.91710 -0.24439 0.31495 0.38019 -0.21147 0.90041 0.93592 -0.10243 0.33699 0.93313 -0.09815 0.34587 0.90433 0.02992 0.42578 0.25645 -0.66646 0.70005 0.94919 -0.23814 0.20575 0.69006 -0.40578 0.59930 0.21665 -0.64639 0.73160 0.38812 -0.42440 0.81807 0.91868 -0.17188 0.35564 0.93764 -0.05092 0.34385 0.92766 -0.03536 0.37175 0.36872 -0.18086 0.91177 0.28723 -0.09069 0.95356 0.39482 0.07909 0.91535 0.91698 0.06185 0.39411 0.93728 0.21555 0.27393 0.87281 0.20909 0.44100 0.35631 0.33642 0.87170 0.29069 0.41024 0.86441 0.31632 0.81048 0.49301 0.39989 0.55520 0.72927 0.20559 0.78625 0.58270 0.18566 -0.97527 -0.11992 0.36546 -0.92859 -0.06445 0.53712 -0.83817 -0.09468 0.90609 -0.39177 -0.15973 0.90607 -0.39182 -0.15975 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.60175 -0.11087 -0.79095 -0.55260 -0.17354 -0.81518 -0.56293 -0.29456 -0.77224 -0.59656 -0.31335 -0.73887 -0.53395 -0.43226 -0.72667 -0.59855 -0.49298 -0.63143 -0.53858 -0.56180 -0.62794 -0.57917 -0.65088 -0.49084 -0.55240 -0.67644 -0.48712 -0.55917 -0.76715 -0.31434 -0.56537 -0.76467 -0.30925 -0.54593 -0.82915 -0.12026 -0.57371 -0.81292 -0.10010 -0.53804 -0.83832 0.08794 -0.58049 -0.80638 0.11305 -0.53318 -0.79543 0.28811 -0.59078 -0.74279 0.31501 -0.52834 -0.71286 0.46119 -0.60082 -0.63008 0.49194 -0.53089 -0.60277 0.59568 -0.61001 -0.45269 0.65035 -0.56030 -0.49860 0.66141 -0.55481 -0.35806 0.75098 -0.60158 -0.29950 0.74055 -0.54973 -0.24456 0.79874 -0.56882 -0.13413 0.81145 -0.65227 -0.03479 0.75718 -0.55468 -0.10199 0.82579 -0.25225 0.69332 -0.67504 -0.29856 0.72856 -0.61649 -0.24741 0.80122 -0.54482 -0.29593 0.85032 -0.43518 -0.25744 0.88139 -0.39607 -0.16263 0.61088 -0.77484 -0.29884 0.84469 -0.44406 -0.38652 0.86862 -0.31001 -0.48835 0.83932 -0.23888 -0.63668 0.74832 -0.18615 -0.15915 0.62871 0.76118 -0.29618 0.84591 0.44353 -0.38577 0.86855 0.31114 -0.48964 0.83827 0.23993 -0.63937 0.74584 0.18689 -0.24788 0.86185 0.44246 -0.26528 0.86359 0.42875 -0.26594 0.74233 0.61500 -0.24343 0.73385 0.63419 -0.28203 0.60308 0.74616 -0.22637 0.55490 0.80053 -0.28338 0.46127 0.84079 -0.23125 0.32622 0.91657 -0.24490 0.33621 0.90939 -0.27617 0.18847 0.94245 -0.20856 0.06716 0.97570 -0.24805 0.09940 0.96363 -0.27362 -0.04414 0.96083 -0.22530 -0.15889 0.96125 -0.24051 -0.14466 0.95981 -0.27809 -0.28122 0.91847 -0.20592 -0.42115 0.88331 -0.26174 -0.37731 0.88833 -0.26835 -0.55035 0.79064 -0.22932 -0.59153 0.77299 -0.28987 -0.68074 0.67273 -0.22593 -0.76613 0.60167 -0.29289 -0.80279 0.51937 -0.23225 -0.89057 0.39107 -0.29251 -0.89910 0.32566 -0.23678 -0.95886 0.15660 -0.29312 -0.95086 0.09975 -0.23781 -0.96738 -0.08730 -0.29169 -0.94661 -0.13729 -0.23916 -0.91479 -0.32553 -0.28702 -0.88640 -0.36320 -0.44935 -0.80371 -0.39005 -0.23582 -0.78860 -0.56789 -0.37426 -0.72633 -0.57653 -0.40666 -0.55975 -0.72202 -0.54778 -0.62292 -0.55849 -0.39647 -0.61212 -0.68419 -0.38431 -0.48490 -0.78561 -0.12955 -0.33273 -0.93408 -0.30457 -0.44371 -0.84283 -0.38468 -0.47189 -0.79331 -0.24704 -0.45679 -0.85458 -0.28159 -0.34197 -0.89653 -0.24228 -0.28167 -0.92842 -0.28001 -0.19989 -0.93896 -0.23516 -0.06479 -0.96980 -0.55730 0.05702 0.82835 -0.63252 0.15189 0.75951 -0.55797 0.11524 0.82182 -0.55541 0.27883 0.78343 -0.60120 0.31219 0.73559 -0.54039 0.40471 0.73770 -0.59035 0.50737 0.62774 -0.56890 0.50605 0.64828 -0.54586 0.64522 0.53454 -0.59262 0.64309 0.48502 -0.52512 0.75709 0.38868 -0.60049 0.74131 0.29980 -0.51763 0.82995 0.20797 -0.62777 0.77615 0.05912 -0.56078 0.82176 0.10119 -0.55339 0.83129 -0.05212 -0.60152 0.79112 -0.11091 -0.52072 0.82848 -0.20609 -0.59707 0.73852 -0.31320 -0.52881 0.75554 -0.38667 -0.58696 0.63817 -0.49822 -0.54267 0.64119 -0.54257 -0.57115 0.48974 -0.65874 -0.56180 0.49809 -0.66052 -0.54455 0.31446 -0.77755 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00229 0.00090 -1.00000 0.00022 0.00142 -1.00000 -0.00013 0.00137 -1.00000 -0.00181 0.00052 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00287 0.00029 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00221 0.00099 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 0.00000 0.93296 0.35999 0.01931 0.90839 0.41767 0.07329 0.87296 0.48226 0.02584 0.89306 0.44920 -0.02382 0.77847 0.62723 0.03304 0.74609 0.66503 -0.03076 0.60209 0.79784 0.03889 0.54786 0.83567 -0.03569 0.38917 0.92047 0.04324 0.31247 0.94894 -0.03930 0.15320 0.98741 0.04626 0.05603 0.99736 -0.04162 -0.09218 0.99487 0.04789 -0.20460 0.97767 -0.04232 -0.33209 0.94230 0.04815 -0.45117 0.89114 -0.04168 -0.55204 0.83278 0.04659 -0.66655 0.74400 -0.04000 -0.73832 0.67327 0.04388 -0.83681 0.54573 -0.03649 -0.88032 0.47297 0.03987 -0.94982 0.31025 -0.03167 -0.96925 0.24404 0.03216 -0.99768 0.05994 0.04106 -0.99773 0.05344 -0.02553 -0.99358 -0.11018 0.11229 -0.97211 -0.20588 -0.90630 0.00000 -0.42263 -0.86964 -0.08004 -0.48716 -0.89996 -0.02187 -0.43542 -0.90429 -0.01077 -0.42679 -0.90564 -0.00650 -0.42399 -0.90705 -0.00088 -0.42103 -0.97622 0.01177 -0.21645 -0.97610 0.01148 -0.21702 -0.90078 -0.42872 0.06920 -0.23467 -0.90790 0.34734 -0.38011 -0.81899 0.42985 -0.93601 -0.30030 0.18358 -0.93307 -0.31049 0.18157 -0.44672 -0.25891 0.85639 -0.91709 -0.24350 0.31568 -0.93310 -0.10343 0.34443 -0.96004 0.02008 0.27915 -0.88250 -0.12152 0.45434 -0.38009 -0.21140 0.90047 -0.42098 -0.90707 0.00000 -0.90018 -0.38708 -0.19959 -0.03426 -0.99935 -0.01107 -0.22538 -0.96807 -0.10972 -0.37293 -0.91155 -0.17319 -0.57419 -0.77333 -0.26881 -0.63800 -0.71164 -0.29416 -0.84456 -0.35638 -0.39964 -0.84810 -0.34464 -0.40243 -0.86355 -0.34435 0.36838 -0.18530 -0.67765 0.71165 -0.25467 -0.63445 0.72981 -0.90722 -0.15464 0.39121 -0.38784 -0.42433 0.81824 -0.91871 -0.17172 0.35564 -0.92735 -0.05479 0.37016 -0.93552 -0.03282 0.35174 -0.21482 -0.19021 0.95795 -0.35603 -0.08683 0.93043 -0.39435 0.07911 0.91555 -0.91700 0.06187 0.39407 -0.93692 0.21779 0.27341 -0.86845 0.20847 0.44981 -0.14894 0.35590 0.92258 -0.33379 0.44138 0.83293 -0.36021 0.56509 0.74224 -0.31768 0.81062 0.49191 -0.20561 0.78621 0.58275 -0.25026 -0.96659 -0.05548 -0.57845 -0.77595 -0.25159 -0.39474 -0.91549 -0.07787 -0.90888 -0.35726 -0.21519 0.56781 0.42068 0.70755 0.65005 0.30960 0.69397 0.55491 0.39474 0.73229 0.54922 0.51733 0.65630 0.60076 0.54852 0.58157 0.55698 0.60269 0.57144 0.61845 0.64850 0.44381 0.55510 0.70789 0.43677 0.53284 0.77122 0.34829 0.59756 0.76810 0.23012 0.54172 0.81835 0.19193 0.62801 0.77595 0.05914 0.57520 0.81767 0.02395 0.54939 0.83396 -0.05174 0.55890 0.80471 -0.20017 0.57329 0.79731 -0.18879 0.55270 0.74187 -0.37967 0.57870 0.71791 -0.38692 0.53584 0.64455 -0.54537 0.59220 0.58621 -0.55286 0.52446 0.50799 -0.68329 0.59974 0.42021 -0.68098 0.61231 0.29515 -0.73346 0.44660 0.27208 -0.85236 0.64151 0.09324 -0.76143 0.34890 -0.01639 -0.93702 0.54828 -0.05448 -0.83452 0.61846 -0.15230 -0.77092 0.57573 -0.18840 -0.79564 0.55772 -0.25315 -0.79049 0.57251 -0.41398 -0.70771 0.65330 -0.30635 -0.69235 0.55497 -0.39466 -0.73229 0.54445 -0.52093 -0.65742 0.59931 -0.54924 -0.58237 0.55510 -0.60780 -0.56784 0.60235 -0.66540 -0.44092 0.55920 -0.70551 -0.43537 0.52905 -0.78549 -0.32111 0.60164 -0.76517 -0.22923 0.51993 -0.84183 -0.14491 0.59979 -0.79982 -0.02343 0.52122 -0.85185 0.05180 0.59424 -0.78264 0.18532 0.52693 -0.81228 0.25008 0.58678 -0.71281 0.38417 0.53799 -0.72414 0.43150 0.56047 -0.59595 0.57508 0.57500 -0.59530 0.56124 0.55205 -0.46385 0.69288 0.59113 -0.42336 0.68653 0.53564 -0.32596 0.77900 0.60099 -0.22961 0.76557 0.54985 -0.18593 0.81431 0.61611 -0.05445 0.78577 0.56673 -0.02406 0.82355 0.54749 0.05911 0.83473 0.61638 0.15487 0.77207 0.57784 0.18798 0.79421 0.55768 0.25377 0.79031 0.28615 0.57168 -0.76896 0.25221 0.69333 -0.67504 0.29853 0.72859 -0.61648 0.24738 0.80123 -0.54483 0.29591 0.85033 -0.43518 0.25742 0.88140 -0.39607 0.16302 0.61210 -0.77379 0.29884 0.84459 -0.44426 0.38634 0.86871 -0.30997 0.48872 0.83916 -0.23869 0.63744 0.74772 -0.18600 0.24869 -0.19671 -0.94840 0.44640 -0.49462 -0.74571 0.51486 -0.51149 -0.68796 0.94330 -0.21642 -0.25171 0.22684 -0.49176 -0.84067 0.26598 -0.45439 -0.85017 0.27274 -0.38929 -0.87981 0.24050 -0.29604 -0.92441 0.25385 -0.28080 -0.92559 0.27661 -0.18625 -0.94276 0.24507 -0.09501 -0.96484 0.31691 0.81044 0.49270 0.37341 0.86446 0.33655 0.43085 0.86208 0.26680 0.49637 0.83828 0.22561 0.57492 0.79448 0.19563 0.67028 0.72250 0.16945 0.19049 0.35601 0.91486 0.26776 0.87810 0.39655 0.22828 0.86977 0.43748 0.28427 0.79120 0.54147 0.25513 0.70166 0.66527 0.22684 0.72704 0.64805 0.27413 0.59534 0.75526 0.25735 0.49384 0.83060 0.22285 0.53449 0.81527 0.27268 0.39198 0.87863 0.23370 0.29726 0.92575 0.22680 0.30461 0.92508 0.27588 0.18904 0.94242 0.22259 0.06886 0.97248 0.23893 0.05447 0.96951 0.28081 -0.06635 0.95747 0.25066 -0.21550 0.94378 0.23221 -0.19924 0.95204 0.27893 -0.37069 0.88588 0.22242 -0.44038 0.86983 0.29208 -0.53205 0.79474 0.22553 -0.65008 0.72562 0.28908 -0.68887 0.66475 0.23735 -0.81368 0.53065 0.28072 -0.82451 0.49130 0.24869 -0.92071 0.30075 0.26912 -0.92047 0.28339 0.25181 -0.96599 0.05874 0.26130 -0.96388 0.05162 0.27659 -0.94706 -0.16302 0.23611 -0.95064 -0.20134 0.26933 -0.91432 -0.30245 0.35858 -0.86409 -0.35323 0.34344 -0.83072 -0.43812 0.48520 -0.71482 -0.50361 0.29171 -0.79734 -0.52835 0.53345 -0.61850 -0.57697 0.26348 0.11725 -0.95751 0.26850 0.11315 -0.95661 -0.00000 0.11747 -0.99308 0.00000 0.11747 -0.99308 -0.26852 0.11315 -0.95661 -0.26350 0.11725 -0.95751 -0.25596 0.36395 -0.89556 -0.26103 0.36037 -0.89554 -0.00000 0.37650 -0.92642 -0.00000 0.37650 -0.92642 0.26081 0.36347 -0.89436 0.25561 0.36091 -0.89689 -0.56332 0.10097 -0.82004 -0.56422 0.10035 -0.81950 -0.28904 0.55927 -0.77696 -0.27231 0.57408 -0.77219 -0.54728 0.31244 -0.77644 -0.55333 -0.05552 -0.83111 -0.26765 -0.09450 -0.95887 0.26778 -0.06276 -0.96143 0.27176 0.56222 -0.78106 0.00965 -0.99918 0.03933 -0.03275 -0.99542 -0.08983 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 0.00000 -0.08748 0.99617 0.00000 -0.08748 0.99617 0.40091 -0.08014 0.91261 0.17719 -0.06659 0.98192 0.90449 0.03213 0.42528 0.01521 -0.06422 0.99782 0.59085 -0.12274 0.79739 -0.80470 -0.13532 0.57805 -0.18092 -0.08603 0.97973 -0.40248 -0.06691 0.91298 0.00252 -0.06387 0.99796 -0.90452 0.03215 0.42522 + + + + + + + + + + + + + + +

3 0 0 0 1 0 2 1 3 1 1 1 4 2 0 2 3 2 3 3 5 3 4 3 4 4 5 4 6 4 4 5 6 5 7 5 4 6 7 6 8 6 9 7 4 7 8 7 8 8 10 8 9 8 9 9 10 9 11 9 12 10 9 10 11 10 13 11 12 11 11 11 14 12 13 12 11 12 14 13 11 13 15 13 16 14 14 14 15 14 15 15 17 15 16 15 16 16 17 16 18 16 19 17 16 17 18 17 18 18 20 18 19 18 21 19 19 19 20 19 22 20 23 20 24 20 25 21 24 21 23 21 23 22 26 22 25 22 27 23 25 23 26 23 26 24 28 24 27 24 29 25 27 25 28 25 28 26 30 26 29 26 31 27 29 27 30 27 30 28 32 28 31 28 31 29 32 29 33 29 34 30 31 30 33 30 32 31 35 31 33 31 35 32 37 32 33 32 47 33 48 33 49 33 50 34 49 34 48 34 48 35 51 35 50 35 52 36 50 36 51 36 51 37 53 37 52 37 54 38 52 38 53 38 53 39 55 39 54 39 56 40 54 40 55 40 57 41 58 41 59 41 60 42 59 42 58 42 58 43 61 43 60 43 62 44 60 44 61 44 61 45 63 45 62 45 64 46 62 46 63 46 65 47 21 47 66 47 65 48 66 48 67 48 65 49 67 49 68 49 69 50 65 50 68 50 19 51 21 51 65 51 65 52 70 52 19 52 16 53 19 53 70 53 70 54 71 54 16 54 14 55 16 55 71 55 71 56 72 56 14 56 13 57 14 57 72 57 72 58 73 58 13 58 12 59 13 59 73 59 73 60 74 60 12 60 9 61 12 61 74 61 74 62 75 62 9 62 4 63 9 63 75 63 75 64 76 64 4 64 0 65 4 65 76 65 77 66 0 66 76 66 1 67 0 67 77 67 77 68 78 68 1 68 2 69 1 69 78 69 78 70 79 70 2 70 80 71 81 71 82 71 83 72 81 72 80 72 80 73 84 73 83 73 96 74 93 74 91 74 91 75 92 75 97 75 59 76 96 76 91 76 57 77 59 77 91 77 97 78 57 78 91 78 98 79 81 79 83 79 98 80 83 80 84 80 98 81 84 81 99 81 98 82 99 82 100 82 101 83 98 83 100 83 82 84 81 84 98 84 102 85 95 85 94 85 94 86 103 86 102 86 85 87 102 87 103 87 103 88 86 88 85 88 90 89 104 89 89 89 105 90 89 90 104 90 104 91 106 91 105 91 107 92 105 92 106 92 106 93 108 93 107 93 109 94 107 94 108 94 108 95 110 95 109 95 111 96 109 96 110 96 110 97 112 97 111 97 113 98 111 98 112 98 112 99 114 99 113 99 115 100 113 100 114 100 114 101 116 101 115 101 117 102 115 102 116 102 2 103 98 103 3 103 2 104 82 104 98 104 118 105 119 105 57 105 97 106 118 106 57 106 120 107 119 107 118 107 118 108 121 108 120 108 122 109 120 109 121 109 98 110 101 110 122 110 121 111 98 111 122 111 95 112 123 112 92 112 124 113 6 113 5 113 124 114 5 114 3 114 124 115 3 115 123 115 123 116 95 116 102 116 124 117 123 117 102 117 102 118 85 118 124 118 7 119 6 119 124 119 124 120 85 120 125 120 125 121 8 121 7 121 124 122 125 122 7 122 10 123 8 123 125 123 89 124 105 124 127 124 128 125 17 125 15 125 127 126 128 126 15 126 128 127 127 127 105 127 105 128 107 128 128 128 18 129 17 129 128 129 129 130 20 130 18 130 128 131 129 131 18 131 128 132 107 132 109 132 129 133 128 133 109 133 109 134 111 134 129 134 21 135 20 135 129 135 66 136 21 136 129 136 67 137 66 137 129 137 129 138 111 138 113 138 67 139 129 139 113 139 115 140 68 140 67 140 113 141 115 141 67 141 115 142 117 142 68 142 123 143 118 143 97 143 123 144 97 144 92 144 121 145 118 145 123 145 123 146 3 146 121 146 98 147 121 147 3 147 133 148 131 148 132 148 134 149 135 149 133 149 132 150 134 150 133 150 136 151 135 151 134 151 137 152 138 152 136 152 134 153 137 153 136 153 139 154 138 154 137 154 137 155 140 155 139 155 141 156 139 156 140 156 140 157 142 157 141 157 143 158 141 158 142 158 142 159 56 159 143 159 144 160 143 160 56 160 117 161 116 161 145 161 55 162 68 162 117 162 55 163 117 163 145 163 145 164 116 164 146 164 145 165 146 165 144 165 145 166 144 166 56 166 56 167 55 167 145 167 69 168 68 168 55 168 147 169 148 169 69 169 55 170 147 170 69 170 149 171 148 171 147 171 147 172 150 172 149 172 151 173 149 173 150 173 150 174 152 174 151 174 151 175 152 175 153 175 154 176 151 176 153 176 153 177 155 177 154 177 156 178 154 178 155 178 155 179 157 179 156 179 37 180 35 180 158 180 158 181 159 181 37 181 37 182 159 182 160 182 39 183 37 183 160 183 160 184 161 184 39 184 41 185 39 185 161 185 161 186 162 186 41 186 43 187 41 187 162 187 162 188 163 188 43 188 43 189 163 189 164 189 45 190 43 190 164 190 164 191 165 191 45 191 46 192 45 192 165 192 165 193 166 193 46 193 44 194 46 194 166 194 166 195 167 195 44 195 42 196 44 196 167 196 167 197 168 197 42 197 40 198 42 198 168 198 168 199 169 199 40 199 40 200 169 200 170 200 38 201 40 201 170 201 170 202 171 202 38 202 36 203 38 203 171 203 171 204 172 204 36 204 36 205 172 205 173 205 36 206 173 206 174 206 34 207 36 207 174 207 51 208 48 208 175 208 175 209 177 209 51 209 53 210 51 210 177 210 177 211 178 211 53 211 55 212 53 212 178 212 147 213 55 213 178 213 150 214 147 214 178 214 152 215 150 215 178 215 153 216 152 216 178 216 178 217 155 217 153 217 179 218 69 218 148 218 179 219 148 219 149 219 179 220 149 220 151 220 179 221 151 221 154 221 156 222 179 222 154 222 69 223 179 223 180 223 65 224 69 224 180 224 180 225 181 225 65 225 70 226 65 226 181 226 181 227 182 227 70 227 71 228 70 228 182 228 182 229 183 229 71 229 71 230 183 230 184 230 72 231 71 231 184 231 184 232 185 232 72 232 72 233 185 233 174 233 73 234 72 234 174 234 174 235 173 235 73 235 73 236 173 236 172 236 74 237 73 237 172 237 172 238 171 238 74 238 74 239 171 239 170 239 75 240 74 240 170 240 170 241 169 241 75 241 76 242 75 242 169 242 169 243 168 243 76 243 77 244 76 244 168 244 168 245 167 245 77 245 78 246 77 246 167 246 167 247 166 247 78 247 79 248 78 248 166 248 166 249 165 249 79 249 80 250 79 250 165 250 165 251 164 251 80 251 84 252 80 252 164 252 164 253 163 253 84 253 162 254 99 254 84 254 163 255 162 255 84 255 100 256 99 256 162 256 161 257 122 257 101 257 161 258 101 258 100 258 162 259 161 259 100 259 120 260 122 260 161 260 160 261 57 261 119 261 160 262 119 262 120 262 161 263 160 263 120 263 58 264 57 264 160 264 160 265 159 265 58 265 61 266 58 266 159 266 159 267 158 267 61 267 61 268 158 268 126 268 185 269 34 269 174 269 34 270 185 270 184 270 31 271 34 271 184 271 184 272 183 272 31 272 29 273 31 273 183 273 183 274 182 274 29 274 29 275 182 275 181 275 27 276 29 276 181 276 181 277 180 277 27 277 25 278 27 278 180 278 180 279 179 279 25 279 24 280 25 280 179 280 179 281 156 281 24 281 24 282 156 282 157 282 22 283 24 283 157 283 22 284 157 284 155 284 23 285 22 285 155 285 155 286 178 286 23 286 26 287 23 287 178 287 178 288 177 288 26 288 28 289 26 289 177 289 177 290 175 290 28 290 28 291 175 291 176 291 30 292 28 292 176 292 32 293 30 293 130 293 186 294 187 294 188 294 188 295 189 295 186 295 186 296 189 296 190 296 191 297 186 297 190 297 190 298 192 298 191 298 193 299 191 299 192 299 192 300 194 300 193 300 195 301 193 301 194 301 196 302 195 302 194 302 194 303 197 303 196 303 198 304 196 304 197 304 197 305 199 305 198 305 198 306 199 306 200 306 198 307 200 307 201 307 202 308 198 308 201 308 201 309 203 309 202 309 202 310 203 310 204 310 205 311 202 311 204 311 206 312 207 312 205 312 204 313 206 313 205 313 208 314 209 314 210 314 210 315 211 315 208 315 212 316 208 316 211 316 211 317 213 317 212 317 214 318 212 318 213 318 213 319 215 319 214 319 216 320 214 320 215 320 215 321 217 321 216 321 216 322 217 322 218 322 219 323 216 323 218 323 217 324 220 324 218 324 221 325 219 325 218 325 220 326 222 326 218 326 223 327 221 327 218 327 224 328 223 328 218 328 222 329 224 329 218 329 225 330 223 330 224 330 224 331 226 331 225 331 227 332 225 332 226 332 226 333 228 333 227 333 229 334 227 334 228 334 228 335 230 335 229 335 231 336 229 336 230 336 230 337 232 337 231 337 146 338 233 338 144 338 144 339 233 339 234 339 144 340 234 340 187 340 235 341 144 341 187 341 187 342 186 342 235 342 236 343 235 343 186 343 186 344 191 344 236 344 237 345 236 345 191 345 191 346 193 346 237 346 238 347 237 347 193 347 193 348 195 348 238 348 239 349 238 349 195 349 195 350 196 350 239 350 240 351 239 351 196 351 196 352 198 352 240 352 241 353 240 353 198 353 198 354 202 354 241 354 242 355 241 355 202 355 202 356 205 356 242 356 243 357 242 357 205 357 205 358 207 358 243 358 244 359 243 359 207 359 207 360 206 360 244 360 244 361 206 361 245 361 246 362 244 362 245 362 245 363 247 363 246 363 248 364 246 364 247 364 247 365 245 365 249 365 250 366 251 366 252 366 250 367 252 367 253 367 250 368 253 368 248 368 250 369 248 369 247 369 249 370 250 370 247 370 206 371 204 371 249 371 245 372 206 372 249 372 204 373 203 373 257 373 258 374 103 374 94 374 258 375 94 375 257 375 257 376 203 376 201 376 258 377 257 377 201 377 86 378 103 378 258 378 201 379 200 379 258 379 258 380 200 380 199 380 258 381 199 381 197 381 258 382 197 382 256 382 258 383 256 383 86 383 93 384 257 384 94 384 257 385 249 385 204 385 59 386 259 386 96 386 260 387 96 387 259 387 259 388 261 388 260 388 262 389 260 389 261 389 261 390 263 390 262 390 262 391 263 391 250 391 249 392 262 392 250 392 190 393 264 393 192 393 265 394 104 394 90 394 265 395 90 395 264 395 265 396 264 396 190 396 106 397 104 397 265 397 190 398 189 398 265 398 265 399 189 399 188 399 266 400 265 400 188 400 266 401 108 401 106 401 265 402 266 402 106 402 110 403 108 403 266 403 188 404 187 404 266 404 266 405 187 405 234 405 233 406 266 406 234 406 233 407 112 407 110 407 266 408 233 408 110 408 114 409 112 409 233 409 233 410 146 410 114 410 116 411 114 411 146 411 93 412 96 412 260 412 262 413 93 413 260 413 262 414 257 414 93 414 262 415 249 415 257 415 225 416 267 416 268 416 225 417 268 417 269 417 225 418 269 418 223 418 270 419 267 419 225 419 225 420 227 420 270 420 271 421 270 421 227 421 229 422 272 422 271 422 227 423 229 423 271 423 273 424 272 424 229 424 229 425 231 425 273 425 133 426 273 426 231 426 232 427 131 427 133 427 231 428 232 428 133 428 132 429 131 429 232 429 230 430 274 430 132 430 232 431 230 431 132 431 275 432 274 432 230 432 230 433 228 433 275 433 276 434 275 434 228 434 228 435 226 435 276 435 277 436 276 436 226 436 226 437 224 437 277 437 222 438 255 438 277 438 224 439 222 439 277 439 220 440 254 440 255 440 220 441 255 441 222 441 278 442 254 442 220 442 217 443 279 443 278 443 220 444 217 444 278 444 279 445 217 445 280 445 215 446 281 446 282 446 215 447 282 447 280 447 217 448 215 448 280 448 250 449 281 449 215 449 215 450 213 450 250 450 283 451 250 451 213 451 211 452 284 452 283 452 213 453 211 453 283 453 285 454 284 454 211 454 211 455 210 455 285 455 286 456 285 456 210 456 210 457 209 457 286 457 287 458 286 458 209 458 209 459 208 459 287 459 288 460 287 460 208 460 208 461 212 461 288 461 289 462 288 462 212 462 214 463 290 463 289 463 212 464 214 464 289 464 291 465 290 465 214 465 214 466 216 466 291 466 292 467 291 467 216 467 216 468 219 468 292 468 293 469 292 469 219 469 221 470 294 470 293 470 219 471 221 471 293 471 295 472 294 472 221 472 223 473 296 473 295 473 221 474 223 474 295 474 269 475 296 475 223 475 276 476 277 476 50 476 50 477 52 477 276 477 275 478 276 478 52 478 52 479 54 479 275 479 274 480 275 480 54 480 54 481 56 481 274 481 274 482 56 482 142 482 274 483 142 483 140 483 274 484 140 484 137 484 274 485 137 485 134 485 132 486 274 486 134 486 259 487 59 487 281 487 261 488 259 488 281 488 263 489 261 489 281 489 281 490 250 490 263 490 60 491 282 491 281 491 59 492 60 492 281 492 280 493 282 493 60 493 62 494 279 494 280 494 60 495 62 495 280 495 278 496 279 496 62 496 62 497 64 497 278 497 141 498 143 498 273 498 139 499 141 499 273 499 138 500 139 500 273 500 136 501 138 501 273 501 135 502 136 502 273 502 273 503 133 503 135 503 143 504 144 504 273 504 272 505 273 505 144 505 144 506 235 506 272 506 271 507 272 507 235 507 236 508 270 508 271 508 235 509 236 509 271 509 267 510 270 510 236 510 237 511 268 511 267 511 236 512 237 512 267 512 269 513 268 513 237 513 238 514 296 514 269 514 237 515 238 515 269 515 295 516 296 516 238 516 239 517 294 517 295 517 238 518 239 518 295 518 293 519 294 519 239 519 240 520 292 520 293 520 239 521 240 521 293 521 291 522 292 522 240 522 240 523 241 523 291 523 290 524 291 524 241 524 241 525 242 525 290 525 289 526 290 526 242 526 242 527 243 527 289 527 288 528 289 528 243 528 243 529 244 529 288 529 287 530 288 530 244 530 246 531 286 531 287 531 244 532 246 532 287 532 285 533 286 533 246 533 246 534 248 534 285 534 285 535 248 535 253 535 284 536 285 536 253 536 253 537 252 537 284 537 284 538 252 538 251 538 283 539 284 539 251 539 283 540 251 540 250 540 64 541 255 541 254 541 64 542 88 542 255 542 64 543 87 543 88 543 63 544 87 544 64 544 63 545 130 545 87 545 63 546 126 546 130 546 47 547 87 547 176 547 87 548 130 548 176 548 47 549 88 549 87 549 47 550 49 550 88 550 49 551 255 551 88 551 49 552 277 552 255 552 32 553 126 553 35 553 32 554 130 554 126 554 47 555 175 555 48 555 47 556 176 556 175 556 30 557 176 557 130 557 35 558 126 558 158 558 61 559 126 559 63 559 64 560 254 560 278 560 49 561 50 561 277 561 2 562 79 562 82 562 79 563 80 563 82 563 91 564 93 564 94 564 91 565 95 565 92 565 91 566 94 566 95 566 33 567 45 567 46 567 33 568 46 568 44 568 33 569 44 569 42 569 33 570 42 570 40 570 33 571 40 571 38 571 33 572 38 572 36 572 34 573 33 573 36 573 33 574 43 574 45 574 33 575 39 575 41 575 33 576 41 576 43 576 37 577 39 577 33 577 86 578 90 578 89 578 85 579 86 579 89 579 85 580 89 580 125 580 89 581 127 581 125 581 10 582 125 582 11 582 11 583 125 583 127 583 11 584 127 584 15 584 192 585 264 585 194 585 86 586 264 586 90 586 86 587 256 587 264 587 194 588 264 588 256 588 194 589 256 589 197 589

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_G4.dae b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_G4.dae new file mode 100644 index 0000000..b86b943 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_knuckle/f_knuckle_G4.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:15.508647 + 2012-07-23T02:15:15.508662 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.00000 -7.45454 5.04167 -2.00000 -8.46762 3.04968 -2.00000 -8.95760 0.87927 -2.00000 -6.00089 1.26557 -2.00000 -5.98181 6.72267 -2.00000 -5.87041 2.08118 -2.00000 -5.49317 2.70207 -2.00000 -4.91993 3.14687 -2.00000 -4.22507 3.35807 -2.00000 -4.14030 7.98967 -2.00000 -3.50089 3.30717 -1.99580 1.04911 2.95447 -2.00000 -2.04357 8.76267 -2.00000 0.17909 8.99567 -2.00000 2.39064 8.67368 -1.86600 4.77932 3.43247 -2.00000 4.45473 7.81767 -2.00000 5.04250 4.35527 -2.00000 5.85836 4.74957 -2.00000 6.24414 6.47868 -2.00000 6.75372 4.88217 -2.00000 7.64707 4.74197 -6.00000 7.99883 -0.06943 -6.00000 7.70889 -2.13763 -6.00000 7.74360 2.00337 -6.00000 6.96060 3.93948 -6.00000 6.89354 -4.06023 -6.00000 5.70319 5.60667 -6.00000 5.60834 -5.70643 -6.00000 4.05705 6.89167 -6.00000 3.94089 -6.96383 -6.00000 2.13437 7.70767 -6.00000 2.00481 -7.74683 -6.00000 -0.00089 -0.00233 -6.00000 0.06618 7.99767 -6.00000 -0.06795 -8.00203 -6.00000 -2.00659 7.74168 -6.00000 -2.13615 -7.71213 -6.00000 -3.94267 6.95867 -6.00000 -4.05883 -6.89673 -6.00000 -5.61012 5.70168 -6.00000 -5.70497 -5.61153 -6.00000 -6.89532 4.05557 -6.00000 -6.96238 -3.94413 -6.00000 -7.71067 2.13297 -6.00000 -7.74538 -2.00803 -6.00000 -8.00061 0.06477 -3.60560 4.59911 -7.73793 -3.60560 5.87471 -6.81972 3.60550 4.59911 -7.73793 3.60550 5.87471 -6.81973 -3.60560 6.97112 -5.69363 3.60550 6.97111 -5.69363 -3.60560 7.85490 -4.39393 3.60550 7.85490 -4.39393 -3.60560 8.49911 -2.96033 3.60550 8.49911 -2.96033 -3.60560 -5.00089 -7.48563 -3.60560 -3.44530 -8.31712 3.60550 -5.00089 -7.48563 3.60550 -3.44496 -8.31723 -3.60560 -1.75737 -8.82922 3.60550 -1.75665 -8.82943 -3.60560 -0.00089 -9.00233 3.60550 -0.00089 -9.00233 -3.60560 7.49365 4.98087 -1.89600 8.00920 4.10117 -1.70680 8.23875 3.61787 -1.34180 8.49911 2.95567 -3.60560 8.49911 2.95567 -3.60560 6.01519 6.69167 -3.60560 4.15704 7.97968 -3.60560 2.03647 8.76367 -3.60560 -0.21260 8.99567 -3.60560 -2.44848 8.65868 -3.60560 -4.52976 7.77467 -3.60560 -6.32525 6.40067 -3.60560 -7.72158 4.62267 -3.60560 -8.63065 2.55248 -3.60560 -8.99508 0.32108 -3.60560 -8.79186 -1.93072 -2.67480 -8.87480 -1.50352 -2.18090 -8.99973 -0.14673 -3.15220 -8.54995 -2.81543 -3.60560 -8.03383 -4.06093 -1.00000 -3.75089 2.33887 1.00000 -3.75089 2.33887 -3.60560 2.09911 -8.75393 3.60550 2.09911 -8.75393 -1.00000 5.17159 3.12238 1.00000 5.17159 3.12238 0.00000 -5.00089 -0.00233 -1.00000 -5.00089 0.93118 1.00000 -5.00089 1.10617 1.00000 -5.00089 1.37067 -1.00000 -5.00089 1.37067 1.37480 -5.00089 -0.58433 -1.25900 -5.00089 -0.53753 -2.31300 -6.00089 -0.50973 -4.17820 -6.95020 -5.63412 -4.34790 -6.49255 -6.10052 -4.54170 -5.78034 -6.70483 -1.00000 -4.74733 2.03607 1.00000 -4.74552 2.03817 1.00000 5.57884 3.51017 -1.00000 5.57893 3.51017 1.00000 6.07904 3.76957 -1.00000 6.07915 3.76968 1.00000 6.63105 3.87917 -1.00000 6.63115 3.87917 1.00000 7.19123 3.83077 -1.00000 7.19131 3.83077 1.00000 7.71590 3.62837 -1.00000 7.71601 3.62827 1.00000 8.16394 3.28727 -1.00000 8.16406 3.28717 1.00000 8.49911 2.83508 -1.00000 8.49911 2.83508 -1.67330 -5.07965 -0.53843 -4.11050 -5.05836 -7.39513 -4.32460 -5.19024 -7.24833 -2.01210 -5.29806 -0.52692 -4.45570 -5.35820 -7.08053 -1.71140 -5.29806 1.17887 -1.70710 -4.79262 2.39278 -1.68300 -3.67164 2.64587 -5.15080 0.02667 -8.57373 -1.50000 5.06648 3.20547 -1.70710 5.92460 4.02497 -1.70710 7.13800 4.14037 -5.15080 2.04048 -8.32713 5.25480 8.49911 -0.00233 5.15080 8.49911 -1.10663 5.15080 8.49911 1.10197 4.97780 8.49911 -1.69952 5.07200 8.49911 1.41367 4.96590 8.49911 1.72547 4.72950 8.49911 -2.20792 4.82350 8.49911 2.03877 4.63240 8.49911 2.34737 4.40720 8.49911 -2.60963 4.36760 8.49911 2.64117 4.01370 8.49911 -2.87433 4.00940 8.49911 2.87157 3.60550 8.49911 2.95567 -0.00000 8.49911 -0.00233 1.34180 8.49911 2.95567 -4.01250 8.49911 -2.87492 -4.01070 8.49911 2.87097 -4.40320 8.49911 2.60887 -4.40880 8.49911 -2.60823 -4.72670 8.49911 2.20777 -4.72850 8.49911 -2.20963 -4.97660 8.49911 -1.70243 -4.97670 8.49911 1.69757 -5.15080 8.49911 -1.10663 -5.15080 8.49911 1.10197 -5.25480 8.49911 -0.00234 -5.15080 -1.16784 -8.49393 -5.15080 -2.39342 -8.23302 -5.15080 -3.69770 -7.73553 -5.15080 -5.03250 -6.94153 -5.15080 -6.33935 -5.77232 -5.15080 -7.48297 -4.18423 -5.15080 -8.26608 -2.27303 -5.15080 -8.57061 -0.17332 -5.15080 -8.34856 1.94337 -5.15080 -7.65831 3.84908 -5.15080 -6.65255 5.40367 -5.15080 -5.48446 6.58567 -5.15080 -4.27482 7.42767 -5.15080 -3.07933 7.99767 -5.15080 -1.92971 8.34967 -5.15080 -0.86492 8.52567 -5.15080 0.07097 8.56867 -5.15080 5.86632 -6.25092 -5.15080 4.29269 -7.42083 -5.15080 7.13263 -4.75442 -5.15080 8.02585 -3.00912 -5.15080 8.01546 3.03207 -5.15080 7.13700 4.74317 -5.15080 5.98916 6.12867 -5.15080 4.73707 7.14067 -5.15080 3.47752 7.83167 -5.15080 2.25250 8.26767 -5.15080 1.10237 8.49767 2.00000 6.26146 6.46167 2.00000 7.64707 4.74197 2.00000 6.75408 4.88217 2.00000 5.85895 4.74967 2.00000 5.04316 4.35577 2.00000 4.49639 7.79367 2.00000 4.38705 3.74247 2.00000 2.45995 8.65467 1.99160 1.03584 2.94627 2.00000 0.27493 8.99368 2.00000 -1.92679 8.78967 2.00000 -3.50089 3.30717 2.00000 -4.01233 8.05467 2.00000 -4.21819 3.35877 2.00000 -4.91452 3.14967 2.00000 -5.48962 2.70607 2.00000 -5.85578 6.83267 2.00000 -5.86839 2.08647 2.00000 -6.00089 1.26557 2.00000 -7.34581 5.19867 2.00000 -8.93237 1.10617 2.00000 -8.39242 3.25067 6.00000 -7.47839 2.84148 6.00000 -7.95962 0.80917 6.00000 -7.89848 -1.27833 6.00000 -7.29913 -3.27893 6.00000 -6.48758 4.67987 6.00000 -6.20241 -5.05613 6.00000 -5.05471 6.19968 6.00000 -4.68308 -6.48903 6.00000 -3.27744 7.29567 6.00000 -2.84466 -7.47983 6.00000 -0.00089 -0.00233 6.00000 -1.27687 7.89568 6.00000 -0.81243 -7.96103 6.00000 0.81066 7.95667 6.00549 1.09911 -7.99241 6.00000 2.84287 7.47567 6.00000 3.27565 -7.30053 6.00000 4.68129 6.48467 6.00000 5.05293 -6.20383 6.00000 6.20063 5.05167 6.00000 6.48580 -4.68453 6.00000 7.29735 3.27417 6.00000 7.47661 -2.84613 6.00000 7.89670 1.27367 6.00000 7.95784 -0.81383 1.65760 8.28299 3.51577 1.89880 8.00438 4.11057 3.60550 7.44183 5.05767 3.60550 5.87572 6.81467 3.60550 3.90805 8.10468 3.60550 1.67290 8.84068 3.60550 -0.67658 8.97267 3.60550 -2.97980 8.49067 3.60550 -5.07941 7.42767 3.60550 -6.83185 5.85767 3.60550 -8.11732 3.88657 3.60550 -8.84796 1.64977 2.28110 -8.99948 -0.16173 3.60550 -8.97381 -0.70003 2.95600 -8.85632 -1.60902 3.60550 -8.48627 -3.00203 2.34850 -6.00089 -0.30623 5.12570 -5.84850 -6.28963 4.91560 -6.47571 -5.81152 4.52990 -7.32036 -4.98423 4.08970 -8.00021 -4.04023 5.15080 0.02667 -8.57373 5.15080 2.04048 -8.32713 1.68300 -3.67164 2.64577 1.68300 -5.31788 1.37067 1.70710 -4.79262 2.39278 4.76790 -5.04422 -7.17183 1.81460 -5.12653 -0.37923 4.94330 -5.14915 -6.99723 2.10240 -5.35301 -0.34243 5.12360 -5.46303 -6.62893 1.50000 5.06648 3.20547 1.70710 5.92717 4.02597 1.70710 7.14342 4.13947 5.15080 4.83180 7.07667 5.15080 3.91347 7.62267 5.15080 3.04600 8.00967 5.15080 5.75663 6.34767 5.15080 6.64504 5.41067 5.15080 7.45116 4.23277 5.15080 8.10373 2.78777 5.15080 8.02586 -3.00913 5.15080 7.13271 -4.75433 5.15080 5.86657 -6.25073 5.15080 4.29269 -7.42083 5.15080 -1.14221 -8.49743 5.15080 -2.17531 -8.29333 5.15080 -3.04778 -8.01392 5.15080 -4.76167 -7.13003 5.15080 -3.88059 -7.64542 5.15080 -6.67612 -5.37923 5.15080 -7.55419 -4.05413 5.15080 -8.22952 -2.40213 5.15080 -8.55833 -0.49193 5.15080 -8.43597 1.52047 5.15080 -7.83186 3.48267 5.15080 -6.79325 5.22567 5.15080 -5.46640 6.60067 5.15080 -4.02045 7.56867 5.15080 -2.57937 8.17168 5.15080 -1.22172 8.48167 5.15080 0.03365 8.56867 5.15080 1.17758 8.48767 5.15080 2.18956 8.28468 + + + + + + + + + + 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00093 -0.00013 1.00000 -0.00022 0.00060 1.00000 -0.00007 0.00068 1.00000 0.00010 0.00071 0.99931 -0.03595 0.00917 0.99942 0.01307 0.03151 0.95139 0.30366 0.05155 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00000 0.58421 -0.81160 -0.00000 0.58421 -0.81160 -0.00000 0.71649 -0.69760 0.00000 0.71649 -0.69760 0.00000 0.82693 -0.56230 -0.00000 0.82693 -0.56231 -0.00000 0.91214 -0.40988 -0.00000 0.91214 -0.40988 -0.00000 -0.47140 -0.88192 0.00001 -0.47137 -0.88194 -0.00000 -0.29032 -0.95693 0.00000 -0.29031 -0.95693 -0.00002 -0.09808 -0.99518 0.00000 -0.09800 -0.99519 -0.01024 0.87126 0.49071 -0.06521 0.91102 0.40717 -0.17235 0.94537 0.27670 0.00000 0.89569 0.44469 0.01917 0.77775 0.62828 -0.02114 0.75645 0.65371 0.02078 0.59899 0.80048 -0.02269 0.56954 0.82165 0.02217 0.38298 0.92349 -0.02391 0.34667 0.93768 0.02368 0.14404 0.98929 -0.02502 0.10258 0.99441 0.02543 -0.10423 0.99423 -0.02645 -0.14899 0.98849 0.02645 -0.34579 0.93794 -0.02841 -0.39078 0.92005 0.02716 -0.56661 0.82354 -0.02926 -0.60746 0.79381 0.02872 -0.75185 0.65870 -0.03036 -0.78610 0.61735 0.02994 -0.89095 0.45311 -0.03152 -0.91516 0.40187 0.03084 -0.97499 0.22011 -0.03298 -0.98639 0.16110 -0.05601 -0.99588 -0.07131 0.02851 -0.96782 -0.25002 -0.14979 -0.93150 -0.33147 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.93971 -0.00005 -0.34197 0.93968 0.00004 -0.34206 0.93969 -0.00001 -0.34203 0.93969 -0.00011 -0.34201 0.94011 -0.03212 -0.33935 0.93968 -0.00001 -0.34206 0.00000 -0.93445 0.35609 0.00047 -0.93398 0.35732 -0.00074 -0.29076 0.95680 0.00000 -0.28939 0.95721 0.00000 -0.68960 0.72419 -0.00003 -0.68952 0.72427 -0.00002 -0.46037 0.88773 0.00002 -0.46050 0.88766 0.00004 -0.19475 0.98085 -0.00001 -0.19457 0.98089 0.00000 0.08608 0.99629 0.00000 0.08608 0.99629 0.00001 0.35991 0.93299 -0.00003 0.36005 0.93293 -0.00001 0.60575 0.79565 -0.00000 0.60574 0.79566 0.00002 0.80338 0.59547 0.00000 0.80342 0.59542 0.98456 0.02268 -0.17359 0.98441 0.02224 -0.17448 0.10580 -0.99355 -0.04069 0.18652 -0.98043 -0.06299 0.43702 -0.88545 -0.15809 0.52681 -0.82743 -0.19452 0.64060 -0.73194 -0.23214 0.83438 -0.45143 -0.31624 0.86804 -0.37946 -0.32018 0.38545 -0.92273 -0.00000 0.93299 -0.30758 0.18688 0.96080 -0.27377 0.04380 0.92127 -0.36020 0.14671 0.28236 -0.89643 0.34160 0.24497 -0.89535 0.37193 0.44814 -0.25993 0.85534 0.91710 -0.24439 0.31495 0.38019 -0.21147 0.90041 0.93592 -0.10243 0.33699 0.93313 -0.09815 0.34587 0.90433 0.02992 0.42578 0.25645 -0.66646 0.70005 0.94919 -0.23814 0.20575 0.69006 -0.40578 0.59930 0.21665 -0.64639 0.73160 0.38812 -0.42440 0.81807 0.91868 -0.17188 0.35564 0.93764 -0.05092 0.34385 0.92766 -0.03536 0.37175 0.36872 -0.18086 0.91177 0.28723 -0.09069 0.95356 0.39482 0.07909 0.91535 0.91698 0.06185 0.39411 0.93728 0.21555 0.27393 0.87281 0.20909 0.44100 0.35631 0.33642 0.87170 0.29069 0.41024 0.86441 0.31632 0.81048 0.49301 0.39989 0.55520 0.72927 0.20559 0.78625 0.58270 0.18566 -0.97527 -0.11992 0.36546 -0.92859 -0.06445 0.53712 -0.83817 -0.09468 0.90609 -0.39177 -0.15973 0.90607 -0.39182 -0.15975 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.60175 -0.11087 -0.79095 -0.55260 -0.17354 -0.81518 -0.56293 -0.29456 -0.77224 -0.59656 -0.31335 -0.73887 -0.53395 -0.43226 -0.72667 -0.59855 -0.49298 -0.63143 -0.53858 -0.56180 -0.62794 -0.57917 -0.65088 -0.49084 -0.55240 -0.67644 -0.48712 -0.55917 -0.76715 -0.31434 -0.56537 -0.76467 -0.30925 -0.54593 -0.82915 -0.12026 -0.57371 -0.81292 -0.10010 -0.53804 -0.83832 0.08794 -0.58049 -0.80638 0.11305 -0.53318 -0.79543 0.28811 -0.59078 -0.74279 0.31501 -0.52834 -0.71286 0.46119 -0.60082 -0.63008 0.49194 -0.53089 -0.60277 0.59568 -0.61001 -0.45269 0.65035 -0.56030 -0.49860 0.66141 -0.55481 -0.35806 0.75098 -0.60158 -0.29950 0.74055 -0.54973 -0.24456 0.79874 -0.56882 -0.13413 0.81145 -0.65227 -0.03479 0.75718 -0.55468 -0.10199 0.82579 -0.25225 0.69332 -0.67504 -0.29856 0.72856 -0.61649 -0.24741 0.80122 -0.54482 -0.29593 0.85032 -0.43518 -0.25744 0.88139 -0.39607 -0.16263 0.61088 -0.77484 -0.29884 0.84469 -0.44406 -0.38652 0.86862 -0.31001 -0.48835 0.83932 -0.23888 -0.63668 0.74832 -0.18615 -0.15915 0.62871 0.76118 -0.29618 0.84591 0.44353 -0.38577 0.86855 0.31114 -0.48964 0.83827 0.23993 -0.63937 0.74584 0.18689 -0.24788 0.86185 0.44246 -0.26528 0.86359 0.42875 -0.26594 0.74233 0.61500 -0.24343 0.73385 0.63419 -0.28203 0.60308 0.74616 -0.22637 0.55490 0.80053 -0.28338 0.46127 0.84079 -0.23125 0.32622 0.91657 -0.24490 0.33621 0.90939 -0.27617 0.18847 0.94245 -0.20856 0.06716 0.97570 -0.24805 0.09940 0.96363 -0.27362 -0.04414 0.96083 -0.22530 -0.15889 0.96125 -0.24051 -0.14466 0.95981 -0.27809 -0.28122 0.91847 -0.20592 -0.42115 0.88331 -0.26174 -0.37731 0.88833 -0.26835 -0.55035 0.79064 -0.22932 -0.59153 0.77299 -0.28987 -0.68074 0.67273 -0.22593 -0.76613 0.60167 -0.29289 -0.80279 0.51937 -0.23225 -0.89057 0.39107 -0.29251 -0.89910 0.32566 -0.23678 -0.95886 0.15660 -0.29312 -0.95086 0.09975 -0.23781 -0.96738 -0.08730 -0.29169 -0.94661 -0.13729 -0.23916 -0.91479 -0.32553 -0.28702 -0.88640 -0.36320 -0.44935 -0.80371 -0.39005 -0.23582 -0.78860 -0.56789 -0.37426 -0.72633 -0.57653 -0.40666 -0.55975 -0.72202 -0.54778 -0.62292 -0.55849 -0.39647 -0.61212 -0.68419 -0.38431 -0.48490 -0.78561 -0.12955 -0.33273 -0.93408 -0.30457 -0.44371 -0.84283 -0.38468 -0.47189 -0.79331 -0.24704 -0.45679 -0.85458 -0.28159 -0.34197 -0.89653 -0.24228 -0.28167 -0.92842 -0.28001 -0.19989 -0.93896 -0.23516 -0.06479 -0.96980 -0.55730 0.05702 0.82835 -0.63252 0.15189 0.75951 -0.55797 0.11524 0.82182 -0.55541 0.27883 0.78343 -0.60120 0.31219 0.73559 -0.54039 0.40471 0.73770 -0.59035 0.50737 0.62774 -0.56890 0.50605 0.64828 -0.54586 0.64522 0.53454 -0.59262 0.64309 0.48502 -0.52512 0.75709 0.38868 -0.60049 0.74131 0.29980 -0.51763 0.82995 0.20797 -0.62777 0.77615 0.05912 -0.56078 0.82176 0.10119 -0.55339 0.83129 -0.05212 -0.60152 0.79112 -0.11091 -0.52072 0.82848 -0.20609 -0.59707 0.73852 -0.31320 -0.52881 0.75554 -0.38667 -0.58696 0.63817 -0.49822 -0.54267 0.64119 -0.54257 -0.57115 0.48974 -0.65874 -0.56180 0.49809 -0.66052 -0.54455 0.31446 -0.77755 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00229 0.00090 -1.00000 0.00022 0.00142 -1.00000 -0.00013 0.00137 -1.00000 -0.00181 0.00052 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00287 0.00029 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00221 0.00099 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 0.00000 0.93296 0.35999 0.01931 0.90839 0.41767 0.07329 0.87296 0.48226 0.02584 0.89306 0.44920 -0.02382 0.77847 0.62723 0.03304 0.74609 0.66503 -0.03076 0.60209 0.79784 0.03889 0.54786 0.83567 -0.03569 0.38917 0.92047 0.04324 0.31247 0.94894 -0.03930 0.15320 0.98741 0.04626 0.05603 0.99736 -0.04162 -0.09218 0.99487 0.04789 -0.20460 0.97767 -0.04232 -0.33209 0.94230 0.04815 -0.45117 0.89114 -0.04168 -0.55204 0.83278 0.04659 -0.66655 0.74400 -0.04000 -0.73832 0.67327 0.04388 -0.83681 0.54573 -0.03649 -0.88032 0.47297 0.03987 -0.94982 0.31025 -0.03167 -0.96925 0.24404 0.03216 -0.99768 0.05994 0.04106 -0.99773 0.05344 -0.02553 -0.99358 -0.11018 0.11229 -0.97211 -0.20588 -0.90630 0.00000 -0.42263 -0.86964 -0.08004 -0.48716 -0.89996 -0.02187 -0.43542 -0.90429 -0.01077 -0.42679 -0.90564 -0.00650 -0.42399 -0.90705 -0.00088 -0.42103 -0.97622 0.01177 -0.21645 -0.97610 0.01148 -0.21702 -0.90078 -0.42872 0.06920 -0.23467 -0.90790 0.34734 -0.38011 -0.81899 0.42985 -0.93601 -0.30030 0.18358 -0.93307 -0.31049 0.18157 -0.44672 -0.25891 0.85639 -0.91709 -0.24350 0.31568 -0.93310 -0.10343 0.34443 -0.96004 0.02008 0.27915 -0.88250 -0.12152 0.45434 -0.38009 -0.21140 0.90047 -0.42098 -0.90707 0.00000 -0.90018 -0.38708 -0.19959 -0.03426 -0.99935 -0.01107 -0.22538 -0.96807 -0.10972 -0.37293 -0.91155 -0.17319 -0.57419 -0.77333 -0.26881 -0.63800 -0.71164 -0.29416 -0.84456 -0.35638 -0.39964 -0.84810 -0.34464 -0.40243 -0.86355 -0.34435 0.36838 -0.18530 -0.67765 0.71165 -0.25467 -0.63445 0.72981 -0.90722 -0.15464 0.39121 -0.38784 -0.42433 0.81824 -0.91871 -0.17172 0.35564 -0.92735 -0.05479 0.37016 -0.93552 -0.03282 0.35174 -0.21482 -0.19021 0.95795 -0.35603 -0.08683 0.93043 -0.39435 0.07911 0.91555 -0.91700 0.06187 0.39407 -0.93692 0.21779 0.27341 -0.86845 0.20847 0.44981 -0.14894 0.35590 0.92258 -0.33379 0.44138 0.83293 -0.36021 0.56509 0.74224 -0.31768 0.81062 0.49191 -0.20561 0.78621 0.58275 -0.25026 -0.96659 -0.05548 -0.57845 -0.77595 -0.25159 -0.39474 -0.91549 -0.07787 -0.90888 -0.35726 -0.21519 0.56781 0.42068 0.70755 0.65005 0.30960 0.69397 0.55491 0.39474 0.73229 0.54922 0.51733 0.65630 0.60076 0.54852 0.58157 0.55698 0.60269 0.57144 0.61845 0.64850 0.44381 0.55510 0.70789 0.43677 0.53284 0.77122 0.34829 0.59756 0.76810 0.23012 0.54172 0.81835 0.19193 0.62801 0.77595 0.05914 0.57520 0.81767 0.02395 0.54939 0.83396 -0.05174 0.55890 0.80471 -0.20017 0.57329 0.79731 -0.18879 0.55270 0.74187 -0.37967 0.57870 0.71791 -0.38692 0.53584 0.64455 -0.54537 0.59220 0.58621 -0.55286 0.52446 0.50799 -0.68329 0.59974 0.42021 -0.68098 0.61231 0.29515 -0.73346 0.44660 0.27208 -0.85236 0.64151 0.09324 -0.76143 0.34890 -0.01639 -0.93702 0.54828 -0.05448 -0.83452 0.61846 -0.15230 -0.77092 0.57573 -0.18840 -0.79564 0.55772 -0.25315 -0.79049 0.57251 -0.41398 -0.70771 0.65330 -0.30635 -0.69235 0.55497 -0.39466 -0.73229 0.54445 -0.52093 -0.65742 0.59931 -0.54924 -0.58237 0.55510 -0.60780 -0.56784 0.60235 -0.66540 -0.44092 0.55920 -0.70551 -0.43537 0.52905 -0.78549 -0.32111 0.60164 -0.76517 -0.22923 0.51993 -0.84183 -0.14491 0.59979 -0.79982 -0.02343 0.52122 -0.85185 0.05180 0.59424 -0.78264 0.18532 0.52693 -0.81228 0.25008 0.58678 -0.71281 0.38417 0.53799 -0.72414 0.43150 0.56047 -0.59595 0.57508 0.57500 -0.59530 0.56124 0.55205 -0.46385 0.69288 0.59113 -0.42336 0.68653 0.53564 -0.32596 0.77900 0.60099 -0.22961 0.76557 0.54985 -0.18593 0.81431 0.61611 -0.05445 0.78577 0.56673 -0.02406 0.82355 0.54749 0.05911 0.83473 0.61638 0.15487 0.77207 0.57784 0.18798 0.79421 0.55768 0.25377 0.79031 0.28615 0.57168 -0.76896 0.25221 0.69333 -0.67504 0.29853 0.72859 -0.61648 0.24738 0.80123 -0.54483 0.29591 0.85033 -0.43518 0.25742 0.88140 -0.39607 0.16302 0.61210 -0.77379 0.29884 0.84459 -0.44426 0.38634 0.86871 -0.30997 0.48872 0.83916 -0.23869 0.63744 0.74772 -0.18600 0.24869 -0.19671 -0.94840 0.44640 -0.49462 -0.74571 0.51486 -0.51149 -0.68796 0.94330 -0.21642 -0.25171 0.22684 -0.49176 -0.84067 0.26598 -0.45439 -0.85017 0.27274 -0.38929 -0.87981 0.24050 -0.29604 -0.92441 0.25385 -0.28080 -0.92559 0.27661 -0.18625 -0.94276 0.24507 -0.09501 -0.96484 0.31691 0.81044 0.49270 0.37341 0.86446 0.33655 0.43085 0.86208 0.26680 0.49637 0.83828 0.22561 0.57492 0.79448 0.19563 0.67028 0.72250 0.16945 0.19049 0.35601 0.91486 0.26776 0.87810 0.39655 0.22828 0.86977 0.43748 0.28427 0.79120 0.54147 0.25513 0.70166 0.66527 0.22684 0.72704 0.64805 0.27413 0.59534 0.75526 0.25735 0.49384 0.83060 0.22285 0.53449 0.81527 0.27268 0.39198 0.87863 0.23370 0.29726 0.92575 0.22680 0.30461 0.92508 0.27588 0.18904 0.94242 0.22259 0.06886 0.97248 0.23893 0.05447 0.96951 0.28081 -0.06635 0.95747 0.25066 -0.21550 0.94378 0.23221 -0.19924 0.95204 0.27893 -0.37069 0.88588 0.22242 -0.44038 0.86983 0.29208 -0.53205 0.79474 0.22553 -0.65008 0.72562 0.28908 -0.68887 0.66475 0.23735 -0.81368 0.53065 0.28072 -0.82451 0.49130 0.24869 -0.92071 0.30075 0.26912 -0.92047 0.28339 0.25181 -0.96599 0.05874 0.26130 -0.96388 0.05162 0.27659 -0.94706 -0.16302 0.23611 -0.95064 -0.20134 0.26933 -0.91432 -0.30245 0.35858 -0.86409 -0.35323 0.34344 -0.83072 -0.43812 0.48520 -0.71482 -0.50361 0.29171 -0.79734 -0.52835 0.53345 -0.61850 -0.57697 0.26348 0.11725 -0.95751 0.26850 0.11315 -0.95661 -0.00000 0.11747 -0.99308 0.00000 0.11747 -0.99308 -0.26852 0.11315 -0.95661 -0.26350 0.11725 -0.95751 -0.25596 0.36395 -0.89556 -0.26103 0.36037 -0.89554 -0.00000 0.37650 -0.92642 -0.00000 0.37650 -0.92642 0.26081 0.36347 -0.89436 0.25561 0.36091 -0.89689 -0.56332 0.10097 -0.82004 -0.56422 0.10035 -0.81950 -0.28904 0.55927 -0.77696 -0.27231 0.57408 -0.77219 -0.54728 0.31244 -0.77644 -0.55333 -0.05552 -0.83111 -0.26765 -0.09450 -0.95887 0.26778 -0.06276 -0.96143 0.27176 0.56222 -0.78106 0.00965 -0.99918 0.03933 -0.03275 -0.99542 -0.08983 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 0.00000 -0.08748 0.99617 0.00000 -0.08748 0.99617 0.40091 -0.08014 0.91261 0.17719 -0.06659 0.98192 0.90449 0.03213 0.42528 0.01521 -0.06422 0.99782 0.59085 -0.12274 0.79739 -0.80470 -0.13532 0.57805 -0.18092 -0.08603 0.97973 -0.40248 -0.06691 0.91298 0.00252 -0.06387 0.99796 -0.90452 0.03215 0.42522 + + + + + + + + + + + + + + +

3 0 0 0 1 0 2 1 3 1 1 1 4 2 0 2 3 2 3 3 5 3 4 3 4 4 5 4 6 4 4 5 6 5 7 5 4 6 7 6 8 6 9 7 4 7 8 7 8 8 10 8 9 8 9 9 10 9 11 9 12 10 9 10 11 10 13 11 12 11 11 11 14 12 13 12 11 12 14 13 11 13 15 13 16 14 14 14 15 14 15 15 17 15 16 15 16 16 17 16 18 16 19 17 16 17 18 17 18 18 20 18 19 18 21 19 19 19 20 19 22 20 23 20 24 20 25 21 24 21 23 21 23 22 26 22 25 22 27 23 25 23 26 23 26 24 28 24 27 24 29 25 27 25 28 25 28 26 30 26 29 26 31 27 29 27 30 27 30 28 32 28 31 28 31 29 32 29 33 29 34 30 31 30 33 30 32 31 35 31 33 31 35 32 37 32 33 32 47 33 48 33 49 33 50 34 49 34 48 34 48 35 51 35 50 35 52 36 50 36 51 36 51 37 53 37 52 37 54 38 52 38 53 38 53 39 55 39 54 39 56 40 54 40 55 40 57 41 58 41 59 41 60 42 59 42 58 42 58 43 61 43 60 43 62 44 60 44 61 44 61 45 63 45 62 45 64 46 62 46 63 46 65 47 21 47 66 47 65 48 66 48 67 48 65 49 67 49 68 49 69 50 65 50 68 50 19 51 21 51 65 51 65 52 70 52 19 52 16 53 19 53 70 53 70 54 71 54 16 54 14 55 16 55 71 55 71 56 72 56 14 56 13 57 14 57 72 57 72 58 73 58 13 58 12 59 13 59 73 59 73 60 74 60 12 60 9 61 12 61 74 61 74 62 75 62 9 62 4 63 9 63 75 63 75 64 76 64 4 64 0 65 4 65 76 65 77 66 0 66 76 66 1 67 0 67 77 67 77 68 78 68 1 68 2 69 1 69 78 69 78 70 79 70 2 70 80 71 81 71 82 71 83 72 81 72 80 72 80 73 84 73 83 73 96 74 93 74 91 74 91 75 92 75 97 75 59 76 96 76 91 76 57 77 59 77 91 77 97 78 57 78 91 78 98 79 81 79 83 79 98 80 83 80 84 80 98 81 84 81 99 81 98 82 99 82 100 82 101 83 98 83 100 83 82 84 81 84 98 84 102 85 95 85 94 85 94 86 103 86 102 86 85 87 102 87 103 87 103 88 86 88 85 88 90 89 104 89 89 89 105 90 89 90 104 90 104 91 106 91 105 91 107 92 105 92 106 92 106 93 108 93 107 93 109 94 107 94 108 94 108 95 110 95 109 95 111 96 109 96 110 96 110 97 112 97 111 97 113 98 111 98 112 98 112 99 114 99 113 99 115 100 113 100 114 100 114 101 116 101 115 101 117 102 115 102 116 102 2 103 98 103 3 103 2 104 82 104 98 104 118 105 119 105 57 105 97 106 118 106 57 106 120 107 119 107 118 107 118 108 121 108 120 108 122 109 120 109 121 109 98 110 101 110 122 110 121 111 98 111 122 111 95 112 123 112 92 112 124 113 6 113 5 113 124 114 5 114 3 114 124 115 3 115 123 115 123 116 95 116 102 116 124 117 123 117 102 117 102 118 85 118 124 118 7 119 6 119 124 119 124 120 85 120 125 120 125 121 8 121 7 121 124 122 125 122 7 122 10 123 8 123 125 123 89 124 105 124 127 124 128 125 17 125 15 125 127 126 128 126 15 126 128 127 127 127 105 127 105 128 107 128 128 128 18 129 17 129 128 129 129 130 20 130 18 130 128 131 129 131 18 131 128 132 107 132 109 132 129 133 128 133 109 133 109 134 111 134 129 134 21 135 20 135 129 135 66 136 21 136 129 136 67 137 66 137 129 137 129 138 111 138 113 138 67 139 129 139 113 139 115 140 68 140 67 140 113 141 115 141 67 141 115 142 117 142 68 142 123 143 118 143 97 143 123 144 97 144 92 144 121 145 118 145 123 145 123 146 3 146 121 146 98 147 121 147 3 147 133 148 131 148 132 148 134 149 135 149 133 149 132 150 134 150 133 150 136 151 135 151 134 151 137 152 138 152 136 152 134 153 137 153 136 153 139 154 138 154 137 154 137 155 140 155 139 155 141 156 139 156 140 156 140 157 142 157 141 157 143 158 141 158 142 158 142 159 56 159 143 159 144 160 143 160 56 160 117 161 116 161 145 161 55 162 68 162 117 162 55 163 117 163 145 163 145 164 116 164 146 164 145 165 146 165 144 165 145 166 144 166 56 166 56 167 55 167 145 167 69 168 68 168 55 168 147 169 148 169 69 169 55 170 147 170 69 170 149 171 148 171 147 171 147 172 150 172 149 172 151 173 149 173 150 173 150 174 152 174 151 174 151 175 152 175 153 175 154 176 151 176 153 176 153 177 155 177 154 177 156 178 154 178 155 178 155 179 157 179 156 179 37 180 35 180 158 180 158 181 159 181 37 181 37 182 159 182 160 182 39 183 37 183 160 183 160 184 161 184 39 184 41 185 39 185 161 185 161 186 162 186 41 186 43 187 41 187 162 187 162 188 163 188 43 188 43 189 163 189 164 189 45 190 43 190 164 190 164 191 165 191 45 191 46 192 45 192 165 192 165 193 166 193 46 193 44 194 46 194 166 194 166 195 167 195 44 195 42 196 44 196 167 196 167 197 168 197 42 197 40 198 42 198 168 198 168 199 169 199 40 199 40 200 169 200 170 200 38 201 40 201 170 201 170 202 171 202 38 202 36 203 38 203 171 203 171 204 172 204 36 204 36 205 172 205 173 205 36 206 173 206 174 206 34 207 36 207 174 207 51 208 48 208 175 208 175 209 177 209 51 209 53 210 51 210 177 210 177 211 178 211 53 211 55 212 53 212 178 212 147 213 55 213 178 213 150 214 147 214 178 214 152 215 150 215 178 215 153 216 152 216 178 216 178 217 155 217 153 217 179 218 69 218 148 218 179 219 148 219 149 219 179 220 149 220 151 220 179 221 151 221 154 221 156 222 179 222 154 222 69 223 179 223 180 223 65 224 69 224 180 224 180 225 181 225 65 225 70 226 65 226 181 226 181 227 182 227 70 227 71 228 70 228 182 228 182 229 183 229 71 229 71 230 183 230 184 230 72 231 71 231 184 231 184 232 185 232 72 232 72 233 185 233 174 233 73 234 72 234 174 234 174 235 173 235 73 235 73 236 173 236 172 236 74 237 73 237 172 237 172 238 171 238 74 238 74 239 171 239 170 239 75 240 74 240 170 240 170 241 169 241 75 241 76 242 75 242 169 242 169 243 168 243 76 243 77 244 76 244 168 244 168 245 167 245 77 245 78 246 77 246 167 246 167 247 166 247 78 247 79 248 78 248 166 248 166 249 165 249 79 249 80 250 79 250 165 250 165 251 164 251 80 251 84 252 80 252 164 252 164 253 163 253 84 253 162 254 99 254 84 254 163 255 162 255 84 255 100 256 99 256 162 256 161 257 122 257 101 257 161 258 101 258 100 258 162 259 161 259 100 259 120 260 122 260 161 260 160 261 57 261 119 261 160 262 119 262 120 262 161 263 160 263 120 263 58 264 57 264 160 264 160 265 159 265 58 265 61 266 58 266 159 266 159 267 158 267 61 267 61 268 158 268 126 268 185 269 34 269 174 269 34 270 185 270 184 270 31 271 34 271 184 271 184 272 183 272 31 272 29 273 31 273 183 273 183 274 182 274 29 274 29 275 182 275 181 275 27 276 29 276 181 276 181 277 180 277 27 277 25 278 27 278 180 278 180 279 179 279 25 279 24 280 25 280 179 280 179 281 156 281 24 281 24 282 156 282 157 282 22 283 24 283 157 283 22 284 157 284 155 284 23 285 22 285 155 285 155 286 178 286 23 286 26 287 23 287 178 287 178 288 177 288 26 288 28 289 26 289 177 289 177 290 175 290 28 290 28 291 175 291 176 291 30 292 28 292 176 292 32 293 30 293 130 293 186 294 187 294 188 294 188 295 189 295 186 295 186 296 189 296 190 296 191 297 186 297 190 297 190 298 192 298 191 298 193 299 191 299 192 299 192 300 194 300 193 300 195 301 193 301 194 301 196 302 195 302 194 302 194 303 197 303 196 303 198 304 196 304 197 304 197 305 199 305 198 305 198 306 199 306 200 306 198 307 200 307 201 307 202 308 198 308 201 308 201 309 203 309 202 309 202 310 203 310 204 310 205 311 202 311 204 311 206 312 207 312 205 312 204 313 206 313 205 313 208 314 209 314 210 314 210 315 211 315 208 315 212 316 208 316 211 316 211 317 213 317 212 317 214 318 212 318 213 318 213 319 215 319 214 319 216 320 214 320 215 320 215 321 217 321 216 321 216 322 217 322 218 322 219 323 216 323 218 323 217 324 220 324 218 324 221 325 219 325 218 325 220 326 222 326 218 326 223 327 221 327 218 327 224 328 223 328 218 328 222 329 224 329 218 329 225 330 223 330 224 330 224 331 226 331 225 331 227 332 225 332 226 332 226 333 228 333 227 333 229 334 227 334 228 334 228 335 230 335 229 335 231 336 229 336 230 336 230 337 232 337 231 337 146 338 233 338 144 338 144 339 233 339 234 339 144 340 234 340 187 340 235 341 144 341 187 341 187 342 186 342 235 342 236 343 235 343 186 343 186 344 191 344 236 344 237 345 236 345 191 345 191 346 193 346 237 346 238 347 237 347 193 347 193 348 195 348 238 348 239 349 238 349 195 349 195 350 196 350 239 350 240 351 239 351 196 351 196 352 198 352 240 352 241 353 240 353 198 353 198 354 202 354 241 354 242 355 241 355 202 355 202 356 205 356 242 356 243 357 242 357 205 357 205 358 207 358 243 358 244 359 243 359 207 359 207 360 206 360 244 360 244 361 206 361 245 361 246 362 244 362 245 362 245 363 247 363 246 363 248 364 246 364 247 364 247 365 245 365 249 365 250 366 251 366 252 366 250 367 252 367 253 367 250 368 253 368 248 368 250 369 248 369 247 369 249 370 250 370 247 370 206 371 204 371 249 371 245 372 206 372 249 372 204 373 203 373 257 373 258 374 103 374 94 374 258 375 94 375 257 375 257 376 203 376 201 376 258 377 257 377 201 377 86 378 103 378 258 378 201 379 200 379 258 379 258 380 200 380 199 380 258 381 199 381 197 381 258 382 197 382 256 382 258 383 256 383 86 383 93 384 257 384 94 384 257 385 249 385 204 385 59 386 259 386 96 386 260 387 96 387 259 387 259 388 261 388 260 388 262 389 260 389 261 389 261 390 263 390 262 390 262 391 263 391 250 391 249 392 262 392 250 392 190 393 264 393 192 393 265 394 104 394 90 394 265 395 90 395 264 395 265 396 264 396 190 396 106 397 104 397 265 397 190 398 189 398 265 398 265 399 189 399 188 399 266 400 265 400 188 400 266 401 108 401 106 401 265 402 266 402 106 402 110 403 108 403 266 403 188 404 187 404 266 404 266 405 187 405 234 405 233 406 266 406 234 406 233 407 112 407 110 407 266 408 233 408 110 408 114 409 112 409 233 409 233 410 146 410 114 410 116 411 114 411 146 411 93 412 96 412 260 412 262 413 93 413 260 413 262 414 257 414 93 414 262 415 249 415 257 415 225 416 267 416 268 416 225 417 268 417 269 417 225 418 269 418 223 418 270 419 267 419 225 419 225 420 227 420 270 420 271 421 270 421 227 421 229 422 272 422 271 422 227 423 229 423 271 423 273 424 272 424 229 424 229 425 231 425 273 425 133 426 273 426 231 426 232 427 131 427 133 427 231 428 232 428 133 428 132 429 131 429 232 429 230 430 274 430 132 430 232 431 230 431 132 431 275 432 274 432 230 432 230 433 228 433 275 433 276 434 275 434 228 434 228 435 226 435 276 435 277 436 276 436 226 436 226 437 224 437 277 437 222 438 255 438 277 438 224 439 222 439 277 439 220 440 254 440 255 440 220 441 255 441 222 441 278 442 254 442 220 442 217 443 279 443 278 443 220 444 217 444 278 444 279 445 217 445 280 445 215 446 281 446 282 446 215 447 282 447 280 447 217 448 215 448 280 448 250 449 281 449 215 449 215 450 213 450 250 450 283 451 250 451 213 451 211 452 284 452 283 452 213 453 211 453 283 453 285 454 284 454 211 454 211 455 210 455 285 455 286 456 285 456 210 456 210 457 209 457 286 457 287 458 286 458 209 458 209 459 208 459 287 459 288 460 287 460 208 460 208 461 212 461 288 461 289 462 288 462 212 462 214 463 290 463 289 463 212 464 214 464 289 464 291 465 290 465 214 465 214 466 216 466 291 466 292 467 291 467 216 467 216 468 219 468 292 468 293 469 292 469 219 469 221 470 294 470 293 470 219 471 221 471 293 471 295 472 294 472 221 472 223 473 296 473 295 473 221 474 223 474 295 474 269 475 296 475 223 475 276 476 277 476 50 476 50 477 52 477 276 477 275 478 276 478 52 478 52 479 54 479 275 479 274 480 275 480 54 480 54 481 56 481 274 481 274 482 56 482 142 482 274 483 142 483 140 483 274 484 140 484 137 484 274 485 137 485 134 485 132 486 274 486 134 486 259 487 59 487 281 487 261 488 259 488 281 488 263 489 261 489 281 489 281 490 250 490 263 490 60 491 282 491 281 491 59 492 60 492 281 492 280 493 282 493 60 493 62 494 279 494 280 494 60 495 62 495 280 495 278 496 279 496 62 496 62 497 64 497 278 497 141 498 143 498 273 498 139 499 141 499 273 499 138 500 139 500 273 500 136 501 138 501 273 501 135 502 136 502 273 502 273 503 133 503 135 503 143 504 144 504 273 504 272 505 273 505 144 505 144 506 235 506 272 506 271 507 272 507 235 507 236 508 270 508 271 508 235 509 236 509 271 509 267 510 270 510 236 510 237 511 268 511 267 511 236 512 237 512 267 512 269 513 268 513 237 513 238 514 296 514 269 514 237 515 238 515 269 515 295 516 296 516 238 516 239 517 294 517 295 517 238 518 239 518 295 518 293 519 294 519 239 519 240 520 292 520 293 520 239 521 240 521 293 521 291 522 292 522 240 522 240 523 241 523 291 523 290 524 291 524 241 524 241 525 242 525 290 525 289 526 290 526 242 526 242 527 243 527 289 527 288 528 289 528 243 528 243 529 244 529 288 529 287 530 288 530 244 530 246 531 286 531 287 531 244 532 246 532 287 532 285 533 286 533 246 533 246 534 248 534 285 534 285 535 248 535 253 535 284 536 285 536 253 536 253 537 252 537 284 537 284 538 252 538 251 538 283 539 284 539 251 539 283 540 251 540 250 540 64 541 255 541 254 541 64 542 88 542 255 542 64 543 87 543 88 543 63 544 87 544 64 544 63 545 130 545 87 545 63 546 126 546 130 546 47 547 87 547 176 547 87 548 130 548 176 548 47 549 88 549 87 549 47 550 49 550 88 550 49 551 255 551 88 551 49 552 277 552 255 552 32 553 126 553 35 553 32 554 130 554 126 554 47 555 175 555 48 555 47 556 176 556 175 556 30 557 176 557 130 557 35 558 126 558 158 558 61 559 126 559 63 559 64 560 254 560 278 560 49 561 50 561 277 561 2 562 79 562 82 562 79 563 80 563 82 563 91 564 93 564 94 564 91 565 95 565 92 565 91 566 94 566 95 566 33 567 45 567 46 567 33 568 46 568 44 568 33 569 44 569 42 569 33 570 42 570 40 570 33 571 40 571 38 571 33 572 38 572 36 572 34 573 33 573 36 573 33 574 43 574 45 574 33 575 39 575 41 575 33 576 41 576 43 576 37 577 39 577 33 577 86 578 90 578 89 578 85 579 86 579 89 579 85 580 89 580 125 580 89 581 127 581 125 581 10 582 125 582 11 582 11 583 125 583 127 583 11 584 127 584 15 584 192 585 264 585 194 585 86 586 264 586 90 586 86 587 256 587 264 587 194 588 264 588 256 588 194 589 256 589 197 589

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_middle/f_middle_C6M2.dae b/URDFs/sr_description/meshes/components/f_middle/f_middle_C6M2.dae new file mode 100644 index 0000000..7385453 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_middle/f_middle_C6M2.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:44.246463 + 2012-07-23T02:15:44.246477 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -5.15497 -5.65164 5.67687 -6.98593 -7.50773 8.86243 -8.01397 -5.97789 7.98236 -8.48097 -4.31842 6.98785 -8.50017 0.02188 5.46986 -8.50017 -3.88961 12.77786 -8.48937 -3.70556 18.59785 -8.50017 0.02188 20.53786 -8.22567 3.73770 21.84346 -3.50017 7.97965 1.21886 -3.50017 7.04980 24.44685 3.49296 7.97965 1.21886 3.49983 7.04980 24.44685 -4.29807 7.00277 24.01886 -4.75757 7.78174 2.14586 -6.73177 6.68550 2.87236 -6.31127 6.25102 22.77386 -7.75257 5.53448 3.44444 -7.62757 4.93940 22.20461 -8.42967 3.69429 4.18787 -3.43169 -8.64405 15.62886 -3.50017 -8.93332 12.68886 3.42448 -8.64405 15.62886 3.49296 -8.93332 12.68886 -3.50017 -8.97607 9.81386 3.49296 -8.97607 9.81386 -6.41337 -7.45056 17.15486 -4.73277 -7.88683 17.09686 -7.46427 -4.93237 19.65934 -4.00017 -5.21445 19.76886 3.99983 -5.21445 19.76886 -3.50017 -8.70539 8.82587 -4.00017 -5.82319 5.84886 3.99983 -5.82319 5.84886 3.49296 -8.70539 8.82587 4.48796 -5.61710 20.77286 -8.11957 -5.83721 12.86186 -7.03567 -7.45782 12.93086 -7.07657 -7.15262 16.53586 -8.02707 -5.46231 17.55201 -5.41357 -8.54068 12.82830 -5.52640 -8.05887 15.99102 -5.66907 -8.47778 9.50586 -4.49517 -5.61710 20.77286 4.75036 -6.43800 22.17986 4.75723 -6.97321 25.88187 4.75723 -6.48965 27.70586 4.75723 -4.19093 30.65686 4.75723 -2.54057 31.57185 4.75723 1.17980 31.95786 4.75723 2.98301 31.40186 4.75723 4.57411 30.38686 4.75723 6.68716 27.30086 4.75723 7.05771 25.45087 -4.75757 -6.43800 22.17986 -4.75757 -6.97321 25.88187 -4.75757 -6.48965 27.70586 -4.75757 -4.19093 30.65686 -4.75757 -2.54057 31.57185 -4.75757 1.17980 31.95786 -4.75757 2.98301 31.40186 -4.75757 4.57411 30.38686 -4.75757 6.68716 27.30086 -4.75757 7.05771 25.45087 -5.90557 -6.46749 22.90086 -5.90557 -6.71430 26.07986 -5.87887 -4.67070 29.33165 -5.90557 -3.05930 31.08986 -5.90557 0.04375 31.82587 -5.90557 3.14202 31.06985 -5.90557 5.55840 28.98886 -5.90557 6.76483 26.03687 -8.77364 -3.34911 22.56881 -8.45003 -3.33963 20.40928 -8.99996 -3.58678 25.82197 -8.99996 -2.60559 27.58099 -8.12147 0.02188 29.93286 -8.99996 3.11434 27.46986 -8.12147 4.95033 25.05086 -9.00000 0.02188 28.72610 -8.99996 3.87812 25.23030 -9.00019 0.02642 23.15286 -6.87887 -6.81239 2.17687 -6.52396 -4.86510 5.63609 -4.75757 -7.07768 3.79886 -4.75757 -7.78383 1.97186 -6.87887 -6.53824 -2.89314 -4.75757 -8.02808 0.02885 -4.75757 -7.79600 -1.91515 -6.87887 -5.85402 -4.57393 -4.75757 -5.98513 -5.35513 -6.40557 -4.61815 -6.29314 -4.75757 -4.51347 -6.64714 -5.90557 -1.56868 -7.33768 -4.75757 -2.77352 -7.54514 -5.90557 1.77076 -7.62013 -4.75757 1.09010 -7.97514 -4.75757 2.98490 -7.48114 -5.90557 4.79136 -6.19514 -4.75757 4.70447 -6.54414 -6.87887 3.66948 -6.17014 -5.90557 6.94247 -3.64114 -4.75757 6.14692 -5.22014 -4.75757 7.22694 -3.58614 -8.12147 6.00887 0.10429 -5.90557 7.63414 -0.42213 -4.75757 7.88062 -1.74014 4.75723 -7.07768 3.79886 4.75723 -7.78383 1.97186 4.75723 -8.02808 0.02885 4.75723 -7.79600 -1.91515 4.75723 -5.98513 -5.35513 4.75723 -4.51347 -6.64714 4.75723 -2.77352 -7.54514 4.75723 1.09010 -7.97514 4.75723 2.98490 -7.48114 4.75723 4.70447 -6.54414 4.75723 6.14692 -5.22014 4.75723 7.22694 -3.58614 4.75723 7.88062 -1.74014 -7.87887 -5.40786 2.46296 -8.50000 -3.55834 4.34187 -9.00000 -3.59913 -1.17314 -9.00000 -2.21603 -3.07614 -9.00000 0.02188 4.39287 -9.00000 0.02188 -4.58014 -9.00000 2.25979 -3.07614 -9.00000 3.74480 -1.09914 -8.12147 1.63616 -5.70114 -8.12147 -5.89100 -0.42914 -6.87887 -7.13355 0.48087 -8.12147 -5.60089 -1.87614 -8.12100 -4.85241 -4.18614 -8.12147 -1.44278 -5.74113 -8.12100 5.47326 -2.53608 -8.12100 4.61814 -4.13956 -6.75466 -5.90532 3.90648 -8.45823 -3.70615 5.68876 -8.12100 -3.83817 28.38669 -8.12100 -4.78404 25.94850 -8.12100 -3.16487 29.14326 -7.96933 -4.72890 22.71507 -8.12100 3.99730 28.01863 -8.12100 3.12703 29.12051 8.11379 3.12703 29.12051 8.11379 3.99730 28.01863 7.96212 -4.72890 22.71507 8.11379 -3.16488 29.14326 8.11379 -4.78404 25.94850 8.11379 -3.83817 28.38669 8.45102 -3.70615 5.68876 6.74746 -5.90533 3.90648 8.11379 4.61814 -4.13956 8.11379 5.47326 -2.53608 8.11426 -1.44278 -5.74114 8.11379 -4.85241 -4.18614 8.11426 -5.60089 -1.87615 6.87166 -7.13355 0.48086 8.11426 -5.89100 -0.42914 8.11426 1.63616 -5.70114 9.00000 3.74480 -1.09914 9.00000 2.25979 -3.07614 9.00000 0.02188 -4.58014 9.00000 0.02188 4.39287 9.00000 -2.21603 -3.07614 9.00000 -3.59913 -1.17314 8.49279 -3.55834 4.34187 7.87166 -5.40786 2.46296 5.89836 7.63414 -0.42213 8.11426 6.00887 0.10428 5.89836 6.94247 -3.64114 6.87166 3.66948 -6.17014 5.89836 4.79136 -6.19515 5.89836 1.77076 -7.62013 5.89836 -1.56868 -7.33768 6.39836 -4.61815 -6.29314 6.87166 -5.85402 -4.57393 6.87166 -6.53824 -2.89314 6.51675 -4.86510 5.63609 6.87166 -6.81239 2.17686 9.00019 0.02642 23.15286 8.99996 3.87812 25.23030 9.00000 0.02188 28.72610 8.11426 4.95033 25.05086 8.99996 3.11434 27.46986 8.11426 0.02188 29.93286 8.99996 -2.60559 27.58099 8.99996 -3.58678 25.82197 8.44282 -3.33963 20.40928 8.76643 -3.34911 22.56881 5.89836 6.76483 26.03687 5.89836 5.55840 28.98886 5.89836 3.14202 31.06985 5.89836 0.04374 31.82587 5.89836 -3.05930 31.08986 5.87166 -4.67070 29.33165 5.89836 -6.71430 26.07986 5.89836 -6.46749 22.90086 5.66186 -8.47778 9.50586 5.51919 -8.05887 15.99102 5.40636 -8.54068 12.82830 8.01986 -5.46231 17.55201 7.06936 -7.15262 16.53586 7.02846 -7.45782 12.93086 8.11236 -5.83721 12.86186 7.45706 -4.93237 19.65934 4.72556 -7.88683 17.09686 6.40616 -7.45056 17.15486 8.42246 3.69429 4.18787 7.62036 4.93940 22.20461 7.74536 5.53448 3.44444 6.30406 6.25102 22.77386 6.72456 6.68550 2.87236 4.75036 7.78174 2.14586 4.29086 7.00277 24.01886 8.21846 3.73770 21.84346 8.49296 0.02188 20.53786 8.48216 -3.70556 18.59785 8.49296 -3.88961 12.77786 8.49296 0.02188 5.46986 8.47376 -4.31842 6.98785 8.00676 -5.97789 7.98236 6.97873 -7.50773 8.86243 5.14776 -5.65164 5.67686 + + + + + + + + + + -0.43084 -0.64978 -0.62623 -0.99998 -0.00544 -0.00291 -0.99999 0.00327 0.00175 -1.00000 -0.00290 0.00000 -0.99728 0.07367 0.00000 0.00000 0.99920 0.04000 0.00000 0.99920 0.04000 -0.08009 0.99599 0.03987 -0.12798 0.99105 0.03798 -0.47339 0.87988 0.04128 -0.36485 0.93065 0.02803 -0.74029 0.67160 0.03030 -0.71143 0.70224 0.02702 -0.89745 0.44067 0.01996 -0.93713 0.34885 0.00997 -0.99966 0.02320 0.01149 -0.00000 -0.99519 0.09792 -0.00000 -0.99519 0.09792 -0.00000 -0.99989 0.01487 -0.00000 -0.99989 0.01487 -0.16644 -0.72939 0.66354 -0.07913 -0.69391 0.71570 0.29821 -0.71453 0.63287 -0.00000 -0.77008 0.63794 0.00000 -0.77008 0.63794 -0.26673 -0.75814 -0.59504 -0.00321 -0.71872 -0.69529 -0.00000 -0.71845 -0.69557 -0.00000 -0.71845 -0.69557 -0.96497 -0.26186 0.01619 -0.98119 -0.19242 -0.01569 -0.82951 -0.55849 -0.00185 -0.83115 -0.55604 -0.00334 -0.47043 -0.87472 0.11647 -0.55126 -0.83186 0.06417 -0.59392 -0.80452 0.00261 -0.55384 -0.83219 0.02684 -0.22374 -0.97465 -0.00125 -0.24438 -0.95988 0.13751 -0.19296 -0.97604 0.10053 -0.19998 -0.97969 0.01457 -0.00000 -0.92814 -0.37223 -0.00000 -0.86374 -0.50394 -0.00000 -0.98971 -0.14308 0.00000 -0.98971 -0.14309 0.00000 -0.96661 0.25626 0.00000 -0.96661 0.25626 0.00000 -0.78890 0.61452 0.00000 -0.78890 0.61452 0.00000 -0.48488 0.87458 0.00000 -0.48488 0.87458 0.00000 -0.10320 0.99466 0.00000 -0.10320 0.99466 -0.00000 0.29465 0.95561 -0.00000 0.29465 0.95561 -0.00000 0.53781 0.84307 0.00000 0.53781 0.84307 0.00000 0.82511 0.56497 0.00000 0.82511 0.56497 0.00000 0.98052 0.19640 0.00000 0.98052 0.19640 0.00000 0.99997 -0.00788 0.00000 0.99997 -0.00788 -0.03267 0.99827 -0.04878 -0.00952 -0.86293 -0.50524 -0.19191 -0.91946 -0.34316 -0.06431 -0.98766 -0.14279 -0.23172 -0.96986 -0.07530 -0.17124 -0.95233 0.25247 -0.51028 -0.72626 0.46061 -0.36232 -0.73530 0.57277 -0.43045 -0.66867 0.60630 -0.14650 -0.47965 0.86514 -0.29107 -0.22079 0.93088 -0.01223 -0.10319 0.99459 -0.37255 0.27344 0.88681 -0.24082 0.23008 0.94290 -0.16695 0.53026 0.83123 -0.34141 0.61335 0.71220 0.01944 0.82495 0.56486 -0.33363 0.87264 0.35663 -0.14825 0.96969 0.19423 -0.30923 0.94131 -0.13534 -0.28461 0.95178 -0.11449 -0.86952 -0.47582 -0.13239 -0.63819 -0.17768 0.74910 -0.63970 0.18221 0.74671 -0.67957 0.67909 0.27753 -0.62051 0.78284 -0.04612 -0.67429 0.72869 -0.11980 -0.73664 0.64008 0.21829 -0.77390 0.60030 -0.20181 -0.86584 0.47665 -0.15208 -0.97286 0.13731 -0.18626 -0.96646 0.12196 -0.22601 -1.00000 -0.00003 0.00003 -1.00000 -0.00004 0.00003 -0.98891 -0.00908 -0.14823 -0.98167 -0.03342 -0.18765 -0.99584 -0.05416 -0.07324 -0.36521 -0.86832 0.33561 -0.22066 -0.86307 -0.45434 -0.35140 -0.86713 -0.35299 -0.27065 -0.74481 -0.60993 -0.11867 -0.65509 -0.74618 -0.14801 0.24950 -0.95700 -0.22483 0.46623 -0.85562 -0.32338 0.40374 -0.85582 -0.45787 0.37931 -0.80404 -0.66821 0.56903 -0.47927 -0.17026 0.66634 -0.72595 -0.33540 0.72055 -0.60689 -0.17744 0.82100 -0.54265 -0.60860 0.77577 -0.16669 -0.16759 0.98511 0.03825 -0.00000 -0.96446 -0.26423 0.00000 -0.85296 0.52197 0.00000 -0.85296 0.52197 0.00000 -0.93275 0.36052 0.00000 -0.93275 0.36052 0.00000 -0.99219 0.12473 0.00000 -0.99219 0.12473 -0.00000 -0.99295 -0.11854 -0.00000 -0.99295 -0.11854 -0.00000 -0.88488 -0.46582 -0.00000 -0.88488 -0.46582 -0.00000 -0.65975 -0.75149 -0.00000 -0.65975 -0.75149 -0.00000 -0.45863 -0.88863 -0.00000 -0.45863 -0.88863 -0.00000 -0.11061 -0.99386 -0.00000 -0.11061 -0.99386 -0.00000 0.25228 -0.96765 -0.00000 0.25228 -0.96765 -0.00000 0.47848 -0.87810 -0.00000 0.47848 -0.87810 -0.00000 0.67621 -0.73671 -0.00000 0.67621 -0.73671 -0.00000 0.83424 -0.55140 -0.00000 0.83424 -0.55140 -0.00000 0.94264 -0.33380 -0.00000 0.94264 -0.33380 -0.00000 0.99944 -0.03345 0.00000 0.99944 -0.03345 -0.26643 -0.75723 -0.59634 -0.91489 -0.39448 0.08586 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -0.00000 -0.96446 -0.26423 -0.90158 0.24131 -0.35907 -0.90485 0.39604 0.15618 -0.94467 0.31082 0.10487 -0.89506 0.16219 0.41539 -0.74557 -0.65479 0.12399 -0.65095 -0.74758 -0.13190 -0.66918 -0.72860 -0.14608 -0.69626 -0.68280 -0.22138 -0.65402 -0.70065 -0.28522 -0.61787 -0.54789 -0.56396 -0.58197 -0.17649 -0.79382 -0.58414 0.01054 -0.81158 -0.65108 -0.06397 -0.75631 -0.64549 0.22621 -0.72950 -0.55447 0.81322 0.17674 -0.74717 0.66462 0.00400 -0.18101 -0.94853 -0.25987 -0.93915 -0.31722 0.13177 -0.92258 -0.37827 -0.07584 -0.92388 -0.36399 -0.11813 -0.95364 -0.24345 -0.17694 -0.89678 -0.24681 -0.36724 -0.79257 0.00792 -0.60973 -0.99956 -0.01586 0.02491 -0.81387 -0.56586 0.13199 0.00000 -0.92814 -0.37223 -0.84513 -0.41959 0.33122 -0.69413 -0.63215 0.34435 -0.66502 -0.62224 0.41300 -0.47825 -0.87339 0.09202 -0.22907 -0.92338 0.30805 -0.20936 -0.93219 0.29528 -0.06197 -0.91543 -0.39768 -0.44992 -0.87948 -0.15518 -0.40578 -0.90753 -0.10834 -0.36482 -0.92381 0.11613 -0.39655 -0.90198 0.17080 -0.72765 -0.28472 -0.62407 -0.92274 -0.16003 -0.35062 -0.78720 -0.59414 0.16529 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.98151 0.15842 0.10739 -0.89920 -0.13152 0.41731 -0.98615 -0.13901 0.09043 -0.91814 0.18394 -0.35098 -0.73800 0.31314 -0.59774 -0.51084 0.61558 -0.60008 -0.63402 0.68235 -0.36389 -0.59956 0.78433 -0.15921 -0.91399 0.39761 -0.08082 -0.96554 -0.26005 0.01002 -0.98113 -0.19024 0.03456 -0.85485 -0.51561 0.05807 -0.83137 -0.55445 0.03751 -0.14858 0.98885 0.00958 -0.43892 0.88671 0.14525 -0.57656 -0.53325 -0.61905 -0.39080 -0.71053 -0.58517 -0.44124 -0.74181 0.50500 -0.37160 -0.81095 0.45197 -0.72353 -0.58860 0.36064 -0.75356 -0.51410 0.40970 -0.67246 -0.62637 0.39428 -0.99951 -0.00949 0.02996 -0.99965 -0.01262 -0.02345 -0.48297 -0.78878 -0.38022 -0.51397 -0.85427 -0.07781 -0.45695 -0.75232 0.47457 -0.20294 -0.80005 0.56457 -1.00000 0.00005 0.00002 -1.00000 0.00003 0.00003 -0.64042 -0.76606 -0.05484 -0.85396 -0.50916 -0.10724 -0.86063 -0.50687 -0.04901 -0.79753 -0.56244 0.21819 -0.85811 -0.44842 0.25013 -0.85616 -0.38599 0.34351 -0.64381 -0.18412 0.74270 -0.64894 0.19266 0.73604 -0.76162 0.50854 0.40165 -0.75386 0.62553 0.20099 -0.62699 0.74169 0.23828 -0.63612 0.60551 0.47824 -0.55727 0.54184 0.62917 -0.48481 -0.64844 0.58693 -0.48698 -0.65246 0.58064 -0.47463 -0.74348 0.47114 -0.64037 -0.71607 0.27779 -0.79712 -0.59566 -0.09897 -0.65381 -0.75439 -0.05857 -0.64141 -0.76598 -0.04315 -0.92870 0.32722 -0.17450 -0.94438 0.26293 -0.19750 -0.88324 -0.18735 0.42986 -0.79998 -0.14442 0.58239 -0.79902 0.15230 0.58169 -0.86767 0.18711 0.46059 -0.33715 -0.07934 -0.93810 -0.28355 -0.10607 -0.95307 -0.40679 -0.23563 -0.88261 -0.15968 -0.45274 -0.87723 -0.21262 0.92109 -0.32617 -0.41120 0.89121 -0.19149 0.41325 0.89030 -0.19130 0.21384 0.92084 -0.32608 0.16033 -0.45269 -0.87713 0.40856 -0.23510 -0.88193 0.28512 -0.10602 -0.95261 0.33894 -0.07929 -0.93746 0.86591 0.18827 0.46342 0.79665 0.15309 0.58473 0.79762 -0.14517 0.58543 0.88165 -0.18855 0.43260 0.94354 0.26485 -0.19894 0.92765 0.32953 -0.17573 0.64141 -0.76598 -0.04315 0.65381 -0.75439 -0.05857 0.79456 -0.59876 -0.10078 0.64037 -0.71607 0.27779 0.47463 -0.74348 0.47114 0.48698 -0.65246 0.58064 0.48481 -0.64844 0.58693 0.55727 0.54184 0.62917 0.63612 0.60551 0.47824 0.62699 0.74169 0.23828 0.75120 0.62843 0.20193 0.75900 0.51095 0.40355 0.64894 0.19266 0.73604 0.64381 -0.18412 0.74270 0.85428 -0.38831 0.34557 0.85625 -0.45112 0.25164 0.79515 -0.56536 0.21933 0.86063 -0.50687 -0.04901 0.85396 -0.50916 -0.10724 0.64042 -0.76606 -0.05484 1.00000 0.00003 0.00003 1.00000 0.00005 0.00002 0.20411 -0.79963 0.56474 0.45858 -0.75108 0.47496 0.51397 -0.85427 -0.07781 0.48297 -0.78878 -0.38022 0.99965 -0.01262 -0.02345 0.99951 -0.00949 0.02996 0.67246 -0.62637 0.39428 0.75356 -0.51409 0.40970 0.72353 -0.58860 0.36064 0.37160 -0.81095 0.45197 0.44124 -0.74181 0.50500 0.39080 -0.71053 -0.58517 0.57656 -0.53325 -0.61905 0.43892 0.88671 0.14525 0.14858 0.98885 0.00958 0.83138 -0.55444 0.03751 0.85485 -0.51561 0.05807 0.98113 -0.19024 0.03456 0.96554 -0.26005 0.01002 0.91275 0.40033 -0.08137 0.59956 0.78433 -0.15921 0.63402 0.68235 -0.36389 0.51084 0.61559 -0.60008 0.73800 0.31314 -0.59774 0.91695 0.18521 -0.35340 0.98576 -0.14096 0.09170 0.89670 -0.13305 0.42216 0.98106 0.16035 0.10870 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 0.78720 -0.59414 0.16529 0.92162 -0.16115 -0.35307 0.72765 -0.28472 -0.62407 0.39764 -0.90152 0.17072 0.36584 -0.92341 0.11608 0.40688 -0.90704 -0.10829 0.45108 -0.87891 -0.15507 0.06211 -0.91555 -0.39738 0.20937 -0.93219 0.29528 0.22907 -0.92338 0.30805 0.47825 -0.87339 0.09202 0.66502 -0.62224 0.41300 0.69413 -0.63215 0.34435 0.84513 -0.41959 0.33122 0.81387 -0.56586 0.13199 0.99956 -0.01586 0.02491 0.79015 0.00796 -0.61286 0.89534 -0.24843 -0.36966 0.95292 -0.24527 -0.17826 0.92277 -0.36653 -0.11895 0.92145 -0.38091 -0.07637 0.93826 -0.31972 0.13212 0.18102 -0.94853 -0.25987 0.74717 0.66462 0.00400 0.55447 0.81322 0.17674 0.64549 0.22621 -0.72950 0.65108 -0.06397 -0.75631 0.58414 0.01054 -0.81158 0.58197 -0.17649 -0.79382 0.61787 -0.54789 -0.56396 0.65402 -0.70064 -0.28522 0.69626 -0.68280 -0.22138 0.66918 -0.72860 -0.14608 0.65095 -0.74757 -0.13190 0.74557 -0.65479 0.12399 0.89253 0.16382 0.42019 0.94386 0.31286 0.10609 0.90485 0.39604 0.15618 0.90019 0.24292 -0.36146 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 0.91435 -0.39547 0.08702 0.26643 -0.75723 -0.59634 0.16796 0.98503 0.03880 0.60860 0.77577 -0.16669 0.17848 0.82084 -0.54255 0.33719 0.72006 -0.60647 0.17126 0.66622 -0.72582 0.66821 0.56903 -0.47927 0.45787 0.37931 -0.80404 0.32512 0.40348 -0.85528 0.22611 0.46609 -0.85536 0.14888 0.24947 -0.95687 0.11916 -0.65505 -0.74613 0.27151 -0.74449 -0.60993 0.35239 -0.86678 -0.35285 0.22134 -0.86293 -0.45426 0.36624 -0.86795 0.33547 0.99558 -0.05587 -0.07555 0.98111 -0.03503 -0.19024 0.98891 -0.00908 -0.14823 1.00000 -0.00004 0.00003 1.00000 -0.00003 0.00003 0.96587 0.12301 -0.22797 0.97224 0.13817 -0.18882 0.86584 0.47665 -0.15208 0.77133 0.60319 -0.20299 0.73388 0.64292 0.21926 0.67428 0.72869 -0.11980 0.62051 0.78284 -0.04612 0.67957 0.67909 0.27753 0.63970 0.18221 0.74671 0.63819 -0.17768 0.74910 0.86952 -0.47582 -0.13239 0.28461 0.95178 -0.11449 0.31198 0.94006 -0.13767 0.14912 0.96956 0.19420 0.33541 0.87206 0.35639 -0.01956 0.82495 0.56486 0.34323 0.61292 0.71170 0.16792 0.53017 0.83109 0.24219 0.23000 0.94257 0.37448 0.27321 0.88607 0.01231 -0.10319 0.99459 0.29267 -0.22068 0.93040 0.14736 -0.47959 0.86503 0.43258 -0.66793 0.60559 0.36425 -0.73470 0.57230 0.51256 -0.72510 0.45990 0.17223 -0.95216 0.25243 0.23304 -0.96955 -0.07527 0.06438 -0.98764 -0.14290 0.19191 -0.91946 -0.34316 0.00953 -0.86293 -0.50524 0.03284 0.99826 -0.04900 0.19998 -0.97969 0.01457 0.19296 -0.97604 0.10053 0.24438 -0.95988 0.13751 0.22374 -0.97465 -0.00125 0.55384 -0.83219 0.02684 0.59392 -0.80452 0.00261 0.55126 -0.83186 0.06417 0.47043 -0.87472 0.11647 0.83115 -0.55603 -0.00334 0.82951 -0.55848 -0.00185 0.98119 -0.19242 -0.01569 0.96497 -0.26186 0.01619 0.00323 -0.71872 -0.69529 0.26673 -0.75814 -0.59504 -0.29870 -0.71412 0.63309 0.07929 -0.69398 0.71562 0.16644 -0.72939 0.66354 0.99966 0.02320 0.01149 0.93713 0.34885 0.00997 0.89745 0.44067 0.01996 0.71143 0.70224 0.02702 0.74029 0.67160 0.03030 0.36484 0.93065 0.02803 0.47339 0.87988 0.04128 0.12798 0.99105 0.03798 0.08078 0.99594 0.03984 0.99728 0.07367 -0.00000 1.00000 -0.00290 -0.00000 0.99999 0.00327 0.00175 0.99998 -0.00544 -0.00291 0.43085 -0.64977 -0.62623 -0.00000 -0.86374 -0.50394 + + + + + + + + + + + + + + +

0 0 1 0 2 0 4 1 3 1 5 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 4 4 7 4 9 5 10 5 11 5 12 6 11 6 10 6 13 7 10 7 9 7 13 8 9 8 14 8 14 9 15 9 13 9 16 10 13 10 15 10 15 11 17 11 16 11 18 12 16 12 17 12 8 13 18 13 17 13 17 14 19 14 8 14 19 15 4 15 8 15 20 16 21 16 22 16 23 17 22 17 21 17 21 18 24 18 23 18 25 19 23 19 24 19 26 20 27 20 28 20 29 21 28 21 27 21 27 22 20 22 29 22 29 23 20 23 22 23 30 24 29 24 22 24 1 25 0 25 31 25 0 26 32 26 31 26 33 27 34 27 31 27 32 28 33 28 31 28 5 29 3 29 2 29 36 30 5 30 2 30 36 31 2 31 1 31 37 32 36 32 1 32 40 33 41 33 38 33 37 34 40 34 38 34 37 35 1 35 42 35 40 36 37 36 42 36 42 37 24 37 40 37 20 38 41 38 40 38 40 39 21 39 20 39 40 40 24 40 21 40 35 41 43 41 29 41 43 42 44 42 54 42 44 43 45 43 54 43 55 44 54 44 45 44 45 45 46 45 55 45 56 46 55 46 46 46 46 47 47 47 56 47 57 48 56 48 47 48 47 49 48 49 57 49 58 50 57 50 48 50 48 51 49 51 58 51 59 52 58 52 49 52 49 53 50 53 59 53 60 54 59 54 50 54 50 55 51 55 60 55 61 56 60 56 51 56 51 57 52 57 61 57 62 58 61 58 52 58 52 59 53 59 62 59 63 60 62 60 53 60 12 61 63 61 53 61 63 62 12 62 10 62 63 63 10 63 13 63 28 64 43 64 54 64 64 65 28 65 54 65 64 66 54 66 55 66 65 67 64 67 55 67 55 68 56 68 65 68 66 69 65 69 56 69 66 70 56 70 57 70 67 71 66 71 57 71 57 72 58 72 67 72 68 73 67 73 58 73 58 74 59 74 68 74 68 75 59 75 60 75 69 76 68 76 60 76 60 77 61 77 69 77 70 78 69 78 61 78 61 79 62 79 70 79 71 80 70 80 62 80 62 81 63 81 71 81 71 82 63 82 13 82 71 83 13 83 16 83 72 84 73 84 28 84 67 85 68 85 76 85 68 86 69 86 76 86 70 87 71 87 78 87 71 88 16 88 78 88 18 89 78 89 16 89 80 90 77 90 78 90 8 91 80 91 78 91 78 92 18 92 8 92 8 93 7 93 81 93 8 94 81 94 80 94 75 95 79 95 81 95 74 96 75 96 81 96 72 97 7 97 73 97 7 98 72 98 81 98 74 99 81 99 72 99 85 100 84 100 82 100 89 101 90 101 88 101 86 102 89 102 88 102 89 103 91 103 90 103 92 104 90 104 91 104 97 105 96 105 95 105 98 106 99 106 97 106 95 107 98 107 97 107 98 108 95 108 100 108 100 109 101 109 98 109 102 110 99 110 98 110 98 111 101 111 102 111 103 112 102 112 101 112 105 113 101 113 104 113 9 114 106 114 105 114 34 115 25 115 31 115 84 116 33 116 32 116 33 117 84 117 107 117 84 118 85 118 107 118 108 119 107 119 85 119 85 120 87 120 108 120 109 121 108 121 87 121 87 122 88 122 109 122 110 123 109 123 88 123 88 124 90 124 110 124 111 125 110 125 90 125 90 126 92 126 111 126 112 127 111 127 92 127 92 128 94 128 112 128 113 129 112 129 94 129 94 130 96 130 113 130 114 131 113 131 96 131 96 132 97 132 114 132 115 133 114 133 97 133 97 134 99 134 115 134 116 135 115 135 99 135 99 136 102 136 116 136 117 137 116 137 102 137 102 138 103 138 117 138 118 139 117 139 103 139 103 140 106 140 118 140 119 141 118 141 106 141 106 142 9 142 119 142 11 143 119 143 9 143 1 144 31 144 42 144 120 145 121 145 122 145 123 146 122 146 124 146 125 147 123 147 124 147 24 148 31 148 25 148 126 149 128 149 125 149 104 150 19 150 17 150 104 151 127 151 19 151 19 152 124 152 4 152 130 153 82 153 129 153 86 154 130 154 129 154 129 155 131 155 86 155 131 156 132 156 86 156 89 157 86 157 132 157 91 158 89 158 132 158 93 159 91 159 133 159 133 160 128 160 93 160 95 161 93 161 128 161 100 162 95 162 128 162 104 163 17 163 105 163 15 164 105 164 17 164 24 165 42 165 31 165 120 166 122 166 129 166 131 167 129 167 122 167 122 168 132 168 131 168 122 169 123 169 132 169 123 170 125 170 133 170 128 171 133 171 125 171 6 172 73 172 7 172 6 173 28 173 73 173 30 174 35 174 29 174 6 175 39 175 28 175 26 176 28 176 39 176 39 177 38 177 26 177 41 178 26 178 38 178 27 179 26 179 41 179 41 180 20 180 27 180 29 181 43 181 28 181 86 182 88 182 130 182 87 183 130 183 88 183 85 184 130 184 87 184 82 185 130 185 85 185 91 186 132 186 133 186 123 187 133 187 132 187 82 188 120 188 129 188 124 189 126 189 125 189 124 190 127 190 126 190 19 191 127 191 124 191 4 192 124 192 121 192 121 193 124 193 122 193 126 194 135 194 128 194 135 195 100 195 128 195 100 196 135 196 101 196 134 197 101 197 135 197 101 198 134 198 104 198 134 199 127 199 104 199 5 200 39 200 6 200 5 201 36 201 39 201 36 202 38 202 39 202 36 203 37 203 38 203 9 204 105 204 14 204 14 205 105 205 15 205 2 206 3 206 83 206 0 207 2 207 83 207 136 208 0 208 83 208 82 209 0 209 136 209 82 210 136 210 120 210 136 211 83 211 120 211 83 212 121 212 120 212 121 213 137 213 4 213 137 214 3 214 4 214 3 215 137 215 83 215 137 216 121 216 83 216 0 217 82 217 84 217 0 218 84 218 32 218 77 219 80 219 81 219 77 220 81 220 79 220 64 221 141 221 28 221 141 222 72 222 28 222 139 223 72 223 141 223 138 224 74 224 139 224 74 225 138 225 75 225 140 226 75 226 138 226 140 227 67 227 76 227 69 228 143 228 76 228 142 229 77 229 143 229 77 230 142 230 78 230 142 231 70 231 78 231 70 232 142 232 143 232 70 233 143 233 69 233 67 234 140 234 66 234 140 235 138 235 66 235 66 236 138 236 65 236 138 237 139 237 65 237 72 238 139 238 74 238 65 239 139 239 64 239 139 240 141 240 64 240 127 241 134 241 135 241 127 242 135 242 126 242 75 243 140 243 79 243 76 244 79 244 140 244 76 245 143 245 79 245 77 246 79 246 143 246 93 247 95 247 96 247 93 248 96 248 94 248 91 249 93 249 94 249 91 250 94 250 92 250 101 251 106 251 103 251 101 252 105 252 106 252 170 253 119 253 168 253 170 254 118 254 119 254 175 255 112 255 113 255 175 256 113 256 174 256 174 257 113 257 114 257 174 258 114 258 173 258 184 259 144 259 182 259 185 260 182 260 144 260 185 261 147 261 182 261 186 262 182 262 147 262 160 263 161 263 152 263 160 264 152 264 153 264 148 265 197 265 146 265 196 266 197 266 148 266 189 267 187 267 148 267 149 268 196 268 148 268 195 269 196 269 149 269 147 270 195 270 149 270 194 271 195 271 147 271 191 272 192 272 144 272 191 273 144 273 145 273 145 274 183 274 191 274 184 275 183 275 145 275 145 276 144 276 184 276 192 277 185 277 144 277 147 278 185 278 194 278 147 279 149 279 186 279 187 280 186 280 149 280 149 281 148 281 187 281 148 282 146 282 189 282 146 283 205 283 189 283 197 284 205 284 146 284 184 285 182 285 180 285 184 286 180 286 181 286 223 287 33 287 107 287 223 288 107 288 179 288 150 289 178 289 166 289 220 290 178 290 150 290 150 291 219 291 220 291 166 292 219 292 150 292 178 293 167 293 166 293 151 294 167 294 178 294 179 295 167 295 151 295 151 296 223 296 179 296 178 297 223 297 151 297 223 298 178 298 221 298 221 299 178 299 220 299 213 300 212 300 168 300 11 301 213 301 168 301 204 302 202 302 203 302 204 303 201 303 202 303 218 304 201 304 204 304 218 305 217 305 201 305 153 306 169 306 160 306 170 307 169 307 153 307 153 308 152 308 170 308 171 309 170 309 152 309 152 310 159 310 171 310 161 311 159 311 152 311 166 312 165 312 163 312 219 313 166 313 163 313 208 314 163 314 160 314 163 315 161 315 160 315 163 316 162 316 161 316 179 317 158 317 167 317 164 318 155 318 154 318 175 319 154 319 155 319 179 320 108 320 157 320 108 321 109 321 157 321 109 322 110 322 157 322 177 323 157 323 110 323 30 324 205 324 35 324 199 325 206 325 22 325 206 326 199 326 207 326 199 327 202 327 207 327 201 328 207 328 202 328 207 329 201 329 205 329 217 330 205 330 201 330 217 331 188 331 205 331 217 332 216 332 188 332 159 333 162 333 154 333 164 334 154 334 162 334 165 335 155 335 164 335 165 336 156 336 155 336 156 337 165 337 158 337 167 338 158 338 165 338 25 339 34 339 198 339 212 340 210 340 168 340 169 341 168 341 210 341 171 342 159 342 173 342 173 343 159 343 174 343 154 344 174 344 159 344 174 345 154 345 175 345 175 346 155 346 176 346 176 347 155 347 177 347 156 348 177 348 155 348 158 349 177 349 156 349 177 350 158 350 157 350 157 351 158 351 179 351 208 352 219 352 163 352 169 353 208 353 160 353 169 354 210 354 208 354 161 355 162 355 159 355 162 356 163 356 164 356 164 357 163 357 165 357 167 358 165 358 166 358 222 359 198 359 34 359 11 360 168 360 119 360 168 361 169 361 170 361 118 362 170 362 117 362 172 363 117 363 170 363 117 364 172 364 116 364 171 365 172 365 170 365 172 366 171 366 173 366 173 367 115 367 172 367 172 368 115 368 116 368 115 369 173 369 114 369 112 370 175 370 111 370 176 371 111 371 175 371 177 372 110 372 176 372 176 373 110 373 111 373 108 374 179 374 107 374 187 375 189 375 180 375 216 376 180 376 189 376 189 377 188 377 216 377 187 378 180 378 186 378 186 379 180 379 182 379 215 380 181 380 180 380 215 381 180 381 216 381 183 382 215 382 209 382 215 383 183 383 181 383 181 384 183 384 184 384 209 385 211 385 183 385 190 386 183 386 211 386 191 387 183 387 190 387 193 388 185 388 192 388 194 389 185 389 193 389 189 390 205 390 188 390 190 391 211 391 214 391 190 392 214 392 53 392 52 393 190 393 53 393 190 394 52 394 191 394 51 395 191 395 52 395 191 396 51 396 192 396 50 397 192 397 51 397 192 398 50 398 193 398 193 399 50 399 49 399 48 400 193 400 49 400 193 401 48 401 194 401 47 402 194 402 48 402 194 403 47 403 195 403 195 404 47 404 46 404 195 405 46 405 196 405 45 406 196 406 46 406 196 407 45 407 197 407 197 408 45 408 44 408 197 409 44 409 205 409 205 410 44 410 35 410 53 411 214 411 12 411 200 412 23 412 25 412 200 413 22 413 23 413 22 414 200 414 199 414 198 415 200 415 25 415 200 416 198 416 203 416 203 417 198 417 222 417 203 418 202 418 200 418 200 419 202 419 199 419 203 420 222 420 204 420 204 421 222 421 221 421 204 422 221 422 218 422 218 423 221 423 220 423 223 424 34 424 33 424 34 425 223 425 222 425 206 426 30 426 22 426 30 427 206 427 205 427 207 428 205 428 206 428 208 429 215 429 219 429 210 430 215 430 208 430 215 431 210 431 209 431 209 432 210 432 211 432 212 433 211 433 210 433 211 434 212 434 214 434 213 435 214 435 212 435 214 436 213 436 11 436 214 437 11 437 12 437 215 438 216 438 219 438 219 439 216 439 217 439 219 440 217 440 218 440 219 441 218 441 220 441 223 442 221 442 222 442 35 443 44 443 43 443

+
+
+
+
+ + + + 0.00000 0.00000 0.00004 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_middle/f_middle_E2M3.dae b/URDFs/sr_description/meshes/components/f_middle/f_middle_E2M3.dae new file mode 100644 index 0000000..7385453 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_middle/f_middle_E2M3.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:44.246463 + 2012-07-23T02:15:44.246477 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -5.15497 -5.65164 5.67687 -6.98593 -7.50773 8.86243 -8.01397 -5.97789 7.98236 -8.48097 -4.31842 6.98785 -8.50017 0.02188 5.46986 -8.50017 -3.88961 12.77786 -8.48937 -3.70556 18.59785 -8.50017 0.02188 20.53786 -8.22567 3.73770 21.84346 -3.50017 7.97965 1.21886 -3.50017 7.04980 24.44685 3.49296 7.97965 1.21886 3.49983 7.04980 24.44685 -4.29807 7.00277 24.01886 -4.75757 7.78174 2.14586 -6.73177 6.68550 2.87236 -6.31127 6.25102 22.77386 -7.75257 5.53448 3.44444 -7.62757 4.93940 22.20461 -8.42967 3.69429 4.18787 -3.43169 -8.64405 15.62886 -3.50017 -8.93332 12.68886 3.42448 -8.64405 15.62886 3.49296 -8.93332 12.68886 -3.50017 -8.97607 9.81386 3.49296 -8.97607 9.81386 -6.41337 -7.45056 17.15486 -4.73277 -7.88683 17.09686 -7.46427 -4.93237 19.65934 -4.00017 -5.21445 19.76886 3.99983 -5.21445 19.76886 -3.50017 -8.70539 8.82587 -4.00017 -5.82319 5.84886 3.99983 -5.82319 5.84886 3.49296 -8.70539 8.82587 4.48796 -5.61710 20.77286 -8.11957 -5.83721 12.86186 -7.03567 -7.45782 12.93086 -7.07657 -7.15262 16.53586 -8.02707 -5.46231 17.55201 -5.41357 -8.54068 12.82830 -5.52640 -8.05887 15.99102 -5.66907 -8.47778 9.50586 -4.49517 -5.61710 20.77286 4.75036 -6.43800 22.17986 4.75723 -6.97321 25.88187 4.75723 -6.48965 27.70586 4.75723 -4.19093 30.65686 4.75723 -2.54057 31.57185 4.75723 1.17980 31.95786 4.75723 2.98301 31.40186 4.75723 4.57411 30.38686 4.75723 6.68716 27.30086 4.75723 7.05771 25.45087 -4.75757 -6.43800 22.17986 -4.75757 -6.97321 25.88187 -4.75757 -6.48965 27.70586 -4.75757 -4.19093 30.65686 -4.75757 -2.54057 31.57185 -4.75757 1.17980 31.95786 -4.75757 2.98301 31.40186 -4.75757 4.57411 30.38686 -4.75757 6.68716 27.30086 -4.75757 7.05771 25.45087 -5.90557 -6.46749 22.90086 -5.90557 -6.71430 26.07986 -5.87887 -4.67070 29.33165 -5.90557 -3.05930 31.08986 -5.90557 0.04375 31.82587 -5.90557 3.14202 31.06985 -5.90557 5.55840 28.98886 -5.90557 6.76483 26.03687 -8.77364 -3.34911 22.56881 -8.45003 -3.33963 20.40928 -8.99996 -3.58678 25.82197 -8.99996 -2.60559 27.58099 -8.12147 0.02188 29.93286 -8.99996 3.11434 27.46986 -8.12147 4.95033 25.05086 -9.00000 0.02188 28.72610 -8.99996 3.87812 25.23030 -9.00019 0.02642 23.15286 -6.87887 -6.81239 2.17687 -6.52396 -4.86510 5.63609 -4.75757 -7.07768 3.79886 -4.75757 -7.78383 1.97186 -6.87887 -6.53824 -2.89314 -4.75757 -8.02808 0.02885 -4.75757 -7.79600 -1.91515 -6.87887 -5.85402 -4.57393 -4.75757 -5.98513 -5.35513 -6.40557 -4.61815 -6.29314 -4.75757 -4.51347 -6.64714 -5.90557 -1.56868 -7.33768 -4.75757 -2.77352 -7.54514 -5.90557 1.77076 -7.62013 -4.75757 1.09010 -7.97514 -4.75757 2.98490 -7.48114 -5.90557 4.79136 -6.19514 -4.75757 4.70447 -6.54414 -6.87887 3.66948 -6.17014 -5.90557 6.94247 -3.64114 -4.75757 6.14692 -5.22014 -4.75757 7.22694 -3.58614 -8.12147 6.00887 0.10429 -5.90557 7.63414 -0.42213 -4.75757 7.88062 -1.74014 4.75723 -7.07768 3.79886 4.75723 -7.78383 1.97186 4.75723 -8.02808 0.02885 4.75723 -7.79600 -1.91515 4.75723 -5.98513 -5.35513 4.75723 -4.51347 -6.64714 4.75723 -2.77352 -7.54514 4.75723 1.09010 -7.97514 4.75723 2.98490 -7.48114 4.75723 4.70447 -6.54414 4.75723 6.14692 -5.22014 4.75723 7.22694 -3.58614 4.75723 7.88062 -1.74014 -7.87887 -5.40786 2.46296 -8.50000 -3.55834 4.34187 -9.00000 -3.59913 -1.17314 -9.00000 -2.21603 -3.07614 -9.00000 0.02188 4.39287 -9.00000 0.02188 -4.58014 -9.00000 2.25979 -3.07614 -9.00000 3.74480 -1.09914 -8.12147 1.63616 -5.70114 -8.12147 -5.89100 -0.42914 -6.87887 -7.13355 0.48087 -8.12147 -5.60089 -1.87614 -8.12100 -4.85241 -4.18614 -8.12147 -1.44278 -5.74113 -8.12100 5.47326 -2.53608 -8.12100 4.61814 -4.13956 -6.75466 -5.90532 3.90648 -8.45823 -3.70615 5.68876 -8.12100 -3.83817 28.38669 -8.12100 -4.78404 25.94850 -8.12100 -3.16487 29.14326 -7.96933 -4.72890 22.71507 -8.12100 3.99730 28.01863 -8.12100 3.12703 29.12051 8.11379 3.12703 29.12051 8.11379 3.99730 28.01863 7.96212 -4.72890 22.71507 8.11379 -3.16488 29.14326 8.11379 -4.78404 25.94850 8.11379 -3.83817 28.38669 8.45102 -3.70615 5.68876 6.74746 -5.90533 3.90648 8.11379 4.61814 -4.13956 8.11379 5.47326 -2.53608 8.11426 -1.44278 -5.74114 8.11379 -4.85241 -4.18614 8.11426 -5.60089 -1.87615 6.87166 -7.13355 0.48086 8.11426 -5.89100 -0.42914 8.11426 1.63616 -5.70114 9.00000 3.74480 -1.09914 9.00000 2.25979 -3.07614 9.00000 0.02188 -4.58014 9.00000 0.02188 4.39287 9.00000 -2.21603 -3.07614 9.00000 -3.59913 -1.17314 8.49279 -3.55834 4.34187 7.87166 -5.40786 2.46296 5.89836 7.63414 -0.42213 8.11426 6.00887 0.10428 5.89836 6.94247 -3.64114 6.87166 3.66948 -6.17014 5.89836 4.79136 -6.19515 5.89836 1.77076 -7.62013 5.89836 -1.56868 -7.33768 6.39836 -4.61815 -6.29314 6.87166 -5.85402 -4.57393 6.87166 -6.53824 -2.89314 6.51675 -4.86510 5.63609 6.87166 -6.81239 2.17686 9.00019 0.02642 23.15286 8.99996 3.87812 25.23030 9.00000 0.02188 28.72610 8.11426 4.95033 25.05086 8.99996 3.11434 27.46986 8.11426 0.02188 29.93286 8.99996 -2.60559 27.58099 8.99996 -3.58678 25.82197 8.44282 -3.33963 20.40928 8.76643 -3.34911 22.56881 5.89836 6.76483 26.03687 5.89836 5.55840 28.98886 5.89836 3.14202 31.06985 5.89836 0.04374 31.82587 5.89836 -3.05930 31.08986 5.87166 -4.67070 29.33165 5.89836 -6.71430 26.07986 5.89836 -6.46749 22.90086 5.66186 -8.47778 9.50586 5.51919 -8.05887 15.99102 5.40636 -8.54068 12.82830 8.01986 -5.46231 17.55201 7.06936 -7.15262 16.53586 7.02846 -7.45782 12.93086 8.11236 -5.83721 12.86186 7.45706 -4.93237 19.65934 4.72556 -7.88683 17.09686 6.40616 -7.45056 17.15486 8.42246 3.69429 4.18787 7.62036 4.93940 22.20461 7.74536 5.53448 3.44444 6.30406 6.25102 22.77386 6.72456 6.68550 2.87236 4.75036 7.78174 2.14586 4.29086 7.00277 24.01886 8.21846 3.73770 21.84346 8.49296 0.02188 20.53786 8.48216 -3.70556 18.59785 8.49296 -3.88961 12.77786 8.49296 0.02188 5.46986 8.47376 -4.31842 6.98785 8.00676 -5.97789 7.98236 6.97873 -7.50773 8.86243 5.14776 -5.65164 5.67686 + + + + + + + + + + -0.43084 -0.64978 -0.62623 -0.99998 -0.00544 -0.00291 -0.99999 0.00327 0.00175 -1.00000 -0.00290 0.00000 -0.99728 0.07367 0.00000 0.00000 0.99920 0.04000 0.00000 0.99920 0.04000 -0.08009 0.99599 0.03987 -0.12798 0.99105 0.03798 -0.47339 0.87988 0.04128 -0.36485 0.93065 0.02803 -0.74029 0.67160 0.03030 -0.71143 0.70224 0.02702 -0.89745 0.44067 0.01996 -0.93713 0.34885 0.00997 -0.99966 0.02320 0.01149 -0.00000 -0.99519 0.09792 -0.00000 -0.99519 0.09792 -0.00000 -0.99989 0.01487 -0.00000 -0.99989 0.01487 -0.16644 -0.72939 0.66354 -0.07913 -0.69391 0.71570 0.29821 -0.71453 0.63287 -0.00000 -0.77008 0.63794 0.00000 -0.77008 0.63794 -0.26673 -0.75814 -0.59504 -0.00321 -0.71872 -0.69529 -0.00000 -0.71845 -0.69557 -0.00000 -0.71845 -0.69557 -0.96497 -0.26186 0.01619 -0.98119 -0.19242 -0.01569 -0.82951 -0.55849 -0.00185 -0.83115 -0.55604 -0.00334 -0.47043 -0.87472 0.11647 -0.55126 -0.83186 0.06417 -0.59392 -0.80452 0.00261 -0.55384 -0.83219 0.02684 -0.22374 -0.97465 -0.00125 -0.24438 -0.95988 0.13751 -0.19296 -0.97604 0.10053 -0.19998 -0.97969 0.01457 -0.00000 -0.92814 -0.37223 -0.00000 -0.86374 -0.50394 -0.00000 -0.98971 -0.14308 0.00000 -0.98971 -0.14309 0.00000 -0.96661 0.25626 0.00000 -0.96661 0.25626 0.00000 -0.78890 0.61452 0.00000 -0.78890 0.61452 0.00000 -0.48488 0.87458 0.00000 -0.48488 0.87458 0.00000 -0.10320 0.99466 0.00000 -0.10320 0.99466 -0.00000 0.29465 0.95561 -0.00000 0.29465 0.95561 -0.00000 0.53781 0.84307 0.00000 0.53781 0.84307 0.00000 0.82511 0.56497 0.00000 0.82511 0.56497 0.00000 0.98052 0.19640 0.00000 0.98052 0.19640 0.00000 0.99997 -0.00788 0.00000 0.99997 -0.00788 -0.03267 0.99827 -0.04878 -0.00952 -0.86293 -0.50524 -0.19191 -0.91946 -0.34316 -0.06431 -0.98766 -0.14279 -0.23172 -0.96986 -0.07530 -0.17124 -0.95233 0.25247 -0.51028 -0.72626 0.46061 -0.36232 -0.73530 0.57277 -0.43045 -0.66867 0.60630 -0.14650 -0.47965 0.86514 -0.29107 -0.22079 0.93088 -0.01223 -0.10319 0.99459 -0.37255 0.27344 0.88681 -0.24082 0.23008 0.94290 -0.16695 0.53026 0.83123 -0.34141 0.61335 0.71220 0.01944 0.82495 0.56486 -0.33363 0.87264 0.35663 -0.14825 0.96969 0.19423 -0.30923 0.94131 -0.13534 -0.28461 0.95178 -0.11449 -0.86952 -0.47582 -0.13239 -0.63819 -0.17768 0.74910 -0.63970 0.18221 0.74671 -0.67957 0.67909 0.27753 -0.62051 0.78284 -0.04612 -0.67429 0.72869 -0.11980 -0.73664 0.64008 0.21829 -0.77390 0.60030 -0.20181 -0.86584 0.47665 -0.15208 -0.97286 0.13731 -0.18626 -0.96646 0.12196 -0.22601 -1.00000 -0.00003 0.00003 -1.00000 -0.00004 0.00003 -0.98891 -0.00908 -0.14823 -0.98167 -0.03342 -0.18765 -0.99584 -0.05416 -0.07324 -0.36521 -0.86832 0.33561 -0.22066 -0.86307 -0.45434 -0.35140 -0.86713 -0.35299 -0.27065 -0.74481 -0.60993 -0.11867 -0.65509 -0.74618 -0.14801 0.24950 -0.95700 -0.22483 0.46623 -0.85562 -0.32338 0.40374 -0.85582 -0.45787 0.37931 -0.80404 -0.66821 0.56903 -0.47927 -0.17026 0.66634 -0.72595 -0.33540 0.72055 -0.60689 -0.17744 0.82100 -0.54265 -0.60860 0.77577 -0.16669 -0.16759 0.98511 0.03825 -0.00000 -0.96446 -0.26423 0.00000 -0.85296 0.52197 0.00000 -0.85296 0.52197 0.00000 -0.93275 0.36052 0.00000 -0.93275 0.36052 0.00000 -0.99219 0.12473 0.00000 -0.99219 0.12473 -0.00000 -0.99295 -0.11854 -0.00000 -0.99295 -0.11854 -0.00000 -0.88488 -0.46582 -0.00000 -0.88488 -0.46582 -0.00000 -0.65975 -0.75149 -0.00000 -0.65975 -0.75149 -0.00000 -0.45863 -0.88863 -0.00000 -0.45863 -0.88863 -0.00000 -0.11061 -0.99386 -0.00000 -0.11061 -0.99386 -0.00000 0.25228 -0.96765 -0.00000 0.25228 -0.96765 -0.00000 0.47848 -0.87810 -0.00000 0.47848 -0.87810 -0.00000 0.67621 -0.73671 -0.00000 0.67621 -0.73671 -0.00000 0.83424 -0.55140 -0.00000 0.83424 -0.55140 -0.00000 0.94264 -0.33380 -0.00000 0.94264 -0.33380 -0.00000 0.99944 -0.03345 0.00000 0.99944 -0.03345 -0.26643 -0.75723 -0.59634 -0.91489 -0.39448 0.08586 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -0.00000 -0.96446 -0.26423 -0.90158 0.24131 -0.35907 -0.90485 0.39604 0.15618 -0.94467 0.31082 0.10487 -0.89506 0.16219 0.41539 -0.74557 -0.65479 0.12399 -0.65095 -0.74758 -0.13190 -0.66918 -0.72860 -0.14608 -0.69626 -0.68280 -0.22138 -0.65402 -0.70065 -0.28522 -0.61787 -0.54789 -0.56396 -0.58197 -0.17649 -0.79382 -0.58414 0.01054 -0.81158 -0.65108 -0.06397 -0.75631 -0.64549 0.22621 -0.72950 -0.55447 0.81322 0.17674 -0.74717 0.66462 0.00400 -0.18101 -0.94853 -0.25987 -0.93915 -0.31722 0.13177 -0.92258 -0.37827 -0.07584 -0.92388 -0.36399 -0.11813 -0.95364 -0.24345 -0.17694 -0.89678 -0.24681 -0.36724 -0.79257 0.00792 -0.60973 -0.99956 -0.01586 0.02491 -0.81387 -0.56586 0.13199 0.00000 -0.92814 -0.37223 -0.84513 -0.41959 0.33122 -0.69413 -0.63215 0.34435 -0.66502 -0.62224 0.41300 -0.47825 -0.87339 0.09202 -0.22907 -0.92338 0.30805 -0.20936 -0.93219 0.29528 -0.06197 -0.91543 -0.39768 -0.44992 -0.87948 -0.15518 -0.40578 -0.90753 -0.10834 -0.36482 -0.92381 0.11613 -0.39655 -0.90198 0.17080 -0.72765 -0.28472 -0.62407 -0.92274 -0.16003 -0.35062 -0.78720 -0.59414 0.16529 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.98151 0.15842 0.10739 -0.89920 -0.13152 0.41731 -0.98615 -0.13901 0.09043 -0.91814 0.18394 -0.35098 -0.73800 0.31314 -0.59774 -0.51084 0.61558 -0.60008 -0.63402 0.68235 -0.36389 -0.59956 0.78433 -0.15921 -0.91399 0.39761 -0.08082 -0.96554 -0.26005 0.01002 -0.98113 -0.19024 0.03456 -0.85485 -0.51561 0.05807 -0.83137 -0.55445 0.03751 -0.14858 0.98885 0.00958 -0.43892 0.88671 0.14525 -0.57656 -0.53325 -0.61905 -0.39080 -0.71053 -0.58517 -0.44124 -0.74181 0.50500 -0.37160 -0.81095 0.45197 -0.72353 -0.58860 0.36064 -0.75356 -0.51410 0.40970 -0.67246 -0.62637 0.39428 -0.99951 -0.00949 0.02996 -0.99965 -0.01262 -0.02345 -0.48297 -0.78878 -0.38022 -0.51397 -0.85427 -0.07781 -0.45695 -0.75232 0.47457 -0.20294 -0.80005 0.56457 -1.00000 0.00005 0.00002 -1.00000 0.00003 0.00003 -0.64042 -0.76606 -0.05484 -0.85396 -0.50916 -0.10724 -0.86063 -0.50687 -0.04901 -0.79753 -0.56244 0.21819 -0.85811 -0.44842 0.25013 -0.85616 -0.38599 0.34351 -0.64381 -0.18412 0.74270 -0.64894 0.19266 0.73604 -0.76162 0.50854 0.40165 -0.75386 0.62553 0.20099 -0.62699 0.74169 0.23828 -0.63612 0.60551 0.47824 -0.55727 0.54184 0.62917 -0.48481 -0.64844 0.58693 -0.48698 -0.65246 0.58064 -0.47463 -0.74348 0.47114 -0.64037 -0.71607 0.27779 -0.79712 -0.59566 -0.09897 -0.65381 -0.75439 -0.05857 -0.64141 -0.76598 -0.04315 -0.92870 0.32722 -0.17450 -0.94438 0.26293 -0.19750 -0.88324 -0.18735 0.42986 -0.79998 -0.14442 0.58239 -0.79902 0.15230 0.58169 -0.86767 0.18711 0.46059 -0.33715 -0.07934 -0.93810 -0.28355 -0.10607 -0.95307 -0.40679 -0.23563 -0.88261 -0.15968 -0.45274 -0.87723 -0.21262 0.92109 -0.32617 -0.41120 0.89121 -0.19149 0.41325 0.89030 -0.19130 0.21384 0.92084 -0.32608 0.16033 -0.45269 -0.87713 0.40856 -0.23510 -0.88193 0.28512 -0.10602 -0.95261 0.33894 -0.07929 -0.93746 0.86591 0.18827 0.46342 0.79665 0.15309 0.58473 0.79762 -0.14517 0.58543 0.88165 -0.18855 0.43260 0.94354 0.26485 -0.19894 0.92765 0.32953 -0.17573 0.64141 -0.76598 -0.04315 0.65381 -0.75439 -0.05857 0.79456 -0.59876 -0.10078 0.64037 -0.71607 0.27779 0.47463 -0.74348 0.47114 0.48698 -0.65246 0.58064 0.48481 -0.64844 0.58693 0.55727 0.54184 0.62917 0.63612 0.60551 0.47824 0.62699 0.74169 0.23828 0.75120 0.62843 0.20193 0.75900 0.51095 0.40355 0.64894 0.19266 0.73604 0.64381 -0.18412 0.74270 0.85428 -0.38831 0.34557 0.85625 -0.45112 0.25164 0.79515 -0.56536 0.21933 0.86063 -0.50687 -0.04901 0.85396 -0.50916 -0.10724 0.64042 -0.76606 -0.05484 1.00000 0.00003 0.00003 1.00000 0.00005 0.00002 0.20411 -0.79963 0.56474 0.45858 -0.75108 0.47496 0.51397 -0.85427 -0.07781 0.48297 -0.78878 -0.38022 0.99965 -0.01262 -0.02345 0.99951 -0.00949 0.02996 0.67246 -0.62637 0.39428 0.75356 -0.51409 0.40970 0.72353 -0.58860 0.36064 0.37160 -0.81095 0.45197 0.44124 -0.74181 0.50500 0.39080 -0.71053 -0.58517 0.57656 -0.53325 -0.61905 0.43892 0.88671 0.14525 0.14858 0.98885 0.00958 0.83138 -0.55444 0.03751 0.85485 -0.51561 0.05807 0.98113 -0.19024 0.03456 0.96554 -0.26005 0.01002 0.91275 0.40033 -0.08137 0.59956 0.78433 -0.15921 0.63402 0.68235 -0.36389 0.51084 0.61559 -0.60008 0.73800 0.31314 -0.59774 0.91695 0.18521 -0.35340 0.98576 -0.14096 0.09170 0.89670 -0.13305 0.42216 0.98106 0.16035 0.10870 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 0.78720 -0.59414 0.16529 0.92162 -0.16115 -0.35307 0.72765 -0.28472 -0.62407 0.39764 -0.90152 0.17072 0.36584 -0.92341 0.11608 0.40688 -0.90704 -0.10829 0.45108 -0.87891 -0.15507 0.06211 -0.91555 -0.39738 0.20937 -0.93219 0.29528 0.22907 -0.92338 0.30805 0.47825 -0.87339 0.09202 0.66502 -0.62224 0.41300 0.69413 -0.63215 0.34435 0.84513 -0.41959 0.33122 0.81387 -0.56586 0.13199 0.99956 -0.01586 0.02491 0.79015 0.00796 -0.61286 0.89534 -0.24843 -0.36966 0.95292 -0.24527 -0.17826 0.92277 -0.36653 -0.11895 0.92145 -0.38091 -0.07637 0.93826 -0.31972 0.13212 0.18102 -0.94853 -0.25987 0.74717 0.66462 0.00400 0.55447 0.81322 0.17674 0.64549 0.22621 -0.72950 0.65108 -0.06397 -0.75631 0.58414 0.01054 -0.81158 0.58197 -0.17649 -0.79382 0.61787 -0.54789 -0.56396 0.65402 -0.70064 -0.28522 0.69626 -0.68280 -0.22138 0.66918 -0.72860 -0.14608 0.65095 -0.74757 -0.13190 0.74557 -0.65479 0.12399 0.89253 0.16382 0.42019 0.94386 0.31286 0.10609 0.90485 0.39604 0.15618 0.90019 0.24292 -0.36146 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 0.91435 -0.39547 0.08702 0.26643 -0.75723 -0.59634 0.16796 0.98503 0.03880 0.60860 0.77577 -0.16669 0.17848 0.82084 -0.54255 0.33719 0.72006 -0.60647 0.17126 0.66622 -0.72582 0.66821 0.56903 -0.47927 0.45787 0.37931 -0.80404 0.32512 0.40348 -0.85528 0.22611 0.46609 -0.85536 0.14888 0.24947 -0.95687 0.11916 -0.65505 -0.74613 0.27151 -0.74449 -0.60993 0.35239 -0.86678 -0.35285 0.22134 -0.86293 -0.45426 0.36624 -0.86795 0.33547 0.99558 -0.05587 -0.07555 0.98111 -0.03503 -0.19024 0.98891 -0.00908 -0.14823 1.00000 -0.00004 0.00003 1.00000 -0.00003 0.00003 0.96587 0.12301 -0.22797 0.97224 0.13817 -0.18882 0.86584 0.47665 -0.15208 0.77133 0.60319 -0.20299 0.73388 0.64292 0.21926 0.67428 0.72869 -0.11980 0.62051 0.78284 -0.04612 0.67957 0.67909 0.27753 0.63970 0.18221 0.74671 0.63819 -0.17768 0.74910 0.86952 -0.47582 -0.13239 0.28461 0.95178 -0.11449 0.31198 0.94006 -0.13767 0.14912 0.96956 0.19420 0.33541 0.87206 0.35639 -0.01956 0.82495 0.56486 0.34323 0.61292 0.71170 0.16792 0.53017 0.83109 0.24219 0.23000 0.94257 0.37448 0.27321 0.88607 0.01231 -0.10319 0.99459 0.29267 -0.22068 0.93040 0.14736 -0.47959 0.86503 0.43258 -0.66793 0.60559 0.36425 -0.73470 0.57230 0.51256 -0.72510 0.45990 0.17223 -0.95216 0.25243 0.23304 -0.96955 -0.07527 0.06438 -0.98764 -0.14290 0.19191 -0.91946 -0.34316 0.00953 -0.86293 -0.50524 0.03284 0.99826 -0.04900 0.19998 -0.97969 0.01457 0.19296 -0.97604 0.10053 0.24438 -0.95988 0.13751 0.22374 -0.97465 -0.00125 0.55384 -0.83219 0.02684 0.59392 -0.80452 0.00261 0.55126 -0.83186 0.06417 0.47043 -0.87472 0.11647 0.83115 -0.55603 -0.00334 0.82951 -0.55848 -0.00185 0.98119 -0.19242 -0.01569 0.96497 -0.26186 0.01619 0.00323 -0.71872 -0.69529 0.26673 -0.75814 -0.59504 -0.29870 -0.71412 0.63309 0.07929 -0.69398 0.71562 0.16644 -0.72939 0.66354 0.99966 0.02320 0.01149 0.93713 0.34885 0.00997 0.89745 0.44067 0.01996 0.71143 0.70224 0.02702 0.74029 0.67160 0.03030 0.36484 0.93065 0.02803 0.47339 0.87988 0.04128 0.12798 0.99105 0.03798 0.08078 0.99594 0.03984 0.99728 0.07367 -0.00000 1.00000 -0.00290 -0.00000 0.99999 0.00327 0.00175 0.99998 -0.00544 -0.00291 0.43085 -0.64977 -0.62623 -0.00000 -0.86374 -0.50394 + + + + + + + + + + + + + + +

0 0 1 0 2 0 4 1 3 1 5 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 4 4 7 4 9 5 10 5 11 5 12 6 11 6 10 6 13 7 10 7 9 7 13 8 9 8 14 8 14 9 15 9 13 9 16 10 13 10 15 10 15 11 17 11 16 11 18 12 16 12 17 12 8 13 18 13 17 13 17 14 19 14 8 14 19 15 4 15 8 15 20 16 21 16 22 16 23 17 22 17 21 17 21 18 24 18 23 18 25 19 23 19 24 19 26 20 27 20 28 20 29 21 28 21 27 21 27 22 20 22 29 22 29 23 20 23 22 23 30 24 29 24 22 24 1 25 0 25 31 25 0 26 32 26 31 26 33 27 34 27 31 27 32 28 33 28 31 28 5 29 3 29 2 29 36 30 5 30 2 30 36 31 2 31 1 31 37 32 36 32 1 32 40 33 41 33 38 33 37 34 40 34 38 34 37 35 1 35 42 35 40 36 37 36 42 36 42 37 24 37 40 37 20 38 41 38 40 38 40 39 21 39 20 39 40 40 24 40 21 40 35 41 43 41 29 41 43 42 44 42 54 42 44 43 45 43 54 43 55 44 54 44 45 44 45 45 46 45 55 45 56 46 55 46 46 46 46 47 47 47 56 47 57 48 56 48 47 48 47 49 48 49 57 49 58 50 57 50 48 50 48 51 49 51 58 51 59 52 58 52 49 52 49 53 50 53 59 53 60 54 59 54 50 54 50 55 51 55 60 55 61 56 60 56 51 56 51 57 52 57 61 57 62 58 61 58 52 58 52 59 53 59 62 59 63 60 62 60 53 60 12 61 63 61 53 61 63 62 12 62 10 62 63 63 10 63 13 63 28 64 43 64 54 64 64 65 28 65 54 65 64 66 54 66 55 66 65 67 64 67 55 67 55 68 56 68 65 68 66 69 65 69 56 69 66 70 56 70 57 70 67 71 66 71 57 71 57 72 58 72 67 72 68 73 67 73 58 73 58 74 59 74 68 74 68 75 59 75 60 75 69 76 68 76 60 76 60 77 61 77 69 77 70 78 69 78 61 78 61 79 62 79 70 79 71 80 70 80 62 80 62 81 63 81 71 81 71 82 63 82 13 82 71 83 13 83 16 83 72 84 73 84 28 84 67 85 68 85 76 85 68 86 69 86 76 86 70 87 71 87 78 87 71 88 16 88 78 88 18 89 78 89 16 89 80 90 77 90 78 90 8 91 80 91 78 91 78 92 18 92 8 92 8 93 7 93 81 93 8 94 81 94 80 94 75 95 79 95 81 95 74 96 75 96 81 96 72 97 7 97 73 97 7 98 72 98 81 98 74 99 81 99 72 99 85 100 84 100 82 100 89 101 90 101 88 101 86 102 89 102 88 102 89 103 91 103 90 103 92 104 90 104 91 104 97 105 96 105 95 105 98 106 99 106 97 106 95 107 98 107 97 107 98 108 95 108 100 108 100 109 101 109 98 109 102 110 99 110 98 110 98 111 101 111 102 111 103 112 102 112 101 112 105 113 101 113 104 113 9 114 106 114 105 114 34 115 25 115 31 115 84 116 33 116 32 116 33 117 84 117 107 117 84 118 85 118 107 118 108 119 107 119 85 119 85 120 87 120 108 120 109 121 108 121 87 121 87 122 88 122 109 122 110 123 109 123 88 123 88 124 90 124 110 124 111 125 110 125 90 125 90 126 92 126 111 126 112 127 111 127 92 127 92 128 94 128 112 128 113 129 112 129 94 129 94 130 96 130 113 130 114 131 113 131 96 131 96 132 97 132 114 132 115 133 114 133 97 133 97 134 99 134 115 134 116 135 115 135 99 135 99 136 102 136 116 136 117 137 116 137 102 137 102 138 103 138 117 138 118 139 117 139 103 139 103 140 106 140 118 140 119 141 118 141 106 141 106 142 9 142 119 142 11 143 119 143 9 143 1 144 31 144 42 144 120 145 121 145 122 145 123 146 122 146 124 146 125 147 123 147 124 147 24 148 31 148 25 148 126 149 128 149 125 149 104 150 19 150 17 150 104 151 127 151 19 151 19 152 124 152 4 152 130 153 82 153 129 153 86 154 130 154 129 154 129 155 131 155 86 155 131 156 132 156 86 156 89 157 86 157 132 157 91 158 89 158 132 158 93 159 91 159 133 159 133 160 128 160 93 160 95 161 93 161 128 161 100 162 95 162 128 162 104 163 17 163 105 163 15 164 105 164 17 164 24 165 42 165 31 165 120 166 122 166 129 166 131 167 129 167 122 167 122 168 132 168 131 168 122 169 123 169 132 169 123 170 125 170 133 170 128 171 133 171 125 171 6 172 73 172 7 172 6 173 28 173 73 173 30 174 35 174 29 174 6 175 39 175 28 175 26 176 28 176 39 176 39 177 38 177 26 177 41 178 26 178 38 178 27 179 26 179 41 179 41 180 20 180 27 180 29 181 43 181 28 181 86 182 88 182 130 182 87 183 130 183 88 183 85 184 130 184 87 184 82 185 130 185 85 185 91 186 132 186 133 186 123 187 133 187 132 187 82 188 120 188 129 188 124 189 126 189 125 189 124 190 127 190 126 190 19 191 127 191 124 191 4 192 124 192 121 192 121 193 124 193 122 193 126 194 135 194 128 194 135 195 100 195 128 195 100 196 135 196 101 196 134 197 101 197 135 197 101 198 134 198 104 198 134 199 127 199 104 199 5 200 39 200 6 200 5 201 36 201 39 201 36 202 38 202 39 202 36 203 37 203 38 203 9 204 105 204 14 204 14 205 105 205 15 205 2 206 3 206 83 206 0 207 2 207 83 207 136 208 0 208 83 208 82 209 0 209 136 209 82 210 136 210 120 210 136 211 83 211 120 211 83 212 121 212 120 212 121 213 137 213 4 213 137 214 3 214 4 214 3 215 137 215 83 215 137 216 121 216 83 216 0 217 82 217 84 217 0 218 84 218 32 218 77 219 80 219 81 219 77 220 81 220 79 220 64 221 141 221 28 221 141 222 72 222 28 222 139 223 72 223 141 223 138 224 74 224 139 224 74 225 138 225 75 225 140 226 75 226 138 226 140 227 67 227 76 227 69 228 143 228 76 228 142 229 77 229 143 229 77 230 142 230 78 230 142 231 70 231 78 231 70 232 142 232 143 232 70 233 143 233 69 233 67 234 140 234 66 234 140 235 138 235 66 235 66 236 138 236 65 236 138 237 139 237 65 237 72 238 139 238 74 238 65 239 139 239 64 239 139 240 141 240 64 240 127 241 134 241 135 241 127 242 135 242 126 242 75 243 140 243 79 243 76 244 79 244 140 244 76 245 143 245 79 245 77 246 79 246 143 246 93 247 95 247 96 247 93 248 96 248 94 248 91 249 93 249 94 249 91 250 94 250 92 250 101 251 106 251 103 251 101 252 105 252 106 252 170 253 119 253 168 253 170 254 118 254 119 254 175 255 112 255 113 255 175 256 113 256 174 256 174 257 113 257 114 257 174 258 114 258 173 258 184 259 144 259 182 259 185 260 182 260 144 260 185 261 147 261 182 261 186 262 182 262 147 262 160 263 161 263 152 263 160 264 152 264 153 264 148 265 197 265 146 265 196 266 197 266 148 266 189 267 187 267 148 267 149 268 196 268 148 268 195 269 196 269 149 269 147 270 195 270 149 270 194 271 195 271 147 271 191 272 192 272 144 272 191 273 144 273 145 273 145 274 183 274 191 274 184 275 183 275 145 275 145 276 144 276 184 276 192 277 185 277 144 277 147 278 185 278 194 278 147 279 149 279 186 279 187 280 186 280 149 280 149 281 148 281 187 281 148 282 146 282 189 282 146 283 205 283 189 283 197 284 205 284 146 284 184 285 182 285 180 285 184 286 180 286 181 286 223 287 33 287 107 287 223 288 107 288 179 288 150 289 178 289 166 289 220 290 178 290 150 290 150 291 219 291 220 291 166 292 219 292 150 292 178 293 167 293 166 293 151 294 167 294 178 294 179 295 167 295 151 295 151 296 223 296 179 296 178 297 223 297 151 297 223 298 178 298 221 298 221 299 178 299 220 299 213 300 212 300 168 300 11 301 213 301 168 301 204 302 202 302 203 302 204 303 201 303 202 303 218 304 201 304 204 304 218 305 217 305 201 305 153 306 169 306 160 306 170 307 169 307 153 307 153 308 152 308 170 308 171 309 170 309 152 309 152 310 159 310 171 310 161 311 159 311 152 311 166 312 165 312 163 312 219 313 166 313 163 313 208 314 163 314 160 314 163 315 161 315 160 315 163 316 162 316 161 316 179 317 158 317 167 317 164 318 155 318 154 318 175 319 154 319 155 319 179 320 108 320 157 320 108 321 109 321 157 321 109 322 110 322 157 322 177 323 157 323 110 323 30 324 205 324 35 324 199 325 206 325 22 325 206 326 199 326 207 326 199 327 202 327 207 327 201 328 207 328 202 328 207 329 201 329 205 329 217 330 205 330 201 330 217 331 188 331 205 331 217 332 216 332 188 332 159 333 162 333 154 333 164 334 154 334 162 334 165 335 155 335 164 335 165 336 156 336 155 336 156 337 165 337 158 337 167 338 158 338 165 338 25 339 34 339 198 339 212 340 210 340 168 340 169 341 168 341 210 341 171 342 159 342 173 342 173 343 159 343 174 343 154 344 174 344 159 344 174 345 154 345 175 345 175 346 155 346 176 346 176 347 155 347 177 347 156 348 177 348 155 348 158 349 177 349 156 349 177 350 158 350 157 350 157 351 158 351 179 351 208 352 219 352 163 352 169 353 208 353 160 353 169 354 210 354 208 354 161 355 162 355 159 355 162 356 163 356 164 356 164 357 163 357 165 357 167 358 165 358 166 358 222 359 198 359 34 359 11 360 168 360 119 360 168 361 169 361 170 361 118 362 170 362 117 362 172 363 117 363 170 363 117 364 172 364 116 364 171 365 172 365 170 365 172 366 171 366 173 366 173 367 115 367 172 367 172 368 115 368 116 368 115 369 173 369 114 369 112 370 175 370 111 370 176 371 111 371 175 371 177 372 110 372 176 372 176 373 110 373 111 373 108 374 179 374 107 374 187 375 189 375 180 375 216 376 180 376 189 376 189 377 188 377 216 377 187 378 180 378 186 378 186 379 180 379 182 379 215 380 181 380 180 380 215 381 180 381 216 381 183 382 215 382 209 382 215 383 183 383 181 383 181 384 183 384 184 384 209 385 211 385 183 385 190 386 183 386 211 386 191 387 183 387 190 387 193 388 185 388 192 388 194 389 185 389 193 389 189 390 205 390 188 390 190 391 211 391 214 391 190 392 214 392 53 392 52 393 190 393 53 393 190 394 52 394 191 394 51 395 191 395 52 395 191 396 51 396 192 396 50 397 192 397 51 397 192 398 50 398 193 398 193 399 50 399 49 399 48 400 193 400 49 400 193 401 48 401 194 401 47 402 194 402 48 402 194 403 47 403 195 403 195 404 47 404 46 404 195 405 46 405 196 405 45 406 196 406 46 406 196 407 45 407 197 407 197 408 45 408 44 408 197 409 44 409 205 409 205 410 44 410 35 410 53 411 214 411 12 411 200 412 23 412 25 412 200 413 22 413 23 413 22 414 200 414 199 414 198 415 200 415 25 415 200 416 198 416 203 416 203 417 198 417 222 417 203 418 202 418 200 418 200 419 202 419 199 419 203 420 222 420 204 420 204 421 222 421 221 421 204 422 221 422 218 422 218 423 221 423 220 423 223 424 34 424 33 424 34 425 223 425 222 425 206 426 30 426 22 426 30 427 206 427 205 427 207 428 205 428 206 428 208 429 215 429 219 429 210 430 215 430 208 430 215 431 210 431 209 431 209 432 210 432 211 432 212 433 211 433 210 433 211 434 212 434 214 434 213 435 214 435 212 435 214 436 213 436 11 436 214 437 11 437 12 437 215 438 216 438 219 438 219 439 216 439 217 439 219 440 217 440 218 440 219 441 218 441 220 441 223 442 221 442 222 442 35 443 44 443 43 443

+
+
+
+
+ + + + 0.00000 0.00000 0.00004 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_middle/f_middle_E3M5.dae b/URDFs/sr_description/meshes/components/f_middle/f_middle_E3M5.dae new file mode 100644 index 0000000..7385453 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_middle/f_middle_E3M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:44.246463 + 2012-07-23T02:15:44.246477 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -5.15497 -5.65164 5.67687 -6.98593 -7.50773 8.86243 -8.01397 -5.97789 7.98236 -8.48097 -4.31842 6.98785 -8.50017 0.02188 5.46986 -8.50017 -3.88961 12.77786 -8.48937 -3.70556 18.59785 -8.50017 0.02188 20.53786 -8.22567 3.73770 21.84346 -3.50017 7.97965 1.21886 -3.50017 7.04980 24.44685 3.49296 7.97965 1.21886 3.49983 7.04980 24.44685 -4.29807 7.00277 24.01886 -4.75757 7.78174 2.14586 -6.73177 6.68550 2.87236 -6.31127 6.25102 22.77386 -7.75257 5.53448 3.44444 -7.62757 4.93940 22.20461 -8.42967 3.69429 4.18787 -3.43169 -8.64405 15.62886 -3.50017 -8.93332 12.68886 3.42448 -8.64405 15.62886 3.49296 -8.93332 12.68886 -3.50017 -8.97607 9.81386 3.49296 -8.97607 9.81386 -6.41337 -7.45056 17.15486 -4.73277 -7.88683 17.09686 -7.46427 -4.93237 19.65934 -4.00017 -5.21445 19.76886 3.99983 -5.21445 19.76886 -3.50017 -8.70539 8.82587 -4.00017 -5.82319 5.84886 3.99983 -5.82319 5.84886 3.49296 -8.70539 8.82587 4.48796 -5.61710 20.77286 -8.11957 -5.83721 12.86186 -7.03567 -7.45782 12.93086 -7.07657 -7.15262 16.53586 -8.02707 -5.46231 17.55201 -5.41357 -8.54068 12.82830 -5.52640 -8.05887 15.99102 -5.66907 -8.47778 9.50586 -4.49517 -5.61710 20.77286 4.75036 -6.43800 22.17986 4.75723 -6.97321 25.88187 4.75723 -6.48965 27.70586 4.75723 -4.19093 30.65686 4.75723 -2.54057 31.57185 4.75723 1.17980 31.95786 4.75723 2.98301 31.40186 4.75723 4.57411 30.38686 4.75723 6.68716 27.30086 4.75723 7.05771 25.45087 -4.75757 -6.43800 22.17986 -4.75757 -6.97321 25.88187 -4.75757 -6.48965 27.70586 -4.75757 -4.19093 30.65686 -4.75757 -2.54057 31.57185 -4.75757 1.17980 31.95786 -4.75757 2.98301 31.40186 -4.75757 4.57411 30.38686 -4.75757 6.68716 27.30086 -4.75757 7.05771 25.45087 -5.90557 -6.46749 22.90086 -5.90557 -6.71430 26.07986 -5.87887 -4.67070 29.33165 -5.90557 -3.05930 31.08986 -5.90557 0.04375 31.82587 -5.90557 3.14202 31.06985 -5.90557 5.55840 28.98886 -5.90557 6.76483 26.03687 -8.77364 -3.34911 22.56881 -8.45003 -3.33963 20.40928 -8.99996 -3.58678 25.82197 -8.99996 -2.60559 27.58099 -8.12147 0.02188 29.93286 -8.99996 3.11434 27.46986 -8.12147 4.95033 25.05086 -9.00000 0.02188 28.72610 -8.99996 3.87812 25.23030 -9.00019 0.02642 23.15286 -6.87887 -6.81239 2.17687 -6.52396 -4.86510 5.63609 -4.75757 -7.07768 3.79886 -4.75757 -7.78383 1.97186 -6.87887 -6.53824 -2.89314 -4.75757 -8.02808 0.02885 -4.75757 -7.79600 -1.91515 -6.87887 -5.85402 -4.57393 -4.75757 -5.98513 -5.35513 -6.40557 -4.61815 -6.29314 -4.75757 -4.51347 -6.64714 -5.90557 -1.56868 -7.33768 -4.75757 -2.77352 -7.54514 -5.90557 1.77076 -7.62013 -4.75757 1.09010 -7.97514 -4.75757 2.98490 -7.48114 -5.90557 4.79136 -6.19514 -4.75757 4.70447 -6.54414 -6.87887 3.66948 -6.17014 -5.90557 6.94247 -3.64114 -4.75757 6.14692 -5.22014 -4.75757 7.22694 -3.58614 -8.12147 6.00887 0.10429 -5.90557 7.63414 -0.42213 -4.75757 7.88062 -1.74014 4.75723 -7.07768 3.79886 4.75723 -7.78383 1.97186 4.75723 -8.02808 0.02885 4.75723 -7.79600 -1.91515 4.75723 -5.98513 -5.35513 4.75723 -4.51347 -6.64714 4.75723 -2.77352 -7.54514 4.75723 1.09010 -7.97514 4.75723 2.98490 -7.48114 4.75723 4.70447 -6.54414 4.75723 6.14692 -5.22014 4.75723 7.22694 -3.58614 4.75723 7.88062 -1.74014 -7.87887 -5.40786 2.46296 -8.50000 -3.55834 4.34187 -9.00000 -3.59913 -1.17314 -9.00000 -2.21603 -3.07614 -9.00000 0.02188 4.39287 -9.00000 0.02188 -4.58014 -9.00000 2.25979 -3.07614 -9.00000 3.74480 -1.09914 -8.12147 1.63616 -5.70114 -8.12147 -5.89100 -0.42914 -6.87887 -7.13355 0.48087 -8.12147 -5.60089 -1.87614 -8.12100 -4.85241 -4.18614 -8.12147 -1.44278 -5.74113 -8.12100 5.47326 -2.53608 -8.12100 4.61814 -4.13956 -6.75466 -5.90532 3.90648 -8.45823 -3.70615 5.68876 -8.12100 -3.83817 28.38669 -8.12100 -4.78404 25.94850 -8.12100 -3.16487 29.14326 -7.96933 -4.72890 22.71507 -8.12100 3.99730 28.01863 -8.12100 3.12703 29.12051 8.11379 3.12703 29.12051 8.11379 3.99730 28.01863 7.96212 -4.72890 22.71507 8.11379 -3.16488 29.14326 8.11379 -4.78404 25.94850 8.11379 -3.83817 28.38669 8.45102 -3.70615 5.68876 6.74746 -5.90533 3.90648 8.11379 4.61814 -4.13956 8.11379 5.47326 -2.53608 8.11426 -1.44278 -5.74114 8.11379 -4.85241 -4.18614 8.11426 -5.60089 -1.87615 6.87166 -7.13355 0.48086 8.11426 -5.89100 -0.42914 8.11426 1.63616 -5.70114 9.00000 3.74480 -1.09914 9.00000 2.25979 -3.07614 9.00000 0.02188 -4.58014 9.00000 0.02188 4.39287 9.00000 -2.21603 -3.07614 9.00000 -3.59913 -1.17314 8.49279 -3.55834 4.34187 7.87166 -5.40786 2.46296 5.89836 7.63414 -0.42213 8.11426 6.00887 0.10428 5.89836 6.94247 -3.64114 6.87166 3.66948 -6.17014 5.89836 4.79136 -6.19515 5.89836 1.77076 -7.62013 5.89836 -1.56868 -7.33768 6.39836 -4.61815 -6.29314 6.87166 -5.85402 -4.57393 6.87166 -6.53824 -2.89314 6.51675 -4.86510 5.63609 6.87166 -6.81239 2.17686 9.00019 0.02642 23.15286 8.99996 3.87812 25.23030 9.00000 0.02188 28.72610 8.11426 4.95033 25.05086 8.99996 3.11434 27.46986 8.11426 0.02188 29.93286 8.99996 -2.60559 27.58099 8.99996 -3.58678 25.82197 8.44282 -3.33963 20.40928 8.76643 -3.34911 22.56881 5.89836 6.76483 26.03687 5.89836 5.55840 28.98886 5.89836 3.14202 31.06985 5.89836 0.04374 31.82587 5.89836 -3.05930 31.08986 5.87166 -4.67070 29.33165 5.89836 -6.71430 26.07986 5.89836 -6.46749 22.90086 5.66186 -8.47778 9.50586 5.51919 -8.05887 15.99102 5.40636 -8.54068 12.82830 8.01986 -5.46231 17.55201 7.06936 -7.15262 16.53586 7.02846 -7.45782 12.93086 8.11236 -5.83721 12.86186 7.45706 -4.93237 19.65934 4.72556 -7.88683 17.09686 6.40616 -7.45056 17.15486 8.42246 3.69429 4.18787 7.62036 4.93940 22.20461 7.74536 5.53448 3.44444 6.30406 6.25102 22.77386 6.72456 6.68550 2.87236 4.75036 7.78174 2.14586 4.29086 7.00277 24.01886 8.21846 3.73770 21.84346 8.49296 0.02188 20.53786 8.48216 -3.70556 18.59785 8.49296 -3.88961 12.77786 8.49296 0.02188 5.46986 8.47376 -4.31842 6.98785 8.00676 -5.97789 7.98236 6.97873 -7.50773 8.86243 5.14776 -5.65164 5.67686 + + + + + + + + + + -0.43084 -0.64978 -0.62623 -0.99998 -0.00544 -0.00291 -0.99999 0.00327 0.00175 -1.00000 -0.00290 0.00000 -0.99728 0.07367 0.00000 0.00000 0.99920 0.04000 0.00000 0.99920 0.04000 -0.08009 0.99599 0.03987 -0.12798 0.99105 0.03798 -0.47339 0.87988 0.04128 -0.36485 0.93065 0.02803 -0.74029 0.67160 0.03030 -0.71143 0.70224 0.02702 -0.89745 0.44067 0.01996 -0.93713 0.34885 0.00997 -0.99966 0.02320 0.01149 -0.00000 -0.99519 0.09792 -0.00000 -0.99519 0.09792 -0.00000 -0.99989 0.01487 -0.00000 -0.99989 0.01487 -0.16644 -0.72939 0.66354 -0.07913 -0.69391 0.71570 0.29821 -0.71453 0.63287 -0.00000 -0.77008 0.63794 0.00000 -0.77008 0.63794 -0.26673 -0.75814 -0.59504 -0.00321 -0.71872 -0.69529 -0.00000 -0.71845 -0.69557 -0.00000 -0.71845 -0.69557 -0.96497 -0.26186 0.01619 -0.98119 -0.19242 -0.01569 -0.82951 -0.55849 -0.00185 -0.83115 -0.55604 -0.00334 -0.47043 -0.87472 0.11647 -0.55126 -0.83186 0.06417 -0.59392 -0.80452 0.00261 -0.55384 -0.83219 0.02684 -0.22374 -0.97465 -0.00125 -0.24438 -0.95988 0.13751 -0.19296 -0.97604 0.10053 -0.19998 -0.97969 0.01457 -0.00000 -0.92814 -0.37223 -0.00000 -0.86374 -0.50394 -0.00000 -0.98971 -0.14308 0.00000 -0.98971 -0.14309 0.00000 -0.96661 0.25626 0.00000 -0.96661 0.25626 0.00000 -0.78890 0.61452 0.00000 -0.78890 0.61452 0.00000 -0.48488 0.87458 0.00000 -0.48488 0.87458 0.00000 -0.10320 0.99466 0.00000 -0.10320 0.99466 -0.00000 0.29465 0.95561 -0.00000 0.29465 0.95561 -0.00000 0.53781 0.84307 0.00000 0.53781 0.84307 0.00000 0.82511 0.56497 0.00000 0.82511 0.56497 0.00000 0.98052 0.19640 0.00000 0.98052 0.19640 0.00000 0.99997 -0.00788 0.00000 0.99997 -0.00788 -0.03267 0.99827 -0.04878 -0.00952 -0.86293 -0.50524 -0.19191 -0.91946 -0.34316 -0.06431 -0.98766 -0.14279 -0.23172 -0.96986 -0.07530 -0.17124 -0.95233 0.25247 -0.51028 -0.72626 0.46061 -0.36232 -0.73530 0.57277 -0.43045 -0.66867 0.60630 -0.14650 -0.47965 0.86514 -0.29107 -0.22079 0.93088 -0.01223 -0.10319 0.99459 -0.37255 0.27344 0.88681 -0.24082 0.23008 0.94290 -0.16695 0.53026 0.83123 -0.34141 0.61335 0.71220 0.01944 0.82495 0.56486 -0.33363 0.87264 0.35663 -0.14825 0.96969 0.19423 -0.30923 0.94131 -0.13534 -0.28461 0.95178 -0.11449 -0.86952 -0.47582 -0.13239 -0.63819 -0.17768 0.74910 -0.63970 0.18221 0.74671 -0.67957 0.67909 0.27753 -0.62051 0.78284 -0.04612 -0.67429 0.72869 -0.11980 -0.73664 0.64008 0.21829 -0.77390 0.60030 -0.20181 -0.86584 0.47665 -0.15208 -0.97286 0.13731 -0.18626 -0.96646 0.12196 -0.22601 -1.00000 -0.00003 0.00003 -1.00000 -0.00004 0.00003 -0.98891 -0.00908 -0.14823 -0.98167 -0.03342 -0.18765 -0.99584 -0.05416 -0.07324 -0.36521 -0.86832 0.33561 -0.22066 -0.86307 -0.45434 -0.35140 -0.86713 -0.35299 -0.27065 -0.74481 -0.60993 -0.11867 -0.65509 -0.74618 -0.14801 0.24950 -0.95700 -0.22483 0.46623 -0.85562 -0.32338 0.40374 -0.85582 -0.45787 0.37931 -0.80404 -0.66821 0.56903 -0.47927 -0.17026 0.66634 -0.72595 -0.33540 0.72055 -0.60689 -0.17744 0.82100 -0.54265 -0.60860 0.77577 -0.16669 -0.16759 0.98511 0.03825 -0.00000 -0.96446 -0.26423 0.00000 -0.85296 0.52197 0.00000 -0.85296 0.52197 0.00000 -0.93275 0.36052 0.00000 -0.93275 0.36052 0.00000 -0.99219 0.12473 0.00000 -0.99219 0.12473 -0.00000 -0.99295 -0.11854 -0.00000 -0.99295 -0.11854 -0.00000 -0.88488 -0.46582 -0.00000 -0.88488 -0.46582 -0.00000 -0.65975 -0.75149 -0.00000 -0.65975 -0.75149 -0.00000 -0.45863 -0.88863 -0.00000 -0.45863 -0.88863 -0.00000 -0.11061 -0.99386 -0.00000 -0.11061 -0.99386 -0.00000 0.25228 -0.96765 -0.00000 0.25228 -0.96765 -0.00000 0.47848 -0.87810 -0.00000 0.47848 -0.87810 -0.00000 0.67621 -0.73671 -0.00000 0.67621 -0.73671 -0.00000 0.83424 -0.55140 -0.00000 0.83424 -0.55140 -0.00000 0.94264 -0.33380 -0.00000 0.94264 -0.33380 -0.00000 0.99944 -0.03345 0.00000 0.99944 -0.03345 -0.26643 -0.75723 -0.59634 -0.91489 -0.39448 0.08586 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -0.00000 -0.96446 -0.26423 -0.90158 0.24131 -0.35907 -0.90485 0.39604 0.15618 -0.94467 0.31082 0.10487 -0.89506 0.16219 0.41539 -0.74557 -0.65479 0.12399 -0.65095 -0.74758 -0.13190 -0.66918 -0.72860 -0.14608 -0.69626 -0.68280 -0.22138 -0.65402 -0.70065 -0.28522 -0.61787 -0.54789 -0.56396 -0.58197 -0.17649 -0.79382 -0.58414 0.01054 -0.81158 -0.65108 -0.06397 -0.75631 -0.64549 0.22621 -0.72950 -0.55447 0.81322 0.17674 -0.74717 0.66462 0.00400 -0.18101 -0.94853 -0.25987 -0.93915 -0.31722 0.13177 -0.92258 -0.37827 -0.07584 -0.92388 -0.36399 -0.11813 -0.95364 -0.24345 -0.17694 -0.89678 -0.24681 -0.36724 -0.79257 0.00792 -0.60973 -0.99956 -0.01586 0.02491 -0.81387 -0.56586 0.13199 0.00000 -0.92814 -0.37223 -0.84513 -0.41959 0.33122 -0.69413 -0.63215 0.34435 -0.66502 -0.62224 0.41300 -0.47825 -0.87339 0.09202 -0.22907 -0.92338 0.30805 -0.20936 -0.93219 0.29528 -0.06197 -0.91543 -0.39768 -0.44992 -0.87948 -0.15518 -0.40578 -0.90753 -0.10834 -0.36482 -0.92381 0.11613 -0.39655 -0.90198 0.17080 -0.72765 -0.28472 -0.62407 -0.92274 -0.16003 -0.35062 -0.78720 -0.59414 0.16529 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.98151 0.15842 0.10739 -0.89920 -0.13152 0.41731 -0.98615 -0.13901 0.09043 -0.91814 0.18394 -0.35098 -0.73800 0.31314 -0.59774 -0.51084 0.61558 -0.60008 -0.63402 0.68235 -0.36389 -0.59956 0.78433 -0.15921 -0.91399 0.39761 -0.08082 -0.96554 -0.26005 0.01002 -0.98113 -0.19024 0.03456 -0.85485 -0.51561 0.05807 -0.83137 -0.55445 0.03751 -0.14858 0.98885 0.00958 -0.43892 0.88671 0.14525 -0.57656 -0.53325 -0.61905 -0.39080 -0.71053 -0.58517 -0.44124 -0.74181 0.50500 -0.37160 -0.81095 0.45197 -0.72353 -0.58860 0.36064 -0.75356 -0.51410 0.40970 -0.67246 -0.62637 0.39428 -0.99951 -0.00949 0.02996 -0.99965 -0.01262 -0.02345 -0.48297 -0.78878 -0.38022 -0.51397 -0.85427 -0.07781 -0.45695 -0.75232 0.47457 -0.20294 -0.80005 0.56457 -1.00000 0.00005 0.00002 -1.00000 0.00003 0.00003 -0.64042 -0.76606 -0.05484 -0.85396 -0.50916 -0.10724 -0.86063 -0.50687 -0.04901 -0.79753 -0.56244 0.21819 -0.85811 -0.44842 0.25013 -0.85616 -0.38599 0.34351 -0.64381 -0.18412 0.74270 -0.64894 0.19266 0.73604 -0.76162 0.50854 0.40165 -0.75386 0.62553 0.20099 -0.62699 0.74169 0.23828 -0.63612 0.60551 0.47824 -0.55727 0.54184 0.62917 -0.48481 -0.64844 0.58693 -0.48698 -0.65246 0.58064 -0.47463 -0.74348 0.47114 -0.64037 -0.71607 0.27779 -0.79712 -0.59566 -0.09897 -0.65381 -0.75439 -0.05857 -0.64141 -0.76598 -0.04315 -0.92870 0.32722 -0.17450 -0.94438 0.26293 -0.19750 -0.88324 -0.18735 0.42986 -0.79998 -0.14442 0.58239 -0.79902 0.15230 0.58169 -0.86767 0.18711 0.46059 -0.33715 -0.07934 -0.93810 -0.28355 -0.10607 -0.95307 -0.40679 -0.23563 -0.88261 -0.15968 -0.45274 -0.87723 -0.21262 0.92109 -0.32617 -0.41120 0.89121 -0.19149 0.41325 0.89030 -0.19130 0.21384 0.92084 -0.32608 0.16033 -0.45269 -0.87713 0.40856 -0.23510 -0.88193 0.28512 -0.10602 -0.95261 0.33894 -0.07929 -0.93746 0.86591 0.18827 0.46342 0.79665 0.15309 0.58473 0.79762 -0.14517 0.58543 0.88165 -0.18855 0.43260 0.94354 0.26485 -0.19894 0.92765 0.32953 -0.17573 0.64141 -0.76598 -0.04315 0.65381 -0.75439 -0.05857 0.79456 -0.59876 -0.10078 0.64037 -0.71607 0.27779 0.47463 -0.74348 0.47114 0.48698 -0.65246 0.58064 0.48481 -0.64844 0.58693 0.55727 0.54184 0.62917 0.63612 0.60551 0.47824 0.62699 0.74169 0.23828 0.75120 0.62843 0.20193 0.75900 0.51095 0.40355 0.64894 0.19266 0.73604 0.64381 -0.18412 0.74270 0.85428 -0.38831 0.34557 0.85625 -0.45112 0.25164 0.79515 -0.56536 0.21933 0.86063 -0.50687 -0.04901 0.85396 -0.50916 -0.10724 0.64042 -0.76606 -0.05484 1.00000 0.00003 0.00003 1.00000 0.00005 0.00002 0.20411 -0.79963 0.56474 0.45858 -0.75108 0.47496 0.51397 -0.85427 -0.07781 0.48297 -0.78878 -0.38022 0.99965 -0.01262 -0.02345 0.99951 -0.00949 0.02996 0.67246 -0.62637 0.39428 0.75356 -0.51409 0.40970 0.72353 -0.58860 0.36064 0.37160 -0.81095 0.45197 0.44124 -0.74181 0.50500 0.39080 -0.71053 -0.58517 0.57656 -0.53325 -0.61905 0.43892 0.88671 0.14525 0.14858 0.98885 0.00958 0.83138 -0.55444 0.03751 0.85485 -0.51561 0.05807 0.98113 -0.19024 0.03456 0.96554 -0.26005 0.01002 0.91275 0.40033 -0.08137 0.59956 0.78433 -0.15921 0.63402 0.68235 -0.36389 0.51084 0.61559 -0.60008 0.73800 0.31314 -0.59774 0.91695 0.18521 -0.35340 0.98576 -0.14096 0.09170 0.89670 -0.13305 0.42216 0.98106 0.16035 0.10870 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 0.78720 -0.59414 0.16529 0.92162 -0.16115 -0.35307 0.72765 -0.28472 -0.62407 0.39764 -0.90152 0.17072 0.36584 -0.92341 0.11608 0.40688 -0.90704 -0.10829 0.45108 -0.87891 -0.15507 0.06211 -0.91555 -0.39738 0.20937 -0.93219 0.29528 0.22907 -0.92338 0.30805 0.47825 -0.87339 0.09202 0.66502 -0.62224 0.41300 0.69413 -0.63215 0.34435 0.84513 -0.41959 0.33122 0.81387 -0.56586 0.13199 0.99956 -0.01586 0.02491 0.79015 0.00796 -0.61286 0.89534 -0.24843 -0.36966 0.95292 -0.24527 -0.17826 0.92277 -0.36653 -0.11895 0.92145 -0.38091 -0.07637 0.93826 -0.31972 0.13212 0.18102 -0.94853 -0.25987 0.74717 0.66462 0.00400 0.55447 0.81322 0.17674 0.64549 0.22621 -0.72950 0.65108 -0.06397 -0.75631 0.58414 0.01054 -0.81158 0.58197 -0.17649 -0.79382 0.61787 -0.54789 -0.56396 0.65402 -0.70064 -0.28522 0.69626 -0.68280 -0.22138 0.66918 -0.72860 -0.14608 0.65095 -0.74757 -0.13190 0.74557 -0.65479 0.12399 0.89253 0.16382 0.42019 0.94386 0.31286 0.10609 0.90485 0.39604 0.15618 0.90019 0.24292 -0.36146 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 0.91435 -0.39547 0.08702 0.26643 -0.75723 -0.59634 0.16796 0.98503 0.03880 0.60860 0.77577 -0.16669 0.17848 0.82084 -0.54255 0.33719 0.72006 -0.60647 0.17126 0.66622 -0.72582 0.66821 0.56903 -0.47927 0.45787 0.37931 -0.80404 0.32512 0.40348 -0.85528 0.22611 0.46609 -0.85536 0.14888 0.24947 -0.95687 0.11916 -0.65505 -0.74613 0.27151 -0.74449 -0.60993 0.35239 -0.86678 -0.35285 0.22134 -0.86293 -0.45426 0.36624 -0.86795 0.33547 0.99558 -0.05587 -0.07555 0.98111 -0.03503 -0.19024 0.98891 -0.00908 -0.14823 1.00000 -0.00004 0.00003 1.00000 -0.00003 0.00003 0.96587 0.12301 -0.22797 0.97224 0.13817 -0.18882 0.86584 0.47665 -0.15208 0.77133 0.60319 -0.20299 0.73388 0.64292 0.21926 0.67428 0.72869 -0.11980 0.62051 0.78284 -0.04612 0.67957 0.67909 0.27753 0.63970 0.18221 0.74671 0.63819 -0.17768 0.74910 0.86952 -0.47582 -0.13239 0.28461 0.95178 -0.11449 0.31198 0.94006 -0.13767 0.14912 0.96956 0.19420 0.33541 0.87206 0.35639 -0.01956 0.82495 0.56486 0.34323 0.61292 0.71170 0.16792 0.53017 0.83109 0.24219 0.23000 0.94257 0.37448 0.27321 0.88607 0.01231 -0.10319 0.99459 0.29267 -0.22068 0.93040 0.14736 -0.47959 0.86503 0.43258 -0.66793 0.60559 0.36425 -0.73470 0.57230 0.51256 -0.72510 0.45990 0.17223 -0.95216 0.25243 0.23304 -0.96955 -0.07527 0.06438 -0.98764 -0.14290 0.19191 -0.91946 -0.34316 0.00953 -0.86293 -0.50524 0.03284 0.99826 -0.04900 0.19998 -0.97969 0.01457 0.19296 -0.97604 0.10053 0.24438 -0.95988 0.13751 0.22374 -0.97465 -0.00125 0.55384 -0.83219 0.02684 0.59392 -0.80452 0.00261 0.55126 -0.83186 0.06417 0.47043 -0.87472 0.11647 0.83115 -0.55603 -0.00334 0.82951 -0.55848 -0.00185 0.98119 -0.19242 -0.01569 0.96497 -0.26186 0.01619 0.00323 -0.71872 -0.69529 0.26673 -0.75814 -0.59504 -0.29870 -0.71412 0.63309 0.07929 -0.69398 0.71562 0.16644 -0.72939 0.66354 0.99966 0.02320 0.01149 0.93713 0.34885 0.00997 0.89745 0.44067 0.01996 0.71143 0.70224 0.02702 0.74029 0.67160 0.03030 0.36484 0.93065 0.02803 0.47339 0.87988 0.04128 0.12798 0.99105 0.03798 0.08078 0.99594 0.03984 0.99728 0.07367 -0.00000 1.00000 -0.00290 -0.00000 0.99999 0.00327 0.00175 0.99998 -0.00544 -0.00291 0.43085 -0.64977 -0.62623 -0.00000 -0.86374 -0.50394 + + + + + + + + + + + + + + +

0 0 1 0 2 0 4 1 3 1 5 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 4 4 7 4 9 5 10 5 11 5 12 6 11 6 10 6 13 7 10 7 9 7 13 8 9 8 14 8 14 9 15 9 13 9 16 10 13 10 15 10 15 11 17 11 16 11 18 12 16 12 17 12 8 13 18 13 17 13 17 14 19 14 8 14 19 15 4 15 8 15 20 16 21 16 22 16 23 17 22 17 21 17 21 18 24 18 23 18 25 19 23 19 24 19 26 20 27 20 28 20 29 21 28 21 27 21 27 22 20 22 29 22 29 23 20 23 22 23 30 24 29 24 22 24 1 25 0 25 31 25 0 26 32 26 31 26 33 27 34 27 31 27 32 28 33 28 31 28 5 29 3 29 2 29 36 30 5 30 2 30 36 31 2 31 1 31 37 32 36 32 1 32 40 33 41 33 38 33 37 34 40 34 38 34 37 35 1 35 42 35 40 36 37 36 42 36 42 37 24 37 40 37 20 38 41 38 40 38 40 39 21 39 20 39 40 40 24 40 21 40 35 41 43 41 29 41 43 42 44 42 54 42 44 43 45 43 54 43 55 44 54 44 45 44 45 45 46 45 55 45 56 46 55 46 46 46 46 47 47 47 56 47 57 48 56 48 47 48 47 49 48 49 57 49 58 50 57 50 48 50 48 51 49 51 58 51 59 52 58 52 49 52 49 53 50 53 59 53 60 54 59 54 50 54 50 55 51 55 60 55 61 56 60 56 51 56 51 57 52 57 61 57 62 58 61 58 52 58 52 59 53 59 62 59 63 60 62 60 53 60 12 61 63 61 53 61 63 62 12 62 10 62 63 63 10 63 13 63 28 64 43 64 54 64 64 65 28 65 54 65 64 66 54 66 55 66 65 67 64 67 55 67 55 68 56 68 65 68 66 69 65 69 56 69 66 70 56 70 57 70 67 71 66 71 57 71 57 72 58 72 67 72 68 73 67 73 58 73 58 74 59 74 68 74 68 75 59 75 60 75 69 76 68 76 60 76 60 77 61 77 69 77 70 78 69 78 61 78 61 79 62 79 70 79 71 80 70 80 62 80 62 81 63 81 71 81 71 82 63 82 13 82 71 83 13 83 16 83 72 84 73 84 28 84 67 85 68 85 76 85 68 86 69 86 76 86 70 87 71 87 78 87 71 88 16 88 78 88 18 89 78 89 16 89 80 90 77 90 78 90 8 91 80 91 78 91 78 92 18 92 8 92 8 93 7 93 81 93 8 94 81 94 80 94 75 95 79 95 81 95 74 96 75 96 81 96 72 97 7 97 73 97 7 98 72 98 81 98 74 99 81 99 72 99 85 100 84 100 82 100 89 101 90 101 88 101 86 102 89 102 88 102 89 103 91 103 90 103 92 104 90 104 91 104 97 105 96 105 95 105 98 106 99 106 97 106 95 107 98 107 97 107 98 108 95 108 100 108 100 109 101 109 98 109 102 110 99 110 98 110 98 111 101 111 102 111 103 112 102 112 101 112 105 113 101 113 104 113 9 114 106 114 105 114 34 115 25 115 31 115 84 116 33 116 32 116 33 117 84 117 107 117 84 118 85 118 107 118 108 119 107 119 85 119 85 120 87 120 108 120 109 121 108 121 87 121 87 122 88 122 109 122 110 123 109 123 88 123 88 124 90 124 110 124 111 125 110 125 90 125 90 126 92 126 111 126 112 127 111 127 92 127 92 128 94 128 112 128 113 129 112 129 94 129 94 130 96 130 113 130 114 131 113 131 96 131 96 132 97 132 114 132 115 133 114 133 97 133 97 134 99 134 115 134 116 135 115 135 99 135 99 136 102 136 116 136 117 137 116 137 102 137 102 138 103 138 117 138 118 139 117 139 103 139 103 140 106 140 118 140 119 141 118 141 106 141 106 142 9 142 119 142 11 143 119 143 9 143 1 144 31 144 42 144 120 145 121 145 122 145 123 146 122 146 124 146 125 147 123 147 124 147 24 148 31 148 25 148 126 149 128 149 125 149 104 150 19 150 17 150 104 151 127 151 19 151 19 152 124 152 4 152 130 153 82 153 129 153 86 154 130 154 129 154 129 155 131 155 86 155 131 156 132 156 86 156 89 157 86 157 132 157 91 158 89 158 132 158 93 159 91 159 133 159 133 160 128 160 93 160 95 161 93 161 128 161 100 162 95 162 128 162 104 163 17 163 105 163 15 164 105 164 17 164 24 165 42 165 31 165 120 166 122 166 129 166 131 167 129 167 122 167 122 168 132 168 131 168 122 169 123 169 132 169 123 170 125 170 133 170 128 171 133 171 125 171 6 172 73 172 7 172 6 173 28 173 73 173 30 174 35 174 29 174 6 175 39 175 28 175 26 176 28 176 39 176 39 177 38 177 26 177 41 178 26 178 38 178 27 179 26 179 41 179 41 180 20 180 27 180 29 181 43 181 28 181 86 182 88 182 130 182 87 183 130 183 88 183 85 184 130 184 87 184 82 185 130 185 85 185 91 186 132 186 133 186 123 187 133 187 132 187 82 188 120 188 129 188 124 189 126 189 125 189 124 190 127 190 126 190 19 191 127 191 124 191 4 192 124 192 121 192 121 193 124 193 122 193 126 194 135 194 128 194 135 195 100 195 128 195 100 196 135 196 101 196 134 197 101 197 135 197 101 198 134 198 104 198 134 199 127 199 104 199 5 200 39 200 6 200 5 201 36 201 39 201 36 202 38 202 39 202 36 203 37 203 38 203 9 204 105 204 14 204 14 205 105 205 15 205 2 206 3 206 83 206 0 207 2 207 83 207 136 208 0 208 83 208 82 209 0 209 136 209 82 210 136 210 120 210 136 211 83 211 120 211 83 212 121 212 120 212 121 213 137 213 4 213 137 214 3 214 4 214 3 215 137 215 83 215 137 216 121 216 83 216 0 217 82 217 84 217 0 218 84 218 32 218 77 219 80 219 81 219 77 220 81 220 79 220 64 221 141 221 28 221 141 222 72 222 28 222 139 223 72 223 141 223 138 224 74 224 139 224 74 225 138 225 75 225 140 226 75 226 138 226 140 227 67 227 76 227 69 228 143 228 76 228 142 229 77 229 143 229 77 230 142 230 78 230 142 231 70 231 78 231 70 232 142 232 143 232 70 233 143 233 69 233 67 234 140 234 66 234 140 235 138 235 66 235 66 236 138 236 65 236 138 237 139 237 65 237 72 238 139 238 74 238 65 239 139 239 64 239 139 240 141 240 64 240 127 241 134 241 135 241 127 242 135 242 126 242 75 243 140 243 79 243 76 244 79 244 140 244 76 245 143 245 79 245 77 246 79 246 143 246 93 247 95 247 96 247 93 248 96 248 94 248 91 249 93 249 94 249 91 250 94 250 92 250 101 251 106 251 103 251 101 252 105 252 106 252 170 253 119 253 168 253 170 254 118 254 119 254 175 255 112 255 113 255 175 256 113 256 174 256 174 257 113 257 114 257 174 258 114 258 173 258 184 259 144 259 182 259 185 260 182 260 144 260 185 261 147 261 182 261 186 262 182 262 147 262 160 263 161 263 152 263 160 264 152 264 153 264 148 265 197 265 146 265 196 266 197 266 148 266 189 267 187 267 148 267 149 268 196 268 148 268 195 269 196 269 149 269 147 270 195 270 149 270 194 271 195 271 147 271 191 272 192 272 144 272 191 273 144 273 145 273 145 274 183 274 191 274 184 275 183 275 145 275 145 276 144 276 184 276 192 277 185 277 144 277 147 278 185 278 194 278 147 279 149 279 186 279 187 280 186 280 149 280 149 281 148 281 187 281 148 282 146 282 189 282 146 283 205 283 189 283 197 284 205 284 146 284 184 285 182 285 180 285 184 286 180 286 181 286 223 287 33 287 107 287 223 288 107 288 179 288 150 289 178 289 166 289 220 290 178 290 150 290 150 291 219 291 220 291 166 292 219 292 150 292 178 293 167 293 166 293 151 294 167 294 178 294 179 295 167 295 151 295 151 296 223 296 179 296 178 297 223 297 151 297 223 298 178 298 221 298 221 299 178 299 220 299 213 300 212 300 168 300 11 301 213 301 168 301 204 302 202 302 203 302 204 303 201 303 202 303 218 304 201 304 204 304 218 305 217 305 201 305 153 306 169 306 160 306 170 307 169 307 153 307 153 308 152 308 170 308 171 309 170 309 152 309 152 310 159 310 171 310 161 311 159 311 152 311 166 312 165 312 163 312 219 313 166 313 163 313 208 314 163 314 160 314 163 315 161 315 160 315 163 316 162 316 161 316 179 317 158 317 167 317 164 318 155 318 154 318 175 319 154 319 155 319 179 320 108 320 157 320 108 321 109 321 157 321 109 322 110 322 157 322 177 323 157 323 110 323 30 324 205 324 35 324 199 325 206 325 22 325 206 326 199 326 207 326 199 327 202 327 207 327 201 328 207 328 202 328 207 329 201 329 205 329 217 330 205 330 201 330 217 331 188 331 205 331 217 332 216 332 188 332 159 333 162 333 154 333 164 334 154 334 162 334 165 335 155 335 164 335 165 336 156 336 155 336 156 337 165 337 158 337 167 338 158 338 165 338 25 339 34 339 198 339 212 340 210 340 168 340 169 341 168 341 210 341 171 342 159 342 173 342 173 343 159 343 174 343 154 344 174 344 159 344 174 345 154 345 175 345 175 346 155 346 176 346 176 347 155 347 177 347 156 348 177 348 155 348 158 349 177 349 156 349 177 350 158 350 157 350 157 351 158 351 179 351 208 352 219 352 163 352 169 353 208 353 160 353 169 354 210 354 208 354 161 355 162 355 159 355 162 356 163 356 164 356 164 357 163 357 165 357 167 358 165 358 166 358 222 359 198 359 34 359 11 360 168 360 119 360 168 361 169 361 170 361 118 362 170 362 117 362 172 363 117 363 170 363 117 364 172 364 116 364 171 365 172 365 170 365 172 366 171 366 173 366 173 367 115 367 172 367 172 368 115 368 116 368 115 369 173 369 114 369 112 370 175 370 111 370 176 371 111 371 175 371 177 372 110 372 176 372 176 373 110 373 111 373 108 374 179 374 107 374 187 375 189 375 180 375 216 376 180 376 189 376 189 377 188 377 216 377 187 378 180 378 186 378 186 379 180 379 182 379 215 380 181 380 180 380 215 381 180 381 216 381 183 382 215 382 209 382 215 383 183 383 181 383 181 384 183 384 184 384 209 385 211 385 183 385 190 386 183 386 211 386 191 387 183 387 190 387 193 388 185 388 192 388 194 389 185 389 193 389 189 390 205 390 188 390 190 391 211 391 214 391 190 392 214 392 53 392 52 393 190 393 53 393 190 394 52 394 191 394 51 395 191 395 52 395 191 396 51 396 192 396 50 397 192 397 51 397 192 398 50 398 193 398 193 399 50 399 49 399 48 400 193 400 49 400 193 401 48 401 194 401 47 402 194 402 48 402 194 403 47 403 195 403 195 404 47 404 46 404 195 405 46 405 196 405 45 406 196 406 46 406 196 407 45 407 197 407 197 408 45 408 44 408 197 409 44 409 205 409 205 410 44 410 35 410 53 411 214 411 12 411 200 412 23 412 25 412 200 413 22 413 23 413 22 414 200 414 199 414 198 415 200 415 25 415 200 416 198 416 203 416 203 417 198 417 222 417 203 418 202 418 200 418 200 419 202 419 199 419 203 420 222 420 204 420 204 421 222 421 221 421 204 422 221 422 218 422 218 423 221 423 220 423 223 424 34 424 33 424 34 425 223 425 222 425 206 426 30 426 22 426 30 427 206 427 205 427 207 428 205 428 206 428 208 429 215 429 219 429 210 430 215 430 208 430 215 431 210 431 209 431 209 432 210 432 211 432 212 433 211 433 210 433 211 434 212 434 214 434 213 435 214 435 212 435 214 436 213 436 11 436 214 437 11 437 12 437 215 438 216 438 219 438 219 439 216 439 217 439 219 440 217 440 218 440 219 441 218 441 220 441 223 442 221 442 222 442 35 443 44 443 43 443

+
+
+
+
+ + + + 0.00000 0.00000 0.00004 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_middle/f_middle_E3M5_no_rot_scaled.dae b/URDFs/sr_description/meshes/components/f_middle/f_middle_E3M5_no_rot_scaled.dae new file mode 100644 index 0000000..03d95a7 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_middle/f_middle_E3M5_no_rot_scaled.dae @@ -0,0 +1,210 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:53:44 + 2025-02-20T09:53:44 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -5.15497 -5.65164 5.67687 -6.98593 -7.50773 8.86243 -8.01397 -5.97789 7.98236 -8.48097 -4.31842 6.98785 -8.50017 0.02187997 5.46986 -8.50017 -3.88961 12.77786 -8.48937 -3.70556 18.59785 -8.50017 0.02187997 20.53786 -8.22567 3.7377 21.84346 -3.50017 7.97965 1.21886 -3.50017 7.0498 24.44685 3.49296 7.97965 1.21886 3.49983 7.0498 24.44685 -4.29807 7.00277 24.01886 -4.75757 7.78174 2.14586 -6.73177 6.6855 2.87236 -6.31127 6.25102 22.77386 -7.75257 5.53448 3.44444 -7.62757 4.9394 22.20461 -8.42967 3.69429 4.18787 -3.43169 -8.64405 15.62886 -3.50017 -8.93332 12.68886 3.42448 -8.64405 15.62886 3.49296 -8.93332 12.68886 -3.50017 -8.97607 9.81386 3.49296 -8.97607 9.81386 -6.41337 -7.45056 17.15486 -4.73277 -7.88683 17.09686 -7.46427 -4.93237 19.65934 -4.00017 -5.21445 19.76886 3.99983 -5.21445 19.76886 -3.50017 -8.70539 8.82587 -4.00017 -5.82319 5.84886 3.99983 -5.82319 5.84886 3.49296 -8.70539 8.82587 4.48796 -5.6171 20.77286 -8.11957 -5.83721 12.86186 -7.03567 -7.45782 12.93086 -7.07657 -7.15262 16.53586 -8.02707 -5.46231 17.55201 -5.41357 -8.54068 12.8283 -5.5264 -8.05887 15.99102 -5.66907 -8.47778 9.50586 -4.49517 -5.6171 20.77286 4.75036 -6.438 22.17986 4.75723 -6.97321 25.88187 4.75723 -6.48965 27.70586 4.75723 -4.19093 30.65686 4.75723 -2.54057 31.57185 4.75723 1.1798 31.95786 4.75723 2.98301 31.40186 4.75723 4.57411 30.38686 4.75723 6.68716 27.30086 4.75723 7.05771 25.45087 -4.75757 -6.438 22.17986 -4.75757 -6.97321 25.88187 -4.75757 -6.48965 27.70586 -4.75757 -4.19093 30.65686 -4.75757 -2.54057 31.57185 -4.75757 1.1798 31.95786 -4.75757 2.98301 31.40186 -4.75757 4.57411 30.38686 -4.75757 6.68716 27.30086 -4.75757 7.05771 25.45087 -5.90557 -6.46749 22.90086 -5.90557 -6.7143 26.07986 -5.87887 -4.6707 29.33165 -5.90557 -3.0593 31.08986 -5.90557 0.04374998 31.82587 -5.90557 3.14202 31.06985 -5.90557 5.5584 28.98886 -5.90557 6.76483 26.03687 -8.77364 -3.34911 22.56881 -8.45003 -3.33963 20.40928 -8.99996 -3.58678 25.82197 -8.99996 -2.60559 27.58099 -8.12147 0.02187997 29.93286 -8.99996 3.11434 27.46986 -8.12147 4.95033 25.05086 -9 0.02187997 28.7261 -8.99996 3.87812 25.2303 -9.00019 0.02641999 23.15286 -6.87887 -6.81239 2.17687 -6.52396 -4.8651 5.63609 -4.75757 -7.07768 3.79886 -4.75757 -7.78383 1.97186 -6.87887 -6.53824 -2.89314 -4.75757 -8.02808 0.02884995 -4.75757 -7.796 -1.91515 -6.87887 -5.85402 -4.57393 -4.75757 -5.98513 -5.35513 -6.40557 -4.61815 -6.29314 -4.75757 -4.51347 -6.64714 -5.90557 -1.56868 -7.33768 -4.75757 -2.77352 -7.54514 -5.90557 1.77076 -7.62013 -4.75757 1.0901 -7.97514 -4.75757 2.9849 -7.48114 -5.90557 4.79136 -6.19514 -4.75757 4.70447 -6.54414 -6.87887 3.66948 -6.17014 -5.90557 6.94247 -3.64114 -4.75757 6.14692 -5.22014 -4.75757 7.22694 -3.58614 -8.12147 6.00887 0.10429 -5.90557 7.63414 -0.42213 -4.75757 7.88062 -1.74014 4.75723 -7.07768 3.79886 4.75723 -7.78383 1.97186 4.75723 -8.02808 0.02884995 4.75723 -7.796 -1.91515 4.75723 -5.98513 -5.35513 4.75723 -4.51347 -6.64714 4.75723 -2.77352 -7.54514 4.75723 1.0901 -7.97514 4.75723 2.9849 -7.48114 4.75723 4.70447 -6.54414 4.75723 6.14692 -5.22014 4.75723 7.22694 -3.58614 4.75723 7.88062 -1.74014 -7.87887 -5.40786 2.46296 -8.5 -3.55834 4.34187 -9 -3.59913 -1.17314 -9 -2.21603 -3.07614 -9 0.02187997 4.39287 -9 0.02187997 -4.58014 -9 2.25979 -3.07614 -9 3.7448 -1.09914 -8.12147 1.63616 -5.70114 -8.12147 -5.891 -0.42914 -6.87887 -7.13355 0.48087 -8.12147 -5.60089 -1.87614 -8.121 -4.85241 -4.18614 -8.12147 -1.44278 -5.74113 -8.121 5.47326 -2.53608 -8.121 4.61814 -4.13956 -6.75466 -5.90532 3.90648 -8.45823 -3.70615 5.68876 -8.121 -3.83817 28.38669 -8.121 -4.78404 25.9485 -8.121 -3.16487 29.14326 -7.96933 -4.7289 22.71507 -8.121 3.9973 28.01863 -8.121 3.12703 29.12051 8.11379 3.12703 29.12051 8.11379 3.9973 28.01863 7.96212 -4.7289 22.71507 8.11379 -3.16488 29.14326 8.11379 -4.78404 25.9485 8.11379 -3.83817 28.38669 8.451021 -3.70615 5.68876 6.74746 -5.90533 3.90648 8.11379 4.61814 -4.13956 8.11379 5.47326 -2.53608 8.11426 -1.44278 -5.74114 8.11379 -4.85241 -4.18614 8.11426 -5.60089 -1.87615 6.87166 -7.13355 0.48086 8.11426 -5.891 -0.42914 8.11426 1.63616 -5.70114 9 3.7448 -1.09914 9 2.25979 -3.07614 9 0.02187997 -4.58014 9 0.02187997 4.39287 9 -2.21603 -3.07614 9 -3.59913 -1.17314 8.492791 -3.55834 4.34187 7.87166 -5.40786 2.46296 5.89836 7.63414 -0.42213 8.11426 6.00887 0.1042799 5.89836 6.94247 -3.64114 6.87166 3.66948 -6.17014 5.89836 4.79136 -6.19515 5.89836 1.77076 -7.62013 5.89836 -1.56868 -7.33768 6.39836 -4.61815 -6.29314 6.87166 -5.85402 -4.57393 6.87166 -6.53824 -2.89314 6.51675 -4.8651 5.63609 6.87166 -6.81239 2.17686 9.00019 0.02641999 23.15286 8.99996 3.87812 25.2303 9 0.02187997 28.7261 8.11426 4.95033 25.05086 8.99996 3.11434 27.46986 8.11426 0.02187997 29.93286 8.99996 -2.60559 27.58099 8.99996 -3.58678 25.82197 8.44282 -3.33963 20.40928 8.76643 -3.34911 22.56881 5.89836 6.76483 26.03687 5.89836 5.5584 28.98886 5.89836 3.14202 31.06985 5.89836 0.04373997 31.82587 5.89836 -3.0593 31.08986 5.87166 -4.6707 29.33165 5.89836 -6.7143 26.07986 5.89836 -6.46749 22.90086 5.66186 -8.47778 9.50586 5.51919 -8.05887 15.99102 5.40636 -8.54068 12.8283 8.019861 -5.46231 17.55201 7.06936 -7.15262 16.53586 7.02846 -7.45782 12.93086 8.11236 -5.83721 12.86186 7.45706 -4.93237 19.65934 4.72556 -7.88683 17.09686 6.40616 -7.45056 17.15486 8.42246 3.69429 4.18787 7.62036 4.9394 22.20461 7.74536 5.53448 3.44444 6.30406 6.25102 22.77386 6.72456 6.6855 2.87236 4.75036 7.78174 2.14586 4.29086 7.00277 24.01886 8.218461 3.7377 21.84346 8.49296 0.02187997 20.53786 8.48216 -3.70556 18.59785 8.49296 -3.88961 12.77786 8.49296 0.02187997 5.46986 8.47376 -4.31842 6.98785 8.00676 -5.97789 7.98236 6.97873 -7.50773 8.86243 5.14776 -5.65164 5.67686 + + + + + + + + + + -0.4308437 -0.649775 -0.6262317 -0.9999811 -0.005441963 -0.002912938 -0.9999932 0.003272891 0.001752138 -0.9999958 -0.002897262 0 -0.9972825 0.07367265 0 0 0.9991997 0.03999942 0 0.9991997 0.03999936 -0.08009231 0.9959898 0.03987085 -0.127985 0.9910485 0.03798317 -0.4733932 0.8798836 0.04128032 -0.3648453 0.9306463 0.02802628 -0.7402926 0.6716015 0.03030383 -0.7114266 0.702241 0.0270155 -0.8974468 0.4406709 0.01995801 -0.9371277 0.3488443 0.009970188 -0.9996648 0.02320361 0.01149344 0 -0.9951945 0.09791904 0 -0.9951946 0.09791803 0 -0.9998895 0.0148676 0 -0.9998896 0.0148676 -0.1664447 -0.7293899 0.6635411 -0.07913184 -0.6939079 0.7157025 0.2982088 -0.7145281 0.6328674 0 -0.7700845 0.637942 0 -0.7700843 0.6379423 -0.2667284 -0.7581416 -0.5950439 -0.003214597 -0.7187208 -0.6952913 0 -0.7184547 -0.6955739 -0.9649717 -0.2618538 0.01619297 -0.9811874 -0.1924199 -0.01568681 -0.8295104 -0.5584884 -0.001850247 -0.831152 -0.5560352 -0.003340184 -0.4704337 -0.8747152 0.116472 -0.551264 -0.8318595 0.06417095 -0.5939166 -0.8045224 0.002608835 -0.5538441 -0.8321878 0.02683615 -0.2237417 -0.9746478 -0.001245677 -0.2443786 -0.9598802 0.1375104 -0.1929633 -0.9760427 0.1005285 -0.1999766 -0.9796924 0.01456767 0 -0.9281419 -0.3722265 0 -0.863739 -0.5039396 0 -0.9897105 -0.1430849 0 -0.9897103 -0.1430855 0 -0.9666082 0.2562589 0 -0.9666083 0.2562585 0 -0.7888987 0.6145232 0 -0.7888987 0.6145234 0 -0.4848834 0.8745788 0 -0.4848835 0.8745788 0 -0.1032016 0.9946605 0 -0.1032016 0.9946605 0 0.2946503 0.9556053 0 0.2946503 0.9556053 0 0.5378109 0.8430656 0 0.8251108 0.5649709 0 0.825111 0.5649708 0 0.9805245 0.1963966 0 0.9805244 0.1963974 0 0.9999691 -0.007877469 0 0.999969 -0.007877588 -0.03267312 0.9982749 -0.04878216 -0.009522497 -0.8629256 -0.5052413 -0.1919035 -0.9194633 -0.3431624 -0.06430685 -0.9876619 -0.1427892 -0.2317212 -0.9698637 -0.07529801 -0.1712378 -0.9523311 0.2524741 -0.5102789 -0.7262601 0.4606102 -0.3623155 -0.7352974 0.5727698 -0.4304507 -0.6686672 0.6062973 -0.1464968 -0.4796521 0.8651432 -0.2910674 -0.2207936 0.930876 -0.01222872 -0.1031938 0.9945862 -0.3725479 0.2734389 0.8868141 -0.2408308 0.2300807 0.9429016 -0.1669487 0.530263 0.8312336 -0.341415 0.613352 0.7122045 0.01943564 0.8249548 0.5648644 -0.3336294 0.8726415 0.3566346 -0.1482455 0.9696904 0.1942268 -0.3092325 0.9413067 -0.1353402 -0.2846054 0.9517839 -0.1144866 -0.8695221 -0.4758201 -0.1323885 -0.6381881 -0.1776778 0.7490972 -0.6397028 0.182208 0.7467132 -0.6795684 0.6790896 0.2775325 -0.6205103 0.782841 -0.04611998 -0.674286 0.7286875 -0.1198045 -0.7366421 0.6400831 0.2182936 -0.7738949 0.6002982 -0.2018142 -0.8658423 0.4766444 -0.1520771 -0.9728576 0.1373134 -0.1862609 -0.9664617 0.1219555 -0.2260062 -1 -3.07286e-5 3.40277e-5 -1 -4.42057e-5 2.51279e-5 -0.9889112 -0.009080529 -0.1482301 -0.9816678 -0.03341692 -0.1876482 -0.9958426 -0.05416417 -0.07323729 -0.3652097 -0.8683232 0.335614 -0.2206593 -0.8630692 -0.4543358 -0.3513966 -0.8671308 -0.3529939 -0.2706477 -0.7448107 -0.6099238 -0.1186717 -0.6550875 -0.7461752 -0.1480126 0.2495017 -0.956996 -0.2248263 0.4662296 -0.8556185 -0.323383 0.4037371 -0.8558152 -0.4578673 0.3793115 -0.8040401 -0.6682094 0.5690326 -0.4792684 -0.1702607 0.6663377 -0.7259513 -0.3353989 0.7205531 -0.6068862 -0.1774426 0.821 -0.5426537 -0.608597 0.7757732 -0.1666905 -0.1675947 0.9851138 0.0382483 0 -0.964459 -0.2642328 0 -0.8529649 0.5219683 0 -0.9327527 0.360517 0 -0.932753 0.3605162 0 -0.9921913 0.1247254 0 -0.9929492 -0.1185408 0 -0.9929493 -0.1185408 0 -0.8848807 -0.465818 0 -0.8848807 -0.4658178 0 -0.6597496 -0.7514855 0 -0.6597496 -0.7514854 0 -0.4586273 -0.8886289 0 -0.4586273 -0.8886287 0 -0.1106116 -0.9938637 0 -0.1106116 -0.9938637 0 0.2522805 -0.9676542 0 0.2522805 -0.9676542 0 0.4784793 -0.878099 0 0.4784793 -0.8780989 0 0.6762115 -0.7367077 0 0.6762112 -0.7367078 0 0.8342383 -0.5514041 0 0.8342385 -0.5514038 0 0.9426452 -0.3337965 0 0.9994404 -0.03344899 0 0.9994404 -0.03344893 -0.2664284 -0.7572292 -0.5963389 -0.9148858 -0.3944765 0.08586263 -1 -5.22951e-7 0 -1 7.5987e-7 0 0 -0.9644593 -0.2642319 -0.9015756 0.241313 -0.3590674 -0.9048529 0.3960403 0.1561837 -0.9446668 0.3108153 0.1048743 -0.8950632 0.1621923 0.4153982 -0.7455703 -0.6547908 0.1239928 -0.6509479 -0.7475753 -0.1319019 -0.6691769 -0.7286037 -0.1460784 -0.6962567 -0.682801 -0.2213811 -0.6540217 -0.700646 -0.2852206 -0.6178693 -0.5478944 -0.5639587 -0.5819758 -0.1764873 -0.7938239 -0.5841436 0.01054096 -0.8115819 -0.6510829 -0.06396824 -0.7563063 -0.6454933 0.2262088 -0.7294985 -0.5544749 0.8132171 0.1767367 -0.7471666 0.6646248 0.004000723 -0.1810144 -0.9485264 -0.2598682 -0.9391516 -0.3172228 0.1317729 -0.9225839 -0.378269 -0.07583928 -0.923883 -0.3639867 -0.1181263 -0.9536355 -0.2434558 -0.176943 -0.8967834 -0.2468066 -0.3672413 -0.7925674 0.007919132 -0.6097328 -0.9995639 -0.01586222 0.02491259 -0.8138718 -0.5658559 0.1319849 0 -0.9281416 -0.3722273 -0.8451275 -0.4195854 0.3312215 -0.6941264 -0.6321494 0.3443484 -0.6650183 -0.6222361 0.4130048 -0.478252 -0.8733886 0.0920186 -0.229071 -0.92338 0.308052 -0.2093656 -0.9321889 0.2952795 -0.06197011 -0.9154284 -0.3976814 -0.4499217 -0.8794834 -0.1551759 -0.4057806 -0.9075263 -0.1083429 -0.3648151 -0.9238094 0.1161296 -0.3965522 -0.901983 0.1708018 -0.7276462 -0.2847147 -0.6240741 -0.9227432 -0.1600307 -0.3506211 -0.7871981 -0.5941376 0.1652869 -1 -5.69902e-7 0 -1 0 0 -0.9815131 0.1584257 0.1073932 -0.8991941 -0.1315225 0.4173152 -0.986153 -0.1390106 0.09043443 -0.9181379 0.1839439 -0.3509808 -0.7380059 0.3131364 -0.5977399 -0.5108405 0.6155853 -0.6000807 -0.634023 0.6823484 -0.3638894 -0.5995619 0.7843322 -0.1592118 -0.9139865 0.3976138 -0.08082056 -0.965543 -0.2600507 0.01001548 -0.9811289 -0.1902423 0.03455662 -0.8548504 -0.5156144 0.05807447 -0.8313746 -0.5544453 0.03750705 -0.1485767 0.9888545 0.009583771 -0.4389213 0.8867076 0.1452512 -0.5765574 -0.5332469 -0.6190552 -0.3907976 -0.7105314 -0.5851686 -0.4412439 -0.7418122 0.5049937 -0.3716042 -0.8109436 0.4519745 -0.7235268 -0.5885977 0.360641 -0.7535559 -0.5141005 0.4097003 -0.6724578 -0.6263756 0.3942767 -0.9995062 -0.009485661 0.02995586 -0.9996454 -0.01262307 -0.02344697 -0.4829662 -0.788785 -0.3802129 -0.5139704 -0.8542717 -0.07781004 -0.4569495 -0.7523179 0.4745684 -0.202934 -0.8000521 0.5645657 -1 5.00517e-5 1.71886e-5 -1 2.74545e-5 3.4074e-5 -0.6404228 -0.7660621 -0.05484187 -0.8539637 -0.5091613 -0.1072424 -0.8606262 -0.5068731 -0.04901301 -0.7975279 -0.5624422 0.2181931 -0.8581108 -0.4484198 0.2501313 -0.8561602 -0.3859933 0.3435098 -0.6438082 -0.1841196 0.7427052 -0.6489417 0.1926569 0.7360422 -0.7616198 0.5085415 0.4016477 -0.7538651 0.625531 0.200994 -0.6269865 0.7416952 0.2382774 -0.6361136 0.6055145 0.4782382 -0.5572707 0.5418428 0.6291708 -0.4848114 -0.648437 0.5869306 -0.4869813 -0.6524561 0.5806465 -0.4746267 -0.7434774 0.471138 -0.6403692 -0.7160717 0.2777925 -0.7971164 -0.5956594 -0.09897261 -0.6538113 -0.7543876 -0.05856877 -0.6414096 -0.7659843 -0.04314863 -0.9286979 0.327215 -0.1745006 -0.9443835 0.2629328 -0.1975004 -0.8832446 -0.1873544 0.4298574 -0.7999778 -0.1444205 0.5823901 -0.7990216 0.1523004 0.5816951 -0.8676674 0.1871142 0.4605885 -0.3371452 -0.07934474 -0.9381032 -0.2835558 -0.1060715 -0.9530714 -0.4067907 -0.2356238 -0.8826113 -0.1596757 -0.4527428 -0.8772273 -0.2126168 0.9210922 -0.3261648 -0.4111976 0.8912053 -0.1914935 0.4132519 0.8902965 -0.1912987 0.2138383 0.9208411 -0.3260751 0.160327 -0.4526945 -0.8771334 0.4085636 -0.2351003 -0.8819319 0.2851246 -0.1060202 -0.9526089 0.3389425 -0.07929027 -0.93746 0.8659065 0.1882663 0.4634242 0.7966517 0.1530938 0.5847294 0.7976155 -0.1451738 0.5854351 0.88165 -0.1885494 0.4325996 0.9435433 0.2648543 -0.1989431 0.9276479 0.3295259 -0.1757332 0.6414095 -0.7659844 -0.04314863 0.6538111 -0.7543877 -0.05856895 0.7945625 -0.5987599 -0.1007825 0.6403691 -0.7160718 0.2777926 0.4746266 -0.7434774 0.4711379 0.4869825 -0.65246 0.580641 0.4848083 -0.6484383 0.5869317 0.5572705 0.5418431 0.6291707 0.6361135 0.6055147 0.4782381 0.6269863 0.7416954 0.2382775 0.7511992 0.6284314 0.2019251 0.7589997 0.5109479 0.403549 0.6489416 0.1926568 0.7360422 0.6438079 -0.1841191 0.7427056 0.8542838 -0.3883087 0.3455654 0.8562532 -0.4511201 0.251637 0.7951483 -0.5653627 0.2193266 0.8606262 -0.506873 -0.04901301 0.8539633 -0.5091618 -0.1072424 0.6404228 -0.7660621 -0.05484193 1 2.74545e-5 3.4074e-5 1 5.00517e-5 1.71886e-5 0.2041163 -0.7996267 0.5647422 0.4585813 -0.7510766 0.4749602 0.5139704 -0.8542717 -0.07781004 0.4829663 -0.788785 -0.380213 0.9996454 -0.01262307 -0.02344697 0.9995062 -0.009485721 0.02995586 0.6724578 -0.6263757 0.3942766 0.7535636 -0.514088 0.4097018 0.7235291 -0.5885999 0.3606325 0.3715867 -0.8109542 0.4519698 0.4412395 -0.7418107 0.5049995 0.3908005 -0.7105292 -0.5851695 0.5765573 -0.5332472 -0.6190551 0.4389218 0.8867073 0.1452516 0.1485767 0.9888545 0.009583353 0.8313751 -0.5544446 0.03750723 0.85485 -0.515615 0.05807429 0.981129 -0.1902415 0.03455668 0.9655429 -0.2600511 0.01001548 0.9127498 0.4003331 -0.08137232 0.5995616 0.7843325 -0.1592123 0.634023 0.6823483 -0.3638898 0.5108403 0.6155855 -0.6000806 0.7380057 0.3131367 -0.59774 0.9169527 0.1852121 -0.353404 0.9857593 -0.1409589 0.0917018 0.8967034 -0.1330493 0.4221622 0.981056 0.1603537 0.1087002 1 0 0 1 -5.69902e-7 0 0.7871974 -0.5941385 0.1652872 0.9216164 -0.1611464 -0.3530653 0.7276459 -0.2847162 -0.6240739 0.3976376 -0.9015215 0.1707147 0.3658428 -0.9234094 0.1160794 0.4068809 -0.9070404 -0.108285 0.4510861 -0.8789046 -0.1550743 0.06211298 -0.9155514 -0.397376 0.2093657 -0.9321888 0.2952796 0.2290709 -0.9233801 0.3080517 0.4782522 -0.8733886 0.092018 0.6650183 -0.6222361 0.4130048 0.6941265 -0.6321492 0.3443484 0.8451275 -0.4195854 0.3312215 0.8138716 -0.5658562 0.1319848 0.9995639 -0.01586222 0.02491259 0.7901512 0.007962226 -0.6128603 0.8953409 -0.2484307 -0.3696579 0.952925 -0.2452694 -0.1782613 0.9227703 -0.3665319 -0.1189514 0.9214547 -0.3809061 -0.07636749 0.9382562 -0.3197202 0.1321154 0.1810144 -0.9485264 -0.2598683 0.7471658 0.6646257 0.0040012 0.5544756 0.8132168 0.176736 0.6454932 0.2262088 -0.7294986 0.6510828 -0.06396842 -0.7563064 0.5841414 0.01054346 -0.8115835 0.5819731 -0.1764883 -0.7938258 0.617869 -0.5478947 -0.5639587 0.6540219 -0.7006456 -0.285221 0.6962556 -0.6828017 -0.2213821 0.6691758 -0.7286049 -0.1460776 0.6509479 -0.7475752 -0.1319025 0.7455692 -0.6547918 0.123993 0.8925245 0.1638181 0.4201948 0.9438555 0.3128594 0.1060935 0.9048534 0.3960394 0.1561833 0.9001884 0.2429193 -0.3614571 1 7.5987e-7 0 1 -5.22951e-7 0 0.9143486 -0.3954679 0.08701658 0.2664281 -0.7572308 -0.5963369 0.1679552 0.9850311 0.03879439 0.6085965 0.7757737 -0.1666904 0.1784768 0.8208441 -0.5425505 0.337187 0.7200655 -0.6064741 0.1712492 0.6662222 -0.7258249 0.6682131 0.5690307 -0.4792654 0.4578718 0.3793083 -0.804039 0.3251225 0.4034799 -0.8552773 0.2261037 0.4660885 -0.8553587 0.1488841 0.2494687 -0.9568694 0.1191615 -0.6550488 -0.7461311 0.27151 -0.7444909 -0.6099309 0.3523964 -0.8667829 -0.3528516 0.2213412 -0.8629323 -0.4542641 0.3662389 -0.867946 0.3354681 0.9955754 -0.05587273 -0.0755499 0.9811118 -0.03502571 -0.1902441 0.9889112 -0.009080529 -0.1482301 1 -4.42057e-5 2.51279e-5 1 -3.07286e-5 3.40277e-5 0.965866 0.1230148 -0.22797 0.972242 0.1381687 -0.1888253 0.8658421 0.4766445 -0.1520771 0.7713346 0.6031897 -0.2029907 0.7338811 0.6429178 0.2192604 0.674286 0.7286875 -0.1198045 0.6205102 0.7828412 -0.04611998 0.6795685 0.6790894 0.2775325 0.6397036 0.1822071 0.7467128 0.6381887 -0.1776779 0.7490966 0.8695223 -0.4758195 -0.1323885 0.2846054 0.9517839 -0.1144866 0.3119713 0.9400646 -0.1376681 0.1491181 0.9695616 0.194201 0.3354128 0.8720555 0.3563951 -0.01955258 0.8249532 0.5648627 0.3432292 0.6129203 0.711704 0.1679255 0.5301741 0.8310934 0.2421915 0.2299996 0.9425729 0.3744827 0.2732099 0.8860695 0.01229876 -0.1031938 0.9945852 0.292671 -0.2206811 0.9303997 0.1473598 -0.47959 0.865031 0.432581 -0.6679321 0.6055911 0.3642538 -0.734701 0.5723057 0.5125667 -0.7250987 0.4598993 0.1722383 -0.9521626 0.2524292 0.2330411 -0.9695493 -0.07527345 0.06438046 -0.9876402 -0.1429055 0.1919035 -0.9194635 -0.3431617 0.009522497 -0.8629256 -0.5052415 0.03284174 0.9982591 -0.04899317 0.1999768 -0.9796924 0.01456767 0.1929633 -0.9760426 0.1005285 0.2443786 -0.9598802 0.1375104 0.2237417 -0.9746478 -0.001245677 0.5538441 -0.8321878 0.02683615 0.593914 -0.8045244 0.002610266 0.5512638 -0.8318596 0.06417095 0.4704334 -0.8747152 0.1164719 0.8311523 -0.5560349 -0.003338277 0.8295127 -0.5584851 -0.001850306 0.9811872 -0.1924207 -0.01568681 0.9649719 -0.2618535 0.01619297 0.003230571 -0.7187258 -0.6952863 0.2667278 -0.7581427 -0.595043 -0.2987011 -0.7141217 0.633094 0.07929217 -0.6939801 0.7156147 0.1664445 -0.7293896 0.6635413 0.9996648 0.02320313 0.01149344 0.9371277 0.3488443 0.009970188 0.8974465 0.4406719 0.01995801 0.7114266 0.702241 0.0270155 0.7402926 0.6716015 0.03030383 0.3648451 0.9306464 0.02802628 0.4733934 0.8798834 0.04128032 0.127985 0.9910485 0.03798317 0.08077067 0.995936 0.03984487 0.9972825 0.07367265 0 0.9999958 -0.002897083 0 0.9999932 0.003273248 0.001752138 0.9999811 -0.005442261 -0.002912938 0.4308458 -0.6497735 -0.6262319 0 -0.8637386 -0.5039403 + + + + + + + + + + + + + + +

0 0 1 0 2 0 4 1 3 1 5 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 4 4 7 4 9 5 10 5 11 5 12 6 11 6 10 6 13 7 10 7 9 7 13 8 9 8 14 8 14 9 15 9 13 9 16 10 13 10 15 10 15 11 17 11 16 11 18 12 16 12 17 12 8 13 18 13 17 13 17 14 19 14 8 14 19 15 4 15 8 15 20 16 21 16 22 16 23 17 22 17 21 17 21 18 24 18 23 18 25 19 23 19 24 19 26 20 27 20 28 20 29 21 28 21 27 21 27 22 20 22 29 22 29 23 20 23 22 23 30 24 29 24 22 24 1 25 0 25 31 25 0 26 32 26 31 26 33 27 34 27 31 27 32 27 33 27 31 27 5 28 3 28 2 28 36 29 5 29 2 29 36 30 2 30 1 30 37 31 36 31 1 31 40 32 41 32 38 32 37 33 40 33 38 33 37 34 1 34 42 34 40 35 37 35 42 35 42 36 24 36 40 36 20 37 41 37 40 37 40 38 21 38 20 38 40 39 24 39 21 39 35 40 43 40 29 40 43 41 44 41 54 41 44 42 45 42 54 42 55 43 54 43 45 43 45 44 46 44 55 44 56 45 55 45 46 45 46 46 47 46 56 46 57 47 56 47 47 47 47 48 48 48 57 48 58 49 57 49 48 49 48 50 49 50 58 50 59 51 58 51 49 51 49 52 50 52 59 52 60 53 59 53 50 53 50 54 51 54 60 54 61 54 60 54 51 54 51 55 52 55 61 55 62 56 61 56 52 56 52 57 53 57 62 57 63 58 62 58 53 58 12 59 63 59 53 59 63 60 12 60 10 60 63 61 10 61 13 61 28 62 43 62 54 62 64 63 28 63 54 63 64 64 54 64 55 64 65 65 64 65 55 65 55 66 56 66 65 66 66 67 65 67 56 67 66 68 56 68 57 68 67 69 66 69 57 69 57 70 58 70 67 70 68 71 67 71 58 71 58 72 59 72 68 72 68 73 59 73 60 73 69 74 68 74 60 74 60 75 61 75 69 75 70 76 69 76 61 76 61 77 62 77 70 77 71 78 70 78 62 78 62 79 63 79 71 79 71 80 63 80 13 80 71 81 13 81 16 81 72 82 73 82 28 82 67 83 68 83 76 83 68 84 69 84 76 84 70 85 71 85 78 85 71 86 16 86 78 86 18 87 78 87 16 87 80 88 77 88 78 88 8 89 80 89 78 89 78 90 18 90 8 90 8 91 7 91 81 91 8 92 81 92 80 92 75 93 79 93 81 93 74 94 75 94 81 94 72 95 7 95 73 95 7 96 72 96 81 96 74 97 81 97 72 97 85 98 84 98 82 98 89 99 90 99 88 99 86 100 89 100 88 100 89 101 91 101 90 101 92 102 90 102 91 102 97 103 96 103 95 103 98 104 99 104 97 104 95 105 98 105 97 105 98 106 95 106 100 106 100 107 101 107 98 107 102 108 99 108 98 108 98 109 101 109 102 109 103 110 102 110 101 110 105 111 101 111 104 111 9 112 106 112 105 112 34 113 25 113 31 113 84 114 33 114 32 114 33 114 84 114 107 114 84 115 85 115 107 115 108 116 107 116 85 116 85 117 87 117 108 117 109 117 108 117 87 117 87 118 88 118 109 118 110 119 109 119 88 119 88 120 90 120 110 120 111 121 110 121 90 121 90 122 92 122 111 122 112 123 111 123 92 123 92 124 94 124 112 124 113 125 112 125 94 125 94 126 96 126 113 126 114 127 113 127 96 127 96 128 97 128 114 128 115 129 114 129 97 129 97 130 99 130 115 130 116 131 115 131 99 131 99 132 102 132 116 132 117 133 116 133 102 133 102 134 103 134 117 134 118 135 117 135 103 135 103 136 106 136 118 136 119 136 118 136 106 136 106 137 9 137 119 137 11 138 119 138 9 138 1 139 31 139 42 139 120 140 121 140 122 140 123 141 122 141 124 141 125 142 123 142 124 142 24 143 31 143 25 143 126 144 128 144 125 144 104 145 19 145 17 145 104 146 127 146 19 146 19 147 124 147 4 147 130 148 82 148 129 148 86 149 130 149 129 149 129 150 131 150 86 150 131 151 132 151 86 151 89 152 86 152 132 152 91 153 89 153 132 153 93 154 91 154 133 154 133 155 128 155 93 155 95 156 93 156 128 156 100 157 95 157 128 157 104 158 17 158 105 158 15 159 105 159 17 159 24 160 42 160 31 160 120 161 122 161 129 161 131 162 129 162 122 162 122 163 132 163 131 163 122 164 123 164 132 164 123 165 125 165 133 165 128 166 133 166 125 166 6 167 73 167 7 167 6 168 28 168 73 168 30 169 35 169 29 169 6 170 39 170 28 170 26 171 28 171 39 171 39 172 38 172 26 172 41 173 26 173 38 173 27 174 26 174 41 174 41 175 20 175 27 175 29 176 43 176 28 176 86 177 88 177 130 177 87 178 130 178 88 178 85 179 130 179 87 179 82 180 130 180 85 180 91 181 132 181 133 181 123 182 133 182 132 182 82 183 120 183 129 183 124 184 126 184 125 184 124 185 127 185 126 185 19 186 127 186 124 186 4 187 124 187 121 187 121 188 124 188 122 188 126 189 135 189 128 189 135 190 100 190 128 190 100 191 135 191 101 191 134 192 101 192 135 192 101 193 134 193 104 193 134 194 127 194 104 194 5 195 39 195 6 195 5 196 36 196 39 196 36 197 38 197 39 197 36 198 37 198 38 198 9 199 105 199 14 199 14 200 105 200 15 200 2 201 3 201 83 201 0 202 2 202 83 202 136 203 0 203 83 203 82 204 0 204 136 204 82 205 136 205 120 205 136 206 83 206 120 206 83 207 121 207 120 207 121 208 137 208 4 208 137 209 3 209 4 209 3 210 137 210 83 210 137 211 121 211 83 211 0 212 82 212 84 212 0 213 84 213 32 213 77 214 80 214 81 214 77 215 81 215 79 215 64 216 141 216 28 216 141 217 72 217 28 217 139 218 72 218 141 218 138 219 74 219 139 219 74 220 138 220 75 220 140 221 75 221 138 221 140 222 67 222 76 222 69 223 143 223 76 223 142 224 77 224 143 224 77 225 142 225 78 225 142 226 70 226 78 226 70 227 142 227 143 227 70 228 143 228 69 228 67 229 140 229 66 229 140 230 138 230 66 230 66 231 138 231 65 231 138 232 139 232 65 232 72 233 139 233 74 233 65 234 139 234 64 234 139 235 141 235 64 235 127 236 134 236 135 236 127 237 135 237 126 237 75 238 140 238 79 238 76 239 79 239 140 239 76 240 143 240 79 240 77 241 79 241 143 241 93 242 95 242 96 242 93 243 96 243 94 243 91 244 93 244 94 244 91 245 94 245 92 245 101 246 106 246 103 246 101 247 105 247 106 247 170 248 119 248 168 248 170 249 118 249 119 249 175 250 112 250 113 250 175 251 113 251 174 251 174 252 113 252 114 252 174 253 114 253 173 253 184 254 144 254 182 254 185 255 182 255 144 255 185 256 147 256 182 256 186 257 182 257 147 257 160 258 161 258 152 258 160 259 152 259 153 259 148 260 197 260 146 260 196 261 197 261 148 261 189 262 187 262 148 262 149 263 196 263 148 263 195 264 196 264 149 264 147 265 195 265 149 265 194 266 195 266 147 266 191 267 192 267 144 267 191 268 144 268 145 268 145 269 183 269 191 269 184 270 183 270 145 270 145 271 144 271 184 271 192 272 185 272 144 272 147 273 185 273 194 273 147 274 149 274 186 274 187 275 186 275 149 275 149 276 148 276 187 276 148 277 146 277 189 277 146 278 205 278 189 278 197 279 205 279 146 279 184 280 182 280 180 280 184 281 180 281 181 281 223 282 33 282 107 282 223 283 107 283 179 283 150 284 178 284 166 284 220 285 178 285 150 285 150 286 219 286 220 286 166 287 219 287 150 287 178 288 167 288 166 288 151 289 167 289 178 289 179 290 167 290 151 290 151 291 223 291 179 291 178 292 223 292 151 292 223 293 178 293 221 293 221 294 178 294 220 294 213 295 212 295 168 295 11 296 213 296 168 296 204 297 202 297 203 297 204 298 201 298 202 298 218 299 201 299 204 299 218 300 217 300 201 300 153 301 169 301 160 301 170 302 169 302 153 302 153 303 152 303 170 303 171 304 170 304 152 304 152 305 159 305 171 305 161 306 159 306 152 306 166 307 165 307 163 307 219 308 166 308 163 308 208 309 163 309 160 309 163 310 161 310 160 310 163 311 162 311 161 311 179 312 158 312 167 312 164 313 155 313 154 313 175 314 154 314 155 314 179 315 108 315 157 315 108 316 109 316 157 316 109 317 110 317 157 317 177 318 157 318 110 318 30 319 205 319 35 319 199 320 206 320 22 320 206 321 199 321 207 321 199 322 202 322 207 322 201 323 207 323 202 323 207 324 201 324 205 324 217 325 205 325 201 325 217 326 188 326 205 326 217 327 216 327 188 327 159 328 162 328 154 328 164 329 154 329 162 329 165 330 155 330 164 330 165 331 156 331 155 331 156 332 165 332 158 332 167 333 158 333 165 333 25 334 34 334 198 334 212 335 210 335 168 335 169 336 168 336 210 336 171 337 159 337 173 337 173 338 159 338 174 338 154 339 174 339 159 339 174 340 154 340 175 340 175 341 155 341 176 341 176 342 155 342 177 342 156 343 177 343 155 343 158 344 177 344 156 344 177 345 158 345 157 345 157 346 158 346 179 346 208 347 219 347 163 347 169 348 208 348 160 348 169 349 210 349 208 349 161 350 162 350 159 350 162 351 163 351 164 351 164 352 163 352 165 352 167 353 165 353 166 353 222 354 198 354 34 354 11 355 168 355 119 355 168 356 169 356 170 356 118 357 170 357 117 357 172 358 117 358 170 358 117 359 172 359 116 359 171 360 172 360 170 360 172 361 171 361 173 361 173 362 115 362 172 362 172 363 115 363 116 363 115 364 173 364 114 364 112 365 175 365 111 365 176 366 111 366 175 366 177 367 110 367 176 367 176 368 110 368 111 368 108 369 179 369 107 369 187 370 189 370 180 370 216 371 180 371 189 371 189 372 188 372 216 372 187 373 180 373 186 373 186 374 180 374 182 374 215 375 181 375 180 375 215 376 180 376 216 376 183 377 215 377 209 377 215 378 183 378 181 378 181 379 183 379 184 379 209 380 211 380 183 380 190 381 183 381 211 381 191 382 183 382 190 382 193 383 185 383 192 383 194 384 185 384 193 384 189 385 205 385 188 385 190 386 211 386 214 386 190 387 214 387 53 387 52 388 190 388 53 388 190 389 52 389 191 389 51 390 191 390 52 390 191 391 51 391 192 391 50 392 192 392 51 392 192 393 50 393 193 393 193 394 50 394 49 394 48 395 193 395 49 395 193 396 48 396 194 396 47 397 194 397 48 397 194 398 47 398 195 398 195 399 47 399 46 399 195 400 46 400 196 400 45 401 196 401 46 401 196 402 45 402 197 402 197 403 45 403 44 403 197 404 44 404 205 404 205 405 44 405 35 405 53 406 214 406 12 406 200 407 23 407 25 407 200 408 22 408 23 408 22 409 200 409 199 409 198 410 200 410 25 410 200 411 198 411 203 411 203 412 198 412 222 412 203 413 202 413 200 413 200 414 202 414 199 414 203 415 222 415 204 415 204 416 222 416 221 416 204 417 221 417 218 417 218 418 221 418 220 418 223 419 34 419 33 419 34 420 223 420 222 420 206 421 30 421 22 421 30 422 206 422 205 422 207 423 205 423 206 423 208 424 215 424 219 424 210 425 215 425 208 425 215 426 210 426 209 426 209 427 210 427 211 427 212 428 211 428 210 428 211 429 212 429 214 429 213 430 214 430 212 430 214 431 213 431 11 431 214 432 11 432 12 432 215 433 216 433 219 433 219 434 216 434 217 434 219 435 217 435 218 435 219 436 218 436 220 436 223 437 221 437 222 437 35 438 44 438 43 438

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 -4e-5 0 0 0.001 -1.74846e-12 0 0 0 1 + + + + + + + + + + -0.2908648 -0.7711008 0.5663932 4.076245 0.9551711 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054209 -0.6141704 -6.925791 -4.01133e-9 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_middle/f_middle_E4.dae b/URDFs/sr_description/meshes/components/f_middle/f_middle_E4.dae new file mode 100644 index 0000000..ad7a2e3 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_middle/f_middle_E4.dae @@ -0,0 +1,130 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:44.246463 + 2012-07-23T02:15:44.246477 + + Y_UP + + + + + + + + 0 0 0 1 + + + 0.04392 0.04392 0.04392 1 + + + 0.21961 0.21961 0.21961 1 + + + 0.45000 0.45000 0.45000 1 + + + 32 + + + 1 + + + + + + + + + + + + + + + + -5.15497 -5.65164 5.67687 -6.98593 -7.50773 8.86243 -8.01397 -5.97789 7.98236 -8.48097 -4.31842 6.98785 -8.50017 0.02188 5.46986 -8.50017 -3.88961 12.77786 -8.48937 -3.70556 18.59785 -8.50017 0.02188 20.53786 -8.22567 3.73770 21.84346 -3.50017 7.97965 1.21886 -3.50017 7.04980 24.44685 3.49296 7.97965 1.21886 3.49983 7.04980 24.44685 -4.29807 7.00277 24.01886 -4.75757 7.78174 2.14586 -6.73177 6.68550 2.87236 -6.31127 6.25102 22.77386 -7.75257 5.53448 3.44444 -7.62757 4.93940 22.20461 -8.42967 3.69429 4.18787 -3.43169 -8.64405 15.62886 -3.50017 -8.93332 12.68886 3.42448 -8.64405 15.62886 3.49296 -8.93332 12.68886 -3.50017 -8.97607 9.81386 3.49296 -8.97607 9.81386 -6.41337 -7.45056 17.15486 -4.73277 -7.88683 17.09686 -7.46427 -4.93237 19.65934 -4.00017 -5.21445 19.76886 3.99983 -5.21445 19.76886 -3.50017 -8.70539 8.82587 -4.00017 -5.82319 5.84886 3.99983 -5.82319 5.84886 3.49296 -8.70539 8.82587 4.48796 -5.61710 20.77286 -8.11957 -5.83721 12.86186 -7.03567 -7.45782 12.93086 -7.07657 -7.15262 16.53586 -8.02707 -5.46231 17.55201 -5.41357 -8.54068 12.82830 -5.52640 -8.05887 15.99102 -5.66907 -8.47778 9.50586 -4.49517 -5.61710 20.77286 4.75036 -6.43800 22.17986 4.75723 -6.97321 25.88187 4.75723 -6.48965 27.70586 4.75723 -4.19093 30.65686 4.75723 -2.54057 31.57185 4.75723 1.17980 31.95786 4.75723 2.98301 31.40186 4.75723 4.57411 30.38686 4.75723 6.68716 27.30086 4.75723 7.05771 25.45087 -4.75757 -6.43800 22.17986 -4.75757 -6.97321 25.88187 -4.75757 -6.48965 27.70586 -4.75757 -4.19093 30.65686 -4.75757 -2.54057 31.57185 -4.75757 1.17980 31.95786 -4.75757 2.98301 31.40186 -4.75757 4.57411 30.38686 -4.75757 6.68716 27.30086 -4.75757 7.05771 25.45087 -5.90557 -6.46749 22.90086 -5.90557 -6.71430 26.07986 -5.87887 -4.67070 29.33165 -5.90557 -3.05930 31.08986 -5.90557 0.04375 31.82587 -5.90557 3.14202 31.06985 -5.90557 5.55840 28.98886 -5.90557 6.76483 26.03687 -8.77364 -3.34911 22.56881 -8.45003 -3.33963 20.40928 -8.99996 -3.58678 25.82197 -8.99996 -2.60559 27.58099 -8.12147 0.02188 29.93286 -8.99996 3.11434 27.46986 -8.12147 4.95033 25.05086 -9.00000 0.02188 28.72610 -8.99996 3.87812 25.23030 -9.00019 0.02642 23.15286 -6.87887 -6.81239 2.17687 -6.52396 -4.86510 5.63609 -4.75757 -7.07768 3.79886 -4.75757 -7.78383 1.97186 -6.87887 -6.53824 -2.89314 -4.75757 -8.02808 0.02885 -4.75757 -7.79600 -1.91515 -6.87887 -5.85402 -4.57393 -4.75757 -5.98513 -5.35513 -6.40557 -4.61815 -6.29314 -4.75757 -4.51347 -6.64714 -5.90557 -1.56868 -7.33768 -4.75757 -2.77352 -7.54514 -5.90557 1.77076 -7.62013 -4.75757 1.09010 -7.97514 -4.75757 2.98490 -7.48114 -5.90557 4.79136 -6.19514 -4.75757 4.70447 -6.54414 -6.87887 3.66948 -6.17014 -5.90557 6.94247 -3.64114 -4.75757 6.14692 -5.22014 -4.75757 7.22694 -3.58614 -8.12147 6.00887 0.10429 -5.90557 7.63414 -0.42213 -4.75757 7.88062 -1.74014 4.75723 -7.07768 3.79886 4.75723 -7.78383 1.97186 4.75723 -8.02808 0.02885 4.75723 -7.79600 -1.91515 4.75723 -5.98513 -5.35513 4.75723 -4.51347 -6.64714 4.75723 -2.77352 -7.54514 4.75723 1.09010 -7.97514 4.75723 2.98490 -7.48114 4.75723 4.70447 -6.54414 4.75723 6.14692 -5.22014 4.75723 7.22694 -3.58614 4.75723 7.88062 -1.74014 -7.87887 -5.40786 2.46296 -8.50000 -3.55834 4.34187 -9.00000 -3.59913 -1.17314 -9.00000 -2.21603 -3.07614 -9.00000 0.02188 4.39287 -9.00000 0.02188 -4.58014 -9.00000 2.25979 -3.07614 -9.00000 3.74480 -1.09914 -8.12147 1.63616 -5.70114 -8.12147 -5.89100 -0.42914 -6.87887 -7.13355 0.48087 -8.12147 -5.60089 -1.87614 -8.12100 -4.85241 -4.18614 -8.12147 -1.44278 -5.74113 -8.12100 5.47326 -2.53608 -8.12100 4.61814 -4.13956 -6.75466 -5.90532 3.90648 -8.45823 -3.70615 5.68876 -8.12100 -3.83817 28.38669 -8.12100 -4.78404 25.94850 -8.12100 -3.16487 29.14326 -7.96933 -4.72890 22.71507 -8.12100 3.99730 28.01863 -8.12100 3.12703 29.12051 8.11379 3.12703 29.12051 8.11379 3.99730 28.01863 7.96212 -4.72890 22.71507 8.11379 -3.16488 29.14326 8.11379 -4.78404 25.94850 8.11379 -3.83817 28.38669 8.45102 -3.70615 5.68876 6.74746 -5.90533 3.90648 8.11379 4.61814 -4.13956 8.11379 5.47326 -2.53608 8.11426 -1.44278 -5.74114 8.11379 -4.85241 -4.18614 8.11426 -5.60089 -1.87615 6.87166 -7.13355 0.48086 8.11426 -5.89100 -0.42914 8.11426 1.63616 -5.70114 9.00000 3.74480 -1.09914 9.00000 2.25979 -3.07614 9.00000 0.02188 -4.58014 9.00000 0.02188 4.39287 9.00000 -2.21603 -3.07614 9.00000 -3.59913 -1.17314 8.49279 -3.55834 4.34187 7.87166 -5.40786 2.46296 5.89836 7.63414 -0.42213 8.11426 6.00887 0.10428 5.89836 6.94247 -3.64114 6.87166 3.66948 -6.17014 5.89836 4.79136 -6.19515 5.89836 1.77076 -7.62013 5.89836 -1.56868 -7.33768 6.39836 -4.61815 -6.29314 6.87166 -5.85402 -4.57393 6.87166 -6.53824 -2.89314 6.51675 -4.86510 5.63609 6.87166 -6.81239 2.17686 9.00019 0.02642 23.15286 8.99996 3.87812 25.23030 9.00000 0.02188 28.72610 8.11426 4.95033 25.05086 8.99996 3.11434 27.46986 8.11426 0.02188 29.93286 8.99996 -2.60559 27.58099 8.99996 -3.58678 25.82197 8.44282 -3.33963 20.40928 8.76643 -3.34911 22.56881 5.89836 6.76483 26.03687 5.89836 5.55840 28.98886 5.89836 3.14202 31.06985 5.89836 0.04374 31.82587 5.89836 -3.05930 31.08986 5.87166 -4.67070 29.33165 5.89836 -6.71430 26.07986 5.89836 -6.46749 22.90086 5.66186 -8.47778 9.50586 5.51919 -8.05887 15.99102 5.40636 -8.54068 12.82830 8.01986 -5.46231 17.55201 7.06936 -7.15262 16.53586 7.02846 -7.45782 12.93086 8.11236 -5.83721 12.86186 7.45706 -4.93237 19.65934 4.72556 -7.88683 17.09686 6.40616 -7.45056 17.15486 8.42246 3.69429 4.18787 7.62036 4.93940 22.20461 7.74536 5.53448 3.44444 6.30406 6.25102 22.77386 6.72456 6.68550 2.87236 4.75036 7.78174 2.14586 4.29086 7.00277 24.01886 8.21846 3.73770 21.84346 8.49296 0.02188 20.53786 8.48216 -3.70556 18.59785 8.49296 -3.88961 12.77786 8.49296 0.02188 5.46986 8.47376 -4.31842 6.98785 8.00676 -5.97789 7.98236 6.97873 -7.50773 8.86243 5.14776 -5.65164 5.67686 + + + + + + + + + + -0.43084 -0.64978 -0.62623 -0.99998 -0.00544 -0.00291 -0.99999 0.00327 0.00175 -1.00000 -0.00290 0.00000 -0.99728 0.07367 0.00000 0.00000 0.99920 0.04000 0.00000 0.99920 0.04000 -0.08009 0.99599 0.03987 -0.12798 0.99105 0.03798 -0.47339 0.87988 0.04128 -0.36485 0.93065 0.02803 -0.74029 0.67160 0.03030 -0.71143 0.70224 0.02702 -0.89745 0.44067 0.01996 -0.93713 0.34885 0.00997 -0.99966 0.02320 0.01149 -0.00000 -0.99519 0.09792 -0.00000 -0.99519 0.09792 -0.00000 -0.99989 0.01487 -0.00000 -0.99989 0.01487 -0.16644 -0.72939 0.66354 -0.07913 -0.69391 0.71570 0.29821 -0.71453 0.63287 -0.00000 -0.77008 0.63794 0.00000 -0.77008 0.63794 -0.26673 -0.75814 -0.59504 -0.00321 -0.71872 -0.69529 -0.00000 -0.71845 -0.69557 -0.00000 -0.71845 -0.69557 -0.96497 -0.26186 0.01619 -0.98119 -0.19242 -0.01569 -0.82951 -0.55849 -0.00185 -0.83115 -0.55604 -0.00334 -0.47043 -0.87472 0.11647 -0.55126 -0.83186 0.06417 -0.59392 -0.80452 0.00261 -0.55384 -0.83219 0.02684 -0.22374 -0.97465 -0.00125 -0.24438 -0.95988 0.13751 -0.19296 -0.97604 0.10053 -0.19998 -0.97969 0.01457 -0.00000 -0.92814 -0.37223 -0.00000 -0.86374 -0.50394 -0.00000 -0.98971 -0.14308 0.00000 -0.98971 -0.14309 0.00000 -0.96661 0.25626 0.00000 -0.96661 0.25626 0.00000 -0.78890 0.61452 0.00000 -0.78890 0.61452 0.00000 -0.48488 0.87458 0.00000 -0.48488 0.87458 0.00000 -0.10320 0.99466 0.00000 -0.10320 0.99466 -0.00000 0.29465 0.95561 -0.00000 0.29465 0.95561 -0.00000 0.53781 0.84307 0.00000 0.53781 0.84307 0.00000 0.82511 0.56497 0.00000 0.82511 0.56497 0.00000 0.98052 0.19640 0.00000 0.98052 0.19640 0.00000 0.99997 -0.00788 0.00000 0.99997 -0.00788 -0.03267 0.99827 -0.04878 -0.00952 -0.86293 -0.50524 -0.19191 -0.91946 -0.34316 -0.06431 -0.98766 -0.14279 -0.23172 -0.96986 -0.07530 -0.17124 -0.95233 0.25247 -0.51028 -0.72626 0.46061 -0.36232 -0.73530 0.57277 -0.43045 -0.66867 0.60630 -0.14650 -0.47965 0.86514 -0.29107 -0.22079 0.93088 -0.01223 -0.10319 0.99459 -0.37255 0.27344 0.88681 -0.24082 0.23008 0.94290 -0.16695 0.53026 0.83123 -0.34141 0.61335 0.71220 0.01944 0.82495 0.56486 -0.33363 0.87264 0.35663 -0.14825 0.96969 0.19423 -0.30923 0.94131 -0.13534 -0.28461 0.95178 -0.11449 -0.86952 -0.47582 -0.13239 -0.63819 -0.17768 0.74910 -0.63970 0.18221 0.74671 -0.67957 0.67909 0.27753 -0.62051 0.78284 -0.04612 -0.67429 0.72869 -0.11980 -0.73664 0.64008 0.21829 -0.77390 0.60030 -0.20181 -0.86584 0.47665 -0.15208 -0.97286 0.13731 -0.18626 -0.96646 0.12196 -0.22601 -1.00000 -0.00003 0.00003 -1.00000 -0.00004 0.00003 -0.98891 -0.00908 -0.14823 -0.98167 -0.03342 -0.18765 -0.99584 -0.05416 -0.07324 -0.36521 -0.86832 0.33561 -0.22066 -0.86307 -0.45434 -0.35140 -0.86713 -0.35299 -0.27065 -0.74481 -0.60993 -0.11867 -0.65509 -0.74618 -0.14801 0.24950 -0.95700 -0.22483 0.46623 -0.85562 -0.32338 0.40374 -0.85582 -0.45787 0.37931 -0.80404 -0.66821 0.56903 -0.47927 -0.17026 0.66634 -0.72595 -0.33540 0.72055 -0.60689 -0.17744 0.82100 -0.54265 -0.60860 0.77577 -0.16669 -0.16759 0.98511 0.03825 -0.00000 -0.96446 -0.26423 0.00000 -0.85296 0.52197 0.00000 -0.85296 0.52197 0.00000 -0.93275 0.36052 0.00000 -0.93275 0.36052 0.00000 -0.99219 0.12473 0.00000 -0.99219 0.12473 -0.00000 -0.99295 -0.11854 -0.00000 -0.99295 -0.11854 -0.00000 -0.88488 -0.46582 -0.00000 -0.88488 -0.46582 -0.00000 -0.65975 -0.75149 -0.00000 -0.65975 -0.75149 -0.00000 -0.45863 -0.88863 -0.00000 -0.45863 -0.88863 -0.00000 -0.11061 -0.99386 -0.00000 -0.11061 -0.99386 -0.00000 0.25228 -0.96765 -0.00000 0.25228 -0.96765 -0.00000 0.47848 -0.87810 -0.00000 0.47848 -0.87810 -0.00000 0.67621 -0.73671 -0.00000 0.67621 -0.73671 -0.00000 0.83424 -0.55140 -0.00000 0.83424 -0.55140 -0.00000 0.94264 -0.33380 -0.00000 0.94264 -0.33380 -0.00000 0.99944 -0.03345 0.00000 0.99944 -0.03345 -0.26643 -0.75723 -0.59634 -0.91489 -0.39448 0.08586 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -0.00000 -0.96446 -0.26423 -0.90158 0.24131 -0.35907 -0.90485 0.39604 0.15618 -0.94467 0.31082 0.10487 -0.89506 0.16219 0.41539 -0.74557 -0.65479 0.12399 -0.65095 -0.74758 -0.13190 -0.66918 -0.72860 -0.14608 -0.69626 -0.68280 -0.22138 -0.65402 -0.70065 -0.28522 -0.61787 -0.54789 -0.56396 -0.58197 -0.17649 -0.79382 -0.58414 0.01054 -0.81158 -0.65108 -0.06397 -0.75631 -0.64549 0.22621 -0.72950 -0.55447 0.81322 0.17674 -0.74717 0.66462 0.00400 -0.18101 -0.94853 -0.25987 -0.93915 -0.31722 0.13177 -0.92258 -0.37827 -0.07584 -0.92388 -0.36399 -0.11813 -0.95364 -0.24345 -0.17694 -0.89678 -0.24681 -0.36724 -0.79257 0.00792 -0.60973 -0.99956 -0.01586 0.02491 -0.81387 -0.56586 0.13199 0.00000 -0.92814 -0.37223 -0.84513 -0.41959 0.33122 -0.69413 -0.63215 0.34435 -0.66502 -0.62224 0.41300 -0.47825 -0.87339 0.09202 -0.22907 -0.92338 0.30805 -0.20936 -0.93219 0.29528 -0.06197 -0.91543 -0.39768 -0.44992 -0.87948 -0.15518 -0.40578 -0.90753 -0.10834 -0.36482 -0.92381 0.11613 -0.39655 -0.90198 0.17080 -0.72765 -0.28472 -0.62407 -0.92274 -0.16003 -0.35062 -0.78720 -0.59414 0.16529 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.98151 0.15842 0.10739 -0.89920 -0.13152 0.41731 -0.98615 -0.13901 0.09043 -0.91814 0.18394 -0.35098 -0.73800 0.31314 -0.59774 -0.51084 0.61558 -0.60008 -0.63402 0.68235 -0.36389 -0.59956 0.78433 -0.15921 -0.91399 0.39761 -0.08082 -0.96554 -0.26005 0.01002 -0.98113 -0.19024 0.03456 -0.85485 -0.51561 0.05807 -0.83137 -0.55445 0.03751 -0.14858 0.98885 0.00958 -0.43892 0.88671 0.14525 -0.57656 -0.53325 -0.61905 -0.39080 -0.71053 -0.58517 -0.44124 -0.74181 0.50500 -0.37160 -0.81095 0.45197 -0.72353 -0.58860 0.36064 -0.75356 -0.51410 0.40970 -0.67246 -0.62637 0.39428 -0.99951 -0.00949 0.02996 -0.99965 -0.01262 -0.02345 -0.48297 -0.78878 -0.38022 -0.51397 -0.85427 -0.07781 -0.45695 -0.75232 0.47457 -0.20294 -0.80005 0.56457 -1.00000 0.00005 0.00002 -1.00000 0.00003 0.00003 -0.64042 -0.76606 -0.05484 -0.85396 -0.50916 -0.10724 -0.86063 -0.50687 -0.04901 -0.79753 -0.56244 0.21819 -0.85811 -0.44842 0.25013 -0.85616 -0.38599 0.34351 -0.64381 -0.18412 0.74270 -0.64894 0.19266 0.73604 -0.76162 0.50854 0.40165 -0.75386 0.62553 0.20099 -0.62699 0.74169 0.23828 -0.63612 0.60551 0.47824 -0.55727 0.54184 0.62917 -0.48481 -0.64844 0.58693 -0.48698 -0.65246 0.58064 -0.47463 -0.74348 0.47114 -0.64037 -0.71607 0.27779 -0.79712 -0.59566 -0.09897 -0.65381 -0.75439 -0.05857 -0.64141 -0.76598 -0.04315 -0.92870 0.32722 -0.17450 -0.94438 0.26293 -0.19750 -0.88324 -0.18735 0.42986 -0.79998 -0.14442 0.58239 -0.79902 0.15230 0.58169 -0.86767 0.18711 0.46059 -0.33715 -0.07934 -0.93810 -0.28355 -0.10607 -0.95307 -0.40679 -0.23563 -0.88261 -0.15968 -0.45274 -0.87723 -0.21262 0.92109 -0.32617 -0.41120 0.89121 -0.19149 0.41325 0.89030 -0.19130 0.21384 0.92084 -0.32608 0.16033 -0.45269 -0.87713 0.40856 -0.23510 -0.88193 0.28512 -0.10602 -0.95261 0.33894 -0.07929 -0.93746 0.86591 0.18827 0.46342 0.79665 0.15309 0.58473 0.79762 -0.14517 0.58543 0.88165 -0.18855 0.43260 0.94354 0.26485 -0.19894 0.92765 0.32953 -0.17573 0.64141 -0.76598 -0.04315 0.65381 -0.75439 -0.05857 0.79456 -0.59876 -0.10078 0.64037 -0.71607 0.27779 0.47463 -0.74348 0.47114 0.48698 -0.65246 0.58064 0.48481 -0.64844 0.58693 0.55727 0.54184 0.62917 0.63612 0.60551 0.47824 0.62699 0.74169 0.23828 0.75120 0.62843 0.20193 0.75900 0.51095 0.40355 0.64894 0.19266 0.73604 0.64381 -0.18412 0.74270 0.85428 -0.38831 0.34557 0.85625 -0.45112 0.25164 0.79515 -0.56536 0.21933 0.86063 -0.50687 -0.04901 0.85396 -0.50916 -0.10724 0.64042 -0.76606 -0.05484 1.00000 0.00003 0.00003 1.00000 0.00005 0.00002 0.20411 -0.79963 0.56474 0.45858 -0.75108 0.47496 0.51397 -0.85427 -0.07781 0.48297 -0.78878 -0.38022 0.99965 -0.01262 -0.02345 0.99951 -0.00949 0.02996 0.67246 -0.62637 0.39428 0.75356 -0.51409 0.40970 0.72353 -0.58860 0.36064 0.37160 -0.81095 0.45197 0.44124 -0.74181 0.50500 0.39080 -0.71053 -0.58517 0.57656 -0.53325 -0.61905 0.43892 0.88671 0.14525 0.14858 0.98885 0.00958 0.83138 -0.55444 0.03751 0.85485 -0.51561 0.05807 0.98113 -0.19024 0.03456 0.96554 -0.26005 0.01002 0.91275 0.40033 -0.08137 0.59956 0.78433 -0.15921 0.63402 0.68235 -0.36389 0.51084 0.61559 -0.60008 0.73800 0.31314 -0.59774 0.91695 0.18521 -0.35340 0.98576 -0.14096 0.09170 0.89670 -0.13305 0.42216 0.98106 0.16035 0.10870 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 0.78720 -0.59414 0.16529 0.92162 -0.16115 -0.35307 0.72765 -0.28472 -0.62407 0.39764 -0.90152 0.17072 0.36584 -0.92341 0.11608 0.40688 -0.90704 -0.10829 0.45108 -0.87891 -0.15507 0.06211 -0.91555 -0.39738 0.20937 -0.93219 0.29528 0.22907 -0.92338 0.30805 0.47825 -0.87339 0.09202 0.66502 -0.62224 0.41300 0.69413 -0.63215 0.34435 0.84513 -0.41959 0.33122 0.81387 -0.56586 0.13199 0.99956 -0.01586 0.02491 0.79015 0.00796 -0.61286 0.89534 -0.24843 -0.36966 0.95292 -0.24527 -0.17826 0.92277 -0.36653 -0.11895 0.92145 -0.38091 -0.07637 0.93826 -0.31972 0.13212 0.18102 -0.94853 -0.25987 0.74717 0.66462 0.00400 0.55447 0.81322 0.17674 0.64549 0.22621 -0.72950 0.65108 -0.06397 -0.75631 0.58414 0.01054 -0.81158 0.58197 -0.17649 -0.79382 0.61787 -0.54789 -0.56396 0.65402 -0.70064 -0.28522 0.69626 -0.68280 -0.22138 0.66918 -0.72860 -0.14608 0.65095 -0.74757 -0.13190 0.74557 -0.65479 0.12399 0.89253 0.16382 0.42019 0.94386 0.31286 0.10609 0.90485 0.39604 0.15618 0.90019 0.24292 -0.36146 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 0.91435 -0.39547 0.08702 0.26643 -0.75723 -0.59634 0.16796 0.98503 0.03880 0.60860 0.77577 -0.16669 0.17848 0.82084 -0.54255 0.33719 0.72006 -0.60647 0.17126 0.66622 -0.72582 0.66821 0.56903 -0.47927 0.45787 0.37931 -0.80404 0.32512 0.40348 -0.85528 0.22611 0.46609 -0.85536 0.14888 0.24947 -0.95687 0.11916 -0.65505 -0.74613 0.27151 -0.74449 -0.60993 0.35239 -0.86678 -0.35285 0.22134 -0.86293 -0.45426 0.36624 -0.86795 0.33547 0.99558 -0.05587 -0.07555 0.98111 -0.03503 -0.19024 0.98891 -0.00908 -0.14823 1.00000 -0.00004 0.00003 1.00000 -0.00003 0.00003 0.96587 0.12301 -0.22797 0.97224 0.13817 -0.18882 0.86584 0.47665 -0.15208 0.77133 0.60319 -0.20299 0.73388 0.64292 0.21926 0.67428 0.72869 -0.11980 0.62051 0.78284 -0.04612 0.67957 0.67909 0.27753 0.63970 0.18221 0.74671 0.63819 -0.17768 0.74910 0.86952 -0.47582 -0.13239 0.28461 0.95178 -0.11449 0.31198 0.94006 -0.13767 0.14912 0.96956 0.19420 0.33541 0.87206 0.35639 -0.01956 0.82495 0.56486 0.34323 0.61292 0.71170 0.16792 0.53017 0.83109 0.24219 0.23000 0.94257 0.37448 0.27321 0.88607 0.01231 -0.10319 0.99459 0.29267 -0.22068 0.93040 0.14736 -0.47959 0.86503 0.43258 -0.66793 0.60559 0.36425 -0.73470 0.57230 0.51256 -0.72510 0.45990 0.17223 -0.95216 0.25243 0.23304 -0.96955 -0.07527 0.06438 -0.98764 -0.14290 0.19191 -0.91946 -0.34316 0.00953 -0.86293 -0.50524 0.03284 0.99826 -0.04900 0.19998 -0.97969 0.01457 0.19296 -0.97604 0.10053 0.24438 -0.95988 0.13751 0.22374 -0.97465 -0.00125 0.55384 -0.83219 0.02684 0.59392 -0.80452 0.00261 0.55126 -0.83186 0.06417 0.47043 -0.87472 0.11647 0.83115 -0.55603 -0.00334 0.82951 -0.55848 -0.00185 0.98119 -0.19242 -0.01569 0.96497 -0.26186 0.01619 0.00323 -0.71872 -0.69529 0.26673 -0.75814 -0.59504 -0.29870 -0.71412 0.63309 0.07929 -0.69398 0.71562 0.16644 -0.72939 0.66354 0.99966 0.02320 0.01149 0.93713 0.34885 0.00997 0.89745 0.44067 0.01996 0.71143 0.70224 0.02702 0.74029 0.67160 0.03030 0.36484 0.93065 0.02803 0.47339 0.87988 0.04128 0.12798 0.99105 0.03798 0.08078 0.99594 0.03984 0.99728 0.07367 -0.00000 1.00000 -0.00290 -0.00000 0.99999 0.00327 0.00175 0.99998 -0.00544 -0.00291 0.43085 -0.64977 -0.62623 -0.00000 -0.86374 -0.50394 + + + + + + + + + + + + + + +

0 0 1 0 2 0 4 1 3 1 5 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 4 4 7 4 9 5 10 5 11 5 12 6 11 6 10 6 13 7 10 7 9 7 13 8 9 8 14 8 14 9 15 9 13 9 16 10 13 10 15 10 15 11 17 11 16 11 18 12 16 12 17 12 8 13 18 13 17 13 17 14 19 14 8 14 19 15 4 15 8 15 20 16 21 16 22 16 23 17 22 17 21 17 21 18 24 18 23 18 25 19 23 19 24 19 26 20 27 20 28 20 29 21 28 21 27 21 27 22 20 22 29 22 29 23 20 23 22 23 30 24 29 24 22 24 1 25 0 25 31 25 0 26 32 26 31 26 33 27 34 27 31 27 32 28 33 28 31 28 5 29 3 29 2 29 36 30 5 30 2 30 36 31 2 31 1 31 37 32 36 32 1 32 40 33 41 33 38 33 37 34 40 34 38 34 37 35 1 35 42 35 40 36 37 36 42 36 42 37 24 37 40 37 20 38 41 38 40 38 40 39 21 39 20 39 40 40 24 40 21 40 35 41 43 41 29 41 43 42 44 42 54 42 44 43 45 43 54 43 55 44 54 44 45 44 45 45 46 45 55 45 56 46 55 46 46 46 46 47 47 47 56 47 57 48 56 48 47 48 47 49 48 49 57 49 58 50 57 50 48 50 48 51 49 51 58 51 59 52 58 52 49 52 49 53 50 53 59 53 60 54 59 54 50 54 50 55 51 55 60 55 61 56 60 56 51 56 51 57 52 57 61 57 62 58 61 58 52 58 52 59 53 59 62 59 63 60 62 60 53 60 12 61 63 61 53 61 63 62 12 62 10 62 63 63 10 63 13 63 28 64 43 64 54 64 64 65 28 65 54 65 64 66 54 66 55 66 65 67 64 67 55 67 55 68 56 68 65 68 66 69 65 69 56 69 66 70 56 70 57 70 67 71 66 71 57 71 57 72 58 72 67 72 68 73 67 73 58 73 58 74 59 74 68 74 68 75 59 75 60 75 69 76 68 76 60 76 60 77 61 77 69 77 70 78 69 78 61 78 61 79 62 79 70 79 71 80 70 80 62 80 62 81 63 81 71 81 71 82 63 82 13 82 71 83 13 83 16 83 72 84 73 84 28 84 67 85 68 85 76 85 68 86 69 86 76 86 70 87 71 87 78 87 71 88 16 88 78 88 18 89 78 89 16 89 80 90 77 90 78 90 8 91 80 91 78 91 78 92 18 92 8 92 8 93 7 93 81 93 8 94 81 94 80 94 75 95 79 95 81 95 74 96 75 96 81 96 72 97 7 97 73 97 7 98 72 98 81 98 74 99 81 99 72 99 85 100 84 100 82 100 89 101 90 101 88 101 86 102 89 102 88 102 89 103 91 103 90 103 92 104 90 104 91 104 97 105 96 105 95 105 98 106 99 106 97 106 95 107 98 107 97 107 98 108 95 108 100 108 100 109 101 109 98 109 102 110 99 110 98 110 98 111 101 111 102 111 103 112 102 112 101 112 105 113 101 113 104 113 9 114 106 114 105 114 34 115 25 115 31 115 84 116 33 116 32 116 33 117 84 117 107 117 84 118 85 118 107 118 108 119 107 119 85 119 85 120 87 120 108 120 109 121 108 121 87 121 87 122 88 122 109 122 110 123 109 123 88 123 88 124 90 124 110 124 111 125 110 125 90 125 90 126 92 126 111 126 112 127 111 127 92 127 92 128 94 128 112 128 113 129 112 129 94 129 94 130 96 130 113 130 114 131 113 131 96 131 96 132 97 132 114 132 115 133 114 133 97 133 97 134 99 134 115 134 116 135 115 135 99 135 99 136 102 136 116 136 117 137 116 137 102 137 102 138 103 138 117 138 118 139 117 139 103 139 103 140 106 140 118 140 119 141 118 141 106 141 106 142 9 142 119 142 11 143 119 143 9 143 1 144 31 144 42 144 120 145 121 145 122 145 123 146 122 146 124 146 125 147 123 147 124 147 24 148 31 148 25 148 126 149 128 149 125 149 104 150 19 150 17 150 104 151 127 151 19 151 19 152 124 152 4 152 130 153 82 153 129 153 86 154 130 154 129 154 129 155 131 155 86 155 131 156 132 156 86 156 89 157 86 157 132 157 91 158 89 158 132 158 93 159 91 159 133 159 133 160 128 160 93 160 95 161 93 161 128 161 100 162 95 162 128 162 104 163 17 163 105 163 15 164 105 164 17 164 24 165 42 165 31 165 120 166 122 166 129 166 131 167 129 167 122 167 122 168 132 168 131 168 122 169 123 169 132 169 123 170 125 170 133 170 128 171 133 171 125 171 6 172 73 172 7 172 6 173 28 173 73 173 30 174 35 174 29 174 6 175 39 175 28 175 26 176 28 176 39 176 39 177 38 177 26 177 41 178 26 178 38 178 27 179 26 179 41 179 41 180 20 180 27 180 29 181 43 181 28 181 86 182 88 182 130 182 87 183 130 183 88 183 85 184 130 184 87 184 82 185 130 185 85 185 91 186 132 186 133 186 123 187 133 187 132 187 82 188 120 188 129 188 124 189 126 189 125 189 124 190 127 190 126 190 19 191 127 191 124 191 4 192 124 192 121 192 121 193 124 193 122 193 126 194 135 194 128 194 135 195 100 195 128 195 100 196 135 196 101 196 134 197 101 197 135 197 101 198 134 198 104 198 134 199 127 199 104 199 5 200 39 200 6 200 5 201 36 201 39 201 36 202 38 202 39 202 36 203 37 203 38 203 9 204 105 204 14 204 14 205 105 205 15 205 2 206 3 206 83 206 0 207 2 207 83 207 136 208 0 208 83 208 82 209 0 209 136 209 82 210 136 210 120 210 136 211 83 211 120 211 83 212 121 212 120 212 121 213 137 213 4 213 137 214 3 214 4 214 3 215 137 215 83 215 137 216 121 216 83 216 0 217 82 217 84 217 0 218 84 218 32 218 77 219 80 219 81 219 77 220 81 220 79 220 64 221 141 221 28 221 141 222 72 222 28 222 139 223 72 223 141 223 138 224 74 224 139 224 74 225 138 225 75 225 140 226 75 226 138 226 140 227 67 227 76 227 69 228 143 228 76 228 142 229 77 229 143 229 77 230 142 230 78 230 142 231 70 231 78 231 70 232 142 232 143 232 70 233 143 233 69 233 67 234 140 234 66 234 140 235 138 235 66 235 66 236 138 236 65 236 138 237 139 237 65 237 72 238 139 238 74 238 65 239 139 239 64 239 139 240 141 240 64 240 127 241 134 241 135 241 127 242 135 242 126 242 75 243 140 243 79 243 76 244 79 244 140 244 76 245 143 245 79 245 77 246 79 246 143 246 93 247 95 247 96 247 93 248 96 248 94 248 91 249 93 249 94 249 91 250 94 250 92 250 101 251 106 251 103 251 101 252 105 252 106 252 170 253 119 253 168 253 170 254 118 254 119 254 175 255 112 255 113 255 175 256 113 256 174 256 174 257 113 257 114 257 174 258 114 258 173 258 184 259 144 259 182 259 185 260 182 260 144 260 185 261 147 261 182 261 186 262 182 262 147 262 160 263 161 263 152 263 160 264 152 264 153 264 148 265 197 265 146 265 196 266 197 266 148 266 189 267 187 267 148 267 149 268 196 268 148 268 195 269 196 269 149 269 147 270 195 270 149 270 194 271 195 271 147 271 191 272 192 272 144 272 191 273 144 273 145 273 145 274 183 274 191 274 184 275 183 275 145 275 145 276 144 276 184 276 192 277 185 277 144 277 147 278 185 278 194 278 147 279 149 279 186 279 187 280 186 280 149 280 149 281 148 281 187 281 148 282 146 282 189 282 146 283 205 283 189 283 197 284 205 284 146 284 184 285 182 285 180 285 184 286 180 286 181 286 223 287 33 287 107 287 223 288 107 288 179 288 150 289 178 289 166 289 220 290 178 290 150 290 150 291 219 291 220 291 166 292 219 292 150 292 178 293 167 293 166 293 151 294 167 294 178 294 179 295 167 295 151 295 151 296 223 296 179 296 178 297 223 297 151 297 223 298 178 298 221 298 221 299 178 299 220 299 213 300 212 300 168 300 11 301 213 301 168 301 204 302 202 302 203 302 204 303 201 303 202 303 218 304 201 304 204 304 218 305 217 305 201 305 153 306 169 306 160 306 170 307 169 307 153 307 153 308 152 308 170 308 171 309 170 309 152 309 152 310 159 310 171 310 161 311 159 311 152 311 166 312 165 312 163 312 219 313 166 313 163 313 208 314 163 314 160 314 163 315 161 315 160 315 163 316 162 316 161 316 179 317 158 317 167 317 164 318 155 318 154 318 175 319 154 319 155 319 179 320 108 320 157 320 108 321 109 321 157 321 109 322 110 322 157 322 177 323 157 323 110 323 30 324 205 324 35 324 199 325 206 325 22 325 206 326 199 326 207 326 199 327 202 327 207 327 201 328 207 328 202 328 207 329 201 329 205 329 217 330 205 330 201 330 217 331 188 331 205 331 217 332 216 332 188 332 159 333 162 333 154 333 164 334 154 334 162 334 165 335 155 335 164 335 165 336 156 336 155 336 156 337 165 337 158 337 167 338 158 338 165 338 25 339 34 339 198 339 212 340 210 340 168 340 169 341 168 341 210 341 171 342 159 342 173 342 173 343 159 343 174 343 154 344 174 344 159 344 174 345 154 345 175 345 175 346 155 346 176 346 176 347 155 347 177 347 156 348 177 348 155 348 158 349 177 349 156 349 177 350 158 350 157 350 157 351 158 351 179 351 208 352 219 352 163 352 169 353 208 353 160 353 169 354 210 354 208 354 161 355 162 355 159 355 162 356 163 356 164 356 164 357 163 357 165 357 167 358 165 358 166 358 222 359 198 359 34 359 11 360 168 360 119 360 168 361 169 361 170 361 118 362 170 362 117 362 172 363 117 363 170 363 117 364 172 364 116 364 171 365 172 365 170 365 172 366 171 366 173 366 173 367 115 367 172 367 172 368 115 368 116 368 115 369 173 369 114 369 112 370 175 370 111 370 176 371 111 371 175 371 177 372 110 372 176 372 176 373 110 373 111 373 108 374 179 374 107 374 187 375 189 375 180 375 216 376 180 376 189 376 189 377 188 377 216 377 187 378 180 378 186 378 186 379 180 379 182 379 215 380 181 380 180 380 215 381 180 381 216 381 183 382 215 382 209 382 215 383 183 383 181 383 181 384 183 384 184 384 209 385 211 385 183 385 190 386 183 386 211 386 191 387 183 387 190 387 193 388 185 388 192 388 194 389 185 389 193 389 189 390 205 390 188 390 190 391 211 391 214 391 190 392 214 392 53 392 52 393 190 393 53 393 190 394 52 394 191 394 51 395 191 395 52 395 191 396 51 396 192 396 50 397 192 397 51 397 192 398 50 398 193 398 193 399 50 399 49 399 48 400 193 400 49 400 193 401 48 401 194 401 47 402 194 402 48 402 194 403 47 403 195 403 195 404 47 404 46 404 195 405 46 405 196 405 45 406 196 406 46 406 196 407 45 407 197 407 197 408 45 408 44 408 197 409 44 409 205 409 205 410 44 410 35 410 53 411 214 411 12 411 200 412 23 412 25 412 200 413 22 413 23 413 22 414 200 414 199 414 198 415 200 415 25 415 200 416 198 416 203 416 203 417 198 417 222 417 203 418 202 418 200 418 200 419 202 419 199 419 203 420 222 420 204 420 204 421 222 421 221 421 204 422 221 422 218 422 218 423 221 423 220 423 223 424 34 424 33 424 34 425 223 425 222 425 206 426 30 426 22 426 30 427 206 427 205 427 207 428 205 428 206 428 208 429 215 429 219 429 210 430 215 430 208 430 215 431 210 431 209 431 209 432 210 432 211 432 212 433 211 433 210 433 211 434 212 434 214 434 213 435 214 435 212 435 214 436 213 436 11 436 214 437 11 437 12 437 215 438 216 438 219 438 219 439 216 439 217 439 219 440 217 440 218 440 219 441 218 441 220 441 223 442 221 442 222 442 35 443 44 443 43 443

+
+
+
+
+ + + + 0.00000 0.00000 0.00004 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_middle/f_middle_G1M5.dae b/URDFs/sr_description/meshes/components/f_middle/f_middle_G1M5.dae new file mode 100644 index 0000000..7385453 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_middle/f_middle_G1M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:44.246463 + 2012-07-23T02:15:44.246477 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -5.15497 -5.65164 5.67687 -6.98593 -7.50773 8.86243 -8.01397 -5.97789 7.98236 -8.48097 -4.31842 6.98785 -8.50017 0.02188 5.46986 -8.50017 -3.88961 12.77786 -8.48937 -3.70556 18.59785 -8.50017 0.02188 20.53786 -8.22567 3.73770 21.84346 -3.50017 7.97965 1.21886 -3.50017 7.04980 24.44685 3.49296 7.97965 1.21886 3.49983 7.04980 24.44685 -4.29807 7.00277 24.01886 -4.75757 7.78174 2.14586 -6.73177 6.68550 2.87236 -6.31127 6.25102 22.77386 -7.75257 5.53448 3.44444 -7.62757 4.93940 22.20461 -8.42967 3.69429 4.18787 -3.43169 -8.64405 15.62886 -3.50017 -8.93332 12.68886 3.42448 -8.64405 15.62886 3.49296 -8.93332 12.68886 -3.50017 -8.97607 9.81386 3.49296 -8.97607 9.81386 -6.41337 -7.45056 17.15486 -4.73277 -7.88683 17.09686 -7.46427 -4.93237 19.65934 -4.00017 -5.21445 19.76886 3.99983 -5.21445 19.76886 -3.50017 -8.70539 8.82587 -4.00017 -5.82319 5.84886 3.99983 -5.82319 5.84886 3.49296 -8.70539 8.82587 4.48796 -5.61710 20.77286 -8.11957 -5.83721 12.86186 -7.03567 -7.45782 12.93086 -7.07657 -7.15262 16.53586 -8.02707 -5.46231 17.55201 -5.41357 -8.54068 12.82830 -5.52640 -8.05887 15.99102 -5.66907 -8.47778 9.50586 -4.49517 -5.61710 20.77286 4.75036 -6.43800 22.17986 4.75723 -6.97321 25.88187 4.75723 -6.48965 27.70586 4.75723 -4.19093 30.65686 4.75723 -2.54057 31.57185 4.75723 1.17980 31.95786 4.75723 2.98301 31.40186 4.75723 4.57411 30.38686 4.75723 6.68716 27.30086 4.75723 7.05771 25.45087 -4.75757 -6.43800 22.17986 -4.75757 -6.97321 25.88187 -4.75757 -6.48965 27.70586 -4.75757 -4.19093 30.65686 -4.75757 -2.54057 31.57185 -4.75757 1.17980 31.95786 -4.75757 2.98301 31.40186 -4.75757 4.57411 30.38686 -4.75757 6.68716 27.30086 -4.75757 7.05771 25.45087 -5.90557 -6.46749 22.90086 -5.90557 -6.71430 26.07986 -5.87887 -4.67070 29.33165 -5.90557 -3.05930 31.08986 -5.90557 0.04375 31.82587 -5.90557 3.14202 31.06985 -5.90557 5.55840 28.98886 -5.90557 6.76483 26.03687 -8.77364 -3.34911 22.56881 -8.45003 -3.33963 20.40928 -8.99996 -3.58678 25.82197 -8.99996 -2.60559 27.58099 -8.12147 0.02188 29.93286 -8.99996 3.11434 27.46986 -8.12147 4.95033 25.05086 -9.00000 0.02188 28.72610 -8.99996 3.87812 25.23030 -9.00019 0.02642 23.15286 -6.87887 -6.81239 2.17687 -6.52396 -4.86510 5.63609 -4.75757 -7.07768 3.79886 -4.75757 -7.78383 1.97186 -6.87887 -6.53824 -2.89314 -4.75757 -8.02808 0.02885 -4.75757 -7.79600 -1.91515 -6.87887 -5.85402 -4.57393 -4.75757 -5.98513 -5.35513 -6.40557 -4.61815 -6.29314 -4.75757 -4.51347 -6.64714 -5.90557 -1.56868 -7.33768 -4.75757 -2.77352 -7.54514 -5.90557 1.77076 -7.62013 -4.75757 1.09010 -7.97514 -4.75757 2.98490 -7.48114 -5.90557 4.79136 -6.19514 -4.75757 4.70447 -6.54414 -6.87887 3.66948 -6.17014 -5.90557 6.94247 -3.64114 -4.75757 6.14692 -5.22014 -4.75757 7.22694 -3.58614 -8.12147 6.00887 0.10429 -5.90557 7.63414 -0.42213 -4.75757 7.88062 -1.74014 4.75723 -7.07768 3.79886 4.75723 -7.78383 1.97186 4.75723 -8.02808 0.02885 4.75723 -7.79600 -1.91515 4.75723 -5.98513 -5.35513 4.75723 -4.51347 -6.64714 4.75723 -2.77352 -7.54514 4.75723 1.09010 -7.97514 4.75723 2.98490 -7.48114 4.75723 4.70447 -6.54414 4.75723 6.14692 -5.22014 4.75723 7.22694 -3.58614 4.75723 7.88062 -1.74014 -7.87887 -5.40786 2.46296 -8.50000 -3.55834 4.34187 -9.00000 -3.59913 -1.17314 -9.00000 -2.21603 -3.07614 -9.00000 0.02188 4.39287 -9.00000 0.02188 -4.58014 -9.00000 2.25979 -3.07614 -9.00000 3.74480 -1.09914 -8.12147 1.63616 -5.70114 -8.12147 -5.89100 -0.42914 -6.87887 -7.13355 0.48087 -8.12147 -5.60089 -1.87614 -8.12100 -4.85241 -4.18614 -8.12147 -1.44278 -5.74113 -8.12100 5.47326 -2.53608 -8.12100 4.61814 -4.13956 -6.75466 -5.90532 3.90648 -8.45823 -3.70615 5.68876 -8.12100 -3.83817 28.38669 -8.12100 -4.78404 25.94850 -8.12100 -3.16487 29.14326 -7.96933 -4.72890 22.71507 -8.12100 3.99730 28.01863 -8.12100 3.12703 29.12051 8.11379 3.12703 29.12051 8.11379 3.99730 28.01863 7.96212 -4.72890 22.71507 8.11379 -3.16488 29.14326 8.11379 -4.78404 25.94850 8.11379 -3.83817 28.38669 8.45102 -3.70615 5.68876 6.74746 -5.90533 3.90648 8.11379 4.61814 -4.13956 8.11379 5.47326 -2.53608 8.11426 -1.44278 -5.74114 8.11379 -4.85241 -4.18614 8.11426 -5.60089 -1.87615 6.87166 -7.13355 0.48086 8.11426 -5.89100 -0.42914 8.11426 1.63616 -5.70114 9.00000 3.74480 -1.09914 9.00000 2.25979 -3.07614 9.00000 0.02188 -4.58014 9.00000 0.02188 4.39287 9.00000 -2.21603 -3.07614 9.00000 -3.59913 -1.17314 8.49279 -3.55834 4.34187 7.87166 -5.40786 2.46296 5.89836 7.63414 -0.42213 8.11426 6.00887 0.10428 5.89836 6.94247 -3.64114 6.87166 3.66948 -6.17014 5.89836 4.79136 -6.19515 5.89836 1.77076 -7.62013 5.89836 -1.56868 -7.33768 6.39836 -4.61815 -6.29314 6.87166 -5.85402 -4.57393 6.87166 -6.53824 -2.89314 6.51675 -4.86510 5.63609 6.87166 -6.81239 2.17686 9.00019 0.02642 23.15286 8.99996 3.87812 25.23030 9.00000 0.02188 28.72610 8.11426 4.95033 25.05086 8.99996 3.11434 27.46986 8.11426 0.02188 29.93286 8.99996 -2.60559 27.58099 8.99996 -3.58678 25.82197 8.44282 -3.33963 20.40928 8.76643 -3.34911 22.56881 5.89836 6.76483 26.03687 5.89836 5.55840 28.98886 5.89836 3.14202 31.06985 5.89836 0.04374 31.82587 5.89836 -3.05930 31.08986 5.87166 -4.67070 29.33165 5.89836 -6.71430 26.07986 5.89836 -6.46749 22.90086 5.66186 -8.47778 9.50586 5.51919 -8.05887 15.99102 5.40636 -8.54068 12.82830 8.01986 -5.46231 17.55201 7.06936 -7.15262 16.53586 7.02846 -7.45782 12.93086 8.11236 -5.83721 12.86186 7.45706 -4.93237 19.65934 4.72556 -7.88683 17.09686 6.40616 -7.45056 17.15486 8.42246 3.69429 4.18787 7.62036 4.93940 22.20461 7.74536 5.53448 3.44444 6.30406 6.25102 22.77386 6.72456 6.68550 2.87236 4.75036 7.78174 2.14586 4.29086 7.00277 24.01886 8.21846 3.73770 21.84346 8.49296 0.02188 20.53786 8.48216 -3.70556 18.59785 8.49296 -3.88961 12.77786 8.49296 0.02188 5.46986 8.47376 -4.31842 6.98785 8.00676 -5.97789 7.98236 6.97873 -7.50773 8.86243 5.14776 -5.65164 5.67686 + + + + + + + + + + -0.43084 -0.64978 -0.62623 -0.99998 -0.00544 -0.00291 -0.99999 0.00327 0.00175 -1.00000 -0.00290 0.00000 -0.99728 0.07367 0.00000 0.00000 0.99920 0.04000 0.00000 0.99920 0.04000 -0.08009 0.99599 0.03987 -0.12798 0.99105 0.03798 -0.47339 0.87988 0.04128 -0.36485 0.93065 0.02803 -0.74029 0.67160 0.03030 -0.71143 0.70224 0.02702 -0.89745 0.44067 0.01996 -0.93713 0.34885 0.00997 -0.99966 0.02320 0.01149 -0.00000 -0.99519 0.09792 -0.00000 -0.99519 0.09792 -0.00000 -0.99989 0.01487 -0.00000 -0.99989 0.01487 -0.16644 -0.72939 0.66354 -0.07913 -0.69391 0.71570 0.29821 -0.71453 0.63287 -0.00000 -0.77008 0.63794 0.00000 -0.77008 0.63794 -0.26673 -0.75814 -0.59504 -0.00321 -0.71872 -0.69529 -0.00000 -0.71845 -0.69557 -0.00000 -0.71845 -0.69557 -0.96497 -0.26186 0.01619 -0.98119 -0.19242 -0.01569 -0.82951 -0.55849 -0.00185 -0.83115 -0.55604 -0.00334 -0.47043 -0.87472 0.11647 -0.55126 -0.83186 0.06417 -0.59392 -0.80452 0.00261 -0.55384 -0.83219 0.02684 -0.22374 -0.97465 -0.00125 -0.24438 -0.95988 0.13751 -0.19296 -0.97604 0.10053 -0.19998 -0.97969 0.01457 -0.00000 -0.92814 -0.37223 -0.00000 -0.86374 -0.50394 -0.00000 -0.98971 -0.14308 0.00000 -0.98971 -0.14309 0.00000 -0.96661 0.25626 0.00000 -0.96661 0.25626 0.00000 -0.78890 0.61452 0.00000 -0.78890 0.61452 0.00000 -0.48488 0.87458 0.00000 -0.48488 0.87458 0.00000 -0.10320 0.99466 0.00000 -0.10320 0.99466 -0.00000 0.29465 0.95561 -0.00000 0.29465 0.95561 -0.00000 0.53781 0.84307 0.00000 0.53781 0.84307 0.00000 0.82511 0.56497 0.00000 0.82511 0.56497 0.00000 0.98052 0.19640 0.00000 0.98052 0.19640 0.00000 0.99997 -0.00788 0.00000 0.99997 -0.00788 -0.03267 0.99827 -0.04878 -0.00952 -0.86293 -0.50524 -0.19191 -0.91946 -0.34316 -0.06431 -0.98766 -0.14279 -0.23172 -0.96986 -0.07530 -0.17124 -0.95233 0.25247 -0.51028 -0.72626 0.46061 -0.36232 -0.73530 0.57277 -0.43045 -0.66867 0.60630 -0.14650 -0.47965 0.86514 -0.29107 -0.22079 0.93088 -0.01223 -0.10319 0.99459 -0.37255 0.27344 0.88681 -0.24082 0.23008 0.94290 -0.16695 0.53026 0.83123 -0.34141 0.61335 0.71220 0.01944 0.82495 0.56486 -0.33363 0.87264 0.35663 -0.14825 0.96969 0.19423 -0.30923 0.94131 -0.13534 -0.28461 0.95178 -0.11449 -0.86952 -0.47582 -0.13239 -0.63819 -0.17768 0.74910 -0.63970 0.18221 0.74671 -0.67957 0.67909 0.27753 -0.62051 0.78284 -0.04612 -0.67429 0.72869 -0.11980 -0.73664 0.64008 0.21829 -0.77390 0.60030 -0.20181 -0.86584 0.47665 -0.15208 -0.97286 0.13731 -0.18626 -0.96646 0.12196 -0.22601 -1.00000 -0.00003 0.00003 -1.00000 -0.00004 0.00003 -0.98891 -0.00908 -0.14823 -0.98167 -0.03342 -0.18765 -0.99584 -0.05416 -0.07324 -0.36521 -0.86832 0.33561 -0.22066 -0.86307 -0.45434 -0.35140 -0.86713 -0.35299 -0.27065 -0.74481 -0.60993 -0.11867 -0.65509 -0.74618 -0.14801 0.24950 -0.95700 -0.22483 0.46623 -0.85562 -0.32338 0.40374 -0.85582 -0.45787 0.37931 -0.80404 -0.66821 0.56903 -0.47927 -0.17026 0.66634 -0.72595 -0.33540 0.72055 -0.60689 -0.17744 0.82100 -0.54265 -0.60860 0.77577 -0.16669 -0.16759 0.98511 0.03825 -0.00000 -0.96446 -0.26423 0.00000 -0.85296 0.52197 0.00000 -0.85296 0.52197 0.00000 -0.93275 0.36052 0.00000 -0.93275 0.36052 0.00000 -0.99219 0.12473 0.00000 -0.99219 0.12473 -0.00000 -0.99295 -0.11854 -0.00000 -0.99295 -0.11854 -0.00000 -0.88488 -0.46582 -0.00000 -0.88488 -0.46582 -0.00000 -0.65975 -0.75149 -0.00000 -0.65975 -0.75149 -0.00000 -0.45863 -0.88863 -0.00000 -0.45863 -0.88863 -0.00000 -0.11061 -0.99386 -0.00000 -0.11061 -0.99386 -0.00000 0.25228 -0.96765 -0.00000 0.25228 -0.96765 -0.00000 0.47848 -0.87810 -0.00000 0.47848 -0.87810 -0.00000 0.67621 -0.73671 -0.00000 0.67621 -0.73671 -0.00000 0.83424 -0.55140 -0.00000 0.83424 -0.55140 -0.00000 0.94264 -0.33380 -0.00000 0.94264 -0.33380 -0.00000 0.99944 -0.03345 0.00000 0.99944 -0.03345 -0.26643 -0.75723 -0.59634 -0.91489 -0.39448 0.08586 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -0.00000 -0.96446 -0.26423 -0.90158 0.24131 -0.35907 -0.90485 0.39604 0.15618 -0.94467 0.31082 0.10487 -0.89506 0.16219 0.41539 -0.74557 -0.65479 0.12399 -0.65095 -0.74758 -0.13190 -0.66918 -0.72860 -0.14608 -0.69626 -0.68280 -0.22138 -0.65402 -0.70065 -0.28522 -0.61787 -0.54789 -0.56396 -0.58197 -0.17649 -0.79382 -0.58414 0.01054 -0.81158 -0.65108 -0.06397 -0.75631 -0.64549 0.22621 -0.72950 -0.55447 0.81322 0.17674 -0.74717 0.66462 0.00400 -0.18101 -0.94853 -0.25987 -0.93915 -0.31722 0.13177 -0.92258 -0.37827 -0.07584 -0.92388 -0.36399 -0.11813 -0.95364 -0.24345 -0.17694 -0.89678 -0.24681 -0.36724 -0.79257 0.00792 -0.60973 -0.99956 -0.01586 0.02491 -0.81387 -0.56586 0.13199 0.00000 -0.92814 -0.37223 -0.84513 -0.41959 0.33122 -0.69413 -0.63215 0.34435 -0.66502 -0.62224 0.41300 -0.47825 -0.87339 0.09202 -0.22907 -0.92338 0.30805 -0.20936 -0.93219 0.29528 -0.06197 -0.91543 -0.39768 -0.44992 -0.87948 -0.15518 -0.40578 -0.90753 -0.10834 -0.36482 -0.92381 0.11613 -0.39655 -0.90198 0.17080 -0.72765 -0.28472 -0.62407 -0.92274 -0.16003 -0.35062 -0.78720 -0.59414 0.16529 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.98151 0.15842 0.10739 -0.89920 -0.13152 0.41731 -0.98615 -0.13901 0.09043 -0.91814 0.18394 -0.35098 -0.73800 0.31314 -0.59774 -0.51084 0.61558 -0.60008 -0.63402 0.68235 -0.36389 -0.59956 0.78433 -0.15921 -0.91399 0.39761 -0.08082 -0.96554 -0.26005 0.01002 -0.98113 -0.19024 0.03456 -0.85485 -0.51561 0.05807 -0.83137 -0.55445 0.03751 -0.14858 0.98885 0.00958 -0.43892 0.88671 0.14525 -0.57656 -0.53325 -0.61905 -0.39080 -0.71053 -0.58517 -0.44124 -0.74181 0.50500 -0.37160 -0.81095 0.45197 -0.72353 -0.58860 0.36064 -0.75356 -0.51410 0.40970 -0.67246 -0.62637 0.39428 -0.99951 -0.00949 0.02996 -0.99965 -0.01262 -0.02345 -0.48297 -0.78878 -0.38022 -0.51397 -0.85427 -0.07781 -0.45695 -0.75232 0.47457 -0.20294 -0.80005 0.56457 -1.00000 0.00005 0.00002 -1.00000 0.00003 0.00003 -0.64042 -0.76606 -0.05484 -0.85396 -0.50916 -0.10724 -0.86063 -0.50687 -0.04901 -0.79753 -0.56244 0.21819 -0.85811 -0.44842 0.25013 -0.85616 -0.38599 0.34351 -0.64381 -0.18412 0.74270 -0.64894 0.19266 0.73604 -0.76162 0.50854 0.40165 -0.75386 0.62553 0.20099 -0.62699 0.74169 0.23828 -0.63612 0.60551 0.47824 -0.55727 0.54184 0.62917 -0.48481 -0.64844 0.58693 -0.48698 -0.65246 0.58064 -0.47463 -0.74348 0.47114 -0.64037 -0.71607 0.27779 -0.79712 -0.59566 -0.09897 -0.65381 -0.75439 -0.05857 -0.64141 -0.76598 -0.04315 -0.92870 0.32722 -0.17450 -0.94438 0.26293 -0.19750 -0.88324 -0.18735 0.42986 -0.79998 -0.14442 0.58239 -0.79902 0.15230 0.58169 -0.86767 0.18711 0.46059 -0.33715 -0.07934 -0.93810 -0.28355 -0.10607 -0.95307 -0.40679 -0.23563 -0.88261 -0.15968 -0.45274 -0.87723 -0.21262 0.92109 -0.32617 -0.41120 0.89121 -0.19149 0.41325 0.89030 -0.19130 0.21384 0.92084 -0.32608 0.16033 -0.45269 -0.87713 0.40856 -0.23510 -0.88193 0.28512 -0.10602 -0.95261 0.33894 -0.07929 -0.93746 0.86591 0.18827 0.46342 0.79665 0.15309 0.58473 0.79762 -0.14517 0.58543 0.88165 -0.18855 0.43260 0.94354 0.26485 -0.19894 0.92765 0.32953 -0.17573 0.64141 -0.76598 -0.04315 0.65381 -0.75439 -0.05857 0.79456 -0.59876 -0.10078 0.64037 -0.71607 0.27779 0.47463 -0.74348 0.47114 0.48698 -0.65246 0.58064 0.48481 -0.64844 0.58693 0.55727 0.54184 0.62917 0.63612 0.60551 0.47824 0.62699 0.74169 0.23828 0.75120 0.62843 0.20193 0.75900 0.51095 0.40355 0.64894 0.19266 0.73604 0.64381 -0.18412 0.74270 0.85428 -0.38831 0.34557 0.85625 -0.45112 0.25164 0.79515 -0.56536 0.21933 0.86063 -0.50687 -0.04901 0.85396 -0.50916 -0.10724 0.64042 -0.76606 -0.05484 1.00000 0.00003 0.00003 1.00000 0.00005 0.00002 0.20411 -0.79963 0.56474 0.45858 -0.75108 0.47496 0.51397 -0.85427 -0.07781 0.48297 -0.78878 -0.38022 0.99965 -0.01262 -0.02345 0.99951 -0.00949 0.02996 0.67246 -0.62637 0.39428 0.75356 -0.51409 0.40970 0.72353 -0.58860 0.36064 0.37160 -0.81095 0.45197 0.44124 -0.74181 0.50500 0.39080 -0.71053 -0.58517 0.57656 -0.53325 -0.61905 0.43892 0.88671 0.14525 0.14858 0.98885 0.00958 0.83138 -0.55444 0.03751 0.85485 -0.51561 0.05807 0.98113 -0.19024 0.03456 0.96554 -0.26005 0.01002 0.91275 0.40033 -0.08137 0.59956 0.78433 -0.15921 0.63402 0.68235 -0.36389 0.51084 0.61559 -0.60008 0.73800 0.31314 -0.59774 0.91695 0.18521 -0.35340 0.98576 -0.14096 0.09170 0.89670 -0.13305 0.42216 0.98106 0.16035 0.10870 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 0.78720 -0.59414 0.16529 0.92162 -0.16115 -0.35307 0.72765 -0.28472 -0.62407 0.39764 -0.90152 0.17072 0.36584 -0.92341 0.11608 0.40688 -0.90704 -0.10829 0.45108 -0.87891 -0.15507 0.06211 -0.91555 -0.39738 0.20937 -0.93219 0.29528 0.22907 -0.92338 0.30805 0.47825 -0.87339 0.09202 0.66502 -0.62224 0.41300 0.69413 -0.63215 0.34435 0.84513 -0.41959 0.33122 0.81387 -0.56586 0.13199 0.99956 -0.01586 0.02491 0.79015 0.00796 -0.61286 0.89534 -0.24843 -0.36966 0.95292 -0.24527 -0.17826 0.92277 -0.36653 -0.11895 0.92145 -0.38091 -0.07637 0.93826 -0.31972 0.13212 0.18102 -0.94853 -0.25987 0.74717 0.66462 0.00400 0.55447 0.81322 0.17674 0.64549 0.22621 -0.72950 0.65108 -0.06397 -0.75631 0.58414 0.01054 -0.81158 0.58197 -0.17649 -0.79382 0.61787 -0.54789 -0.56396 0.65402 -0.70064 -0.28522 0.69626 -0.68280 -0.22138 0.66918 -0.72860 -0.14608 0.65095 -0.74757 -0.13190 0.74557 -0.65479 0.12399 0.89253 0.16382 0.42019 0.94386 0.31286 0.10609 0.90485 0.39604 0.15618 0.90019 0.24292 -0.36146 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 0.91435 -0.39547 0.08702 0.26643 -0.75723 -0.59634 0.16796 0.98503 0.03880 0.60860 0.77577 -0.16669 0.17848 0.82084 -0.54255 0.33719 0.72006 -0.60647 0.17126 0.66622 -0.72582 0.66821 0.56903 -0.47927 0.45787 0.37931 -0.80404 0.32512 0.40348 -0.85528 0.22611 0.46609 -0.85536 0.14888 0.24947 -0.95687 0.11916 -0.65505 -0.74613 0.27151 -0.74449 -0.60993 0.35239 -0.86678 -0.35285 0.22134 -0.86293 -0.45426 0.36624 -0.86795 0.33547 0.99558 -0.05587 -0.07555 0.98111 -0.03503 -0.19024 0.98891 -0.00908 -0.14823 1.00000 -0.00004 0.00003 1.00000 -0.00003 0.00003 0.96587 0.12301 -0.22797 0.97224 0.13817 -0.18882 0.86584 0.47665 -0.15208 0.77133 0.60319 -0.20299 0.73388 0.64292 0.21926 0.67428 0.72869 -0.11980 0.62051 0.78284 -0.04612 0.67957 0.67909 0.27753 0.63970 0.18221 0.74671 0.63819 -0.17768 0.74910 0.86952 -0.47582 -0.13239 0.28461 0.95178 -0.11449 0.31198 0.94006 -0.13767 0.14912 0.96956 0.19420 0.33541 0.87206 0.35639 -0.01956 0.82495 0.56486 0.34323 0.61292 0.71170 0.16792 0.53017 0.83109 0.24219 0.23000 0.94257 0.37448 0.27321 0.88607 0.01231 -0.10319 0.99459 0.29267 -0.22068 0.93040 0.14736 -0.47959 0.86503 0.43258 -0.66793 0.60559 0.36425 -0.73470 0.57230 0.51256 -0.72510 0.45990 0.17223 -0.95216 0.25243 0.23304 -0.96955 -0.07527 0.06438 -0.98764 -0.14290 0.19191 -0.91946 -0.34316 0.00953 -0.86293 -0.50524 0.03284 0.99826 -0.04900 0.19998 -0.97969 0.01457 0.19296 -0.97604 0.10053 0.24438 -0.95988 0.13751 0.22374 -0.97465 -0.00125 0.55384 -0.83219 0.02684 0.59392 -0.80452 0.00261 0.55126 -0.83186 0.06417 0.47043 -0.87472 0.11647 0.83115 -0.55603 -0.00334 0.82951 -0.55848 -0.00185 0.98119 -0.19242 -0.01569 0.96497 -0.26186 0.01619 0.00323 -0.71872 -0.69529 0.26673 -0.75814 -0.59504 -0.29870 -0.71412 0.63309 0.07929 -0.69398 0.71562 0.16644 -0.72939 0.66354 0.99966 0.02320 0.01149 0.93713 0.34885 0.00997 0.89745 0.44067 0.01996 0.71143 0.70224 0.02702 0.74029 0.67160 0.03030 0.36484 0.93065 0.02803 0.47339 0.87988 0.04128 0.12798 0.99105 0.03798 0.08078 0.99594 0.03984 0.99728 0.07367 -0.00000 1.00000 -0.00290 -0.00000 0.99999 0.00327 0.00175 0.99998 -0.00544 -0.00291 0.43085 -0.64977 -0.62623 -0.00000 -0.86374 -0.50394 + + + + + + + + + + + + + + +

0 0 1 0 2 0 4 1 3 1 5 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 4 4 7 4 9 5 10 5 11 5 12 6 11 6 10 6 13 7 10 7 9 7 13 8 9 8 14 8 14 9 15 9 13 9 16 10 13 10 15 10 15 11 17 11 16 11 18 12 16 12 17 12 8 13 18 13 17 13 17 14 19 14 8 14 19 15 4 15 8 15 20 16 21 16 22 16 23 17 22 17 21 17 21 18 24 18 23 18 25 19 23 19 24 19 26 20 27 20 28 20 29 21 28 21 27 21 27 22 20 22 29 22 29 23 20 23 22 23 30 24 29 24 22 24 1 25 0 25 31 25 0 26 32 26 31 26 33 27 34 27 31 27 32 28 33 28 31 28 5 29 3 29 2 29 36 30 5 30 2 30 36 31 2 31 1 31 37 32 36 32 1 32 40 33 41 33 38 33 37 34 40 34 38 34 37 35 1 35 42 35 40 36 37 36 42 36 42 37 24 37 40 37 20 38 41 38 40 38 40 39 21 39 20 39 40 40 24 40 21 40 35 41 43 41 29 41 43 42 44 42 54 42 44 43 45 43 54 43 55 44 54 44 45 44 45 45 46 45 55 45 56 46 55 46 46 46 46 47 47 47 56 47 57 48 56 48 47 48 47 49 48 49 57 49 58 50 57 50 48 50 48 51 49 51 58 51 59 52 58 52 49 52 49 53 50 53 59 53 60 54 59 54 50 54 50 55 51 55 60 55 61 56 60 56 51 56 51 57 52 57 61 57 62 58 61 58 52 58 52 59 53 59 62 59 63 60 62 60 53 60 12 61 63 61 53 61 63 62 12 62 10 62 63 63 10 63 13 63 28 64 43 64 54 64 64 65 28 65 54 65 64 66 54 66 55 66 65 67 64 67 55 67 55 68 56 68 65 68 66 69 65 69 56 69 66 70 56 70 57 70 67 71 66 71 57 71 57 72 58 72 67 72 68 73 67 73 58 73 58 74 59 74 68 74 68 75 59 75 60 75 69 76 68 76 60 76 60 77 61 77 69 77 70 78 69 78 61 78 61 79 62 79 70 79 71 80 70 80 62 80 62 81 63 81 71 81 71 82 63 82 13 82 71 83 13 83 16 83 72 84 73 84 28 84 67 85 68 85 76 85 68 86 69 86 76 86 70 87 71 87 78 87 71 88 16 88 78 88 18 89 78 89 16 89 80 90 77 90 78 90 8 91 80 91 78 91 78 92 18 92 8 92 8 93 7 93 81 93 8 94 81 94 80 94 75 95 79 95 81 95 74 96 75 96 81 96 72 97 7 97 73 97 7 98 72 98 81 98 74 99 81 99 72 99 85 100 84 100 82 100 89 101 90 101 88 101 86 102 89 102 88 102 89 103 91 103 90 103 92 104 90 104 91 104 97 105 96 105 95 105 98 106 99 106 97 106 95 107 98 107 97 107 98 108 95 108 100 108 100 109 101 109 98 109 102 110 99 110 98 110 98 111 101 111 102 111 103 112 102 112 101 112 105 113 101 113 104 113 9 114 106 114 105 114 34 115 25 115 31 115 84 116 33 116 32 116 33 117 84 117 107 117 84 118 85 118 107 118 108 119 107 119 85 119 85 120 87 120 108 120 109 121 108 121 87 121 87 122 88 122 109 122 110 123 109 123 88 123 88 124 90 124 110 124 111 125 110 125 90 125 90 126 92 126 111 126 112 127 111 127 92 127 92 128 94 128 112 128 113 129 112 129 94 129 94 130 96 130 113 130 114 131 113 131 96 131 96 132 97 132 114 132 115 133 114 133 97 133 97 134 99 134 115 134 116 135 115 135 99 135 99 136 102 136 116 136 117 137 116 137 102 137 102 138 103 138 117 138 118 139 117 139 103 139 103 140 106 140 118 140 119 141 118 141 106 141 106 142 9 142 119 142 11 143 119 143 9 143 1 144 31 144 42 144 120 145 121 145 122 145 123 146 122 146 124 146 125 147 123 147 124 147 24 148 31 148 25 148 126 149 128 149 125 149 104 150 19 150 17 150 104 151 127 151 19 151 19 152 124 152 4 152 130 153 82 153 129 153 86 154 130 154 129 154 129 155 131 155 86 155 131 156 132 156 86 156 89 157 86 157 132 157 91 158 89 158 132 158 93 159 91 159 133 159 133 160 128 160 93 160 95 161 93 161 128 161 100 162 95 162 128 162 104 163 17 163 105 163 15 164 105 164 17 164 24 165 42 165 31 165 120 166 122 166 129 166 131 167 129 167 122 167 122 168 132 168 131 168 122 169 123 169 132 169 123 170 125 170 133 170 128 171 133 171 125 171 6 172 73 172 7 172 6 173 28 173 73 173 30 174 35 174 29 174 6 175 39 175 28 175 26 176 28 176 39 176 39 177 38 177 26 177 41 178 26 178 38 178 27 179 26 179 41 179 41 180 20 180 27 180 29 181 43 181 28 181 86 182 88 182 130 182 87 183 130 183 88 183 85 184 130 184 87 184 82 185 130 185 85 185 91 186 132 186 133 186 123 187 133 187 132 187 82 188 120 188 129 188 124 189 126 189 125 189 124 190 127 190 126 190 19 191 127 191 124 191 4 192 124 192 121 192 121 193 124 193 122 193 126 194 135 194 128 194 135 195 100 195 128 195 100 196 135 196 101 196 134 197 101 197 135 197 101 198 134 198 104 198 134 199 127 199 104 199 5 200 39 200 6 200 5 201 36 201 39 201 36 202 38 202 39 202 36 203 37 203 38 203 9 204 105 204 14 204 14 205 105 205 15 205 2 206 3 206 83 206 0 207 2 207 83 207 136 208 0 208 83 208 82 209 0 209 136 209 82 210 136 210 120 210 136 211 83 211 120 211 83 212 121 212 120 212 121 213 137 213 4 213 137 214 3 214 4 214 3 215 137 215 83 215 137 216 121 216 83 216 0 217 82 217 84 217 0 218 84 218 32 218 77 219 80 219 81 219 77 220 81 220 79 220 64 221 141 221 28 221 141 222 72 222 28 222 139 223 72 223 141 223 138 224 74 224 139 224 74 225 138 225 75 225 140 226 75 226 138 226 140 227 67 227 76 227 69 228 143 228 76 228 142 229 77 229 143 229 77 230 142 230 78 230 142 231 70 231 78 231 70 232 142 232 143 232 70 233 143 233 69 233 67 234 140 234 66 234 140 235 138 235 66 235 66 236 138 236 65 236 138 237 139 237 65 237 72 238 139 238 74 238 65 239 139 239 64 239 139 240 141 240 64 240 127 241 134 241 135 241 127 242 135 242 126 242 75 243 140 243 79 243 76 244 79 244 140 244 76 245 143 245 79 245 77 246 79 246 143 246 93 247 95 247 96 247 93 248 96 248 94 248 91 249 93 249 94 249 91 250 94 250 92 250 101 251 106 251 103 251 101 252 105 252 106 252 170 253 119 253 168 253 170 254 118 254 119 254 175 255 112 255 113 255 175 256 113 256 174 256 174 257 113 257 114 257 174 258 114 258 173 258 184 259 144 259 182 259 185 260 182 260 144 260 185 261 147 261 182 261 186 262 182 262 147 262 160 263 161 263 152 263 160 264 152 264 153 264 148 265 197 265 146 265 196 266 197 266 148 266 189 267 187 267 148 267 149 268 196 268 148 268 195 269 196 269 149 269 147 270 195 270 149 270 194 271 195 271 147 271 191 272 192 272 144 272 191 273 144 273 145 273 145 274 183 274 191 274 184 275 183 275 145 275 145 276 144 276 184 276 192 277 185 277 144 277 147 278 185 278 194 278 147 279 149 279 186 279 187 280 186 280 149 280 149 281 148 281 187 281 148 282 146 282 189 282 146 283 205 283 189 283 197 284 205 284 146 284 184 285 182 285 180 285 184 286 180 286 181 286 223 287 33 287 107 287 223 288 107 288 179 288 150 289 178 289 166 289 220 290 178 290 150 290 150 291 219 291 220 291 166 292 219 292 150 292 178 293 167 293 166 293 151 294 167 294 178 294 179 295 167 295 151 295 151 296 223 296 179 296 178 297 223 297 151 297 223 298 178 298 221 298 221 299 178 299 220 299 213 300 212 300 168 300 11 301 213 301 168 301 204 302 202 302 203 302 204 303 201 303 202 303 218 304 201 304 204 304 218 305 217 305 201 305 153 306 169 306 160 306 170 307 169 307 153 307 153 308 152 308 170 308 171 309 170 309 152 309 152 310 159 310 171 310 161 311 159 311 152 311 166 312 165 312 163 312 219 313 166 313 163 313 208 314 163 314 160 314 163 315 161 315 160 315 163 316 162 316 161 316 179 317 158 317 167 317 164 318 155 318 154 318 175 319 154 319 155 319 179 320 108 320 157 320 108 321 109 321 157 321 109 322 110 322 157 322 177 323 157 323 110 323 30 324 205 324 35 324 199 325 206 325 22 325 206 326 199 326 207 326 199 327 202 327 207 327 201 328 207 328 202 328 207 329 201 329 205 329 217 330 205 330 201 330 217 331 188 331 205 331 217 332 216 332 188 332 159 333 162 333 154 333 164 334 154 334 162 334 165 335 155 335 164 335 165 336 156 336 155 336 156 337 165 337 158 337 167 338 158 338 165 338 25 339 34 339 198 339 212 340 210 340 168 340 169 341 168 341 210 341 171 342 159 342 173 342 173 343 159 343 174 343 154 344 174 344 159 344 174 345 154 345 175 345 175 346 155 346 176 346 176 347 155 347 177 347 156 348 177 348 155 348 158 349 177 349 156 349 177 350 158 350 157 350 157 351 158 351 179 351 208 352 219 352 163 352 169 353 208 353 160 353 169 354 210 354 208 354 161 355 162 355 159 355 162 356 163 356 164 356 164 357 163 357 165 357 167 358 165 358 166 358 222 359 198 359 34 359 11 360 168 360 119 360 168 361 169 361 170 361 118 362 170 362 117 362 172 363 117 363 170 363 117 364 172 364 116 364 171 365 172 365 170 365 172 366 171 366 173 366 173 367 115 367 172 367 172 368 115 368 116 368 115 369 173 369 114 369 112 370 175 370 111 370 176 371 111 371 175 371 177 372 110 372 176 372 176 373 110 373 111 373 108 374 179 374 107 374 187 375 189 375 180 375 216 376 180 376 189 376 189 377 188 377 216 377 187 378 180 378 186 378 186 379 180 379 182 379 215 380 181 380 180 380 215 381 180 381 216 381 183 382 215 382 209 382 215 383 183 383 181 383 181 384 183 384 184 384 209 385 211 385 183 385 190 386 183 386 211 386 191 387 183 387 190 387 193 388 185 388 192 388 194 389 185 389 193 389 189 390 205 390 188 390 190 391 211 391 214 391 190 392 214 392 53 392 52 393 190 393 53 393 190 394 52 394 191 394 51 395 191 395 52 395 191 396 51 396 192 396 50 397 192 397 51 397 192 398 50 398 193 398 193 399 50 399 49 399 48 400 193 400 49 400 193 401 48 401 194 401 47 402 194 402 48 402 194 403 47 403 195 403 195 404 47 404 46 404 195 405 46 405 196 405 45 406 196 406 46 406 196 407 45 407 197 407 197 408 45 408 44 408 197 409 44 409 205 409 205 410 44 410 35 410 53 411 214 411 12 411 200 412 23 412 25 412 200 413 22 413 23 413 22 414 200 414 199 414 198 415 200 415 25 415 200 416 198 416 203 416 203 417 198 417 222 417 203 418 202 418 200 418 200 419 202 419 199 419 203 420 222 420 204 420 204 421 222 421 221 421 204 422 221 422 218 422 218 423 221 423 220 423 223 424 34 424 33 424 34 425 223 425 222 425 206 426 30 426 22 426 30 427 206 427 205 427 207 428 205 428 206 428 208 429 215 429 219 429 210 430 215 430 208 430 215 431 210 431 209 431 209 432 210 432 211 432 212 433 211 433 210 433 211 434 212 434 214 434 213 435 214 435 212 435 214 436 213 436 11 436 214 437 11 437 12 437 215 438 216 438 219 438 219 439 216 439 217 439 219 440 217 440 218 440 219 441 218 441 220 441 223 442 221 442 222 442 35 443 44 443 43 443

+
+
+
+
+ + + + 0.00000 0.00000 0.00004 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_middle/f_middle_G4.dae b/URDFs/sr_description/meshes/components/f_middle/f_middle_G4.dae new file mode 100644 index 0000000..ab94bb1 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_middle/f_middle_G4.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:44.246463 + 2012-07-23T02:15:44.246477 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -5.15497 -5.65164 5.67687 -6.98593 -7.50773 8.86243 -8.01397 -5.97789 7.98236 -8.48097 -4.31842 6.98785 -8.50017 0.02188 5.46986 -8.50017 -3.88961 12.77786 -8.48937 -3.70556 18.59785 -8.50017 0.02188 20.53786 -8.22567 3.73770 21.84346 -3.50017 7.97965 1.21886 -3.50017 7.04980 24.44685 3.49296 7.97965 1.21886 3.49983 7.04980 24.44685 -4.29807 7.00277 24.01886 -4.75757 7.78174 2.14586 -6.73177 6.68550 2.87236 -6.31127 6.25102 22.77386 -7.75257 5.53448 3.44444 -7.62757 4.93940 22.20461 -8.42967 3.69429 4.18787 -3.43169 -8.64405 15.62886 -3.50017 -8.93332 12.68886 3.42448 -8.64405 15.62886 3.49296 -8.93332 12.68886 -3.50017 -8.97607 9.81386 3.49296 -8.97607 9.81386 -6.41337 -7.45056 17.15486 -4.73277 -7.88683 17.09686 -7.46427 -4.93237 19.65934 -4.00017 -5.21445 19.76886 3.99983 -5.21445 19.76886 -3.50017 -8.70539 8.82587 -4.00017 -5.82319 5.84886 3.99983 -5.82319 5.84886 3.49296 -8.70539 8.82587 4.48796 -5.61710 20.77286 -8.11957 -5.83721 12.86186 -7.03567 -7.45782 12.93086 -7.07657 -7.15262 16.53586 -8.02707 -5.46231 17.55201 -5.41357 -8.54068 12.82830 -5.52640 -8.05887 15.99102 -5.66907 -8.47778 9.50586 -4.49517 -5.61710 20.77286 4.75036 -6.43800 22.17986 4.75723 -6.97321 25.88187 4.75723 -6.48965 27.70586 4.75723 -4.19093 30.65686 4.75723 -2.54057 31.57185 4.75723 1.17980 31.95786 4.75723 2.98301 31.40186 4.75723 4.57411 30.38686 4.75723 6.68716 27.30086 4.75723 7.05771 25.45087 -4.75757 -6.43800 22.17986 -4.75757 -6.97321 25.88187 -4.75757 -6.48965 27.70586 -4.75757 -4.19093 30.65686 -4.75757 -2.54057 31.57185 -4.75757 1.17980 31.95786 -4.75757 2.98301 31.40186 -4.75757 4.57411 30.38686 -4.75757 6.68716 27.30086 -4.75757 7.05771 25.45087 -5.90557 -6.46749 22.90086 -5.90557 -6.71430 26.07986 -5.87887 -4.67070 29.33165 -5.90557 -3.05930 31.08986 -5.90557 0.04375 31.82587 -5.90557 3.14202 31.06985 -5.90557 5.55840 28.98886 -5.90557 6.76483 26.03687 -8.77364 -3.34911 22.56881 -8.45003 -3.33963 20.40928 -8.99996 -3.58678 25.82197 -8.99996 -2.60559 27.58099 -8.12147 0.02188 29.93286 -8.99996 3.11434 27.46986 -8.12147 4.95033 25.05086 -9.00000 0.02188 28.72610 -8.99996 3.87812 25.23030 -9.00019 0.02642 23.15286 -6.87887 -6.81239 2.17687 -6.52396 -4.86510 5.63609 -4.75757 -7.07768 3.79886 -4.75757 -7.78383 1.97186 -6.87887 -6.53824 -2.89314 -4.75757 -8.02808 0.02885 -4.75757 -7.79600 -1.91515 -6.87887 -5.85402 -4.57393 -4.75757 -5.98513 -5.35513 -6.40557 -4.61815 -6.29314 -4.75757 -4.51347 -6.64714 -5.90557 -1.56868 -7.33768 -4.75757 -2.77352 -7.54514 -5.90557 1.77076 -7.62013 -4.75757 1.09010 -7.97514 -4.75757 2.98490 -7.48114 -5.90557 4.79136 -6.19514 -4.75757 4.70447 -6.54414 -6.87887 3.66948 -6.17014 -5.90557 6.94247 -3.64114 -4.75757 6.14692 -5.22014 -4.75757 7.22694 -3.58614 -8.12147 6.00887 0.10429 -5.90557 7.63414 -0.42213 -4.75757 7.88062 -1.74014 4.75723 -7.07768 3.79886 4.75723 -7.78383 1.97186 4.75723 -8.02808 0.02885 4.75723 -7.79600 -1.91515 4.75723 -5.98513 -5.35513 4.75723 -4.51347 -6.64714 4.75723 -2.77352 -7.54514 4.75723 1.09010 -7.97514 4.75723 2.98490 -7.48114 4.75723 4.70447 -6.54414 4.75723 6.14692 -5.22014 4.75723 7.22694 -3.58614 4.75723 7.88062 -1.74014 -7.87887 -5.40786 2.46296 -8.50000 -3.55834 4.34187 -9.00000 -3.59913 -1.17314 -9.00000 -2.21603 -3.07614 -9.00000 0.02188 4.39287 -9.00000 0.02188 -4.58014 -9.00000 2.25979 -3.07614 -9.00000 3.74480 -1.09914 -8.12147 1.63616 -5.70114 -8.12147 -5.89100 -0.42914 -6.87887 -7.13355 0.48087 -8.12147 -5.60089 -1.87614 -8.12100 -4.85241 -4.18614 -8.12147 -1.44278 -5.74113 -8.12100 5.47326 -2.53608 -8.12100 4.61814 -4.13956 -6.75466 -5.90532 3.90648 -8.45823 -3.70615 5.68876 -8.12100 -3.83817 28.38669 -8.12100 -4.78404 25.94850 -8.12100 -3.16487 29.14326 -7.96933 -4.72890 22.71507 -8.12100 3.99730 28.01863 -8.12100 3.12703 29.12051 8.11379 3.12703 29.12051 8.11379 3.99730 28.01863 7.96212 -4.72890 22.71507 8.11379 -3.16488 29.14326 8.11379 -4.78404 25.94850 8.11379 -3.83817 28.38669 8.45102 -3.70615 5.68876 6.74746 -5.90533 3.90648 8.11379 4.61814 -4.13956 8.11379 5.47326 -2.53608 8.11426 -1.44278 -5.74114 8.11379 -4.85241 -4.18614 8.11426 -5.60089 -1.87615 6.87166 -7.13355 0.48086 8.11426 -5.89100 -0.42914 8.11426 1.63616 -5.70114 9.00000 3.74480 -1.09914 9.00000 2.25979 -3.07614 9.00000 0.02188 -4.58014 9.00000 0.02188 4.39287 9.00000 -2.21603 -3.07614 9.00000 -3.59913 -1.17314 8.49279 -3.55834 4.34187 7.87166 -5.40786 2.46296 5.89836 7.63414 -0.42213 8.11426 6.00887 0.10428 5.89836 6.94247 -3.64114 6.87166 3.66948 -6.17014 5.89836 4.79136 -6.19515 5.89836 1.77076 -7.62013 5.89836 -1.56868 -7.33768 6.39836 -4.61815 -6.29314 6.87166 -5.85402 -4.57393 6.87166 -6.53824 -2.89314 6.51675 -4.86510 5.63609 6.87166 -6.81239 2.17686 9.00019 0.02642 23.15286 8.99996 3.87812 25.23030 9.00000 0.02188 28.72610 8.11426 4.95033 25.05086 8.99996 3.11434 27.46986 8.11426 0.02188 29.93286 8.99996 -2.60559 27.58099 8.99996 -3.58678 25.82197 8.44282 -3.33963 20.40928 8.76643 -3.34911 22.56881 5.89836 6.76483 26.03687 5.89836 5.55840 28.98886 5.89836 3.14202 31.06985 5.89836 0.04374 31.82587 5.89836 -3.05930 31.08986 5.87166 -4.67070 29.33165 5.89836 -6.71430 26.07986 5.89836 -6.46749 22.90086 5.66186 -8.47778 9.50586 5.51919 -8.05887 15.99102 5.40636 -8.54068 12.82830 8.01986 -5.46231 17.55201 7.06936 -7.15262 16.53586 7.02846 -7.45782 12.93086 8.11236 -5.83721 12.86186 7.45706 -4.93237 19.65934 4.72556 -7.88683 17.09686 6.40616 -7.45056 17.15486 8.42246 3.69429 4.18787 7.62036 4.93940 22.20461 7.74536 5.53448 3.44444 6.30406 6.25102 22.77386 6.72456 6.68550 2.87236 4.75036 7.78174 2.14586 4.29086 7.00277 24.01886 8.21846 3.73770 21.84346 8.49296 0.02188 20.53786 8.48216 -3.70556 18.59785 8.49296 -3.88961 12.77786 8.49296 0.02188 5.46986 8.47376 -4.31842 6.98785 8.00676 -5.97789 7.98236 6.97873 -7.50773 8.86243 5.14776 -5.65164 5.67686 + + + + + + + + + + -0.43084 -0.64978 -0.62623 -0.99998 -0.00544 -0.00291 -0.99999 0.00327 0.00175 -1.00000 -0.00290 0.00000 -0.99728 0.07367 0.00000 0.00000 0.99920 0.04000 0.00000 0.99920 0.04000 -0.08009 0.99599 0.03987 -0.12798 0.99105 0.03798 -0.47339 0.87988 0.04128 -0.36485 0.93065 0.02803 -0.74029 0.67160 0.03030 -0.71143 0.70224 0.02702 -0.89745 0.44067 0.01996 -0.93713 0.34885 0.00997 -0.99966 0.02320 0.01149 -0.00000 -0.99519 0.09792 -0.00000 -0.99519 0.09792 -0.00000 -0.99989 0.01487 -0.00000 -0.99989 0.01487 -0.16644 -0.72939 0.66354 -0.07913 -0.69391 0.71570 0.29821 -0.71453 0.63287 -0.00000 -0.77008 0.63794 0.00000 -0.77008 0.63794 -0.26673 -0.75814 -0.59504 -0.00321 -0.71872 -0.69529 -0.00000 -0.71845 -0.69557 -0.00000 -0.71845 -0.69557 -0.96497 -0.26186 0.01619 -0.98119 -0.19242 -0.01569 -0.82951 -0.55849 -0.00185 -0.83115 -0.55604 -0.00334 -0.47043 -0.87472 0.11647 -0.55126 -0.83186 0.06417 -0.59392 -0.80452 0.00261 -0.55384 -0.83219 0.02684 -0.22374 -0.97465 -0.00125 -0.24438 -0.95988 0.13751 -0.19296 -0.97604 0.10053 -0.19998 -0.97969 0.01457 -0.00000 -0.92814 -0.37223 -0.00000 -0.86374 -0.50394 -0.00000 -0.98971 -0.14308 0.00000 -0.98971 -0.14309 0.00000 -0.96661 0.25626 0.00000 -0.96661 0.25626 0.00000 -0.78890 0.61452 0.00000 -0.78890 0.61452 0.00000 -0.48488 0.87458 0.00000 -0.48488 0.87458 0.00000 -0.10320 0.99466 0.00000 -0.10320 0.99466 -0.00000 0.29465 0.95561 -0.00000 0.29465 0.95561 -0.00000 0.53781 0.84307 0.00000 0.53781 0.84307 0.00000 0.82511 0.56497 0.00000 0.82511 0.56497 0.00000 0.98052 0.19640 0.00000 0.98052 0.19640 0.00000 0.99997 -0.00788 0.00000 0.99997 -0.00788 -0.03267 0.99827 -0.04878 -0.00952 -0.86293 -0.50524 -0.19191 -0.91946 -0.34316 -0.06431 -0.98766 -0.14279 -0.23172 -0.96986 -0.07530 -0.17124 -0.95233 0.25247 -0.51028 -0.72626 0.46061 -0.36232 -0.73530 0.57277 -0.43045 -0.66867 0.60630 -0.14650 -0.47965 0.86514 -0.29107 -0.22079 0.93088 -0.01223 -0.10319 0.99459 -0.37255 0.27344 0.88681 -0.24082 0.23008 0.94290 -0.16695 0.53026 0.83123 -0.34141 0.61335 0.71220 0.01944 0.82495 0.56486 -0.33363 0.87264 0.35663 -0.14825 0.96969 0.19423 -0.30923 0.94131 -0.13534 -0.28461 0.95178 -0.11449 -0.86952 -0.47582 -0.13239 -0.63819 -0.17768 0.74910 -0.63970 0.18221 0.74671 -0.67957 0.67909 0.27753 -0.62051 0.78284 -0.04612 -0.67429 0.72869 -0.11980 -0.73664 0.64008 0.21829 -0.77390 0.60030 -0.20181 -0.86584 0.47665 -0.15208 -0.97286 0.13731 -0.18626 -0.96646 0.12196 -0.22601 -1.00000 -0.00003 0.00003 -1.00000 -0.00004 0.00003 -0.98891 -0.00908 -0.14823 -0.98167 -0.03342 -0.18765 -0.99584 -0.05416 -0.07324 -0.36521 -0.86832 0.33561 -0.22066 -0.86307 -0.45434 -0.35140 -0.86713 -0.35299 -0.27065 -0.74481 -0.60993 -0.11867 -0.65509 -0.74618 -0.14801 0.24950 -0.95700 -0.22483 0.46623 -0.85562 -0.32338 0.40374 -0.85582 -0.45787 0.37931 -0.80404 -0.66821 0.56903 -0.47927 -0.17026 0.66634 -0.72595 -0.33540 0.72055 -0.60689 -0.17744 0.82100 -0.54265 -0.60860 0.77577 -0.16669 -0.16759 0.98511 0.03825 -0.00000 -0.96446 -0.26423 0.00000 -0.85296 0.52197 0.00000 -0.85296 0.52197 0.00000 -0.93275 0.36052 0.00000 -0.93275 0.36052 0.00000 -0.99219 0.12473 0.00000 -0.99219 0.12473 -0.00000 -0.99295 -0.11854 -0.00000 -0.99295 -0.11854 -0.00000 -0.88488 -0.46582 -0.00000 -0.88488 -0.46582 -0.00000 -0.65975 -0.75149 -0.00000 -0.65975 -0.75149 -0.00000 -0.45863 -0.88863 -0.00000 -0.45863 -0.88863 -0.00000 -0.11061 -0.99386 -0.00000 -0.11061 -0.99386 -0.00000 0.25228 -0.96765 -0.00000 0.25228 -0.96765 -0.00000 0.47848 -0.87810 -0.00000 0.47848 -0.87810 -0.00000 0.67621 -0.73671 -0.00000 0.67621 -0.73671 -0.00000 0.83424 -0.55140 -0.00000 0.83424 -0.55140 -0.00000 0.94264 -0.33380 -0.00000 0.94264 -0.33380 -0.00000 0.99944 -0.03345 0.00000 0.99944 -0.03345 -0.26643 -0.75723 -0.59634 -0.91489 -0.39448 0.08586 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -0.00000 -0.96446 -0.26423 -0.90158 0.24131 -0.35907 -0.90485 0.39604 0.15618 -0.94467 0.31082 0.10487 -0.89506 0.16219 0.41539 -0.74557 -0.65479 0.12399 -0.65095 -0.74758 -0.13190 -0.66918 -0.72860 -0.14608 -0.69626 -0.68280 -0.22138 -0.65402 -0.70065 -0.28522 -0.61787 -0.54789 -0.56396 -0.58197 -0.17649 -0.79382 -0.58414 0.01054 -0.81158 -0.65108 -0.06397 -0.75631 -0.64549 0.22621 -0.72950 -0.55447 0.81322 0.17674 -0.74717 0.66462 0.00400 -0.18101 -0.94853 -0.25987 -0.93915 -0.31722 0.13177 -0.92258 -0.37827 -0.07584 -0.92388 -0.36399 -0.11813 -0.95364 -0.24345 -0.17694 -0.89678 -0.24681 -0.36724 -0.79257 0.00792 -0.60973 -0.99956 -0.01586 0.02491 -0.81387 -0.56586 0.13199 0.00000 -0.92814 -0.37223 -0.84513 -0.41959 0.33122 -0.69413 -0.63215 0.34435 -0.66502 -0.62224 0.41300 -0.47825 -0.87339 0.09202 -0.22907 -0.92338 0.30805 -0.20936 -0.93219 0.29528 -0.06197 -0.91543 -0.39768 -0.44992 -0.87948 -0.15518 -0.40578 -0.90753 -0.10834 -0.36482 -0.92381 0.11613 -0.39655 -0.90198 0.17080 -0.72765 -0.28472 -0.62407 -0.92274 -0.16003 -0.35062 -0.78720 -0.59414 0.16529 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.98151 0.15842 0.10739 -0.89920 -0.13152 0.41731 -0.98615 -0.13901 0.09043 -0.91814 0.18394 -0.35098 -0.73800 0.31314 -0.59774 -0.51084 0.61558 -0.60008 -0.63402 0.68235 -0.36389 -0.59956 0.78433 -0.15921 -0.91399 0.39761 -0.08082 -0.96554 -0.26005 0.01002 -0.98113 -0.19024 0.03456 -0.85485 -0.51561 0.05807 -0.83137 -0.55445 0.03751 -0.14858 0.98885 0.00958 -0.43892 0.88671 0.14525 -0.57656 -0.53325 -0.61905 -0.39080 -0.71053 -0.58517 -0.44124 -0.74181 0.50500 -0.37160 -0.81095 0.45197 -0.72353 -0.58860 0.36064 -0.75356 -0.51410 0.40970 -0.67246 -0.62637 0.39428 -0.99951 -0.00949 0.02996 -0.99965 -0.01262 -0.02345 -0.48297 -0.78878 -0.38022 -0.51397 -0.85427 -0.07781 -0.45695 -0.75232 0.47457 -0.20294 -0.80005 0.56457 -1.00000 0.00005 0.00002 -1.00000 0.00003 0.00003 -0.64042 -0.76606 -0.05484 -0.85396 -0.50916 -0.10724 -0.86063 -0.50687 -0.04901 -0.79753 -0.56244 0.21819 -0.85811 -0.44842 0.25013 -0.85616 -0.38599 0.34351 -0.64381 -0.18412 0.74270 -0.64894 0.19266 0.73604 -0.76162 0.50854 0.40165 -0.75386 0.62553 0.20099 -0.62699 0.74169 0.23828 -0.63612 0.60551 0.47824 -0.55727 0.54184 0.62917 -0.48481 -0.64844 0.58693 -0.48698 -0.65246 0.58064 -0.47463 -0.74348 0.47114 -0.64037 -0.71607 0.27779 -0.79712 -0.59566 -0.09897 -0.65381 -0.75439 -0.05857 -0.64141 -0.76598 -0.04315 -0.92870 0.32722 -0.17450 -0.94438 0.26293 -0.19750 -0.88324 -0.18735 0.42986 -0.79998 -0.14442 0.58239 -0.79902 0.15230 0.58169 -0.86767 0.18711 0.46059 -0.33715 -0.07934 -0.93810 -0.28355 -0.10607 -0.95307 -0.40679 -0.23563 -0.88261 -0.15968 -0.45274 -0.87723 -0.21262 0.92109 -0.32617 -0.41120 0.89121 -0.19149 0.41325 0.89030 -0.19130 0.21384 0.92084 -0.32608 0.16033 -0.45269 -0.87713 0.40856 -0.23510 -0.88193 0.28512 -0.10602 -0.95261 0.33894 -0.07929 -0.93746 0.86591 0.18827 0.46342 0.79665 0.15309 0.58473 0.79762 -0.14517 0.58543 0.88165 -0.18855 0.43260 0.94354 0.26485 -0.19894 0.92765 0.32953 -0.17573 0.64141 -0.76598 -0.04315 0.65381 -0.75439 -0.05857 0.79456 -0.59876 -0.10078 0.64037 -0.71607 0.27779 0.47463 -0.74348 0.47114 0.48698 -0.65246 0.58064 0.48481 -0.64844 0.58693 0.55727 0.54184 0.62917 0.63612 0.60551 0.47824 0.62699 0.74169 0.23828 0.75120 0.62843 0.20193 0.75900 0.51095 0.40355 0.64894 0.19266 0.73604 0.64381 -0.18412 0.74270 0.85428 -0.38831 0.34557 0.85625 -0.45112 0.25164 0.79515 -0.56536 0.21933 0.86063 -0.50687 -0.04901 0.85396 -0.50916 -0.10724 0.64042 -0.76606 -0.05484 1.00000 0.00003 0.00003 1.00000 0.00005 0.00002 0.20411 -0.79963 0.56474 0.45858 -0.75108 0.47496 0.51397 -0.85427 -0.07781 0.48297 -0.78878 -0.38022 0.99965 -0.01262 -0.02345 0.99951 -0.00949 0.02996 0.67246 -0.62637 0.39428 0.75356 -0.51409 0.40970 0.72353 -0.58860 0.36064 0.37160 -0.81095 0.45197 0.44124 -0.74181 0.50500 0.39080 -0.71053 -0.58517 0.57656 -0.53325 -0.61905 0.43892 0.88671 0.14525 0.14858 0.98885 0.00958 0.83138 -0.55444 0.03751 0.85485 -0.51561 0.05807 0.98113 -0.19024 0.03456 0.96554 -0.26005 0.01002 0.91275 0.40033 -0.08137 0.59956 0.78433 -0.15921 0.63402 0.68235 -0.36389 0.51084 0.61559 -0.60008 0.73800 0.31314 -0.59774 0.91695 0.18521 -0.35340 0.98576 -0.14096 0.09170 0.89670 -0.13305 0.42216 0.98106 0.16035 0.10870 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 0.78720 -0.59414 0.16529 0.92162 -0.16115 -0.35307 0.72765 -0.28472 -0.62407 0.39764 -0.90152 0.17072 0.36584 -0.92341 0.11608 0.40688 -0.90704 -0.10829 0.45108 -0.87891 -0.15507 0.06211 -0.91555 -0.39738 0.20937 -0.93219 0.29528 0.22907 -0.92338 0.30805 0.47825 -0.87339 0.09202 0.66502 -0.62224 0.41300 0.69413 -0.63215 0.34435 0.84513 -0.41959 0.33122 0.81387 -0.56586 0.13199 0.99956 -0.01586 0.02491 0.79015 0.00796 -0.61286 0.89534 -0.24843 -0.36966 0.95292 -0.24527 -0.17826 0.92277 -0.36653 -0.11895 0.92145 -0.38091 -0.07637 0.93826 -0.31972 0.13212 0.18102 -0.94853 -0.25987 0.74717 0.66462 0.00400 0.55447 0.81322 0.17674 0.64549 0.22621 -0.72950 0.65108 -0.06397 -0.75631 0.58414 0.01054 -0.81158 0.58197 -0.17649 -0.79382 0.61787 -0.54789 -0.56396 0.65402 -0.70064 -0.28522 0.69626 -0.68280 -0.22138 0.66918 -0.72860 -0.14608 0.65095 -0.74757 -0.13190 0.74557 -0.65479 0.12399 0.89253 0.16382 0.42019 0.94386 0.31286 0.10609 0.90485 0.39604 0.15618 0.90019 0.24292 -0.36146 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 0.91435 -0.39547 0.08702 0.26643 -0.75723 -0.59634 0.16796 0.98503 0.03880 0.60860 0.77577 -0.16669 0.17848 0.82084 -0.54255 0.33719 0.72006 -0.60647 0.17126 0.66622 -0.72582 0.66821 0.56903 -0.47927 0.45787 0.37931 -0.80404 0.32512 0.40348 -0.85528 0.22611 0.46609 -0.85536 0.14888 0.24947 -0.95687 0.11916 -0.65505 -0.74613 0.27151 -0.74449 -0.60993 0.35239 -0.86678 -0.35285 0.22134 -0.86293 -0.45426 0.36624 -0.86795 0.33547 0.99558 -0.05587 -0.07555 0.98111 -0.03503 -0.19024 0.98891 -0.00908 -0.14823 1.00000 -0.00004 0.00003 1.00000 -0.00003 0.00003 0.96587 0.12301 -0.22797 0.97224 0.13817 -0.18882 0.86584 0.47665 -0.15208 0.77133 0.60319 -0.20299 0.73388 0.64292 0.21926 0.67428 0.72869 -0.11980 0.62051 0.78284 -0.04612 0.67957 0.67909 0.27753 0.63970 0.18221 0.74671 0.63819 -0.17768 0.74910 0.86952 -0.47582 -0.13239 0.28461 0.95178 -0.11449 0.31198 0.94006 -0.13767 0.14912 0.96956 0.19420 0.33541 0.87206 0.35639 -0.01956 0.82495 0.56486 0.34323 0.61292 0.71170 0.16792 0.53017 0.83109 0.24219 0.23000 0.94257 0.37448 0.27321 0.88607 0.01231 -0.10319 0.99459 0.29267 -0.22068 0.93040 0.14736 -0.47959 0.86503 0.43258 -0.66793 0.60559 0.36425 -0.73470 0.57230 0.51256 -0.72510 0.45990 0.17223 -0.95216 0.25243 0.23304 -0.96955 -0.07527 0.06438 -0.98764 -0.14290 0.19191 -0.91946 -0.34316 0.00953 -0.86293 -0.50524 0.03284 0.99826 -0.04900 0.19998 -0.97969 0.01457 0.19296 -0.97604 0.10053 0.24438 -0.95988 0.13751 0.22374 -0.97465 -0.00125 0.55384 -0.83219 0.02684 0.59392 -0.80452 0.00261 0.55126 -0.83186 0.06417 0.47043 -0.87472 0.11647 0.83115 -0.55603 -0.00334 0.82951 -0.55848 -0.00185 0.98119 -0.19242 -0.01569 0.96497 -0.26186 0.01619 0.00323 -0.71872 -0.69529 0.26673 -0.75814 -0.59504 -0.29870 -0.71412 0.63309 0.07929 -0.69398 0.71562 0.16644 -0.72939 0.66354 0.99966 0.02320 0.01149 0.93713 0.34885 0.00997 0.89745 0.44067 0.01996 0.71143 0.70224 0.02702 0.74029 0.67160 0.03030 0.36484 0.93065 0.02803 0.47339 0.87988 0.04128 0.12798 0.99105 0.03798 0.08078 0.99594 0.03984 0.99728 0.07367 -0.00000 1.00000 -0.00290 -0.00000 0.99999 0.00327 0.00175 0.99998 -0.00544 -0.00291 0.43085 -0.64977 -0.62623 -0.00000 -0.86374 -0.50394 + + + + + + + + + + + + + + +

0 0 1 0 2 0 4 1 3 1 5 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 4 4 7 4 9 5 10 5 11 5 12 6 11 6 10 6 13 7 10 7 9 7 13 8 9 8 14 8 14 9 15 9 13 9 16 10 13 10 15 10 15 11 17 11 16 11 18 12 16 12 17 12 8 13 18 13 17 13 17 14 19 14 8 14 19 15 4 15 8 15 20 16 21 16 22 16 23 17 22 17 21 17 21 18 24 18 23 18 25 19 23 19 24 19 26 20 27 20 28 20 29 21 28 21 27 21 27 22 20 22 29 22 29 23 20 23 22 23 30 24 29 24 22 24 1 25 0 25 31 25 0 26 32 26 31 26 33 27 34 27 31 27 32 28 33 28 31 28 5 29 3 29 2 29 36 30 5 30 2 30 36 31 2 31 1 31 37 32 36 32 1 32 40 33 41 33 38 33 37 34 40 34 38 34 37 35 1 35 42 35 40 36 37 36 42 36 42 37 24 37 40 37 20 38 41 38 40 38 40 39 21 39 20 39 40 40 24 40 21 40 35 41 43 41 29 41 43 42 44 42 54 42 44 43 45 43 54 43 55 44 54 44 45 44 45 45 46 45 55 45 56 46 55 46 46 46 46 47 47 47 56 47 57 48 56 48 47 48 47 49 48 49 57 49 58 50 57 50 48 50 48 51 49 51 58 51 59 52 58 52 49 52 49 53 50 53 59 53 60 54 59 54 50 54 50 55 51 55 60 55 61 56 60 56 51 56 51 57 52 57 61 57 62 58 61 58 52 58 52 59 53 59 62 59 63 60 62 60 53 60 12 61 63 61 53 61 63 62 12 62 10 62 63 63 10 63 13 63 28 64 43 64 54 64 64 65 28 65 54 65 64 66 54 66 55 66 65 67 64 67 55 67 55 68 56 68 65 68 66 69 65 69 56 69 66 70 56 70 57 70 67 71 66 71 57 71 57 72 58 72 67 72 68 73 67 73 58 73 58 74 59 74 68 74 68 75 59 75 60 75 69 76 68 76 60 76 60 77 61 77 69 77 70 78 69 78 61 78 61 79 62 79 70 79 71 80 70 80 62 80 62 81 63 81 71 81 71 82 63 82 13 82 71 83 13 83 16 83 72 84 73 84 28 84 67 85 68 85 76 85 68 86 69 86 76 86 70 87 71 87 78 87 71 88 16 88 78 88 18 89 78 89 16 89 80 90 77 90 78 90 8 91 80 91 78 91 78 92 18 92 8 92 8 93 7 93 81 93 8 94 81 94 80 94 75 95 79 95 81 95 74 96 75 96 81 96 72 97 7 97 73 97 7 98 72 98 81 98 74 99 81 99 72 99 85 100 84 100 82 100 89 101 90 101 88 101 86 102 89 102 88 102 89 103 91 103 90 103 92 104 90 104 91 104 97 105 96 105 95 105 98 106 99 106 97 106 95 107 98 107 97 107 98 108 95 108 100 108 100 109 101 109 98 109 102 110 99 110 98 110 98 111 101 111 102 111 103 112 102 112 101 112 105 113 101 113 104 113 9 114 106 114 105 114 34 115 25 115 31 115 84 116 33 116 32 116 33 117 84 117 107 117 84 118 85 118 107 118 108 119 107 119 85 119 85 120 87 120 108 120 109 121 108 121 87 121 87 122 88 122 109 122 110 123 109 123 88 123 88 124 90 124 110 124 111 125 110 125 90 125 90 126 92 126 111 126 112 127 111 127 92 127 92 128 94 128 112 128 113 129 112 129 94 129 94 130 96 130 113 130 114 131 113 131 96 131 96 132 97 132 114 132 115 133 114 133 97 133 97 134 99 134 115 134 116 135 115 135 99 135 99 136 102 136 116 136 117 137 116 137 102 137 102 138 103 138 117 138 118 139 117 139 103 139 103 140 106 140 118 140 119 141 118 141 106 141 106 142 9 142 119 142 11 143 119 143 9 143 1 144 31 144 42 144 120 145 121 145 122 145 123 146 122 146 124 146 125 147 123 147 124 147 24 148 31 148 25 148 126 149 128 149 125 149 104 150 19 150 17 150 104 151 127 151 19 151 19 152 124 152 4 152 130 153 82 153 129 153 86 154 130 154 129 154 129 155 131 155 86 155 131 156 132 156 86 156 89 157 86 157 132 157 91 158 89 158 132 158 93 159 91 159 133 159 133 160 128 160 93 160 95 161 93 161 128 161 100 162 95 162 128 162 104 163 17 163 105 163 15 164 105 164 17 164 24 165 42 165 31 165 120 166 122 166 129 166 131 167 129 167 122 167 122 168 132 168 131 168 122 169 123 169 132 169 123 170 125 170 133 170 128 171 133 171 125 171 6 172 73 172 7 172 6 173 28 173 73 173 30 174 35 174 29 174 6 175 39 175 28 175 26 176 28 176 39 176 39 177 38 177 26 177 41 178 26 178 38 178 27 179 26 179 41 179 41 180 20 180 27 180 29 181 43 181 28 181 86 182 88 182 130 182 87 183 130 183 88 183 85 184 130 184 87 184 82 185 130 185 85 185 91 186 132 186 133 186 123 187 133 187 132 187 82 188 120 188 129 188 124 189 126 189 125 189 124 190 127 190 126 190 19 191 127 191 124 191 4 192 124 192 121 192 121 193 124 193 122 193 126 194 135 194 128 194 135 195 100 195 128 195 100 196 135 196 101 196 134 197 101 197 135 197 101 198 134 198 104 198 134 199 127 199 104 199 5 200 39 200 6 200 5 201 36 201 39 201 36 202 38 202 39 202 36 203 37 203 38 203 9 204 105 204 14 204 14 205 105 205 15 205 2 206 3 206 83 206 0 207 2 207 83 207 136 208 0 208 83 208 82 209 0 209 136 209 82 210 136 210 120 210 136 211 83 211 120 211 83 212 121 212 120 212 121 213 137 213 4 213 137 214 3 214 4 214 3 215 137 215 83 215 137 216 121 216 83 216 0 217 82 217 84 217 0 218 84 218 32 218 77 219 80 219 81 219 77 220 81 220 79 220 64 221 141 221 28 221 141 222 72 222 28 222 139 223 72 223 141 223 138 224 74 224 139 224 74 225 138 225 75 225 140 226 75 226 138 226 140 227 67 227 76 227 69 228 143 228 76 228 142 229 77 229 143 229 77 230 142 230 78 230 142 231 70 231 78 231 70 232 142 232 143 232 70 233 143 233 69 233 67 234 140 234 66 234 140 235 138 235 66 235 66 236 138 236 65 236 138 237 139 237 65 237 72 238 139 238 74 238 65 239 139 239 64 239 139 240 141 240 64 240 127 241 134 241 135 241 127 242 135 242 126 242 75 243 140 243 79 243 76 244 79 244 140 244 76 245 143 245 79 245 77 246 79 246 143 246 93 247 95 247 96 247 93 248 96 248 94 248 91 249 93 249 94 249 91 250 94 250 92 250 101 251 106 251 103 251 101 252 105 252 106 252 170 253 119 253 168 253 170 254 118 254 119 254 175 255 112 255 113 255 175 256 113 256 174 256 174 257 113 257 114 257 174 258 114 258 173 258 184 259 144 259 182 259 185 260 182 260 144 260 185 261 147 261 182 261 186 262 182 262 147 262 160 263 161 263 152 263 160 264 152 264 153 264 148 265 197 265 146 265 196 266 197 266 148 266 189 267 187 267 148 267 149 268 196 268 148 268 195 269 196 269 149 269 147 270 195 270 149 270 194 271 195 271 147 271 191 272 192 272 144 272 191 273 144 273 145 273 145 274 183 274 191 274 184 275 183 275 145 275 145 276 144 276 184 276 192 277 185 277 144 277 147 278 185 278 194 278 147 279 149 279 186 279 187 280 186 280 149 280 149 281 148 281 187 281 148 282 146 282 189 282 146 283 205 283 189 283 197 284 205 284 146 284 184 285 182 285 180 285 184 286 180 286 181 286 223 287 33 287 107 287 223 288 107 288 179 288 150 289 178 289 166 289 220 290 178 290 150 290 150 291 219 291 220 291 166 292 219 292 150 292 178 293 167 293 166 293 151 294 167 294 178 294 179 295 167 295 151 295 151 296 223 296 179 296 178 297 223 297 151 297 223 298 178 298 221 298 221 299 178 299 220 299 213 300 212 300 168 300 11 301 213 301 168 301 204 302 202 302 203 302 204 303 201 303 202 303 218 304 201 304 204 304 218 305 217 305 201 305 153 306 169 306 160 306 170 307 169 307 153 307 153 308 152 308 170 308 171 309 170 309 152 309 152 310 159 310 171 310 161 311 159 311 152 311 166 312 165 312 163 312 219 313 166 313 163 313 208 314 163 314 160 314 163 315 161 315 160 315 163 316 162 316 161 316 179 317 158 317 167 317 164 318 155 318 154 318 175 319 154 319 155 319 179 320 108 320 157 320 108 321 109 321 157 321 109 322 110 322 157 322 177 323 157 323 110 323 30 324 205 324 35 324 199 325 206 325 22 325 206 326 199 326 207 326 199 327 202 327 207 327 201 328 207 328 202 328 207 329 201 329 205 329 217 330 205 330 201 330 217 331 188 331 205 331 217 332 216 332 188 332 159 333 162 333 154 333 164 334 154 334 162 334 165 335 155 335 164 335 165 336 156 336 155 336 156 337 165 337 158 337 167 338 158 338 165 338 25 339 34 339 198 339 212 340 210 340 168 340 169 341 168 341 210 341 171 342 159 342 173 342 173 343 159 343 174 343 154 344 174 344 159 344 174 345 154 345 175 345 175 346 155 346 176 346 176 347 155 347 177 347 156 348 177 348 155 348 158 349 177 349 156 349 177 350 158 350 157 350 157 351 158 351 179 351 208 352 219 352 163 352 169 353 208 353 160 353 169 354 210 354 208 354 161 355 162 355 159 355 162 356 163 356 164 356 164 357 163 357 165 357 167 358 165 358 166 358 222 359 198 359 34 359 11 360 168 360 119 360 168 361 169 361 170 361 118 362 170 362 117 362 172 363 117 363 170 363 117 364 172 364 116 364 171 365 172 365 170 365 172 366 171 366 173 366 173 367 115 367 172 367 172 368 115 368 116 368 115 369 173 369 114 369 112 370 175 370 111 370 176 371 111 371 175 371 177 372 110 372 176 372 176 373 110 373 111 373 108 374 179 374 107 374 187 375 189 375 180 375 216 376 180 376 189 376 189 377 188 377 216 377 187 378 180 378 186 378 186 379 180 379 182 379 215 380 181 380 180 380 215 381 180 381 216 381 183 382 215 382 209 382 215 383 183 383 181 383 181 384 183 384 184 384 209 385 211 385 183 385 190 386 183 386 211 386 191 387 183 387 190 387 193 388 185 388 192 388 194 389 185 389 193 389 189 390 205 390 188 390 190 391 211 391 214 391 190 392 214 392 53 392 52 393 190 393 53 393 190 394 52 394 191 394 51 395 191 395 52 395 191 396 51 396 192 396 50 397 192 397 51 397 192 398 50 398 193 398 193 399 50 399 49 399 48 400 193 400 49 400 193 401 48 401 194 401 47 402 194 402 48 402 194 403 47 403 195 403 195 404 47 404 46 404 195 405 46 405 196 405 45 406 196 406 46 406 196 407 45 407 197 407 197 408 45 408 44 408 197 409 44 409 205 409 205 410 44 410 35 410 53 411 214 411 12 411 200 412 23 412 25 412 200 413 22 413 23 413 22 414 200 414 199 414 198 415 200 415 25 415 200 416 198 416 203 416 203 417 198 417 222 417 203 418 202 418 200 418 200 419 202 419 199 419 203 420 222 420 204 420 204 421 222 421 221 421 204 422 221 422 218 422 218 423 221 423 220 423 223 424 34 424 33 424 34 425 223 425 222 425 206 426 30 426 22 426 30 427 206 427 205 427 207 428 205 428 206 428 208 429 215 429 219 429 210 430 215 430 208 430 215 431 210 431 209 431 209 432 210 432 211 432 212 433 211 433 210 433 211 434 212 434 214 434 213 435 214 435 212 435 214 436 213 436 11 436 214 437 11 437 12 437 215 438 216 438 219 438 219 439 216 439 217 439 219 440 217 440 218 440 219 441 218 441 220 441 223 442 221 442 222 442 35 443 44 443 43 443

+
+
+
+
+ + + + 0.00000 0.00000 0.00004 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_proximal/f_proximal_C6M2.dae b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_C6M2.dae new file mode 100644 index 0000000..a461aa4 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_C6M2.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:31.855069 + 2012-07-23T02:15:31.855082 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -7.17350 6.94911 4.21838 -9.93270 -1.15879 -0.00031 -9.92969 1.15514 -0.00031 -7.45360 6.66578 -0.00031 -6.19669 -7.61001 14.00068 -5.99999 -7.69760 7.99969 -5.93079 -7.72543 8.52069 -5.99999 -7.62085 -1.45521 -6.53730 7.42476 2.97619 -6.00000 7.62007 -1.44611 -5.99999 -0.00089 -0.00031 -4.99999 3.65198 9.71969 -3.55469 -9.23031 23.11969 -3.56699 -8.61560 18.55868 -1.76899 -9.59040 22.63068 -4.59092 -8.80456 23.59968 4.59459 -8.80456 23.59968 1.77266 -9.59040 22.63068 3.57066 -8.61560 18.55868 3.55836 -9.23031 23.11969 0.00406 -8.84559 18.22268 0.00406 -9.69028 22.44568 9.93636 -1.15879 -0.00031 5.00366 3.81254 9.73169 6.00366 -0.00089 -0.00031 6.00366 7.62007 -1.44611 7.14516 6.97814 3.97919 6.00366 -7.62085 -1.45522 9.93336 1.15514 -0.00031 7.45726 6.66578 -0.00031 -4.47209 7.99911 23.99968 -0.92010 7.99911 10.96068 -2.73450 7.99911 10.65468 -5.10259 7.94911 9.74469 -3.99999 -8.00089 9.99969 -5.00999 -7.96456 14.00168 -6.00000 6.94911 4.50619 -5.64640 6.94911 8.25268 -7.17349 6.94911 6.96669 -7.06460 7.04525 7.66968 -6.70469 7.31810 8.43568 -6.02019 7.68741 9.16469 -7.45360 -6.66756 -0.00031 -7.46809 -6.65131 13.99969 -9.91719 -1.28497 23.99968 -9.99999 -0.02064 23.99968 -9.92209 1.24482 23.99968 -9.68389 2.49335 23.99968 -9.63909 2.66125 -0.00031 -8.93994 4.00025 23.99968 -9.11909 4.10304 -0.00031 -8.39959 5.42557 23.99968 -8.38479 5.44841 -0.00031 -7.47299 6.64398 23.99968 -6.00000 -5.49870 -5.79131 -5.99999 -6.96596 -3.90192 -6.00000 -3.36071 -7.26061 -6.00000 -4.50038 -6.61501 -6.00000 -2.24851 -7.67811 -9.41220 -1.47532 -3.03941 -8.06000 -1.20361 -5.79601 -6.00000 -1.13267 -7.91981 -6.00000 -0.00089 -8.00031 -8.06000 1.20183 -5.79601 -9.41220 1.47352 -3.03941 -6.00000 1.13089 -7.91981 -7.35780 3.50247 -5.79601 -6.00000 2.24673 -7.67811 -8.51050 4.28110 -3.03941 -6.00000 3.35892 -7.26061 -6.00000 5.49692 -5.79131 -6.00000 4.49860 -6.61501 -6.62189 6.66578 -3.42181 -6.00000 6.66577 -4.42251 -6.78489 -7.26453 -0.00031 -6.83189 -7.23065 13.99969 -5.99999 -7.69760 -0.00031 -5.71839 -7.80180 9.02269 -5.38550 -7.89522 9.44169 -4.95869 -7.97119 9.75468 -5.99999 -7.34730 -2.89871 -5.57889 7.84294 23.99968 -6.59929 7.38662 23.99968 -6.00000 7.69581 -0.00031 -6.00000 7.69581 2.18159 -6.00000 7.34767 -2.89111 -6.00000 7.07516 -3.64421 -6.00000 7.31252 3.24219 6.00366 6.94911 4.50619 6.00366 7.31252 3.24219 6.00366 6.66577 -4.42252 6.00366 7.34767 -2.89111 6.66886 7.34083 3.17053 6.00366 7.69581 2.18159 6.00366 7.69581 -0.00031 6.60296 7.38662 23.99968 5.58256 7.84294 23.99968 6.00366 -7.18556 -3.39231 4.96236 -7.97119 9.75468 5.38916 -7.89522 9.44169 5.72206 -7.80180 9.02269 5.93446 -7.72543 8.52069 6.00366 -7.69760 7.99968 6.00366 -7.69760 -0.00031 6.20036 -7.61001 14.00068 6.83556 -7.23065 13.99968 6.78856 -7.26453 -0.00031 6.62556 6.66578 -3.42181 6.00366 4.49860 -6.61501 6.00366 5.49692 -5.79131 6.00366 3.35892 -7.26061 8.51416 4.28110 -3.03941 6.00366 2.24673 -7.67812 7.36146 3.50247 -5.79601 6.00366 1.13089 -7.91981 9.41586 1.47352 -3.03941 8.06366 1.20183 -5.79601 6.00366 -0.00089 -8.00031 6.00366 -1.13267 -7.91981 8.06366 -1.20361 -5.79601 9.41586 -1.47532 -3.03941 6.00366 -2.24851 -7.67812 6.00366 -4.50038 -6.61501 6.00366 -3.36071 -7.26061 6.00366 -6.66755 -4.42252 6.00366 -5.49870 -5.79131 7.47666 6.64398 23.99968 8.38846 5.44841 -0.00031 8.40326 5.42557 23.99968 9.12276 4.10304 -0.00031 8.94361 4.00025 23.99968 9.64276 2.66125 -0.00031 9.68756 2.49335 23.99968 9.92576 1.24482 23.99968 10.00366 -0.02064 23.99968 9.92086 -1.28497 23.99968 7.47176 -6.65131 13.99968 7.45726 -6.66756 -0.00031 5.10626 7.94911 9.74469 6.02386 7.68741 9.16469 7.06826 7.04525 7.66968 7.17716 6.94911 6.96669 0.00406 -8.00089 13.99868 3.58286 -8.00089 13.99868 4.00366 -8.00089 9.99969 5.01366 -7.96456 14.00168 0.00366 7.99911 23.99968 2.73816 7.99911 10.65468 0.92376 7.99911 10.96068 4.47576 7.99911 23.99968 -3.99999 -5.02735 37.82068 4.00366 -5.02735 37.82068 -3.99999 -5.00089 39.42268 -4.48079 7.99911 34.49768 -3.53979 -8.82177 32.40168 -2.34909 -9.28970 31.73368 -1.16229 -9.55490 31.35468 4.48446 7.99911 34.49768 0.00346 -9.63919 31.23468 1.16596 -9.55490 31.35468 2.35276 -9.28970 31.73368 3.54346 -8.82177 32.40168 0.00366 7.99911 44.99968 4.46387 7.99911 44.99968 4.00366 6.94911 44.99968 7.00366 -0.00089 44.99968 7.00366 -3.61239 46.59969 7.00366 3.37761 47.04568 7.00366 -3.04855 47.51268 7.00366 2.70194 47.87968 7.00366 -2.25983 48.23969 7.00366 1.82715 48.50168 7.00366 -1.30441 48.72868 7.00366 0.81734 48.86368 7.00366 -0.25282 48.94168 4.00366 6.69274 46.86967 4.00366 5.94276 48.60168 4.00366 4.75370 50.06868 4.00366 3.21449 51.16068 4.00366 1.43786 51.79867 4.00366 -0.44483 51.93568 4.00366 -2.29479 51.56068 4.00366 -3.97553 50.70068 4.00366 -5.36307 49.42068 4.00366 -6.35507 47.81468 4.00366 -6.87828 46.00168 4.00366 -6.89415 44.11368 4.00366 -6.40153 42.29169 6.60256 4.84007 47.50069 5.76706 6.37616 44.99969 5.50366 5.81689 48.00468 6.60256 3.15259 49.44267 5.50366 3.78892 50.33968 6.60256 0.76172 50.39468 5.50366 0.91560 51.48367 6.60256 -1.79926 50.14268 5.50366 -2.16214 51.18068 6.60256 -3.95910 48.74368 5.50366 -4.75780 49.49968 6.60256 -5.23604 46.50967 5.50366 -6.29241 46.81468 -6.59889 -5.34526 43.93867 -5.49999 -6.29241 46.81468 -6.59889 -5.23604 46.50967 -5.49999 -4.75780 49.49968 -6.59889 -3.95910 48.74368 -5.49999 -2.16214 51.18068 -6.59889 -1.79926 50.14268 -5.49999 0.91560 51.48367 -6.59889 0.76172 50.39468 -5.49999 3.78892 50.33968 -6.59889 3.15259 49.44267 -5.49999 5.81689 48.00468 -5.76339 6.37616 44.99968 -6.59889 4.84007 47.50069 -6.42709 5.71247 44.99968 -3.99999 -6.40153 42.29169 -3.99999 -6.89415 44.11368 -3.99999 -6.87828 46.00168 -3.99999 -6.35507 47.81468 -3.99999 -5.36307 49.42068 -3.99999 -3.97553 50.70068 -3.99999 -2.29479 51.56068 -3.99999 -0.44483 51.93568 -3.99999 1.43786 51.79867 -3.99999 3.21449 51.16068 -3.99999 4.75370 50.06868 -3.99999 5.94276 48.60168 -3.99999 6.69274 46.86967 -6.85319 4.87616 44.99968 -4.92709 6.80228 44.99968 -6.99999 -0.25282 48.94168 -6.99999 0.81734 48.86368 -6.99999 -1.30441 48.72868 -6.99999 1.82715 48.50168 -6.99999 -2.25983 48.23969 -6.99999 2.70194 47.87968 -6.99999 -0.00090 44.99968 -6.99999 -3.04855 47.51268 -6.99999 3.37761 47.04568 -6.99999 -3.61239 46.59969 -6.99999 3.80368 46.06168 -6.99999 -3.90969 45.56868 -6.99999 3.94911 44.99968 -6.99999 -3.91855 44.49568 -3.99999 6.94911 44.99968 -4.46019 7.99911 44.99968 8.35526 -5.50089 23.99968 8.73536 -4.87502 23.99968 9.28136 -3.73246 23.99968 9.67876 -2.52910 23.99968 7.43666 6.69810 34.49368 8.31437 5.81849 29.52985 8.89386 -4.46979 29.51968 8.76546 -4.19563 35.80267 9.26076 -2.79232 29.51968 8.91906 -2.27439 35.04568 9.45096 -1.09815 29.51968 8.96676 -0.33818 35.04568 9.47666 0.60681 29.51968 8.94576 1.60178 35.04568 9.33576 2.31798 29.51968 8.83896 3.55496 35.04568 8.30708 5.67738 34.68957 8.98616 4.04325 29.51968 0.00416 -10.00089 29.52368 0.00336 -10.00089 30.08768 2.93366 -9.56529 30.58668 3.43473 -9.48162 29.13079 3.49076 -9.37344 25.99968 1.45316 -9.89544 25.99968 4.39459 -9.10315 25.99968 4.41876 -8.98168 31.25368 6.33566 -7.76061 29.52368 5.84346 -8.13534 32.22368 7.02016 -7.12658 25.99968 7.14446 -7.03138 33.48969 8.27176 -5.67266 35.04868 8.54566 -5.26191 29.52368 4.68486 -8.14347 33.37068 5.30646 7.91391 34.49867 6.09576 7.66057 34.49867 6.81586 7.24997 34.49968 6.91396 -7.18597 33.86967 5.65496 -8.25206 32.34668 5.01416 -8.44358 32.71868 3.31336 -9.32459 31.45968 1.18046 -9.86343 30.69068 5.37426 -8.43667 25.99968 5.71986 -8.20649 23.99968 6.46616 -7.63259 23.99968 7.16186 -6.98424 23.99968 -7.15819 -6.98424 23.99968 -6.46249 -7.63259 23.99968 -5.71619 -8.20649 23.99968 -5.37059 -8.43667 25.99968 -1.17679 -9.86343 30.69068 -3.30969 -9.32459 31.45968 -5.01049 -8.44358 32.71868 -5.65129 -8.25206 32.34668 -6.31069 -7.37931 34.23868 -6.91029 -7.18597 33.86967 -7.85419 -6.04028 35.50568 -6.81219 7.24997 34.49968 -6.09209 7.66057 34.49867 -5.30279 7.91391 34.49867 -8.26809 -5.67266 35.04868 -4.68119 -8.14347 33.37068 -5.72309 -7.25891 34.63368 -8.54199 -5.26191 29.52368 -7.14079 -7.03138 33.48969 -7.01649 -7.12658 25.99968 -5.83979 -8.13534 32.22368 -6.33199 -7.76061 29.52368 -4.41509 -8.98168 31.25368 -4.39092 -9.10315 25.99968 -1.44949 -9.89544 25.99968 -3.48709 -9.37343 25.99968 -3.43106 -9.48162 29.13079 -2.92999 -9.56529 30.58668 0.00184 -10.00019 25.99969 -8.98249 4.04325 29.51968 -8.30341 5.67738 34.68957 -8.83529 3.55496 35.04568 -9.33209 2.31798 29.51968 -8.94209 1.60178 35.04568 -9.47299 0.60681 29.51968 -8.96309 -0.33818 35.04568 -9.44729 -1.09815 29.51968 -8.91539 -2.27439 35.04568 -9.25709 -2.79232 29.51968 -8.76179 -4.19563 35.80267 -8.89019 -4.46979 29.51968 -8.31070 5.81849 29.52985 -7.43299 6.69810 34.49368 -9.67509 -2.52910 23.99968 -9.27769 -3.73246 23.99968 -8.73169 -4.87502 23.99968 -8.35159 -5.50089 23.99968 0.00183 7.24200 10.60569 4.00366 4.25152 9.99969 5.65006 6.94911 8.25268 5.55006 6.94911 5.59469 3.89726 6.94911 9.21068 3.63686 6.94093 6.60969 1.98966 6.94911 9.80069 0.00366 6.94911 9.99969 0.00366 6.94911 7.84768 4.30636 7.24200 9.80469 1.47496 7.24200 10.60569 4.32487 5.06448 8.40697 3.63686 6.82538 6.40069 4.38886 6.06216 6.65668 4.68666 3.94590 9.87969 4.34936 4.09318 9.96969 3.63371 6.43688 6.43168 4.43506 6.73264 6.19568 4.49076 6.91366 6.33069 5.94346 3.82193 8.45469 6.00400 4.02117 8.04468 -6.00000 4.02117 8.04468 -5.93979 3.82193 8.45469 -5.54639 6.94911 5.59469 -4.54040 6.94911 6.46068 -3.63320 6.94093 6.60969 -4.45075 6.64691 6.24219 -4.34569 4.09222 9.96969 -3.63320 6.82538 6.40069 3.63321 5.95391 6.88068 -4.32395 5.11941 8.41997 -1.47129 7.24200 10.60569 -4.30269 7.24200 9.80469 -1.98599 6.94911 9.80069 -3.89359 6.94911 9.21068 -3.99999 4.25198 9.99969 4.47576 -8.00089 9.94269 6.00366 5.96671 5.62369 6.00366 4.86318 6.60168 6.00366 4.40365 7.39368 5.41736 3.62295 9.41469 5.73196 3.74311 9.00368 -5.72829 3.74311 9.00368 -3.63359 6.44435 6.42669 -4.68299 3.85204 9.87969 -5.41369 3.62295 9.41469 -4.38520 6.06216 6.65668 -3.63320 5.95391 6.88068 -5.99999 4.40365 7.39368 -5.99999 4.86318 6.60168 -6.00000 5.96671 5.62369 -4.47209 -8.00089 9.94269 -8.38479 -5.45020 -0.00031 -9.63909 -2.66304 -0.00031 -6.78409 -6.66756 -3.03501 -8.51050 -4.28290 -3.03941 -7.35780 -3.50425 -5.79601 7.36146 -3.50425 -5.79601 8.51416 -4.28290 -3.03941 6.78776 -6.66756 -3.03501 9.64276 -2.66304 -0.00031 8.38846 -5.45020 -0.00031 9.12276 -4.10482 -0.00031 -9.11909 -4.10482 -0.00031 -3.57919 -8.00089 13.99868 -3.99999 -5.43664 40.66869 -5.48459 -5.09962 40.93769 -5.49999 -4.73356 40.21569 -5.76329 -4.42797 39.42269 -6.42709 -4.46943 41.43969 -6.59809 -3.69701 40.57769 -6.42699 -3.76429 39.42269 -6.85319 -2.92798 39.42269 -6.68310 -3.81534 41.96069 -6.99999 -3.09028 42.53869 -6.99999 -2.49594 41.59168 -6.99999 -2.12557 40.53269 -6.99999 -2.00089 39.42269 -5.36349 -4.67315 38.32668 -6.19619 -4.04460 39.22469 -6.72699 -3.25133 38.74369 -6.99999 -2.00089 38.27869 -6.96549 -2.45480 38.42168 -8.53599 -1.46623 39.60468 -8.55289 -0.11087 39.43468 -8.54059 1.25595 39.55968 -8.50409 2.50568 39.95368 -8.45399 3.57721 40.56069 -6.76829 -5.70594 36.85169 -6.86009 -4.03110 39.22569 -6.92969 7.10944 44.99969 -6.11599 7.64029 44.99969 -5.93589 7.04911 44.99969 -5.49999 6.94911 44.99969 -5.31029 7.90772 44.99969 -4.88529 7.95342 44.99969 -7.19169 6.82799 43.78869 -8.19199 4.97673 41.65069 -7.71279 6.06131 42.71468 -7.49639 -5.59217 36.77569 -7.60349 -3.56948 39.46268 -8.12469 -5.26918 36.55169 -8.06229 -2.97472 39.64069 -8.56689 -4.78127 36.21169 -8.39929 -2.25591 39.68868 -7.28129 -6.21366 35.90269 -6.99999 1.68717 38.19369 -6.99999 0.45891 38.00269 -6.99999 -0.78335 38.03168 -6.99999 2.86304 38.59969 -6.99999 3.94911 39.20568 -6.99999 -3.63839 43.45969 -5.03399 6.76527 43.41169 -5.49999 6.54719 42.67069 -5.93590 6.24091 41.72169 -6.39679 5.75341 40.92669 -6.83869 4.91954 39.95969 -7.08054 5.94669 41.49869 -7.43409 4.97597 40.42869 -8.19199 4.02715 40.55369 -7.43409 3.77077 39.39269 -8.19199 2.84199 39.71668 -7.43409 2.35678 38.66769 -8.19199 1.49065 39.18868 -7.43409 0.81253 38.29169 -8.19199 0.05167 39.00069 -7.43409 -0.77680 38.28768 -8.19199 -1.39001 39.16369 -7.43409 -2.32320 38.65369 -6.72699 6.57048 42.44669 -6.72699 6.92842 43.70069 -5.49999 -6.42367 43.72469 5.48826 -5.09962 40.93769 6.43076 -4.46943 41.43969 5.50366 -6.42367 43.72469 6.60256 -5.34526 43.93868 6.85686 4.87616 44.99969 6.73066 6.92842 43.70069 6.73066 -3.25133 38.74369 6.73066 6.57048 42.44669 7.08421 5.94669 41.49869 7.43776 -2.32320 38.65369 8.19566 -1.39001 39.16369 7.43776 -0.77680 38.28768 8.19566 0.05167 39.00069 7.43776 0.81253 38.29169 8.19566 1.49065 39.18868 7.43776 2.35678 38.66769 8.19566 2.84199 39.71668 7.43776 3.77077 39.39269 8.19566 4.02715 40.55369 7.43776 4.97597 40.42869 6.84236 4.91954 39.95969 6.40046 5.75341 40.92669 6.43076 5.71247 44.99969 5.93956 6.24091 41.72169 5.50366 6.54719 42.67069 5.03766 6.76527 43.41169 4.93076 6.80228 44.99969 7.00366 3.80368 46.06168 7.00366 -3.90969 45.56869 7.00366 3.94911 44.99969 7.00366 -3.91855 44.49569 7.00366 -3.63839 43.45969 7.00366 3.94911 39.20568 7.00366 2.86304 38.59969 7.00366 -0.78335 38.03168 7.00366 0.45891 38.00269 7.00366 1.68717 38.19369 6.31436 -7.37931 34.23869 8.12836 -5.26918 36.55169 7.85786 -6.04028 35.50568 7.28496 -6.21366 35.90269 8.40296 -2.25591 39.68868 8.57056 -4.78127 36.21169 8.06596 -2.97472 39.64069 7.60716 -3.56948 39.46268 6.99346 -4.00149 39.23769 7.50006 -5.59217 36.77569 7.71646 6.06131 42.71468 8.19566 4.97673 41.65069 7.19536 6.82799 43.78869 4.88896 7.95342 44.99969 5.31396 7.90772 44.99969 5.93956 7.04911 44.99969 6.11966 7.64029 44.99969 6.93336 7.10944 44.99969 5.72676 -7.25891 34.63369 6.77196 -5.70594 36.85169 8.45766 3.57721 40.56069 8.50776 2.50568 39.95368 8.54426 1.25595 39.55968 8.55656 -0.11086 39.43468 8.53966 -1.46623 39.60468 7.00366 -2.00089 38.27869 6.96916 -2.45480 38.42168 6.19986 -4.04460 39.22469 5.36716 -4.67315 38.32668 7.00366 -2.31088 41.06269 7.00366 -2.00089 39.42269 7.00366 -2.49594 41.59168 7.00366 -3.09028 42.53869 6.75609 -3.81534 41.96069 6.85686 -2.92798 39.42269 6.43066 -3.76429 39.42269 6.60176 -3.69701 40.57769 5.76696 -4.42797 39.42269 5.50366 -4.73356 40.21569 4.00366 -5.00089 39.42269 4.00366 -5.43664 40.66869 + + + + + + + + + + -0.37992 -0.92502 0.00105 -0.61397 0.78924 -0.01224 -0.07593 -0.97679 -0.20031 -0.22994 -0.96457 -0.12938 -0.08134 -0.97733 -0.19549 -0.42429 -0.89757 -0.11982 0.42429 -0.89757 -0.11983 0.08144 -0.97732 -0.19548 0.22994 -0.96457 -0.12938 0.07611 -0.97679 -0.20023 0.00000 1.00000 -0.00000 -0.02010 0.99979 -0.00262 -0.99786 -0.06535 0.00030 -1.00000 0.00130 -0.00287 -0.99811 0.06144 0.00009 -0.98228 0.18741 -0.00039 -0.98189 0.18945 -0.00051 -0.89668 0.44268 0.00142 -0.94065 0.33926 0.00847 -0.93503 0.35447 0.00850 -0.87777 0.47908 -0.00009 -0.79597 0.60534 0.00009 -0.79427 0.60756 -0.00009 -0.73062 -0.00000 -0.68279 -0.89780 -0.00000 -0.44040 -0.89780 -0.00000 -0.44040 -0.71610 0.04952 -0.69624 -0.75711 0.13830 -0.63848 -0.69777 0.21297 -0.68393 -0.85617 0.26132 -0.44574 -0.92192 0.33250 -0.19878 -0.93821 0.30132 -0.17023 -0.85683 0.27518 -0.43602 -0.69725 0.25192 -0.67110 -0.86835 0.47394 -0.14612 -0.73749 0.50314 -0.45051 -0.77877 0.59570 -0.19660 -0.78420 0.59050 -0.19062 -0.73536 0.51102 -0.44509 -0.72246 0.52579 -0.44899 -0.67329 -0.73938 -0.00047 -0.66596 -0.74598 0.00018 -0.51275 -0.85854 0.00036 -0.48310 -0.87557 -0.00131 -0.34471 -0.93870 0.00305 -0.28004 -0.95995 0.00846 -0.17483 -0.98460 -0.00057 -0.13972 0.99019 0.00271 -0.27312 0.96198 -0.00196 -0.40823 0.91287 0.00257 -0.47428 0.88037 -0.00066 -0.45040 0.89283 0.00000 -0.71115 0.70304 0.00000 -0.57790 0.81555 -0.03005 -0.60493 0.79627 0.00059 -0.67564 0.73722 0.00384 -0.57764 0.81518 -0.04270 -0.64644 0.74661 -0.15714 -0.67682 0.72341 -0.13637 -0.59520 0.75563 -0.27343 -0.59953 0.70834 -0.37259 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.02819 0.94010 0.33974 0.01436 0.93130 0.36396 0.12973 0.97951 -0.15405 -0.64764 0.76194 0.00226 -0.71191 0.70227 0.00006 -0.98581 0.00000 -0.16786 -0.97140 0.18743 -0.14577 0.97140 0.18743 -0.14578 0.98565 0.00000 -0.16881 0.71191 0.70227 0.00006 0.64764 0.76194 0.00226 0.00494 0.91350 0.40681 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 0.54765 0.76436 -0.34035 0.67682 0.72341 -0.13637 0.64644 0.74661 -0.15714 0.57764 0.81518 -0.04270 0.67564 0.73722 0.00384 0.57791 0.81555 -0.02994 0.61966 0.78477 -0.01300 0.70339 0.71081 -0.00063 0.47080 0.88224 -0.00000 0.40823 0.91287 0.00257 0.27312 0.96198 -0.00196 0.13972 0.99019 0.00271 0.17483 -0.98460 -0.00057 0.28004 -0.95995 0.00846 0.34471 -0.93870 0.00305 0.37991 -0.92502 0.00105 0.48310 -0.87557 -0.00131 0.51275 -0.85854 0.00036 0.66596 -0.74598 0.00018 0.67329 -0.73937 -0.00047 0.72246 0.52579 -0.44899 0.73536 0.51102 -0.44509 0.78420 0.59050 -0.19063 0.77877 0.59570 -0.19660 0.73749 0.50314 -0.45051 0.86835 0.47394 -0.14612 0.69725 0.25192 -0.67110 0.85683 0.27518 -0.43602 0.93821 0.30132 -0.17023 0.92192 0.33250 -0.19878 0.85617 0.26132 -0.44574 0.69777 0.21297 -0.68393 0.75711 0.13830 -0.63848 0.71610 0.04952 -0.69624 0.89780 0.00000 -0.44040 0.89780 0.00000 -0.44040 0.73062 0.00000 -0.68279 0.79427 0.60756 -0.00009 0.79597 0.60534 0.00009 0.87777 0.47908 -0.00009 0.93503 0.35448 0.00850 0.94065 0.33926 0.00847 0.89668 0.44268 0.00142 0.98189 0.18945 -0.00051 0.98228 0.18741 -0.00039 0.99809 0.06144 -0.00571 1.00000 0.00130 0.00031 0.99786 -0.06535 0.00030 0.02010 0.99979 -0.00262 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 -0.99986 0.01651 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 0.00000 1.00000 0.69946 0.68907 0.18956 0.22891 0.89330 0.38681 0.96248 0.21083 0.17081 0.95946 0.21276 0.18488 0.69693 0.54133 0.47038 0.36003 0.72476 0.58745 0.30851 0.71817 0.62374 0.69716 0.54127 0.47010 0.96751 0.14650 0.20605 0.21934 0.56453 0.79573 0.95759 0.09723 0.27122 0.96142 0.10177 0.25557 0.69721 0.26520 0.66601 0.69718 0.26518 0.66605 0.30072 0.32233 0.89759 0.34441 0.34727 0.87223 0.96702 0.01852 0.25402 0.22851 0.07066 0.97097 0.69718 -0.07020 0.71345 0.95018 -0.06188 0.30550 0.96407 -0.02601 0.26437 0.36233 -0.09132 0.92757 0.69714 -0.07024 0.71349 0.25693 -0.19200 0.94717 0.96537 -0.11886 0.23224 0.69711 -0.38978 0.60175 0.95840 -0.15517 0.23956 0.69719 -0.38969 0.60172 0.42922 -0.41142 0.80405 0.25228 -0.52600 0.81221 0.22867 -0.66008 0.71554 0.96700 -0.17269 0.18735 0.69715 -0.62243 0.35577 0.96242 -0.23105 0.14269 0.95943 -0.24477 0.13991 0.69712 -0.62246 0.35577 0.36001 -0.79374 0.49028 0.30840 -0.82588 0.47203 0.21950 -0.93736 0.27051 -0.95765 -0.28792 0.00238 -0.69707 -0.71635 0.03043 -0.96752 -0.24290 0.07004 -0.21950 -0.93736 0.27051 -0.30839 -0.82588 0.47203 -0.36001 -0.79374 0.49028 -0.69712 -0.62246 0.35577 -0.95943 -0.24477 0.13991 -0.96242 -0.23105 0.14269 -0.69715 -0.62243 0.35577 -0.96700 -0.17269 0.18735 -0.22867 -0.66008 0.71554 -0.25228 -0.52600 0.81221 -0.42922 -0.41142 0.80405 -0.69719 -0.38969 0.60172 -0.95840 -0.15517 0.23956 -0.69711 -0.38978 0.60175 -0.96537 -0.11886 0.23224 -0.25693 -0.19200 0.94717 -0.69714 -0.07024 0.71349 -0.36233 -0.09132 0.92757 -0.96407 -0.02601 0.26437 -0.95018 -0.06188 0.30550 -0.69718 -0.07020 0.71345 -0.22851 0.07066 0.97097 -0.96702 0.01852 0.25402 -0.34441 0.34727 0.87223 -0.30072 0.32233 0.89759 -0.69718 0.26518 0.66605 -0.69721 0.26520 0.66601 -0.96142 0.10177 0.25557 -0.95759 0.09723 0.27122 -0.21934 0.56453 0.79573 -0.96751 0.14650 0.20605 -0.69716 0.54127 0.47010 -0.30851 0.71817 0.62374 -0.36003 0.72476 0.58745 -0.69693 0.54133 0.47038 -0.95946 0.21276 0.18488 -0.96248 0.21083 0.17081 -0.22891 0.89330 0.38681 -0.96702 0.23373 0.10120 -0.69946 0.68907 0.18956 -0.44469 0.87275 0.20141 -0.15007 0.94757 0.28211 -0.42958 0.89466 0.12265 -0.95018 0.30880 0.04245 -0.69362 0.69364 0.19431 -0.98747 0.15637 0.02141 -0.84480 0.43042 0.31789 -0.00000 -0.96534 -0.26100 -0.00000 -0.96534 -0.26100 -0.00000 -0.99996 0.00841 -0.00000 -0.99996 0.00841 -0.00000 -0.96079 0.27727 -0.00000 -0.96079 0.27727 -0.00000 -0.85078 0.52551 -0.00000 -0.85078 0.52551 -0.00000 -0.67805 0.73502 0.00000 -0.67805 0.73502 0.00000 -0.45551 0.89023 0.00000 -0.45551 0.89023 0.00000 -0.19866 0.98007 0.00000 -0.19866 0.98007 -0.00000 0.07258 0.99736 0.00000 0.07258 0.99736 0.00000 0.33797 0.94116 -0.00000 0.33797 0.94116 -0.00000 0.57862 0.81559 0.00000 0.57862 0.81559 0.00000 0.77686 0.62968 0.00000 0.77686 0.62968 0.00000 0.91766 0.39736 0.00000 0.91766 0.39736 0.00000 0.99073 0.13583 0.00000 0.99073 0.13583 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.97499 0.22226 -0.00000 -0.92453 0.38110 0.90226 -0.43116 0.00574 0.97649 -0.21358 0.02928 0.97612 -0.21350 0.04000 0.94802 -0.31308 0.05686 0.99635 -0.05341 0.06661 0.97763 -0.19024 0.08966 0.99134 -0.11130 0.06976 0.99120 -0.11128 0.07172 0.99558 -0.02453 0.09061 0.99409 -0.06510 0.08683 0.99589 -0.01501 0.08933 0.99520 -0.01500 0.09672 0.99424 0.06120 0.08796 0.99554 0.01078 0.09370 0.99338 0.08180 0.08071 0.99256 0.08173 0.09020 0.97998 0.18697 0.06840 0.99552 0.05444 0.07731 0.96826 0.24794 0.03155 0.97796 0.19817 0.06582 0.89663 0.44266 -0.01036 0.97777 0.19813 0.06861 0.14700 -0.98914 0.00021 0.24807 -0.96831 -0.02902 0.07172 -0.99371 0.08595 0.14963 -0.98874 -0.00030 0.14904 -0.98882 -0.00554 0.28639 -0.95770 -0.02796 0.34030 -0.93819 0.06320 0.56248 -0.82680 0.00516 0.50451 -0.86193 0.05048 0.53463 -0.84366 -0.04914 0.51263 -0.85823 -0.02566 0.62265 -0.78225 -0.01980 0.64109 -0.76740 0.01036 0.79702 -0.60172 -0.05190 0.74900 -0.66246 -0.01212 0.74880 -0.66228 0.02629 0.91538 -0.40230 0.01547 0.61539 -0.78641 0.05336 0.57003 -0.81556 0.09967 0.12475 -0.87586 0.46616 0.51875 -0.85477 -0.01612 0.37649 -0.90862 0.18073 0.32485 -0.92285 0.20694 0.13312 -0.88748 0.44120 0.09621 -0.88767 0.45032 0.31482 -0.94120 0.12258 0.06742 -0.90426 0.42164 0.08306 -0.90964 0.40702 0.17554 -0.96597 0.18998 0.02220 -0.90647 0.42168 0.16166 -0.98259 -0.09158 0.06493 -0.99436 -0.08387 0.07172 -0.99366 -0.08660 0.20896 -0.97695 -0.04364 0.24766 -0.96673 -0.06404 0.60929 -0.79232 0.03169 0.62268 -0.78228 0.01757 0.68177 -0.73156 -0.00376 0.47456 -0.88001 -0.01928 0.56160 -0.82551 -0.05591 0.40991 -0.90871 -0.07890 0.28626 -0.95728 -0.04085 0.79561 0.60506 -0.03020 0.93501 0.35447 -0.01016 0.93521 0.35396 -0.00997 0.93524 0.35385 0.01100 0.75898 0.65084 0.01887 0.77910 -0.62681 0.01059 0.77326 -0.63409 0.00078 0.85470 -0.51907 -0.00700 0.91546 -0.40240 0.00325 -0.00000 1.00000 0.00000 0.10310 0.99467 -0.00009 0.13972 0.99019 -0.00302 0.30561 0.95215 0.00160 0.40823 0.91287 -0.00410 0.49533 0.86870 0.00126 0.64764 0.76194 -0.00322 0.66439 0.74739 -0.00132 0.70513 0.70908 -0.00097 -0.70513 0.70908 -0.00097 -0.66439 0.74739 -0.00132 -0.64764 0.76194 -0.00322 -0.49533 0.86870 0.00126 -0.40823 0.91287 -0.00410 -0.30561 0.95215 0.00160 -0.13972 0.99019 -0.00302 -0.10310 0.99467 -0.00009 0.00000 1.00000 0.00000 -0.91546 -0.40240 0.00325 -0.85470 -0.51907 -0.00700 -0.77326 -0.63409 0.00078 -0.77910 -0.62681 0.01059 -0.75898 0.65084 0.01887 -0.93524 0.35385 0.01100 -0.93521 0.35396 -0.00997 -0.93501 0.35447 -0.01016 -0.79561 0.60506 -0.03020 -0.28626 -0.95728 -0.04085 -0.40991 -0.90871 -0.07890 -0.56160 -0.82551 -0.05591 -0.47456 -0.88001 -0.01928 -0.68177 -0.73156 -0.00376 -0.62268 -0.78228 0.01757 -0.60929 -0.79232 0.03169 -0.24766 -0.96673 -0.06404 -0.20896 -0.97695 -0.04364 -0.07172 -0.99365 -0.08669 -0.06477 -0.99437 -0.08389 -0.16161 -0.98253 -0.09231 -0.02214 -0.90647 0.42168 -0.17554 -0.96597 0.18998 -0.08306 -0.90964 0.40702 -0.06742 -0.90426 0.42164 -0.31482 -0.94120 0.12258 -0.09621 -0.88767 0.45032 -0.13312 -0.88748 0.44120 -0.32485 -0.92285 0.20694 -0.37649 -0.90862 0.18073 -0.51875 -0.85477 -0.01612 -0.12475 -0.87586 0.46616 -0.15273 -0.86617 0.47583 -0.41173 -0.87359 0.25948 -0.57003 -0.81556 0.09967 -0.61539 -0.78642 0.05336 -0.43261 -0.86653 0.24894 -0.14765 -0.86322 0.48276 -0.71431 -0.69421 0.08851 -0.67849 -0.72532 0.11649 -0.94257 -0.33229 0.03376 -0.91537 -0.40231 0.01547 -0.74880 -0.66228 0.02629 -0.74900 -0.66246 -0.01212 -0.79702 -0.60172 -0.05190 -0.64109 -0.76740 0.01036 -0.62265 -0.78225 -0.01980 -0.51263 -0.85823 -0.02566 -0.53463 -0.84366 -0.04914 -0.50451 -0.86193 0.05048 -0.56248 -0.82680 0.00516 -0.34030 -0.93819 0.06320 -0.28639 -0.95770 -0.02796 -0.14884 -0.98885 -0.00561 -0.14945 -0.98877 -0.00010 -0.07172 -0.99371 0.08595 -0.24807 -0.96831 -0.02902 -0.14692 -0.98915 -0.00021 -0.97777 0.19813 0.06861 -0.89663 0.44266 -0.01036 -0.97796 0.19817 0.06582 -0.96826 0.24794 0.03155 -0.99552 0.05444 0.07731 -0.97998 0.18697 0.06840 -0.99256 0.08173 0.09020 -0.99338 0.08180 0.08071 -0.99554 0.01078 0.09370 -0.99424 0.06120 0.08796 -0.99520 -0.01500 0.09672 -0.99589 -0.01501 0.08933 -0.99409 -0.06510 0.08683 -0.99558 -0.02453 0.09061 -0.99120 -0.11128 0.07172 -0.99134 -0.11130 0.06976 -0.97763 -0.19024 0.08966 -0.99635 -0.05341 0.06661 -0.94802 -0.31308 0.05686 -0.97612 -0.21350 0.04000 -0.97649 -0.21358 0.02928 -0.90226 -0.43116 0.00574 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.90036 -0.43515 0.00000 0.90036 -0.43515 0.00000 0.00000 -1.00000 -0.00000 1.00000 -0.00000 0.02992 0.99953 -0.00614 -0.04897 0.99855 -0.02238 -0.00000 1.00000 0.00000 -0.00094 0.99999 -0.00305 -0.00000 1.00000 0.00000 0.00167 1.00000 -0.00170 -0.18127 0.92582 -0.33166 -0.33605 0.30453 -0.89125 -0.24187 0.45887 -0.85495 -0.12672 0.90338 -0.40970 -0.10729 0.91905 -0.37927 -0.15739 0.32299 -0.93322 -0.03628 0.93144 -0.36209 -0.98931 0.00059 -0.14580 -0.08645 0.00000 -0.99626 -0.25621 -0.07481 -0.96372 -0.46284 0.61705 -0.63642 -0.12748 0.61787 -0.77588 -0.12905 0.86783 -0.47980 0.52405 0.59562 -0.60877 0.08703 0.87183 -0.48201 0.02729 0.59100 -0.80621 0.08645 0.00000 -0.99626 0.98943 0.00056 -0.14501 -0.00000 -0.07954 -0.99683 -0.00000 0.87515 -0.48385 -0.00000 0.87515 -0.48385 0.03621 0.93145 -0.36205 0.15739 0.32299 -0.93322 0.10729 0.91905 -0.37927 0.12672 0.90337 -0.40970 0.24187 0.45887 -0.85495 0.33605 0.30453 -0.89125 0.18127 0.92582 -0.33166 0.00000 0.99998 -0.00661 -0.00167 1.00000 -0.00170 0.00000 1.00000 -0.00000 0.00094 0.99999 -0.00305 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00938 0.99995 -0.00221 0.00000 1.00000 -0.00000 -0.03447 -0.56461 -0.82463 -0.02257 -0.86820 -0.49570 -0.00000 -1.00000 -0.00000 -0.02658 0.99964 -0.00251 0.00811 0.99992 0.00963 0.40679 -0.91352 -0.00000 -0.99129 0.00002 -0.13166 -0.93308 -0.00133 -0.35966 -0.92096 0.00015 -0.38965 -0.79403 -0.00032 -0.60788 -0.78301 0.00046 -0.62201 -0.60834 -0.00037 -0.79368 -0.59143 0.00050 -0.80636 -0.42313 -0.00028 -0.90607 -0.36047 0.00144 -0.93277 -0.25804 -0.00054 -0.96613 -0.11987 0.00096 -0.99279 -0.00342 0.94046 0.33987 0.10258 0.95600 0.27486 -0.54107 -0.72740 -0.42205 -0.54206 -0.72466 -0.42548 -0.54151 -0.72194 -0.43078 -0.56924 -0.75410 -0.32757 -0.66245 -0.49685 -0.56063 -0.35061 -0.80805 -0.47342 -0.84565 -0.40086 -0.35240 -0.38367 0.78835 -0.48095 -0.40881 0.39255 -0.82388 -0.12973 0.97951 -0.15405 -0.49552 -0.46867 -0.73130 -0.42845 -0.22367 -0.87544 0.44674 -0.23178 -0.86412 0.49661 -0.46421 -0.73341 0.23270 0.87645 -0.42153 0.17952 0.79930 -0.57349 0.40881 0.39255 -0.82388 0.38366 0.78835 -0.48095 0.84565 -0.40086 -0.35240 0.33841 -0.82490 -0.45279 0.01364 -0.88159 -0.47182 0.67437 -0.48974 -0.55261 0.58626 -0.73899 -0.33195 0.56054 -0.70950 -0.42709 0.56140 -0.71351 -0.41920 0.56043 -0.71635 -0.41564 -0.06761 0.95887 0.27568 0.11987 0.00096 -0.99279 0.25818 -0.00054 -0.96610 0.36048 0.00146 -0.93277 0.45114 -0.00108 -0.89245 0.59133 -0.00033 -0.80643 0.59343 -0.00043 -0.80488 0.78301 0.00046 -0.62201 0.79403 -0.00032 -0.60788 0.92096 0.00015 -0.38965 0.93308 -0.00133 -0.35966 0.99129 0.00002 -0.13166 -0.40679 -0.91352 0.00000 -0.00625 -0.86521 -0.50136 -0.00000 -0.87912 -0.47660 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 0.00000 -1.00000 -0.11875 -0.67600 -0.72728 -0.69945 -0.56446 -0.43835 -0.73008 -0.52935 -0.43217 -0.79534 -0.57614 -0.18840 -0.73749 -0.50314 -0.45051 -0.66333 -0.36884 -0.65111 -0.68186 -0.46553 -0.56422 -0.69725 -0.25192 -0.67110 -0.93527 -0.30038 -0.18722 -0.85683 -0.27518 -0.43602 -0.70722 -0.14967 -0.69097 -0.71631 -0.21863 -0.66264 -0.85617 -0.26132 -0.44574 -0.71610 -0.04952 -0.69624 -0.59927 -0.74831 -0.28445 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -0.63379 -0.75998 -0.14402 -0.65889 -0.73806 -0.14536 -0.62639 -0.76482 -0.15062 0.62639 -0.76482 -0.15062 0.65889 -0.73806 -0.14536 -1.00000 0.00000 0.00000 0.59715 -0.78261 -0.17586 0.62227 -0.69937 -0.35166 0.71610 -0.04952 -0.69624 0.85617 -0.26132 -0.44574 0.71631 -0.21863 -0.66264 0.70722 -0.14967 -0.69097 0.85683 -0.27518 -0.43602 0.93527 -0.30038 -0.18722 0.69725 -0.25192 -0.67110 0.68186 -0.46553 -0.56422 0.66333 -0.36884 -0.65111 0.73749 -0.50314 -0.45051 0.79534 -0.57614 -0.18840 0.73008 -0.52935 -0.43217 0.75435 -0.49922 -0.42630 -0.00000 -1.00000 0.00000 0.00106 -0.99996 0.00881 0.02538 -0.99967 0.00267 0.79359 -0.60845 -0.00012 0.79427 -0.60756 -0.00018 0.85472 -0.51909 0.00009 0.87777 -0.47908 -0.00121 0.90227 -0.43117 0.00073 0.94069 -0.33927 -0.00095 0.94956 -0.31358 0.00033 0.98159 -0.19101 -0.00041 0.98148 -0.19157 -0.00037 0.86835 -0.47394 -0.14612 0.92761 -0.33456 -0.16616 0.28626 -0.95811 0.00941 0.06124 -0.99812 0.00082 -1.00000 -0.00000 0.00000 0.77914 -0.62684 0.00328 0.00000 -0.98059 -0.19609 0.07625 -0.98818 -0.13301 0.67329 -0.73937 -0.00375 0.68177 -0.73156 -0.00422 0.51266 -0.85845 -0.01557 0.60949 -0.79259 -0.01799 0.28596 -0.95726 -0.04336 0.48386 -0.87340 -0.05531 0.02544 -0.99072 -0.13349 0.19812 -0.97716 -0.07687 0.97088 -0.18950 -0.14654 0.78235 -0.59845 -0.17260 0.48258 -0.87463 -0.04614 -0.48258 -0.87464 -0.04614 -0.78235 -0.59845 -0.17260 -0.97088 -0.18950 -0.14654 -0.19812 -0.97716 -0.07687 -0.02544 -0.99072 -0.13349 -0.48386 -0.87340 -0.05531 -0.28596 -0.95726 -0.04336 -0.60949 -0.79259 -0.01799 -0.51266 -0.85845 -0.01557 -0.68177 -0.73156 -0.00422 -0.67329 -0.73937 -0.00375 -0.07616 -0.98818 -0.13301 -0.00000 -0.98059 -0.19609 -0.77914 -0.62684 0.00328 0.20395 -0.06686 -0.97670 1.00000 0.00000 -0.00000 -0.06124 -0.99812 0.00082 -0.28626 -0.95811 0.00941 -0.92761 -0.33456 -0.16616 -0.86835 -0.47394 -0.14612 -0.98148 -0.19157 -0.00037 -0.98159 -0.19101 -0.00041 -0.94956 -0.31358 0.00033 -0.94069 -0.33927 -0.00095 -0.90227 -0.43117 0.00073 -0.87777 -0.47908 -0.00121 -0.85472 -0.51908 0.00009 -0.79427 -0.60756 -0.00018 -0.79359 -0.60845 -0.00012 0.00062 -0.06808 -0.99768 -0.00020 -0.68088 -0.73240 -0.00000 -0.67931 -0.73385 -0.02538 -0.99967 0.00267 -0.00106 -0.99996 0.00881 -0.00000 -0.99986 0.01651 0.00000 -0.94394 -0.33011 -0.00000 -0.94394 -0.33011 -0.26435 -0.91036 -0.31837 -0.29878 -0.91958 -0.25516 -0.36744 -0.83266 -0.41433 -0.64066 -0.69026 -0.33630 -0.69571 -0.59806 -0.39790 -0.70567 -0.70569 -0.06343 -0.69377 -0.71869 -0.04660 -0.88605 -0.45155 -0.10496 -0.94887 -0.30419 -0.08435 -0.93636 -0.34017 -0.08666 -0.96824 -0.21178 -0.13291 -0.96453 -0.24918 -0.08715 -0.98754 -0.15637 -0.01756 -0.96795 -0.24613 0.04991 -0.30897 -0.95094 0.01571 -0.19818 -0.96944 0.14457 -0.64480 -0.76159 -0.06484 -0.80014 -0.59240 -0.09401 -0.69629 -0.69631 0.17415 -0.88983 -0.45348 0.05057 -0.99712 -0.07579 0.00000 -0.96339 -0.25512 0.08248 -0.98187 -0.15548 -0.10845 -0.99492 -0.04386 0.09057 -0.99589 -0.02453 0.08723 -0.99566 -0.00074 0.09309 -0.99566 0.00045 0.09303 -0.99594 0.01078 0.08941 -0.99606 0.00113 0.08868 -0.99596 -0.00422 0.08966 -0.01576 -0.81730 0.57599 -0.00007 -0.81918 0.57353 0.00019 -0.81917 0.57355 0.00007 -0.81914 0.57359 -0.00016 -0.81916 0.57357 0.00016 -0.81915 0.57358 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00001 0.00000 1.00000 0.00001 -0.00000 1.00000 -0.10686 0.99427 0.00021 -0.10691 0.99427 0.00051 -0.10310 0.99467 0.00036 -0.31502 0.94908 0.00033 -0.30561 0.95216 0.00114 -0.54640 0.83753 0.00037 -0.49532 0.86869 0.00608 -0.73383 0.67933 0.00088 -0.66442 0.74733 0.00680 -0.29659 -0.76863 0.56678 -0.62243 -0.62224 0.47476 -0.84125 -0.41735 0.34367 -0.97445 -0.15100 0.16627 -0.18468 -0.82157 0.53937 -0.52793 -0.74792 0.40237 -0.51590 -0.74782 0.41787 -0.79345 -0.56953 0.21466 -0.77990 -0.57721 0.24203 -0.94860 -0.31649 -0.00114 -0.13722 -0.84064 0.52392 -0.16245 -0.85018 0.50080 -0.46619 -0.82821 0.31103 -0.46054 -0.83055 0.31318 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.15641 0.98761 -0.01249 -0.43461 0.90058 0.00827 -0.45395 0.89092 0.01409 -0.56909 0.82226 -0.00398 -0.73529 0.67767 0.01073 -0.70710 0.70711 0.00185 -0.88271 0.46992 -0.00184 -0.89102 0.45397 0.00134 -0.98629 0.16504 -0.00142 -0.98769 0.15640 0.00000 0.63460 -0.66563 0.39270 0.63436 -0.66518 0.39385 0.72560 -0.52027 0.45035 0.68535 -0.47470 0.55223 0.72614 -0.39663 0.56161 0.68473 -0.33252 0.64852 0.72616 -0.25021 0.64038 0.68424 -0.17252 0.70856 0.72663 -0.08900 0.68124 0.68414 -0.00184 0.72935 0.72662 0.07718 0.68269 0.68429 0.16795 0.70960 0.73343 0.25027 0.63201 0.68191 0.33078 0.65237 0.50247 0.42166 0.75480 0.79620 -0.45746 0.39598 0.71150 -0.40537 0.57398 0.77296 -0.33970 0.53585 0.73978 -0.24487 0.62671 0.77536 -0.21037 0.59545 0.75248 -0.08532 0.65307 0.77897 -0.06406 0.62378 0.75300 0.07392 0.65386 0.77803 0.08772 0.62207 0.75616 0.19727 0.62394 0.66429 0.26477 0.69901 0.24972 -0.78683 0.56439 0.13613 -0.87777 0.45933 0.11798 -0.84918 0.51476 -0.06009 -0.98988 0.12857 0.23889 -0.95596 0.17049 0.27051 -0.84078 0.46894 0.49605 -0.83495 0.23833 0.50274 -0.79627 0.33645 0.36695 -0.74608 0.55562 0.51142 -0.57864 0.63532 0.47211 -0.57465 0.66850 0.49937 -0.42215 0.75659 0.55746 -0.37879 0.73875 0.46738 -0.28853 0.83565 0.57126 -0.19417 0.79747 0.47014 -0.13561 0.87211 0.50809 0.02010 0.86107 0.55298 -0.00210 0.83319 0.50233 0.17192 0.84741 0.55640 0.19138 0.80858 0.48927 0.29566 0.82049 0.37156 0.44143 0.81675 0.49467 0.42090 0.76036 -0.07970 -0.93736 0.33913 -0.06820 -0.95935 0.27384 -0.21807 -0.95055 0.22112 -0.06791 -0.98506 0.15826 0.00000 -0.99987 0.01593 -0.03964 -0.95154 0.30497 0.01193 0.52427 0.85147 -0.00000 -0.85957 -0.51102 -0.00000 -0.85957 -0.51102 -0.96142 -0.27485 0.01168 -0.30116 -0.95354 0.00802 -0.34472 -0.93786 0.03984 -0.69707 -0.71635 0.03043 -0.22886 -0.93972 -0.25408 -0.96701 -0.24590 -0.06650 -0.95011 -0.26803 -0.15951 -0.94563 -0.27551 -0.17284 -0.95556 -0.25147 -0.15383 -0.69977 -0.65778 -0.27864 -0.37006 -0.83833 -0.40032 -0.64017 -0.69253 -0.33254 -0.27651 -0.82605 -0.49110 -0.99615 0.05447 0.06865 -0.98889 0.13229 0.06784 -0.96758 0.24929 0.04058 -0.93111 0.36112 0.05125 -0.75833 0.65140 0.02465 -0.83600 0.54855 0.01404 0.00000 1.00000 -0.00000 -0.18465 -0.80642 0.56178 -0.53029 -0.68737 0.49630 -0.80208 -0.47156 0.36647 -0.96387 -0.19129 0.18539 0.96386 -0.19129 0.18540 0.80208 -0.47156 0.36647 0.53029 -0.68737 0.49630 0.18466 -0.80774 0.55987 -0.00000 1.00000 -0.00000 0.83600 0.54855 0.01404 0.75833 0.65140 0.02465 0.93111 0.36112 0.05125 0.96758 0.24929 0.04058 0.98889 0.13229 0.06784 0.99615 0.05447 0.06865 0.27651 -0.82605 -0.49110 0.64017 -0.69253 -0.33254 0.37007 -0.83833 -0.40032 0.69978 -0.65778 -0.27864 0.93015 -0.32185 -0.17675 0.96424 -0.24057 -0.11123 0.95011 -0.26803 -0.15951 0.96701 -0.24590 -0.06650 0.22886 -0.93972 -0.25408 0.69707 -0.71635 0.03043 0.34472 -0.93786 0.03984 0.30116 -0.95354 0.00802 0.96142 -0.27485 0.01167 0.95765 -0.28791 0.00238 0.69707 -0.71635 0.03043 0.96752 -0.24290 0.07004 0.96702 0.23373 0.10120 0.44469 0.87275 0.20141 0.15007 0.94757 0.28211 0.42958 0.89466 0.12265 0.96712 0.23308 0.10170 0.88684 0.45184 0.09669 0.69363 0.69363 0.19431 0.98747 0.15637 0.02141 -0.04306 0.53891 0.84126 0.03964 -0.95154 0.30497 0.05119 -0.99105 0.12326 0.06791 -0.98506 0.15826 0.06820 -0.95935 0.27384 0.07970 -0.93736 0.33913 -0.49441 0.39951 0.77197 -0.32782 0.43681 0.83770 -0.55640 0.19138 0.80858 -0.48927 0.29566 0.82049 -0.50233 0.17192 0.84741 -0.55298 -0.00210 0.83319 -0.50809 0.02010 0.86107 -0.47014 -0.13561 0.87211 -0.57126 -0.19417 0.79747 -0.46738 -0.28853 0.83565 -0.55746 -0.37879 0.73875 -0.49937 -0.42215 0.75659 -0.47211 -0.57465 0.66850 -0.51142 -0.57864 0.63532 -0.33681 -0.78370 0.52189 -0.28175 -0.75512 0.59196 -0.50274 -0.79627 0.33645 -0.49604 -0.83495 0.23833 -0.27051 -0.84078 0.46894 -0.23889 -0.95596 0.17049 0.06009 -0.98988 0.12857 -0.11798 -0.84918 0.51476 -0.13613 -0.87777 0.45934 -0.66429 0.26477 0.69901 -0.75616 0.19727 0.62394 -0.77803 0.08772 0.62207 -0.75300 0.07392 0.65386 -0.77897 -0.06406 0.62378 -0.75248 -0.08532 0.65307 -0.77536 -0.21037 0.59545 -0.73978 -0.24487 0.62671 -0.77296 -0.33970 0.53585 -0.71150 -0.40537 0.57398 -0.79620 -0.45746 0.39598 -0.55052 0.40061 0.73242 -0.68191 0.33078 0.65237 -0.73343 0.25027 0.63201 -0.68429 0.16795 0.70960 -0.72662 0.07718 0.68269 -0.68414 -0.00184 0.72935 -0.72663 -0.08900 0.68124 -0.68424 -0.17252 0.70856 -0.72616 -0.25021 0.64038 -0.68473 -0.33252 0.64852 -0.72614 -0.39663 0.56161 -0.68535 -0.47470 0.55223 -0.72560 -0.52027 0.45035 -0.63436 -0.66518 0.39385 -0.63460 -0.66563 0.39270 0.98769 0.15640 -0.00000 0.98629 0.16504 -0.00142 0.89102 0.45397 0.00134 0.88271 0.46992 -0.00184 0.70710 0.70711 0.00185 0.73529 0.67767 0.01073 0.56909 0.82227 -0.00398 0.45395 0.89092 0.01408 0.43460 0.90058 0.00827 0.15641 0.98761 -0.01249 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 0.15273 -0.86617 0.47583 0.41173 -0.87359 0.25948 0.43261 -0.86653 0.24894 0.14765 -0.86322 0.48276 0.46055 -0.83055 0.31318 0.46618 -0.82821 0.31103 0.16245 -0.85018 0.50080 0.71431 -0.69421 0.08851 0.67849 -0.72532 0.11649 0.13722 -0.84064 0.52392 0.94860 -0.31649 -0.00114 0.79507 -0.56250 0.22686 0.77632 -0.58631 0.23146 0.51589 -0.74782 0.41787 0.52793 -0.74792 0.40237 0.18468 -0.82157 0.53937 0.97445 -0.15100 0.16627 0.84126 -0.41735 0.34367 0.62243 -0.62224 0.47476 0.33025 -0.76039 0.55924 0.66442 0.74733 0.00681 0.73383 0.67933 0.00088 0.49532 0.86869 0.00608 0.54640 0.83753 0.00037 0.30561 0.95216 0.00114 0.31502 0.94908 0.00033 0.10310 0.99467 0.00036 0.10691 0.99427 0.00051 0.10687 0.99427 0.00021 0.94257 -0.33229 0.03376 -0.00000 -0.00000 1.00000 -0.00001 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00016 -0.81915 0.57358 0.00016 -0.81916 0.57357 -0.00007 -0.81914 0.57359 -0.00019 -0.81917 0.57355 0.00008 -0.81918 0.57353 0.03478 -0.81474 0.57878 0.99596 -0.00422 0.08966 0.99606 0.00113 0.08868 0.99594 0.01078 0.08941 0.99566 0.00045 0.09303 0.99566 -0.00074 0.09309 0.99589 -0.02453 0.08723 0.99492 -0.04386 0.09057 0.99712 -0.07579 0.00000 0.98187 -0.15548 -0.10845 0.96339 -0.25512 0.08248 0.88983 -0.45348 0.05057 0.69629 -0.69631 0.17415 0.80014 -0.59240 -0.09401 0.64480 -0.76159 -0.06484 0.19818 -0.96944 0.14457 0.30897 -0.95094 0.01571 0.95817 -0.28538 0.02161 0.98726 -0.15633 -0.02955 0.96453 -0.24916 -0.08717 0.96824 -0.21178 -0.13291 0.96527 -0.22815 -0.12724 0.92566 -0.35400 -0.13359 0.88605 -0.45155 -0.10496 0.69377 -0.71869 -0.04660 0.70567 -0.70569 -0.06343 0.69571 -0.59806 -0.39790 0.64066 -0.69026 -0.33630 0.36744 -0.83266 -0.41433 0.29878 -0.91958 -0.25516 0.26435 -0.91036 -0.31837 -1.00000 -0.00000 0.00000 -1.00000 0.00003 0.00003 -1.00000 -0.00044 0.00026 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.45492 -0.69848 -0.55242 0.45573 -0.69856 -0.55166 0.62626 -0.65836 -0.41756 0.59609 -0.67308 -0.43777 0.39819 -0.76716 -0.50290 -0.43938 -0.71403 -0.54507 -0.60326 -0.71049 -0.36234 -0.51410 -0.73917 -0.43513 -0.45554 -0.75926 -0.46477 -0.39950 -0.78139 -0.47941 -0.00634 -0.89015 -0.45563 -0.00005 -0.87655 -0.48130 -0.00000 -0.81914 0.57360 -0.00019 -0.81919 0.57352 0.00014 -0.81912 0.57362 -0.00014 -0.81916 0.57357 0.00019 -0.81919 0.57352 -0.00014 -0.81912 0.57362 0.00014 -0.81916 0.57357 -0.68186 0.46553 -0.56422 -0.66333 0.36884 -0.65111 0.66333 0.36884 -0.65111 0.68186 0.46553 -0.56422 -0.98563 0.00128 -0.16894 0.98583 0.00128 -0.16773 -0.27402 0.79933 -0.53477 0.52064 0.85377 -0.00301 0.04210 -0.57464 -0.81732 0.11996 -0.67436 -0.72860 + + + + + + + + + + + + + + +

4 0 5 0 6 0 3 1 0 1 8 1 13 2 21 2 14 2 12 3 13 3 14 3 20 4 21 4 13 4 12 5 15 5 13 5 19 6 18 6 16 6 20 7 18 7 21 7 19 8 17 8 18 8 18 9 17 9 21 9 30 10 31 10 32 10 33 11 30 11 32 11 44 12 45 12 1 12 2 13 1 13 45 13 45 14 46 14 2 14 2 15 46 15 47 15 48 16 2 16 47 16 47 17 49 17 48 17 50 18 48 18 49 18 50 19 49 19 51 19 52 20 50 20 51 20 52 21 51 21 53 21 3 22 52 22 53 22 60 23 63 23 62 23 64 24 63 24 60 24 59 25 64 25 60 25 65 26 62 26 63 26 66 27 67 27 65 27 63 28 66 28 65 28 66 29 63 29 64 29 64 30 48 30 50 30 68 31 64 31 50 31 64 32 68 32 66 32 69 33 67 33 66 33 50 34 52 34 68 34 70 35 66 35 68 35 68 36 52 36 3 36 68 37 3 37 72 37 68 38 72 38 70 38 73 39 70 39 72 39 74 40 75 40 43 40 42 41 74 41 43 41 4 42 75 42 74 42 74 43 76 43 4 43 4 44 6 44 77 44 77 45 78 45 35 45 78 46 79 46 35 46 81 47 30 47 33 47 33 48 41 48 81 48 82 49 81 49 41 49 41 50 40 50 82 50 83 51 8 51 84 51 38 52 0 52 3 52 83 53 3 53 8 53 82 54 40 54 39 54 82 55 39 55 38 55 9 56 3 56 83 56 72 57 3 57 9 57 9 58 85 58 72 58 85 59 86 59 72 59 73 60 72 60 86 60 61 61 62 61 65 61 65 62 67 62 61 62 67 63 69 63 58 63 56 64 58 64 69 64 69 65 71 65 56 65 57 66 56 66 71 66 71 67 70 67 57 67 54 68 57 68 70 68 70 69 73 69 54 69 55 70 54 70 73 70 73 71 86 71 55 71 80 72 55 72 86 72 86 73 85 73 80 73 85 74 9 74 80 74 80 75 9 75 10 75 9 76 83 76 10 76 83 77 84 77 10 77 87 78 84 78 8 78 8 79 0 79 87 79 37 80 38 80 39 80 82 81 38 81 53 81 38 82 3 82 53 82 59 83 2 83 64 83 48 84 64 84 2 84 131 85 28 85 115 85 120 86 115 86 22 86 141 87 126 87 29 87 95 88 126 88 141 88 92 89 89 89 26 89 94 90 24 90 93 90 25 91 24 91 94 91 91 92 24 92 25 92 27 93 24 93 91 93 90 94 27 94 91 94 27 95 90 95 97 95 90 96 124 96 97 96 124 97 90 97 125 97 109 98 125 98 90 98 125 99 109 99 122 99 108 100 122 100 109 100 122 101 108 101 123 101 110 102 123 102 108 102 123 103 110 103 121 103 112 104 121 104 110 104 114 105 118 105 112 105 118 106 114 106 117 106 91 107 107 107 90 107 107 108 91 108 25 108 107 109 25 109 29 109 25 110 94 110 29 110 95 111 141 111 140 111 94 112 92 112 29 112 29 113 92 113 26 113 29 114 26 114 141 114 94 115 93 115 92 115 95 116 139 116 96 116 138 117 96 117 139 117 138 118 149 118 96 118 99 119 145 119 98 119 100 120 145 120 99 120 104 121 100 121 101 121 104 122 101 122 102 122 106 123 104 123 103 123 104 124 106 124 105 124 137 125 136 125 106 125 106 126 136 126 105 126 90 127 107 127 109 127 111 128 109 128 107 128 111 129 107 129 29 129 111 130 29 130 127 130 109 131 111 131 113 131 129 132 111 132 127 132 110 133 113 133 112 133 115 134 113 134 111 134 111 135 129 135 115 135 115 136 129 136 131 136 113 137 115 137 116 137 116 138 114 138 113 138 113 139 114 139 112 139 114 140 116 140 117 140 120 141 119 141 115 141 115 142 119 142 116 142 119 143 117 143 116 143 29 144 126 144 127 144 127 145 126 145 128 145 127 146 128 146 129 146 129 147 128 147 130 147 129 148 130 148 131 148 132 149 131 149 130 149 131 150 132 150 28 150 28 151 132 151 133 151 134 152 22 152 133 152 133 153 22 153 28 153 135 154 22 154 134 154 147 155 149 155 138 155 149 156 147 156 148 156 142 157 144 157 143 157 31 158 146 158 148 158 30 159 146 159 31 159 146 160 149 160 148 160 150 161 151 161 152 161 146 162 153 162 162 162 146 163 162 163 157 163 164 164 163 164 162 164 190 165 188 165 189 165 176 166 190 166 175 166 188 167 169 167 167 167 191 168 169 168 188 168 188 169 190 169 191 169 192 170 176 170 177 170 190 171 176 171 192 171 192 172 191 172 190 172 169 173 191 173 171 173 178 174 192 174 177 174 191 175 173 175 171 175 193 176 173 176 191 176 191 177 192 177 193 177 194 178 193 178 192 178 194 179 178 179 179 179 192 180 178 180 194 180 173 181 193 181 174 181 180 182 194 182 179 182 193 183 194 183 195 183 193 184 172 184 174 184 195 185 172 185 193 185 194 186 180 186 196 186 196 187 195 187 194 187 181 188 196 188 180 188 172 189 195 189 170 189 195 190 196 190 197 190 197 191 170 191 195 191 198 192 197 192 196 192 198 193 181 193 182 193 196 194 181 194 198 194 183 195 198 195 182 195 170 196 197 196 168 196 197 197 198 197 199 197 197 198 166 198 168 198 199 199 166 199 197 199 200 200 199 200 198 200 200 201 183 201 184 201 198 202 183 202 200 202 185 203 200 203 184 203 203 204 242 204 244 204 203 205 201 205 202 205 240 206 242 206 203 206 218 207 219 207 202 207 204 208 202 208 220 208 202 209 219 209 220 209 202 210 204 210 203 210 203 211 205 211 240 211 205 212 238 212 240 212 205 213 203 213 204 213 235 214 238 214 205 214 220 215 221 215 204 215 206 216 204 216 222 216 204 217 221 217 222 217 204 218 206 218 205 218 205 219 207 219 235 219 207 220 205 220 206 220 233 221 235 221 207 221 222 222 223 222 206 222 206 223 208 223 207 223 208 224 206 224 223 224 207 225 209 225 233 225 209 226 231 226 233 226 209 227 207 227 208 227 223 228 224 228 208 228 232 229 231 229 209 229 210 230 208 230 225 230 208 231 224 231 225 231 208 232 210 232 209 232 211 233 209 233 210 233 209 234 211 234 232 234 211 235 234 235 232 235 225 236 226 236 210 236 236 237 234 237 211 237 210 238 212 238 211 238 212 239 210 239 227 239 210 240 226 240 227 240 214 241 211 241 212 241 211 242 214 242 236 242 214 243 239 243 236 243 227 244 228 244 212 244 241 245 239 245 214 245 212 246 213 246 214 246 213 247 212 247 230 247 212 248 245 248 230 248 212 249 228 249 245 249 214 250 215 250 241 250 214 251 213 251 215 251 243 252 241 252 229 252 241 253 215 253 229 253 187 254 186 254 216 254 217 255 216 255 186 255 186 256 185 256 217 256 218 257 217 257 185 257 185 258 184 258 218 258 219 259 218 259 184 259 184 260 183 260 219 260 220 261 219 261 183 261 183 262 182 262 220 262 221 263 220 263 182 263 182 264 181 264 221 264 222 265 221 265 181 265 181 266 180 266 222 266 223 267 222 267 180 267 180 268 179 268 223 268 224 269 223 269 179 269 179 270 178 270 224 270 225 271 224 271 178 271 178 272 177 272 225 272 226 273 225 273 177 273 177 274 176 274 226 274 227 275 226 275 176 275 176 276 175 276 227 276 228 277 227 277 175 277 175 278 164 278 228 278 245 279 228 279 164 279 240 280 238 280 237 280 242 281 240 281 237 281 241 282 243 282 237 282 244 283 242 283 237 283 245 284 164 284 162 284 162 285 246 285 245 285 296 286 266 286 287 286 296 287 287 287 158 287 249 288 253 288 248 288 253 289 255 289 254 289 253 290 249 290 255 290 250 291 255 291 249 291 254 292 255 292 256 292 257 293 250 293 135 293 255 294 250 294 257 294 257 295 256 295 255 295 256 296 257 296 258 296 134 297 257 297 135 297 259 298 258 298 257 298 257 299 134 299 259 299 133 300 259 300 134 300 258 301 259 301 260 301 261 302 260 302 259 302 259 303 133 303 261 303 132 304 261 304 133 304 260 305 261 305 262 305 261 306 263 306 262 306 264 307 263 307 261 307 264 308 132 308 130 308 261 309 132 309 264 309 266 310 265 310 267 310 268 311 270 311 269 311 268 312 320 312 270 312 265 313 320 313 268 313 268 314 267 314 265 314 271 315 268 315 269 315 267 316 268 316 272 316 273 317 271 317 288 317 268 318 271 318 273 318 268 319 274 319 272 319 273 320 274 320 268 320 275 321 273 321 288 321 274 322 273 322 276 322 273 323 277 323 276 323 273 324 278 324 277 324 273 325 275 325 278 325 253 326 277 326 278 326 283 327 274 327 276 327 284 328 274 328 283 328 161 329 285 329 279 329 274 330 284 330 272 330 284 331 285 331 272 331 286 332 272 332 285 332 285 333 161 333 286 333 160 334 286 334 161 334 272 335 286 335 267 335 287 336 160 336 159 336 286 337 160 337 287 337 287 338 267 338 286 338 158 339 287 339 159 339 267 340 287 340 266 340 270 341 21 341 17 341 320 342 21 342 270 342 269 343 17 343 19 343 269 344 270 344 17 344 275 345 289 345 290 345 288 346 289 346 275 346 291 347 275 347 290 347 288 348 16 348 289 348 271 349 16 349 288 349 271 350 19 350 16 350 269 351 19 351 271 351 128 352 126 352 252 352 130 353 128 353 252 353 130 354 252 354 264 354 252 355 263 355 264 355 251 356 263 356 252 356 247 357 275 357 291 357 247 358 278 358 275 358 247 359 248 359 278 359 248 360 253 360 278 360 149 361 146 361 157 361 149 362 157 362 280 362 149 363 280 363 96 363 96 364 280 364 281 364 96 365 281 365 95 365 95 366 281 366 282 366 126 367 95 367 282 367 126 368 282 368 251 368 126 369 251 369 252 369 53 370 333 370 334 370 53 371 334 371 303 371 53 372 303 372 82 372 82 373 303 373 304 373 81 374 82 374 304 374 81 375 304 375 305 375 30 376 81 376 305 376 30 377 305 377 153 377 30 378 153 378 146 378 337 379 309 379 332 379 338 380 309 380 337 380 338 381 311 381 309 381 338 382 292 382 311 382 334 383 333 383 322 383 333 384 321 384 322 384 49 385 321 385 333 385 49 386 333 386 51 386 51 387 333 387 53 387 317 388 315 388 12 388 315 389 15 389 12 389 315 390 295 390 15 390 295 391 294 391 15 391 292 392 293 392 311 392 295 393 311 393 294 393 311 394 293 394 294 394 317 395 14 395 316 395 317 396 12 396 14 396 320 397 316 397 21 397 316 398 14 398 21 398 319 399 266 399 296 399 158 400 156 400 296 400 296 401 297 401 319 401 297 402 296 402 155 402 296 403 156 403 155 403 314 404 319 404 297 404 155 405 154 405 297 405 298 406 297 406 154 406 297 407 298 407 314 407 299 408 314 408 298 408 312 409 314 409 299 409 154 410 307 410 298 410 300 411 298 411 307 411 298 412 300 412 299 412 299 413 301 413 312 413 301 414 310 414 312 414 301 415 299 415 300 415 307 416 308 416 300 416 306 417 310 417 302 417 310 418 301 418 302 418 331 419 332 419 306 419 332 420 309 420 306 420 313 421 309 421 311 421 309 422 313 422 306 422 313 423 310 423 306 423 312 424 310 424 313 424 311 425 295 425 313 425 313 426 318 426 312 426 318 427 314 427 312 427 318 428 313 428 315 428 313 429 295 429 315 429 319 430 314 430 318 430 315 431 317 431 318 431 318 432 265 432 319 432 265 433 318 433 320 433 318 434 316 434 320 434 318 435 317 435 316 435 266 436 319 436 265 436 324 437 321 437 47 437 321 438 49 438 47 438 321 439 324 439 322 439 324 440 323 440 322 440 325 441 323 441 324 441 47 442 46 442 324 442 326 443 324 443 46 443 324 444 326 444 325 444 327 445 325 445 326 445 46 446 45 446 326 446 328 447 326 447 45 447 326 448 328 448 327 448 45 449 44 449 328 449 329 450 327 450 328 450 328 451 330 451 329 451 330 452 328 452 335 452 328 453 44 453 335 453 331 454 329 454 330 454 335 455 336 455 330 455 332 456 330 456 336 456 330 457 332 457 331 457 336 458 337 458 332 458 349 459 339 459 148 459 148 460 339 460 31 460 31 461 339 461 370 461 339 462 349 462 346 462 370 463 339 463 346 463 374 464 340 464 144 464 341 465 88 465 342 465 343 466 357 466 344 466 343 467 342 467 357 467 341 468 342 468 343 468 343 469 344 469 345 469 345 470 347 470 346 470 344 471 347 471 345 471 343 472 348 472 341 472 138 473 348 473 147 473 349 474 147 474 348 474 349 475 343 475 345 475 348 476 343 476 349 476 147 477 349 477 148 477 346 478 349 478 345 478 359 479 102 479 358 479 354 480 144 480 340 480 351 481 356 481 355 481 357 482 342 482 356 482 356 483 351 483 357 483 344 484 357 484 351 484 362 485 363 485 365 485 364 486 367 486 363 486 365 487 363 487 367 487 366 488 374 488 34 488 5 489 360 489 361 489 351 490 355 490 367 490 367 491 364 491 351 491 344 492 351 492 364 492 346 493 372 493 370 493 32 494 31 494 370 494 371 495 370 495 373 495 370 496 372 496 373 496 370 497 371 497 32 497 33 498 32 498 371 498 373 499 37 499 371 499 344 500 364 500 347 500 364 501 372 501 347 501 372 502 346 502 347 502 373 503 372 503 364 503 37 504 373 504 362 504 373 505 363 505 362 505 373 506 364 506 363 506 37 507 362 507 36 507 355 508 356 508 352 508 368 509 352 509 350 509 34 510 144 510 142 510 341 511 26 511 88 511 141 512 26 512 341 512 104 513 102 513 103 513 101 514 358 514 102 514 358 515 101 515 380 515 100 516 380 516 101 516 380 517 100 517 379 517 99 518 379 518 100 518 379 519 99 519 23 519 98 520 23 520 99 520 23 521 98 521 353 521 375 522 353 522 98 522 353 523 375 523 354 523 354 524 375 524 144 524 93 525 89 525 92 525 88 526 26 526 89 526 350 527 377 527 378 527 350 528 378 528 359 528 358 529 350 529 359 529 380 530 350 530 358 530 376 531 377 531 350 531 376 532 350 532 352 532 88 533 376 533 342 533 341 534 348 534 139 534 348 535 138 535 139 535 341 536 140 536 141 536 376 537 352 537 356 537 356 538 342 538 376 538 365 539 389 539 362 539 389 540 365 540 385 540 37 541 39 541 40 541 37 542 40 542 41 542 371 543 41 543 33 543 37 544 41 544 371 544 36 545 362 545 389 545 389 546 385 546 369 546 369 547 385 547 386 547 389 548 369 548 388 548 381 549 361 549 369 549 361 550 360 550 369 550 369 551 360 551 387 551 369 552 387 552 388 552 87 553 0 553 36 553 34 554 390 554 366 554 383 555 366 555 390 555 390 556 79 556 383 556 11 557 383 557 79 557 79 558 78 558 11 558 384 559 11 559 78 559 78 560 77 560 384 560 381 561 384 561 77 561 77 562 6 562 381 562 361 563 381 563 6 563 6 564 5 564 361 564 4 565 76 565 5 565 368 566 350 566 369 566 369 567 386 567 368 567 37 568 0 568 38 568 36 569 0 569 37 569 34 570 374 570 144 570 352 571 368 571 355 571 54 572 55 572 393 572 393 573 394 573 54 573 393 574 391 574 394 574 395 575 54 575 394 575 395 576 56 576 57 576 54 577 395 577 57 577 58 578 56 578 395 578 59 579 394 579 392 579 394 580 59 580 395 580 60 581 61 581 58 581 395 582 60 582 58 582 60 583 395 583 59 583 62 584 61 584 60 584 55 585 80 585 393 585 58 586 61 586 67 586 7 587 80 587 10 587 393 588 80 588 7 588 393 589 74 589 42 589 74 590 393 590 7 590 106 591 27 591 398 591 398 592 137 592 106 592 121 593 112 593 118 593 97 594 398 594 27 594 398 595 97 595 124 595 117 596 119 596 118 596 119 597 120 597 396 597 396 598 121 598 119 598 119 599 121 599 118 599 397 600 396 600 120 600 120 601 399 601 397 601 121 602 396 602 123 602 125 603 122 603 396 603 396 604 122 604 123 604 396 605 397 605 125 605 397 606 400 606 398 606 398 607 125 607 397 607 125 608 398 608 124 608 34 609 142 609 403 609 375 610 145 610 144 610 143 611 144 611 145 611 137 612 247 612 136 612 400 613 247 613 137 613 400 614 248 614 247 614 401 615 248 615 400 615 248 616 401 616 249 616 399 617 249 617 401 617 249 618 399 618 250 618 399 619 135 619 250 619 22 620 135 620 399 620 400 621 397 621 401 621 397 622 399 622 401 622 145 623 100 623 104 623 145 624 375 624 98 624 103 625 24 625 27 625 247 626 291 626 136 626 143 627 20 627 142 627 18 628 20 628 143 628 136 629 291 629 105 629 105 630 291 630 290 630 105 631 290 631 104 631 104 632 290 632 289 632 145 633 104 633 289 633 145 634 289 634 16 634 145 635 18 635 143 635 145 636 16 636 18 636 399 637 120 637 22 637 400 638 137 638 398 638 106 639 103 639 27 639 74 640 7 640 76 640 391 641 393 641 42 641 392 642 1 642 59 642 35 643 13 643 15 643 35 644 403 644 13 644 35 645 15 645 294 645 35 646 294 646 4 646 4 647 294 647 293 647 75 648 4 648 293 648 75 649 293 649 292 649 43 650 75 650 292 650 13 651 403 651 20 651 403 652 142 652 20 652 338 653 43 653 292 653 367 654 382 654 365 654 76 655 7 655 10 655 79 656 390 656 35 656 35 657 4 657 77 657 394 658 402 658 392 658 391 659 402 659 394 659 1 660 392 660 44 660 392 661 335 661 44 661 336 662 335 662 392 662 392 663 402 663 336 663 337 664 336 664 402 664 402 665 391 665 337 665 391 666 338 666 337 666 391 667 42 667 338 667 42 668 43 668 338 668 382 669 367 669 355 669 355 670 368 670 382 670 386 671 382 671 368 671 403 672 35 672 34 672 390 673 34 673 35 673 152 674 151 674 547 674 547 675 548 675 152 675 404 676 152 676 548 676 404 677 405 677 152 677 406 678 407 678 152 678 406 679 152 679 405 679 406 680 405 680 408 680 409 681 406 681 408 681 409 682 410 682 407 682 406 683 409 683 407 683 411 684 410 684 409 684 408 685 412 685 409 685 409 686 412 686 413 686 409 687 413 687 414 687 415 688 409 688 414 688 415 689 416 689 411 689 409 690 415 690 411 690 407 691 150 691 152 691 417 692 150 692 407 692 418 693 417 693 407 693 410 694 419 694 418 694 407 695 410 695 418 695 410 696 411 696 419 696 416 697 420 697 421 697 416 698 421 698 419 698 411 699 416 699 419 699 331 700 422 700 329 700 327 701 329 701 422 701 422 702 423 702 327 702 327 703 423 703 424 703 325 704 327 704 424 704 424 705 425 705 325 705 325 706 425 706 426 706 418 707 428 707 427 707 427 708 308 708 418 708 417 709 418 709 308 709 307 710 150 710 417 710 308 711 307 711 417 711 307 712 154 712 150 712 429 713 431 713 430 713 430 714 431 714 432 714 433 715 430 715 432 715 245 716 246 716 433 716 432 717 245 717 433 717 434 718 246 718 153 718 305 719 433 719 434 719 153 720 305 720 434 720 430 721 433 721 305 721 305 722 304 722 430 722 429 723 430 723 304 723 304 724 303 724 429 724 435 725 429 725 303 725 303 726 334 726 435 726 438 727 428 727 439 727 439 728 441 728 440 728 441 729 443 729 442 729 443 730 422 730 331 730 444 731 427 731 438 731 438 732 440 732 444 732 302 733 444 733 440 733 440 734 442 734 302 734 306 735 302 735 442 735 442 736 331 736 306 736 308 737 427 737 444 737 444 738 300 738 308 738 444 739 302 739 301 739 300 740 444 740 301 740 445 741 446 741 447 741 447 742 420 742 445 742 448 743 445 743 420 743 416 744 449 744 448 744 420 745 416 745 448 745 413 746 450 746 237 746 450 747 244 747 237 747 449 748 416 748 415 748 449 749 415 749 414 749 449 750 414 750 413 750 449 751 413 751 237 751 243 752 449 752 237 752 230 753 245 753 451 753 230 754 451 754 452 754 213 755 230 755 452 755 213 756 452 756 453 756 213 757 453 757 454 757 215 758 213 758 454 758 454 759 455 759 215 759 229 760 215 760 455 760 455 761 449 761 229 761 243 762 229 762 449 762 437 763 436 763 456 763 457 764 456 764 436 764 436 765 458 765 457 765 459 766 457 766 458 766 458 767 460 767 459 767 461 768 459 768 460 768 460 769 462 769 461 769 463 770 461 770 462 770 462 771 464 771 463 771 465 772 463 772 464 772 464 773 466 773 465 773 467 774 465 774 466 774 466 775 441 775 467 775 467 776 441 776 439 776 428 777 467 777 439 777 436 778 426 778 458 778 460 779 458 779 426 779 426 780 425 780 460 780 462 781 460 781 425 781 425 782 424 782 462 782 464 783 462 783 424 783 424 784 423 784 464 784 466 785 464 785 423 785 423 786 422 786 466 786 466 787 422 787 443 787 466 788 443 788 441 788 456 789 455 789 454 789 454 790 453 790 456 790 468 791 456 791 453 791 429 792 469 792 431 792 469 793 429 793 435 793 469 794 435 794 437 794 468 795 469 795 437 795 437 796 456 796 468 796 457 797 455 797 456 797 459 798 449 798 455 798 457 799 459 799 455 799 448 800 449 800 459 800 459 801 461 801 448 801 445 802 448 802 461 802 461 803 463 803 445 803 446 804 445 804 463 804 465 805 447 805 446 805 463 806 465 806 446 806 420 807 447 807 465 807 465 808 467 808 420 808 421 809 420 809 467 809 428 810 419 810 421 810 467 811 428 811 421 811 468 812 453 812 452 812 452 813 469 813 468 813 431 814 469 814 432 814 469 815 451 815 245 815 432 816 469 816 245 816 469 817 452 817 451 817 418 818 419 818 428 818 216 819 404 819 187 819 548 820 187 820 404 820 201 821 203 821 244 821 470 822 217 822 218 822 202 823 470 823 218 823 470 824 202 824 201 824 216 825 217 825 470 825 244 826 450 826 201 826 201 827 450 827 413 827 201 828 413 828 412 828 408 829 201 829 412 829 201 830 408 830 470 830 470 831 405 831 216 831 470 832 408 832 405 832 404 833 216 833 405 833 325 834 426 834 323 834 426 835 436 835 323 835 323 836 436 836 322 836 322 837 436 837 437 837 334 838 322 838 437 838 334 839 437 839 435 839 246 840 162 840 153 840 427 841 428 841 438 841 438 842 439 842 440 842 440 843 441 843 442 843 331 844 442 844 443 844 254 845 512 845 513 845 509 846 513 846 514 846 517 847 509 847 515 847 527 848 517 848 516 848 163 849 157 849 162 849 251 850 520 850 518 850 251 851 518 851 263 851 263 852 518 852 519 852 262 853 263 853 519 853 528 854 262 854 519 854 260 855 262 855 528 855 548 856 471 856 187 856 473 857 471 857 472 857 473 858 187 858 471 858 474 859 473 859 472 859 472 860 541 860 474 860 474 861 541 861 540 861 474 862 540 862 502 862 501 863 474 863 502 863 187 864 473 864 186 864 473 865 474 865 200 865 200 866 185 866 473 866 473 867 185 867 186 867 474 868 501 868 199 868 199 869 501 869 499 869 199 870 200 870 474 870 166 871 199 871 499 871 498 872 188 872 167 872 189 873 497 873 190 873 190 874 497 874 164 874 190 875 164 875 175 875 188 876 498 876 475 876 475 877 493 877 188 877 188 878 493 878 189 878 500 879 475 879 498 879 535 880 516 880 477 880 476 881 496 881 495 881 523 882 164 882 476 882 476 883 164 883 496 883 495 884 478 884 476 884 478 885 495 885 494 885 480 886 534 886 516 886 516 887 534 887 477 887 482 888 533 888 480 888 480 889 533 889 534 889 533 890 482 890 505 890 484 891 506 891 482 891 482 892 506 892 505 892 506 893 484 893 507 893 486 894 507 894 484 894 507 895 486 895 504 895 488 896 504 896 486 896 504 897 488 897 503 897 490 898 491 898 488 898 488 899 491 899 503 899 491 900 490 900 492 900 490 901 479 901 492 901 518 902 478 902 479 902 478 903 518 903 476 903 476 904 518 904 520 904 476 905 520 905 525 905 525 906 523 906 476 906 478 907 494 907 479 907 492 908 479 908 494 908 481 909 514 909 512 909 481 910 512 910 532 910 531 911 481 911 532 911 481 912 531 912 483 912 530 913 483 913 531 913 483 914 530 914 485 914 529 915 485 915 530 915 485 916 529 916 487 916 528 917 487 917 529 917 487 918 528 918 489 918 519 919 489 919 528 919 516 920 515 920 480 920 480 921 515 921 514 921 481 922 480 922 514 922 480 923 481 923 482 923 483 924 482 924 481 924 482 925 483 925 484 925 485 926 484 926 483 926 484 927 485 927 486 927 487 928 486 928 485 928 486 929 487 929 488 929 489 930 488 930 487 930 488 931 489 931 490 931 519 932 490 932 489 932 490 933 519 933 479 933 518 934 479 934 519 934 500 935 503 935 475 935 475 936 503 936 491 936 475 937 491 937 493 937 493 938 491 938 492 938 493 939 492 939 189 939 189 940 492 940 494 940 189 941 494 941 495 941 189 942 495 942 497 942 497 943 495 943 496 943 497 944 496 944 164 944 499 945 165 945 166 945 498 946 165 946 500 946 501 947 165 947 499 947 500 948 165 948 503 948 533 949 504 949 538 949 538 950 504 950 503 950 504 951 533 951 507 951 505 952 507 952 533 952 507 953 505 953 506 953 508 954 279 954 285 954 285 955 284 955 508 955 283 956 508 956 284 956 279 957 508 957 526 957 508 958 283 958 511 958 511 959 283 959 510 959 511 960 526 960 508 960 277 961 510 961 276 961 276 962 510 962 283 962 526 963 511 963 527 963 513 964 277 964 254 964 277 965 513 965 509 965 277 966 509 966 510 966 511 967 510 967 509 967 517 968 511 968 509 968 511 969 517 969 527 969 512 970 254 970 532 970 514 971 513 971 512 971 515 972 509 972 514 972 517 973 515 973 516 973 282 974 520 974 251 974 520 975 282 975 525 975 281 976 525 976 282 976 525 977 281 977 524 977 280 978 524 978 281 978 524 979 280 979 522 979 157 980 521 980 280 980 280 981 521 981 522 981 157 982 163 982 521 982 277 983 253 983 254 983 523 984 522 984 164 984 522 985 163 985 164 985 522 986 523 986 524 986 525 987 524 987 523 987 279 988 151 988 161 988 526 989 536 989 279 989 279 990 536 990 151 990 536 991 526 991 535 991 527 992 535 992 526 992 535 993 527 993 516 993 260 994 528 994 529 994 530 995 260 995 529 995 260 996 530 996 258 996 258 997 530 997 531 997 532 998 258 998 531 998 258 999 532 999 256 999 254 1000 256 1000 532 1000 533 1001 538 1001 534 1001 542 1002 477 1002 538 1002 538 1003 477 1003 534 1003 543 1004 477 1004 542 1004 545 1005 535 1005 543 1005 543 1006 535 1006 477 1006 535 1007 545 1007 536 1007 536 1008 545 1008 151 1008 547 1009 151 1009 545 1009 544 1010 542 1010 537 1010 537 1011 542 1011 538 1011 537 1012 539 1012 544 1012 544 1013 539 1013 540 1013 544 1014 540 1014 541 1014 472 1015 544 1015 541 1015 542 1016 544 1016 543 1016 546 1017 545 1017 544 1017 544 1018 545 1018 543 1018 544 1019 472 1019 546 1019 546 1020 472 1020 471 1020 546 1021 471 1021 547 1021 546 1022 547 1022 545 1022 548 1023 547 1023 471 1023 24 1024 103 1024 102 1024 24 1025 102 1025 359 1025 24 1026 359 1026 378 1026 24 1027 378 1027 377 1027 24 1028 377 1028 376 1028 24 1029 376 1029 88 1029 88 1030 89 1030 24 1030 5 1031 76 1031 10 1031 5 1032 10 1032 360 1032 10 1033 387 1033 360 1033 10 1034 388 1034 387 1034 10 1035 389 1035 388 1035 10 1036 36 1036 389 1036 36 1037 10 1037 87 1037 84 1038 87 1038 10 1038 89 1039 93 1039 24 1039 239 1040 241 1040 237 1040 236 1041 239 1041 237 1041 234 1042 236 1042 237 1042 232 1043 234 1043 237 1043 231 1044 232 1044 237 1044 231 1045 237 1045 233 1045 233 1046 237 1046 235 1046 235 1047 237 1047 238 1047 165 1048 168 1048 166 1048 165 1049 170 1049 168 1049 165 1050 172 1050 170 1050 165 1051 174 1051 172 1051 165 1052 173 1052 174 1052 165 1053 171 1053 173 1053 165 1054 169 1054 171 1054 165 1055 167 1055 169 1055 165 1056 498 1056 167 1056 165 1057 501 1057 502 1057 165 1058 502 1058 540 1058 165 1059 540 1059 539 1059 165 1060 539 1060 537 1060 165 1061 537 1061 538 1061 165 1062 538 1062 503 1062 381 1063 369 1063 384 1063 11 1064 384 1064 369 1064 11 1065 369 1065 383 1065 366 1066 383 1066 369 1066 366 1067 369 1067 374 1067 379 1068 350 1068 380 1068 23 1069 350 1069 379 1069 23 1070 353 1070 350 1070 353 1071 354 1071 350 1071 340 1072 350 1072 354 1072 340 1073 369 1073 350 1073 340 1074 374 1074 369 1074 150 1075 158 1075 151 1075 150 1076 156 1076 158 1076 150 1077 155 1077 156 1077 150 1078 154 1078 155 1078 151 1079 158 1079 159 1079 151 1080 159 1080 160 1080 151 1081 160 1081 161 1081 66 1082 70 1082 71 1082 66 1083 71 1083 69 1083 108 1084 113 1084 110 1084 108 1085 109 1085 113 1085 1 1086 2 1086 59 1086 22 1087 115 1087 28 1087 139 1088 140 1088 341 1088 95 1089 140 1089 139 1089 365 1090 382 1090 385 1090 382 1091 386 1091 385 1091

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E2M3.dae b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E2M3.dae new file mode 100644 index 0000000..a461aa4 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E2M3.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:31.855069 + 2012-07-23T02:15:31.855082 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -7.17350 6.94911 4.21838 -9.93270 -1.15879 -0.00031 -9.92969 1.15514 -0.00031 -7.45360 6.66578 -0.00031 -6.19669 -7.61001 14.00068 -5.99999 -7.69760 7.99969 -5.93079 -7.72543 8.52069 -5.99999 -7.62085 -1.45521 -6.53730 7.42476 2.97619 -6.00000 7.62007 -1.44611 -5.99999 -0.00089 -0.00031 -4.99999 3.65198 9.71969 -3.55469 -9.23031 23.11969 -3.56699 -8.61560 18.55868 -1.76899 -9.59040 22.63068 -4.59092 -8.80456 23.59968 4.59459 -8.80456 23.59968 1.77266 -9.59040 22.63068 3.57066 -8.61560 18.55868 3.55836 -9.23031 23.11969 0.00406 -8.84559 18.22268 0.00406 -9.69028 22.44568 9.93636 -1.15879 -0.00031 5.00366 3.81254 9.73169 6.00366 -0.00089 -0.00031 6.00366 7.62007 -1.44611 7.14516 6.97814 3.97919 6.00366 -7.62085 -1.45522 9.93336 1.15514 -0.00031 7.45726 6.66578 -0.00031 -4.47209 7.99911 23.99968 -0.92010 7.99911 10.96068 -2.73450 7.99911 10.65468 -5.10259 7.94911 9.74469 -3.99999 -8.00089 9.99969 -5.00999 -7.96456 14.00168 -6.00000 6.94911 4.50619 -5.64640 6.94911 8.25268 -7.17349 6.94911 6.96669 -7.06460 7.04525 7.66968 -6.70469 7.31810 8.43568 -6.02019 7.68741 9.16469 -7.45360 -6.66756 -0.00031 -7.46809 -6.65131 13.99969 -9.91719 -1.28497 23.99968 -9.99999 -0.02064 23.99968 -9.92209 1.24482 23.99968 -9.68389 2.49335 23.99968 -9.63909 2.66125 -0.00031 -8.93994 4.00025 23.99968 -9.11909 4.10304 -0.00031 -8.39959 5.42557 23.99968 -8.38479 5.44841 -0.00031 -7.47299 6.64398 23.99968 -6.00000 -5.49870 -5.79131 -5.99999 -6.96596 -3.90192 -6.00000 -3.36071 -7.26061 -6.00000 -4.50038 -6.61501 -6.00000 -2.24851 -7.67811 -9.41220 -1.47532 -3.03941 -8.06000 -1.20361 -5.79601 -6.00000 -1.13267 -7.91981 -6.00000 -0.00089 -8.00031 -8.06000 1.20183 -5.79601 -9.41220 1.47352 -3.03941 -6.00000 1.13089 -7.91981 -7.35780 3.50247 -5.79601 -6.00000 2.24673 -7.67811 -8.51050 4.28110 -3.03941 -6.00000 3.35892 -7.26061 -6.00000 5.49692 -5.79131 -6.00000 4.49860 -6.61501 -6.62189 6.66578 -3.42181 -6.00000 6.66577 -4.42251 -6.78489 -7.26453 -0.00031 -6.83189 -7.23065 13.99969 -5.99999 -7.69760 -0.00031 -5.71839 -7.80180 9.02269 -5.38550 -7.89522 9.44169 -4.95869 -7.97119 9.75468 -5.99999 -7.34730 -2.89871 -5.57889 7.84294 23.99968 -6.59929 7.38662 23.99968 -6.00000 7.69581 -0.00031 -6.00000 7.69581 2.18159 -6.00000 7.34767 -2.89111 -6.00000 7.07516 -3.64421 -6.00000 7.31252 3.24219 6.00366 6.94911 4.50619 6.00366 7.31252 3.24219 6.00366 6.66577 -4.42252 6.00366 7.34767 -2.89111 6.66886 7.34083 3.17053 6.00366 7.69581 2.18159 6.00366 7.69581 -0.00031 6.60296 7.38662 23.99968 5.58256 7.84294 23.99968 6.00366 -7.18556 -3.39231 4.96236 -7.97119 9.75468 5.38916 -7.89522 9.44169 5.72206 -7.80180 9.02269 5.93446 -7.72543 8.52069 6.00366 -7.69760 7.99968 6.00366 -7.69760 -0.00031 6.20036 -7.61001 14.00068 6.83556 -7.23065 13.99968 6.78856 -7.26453 -0.00031 6.62556 6.66578 -3.42181 6.00366 4.49860 -6.61501 6.00366 5.49692 -5.79131 6.00366 3.35892 -7.26061 8.51416 4.28110 -3.03941 6.00366 2.24673 -7.67812 7.36146 3.50247 -5.79601 6.00366 1.13089 -7.91981 9.41586 1.47352 -3.03941 8.06366 1.20183 -5.79601 6.00366 -0.00089 -8.00031 6.00366 -1.13267 -7.91981 8.06366 -1.20361 -5.79601 9.41586 -1.47532 -3.03941 6.00366 -2.24851 -7.67812 6.00366 -4.50038 -6.61501 6.00366 -3.36071 -7.26061 6.00366 -6.66755 -4.42252 6.00366 -5.49870 -5.79131 7.47666 6.64398 23.99968 8.38846 5.44841 -0.00031 8.40326 5.42557 23.99968 9.12276 4.10304 -0.00031 8.94361 4.00025 23.99968 9.64276 2.66125 -0.00031 9.68756 2.49335 23.99968 9.92576 1.24482 23.99968 10.00366 -0.02064 23.99968 9.92086 -1.28497 23.99968 7.47176 -6.65131 13.99968 7.45726 -6.66756 -0.00031 5.10626 7.94911 9.74469 6.02386 7.68741 9.16469 7.06826 7.04525 7.66968 7.17716 6.94911 6.96669 0.00406 -8.00089 13.99868 3.58286 -8.00089 13.99868 4.00366 -8.00089 9.99969 5.01366 -7.96456 14.00168 0.00366 7.99911 23.99968 2.73816 7.99911 10.65468 0.92376 7.99911 10.96068 4.47576 7.99911 23.99968 -3.99999 -5.02735 37.82068 4.00366 -5.02735 37.82068 -3.99999 -5.00089 39.42268 -4.48079 7.99911 34.49768 -3.53979 -8.82177 32.40168 -2.34909 -9.28970 31.73368 -1.16229 -9.55490 31.35468 4.48446 7.99911 34.49768 0.00346 -9.63919 31.23468 1.16596 -9.55490 31.35468 2.35276 -9.28970 31.73368 3.54346 -8.82177 32.40168 0.00366 7.99911 44.99968 4.46387 7.99911 44.99968 4.00366 6.94911 44.99968 7.00366 -0.00089 44.99968 7.00366 -3.61239 46.59969 7.00366 3.37761 47.04568 7.00366 -3.04855 47.51268 7.00366 2.70194 47.87968 7.00366 -2.25983 48.23969 7.00366 1.82715 48.50168 7.00366 -1.30441 48.72868 7.00366 0.81734 48.86368 7.00366 -0.25282 48.94168 4.00366 6.69274 46.86967 4.00366 5.94276 48.60168 4.00366 4.75370 50.06868 4.00366 3.21449 51.16068 4.00366 1.43786 51.79867 4.00366 -0.44483 51.93568 4.00366 -2.29479 51.56068 4.00366 -3.97553 50.70068 4.00366 -5.36307 49.42068 4.00366 -6.35507 47.81468 4.00366 -6.87828 46.00168 4.00366 -6.89415 44.11368 4.00366 -6.40153 42.29169 6.60256 4.84007 47.50069 5.76706 6.37616 44.99969 5.50366 5.81689 48.00468 6.60256 3.15259 49.44267 5.50366 3.78892 50.33968 6.60256 0.76172 50.39468 5.50366 0.91560 51.48367 6.60256 -1.79926 50.14268 5.50366 -2.16214 51.18068 6.60256 -3.95910 48.74368 5.50366 -4.75780 49.49968 6.60256 -5.23604 46.50967 5.50366 -6.29241 46.81468 -6.59889 -5.34526 43.93867 -5.49999 -6.29241 46.81468 -6.59889 -5.23604 46.50967 -5.49999 -4.75780 49.49968 -6.59889 -3.95910 48.74368 -5.49999 -2.16214 51.18068 -6.59889 -1.79926 50.14268 -5.49999 0.91560 51.48367 -6.59889 0.76172 50.39468 -5.49999 3.78892 50.33968 -6.59889 3.15259 49.44267 -5.49999 5.81689 48.00468 -5.76339 6.37616 44.99968 -6.59889 4.84007 47.50069 -6.42709 5.71247 44.99968 -3.99999 -6.40153 42.29169 -3.99999 -6.89415 44.11368 -3.99999 -6.87828 46.00168 -3.99999 -6.35507 47.81468 -3.99999 -5.36307 49.42068 -3.99999 -3.97553 50.70068 -3.99999 -2.29479 51.56068 -3.99999 -0.44483 51.93568 -3.99999 1.43786 51.79867 -3.99999 3.21449 51.16068 -3.99999 4.75370 50.06868 -3.99999 5.94276 48.60168 -3.99999 6.69274 46.86967 -6.85319 4.87616 44.99968 -4.92709 6.80228 44.99968 -6.99999 -0.25282 48.94168 -6.99999 0.81734 48.86368 -6.99999 -1.30441 48.72868 -6.99999 1.82715 48.50168 -6.99999 -2.25983 48.23969 -6.99999 2.70194 47.87968 -6.99999 -0.00090 44.99968 -6.99999 -3.04855 47.51268 -6.99999 3.37761 47.04568 -6.99999 -3.61239 46.59969 -6.99999 3.80368 46.06168 -6.99999 -3.90969 45.56868 -6.99999 3.94911 44.99968 -6.99999 -3.91855 44.49568 -3.99999 6.94911 44.99968 -4.46019 7.99911 44.99968 8.35526 -5.50089 23.99968 8.73536 -4.87502 23.99968 9.28136 -3.73246 23.99968 9.67876 -2.52910 23.99968 7.43666 6.69810 34.49368 8.31437 5.81849 29.52985 8.89386 -4.46979 29.51968 8.76546 -4.19563 35.80267 9.26076 -2.79232 29.51968 8.91906 -2.27439 35.04568 9.45096 -1.09815 29.51968 8.96676 -0.33818 35.04568 9.47666 0.60681 29.51968 8.94576 1.60178 35.04568 9.33576 2.31798 29.51968 8.83896 3.55496 35.04568 8.30708 5.67738 34.68957 8.98616 4.04325 29.51968 0.00416 -10.00089 29.52368 0.00336 -10.00089 30.08768 2.93366 -9.56529 30.58668 3.43473 -9.48162 29.13079 3.49076 -9.37344 25.99968 1.45316 -9.89544 25.99968 4.39459 -9.10315 25.99968 4.41876 -8.98168 31.25368 6.33566 -7.76061 29.52368 5.84346 -8.13534 32.22368 7.02016 -7.12658 25.99968 7.14446 -7.03138 33.48969 8.27176 -5.67266 35.04868 8.54566 -5.26191 29.52368 4.68486 -8.14347 33.37068 5.30646 7.91391 34.49867 6.09576 7.66057 34.49867 6.81586 7.24997 34.49968 6.91396 -7.18597 33.86967 5.65496 -8.25206 32.34668 5.01416 -8.44358 32.71868 3.31336 -9.32459 31.45968 1.18046 -9.86343 30.69068 5.37426 -8.43667 25.99968 5.71986 -8.20649 23.99968 6.46616 -7.63259 23.99968 7.16186 -6.98424 23.99968 -7.15819 -6.98424 23.99968 -6.46249 -7.63259 23.99968 -5.71619 -8.20649 23.99968 -5.37059 -8.43667 25.99968 -1.17679 -9.86343 30.69068 -3.30969 -9.32459 31.45968 -5.01049 -8.44358 32.71868 -5.65129 -8.25206 32.34668 -6.31069 -7.37931 34.23868 -6.91029 -7.18597 33.86967 -7.85419 -6.04028 35.50568 -6.81219 7.24997 34.49968 -6.09209 7.66057 34.49867 -5.30279 7.91391 34.49867 -8.26809 -5.67266 35.04868 -4.68119 -8.14347 33.37068 -5.72309 -7.25891 34.63368 -8.54199 -5.26191 29.52368 -7.14079 -7.03138 33.48969 -7.01649 -7.12658 25.99968 -5.83979 -8.13534 32.22368 -6.33199 -7.76061 29.52368 -4.41509 -8.98168 31.25368 -4.39092 -9.10315 25.99968 -1.44949 -9.89544 25.99968 -3.48709 -9.37343 25.99968 -3.43106 -9.48162 29.13079 -2.92999 -9.56529 30.58668 0.00184 -10.00019 25.99969 -8.98249 4.04325 29.51968 -8.30341 5.67738 34.68957 -8.83529 3.55496 35.04568 -9.33209 2.31798 29.51968 -8.94209 1.60178 35.04568 -9.47299 0.60681 29.51968 -8.96309 -0.33818 35.04568 -9.44729 -1.09815 29.51968 -8.91539 -2.27439 35.04568 -9.25709 -2.79232 29.51968 -8.76179 -4.19563 35.80267 -8.89019 -4.46979 29.51968 -8.31070 5.81849 29.52985 -7.43299 6.69810 34.49368 -9.67509 -2.52910 23.99968 -9.27769 -3.73246 23.99968 -8.73169 -4.87502 23.99968 -8.35159 -5.50089 23.99968 0.00183 7.24200 10.60569 4.00366 4.25152 9.99969 5.65006 6.94911 8.25268 5.55006 6.94911 5.59469 3.89726 6.94911 9.21068 3.63686 6.94093 6.60969 1.98966 6.94911 9.80069 0.00366 6.94911 9.99969 0.00366 6.94911 7.84768 4.30636 7.24200 9.80469 1.47496 7.24200 10.60569 4.32487 5.06448 8.40697 3.63686 6.82538 6.40069 4.38886 6.06216 6.65668 4.68666 3.94590 9.87969 4.34936 4.09318 9.96969 3.63371 6.43688 6.43168 4.43506 6.73264 6.19568 4.49076 6.91366 6.33069 5.94346 3.82193 8.45469 6.00400 4.02117 8.04468 -6.00000 4.02117 8.04468 -5.93979 3.82193 8.45469 -5.54639 6.94911 5.59469 -4.54040 6.94911 6.46068 -3.63320 6.94093 6.60969 -4.45075 6.64691 6.24219 -4.34569 4.09222 9.96969 -3.63320 6.82538 6.40069 3.63321 5.95391 6.88068 -4.32395 5.11941 8.41997 -1.47129 7.24200 10.60569 -4.30269 7.24200 9.80469 -1.98599 6.94911 9.80069 -3.89359 6.94911 9.21068 -3.99999 4.25198 9.99969 4.47576 -8.00089 9.94269 6.00366 5.96671 5.62369 6.00366 4.86318 6.60168 6.00366 4.40365 7.39368 5.41736 3.62295 9.41469 5.73196 3.74311 9.00368 -5.72829 3.74311 9.00368 -3.63359 6.44435 6.42669 -4.68299 3.85204 9.87969 -5.41369 3.62295 9.41469 -4.38520 6.06216 6.65668 -3.63320 5.95391 6.88068 -5.99999 4.40365 7.39368 -5.99999 4.86318 6.60168 -6.00000 5.96671 5.62369 -4.47209 -8.00089 9.94269 -8.38479 -5.45020 -0.00031 -9.63909 -2.66304 -0.00031 -6.78409 -6.66756 -3.03501 -8.51050 -4.28290 -3.03941 -7.35780 -3.50425 -5.79601 7.36146 -3.50425 -5.79601 8.51416 -4.28290 -3.03941 6.78776 -6.66756 -3.03501 9.64276 -2.66304 -0.00031 8.38846 -5.45020 -0.00031 9.12276 -4.10482 -0.00031 -9.11909 -4.10482 -0.00031 -3.57919 -8.00089 13.99868 -3.99999 -5.43664 40.66869 -5.48459 -5.09962 40.93769 -5.49999 -4.73356 40.21569 -5.76329 -4.42797 39.42269 -6.42709 -4.46943 41.43969 -6.59809 -3.69701 40.57769 -6.42699 -3.76429 39.42269 -6.85319 -2.92798 39.42269 -6.68310 -3.81534 41.96069 -6.99999 -3.09028 42.53869 -6.99999 -2.49594 41.59168 -6.99999 -2.12557 40.53269 -6.99999 -2.00089 39.42269 -5.36349 -4.67315 38.32668 -6.19619 -4.04460 39.22469 -6.72699 -3.25133 38.74369 -6.99999 -2.00089 38.27869 -6.96549 -2.45480 38.42168 -8.53599 -1.46623 39.60468 -8.55289 -0.11087 39.43468 -8.54059 1.25595 39.55968 -8.50409 2.50568 39.95368 -8.45399 3.57721 40.56069 -6.76829 -5.70594 36.85169 -6.86009 -4.03110 39.22569 -6.92969 7.10944 44.99969 -6.11599 7.64029 44.99969 -5.93589 7.04911 44.99969 -5.49999 6.94911 44.99969 -5.31029 7.90772 44.99969 -4.88529 7.95342 44.99969 -7.19169 6.82799 43.78869 -8.19199 4.97673 41.65069 -7.71279 6.06131 42.71468 -7.49639 -5.59217 36.77569 -7.60349 -3.56948 39.46268 -8.12469 -5.26918 36.55169 -8.06229 -2.97472 39.64069 -8.56689 -4.78127 36.21169 -8.39929 -2.25591 39.68868 -7.28129 -6.21366 35.90269 -6.99999 1.68717 38.19369 -6.99999 0.45891 38.00269 -6.99999 -0.78335 38.03168 -6.99999 2.86304 38.59969 -6.99999 3.94911 39.20568 -6.99999 -3.63839 43.45969 -5.03399 6.76527 43.41169 -5.49999 6.54719 42.67069 -5.93590 6.24091 41.72169 -6.39679 5.75341 40.92669 -6.83869 4.91954 39.95969 -7.08054 5.94669 41.49869 -7.43409 4.97597 40.42869 -8.19199 4.02715 40.55369 -7.43409 3.77077 39.39269 -8.19199 2.84199 39.71668 -7.43409 2.35678 38.66769 -8.19199 1.49065 39.18868 -7.43409 0.81253 38.29169 -8.19199 0.05167 39.00069 -7.43409 -0.77680 38.28768 -8.19199 -1.39001 39.16369 -7.43409 -2.32320 38.65369 -6.72699 6.57048 42.44669 -6.72699 6.92842 43.70069 -5.49999 -6.42367 43.72469 5.48826 -5.09962 40.93769 6.43076 -4.46943 41.43969 5.50366 -6.42367 43.72469 6.60256 -5.34526 43.93868 6.85686 4.87616 44.99969 6.73066 6.92842 43.70069 6.73066 -3.25133 38.74369 6.73066 6.57048 42.44669 7.08421 5.94669 41.49869 7.43776 -2.32320 38.65369 8.19566 -1.39001 39.16369 7.43776 -0.77680 38.28768 8.19566 0.05167 39.00069 7.43776 0.81253 38.29169 8.19566 1.49065 39.18868 7.43776 2.35678 38.66769 8.19566 2.84199 39.71668 7.43776 3.77077 39.39269 8.19566 4.02715 40.55369 7.43776 4.97597 40.42869 6.84236 4.91954 39.95969 6.40046 5.75341 40.92669 6.43076 5.71247 44.99969 5.93956 6.24091 41.72169 5.50366 6.54719 42.67069 5.03766 6.76527 43.41169 4.93076 6.80228 44.99969 7.00366 3.80368 46.06168 7.00366 -3.90969 45.56869 7.00366 3.94911 44.99969 7.00366 -3.91855 44.49569 7.00366 -3.63839 43.45969 7.00366 3.94911 39.20568 7.00366 2.86304 38.59969 7.00366 -0.78335 38.03168 7.00366 0.45891 38.00269 7.00366 1.68717 38.19369 6.31436 -7.37931 34.23869 8.12836 -5.26918 36.55169 7.85786 -6.04028 35.50568 7.28496 -6.21366 35.90269 8.40296 -2.25591 39.68868 8.57056 -4.78127 36.21169 8.06596 -2.97472 39.64069 7.60716 -3.56948 39.46268 6.99346 -4.00149 39.23769 7.50006 -5.59217 36.77569 7.71646 6.06131 42.71468 8.19566 4.97673 41.65069 7.19536 6.82799 43.78869 4.88896 7.95342 44.99969 5.31396 7.90772 44.99969 5.93956 7.04911 44.99969 6.11966 7.64029 44.99969 6.93336 7.10944 44.99969 5.72676 -7.25891 34.63369 6.77196 -5.70594 36.85169 8.45766 3.57721 40.56069 8.50776 2.50568 39.95368 8.54426 1.25595 39.55968 8.55656 -0.11086 39.43468 8.53966 -1.46623 39.60468 7.00366 -2.00089 38.27869 6.96916 -2.45480 38.42168 6.19986 -4.04460 39.22469 5.36716 -4.67315 38.32668 7.00366 -2.31088 41.06269 7.00366 -2.00089 39.42269 7.00366 -2.49594 41.59168 7.00366 -3.09028 42.53869 6.75609 -3.81534 41.96069 6.85686 -2.92798 39.42269 6.43066 -3.76429 39.42269 6.60176 -3.69701 40.57769 5.76696 -4.42797 39.42269 5.50366 -4.73356 40.21569 4.00366 -5.00089 39.42269 4.00366 -5.43664 40.66869 + + + + + + + + + + -0.37992 -0.92502 0.00105 -0.61397 0.78924 -0.01224 -0.07593 -0.97679 -0.20031 -0.22994 -0.96457 -0.12938 -0.08134 -0.97733 -0.19549 -0.42429 -0.89757 -0.11982 0.42429 -0.89757 -0.11983 0.08144 -0.97732 -0.19548 0.22994 -0.96457 -0.12938 0.07611 -0.97679 -0.20023 0.00000 1.00000 -0.00000 -0.02010 0.99979 -0.00262 -0.99786 -0.06535 0.00030 -1.00000 0.00130 -0.00287 -0.99811 0.06144 0.00009 -0.98228 0.18741 -0.00039 -0.98189 0.18945 -0.00051 -0.89668 0.44268 0.00142 -0.94065 0.33926 0.00847 -0.93503 0.35447 0.00850 -0.87777 0.47908 -0.00009 -0.79597 0.60534 0.00009 -0.79427 0.60756 -0.00009 -0.73062 -0.00000 -0.68279 -0.89780 -0.00000 -0.44040 -0.89780 -0.00000 -0.44040 -0.71610 0.04952 -0.69624 -0.75711 0.13830 -0.63848 -0.69777 0.21297 -0.68393 -0.85617 0.26132 -0.44574 -0.92192 0.33250 -0.19878 -0.93821 0.30132 -0.17023 -0.85683 0.27518 -0.43602 -0.69725 0.25192 -0.67110 -0.86835 0.47394 -0.14612 -0.73749 0.50314 -0.45051 -0.77877 0.59570 -0.19660 -0.78420 0.59050 -0.19062 -0.73536 0.51102 -0.44509 -0.72246 0.52579 -0.44899 -0.67329 -0.73938 -0.00047 -0.66596 -0.74598 0.00018 -0.51275 -0.85854 0.00036 -0.48310 -0.87557 -0.00131 -0.34471 -0.93870 0.00305 -0.28004 -0.95995 0.00846 -0.17483 -0.98460 -0.00057 -0.13972 0.99019 0.00271 -0.27312 0.96198 -0.00196 -0.40823 0.91287 0.00257 -0.47428 0.88037 -0.00066 -0.45040 0.89283 0.00000 -0.71115 0.70304 0.00000 -0.57790 0.81555 -0.03005 -0.60493 0.79627 0.00059 -0.67564 0.73722 0.00384 -0.57764 0.81518 -0.04270 -0.64644 0.74661 -0.15714 -0.67682 0.72341 -0.13637 -0.59520 0.75563 -0.27343 -0.59953 0.70834 -0.37259 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.02819 0.94010 0.33974 0.01436 0.93130 0.36396 0.12973 0.97951 -0.15405 -0.64764 0.76194 0.00226 -0.71191 0.70227 0.00006 -0.98581 0.00000 -0.16786 -0.97140 0.18743 -0.14577 0.97140 0.18743 -0.14578 0.98565 0.00000 -0.16881 0.71191 0.70227 0.00006 0.64764 0.76194 0.00226 0.00494 0.91350 0.40681 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 0.54765 0.76436 -0.34035 0.67682 0.72341 -0.13637 0.64644 0.74661 -0.15714 0.57764 0.81518 -0.04270 0.67564 0.73722 0.00384 0.57791 0.81555 -0.02994 0.61966 0.78477 -0.01300 0.70339 0.71081 -0.00063 0.47080 0.88224 -0.00000 0.40823 0.91287 0.00257 0.27312 0.96198 -0.00196 0.13972 0.99019 0.00271 0.17483 -0.98460 -0.00057 0.28004 -0.95995 0.00846 0.34471 -0.93870 0.00305 0.37991 -0.92502 0.00105 0.48310 -0.87557 -0.00131 0.51275 -0.85854 0.00036 0.66596 -0.74598 0.00018 0.67329 -0.73937 -0.00047 0.72246 0.52579 -0.44899 0.73536 0.51102 -0.44509 0.78420 0.59050 -0.19063 0.77877 0.59570 -0.19660 0.73749 0.50314 -0.45051 0.86835 0.47394 -0.14612 0.69725 0.25192 -0.67110 0.85683 0.27518 -0.43602 0.93821 0.30132 -0.17023 0.92192 0.33250 -0.19878 0.85617 0.26132 -0.44574 0.69777 0.21297 -0.68393 0.75711 0.13830 -0.63848 0.71610 0.04952 -0.69624 0.89780 0.00000 -0.44040 0.89780 0.00000 -0.44040 0.73062 0.00000 -0.68279 0.79427 0.60756 -0.00009 0.79597 0.60534 0.00009 0.87777 0.47908 -0.00009 0.93503 0.35448 0.00850 0.94065 0.33926 0.00847 0.89668 0.44268 0.00142 0.98189 0.18945 -0.00051 0.98228 0.18741 -0.00039 0.99809 0.06144 -0.00571 1.00000 0.00130 0.00031 0.99786 -0.06535 0.00030 0.02010 0.99979 -0.00262 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 -0.99986 0.01651 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 0.00000 1.00000 0.69946 0.68907 0.18956 0.22891 0.89330 0.38681 0.96248 0.21083 0.17081 0.95946 0.21276 0.18488 0.69693 0.54133 0.47038 0.36003 0.72476 0.58745 0.30851 0.71817 0.62374 0.69716 0.54127 0.47010 0.96751 0.14650 0.20605 0.21934 0.56453 0.79573 0.95759 0.09723 0.27122 0.96142 0.10177 0.25557 0.69721 0.26520 0.66601 0.69718 0.26518 0.66605 0.30072 0.32233 0.89759 0.34441 0.34727 0.87223 0.96702 0.01852 0.25402 0.22851 0.07066 0.97097 0.69718 -0.07020 0.71345 0.95018 -0.06188 0.30550 0.96407 -0.02601 0.26437 0.36233 -0.09132 0.92757 0.69714 -0.07024 0.71349 0.25693 -0.19200 0.94717 0.96537 -0.11886 0.23224 0.69711 -0.38978 0.60175 0.95840 -0.15517 0.23956 0.69719 -0.38969 0.60172 0.42922 -0.41142 0.80405 0.25228 -0.52600 0.81221 0.22867 -0.66008 0.71554 0.96700 -0.17269 0.18735 0.69715 -0.62243 0.35577 0.96242 -0.23105 0.14269 0.95943 -0.24477 0.13991 0.69712 -0.62246 0.35577 0.36001 -0.79374 0.49028 0.30840 -0.82588 0.47203 0.21950 -0.93736 0.27051 -0.95765 -0.28792 0.00238 -0.69707 -0.71635 0.03043 -0.96752 -0.24290 0.07004 -0.21950 -0.93736 0.27051 -0.30839 -0.82588 0.47203 -0.36001 -0.79374 0.49028 -0.69712 -0.62246 0.35577 -0.95943 -0.24477 0.13991 -0.96242 -0.23105 0.14269 -0.69715 -0.62243 0.35577 -0.96700 -0.17269 0.18735 -0.22867 -0.66008 0.71554 -0.25228 -0.52600 0.81221 -0.42922 -0.41142 0.80405 -0.69719 -0.38969 0.60172 -0.95840 -0.15517 0.23956 -0.69711 -0.38978 0.60175 -0.96537 -0.11886 0.23224 -0.25693 -0.19200 0.94717 -0.69714 -0.07024 0.71349 -0.36233 -0.09132 0.92757 -0.96407 -0.02601 0.26437 -0.95018 -0.06188 0.30550 -0.69718 -0.07020 0.71345 -0.22851 0.07066 0.97097 -0.96702 0.01852 0.25402 -0.34441 0.34727 0.87223 -0.30072 0.32233 0.89759 -0.69718 0.26518 0.66605 -0.69721 0.26520 0.66601 -0.96142 0.10177 0.25557 -0.95759 0.09723 0.27122 -0.21934 0.56453 0.79573 -0.96751 0.14650 0.20605 -0.69716 0.54127 0.47010 -0.30851 0.71817 0.62374 -0.36003 0.72476 0.58745 -0.69693 0.54133 0.47038 -0.95946 0.21276 0.18488 -0.96248 0.21083 0.17081 -0.22891 0.89330 0.38681 -0.96702 0.23373 0.10120 -0.69946 0.68907 0.18956 -0.44469 0.87275 0.20141 -0.15007 0.94757 0.28211 -0.42958 0.89466 0.12265 -0.95018 0.30880 0.04245 -0.69362 0.69364 0.19431 -0.98747 0.15637 0.02141 -0.84480 0.43042 0.31789 -0.00000 -0.96534 -0.26100 -0.00000 -0.96534 -0.26100 -0.00000 -0.99996 0.00841 -0.00000 -0.99996 0.00841 -0.00000 -0.96079 0.27727 -0.00000 -0.96079 0.27727 -0.00000 -0.85078 0.52551 -0.00000 -0.85078 0.52551 -0.00000 -0.67805 0.73502 0.00000 -0.67805 0.73502 0.00000 -0.45551 0.89023 0.00000 -0.45551 0.89023 0.00000 -0.19866 0.98007 0.00000 -0.19866 0.98007 -0.00000 0.07258 0.99736 0.00000 0.07258 0.99736 0.00000 0.33797 0.94116 -0.00000 0.33797 0.94116 -0.00000 0.57862 0.81559 0.00000 0.57862 0.81559 0.00000 0.77686 0.62968 0.00000 0.77686 0.62968 0.00000 0.91766 0.39736 0.00000 0.91766 0.39736 0.00000 0.99073 0.13583 0.00000 0.99073 0.13583 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.97499 0.22226 -0.00000 -0.92453 0.38110 0.90226 -0.43116 0.00574 0.97649 -0.21358 0.02928 0.97612 -0.21350 0.04000 0.94802 -0.31308 0.05686 0.99635 -0.05341 0.06661 0.97763 -0.19024 0.08966 0.99134 -0.11130 0.06976 0.99120 -0.11128 0.07172 0.99558 -0.02453 0.09061 0.99409 -0.06510 0.08683 0.99589 -0.01501 0.08933 0.99520 -0.01500 0.09672 0.99424 0.06120 0.08796 0.99554 0.01078 0.09370 0.99338 0.08180 0.08071 0.99256 0.08173 0.09020 0.97998 0.18697 0.06840 0.99552 0.05444 0.07731 0.96826 0.24794 0.03155 0.97796 0.19817 0.06582 0.89663 0.44266 -0.01036 0.97777 0.19813 0.06861 0.14700 -0.98914 0.00021 0.24807 -0.96831 -0.02902 0.07172 -0.99371 0.08595 0.14963 -0.98874 -0.00030 0.14904 -0.98882 -0.00554 0.28639 -0.95770 -0.02796 0.34030 -0.93819 0.06320 0.56248 -0.82680 0.00516 0.50451 -0.86193 0.05048 0.53463 -0.84366 -0.04914 0.51263 -0.85823 -0.02566 0.62265 -0.78225 -0.01980 0.64109 -0.76740 0.01036 0.79702 -0.60172 -0.05190 0.74900 -0.66246 -0.01212 0.74880 -0.66228 0.02629 0.91538 -0.40230 0.01547 0.61539 -0.78641 0.05336 0.57003 -0.81556 0.09967 0.12475 -0.87586 0.46616 0.51875 -0.85477 -0.01612 0.37649 -0.90862 0.18073 0.32485 -0.92285 0.20694 0.13312 -0.88748 0.44120 0.09621 -0.88767 0.45032 0.31482 -0.94120 0.12258 0.06742 -0.90426 0.42164 0.08306 -0.90964 0.40702 0.17554 -0.96597 0.18998 0.02220 -0.90647 0.42168 0.16166 -0.98259 -0.09158 0.06493 -0.99436 -0.08387 0.07172 -0.99366 -0.08660 0.20896 -0.97695 -0.04364 0.24766 -0.96673 -0.06404 0.60929 -0.79232 0.03169 0.62268 -0.78228 0.01757 0.68177 -0.73156 -0.00376 0.47456 -0.88001 -0.01928 0.56160 -0.82551 -0.05591 0.40991 -0.90871 -0.07890 0.28626 -0.95728 -0.04085 0.79561 0.60506 -0.03020 0.93501 0.35447 -0.01016 0.93521 0.35396 -0.00997 0.93524 0.35385 0.01100 0.75898 0.65084 0.01887 0.77910 -0.62681 0.01059 0.77326 -0.63409 0.00078 0.85470 -0.51907 -0.00700 0.91546 -0.40240 0.00325 -0.00000 1.00000 0.00000 0.10310 0.99467 -0.00009 0.13972 0.99019 -0.00302 0.30561 0.95215 0.00160 0.40823 0.91287 -0.00410 0.49533 0.86870 0.00126 0.64764 0.76194 -0.00322 0.66439 0.74739 -0.00132 0.70513 0.70908 -0.00097 -0.70513 0.70908 -0.00097 -0.66439 0.74739 -0.00132 -0.64764 0.76194 -0.00322 -0.49533 0.86870 0.00126 -0.40823 0.91287 -0.00410 -0.30561 0.95215 0.00160 -0.13972 0.99019 -0.00302 -0.10310 0.99467 -0.00009 0.00000 1.00000 0.00000 -0.91546 -0.40240 0.00325 -0.85470 -0.51907 -0.00700 -0.77326 -0.63409 0.00078 -0.77910 -0.62681 0.01059 -0.75898 0.65084 0.01887 -0.93524 0.35385 0.01100 -0.93521 0.35396 -0.00997 -0.93501 0.35447 -0.01016 -0.79561 0.60506 -0.03020 -0.28626 -0.95728 -0.04085 -0.40991 -0.90871 -0.07890 -0.56160 -0.82551 -0.05591 -0.47456 -0.88001 -0.01928 -0.68177 -0.73156 -0.00376 -0.62268 -0.78228 0.01757 -0.60929 -0.79232 0.03169 -0.24766 -0.96673 -0.06404 -0.20896 -0.97695 -0.04364 -0.07172 -0.99365 -0.08669 -0.06477 -0.99437 -0.08389 -0.16161 -0.98253 -0.09231 -0.02214 -0.90647 0.42168 -0.17554 -0.96597 0.18998 -0.08306 -0.90964 0.40702 -0.06742 -0.90426 0.42164 -0.31482 -0.94120 0.12258 -0.09621 -0.88767 0.45032 -0.13312 -0.88748 0.44120 -0.32485 -0.92285 0.20694 -0.37649 -0.90862 0.18073 -0.51875 -0.85477 -0.01612 -0.12475 -0.87586 0.46616 -0.15273 -0.86617 0.47583 -0.41173 -0.87359 0.25948 -0.57003 -0.81556 0.09967 -0.61539 -0.78642 0.05336 -0.43261 -0.86653 0.24894 -0.14765 -0.86322 0.48276 -0.71431 -0.69421 0.08851 -0.67849 -0.72532 0.11649 -0.94257 -0.33229 0.03376 -0.91537 -0.40231 0.01547 -0.74880 -0.66228 0.02629 -0.74900 -0.66246 -0.01212 -0.79702 -0.60172 -0.05190 -0.64109 -0.76740 0.01036 -0.62265 -0.78225 -0.01980 -0.51263 -0.85823 -0.02566 -0.53463 -0.84366 -0.04914 -0.50451 -0.86193 0.05048 -0.56248 -0.82680 0.00516 -0.34030 -0.93819 0.06320 -0.28639 -0.95770 -0.02796 -0.14884 -0.98885 -0.00561 -0.14945 -0.98877 -0.00010 -0.07172 -0.99371 0.08595 -0.24807 -0.96831 -0.02902 -0.14692 -0.98915 -0.00021 -0.97777 0.19813 0.06861 -0.89663 0.44266 -0.01036 -0.97796 0.19817 0.06582 -0.96826 0.24794 0.03155 -0.99552 0.05444 0.07731 -0.97998 0.18697 0.06840 -0.99256 0.08173 0.09020 -0.99338 0.08180 0.08071 -0.99554 0.01078 0.09370 -0.99424 0.06120 0.08796 -0.99520 -0.01500 0.09672 -0.99589 -0.01501 0.08933 -0.99409 -0.06510 0.08683 -0.99558 -0.02453 0.09061 -0.99120 -0.11128 0.07172 -0.99134 -0.11130 0.06976 -0.97763 -0.19024 0.08966 -0.99635 -0.05341 0.06661 -0.94802 -0.31308 0.05686 -0.97612 -0.21350 0.04000 -0.97649 -0.21358 0.02928 -0.90226 -0.43116 0.00574 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.90036 -0.43515 0.00000 0.90036 -0.43515 0.00000 0.00000 -1.00000 -0.00000 1.00000 -0.00000 0.02992 0.99953 -0.00614 -0.04897 0.99855 -0.02238 -0.00000 1.00000 0.00000 -0.00094 0.99999 -0.00305 -0.00000 1.00000 0.00000 0.00167 1.00000 -0.00170 -0.18127 0.92582 -0.33166 -0.33605 0.30453 -0.89125 -0.24187 0.45887 -0.85495 -0.12672 0.90338 -0.40970 -0.10729 0.91905 -0.37927 -0.15739 0.32299 -0.93322 -0.03628 0.93144 -0.36209 -0.98931 0.00059 -0.14580 -0.08645 0.00000 -0.99626 -0.25621 -0.07481 -0.96372 -0.46284 0.61705 -0.63642 -0.12748 0.61787 -0.77588 -0.12905 0.86783 -0.47980 0.52405 0.59562 -0.60877 0.08703 0.87183 -0.48201 0.02729 0.59100 -0.80621 0.08645 0.00000 -0.99626 0.98943 0.00056 -0.14501 -0.00000 -0.07954 -0.99683 -0.00000 0.87515 -0.48385 -0.00000 0.87515 -0.48385 0.03621 0.93145 -0.36205 0.15739 0.32299 -0.93322 0.10729 0.91905 -0.37927 0.12672 0.90337 -0.40970 0.24187 0.45887 -0.85495 0.33605 0.30453 -0.89125 0.18127 0.92582 -0.33166 0.00000 0.99998 -0.00661 -0.00167 1.00000 -0.00170 0.00000 1.00000 -0.00000 0.00094 0.99999 -0.00305 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00938 0.99995 -0.00221 0.00000 1.00000 -0.00000 -0.03447 -0.56461 -0.82463 -0.02257 -0.86820 -0.49570 -0.00000 -1.00000 -0.00000 -0.02658 0.99964 -0.00251 0.00811 0.99992 0.00963 0.40679 -0.91352 -0.00000 -0.99129 0.00002 -0.13166 -0.93308 -0.00133 -0.35966 -0.92096 0.00015 -0.38965 -0.79403 -0.00032 -0.60788 -0.78301 0.00046 -0.62201 -0.60834 -0.00037 -0.79368 -0.59143 0.00050 -0.80636 -0.42313 -0.00028 -0.90607 -0.36047 0.00144 -0.93277 -0.25804 -0.00054 -0.96613 -0.11987 0.00096 -0.99279 -0.00342 0.94046 0.33987 0.10258 0.95600 0.27486 -0.54107 -0.72740 -0.42205 -0.54206 -0.72466 -0.42548 -0.54151 -0.72194 -0.43078 -0.56924 -0.75410 -0.32757 -0.66245 -0.49685 -0.56063 -0.35061 -0.80805 -0.47342 -0.84565 -0.40086 -0.35240 -0.38367 0.78835 -0.48095 -0.40881 0.39255 -0.82388 -0.12973 0.97951 -0.15405 -0.49552 -0.46867 -0.73130 -0.42845 -0.22367 -0.87544 0.44674 -0.23178 -0.86412 0.49661 -0.46421 -0.73341 0.23270 0.87645 -0.42153 0.17952 0.79930 -0.57349 0.40881 0.39255 -0.82388 0.38366 0.78835 -0.48095 0.84565 -0.40086 -0.35240 0.33841 -0.82490 -0.45279 0.01364 -0.88159 -0.47182 0.67437 -0.48974 -0.55261 0.58626 -0.73899 -0.33195 0.56054 -0.70950 -0.42709 0.56140 -0.71351 -0.41920 0.56043 -0.71635 -0.41564 -0.06761 0.95887 0.27568 0.11987 0.00096 -0.99279 0.25818 -0.00054 -0.96610 0.36048 0.00146 -0.93277 0.45114 -0.00108 -0.89245 0.59133 -0.00033 -0.80643 0.59343 -0.00043 -0.80488 0.78301 0.00046 -0.62201 0.79403 -0.00032 -0.60788 0.92096 0.00015 -0.38965 0.93308 -0.00133 -0.35966 0.99129 0.00002 -0.13166 -0.40679 -0.91352 0.00000 -0.00625 -0.86521 -0.50136 -0.00000 -0.87912 -0.47660 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 0.00000 -1.00000 -0.11875 -0.67600 -0.72728 -0.69945 -0.56446 -0.43835 -0.73008 -0.52935 -0.43217 -0.79534 -0.57614 -0.18840 -0.73749 -0.50314 -0.45051 -0.66333 -0.36884 -0.65111 -0.68186 -0.46553 -0.56422 -0.69725 -0.25192 -0.67110 -0.93527 -0.30038 -0.18722 -0.85683 -0.27518 -0.43602 -0.70722 -0.14967 -0.69097 -0.71631 -0.21863 -0.66264 -0.85617 -0.26132 -0.44574 -0.71610 -0.04952 -0.69624 -0.59927 -0.74831 -0.28445 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -0.63379 -0.75998 -0.14402 -0.65889 -0.73806 -0.14536 -0.62639 -0.76482 -0.15062 0.62639 -0.76482 -0.15062 0.65889 -0.73806 -0.14536 -1.00000 0.00000 0.00000 0.59715 -0.78261 -0.17586 0.62227 -0.69937 -0.35166 0.71610 -0.04952 -0.69624 0.85617 -0.26132 -0.44574 0.71631 -0.21863 -0.66264 0.70722 -0.14967 -0.69097 0.85683 -0.27518 -0.43602 0.93527 -0.30038 -0.18722 0.69725 -0.25192 -0.67110 0.68186 -0.46553 -0.56422 0.66333 -0.36884 -0.65111 0.73749 -0.50314 -0.45051 0.79534 -0.57614 -0.18840 0.73008 -0.52935 -0.43217 0.75435 -0.49922 -0.42630 -0.00000 -1.00000 0.00000 0.00106 -0.99996 0.00881 0.02538 -0.99967 0.00267 0.79359 -0.60845 -0.00012 0.79427 -0.60756 -0.00018 0.85472 -0.51909 0.00009 0.87777 -0.47908 -0.00121 0.90227 -0.43117 0.00073 0.94069 -0.33927 -0.00095 0.94956 -0.31358 0.00033 0.98159 -0.19101 -0.00041 0.98148 -0.19157 -0.00037 0.86835 -0.47394 -0.14612 0.92761 -0.33456 -0.16616 0.28626 -0.95811 0.00941 0.06124 -0.99812 0.00082 -1.00000 -0.00000 0.00000 0.77914 -0.62684 0.00328 0.00000 -0.98059 -0.19609 0.07625 -0.98818 -0.13301 0.67329 -0.73937 -0.00375 0.68177 -0.73156 -0.00422 0.51266 -0.85845 -0.01557 0.60949 -0.79259 -0.01799 0.28596 -0.95726 -0.04336 0.48386 -0.87340 -0.05531 0.02544 -0.99072 -0.13349 0.19812 -0.97716 -0.07687 0.97088 -0.18950 -0.14654 0.78235 -0.59845 -0.17260 0.48258 -0.87463 -0.04614 -0.48258 -0.87464 -0.04614 -0.78235 -0.59845 -0.17260 -0.97088 -0.18950 -0.14654 -0.19812 -0.97716 -0.07687 -0.02544 -0.99072 -0.13349 -0.48386 -0.87340 -0.05531 -0.28596 -0.95726 -0.04336 -0.60949 -0.79259 -0.01799 -0.51266 -0.85845 -0.01557 -0.68177 -0.73156 -0.00422 -0.67329 -0.73937 -0.00375 -0.07616 -0.98818 -0.13301 -0.00000 -0.98059 -0.19609 -0.77914 -0.62684 0.00328 0.20395 -0.06686 -0.97670 1.00000 0.00000 -0.00000 -0.06124 -0.99812 0.00082 -0.28626 -0.95811 0.00941 -0.92761 -0.33456 -0.16616 -0.86835 -0.47394 -0.14612 -0.98148 -0.19157 -0.00037 -0.98159 -0.19101 -0.00041 -0.94956 -0.31358 0.00033 -0.94069 -0.33927 -0.00095 -0.90227 -0.43117 0.00073 -0.87777 -0.47908 -0.00121 -0.85472 -0.51908 0.00009 -0.79427 -0.60756 -0.00018 -0.79359 -0.60845 -0.00012 0.00062 -0.06808 -0.99768 -0.00020 -0.68088 -0.73240 -0.00000 -0.67931 -0.73385 -0.02538 -0.99967 0.00267 -0.00106 -0.99996 0.00881 -0.00000 -0.99986 0.01651 0.00000 -0.94394 -0.33011 -0.00000 -0.94394 -0.33011 -0.26435 -0.91036 -0.31837 -0.29878 -0.91958 -0.25516 -0.36744 -0.83266 -0.41433 -0.64066 -0.69026 -0.33630 -0.69571 -0.59806 -0.39790 -0.70567 -0.70569 -0.06343 -0.69377 -0.71869 -0.04660 -0.88605 -0.45155 -0.10496 -0.94887 -0.30419 -0.08435 -0.93636 -0.34017 -0.08666 -0.96824 -0.21178 -0.13291 -0.96453 -0.24918 -0.08715 -0.98754 -0.15637 -0.01756 -0.96795 -0.24613 0.04991 -0.30897 -0.95094 0.01571 -0.19818 -0.96944 0.14457 -0.64480 -0.76159 -0.06484 -0.80014 -0.59240 -0.09401 -0.69629 -0.69631 0.17415 -0.88983 -0.45348 0.05057 -0.99712 -0.07579 0.00000 -0.96339 -0.25512 0.08248 -0.98187 -0.15548 -0.10845 -0.99492 -0.04386 0.09057 -0.99589 -0.02453 0.08723 -0.99566 -0.00074 0.09309 -0.99566 0.00045 0.09303 -0.99594 0.01078 0.08941 -0.99606 0.00113 0.08868 -0.99596 -0.00422 0.08966 -0.01576 -0.81730 0.57599 -0.00007 -0.81918 0.57353 0.00019 -0.81917 0.57355 0.00007 -0.81914 0.57359 -0.00016 -0.81916 0.57357 0.00016 -0.81915 0.57358 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00001 0.00000 1.00000 0.00001 -0.00000 1.00000 -0.10686 0.99427 0.00021 -0.10691 0.99427 0.00051 -0.10310 0.99467 0.00036 -0.31502 0.94908 0.00033 -0.30561 0.95216 0.00114 -0.54640 0.83753 0.00037 -0.49532 0.86869 0.00608 -0.73383 0.67933 0.00088 -0.66442 0.74733 0.00680 -0.29659 -0.76863 0.56678 -0.62243 -0.62224 0.47476 -0.84125 -0.41735 0.34367 -0.97445 -0.15100 0.16627 -0.18468 -0.82157 0.53937 -0.52793 -0.74792 0.40237 -0.51590 -0.74782 0.41787 -0.79345 -0.56953 0.21466 -0.77990 -0.57721 0.24203 -0.94860 -0.31649 -0.00114 -0.13722 -0.84064 0.52392 -0.16245 -0.85018 0.50080 -0.46619 -0.82821 0.31103 -0.46054 -0.83055 0.31318 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.15641 0.98761 -0.01249 -0.43461 0.90058 0.00827 -0.45395 0.89092 0.01409 -0.56909 0.82226 -0.00398 -0.73529 0.67767 0.01073 -0.70710 0.70711 0.00185 -0.88271 0.46992 -0.00184 -0.89102 0.45397 0.00134 -0.98629 0.16504 -0.00142 -0.98769 0.15640 0.00000 0.63460 -0.66563 0.39270 0.63436 -0.66518 0.39385 0.72560 -0.52027 0.45035 0.68535 -0.47470 0.55223 0.72614 -0.39663 0.56161 0.68473 -0.33252 0.64852 0.72616 -0.25021 0.64038 0.68424 -0.17252 0.70856 0.72663 -0.08900 0.68124 0.68414 -0.00184 0.72935 0.72662 0.07718 0.68269 0.68429 0.16795 0.70960 0.73343 0.25027 0.63201 0.68191 0.33078 0.65237 0.50247 0.42166 0.75480 0.79620 -0.45746 0.39598 0.71150 -0.40537 0.57398 0.77296 -0.33970 0.53585 0.73978 -0.24487 0.62671 0.77536 -0.21037 0.59545 0.75248 -0.08532 0.65307 0.77897 -0.06406 0.62378 0.75300 0.07392 0.65386 0.77803 0.08772 0.62207 0.75616 0.19727 0.62394 0.66429 0.26477 0.69901 0.24972 -0.78683 0.56439 0.13613 -0.87777 0.45933 0.11798 -0.84918 0.51476 -0.06009 -0.98988 0.12857 0.23889 -0.95596 0.17049 0.27051 -0.84078 0.46894 0.49605 -0.83495 0.23833 0.50274 -0.79627 0.33645 0.36695 -0.74608 0.55562 0.51142 -0.57864 0.63532 0.47211 -0.57465 0.66850 0.49937 -0.42215 0.75659 0.55746 -0.37879 0.73875 0.46738 -0.28853 0.83565 0.57126 -0.19417 0.79747 0.47014 -0.13561 0.87211 0.50809 0.02010 0.86107 0.55298 -0.00210 0.83319 0.50233 0.17192 0.84741 0.55640 0.19138 0.80858 0.48927 0.29566 0.82049 0.37156 0.44143 0.81675 0.49467 0.42090 0.76036 -0.07970 -0.93736 0.33913 -0.06820 -0.95935 0.27384 -0.21807 -0.95055 0.22112 -0.06791 -0.98506 0.15826 0.00000 -0.99987 0.01593 -0.03964 -0.95154 0.30497 0.01193 0.52427 0.85147 -0.00000 -0.85957 -0.51102 -0.00000 -0.85957 -0.51102 -0.96142 -0.27485 0.01168 -0.30116 -0.95354 0.00802 -0.34472 -0.93786 0.03984 -0.69707 -0.71635 0.03043 -0.22886 -0.93972 -0.25408 -0.96701 -0.24590 -0.06650 -0.95011 -0.26803 -0.15951 -0.94563 -0.27551 -0.17284 -0.95556 -0.25147 -0.15383 -0.69977 -0.65778 -0.27864 -0.37006 -0.83833 -0.40032 -0.64017 -0.69253 -0.33254 -0.27651 -0.82605 -0.49110 -0.99615 0.05447 0.06865 -0.98889 0.13229 0.06784 -0.96758 0.24929 0.04058 -0.93111 0.36112 0.05125 -0.75833 0.65140 0.02465 -0.83600 0.54855 0.01404 0.00000 1.00000 -0.00000 -0.18465 -0.80642 0.56178 -0.53029 -0.68737 0.49630 -0.80208 -0.47156 0.36647 -0.96387 -0.19129 0.18539 0.96386 -0.19129 0.18540 0.80208 -0.47156 0.36647 0.53029 -0.68737 0.49630 0.18466 -0.80774 0.55987 -0.00000 1.00000 -0.00000 0.83600 0.54855 0.01404 0.75833 0.65140 0.02465 0.93111 0.36112 0.05125 0.96758 0.24929 0.04058 0.98889 0.13229 0.06784 0.99615 0.05447 0.06865 0.27651 -0.82605 -0.49110 0.64017 -0.69253 -0.33254 0.37007 -0.83833 -0.40032 0.69978 -0.65778 -0.27864 0.93015 -0.32185 -0.17675 0.96424 -0.24057 -0.11123 0.95011 -0.26803 -0.15951 0.96701 -0.24590 -0.06650 0.22886 -0.93972 -0.25408 0.69707 -0.71635 0.03043 0.34472 -0.93786 0.03984 0.30116 -0.95354 0.00802 0.96142 -0.27485 0.01167 0.95765 -0.28791 0.00238 0.69707 -0.71635 0.03043 0.96752 -0.24290 0.07004 0.96702 0.23373 0.10120 0.44469 0.87275 0.20141 0.15007 0.94757 0.28211 0.42958 0.89466 0.12265 0.96712 0.23308 0.10170 0.88684 0.45184 0.09669 0.69363 0.69363 0.19431 0.98747 0.15637 0.02141 -0.04306 0.53891 0.84126 0.03964 -0.95154 0.30497 0.05119 -0.99105 0.12326 0.06791 -0.98506 0.15826 0.06820 -0.95935 0.27384 0.07970 -0.93736 0.33913 -0.49441 0.39951 0.77197 -0.32782 0.43681 0.83770 -0.55640 0.19138 0.80858 -0.48927 0.29566 0.82049 -0.50233 0.17192 0.84741 -0.55298 -0.00210 0.83319 -0.50809 0.02010 0.86107 -0.47014 -0.13561 0.87211 -0.57126 -0.19417 0.79747 -0.46738 -0.28853 0.83565 -0.55746 -0.37879 0.73875 -0.49937 -0.42215 0.75659 -0.47211 -0.57465 0.66850 -0.51142 -0.57864 0.63532 -0.33681 -0.78370 0.52189 -0.28175 -0.75512 0.59196 -0.50274 -0.79627 0.33645 -0.49604 -0.83495 0.23833 -0.27051 -0.84078 0.46894 -0.23889 -0.95596 0.17049 0.06009 -0.98988 0.12857 -0.11798 -0.84918 0.51476 -0.13613 -0.87777 0.45934 -0.66429 0.26477 0.69901 -0.75616 0.19727 0.62394 -0.77803 0.08772 0.62207 -0.75300 0.07392 0.65386 -0.77897 -0.06406 0.62378 -0.75248 -0.08532 0.65307 -0.77536 -0.21037 0.59545 -0.73978 -0.24487 0.62671 -0.77296 -0.33970 0.53585 -0.71150 -0.40537 0.57398 -0.79620 -0.45746 0.39598 -0.55052 0.40061 0.73242 -0.68191 0.33078 0.65237 -0.73343 0.25027 0.63201 -0.68429 0.16795 0.70960 -0.72662 0.07718 0.68269 -0.68414 -0.00184 0.72935 -0.72663 -0.08900 0.68124 -0.68424 -0.17252 0.70856 -0.72616 -0.25021 0.64038 -0.68473 -0.33252 0.64852 -0.72614 -0.39663 0.56161 -0.68535 -0.47470 0.55223 -0.72560 -0.52027 0.45035 -0.63436 -0.66518 0.39385 -0.63460 -0.66563 0.39270 0.98769 0.15640 -0.00000 0.98629 0.16504 -0.00142 0.89102 0.45397 0.00134 0.88271 0.46992 -0.00184 0.70710 0.70711 0.00185 0.73529 0.67767 0.01073 0.56909 0.82227 -0.00398 0.45395 0.89092 0.01408 0.43460 0.90058 0.00827 0.15641 0.98761 -0.01249 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 0.15273 -0.86617 0.47583 0.41173 -0.87359 0.25948 0.43261 -0.86653 0.24894 0.14765 -0.86322 0.48276 0.46055 -0.83055 0.31318 0.46618 -0.82821 0.31103 0.16245 -0.85018 0.50080 0.71431 -0.69421 0.08851 0.67849 -0.72532 0.11649 0.13722 -0.84064 0.52392 0.94860 -0.31649 -0.00114 0.79507 -0.56250 0.22686 0.77632 -0.58631 0.23146 0.51589 -0.74782 0.41787 0.52793 -0.74792 0.40237 0.18468 -0.82157 0.53937 0.97445 -0.15100 0.16627 0.84126 -0.41735 0.34367 0.62243 -0.62224 0.47476 0.33025 -0.76039 0.55924 0.66442 0.74733 0.00681 0.73383 0.67933 0.00088 0.49532 0.86869 0.00608 0.54640 0.83753 0.00037 0.30561 0.95216 0.00114 0.31502 0.94908 0.00033 0.10310 0.99467 0.00036 0.10691 0.99427 0.00051 0.10687 0.99427 0.00021 0.94257 -0.33229 0.03376 -0.00000 -0.00000 1.00000 -0.00001 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00016 -0.81915 0.57358 0.00016 -0.81916 0.57357 -0.00007 -0.81914 0.57359 -0.00019 -0.81917 0.57355 0.00008 -0.81918 0.57353 0.03478 -0.81474 0.57878 0.99596 -0.00422 0.08966 0.99606 0.00113 0.08868 0.99594 0.01078 0.08941 0.99566 0.00045 0.09303 0.99566 -0.00074 0.09309 0.99589 -0.02453 0.08723 0.99492 -0.04386 0.09057 0.99712 -0.07579 0.00000 0.98187 -0.15548 -0.10845 0.96339 -0.25512 0.08248 0.88983 -0.45348 0.05057 0.69629 -0.69631 0.17415 0.80014 -0.59240 -0.09401 0.64480 -0.76159 -0.06484 0.19818 -0.96944 0.14457 0.30897 -0.95094 0.01571 0.95817 -0.28538 0.02161 0.98726 -0.15633 -0.02955 0.96453 -0.24916 -0.08717 0.96824 -0.21178 -0.13291 0.96527 -0.22815 -0.12724 0.92566 -0.35400 -0.13359 0.88605 -0.45155 -0.10496 0.69377 -0.71869 -0.04660 0.70567 -0.70569 -0.06343 0.69571 -0.59806 -0.39790 0.64066 -0.69026 -0.33630 0.36744 -0.83266 -0.41433 0.29878 -0.91958 -0.25516 0.26435 -0.91036 -0.31837 -1.00000 -0.00000 0.00000 -1.00000 0.00003 0.00003 -1.00000 -0.00044 0.00026 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.45492 -0.69848 -0.55242 0.45573 -0.69856 -0.55166 0.62626 -0.65836 -0.41756 0.59609 -0.67308 -0.43777 0.39819 -0.76716 -0.50290 -0.43938 -0.71403 -0.54507 -0.60326 -0.71049 -0.36234 -0.51410 -0.73917 -0.43513 -0.45554 -0.75926 -0.46477 -0.39950 -0.78139 -0.47941 -0.00634 -0.89015 -0.45563 -0.00005 -0.87655 -0.48130 -0.00000 -0.81914 0.57360 -0.00019 -0.81919 0.57352 0.00014 -0.81912 0.57362 -0.00014 -0.81916 0.57357 0.00019 -0.81919 0.57352 -0.00014 -0.81912 0.57362 0.00014 -0.81916 0.57357 -0.68186 0.46553 -0.56422 -0.66333 0.36884 -0.65111 0.66333 0.36884 -0.65111 0.68186 0.46553 -0.56422 -0.98563 0.00128 -0.16894 0.98583 0.00128 -0.16773 -0.27402 0.79933 -0.53477 0.52064 0.85377 -0.00301 0.04210 -0.57464 -0.81732 0.11996 -0.67436 -0.72860 + + + + + + + + + + + + + + +

4 0 5 0 6 0 3 1 0 1 8 1 13 2 21 2 14 2 12 3 13 3 14 3 20 4 21 4 13 4 12 5 15 5 13 5 19 6 18 6 16 6 20 7 18 7 21 7 19 8 17 8 18 8 18 9 17 9 21 9 30 10 31 10 32 10 33 11 30 11 32 11 44 12 45 12 1 12 2 13 1 13 45 13 45 14 46 14 2 14 2 15 46 15 47 15 48 16 2 16 47 16 47 17 49 17 48 17 50 18 48 18 49 18 50 19 49 19 51 19 52 20 50 20 51 20 52 21 51 21 53 21 3 22 52 22 53 22 60 23 63 23 62 23 64 24 63 24 60 24 59 25 64 25 60 25 65 26 62 26 63 26 66 27 67 27 65 27 63 28 66 28 65 28 66 29 63 29 64 29 64 30 48 30 50 30 68 31 64 31 50 31 64 32 68 32 66 32 69 33 67 33 66 33 50 34 52 34 68 34 70 35 66 35 68 35 68 36 52 36 3 36 68 37 3 37 72 37 68 38 72 38 70 38 73 39 70 39 72 39 74 40 75 40 43 40 42 41 74 41 43 41 4 42 75 42 74 42 74 43 76 43 4 43 4 44 6 44 77 44 77 45 78 45 35 45 78 46 79 46 35 46 81 47 30 47 33 47 33 48 41 48 81 48 82 49 81 49 41 49 41 50 40 50 82 50 83 51 8 51 84 51 38 52 0 52 3 52 83 53 3 53 8 53 82 54 40 54 39 54 82 55 39 55 38 55 9 56 3 56 83 56 72 57 3 57 9 57 9 58 85 58 72 58 85 59 86 59 72 59 73 60 72 60 86 60 61 61 62 61 65 61 65 62 67 62 61 62 67 63 69 63 58 63 56 64 58 64 69 64 69 65 71 65 56 65 57 66 56 66 71 66 71 67 70 67 57 67 54 68 57 68 70 68 70 69 73 69 54 69 55 70 54 70 73 70 73 71 86 71 55 71 80 72 55 72 86 72 86 73 85 73 80 73 85 74 9 74 80 74 80 75 9 75 10 75 9 76 83 76 10 76 83 77 84 77 10 77 87 78 84 78 8 78 8 79 0 79 87 79 37 80 38 80 39 80 82 81 38 81 53 81 38 82 3 82 53 82 59 83 2 83 64 83 48 84 64 84 2 84 131 85 28 85 115 85 120 86 115 86 22 86 141 87 126 87 29 87 95 88 126 88 141 88 92 89 89 89 26 89 94 90 24 90 93 90 25 91 24 91 94 91 91 92 24 92 25 92 27 93 24 93 91 93 90 94 27 94 91 94 27 95 90 95 97 95 90 96 124 96 97 96 124 97 90 97 125 97 109 98 125 98 90 98 125 99 109 99 122 99 108 100 122 100 109 100 122 101 108 101 123 101 110 102 123 102 108 102 123 103 110 103 121 103 112 104 121 104 110 104 114 105 118 105 112 105 118 106 114 106 117 106 91 107 107 107 90 107 107 108 91 108 25 108 107 109 25 109 29 109 25 110 94 110 29 110 95 111 141 111 140 111 94 112 92 112 29 112 29 113 92 113 26 113 29 114 26 114 141 114 94 115 93 115 92 115 95 116 139 116 96 116 138 117 96 117 139 117 138 118 149 118 96 118 99 119 145 119 98 119 100 120 145 120 99 120 104 121 100 121 101 121 104 122 101 122 102 122 106 123 104 123 103 123 104 124 106 124 105 124 137 125 136 125 106 125 106 126 136 126 105 126 90 127 107 127 109 127 111 128 109 128 107 128 111 129 107 129 29 129 111 130 29 130 127 130 109 131 111 131 113 131 129 132 111 132 127 132 110 133 113 133 112 133 115 134 113 134 111 134 111 135 129 135 115 135 115 136 129 136 131 136 113 137 115 137 116 137 116 138 114 138 113 138 113 139 114 139 112 139 114 140 116 140 117 140 120 141 119 141 115 141 115 142 119 142 116 142 119 143 117 143 116 143 29 144 126 144 127 144 127 145 126 145 128 145 127 146 128 146 129 146 129 147 128 147 130 147 129 148 130 148 131 148 132 149 131 149 130 149 131 150 132 150 28 150 28 151 132 151 133 151 134 152 22 152 133 152 133 153 22 153 28 153 135 154 22 154 134 154 147 155 149 155 138 155 149 156 147 156 148 156 142 157 144 157 143 157 31 158 146 158 148 158 30 159 146 159 31 159 146 160 149 160 148 160 150 161 151 161 152 161 146 162 153 162 162 162 146 163 162 163 157 163 164 164 163 164 162 164 190 165 188 165 189 165 176 166 190 166 175 166 188 167 169 167 167 167 191 168 169 168 188 168 188 169 190 169 191 169 192 170 176 170 177 170 190 171 176 171 192 171 192 172 191 172 190 172 169 173 191 173 171 173 178 174 192 174 177 174 191 175 173 175 171 175 193 176 173 176 191 176 191 177 192 177 193 177 194 178 193 178 192 178 194 179 178 179 179 179 192 180 178 180 194 180 173 181 193 181 174 181 180 182 194 182 179 182 193 183 194 183 195 183 193 184 172 184 174 184 195 185 172 185 193 185 194 186 180 186 196 186 196 187 195 187 194 187 181 188 196 188 180 188 172 189 195 189 170 189 195 190 196 190 197 190 197 191 170 191 195 191 198 192 197 192 196 192 198 193 181 193 182 193 196 194 181 194 198 194 183 195 198 195 182 195 170 196 197 196 168 196 197 197 198 197 199 197 197 198 166 198 168 198 199 199 166 199 197 199 200 200 199 200 198 200 200 201 183 201 184 201 198 202 183 202 200 202 185 203 200 203 184 203 203 204 242 204 244 204 203 205 201 205 202 205 240 206 242 206 203 206 218 207 219 207 202 207 204 208 202 208 220 208 202 209 219 209 220 209 202 210 204 210 203 210 203 211 205 211 240 211 205 212 238 212 240 212 205 213 203 213 204 213 235 214 238 214 205 214 220 215 221 215 204 215 206 216 204 216 222 216 204 217 221 217 222 217 204 218 206 218 205 218 205 219 207 219 235 219 207 220 205 220 206 220 233 221 235 221 207 221 222 222 223 222 206 222 206 223 208 223 207 223 208 224 206 224 223 224 207 225 209 225 233 225 209 226 231 226 233 226 209 227 207 227 208 227 223 228 224 228 208 228 232 229 231 229 209 229 210 230 208 230 225 230 208 231 224 231 225 231 208 232 210 232 209 232 211 233 209 233 210 233 209 234 211 234 232 234 211 235 234 235 232 235 225 236 226 236 210 236 236 237 234 237 211 237 210 238 212 238 211 238 212 239 210 239 227 239 210 240 226 240 227 240 214 241 211 241 212 241 211 242 214 242 236 242 214 243 239 243 236 243 227 244 228 244 212 244 241 245 239 245 214 245 212 246 213 246 214 246 213 247 212 247 230 247 212 248 245 248 230 248 212 249 228 249 245 249 214 250 215 250 241 250 214 251 213 251 215 251 243 252 241 252 229 252 241 253 215 253 229 253 187 254 186 254 216 254 217 255 216 255 186 255 186 256 185 256 217 256 218 257 217 257 185 257 185 258 184 258 218 258 219 259 218 259 184 259 184 260 183 260 219 260 220 261 219 261 183 261 183 262 182 262 220 262 221 263 220 263 182 263 182 264 181 264 221 264 222 265 221 265 181 265 181 266 180 266 222 266 223 267 222 267 180 267 180 268 179 268 223 268 224 269 223 269 179 269 179 270 178 270 224 270 225 271 224 271 178 271 178 272 177 272 225 272 226 273 225 273 177 273 177 274 176 274 226 274 227 275 226 275 176 275 176 276 175 276 227 276 228 277 227 277 175 277 175 278 164 278 228 278 245 279 228 279 164 279 240 280 238 280 237 280 242 281 240 281 237 281 241 282 243 282 237 282 244 283 242 283 237 283 245 284 164 284 162 284 162 285 246 285 245 285 296 286 266 286 287 286 296 287 287 287 158 287 249 288 253 288 248 288 253 289 255 289 254 289 253 290 249 290 255 290 250 291 255 291 249 291 254 292 255 292 256 292 257 293 250 293 135 293 255 294 250 294 257 294 257 295 256 295 255 295 256 296 257 296 258 296 134 297 257 297 135 297 259 298 258 298 257 298 257 299 134 299 259 299 133 300 259 300 134 300 258 301 259 301 260 301 261 302 260 302 259 302 259 303 133 303 261 303 132 304 261 304 133 304 260 305 261 305 262 305 261 306 263 306 262 306 264 307 263 307 261 307 264 308 132 308 130 308 261 309 132 309 264 309 266 310 265 310 267 310 268 311 270 311 269 311 268 312 320 312 270 312 265 313 320 313 268 313 268 314 267 314 265 314 271 315 268 315 269 315 267 316 268 316 272 316 273 317 271 317 288 317 268 318 271 318 273 318 268 319 274 319 272 319 273 320 274 320 268 320 275 321 273 321 288 321 274 322 273 322 276 322 273 323 277 323 276 323 273 324 278 324 277 324 273 325 275 325 278 325 253 326 277 326 278 326 283 327 274 327 276 327 284 328 274 328 283 328 161 329 285 329 279 329 274 330 284 330 272 330 284 331 285 331 272 331 286 332 272 332 285 332 285 333 161 333 286 333 160 334 286 334 161 334 272 335 286 335 267 335 287 336 160 336 159 336 286 337 160 337 287 337 287 338 267 338 286 338 158 339 287 339 159 339 267 340 287 340 266 340 270 341 21 341 17 341 320 342 21 342 270 342 269 343 17 343 19 343 269 344 270 344 17 344 275 345 289 345 290 345 288 346 289 346 275 346 291 347 275 347 290 347 288 348 16 348 289 348 271 349 16 349 288 349 271 350 19 350 16 350 269 351 19 351 271 351 128 352 126 352 252 352 130 353 128 353 252 353 130 354 252 354 264 354 252 355 263 355 264 355 251 356 263 356 252 356 247 357 275 357 291 357 247 358 278 358 275 358 247 359 248 359 278 359 248 360 253 360 278 360 149 361 146 361 157 361 149 362 157 362 280 362 149 363 280 363 96 363 96 364 280 364 281 364 96 365 281 365 95 365 95 366 281 366 282 366 126 367 95 367 282 367 126 368 282 368 251 368 126 369 251 369 252 369 53 370 333 370 334 370 53 371 334 371 303 371 53 372 303 372 82 372 82 373 303 373 304 373 81 374 82 374 304 374 81 375 304 375 305 375 30 376 81 376 305 376 30 377 305 377 153 377 30 378 153 378 146 378 337 379 309 379 332 379 338 380 309 380 337 380 338 381 311 381 309 381 338 382 292 382 311 382 334 383 333 383 322 383 333 384 321 384 322 384 49 385 321 385 333 385 49 386 333 386 51 386 51 387 333 387 53 387 317 388 315 388 12 388 315 389 15 389 12 389 315 390 295 390 15 390 295 391 294 391 15 391 292 392 293 392 311 392 295 393 311 393 294 393 311 394 293 394 294 394 317 395 14 395 316 395 317 396 12 396 14 396 320 397 316 397 21 397 316 398 14 398 21 398 319 399 266 399 296 399 158 400 156 400 296 400 296 401 297 401 319 401 297 402 296 402 155 402 296 403 156 403 155 403 314 404 319 404 297 404 155 405 154 405 297 405 298 406 297 406 154 406 297 407 298 407 314 407 299 408 314 408 298 408 312 409 314 409 299 409 154 410 307 410 298 410 300 411 298 411 307 411 298 412 300 412 299 412 299 413 301 413 312 413 301 414 310 414 312 414 301 415 299 415 300 415 307 416 308 416 300 416 306 417 310 417 302 417 310 418 301 418 302 418 331 419 332 419 306 419 332 420 309 420 306 420 313 421 309 421 311 421 309 422 313 422 306 422 313 423 310 423 306 423 312 424 310 424 313 424 311 425 295 425 313 425 313 426 318 426 312 426 318 427 314 427 312 427 318 428 313 428 315 428 313 429 295 429 315 429 319 430 314 430 318 430 315 431 317 431 318 431 318 432 265 432 319 432 265 433 318 433 320 433 318 434 316 434 320 434 318 435 317 435 316 435 266 436 319 436 265 436 324 437 321 437 47 437 321 438 49 438 47 438 321 439 324 439 322 439 324 440 323 440 322 440 325 441 323 441 324 441 47 442 46 442 324 442 326 443 324 443 46 443 324 444 326 444 325 444 327 445 325 445 326 445 46 446 45 446 326 446 328 447 326 447 45 447 326 448 328 448 327 448 45 449 44 449 328 449 329 450 327 450 328 450 328 451 330 451 329 451 330 452 328 452 335 452 328 453 44 453 335 453 331 454 329 454 330 454 335 455 336 455 330 455 332 456 330 456 336 456 330 457 332 457 331 457 336 458 337 458 332 458 349 459 339 459 148 459 148 460 339 460 31 460 31 461 339 461 370 461 339 462 349 462 346 462 370 463 339 463 346 463 374 464 340 464 144 464 341 465 88 465 342 465 343 466 357 466 344 466 343 467 342 467 357 467 341 468 342 468 343 468 343 469 344 469 345 469 345 470 347 470 346 470 344 471 347 471 345 471 343 472 348 472 341 472 138 473 348 473 147 473 349 474 147 474 348 474 349 475 343 475 345 475 348 476 343 476 349 476 147 477 349 477 148 477 346 478 349 478 345 478 359 479 102 479 358 479 354 480 144 480 340 480 351 481 356 481 355 481 357 482 342 482 356 482 356 483 351 483 357 483 344 484 357 484 351 484 362 485 363 485 365 485 364 486 367 486 363 486 365 487 363 487 367 487 366 488 374 488 34 488 5 489 360 489 361 489 351 490 355 490 367 490 367 491 364 491 351 491 344 492 351 492 364 492 346 493 372 493 370 493 32 494 31 494 370 494 371 495 370 495 373 495 370 496 372 496 373 496 370 497 371 497 32 497 33 498 32 498 371 498 373 499 37 499 371 499 344 500 364 500 347 500 364 501 372 501 347 501 372 502 346 502 347 502 373 503 372 503 364 503 37 504 373 504 362 504 373 505 363 505 362 505 373 506 364 506 363 506 37 507 362 507 36 507 355 508 356 508 352 508 368 509 352 509 350 509 34 510 144 510 142 510 341 511 26 511 88 511 141 512 26 512 341 512 104 513 102 513 103 513 101 514 358 514 102 514 358 515 101 515 380 515 100 516 380 516 101 516 380 517 100 517 379 517 99 518 379 518 100 518 379 519 99 519 23 519 98 520 23 520 99 520 23 521 98 521 353 521 375 522 353 522 98 522 353 523 375 523 354 523 354 524 375 524 144 524 93 525 89 525 92 525 88 526 26 526 89 526 350 527 377 527 378 527 350 528 378 528 359 528 358 529 350 529 359 529 380 530 350 530 358 530 376 531 377 531 350 531 376 532 350 532 352 532 88 533 376 533 342 533 341 534 348 534 139 534 348 535 138 535 139 535 341 536 140 536 141 536 376 537 352 537 356 537 356 538 342 538 376 538 365 539 389 539 362 539 389 540 365 540 385 540 37 541 39 541 40 541 37 542 40 542 41 542 371 543 41 543 33 543 37 544 41 544 371 544 36 545 362 545 389 545 389 546 385 546 369 546 369 547 385 547 386 547 389 548 369 548 388 548 381 549 361 549 369 549 361 550 360 550 369 550 369 551 360 551 387 551 369 552 387 552 388 552 87 553 0 553 36 553 34 554 390 554 366 554 383 555 366 555 390 555 390 556 79 556 383 556 11 557 383 557 79 557 79 558 78 558 11 558 384 559 11 559 78 559 78 560 77 560 384 560 381 561 384 561 77 561 77 562 6 562 381 562 361 563 381 563 6 563 6 564 5 564 361 564 4 565 76 565 5 565 368 566 350 566 369 566 369 567 386 567 368 567 37 568 0 568 38 568 36 569 0 569 37 569 34 570 374 570 144 570 352 571 368 571 355 571 54 572 55 572 393 572 393 573 394 573 54 573 393 574 391 574 394 574 395 575 54 575 394 575 395 576 56 576 57 576 54 577 395 577 57 577 58 578 56 578 395 578 59 579 394 579 392 579 394 580 59 580 395 580 60 581 61 581 58 581 395 582 60 582 58 582 60 583 395 583 59 583 62 584 61 584 60 584 55 585 80 585 393 585 58 586 61 586 67 586 7 587 80 587 10 587 393 588 80 588 7 588 393 589 74 589 42 589 74 590 393 590 7 590 106 591 27 591 398 591 398 592 137 592 106 592 121 593 112 593 118 593 97 594 398 594 27 594 398 595 97 595 124 595 117 596 119 596 118 596 119 597 120 597 396 597 396 598 121 598 119 598 119 599 121 599 118 599 397 600 396 600 120 600 120 601 399 601 397 601 121 602 396 602 123 602 125 603 122 603 396 603 396 604 122 604 123 604 396 605 397 605 125 605 397 606 400 606 398 606 398 607 125 607 397 607 125 608 398 608 124 608 34 609 142 609 403 609 375 610 145 610 144 610 143 611 144 611 145 611 137 612 247 612 136 612 400 613 247 613 137 613 400 614 248 614 247 614 401 615 248 615 400 615 248 616 401 616 249 616 399 617 249 617 401 617 249 618 399 618 250 618 399 619 135 619 250 619 22 620 135 620 399 620 400 621 397 621 401 621 397 622 399 622 401 622 145 623 100 623 104 623 145 624 375 624 98 624 103 625 24 625 27 625 247 626 291 626 136 626 143 627 20 627 142 627 18 628 20 628 143 628 136 629 291 629 105 629 105 630 291 630 290 630 105 631 290 631 104 631 104 632 290 632 289 632 145 633 104 633 289 633 145 634 289 634 16 634 145 635 18 635 143 635 145 636 16 636 18 636 399 637 120 637 22 637 400 638 137 638 398 638 106 639 103 639 27 639 74 640 7 640 76 640 391 641 393 641 42 641 392 642 1 642 59 642 35 643 13 643 15 643 35 644 403 644 13 644 35 645 15 645 294 645 35 646 294 646 4 646 4 647 294 647 293 647 75 648 4 648 293 648 75 649 293 649 292 649 43 650 75 650 292 650 13 651 403 651 20 651 403 652 142 652 20 652 338 653 43 653 292 653 367 654 382 654 365 654 76 655 7 655 10 655 79 656 390 656 35 656 35 657 4 657 77 657 394 658 402 658 392 658 391 659 402 659 394 659 1 660 392 660 44 660 392 661 335 661 44 661 336 662 335 662 392 662 392 663 402 663 336 663 337 664 336 664 402 664 402 665 391 665 337 665 391 666 338 666 337 666 391 667 42 667 338 667 42 668 43 668 338 668 382 669 367 669 355 669 355 670 368 670 382 670 386 671 382 671 368 671 403 672 35 672 34 672 390 673 34 673 35 673 152 674 151 674 547 674 547 675 548 675 152 675 404 676 152 676 548 676 404 677 405 677 152 677 406 678 407 678 152 678 406 679 152 679 405 679 406 680 405 680 408 680 409 681 406 681 408 681 409 682 410 682 407 682 406 683 409 683 407 683 411 684 410 684 409 684 408 685 412 685 409 685 409 686 412 686 413 686 409 687 413 687 414 687 415 688 409 688 414 688 415 689 416 689 411 689 409 690 415 690 411 690 407 691 150 691 152 691 417 692 150 692 407 692 418 693 417 693 407 693 410 694 419 694 418 694 407 695 410 695 418 695 410 696 411 696 419 696 416 697 420 697 421 697 416 698 421 698 419 698 411 699 416 699 419 699 331 700 422 700 329 700 327 701 329 701 422 701 422 702 423 702 327 702 327 703 423 703 424 703 325 704 327 704 424 704 424 705 425 705 325 705 325 706 425 706 426 706 418 707 428 707 427 707 427 708 308 708 418 708 417 709 418 709 308 709 307 710 150 710 417 710 308 711 307 711 417 711 307 712 154 712 150 712 429 713 431 713 430 713 430 714 431 714 432 714 433 715 430 715 432 715 245 716 246 716 433 716 432 717 245 717 433 717 434 718 246 718 153 718 305 719 433 719 434 719 153 720 305 720 434 720 430 721 433 721 305 721 305 722 304 722 430 722 429 723 430 723 304 723 304 724 303 724 429 724 435 725 429 725 303 725 303 726 334 726 435 726 438 727 428 727 439 727 439 728 441 728 440 728 441 729 443 729 442 729 443 730 422 730 331 730 444 731 427 731 438 731 438 732 440 732 444 732 302 733 444 733 440 733 440 734 442 734 302 734 306 735 302 735 442 735 442 736 331 736 306 736 308 737 427 737 444 737 444 738 300 738 308 738 444 739 302 739 301 739 300 740 444 740 301 740 445 741 446 741 447 741 447 742 420 742 445 742 448 743 445 743 420 743 416 744 449 744 448 744 420 745 416 745 448 745 413 746 450 746 237 746 450 747 244 747 237 747 449 748 416 748 415 748 449 749 415 749 414 749 449 750 414 750 413 750 449 751 413 751 237 751 243 752 449 752 237 752 230 753 245 753 451 753 230 754 451 754 452 754 213 755 230 755 452 755 213 756 452 756 453 756 213 757 453 757 454 757 215 758 213 758 454 758 454 759 455 759 215 759 229 760 215 760 455 760 455 761 449 761 229 761 243 762 229 762 449 762 437 763 436 763 456 763 457 764 456 764 436 764 436 765 458 765 457 765 459 766 457 766 458 766 458 767 460 767 459 767 461 768 459 768 460 768 460 769 462 769 461 769 463 770 461 770 462 770 462 771 464 771 463 771 465 772 463 772 464 772 464 773 466 773 465 773 467 774 465 774 466 774 466 775 441 775 467 775 467 776 441 776 439 776 428 777 467 777 439 777 436 778 426 778 458 778 460 779 458 779 426 779 426 780 425 780 460 780 462 781 460 781 425 781 425 782 424 782 462 782 464 783 462 783 424 783 424 784 423 784 464 784 466 785 464 785 423 785 423 786 422 786 466 786 466 787 422 787 443 787 466 788 443 788 441 788 456 789 455 789 454 789 454 790 453 790 456 790 468 791 456 791 453 791 429 792 469 792 431 792 469 793 429 793 435 793 469 794 435 794 437 794 468 795 469 795 437 795 437 796 456 796 468 796 457 797 455 797 456 797 459 798 449 798 455 798 457 799 459 799 455 799 448 800 449 800 459 800 459 801 461 801 448 801 445 802 448 802 461 802 461 803 463 803 445 803 446 804 445 804 463 804 465 805 447 805 446 805 463 806 465 806 446 806 420 807 447 807 465 807 465 808 467 808 420 808 421 809 420 809 467 809 428 810 419 810 421 810 467 811 428 811 421 811 468 812 453 812 452 812 452 813 469 813 468 813 431 814 469 814 432 814 469 815 451 815 245 815 432 816 469 816 245 816 469 817 452 817 451 817 418 818 419 818 428 818 216 819 404 819 187 819 548 820 187 820 404 820 201 821 203 821 244 821 470 822 217 822 218 822 202 823 470 823 218 823 470 824 202 824 201 824 216 825 217 825 470 825 244 826 450 826 201 826 201 827 450 827 413 827 201 828 413 828 412 828 408 829 201 829 412 829 201 830 408 830 470 830 470 831 405 831 216 831 470 832 408 832 405 832 404 833 216 833 405 833 325 834 426 834 323 834 426 835 436 835 323 835 323 836 436 836 322 836 322 837 436 837 437 837 334 838 322 838 437 838 334 839 437 839 435 839 246 840 162 840 153 840 427 841 428 841 438 841 438 842 439 842 440 842 440 843 441 843 442 843 331 844 442 844 443 844 254 845 512 845 513 845 509 846 513 846 514 846 517 847 509 847 515 847 527 848 517 848 516 848 163 849 157 849 162 849 251 850 520 850 518 850 251 851 518 851 263 851 263 852 518 852 519 852 262 853 263 853 519 853 528 854 262 854 519 854 260 855 262 855 528 855 548 856 471 856 187 856 473 857 471 857 472 857 473 858 187 858 471 858 474 859 473 859 472 859 472 860 541 860 474 860 474 861 541 861 540 861 474 862 540 862 502 862 501 863 474 863 502 863 187 864 473 864 186 864 473 865 474 865 200 865 200 866 185 866 473 866 473 867 185 867 186 867 474 868 501 868 199 868 199 869 501 869 499 869 199 870 200 870 474 870 166 871 199 871 499 871 498 872 188 872 167 872 189 873 497 873 190 873 190 874 497 874 164 874 190 875 164 875 175 875 188 876 498 876 475 876 475 877 493 877 188 877 188 878 493 878 189 878 500 879 475 879 498 879 535 880 516 880 477 880 476 881 496 881 495 881 523 882 164 882 476 882 476 883 164 883 496 883 495 884 478 884 476 884 478 885 495 885 494 885 480 886 534 886 516 886 516 887 534 887 477 887 482 888 533 888 480 888 480 889 533 889 534 889 533 890 482 890 505 890 484 891 506 891 482 891 482 892 506 892 505 892 506 893 484 893 507 893 486 894 507 894 484 894 507 895 486 895 504 895 488 896 504 896 486 896 504 897 488 897 503 897 490 898 491 898 488 898 488 899 491 899 503 899 491 900 490 900 492 900 490 901 479 901 492 901 518 902 478 902 479 902 478 903 518 903 476 903 476 904 518 904 520 904 476 905 520 905 525 905 525 906 523 906 476 906 478 907 494 907 479 907 492 908 479 908 494 908 481 909 514 909 512 909 481 910 512 910 532 910 531 911 481 911 532 911 481 912 531 912 483 912 530 913 483 913 531 913 483 914 530 914 485 914 529 915 485 915 530 915 485 916 529 916 487 916 528 917 487 917 529 917 487 918 528 918 489 918 519 919 489 919 528 919 516 920 515 920 480 920 480 921 515 921 514 921 481 922 480 922 514 922 480 923 481 923 482 923 483 924 482 924 481 924 482 925 483 925 484 925 485 926 484 926 483 926 484 927 485 927 486 927 487 928 486 928 485 928 486 929 487 929 488 929 489 930 488 930 487 930 488 931 489 931 490 931 519 932 490 932 489 932 490 933 519 933 479 933 518 934 479 934 519 934 500 935 503 935 475 935 475 936 503 936 491 936 475 937 491 937 493 937 493 938 491 938 492 938 493 939 492 939 189 939 189 940 492 940 494 940 189 941 494 941 495 941 189 942 495 942 497 942 497 943 495 943 496 943 497 944 496 944 164 944 499 945 165 945 166 945 498 946 165 946 500 946 501 947 165 947 499 947 500 948 165 948 503 948 533 949 504 949 538 949 538 950 504 950 503 950 504 951 533 951 507 951 505 952 507 952 533 952 507 953 505 953 506 953 508 954 279 954 285 954 285 955 284 955 508 955 283 956 508 956 284 956 279 957 508 957 526 957 508 958 283 958 511 958 511 959 283 959 510 959 511 960 526 960 508 960 277 961 510 961 276 961 276 962 510 962 283 962 526 963 511 963 527 963 513 964 277 964 254 964 277 965 513 965 509 965 277 966 509 966 510 966 511 967 510 967 509 967 517 968 511 968 509 968 511 969 517 969 527 969 512 970 254 970 532 970 514 971 513 971 512 971 515 972 509 972 514 972 517 973 515 973 516 973 282 974 520 974 251 974 520 975 282 975 525 975 281 976 525 976 282 976 525 977 281 977 524 977 280 978 524 978 281 978 524 979 280 979 522 979 157 980 521 980 280 980 280 981 521 981 522 981 157 982 163 982 521 982 277 983 253 983 254 983 523 984 522 984 164 984 522 985 163 985 164 985 522 986 523 986 524 986 525 987 524 987 523 987 279 988 151 988 161 988 526 989 536 989 279 989 279 990 536 990 151 990 536 991 526 991 535 991 527 992 535 992 526 992 535 993 527 993 516 993 260 994 528 994 529 994 530 995 260 995 529 995 260 996 530 996 258 996 258 997 530 997 531 997 532 998 258 998 531 998 258 999 532 999 256 999 254 1000 256 1000 532 1000 533 1001 538 1001 534 1001 542 1002 477 1002 538 1002 538 1003 477 1003 534 1003 543 1004 477 1004 542 1004 545 1005 535 1005 543 1005 543 1006 535 1006 477 1006 535 1007 545 1007 536 1007 536 1008 545 1008 151 1008 547 1009 151 1009 545 1009 544 1010 542 1010 537 1010 537 1011 542 1011 538 1011 537 1012 539 1012 544 1012 544 1013 539 1013 540 1013 544 1014 540 1014 541 1014 472 1015 544 1015 541 1015 542 1016 544 1016 543 1016 546 1017 545 1017 544 1017 544 1018 545 1018 543 1018 544 1019 472 1019 546 1019 546 1020 472 1020 471 1020 546 1021 471 1021 547 1021 546 1022 547 1022 545 1022 548 1023 547 1023 471 1023 24 1024 103 1024 102 1024 24 1025 102 1025 359 1025 24 1026 359 1026 378 1026 24 1027 378 1027 377 1027 24 1028 377 1028 376 1028 24 1029 376 1029 88 1029 88 1030 89 1030 24 1030 5 1031 76 1031 10 1031 5 1032 10 1032 360 1032 10 1033 387 1033 360 1033 10 1034 388 1034 387 1034 10 1035 389 1035 388 1035 10 1036 36 1036 389 1036 36 1037 10 1037 87 1037 84 1038 87 1038 10 1038 89 1039 93 1039 24 1039 239 1040 241 1040 237 1040 236 1041 239 1041 237 1041 234 1042 236 1042 237 1042 232 1043 234 1043 237 1043 231 1044 232 1044 237 1044 231 1045 237 1045 233 1045 233 1046 237 1046 235 1046 235 1047 237 1047 238 1047 165 1048 168 1048 166 1048 165 1049 170 1049 168 1049 165 1050 172 1050 170 1050 165 1051 174 1051 172 1051 165 1052 173 1052 174 1052 165 1053 171 1053 173 1053 165 1054 169 1054 171 1054 165 1055 167 1055 169 1055 165 1056 498 1056 167 1056 165 1057 501 1057 502 1057 165 1058 502 1058 540 1058 165 1059 540 1059 539 1059 165 1060 539 1060 537 1060 165 1061 537 1061 538 1061 165 1062 538 1062 503 1062 381 1063 369 1063 384 1063 11 1064 384 1064 369 1064 11 1065 369 1065 383 1065 366 1066 383 1066 369 1066 366 1067 369 1067 374 1067 379 1068 350 1068 380 1068 23 1069 350 1069 379 1069 23 1070 353 1070 350 1070 353 1071 354 1071 350 1071 340 1072 350 1072 354 1072 340 1073 369 1073 350 1073 340 1074 374 1074 369 1074 150 1075 158 1075 151 1075 150 1076 156 1076 158 1076 150 1077 155 1077 156 1077 150 1078 154 1078 155 1078 151 1079 158 1079 159 1079 151 1080 159 1080 160 1080 151 1081 160 1081 161 1081 66 1082 70 1082 71 1082 66 1083 71 1083 69 1083 108 1084 113 1084 110 1084 108 1085 109 1085 113 1085 1 1086 2 1086 59 1086 22 1087 115 1087 28 1087 139 1088 140 1088 341 1088 95 1089 140 1089 139 1089 365 1090 382 1090 385 1090 382 1091 386 1091 385 1091

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5.dae b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5.dae new file mode 100644 index 0000000..a461aa4 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:31.855069 + 2012-07-23T02:15:31.855082 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -7.17350 6.94911 4.21838 -9.93270 -1.15879 -0.00031 -9.92969 1.15514 -0.00031 -7.45360 6.66578 -0.00031 -6.19669 -7.61001 14.00068 -5.99999 -7.69760 7.99969 -5.93079 -7.72543 8.52069 -5.99999 -7.62085 -1.45521 -6.53730 7.42476 2.97619 -6.00000 7.62007 -1.44611 -5.99999 -0.00089 -0.00031 -4.99999 3.65198 9.71969 -3.55469 -9.23031 23.11969 -3.56699 -8.61560 18.55868 -1.76899 -9.59040 22.63068 -4.59092 -8.80456 23.59968 4.59459 -8.80456 23.59968 1.77266 -9.59040 22.63068 3.57066 -8.61560 18.55868 3.55836 -9.23031 23.11969 0.00406 -8.84559 18.22268 0.00406 -9.69028 22.44568 9.93636 -1.15879 -0.00031 5.00366 3.81254 9.73169 6.00366 -0.00089 -0.00031 6.00366 7.62007 -1.44611 7.14516 6.97814 3.97919 6.00366 -7.62085 -1.45522 9.93336 1.15514 -0.00031 7.45726 6.66578 -0.00031 -4.47209 7.99911 23.99968 -0.92010 7.99911 10.96068 -2.73450 7.99911 10.65468 -5.10259 7.94911 9.74469 -3.99999 -8.00089 9.99969 -5.00999 -7.96456 14.00168 -6.00000 6.94911 4.50619 -5.64640 6.94911 8.25268 -7.17349 6.94911 6.96669 -7.06460 7.04525 7.66968 -6.70469 7.31810 8.43568 -6.02019 7.68741 9.16469 -7.45360 -6.66756 -0.00031 -7.46809 -6.65131 13.99969 -9.91719 -1.28497 23.99968 -9.99999 -0.02064 23.99968 -9.92209 1.24482 23.99968 -9.68389 2.49335 23.99968 -9.63909 2.66125 -0.00031 -8.93994 4.00025 23.99968 -9.11909 4.10304 -0.00031 -8.39959 5.42557 23.99968 -8.38479 5.44841 -0.00031 -7.47299 6.64398 23.99968 -6.00000 -5.49870 -5.79131 -5.99999 -6.96596 -3.90192 -6.00000 -3.36071 -7.26061 -6.00000 -4.50038 -6.61501 -6.00000 -2.24851 -7.67811 -9.41220 -1.47532 -3.03941 -8.06000 -1.20361 -5.79601 -6.00000 -1.13267 -7.91981 -6.00000 -0.00089 -8.00031 -8.06000 1.20183 -5.79601 -9.41220 1.47352 -3.03941 -6.00000 1.13089 -7.91981 -7.35780 3.50247 -5.79601 -6.00000 2.24673 -7.67811 -8.51050 4.28110 -3.03941 -6.00000 3.35892 -7.26061 -6.00000 5.49692 -5.79131 -6.00000 4.49860 -6.61501 -6.62189 6.66578 -3.42181 -6.00000 6.66577 -4.42251 -6.78489 -7.26453 -0.00031 -6.83189 -7.23065 13.99969 -5.99999 -7.69760 -0.00031 -5.71839 -7.80180 9.02269 -5.38550 -7.89522 9.44169 -4.95869 -7.97119 9.75468 -5.99999 -7.34730 -2.89871 -5.57889 7.84294 23.99968 -6.59929 7.38662 23.99968 -6.00000 7.69581 -0.00031 -6.00000 7.69581 2.18159 -6.00000 7.34767 -2.89111 -6.00000 7.07516 -3.64421 -6.00000 7.31252 3.24219 6.00366 6.94911 4.50619 6.00366 7.31252 3.24219 6.00366 6.66577 -4.42252 6.00366 7.34767 -2.89111 6.66886 7.34083 3.17053 6.00366 7.69581 2.18159 6.00366 7.69581 -0.00031 6.60296 7.38662 23.99968 5.58256 7.84294 23.99968 6.00366 -7.18556 -3.39231 4.96236 -7.97119 9.75468 5.38916 -7.89522 9.44169 5.72206 -7.80180 9.02269 5.93446 -7.72543 8.52069 6.00366 -7.69760 7.99968 6.00366 -7.69760 -0.00031 6.20036 -7.61001 14.00068 6.83556 -7.23065 13.99968 6.78856 -7.26453 -0.00031 6.62556 6.66578 -3.42181 6.00366 4.49860 -6.61501 6.00366 5.49692 -5.79131 6.00366 3.35892 -7.26061 8.51416 4.28110 -3.03941 6.00366 2.24673 -7.67812 7.36146 3.50247 -5.79601 6.00366 1.13089 -7.91981 9.41586 1.47352 -3.03941 8.06366 1.20183 -5.79601 6.00366 -0.00089 -8.00031 6.00366 -1.13267 -7.91981 8.06366 -1.20361 -5.79601 9.41586 -1.47532 -3.03941 6.00366 -2.24851 -7.67812 6.00366 -4.50038 -6.61501 6.00366 -3.36071 -7.26061 6.00366 -6.66755 -4.42252 6.00366 -5.49870 -5.79131 7.47666 6.64398 23.99968 8.38846 5.44841 -0.00031 8.40326 5.42557 23.99968 9.12276 4.10304 -0.00031 8.94361 4.00025 23.99968 9.64276 2.66125 -0.00031 9.68756 2.49335 23.99968 9.92576 1.24482 23.99968 10.00366 -0.02064 23.99968 9.92086 -1.28497 23.99968 7.47176 -6.65131 13.99968 7.45726 -6.66756 -0.00031 5.10626 7.94911 9.74469 6.02386 7.68741 9.16469 7.06826 7.04525 7.66968 7.17716 6.94911 6.96669 0.00406 -8.00089 13.99868 3.58286 -8.00089 13.99868 4.00366 -8.00089 9.99969 5.01366 -7.96456 14.00168 0.00366 7.99911 23.99968 2.73816 7.99911 10.65468 0.92376 7.99911 10.96068 4.47576 7.99911 23.99968 -3.99999 -5.02735 37.82068 4.00366 -5.02735 37.82068 -3.99999 -5.00089 39.42268 -4.48079 7.99911 34.49768 -3.53979 -8.82177 32.40168 -2.34909 -9.28970 31.73368 -1.16229 -9.55490 31.35468 4.48446 7.99911 34.49768 0.00346 -9.63919 31.23468 1.16596 -9.55490 31.35468 2.35276 -9.28970 31.73368 3.54346 -8.82177 32.40168 0.00366 7.99911 44.99968 4.46387 7.99911 44.99968 4.00366 6.94911 44.99968 7.00366 -0.00089 44.99968 7.00366 -3.61239 46.59969 7.00366 3.37761 47.04568 7.00366 -3.04855 47.51268 7.00366 2.70194 47.87968 7.00366 -2.25983 48.23969 7.00366 1.82715 48.50168 7.00366 -1.30441 48.72868 7.00366 0.81734 48.86368 7.00366 -0.25282 48.94168 4.00366 6.69274 46.86967 4.00366 5.94276 48.60168 4.00366 4.75370 50.06868 4.00366 3.21449 51.16068 4.00366 1.43786 51.79867 4.00366 -0.44483 51.93568 4.00366 -2.29479 51.56068 4.00366 -3.97553 50.70068 4.00366 -5.36307 49.42068 4.00366 -6.35507 47.81468 4.00366 -6.87828 46.00168 4.00366 -6.89415 44.11368 4.00366 -6.40153 42.29169 6.60256 4.84007 47.50069 5.76706 6.37616 44.99969 5.50366 5.81689 48.00468 6.60256 3.15259 49.44267 5.50366 3.78892 50.33968 6.60256 0.76172 50.39468 5.50366 0.91560 51.48367 6.60256 -1.79926 50.14268 5.50366 -2.16214 51.18068 6.60256 -3.95910 48.74368 5.50366 -4.75780 49.49968 6.60256 -5.23604 46.50967 5.50366 -6.29241 46.81468 -6.59889 -5.34526 43.93867 -5.49999 -6.29241 46.81468 -6.59889 -5.23604 46.50967 -5.49999 -4.75780 49.49968 -6.59889 -3.95910 48.74368 -5.49999 -2.16214 51.18068 -6.59889 -1.79926 50.14268 -5.49999 0.91560 51.48367 -6.59889 0.76172 50.39468 -5.49999 3.78892 50.33968 -6.59889 3.15259 49.44267 -5.49999 5.81689 48.00468 -5.76339 6.37616 44.99968 -6.59889 4.84007 47.50069 -6.42709 5.71247 44.99968 -3.99999 -6.40153 42.29169 -3.99999 -6.89415 44.11368 -3.99999 -6.87828 46.00168 -3.99999 -6.35507 47.81468 -3.99999 -5.36307 49.42068 -3.99999 -3.97553 50.70068 -3.99999 -2.29479 51.56068 -3.99999 -0.44483 51.93568 -3.99999 1.43786 51.79867 -3.99999 3.21449 51.16068 -3.99999 4.75370 50.06868 -3.99999 5.94276 48.60168 -3.99999 6.69274 46.86967 -6.85319 4.87616 44.99968 -4.92709 6.80228 44.99968 -6.99999 -0.25282 48.94168 -6.99999 0.81734 48.86368 -6.99999 -1.30441 48.72868 -6.99999 1.82715 48.50168 -6.99999 -2.25983 48.23969 -6.99999 2.70194 47.87968 -6.99999 -0.00090 44.99968 -6.99999 -3.04855 47.51268 -6.99999 3.37761 47.04568 -6.99999 -3.61239 46.59969 -6.99999 3.80368 46.06168 -6.99999 -3.90969 45.56868 -6.99999 3.94911 44.99968 -6.99999 -3.91855 44.49568 -3.99999 6.94911 44.99968 -4.46019 7.99911 44.99968 8.35526 -5.50089 23.99968 8.73536 -4.87502 23.99968 9.28136 -3.73246 23.99968 9.67876 -2.52910 23.99968 7.43666 6.69810 34.49368 8.31437 5.81849 29.52985 8.89386 -4.46979 29.51968 8.76546 -4.19563 35.80267 9.26076 -2.79232 29.51968 8.91906 -2.27439 35.04568 9.45096 -1.09815 29.51968 8.96676 -0.33818 35.04568 9.47666 0.60681 29.51968 8.94576 1.60178 35.04568 9.33576 2.31798 29.51968 8.83896 3.55496 35.04568 8.30708 5.67738 34.68957 8.98616 4.04325 29.51968 0.00416 -10.00089 29.52368 0.00336 -10.00089 30.08768 2.93366 -9.56529 30.58668 3.43473 -9.48162 29.13079 3.49076 -9.37344 25.99968 1.45316 -9.89544 25.99968 4.39459 -9.10315 25.99968 4.41876 -8.98168 31.25368 6.33566 -7.76061 29.52368 5.84346 -8.13534 32.22368 7.02016 -7.12658 25.99968 7.14446 -7.03138 33.48969 8.27176 -5.67266 35.04868 8.54566 -5.26191 29.52368 4.68486 -8.14347 33.37068 5.30646 7.91391 34.49867 6.09576 7.66057 34.49867 6.81586 7.24997 34.49968 6.91396 -7.18597 33.86967 5.65496 -8.25206 32.34668 5.01416 -8.44358 32.71868 3.31336 -9.32459 31.45968 1.18046 -9.86343 30.69068 5.37426 -8.43667 25.99968 5.71986 -8.20649 23.99968 6.46616 -7.63259 23.99968 7.16186 -6.98424 23.99968 -7.15819 -6.98424 23.99968 -6.46249 -7.63259 23.99968 -5.71619 -8.20649 23.99968 -5.37059 -8.43667 25.99968 -1.17679 -9.86343 30.69068 -3.30969 -9.32459 31.45968 -5.01049 -8.44358 32.71868 -5.65129 -8.25206 32.34668 -6.31069 -7.37931 34.23868 -6.91029 -7.18597 33.86967 -7.85419 -6.04028 35.50568 -6.81219 7.24997 34.49968 -6.09209 7.66057 34.49867 -5.30279 7.91391 34.49867 -8.26809 -5.67266 35.04868 -4.68119 -8.14347 33.37068 -5.72309 -7.25891 34.63368 -8.54199 -5.26191 29.52368 -7.14079 -7.03138 33.48969 -7.01649 -7.12658 25.99968 -5.83979 -8.13534 32.22368 -6.33199 -7.76061 29.52368 -4.41509 -8.98168 31.25368 -4.39092 -9.10315 25.99968 -1.44949 -9.89544 25.99968 -3.48709 -9.37343 25.99968 -3.43106 -9.48162 29.13079 -2.92999 -9.56529 30.58668 0.00184 -10.00019 25.99969 -8.98249 4.04325 29.51968 -8.30341 5.67738 34.68957 -8.83529 3.55496 35.04568 -9.33209 2.31798 29.51968 -8.94209 1.60178 35.04568 -9.47299 0.60681 29.51968 -8.96309 -0.33818 35.04568 -9.44729 -1.09815 29.51968 -8.91539 -2.27439 35.04568 -9.25709 -2.79232 29.51968 -8.76179 -4.19563 35.80267 -8.89019 -4.46979 29.51968 -8.31070 5.81849 29.52985 -7.43299 6.69810 34.49368 -9.67509 -2.52910 23.99968 -9.27769 -3.73246 23.99968 -8.73169 -4.87502 23.99968 -8.35159 -5.50089 23.99968 0.00183 7.24200 10.60569 4.00366 4.25152 9.99969 5.65006 6.94911 8.25268 5.55006 6.94911 5.59469 3.89726 6.94911 9.21068 3.63686 6.94093 6.60969 1.98966 6.94911 9.80069 0.00366 6.94911 9.99969 0.00366 6.94911 7.84768 4.30636 7.24200 9.80469 1.47496 7.24200 10.60569 4.32487 5.06448 8.40697 3.63686 6.82538 6.40069 4.38886 6.06216 6.65668 4.68666 3.94590 9.87969 4.34936 4.09318 9.96969 3.63371 6.43688 6.43168 4.43506 6.73264 6.19568 4.49076 6.91366 6.33069 5.94346 3.82193 8.45469 6.00400 4.02117 8.04468 -6.00000 4.02117 8.04468 -5.93979 3.82193 8.45469 -5.54639 6.94911 5.59469 -4.54040 6.94911 6.46068 -3.63320 6.94093 6.60969 -4.45075 6.64691 6.24219 -4.34569 4.09222 9.96969 -3.63320 6.82538 6.40069 3.63321 5.95391 6.88068 -4.32395 5.11941 8.41997 -1.47129 7.24200 10.60569 -4.30269 7.24200 9.80469 -1.98599 6.94911 9.80069 -3.89359 6.94911 9.21068 -3.99999 4.25198 9.99969 4.47576 -8.00089 9.94269 6.00366 5.96671 5.62369 6.00366 4.86318 6.60168 6.00366 4.40365 7.39368 5.41736 3.62295 9.41469 5.73196 3.74311 9.00368 -5.72829 3.74311 9.00368 -3.63359 6.44435 6.42669 -4.68299 3.85204 9.87969 -5.41369 3.62295 9.41469 -4.38520 6.06216 6.65668 -3.63320 5.95391 6.88068 -5.99999 4.40365 7.39368 -5.99999 4.86318 6.60168 -6.00000 5.96671 5.62369 -4.47209 -8.00089 9.94269 -8.38479 -5.45020 -0.00031 -9.63909 -2.66304 -0.00031 -6.78409 -6.66756 -3.03501 -8.51050 -4.28290 -3.03941 -7.35780 -3.50425 -5.79601 7.36146 -3.50425 -5.79601 8.51416 -4.28290 -3.03941 6.78776 -6.66756 -3.03501 9.64276 -2.66304 -0.00031 8.38846 -5.45020 -0.00031 9.12276 -4.10482 -0.00031 -9.11909 -4.10482 -0.00031 -3.57919 -8.00089 13.99868 -3.99999 -5.43664 40.66869 -5.48459 -5.09962 40.93769 -5.49999 -4.73356 40.21569 -5.76329 -4.42797 39.42269 -6.42709 -4.46943 41.43969 -6.59809 -3.69701 40.57769 -6.42699 -3.76429 39.42269 -6.85319 -2.92798 39.42269 -6.68310 -3.81534 41.96069 -6.99999 -3.09028 42.53869 -6.99999 -2.49594 41.59168 -6.99999 -2.12557 40.53269 -6.99999 -2.00089 39.42269 -5.36349 -4.67315 38.32668 -6.19619 -4.04460 39.22469 -6.72699 -3.25133 38.74369 -6.99999 -2.00089 38.27869 -6.96549 -2.45480 38.42168 -8.53599 -1.46623 39.60468 -8.55289 -0.11087 39.43468 -8.54059 1.25595 39.55968 -8.50409 2.50568 39.95368 -8.45399 3.57721 40.56069 -6.76829 -5.70594 36.85169 -6.86009 -4.03110 39.22569 -6.92969 7.10944 44.99969 -6.11599 7.64029 44.99969 -5.93589 7.04911 44.99969 -5.49999 6.94911 44.99969 -5.31029 7.90772 44.99969 -4.88529 7.95342 44.99969 -7.19169 6.82799 43.78869 -8.19199 4.97673 41.65069 -7.71279 6.06131 42.71468 -7.49639 -5.59217 36.77569 -7.60349 -3.56948 39.46268 -8.12469 -5.26918 36.55169 -8.06229 -2.97472 39.64069 -8.56689 -4.78127 36.21169 -8.39929 -2.25591 39.68868 -7.28129 -6.21366 35.90269 -6.99999 1.68717 38.19369 -6.99999 0.45891 38.00269 -6.99999 -0.78335 38.03168 -6.99999 2.86304 38.59969 -6.99999 3.94911 39.20568 -6.99999 -3.63839 43.45969 -5.03399 6.76527 43.41169 -5.49999 6.54719 42.67069 -5.93590 6.24091 41.72169 -6.39679 5.75341 40.92669 -6.83869 4.91954 39.95969 -7.08054 5.94669 41.49869 -7.43409 4.97597 40.42869 -8.19199 4.02715 40.55369 -7.43409 3.77077 39.39269 -8.19199 2.84199 39.71668 -7.43409 2.35678 38.66769 -8.19199 1.49065 39.18868 -7.43409 0.81253 38.29169 -8.19199 0.05167 39.00069 -7.43409 -0.77680 38.28768 -8.19199 -1.39001 39.16369 -7.43409 -2.32320 38.65369 -6.72699 6.57048 42.44669 -6.72699 6.92842 43.70069 -5.49999 -6.42367 43.72469 5.48826 -5.09962 40.93769 6.43076 -4.46943 41.43969 5.50366 -6.42367 43.72469 6.60256 -5.34526 43.93868 6.85686 4.87616 44.99969 6.73066 6.92842 43.70069 6.73066 -3.25133 38.74369 6.73066 6.57048 42.44669 7.08421 5.94669 41.49869 7.43776 -2.32320 38.65369 8.19566 -1.39001 39.16369 7.43776 -0.77680 38.28768 8.19566 0.05167 39.00069 7.43776 0.81253 38.29169 8.19566 1.49065 39.18868 7.43776 2.35678 38.66769 8.19566 2.84199 39.71668 7.43776 3.77077 39.39269 8.19566 4.02715 40.55369 7.43776 4.97597 40.42869 6.84236 4.91954 39.95969 6.40046 5.75341 40.92669 6.43076 5.71247 44.99969 5.93956 6.24091 41.72169 5.50366 6.54719 42.67069 5.03766 6.76527 43.41169 4.93076 6.80228 44.99969 7.00366 3.80368 46.06168 7.00366 -3.90969 45.56869 7.00366 3.94911 44.99969 7.00366 -3.91855 44.49569 7.00366 -3.63839 43.45969 7.00366 3.94911 39.20568 7.00366 2.86304 38.59969 7.00366 -0.78335 38.03168 7.00366 0.45891 38.00269 7.00366 1.68717 38.19369 6.31436 -7.37931 34.23869 8.12836 -5.26918 36.55169 7.85786 -6.04028 35.50568 7.28496 -6.21366 35.90269 8.40296 -2.25591 39.68868 8.57056 -4.78127 36.21169 8.06596 -2.97472 39.64069 7.60716 -3.56948 39.46268 6.99346 -4.00149 39.23769 7.50006 -5.59217 36.77569 7.71646 6.06131 42.71468 8.19566 4.97673 41.65069 7.19536 6.82799 43.78869 4.88896 7.95342 44.99969 5.31396 7.90772 44.99969 5.93956 7.04911 44.99969 6.11966 7.64029 44.99969 6.93336 7.10944 44.99969 5.72676 -7.25891 34.63369 6.77196 -5.70594 36.85169 8.45766 3.57721 40.56069 8.50776 2.50568 39.95368 8.54426 1.25595 39.55968 8.55656 -0.11086 39.43468 8.53966 -1.46623 39.60468 7.00366 -2.00089 38.27869 6.96916 -2.45480 38.42168 6.19986 -4.04460 39.22469 5.36716 -4.67315 38.32668 7.00366 -2.31088 41.06269 7.00366 -2.00089 39.42269 7.00366 -2.49594 41.59168 7.00366 -3.09028 42.53869 6.75609 -3.81534 41.96069 6.85686 -2.92798 39.42269 6.43066 -3.76429 39.42269 6.60176 -3.69701 40.57769 5.76696 -4.42797 39.42269 5.50366 -4.73356 40.21569 4.00366 -5.00089 39.42269 4.00366 -5.43664 40.66869 + + + + + + + + + + -0.37992 -0.92502 0.00105 -0.61397 0.78924 -0.01224 -0.07593 -0.97679 -0.20031 -0.22994 -0.96457 -0.12938 -0.08134 -0.97733 -0.19549 -0.42429 -0.89757 -0.11982 0.42429 -0.89757 -0.11983 0.08144 -0.97732 -0.19548 0.22994 -0.96457 -0.12938 0.07611 -0.97679 -0.20023 0.00000 1.00000 -0.00000 -0.02010 0.99979 -0.00262 -0.99786 -0.06535 0.00030 -1.00000 0.00130 -0.00287 -0.99811 0.06144 0.00009 -0.98228 0.18741 -0.00039 -0.98189 0.18945 -0.00051 -0.89668 0.44268 0.00142 -0.94065 0.33926 0.00847 -0.93503 0.35447 0.00850 -0.87777 0.47908 -0.00009 -0.79597 0.60534 0.00009 -0.79427 0.60756 -0.00009 -0.73062 -0.00000 -0.68279 -0.89780 -0.00000 -0.44040 -0.89780 -0.00000 -0.44040 -0.71610 0.04952 -0.69624 -0.75711 0.13830 -0.63848 -0.69777 0.21297 -0.68393 -0.85617 0.26132 -0.44574 -0.92192 0.33250 -0.19878 -0.93821 0.30132 -0.17023 -0.85683 0.27518 -0.43602 -0.69725 0.25192 -0.67110 -0.86835 0.47394 -0.14612 -0.73749 0.50314 -0.45051 -0.77877 0.59570 -0.19660 -0.78420 0.59050 -0.19062 -0.73536 0.51102 -0.44509 -0.72246 0.52579 -0.44899 -0.67329 -0.73938 -0.00047 -0.66596 -0.74598 0.00018 -0.51275 -0.85854 0.00036 -0.48310 -0.87557 -0.00131 -0.34471 -0.93870 0.00305 -0.28004 -0.95995 0.00846 -0.17483 -0.98460 -0.00057 -0.13972 0.99019 0.00271 -0.27312 0.96198 -0.00196 -0.40823 0.91287 0.00257 -0.47428 0.88037 -0.00066 -0.45040 0.89283 0.00000 -0.71115 0.70304 0.00000 -0.57790 0.81555 -0.03005 -0.60493 0.79627 0.00059 -0.67564 0.73722 0.00384 -0.57764 0.81518 -0.04270 -0.64644 0.74661 -0.15714 -0.67682 0.72341 -0.13637 -0.59520 0.75563 -0.27343 -0.59953 0.70834 -0.37259 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.02819 0.94010 0.33974 0.01436 0.93130 0.36396 0.12973 0.97951 -0.15405 -0.64764 0.76194 0.00226 -0.71191 0.70227 0.00006 -0.98581 0.00000 -0.16786 -0.97140 0.18743 -0.14577 0.97140 0.18743 -0.14578 0.98565 0.00000 -0.16881 0.71191 0.70227 0.00006 0.64764 0.76194 0.00226 0.00494 0.91350 0.40681 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 0.54765 0.76436 -0.34035 0.67682 0.72341 -0.13637 0.64644 0.74661 -0.15714 0.57764 0.81518 -0.04270 0.67564 0.73722 0.00384 0.57791 0.81555 -0.02994 0.61966 0.78477 -0.01300 0.70339 0.71081 -0.00063 0.47080 0.88224 -0.00000 0.40823 0.91287 0.00257 0.27312 0.96198 -0.00196 0.13972 0.99019 0.00271 0.17483 -0.98460 -0.00057 0.28004 -0.95995 0.00846 0.34471 -0.93870 0.00305 0.37991 -0.92502 0.00105 0.48310 -0.87557 -0.00131 0.51275 -0.85854 0.00036 0.66596 -0.74598 0.00018 0.67329 -0.73937 -0.00047 0.72246 0.52579 -0.44899 0.73536 0.51102 -0.44509 0.78420 0.59050 -0.19063 0.77877 0.59570 -0.19660 0.73749 0.50314 -0.45051 0.86835 0.47394 -0.14612 0.69725 0.25192 -0.67110 0.85683 0.27518 -0.43602 0.93821 0.30132 -0.17023 0.92192 0.33250 -0.19878 0.85617 0.26132 -0.44574 0.69777 0.21297 -0.68393 0.75711 0.13830 -0.63848 0.71610 0.04952 -0.69624 0.89780 0.00000 -0.44040 0.89780 0.00000 -0.44040 0.73062 0.00000 -0.68279 0.79427 0.60756 -0.00009 0.79597 0.60534 0.00009 0.87777 0.47908 -0.00009 0.93503 0.35448 0.00850 0.94065 0.33926 0.00847 0.89668 0.44268 0.00142 0.98189 0.18945 -0.00051 0.98228 0.18741 -0.00039 0.99809 0.06144 -0.00571 1.00000 0.00130 0.00031 0.99786 -0.06535 0.00030 0.02010 0.99979 -0.00262 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 -0.99986 0.01651 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 0.00000 1.00000 0.69946 0.68907 0.18956 0.22891 0.89330 0.38681 0.96248 0.21083 0.17081 0.95946 0.21276 0.18488 0.69693 0.54133 0.47038 0.36003 0.72476 0.58745 0.30851 0.71817 0.62374 0.69716 0.54127 0.47010 0.96751 0.14650 0.20605 0.21934 0.56453 0.79573 0.95759 0.09723 0.27122 0.96142 0.10177 0.25557 0.69721 0.26520 0.66601 0.69718 0.26518 0.66605 0.30072 0.32233 0.89759 0.34441 0.34727 0.87223 0.96702 0.01852 0.25402 0.22851 0.07066 0.97097 0.69718 -0.07020 0.71345 0.95018 -0.06188 0.30550 0.96407 -0.02601 0.26437 0.36233 -0.09132 0.92757 0.69714 -0.07024 0.71349 0.25693 -0.19200 0.94717 0.96537 -0.11886 0.23224 0.69711 -0.38978 0.60175 0.95840 -0.15517 0.23956 0.69719 -0.38969 0.60172 0.42922 -0.41142 0.80405 0.25228 -0.52600 0.81221 0.22867 -0.66008 0.71554 0.96700 -0.17269 0.18735 0.69715 -0.62243 0.35577 0.96242 -0.23105 0.14269 0.95943 -0.24477 0.13991 0.69712 -0.62246 0.35577 0.36001 -0.79374 0.49028 0.30840 -0.82588 0.47203 0.21950 -0.93736 0.27051 -0.95765 -0.28792 0.00238 -0.69707 -0.71635 0.03043 -0.96752 -0.24290 0.07004 -0.21950 -0.93736 0.27051 -0.30839 -0.82588 0.47203 -0.36001 -0.79374 0.49028 -0.69712 -0.62246 0.35577 -0.95943 -0.24477 0.13991 -0.96242 -0.23105 0.14269 -0.69715 -0.62243 0.35577 -0.96700 -0.17269 0.18735 -0.22867 -0.66008 0.71554 -0.25228 -0.52600 0.81221 -0.42922 -0.41142 0.80405 -0.69719 -0.38969 0.60172 -0.95840 -0.15517 0.23956 -0.69711 -0.38978 0.60175 -0.96537 -0.11886 0.23224 -0.25693 -0.19200 0.94717 -0.69714 -0.07024 0.71349 -0.36233 -0.09132 0.92757 -0.96407 -0.02601 0.26437 -0.95018 -0.06188 0.30550 -0.69718 -0.07020 0.71345 -0.22851 0.07066 0.97097 -0.96702 0.01852 0.25402 -0.34441 0.34727 0.87223 -0.30072 0.32233 0.89759 -0.69718 0.26518 0.66605 -0.69721 0.26520 0.66601 -0.96142 0.10177 0.25557 -0.95759 0.09723 0.27122 -0.21934 0.56453 0.79573 -0.96751 0.14650 0.20605 -0.69716 0.54127 0.47010 -0.30851 0.71817 0.62374 -0.36003 0.72476 0.58745 -0.69693 0.54133 0.47038 -0.95946 0.21276 0.18488 -0.96248 0.21083 0.17081 -0.22891 0.89330 0.38681 -0.96702 0.23373 0.10120 -0.69946 0.68907 0.18956 -0.44469 0.87275 0.20141 -0.15007 0.94757 0.28211 -0.42958 0.89466 0.12265 -0.95018 0.30880 0.04245 -0.69362 0.69364 0.19431 -0.98747 0.15637 0.02141 -0.84480 0.43042 0.31789 -0.00000 -0.96534 -0.26100 -0.00000 -0.96534 -0.26100 -0.00000 -0.99996 0.00841 -0.00000 -0.99996 0.00841 -0.00000 -0.96079 0.27727 -0.00000 -0.96079 0.27727 -0.00000 -0.85078 0.52551 -0.00000 -0.85078 0.52551 -0.00000 -0.67805 0.73502 0.00000 -0.67805 0.73502 0.00000 -0.45551 0.89023 0.00000 -0.45551 0.89023 0.00000 -0.19866 0.98007 0.00000 -0.19866 0.98007 -0.00000 0.07258 0.99736 0.00000 0.07258 0.99736 0.00000 0.33797 0.94116 -0.00000 0.33797 0.94116 -0.00000 0.57862 0.81559 0.00000 0.57862 0.81559 0.00000 0.77686 0.62968 0.00000 0.77686 0.62968 0.00000 0.91766 0.39736 0.00000 0.91766 0.39736 0.00000 0.99073 0.13583 0.00000 0.99073 0.13583 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.97499 0.22226 -0.00000 -0.92453 0.38110 0.90226 -0.43116 0.00574 0.97649 -0.21358 0.02928 0.97612 -0.21350 0.04000 0.94802 -0.31308 0.05686 0.99635 -0.05341 0.06661 0.97763 -0.19024 0.08966 0.99134 -0.11130 0.06976 0.99120 -0.11128 0.07172 0.99558 -0.02453 0.09061 0.99409 -0.06510 0.08683 0.99589 -0.01501 0.08933 0.99520 -0.01500 0.09672 0.99424 0.06120 0.08796 0.99554 0.01078 0.09370 0.99338 0.08180 0.08071 0.99256 0.08173 0.09020 0.97998 0.18697 0.06840 0.99552 0.05444 0.07731 0.96826 0.24794 0.03155 0.97796 0.19817 0.06582 0.89663 0.44266 -0.01036 0.97777 0.19813 0.06861 0.14700 -0.98914 0.00021 0.24807 -0.96831 -0.02902 0.07172 -0.99371 0.08595 0.14963 -0.98874 -0.00030 0.14904 -0.98882 -0.00554 0.28639 -0.95770 -0.02796 0.34030 -0.93819 0.06320 0.56248 -0.82680 0.00516 0.50451 -0.86193 0.05048 0.53463 -0.84366 -0.04914 0.51263 -0.85823 -0.02566 0.62265 -0.78225 -0.01980 0.64109 -0.76740 0.01036 0.79702 -0.60172 -0.05190 0.74900 -0.66246 -0.01212 0.74880 -0.66228 0.02629 0.91538 -0.40230 0.01547 0.61539 -0.78641 0.05336 0.57003 -0.81556 0.09967 0.12475 -0.87586 0.46616 0.51875 -0.85477 -0.01612 0.37649 -0.90862 0.18073 0.32485 -0.92285 0.20694 0.13312 -0.88748 0.44120 0.09621 -0.88767 0.45032 0.31482 -0.94120 0.12258 0.06742 -0.90426 0.42164 0.08306 -0.90964 0.40702 0.17554 -0.96597 0.18998 0.02220 -0.90647 0.42168 0.16166 -0.98259 -0.09158 0.06493 -0.99436 -0.08387 0.07172 -0.99366 -0.08660 0.20896 -0.97695 -0.04364 0.24766 -0.96673 -0.06404 0.60929 -0.79232 0.03169 0.62268 -0.78228 0.01757 0.68177 -0.73156 -0.00376 0.47456 -0.88001 -0.01928 0.56160 -0.82551 -0.05591 0.40991 -0.90871 -0.07890 0.28626 -0.95728 -0.04085 0.79561 0.60506 -0.03020 0.93501 0.35447 -0.01016 0.93521 0.35396 -0.00997 0.93524 0.35385 0.01100 0.75898 0.65084 0.01887 0.77910 -0.62681 0.01059 0.77326 -0.63409 0.00078 0.85470 -0.51907 -0.00700 0.91546 -0.40240 0.00325 -0.00000 1.00000 0.00000 0.10310 0.99467 -0.00009 0.13972 0.99019 -0.00302 0.30561 0.95215 0.00160 0.40823 0.91287 -0.00410 0.49533 0.86870 0.00126 0.64764 0.76194 -0.00322 0.66439 0.74739 -0.00132 0.70513 0.70908 -0.00097 -0.70513 0.70908 -0.00097 -0.66439 0.74739 -0.00132 -0.64764 0.76194 -0.00322 -0.49533 0.86870 0.00126 -0.40823 0.91287 -0.00410 -0.30561 0.95215 0.00160 -0.13972 0.99019 -0.00302 -0.10310 0.99467 -0.00009 0.00000 1.00000 0.00000 -0.91546 -0.40240 0.00325 -0.85470 -0.51907 -0.00700 -0.77326 -0.63409 0.00078 -0.77910 -0.62681 0.01059 -0.75898 0.65084 0.01887 -0.93524 0.35385 0.01100 -0.93521 0.35396 -0.00997 -0.93501 0.35447 -0.01016 -0.79561 0.60506 -0.03020 -0.28626 -0.95728 -0.04085 -0.40991 -0.90871 -0.07890 -0.56160 -0.82551 -0.05591 -0.47456 -0.88001 -0.01928 -0.68177 -0.73156 -0.00376 -0.62268 -0.78228 0.01757 -0.60929 -0.79232 0.03169 -0.24766 -0.96673 -0.06404 -0.20896 -0.97695 -0.04364 -0.07172 -0.99365 -0.08669 -0.06477 -0.99437 -0.08389 -0.16161 -0.98253 -0.09231 -0.02214 -0.90647 0.42168 -0.17554 -0.96597 0.18998 -0.08306 -0.90964 0.40702 -0.06742 -0.90426 0.42164 -0.31482 -0.94120 0.12258 -0.09621 -0.88767 0.45032 -0.13312 -0.88748 0.44120 -0.32485 -0.92285 0.20694 -0.37649 -0.90862 0.18073 -0.51875 -0.85477 -0.01612 -0.12475 -0.87586 0.46616 -0.15273 -0.86617 0.47583 -0.41173 -0.87359 0.25948 -0.57003 -0.81556 0.09967 -0.61539 -0.78642 0.05336 -0.43261 -0.86653 0.24894 -0.14765 -0.86322 0.48276 -0.71431 -0.69421 0.08851 -0.67849 -0.72532 0.11649 -0.94257 -0.33229 0.03376 -0.91537 -0.40231 0.01547 -0.74880 -0.66228 0.02629 -0.74900 -0.66246 -0.01212 -0.79702 -0.60172 -0.05190 -0.64109 -0.76740 0.01036 -0.62265 -0.78225 -0.01980 -0.51263 -0.85823 -0.02566 -0.53463 -0.84366 -0.04914 -0.50451 -0.86193 0.05048 -0.56248 -0.82680 0.00516 -0.34030 -0.93819 0.06320 -0.28639 -0.95770 -0.02796 -0.14884 -0.98885 -0.00561 -0.14945 -0.98877 -0.00010 -0.07172 -0.99371 0.08595 -0.24807 -0.96831 -0.02902 -0.14692 -0.98915 -0.00021 -0.97777 0.19813 0.06861 -0.89663 0.44266 -0.01036 -0.97796 0.19817 0.06582 -0.96826 0.24794 0.03155 -0.99552 0.05444 0.07731 -0.97998 0.18697 0.06840 -0.99256 0.08173 0.09020 -0.99338 0.08180 0.08071 -0.99554 0.01078 0.09370 -0.99424 0.06120 0.08796 -0.99520 -0.01500 0.09672 -0.99589 -0.01501 0.08933 -0.99409 -0.06510 0.08683 -0.99558 -0.02453 0.09061 -0.99120 -0.11128 0.07172 -0.99134 -0.11130 0.06976 -0.97763 -0.19024 0.08966 -0.99635 -0.05341 0.06661 -0.94802 -0.31308 0.05686 -0.97612 -0.21350 0.04000 -0.97649 -0.21358 0.02928 -0.90226 -0.43116 0.00574 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.90036 -0.43515 0.00000 0.90036 -0.43515 0.00000 0.00000 -1.00000 -0.00000 1.00000 -0.00000 0.02992 0.99953 -0.00614 -0.04897 0.99855 -0.02238 -0.00000 1.00000 0.00000 -0.00094 0.99999 -0.00305 -0.00000 1.00000 0.00000 0.00167 1.00000 -0.00170 -0.18127 0.92582 -0.33166 -0.33605 0.30453 -0.89125 -0.24187 0.45887 -0.85495 -0.12672 0.90338 -0.40970 -0.10729 0.91905 -0.37927 -0.15739 0.32299 -0.93322 -0.03628 0.93144 -0.36209 -0.98931 0.00059 -0.14580 -0.08645 0.00000 -0.99626 -0.25621 -0.07481 -0.96372 -0.46284 0.61705 -0.63642 -0.12748 0.61787 -0.77588 -0.12905 0.86783 -0.47980 0.52405 0.59562 -0.60877 0.08703 0.87183 -0.48201 0.02729 0.59100 -0.80621 0.08645 0.00000 -0.99626 0.98943 0.00056 -0.14501 -0.00000 -0.07954 -0.99683 -0.00000 0.87515 -0.48385 -0.00000 0.87515 -0.48385 0.03621 0.93145 -0.36205 0.15739 0.32299 -0.93322 0.10729 0.91905 -0.37927 0.12672 0.90337 -0.40970 0.24187 0.45887 -0.85495 0.33605 0.30453 -0.89125 0.18127 0.92582 -0.33166 0.00000 0.99998 -0.00661 -0.00167 1.00000 -0.00170 0.00000 1.00000 -0.00000 0.00094 0.99999 -0.00305 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00938 0.99995 -0.00221 0.00000 1.00000 -0.00000 -0.03447 -0.56461 -0.82463 -0.02257 -0.86820 -0.49570 -0.00000 -1.00000 -0.00000 -0.02658 0.99964 -0.00251 0.00811 0.99992 0.00963 0.40679 -0.91352 -0.00000 -0.99129 0.00002 -0.13166 -0.93308 -0.00133 -0.35966 -0.92096 0.00015 -0.38965 -0.79403 -0.00032 -0.60788 -0.78301 0.00046 -0.62201 -0.60834 -0.00037 -0.79368 -0.59143 0.00050 -0.80636 -0.42313 -0.00028 -0.90607 -0.36047 0.00144 -0.93277 -0.25804 -0.00054 -0.96613 -0.11987 0.00096 -0.99279 -0.00342 0.94046 0.33987 0.10258 0.95600 0.27486 -0.54107 -0.72740 -0.42205 -0.54206 -0.72466 -0.42548 -0.54151 -0.72194 -0.43078 -0.56924 -0.75410 -0.32757 -0.66245 -0.49685 -0.56063 -0.35061 -0.80805 -0.47342 -0.84565 -0.40086 -0.35240 -0.38367 0.78835 -0.48095 -0.40881 0.39255 -0.82388 -0.12973 0.97951 -0.15405 -0.49552 -0.46867 -0.73130 -0.42845 -0.22367 -0.87544 0.44674 -0.23178 -0.86412 0.49661 -0.46421 -0.73341 0.23270 0.87645 -0.42153 0.17952 0.79930 -0.57349 0.40881 0.39255 -0.82388 0.38366 0.78835 -0.48095 0.84565 -0.40086 -0.35240 0.33841 -0.82490 -0.45279 0.01364 -0.88159 -0.47182 0.67437 -0.48974 -0.55261 0.58626 -0.73899 -0.33195 0.56054 -0.70950 -0.42709 0.56140 -0.71351 -0.41920 0.56043 -0.71635 -0.41564 -0.06761 0.95887 0.27568 0.11987 0.00096 -0.99279 0.25818 -0.00054 -0.96610 0.36048 0.00146 -0.93277 0.45114 -0.00108 -0.89245 0.59133 -0.00033 -0.80643 0.59343 -0.00043 -0.80488 0.78301 0.00046 -0.62201 0.79403 -0.00032 -0.60788 0.92096 0.00015 -0.38965 0.93308 -0.00133 -0.35966 0.99129 0.00002 -0.13166 -0.40679 -0.91352 0.00000 -0.00625 -0.86521 -0.50136 -0.00000 -0.87912 -0.47660 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 0.00000 -1.00000 -0.11875 -0.67600 -0.72728 -0.69945 -0.56446 -0.43835 -0.73008 -0.52935 -0.43217 -0.79534 -0.57614 -0.18840 -0.73749 -0.50314 -0.45051 -0.66333 -0.36884 -0.65111 -0.68186 -0.46553 -0.56422 -0.69725 -0.25192 -0.67110 -0.93527 -0.30038 -0.18722 -0.85683 -0.27518 -0.43602 -0.70722 -0.14967 -0.69097 -0.71631 -0.21863 -0.66264 -0.85617 -0.26132 -0.44574 -0.71610 -0.04952 -0.69624 -0.59927 -0.74831 -0.28445 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -0.63379 -0.75998 -0.14402 -0.65889 -0.73806 -0.14536 -0.62639 -0.76482 -0.15062 0.62639 -0.76482 -0.15062 0.65889 -0.73806 -0.14536 -1.00000 0.00000 0.00000 0.59715 -0.78261 -0.17586 0.62227 -0.69937 -0.35166 0.71610 -0.04952 -0.69624 0.85617 -0.26132 -0.44574 0.71631 -0.21863 -0.66264 0.70722 -0.14967 -0.69097 0.85683 -0.27518 -0.43602 0.93527 -0.30038 -0.18722 0.69725 -0.25192 -0.67110 0.68186 -0.46553 -0.56422 0.66333 -0.36884 -0.65111 0.73749 -0.50314 -0.45051 0.79534 -0.57614 -0.18840 0.73008 -0.52935 -0.43217 0.75435 -0.49922 -0.42630 -0.00000 -1.00000 0.00000 0.00106 -0.99996 0.00881 0.02538 -0.99967 0.00267 0.79359 -0.60845 -0.00012 0.79427 -0.60756 -0.00018 0.85472 -0.51909 0.00009 0.87777 -0.47908 -0.00121 0.90227 -0.43117 0.00073 0.94069 -0.33927 -0.00095 0.94956 -0.31358 0.00033 0.98159 -0.19101 -0.00041 0.98148 -0.19157 -0.00037 0.86835 -0.47394 -0.14612 0.92761 -0.33456 -0.16616 0.28626 -0.95811 0.00941 0.06124 -0.99812 0.00082 -1.00000 -0.00000 0.00000 0.77914 -0.62684 0.00328 0.00000 -0.98059 -0.19609 0.07625 -0.98818 -0.13301 0.67329 -0.73937 -0.00375 0.68177 -0.73156 -0.00422 0.51266 -0.85845 -0.01557 0.60949 -0.79259 -0.01799 0.28596 -0.95726 -0.04336 0.48386 -0.87340 -0.05531 0.02544 -0.99072 -0.13349 0.19812 -0.97716 -0.07687 0.97088 -0.18950 -0.14654 0.78235 -0.59845 -0.17260 0.48258 -0.87463 -0.04614 -0.48258 -0.87464 -0.04614 -0.78235 -0.59845 -0.17260 -0.97088 -0.18950 -0.14654 -0.19812 -0.97716 -0.07687 -0.02544 -0.99072 -0.13349 -0.48386 -0.87340 -0.05531 -0.28596 -0.95726 -0.04336 -0.60949 -0.79259 -0.01799 -0.51266 -0.85845 -0.01557 -0.68177 -0.73156 -0.00422 -0.67329 -0.73937 -0.00375 -0.07616 -0.98818 -0.13301 -0.00000 -0.98059 -0.19609 -0.77914 -0.62684 0.00328 0.20395 -0.06686 -0.97670 1.00000 0.00000 -0.00000 -0.06124 -0.99812 0.00082 -0.28626 -0.95811 0.00941 -0.92761 -0.33456 -0.16616 -0.86835 -0.47394 -0.14612 -0.98148 -0.19157 -0.00037 -0.98159 -0.19101 -0.00041 -0.94956 -0.31358 0.00033 -0.94069 -0.33927 -0.00095 -0.90227 -0.43117 0.00073 -0.87777 -0.47908 -0.00121 -0.85472 -0.51908 0.00009 -0.79427 -0.60756 -0.00018 -0.79359 -0.60845 -0.00012 0.00062 -0.06808 -0.99768 -0.00020 -0.68088 -0.73240 -0.00000 -0.67931 -0.73385 -0.02538 -0.99967 0.00267 -0.00106 -0.99996 0.00881 -0.00000 -0.99986 0.01651 0.00000 -0.94394 -0.33011 -0.00000 -0.94394 -0.33011 -0.26435 -0.91036 -0.31837 -0.29878 -0.91958 -0.25516 -0.36744 -0.83266 -0.41433 -0.64066 -0.69026 -0.33630 -0.69571 -0.59806 -0.39790 -0.70567 -0.70569 -0.06343 -0.69377 -0.71869 -0.04660 -0.88605 -0.45155 -0.10496 -0.94887 -0.30419 -0.08435 -0.93636 -0.34017 -0.08666 -0.96824 -0.21178 -0.13291 -0.96453 -0.24918 -0.08715 -0.98754 -0.15637 -0.01756 -0.96795 -0.24613 0.04991 -0.30897 -0.95094 0.01571 -0.19818 -0.96944 0.14457 -0.64480 -0.76159 -0.06484 -0.80014 -0.59240 -0.09401 -0.69629 -0.69631 0.17415 -0.88983 -0.45348 0.05057 -0.99712 -0.07579 0.00000 -0.96339 -0.25512 0.08248 -0.98187 -0.15548 -0.10845 -0.99492 -0.04386 0.09057 -0.99589 -0.02453 0.08723 -0.99566 -0.00074 0.09309 -0.99566 0.00045 0.09303 -0.99594 0.01078 0.08941 -0.99606 0.00113 0.08868 -0.99596 -0.00422 0.08966 -0.01576 -0.81730 0.57599 -0.00007 -0.81918 0.57353 0.00019 -0.81917 0.57355 0.00007 -0.81914 0.57359 -0.00016 -0.81916 0.57357 0.00016 -0.81915 0.57358 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00001 0.00000 1.00000 0.00001 -0.00000 1.00000 -0.10686 0.99427 0.00021 -0.10691 0.99427 0.00051 -0.10310 0.99467 0.00036 -0.31502 0.94908 0.00033 -0.30561 0.95216 0.00114 -0.54640 0.83753 0.00037 -0.49532 0.86869 0.00608 -0.73383 0.67933 0.00088 -0.66442 0.74733 0.00680 -0.29659 -0.76863 0.56678 -0.62243 -0.62224 0.47476 -0.84125 -0.41735 0.34367 -0.97445 -0.15100 0.16627 -0.18468 -0.82157 0.53937 -0.52793 -0.74792 0.40237 -0.51590 -0.74782 0.41787 -0.79345 -0.56953 0.21466 -0.77990 -0.57721 0.24203 -0.94860 -0.31649 -0.00114 -0.13722 -0.84064 0.52392 -0.16245 -0.85018 0.50080 -0.46619 -0.82821 0.31103 -0.46054 -0.83055 0.31318 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.15641 0.98761 -0.01249 -0.43461 0.90058 0.00827 -0.45395 0.89092 0.01409 -0.56909 0.82226 -0.00398 -0.73529 0.67767 0.01073 -0.70710 0.70711 0.00185 -0.88271 0.46992 -0.00184 -0.89102 0.45397 0.00134 -0.98629 0.16504 -0.00142 -0.98769 0.15640 0.00000 0.63460 -0.66563 0.39270 0.63436 -0.66518 0.39385 0.72560 -0.52027 0.45035 0.68535 -0.47470 0.55223 0.72614 -0.39663 0.56161 0.68473 -0.33252 0.64852 0.72616 -0.25021 0.64038 0.68424 -0.17252 0.70856 0.72663 -0.08900 0.68124 0.68414 -0.00184 0.72935 0.72662 0.07718 0.68269 0.68429 0.16795 0.70960 0.73343 0.25027 0.63201 0.68191 0.33078 0.65237 0.50247 0.42166 0.75480 0.79620 -0.45746 0.39598 0.71150 -0.40537 0.57398 0.77296 -0.33970 0.53585 0.73978 -0.24487 0.62671 0.77536 -0.21037 0.59545 0.75248 -0.08532 0.65307 0.77897 -0.06406 0.62378 0.75300 0.07392 0.65386 0.77803 0.08772 0.62207 0.75616 0.19727 0.62394 0.66429 0.26477 0.69901 0.24972 -0.78683 0.56439 0.13613 -0.87777 0.45933 0.11798 -0.84918 0.51476 -0.06009 -0.98988 0.12857 0.23889 -0.95596 0.17049 0.27051 -0.84078 0.46894 0.49605 -0.83495 0.23833 0.50274 -0.79627 0.33645 0.36695 -0.74608 0.55562 0.51142 -0.57864 0.63532 0.47211 -0.57465 0.66850 0.49937 -0.42215 0.75659 0.55746 -0.37879 0.73875 0.46738 -0.28853 0.83565 0.57126 -0.19417 0.79747 0.47014 -0.13561 0.87211 0.50809 0.02010 0.86107 0.55298 -0.00210 0.83319 0.50233 0.17192 0.84741 0.55640 0.19138 0.80858 0.48927 0.29566 0.82049 0.37156 0.44143 0.81675 0.49467 0.42090 0.76036 -0.07970 -0.93736 0.33913 -0.06820 -0.95935 0.27384 -0.21807 -0.95055 0.22112 -0.06791 -0.98506 0.15826 0.00000 -0.99987 0.01593 -0.03964 -0.95154 0.30497 0.01193 0.52427 0.85147 -0.00000 -0.85957 -0.51102 -0.00000 -0.85957 -0.51102 -0.96142 -0.27485 0.01168 -0.30116 -0.95354 0.00802 -0.34472 -0.93786 0.03984 -0.69707 -0.71635 0.03043 -0.22886 -0.93972 -0.25408 -0.96701 -0.24590 -0.06650 -0.95011 -0.26803 -0.15951 -0.94563 -0.27551 -0.17284 -0.95556 -0.25147 -0.15383 -0.69977 -0.65778 -0.27864 -0.37006 -0.83833 -0.40032 -0.64017 -0.69253 -0.33254 -0.27651 -0.82605 -0.49110 -0.99615 0.05447 0.06865 -0.98889 0.13229 0.06784 -0.96758 0.24929 0.04058 -0.93111 0.36112 0.05125 -0.75833 0.65140 0.02465 -0.83600 0.54855 0.01404 0.00000 1.00000 -0.00000 -0.18465 -0.80642 0.56178 -0.53029 -0.68737 0.49630 -0.80208 -0.47156 0.36647 -0.96387 -0.19129 0.18539 0.96386 -0.19129 0.18540 0.80208 -0.47156 0.36647 0.53029 -0.68737 0.49630 0.18466 -0.80774 0.55987 -0.00000 1.00000 -0.00000 0.83600 0.54855 0.01404 0.75833 0.65140 0.02465 0.93111 0.36112 0.05125 0.96758 0.24929 0.04058 0.98889 0.13229 0.06784 0.99615 0.05447 0.06865 0.27651 -0.82605 -0.49110 0.64017 -0.69253 -0.33254 0.37007 -0.83833 -0.40032 0.69978 -0.65778 -0.27864 0.93015 -0.32185 -0.17675 0.96424 -0.24057 -0.11123 0.95011 -0.26803 -0.15951 0.96701 -0.24590 -0.06650 0.22886 -0.93972 -0.25408 0.69707 -0.71635 0.03043 0.34472 -0.93786 0.03984 0.30116 -0.95354 0.00802 0.96142 -0.27485 0.01167 0.95765 -0.28791 0.00238 0.69707 -0.71635 0.03043 0.96752 -0.24290 0.07004 0.96702 0.23373 0.10120 0.44469 0.87275 0.20141 0.15007 0.94757 0.28211 0.42958 0.89466 0.12265 0.96712 0.23308 0.10170 0.88684 0.45184 0.09669 0.69363 0.69363 0.19431 0.98747 0.15637 0.02141 -0.04306 0.53891 0.84126 0.03964 -0.95154 0.30497 0.05119 -0.99105 0.12326 0.06791 -0.98506 0.15826 0.06820 -0.95935 0.27384 0.07970 -0.93736 0.33913 -0.49441 0.39951 0.77197 -0.32782 0.43681 0.83770 -0.55640 0.19138 0.80858 -0.48927 0.29566 0.82049 -0.50233 0.17192 0.84741 -0.55298 -0.00210 0.83319 -0.50809 0.02010 0.86107 -0.47014 -0.13561 0.87211 -0.57126 -0.19417 0.79747 -0.46738 -0.28853 0.83565 -0.55746 -0.37879 0.73875 -0.49937 -0.42215 0.75659 -0.47211 -0.57465 0.66850 -0.51142 -0.57864 0.63532 -0.33681 -0.78370 0.52189 -0.28175 -0.75512 0.59196 -0.50274 -0.79627 0.33645 -0.49604 -0.83495 0.23833 -0.27051 -0.84078 0.46894 -0.23889 -0.95596 0.17049 0.06009 -0.98988 0.12857 -0.11798 -0.84918 0.51476 -0.13613 -0.87777 0.45934 -0.66429 0.26477 0.69901 -0.75616 0.19727 0.62394 -0.77803 0.08772 0.62207 -0.75300 0.07392 0.65386 -0.77897 -0.06406 0.62378 -0.75248 -0.08532 0.65307 -0.77536 -0.21037 0.59545 -0.73978 -0.24487 0.62671 -0.77296 -0.33970 0.53585 -0.71150 -0.40537 0.57398 -0.79620 -0.45746 0.39598 -0.55052 0.40061 0.73242 -0.68191 0.33078 0.65237 -0.73343 0.25027 0.63201 -0.68429 0.16795 0.70960 -0.72662 0.07718 0.68269 -0.68414 -0.00184 0.72935 -0.72663 -0.08900 0.68124 -0.68424 -0.17252 0.70856 -0.72616 -0.25021 0.64038 -0.68473 -0.33252 0.64852 -0.72614 -0.39663 0.56161 -0.68535 -0.47470 0.55223 -0.72560 -0.52027 0.45035 -0.63436 -0.66518 0.39385 -0.63460 -0.66563 0.39270 0.98769 0.15640 -0.00000 0.98629 0.16504 -0.00142 0.89102 0.45397 0.00134 0.88271 0.46992 -0.00184 0.70710 0.70711 0.00185 0.73529 0.67767 0.01073 0.56909 0.82227 -0.00398 0.45395 0.89092 0.01408 0.43460 0.90058 0.00827 0.15641 0.98761 -0.01249 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 0.15273 -0.86617 0.47583 0.41173 -0.87359 0.25948 0.43261 -0.86653 0.24894 0.14765 -0.86322 0.48276 0.46055 -0.83055 0.31318 0.46618 -0.82821 0.31103 0.16245 -0.85018 0.50080 0.71431 -0.69421 0.08851 0.67849 -0.72532 0.11649 0.13722 -0.84064 0.52392 0.94860 -0.31649 -0.00114 0.79507 -0.56250 0.22686 0.77632 -0.58631 0.23146 0.51589 -0.74782 0.41787 0.52793 -0.74792 0.40237 0.18468 -0.82157 0.53937 0.97445 -0.15100 0.16627 0.84126 -0.41735 0.34367 0.62243 -0.62224 0.47476 0.33025 -0.76039 0.55924 0.66442 0.74733 0.00681 0.73383 0.67933 0.00088 0.49532 0.86869 0.00608 0.54640 0.83753 0.00037 0.30561 0.95216 0.00114 0.31502 0.94908 0.00033 0.10310 0.99467 0.00036 0.10691 0.99427 0.00051 0.10687 0.99427 0.00021 0.94257 -0.33229 0.03376 -0.00000 -0.00000 1.00000 -0.00001 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00016 -0.81915 0.57358 0.00016 -0.81916 0.57357 -0.00007 -0.81914 0.57359 -0.00019 -0.81917 0.57355 0.00008 -0.81918 0.57353 0.03478 -0.81474 0.57878 0.99596 -0.00422 0.08966 0.99606 0.00113 0.08868 0.99594 0.01078 0.08941 0.99566 0.00045 0.09303 0.99566 -0.00074 0.09309 0.99589 -0.02453 0.08723 0.99492 -0.04386 0.09057 0.99712 -0.07579 0.00000 0.98187 -0.15548 -0.10845 0.96339 -0.25512 0.08248 0.88983 -0.45348 0.05057 0.69629 -0.69631 0.17415 0.80014 -0.59240 -0.09401 0.64480 -0.76159 -0.06484 0.19818 -0.96944 0.14457 0.30897 -0.95094 0.01571 0.95817 -0.28538 0.02161 0.98726 -0.15633 -0.02955 0.96453 -0.24916 -0.08717 0.96824 -0.21178 -0.13291 0.96527 -0.22815 -0.12724 0.92566 -0.35400 -0.13359 0.88605 -0.45155 -0.10496 0.69377 -0.71869 -0.04660 0.70567 -0.70569 -0.06343 0.69571 -0.59806 -0.39790 0.64066 -0.69026 -0.33630 0.36744 -0.83266 -0.41433 0.29878 -0.91958 -0.25516 0.26435 -0.91036 -0.31837 -1.00000 -0.00000 0.00000 -1.00000 0.00003 0.00003 -1.00000 -0.00044 0.00026 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.45492 -0.69848 -0.55242 0.45573 -0.69856 -0.55166 0.62626 -0.65836 -0.41756 0.59609 -0.67308 -0.43777 0.39819 -0.76716 -0.50290 -0.43938 -0.71403 -0.54507 -0.60326 -0.71049 -0.36234 -0.51410 -0.73917 -0.43513 -0.45554 -0.75926 -0.46477 -0.39950 -0.78139 -0.47941 -0.00634 -0.89015 -0.45563 -0.00005 -0.87655 -0.48130 -0.00000 -0.81914 0.57360 -0.00019 -0.81919 0.57352 0.00014 -0.81912 0.57362 -0.00014 -0.81916 0.57357 0.00019 -0.81919 0.57352 -0.00014 -0.81912 0.57362 0.00014 -0.81916 0.57357 -0.68186 0.46553 -0.56422 -0.66333 0.36884 -0.65111 0.66333 0.36884 -0.65111 0.68186 0.46553 -0.56422 -0.98563 0.00128 -0.16894 0.98583 0.00128 -0.16773 -0.27402 0.79933 -0.53477 0.52064 0.85377 -0.00301 0.04210 -0.57464 -0.81732 0.11996 -0.67436 -0.72860 + + + + + + + + + + + + + + +

4 0 5 0 6 0 3 1 0 1 8 1 13 2 21 2 14 2 12 3 13 3 14 3 20 4 21 4 13 4 12 5 15 5 13 5 19 6 18 6 16 6 20 7 18 7 21 7 19 8 17 8 18 8 18 9 17 9 21 9 30 10 31 10 32 10 33 11 30 11 32 11 44 12 45 12 1 12 2 13 1 13 45 13 45 14 46 14 2 14 2 15 46 15 47 15 48 16 2 16 47 16 47 17 49 17 48 17 50 18 48 18 49 18 50 19 49 19 51 19 52 20 50 20 51 20 52 21 51 21 53 21 3 22 52 22 53 22 60 23 63 23 62 23 64 24 63 24 60 24 59 25 64 25 60 25 65 26 62 26 63 26 66 27 67 27 65 27 63 28 66 28 65 28 66 29 63 29 64 29 64 30 48 30 50 30 68 31 64 31 50 31 64 32 68 32 66 32 69 33 67 33 66 33 50 34 52 34 68 34 70 35 66 35 68 35 68 36 52 36 3 36 68 37 3 37 72 37 68 38 72 38 70 38 73 39 70 39 72 39 74 40 75 40 43 40 42 41 74 41 43 41 4 42 75 42 74 42 74 43 76 43 4 43 4 44 6 44 77 44 77 45 78 45 35 45 78 46 79 46 35 46 81 47 30 47 33 47 33 48 41 48 81 48 82 49 81 49 41 49 41 50 40 50 82 50 83 51 8 51 84 51 38 52 0 52 3 52 83 53 3 53 8 53 82 54 40 54 39 54 82 55 39 55 38 55 9 56 3 56 83 56 72 57 3 57 9 57 9 58 85 58 72 58 85 59 86 59 72 59 73 60 72 60 86 60 61 61 62 61 65 61 65 62 67 62 61 62 67 63 69 63 58 63 56 64 58 64 69 64 69 65 71 65 56 65 57 66 56 66 71 66 71 67 70 67 57 67 54 68 57 68 70 68 70 69 73 69 54 69 55 70 54 70 73 70 73 71 86 71 55 71 80 72 55 72 86 72 86 73 85 73 80 73 85 74 9 74 80 74 80 75 9 75 10 75 9 76 83 76 10 76 83 77 84 77 10 77 87 78 84 78 8 78 8 79 0 79 87 79 37 80 38 80 39 80 82 81 38 81 53 81 38 82 3 82 53 82 59 83 2 83 64 83 48 84 64 84 2 84 131 85 28 85 115 85 120 86 115 86 22 86 141 87 126 87 29 87 95 88 126 88 141 88 92 89 89 89 26 89 94 90 24 90 93 90 25 91 24 91 94 91 91 92 24 92 25 92 27 93 24 93 91 93 90 94 27 94 91 94 27 95 90 95 97 95 90 96 124 96 97 96 124 97 90 97 125 97 109 98 125 98 90 98 125 99 109 99 122 99 108 100 122 100 109 100 122 101 108 101 123 101 110 102 123 102 108 102 123 103 110 103 121 103 112 104 121 104 110 104 114 105 118 105 112 105 118 106 114 106 117 106 91 107 107 107 90 107 107 108 91 108 25 108 107 109 25 109 29 109 25 110 94 110 29 110 95 111 141 111 140 111 94 112 92 112 29 112 29 113 92 113 26 113 29 114 26 114 141 114 94 115 93 115 92 115 95 116 139 116 96 116 138 117 96 117 139 117 138 118 149 118 96 118 99 119 145 119 98 119 100 120 145 120 99 120 104 121 100 121 101 121 104 122 101 122 102 122 106 123 104 123 103 123 104 124 106 124 105 124 137 125 136 125 106 125 106 126 136 126 105 126 90 127 107 127 109 127 111 128 109 128 107 128 111 129 107 129 29 129 111 130 29 130 127 130 109 131 111 131 113 131 129 132 111 132 127 132 110 133 113 133 112 133 115 134 113 134 111 134 111 135 129 135 115 135 115 136 129 136 131 136 113 137 115 137 116 137 116 138 114 138 113 138 113 139 114 139 112 139 114 140 116 140 117 140 120 141 119 141 115 141 115 142 119 142 116 142 119 143 117 143 116 143 29 144 126 144 127 144 127 145 126 145 128 145 127 146 128 146 129 146 129 147 128 147 130 147 129 148 130 148 131 148 132 149 131 149 130 149 131 150 132 150 28 150 28 151 132 151 133 151 134 152 22 152 133 152 133 153 22 153 28 153 135 154 22 154 134 154 147 155 149 155 138 155 149 156 147 156 148 156 142 157 144 157 143 157 31 158 146 158 148 158 30 159 146 159 31 159 146 160 149 160 148 160 150 161 151 161 152 161 146 162 153 162 162 162 146 163 162 163 157 163 164 164 163 164 162 164 190 165 188 165 189 165 176 166 190 166 175 166 188 167 169 167 167 167 191 168 169 168 188 168 188 169 190 169 191 169 192 170 176 170 177 170 190 171 176 171 192 171 192 172 191 172 190 172 169 173 191 173 171 173 178 174 192 174 177 174 191 175 173 175 171 175 193 176 173 176 191 176 191 177 192 177 193 177 194 178 193 178 192 178 194 179 178 179 179 179 192 180 178 180 194 180 173 181 193 181 174 181 180 182 194 182 179 182 193 183 194 183 195 183 193 184 172 184 174 184 195 185 172 185 193 185 194 186 180 186 196 186 196 187 195 187 194 187 181 188 196 188 180 188 172 189 195 189 170 189 195 190 196 190 197 190 197 191 170 191 195 191 198 192 197 192 196 192 198 193 181 193 182 193 196 194 181 194 198 194 183 195 198 195 182 195 170 196 197 196 168 196 197 197 198 197 199 197 197 198 166 198 168 198 199 199 166 199 197 199 200 200 199 200 198 200 200 201 183 201 184 201 198 202 183 202 200 202 185 203 200 203 184 203 203 204 242 204 244 204 203 205 201 205 202 205 240 206 242 206 203 206 218 207 219 207 202 207 204 208 202 208 220 208 202 209 219 209 220 209 202 210 204 210 203 210 203 211 205 211 240 211 205 212 238 212 240 212 205 213 203 213 204 213 235 214 238 214 205 214 220 215 221 215 204 215 206 216 204 216 222 216 204 217 221 217 222 217 204 218 206 218 205 218 205 219 207 219 235 219 207 220 205 220 206 220 233 221 235 221 207 221 222 222 223 222 206 222 206 223 208 223 207 223 208 224 206 224 223 224 207 225 209 225 233 225 209 226 231 226 233 226 209 227 207 227 208 227 223 228 224 228 208 228 232 229 231 229 209 229 210 230 208 230 225 230 208 231 224 231 225 231 208 232 210 232 209 232 211 233 209 233 210 233 209 234 211 234 232 234 211 235 234 235 232 235 225 236 226 236 210 236 236 237 234 237 211 237 210 238 212 238 211 238 212 239 210 239 227 239 210 240 226 240 227 240 214 241 211 241 212 241 211 242 214 242 236 242 214 243 239 243 236 243 227 244 228 244 212 244 241 245 239 245 214 245 212 246 213 246 214 246 213 247 212 247 230 247 212 248 245 248 230 248 212 249 228 249 245 249 214 250 215 250 241 250 214 251 213 251 215 251 243 252 241 252 229 252 241 253 215 253 229 253 187 254 186 254 216 254 217 255 216 255 186 255 186 256 185 256 217 256 218 257 217 257 185 257 185 258 184 258 218 258 219 259 218 259 184 259 184 260 183 260 219 260 220 261 219 261 183 261 183 262 182 262 220 262 221 263 220 263 182 263 182 264 181 264 221 264 222 265 221 265 181 265 181 266 180 266 222 266 223 267 222 267 180 267 180 268 179 268 223 268 224 269 223 269 179 269 179 270 178 270 224 270 225 271 224 271 178 271 178 272 177 272 225 272 226 273 225 273 177 273 177 274 176 274 226 274 227 275 226 275 176 275 176 276 175 276 227 276 228 277 227 277 175 277 175 278 164 278 228 278 245 279 228 279 164 279 240 280 238 280 237 280 242 281 240 281 237 281 241 282 243 282 237 282 244 283 242 283 237 283 245 284 164 284 162 284 162 285 246 285 245 285 296 286 266 286 287 286 296 287 287 287 158 287 249 288 253 288 248 288 253 289 255 289 254 289 253 290 249 290 255 290 250 291 255 291 249 291 254 292 255 292 256 292 257 293 250 293 135 293 255 294 250 294 257 294 257 295 256 295 255 295 256 296 257 296 258 296 134 297 257 297 135 297 259 298 258 298 257 298 257 299 134 299 259 299 133 300 259 300 134 300 258 301 259 301 260 301 261 302 260 302 259 302 259 303 133 303 261 303 132 304 261 304 133 304 260 305 261 305 262 305 261 306 263 306 262 306 264 307 263 307 261 307 264 308 132 308 130 308 261 309 132 309 264 309 266 310 265 310 267 310 268 311 270 311 269 311 268 312 320 312 270 312 265 313 320 313 268 313 268 314 267 314 265 314 271 315 268 315 269 315 267 316 268 316 272 316 273 317 271 317 288 317 268 318 271 318 273 318 268 319 274 319 272 319 273 320 274 320 268 320 275 321 273 321 288 321 274 322 273 322 276 322 273 323 277 323 276 323 273 324 278 324 277 324 273 325 275 325 278 325 253 326 277 326 278 326 283 327 274 327 276 327 284 328 274 328 283 328 161 329 285 329 279 329 274 330 284 330 272 330 284 331 285 331 272 331 286 332 272 332 285 332 285 333 161 333 286 333 160 334 286 334 161 334 272 335 286 335 267 335 287 336 160 336 159 336 286 337 160 337 287 337 287 338 267 338 286 338 158 339 287 339 159 339 267 340 287 340 266 340 270 341 21 341 17 341 320 342 21 342 270 342 269 343 17 343 19 343 269 344 270 344 17 344 275 345 289 345 290 345 288 346 289 346 275 346 291 347 275 347 290 347 288 348 16 348 289 348 271 349 16 349 288 349 271 350 19 350 16 350 269 351 19 351 271 351 128 352 126 352 252 352 130 353 128 353 252 353 130 354 252 354 264 354 252 355 263 355 264 355 251 356 263 356 252 356 247 357 275 357 291 357 247 358 278 358 275 358 247 359 248 359 278 359 248 360 253 360 278 360 149 361 146 361 157 361 149 362 157 362 280 362 149 363 280 363 96 363 96 364 280 364 281 364 96 365 281 365 95 365 95 366 281 366 282 366 126 367 95 367 282 367 126 368 282 368 251 368 126 369 251 369 252 369 53 370 333 370 334 370 53 371 334 371 303 371 53 372 303 372 82 372 82 373 303 373 304 373 81 374 82 374 304 374 81 375 304 375 305 375 30 376 81 376 305 376 30 377 305 377 153 377 30 378 153 378 146 378 337 379 309 379 332 379 338 380 309 380 337 380 338 381 311 381 309 381 338 382 292 382 311 382 334 383 333 383 322 383 333 384 321 384 322 384 49 385 321 385 333 385 49 386 333 386 51 386 51 387 333 387 53 387 317 388 315 388 12 388 315 389 15 389 12 389 315 390 295 390 15 390 295 391 294 391 15 391 292 392 293 392 311 392 295 393 311 393 294 393 311 394 293 394 294 394 317 395 14 395 316 395 317 396 12 396 14 396 320 397 316 397 21 397 316 398 14 398 21 398 319 399 266 399 296 399 158 400 156 400 296 400 296 401 297 401 319 401 297 402 296 402 155 402 296 403 156 403 155 403 314 404 319 404 297 404 155 405 154 405 297 405 298 406 297 406 154 406 297 407 298 407 314 407 299 408 314 408 298 408 312 409 314 409 299 409 154 410 307 410 298 410 300 411 298 411 307 411 298 412 300 412 299 412 299 413 301 413 312 413 301 414 310 414 312 414 301 415 299 415 300 415 307 416 308 416 300 416 306 417 310 417 302 417 310 418 301 418 302 418 331 419 332 419 306 419 332 420 309 420 306 420 313 421 309 421 311 421 309 422 313 422 306 422 313 423 310 423 306 423 312 424 310 424 313 424 311 425 295 425 313 425 313 426 318 426 312 426 318 427 314 427 312 427 318 428 313 428 315 428 313 429 295 429 315 429 319 430 314 430 318 430 315 431 317 431 318 431 318 432 265 432 319 432 265 433 318 433 320 433 318 434 316 434 320 434 318 435 317 435 316 435 266 436 319 436 265 436 324 437 321 437 47 437 321 438 49 438 47 438 321 439 324 439 322 439 324 440 323 440 322 440 325 441 323 441 324 441 47 442 46 442 324 442 326 443 324 443 46 443 324 444 326 444 325 444 327 445 325 445 326 445 46 446 45 446 326 446 328 447 326 447 45 447 326 448 328 448 327 448 45 449 44 449 328 449 329 450 327 450 328 450 328 451 330 451 329 451 330 452 328 452 335 452 328 453 44 453 335 453 331 454 329 454 330 454 335 455 336 455 330 455 332 456 330 456 336 456 330 457 332 457 331 457 336 458 337 458 332 458 349 459 339 459 148 459 148 460 339 460 31 460 31 461 339 461 370 461 339 462 349 462 346 462 370 463 339 463 346 463 374 464 340 464 144 464 341 465 88 465 342 465 343 466 357 466 344 466 343 467 342 467 357 467 341 468 342 468 343 468 343 469 344 469 345 469 345 470 347 470 346 470 344 471 347 471 345 471 343 472 348 472 341 472 138 473 348 473 147 473 349 474 147 474 348 474 349 475 343 475 345 475 348 476 343 476 349 476 147 477 349 477 148 477 346 478 349 478 345 478 359 479 102 479 358 479 354 480 144 480 340 480 351 481 356 481 355 481 357 482 342 482 356 482 356 483 351 483 357 483 344 484 357 484 351 484 362 485 363 485 365 485 364 486 367 486 363 486 365 487 363 487 367 487 366 488 374 488 34 488 5 489 360 489 361 489 351 490 355 490 367 490 367 491 364 491 351 491 344 492 351 492 364 492 346 493 372 493 370 493 32 494 31 494 370 494 371 495 370 495 373 495 370 496 372 496 373 496 370 497 371 497 32 497 33 498 32 498 371 498 373 499 37 499 371 499 344 500 364 500 347 500 364 501 372 501 347 501 372 502 346 502 347 502 373 503 372 503 364 503 37 504 373 504 362 504 373 505 363 505 362 505 373 506 364 506 363 506 37 507 362 507 36 507 355 508 356 508 352 508 368 509 352 509 350 509 34 510 144 510 142 510 341 511 26 511 88 511 141 512 26 512 341 512 104 513 102 513 103 513 101 514 358 514 102 514 358 515 101 515 380 515 100 516 380 516 101 516 380 517 100 517 379 517 99 518 379 518 100 518 379 519 99 519 23 519 98 520 23 520 99 520 23 521 98 521 353 521 375 522 353 522 98 522 353 523 375 523 354 523 354 524 375 524 144 524 93 525 89 525 92 525 88 526 26 526 89 526 350 527 377 527 378 527 350 528 378 528 359 528 358 529 350 529 359 529 380 530 350 530 358 530 376 531 377 531 350 531 376 532 350 532 352 532 88 533 376 533 342 533 341 534 348 534 139 534 348 535 138 535 139 535 341 536 140 536 141 536 376 537 352 537 356 537 356 538 342 538 376 538 365 539 389 539 362 539 389 540 365 540 385 540 37 541 39 541 40 541 37 542 40 542 41 542 371 543 41 543 33 543 37 544 41 544 371 544 36 545 362 545 389 545 389 546 385 546 369 546 369 547 385 547 386 547 389 548 369 548 388 548 381 549 361 549 369 549 361 550 360 550 369 550 369 551 360 551 387 551 369 552 387 552 388 552 87 553 0 553 36 553 34 554 390 554 366 554 383 555 366 555 390 555 390 556 79 556 383 556 11 557 383 557 79 557 79 558 78 558 11 558 384 559 11 559 78 559 78 560 77 560 384 560 381 561 384 561 77 561 77 562 6 562 381 562 361 563 381 563 6 563 6 564 5 564 361 564 4 565 76 565 5 565 368 566 350 566 369 566 369 567 386 567 368 567 37 568 0 568 38 568 36 569 0 569 37 569 34 570 374 570 144 570 352 571 368 571 355 571 54 572 55 572 393 572 393 573 394 573 54 573 393 574 391 574 394 574 395 575 54 575 394 575 395 576 56 576 57 576 54 577 395 577 57 577 58 578 56 578 395 578 59 579 394 579 392 579 394 580 59 580 395 580 60 581 61 581 58 581 395 582 60 582 58 582 60 583 395 583 59 583 62 584 61 584 60 584 55 585 80 585 393 585 58 586 61 586 67 586 7 587 80 587 10 587 393 588 80 588 7 588 393 589 74 589 42 589 74 590 393 590 7 590 106 591 27 591 398 591 398 592 137 592 106 592 121 593 112 593 118 593 97 594 398 594 27 594 398 595 97 595 124 595 117 596 119 596 118 596 119 597 120 597 396 597 396 598 121 598 119 598 119 599 121 599 118 599 397 600 396 600 120 600 120 601 399 601 397 601 121 602 396 602 123 602 125 603 122 603 396 603 396 604 122 604 123 604 396 605 397 605 125 605 397 606 400 606 398 606 398 607 125 607 397 607 125 608 398 608 124 608 34 609 142 609 403 609 375 610 145 610 144 610 143 611 144 611 145 611 137 612 247 612 136 612 400 613 247 613 137 613 400 614 248 614 247 614 401 615 248 615 400 615 248 616 401 616 249 616 399 617 249 617 401 617 249 618 399 618 250 618 399 619 135 619 250 619 22 620 135 620 399 620 400 621 397 621 401 621 397 622 399 622 401 622 145 623 100 623 104 623 145 624 375 624 98 624 103 625 24 625 27 625 247 626 291 626 136 626 143 627 20 627 142 627 18 628 20 628 143 628 136 629 291 629 105 629 105 630 291 630 290 630 105 631 290 631 104 631 104 632 290 632 289 632 145 633 104 633 289 633 145 634 289 634 16 634 145 635 18 635 143 635 145 636 16 636 18 636 399 637 120 637 22 637 400 638 137 638 398 638 106 639 103 639 27 639 74 640 7 640 76 640 391 641 393 641 42 641 392 642 1 642 59 642 35 643 13 643 15 643 35 644 403 644 13 644 35 645 15 645 294 645 35 646 294 646 4 646 4 647 294 647 293 647 75 648 4 648 293 648 75 649 293 649 292 649 43 650 75 650 292 650 13 651 403 651 20 651 403 652 142 652 20 652 338 653 43 653 292 653 367 654 382 654 365 654 76 655 7 655 10 655 79 656 390 656 35 656 35 657 4 657 77 657 394 658 402 658 392 658 391 659 402 659 394 659 1 660 392 660 44 660 392 661 335 661 44 661 336 662 335 662 392 662 392 663 402 663 336 663 337 664 336 664 402 664 402 665 391 665 337 665 391 666 338 666 337 666 391 667 42 667 338 667 42 668 43 668 338 668 382 669 367 669 355 669 355 670 368 670 382 670 386 671 382 671 368 671 403 672 35 672 34 672 390 673 34 673 35 673 152 674 151 674 547 674 547 675 548 675 152 675 404 676 152 676 548 676 404 677 405 677 152 677 406 678 407 678 152 678 406 679 152 679 405 679 406 680 405 680 408 680 409 681 406 681 408 681 409 682 410 682 407 682 406 683 409 683 407 683 411 684 410 684 409 684 408 685 412 685 409 685 409 686 412 686 413 686 409 687 413 687 414 687 415 688 409 688 414 688 415 689 416 689 411 689 409 690 415 690 411 690 407 691 150 691 152 691 417 692 150 692 407 692 418 693 417 693 407 693 410 694 419 694 418 694 407 695 410 695 418 695 410 696 411 696 419 696 416 697 420 697 421 697 416 698 421 698 419 698 411 699 416 699 419 699 331 700 422 700 329 700 327 701 329 701 422 701 422 702 423 702 327 702 327 703 423 703 424 703 325 704 327 704 424 704 424 705 425 705 325 705 325 706 425 706 426 706 418 707 428 707 427 707 427 708 308 708 418 708 417 709 418 709 308 709 307 710 150 710 417 710 308 711 307 711 417 711 307 712 154 712 150 712 429 713 431 713 430 713 430 714 431 714 432 714 433 715 430 715 432 715 245 716 246 716 433 716 432 717 245 717 433 717 434 718 246 718 153 718 305 719 433 719 434 719 153 720 305 720 434 720 430 721 433 721 305 721 305 722 304 722 430 722 429 723 430 723 304 723 304 724 303 724 429 724 435 725 429 725 303 725 303 726 334 726 435 726 438 727 428 727 439 727 439 728 441 728 440 728 441 729 443 729 442 729 443 730 422 730 331 730 444 731 427 731 438 731 438 732 440 732 444 732 302 733 444 733 440 733 440 734 442 734 302 734 306 735 302 735 442 735 442 736 331 736 306 736 308 737 427 737 444 737 444 738 300 738 308 738 444 739 302 739 301 739 300 740 444 740 301 740 445 741 446 741 447 741 447 742 420 742 445 742 448 743 445 743 420 743 416 744 449 744 448 744 420 745 416 745 448 745 413 746 450 746 237 746 450 747 244 747 237 747 449 748 416 748 415 748 449 749 415 749 414 749 449 750 414 750 413 750 449 751 413 751 237 751 243 752 449 752 237 752 230 753 245 753 451 753 230 754 451 754 452 754 213 755 230 755 452 755 213 756 452 756 453 756 213 757 453 757 454 757 215 758 213 758 454 758 454 759 455 759 215 759 229 760 215 760 455 760 455 761 449 761 229 761 243 762 229 762 449 762 437 763 436 763 456 763 457 764 456 764 436 764 436 765 458 765 457 765 459 766 457 766 458 766 458 767 460 767 459 767 461 768 459 768 460 768 460 769 462 769 461 769 463 770 461 770 462 770 462 771 464 771 463 771 465 772 463 772 464 772 464 773 466 773 465 773 467 774 465 774 466 774 466 775 441 775 467 775 467 776 441 776 439 776 428 777 467 777 439 777 436 778 426 778 458 778 460 779 458 779 426 779 426 780 425 780 460 780 462 781 460 781 425 781 425 782 424 782 462 782 464 783 462 783 424 783 424 784 423 784 464 784 466 785 464 785 423 785 423 786 422 786 466 786 466 787 422 787 443 787 466 788 443 788 441 788 456 789 455 789 454 789 454 790 453 790 456 790 468 791 456 791 453 791 429 792 469 792 431 792 469 793 429 793 435 793 469 794 435 794 437 794 468 795 469 795 437 795 437 796 456 796 468 796 457 797 455 797 456 797 459 798 449 798 455 798 457 799 459 799 455 799 448 800 449 800 459 800 459 801 461 801 448 801 445 802 448 802 461 802 461 803 463 803 445 803 446 804 445 804 463 804 465 805 447 805 446 805 463 806 465 806 446 806 420 807 447 807 465 807 465 808 467 808 420 808 421 809 420 809 467 809 428 810 419 810 421 810 467 811 428 811 421 811 468 812 453 812 452 812 452 813 469 813 468 813 431 814 469 814 432 814 469 815 451 815 245 815 432 816 469 816 245 816 469 817 452 817 451 817 418 818 419 818 428 818 216 819 404 819 187 819 548 820 187 820 404 820 201 821 203 821 244 821 470 822 217 822 218 822 202 823 470 823 218 823 470 824 202 824 201 824 216 825 217 825 470 825 244 826 450 826 201 826 201 827 450 827 413 827 201 828 413 828 412 828 408 829 201 829 412 829 201 830 408 830 470 830 470 831 405 831 216 831 470 832 408 832 405 832 404 833 216 833 405 833 325 834 426 834 323 834 426 835 436 835 323 835 323 836 436 836 322 836 322 837 436 837 437 837 334 838 322 838 437 838 334 839 437 839 435 839 246 840 162 840 153 840 427 841 428 841 438 841 438 842 439 842 440 842 440 843 441 843 442 843 331 844 442 844 443 844 254 845 512 845 513 845 509 846 513 846 514 846 517 847 509 847 515 847 527 848 517 848 516 848 163 849 157 849 162 849 251 850 520 850 518 850 251 851 518 851 263 851 263 852 518 852 519 852 262 853 263 853 519 853 528 854 262 854 519 854 260 855 262 855 528 855 548 856 471 856 187 856 473 857 471 857 472 857 473 858 187 858 471 858 474 859 473 859 472 859 472 860 541 860 474 860 474 861 541 861 540 861 474 862 540 862 502 862 501 863 474 863 502 863 187 864 473 864 186 864 473 865 474 865 200 865 200 866 185 866 473 866 473 867 185 867 186 867 474 868 501 868 199 868 199 869 501 869 499 869 199 870 200 870 474 870 166 871 199 871 499 871 498 872 188 872 167 872 189 873 497 873 190 873 190 874 497 874 164 874 190 875 164 875 175 875 188 876 498 876 475 876 475 877 493 877 188 877 188 878 493 878 189 878 500 879 475 879 498 879 535 880 516 880 477 880 476 881 496 881 495 881 523 882 164 882 476 882 476 883 164 883 496 883 495 884 478 884 476 884 478 885 495 885 494 885 480 886 534 886 516 886 516 887 534 887 477 887 482 888 533 888 480 888 480 889 533 889 534 889 533 890 482 890 505 890 484 891 506 891 482 891 482 892 506 892 505 892 506 893 484 893 507 893 486 894 507 894 484 894 507 895 486 895 504 895 488 896 504 896 486 896 504 897 488 897 503 897 490 898 491 898 488 898 488 899 491 899 503 899 491 900 490 900 492 900 490 901 479 901 492 901 518 902 478 902 479 902 478 903 518 903 476 903 476 904 518 904 520 904 476 905 520 905 525 905 525 906 523 906 476 906 478 907 494 907 479 907 492 908 479 908 494 908 481 909 514 909 512 909 481 910 512 910 532 910 531 911 481 911 532 911 481 912 531 912 483 912 530 913 483 913 531 913 483 914 530 914 485 914 529 915 485 915 530 915 485 916 529 916 487 916 528 917 487 917 529 917 487 918 528 918 489 918 519 919 489 919 528 919 516 920 515 920 480 920 480 921 515 921 514 921 481 922 480 922 514 922 480 923 481 923 482 923 483 924 482 924 481 924 482 925 483 925 484 925 485 926 484 926 483 926 484 927 485 927 486 927 487 928 486 928 485 928 486 929 487 929 488 929 489 930 488 930 487 930 488 931 489 931 490 931 519 932 490 932 489 932 490 933 519 933 479 933 518 934 479 934 519 934 500 935 503 935 475 935 475 936 503 936 491 936 475 937 491 937 493 937 493 938 491 938 492 938 493 939 492 939 189 939 189 940 492 940 494 940 189 941 494 941 495 941 189 942 495 942 497 942 497 943 495 943 496 943 497 944 496 944 164 944 499 945 165 945 166 945 498 946 165 946 500 946 501 947 165 947 499 947 500 948 165 948 503 948 533 949 504 949 538 949 538 950 504 950 503 950 504 951 533 951 507 951 505 952 507 952 533 952 507 953 505 953 506 953 508 954 279 954 285 954 285 955 284 955 508 955 283 956 508 956 284 956 279 957 508 957 526 957 508 958 283 958 511 958 511 959 283 959 510 959 511 960 526 960 508 960 277 961 510 961 276 961 276 962 510 962 283 962 526 963 511 963 527 963 513 964 277 964 254 964 277 965 513 965 509 965 277 966 509 966 510 966 511 967 510 967 509 967 517 968 511 968 509 968 511 969 517 969 527 969 512 970 254 970 532 970 514 971 513 971 512 971 515 972 509 972 514 972 517 973 515 973 516 973 282 974 520 974 251 974 520 975 282 975 525 975 281 976 525 976 282 976 525 977 281 977 524 977 280 978 524 978 281 978 524 979 280 979 522 979 157 980 521 980 280 980 280 981 521 981 522 981 157 982 163 982 521 982 277 983 253 983 254 983 523 984 522 984 164 984 522 985 163 985 164 985 522 986 523 986 524 986 525 987 524 987 523 987 279 988 151 988 161 988 526 989 536 989 279 989 279 990 536 990 151 990 536 991 526 991 535 991 527 992 535 992 526 992 535 993 527 993 516 993 260 994 528 994 529 994 530 995 260 995 529 995 260 996 530 996 258 996 258 997 530 997 531 997 532 998 258 998 531 998 258 999 532 999 256 999 254 1000 256 1000 532 1000 533 1001 538 1001 534 1001 542 1002 477 1002 538 1002 538 1003 477 1003 534 1003 543 1004 477 1004 542 1004 545 1005 535 1005 543 1005 543 1006 535 1006 477 1006 535 1007 545 1007 536 1007 536 1008 545 1008 151 1008 547 1009 151 1009 545 1009 544 1010 542 1010 537 1010 537 1011 542 1011 538 1011 537 1012 539 1012 544 1012 544 1013 539 1013 540 1013 544 1014 540 1014 541 1014 472 1015 544 1015 541 1015 542 1016 544 1016 543 1016 546 1017 545 1017 544 1017 544 1018 545 1018 543 1018 544 1019 472 1019 546 1019 546 1020 472 1020 471 1020 546 1021 471 1021 547 1021 546 1022 547 1022 545 1022 548 1023 547 1023 471 1023 24 1024 103 1024 102 1024 24 1025 102 1025 359 1025 24 1026 359 1026 378 1026 24 1027 378 1027 377 1027 24 1028 377 1028 376 1028 24 1029 376 1029 88 1029 88 1030 89 1030 24 1030 5 1031 76 1031 10 1031 5 1032 10 1032 360 1032 10 1033 387 1033 360 1033 10 1034 388 1034 387 1034 10 1035 389 1035 388 1035 10 1036 36 1036 389 1036 36 1037 10 1037 87 1037 84 1038 87 1038 10 1038 89 1039 93 1039 24 1039 239 1040 241 1040 237 1040 236 1041 239 1041 237 1041 234 1042 236 1042 237 1042 232 1043 234 1043 237 1043 231 1044 232 1044 237 1044 231 1045 237 1045 233 1045 233 1046 237 1046 235 1046 235 1047 237 1047 238 1047 165 1048 168 1048 166 1048 165 1049 170 1049 168 1049 165 1050 172 1050 170 1050 165 1051 174 1051 172 1051 165 1052 173 1052 174 1052 165 1053 171 1053 173 1053 165 1054 169 1054 171 1054 165 1055 167 1055 169 1055 165 1056 498 1056 167 1056 165 1057 501 1057 502 1057 165 1058 502 1058 540 1058 165 1059 540 1059 539 1059 165 1060 539 1060 537 1060 165 1061 537 1061 538 1061 165 1062 538 1062 503 1062 381 1063 369 1063 384 1063 11 1064 384 1064 369 1064 11 1065 369 1065 383 1065 366 1066 383 1066 369 1066 366 1067 369 1067 374 1067 379 1068 350 1068 380 1068 23 1069 350 1069 379 1069 23 1070 353 1070 350 1070 353 1071 354 1071 350 1071 340 1072 350 1072 354 1072 340 1073 369 1073 350 1073 340 1074 374 1074 369 1074 150 1075 158 1075 151 1075 150 1076 156 1076 158 1076 150 1077 155 1077 156 1077 150 1078 154 1078 155 1078 151 1079 158 1079 159 1079 151 1080 159 1080 160 1080 151 1081 160 1081 161 1081 66 1082 70 1082 71 1082 66 1083 71 1083 69 1083 108 1084 113 1084 110 1084 108 1085 109 1085 113 1085 1 1086 2 1086 59 1086 22 1087 115 1087 28 1087 139 1088 140 1088 341 1088 95 1089 140 1089 139 1089 365 1090 382 1090 385 1090 382 1091 386 1091 385 1091

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5_no_rot_scaled.dae b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5_no_rot_scaled.dae new file mode 100644 index 0000000..cfcb960 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5_no_rot_scaled.dae @@ -0,0 +1,153 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:48:02 + 2025-02-20T09:48:02 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -7.1735 6.94911 4.21838 -9.932701 -1.15879 -3.1e-4 -9.92969 1.15514 -3.1e-4 -7.4536 6.66578 -3.1e-4 -6.19669 -7.61001 14.00068 -5.99999 -7.6976 7.99969 -5.93079 -7.72543 8.52069 -5.99999 -7.62085 -1.45521 -6.5373 7.42476 2.97619 -6 7.62007 -1.44611 -5.99999 -8.9e-4 -3.1e-4 -4.99999 3.65198 9.71969 -3.55469 -9.23031 23.11969 -3.56699 -8.6156 18.55868 -1.76899 -9.5904 22.63068 -4.59092 -8.80456 23.59968 4.59459 -8.80456 23.59968 1.77266 -9.5904 22.63068 3.57066 -8.6156 18.55868 3.55836 -9.23031 23.11969 0.00405997 -8.84559 18.22268 0.00405997 -9.69028 22.44568 9.93636 -1.15879 -3.1e-4 5.00366 3.81254 9.73169 6.00366 -8.9e-4 -3.1e-4 6.00366 7.62007 -1.44611 7.14516 6.97814 3.97919 6.00366 -7.62085 -1.45522 9.933361 1.15514 -3.1e-4 7.45726 6.66578 -3.1e-4 -4.47209 7.99911 23.99968 -0.9201 7.99911 10.96068 -2.7345 7.99911 10.65468 -5.10259 7.94911 9.74469 -3.99999 -8.00089 9.999691 -5.00999 -7.96456 14.00168 -6 6.94911 4.50619 -5.6464 6.94911 8.25268 -7.17349 6.94911 6.96669 -7.0646 7.04525 7.66968 -6.70469 7.3181 8.43568 -6.02019 7.68741 9.16469 -7.4536 -6.66756 -3.1e-4 -7.46809 -6.65131 13.99969 -9.91719 -1.28497 23.99968 -9.99999 -0.02063995 23.99968 -9.92209 1.24482 23.99968 -9.68389 2.49335 23.99968 -9.63909 2.66125 -3.1e-4 -8.93994 4.00025 23.99968 -9.119091 4.10304 -3.1e-4 -8.39959 5.42557 23.99968 -8.38479 5.44841 -3.1e-4 -7.47299 6.64398 23.99968 -6 -5.4987 -5.79131 -5.99999 -6.96596 -3.90192 -6 -3.36071 -7.26061 -6 -4.50038 -6.61501 -6 -2.24851 -7.67811 -9.4122 -1.47532 -3.03941 -8.06 -1.20361 -5.79601 -6 -1.13267 -7.91981 -6 -8.9e-4 -8.00031 -8.06 1.20183 -5.79601 -9.4122 1.47352 -3.03941 -6 1.13089 -7.91981 -7.3578 3.50247 -5.79601 -6 2.24673 -7.67811 -8.5105 4.2811 -3.03941 -6 3.35892 -7.26061 -6 5.49692 -5.79131 -6 4.4986 -6.61501 -6.62189 6.66578 -3.42181 -6 6.66577 -4.42251 -6.78489 -7.26453 -3.1e-4 -6.83189 -7.23065 13.99969 -5.99999 -7.6976 -3.1e-4 -5.71839 -7.8018 9.02269 -5.3855 -7.89522 9.44169 -4.95869 -7.97119 9.75468 -5.99999 -7.3473 -2.89871 -5.57889 7.84294 23.99968 -6.59929 7.38662 23.99968 -6 7.69581 -3.1e-4 -6 7.69581 2.18159 -6 7.34767 -2.89111 -6 7.07516 -3.64421 -6 7.31252 3.24219 6.00366 6.94911 4.50619 6.00366 7.31252 3.24219 6.00366 6.66577 -4.42252 6.00366 7.34767 -2.89111 6.66886 7.34083 3.17053 6.00366 7.69581 2.18159 6.00366 7.69581 -3.1e-4 6.60296 7.38662 23.99968 5.58256 7.84294 23.99968 6.00366 -7.18556 -3.39231 4.96236 -7.97119 9.75468 5.38916 -7.89522 9.44169 5.72206 -7.8018 9.02269 5.93446 -7.72543 8.52069 6.00366 -7.6976 7.99968 6.00366 -7.6976 -3.1e-4 6.20036 -7.61001 14.00068 6.83556 -7.23065 13.99968 6.78856 -7.26453 -3.1e-4 6.62556 6.66578 -3.42181 6.00366 4.4986 -6.61501 6.00366 5.49692 -5.79131 6.00366 3.35892 -7.26061 8.514161 4.2811 -3.03941 6.00366 2.24673 -7.67812 7.36146 3.50247 -5.79601 6.00366 1.13089 -7.91981 9.415861 1.47352 -3.03941 8.06366 1.20183 -5.79601 6.00366 -8.9e-4 -8.00031 6.00366 -1.13267 -7.91981 8.06366 -1.20361 -5.79601 9.415861 -1.47532 -3.03941 6.00366 -2.24851 -7.67812 6.00366 -4.50038 -6.61501 6.00366 -3.36071 -7.26061 6.00366 -6.66755 -4.42252 6.00366 -5.4987 -5.79131 7.47666 6.64398 23.99968 8.388461 5.44841 -3.1e-4 8.403261 5.42557 23.99968 9.12276 4.10304 -3.1e-4 8.943611 4.00025 23.99968 9.64276 2.66125 -3.1e-4 9.687561 2.49335 23.99968 9.92576 1.24482 23.99968 10.00366 -0.02063995 23.99968 9.92086 -1.28497 23.99968 7.47176 -6.65131 13.99968 7.45726 -6.66756 -3.1e-4 5.10626 7.94911 9.74469 6.02386 7.68741 9.16469 7.06826 7.04525 7.66968 7.17716 6.94911 6.96669 0.00405997 -8.00089 13.99868 3.58286 -8.00089 13.99868 4.00366 -8.00089 9.999691 5.01366 -7.96456 14.00168 0.003659963 7.99911 23.99968 2.73816 7.99911 10.65468 0.92376 7.99911 10.96068 4.47576 7.99911 23.99968 -3.99999 -5.02735 37.82068 4.00366 -5.02735 37.82068 -3.99999 -5.00089 39.42268 -4.48079 7.99911 34.49768 -3.53979 -8.82177 32.40168 -2.34909 -9.2897 31.73368 -1.16229 -9.554901 31.35468 4.48446 7.99911 34.49768 0.00345999 -9.63919 31.23468 1.16596 -9.554901 31.35468 2.35276 -9.2897 31.73368 3.54346 -8.82177 32.40168 0.003659963 7.99911 44.99968 4.46387 7.99911 44.99968 4.00366 6.94911 44.99968 7.00366 -8.9e-4 44.99968 7.00366 -3.61239 46.59969 7.00366 3.37761 47.04568 7.00366 -3.04855 47.51268 7.00366 2.70194 47.87968 7.00366 -2.25983 48.23969 7.00366 1.82715 48.50168 7.00366 -1.30441 48.72868 7.00366 0.81734 48.86368 7.00366 -0.25282 48.94168 4.00366 6.69274 46.86967 4.00366 5.94276 48.60168 4.00366 4.7537 50.06868 4.00366 3.21449 51.16068 4.00366 1.43786 51.79867 4.00366 -0.44483 51.93568 4.00366 -2.29479 51.56068 4.00366 -3.97553 50.70068 4.00366 -5.36307 49.42068 4.00366 -6.35507 47.81468 4.00366 -6.87828 46.00168 4.00366 -6.89415 44.11368 4.00366 -6.40153 42.29169 6.60256 4.84007 47.50069 5.76706 6.37616 44.99969 5.50366 5.81689 48.00468 6.60256 3.15259 49.44267 5.50366 3.78892 50.33968 6.60256 0.76172 50.39468 5.50366 0.9156 51.48367 6.60256 -1.79926 50.14268 5.50366 -2.16214 51.18068 6.60256 -3.9591 48.74368 5.50366 -4.7578 49.49968 6.60256 -5.23604 46.50967 5.50366 -6.29241 46.81468 -6.59889 -5.34526 43.93867 -5.49999 -6.29241 46.81468 -6.59889 -5.23604 46.50967 -5.49999 -4.7578 49.49968 -6.59889 -3.9591 48.74368 -5.49999 -2.16214 51.18068 -6.59889 -1.79926 50.14268 -5.49999 0.9156 51.48367 -6.59889 0.76172 50.39468 -5.49999 3.78892 50.33968 -6.59889 3.15259 49.44267 -5.49999 5.81689 48.00468 -5.76339 6.37616 44.99968 -6.59889 4.84007 47.50069 -6.42709 5.71247 44.99968 -3.99999 -6.40153 42.29169 -3.99999 -6.89415 44.11368 -3.99999 -6.87828 46.00168 -3.99999 -6.35507 47.81468 -3.99999 -5.36307 49.42068 -3.99999 -3.97553 50.70068 -3.99999 -2.29479 51.56068 -3.99999 -0.44483 51.93568 -3.99999 1.43786 51.79867 -3.99999 3.21449 51.16068 -3.99999 4.7537 50.06868 -3.99999 5.94276 48.60168 -3.99999 6.69274 46.86967 -6.85319 4.87616 44.99968 -4.92709 6.80228 44.99968 -6.99999 -0.25282 48.94168 -6.99999 0.81734 48.86368 -6.99999 -1.30441 48.72868 -6.99999 1.82715 48.50168 -6.99999 -2.25983 48.23969 -6.99999 2.70194 47.87968 -6.99999 -9e-4 44.99968 -6.99999 -3.04855 47.51268 -6.99999 3.37761 47.04568 -6.99999 -3.61239 46.59969 -6.99999 3.80368 46.06168 -6.99999 -3.90969 45.56868 -6.99999 3.94911 44.99968 -6.99999 -3.91855 44.49568 -3.99999 6.94911 44.99968 -4.46019 7.99911 44.99968 8.35526 -5.50089 23.99968 8.735361 -4.87502 23.99968 9.28136 -3.73246 23.99968 9.67876 -2.5291 23.99968 7.43666 6.6981 34.49368 8.314371 5.81849 29.52985 8.89386 -4.46979 29.51968 8.76546 -4.19563 35.80267 9.26076 -2.79232 29.51968 8.91906 -2.27439 35.04568 9.450961 -1.09815 29.51968 8.96676 -0.33818 35.04568 9.47666 0.60681 29.51968 8.94576 1.60178 35.04568 9.335761 2.31798 29.51968 8.83896 3.55496 35.04568 8.30708 5.67738 34.68957 8.98616 4.04325 29.51968 0.004159986 -10.00089 29.52368 0.003359973 -10.00089 30.08768 2.93366 -9.56529 30.58668 3.43473 -9.48162 29.13079 3.49076 -9.37344 25.99968 1.45316 -9.895441 25.99968 4.39459 -9.10315 25.99968 4.41876 -8.98168 31.25368 6.33566 -7.76061 29.52368 5.84346 -8.13534 32.22368 7.02016 -7.12658 25.99968 7.14446 -7.03138 33.48969 8.27176 -5.67266 35.04868 8.54566 -5.26191 29.52368 4.68486 -8.14347 33.37068 5.30646 7.91391 34.49867 6.09576 7.66057 34.49867 6.81586 7.24997 34.49968 6.91396 -7.18597 33.86967 5.65496 -8.25206 32.34668 5.01416 -8.44358 32.71868 3.31336 -9.32459 31.45968 1.18046 -9.86343 30.69068 5.37426 -8.43667 25.99968 5.71986 -8.20649 23.99968 6.46616 -7.63259 23.99968 7.16186 -6.98424 23.99968 -7.15819 -6.98424 23.99968 -6.46249 -7.63259 23.99968 -5.71619 -8.20649 23.99968 -5.37059 -8.43667 25.99968 -1.17679 -9.86343 30.69068 -3.30969 -9.32459 31.45968 -5.01049 -8.44358 32.71868 -5.65129 -8.25206 32.34668 -6.31069 -7.37931 34.23868 -6.91029 -7.18597 33.86967 -7.85419 -6.04028 35.50568 -6.81219 7.24997 34.49968 -6.09209 7.66057 34.49867 -5.30279 7.91391 34.49867 -8.268091 -5.67266 35.04868 -4.68119 -8.14347 33.37068 -5.72309 -7.25891 34.63368 -8.54199 -5.26191 29.52368 -7.14079 -7.03138 33.48969 -7.01649 -7.12658 25.99968 -5.83979 -8.13534 32.22368 -6.33199 -7.76061 29.52368 -4.41509 -8.98168 31.25368 -4.39092 -9.10315 25.99968 -1.44949 -9.895441 25.99968 -3.48709 -9.37343 25.99968 -3.43106 -9.48162 29.13079 -2.92999 -9.56529 30.58668 0.001839995 -10.00019 25.99969 -8.98249 4.04325 29.51968 -8.30341 5.67738 34.68957 -8.83529 3.55496 35.04568 -9.33209 2.31798 29.51968 -8.94209 1.60178 35.04568 -9.47299 0.60681 29.51968 -8.96309 -0.33818 35.04568 -9.44729 -1.09815 29.51968 -8.91539 -2.27439 35.04568 -9.25709 -2.79232 29.51968 -8.76179 -4.19563 35.80267 -8.890191 -4.46979 29.51968 -8.3107 5.81849 29.52985 -7.43299 6.6981 34.49368 -9.67509 -2.5291 23.99968 -9.27769 -3.73246 23.99968 -8.73169 -4.87502 23.99968 -8.351591 -5.50089 23.99968 0.001829981 7.242 10.60569 4.00366 4.25152 9.999691 5.65006 6.94911 8.25268 5.55006 6.94911 5.59469 3.89726 6.94911 9.21068 3.63686 6.94093 6.60969 1.98966 6.94911 9.80069 0.003659963 6.94911 9.999691 0.003659963 6.94911 7.84768 4.30636 7.242 9.80469 1.47496 7.242 10.60569 4.32487 5.06448 8.40697 3.63686 6.82538 6.40069 4.38886 6.06216 6.65668 4.68666 3.9459 9.879691 4.34936 4.09318 9.96969 3.63371 6.43688 6.43168 4.43506 6.73264 6.19568 4.49076 6.91366 6.33069 5.94346 3.82193 8.45469 6.004 4.02117 8.04468 -6 4.02117 8.04468 -5.93979 3.82193 8.45469 -5.54639 6.94911 5.59469 -4.5404 6.94911 6.46068 -3.6332 6.94093 6.60969 -4.45075 6.64691 6.24219 -4.34569 4.09222 9.96969 -3.6332 6.82538 6.40069 3.63321 5.95391 6.88068 -4.32395 5.11941 8.41997 -1.47129 7.242 10.60569 -4.30269 7.242 9.80469 -1.98599 6.94911 9.80069 -3.89359 6.94911 9.21068 -3.99999 4.25198 9.999691 4.47576 -8.00089 9.94269 6.00366 5.96671 5.62369 6.00366 4.86318 6.60168 6.00366 4.40365 7.39368 5.41736 3.62295 9.41469 5.73196 3.74311 9.003681 -5.72829 3.74311 9.003681 -3.63359 6.44435 6.42669 -4.68299 3.85204 9.879691 -5.41369 3.62295 9.41469 -4.3852 6.06216 6.65668 -3.6332 5.95391 6.88068 -5.99999 4.40365 7.39368 -5.99999 4.86318 6.60168 -6 5.96671 5.62369 -4.47209 -8.00089 9.94269 -8.38479 -5.4502 -3.1e-4 -9.63909 -2.66304 -3.1e-4 -6.78409 -6.66756 -3.03501 -8.5105 -4.2829 -3.03941 -7.3578 -3.50425 -5.79601 7.36146 -3.50425 -5.79601 8.514161 -4.2829 -3.03941 6.78776 -6.66756 -3.03501 9.64276 -2.66304 -3.1e-4 8.388461 -5.4502 -3.1e-4 9.12276 -4.10482 -3.1e-4 -9.119091 -4.10482 -3.1e-4 -3.57919 -8.00089 13.99868 -3.99999 -5.43664 40.66869 -5.48459 -5.09962 40.93769 -5.49999 -4.73356 40.21569 -5.76329 -4.42797 39.42269 -6.42709 -4.46943 41.43969 -6.59809 -3.69701 40.57769 -6.42699 -3.76429 39.42269 -6.85319 -2.92798 39.42269 -6.6831 -3.81534 41.96069 -6.99999 -3.09028 42.53869 -6.99999 -2.49594 41.59168 -6.99999 -2.12557 40.53269 -6.99999 -2.00089 39.42269 -5.36349 -4.67315 38.32668 -6.19619 -4.0446 39.22469 -6.72699 -3.25133 38.74369 -6.99999 -2.00089 38.27869 -6.96549 -2.4548 38.42168 -8.53599 -1.46623 39.60468 -8.55289 -0.11087 39.43468 -8.54059 1.25595 39.55968 -8.50409 2.50568 39.95368 -8.45399 3.57721 40.56069 -6.76829 -5.70594 36.85169 -6.86009 -4.0311 39.22569 -6.92969 7.10944 44.99969 -6.11599 7.64029 44.99969 -5.93589 7.04911 44.99969 -5.49999 6.94911 44.99969 -5.31029 7.90772 44.99969 -4.88529 7.95342 44.99969 -7.19169 6.82799 43.78869 -8.19199 4.97673 41.65069 -7.71279 6.06131 42.71468 -7.49639 -5.59217 36.77569 -7.60349 -3.56948 39.46268 -8.124691 -5.26918 36.55169 -8.062291 -2.97472 39.64069 -8.56689 -4.78127 36.21169 -8.399291 -2.25591 39.68868 -7.28129 -6.21366 35.90269 -6.99999 1.68717 38.19369 -6.99999 0.45891 38.00269 -6.99999 -0.78335 38.03168 -6.99999 2.86304 38.59969 -6.99999 3.94911 39.20568 -6.99999 -3.63839 43.45969 -5.03399 6.76527 43.41169 -5.49999 6.54719 42.67069 -5.9359 6.24091 41.72169 -6.39679 5.75341 40.92669 -6.83869 4.91954 39.95969 -7.08054 5.94669 41.49869 -7.43409 4.97597 40.42869 -8.19199 4.02715 40.55369 -7.43409 3.77077 39.39269 -8.19199 2.84199 39.71668 -7.43409 2.35678 38.66769 -8.19199 1.49065 39.18868 -7.43409 0.81253 38.29169 -8.19199 0.05166995 39.00069 -7.43409 -0.7768 38.28768 -8.19199 -1.39001 39.16369 -7.43409 -2.3232 38.65369 -6.72699 6.57048 42.44669 -6.72699 6.92842 43.70069 -5.49999 -6.42367 43.72469 5.48826 -5.09962 40.93769 6.43076 -4.46943 41.43969 5.50366 -6.42367 43.72469 6.60256 -5.34526 43.93868 6.85686 4.87616 44.99969 6.73066 6.92842 43.70069 6.73066 -3.25133 38.74369 6.73066 6.57048 42.44669 7.08421 5.94669 41.49869 7.43776 -2.3232 38.65369 8.19566 -1.39001 39.16369 7.43776 -0.7768 38.28768 8.19566 0.05166995 39.00069 7.43776 0.81253 38.29169 8.19566 1.49065 39.18868 7.43776 2.35678 38.66769 8.19566 2.84199 39.71668 7.43776 3.77077 39.39269 8.19566 4.02715 40.55369 7.43776 4.97597 40.42869 6.84236 4.91954 39.95969 6.40046 5.75341 40.92669 6.43076 5.71247 44.99969 5.93956 6.24091 41.72169 5.50366 6.54719 42.67069 5.03766 6.76527 43.41169 4.93076 6.80228 44.99969 7.00366 3.80368 46.06168 7.00366 -3.90969 45.56869 7.00366 3.94911 44.99969 7.00366 -3.91855 44.49569 7.00366 -3.63839 43.45969 7.00366 3.94911 39.20568 7.00366 2.86304 38.59969 7.00366 -0.78335 38.03168 7.00366 0.45891 38.00269 7.00366 1.68717 38.19369 6.31436 -7.37931 34.23869 8.12836 -5.26918 36.55169 7.85786 -6.04028 35.50568 7.28496 -6.21366 35.90269 8.40296 -2.25591 39.68868 8.57056 -4.78127 36.21169 8.06596 -2.97472 39.64069 7.60716 -3.56948 39.46268 6.99346 -4.00149 39.23769 7.50006 -5.59217 36.77569 7.71646 6.06131 42.71468 8.19566 4.97673 41.65069 7.19536 6.82799 43.78869 4.88896 7.95342 44.99969 5.31396 7.90772 44.99969 5.93956 7.04911 44.99969 6.11966 7.64029 44.99969 6.93336 7.10944 44.99969 5.72676 -7.25891 34.63369 6.77196 -5.70594 36.85169 8.45766 3.57721 40.56069 8.507761 2.50568 39.95368 8.54426 1.25595 39.55968 8.55656 -0.11086 39.43468 8.53966 -1.46623 39.60468 7.00366 -2.00089 38.27869 6.96916 -2.4548 38.42168 6.19986 -4.0446 39.22469 5.36716 -4.67315 38.32668 7.00366 -2.31088 41.06269 7.00366 -2.00089 39.42269 7.00366 -2.49594 41.59168 7.00366 -3.09028 42.53869 6.75609 -3.81534 41.96069 6.85686 -2.92798 39.42269 6.43066 -3.76429 39.42269 6.60176 -3.69701 40.57769 5.76696 -4.42797 39.42269 5.50366 -4.73356 40.21569 4.00366 -5.00089 39.42269 4.00366 -5.43664 40.66869 + + + + + + + + + + -0.3799088 -0.9250235 0.001048445 -0.6139672 0.7892366 -0.01224112 -0.0759257 -0.9767864 -0.200309 -0.2299373 -0.9645672 -0.1293793 -0.08133679 -0.9773278 -0.1954864 -0.4242824 -0.8975669 -0.1198255 0.4242821 -0.897567 -0.1198257 0.08143758 -0.9773196 -0.1954848 0.2299373 -0.9645672 -0.1293793 0.07610845 -0.9767886 -0.2002285 0 1 0 -0.02010369 0.9997945 -0.002617537 -0.9978624 -0.06534969 3.01319e-4 -0.9999951 0.001300692 -0.002865374 -0.9981107 0.06144225 8.64721e-5 -0.9822826 0.1874051 -3.89221e-4 -0.9818897 0.189453 -5.07475e-4 -0.896676 0.4426852 0.00142312 -0.9406546 0.3392596 0.008474588 -0.9350273 0.3544741 0.008497774 -0.8777682 0.4790858 -8.53726e-5 -0.7959709 0.6053348 8.52243e-5 -0.7942761 0.607557 -8.98341e-5 -0.7306165 0 -0.6827881 -0.8978016 0 -0.4404002 -0.8978015 0 -0.4404005 -0.7160986 0.04952156 -0.6962403 -0.7571126 0.1382995 -0.6384776 -0.6977736 0.212974 -0.6839255 -0.8561726 0.2613199 -0.4457358 -0.9219178 0.3325002 -0.1987744 -0.9382056 0.3013204 -0.1702246 -0.8568307 0.2751851 -0.4360212 -0.6972523 0.2519209 -0.6711 -0.868348 0.4739412 -0.1461215 -0.7374927 0.5031387 -0.4505063 -0.7787755 0.5957012 -0.1965932 -0.7842012 0.5905 -0.1906262 -0.7353641 0.5110189 -0.4450837 -0.722465 0.5257914 -0.4489853 -0.6732938 -0.7393749 -4.71043e-4 -0.6659585 -0.7459889 1.76529e-4 -0.5127453 -0.8585407 3.56307e-4 -0.4830961 -0.8755664 -0.001309394 -0.3447124 -0.9387034 0.003044724 -0.2800471 -0.959949 0.008464515 -0.1748322 -0.9845982 -5.74761e-4 -0.1397159 0.990188 0.002706468 -0.2731179 0.9619786 -0.001960813 -0.4082341 0.9128737 0.002573251 -0.4742823 0.8803726 -6.63911e-4 -0.4504006 0.8928266 0 -0.7111676 0.7030225 2.61297e-6 -0.5779047 0.8155508 -0.03005313 -0.6049246 0.7962827 5.90979e-4 -0.6756773 0.7371875 0.003842294 -0.5776383 0.8151751 -0.04270333 -0.646443 0.7466048 -0.1571398 -0.6768237 0.7234036 -0.1363707 -0.5952005 0.7556287 -0.2734258 -0.5995312 0.7083365 -0.372588 1 0 0 1 4.57914e-7 -4.87399e-6 1 6.60885e-7 -3.78783e-7 1 7.73188e-7 2.69209e-7 1 6.10067e-7 -2.46621e-7 1 6.28831e-7 -1.2847e-7 1 9.32973e-7 -2.24897e-6 1 1.37122e-6 0 1 1.13577e-6 0 0.02818775 0.9400969 0.3397405 0.01435941 0.9313032 0.3639617 0.1297287 0.9795094 -0.1540516 -0.6476441 0.7619397 0.002261519 -0.7119071 0.7022737 6.27266e-5 -0.9858108 0 -0.1678611 -0.9714014 0.1874296 -0.1457722 0.971401 0.1874295 -0.1457754 0.9856487 0 -0.1688096 0.7119134 0.7022674 6.24341e-5 0.6476438 0.7619401 0.002261519 0.004945993 0.9135041 0.4067998 -1 0 0 -1 1.67221e-7 0 -1 0 0 -1 0 0 -1 0 0 0.5476507 0.7643564 -0.3403499 0.6768175 0.7234092 -0.1363717 0.6464421 0.746606 -0.1571373 0.5776383 0.8151751 -0.04270333 0.6756373 0.7372242 0.00383985 0.5779066 0.8155539 -0.02993488 0.619653 0.7847682 -0.01300072 0.7033936 0.7108004 -6.27444e-4 0.4708018 0.8822391 0 0.4082344 0.9128735 0.002573251 0.2731176 0.9619786 -0.001960813 0.1397159 0.990188 0.002706468 0.1748364 -0.9845974 -5.74775e-4 0.2800377 -0.9599518 0.008463203 0.3447131 -0.9387032 0.003044724 0.3799099 -0.925023 0.001048922 0.4830951 -0.875567 -0.001309454 0.5127458 -0.8585404 3.56307e-4 0.6659643 -0.7459837 1.76075e-4 0.6732935 -0.7393752 -4.71043e-4 0.7224647 0.5257896 -0.4489881 0.7353649 0.511016 -0.4450857 0.7842025 0.5904989 -0.1906242 0.7787721 0.5957042 -0.1965978 0.7374925 0.5031391 -0.4505063 0.8683471 0.4739423 -0.146124 0.6972507 0.2519274 -0.6710993 0.8568306 0.2751851 -0.4360213 0.9382053 0.3013195 -0.1702275 0.9219167 0.3325015 -0.198777 0.8561726 0.2613199 -0.4457358 0.6977736 0.212974 -0.6839255 0.7571178 0.1382925 -0.6384732 0.7160985 0.04952156 -0.6962404 0.8978015 0 -0.4404005 0.8978016 0 -0.4404002 0.7306165 0 -0.6827881 0.794273 0.6075612 -9.01708e-5 0.7959702 0.6053359 8.52243e-5 0.8777693 0.4790838 -8.53857e-5 0.9350267 0.3544756 0.008497774 0.9406552 0.3392581 0.008474588 0.896676 0.4426852 0.00142312 0.9818896 0.1894538 -5.07507e-4 0.9822829 0.1874042 -3.89178e-4 0.9980943 0.06144225 -0.005712568 0.9999992 0.001295745 3.11856e-4 0.9978625 -0.06534868 3.00879e-4 0.02010363 0.9997945 -0.002617657 0 -1 -3.33183e-7 0 1 1.30838e-7 0 -0.9998636 0.01651459 0 0 1 0.699459 0.6890758 0.1895569 0.2289098 0.8932969 0.3868089 0.9624838 0.2108318 0.1708065 0.9594557 0.212758 0.1848753 0.6969233 0.541327 0.470386 0.3600229 0.7247664 0.5874498 0.308513 0.7181713 0.6237385 0.6971632 0.541269 0.4700971 0.967513 0.1465044 0.2060467 0.2193372 0.5645359 0.7957327 0.9575935 0.09722816 0.2712224 0.9614183 0.1017668 0.2555749 0.6972126 0.2651948 0.6660078 0.6971736 0.2651839 0.6660529 0.3007256 0.3223257 0.8975914 0.3444123 0.347271 0.8722288 0.9670221 0.01851361 0.2540191 0.2285001 0.07066261 0.9709761 0.6971852 -0.07020366 0.7134453 0.9501792 -0.0618782 0.3055006 0.9640705 -0.02601414 0.2643697 0.3623325 -0.09131467 0.927565 0.6971447 -0.07023918 0.7134815 0.2569239 -0.1919976 0.9471679 0.9653677 -0.1188648 0.2322424 0.6971182 -0.389773 0.6017503 0.9584006 -0.1551722 0.2395622 0.6971911 -0.389687 0.6017215 0.4292185 -0.4114192 0.8040559 0.252278 -0.5260005 0.8122065 0.2286626 -0.6600856 0.7155421 0.9669961 -0.1726864 0.1873446 0.6971476 -0.622424 0.355772 0.9624235 -0.2310442 0.1426877 0.9594331 -0.244772 0.1399094 0.6971164 -0.6224615 0.3557673 0.3600109 -0.7937372 0.4902789 0.3083918 -0.8258818 0.4720316 0.2194978 -0.9373604 0.2705109 -0.9576526 -0.2879167 0.002377569 -0.6970757 -0.7163515 0.03043162 -0.9675209 -0.2428946 0.07004058 -0.2194978 -0.9373604 0.2705109 -0.3083918 -0.8258818 0.4720316 -0.3600109 -0.7937372 0.4902789 -0.6971169 -0.6224611 0.3557673 -0.959433 -0.2447725 0.1399096 -0.9624231 -0.2310454 0.1426878 -0.6971476 -0.622424 0.355772 -0.9669961 -0.1726864 0.1873448 -0.2286626 -0.6600856 0.7155421 -0.252278 -0.5260005 0.8122065 -0.4292185 -0.4114191 0.804056 -0.6971914 -0.3896868 0.6017214 -0.9584004 -0.1551728 0.2395625 -0.6971185 -0.3897727 0.6017501 -0.9653677 -0.1188637 0.2322427 -0.2569239 -0.1919976 0.9471679 -0.6971448 -0.070239 0.7134814 -0.3623325 -0.09131467 0.927565 -0.9640705 -0.02601414 0.26437 -0.9501791 -0.06187868 0.3055009 -0.6971854 -0.07020372 0.7134452 -0.2285001 0.07066261 0.9709761 -0.967022 0.01851475 0.2540194 -0.3444123 0.3472709 0.8722288 -0.3007255 0.3223258 0.8975914 -0.6971738 0.2651837 0.6660528 -0.6972126 0.2651949 0.6660076 -0.9614183 0.1017662 0.2555752 -0.9575933 0.09722852 0.2712227 -0.2193372 0.564536 0.7957326 -0.967513 0.1465044 0.2060468 -0.6971634 0.5412688 0.4700971 -0.3085131 0.7181711 0.6237387 -0.3600229 0.7247664 0.5874498 -0.6969231 0.5413278 0.4703854 -0.9594557 0.2127577 0.1848756 -0.9624837 0.2108324 0.1708068 -0.2289098 0.8932969 0.3868089 -0.9670202 0.2337297 0.1012045 -0.6994597 0.6890752 0.1895562 -0.4446891 0.8727464 0.2014088 -0.1500748 0.9475706 0.2821127 -0.4295782 0.894661 0.1226552 -0.9501794 0.3088003 0.04244536 -0.6936243 0.6936355 0.1943067 -0.9874669 0.1563673 0.02141278 -0.8447947 0.4304234 0.3178956 0 -0.9653381 -0.2610028 0 -0.9653378 -0.2610037 0 -0.9999648 0.008405625 0 -0.9999648 0.008405148 0 -0.9607912 0.2772729 0 -0.9607913 0.277273 0 -0.8507841 0.5255154 0 -0.850784 0.5255157 0 -0.6780502 0.7350156 0 -0.6780502 0.7350156 0 -0.4555124 0.8902295 0 -0.4555125 0.8902295 0 -0.1986665 0.9800672 0 -0.1986665 0.9800672 0 0.0725829 0.9973624 0 0.3379701 0.9411569 0 0.3379701 0.9411569 0 0.578626 0.8155931 0 0.5786261 0.8155931 0 0.7768597 0.6296737 0 0.9176633 0.3973588 0 0.9176635 0.3973583 0 0.9907326 0.1358266 0 0.9907326 0.1358271 -1 0 0 0 -0.9749884 0.222256 0 -0.9245343 0.381099 0.9022545 -0.4311658 0.005745112 0.9764875 -0.2135774 0.02927517 0.976124 -0.2134988 0.04000508 0.948024 -0.3130773 0.05685973 0.9963483 -0.05341035 0.06661492 0.9776344 -0.1902419 0.08966118 0.9913359 -0.1112947 0.06976151 0.9911978 -0.1112794 0.07172036 0.9955846 -0.02452743 0.09060841 0.9940939 -0.06510329 0.08682727 0.9958893 -0.01501119 0.08932644 0.9951989 -0.01500093 0.09671789 0.9942417 0.06120407 0.08796417 0.9955418 0.0107764 0.09370434 0.9933758 0.08179557 0.08070921 0.9925646 0.08172851 0.09019994 0.9799824 0.1869666 0.06839597 0.9955196 0.05443531 0.07731437 0.9682614 0.247941 0.03154814 0.9779558 0.1981679 0.0658192 0.8966289 0.4426618 -0.01035964 0.9777716 0.1981301 0.06860983 0.1470032 -0.9891361 2.09995e-4 0.2480651 -0.9683088 -0.02901625 0.07172209 -0.9937151 0.08594286 0.1496278 -0.9887424 -2.95121e-4 0.149039 -0.9888159 -0.005531847 0.2864006 -0.9577018 -0.02796369 0.3403009 -0.9381902 0.06320196 0.562478 -0.8267962 0.005163013 0.5045124 -0.8619278 0.05047631 0.5346261 -0.8436591 -0.04913645 0.5126293 -0.8582266 -0.02566188 0.6226496 -0.7822504 -0.01979756 0.6410891 -0.7673967 0.01036179 0.7970201 -0.6017187 -0.0519002 0.7489991 -0.6624602 -0.01211839 0.7487949 -0.6622802 0.0262897 0.9153769 -0.4023008 0.01547068 0.6153915 -0.7864137 0.05335718 0.5700288 -0.8155577 0.09966385 0.1247459 -0.8758621 0.4661591 0.5187477 -0.8547754 -0.01612663 0.3764861 -0.9086223 0.1807313 0.3248482 -0.9228477 0.2069437 0.1331168 -0.8874807 0.4412004 0.09620517 -0.88767 0.4503185 0.3148171 -0.9412037 0.1225793 0.06741726 -0.9042549 0.4216374 0.0830574 -0.9096373 0.4070155 0.1755372 -0.9659669 0.189986 0.02219641 -0.9064726 0.421681 0.1616611 -0.9825876 -0.09158265 0.0649293 -0.9943587 -0.08387511 0.07171708 -0.9936583 -0.08660238 0.208957 -0.9769504 -0.04364818 0.2476602 -0.966728 -0.06404381 0.6092862 -0.792317 0.03168803 0.6226751 -0.7822833 0.01756477 0.6817677 -0.7315591 -0.003761589 0.4745671 -0.8800084 -0.01927512 0.561607 -0.8255136 -0.05590271 0.409902 -0.9087111 -0.07889592 0.2862735 -0.9572765 -0.040856 0.7956075 0.6050592 -0.03020125 0.9350122 0.3544702 -0.01015615 0.9352077 0.3539596 -0.009966015 0.9352367 0.3538522 0.01099866 0.7589787 0.6508421 0.01887196 0.7791006 -0.6268095 0.01058924 0.7732634 -0.6340846 7.7921e-4 0.8547009 -0.5190737 -0.007003486 0.9154593 -0.4023976 0.003254473 0.1030972 0.9946714 -8.55227e-5 0.1397158 0.9901871 -0.003019094 0.3056116 0.952155 0.001600563 0.4082323 0.9128689 -0.004097938 0.4953317 0.8687031 0.001262128 0.6476423 0.7619379 -0.00321561 0.6643888 0.747386 -0.001322031 0.7051305 0.709077 -9.69156e-4 -0.7051307 0.7090767 -9.69081e-4 -0.6643887 0.7473861 -0.001322031 -0.647643 0.7619373 -0.00321561 -0.4953312 0.8687033 0.001262128 -0.4082321 0.912869 -0.004097938 -0.3056116 0.952155 0.001600563 -0.1397157 0.9901871 -0.003019094 -0.1030972 0.9946713 -8.55227e-5 -0.9154574 -0.4024018 0.003254473 -0.8547025 -0.5190709 -0.007003366 -0.7732635 -0.6340844 7.79522e-4 -0.7791004 -0.6268098 0.01058894 -0.7589781 0.6508427 0.01887178 -0.935237 0.3538515 0.01099854 -0.9352076 0.3539597 -0.009966194 -0.9350122 0.3544702 -0.01015615 -0.7956079 0.6050586 -0.03020131 -0.2862634 -0.9572798 -0.0408523 -0.4099018 -0.9087113 -0.07889586 -0.561607 -0.8255136 -0.05590271 -0.4745674 -0.8800082 -0.01927512 -0.6817677 -0.7315591 -0.003761589 -0.6226751 -0.7822833 0.01756477 -0.6092863 -0.7923171 0.03168749 -0.2476648 -0.9667268 -0.0640437 -0.2089563 -0.9769506 -0.0436446 -0.07171607 -0.9936506 -0.0866912 -0.06476855 -0.9943678 -0.08389127 -0.1616078 -0.9825281 -0.09231173 -0.02213466 -0.9064741 0.4216809 -0.1755372 -0.9659669 0.1899862 -0.0830574 -0.9096373 0.4070156 -0.06741726 -0.9042549 0.4216374 -0.3148171 -0.9412038 0.1225789 -0.09620517 -0.8876698 0.4503187 -0.1331168 -0.8874802 0.4412016 -0.3248481 -0.9228479 0.2069436 -0.3764863 -0.9086222 0.1807314 -0.5187487 -0.8547747 -0.01612663 -0.1247459 -0.8758621 0.4661591 -0.1527347 -0.866174 0.4758308 -0.4117256 -0.8735862 0.2594783 -0.5700271 -0.8155589 0.09966355 -0.6153938 -0.7864118 0.05335736 -0.4326135 -0.8665297 0.248942 -0.1476498 -0.8632162 0.4827603 -0.7143134 -0.6942062 0.08851099 -0.6784806 -0.725324 0.1164872 -0.9425724 -0.3322913 0.03376227 -0.9153763 -0.4023022 0.01547038 -0.7487951 -0.66228 0.02628976 -0.7489992 -0.6624601 -0.01211845 -0.7970203 -0.6017185 -0.05190044 -0.6410887 -0.767397 0.01036196 -0.6226494 -0.7822505 -0.01979744 -0.512629 -0.8582267 -0.02566182 -0.5346265 -0.8436589 -0.04913651 -0.5045122 -0.8619278 0.05047631 -0.5624784 -0.826796 0.005163013 -0.3403007 -0.9381903 0.0632019 -0.2863907 -0.9577047 -0.02796787 -0.1488336 -0.9888464 -0.005604267 -0.1494517 -0.9887691 -9.78426e-5 -0.07172155 -0.9937152 0.08594262 -0.2480699 -0.9683075 -0.02901911 -0.146923 -0.989148 -2.0988e-4 -0.9777713 0.1981316 0.06860983 -0.8966289 0.4426618 -0.01035982 -0.9779558 0.1981671 0.06581944 -0.9682613 0.2479413 0.03154796 -0.9955196 0.05443459 0.07731419 -0.9799828 0.1869645 0.06839603 -0.9925644 0.08173012 0.0902 -0.9933757 0.08179718 0.08070909 -0.9955418 0.0107764 0.09370434 -0.9942417 0.06120407 0.08796411 -0.9951989 -0.01500177 0.09671777 -0.9958893 -0.0150128 0.08932638 -0.9940939 -0.06510329 0.08682739 -0.9955846 -0.02452677 0.09060823 -0.991198 -0.1112787 0.0717203 -0.9913359 -0.1112955 0.06976151 -0.9776346 -0.1902409 0.08966141 -0.9963483 -0.05341035 0.06661498 -0.9480245 -0.3130764 0.05685979 -0.976124 -0.2134988 0.04000508 -0.9764872 -0.2135787 0.02927529 -0.9022545 -0.4311658 0.005745112 0 0.4245262 -0.9054157 0 0.4245272 -0.9054152 0 0.4245259 -0.9054158 0 0.9003555 -0.4351552 0 0.9003555 -0.4351555 0 0 -1 0.02991503 0.9995336 -0.006138741 -0.04896819 0.9985495 -0.02238243 -9.43513e-4 0.999995 -0.003050804 0.001672089 0.9999972 -0.00170046 -0.181268 0.9258216 -0.3316572 -0.3360532 0.3045262 -0.8912532 -0.2418651 0.4588615 -0.8549546 -0.1267189 0.9033753 -0.4097017 -0.1072931 0.9190465 -0.3792648 -0.1573909 0.3229818 -0.9332261 -0.0362823 0.9314368 -0.36209 -0.9893153 5.88579e-4 -0.1457909 -0.08645462 0 -0.9962558 -0.2562138 -0.07479709 -0.9637219 -0.4628279 0.6170639 -0.6364138 -0.1274827 0.6178865 -0.7758637 -0.1290537 0.8678367 -0.4797965 0.5240565 0.5956107 -0.6087797 0.08703243 0.8718323 -0.4820104 0.02729153 0.5909897 -0.8062173 0.08645868 0 -0.9962555 0.9894277 5.57673e-4 -0.1450267 0 -0.07951611 -0.9968336 0 0.8751525 -0.4838472 0 0.8751526 -0.4838472 0.0362119 0.9314544 -0.362052 0.1573909 0.3229839 -0.9332254 0.1072932 0.9190472 -0.3792634 0.1267189 0.9033752 -0.4097018 0.2418644 0.4588636 -0.8549537 0.3360537 0.3045269 -0.8912526 0.181267 0.925822 -0.3316566 0 0.9999783 -0.006607115 -0.001670062 0.9999971 -0.001701354 9.43515e-4 0.999995 -0.003050446 0.00937879 0.9999536 -0.002205908 -0.03447008 -0.5646155 -0.824634 -0.02256971 -0.8681976 -0.4957052 0 -1 0 -0.02658045 0.9996436 -0.002508521 0.008109092 0.9999209 0.009629666 0.4067909 -0.9135214 0 -0.9912948 2.01194e-5 -0.1316614 -0.9330816 -0.001328408 -0.3596625 -0.9209654 1.48251e-4 -0.3896445 -0.7940332 -3.20046e-4 -0.6078744 -0.7830108 4.59087e-4 -0.622008 -0.6083325 -3.71086e-4 -0.7936823 -0.5914261 4.99623e-4 -0.806359 -0.4231368 -2.84714e-4 -0.9060659 -0.3604894 0.001444935 -0.9327622 -0.258025 -5.39848e-4 -0.9661381 -0.1198638 9.6358e-4 -0.9927899 -0.003411054 0.9404647 0.3398744 0.1025817 0.9559973 0.2748565 -0.541073 -0.7274026 -0.4220492 -0.5420631 -0.7246638 -0.4254764 -0.5415135 -0.7219391 -0.4307752 -0.5692425 -0.7540961 -0.3275701 -0.6624484 -0.4968496 -0.560627 -0.3506087 -0.8080537 -0.473416 -0.8456505 -0.4008612 -0.3523998 -0.3836638 0.7883505 -0.4809427 -0.4088085 0.3925459 -0.8238832 -0.1297296 0.9795089 -0.1540536 -0.4955191 -0.4686755 -0.731303 -0.4284467 -0.2236674 -0.8754464 0.4467427 -0.2317857 -0.864116 0.4966071 -0.464201 -0.733416 0.2326981 0.8764512 -0.421527 0.1795241 0.799304 -0.5734844 0.4088085 0.3925459 -0.8238832 0.3836643 0.7883484 -0.4809457 0.8456452 -0.4008675 -0.3524051 0.3384107 -0.824899 -0.4527911 0.01363778 -0.8815902 -0.4718188 0.6743778 -0.4897354 -0.5526065 0.586257 -0.7389912 -0.3319561 0.5605377 -0.7095019 -0.4270886 0.5613982 -0.7135143 -0.419201 0.5604301 -0.7163533 -0.4156394 -0.067613 0.958868 0.2756824 0.1198654 9.63657e-4 -0.9927897 0.2581613 -5.41422e-4 -0.9661017 0.3604868 0.001456379 -0.9327633 0.4511359 -0.001083612 -0.8924546 0.5913214 -3.26541e-4 -0.8064359 0.5934292 -4.34382e-4 -0.8048861 0.7830199 4.58473e-4 -0.6219966 0.7940332 -3.19967e-4 -0.6078744 0.9209654 1.48175e-4 -0.3896445 0.9330819 -0.001328527 -0.3596618 0.9912944 1.99627e-5 -0.131664 -0.4067897 -0.9135219 0 -0.006248712 -0.8652143 -0.5013635 0 -0.8791204 -0.4765997 0 1 2.31276e-7 -0.1187474 -0.6759967 -0.727274 -0.6994545 -0.5644611 -0.4383458 -0.730081 -0.5293507 -0.4321686 -0.7953388 -0.5761455 -0.188395 -0.7374915 -0.5031378 -0.4505094 -0.6633329 -0.3688408 -0.6511113 -0.6818597 -0.4655324 -0.5642226 -0.6972542 -0.2519184 -0.671099 -0.9352673 -0.3003759 -0.1872151 -0.8568298 -0.2751849 -0.4360229 -0.7072177 -0.1496701 -0.6909718 -0.7163138 -0.2186332 -0.6626418 -0.856172 -0.2613197 -0.4457372 -0.7160985 -0.04952162 -0.6962404 -0.5992678 -0.7483098 -0.2844477 -0.6337927 -0.7599773 -0.1440187 -0.6588848 -0.7380656 -0.1453619 -0.6263898 -0.7648207 -0.1506165 0.6263903 -0.7648203 -0.1506165 0.6588904 -0.7380607 -0.145361 0.5971537 -0.7826108 -0.1758633 0.6222693 -0.69937 -0.3516567 0.7160984 -0.04952156 -0.6962406 0.856172 -0.2613197 -0.4457373 0.7163156 -0.2186334 -0.6626397 0.7072184 -0.1496642 -0.6909723 0.8568298 -0.2751849 -0.436023 0.9352666 -0.3003761 -0.1872179 0.6972525 -0.251925 -0.6710982 0.6818597 -0.4655324 -0.5642226 0.6633328 -0.3688412 -0.6511113 0.7374912 -0.5031381 -0.4505095 0.7953405 -0.5761426 -0.1883969 0.7300819 -0.5293479 -0.4321705 0.7543528 -0.4992209 -0.4262984 0 -1 -2.66215e-7 0.001063585 -0.9999607 0.00880891 0.02537727 -0.9996744 0.002670288 0.7935888 -0.6084544 -1.15683e-4 0.7942696 -0.6075656 -1.84465e-4 0.854722 -0.519086 8.60392e-5 0.8777705 -0.4790801 -0.001205861 0.9022697 -0.4311717 7.27118e-4 0.9406878 -0.3392723 -9.5256e-4 0.9495603 -0.3135846 3.25717e-4 0.9815879 -0.1910108 -4.0639e-4 0.9814795 -0.1915668 -3.73282e-4 0.8683488 -0.4739397 -0.1461213 0.9276118 -0.334557 -0.1661565 0.2862613 -0.9581054 0.009408593 0.06123709 -0.9981229 8.18592e-4 0.7791398 -0.6268418 0.00327599 0 -0.9805852 -0.1960937 0.07625222 -0.9881774 -0.1330072 0.6732891 -0.7393699 -0.003750562 0.6817668 -0.7315576 -0.00421977 0.512665 -0.8584476 -0.01556652 0.609494 -0.7925865 -0.01799172 0.2859638 -0.9572588 -0.04336237 0.483862 -0.8733946 -0.05531126 0.02543574 -0.9907243 -0.1334865 0.1981129 -0.9771604 -0.07686901 0.970884 -0.1894968 -0.1465443 0.7823502 -0.5984465 -0.1725981 0.4825818 -0.8746349 -0.04613882 -0.4825817 -0.8746348 -0.04613989 -0.7823529 -0.5984421 -0.1726012 -0.9708826 -0.1895046 -0.1465436 -0.1981127 -0.9771605 -0.07686907 -0.02543574 -0.9907242 -0.1334866 -0.4838626 -0.8733943 -0.05531144 -0.2859634 -0.9572589 -0.04336231 -0.609494 -0.7925865 -0.01799172 -0.5126656 -0.8584472 -0.01556658 -0.6817663 -0.7315579 -0.00421977 -0.6732887 -0.7393702 -0.003750562 -0.0761578 -0.9881846 -0.1330084 0 -0.9805853 -0.1960936 -0.7791401 -0.6268413 0.00327605 0.2039476 -0.06685477 -0.9766964 -0.06123709 -0.9981229 8.18363e-4 -0.2862615 -0.9581055 0.009408712 -0.9276121 -0.3345579 -0.1661536 -0.8683499 -0.4739387 -0.1461187 -0.9814785 -0.1915725 -3.72887e-4 -0.9815879 -0.1910108 -4.0639e-4 -0.9495603 -0.3135846 3.25717e-4 -0.9406878 -0.3392723 -9.5256e-4 -0.9022697 -0.4311717 7.27118e-4 -0.8777694 -0.479082 -0.001205801 -0.8547229 -0.5190847 8.59986e-5 -0.7942736 -0.6075603 -1.84491e-4 -0.7935859 -0.6084584 -1.15113e-4 6.15052e-4 -0.06807857 -0.9976798 -1.97109e-4 -0.680881 -0.732394 0 -0.6793107 -0.7338509 -0.02537733 -0.9996744 0.002670288 -0.001063525 -0.9999607 0.00880891 0 -0.9998636 0.01651448 3.61076e-7 -0.9439413 -0.3301134 0 -0.9439417 -0.3301122 -0.2643494 -0.910363 -0.3183687 -0.2987821 -0.9195772 -0.2551611 -0.3674415 -0.8326583 -0.4143273 -0.6406548 -0.6902621 -0.3363029 -0.6957071 -0.5980561 -0.3978953 -0.7056724 -0.7056935 -0.06342935 -0.6937651 -0.7186921 -0.04660135 -0.8860521 -0.4515488 -0.1049545 -0.9488672 -0.3041971 -0.08435231 -0.9363663 -0.3401591 -0.0866605 -0.9682372 -0.2117811 -0.1329126 -0.9645293 -0.2491763 -0.08714658 -0.9875419 -0.1563731 -0.01756435 -0.9679518 -0.246127 0.04990941 -0.3089751 -0.9509404 0.01570671 -0.198183 -0.9694441 0.1445745 -0.6448025 -0.7615943 -0.06483876 -0.8001385 -0.5924012 -0.09401708 -0.696296 -0.6963099 0.174139 -0.8898327 -0.4534764 0.05056643 -0.997124 -0.07578724 0 -0.9633862 -0.2551158 0.08247965 -0.9818682 -0.1554756 -0.1084543 -0.9949239 -0.04385644 0.09057188 -0.9958863 -0.02453488 0.08722692 -0.9956572 -7.38399e-4 0.09309339 -0.9956631 4.52381e-4 0.09303241 -0.9959366 0.0107811 0.08941024 -0.9960593 0.001133799 0.08868205 -0.9959635 -0.004226863 0.08966004 -0.01575094 -0.8173039 0.5759916 -7.33479e-5 -0.8191851 0.5735293 1.94956e-4 -0.8191721 0.5735478 7.28531e-5 -0.8191405 0.5735931 -1.65615e-4 -0.8191556 0.5735715 1.56803e-4 -0.8191463 0.5735847 -6.61529e-6 0 1 3.97887e-6 0 1 5.28629e-6 0 1 1.02034e-5 3.75648e-6 1 5.30588e-6 -1.00653e-6 1 -0.1068651 0.9942736 2.0964e-4 -0.1069134 0.9942683 5.09699e-4 -0.1030966 0.9946714 3.56481e-4 -0.3150224 0.9490842 3.34396e-4 -0.3056117 0.9521557 0.001143276 -0.5463944 0.837528 3.73921e-4 -0.4953166 0.8686912 0.006083488 -0.7338324 0.6793301 8.80197e-4 -0.6644177 0.7473306 0.006805062 -0.296597 -0.7686298 0.566779 -0.6224273 -0.6222412 0.4747633 -0.8412539 -0.4173478 0.3436754 -0.9744503 -0.1509977 0.1662719 -0.1846795 -0.8215659 0.5393727 -0.5279394 -0.7479178 0.4023666 -0.5158854 -0.7478268 0.4178726 -0.7934526 -0.569522 0.2146568 -0.7799017 -0.5772125 0.2420315 -0.9485962 -0.3164871 -0.001140654 -0.1372181 -0.8406397 0.5239238 -0.162445 -0.8501812 0.5008029 -0.4661837 -0.828212 0.3110271 -0.4605458 -0.8305534 0.3131752 -1 -3.27641e-7 0 -1 1.49267e-7 0 -1 2.48264e-7 0 -1 -1.71391e-7 0 -1 0 0 -1 1.44991e-7 0 -1 3.21019e-7 0 -1 -8.14166e-7 0 -0.1564131 0.9876128 -0.01248794 -0.4346013 0.9005851 0.0082677 -0.4539496 0.8909162 0.01408469 -0.5690831 0.8222705 -0.003977894 -0.7353002 0.6776565 0.01073616 -0.7071006 0.7071106 0.001847326 -0.8827075 0.4699193 -0.001843154 -0.8910149 0.4539722 0.001343846 -0.9862865 0.1650364 -0.00141704 -0.9876932 0.1564038 0 0.6346035 -0.6656314 0.3927003 0.6343637 -0.6651783 0.3938536 0.7256048 -0.5202691 0.4503529 0.6853549 -0.4746962 0.5522248 0.7261381 -0.3966333 0.5616099 0.6847252 -0.3325186 0.6485236 0.7261522 -0.2502147 0.6403871 0.684234 -0.1725227 0.7085618 0.7266325 -0.08899724 0.6812376 0.6841402 -0.001841425 0.7293482 0.7266234 0.07718521 0.6826865 0.684294 0.1679532 0.709601 0.7334364 0.2502648 0.6320117 0.6819126 0.3307781 0.6523658 0.502461 0.4216653 0.7548056 0.7961958 -0.4574593 0.395984 0.7114854 -0.405374 0.5739865 0.7729598 -0.339695 0.535855 0.7397748 -0.2448716 0.6267147 0.7753537 -0.2103731 0.5954577 0.7524687 -0.08531767 0.6530787 0.7789666 -0.06405907 0.6237848 0.7529864 0.07392728 0.6538702 0.7780252 0.08772855 0.6220777 0.7561592 0.1972671 0.6239464 0.6642833 0.2647737 0.6990155 0.2497181 -0.786834 0.5643876 0.1361342 -0.87777 0.4593336 0.1179847 -0.8491773 0.51476 -0.06009161 -0.9898787 0.1285665 0.2388814 -0.9559645 0.1704926 0.2705117 -0.8407834 0.4689423 0.4960436 -0.8349499 0.2383263 0.5027434 -0.7962702 0.3364564 0.3669498 -0.7460848 0.5556125 0.5114145 -0.5786386 0.6353209 0.4721146 -0.574646 0.6684982 0.499365 -0.4221509 0.7565867 0.557468 -0.3787819 0.7387515 0.467388 -0.2885296 0.835643 0.5712579 -0.1941712 0.7974724 0.470137 -0.135616 0.8721122 0.5081035 0.0200926 0.8610617 0.5529832 -0.002104103 0.8331898 0.5023533 0.1719196 0.8473989 0.5563976 0.1913799 0.8085762 0.4892705 0.295656 0.8204889 0.3715515 0.4414342 0.816753 0.49467 0.4209045 0.7603559 -0.07970446 -0.9373559 0.339133 -0.06820148 -0.9593552 0.273836 -0.2180658 -0.9505538 0.2211221 -0.06791192 -0.9850595 0.1582584 1.22344e-7 -0.9998733 0.01592624 -0.03964042 -0.9515368 0.3049697 0.01193594 0.5242769 0.8514643 0 -0.8595678 -0.5110219 0 -0.8595682 -0.5110211 -0.9614171 -0.2748471 0.01167583 -0.3011589 -0.9535403 0.008015394 -0.3447172 -0.9378608 0.03983944 -0.6970722 -0.716355 0.03043007 -0.228857 -0.9397178 -0.2540769 -0.9670111 -0.2459016 -0.06649869 -0.9501139 -0.2680299 -0.1595109 -0.9456332 -0.2755073 -0.1728396 -0.9555607 -0.2514765 -0.153829 -0.6997743 -0.6577793 -0.2786435 -0.3700652 -0.8383296 -0.4003189 -0.6401704 -0.6925287 -0.3325446 -0.2765077 -0.8260547 -0.4910978 -0.9961526 0.05446982 0.0686528 -0.9888867 0.1322932 0.0678364 -0.9675799 0.2492844 0.04057806 -0.9311121 0.3611149 0.05125027 -0.7583342 0.6513999 0.02464699 -0.8359994 0.5485509 0.01403707 -0.18465 -0.806416 0.5617807 -0.530295 -0.6873696 0.4962966 -0.8020793 -0.4715605 0.3664692 -0.963866 -0.1912884 0.1853947 0.9638656 -0.1912895 0.1853953 0.8020799 -0.4715595 0.3664695 0.5302944 -0.6873704 0.4962961 0.1846542 -0.8077426 0.5598704 0.8359994 0.5485509 0.01403719 0.7583346 0.6513995 0.02464705 0.9311118 0.3611155 0.05125021 0.9675799 0.2492844 0.04057806 0.9888867 0.1322932 0.0678364 0.9961526 0.05446982 0.0686528 0.2765077 -0.8260549 -0.4910978 0.6401702 -0.6925289 -0.3325447 0.3700652 -0.8383296 -0.400319 0.6997752 -0.657779 -0.2786424 0.9301458 -0.3218536 -0.1767461 0.9642388 -0.2405658 -0.1112284 0.9501128 -0.2680328 -0.1595125 0.9670118 -0.2458992 -0.06649732 0.228857 -0.9397178 -0.2540769 0.6970718 -0.7163553 0.03043007 0.3447174 -0.9378608 0.03983944 0.3011589 -0.9535403 0.008015394 0.9614166 -0.2748488 0.01167595 0.9576529 -0.2879158 0.00237745 0.6970752 -0.716352 0.03043174 0.967521 -0.2428941 0.07004094 0.9670205 0.2337284 0.1012044 0.4446899 0.8727459 0.2014088 0.1500748 0.9475701 0.2821143 0.4295781 0.8946611 0.1226551 0.9671238 0.2330853 0.1016999 0.8868406 0.4518455 0.09669333 0.6936243 0.6936354 0.1943072 0.987467 0.1563664 0.02141278 -0.04305464 0.5389091 0.8412629 0.03964042 -0.9515368 0.3049698 0.05119282 -0.9910536 0.1232563 0.06791192 -0.9850594 0.158259 0.06820148 -0.9593553 0.2738358 0.07970434 -0.9373562 0.3391324 -0.4944111 0.3995135 0.7719758 -0.3278042 0.4368091 0.8377007 -0.5563971 0.1913798 0.8085765 -0.4892702 0.2956563 0.8204888 -0.5023529 0.1719195 0.8473991 -0.5529828 -0.002103567 0.83319 -0.5081031 0.02009284 0.861062 -0.4701366 -0.1356163 0.8721123 -0.5712574 -0.1941713 0.7974725 -0.4673875 -0.2885295 0.8356433 -0.5574677 -0.3787821 0.7387516 -0.4993646 -0.4221506 0.756587 -0.4721148 -0.5746454 0.6684985 -0.5114136 -0.5786392 0.6353211 -0.3368144 -0.7837018 0.5218885 -0.2817511 -0.7551178 0.5919574 -0.5027431 -0.7962704 0.3364561 -0.4960439 -0.8349497 0.2383264 -0.2705125 -0.8407831 0.4689424 -0.2388828 -0.9559639 0.1704936 0.06009149 -0.9898787 0.1285663 -0.1179835 -0.8491775 0.5147596 -0.1361332 -0.8777707 0.4593325 -0.6642834 0.2647733 0.6990156 -0.7561591 0.1972678 0.6239462 -0.778027 0.0877276 0.6220756 -0.7529881 0.0739271 0.6538685 -0.7789637 -0.06405752 0.6237888 -0.7524677 -0.0853188 0.6530798 -0.7753523 -0.2103767 0.5954583 -0.7397738 -0.2448713 0.6267158 -0.7729594 -0.3396948 0.5358557 -0.7114849 -0.4053757 0.5739861 -0.7961947 -0.4574616 0.3959835 -0.5505176 0.4006057 0.7324244 -0.6819129 0.3307773 0.6523658 -0.7334365 0.2502648 0.6320114 -0.6842941 0.1679532 0.7096008 -0.7266237 0.07718527 0.6826863 -0.6841405 -0.001841425 0.729348 -0.7266328 -0.0889967 0.6812375 -0.6842341 -0.1725233 0.7085615 -0.7261526 -0.2502136 0.6403871 -0.6847253 -0.3325192 0.6485232 -0.7261384 -0.3966323 0.5616102 -0.6853551 -0.4746963 0.5522244 -0.7256049 -0.5202692 0.4503527 -0.6343642 -0.6651779 0.3938534 -0.6346035 -0.6656314 0.3927003 0.9876933 0.1564036 0 0.9862866 0.1650358 -0.001416981 0.8910146 0.4539728 0.001344025 0.8827075 0.4699192 -0.001843273 0.7071001 0.7071111 0.001847326 0.7352903 0.6776674 0.01073312 0.5690906 0.8222653 -0.003979146 0.4539485 0.8909167 0.01408487 0.4346037 0.9005839 0.008266985 0.1564134 0.9876128 -0.01248848 1 0 0 1 -1.71391e-7 0 1 2.48264e-7 0 1 0 0 1 -1.47623e-7 0 1 0 0 0.1527272 -0.8661755 0.4758303 0.411724 -0.8735874 0.2594773 0.4326195 -0.8665274 0.2489391 0.1476478 -0.8632179 0.4827578 0.4605485 -0.8305523 0.3131741 0.4661831 -0.8282123 0.3110268 0.1624466 -0.8501803 0.5008039 0.7143128 -0.6942068 0.08851093 0.6784824 -0.7253223 0.1164875 0.1372244 -0.8406382 0.5239247 0.948596 -0.3164879 -0.00113976 0.7950698 -0.5624948 0.2268564 0.7763164 -0.5863091 0.2314618 0.5158879 -0.7478256 0.4178716 0.527939 -0.7479184 0.4023663 0.1846798 -0.8215655 0.5393733 0.9744503 -0.1509977 0.1662721 0.8412534 -0.4173489 0.3436753 0.6224266 -0.6222422 0.4747628 0.3302499 -0.7603887 0.5592354 0.6644177 0.7473306 0.006805062 0.7338306 0.679332 8.80194e-4 0.4953174 0.8686909 0.006083488 0.5463951 0.8375276 3.74015e-4 0.3056114 0.9521557 0.001143276 0.3150226 0.9490841 3.34396e-4 0.1030967 0.9946714 3.56481e-4 0.106913 0.9942683 5.09697e-4 0.1068677 0.9942733 2.09532e-4 0.9425719 -0.3322927 0.03376209 -4.4235e-6 -2.76735e-6 1 -8.16281e-6 3.75661e-6 1 -1.45466e-5 0 1 6.6153e-6 0 1 -1.56803e-4 -0.8191462 0.5735849 1.56899e-4 -0.8191552 0.573572 -7.28531e-5 -0.8191406 0.573593 -1.94956e-4 -0.8191713 0.573549 8.0016e-5 -0.8191846 0.57353 0.03477114 -0.8147392 0.5787841 0.9959636 -0.004223585 0.08965963 0.9960593 0.001132488 0.08868187 0.9959366 0.0107811 0.08941 0.9956631 4.5143e-4 0.09303247 0.9956572 -7.37124e-4 0.09309339 0.9958863 -0.02453488 0.08722692 0.9949239 -0.04385644 0.09057176 0.997124 -0.07578748 0 0.9818683 -0.1554756 -0.1084535 0.9633866 -0.2551149 0.08247941 0.889832 -0.4534776 0.05056697 0.696296 -0.6963099 0.174139 0.8001399 -0.5923995 -0.09401661 0.6448025 -0.7615943 -0.06483846 0.198183 -0.9694438 0.144576 0.308975 -0.9509405 0.01570665 0.9581708 -0.2853796 0.02161431 0.987263 -0.1563284 -0.02954876 0.9645317 -0.24916 -0.08716541 0.9682373 -0.2117806 -0.1329123 0.9652741 -0.2281593 -0.1272372 0.9256566 -0.353999 -0.1335835 0.8860517 -0.4515495 -0.1049548 0.6937648 -0.7186924 -0.04660135 0.7056724 -0.7056935 -0.06342977 0.6957064 -0.5980572 -0.3978949 0.6406549 -0.6902615 -0.3363041 0.367438 -0.8326594 -0.4143279 0.2987847 -0.9195762 -0.2551612 0.2643498 -0.9103623 -0.3183706 -1 2.90123e-5 2.78094e-5 -1 -4.4189e-4 2.62927e-4 -1 -1.38492e-7 0 -1 -1.58385e-7 0 -1 0 0 1 8.91887e-7 8.19071e-7 1 -1.24747e-5 7.74399e-6 1 -1.38492e-7 0 1 5.2267e-6 -4.04457e-6 1 1.09494e-6 8.06749e-7 1 1.09802e-6 3.49152e-7 1 1.27165e-6 4.26484e-7 -1 2.27269e-7 0 -1 -9.08496e-7 0 1 -2.27097e-7 0 1 2.27055e-7 0 1 -2.83898e-7 0 1 3.12296e-7 0 1 3.40752e-7 0 1 -4.54071e-7 0 1 -2.27061e-7 0 1 2.27271e-7 0 1 -2.27071e-7 0 1 2.27379e-7 0 1 7.61596e-7 0 1 -1.84397e-7 0 0.4549254 -0.6984828 -0.5524172 0.4557287 -0.6985597 -0.5516573 0.6262539 -0.6583629 -0.4175698 0.5960876 -0.6730796 -0.4377711 0.3981733 -0.7671643 -0.5029087 -0.439383 -0.7140334 -0.5450678 -0.6032525 -0.7104871 -0.3623459 -0.5141074 -0.7391632 -0.4351224 -0.4555376 -0.7592567 -0.464774 -0.3995009 -0.7813888 -0.4794068 -0.006338238 -0.890147 -0.4556294 -5.03807e-5 -0.876552 -0.4813073 0 -0.8191362 0.5735992 -1.98697e-4 -0.8191915 0.57352 1.46803e-4 -0.8191221 0.5736192 -1.40351e-4 -0.8191577 0.5735684 1.99279e-4 -0.8191918 0.5735198 -1.46803e-4 -0.8191223 0.5736191 1.40351e-4 -0.8191579 0.5735681 -0.6818593 0.4655323 -0.564223 -0.6633327 0.3688387 -0.6511127 0.6633325 0.3688394 -0.6511126 0.6818595 0.4655323 -0.5642229 -0.9856256 0.001282632 -0.1689396 0.9858314 0.001277565 -0.1677341 -0.2740227 0.799332 -0.5347709 0.5206381 0.8537723 -0.003012716 0.04209697 -0.5746313 -0.817329 0.119957 -0.674353 -0.7286003 + + + + + + + + + + + + + + +

4 0 5 0 6 0 3 1 0 1 8 1 13 2 21 2 14 2 12 3 13 3 14 3 20 4 21 4 13 4 12 5 15 5 13 5 19 6 18 6 16 6 20 7 18 7 21 7 19 8 17 8 18 8 18 9 17 9 21 9 30 10 31 10 32 10 33 11 30 11 32 11 44 12 45 12 1 12 2 13 1 13 45 13 45 14 46 14 2 14 2 15 46 15 47 15 48 16 2 16 47 16 47 17 49 17 48 17 50 18 48 18 49 18 50 19 49 19 51 19 52 20 50 20 51 20 52 21 51 21 53 21 3 22 52 22 53 22 60 23 63 23 62 23 64 24 63 24 60 24 59 25 64 25 60 25 65 26 62 26 63 26 66 27 67 27 65 27 63 28 66 28 65 28 66 29 63 29 64 29 64 30 48 30 50 30 68 31 64 31 50 31 64 32 68 32 66 32 69 33 67 33 66 33 50 34 52 34 68 34 70 35 66 35 68 35 68 36 52 36 3 36 68 37 3 37 72 37 68 38 72 38 70 38 73 39 70 39 72 39 74 40 75 40 43 40 42 41 74 41 43 41 4 42 75 42 74 42 74 43 76 43 4 43 4 44 6 44 77 44 77 45 78 45 35 45 78 46 79 46 35 46 81 47 30 47 33 47 33 48 41 48 81 48 82 49 81 49 41 49 41 50 40 50 82 50 83 51 8 51 84 51 38 52 0 52 3 52 83 53 3 53 8 53 82 54 40 54 39 54 82 55 39 55 38 55 9 56 3 56 83 56 72 57 3 57 9 57 9 58 85 58 72 58 85 59 86 59 72 59 73 60 72 60 86 60 61 61 62 61 65 61 65 61 67 61 61 61 67 61 69 61 58 61 56 61 58 61 69 61 69 61 71 61 56 61 57 61 56 61 71 61 71 61 70 61 57 61 54 61 57 61 70 61 70 61 73 61 54 61 55 62 54 62 73 62 73 63 86 63 55 63 80 64 55 64 86 64 86 65 85 65 80 65 85 66 9 66 80 66 80 67 9 67 10 67 9 68 83 68 10 68 83 69 84 69 10 69 87 70 84 70 8 70 8 71 0 71 87 71 37 72 38 72 39 72 82 73 38 73 53 73 38 74 3 74 53 74 59 75 2 75 64 75 48 76 64 76 2 76 131 77 28 77 115 77 120 78 115 78 22 78 141 79 126 79 29 79 95 80 126 80 141 80 92 81 89 81 26 81 94 82 24 82 93 82 25 82 24 82 94 82 91 83 24 83 25 83 27 84 24 84 91 84 90 85 27 85 91 85 27 86 90 86 97 86 90 82 124 82 97 82 124 82 90 82 125 82 109 82 125 82 90 82 125 82 109 82 122 82 108 82 122 82 109 82 122 82 108 82 123 82 110 82 123 82 108 82 123 82 110 82 121 82 112 82 121 82 110 82 114 82 118 82 112 82 118 82 114 82 117 82 91 87 107 87 90 87 107 88 91 88 25 88 107 89 25 89 29 89 25 90 94 90 29 90 95 91 141 91 140 91 94 92 92 92 29 92 29 93 92 93 26 93 29 94 26 94 141 94 94 95 93 95 92 95 95 96 139 96 96 96 138 97 96 97 139 97 138 98 149 98 96 98 99 99 145 99 98 99 100 100 145 100 99 100 104 101 100 101 101 101 104 102 101 102 102 102 106 103 104 103 103 103 104 104 106 104 105 104 137 105 136 105 106 105 106 106 136 106 105 106 90 107 107 107 109 107 111 108 109 108 107 108 111 109 107 109 29 109 111 110 29 110 127 110 109 111 111 111 113 111 129 112 111 112 127 112 110 113 113 113 112 113 115 114 113 114 111 114 111 115 129 115 115 115 115 116 129 116 131 116 113 117 115 117 116 117 116 118 114 118 113 118 113 119 114 119 112 119 114 120 116 120 117 120 120 121 119 121 115 121 115 122 119 122 116 122 119 123 117 123 116 123 29 124 126 124 127 124 127 125 126 125 128 125 127 126 128 126 129 126 129 127 128 127 130 127 129 128 130 128 131 128 132 129 131 129 130 129 131 130 132 130 28 130 28 131 132 131 133 131 134 132 22 132 133 132 133 133 22 133 28 133 135 134 22 134 134 134 147 135 149 135 138 135 149 10 147 10 148 10 142 136 144 136 143 136 31 10 146 10 148 10 30 10 146 10 31 10 146 137 149 137 148 137 150 138 151 138 152 138 146 10 153 10 162 10 146 10 162 10 157 10 164 139 163 139 162 139 190 140 188 140 189 140 176 141 190 141 175 141 188 142 169 142 167 142 191 143 169 143 188 143 188 144 190 144 191 144 192 145 176 145 177 145 190 146 176 146 192 146 192 147 191 147 190 147 169 148 191 148 171 148 178 149 192 149 177 149 191 150 173 150 171 150 193 151 173 151 191 151 191 152 192 152 193 152 194 153 193 153 192 153 194 154 178 154 179 154 192 155 178 155 194 155 173 156 193 156 174 156 180 157 194 157 179 157 193 158 194 158 195 158 193 159 172 159 174 159 195 160 172 160 193 160 194 161 180 161 196 161 196 162 195 162 194 162 181 163 196 163 180 163 172 164 195 164 170 164 195 165 196 165 197 165 197 166 170 166 195 166 198 167 197 167 196 167 198 168 181 168 182 168 196 169 181 169 198 169 183 170 198 170 182 170 170 171 197 171 168 171 197 172 198 172 199 172 197 173 166 173 168 173 199 174 166 174 197 174 200 175 199 175 198 175 200 176 183 176 184 176 198 177 183 177 200 177 185 178 200 178 184 178 203 179 242 179 244 179 203 180 201 180 202 180 240 181 242 181 203 181 218 182 219 182 202 182 204 183 202 183 220 183 202 184 219 184 220 184 202 185 204 185 203 185 203 186 205 186 240 186 205 187 238 187 240 187 205 188 203 188 204 188 235 189 238 189 205 189 220 190 221 190 204 190 206 191 204 191 222 191 204 192 221 192 222 192 204 193 206 193 205 193 205 194 207 194 235 194 207 195 205 195 206 195 233 196 235 196 207 196 222 197 223 197 206 197 206 198 208 198 207 198 208 199 206 199 223 199 207 200 209 200 233 200 209 201 231 201 233 201 209 202 207 202 208 202 223 203 224 203 208 203 232 204 231 204 209 204 210 205 208 205 225 205 208 206 224 206 225 206 208 207 210 207 209 207 211 208 209 208 210 208 209 209 211 209 232 209 211 210 234 210 232 210 225 211 226 211 210 211 236 212 234 212 211 212 210 213 212 213 211 213 212 214 210 214 227 214 210 215 226 215 227 215 214 216 211 216 212 216 211 217 214 217 236 217 214 218 239 218 236 218 227 219 228 219 212 219 241 220 239 220 214 220 212 221 213 221 214 221 213 222 212 222 230 222 212 223 245 223 230 223 212 224 228 224 245 224 214 225 215 225 241 225 214 226 213 226 215 226 243 227 241 227 229 227 241 228 215 228 229 228 187 229 186 229 216 229 217 230 216 230 186 230 186 231 185 231 217 231 218 232 217 232 185 232 185 233 184 233 218 233 219 234 218 234 184 234 184 235 183 235 219 235 220 236 219 236 183 236 183 237 182 237 220 237 221 238 220 238 182 238 182 239 181 239 221 239 222 240 221 240 181 240 181 241 180 241 222 241 223 242 222 242 180 242 180 243 179 243 223 243 224 243 223 243 179 243 179 244 178 244 224 244 225 245 224 245 178 245 178 246 177 246 225 246 226 247 225 247 177 247 177 248 176 248 226 248 227 248 226 248 176 248 176 249 175 249 227 249 228 250 227 250 175 250 175 251 164 251 228 251 245 252 228 252 164 252 240 82 238 82 237 82 242 82 240 82 237 82 241 82 243 82 237 82 244 253 242 253 237 253 245 139 164 139 162 139 162 139 246 139 245 139 296 254 266 254 287 254 296 255 287 255 158 255 249 256 253 256 248 256 253 257 255 257 254 257 253 258 249 258 255 258 250 259 255 259 249 259 254 260 255 260 256 260 257 261 250 261 135 261 255 262 250 262 257 262 257 263 256 263 255 263 256 264 257 264 258 264 134 265 257 265 135 265 259 266 258 266 257 266 257 267 134 267 259 267 133 268 259 268 134 268 258 269 259 269 260 269 261 270 260 270 259 270 259 271 133 271 261 271 132 272 261 272 133 272 260 273 261 273 262 273 261 274 263 274 262 274 264 275 263 275 261 275 264 276 132 276 130 276 261 277 132 277 264 277 266 278 265 278 267 278 268 279 270 279 269 279 268 280 320 280 270 280 265 281 320 281 268 281 268 282 267 282 265 282 271 283 268 283 269 283 267 284 268 284 272 284 273 285 271 285 288 285 268 286 271 286 273 286 268 287 274 287 272 287 273 288 274 288 268 288 275 289 273 289 288 289 274 290 273 290 276 290 273 291 277 291 276 291 273 292 278 292 277 292 273 293 275 293 278 293 253 294 277 294 278 294 283 295 274 295 276 295 284 296 274 296 283 296 161 297 285 297 279 297 274 298 284 298 272 298 284 299 285 299 272 299 286 300 272 300 285 300 285 301 161 301 286 301 160 302 286 302 161 302 272 303 286 303 267 303 287 304 160 304 159 304 286 305 160 305 287 305 287 306 267 306 286 306 158 307 287 307 159 307 267 308 287 308 266 308 270 309 21 309 17 309 320 310 21 310 270 310 269 311 17 311 19 311 269 312 270 312 17 312 275 313 289 313 290 313 288 314 289 314 275 314 291 315 275 315 290 315 288 316 16 316 289 316 271 317 16 317 288 317 271 318 19 318 16 318 269 319 19 319 271 319 128 320 126 320 252 320 130 321 128 321 252 321 130 322 252 322 264 322 252 323 263 323 264 323 251 324 263 324 252 324 247 325 275 325 291 325 247 326 278 326 275 326 247 327 248 327 278 327 248 328 253 328 278 328 149 10 146 10 157 10 149 329 157 329 280 329 149 330 280 330 96 330 96 331 280 331 281 331 96 332 281 332 95 332 95 333 281 333 282 333 126 334 95 334 282 334 126 335 282 335 251 335 126 336 251 336 252 336 53 337 333 337 334 337 53 338 334 338 303 338 53 339 303 339 82 339 82 340 303 340 304 340 81 341 82 341 304 341 81 342 304 342 305 342 30 343 81 343 305 343 30 344 305 344 153 344 30 10 153 10 146 10 337 345 309 345 332 345 338 346 309 346 337 346 338 347 311 347 309 347 338 348 292 348 311 348 334 349 333 349 322 349 333 350 321 350 322 350 49 351 321 351 333 351 49 352 333 352 51 352 51 353 333 353 53 353 317 354 315 354 12 354 315 355 15 355 12 355 315 356 295 356 15 356 295 357 294 357 15 357 292 358 293 358 311 358 295 359 311 359 294 359 311 360 293 360 294 360 317 361 14 361 316 361 317 362 12 362 14 362 320 363 316 363 21 363 316 364 14 364 21 364 319 365 266 365 296 365 158 366 156 366 296 366 296 367 297 367 319 367 297 368 296 368 155 368 296 369 156 369 155 369 314 370 319 370 297 370 155 371 154 371 297 371 298 372 297 372 154 372 297 373 298 373 314 373 299 374 314 374 298 374 312 375 314 375 299 375 154 376 307 376 298 376 300 377 298 377 307 377 298 378 300 378 299 378 299 379 301 379 312 379 301 380 310 380 312 380 301 381 299 381 300 381 307 382 308 382 300 382 306 383 310 383 302 383 310 384 301 384 302 384 331 385 332 385 306 385 332 386 309 386 306 386 313 387 309 387 311 387 309 388 313 388 306 388 313 389 310 389 306 389 312 390 310 390 313 390 311 391 295 391 313 391 313 392 318 392 312 392 318 393 314 393 312 393 318 394 313 394 315 394 313 395 295 395 315 395 319 396 314 396 318 396 315 397 317 397 318 397 318 398 265 398 319 398 265 399 318 399 320 399 318 400 316 400 320 400 318 401 317 401 316 401 266 402 319 402 265 402 324 403 321 403 47 403 321 404 49 404 47 404 321 405 324 405 322 405 324 406 323 406 322 406 325 407 323 407 324 407 47 408 46 408 324 408 326 409 324 409 46 409 324 410 326 410 325 410 327 411 325 411 326 411 46 412 45 412 326 412 328 413 326 413 45 413 326 414 328 414 327 414 45 415 44 415 328 415 329 416 327 416 328 416 328 417 330 417 329 417 330 418 328 418 335 418 328 419 44 419 335 419 331 420 329 420 330 420 335 421 336 421 330 421 332 422 330 422 336 422 330 423 332 423 331 423 336 424 337 424 332 424 349 425 339 425 148 425 148 426 339 426 31 426 31 427 339 427 370 427 339 428 349 428 346 428 370 429 339 429 346 429 374 430 340 430 144 430 341 10 88 10 342 10 343 431 357 431 344 431 343 432 342 432 357 432 341 10 342 10 343 10 343 433 344 433 345 433 345 10 347 10 346 10 344 434 347 434 345 434 343 435 348 435 341 435 138 436 348 436 147 436 349 437 147 437 348 437 349 438 343 438 345 438 348 439 343 439 349 439 147 440 349 440 148 440 346 441 349 441 345 441 359 442 102 442 358 442 354 443 144 443 340 443 351 444 356 444 355 444 357 445 342 445 356 445 356 446 351 446 357 446 344 447 357 447 351 447 362 448 363 448 365 448 364 449 367 449 363 449 365 450 363 450 367 450 366 451 374 451 34 451 5 452 360 452 361 452 351 453 355 453 367 453 367 454 364 454 351 454 344 455 351 455 364 455 346 456 372 456 370 456 32 457 31 457 370 457 371 458 370 458 373 458 370 459 372 459 373 459 370 460 371 460 32 460 33 461 32 461 371 461 373 462 37 462 371 462 344 463 364 463 347 463 364 464 372 464 347 464 372 10 346 10 347 10 373 465 372 465 364 465 37 10 373 10 362 10 373 10 363 10 362 10 373 466 364 466 363 466 37 10 362 10 36 10 355 467 356 467 352 467 368 468 352 468 350 468 34 469 144 469 142 469 341 470 26 470 88 470 141 471 26 471 341 471 104 472 102 472 103 472 101 473 358 473 102 473 358 474 101 474 380 474 100 475 380 475 101 475 380 476 100 476 379 476 99 477 379 477 100 477 379 478 99 478 23 478 98 479 23 479 99 479 23 480 98 480 353 480 375 481 353 481 98 481 353 482 375 482 354 482 354 483 375 483 144 483 93 484 89 484 92 484 88 485 26 485 89 485 350 486 377 486 378 486 350 487 378 487 359 487 358 488 350 488 359 488 380 489 350 489 358 489 376 490 377 490 350 490 376 491 350 491 352 491 88 492 376 492 342 492 341 493 348 493 139 493 348 494 138 494 139 494 341 495 140 495 141 495 376 496 352 496 356 496 356 497 342 497 376 497 365 498 389 498 362 498 389 499 365 499 385 499 37 500 39 500 40 500 37 501 40 501 41 501 371 502 41 502 33 502 37 503 41 503 371 503 36 504 362 504 389 504 389 505 385 505 369 505 369 506 385 506 386 506 389 507 369 507 388 507 381 508 361 508 369 508 361 509 360 509 369 509 369 510 360 510 387 510 369 511 387 511 388 511 87 512 0 512 36 512 34 513 390 513 366 513 383 514 366 514 390 514 390 515 79 515 383 515 11 516 383 516 79 516 79 517 78 517 11 517 384 518 11 518 78 518 78 519 77 519 384 519 381 520 384 520 77 520 77 521 6 521 381 521 361 522 381 522 6 522 6 523 5 523 361 523 4 524 76 524 5 524 368 525 350 525 369 525 369 526 386 526 368 526 37 527 0 527 38 527 36 10 0 10 37 10 34 430 374 430 144 430 352 528 368 528 355 528 54 529 55 529 393 529 393 530 394 530 54 530 393 531 391 531 394 531 395 532 54 532 394 532 395 533 56 533 57 533 54 534 395 534 57 534 58 535 56 535 395 535 59 536 394 536 392 536 394 537 59 537 395 537 60 538 61 538 58 538 395 539 60 539 58 539 60 540 395 540 59 540 62 541 61 541 60 541 55 542 80 542 393 542 58 61 61 61 67 61 7 61 80 61 10 61 393 543 80 543 7 543 393 544 74 544 42 544 74 545 393 545 7 545 106 546 27 546 398 546 398 547 137 547 106 547 121 82 112 82 118 82 97 548 398 548 27 548 398 549 97 549 124 549 117 550 119 550 118 550 119 551 120 551 396 551 396 552 121 552 119 552 119 553 121 553 118 553 397 554 396 554 120 554 120 555 399 555 397 555 121 556 396 556 123 556 125 557 122 557 396 557 396 558 122 558 123 558 396 559 397 559 125 559 397 560 400 560 398 560 398 561 125 561 397 561 125 562 398 562 124 562 34 563 142 563 403 563 375 564 145 564 144 564 143 565 144 565 145 565 137 566 247 566 136 566 400 567 247 567 137 567 400 568 248 568 247 568 401 569 248 569 400 569 248 570 401 570 249 570 399 571 249 571 401 571 249 572 399 572 250 572 399 573 135 573 250 573 22 574 135 574 399 574 400 575 397 575 401 575 397 576 399 576 401 576 145 577 100 577 104 577 145 578 375 578 98 578 103 82 24 82 27 82 247 579 291 579 136 579 143 580 20 580 142 580 18 581 20 581 143 581 136 582 291 582 105 582 105 583 291 583 290 583 105 584 290 584 104 584 104 585 290 585 289 585 145 586 104 586 289 586 145 587 289 587 16 587 145 588 18 588 143 588 145 589 16 589 18 589 399 590 120 590 22 590 400 591 137 591 398 591 106 592 103 592 27 592 74 593 7 593 76 593 391 594 393 594 42 594 392 595 1 595 59 595 35 596 13 596 15 596 35 597 403 597 13 597 35 598 15 598 294 598 35 599 294 599 4 599 4 600 294 600 293 600 75 601 4 601 293 601 75 602 293 602 292 602 43 603 75 603 292 603 13 604 403 604 20 604 403 605 142 605 20 605 338 606 43 606 292 606 367 607 382 607 365 607 76 61 7 61 10 61 79 608 390 608 35 608 35 609 4 609 77 609 394 610 402 610 392 610 391 611 402 611 394 611 1 612 392 612 44 612 392 613 335 613 44 613 336 614 335 614 392 614 392 615 402 615 336 615 337 616 336 616 402 616 402 617 391 617 337 617 391 618 338 618 337 618 391 619 42 619 338 619 42 620 43 620 338 620 382 621 367 621 355 621 355 622 368 622 382 622 386 623 382 623 368 623 403 624 35 624 34 624 390 625 34 625 35 625 152 626 151 626 547 626 547 627 548 627 152 627 404 628 152 628 548 628 404 629 405 629 152 629 406 630 407 630 152 630 406 631 152 631 405 631 406 632 405 632 408 632 409 633 406 633 408 633 409 634 410 634 407 634 406 635 409 635 407 635 411 636 410 636 409 636 408 637 412 637 409 637 409 638 412 638 413 638 409 639 413 639 414 639 415 640 409 640 414 640 415 641 416 641 411 641 409 642 415 642 411 642 407 643 150 643 152 643 417 644 150 644 407 644 418 645 417 645 407 645 410 646 419 646 418 646 407 647 410 647 418 647 410 648 411 648 419 648 416 649 420 649 421 649 416 650 421 650 419 650 411 651 416 651 419 651 331 652 422 652 329 652 327 653 329 653 422 653 422 654 423 654 327 654 327 655 423 655 424 655 325 656 327 656 424 656 424 657 425 657 325 657 325 658 425 658 426 658 418 659 428 659 427 659 427 660 308 660 418 660 417 661 418 661 308 661 307 662 150 662 417 662 308 663 307 663 417 663 307 664 154 664 150 664 429 665 431 665 430 665 430 666 431 666 432 666 433 667 430 667 432 667 245 668 246 668 433 668 432 669 245 669 433 669 434 670 246 670 153 670 305 671 433 671 434 671 153 672 305 672 434 672 430 673 433 673 305 673 305 674 304 674 430 674 429 675 430 675 304 675 304 676 303 676 429 676 435 677 429 677 303 677 303 678 334 678 435 678 438 679 428 679 439 679 439 680 441 680 440 680 441 681 443 681 442 681 443 682 422 682 331 682 444 683 427 683 438 683 438 684 440 684 444 684 302 685 444 685 440 685 440 686 442 686 302 686 306 687 302 687 442 687 442 688 331 688 306 688 308 689 427 689 444 689 444 690 300 690 308 690 444 691 302 691 301 691 300 692 444 692 301 692 445 693 446 693 447 693 447 82 420 82 445 82 448 694 445 694 420 694 416 695 449 695 448 695 420 696 416 696 448 696 413 82 450 82 237 82 450 697 244 697 237 697 449 698 416 698 415 698 449 699 415 699 414 699 449 700 414 700 413 700 449 82 413 82 237 82 243 82 449 82 237 82 230 701 245 701 451 701 230 702 451 702 452 702 213 703 230 703 452 703 213 704 452 704 453 704 213 705 453 705 454 705 215 706 213 706 454 706 454 707 455 707 215 707 229 708 215 708 455 708 455 709 449 709 229 709 243 710 229 710 449 710 437 711 436 711 456 711 457 712 456 712 436 712 436 713 458 713 457 713 459 714 457 714 458 714 458 715 460 715 459 715 461 716 459 716 460 716 460 717 462 717 461 717 463 718 461 718 462 718 462 719 464 719 463 719 465 720 463 720 464 720 464 721 466 721 465 721 467 722 465 722 466 722 466 723 441 723 467 723 467 724 441 724 439 724 428 725 467 725 439 725 436 726 426 726 458 726 460 727 458 727 426 727 426 728 425 728 460 728 462 729 460 729 425 729 425 730 424 730 462 730 464 731 462 731 424 731 424 732 423 732 464 732 466 733 464 733 423 733 423 734 422 734 466 734 466 735 422 735 443 735 466 736 443 736 441 736 456 737 455 737 454 737 454 738 453 738 456 738 468 739 456 739 453 739 429 740 469 740 431 740 469 741 429 741 435 741 469 742 435 742 437 742 468 743 469 743 437 743 437 744 456 744 468 744 457 745 455 745 456 745 459 746 449 746 455 746 457 747 459 747 455 747 448 748 449 748 459 748 459 749 461 749 448 749 445 750 448 750 461 750 461 751 463 751 445 751 446 752 445 752 463 752 465 753 447 753 446 753 463 754 465 754 446 754 420 755 447 755 465 755 465 756 467 756 420 756 421 757 420 757 467 757 428 758 419 758 421 758 467 759 428 759 421 759 468 760 453 760 452 760 452 761 469 761 468 761 431 762 469 762 432 762 469 763 451 763 245 763 432 764 469 764 245 764 469 765 452 765 451 765 418 766 419 766 428 766 216 767 404 767 187 767 548 768 187 768 404 768 201 769 203 769 244 769 470 770 217 770 218 770 202 771 470 771 218 771 470 772 202 772 201 772 216 773 217 773 470 773 244 774 450 774 201 774 201 775 450 775 413 775 201 776 413 776 412 776 408 777 201 777 412 777 201 778 408 778 470 778 470 779 405 779 216 779 470 780 408 780 405 780 404 781 216 781 405 781 325 782 426 782 323 782 426 783 436 783 323 783 323 784 436 784 322 784 322 785 436 785 437 785 334 786 322 786 437 786 334 787 437 787 435 787 246 10 162 10 153 10 427 788 428 788 438 788 438 789 439 789 440 789 440 790 441 790 442 790 331 791 442 791 443 791 254 792 512 792 513 792 509 793 513 793 514 793 517 794 509 794 515 794 527 795 517 795 516 795 163 10 157 10 162 10 251 796 520 796 518 796 251 797 518 797 263 797 263 798 518 798 519 798 262 799 263 799 519 799 528 800 262 800 519 800 260 801 262 801 528 801 548 802 471 802 187 802 473 803 471 803 472 803 473 804 187 804 471 804 474 805 473 805 472 805 472 806 541 806 474 806 474 807 541 807 540 807 474 808 540 808 502 808 501 809 474 809 502 809 187 810 473 810 186 810 473 811 474 811 200 811 200 812 185 812 473 812 473 813 185 813 186 813 474 814 501 814 199 814 199 815 501 815 499 815 199 816 200 816 474 816 166 817 199 817 499 817 498 818 188 818 167 818 189 819 497 819 190 819 190 820 497 820 164 820 190 821 164 821 175 821 188 822 498 822 475 822 475 823 493 823 188 823 188 824 493 824 189 824 500 825 475 825 498 825 535 826 516 826 477 826 476 827 496 827 495 827 523 828 164 828 476 828 476 829 164 829 496 829 495 830 478 830 476 830 478 831 495 831 494 831 480 832 534 832 516 832 516 833 534 833 477 833 482 834 533 834 480 834 480 835 533 835 534 835 533 836 482 836 505 836 484 837 506 837 482 837 482 838 506 838 505 838 506 839 484 839 507 839 486 840 507 840 484 840 507 841 486 841 504 841 488 842 504 842 486 842 504 843 488 843 503 843 490 844 491 844 488 844 488 845 491 845 503 845 491 846 490 846 492 846 490 847 479 847 492 847 518 848 478 848 479 848 478 849 518 849 476 849 476 850 518 850 520 850 476 851 520 851 525 851 525 852 523 852 476 852 478 853 494 853 479 853 492 854 479 854 494 854 481 855 514 855 512 855 481 856 512 856 532 856 531 857 481 857 532 857 481 858 531 858 483 858 530 859 483 859 531 859 483 860 530 860 485 860 529 861 485 861 530 861 485 862 529 862 487 862 528 863 487 863 529 863 487 864 528 864 489 864 519 865 489 865 528 865 516 866 515 866 480 866 480 867 515 867 514 867 481 868 480 868 514 868 480 869 481 869 482 869 483 870 482 870 481 870 482 871 483 871 484 871 485 872 484 872 483 872 484 873 485 873 486 873 487 874 486 874 485 874 486 875 487 875 488 875 489 876 488 876 487 876 488 877 489 877 490 877 519 878 490 878 489 878 490 879 519 879 479 879 518 880 479 880 519 880 500 881 503 881 475 881 475 882 503 882 491 882 475 883 491 883 493 883 493 884 491 884 492 884 493 885 492 885 189 885 189 886 492 886 494 886 189 887 494 887 495 887 189 888 495 888 497 888 497 889 495 889 496 889 497 890 496 890 164 890 499 61 165 61 166 61 498 891 165 891 500 891 501 61 165 61 499 61 500 61 165 61 503 61 533 892 504 892 538 892 538 893 504 893 503 893 504 894 533 894 507 894 505 895 507 895 533 895 507 896 505 896 506 896 508 897 279 897 285 897 285 898 284 898 508 898 283 899 508 899 284 899 279 900 508 900 526 900 508 901 283 901 511 901 511 902 283 902 510 902 511 903 526 903 508 903 277 904 510 904 276 904 276 905 510 905 283 905 526 906 511 906 527 906 513 907 277 907 254 907 277 908 513 908 509 908 277 909 509 909 510 909 511 910 510 910 509 910 517 911 511 911 509 911 511 912 517 912 527 912 512 913 254 913 532 913 514 914 513 914 512 914 515 915 509 915 514 915 517 916 515 916 516 916 282 917 520 917 251 917 520 918 282 918 525 918 281 919 525 919 282 919 525 920 281 920 524 920 280 921 524 921 281 921 524 922 280 922 522 922 157 923 521 923 280 923 280 924 521 924 522 924 157 925 163 925 521 925 277 926 253 926 254 926 523 927 522 927 164 927 522 928 163 928 164 928 522 929 523 929 524 929 525 930 524 930 523 930 279 931 151 931 161 931 526 932 536 932 279 932 279 933 536 933 151 933 536 934 526 934 535 934 527 935 535 935 526 935 535 936 527 936 516 936 260 937 528 937 529 937 530 938 260 938 529 938 260 939 530 939 258 939 258 940 530 940 531 940 532 941 258 941 531 941 258 942 532 942 256 942 254 943 256 943 532 943 533 944 538 944 534 944 542 945 477 945 538 945 538 946 477 946 534 946 543 947 477 947 542 947 545 948 535 948 543 948 543 949 535 949 477 949 535 950 545 950 536 950 536 951 545 951 151 951 547 952 151 952 545 952 544 953 542 953 537 953 537 954 542 954 538 954 537 955 539 955 544 955 544 956 539 956 540 956 544 957 540 957 541 957 472 958 544 958 541 958 542 959 544 959 543 959 546 960 545 960 544 960 544 961 545 961 543 961 544 962 472 962 546 962 546 963 472 963 471 963 546 964 471 964 547 964 546 965 547 965 545 965 548 966 547 966 471 966 24 82 103 82 102 82 24 967 102 967 359 967 24 968 359 968 378 968 24 969 378 969 377 969 24 970 377 970 376 970 24 971 376 971 88 971 88 82 89 82 24 82 5 61 76 61 10 61 5 972 10 972 360 972 10 973 387 973 360 973 10 974 388 974 387 974 10 975 389 975 388 975 10 976 36 976 389 976 36 977 10 977 87 977 84 978 87 978 10 978 89 82 93 82 24 82 239 979 241 979 237 979 236 82 239 82 237 82 234 82 236 82 237 82 232 82 234 82 237 82 231 980 232 980 237 980 231 82 237 82 233 82 233 82 237 82 235 82 235 82 237 82 238 82 165 981 168 981 166 981 165 61 170 61 168 61 165 982 172 982 170 982 165 983 174 983 172 983 165 984 173 984 174 984 165 985 171 985 173 985 165 986 169 986 171 986 165 987 167 987 169 987 165 988 498 988 167 988 165 989 501 989 502 989 165 990 502 990 540 990 165 61 540 61 539 61 165 61 539 61 537 61 165 991 537 991 538 991 165 992 538 992 503 992 381 993 369 993 384 993 11 994 384 994 369 994 11 995 369 995 383 995 366 996 383 996 369 996 366 997 369 997 374 997 379 998 350 998 380 998 23 999 350 999 379 999 23 1000 353 1000 350 1000 353 1001 354 1001 350 1001 340 1002 350 1002 354 1002 340 1003 369 1003 350 1003 340 1004 374 1004 369 1004 150 1005 158 1005 151 1005 150 1006 156 1006 158 1006 150 1007 155 1007 156 1007 150 1008 154 1008 155 1008 151 1009 158 1009 159 1009 151 1010 159 1010 160 1010 151 1011 160 1011 161 1011 66 1012 70 1012 71 1012 66 1013 71 1013 69 1013 108 1014 113 1014 110 1014 108 1015 109 1015 113 1015 1 1016 2 1016 59 1016 22 1017 115 1017 28 1017 139 1018 140 1018 341 1018 95 1019 140 1019 139 1019 365 1020 382 1020 385 1020 382 1021 386 1021 385 1021

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5_scaled.dae b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5_scaled.dae new file mode 100644 index 0000000..58f9a90 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E3M5_scaled.dae @@ -0,0 +1,153 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:46:24 + 2025-02-20T09:46:24 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -7.1735 6.94911 4.21838 -9.932701 -1.15879 -3.1e-4 -9.92969 1.15514 -3.1e-4 -7.4536 6.66578 -3.1e-4 -6.19669 -7.61001 14.00068 -5.99999 -7.6976 7.99969 -5.93079 -7.72543 8.52069 -5.99999 -7.62085 -1.45521 -6.5373 7.42476 2.97619 -6 7.62007 -1.44611 -5.99999 -8.9e-4 -3.1e-4 -4.99999 3.65198 9.71969 -3.55469 -9.23031 23.11969 -3.56699 -8.6156 18.55868 -1.76899 -9.5904 22.63068 -4.59092 -8.80456 23.59968 4.59459 -8.80456 23.59968 1.77266 -9.5904 22.63068 3.57066 -8.6156 18.55868 3.55836 -9.23031 23.11969 0.00405997 -8.84559 18.22268 0.00405997 -9.69028 22.44568 9.93636 -1.15879 -3.1e-4 5.00366 3.81254 9.73169 6.00366 -8.9e-4 -3.1e-4 6.00366 7.62007 -1.44611 7.14516 6.97814 3.97919 6.00366 -7.62085 -1.45522 9.933361 1.15514 -3.1e-4 7.45726 6.66578 -3.1e-4 -4.47209 7.99911 23.99968 -0.9201 7.99911 10.96068 -2.7345 7.99911 10.65468 -5.10259 7.94911 9.74469 -3.99999 -8.00089 9.999691 -5.00999 -7.96456 14.00168 -6 6.94911 4.50619 -5.6464 6.94911 8.25268 -7.17349 6.94911 6.96669 -7.0646 7.04525 7.66968 -6.70469 7.3181 8.43568 -6.02019 7.68741 9.16469 -7.4536 -6.66756 -3.1e-4 -7.46809 -6.65131 13.99969 -9.91719 -1.28497 23.99968 -9.99999 -0.02063995 23.99968 -9.92209 1.24482 23.99968 -9.68389 2.49335 23.99968 -9.63909 2.66125 -3.1e-4 -8.93994 4.00025 23.99968 -9.119091 4.10304 -3.1e-4 -8.39959 5.42557 23.99968 -8.38479 5.44841 -3.1e-4 -7.47299 6.64398 23.99968 -6 -5.4987 -5.79131 -5.99999 -6.96596 -3.90192 -6 -3.36071 -7.26061 -6 -4.50038 -6.61501 -6 -2.24851 -7.67811 -9.4122 -1.47532 -3.03941 -8.06 -1.20361 -5.79601 -6 -1.13267 -7.91981 -6 -8.9e-4 -8.00031 -8.06 1.20183 -5.79601 -9.4122 1.47352 -3.03941 -6 1.13089 -7.91981 -7.3578 3.50247 -5.79601 -6 2.24673 -7.67811 -8.5105 4.2811 -3.03941 -6 3.35892 -7.26061 -6 5.49692 -5.79131 -6 4.4986 -6.61501 -6.62189 6.66578 -3.42181 -6 6.66577 -4.42251 -6.78489 -7.26453 -3.1e-4 -6.83189 -7.23065 13.99969 -5.99999 -7.6976 -3.1e-4 -5.71839 -7.8018 9.02269 -5.3855 -7.89522 9.44169 -4.95869 -7.97119 9.75468 -5.99999 -7.3473 -2.89871 -5.57889 7.84294 23.99968 -6.59929 7.38662 23.99968 -6 7.69581 -3.1e-4 -6 7.69581 2.18159 -6 7.34767 -2.89111 -6 7.07516 -3.64421 -6 7.31252 3.24219 6.00366 6.94911 4.50619 6.00366 7.31252 3.24219 6.00366 6.66577 -4.42252 6.00366 7.34767 -2.89111 6.66886 7.34083 3.17053 6.00366 7.69581 2.18159 6.00366 7.69581 -3.1e-4 6.60296 7.38662 23.99968 5.58256 7.84294 23.99968 6.00366 -7.18556 -3.39231 4.96236 -7.97119 9.75468 5.38916 -7.89522 9.44169 5.72206 -7.8018 9.02269 5.93446 -7.72543 8.52069 6.00366 -7.6976 7.99968 6.00366 -7.6976 -3.1e-4 6.20036 -7.61001 14.00068 6.83556 -7.23065 13.99968 6.78856 -7.26453 -3.1e-4 6.62556 6.66578 -3.42181 6.00366 4.4986 -6.61501 6.00366 5.49692 -5.79131 6.00366 3.35892 -7.26061 8.514161 4.2811 -3.03941 6.00366 2.24673 -7.67812 7.36146 3.50247 -5.79601 6.00366 1.13089 -7.91981 9.415861 1.47352 -3.03941 8.06366 1.20183 -5.79601 6.00366 -8.9e-4 -8.00031 6.00366 -1.13267 -7.91981 8.06366 -1.20361 -5.79601 9.415861 -1.47532 -3.03941 6.00366 -2.24851 -7.67812 6.00366 -4.50038 -6.61501 6.00366 -3.36071 -7.26061 6.00366 -6.66755 -4.42252 6.00366 -5.4987 -5.79131 7.47666 6.64398 23.99968 8.388461 5.44841 -3.1e-4 8.403261 5.42557 23.99968 9.12276 4.10304 -3.1e-4 8.943611 4.00025 23.99968 9.64276 2.66125 -3.1e-4 9.687561 2.49335 23.99968 9.92576 1.24482 23.99968 10.00366 -0.02063995 23.99968 9.92086 -1.28497 23.99968 7.47176 -6.65131 13.99968 7.45726 -6.66756 -3.1e-4 5.10626 7.94911 9.74469 6.02386 7.68741 9.16469 7.06826 7.04525 7.66968 7.17716 6.94911 6.96669 0.00405997 -8.00089 13.99868 3.58286 -8.00089 13.99868 4.00366 -8.00089 9.999691 5.01366 -7.96456 14.00168 0.003659963 7.99911 23.99968 2.73816 7.99911 10.65468 0.92376 7.99911 10.96068 4.47576 7.99911 23.99968 -3.99999 -5.02735 37.82068 4.00366 -5.02735 37.82068 -3.99999 -5.00089 39.42268 -4.48079 7.99911 34.49768 -3.53979 -8.82177 32.40168 -2.34909 -9.2897 31.73368 -1.16229 -9.554901 31.35468 4.48446 7.99911 34.49768 0.00345999 -9.63919 31.23468 1.16596 -9.554901 31.35468 2.35276 -9.2897 31.73368 3.54346 -8.82177 32.40168 0.003659963 7.99911 44.99968 4.46387 7.99911 44.99968 4.00366 6.94911 44.99968 7.00366 -8.9e-4 44.99968 7.00366 -3.61239 46.59969 7.00366 3.37761 47.04568 7.00366 -3.04855 47.51268 7.00366 2.70194 47.87968 7.00366 -2.25983 48.23969 7.00366 1.82715 48.50168 7.00366 -1.30441 48.72868 7.00366 0.81734 48.86368 7.00366 -0.25282 48.94168 4.00366 6.69274 46.86967 4.00366 5.94276 48.60168 4.00366 4.7537 50.06868 4.00366 3.21449 51.16068 4.00366 1.43786 51.79867 4.00366 -0.44483 51.93568 4.00366 -2.29479 51.56068 4.00366 -3.97553 50.70068 4.00366 -5.36307 49.42068 4.00366 -6.35507 47.81468 4.00366 -6.87828 46.00168 4.00366 -6.89415 44.11368 4.00366 -6.40153 42.29169 6.60256 4.84007 47.50069 5.76706 6.37616 44.99969 5.50366 5.81689 48.00468 6.60256 3.15259 49.44267 5.50366 3.78892 50.33968 6.60256 0.76172 50.39468 5.50366 0.9156 51.48367 6.60256 -1.79926 50.14268 5.50366 -2.16214 51.18068 6.60256 -3.9591 48.74368 5.50366 -4.7578 49.49968 6.60256 -5.23604 46.50967 5.50366 -6.29241 46.81468 -6.59889 -5.34526 43.93867 -5.49999 -6.29241 46.81468 -6.59889 -5.23604 46.50967 -5.49999 -4.7578 49.49968 -6.59889 -3.9591 48.74368 -5.49999 -2.16214 51.18068 -6.59889 -1.79926 50.14268 -5.49999 0.9156 51.48367 -6.59889 0.76172 50.39468 -5.49999 3.78892 50.33968 -6.59889 3.15259 49.44267 -5.49999 5.81689 48.00468 -5.76339 6.37616 44.99968 -6.59889 4.84007 47.50069 -6.42709 5.71247 44.99968 -3.99999 -6.40153 42.29169 -3.99999 -6.89415 44.11368 -3.99999 -6.87828 46.00168 -3.99999 -6.35507 47.81468 -3.99999 -5.36307 49.42068 -3.99999 -3.97553 50.70068 -3.99999 -2.29479 51.56068 -3.99999 -0.44483 51.93568 -3.99999 1.43786 51.79867 -3.99999 3.21449 51.16068 -3.99999 4.7537 50.06868 -3.99999 5.94276 48.60168 -3.99999 6.69274 46.86967 -6.85319 4.87616 44.99968 -4.92709 6.80228 44.99968 -6.99999 -0.25282 48.94168 -6.99999 0.81734 48.86368 -6.99999 -1.30441 48.72868 -6.99999 1.82715 48.50168 -6.99999 -2.25983 48.23969 -6.99999 2.70194 47.87968 -6.99999 -9e-4 44.99968 -6.99999 -3.04855 47.51268 -6.99999 3.37761 47.04568 -6.99999 -3.61239 46.59969 -6.99999 3.80368 46.06168 -6.99999 -3.90969 45.56868 -6.99999 3.94911 44.99968 -6.99999 -3.91855 44.49568 -3.99999 6.94911 44.99968 -4.46019 7.99911 44.99968 8.35526 -5.50089 23.99968 8.735361 -4.87502 23.99968 9.28136 -3.73246 23.99968 9.67876 -2.5291 23.99968 7.43666 6.6981 34.49368 8.314371 5.81849 29.52985 8.89386 -4.46979 29.51968 8.76546 -4.19563 35.80267 9.26076 -2.79232 29.51968 8.91906 -2.27439 35.04568 9.450961 -1.09815 29.51968 8.96676 -0.33818 35.04568 9.47666 0.60681 29.51968 8.94576 1.60178 35.04568 9.335761 2.31798 29.51968 8.83896 3.55496 35.04568 8.30708 5.67738 34.68957 8.98616 4.04325 29.51968 0.004159986 -10.00089 29.52368 0.003359973 -10.00089 30.08768 2.93366 -9.56529 30.58668 3.43473 -9.48162 29.13079 3.49076 -9.37344 25.99968 1.45316 -9.895441 25.99968 4.39459 -9.10315 25.99968 4.41876 -8.98168 31.25368 6.33566 -7.76061 29.52368 5.84346 -8.13534 32.22368 7.02016 -7.12658 25.99968 7.14446 -7.03138 33.48969 8.27176 -5.67266 35.04868 8.54566 -5.26191 29.52368 4.68486 -8.14347 33.37068 5.30646 7.91391 34.49867 6.09576 7.66057 34.49867 6.81586 7.24997 34.49968 6.91396 -7.18597 33.86967 5.65496 -8.25206 32.34668 5.01416 -8.44358 32.71868 3.31336 -9.32459 31.45968 1.18046 -9.86343 30.69068 5.37426 -8.43667 25.99968 5.71986 -8.20649 23.99968 6.46616 -7.63259 23.99968 7.16186 -6.98424 23.99968 -7.15819 -6.98424 23.99968 -6.46249 -7.63259 23.99968 -5.71619 -8.20649 23.99968 -5.37059 -8.43667 25.99968 -1.17679 -9.86343 30.69068 -3.30969 -9.32459 31.45968 -5.01049 -8.44358 32.71868 -5.65129 -8.25206 32.34668 -6.31069 -7.37931 34.23868 -6.91029 -7.18597 33.86967 -7.85419 -6.04028 35.50568 -6.81219 7.24997 34.49968 -6.09209 7.66057 34.49867 -5.30279 7.91391 34.49867 -8.268091 -5.67266 35.04868 -4.68119 -8.14347 33.37068 -5.72309 -7.25891 34.63368 -8.54199 -5.26191 29.52368 -7.14079 -7.03138 33.48969 -7.01649 -7.12658 25.99968 -5.83979 -8.13534 32.22368 -6.33199 -7.76061 29.52368 -4.41509 -8.98168 31.25368 -4.39092 -9.10315 25.99968 -1.44949 -9.895441 25.99968 -3.48709 -9.37343 25.99968 -3.43106 -9.48162 29.13079 -2.92999 -9.56529 30.58668 0.001839995 -10.00019 25.99969 -8.98249 4.04325 29.51968 -8.30341 5.67738 34.68957 -8.83529 3.55496 35.04568 -9.33209 2.31798 29.51968 -8.94209 1.60178 35.04568 -9.47299 0.60681 29.51968 -8.96309 -0.33818 35.04568 -9.44729 -1.09815 29.51968 -8.91539 -2.27439 35.04568 -9.25709 -2.79232 29.51968 -8.76179 -4.19563 35.80267 -8.890191 -4.46979 29.51968 -8.3107 5.81849 29.52985 -7.43299 6.6981 34.49368 -9.67509 -2.5291 23.99968 -9.27769 -3.73246 23.99968 -8.73169 -4.87502 23.99968 -8.351591 -5.50089 23.99968 0.001829981 7.242 10.60569 4.00366 4.25152 9.999691 5.65006 6.94911 8.25268 5.55006 6.94911 5.59469 3.89726 6.94911 9.21068 3.63686 6.94093 6.60969 1.98966 6.94911 9.80069 0.003659963 6.94911 9.999691 0.003659963 6.94911 7.84768 4.30636 7.242 9.80469 1.47496 7.242 10.60569 4.32487 5.06448 8.40697 3.63686 6.82538 6.40069 4.38886 6.06216 6.65668 4.68666 3.9459 9.879691 4.34936 4.09318 9.96969 3.63371 6.43688 6.43168 4.43506 6.73264 6.19568 4.49076 6.91366 6.33069 5.94346 3.82193 8.45469 6.004 4.02117 8.04468 -6 4.02117 8.04468 -5.93979 3.82193 8.45469 -5.54639 6.94911 5.59469 -4.5404 6.94911 6.46068 -3.6332 6.94093 6.60969 -4.45075 6.64691 6.24219 -4.34569 4.09222 9.96969 -3.6332 6.82538 6.40069 3.63321 5.95391 6.88068 -4.32395 5.11941 8.41997 -1.47129 7.242 10.60569 -4.30269 7.242 9.80469 -1.98599 6.94911 9.80069 -3.89359 6.94911 9.21068 -3.99999 4.25198 9.999691 4.47576 -8.00089 9.94269 6.00366 5.96671 5.62369 6.00366 4.86318 6.60168 6.00366 4.40365 7.39368 5.41736 3.62295 9.41469 5.73196 3.74311 9.003681 -5.72829 3.74311 9.003681 -3.63359 6.44435 6.42669 -4.68299 3.85204 9.879691 -5.41369 3.62295 9.41469 -4.3852 6.06216 6.65668 -3.6332 5.95391 6.88068 -5.99999 4.40365 7.39368 -5.99999 4.86318 6.60168 -6 5.96671 5.62369 -4.47209 -8.00089 9.94269 -8.38479 -5.4502 -3.1e-4 -9.63909 -2.66304 -3.1e-4 -6.78409 -6.66756 -3.03501 -8.5105 -4.2829 -3.03941 -7.3578 -3.50425 -5.79601 7.36146 -3.50425 -5.79601 8.514161 -4.2829 -3.03941 6.78776 -6.66756 -3.03501 9.64276 -2.66304 -3.1e-4 8.388461 -5.4502 -3.1e-4 9.12276 -4.10482 -3.1e-4 -9.119091 -4.10482 -3.1e-4 -3.57919 -8.00089 13.99868 -3.99999 -5.43664 40.66869 -5.48459 -5.09962 40.93769 -5.49999 -4.73356 40.21569 -5.76329 -4.42797 39.42269 -6.42709 -4.46943 41.43969 -6.59809 -3.69701 40.57769 -6.42699 -3.76429 39.42269 -6.85319 -2.92798 39.42269 -6.6831 -3.81534 41.96069 -6.99999 -3.09028 42.53869 -6.99999 -2.49594 41.59168 -6.99999 -2.12557 40.53269 -6.99999 -2.00089 39.42269 -5.36349 -4.67315 38.32668 -6.19619 -4.0446 39.22469 -6.72699 -3.25133 38.74369 -6.99999 -2.00089 38.27869 -6.96549 -2.4548 38.42168 -8.53599 -1.46623 39.60468 -8.55289 -0.11087 39.43468 -8.54059 1.25595 39.55968 -8.50409 2.50568 39.95368 -8.45399 3.57721 40.56069 -6.76829 -5.70594 36.85169 -6.86009 -4.0311 39.22569 -6.92969 7.10944 44.99969 -6.11599 7.64029 44.99969 -5.93589 7.04911 44.99969 -5.49999 6.94911 44.99969 -5.31029 7.90772 44.99969 -4.88529 7.95342 44.99969 -7.19169 6.82799 43.78869 -8.19199 4.97673 41.65069 -7.71279 6.06131 42.71468 -7.49639 -5.59217 36.77569 -7.60349 -3.56948 39.46268 -8.124691 -5.26918 36.55169 -8.062291 -2.97472 39.64069 -8.56689 -4.78127 36.21169 -8.399291 -2.25591 39.68868 -7.28129 -6.21366 35.90269 -6.99999 1.68717 38.19369 -6.99999 0.45891 38.00269 -6.99999 -0.78335 38.03168 -6.99999 2.86304 38.59969 -6.99999 3.94911 39.20568 -6.99999 -3.63839 43.45969 -5.03399 6.76527 43.41169 -5.49999 6.54719 42.67069 -5.9359 6.24091 41.72169 -6.39679 5.75341 40.92669 -6.83869 4.91954 39.95969 -7.08054 5.94669 41.49869 -7.43409 4.97597 40.42869 -8.19199 4.02715 40.55369 -7.43409 3.77077 39.39269 -8.19199 2.84199 39.71668 -7.43409 2.35678 38.66769 -8.19199 1.49065 39.18868 -7.43409 0.81253 38.29169 -8.19199 0.05166995 39.00069 -7.43409 -0.7768 38.28768 -8.19199 -1.39001 39.16369 -7.43409 -2.3232 38.65369 -6.72699 6.57048 42.44669 -6.72699 6.92842 43.70069 -5.49999 -6.42367 43.72469 5.48826 -5.09962 40.93769 6.43076 -4.46943 41.43969 5.50366 -6.42367 43.72469 6.60256 -5.34526 43.93868 6.85686 4.87616 44.99969 6.73066 6.92842 43.70069 6.73066 -3.25133 38.74369 6.73066 6.57048 42.44669 7.08421 5.94669 41.49869 7.43776 -2.3232 38.65369 8.19566 -1.39001 39.16369 7.43776 -0.7768 38.28768 8.19566 0.05166995 39.00069 7.43776 0.81253 38.29169 8.19566 1.49065 39.18868 7.43776 2.35678 38.66769 8.19566 2.84199 39.71668 7.43776 3.77077 39.39269 8.19566 4.02715 40.55369 7.43776 4.97597 40.42869 6.84236 4.91954 39.95969 6.40046 5.75341 40.92669 6.43076 5.71247 44.99969 5.93956 6.24091 41.72169 5.50366 6.54719 42.67069 5.03766 6.76527 43.41169 4.93076 6.80228 44.99969 7.00366 3.80368 46.06168 7.00366 -3.90969 45.56869 7.00366 3.94911 44.99969 7.00366 -3.91855 44.49569 7.00366 -3.63839 43.45969 7.00366 3.94911 39.20568 7.00366 2.86304 38.59969 7.00366 -0.78335 38.03168 7.00366 0.45891 38.00269 7.00366 1.68717 38.19369 6.31436 -7.37931 34.23869 8.12836 -5.26918 36.55169 7.85786 -6.04028 35.50568 7.28496 -6.21366 35.90269 8.40296 -2.25591 39.68868 8.57056 -4.78127 36.21169 8.06596 -2.97472 39.64069 7.60716 -3.56948 39.46268 6.99346 -4.00149 39.23769 7.50006 -5.59217 36.77569 7.71646 6.06131 42.71468 8.19566 4.97673 41.65069 7.19536 6.82799 43.78869 4.88896 7.95342 44.99969 5.31396 7.90772 44.99969 5.93956 7.04911 44.99969 6.11966 7.64029 44.99969 6.93336 7.10944 44.99969 5.72676 -7.25891 34.63369 6.77196 -5.70594 36.85169 8.45766 3.57721 40.56069 8.507761 2.50568 39.95368 8.54426 1.25595 39.55968 8.55656 -0.11086 39.43468 8.53966 -1.46623 39.60468 7.00366 -2.00089 38.27869 6.96916 -2.4548 38.42168 6.19986 -4.0446 39.22469 5.36716 -4.67315 38.32668 7.00366 -2.31088 41.06269 7.00366 -2.00089 39.42269 7.00366 -2.49594 41.59168 7.00366 -3.09028 42.53869 6.75609 -3.81534 41.96069 6.85686 -2.92798 39.42269 6.43066 -3.76429 39.42269 6.60176 -3.69701 40.57769 5.76696 -4.42797 39.42269 5.50366 -4.73356 40.21569 4.00366 -5.00089 39.42269 4.00366 -5.43664 40.66869 + + + + + + + + + + -0.3799088 -0.9250235 0.001048445 -0.6139672 0.7892366 -0.01224112 -0.0759257 -0.9767864 -0.200309 -0.2299373 -0.9645672 -0.1293793 -0.08133679 -0.9773278 -0.1954864 -0.4242824 -0.8975669 -0.1198255 0.4242821 -0.897567 -0.1198257 0.08143758 -0.9773196 -0.1954848 0.2299373 -0.9645672 -0.1293793 0.07610845 -0.9767886 -0.2002285 0 1 0 -0.02010369 0.9997945 -0.002617537 -0.9978624 -0.06534969 3.01319e-4 -0.9999951 0.001300692 -0.002865374 -0.9981107 0.06144225 8.64721e-5 -0.9822826 0.1874051 -3.89221e-4 -0.9818897 0.189453 -5.07475e-4 -0.896676 0.4426852 0.00142312 -0.9406546 0.3392596 0.008474588 -0.9350273 0.3544741 0.008497774 -0.8777682 0.4790858 -8.53726e-5 -0.7959709 0.6053348 8.52243e-5 -0.7942761 0.607557 -8.98341e-5 -0.7306165 0 -0.6827881 -0.8978016 0 -0.4404002 -0.8978015 0 -0.4404005 -0.7160986 0.04952156 -0.6962403 -0.7571126 0.1382995 -0.6384776 -0.6977736 0.212974 -0.6839255 -0.8561726 0.2613199 -0.4457358 -0.9219178 0.3325002 -0.1987744 -0.9382056 0.3013204 -0.1702246 -0.8568307 0.2751851 -0.4360212 -0.6972523 0.2519209 -0.6711 -0.868348 0.4739412 -0.1461215 -0.7374927 0.5031387 -0.4505063 -0.7787755 0.5957012 -0.1965932 -0.7842012 0.5905 -0.1906262 -0.7353641 0.5110189 -0.4450837 -0.722465 0.5257914 -0.4489853 -0.6732938 -0.7393749 -4.71043e-4 -0.6659585 -0.7459889 1.76529e-4 -0.5127453 -0.8585407 3.56307e-4 -0.4830961 -0.8755664 -0.001309394 -0.3447124 -0.9387034 0.003044724 -0.2800471 -0.959949 0.008464515 -0.1748322 -0.9845982 -5.74761e-4 -0.1397159 0.990188 0.002706468 -0.2731179 0.9619786 -0.001960813 -0.4082341 0.9128737 0.002573251 -0.4742823 0.8803726 -6.63911e-4 -0.4504006 0.8928266 0 -0.7111676 0.7030225 2.61297e-6 -0.5779047 0.8155508 -0.03005313 -0.6049246 0.7962827 5.90979e-4 -0.6756773 0.7371875 0.003842294 -0.5776383 0.8151751 -0.04270333 -0.646443 0.7466048 -0.1571398 -0.6768237 0.7234036 -0.1363707 -0.5952005 0.7556287 -0.2734258 -0.5995312 0.7083365 -0.372588 1 0 0 1 4.57914e-7 -4.87399e-6 1 6.60885e-7 -3.78783e-7 1 7.73188e-7 2.69209e-7 1 6.10067e-7 -2.46621e-7 1 6.28831e-7 -1.2847e-7 1 9.32973e-7 -2.24897e-6 1 1.37122e-6 0 1 1.13577e-6 0 0.02818775 0.9400969 0.3397405 0.01435941 0.9313032 0.3639617 0.1297287 0.9795094 -0.1540516 -0.6476441 0.7619397 0.002261519 -0.7119071 0.7022737 6.27266e-5 -0.9858108 0 -0.1678611 -0.9714014 0.1874296 -0.1457722 0.971401 0.1874295 -0.1457754 0.9856487 0 -0.1688096 0.7119134 0.7022674 6.24341e-5 0.6476438 0.7619401 0.002261519 0.004945993 0.9135041 0.4067998 -1 0 0 -1 1.67221e-7 0 -1 0 0 -1 0 0 -1 0 0 0.5476507 0.7643564 -0.3403499 0.6768175 0.7234092 -0.1363717 0.6464421 0.746606 -0.1571373 0.5776383 0.8151751 -0.04270333 0.6756373 0.7372242 0.00383985 0.5779066 0.8155539 -0.02993488 0.619653 0.7847682 -0.01300072 0.7033936 0.7108004 -6.27444e-4 0.4708018 0.8822391 0 0.4082344 0.9128735 0.002573251 0.2731176 0.9619786 -0.001960813 0.1397159 0.990188 0.002706468 0.1748364 -0.9845974 -5.74775e-4 0.2800377 -0.9599518 0.008463203 0.3447131 -0.9387032 0.003044724 0.3799099 -0.925023 0.001048922 0.4830951 -0.875567 -0.001309454 0.5127458 -0.8585404 3.56307e-4 0.6659643 -0.7459837 1.76075e-4 0.6732935 -0.7393752 -4.71043e-4 0.7224647 0.5257896 -0.4489881 0.7353649 0.511016 -0.4450857 0.7842025 0.5904989 -0.1906242 0.7787721 0.5957042 -0.1965978 0.7374925 0.5031391 -0.4505063 0.8683471 0.4739423 -0.146124 0.6972507 0.2519274 -0.6710993 0.8568306 0.2751851 -0.4360213 0.9382053 0.3013195 -0.1702275 0.9219167 0.3325015 -0.198777 0.8561726 0.2613199 -0.4457358 0.6977736 0.212974 -0.6839255 0.7571178 0.1382925 -0.6384732 0.7160985 0.04952156 -0.6962404 0.8978015 0 -0.4404005 0.8978016 0 -0.4404002 0.7306165 0 -0.6827881 0.794273 0.6075612 -9.01708e-5 0.7959702 0.6053359 8.52243e-5 0.8777693 0.4790838 -8.53857e-5 0.9350267 0.3544756 0.008497774 0.9406552 0.3392581 0.008474588 0.896676 0.4426852 0.00142312 0.9818896 0.1894538 -5.07507e-4 0.9822829 0.1874042 -3.89178e-4 0.9980943 0.06144225 -0.005712568 0.9999992 0.001295745 3.11856e-4 0.9978625 -0.06534868 3.00879e-4 0.02010363 0.9997945 -0.002617657 0 -1 -3.33183e-7 0 1 1.30838e-7 0 -0.9998636 0.01651459 0 0 1 0.699459 0.6890758 0.1895569 0.2289098 0.8932969 0.3868089 0.9624838 0.2108318 0.1708065 0.9594557 0.212758 0.1848753 0.6969233 0.541327 0.470386 0.3600229 0.7247664 0.5874498 0.308513 0.7181713 0.6237385 0.6971632 0.541269 0.4700971 0.967513 0.1465044 0.2060467 0.2193372 0.5645359 0.7957327 0.9575935 0.09722816 0.2712224 0.9614183 0.1017668 0.2555749 0.6972126 0.2651948 0.6660078 0.6971736 0.2651839 0.6660529 0.3007256 0.3223257 0.8975914 0.3444123 0.347271 0.8722288 0.9670221 0.01851361 0.2540191 0.2285001 0.07066261 0.9709761 0.6971852 -0.07020366 0.7134453 0.9501792 -0.0618782 0.3055006 0.9640705 -0.02601414 0.2643697 0.3623325 -0.09131467 0.927565 0.6971447 -0.07023918 0.7134815 0.2569239 -0.1919976 0.9471679 0.9653677 -0.1188648 0.2322424 0.6971182 -0.389773 0.6017503 0.9584006 -0.1551722 0.2395622 0.6971911 -0.389687 0.6017215 0.4292185 -0.4114192 0.8040559 0.252278 -0.5260005 0.8122065 0.2286626 -0.6600856 0.7155421 0.9669961 -0.1726864 0.1873446 0.6971476 -0.622424 0.355772 0.9624235 -0.2310442 0.1426877 0.9594331 -0.244772 0.1399094 0.6971164 -0.6224615 0.3557673 0.3600109 -0.7937372 0.4902789 0.3083918 -0.8258818 0.4720316 0.2194978 -0.9373604 0.2705109 -0.9576526 -0.2879167 0.002377569 -0.6970757 -0.7163515 0.03043162 -0.9675209 -0.2428946 0.07004058 -0.2194978 -0.9373604 0.2705109 -0.3083918 -0.8258818 0.4720316 -0.3600109 -0.7937372 0.4902789 -0.6971169 -0.6224611 0.3557673 -0.959433 -0.2447725 0.1399096 -0.9624231 -0.2310454 0.1426878 -0.6971476 -0.622424 0.355772 -0.9669961 -0.1726864 0.1873448 -0.2286626 -0.6600856 0.7155421 -0.252278 -0.5260005 0.8122065 -0.4292185 -0.4114191 0.804056 -0.6971914 -0.3896868 0.6017214 -0.9584004 -0.1551728 0.2395625 -0.6971185 -0.3897727 0.6017501 -0.9653677 -0.1188637 0.2322427 -0.2569239 -0.1919976 0.9471679 -0.6971448 -0.070239 0.7134814 -0.3623325 -0.09131467 0.927565 -0.9640705 -0.02601414 0.26437 -0.9501791 -0.06187868 0.3055009 -0.6971854 -0.07020372 0.7134452 -0.2285001 0.07066261 0.9709761 -0.967022 0.01851475 0.2540194 -0.3444123 0.3472709 0.8722288 -0.3007255 0.3223258 0.8975914 -0.6971738 0.2651837 0.6660528 -0.6972126 0.2651949 0.6660076 -0.9614183 0.1017662 0.2555752 -0.9575933 0.09722852 0.2712227 -0.2193372 0.564536 0.7957326 -0.967513 0.1465044 0.2060468 -0.6971634 0.5412688 0.4700971 -0.3085131 0.7181711 0.6237387 -0.3600229 0.7247664 0.5874498 -0.6969231 0.5413278 0.4703854 -0.9594557 0.2127577 0.1848756 -0.9624837 0.2108324 0.1708068 -0.2289098 0.8932969 0.3868089 -0.9670202 0.2337297 0.1012045 -0.6994597 0.6890752 0.1895562 -0.4446891 0.8727464 0.2014088 -0.1500748 0.9475706 0.2821127 -0.4295782 0.894661 0.1226552 -0.9501794 0.3088003 0.04244536 -0.6936243 0.6936355 0.1943067 -0.9874669 0.1563673 0.02141278 -0.8447947 0.4304234 0.3178956 0 -0.9653381 -0.2610028 0 -0.9653378 -0.2610037 0 -0.9999648 0.008405625 0 -0.9999648 0.008405148 0 -0.9607912 0.2772729 0 -0.9607913 0.277273 0 -0.8507841 0.5255154 0 -0.850784 0.5255157 0 -0.6780502 0.7350156 0 -0.6780502 0.7350156 0 -0.4555124 0.8902295 0 -0.4555125 0.8902295 0 -0.1986665 0.9800672 0 -0.1986665 0.9800672 0 0.0725829 0.9973624 0 0.3379701 0.9411569 0 0.3379701 0.9411569 0 0.578626 0.8155931 0 0.5786261 0.8155931 0 0.7768597 0.6296737 0 0.9176633 0.3973588 0 0.9176635 0.3973583 0 0.9907326 0.1358266 0 0.9907326 0.1358271 -1 0 0 0 -0.9749884 0.222256 0 -0.9245343 0.381099 0.9022545 -0.4311658 0.005745112 0.9764875 -0.2135774 0.02927517 0.976124 -0.2134988 0.04000508 0.948024 -0.3130773 0.05685973 0.9963483 -0.05341035 0.06661492 0.9776344 -0.1902419 0.08966118 0.9913359 -0.1112947 0.06976151 0.9911978 -0.1112794 0.07172036 0.9955846 -0.02452743 0.09060841 0.9940939 -0.06510329 0.08682727 0.9958893 -0.01501119 0.08932644 0.9951989 -0.01500093 0.09671789 0.9942417 0.06120407 0.08796417 0.9955418 0.0107764 0.09370434 0.9933758 0.08179557 0.08070921 0.9925646 0.08172851 0.09019994 0.9799824 0.1869666 0.06839597 0.9955196 0.05443531 0.07731437 0.9682614 0.247941 0.03154814 0.9779558 0.1981679 0.0658192 0.8966289 0.4426618 -0.01035964 0.9777716 0.1981301 0.06860983 0.1470032 -0.9891361 2.09995e-4 0.2480651 -0.9683088 -0.02901625 0.07172209 -0.9937151 0.08594286 0.1496278 -0.9887424 -2.95121e-4 0.149039 -0.9888159 -0.005531847 0.2864006 -0.9577018 -0.02796369 0.3403009 -0.9381902 0.06320196 0.562478 -0.8267962 0.005163013 0.5045124 -0.8619278 0.05047631 0.5346261 -0.8436591 -0.04913645 0.5126293 -0.8582266 -0.02566188 0.6226496 -0.7822504 -0.01979756 0.6410891 -0.7673967 0.01036179 0.7970201 -0.6017187 -0.0519002 0.7489991 -0.6624602 -0.01211839 0.7487949 -0.6622802 0.0262897 0.9153769 -0.4023008 0.01547068 0.6153915 -0.7864137 0.05335718 0.5700288 -0.8155577 0.09966385 0.1247459 -0.8758621 0.4661591 0.5187477 -0.8547754 -0.01612663 0.3764861 -0.9086223 0.1807313 0.3248482 -0.9228477 0.2069437 0.1331168 -0.8874807 0.4412004 0.09620517 -0.88767 0.4503185 0.3148171 -0.9412037 0.1225793 0.06741726 -0.9042549 0.4216374 0.0830574 -0.9096373 0.4070155 0.1755372 -0.9659669 0.189986 0.02219641 -0.9064726 0.421681 0.1616611 -0.9825876 -0.09158265 0.0649293 -0.9943587 -0.08387511 0.07171708 -0.9936583 -0.08660238 0.208957 -0.9769504 -0.04364818 0.2476602 -0.966728 -0.06404381 0.6092862 -0.792317 0.03168803 0.6226751 -0.7822833 0.01756477 0.6817677 -0.7315591 -0.003761589 0.4745671 -0.8800084 -0.01927512 0.561607 -0.8255136 -0.05590271 0.409902 -0.9087111 -0.07889592 0.2862735 -0.9572765 -0.040856 0.7956075 0.6050592 -0.03020125 0.9350122 0.3544702 -0.01015615 0.9352077 0.3539596 -0.009966015 0.9352367 0.3538522 0.01099866 0.7589787 0.6508421 0.01887196 0.7791006 -0.6268095 0.01058924 0.7732634 -0.6340846 7.7921e-4 0.8547009 -0.5190737 -0.007003486 0.9154593 -0.4023976 0.003254473 0.1030972 0.9946714 -8.55227e-5 0.1397158 0.9901871 -0.003019094 0.3056116 0.952155 0.001600563 0.4082323 0.9128689 -0.004097938 0.4953317 0.8687031 0.001262128 0.6476423 0.7619379 -0.00321561 0.6643888 0.747386 -0.001322031 0.7051305 0.709077 -9.69156e-4 -0.7051307 0.7090767 -9.69081e-4 -0.6643887 0.7473861 -0.001322031 -0.647643 0.7619373 -0.00321561 -0.4953312 0.8687033 0.001262128 -0.4082321 0.912869 -0.004097938 -0.3056116 0.952155 0.001600563 -0.1397157 0.9901871 -0.003019094 -0.1030972 0.9946713 -8.55227e-5 -0.9154574 -0.4024018 0.003254473 -0.8547025 -0.5190709 -0.007003366 -0.7732635 -0.6340844 7.79522e-4 -0.7791004 -0.6268098 0.01058894 -0.7589781 0.6508427 0.01887178 -0.935237 0.3538515 0.01099854 -0.9352076 0.3539597 -0.009966194 -0.9350122 0.3544702 -0.01015615 -0.7956079 0.6050586 -0.03020131 -0.2862634 -0.9572798 -0.0408523 -0.4099018 -0.9087113 -0.07889586 -0.561607 -0.8255136 -0.05590271 -0.4745674 -0.8800082 -0.01927512 -0.6817677 -0.7315591 -0.003761589 -0.6226751 -0.7822833 0.01756477 -0.6092863 -0.7923171 0.03168749 -0.2476648 -0.9667268 -0.0640437 -0.2089563 -0.9769506 -0.0436446 -0.07171607 -0.9936506 -0.0866912 -0.06476855 -0.9943678 -0.08389127 -0.1616078 -0.9825281 -0.09231173 -0.02213466 -0.9064741 0.4216809 -0.1755372 -0.9659669 0.1899862 -0.0830574 -0.9096373 0.4070156 -0.06741726 -0.9042549 0.4216374 -0.3148171 -0.9412038 0.1225789 -0.09620517 -0.8876698 0.4503187 -0.1331168 -0.8874802 0.4412016 -0.3248481 -0.9228479 0.2069436 -0.3764863 -0.9086222 0.1807314 -0.5187487 -0.8547747 -0.01612663 -0.1247459 -0.8758621 0.4661591 -0.1527347 -0.866174 0.4758308 -0.4117256 -0.8735862 0.2594783 -0.5700271 -0.8155589 0.09966355 -0.6153938 -0.7864118 0.05335736 -0.4326135 -0.8665297 0.248942 -0.1476498 -0.8632162 0.4827603 -0.7143134 -0.6942062 0.08851099 -0.6784806 -0.725324 0.1164872 -0.9425724 -0.3322913 0.03376227 -0.9153763 -0.4023022 0.01547038 -0.7487951 -0.66228 0.02628976 -0.7489992 -0.6624601 -0.01211845 -0.7970203 -0.6017185 -0.05190044 -0.6410887 -0.767397 0.01036196 -0.6226494 -0.7822505 -0.01979744 -0.512629 -0.8582267 -0.02566182 -0.5346265 -0.8436589 -0.04913651 -0.5045122 -0.8619278 0.05047631 -0.5624784 -0.826796 0.005163013 -0.3403007 -0.9381903 0.0632019 -0.2863907 -0.9577047 -0.02796787 -0.1488336 -0.9888464 -0.005604267 -0.1494517 -0.9887691 -9.78426e-5 -0.07172155 -0.9937152 0.08594262 -0.2480699 -0.9683075 -0.02901911 -0.146923 -0.989148 -2.0988e-4 -0.9777713 0.1981316 0.06860983 -0.8966289 0.4426618 -0.01035982 -0.9779558 0.1981671 0.06581944 -0.9682613 0.2479413 0.03154796 -0.9955196 0.05443459 0.07731419 -0.9799828 0.1869645 0.06839603 -0.9925644 0.08173012 0.0902 -0.9933757 0.08179718 0.08070909 -0.9955418 0.0107764 0.09370434 -0.9942417 0.06120407 0.08796411 -0.9951989 -0.01500177 0.09671777 -0.9958893 -0.0150128 0.08932638 -0.9940939 -0.06510329 0.08682739 -0.9955846 -0.02452677 0.09060823 -0.991198 -0.1112787 0.0717203 -0.9913359 -0.1112955 0.06976151 -0.9776346 -0.1902409 0.08966141 -0.9963483 -0.05341035 0.06661498 -0.9480245 -0.3130764 0.05685979 -0.976124 -0.2134988 0.04000508 -0.9764872 -0.2135787 0.02927529 -0.9022545 -0.4311658 0.005745112 0 0.4245262 -0.9054157 0 0.4245272 -0.9054152 0 0.4245259 -0.9054158 0 0.9003555 -0.4351552 0 0.9003555 -0.4351555 0 0 -1 0.02991503 0.9995336 -0.006138741 -0.04896819 0.9985495 -0.02238243 -9.43513e-4 0.999995 -0.003050804 0.001672089 0.9999972 -0.00170046 -0.181268 0.9258216 -0.3316572 -0.3360532 0.3045262 -0.8912532 -0.2418651 0.4588615 -0.8549546 -0.1267189 0.9033753 -0.4097017 -0.1072931 0.9190465 -0.3792648 -0.1573909 0.3229818 -0.9332261 -0.0362823 0.9314368 -0.36209 -0.9893153 5.88579e-4 -0.1457909 -0.08645462 0 -0.9962558 -0.2562138 -0.07479709 -0.9637219 -0.4628279 0.6170639 -0.6364138 -0.1274827 0.6178865 -0.7758637 -0.1290537 0.8678367 -0.4797965 0.5240565 0.5956107 -0.6087797 0.08703243 0.8718323 -0.4820104 0.02729153 0.5909897 -0.8062173 0.08645868 0 -0.9962555 0.9894277 5.57673e-4 -0.1450267 0 -0.07951611 -0.9968336 0 0.8751525 -0.4838472 0 0.8751526 -0.4838472 0.0362119 0.9314544 -0.362052 0.1573909 0.3229839 -0.9332254 0.1072932 0.9190472 -0.3792634 0.1267189 0.9033752 -0.4097018 0.2418644 0.4588636 -0.8549537 0.3360537 0.3045269 -0.8912526 0.181267 0.925822 -0.3316566 0 0.9999783 -0.006607115 -0.001670062 0.9999971 -0.001701354 9.43515e-4 0.999995 -0.003050446 0.00937879 0.9999536 -0.002205908 -0.03447008 -0.5646155 -0.824634 -0.02256971 -0.8681976 -0.4957052 0 -1 0 -0.02658045 0.9996436 -0.002508521 0.008109092 0.9999209 0.009629666 0.4067909 -0.9135214 0 -0.9912948 2.01194e-5 -0.1316614 -0.9330816 -0.001328408 -0.3596625 -0.9209654 1.48251e-4 -0.3896445 -0.7940332 -3.20046e-4 -0.6078744 -0.7830108 4.59087e-4 -0.622008 -0.6083325 -3.71086e-4 -0.7936823 -0.5914261 4.99623e-4 -0.806359 -0.4231368 -2.84714e-4 -0.9060659 -0.3604894 0.001444935 -0.9327622 -0.258025 -5.39848e-4 -0.9661381 -0.1198638 9.6358e-4 -0.9927899 -0.003411054 0.9404647 0.3398744 0.1025817 0.9559973 0.2748565 -0.541073 -0.7274026 -0.4220492 -0.5420631 -0.7246638 -0.4254764 -0.5415135 -0.7219391 -0.4307752 -0.5692425 -0.7540961 -0.3275701 -0.6624484 -0.4968496 -0.560627 -0.3506087 -0.8080537 -0.473416 -0.8456505 -0.4008612 -0.3523998 -0.3836638 0.7883505 -0.4809427 -0.4088085 0.3925459 -0.8238832 -0.1297296 0.9795089 -0.1540536 -0.4955191 -0.4686755 -0.731303 -0.4284467 -0.2236674 -0.8754464 0.4467427 -0.2317857 -0.864116 0.4966071 -0.464201 -0.733416 0.2326981 0.8764512 -0.421527 0.1795241 0.799304 -0.5734844 0.4088085 0.3925459 -0.8238832 0.3836643 0.7883484 -0.4809457 0.8456452 -0.4008675 -0.3524051 0.3384107 -0.824899 -0.4527911 0.01363778 -0.8815902 -0.4718188 0.6743778 -0.4897354 -0.5526065 0.586257 -0.7389912 -0.3319561 0.5605377 -0.7095019 -0.4270886 0.5613982 -0.7135143 -0.419201 0.5604301 -0.7163533 -0.4156394 -0.067613 0.958868 0.2756824 0.1198654 9.63657e-4 -0.9927897 0.2581613 -5.41422e-4 -0.9661017 0.3604868 0.001456379 -0.9327633 0.4511359 -0.001083612 -0.8924546 0.5913214 -3.26541e-4 -0.8064359 0.5934292 -4.34382e-4 -0.8048861 0.7830199 4.58473e-4 -0.6219966 0.7940332 -3.19967e-4 -0.6078744 0.9209654 1.48175e-4 -0.3896445 0.9330819 -0.001328527 -0.3596618 0.9912944 1.99627e-5 -0.131664 -0.4067897 -0.9135219 0 -0.006248712 -0.8652143 -0.5013635 0 -0.8791204 -0.4765997 0 1 2.31276e-7 -0.1187474 -0.6759967 -0.727274 -0.6994545 -0.5644611 -0.4383458 -0.730081 -0.5293507 -0.4321686 -0.7953388 -0.5761455 -0.188395 -0.7374915 -0.5031378 -0.4505094 -0.6633329 -0.3688408 -0.6511113 -0.6818597 -0.4655324 -0.5642226 -0.6972542 -0.2519184 -0.671099 -0.9352673 -0.3003759 -0.1872151 -0.8568298 -0.2751849 -0.4360229 -0.7072177 -0.1496701 -0.6909718 -0.7163138 -0.2186332 -0.6626418 -0.856172 -0.2613197 -0.4457372 -0.7160985 -0.04952162 -0.6962404 -0.5992678 -0.7483098 -0.2844477 -0.6337927 -0.7599773 -0.1440187 -0.6588848 -0.7380656 -0.1453619 -0.6263898 -0.7648207 -0.1506165 0.6263903 -0.7648203 -0.1506165 0.6588904 -0.7380607 -0.145361 0.5971537 -0.7826108 -0.1758633 0.6222693 -0.69937 -0.3516567 0.7160984 -0.04952156 -0.6962406 0.856172 -0.2613197 -0.4457373 0.7163156 -0.2186334 -0.6626397 0.7072184 -0.1496642 -0.6909723 0.8568298 -0.2751849 -0.436023 0.9352666 -0.3003761 -0.1872179 0.6972525 -0.251925 -0.6710982 0.6818597 -0.4655324 -0.5642226 0.6633328 -0.3688412 -0.6511113 0.7374912 -0.5031381 -0.4505095 0.7953405 -0.5761426 -0.1883969 0.7300819 -0.5293479 -0.4321705 0.7543528 -0.4992209 -0.4262984 0 -1 -2.66215e-7 0.001063585 -0.9999607 0.00880891 0.02537727 -0.9996744 0.002670288 0.7935888 -0.6084544 -1.15683e-4 0.7942696 -0.6075656 -1.84465e-4 0.854722 -0.519086 8.60392e-5 0.8777705 -0.4790801 -0.001205861 0.9022697 -0.4311717 7.27118e-4 0.9406878 -0.3392723 -9.5256e-4 0.9495603 -0.3135846 3.25717e-4 0.9815879 -0.1910108 -4.0639e-4 0.9814795 -0.1915668 -3.73282e-4 0.8683488 -0.4739397 -0.1461213 0.9276118 -0.334557 -0.1661565 0.2862613 -0.9581054 0.009408593 0.06123709 -0.9981229 8.18592e-4 0.7791398 -0.6268418 0.00327599 0 -0.9805852 -0.1960937 0.07625222 -0.9881774 -0.1330072 0.6732891 -0.7393699 -0.003750562 0.6817668 -0.7315576 -0.00421977 0.512665 -0.8584476 -0.01556652 0.609494 -0.7925865 -0.01799172 0.2859638 -0.9572588 -0.04336237 0.483862 -0.8733946 -0.05531126 0.02543574 -0.9907243 -0.1334865 0.1981129 -0.9771604 -0.07686901 0.970884 -0.1894968 -0.1465443 0.7823502 -0.5984465 -0.1725981 0.4825818 -0.8746349 -0.04613882 -0.4825817 -0.8746348 -0.04613989 -0.7823529 -0.5984421 -0.1726012 -0.9708826 -0.1895046 -0.1465436 -0.1981127 -0.9771605 -0.07686907 -0.02543574 -0.9907242 -0.1334866 -0.4838626 -0.8733943 -0.05531144 -0.2859634 -0.9572589 -0.04336231 -0.609494 -0.7925865 -0.01799172 -0.5126656 -0.8584472 -0.01556658 -0.6817663 -0.7315579 -0.00421977 -0.6732887 -0.7393702 -0.003750562 -0.0761578 -0.9881846 -0.1330084 0 -0.9805853 -0.1960936 -0.7791401 -0.6268413 0.00327605 0.2039476 -0.06685477 -0.9766964 -0.06123709 -0.9981229 8.18363e-4 -0.2862615 -0.9581055 0.009408712 -0.9276121 -0.3345579 -0.1661536 -0.8683499 -0.4739387 -0.1461187 -0.9814785 -0.1915725 -3.72887e-4 -0.9815879 -0.1910108 -4.0639e-4 -0.9495603 -0.3135846 3.25717e-4 -0.9406878 -0.3392723 -9.5256e-4 -0.9022697 -0.4311717 7.27118e-4 -0.8777694 -0.479082 -0.001205801 -0.8547229 -0.5190847 8.59986e-5 -0.7942736 -0.6075603 -1.84491e-4 -0.7935859 -0.6084584 -1.15113e-4 6.15052e-4 -0.06807857 -0.9976798 -1.97109e-4 -0.680881 -0.732394 0 -0.6793107 -0.7338509 -0.02537733 -0.9996744 0.002670288 -0.001063525 -0.9999607 0.00880891 0 -0.9998636 0.01651448 3.61076e-7 -0.9439413 -0.3301134 0 -0.9439417 -0.3301122 -0.2643494 -0.910363 -0.3183687 -0.2987821 -0.9195772 -0.2551611 -0.3674415 -0.8326583 -0.4143273 -0.6406548 -0.6902621 -0.3363029 -0.6957071 -0.5980561 -0.3978953 -0.7056724 -0.7056935 -0.06342935 -0.6937651 -0.7186921 -0.04660135 -0.8860521 -0.4515488 -0.1049545 -0.9488672 -0.3041971 -0.08435231 -0.9363663 -0.3401591 -0.0866605 -0.9682372 -0.2117811 -0.1329126 -0.9645293 -0.2491763 -0.08714658 -0.9875419 -0.1563731 -0.01756435 -0.9679518 -0.246127 0.04990941 -0.3089751 -0.9509404 0.01570671 -0.198183 -0.9694441 0.1445745 -0.6448025 -0.7615943 -0.06483876 -0.8001385 -0.5924012 -0.09401708 -0.696296 -0.6963099 0.174139 -0.8898327 -0.4534764 0.05056643 -0.997124 -0.07578724 0 -0.9633862 -0.2551158 0.08247965 -0.9818682 -0.1554756 -0.1084543 -0.9949239 -0.04385644 0.09057188 -0.9958863 -0.02453488 0.08722692 -0.9956572 -7.38399e-4 0.09309339 -0.9956631 4.52381e-4 0.09303241 -0.9959366 0.0107811 0.08941024 -0.9960593 0.001133799 0.08868205 -0.9959635 -0.004226863 0.08966004 -0.01575094 -0.8173039 0.5759916 -7.33479e-5 -0.8191851 0.5735293 1.94956e-4 -0.8191721 0.5735478 7.28531e-5 -0.8191405 0.5735931 -1.65615e-4 -0.8191556 0.5735715 1.56803e-4 -0.8191463 0.5735847 -6.61529e-6 0 1 3.97887e-6 0 1 5.28629e-6 0 1 1.02034e-5 3.75648e-6 1 5.30588e-6 -1.00653e-6 1 -0.1068651 0.9942736 2.0964e-4 -0.1069134 0.9942683 5.09699e-4 -0.1030966 0.9946714 3.56481e-4 -0.3150224 0.9490842 3.34396e-4 -0.3056117 0.9521557 0.001143276 -0.5463944 0.837528 3.73921e-4 -0.4953166 0.8686912 0.006083488 -0.7338324 0.6793301 8.80197e-4 -0.6644177 0.7473306 0.006805062 -0.296597 -0.7686298 0.566779 -0.6224273 -0.6222412 0.4747633 -0.8412539 -0.4173478 0.3436754 -0.9744503 -0.1509977 0.1662719 -0.1846795 -0.8215659 0.5393727 -0.5279394 -0.7479178 0.4023666 -0.5158854 -0.7478268 0.4178726 -0.7934526 -0.569522 0.2146568 -0.7799017 -0.5772125 0.2420315 -0.9485962 -0.3164871 -0.001140654 -0.1372181 -0.8406397 0.5239238 -0.162445 -0.8501812 0.5008029 -0.4661837 -0.828212 0.3110271 -0.4605458 -0.8305534 0.3131752 -1 -3.27641e-7 0 -1 1.49267e-7 0 -1 2.48264e-7 0 -1 -1.71391e-7 0 -1 0 0 -1 1.44991e-7 0 -1 3.21019e-7 0 -1 -8.14166e-7 0 -0.1564131 0.9876128 -0.01248794 -0.4346013 0.9005851 0.0082677 -0.4539496 0.8909162 0.01408469 -0.5690831 0.8222705 -0.003977894 -0.7353002 0.6776565 0.01073616 -0.7071006 0.7071106 0.001847326 -0.8827075 0.4699193 -0.001843154 -0.8910149 0.4539722 0.001343846 -0.9862865 0.1650364 -0.00141704 -0.9876932 0.1564038 0 0.6346035 -0.6656314 0.3927003 0.6343637 -0.6651783 0.3938536 0.7256048 -0.5202691 0.4503529 0.6853549 -0.4746962 0.5522248 0.7261381 -0.3966333 0.5616099 0.6847252 -0.3325186 0.6485236 0.7261522 -0.2502147 0.6403871 0.684234 -0.1725227 0.7085618 0.7266325 -0.08899724 0.6812376 0.6841402 -0.001841425 0.7293482 0.7266234 0.07718521 0.6826865 0.684294 0.1679532 0.709601 0.7334364 0.2502648 0.6320117 0.6819126 0.3307781 0.6523658 0.502461 0.4216653 0.7548056 0.7961958 -0.4574593 0.395984 0.7114854 -0.405374 0.5739865 0.7729598 -0.339695 0.535855 0.7397748 -0.2448716 0.6267147 0.7753537 -0.2103731 0.5954577 0.7524687 -0.08531767 0.6530787 0.7789666 -0.06405907 0.6237848 0.7529864 0.07392728 0.6538702 0.7780252 0.08772855 0.6220777 0.7561592 0.1972671 0.6239464 0.6642833 0.2647737 0.6990155 0.2497181 -0.786834 0.5643876 0.1361342 -0.87777 0.4593336 0.1179847 -0.8491773 0.51476 -0.06009161 -0.9898787 0.1285665 0.2388814 -0.9559645 0.1704926 0.2705117 -0.8407834 0.4689423 0.4960436 -0.8349499 0.2383263 0.5027434 -0.7962702 0.3364564 0.3669498 -0.7460848 0.5556125 0.5114145 -0.5786386 0.6353209 0.4721146 -0.574646 0.6684982 0.499365 -0.4221509 0.7565867 0.557468 -0.3787819 0.7387515 0.467388 -0.2885296 0.835643 0.5712579 -0.1941712 0.7974724 0.470137 -0.135616 0.8721122 0.5081035 0.0200926 0.8610617 0.5529832 -0.002104103 0.8331898 0.5023533 0.1719196 0.8473989 0.5563976 0.1913799 0.8085762 0.4892705 0.295656 0.8204889 0.3715515 0.4414342 0.816753 0.49467 0.4209045 0.7603559 -0.07970446 -0.9373559 0.339133 -0.06820148 -0.9593552 0.273836 -0.2180658 -0.9505538 0.2211221 -0.06791192 -0.9850595 0.1582584 1.22344e-7 -0.9998733 0.01592624 -0.03964042 -0.9515368 0.3049697 0.01193594 0.5242769 0.8514643 0 -0.8595678 -0.5110219 0 -0.8595682 -0.5110211 -0.9614171 -0.2748471 0.01167583 -0.3011589 -0.9535403 0.008015394 -0.3447172 -0.9378608 0.03983944 -0.6970722 -0.716355 0.03043007 -0.228857 -0.9397178 -0.2540769 -0.9670111 -0.2459016 -0.06649869 -0.9501139 -0.2680299 -0.1595109 -0.9456332 -0.2755073 -0.1728396 -0.9555607 -0.2514765 -0.153829 -0.6997743 -0.6577793 -0.2786435 -0.3700652 -0.8383296 -0.4003189 -0.6401704 -0.6925287 -0.3325446 -0.2765077 -0.8260547 -0.4910978 -0.9961526 0.05446982 0.0686528 -0.9888867 0.1322932 0.0678364 -0.9675799 0.2492844 0.04057806 -0.9311121 0.3611149 0.05125027 -0.7583342 0.6513999 0.02464699 -0.8359994 0.5485509 0.01403707 -0.18465 -0.806416 0.5617807 -0.530295 -0.6873696 0.4962966 -0.8020793 -0.4715605 0.3664692 -0.963866 -0.1912884 0.1853947 0.9638656 -0.1912895 0.1853953 0.8020799 -0.4715595 0.3664695 0.5302944 -0.6873704 0.4962961 0.1846542 -0.8077426 0.5598704 0.8359994 0.5485509 0.01403719 0.7583346 0.6513995 0.02464705 0.9311118 0.3611155 0.05125021 0.9675799 0.2492844 0.04057806 0.9888867 0.1322932 0.0678364 0.9961526 0.05446982 0.0686528 0.2765077 -0.8260549 -0.4910978 0.6401702 -0.6925289 -0.3325447 0.3700652 -0.8383296 -0.400319 0.6997752 -0.657779 -0.2786424 0.9301458 -0.3218536 -0.1767461 0.9642388 -0.2405658 -0.1112284 0.9501128 -0.2680328 -0.1595125 0.9670118 -0.2458992 -0.06649732 0.228857 -0.9397178 -0.2540769 0.6970718 -0.7163553 0.03043007 0.3447174 -0.9378608 0.03983944 0.3011589 -0.9535403 0.008015394 0.9614166 -0.2748488 0.01167595 0.9576529 -0.2879158 0.00237745 0.6970752 -0.716352 0.03043174 0.967521 -0.2428941 0.07004094 0.9670205 0.2337284 0.1012044 0.4446899 0.8727459 0.2014088 0.1500748 0.9475701 0.2821143 0.4295781 0.8946611 0.1226551 0.9671238 0.2330853 0.1016999 0.8868406 0.4518455 0.09669333 0.6936243 0.6936354 0.1943072 0.987467 0.1563664 0.02141278 -0.04305464 0.5389091 0.8412629 0.03964042 -0.9515368 0.3049698 0.05119282 -0.9910536 0.1232563 0.06791192 -0.9850594 0.158259 0.06820148 -0.9593553 0.2738358 0.07970434 -0.9373562 0.3391324 -0.4944111 0.3995135 0.7719758 -0.3278042 0.4368091 0.8377007 -0.5563971 0.1913798 0.8085765 -0.4892702 0.2956563 0.8204888 -0.5023529 0.1719195 0.8473991 -0.5529828 -0.002103567 0.83319 -0.5081031 0.02009284 0.861062 -0.4701366 -0.1356163 0.8721123 -0.5712574 -0.1941713 0.7974725 -0.4673875 -0.2885295 0.8356433 -0.5574677 -0.3787821 0.7387516 -0.4993646 -0.4221506 0.756587 -0.4721148 -0.5746454 0.6684985 -0.5114136 -0.5786392 0.6353211 -0.3368144 -0.7837018 0.5218885 -0.2817511 -0.7551178 0.5919574 -0.5027431 -0.7962704 0.3364561 -0.4960439 -0.8349497 0.2383264 -0.2705125 -0.8407831 0.4689424 -0.2388828 -0.9559639 0.1704936 0.06009149 -0.9898787 0.1285663 -0.1179835 -0.8491775 0.5147596 -0.1361332 -0.8777707 0.4593325 -0.6642834 0.2647733 0.6990156 -0.7561591 0.1972678 0.6239462 -0.778027 0.0877276 0.6220756 -0.7529881 0.0739271 0.6538685 -0.7789637 -0.06405752 0.6237888 -0.7524677 -0.0853188 0.6530798 -0.7753523 -0.2103767 0.5954583 -0.7397738 -0.2448713 0.6267158 -0.7729594 -0.3396948 0.5358557 -0.7114849 -0.4053757 0.5739861 -0.7961947 -0.4574616 0.3959835 -0.5505176 0.4006057 0.7324244 -0.6819129 0.3307773 0.6523658 -0.7334365 0.2502648 0.6320114 -0.6842941 0.1679532 0.7096008 -0.7266237 0.07718527 0.6826863 -0.6841405 -0.001841425 0.729348 -0.7266328 -0.0889967 0.6812375 -0.6842341 -0.1725233 0.7085615 -0.7261526 -0.2502136 0.6403871 -0.6847253 -0.3325192 0.6485232 -0.7261384 -0.3966323 0.5616102 -0.6853551 -0.4746963 0.5522244 -0.7256049 -0.5202692 0.4503527 -0.6343642 -0.6651779 0.3938534 -0.6346035 -0.6656314 0.3927003 0.9876933 0.1564036 0 0.9862866 0.1650358 -0.001416981 0.8910146 0.4539728 0.001344025 0.8827075 0.4699192 -0.001843273 0.7071001 0.7071111 0.001847326 0.7352903 0.6776674 0.01073312 0.5690906 0.8222653 -0.003979146 0.4539485 0.8909167 0.01408487 0.4346037 0.9005839 0.008266985 0.1564134 0.9876128 -0.01248848 1 0 0 1 -1.71391e-7 0 1 2.48264e-7 0 1 0 0 1 -1.47623e-7 0 1 0 0 0.1527272 -0.8661755 0.4758303 0.411724 -0.8735874 0.2594773 0.4326195 -0.8665274 0.2489391 0.1476478 -0.8632179 0.4827578 0.4605485 -0.8305523 0.3131741 0.4661831 -0.8282123 0.3110268 0.1624466 -0.8501803 0.5008039 0.7143128 -0.6942068 0.08851093 0.6784824 -0.7253223 0.1164875 0.1372244 -0.8406382 0.5239247 0.948596 -0.3164879 -0.00113976 0.7950698 -0.5624948 0.2268564 0.7763164 -0.5863091 0.2314618 0.5158879 -0.7478256 0.4178716 0.527939 -0.7479184 0.4023663 0.1846798 -0.8215655 0.5393733 0.9744503 -0.1509977 0.1662721 0.8412534 -0.4173489 0.3436753 0.6224266 -0.6222422 0.4747628 0.3302499 -0.7603887 0.5592354 0.6644177 0.7473306 0.006805062 0.7338306 0.679332 8.80194e-4 0.4953174 0.8686909 0.006083488 0.5463951 0.8375276 3.74015e-4 0.3056114 0.9521557 0.001143276 0.3150226 0.9490841 3.34396e-4 0.1030967 0.9946714 3.56481e-4 0.106913 0.9942683 5.09697e-4 0.1068677 0.9942733 2.09532e-4 0.9425719 -0.3322927 0.03376209 -4.4235e-6 -2.76735e-6 1 -8.16281e-6 3.75661e-6 1 -1.45466e-5 0 1 6.6153e-6 0 1 -1.56803e-4 -0.8191462 0.5735849 1.56899e-4 -0.8191552 0.573572 -7.28531e-5 -0.8191406 0.573593 -1.94956e-4 -0.8191713 0.573549 8.0016e-5 -0.8191846 0.57353 0.03477114 -0.8147392 0.5787841 0.9959636 -0.004223585 0.08965963 0.9960593 0.001132488 0.08868187 0.9959366 0.0107811 0.08941 0.9956631 4.5143e-4 0.09303247 0.9956572 -7.37124e-4 0.09309339 0.9958863 -0.02453488 0.08722692 0.9949239 -0.04385644 0.09057176 0.997124 -0.07578748 0 0.9818683 -0.1554756 -0.1084535 0.9633866 -0.2551149 0.08247941 0.889832 -0.4534776 0.05056697 0.696296 -0.6963099 0.174139 0.8001399 -0.5923995 -0.09401661 0.6448025 -0.7615943 -0.06483846 0.198183 -0.9694438 0.144576 0.308975 -0.9509405 0.01570665 0.9581708 -0.2853796 0.02161431 0.987263 -0.1563284 -0.02954876 0.9645317 -0.24916 -0.08716541 0.9682373 -0.2117806 -0.1329123 0.9652741 -0.2281593 -0.1272372 0.9256566 -0.353999 -0.1335835 0.8860517 -0.4515495 -0.1049548 0.6937648 -0.7186924 -0.04660135 0.7056724 -0.7056935 -0.06342977 0.6957064 -0.5980572 -0.3978949 0.6406549 -0.6902615 -0.3363041 0.367438 -0.8326594 -0.4143279 0.2987847 -0.9195762 -0.2551612 0.2643498 -0.9103623 -0.3183706 -1 2.90123e-5 2.78094e-5 -1 -4.4189e-4 2.62927e-4 -1 -1.38492e-7 0 -1 -1.58385e-7 0 -1 0 0 1 8.91887e-7 8.19071e-7 1 -1.24747e-5 7.74399e-6 1 -1.38492e-7 0 1 5.2267e-6 -4.04457e-6 1 1.09494e-6 8.06749e-7 1 1.09802e-6 3.49152e-7 1 1.27165e-6 4.26484e-7 -1 2.27269e-7 0 -1 -9.08496e-7 0 1 -2.27097e-7 0 1 2.27055e-7 0 1 -2.83898e-7 0 1 3.12296e-7 0 1 3.40752e-7 0 1 -4.54071e-7 0 1 -2.27061e-7 0 1 2.27271e-7 0 1 -2.27071e-7 0 1 2.27379e-7 0 1 7.61596e-7 0 1 -1.84397e-7 0 0.4549254 -0.6984828 -0.5524172 0.4557287 -0.6985597 -0.5516573 0.6262539 -0.6583629 -0.4175698 0.5960876 -0.6730796 -0.4377711 0.3981733 -0.7671643 -0.5029087 -0.439383 -0.7140334 -0.5450678 -0.6032525 -0.7104871 -0.3623459 -0.5141074 -0.7391632 -0.4351224 -0.4555376 -0.7592567 -0.464774 -0.3995009 -0.7813888 -0.4794068 -0.006338238 -0.890147 -0.4556294 -5.03807e-5 -0.876552 -0.4813073 0 -0.8191362 0.5735992 -1.98697e-4 -0.8191915 0.57352 1.46803e-4 -0.8191221 0.5736192 -1.40351e-4 -0.8191577 0.5735684 1.99279e-4 -0.8191918 0.5735198 -1.46803e-4 -0.8191223 0.5736191 1.40351e-4 -0.8191579 0.5735681 -0.6818593 0.4655323 -0.564223 -0.6633327 0.3688387 -0.6511127 0.6633325 0.3688394 -0.6511126 0.6818595 0.4655323 -0.5642229 -0.9856256 0.001282632 -0.1689396 0.9858314 0.001277565 -0.1677341 -0.2740227 0.799332 -0.5347709 0.5206381 0.8537723 -0.003012716 0.04209697 -0.5746313 -0.817329 0.119957 -0.674353 -0.7286003 + + + + + + + + + + + + + + +

4 0 5 0 6 0 3 1 0 1 8 1 13 2 21 2 14 2 12 3 13 3 14 3 20 4 21 4 13 4 12 5 15 5 13 5 19 6 18 6 16 6 20 7 18 7 21 7 19 8 17 8 18 8 18 9 17 9 21 9 30 10 31 10 32 10 33 11 30 11 32 11 44 12 45 12 1 12 2 13 1 13 45 13 45 14 46 14 2 14 2 15 46 15 47 15 48 16 2 16 47 16 47 17 49 17 48 17 50 18 48 18 49 18 50 19 49 19 51 19 52 20 50 20 51 20 52 21 51 21 53 21 3 22 52 22 53 22 60 23 63 23 62 23 64 24 63 24 60 24 59 25 64 25 60 25 65 26 62 26 63 26 66 27 67 27 65 27 63 28 66 28 65 28 66 29 63 29 64 29 64 30 48 30 50 30 68 31 64 31 50 31 64 32 68 32 66 32 69 33 67 33 66 33 50 34 52 34 68 34 70 35 66 35 68 35 68 36 52 36 3 36 68 37 3 37 72 37 68 38 72 38 70 38 73 39 70 39 72 39 74 40 75 40 43 40 42 41 74 41 43 41 4 42 75 42 74 42 74 43 76 43 4 43 4 44 6 44 77 44 77 45 78 45 35 45 78 46 79 46 35 46 81 47 30 47 33 47 33 48 41 48 81 48 82 49 81 49 41 49 41 50 40 50 82 50 83 51 8 51 84 51 38 52 0 52 3 52 83 53 3 53 8 53 82 54 40 54 39 54 82 55 39 55 38 55 9 56 3 56 83 56 72 57 3 57 9 57 9 58 85 58 72 58 85 59 86 59 72 59 73 60 72 60 86 60 61 61 62 61 65 61 65 61 67 61 61 61 67 61 69 61 58 61 56 61 58 61 69 61 69 61 71 61 56 61 57 61 56 61 71 61 71 61 70 61 57 61 54 61 57 61 70 61 70 61 73 61 54 61 55 62 54 62 73 62 73 63 86 63 55 63 80 64 55 64 86 64 86 65 85 65 80 65 85 66 9 66 80 66 80 67 9 67 10 67 9 68 83 68 10 68 83 69 84 69 10 69 87 70 84 70 8 70 8 71 0 71 87 71 37 72 38 72 39 72 82 73 38 73 53 73 38 74 3 74 53 74 59 75 2 75 64 75 48 76 64 76 2 76 131 77 28 77 115 77 120 78 115 78 22 78 141 79 126 79 29 79 95 80 126 80 141 80 92 81 89 81 26 81 94 82 24 82 93 82 25 82 24 82 94 82 91 83 24 83 25 83 27 84 24 84 91 84 90 85 27 85 91 85 27 86 90 86 97 86 90 82 124 82 97 82 124 82 90 82 125 82 109 82 125 82 90 82 125 82 109 82 122 82 108 82 122 82 109 82 122 82 108 82 123 82 110 82 123 82 108 82 123 82 110 82 121 82 112 82 121 82 110 82 114 82 118 82 112 82 118 82 114 82 117 82 91 87 107 87 90 87 107 88 91 88 25 88 107 89 25 89 29 89 25 90 94 90 29 90 95 91 141 91 140 91 94 92 92 92 29 92 29 93 92 93 26 93 29 94 26 94 141 94 94 95 93 95 92 95 95 96 139 96 96 96 138 97 96 97 139 97 138 98 149 98 96 98 99 99 145 99 98 99 100 100 145 100 99 100 104 101 100 101 101 101 104 102 101 102 102 102 106 103 104 103 103 103 104 104 106 104 105 104 137 105 136 105 106 105 106 106 136 106 105 106 90 107 107 107 109 107 111 108 109 108 107 108 111 109 107 109 29 109 111 110 29 110 127 110 109 111 111 111 113 111 129 112 111 112 127 112 110 113 113 113 112 113 115 114 113 114 111 114 111 115 129 115 115 115 115 116 129 116 131 116 113 117 115 117 116 117 116 118 114 118 113 118 113 119 114 119 112 119 114 120 116 120 117 120 120 121 119 121 115 121 115 122 119 122 116 122 119 123 117 123 116 123 29 124 126 124 127 124 127 125 126 125 128 125 127 126 128 126 129 126 129 127 128 127 130 127 129 128 130 128 131 128 132 129 131 129 130 129 131 130 132 130 28 130 28 131 132 131 133 131 134 132 22 132 133 132 133 133 22 133 28 133 135 134 22 134 134 134 147 135 149 135 138 135 149 10 147 10 148 10 142 136 144 136 143 136 31 10 146 10 148 10 30 10 146 10 31 10 146 137 149 137 148 137 150 138 151 138 152 138 146 10 153 10 162 10 146 10 162 10 157 10 164 139 163 139 162 139 190 140 188 140 189 140 176 141 190 141 175 141 188 142 169 142 167 142 191 143 169 143 188 143 188 144 190 144 191 144 192 145 176 145 177 145 190 146 176 146 192 146 192 147 191 147 190 147 169 148 191 148 171 148 178 149 192 149 177 149 191 150 173 150 171 150 193 151 173 151 191 151 191 152 192 152 193 152 194 153 193 153 192 153 194 154 178 154 179 154 192 155 178 155 194 155 173 156 193 156 174 156 180 157 194 157 179 157 193 158 194 158 195 158 193 159 172 159 174 159 195 160 172 160 193 160 194 161 180 161 196 161 196 162 195 162 194 162 181 163 196 163 180 163 172 164 195 164 170 164 195 165 196 165 197 165 197 166 170 166 195 166 198 167 197 167 196 167 198 168 181 168 182 168 196 169 181 169 198 169 183 170 198 170 182 170 170 171 197 171 168 171 197 172 198 172 199 172 197 173 166 173 168 173 199 174 166 174 197 174 200 175 199 175 198 175 200 176 183 176 184 176 198 177 183 177 200 177 185 178 200 178 184 178 203 179 242 179 244 179 203 180 201 180 202 180 240 181 242 181 203 181 218 182 219 182 202 182 204 183 202 183 220 183 202 184 219 184 220 184 202 185 204 185 203 185 203 186 205 186 240 186 205 187 238 187 240 187 205 188 203 188 204 188 235 189 238 189 205 189 220 190 221 190 204 190 206 191 204 191 222 191 204 192 221 192 222 192 204 193 206 193 205 193 205 194 207 194 235 194 207 195 205 195 206 195 233 196 235 196 207 196 222 197 223 197 206 197 206 198 208 198 207 198 208 199 206 199 223 199 207 200 209 200 233 200 209 201 231 201 233 201 209 202 207 202 208 202 223 203 224 203 208 203 232 204 231 204 209 204 210 205 208 205 225 205 208 206 224 206 225 206 208 207 210 207 209 207 211 208 209 208 210 208 209 209 211 209 232 209 211 210 234 210 232 210 225 211 226 211 210 211 236 212 234 212 211 212 210 213 212 213 211 213 212 214 210 214 227 214 210 215 226 215 227 215 214 216 211 216 212 216 211 217 214 217 236 217 214 218 239 218 236 218 227 219 228 219 212 219 241 220 239 220 214 220 212 221 213 221 214 221 213 222 212 222 230 222 212 223 245 223 230 223 212 224 228 224 245 224 214 225 215 225 241 225 214 226 213 226 215 226 243 227 241 227 229 227 241 228 215 228 229 228 187 229 186 229 216 229 217 230 216 230 186 230 186 231 185 231 217 231 218 232 217 232 185 232 185 233 184 233 218 233 219 234 218 234 184 234 184 235 183 235 219 235 220 236 219 236 183 236 183 237 182 237 220 237 221 238 220 238 182 238 182 239 181 239 221 239 222 240 221 240 181 240 181 241 180 241 222 241 223 242 222 242 180 242 180 243 179 243 223 243 224 243 223 243 179 243 179 244 178 244 224 244 225 245 224 245 178 245 178 246 177 246 225 246 226 247 225 247 177 247 177 248 176 248 226 248 227 248 226 248 176 248 176 249 175 249 227 249 228 250 227 250 175 250 175 251 164 251 228 251 245 252 228 252 164 252 240 82 238 82 237 82 242 82 240 82 237 82 241 82 243 82 237 82 244 253 242 253 237 253 245 139 164 139 162 139 162 139 246 139 245 139 296 254 266 254 287 254 296 255 287 255 158 255 249 256 253 256 248 256 253 257 255 257 254 257 253 258 249 258 255 258 250 259 255 259 249 259 254 260 255 260 256 260 257 261 250 261 135 261 255 262 250 262 257 262 257 263 256 263 255 263 256 264 257 264 258 264 134 265 257 265 135 265 259 266 258 266 257 266 257 267 134 267 259 267 133 268 259 268 134 268 258 269 259 269 260 269 261 270 260 270 259 270 259 271 133 271 261 271 132 272 261 272 133 272 260 273 261 273 262 273 261 274 263 274 262 274 264 275 263 275 261 275 264 276 132 276 130 276 261 277 132 277 264 277 266 278 265 278 267 278 268 279 270 279 269 279 268 280 320 280 270 280 265 281 320 281 268 281 268 282 267 282 265 282 271 283 268 283 269 283 267 284 268 284 272 284 273 285 271 285 288 285 268 286 271 286 273 286 268 287 274 287 272 287 273 288 274 288 268 288 275 289 273 289 288 289 274 290 273 290 276 290 273 291 277 291 276 291 273 292 278 292 277 292 273 293 275 293 278 293 253 294 277 294 278 294 283 295 274 295 276 295 284 296 274 296 283 296 161 297 285 297 279 297 274 298 284 298 272 298 284 299 285 299 272 299 286 300 272 300 285 300 285 301 161 301 286 301 160 302 286 302 161 302 272 303 286 303 267 303 287 304 160 304 159 304 286 305 160 305 287 305 287 306 267 306 286 306 158 307 287 307 159 307 267 308 287 308 266 308 270 309 21 309 17 309 320 310 21 310 270 310 269 311 17 311 19 311 269 312 270 312 17 312 275 313 289 313 290 313 288 314 289 314 275 314 291 315 275 315 290 315 288 316 16 316 289 316 271 317 16 317 288 317 271 318 19 318 16 318 269 319 19 319 271 319 128 320 126 320 252 320 130 321 128 321 252 321 130 322 252 322 264 322 252 323 263 323 264 323 251 324 263 324 252 324 247 325 275 325 291 325 247 326 278 326 275 326 247 327 248 327 278 327 248 328 253 328 278 328 149 10 146 10 157 10 149 329 157 329 280 329 149 330 280 330 96 330 96 331 280 331 281 331 96 332 281 332 95 332 95 333 281 333 282 333 126 334 95 334 282 334 126 335 282 335 251 335 126 336 251 336 252 336 53 337 333 337 334 337 53 338 334 338 303 338 53 339 303 339 82 339 82 340 303 340 304 340 81 341 82 341 304 341 81 342 304 342 305 342 30 343 81 343 305 343 30 344 305 344 153 344 30 10 153 10 146 10 337 345 309 345 332 345 338 346 309 346 337 346 338 347 311 347 309 347 338 348 292 348 311 348 334 349 333 349 322 349 333 350 321 350 322 350 49 351 321 351 333 351 49 352 333 352 51 352 51 353 333 353 53 353 317 354 315 354 12 354 315 355 15 355 12 355 315 356 295 356 15 356 295 357 294 357 15 357 292 358 293 358 311 358 295 359 311 359 294 359 311 360 293 360 294 360 317 361 14 361 316 361 317 362 12 362 14 362 320 363 316 363 21 363 316 364 14 364 21 364 319 365 266 365 296 365 158 366 156 366 296 366 296 367 297 367 319 367 297 368 296 368 155 368 296 369 156 369 155 369 314 370 319 370 297 370 155 371 154 371 297 371 298 372 297 372 154 372 297 373 298 373 314 373 299 374 314 374 298 374 312 375 314 375 299 375 154 376 307 376 298 376 300 377 298 377 307 377 298 378 300 378 299 378 299 379 301 379 312 379 301 380 310 380 312 380 301 381 299 381 300 381 307 382 308 382 300 382 306 383 310 383 302 383 310 384 301 384 302 384 331 385 332 385 306 385 332 386 309 386 306 386 313 387 309 387 311 387 309 388 313 388 306 388 313 389 310 389 306 389 312 390 310 390 313 390 311 391 295 391 313 391 313 392 318 392 312 392 318 393 314 393 312 393 318 394 313 394 315 394 313 395 295 395 315 395 319 396 314 396 318 396 315 397 317 397 318 397 318 398 265 398 319 398 265 399 318 399 320 399 318 400 316 400 320 400 318 401 317 401 316 401 266 402 319 402 265 402 324 403 321 403 47 403 321 404 49 404 47 404 321 405 324 405 322 405 324 406 323 406 322 406 325 407 323 407 324 407 47 408 46 408 324 408 326 409 324 409 46 409 324 410 326 410 325 410 327 411 325 411 326 411 46 412 45 412 326 412 328 413 326 413 45 413 326 414 328 414 327 414 45 415 44 415 328 415 329 416 327 416 328 416 328 417 330 417 329 417 330 418 328 418 335 418 328 419 44 419 335 419 331 420 329 420 330 420 335 421 336 421 330 421 332 422 330 422 336 422 330 423 332 423 331 423 336 424 337 424 332 424 349 425 339 425 148 425 148 426 339 426 31 426 31 427 339 427 370 427 339 428 349 428 346 428 370 429 339 429 346 429 374 430 340 430 144 430 341 10 88 10 342 10 343 431 357 431 344 431 343 432 342 432 357 432 341 10 342 10 343 10 343 433 344 433 345 433 345 10 347 10 346 10 344 434 347 434 345 434 343 435 348 435 341 435 138 436 348 436 147 436 349 437 147 437 348 437 349 438 343 438 345 438 348 439 343 439 349 439 147 440 349 440 148 440 346 441 349 441 345 441 359 442 102 442 358 442 354 443 144 443 340 443 351 444 356 444 355 444 357 445 342 445 356 445 356 446 351 446 357 446 344 447 357 447 351 447 362 448 363 448 365 448 364 449 367 449 363 449 365 450 363 450 367 450 366 451 374 451 34 451 5 452 360 452 361 452 351 453 355 453 367 453 367 454 364 454 351 454 344 455 351 455 364 455 346 456 372 456 370 456 32 457 31 457 370 457 371 458 370 458 373 458 370 459 372 459 373 459 370 460 371 460 32 460 33 461 32 461 371 461 373 462 37 462 371 462 344 463 364 463 347 463 364 464 372 464 347 464 372 10 346 10 347 10 373 465 372 465 364 465 37 10 373 10 362 10 373 10 363 10 362 10 373 466 364 466 363 466 37 10 362 10 36 10 355 467 356 467 352 467 368 468 352 468 350 468 34 469 144 469 142 469 341 470 26 470 88 470 141 471 26 471 341 471 104 472 102 472 103 472 101 473 358 473 102 473 358 474 101 474 380 474 100 475 380 475 101 475 380 476 100 476 379 476 99 477 379 477 100 477 379 478 99 478 23 478 98 479 23 479 99 479 23 480 98 480 353 480 375 481 353 481 98 481 353 482 375 482 354 482 354 483 375 483 144 483 93 484 89 484 92 484 88 485 26 485 89 485 350 486 377 486 378 486 350 487 378 487 359 487 358 488 350 488 359 488 380 489 350 489 358 489 376 490 377 490 350 490 376 491 350 491 352 491 88 492 376 492 342 492 341 493 348 493 139 493 348 494 138 494 139 494 341 495 140 495 141 495 376 496 352 496 356 496 356 497 342 497 376 497 365 498 389 498 362 498 389 499 365 499 385 499 37 500 39 500 40 500 37 501 40 501 41 501 371 502 41 502 33 502 37 503 41 503 371 503 36 504 362 504 389 504 389 505 385 505 369 505 369 506 385 506 386 506 389 507 369 507 388 507 381 508 361 508 369 508 361 509 360 509 369 509 369 510 360 510 387 510 369 511 387 511 388 511 87 512 0 512 36 512 34 513 390 513 366 513 383 514 366 514 390 514 390 515 79 515 383 515 11 516 383 516 79 516 79 517 78 517 11 517 384 518 11 518 78 518 78 519 77 519 384 519 381 520 384 520 77 520 77 521 6 521 381 521 361 522 381 522 6 522 6 523 5 523 361 523 4 524 76 524 5 524 368 525 350 525 369 525 369 526 386 526 368 526 37 527 0 527 38 527 36 10 0 10 37 10 34 430 374 430 144 430 352 528 368 528 355 528 54 529 55 529 393 529 393 530 394 530 54 530 393 531 391 531 394 531 395 532 54 532 394 532 395 533 56 533 57 533 54 534 395 534 57 534 58 535 56 535 395 535 59 536 394 536 392 536 394 537 59 537 395 537 60 538 61 538 58 538 395 539 60 539 58 539 60 540 395 540 59 540 62 541 61 541 60 541 55 542 80 542 393 542 58 61 61 61 67 61 7 61 80 61 10 61 393 543 80 543 7 543 393 544 74 544 42 544 74 545 393 545 7 545 106 546 27 546 398 546 398 547 137 547 106 547 121 82 112 82 118 82 97 548 398 548 27 548 398 549 97 549 124 549 117 550 119 550 118 550 119 551 120 551 396 551 396 552 121 552 119 552 119 553 121 553 118 553 397 554 396 554 120 554 120 555 399 555 397 555 121 556 396 556 123 556 125 557 122 557 396 557 396 558 122 558 123 558 396 559 397 559 125 559 397 560 400 560 398 560 398 561 125 561 397 561 125 562 398 562 124 562 34 563 142 563 403 563 375 564 145 564 144 564 143 565 144 565 145 565 137 566 247 566 136 566 400 567 247 567 137 567 400 568 248 568 247 568 401 569 248 569 400 569 248 570 401 570 249 570 399 571 249 571 401 571 249 572 399 572 250 572 399 573 135 573 250 573 22 574 135 574 399 574 400 575 397 575 401 575 397 576 399 576 401 576 145 577 100 577 104 577 145 578 375 578 98 578 103 82 24 82 27 82 247 579 291 579 136 579 143 580 20 580 142 580 18 581 20 581 143 581 136 582 291 582 105 582 105 583 291 583 290 583 105 584 290 584 104 584 104 585 290 585 289 585 145 586 104 586 289 586 145 587 289 587 16 587 145 588 18 588 143 588 145 589 16 589 18 589 399 590 120 590 22 590 400 591 137 591 398 591 106 592 103 592 27 592 74 593 7 593 76 593 391 594 393 594 42 594 392 595 1 595 59 595 35 596 13 596 15 596 35 597 403 597 13 597 35 598 15 598 294 598 35 599 294 599 4 599 4 600 294 600 293 600 75 601 4 601 293 601 75 602 293 602 292 602 43 603 75 603 292 603 13 604 403 604 20 604 403 605 142 605 20 605 338 606 43 606 292 606 367 607 382 607 365 607 76 61 7 61 10 61 79 608 390 608 35 608 35 609 4 609 77 609 394 610 402 610 392 610 391 611 402 611 394 611 1 612 392 612 44 612 392 613 335 613 44 613 336 614 335 614 392 614 392 615 402 615 336 615 337 616 336 616 402 616 402 617 391 617 337 617 391 618 338 618 337 618 391 619 42 619 338 619 42 620 43 620 338 620 382 621 367 621 355 621 355 622 368 622 382 622 386 623 382 623 368 623 403 624 35 624 34 624 390 625 34 625 35 625 152 626 151 626 547 626 547 627 548 627 152 627 404 628 152 628 548 628 404 629 405 629 152 629 406 630 407 630 152 630 406 631 152 631 405 631 406 632 405 632 408 632 409 633 406 633 408 633 409 634 410 634 407 634 406 635 409 635 407 635 411 636 410 636 409 636 408 637 412 637 409 637 409 638 412 638 413 638 409 639 413 639 414 639 415 640 409 640 414 640 415 641 416 641 411 641 409 642 415 642 411 642 407 643 150 643 152 643 417 644 150 644 407 644 418 645 417 645 407 645 410 646 419 646 418 646 407 647 410 647 418 647 410 648 411 648 419 648 416 649 420 649 421 649 416 650 421 650 419 650 411 651 416 651 419 651 331 652 422 652 329 652 327 653 329 653 422 653 422 654 423 654 327 654 327 655 423 655 424 655 325 656 327 656 424 656 424 657 425 657 325 657 325 658 425 658 426 658 418 659 428 659 427 659 427 660 308 660 418 660 417 661 418 661 308 661 307 662 150 662 417 662 308 663 307 663 417 663 307 664 154 664 150 664 429 665 431 665 430 665 430 666 431 666 432 666 433 667 430 667 432 667 245 668 246 668 433 668 432 669 245 669 433 669 434 670 246 670 153 670 305 671 433 671 434 671 153 672 305 672 434 672 430 673 433 673 305 673 305 674 304 674 430 674 429 675 430 675 304 675 304 676 303 676 429 676 435 677 429 677 303 677 303 678 334 678 435 678 438 679 428 679 439 679 439 680 441 680 440 680 441 681 443 681 442 681 443 682 422 682 331 682 444 683 427 683 438 683 438 684 440 684 444 684 302 685 444 685 440 685 440 686 442 686 302 686 306 687 302 687 442 687 442 688 331 688 306 688 308 689 427 689 444 689 444 690 300 690 308 690 444 691 302 691 301 691 300 692 444 692 301 692 445 693 446 693 447 693 447 82 420 82 445 82 448 694 445 694 420 694 416 695 449 695 448 695 420 696 416 696 448 696 413 82 450 82 237 82 450 697 244 697 237 697 449 698 416 698 415 698 449 699 415 699 414 699 449 700 414 700 413 700 449 82 413 82 237 82 243 82 449 82 237 82 230 701 245 701 451 701 230 702 451 702 452 702 213 703 230 703 452 703 213 704 452 704 453 704 213 705 453 705 454 705 215 706 213 706 454 706 454 707 455 707 215 707 229 708 215 708 455 708 455 709 449 709 229 709 243 710 229 710 449 710 437 711 436 711 456 711 457 712 456 712 436 712 436 713 458 713 457 713 459 714 457 714 458 714 458 715 460 715 459 715 461 716 459 716 460 716 460 717 462 717 461 717 463 718 461 718 462 718 462 719 464 719 463 719 465 720 463 720 464 720 464 721 466 721 465 721 467 722 465 722 466 722 466 723 441 723 467 723 467 724 441 724 439 724 428 725 467 725 439 725 436 726 426 726 458 726 460 727 458 727 426 727 426 728 425 728 460 728 462 729 460 729 425 729 425 730 424 730 462 730 464 731 462 731 424 731 424 732 423 732 464 732 466 733 464 733 423 733 423 734 422 734 466 734 466 735 422 735 443 735 466 736 443 736 441 736 456 737 455 737 454 737 454 738 453 738 456 738 468 739 456 739 453 739 429 740 469 740 431 740 469 741 429 741 435 741 469 742 435 742 437 742 468 743 469 743 437 743 437 744 456 744 468 744 457 745 455 745 456 745 459 746 449 746 455 746 457 747 459 747 455 747 448 748 449 748 459 748 459 749 461 749 448 749 445 750 448 750 461 750 461 751 463 751 445 751 446 752 445 752 463 752 465 753 447 753 446 753 463 754 465 754 446 754 420 755 447 755 465 755 465 756 467 756 420 756 421 757 420 757 467 757 428 758 419 758 421 758 467 759 428 759 421 759 468 760 453 760 452 760 452 761 469 761 468 761 431 762 469 762 432 762 469 763 451 763 245 763 432 764 469 764 245 764 469 765 452 765 451 765 418 766 419 766 428 766 216 767 404 767 187 767 548 768 187 768 404 768 201 769 203 769 244 769 470 770 217 770 218 770 202 771 470 771 218 771 470 772 202 772 201 772 216 773 217 773 470 773 244 774 450 774 201 774 201 775 450 775 413 775 201 776 413 776 412 776 408 777 201 777 412 777 201 778 408 778 470 778 470 779 405 779 216 779 470 780 408 780 405 780 404 781 216 781 405 781 325 782 426 782 323 782 426 783 436 783 323 783 323 784 436 784 322 784 322 785 436 785 437 785 334 786 322 786 437 786 334 787 437 787 435 787 246 10 162 10 153 10 427 788 428 788 438 788 438 789 439 789 440 789 440 790 441 790 442 790 331 791 442 791 443 791 254 792 512 792 513 792 509 793 513 793 514 793 517 794 509 794 515 794 527 795 517 795 516 795 163 10 157 10 162 10 251 796 520 796 518 796 251 797 518 797 263 797 263 798 518 798 519 798 262 799 263 799 519 799 528 800 262 800 519 800 260 801 262 801 528 801 548 802 471 802 187 802 473 803 471 803 472 803 473 804 187 804 471 804 474 805 473 805 472 805 472 806 541 806 474 806 474 807 541 807 540 807 474 808 540 808 502 808 501 809 474 809 502 809 187 810 473 810 186 810 473 811 474 811 200 811 200 812 185 812 473 812 473 813 185 813 186 813 474 814 501 814 199 814 199 815 501 815 499 815 199 816 200 816 474 816 166 817 199 817 499 817 498 818 188 818 167 818 189 819 497 819 190 819 190 820 497 820 164 820 190 821 164 821 175 821 188 822 498 822 475 822 475 823 493 823 188 823 188 824 493 824 189 824 500 825 475 825 498 825 535 826 516 826 477 826 476 827 496 827 495 827 523 828 164 828 476 828 476 829 164 829 496 829 495 830 478 830 476 830 478 831 495 831 494 831 480 832 534 832 516 832 516 833 534 833 477 833 482 834 533 834 480 834 480 835 533 835 534 835 533 836 482 836 505 836 484 837 506 837 482 837 482 838 506 838 505 838 506 839 484 839 507 839 486 840 507 840 484 840 507 841 486 841 504 841 488 842 504 842 486 842 504 843 488 843 503 843 490 844 491 844 488 844 488 845 491 845 503 845 491 846 490 846 492 846 490 847 479 847 492 847 518 848 478 848 479 848 478 849 518 849 476 849 476 850 518 850 520 850 476 851 520 851 525 851 525 852 523 852 476 852 478 853 494 853 479 853 492 854 479 854 494 854 481 855 514 855 512 855 481 856 512 856 532 856 531 857 481 857 532 857 481 858 531 858 483 858 530 859 483 859 531 859 483 860 530 860 485 860 529 861 485 861 530 861 485 862 529 862 487 862 528 863 487 863 529 863 487 864 528 864 489 864 519 865 489 865 528 865 516 866 515 866 480 866 480 867 515 867 514 867 481 868 480 868 514 868 480 869 481 869 482 869 483 870 482 870 481 870 482 871 483 871 484 871 485 872 484 872 483 872 484 873 485 873 486 873 487 874 486 874 485 874 486 875 487 875 488 875 489 876 488 876 487 876 488 877 489 877 490 877 519 878 490 878 489 878 490 879 519 879 479 879 518 880 479 880 519 880 500 881 503 881 475 881 475 882 503 882 491 882 475 883 491 883 493 883 493 884 491 884 492 884 493 885 492 885 189 885 189 886 492 886 494 886 189 887 494 887 495 887 189 888 495 888 497 888 497 889 495 889 496 889 497 890 496 890 164 890 499 61 165 61 166 61 498 891 165 891 500 891 501 61 165 61 499 61 500 61 165 61 503 61 533 892 504 892 538 892 538 893 504 893 503 893 504 894 533 894 507 894 505 895 507 895 533 895 507 896 505 896 506 896 508 897 279 897 285 897 285 898 284 898 508 898 283 899 508 899 284 899 279 900 508 900 526 900 508 901 283 901 511 901 511 902 283 902 510 902 511 903 526 903 508 903 277 904 510 904 276 904 276 905 510 905 283 905 526 906 511 906 527 906 513 907 277 907 254 907 277 908 513 908 509 908 277 909 509 909 510 909 511 910 510 910 509 910 517 911 511 911 509 911 511 912 517 912 527 912 512 913 254 913 532 913 514 914 513 914 512 914 515 915 509 915 514 915 517 916 515 916 516 916 282 917 520 917 251 917 520 918 282 918 525 918 281 919 525 919 282 919 525 920 281 920 524 920 280 921 524 921 281 921 524 922 280 922 522 922 157 923 521 923 280 923 280 924 521 924 522 924 157 925 163 925 521 925 277 926 253 926 254 926 523 927 522 927 164 927 522 928 163 928 164 928 522 929 523 929 524 929 525 930 524 930 523 930 279 931 151 931 161 931 526 932 536 932 279 932 279 933 536 933 151 933 536 934 526 934 535 934 527 935 535 935 526 935 535 936 527 936 516 936 260 937 528 937 529 937 530 938 260 938 529 938 260 939 530 939 258 939 258 940 530 940 531 940 532 941 258 941 531 941 258 942 532 942 256 942 254 943 256 943 532 943 533 944 538 944 534 944 542 945 477 945 538 945 538 946 477 946 534 946 543 947 477 947 542 947 545 948 535 948 543 948 543 949 535 949 477 949 535 950 545 950 536 950 536 951 545 951 151 951 547 952 151 952 545 952 544 953 542 953 537 953 537 954 542 954 538 954 537 955 539 955 544 955 544 956 539 956 540 956 544 957 540 957 541 957 472 958 544 958 541 958 542 959 544 959 543 959 546 960 545 960 544 960 544 961 545 961 543 961 544 962 472 962 546 962 546 963 472 963 471 963 546 964 471 964 547 964 546 965 547 965 545 965 548 966 547 966 471 966 24 82 103 82 102 82 24 967 102 967 359 967 24 968 359 968 378 968 24 969 378 969 377 969 24 970 377 970 376 970 24 971 376 971 88 971 88 82 89 82 24 82 5 61 76 61 10 61 5 972 10 972 360 972 10 973 387 973 360 973 10 974 388 974 387 974 10 975 389 975 388 975 10 976 36 976 389 976 36 977 10 977 87 977 84 978 87 978 10 978 89 82 93 82 24 82 239 979 241 979 237 979 236 82 239 82 237 82 234 82 236 82 237 82 232 82 234 82 237 82 231 980 232 980 237 980 231 82 237 82 233 82 233 82 237 82 235 82 235 82 237 82 238 82 165 981 168 981 166 981 165 61 170 61 168 61 165 982 172 982 170 982 165 983 174 983 172 983 165 984 173 984 174 984 165 985 171 985 173 985 165 986 169 986 171 986 165 987 167 987 169 987 165 988 498 988 167 988 165 989 501 989 502 989 165 990 502 990 540 990 165 61 540 61 539 61 165 61 539 61 537 61 165 991 537 991 538 991 165 992 538 992 503 992 381 993 369 993 384 993 11 994 384 994 369 994 11 995 369 995 383 995 366 996 383 996 369 996 366 997 369 997 374 997 379 998 350 998 380 998 23 999 350 999 379 999 23 1000 353 1000 350 1000 353 1001 354 1001 350 1001 340 1002 350 1002 354 1002 340 1003 369 1003 350 1003 340 1004 374 1004 369 1004 150 1005 158 1005 151 1005 150 1006 156 1006 158 1006 150 1007 155 1007 156 1007 150 1008 154 1008 155 1008 151 1009 158 1009 159 1009 151 1010 159 1010 160 1010 151 1011 160 1011 161 1011 66 1012 70 1012 71 1012 66 1013 71 1013 69 1013 108 1014 113 1014 110 1014 108 1015 109 1015 113 1015 1 1016 2 1016 59 1016 22 1017 115 1017 28 1017 139 1018 140 1018 341 1018 95 1019 140 1019 139 1019 365 1020 382 1020 385 1020 382 1021 386 1021 385 1021

+
+
+
+
+ + + + 0.001 0 0 0 0 7.54979e-11 -0.001 0 0 0.001 7.54979e-11 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E4.dae b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E4.dae new file mode 100644 index 0000000..f590715 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_E4.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:31.855069 + 2012-07-23T02:15:31.855082 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -7.17350 6.94911 4.21838 -9.93270 -1.15879 -0.00031 -9.92969 1.15514 -0.00031 -7.45360 6.66578 -0.00031 -6.19669 -7.61001 14.00068 -5.99999 -7.69760 7.99969 -5.93079 -7.72543 8.52069 -5.99999 -7.62085 -1.45521 -6.53730 7.42476 2.97619 -6.00000 7.62007 -1.44611 -5.99999 -0.00089 -0.00031 -4.99999 3.65198 9.71969 -3.55469 -9.23031 23.11969 -3.56699 -8.61560 18.55868 -1.76899 -9.59040 22.63068 -4.59092 -8.80456 23.59968 4.59459 -8.80456 23.59968 1.77266 -9.59040 22.63068 3.57066 -8.61560 18.55868 3.55836 -9.23031 23.11969 0.00406 -8.84559 18.22268 0.00406 -9.69028 22.44568 9.93636 -1.15879 -0.00031 5.00366 3.81254 9.73169 6.00366 -0.00089 -0.00031 6.00366 7.62007 -1.44611 7.14516 6.97814 3.97919 6.00366 -7.62085 -1.45522 9.93336 1.15514 -0.00031 7.45726 6.66578 -0.00031 -4.47209 7.99911 23.99968 -0.92010 7.99911 10.96068 -2.73450 7.99911 10.65468 -5.10259 7.94911 9.74469 -3.99999 -8.00089 9.99969 -5.00999 -7.96456 14.00168 -6.00000 6.94911 4.50619 -5.64640 6.94911 8.25268 -7.17349 6.94911 6.96669 -7.06460 7.04525 7.66968 -6.70469 7.31810 8.43568 -6.02019 7.68741 9.16469 -7.45360 -6.66756 -0.00031 -7.46809 -6.65131 13.99969 -9.91719 -1.28497 23.99968 -9.99999 -0.02064 23.99968 -9.92209 1.24482 23.99968 -9.68389 2.49335 23.99968 -9.63909 2.66125 -0.00031 -8.93994 4.00025 23.99968 -9.11909 4.10304 -0.00031 -8.39959 5.42557 23.99968 -8.38479 5.44841 -0.00031 -7.47299 6.64398 23.99968 -6.00000 -5.49870 -5.79131 -5.99999 -6.96596 -3.90192 -6.00000 -3.36071 -7.26061 -6.00000 -4.50038 -6.61501 -6.00000 -2.24851 -7.67811 -9.41220 -1.47532 -3.03941 -8.06000 -1.20361 -5.79601 -6.00000 -1.13267 -7.91981 -6.00000 -0.00089 -8.00031 -8.06000 1.20183 -5.79601 -9.41220 1.47352 -3.03941 -6.00000 1.13089 -7.91981 -7.35780 3.50247 -5.79601 -6.00000 2.24673 -7.67811 -8.51050 4.28110 -3.03941 -6.00000 3.35892 -7.26061 -6.00000 5.49692 -5.79131 -6.00000 4.49860 -6.61501 -6.62189 6.66578 -3.42181 -6.00000 6.66577 -4.42251 -6.78489 -7.26453 -0.00031 -6.83189 -7.23065 13.99969 -5.99999 -7.69760 -0.00031 -5.71839 -7.80180 9.02269 -5.38550 -7.89522 9.44169 -4.95869 -7.97119 9.75468 -5.99999 -7.34730 -2.89871 -5.57889 7.84294 23.99968 -6.59929 7.38662 23.99968 -6.00000 7.69581 -0.00031 -6.00000 7.69581 2.18159 -6.00000 7.34767 -2.89111 -6.00000 7.07516 -3.64421 -6.00000 7.31252 3.24219 6.00366 6.94911 4.50619 6.00366 7.31252 3.24219 6.00366 6.66577 -4.42252 6.00366 7.34767 -2.89111 6.66886 7.34083 3.17053 6.00366 7.69581 2.18159 6.00366 7.69581 -0.00031 6.60296 7.38662 23.99968 5.58256 7.84294 23.99968 6.00366 -7.18556 -3.39231 4.96236 -7.97119 9.75468 5.38916 -7.89522 9.44169 5.72206 -7.80180 9.02269 5.93446 -7.72543 8.52069 6.00366 -7.69760 7.99968 6.00366 -7.69760 -0.00031 6.20036 -7.61001 14.00068 6.83556 -7.23065 13.99968 6.78856 -7.26453 -0.00031 6.62556 6.66578 -3.42181 6.00366 4.49860 -6.61501 6.00366 5.49692 -5.79131 6.00366 3.35892 -7.26061 8.51416 4.28110 -3.03941 6.00366 2.24673 -7.67812 7.36146 3.50247 -5.79601 6.00366 1.13089 -7.91981 9.41586 1.47352 -3.03941 8.06366 1.20183 -5.79601 6.00366 -0.00089 -8.00031 6.00366 -1.13267 -7.91981 8.06366 -1.20361 -5.79601 9.41586 -1.47532 -3.03941 6.00366 -2.24851 -7.67812 6.00366 -4.50038 -6.61501 6.00366 -3.36071 -7.26061 6.00366 -6.66755 -4.42252 6.00366 -5.49870 -5.79131 7.47666 6.64398 23.99968 8.38846 5.44841 -0.00031 8.40326 5.42557 23.99968 9.12276 4.10304 -0.00031 8.94361 4.00025 23.99968 9.64276 2.66125 -0.00031 9.68756 2.49335 23.99968 9.92576 1.24482 23.99968 10.00366 -0.02064 23.99968 9.92086 -1.28497 23.99968 7.47176 -6.65131 13.99968 7.45726 -6.66756 -0.00031 5.10626 7.94911 9.74469 6.02386 7.68741 9.16469 7.06826 7.04525 7.66968 7.17716 6.94911 6.96669 0.00406 -8.00089 13.99868 3.58286 -8.00089 13.99868 4.00366 -8.00089 9.99969 5.01366 -7.96456 14.00168 0.00366 7.99911 23.99968 2.73816 7.99911 10.65468 0.92376 7.99911 10.96068 4.47576 7.99911 23.99968 -3.99999 -5.02735 37.82068 4.00366 -5.02735 37.82068 -3.99999 -5.00089 39.42268 -4.48079 7.99911 34.49768 -3.53979 -8.82177 32.40168 -2.34909 -9.28970 31.73368 -1.16229 -9.55490 31.35468 4.48446 7.99911 34.49768 0.00346 -9.63919 31.23468 1.16596 -9.55490 31.35468 2.35276 -9.28970 31.73368 3.54346 -8.82177 32.40168 0.00366 7.99911 44.99968 4.46387 7.99911 44.99968 4.00366 6.94911 44.99968 7.00366 -0.00089 44.99968 7.00366 -3.61239 46.59969 7.00366 3.37761 47.04568 7.00366 -3.04855 47.51268 7.00366 2.70194 47.87968 7.00366 -2.25983 48.23969 7.00366 1.82715 48.50168 7.00366 -1.30441 48.72868 7.00366 0.81734 48.86368 7.00366 -0.25282 48.94168 4.00366 6.69274 46.86967 4.00366 5.94276 48.60168 4.00366 4.75370 50.06868 4.00366 3.21449 51.16068 4.00366 1.43786 51.79867 4.00366 -0.44483 51.93568 4.00366 -2.29479 51.56068 4.00366 -3.97553 50.70068 4.00366 -5.36307 49.42068 4.00366 -6.35507 47.81468 4.00366 -6.87828 46.00168 4.00366 -6.89415 44.11368 4.00366 -6.40153 42.29169 6.60256 4.84007 47.50069 5.76706 6.37616 44.99969 5.50366 5.81689 48.00468 6.60256 3.15259 49.44267 5.50366 3.78892 50.33968 6.60256 0.76172 50.39468 5.50366 0.91560 51.48367 6.60256 -1.79926 50.14268 5.50366 -2.16214 51.18068 6.60256 -3.95910 48.74368 5.50366 -4.75780 49.49968 6.60256 -5.23604 46.50967 5.50366 -6.29241 46.81468 -6.59889 -5.34526 43.93867 -5.49999 -6.29241 46.81468 -6.59889 -5.23604 46.50967 -5.49999 -4.75780 49.49968 -6.59889 -3.95910 48.74368 -5.49999 -2.16214 51.18068 -6.59889 -1.79926 50.14268 -5.49999 0.91560 51.48367 -6.59889 0.76172 50.39468 -5.49999 3.78892 50.33968 -6.59889 3.15259 49.44267 -5.49999 5.81689 48.00468 -5.76339 6.37616 44.99968 -6.59889 4.84007 47.50069 -6.42709 5.71247 44.99968 -3.99999 -6.40153 42.29169 -3.99999 -6.89415 44.11368 -3.99999 -6.87828 46.00168 -3.99999 -6.35507 47.81468 -3.99999 -5.36307 49.42068 -3.99999 -3.97553 50.70068 -3.99999 -2.29479 51.56068 -3.99999 -0.44483 51.93568 -3.99999 1.43786 51.79867 -3.99999 3.21449 51.16068 -3.99999 4.75370 50.06868 -3.99999 5.94276 48.60168 -3.99999 6.69274 46.86967 -6.85319 4.87616 44.99968 -4.92709 6.80228 44.99968 -6.99999 -0.25282 48.94168 -6.99999 0.81734 48.86368 -6.99999 -1.30441 48.72868 -6.99999 1.82715 48.50168 -6.99999 -2.25983 48.23969 -6.99999 2.70194 47.87968 -6.99999 -0.00090 44.99968 -6.99999 -3.04855 47.51268 -6.99999 3.37761 47.04568 -6.99999 -3.61239 46.59969 -6.99999 3.80368 46.06168 -6.99999 -3.90969 45.56868 -6.99999 3.94911 44.99968 -6.99999 -3.91855 44.49568 -3.99999 6.94911 44.99968 -4.46019 7.99911 44.99968 8.35526 -5.50089 23.99968 8.73536 -4.87502 23.99968 9.28136 -3.73246 23.99968 9.67876 -2.52910 23.99968 7.43666 6.69810 34.49368 8.31437 5.81849 29.52985 8.89386 -4.46979 29.51968 8.76546 -4.19563 35.80267 9.26076 -2.79232 29.51968 8.91906 -2.27439 35.04568 9.45096 -1.09815 29.51968 8.96676 -0.33818 35.04568 9.47666 0.60681 29.51968 8.94576 1.60178 35.04568 9.33576 2.31798 29.51968 8.83896 3.55496 35.04568 8.30708 5.67738 34.68957 8.98616 4.04325 29.51968 0.00416 -10.00089 29.52368 0.00336 -10.00089 30.08768 2.93366 -9.56529 30.58668 3.43473 -9.48162 29.13079 3.49076 -9.37344 25.99968 1.45316 -9.89544 25.99968 4.39459 -9.10315 25.99968 4.41876 -8.98168 31.25368 6.33566 -7.76061 29.52368 5.84346 -8.13534 32.22368 7.02016 -7.12658 25.99968 7.14446 -7.03138 33.48969 8.27176 -5.67266 35.04868 8.54566 -5.26191 29.52368 4.68486 -8.14347 33.37068 5.30646 7.91391 34.49867 6.09576 7.66057 34.49867 6.81586 7.24997 34.49968 6.91396 -7.18597 33.86967 5.65496 -8.25206 32.34668 5.01416 -8.44358 32.71868 3.31336 -9.32459 31.45968 1.18046 -9.86343 30.69068 5.37426 -8.43667 25.99968 5.71986 -8.20649 23.99968 6.46616 -7.63259 23.99968 7.16186 -6.98424 23.99968 -7.15819 -6.98424 23.99968 -6.46249 -7.63259 23.99968 -5.71619 -8.20649 23.99968 -5.37059 -8.43667 25.99968 -1.17679 -9.86343 30.69068 -3.30969 -9.32459 31.45968 -5.01049 -8.44358 32.71868 -5.65129 -8.25206 32.34668 -6.31069 -7.37931 34.23868 -6.91029 -7.18597 33.86967 -7.85419 -6.04028 35.50568 -6.81219 7.24997 34.49968 -6.09209 7.66057 34.49867 -5.30279 7.91391 34.49867 -8.26809 -5.67266 35.04868 -4.68119 -8.14347 33.37068 -5.72309 -7.25891 34.63368 -8.54199 -5.26191 29.52368 -7.14079 -7.03138 33.48969 -7.01649 -7.12658 25.99968 -5.83979 -8.13534 32.22368 -6.33199 -7.76061 29.52368 -4.41509 -8.98168 31.25368 -4.39092 -9.10315 25.99968 -1.44949 -9.89544 25.99968 -3.48709 -9.37343 25.99968 -3.43106 -9.48162 29.13079 -2.92999 -9.56529 30.58668 0.00184 -10.00019 25.99969 -8.98249 4.04325 29.51968 -8.30341 5.67738 34.68957 -8.83529 3.55496 35.04568 -9.33209 2.31798 29.51968 -8.94209 1.60178 35.04568 -9.47299 0.60681 29.51968 -8.96309 -0.33818 35.04568 -9.44729 -1.09815 29.51968 -8.91539 -2.27439 35.04568 -9.25709 -2.79232 29.51968 -8.76179 -4.19563 35.80267 -8.89019 -4.46979 29.51968 -8.31070 5.81849 29.52985 -7.43299 6.69810 34.49368 -9.67509 -2.52910 23.99968 -9.27769 -3.73246 23.99968 -8.73169 -4.87502 23.99968 -8.35159 -5.50089 23.99968 0.00183 7.24200 10.60569 4.00366 4.25152 9.99969 5.65006 6.94911 8.25268 5.55006 6.94911 5.59469 3.89726 6.94911 9.21068 3.63686 6.94093 6.60969 1.98966 6.94911 9.80069 0.00366 6.94911 9.99969 0.00366 6.94911 7.84768 4.30636 7.24200 9.80469 1.47496 7.24200 10.60569 4.32487 5.06448 8.40697 3.63686 6.82538 6.40069 4.38886 6.06216 6.65668 4.68666 3.94590 9.87969 4.34936 4.09318 9.96969 3.63371 6.43688 6.43168 4.43506 6.73264 6.19568 4.49076 6.91366 6.33069 5.94346 3.82193 8.45469 6.00400 4.02117 8.04468 -6.00000 4.02117 8.04468 -5.93979 3.82193 8.45469 -5.54639 6.94911 5.59469 -4.54040 6.94911 6.46068 -3.63320 6.94093 6.60969 -4.45075 6.64691 6.24219 -4.34569 4.09222 9.96969 -3.63320 6.82538 6.40069 3.63321 5.95391 6.88068 -4.32395 5.11941 8.41997 -1.47129 7.24200 10.60569 -4.30269 7.24200 9.80469 -1.98599 6.94911 9.80069 -3.89359 6.94911 9.21068 -3.99999 4.25198 9.99969 4.47576 -8.00089 9.94269 6.00366 5.96671 5.62369 6.00366 4.86318 6.60168 6.00366 4.40365 7.39368 5.41736 3.62295 9.41469 5.73196 3.74311 9.00368 -5.72829 3.74311 9.00368 -3.63359 6.44435 6.42669 -4.68299 3.85204 9.87969 -5.41369 3.62295 9.41469 -4.38520 6.06216 6.65668 -3.63320 5.95391 6.88068 -5.99999 4.40365 7.39368 -5.99999 4.86318 6.60168 -6.00000 5.96671 5.62369 -4.47209 -8.00089 9.94269 -8.38479 -5.45020 -0.00031 -9.63909 -2.66304 -0.00031 -6.78409 -6.66756 -3.03501 -8.51050 -4.28290 -3.03941 -7.35780 -3.50425 -5.79601 7.36146 -3.50425 -5.79601 8.51416 -4.28290 -3.03941 6.78776 -6.66756 -3.03501 9.64276 -2.66304 -0.00031 8.38846 -5.45020 -0.00031 9.12276 -4.10482 -0.00031 -9.11909 -4.10482 -0.00031 -3.57919 -8.00089 13.99868 -3.99999 -5.43664 40.66869 -5.48459 -5.09962 40.93769 -5.49999 -4.73356 40.21569 -5.76329 -4.42797 39.42269 -6.42709 -4.46943 41.43969 -6.59809 -3.69701 40.57769 -6.42699 -3.76429 39.42269 -6.85319 -2.92798 39.42269 -6.68310 -3.81534 41.96069 -6.99999 -3.09028 42.53869 -6.99999 -2.49594 41.59168 -6.99999 -2.12557 40.53269 -6.99999 -2.00089 39.42269 -5.36349 -4.67315 38.32668 -6.19619 -4.04460 39.22469 -6.72699 -3.25133 38.74369 -6.99999 -2.00089 38.27869 -6.96549 -2.45480 38.42168 -8.53599 -1.46623 39.60468 -8.55289 -0.11087 39.43468 -8.54059 1.25595 39.55968 -8.50409 2.50568 39.95368 -8.45399 3.57721 40.56069 -6.76829 -5.70594 36.85169 -6.86009 -4.03110 39.22569 -6.92969 7.10944 44.99969 -6.11599 7.64029 44.99969 -5.93589 7.04911 44.99969 -5.49999 6.94911 44.99969 -5.31029 7.90772 44.99969 -4.88529 7.95342 44.99969 -7.19169 6.82799 43.78869 -8.19199 4.97673 41.65069 -7.71279 6.06131 42.71468 -7.49639 -5.59217 36.77569 -7.60349 -3.56948 39.46268 -8.12469 -5.26918 36.55169 -8.06229 -2.97472 39.64069 -8.56689 -4.78127 36.21169 -8.39929 -2.25591 39.68868 -7.28129 -6.21366 35.90269 -6.99999 1.68717 38.19369 -6.99999 0.45891 38.00269 -6.99999 -0.78335 38.03168 -6.99999 2.86304 38.59969 -6.99999 3.94911 39.20568 -6.99999 -3.63839 43.45969 -5.03399 6.76527 43.41169 -5.49999 6.54719 42.67069 -5.93590 6.24091 41.72169 -6.39679 5.75341 40.92669 -6.83869 4.91954 39.95969 -7.08054 5.94669 41.49869 -7.43409 4.97597 40.42869 -8.19199 4.02715 40.55369 -7.43409 3.77077 39.39269 -8.19199 2.84199 39.71668 -7.43409 2.35678 38.66769 -8.19199 1.49065 39.18868 -7.43409 0.81253 38.29169 -8.19199 0.05167 39.00069 -7.43409 -0.77680 38.28768 -8.19199 -1.39001 39.16369 -7.43409 -2.32320 38.65369 -6.72699 6.57048 42.44669 -6.72699 6.92842 43.70069 -5.49999 -6.42367 43.72469 5.48826 -5.09962 40.93769 6.43076 -4.46943 41.43969 5.50366 -6.42367 43.72469 6.60256 -5.34526 43.93868 6.85686 4.87616 44.99969 6.73066 6.92842 43.70069 6.73066 -3.25133 38.74369 6.73066 6.57048 42.44669 7.08421 5.94669 41.49869 7.43776 -2.32320 38.65369 8.19566 -1.39001 39.16369 7.43776 -0.77680 38.28768 8.19566 0.05167 39.00069 7.43776 0.81253 38.29169 8.19566 1.49065 39.18868 7.43776 2.35678 38.66769 8.19566 2.84199 39.71668 7.43776 3.77077 39.39269 8.19566 4.02715 40.55369 7.43776 4.97597 40.42869 6.84236 4.91954 39.95969 6.40046 5.75341 40.92669 6.43076 5.71247 44.99969 5.93956 6.24091 41.72169 5.50366 6.54719 42.67069 5.03766 6.76527 43.41169 4.93076 6.80228 44.99969 7.00366 3.80368 46.06168 7.00366 -3.90969 45.56869 7.00366 3.94911 44.99969 7.00366 -3.91855 44.49569 7.00366 -3.63839 43.45969 7.00366 3.94911 39.20568 7.00366 2.86304 38.59969 7.00366 -0.78335 38.03168 7.00366 0.45891 38.00269 7.00366 1.68717 38.19369 6.31436 -7.37931 34.23869 8.12836 -5.26918 36.55169 7.85786 -6.04028 35.50568 7.28496 -6.21366 35.90269 8.40296 -2.25591 39.68868 8.57056 -4.78127 36.21169 8.06596 -2.97472 39.64069 7.60716 -3.56948 39.46268 6.99346 -4.00149 39.23769 7.50006 -5.59217 36.77569 7.71646 6.06131 42.71468 8.19566 4.97673 41.65069 7.19536 6.82799 43.78869 4.88896 7.95342 44.99969 5.31396 7.90772 44.99969 5.93956 7.04911 44.99969 6.11966 7.64029 44.99969 6.93336 7.10944 44.99969 5.72676 -7.25891 34.63369 6.77196 -5.70594 36.85169 8.45766 3.57721 40.56069 8.50776 2.50568 39.95368 8.54426 1.25595 39.55968 8.55656 -0.11086 39.43468 8.53966 -1.46623 39.60468 7.00366 -2.00089 38.27869 6.96916 -2.45480 38.42168 6.19986 -4.04460 39.22469 5.36716 -4.67315 38.32668 7.00366 -2.31088 41.06269 7.00366 -2.00089 39.42269 7.00366 -2.49594 41.59168 7.00366 -3.09028 42.53869 6.75609 -3.81534 41.96069 6.85686 -2.92798 39.42269 6.43066 -3.76429 39.42269 6.60176 -3.69701 40.57769 5.76696 -4.42797 39.42269 5.50366 -4.73356 40.21569 4.00366 -5.00089 39.42269 4.00366 -5.43664 40.66869 + + + + + + + + + + -0.37992 -0.92502 0.00105 -0.61397 0.78924 -0.01224 -0.07593 -0.97679 -0.20031 -0.22994 -0.96457 -0.12938 -0.08134 -0.97733 -0.19549 -0.42429 -0.89757 -0.11982 0.42429 -0.89757 -0.11983 0.08144 -0.97732 -0.19548 0.22994 -0.96457 -0.12938 0.07611 -0.97679 -0.20023 0.00000 1.00000 -0.00000 -0.02010 0.99979 -0.00262 -0.99786 -0.06535 0.00030 -1.00000 0.00130 -0.00287 -0.99811 0.06144 0.00009 -0.98228 0.18741 -0.00039 -0.98189 0.18945 -0.00051 -0.89668 0.44268 0.00142 -0.94065 0.33926 0.00847 -0.93503 0.35447 0.00850 -0.87777 0.47908 -0.00009 -0.79597 0.60534 0.00009 -0.79427 0.60756 -0.00009 -0.73062 -0.00000 -0.68279 -0.89780 -0.00000 -0.44040 -0.89780 -0.00000 -0.44040 -0.71610 0.04952 -0.69624 -0.75711 0.13830 -0.63848 -0.69777 0.21297 -0.68393 -0.85617 0.26132 -0.44574 -0.92192 0.33250 -0.19878 -0.93821 0.30132 -0.17023 -0.85683 0.27518 -0.43602 -0.69725 0.25192 -0.67110 -0.86835 0.47394 -0.14612 -0.73749 0.50314 -0.45051 -0.77877 0.59570 -0.19660 -0.78420 0.59050 -0.19062 -0.73536 0.51102 -0.44509 -0.72246 0.52579 -0.44899 -0.67329 -0.73938 -0.00047 -0.66596 -0.74598 0.00018 -0.51275 -0.85854 0.00036 -0.48310 -0.87557 -0.00131 -0.34471 -0.93870 0.00305 -0.28004 -0.95995 0.00846 -0.17483 -0.98460 -0.00057 -0.13972 0.99019 0.00271 -0.27312 0.96198 -0.00196 -0.40823 0.91287 0.00257 -0.47428 0.88037 -0.00066 -0.45040 0.89283 0.00000 -0.71115 0.70304 0.00000 -0.57790 0.81555 -0.03005 -0.60493 0.79627 0.00059 -0.67564 0.73722 0.00384 -0.57764 0.81518 -0.04270 -0.64644 0.74661 -0.15714 -0.67682 0.72341 -0.13637 -0.59520 0.75563 -0.27343 -0.59953 0.70834 -0.37259 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.02819 0.94010 0.33974 0.01436 0.93130 0.36396 0.12973 0.97951 -0.15405 -0.64764 0.76194 0.00226 -0.71191 0.70227 0.00006 -0.98581 0.00000 -0.16786 -0.97140 0.18743 -0.14577 0.97140 0.18743 -0.14578 0.98565 0.00000 -0.16881 0.71191 0.70227 0.00006 0.64764 0.76194 0.00226 0.00494 0.91350 0.40681 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 0.54765 0.76436 -0.34035 0.67682 0.72341 -0.13637 0.64644 0.74661 -0.15714 0.57764 0.81518 -0.04270 0.67564 0.73722 0.00384 0.57791 0.81555 -0.02994 0.61966 0.78477 -0.01300 0.70339 0.71081 -0.00063 0.47080 0.88224 -0.00000 0.40823 0.91287 0.00257 0.27312 0.96198 -0.00196 0.13972 0.99019 0.00271 0.17483 -0.98460 -0.00057 0.28004 -0.95995 0.00846 0.34471 -0.93870 0.00305 0.37991 -0.92502 0.00105 0.48310 -0.87557 -0.00131 0.51275 -0.85854 0.00036 0.66596 -0.74598 0.00018 0.67329 -0.73937 -0.00047 0.72246 0.52579 -0.44899 0.73536 0.51102 -0.44509 0.78420 0.59050 -0.19063 0.77877 0.59570 -0.19660 0.73749 0.50314 -0.45051 0.86835 0.47394 -0.14612 0.69725 0.25192 -0.67110 0.85683 0.27518 -0.43602 0.93821 0.30132 -0.17023 0.92192 0.33250 -0.19878 0.85617 0.26132 -0.44574 0.69777 0.21297 -0.68393 0.75711 0.13830 -0.63848 0.71610 0.04952 -0.69624 0.89780 0.00000 -0.44040 0.89780 0.00000 -0.44040 0.73062 0.00000 -0.68279 0.79427 0.60756 -0.00009 0.79597 0.60534 0.00009 0.87777 0.47908 -0.00009 0.93503 0.35448 0.00850 0.94065 0.33926 0.00847 0.89668 0.44268 0.00142 0.98189 0.18945 -0.00051 0.98228 0.18741 -0.00039 0.99809 0.06144 -0.00571 1.00000 0.00130 0.00031 0.99786 -0.06535 0.00030 0.02010 0.99979 -0.00262 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 -0.99986 0.01651 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 0.00000 1.00000 0.69946 0.68907 0.18956 0.22891 0.89330 0.38681 0.96248 0.21083 0.17081 0.95946 0.21276 0.18488 0.69693 0.54133 0.47038 0.36003 0.72476 0.58745 0.30851 0.71817 0.62374 0.69716 0.54127 0.47010 0.96751 0.14650 0.20605 0.21934 0.56453 0.79573 0.95759 0.09723 0.27122 0.96142 0.10177 0.25557 0.69721 0.26520 0.66601 0.69718 0.26518 0.66605 0.30072 0.32233 0.89759 0.34441 0.34727 0.87223 0.96702 0.01852 0.25402 0.22851 0.07066 0.97097 0.69718 -0.07020 0.71345 0.95018 -0.06188 0.30550 0.96407 -0.02601 0.26437 0.36233 -0.09132 0.92757 0.69714 -0.07024 0.71349 0.25693 -0.19200 0.94717 0.96537 -0.11886 0.23224 0.69711 -0.38978 0.60175 0.95840 -0.15517 0.23956 0.69719 -0.38969 0.60172 0.42922 -0.41142 0.80405 0.25228 -0.52600 0.81221 0.22867 -0.66008 0.71554 0.96700 -0.17269 0.18735 0.69715 -0.62243 0.35577 0.96242 -0.23105 0.14269 0.95943 -0.24477 0.13991 0.69712 -0.62246 0.35577 0.36001 -0.79374 0.49028 0.30840 -0.82588 0.47203 0.21950 -0.93736 0.27051 -0.95765 -0.28792 0.00238 -0.69707 -0.71635 0.03043 -0.96752 -0.24290 0.07004 -0.21950 -0.93736 0.27051 -0.30839 -0.82588 0.47203 -0.36001 -0.79374 0.49028 -0.69712 -0.62246 0.35577 -0.95943 -0.24477 0.13991 -0.96242 -0.23105 0.14269 -0.69715 -0.62243 0.35577 -0.96700 -0.17269 0.18735 -0.22867 -0.66008 0.71554 -0.25228 -0.52600 0.81221 -0.42922 -0.41142 0.80405 -0.69719 -0.38969 0.60172 -0.95840 -0.15517 0.23956 -0.69711 -0.38978 0.60175 -0.96537 -0.11886 0.23224 -0.25693 -0.19200 0.94717 -0.69714 -0.07024 0.71349 -0.36233 -0.09132 0.92757 -0.96407 -0.02601 0.26437 -0.95018 -0.06188 0.30550 -0.69718 -0.07020 0.71345 -0.22851 0.07066 0.97097 -0.96702 0.01852 0.25402 -0.34441 0.34727 0.87223 -0.30072 0.32233 0.89759 -0.69718 0.26518 0.66605 -0.69721 0.26520 0.66601 -0.96142 0.10177 0.25557 -0.95759 0.09723 0.27122 -0.21934 0.56453 0.79573 -0.96751 0.14650 0.20605 -0.69716 0.54127 0.47010 -0.30851 0.71817 0.62374 -0.36003 0.72476 0.58745 -0.69693 0.54133 0.47038 -0.95946 0.21276 0.18488 -0.96248 0.21083 0.17081 -0.22891 0.89330 0.38681 -0.96702 0.23373 0.10120 -0.69946 0.68907 0.18956 -0.44469 0.87275 0.20141 -0.15007 0.94757 0.28211 -0.42958 0.89466 0.12265 -0.95018 0.30880 0.04245 -0.69362 0.69364 0.19431 -0.98747 0.15637 0.02141 -0.84480 0.43042 0.31789 -0.00000 -0.96534 -0.26100 -0.00000 -0.96534 -0.26100 -0.00000 -0.99996 0.00841 -0.00000 -0.99996 0.00841 -0.00000 -0.96079 0.27727 -0.00000 -0.96079 0.27727 -0.00000 -0.85078 0.52551 -0.00000 -0.85078 0.52551 -0.00000 -0.67805 0.73502 0.00000 -0.67805 0.73502 0.00000 -0.45551 0.89023 0.00000 -0.45551 0.89023 0.00000 -0.19866 0.98007 0.00000 -0.19866 0.98007 -0.00000 0.07258 0.99736 0.00000 0.07258 0.99736 0.00000 0.33797 0.94116 -0.00000 0.33797 0.94116 -0.00000 0.57862 0.81559 0.00000 0.57862 0.81559 0.00000 0.77686 0.62968 0.00000 0.77686 0.62968 0.00000 0.91766 0.39736 0.00000 0.91766 0.39736 0.00000 0.99073 0.13583 0.00000 0.99073 0.13583 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.97499 0.22226 -0.00000 -0.92453 0.38110 0.90226 -0.43116 0.00574 0.97649 -0.21358 0.02928 0.97612 -0.21350 0.04000 0.94802 -0.31308 0.05686 0.99635 -0.05341 0.06661 0.97763 -0.19024 0.08966 0.99134 -0.11130 0.06976 0.99120 -0.11128 0.07172 0.99558 -0.02453 0.09061 0.99409 -0.06510 0.08683 0.99589 -0.01501 0.08933 0.99520 -0.01500 0.09672 0.99424 0.06120 0.08796 0.99554 0.01078 0.09370 0.99338 0.08180 0.08071 0.99256 0.08173 0.09020 0.97998 0.18697 0.06840 0.99552 0.05444 0.07731 0.96826 0.24794 0.03155 0.97796 0.19817 0.06582 0.89663 0.44266 -0.01036 0.97777 0.19813 0.06861 0.14700 -0.98914 0.00021 0.24807 -0.96831 -0.02902 0.07172 -0.99371 0.08595 0.14963 -0.98874 -0.00030 0.14904 -0.98882 -0.00554 0.28639 -0.95770 -0.02796 0.34030 -0.93819 0.06320 0.56248 -0.82680 0.00516 0.50451 -0.86193 0.05048 0.53463 -0.84366 -0.04914 0.51263 -0.85823 -0.02566 0.62265 -0.78225 -0.01980 0.64109 -0.76740 0.01036 0.79702 -0.60172 -0.05190 0.74900 -0.66246 -0.01212 0.74880 -0.66228 0.02629 0.91538 -0.40230 0.01547 0.61539 -0.78641 0.05336 0.57003 -0.81556 0.09967 0.12475 -0.87586 0.46616 0.51875 -0.85477 -0.01612 0.37649 -0.90862 0.18073 0.32485 -0.92285 0.20694 0.13312 -0.88748 0.44120 0.09621 -0.88767 0.45032 0.31482 -0.94120 0.12258 0.06742 -0.90426 0.42164 0.08306 -0.90964 0.40702 0.17554 -0.96597 0.18998 0.02220 -0.90647 0.42168 0.16166 -0.98259 -0.09158 0.06493 -0.99436 -0.08387 0.07172 -0.99366 -0.08660 0.20896 -0.97695 -0.04364 0.24766 -0.96673 -0.06404 0.60929 -0.79232 0.03169 0.62268 -0.78228 0.01757 0.68177 -0.73156 -0.00376 0.47456 -0.88001 -0.01928 0.56160 -0.82551 -0.05591 0.40991 -0.90871 -0.07890 0.28626 -0.95728 -0.04085 0.79561 0.60506 -0.03020 0.93501 0.35447 -0.01016 0.93521 0.35396 -0.00997 0.93524 0.35385 0.01100 0.75898 0.65084 0.01887 0.77910 -0.62681 0.01059 0.77326 -0.63409 0.00078 0.85470 -0.51907 -0.00700 0.91546 -0.40240 0.00325 -0.00000 1.00000 0.00000 0.10310 0.99467 -0.00009 0.13972 0.99019 -0.00302 0.30561 0.95215 0.00160 0.40823 0.91287 -0.00410 0.49533 0.86870 0.00126 0.64764 0.76194 -0.00322 0.66439 0.74739 -0.00132 0.70513 0.70908 -0.00097 -0.70513 0.70908 -0.00097 -0.66439 0.74739 -0.00132 -0.64764 0.76194 -0.00322 -0.49533 0.86870 0.00126 -0.40823 0.91287 -0.00410 -0.30561 0.95215 0.00160 -0.13972 0.99019 -0.00302 -0.10310 0.99467 -0.00009 0.00000 1.00000 0.00000 -0.91546 -0.40240 0.00325 -0.85470 -0.51907 -0.00700 -0.77326 -0.63409 0.00078 -0.77910 -0.62681 0.01059 -0.75898 0.65084 0.01887 -0.93524 0.35385 0.01100 -0.93521 0.35396 -0.00997 -0.93501 0.35447 -0.01016 -0.79561 0.60506 -0.03020 -0.28626 -0.95728 -0.04085 -0.40991 -0.90871 -0.07890 -0.56160 -0.82551 -0.05591 -0.47456 -0.88001 -0.01928 -0.68177 -0.73156 -0.00376 -0.62268 -0.78228 0.01757 -0.60929 -0.79232 0.03169 -0.24766 -0.96673 -0.06404 -0.20896 -0.97695 -0.04364 -0.07172 -0.99365 -0.08669 -0.06477 -0.99437 -0.08389 -0.16161 -0.98253 -0.09231 -0.02214 -0.90647 0.42168 -0.17554 -0.96597 0.18998 -0.08306 -0.90964 0.40702 -0.06742 -0.90426 0.42164 -0.31482 -0.94120 0.12258 -0.09621 -0.88767 0.45032 -0.13312 -0.88748 0.44120 -0.32485 -0.92285 0.20694 -0.37649 -0.90862 0.18073 -0.51875 -0.85477 -0.01612 -0.12475 -0.87586 0.46616 -0.15273 -0.86617 0.47583 -0.41173 -0.87359 0.25948 -0.57003 -0.81556 0.09967 -0.61539 -0.78642 0.05336 -0.43261 -0.86653 0.24894 -0.14765 -0.86322 0.48276 -0.71431 -0.69421 0.08851 -0.67849 -0.72532 0.11649 -0.94257 -0.33229 0.03376 -0.91537 -0.40231 0.01547 -0.74880 -0.66228 0.02629 -0.74900 -0.66246 -0.01212 -0.79702 -0.60172 -0.05190 -0.64109 -0.76740 0.01036 -0.62265 -0.78225 -0.01980 -0.51263 -0.85823 -0.02566 -0.53463 -0.84366 -0.04914 -0.50451 -0.86193 0.05048 -0.56248 -0.82680 0.00516 -0.34030 -0.93819 0.06320 -0.28639 -0.95770 -0.02796 -0.14884 -0.98885 -0.00561 -0.14945 -0.98877 -0.00010 -0.07172 -0.99371 0.08595 -0.24807 -0.96831 -0.02902 -0.14692 -0.98915 -0.00021 -0.97777 0.19813 0.06861 -0.89663 0.44266 -0.01036 -0.97796 0.19817 0.06582 -0.96826 0.24794 0.03155 -0.99552 0.05444 0.07731 -0.97998 0.18697 0.06840 -0.99256 0.08173 0.09020 -0.99338 0.08180 0.08071 -0.99554 0.01078 0.09370 -0.99424 0.06120 0.08796 -0.99520 -0.01500 0.09672 -0.99589 -0.01501 0.08933 -0.99409 -0.06510 0.08683 -0.99558 -0.02453 0.09061 -0.99120 -0.11128 0.07172 -0.99134 -0.11130 0.06976 -0.97763 -0.19024 0.08966 -0.99635 -0.05341 0.06661 -0.94802 -0.31308 0.05686 -0.97612 -0.21350 0.04000 -0.97649 -0.21358 0.02928 -0.90226 -0.43116 0.00574 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.90036 -0.43515 0.00000 0.90036 -0.43515 0.00000 0.00000 -1.00000 -0.00000 1.00000 -0.00000 0.02992 0.99953 -0.00614 -0.04897 0.99855 -0.02238 -0.00000 1.00000 0.00000 -0.00094 0.99999 -0.00305 -0.00000 1.00000 0.00000 0.00167 1.00000 -0.00170 -0.18127 0.92582 -0.33166 -0.33605 0.30453 -0.89125 -0.24187 0.45887 -0.85495 -0.12672 0.90338 -0.40970 -0.10729 0.91905 -0.37927 -0.15739 0.32299 -0.93322 -0.03628 0.93144 -0.36209 -0.98931 0.00059 -0.14580 -0.08645 0.00000 -0.99626 -0.25621 -0.07481 -0.96372 -0.46284 0.61705 -0.63642 -0.12748 0.61787 -0.77588 -0.12905 0.86783 -0.47980 0.52405 0.59562 -0.60877 0.08703 0.87183 -0.48201 0.02729 0.59100 -0.80621 0.08645 0.00000 -0.99626 0.98943 0.00056 -0.14501 -0.00000 -0.07954 -0.99683 -0.00000 0.87515 -0.48385 -0.00000 0.87515 -0.48385 0.03621 0.93145 -0.36205 0.15739 0.32299 -0.93322 0.10729 0.91905 -0.37927 0.12672 0.90337 -0.40970 0.24187 0.45887 -0.85495 0.33605 0.30453 -0.89125 0.18127 0.92582 -0.33166 0.00000 0.99998 -0.00661 -0.00167 1.00000 -0.00170 0.00000 1.00000 -0.00000 0.00094 0.99999 -0.00305 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00938 0.99995 -0.00221 0.00000 1.00000 -0.00000 -0.03447 -0.56461 -0.82463 -0.02257 -0.86820 -0.49570 -0.00000 -1.00000 -0.00000 -0.02658 0.99964 -0.00251 0.00811 0.99992 0.00963 0.40679 -0.91352 -0.00000 -0.99129 0.00002 -0.13166 -0.93308 -0.00133 -0.35966 -0.92096 0.00015 -0.38965 -0.79403 -0.00032 -0.60788 -0.78301 0.00046 -0.62201 -0.60834 -0.00037 -0.79368 -0.59143 0.00050 -0.80636 -0.42313 -0.00028 -0.90607 -0.36047 0.00144 -0.93277 -0.25804 -0.00054 -0.96613 -0.11987 0.00096 -0.99279 -0.00342 0.94046 0.33987 0.10258 0.95600 0.27486 -0.54107 -0.72740 -0.42205 -0.54206 -0.72466 -0.42548 -0.54151 -0.72194 -0.43078 -0.56924 -0.75410 -0.32757 -0.66245 -0.49685 -0.56063 -0.35061 -0.80805 -0.47342 -0.84565 -0.40086 -0.35240 -0.38367 0.78835 -0.48095 -0.40881 0.39255 -0.82388 -0.12973 0.97951 -0.15405 -0.49552 -0.46867 -0.73130 -0.42845 -0.22367 -0.87544 0.44674 -0.23178 -0.86412 0.49661 -0.46421 -0.73341 0.23270 0.87645 -0.42153 0.17952 0.79930 -0.57349 0.40881 0.39255 -0.82388 0.38366 0.78835 -0.48095 0.84565 -0.40086 -0.35240 0.33841 -0.82490 -0.45279 0.01364 -0.88159 -0.47182 0.67437 -0.48974 -0.55261 0.58626 -0.73899 -0.33195 0.56054 -0.70950 -0.42709 0.56140 -0.71351 -0.41920 0.56043 -0.71635 -0.41564 -0.06761 0.95887 0.27568 0.11987 0.00096 -0.99279 0.25818 -0.00054 -0.96610 0.36048 0.00146 -0.93277 0.45114 -0.00108 -0.89245 0.59133 -0.00033 -0.80643 0.59343 -0.00043 -0.80488 0.78301 0.00046 -0.62201 0.79403 -0.00032 -0.60788 0.92096 0.00015 -0.38965 0.93308 -0.00133 -0.35966 0.99129 0.00002 -0.13166 -0.40679 -0.91352 0.00000 -0.00625 -0.86521 -0.50136 -0.00000 -0.87912 -0.47660 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 0.00000 -1.00000 -0.11875 -0.67600 -0.72728 -0.69945 -0.56446 -0.43835 -0.73008 -0.52935 -0.43217 -0.79534 -0.57614 -0.18840 -0.73749 -0.50314 -0.45051 -0.66333 -0.36884 -0.65111 -0.68186 -0.46553 -0.56422 -0.69725 -0.25192 -0.67110 -0.93527 -0.30038 -0.18722 -0.85683 -0.27518 -0.43602 -0.70722 -0.14967 -0.69097 -0.71631 -0.21863 -0.66264 -0.85617 -0.26132 -0.44574 -0.71610 -0.04952 -0.69624 -0.59927 -0.74831 -0.28445 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -0.63379 -0.75998 -0.14402 -0.65889 -0.73806 -0.14536 -0.62639 -0.76482 -0.15062 0.62639 -0.76482 -0.15062 0.65889 -0.73806 -0.14536 -1.00000 0.00000 0.00000 0.59715 -0.78261 -0.17586 0.62227 -0.69937 -0.35166 0.71610 -0.04952 -0.69624 0.85617 -0.26132 -0.44574 0.71631 -0.21863 -0.66264 0.70722 -0.14967 -0.69097 0.85683 -0.27518 -0.43602 0.93527 -0.30038 -0.18722 0.69725 -0.25192 -0.67110 0.68186 -0.46553 -0.56422 0.66333 -0.36884 -0.65111 0.73749 -0.50314 -0.45051 0.79534 -0.57614 -0.18840 0.73008 -0.52935 -0.43217 0.75435 -0.49922 -0.42630 -0.00000 -1.00000 0.00000 0.00106 -0.99996 0.00881 0.02538 -0.99967 0.00267 0.79359 -0.60845 -0.00012 0.79427 -0.60756 -0.00018 0.85472 -0.51909 0.00009 0.87777 -0.47908 -0.00121 0.90227 -0.43117 0.00073 0.94069 -0.33927 -0.00095 0.94956 -0.31358 0.00033 0.98159 -0.19101 -0.00041 0.98148 -0.19157 -0.00037 0.86835 -0.47394 -0.14612 0.92761 -0.33456 -0.16616 0.28626 -0.95811 0.00941 0.06124 -0.99812 0.00082 -1.00000 -0.00000 0.00000 0.77914 -0.62684 0.00328 0.00000 -0.98059 -0.19609 0.07625 -0.98818 -0.13301 0.67329 -0.73937 -0.00375 0.68177 -0.73156 -0.00422 0.51266 -0.85845 -0.01557 0.60949 -0.79259 -0.01799 0.28596 -0.95726 -0.04336 0.48386 -0.87340 -0.05531 0.02544 -0.99072 -0.13349 0.19812 -0.97716 -0.07687 0.97088 -0.18950 -0.14654 0.78235 -0.59845 -0.17260 0.48258 -0.87463 -0.04614 -0.48258 -0.87464 -0.04614 -0.78235 -0.59845 -0.17260 -0.97088 -0.18950 -0.14654 -0.19812 -0.97716 -0.07687 -0.02544 -0.99072 -0.13349 -0.48386 -0.87340 -0.05531 -0.28596 -0.95726 -0.04336 -0.60949 -0.79259 -0.01799 -0.51266 -0.85845 -0.01557 -0.68177 -0.73156 -0.00422 -0.67329 -0.73937 -0.00375 -0.07616 -0.98818 -0.13301 -0.00000 -0.98059 -0.19609 -0.77914 -0.62684 0.00328 0.20395 -0.06686 -0.97670 1.00000 0.00000 -0.00000 -0.06124 -0.99812 0.00082 -0.28626 -0.95811 0.00941 -0.92761 -0.33456 -0.16616 -0.86835 -0.47394 -0.14612 -0.98148 -0.19157 -0.00037 -0.98159 -0.19101 -0.00041 -0.94956 -0.31358 0.00033 -0.94069 -0.33927 -0.00095 -0.90227 -0.43117 0.00073 -0.87777 -0.47908 -0.00121 -0.85472 -0.51908 0.00009 -0.79427 -0.60756 -0.00018 -0.79359 -0.60845 -0.00012 0.00062 -0.06808 -0.99768 -0.00020 -0.68088 -0.73240 -0.00000 -0.67931 -0.73385 -0.02538 -0.99967 0.00267 -0.00106 -0.99996 0.00881 -0.00000 -0.99986 0.01651 0.00000 -0.94394 -0.33011 -0.00000 -0.94394 -0.33011 -0.26435 -0.91036 -0.31837 -0.29878 -0.91958 -0.25516 -0.36744 -0.83266 -0.41433 -0.64066 -0.69026 -0.33630 -0.69571 -0.59806 -0.39790 -0.70567 -0.70569 -0.06343 -0.69377 -0.71869 -0.04660 -0.88605 -0.45155 -0.10496 -0.94887 -0.30419 -0.08435 -0.93636 -0.34017 -0.08666 -0.96824 -0.21178 -0.13291 -0.96453 -0.24918 -0.08715 -0.98754 -0.15637 -0.01756 -0.96795 -0.24613 0.04991 -0.30897 -0.95094 0.01571 -0.19818 -0.96944 0.14457 -0.64480 -0.76159 -0.06484 -0.80014 -0.59240 -0.09401 -0.69629 -0.69631 0.17415 -0.88983 -0.45348 0.05057 -0.99712 -0.07579 0.00000 -0.96339 -0.25512 0.08248 -0.98187 -0.15548 -0.10845 -0.99492 -0.04386 0.09057 -0.99589 -0.02453 0.08723 -0.99566 -0.00074 0.09309 -0.99566 0.00045 0.09303 -0.99594 0.01078 0.08941 -0.99606 0.00113 0.08868 -0.99596 -0.00422 0.08966 -0.01576 -0.81730 0.57599 -0.00007 -0.81918 0.57353 0.00019 -0.81917 0.57355 0.00007 -0.81914 0.57359 -0.00016 -0.81916 0.57357 0.00016 -0.81915 0.57358 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00001 0.00000 1.00000 0.00001 -0.00000 1.00000 -0.10686 0.99427 0.00021 -0.10691 0.99427 0.00051 -0.10310 0.99467 0.00036 -0.31502 0.94908 0.00033 -0.30561 0.95216 0.00114 -0.54640 0.83753 0.00037 -0.49532 0.86869 0.00608 -0.73383 0.67933 0.00088 -0.66442 0.74733 0.00680 -0.29659 -0.76863 0.56678 -0.62243 -0.62224 0.47476 -0.84125 -0.41735 0.34367 -0.97445 -0.15100 0.16627 -0.18468 -0.82157 0.53937 -0.52793 -0.74792 0.40237 -0.51590 -0.74782 0.41787 -0.79345 -0.56953 0.21466 -0.77990 -0.57721 0.24203 -0.94860 -0.31649 -0.00114 -0.13722 -0.84064 0.52392 -0.16245 -0.85018 0.50080 -0.46619 -0.82821 0.31103 -0.46054 -0.83055 0.31318 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.15641 0.98761 -0.01249 -0.43461 0.90058 0.00827 -0.45395 0.89092 0.01409 -0.56909 0.82226 -0.00398 -0.73529 0.67767 0.01073 -0.70710 0.70711 0.00185 -0.88271 0.46992 -0.00184 -0.89102 0.45397 0.00134 -0.98629 0.16504 -0.00142 -0.98769 0.15640 0.00000 0.63460 -0.66563 0.39270 0.63436 -0.66518 0.39385 0.72560 -0.52027 0.45035 0.68535 -0.47470 0.55223 0.72614 -0.39663 0.56161 0.68473 -0.33252 0.64852 0.72616 -0.25021 0.64038 0.68424 -0.17252 0.70856 0.72663 -0.08900 0.68124 0.68414 -0.00184 0.72935 0.72662 0.07718 0.68269 0.68429 0.16795 0.70960 0.73343 0.25027 0.63201 0.68191 0.33078 0.65237 0.50247 0.42166 0.75480 0.79620 -0.45746 0.39598 0.71150 -0.40537 0.57398 0.77296 -0.33970 0.53585 0.73978 -0.24487 0.62671 0.77536 -0.21037 0.59545 0.75248 -0.08532 0.65307 0.77897 -0.06406 0.62378 0.75300 0.07392 0.65386 0.77803 0.08772 0.62207 0.75616 0.19727 0.62394 0.66429 0.26477 0.69901 0.24972 -0.78683 0.56439 0.13613 -0.87777 0.45933 0.11798 -0.84918 0.51476 -0.06009 -0.98988 0.12857 0.23889 -0.95596 0.17049 0.27051 -0.84078 0.46894 0.49605 -0.83495 0.23833 0.50274 -0.79627 0.33645 0.36695 -0.74608 0.55562 0.51142 -0.57864 0.63532 0.47211 -0.57465 0.66850 0.49937 -0.42215 0.75659 0.55746 -0.37879 0.73875 0.46738 -0.28853 0.83565 0.57126 -0.19417 0.79747 0.47014 -0.13561 0.87211 0.50809 0.02010 0.86107 0.55298 -0.00210 0.83319 0.50233 0.17192 0.84741 0.55640 0.19138 0.80858 0.48927 0.29566 0.82049 0.37156 0.44143 0.81675 0.49467 0.42090 0.76036 -0.07970 -0.93736 0.33913 -0.06820 -0.95935 0.27384 -0.21807 -0.95055 0.22112 -0.06791 -0.98506 0.15826 0.00000 -0.99987 0.01593 -0.03964 -0.95154 0.30497 0.01193 0.52427 0.85147 -0.00000 -0.85957 -0.51102 -0.00000 -0.85957 -0.51102 -0.96142 -0.27485 0.01168 -0.30116 -0.95354 0.00802 -0.34472 -0.93786 0.03984 -0.69707 -0.71635 0.03043 -0.22886 -0.93972 -0.25408 -0.96701 -0.24590 -0.06650 -0.95011 -0.26803 -0.15951 -0.94563 -0.27551 -0.17284 -0.95556 -0.25147 -0.15383 -0.69977 -0.65778 -0.27864 -0.37006 -0.83833 -0.40032 -0.64017 -0.69253 -0.33254 -0.27651 -0.82605 -0.49110 -0.99615 0.05447 0.06865 -0.98889 0.13229 0.06784 -0.96758 0.24929 0.04058 -0.93111 0.36112 0.05125 -0.75833 0.65140 0.02465 -0.83600 0.54855 0.01404 0.00000 1.00000 -0.00000 -0.18465 -0.80642 0.56178 -0.53029 -0.68737 0.49630 -0.80208 -0.47156 0.36647 -0.96387 -0.19129 0.18539 0.96386 -0.19129 0.18540 0.80208 -0.47156 0.36647 0.53029 -0.68737 0.49630 0.18466 -0.80774 0.55987 -0.00000 1.00000 -0.00000 0.83600 0.54855 0.01404 0.75833 0.65140 0.02465 0.93111 0.36112 0.05125 0.96758 0.24929 0.04058 0.98889 0.13229 0.06784 0.99615 0.05447 0.06865 0.27651 -0.82605 -0.49110 0.64017 -0.69253 -0.33254 0.37007 -0.83833 -0.40032 0.69978 -0.65778 -0.27864 0.93015 -0.32185 -0.17675 0.96424 -0.24057 -0.11123 0.95011 -0.26803 -0.15951 0.96701 -0.24590 -0.06650 0.22886 -0.93972 -0.25408 0.69707 -0.71635 0.03043 0.34472 -0.93786 0.03984 0.30116 -0.95354 0.00802 0.96142 -0.27485 0.01167 0.95765 -0.28791 0.00238 0.69707 -0.71635 0.03043 0.96752 -0.24290 0.07004 0.96702 0.23373 0.10120 0.44469 0.87275 0.20141 0.15007 0.94757 0.28211 0.42958 0.89466 0.12265 0.96712 0.23308 0.10170 0.88684 0.45184 0.09669 0.69363 0.69363 0.19431 0.98747 0.15637 0.02141 -0.04306 0.53891 0.84126 0.03964 -0.95154 0.30497 0.05119 -0.99105 0.12326 0.06791 -0.98506 0.15826 0.06820 -0.95935 0.27384 0.07970 -0.93736 0.33913 -0.49441 0.39951 0.77197 -0.32782 0.43681 0.83770 -0.55640 0.19138 0.80858 -0.48927 0.29566 0.82049 -0.50233 0.17192 0.84741 -0.55298 -0.00210 0.83319 -0.50809 0.02010 0.86107 -0.47014 -0.13561 0.87211 -0.57126 -0.19417 0.79747 -0.46738 -0.28853 0.83565 -0.55746 -0.37879 0.73875 -0.49937 -0.42215 0.75659 -0.47211 -0.57465 0.66850 -0.51142 -0.57864 0.63532 -0.33681 -0.78370 0.52189 -0.28175 -0.75512 0.59196 -0.50274 -0.79627 0.33645 -0.49604 -0.83495 0.23833 -0.27051 -0.84078 0.46894 -0.23889 -0.95596 0.17049 0.06009 -0.98988 0.12857 -0.11798 -0.84918 0.51476 -0.13613 -0.87777 0.45934 -0.66429 0.26477 0.69901 -0.75616 0.19727 0.62394 -0.77803 0.08772 0.62207 -0.75300 0.07392 0.65386 -0.77897 -0.06406 0.62378 -0.75248 -0.08532 0.65307 -0.77536 -0.21037 0.59545 -0.73978 -0.24487 0.62671 -0.77296 -0.33970 0.53585 -0.71150 -0.40537 0.57398 -0.79620 -0.45746 0.39598 -0.55052 0.40061 0.73242 -0.68191 0.33078 0.65237 -0.73343 0.25027 0.63201 -0.68429 0.16795 0.70960 -0.72662 0.07718 0.68269 -0.68414 -0.00184 0.72935 -0.72663 -0.08900 0.68124 -0.68424 -0.17252 0.70856 -0.72616 -0.25021 0.64038 -0.68473 -0.33252 0.64852 -0.72614 -0.39663 0.56161 -0.68535 -0.47470 0.55223 -0.72560 -0.52027 0.45035 -0.63436 -0.66518 0.39385 -0.63460 -0.66563 0.39270 0.98769 0.15640 -0.00000 0.98629 0.16504 -0.00142 0.89102 0.45397 0.00134 0.88271 0.46992 -0.00184 0.70710 0.70711 0.00185 0.73529 0.67767 0.01073 0.56909 0.82227 -0.00398 0.45395 0.89092 0.01408 0.43460 0.90058 0.00827 0.15641 0.98761 -0.01249 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 0.15273 -0.86617 0.47583 0.41173 -0.87359 0.25948 0.43261 -0.86653 0.24894 0.14765 -0.86322 0.48276 0.46055 -0.83055 0.31318 0.46618 -0.82821 0.31103 0.16245 -0.85018 0.50080 0.71431 -0.69421 0.08851 0.67849 -0.72532 0.11649 0.13722 -0.84064 0.52392 0.94860 -0.31649 -0.00114 0.79507 -0.56250 0.22686 0.77632 -0.58631 0.23146 0.51589 -0.74782 0.41787 0.52793 -0.74792 0.40237 0.18468 -0.82157 0.53937 0.97445 -0.15100 0.16627 0.84126 -0.41735 0.34367 0.62243 -0.62224 0.47476 0.33025 -0.76039 0.55924 0.66442 0.74733 0.00681 0.73383 0.67933 0.00088 0.49532 0.86869 0.00608 0.54640 0.83753 0.00037 0.30561 0.95216 0.00114 0.31502 0.94908 0.00033 0.10310 0.99467 0.00036 0.10691 0.99427 0.00051 0.10687 0.99427 0.00021 0.94257 -0.33229 0.03376 -0.00000 -0.00000 1.00000 -0.00001 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00016 -0.81915 0.57358 0.00016 -0.81916 0.57357 -0.00007 -0.81914 0.57359 -0.00019 -0.81917 0.57355 0.00008 -0.81918 0.57353 0.03478 -0.81474 0.57878 0.99596 -0.00422 0.08966 0.99606 0.00113 0.08868 0.99594 0.01078 0.08941 0.99566 0.00045 0.09303 0.99566 -0.00074 0.09309 0.99589 -0.02453 0.08723 0.99492 -0.04386 0.09057 0.99712 -0.07579 0.00000 0.98187 -0.15548 -0.10845 0.96339 -0.25512 0.08248 0.88983 -0.45348 0.05057 0.69629 -0.69631 0.17415 0.80014 -0.59240 -0.09401 0.64480 -0.76159 -0.06484 0.19818 -0.96944 0.14457 0.30897 -0.95094 0.01571 0.95817 -0.28538 0.02161 0.98726 -0.15633 -0.02955 0.96453 -0.24916 -0.08717 0.96824 -0.21178 -0.13291 0.96527 -0.22815 -0.12724 0.92566 -0.35400 -0.13359 0.88605 -0.45155 -0.10496 0.69377 -0.71869 -0.04660 0.70567 -0.70569 -0.06343 0.69571 -0.59806 -0.39790 0.64066 -0.69026 -0.33630 0.36744 -0.83266 -0.41433 0.29878 -0.91958 -0.25516 0.26435 -0.91036 -0.31837 -1.00000 -0.00000 0.00000 -1.00000 0.00003 0.00003 -1.00000 -0.00044 0.00026 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.45492 -0.69848 -0.55242 0.45573 -0.69856 -0.55166 0.62626 -0.65836 -0.41756 0.59609 -0.67308 -0.43777 0.39819 -0.76716 -0.50290 -0.43938 -0.71403 -0.54507 -0.60326 -0.71049 -0.36234 -0.51410 -0.73917 -0.43513 -0.45554 -0.75926 -0.46477 -0.39950 -0.78139 -0.47941 -0.00634 -0.89015 -0.45563 -0.00005 -0.87655 -0.48130 -0.00000 -0.81914 0.57360 -0.00019 -0.81919 0.57352 0.00014 -0.81912 0.57362 -0.00014 -0.81916 0.57357 0.00019 -0.81919 0.57352 -0.00014 -0.81912 0.57362 0.00014 -0.81916 0.57357 -0.68186 0.46553 -0.56422 -0.66333 0.36884 -0.65111 0.66333 0.36884 -0.65111 0.68186 0.46553 -0.56422 -0.98563 0.00128 -0.16894 0.98583 0.00128 -0.16773 -0.27402 0.79933 -0.53477 0.52064 0.85377 -0.00301 0.04210 -0.57464 -0.81732 0.11996 -0.67436 -0.72860 + + + + + + + + + + + + + + +

4 0 5 0 6 0 3 1 0 1 8 1 13 2 21 2 14 2 12 3 13 3 14 3 20 4 21 4 13 4 12 5 15 5 13 5 19 6 18 6 16 6 20 7 18 7 21 7 19 8 17 8 18 8 18 9 17 9 21 9 30 10 31 10 32 10 33 11 30 11 32 11 44 12 45 12 1 12 2 13 1 13 45 13 45 14 46 14 2 14 2 15 46 15 47 15 48 16 2 16 47 16 47 17 49 17 48 17 50 18 48 18 49 18 50 19 49 19 51 19 52 20 50 20 51 20 52 21 51 21 53 21 3 22 52 22 53 22 60 23 63 23 62 23 64 24 63 24 60 24 59 25 64 25 60 25 65 26 62 26 63 26 66 27 67 27 65 27 63 28 66 28 65 28 66 29 63 29 64 29 64 30 48 30 50 30 68 31 64 31 50 31 64 32 68 32 66 32 69 33 67 33 66 33 50 34 52 34 68 34 70 35 66 35 68 35 68 36 52 36 3 36 68 37 3 37 72 37 68 38 72 38 70 38 73 39 70 39 72 39 74 40 75 40 43 40 42 41 74 41 43 41 4 42 75 42 74 42 74 43 76 43 4 43 4 44 6 44 77 44 77 45 78 45 35 45 78 46 79 46 35 46 81 47 30 47 33 47 33 48 41 48 81 48 82 49 81 49 41 49 41 50 40 50 82 50 83 51 8 51 84 51 38 52 0 52 3 52 83 53 3 53 8 53 82 54 40 54 39 54 82 55 39 55 38 55 9 56 3 56 83 56 72 57 3 57 9 57 9 58 85 58 72 58 85 59 86 59 72 59 73 60 72 60 86 60 61 61 62 61 65 61 65 62 67 62 61 62 67 63 69 63 58 63 56 64 58 64 69 64 69 65 71 65 56 65 57 66 56 66 71 66 71 67 70 67 57 67 54 68 57 68 70 68 70 69 73 69 54 69 55 70 54 70 73 70 73 71 86 71 55 71 80 72 55 72 86 72 86 73 85 73 80 73 85 74 9 74 80 74 80 75 9 75 10 75 9 76 83 76 10 76 83 77 84 77 10 77 87 78 84 78 8 78 8 79 0 79 87 79 37 80 38 80 39 80 82 81 38 81 53 81 38 82 3 82 53 82 59 83 2 83 64 83 48 84 64 84 2 84 131 85 28 85 115 85 120 86 115 86 22 86 141 87 126 87 29 87 95 88 126 88 141 88 92 89 89 89 26 89 94 90 24 90 93 90 25 91 24 91 94 91 91 92 24 92 25 92 27 93 24 93 91 93 90 94 27 94 91 94 27 95 90 95 97 95 90 96 124 96 97 96 124 97 90 97 125 97 109 98 125 98 90 98 125 99 109 99 122 99 108 100 122 100 109 100 122 101 108 101 123 101 110 102 123 102 108 102 123 103 110 103 121 103 112 104 121 104 110 104 114 105 118 105 112 105 118 106 114 106 117 106 91 107 107 107 90 107 107 108 91 108 25 108 107 109 25 109 29 109 25 110 94 110 29 110 95 111 141 111 140 111 94 112 92 112 29 112 29 113 92 113 26 113 29 114 26 114 141 114 94 115 93 115 92 115 95 116 139 116 96 116 138 117 96 117 139 117 138 118 149 118 96 118 99 119 145 119 98 119 100 120 145 120 99 120 104 121 100 121 101 121 104 122 101 122 102 122 106 123 104 123 103 123 104 124 106 124 105 124 137 125 136 125 106 125 106 126 136 126 105 126 90 127 107 127 109 127 111 128 109 128 107 128 111 129 107 129 29 129 111 130 29 130 127 130 109 131 111 131 113 131 129 132 111 132 127 132 110 133 113 133 112 133 115 134 113 134 111 134 111 135 129 135 115 135 115 136 129 136 131 136 113 137 115 137 116 137 116 138 114 138 113 138 113 139 114 139 112 139 114 140 116 140 117 140 120 141 119 141 115 141 115 142 119 142 116 142 119 143 117 143 116 143 29 144 126 144 127 144 127 145 126 145 128 145 127 146 128 146 129 146 129 147 128 147 130 147 129 148 130 148 131 148 132 149 131 149 130 149 131 150 132 150 28 150 28 151 132 151 133 151 134 152 22 152 133 152 133 153 22 153 28 153 135 154 22 154 134 154 147 155 149 155 138 155 149 156 147 156 148 156 142 157 144 157 143 157 31 158 146 158 148 158 30 159 146 159 31 159 146 160 149 160 148 160 150 161 151 161 152 161 146 162 153 162 162 162 146 163 162 163 157 163 164 164 163 164 162 164 190 165 188 165 189 165 176 166 190 166 175 166 188 167 169 167 167 167 191 168 169 168 188 168 188 169 190 169 191 169 192 170 176 170 177 170 190 171 176 171 192 171 192 172 191 172 190 172 169 173 191 173 171 173 178 174 192 174 177 174 191 175 173 175 171 175 193 176 173 176 191 176 191 177 192 177 193 177 194 178 193 178 192 178 194 179 178 179 179 179 192 180 178 180 194 180 173 181 193 181 174 181 180 182 194 182 179 182 193 183 194 183 195 183 193 184 172 184 174 184 195 185 172 185 193 185 194 186 180 186 196 186 196 187 195 187 194 187 181 188 196 188 180 188 172 189 195 189 170 189 195 190 196 190 197 190 197 191 170 191 195 191 198 192 197 192 196 192 198 193 181 193 182 193 196 194 181 194 198 194 183 195 198 195 182 195 170 196 197 196 168 196 197 197 198 197 199 197 197 198 166 198 168 198 199 199 166 199 197 199 200 200 199 200 198 200 200 201 183 201 184 201 198 202 183 202 200 202 185 203 200 203 184 203 203 204 242 204 244 204 203 205 201 205 202 205 240 206 242 206 203 206 218 207 219 207 202 207 204 208 202 208 220 208 202 209 219 209 220 209 202 210 204 210 203 210 203 211 205 211 240 211 205 212 238 212 240 212 205 213 203 213 204 213 235 214 238 214 205 214 220 215 221 215 204 215 206 216 204 216 222 216 204 217 221 217 222 217 204 218 206 218 205 218 205 219 207 219 235 219 207 220 205 220 206 220 233 221 235 221 207 221 222 222 223 222 206 222 206 223 208 223 207 223 208 224 206 224 223 224 207 225 209 225 233 225 209 226 231 226 233 226 209 227 207 227 208 227 223 228 224 228 208 228 232 229 231 229 209 229 210 230 208 230 225 230 208 231 224 231 225 231 208 232 210 232 209 232 211 233 209 233 210 233 209 234 211 234 232 234 211 235 234 235 232 235 225 236 226 236 210 236 236 237 234 237 211 237 210 238 212 238 211 238 212 239 210 239 227 239 210 240 226 240 227 240 214 241 211 241 212 241 211 242 214 242 236 242 214 243 239 243 236 243 227 244 228 244 212 244 241 245 239 245 214 245 212 246 213 246 214 246 213 247 212 247 230 247 212 248 245 248 230 248 212 249 228 249 245 249 214 250 215 250 241 250 214 251 213 251 215 251 243 252 241 252 229 252 241 253 215 253 229 253 187 254 186 254 216 254 217 255 216 255 186 255 186 256 185 256 217 256 218 257 217 257 185 257 185 258 184 258 218 258 219 259 218 259 184 259 184 260 183 260 219 260 220 261 219 261 183 261 183 262 182 262 220 262 221 263 220 263 182 263 182 264 181 264 221 264 222 265 221 265 181 265 181 266 180 266 222 266 223 267 222 267 180 267 180 268 179 268 223 268 224 269 223 269 179 269 179 270 178 270 224 270 225 271 224 271 178 271 178 272 177 272 225 272 226 273 225 273 177 273 177 274 176 274 226 274 227 275 226 275 176 275 176 276 175 276 227 276 228 277 227 277 175 277 175 278 164 278 228 278 245 279 228 279 164 279 240 280 238 280 237 280 242 281 240 281 237 281 241 282 243 282 237 282 244 283 242 283 237 283 245 284 164 284 162 284 162 285 246 285 245 285 296 286 266 286 287 286 296 287 287 287 158 287 249 288 253 288 248 288 253 289 255 289 254 289 253 290 249 290 255 290 250 291 255 291 249 291 254 292 255 292 256 292 257 293 250 293 135 293 255 294 250 294 257 294 257 295 256 295 255 295 256 296 257 296 258 296 134 297 257 297 135 297 259 298 258 298 257 298 257 299 134 299 259 299 133 300 259 300 134 300 258 301 259 301 260 301 261 302 260 302 259 302 259 303 133 303 261 303 132 304 261 304 133 304 260 305 261 305 262 305 261 306 263 306 262 306 264 307 263 307 261 307 264 308 132 308 130 308 261 309 132 309 264 309 266 310 265 310 267 310 268 311 270 311 269 311 268 312 320 312 270 312 265 313 320 313 268 313 268 314 267 314 265 314 271 315 268 315 269 315 267 316 268 316 272 316 273 317 271 317 288 317 268 318 271 318 273 318 268 319 274 319 272 319 273 320 274 320 268 320 275 321 273 321 288 321 274 322 273 322 276 322 273 323 277 323 276 323 273 324 278 324 277 324 273 325 275 325 278 325 253 326 277 326 278 326 283 327 274 327 276 327 284 328 274 328 283 328 161 329 285 329 279 329 274 330 284 330 272 330 284 331 285 331 272 331 286 332 272 332 285 332 285 333 161 333 286 333 160 334 286 334 161 334 272 335 286 335 267 335 287 336 160 336 159 336 286 337 160 337 287 337 287 338 267 338 286 338 158 339 287 339 159 339 267 340 287 340 266 340 270 341 21 341 17 341 320 342 21 342 270 342 269 343 17 343 19 343 269 344 270 344 17 344 275 345 289 345 290 345 288 346 289 346 275 346 291 347 275 347 290 347 288 348 16 348 289 348 271 349 16 349 288 349 271 350 19 350 16 350 269 351 19 351 271 351 128 352 126 352 252 352 130 353 128 353 252 353 130 354 252 354 264 354 252 355 263 355 264 355 251 356 263 356 252 356 247 357 275 357 291 357 247 358 278 358 275 358 247 359 248 359 278 359 248 360 253 360 278 360 149 361 146 361 157 361 149 362 157 362 280 362 149 363 280 363 96 363 96 364 280 364 281 364 96 365 281 365 95 365 95 366 281 366 282 366 126 367 95 367 282 367 126 368 282 368 251 368 126 369 251 369 252 369 53 370 333 370 334 370 53 371 334 371 303 371 53 372 303 372 82 372 82 373 303 373 304 373 81 374 82 374 304 374 81 375 304 375 305 375 30 376 81 376 305 376 30 377 305 377 153 377 30 378 153 378 146 378 337 379 309 379 332 379 338 380 309 380 337 380 338 381 311 381 309 381 338 382 292 382 311 382 334 383 333 383 322 383 333 384 321 384 322 384 49 385 321 385 333 385 49 386 333 386 51 386 51 387 333 387 53 387 317 388 315 388 12 388 315 389 15 389 12 389 315 390 295 390 15 390 295 391 294 391 15 391 292 392 293 392 311 392 295 393 311 393 294 393 311 394 293 394 294 394 317 395 14 395 316 395 317 396 12 396 14 396 320 397 316 397 21 397 316 398 14 398 21 398 319 399 266 399 296 399 158 400 156 400 296 400 296 401 297 401 319 401 297 402 296 402 155 402 296 403 156 403 155 403 314 404 319 404 297 404 155 405 154 405 297 405 298 406 297 406 154 406 297 407 298 407 314 407 299 408 314 408 298 408 312 409 314 409 299 409 154 410 307 410 298 410 300 411 298 411 307 411 298 412 300 412 299 412 299 413 301 413 312 413 301 414 310 414 312 414 301 415 299 415 300 415 307 416 308 416 300 416 306 417 310 417 302 417 310 418 301 418 302 418 331 419 332 419 306 419 332 420 309 420 306 420 313 421 309 421 311 421 309 422 313 422 306 422 313 423 310 423 306 423 312 424 310 424 313 424 311 425 295 425 313 425 313 426 318 426 312 426 318 427 314 427 312 427 318 428 313 428 315 428 313 429 295 429 315 429 319 430 314 430 318 430 315 431 317 431 318 431 318 432 265 432 319 432 265 433 318 433 320 433 318 434 316 434 320 434 318 435 317 435 316 435 266 436 319 436 265 436 324 437 321 437 47 437 321 438 49 438 47 438 321 439 324 439 322 439 324 440 323 440 322 440 325 441 323 441 324 441 47 442 46 442 324 442 326 443 324 443 46 443 324 444 326 444 325 444 327 445 325 445 326 445 46 446 45 446 326 446 328 447 326 447 45 447 326 448 328 448 327 448 45 449 44 449 328 449 329 450 327 450 328 450 328 451 330 451 329 451 330 452 328 452 335 452 328 453 44 453 335 453 331 454 329 454 330 454 335 455 336 455 330 455 332 456 330 456 336 456 330 457 332 457 331 457 336 458 337 458 332 458 349 459 339 459 148 459 148 460 339 460 31 460 31 461 339 461 370 461 339 462 349 462 346 462 370 463 339 463 346 463 374 464 340 464 144 464 341 465 88 465 342 465 343 466 357 466 344 466 343 467 342 467 357 467 341 468 342 468 343 468 343 469 344 469 345 469 345 470 347 470 346 470 344 471 347 471 345 471 343 472 348 472 341 472 138 473 348 473 147 473 349 474 147 474 348 474 349 475 343 475 345 475 348 476 343 476 349 476 147 477 349 477 148 477 346 478 349 478 345 478 359 479 102 479 358 479 354 480 144 480 340 480 351 481 356 481 355 481 357 482 342 482 356 482 356 483 351 483 357 483 344 484 357 484 351 484 362 485 363 485 365 485 364 486 367 486 363 486 365 487 363 487 367 487 366 488 374 488 34 488 5 489 360 489 361 489 351 490 355 490 367 490 367 491 364 491 351 491 344 492 351 492 364 492 346 493 372 493 370 493 32 494 31 494 370 494 371 495 370 495 373 495 370 496 372 496 373 496 370 497 371 497 32 497 33 498 32 498 371 498 373 499 37 499 371 499 344 500 364 500 347 500 364 501 372 501 347 501 372 502 346 502 347 502 373 503 372 503 364 503 37 504 373 504 362 504 373 505 363 505 362 505 373 506 364 506 363 506 37 507 362 507 36 507 355 508 356 508 352 508 368 509 352 509 350 509 34 510 144 510 142 510 341 511 26 511 88 511 141 512 26 512 341 512 104 513 102 513 103 513 101 514 358 514 102 514 358 515 101 515 380 515 100 516 380 516 101 516 380 517 100 517 379 517 99 518 379 518 100 518 379 519 99 519 23 519 98 520 23 520 99 520 23 521 98 521 353 521 375 522 353 522 98 522 353 523 375 523 354 523 354 524 375 524 144 524 93 525 89 525 92 525 88 526 26 526 89 526 350 527 377 527 378 527 350 528 378 528 359 528 358 529 350 529 359 529 380 530 350 530 358 530 376 531 377 531 350 531 376 532 350 532 352 532 88 533 376 533 342 533 341 534 348 534 139 534 348 535 138 535 139 535 341 536 140 536 141 536 376 537 352 537 356 537 356 538 342 538 376 538 365 539 389 539 362 539 389 540 365 540 385 540 37 541 39 541 40 541 37 542 40 542 41 542 371 543 41 543 33 543 37 544 41 544 371 544 36 545 362 545 389 545 389 546 385 546 369 546 369 547 385 547 386 547 389 548 369 548 388 548 381 549 361 549 369 549 361 550 360 550 369 550 369 551 360 551 387 551 369 552 387 552 388 552 87 553 0 553 36 553 34 554 390 554 366 554 383 555 366 555 390 555 390 556 79 556 383 556 11 557 383 557 79 557 79 558 78 558 11 558 384 559 11 559 78 559 78 560 77 560 384 560 381 561 384 561 77 561 77 562 6 562 381 562 361 563 381 563 6 563 6 564 5 564 361 564 4 565 76 565 5 565 368 566 350 566 369 566 369 567 386 567 368 567 37 568 0 568 38 568 36 569 0 569 37 569 34 570 374 570 144 570 352 571 368 571 355 571 54 572 55 572 393 572 393 573 394 573 54 573 393 574 391 574 394 574 395 575 54 575 394 575 395 576 56 576 57 576 54 577 395 577 57 577 58 578 56 578 395 578 59 579 394 579 392 579 394 580 59 580 395 580 60 581 61 581 58 581 395 582 60 582 58 582 60 583 395 583 59 583 62 584 61 584 60 584 55 585 80 585 393 585 58 586 61 586 67 586 7 587 80 587 10 587 393 588 80 588 7 588 393 589 74 589 42 589 74 590 393 590 7 590 106 591 27 591 398 591 398 592 137 592 106 592 121 593 112 593 118 593 97 594 398 594 27 594 398 595 97 595 124 595 117 596 119 596 118 596 119 597 120 597 396 597 396 598 121 598 119 598 119 599 121 599 118 599 397 600 396 600 120 600 120 601 399 601 397 601 121 602 396 602 123 602 125 603 122 603 396 603 396 604 122 604 123 604 396 605 397 605 125 605 397 606 400 606 398 606 398 607 125 607 397 607 125 608 398 608 124 608 34 609 142 609 403 609 375 610 145 610 144 610 143 611 144 611 145 611 137 612 247 612 136 612 400 613 247 613 137 613 400 614 248 614 247 614 401 615 248 615 400 615 248 616 401 616 249 616 399 617 249 617 401 617 249 618 399 618 250 618 399 619 135 619 250 619 22 620 135 620 399 620 400 621 397 621 401 621 397 622 399 622 401 622 145 623 100 623 104 623 145 624 375 624 98 624 103 625 24 625 27 625 247 626 291 626 136 626 143 627 20 627 142 627 18 628 20 628 143 628 136 629 291 629 105 629 105 630 291 630 290 630 105 631 290 631 104 631 104 632 290 632 289 632 145 633 104 633 289 633 145 634 289 634 16 634 145 635 18 635 143 635 145 636 16 636 18 636 399 637 120 637 22 637 400 638 137 638 398 638 106 639 103 639 27 639 74 640 7 640 76 640 391 641 393 641 42 641 392 642 1 642 59 642 35 643 13 643 15 643 35 644 403 644 13 644 35 645 15 645 294 645 35 646 294 646 4 646 4 647 294 647 293 647 75 648 4 648 293 648 75 649 293 649 292 649 43 650 75 650 292 650 13 651 403 651 20 651 403 652 142 652 20 652 338 653 43 653 292 653 367 654 382 654 365 654 76 655 7 655 10 655 79 656 390 656 35 656 35 657 4 657 77 657 394 658 402 658 392 658 391 659 402 659 394 659 1 660 392 660 44 660 392 661 335 661 44 661 336 662 335 662 392 662 392 663 402 663 336 663 337 664 336 664 402 664 402 665 391 665 337 665 391 666 338 666 337 666 391 667 42 667 338 667 42 668 43 668 338 668 382 669 367 669 355 669 355 670 368 670 382 670 386 671 382 671 368 671 403 672 35 672 34 672 390 673 34 673 35 673 152 674 151 674 547 674 547 675 548 675 152 675 404 676 152 676 548 676 404 677 405 677 152 677 406 678 407 678 152 678 406 679 152 679 405 679 406 680 405 680 408 680 409 681 406 681 408 681 409 682 410 682 407 682 406 683 409 683 407 683 411 684 410 684 409 684 408 685 412 685 409 685 409 686 412 686 413 686 409 687 413 687 414 687 415 688 409 688 414 688 415 689 416 689 411 689 409 690 415 690 411 690 407 691 150 691 152 691 417 692 150 692 407 692 418 693 417 693 407 693 410 694 419 694 418 694 407 695 410 695 418 695 410 696 411 696 419 696 416 697 420 697 421 697 416 698 421 698 419 698 411 699 416 699 419 699 331 700 422 700 329 700 327 701 329 701 422 701 422 702 423 702 327 702 327 703 423 703 424 703 325 704 327 704 424 704 424 705 425 705 325 705 325 706 425 706 426 706 418 707 428 707 427 707 427 708 308 708 418 708 417 709 418 709 308 709 307 710 150 710 417 710 308 711 307 711 417 711 307 712 154 712 150 712 429 713 431 713 430 713 430 714 431 714 432 714 433 715 430 715 432 715 245 716 246 716 433 716 432 717 245 717 433 717 434 718 246 718 153 718 305 719 433 719 434 719 153 720 305 720 434 720 430 721 433 721 305 721 305 722 304 722 430 722 429 723 430 723 304 723 304 724 303 724 429 724 435 725 429 725 303 725 303 726 334 726 435 726 438 727 428 727 439 727 439 728 441 728 440 728 441 729 443 729 442 729 443 730 422 730 331 730 444 731 427 731 438 731 438 732 440 732 444 732 302 733 444 733 440 733 440 734 442 734 302 734 306 735 302 735 442 735 442 736 331 736 306 736 308 737 427 737 444 737 444 738 300 738 308 738 444 739 302 739 301 739 300 740 444 740 301 740 445 741 446 741 447 741 447 742 420 742 445 742 448 743 445 743 420 743 416 744 449 744 448 744 420 745 416 745 448 745 413 746 450 746 237 746 450 747 244 747 237 747 449 748 416 748 415 748 449 749 415 749 414 749 449 750 414 750 413 750 449 751 413 751 237 751 243 752 449 752 237 752 230 753 245 753 451 753 230 754 451 754 452 754 213 755 230 755 452 755 213 756 452 756 453 756 213 757 453 757 454 757 215 758 213 758 454 758 454 759 455 759 215 759 229 760 215 760 455 760 455 761 449 761 229 761 243 762 229 762 449 762 437 763 436 763 456 763 457 764 456 764 436 764 436 765 458 765 457 765 459 766 457 766 458 766 458 767 460 767 459 767 461 768 459 768 460 768 460 769 462 769 461 769 463 770 461 770 462 770 462 771 464 771 463 771 465 772 463 772 464 772 464 773 466 773 465 773 467 774 465 774 466 774 466 775 441 775 467 775 467 776 441 776 439 776 428 777 467 777 439 777 436 778 426 778 458 778 460 779 458 779 426 779 426 780 425 780 460 780 462 781 460 781 425 781 425 782 424 782 462 782 464 783 462 783 424 783 424 784 423 784 464 784 466 785 464 785 423 785 423 786 422 786 466 786 466 787 422 787 443 787 466 788 443 788 441 788 456 789 455 789 454 789 454 790 453 790 456 790 468 791 456 791 453 791 429 792 469 792 431 792 469 793 429 793 435 793 469 794 435 794 437 794 468 795 469 795 437 795 437 796 456 796 468 796 457 797 455 797 456 797 459 798 449 798 455 798 457 799 459 799 455 799 448 800 449 800 459 800 459 801 461 801 448 801 445 802 448 802 461 802 461 803 463 803 445 803 446 804 445 804 463 804 465 805 447 805 446 805 463 806 465 806 446 806 420 807 447 807 465 807 465 808 467 808 420 808 421 809 420 809 467 809 428 810 419 810 421 810 467 811 428 811 421 811 468 812 453 812 452 812 452 813 469 813 468 813 431 814 469 814 432 814 469 815 451 815 245 815 432 816 469 816 245 816 469 817 452 817 451 817 418 818 419 818 428 818 216 819 404 819 187 819 548 820 187 820 404 820 201 821 203 821 244 821 470 822 217 822 218 822 202 823 470 823 218 823 470 824 202 824 201 824 216 825 217 825 470 825 244 826 450 826 201 826 201 827 450 827 413 827 201 828 413 828 412 828 408 829 201 829 412 829 201 830 408 830 470 830 470 831 405 831 216 831 470 832 408 832 405 832 404 833 216 833 405 833 325 834 426 834 323 834 426 835 436 835 323 835 323 836 436 836 322 836 322 837 436 837 437 837 334 838 322 838 437 838 334 839 437 839 435 839 246 840 162 840 153 840 427 841 428 841 438 841 438 842 439 842 440 842 440 843 441 843 442 843 331 844 442 844 443 844 254 845 512 845 513 845 509 846 513 846 514 846 517 847 509 847 515 847 527 848 517 848 516 848 163 849 157 849 162 849 251 850 520 850 518 850 251 851 518 851 263 851 263 852 518 852 519 852 262 853 263 853 519 853 528 854 262 854 519 854 260 855 262 855 528 855 548 856 471 856 187 856 473 857 471 857 472 857 473 858 187 858 471 858 474 859 473 859 472 859 472 860 541 860 474 860 474 861 541 861 540 861 474 862 540 862 502 862 501 863 474 863 502 863 187 864 473 864 186 864 473 865 474 865 200 865 200 866 185 866 473 866 473 867 185 867 186 867 474 868 501 868 199 868 199 869 501 869 499 869 199 870 200 870 474 870 166 871 199 871 499 871 498 872 188 872 167 872 189 873 497 873 190 873 190 874 497 874 164 874 190 875 164 875 175 875 188 876 498 876 475 876 475 877 493 877 188 877 188 878 493 878 189 878 500 879 475 879 498 879 535 880 516 880 477 880 476 881 496 881 495 881 523 882 164 882 476 882 476 883 164 883 496 883 495 884 478 884 476 884 478 885 495 885 494 885 480 886 534 886 516 886 516 887 534 887 477 887 482 888 533 888 480 888 480 889 533 889 534 889 533 890 482 890 505 890 484 891 506 891 482 891 482 892 506 892 505 892 506 893 484 893 507 893 486 894 507 894 484 894 507 895 486 895 504 895 488 896 504 896 486 896 504 897 488 897 503 897 490 898 491 898 488 898 488 899 491 899 503 899 491 900 490 900 492 900 490 901 479 901 492 901 518 902 478 902 479 902 478 903 518 903 476 903 476 904 518 904 520 904 476 905 520 905 525 905 525 906 523 906 476 906 478 907 494 907 479 907 492 908 479 908 494 908 481 909 514 909 512 909 481 910 512 910 532 910 531 911 481 911 532 911 481 912 531 912 483 912 530 913 483 913 531 913 483 914 530 914 485 914 529 915 485 915 530 915 485 916 529 916 487 916 528 917 487 917 529 917 487 918 528 918 489 918 519 919 489 919 528 919 516 920 515 920 480 920 480 921 515 921 514 921 481 922 480 922 514 922 480 923 481 923 482 923 483 924 482 924 481 924 482 925 483 925 484 925 485 926 484 926 483 926 484 927 485 927 486 927 487 928 486 928 485 928 486 929 487 929 488 929 489 930 488 930 487 930 488 931 489 931 490 931 519 932 490 932 489 932 490 933 519 933 479 933 518 934 479 934 519 934 500 935 503 935 475 935 475 936 503 936 491 936 475 937 491 937 493 937 493 938 491 938 492 938 493 939 492 939 189 939 189 940 492 940 494 940 189 941 494 941 495 941 189 942 495 942 497 942 497 943 495 943 496 943 497 944 496 944 164 944 499 945 165 945 166 945 498 946 165 946 500 946 501 947 165 947 499 947 500 948 165 948 503 948 533 949 504 949 538 949 538 950 504 950 503 950 504 951 533 951 507 951 505 952 507 952 533 952 507 953 505 953 506 953 508 954 279 954 285 954 285 955 284 955 508 955 283 956 508 956 284 956 279 957 508 957 526 957 508 958 283 958 511 958 511 959 283 959 510 959 511 960 526 960 508 960 277 961 510 961 276 961 276 962 510 962 283 962 526 963 511 963 527 963 513 964 277 964 254 964 277 965 513 965 509 965 277 966 509 966 510 966 511 967 510 967 509 967 517 968 511 968 509 968 511 969 517 969 527 969 512 970 254 970 532 970 514 971 513 971 512 971 515 972 509 972 514 972 517 973 515 973 516 973 282 974 520 974 251 974 520 975 282 975 525 975 281 976 525 976 282 976 525 977 281 977 524 977 280 978 524 978 281 978 524 979 280 979 522 979 157 980 521 980 280 980 280 981 521 981 522 981 157 982 163 982 521 982 277 983 253 983 254 983 523 984 522 984 164 984 522 985 163 985 164 985 522 986 523 986 524 986 525 987 524 987 523 987 279 988 151 988 161 988 526 989 536 989 279 989 279 990 536 990 151 990 536 991 526 991 535 991 527 992 535 992 526 992 535 993 527 993 516 993 260 994 528 994 529 994 530 995 260 995 529 995 260 996 530 996 258 996 258 997 530 997 531 997 532 998 258 998 531 998 258 999 532 999 256 999 254 1000 256 1000 532 1000 533 1001 538 1001 534 1001 542 1002 477 1002 538 1002 538 1003 477 1003 534 1003 543 1004 477 1004 542 1004 545 1005 535 1005 543 1005 543 1006 535 1006 477 1006 535 1007 545 1007 536 1007 536 1008 545 1008 151 1008 547 1009 151 1009 545 1009 544 1010 542 1010 537 1010 537 1011 542 1011 538 1011 537 1012 539 1012 544 1012 544 1013 539 1013 540 1013 544 1014 540 1014 541 1014 472 1015 544 1015 541 1015 542 1016 544 1016 543 1016 546 1017 545 1017 544 1017 544 1018 545 1018 543 1018 544 1019 472 1019 546 1019 546 1020 472 1020 471 1020 546 1021 471 1021 547 1021 546 1022 547 1022 545 1022 548 1023 547 1023 471 1023 24 1024 103 1024 102 1024 24 1025 102 1025 359 1025 24 1026 359 1026 378 1026 24 1027 378 1027 377 1027 24 1028 377 1028 376 1028 24 1029 376 1029 88 1029 88 1030 89 1030 24 1030 5 1031 76 1031 10 1031 5 1032 10 1032 360 1032 10 1033 387 1033 360 1033 10 1034 388 1034 387 1034 10 1035 389 1035 388 1035 10 1036 36 1036 389 1036 36 1037 10 1037 87 1037 84 1038 87 1038 10 1038 89 1039 93 1039 24 1039 239 1040 241 1040 237 1040 236 1041 239 1041 237 1041 234 1042 236 1042 237 1042 232 1043 234 1043 237 1043 231 1044 232 1044 237 1044 231 1045 237 1045 233 1045 233 1046 237 1046 235 1046 235 1047 237 1047 238 1047 165 1048 168 1048 166 1048 165 1049 170 1049 168 1049 165 1050 172 1050 170 1050 165 1051 174 1051 172 1051 165 1052 173 1052 174 1052 165 1053 171 1053 173 1053 165 1054 169 1054 171 1054 165 1055 167 1055 169 1055 165 1056 498 1056 167 1056 165 1057 501 1057 502 1057 165 1058 502 1058 540 1058 165 1059 540 1059 539 1059 165 1060 539 1060 537 1060 165 1061 537 1061 538 1061 165 1062 538 1062 503 1062 381 1063 369 1063 384 1063 11 1064 384 1064 369 1064 11 1065 369 1065 383 1065 366 1066 383 1066 369 1066 366 1067 369 1067 374 1067 379 1068 350 1068 380 1068 23 1069 350 1069 379 1069 23 1070 353 1070 350 1070 353 1071 354 1071 350 1071 340 1072 350 1072 354 1072 340 1073 369 1073 350 1073 340 1074 374 1074 369 1074 150 1075 158 1075 151 1075 150 1076 156 1076 158 1076 150 1077 155 1077 156 1077 150 1078 154 1078 155 1078 151 1079 158 1079 159 1079 151 1080 159 1080 160 1080 151 1081 160 1081 161 1081 66 1082 70 1082 71 1082 66 1083 71 1083 69 1083 108 1084 113 1084 110 1084 108 1085 109 1085 113 1085 1 1086 2 1086 59 1086 22 1087 115 1087 28 1087 139 1088 140 1088 341 1088 95 1089 140 1089 139 1089 365 1090 382 1090 385 1090 382 1091 386 1091 385 1091

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_proximal/f_proximal_G1M5.dae b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_G1M5.dae new file mode 100644 index 0000000..a461aa4 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_G1M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:31.855069 + 2012-07-23T02:15:31.855082 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -7.17350 6.94911 4.21838 -9.93270 -1.15879 -0.00031 -9.92969 1.15514 -0.00031 -7.45360 6.66578 -0.00031 -6.19669 -7.61001 14.00068 -5.99999 -7.69760 7.99969 -5.93079 -7.72543 8.52069 -5.99999 -7.62085 -1.45521 -6.53730 7.42476 2.97619 -6.00000 7.62007 -1.44611 -5.99999 -0.00089 -0.00031 -4.99999 3.65198 9.71969 -3.55469 -9.23031 23.11969 -3.56699 -8.61560 18.55868 -1.76899 -9.59040 22.63068 -4.59092 -8.80456 23.59968 4.59459 -8.80456 23.59968 1.77266 -9.59040 22.63068 3.57066 -8.61560 18.55868 3.55836 -9.23031 23.11969 0.00406 -8.84559 18.22268 0.00406 -9.69028 22.44568 9.93636 -1.15879 -0.00031 5.00366 3.81254 9.73169 6.00366 -0.00089 -0.00031 6.00366 7.62007 -1.44611 7.14516 6.97814 3.97919 6.00366 -7.62085 -1.45522 9.93336 1.15514 -0.00031 7.45726 6.66578 -0.00031 -4.47209 7.99911 23.99968 -0.92010 7.99911 10.96068 -2.73450 7.99911 10.65468 -5.10259 7.94911 9.74469 -3.99999 -8.00089 9.99969 -5.00999 -7.96456 14.00168 -6.00000 6.94911 4.50619 -5.64640 6.94911 8.25268 -7.17349 6.94911 6.96669 -7.06460 7.04525 7.66968 -6.70469 7.31810 8.43568 -6.02019 7.68741 9.16469 -7.45360 -6.66756 -0.00031 -7.46809 -6.65131 13.99969 -9.91719 -1.28497 23.99968 -9.99999 -0.02064 23.99968 -9.92209 1.24482 23.99968 -9.68389 2.49335 23.99968 -9.63909 2.66125 -0.00031 -8.93994 4.00025 23.99968 -9.11909 4.10304 -0.00031 -8.39959 5.42557 23.99968 -8.38479 5.44841 -0.00031 -7.47299 6.64398 23.99968 -6.00000 -5.49870 -5.79131 -5.99999 -6.96596 -3.90192 -6.00000 -3.36071 -7.26061 -6.00000 -4.50038 -6.61501 -6.00000 -2.24851 -7.67811 -9.41220 -1.47532 -3.03941 -8.06000 -1.20361 -5.79601 -6.00000 -1.13267 -7.91981 -6.00000 -0.00089 -8.00031 -8.06000 1.20183 -5.79601 -9.41220 1.47352 -3.03941 -6.00000 1.13089 -7.91981 -7.35780 3.50247 -5.79601 -6.00000 2.24673 -7.67811 -8.51050 4.28110 -3.03941 -6.00000 3.35892 -7.26061 -6.00000 5.49692 -5.79131 -6.00000 4.49860 -6.61501 -6.62189 6.66578 -3.42181 -6.00000 6.66577 -4.42251 -6.78489 -7.26453 -0.00031 -6.83189 -7.23065 13.99969 -5.99999 -7.69760 -0.00031 -5.71839 -7.80180 9.02269 -5.38550 -7.89522 9.44169 -4.95869 -7.97119 9.75468 -5.99999 -7.34730 -2.89871 -5.57889 7.84294 23.99968 -6.59929 7.38662 23.99968 -6.00000 7.69581 -0.00031 -6.00000 7.69581 2.18159 -6.00000 7.34767 -2.89111 -6.00000 7.07516 -3.64421 -6.00000 7.31252 3.24219 6.00366 6.94911 4.50619 6.00366 7.31252 3.24219 6.00366 6.66577 -4.42252 6.00366 7.34767 -2.89111 6.66886 7.34083 3.17053 6.00366 7.69581 2.18159 6.00366 7.69581 -0.00031 6.60296 7.38662 23.99968 5.58256 7.84294 23.99968 6.00366 -7.18556 -3.39231 4.96236 -7.97119 9.75468 5.38916 -7.89522 9.44169 5.72206 -7.80180 9.02269 5.93446 -7.72543 8.52069 6.00366 -7.69760 7.99968 6.00366 -7.69760 -0.00031 6.20036 -7.61001 14.00068 6.83556 -7.23065 13.99968 6.78856 -7.26453 -0.00031 6.62556 6.66578 -3.42181 6.00366 4.49860 -6.61501 6.00366 5.49692 -5.79131 6.00366 3.35892 -7.26061 8.51416 4.28110 -3.03941 6.00366 2.24673 -7.67812 7.36146 3.50247 -5.79601 6.00366 1.13089 -7.91981 9.41586 1.47352 -3.03941 8.06366 1.20183 -5.79601 6.00366 -0.00089 -8.00031 6.00366 -1.13267 -7.91981 8.06366 -1.20361 -5.79601 9.41586 -1.47532 -3.03941 6.00366 -2.24851 -7.67812 6.00366 -4.50038 -6.61501 6.00366 -3.36071 -7.26061 6.00366 -6.66755 -4.42252 6.00366 -5.49870 -5.79131 7.47666 6.64398 23.99968 8.38846 5.44841 -0.00031 8.40326 5.42557 23.99968 9.12276 4.10304 -0.00031 8.94361 4.00025 23.99968 9.64276 2.66125 -0.00031 9.68756 2.49335 23.99968 9.92576 1.24482 23.99968 10.00366 -0.02064 23.99968 9.92086 -1.28497 23.99968 7.47176 -6.65131 13.99968 7.45726 -6.66756 -0.00031 5.10626 7.94911 9.74469 6.02386 7.68741 9.16469 7.06826 7.04525 7.66968 7.17716 6.94911 6.96669 0.00406 -8.00089 13.99868 3.58286 -8.00089 13.99868 4.00366 -8.00089 9.99969 5.01366 -7.96456 14.00168 0.00366 7.99911 23.99968 2.73816 7.99911 10.65468 0.92376 7.99911 10.96068 4.47576 7.99911 23.99968 -3.99999 -5.02735 37.82068 4.00366 -5.02735 37.82068 -3.99999 -5.00089 39.42268 -4.48079 7.99911 34.49768 -3.53979 -8.82177 32.40168 -2.34909 -9.28970 31.73368 -1.16229 -9.55490 31.35468 4.48446 7.99911 34.49768 0.00346 -9.63919 31.23468 1.16596 -9.55490 31.35468 2.35276 -9.28970 31.73368 3.54346 -8.82177 32.40168 0.00366 7.99911 44.99968 4.46387 7.99911 44.99968 4.00366 6.94911 44.99968 7.00366 -0.00089 44.99968 7.00366 -3.61239 46.59969 7.00366 3.37761 47.04568 7.00366 -3.04855 47.51268 7.00366 2.70194 47.87968 7.00366 -2.25983 48.23969 7.00366 1.82715 48.50168 7.00366 -1.30441 48.72868 7.00366 0.81734 48.86368 7.00366 -0.25282 48.94168 4.00366 6.69274 46.86967 4.00366 5.94276 48.60168 4.00366 4.75370 50.06868 4.00366 3.21449 51.16068 4.00366 1.43786 51.79867 4.00366 -0.44483 51.93568 4.00366 -2.29479 51.56068 4.00366 -3.97553 50.70068 4.00366 -5.36307 49.42068 4.00366 -6.35507 47.81468 4.00366 -6.87828 46.00168 4.00366 -6.89415 44.11368 4.00366 -6.40153 42.29169 6.60256 4.84007 47.50069 5.76706 6.37616 44.99969 5.50366 5.81689 48.00468 6.60256 3.15259 49.44267 5.50366 3.78892 50.33968 6.60256 0.76172 50.39468 5.50366 0.91560 51.48367 6.60256 -1.79926 50.14268 5.50366 -2.16214 51.18068 6.60256 -3.95910 48.74368 5.50366 -4.75780 49.49968 6.60256 -5.23604 46.50967 5.50366 -6.29241 46.81468 -6.59889 -5.34526 43.93867 -5.49999 -6.29241 46.81468 -6.59889 -5.23604 46.50967 -5.49999 -4.75780 49.49968 -6.59889 -3.95910 48.74368 -5.49999 -2.16214 51.18068 -6.59889 -1.79926 50.14268 -5.49999 0.91560 51.48367 -6.59889 0.76172 50.39468 -5.49999 3.78892 50.33968 -6.59889 3.15259 49.44267 -5.49999 5.81689 48.00468 -5.76339 6.37616 44.99968 -6.59889 4.84007 47.50069 -6.42709 5.71247 44.99968 -3.99999 -6.40153 42.29169 -3.99999 -6.89415 44.11368 -3.99999 -6.87828 46.00168 -3.99999 -6.35507 47.81468 -3.99999 -5.36307 49.42068 -3.99999 -3.97553 50.70068 -3.99999 -2.29479 51.56068 -3.99999 -0.44483 51.93568 -3.99999 1.43786 51.79867 -3.99999 3.21449 51.16068 -3.99999 4.75370 50.06868 -3.99999 5.94276 48.60168 -3.99999 6.69274 46.86967 -6.85319 4.87616 44.99968 -4.92709 6.80228 44.99968 -6.99999 -0.25282 48.94168 -6.99999 0.81734 48.86368 -6.99999 -1.30441 48.72868 -6.99999 1.82715 48.50168 -6.99999 -2.25983 48.23969 -6.99999 2.70194 47.87968 -6.99999 -0.00090 44.99968 -6.99999 -3.04855 47.51268 -6.99999 3.37761 47.04568 -6.99999 -3.61239 46.59969 -6.99999 3.80368 46.06168 -6.99999 -3.90969 45.56868 -6.99999 3.94911 44.99968 -6.99999 -3.91855 44.49568 -3.99999 6.94911 44.99968 -4.46019 7.99911 44.99968 8.35526 -5.50089 23.99968 8.73536 -4.87502 23.99968 9.28136 -3.73246 23.99968 9.67876 -2.52910 23.99968 7.43666 6.69810 34.49368 8.31437 5.81849 29.52985 8.89386 -4.46979 29.51968 8.76546 -4.19563 35.80267 9.26076 -2.79232 29.51968 8.91906 -2.27439 35.04568 9.45096 -1.09815 29.51968 8.96676 -0.33818 35.04568 9.47666 0.60681 29.51968 8.94576 1.60178 35.04568 9.33576 2.31798 29.51968 8.83896 3.55496 35.04568 8.30708 5.67738 34.68957 8.98616 4.04325 29.51968 0.00416 -10.00089 29.52368 0.00336 -10.00089 30.08768 2.93366 -9.56529 30.58668 3.43473 -9.48162 29.13079 3.49076 -9.37344 25.99968 1.45316 -9.89544 25.99968 4.39459 -9.10315 25.99968 4.41876 -8.98168 31.25368 6.33566 -7.76061 29.52368 5.84346 -8.13534 32.22368 7.02016 -7.12658 25.99968 7.14446 -7.03138 33.48969 8.27176 -5.67266 35.04868 8.54566 -5.26191 29.52368 4.68486 -8.14347 33.37068 5.30646 7.91391 34.49867 6.09576 7.66057 34.49867 6.81586 7.24997 34.49968 6.91396 -7.18597 33.86967 5.65496 -8.25206 32.34668 5.01416 -8.44358 32.71868 3.31336 -9.32459 31.45968 1.18046 -9.86343 30.69068 5.37426 -8.43667 25.99968 5.71986 -8.20649 23.99968 6.46616 -7.63259 23.99968 7.16186 -6.98424 23.99968 -7.15819 -6.98424 23.99968 -6.46249 -7.63259 23.99968 -5.71619 -8.20649 23.99968 -5.37059 -8.43667 25.99968 -1.17679 -9.86343 30.69068 -3.30969 -9.32459 31.45968 -5.01049 -8.44358 32.71868 -5.65129 -8.25206 32.34668 -6.31069 -7.37931 34.23868 -6.91029 -7.18597 33.86967 -7.85419 -6.04028 35.50568 -6.81219 7.24997 34.49968 -6.09209 7.66057 34.49867 -5.30279 7.91391 34.49867 -8.26809 -5.67266 35.04868 -4.68119 -8.14347 33.37068 -5.72309 -7.25891 34.63368 -8.54199 -5.26191 29.52368 -7.14079 -7.03138 33.48969 -7.01649 -7.12658 25.99968 -5.83979 -8.13534 32.22368 -6.33199 -7.76061 29.52368 -4.41509 -8.98168 31.25368 -4.39092 -9.10315 25.99968 -1.44949 -9.89544 25.99968 -3.48709 -9.37343 25.99968 -3.43106 -9.48162 29.13079 -2.92999 -9.56529 30.58668 0.00184 -10.00019 25.99969 -8.98249 4.04325 29.51968 -8.30341 5.67738 34.68957 -8.83529 3.55496 35.04568 -9.33209 2.31798 29.51968 -8.94209 1.60178 35.04568 -9.47299 0.60681 29.51968 -8.96309 -0.33818 35.04568 -9.44729 -1.09815 29.51968 -8.91539 -2.27439 35.04568 -9.25709 -2.79232 29.51968 -8.76179 -4.19563 35.80267 -8.89019 -4.46979 29.51968 -8.31070 5.81849 29.52985 -7.43299 6.69810 34.49368 -9.67509 -2.52910 23.99968 -9.27769 -3.73246 23.99968 -8.73169 -4.87502 23.99968 -8.35159 -5.50089 23.99968 0.00183 7.24200 10.60569 4.00366 4.25152 9.99969 5.65006 6.94911 8.25268 5.55006 6.94911 5.59469 3.89726 6.94911 9.21068 3.63686 6.94093 6.60969 1.98966 6.94911 9.80069 0.00366 6.94911 9.99969 0.00366 6.94911 7.84768 4.30636 7.24200 9.80469 1.47496 7.24200 10.60569 4.32487 5.06448 8.40697 3.63686 6.82538 6.40069 4.38886 6.06216 6.65668 4.68666 3.94590 9.87969 4.34936 4.09318 9.96969 3.63371 6.43688 6.43168 4.43506 6.73264 6.19568 4.49076 6.91366 6.33069 5.94346 3.82193 8.45469 6.00400 4.02117 8.04468 -6.00000 4.02117 8.04468 -5.93979 3.82193 8.45469 -5.54639 6.94911 5.59469 -4.54040 6.94911 6.46068 -3.63320 6.94093 6.60969 -4.45075 6.64691 6.24219 -4.34569 4.09222 9.96969 -3.63320 6.82538 6.40069 3.63321 5.95391 6.88068 -4.32395 5.11941 8.41997 -1.47129 7.24200 10.60569 -4.30269 7.24200 9.80469 -1.98599 6.94911 9.80069 -3.89359 6.94911 9.21068 -3.99999 4.25198 9.99969 4.47576 -8.00089 9.94269 6.00366 5.96671 5.62369 6.00366 4.86318 6.60168 6.00366 4.40365 7.39368 5.41736 3.62295 9.41469 5.73196 3.74311 9.00368 -5.72829 3.74311 9.00368 -3.63359 6.44435 6.42669 -4.68299 3.85204 9.87969 -5.41369 3.62295 9.41469 -4.38520 6.06216 6.65668 -3.63320 5.95391 6.88068 -5.99999 4.40365 7.39368 -5.99999 4.86318 6.60168 -6.00000 5.96671 5.62369 -4.47209 -8.00089 9.94269 -8.38479 -5.45020 -0.00031 -9.63909 -2.66304 -0.00031 -6.78409 -6.66756 -3.03501 -8.51050 -4.28290 -3.03941 -7.35780 -3.50425 -5.79601 7.36146 -3.50425 -5.79601 8.51416 -4.28290 -3.03941 6.78776 -6.66756 -3.03501 9.64276 -2.66304 -0.00031 8.38846 -5.45020 -0.00031 9.12276 -4.10482 -0.00031 -9.11909 -4.10482 -0.00031 -3.57919 -8.00089 13.99868 -3.99999 -5.43664 40.66869 -5.48459 -5.09962 40.93769 -5.49999 -4.73356 40.21569 -5.76329 -4.42797 39.42269 -6.42709 -4.46943 41.43969 -6.59809 -3.69701 40.57769 -6.42699 -3.76429 39.42269 -6.85319 -2.92798 39.42269 -6.68310 -3.81534 41.96069 -6.99999 -3.09028 42.53869 -6.99999 -2.49594 41.59168 -6.99999 -2.12557 40.53269 -6.99999 -2.00089 39.42269 -5.36349 -4.67315 38.32668 -6.19619 -4.04460 39.22469 -6.72699 -3.25133 38.74369 -6.99999 -2.00089 38.27869 -6.96549 -2.45480 38.42168 -8.53599 -1.46623 39.60468 -8.55289 -0.11087 39.43468 -8.54059 1.25595 39.55968 -8.50409 2.50568 39.95368 -8.45399 3.57721 40.56069 -6.76829 -5.70594 36.85169 -6.86009 -4.03110 39.22569 -6.92969 7.10944 44.99969 -6.11599 7.64029 44.99969 -5.93589 7.04911 44.99969 -5.49999 6.94911 44.99969 -5.31029 7.90772 44.99969 -4.88529 7.95342 44.99969 -7.19169 6.82799 43.78869 -8.19199 4.97673 41.65069 -7.71279 6.06131 42.71468 -7.49639 -5.59217 36.77569 -7.60349 -3.56948 39.46268 -8.12469 -5.26918 36.55169 -8.06229 -2.97472 39.64069 -8.56689 -4.78127 36.21169 -8.39929 -2.25591 39.68868 -7.28129 -6.21366 35.90269 -6.99999 1.68717 38.19369 -6.99999 0.45891 38.00269 -6.99999 -0.78335 38.03168 -6.99999 2.86304 38.59969 -6.99999 3.94911 39.20568 -6.99999 -3.63839 43.45969 -5.03399 6.76527 43.41169 -5.49999 6.54719 42.67069 -5.93590 6.24091 41.72169 -6.39679 5.75341 40.92669 -6.83869 4.91954 39.95969 -7.08054 5.94669 41.49869 -7.43409 4.97597 40.42869 -8.19199 4.02715 40.55369 -7.43409 3.77077 39.39269 -8.19199 2.84199 39.71668 -7.43409 2.35678 38.66769 -8.19199 1.49065 39.18868 -7.43409 0.81253 38.29169 -8.19199 0.05167 39.00069 -7.43409 -0.77680 38.28768 -8.19199 -1.39001 39.16369 -7.43409 -2.32320 38.65369 -6.72699 6.57048 42.44669 -6.72699 6.92842 43.70069 -5.49999 -6.42367 43.72469 5.48826 -5.09962 40.93769 6.43076 -4.46943 41.43969 5.50366 -6.42367 43.72469 6.60256 -5.34526 43.93868 6.85686 4.87616 44.99969 6.73066 6.92842 43.70069 6.73066 -3.25133 38.74369 6.73066 6.57048 42.44669 7.08421 5.94669 41.49869 7.43776 -2.32320 38.65369 8.19566 -1.39001 39.16369 7.43776 -0.77680 38.28768 8.19566 0.05167 39.00069 7.43776 0.81253 38.29169 8.19566 1.49065 39.18868 7.43776 2.35678 38.66769 8.19566 2.84199 39.71668 7.43776 3.77077 39.39269 8.19566 4.02715 40.55369 7.43776 4.97597 40.42869 6.84236 4.91954 39.95969 6.40046 5.75341 40.92669 6.43076 5.71247 44.99969 5.93956 6.24091 41.72169 5.50366 6.54719 42.67069 5.03766 6.76527 43.41169 4.93076 6.80228 44.99969 7.00366 3.80368 46.06168 7.00366 -3.90969 45.56869 7.00366 3.94911 44.99969 7.00366 -3.91855 44.49569 7.00366 -3.63839 43.45969 7.00366 3.94911 39.20568 7.00366 2.86304 38.59969 7.00366 -0.78335 38.03168 7.00366 0.45891 38.00269 7.00366 1.68717 38.19369 6.31436 -7.37931 34.23869 8.12836 -5.26918 36.55169 7.85786 -6.04028 35.50568 7.28496 -6.21366 35.90269 8.40296 -2.25591 39.68868 8.57056 -4.78127 36.21169 8.06596 -2.97472 39.64069 7.60716 -3.56948 39.46268 6.99346 -4.00149 39.23769 7.50006 -5.59217 36.77569 7.71646 6.06131 42.71468 8.19566 4.97673 41.65069 7.19536 6.82799 43.78869 4.88896 7.95342 44.99969 5.31396 7.90772 44.99969 5.93956 7.04911 44.99969 6.11966 7.64029 44.99969 6.93336 7.10944 44.99969 5.72676 -7.25891 34.63369 6.77196 -5.70594 36.85169 8.45766 3.57721 40.56069 8.50776 2.50568 39.95368 8.54426 1.25595 39.55968 8.55656 -0.11086 39.43468 8.53966 -1.46623 39.60468 7.00366 -2.00089 38.27869 6.96916 -2.45480 38.42168 6.19986 -4.04460 39.22469 5.36716 -4.67315 38.32668 7.00366 -2.31088 41.06269 7.00366 -2.00089 39.42269 7.00366 -2.49594 41.59168 7.00366 -3.09028 42.53869 6.75609 -3.81534 41.96069 6.85686 -2.92798 39.42269 6.43066 -3.76429 39.42269 6.60176 -3.69701 40.57769 5.76696 -4.42797 39.42269 5.50366 -4.73356 40.21569 4.00366 -5.00089 39.42269 4.00366 -5.43664 40.66869 + + + + + + + + + + -0.37992 -0.92502 0.00105 -0.61397 0.78924 -0.01224 -0.07593 -0.97679 -0.20031 -0.22994 -0.96457 -0.12938 -0.08134 -0.97733 -0.19549 -0.42429 -0.89757 -0.11982 0.42429 -0.89757 -0.11983 0.08144 -0.97732 -0.19548 0.22994 -0.96457 -0.12938 0.07611 -0.97679 -0.20023 0.00000 1.00000 -0.00000 -0.02010 0.99979 -0.00262 -0.99786 -0.06535 0.00030 -1.00000 0.00130 -0.00287 -0.99811 0.06144 0.00009 -0.98228 0.18741 -0.00039 -0.98189 0.18945 -0.00051 -0.89668 0.44268 0.00142 -0.94065 0.33926 0.00847 -0.93503 0.35447 0.00850 -0.87777 0.47908 -0.00009 -0.79597 0.60534 0.00009 -0.79427 0.60756 -0.00009 -0.73062 -0.00000 -0.68279 -0.89780 -0.00000 -0.44040 -0.89780 -0.00000 -0.44040 -0.71610 0.04952 -0.69624 -0.75711 0.13830 -0.63848 -0.69777 0.21297 -0.68393 -0.85617 0.26132 -0.44574 -0.92192 0.33250 -0.19878 -0.93821 0.30132 -0.17023 -0.85683 0.27518 -0.43602 -0.69725 0.25192 -0.67110 -0.86835 0.47394 -0.14612 -0.73749 0.50314 -0.45051 -0.77877 0.59570 -0.19660 -0.78420 0.59050 -0.19062 -0.73536 0.51102 -0.44509 -0.72246 0.52579 -0.44899 -0.67329 -0.73938 -0.00047 -0.66596 -0.74598 0.00018 -0.51275 -0.85854 0.00036 -0.48310 -0.87557 -0.00131 -0.34471 -0.93870 0.00305 -0.28004 -0.95995 0.00846 -0.17483 -0.98460 -0.00057 -0.13972 0.99019 0.00271 -0.27312 0.96198 -0.00196 -0.40823 0.91287 0.00257 -0.47428 0.88037 -0.00066 -0.45040 0.89283 0.00000 -0.71115 0.70304 0.00000 -0.57790 0.81555 -0.03005 -0.60493 0.79627 0.00059 -0.67564 0.73722 0.00384 -0.57764 0.81518 -0.04270 -0.64644 0.74661 -0.15714 -0.67682 0.72341 -0.13637 -0.59520 0.75563 -0.27343 -0.59953 0.70834 -0.37259 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.02819 0.94010 0.33974 0.01436 0.93130 0.36396 0.12973 0.97951 -0.15405 -0.64764 0.76194 0.00226 -0.71191 0.70227 0.00006 -0.98581 0.00000 -0.16786 -0.97140 0.18743 -0.14577 0.97140 0.18743 -0.14578 0.98565 0.00000 -0.16881 0.71191 0.70227 0.00006 0.64764 0.76194 0.00226 0.00494 0.91350 0.40681 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 0.54765 0.76436 -0.34035 0.67682 0.72341 -0.13637 0.64644 0.74661 -0.15714 0.57764 0.81518 -0.04270 0.67564 0.73722 0.00384 0.57791 0.81555 -0.02994 0.61966 0.78477 -0.01300 0.70339 0.71081 -0.00063 0.47080 0.88224 -0.00000 0.40823 0.91287 0.00257 0.27312 0.96198 -0.00196 0.13972 0.99019 0.00271 0.17483 -0.98460 -0.00057 0.28004 -0.95995 0.00846 0.34471 -0.93870 0.00305 0.37991 -0.92502 0.00105 0.48310 -0.87557 -0.00131 0.51275 -0.85854 0.00036 0.66596 -0.74598 0.00018 0.67329 -0.73937 -0.00047 0.72246 0.52579 -0.44899 0.73536 0.51102 -0.44509 0.78420 0.59050 -0.19063 0.77877 0.59570 -0.19660 0.73749 0.50314 -0.45051 0.86835 0.47394 -0.14612 0.69725 0.25192 -0.67110 0.85683 0.27518 -0.43602 0.93821 0.30132 -0.17023 0.92192 0.33250 -0.19878 0.85617 0.26132 -0.44574 0.69777 0.21297 -0.68393 0.75711 0.13830 -0.63848 0.71610 0.04952 -0.69624 0.89780 0.00000 -0.44040 0.89780 0.00000 -0.44040 0.73062 0.00000 -0.68279 0.79427 0.60756 -0.00009 0.79597 0.60534 0.00009 0.87777 0.47908 -0.00009 0.93503 0.35448 0.00850 0.94065 0.33926 0.00847 0.89668 0.44268 0.00142 0.98189 0.18945 -0.00051 0.98228 0.18741 -0.00039 0.99809 0.06144 -0.00571 1.00000 0.00130 0.00031 0.99786 -0.06535 0.00030 0.02010 0.99979 -0.00262 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 -0.99986 0.01651 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 0.00000 1.00000 0.69946 0.68907 0.18956 0.22891 0.89330 0.38681 0.96248 0.21083 0.17081 0.95946 0.21276 0.18488 0.69693 0.54133 0.47038 0.36003 0.72476 0.58745 0.30851 0.71817 0.62374 0.69716 0.54127 0.47010 0.96751 0.14650 0.20605 0.21934 0.56453 0.79573 0.95759 0.09723 0.27122 0.96142 0.10177 0.25557 0.69721 0.26520 0.66601 0.69718 0.26518 0.66605 0.30072 0.32233 0.89759 0.34441 0.34727 0.87223 0.96702 0.01852 0.25402 0.22851 0.07066 0.97097 0.69718 -0.07020 0.71345 0.95018 -0.06188 0.30550 0.96407 -0.02601 0.26437 0.36233 -0.09132 0.92757 0.69714 -0.07024 0.71349 0.25693 -0.19200 0.94717 0.96537 -0.11886 0.23224 0.69711 -0.38978 0.60175 0.95840 -0.15517 0.23956 0.69719 -0.38969 0.60172 0.42922 -0.41142 0.80405 0.25228 -0.52600 0.81221 0.22867 -0.66008 0.71554 0.96700 -0.17269 0.18735 0.69715 -0.62243 0.35577 0.96242 -0.23105 0.14269 0.95943 -0.24477 0.13991 0.69712 -0.62246 0.35577 0.36001 -0.79374 0.49028 0.30840 -0.82588 0.47203 0.21950 -0.93736 0.27051 -0.95765 -0.28792 0.00238 -0.69707 -0.71635 0.03043 -0.96752 -0.24290 0.07004 -0.21950 -0.93736 0.27051 -0.30839 -0.82588 0.47203 -0.36001 -0.79374 0.49028 -0.69712 -0.62246 0.35577 -0.95943 -0.24477 0.13991 -0.96242 -0.23105 0.14269 -0.69715 -0.62243 0.35577 -0.96700 -0.17269 0.18735 -0.22867 -0.66008 0.71554 -0.25228 -0.52600 0.81221 -0.42922 -0.41142 0.80405 -0.69719 -0.38969 0.60172 -0.95840 -0.15517 0.23956 -0.69711 -0.38978 0.60175 -0.96537 -0.11886 0.23224 -0.25693 -0.19200 0.94717 -0.69714 -0.07024 0.71349 -0.36233 -0.09132 0.92757 -0.96407 -0.02601 0.26437 -0.95018 -0.06188 0.30550 -0.69718 -0.07020 0.71345 -0.22851 0.07066 0.97097 -0.96702 0.01852 0.25402 -0.34441 0.34727 0.87223 -0.30072 0.32233 0.89759 -0.69718 0.26518 0.66605 -0.69721 0.26520 0.66601 -0.96142 0.10177 0.25557 -0.95759 0.09723 0.27122 -0.21934 0.56453 0.79573 -0.96751 0.14650 0.20605 -0.69716 0.54127 0.47010 -0.30851 0.71817 0.62374 -0.36003 0.72476 0.58745 -0.69693 0.54133 0.47038 -0.95946 0.21276 0.18488 -0.96248 0.21083 0.17081 -0.22891 0.89330 0.38681 -0.96702 0.23373 0.10120 -0.69946 0.68907 0.18956 -0.44469 0.87275 0.20141 -0.15007 0.94757 0.28211 -0.42958 0.89466 0.12265 -0.95018 0.30880 0.04245 -0.69362 0.69364 0.19431 -0.98747 0.15637 0.02141 -0.84480 0.43042 0.31789 -0.00000 -0.96534 -0.26100 -0.00000 -0.96534 -0.26100 -0.00000 -0.99996 0.00841 -0.00000 -0.99996 0.00841 -0.00000 -0.96079 0.27727 -0.00000 -0.96079 0.27727 -0.00000 -0.85078 0.52551 -0.00000 -0.85078 0.52551 -0.00000 -0.67805 0.73502 0.00000 -0.67805 0.73502 0.00000 -0.45551 0.89023 0.00000 -0.45551 0.89023 0.00000 -0.19866 0.98007 0.00000 -0.19866 0.98007 -0.00000 0.07258 0.99736 0.00000 0.07258 0.99736 0.00000 0.33797 0.94116 -0.00000 0.33797 0.94116 -0.00000 0.57862 0.81559 0.00000 0.57862 0.81559 0.00000 0.77686 0.62968 0.00000 0.77686 0.62968 0.00000 0.91766 0.39736 0.00000 0.91766 0.39736 0.00000 0.99073 0.13583 0.00000 0.99073 0.13583 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.97499 0.22226 -0.00000 -0.92453 0.38110 0.90226 -0.43116 0.00574 0.97649 -0.21358 0.02928 0.97612 -0.21350 0.04000 0.94802 -0.31308 0.05686 0.99635 -0.05341 0.06661 0.97763 -0.19024 0.08966 0.99134 -0.11130 0.06976 0.99120 -0.11128 0.07172 0.99558 -0.02453 0.09061 0.99409 -0.06510 0.08683 0.99589 -0.01501 0.08933 0.99520 -0.01500 0.09672 0.99424 0.06120 0.08796 0.99554 0.01078 0.09370 0.99338 0.08180 0.08071 0.99256 0.08173 0.09020 0.97998 0.18697 0.06840 0.99552 0.05444 0.07731 0.96826 0.24794 0.03155 0.97796 0.19817 0.06582 0.89663 0.44266 -0.01036 0.97777 0.19813 0.06861 0.14700 -0.98914 0.00021 0.24807 -0.96831 -0.02902 0.07172 -0.99371 0.08595 0.14963 -0.98874 -0.00030 0.14904 -0.98882 -0.00554 0.28639 -0.95770 -0.02796 0.34030 -0.93819 0.06320 0.56248 -0.82680 0.00516 0.50451 -0.86193 0.05048 0.53463 -0.84366 -0.04914 0.51263 -0.85823 -0.02566 0.62265 -0.78225 -0.01980 0.64109 -0.76740 0.01036 0.79702 -0.60172 -0.05190 0.74900 -0.66246 -0.01212 0.74880 -0.66228 0.02629 0.91538 -0.40230 0.01547 0.61539 -0.78641 0.05336 0.57003 -0.81556 0.09967 0.12475 -0.87586 0.46616 0.51875 -0.85477 -0.01612 0.37649 -0.90862 0.18073 0.32485 -0.92285 0.20694 0.13312 -0.88748 0.44120 0.09621 -0.88767 0.45032 0.31482 -0.94120 0.12258 0.06742 -0.90426 0.42164 0.08306 -0.90964 0.40702 0.17554 -0.96597 0.18998 0.02220 -0.90647 0.42168 0.16166 -0.98259 -0.09158 0.06493 -0.99436 -0.08387 0.07172 -0.99366 -0.08660 0.20896 -0.97695 -0.04364 0.24766 -0.96673 -0.06404 0.60929 -0.79232 0.03169 0.62268 -0.78228 0.01757 0.68177 -0.73156 -0.00376 0.47456 -0.88001 -0.01928 0.56160 -0.82551 -0.05591 0.40991 -0.90871 -0.07890 0.28626 -0.95728 -0.04085 0.79561 0.60506 -0.03020 0.93501 0.35447 -0.01016 0.93521 0.35396 -0.00997 0.93524 0.35385 0.01100 0.75898 0.65084 0.01887 0.77910 -0.62681 0.01059 0.77326 -0.63409 0.00078 0.85470 -0.51907 -0.00700 0.91546 -0.40240 0.00325 -0.00000 1.00000 0.00000 0.10310 0.99467 -0.00009 0.13972 0.99019 -0.00302 0.30561 0.95215 0.00160 0.40823 0.91287 -0.00410 0.49533 0.86870 0.00126 0.64764 0.76194 -0.00322 0.66439 0.74739 -0.00132 0.70513 0.70908 -0.00097 -0.70513 0.70908 -0.00097 -0.66439 0.74739 -0.00132 -0.64764 0.76194 -0.00322 -0.49533 0.86870 0.00126 -0.40823 0.91287 -0.00410 -0.30561 0.95215 0.00160 -0.13972 0.99019 -0.00302 -0.10310 0.99467 -0.00009 0.00000 1.00000 0.00000 -0.91546 -0.40240 0.00325 -0.85470 -0.51907 -0.00700 -0.77326 -0.63409 0.00078 -0.77910 -0.62681 0.01059 -0.75898 0.65084 0.01887 -0.93524 0.35385 0.01100 -0.93521 0.35396 -0.00997 -0.93501 0.35447 -0.01016 -0.79561 0.60506 -0.03020 -0.28626 -0.95728 -0.04085 -0.40991 -0.90871 -0.07890 -0.56160 -0.82551 -0.05591 -0.47456 -0.88001 -0.01928 -0.68177 -0.73156 -0.00376 -0.62268 -0.78228 0.01757 -0.60929 -0.79232 0.03169 -0.24766 -0.96673 -0.06404 -0.20896 -0.97695 -0.04364 -0.07172 -0.99365 -0.08669 -0.06477 -0.99437 -0.08389 -0.16161 -0.98253 -0.09231 -0.02214 -0.90647 0.42168 -0.17554 -0.96597 0.18998 -0.08306 -0.90964 0.40702 -0.06742 -0.90426 0.42164 -0.31482 -0.94120 0.12258 -0.09621 -0.88767 0.45032 -0.13312 -0.88748 0.44120 -0.32485 -0.92285 0.20694 -0.37649 -0.90862 0.18073 -0.51875 -0.85477 -0.01612 -0.12475 -0.87586 0.46616 -0.15273 -0.86617 0.47583 -0.41173 -0.87359 0.25948 -0.57003 -0.81556 0.09967 -0.61539 -0.78642 0.05336 -0.43261 -0.86653 0.24894 -0.14765 -0.86322 0.48276 -0.71431 -0.69421 0.08851 -0.67849 -0.72532 0.11649 -0.94257 -0.33229 0.03376 -0.91537 -0.40231 0.01547 -0.74880 -0.66228 0.02629 -0.74900 -0.66246 -0.01212 -0.79702 -0.60172 -0.05190 -0.64109 -0.76740 0.01036 -0.62265 -0.78225 -0.01980 -0.51263 -0.85823 -0.02566 -0.53463 -0.84366 -0.04914 -0.50451 -0.86193 0.05048 -0.56248 -0.82680 0.00516 -0.34030 -0.93819 0.06320 -0.28639 -0.95770 -0.02796 -0.14884 -0.98885 -0.00561 -0.14945 -0.98877 -0.00010 -0.07172 -0.99371 0.08595 -0.24807 -0.96831 -0.02902 -0.14692 -0.98915 -0.00021 -0.97777 0.19813 0.06861 -0.89663 0.44266 -0.01036 -0.97796 0.19817 0.06582 -0.96826 0.24794 0.03155 -0.99552 0.05444 0.07731 -0.97998 0.18697 0.06840 -0.99256 0.08173 0.09020 -0.99338 0.08180 0.08071 -0.99554 0.01078 0.09370 -0.99424 0.06120 0.08796 -0.99520 -0.01500 0.09672 -0.99589 -0.01501 0.08933 -0.99409 -0.06510 0.08683 -0.99558 -0.02453 0.09061 -0.99120 -0.11128 0.07172 -0.99134 -0.11130 0.06976 -0.97763 -0.19024 0.08966 -0.99635 -0.05341 0.06661 -0.94802 -0.31308 0.05686 -0.97612 -0.21350 0.04000 -0.97649 -0.21358 0.02928 -0.90226 -0.43116 0.00574 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.90036 -0.43515 0.00000 0.90036 -0.43515 0.00000 0.00000 -1.00000 -0.00000 1.00000 -0.00000 0.02992 0.99953 -0.00614 -0.04897 0.99855 -0.02238 -0.00000 1.00000 0.00000 -0.00094 0.99999 -0.00305 -0.00000 1.00000 0.00000 0.00167 1.00000 -0.00170 -0.18127 0.92582 -0.33166 -0.33605 0.30453 -0.89125 -0.24187 0.45887 -0.85495 -0.12672 0.90338 -0.40970 -0.10729 0.91905 -0.37927 -0.15739 0.32299 -0.93322 -0.03628 0.93144 -0.36209 -0.98931 0.00059 -0.14580 -0.08645 0.00000 -0.99626 -0.25621 -0.07481 -0.96372 -0.46284 0.61705 -0.63642 -0.12748 0.61787 -0.77588 -0.12905 0.86783 -0.47980 0.52405 0.59562 -0.60877 0.08703 0.87183 -0.48201 0.02729 0.59100 -0.80621 0.08645 0.00000 -0.99626 0.98943 0.00056 -0.14501 -0.00000 -0.07954 -0.99683 -0.00000 0.87515 -0.48385 -0.00000 0.87515 -0.48385 0.03621 0.93145 -0.36205 0.15739 0.32299 -0.93322 0.10729 0.91905 -0.37927 0.12672 0.90337 -0.40970 0.24187 0.45887 -0.85495 0.33605 0.30453 -0.89125 0.18127 0.92582 -0.33166 0.00000 0.99998 -0.00661 -0.00167 1.00000 -0.00170 0.00000 1.00000 -0.00000 0.00094 0.99999 -0.00305 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00938 0.99995 -0.00221 0.00000 1.00000 -0.00000 -0.03447 -0.56461 -0.82463 -0.02257 -0.86820 -0.49570 -0.00000 -1.00000 -0.00000 -0.02658 0.99964 -0.00251 0.00811 0.99992 0.00963 0.40679 -0.91352 -0.00000 -0.99129 0.00002 -0.13166 -0.93308 -0.00133 -0.35966 -0.92096 0.00015 -0.38965 -0.79403 -0.00032 -0.60788 -0.78301 0.00046 -0.62201 -0.60834 -0.00037 -0.79368 -0.59143 0.00050 -0.80636 -0.42313 -0.00028 -0.90607 -0.36047 0.00144 -0.93277 -0.25804 -0.00054 -0.96613 -0.11987 0.00096 -0.99279 -0.00342 0.94046 0.33987 0.10258 0.95600 0.27486 -0.54107 -0.72740 -0.42205 -0.54206 -0.72466 -0.42548 -0.54151 -0.72194 -0.43078 -0.56924 -0.75410 -0.32757 -0.66245 -0.49685 -0.56063 -0.35061 -0.80805 -0.47342 -0.84565 -0.40086 -0.35240 -0.38367 0.78835 -0.48095 -0.40881 0.39255 -0.82388 -0.12973 0.97951 -0.15405 -0.49552 -0.46867 -0.73130 -0.42845 -0.22367 -0.87544 0.44674 -0.23178 -0.86412 0.49661 -0.46421 -0.73341 0.23270 0.87645 -0.42153 0.17952 0.79930 -0.57349 0.40881 0.39255 -0.82388 0.38366 0.78835 -0.48095 0.84565 -0.40086 -0.35240 0.33841 -0.82490 -0.45279 0.01364 -0.88159 -0.47182 0.67437 -0.48974 -0.55261 0.58626 -0.73899 -0.33195 0.56054 -0.70950 -0.42709 0.56140 -0.71351 -0.41920 0.56043 -0.71635 -0.41564 -0.06761 0.95887 0.27568 0.11987 0.00096 -0.99279 0.25818 -0.00054 -0.96610 0.36048 0.00146 -0.93277 0.45114 -0.00108 -0.89245 0.59133 -0.00033 -0.80643 0.59343 -0.00043 -0.80488 0.78301 0.00046 -0.62201 0.79403 -0.00032 -0.60788 0.92096 0.00015 -0.38965 0.93308 -0.00133 -0.35966 0.99129 0.00002 -0.13166 -0.40679 -0.91352 0.00000 -0.00625 -0.86521 -0.50136 -0.00000 -0.87912 -0.47660 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 0.00000 -1.00000 -0.11875 -0.67600 -0.72728 -0.69945 -0.56446 -0.43835 -0.73008 -0.52935 -0.43217 -0.79534 -0.57614 -0.18840 -0.73749 -0.50314 -0.45051 -0.66333 -0.36884 -0.65111 -0.68186 -0.46553 -0.56422 -0.69725 -0.25192 -0.67110 -0.93527 -0.30038 -0.18722 -0.85683 -0.27518 -0.43602 -0.70722 -0.14967 -0.69097 -0.71631 -0.21863 -0.66264 -0.85617 -0.26132 -0.44574 -0.71610 -0.04952 -0.69624 -0.59927 -0.74831 -0.28445 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -0.63379 -0.75998 -0.14402 -0.65889 -0.73806 -0.14536 -0.62639 -0.76482 -0.15062 0.62639 -0.76482 -0.15062 0.65889 -0.73806 -0.14536 -1.00000 0.00000 0.00000 0.59715 -0.78261 -0.17586 0.62227 -0.69937 -0.35166 0.71610 -0.04952 -0.69624 0.85617 -0.26132 -0.44574 0.71631 -0.21863 -0.66264 0.70722 -0.14967 -0.69097 0.85683 -0.27518 -0.43602 0.93527 -0.30038 -0.18722 0.69725 -0.25192 -0.67110 0.68186 -0.46553 -0.56422 0.66333 -0.36884 -0.65111 0.73749 -0.50314 -0.45051 0.79534 -0.57614 -0.18840 0.73008 -0.52935 -0.43217 0.75435 -0.49922 -0.42630 -0.00000 -1.00000 0.00000 0.00106 -0.99996 0.00881 0.02538 -0.99967 0.00267 0.79359 -0.60845 -0.00012 0.79427 -0.60756 -0.00018 0.85472 -0.51909 0.00009 0.87777 -0.47908 -0.00121 0.90227 -0.43117 0.00073 0.94069 -0.33927 -0.00095 0.94956 -0.31358 0.00033 0.98159 -0.19101 -0.00041 0.98148 -0.19157 -0.00037 0.86835 -0.47394 -0.14612 0.92761 -0.33456 -0.16616 0.28626 -0.95811 0.00941 0.06124 -0.99812 0.00082 -1.00000 -0.00000 0.00000 0.77914 -0.62684 0.00328 0.00000 -0.98059 -0.19609 0.07625 -0.98818 -0.13301 0.67329 -0.73937 -0.00375 0.68177 -0.73156 -0.00422 0.51266 -0.85845 -0.01557 0.60949 -0.79259 -0.01799 0.28596 -0.95726 -0.04336 0.48386 -0.87340 -0.05531 0.02544 -0.99072 -0.13349 0.19812 -0.97716 -0.07687 0.97088 -0.18950 -0.14654 0.78235 -0.59845 -0.17260 0.48258 -0.87463 -0.04614 -0.48258 -0.87464 -0.04614 -0.78235 -0.59845 -0.17260 -0.97088 -0.18950 -0.14654 -0.19812 -0.97716 -0.07687 -0.02544 -0.99072 -0.13349 -0.48386 -0.87340 -0.05531 -0.28596 -0.95726 -0.04336 -0.60949 -0.79259 -0.01799 -0.51266 -0.85845 -0.01557 -0.68177 -0.73156 -0.00422 -0.67329 -0.73937 -0.00375 -0.07616 -0.98818 -0.13301 -0.00000 -0.98059 -0.19609 -0.77914 -0.62684 0.00328 0.20395 -0.06686 -0.97670 1.00000 0.00000 -0.00000 -0.06124 -0.99812 0.00082 -0.28626 -0.95811 0.00941 -0.92761 -0.33456 -0.16616 -0.86835 -0.47394 -0.14612 -0.98148 -0.19157 -0.00037 -0.98159 -0.19101 -0.00041 -0.94956 -0.31358 0.00033 -0.94069 -0.33927 -0.00095 -0.90227 -0.43117 0.00073 -0.87777 -0.47908 -0.00121 -0.85472 -0.51908 0.00009 -0.79427 -0.60756 -0.00018 -0.79359 -0.60845 -0.00012 0.00062 -0.06808 -0.99768 -0.00020 -0.68088 -0.73240 -0.00000 -0.67931 -0.73385 -0.02538 -0.99967 0.00267 -0.00106 -0.99996 0.00881 -0.00000 -0.99986 0.01651 0.00000 -0.94394 -0.33011 -0.00000 -0.94394 -0.33011 -0.26435 -0.91036 -0.31837 -0.29878 -0.91958 -0.25516 -0.36744 -0.83266 -0.41433 -0.64066 -0.69026 -0.33630 -0.69571 -0.59806 -0.39790 -0.70567 -0.70569 -0.06343 -0.69377 -0.71869 -0.04660 -0.88605 -0.45155 -0.10496 -0.94887 -0.30419 -0.08435 -0.93636 -0.34017 -0.08666 -0.96824 -0.21178 -0.13291 -0.96453 -0.24918 -0.08715 -0.98754 -0.15637 -0.01756 -0.96795 -0.24613 0.04991 -0.30897 -0.95094 0.01571 -0.19818 -0.96944 0.14457 -0.64480 -0.76159 -0.06484 -0.80014 -0.59240 -0.09401 -0.69629 -0.69631 0.17415 -0.88983 -0.45348 0.05057 -0.99712 -0.07579 0.00000 -0.96339 -0.25512 0.08248 -0.98187 -0.15548 -0.10845 -0.99492 -0.04386 0.09057 -0.99589 -0.02453 0.08723 -0.99566 -0.00074 0.09309 -0.99566 0.00045 0.09303 -0.99594 0.01078 0.08941 -0.99606 0.00113 0.08868 -0.99596 -0.00422 0.08966 -0.01576 -0.81730 0.57599 -0.00007 -0.81918 0.57353 0.00019 -0.81917 0.57355 0.00007 -0.81914 0.57359 -0.00016 -0.81916 0.57357 0.00016 -0.81915 0.57358 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00001 0.00000 1.00000 0.00001 -0.00000 1.00000 -0.10686 0.99427 0.00021 -0.10691 0.99427 0.00051 -0.10310 0.99467 0.00036 -0.31502 0.94908 0.00033 -0.30561 0.95216 0.00114 -0.54640 0.83753 0.00037 -0.49532 0.86869 0.00608 -0.73383 0.67933 0.00088 -0.66442 0.74733 0.00680 -0.29659 -0.76863 0.56678 -0.62243 -0.62224 0.47476 -0.84125 -0.41735 0.34367 -0.97445 -0.15100 0.16627 -0.18468 -0.82157 0.53937 -0.52793 -0.74792 0.40237 -0.51590 -0.74782 0.41787 -0.79345 -0.56953 0.21466 -0.77990 -0.57721 0.24203 -0.94860 -0.31649 -0.00114 -0.13722 -0.84064 0.52392 -0.16245 -0.85018 0.50080 -0.46619 -0.82821 0.31103 -0.46054 -0.83055 0.31318 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.15641 0.98761 -0.01249 -0.43461 0.90058 0.00827 -0.45395 0.89092 0.01409 -0.56909 0.82226 -0.00398 -0.73529 0.67767 0.01073 -0.70710 0.70711 0.00185 -0.88271 0.46992 -0.00184 -0.89102 0.45397 0.00134 -0.98629 0.16504 -0.00142 -0.98769 0.15640 0.00000 0.63460 -0.66563 0.39270 0.63436 -0.66518 0.39385 0.72560 -0.52027 0.45035 0.68535 -0.47470 0.55223 0.72614 -0.39663 0.56161 0.68473 -0.33252 0.64852 0.72616 -0.25021 0.64038 0.68424 -0.17252 0.70856 0.72663 -0.08900 0.68124 0.68414 -0.00184 0.72935 0.72662 0.07718 0.68269 0.68429 0.16795 0.70960 0.73343 0.25027 0.63201 0.68191 0.33078 0.65237 0.50247 0.42166 0.75480 0.79620 -0.45746 0.39598 0.71150 -0.40537 0.57398 0.77296 -0.33970 0.53585 0.73978 -0.24487 0.62671 0.77536 -0.21037 0.59545 0.75248 -0.08532 0.65307 0.77897 -0.06406 0.62378 0.75300 0.07392 0.65386 0.77803 0.08772 0.62207 0.75616 0.19727 0.62394 0.66429 0.26477 0.69901 0.24972 -0.78683 0.56439 0.13613 -0.87777 0.45933 0.11798 -0.84918 0.51476 -0.06009 -0.98988 0.12857 0.23889 -0.95596 0.17049 0.27051 -0.84078 0.46894 0.49605 -0.83495 0.23833 0.50274 -0.79627 0.33645 0.36695 -0.74608 0.55562 0.51142 -0.57864 0.63532 0.47211 -0.57465 0.66850 0.49937 -0.42215 0.75659 0.55746 -0.37879 0.73875 0.46738 -0.28853 0.83565 0.57126 -0.19417 0.79747 0.47014 -0.13561 0.87211 0.50809 0.02010 0.86107 0.55298 -0.00210 0.83319 0.50233 0.17192 0.84741 0.55640 0.19138 0.80858 0.48927 0.29566 0.82049 0.37156 0.44143 0.81675 0.49467 0.42090 0.76036 -0.07970 -0.93736 0.33913 -0.06820 -0.95935 0.27384 -0.21807 -0.95055 0.22112 -0.06791 -0.98506 0.15826 0.00000 -0.99987 0.01593 -0.03964 -0.95154 0.30497 0.01193 0.52427 0.85147 -0.00000 -0.85957 -0.51102 -0.00000 -0.85957 -0.51102 -0.96142 -0.27485 0.01168 -0.30116 -0.95354 0.00802 -0.34472 -0.93786 0.03984 -0.69707 -0.71635 0.03043 -0.22886 -0.93972 -0.25408 -0.96701 -0.24590 -0.06650 -0.95011 -0.26803 -0.15951 -0.94563 -0.27551 -0.17284 -0.95556 -0.25147 -0.15383 -0.69977 -0.65778 -0.27864 -0.37006 -0.83833 -0.40032 -0.64017 -0.69253 -0.33254 -0.27651 -0.82605 -0.49110 -0.99615 0.05447 0.06865 -0.98889 0.13229 0.06784 -0.96758 0.24929 0.04058 -0.93111 0.36112 0.05125 -0.75833 0.65140 0.02465 -0.83600 0.54855 0.01404 0.00000 1.00000 -0.00000 -0.18465 -0.80642 0.56178 -0.53029 -0.68737 0.49630 -0.80208 -0.47156 0.36647 -0.96387 -0.19129 0.18539 0.96386 -0.19129 0.18540 0.80208 -0.47156 0.36647 0.53029 -0.68737 0.49630 0.18466 -0.80774 0.55987 -0.00000 1.00000 -0.00000 0.83600 0.54855 0.01404 0.75833 0.65140 0.02465 0.93111 0.36112 0.05125 0.96758 0.24929 0.04058 0.98889 0.13229 0.06784 0.99615 0.05447 0.06865 0.27651 -0.82605 -0.49110 0.64017 -0.69253 -0.33254 0.37007 -0.83833 -0.40032 0.69978 -0.65778 -0.27864 0.93015 -0.32185 -0.17675 0.96424 -0.24057 -0.11123 0.95011 -0.26803 -0.15951 0.96701 -0.24590 -0.06650 0.22886 -0.93972 -0.25408 0.69707 -0.71635 0.03043 0.34472 -0.93786 0.03984 0.30116 -0.95354 0.00802 0.96142 -0.27485 0.01167 0.95765 -0.28791 0.00238 0.69707 -0.71635 0.03043 0.96752 -0.24290 0.07004 0.96702 0.23373 0.10120 0.44469 0.87275 0.20141 0.15007 0.94757 0.28211 0.42958 0.89466 0.12265 0.96712 0.23308 0.10170 0.88684 0.45184 0.09669 0.69363 0.69363 0.19431 0.98747 0.15637 0.02141 -0.04306 0.53891 0.84126 0.03964 -0.95154 0.30497 0.05119 -0.99105 0.12326 0.06791 -0.98506 0.15826 0.06820 -0.95935 0.27384 0.07970 -0.93736 0.33913 -0.49441 0.39951 0.77197 -0.32782 0.43681 0.83770 -0.55640 0.19138 0.80858 -0.48927 0.29566 0.82049 -0.50233 0.17192 0.84741 -0.55298 -0.00210 0.83319 -0.50809 0.02010 0.86107 -0.47014 -0.13561 0.87211 -0.57126 -0.19417 0.79747 -0.46738 -0.28853 0.83565 -0.55746 -0.37879 0.73875 -0.49937 -0.42215 0.75659 -0.47211 -0.57465 0.66850 -0.51142 -0.57864 0.63532 -0.33681 -0.78370 0.52189 -0.28175 -0.75512 0.59196 -0.50274 -0.79627 0.33645 -0.49604 -0.83495 0.23833 -0.27051 -0.84078 0.46894 -0.23889 -0.95596 0.17049 0.06009 -0.98988 0.12857 -0.11798 -0.84918 0.51476 -0.13613 -0.87777 0.45934 -0.66429 0.26477 0.69901 -0.75616 0.19727 0.62394 -0.77803 0.08772 0.62207 -0.75300 0.07392 0.65386 -0.77897 -0.06406 0.62378 -0.75248 -0.08532 0.65307 -0.77536 -0.21037 0.59545 -0.73978 -0.24487 0.62671 -0.77296 -0.33970 0.53585 -0.71150 -0.40537 0.57398 -0.79620 -0.45746 0.39598 -0.55052 0.40061 0.73242 -0.68191 0.33078 0.65237 -0.73343 0.25027 0.63201 -0.68429 0.16795 0.70960 -0.72662 0.07718 0.68269 -0.68414 -0.00184 0.72935 -0.72663 -0.08900 0.68124 -0.68424 -0.17252 0.70856 -0.72616 -0.25021 0.64038 -0.68473 -0.33252 0.64852 -0.72614 -0.39663 0.56161 -0.68535 -0.47470 0.55223 -0.72560 -0.52027 0.45035 -0.63436 -0.66518 0.39385 -0.63460 -0.66563 0.39270 0.98769 0.15640 -0.00000 0.98629 0.16504 -0.00142 0.89102 0.45397 0.00134 0.88271 0.46992 -0.00184 0.70710 0.70711 0.00185 0.73529 0.67767 0.01073 0.56909 0.82227 -0.00398 0.45395 0.89092 0.01408 0.43460 0.90058 0.00827 0.15641 0.98761 -0.01249 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 0.15273 -0.86617 0.47583 0.41173 -0.87359 0.25948 0.43261 -0.86653 0.24894 0.14765 -0.86322 0.48276 0.46055 -0.83055 0.31318 0.46618 -0.82821 0.31103 0.16245 -0.85018 0.50080 0.71431 -0.69421 0.08851 0.67849 -0.72532 0.11649 0.13722 -0.84064 0.52392 0.94860 -0.31649 -0.00114 0.79507 -0.56250 0.22686 0.77632 -0.58631 0.23146 0.51589 -0.74782 0.41787 0.52793 -0.74792 0.40237 0.18468 -0.82157 0.53937 0.97445 -0.15100 0.16627 0.84126 -0.41735 0.34367 0.62243 -0.62224 0.47476 0.33025 -0.76039 0.55924 0.66442 0.74733 0.00681 0.73383 0.67933 0.00088 0.49532 0.86869 0.00608 0.54640 0.83753 0.00037 0.30561 0.95216 0.00114 0.31502 0.94908 0.00033 0.10310 0.99467 0.00036 0.10691 0.99427 0.00051 0.10687 0.99427 0.00021 0.94257 -0.33229 0.03376 -0.00000 -0.00000 1.00000 -0.00001 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00016 -0.81915 0.57358 0.00016 -0.81916 0.57357 -0.00007 -0.81914 0.57359 -0.00019 -0.81917 0.57355 0.00008 -0.81918 0.57353 0.03478 -0.81474 0.57878 0.99596 -0.00422 0.08966 0.99606 0.00113 0.08868 0.99594 0.01078 0.08941 0.99566 0.00045 0.09303 0.99566 -0.00074 0.09309 0.99589 -0.02453 0.08723 0.99492 -0.04386 0.09057 0.99712 -0.07579 0.00000 0.98187 -0.15548 -0.10845 0.96339 -0.25512 0.08248 0.88983 -0.45348 0.05057 0.69629 -0.69631 0.17415 0.80014 -0.59240 -0.09401 0.64480 -0.76159 -0.06484 0.19818 -0.96944 0.14457 0.30897 -0.95094 0.01571 0.95817 -0.28538 0.02161 0.98726 -0.15633 -0.02955 0.96453 -0.24916 -0.08717 0.96824 -0.21178 -0.13291 0.96527 -0.22815 -0.12724 0.92566 -0.35400 -0.13359 0.88605 -0.45155 -0.10496 0.69377 -0.71869 -0.04660 0.70567 -0.70569 -0.06343 0.69571 -0.59806 -0.39790 0.64066 -0.69026 -0.33630 0.36744 -0.83266 -0.41433 0.29878 -0.91958 -0.25516 0.26435 -0.91036 -0.31837 -1.00000 -0.00000 0.00000 -1.00000 0.00003 0.00003 -1.00000 -0.00044 0.00026 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.45492 -0.69848 -0.55242 0.45573 -0.69856 -0.55166 0.62626 -0.65836 -0.41756 0.59609 -0.67308 -0.43777 0.39819 -0.76716 -0.50290 -0.43938 -0.71403 -0.54507 -0.60326 -0.71049 -0.36234 -0.51410 -0.73917 -0.43513 -0.45554 -0.75926 -0.46477 -0.39950 -0.78139 -0.47941 -0.00634 -0.89015 -0.45563 -0.00005 -0.87655 -0.48130 -0.00000 -0.81914 0.57360 -0.00019 -0.81919 0.57352 0.00014 -0.81912 0.57362 -0.00014 -0.81916 0.57357 0.00019 -0.81919 0.57352 -0.00014 -0.81912 0.57362 0.00014 -0.81916 0.57357 -0.68186 0.46553 -0.56422 -0.66333 0.36884 -0.65111 0.66333 0.36884 -0.65111 0.68186 0.46553 -0.56422 -0.98563 0.00128 -0.16894 0.98583 0.00128 -0.16773 -0.27402 0.79933 -0.53477 0.52064 0.85377 -0.00301 0.04210 -0.57464 -0.81732 0.11996 -0.67436 -0.72860 + + + + + + + + + + + + + + +

4 0 5 0 6 0 3 1 0 1 8 1 13 2 21 2 14 2 12 3 13 3 14 3 20 4 21 4 13 4 12 5 15 5 13 5 19 6 18 6 16 6 20 7 18 7 21 7 19 8 17 8 18 8 18 9 17 9 21 9 30 10 31 10 32 10 33 11 30 11 32 11 44 12 45 12 1 12 2 13 1 13 45 13 45 14 46 14 2 14 2 15 46 15 47 15 48 16 2 16 47 16 47 17 49 17 48 17 50 18 48 18 49 18 50 19 49 19 51 19 52 20 50 20 51 20 52 21 51 21 53 21 3 22 52 22 53 22 60 23 63 23 62 23 64 24 63 24 60 24 59 25 64 25 60 25 65 26 62 26 63 26 66 27 67 27 65 27 63 28 66 28 65 28 66 29 63 29 64 29 64 30 48 30 50 30 68 31 64 31 50 31 64 32 68 32 66 32 69 33 67 33 66 33 50 34 52 34 68 34 70 35 66 35 68 35 68 36 52 36 3 36 68 37 3 37 72 37 68 38 72 38 70 38 73 39 70 39 72 39 74 40 75 40 43 40 42 41 74 41 43 41 4 42 75 42 74 42 74 43 76 43 4 43 4 44 6 44 77 44 77 45 78 45 35 45 78 46 79 46 35 46 81 47 30 47 33 47 33 48 41 48 81 48 82 49 81 49 41 49 41 50 40 50 82 50 83 51 8 51 84 51 38 52 0 52 3 52 83 53 3 53 8 53 82 54 40 54 39 54 82 55 39 55 38 55 9 56 3 56 83 56 72 57 3 57 9 57 9 58 85 58 72 58 85 59 86 59 72 59 73 60 72 60 86 60 61 61 62 61 65 61 65 62 67 62 61 62 67 63 69 63 58 63 56 64 58 64 69 64 69 65 71 65 56 65 57 66 56 66 71 66 71 67 70 67 57 67 54 68 57 68 70 68 70 69 73 69 54 69 55 70 54 70 73 70 73 71 86 71 55 71 80 72 55 72 86 72 86 73 85 73 80 73 85 74 9 74 80 74 80 75 9 75 10 75 9 76 83 76 10 76 83 77 84 77 10 77 87 78 84 78 8 78 8 79 0 79 87 79 37 80 38 80 39 80 82 81 38 81 53 81 38 82 3 82 53 82 59 83 2 83 64 83 48 84 64 84 2 84 131 85 28 85 115 85 120 86 115 86 22 86 141 87 126 87 29 87 95 88 126 88 141 88 92 89 89 89 26 89 94 90 24 90 93 90 25 91 24 91 94 91 91 92 24 92 25 92 27 93 24 93 91 93 90 94 27 94 91 94 27 95 90 95 97 95 90 96 124 96 97 96 124 97 90 97 125 97 109 98 125 98 90 98 125 99 109 99 122 99 108 100 122 100 109 100 122 101 108 101 123 101 110 102 123 102 108 102 123 103 110 103 121 103 112 104 121 104 110 104 114 105 118 105 112 105 118 106 114 106 117 106 91 107 107 107 90 107 107 108 91 108 25 108 107 109 25 109 29 109 25 110 94 110 29 110 95 111 141 111 140 111 94 112 92 112 29 112 29 113 92 113 26 113 29 114 26 114 141 114 94 115 93 115 92 115 95 116 139 116 96 116 138 117 96 117 139 117 138 118 149 118 96 118 99 119 145 119 98 119 100 120 145 120 99 120 104 121 100 121 101 121 104 122 101 122 102 122 106 123 104 123 103 123 104 124 106 124 105 124 137 125 136 125 106 125 106 126 136 126 105 126 90 127 107 127 109 127 111 128 109 128 107 128 111 129 107 129 29 129 111 130 29 130 127 130 109 131 111 131 113 131 129 132 111 132 127 132 110 133 113 133 112 133 115 134 113 134 111 134 111 135 129 135 115 135 115 136 129 136 131 136 113 137 115 137 116 137 116 138 114 138 113 138 113 139 114 139 112 139 114 140 116 140 117 140 120 141 119 141 115 141 115 142 119 142 116 142 119 143 117 143 116 143 29 144 126 144 127 144 127 145 126 145 128 145 127 146 128 146 129 146 129 147 128 147 130 147 129 148 130 148 131 148 132 149 131 149 130 149 131 150 132 150 28 150 28 151 132 151 133 151 134 152 22 152 133 152 133 153 22 153 28 153 135 154 22 154 134 154 147 155 149 155 138 155 149 156 147 156 148 156 142 157 144 157 143 157 31 158 146 158 148 158 30 159 146 159 31 159 146 160 149 160 148 160 150 161 151 161 152 161 146 162 153 162 162 162 146 163 162 163 157 163 164 164 163 164 162 164 190 165 188 165 189 165 176 166 190 166 175 166 188 167 169 167 167 167 191 168 169 168 188 168 188 169 190 169 191 169 192 170 176 170 177 170 190 171 176 171 192 171 192 172 191 172 190 172 169 173 191 173 171 173 178 174 192 174 177 174 191 175 173 175 171 175 193 176 173 176 191 176 191 177 192 177 193 177 194 178 193 178 192 178 194 179 178 179 179 179 192 180 178 180 194 180 173 181 193 181 174 181 180 182 194 182 179 182 193 183 194 183 195 183 193 184 172 184 174 184 195 185 172 185 193 185 194 186 180 186 196 186 196 187 195 187 194 187 181 188 196 188 180 188 172 189 195 189 170 189 195 190 196 190 197 190 197 191 170 191 195 191 198 192 197 192 196 192 198 193 181 193 182 193 196 194 181 194 198 194 183 195 198 195 182 195 170 196 197 196 168 196 197 197 198 197 199 197 197 198 166 198 168 198 199 199 166 199 197 199 200 200 199 200 198 200 200 201 183 201 184 201 198 202 183 202 200 202 185 203 200 203 184 203 203 204 242 204 244 204 203 205 201 205 202 205 240 206 242 206 203 206 218 207 219 207 202 207 204 208 202 208 220 208 202 209 219 209 220 209 202 210 204 210 203 210 203 211 205 211 240 211 205 212 238 212 240 212 205 213 203 213 204 213 235 214 238 214 205 214 220 215 221 215 204 215 206 216 204 216 222 216 204 217 221 217 222 217 204 218 206 218 205 218 205 219 207 219 235 219 207 220 205 220 206 220 233 221 235 221 207 221 222 222 223 222 206 222 206 223 208 223 207 223 208 224 206 224 223 224 207 225 209 225 233 225 209 226 231 226 233 226 209 227 207 227 208 227 223 228 224 228 208 228 232 229 231 229 209 229 210 230 208 230 225 230 208 231 224 231 225 231 208 232 210 232 209 232 211 233 209 233 210 233 209 234 211 234 232 234 211 235 234 235 232 235 225 236 226 236 210 236 236 237 234 237 211 237 210 238 212 238 211 238 212 239 210 239 227 239 210 240 226 240 227 240 214 241 211 241 212 241 211 242 214 242 236 242 214 243 239 243 236 243 227 244 228 244 212 244 241 245 239 245 214 245 212 246 213 246 214 246 213 247 212 247 230 247 212 248 245 248 230 248 212 249 228 249 245 249 214 250 215 250 241 250 214 251 213 251 215 251 243 252 241 252 229 252 241 253 215 253 229 253 187 254 186 254 216 254 217 255 216 255 186 255 186 256 185 256 217 256 218 257 217 257 185 257 185 258 184 258 218 258 219 259 218 259 184 259 184 260 183 260 219 260 220 261 219 261 183 261 183 262 182 262 220 262 221 263 220 263 182 263 182 264 181 264 221 264 222 265 221 265 181 265 181 266 180 266 222 266 223 267 222 267 180 267 180 268 179 268 223 268 224 269 223 269 179 269 179 270 178 270 224 270 225 271 224 271 178 271 178 272 177 272 225 272 226 273 225 273 177 273 177 274 176 274 226 274 227 275 226 275 176 275 176 276 175 276 227 276 228 277 227 277 175 277 175 278 164 278 228 278 245 279 228 279 164 279 240 280 238 280 237 280 242 281 240 281 237 281 241 282 243 282 237 282 244 283 242 283 237 283 245 284 164 284 162 284 162 285 246 285 245 285 296 286 266 286 287 286 296 287 287 287 158 287 249 288 253 288 248 288 253 289 255 289 254 289 253 290 249 290 255 290 250 291 255 291 249 291 254 292 255 292 256 292 257 293 250 293 135 293 255 294 250 294 257 294 257 295 256 295 255 295 256 296 257 296 258 296 134 297 257 297 135 297 259 298 258 298 257 298 257 299 134 299 259 299 133 300 259 300 134 300 258 301 259 301 260 301 261 302 260 302 259 302 259 303 133 303 261 303 132 304 261 304 133 304 260 305 261 305 262 305 261 306 263 306 262 306 264 307 263 307 261 307 264 308 132 308 130 308 261 309 132 309 264 309 266 310 265 310 267 310 268 311 270 311 269 311 268 312 320 312 270 312 265 313 320 313 268 313 268 314 267 314 265 314 271 315 268 315 269 315 267 316 268 316 272 316 273 317 271 317 288 317 268 318 271 318 273 318 268 319 274 319 272 319 273 320 274 320 268 320 275 321 273 321 288 321 274 322 273 322 276 322 273 323 277 323 276 323 273 324 278 324 277 324 273 325 275 325 278 325 253 326 277 326 278 326 283 327 274 327 276 327 284 328 274 328 283 328 161 329 285 329 279 329 274 330 284 330 272 330 284 331 285 331 272 331 286 332 272 332 285 332 285 333 161 333 286 333 160 334 286 334 161 334 272 335 286 335 267 335 287 336 160 336 159 336 286 337 160 337 287 337 287 338 267 338 286 338 158 339 287 339 159 339 267 340 287 340 266 340 270 341 21 341 17 341 320 342 21 342 270 342 269 343 17 343 19 343 269 344 270 344 17 344 275 345 289 345 290 345 288 346 289 346 275 346 291 347 275 347 290 347 288 348 16 348 289 348 271 349 16 349 288 349 271 350 19 350 16 350 269 351 19 351 271 351 128 352 126 352 252 352 130 353 128 353 252 353 130 354 252 354 264 354 252 355 263 355 264 355 251 356 263 356 252 356 247 357 275 357 291 357 247 358 278 358 275 358 247 359 248 359 278 359 248 360 253 360 278 360 149 361 146 361 157 361 149 362 157 362 280 362 149 363 280 363 96 363 96 364 280 364 281 364 96 365 281 365 95 365 95 366 281 366 282 366 126 367 95 367 282 367 126 368 282 368 251 368 126 369 251 369 252 369 53 370 333 370 334 370 53 371 334 371 303 371 53 372 303 372 82 372 82 373 303 373 304 373 81 374 82 374 304 374 81 375 304 375 305 375 30 376 81 376 305 376 30 377 305 377 153 377 30 378 153 378 146 378 337 379 309 379 332 379 338 380 309 380 337 380 338 381 311 381 309 381 338 382 292 382 311 382 334 383 333 383 322 383 333 384 321 384 322 384 49 385 321 385 333 385 49 386 333 386 51 386 51 387 333 387 53 387 317 388 315 388 12 388 315 389 15 389 12 389 315 390 295 390 15 390 295 391 294 391 15 391 292 392 293 392 311 392 295 393 311 393 294 393 311 394 293 394 294 394 317 395 14 395 316 395 317 396 12 396 14 396 320 397 316 397 21 397 316 398 14 398 21 398 319 399 266 399 296 399 158 400 156 400 296 400 296 401 297 401 319 401 297 402 296 402 155 402 296 403 156 403 155 403 314 404 319 404 297 404 155 405 154 405 297 405 298 406 297 406 154 406 297 407 298 407 314 407 299 408 314 408 298 408 312 409 314 409 299 409 154 410 307 410 298 410 300 411 298 411 307 411 298 412 300 412 299 412 299 413 301 413 312 413 301 414 310 414 312 414 301 415 299 415 300 415 307 416 308 416 300 416 306 417 310 417 302 417 310 418 301 418 302 418 331 419 332 419 306 419 332 420 309 420 306 420 313 421 309 421 311 421 309 422 313 422 306 422 313 423 310 423 306 423 312 424 310 424 313 424 311 425 295 425 313 425 313 426 318 426 312 426 318 427 314 427 312 427 318 428 313 428 315 428 313 429 295 429 315 429 319 430 314 430 318 430 315 431 317 431 318 431 318 432 265 432 319 432 265 433 318 433 320 433 318 434 316 434 320 434 318 435 317 435 316 435 266 436 319 436 265 436 324 437 321 437 47 437 321 438 49 438 47 438 321 439 324 439 322 439 324 440 323 440 322 440 325 441 323 441 324 441 47 442 46 442 324 442 326 443 324 443 46 443 324 444 326 444 325 444 327 445 325 445 326 445 46 446 45 446 326 446 328 447 326 447 45 447 326 448 328 448 327 448 45 449 44 449 328 449 329 450 327 450 328 450 328 451 330 451 329 451 330 452 328 452 335 452 328 453 44 453 335 453 331 454 329 454 330 454 335 455 336 455 330 455 332 456 330 456 336 456 330 457 332 457 331 457 336 458 337 458 332 458 349 459 339 459 148 459 148 460 339 460 31 460 31 461 339 461 370 461 339 462 349 462 346 462 370 463 339 463 346 463 374 464 340 464 144 464 341 465 88 465 342 465 343 466 357 466 344 466 343 467 342 467 357 467 341 468 342 468 343 468 343 469 344 469 345 469 345 470 347 470 346 470 344 471 347 471 345 471 343 472 348 472 341 472 138 473 348 473 147 473 349 474 147 474 348 474 349 475 343 475 345 475 348 476 343 476 349 476 147 477 349 477 148 477 346 478 349 478 345 478 359 479 102 479 358 479 354 480 144 480 340 480 351 481 356 481 355 481 357 482 342 482 356 482 356 483 351 483 357 483 344 484 357 484 351 484 362 485 363 485 365 485 364 486 367 486 363 486 365 487 363 487 367 487 366 488 374 488 34 488 5 489 360 489 361 489 351 490 355 490 367 490 367 491 364 491 351 491 344 492 351 492 364 492 346 493 372 493 370 493 32 494 31 494 370 494 371 495 370 495 373 495 370 496 372 496 373 496 370 497 371 497 32 497 33 498 32 498 371 498 373 499 37 499 371 499 344 500 364 500 347 500 364 501 372 501 347 501 372 502 346 502 347 502 373 503 372 503 364 503 37 504 373 504 362 504 373 505 363 505 362 505 373 506 364 506 363 506 37 507 362 507 36 507 355 508 356 508 352 508 368 509 352 509 350 509 34 510 144 510 142 510 341 511 26 511 88 511 141 512 26 512 341 512 104 513 102 513 103 513 101 514 358 514 102 514 358 515 101 515 380 515 100 516 380 516 101 516 380 517 100 517 379 517 99 518 379 518 100 518 379 519 99 519 23 519 98 520 23 520 99 520 23 521 98 521 353 521 375 522 353 522 98 522 353 523 375 523 354 523 354 524 375 524 144 524 93 525 89 525 92 525 88 526 26 526 89 526 350 527 377 527 378 527 350 528 378 528 359 528 358 529 350 529 359 529 380 530 350 530 358 530 376 531 377 531 350 531 376 532 350 532 352 532 88 533 376 533 342 533 341 534 348 534 139 534 348 535 138 535 139 535 341 536 140 536 141 536 376 537 352 537 356 537 356 538 342 538 376 538 365 539 389 539 362 539 389 540 365 540 385 540 37 541 39 541 40 541 37 542 40 542 41 542 371 543 41 543 33 543 37 544 41 544 371 544 36 545 362 545 389 545 389 546 385 546 369 546 369 547 385 547 386 547 389 548 369 548 388 548 381 549 361 549 369 549 361 550 360 550 369 550 369 551 360 551 387 551 369 552 387 552 388 552 87 553 0 553 36 553 34 554 390 554 366 554 383 555 366 555 390 555 390 556 79 556 383 556 11 557 383 557 79 557 79 558 78 558 11 558 384 559 11 559 78 559 78 560 77 560 384 560 381 561 384 561 77 561 77 562 6 562 381 562 361 563 381 563 6 563 6 564 5 564 361 564 4 565 76 565 5 565 368 566 350 566 369 566 369 567 386 567 368 567 37 568 0 568 38 568 36 569 0 569 37 569 34 570 374 570 144 570 352 571 368 571 355 571 54 572 55 572 393 572 393 573 394 573 54 573 393 574 391 574 394 574 395 575 54 575 394 575 395 576 56 576 57 576 54 577 395 577 57 577 58 578 56 578 395 578 59 579 394 579 392 579 394 580 59 580 395 580 60 581 61 581 58 581 395 582 60 582 58 582 60 583 395 583 59 583 62 584 61 584 60 584 55 585 80 585 393 585 58 586 61 586 67 586 7 587 80 587 10 587 393 588 80 588 7 588 393 589 74 589 42 589 74 590 393 590 7 590 106 591 27 591 398 591 398 592 137 592 106 592 121 593 112 593 118 593 97 594 398 594 27 594 398 595 97 595 124 595 117 596 119 596 118 596 119 597 120 597 396 597 396 598 121 598 119 598 119 599 121 599 118 599 397 600 396 600 120 600 120 601 399 601 397 601 121 602 396 602 123 602 125 603 122 603 396 603 396 604 122 604 123 604 396 605 397 605 125 605 397 606 400 606 398 606 398 607 125 607 397 607 125 608 398 608 124 608 34 609 142 609 403 609 375 610 145 610 144 610 143 611 144 611 145 611 137 612 247 612 136 612 400 613 247 613 137 613 400 614 248 614 247 614 401 615 248 615 400 615 248 616 401 616 249 616 399 617 249 617 401 617 249 618 399 618 250 618 399 619 135 619 250 619 22 620 135 620 399 620 400 621 397 621 401 621 397 622 399 622 401 622 145 623 100 623 104 623 145 624 375 624 98 624 103 625 24 625 27 625 247 626 291 626 136 626 143 627 20 627 142 627 18 628 20 628 143 628 136 629 291 629 105 629 105 630 291 630 290 630 105 631 290 631 104 631 104 632 290 632 289 632 145 633 104 633 289 633 145 634 289 634 16 634 145 635 18 635 143 635 145 636 16 636 18 636 399 637 120 637 22 637 400 638 137 638 398 638 106 639 103 639 27 639 74 640 7 640 76 640 391 641 393 641 42 641 392 642 1 642 59 642 35 643 13 643 15 643 35 644 403 644 13 644 35 645 15 645 294 645 35 646 294 646 4 646 4 647 294 647 293 647 75 648 4 648 293 648 75 649 293 649 292 649 43 650 75 650 292 650 13 651 403 651 20 651 403 652 142 652 20 652 338 653 43 653 292 653 367 654 382 654 365 654 76 655 7 655 10 655 79 656 390 656 35 656 35 657 4 657 77 657 394 658 402 658 392 658 391 659 402 659 394 659 1 660 392 660 44 660 392 661 335 661 44 661 336 662 335 662 392 662 392 663 402 663 336 663 337 664 336 664 402 664 402 665 391 665 337 665 391 666 338 666 337 666 391 667 42 667 338 667 42 668 43 668 338 668 382 669 367 669 355 669 355 670 368 670 382 670 386 671 382 671 368 671 403 672 35 672 34 672 390 673 34 673 35 673 152 674 151 674 547 674 547 675 548 675 152 675 404 676 152 676 548 676 404 677 405 677 152 677 406 678 407 678 152 678 406 679 152 679 405 679 406 680 405 680 408 680 409 681 406 681 408 681 409 682 410 682 407 682 406 683 409 683 407 683 411 684 410 684 409 684 408 685 412 685 409 685 409 686 412 686 413 686 409 687 413 687 414 687 415 688 409 688 414 688 415 689 416 689 411 689 409 690 415 690 411 690 407 691 150 691 152 691 417 692 150 692 407 692 418 693 417 693 407 693 410 694 419 694 418 694 407 695 410 695 418 695 410 696 411 696 419 696 416 697 420 697 421 697 416 698 421 698 419 698 411 699 416 699 419 699 331 700 422 700 329 700 327 701 329 701 422 701 422 702 423 702 327 702 327 703 423 703 424 703 325 704 327 704 424 704 424 705 425 705 325 705 325 706 425 706 426 706 418 707 428 707 427 707 427 708 308 708 418 708 417 709 418 709 308 709 307 710 150 710 417 710 308 711 307 711 417 711 307 712 154 712 150 712 429 713 431 713 430 713 430 714 431 714 432 714 433 715 430 715 432 715 245 716 246 716 433 716 432 717 245 717 433 717 434 718 246 718 153 718 305 719 433 719 434 719 153 720 305 720 434 720 430 721 433 721 305 721 305 722 304 722 430 722 429 723 430 723 304 723 304 724 303 724 429 724 435 725 429 725 303 725 303 726 334 726 435 726 438 727 428 727 439 727 439 728 441 728 440 728 441 729 443 729 442 729 443 730 422 730 331 730 444 731 427 731 438 731 438 732 440 732 444 732 302 733 444 733 440 733 440 734 442 734 302 734 306 735 302 735 442 735 442 736 331 736 306 736 308 737 427 737 444 737 444 738 300 738 308 738 444 739 302 739 301 739 300 740 444 740 301 740 445 741 446 741 447 741 447 742 420 742 445 742 448 743 445 743 420 743 416 744 449 744 448 744 420 745 416 745 448 745 413 746 450 746 237 746 450 747 244 747 237 747 449 748 416 748 415 748 449 749 415 749 414 749 449 750 414 750 413 750 449 751 413 751 237 751 243 752 449 752 237 752 230 753 245 753 451 753 230 754 451 754 452 754 213 755 230 755 452 755 213 756 452 756 453 756 213 757 453 757 454 757 215 758 213 758 454 758 454 759 455 759 215 759 229 760 215 760 455 760 455 761 449 761 229 761 243 762 229 762 449 762 437 763 436 763 456 763 457 764 456 764 436 764 436 765 458 765 457 765 459 766 457 766 458 766 458 767 460 767 459 767 461 768 459 768 460 768 460 769 462 769 461 769 463 770 461 770 462 770 462 771 464 771 463 771 465 772 463 772 464 772 464 773 466 773 465 773 467 774 465 774 466 774 466 775 441 775 467 775 467 776 441 776 439 776 428 777 467 777 439 777 436 778 426 778 458 778 460 779 458 779 426 779 426 780 425 780 460 780 462 781 460 781 425 781 425 782 424 782 462 782 464 783 462 783 424 783 424 784 423 784 464 784 466 785 464 785 423 785 423 786 422 786 466 786 466 787 422 787 443 787 466 788 443 788 441 788 456 789 455 789 454 789 454 790 453 790 456 790 468 791 456 791 453 791 429 792 469 792 431 792 469 793 429 793 435 793 469 794 435 794 437 794 468 795 469 795 437 795 437 796 456 796 468 796 457 797 455 797 456 797 459 798 449 798 455 798 457 799 459 799 455 799 448 800 449 800 459 800 459 801 461 801 448 801 445 802 448 802 461 802 461 803 463 803 445 803 446 804 445 804 463 804 465 805 447 805 446 805 463 806 465 806 446 806 420 807 447 807 465 807 465 808 467 808 420 808 421 809 420 809 467 809 428 810 419 810 421 810 467 811 428 811 421 811 468 812 453 812 452 812 452 813 469 813 468 813 431 814 469 814 432 814 469 815 451 815 245 815 432 816 469 816 245 816 469 817 452 817 451 817 418 818 419 818 428 818 216 819 404 819 187 819 548 820 187 820 404 820 201 821 203 821 244 821 470 822 217 822 218 822 202 823 470 823 218 823 470 824 202 824 201 824 216 825 217 825 470 825 244 826 450 826 201 826 201 827 450 827 413 827 201 828 413 828 412 828 408 829 201 829 412 829 201 830 408 830 470 830 470 831 405 831 216 831 470 832 408 832 405 832 404 833 216 833 405 833 325 834 426 834 323 834 426 835 436 835 323 835 323 836 436 836 322 836 322 837 436 837 437 837 334 838 322 838 437 838 334 839 437 839 435 839 246 840 162 840 153 840 427 841 428 841 438 841 438 842 439 842 440 842 440 843 441 843 442 843 331 844 442 844 443 844 254 845 512 845 513 845 509 846 513 846 514 846 517 847 509 847 515 847 527 848 517 848 516 848 163 849 157 849 162 849 251 850 520 850 518 850 251 851 518 851 263 851 263 852 518 852 519 852 262 853 263 853 519 853 528 854 262 854 519 854 260 855 262 855 528 855 548 856 471 856 187 856 473 857 471 857 472 857 473 858 187 858 471 858 474 859 473 859 472 859 472 860 541 860 474 860 474 861 541 861 540 861 474 862 540 862 502 862 501 863 474 863 502 863 187 864 473 864 186 864 473 865 474 865 200 865 200 866 185 866 473 866 473 867 185 867 186 867 474 868 501 868 199 868 199 869 501 869 499 869 199 870 200 870 474 870 166 871 199 871 499 871 498 872 188 872 167 872 189 873 497 873 190 873 190 874 497 874 164 874 190 875 164 875 175 875 188 876 498 876 475 876 475 877 493 877 188 877 188 878 493 878 189 878 500 879 475 879 498 879 535 880 516 880 477 880 476 881 496 881 495 881 523 882 164 882 476 882 476 883 164 883 496 883 495 884 478 884 476 884 478 885 495 885 494 885 480 886 534 886 516 886 516 887 534 887 477 887 482 888 533 888 480 888 480 889 533 889 534 889 533 890 482 890 505 890 484 891 506 891 482 891 482 892 506 892 505 892 506 893 484 893 507 893 486 894 507 894 484 894 507 895 486 895 504 895 488 896 504 896 486 896 504 897 488 897 503 897 490 898 491 898 488 898 488 899 491 899 503 899 491 900 490 900 492 900 490 901 479 901 492 901 518 902 478 902 479 902 478 903 518 903 476 903 476 904 518 904 520 904 476 905 520 905 525 905 525 906 523 906 476 906 478 907 494 907 479 907 492 908 479 908 494 908 481 909 514 909 512 909 481 910 512 910 532 910 531 911 481 911 532 911 481 912 531 912 483 912 530 913 483 913 531 913 483 914 530 914 485 914 529 915 485 915 530 915 485 916 529 916 487 916 528 917 487 917 529 917 487 918 528 918 489 918 519 919 489 919 528 919 516 920 515 920 480 920 480 921 515 921 514 921 481 922 480 922 514 922 480 923 481 923 482 923 483 924 482 924 481 924 482 925 483 925 484 925 485 926 484 926 483 926 484 927 485 927 486 927 487 928 486 928 485 928 486 929 487 929 488 929 489 930 488 930 487 930 488 931 489 931 490 931 519 932 490 932 489 932 490 933 519 933 479 933 518 934 479 934 519 934 500 935 503 935 475 935 475 936 503 936 491 936 475 937 491 937 493 937 493 938 491 938 492 938 493 939 492 939 189 939 189 940 492 940 494 940 189 941 494 941 495 941 189 942 495 942 497 942 497 943 495 943 496 943 497 944 496 944 164 944 499 945 165 945 166 945 498 946 165 946 500 946 501 947 165 947 499 947 500 948 165 948 503 948 533 949 504 949 538 949 538 950 504 950 503 950 504 951 533 951 507 951 505 952 507 952 533 952 507 953 505 953 506 953 508 954 279 954 285 954 285 955 284 955 508 955 283 956 508 956 284 956 279 957 508 957 526 957 508 958 283 958 511 958 511 959 283 959 510 959 511 960 526 960 508 960 277 961 510 961 276 961 276 962 510 962 283 962 526 963 511 963 527 963 513 964 277 964 254 964 277 965 513 965 509 965 277 966 509 966 510 966 511 967 510 967 509 967 517 968 511 968 509 968 511 969 517 969 527 969 512 970 254 970 532 970 514 971 513 971 512 971 515 972 509 972 514 972 517 973 515 973 516 973 282 974 520 974 251 974 520 975 282 975 525 975 281 976 525 976 282 976 525 977 281 977 524 977 280 978 524 978 281 978 524 979 280 979 522 979 157 980 521 980 280 980 280 981 521 981 522 981 157 982 163 982 521 982 277 983 253 983 254 983 523 984 522 984 164 984 522 985 163 985 164 985 522 986 523 986 524 986 525 987 524 987 523 987 279 988 151 988 161 988 526 989 536 989 279 989 279 990 536 990 151 990 536 991 526 991 535 991 527 992 535 992 526 992 535 993 527 993 516 993 260 994 528 994 529 994 530 995 260 995 529 995 260 996 530 996 258 996 258 997 530 997 531 997 532 998 258 998 531 998 258 999 532 999 256 999 254 1000 256 1000 532 1000 533 1001 538 1001 534 1001 542 1002 477 1002 538 1002 538 1003 477 1003 534 1003 543 1004 477 1004 542 1004 545 1005 535 1005 543 1005 543 1006 535 1006 477 1006 535 1007 545 1007 536 1007 536 1008 545 1008 151 1008 547 1009 151 1009 545 1009 544 1010 542 1010 537 1010 537 1011 542 1011 538 1011 537 1012 539 1012 544 1012 544 1013 539 1013 540 1013 544 1014 540 1014 541 1014 472 1015 544 1015 541 1015 542 1016 544 1016 543 1016 546 1017 545 1017 544 1017 544 1018 545 1018 543 1018 544 1019 472 1019 546 1019 546 1020 472 1020 471 1020 546 1021 471 1021 547 1021 546 1022 547 1022 545 1022 548 1023 547 1023 471 1023 24 1024 103 1024 102 1024 24 1025 102 1025 359 1025 24 1026 359 1026 378 1026 24 1027 378 1027 377 1027 24 1028 377 1028 376 1028 24 1029 376 1029 88 1029 88 1030 89 1030 24 1030 5 1031 76 1031 10 1031 5 1032 10 1032 360 1032 10 1033 387 1033 360 1033 10 1034 388 1034 387 1034 10 1035 389 1035 388 1035 10 1036 36 1036 389 1036 36 1037 10 1037 87 1037 84 1038 87 1038 10 1038 89 1039 93 1039 24 1039 239 1040 241 1040 237 1040 236 1041 239 1041 237 1041 234 1042 236 1042 237 1042 232 1043 234 1043 237 1043 231 1044 232 1044 237 1044 231 1045 237 1045 233 1045 233 1046 237 1046 235 1046 235 1047 237 1047 238 1047 165 1048 168 1048 166 1048 165 1049 170 1049 168 1049 165 1050 172 1050 170 1050 165 1051 174 1051 172 1051 165 1052 173 1052 174 1052 165 1053 171 1053 173 1053 165 1054 169 1054 171 1054 165 1055 167 1055 169 1055 165 1056 498 1056 167 1056 165 1057 501 1057 502 1057 165 1058 502 1058 540 1058 165 1059 540 1059 539 1059 165 1060 539 1060 537 1060 165 1061 537 1061 538 1061 165 1062 538 1062 503 1062 381 1063 369 1063 384 1063 11 1064 384 1064 369 1064 11 1065 369 1065 383 1065 366 1066 383 1066 369 1066 366 1067 369 1067 374 1067 379 1068 350 1068 380 1068 23 1069 350 1069 379 1069 23 1070 353 1070 350 1070 353 1071 354 1071 350 1071 340 1072 350 1072 354 1072 340 1073 369 1073 350 1073 340 1074 374 1074 369 1074 150 1075 158 1075 151 1075 150 1076 156 1076 158 1076 150 1077 155 1077 156 1077 150 1078 154 1078 155 1078 151 1079 158 1079 159 1079 151 1080 159 1080 160 1080 151 1081 160 1081 161 1081 66 1082 70 1082 71 1082 66 1083 71 1083 69 1083 108 1084 113 1084 110 1084 108 1085 109 1085 113 1085 1 1086 2 1086 59 1086 22 1087 115 1087 28 1087 139 1088 140 1088 341 1088 95 1089 140 1089 139 1089 365 1090 382 1090 385 1090 382 1091 386 1091 385 1091

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/f_proximal/f_proximal_G4.dae b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_G4.dae new file mode 100644 index 0000000..1b61469 --- /dev/null +++ b/URDFs/sr_description/meshes/components/f_proximal/f_proximal_G4.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:15:31.855069 + 2012-07-23T02:15:31.855082 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -7.17350 6.94911 4.21838 -9.93270 -1.15879 -0.00031 -9.92969 1.15514 -0.00031 -7.45360 6.66578 -0.00031 -6.19669 -7.61001 14.00068 -5.99999 -7.69760 7.99969 -5.93079 -7.72543 8.52069 -5.99999 -7.62085 -1.45521 -6.53730 7.42476 2.97619 -6.00000 7.62007 -1.44611 -5.99999 -0.00089 -0.00031 -4.99999 3.65198 9.71969 -3.55469 -9.23031 23.11969 -3.56699 -8.61560 18.55868 -1.76899 -9.59040 22.63068 -4.59092 -8.80456 23.59968 4.59459 -8.80456 23.59968 1.77266 -9.59040 22.63068 3.57066 -8.61560 18.55868 3.55836 -9.23031 23.11969 0.00406 -8.84559 18.22268 0.00406 -9.69028 22.44568 9.93636 -1.15879 -0.00031 5.00366 3.81254 9.73169 6.00366 -0.00089 -0.00031 6.00366 7.62007 -1.44611 7.14516 6.97814 3.97919 6.00366 -7.62085 -1.45522 9.93336 1.15514 -0.00031 7.45726 6.66578 -0.00031 -4.47209 7.99911 23.99968 -0.92010 7.99911 10.96068 -2.73450 7.99911 10.65468 -5.10259 7.94911 9.74469 -3.99999 -8.00089 9.99969 -5.00999 -7.96456 14.00168 -6.00000 6.94911 4.50619 -5.64640 6.94911 8.25268 -7.17349 6.94911 6.96669 -7.06460 7.04525 7.66968 -6.70469 7.31810 8.43568 -6.02019 7.68741 9.16469 -7.45360 -6.66756 -0.00031 -7.46809 -6.65131 13.99969 -9.91719 -1.28497 23.99968 -9.99999 -0.02064 23.99968 -9.92209 1.24482 23.99968 -9.68389 2.49335 23.99968 -9.63909 2.66125 -0.00031 -8.93994 4.00025 23.99968 -9.11909 4.10304 -0.00031 -8.39959 5.42557 23.99968 -8.38479 5.44841 -0.00031 -7.47299 6.64398 23.99968 -6.00000 -5.49870 -5.79131 -5.99999 -6.96596 -3.90192 -6.00000 -3.36071 -7.26061 -6.00000 -4.50038 -6.61501 -6.00000 -2.24851 -7.67811 -9.41220 -1.47532 -3.03941 -8.06000 -1.20361 -5.79601 -6.00000 -1.13267 -7.91981 -6.00000 -0.00089 -8.00031 -8.06000 1.20183 -5.79601 -9.41220 1.47352 -3.03941 -6.00000 1.13089 -7.91981 -7.35780 3.50247 -5.79601 -6.00000 2.24673 -7.67811 -8.51050 4.28110 -3.03941 -6.00000 3.35892 -7.26061 -6.00000 5.49692 -5.79131 -6.00000 4.49860 -6.61501 -6.62189 6.66578 -3.42181 -6.00000 6.66577 -4.42251 -6.78489 -7.26453 -0.00031 -6.83189 -7.23065 13.99969 -5.99999 -7.69760 -0.00031 -5.71839 -7.80180 9.02269 -5.38550 -7.89522 9.44169 -4.95869 -7.97119 9.75468 -5.99999 -7.34730 -2.89871 -5.57889 7.84294 23.99968 -6.59929 7.38662 23.99968 -6.00000 7.69581 -0.00031 -6.00000 7.69581 2.18159 -6.00000 7.34767 -2.89111 -6.00000 7.07516 -3.64421 -6.00000 7.31252 3.24219 6.00366 6.94911 4.50619 6.00366 7.31252 3.24219 6.00366 6.66577 -4.42252 6.00366 7.34767 -2.89111 6.66886 7.34083 3.17053 6.00366 7.69581 2.18159 6.00366 7.69581 -0.00031 6.60296 7.38662 23.99968 5.58256 7.84294 23.99968 6.00366 -7.18556 -3.39231 4.96236 -7.97119 9.75468 5.38916 -7.89522 9.44169 5.72206 -7.80180 9.02269 5.93446 -7.72543 8.52069 6.00366 -7.69760 7.99968 6.00366 -7.69760 -0.00031 6.20036 -7.61001 14.00068 6.83556 -7.23065 13.99968 6.78856 -7.26453 -0.00031 6.62556 6.66578 -3.42181 6.00366 4.49860 -6.61501 6.00366 5.49692 -5.79131 6.00366 3.35892 -7.26061 8.51416 4.28110 -3.03941 6.00366 2.24673 -7.67812 7.36146 3.50247 -5.79601 6.00366 1.13089 -7.91981 9.41586 1.47352 -3.03941 8.06366 1.20183 -5.79601 6.00366 -0.00089 -8.00031 6.00366 -1.13267 -7.91981 8.06366 -1.20361 -5.79601 9.41586 -1.47532 -3.03941 6.00366 -2.24851 -7.67812 6.00366 -4.50038 -6.61501 6.00366 -3.36071 -7.26061 6.00366 -6.66755 -4.42252 6.00366 -5.49870 -5.79131 7.47666 6.64398 23.99968 8.38846 5.44841 -0.00031 8.40326 5.42557 23.99968 9.12276 4.10304 -0.00031 8.94361 4.00025 23.99968 9.64276 2.66125 -0.00031 9.68756 2.49335 23.99968 9.92576 1.24482 23.99968 10.00366 -0.02064 23.99968 9.92086 -1.28497 23.99968 7.47176 -6.65131 13.99968 7.45726 -6.66756 -0.00031 5.10626 7.94911 9.74469 6.02386 7.68741 9.16469 7.06826 7.04525 7.66968 7.17716 6.94911 6.96669 0.00406 -8.00089 13.99868 3.58286 -8.00089 13.99868 4.00366 -8.00089 9.99969 5.01366 -7.96456 14.00168 0.00366 7.99911 23.99968 2.73816 7.99911 10.65468 0.92376 7.99911 10.96068 4.47576 7.99911 23.99968 -3.99999 -5.02735 37.82068 4.00366 -5.02735 37.82068 -3.99999 -5.00089 39.42268 -4.48079 7.99911 34.49768 -3.53979 -8.82177 32.40168 -2.34909 -9.28970 31.73368 -1.16229 -9.55490 31.35468 4.48446 7.99911 34.49768 0.00346 -9.63919 31.23468 1.16596 -9.55490 31.35468 2.35276 -9.28970 31.73368 3.54346 -8.82177 32.40168 0.00366 7.99911 44.99968 4.46387 7.99911 44.99968 4.00366 6.94911 44.99968 7.00366 -0.00089 44.99968 7.00366 -3.61239 46.59969 7.00366 3.37761 47.04568 7.00366 -3.04855 47.51268 7.00366 2.70194 47.87968 7.00366 -2.25983 48.23969 7.00366 1.82715 48.50168 7.00366 -1.30441 48.72868 7.00366 0.81734 48.86368 7.00366 -0.25282 48.94168 4.00366 6.69274 46.86967 4.00366 5.94276 48.60168 4.00366 4.75370 50.06868 4.00366 3.21449 51.16068 4.00366 1.43786 51.79867 4.00366 -0.44483 51.93568 4.00366 -2.29479 51.56068 4.00366 -3.97553 50.70068 4.00366 -5.36307 49.42068 4.00366 -6.35507 47.81468 4.00366 -6.87828 46.00168 4.00366 -6.89415 44.11368 4.00366 -6.40153 42.29169 6.60256 4.84007 47.50069 5.76706 6.37616 44.99969 5.50366 5.81689 48.00468 6.60256 3.15259 49.44267 5.50366 3.78892 50.33968 6.60256 0.76172 50.39468 5.50366 0.91560 51.48367 6.60256 -1.79926 50.14268 5.50366 -2.16214 51.18068 6.60256 -3.95910 48.74368 5.50366 -4.75780 49.49968 6.60256 -5.23604 46.50967 5.50366 -6.29241 46.81468 -6.59889 -5.34526 43.93867 -5.49999 -6.29241 46.81468 -6.59889 -5.23604 46.50967 -5.49999 -4.75780 49.49968 -6.59889 -3.95910 48.74368 -5.49999 -2.16214 51.18068 -6.59889 -1.79926 50.14268 -5.49999 0.91560 51.48367 -6.59889 0.76172 50.39468 -5.49999 3.78892 50.33968 -6.59889 3.15259 49.44267 -5.49999 5.81689 48.00468 -5.76339 6.37616 44.99968 -6.59889 4.84007 47.50069 -6.42709 5.71247 44.99968 -3.99999 -6.40153 42.29169 -3.99999 -6.89415 44.11368 -3.99999 -6.87828 46.00168 -3.99999 -6.35507 47.81468 -3.99999 -5.36307 49.42068 -3.99999 -3.97553 50.70068 -3.99999 -2.29479 51.56068 -3.99999 -0.44483 51.93568 -3.99999 1.43786 51.79867 -3.99999 3.21449 51.16068 -3.99999 4.75370 50.06868 -3.99999 5.94276 48.60168 -3.99999 6.69274 46.86967 -6.85319 4.87616 44.99968 -4.92709 6.80228 44.99968 -6.99999 -0.25282 48.94168 -6.99999 0.81734 48.86368 -6.99999 -1.30441 48.72868 -6.99999 1.82715 48.50168 -6.99999 -2.25983 48.23969 -6.99999 2.70194 47.87968 -6.99999 -0.00090 44.99968 -6.99999 -3.04855 47.51268 -6.99999 3.37761 47.04568 -6.99999 -3.61239 46.59969 -6.99999 3.80368 46.06168 -6.99999 -3.90969 45.56868 -6.99999 3.94911 44.99968 -6.99999 -3.91855 44.49568 -3.99999 6.94911 44.99968 -4.46019 7.99911 44.99968 8.35526 -5.50089 23.99968 8.73536 -4.87502 23.99968 9.28136 -3.73246 23.99968 9.67876 -2.52910 23.99968 7.43666 6.69810 34.49368 8.31437 5.81849 29.52985 8.89386 -4.46979 29.51968 8.76546 -4.19563 35.80267 9.26076 -2.79232 29.51968 8.91906 -2.27439 35.04568 9.45096 -1.09815 29.51968 8.96676 -0.33818 35.04568 9.47666 0.60681 29.51968 8.94576 1.60178 35.04568 9.33576 2.31798 29.51968 8.83896 3.55496 35.04568 8.30708 5.67738 34.68957 8.98616 4.04325 29.51968 0.00416 -10.00089 29.52368 0.00336 -10.00089 30.08768 2.93366 -9.56529 30.58668 3.43473 -9.48162 29.13079 3.49076 -9.37344 25.99968 1.45316 -9.89544 25.99968 4.39459 -9.10315 25.99968 4.41876 -8.98168 31.25368 6.33566 -7.76061 29.52368 5.84346 -8.13534 32.22368 7.02016 -7.12658 25.99968 7.14446 -7.03138 33.48969 8.27176 -5.67266 35.04868 8.54566 -5.26191 29.52368 4.68486 -8.14347 33.37068 5.30646 7.91391 34.49867 6.09576 7.66057 34.49867 6.81586 7.24997 34.49968 6.91396 -7.18597 33.86967 5.65496 -8.25206 32.34668 5.01416 -8.44358 32.71868 3.31336 -9.32459 31.45968 1.18046 -9.86343 30.69068 5.37426 -8.43667 25.99968 5.71986 -8.20649 23.99968 6.46616 -7.63259 23.99968 7.16186 -6.98424 23.99968 -7.15819 -6.98424 23.99968 -6.46249 -7.63259 23.99968 -5.71619 -8.20649 23.99968 -5.37059 -8.43667 25.99968 -1.17679 -9.86343 30.69068 -3.30969 -9.32459 31.45968 -5.01049 -8.44358 32.71868 -5.65129 -8.25206 32.34668 -6.31069 -7.37931 34.23868 -6.91029 -7.18597 33.86967 -7.85419 -6.04028 35.50568 -6.81219 7.24997 34.49968 -6.09209 7.66057 34.49867 -5.30279 7.91391 34.49867 -8.26809 -5.67266 35.04868 -4.68119 -8.14347 33.37068 -5.72309 -7.25891 34.63368 -8.54199 -5.26191 29.52368 -7.14079 -7.03138 33.48969 -7.01649 -7.12658 25.99968 -5.83979 -8.13534 32.22368 -6.33199 -7.76061 29.52368 -4.41509 -8.98168 31.25368 -4.39092 -9.10315 25.99968 -1.44949 -9.89544 25.99968 -3.48709 -9.37343 25.99968 -3.43106 -9.48162 29.13079 -2.92999 -9.56529 30.58668 0.00184 -10.00019 25.99969 -8.98249 4.04325 29.51968 -8.30341 5.67738 34.68957 -8.83529 3.55496 35.04568 -9.33209 2.31798 29.51968 -8.94209 1.60178 35.04568 -9.47299 0.60681 29.51968 -8.96309 -0.33818 35.04568 -9.44729 -1.09815 29.51968 -8.91539 -2.27439 35.04568 -9.25709 -2.79232 29.51968 -8.76179 -4.19563 35.80267 -8.89019 -4.46979 29.51968 -8.31070 5.81849 29.52985 -7.43299 6.69810 34.49368 -9.67509 -2.52910 23.99968 -9.27769 -3.73246 23.99968 -8.73169 -4.87502 23.99968 -8.35159 -5.50089 23.99968 0.00183 7.24200 10.60569 4.00366 4.25152 9.99969 5.65006 6.94911 8.25268 5.55006 6.94911 5.59469 3.89726 6.94911 9.21068 3.63686 6.94093 6.60969 1.98966 6.94911 9.80069 0.00366 6.94911 9.99969 0.00366 6.94911 7.84768 4.30636 7.24200 9.80469 1.47496 7.24200 10.60569 4.32487 5.06448 8.40697 3.63686 6.82538 6.40069 4.38886 6.06216 6.65668 4.68666 3.94590 9.87969 4.34936 4.09318 9.96969 3.63371 6.43688 6.43168 4.43506 6.73264 6.19568 4.49076 6.91366 6.33069 5.94346 3.82193 8.45469 6.00400 4.02117 8.04468 -6.00000 4.02117 8.04468 -5.93979 3.82193 8.45469 -5.54639 6.94911 5.59469 -4.54040 6.94911 6.46068 -3.63320 6.94093 6.60969 -4.45075 6.64691 6.24219 -4.34569 4.09222 9.96969 -3.63320 6.82538 6.40069 3.63321 5.95391 6.88068 -4.32395 5.11941 8.41997 -1.47129 7.24200 10.60569 -4.30269 7.24200 9.80469 -1.98599 6.94911 9.80069 -3.89359 6.94911 9.21068 -3.99999 4.25198 9.99969 4.47576 -8.00089 9.94269 6.00366 5.96671 5.62369 6.00366 4.86318 6.60168 6.00366 4.40365 7.39368 5.41736 3.62295 9.41469 5.73196 3.74311 9.00368 -5.72829 3.74311 9.00368 -3.63359 6.44435 6.42669 -4.68299 3.85204 9.87969 -5.41369 3.62295 9.41469 -4.38520 6.06216 6.65668 -3.63320 5.95391 6.88068 -5.99999 4.40365 7.39368 -5.99999 4.86318 6.60168 -6.00000 5.96671 5.62369 -4.47209 -8.00089 9.94269 -8.38479 -5.45020 -0.00031 -9.63909 -2.66304 -0.00031 -6.78409 -6.66756 -3.03501 -8.51050 -4.28290 -3.03941 -7.35780 -3.50425 -5.79601 7.36146 -3.50425 -5.79601 8.51416 -4.28290 -3.03941 6.78776 -6.66756 -3.03501 9.64276 -2.66304 -0.00031 8.38846 -5.45020 -0.00031 9.12276 -4.10482 -0.00031 -9.11909 -4.10482 -0.00031 -3.57919 -8.00089 13.99868 -3.99999 -5.43664 40.66869 -5.48459 -5.09962 40.93769 -5.49999 -4.73356 40.21569 -5.76329 -4.42797 39.42269 -6.42709 -4.46943 41.43969 -6.59809 -3.69701 40.57769 -6.42699 -3.76429 39.42269 -6.85319 -2.92798 39.42269 -6.68310 -3.81534 41.96069 -6.99999 -3.09028 42.53869 -6.99999 -2.49594 41.59168 -6.99999 -2.12557 40.53269 -6.99999 -2.00089 39.42269 -5.36349 -4.67315 38.32668 -6.19619 -4.04460 39.22469 -6.72699 -3.25133 38.74369 -6.99999 -2.00089 38.27869 -6.96549 -2.45480 38.42168 -8.53599 -1.46623 39.60468 -8.55289 -0.11087 39.43468 -8.54059 1.25595 39.55968 -8.50409 2.50568 39.95368 -8.45399 3.57721 40.56069 -6.76829 -5.70594 36.85169 -6.86009 -4.03110 39.22569 -6.92969 7.10944 44.99969 -6.11599 7.64029 44.99969 -5.93589 7.04911 44.99969 -5.49999 6.94911 44.99969 -5.31029 7.90772 44.99969 -4.88529 7.95342 44.99969 -7.19169 6.82799 43.78869 -8.19199 4.97673 41.65069 -7.71279 6.06131 42.71468 -7.49639 -5.59217 36.77569 -7.60349 -3.56948 39.46268 -8.12469 -5.26918 36.55169 -8.06229 -2.97472 39.64069 -8.56689 -4.78127 36.21169 -8.39929 -2.25591 39.68868 -7.28129 -6.21366 35.90269 -6.99999 1.68717 38.19369 -6.99999 0.45891 38.00269 -6.99999 -0.78335 38.03168 -6.99999 2.86304 38.59969 -6.99999 3.94911 39.20568 -6.99999 -3.63839 43.45969 -5.03399 6.76527 43.41169 -5.49999 6.54719 42.67069 -5.93590 6.24091 41.72169 -6.39679 5.75341 40.92669 -6.83869 4.91954 39.95969 -7.08054 5.94669 41.49869 -7.43409 4.97597 40.42869 -8.19199 4.02715 40.55369 -7.43409 3.77077 39.39269 -8.19199 2.84199 39.71668 -7.43409 2.35678 38.66769 -8.19199 1.49065 39.18868 -7.43409 0.81253 38.29169 -8.19199 0.05167 39.00069 -7.43409 -0.77680 38.28768 -8.19199 -1.39001 39.16369 -7.43409 -2.32320 38.65369 -6.72699 6.57048 42.44669 -6.72699 6.92842 43.70069 -5.49999 -6.42367 43.72469 5.48826 -5.09962 40.93769 6.43076 -4.46943 41.43969 5.50366 -6.42367 43.72469 6.60256 -5.34526 43.93868 6.85686 4.87616 44.99969 6.73066 6.92842 43.70069 6.73066 -3.25133 38.74369 6.73066 6.57048 42.44669 7.08421 5.94669 41.49869 7.43776 -2.32320 38.65369 8.19566 -1.39001 39.16369 7.43776 -0.77680 38.28768 8.19566 0.05167 39.00069 7.43776 0.81253 38.29169 8.19566 1.49065 39.18868 7.43776 2.35678 38.66769 8.19566 2.84199 39.71668 7.43776 3.77077 39.39269 8.19566 4.02715 40.55369 7.43776 4.97597 40.42869 6.84236 4.91954 39.95969 6.40046 5.75341 40.92669 6.43076 5.71247 44.99969 5.93956 6.24091 41.72169 5.50366 6.54719 42.67069 5.03766 6.76527 43.41169 4.93076 6.80228 44.99969 7.00366 3.80368 46.06168 7.00366 -3.90969 45.56869 7.00366 3.94911 44.99969 7.00366 -3.91855 44.49569 7.00366 -3.63839 43.45969 7.00366 3.94911 39.20568 7.00366 2.86304 38.59969 7.00366 -0.78335 38.03168 7.00366 0.45891 38.00269 7.00366 1.68717 38.19369 6.31436 -7.37931 34.23869 8.12836 -5.26918 36.55169 7.85786 -6.04028 35.50568 7.28496 -6.21366 35.90269 8.40296 -2.25591 39.68868 8.57056 -4.78127 36.21169 8.06596 -2.97472 39.64069 7.60716 -3.56948 39.46268 6.99346 -4.00149 39.23769 7.50006 -5.59217 36.77569 7.71646 6.06131 42.71468 8.19566 4.97673 41.65069 7.19536 6.82799 43.78869 4.88896 7.95342 44.99969 5.31396 7.90772 44.99969 5.93956 7.04911 44.99969 6.11966 7.64029 44.99969 6.93336 7.10944 44.99969 5.72676 -7.25891 34.63369 6.77196 -5.70594 36.85169 8.45766 3.57721 40.56069 8.50776 2.50568 39.95368 8.54426 1.25595 39.55968 8.55656 -0.11086 39.43468 8.53966 -1.46623 39.60468 7.00366 -2.00089 38.27869 6.96916 -2.45480 38.42168 6.19986 -4.04460 39.22469 5.36716 -4.67315 38.32668 7.00366 -2.31088 41.06269 7.00366 -2.00089 39.42269 7.00366 -2.49594 41.59168 7.00366 -3.09028 42.53869 6.75609 -3.81534 41.96069 6.85686 -2.92798 39.42269 6.43066 -3.76429 39.42269 6.60176 -3.69701 40.57769 5.76696 -4.42797 39.42269 5.50366 -4.73356 40.21569 4.00366 -5.00089 39.42269 4.00366 -5.43664 40.66869 + + + + + + + + + + -0.37992 -0.92502 0.00105 -0.61397 0.78924 -0.01224 -0.07593 -0.97679 -0.20031 -0.22994 -0.96457 -0.12938 -0.08134 -0.97733 -0.19549 -0.42429 -0.89757 -0.11982 0.42429 -0.89757 -0.11983 0.08144 -0.97732 -0.19548 0.22994 -0.96457 -0.12938 0.07611 -0.97679 -0.20023 0.00000 1.00000 -0.00000 -0.02010 0.99979 -0.00262 -0.99786 -0.06535 0.00030 -1.00000 0.00130 -0.00287 -0.99811 0.06144 0.00009 -0.98228 0.18741 -0.00039 -0.98189 0.18945 -0.00051 -0.89668 0.44268 0.00142 -0.94065 0.33926 0.00847 -0.93503 0.35447 0.00850 -0.87777 0.47908 -0.00009 -0.79597 0.60534 0.00009 -0.79427 0.60756 -0.00009 -0.73062 -0.00000 -0.68279 -0.89780 -0.00000 -0.44040 -0.89780 -0.00000 -0.44040 -0.71610 0.04952 -0.69624 -0.75711 0.13830 -0.63848 -0.69777 0.21297 -0.68393 -0.85617 0.26132 -0.44574 -0.92192 0.33250 -0.19878 -0.93821 0.30132 -0.17023 -0.85683 0.27518 -0.43602 -0.69725 0.25192 -0.67110 -0.86835 0.47394 -0.14612 -0.73749 0.50314 -0.45051 -0.77877 0.59570 -0.19660 -0.78420 0.59050 -0.19062 -0.73536 0.51102 -0.44509 -0.72246 0.52579 -0.44899 -0.67329 -0.73938 -0.00047 -0.66596 -0.74598 0.00018 -0.51275 -0.85854 0.00036 -0.48310 -0.87557 -0.00131 -0.34471 -0.93870 0.00305 -0.28004 -0.95995 0.00846 -0.17483 -0.98460 -0.00057 -0.13972 0.99019 0.00271 -0.27312 0.96198 -0.00196 -0.40823 0.91287 0.00257 -0.47428 0.88037 -0.00066 -0.45040 0.89283 0.00000 -0.71115 0.70304 0.00000 -0.57790 0.81555 -0.03005 -0.60493 0.79627 0.00059 -0.67564 0.73722 0.00384 -0.57764 0.81518 -0.04270 -0.64644 0.74661 -0.15714 -0.67682 0.72341 -0.13637 -0.59520 0.75563 -0.27343 -0.59953 0.70834 -0.37259 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.02819 0.94010 0.33974 0.01436 0.93130 0.36396 0.12973 0.97951 -0.15405 -0.64764 0.76194 0.00226 -0.71191 0.70227 0.00006 -0.98581 0.00000 -0.16786 -0.97140 0.18743 -0.14577 0.97140 0.18743 -0.14578 0.98565 0.00000 -0.16881 0.71191 0.70227 0.00006 0.64764 0.76194 0.00226 0.00494 0.91350 0.40681 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 0.54765 0.76436 -0.34035 0.67682 0.72341 -0.13637 0.64644 0.74661 -0.15714 0.57764 0.81518 -0.04270 0.67564 0.73722 0.00384 0.57791 0.81555 -0.02994 0.61966 0.78477 -0.01300 0.70339 0.71081 -0.00063 0.47080 0.88224 -0.00000 0.40823 0.91287 0.00257 0.27312 0.96198 -0.00196 0.13972 0.99019 0.00271 0.17483 -0.98460 -0.00057 0.28004 -0.95995 0.00846 0.34471 -0.93870 0.00305 0.37991 -0.92502 0.00105 0.48310 -0.87557 -0.00131 0.51275 -0.85854 0.00036 0.66596 -0.74598 0.00018 0.67329 -0.73937 -0.00047 0.72246 0.52579 -0.44899 0.73536 0.51102 -0.44509 0.78420 0.59050 -0.19063 0.77877 0.59570 -0.19660 0.73749 0.50314 -0.45051 0.86835 0.47394 -0.14612 0.69725 0.25192 -0.67110 0.85683 0.27518 -0.43602 0.93821 0.30132 -0.17023 0.92192 0.33250 -0.19878 0.85617 0.26132 -0.44574 0.69777 0.21297 -0.68393 0.75711 0.13830 -0.63848 0.71610 0.04952 -0.69624 0.89780 0.00000 -0.44040 0.89780 0.00000 -0.44040 0.73062 0.00000 -0.68279 0.79427 0.60756 -0.00009 0.79597 0.60534 0.00009 0.87777 0.47908 -0.00009 0.93503 0.35448 0.00850 0.94065 0.33926 0.00847 0.89668 0.44268 0.00142 0.98189 0.18945 -0.00051 0.98228 0.18741 -0.00039 0.99809 0.06144 -0.00571 1.00000 0.00130 0.00031 0.99786 -0.06535 0.00030 0.02010 0.99979 -0.00262 -0.00000 1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 -0.99986 0.01651 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 0.00000 1.00000 0.69946 0.68907 0.18956 0.22891 0.89330 0.38681 0.96248 0.21083 0.17081 0.95946 0.21276 0.18488 0.69693 0.54133 0.47038 0.36003 0.72476 0.58745 0.30851 0.71817 0.62374 0.69716 0.54127 0.47010 0.96751 0.14650 0.20605 0.21934 0.56453 0.79573 0.95759 0.09723 0.27122 0.96142 0.10177 0.25557 0.69721 0.26520 0.66601 0.69718 0.26518 0.66605 0.30072 0.32233 0.89759 0.34441 0.34727 0.87223 0.96702 0.01852 0.25402 0.22851 0.07066 0.97097 0.69718 -0.07020 0.71345 0.95018 -0.06188 0.30550 0.96407 -0.02601 0.26437 0.36233 -0.09132 0.92757 0.69714 -0.07024 0.71349 0.25693 -0.19200 0.94717 0.96537 -0.11886 0.23224 0.69711 -0.38978 0.60175 0.95840 -0.15517 0.23956 0.69719 -0.38969 0.60172 0.42922 -0.41142 0.80405 0.25228 -0.52600 0.81221 0.22867 -0.66008 0.71554 0.96700 -0.17269 0.18735 0.69715 -0.62243 0.35577 0.96242 -0.23105 0.14269 0.95943 -0.24477 0.13991 0.69712 -0.62246 0.35577 0.36001 -0.79374 0.49028 0.30840 -0.82588 0.47203 0.21950 -0.93736 0.27051 -0.95765 -0.28792 0.00238 -0.69707 -0.71635 0.03043 -0.96752 -0.24290 0.07004 -0.21950 -0.93736 0.27051 -0.30839 -0.82588 0.47203 -0.36001 -0.79374 0.49028 -0.69712 -0.62246 0.35577 -0.95943 -0.24477 0.13991 -0.96242 -0.23105 0.14269 -0.69715 -0.62243 0.35577 -0.96700 -0.17269 0.18735 -0.22867 -0.66008 0.71554 -0.25228 -0.52600 0.81221 -0.42922 -0.41142 0.80405 -0.69719 -0.38969 0.60172 -0.95840 -0.15517 0.23956 -0.69711 -0.38978 0.60175 -0.96537 -0.11886 0.23224 -0.25693 -0.19200 0.94717 -0.69714 -0.07024 0.71349 -0.36233 -0.09132 0.92757 -0.96407 -0.02601 0.26437 -0.95018 -0.06188 0.30550 -0.69718 -0.07020 0.71345 -0.22851 0.07066 0.97097 -0.96702 0.01852 0.25402 -0.34441 0.34727 0.87223 -0.30072 0.32233 0.89759 -0.69718 0.26518 0.66605 -0.69721 0.26520 0.66601 -0.96142 0.10177 0.25557 -0.95759 0.09723 0.27122 -0.21934 0.56453 0.79573 -0.96751 0.14650 0.20605 -0.69716 0.54127 0.47010 -0.30851 0.71817 0.62374 -0.36003 0.72476 0.58745 -0.69693 0.54133 0.47038 -0.95946 0.21276 0.18488 -0.96248 0.21083 0.17081 -0.22891 0.89330 0.38681 -0.96702 0.23373 0.10120 -0.69946 0.68907 0.18956 -0.44469 0.87275 0.20141 -0.15007 0.94757 0.28211 -0.42958 0.89466 0.12265 -0.95018 0.30880 0.04245 -0.69362 0.69364 0.19431 -0.98747 0.15637 0.02141 -0.84480 0.43042 0.31789 -0.00000 -0.96534 -0.26100 -0.00000 -0.96534 -0.26100 -0.00000 -0.99996 0.00841 -0.00000 -0.99996 0.00841 -0.00000 -0.96079 0.27727 -0.00000 -0.96079 0.27727 -0.00000 -0.85078 0.52551 -0.00000 -0.85078 0.52551 -0.00000 -0.67805 0.73502 0.00000 -0.67805 0.73502 0.00000 -0.45551 0.89023 0.00000 -0.45551 0.89023 0.00000 -0.19866 0.98007 0.00000 -0.19866 0.98007 -0.00000 0.07258 0.99736 0.00000 0.07258 0.99736 0.00000 0.33797 0.94116 -0.00000 0.33797 0.94116 -0.00000 0.57862 0.81559 0.00000 0.57862 0.81559 0.00000 0.77686 0.62968 0.00000 0.77686 0.62968 0.00000 0.91766 0.39736 0.00000 0.91766 0.39736 0.00000 0.99073 0.13583 0.00000 0.99073 0.13583 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.97499 0.22226 -0.00000 -0.92453 0.38110 0.90226 -0.43116 0.00574 0.97649 -0.21358 0.02928 0.97612 -0.21350 0.04000 0.94802 -0.31308 0.05686 0.99635 -0.05341 0.06661 0.97763 -0.19024 0.08966 0.99134 -0.11130 0.06976 0.99120 -0.11128 0.07172 0.99558 -0.02453 0.09061 0.99409 -0.06510 0.08683 0.99589 -0.01501 0.08933 0.99520 -0.01500 0.09672 0.99424 0.06120 0.08796 0.99554 0.01078 0.09370 0.99338 0.08180 0.08071 0.99256 0.08173 0.09020 0.97998 0.18697 0.06840 0.99552 0.05444 0.07731 0.96826 0.24794 0.03155 0.97796 0.19817 0.06582 0.89663 0.44266 -0.01036 0.97777 0.19813 0.06861 0.14700 -0.98914 0.00021 0.24807 -0.96831 -0.02902 0.07172 -0.99371 0.08595 0.14963 -0.98874 -0.00030 0.14904 -0.98882 -0.00554 0.28639 -0.95770 -0.02796 0.34030 -0.93819 0.06320 0.56248 -0.82680 0.00516 0.50451 -0.86193 0.05048 0.53463 -0.84366 -0.04914 0.51263 -0.85823 -0.02566 0.62265 -0.78225 -0.01980 0.64109 -0.76740 0.01036 0.79702 -0.60172 -0.05190 0.74900 -0.66246 -0.01212 0.74880 -0.66228 0.02629 0.91538 -0.40230 0.01547 0.61539 -0.78641 0.05336 0.57003 -0.81556 0.09967 0.12475 -0.87586 0.46616 0.51875 -0.85477 -0.01612 0.37649 -0.90862 0.18073 0.32485 -0.92285 0.20694 0.13312 -0.88748 0.44120 0.09621 -0.88767 0.45032 0.31482 -0.94120 0.12258 0.06742 -0.90426 0.42164 0.08306 -0.90964 0.40702 0.17554 -0.96597 0.18998 0.02220 -0.90647 0.42168 0.16166 -0.98259 -0.09158 0.06493 -0.99436 -0.08387 0.07172 -0.99366 -0.08660 0.20896 -0.97695 -0.04364 0.24766 -0.96673 -0.06404 0.60929 -0.79232 0.03169 0.62268 -0.78228 0.01757 0.68177 -0.73156 -0.00376 0.47456 -0.88001 -0.01928 0.56160 -0.82551 -0.05591 0.40991 -0.90871 -0.07890 0.28626 -0.95728 -0.04085 0.79561 0.60506 -0.03020 0.93501 0.35447 -0.01016 0.93521 0.35396 -0.00997 0.93524 0.35385 0.01100 0.75898 0.65084 0.01887 0.77910 -0.62681 0.01059 0.77326 -0.63409 0.00078 0.85470 -0.51907 -0.00700 0.91546 -0.40240 0.00325 -0.00000 1.00000 0.00000 0.10310 0.99467 -0.00009 0.13972 0.99019 -0.00302 0.30561 0.95215 0.00160 0.40823 0.91287 -0.00410 0.49533 0.86870 0.00126 0.64764 0.76194 -0.00322 0.66439 0.74739 -0.00132 0.70513 0.70908 -0.00097 -0.70513 0.70908 -0.00097 -0.66439 0.74739 -0.00132 -0.64764 0.76194 -0.00322 -0.49533 0.86870 0.00126 -0.40823 0.91287 -0.00410 -0.30561 0.95215 0.00160 -0.13972 0.99019 -0.00302 -0.10310 0.99467 -0.00009 0.00000 1.00000 0.00000 -0.91546 -0.40240 0.00325 -0.85470 -0.51907 -0.00700 -0.77326 -0.63409 0.00078 -0.77910 -0.62681 0.01059 -0.75898 0.65084 0.01887 -0.93524 0.35385 0.01100 -0.93521 0.35396 -0.00997 -0.93501 0.35447 -0.01016 -0.79561 0.60506 -0.03020 -0.28626 -0.95728 -0.04085 -0.40991 -0.90871 -0.07890 -0.56160 -0.82551 -0.05591 -0.47456 -0.88001 -0.01928 -0.68177 -0.73156 -0.00376 -0.62268 -0.78228 0.01757 -0.60929 -0.79232 0.03169 -0.24766 -0.96673 -0.06404 -0.20896 -0.97695 -0.04364 -0.07172 -0.99365 -0.08669 -0.06477 -0.99437 -0.08389 -0.16161 -0.98253 -0.09231 -0.02214 -0.90647 0.42168 -0.17554 -0.96597 0.18998 -0.08306 -0.90964 0.40702 -0.06742 -0.90426 0.42164 -0.31482 -0.94120 0.12258 -0.09621 -0.88767 0.45032 -0.13312 -0.88748 0.44120 -0.32485 -0.92285 0.20694 -0.37649 -0.90862 0.18073 -0.51875 -0.85477 -0.01612 -0.12475 -0.87586 0.46616 -0.15273 -0.86617 0.47583 -0.41173 -0.87359 0.25948 -0.57003 -0.81556 0.09967 -0.61539 -0.78642 0.05336 -0.43261 -0.86653 0.24894 -0.14765 -0.86322 0.48276 -0.71431 -0.69421 0.08851 -0.67849 -0.72532 0.11649 -0.94257 -0.33229 0.03376 -0.91537 -0.40231 0.01547 -0.74880 -0.66228 0.02629 -0.74900 -0.66246 -0.01212 -0.79702 -0.60172 -0.05190 -0.64109 -0.76740 0.01036 -0.62265 -0.78225 -0.01980 -0.51263 -0.85823 -0.02566 -0.53463 -0.84366 -0.04914 -0.50451 -0.86193 0.05048 -0.56248 -0.82680 0.00516 -0.34030 -0.93819 0.06320 -0.28639 -0.95770 -0.02796 -0.14884 -0.98885 -0.00561 -0.14945 -0.98877 -0.00010 -0.07172 -0.99371 0.08595 -0.24807 -0.96831 -0.02902 -0.14692 -0.98915 -0.00021 -0.97777 0.19813 0.06861 -0.89663 0.44266 -0.01036 -0.97796 0.19817 0.06582 -0.96826 0.24794 0.03155 -0.99552 0.05444 0.07731 -0.97998 0.18697 0.06840 -0.99256 0.08173 0.09020 -0.99338 0.08180 0.08071 -0.99554 0.01078 0.09370 -0.99424 0.06120 0.08796 -0.99520 -0.01500 0.09672 -0.99589 -0.01501 0.08933 -0.99409 -0.06510 0.08683 -0.99558 -0.02453 0.09061 -0.99120 -0.11128 0.07172 -0.99134 -0.11130 0.06976 -0.97763 -0.19024 0.08966 -0.99635 -0.05341 0.06661 -0.94802 -0.31308 0.05686 -0.97612 -0.21350 0.04000 -0.97649 -0.21358 0.02928 -0.90226 -0.43116 0.00574 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.42453 -0.90541 0.00000 0.90036 -0.43515 0.00000 0.90036 -0.43515 0.00000 0.00000 -1.00000 -0.00000 1.00000 -0.00000 0.02992 0.99953 -0.00614 -0.04897 0.99855 -0.02238 -0.00000 1.00000 0.00000 -0.00094 0.99999 -0.00305 -0.00000 1.00000 0.00000 0.00167 1.00000 -0.00170 -0.18127 0.92582 -0.33166 -0.33605 0.30453 -0.89125 -0.24187 0.45887 -0.85495 -0.12672 0.90338 -0.40970 -0.10729 0.91905 -0.37927 -0.15739 0.32299 -0.93322 -0.03628 0.93144 -0.36209 -0.98931 0.00059 -0.14580 -0.08645 0.00000 -0.99626 -0.25621 -0.07481 -0.96372 -0.46284 0.61705 -0.63642 -0.12748 0.61787 -0.77588 -0.12905 0.86783 -0.47980 0.52405 0.59562 -0.60877 0.08703 0.87183 -0.48201 0.02729 0.59100 -0.80621 0.08645 0.00000 -0.99626 0.98943 0.00056 -0.14501 -0.00000 -0.07954 -0.99683 -0.00000 0.87515 -0.48385 -0.00000 0.87515 -0.48385 0.03621 0.93145 -0.36205 0.15739 0.32299 -0.93322 0.10729 0.91905 -0.37927 0.12672 0.90337 -0.40970 0.24187 0.45887 -0.85495 0.33605 0.30453 -0.89125 0.18127 0.92582 -0.33166 0.00000 0.99998 -0.00661 -0.00167 1.00000 -0.00170 0.00000 1.00000 -0.00000 0.00094 0.99999 -0.00305 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00938 0.99995 -0.00221 0.00000 1.00000 -0.00000 -0.03447 -0.56461 -0.82463 -0.02257 -0.86820 -0.49570 -0.00000 -1.00000 -0.00000 -0.02658 0.99964 -0.00251 0.00811 0.99992 0.00963 0.40679 -0.91352 -0.00000 -0.99129 0.00002 -0.13166 -0.93308 -0.00133 -0.35966 -0.92096 0.00015 -0.38965 -0.79403 -0.00032 -0.60788 -0.78301 0.00046 -0.62201 -0.60834 -0.00037 -0.79368 -0.59143 0.00050 -0.80636 -0.42313 -0.00028 -0.90607 -0.36047 0.00144 -0.93277 -0.25804 -0.00054 -0.96613 -0.11987 0.00096 -0.99279 -0.00342 0.94046 0.33987 0.10258 0.95600 0.27486 -0.54107 -0.72740 -0.42205 -0.54206 -0.72466 -0.42548 -0.54151 -0.72194 -0.43078 -0.56924 -0.75410 -0.32757 -0.66245 -0.49685 -0.56063 -0.35061 -0.80805 -0.47342 -0.84565 -0.40086 -0.35240 -0.38367 0.78835 -0.48095 -0.40881 0.39255 -0.82388 -0.12973 0.97951 -0.15405 -0.49552 -0.46867 -0.73130 -0.42845 -0.22367 -0.87544 0.44674 -0.23178 -0.86412 0.49661 -0.46421 -0.73341 0.23270 0.87645 -0.42153 0.17952 0.79930 -0.57349 0.40881 0.39255 -0.82388 0.38366 0.78835 -0.48095 0.84565 -0.40086 -0.35240 0.33841 -0.82490 -0.45279 0.01364 -0.88159 -0.47182 0.67437 -0.48974 -0.55261 0.58626 -0.73899 -0.33195 0.56054 -0.70950 -0.42709 0.56140 -0.71351 -0.41920 0.56043 -0.71635 -0.41564 -0.06761 0.95887 0.27568 0.11987 0.00096 -0.99279 0.25818 -0.00054 -0.96610 0.36048 0.00146 -0.93277 0.45114 -0.00108 -0.89245 0.59133 -0.00033 -0.80643 0.59343 -0.00043 -0.80488 0.78301 0.00046 -0.62201 0.79403 -0.00032 -0.60788 0.92096 0.00015 -0.38965 0.93308 -0.00133 -0.35966 0.99129 0.00002 -0.13166 -0.40679 -0.91352 0.00000 -0.00625 -0.86521 -0.50136 -0.00000 -0.87912 -0.47660 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 0.00000 -1.00000 -0.11875 -0.67600 -0.72728 -0.69945 -0.56446 -0.43835 -0.73008 -0.52935 -0.43217 -0.79534 -0.57614 -0.18840 -0.73749 -0.50314 -0.45051 -0.66333 -0.36884 -0.65111 -0.68186 -0.46553 -0.56422 -0.69725 -0.25192 -0.67110 -0.93527 -0.30038 -0.18722 -0.85683 -0.27518 -0.43602 -0.70722 -0.14967 -0.69097 -0.71631 -0.21863 -0.66264 -0.85617 -0.26132 -0.44574 -0.71610 -0.04952 -0.69624 -0.59927 -0.74831 -0.28445 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -0.63379 -0.75998 -0.14402 -0.65889 -0.73806 -0.14536 -0.62639 -0.76482 -0.15062 0.62639 -0.76482 -0.15062 0.65889 -0.73806 -0.14536 -1.00000 0.00000 0.00000 0.59715 -0.78261 -0.17586 0.62227 -0.69937 -0.35166 0.71610 -0.04952 -0.69624 0.85617 -0.26132 -0.44574 0.71631 -0.21863 -0.66264 0.70722 -0.14967 -0.69097 0.85683 -0.27518 -0.43602 0.93527 -0.30038 -0.18722 0.69725 -0.25192 -0.67110 0.68186 -0.46553 -0.56422 0.66333 -0.36884 -0.65111 0.73749 -0.50314 -0.45051 0.79534 -0.57614 -0.18840 0.73008 -0.52935 -0.43217 0.75435 -0.49922 -0.42630 -0.00000 -1.00000 0.00000 0.00106 -0.99996 0.00881 0.02538 -0.99967 0.00267 0.79359 -0.60845 -0.00012 0.79427 -0.60756 -0.00018 0.85472 -0.51909 0.00009 0.87777 -0.47908 -0.00121 0.90227 -0.43117 0.00073 0.94069 -0.33927 -0.00095 0.94956 -0.31358 0.00033 0.98159 -0.19101 -0.00041 0.98148 -0.19157 -0.00037 0.86835 -0.47394 -0.14612 0.92761 -0.33456 -0.16616 0.28626 -0.95811 0.00941 0.06124 -0.99812 0.00082 -1.00000 -0.00000 0.00000 0.77914 -0.62684 0.00328 0.00000 -0.98059 -0.19609 0.07625 -0.98818 -0.13301 0.67329 -0.73937 -0.00375 0.68177 -0.73156 -0.00422 0.51266 -0.85845 -0.01557 0.60949 -0.79259 -0.01799 0.28596 -0.95726 -0.04336 0.48386 -0.87340 -0.05531 0.02544 -0.99072 -0.13349 0.19812 -0.97716 -0.07687 0.97088 -0.18950 -0.14654 0.78235 -0.59845 -0.17260 0.48258 -0.87463 -0.04614 -0.48258 -0.87464 -0.04614 -0.78235 -0.59845 -0.17260 -0.97088 -0.18950 -0.14654 -0.19812 -0.97716 -0.07687 -0.02544 -0.99072 -0.13349 -0.48386 -0.87340 -0.05531 -0.28596 -0.95726 -0.04336 -0.60949 -0.79259 -0.01799 -0.51266 -0.85845 -0.01557 -0.68177 -0.73156 -0.00422 -0.67329 -0.73937 -0.00375 -0.07616 -0.98818 -0.13301 -0.00000 -0.98059 -0.19609 -0.77914 -0.62684 0.00328 0.20395 -0.06686 -0.97670 1.00000 0.00000 -0.00000 -0.06124 -0.99812 0.00082 -0.28626 -0.95811 0.00941 -0.92761 -0.33456 -0.16616 -0.86835 -0.47394 -0.14612 -0.98148 -0.19157 -0.00037 -0.98159 -0.19101 -0.00041 -0.94956 -0.31358 0.00033 -0.94069 -0.33927 -0.00095 -0.90227 -0.43117 0.00073 -0.87777 -0.47908 -0.00121 -0.85472 -0.51908 0.00009 -0.79427 -0.60756 -0.00018 -0.79359 -0.60845 -0.00012 0.00062 -0.06808 -0.99768 -0.00020 -0.68088 -0.73240 -0.00000 -0.67931 -0.73385 -0.02538 -0.99967 0.00267 -0.00106 -0.99996 0.00881 -0.00000 -0.99986 0.01651 0.00000 -0.94394 -0.33011 -0.00000 -0.94394 -0.33011 -0.26435 -0.91036 -0.31837 -0.29878 -0.91958 -0.25516 -0.36744 -0.83266 -0.41433 -0.64066 -0.69026 -0.33630 -0.69571 -0.59806 -0.39790 -0.70567 -0.70569 -0.06343 -0.69377 -0.71869 -0.04660 -0.88605 -0.45155 -0.10496 -0.94887 -0.30419 -0.08435 -0.93636 -0.34017 -0.08666 -0.96824 -0.21178 -0.13291 -0.96453 -0.24918 -0.08715 -0.98754 -0.15637 -0.01756 -0.96795 -0.24613 0.04991 -0.30897 -0.95094 0.01571 -0.19818 -0.96944 0.14457 -0.64480 -0.76159 -0.06484 -0.80014 -0.59240 -0.09401 -0.69629 -0.69631 0.17415 -0.88983 -0.45348 0.05057 -0.99712 -0.07579 0.00000 -0.96339 -0.25512 0.08248 -0.98187 -0.15548 -0.10845 -0.99492 -0.04386 0.09057 -0.99589 -0.02453 0.08723 -0.99566 -0.00074 0.09309 -0.99566 0.00045 0.09303 -0.99594 0.01078 0.08941 -0.99606 0.00113 0.08868 -0.99596 -0.00422 0.08966 -0.01576 -0.81730 0.57599 -0.00007 -0.81918 0.57353 0.00019 -0.81917 0.57355 0.00007 -0.81914 0.57359 -0.00016 -0.81916 0.57357 0.00016 -0.81915 0.57358 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00001 0.00000 1.00000 0.00001 -0.00000 1.00000 -0.10686 0.99427 0.00021 -0.10691 0.99427 0.00051 -0.10310 0.99467 0.00036 -0.31502 0.94908 0.00033 -0.30561 0.95216 0.00114 -0.54640 0.83753 0.00037 -0.49532 0.86869 0.00608 -0.73383 0.67933 0.00088 -0.66442 0.74733 0.00680 -0.29659 -0.76863 0.56678 -0.62243 -0.62224 0.47476 -0.84125 -0.41735 0.34367 -0.97445 -0.15100 0.16627 -0.18468 -0.82157 0.53937 -0.52793 -0.74792 0.40237 -0.51590 -0.74782 0.41787 -0.79345 -0.56953 0.21466 -0.77990 -0.57721 0.24203 -0.94860 -0.31649 -0.00114 -0.13722 -0.84064 0.52392 -0.16245 -0.85018 0.50080 -0.46619 -0.82821 0.31103 -0.46054 -0.83055 0.31318 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.15641 0.98761 -0.01249 -0.43461 0.90058 0.00827 -0.45395 0.89092 0.01409 -0.56909 0.82226 -0.00398 -0.73529 0.67767 0.01073 -0.70710 0.70711 0.00185 -0.88271 0.46992 -0.00184 -0.89102 0.45397 0.00134 -0.98629 0.16504 -0.00142 -0.98769 0.15640 0.00000 0.63460 -0.66563 0.39270 0.63436 -0.66518 0.39385 0.72560 -0.52027 0.45035 0.68535 -0.47470 0.55223 0.72614 -0.39663 0.56161 0.68473 -0.33252 0.64852 0.72616 -0.25021 0.64038 0.68424 -0.17252 0.70856 0.72663 -0.08900 0.68124 0.68414 -0.00184 0.72935 0.72662 0.07718 0.68269 0.68429 0.16795 0.70960 0.73343 0.25027 0.63201 0.68191 0.33078 0.65237 0.50247 0.42166 0.75480 0.79620 -0.45746 0.39598 0.71150 -0.40537 0.57398 0.77296 -0.33970 0.53585 0.73978 -0.24487 0.62671 0.77536 -0.21037 0.59545 0.75248 -0.08532 0.65307 0.77897 -0.06406 0.62378 0.75300 0.07392 0.65386 0.77803 0.08772 0.62207 0.75616 0.19727 0.62394 0.66429 0.26477 0.69901 0.24972 -0.78683 0.56439 0.13613 -0.87777 0.45933 0.11798 -0.84918 0.51476 -0.06009 -0.98988 0.12857 0.23889 -0.95596 0.17049 0.27051 -0.84078 0.46894 0.49605 -0.83495 0.23833 0.50274 -0.79627 0.33645 0.36695 -0.74608 0.55562 0.51142 -0.57864 0.63532 0.47211 -0.57465 0.66850 0.49937 -0.42215 0.75659 0.55746 -0.37879 0.73875 0.46738 -0.28853 0.83565 0.57126 -0.19417 0.79747 0.47014 -0.13561 0.87211 0.50809 0.02010 0.86107 0.55298 -0.00210 0.83319 0.50233 0.17192 0.84741 0.55640 0.19138 0.80858 0.48927 0.29566 0.82049 0.37156 0.44143 0.81675 0.49467 0.42090 0.76036 -0.07970 -0.93736 0.33913 -0.06820 -0.95935 0.27384 -0.21807 -0.95055 0.22112 -0.06791 -0.98506 0.15826 0.00000 -0.99987 0.01593 -0.03964 -0.95154 0.30497 0.01193 0.52427 0.85147 -0.00000 -0.85957 -0.51102 -0.00000 -0.85957 -0.51102 -0.96142 -0.27485 0.01168 -0.30116 -0.95354 0.00802 -0.34472 -0.93786 0.03984 -0.69707 -0.71635 0.03043 -0.22886 -0.93972 -0.25408 -0.96701 -0.24590 -0.06650 -0.95011 -0.26803 -0.15951 -0.94563 -0.27551 -0.17284 -0.95556 -0.25147 -0.15383 -0.69977 -0.65778 -0.27864 -0.37006 -0.83833 -0.40032 -0.64017 -0.69253 -0.33254 -0.27651 -0.82605 -0.49110 -0.99615 0.05447 0.06865 -0.98889 0.13229 0.06784 -0.96758 0.24929 0.04058 -0.93111 0.36112 0.05125 -0.75833 0.65140 0.02465 -0.83600 0.54855 0.01404 0.00000 1.00000 -0.00000 -0.18465 -0.80642 0.56178 -0.53029 -0.68737 0.49630 -0.80208 -0.47156 0.36647 -0.96387 -0.19129 0.18539 0.96386 -0.19129 0.18540 0.80208 -0.47156 0.36647 0.53029 -0.68737 0.49630 0.18466 -0.80774 0.55987 -0.00000 1.00000 -0.00000 0.83600 0.54855 0.01404 0.75833 0.65140 0.02465 0.93111 0.36112 0.05125 0.96758 0.24929 0.04058 0.98889 0.13229 0.06784 0.99615 0.05447 0.06865 0.27651 -0.82605 -0.49110 0.64017 -0.69253 -0.33254 0.37007 -0.83833 -0.40032 0.69978 -0.65778 -0.27864 0.93015 -0.32185 -0.17675 0.96424 -0.24057 -0.11123 0.95011 -0.26803 -0.15951 0.96701 -0.24590 -0.06650 0.22886 -0.93972 -0.25408 0.69707 -0.71635 0.03043 0.34472 -0.93786 0.03984 0.30116 -0.95354 0.00802 0.96142 -0.27485 0.01167 0.95765 -0.28791 0.00238 0.69707 -0.71635 0.03043 0.96752 -0.24290 0.07004 0.96702 0.23373 0.10120 0.44469 0.87275 0.20141 0.15007 0.94757 0.28211 0.42958 0.89466 0.12265 0.96712 0.23308 0.10170 0.88684 0.45184 0.09669 0.69363 0.69363 0.19431 0.98747 0.15637 0.02141 -0.04306 0.53891 0.84126 0.03964 -0.95154 0.30497 0.05119 -0.99105 0.12326 0.06791 -0.98506 0.15826 0.06820 -0.95935 0.27384 0.07970 -0.93736 0.33913 -0.49441 0.39951 0.77197 -0.32782 0.43681 0.83770 -0.55640 0.19138 0.80858 -0.48927 0.29566 0.82049 -0.50233 0.17192 0.84741 -0.55298 -0.00210 0.83319 -0.50809 0.02010 0.86107 -0.47014 -0.13561 0.87211 -0.57126 -0.19417 0.79747 -0.46738 -0.28853 0.83565 -0.55746 -0.37879 0.73875 -0.49937 -0.42215 0.75659 -0.47211 -0.57465 0.66850 -0.51142 -0.57864 0.63532 -0.33681 -0.78370 0.52189 -0.28175 -0.75512 0.59196 -0.50274 -0.79627 0.33645 -0.49604 -0.83495 0.23833 -0.27051 -0.84078 0.46894 -0.23889 -0.95596 0.17049 0.06009 -0.98988 0.12857 -0.11798 -0.84918 0.51476 -0.13613 -0.87777 0.45934 -0.66429 0.26477 0.69901 -0.75616 0.19727 0.62394 -0.77803 0.08772 0.62207 -0.75300 0.07392 0.65386 -0.77897 -0.06406 0.62378 -0.75248 -0.08532 0.65307 -0.77536 -0.21037 0.59545 -0.73978 -0.24487 0.62671 -0.77296 -0.33970 0.53585 -0.71150 -0.40537 0.57398 -0.79620 -0.45746 0.39598 -0.55052 0.40061 0.73242 -0.68191 0.33078 0.65237 -0.73343 0.25027 0.63201 -0.68429 0.16795 0.70960 -0.72662 0.07718 0.68269 -0.68414 -0.00184 0.72935 -0.72663 -0.08900 0.68124 -0.68424 -0.17252 0.70856 -0.72616 -0.25021 0.64038 -0.68473 -0.33252 0.64852 -0.72614 -0.39663 0.56161 -0.68535 -0.47470 0.55223 -0.72560 -0.52027 0.45035 -0.63436 -0.66518 0.39385 -0.63460 -0.66563 0.39270 0.98769 0.15640 -0.00000 0.98629 0.16504 -0.00142 0.89102 0.45397 0.00134 0.88271 0.46992 -0.00184 0.70710 0.70711 0.00185 0.73529 0.67767 0.01073 0.56909 0.82227 -0.00398 0.45395 0.89092 0.01408 0.43460 0.90058 0.00827 0.15641 0.98761 -0.01249 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 0.15273 -0.86617 0.47583 0.41173 -0.87359 0.25948 0.43261 -0.86653 0.24894 0.14765 -0.86322 0.48276 0.46055 -0.83055 0.31318 0.46618 -0.82821 0.31103 0.16245 -0.85018 0.50080 0.71431 -0.69421 0.08851 0.67849 -0.72532 0.11649 0.13722 -0.84064 0.52392 0.94860 -0.31649 -0.00114 0.79507 -0.56250 0.22686 0.77632 -0.58631 0.23146 0.51589 -0.74782 0.41787 0.52793 -0.74792 0.40237 0.18468 -0.82157 0.53937 0.97445 -0.15100 0.16627 0.84126 -0.41735 0.34367 0.62243 -0.62224 0.47476 0.33025 -0.76039 0.55924 0.66442 0.74733 0.00681 0.73383 0.67933 0.00088 0.49532 0.86869 0.00608 0.54640 0.83753 0.00037 0.30561 0.95216 0.00114 0.31502 0.94908 0.00033 0.10310 0.99467 0.00036 0.10691 0.99427 0.00051 0.10687 0.99427 0.00021 0.94257 -0.33229 0.03376 -0.00000 -0.00000 1.00000 -0.00001 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00016 -0.81915 0.57358 0.00016 -0.81916 0.57357 -0.00007 -0.81914 0.57359 -0.00019 -0.81917 0.57355 0.00008 -0.81918 0.57353 0.03478 -0.81474 0.57878 0.99596 -0.00422 0.08966 0.99606 0.00113 0.08868 0.99594 0.01078 0.08941 0.99566 0.00045 0.09303 0.99566 -0.00074 0.09309 0.99589 -0.02453 0.08723 0.99492 -0.04386 0.09057 0.99712 -0.07579 0.00000 0.98187 -0.15548 -0.10845 0.96339 -0.25512 0.08248 0.88983 -0.45348 0.05057 0.69629 -0.69631 0.17415 0.80014 -0.59240 -0.09401 0.64480 -0.76159 -0.06484 0.19818 -0.96944 0.14457 0.30897 -0.95094 0.01571 0.95817 -0.28538 0.02161 0.98726 -0.15633 -0.02955 0.96453 -0.24916 -0.08717 0.96824 -0.21178 -0.13291 0.96527 -0.22815 -0.12724 0.92566 -0.35400 -0.13359 0.88605 -0.45155 -0.10496 0.69377 -0.71869 -0.04660 0.70567 -0.70569 -0.06343 0.69571 -0.59806 -0.39790 0.64066 -0.69026 -0.33630 0.36744 -0.83266 -0.41433 0.29878 -0.91958 -0.25516 0.26435 -0.91036 -0.31837 -1.00000 -0.00000 0.00000 -1.00000 0.00003 0.00003 -1.00000 -0.00044 0.00026 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.45492 -0.69848 -0.55242 0.45573 -0.69856 -0.55166 0.62626 -0.65836 -0.41756 0.59609 -0.67308 -0.43777 0.39819 -0.76716 -0.50290 -0.43938 -0.71403 -0.54507 -0.60326 -0.71049 -0.36234 -0.51410 -0.73917 -0.43513 -0.45554 -0.75926 -0.46477 -0.39950 -0.78139 -0.47941 -0.00634 -0.89015 -0.45563 -0.00005 -0.87655 -0.48130 -0.00000 -0.81914 0.57360 -0.00019 -0.81919 0.57352 0.00014 -0.81912 0.57362 -0.00014 -0.81916 0.57357 0.00019 -0.81919 0.57352 -0.00014 -0.81912 0.57362 0.00014 -0.81916 0.57357 -0.68186 0.46553 -0.56422 -0.66333 0.36884 -0.65111 0.66333 0.36884 -0.65111 0.68186 0.46553 -0.56422 -0.98563 0.00128 -0.16894 0.98583 0.00128 -0.16773 -0.27402 0.79933 -0.53477 0.52064 0.85377 -0.00301 0.04210 -0.57464 -0.81732 0.11996 -0.67436 -0.72860 + + + + + + + + + + + + + + +

4 0 5 0 6 0 3 1 0 1 8 1 13 2 21 2 14 2 12 3 13 3 14 3 20 4 21 4 13 4 12 5 15 5 13 5 19 6 18 6 16 6 20 7 18 7 21 7 19 8 17 8 18 8 18 9 17 9 21 9 30 10 31 10 32 10 33 11 30 11 32 11 44 12 45 12 1 12 2 13 1 13 45 13 45 14 46 14 2 14 2 15 46 15 47 15 48 16 2 16 47 16 47 17 49 17 48 17 50 18 48 18 49 18 50 19 49 19 51 19 52 20 50 20 51 20 52 21 51 21 53 21 3 22 52 22 53 22 60 23 63 23 62 23 64 24 63 24 60 24 59 25 64 25 60 25 65 26 62 26 63 26 66 27 67 27 65 27 63 28 66 28 65 28 66 29 63 29 64 29 64 30 48 30 50 30 68 31 64 31 50 31 64 32 68 32 66 32 69 33 67 33 66 33 50 34 52 34 68 34 70 35 66 35 68 35 68 36 52 36 3 36 68 37 3 37 72 37 68 38 72 38 70 38 73 39 70 39 72 39 74 40 75 40 43 40 42 41 74 41 43 41 4 42 75 42 74 42 74 43 76 43 4 43 4 44 6 44 77 44 77 45 78 45 35 45 78 46 79 46 35 46 81 47 30 47 33 47 33 48 41 48 81 48 82 49 81 49 41 49 41 50 40 50 82 50 83 51 8 51 84 51 38 52 0 52 3 52 83 53 3 53 8 53 82 54 40 54 39 54 82 55 39 55 38 55 9 56 3 56 83 56 72 57 3 57 9 57 9 58 85 58 72 58 85 59 86 59 72 59 73 60 72 60 86 60 61 61 62 61 65 61 65 62 67 62 61 62 67 63 69 63 58 63 56 64 58 64 69 64 69 65 71 65 56 65 57 66 56 66 71 66 71 67 70 67 57 67 54 68 57 68 70 68 70 69 73 69 54 69 55 70 54 70 73 70 73 71 86 71 55 71 80 72 55 72 86 72 86 73 85 73 80 73 85 74 9 74 80 74 80 75 9 75 10 75 9 76 83 76 10 76 83 77 84 77 10 77 87 78 84 78 8 78 8 79 0 79 87 79 37 80 38 80 39 80 82 81 38 81 53 81 38 82 3 82 53 82 59 83 2 83 64 83 48 84 64 84 2 84 131 85 28 85 115 85 120 86 115 86 22 86 141 87 126 87 29 87 95 88 126 88 141 88 92 89 89 89 26 89 94 90 24 90 93 90 25 91 24 91 94 91 91 92 24 92 25 92 27 93 24 93 91 93 90 94 27 94 91 94 27 95 90 95 97 95 90 96 124 96 97 96 124 97 90 97 125 97 109 98 125 98 90 98 125 99 109 99 122 99 108 100 122 100 109 100 122 101 108 101 123 101 110 102 123 102 108 102 123 103 110 103 121 103 112 104 121 104 110 104 114 105 118 105 112 105 118 106 114 106 117 106 91 107 107 107 90 107 107 108 91 108 25 108 107 109 25 109 29 109 25 110 94 110 29 110 95 111 141 111 140 111 94 112 92 112 29 112 29 113 92 113 26 113 29 114 26 114 141 114 94 115 93 115 92 115 95 116 139 116 96 116 138 117 96 117 139 117 138 118 149 118 96 118 99 119 145 119 98 119 100 120 145 120 99 120 104 121 100 121 101 121 104 122 101 122 102 122 106 123 104 123 103 123 104 124 106 124 105 124 137 125 136 125 106 125 106 126 136 126 105 126 90 127 107 127 109 127 111 128 109 128 107 128 111 129 107 129 29 129 111 130 29 130 127 130 109 131 111 131 113 131 129 132 111 132 127 132 110 133 113 133 112 133 115 134 113 134 111 134 111 135 129 135 115 135 115 136 129 136 131 136 113 137 115 137 116 137 116 138 114 138 113 138 113 139 114 139 112 139 114 140 116 140 117 140 120 141 119 141 115 141 115 142 119 142 116 142 119 143 117 143 116 143 29 144 126 144 127 144 127 145 126 145 128 145 127 146 128 146 129 146 129 147 128 147 130 147 129 148 130 148 131 148 132 149 131 149 130 149 131 150 132 150 28 150 28 151 132 151 133 151 134 152 22 152 133 152 133 153 22 153 28 153 135 154 22 154 134 154 147 155 149 155 138 155 149 156 147 156 148 156 142 157 144 157 143 157 31 158 146 158 148 158 30 159 146 159 31 159 146 160 149 160 148 160 150 161 151 161 152 161 146 162 153 162 162 162 146 163 162 163 157 163 164 164 163 164 162 164 190 165 188 165 189 165 176 166 190 166 175 166 188 167 169 167 167 167 191 168 169 168 188 168 188 169 190 169 191 169 192 170 176 170 177 170 190 171 176 171 192 171 192 172 191 172 190 172 169 173 191 173 171 173 178 174 192 174 177 174 191 175 173 175 171 175 193 176 173 176 191 176 191 177 192 177 193 177 194 178 193 178 192 178 194 179 178 179 179 179 192 180 178 180 194 180 173 181 193 181 174 181 180 182 194 182 179 182 193 183 194 183 195 183 193 184 172 184 174 184 195 185 172 185 193 185 194 186 180 186 196 186 196 187 195 187 194 187 181 188 196 188 180 188 172 189 195 189 170 189 195 190 196 190 197 190 197 191 170 191 195 191 198 192 197 192 196 192 198 193 181 193 182 193 196 194 181 194 198 194 183 195 198 195 182 195 170 196 197 196 168 196 197 197 198 197 199 197 197 198 166 198 168 198 199 199 166 199 197 199 200 200 199 200 198 200 200 201 183 201 184 201 198 202 183 202 200 202 185 203 200 203 184 203 203 204 242 204 244 204 203 205 201 205 202 205 240 206 242 206 203 206 218 207 219 207 202 207 204 208 202 208 220 208 202 209 219 209 220 209 202 210 204 210 203 210 203 211 205 211 240 211 205 212 238 212 240 212 205 213 203 213 204 213 235 214 238 214 205 214 220 215 221 215 204 215 206 216 204 216 222 216 204 217 221 217 222 217 204 218 206 218 205 218 205 219 207 219 235 219 207 220 205 220 206 220 233 221 235 221 207 221 222 222 223 222 206 222 206 223 208 223 207 223 208 224 206 224 223 224 207 225 209 225 233 225 209 226 231 226 233 226 209 227 207 227 208 227 223 228 224 228 208 228 232 229 231 229 209 229 210 230 208 230 225 230 208 231 224 231 225 231 208 232 210 232 209 232 211 233 209 233 210 233 209 234 211 234 232 234 211 235 234 235 232 235 225 236 226 236 210 236 236 237 234 237 211 237 210 238 212 238 211 238 212 239 210 239 227 239 210 240 226 240 227 240 214 241 211 241 212 241 211 242 214 242 236 242 214 243 239 243 236 243 227 244 228 244 212 244 241 245 239 245 214 245 212 246 213 246 214 246 213 247 212 247 230 247 212 248 245 248 230 248 212 249 228 249 245 249 214 250 215 250 241 250 214 251 213 251 215 251 243 252 241 252 229 252 241 253 215 253 229 253 187 254 186 254 216 254 217 255 216 255 186 255 186 256 185 256 217 256 218 257 217 257 185 257 185 258 184 258 218 258 219 259 218 259 184 259 184 260 183 260 219 260 220 261 219 261 183 261 183 262 182 262 220 262 221 263 220 263 182 263 182 264 181 264 221 264 222 265 221 265 181 265 181 266 180 266 222 266 223 267 222 267 180 267 180 268 179 268 223 268 224 269 223 269 179 269 179 270 178 270 224 270 225 271 224 271 178 271 178 272 177 272 225 272 226 273 225 273 177 273 177 274 176 274 226 274 227 275 226 275 176 275 176 276 175 276 227 276 228 277 227 277 175 277 175 278 164 278 228 278 245 279 228 279 164 279 240 280 238 280 237 280 242 281 240 281 237 281 241 282 243 282 237 282 244 283 242 283 237 283 245 284 164 284 162 284 162 285 246 285 245 285 296 286 266 286 287 286 296 287 287 287 158 287 249 288 253 288 248 288 253 289 255 289 254 289 253 290 249 290 255 290 250 291 255 291 249 291 254 292 255 292 256 292 257 293 250 293 135 293 255 294 250 294 257 294 257 295 256 295 255 295 256 296 257 296 258 296 134 297 257 297 135 297 259 298 258 298 257 298 257 299 134 299 259 299 133 300 259 300 134 300 258 301 259 301 260 301 261 302 260 302 259 302 259 303 133 303 261 303 132 304 261 304 133 304 260 305 261 305 262 305 261 306 263 306 262 306 264 307 263 307 261 307 264 308 132 308 130 308 261 309 132 309 264 309 266 310 265 310 267 310 268 311 270 311 269 311 268 312 320 312 270 312 265 313 320 313 268 313 268 314 267 314 265 314 271 315 268 315 269 315 267 316 268 316 272 316 273 317 271 317 288 317 268 318 271 318 273 318 268 319 274 319 272 319 273 320 274 320 268 320 275 321 273 321 288 321 274 322 273 322 276 322 273 323 277 323 276 323 273 324 278 324 277 324 273 325 275 325 278 325 253 326 277 326 278 326 283 327 274 327 276 327 284 328 274 328 283 328 161 329 285 329 279 329 274 330 284 330 272 330 284 331 285 331 272 331 286 332 272 332 285 332 285 333 161 333 286 333 160 334 286 334 161 334 272 335 286 335 267 335 287 336 160 336 159 336 286 337 160 337 287 337 287 338 267 338 286 338 158 339 287 339 159 339 267 340 287 340 266 340 270 341 21 341 17 341 320 342 21 342 270 342 269 343 17 343 19 343 269 344 270 344 17 344 275 345 289 345 290 345 288 346 289 346 275 346 291 347 275 347 290 347 288 348 16 348 289 348 271 349 16 349 288 349 271 350 19 350 16 350 269 351 19 351 271 351 128 352 126 352 252 352 130 353 128 353 252 353 130 354 252 354 264 354 252 355 263 355 264 355 251 356 263 356 252 356 247 357 275 357 291 357 247 358 278 358 275 358 247 359 248 359 278 359 248 360 253 360 278 360 149 361 146 361 157 361 149 362 157 362 280 362 149 363 280 363 96 363 96 364 280 364 281 364 96 365 281 365 95 365 95 366 281 366 282 366 126 367 95 367 282 367 126 368 282 368 251 368 126 369 251 369 252 369 53 370 333 370 334 370 53 371 334 371 303 371 53 372 303 372 82 372 82 373 303 373 304 373 81 374 82 374 304 374 81 375 304 375 305 375 30 376 81 376 305 376 30 377 305 377 153 377 30 378 153 378 146 378 337 379 309 379 332 379 338 380 309 380 337 380 338 381 311 381 309 381 338 382 292 382 311 382 334 383 333 383 322 383 333 384 321 384 322 384 49 385 321 385 333 385 49 386 333 386 51 386 51 387 333 387 53 387 317 388 315 388 12 388 315 389 15 389 12 389 315 390 295 390 15 390 295 391 294 391 15 391 292 392 293 392 311 392 295 393 311 393 294 393 311 394 293 394 294 394 317 395 14 395 316 395 317 396 12 396 14 396 320 397 316 397 21 397 316 398 14 398 21 398 319 399 266 399 296 399 158 400 156 400 296 400 296 401 297 401 319 401 297 402 296 402 155 402 296 403 156 403 155 403 314 404 319 404 297 404 155 405 154 405 297 405 298 406 297 406 154 406 297 407 298 407 314 407 299 408 314 408 298 408 312 409 314 409 299 409 154 410 307 410 298 410 300 411 298 411 307 411 298 412 300 412 299 412 299 413 301 413 312 413 301 414 310 414 312 414 301 415 299 415 300 415 307 416 308 416 300 416 306 417 310 417 302 417 310 418 301 418 302 418 331 419 332 419 306 419 332 420 309 420 306 420 313 421 309 421 311 421 309 422 313 422 306 422 313 423 310 423 306 423 312 424 310 424 313 424 311 425 295 425 313 425 313 426 318 426 312 426 318 427 314 427 312 427 318 428 313 428 315 428 313 429 295 429 315 429 319 430 314 430 318 430 315 431 317 431 318 431 318 432 265 432 319 432 265 433 318 433 320 433 318 434 316 434 320 434 318 435 317 435 316 435 266 436 319 436 265 436 324 437 321 437 47 437 321 438 49 438 47 438 321 439 324 439 322 439 324 440 323 440 322 440 325 441 323 441 324 441 47 442 46 442 324 442 326 443 324 443 46 443 324 444 326 444 325 444 327 445 325 445 326 445 46 446 45 446 326 446 328 447 326 447 45 447 326 448 328 448 327 448 45 449 44 449 328 449 329 450 327 450 328 450 328 451 330 451 329 451 330 452 328 452 335 452 328 453 44 453 335 453 331 454 329 454 330 454 335 455 336 455 330 455 332 456 330 456 336 456 330 457 332 457 331 457 336 458 337 458 332 458 349 459 339 459 148 459 148 460 339 460 31 460 31 461 339 461 370 461 339 462 349 462 346 462 370 463 339 463 346 463 374 464 340 464 144 464 341 465 88 465 342 465 343 466 357 466 344 466 343 467 342 467 357 467 341 468 342 468 343 468 343 469 344 469 345 469 345 470 347 470 346 470 344 471 347 471 345 471 343 472 348 472 341 472 138 473 348 473 147 473 349 474 147 474 348 474 349 475 343 475 345 475 348 476 343 476 349 476 147 477 349 477 148 477 346 478 349 478 345 478 359 479 102 479 358 479 354 480 144 480 340 480 351 481 356 481 355 481 357 482 342 482 356 482 356 483 351 483 357 483 344 484 357 484 351 484 362 485 363 485 365 485 364 486 367 486 363 486 365 487 363 487 367 487 366 488 374 488 34 488 5 489 360 489 361 489 351 490 355 490 367 490 367 491 364 491 351 491 344 492 351 492 364 492 346 493 372 493 370 493 32 494 31 494 370 494 371 495 370 495 373 495 370 496 372 496 373 496 370 497 371 497 32 497 33 498 32 498 371 498 373 499 37 499 371 499 344 500 364 500 347 500 364 501 372 501 347 501 372 502 346 502 347 502 373 503 372 503 364 503 37 504 373 504 362 504 373 505 363 505 362 505 373 506 364 506 363 506 37 507 362 507 36 507 355 508 356 508 352 508 368 509 352 509 350 509 34 510 144 510 142 510 341 511 26 511 88 511 141 512 26 512 341 512 104 513 102 513 103 513 101 514 358 514 102 514 358 515 101 515 380 515 100 516 380 516 101 516 380 517 100 517 379 517 99 518 379 518 100 518 379 519 99 519 23 519 98 520 23 520 99 520 23 521 98 521 353 521 375 522 353 522 98 522 353 523 375 523 354 523 354 524 375 524 144 524 93 525 89 525 92 525 88 526 26 526 89 526 350 527 377 527 378 527 350 528 378 528 359 528 358 529 350 529 359 529 380 530 350 530 358 530 376 531 377 531 350 531 376 532 350 532 352 532 88 533 376 533 342 533 341 534 348 534 139 534 348 535 138 535 139 535 341 536 140 536 141 536 376 537 352 537 356 537 356 538 342 538 376 538 365 539 389 539 362 539 389 540 365 540 385 540 37 541 39 541 40 541 37 542 40 542 41 542 371 543 41 543 33 543 37 544 41 544 371 544 36 545 362 545 389 545 389 546 385 546 369 546 369 547 385 547 386 547 389 548 369 548 388 548 381 549 361 549 369 549 361 550 360 550 369 550 369 551 360 551 387 551 369 552 387 552 388 552 87 553 0 553 36 553 34 554 390 554 366 554 383 555 366 555 390 555 390 556 79 556 383 556 11 557 383 557 79 557 79 558 78 558 11 558 384 559 11 559 78 559 78 560 77 560 384 560 381 561 384 561 77 561 77 562 6 562 381 562 361 563 381 563 6 563 6 564 5 564 361 564 4 565 76 565 5 565 368 566 350 566 369 566 369 567 386 567 368 567 37 568 0 568 38 568 36 569 0 569 37 569 34 570 374 570 144 570 352 571 368 571 355 571 54 572 55 572 393 572 393 573 394 573 54 573 393 574 391 574 394 574 395 575 54 575 394 575 395 576 56 576 57 576 54 577 395 577 57 577 58 578 56 578 395 578 59 579 394 579 392 579 394 580 59 580 395 580 60 581 61 581 58 581 395 582 60 582 58 582 60 583 395 583 59 583 62 584 61 584 60 584 55 585 80 585 393 585 58 586 61 586 67 586 7 587 80 587 10 587 393 588 80 588 7 588 393 589 74 589 42 589 74 590 393 590 7 590 106 591 27 591 398 591 398 592 137 592 106 592 121 593 112 593 118 593 97 594 398 594 27 594 398 595 97 595 124 595 117 596 119 596 118 596 119 597 120 597 396 597 396 598 121 598 119 598 119 599 121 599 118 599 397 600 396 600 120 600 120 601 399 601 397 601 121 602 396 602 123 602 125 603 122 603 396 603 396 604 122 604 123 604 396 605 397 605 125 605 397 606 400 606 398 606 398 607 125 607 397 607 125 608 398 608 124 608 34 609 142 609 403 609 375 610 145 610 144 610 143 611 144 611 145 611 137 612 247 612 136 612 400 613 247 613 137 613 400 614 248 614 247 614 401 615 248 615 400 615 248 616 401 616 249 616 399 617 249 617 401 617 249 618 399 618 250 618 399 619 135 619 250 619 22 620 135 620 399 620 400 621 397 621 401 621 397 622 399 622 401 622 145 623 100 623 104 623 145 624 375 624 98 624 103 625 24 625 27 625 247 626 291 626 136 626 143 627 20 627 142 627 18 628 20 628 143 628 136 629 291 629 105 629 105 630 291 630 290 630 105 631 290 631 104 631 104 632 290 632 289 632 145 633 104 633 289 633 145 634 289 634 16 634 145 635 18 635 143 635 145 636 16 636 18 636 399 637 120 637 22 637 400 638 137 638 398 638 106 639 103 639 27 639 74 640 7 640 76 640 391 641 393 641 42 641 392 642 1 642 59 642 35 643 13 643 15 643 35 644 403 644 13 644 35 645 15 645 294 645 35 646 294 646 4 646 4 647 294 647 293 647 75 648 4 648 293 648 75 649 293 649 292 649 43 650 75 650 292 650 13 651 403 651 20 651 403 652 142 652 20 652 338 653 43 653 292 653 367 654 382 654 365 654 76 655 7 655 10 655 79 656 390 656 35 656 35 657 4 657 77 657 394 658 402 658 392 658 391 659 402 659 394 659 1 660 392 660 44 660 392 661 335 661 44 661 336 662 335 662 392 662 392 663 402 663 336 663 337 664 336 664 402 664 402 665 391 665 337 665 391 666 338 666 337 666 391 667 42 667 338 667 42 668 43 668 338 668 382 669 367 669 355 669 355 670 368 670 382 670 386 671 382 671 368 671 403 672 35 672 34 672 390 673 34 673 35 673 152 674 151 674 547 674 547 675 548 675 152 675 404 676 152 676 548 676 404 677 405 677 152 677 406 678 407 678 152 678 406 679 152 679 405 679 406 680 405 680 408 680 409 681 406 681 408 681 409 682 410 682 407 682 406 683 409 683 407 683 411 684 410 684 409 684 408 685 412 685 409 685 409 686 412 686 413 686 409 687 413 687 414 687 415 688 409 688 414 688 415 689 416 689 411 689 409 690 415 690 411 690 407 691 150 691 152 691 417 692 150 692 407 692 418 693 417 693 407 693 410 694 419 694 418 694 407 695 410 695 418 695 410 696 411 696 419 696 416 697 420 697 421 697 416 698 421 698 419 698 411 699 416 699 419 699 331 700 422 700 329 700 327 701 329 701 422 701 422 702 423 702 327 702 327 703 423 703 424 703 325 704 327 704 424 704 424 705 425 705 325 705 325 706 425 706 426 706 418 707 428 707 427 707 427 708 308 708 418 708 417 709 418 709 308 709 307 710 150 710 417 710 308 711 307 711 417 711 307 712 154 712 150 712 429 713 431 713 430 713 430 714 431 714 432 714 433 715 430 715 432 715 245 716 246 716 433 716 432 717 245 717 433 717 434 718 246 718 153 718 305 719 433 719 434 719 153 720 305 720 434 720 430 721 433 721 305 721 305 722 304 722 430 722 429 723 430 723 304 723 304 724 303 724 429 724 435 725 429 725 303 725 303 726 334 726 435 726 438 727 428 727 439 727 439 728 441 728 440 728 441 729 443 729 442 729 443 730 422 730 331 730 444 731 427 731 438 731 438 732 440 732 444 732 302 733 444 733 440 733 440 734 442 734 302 734 306 735 302 735 442 735 442 736 331 736 306 736 308 737 427 737 444 737 444 738 300 738 308 738 444 739 302 739 301 739 300 740 444 740 301 740 445 741 446 741 447 741 447 742 420 742 445 742 448 743 445 743 420 743 416 744 449 744 448 744 420 745 416 745 448 745 413 746 450 746 237 746 450 747 244 747 237 747 449 748 416 748 415 748 449 749 415 749 414 749 449 750 414 750 413 750 449 751 413 751 237 751 243 752 449 752 237 752 230 753 245 753 451 753 230 754 451 754 452 754 213 755 230 755 452 755 213 756 452 756 453 756 213 757 453 757 454 757 215 758 213 758 454 758 454 759 455 759 215 759 229 760 215 760 455 760 455 761 449 761 229 761 243 762 229 762 449 762 437 763 436 763 456 763 457 764 456 764 436 764 436 765 458 765 457 765 459 766 457 766 458 766 458 767 460 767 459 767 461 768 459 768 460 768 460 769 462 769 461 769 463 770 461 770 462 770 462 771 464 771 463 771 465 772 463 772 464 772 464 773 466 773 465 773 467 774 465 774 466 774 466 775 441 775 467 775 467 776 441 776 439 776 428 777 467 777 439 777 436 778 426 778 458 778 460 779 458 779 426 779 426 780 425 780 460 780 462 781 460 781 425 781 425 782 424 782 462 782 464 783 462 783 424 783 424 784 423 784 464 784 466 785 464 785 423 785 423 786 422 786 466 786 466 787 422 787 443 787 466 788 443 788 441 788 456 789 455 789 454 789 454 790 453 790 456 790 468 791 456 791 453 791 429 792 469 792 431 792 469 793 429 793 435 793 469 794 435 794 437 794 468 795 469 795 437 795 437 796 456 796 468 796 457 797 455 797 456 797 459 798 449 798 455 798 457 799 459 799 455 799 448 800 449 800 459 800 459 801 461 801 448 801 445 802 448 802 461 802 461 803 463 803 445 803 446 804 445 804 463 804 465 805 447 805 446 805 463 806 465 806 446 806 420 807 447 807 465 807 465 808 467 808 420 808 421 809 420 809 467 809 428 810 419 810 421 810 467 811 428 811 421 811 468 812 453 812 452 812 452 813 469 813 468 813 431 814 469 814 432 814 469 815 451 815 245 815 432 816 469 816 245 816 469 817 452 817 451 817 418 818 419 818 428 818 216 819 404 819 187 819 548 820 187 820 404 820 201 821 203 821 244 821 470 822 217 822 218 822 202 823 470 823 218 823 470 824 202 824 201 824 216 825 217 825 470 825 244 826 450 826 201 826 201 827 450 827 413 827 201 828 413 828 412 828 408 829 201 829 412 829 201 830 408 830 470 830 470 831 405 831 216 831 470 832 408 832 405 832 404 833 216 833 405 833 325 834 426 834 323 834 426 835 436 835 323 835 323 836 436 836 322 836 322 837 436 837 437 837 334 838 322 838 437 838 334 839 437 839 435 839 246 840 162 840 153 840 427 841 428 841 438 841 438 842 439 842 440 842 440 843 441 843 442 843 331 844 442 844 443 844 254 845 512 845 513 845 509 846 513 846 514 846 517 847 509 847 515 847 527 848 517 848 516 848 163 849 157 849 162 849 251 850 520 850 518 850 251 851 518 851 263 851 263 852 518 852 519 852 262 853 263 853 519 853 528 854 262 854 519 854 260 855 262 855 528 855 548 856 471 856 187 856 473 857 471 857 472 857 473 858 187 858 471 858 474 859 473 859 472 859 472 860 541 860 474 860 474 861 541 861 540 861 474 862 540 862 502 862 501 863 474 863 502 863 187 864 473 864 186 864 473 865 474 865 200 865 200 866 185 866 473 866 473 867 185 867 186 867 474 868 501 868 199 868 199 869 501 869 499 869 199 870 200 870 474 870 166 871 199 871 499 871 498 872 188 872 167 872 189 873 497 873 190 873 190 874 497 874 164 874 190 875 164 875 175 875 188 876 498 876 475 876 475 877 493 877 188 877 188 878 493 878 189 878 500 879 475 879 498 879 535 880 516 880 477 880 476 881 496 881 495 881 523 882 164 882 476 882 476 883 164 883 496 883 495 884 478 884 476 884 478 885 495 885 494 885 480 886 534 886 516 886 516 887 534 887 477 887 482 888 533 888 480 888 480 889 533 889 534 889 533 890 482 890 505 890 484 891 506 891 482 891 482 892 506 892 505 892 506 893 484 893 507 893 486 894 507 894 484 894 507 895 486 895 504 895 488 896 504 896 486 896 504 897 488 897 503 897 490 898 491 898 488 898 488 899 491 899 503 899 491 900 490 900 492 900 490 901 479 901 492 901 518 902 478 902 479 902 478 903 518 903 476 903 476 904 518 904 520 904 476 905 520 905 525 905 525 906 523 906 476 906 478 907 494 907 479 907 492 908 479 908 494 908 481 909 514 909 512 909 481 910 512 910 532 910 531 911 481 911 532 911 481 912 531 912 483 912 530 913 483 913 531 913 483 914 530 914 485 914 529 915 485 915 530 915 485 916 529 916 487 916 528 917 487 917 529 917 487 918 528 918 489 918 519 919 489 919 528 919 516 920 515 920 480 920 480 921 515 921 514 921 481 922 480 922 514 922 480 923 481 923 482 923 483 924 482 924 481 924 482 925 483 925 484 925 485 926 484 926 483 926 484 927 485 927 486 927 487 928 486 928 485 928 486 929 487 929 488 929 489 930 488 930 487 930 488 931 489 931 490 931 519 932 490 932 489 932 490 933 519 933 479 933 518 934 479 934 519 934 500 935 503 935 475 935 475 936 503 936 491 936 475 937 491 937 493 937 493 938 491 938 492 938 493 939 492 939 189 939 189 940 492 940 494 940 189 941 494 941 495 941 189 942 495 942 497 942 497 943 495 943 496 943 497 944 496 944 164 944 499 945 165 945 166 945 498 946 165 946 500 946 501 947 165 947 499 947 500 948 165 948 503 948 533 949 504 949 538 949 538 950 504 950 503 950 504 951 533 951 507 951 505 952 507 952 533 952 507 953 505 953 506 953 508 954 279 954 285 954 285 955 284 955 508 955 283 956 508 956 284 956 279 957 508 957 526 957 508 958 283 958 511 958 511 959 283 959 510 959 511 960 526 960 508 960 277 961 510 961 276 961 276 962 510 962 283 962 526 963 511 963 527 963 513 964 277 964 254 964 277 965 513 965 509 965 277 966 509 966 510 966 511 967 510 967 509 967 517 968 511 968 509 968 511 969 517 969 527 969 512 970 254 970 532 970 514 971 513 971 512 971 515 972 509 972 514 972 517 973 515 973 516 973 282 974 520 974 251 974 520 975 282 975 525 975 281 976 525 976 282 976 525 977 281 977 524 977 280 978 524 978 281 978 524 979 280 979 522 979 157 980 521 980 280 980 280 981 521 981 522 981 157 982 163 982 521 982 277 983 253 983 254 983 523 984 522 984 164 984 522 985 163 985 164 985 522 986 523 986 524 986 525 987 524 987 523 987 279 988 151 988 161 988 526 989 536 989 279 989 279 990 536 990 151 990 536 991 526 991 535 991 527 992 535 992 526 992 535 993 527 993 516 993 260 994 528 994 529 994 530 995 260 995 529 995 260 996 530 996 258 996 258 997 530 997 531 997 532 998 258 998 531 998 258 999 532 999 256 999 254 1000 256 1000 532 1000 533 1001 538 1001 534 1001 542 1002 477 1002 538 1002 538 1003 477 1003 534 1003 543 1004 477 1004 542 1004 545 1005 535 1005 543 1005 543 1006 535 1006 477 1006 535 1007 545 1007 536 1007 536 1008 545 1008 151 1008 547 1009 151 1009 545 1009 544 1010 542 1010 537 1010 537 1011 542 1011 538 1011 537 1012 539 1012 544 1012 544 1013 539 1013 540 1013 544 1014 540 1014 541 1014 472 1015 544 1015 541 1015 542 1016 544 1016 543 1016 546 1017 545 1017 544 1017 544 1018 545 1018 543 1018 544 1019 472 1019 546 1019 546 1020 472 1020 471 1020 546 1021 471 1021 547 1021 546 1022 547 1022 545 1022 548 1023 547 1023 471 1023 24 1024 103 1024 102 1024 24 1025 102 1025 359 1025 24 1026 359 1026 378 1026 24 1027 378 1027 377 1027 24 1028 377 1028 376 1028 24 1029 376 1029 88 1029 88 1030 89 1030 24 1030 5 1031 76 1031 10 1031 5 1032 10 1032 360 1032 10 1033 387 1033 360 1033 10 1034 388 1034 387 1034 10 1035 389 1035 388 1035 10 1036 36 1036 389 1036 36 1037 10 1037 87 1037 84 1038 87 1038 10 1038 89 1039 93 1039 24 1039 239 1040 241 1040 237 1040 236 1041 239 1041 237 1041 234 1042 236 1042 237 1042 232 1043 234 1043 237 1043 231 1044 232 1044 237 1044 231 1045 237 1045 233 1045 233 1046 237 1046 235 1046 235 1047 237 1047 238 1047 165 1048 168 1048 166 1048 165 1049 170 1049 168 1049 165 1050 172 1050 170 1050 165 1051 174 1051 172 1051 165 1052 173 1052 174 1052 165 1053 171 1053 173 1053 165 1054 169 1054 171 1054 165 1055 167 1055 169 1055 165 1056 498 1056 167 1056 165 1057 501 1057 502 1057 165 1058 502 1058 540 1058 165 1059 540 1059 539 1059 165 1060 539 1060 537 1060 165 1061 537 1061 538 1061 165 1062 538 1062 503 1062 381 1063 369 1063 384 1063 11 1064 384 1064 369 1064 11 1065 369 1065 383 1065 366 1066 383 1066 369 1066 366 1067 369 1067 374 1067 379 1068 350 1068 380 1068 23 1069 350 1069 379 1069 23 1070 353 1070 350 1070 353 1071 354 1071 350 1071 340 1072 350 1072 354 1072 340 1073 369 1073 350 1073 340 1074 374 1074 369 1074 150 1075 158 1075 151 1075 150 1076 156 1076 158 1076 150 1077 155 1077 156 1077 150 1078 154 1078 155 1078 151 1079 158 1079 159 1079 151 1080 159 1080 160 1080 151 1081 160 1081 161 1081 66 1082 70 1082 71 1082 66 1083 71 1083 69 1083 108 1084 113 1084 110 1084 108 1085 109 1085 113 1085 1 1086 2 1086 59 1086 22 1087 115 1087 28 1087 139 1088 140 1088 341 1088 95 1089 140 1089 139 1089 365 1090 382 1090 385 1090 382 1091 386 1091 385 1091

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_C6M2.dae b/URDFs/sr_description/meshes/components/forearm/forearm_C6M2.dae new file mode 100644 index 0000000..3bfce97 --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_C6M2.dae @@ -0,0 +1,134 @@ + + + + + + Blender User + Blender 2.65.10 r54602 + + 2013-02-21T11:19:02 + 2013-02-21T11:19:02 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -0.07187819 -0.004186391 0 0.04628068 0.05515515 0 -0.06897521 -0.02064979 0 -0.06235378 -0.03599995 0 0.008358657 -0.07151311 0 -0.008358657 -0.07151311 0 -0.02462542 -0.06765782 0 -0.05775284 0.04299539 0 0 0.07199996 0 -0.06611156 0.02851772 0 0.0166043 0.07005923 0 0.0395646 -0.06015509 0 0.05775284 0.04299539 0 0.06611156 0.02851772 0 0.07187819 -0.004186391 0 0.06897521 -0.02064979 0 0.06235378 -0.03599995 0 0.02462542 -0.06765782 0 -0.0395646 -0.06015509 0 -0.0523709 -0.04940938 0 -0.07090616 0.01250267 0 0.03231352 0.06434154 0 0.07090616 0.01250267 0 0.0523709 -0.04940938 0 -0.04628068 0.05515515 0 -0.03231352 0.06434154 0 -0.0166043 0.07005923 0 -0.0166043 0.07005923 0 -0.01654911 0.0698353 0.1216 -0.01154959 0.07106757 0.1216 0 0.07199996 0 -0.02280008 0.06829458 0.1216 -0.03231352 0.06434154 0 -0.03227734 0.06425672 0.1216 -0.03346002 0.06375283 0.1216 -0.04628068 0.05515515 0 -0.04325342 0.05755984 0.1216 -0.05925482 0.04090064 0.1216 -0.05762785 0.04289335 0.1216 -0.05775284 0.04299539 0 -0.05192655 0.04987615 0.1216 -0.04614305 0.05499982 0.1216 -0.06504839 0.03086584 0.1216 -0.06611156 0.02851772 0 -0.06596064 0.0284605 0.1216 -0.0691573 0.02003163 0.1216 -0.07090616 0.01250267 0 -0.07070279 0.01246112 0.1216 -0.07147502 0.008678615 0.1216 -0.07187819 -0.004186391 0 -0.07194161 -0.00289911 0.1216 -0.06897521 -0.02064979 0 -0.07054489 -0.01440185 0.1216 -0.07178664 -0.004175305 0.1216 -0.06235378 -0.03599995 0 -0.06732112 -0.02553153 0.1216 -0.06875371 -0.02058565 0.1216 -0.0523709 -0.04940938 0 -0.05577152 -0.04553604 0.1216 -0.06235378 -0.03599995 0.1216 -0.0395646 -0.06015509 0 -0.04774481 -0.05389273 0.1216 -0.05220454 -0.04924964 0.1216 -0.02455973 -0.06746101 0.1216 -0.02822154 -0.06623852 0.1216 -0.02462542 -0.06765782 0 -0.03848153 -0.06085366 0.1216 -0.03950923 -0.06008136 0.1216 -0.01723068 -0.06990778 0.1216 -0.008358657 -0.07151311 0 -0.008332788 -0.07135385 0.1216 -0.005793571 -0.07176649 0.1216 0.008358657 -0.07151311 0 0.005793571 -0.07176649 0.1216 0.02822154 -0.06623852 0.1216 0.02455973 -0.06746101 0.1216 0.02462542 -0.06765782 0 0.01723068 -0.06990778 0.1216 0.008332788 -0.07135385 0.1216 0.03848153 -0.06085366 0.1216 0.0395646 -0.06015509 0 0.03950923 -0.06008136 0.1216 0.04774481 -0.05389273 0.1216 0.0523709 -0.04940938 0 0.05220454 -0.04924964 0.1216 0.05577152 -0.04553604 0.1216 0.06235378 -0.03599995 0 0.06235378 -0.03599995 0.1216 0.06732112 -0.02553153 0.1216 0.06897521 -0.02064979 0 0.06875371 -0.02058565 0.1216 0.07054489 -0.01440185 0.1216 0.07187819 -0.004186391 0 0.07178664 -0.004175305 0.1216 0.07090616 0.01250267 0 0.07147502 0.008678615 0.1216 0.07194161 -0.00289911 0.1216 0.06611156 0.02851772 0 0.0691573 0.02003163 0.1216 0.07070279 0.01246112 0.1216 0.05762785 0.04289335 0.1216 0.05925482 0.04090064 0.1216 0.05775284 0.04299539 0 0.06504839 0.03086584 0.1216 0.06596064 0.0284605 0.1216 0.05192655 0.04987615 0.1216 0.04628068 0.05515515 0 0.04614305 0.05499982 0.1216 0.03231352 0.06434154 0 0.03346002 0.06375283 0.1216 0.04325342 0.05755984 0.1216 0.0166043 0.07005923 0 0.02280008 0.06829458 0.1216 0.03227734 0.06425672 0.1216 0 0.07199996 0.1216 0.01154959 0.07106757 0.1216 0.01654911 0.0698353 0.1216 0.03247708 0.06742197 0.12494 0.03485423 0.06640917 0.12494 0.03479444 0.06629526 0.1236902 0.05845278 0.04661101 0.12494 0.06172376 0.0426048 0.12494 0.06161791 0.04253172 0.1236902 0.0166741 -0.07302772 0.12494 0.00603497 -0.0747568 0.12494 0.006024599 -0.07462853 0.1236902 -0.05858427 -0.04672509 0.12494 -0.06495189 -0.03749996 0.12494 -0.06484049 -0.03743565 0.1236902 -0.07481777 -7.34357e-6 0.12494 -0.07445317 0.009040236 0.12494 -0.07432544 0.009024739 0.1236902 -0.04666709 0.05853056 0.12494 -0.04505562 0.05995815 0.12494 -0.04497838 0.05985534 0.1236902 0.06615871 0.03139269 0.1218616 0.06026619 0.04159873 0.1218616 0.06110221 0.04217582 0.122601 0.05672347 -0.04631328 0.1218616 0.06341809 -0.03661447 0.1218616 0.06429785 -0.03712236 0.122601 -0.0117467 0.07228064 0.1218616 -0.02318924 0.06946033 0.1218616 -0.02351093 0.07042384 0.122601 0.0117467 0.07228064 0.1218616 0.04399168 0.05854231 0.1218616 0.07269501 0.008826732 0.1218616 0.07174903 -0.01464766 0.1218616 0.04855972 -0.05481261 0.1218616 0.03913831 -0.06189233 0.1218616 0.01752483 -0.071101 0.1218616 0.005892455 -0.07299149 0.1218616 -0.02870327 -0.0673691 0.1218616 -0.05672347 -0.04631328 0.1218616 -0.07174903 -0.01464766 0.1218616 -0.07316952 -0.002948582 0.1218616 -0.07033771 0.02037352 0.1218616 -0.06615871 0.03139269 0.1218616 -0.05281287 0.05072742 0.1218616 -0.03403115 0.06484097 0.1218616 -0.04399168 0.05854231 0.1218616 -0.06026619 0.04159873 0.1218616 -0.03913831 -0.06189233 0.1218616 -0.005892455 -0.07299149 0.1218616 0.06847023 -0.02596729 0.1218616 0.07316952 -0.002948582 0.1218616 0.05281287 0.05072742 0.1218616 0.03403115 0.06484097 0.1218616 0.02318924 0.06946033 0.1218616 0 0.07322895 0.1218616 -0.03479444 0.06629526 0.1236902 -0.03450322 0.06574046 0.122601 0.07000589 -0.02654969 0.1236902 0.06942003 -0.02632755 0.122601 0.0737034 0.00894922 0.122601 0.07418453 -0.00298953 0.122601 0.05399739 0.05186516 0.1236902 0.05354547 0.05143111 0.122601 0.01190966 0.07328331 0.122601 0 0.07424473 0.122601 -0.01190966 0.07328331 0.122601 -0.0676425 0.03209674 0.1236902 -0.06161791 0.04253172 0.1236902 -0.06110221 0.04217582 0.122601 -0.07290077 0.01664435 0.12494 -0.07203882 0.02086627 0.12494 -0.07191526 0.02083051 0.1236902 -0.06707644 0.03182816 0.122601 -0.07269501 0.008826732 0.1218616 -0.0737034 0.00894922 0.122601 -0.07418453 -0.00298953 0.122601 -0.07481062 -0.003014743 0.1236902 -0.07335823 -0.01497614 0.1236902 -0.06847023 -0.02596729 0.1218616 -0.06341809 -0.03661447 0.1218616 -0.06429785 -0.03712236 0.122601 -0.05751037 -0.04695576 0.122601 -0.05799567 -0.04735201 0.1236902 -0.04964888 -0.05604195 0.1236902 -0.04855972 -0.05481261 0.1218616 -0.03968125 -0.06275093 0.122601 -0.02910143 -0.06830364 0.122601 -0.02934706 -0.06888008 0.1236902 -0.01791787 -0.07269573 0.1236902 0.005974173 -0.07400399 0.122601 0.0177679 -0.07208734 0.122601 0.01791787 -0.07269573 0.1236902 0.02934706 -0.06888008 0.1236902 0.02870327 -0.0673691 0.1218616 0.03968125 -0.06275093 0.122601 0.04923337 -0.05557298 0.122601 0.04964888 -0.05604195 0.1236902 0.05799567 -0.04735201 0.1236902 0.07481062 -0.003014743 0.1236902 0.07432544 0.009024739 0.1236902 0.07191526 0.02083051 0.1236902 0.07131344 0.02065616 0.122601 0.0676425 0.03209674 0.1236902 0.06775873 0.03215193 0.12494 0.06754362 0.03252452 0.12494 0.01201015 0.07390177 0.1236902 0 0.0748713 0.1236902 -0.01201015 0.07390177 0.1236902 -0.02370935 0.07101815 0.1236902 -0.03485423 0.06640917 0.12494 -0.03247708 0.06742197 0.12494 -0.04460197 0.05935442 0.122601 -0.05354547 0.05143111 0.122601 -0.05399739 0.05186516 0.1236902 -0.05409014 0.05195432 0.12494 -0.05845278 0.04661101 0.12494 -0.06775873 0.03215193 0.12494 -0.06754362 0.03252452 0.12494 -0.06172376 0.0426048 0.12494 -0.07131344 0.02065616 0.122601 -0.06735402 -0.0324375 0.12494 -0.07012617 -0.02659535 0.12494 -0.07000589 -0.02654969 0.1236902 -0.0727443 -0.01485085 0.122601 -0.07300519 -0.01665592 0.12494 -0.0734843 -0.01500189 0.12494 -0.07493913 -0.003019928 0.12494 -0.06942003 -0.02632755 0.122601 -0.032449 -0.06739687 0.12494 -0.04008489 -0.06338924 0.12494 -0.04001617 -0.06328052 0.1236902 -0.04923337 -0.05557298 0.122601 -0.04663425 -0.05846774 0.12494 -0.04973417 -0.05613827 0.12494 -0.05809533 -0.04743337 0.12494 0 -0.0747568 0.12494 -0.00603497 -0.0747568 0.12494 -0.006024599 -0.07462853 0.1236902 -0.0177679 -0.07208734 0.122601 -0.0166741 -0.07302772 0.12494 -0.01794862 -0.0728206 0.12494 -0.02939748 -0.06899845 0.12494 -0.01752483 -0.071101 0.1218616 -0.005974173 -0.07400399 0.122601 0.04663425 -0.05846774 0.12494 0.04008489 -0.06338924 0.12494 0.04001617 -0.06328052 0.1236902 0.02910143 -0.06830364 0.122601 0.032449 -0.06739687 0.12494 0.02939748 -0.06899845 0.12494 0.01794862 -0.0728206 0.12494 0.06735402 -0.0324375 0.12494 0.06495189 -0.03749996 0.12494 0.06484049 -0.03743565 0.1236902 0.05751037 -0.04695576 0.122601 0.05858427 -0.04672509 0.12494 0.05809533 -0.04743337 0.12494 0.04973417 -0.05613827 0.12494 0.07012617 -0.02659535 0.12494 0.07335823 -0.01497614 0.1236902 0.0734843 -0.01500189 0.12494 0.07300519 -0.01665592 0.12494 0.0727443 -0.01485085 0.122601 0.07493913 -0.003019928 0.12494 0.07203882 0.02086627 0.12494 0.07290077 0.01664435 0.12494 0.07445317 0.009040236 0.12494 0.07481777 -7.34357e-6 0.12494 0.06707644 0.03182816 0.122601 0.07033771 0.02037352 0.1218616 0.05409014 0.05195432 0.12494 0.04497838 0.05985534 0.1236902 0.04505562 0.05995815 0.12494 0.04666709 0.05853056 0.12494 0.04460197 0.05935442 0.122601 0.03450322 0.06574046 0.122601 0.02351093 0.07042384 0.122601 0.02370935 0.07101815 0.1236902 0.02375006 0.07114022 0.12494 0.01663351 0.07289427 0.12494 -0.02375006 0.07114022 0.12494 -0.01663351 0.07289427 0.12494 -0.01203083 0.07402873 0.12494 0 0.07499998 0.12494 0.01203083 0.07402873 0.12494 0 0.04996079 0.3576697 -0.009746849 0.04900079 0.3576697 -0.01108312 0.04859542 0.3576697 -0.01911914 0.04615771 0.3576697 -0.02158457 0.04483991 0.3576697 -0.02775669 0.04154086 0.3576697 -0.03100055 0.03887873 0.3576697 -0.03532761 0.03532761 0.3576697 -0.03887873 0.03100055 0.3576697 -0.04154086 0.02775669 0.3576697 -0.04483991 0.02158457 0.3576697 -0.04615771 0.01911914 0.3576697 -0.04859542 0.01108312 0.3576697 -0.04900079 0.009746849 0.3576697 -0.04996079 0 0.3576697 -0.04900079 -0.009746849 0.3576697 -0.04859542 -0.01108312 0.3576697 -0.04615771 -0.01911914 0.3576697 -0.04483991 -0.02158457 0.3576697 -0.04154086 -0.02775669 0.3576697 -0.03887873 -0.03100055 0.3576697 -0.03532761 -0.03532761 0.3576697 -0.03100055 -0.03887873 0.3576697 -0.02775669 -0.04154086 0.3576697 -0.02158457 -0.04483991 0.3576697 -0.01911914 -0.04615771 0.3576697 -0.01108312 -0.04859542 0.3576697 -0.009746849 -0.04900079 0.3576697 0 -0.04996079 0.3576697 0.009746849 -0.04900079 0.3576697 0.01108312 -0.04859542 0.3576697 0.01911914 -0.04615771 0.3576697 0.02158457 -0.04483991 0.3576697 0.02775669 -0.04154086 0.3576697 0.03100055 -0.03887873 0.3576697 0.03532761 -0.03532761 0.3576697 0.04996079 0 0.3576697 0.04900079 -0.009746849 0.3576697 0.03887873 -0.03100055 0.3576697 0.04154086 -0.02775669 0.3576697 0.04483991 -0.02158457 0.3576697 0.04615771 -0.01911914 0.3576697 0.04859542 -0.01108312 0.3576697 0.04900079 0.009746849 0.3576697 0.04859542 0.01108312 0.3576697 0.04615771 0.01911914 0.3576697 0.04483991 0.02158457 0.3576697 0.04154086 0.02775669 0.3576697 0.03887873 0.03100055 0.3576697 0.03532761 0.03532761 0.3576697 0.03100055 0.03887873 0.3576697 0.02775669 0.04154086 0.3576697 0.02158457 0.04483991 0.3576697 0.01911914 0.04615771 0.3576697 0.01108312 0.04859542 0.3576697 0.009746849 0.04900079 0.3576697 0 0.04001814 0.3666 0 -0.04001814 0.3666 0.007807135 -0.03924924 0.3666 -0.007807135 0.03924924 0.3666 -0.01531428 -0.03697192 0.3666 -0.007807135 -0.03924924 0.3666 0.01531428 -0.03697192 0.3666 0.02223289 -0.03327387 0.3666 0.02829712 -0.02829712 0.3666 0.03327387 -0.02223289 0.3666 0.03697192 -0.01531428 0.3666 0.03924924 -0.007807135 0.3666 -0.01531428 0.03697192 0.3666 -0.02223289 0.03327387 0.3666 -0.02829712 0.02829712 0.3666 -0.03327387 0.02223289 0.3666 -0.03697192 0.01531428 0.3666 -0.03924924 0.007807135 0.3666 -0.04001814 0 0.3666 -0.03924924 -0.007807135 0.3666 -0.03697192 -0.01531428 0.3666 -0.03327387 -0.02223289 0.3666 -0.02829712 -0.02829712 0.3666 -0.02223289 -0.03327387 0.3666 0.04001814 0 0.3666 0.03924924 0.007807135 0.3666 0.03697192 0.01531428 0.3666 0.02829712 0.02829712 0.3666 0.02223289 0.03327387 0.3666 0.01531428 0.03697192 0.3666 0.03327387 0.02223289 0.3666 0.007807135 0.03924924 0.3666 0.04067534 -0.0271784 0.3611563 0.0271784 0.04067534 0.3611563 -0.04067534 0.0271784 0.3611563 -0.0271784 -0.04067534 0.3611563 0.01668351 -0.04027754 0.365938 0.0242207 -0.0362488 0.365938 0.0308271 -0.0308271 0.365938 0.0362488 -0.0242207 0.365938 0.04027754 0.01668351 0.365938 0.0362488 0.0242207 0.365938 0.0308271 0.0308271 0.365938 0.0242207 0.0362488 0.365938 -0.01668351 0.04027754 0.365938 -0.0242207 0.0362488 0.365938 -0.0308271 0.0308271 0.365938 -0.0362488 0.0242207 0.365938 -0.04027754 -0.01668351 0.365938 -0.0362488 -0.0242207 0.365938 -0.0308271 -0.0308271 0.365938 -0.0242207 -0.0362488 0.365938 -0.04027754 0.01668351 0.365938 -0.0427584 0.008505165 0.365938 -0.04001814 0 0.3666 -0.04359608 0 0.365938 -0.0427584 -0.008505165 0.365938 0.01668351 0.04027754 0.365938 0.008505165 0.0427584 0.365938 0 0.04001814 0.3666 0 0.04359608 0.365938 -0.008505165 0.0427584 0.365938 0.04027754 -0.01668351 0.365938 0.0427584 -0.008505165 0.365938 0.04001814 0 0.3666 0.04359608 0 0.365938 0.0427584 0.008505165 0.365938 -0.01668351 -0.04027754 0.365938 -0.008505165 -0.0427584 0.365938 0 -0.04001814 0.3666 0 -0.04359608 0.365938 0.008505165 -0.0427584 0.365938 -0.04314547 0.01787143 0.3640397 -0.04580301 0.009110748 0.3640397 -0.04670029 0 0.3640397 -0.04580301 -0.009110748 0.3640397 0.01787143 0.04314547 0.3640397 0.009110748 0.04580301 0.3640397 0 0.04670029 0.3640397 -0.009110748 0.04580301 0.3640397 0.04314547 -0.01787143 0.3640397 0.04580301 -0.009110748 0.3640397 0.04670029 0 0.3640397 0.04580301 0.009110748 0.3640397 -0.01787143 -0.04314547 0.3640397 -0.009110748 -0.04580301 0.3640397 0 -0.04670029 0.3640397 0.009110748 -0.04580301 0.3640397 -0.04519605 0.0187208 0.3611563 -0.04797983 0.009543776 0.3611563 -0.04891985 0 0.3611563 -0.04797983 -0.009543776 0.3611563 0.0187208 0.04519605 0.3611563 0.009543776 0.04797983 0.3611563 0 0.04891985 0.3611563 -0.009543776 0.04797983 0.3611563 0.04519605 -0.0187208 0.3611563 0.04797983 -0.009543776 0.3611563 0.04891985 0 0.3611563 0.04797983 0.009543776 0.3611563 -0.0187208 -0.04519605 0.3611563 -0.009543776 -0.04797983 0.3611563 0 -0.04891985 0.3611563 0.009543776 -0.04797983 0.3611563 -0.0259453 -0.03882992 0.3640397 -0.0330221 -0.0330221 0.3640397 -0.03459155 -0.03459155 0.3611563 -0.04067534 -0.0271784 0.3611563 -0.03882992 -0.0259453 0.3640397 -0.04519605 -0.0187208 0.3611563 -0.04314547 -0.01787143 0.3640397 -0.04996079 0 0.3576697 -0.03882992 0.0259453 0.3640397 -0.0330221 0.0330221 0.3640397 -0.03459155 0.03459155 0.3611563 -0.0271784 0.04067534 0.3611563 -0.0259453 0.03882992 0.3640397 -0.0187208 0.04519605 0.3611563 -0.01787143 0.04314547 0.3640397 0 0.04996079 0.3576697 0.0259453 0.03882992 0.3640397 0.0330221 0.0330221 0.3640397 0.03459155 0.03459155 0.3611563 0.04067534 0.0271784 0.3611563 0.03882992 0.0259453 0.3640397 0.04519605 0.0187208 0.3611563 0.04314547 0.01787143 0.3640397 0.04996079 0 0.3576697 0.03882992 -0.0259453 0.3640397 0.0330221 -0.0330221 0.3640397 0.03459155 -0.03459155 0.3611563 0.0271784 -0.04067534 0.3611563 0.0259453 -0.03882992 0.3640397 0.0187208 -0.04519605 0.3611563 0.01787143 -0.04314547 0.3640397 0 -0.04996079 0.3576697 -9.97302e-4 -0.01712656 0.3815245 -0.001768171 -0.0185312 0.3841782 -0.000999987 -0.01719999 0.3816499 -9.99995e-4 -0.01856958 0.3839784 -9.81216e-4 -0.01700705 0.3813179 -9.26628e-4 -0.01687663 0.3810852 -5.38521e-4 -0.01542317 0.3785513 -8.26135e-4 -0.01663649 0.380657 -6.46162e-4 -0.01641011 0.3802427 -4.47178e-4 -0.01621794 0.379902 -4.20789e-4 -0.01619243 0.3798568 1.97014e-7 -0.01546436 0.3785936 -0.002096772 -0.01851475 0.3842637 -7.0358e-4 -0.01538938 0.3785163 -0.002576649 -0.01847296 0.3844786 -0.002581238 -0.01847255 0.3844807 -0.001285076 -0.01519346 0.3783108 -0.001499354 -0.01508712 0.3781969 -0.001527726 -0.01507306 0.3781819 -0.002046644 -0.01472252 0.3777934 -0.002366423 -0.01442307 0.3774439 -0.002728641 -0.01394772 0.3768467 -0.002915263 -0.01355922 0.3763078 -0.004947781 -0.01815599 0.3861157 -0.004107356 -0.01830083 0.3853677 -0.004035413 -0.01830989 0.3853209 -0.003457784 -0.01838254 0.3849452 -0.002581179 -0.01414126 0.3770898 -0.002585291 -0.01413589 0.3770831 -0.003103494 -0.01842713 0.3847146 -0.003332912 -0.01839828 0.3848639 -0.002999961 -0.01310867 0.3756 -0.002956926 -0.01282829 0.3750935 -0.004949212 -0.007979869 0.3688088 -0.002909421 -0.01271486 0.3748684 -0.002667188 -0.01242899 0.3742267 -0.003623545 -0.008763432 0.3687224 -0.00379002 -0.008693873 0.3687303 -0.004851818 -0.008058905 0.3688004 -0.006884336 -0.01766562 0.3886485 -0.006244003 -0.01785719 0.3876586 -0.006896734 -0.006075561 0.3690016 -0.00607419 -0.01790803 0.387396 -0.005246758 -0.01809781 0.386416 -0.00513035 -0.01812452 0.3862782 -0.005213558 -0.007765471 0.3688317 -0.005856633 -0.007243871 0.3688873 -0.006577312 -0.006457984 0.3689653 -0.006803452 -0.00621134 0.3689898 -0.008215844 -0.01704877 0.3918347 -0.008145928 -0.01709944 0.3915725 -0.007511317 -0.005180418 0.3690793 -0.007709681 -0.0173276 0.3903928 -0.007601857 -0.01738399 0.3901012 -0.00705558 -0.01759839 0.3889952 -0.006948053 -0.01764065 0.3887776 -0.006902217 -0.01765859 0.3886848 -0.008259892 -0.01701676 0.392 -0.007656872 -0.004889428 0.3690973 -0.007720649 -0.004761993 0.3691052 -0.008258938 -0.003585815 0.3691607 -0.008421659 -0.003108263 0.3691641 -0.008934259 -0.008014082 0.3816623 -0.008909881 -0.008552789 0.3820858 -0.008882641 -0.008974373 0.3824504 -0.008882522 -0.008976161 0.382452 -0.008833289 -0.009661018 0.383074 -0.008812069 -0.009927093 0.3833427 -0.008707344 -0.01123857 0.3846674 -0.008663773 -0.01180291 0.3853136 -0.008645296 -0.01204216 0.3855875 -0.008563995 -0.0133835 0.3873449 -0.008151829 -0.00390011 0.3691585 -0.008563041 -0.01341313 0.3873896 -0.008564233 -0.002689778 0.369167 -0.00868541 -0.00214982 0.3691106 -0.008765399 -0.001793384 0.3690733 -0.008785724 -0.001652956 0.3690319 -0.008859932 -0.001141428 0.3688811 -0.008865892 -0.001100063 0.3688688 -0.008893072 -0.01592659 0.394398 -0.008598029 -0.0167641 0.3933044 -0.008558511 -0.01680022 0.3931199 -0.008999943 -0.01500004 0.3955511 -0.008921146 -0.01568293 0.3947013 -0.00892508 -0.01445895 0.3926215 -0.008896172 -0.01589965 0.3944317 -0.00856769 -0.01352047 0.3876006 -0.008587002 -0.01358419 0.3878285 -0.008643984 -0.01368069 0.3883648 -0.008903145 -0.01430088 0.3917657 -0.008897125 -0.01428633 0.3916862 -0.008905112 -6.53215e-4 0.3686026 -0.008914709 -5.43413e-4 0.3685373 -0.008928835 -2.23709e-4 0.3682112 -0.008999943 0 0.3700508 -0.008999943 -0.005900204 0.3800812 -0.008940339 0 0.3680386 -0.008987128 -0.00684452 0.3807428 -0.008939445 -0.007899284 0.381572 -0.008940339 0 0.3680385 -0.00893867 0 0.367983 -0.002646863 -0.009171485 0.3686767 -0.002595782 -0.01238024 0.3741013 -0.002584993 -0.009187042 0.3686749 -0.002585768 -0.01237338 0.3740836 -0.002542853 -0.01234406 0.3740082 -0.002110242 -0.01216048 0.3734677 -0.001909792 -0.01210713 0.3732864 -0.001490652 -0.01203697 0.3730164 -0.001317203 -0.01200789 0.3729046 -0.001064419 -0.01198267 0.3727952 -0.001853168 -0.009370386 0.3686538 -3.73065e-4 -0.0119459 0.3726233 -0.001387298 -0.009487152 0.3686404 0.00178188 -0.01207947 0.3731865 0.002291142 -0.01222264 0.3736633 0.002582073 -0.00917834 0.3686758 0.001520574 -0.01203453 0.3730139 -1.39584e-4 -0.009602904 0.3686271 -1.03153e-4 -0.01194149 0.3726018 -3.79978e-7 -0.009594619 0.368628 -8.9312e-7 -0.01194328 0.3726105 -3.29839e-7 -0.009594619 0.368628 0 -0.01194334 0.3726106 0.001116991 -0.009528398 0.3686356 6.08811e-4 -0.01195394 0.3726624 0.001854062 -0.009369969 0.3686539 8.70613e-4 -0.01196813 0.3727291 0.002368032 -0.009259462 0.3686666 0.001498878 -0.01203233 0.3730044 0.003624618 -0.008767426 0.368722 0.003538727 -0.008815765 0.3687167 0.002829194 -0.01258963 0.3746023 0.00253278 -0.0123381 0.3739922 0.002585828 -0.01238316 0.3741015 0.002587616 -0.01238465 0.3741051 0.002923905 -0.01274454 0.3749287 0.00494647 -0.007974505 0.3688093 0.004701972 -0.008161127 0.3687891 0.002999961 -0.01310867 0.3756 0.002928555 -0.0135203 0.3762506 0.004944741 -0.01815456 0.3861229 0.002827823 -0.01376628 0.3766016 0.00436294 -0.01826155 0.3855696 0.003336846 -0.018399 0.3848602 0.003470301 -0.01838576 0.3849284 0.00348258 -0.01838403 0.3849373 0.004028677 -0.01830804 0.3853296 0.006523668 -0.006550014 0.3689574 0.005598127 -0.007477104 0.3688629 0.005327224 -0.01808422 0.3864867 0.005216658 -0.007768273 0.3688315 0.005250513 -0.01809835 0.3864137 0.00621128 -0.01787126 0.3875861 0.006890356 -0.006068527 0.3690017 0.00658673 -0.006467223 0.368965 0.007656931 -0.004887938 0.3690982 0.007244646 -0.005603373 0.3690446 0.007048606 -0.01760768 0.3889465 0.006252408 -0.01785826 0.387653 0.006894648 -0.01765614 0.3886964 0.006945312 -0.01764017 0.3887788 0.007068157 -0.01759946 0.3889889 0.007880866 -0.004499435 0.3691274 0.007729351 -0.004762291 0.3691077 0.007714927 -0.01732814 0.3903913 0.007768034 -0.01730585 0.3905065 0.008223652 -0.01704925 0.3918328 0.008940398 0 0.3680391 0.008938789 0 0.3679844 0.008931636 -2.09147e-4 0.3682234 0.008939981 -0.0079993 0.3816331 0.008929967 -2.5805e-4 0.3682793 0.008903801 -6.61226e-4 0.3685988 0.008892595 -8.34154e-4 0.3687357 0.008855104 -0.001150131 0.3688641 0.008813738 -0.001498281 0.3690056 0.008893489 -0.01589828 0.3944319 0.008939266 -0.01445853 0.3926193 0.008654892 -0.01664042 0.3934714 0.008872866 -0.01424252 0.3914442 0.008598029 -0.0167641 0.3933044 0.008268833 -0.01701807 0.3919938 0.008794903 -0.01398891 0.3900645 0.008709371 -0.0138061 0.3890467 0.008785426 -0.001650214 0.3690323 0.008692264 -0.002150475 0.3691205 0.008675158 -0.002242207 0.3691368 0.008587002 -0.01358419 0.3878285 0.00856781 -0.01352095 0.3876018 0.008563041 -0.01341331 0.3873898 0.008241474 -0.01703923 0.3918846 0.00826174 -0.003588199 0.3691647 0.008563995 -0.0133835 0.3873449 0.008604526 -0.01263993 0.3863336 0.008667767 -0.01177841 0.3853093 0.008707523 -0.0112366 0.3846651 0.008750975 -0.01069951 0.3840945 0.008812785 -0.009890019 0.3833231 0.008882582 -0.008975327 0.3824513 0.008427739 -0.003111124 0.3691656 0.008356273 -0.003362059 0.369174 0.008910119 -0.008549034 0.3820827 0.008884727 -0.008942604 0.382423 0.008954167 -0.007737517 0.381419 0.008999943 -0.005900859 0.3800817 0.008999943 0 0.3700508 0.008946955 -0.007870316 0.3815276 0.008940398 0 0.3680393 0.008928656 -0.01568359 0.3947017 0.008999943 -0.01499986 0.3955513 0.008999347 -0.01499974 0.3953347 0.008912444 -0.01583945 0.3945081 0.008948028 -0.01448702 0.3927742 0.002581954 -0.01847386 0.384474 0.002585768 -0.01414072 0.37709 0.002584218 -0.01414304 0.377093 9.22638e-4 -0.01681429 0.3809779 0.001565277 -0.01505219 0.3781593 0.001496851 -0.01508253 0.3781915 9.80936e-4 -0.01531136 0.3784351 8.85898e-4 -0.01534116 0.3784662 8.26145e-4 -0.01663649 0.380657 2.81697e-4 -0.01545763 0.3785867 0.000999987 -0.01719999 0.3816499 9.99999e-4 -0.0185697 0.3839785 0.0013749 -0.01855534 0.3840525 0.00176686 -0.01853126 0.384177 0.002385795 -0.01849329 0.3843737 9.34208e-4 -0.01687198 0.3810784 0.002271771 -0.01452028 0.3775593 0.001760125 -0.01493328 0.3780294 0.002509474 -0.01425874 0.3772439 0.002578198 -0.01847422 0.3844721 7.09929e-5 -0.01546972 0.3785992 1.41762e-7 -0.01578611 0.3791366 3.81218e-4 -0.01613956 0.379753 4.25931e-4 -0.01618951 0.3798438 4.50633e-4 -0.01621711 0.379894 0 -0.01578599 0.3791364 5.00215e-7 -0.01546436 0.3785936 0.00142312 -0.01569998 0.4194982 -0.006548583 -0.01569998 0.4020425 -0.004154145 -0.01569998 0.4005036 -0.004154145 -0.01569998 0.4186963 -0.006548583 -0.01569998 0.4171575 -0.00841248 -0.01569998 0.4041936 -0.00142312 -0.01569998 0.3997018 0.00142312 -0.01569998 0.3997018 0.004154145 -0.01569998 0.4186963 0.006548583 -0.01569998 0.4171575 -0.00142312 -0.01569998 0.4194982 -0.00841248 -0.01569998 0.4150064 -0.009594917 -0.01569998 0.4124173 -0.009594917 -0.01569998 0.4067827 -0.00999999 -0.01569998 0.4096 0.00841248 -0.01569998 0.4150064 0.004154145 -0.01569998 0.4005036 0.006548583 -0.01569998 0.4020425 0.00841248 -0.01569998 0.4041936 0.009594917 -0.01569998 0.4067827 0.009594917 -0.01569998 0.4124173 0.00999999 -0.01569998 0.4096 -0.006548583 0.01569998 0.4020425 -0.00841248 0.01569998 0.4041936 0.00142312 0.01569998 0.4194982 -0.004154145 0.01569998 0.4005036 0.004154145 0.01569998 0.4186963 0.00142312 0.01569998 0.3997018 -0.00142312 0.01569998 0.3997018 0.00841248 0.01569998 0.4150064 0.00841248 0.01569998 0.4041936 0.006548583 0.01569998 0.4020425 -0.00841248 0.01569998 0.4150064 -0.006548583 0.01569998 0.4171575 0.009594917 0.01569998 0.4067827 0.009594917 0.01569998 0.4124173 0.00999999 0.01569998 0.4096 0.006548583 0.01569998 0.4171575 0.004154145 0.01569998 0.4005036 -0.009594917 0.01569998 0.4124173 -0.009594917 0.01569998 0.4067827 -0.00999999 0.01569998 0.4096 -0.004154145 0.01569998 0.4186963 -0.00142312 0.01569998 0.4194982 -0.00999999 -0.01559996 0.4096 -0.009594917 -0.01559996 0.4067827 -0.00841248 -0.01559996 0.4041936 -0.006548583 -0.01559996 0.4020425 -0.004154145 -0.01559996 0.4005036 -0.00142312 -0.01559996 0.3997018 0.00142312 -0.01559996 0.3997018 0.004154145 -0.01559996 0.4005036 0.006548583 -0.01559996 0.4020425 0.00841248 -0.01559996 0.4041936 0.009594917 -0.01559996 0.4067827 0.00999999 -0.01559996 0.4096 0.009594917 -0.01559996 0.4124173 0.00841248 -0.01559996 0.4150064 0.006548583 -0.01559996 0.4171575 0.004154145 -0.01559996 0.4186963 0.00142312 -0.01559996 0.4194982 -0.00142312 -0.01559996 0.4194982 -0.004154145 -0.01559996 0.4186963 -0.006548583 -0.01559996 0.4171575 -0.00841248 -0.01559996 0.4150064 -0.009594917 -0.01559996 0.4124173 -0.009594917 0.01559996 0.4124173 -0.00999999 0.01559996 0.4096 -0.009594917 0.01559996 0.4067827 -0.00841248 0.01559996 0.4041936 -0.006548583 0.01559996 0.4020425 -0.004154145 0.01559996 0.4005036 -0.00142312 0.01559996 0.3997018 0.00142312 0.01559996 0.3997018 0.004154145 0.01559996 0.4005036 0.006548583 0.01559996 0.4020425 0.00841248 0.01559996 0.4041936 0.009594917 0.01559996 0.4067827 0.00999999 0.01559996 0.4096 0.009594917 0.01559996 0.4124173 0.00841248 0.01559996 0.4150064 0.006548583 0.01559996 0.4171575 0.004154145 0.01559996 0.4186963 0.00142312 0.01559996 0.4194982 -0.00142312 0.01559996 0.4194982 -0.004154145 0.01559996 0.4186963 -0.006548583 0.01559996 0.4171575 -0.00841248 0.01559996 0.4150064 0 -0.01559996 0.4216 -0.003105819 -0.01559996 0.4211911 -0.005999982 -0.01559996 0.4199923 -0.008485257 -0.01559996 0.4180853 -0.0103923 -0.01559996 0.4156 -0.01159107 -0.01559996 0.4127058 -0.01199996 -0.01559996 0.4096 -0.01159107 -0.01559996 0.4064942 -0.0103923 -0.01559996 0.4036 -0.008485257 -0.01559996 0.4011147 -0.005999982 -0.01559996 0.3992077 -0.003105819 -0.01559996 0.3980089 0 -0.01559996 0.3976 0.003105819 -0.01559996 0.3980089 0.005999982 -0.01559996 0.3992077 0.008485257 -0.01559996 0.4011147 0.0103923 -0.01559996 0.4036 0.01159107 -0.01559996 0.4064942 0.01199996 -0.01559996 0.4096 0.01159107 -0.01559996 0.4127058 0.0103923 -0.01559996 0.4156 0.008485257 -0.01559996 0.4180853 0.005999982 -0.01559996 0.4199923 0.003105819 -0.01559996 0.4211911 -0.003105819 0.01559996 0.3980089 -0.005999982 0.01559996 0.3992077 -0.008485257 0.01559996 0.4011147 -0.0103923 0.01559996 0.4036 -0.01159107 0.01559996 0.4064942 -0.01199996 0.01559996 0.4096 -0.01159107 0.01559996 0.4127058 -0.0103923 0.01559996 0.4156 -0.008485257 0.01559996 0.4180853 -0.005999982 0.01559996 0.4199923 -0.003105819 0.01559996 0.4211911 0 0.01559996 0.4216 0.003105819 0.01559996 0.4211911 0.005999982 0.01559996 0.4199923 0.008485257 0.01559996 0.4180853 0.0103923 0.01559996 0.4156 0.01159107 0.01559996 0.4127058 0.01199996 0.01559996 0.4096 0.01159107 0.01559996 0.4064942 0.0103923 0.01559996 0.4036 0.008485257 0.01559996 0.4011147 0.005999982 0.01559996 0.3992077 0.003105819 0.01559996 0.3980089 0 0.01559996 0.3976 0.01159107 -0.01059997 0.4127058 0.01199996 -0.01059997 0.4096 0.01159107 -0.01059997 0.4064942 0.0103923 -0.01059997 0.4036 0.008485257 -0.01059997 0.4011147 0.005999982 -0.01059997 0.3992077 0.003105819 -0.01059997 0.3980089 0 -0.01559996 0.3976 0 -0.01059997 0.3976 -0.003105819 -0.01059997 0.3980089 -0.005999982 -0.01059997 0.3992077 -0.008485257 -0.01059997 0.4011147 -0.0103923 -0.01059997 0.4036 -0.01159107 -0.01059997 0.4064942 -0.01199996 -0.01059997 0.4096 -0.01159107 -0.01059997 0.4127058 -0.0103923 -0.01059997 0.4156 -0.008485257 -0.01059997 0.4180853 -0.005999982 -0.01059997 0.4199923 -0.003105819 -0.01059997 0.4211911 0 -0.01559996 0.4216 0 -0.01059997 0.4216 0.003105819 -0.01059997 0.4211911 0.005999982 -0.01059997 0.4199923 0.008485257 -0.01059997 0.4180853 0.0103923 -0.01059997 0.4156 0.01199996 0.01059997 0.4096 0.01159107 0.01059997 0.4064942 0.0103923 0.01059997 0.4036 0.008485257 0.01059997 0.4011147 0.005999982 0.01059997 0.3992077 0.003105819 0.01059997 0.3980089 0 0.01059997 0.3976 0 0.01559996 0.3976 -0.003105819 0.01059997 0.3980089 -0.005999982 0.01059997 0.3992077 -0.008485257 0.01059997 0.4011147 -0.0103923 0.01059997 0.4036 -0.01159107 0.01059997 0.4064942 -0.01199996 0.01059997 0.4096 -0.01159107 0.01059997 0.4127058 -0.0103923 0.01059997 0.4156 -0.008485257 0.01059997 0.4180853 -0.005999982 0.01059997 0.4199923 -0.003105819 0.01059997 0.4211911 0 0.01059997 0.4216 0 0.01559996 0.4216 0.003105819 0.01059997 0.4211911 0.005999982 0.01059997 0.4199923 0.008485257 0.01059997 0.4180853 0.0103923 0.01059997 0.4156 0.01159107 0.01059997 0.4127058 0.009011745 -0.01663351 0.3982506 0.009179353 -0.01660895 0.3986154 0.009541928 -0.01589709 0.3982594 0.008832335 -0.01638221 0.3964715 0.008727312 -0.01669144 0.3965988 0.008734762 -0.0166909 0.3967368 0.009158194 -0.01603496 0.3976084 0.008757531 -0.01668709 0.3970034 0.00885421 -0.01666545 0.3976495 0.008857548 -0.01666468 0.3976719 0.008705496 -0.01669025 0.3957846 0.008711159 -0.01669287 0.3962463 0.008716523 -0.01669228 0.3963991 0.008917808 -0.01609176 0.3965018 0.008886337 -0.01617872 0.3963962 0.008854985 -0.01626551 0.3962908 0.008823573 -0.01635527 0.3961832 0.008807718 -0.01640051 0.3961279 0.008747518 -0.01657122 0.3959257 0.009177446 -0.015531 0.3972412 0.009135127 -0.01560169 0.397138 0.009083449 -0.01570004 0.3970032 0.009030342 -0.01582556 0.3968425 0.008918046 -0.01609128 0.3965024 0.009646177 -0.0150786 0.3980141 0.009431004 -0.01521527 0.397736 0.009381532 -0.01527684 0.3976394 0.009265184 -0.0154218 0.3974123 0.009900748 -0.01595747 0.398743 0.009922027 -0.01584422 0.3986963 0.009926795 -0.01581865 0.3986857 0.01000624 -0.01533937 0.3984997 0.009999513 -0.01490169 0.398419 0.009849786 -0.01495176 0.3982747 0.01000702 -0.01539146 0.3985093 0.009841501 -0.01495456 0.3982667 0.009782075 -0.01624369 0.3989334 0.009779393 -0.01624757 0.3989372 0.009319126 -0.0165885 0.3989195 0.009554386 -0.01656979 0.3992542 0.008909761 -0.01665413 0.3978833 0.008963763 -0.01664322 0.3981019 0.009008824 -0.0166341 0.3982415 0.0061962 -0.00999999 0.395772 0.00618267 -0.00999999 0.3957487 0.006340384 -0.01001757 0.3956505 0.005306661 -0.0100001 0.3942363 0.005320131 -0.0100001 0.3942286 0.005914568 -0.01002258 0.3948904 0.004551708 -0.01000487 0.3928384 0.004603385 -0.01001936 0.3926386 0.004688262 -0.0100252 0.3927267 0.005062937 -0.01002448 0.3933766 0.004846751 -0.0100001 0.3934423 0.004895806 -0.01000076 0.3934723 0.004872024 -0.0100001 0.393486 0.005304396 -0.0100001 0.3942325 0.00650835 -0.01007682 0.395546 0.005764007 -0.01000005 0.395026 0.005743086 -0.01000005 0.3949898 0.006791591 -0.01001149 0.3964024 0.007441639 -0.01004743 0.3970097 0.007288575 -0.01000565 0.3971351 0.007214426 -0.00999999 0.3971952 0.007085144 -0.00999999 0.3970513 0.006853818 -0.00999999 0.3967185 0.006685674 -0.00999999 0.3964765 0.006237089 -0.00999999 0.3958309 0.007718086 -0.01025021 0.3967834 0.009001314 -0.01046562 0.3978192 0.008244454 -0.01020985 0.3974384 0.008917331 -0.01031273 0.3979291 0.008120775 -0.01010084 0.3975627 0.008839786 -0.01017141 0.3980307 0.007986962 -0.01003116 0.3976973 0.008717834 -0.01009625 0.3981903 0.00781852 -0.00999999 0.3978675 0.008573889 -0.01000744 0.3983786 0.007903397 -0.00999999 0.3979619 0.008499562 -0.00999999 0.3984756 0.007902622 -0.01056432 0.3966324 0.009080648 -0.01082789 0.3977155 0.009051859 -0.01063978 0.3977531 0.007489025 -0.01060259 0.3960487 0.00796175 -0.01073014 0.3965836 0.00811994 -0.01077282 0.3967626 0.008262157 -0.0108112 0.3969235 0.008317887 -0.01082473 0.3969779 0.008592128 -0.01089125 0.3972452 0.009106993 -0.01099997 0.397681 0.007344663 -0.01056361 0.3958854 0.006785929 -0.01029723 0.3953732 0.006919324 -0.01044958 0.3953546 0.006884157 -0.01044017 0.3953108 0.006227254 -0.01018035 0.3947092 0.006368637 -0.01030194 0.3946676 0.004990935 -0.01006132 0.3930595 0.005205988 -0.01008695 0.3932959 0.005655407 -0.01008653 0.3940398 0.005483686 -0.01012009 0.3936012 0.005502223 -0.01012229 0.3936216 0.005787193 -0.01018136 0.3939657 0.006148815 -0.01025635 0.3944022 0.006955444 -0.01006352 0.396288 0.007588028 -0.01013028 0.3968899 0.005494952 -0.01002508 0.3941301 0.006080925 -0.0100851 0.394794 0.006659269 -0.01017302 0.395452 0.007824361 -0.01039862 0.3966965 0.009034395 -0.01052594 0.397776 0.00453478 -0.01000016 0.3929038 0.00453478 0.01000016 0.3929038 0.005062937 0.01002448 0.3933766 0.004551708 0.01000487 0.3928384 0.004993259 0.01005899 0.3930584 0.004771411 0.01003146 0.3928127 0.004698574 0.01002579 0.3927367 0.004688203 0.01002514 0.3927268 0.004687011 0.01002496 0.3927247 0.00468111 0.01002454 0.3927186 0.004603385 0.01001936 0.3926386 0.005786955 0.01018118 0.3939658 0.005501985 0.01012212 0.3936218 0.005655407 0.01008653 0.3940398 0.005482912 0.01011973 0.3936007 0.005206942 0.01008552 0.3932951 0.006148755 0.01025617 0.3944025 0.006227254 0.01018035 0.3947092 0.006345808 0.010297 0.3946405 0.006810545 0.01041644 0.3952216 0.006808757 0.01041597 0.3952193 0.006785929 0.01029723 0.3953732 0.006728351 0.01039439 0.3951184 0.006368517 0.0103017 0.3946678 0.007413804 0.01058244 0.3959677 0.007344603 0.01056325 0.3958855 0.007237315 0.01028043 0.3960912 0.006946504 0.01045328 0.3953924 0.006659269 0.01017302 0.395452 0.006941556 0.01045191 0.3953862 0.006883025 0.01043605 0.3953127 0.006825149 0.01042038 0.39524 0.007824361 0.01039862 0.3966965 0.007960557 0.01072925 0.396584 0.007725238 0.01066881 0.3963376 0.007481157 0.01060116 0.3960477 0.009057044 0.01064115 0.3977463 0.008516013 0.01087182 0.3971655 0.008430421 0.0105192 0.3972512 0.008339226 0.01082646 0.3969805 0.008111357 0.01076793 0.3967419 0.009083509 0.01072466 0.3977118 0.009096682 0.01087898 0.3976945 0.008592128 0.01089137 0.3972452 0.009106993 0.01099997 0.3976811 0.008349597 0.01035261 0.3973325 0.008971035 0.01036947 0.3978588 0.008995354 0.01044636 0.397827 0.00872159 0.0100845 0.3981851 0.008766233 0.01010149 0.3981267 0.007441639 0.01004743 0.3970097 0.008784592 0.01012551 0.3981027 0.008825242 0.01017874 0.3980495 0.006836116 0.00999999 0.3967197 0.007288575 0.01000565 0.3971351 0.007221817 0.00999999 0.3971897 0.00756514 0.00999999 0.397608 0.008606851 0.01004087 0.3983351 0.007626116 0.00999999 0.3976823 0.008499443 0.00999999 0.3984756 0.006955444 0.01006352 0.396288 0.006262421 0.00999999 0.3958386 0.006810486 0.00999999 0.3966885 0.00573045 0.00999999 0.3949899 0.005733549 0.00999999 0.3949953 0.005736947 0.00999993 0.3949934 0.005852758 0.00999999 0.3952032 0.006340384 0.01001757 0.3956505 0.006198108 0.00999999 0.3957388 0.007107019 0.01015549 0.3961822 0.007588028 0.01013028 0.3968899 0.007718086 0.01025021 0.3967834 0.008244454 0.01020985 0.3974384 0.00892347 0.01030719 0.397921 0.005283415 0.01000005 0.3942099 0.005300521 0.01000005 0.3942397 0.005320131 0.0100001 0.3942286 0.005914568 0.01002258 0.3948904 0.00650835 0.01007682 0.395546 0.006080925 0.0100851 0.394794 0.005494952 0.01002508 0.3941301 0.004895806 0.01000076 0.3934723 0.004838228 0.0100001 0.3934332 0.004869341 0.0100001 0.3934874 -0.01438385 -0.01099997 0.4055175 -0.01415354 -0.01099997 0.4046325 -0.01404082 -0.01052594 0.4046721 -0.009551644 -0.01099997 0.4211069 -0.01018869 -0.01099997 0.4206086 -0.01010751 -0.01052594 0.4205209 -0.01148349 -0.00999999 0.4016726 -0.0122627 -0.00999999 0.4028453 -0.01236957 -0.01000744 0.4027864 -0.01306772 -0.00999999 0.4046456 -0.01320999 -0.00999999 0.4049637 -0.01332509 -0.01000744 0.4049233 -0.01386457 -0.00999999 0.4112848 -0.01382052 -0.00999999 0.4118344 -0.01394098 -0.01000744 0.4118539 -0.01148629 -0.00999999 0.4175299 -0.01107603 -0.00999999 0.4181628 -0.01117253 -0.01000744 0.4182374 -0.006483793 -0.00999999 0.4219554 -0.005642712 -0.00999999 0.4224125 -0.005691885 -0.01000744 0.4225241 0 -0.00999999 0.4235518 0.001160323 -0.00999999 0.4235518 0.001170456 -0.01000744 0.4236734 0.003349065 -0.00999999 0.4231852 0.003448963 -0.00999999 0.4231685 0.003479003 -0.01000744 0.4232867 0.009270191 -0.00999999 0.4200618 0.009509563 -0.00999999 0.4198746 0.009592413 -0.01000744 0.4199641 0.01306003 -0.00999999 0.4145514 0.01326161 -0.00999999 0.4140865 0.01337718 -0.01000744 0.4141256 0.01148343 -0.00999999 0.4016726 0.0109784 -0.00999999 0.4009124 0.01107406 -0.01000744 0.4008367 -0.008571207 -0.01002717 0.3983823 -0.008499741 -0.00999999 0.3984758 -0.009474515 -0.01000744 0.3991279 -0.009280264 -0.00999999 0.3991249 -0.009392678 -0.00999999 0.3992184 -0.009768307 -0.01017141 0.3988032 -0.008832156 -0.01018744 0.3980409 -0.008825361 -0.01017862 0.3980498 -0.008766472 -0.01010149 0.3981269 -0.008721768 -0.01008445 0.3981854 -0.008607149 -0.01004081 0.3983353 -0.009057044 -0.01064068 0.3977466 -0.009023666 -0.01053524 0.3977903 -0.00998336 -0.01052594 0.3985655 -0.008971214 -0.01036953 0.3978589 -0.00892347 -0.01030701 0.3979214 -0.009083628 -0.01072472 0.3977118 -0.01006358 -0.01099997 0.3984768 -0.009107053 -0.01099997 0.3976811 0.009983241 -0.01052594 0.3985654 0.0100634 -0.01099997 0.3984767 0.009768187 -0.01017141 0.3988031 0.009474396 -0.01000744 0.3991278 0.009280264 -0.00999999 0.3991249 0.009392559 -0.00999999 0.3992183 0.01306772 -0.00999999 0.4046456 0.01226264 -0.00999999 0.4028452 0.01236951 -0.01000744 0.4027863 0.01332509 -0.01000744 0.4049231 0.01320993 -0.00999999 0.4049635 0.01379436 -0.00999999 0.4072093 0.01386457 -0.00999999 0.4112848 0.01399976 -0.00999999 0.4096 0.01412177 -0.01000744 0.40952 0.01399976 -0.00999999 0.4095207 0.01385712 -0.00999999 0.4079161 0.01394098 -0.01000744 0.4118537 0.01382052 -0.00999999 0.4118343 0.01148629 -0.00999999 0.4175299 0.01233834 -0.00999999 0.4162155 0.01244586 -0.01000744 0.4162731 0.01117265 -0.01000744 0.4182373 0.01107609 -0.00999999 0.4181627 0.007681727 -0.00999999 0.4213043 0.005692064 -0.01000744 0.422524 0.00564289 -0.00999999 0.4224124 0.006483793 -0.00999999 0.4219554 -0.003349065 -0.00999999 0.4231852 -0.001160144 -0.00999999 0.4235519 -0.001170277 -0.01000744 0.4236735 -0.003478884 -0.01000744 0.4232868 -0.003448784 -0.00999999 0.4231685 -0.009270191 -0.00999999 0.4200619 -0.007681608 -0.00999999 0.4213044 -0.007748544 -0.01000744 0.4214064 -0.009592294 -0.01000744 0.4199643 -0.009509444 -0.00999999 0.4198747 -0.01306003 -0.00999999 0.4145514 -0.01233828 -0.00999999 0.4162156 -0.0124458 -0.01000744 0.4162732 -0.01337713 -0.01000744 0.4141258 -0.01326155 -0.00999999 0.4140866 -0.01385718 -0.00999999 0.4079161 -0.01399976 -0.00999999 0.4095209 -0.01412177 -0.01000744 0.4095202 -0.01399976 -0.00999999 0.4096 -0.01391458 -0.01000744 0.4071886 -0.01379436 -0.00999999 0.4072094 -0.01107418 -0.01000744 0.4008368 -0.01097846 -0.00999999 0.4009125 0.01141744 -0.01017141 0.4005649 0.01275306 -0.01017141 0.402575 0.01166886 -0.01052594 0.400366 0.01303386 -0.01052594 0.4024204 0.01373827 -0.01017141 0.4047781 0.01404076 -0.01052594 0.4046719 0.01455962 -0.01017141 0.4095175 0.01437324 -0.01017141 0.4119237 0.01488023 -0.01052594 0.4095157 0.01468974 -0.01052594 0.4119748 0.0128318 -0.01017141 0.41648 0.01151907 -0.01017141 0.4185051 0.01311433 -0.01052594 0.4166315 0.01177269 -0.01052594 0.4187012 0.0098899 -0.01017141 0.4202855 0.01010763 -0.01052594 0.4205208 0.005868554 -0.01017141 0.4229248 0.003586888 -0.01017141 0.4237111 0.005997776 -0.01052594 0.4232182 0.003665864 -0.01052594 0.4240218 -0.001206576 -0.01017141 0.4241098 -0.003586769 -0.01017141 0.4237112 -0.0012331 -0.01052594 0.4244293 -0.003665745 -0.01052594 0.4240219 -0.005868375 -0.01017141 0.4229249 -0.005997598 -0.01052594 0.4232183 -0.01151895 -0.01017141 0.4185053 -0.01283174 -0.01017141 0.4164802 -0.01177257 -0.01052594 0.4187013 -0.01311427 -0.01052594 0.4166316 -0.01437324 -0.01017141 0.4119238 -0.01455962 -0.01017141 0.4095177 -0.01468974 -0.01052594 0.411975 -0.01488023 -0.01052594 0.4095159 -0.01275312 -0.01017141 0.4025751 -0.01141756 -0.01017141 0.4005651 -0.01303392 -0.01052594 0.4024205 -0.01166898 -0.01052594 0.4003661 0.01105767 -0.01099997 0.3995388 0.01176255 -0.01099997 0.4002919 0.01310628 -0.01099997 0.4023142 0.01313853 -0.01099997 0.4023627 0.01415348 -0.01099997 0.4046323 0.01438385 -0.01099997 0.4055176 0.01391458 -0.01000744 0.4071884 0.014346 -0.01017141 0.4071137 0.0146619 -0.01052594 0.4070589 0.01477962 -0.01099997 0.4070385 0.01494687 -0.01099997 0.4089201 0.01499974 -0.01099997 0.409515 0.0148077 -0.01099997 0.4119939 0.0147174 -0.01099997 0.4123579 0.01379197 -0.01017141 0.4142659 0.01409566 -0.01052594 0.4143687 0.01420885 -0.01099997 0.414407 0.01367217 -0.01099997 0.4156446 0.01321965 -0.01099997 0.416688 0.01195627 -0.01099997 0.4186369 0.01186728 -0.01099997 0.4187743 0.01018881 -0.01099997 0.4206085 0.009551644 -0.01099997 0.4211069 0.007748663 -0.01000744 0.4214063 0.007988929 -0.01017141 0.4217724 0.008164882 -0.01052594 0.4220404 0.008230447 -0.01099997 0.4221403 0.00666362 -0.01099997 0.4229919 0.006045937 -0.01099997 0.4233276 0.003695309 -0.01099997 0.4241377 0.003429591 -0.01099997 0.4241822 0.001206696 -0.01017141 0.4241098 0.001233279 -0.01052594 0.4244293 0.001243174 -0.01099997 0.4245484 0 -0.01099997 0.4245484 -0.001243054 -0.01099997 0.4245484 -0.003429591 -0.01099997 0.4241822 -0.00369513 -0.01099997 0.4241377 -0.006045758 -0.01099997 0.4233276 -0.00666362 -0.01099997 0.4229919 -0.00798881 -0.01017141 0.4217725 -0.008164703 -0.01052594 0.4220405 -0.008230268 -0.01099997 0.4221404 -0.009889721 -0.01017141 0.4202857 -0.01186716 -0.01099997 0.4187744 -0.01195627 -0.01099997 0.4186369 -0.01321959 -0.01099997 0.4166882 -0.01367217 -0.01099997 0.4156446 -0.01379191 -0.01017141 0.4142661 -0.0140956 -0.01052594 0.4143688 -0.01420879 -0.01099997 0.4144071 -0.0147174 -0.01099997 0.4123579 -0.0148077 -0.01099997 0.411994 -0.01499974 -0.01099997 0.4095152 -0.01494687 -0.01099997 0.4089201 -0.01434606 -0.01017141 0.4071138 -0.0146619 -0.01052594 0.4070591 -0.01477968 -0.01099997 0.4070387 -0.01373833 -0.01017141 0.4047783 -0.01313859 -0.01099997 0.4023628 -0.01310628 -0.01099997 0.4023142 -0.01176267 -0.01099997 0.400292 -0.01105761 -0.01099997 0.3995388 0 -0.01059997 0.3976 0 -0.01059997 0.3956 0.003350377 -0.01059997 0.3960068 0.01389789 -0.01059997 0.4079125 0.01309019 -0.01059997 0.4046355 0.01152175 -0.01059997 0.4016471 0.009283661 -0.01059997 0.3991208 0.006506085 -0.01059997 0.3972036 -0.003350377 -0.01059997 0.3960068 -0.006506085 -0.01059997 0.3972036 -0.009283661 -0.01059997 0.3991208 -0.01152175 -0.01059997 0.4016471 -0.01309019 -0.01059997 0.4046355 -0.01389789 -0.01059997 0.4079125 -0.01399999 -0.01059997 0.4096 0.01399999 -0.01059997 0.4096 0.01389789 -0.01059997 0.4112875 0.01309019 -0.01059997 0.4145644 0.01152175 -0.01059997 0.4175529 0.009283661 -0.01059997 0.4200791 0.006506085 -0.01059997 0.4219964 0.003350377 -0.01059997 0.4231932 0 -0.01059997 0.4216 0 -0.01059997 0.4236 -0.003350377 -0.01059997 0.4231932 -0.006506085 -0.01059997 0.4219964 -0.009283661 -0.01059997 0.4200791 -0.01152175 -0.01059997 0.4175529 -0.01309019 -0.01059997 0.4145644 -0.01389789 -0.01059997 0.4112875 0 0.01059997 0.3976 -0.001687467 0.01059997 0.3957021 -0.004964411 0.01059997 0.3965098 -0.007952868 0.01059997 0.3980782 -0.01047915 0.01059997 0.4003162 -0.01239633 0.01059997 0.4030939 -0.01359313 0.01059997 0.4062496 -0.01399999 0.01059997 0.4096 -0.01359313 0.01059997 0.4129504 -0.01239633 0.01059997 0.4161061 -0.01047915 0.01059997 0.4188837 -0.007952868 0.01059997 0.4211218 -0.004964411 0.01059997 0.4226902 0 0.01059997 0.4216 -0.001687467 0.01059997 0.4234979 0.001687467 0.01059997 0.4234979 0.004964411 0.01059997 0.4226902 0.007952868 0.01059997 0.4211218 0.01047915 0.01059997 0.4188837 0.01239633 0.01059997 0.4161061 0.01359313 0.01059997 0.4129504 0.01399999 0.01059997 0.4096 0.01359313 0.01059997 0.4062496 0.01239633 0.01059997 0.4030939 0.01047915 0.01059997 0.4003162 0.007952868 0.01059997 0.3980782 0.004964411 0.01059997 0.3965098 0.001687467 0.01059997 0.3957021 -0.008376598 -0.01035666 0.3973544 -0.008456408 -0.01052373 0.3972734 -0.00784564 -0.01040256 0.3967178 -0.006836354 -0.00999999 0.3967202 -0.007313132 -0.01000624 0.3971566 -0.007465541 -0.01004904 0.397031 -0.0072425 -0.00999999 0.3972148 -0.007565557 -0.00999999 0.3976084 -0.004687309 -0.01002508 0.3927261 -0.004603266 -0.0100193 0.392639 -0.004551529 -0.01000481 0.3928391 -0.005066335 -0.01002466 0.3933812 -0.00453478 -0.01000016 0.3929038 -0.005165696 -0.010073 0.3932397 -0.004995524 -0.0100556 0.3930563 -0.004721522 -0.01002752 0.3927611 -0.00548315 -0.01011902 0.3936001 -0.005500674 -0.01012182 0.3936206 -0.005662143 -0.01008731 0.3940483 -0.005473971 -0.01011759 0.3935893 -0.005215287 -0.01008021 0.393296 -0.006799042 -0.0102998 0.3953894 -0.00636667 -0.01030117 0.3946657 -0.006237149 -0.01018196 0.3947218 -0.006147027 -0.01025569 0.3944007 -0.005793809 -0.01018249 0.3939743 -0.007433056 -0.01058691 0.3959844 -0.0073421 -0.01056253 0.3958825 -0.00725454 -0.01028352 0.3961103 -0.006918728 -0.01044911 0.3953544 -0.006896853 -0.01044327 0.3953271 -0.007984697 -0.01073497 0.3966026 -0.007487952 -0.01060169 0.396046 -0.008536577 -0.01087808 0.397192 -0.008351922 -0.01083356 0.3970141 -0.008316814 -0.01082414 0.3969748 -0.008111774 -0.01076906 0.396745 -0.008587896 -0.01089042 0.3972413 -0.007626295 -0.00999999 0.3976824 -0.006973981 -0.01006513 0.3963071 -0.006263136 -0.00999999 0.3958396 -0.006811857 -0.00999999 0.3966903 -0.005731403 -0.00999999 0.3949915 -0.005741596 -0.00999999 0.3950092 -0.005747675 -0.00999999 0.3950057 -0.00585401 -0.00999999 0.3952053 -0.006354928 -0.01001828 0.3956665 -0.006209731 -0.00999999 0.3957569 -0.005284488 -0.01000005 0.3942117 -0.005305945 -0.01000005 0.3942492 -0.005327165 -0.01000016 0.3942371 -0.005925059 -0.01002323 0.3949028 -0.006522476 -0.01007831 0.395562 -0.004839479 -0.0100001 0.3934353 -0.004899322 -0.01000076 0.3934768 -0.005501866 -0.0100255 0.3941386 -0.006091177 -0.01008629 0.3948065 -0.006672918 -0.0101751 0.3954681 -0.00712496 -0.01015788 0.3962012 -0.007740318 -0.01025354 0.3968046 -0.007611095 -0.01013278 0.396911 -0.008272528 -0.01021319 0.3974602 -0.004872143 -0.0100001 0.3934924 0.008639752 -0.01637536 0.4179275 0.008492231 -0.01629602 0.4180736 0.008923947 -0.01621276 0.4184894 0.008725702 -0.01651108 0.4178423 0.008725643 -0.01651096 0.4178423 0.00919485 -0.01643264 0.4182825 0.01033645 -0.01351165 0.4204181 0.01036304 -0.01319992 0.4204447 0.0105946 -0.01379728 0.4202177 0.0109384 -0.01539373 0.4197331 0.01093828 -0.01539826 0.4197319 0.01071631 -0.01577717 0.4194989 0.01032578 -0.01622867 0.419106 0.01047503 -0.01645296 0.4191673 0.01036483 -0.01658254 0.4190542 0.009880781 -0.01656258 0.4186584 0.01082187 -0.01588678 0.4195429 0.01074963 -0.01607084 0.4194559 0.01072055 -0.01614499 0.4194208 0.01068276 -0.01620864 0.4193805 0.01093357 -0.01556426 0.4196853 0.01091563 -0.0156477 0.4196559 0.01068216 -0.01503533 0.4197723 0.01084136 -0.01458382 0.4199647 0.01092725 -0.0148676 0.4198759 0.0109499 -0.01498979 0.4198463 0.01094466 -0.01517486 0.4197944 0.01039117 -0.01553523 0.4194805 0.01051175 -0.01437687 0.4200753 0.01062434 -0.01387399 0.4201886 0.010634 -0.0138989 0.4201791 0.009992957 -0.01485383 0.4200749 0.01010292 -0.01463907 0.4201846 0.01031041 -0.01490867 0.4198738 0.01080286 -0.01445662 0.4200046 0.01018232 -0.01434981 0.420264 0.01018536 -0.01433873 0.420267 0.01030236 -0.01391249 0.4203839 0.01031333 -0.01378327 0.420395 0.009850203 -0.01513278 0.4199323 0.01003938 -0.01537448 0.4196028 0.009790599 -0.01524913 0.4198728 0.00973612 -0.01531267 0.4198185 0.009709179 -0.0157563 0.4192728 0.009414613 -0.01568734 0.4194982 0.008905768 -0.01604807 0.4189912 0.0090456 -0.01595503 0.4191305 0.009332478 -0.01603931 0.4188968 0.009359717 -0.01574599 0.4194435 0.009370386 -0.01573884 0.4194542 0.00879389 -0.01607877 0.4188796 0.00864917 -0.01611852 0.4187355 0.008328974 -0.01620823 0.4182354 0.008237898 -0.01619994 0.4183256 0.008375167 -0.01619374 0.4184623 0.008476734 -0.01628768 0.418089 0.009348273 -0.0171597 0.4180254 0.008948266 -0.01719999 0.4176217 0.008888244 -0.01685947 0.4176812 0.01001912 -0.01687783 0.418703 0.009945213 -0.01694095 0.4186279 0.009398698 -0.01676613 0.4181739 0.009494304 -0.01710617 0.4181728 0.008884251 -0.01683676 0.4176852 0.008865833 -0.01673239 0.4177035 0.009632766 -0.01624763 0.4187207 0.01003676 -0.01594465 0.4191253 0.009762287 -0.01658254 0.3995247 0.01002341 -0.01624596 0.3992552 0.0101549 -0.01607644 0.3991194 0.01023674 -0.01583838 0.399035 0.01038819 -0.01539736 0.3988787 0.01039093 -0.01536816 0.3988758 0.0104379 -0.0148676 0.3988273 -0.008852839 -0.01610368 0.4187809 -0.008730351 -0.01612555 0.4186613 -0.009000837 -0.01621288 0.4184113 -0.009011209 -0.01707178 0.4175494 -0.00901699 -0.01719999 0.4175436 -0.009570479 -0.0171144 0.418092 -0.01090276 -0.01443183 0.4199019 -0.01070308 -0.01387882 0.4201045 -0.01060348 -0.01437717 0.4199824 -0.01067656 -0.01380538 0.4201313 -0.01045799 -0.01319998 0.4203531 -0.01045203 -0.01342362 0.4203473 -0.01043921 -0.01351219 0.4203346 -0.01040029 -0.01378035 0.4202965 -0.01034504 -0.01416116 0.4202424 -0.01040023 -0.01490896 0.4197828 -0.01094442 -0.01459074 0.4198573 -0.01090538 -0.0144419 0.4198991 -0.01077103 -0.01503568 0.419678 -0.01103794 -0.01517784 0.4196999 -0.01101708 -0.0148676 0.4197795 -0.01104992 -0.01535648 0.419654 -0.0104773 -0.01553559 0.4193889 -0.0110436 -0.01538431 0.4196439 -0.0110411 -0.01539528 0.4196399 -0.01080244 -0.01577758 0.4194043 -0.01092904 -0.015886 0.4194626 -0.01092195 -0.01589834 0.4194551 -0.01044702 -0.01658254 0.4189633 -0.01056396 -0.01646327 0.4190801 -0.01040828 -0.01622897 0.4190151 -0.01064318 -0.01638245 0.4191592 -0.01082831 -0.016061 0.4193556 -0.0100978 -0.01687806 0.418615 -0.009959101 -0.01656281 0.4185716 -0.01002413 -0.01694041 0.4185415 -0.009472548 -0.0167663 0.4180915 -0.009635746 -0.01710432 0.4181567 -0.008954763 -0.01686179 0.4176064 -0.008313179 -0.01619994 0.4182539 -0.008547842 -0.01628273 0.4180171 -0.009497344 -0.015679 0.4194114 -0.009440481 -0.01573628 0.4193558 -0.009793341 -0.01575648 0.4191873 -0.009352803 -0.01582461 0.4192699 -0.009413182 -0.01603949 0.4188148 -0.009128212 -0.01595002 0.4190502 -0.008875846 -0.01609086 0.4188034 -0.009764552 -0.01540988 0.4196729 -0.0101267 -0.01537472 0.4195142 -0.009823739 -0.01531332 0.4197309 -0.01028233 -0.01433914 0.4201808 -0.01027864 -0.01434957 0.4201772 -0.01009511 -0.0148707 0.419997 -0.009937524 -0.01512765 0.4198426 -0.008798003 -0.01651328 0.4177646 -0.008893609 -0.01663434 0.4176682 -0.008949339 -0.01684176 0.4176118 -0.01011955 -0.01594495 0.4190369 -0.009711742 -0.01624786 0.418636 -0.009269773 -0.01643282 0.4182019 -0.008795559 -0.01651018 0.4177671 -0.008568763 -0.01629012 0.417996 -0.008642315 -0.01631605 0.4179218 -0.00913304 -0.01105493 0.397701 -0.01036888 -0.01486915 0.3987609 -0.009988665 -0.01453065 0.3984095 -0.01043796 -0.0148676 0.3988274 -0.01108914 -0.0148676 0.3995094 -0.009999334 -0.01490163 0.3984191 -0.009998261 -0.01486253 0.3984181 -0.009989678 -0.01455289 0.3984104 -0.009926497 -0.01399445 0.3983547 -0.009843647 -0.01328027 0.3982818 -0.009831666 -0.01321691 0.3982713 -0.009803414 -0.01311004 0.3982475 -0.009559392 -0.0121873 0.398042 -0.009493827 -0.01193928 0.3979867 -0.009205758 -0.01123327 0.3977586 -0.01124382 -0.0148676 0.3996714 -0.01264691 -0.0148676 0.4015343 -0.01307219 -0.0148676 0.4023318 -0.01374429 -0.0148676 0.4035922 -0.01441109 -0.0148676 0.4055122 -0.01450943 -0.0148676 0.4057953 -0.01492381 -0.0148676 0.4080904 -0.01494282 -0.0148676 0.4089177 -0.01471871 -0.0148676 0.412361 -0.01497745 -0.0148676 0.410422 -0.009698331 -0.01319998 0.421043 -0.01194351 -0.0148676 0.4186278 -0.0130043 -0.0148676 0.4170758 -0.01368331 -0.0148676 0.415648 -0.01400595 -0.0148676 0.4149696 -0.014669 -0.0148676 0.4127336 -0.01168835 -0.0148676 0.4190012 0.01161348 -0.0148676 0.4190935 0.01193892 -0.0148676 0.4186244 0.00959742 -0.01319998 0.4211277 0.009578526 -0.01319998 0.4211412 0.00769937 -0.01319998 0.4224732 0.006663501 -0.01319998 0.4229882 0.005616068 -0.01319998 0.423509 0.003432095 -0.01319998 0.4241992 0.003397703 -0.01319998 0.4242101 0.001097559 -0.01319998 0.4245598 1.96694e-7 -0.01319998 0.424555 -0.001228928 -0.01319998 0.4245496 -0.003431797 -0.01319998 0.4241949 -0.003525912 -0.01319998 0.4241797 -0.005738079 -0.01319998 0.4234591 -0.006663382 -0.01319998 0.4229888 -0.007812142 -0.01319998 0.4224051 -0.009572982 -0.01319998 0.4211335 0.01371532 -0.0148676 0.4035264 0.01441341 -0.0148676 0.4055114 0.01449805 -0.0148676 0.4057521 0.01492208 -0.0148676 0.4080731 0.01494169 -0.0148676 0.4089177 0.01497691 -0.0148676 0.4104318 0.01471644 -0.0148676 0.4123606 0.01466119 -0.0148676 0.4127699 0.01398277 -0.0148676 0.4150297 0.01368457 -0.0148676 0.4156484 0.0129584 -0.0148676 0.417155 0.01307028 -0.0148676 0.4023331 0.01259332 -0.0148676 0.4014509 0.009558081 -0.01213455 0.3980395 0.009495198 -0.01194375 0.3979879 0.009205222 -0.01123875 0.3977587 0.009571373 -0.01218789 0.3980508 0.00980246 -0.0131154 0.3982468 0.00984472 -0.01328498 0.3982827 0.009889781 -0.01355445 0.398322 0.011092 -0.0148676 0.3995067 0.01115971 -0.0148676 0.399577 0.009933829 -0.01399755 0.398361 0.009989559 -0.01455801 0.3984103 0.0099985 -0.01486778 0.3984182 -0.005960464 6.8354e-4 0.3526 -0.005997598 1.50804e-4 0.3526 0.005999505 0 0.3526 -0.00598669 -3.91727e-4 0.3526 0.005974948 -5.42086e-4 0.3526 -0.005705893 -0.001853883 0.3526 -0.005073606 -0.003201901 0.3526 0.005657494 -0.001996755 0.3526 0.004991531 -0.003328442 0.3526 0.005975723 5.33502e-4 0.3526 0.005668163 0.001966238 0.3526 0.005022406 0.003281712 0.3526 0.004077017 0.004401326 0.3526 0.002888381 0.00525844 0.3526 0.001527428 0.005801796 0.3526 7.5408e-5 0.005999028 0.3526 -0.001381158 0.005838334 0.3526 -0.002755284 0.00532937 0.3526 -0.003965079 0.004502415 0.3526 -0.004938304 0.003406882 0.3526 -0.005616903 0.002108097 0.3526 0.002797305 -0.005307435 0.3526 -0.002929866 -0.005235433 0.3526 0.001404166 -0.00583285 0.3526 -0.001550376 -0.005795717 0.3526 -7.5408e-5 -0.005999028 0.3526 -0.004128873 -0.004352748 0.3526 0.004018187 -0.004455149 0.3526 0.006506085 -0.00999999 0.3972036 0.003350377 -0.00999999 0.3960068 0.002630591 -0.00999993 0.3958494 0.002726018 -0.00999993 0.3957167 0.002965927 -0.00999993 0.3953756 0.00297594 -0.00999999 0.3953613 0.003308892 -0.00999993 0.3948603 0.003773093 -0.009999871 0.3941618 0.003905177 -0.009999871 0.3939631 0.003966271 -0.009999752 0.3938657 0.004964411 0.00999999 0.3965098 0.007952868 0.00999999 0.3980782 0.003905177 0.009999871 0.393963 0.003773272 0.009999871 0.3941615 0.003308892 0.00999993 0.3948603 0.00297594 0.00999999 0.3953613 0.002967894 0.00999993 0.3953728 0.004059433 0.00999993 0.3937035 0.002965986 0.00999993 0.3953756 0.002726018 0.00999993 0.3957167 0.002630591 0.00999993 0.3958494 -0.007912516 0.00999999 0.3979705 -0.007844746 0.00999999 0.3978953 -0.008017182 0.01003253 0.3977196 -0.006206691 0.00999999 0.3957888 -0.006193995 0.00999999 0.3957669 -0.006354928 0.01001828 0.3956665 -0.005312383 0.01000005 0.3942456 -0.005327165 0.01000016 0.3942371 -0.005925059 0.01002323 0.3949028 -0.004848241 0.0100001 0.3934447 -0.00453478 0.01000016 0.3929038 -0.004551529 0.01000481 0.3928391 -0.006897032 0.0104435 0.395327 -0.006799042 0.0102998 0.3953894 -0.006237149 0.01018196 0.3947218 -0.007688105 0.01065856 0.3962944 -0.007982373 0.01073431 0.3966041 -0.007923066 0.01056867 0.3966541 -0.008109629 0.0107671 0.3967381 -0.008336722 0.01082557 0.396977 -0.006919205 0.01044946 0.3953547 -0.007342159 0.01056283 0.3958824 -0.007478058 0.01060044 0.3960443 -0.005793988 0.01018267 0.3939742 -0.006147086 0.01025587 0.3944004 -0.006366848 0.01030141 0.3946655 -0.005483746 0.01011925 0.3936004 -0.005500853 0.01012194 0.3936204 -0.005662143 0.01008731 0.3940483 -0.004687368 0.01002508 0.3927261 -0.004990398 0.01006078 0.3930584 -0.005066335 0.01002466 0.3933812 -0.005210459 0.01008671 0.3932998 -0.005474209 0.01011776 0.3935891 -0.004603266 0.0100193 0.392639 -0.004899322 0.01000076 0.3934768 -0.004874944 0.0100001 0.3934908 -0.005306184 0.0100001 0.3942349 -0.006522476 0.01007831 0.395562 -0.005766034 0.01000005 0.3950284 -0.00575155 0.01000005 0.3950034 -0.006810665 0.0100122 0.3964216 -0.007465541 0.01004904 0.397031 -0.007313132 0.01000624 0.3971566 -0.007235467 0.00999999 0.39722 -0.007095873 0.00999999 0.3970653 -0.006854295 0.00999999 0.3967185 -0.006701052 0.00999999 0.3964985 -0.006236791 0.00999999 0.395832 -0.007740318 0.01025354 0.3968046 -0.009002983 0.01043993 0.3978174 -0.008272528 0.01021319 0.3974602 -0.008918583 0.01031434 0.3979278 -0.008149981 0.01010322 0.3975847 -0.008787751 0.01011949 0.398099 -0.008720517 0.01009154 0.398187 -0.008499741 0.00999999 0.3984758 -0.009049296 0.01064354 0.3977568 -0.009090483 0.01082462 0.3977029 -0.009102523 0.01087766 0.3976871 -0.008587896 0.01089024 0.3972414 -0.009107053 0.01099997 0.3976811 -0.005501866 0.0100255 0.3941386 -0.006091177 0.01008629 0.3948065 -0.006672918 0.0101751 0.3954681 -0.00784564 0.01040256 0.3967178 -0.0090065 0.0104556 0.3978127 -0.006974041 0.01006513 0.3963071 -0.007611095 0.01013278 0.396911 -0.003350377 -0.00999999 0.3960068 0 -0.01059997 0.4236 -3.93444e-7 -0.009799838 0.3956096 0.001342773 -0.009810864 0.3956645 0.002133131 -0.009910106 0.3957635 0.00230664 -0.009954869 0.3957913 0.002506971 -0.009982705 0.3958272 -0.001523017 -0.009818673 0.3956831 -0.001342773 -0.009810864 0.3956645 -2.00569e-4 -0.009798228 0.3956015 -0.002630591 -0.00999993 0.3958494 -0.002506971 -0.009982705 0.3958272 -0.00230664 -0.009954869 0.3957913 -0.006506085 -0.00999999 0.3972036 -0.007952868 0.00999999 0.3980782 0.007763206 0.00999999 0.4212504 0.00794208 0.00999999 0.4211082 0.01374131 0.00999999 0.4069212 0.01399576 0.00999999 0.4092556 0.01332718 0.00999999 0.4138877 0.01354652 0.00999999 0.4129396 0.01385641 0.00999999 0.4115998 0.01399976 0.00999999 0.4096 0.01242303 0.00999999 0.416055 0.0123924 0.00999999 0.4161036 0.01116931 0.00999999 0.4180407 0.01044261 0.00999999 0.418851 0.009601354 0.00999999 0.4197889 0.005706667 0.00999999 0.4223841 0.004949808 0.00999999 0.4226483 -0.001173973 0.00999999 0.4235507 0.001174271 0.00999999 0.4235507 0.001681864 0.00999999 0.4234646 0.003489613 0.00999999 0.4231581 -0.005706369 0.00999999 0.4223842 -0.004949808 0.00999999 0.4226483 -0.003489255 0.00999999 0.4231582 -0.001681864 0.00999999 0.4234646 -0.007762968 0.00999999 0.4212506 -0.00794208 0.00999999 0.4211082 -0.009601116 0.00999999 0.4197891 -0.01044261 0.00999999 0.418851 -0.01354652 0.00999999 0.4129396 -0.01332712 0.00999999 0.413888 -0.01242285 0.00999999 0.4160553 -0.0123924 0.00999999 0.4161036 -0.01116913 0.00999999 0.418041 -0.01355385 0.00999999 0.4062607 -0.01374137 0.00999999 0.4069215 -0.01399576 0.00999999 0.409256 -0.01399976 0.00999999 0.4096 -0.01385635 0.00999999 0.4116002 -0.0123614 0.00999999 0.4031105 -0.01310032 0.00999999 0.4046623 -0.01074093 0.00999999 0.4006205 -0.01209074 0.00999999 0.4025421 -0.009088933 0.00999999 0.3989515 -0.0104593 0.00999999 0.4003359 -0.00230664 0.009954869 0.3957913 -0.002133131 0.009910106 0.3957635 -0.001686811 0.009854078 0.3957076 -0.002506971 0.009982705 0.3958272 -0.002630591 0.00999993 0.3958494 -0.004964411 0.00999999 0.3965098 0.00168699 0.009847164 0.3957057 0.001522958 0.009818673 0.3956831 0.001342773 0.009810864 0.3956645 2.00569e-4 0.009798228 0.3956015 -0.001342773 0.009810864 0.3956645 0.002506971 0.009982705 0.3958272 0.00230658 0.009954869 0.3957913 0.01209056 0.00999999 0.4025418 0.01074069 0.00999999 0.4006202 0.0104593 0.00999999 0.4003359 0.009088635 0.00999999 0.3989512 0.01355385 0.00999999 0.4062607 0.0131002 0.00999999 0.404662 0.0123614 0.00999999 0.4031105 -0.004052042 -0.00999993 0.3937145 -0.003895342 -0.009999871 0.3939777 -0.003775656 -0.009999871 0.3941596 -0.00330305 -0.009999871 0.3948782 -0.003161191 -0.009999871 0.3950937 -0.002706766 -0.00999993 0.3957428 -0.002714991 -0.00999993 0.3957318 -0.002965748 -0.00999993 0.3953734 -0.002754151 -0.00999993 0.3956761 -0.002714991 0.00999993 0.3957318 -0.002947866 0.00999993 0.3954011 -0.002966344 0.00999993 0.3953734 -0.003895282 0.009999871 0.3939777 -0.003775238 0.009999871 0.394158 -0.003298163 0.00999993 0.3948749 -0.01038819 -0.01539736 0.3988787 -0.009996354 -0.01538527 0.3985202 -0.009995579 -0.01551604 0.3985477 -0.01023477 -0.01584404 0.3990371 -0.009729921 -0.01657718 0.3994799 -0.0101549 -0.0160765 0.3991195 -0.009749054 -0.01658016 0.3995063 -0.009762287 -0.01658254 0.3995248 -0.009757578 -0.01625001 0.3989623 -0.009616672 -0.01649862 0.3991702 -0.009554266 -0.01656973 0.3992543 -0.009863078 -0.01606398 0.3988066 -0.009915292 -0.01584798 0.3987045 -0.009921967 -0.01582062 0.3986916 0.009448528 -0.01435863 0.4209488 0.002974927 -0.0162 0.4212255 0.002715587 -0.0162 0.4212746 0.002896547 -0.01609474 0.4220553 -0.009237408 -0.01514136 0.4204992 -0.009687662 -0.01351416 0.4210304 -0.009547829 -0.01435863 0.4208654 -0.008782744 -0.01574778 0.4199627 -0.00774306 -0.01619994 0.4187359 -0.008267939 -0.01609474 0.4193553 -0.006659924 -0.01609474 0.4205164 -0.006238996 -0.0162 0.4198275 -0.007150411 -0.0162 0.4192371 -0.003005862 -0.01609474 0.4220293 -0.002818226 -0.0162 0.4212512 -0.003055036 -0.0162 0.4212047 -0.004891753 -0.01609474 0.421415 -0.004499316 -0.0162 0.4207246 -0.004587888 -0.0162 0.420682 -0.005871593 -0.0162 0.4200655 -0.001560091 -0.0162 0.4214982 -0.00104767 -0.01609474 0.4223447 -9.81645e-4 -0.0162 0.421537 -4.11521e-5 -0.0162 0.4215999 9.35707e-4 -0.01609474 0.4223534 8.76691e-4 -0.0162 0.4215448 0.001478016 -0.0162 0.4215087 0.004422903 -0.0162 0.4207552 0.004787802 -0.01609474 0.4214575 0.004490911 -0.0162 0.420723 0.005799293 -0.0162 0.4201057 0.006563782 -0.01609474 0.4205746 0.006149232 -0.0162 0.4198824 0.008181929 -0.01609474 0.4194275 0.007083296 -0.0162 0.4192865 0.007662951 -0.01619994 0.4188041 0.00869137 -0.01574778 0.4200394 0.009141325 -0.01514136 0.4205799 0.00958687 -0.01351416 0.4211151 0.007690906 -0.01351416 0.422459 0.005609929 -0.01351416 0.4234936 0.003393948 -0.01351416 0.424194 0.001096367 -0.01351416 0.4245433 -0.001227557 -0.01351416 0.4245331 -0.003522038 -0.01351416 0.4241636 -0.005731761 -0.01351416 0.4234439 -0.007803559 -0.01351416 0.4223909 -0.007690906 -0.01435863 0.4222064 -0.00564903 -0.01435863 0.423244 -0.003471195 -0.01435863 0.4239534 -0.001209855 -0.01435863 0.4243175 0.001080513 -0.01435863 0.4243276 0.003344953 -0.01435863 0.4239834 0.005528926 -0.01435863 0.4232931 0.007579922 -0.01435863 0.4222734 -0.007440924 -0.01514136 0.4217965 -0.005465328 -0.01514136 0.4228004 -0.003358364 -0.01514136 0.4234868 -0.001170516 -0.01514136 0.4238391 0.001045405 -0.01514136 0.4238488 0.003236234 -0.01514136 0.4235157 0.005349218 -0.01514136 0.4228479 0.007333457 -0.01514136 0.4218614 -0.007074654 -0.01574778 0.4211962 -0.005196332 -0.01574778 0.4221507 -0.00319302 -0.01574778 0.4228033 -0.001112878 -0.01574778 0.4231383 9.93971e-4 -0.01574778 0.4231475 0.00307691 -0.01574778 0.4228308 0.005085885 -0.01574778 0.4221959 0.006972491 -0.01574778 0.4212579 0.01260709 -0.01607644 0.4169502 0.01129859 -0.01607644 0.4188361 0.01155817 -0.01539736 0.4190483 0.01289671 -0.01539736 0.417119 0.01110661 -0.01539736 0.3996248 0.01085716 -0.01607644 0.3998488 0.01043736 -0.01658254 0.4002258 0.01253336 -0.01539736 0.4014897 0.01485097 -0.01539736 0.4080803 0.01442897 -0.01539736 0.4057705 0.01365 -0.01539736 0.4035553 0.01490557 -0.01539736 0.4104278 0.01459133 -0.01539736 0.4127548 0.01391619 -0.01539736 0.4150038 0.01402896 -0.01658254 0.4096 0.01457083 -0.01607644 0.4104092 0.01395612 -0.01658254 0.4081719 0.01451748 -0.01607644 0.4081145 0.01382678 -0.01658254 0.4074639 0.01355957 -0.01658254 0.4060012 0.01410496 -0.01607644 0.4058564 0.01291352 -0.01658254 0.404164 0.01334345 -0.01607644 0.4036911 0.01282751 -0.01658254 0.4039195 0.01225185 -0.01607644 0.4016718 0.01177811 -0.01658254 0.4019784 0.01119035 -0.01658254 0.4012101 0.01426368 -0.01607644 0.412684 0.01360368 -0.01607644 0.4148824 0.01400738 -0.01658254 0.4103779 0.01393961 -0.01658254 0.41088 0.0137121 -0.01658254 0.4125648 0.01321339 -0.01658254 0.414226 0.01307761 -0.01658254 0.4146782 0.01086169 -0.01658254 0.418479 0.01168966 -0.01658254 0.4172856 0.01211959 -0.01658254 0.416666 -0.01411604 -0.0160765 0.4058985 -0.01337164 -0.0160765 0.4037551 -0.01367884 -0.01539736 0.4036208 -0.01362621 -0.0160765 0.414824 -0.01427125 -0.0160765 0.4126487 -0.01459914 -0.01539736 0.4127187 -0.0149061 -0.01539736 0.410418 -0.01137143 -0.0160765 0.4187462 -0.01093894 -0.0160765 0.3999406 -0.01051592 -0.01658254 0.4003142 -0.01093173 -0.01658254 0.4183926 -0.01163268 -0.01539736 0.4189564 -0.01393926 -0.01539736 0.414944 -0.01444029 -0.01539736 0.4058134 -0.01258665 -0.01539736 0.4015728 -0.01119023 -0.01539736 0.3997187 -0.01265174 -0.0160765 0.416873 -0.01294237 -0.01539736 0.4170401 -0.01457136 -0.0160765 0.4103997 -0.01451915 -0.0160765 0.4081313 -0.0148527 -0.01539736 0.4080976 -0.012304 -0.0160765 0.401753 -0.01175063 -0.01658254 0.4171944 -0.0121625 -0.01658254 0.4165918 -0.01309931 -0.01658254 0.414622 -0.01324212 -0.01658254 0.4141403 -0.01371943 -0.01658254 0.4125308 -0.01394903 -0.01658254 0.4108097 -0.01400786 -0.01658254 0.4103688 -0.01395773 -0.01658254 0.4081881 -0.01381778 -0.01658254 0.4074131 -0.01357018 -0.01658254 0.4060416 -0.01290708 -0.01658254 0.4041323 -0.01285457 -0.01658254 0.4039811 -0.01182824 -0.01658254 0.4020565 -0.01118284 -0.01658254 0.4011996 0.008222639 0.01043993 0.4219398 0.006044387 0.01043993 0.4231406 0.006111264 0.01087766 0.4232904 -0.01106607 0.01099997 0.3995324 -0.0115081 0.01099997 0.3999791 -0.01150238 0.01087766 0.3999839 -0.0143795 0.01099997 0.4055199 -0.01472288 0.01099997 0.4067301 -0.01471549 0.01087766 0.4067316 -0.01196694 0.01099997 0.4186438 -0.01196694 0.01099997 0.4186439 -0.01196092 0.01087766 0.4186394 -0.006664514 0.01099997 0.422994 -0.006114006 0.01099997 0.4232974 -0.006110906 0.01087766 0.4232906 0 0.01099997 0.4245471 0.001258194 0.01099997 0.4245471 0.001257538 0.01087766 0.4245396 0.003429055 0.01099997 0.4241791 0.00373882 0.01099997 0.4241266 0.003736972 0.01087766 0.4241193 0.01308935 0.01099997 0.4023215 0.01295417 0.01099997 0.4020376 0.01294767 0.01087766 0.4020414 0.009396374 0.01011949 0.3985907 0.009626507 0.01043993 0.3983211 0.009732961 0.01087766 0.3981963 0.009737849 0.01099997 0.3981906 -0.009626746 0.01043993 0.3983213 -0.009733259 0.01087766 0.3981966 -0.009396672 0.01011949 0.3985909 0.01150214 0.01087766 0.3999836 0.01150792 0.01099997 0.3999788 0.01106607 0.01099997 0.3995324 0.01403594 0.01099997 0.4043093 0.01496142 0.01099997 0.4089192 0.01472282 0.01099997 0.4067298 0.01471543 0.01087766 0.4067313 0.0143795 0.01099997 0.4055199 0.01498794 0.01087766 0.4092313 0.01499545 0.01099997 0.409231 0.01484614 0.01099997 0.4117427 0.01367342 0.01099997 0.4156459 0.01427912 0.01099997 0.4141941 0.01427197 0.01087766 0.4141917 0.01470446 0.01099997 0.4123553 0.01330375 0.01087766 0.4165127 0.01331037 0.01099997 0.4165161 0.01196712 0.01099997 0.4186436 0.01028203 0.01087766 0.4205112 0.01028716 0.01099997 0.4205167 0.01196694 0.01099997 0.4186438 0.006664514 0.01099997 0.422994 0.008317768 0.01099997 0.4220826 0.008313596 0.01087766 0.4220763 0.009548723 0.01099997 0.4211038 0.006114304 0.01099997 0.4232972 -0.003429055 0.01099997 0.4241791 -0.001257836 0.01099997 0.4245471 -0.001257181 0.01087766 0.4245397 -0.003736615 0.01087766 0.4241194 -0.003738522 0.01099997 0.4241266 -0.009548723 0.01099997 0.4211038 -0.00831747 0.01099997 0.4220827 -0.008313298 0.01087766 0.4220765 -0.01028174 0.01087766 0.4205114 -0.01028692 0.01099997 0.4205169 -0.01367342 0.01099997 0.4156459 -0.01331025 0.01099997 0.4165164 -0.01330357 0.01087766 0.416513 -0.01470446 0.01099997 0.4123553 -0.01427906 0.01099997 0.4141944 -0.01427191 0.01087766 0.4141921 -0.01483869 0.01087766 0.411742 -0.01484608 0.01099997 0.4117431 -0.01496142 0.01099997 0.4089192 -0.01498794 0.01087766 0.4092316 -0.01499545 0.01099997 0.4092314 -0.01499998 0.01099997 0.4096 -0.01402902 0.01087766 0.4043123 -0.01403605 0.01099997 0.4043096 -0.01294785 0.01087766 0.4020417 -0.01295435 0.01099997 0.402038 -0.01308935 0.01099997 0.4023215 -0.009738147 0.01099997 0.3981909 0.0101695 0.01043993 0.4203918 0.01137632 0.01043993 0.4000888 0.01280605 0.01043993 0.4021241 0.0111044 0.01011949 0.4003161 0.01249992 0.01011949 0.4023028 0.01455444 0.01043993 0.4067626 0.01482397 0.01043993 0.4092352 0.01420658 0.01011949 0.4068304 0.01446962 0.01011949 0.409244 0.01411586 0.01043993 0.4141415 0.0131582 0.01043993 0.416437 0.01377844 0.01011949 0.4140329 0.01284366 0.01011949 0.4162736 0.0115475 0.01011949 0.4183265 0.01183027 0.01043993 0.4185402 0.01196116 0.01087766 0.4186391 0.005899906 0.01011949 0.4228169 0.008026123 0.01011949 0.4216449 0.009926438 0.01011949 0.4201339 0.00124377 0.01043993 0.4243762 -0.001243472 0.01043993 0.4243763 0.001214087 0.01011949 0.424023 -0.001213729 0.01011949 0.424023 -0.006044089 0.01043993 0.4231408 -0.008222341 0.01043993 0.42194 -0.005899608 0.01011949 0.4228171 -0.008025825 0.01011949 0.4216451 -0.01183009 0.01043993 0.4185405 -0.01315802 0.01043993 0.4164373 -0.01154732 0.01011949 0.4183268 -0.01284348 0.01011949 0.4162739 -0.01411575 0.01043993 0.4141418 -0.01377832 0.01011949 0.4140332 -0.01482397 0.01043993 0.4092356 -0.0145545 0.01043993 0.406763 -0.01446962 0.01011949 0.4092443 -0.01420664 0.01011949 0.4068308 -0.01280623 0.01043993 0.4021244 -0.01137655 0.01043993 0.4000891 -0.0125001 0.01011949 0.4023031 -0.01110458 0.01011949 0.4003164 0.0140289 0.01087766 0.404312 0.01387542 0.01043993 0.4043698 0.01354378 0.01011949 0.4044948 0.01483869 0.01087766 0.4117416 0.01467639 0.01043993 0.4117182 0.01432555 0.01011949 0.4116675 0.003696084 0.01043993 0.4239605 0.003607749 0.01011949 0.4236172 -0.003695726 0.01043993 0.4239605 -0.003607392 0.01011949 0.4236173 -0.01016926 0.01043993 0.4203921 -0.009926199 0.01011949 0.4201341 -0.01467633 0.01043993 0.4117185 -0.01432549 0.01011949 0.4116679 -0.01387554 0.01043993 0.4043701 -0.0135439 0.01011949 0.4044951 0.006029725 0.002091646 0.3526761 0.006356894 5.67532e-4 0.3526761 0.006680071 5.96381e-4 0.3528929 0.003072619 0.005593836 0.3526761 0.004337072 0.004682123 0.3526761 0.004557549 0.004920125 0.3528929 -0.002931058 0.005669295 0.3526761 -0.001469254 0.006210744 0.3526761 -0.001543939 0.00652647 0.3528929 -0.006340622 7.2714e-4 0.3526761 -0.005975186 0.002242565 0.3526761 -0.006278932 0.002356529 0.3528929 0.006382167 0 0.3526761 0.006706595 0 0.3528929 0.006681919 5.53752e-4 0.3528929 -0.006704509 1.68578e-4 0.3528929 -0.0063802 1.60423e-4 0.3526761 -0.006677627 5.53407e-4 0.3528929 -0.006662964 7.64103e-4 0.3528929 -0.004217982 0.00478965 0.3526761 -0.004897475 0.004509627 0.3528929 -0.005253314 0.0036242 0.3526761 -0.005520343 0.003808438 0.3528929 -0.006111025 0.002677977 0.3528929 -0.00308007 0.005957484 0.3528929 -0.003183901 0.005886495 0.3528929 -0.004432439 0.005033075 0.3528929 0.001624882 0.006171882 0.3526761 0.0010975 0.006568431 0.3528929 8.02179e-5 0.00638169 0.3526761 8.42956e-5 0.006706058 0.3528929 -0.001099467 0.006575524 0.3528929 0.003228843 0.00587821 0.3528929 0.0031901 0.005893647 0.3528929 0.001707494 0.006485581 0.3528929 0.006336212 0.00219798 0.3528929 0.006102204 0.002674579 0.3528929 0.005342781 0.003490984 0.3526761 0.00561434 0.003668487 0.3528929 0.004900574 0.004513859 0.3528929 -0.00539726 -0.003406167 0.3526761 -0.006069839 -0.001972138 0.3526761 -0.006378352 -0.002072393 0.3528929 -8.02179e-5 -0.00638169 0.3526761 -0.00164926 -0.006165385 0.3526761 -0.001733064 -0.006478786 0.3528929 0.005309939 -0.003540754 0.3526761 0.004274487 -0.004739284 0.3526761 0.004491746 -0.004980206 0.3528929 -0.006706595 0 0.3528929 0.006382167 0 0.3526761 0.006679177 -6.05976e-4 0.3528929 0.00635606 -5.76663e-4 0.3526761 0.006454348 -0.001636087 0.3528929 0.00601834 -0.00212413 0.3526761 0.005579829 -0.0037207 0.3528929 0.005607843 -0.003664791 0.3528929 0.006324291 -0.002232074 0.3528929 0.001493752 -0.006204903 0.3526761 0.00216037 -0.006297528 0.3528929 0.002975761 -0.00564599 0.3526761 0.003127038 -0.005932986 0.3528929 0.004094779 -0.005257368 0.3528929 -8.42956e-5 -0.006706058 0.3528929 -1.10871e-6 -0.00669676 0.3528929 0.001569688 -0.00652033 0.3528929 -0.004392266 -0.004630386 0.3526761 -0.004089951 -0.005252659 0.3528929 -0.003116726 -0.005569398 0.3526761 -0.003275156 -0.00585252 0.3528929 -0.00216192 -0.006304621 0.3528929 -0.00567162 -0.003579318 0.3528929 -0.005605041 -0.00366038 0.3528929 -0.004615545 -0.004865765 0.3528929 -0.006368577 -4.16714e-4 0.3526761 -0.00669229 -4.37896e-4 0.3528929 -0.006461679 -0.00163871 0.3528929 0.004417419 -0.009931623 0.3921844 0.004419684 -0.009932518 0.3921858 0.004299104 -0.00990504 0.3923919 0.004729926 -0.01005351 0.392377 0.004308223 -0.009914815 0.3924006 0.004307866 -0.009914457 0.3924003 0.004415571 -0.009930849 0.3921833 0.004083752 -0.009673655 0.3921838 0.004171252 -0.009677112 0.392018 0.004185199 -0.009915947 0.3927089 0.004186689 -0.009917199 0.3927097 0.004361391 -0.009958803 0.3928071 0.004184901 -0.009915769 0.3927087 0.003896474 -0.009682476 0.392548 0.003520429 -0.009767413 0.3933655 0.003661274 -0.009880661 0.3934598 0.00351727 -0.009768128 0.3933724 0.003404021 -0.009793698 0.3936186 0.00240755 -0.009944796 0.3955987 0.002431213 -0.009942471 0.3955534 0.00244677 -0.009940803 0.3955237 0.002448976 -0.009940564 0.3955194 0.00249803 -0.009933114 0.395422 0.00307399 -0.009955704 0.3947013 0.002913892 -0.009869456 0.3945952 0.003393352 -0.009796142 0.3936419 0.00324279 -0.009995877 0.3948155 0.003825187 -0.009959638 0.3935601 0.00324279 0.009995877 0.3948155 0.00399959 0.009996831 0.3936668 0.00307399 0.009955704 0.3947013 0.002913892 0.009869456 0.3945952 0.00254184 0.009926378 0.3953349 0.002448976 0.009940564 0.3955194 0.002407491 0.009944736 0.3955987 0.003896474 0.009682476 0.392548 0.003563582 0.009757637 0.3932717 0.004037439 0.00979644 0.3926265 0.003404021 0.009793698 0.3936185 0.003393292 0.009796142 0.3936419 0.003825187 0.009959638 0.3935601 0.004185199 0.009915947 0.3927088 0.004184901 0.009915769 0.3927087 0.004186689 0.009917199 0.3927097 0.004307746 0.009914338 0.3924006 0.004083752 0.009673655 0.3921838 0.004298985 0.00990498 0.3923922 0.004307687 0.009914338 0.3924006 0.004729926 0.01005351 0.392377 0.004419684 0.009932518 0.3921858 0.004171252 0.009677112 0.392018 0.004415571 0.009930849 0.3921833 0.004417419 0.009931623 0.3921844 0.001342773 -0.009768307 0.39546 0.001342773 -0.009176492 0.3936262 -0.001342773 -0.009768307 0.39546 -0.001342773 -0.009176492 0.3936262 -0.001342773 -0.008944332 0.3932063 -0.001342773 0.009750127 0.3953785 0.001342773 0.009750127 0.3953785 -0.001342773 0.009142994 0.3935497 0.001342773 0.008948266 0.3932045 0.001342773 0.009142994 0.3935497 0.001342773 -0.008944332 0.3932063 0.001342773 -0.008243978 0.3919399 -0.001342773 -0.008243978 0.3919399 0.001342773 -0.007386088 0.3909175 -0.001342773 -0.007386088 0.3909175 0.001342773 -0.007005333 0.3904638 -0.001342773 -0.007005333 0.3904638 0.001342773 -0.005506575 0.3892527 -0.001342773 -0.005506575 0.3892527 0.001342773 -0.005276322 0.3891309 -0.001342773 -0.005276322 0.3891309 0.001342773 -0.003803312 0.3883515 -0.001342773 -0.003803312 0.3883515 0.001342773 -0.002736032 0.3880288 -0.001342773 -0.002736032 0.3880288 0.001342773 -0.001958906 0.3877937 -0.001342773 -0.001958906 0.3877937 0.001342773 -4.1737e-5 0.3876001 -0.001342773 -4.17357e-5 0.3876001 0.001342773 -3.62733e-7 0.3876039 -0.001342773 -3.62723e-7 0.3876039 0.001342773 0.00187695 0.3877778 -0.001342773 0.00187695 0.3877778 0.001342773 0.002736151 0.3880298 -0.001342773 0.002736151 0.3880298 0.001342773 0.003726005 0.3883201 -0.001342773 0.003726005 0.3883201 0.001342773 0.005279362 0.3891254 -0.001342773 0.005279362 0.3891254 0.001342773 0.005436718 0.389207 -0.001342773 0.005436718 0.389207 0.001342773 0.00694549 0.3904056 -0.001342773 0.00694549 0.3904056 0.001342773 0.007384181 0.3909196 -0.001342773 0.007384181 0.3909196 0.001342773 0.008196413 0.3918713 -0.001342773 0.008196413 0.3918713 -0.001342773 0.008948266 0.3932045 -0.003819882 -0.009960174 0.3935722 -0.003994286 -0.00999695 0.393679 -0.003234863 -0.009996116 0.3948319 -0.003066003 -0.009956479 0.3947176 -0.002497851 -0.009932756 0.3954218 -0.002905786 -0.009870648 0.3946112 -0.003310859 -0.009809017 0.3938064 -0.002440333 -0.009941518 0.3955361 -0.002308428 -0.00995469 0.3957879 -0.003896474 -0.009682476 0.392548 -0.003520309 -0.009767293 0.3933653 -0.004037439 -0.0097965 0.3926265 -0.003385841 -0.009797632 0.3936575 -0.00418514 -0.009916007 0.3927089 -0.004184901 -0.009915828 0.3927088 -0.004186809 -0.009917378 0.3927098 -0.004307687 -0.009914338 0.3924008 -0.004083752 -0.009673655 0.3921838 -0.004298925 -0.00990498 0.3923923 -0.004307627 -0.009914338 0.3924008 -0.004185259 0.009915888 0.3927089 -0.004298925 0.00990498 0.3923923 -0.004307627 0.009914338 0.3924008 -0.004361391 0.009958803 0.3928071 -0.004186809 0.00991714 0.3927098 -0.004307687 0.009914338 0.3924008 -0.004083752 0.009673655 0.3921838 -0.004184961 0.009915649 0.3927088 -0.003896474 0.009682476 0.392548 -0.003066003 0.009956479 0.3947176 -0.003819823 0.009960174 0.3935722 -0.003234803 0.009996116 0.3948319 -0.003563523 0.009757578 0.3932715 -0.00365585 0.009881556 0.3934718 -0.003511607 0.00976926 0.3933842 -0.003385841 0.009797632 0.3936575 -0.002308428 0.00995469 0.3957879 -0.002440333 0.009941518 0.3955361 -0.00254172 0.00992608 0.3953347 -0.002905786 0.009870707 0.3946113 -0.003310859 0.009809017 0.3938065 -0.004729926 -0.01005351 0.392377 -0.004419684 -0.009932518 0.3921858 -0.004171252 -0.009677112 0.392018 -0.004415571 -0.009930849 0.3921833 -0.004419684 0.009932518 0.3921858 -0.004415571 0.009930849 0.3921833 -0.004171252 0.009677112 0.392018 -0.004729926 0.01005351 0.392377 -0.008924961 -0.0160889 0.3965126 -0.008889675 -0.01626223 0.3965696 -0.008862793 -0.01625216 0.3963106 -0.009137213 -0.01559782 0.3971436 -0.009167373 -0.01556062 0.3972021 -0.009155988 -0.01580744 0.3972787 -0.009912908 -0.01492875 0.3983384 -0.009170055 -0.01660728 0.3986423 -0.00905323 -0.01627528 0.3974543 -0.008782327 -0.0166828 0.3972263 -0.008740603 -0.01668936 0.396717 -0.008717477 -0.01669299 0.3964349 -0.008825063 -0.01635128 0.396188 -0.008714973 -0.01669353 0.3963778 -0.008706927 -0.01668655 0.3957785 -0.008975565 -0.01663947 0.3981356 -0.008881151 -0.01666063 0.3976915 -0.00887072 -0.01666301 0.3976422 -0.009337306 -0.01627153 0.3982698 -0.009120404 -0.0166155 0.3985128 -0.009012639 -0.01663333 0.3982322 -0.00948143 -0.01583355 0.3980515 -0.009518742 -0.01535016 0.397892 -0.009350836 -0.01533412 0.3975588 -0.009387612 -0.01528877 0.3976302 -0.009486675 -0.0151664 0.3978228 -0.009505927 -0.01515567 0.3978461 -0.009855329 -0.01496082 0.3982688 -0.008928179 -0.01608037 0.3965232 -0.009027957 -0.01581823 0.3968475 -0.009029924 -0.0158143 0.3968527 -0.009040832 -0.01579231 0.3968824 -0.005960047 -0.01648598 0.4149364 -0.005961835 -0.01648998 0.4149343 -0.006156146 -0.01719999 0.4147089 -0.006110846 -0.01685345 0.414763 -0.006105363 -0.01681154 0.4147695 -0.005711555 -0.0162661 0.4152004 -0.005738794 -0.01627355 0.4151737 -0.005470454 -0.0162 0.4154373 0.00542128 -0.0162 0.4154829 0.004756152 -0.0162 0.4160326 0.002487897 -0.0162 0.4172033 -0.004809916 -0.0162 0.4159925 -0.002551555 -0.0162 0.4171822 -3.35409e-5 -0.0162 0.4175999 0.005962908 -0.01656365 0.4149332 0.005911946 -0.01650583 0.4149878 0.005726158 -0.01629507 0.4151867 0.00566715 -0.01627665 0.4152441 0.00606209 -0.01686191 0.4148195 0.00609374 -0.01695704 0.4147832 0.006113111 -0.01719999 0.4147604 0.009157955 -0.01739335 0.4008327 0.008621037 -0.01798135 0.4016929 0.009750604 -0.01660066 0.3995554 0.009654104 -0.01674336 0.3997936 0.009635865 -0.01677024 0.3998386 0.009397506 -0.01708102 0.4003345 0.008473336 -0.01811867 0.4018707 0.008564352 -0.01857244 0.4031789 0.008100986 -0.01846498 0.4023191 0.008024394 -0.01853013 0.4023965 0.008018016 -0.01853555 0.4024031 0.008014261 -0.01853871 0.4024065 0.007973551 -0.0185725 0.4024459 0.00868386 -0.01857244 0.4033272 0.009661436 -0.01857244 0.4049725 0.009842038 -0.01857244 0.4054564 0.01033067 -0.01857244 0.4067655 0.01054793 -0.01857244 0.4079707 0.01067018 -0.01857244 0.4086489 0.01066917 -0.01857244 0.4105627 0.01066595 -0.01857244 0.4105802 0.01032757 -0.01857244 0.4124458 0.01007336 -0.01857244 0.4131247 0.009656369 -0.01857244 0.414238 0.008923053 -0.01857244 0.4154692 0.008677005 -0.01857244 0.4158823 0.00802797 -0.01857244 0.4166929 -0.009688436 -0.01857244 0.4141707 -0.008969128 -0.01857244 0.4153993 -0.008727133 -0.01857244 0.4158125 -0.008088588 -0.01857244 0.4166237 -0.0106737 -0.01857244 0.410511 -0.01067101 -0.01857244 0.4105263 -0.0103442 -0.01857244 0.4123848 -0.01009637 -0.01857244 0.4130598 -0.00801599 -0.01853734 0.4024055 -0.008558571 -0.01857244 0.4031713 -0.008003175 -0.01854777 0.4024173 -0.007973551 -0.01857244 0.4024459 -0.00846976 -0.01812201 0.4018755 -0.008617341 -0.01798516 0.4016988 -0.008018553 -0.01853489 0.4024022 -0.008026361 -0.01852828 0.4023945 -0.008088767 -0.01847529 0.4023318 -0.008679926 -0.01857244 0.4033218 -0.009653687 -0.01857244 0.4049562 -0.009833097 -0.01857244 0.4054337 -0.01032286 -0.01857244 0.4067372 -0.01054227 -0.01857244 0.4079318 -0.01066648 -0.01857244 0.4086084 -0.009152472 -0.01739954 0.4008424 -0.009391188 -0.01708871 0.4003466 -0.009628772 -0.01677942 0.3998531 -0.009749114 0.01658016 0.3995063 -0.009762287 0.01658254 0.3995247 -0.0100528 0.0162487 0.3992249 -0.010338 0.01561182 0.3989306 -0.0104379 0.0148676 0.3988274 -0.01000934 0.01502704 0.3984333 -0.01036888 0.01486843 0.3987609 -0.009999334 0.01490163 0.3984191 -0.009992063 0.01538282 0.3985246 -0.009980261 0.01562488 0.3985868 -0.0102356 0.01584041 0.3990362 -0.009761214 0.01625311 0.3989589 -0.009554266 0.01656973 0.3992543 -0.009708523 0.01657426 0.3994508 -0.00992316 0.01582008 0.3986902 -0.009915411 0.01584649 0.3987041 -0.009824931 0.0161556 0.3988679 -0.009729921 0.01657718 0.3994799 -0.009727299 0.01657676 0.3994762 -0.01491588 0.0148676 0.4080142 -0.01494091 0.0148676 0.4089179 0.009115993 0.01101869 0.3976879 -0.009560585 0.01218718 0.3980429 -0.009810745 0.01310664 0.3982532 -0.009117662 0.01102226 0.3976892 -0.009204387 0.01123404 0.3977578 -0.009493231 0.0119397 0.3979862 -0.009984493 0.01445412 0.3984058 -0.009989678 0.01455289 0.3984104 -0.009998261 0.01486253 0.3984181 -0.009844541 0.01327991 0.3982825 -0.009929656 0.01399397 0.3983575 -0.01109212 0.0148676 0.3995066 0.009985268 0.014463 0.3984065 0.011092 0.0148676 0.3995067 0.0104379 0.0148676 0.3988274 0.009999513 0.01490169 0.398419 0.009998619 0.01486778 0.3984182 0.009990096 0.01455795 0.3984108 0.009930312 0.01399892 0.3983581 0.009845674 0.01328462 0.3982835 0.009810745 0.01311182 0.3982533 0.009784042 0.01297956 0.3982301 0.009563744 0.01219111 0.3980454 0.009494721 0.01194411 0.3979875 0.009205877 0.01123839 0.397759 0.01115971 0.0148676 0.399577 0.01259332 0.0148676 0.4014509 0.01307028 0.0148676 0.4023331 0.01371532 0.0148676 0.4035264 0.01441341 0.0148676 0.4055114 0.01449805 0.0148676 0.4057521 0.01492208 0.0148676 0.4080731 0.01494169 0.0148676 0.4089177 0.01497691 0.0148676 0.4104318 0.01471644 0.0148676 0.4123606 0.01466119 0.0148676 0.4127699 0.01398277 0.0148676 0.4150297 0.01368457 0.0148676 0.4156484 0.0129584 0.0148676 0.417155 0.01193892 0.0148676 0.4186244 0.009578526 0.01319998 0.4211412 0.009597301 0.01319998 0.4211278 0.01036304 0.01319998 0.4204447 0.01085394 0.01459079 0.419953 0.01092725 0.0148676 0.4198759 0.01161348 0.0148676 0.4190935 0.01058357 0.01380538 0.4202249 0.01061034 0.01387882 0.4201982 0.01081192 0.01443225 0.4199972 0.01081442 0.01444178 0.4199945 0.007699251 0.01319998 0.4224733 0.006663501 0.01319998 0.4229882 0.005615949 0.01319998 0.423509 0.003432095 0.01319998 0.4241992 0.003397524 0.01319998 0.4242101 -0.01089388 0.01445674 0.4199092 -0.01072663 0.01389908 0.4200851 -0.01101708 0.0148676 0.4197795 -0.01093196 0.01458382 0.4198691 -0.0116927 0.0148676 0.4189957 -0.01194363 0.0148676 0.4186279 -0.01071703 0.01387399 0.4200948 -0.01068753 0.01379728 0.4201241 -0.01045799 0.01319992 0.4203531 -0.00969845 0.01319998 0.4210429 -0.009572982 0.01319998 0.4211335 -0.007812321 0.01319998 0.422405 -0.006663382 0.01319998 0.4229888 -0.005738198 0.01319998 0.423459 -0.003526091 0.01319998 0.4241797 -0.003431797 0.01319998 0.4241948 -0.001229107 0.01319998 0.4245495 1.97258e-7 0.01319998 0.424555 0.001097381 0.01319998 0.4245598 -0.01301473 0.0148676 0.4170576 -0.01368212 0.0148676 0.4156475 -0.01401835 0.0148676 0.4149371 -0.01467913 0.0148676 0.4126859 -0.01472115 0.0148676 0.4123614 -0.01498073 0.0148676 0.4103593 -0.01448619 0.0148676 0.4057078 -0.01441621 0.0148676 0.4055105 -0.01370209 0.0148676 0.4034966 -0.01307052 0.0148676 0.4023331 -0.01115578 0.0148676 0.3995726 -0.01258283 0.0148676 0.4014347 -3.23602e-7 -0.005994081 0.3620768 0 -0.005994081 0.3620768 0 -0.005994081 0.3591233 3.2416e-7 -0.005994081 0.3591233 2.8411e-4 -0.005993127 0.3620728 7.46865e-4 -0.005951106 0.361891 0.001277863 -0.005860805 0.3598621 7.9431e-4 -0.005946815 0.3618724 0.001164853 -0.005886018 0.361545 0.00149995 -0.005809426 0.3606 0.001415073 -0.005830764 0.3601025 0.001404583 -0.005833268 0.3611264 0.001282095 -0.005860209 0.3613403 0.001147985 -0.005889236 0.3596346 7.46113e-4 -0.005952239 0.3593057 7.19062e-4 -0.00595647 0.3592836 2.43518e-4 -0.005994915 0.3591199 -2.84626e-4 -0.005993068 0.3591272 -7.46845e-4 -0.005951106 0.359309 -0.001277804 -0.005860805 0.3613379 -7.94605e-4 -0.005946755 0.3593277 -0.001164853 -0.005886018 0.359655 -0.00149995 -0.005809426 0.3606 -0.001415491 -0.005830645 0.3610963 -0.001404583 -0.005833268 0.3600736 -0.001282095 -0.005860209 0.3598597 -0.001148521 -0.005889177 0.3615648 -7.4617e-4 -0.005952239 0.3618943 -7.19577e-4 -0.005956411 0.3619161 -2.42887e-4 -0.005994915 0.3620802 -3.55e-7 0.005994081 0.3591232 0 0.005994081 0.3591232 0 0.005994081 0.3620768 3.55058e-7 0.005994081 0.3620768 7.46927e-4 0.005951106 0.3593088 7.93584e-4 0.005946874 0.3593271 0.001284599 0.005859673 0.3613411 0.001162171 0.005886554 0.3596517 0.001282274 0.005860149 0.3598597 0.001380324 0.005839049 0.3611871 0.001498162 0.005809962 0.360674 0.00149995 0.005809426 0.3606 0.001402318 0.005833804 0.3600676 0.001137375 0.005891323 0.3615779 7.44724e-4 0.00595206 0.3618924 7.05969e-4 0.00595802 0.3619235 2.86379e-4 0.005993008 0.3591276 2.41198e-4 0.005994975 0.3620805 -7.46927e-4 0.005951106 0.3618912 -7.93586e-4 0.005946874 0.3618729 -0.001284599 0.005859673 0.3598589 -0.001162111 0.005886554 0.3615484 -0.001282274 0.005860149 0.3613403 -0.001380324 0.005839049 0.360013 -0.001498162 0.005809962 0.3605259 -0.00149995 0.005809426 0.3606 -0.001402258 0.005833804 0.3611325 -0.001137375 0.005891323 0.3596221 -7.44724e-4 0.00595206 0.3593075 -7.05971e-4 0.00595802 0.3592765 -2.86381e-4 0.005993008 0.3620724 -2.41204e-4 0.005994975 0.3591195 -1.84239e-6 -0.007708251 0.3539285 -4.19157e-4 -0.007730841 0.3539285 -0.002071261 -0.007459998 0.3539285 -0.002500414 -0.007288992 0.3539285 -0.003626525 -0.006840348 0.3539285 -0.004739224 -0.006085872 0.3539285 -0.005012214 -0.0059008 0.3539285 -0.006163537 -0.004685401 0.3539285 -0.006447196 -0.004213929 0.3539285 -0.007026672 -0.003250837 0.3539285 -0.007484018 -0.001893401 0.3539285 -0.007561206 -0.00166434 0.3539285 -0.007742226 0 0.3539285 -0.007673203 6.34718e-4 0.3539285 -0.007561206 0.00166434 0.3539285 -0.007075726 0.003105163 0.3539285 -0.007026672 0.003250837 0.3539285 -0.006163537 0.004685401 0.3539285 -0.005663752 0.005212962 0.3539285 -0.005012214 0.0059008 0.3539285 -0.003681004 0.006803393 0.3539285 -0.003626525 0.006840348 0.3539285 -0.002071261 0.007459998 0.3539285 -0.001266956 0.007591843 0.3539285 -4.19157e-4 0.007730841 0.3539285 0.001252532 0.007640242 0.3539285 0.001273691 0.007634341 0.3539285 0.002865672 0.007192313 0.3539285 0.003663718 0.006769239 0.3539285 0.00434482 0.006408154 0.3539285 0.005620837 0.005324304 0.3539285 0.005687236 0.005236923 0.3539285 0.006633996 0.003991544 0.3539285 0.007050335 0.003091573 0.3539285 0.007336914 0.002472102 0.3539285 0.007696807 8.37084e-4 0.3539285 0.007696807 6.3935e-4 0.3539285 0.007696807 -8.37084e-4 0.3539285 0.007464706 -0.001891613 0.3539285 0.007336914 -0.002472102 0.3539285 0.006633996 -0.003991544 0.3539285 0.006461024 -0.004218995 0.3539285 0.005620837 -0.005324304 0.3539285 0.004730582 -0.006080508 0.3539285 0.001252532 -0.007640242 0.3539285 0.002505421 -0.00729233 0.3539285 0.002865672 -0.007192313 0.3539285 0.00434482 -0.006408154 0.3539285 0.004424631 -0.009932398 0.3921715 0.0047369 -0.01005458 0.3923613 0.004177093 -0.009677708 0.3920074 0.004415571 -0.009930849 0.3921833 0.004422128 -0.009931445 0.3921699 0.00240767 -0.009308993 0.3935688 0.00240767 0.003779768 0.3881861 0.00240767 0.005515158 0.3890859 0.003404796 0.005747914 0.3887265 0.00240767 -0.001987159 0.3876522 0.00240767 -4.23394e-5 0.3874557 0.003404796 -4.41262e-5 0.3870276 0.00240767 -0.008362948 0.3918582 0.00240767 -0.007106423 0.3903608 0.003404796 -0.007406353 0.3900553 0.003404796 0.008665621 0.3915433 0.00240767 0.008314728 0.3917886 0.00240767 0.009275019 0.3934913 0.003404796 0.009666383 0.3933179 0.00240767 0.009890854 0.3953465 0.00240767 -0.009909331 0.3954291 0.003404796 -0.009701788 0.3933987 0.004171252 -0.008950769 0.390968 0.004171252 -0.009209871 0.3912768 0.003404796 -0.008715927 0.3916159 0.004171252 -0.002572894 0.3867611 0.004171252 -0.004248976 0.387268 0.003404796 -0.004021048 0.3878221 0.004171252 -0.005001068 0.3876659 0.003404796 -0.005821764 0.3887749 0.004171252 -0.006151735 0.3882747 0.004171252 -0.007163166 0.389092 0.004171252 -0.007826089 0.3896278 0.004171252 -4.66269e-5 0.3864285 0.004171252 -0.002188384 0.3866448 0.003404796 -0.002071022 0.3872324 0.003404796 0.001984417 0.3872154 0.004171252 0.002096891 0.3866269 0.004171252 -4.04188e-7 0.3864328 0.004171252 0.006073653 0.3882237 0.004171252 0.00500071 0.3876674 0.003404796 0.00393933 0.3877888 0.004171252 0.004162549 0.3872328 0.004171252 0.002571702 0.3867662 0.003404796 0.007343113 0.3899937 0.004171252 0.007759273 0.3895627 0.004171252 0.007164895 0.3890905 0.004171252 0.008955478 0.3909643 0.004171252 0.009156763 0.3912001 0.00240767 -0.005586028 0.3891322 0.00240767 0.00190407 0.387636 0.00240767 0.007045745 0.3903017 0.00240767 -0.003858268 0.388218 0.004177093 0.009677708 0.3920074 0.004422128 0.009931445 0.3921699 0.004415571 0.009930849 0.3921833 0.004424035 0.00993216 0.3921711 0.004424631 0.009932398 0.3921715 0.0047369 0.01005458 0.3923613 -0.00948143 0.01583349 0.3980514 -0.009167075 0.0166074 0.398635 -0.009337365 0.01627135 0.3982697 -0.009120225 0.01661533 0.3985128 -0.009012579 0.01663351 0.3982326 -0.008975148 0.01663982 0.3981351 -0.009053289 0.0162751 0.3974542 -0.008884847 0.01665997 0.3976933 -0.008739054 0.01668989 0.3967172 -0.008771002 0.01668542 0.3971362 -0.008874297 0.01666235 0.3976416 -0.008706927 0.01668655 0.3957785 -0.008717477 0.01669293 0.3964349 -0.008816123 0.01637643 0.3961549 -0.008824944 0.01635128 0.3961862 -0.009027838 0.01581889 0.3968471 -0.008928179 0.01608031 0.3965225 -0.008889734 0.01626205 0.3965695 -0.00892508 0.01608836 0.3965125 -0.008862733 0.01625204 0.3963092 -0.009041011 0.01579219 0.3968828 -0.009029805 0.0158149 0.3968525 -0.008825719 0.01634913 0.3961886 -0.009511828 0.0151605 0.3978447 -0.009388744 0.015289 0.3976298 -0.009518742 0.0153501 0.397892 -0.009345531 0.01533418 0.3975543 -0.009215414 0.01547002 0.3973272 -0.009155988 0.01580733 0.3972787 -0.009162664 0.01555579 0.3972032 -0.009136676 0.01559811 0.3971421 -0.009859859 0.01496756 0.3982637 -0.009561479 0.01510864 0.3979313 -0.003316223 0.008623242 0.391573 -0.003316223 0.009619116 0.3933388 -0.002308428 0.009251177 0.3935018 -0.003316223 0.003920018 0.3878369 -0.003316223 0.00571978 0.38877 -0.002308428 0.005501031 0.3891077 -0.002308428 0.00829339 0.3918035 -0.002308428 0.003770112 0.3882103 -0.002308428 -4.22295e-5 0.3874818 -0.002308428 -0.001982092 0.3876777 -0.002308428 -0.008341491 0.391873 -0.002308428 -0.009285092 0.3935792 -0.004171252 0.008955478 0.3909643 -0.004171252 0.009156763 0.3912001 -0.004171252 -0.009209871 0.3912768 -0.003316223 -0.00867325 0.3916452 -0.003316223 -0.009654343 0.3934193 -0.002308428 -0.00988388 0.3954347 -0.002308428 0.009865462 0.3953523 -0.002308428 -0.007088184 0.3903794 -0.002308428 -0.005571722 0.389154 -0.002308428 -0.003848314 0.3882421 -0.002308428 0.001899182 0.3876615 -0.002308428 0.007027685 0.3903205 -0.003316223 -4.39089e-5 0.3870794 -0.003316223 -0.00206089 0.3872832 -0.003316223 -0.004001379 0.38787 -0.003316223 -0.005793273 0.388818 -0.003316223 -0.007370114 0.3900923 -0.003316223 0.001974701 0.3872663 -0.003316223 0.007307171 0.390031 -0.004171252 -0.008950769 0.390968 -0.004171252 -0.007826089 0.3896277 -0.004171252 -0.007163166 0.389092 -0.004171252 -0.006151735 0.3882747 -0.004171252 -0.005001068 0.3876659 -0.004171252 -0.004248976 0.387268 -0.004171252 -0.002572894 0.3867611 -0.004171252 -0.002188384 0.3866448 -0.004171252 -4.66255e-5 0.3864285 -0.004171252 -4.05781e-7 0.3864328 -0.004171252 0.002096891 0.3866269 -0.004171252 0.002571702 0.3867662 -0.004171252 0.004162549 0.3872328 -0.004171252 0.00500071 0.3876674 -0.004171252 0.006073653 0.3882237 -0.004171252 0.007164895 0.3890905 -0.004171252 0.007759273 0.3895627 -0.004177093 -0.009677708 0.3920074 -0.004422128 -0.009931445 0.3921699 -0.004422724 -0.009931683 0.3921703 -0.0047369 -0.01005458 0.3923613 -0.004422724 0.009931683 0.3921703 -0.004424035 0.00993216 0.392171 -0.0047369 0.01005458 0.3923613 -0.004422128 0.009931445 0.3921699 -0.004177093 0.009677708 0.3920074 0.0100333 0.01626104 0.399245 0.0100823 0.01620292 0.3991944 0.0107795 0.01620292 0.3999185 0.01151996 0.01555192 0.4190171 0.01048129 0.01646387 0.4191727 0.01036483 0.01658254 0.4190542 0.01086169 0.01658254 0.418479 0.01081621 0.01595062 0.4195274 0.01067316 0.0161885 0.4193743 0.01121777 0.01620292 0.4187701 0.01054912 0.01639473 0.4192416 0.01092284 0.01554578 0.4196835 0.0108307 0.01589554 0.4195486 0.01094257 0.01517587 0.4197953 0.01095306 0.0153867 0.4197402 0.01095491 0.01542413 0.4197304 0.01285409 0.01555192 0.4170942 0.01387023 0.01555192 0.414986 0.01454317 0.01555192 0.4127444 0.01438134 0.01555192 0.4057831 0.01480197 0.01555192 0.4080854 0.01485633 0.01555192 0.4104251 0.01360493 0.01555192 0.4035753 0.01106989 0.01555192 0.3996577 0.01249194 0.01555192 0.4015165 0.01037693 0.01536446 0.3988903 0.01035392 0.01555192 0.3989141 0.01023596 0.01583456 0.3990358 0.009762287 0.01658254 0.3995247 0.01043736 0.01658254 0.4002258 0.01119035 0.01658254 0.4012101 0.01216423 0.01620292 0.4017286 0.01177811 0.01658254 0.4019784 0.01324808 0.01620292 0.4037333 0.01400411 0.01620292 0.4058833 0.01291352 0.01658254 0.404164 0.01282751 0.01658254 0.4039195 0.01441365 0.01620292 0.4081251 0.01382678 0.01658254 0.4074639 0.01355957 0.01658254 0.4060012 0.01393961 0.01658254 0.41088 0.01400738 0.01658254 0.410378 0.01446664 0.01620292 0.4104034 0.01402896 0.01658254 0.4096 0.01395612 0.01658254 0.4081719 0.0137121 0.01658254 0.4125648 0.0141617 0.01620292 0.4126619 0.01321339 0.01658254 0.414226 0.01350635 0.01620292 0.4148446 0.01307761 0.01658254 0.4146782 0.01251691 0.01620292 0.4168977 0.01211959 0.01658254 0.416666 0.01168966 0.01658254 0.4172856 -0.00307548 0.0162 0.4211993 -0.002818167 0.0162 0.4212503 -0.002894699 0.01618349 0.4215692 0.009045422 0.01595002 0.4191295 0.009053349 0.01594555 0.4191374 0.008419275 0.01596713 0.4197128 -0.009456157 0.01573884 0.4193719 -0.00913608 0.0159499 0.4190589 -0.008507966 0.01596713 0.4196383 -0.009128332 0.01595503 0.4190513 -0.008987188 0.01604807 0.4189133 -0.008728265 0.01611852 0.4186599 -0.007961988 0.01618349 0.4189941 -0.008536219 0.01617074 0.4184721 -0.00845164 0.01619374 0.4183893 -0.009880304 0.01524913 0.4197866 -0.009825229 0.01531267 0.4197328 -0.00901407 0.01548701 0.4202353 -0.009690582 0.01546818 0.4196011 -0.009500801 0.01568734 0.4194155 -0.01019549 0.01463907 0.4200955 -0.01012569 0.0147742 0.4200271 -0.009406089 0.01478379 0.4206979 -0.0100845 0.01485383 0.4199867 -0.009630441 0.01398754 0.4209626 -0.01040786 0.01378327 0.4203038 -0.01039677 0.01391249 0.4202929 -0.01037687 0.01398426 0.4202734 -0.0102787 0.01433873 0.4201771 -0.007757484 0.01398754 0.4223151 -0.005697965 0.01398754 0.4233618 -0.003501355 0.01398754 0.4240774 -0.001220464 0.01398754 0.4244447 0.001089692 0.01398754 0.4244549 0.003373682 0.01398754 0.4241077 0.00557655 0.01398754 0.4234114 0.007645249 0.01398754 0.422383 0.009530007 0.01398754 0.421047 0.01030582 0.01378035 0.4203876 0.01035714 0.01342362 0.4204388 0.01003563 0.01477855 0.4201174 0.01018899 0.01433914 0.4202708 0.0102511 0.0141611 0.4203329 0.01027655 0.01398408 0.4203583 0.00967592 0.01540988 0.419758 0.00973457 0.01531332 0.4198166 0.008920073 0.01548701 0.4203143 0.009267985 0.01582461 0.4193513 0.009411215 0.015679 0.419494 0.009609222 0.01547765 0.4196915 0.007878959 0.01618349 0.4190638 0.008458733 0.01616019 0.4185453 0.008651256 0.01612555 0.4187368 0.008772671 0.01610368 0.4188576 0.008237898 0.01619994 0.4183256 0.007662415 0.01619994 0.4188037 0.007066667 0.0162 0.4192987 0.006320714 0.01618349 0.4201683 0.006148815 0.0162 0.419882 0.002789199 0.01618349 0.4215943 0.002715647 0.0162 0.4212754 0.002954483 0.0162 0.4212307 0.004610419 0.01618349 0.4210187 0.004402816 0.0162 0.4207631 0.004490315 0.0162 0.420722 0.005780756 0.0162 0.4201159 0.001457035 0.0162 0.4215113 9.00934e-4 0.01618349 0.4218813 8.76616e-4 0.0162 0.4215451 -6.27601e-5 0.0162 0.4215998 -0.001009047 0.01618349 0.4218729 -9.81717e-4 0.0162 0.4215367 -0.001581072 0.0162 0.4214955 -0.004519343 0.0162 0.4207165 -0.004710793 0.01618349 0.4209776 -0.004588544 0.0162 0.420683 -0.005890011 0.0162 0.4200551 -0.006413519 0.01618349 0.4201123 -0.006239414 0.0162 0.4198279 -0.007166922 0.0162 0.4192248 -0.007743597 0.01619994 0.4187363 -0.008313179 0.01619994 0.418254 -0.006853342 0.01596713 0.4208332 -0.00503385 0.01596713 0.4217578 -0.003093242 0.01596713 0.42239 -0.001078188 0.01596713 0.4227145 9.62716e-4 0.01596713 0.4227235 0.00298047 0.01596713 0.4224168 0.004926562 0.01596713 0.4218017 0.006754159 0.01596713 0.4208931 -0.007260978 0.01548701 0.4215013 -0.005333244 0.01548701 0.422481 -0.003277242 0.01548701 0.4231508 -0.001142323 0.01548701 0.4234946 0.001019954 0.01548701 0.4235041 0.003157794 0.01548701 0.4231792 0.005219638 0.01548701 0.4225275 0.007155895 0.01548701 0.4215648 -0.007576823 0.01478379 0.422019 -0.005565226 0.01478379 0.4230412 -0.003419756 0.01478379 0.4237402 -0.001192033 0.01478379 0.4240989 0.0010643 0.01478379 0.4241089 0.003295123 0.01478379 0.4237697 0.005446672 0.01478379 0.4230898 0.00746715 0.01478379 0.4220852 0.00930804 0.01478379 0.4207803 0.01000344 0.0148707 0.4200853 -0.0135709 0.01561182 0.403555 -0.01246237 0.01561182 0.4015129 -0.01211857 0.0162487 0.401736 -0.01453852 0.01561182 0.4126564 -0.01483726 0.01561182 0.4103521 -0.01442801 0.0162487 0.4103313 -0.0111832 0.01658254 0.4011998 -0.01176834 0.01658254 0.4019633 -0.01290124 0.01658254 0.4041345 -0.01354849 0.01658254 0.4059597 -0.01395171 0.0162487 0.4058514 -0.01394629 0.01658254 0.4108094 -0.01372885 0.01658254 0.4124862 -0.0141375 0.0162487 0.4125721 -0.01105195 0.01511305 0.4197193 -0.0116927 0.0148676 0.4189957 -0.01104509 0.01517784 0.4196995 -0.01090788 0.01588565 0.4194468 -0.01098942 0.01570194 0.4195395 -0.01158076 0.01561182 0.4189057 -0.01099938 0.01560842 0.4195681 -0.01102131 0.0154016 0.4196312 -0.01055866 0.01645416 0.4190757 -0.01073998 0.0162456 0.4192582 -0.01126128 0.0162487 0.4186491 -0.01075643 0.0162267 0.4192748 -0.01044702 0.01658254 0.4189633 -0.01093578 0.01658254 0.4183875 -0.01174998 0.01658254 0.417194 -0.01253449 0.0162487 0.4167824 -0.01217222 0.01658254 0.4165748 -0.01350116 0.0162487 0.4147402 -0.01311093 0.01658254 0.4145916 -0.01324325 0.01658254 0.4141407 -0.01436555 0.0162487 0.4080727 -0.01381927 0.01658254 0.4074131 -0.0139504 0.01658254 0.4081168 -0.01402896 0.01658254 0.4096 -0.01401096 0.01658254 0.4103102 -0.01043361 0.01658254 0.4002217 -0.01104891 0.01561182 0.3996686 -0.01115578 0.0148676 0.3995726 -0.01074415 0.0162487 0.3999426 -0.0128901 0.01561182 0.4169862 -0.01388412 0.01561182 0.4148859 -0.01477307 0.01561182 0.4080293 -0.01434749 0.01561182 0.405745 -0.01319652 0.0162487 0.4037218 -0.01281517 0.01658254 0.4038917 -0.01301473 0.0148676 0.4170576 -0.01401835 0.0148676 0.4149371 -0.01467913 0.0148676 0.4126859 -0.01498073 0.0148676 0.4103593 -0.01491588 0.0148676 0.4080142 -0.01448619 0.0148676 0.4057078 -0.01370209 0.0148676 0.4034966 -0.01258283 0.0148676 0.4014347 0.008992314 -0.01472377 0.3961726 0.008988738 -0.01491671 0.3961674 0.009093523 -0.01490473 0.3969294 0.008827507 -0.01630181 0.3959466 0.009774208 -0.01403605 0.3982062 0.008259832 -0.01090973 0.3968915 0.005139529 -0.01014512 0.3925786 0.004786431 -0.01006221 0.3923853 0.005934834 -0.01040756 0.3930703 0.006414651 -0.0106365 0.3934186 0.006212353 -0.01040172 0.3941019 0.005495011 -0.01022863 0.3927732 0.005720734 -0.0103054 0.3929149 0.007430076 -0.01122087 0.3951327 0.007430851 -0.01080703 0.3957915 0.008512139 -0.01201885 0.3967763 0.008821904 -0.01161056 0.3973613 0.009270191 -0.01239496 0.3977519 0.009585618 -0.01321256 0.3980345 0.009848296 -0.01487237 0.3982743 0.009383022 -0.01488924 0.3976513 0.008978426 -0.01546341 0.3961527 0.008975148 -0.01549744 0.3961481 0.008921027 -0.01588493 0.3960714 0.008894622 -0.01600253 0.3960363 0.008813679 -0.01634585 0.3959283 0.008883714 -0.01392805 0.3960194 0.008974492 -0.01455897 0.3961473 0.008987843 -0.01465177 0.3961662 0.008373439 -0.01237457 0.3960983 0.008396804 -0.01266115 0.3953857 0.008490502 -0.01283353 0.3955014 0.008588969 -0.01301479 0.3956232 0.008620858 -0.01309013 0.3956647 0.008915245 -0.01365226 0.3967166 0.008857309 -0.01382088 0.395983 0.008863687 -0.01384067 0.3959916 0.00811249 -0.01215618 0.3950376 0.00816214 -0.01222932 0.3950956 0.0074445 -0.01137602 0.3943182 0.007481932 -0.01141166 0.3943555 0.007568478 -0.01151388 0.3944492 0.006566166 -0.0107088 0.3935285 0.006640911 -0.01075434 0.3935893 0.007410824 -0.01134395 0.3942847 0.008895754 -0.01272183 0.3971538 0.009162724 -0.01344352 0.3974241 0.009321093 -0.01416277 0.397587 0.008641302 -0.01685947 0.3962924 0.00871706 -0.01732993 0.3998894 0.008170068 -0.01817911 0.4016025 0.007953703 -0.01857191 0.4024215 0.007837951 -0.01855516 0.4022194 0.007841289 -0.01855605 0.4022274 0.007797539 -0.01834529 0.4012123 0.007749259 -0.01845806 0.4016593 0.007744848 -0.01846849 0.4017005 0.007799863 -0.01853859 0.4020988 0.007802665 -0.01854217 0.4021191 0.007829129 -0.01855278 0.4021982 0.008124411 -0.01782929 0.3993333 0.008022487 -0.01798528 0.3998907 0.007893621 -0.01817744 0.400583 0.007826745 -0.0182771 0.400942 0.008226633 -0.01767289 0.3987741 0.008330106 -0.01750004 0.3981462 0.008386075 -0.01740038 0.3978653 0.008438885 -0.01730126 0.3975827 0.008494496 -0.01719009 0.3972623 0.008505403 -0.01716822 0.3971994 0.008566677 -0.01703596 0.3968139 0.006390213 -0.01060831 0.3898256 0.00610888 -0.01047784 0.3901749 0.005897164 -0.01028525 0.3898857 0.005094707 -0.01003485 0.3909787 0.005219638 -0.01015102 0.3914514 0.005938947 -0.01039904 0.3903858 0.005807816 -0.01033824 0.3905487 0.00537163 -0.01019936 0.3912181 0.007245182 -0.01115447 0.3888064 0.007245182 -0.01115453 0.3888064 0.006687343 -0.01068967 0.3890796 0.006814002 -0.01087588 0.3894138 0.006937265 -0.01095372 0.3892941 0.007291495 -0.01123619 0.3890373 0.006667912 -0.01059728 0.3889678 0.006817698 -0.0106911 0.3888458 0.007243812 -0.01108485 0.3886843 0.007242679 -0.01103109 0.38859 0.006187796 -0.01029634 0.3893589 0.006161153 -0.01028215 0.3893841 0.005462229 -0.00997138 0.3901244 0.00547415 -0.009975969 0.3901103 0.005821704 -0.01013088 0.3897429 0.004756629 -0.009768843 0.3910581 0.004938304 -0.009820997 0.3908177 0.005389273 -0.009950459 0.3902209 -0.00149995 -0.008786678 0.3606 -0.001434624 -0.008797585 0.3610382 -0.001279056 -0.008820712 0.3613398 -7.47233e-4 -0.00888127 0.361892 -7.91005e-4 -0.008878588 0.3618747 -0.001188576 -0.008834183 0.3615152 2.02058e-4 -0.00891149 0.3620865 6.66068e-4 -0.008887648 0.3619354 5.89589e-7 -0.008910477 0.3620805 -2.91736e-4 -0.008908987 0.3620716 7.11404e-4 -0.008885324 0.3619207 7.45531e-4 -0.008881807 0.3618934 0.00113064 -0.008841753 0.3615858 0.001278221 -0.008820593 0.3613376 0.001405417 -0.008802294 0.3611236 0.00149995 -0.008786678 0.3606 0.001434624 -0.008797585 0.3601619 0.001279056 -0.008820712 0.3598603 0.001188576 -0.008834183 0.3596848 7.91005e-4 -0.008878588 0.3593252 7.47233e-4 -0.00888127 0.359308 6.65968e-4 -0.008886218 0.3592759 2.91736e-4 -0.008908987 0.3591284 -5.89589e-7 -0.008910477 0.3591195 -2.02058e-4 -0.00891149 0.3591135 -7.11404e-4 -0.008885324 0.3592793 -7.45531e-4 -0.008881807 0.3593066 -0.00113064 -0.008841753 0.3596141 -0.001278221 -0.008820593 0.3598623 -0.001405417 -0.008802294 0.3600763 -0.007617413 -0.003524184 0.3547835 -0.00819689 -0.001804232 0.3547835 -0.008589863 -0.001890718 0.3557913 -0.003931403 -0.007415413 0.3547835 -0.005433559 -0.006396889 0.3547835 -0.005694091 -0.006703555 0.3557913 0.001357853 -0.008282542 0.3547835 -4.54396e-4 -0.00838083 0.3547835 -4.7618e-4 -0.008782565 0.3557913 0.006093382 -0.005771934 0.3547835 0.004710078 -0.006946861 0.3547835 0.00493592 -0.007279932 0.3557913 0.008343935 9.07459e-4 0.3547835 0.008343935 -9.07459e-4 0.3547835 0.008743941 -9.50963e-4 0.3557913 0.006093382 0.005771934 0.3547835 0.007191717 0.004327118 0.3547835 0.00753647 0.004534542 0.3557913 0.001357853 0.008282542 0.3547835 0.003106594 0.007797002 0.3547835 0.003255546 0.008170783 0.3557913 -0.005433559 0.006396889 0.3547835 -0.003931403 0.007415413 0.3547835 -0.004119873 0.007770895 0.3557913 -0.004440605 -0.007695555 0.3567569 -0.004175245 -0.007875442 0.3567569 -0.004119873 -0.007770895 0.3557913 0.008496344 -0.002622663 0.3567569 0.008861541 -9.63752e-4 0.3567569 0.007332742 0.004996836 0.3567569 0.006471335 0.00612998 0.3567569 0.006385505 0.006048619 0.3557913 0.003255248 0.008292913 0.3567569 0.001442074 0.008796334 0.3567569 0.001422941 0.008679628 0.3557913 -0.004440605 0.007695555 0.3567569 -0.005770623 0.006793737 0.3567569 -0.005694091 0.006703555 0.3557913 -0.008589863 0.001890718 0.3557913 -0.008705377 0.00191617 0.3567569 -0.00876981 0.001323699 0.3567569 -0.0080899 0.003742754 0.3567569 -0.007982552 0.003693103 0.3557913 -0.008019149 0.003860414 0.3567569 -0.007001996 0.005322813 0.3557913 -0.007096171 0.005394399 0.3567569 -0.006496667 0.006027281 0.3567569 -0.004175245 0.007875442 0.3567569 -0.002384662 0.00858885 0.3567569 -0.002353012 0.008474886 0.3557913 -0.001977801 0.008655548 0.3567569 -4.7618e-4 0.008782565 0.3557913 6.63758e-4 0.008859753 0.3567569 0 0.008913755 0.3567569 -4.82584e-4 0.008900701 0.3567569 0.00493592 0.007279932 0.3557913 0.00500226 0.007377803 0.3567569 0.003299295 0.008280694 0.3567569 0.005526602 0.006932497 0.3567569 0.007637858 0.004595518 0.3567569 0.00844717 0.002846181 0.3567569 0.008335053 0.002808392 0.3557913 0.008496344 0.002622663 0.3567569 0.008743941 9.50963e-4 0.3557913 0.008861541 9.63752e-4 0.3567569 0.008861541 0 0.3567569 0.008335053 -0.002808392 0.3557913 0.00844717 -0.002846181 0.3567569 0.007637858 -0.004595518 0.3567569 0.005526602 -0.006932497 0.3567569 0.006471335 -0.00612998 0.3567569 0.006385505 -0.006048619 0.3557913 0.007332742 -0.004996836 0.3567569 0.00500226 -0.007377803 0.3567569 0.003299295 -0.008280694 0.3567569 0.003255546 -0.008170783 0.3557913 0.003255248 -0.008292913 0.3567569 0.001422941 -0.008679628 0.3557913 -4.82584e-4 -0.008900701 0.3567569 6.63403e-4 -0.008838593 0.3567569 0.001442074 -0.008796334 0.3567569 -0.002353012 -0.008474886 0.3557913 -0.001977801 -0.008655548 0.3567569 -0.002384662 -0.00858885 0.3567569 -0.005770623 -0.006793737 0.3567569 -0.006496667 -0.006027281 0.3567569 -0.007001996 -0.005322813 0.3557913 -0.008705377 -0.00191617 0.3567569 -0.0080899 -0.003742754 0.3567569 -0.007982552 -0.003693103 0.3557913 -0.008019149 -0.003860414 0.3567569 -0.007096171 -0.005394399 0.3567569 -0.008913755 0 0.3567569 -0.00876981 -0.001323699 0.3567569 -0.00819689 0.001804232 0.3547835 -0.007617413 0.003524184 0.3547835 -0.00668168 0.005079269 0.3547835 -0.002245366 0.008087217 0.3547835 0.004710078 0.006946861 0.3547835 0.007953763 0.002679944 0.3547835 0.007953763 -0.002679944 0.3547835 0.007191717 -0.004327118 0.3547835 0.00753647 -0.004534542 0.3557913 0.003106594 -0.007797002 0.3547835 -0.002245366 -0.008087217 0.3547835 -0.00668168 -0.005079269 0.3547835 -0.008795499 0 0.3557913 -0.008393108 0 0.3547835 -4.54396e-4 0.00838083 0.3547835 -7.37776e-4 0.008880198 0.3593215 -9.84303e-4 0.008859276 0.359468 -0.001293599 0.008818924 0.3598543 -0.001320064 0.008815467 0.3598874 -0.001486301 0.008789002 0.3603966 -0.00149995 0.008786678 0.3606 2.02455e-4 0.00891149 0.3591135 6.66068e-4 0.008887648 0.3592645 0 0.008913755 0.3591 -5.23806e-4 0.008898377 0.3591945 7.11698e-4 0.008885324 0.3592794 7.45596e-4 0.008881807 0.3593065 0.001131534 0.008841693 0.3596151 0.0012784 0.008820533 0.3598622 0.001405298 0.008802294 0.3600757 0.00149995 0.008786678 0.3606 -0.001405298 0.008802294 0.3611243 -0.0012784 0.008820533 0.3613378 -0.001131534 0.008841693 0.3615849 -7.45596e-4 0.008881807 0.3618935 -7.11698e-4 0.008885324 0.3619206 -2.02449e-4 0.00891149 0.3620865 0 0.008913755 0.3621 5.23873e-4 0.008898377 0.3620055 6.65916e-4 0.008886277 0.3619211 7.37776e-4 0.008880198 0.3618785 9.84351e-4 0.008859276 0.361732 0.001293599 0.008818924 0.3613457 0.001320064 0.008815467 0.3613126 0.001486301 0.008789002 0.3608033 0.01000708 0.01539218 0.3985096 0.009779572 0.01624763 0.3989372 0.009781897 0.01624423 0.398934 0.009921967 0.0158419 0.3986959 0.009930253 0.01581811 0.3986819 0.009960472 0.01573139 0.3986306 0.009554386 0.01656985 0.3992542 0.0100063 0.01533937 0.3984999 0.009427428 0.0152167 0.3977296 0.009635686 0.01509338 0.3980015 0.00953412 0.01590472 0.3982552 0.009850144 0.01496922 0.3982746 0.009829878 0.0149784 0.3982549 0.009065806 0.01573771 0.3969559 0.00913608 0.01560205 0.3971412 0.00915116 0.01605099 0.3976085 0.008885562 0.01618129 0.3963909 0.008916258 0.01609545 0.3964958 0.008823692 0.01641017 0.3964795 0.008918166 0.01609092 0.3965017 0.009029865 0.0158236 0.3968454 0.009172976 0.01553958 0.3972311 0.009259641 0.01542961 0.3974009 0.009381532 0.015275 0.3976396 0.008724093 0.01663738 0.395846 0.008808076 0.01639842 0.3961234 0.008823573 0.01635444 0.3961794 0.008705556 0.01669025 0.3957846 0.008711278 0.01669245 0.396247 0.008718013 0.01668941 0.3964028 0.00872755 0.01669096 0.3965998 0.008858621 0.01666349 0.397673 0.008854985 0.01666438 0.3976503 0.008765697 0.01668632 0.3970851 0.008734345 0.01669204 0.3967388 0.009182631 0.01660704 0.3986144 0.009009242 0.01663428 0.3982403 0.009004831 0.016635 0.3982309 0.008964538 0.01664251 0.3981026 0.008910775 0.01665312 0.3978846 0.00932306 0.01658499 0.3989174 0.009512901 0.01656991 0.3991957 0.007242679 -0.009158194 0.3867222 0.007242679 -0.009476125 0.3869666 0.007242679 -0.01091343 0.3884478 0.006161153 0.01028203 0.389384 0.006239473 0.01032441 0.3893119 0.007242679 0.009160518 0.3867193 0.006817698 0.01069182 0.3888465 0.007242679 0.01103109 0.38859 0.007242679 0.01086306 0.388388 0.006662726 0.01059335 0.3889712 0.007242679 0.009417593 0.3869147 0.005811274 0.01012605 0.3897539 0.005461752 0.009970247 0.3901236 0.00538516 0.009947538 0.3902235 0.004917502 0.009809136 0.3908336 0.004843413 0.009787201 0.3909303 0.004756212 0.009768068 0.3910577 0.007242679 0.007774472 0.3856658 0.007242679 0.006392657 0.3849022 0.007242679 0.005968034 0.3846675 0.007242679 0.004036307 0.3839408 0.007242679 0.003284513 0.3837767 0.007242679 0.002019762 0.3835008 0.007242679 -1.92588e-7 0.3833596 0.007242679 -3.9085e-5 0.3833569 0.007242679 -0.002097129 0.3835121 0.007242679 -0.003284037 0.3837779 0.007242679 -0.00411117 0.3839631 0.007242679 -0.006038904 0.3847004 0.007242679 -0.006394088 0.3848993 0.007242679 -0.007839798 0.3857087 -0.004938244 0.009820997 0.3908177 -0.004756629 0.009768843 0.3910581 -0.007242679 0.009158372 0.386722 -0.007242679 0.009469866 0.386961 -0.006817698 0.01069134 0.388846 -0.007242679 0.010912 0.388446 -0.007242679 0.01103109 0.38859 -0.006667912 0.0105974 0.3889679 -0.006187856 0.0102964 0.3893589 -0.006161153 0.01028215 0.3893841 -0.005821764 0.01013088 0.3897429 -0.005473792 0.00997579 0.3901108 -0.005462169 0.00997138 0.3901243 -0.005389213 0.009950399 0.3902209 -0.006817758 -0.01069229 0.3888471 -0.007242679 -0.01103109 0.38859 -0.007242679 -0.010912 0.388446 -0.006161093 -0.01028186 0.3893839 -0.00666815 -0.01059883 0.3889694 -0.007242679 -0.009158372 0.386722 -0.007242679 -0.009469866 0.386961 -0.004756152 -0.009767889 0.3910576 -0.005821764 -0.01013064 0.3897428 -0.005461752 -0.009970188 0.3901236 -0.005387365 -0.009948909 0.390222 -0.004937767 -0.009819984 0.3908171 -0.007242679 -0.007827699 0.3857007 -0.007242679 -0.006393611 0.3849002 -0.007242679 -0.006020188 0.3846917 -0.007242679 -0.00408554 0.3839554 -0.007242679 -0.003284156 0.3837777 -0.007242679 -0.002064526 0.3835073 -0.007242679 0 0.3833569 -0.007242679 0.002064526 0.3835073 -0.007242679 0.003284156 0.3837777 -0.007242679 0.00408554 0.3839554 -0.007242679 0.006020188 0.3846917 -0.007242679 0.006393611 0.3849002 -0.007242679 0.007827699 0.3857007 0.0100395 0.01537466 0.4196027 0.01031053 0.01490885 0.4198737 0.008474767 0.01628273 0.4180909 0.008495867 0.01629012 0.41807 0.008924007 0.01621282 0.4184893 0.008942425 0.01707178 0.4176276 0.008948266 0.01719999 0.4176217 0.009496688 0.0171144 0.4181752 0.01051187 0.01437711 0.4200752 0.01039123 0.01553541 0.4194805 0.01068222 0.01503556 0.4197722 0.01071625 0.01577734 0.4194988 0.01032578 0.01622879 0.4191059 0.009561359 0.01710432 0.4182405 0.009398698 0.01676619 0.4181738 0.009945213 0.01694095 0.4186279 0.009880721 0.01656264 0.4186584 0.01001906 0.01687788 0.418703 0.008885443 0.01686179 0.417684 0.008880019 0.01684176 0.4176894 0.009332537 0.01603943 0.4188966 0.009709239 0.01575642 0.4192727 0.00919491 0.0164327 0.4182824 0.009632766 0.01624774 0.4187206 0.01003682 0.01594477 0.4191252 0.008570075 0.01631605 0.4179965 0.008724749 0.01651018 0.4178432 0.008727252 0.01651328 0.4178407 0.008823692 0.01663434 0.4177452 0.009708583 0.01666367 0.3996611 0.009656369 0.01857244 0.414238 0.008923053 0.01857244 0.4154692 0.008677005 0.01857244 0.4158823 0.00802797 0.01857244 0.4166929 0.01066917 0.01857244 0.4105627 0.01066595 0.01857244 0.4105802 0.01032757 0.01857244 0.4124458 0.01007336 0.01857244 0.4131247 0.007976293 0.01857036 0.4024433 0.008014082 0.01853883 0.4024067 0.008018136 0.01853555 0.4024032 0.008564352 0.01857244 0.4031789 0.007973551 0.0185725 0.4024459 0.008473098 0.01811873 0.4018706 0.008621037 0.01798135 0.4016929 0.008027732 0.01852732 0.4023932 0.008090734 0.0184738 0.4023297 0.008019864 0.01853394 0.4024009 0.00868386 0.01857244 0.4033272 0.009661436 0.01857244 0.4049725 0.009842038 0.01857244 0.4054564 0.01033067 0.01857244 0.4067655 0.01054793 0.01857244 0.4079707 0.01067018 0.01857244 0.4086489 0.00965327 0.01674455 0.3997957 0.00965476 0.0167424 0.3997921 0.009660363 0.0167343 0.3997787 0.009158074 0.01739329 0.4008328 0.009397506 0.01708102 0.4003345 0.009635746 0.0167703 0.3998386 0.005915343 0.01648628 0.414986 0.005916953 0.01648992 0.4149841 0.006113111 0.01719999 0.4147604 0.006067335 0.01685345 0.4148141 0.006061851 0.01681166 0.4148205 0.005664348 0.01626628 0.4152482 0.005692422 0.01627397 0.415221 0.00542128 0.0162 0.4154829 -0.002551555 0.0162 0.4171822 -0.005470454 0.0162 0.4154373 -0.004809916 0.0162 0.4159925 0.004756152 0.0162 0.4160326 0.002487897 0.0162 0.4172033 -3.35409e-5 0.0162 0.4175999 -0.006007552 0.01656389 0.4148829 -0.005956888 0.01650583 0.414938 -0.008796453 0.01651108 0.4177662 -0.00840342 0.01620823 0.4181628 -0.005772948 0.01629513 0.4151383 -0.008711278 0.01637536 0.4178521 -0.008796393 0.01651096 0.4177662 -0.005714237 0.01627665 0.4151963 -0.008549809 0.01628768 0.4180151 -0.008565127 0.01629602 0.4179996 -0.008935332 0.01673239 0.417626 -0.008953571 0.01683676 0.4176076 -0.006105661 0.01686191 0.4147685 -0.008957505 0.01685947 0.4176036 -0.006136953 0.01695692 0.414732 -0.00901699 0.01719999 0.4175436 -0.006156146 0.01719999 0.4147089 -0.009472548 0.01676625 0.4180915 -0.009793281 0.01575636 0.4191875 -0.009959101 0.0165627 0.4185717 -0.01002413 0.01694041 0.4185415 -0.01040834 0.01622885 0.4190151 -0.01009786 0.016878 0.4186151 -0.0108025 0.0157774 0.4194045 -0.01077097 0.01503545 0.4196781 -0.01060336 0.01437693 0.4199826 -0.01040017 0.01490873 0.4197829 -0.01012659 0.0153746 0.4195144 -0.009413063 0.01603937 0.418815 -0.009000718 0.01621282 0.4184114 -0.009421706 0.01715952 0.4179446 -0.009568095 0.01710629 0.4180896 -0.01047724 0.01553541 0.419389 -0.01011949 0.01594477 0.419037 -0.009711682 0.01624774 0.4186361 -0.009269714 0.0164327 0.418202 -0.0106737 0.01857244 0.410511 -0.01067101 0.01857244 0.4105263 -0.008015871 0.01853734 0.4024055 -0.007973551 0.01857244 0.4024459 -0.008558571 0.01857244 0.4031713 -0.009151995 0.0173996 0.4008421 -0.008617162 0.01798516 0.4016987 -0.009628474 0.01677948 0.3998529 -0.009390771 0.01708877 0.4003463 -0.008468091 0.01812207 0.4018738 -0.0103442 0.01857244 0.4123848 -0.01009637 0.01857244 0.4130598 -0.009688436 0.01857244 0.4141707 -0.008969128 0.01857244 0.4153993 -0.008727133 0.01857244 0.4158125 -0.008088588 0.01857244 0.4166237 -0.009653687 0.01857244 0.4049562 -0.008679926 0.01857244 0.4033218 -0.01066648 0.01857244 0.4086084 -0.01054227 0.01857244 0.4079318 -0.01032286 0.01857244 0.4067372 -0.009833097 0.01857244 0.4054337 0.002598047 0.008499979 0.3741 0.002999961 0.008499979 0.3756 0.002598047 0.008499979 0.3771 0.00149995 0.008499979 0.3781981 -0.002598047 0.008499979 0.3741 0 0.008499979 0.3786 -0.00149995 0.008499979 0.3730019 0 0.008499979 0.3726 -0.00149995 0.008499979 0.3781981 -0.002598047 0.008499979 0.3771 -0.002999961 0.008499979 0.3756 0.00149995 0.008499979 0.3730019 -0.008714675 0.01733553 0.3999033 -0.008168458 0.01818197 0.4016085 -0.007797241 0.0183469 0.4012201 -0.007751643 0.01845729 0.4016601 -0.007744431 0.01847481 0.4017299 -0.007798135 0.01854068 0.4021006 -0.007803201 0.01854681 0.4021354 -0.007822811 0.01855379 0.4021911 -0.007825672 0.01855486 0.402199 -0.007833063 0.01855665 0.4022164 -0.00783658 0.01855719 0.4022231 -0.007904469 0.01856815 0.4023517 -0.008123219 0.0178315 0.3993487 -0.008022129 0.01798641 0.3999041 -0.007894277 0.01817649 0.4005831 -0.007825314 0.01827895 0.4009492 -0.008468568 0.01720249 0.3972807 -0.008224666 0.01767605 0.3987915 -0.008330106 0.01749998 0.398146 -0.008700668 0.01670396 0.3958306 -0.009773492 0.01403129 0.3982055 -0.009584367 0.01320821 0.3980333 -0.009161651 0.01343971 0.397423 -0.008771717 0.01649343 0.3958657 -0.004761219 0.01005828 0.392373 -0.004785537 0.01006209 0.3923848 -0.005142927 0.0101369 0.3925735 -0.006194531 0.01050734 0.3932422 -0.006416678 0.01063019 0.393415 -0.006210625 0.01040083 0.3941006 -0.005939364 0.01039862 0.393066 -0.005262494 0.01016199 0.3926367 -0.005719304 0.01030486 0.392914 -0.007428109 0.01121902 0.3951309 -0.008257389 0.01090705 0.3968895 -0.008510231 0.01201593 0.3967745 -0.007428586 0.01080513 0.3957897 -0.008819699 0.01160728 0.3973594 -0.009268403 0.01239109 0.3977503 -0.009848177 0.0148673 0.3982742 -0.009382963 0.01488488 0.3976513 -0.009093463 0.01490092 0.3969294 -0.008975505 0.01549392 0.3961487 -0.008998751 0.01510781 0.3961819 -0.008995473 0.01491427 0.3961772 -0.008896052 0.0159986 0.396037 -0.008918225 0.01590019 0.3960677 -0.008828938 0.01629656 0.3959438 -0.008814513 0.01634609 0.3959242 -0.008914351 0.01364886 0.3967156 -0.008854746 0.01381903 0.3959798 -0.008883059 0.01392501 0.3960186 -0.008953332 0.01431912 0.3961173 -0.008976459 0.01455843 0.3961502 -0.008992135 0.01472055 0.3961725 -0.008409738 0.01264321 0.3953953 -0.008497655 0.01282924 0.3955076 -0.008371829 0.01237177 0.3960967 -0.008619725 0.01308739 0.3956633 -0.008768916 0.01349759 0.3958619 -0.007480025 0.01140981 0.3943538 -0.007570743 0.01150763 0.3944487 -0.007841527 0.01179951 0.3947324 -0.008160531 0.01222687 0.3950938 -0.006639122 0.01075321 0.393588 -0.007079064 0.01106047 0.3939694 -0.00744313 0.01137763 0.3943184 -0.008894264 0.01271843 0.3971523 -0.009320497 0.01415866 0.3975864 -0.006390213 0.01060831 0.3898256 -0.00610888 0.01047784 0.3901749 -0.005898118 0.01028668 0.3898873 -0.005219638 0.01015102 0.3914514 -0.00537163 0.01019936 0.3912181 -0.005096137 0.01003617 0.39098 -0.005807816 0.01033824 0.3905487 -0.005938947 0.01039904 0.3903858 -0.007245182 0.01115447 0.3888064 -0.007245182 0.01115453 0.3888064 -0.006687819 0.0106911 0.3890814 -0.006814002 0.01087588 0.3894138 -0.006937265 0.01095372 0.3892941 -0.007291495 0.01123619 0.3890373 -0.007243812 0.01108604 0.3886863 -0.008046686 0.01198512 0.3881176 -0.008133351 0.01211756 0.3880556 -0.008149862 0.01215392 0.3881476 -0.008539795 0.01288861 0.3878604 -0.008541107 0.01290768 0.3879804 -0.00853604 0.01283085 0.387757 -0.008502244 0.01282715 0.388028 -0.008535385 0.01282 0.3877446 -0.008463621 0.01274704 0.3880754 -0.008534967 0.01281261 0.3877362 -0.008419156 0.01256889 0.3878449 -0.008382797 0.01249873 0.3878772 -0.007691025 0.01158004 0.388515 -0.007826507 0.01164871 0.3882751 -0.007683992 0.01149797 0.3883519 -0.008159875 0.01226192 0.3883722 -0.007975816 0.01196801 0.388552 -0.007711112 0.01168495 0.3887397 -0.007432639 0.01138716 0.3889371 -0.005897164 -0.01028525 0.3898857 -0.005219638 -0.01015102 0.3914514 -0.00537163 -0.01019936 0.3912181 -0.005094707 -0.01003485 0.3909787 -0.006937265 -0.01095372 0.3892941 -0.007291495 -0.01123619 0.3890373 -0.007262229 -0.01113796 0.3888114 -0.005938947 -0.01039904 0.3903858 -0.00610888 -0.01047784 0.3901749 -0.006390213 -0.01060831 0.3898256 -0.006687343 -0.01068967 0.3890796 -0.006814002 -0.01087588 0.3894138 -0.005807816 -0.01033824 0.3905487 -0.007245719 -0.01108241 0.3886838 -0.00723946 -0.01106137 0.3886355 -0.006210565 -0.01040077 0.3941007 -0.007428646 -0.01080513 0.3957898 -0.009773492 -0.01403129 0.3982056 -0.004761219 -0.01005828 0.392373 -0.004785537 -0.01006209 0.3923848 -0.005142927 -0.0101369 0.3925735 -0.005262553 -0.01016199 0.3926367 -0.005719304 -0.01030486 0.392914 -0.005939364 -0.01039862 0.393066 -0.006194531 -0.01050734 0.3932422 -0.007570743 -0.01150763 0.3944487 -0.007480084 -0.01140987 0.3943537 -0.00742805 -0.01121896 0.3951311 -0.00744313 -0.01137763 0.3943183 -0.007079064 -0.01106047 0.3939694 -0.006639122 -0.01075321 0.393588 -0.006416678 -0.01063019 0.393415 -0.008497655 -0.01282924 0.3955076 -0.008409738 -0.01264321 0.3953953 -0.008371829 -0.01237177 0.3960968 -0.008160531 -0.01222693 0.3950938 -0.007841527 -0.01179951 0.3947324 -0.008883059 -0.01392501 0.3960186 -0.008854746 -0.01381903 0.3959798 -0.008914351 -0.01364886 0.3967157 -0.008768916 -0.01349759 0.3958619 -0.008619725 -0.01308739 0.3956633 -0.009093463 -0.01490092 0.3969295 -0.008992135 -0.01472055 0.3961725 -0.008976459 -0.01455843 0.3961502 -0.008953332 -0.01431912 0.3961172 -0.008975505 -0.01549392 0.3961487 -0.008998751 -0.01510781 0.3961818 -0.008995473 -0.01491427 0.3961772 -0.008771717 -0.01649343 0.3958657 -0.008814513 -0.01634609 0.3959241 -0.008828938 -0.01629656 0.3959438 -0.008896052 -0.0159986 0.3960369 -0.009383022 -0.01488488 0.3976513 -0.008918225 -0.01590019 0.3960677 -0.009848237 -0.0148673 0.3982742 -0.009584367 -0.01320821 0.3980333 -0.009268403 -0.01239109 0.3977503 -0.008819699 -0.01160728 0.3973594 -0.008257389 -0.01090705 0.3968895 -0.008510291 -0.01201587 0.3967745 -0.008894264 -0.01271837 0.3971524 -0.009320557 -0.01415866 0.3975865 -0.009161651 -0.01343971 0.397423 -0.008022189 -0.01798635 0.3999043 -0.008123159 -0.01783162 0.3993486 -0.008714675 -0.01733553 0.3999033 -0.008224487 -0.01767641 0.398791 -0.008469998 -0.01720219 0.3972811 -0.008330106 -0.01749998 0.398146 -0.008345484 -0.01747316 0.3980707 -0.007894217 -0.01817649 0.4005831 -0.007825195 -0.01827901 0.400949 -0.008168458 -0.01818197 0.4016085 -0.0077973 -0.01834696 0.4012202 -0.007838487 -0.01855635 0.4022203 -0.00782597 -0.01855486 0.4021995 -0.007808327 -0.01853781 0.4020992 -0.007744252 -0.018476 0.4017353 -0.007752001 -0.01845717 0.4016602 -0.006156146 -0.01899999 0.4147089 -0.006989419 -0.01899999 0.4155346 -0.007526576 -0.01890367 0.4160668 -0.007555067 -0.01888763 0.416095 -0.008027493 -0.01862204 0.4165631 0.004849314 -0.01899999 0.4159627 0.004752039 -0.01899999 0.4160264 -0.005290508 -0.01899999 0.415601 -0.004795432 -0.01899999 0.4159733 0.006113111 -0.01899999 0.4147604 0.00577563 -0.01899999 0.4151356 -0.004296183 -0.01899999 0.4163486 -0.003199219 -0.01899999 0.4169325 -3.2824e-5 -0.01899999 0.4175797 -9.05239e-4 -0.01899999 0.4175488 -0.002025663 -0.01899999 0.4173393 -0.002543807 -0.01899999 0.4171597 3.37973e-4 -0.01899999 0.4175929 0.001571297 -0.01899999 0.4174442 0.003898084 -0.01899999 0.4165862 0.002767741 -0.01899999 0.4171061 0.002483189 -0.01899999 0.4171865 0.007536947 -0.01887774 0.4161974 0.00750333 -0.01888543 0.4161635 0.007006585 -0.01899844 0.4156621 0.006938755 -0.01899999 0.4155937 0.006871104 -0.018992 0.4034351 0.006824731 -0.01899993 0.4034767 0.007421076 -0.01899999 0.40424 0.007408082 -0.01899999 0.4149632 0.008986949 -0.01889109 0.4139165 0.00825268 -0.01899999 0.4135631 0.008075416 -0.01889109 0.4154468 0.007733285 -0.01899999 0.4145262 0.009090244 -0.01899999 0.4107996 0.008834898 -0.01899999 0.4120348 0.009611606 -0.01889109 0.4122485 0.008820772 -0.01899999 0.4121033 0.008365213 -0.01899999 0.4133545 0.009112358 -0.01899999 0.4104229 0.009929478 -0.01889109 0.410496 0.009168148 -0.01899999 0.4094713 0.009930431 -0.01889109 0.4087148 0.008824527 -0.01899999 0.4071781 0.009053051 -0.01899999 0.408146 0.009108781 -0.01899999 0.408788 0.007458746 -0.01886433 0.4029078 0.007419109 -0.01888555 0.4029434 0.008081853 -0.01889109 0.4037621 0.007383823 -0.01890438 0.4029751 0.00874722 -0.01899999 0.4068506 0.009614467 -0.01889109 0.406962 0.008256793 -0.01899999 0.4056128 0.008991658 -0.01889109 0.4052933 0.007592439 -0.01899999 0.4044593 0.007904648 -0.01862579 0.4025077 0.007193326 -0.01885813 0.402425 0.007290065 -0.0186215 0.4006474 0.007588326 -0.01837158 0.3994045 0.007853865 -0.01808023 0.3981461 0.007110714 -0.01880896 0.4018594 0.007166445 -0.01872724 0.4012595 0.006364703 -0.01898771 0.4020956 0.00638169 -0.01899999 0.4028403 0.006497859 -0.01899755 0.4028007 0.006393194 -0.01899999 0.4028568 0.006411314 -0.01896101 0.4013987 0.006057798 -0.01899999 0.4020127 0.006119966 -0.01899999 0.4021715 0.005830645 -0.01899999 0.4005389 0.00584656 -0.01899999 0.4008039 0.006547152 -0.0189144 0.4007278 0.005853593 -0.01899999 0.4009214 0.005958497 -0.01899999 0.4014821 0.005740463 -0.01899999 0.3990345 0.005766332 -0.01899999 0.3994661 0.00611782 -0.01897758 0.3994544 0.006894171 -0.01877379 0.3994281 0.00770992 -0.01825565 0.398146 0.005731999 -0.01899999 0.398146 0.006496429 -0.01887124 0.398146 0.006714344 -0.01883459 0.398146 0.007214844 -0.01854354 0.398146 0.007699251 -0.01824164 0.3937538 0.007841229 -0.01813334 0.3937538 0.007942557 -0.01800382 0.3937538 0.008309721 -0.01753479 0.3937538 0.008330106 -0.01749998 0.3937538 0.005731999 -0.01899999 0.3937538 0.006382584 -0.01892858 0.3937487 0.007232129 -0.01859802 0.3937538 0.007202327 -0.01861494 0.3937618 0.007024466 -0.01870721 0.3937773 0.006708085 -0.01881635 0.3937632 0.006505131 -0.01888632 0.3937541 -0.007447123 -0.01887524 0.4029182 -0.006861805 -0.01899325 0.4034435 -0.007417261 -0.0188924 0.4029451 -0.008074343 -0.0188924 0.4037598 -0.008980154 -0.0188924 0.4052802 -0.00825864 -0.01899999 0.4056277 -0.006824731 -0.01899999 0.4034767 -0.007414042 -0.01899999 0.4042382 -0.007639169 -0.01899999 0.404529 -0.009602665 -0.0188924 0.406937 -0.008772075 -0.01899999 0.406931 -0.008293032 -0.01899999 0.4056887 -0.009922325 -0.0188924 0.4086776 -0.009066045 -0.01899999 0.4082295 -0.008822262 -0.01899999 0.4071527 -0.009113132 -0.01899999 0.4103782 -0.009168922 -0.01899999 0.4095562 -0.009106636 -0.01899999 0.4087531 -0.0090788 -0.01899999 0.4108833 -0.009929001 -0.0188924 0.4104474 -0.008841395 -0.01899999 0.4119808 -0.009622514 -0.0188924 0.4121904 -0.008797407 -0.01899999 0.4121841 -0.008330464 -0.01899999 0.413431 -0.008118212 -0.0188924 0.4153791 -0.00828731 -0.01899999 0.4135093 -0.00901252 -0.0188924 0.4138518 -0.007687926 -0.01899999 0.4145967 -0.007456421 -0.01899999 0.4149075 0.008377611 0.01248884 0.3878815 0.008152067 0.01215708 0.3881456 0.008422434 0.0125752 0.3878418 0.008535385 0.01282 0.3877446 0.008534967 0.01281261 0.3877362 0.008496284 0.01283067 0.388027 0.008541107 0.01290768 0.3879804 0.008539676 0.01288855 0.3878611 0.008165478 0.01226276 0.3883708 0.00853604 0.01283091 0.3877571 0.007262229 0.01113796 0.3888114 0.007692396 0.01158154 0.388514 0.007245957 0.0110833 0.388686 0.007685303 0.01149964 0.3883512 0.00723946 0.01106137 0.3886355 0.008136212 0.0121206 0.388054 0.008047223 0.01198476 0.3881176 0.007828712 0.01165145 0.3882737 0.007291495 0.01123619 0.3890373 0.007443904 0.01137673 0.3889403 0.007484972 0.01141458 0.3889142 0.007716119 0.0116828 0.3887398 0.008060276 0.01208215 0.3884801 0.005219638 0.01015102 0.3914514 0.005358338 0.01019519 0.3912385 0.005082309 0.01003313 0.3910016 0.006683111 0.01068812 0.3890854 0.006937265 0.01095372 0.3892941 0.005938947 0.01039904 0.3903858 0.006100118 0.01047378 0.3901857 0.005888521 0.01028281 0.3898988 0.006390213 0.01060831 0.3898256 0.00680989 0.01087325 0.3894178 0.005807816 0.01033824 0.3905487 0.009321093 0.01416277 0.397587 0.009383022 0.01488924 0.3976513 0.009093523 0.01490473 0.3969294 0.007430851 0.01080703 0.3957915 0.006640911 0.01075434 0.3935893 0.006411314 0.01064074 0.3934199 0.006212353 0.01040166 0.3941019 0.004907488 0.0100829 0.3924455 0.00480163 0.01006466 0.3923926 0.004788339 0.01006251 0.3923861 0.004786431 0.01006221 0.3923853 0.005138456 0.01014608 0.3925788 0.005720734 0.0103054 0.3929149 0.005773901 0.01032525 0.3929496 0.005935728 0.01040536 0.393069 0.007430076 0.01122087 0.3951327 0.007575094 0.01150667 0.3944509 0.007564544 0.01149374 0.3944393 0.007481932 0.01141166 0.3943555 0.007441639 0.01137965 0.3943185 0.006710886 0.01079863 0.3936474 0.00816214 0.01222932 0.3950956 0.008373439 0.01237452 0.3960984 0.008222818 0.01232272 0.3951675 0.008620858 0.01309013 0.3956648 0.008488237 0.01283442 0.3954991 0.008397698 0.0126599 0.3953859 0.008970797 0.01455932 0.3961422 0.008895158 0.01398164 0.3960354 0.008915245 0.01365226 0.3967166 0.008993685 0.01474982 0.3961746 0.008992314 0.01472377 0.3961726 0.008883714 0.01392805 0.3960195 0.008852362 0.01382482 0.395977 0.008654415 0.01317352 0.3957088 0.008894681 0.01600253 0.3960363 0.008920848 0.01588588 0.3960713 0.008951783 0.01569259 0.3961148 0.008975148 0.01549744 0.3961481 0.008989572 0.01491659 0.3961687 0.008827507 0.01630181 0.3959466 0.008813679 0.01634585 0.3959283 0.009848296 0.01487237 0.3982743 0.009774208 0.01403605 0.3982062 0.009585678 0.01321256 0.3980345 0.009270191 0.01239496 0.3977519 0.008821904 0.01161056 0.3973613 0.008259832 0.01090973 0.3968915 0.008512139 0.01201885 0.3967763 0.009162724 0.01344352 0.3974241 0.008895754 0.01272183 0.3971538 0.00722754 -0.01859003 0.3935193 0.007160544 -0.01862835 0.3935298 0.006536424 -0.01888138 0.3936277 0.00652486 -0.01888597 0.3936295 0.00648868 -0.01890057 0.3936352 0.006910383 -0.01873081 0.393569 0.006638646 -0.01884019 0.3936116 0.007150053 -0.01863431 0.3935315 -0.000999987 -0.01719999 0.4016627 -0.000999987 -0.01899999 0.4016627 0.000999987 -0.01899999 0.4016627 9.26865e-4 -0.01687353 0.401654 5.8614e-4 -0.01655209 0.4016215 0.000999987 -0.01719999 0.4016627 9.04651e-4 -0.01677435 0.4016513 6.6699e-4 -0.0164678 0.4016283 6.36592e-4 -0.01642858 0.4016253 2.46943e-4 -0.01623082 0.4016038 2.44328e-4 -0.0162307 0.4016038 -1.88727e-4 -0.0162177 0.4016022 -6.62459e-4 -0.01647394 0.4016286 -8.32036e-4 -0.01664513 0.4016434 -9.27632e-4 -0.01687639 0.4016543 -2.40617e-4 -0.01623928 0.4016047 -5.6234e-4 -0.01637285 0.4016198 -9.81112e-4 -0.0170058 0.4016604 0 -0.01619911 0.3805859 0 -0.01609033 0.3798697 0 -0.01608961 0.379865 0 -0.01608502 0.3798347 0 -0.01619994 0.380657 2.37274e-4 -0.01625877 0.380657 4.67199e-4 -0.01631581 0.380657 6.55144e-4 -0.01648372 0.380657 -2.37143e-4 -0.01625913 0.380657 -4.6981e-4 -0.01631718 0.380657 -6.55332e-4 -0.01648342 0.380657 0.006404817 -0.01838409 0.3892537 0.00688976 -0.01838409 0.390641 0.007550239 -0.01764124 0.3904404 0.002610623 -0.01899999 0.3865885 0.002688646 -0.01899999 0.3866778 0.003342032 -0.01885432 0.3860189 0.005708158 -0.01899999 0.3936044 0.00549364 -0.01899999 0.3924704 0.005729079 -0.01899999 0.3937351 0.005175232 -0.01899993 0.3912273 0.006030857 -0.01885432 0.3909018 0.005154371 -0.01899993 0.3911681 0.005571186 -0.01885432 0.3895866 0.004700541 -0.01899999 0.389881 0.004988789 -0.01885432 0.3883152 0.004163503 -0.01899999 0.3887475 0.004258096 -0.01885432 0.3871117 0.003375351 -0.01899999 0.3874636 0.00349301 -0.01899999 0.3876501 0.004097819 -0.01899999 0.3886089 0.00279951 -0.01885432 0.3855378 0.001823604 -0.01899999 0.3859727 0.002193391 -0.01885432 0.3851208 0.001719892 -0.01899999 0.3859236 0.001522004 -0.01885432 0.3847905 0.001174271 -0.01899999 0.385665 0.000999987 -0.01899999 0.3855825 0.001000046 -0.01899611 0.3854225 0.001000404 -0.01886838 0.3846668 0.001000344 -0.01884949 0.3846232 0.003973662 -0.01838409 0.3853812 0.004991829 -0.01838409 0.3865945 0.005783736 -0.01838409 0.3878985 0.007045805 -0.01764124 0.3889977 0.007933855 -0.01764124 0.3918977 0.008036792 -0.01784807 0.3933924 0.008202373 -0.01763296 0.3933664 0.008280694 -0.01753121 0.3933541 0.008402109 -0.01724815 0.3933351 0.008577227 -0.01683992 0.3933076 0.007516443 -0.01836496 0.393474 0.007599771 -0.01830011 0.3934609 0.007260441 -0.01838409 0.3920493 0.007822394 -0.01812666 0.393426 0.007887721 -0.01804178 0.3934158 0.007355153 -0.01849061 0.3934993 -10e-4 -0.01884758 0.3846244 -0.000999987 -0.01899999 0.3855825 -0.000999987 -0.01899737 0.385452 -0.000999987 -0.01887404 0.3846859 -0.004833281 -0.01899999 0.3902158 -0.004706919 -0.01899999 0.3899324 -0.005571246 -0.01885437 0.3895867 -0.007045924 -0.01764124 0.3889979 -0.007933855 -0.01764124 0.3918978 -0.008360326 -0.01722884 0.3933416 -0.008379042 -0.01719218 0.3933387 -0.007550299 -0.01764124 0.3904405 -0.006404876 -0.01838415 0.3892539 -0.005783796 -0.01838415 0.3878986 -0.004991829 -0.01838415 0.3865947 -0.003973722 -0.01838415 0.3853814 -0.00219351 -0.01885437 0.3851209 -0.00279951 -0.01885437 0.3855378 -0.001522123 -0.01885437 0.3847905 -0.001180589 -0.01899999 0.3856527 -0.003342092 -0.01885437 0.3860192 -0.004258155 -0.01885437 0.3871119 -0.00350058 -0.01899999 0.3876463 -0.002839028 -0.01899999 0.3868183 -0.002685904 -0.01899999 0.3866829 -0.002068281 -0.01899999 0.3861365 -0.001714587 -0.01899999 0.3859309 -0.001347601 -0.01899999 0.3857176 -0.004988789 -0.01885437 0.3883154 -0.004219412 -0.01899999 0.388839 -0.004165172 -0.01899999 0.3887476 -0.003541827 -0.01899999 0.3876979 -0.006981492 -0.01872032 0.3935579 -0.00663197 -0.01879858 0.3936127 -0.006030857 -0.01885437 0.3909019 -0.006418049 -0.01884645 0.3936462 -0.006292521 -0.01887452 0.3936659 -0.005138218 -0.01899999 0.3911733 -0.00531727 -0.01899999 0.3917353 -0.005731999 -0.01899999 0.3937538 -0.008162736 -0.01761496 0.3933726 -0.008002579 -0.01792812 0.3933978 -0.007883548 -0.01804369 0.3934164 -0.007541239 -0.01837617 0.3934701 -0.007260382 -0.01838415 0.3920494 -0.00688976 -0.01838415 0.3906411 -0.00753057 -0.01838356 0.3934718 -0.007518827 -0.01839172 0.3934736 -0.00734353 -0.01851338 0.3935011 -0.007269918 -0.01856446 0.3935126 -0.007229447 -0.01858633 0.393519 -0.007121682 -0.01864457 0.3935359 -0.00700283 -0.01870882 0.3935545 -0.006017327 -0.01899999 0.4018589 -0.006127893 -0.01899999 0.4021692 -0.006333708 -0.01899999 0.4027469 -0.006401062 -0.01899999 0.4028515 -0.006741702 -0.01899999 0.4033803 -0.00573498 -0.01899999 0.3986881 -0.005768895 -0.01899999 0.3994662 -0.005815386 -0.01899999 0.4005333 -0.005816996 -0.01899999 0.4005704 -0.005853056 -0.01899999 0.4008023 -0.005958914 -0.01899999 0.401483 -0.005731999 -0.01899999 0.398146 -0.006486892 -0.01899802 0.4028067 -0.006706714 -0.01881563 0.398146 -0.007202029 -0.01861518 0.398146 -0.006882548 -0.01877856 0.3994285 -0.006111681 -0.01897829 0.3994547 -0.00649476 -0.0189014 0.398146 -0.006495237 -0.01890116 0.398146 -0.006399333 -0.01896297 0.401401 -0.006534993 -0.01891738 0.4007292 -0.006352841 -0.01898884 0.4020993 -0.007177889 -0.01886367 0.4024334 -0.007094264 -0.01881539 0.4018647 -0.007273972 -0.01863044 0.4006492 -0.007150053 -0.01873487 0.4012625 -0.007573723 -0.01838284 0.3994051 -0.007701516 -0.01824432 0.398146 -0.007810175 -0.01816362 0.398146 -0.007856547 -0.01810628 0.398146 -0.008283495 -0.017578 0.398146 0.007908344 -0.01804119 0.3934422 0.008561432 -0.01693242 0.3934002 0.008437931 -0.01723539 0.393589 0.008811235 -0.01627957 0.3946586 0.008714616 -0.01666492 0.3943856 0.008795797 -0.01634126 0.3946149 0.008942365 -0.01575666 0.3950292 0.008463621 -0.01274704 0.3880754 0.008502304 -0.01282715 0.388028 0.008966386 -0.0145592 0.3939676 0.008541107 -0.01290768 0.3879804 0.008772492 -0.01350921 0.3901718 0.008858919 -0.01388251 0.3915246 0.008886992 -0.01400387 0.3919646 0.008942186 -0.01424235 0.3928288 0.007975816 -0.01196801 0.388552 0.008161902 -0.0122652 0.3883702 0.007432699 -0.01138722 0.3889371 0.007712483 -0.01168644 0.3887387 0.008051276 -0.0119825 0.3881182 0.008141934 -0.01211738 0.3880548 0.008152067 -0.01215708 0.3881456 0.008534967 -0.01281261 0.3877362 0.008535385 -0.01282 0.3877446 0.008422434 -0.0125752 0.3878418 0.008318364 -0.01237976 0.3879315 0.007692396 -0.01158154 0.388514 0.007828712 -0.01165145 0.3882737 0.007685303 -0.01149964 0.3883512 0.008539676 -0.01288855 0.3878611 0.00853604 -0.01283091 0.3877571 -0.008826076 -0.001218557 0.3684176 -0.008810341 -0.001327753 0.3684439 0.006976723 -0.005548 0.3674207 0.007345259 -0.005007803 0.3676182 0.008898437 -4.88019e-4 0.3679001 2.3408e-7 -0.008891344 0.366101 -6.73011e-4 -0.008888304 0.3661022 -0.001981139 -0.008682072 0.3661859 -0.001852273 -0.008719205 0.3661708 0.003249168 -0.008280277 0.3663481 5.92609e-4 -0.008894026 0.3661 6.6545e-4 -0.008883893 0.366104 0.002917289 -0.008422851 0.3662907 0.001852512 -0.008719086 0.3661709 -0.001979291 0.008678138 0.3661875 -0.00187838 0.008713603 0.3661731 0 0.008913755 0.3660919 0 0.008913755 0.3660919 6.64551e-4 0.008866608 0.3661114 0.001258492 0.008824467 0.3661289 0.00184822 0.008701562 0.3661789 0.00237143 0.008592486 0.3662233 0.003251731 0.008283913 0.3663471 0.008829593 -0.001213908 0.3684356 0.008837044 -0.001167058 0.3684287 0.008875072 -8.14195e-4 0.3682399 0.008506417 -0.002623498 0.3683645 0.008588135 -0.002387404 0.3684247 0.008658111 -0.002085924 0.3684549 0.008759677 -0.001648783 0.3684986 0.008761167 -0.001642286 0.3684992 0.008882939 -7.4086e-4 0.3682007 0.008394777 -0.002946138 0.3682821 0.008227288 -0.003430247 0.3681585 0.007639765 -0.004575967 0.367776 0.007711291 -0.004471182 0.3678144 0.005547046 -0.006955802 0.3668762 0.006082475 -0.006516039 0.3670491 0.006550073 -0.006009876 0.3672434 0.003605365 -0.008127212 0.3664097 0.004102468 -0.007913589 0.3664957 0.005209088 -0.007233321 0.3667671 -0.003605008 -0.008127868 0.3664094 -0.003064155 -0.008370518 0.3663119 -0.005208849 -0.00723344 0.366767 -0.004449605 -0.007707655 0.3665779 -0.004214942 -0.007854223 0.3665195 -0.007635295 -0.004573464 0.3677761 -0.007042884 -0.005463778 0.3674524 -0.006551027 -0.006011426 0.3672429 -0.006518006 -0.006048142 0.3672288 -0.006186068 -0.006417751 0.3670874 -0.008779585 -0.00154078 0.368495 -0.008756458 -0.00164771 0.3684883 -0.008661091 -0.00208801 0.368461 -0.008630335 -0.002229869 0.3684521 -0.008399784 -0.002949297 0.3682847 -0.008318543 -0.003202617 0.3682258 -0.008009552 -0.003857374 0.3680147 -0.007760167 -0.004385769 0.3678444 -0.008871316 8.2978e-4 0.3682203 -0.008895218 5.74962e-4 0.3680421 -0.008897721 4.97461e-4 0.3679005 -0.008899152 -4.85067e-4 0.3679045 -0.008891522 -6.29493e-4 0.3680997 -0.008873999 -8.19903e-4 0.3682351 -0.00890845 -3.07979e-4 0.3676652 -0.008905589 2.53076e-4 0.3674539 -0.008913755 0 0.3567569 -0.008913755 0 0.3669915 -0.00891 -2.20158e-4 0.3674731 -0.008857011 -0.001004457 0.3683663 -0.008644759 0.002078175 0.3684293 -0.008756458 0.001646995 0.3684905 -0.008846879 0.00108993 0.3684023 -0.008827686 0.001215875 0.3684261 -0.008810579 0.001327931 0.3684473 -0.008769869 0.001595079 0.3684979 -0.006481826 0.006015896 0.3672378 -0.006513237 0.005980789 0.3672512 -0.007342338 0.005054235 0.3676046 -0.007605075 0.00455749 0.3677715 -0.007983326 0.003842353 0.3680118 -0.0083099 0.003225028 0.3682193 -0.008408427 0.002953946 0.3682932 -0.008441209 0.002863824 0.3683178 -0.004428923 0.007677614 0.3665892 -0.005169928 0.007182598 0.3667858 -0.005835771 0.006737887 0.3669624 -0.003599286 0.008108377 0.3664172 -0.003989279 0.007971286 0.3664726 0.00351268 0.00819242 0.3663838 0.00361222 0.008141934 0.3664041 0.004540503 0.00767064 0.3665929 0.007308721 0.005102694 0.3675864 0.006563365 0.006021499 0.36724 0.006499946 0.0060997 0.3672105 0.005638122 0.006904125 0.3668972 0.005553662 0.006963074 0.3668738 0.005193889 0.007214367 0.3667741 0.007978141 0.00397545 0.3679851 0.007626116 0.004568278 0.3677754 0.007359206 0.005017697 0.3676165 0.00890696 -3.49457e-4 0.3677353 0.008909404 -2.2503e-4 0.3674705 0.008913755 0 0.3669915 0.008911252 2.07838e-4 0.3674791 0.008827686 0.001218318 0.3684261 0.008808791 0.001363813 0.3684759 0.008753597 0.00164777 0.3684771 0.008911192 2.14609e-4 0.367495 0.008838653 0.00115472 0.367974 0.008899331 4.84224e-4 0.367906 0.008895635 5.68106e-4 0.3680338 0.008874475 8.19088e-4 0.3682378 0.008865177 9.29248e-4 0.3683273 0.008677601 0.00203818 0.3684789 0.008663058 0.00208795 0.3684689 0.008506417 0.002624034 0.3683609 0.008409857 0.002954483 0.3682944 0.008409798 0.002954721 0.3682944 -0.007826507 -0.01164871 0.3882751 -0.007683634 -0.01149755 0.3883522 -0.007690668 -0.01157969 0.3885152 -0.008149147 -0.01215285 0.3881483 -0.008535385 -0.01282 0.3877446 -0.008419156 -0.01256889 0.3878449 -0.008534967 -0.01281261 0.3877362 -0.008496284 -0.01283067 0.388027 -0.008541107 -0.01290768 0.3879804 -0.008539676 -0.01288831 0.3878605 -0.008162915 -0.01225829 0.3883735 -0.00853604 -0.01283079 0.387757 -0.008140742 -0.01211088 0.388057 -0.008059144 -0.01197671 0.3881191 -0.007992684 -0.01186734 0.3881698 -0.007443904 -0.01137673 0.3889403 -0.007484972 -0.01141458 0.3889142 -0.00771445 -0.01168084 0.3887411 -0.008060276 -0.01208215 0.3884801 0.008120357 0.0178399 0.399382 0.008128821 0.01782655 0.3993338 0.00871706 0.01732993 0.3998894 0.008438885 0.01730126 0.3975827 0.008492052 0.01719057 0.3972617 0.008330047 0.01750004 0.3981462 0.008227467 0.01767164 0.3987751 0.008641302 0.01685947 0.3962924 0.008572101 0.01702374 0.3967781 0.007826685 0.01827716 0.4009418 0.007894456 0.01817649 0.4005829 0.008024573 0.01798307 0.3998933 0.008170068 0.01817911 0.4016025 0.007796347 0.01834541 0.4012107 0.007835626 0.01855742 0.4022228 0.007823824 0.01855432 0.4021943 0.007822811 0.01855391 0.4021914 0.007799863 0.01854568 0.4021255 0.007796883 0.01854115 0.4021009 0.007744789 0.01846134 0.401667 0.007745742 0.01845926 0.4016589 0.007837653 0.01855796 0.4022276 0.008688032 -0.01081109 0.3850346 0.008800745 -0.009576559 0.3836289 0.008828699 -0.009838044 0.3833746 0.008974432 -0.007113099 0.3811386 0.008820116 -0.009364306 0.3833873 0.008837282 -0.009176909 0.3831738 0.008904099 -0.008342385 0.3823103 0.008909225 -0.008271694 0.3822396 0.008940637 -0.007713377 0.381709 0.008951544 -0.007519423 0.3815248 0.008948922 -0.007566094 0.3815691 0.008700489 -0.01159286 0.3854637 0.008650362 -0.01123708 0.3855746 0.008672058 -0.01099175 0.3852636 0.008562207 -0.01241773 0.3871831 0.008620381 -0.01157701 0.3860055 0.008642852 -0.01132255 0.385683 0.008610546 -0.0130937 0.3875452 0.008611261 -0.01309645 0.3875433 0.008611083 -0.01309758 0.3875425 0.008608818 -0.0132628 0.3878963 0.008610367 -0.01323992 0.3879011 0.008616149 -0.01315474 0.3879191 0.00888127 -0.01391983 0.3915151 0.008066296 0.004327654 0.3829547 0.008066296 0.008335649 0.3848043 0.008066296 0.01009744 0.3861434 0.008651137 0.01088988 0.3852443 0.008651137 -0.002425014 0.3813098 0.008651137 -4.51951e-5 0.3811303 0.008953928 -4.86908e-5 0.3798564 0.008999943 0.001555979 0.3791798 0.008999943 -5.1132e-5 0.3791266 0.008560538 0.01237791 0.3871031 0.008999943 0.005264818 0.3798798 0.008999943 0.005238234 0.3798734 0.008953928 0.005028307 0.3805837 0.008949875 -0.007516086 0.3815327 0.008066296 -0.01170122 0.3877871 0.008651137 -0.01095753 0.3853043 0.008066296 -0.0101602 0.386199 0.008651137 -0.009065449 0.3838497 0.008651137 -0.006982982 0.3826839 0.008999943 -0.002718567 0.3793345 0.008999943 -0.004080355 0.3795701 0.008953928 -0.005121588 0.3806116 0.008999943 -0.005330145 0.3799213 0.008999943 0.005900144 0.3800812 0.008651137 0.00898981 0.3838002 0.008823633 0.009286344 0.3833218 0.008904159 0.008342385 0.3823102 0.008942306 0.007752537 0.3817357 0.008944988 0.007711112 0.3816953 0.008651137 0.006901025 0.3826458 0.008949518 0.007561981 0.3815624 0.008953928 0.007434785 0.3814891 0.008953154 0.007442772 0.3814561 0.008687973 0.01081103 0.3850346 0.008751451 0.01013302 0.3842291 0.00879693 0.009599387 0.3836573 0.008066296 0.01164722 0.387723 0.00856316 0.01233237 0.3870369 0.00864619 0.01132065 0.3857052 0.008648753 0.01128911 0.3856638 0.008678138 0.01093143 0.385193 0.008999943 -3.32737e-4 0.3791173 0.008999943 -0.002217292 0.3792477 0.008953928 -0.002612531 0.3800498 0.008999943 0.003429055 0.3794351 0.008953928 0.00251621 0.3800356 0.008999943 0.002618253 0.3793246 0.008066296 -0.008405745 0.3848503 0.008066296 -4.19064e-5 0.3823288 0.008066296 -0.002248525 0.3824951 0.008066296 -0.004407942 0.3829787 0.008066296 0.006398856 0.3837339 0.008066296 -0.006474852 0.3837693 0.008651137 -0.004753887 0.3818312 0.008651137 0.002335548 0.3812967 0.008066296 0.002165615 0.382483 0.008651137 0.004667282 0.3818054 -0.008625686 -0.01324266 0.387899 -0.008625924 -0.01324063 0.3878994 -0.008869886 -0.01394766 0.3917623 -0.008969068 -0.0145598 0.3939681 -0.008990466 -0.01469177 0.3944435 -0.008867621 -0.01393359 0.3917117 -0.008832335 -0.01371616 0.390928 -0.008625924 -0.01324063 0.3878994 -0.008610844 -0.01309937 0.3875413 -0.008611261 -0.01309657 0.3875433 -0.008557319 -0.01242762 0.3871744 -0.008942127 -0.00775516 0.3817383 -0.008903861 -0.008345842 0.3823137 -0.008819043 -0.009340047 0.3833794 -0.008826494 -0.009867668 0.383402 -0.008945167 -0.007708191 0.3816925 -0.008949577 -0.007561862 0.3815621 -0.008951485 -0.007499814 0.3815068 -0.008699655 -0.01160728 0.3854764 -0.008796691 -0.00960201 0.3836602 -0.008751213 -0.01013541 0.3842319 -0.008687794 -0.01081293 0.3850369 -0.008674144 -0.0109806 0.385258 -0.008648693 -0.01129209 0.3856688 -0.008646309 -0.01132136 0.3857075 -0.008560597 -0.01237124 0.3870921 -0.008812069 -0.0162791 0.3946588 -0.008793711 -0.01633971 0.3946152 -0.008495569 -0.01714509 0.3935265 -0.008453667 -0.01723492 0.393584 -0.008620679 -0.01691031 0.3942054 -0.008330106 -0.01749998 0.3937538 -0.008903324 -0.01597815 0.3948749 -0.00884664 0.009075284 0.3830624 -0.008821606 0.009349524 0.383374 -0.008651137 0.009051382 0.3838405 -0.008798539 0.009601354 0.3836601 -0.008687794 0.01081287 0.385037 -0.008651137 0.006961345 0.3826737 -0.008933603 0.00774306 0.3817508 -0.008903861 0.008345782 0.3823137 -0.008651137 -0.009051382 0.3838405 -0.008651137 -0.006961345 0.3826737 -0.008953928 -0.007499754 0.3815193 -0.008066296 -0.01015347 0.386193 -0.008651137 -0.01095026 0.3852978 -0.008066296 -0.008392751 0.3848417 -0.008066296 -0.01169973 0.3877853 -0.008563578 0.01241326 0.387183 -0.008066296 0.01169973 0.3877853 -0.008672177 0.0109871 0.3852553 -0.008651137 0.01095026 0.3852978 -0.008651077 0.01122266 0.3855506 -0.008066296 0.01015347 0.386193 -0.008639872 0.0113483 0.3857081 -0.008640766 0.01133769 0.3856948 -0.008999943 0.002676486 0.3793272 -0.008999943 0.004080414 0.3795702 -0.008953928 0.00508964 0.380602 -0.008999943 0.005296707 0.3799117 -0.008999943 0.005900204 0.3800812 -0.008953928 0 0.3798564 -0.008999943 4.62621e-7 0.3791282 -0.008999943 3.32786e-4 0.3791173 -0.008999943 -0.001555979 0.3791798 -0.008953928 -0.00257194 0.3800438 -0.008999943 -0.002676367 0.3793325 -0.008953928 -0.00508964 0.380602 -0.008999943 -0.005264759 0.3798798 -0.008999943 -0.003429055 0.3794351 -0.008992314 0.006551444 0.3806377 -0.00894618 0.007487475 0.381512 -0.008941173 0.007588803 0.3816066 -0.008651137 -0.004724204 0.3818224 -0.008651137 -0.002387285 0.3813042 -0.008651137 0 0.3811302 -0.008651137 0.002387285 0.3813042 -0.008066296 0.008392751 0.3848417 -0.008066296 -0.004380464 0.3829704 -0.008066296 -0.002213597 0.38249 -0.008066296 0 0.3823287 -0.008066296 0.002213597 0.38249 -0.008066296 0.004380464 0.3829704 -0.008066296 -0.006454765 0.3837599 -0.008066296 0.006454765 0.3837599 -0.008651137 0.004724204 0.3818224 -0.008953928 0.00257194 0.3800438 -0.008999943 0.002217352 0.3792477 -0.007242679 0 0.3833569 -0.000999987 0.01899999 0.4016627 -0.000999987 0.01719999 0.4016627 2.41729e-4 0.01899999 0.4016035 3.49919e-5 0.0170449 0.4016001 0.000999987 0.01899999 0.4016627 0.000999987 0.01719999 0.4016627 -9.30514e-4 0.01688981 0.4016544 -9.04677e-4 0.01677453 0.4016513 -6.75408e-4 0.01647859 0.4016291 6.5904e-4 0.01647031 0.4016283 8.31973e-4 0.01664507 0.4016433 9.26842e-4 0.01687455 0.4016542 -6.36625e-4 0.01642853 0.4016253 -2.54071e-4 0.01623463 0.4016042 -2.45828e-4 0.01623046 0.4016038 5.63043e-4 0.01637333 0.4016199 2.3329e-4 0.01623642 0.4016043 1.88059e-4 0.01621764 0.4016022 9.81118e-4 0.01700586 0.4016604 0.009614467 0.01889109 0.406962 0.006993889 0.01899898 0.4156493 0.006938755 0.01899999 0.4155937 0.007411003 0.01899999 0.4149652 0.008081853 0.01889109 0.4037621 0.007420778 0.01889109 0.402942 0.007447421 0.01887577 0.402918 0.006861865 0.01899313 0.4034433 0.007417559 0.01899999 0.4042427 0.006824672 0.01899993 0.4034767 0.007528066 0.01888149 0.4161882 0.007503569 0.01888686 0.4161635 0.008075416 0.01889109 0.4154468 0.008986949 0.01889109 0.4139165 0.009611606 0.01889109 0.4122485 0.009930431 0.01889109 0.4087148 0.009929478 0.01889109 0.410496 0.008991658 0.01889109 0.4052933 0.007687866 0.01899999 0.4145968 0.008256494 0.01899999 0.4135651 0.008330345 0.01899999 0.4134311 0.008797407 0.01899999 0.4121842 0.008829951 0.01899999 0.4120337 0.0090788 0.01899999 0.4108833 0.009110093 0.01899999 0.4104225 0.009168922 0.01899999 0.409556 0.008827745 0.01899999 0.4071772 0.009066045 0.01899999 0.4082295 0.009109318 0.01899999 0.4087878 0.008772075 0.01899999 0.4069311 0.008292973 0.01899999 0.4056887 0.00826615 0.01899999 0.4056411 0.007639169 0.01899999 0.404529 0.006113111 0.01899999 0.4147604 -0.002830564 0.01899999 0.4170826 -0.002546727 0.01899999 0.4171654 0.005240023 0.01899999 0.4156451 -0.004805803 0.01899999 0.4159864 -0.005821883 0.01899999 0.4150869 -0.006156146 0.01899999 0.4147089 -0.004902482 0.01899999 0.4159218 0.004741787 0.01899999 0.4160133 0.004239499 0.01899999 0.4163845 0.003137648 0.01899999 0.416959 0.002480328 0.01899999 0.4171808 0.001960694 0.01899999 0.417356 8.38555e-4 0.01899999 0.4175561 -0.001637041 0.01899999 0.4174307 -4.04983e-4 0.01899999 0.4175898 -3.40884e-5 0.01899999 0.4175797 -0.003956556 0.01899999 0.4165532 -0.007593095 0.01887774 0.4161327 -0.00755912 0.01888543 0.4160991 -0.007057845 0.01899844 0.4156024 -0.006989419 0.01899999 0.4155346 -0.008984386 0.01889109 0.4052782 -0.008078157 0.01889109 0.403757 -0.007447838 0.0188775 0.4029176 -0.007430851 0.01888734 0.4029328 -0.007420539 0.01888924 0.4029421 -0.006861746 0.01899307 0.4034435 -0.008122086 0.01889109 0.4153818 -0.007450759 0.01899999 0.4149036 -0.009607195 0.01889109 0.4069356 -0.009927034 0.01889109 0.4086772 -0.00993371 0.01889109 0.4104478 -0.009627044 0.01889109 0.4121917 -0.009016752 0.01889109 0.4138538 -0.008222639 0.01899999 0.4055429 -0.00754857 0.01899999 0.4043951 -0.007420837 0.01899999 0.404233 -0.006824672 0.01899999 0.4034767 -0.008257091 0.01899999 0.4056276 -0.008723556 0.01899999 0.4067765 -0.008816182 0.01899999 0.4071545 -0.009040355 0.01899999 0.4080691 -0.009105622 0.01899999 0.4087536 -0.009166657 0.01899999 0.4093934 -0.009117305 0.01899999 0.4103788 -0.009100079 0.01899999 0.4107224 -0.008841693 0.01899999 0.4120284 -0.008396744 0.01899999 0.4132834 -0.008279502 0.01899999 0.4135053 -0.007774829 0.01899999 0.4144604 -0.006486892 0.01899802 0.4028067 -0.006352841 0.01898884 0.4020993 -0.006377995 0.01899999 0.4028334 -0.006393909 0.01899999 0.4028563 -0.006399333 0.01896297 0.401401 -0.006055712 0.01899999 0.4020053 -0.006120383 0.01899999 0.4021713 -0.005829274 0.01899999 0.4005206 -0.005846142 0.01899999 0.4008039 -0.006534993 0.01891738 0.4007292 -0.005852699 0.01899999 0.4009143 -0.005958437 0.01899999 0.4014823 -0.005740225 0.01899999 0.3990225 -0.00576663 0.01899999 0.3994662 -0.006111681 0.01897829 0.3994547 -0.006882548 0.01877856 0.3994285 -0.005731999 0.01899999 0.398146 -0.006490409 0.01887232 0.398146 -0.006714344 0.01883459 0.398146 -0.007204055 0.01854979 0.398146 -0.00770992 0.01825565 0.398146 -0.007273972 0.01863044 0.4006492 -0.007573723 0.01838284 0.3994051 -0.007842242 0.01809442 0.398146 -0.007094264 0.01881539 0.4018647 -0.007177889 0.01886367 0.4024334 -0.007150053 0.01873487 0.4012625 -0.007668197 -0.004887402 0.3690664 0.00653994 -0.006317377 0.368533 0.007668375 -0.004887163 0.3690665 0.008930623 0 0.3676608 0.005155324 -0.007488965 0.3680679 0.003561913 -0.008363962 0.3677097 0.001819789 -0.008906066 0.3674841 0 -0.009089827 0.367407 -0.00181961 -0.008906126 0.367484 -0.003561735 -0.008364081 0.3677096 -0.005155086 -0.007489144 0.3680679 -0.006539702 -0.006317555 0.368533 -0.008930623 0 0.3676609 0.006887733 0.006065845 0.3690016 0.006585597 0.006477832 0.3689644 0.006539285 0.006314933 0.3685253 -0.001303553 0.00950098 0.3686389 -0.001853227 0.00936973 0.368654 -0.00181955 0.00890392 0.3674762 -0.005154788 0.007486701 0.3680601 0 0.009087681 0.3673992 0.008930623 0 0.3676608 0.008933424 1.70426e-4 0.3681863 0.008931159 2.10368e-4 0.368221 0.008436858 0.003113508 0.369174 0.008694171 0.002149462 0.3691248 0.008700609 0.002125322 0.3691236 0.008781731 0.001652717 0.3690227 0.008839011 0.00131911 0.3689514 0.008857011 0.001148879 0.3688703 0.008901774 7.25186e-4 0.3686684 0.008905827 6.54274e-4 0.3686068 0.007739961 0.004731714 0.3691087 0.008425056 0.003157615 0.3691762 0.008258044 0.003584861 0.3691627 0.007989525 0.004271745 0.369141 0.007667303 0.004884779 0.3690588 0.005155026 0.007486581 0.3680601 0.003561794 0.008361697 0.3677019 0.001819789 0.008903861 0.3674762 -0.003561615 0.008361816 0.3677018 -0.006539106 0.006315112 0.3685252 -0.007667124 0.004885017 0.3690587 -0.007738769 0.004731833 0.3691083 -0.008060276 0.004115045 0.3691493 -0.008256316 0.003583669 0.3691608 -0.008430659 0.003111064 0.369171 -0.008488535 0.002954244 0.3691744 -0.008783817 0.001653611 0.369027 -0.008745551 0.001901268 0.3690922 -0.008685111 0.002148926 0.3691115 -0.008859634 0.001144349 0.3688795 -0.008855402 0.001190125 0.3689051 -0.008905351 6.51959e-4 0.3686037 -0.00891298 5.70375e-4 0.368558 -0.008928537 2.24945e-4 0.3682097 -0.006583631 0.006463766 0.3689653 -0.00670731 0.006331443 0.3689785 -0.006891548 0.006070375 0.3690016 -0.007463335 0.005260288 0.3690731 -0.007656812 0.00488907 0.3690978 -0.00584048 0.00725913 0.3688859 -0.004783749 0.008105874 0.3687953 -0.004946351 0.007975637 0.3688092 -0.00521171 0.007762968 0.368832 -0.0037207 0.008728504 0.3687265 -0.002548933 0.009203612 0.368673 -0.002584874 0.009189069 0.3686746 -0.003625154 0.008767247 0.3687221 -4.93604e-5 0.009603917 0.368627 0.002449691 0.009234786 0.3686695 0.001853764 0.009369611 0.368654 0.001208901 0.009515464 0.3686372 0 0.00960046 0.3686274 0.005215704 0.00776726 0.3688317 0.004947543 0.007976531 0.3688092 0.004768013 0.008116602 0.3687941 0.003630697 0.008772373 0.3687216 0.002583146 0.009182572 0.3686753 0.005683183 0.00740242 0.3688709 0.007655382 0.00488758 0.3690978 0.007381379 0.00539267 0.3690624 0.008667051 0.01178866 0.3853226 0.008707523 0.01123654 0.3846651 0.008699715 0.01160591 0.3854746 0.008782327 0.0103119 0.383701 0.008826673 0.009865045 0.383399 0.008595585 0.01309525 0.3875437 0.008595287 0.013098 0.3875418 0.008602857 0.01266443 0.3863655 0.008563995 0.0133835 0.3873449 0.008603513 0.01302289 0.3875936 0.008945286 0.007906377 0.3815575 0.008940517 0.007993876 0.381629 0.008810579 0.009921908 0.3833429 0.008877992 0.008992016 0.3824892 0.008910119 0.008549034 0.3820826 0.008953511 0.007755339 0.3814341 0.008563041 0.01341331 0.3873898 0.008625686 0.01324266 0.387899 0.008625924 0.01324057 0.3878994 0.00856781 0.01352095 0.3876018 0.008587002 0.01358419 0.3878285 0.008623301 0.0132637 0.3878946 0.00888735 0.01400536 0.3919701 0.00888133 0.01392036 0.3915153 0.008858919 0.01388251 0.3915249 0.008772432 0.01350903 0.3901718 0.008999943 0.01499992 0.3955515 0.008999288 0.01500093 0.3953346 0.008966386 0.0145592 0.3939676 0.008948028 0.01448708 0.3927742 0.008942186 0.01424235 0.3928288 0.008939266 0.01445865 0.3926196 0.008872866 0.01424264 0.3914445 0.008794903 0.01398897 0.3900645 10e-4 0.0188474 0.3846241 9.99998e-4 0.0185697 0.3839785 0.000999987 0.01719999 0.3816499 0.000999987 0.01899999 0.3855825 0.000999987 0.01899743 0.3854528 0.000999987 0.01887422 0.3846864 2.31335e-4 0.01625192 0.380657 0 0.01619994 0.380657 0 0.01619911 0.3805859 4.51262e-4 0.01621836 0.3798967 8.26146e-4 0.01663649 0.380657 7.72986e-4 0.01656556 0.380657 6.57679e-4 0.01647555 0.380657 4.63232e-4 0.0163238 0.380657 4.2773e-4 0.01629608 0.380657 0 0.01608502 0.3798347 0 0.01578599 0.3791364 1.85692e-7 0.01578617 0.3791367 3.77162e-4 0.01613569 0.3797463 4.2544e-4 0.01618957 0.3798443 0 0.01608961 0.379865 -2.54901e-4 0.01623302 0.380657 0 0.01608961 0.379865 -4.16622e-4 0.01619029 0.3798539 -4.41476e-4 0.01621443 0.3798967 -4.52397e-4 0.01634246 0.380657 -6.626e-4 0.016429 0.3802776 -6.84842e-4 0.01647126 0.380657 -8.26136e-4 0.01663649 0.380657 -9.29391e-4 0.01689302 0.3811137 -0.000999987 0.01719999 0.3816499 -9.86253e-4 0.01703423 0.3813652 9.07535e-4 0.01677978 0.3809162 9.27772e-4 0.01687175 0.3810768 -0.008616149 0.01315474 0.3879191 -0.008629977 0.01311236 0.3887287 -0.008610367 0.01323992 0.3879011 -0.008877694 0.01393377 0.3917132 -0.008901715 0.01401346 0.3920027 -0.008881688 0.01394718 0.3917618 -0.008887052 0.01428711 0.3916864 -0.008715391 0.0138154 0.3891087 -0.008587002 0.01358419 0.3878285 -0.008930146 0.01440536 0.3923326 -0.008936285 0.01445806 0.3926179 -0.008956193 0.0145604 0.3939698 -0.008999943 0.01500004 0.3955509 -0.00856769 0.01352047 0.3876006 -0.008610367 0.01323992 0.3879011 -0.008595287 0.01309627 0.387543 -0.008595407 0.0130952 0.3875437 -0.008603334 0.01302236 0.387594 -0.008563995 0.0133835 0.3873449 -0.008563041 0.01341313 0.3873896 -0.008699595 0.01160728 0.3854764 -0.008826494 0.009867668 0.383402 -0.008663654 0.01180315 0.3853133 -0.008646309 0.0120269 0.3855695 -0.008880257 0.008984386 0.3824689 -0.008839905 0.009571552 0.3829898 -0.008811831 0.00992465 0.3833451 -0.008707284 0.01123881 0.3846672 -0.00890994 0.00855267 0.3820859 -0.008933484 0.008015215 0.3816658 -0.00893861 0.007897675 0.381574 -0.008990466 0.006714403 0.3806493 0.001976966 0.01477807 0.3778563 0.001496493 0.01508373 0.3781926 0.001489102 0.01203823 0.3730216 0.001767754 0.01207637 0.3731757 0.002305269 0.01222801 0.3736799 0.002650082 0.01241564 0.3741936 0.002590656 0.01238328 0.374105 0.002585828 0.01238065 0.3740979 0 0.01194113 0.3726 1.86122e-7 0.01194113 0.3726 3.93082e-4 0.0119462 0.3726255 0.001117587 0.01198738 0.372816 -0.001095652 0.01198542 0.3728073 -3.72472e-4 0.01194566 0.3726229 -7.52765e-5 0.01194131 0.3726009 -2.35745e-5 0.01194119 0.3726001 -4.7295e-6 0.01194113 0.3726 0 0.01194113 0.3726 -0.002586364 0.01238572 0.3741078 -0.002585351 0.01238518 0.3741063 -0.002275347 0.01221638 0.3736445 -0.001726508 0.01206845 0.3731461 -0.001490592 0.01203739 0.3730194 -0.002671122 0.01243191 0.3742341 -0.002925455 0.01274693 0.3749337 -0.002590596 0.01414197 0.3770948 -0.00263518 0.01409065 0.3770321 -0.002908289 0.01357769 0.3763345 -0.002999961 0.01310867 0.3756 -0.00258547 0.01414787 0.377102 -0.002210676 0.01457947 0.3776289 -0.001104593 0.01526761 0.3783892 -0.001491308 0.01507443 0.3781818 -0.00171411 0.01496309 0.3780623 2.61577e-7 0.01545727 0.3785864 -5.62131e-4 0.01536238 0.3785468 -4.71406e-4 0.0154345 0.3785631 0.001440048 0.01511961 0.3782321 8.07754e-4 0.01536333 0.3784893 1.7481e-4 0.01546567 0.378595 6.63362e-7 0.01545727 0.3785864 0.002910256 0.01271575 0.3748705 0.002999961 0.01310867 0.3756 0.002983987 0.01329791 0.3759106 0.002802252 0.01381456 0.3766672 0.002585589 0.0141313 0.3770754 0.002578139 0.01414221 0.3770894 0.00244677 0.01433426 0.3773369 -0.008943378 0.01574999 0.395034 -0.007779002 0.01803976 0.3935987 -0.008669793 0.0162881 0.3946967 -0.008688867 0.01625049 0.3947202 -9.99994e-4 0.01856958 0.3839784 -10e-4 0.01899999 0.3855825 -0.000999987 0.01890349 0.384795 -0.000999987 0.01883983 0.3846278 -0.000999987 0.01864224 0.3841091 -0.007639169 0.01810532 0.3936093 -0.006540656 0.01862066 0.3936926 -0.005731999 0.01899999 0.3937538 -0.007452666 0.01819282 0.3936234 -0.006600797 0.01859241 0.393688 -0.008099257 0.01754093 0.3934836 -0.007933795 0.0176413 0.3918978 -0.001522064 0.01885437 0.3847905 -0.00117588 0.01899999 0.3856623 -0.002480804 0.01899999 0.3864686 -0.002682566 0.01899999 0.3866841 -0.003342032 0.01885437 0.3860192 -0.005527138 0.01899999 0.3926268 -0.005140602 0.01899993 0.3911717 -0.005571186 0.01885437 0.3895868 -0.004988729 0.01885437 0.3883154 -0.00415486 0.01899999 0.3887524 -0.004542529 0.01899999 0.3895114 -0.004705071 0.01899999 0.3899324 -0.006030797 0.01885437 0.390902 -0.005046129 0.01899993 0.3908159 -0.004258096 0.01885437 0.387112 -0.003206312 0.01899999 0.3872437 -0.003485858 0.01899999 0.3876558 -0.003926336 0.01899999 0.3883051 -0.00219345 0.01885437 0.385121 -0.001724183 0.01899999 0.3859142 -0.00279951 0.01885437 0.3855379 -0.001713812 0.01899999 0.3859065 -0.001768767 0.01853144 0.3841758 -0.002063572 0.01851683 0.3842515 -0.002575874 0.01847243 0.3844804 -0.00258094 0.01847201 0.3844826 -0.003116726 0.01842558 0.3847219 -0.003333568 0.01839834 0.3848628 -0.003459215 0.01838254 0.3849445 -0.005079448 0.01813459 0.3862261 -0.00494939 0.01815676 0.3861115 -0.004991769 0.01838415 0.3865948 -0.003973662 0.01838415 0.3853814 -0.004090726 0.01830309 0.3853548 -0.004036247 0.01830995 0.3853195 -0.005783736 0.01838415 0.3878986 -0.00596261 0.017937 0.3872476 -0.00524497 0.01809757 0.3864176 -0.006943583 0.01764017 0.3887798 -0.006898343 0.01765763 0.3886893 -0.006404817 0.01838415 0.3892539 -0.006834506 0.01768237 0.3885615 -0.006238043 0.01785659 0.3876626 -0.007052063 0.01759821 0.388997 -0.007045924 0.0176413 0.3889979 -0.007586896 0.01739138 0.3900676 -0.007550239 0.0176413 0.3904406 -0.007707238 0.01732826 0.3903936 -0.008164882 0.01708829 0.3916338 -0.008216917 0.01704937 0.3918344 -0.008258879 0.01701796 0.3919962 -0.008598029 0.0167641 0.3933044 -0.0068897 0.01838415 0.3906412 -0.007260382 0.01838415 0.3920494 -0.008896887 0.01590991 0.394419 -0.008898019 0.01589983 0.3944315 -0.008922636 0.01568263 0.3947017 0.008936107 0.01568394 0.3947025 0.002164423 0.01850962 0.3842874 0.001767873 0.01853114 0.3841769 0.001156389 0.01856422 0.3840064 0.002581834 0.01847249 0.3844795 0.002576828 0.01847296 0.3844771 0.004031717 0.01830887 0.385326 0.003459751 0.01838237 0.3849456 0.003156363 0.01842141 0.3847439 0.003333866 0.01839858 0.3848619 0.004949212 0.01815652 0.3861129 0.004187822 0.01828885 0.3854298 0.006240904 0.01785695 0.3876604 0.006020784 0.01792204 0.3873245 0.006857156 0.01767468 0.3886008 0.005245804 0.01809775 0.3864166 0.005108654 0.01812887 0.3862559 0.008213102 0.01704919 0.3918353 0.008137762 0.01710504 0.3915477 0.007705569 0.01732814 0.3903942 0.007559299 0.01740366 0.3900037 0.007054686 0.01759845 0.3889955 0.006946682 0.01764011 0.3887798 0.006900489 0.01765793 0.3886874 0.008255898 0.01701754 0.3919986 0.008598029 0.0167641 0.3933044 0.008704483 0.01652264 0.3936282 0.008887648 0.01589679 0.394432 0.008929669 0.0157532 0.3946165 0.006236016 0.01899999 0.4025318 0.006129682 0.01899999 0.4021708 0.005954861 0.01899999 0.4015772 0.006411969 0.01899999 0.4028465 0.006629943 0.01899999 0.4032365 0.00576961 0.01899999 0.3994663 0.00579214 0.01899999 0.4002599 0.005825996 0.01899999 0.4005339 0.001175105 0.01899999 0.3856636 0.005859076 0.01899999 0.400802 0.005943536 0.01899999 0.4014854 0.004531621 0.01899999 0.3894847 0.004703998 0.01899999 0.3899326 0.005486547 0.01899999 0.3924397 0.005731999 0.01899999 0.3937538 0.005731999 0.01899999 0.398146 0.00505954 0.01899999 0.3908568 0.005144178 0.01899999 0.3911706 0.001722872 0.01899999 0.3859174 0.00176829 0.01899999 0.3859385 0.002473354 0.01899999 0.3864615 0.002682447 0.01899999 0.3866841 0.003193557 0.01899999 0.3872282 0.003489315 0.01899999 0.3876535 0.003832519 0.01899999 0.3881471 0.004150152 0.01899999 0.3887549 0.001522064 0.01885432 0.3847903 0.00219351 0.01885432 0.3851206 0.007045865 0.01764118 0.3889977 0.007260501 0.01838403 0.3920493 0.007317662 0.01852864 0.3935052 0.00688982 0.01838403 0.390641 0.007285714 0.01855474 0.3935102 0.00722754 0.01859003 0.3935193 0.007129132 0.01863247 0.3935347 0.006909132 0.01872742 0.3935692 0.006031036 0.01885432 0.3909018 0.006643295 0.0188421 0.3936109 0.006639897 0.01884359 0.3936114 0.007870316 0.01807731 0.3934185 0.007582485 0.01831233 0.3934636 0.007516741 0.01836603 0.3934739 0.007933855 0.01764118 0.3918977 0.008018434 0.01787608 0.3933953 0.007894396 0.01804453 0.3934147 0.008403062 0.01724892 0.3933349 0.008310317 0.01747941 0.3933495 0.008198976 0.01763069 0.3933669 0.007550239 0.01764118 0.3904404 0.006404876 0.01838403 0.3892537 0.005783796 0.01838403 0.3878984 0.004991888 0.01838403 0.3865945 0.003973722 0.01838403 0.3853811 0.00279957 0.01885432 0.3855377 0.003342151 0.01885432 0.3860189 0.004258275 0.01885432 0.3871116 0.005571305 0.01885432 0.3895865 0.004988908 0.01885432 0.3883152 0.006542325 0.01888567 0.3936268 0.006517708 0.01888948 0.3936306 0.005809903 0.01899892 0.3937416 0.008903384 0.01597803 0.3948753 0.008495569 0.01714509 0.3935265 0.008620679 0.01691025 0.3942055 0.008330106 0.01749998 0.3937538 0.008453667 0.01723492 0.3935841 0.008793652 0.01633983 0.3946154 0.008812069 0.01627904 0.394659 0.007010638 0.01871389 0.398146 0.007214426 0.0185725 0.398146 0.006882667 0.01877856 0.3994285 0.006479918 0.01883262 0.398146 0.006111741 0.01897829 0.3994546 0.007177889 0.01886367 0.4024333 0.007094323 0.01881533 0.4018646 0.007274091 0.01863032 0.4006491 0.007149994 0.01873487 0.4012625 0.007573783 0.01838278 0.399405 0.006352901 0.01898878 0.4020993 0.006399214 0.01896297 0.4014009 0.006486952 0.01899802 0.4028066 0.00670278 0.01878273 0.398146 0.006535112 0.01891732 0.4007291 0.007857739 0.01810729 0.3981461 0.007825493 0.01814877 0.398146 0.007697403 0.01823759 0.398146 0.007232129 0.01859802 0.3937538 0.00650388 0.01886999 0.3937538 0.006714344 0.01883459 0.3937538 0 -0.008499979 0.3786 0.00149995 -0.008499979 0.3781981 0.002598047 -0.008499979 0.3771 0.002999961 -0.008499979 0.3756 -0.002598047 -0.008499979 0.3741 0.002598047 -0.008499979 0.3741 0.00149995 -0.008499979 0.3730019 0 -0.008499979 0.3726 -0.00149995 -0.008499979 0.3730019 -0.00149995 -0.008499979 0.3781981 -0.002598047 -0.008499979 0.3771 -0.002999961 -0.008499979 0.3756 -0.007232129 -0.01859796 0.3937538 -0.007688701 -0.01822936 0.3937538 -0.007928907 -0.01802933 0.3935182 -0.007955551 -0.01801395 0.3937538 -0.006707072 -0.01881706 0.3937541 -0.006523072 -0.01889377 0.3937542 -0.006362378 -0.01891642 0.3937541 -0.005770385 -0.01899975 0.3937539 0.007277429 0.01857131 0.3937538 0.007697761 0.01824021 0.3937538 0.007870018 0.01810449 0.3937539 0.007945001 0.01800596 0.3937538 0.007907807 0.01804149 0.3934405 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.2393146 0.9709402 0.001896262 -0.1160919 0.9932326 -0.003410696 -0.2393156 0.9709399 0.001896262 -0.3420177 0.9396859 -0.00379008 -0.3919665 0.9199791 7.58312e-4 -0.3919622 0.919981 7.58312e-4 -0.5495088 0.8354872 -0.001136183 -0.534463 0.845185 -0.003408193 -0.7746042 0.632445 0.001327157 -0.7746042 0.632445 0.001327157 -0.7273678 0.6862362 -0.003979802 -0.6631217 0.7485096 0.00170654 -0.6631217 0.7485096 0.00170654 -0.8660235 0.4999989 -0.002083539 -0.8660236 0.4999988 -0.002083599 -0.9350158 0.3546037 0.001327157 -0.9350154 0.3546044 0.001327157 -0.957982 0.2868009 -0.003979861 -0.9797891 0.200026 0.00170648 -0.9797896 0.2000238 0.00170648 -0.9983041 0.05814474 -0.00284183 -0.9991885 0.04026603 -9.47381e-4 -0.9848008 -0.1736468 -0.00379008 -0.9927086 -0.1205369 7.58246e-4 -0.9927091 -0.1205329 7.58246e-4 -0.9182108 -0.3960776 -0.003410696 -0.9605164 -0.278217 0.001896321 -0.9605163 -0.2782176 0.001896321 -0.8021184 -0.5971552 -0.003410756 -0.8229838 -0.5680649 0 -0.9034506 -0.4286923 0 -0.6427831 -0.7660389 -0.00379008 -0.721201 -0.6927233 0.001896262 -0.7212015 -0.6927227 0.001896262 -0.316667 -0.9485352 0.00170654 -0.4647206 -0.8854508 -0.003408253 -0.4487987 -0.8936321 -0.001136183 -0.6007428 -0.7994419 7.58287e-4 -0.6007421 -0.7994426 7.58287e-4 -0.3166679 -0.948535 0.00170654 -0.2306142 -0.9730371 -0.003979861 -0.160411 -0.9870494 0.001327157 -0.1604098 -0.9870496 0.001327157 0 -0.9999979 -0.002083539 0 -0.9999979 -0.002083539 0.316667 -0.9485352 0.00170654 0.3166679 -0.9485349 0.00170654 0.2306141 -0.9730372 -0.003979861 0.160411 -0.9870494 0.001327157 0.1604098 -0.9870496 0.001327157 0.4647206 -0.8854508 -0.003408253 0.4487987 -0.8936321 -0.001136183 0.6007428 -0.7994419 7.58287e-4 0.6007421 -0.7994425 7.58287e-4 0.6427831 -0.7660388 -0.00379014 0.721201 -0.6927233 0.001896262 0.7212015 -0.6927227 0.001896262 0.8021184 -0.5971552 -0.003410756 0.8229838 -0.5680649 0 0.9034506 -0.4286923 0 0.9182108 -0.3960775 -0.003410696 0.9605164 -0.278217 0.001896321 0.9605163 -0.2782176 0.001896321 0.9848008 -0.1736468 -0.00379008 0.9927086 -0.1205369 7.58246e-4 0.9983041 0.05814474 -0.00284183 0.9991885 0.04026603 -9.47381e-4 0.9927091 -0.1205329 7.58246e-4 0.957982 0.2868009 -0.003979861 0.9797891 0.200026 0.00170648 0.9797896 0.2000238 0.00170648 0.7746042 0.632445 0.001327157 0.8660235 0.4999989 -0.002083539 0.8660236 0.4999988 -0.002083599 0.9350158 0.3546037 0.001327157 0.9350155 0.3546044 0.001327157 0.7746042 0.632445 0.001327157 0.7273678 0.6862362 -0.003979802 0.6631217 0.7485096 0.00170654 0.5495087 0.8354872 -0.001136183 0.5344631 0.845185 -0.003408193 0.6631217 0.7485096 0.00170654 0.3420177 0.9396858 -0.00379008 0.3919665 0.9199792 7.58313e-4 0.3919622 0.919981 7.58312e-4 -0.0804665 0.9967573 0 0.0804665 0.9967573 0 0.1160919 0.9932326 -0.003410696 0.2393146 0.9709402 0.001896262 0.2393156 0.97094 0.001896262 0.3899208 0.9151753 -0.1020591 0.7705597 0.629143 -0.102063 0.1595738 -0.9818956 -0.1020655 -0.8186862 -0.5650983 -0.102063 -0.993971 0.04005521 -0.102065 -0.6596598 0.7446022 -0.1020619 0.5107645 0.2948899 -0.807564 0.48538 -0.3350336 -0.8075634 -0.1411437 0.5726425 -0.8075637 0.0499826 0.202788 -0.9779462 0.1384986 0.1563325 -0.977946 0.208688 0.008409857 -0.9779461 0.2006115 -0.05810797 -0.977946 0.1254698 -0.16697 -0.977946 0.09706109 -0.1849344 -0.977946 0.03350317 -0.2061535 -0.9779459 0 -0.2088583 -0.9779459 -0.09706115 -0.1849346 -0.977946 -0.1718864 -0.1186447 -0.9779462 -0.2073348 -0.02517503 -0.9779461 -0.2086879 0.008409857 -0.9779461 -0.1952853 0.07406193 -0.9779461 -0.1808769 0.1044294 -0.9779459 -0.1384986 0.1563326 -0.977946 -0.08186477 0.1921463 -0.9779459 -0.0499829 0.2027883 -0.9779462 -0.0499829 0.2027886 -0.9779461 -0.0499826 0.202788 -0.9779462 -0.01680594 0.2081797 -0.9779462 -0.1116276 0.1765248 -0.977946 -0.1384986 0.1563325 -0.977946 -0.1617825 0.1320914 -0.977946 -0.1254696 -0.1669698 -0.9779461 -0.03350329 -0.2061542 -0.9779458 0.1718866 -0.1186448 -0.9779461 0.1718864 -0.1186446 -0.9779461 0.1506287 -0.1446807 -0.9779461 0.2006112 -0.05810773 -0.9779462 0.2073353 -0.02517509 -0.977946 0.195286 0.07406216 -0.9779459 0.1952864 0.07406216 -0.9779458 0.1808769 0.1044293 -0.9779458 0.1808764 0.1044291 -0.9779461 0.1617825 0.1320914 -0.9779459 0.1384986 0.1563326 -0.977946 0.1116279 0.1765253 -0.9779458 0.08186477 0.1921463 -0.9779459 0.08186513 0.1921445 -0.9779462 0.0499829 0.2027883 -0.9779462 0.01680594 0.2081797 -0.9779462 -0.3400275 0.7980742 -0.4974523 -0.2311741 0.5425859 -0.8075638 -0.2311736 0.542584 -0.807565 -0.08186513 0.1921444 -0.9779461 -0.08186525 0.1921448 -0.9779461 0.7837349 -0.3718872 -0.4974529 0.5328376 -0.2528348 -0.8075634 0.5328364 -0.252834 -0.8075645 0.1886927 -0.08953577 -0.977946 0.1886923 -0.08953553 -0.9779461 0.5893025 0.02374798 -0.8075634 0.6719631 0.5486409 -0.4974523 0.4568465 0.3730036 -0.8075639 0.4568454 0.3730029 -0.807565 0.1617825 0.1320914 -0.9779459 0.1617826 0.1320915 -0.9779459 0.04745769 0.5878682 -0.8075636 0.04745745 0.5878671 -0.8075642 -0.04745763 0.5878671 -0.8075643 -0.7512697 0.433746 -0.4974518 -0.9746742 0.1989801 -0.102064 -0.9301335 0.3527527 -0.1020638 -0.8111187 0.3076164 -0.4974521 -0.7512694 0.4337458 -0.4974524 -0.5107644 0.2948901 -0.8075639 -0.2046368 0.04177701 -0.9779461 -0.2046375 0.04177707 -0.9779459 -0.5778602 0.117971 -0.8075645 -0.5893009 0.02374792 -0.8075645 -0.8667864 0.03493016 -0.4974546 -0.861165 -0.1045648 -0.4974546 -0.2006112 -0.05810773 -0.9779462 -0.1886923 -0.08953559 -0.9779461 -0.5328378 -0.2528346 -0.8075634 -0.4853801 -0.3350335 -0.8075634 -0.7139319 -0.4927914 -0.4974514 -0.6256372 -0.6009327 -0.4974514 -0.1506289 -0.144681 -0.9779459 -0.1254698 -0.16697 -0.977946 -0.3543061 -0.4714956 -0.8075637 -0.2740848 -0.5222246 -0.8075637 -0.4031437 -0.7681256 -0.4974517 -0.2747068 -0.8228476 -0.4974516 -0.03350293 -0.2061537 -0.9779459 0 -0.2088583 -0.9779459 0 -0.5897793 -0.8075646 0.09460705 -0.5821418 -0.8075645 0.1391551 -0.8562575 -0.4974524 0.2747067 -0.8228471 -0.4974525 0.06613856 -0.1981095 -0.9779459 0.09706115 -0.1849346 -0.977946 0.2740846 -0.5222246 -0.8075637 0.3543059 -0.4714958 -0.8075637 0.5211389 -0.6935101 -0.4974515 0.6256371 -0.6009326 -0.4974517 0.8667864 0.0349307 -0.4974545 0.8667892 0.03493028 -0.49745 0.8499612 0.1735208 -0.49745 0.2073345 -0.02517414 -0.9779461 0.2086879 0.008409857 -0.9779462 0.589301 0.02374809 -0.8075646 0.5778602 0.117971 -0.8075644 0.8499608 0.1735208 -0.4974507 0.8111194 0.3076167 -0.4974508 0.930134 0.3527529 -0.1020599 0.8615011 0.4973929 -0.1020596 0.06980359 0.8646775 -0.4974538 0.06980437 0.8646801 -0.4974492 -0.06980377 0.8646801 -0.4974492 -0.06980413 0.8646774 -0.4974538 -0.2076041 0.8422827 -0.4974538 -0.3899208 0.9151753 -0.1020591 -0.3899198 0.9151754 -0.102061 -0.3400275 0.7980738 -0.4974533 -0.2076041 0.842283 -0.4974532 -0.1411437 0.5726428 -0.8075634 -0.04745757 0.5878682 -0.8075634 -0.01680594 0.2081797 -0.9779462 0.01680594 0.2081797 -0.9779462 -0.1116279 0.1765254 -0.9779458 -0.3152169 0.4984757 -0.8075644 -0.3152166 0.4984749 -0.807565 -0.4636446 0.7331949 -0.4974525 -0.4636446 0.7331951 -0.4974521 -0.531675 0.8407765 -0.1020623 -0.5316748 0.8407768 -0.1020591 -0.1384986 0.1563326 -0.9779459 -0.3910955 0.4414556 -0.807565 -0.391096 0.4414563 -0.8075644 -0.5752533 0.6493268 -0.497452 -0.5752531 0.6493266 -0.4974526 -0.6596599 0.7446021 -0.1020607 -0.6596599 0.744602 -0.1020623 -0.1617826 0.1320914 -0.9779459 -0.4568464 0.3730038 -0.8075639 -0.4568456 0.3730029 -0.8075648 -0.6719633 0.548641 -0.497452 -0.6719632 0.5486409 -0.4974523 -0.77056 0.6291427 -0.1020613 -0.7705602 0.629143 -0.1020604 -0.9301338 0.3527532 -0.1020599 -0.8615012 0.4973929 -0.1020596 -0.8615032 0.4973894 -0.1020583 -0.861503 0.4973887 -0.1020633 -0.7705597 0.629143 -0.102063 -0.1617825 0.1320914 -0.9779459 -0.1808764 0.104429 -0.9779459 -0.5107626 0.2948887 -0.8075656 -0.5514516 0.2091379 -0.8075658 -0.8111193 0.3076168 -0.4974508 -0.8499608 0.1735207 -0.4974507 -0.9746744 0.1989812 -0.1020606 -0.9746738 0.1989818 -0.102065 -0.1952864 0.07406216 -0.9779458 -0.1952859 0.07406216 -0.9779459 -0.5514532 0.2091388 -0.8075645 -0.5778604 0.1179711 -0.8075644 -0.8499612 0.1735209 -0.49745 -0.8667891 0.03493082 -0.4974499 -0.9939716 0.04005616 -0.1020582 -0.8987327 -0.4264539 -0.1020609 -0.9555026 -0.2767642 -0.1020606 -0.8332417 -0.2413509 -0.4974517 -0.8611667 -0.1045646 -0.4974516 -0.5854806 -0.07109028 -0.8075635 -0.5893025 0.02374815 -0.8075635 -0.208688 0.008409857 -0.9779461 -0.2046366 0.04177653 -0.9779461 -0.9555025 -0.2767642 -0.1020615 -0.9555013 -0.2767668 -0.1020652 -0.9875246 -0.1199077 -0.1020653 -0.9875252 -0.1199072 -0.1020597 -0.9939715 0.04005682 -0.1020597 -0.8987324 -0.4264544 -0.1020628 -0.8987324 -0.4264543 -0.1020633 -0.7837349 -0.3718872 -0.497453 -0.8332407 -0.2413508 -0.4974532 -0.5664955 -0.1640872 -0.8075631 -0.5854811 -0.07109022 -0.807563 -0.2073352 -0.02517503 -0.9779459 -0.2073345 -0.02517414 -0.9779461 -0.2006115 -0.05810797 -0.977946 -0.2006111 -0.05810773 -0.9779462 -0.5664936 -0.1640869 -0.8075645 -0.5328362 -0.2528342 -0.8075645 -0.7837354 -0.3718874 -0.4974522 -0.7139317 -0.4927912 -0.4974519 -0.8186864 -0.5650982 -0.1020619 -0.4622967 -0.8808322 -0.1020599 -0.5976055 -0.7952682 -0.1020598 -0.5211391 -0.6935099 -0.4974516 -0.6256371 -0.6009327 -0.4974517 -0.4253504 -0.4085547 -0.8075644 -0.4853789 -0.3350329 -0.8075643 -0.1718866 -0.1186447 -0.9779461 -0.1886928 -0.08953571 -0.9779461 -0.5976051 -0.7952681 -0.1020628 -0.5976055 -0.795268 -0.1020615 -0.7174364 -0.6891071 -0.102061 -0.7174363 -0.689107 -0.1020615 -0.8186863 -0.5650982 -0.1020619 -0.1506287 -0.1446807 -0.977946 -0.1506289 -0.1446811 -0.9779459 -0.4253502 -0.4085545 -0.8075646 -0.3543052 -0.4714947 -0.8075646 -0.5211381 -0.6935091 -0.497454 -0.4031429 -0.7681246 -0.4974539 -0.4622964 -0.8808322 -0.1020616 0 -0.9947777 -0.1020656 -0.1595733 -0.9818956 -0.1020655 -0.1391551 -0.8562576 -0.4974524 -0.2747065 -0.8228471 -0.4974524 -0.186764 -0.559427 -0.8075647 -0.2740841 -0.5222235 -0.8075647 -0.09706109 -0.1849344 -0.9779461 -0.1254699 -0.1669698 -0.9779459 -0.1595739 -0.9818961 -0.10206 -0.1595757 -0.981896 -0.1020583 -0.3150144 -0.9435836 -0.1020583 -0.3150144 -0.9435836 -0.1020582 -0.4622955 -0.8808332 -0.1020581 -0.06613856 -0.1981095 -0.9779459 -0.06613856 -0.1981092 -0.9779461 -0.1867644 -0.5594278 -0.8075641 -0.09460717 -0.5821425 -0.807564 -0.1391551 -0.8562575 -0.4974523 0 -0.8674913 -0.4974523 0 -0.9947777 -0.1020656 0 -0.9947777 -0.1020656 -0.0661388 -0.1981096 -0.9779459 -0.03350311 -0.2061536 -0.977946 -0.09460699 -0.5821418 -0.8075646 0 -0.5897792 -0.8075645 0 -0.8674913 -0.4974523 0.1391551 -0.8562576 -0.4974524 0.1595733 -0.9818962 -0.1020606 0.5976052 -0.7952684 -0.1020598 0.4622965 -0.8808324 -0.10206 0.4031435 -0.7681258 -0.4974517 0.2747067 -0.8228476 -0.4974516 0.1867643 -0.5594278 -0.807564 0.09460711 -0.5821425 -0.807564 0.03350317 -0.2061541 -0.9779458 0.03350293 -0.2061537 -0.9779459 0.4622966 -0.880832 -0.1020622 0.4622955 -0.8808332 -0.102058 0.3150144 -0.9435837 -0.102058 0.3150144 -0.9435836 -0.1020582 0.1595757 -0.981896 -0.1020583 0.0661388 -0.1981096 -0.9779459 0.06613856 -0.1981092 -0.9779461 0.1867641 -0.5594269 -0.8075646 0.2740842 -0.5222234 -0.8075646 0.4031432 -0.7681245 -0.497454 0.5211383 -0.6935089 -0.4974539 0.5976054 -0.7952681 -0.1020618 0.8987324 -0.4264544 -0.1020628 0.8186863 -0.5650982 -0.1020631 0.7139319 -0.4927914 -0.4974514 0.6256372 -0.6009328 -0.4974514 0.4253502 -0.4085545 -0.8075645 0.3543053 -0.4714946 -0.8075646 0.1254697 -0.1669698 -0.977946 0.1254699 -0.1669698 -0.9779459 0.8186863 -0.5650984 -0.1020618 0.8186863 -0.5650982 -0.1020619 0.7174364 -0.6891071 -0.1020617 0.7174364 -0.6891071 -0.102061 0.5976055 -0.795268 -0.1020614 0.1506289 -0.144681 -0.9779459 0.1506289 -0.1446811 -0.9779459 0.4253504 -0.4085547 -0.8075643 0.485379 -0.3350328 -0.8075643 0.7139317 -0.4927912 -0.497452 0.7837353 -0.3718875 -0.4974522 0.8987324 -0.4264543 -0.1020633 0.8987327 -0.426454 -0.1020609 0.9555013 -0.2767668 -0.1020652 0.2006111 -0.05810773 -0.9779461 0.5664955 -0.1640875 -0.8075631 0.5664938 -0.1640867 -0.8075646 0.8332415 -0.2413511 -0.4974516 0.8332408 -0.2413507 -0.4974532 0.9555025 -0.2767642 -0.1020613 0.9555026 -0.2767643 -0.1020606 0.2073349 -0.02517497 -0.977946 0.5854806 -0.07109016 -0.8075634 0.5854811 -0.07109034 -0.8075631 0.8611651 -0.1045644 -0.4974546 0.8611667 -0.104565 -0.4974517 0.9875251 -0.1199077 -0.1020597 0.9875247 -0.1199071 -0.1020653 0.9301334 0.3527531 -0.1020638 0.9746742 0.1989801 -0.102064 0.9746744 0.1989812 -0.1020605 0.9746738 0.1989818 -0.102065 0.9939709 0.04005616 -0.102065 0.9939719 0.04005521 -0.102056 0.9939715 0.04005682 -0.1020597 0.861503 0.4973887 -0.1020633 0.8615032 0.4973894 -0.1020583 0.7512694 0.4337459 -0.4974524 0.8111187 0.3076165 -0.4974521 0.5514533 0.2091385 -0.8075645 0.5778603 0.1179711 -0.8075644 0.2046376 0.04177707 -0.9779459 0.2046366 0.04177653 -0.9779461 0.2046368 0.04177701 -0.9779461 0.1952853 0.07406198 -0.9779461 0.5514515 0.209138 -0.8075658 0.5107625 0.294889 -0.8075656 0.7512697 0.433746 -0.4974518 0.6719634 0.548641 -0.497452 0.77056 0.6291427 -0.1020615 0.7705601 0.6291429 -0.1020606 0.6596598 0.7446022 -0.1020619 0.1384986 0.1563326 -0.9779459 0.3910961 0.4414562 -0.8075644 0.3910954 0.4414556 -0.8075651 0.575253 0.6493265 -0.4974525 0.5752532 0.6493267 -0.4974522 0.6596598 0.744602 -0.1020622 0.6596601 0.7446021 -0.1020606 0.1116275 0.1765247 -0.977946 0.3152165 0.498475 -0.8075649 0.315217 0.4984755 -0.8075645 0.4636446 0.7331951 -0.4974522 0.4636445 0.733195 -0.4974525 0.5316751 0.8407767 -0.1020593 0.5316747 0.8407766 -0.102062 0.08186531 0.1921448 -0.977946 0.2311743 0.5425857 -0.8075637 0.2311734 0.5425842 -0.8075651 0.3400273 0.7980737 -0.4974532 0.3400276 0.7980743 -0.4974523 0.3899199 0.9151757 -0.1020579 0.3899194 0.9151756 -0.1020618 0.0499829 0.2027886 -0.9779461 0.1411438 0.5726428 -0.8075634 0.1411436 0.5726424 -0.8075637 0.2076041 0.8422828 -0.4974539 0.2076042 0.842283 -0.4974535 0.2380661 0.9658719 -0.102058 0.2380662 0.9658719 -0.1020578 -0.3899196 0.9151759 -0.1020579 -0.2380662 0.9658719 -0.1020577 -0.2380661 0.9658719 -0.102058 -0.2380661 0.9658721 -0.1020575 -0.08004593 0.9915528 -0.1020574 -0.08004671 0.9915518 -0.1020656 0.08004587 0.9915519 -0.1020656 0.08004677 0.9915527 -0.1020575 0.2380661 0.9658721 -0.1020576 -0.09745079 0.9894328 0.1073608 -0.2379633 0.965455 0.1061612 -0.288641 0.9515258 0.1062307 -0.2379554 0.9654225 0.1064729 -0.288591 0.951357 0.1078663 -0.3897598 0.914801 0.1059553 -0.4686889 0.8768568 0.1070187 -0.3897175 0.9146981 0.1069943 -0.468641 0.8767645 0.1079787 -0.5314539 0.8404274 0.1060115 -0.6307035 0.7685143 0.1076978 -0.6592997 0.7441958 0.1072221 -0.630727 0.768543 0.1073546 -0.6593635 0.7442673 0.1063296 -0.7685706 0.6307497 0.1070239 -0.7701618 0.6288177 0.106954 -0.768577 0.6307544 0.1069506 -0.7701653 0.628821 0.1069094 -0.8769565 0.4687435 0.1059576 -0.8610197 0.4971098 0.1073635 -0.8768044 0.4686616 0.1075661 -0.8609814 0.4970928 0.1077498 -0.9297444 0.3526055 0.1060408 -0.9513469 0.2885882 0.1079626 -0.9742189 0.1988872 0.1064959 -0.9515222 0.2886385 0.1062701 -0.974276 0.1989006 0.1059472 -0.9893738 0.09744495 0.1079065 -0.9935474 0.0400381 0.1061157 -0.9935473 0.04003971 0.1061157 -0.9894223 -0.09744977 0.1074571 -0.9870582 -0.1198505 0.1065461 -0.9514865 -0.2886292 0.106615 -0.9550246 -0.2766287 0.1067913 -0.9514768 -0.2886273 0.1067065 -0.9549794 -0.2766127 0.1072377 -0.8770111 -0.4687713 0.1053808 -0.8982855 -0.4262417 0.1067765 -0.8768876 -0.4687067 0.1066868 -0.8981472 -0.4261768 0.1081895 -0.7688385 -0.6309692 0.1037555 -0.8182201 -0.5647765 0.1074393 -0.8182203 -0.5647765 0.1074393 -0.7684901 -0.6306836 0.1079867 -0.7171402 -0.6888226 0.1059874 -0.6306992 -0.7685089 0.107762 -0.5972919 -0.7948507 0.1070264 -0.630747 -0.7685676 0.1070615 -0.5973404 -0.794916 0.1062681 -0.4686834 -0.8768444 0.1071442 -0.4620605 -0.8803821 0.1068997 -0.468697 -0.8768706 0.1068692 -0.4620635 -0.8803912 0.1068105 -0.314868 -0.9431452 0.1064686 -0.2886013 -0.9513902 0.1075453 -0.1594947 -0.9813981 0.1068602 -0.2886228 -0.9514654 0.10682 -0.1595065 -0.9814813 0.1060757 -0.09744465 -0.9893704 0.1079385 0 -0.9943721 0.1059446 0 -0.9943721 0.1059446 0.09744465 -0.9893704 0.1079385 0.1595065 -0.9814813 0.1060757 0.2886228 -0.9514654 0.10682 0.1594947 -0.9813981 0.1068602 0.2886013 -0.9513902 0.1075453 0.314868 -0.9431452 0.1064686 0.4687021 -0.8768814 0.1067593 0.4620591 -0.8803828 0.1068997 0.4686975 -0.8768703 0.1068692 0.4620493 -0.8803609 0.1071229 0.6308475 -0.7686898 0.105581 0.5972916 -0.794851 0.1070264 0.6307471 -0.7685674 0.1070615 0.9894223 -0.09744977 0.1074571 0.5972262 -0.7947633 0.1080376 0.7171402 -0.6888226 0.1059874 0.7684901 -0.6306836 0.1079867 0.8182203 -0.5647765 0.1074393 0.7685153 -0.6307045 0.1076852 0.8183501 -0.5648662 0.1059687 0.87678 -0.4686492 0.1078181 0.8982853 -0.4262422 0.1067765 0.8768882 -0.4687057 0.1066868 0.8983401 -0.4262676 0.106212 0.95142 -0.2886103 0.1072565 0.9550255 -0.2766261 0.1067913 0.951477 -0.2886263 0.1067065 0.9550324 -0.2766309 0.1067171 0.9870582 -0.1198505 0.1065461 0.9935473 0.04003971 0.1061157 0.9935474 0.0400381 0.1061157 0.9893738 0.09744495 0.1079065 0.974276 0.1989006 0.1059472 0.9515222 0.2886385 0.1062701 0.9742189 0.1988872 0.1064959 0.9513469 0.2885882 0.1079626 0.9297444 0.3526055 0.1060408 0.8767989 0.4686581 0.1076256 0.8610175 0.4971137 0.1073635 0.8768042 0.4686619 0.1075661 0.8611097 0.4971617 0.1063964 0.7685814 0.6307583 0.1068956 0.7701616 0.6288179 0.106954 0.7685767 0.6307548 0.1069506 0.7701568 0.6288136 0.1070135 0.6308346 0.768674 0.1057733 0.6593 0.7441956 0.1072221 0.6307269 0.7685431 0.1073547 0.6592517 0.7441416 0.107891 0.5314539 0.8404274 0.1060115 0.468641 0.8767645 0.1079787 0.3897175 0.9146981 0.1069943 0.4686889 0.8768568 0.1070187 0.3897598 0.914801 0.1059553 0.288591 0.951357 0.1078663 0.2379554 0.9654225 0.1064729 0.288641 0.9515258 0.1062307 0.2379633 0.965455 0.1061612 0.09745079 0.9894328 0.1073608 0.0800082 0.9910746 0.1066289 -0.0800082 0.9910746 0.1066289 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.7409957 -0.6081193 0.2848094 0.6081193 0.7409957 0.2848094 -0.7409957 0.6081193 0.2848094 -0.6081193 -0.7409957 0.2848094 0.08616435 -0.1612022 0.9831529 0.1159577 -0.141295 0.9831529 0.1412949 -0.1159577 0.9831529 0.1612023 -0.08616441 0.9831528 0.1612022 0.08616435 0.9831529 0.141295 0.1159577 0.9831529 0.1159577 0.1412949 0.9831529 0.08616441 0.1612023 0.9831528 -0.08616435 0.1612022 0.9831529 -0.1159577 0.141295 0.9831529 -0.1412949 0.1159577 0.9831529 -0.1612023 0.08616441 0.9831528 -0.1612022 -0.08616435 0.9831529 -0.141295 -0.1159577 0.9831529 -0.1159577 -0.1412949 0.9831529 -0.08616441 -0.1612023 0.9831528 -0.1749146 0.05305975 0.9831529 -0.1749146 0.05305975 0.9831528 -0.1819051 0.01791602 0.9831529 -0.181905 0.01791608 0.9831529 -0.181905 -0.01791602 0.9831529 -0.1819051 -0.01791608 0.9831528 -0.1749146 -0.05305975 0.9831529 0.05305975 0.1749146 0.9831529 0.05305975 0.1749146 0.9831528 0.01791602 0.1819051 0.9831529 0.01791608 0.181905 0.9831529 -0.01791602 0.181905 0.9831529 -0.01791608 0.1819051 0.9831528 -0.05305975 0.1749146 0.9831529 0.1749146 -0.05305975 0.9831529 0.1749146 -0.05305975 0.9831528 0.1819051 -0.01791602 0.9831529 0.181905 -0.01791608 0.9831529 0.181905 0.01791602 0.9831529 0.1819051 0.01791608 0.9831528 0.1749146 0.05305975 0.9831529 -0.05305975 -0.1749146 0.9831529 -0.05305975 -0.1749146 0.9831528 -0.01791602 -0.1819051 0.9831529 -0.01791608 -0.181905 0.9831529 0.01791602 -0.181905 0.9831529 0.01791608 -0.1819051 0.9831528 0.05305975 -0.1749146 0.9831529 -0.5010039 0.151978 0.8519963 -0.5010042 0.1519779 0.8519961 -0.521027 0.05131667 0.8519961 -0.5210272 0.05131661 0.8519961 -0.5210271 -0.05131667 0.8519961 -0.521027 -0.05131655 0.8519962 0.151978 0.5010039 0.8519963 0.1519779 0.5010042 0.8519961 0.05131667 0.521027 0.8519961 0.05131661 0.5210272 0.8519961 -0.05131667 0.5210271 0.8519961 -0.05131655 0.521027 0.8519962 0.5010039 -0.151978 0.8519963 0.5010042 -0.1519779 0.8519961 0.521027 -0.05131667 0.8519961 0.5210272 -0.05131661 0.8519961 0.5210271 0.05131667 0.8519961 0.521027 0.05131655 0.8519962 -0.151978 -0.5010039 0.8519963 -0.1519779 -0.5010042 0.8519961 -0.05131667 -0.521027 0.8519961 -0.05131661 -0.5210272 0.8519961 0.05131667 -0.5210271 0.8519961 0.05131655 -0.521027 0.8519962 -0.7596551 0.2304388 0.6081302 -0.7596551 0.2304387 0.60813 -0.7900149 0.07780957 0.60813 -0.7900149 0.07780957 0.60813 -0.7900149 -0.07780957 0.60813 -0.7900149 -0.07780957 0.60813 0.2304388 0.7596551 0.6081302 0.2304387 0.7596551 0.60813 0.07780957 0.7900149 0.60813 0.07780957 0.7900149 0.60813 -0.07780957 0.7900149 0.60813 -0.07780957 0.7900149 0.60813 0.7596551 -0.2304388 0.6081302 0.7596551 -0.2304387 0.60813 0.7900149 -0.07780957 0.60813 0.7900149 -0.07780957 0.60813 0.7900149 0.07780957 0.60813 0.7900149 0.07780957 0.60813 -0.2304388 -0.7596551 0.6081302 -0.2304387 -0.7596551 0.60813 -0.07780957 -0.7900149 0.60813 -0.07780957 -0.7900149 0.60813 0.07780957 -0.7900149 0.60813 0.07780957 -0.7900149 0.60813 -0.08616441 -0.1612022 0.9831529 -0.2467987 -0.4617278 0.8519964 -0.2467987 -0.4617279 0.8519963 -0.3742123 -0.7001019 0.6081304 -0.3742123 -0.700102 0.6081302 -0.4518734 -0.8453958 0.2848094 -0.4518737 -0.8453953 0.2848104 -0.1159577 -0.141295 0.9831528 -0.3321352 -0.4047082 0.8519962 -0.3321352 -0.4047079 0.8519964 -0.5036053 -0.6136449 0.6081296 -0.5036053 -0.6136443 0.6081304 -0.6081195 -0.7409951 0.2848105 -0.6081194 -0.7409955 0.2848097 -0.7409957 -0.6081193 0.2848094 -0.1412949 -0.1159577 0.9831529 -0.4047079 -0.332135 0.8519964 -0.404708 -0.3321353 0.8519961 -0.6136445 -0.503605 0.6081304 -0.6136447 -0.5036056 0.6081297 -0.7409952 -0.6081196 0.28481 -0.7409953 -0.6081192 0.2848104 -0.8453959 -0.451873 0.2848099 -0.1612023 -0.08616441 0.9831529 -0.4617279 -0.2467988 0.8519964 -0.4617278 -0.2467987 0.8519963 -0.700102 -0.3742124 0.6081302 -0.7001018 -0.3742122 0.6081304 -0.8453956 -0.4518734 0.2848102 -0.8453955 -0.4518738 0.2848094 -0.1749145 -0.05305975 0.9831528 -0.5010042 -0.151978 0.8519962 -0.5010039 -0.1519778 0.8519963 -0.7596551 -0.2304388 0.60813 -0.7596549 -0.2304387 0.6081302 -0.9173077 -0.2782621 0.2848106 -0.9173077 -0.2782624 0.2848098 -0.8453959 0.451873 0.2848099 -0.9173077 0.2782624 0.2848099 -0.9173077 0.2782621 0.2848106 -0.9173082 0.2782606 0.2848101 -0.9539682 0.09395748 0.28481 -0.9539679 0.09395784 0.2848109 -0.9539678 -0.09395748 0.2848109 -0.9539682 -0.09395784 0.28481 -0.9173082 -0.2782606 0.2848101 -0.1612022 0.08616441 0.9831529 -0.4617278 0.2467987 0.8519964 -0.4617279 0.2467987 0.8519963 -0.7001019 0.3742123 0.6081304 -0.700102 0.3742123 0.6081302 -0.8453958 0.4518734 0.2848094 -0.8453953 0.4518737 0.2848104 -0.141295 0.1159577 0.9831528 -0.4047082 0.3321352 0.8519962 -0.4047079 0.3321352 0.8519964 -0.6136449 0.5036053 0.6081296 -0.6136443 0.5036053 0.6081304 -0.7409951 0.6081195 0.2848105 -0.7409955 0.6081194 0.2848097 -0.6081193 0.7409957 0.2848094 -0.1159577 0.1412949 0.9831529 -0.332135 0.4047079 0.8519964 -0.3321353 0.404708 0.8519961 -0.503605 0.6136445 0.6081304 -0.5036056 0.6136447 0.6081297 -0.6081196 0.7409952 0.28481 -0.6081192 0.7409953 0.2848104 -0.451873 0.8453959 0.2848099 -0.08616441 0.1612023 0.9831529 -0.2467988 0.4617279 0.8519964 -0.2467987 0.4617278 0.8519963 -0.3742124 0.700102 0.6081302 -0.3742122 0.7001018 0.6081304 -0.4518734 0.8453956 0.2848102 -0.4518738 0.8453955 0.2848094 -0.05305975 0.1749145 0.9831528 -0.151978 0.5010042 0.8519962 -0.1519778 0.5010039 0.8519963 -0.2304388 0.7596551 0.60813 -0.2304387 0.7596549 0.6081302 -0.2782621 0.9173077 0.2848106 -0.2782624 0.9173077 0.2848098 0.451873 0.8453959 0.2848099 0.2782624 0.9173077 0.2848099 0.2782621 0.9173077 0.2848106 0.2782606 0.9173082 0.2848101 0.09395748 0.9539682 0.28481 0.09395784 0.9539679 0.2848109 -0.09395748 0.9539678 0.2848109 -0.09395784 0.9539682 0.28481 -0.2782606 0.9173082 0.2848101 0.08616441 0.1612022 0.9831529 0.2467987 0.4617278 0.8519964 0.2467987 0.4617279 0.8519963 0.3742123 0.7001019 0.6081304 0.3742123 0.700102 0.6081302 0.4518734 0.8453958 0.2848094 0.4518737 0.8453953 0.2848104 0.1159577 0.141295 0.9831528 0.3321352 0.4047082 0.8519962 0.3321352 0.4047079 0.8519964 0.5036053 0.6136449 0.6081296 0.5036053 0.6136443 0.6081304 0.6081195 0.7409951 0.2848105 0.6081194 0.7409955 0.2848097 0.7409957 0.6081193 0.2848094 0.1412949 0.1159577 0.9831529 0.4047079 0.332135 0.8519964 0.404708 0.3321353 0.8519961 0.6136445 0.503605 0.6081304 0.6136447 0.5036056 0.6081297 0.7409952 0.6081196 0.28481 0.7409953 0.6081192 0.2848104 0.8453959 0.451873 0.2848099 0.1612023 0.08616441 0.9831529 0.4617279 0.2467988 0.8519964 0.4617278 0.2467987 0.8519963 0.700102 0.3742124 0.6081302 0.7001018 0.3742122 0.6081304 0.8453956 0.4518734 0.2848102 0.8453955 0.4518738 0.2848094 0.1749145 0.05305975 0.9831528 0.5010042 0.151978 0.8519962 0.5010039 0.1519778 0.8519963 0.7596551 0.2304388 0.60813 0.7596549 0.2304387 0.6081302 0.9173077 0.2782621 0.2848106 0.9173077 0.2782624 0.2848098 0.8453959 -0.451873 0.2848099 0.9173077 -0.2782624 0.2848099 0.9173077 -0.2782621 0.2848106 0.9173082 -0.2782606 0.2848101 0.9539682 -0.09395748 0.28481 0.9539679 -0.09395784 0.2848109 0.9539678 0.09395748 0.2848109 0.9539682 0.09395784 0.28481 0.9173082 0.2782606 0.2848101 0.1612022 -0.08616441 0.9831529 0.4617278 -0.2467987 0.8519964 0.4617279 -0.2467987 0.8519963 0.7001019 -0.3742123 0.6081304 0.700102 -0.3742123 0.6081302 0.8453958 -0.4518734 0.2848094 0.8453953 -0.4518737 0.2848104 0.141295 -0.1159577 0.9831528 0.4047082 -0.3321352 0.8519962 0.4047079 -0.3321352 0.8519964 0.6136449 -0.5036053 0.6081296 0.6136443 -0.5036053 0.6081304 0.7409951 -0.6081195 0.2848105 0.7409955 -0.6081194 0.2848097 0.6081193 -0.7409957 0.2848094 0.1159577 -0.1412949 0.9831529 0.332135 -0.4047079 0.8519964 0.3321353 -0.404708 0.8519961 0.503605 -0.6136445 0.6081304 0.5036056 -0.6136447 0.6081297 0.6081196 -0.7409952 0.28481 0.6081192 -0.7409953 0.2848104 0.451873 -0.8453959 0.2848099 0.08616441 -0.1612023 0.9831529 0.2467988 -0.4617279 0.8519964 0.2467987 -0.4617278 0.8519963 0.3742124 -0.700102 0.6081302 0.3742122 -0.7001018 0.6081304 0.4518734 -0.8453956 0.2848102 0.4518738 -0.8453955 0.2848094 0.05305975 -0.1749145 0.9831528 0.151978 -0.5010042 0.8519962 0.1519778 -0.5010039 0.8519963 0.2304388 -0.7596551 0.60813 0.2304387 -0.7596549 0.6081302 0.2782621 -0.9173077 0.2848106 0.2782624 -0.9173077 0.2848098 -0.451873 -0.8453959 0.2848099 -0.2782624 -0.9173077 0.2848099 -0.2782621 -0.9173077 0.2848106 -0.2782606 -0.9173082 0.2848101 -0.09395748 -0.9539682 0.28481 -0.09395784 -0.9539679 0.2848109 0.09395748 -0.9539678 0.2848109 0.09395784 -0.9539682 0.28481 0.2782606 -0.9173082 0.2848101 0.1771482 0.8476391 0.5001266 0.1723535 0.8490473 0.4994126 0.1336655 0.8506807 0.5084052 0.1335421 0.8507036 0.5083993 0.08596956 0.8581314 0.5061816 0.03201937 0.862389 0.5052326 0.03193265 0.8623888 0.5052384 0.02613562 0.8623062 0.5057125 0.1936767 0.8427115 0.5023213 0.2801082 0.81309 0.5103175 0.1736528 0.8454978 0.5049536 0.07402068 0.8684598 0.4902024 0.298962 0.8060482 0.5107915 0.3003106 0.8054767 0.5109021 0.1201967 0.865948 0.485476 0.1646314 0.8562361 0.4896491 0.1649009 0.8561762 0.4896633 0.2043089 0.8467621 0.4911739 0.2487423 0.8361856 0.4887952 0.3690595 0.809833 0.4560325 0.5268986 0.7193171 0.452726 0.4030019 0.7869471 0.4672297 0.4029482 0.7869721 0.4672342 0.2861331 0.8266892 0.4844717 0.2842158 0.8271813 0.4847602 0.2887434 0.8260145 0.4840736 0.2864297 0.8266894 0.484296 0.402996 0.7869525 0.467226 0.4028993 0.7869928 0.4672414 0.4213796 0.7777473 0.4664207 0.3970286 0.7832652 0.4783973 0.3707754 0.7882409 0.4911229 0.3584042 0.8045607 0.4735278 0.4858133 0.7658756 0.4212126 0.6113061 0.7182375 0.3323249 0.7216857 0.596409 0.3513774 0.7216947 0.5964012 0.3513722 0.6279184 0.6670246 0.4009947 0.6279652 0.6669953 0.4009701 0.4066727 0.791951 0.4554462 0.4489412 0.7702929 0.4528802 0.5142704 0.7393198 0.4346631 0.5961802 0.6915768 0.4077876 0.5961797 0.6915771 0.4077878 0.7065811 0.6127887 0.3538829 0.7065939 0.6127786 0.3538751 0.8015999 0.5257254 0.2846935 0.9325879 0.3073855 0.1891927 0.8768694 0.4141029 0.2441697 0.8768753 0.4140934 0.2441644 0.8064287 0.5098909 0.299473 0.8064042 0.509919 0.2994911 0.796905 0.520575 0.3065032 0.8068162 0.5090808 0.2998071 0.8068308 0.5090636 0.299797 0.9325832 0.3073965 0.1891985 0.872835 0.4214057 0.2461223 0.8728056 0.4214527 0.2461463 0.9342831 0.3171821 0.1628206 0.9881254 0.1200471 0.09590059 0.9810773 0.1589826 0.1105081 0.9772129 0.1767523 0.1175318 0.9771233 0.1771435 0.1176863 0.9686396 0.2105546 0.1319249 0.968634 0.2105743 0.1319335 0.9586575 0.2432008 0.1477466 0.9586508 0.2432212 0.1477568 0.9503652 0.2669713 0.1597882 0.872826 0.4214205 0.2461295 0.9304946 0.3157374 0.185714 0.93028 0.316207 0.1859901 0.9432404 0.2855063 0.1696579 0.9342826 0.3171837 0.1628212 0.9649853 0.2297898 0.1264912 0.9649877 0.2297817 0.1264875 0.9804372 0.1709244 0.09761095 0.9804413 0.1709058 0.09760165 0.9804292 0.1709591 0.0976302 0.9770146 0.0948109 0.1909273 0.996978 0.06775051 0.0380091 0.9969781 0.06774967 0.03800863 0.9373451 0.3017233 0.1742046 0.9456342 0.2835944 0.1592171 0.950254 0.2729335 0.1500821 0.9969797 0.06773465 0.03799659 0.9746984 0.1806307 0.1316648 0.9845383 0.1660293 0.05584371 0.9480935 0.2423182 0.2059146 0.9640924 0.2384328 0.1169423 0.96409 0.2384343 0.1169596 0.9882116 0.1324132 0.07684028 0.9882149 0.1323948 0.07682985 0.9921532 0.1080181 0.06296056 0.9982966 0.05028748 0.02958095 0.9995049 0.02601587 0.01769506 0.9953711 0.08303064 0.04839718 0.995372 0.08302307 0.04839277 0.9957374 0.07969254 0.04643207 0.9941695 0.09313458 0.05434137 0.9968132 0.07410949 0.02951264 0.3583906 0.804564 0.4735324 0.2893133 0.825082 0.4853221 0.2246828 0.8396182 0.494529 0.2911403 0.824261 0.4856246 0.2905218 0.824423 0.48572 0.2596535 0.8319181 0.4904003 0.2267661 0.8375182 0.4971321 0.1851282 0.842284 0.5062461 0.1851177 0.8422846 0.5062491 0.1409058 0.8426297 0.5197312 0.2252787 0.8428428 0.4887388 0.08406788 0.8499485 0.5201153 0.2273669 0.8534541 0.4689567 -0.2303087 0.8365318 0.4971643 -0.1902638 0.8407111 0.5069562 0.08494424 0.85737 0.5076428 0.02646279 0.8616837 0.5067551 -0.05445486 0.8603826 0.5067313 -0.0281645 0.8610213 0.5077885 -0.06265163 0.8596729 0.5069886 -0.03303676 0.860893 0.5077125 -0.05440604 0.8600865 0.5072388 -0.02871161 0.8578488 0.5130995 -0.1950212 0.8508411 0.4878897 -0.08659917 0.8493796 0.5206294 -0.1944746 0.8477075 0.4935297 -0.3354349 0.8361937 0.4338934 -0.1417724 0.8423699 0.519917 -0.1423745 0.8423637 0.5197623 -0.4613648 0.7710985 0.4388049 -0.2709239 0.8285856 0.4899449 -0.3017019 0.8208033 0.4850341 -0.3286678 0.813083 0.4804928 -0.3057358 0.8177567 0.4876471 -0.3084647 0.8172275 0.4868149 -0.385625 0.7851634 0.4845738 -0.5837713 0.7254557 0.3645889 -0.461319 0.7711159 0.4388224 -0.410797 0.7901783 0.4548233 -0.3791372 0.8054504 0.4555267 -0.5541232 0.7023059 0.4468936 -0.3252794 0.8160233 0.4778068 -0.438923 0.7709189 0.4615525 -0.438808 0.7709721 0.4615729 -0.4387944 0.7709788 0.4615746 -0.6754168 0.6363662 0.3726261 -0.5731281 0.7059694 0.4160905 -0.4159947 0.7787639 0.469548 -0.4512458 0.7692954 0.4522851 -0.5733498 0.7062956 0.4152305 -0.5396947 0.7253973 0.4272335 -0.5397602 0.7253611 0.4272123 -0.6457945 0.654978 0.3923689 -0.7690659 0.5567942 0.3138757 -0.7690718 0.5567885 0.3138715 -0.8423787 0.4650736 0.2722218 -0.7385367 0.5810254 0.3420135 -0.7385373 0.5810248 0.342013 -0.7663472 0.5536261 0.3258988 -0.7391371 0.5799555 0.3425315 -0.7390614 0.5800261 0.3425757 -0.825617 0.4859451 0.2867299 -0.8423825 0.4650685 0.2722187 -0.8424006 0.465045 0.2722029 -0.8256018 0.4859632 0.2867429 -0.8255937 0.4859733 0.286749 -0.89072 0.3920013 0.2301147 -0.9972516 0.06795549 0.02952027 -0.9949113 0.08685058 0.05107474 -0.9927725 0.1035014 0.06074661 -0.9903202 0.1197595 0.0701698 -0.9903222 0.1197465 0.07016247 -0.9842712 0.1528733 0.08854401 -0.9842739 0.1528598 0.08853679 -0.9789913 0.1709793 0.1110944 -0.9831991 0.1614226 0.0852192 -0.9611724 0.2238245 0.1614009 -0.9505247 0.2447391 0.1913253 -0.9683612 0.229939 0.09697753 -0.9610206 0.2465641 0.1250825 -0.9729635 0.2012409 0.1133318 -0.9729655 0.2012334 0.113328 -0.972964 0.2012392 0.1133307 -0.9541179 0.2626975 0.1436977 -0.9469735 0.2796545 0.158223 -0.9402039 0.294749 0.1707028 -0.8907348 0.391976 0.2301009 -0.9382705 0.2964556 0.1782201 -0.9037373 0.3688534 0.2172697 -0.9339157 0.3080029 0.181482 -0.9432944 0.285438 0.1694724 -0.9478718 0.2736794 0.1632131 -0.9567643 0.2489806 0.1503691 -0.9567592 0.2489954 0.1503764 -0.9641637 0.2258709 0.1391789 -0.9736605 0.1918089 0.123266 -0.9736599 0.1918113 0.123267 -0.9500225 0.2754002 0.1470107 -0.9500268 0.275388 0.1470061 -0.9867642 0.1313394 0.09511268 -0.9088133 0.3721714 0.1885387 -0.9811633 0.1586768 0.1101831 -0.9811761 0.1586138 0.1101591 -0.9987224 0.04355639 0.0256232 -0.9927181 0.103833 0.06106817 -0.9927232 0.1037973 0.06104731 -0.9981485 0.05220574 0.03121262 -0.9983451 0.0493316 0.02955549 -0.9949753 0.1000776 0.002957165 -0.9789936 0.170971 0.1110877 -0.9974405 0.06373172 0.0324195 -0.9851701 0.1500304 0.08325076 -0.9968666 0.07129907 0.03425663 -0.3253397 0.8160037 0.4777994 -0.2991439 0.8230391 0.4828246 -0.3020185 0.8222585 0.482365 -0.1420326 0.8535683 0.5012463 -0.1419763 0.8535702 0.5012591 -0.1037201 0.857265 0.5043201 -0.09693253 0.8578988 0.5045925 -0.06472074 0.859764 0.5065739 -0.1319161 0.8544048 0.502584 -0.2118615 0.8366779 0.5050591 -0.2118191 0.8366919 0.5050537 -0.2106747 0.8371896 0.5047076 -0.1821758 0.8481049 0.4975238 -0.1614668 0.8477771 0.5051756 -0.2532439 0.8465811 0.4681536 -0.1941749 0.8510835 0.4878043 -0.2992746 0.8230041 0.4828033 -0.2679157 0.8311545 0.4872406 -0.3291404 0.8133094 0.4797857 -0.3263441 0.814207 0.4801734 -0.01971721 0.8627517 0.5052433 -0.01821947 0.8624432 0.5058259 -0.07367765 0.8581662 0.5080575 -0.07375937 0.8581568 0.5080615 -0.07394993 0.8581337 0.5080727 0.04173773 0.8595593 0.5093287 0.06214785 0.8586426 0.5087931 0.01596242 0.8601981 0.5097101 0.02561187 0.8600227 0.5096126 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.9898214 0 0.1423145 -0.9898213 0 -0.1423159 -0.9898213 0 -0.1423159 -0.9096335 0 -0.4154118 -0.9096335 0 -0.4154118 -0.7557472 0 -0.6548634 -0.7557472 0 -0.6548634 -0.5406454 0 -0.8412505 -0.5406454 0 -0.8412505 -0.2817315 0 -0.9594932 -0.2817315 0 -0.9594932 0 0 -1 0 0 -1 0.2817315 0 -0.9594932 0.2817315 0 -0.9594932 0.5406454 0 -0.8412505 0.5406454 0 -0.8412505 0.7557472 0 -0.6548634 0.7557472 0 -0.6548634 0.9096335 0 -0.4154118 0.9096335 0 -0.4154118 0.9898213 0 -0.1423159 0.9898213 0 -0.1423159 0.9898214 0 0.1423145 0.9898214 0 0.1423145 0.9096318 0 0.4154157 0.9096318 0 0.4154157 0.7557518 0 0.6548583 0.7557518 0 0.6548583 0.540638 0 0.8412554 0.540638 0 0.8412554 0.2817315 0 0.9594932 0.2817315 0 0.9594932 0 0 1 0 0 1 -0.2817315 0 0.9594932 -0.2817315 0 0.9594932 -0.540638 0 0.8412554 -0.540638 0 0.8412554 -0.7557518 0 0.6548583 -0.7557518 0 0.6548583 -0.9096318 0 0.4154157 -0.9096318 0 0.4154157 -0.9898214 0 0.1423145 -0.9898214 0 0.1423145 -0.9898213 0 -0.1423159 -0.9898213 0 -0.1423159 -0.9096335 0 -0.4154118 -0.9096335 0 -0.4154118 -0.7557472 0 -0.6548634 -0.7557472 0 -0.6548634 -0.5406454 0 -0.8412505 -0.5406454 0 -0.8412505 -0.2817315 0 -0.9594932 -0.2817315 0 -0.9594932 0 0 -1 0 0 -1 0.2817315 0 -0.9594932 0.2817315 0 -0.9594932 0.5406454 0 -0.8412505 0.5406454 0 -0.8412505 0.7557472 0 -0.6548634 0.7557472 0 -0.6548634 0.9096335 0 -0.4154118 0.9096335 0 -0.4154118 0.9898213 0 -0.1423159 0.9898213 0 -0.1423159 0.9898214 0 0.1423145 0.9898214 0 0.1423145 0.9096318 0 0.4154157 0.9096318 0 0.4154157 0.7557518 0 0.6548583 0.7557518 0 0.6548583 0.540638 0 0.8412554 0.540638 0 0.8412554 0.2817315 0 0.9594932 0.2817315 0 0.9594932 0 0 1 0 0 1 -0.2817315 0 0.9594932 -0.2817315 0 0.9594932 -0.540638 0 0.8412554 -0.540638 0 0.8412554 -0.7557518 0 0.6548583 -0.7557518 0 0.6548583 -0.9096318 0 0.4154157 -0.9096318 0 0.4154157 -0.9898214 0 0.1423145 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.991445 0 0.1305252 0.9914449 0 -0.1305264 0.9914449 0 -0.1305264 0.923879 0 -0.3826845 0.923879 0 -0.3826845 0.7933526 0 -0.6087624 0.7933526 0 -0.6087624 0.608767 0 -0.7933492 0.608767 0 -0.7933492 0.3826816 0 -0.9238803 0.3826816 0 -0.9238803 0.1305255 0 -0.9914449 0.1305255 0 -0.9914449 -0.1305255 0 -0.9914449 -0.1305255 0 -0.9914449 -0.3826816 0 -0.9238803 -0.3826816 0 -0.9238803 -0.608767 0 -0.7933492 -0.608767 0 -0.7933492 -0.7933526 0 -0.6087624 -0.7933526 0 -0.6087624 -0.923879 0 -0.3826845 -0.923879 0 -0.3826845 -0.9914449 0 -0.1305264 -0.9914449 0 -0.1305264 -0.991445 0 0.1305252 -0.991445 0 0.1305252 -0.923879 0 0.3826845 -0.923879 0 0.3826845 -0.7933526 0 0.6087624 -0.7933526 0 0.6087624 -0.608761 0 0.7933537 -0.608761 0 0.7933537 -0.3826816 0 0.9238803 -0.3826816 0 0.9238803 -0.1305348 0 0.9914438 -0.1305348 0 0.9914438 0.1305348 0 0.9914438 0.1305348 0 0.9914438 0.3826816 0 0.9238803 0.3826816 0 0.9238803 0.608761 0 0.7933537 0.608761 0 0.7933537 0.7933526 0 0.6087624 0.7933526 0 0.6087624 0.923879 0 0.3826845 0.923879 0 0.3826845 0.991445 0 0.1305252 0.991445 0 0.1305252 0.9914449 0 -0.1305264 0.9914449 0 -0.1305264 0.923879 0 -0.3826845 0.923879 0 -0.3826845 0.7933526 0 -0.6087624 0.7933526 0 -0.6087624 0.608767 0 -0.7933492 0.608767 0 -0.7933492 0.3826816 0 -0.9238803 0.3826816 0 -0.9238803 0.1305255 0 -0.9914449 0.1305255 0 -0.9914449 -0.1305255 0 -0.9914449 -0.1305255 0 -0.9914449 -0.3826816 0 -0.9238803 -0.3826816 0 -0.9238803 -0.608767 0 -0.7933492 -0.608767 0 -0.7933492 -0.7933526 0 -0.6087624 -0.7933526 0 -0.6087624 -0.923879 0 -0.3826845 -0.923879 0 -0.3826845 -0.9914449 0 -0.1305264 -0.9914449 0 -0.1305264 -0.991445 0 0.1305252 -0.991445 0 0.1305252 -0.923879 0 0.3826845 -0.923879 0 0.3826845 -0.7933526 0 0.6087624 -0.7933526 0 0.6087624 -0.608761 0 0.7933537 -0.608761 0 0.7933537 -0.3826816 0 0.9238803 -0.3826816 0 0.9238803 -0.1305348 0 0.9914438 -0.1305348 0 0.9914438 0.1305348 0 0.9914438 0.1305348 0 0.9914438 0.3826816 0 0.9238803 0.3826816 0 0.9238803 0.608761 0 0.7933537 0.608761 0 0.7933537 0.7933526 0 0.6087624 0.7933526 0 0.6087624 0.923879 0 0.3826845 0.923879 0 0.3826845 0.991445 0 0.1305252 -0.7713736 0.551595 0.317373 -0.9393426 0.3394125 0.04934239 -0.9049234 0.4031868 0.1362128 -0.8769772 0.4756857 0.06807553 -0.8913453 0.4374921 0.1187611 -0.8913337 0.4374921 0.1188485 -0.9347507 0.3550533 0.01335841 -0.9386913 0.3432996 0.03168785 -0.9393408 0.339416 0.04935216 -0.9593169 0.2762388 0.05833554 -0.9593167 0.2762395 0.05833739 -0.9611548 0.2705852 0.05445444 -0.9611374 0.2706455 0.05445957 -0.9600747 0.2744467 0.05418151 -0.9600725 0.2744549 0.05417835 -0.9465458 0.2128177 0.242404 -0.9548746 0.1936721 0.2251788 -0.9677428 0.1498629 0.2025217 -0.9566469 0.1978033 0.2137773 -0.956962 0.2707319 0.1045365 -0.9566904 0.2702665 0.1081646 -0.8214769 0.2570979 0.5089955 -0.9147431 0.1416732 0.3783833 -0.8583859 0.2342339 0.4564079 -0.9167163 0.2575926 0.3054136 -0.9167169 0.2575922 0.3054121 -0.7212498 0.375685 0.5819446 -0.7212435 0.3757103 0.5819361 -0.7378987 0.278182 0.6149147 -0.7093176 0.1171907 0.695079 -0.6028031 0.3986225 0.6911793 -0.7714525 0.1037355 0.6277737 -0.7966313 0.02462768 0.6039636 -0.7091083 0.1173802 0.6952607 -0.6052896 0.5993465 0.5238401 -0.62633 0.5796846 0.5212261 -0.6073679 0.7306315 0.3119003 -0.5864359 0.7803953 0.2169703 -0.5651069 0.7444419 0.3556129 -0.8773838 0.4384871 0.1947481 -0.8773899 0.4384822 0.1947315 -0.7756792 0.5282207 0.3454051 -0.7930885 0.5683902 0.218959 -0.7931048 0.5684043 0.2188643 -0.08154016 -0.9955457 0.04732745 -0.0152229 -0.9996797 -0.02022224 -0.1125777 -0.9927266 0.04266345 -0.09969985 -0.9932953 0.05851769 -0.01977074 -0.999738 0.01153856 -0.01960134 -0.9997379 0.01183247 -0.002577781 -0.9999955 0.001560449 -0.002539515 -0.9999953 0.001714348 -0.1225591 -0.9920409 0.02888345 -0.09772521 -0.9935958 0.05672019 -0.09774684 -0.9935957 0.05668288 -0.1675373 -0.9783613 0.1214097 -0.04427683 -0.9982266 0.03978961 -0.03909945 -0.9988659 0.02717006 -0.05892258 -0.9971138 0.0478788 -0.07277506 -0.9960656 0.05056905 -0.07277351 -0.9960655 0.05057126 -0.4755534 -0.7677407 0.429445 -0.5018814 -0.6693027 0.5478585 -0.3899638 -0.8488987 0.3567903 -0.4497487 -0.6707678 0.5897428 -0.2479326 -0.9387671 0.2392603 -0.2511548 -0.9353923 0.2489228 -0.126282 -0.990383 0.05651825 -0.2029606 -0.9364204 0.2862233 -0.02523303 -0.9994243 0.02267813 -0.03992074 -0.9981282 0.04633283 -0.685445 -0.2424415 0.6865765 -0.7275137 -0.419498 0.5429043 -0.72754 -0.4194973 0.54287 -0.7275049 -0.4193702 0.543015 -0.7066401 -0.2478322 0.662751 -0.7065387 -0.2472282 0.6630846 -0.6847879 -0.08837395 0.7233642 -0.6560305 -0.2434971 0.714376 -0.7275679 -0.4193657 0.5429341 -0.7077614 -0.4692398 0.5280982 -0.6657117 -0.6312375 0.3979538 -0.6657114 -0.6312374 0.3979545 -0.6445996 -0.6312713 0.4312632 -0.5720189 -0.7657665 0.2939323 -0.3075073 -0.9346985 0.1782637 -0.3074883 -0.9347054 0.1782602 -0.3041082 -0.9346566 0.1842154 -0.3294758 -0.9228387 0.1995357 -0.3291224 -0.9229921 0.1994091 -0.4715764 -0.8470777 0.2451021 -0.4567848 -0.8471363 0.2714917 -0.5573701 -0.7614718 0.3309067 -0.55742 -0.7614338 0.33091 -0.076581 -0.9956417 0.05322617 -0.1095702 -0.9933934 0.03411436 -0.1912631 -0.9673812 0.1661084 -0.220426 -0.9674416 0.1243739 -0.2999156 -0.9158955 0.2668066 -0.09624487 -0.9915931 0.08648729 -0.05641597 -0.9980992 0.02480447 -0.2362412 -0.9387505 0.2508735 -0.1716423 -0.9782631 0.1163624 -0.3719854 -0.8491649 0.3748946 -0.3168097 -0.9159724 0.2462241 -0.427715 -0.8136107 0.3938241 -0.443136 -0.8140373 0.3754648 -0.3766405 -0.8939232 0.2429882 -0.2380752 -0.9578685 0.1606488 -0.2252398 -0.9573487 0.1809712 -0.08155483 -0.9955458 0.04730385 -0.1073195 -0.9923493 0.06103718 -0.1282848 -0.9914569 0.02358412 -0.2472107 -0.9501888 0.1898111 -0.2854571 -0.9503448 0.1239317 -0.3871782 -0.8791247 0.2779079 -0.4166784 -0.8792967 0.2306869 -0.5702589 -0.6789686 0.4623922 -0.5279344 -0.6776722 0.511904 -0.5326401 -0.6668569 0.5211491 -0.08581554 -0.995067 0.04977315 -0.09548097 -0.993939 0.05448657 -0.07872617 -0.9909793 0.1084538 -0.1283549 -0.9914868 0.02188396 -0.2530274 -0.947521 0.1953999 -0.2957004 -0.9477401 0.1197907 -0.4051817 -0.8706547 0.2789051 -0.4407949 -0.8708242 0.217635 -0.5282619 -0.7681989 0.3616764 -0.5509427 -0.768413 0.325582 -0.6682277 -0.5209156 0.5311485 -0.6137524 -0.5196331 0.5943816 -0.6598056 -0.2433413 0.7109442 -0.08952122 0.994789 0.04879409 -0.1922549 0.9702301 0.1472808 -0.1203647 0.9927264 -0.002555012 -0.1157435 0.992596 0.03683197 -0.1075364 0.9930046 0.0487619 -0.1534767 0.9881172 -0.008324682 -0.1132142 0.9927493 0.04039257 -0.1106663 0.9929195 0.04317206 -0.4714648 0.8471338 0.2451229 -0.3381639 0.9190807 0.2023261 -0.314144 0.929411 0.193672 -0.3024266 0.9382596 0.1679499 -0.3024287 0.9382595 0.1679462 -0.4714689 0.8471337 0.2451153 -0.5134825 0.7931495 0.3274898 -0.55732 0.7615147 0.3308925 -0.6647171 0.6358771 0.392188 -0.6641398 0.63625 0.3925613 -0.6155939 0.6800116 0.398282 -0.5702683 0.7654718 0.2980719 -0.5571764 0.7615131 0.3311377 -0.6846411 0.5803433 0.4409856 -0.6937146 0.5767899 0.4313624 -0.5891833 0.6924095 0.4164521 -0.6648893 0.635783 0.3920487 -0.6649432 0.6357817 0.3919593 -0.6643797 0.6360918 0.3924117 -0.6926977 0.471121 0.5460906 -0.6713206 0.4910296 0.5551744 -0.6846849 0.580317 0.4409523 -0.6847346 0.5803402 0.4408445 -0.6245481 0.3240706 0.7105758 -0.7225759 0.3236309 0.6108578 -0.6658565 0.3720412 0.6466997 -0.6927024 0.4711495 0.54606 -0.6926754 0.4711213 0.5461186 -0.549826 0.4621152 0.6958023 -0.667881 0.1385314 0.731262 -0.6200338 -0.3812005 0.6857436 -0.6566904 0.138802 0.741277 -0.5805941 0.4615577 0.6707272 -0.169361 0.9734898 0.1537349 -0.4203335 0.7817549 0.4606291 -0.4203289 0.7817608 0.4606232 -0.1468762 0.9782302 0.1466048 -0.05084502 0.9978344 0.04172962 -0.05084675 0.9978343 0.04172754 -0.1544792 0.9783991 0.1373736 -0.1106465 0.9909025 0.07661294 -0.1538771 0.9740954 0.1657106 -0.09122592 0.9930108 0.07488203 -0.15192 0.9741392 0.167252 -0.1832764 0.9722879 0.1451415 -0.1109353 0.9912497 0.07153564 -0.1273105 0.9863501 0.1044296 0.01169604 0.9999102 -0.006539642 0.01166224 0.9999102 -0.006598591 -0.07247328 0.996575 0.03982245 -0.08781039 0.9945266 0.05662453 -0.4667933 0.8137636 0.3462553 -0.427715 0.8136107 0.3938241 -0.5169977 0.7219259 0.4599307 -0.4665088 0.7222709 0.5105823 -0.4150243 0.782007 0.4649946 -0.5185111 0.7859379 0.3368199 -0.4913268 0.7858303 0.3755909 -0.589055 0.6785923 0.4387789 -0.5416391 0.6783965 0.4963921 -0.6148936 0.5663391 0.5487859 -0.5512384 0.5665602 0.6124916 -0.6037444 0.4606543 0.6506077 -0.002659261 0.9999952 0.001585781 -0.002648949 0.9999952 0.001603901 -0.09434866 0.9942307 0.05102771 -0.05633103 0.9910938 0.120665 -0.1142272 0.9932276 0.02123862 -0.2251664 0.9573441 0.1810863 -0.2380752 0.9578685 0.1606488 -0.1046823 0.9940726 0.0293498 -0.1548911 0.9828696 0.09988003 -0.6189513 0.7070688 0.3419839 -0.704369 0.7097085 -0.01334589 -0.5282619 0.7681989 0.3616764 -0.4407949 0.8708243 0.217635 -0.4051817 0.8706547 0.2789051 -0.2957003 0.9477402 0.1197907 -0.2530274 0.947521 0.1953999 -0.1283549 0.9914868 0.02188396 -0.08139294 0.9912556 0.1038638 -0.09423506 0.9940793 0.05409568 -0.01809328 0.9997816 0.01045465 -0.01809245 0.9997816 0.01045608 -0.09785282 0.9938224 0.05236089 -0.06805509 0.9891818 0.1299534 -0.1282848 0.9914569 0.02358412 -0.2472106 0.9501888 0.189811 -0.2854571 0.9503448 0.1239317 -0.3871781 0.8791247 0.2779079 -0.3960582 0.8794602 0.2639843 -0.3744164 0.8952136 0.2416713 -0.3532176 0.8951392 0.2719619 -0.3232884 0.9158277 0.2382106 -0.3168097 0.9159724 0.2462241 -0.3855465 0.8272916 0.408586 -0.4323735 0.7809578 0.4507305 0.938605 -0.2436566 0.2442377 0.5975178 -0.2436553 -0.7639402 0.05108076 -0.9981176 0.03393959 0.0559954 -0.9981171 0.02504009 0.06112354 -0.9981182 -0.00490278 0.05146664 -0.9981172 -0.03336381 0.02929472 -0.9981166 -0.05389899 0 -0.9981172 -0.06133496 -0.01012271 -0.9981173 -0.06049305 -0.03779035 -0.9981167 -0.04831981 -0.05627053 -0.9981173 -0.02440333 -0.05108225 -0.9981176 0.03394156 0.1304152 -0.9742806 0.1837638 0.03911852 -0.998127 0.04703313 0.03911852 -0.998127 0.04703521 0.384499 -0.783167 0.488682 0.3847855 -0.7828044 0.4890372 0.1709173 -0.9734097 0.1525152 0.2327011 -0.9364907 0.2623649 0.1304265 -0.9742771 0.1837747 0.1304036 -0.9742848 0.18375 0.5545232 -0.4621267 0.6920569 0.5544981 -0.4622021 0.6920267 0.4914472 -0.6707014 0.5555531 0.3848211 -0.7827738 0.4890581 0.3847932 -0.7828016 0.4890357 0.5545169 -0.462142 0.6920518 0.6384496 -0.2444315 0.7298188 0.633367 -0.1388809 0.7612873 -0.474579 -0.6703739 0.5704154 -0.6202128 -0.2441877 0.7454586 -0.6201945 -0.244265 0.7454484 -0.6201927 -0.2442408 0.7454578 -0.620193 -0.2442341 0.7454599 -0.474537 -0.6704561 0.5703536 -0.4745544 -0.6704041 0.5704002 -0.4745206 -0.6704498 0.5703747 -0.224455 -0.9363922 0.2697954 -0.2244496 -0.9363963 0.2697857 -0.2244535 -0.9363945 0.2697886 -0.03907716 -0.9981312 0.04697978 -0.03911548 -0.998128 0.04701602 -0.03911578 -0.9981269 0.04703772 -0.04477679 -0.9981173 0.04191517 -0.05599212 -0.9981172 0.02503973 -0.05108761 -0.9981171 0.03394508 -0.05598998 -0.9981173 0.02503842 -0.05935704 -0.9981173 0.01544606 -0.06449776 -0.9979044 -0.005173146 -0.06112462 -0.9981302 -6.46047e-6 -0.06109333 -0.9981173 0.005429267 -0.06112438 -0.9981181 -0.004902362 -0.05952954 -0.9981172 -0.01477301 -0.05147069 -0.998117 -0.03336554 -0.05627399 -0.9981171 -0.02440416 -0.05146712 -0.9981173 -0.0333625 -0.04524922 -0.9981173 -0.04140579 -0.03778779 -0.9981173 -0.04831135 -0.02928632 -0.9981175 -0.05388796 -0.01998412 -0.9981174 -0.0579847 -0.01013046 -0.9981179 -0.06048321 0.01013123 -0.9981173 -0.06049245 -1.57555e-6 -0.9981172 -0.06133508 0.01013845 -0.9981174 -0.06048923 0.01998323 -0.9981174 -0.05798691 0.03778523 -0.9981175 -0.04831016 0.02928656 -0.9981174 -0.05388754 0.03778797 -0.9981175 -0.0483064 0.05626803 -0.9981175 -0.02440273 0.05146378 -0.9981175 -0.03336119 0.05627036 -0.9981172 -0.02440387 0.06109333 -0.9981173 0.005428493 0.06112462 -0.9981302 -8.63343e-6 0.06448847 -0.997905 -0.005172729 0.06109321 -0.9981173 0.005428612 0.05935752 -0.9981173 0.01544553 0.05108296 -0.9981175 0.03394067 0.04477393 -0.9981176 0.04191201 -0.05108481 -0.9981173 0.03394287 -0.2929669 -0.9360973 0.1946593 -0.2929615 -0.9360994 0.1946571 -0.6187149 -0.6694673 0.4111028 -0.6187136 -0.6694687 0.4111024 -0.05599087 -0.9981173 0.02503925 -0.3210921 -0.9360987 0.1435933 -0.3210984 -0.9360964 0.1435947 -0.6781209 -0.6694691 0.3032546 -0.6781247 -0.6694649 0.3032551 -0.06191325 -0.99807 -0.004795849 -0.3506925 -0.9360967 -0.02716493 -0.3506929 -0.9360966 -0.02716505 -0.74062 -0.6694706 -0.05736929 -0.7406188 -0.6694718 -0.05736881 -0.0514661 -0.9981173 -0.03336209 -0.2951554 -0.9360963 -0.1913297 -0.2951524 -0.9360978 -0.1913267 -0.6233322 -0.66947 -0.4040629 -0.6233338 -0.6694674 -0.4040648 -0.04525381 -0.9981169 -0.04141044 -0.2594919 -0.9360982 -0.2374535 -0.2594898 -0.9360994 -0.2374507 -0.5480253 -0.669467 -0.5014801 -0.5480296 -0.6694583 -0.501487 -0.01998454 -0.9981173 -0.05798631 -0.1146095 -0.9360974 -0.3325454 -0.1146109 -0.9360933 -0.3325564 -0.2420422 -0.6694567 -0.7023128 -0.2420407 -0.6694904 -0.7022812 0.01013231 -0.998117 -0.06049704 0.05810487 -0.9360905 -0.3469271 0.05809497 -0.9361005 -0.3469018 0.1226928 -0.6694737 -0.7326334 0.1226997 -0.6694566 -0.7326477 0.019988 -0.9981166 -0.05799865 0.1146025 -0.9361004 -0.3325393 0.1146073 -0.9360969 -0.3325475 0.2420412 -0.669457 -0.7023129 0.2420247 -0.6694875 -0.7022895 0.05146795 -0.9981172 -0.03336435 0.2951499 -0.9360973 -0.1913326 0.2951547 -0.9360955 -0.1913344 0.6233299 -0.6694652 -0.4040746 0.6233267 -0.6694687 -0.4040735 0.06191128 -0.9980702 -0.004796445 0.3506922 -0.9360966 -0.0271691 0.3506924 -0.9360964 -0.0271691 0.7406188 -0.6694712 -0.05737775 0.7406197 -0.6694703 -0.05737757 0.0510807 -0.9981176 0.03393954 0.2929723 -0.9360956 0.1946595 0.2929762 -0.9360935 0.1946635 0.6187149 -0.6694716 0.4110956 0.6187155 -0.6694705 0.4110963 -0.04477357 -0.9981175 0.04191249 -0.2567874 -0.9360974 0.2403786 -0.2567872 -0.9360975 0.2403784 -0.5423196 -0.6694517 0.5076652 -0.542307 -0.6694666 0.5076589 -0.7080386 -0.2436702 0.6628018 -0.7080382 -0.2436712 0.6628017 -0.7080539 -0.2436412 0.6627961 -0.8078002 -0.2436443 0.5367462 -0.8077979 -0.2436677 0.5367389 -0.8078184 -0.2436643 0.5367096 -0.8853628 -0.2436619 0.3959313 -0.885365 -0.2436549 0.3959307 -0.9386032 -0.243655 0.2442462 -0.05935788 -0.9981173 0.01544624 -0.3404068 -0.9360964 0.0885815 -0.3404068 -0.9360964 0.0885815 -0.7188999 -0.6694672 0.1870739 -0.7188963 -0.669471 0.187074 -0.9386034 -0.2436537 0.244247 -0.9386014 -0.2436596 0.2442485 -0.966054 -0.2436576 0.08585256 -0.7399221 -0.6694709 0.06575638 -0.7399226 -0.6694706 0.06575626 -0.350363 -0.9360964 0.03113645 -0.3503623 -0.9360966 0.03113651 -0.06109404 -0.9981173 0.005429387 -0.06109356 -0.9981173 0.005429387 -0.9660538 -0.2436586 0.08585268 -0.9660539 -0.2436583 0.08585256 -0.9669651 -0.2436556 -0.07490181 -0.966965 -0.2436563 -0.07490164 -0.9413099 -0.2436566 -0.2335957 -0.05952858 -0.9981173 -0.01477271 -0.3413881 -0.9360966 -0.08471947 -0.341391 -0.9360954 -0.08472084 -0.7209672 -0.6694735 -0.178918 -0.7209645 -0.6694769 -0.1789163 -0.9413091 -0.2436581 -0.2335976 -0.9413098 -0.2436551 -0.2335986 -0.05626946 -0.9981174 -0.02440255 -0.3227089 -0.9360945 -0.1399503 -0.3227047 -0.9360963 -0.1399474 -0.6815032 -0.669481 -0.2955476 -0.6815113 -0.6694701 -0.2955543 -0.8897916 -0.2436542 -0.3858802 -0.8897931 -0.2436442 -0.385883 -0.8897923 -0.2436596 -0.3858753 -0.8138281 -0.2436605 -0.527554 -0.8138342 -0.243642 -0.5275532 -0.8138263 -0.243637 -0.5275679 -0.7155098 -0.2436319 -0.6547436 -0.7155086 -0.2436577 -0.6547353 -0.5975281 -0.2436578 -0.7639314 -0.03778612 -0.9981175 -0.04830902 -0.2167022 -0.9360999 -0.2770505 -0.2167056 -0.9360972 -0.2770574 -0.4576659 -0.6694562 -0.5851243 -0.457661 -0.6694701 -0.585112 -0.5975291 -0.2436561 -0.7639311 -0.597531 -0.2436794 -0.7639221 -0.4631248 -0.243682 -0.8521352 -0.3547254 -0.6694579 -0.6526837 -0.354723 -0.6694701 -0.6526725 -0.1679647 -0.9360973 -0.3090466 -0.1679648 -0.9360972 -0.3090468 -0.02929216 -0.9981168 -0.05389612 -0.02928787 -0.9981175 -0.05388629 -0.4631252 -0.2436882 -0.8521332 -0.4631116 -0.243662 -0.8521481 -0.3160193 -0.2436623 -0.9169299 -0.3160158 -0.2436315 -0.9169393 -0.160176 -0.2436296 -0.9565502 -0.01013153 -0.9981172 -0.06049233 -0.05810385 -0.936093 -0.3469204 -0.05810445 -0.9360984 -0.3469057 -0.1227082 -0.6694919 -0.7326142 -0.1227061 -0.6694737 -0.7326309 -0.1602095 -0.2436125 -0.9565489 -0.1602149 -0.2436416 -0.9565407 -7.80816e-7 -0.9981177 -0.06132745 -4.4783e-6 -0.9360986 -0.3517378 0 -0.9360905 -0.3517591 0 -0.6694737 -0.7428358 0 -0.6694736 -0.7428358 0 -0.2436414 -0.9698654 0 -0.2436414 -0.9698654 -2.32523e-5 -0.2436984 -0.9698511 0.1601997 -0.2436981 -0.9565288 0.1601953 -0.2436738 -0.9565358 0.1601718 -0.2436857 -0.9565366 0.3159953 -0.243685 -0.9169321 0.3160018 -0.2436616 -0.9169362 0.4631142 -0.2436615 -0.8521469 0.02928662 -0.9981174 -0.05388778 0.167961 -0.9360967 -0.30905 0.1679615 -0.9360964 -0.3090507 0.3547072 -0.6694864 -0.6526643 0.3547192 -0.6694684 -0.6526764 0.463123 -0.2436785 -0.8521372 0.463122 -0.2436812 -0.852137 0.03779107 -0.9981169 -0.04831677 0.216704 -0.9360965 -0.2770609 0.216698 -0.9360993 -0.2770559 0.4576505 -0.6694687 -0.585122 0.4576618 -0.669454 -0.5851301 0.5975148 -0.2436787 -0.763935 0.5975262 -0.2436422 -0.7639377 0.7155015 -0.2436554 -0.654744 0.5480225 -0.6694643 -0.5014867 0.5480294 -0.6694561 -0.5014901 0.2594921 -0.9360976 -0.2374557 0.2594887 -0.936099 -0.2374536 0.04524904 -0.9981172 -0.04140663 0.04524618 -0.9981175 -0.0414043 0.7154965 -0.2436705 -0.6547437 0.8138164 -0.2436683 -0.5275686 0.8138203 -0.2436707 -0.5275616 0.8138241 -0.2436587 -0.5275611 0.8897869 -0.2436582 -0.3858885 0.05626946 -0.9981173 -0.02440321 0.3227043 -0.9360957 -0.1399521 0.3227009 -0.936097 -0.1399514 0.6815086 -0.6694693 -0.2955619 0.6815117 -0.669466 -0.2955623 0.8897869 -0.2436584 -0.3858884 0.8897891 -0.2436524 -0.3858869 0.941307 -0.2436535 -0.233611 0.7209662 -0.669472 -0.1789274 0.7209701 -0.6694678 -0.1789273 0.3413873 -0.9360964 -0.08472406 0.341386 -0.9360969 -0.084724 0.05952638 -0.9981175 -0.01477301 0.05952835 -0.9981172 -0.01477342 0.9413054 -0.2436589 -0.2336117 0.9413079 -0.2436547 -0.2336063 0.9669645 -0.2436548 -0.07491308 0.9669643 -0.2436554 -0.0749132 0.9660548 -0.2436586 0.08584046 0.06109374 -0.9981173 0.005428552 0.350363 -0.9360964 0.03113198 0.350363 -0.9360964 0.03113198 0.7399227 -0.6694714 0.0657469 0.7399228 -0.6694712 0.0657469 0.9660549 -0.2436583 0.08584022 0.9660559 -0.2436541 0.08584141 0.05936038 -0.998117 0.01544642 0.3404073 -0.9360965 0.08857882 0.3404065 -0.9360968 0.08857846 0.7188969 -0.6694723 0.1870669 0.7188935 -0.6694766 0.1870648 0.9386076 -0.2436472 0.2442371 0.9386041 -0.2436656 0.2442324 0.8853679 -0.2436568 0.395923 0.6781222 -0.6694716 0.3032459 0.6781159 -0.6694803 0.3032405 0.321102 -0.9360957 0.1435906 0.3210993 -0.936097 0.1435887 0.05598676 -0.9981176 0.02503603 0.05599629 -0.9981169 0.02504092 0.8853672 -0.2436617 0.3959215 0.8076772 -0.2436592 0.5369246 0.8078087 -0.2436371 0.5367364 0.8078051 -0.2436757 0.5367245 0.7080461 -0.2436804 0.6627899 0.04477691 -0.9981174 0.04191511 0.256798 -0.9360927 0.2403855 0.2567895 -0.9360981 0.2403734 0.5423148 -0.6694704 0.5076456 0.5423228 -0.6694537 0.507659 0.7080463 -0.2436803 0.6627899 0.7080457 -0.2436713 0.6627937 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.6148648 -0.5619364 0.5533253 0.1504399 -0.9771265 0.1503046 0.05277335 -0.9976664 0.04332333 0.153903 -0.9740815 0.1657678 0.1123997 -0.9927495 0.0426014 0.08952254 -0.9947944 0.04868274 0.2561604 -0.9554145 0.1468503 0.1757102 -0.9756553 0.1312348 0.1231287 -0.9921914 0.01988619 0.1132397 -0.9926971 0.04158222 0.2703541 -0.9573549 0.1018841 0.3147019 -0.9292021 0.1937681 0.2700536 -0.9575073 0.1012471 0.2818648 -0.950971 0.1273044 0.2818872 -0.9509696 0.1272643 0.5562016 -0.7610871 0.3337459 0.5574501 -0.7612671 0.3312429 0.5127931 -0.7941057 0.3262502 0.4730149 -0.845785 0.246789 0.4730171 -0.8457849 0.2467852 0.6700673 -0.5841323 0.4580385 0.6952605 -0.5726831 0.434335 0.6538395 -0.6244467 0.4272707 0.6671273 -0.6286336 0.3997013 0.6671002 -0.6286342 0.3997455 0.7095409 -0.476585 0.5190555 0.6975269 -0.3067314 0.6475895 0.7507563 -0.2563318 0.6088178 0.6681735 -0.3448355 0.6592668 0.7095534 -0.4765961 0.519028 0.7095409 -0.476585 0.5190553 0.656968 -0.1386322 0.7410628 0.6912909 0.01708233 0.7223747 0.5393356 -0.4622386 0.7038841 0.6251875 -0.3064919 0.7177768 0.6029078 -0.4606069 0.6514165 0.5630796 -0.5624857 0.6054348 0.5797048 -0.4616475 0.6714342 0.4129862 -0.7820219 0.4667806 0.05277317 -0.9976663 0.04332357 0.1099408 -0.9910911 0.07517606 0.1576718 -0.9772891 0.1415821 0.1689912 -0.9735096 0.1540166 0.4199272 -0.781705 0.4610841 0.1538853 -0.9740888 0.165742 0.0730884 -0.9955193 0.05999559 0.1519315 -0.974134 0.1672708 0.1864919 -0.9712103 0.1482275 0.1120405 -0.9910721 0.07227033 0.1292818 -0.9859163 0.1060917 -0.002588868 -0.9999958 -0.001378655 -0.002580344 -0.9999958 -0.001393437 0.07158434 -0.9967058 0.03812164 0.08962917 -0.9942958 0.0578143 0.004024505 -0.999989 0.002405762 0.004030823 -0.9999891 0.002394556 0.09559923 -0.9940887 0.05146247 0.07779639 -0.9928955 0.09003484 0.1167901 -0.9928942 0.02282649 0.2281973 -0.9562307 0.1831638 0.240979 -0.9567483 0.1629778 0.1066244 -0.9938344 0.0304026 0.1563684 -0.9825381 0.1008358 0.09447294 -0.9940491 0.05423265 0.08237183 -0.9911946 0.1036731 0.1290497 -0.9913908 0.02214318 0.2545049 -0.9469394 0.1962983 0.2972156 -0.9471595 0.1206299 0.4072079 -0.869284 0.2802268 0.4427522 -0.8694507 0.2191485 0.5304087 -0.7658383 0.3635357 0.5354769 -0.766003 0.3556742 0.52091 -0.7831565 0.3395863 0.4932119 -0.7830442 0.3789246 0.4691334 -0.8108253 0.3499659 0.4291769 -0.8106698 0.3982732 0.4321295 -0.780938 0.4509986 0.4679996 -0.7186634 0.514295 0.5179143 -0.7182562 0.464621 0.5421249 -0.6747624 0.5007958 0.5905503 -0.6749602 0.4423563 0.6405816 -0.5732002 0.5109763 0.6700595 -0.5841324 0.4580498 0.01779067 -0.9997889 0.01028233 0.01779103 -0.9997888 0.01028168 0.09863555 -0.9937301 0.05264467 0.07489848 -0.989717 0.121863 0.1299678 -0.991216 0.02447861 0.2495572 -0.9492791 0.1912859 0.2877637 -0.9494392 0.125528 0.3897863 -0.8773457 0.279877 0.3984624 -0.8776716 0.2663087 0.3774254 -0.893166 0.2445498 0.355829 -0.8930887 0.2752783 0.3264344 -0.9137261 0.2419609 0.3192616 -0.9138838 0.2507762 0.386431 -0.8257978 0.4107665 0.4318144 -0.781279 0.45071 0.1548436 0.9253682 -0.3460017 0.4709298 0.6327275 -0.6147204 -0.5253261 0.1166142 -0.8428723 0.5009528 0.2210701 -0.8367641 0.5933716 0.1801095 -0.7845193 0.6271231 0.1799325 -0.757853 0.5578011 0.2150878 -0.8016204 0.5996794 0.1373749 -0.7883608 0.5997756 0.1370714 -0.7883405 0.5981897 0.1442596 -0.7882629 0.5933307 0.1800713 -0.7845592 0.5021568 0.2200812 -0.836303 0.5355697 0.1767731 -0.8257822 0.5330857 0.1813439 -0.8263983 0.1599647 0.3387114 -0.9271925 0.2141281 0.2672033 -0.9395486 0.2163385 0.2576946 -0.9416959 0.2686986 0.3640958 -0.8917598 -0.2379112 0.2638068 -0.934775 -0.3691433 0.5657842 -0.737307 -0.4946827 0.4653505 -0.7339876 -0.1153649 0.3897991 -0.9136452 -0.1638339 0.2491444 -0.954508 -0.4441003 0.3483181 -0.8254994 -0.4441369 0.3481701 -0.8255422 -0.4588 0.2917395 -0.8392798 -0.5155214 0.3553614 -0.7797153 -0.5252825 0.1164082 -0.8429279 -0.5253422 0.1166649 -0.8428552 -0.52535 0.1165849 -0.8428614 -0.3691073 0.5658562 -0.7372697 -0.389047 0.6218129 -0.6796993 -0.4485725 0.5779688 -0.6817145 -0.2748312 0.7500721 -0.6015478 -0.2722971 0.7531385 -0.5988629 -0.2809048 0.7514212 -0.5970417 -0.1208077 0.8771836 -0.464709 -0.1207823 0.8772004 -0.4646838 -0.1970139 0.8679429 -0.4559172 -0.1772331 0.8915306 -0.4168475 -0.2809311 0.7513912 -0.5970668 -0.06508833 0.9768787 -0.2036458 -0.05786877 0.9381461 -0.3413693 0.04825663 0.9495389 -0.3099147 0.02265506 0.9974039 -0.06835353 0.3640252 0.9218506 -0.132956 0.04827672 0.9495446 -0.3098945 0.04557794 0.9693635 -0.2413652 0.3638991 0.9218937 -0.1330012 0.6773088 0.2408608 -0.695154 0.6281431 0.1682434 -0.7596911 0.6281526 0.1682488 -0.7596819 0.6614627 0.1715356 -0.7300977 0.6625613 0.1884124 -0.724923 0.6626217 0.1884292 -0.7248634 0.664055 0.1878111 -0.7237113 0.6509506 0.2403061 -0.7200807 0.6508827 0.2405839 -0.7200494 0.5173217 0.6653072 -0.5382794 0.5277379 0.5369142 -0.6581916 0.4835842 0.5239293 -0.7011736 0.484162 0.5202782 -0.7034897 0.4161339 0.4802662 -0.7721249 0.4170478 0.4770707 -0.7736114 0.3558998 0.4190477 -0.835305 0.3569996 0.4164426 -0.836138 0.314288 0.3557047 -0.8801689 0.354061 0.242901 -0.9031279 0.4512698 0.6615743 -0.598895 0.3554378 0.8344473 -0.4211433 0.2215998 0.7991215 -0.5588368 0.222598 0.7964058 -0.562306 0.1179196 0.73482 -0.667933 0.1190785 0.7323198 -0.6704685 0.02480161 0.6428373 -0.7656011 0.02601057 0.6407285 -0.7673269 -0.05424469 0.526713 -0.8483105 -0.05310136 0.5250861 -0.8493909 -0.1029717 0.4204384 -0.9014591 -0.01645141 0.294179 -0.9556088 -0.4980219 0.7594875 0.4185128 -0.5348285 0.7406451 0.4066983 -0.5222173 0.7547978 0.3969503 -0.6435817 0.5906022 0.486818 -0.4216077 0.7431584 0.5195793 -0.70682 0.3792478 0.5971403 -0.6610059 0.442018 0.6063755 -0.6793857 0.3853914 0.6244267 -0.6793712 0.3854334 0.6244163 -0.6204479 0.4426985 0.6473503 -0.6898369 0.1208389 0.7138087 -0.6876896 0.1336259 0.7136017 -0.6876873 0.1336421 0.7136007 -0.6814936 0.1224896 0.7215005 -0.07625776 0.9641279 -0.2542485 -0.697354 0.06429028 -0.7138377 0.2035287 0.2711364 -0.9407769 0.659066 0.03720349 -0.7511644 0.4905766 0.1921629 -0.8499459 0.4906497 0.1920864 -0.8499209 0.4996314 0.1329464 -0.8559752 0.4805242 0.1914189 -0.8558359 0.5397784 0.3005207 -0.7863374 0.09770143 0.3822626 -0.9188742 0.2178152 0.2105197 -0.9530152 0.21843 0.2081429 -0.9533966 -0.2136333 0.2564935 -0.9426409 -0.2136593 0.2565454 -0.9426209 -0.3076968 0.3344211 -0.8907779 -0.3412981 0.2497714 -0.9061622 -0.5327213 0.1773675 -0.8274956 -0.5398682 0.1896864 -0.8200984 -0.5972228 0.1798322 -0.7816555 -0.5971328 0.179748 -0.7817437 -0.5915991 0.1641358 -0.7893478 -0.5401375 0.190043 -0.8198385 -0.5401228 0.1900433 -0.8198482 -0.6142673 0.1797539 -0.7683517 -0.6252962 0.170304 -0.7615781 -0.6212319 0.1679885 -0.7654089 -0.6547324 0.1714263 -0.7361648 -0.6549453 0.1743906 -0.7352787 -0.676363 0.1892527 -0.7118403 -0.6539342 0.1829063 -0.7341085 -0.6643154 0.3568069 -0.6567907 -0.07969182 0.9629758 -0.2575402 0.2291532 0.7858135 -0.5744438 0.22922 0.7857016 -0.5745704 0.2172361 0.8712659 -0.4401183 0.07665425 0.897673 -0.4339441 0.02058684 0.9260381 -0.3768681 0.1784007 0.9219642 -0.3437371 0.178492 0.9219387 -0.3437582 0.229243 0.7857235 -0.5745313 0.3204584 0.7618628 -0.5629134 0.3612856 0.6330516 -0.68463 0.4379265 0.4276905 -0.7907599 0.4381063 0.4271569 -0.7909487 0.4287905 0.4565134 -0.7795732 0.4810159 0.4329982 -0.762323 0.3962336 0.6220282 -0.6753367 0.3612494 0.6330989 -0.6846055 0.3612605 0.6330915 -0.6846063 -0.4954995 0.745854 -0.4451767 -0.6030921 0.3558958 -0.7138754 -0.603169 0.3556689 -0.7139235 -0.531725 0.1782651 -0.8279432 -0.304333 0.3524265 -0.8849728 -0.3503488 0.4172354 -0.8385525 -0.3475835 0.4179414 -0.8393514 -0.4112557 0.4778021 -0.7762564 -0.4079577 0.4792818 -0.7770839 -0.4792656 0.5208336 -0.7064253 -0.475553 0.5232816 -0.707125 -0.5224095 0.5369536 -0.6623966 -0.3824029 0.7429999 -0.5492896 -0.07432466 0.9637592 -0.2562109 -0.07758897 0.9625542 -0.2597488 -0.07744604 0.9626033 -0.2596092 -0.1749296 0.3085269 -0.9349924 0.1156276 0.4096469 -0.9048866 0.05992633 0.5259298 -0.8484142 0.06223624 0.5256502 -0.8484212 -0.02018678 0.6416391 -0.766741 -0.01711755 0.6416984 -0.7667661 -0.1144226 0.7331736 -0.6703461 -0.110694 0.733767 -0.6703229 -0.2192338 0.7970101 -0.5627711 -0.2148697 0.7983234 -0.5625929 -0.3029975 0.8248749 -0.4772567 -0.452199 0.7462393 -0.4885111 0.6393782 -0.02416068 0.7685127 0.6929134 -0.03044509 0.7203777 0.719094 -0.1072893 0.6865805 0.6789929 -8.3781e-4 0.7341445 0.6789904 -5.73802e-4 0.7341469 0.6785246 4.61915e-4 0.7345775 0.7098264 -0.01036339 0.7043005 0.7045087 -0.01606827 0.7095135 0.6967058 -0.02462619 0.7169342 0.6967414 -0.02458471 0.716901 0.6967549 -0.0245524 0.7168889 0.7273519 0.08591097 0.680866 0.6399028 -0.01278173 0.7683495 0.6399117 -0.01272916 0.768343 0.7084391 -0.01006257 0.7057002 0.7088324 -0.01112985 0.7052891 0.7232361 -0.01113486 0.6905111 0.7300032 -0.01170635 0.6833435 0.7987341 0.0106312 0.6015902 0.832845 -0.01265966 0.5533615 0.8823322 0.009921789 0.4705225 0.8327358 0.009863615 0.5535829 0.8823211 0.01137995 0.4705104 0.9128017 -0.01320302 0.4081897 0.9445872 0.01171606 0.3280513 0.9677474 -0.007163703 0.251821 0.9446254 -0.007107257 0.3280736 0.9676874 -0.01333367 0.2518001 0.9840216 0.01163965 0.1776691 0.9959905 -0.01305311 0.08850133 0.9997352 0.00102216 0.02299094 0.9705583 -5.23025e-4 -0.2408655 0.9911636 0.01025474 -0.1322485 0.9997351 0.00102216 0.02299118 0.9957261 0.02648407 0.08847695 0.9969363 -0.01236027 -0.07723522 0.6159834 -0.01819193 -0.787549 0.6722668 0.003680825 -0.7402998 0.7824429 -0.05526942 -0.6202648 0.7398141 -0.02076494 -0.672491 0.8301723 0.1455532 -0.5381714 0.737681 -0.0119068 -0.6750444 0.7397224 -0.02085888 -0.6725889 0.7643553 0.004038572 -0.6447827 0.8391073 0.004048347 -0.5439509 0.8255441 -0.01060104 -0.5642381 0.91738 0.01118487 -0.3978553 0.9030729 -0.00298649 -0.429477 0.9174342 -0.003000557 -0.3978762 0.9029789 -0.0150848 -0.42942 0.9704347 0.01587814 -0.240841 0.9586178 -0.01562058 -0.2842674 0.9912157 -4.43009e-4 -0.1322546 0.7791189 -0.03011524 -0.6261525 0.7788807 -0.02841228 -0.6265282 0.7462087 -0.4278086 -0.5100513 0.7572084 -0.01528853 -0.6529945 -0.743885 -0.01611298 -0.6681134 -0.7516385 -0.02118062 -0.6592351 -0.7391437 -0.4366561 -0.5128334 -0.734086 -0.02613639 -0.6785534 -0.7336413 -0.02659255 -0.6790164 -0.8348584 0.1005603 -0.5412016 -0.7282876 -0.02208316 -0.6849157 -0.7377187 -0.008150398 -0.675059 -0.665738 0.002845823 -0.7461801 -0.6159696 -0.02028566 -0.7875087 -0.5778933 -0.0197612 -0.815873 -0.6159824 -0.01978522 -0.7875115 -0.5782297 0.01615703 -0.815714 -0.4774462 -0.01766747 -0.8784834 -0.44519 0.001515209 -0.8954348 -0.477503 0.001488924 -0.8786289 -0.4451628 0.01314711 -0.8953532 -0.3258007 -0.0142948 -0.9453305 -0.3013528 0.009375035 -0.9534665 -0.1651472 -0.007840394 -0.9862378 -0.300906 -0.007739365 -0.9536224 -0.1651844 -0.01012182 -0.9862108 -0.1503055 0.004820942 -0.9886279 0 -0.005188226 -0.9999866 0.004399418 -0.002993285 -0.9999858 -2.39751e-5 -0.002993762 -0.9999955 0.004388511 -5.00181e-4 -0.9999903 0.1651797 5.37638e-4 -0.9862633 0.158971 -0.00584042 -0.987266 0.1651476 -0.005840599 -0.9862515 0.1591112 -0.006588935 -0.9872387 0.3258139 0.007034063 -0.9454078 0.3097072 -0.01347815 -0.9507364 0.4774572 0.01429814 -0.8785386 0.4530248 0.001267194 -0.891497 0.4775161 0.001252114 -0.8786221 0.4529455 -0.02113217 -0.8912878 0.6159384 0.02233266 -0.7874777 0.5853749 -0.01548546 -0.8106149 0.5854312 -0.01548552 -0.8105743 -0.9433422 -0.007729947 0.3317315 -0.9433414 -0.007729947 0.3317338 -0.9676836 -0.01329565 0.2518165 -0.9836496 0.01185154 0.1797029 -0.9959902 -0.01299607 0.08851313 -0.999729 0.001321375 0.02324181 -0.9960736 0.001277267 0.08852034 -0.9996648 0.01141262 0.02324086 -0.9969366 -0.01241743 -0.07722324 -0.990951 0.01069432 -0.1337981 -0.9705612 6.15771e-5 -0.2408547 -0.9910072 1.43222e-4 -0.1338087 -0.9704956 -0.01155865 -0.2408415 -0.9577229 0.009696483 -0.2875291 -0.9173907 -0.0104233 -0.3978515 -0.9008203 -0.003316402 -0.4341794 -0.9174382 -0.003334879 -0.3978644 -0.9008021 0.008418262 -0.4341481 -0.8390848 -0.009007573 -0.5439263 -0.821595 0.005531191 -0.5700448 -0.771247 0.005520403 -0.6365122 -0.7771025 -0.03862375 -0.6281878 -0.9670857 0.03759866 0.251658 -0.9127964 -0.01331508 0.4081979 -0.8796217 0.0118907 0.4755253 -0.8328774 0.01047223 0.5533586 -0.8796325 0.0105257 0.4755373 -0.8328288 -0.01305645 0.5533766 -0.6937009 -0.03388112 0.7194659 -0.7273864 0.08523869 0.6809138 -0.6395068 -0.01312738 0.7686735 -0.6395061 -0.01313048 0.7686738 -0.6981844 -0.02278739 0.7155551 -0.6982131 -0.02271932 0.7155294 -0.6981603 -0.02278095 0.715579 -0.7057987 -0.01470273 0.7082599 -0.7085554 -0.01215189 0.7055507 -0.7299997 -0.01215809 0.6833392 -0.720267 -0.0159111 0.6935145 -0.7941745 0.0114904 0.6075812 -0.7062377 -0.007882475 0.707931 -0.7062467 -0.007906854 0.7079216 -0.7161293 -0.1082961 0.6895149 -0.6814928 -0.001133322 0.731824 -0.6814928 -0.001093268 0.731824 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -2.65782e-6 -1 4.89766e-6 -8.95591e-5 -1 9.00115e-5 5.07168e-6 -1 6.50456e-5 8.24408e-6 -1 7.25093e-5 0 -1 0 0 -1 0 0 -1 0 -5.51011e-5 -1 1.58569e-5 -6.30733e-5 -1 2.07126e-5 4.55058e-5 -1 -4.22614e-5 4.47904e-5 -1 -4.22355e-5 4.08537e-5 -1 -4.31375e-5 0.002484142 -0.9999967 6.20158e-4 -2.96473e-4 -1 2.39158e-4 -2.89693e-4 -0.9999999 2.5326e-4 -4.95137e-4 -0.9999998 -2.36808e-4 4.48157e-6 -1 6.47722e-5 1.07361e-4 -1 1.78071e-4 5.28559e-6 -1 6.52291e-5 6.29222e-6 -1 7.62773e-5 0 -1 0 1.48803e-4 1 8.72545e-5 4.26021e-6 1 -3.51611e-6 -1.70559e-4 1 1.60028e-4 -1.75792e-4 1 1.86418e-4 -2.27937e-5 1 -8.5552e-5 -2.22761e-5 1 -8.67749e-5 -2.68532e-5 1 -1.27904e-6 2.65372e-5 1 -5.48647e-5 -3.35377e-4 0.9999998 5.71734e-4 0 1 0 0 1 0 0 1 0 -1.75368e-4 0.9999999 1.86885e-4 -1.75573e-4 1 1.86469e-4 -1.75758e-4 1 1.86143e-4 -1.76039e-4 1 1.85334e-4 -7.00685e-6 1 -4.89754e-6 -1.91751e-5 1 1.65426e-5 -5.42125e-5 1 1.15434e-4 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 6.79069e-5 1 4.61709e-5 0.09758448 0.9913258 0.08803695 0.08326435 0.9953556 0.04831612 0.01722496 0.9996688 -0.01912015 0.08565628 0.9950842 0.04970395 0.6461945 0.6285331 0.4328725 0.7060895 0.4239397 0.5671973 0.7061414 0.4239389 0.5671332 0.7060982 0.4238464 0.5672562 0.6671606 0.6284988 0.3998574 0.6672036 0.6285119 0.399765 0.7072062 0.4693006 0.5287877 0.7644134 0.2952285 0.5731601 0.7643721 0.2953784 0.5731378 0.5575482 0.761183 0.3312712 0.5575413 0.7611883 0.3312706 0.5743532 0.7630512 0.296431 0.4020854 0.8879209 0.2234364 0.3036506 0.9363334 0.1762837 0.3036394 0.9363375 0.1762816 0.3036402 0.9363375 0.17628 0.1125165 0.9927375 0.04257029 0.0995506 0.9933254 0.05826026 0.09577357 0.9939017 0.05465215 0.07993835 0.9909467 0.1078637 0.01946818 0.9997461 0.01134335 0.01929724 0.999746 0.01163977 0.004582643 0.9999858 0.002723217 0.00458461 0.9999858 0.00274229 0.122451 0.9920787 0.02802485 0.09928297 0.9933911 0.05759423 0.09927892 0.993391 0.05760109 0.1713002 0.977257 0.125 0.04637926 0.9980472 0.04184138 0.04074054 0.9987667 0.02837866 0.0613982 0.9968583 0.0500372 0.07453852 0.9958654 0.05192583 0.07453942 0.9958653 0.05192458 0.4479876 0.7931968 0.4124876 0.4667785 0.7395364 0.484978 0.3931576 0.845964 0.3602387 0.4326362 0.7413746 0.5130199 0.23385 0.936761 0.2603708 0.1892269 0.9683946 0.1624962 0.1317324 0.9885616 0.07343345 0.1596122 0.9695918 0.1855149 0.6676166 0.3478686 0.6582367 0.678562 0.2064653 0.7049295 0.6498149 0.3489351 0.6752665 0.5928577 -0.4438182 0.6719711 0.6525934 0.06106638 0.7552434 0.473082 0.8457527 0.2467707 0.4585573 0.8458002 0.2726668 0.2972183 0.9471583 0.120634 0.4072056 0.8692861 0.2802238 0.4427498 0.8694527 0.2191452 0.530385 0.7658747 0.3634939 0.5525824 0.7660881 0.328271 0.6692507 0.5166541 0.5340151 0.6167262 0.5155318 0.5948746 0.6514515 0.3487505 0.6737833 0.2704908 0.9573197 0.1018515 0.3109758 0.9311807 0.1902537 0.12905 0.9913909 0.02214217 0.254508 0.9469379 0.1963015 0.1089233 0.9921103 0.06207138 0.1299682 0.991216 0.02447783 0.2495602 0.9492778 0.1912889 0.2877689 0.9494378 0.1255274 0.3898158 0.8773234 0.2799062 0.418923 0.8775041 0.233431 0.572035 0.6753956 0.4654212 0.5230971 0.6737408 0.5219606 0.6168692 0.3511192 0.7044061 0.07820481 0.9954484 0.05446529 0.1087292 0.9935414 0.0324586 0.1944839 0.9661854 0.1692975 0.2236822 0.9662614 0.1276927 0.3030465 0.9138081 0.2704026 0.08326226 0.9953556 0.04831939 0.2281845 0.9562299 0.183184 0.2409789 0.9567483 0.1629779 0.3786458 0.8924497 0.2452772 0.4454983 0.811081 0.3790498 0.4292076 0.8106332 0.3983148 0.319262 0.9138837 0.2507757 0.373938 0.8462838 0.3794392 0.1749143 0.9771715 0.1205852 0.2391116 0.9368458 0.2552366 0.05869066 0.9979178 0.0267474 0.09758549 0.9913257 0.08803594 -0.354605 0 -0.9350162 0.6156422 0.03655117 0.7871777 0.1650277 0.0134449 0.9861974 -0.9981467 -0.007588863 -0.06037729 -0.9160609 0.0547344 0.3972866 -0.96731 -0.08640992 0.2384213 -0.9662638 -0.09396207 0.2398023 -0.9952566 0.0556004 0.07983046 -0.9966322 0.05558937 0.06028461 -0.9967984 3.91454e-4 0.07995486 -0.9999999 3.92708e-4 1.41243e-4 -0.9160618 0.0547344 0.3972844 -0.8730487 -0.1668265 0.4582083 -0.8370398 0.07029277 0.542608 -0.6157252 0.0365054 0.7871147 -0.7473498 -0.05560761 0.6620997 -0.7307946 -0.1368346 0.6687418 -0.8370342 0.07029271 0.5426166 -0.615668 0.0365054 0.7871596 -0.5606003 -0.1615977 0.8121658 -0.4760714 0.07760387 0.8759759 -0.1652874 0.0133953 0.9861544 -0.3545358 -0.01975667 0.9348337 -0.3202705 -0.18365 0.9293543 -0.4760958 0.07760387 0.8759626 -0.1651647 0.0133953 0.9861751 -0.1191387 -0.1516595 0.9812265 2.56044e-5 0.08001023 0.996794 0.120522 0.01343137 0.9926198 0.1606193 -0.2336503 0.9589625 0 0.08001023 0.996794 0.3258012 -0.01465171 0.9453248 0.3512703 -0.1368211 0.9262232 0.4760669 0.07755988 0.8759822 0.5676884 0.0364862 0.8224346 0.5903398 -0.2861121 0.7547442 0.4760984 0.07755982 0.8759651 0.736909 -0.04756546 0.6743164 0.7433541 -0.1171481 0.6585597 0.8370463 0.07028758 0.5425985 0.8841367 0.05459374 0.4640278 0.862721 -0.3402003 0.374134 0.8370408 0.07028764 0.5426069 0.9667789 -0.09250026 0.2382904 0.9670386 -0.08511483 0.2399829 0.916064 0.0547443 0.3972781 0.9937674 0.06801956 -0.08831691 0.9937674 0.06801956 -0.08831483 0.9981466 -0.007605314 -0.06037729 1 3.89603e-4 1.05693e-4 0.9981755 3.88892e-4 0.06037801 0.9952579 0.05558347 0.07982635 0.9952581 0.05558341 0.07982355 0.9599239 -0.1270779 -0.2497946 0.969025 -0.06281065 -0.2388418 0.9121111 0.04096215 -0.4078916 0.9121089 0.04096215 -0.4078962 0.8735905 -0.1631556 -0.4584973 0.8304673 0.07640492 -0.5518029 0.7482169 -0.0280711 -0.6628601 0.71904 -0.1730139 -0.6730881 0.8304667 0.07640492 -0.5518038 0.5270744 -0.1995521 -0.8260578 0.6394456 0.008891463 -0.7687849 0.6393644 0.008891463 -0.7688525 0.2136872 0 -0.9769021 0.354605 0 -0.9350162 0.354605 0 -0.9350162 0.5680607 0 -0.8229867 0.04095309 0.01204025 -0.9990886 0.1102595 -0.106795 -0.9881486 0.1211917 -0.1419551 -0.9824262 0.1194328 -0.1353245 -0.9835767 0.1686237 -0.05590844 -0.9840936 0.1684226 -0.05618864 -0.9841122 -0.09826421 -0.08611404 -0.9914276 -0.05501496 -0.01194429 -0.9984141 0.04085505 0.01204025 -0.9990925 -0.2136864 0 -0.9769023 -0.1684681 -0.05613231 -0.9841075 -0.1196237 -0.1231766 -0.9851486 -0.1420472 -0.2217829 -0.9646942 -0.1153496 -0.1199907 -0.9860511 -0.639411 0.00889939 -0.7688136 -0.639428 0.00889939 -0.7687995 -0.5623713 -0.1411756 -0.8147441 -0.5379137 0 -0.8429999 -0.354605 0 -0.9350162 -0.7298858 -0.02144938 -0.6832324 -0.7418695 -0.1329257 -0.6572368 -0.8304776 0.07640236 -0.5517877 -0.8847147 0.04089409 -0.4643357 -0.8714337 -0.2978931 -0.3896961 -0.8304745 0.07640236 -0.5517923 -0.9937693 0.06801033 -0.08830225 -0.9937691 0.06801033 -0.08830428 -0.964815 -0.1121665 -0.2378042 -0.9662862 -0.05540221 -0.2514389 -0.912115 0.04097491 -0.4078813 -0.4647263 0 -0.8854545 0.6221397 -0.02891576 0.7823721 0.9865386 0.1232041 -0.1075282 0.990796 0.06204771 -0.1203049 0.9711898 -0.07955056 0.2246376 0.97119 -0.07955056 0.2246367 0.9795883 0.1620474 0.118943 0.9974412 -3.91693e-4 0.07148939 0.9999325 -3.92681e-4 -0.01161581 0.9062792 0.188955 0.3780927 0.9349558 0.01137465 0.3545818 0.8454917 -0.00787121 0.5339307 0.8455405 -0.00787121 0.5338532 0.8140462 0.1469642 0.5618988 0.7419551 -0.08149194 0.6654785 0.6628476 -0.02887421 0.7481976 0.6007804 0.261018 0.7556008 0.74196 -0.081492 0.6654731 0.4824747 0.03512936 0.8752052 0.4612339 0.1222462 0.878817 0.3286974 -0.07371979 0.9415537 0 0.08762812 0.9961532 1.26421e-5 0.08756828 0.9961585 0.1668749 -0.05618596 0.9843759 0.2389412 -0.05603432 0.9694159 0.1573923 0.3369969 0.9282568 0.3286987 -0.07371979 0.9415532 -0.3286835 -0.07371777 0.9415587 -0.3286852 -0.07371777 0.9415581 -0.2359742 0.1665623 0.9573783 -0.1668717 -0.05623525 0.9843737 -0.1668821 -0.05623519 0.9843719 -0.4773827 0.1486818 0.8660252 -0.4642905 0.04295045 0.8846409 -0.622062 -0.02893018 0.7824333 -0.6220862 -0.02893018 0.7824141 -0.6548864 0.1571322 0.7392113 -0.7419382 -0.08148854 0.6654978 -0.9711829 -0.07955658 0.2246655 -0.926044 0.138202 0.351202 -0.9228659 0.008202433 0.385034 -0.8455298 -0.007813155 0.5338711 -0.8229572 -0.007806658 0.5680497 -0.8253666 0.2172017 0.5211462 -0.7419378 -0.08148849 0.6654983 -0.9598028 -0.06790971 -0.2723363 -0.9867348 0.1095425 -0.1198118 -0.9926091 0.05502176 -0.108166 -0.9999325 -3.89577e-4 -0.01161068 -0.9927089 -3.86763e-4 0.1205361 -0.9613363 0.2666146 0.06891405 -0.9711844 -0.07955652 0.2246586 -0.9330873 -0.06420356 -0.3538731 -0.8395045 0.3679976 -0.3997623 -0.9598024 -0.06790977 -0.2723373 -0.8209136 0.07090789 -0.5666329 -0.8132421 0.111039 -0.5712335 -0.9009858 -0.0644198 -0.4290391 -0.587979 0 -0.8088762 -0.6271969 0.0570172 -0.776771 -0.6541506 0.1639099 -0.7383905 -0.7099475 -0.0465191 -0.7027165 -0.7099293 -0.04651898 -0.7027348 -0.155439 0.01251268 -0.9877663 -0.1250768 -0.007488965 -0.9921188 -0.1724071 0.02923667 -0.9845917 -0.1723173 0.02911347 -0.9846112 -0.2370777 0.1364865 -0.9618552 -0.2722727 0 -0.9622203 -0.4647263 0 -0.8854545 0.1376489 -0.004915356 -0.9904689 0.1022137 0.002649605 -0.994759 0.05487608 0.02349311 -0.9982168 0 0.124515 -0.9922177 -0.04058289 0.02976149 -0.9987328 -0.1251345 -0.007488965 -0.9921115 0.2673997 0.1882801 -0.9450122 0.1722862 0.0290637 -0.9846181 0.1724146 0.02923971 -0.9845903 0.1376722 -0.004915356 -0.9904656 0.5880321 0 -0.8088377 0.4647263 0 -0.8854545 0.4647263 0 -0.8854545 0.2393172 0 -0.9709414 0.8186363 0.1026682 -0.565061 0.8165324 0.06541228 -0.5735818 0.7099558 -0.04646766 -0.7027117 0.6624057 -0.04636889 -0.7477089 0.6765489 0.3062381 -0.6697013 0.6271353 0.05681389 -0.7768356 0.9597973 -0.06789046 -0.2723603 0.9597967 -0.06789046 -0.2723621 0.9217794 0.1676704 -0.3495846 0.9009767 -0.06443649 -0.429056 0.9009765 -0.06443655 -0.4290562 1.72796e-4 -1 1.83141e-4 0.001034438 -0.9999994 -3.32883e-4 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -2.31287e-5 -1 7.22426e-5 -2.96504e-5 -1 8.78749e-5 0 -1 0 0 -1 0 0 -1 0 7.57406e-5 -1 -7.54159e-5 6.89236e-5 -1 -7.38465e-5 6.6461e-5 -1 -7.39499e-5 2.06879e-5 -1 -2.07097e-4 0.00111109 -0.9999964 0.00245136 4.16706e-5 -1 -7.90865e-5 3.98807e-5 -1 -8.01734e-5 -7.29445e-5 -1 -2.83607e-4 -2.25188e-5 -1 7.11513e-5 -3.16944e-5 -1 8.13598e-5 8.22769e-5 -1 -4.14347e-5 1.72927e-4 -1 1.83271e-4 1.73499e-4 -1 1.81158e-4 4.85754e-5 1 9.97437e-5 2.15043e-5 1 2.14747e-5 -1.99191e-5 1 -5.38743e-5 -3.57016e-5 1 5.38984e-5 1.85695e-4 1 1.7475e-4 1.88436e-4 1 1.69849e-4 -2.87858e-5 1 5.0156e-5 -3.70362e-5 1 6.38127e-5 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 3.98937e-5 1 -8.85055e-5 7.58705e-5 1 -4.40437e-6 -1.89466e-5 1 -5.23504e-5 -1.91982e-5 1 -5.26069e-5 1.85758e-4 1 1.75237e-4 1.89713e-4 0.9999999 1.96923e-4 1.85594e-4 1 1.75143e-4 0 1 0 0 1 0 0 1 0 0.6889428 0.1336625 0.7123849 0.6781631 0.1544554 0.7184973 0.6660729 0.1390548 0.7328101 0.6639404 0.1571267 0.7310913 0.6525024 0.4423038 0.6153113 0.4977497 0.7437242 0.4462282 0.4946786 0.7437847 0.4495302 0.5051088 0.7039529 0.4993149 0.5459307 0.7426304 0.3878914 0.4382876 0.8199899 0.3681313 0.5051058 0.7039873 0.4992695 0.6445772 0.4485229 0.6191505 0.6493526 0.4424232 0.6185491 0.6474519 0.4478147 0.6166589 0.647387 0.4479743 0.616611 -0.6384863 0.3614676 -0.6794678 -0.02421963 0.9914728 -0.1280441 0.5258244 0.6513062 -0.5470914 0.6660652 0.1988638 -0.7188953 0.6660541 0.1988965 -0.7188965 0.6660447 0.1989659 -0.718886 0.6177052 0.442382 -0.6501834 0.6178393 0.4419773 -0.6503312 0.525852 0.6512727 -0.5471047 0.2311248 0.9277181 -0.2931219 0.2311499 0.9277095 -0.2931295 0.403974 0.8113872 -0.4224405 0.403903 0.8114632 -0.4223621 0.08301311 0.9917004 -0.09817916 0.08113718 0.9918618 -0.09811753 0.0811398 0.9918614 -0.09811925 0.07589745 0.9915611 -0.1051006 0.08008009 0.989093 -0.123622 0.08301621 0.9917004 -0.09817647 0.02515256 0.9914504 -0.1280361 0.04200577 0.9907605 -0.1289534 0.04223692 0.9909963 -0.1270527 0.05700469 0.9912921 -0.1187037 0.05974429 0.9912665 -0.1175645 0.06033623 0.9902414 -0.1256253 0.07029986 0.9916046 -0.1085273 0.02514022 0.9914504 -0.1280391 0.02197349 0.9904029 -0.1364519 0.008606851 0.99167 -0.128517 0.008601009 0.9916699 -0.1285175 6.10395e-4 0.9902753 -0.1391198 -0.00771594 0.9916768 -0.1285204 -0.01962751 0.9914368 -0.1291037 -0.02656489 0.9897407 -0.1403837 -0.007713198 0.9916769 -0.1285207 -0.04210549 0.9906679 -0.1296311 -0.04031699 0.9910112 -0.1275591 -0.05631601 0.9912617 -0.1192846 -0.05628794 0.9912619 -0.119296 -0.06105661 0.9905503 -0.1228088 -0.06960815 0.9915909 -0.1090972 -0.1409291 0.9815961 -0.1288733 -0.1409511 0.9815896 -0.1288981 -0.1409395 0.9815922 -0.1288903 -0.06960755 0.9915909 -0.1090975 -0.08032554 0.9903067 -0.1133153 -0.08230841 0.9916876 -0.09889882 -0.06361168 0.9913944 -0.1144148 -0.02072304 0.9994752 -0.02489751 -0.4219375 0.7705044 -0.4777989 -0.4219551 0.7704784 -0.4778253 -0.2852742 0.9044317 -0.3172098 -0.285497 0.9042734 -0.3174602 -0.550487 0.5857936 -0.5948194 -0.5504778 0.585851 -0.5947713 -0.5505231 0.585757 -0.5948221 -0.6762478 0.1195499 -0.7269091 -0.6384544 0.3615954 -0.6794297 -0.6609771 0.1194635 -0.7408359 -0.6800739 0.05239838 -0.7312687 -0.5772144 0.05232208 -0.8149146 -0.5775167 0.0522964 -0.8147022 -0.5775147 0.05227148 -0.8147053 -0.4445819 0.05227053 -0.8942118 -0.4445791 0.05228072 -0.8942126 -0.4445912 0.05233573 -0.8942034 -0.300953 0.05233931 -0.9522016 -0.3009566 0.05231469 -0.9522018 -0.3005037 0.05226218 -0.9523477 -0.1500882 0.05225944 -0.9872904 -0.1501011 0.0523616 -0.9872831 0.004393398 0.0523625 -0.9986185 0.004379689 0.05231469 -0.9986211 0.004382491 0.05230367 -0.9986217 0.1587561 0.05230343 -0.9859315 0.1587575 0.05231362 -0.9859307 0.1588972 0.05227148 -0.9859104 0.3093072 0.05227142 -0.9495245 0.3093125 0.052235 -0.9495248 0.4524067 0.05223792 -0.8902806 0.4524259 0.05231577 -0.8902662 0.4524263 0.05231434 -0.8902661 0.5846435 0.05231148 -0.8096021 0.5846416 0.05229032 -0.8096048 0.5847014 0.05225479 -0.8095639 0.668896 0.05238914 -0.7415077 0.6718049 0.03724628 -0.7397912 0.6177002 0.4424091 -0.6501696 0.6339219 0.2481162 -0.7325171 0.5672472 0.2474284 -0.7854998 0.5672428 0.2474021 -0.7855111 0.4389522 0.2474011 -0.8637788 0.4389591 0.2474311 -0.8637666 0.300107 0.2474327 -0.9212561 0.3001012 0.2474128 -0.9212633 0.154032 0.2474129 -0.9565882 0.1540325 0.2474145 -0.9565877 0.004261136 0.2474147 -0.9689003 0.004249334 0.2473844 -0.9689081 -0.1456242 0.2473846 -0.9579116 -0.1456218 0.2473902 -0.9579105 -0.2920041 0.2473909 -0.9238677 -0.2920009 0.247398 -0.9238666 -0.4313499 0.2473987 -0.8676007 -0.4313484 0.247402 -0.8676006 -0.5603297 0.2474027 -0.7904572 -0.5603301 0.2474017 -0.7904572 -0.6213522 0.248103 -0.7432135 -0.6762289 0.1196182 -0.7269154 0.525821 0.651312 -0.5470876 0.5474938 0.5228316 -0.6533741 0.4994666 0.5216922 -0.6916434 0.4994667 0.5216963 -0.6916402 0.3865072 0.5216972 -0.7605553 0.3865042 0.5216772 -0.7605705 0.2642501 0.5216763 -0.8111879 0.2642508 0.5216786 -0.8111862 0.135619 0.521678 -0.8422943 0.135626 0.5216968 -0.8422815 0.003751814 0.521697 -0.8531225 0.003751933 0.5216973 -0.8531224 -0.1282278 0.5216972 -0.8434392 -0.1282209 0.5217096 -0.8434326 -0.2570971 0.5217093 -0.8134621 -0.2571117 0.5216863 -0.8134722 -0.3798106 0.5216864 -0.7639289 -0.3798056 0.5216935 -0.7639265 -0.493373 0.5216932 -0.6960024 -0.4933739 0.521692 -0.6960027 -0.5431514 0.5228351 -0.6569857 -0.638453 0.3615962 -0.6794305 0.4039558 0.8113971 -0.4224389 0.4105625 0.757225 -0.5079851 0.3829882 0.7563372 -0.5303527 0.3829876 0.7563412 -0.5303475 0.2963657 0.7563406 -0.5831947 0.2963664 0.7563521 -0.5831796 0.2026236 0.7563531 -0.6219918 0.2026215 0.7563451 -0.6220022 0.1039971 0.7563452 -0.6458534 0.103992 0.7563341 -0.645867 0.002868533 0.7563335 -0.6541798 0.002876818 0.7563463 -0.654165 -0.09831541 0.7563467 -0.6467409 -0.09832584 0.756334 -0.6467542 -0.197153 0.7563342 -0.6237702 -0.1971408 0.7563467 -0.6237589 -0.2912347 0.7563467 -0.5857661 -0.2912299 0.7563511 -0.5857629 -0.3783063 0.7563506 -0.5336836 -0.3783127 0.7563452 -0.5336866 -0.4209811 0.757314 -0.4992499 -0.4074219 0.7697289 -0.4914517 0.2526153 0.9286167 -0.2717658 0.2719109 0.9165984 -0.2931071 0.2344627 0.9163033 -0.3246774 0.234463 0.9163028 -0.3246786 0.1814364 0.9163027 -0.3570297 0.1814366 0.9163007 -0.3570349 0.1240426 0.9163002 -0.3807982 0.1240448 0.9163078 -0.3807793 0.06366997 0.9163083 -0.39538 0.06366688 0.9163037 -0.3953909 0.001757085 0.9163037 -0.4004803 0.001756072 0.9163028 -0.4004826 -0.06019395 0.9163025 -0.3959372 -0.06018757 0.9163072 -0.3959277 -0.1206917 0.916307 -0.3818571 -0.1206926 0.9163066 -0.3818581 -0.1782861 0.9163064 -0.3586035 -0.1782969 0.916301 -0.3586122 -0.2316064 0.9163011 -0.3267272 -0.2316013 0.9163034 -0.3267243 -0.2479408 0.9167004 -0.3133458 -0.2855247 0.904262 -0.3174684 -0.7371677 0.4415783 -0.511461 -0.81428 0.1332573 -0.5649695 -0.7139177 0.1335434 0.6873774 -0.6460239 0.4424192 0.6220276 -0.4811196 0.7442603 0.4632499 -0.7139119 0.1335596 0.6873803 -0.7139146 0.1335694 0.6873755 -0.7139031 0.1335723 0.687387 -0.7871472 0.1332443 0.6022003 -0.7871432 0.1332607 0.6022019 -0.9908159 0.1332414 0.02303457 -0.9749475 0.133241 0.1781131 -0.9749475 0.1332408 0.1781131 -0.9349582 0.1332411 0.3287857 -0.9349586 0.1332406 0.3287848 -0.9349583 0.133246 0.3287832 -0.8718374 0.1332483 0.4713218 -0.8718373 0.1332664 0.471317 -0.871836 0.1332566 0.4713223 -0.990816 0.1332405 0.0230351 -0.9908159 0.1332405 0.0230351 -0.9821714 0.1332411 -0.1326127 -0.9821717 0.1332396 -0.1326123 -0.9821716 0.133237 -0.1326158 -0.9492284 0.1332316 -0.2849819 -0.9492276 0.1332444 -0.2849786 -0.8927972 0.1332535 -0.4302985 -0.8928045 0.1332205 -0.4302936 -0.8927926 0.133246 -0.4303101 -0.7455953 0.1335625 -0.6528773 -0.7510542 0.1978736 -0.6298918 -0.7516522 0.02030324 -0.6592472 -0.7107927 0.3650465 -0.601261 -0.6868326 0.5128395 -0.5150308 -0.6838328 0.442624 -0.5800489 -0.6374409 0.5191931 -0.5693046 -0.7252008 0.2048695 -0.6573525 -0.7250788 0.2056582 -0.6572408 -0.725217 0.2047842 -0.6573612 -0.507613 0.7695689 -0.387418 -0.5751285 0.6536224 -0.49194 -0.6374982 0.5190681 -0.5693542 -0.710531 0.7027312 0.036255 -0.6686484 0.7434163 0.01554518 -0.6579406 0.7434152 0.1201987 -0.6579409 0.7434152 0.120199 -0.6579396 0.7434163 0.1201981 -0.6309522 0.7434165 0.2218807 -0.6309528 0.743416 0.2218813 -0.6309567 0.7434142 0.221876 -0.5883604 0.7434136 0.3180696 -0.5883579 0.7434157 0.3180694 -0.4811319 0.7442458 0.4632605 -0.4811271 0.7442547 0.4632512 -0.5311985 0.743423 0.406387 -0.5311977 0.7434244 0.4063856 -0.5311996 0.7434149 0.4064003 -0.6460093 0.4424883 0.6219937 -0.6460088 0.4424464 0.6220241 -0.712608 0.4415591 0.5451747 -0.7126071 0.4415645 0.5451716 -0.7892759 0.441566 0.4266884 -0.7892739 0.441574 0.426684 -0.8464152 0.4415733 0.2976479 -0.846418 0.4415652 0.297652 -0.8826193 0.4415686 0.1612457 -0.8826182 0.4415714 0.1612444 -0.8969835 0.4415719 0.02085363 -0.8969836 0.4415718 0.02085363 -0.8891572 0.4415729 -0.1200535 -0.889156 0.4415752 -0.1200543 -0.8593301 0.4415786 -0.2579922 -0.8593337 0.4415724 -0.2579909 -0.8082483 0.4415726 -0.3895487 -0.6675591 0.7443263 -0.01852911 -0.6628068 0.7434234 -0.0894919 -0.662807 0.7434231 -0.08949249 -0.6628085 0.7434218 -0.08949184 -0.6405782 0.7434207 -0.1923156 -0.6405735 0.7434245 -0.1923163 -0.6405746 0.7434238 -0.1923151 -0.6024939 0.7434239 -0.2903825 -0.8082472 0.4415746 -0.389549 -0.7371698 0.4415751 -0.511461 -0.8142862 0.1332356 -0.5649657 -0.814285 0.1332328 -0.5649681 -0.4812174 0.7718051 -0.4156283 -0.5124545 0.7444378 -0.4280219 -0.5495049 0.7434257 -0.3812643 -0.5495157 0.7434178 -0.3812645 -0.5495161 0.7434145 -0.3812704 -0.602503 0.7434166 -0.2903828 0.8475548 0.4415967 0.2943521 0.8601836 0.4416104 -0.2550771 0.8745069 0.1332726 0.4663434 0.9908202 0.1332519 0.0227862 0.9823769 0.1332474 -0.1310752 0.564142 0.642098 -0.5190895 0.4831075 0.7442064 0.4612635 0.4470595 0.8099332 -0.3796654 0.5264235 0.7444185 -0.4107549 0.5115063 0.8023671 -0.3075197 0.5641372 0.6421055 -0.5190854 0.7591853 0.1136397 -0.6408775 0.6991758 0.3788648 -0.6063124 0.6991471 0.3789541 -0.6062896 0.6774088 0.4424454 -0.5876729 0.7428371 0.3709123 -0.5573303 0.5643486 0.6418591 -0.5191605 0.7521775 0.1160759 -0.6486566 0.7542695 0.1335763 -0.6428333 0.818211 0.1332352 -0.5592666 0.8182268 0.1332628 -0.5592369 0.8950285 0.1332487 -0.4256392 0.9823769 0.1332468 -0.1310761 0.9362251 0.1332518 0.3251562 0.9753121 0.1332527 0.1760966 0.874507 0.1332502 0.4663496 0.7168013 0.1335563 0.6843674 0.7916553 0.1332578 0.5962585 0.7167882 0.1335663 0.6843791 0.7167876 0.133564 0.6843802 0.6486408 0.4423965 0.6193146 0.6486404 0.4424111 0.6193044 0.6486254 0.4424396 0.6192999 0.4831076 0.7442052 0.4612655 0.8102482 0.4416091 -0.3853302 0.8950231 0.1332613 -0.4256467 0.8950231 0.1332556 -0.4256488 0.9823758 0.1332572 -0.1310735 0.889328 0.4416061 -0.1186586 0.8893305 0.4416004 -0.1186611 0.8829323 0.4416068 0.1594175 0.9753123 0.1332504 0.1760972 0.9908201 0.1332527 0.0227859 0.8745092 0.1332644 0.4663411 0.7916842 0.4415941 0.4221738 0.7916781 0.4416041 0.4221747 0.8182266 0.1332567 -0.5592386 0.740724 0.4416123 -0.5062673 0.7407242 0.4416114 -0.5062678 0.5521491 0.743448 -0.3773811 0.5521534 0.743441 -0.3773884 0.5521533 0.7434434 -0.377384 0.6039747 0.7434454 -0.2872344 0.81025 0.441603 -0.3853335 0.8601864 0.4416029 -0.2550809 0.9501845 0.1332504 -0.281769 0.9501864 0.1332403 -0.2817672 0.6039712 0.7434497 -0.2872303 0.641194 0.7434501 -0.1901375 0.6411933 0.7434504 -0.1901382 0.6411956 0.7434479 -0.1901406 0.6629169 0.7434498 -0.08845132 0.6629153 0.7434513 -0.08845031 0.6629146 0.7434523 -0.08844792 0.9908201 0.1332522 0.02278625 0.8969737 0.4416025 0.02062803 0.8969736 0.4416027 0.02062809 0.6686136 0.743451 0.01537638 0.6686131 0.7434515 0.01537662 0.65815 0.7434498 0.1188324 0.6581495 0.7434502 0.1188315 0.8829331 0.4416054 0.1594171 0.847548 0.4416084 0.2943543 0.9362266 0.1332497 0.3251524 0.936226 0.1332665 0.3251474 0.6581515 0.7434487 0.1188306 0.6317782 0.7434468 0.2194157 0.6317753 0.7434501 0.2194128 0.6317671 0.743453 0.2194266 0.5901239 0.743453 0.3146928 0.5901309 0.7434473 0.3146932 0.5342167 0.7434461 0.4023685 0.791655 0.1332491 0.5962609 0.7166715 0.4416046 0.5397846 0.7166728 0.4416024 0.5397846 0.5342153 0.7434512 0.402361 0.5342158 0.7434509 0.4023609 -0.452265 0.3498383 -0.8204082 0.7093656 0.06112837 0.702185 0.9602282 0.06105023 0.2724605 0.8044967 0.06113684 -0.5908023 0.4818435 0.06103849 -0.8741288 -2.36421e-5 0.06103754 -0.9981355 -0.1668044 0.06105333 -0.9840979 -0.9011654 0.06105852 0.4291535 -0.1414961 0.9742994 0.1752701 -0.141475 0.9743053 0.175254 -0.1608781 0.969664 0.1840379 -0.1513099 0.9741515 0.1677323 -0.5437014 0.4622943 0.7004803 -0.5437276 0.4622142 0.7005128 -0.4131227 0.7820953 0.4665367 -0.4131326 0.7820758 0.4665607 -0.4192968 0.7415757 0.5236943 -0.3832062 0.7828941 0.4901323 -0.3832122 0.7828867 0.4901398 -0.5437837 0.4621505 0.7005114 -0.6116811 0.3508872 0.7090306 -0.6130324 0.139024 0.7777298 -0.6179819 0.06129455 0.7837994 -0.6222607 0.1391055 0.7703513 0.5882545 0.3517214 0.7281819 0.588467 0.3508163 0.7284467 0.5884726 0.3507848 0.7284573 0.5884811 0.3507719 0.7284567 0.5885113 0.3507063 0.7284638 0.421574 0.7415822 0.5218534 0.4215574 0.7416217 0.5218108 0.4215373 0.7416397 0.5218017 0.1536015 0.9696674 0.1901363 0.1536474 0.9696447 0.1902147 0.1535525 0.9696681 0.1901718 -0.709369 0.06112843 0.7021815 -0.816757 0.06111735 0.5737358 -0.9011684 0.06108456 0.4291436 -0.992256 0.0610851 0.1081508 -0.9602175 0.06111621 0.2724833 -0.9922552 0.06108891 0.108156 -0.9963759 0.06105637 -0.05922245 -0.9211761 0.06113767 -0.3843132 -0.9724572 0.06110578 -0.2249293 -0.9211851 0.06104201 -0.3843072 -0.8439885 0.06103557 -0.5328773 -0.7430471 0.06099766 -0.6664535 -0.4818661 0.06112802 -0.8741101 -0.6211922 0.06112182 -0.7812711 -0.3289903 0.06103837 -0.9423586 0.1668208 0.06103777 -0.9840961 0 0.06103742 -0.9981355 0.1668032 0.06105303 -0.9840981 0.6211755 0.06092762 -0.7812995 0.4818649 0.06091213 -0.8741258 0.6211917 0.06098681 -0.781282 0.743034 0.06099778 -0.6664682 0.9211717 0.06114238 -0.3843234 0.8439667 0.06117111 -0.532896 0.9724547 0.0610513 -0.2249542 0.9211739 0.06104433 -0.3843335 0.972454 0.06106239 -0.2249546 0.9922591 0.0610758 0.1081279 0.9922585 0.06108152 0.1081301 0.9980457 0.06127321 0.01226419 0.960227 0.06107407 0.2724593 0.9011694 0.06105846 0.4291453 0.8167768 0.06105709 0.5737139 0.627229 0.06116795 0.7764291 0.6272056 0.06131786 0.7764362 0.7093904 0.06111896 0.7021608 -0.5830278 0.3498414 -0.7332731 -0.6211919 0.06111192 -0.7812719 -0.6212094 0.06098699 -0.781268 -0.8167583 0.06105691 0.5737403 -0.766587 0.3498076 0.538497 -0.7665843 0.3498215 0.5384918 -0.5498809 0.7405598 0.3862671 -0.5498761 0.7405663 0.3862615 -0.9922565 0.06107693 0.1081514 -0.9313069 0.3498048 0.1015082 -0.9313076 0.3498033 0.1015085 -0.6680282 0.7405651 0.07281219 -0.6680244 0.7405687 0.0728107 -0.921185 0.06103491 -0.3843082 -0.864602 0.3497958 -0.3607024 -0.8645927 0.349818 -0.3607033 -0.6201701 0.740572 -0.2587315 -0.6201837 0.7405601 -0.2587335 -0.5002533 0.7405576 -0.4486883 -0.6973924 0.3498362 -0.6255067 -0.6974049 0.3498055 -0.6255097 -0.7430458 0.06110054 -0.6664456 -0.7511692 0.06113046 -0.6572731 -0.3244187 0.7405592 -0.5884936 -0.3244167 0.7405617 -0.5884916 -0.4182155 0.7405623 -0.5259878 -1.18286e-5 0.06115853 -0.9981281 -1.1102e-5 0.3498114 -0.9368202 -1.12248e-5 0.3498107 -0.9368203 -8.05169e-6 0.7405576 -0.6719928 -8.24887e-6 0.740557 -0.6719936 0.48185 0.06108456 -0.874122 0.4522469 0.3498359 -0.8204191 0.452247 0.3498175 -0.820427 0.324404 0.7405563 -0.5885052 0.3244035 0.740558 -0.5885035 0.8439814 0.0609827 -0.5328944 0.7921264 0.3498326 -0.5001529 0.7921358 0.3497877 -0.5001695 0.568205 0.7405561 -0.3587753 0.5681952 0.7405687 -0.3587648 0.9211721 0.06106531 -0.3843345 0.8645927 0.3497921 -0.3607283 0.864587 0.3498135 -0.3607213 0.6201687 0.7405684 -0.2587456 0.620168 0.7405692 -0.258745 0.9922603 0.06105875 0.1081272 0.9313098 0.3498039 0.1014854 0.931309 0.349806 0.1014857 0.6680277 0.7405672 0.07279568 0.6680253 0.7405692 0.07279598 0.8167721 0.06111741 0.5737141 0.7666074 0.3497928 0.5384777 0.7665995 0.3498113 0.5384767 0.54988 0.7405704 0.386248 0.5498883 0.7405626 0.3862511 -0.1742904 0.9694629 0.1725245 -0.4775838 0.7405579 0.4727449 -0.4775817 0.7405617 0.4727412 -0.6657982 0.3498087 0.65905 -0.6657984 0.3498066 0.6590508 -0.7093702 0.06112229 0.7021811 -0.7093701 0.06111925 0.7021812 -0.174294 0.9694612 0.1725299 -0.1742948 0.9694635 0.1725164 -0.2006753 0.9694629 0.1409648 -0.20068 0.9694612 0.1409698 -0.2214197 0.9694612 0.1054428 -0.9011685 0.06107902 0.4291439 -0.84581 0.3498175 0.4027817 -0.8458136 0.3498032 0.4027866 -0.606702 0.7405664 0.2889189 -0.6067007 0.7405679 0.2889177 -0.2214201 0.9694611 0.1054427 -0.2214206 0.9694611 0.1054431 -0.2359295 0.9694612 0.06695026 -0.6464635 0.7405616 0.1834485 -0.6464579 0.7405675 0.1834452 -0.9012389 0.3498045 0.2557443 -0.9012392 0.3498039 0.2557446 -0.9602196 0.06109178 0.2724815 -0.9602201 0.06107425 0.2724834 -0.2359277 0.9694616 0.06694936 -0.2359272 0.9694619 0.06694871 -0.2437996 0.9694616 0.0265727 -0.2438009 0.9694611 0.02657318 -0.2444351 0.9696615 0.002839505 -0.996375 0.0610699 -0.05922311 -0.9351714 0.3498067 -0.05558526 -0.9351722 0.3498045 -0.05558484 -0.6707993 0.7405665 -0.03987103 -0.6707984 0.7405673 -0.03987121 -0.2572953 0.9662118 -0.01529318 -0.2443983 0.9695167 -0.01751667 -0.2389361 0.9694613 -0.05526643 -0.654694 0.7405701 -0.1514321 -0.6546968 0.7405677 -0.151432 -0.9127269 0.3498002 -0.2111147 -0.9127256 0.3498035 -0.211115 -0.9724583 0.06108045 -0.2249313 -0.9724594 0.06106984 -0.2249294 -0.238938 0.9694609 -0.05526643 -0.2389375 0.9694609 -0.05526655 -0.2263398 0.9694606 -0.09442633 -0.2263359 0.9694616 -0.09442561 -0.2073584 0.9694613 -0.1309475 -0.8439858 0.0610693 -0.5328776 -0.7921379 0.3498225 -0.5001417 -0.7921451 0.3498052 -0.5001422 -0.5682146 0.7405574 -0.3587576 -0.568212 0.7405598 -0.3587568 -0.2073665 0.9694623 -0.1309268 -0.2073692 0.9694617 -0.1309278 -0.1825661 0.9694617 -0.1637482 -0.1825654 0.9694622 -0.1637467 -0.5002554 0.7405555 -0.4486894 -0.4182237 0.7405532 -0.5259941 -0.5830367 0.3498188 -0.733277 -0.4522712 0.3498207 -0.8204122 -0.4818746 0.06102955 -0.8741122 -0.4818761 0.06104016 -0.8741107 -0.1825683 0.9694615 -0.1637478 -0.1526287 0.9694614 -0.1919609 -0.1526282 0.9694618 -0.1919599 -0.1526436 0.9694598 -0.1919571 -0.1183997 0.96946 -0.2147763 -0.1184001 0.9694599 -0.2147768 -0.08083325 0.9694596 -0.2315469 -0.3289893 0.0610544 -0.9423578 -0.3087762 0.3498409 -0.8844594 -0.3087806 0.3498272 -0.8844635 -0.2214931 0.7405588 -0.6344397 -0.2214855 0.7405707 -0.6344283 -0.08083403 0.9694606 -0.231543 -0.08083069 0.9694619 -0.2315385 -0.04099559 0.9694619 -0.2417913 -0.1123329 0.7405576 -0.6625373 -0.1123267 0.7405709 -0.6625236 -0.1565972 0.3498113 -0.9236392 -0.1565929 0.349828 -0.9236336 -0.166843 0.06103801 -0.9840924 -0.1668486 0.06094229 -0.9840973 -0.04099863 0.9694598 -0.2417991 -0.04098939 0.9694619 -0.2417918 -3.00925e-6 0.969462 -0.2452419 -3.11234e-6 0.9694619 -0.2452424 0.04099142 0.9694617 -0.2417925 0.1668196 0.06101149 -0.9840979 0.1565717 0.3498108 -0.9236437 0.1565738 0.3498263 -0.9236375 0.1123131 0.7405572 -0.6625413 0.1123143 0.7405691 -0.6625276 0.04098933 0.9694623 -0.2417908 0.04098904 0.9694615 -0.2417938 0.08082675 0.9694615 -0.2315413 0.2214747 0.7405554 -0.63445 0.2214735 0.7405689 -0.6344347 0.3087569 0.3498383 -0.8844673 0.3087561 0.3498256 -0.8844726 0.3289662 0.061037 -0.9423671 0.3289666 0.06105333 -0.9423659 0.0808261 0.9694629 -0.2315362 0.08082592 0.9694626 -0.2315369 0.118389 0.9694625 -0.2147706 0.1183891 0.9694625 -0.2147709 0.1526182 0.9694626 -0.191964 0.6211789 0.06107717 -0.781285 0.5830203 0.3498161 -0.7332912 0.5830221 0.3497938 -0.7333006 0.418205 0.7405592 -0.5260006 0.4181997 0.7405709 -0.5259885 0.1526246 0.9694617 -0.1919628 0.1526213 0.9694636 -0.1919558 0.743035 0.06091052 -0.6664749 0.6973896 0.3497955 -0.6255326 0.6973831 0.3498398 -0.6255149 0.5002371 0.7405701 -0.4486857 0.5002479 0.7405531 -0.4487019 0.1825588 0.9694633 -0.1637477 0.1825638 0.9694612 -0.1637546 0.1825639 0.969461 -0.1637549 0.2073676 0.9694611 -0.1309344 0.2073681 0.969461 -0.1309345 0.2073685 0.9694612 -0.1309334 0.2263358 0.9694612 -0.09443128 0.226334 0.9694616 -0.09443008 0.2389335 0.9694616 -0.05527293 0.9724545 0.06105774 -0.2249537 0.9127185 0.34981 -0.2111352 0.9127172 0.3498138 -0.2111341 0.6546929 0.7405681 -0.1514467 0.6546949 0.7405662 -0.1514478 0.2389366 0.9694609 -0.05527216 0.2389358 0.969461 -0.05527168 0.2448118 0.9694613 -0.01455694 0.6707962 0.7405683 -0.03988677 0.6707977 0.740567 -0.03988724 0.9351704 0.3498061 -0.05560749 0.9351701 0.3498068 -0.05560737 0.9620203 0.2669169 -0.05720394 0.9955675 0.06112074 -0.07148283 0.2596192 0.9655317 -0.01861095 0.2444347 0.9696616 0.002838194 0.2438007 0.9694615 0.02656739 0.2438012 0.9694613 0.02656733 0.2359313 0.9694612 0.06694364 0.9602274 0.06105834 0.2724611 0.9012437 0.3498067 0.2557247 0.9012444 0.3498049 0.2557245 0.6464574 0.7405717 0.1834297 0.6464679 0.7405624 0.1834299 0.2359313 0.9694612 0.06694352 0.2359301 0.9694614 0.06694352 0.2214208 0.9694616 0.1054378 0.6067044 0.7405697 0.288905 0.6067157 0.7405596 0.2889072 0.8458259 0.349796 0.4027671 0.8458219 0.3498053 0.4027673 0.9011752 0.06111007 0.4291257 0.9011777 0.06107854 0.429125 0.2214199 0.9694618 0.1054376 0.2214199 0.9694617 0.1054376 0.2006818 0.969462 0.1409624 0.2006836 0.9694614 0.1409631 0.1742947 0.9694614 0.1725283 0.7093901 0.06099313 0.7021721 0.6658102 0.3498129 0.6590355 0.6658104 0.3498122 0.6590356 0.4775912 0.7405616 0.4727315 0.4775879 0.740565 0.4727296 0.1742951 0.9694625 0.1725221 0.1743006 0.9694609 0.1725253 -0.546031 -0.1172238 0.8295233 -0.326638 -0.4529882 0.8295235 0.1939767 -0.5237026 0.8295232 0.5429118 -0.1309118 0.8295233 -0.555415 -0.02474373 0.8312052 -0.5554151 -0.02474391 0.831205 -0.5554152 -0.02474755 0.8312049 0.554618 -0.038697 0.8312048 0.5546181 -0.03869694 0.8312048 0.5546178 -0.03869628 0.831205 0.5429117 -0.1309118 0.8295235 0.4175192 -0.370903 0.8295232 0.417519 -0.3709029 0.8295233 0.4949808 -0.2586219 0.8295233 0.4949808 -0.2586219 0.8295233 0.4949805 -0.2586221 0.8295233 0.1939764 -0.5237021 0.8295236 0.315149 -0.4610552 0.8295236 0.3151485 -0.4610556 0.8295234 0.3151485 -0.4610555 0.8295235 0.4175191 -0.3709025 0.8295235 -0.0751658 -0.5533908 0.8295232 -0.07516586 -0.5533909 0.8295233 0.06123197 -0.5551053 0.8295233 0.06123214 -0.5551058 0.8295229 0.06123179 -0.5551055 0.8295231 -0.326638 -0.4529883 0.8295235 -0.2070776 -0.5186615 0.8295235 -0.207079 -0.518661 0.8295235 -0.2070789 -0.518661 0.8295234 -0.07516556 -0.5533905 0.8295233 -0.546031 -0.1172239 0.8295231 -0.5013251 -0.2460985 0.8295231 -0.5013253 -0.2460985 0.8295231 -0.5013253 -0.2460985 0.829523 -0.4267104 -0.3602911 0.8295231 -0.42671 -0.3602904 0.8295236 -0.4267099 -0.3602906 0.8295235 -0.1950687 -0.008690237 0.980751 -0.1950688 -0.008690297 0.980751 -0.1921135 -0.04124361 0.9805057 -0.1921134 -0.04124355 0.9805057 -0.1763843 -0.08658629 0.9805057 -0.1763842 -0.08658629 0.9805058 -0.1501321 -0.1267633 0.9805057 -0.1501322 -0.1267635 0.9805057 -0.1149232 -0.1593779 0.9805056 -0.1149232 -0.1593779 0.9805057 -0.07285797 -0.1824839 0.9805057 -0.07285797 -0.1824839 0.9805056 -0.02644604 -0.194703 0.9805057 -0.02644604 -0.1947029 0.9805057 0.02154362 -0.1953061 0.9805057 0.02154362 -0.1953061 0.9805058 0.06824797 -0.1842574 0.9805057 0.06824803 -0.1842576 0.9805057 0.1108808 -0.1622162 0.9805057 0.1108807 -0.1622161 0.9805057 0.1468983 -0.130497 0.9805057 0.1468983 -0.1304971 0.9805057 0.1741521 -0.09099251 0.9805057 0.1741521 -0.09099251 0.9805057 0.191016 -0.04605948 0.9805057 0.191016 -0.04605948 0.9805057 0.1947886 -0.01359093 0.980751 0.1947887 -0.01359081 0.980751 0.5057054 0.2371879 0.82946 0.07627153 0.5533343 0.82946 -0.4226789 0.3651565 0.8294597 0.5555719 -0.006984174 0.8314391 -0.5554094 0.02514338 0.8311969 -0.5554096 0.02514326 0.8311968 -0.5457195 0.1191061 0.82946 -0.5457196 0.1191061 0.82946 -0.4226784 0.3651563 0.82946 -0.4995829 0.2498257 0.82946 -0.4995836 0.2498244 0.8294602 -0.4995836 0.2498244 0.82946 -0.5457196 0.119106 0.82946 -0.1971094 0.5226317 0.82946 -0.1971098 0.522632 0.8294599 -0.3197404 0.4579983 0.8294597 -0.3197407 0.4579985 0.8294596 -0.3197405 0.4579985 0.8294597 0.07627153 0.5533345 0.8294599 -0.0623396 0.5550768 0.8294597 -0.06233894 0.555077 0.8294597 -0.0623387 0.5550765 0.8294601 -0.1971094 0.5226317 0.8294601 0.3311518 0.449817 0.8294596 0.3311516 0.4498161 0.8294601 0.210184 0.5175119 0.8294602 0.210184 0.5175123 0.82946 0.2101842 0.5175121 0.82946 0.5057057 0.2371882 0.8294598 0.4317243 0.3544157 0.8294599 0.4317235 0.3544164 0.82946 0.4317235 0.3544166 0.8294598 0.3311514 0.4498168 0.8294599 0.5493998 0.0110448 0.8354866 0.5554937 0.01815444 0.8313226 0.548541 0.1053512 0.82946 0.5485413 0.1053514 0.8294599 0.5485411 0.105351 0.82946 0.1952289 0.003924727 0.9807499 0.1952289 0.003924727 0.9807499 0.1930097 0.0370689 0.9804964 0.1930096 0.0370689 0.9804964 0.1779375 0.08345693 0.9804964 0.1779374 0.08345687 0.9804964 0.1519061 0.1247048 0.9804964 0.151906 0.1247048 0.9804965 0.1165189 0.1582722 0.9804965 0.116519 0.1582725 0.9804964 0.07395541 0.1820918 0.9804964 0.07395541 0.1820919 0.9804964 0.02683687 0.1946963 0.9804964 0.02683687 0.1946962 0.9804964 -0.02193456 0.1953092 0.9804964 -0.02193456 0.1953092 0.9804964 -0.06935495 0.1838932 0.9804964 -0.06935489 0.1838931 0.9804964 -0.1125038 0.1611511 0.9804964 -0.1125037 0.1611511 0.9804964 -0.1487234 0.1284837 0.9804964 -0.1487237 0.1284839 0.9804964 -0.1757835 0.08790326 0.9804964 -0.1757836 0.08790332 0.9804964 -0.192017 0.04190868 0.9804964 -0.192017 0.04190868 0.9804964 -0.1950686 0.008830606 0.9807499 -0.1950685 0.008830666 0.9807499 -0.3272666 -0.9426205 -0.06605517 -0.3136991 -0.9491179 -0.02771574 -0.3156049 -0.9449755 -0.08610975 -0.5956048 -0.7645877 -0.246294 -0.5910075 -0.7690292 -0.2435243 -0.3273624 -0.942583 -0.06611466 -0.5953592 -0.7675864 -0.2373996 -0.5859054 -0.7552863 -0.293696 -0.5936778 -0.7681484 -0.2397803 -0.5987225 -0.7635976 -0.2417643 -0.5383294 -0.8140903 -0.2178498 -0.2366302 -0.9715577 0.009045541 -0.1879624 -0.978799 -0.08137947 -0.285165 -0.9561887 -0.06621265 -0.236628 -0.9715584 0.009031713 -0.5936713 -0.7681542 -0.2397781 -0.4826594 -0.8269749 -0.2883617 -0.5048984 -0.8167259 -0.2793501 -0.1218673 -0.9886822 -0.08749783 -0.4878928 -0.8162926 -0.3092362 -0.4734263 -0.8313019 -0.2912123 -0.4669755 -0.831454 -0.3010286 -0.4668954 -0.831452 -0.3011582 -0.1170526 -0.9867113 -0.112693 -0.117067 -0.9867102 -0.1126865 -0.1131711 -0.9870356 -0.1138117 -0.1141981 -0.9869422 -0.1135952 -0.08577549 -0.9891521 -0.1192505 -0.1829001 -0.9763193 -0.1155356 -0.3335467 -0.9122132 -0.2379366 -0.3461856 -0.9122676 -0.218914 -0.4654811 -0.8333008 -0.2982236 -0.4669141 -0.8314251 -0.3012033 -0.03482824 -0.9990943 -0.02444738 -0.04179465 -0.9987379 -0.02785027 -0.04179483 -0.9987379 -0.02785009 -0.09978491 -0.9921827 -0.074943 -0.0459302 -0.9964488 -0.070571 -0.1757071 -0.9789927 -0.1034424 -0.5462296 -0.8129492 -0.2018586 -0.1745815 -0.9789782 -0.1054653 -0.1296097 -0.9878107 -0.086205 -0.1465926 -0.9848343 -0.09280121 -0.1204604 -0.989103 -0.0846439 -0.1199921 -0.9892008 -0.08416438 -0.1714897 -0.9808927 -0.09187358 -0.1465989 -0.9807961 -0.1286386 -0.3344721 -0.9246905 -0.1818677 -0.3310286 -0.9247896 -0.1875748 -0.5031098 -0.8256911 -0.2551761 -0.04180574 0.9987373 -0.0278567 -0.03838777 0.999009 -0.02252686 -0.3573482 0.9119005 -0.2018407 -0.08581507 0.989147 -0.1192645 -0.08580565 0.9891479 -0.1192639 -0.116957 0.9866808 -0.113058 -0.1169943 0.9866783 -0.1130414 -0.487907 0.8162838 -0.3092368 -0.4879545 0.8162413 -0.3092742 -0.4873657 0.8167358 -0.3088969 -0.1632772 0.9810753 -0.104076 -0.5324764 0.8034167 -0.2664408 -0.5154941 0.8165151 -0.2599404 -0.3710405 0.8967645 -0.2411273 -0.3995105 0.8810843 -0.2531442 -0.3335721 0.9121989 -0.2379556 -0.148487 0.9838638 -0.09981679 -0.1665861 0.9787341 -0.1197019 -0.5137844 0.8178036 -0.259274 -0.0312913 0.9985697 -0.04335111 -0.1144126 0.9905138 -0.07610654 -0.1607971 0.9837678 -0.0796566 -0.02956593 0.9993683 -0.01971888 -0.03838753 0.999009 -0.02252733 -0.1218673 0.9886823 -0.08749634 -0.1203007 0.9891502 -0.08431845 -0.1195741 0.9892591 -0.08407425 -0.1715071 0.9808924 -0.09184384 -0.03523588 0.9990756 -0.02462857 -0.03956139 0.9988587 -0.02676039 -0.5359977 0.8157499 -0.2173905 -0.3236007 0.9460697 -0.01531779 -0.2031168 0.97515 -0.08846455 -0.2366311 0.9715574 0.009045243 -0.5479469 0.7806357 -0.3006029 -0.5359783 0.8148301 -0.2208601 -0.2806444 0.9527094 -0.1165475 -0.5932323 0.7684774 -0.2398291 -0.5507782 0.803533 -0.2257832 -0.5359567 0.8148538 -0.2208251 -0.3405676 0.9392817 -0.04199689 -0.2849226 0.9561491 -0.06780874 -0.5859057 0.7552868 -0.2936945 -0.595396 0.7676343 -0.2371522 -0.3274495 0.9425636 -0.06596046 -0.3273535 0.9426012 -0.06590038 -0.5908673 0.7692603 -0.2431348 -0.3016023 0.95032 -0.07699328 3.02009e-4 -0.9790127 -0.203799 -0.01184725 -0.9516049 -0.3070958 -4.04806e-4 -0.9790127 -0.203799 0.01310396 -0.9515898 -0.3070914 0.3391761 -0.8232307 -0.4552479 0.006085276 -0.94099 -0.3383794 -4.72867e-4 0.9781572 -0.207866 6.38932e-4 0.9781571 -0.207866 0.02829784 0.948693 -0.3149298 0.01771587 0.9449849 -0.326634 -0.3574993 0.8134506 -0.4587945 -0.02149969 0.9488552 -0.3149785 -0.2947738 -0.83622 -0.462433 0 -0.9420862 -0.3353706 0 -0.8750931 -0.4839547 5.38224e-6 -0.8750979 -0.483946 7.13319e-6 -0.7660325 -0.642802 0 -0.7660232 -0.642813 0 -0.7660374 -0.6427961 -1.34002e-7 -0.766037 -0.6427966 0 -0.6285255 -0.777789 0 -0.6285255 -0.777789 0 -0.4676074 -0.8839362 0 -0.4676082 -0.8839358 0 -0.4676761 -0.8838999 -1.52414e-7 -0.4676759 -0.8839001 0 -0.2894607 -0.9571899 0 -0.2894609 -0.9571899 0 -0.2894681 -0.9571877 -1.23829e-7 -0.2894678 -0.9571878 0 -0.1004989 -0.9949372 0 -0.1004989 -0.9949372 0 0.0918104 -0.9957765 0 0.09181314 -0.9957762 0 0.092202 -0.9957404 0 0.09220194 -0.9957404 1.34206e-7 0.2814566 -0.9595739 0 0.281457 -0.9595739 0 0.2814504 -0.9595757 1.43628e-7 0.2814501 -0.959576 2.39425e-7 0.4602795 -0.8877741 0 0.4602798 -0.8877739 0 0.4603477 -0.8877388 2.40683e-7 0.4603444 -0.8877404 3.23549e-7 0.6220037 -0.7830144 3.29527e-7 0.6220036 -0.7830144 3.95665e-7 0.7606414 -0.6491723 0 0.7606425 -0.6491711 0 0.7606384 -0.6491758 5.41328e-7 0.7606377 -0.6491767 6.04114e-7 0.8710295 -0.4912307 0 0.8710299 -0.4912297 0 0.8710309 -0.4912282 0.1593497 -0.9840987 -0.07846993 0.02977329 -0.9993643 -0.01960879 0.03791511 -0.9989689 -0.02496898 0.03412753 -0.9991315 -0.02390617 0.1218955 -0.9886934 -0.08733129 0.1218463 -0.9887101 -0.08721154 0.1211074 -0.9889451 -0.08555942 0.1201203 -0.9892064 -0.08391511 0.08769571 -0.9889062 -0.1198916 0.355661 -0.9127972 -0.200765 0.3318152 -0.913102 -0.236946 0.08774727 -0.9889019 -0.1198899 0.1170329 -0.986693 -0.1128732 0.1170522 -0.9867012 -0.1127814 0.4880021 -0.8161975 -0.3093149 0.4880079 -0.8161923 -0.3093191 0.1198701 -0.9892435 -0.08383536 0.169048 -0.9814131 -0.09083515 0.1609968 -0.9815879 -0.1027874 0.02699899 -0.9987924 -0.04104632 0.114825 -0.9905084 -0.07555305 0.5210455 -0.8123216 -0.2620025 0.5156702 -0.8164041 -0.2599398 0.3696374 -0.8975417 -0.2403892 0.397402 -0.8823294 -0.252124 0.3317797 -0.9131168 -0.2369388 0.03794527 -0.9990307 -0.02231407 0.03794759 -0.9990307 -0.02231031 0.1471182 -0.9842041 -0.09848093 0.1663684 -0.9788091 -0.1193916 0.5156044 -0.8164545 -0.2599119 0.5374256 -0.8146079 -0.2181459 0.3234848 -0.9461088 -0.01535677 0.2024737 -0.9752638 -0.08868479 0.2362496 -0.9716503 0.009048998 0.5479057 -0.7806733 -0.3005805 0.5360015 -0.8147478 -0.2211076 0.338396 -0.9305889 -0.1396162 0.5933027 -0.7683424 -0.2400875 0.5405181 -0.8113477 -0.2226098 0.535994 -0.814756 -0.2210953 0.5936084 0.7682612 -0.2395913 0.2367783 0.9715229 0.008903026 0.5361196 0.8157767 -0.216989 0.3383437 0.9304451 -0.1406956 0.1877163 0.978776 -0.08222109 0.2855444 0.9560345 -0.06680148 0.2367782 0.9715229 0.008902072 0.5936335 0.7682391 -0.2395995 0.5193438 0.8097516 -0.2731015 0.5046636 0.8169112 -0.2792324 0.1218967 0.9886938 -0.08732622 0.1209174 0.9890049 -0.08513677 0.1194024 0.9893236 -0.08355629 0.1274123 0.9882122 -0.08486968 0.1001735 0.9921512 -0.07484143 0.04101556 0.9987837 -0.02736371 0.04101568 0.9987837 -0.02736353 0.1755015 0.9789462 -0.1042291 0.1293812 0.9878432 -0.08617562 0.1747319 0.9789387 -0.1055832 0.487626 0.8164777 -0.3091685 0.4764052 0.8288645 -0.2932947 0.4653916 0.8324902 -0.3006174 0.4654012 0.8324903 -0.3006017 0.1169225 0.9866444 -0.1134107 0.117038 0.9866935 -0.1128624 0.087704 0.9889057 -0.1198899 0.2046044 0.9706965 -0.1260377 0.331801 0.9131092 -0.2369384 0.3443964 0.9131628 -0.2180019 0.4638463 0.8345118 -0.2973831 0.4637812 0.8345767 -0.297302 0.1691048 0.9814109 -0.09075361 0.1443004 0.9813048 -0.1273511 0.3329455 0.9254034 -0.1810409 0.3293478 0.9255064 -0.1869972 0.04650998 0.9963884 -0.071042 0.5528199 0.8081319 -0.2032556 0.5441104 0.8145411 -0.201163 0.3405088 -0.9393041 -0.04197293 0.2848199 -0.9561828 -0.06776583 0.5859221 -0.7552726 -0.2936983 0.5954201 -0.7676368 -0.2370839 0.3269359 -0.9427657 -0.06561762 0.5910614 -0.7690833 -0.2432227 0.3400866 -0.9352382 -0.09834015 0.5910274 0.7691159 -0.2432022 0.3269324 0.9427665 -0.06562459 0.5954196 0.7676361 -0.2370873 0.5859218 0.7552722 -0.2936998 0.3400862 0.9352369 -0.09835332 0.316145 0.9448912 -0.08504641 0.3142693 0.94892 -0.02802872 0.9664217 0.232519 0.1093795 0.9152194 0.1572415 0.3710103 0.699109 0.1505034 0.6989959 0.5294335 0.7996339 0.2833472 0.8615331 0.4796815 0.1663327 0.9336742 0.3508099 0.07200574 0.9259274 0.3612775 0.1101685 0.9408942 0.3307731 0.0728529 0.946537 0.3210314 0.03172856 0.944848 0.3252603 0.03831589 0.9491268 0.314468 0.01638156 0.8609588 0.4828696 0.1599591 0.8609533 0.4828749 0.1599719 0.8609599 0.4828693 0.1599538 0.7345983 0.633987 0.2417143 0.7346202 0.6339753 0.2416782 0.6190496 0.7010333 0.3540193 0.6238495 0.678332 0.3881717 0.7317921 0.1439441 0.6661534 0.7509081 0.4217568 0.508191 0.7509564 0.4216281 0.5082267 0.7241321 0.4835237 0.49177 0.7223949 0.4304658 0.5411514 0.6418496 0.6723497 0.368748 0.7628679 0.254889 0.594192 0.868015 0.2146968 0.4477223 0.8926783 0.01391148 0.4504796 0.8926784 0.01390981 0.4504793 0.7880373 0.09173613 0.6087542 0.7903215 0.09091508 0.6059096 0.7887195 0.09747171 0.6069769 0.7887248 0.09746628 0.6069707 0.9664334 0.2325003 0.1093157 0.9664223 0.2325152 0.1093832 0.9654527 0.1872303 0.1812344 0.9576843 0.2093208 0.1975488 0.9157369 0.3009794 0.2661532 0.9548896 0.0958755 0.2810583 0.9549072 0.0957033 0.2810569 0.9152144 0.1572447 0.3710212 0.9101015 0.1449767 0.3881971 0.8655623 0.3310937 0.3757378 0.8539394 0.4283595 0.2954584 0.7344567 0.6297664 0.2529183 0.7345965 0.633984 0.2417278 -0.5862615 0.5630686 -0.5824528 -0.4721089 0.7477136 -0.4669451 -0.70239 0.06429153 -0.7088827 -0.6867277 0.198774 -0.6992096 -0.6610363 0.356819 -0.6600843 -0.6932634 0.1986004 -0.6927798 -0.6623119 0.3566496 -0.658896 -0.5880942 0.5611425 -0.582464 -0.6464262 0.35683 -0.6743927 -0.4731511 0.7463936 -0.4680007 -0.1385082 0.9813714 -0.1331385 -0.3908082 0.8363943 -0.3843351 -0.4631789 0.7464103 -0.4778461 -0.1729607 0.9705386 -0.1677479 -0.172708 0.9705079 -0.1681855 -0.1726244 0.9705374 -0.1681011 -0.1351823 0.9813824 -0.1364346 -2.37318e-6 1 1.04095e-6 -2.9752e-7 1 -3.60032e-7 -2.01447e-6 1 1.44075e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.95203e-6 1 1.40811e-6 3.00577e-7 1 -3.57581e-7 3.01694e-7 1 -3.56812e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.4370794 0.7903138 -0.4293782 0.0456289 0.9979347 -0.0452125 0.5480126 0.6396552 -0.5390022 0.4370161 0.7903769 -0.4293265 0.5211275 0.6653938 -0.5344881 0.1515654 0.975868 -0.157193 0.2557303 0.9341494 -0.2489316 0.1571622 0.9758947 -0.1514248 0.2577695 0.9341896 -0.2466673 0.2578752 0.9341336 -0.2467686 0.5352397 0.6654013 -0.5203456 0.6773409 0.240891 -0.6951121 0.6341298 0.450491 -0.6284405 0.6905065 0.2406615 -0.6821164 0.6350299 0.4505212 -0.627509 0.6945853 0.2408891 -0.6778817 0.7050563 0.1218974 -0.6985962 -0.4020562 0.8531898 0.3322921 -0.3748583 0.853935 0.3609383 -0.3742471 0.8544732 0.3602977 -0.373965 0.8548752 0.3596369 -0.3365274 0.9057957 0.2574557 -0.4022201 0.8502635 0.3395158 -0.402229 0.8502486 0.3395427 -0.4041934 0.8550873 0.324736 -0.4041686 0.8550982 0.3247381 -0.4019224 0.8565461 0.3237085 -0.3955122 0.8610869 0.31953 -0.4135759 0.8479267 0.3316252 -0.4005029 0.857577 0.322737 -0.4044609 0.8549808 0.3246834 -0.4039024 0.8549668 0.3254143 -0.4122195 0.8547602 0.3153732 -0.4391325 0.8596996 0.2609198 -0.4556835 0.8553751 0.2463449 -0.4832617 0.858824 0.1699392 -0.4806352 0.8583744 0.1793972 -0.4843153 0.8581559 0.1703144 -0.4846146 0.8558211 0.1808837 -0.5064393 0.8572975 0.09252125 -0.506309 0.857509 0.09126651 -0.5061157 0.8574951 0.09246188 -0.5061188 0.8576251 0.09122937 -0.5150291 0.8567696 0.02628177 -0.509649 0.8603824 -2.78521e-4 -0.5125524 0.8585381 -0.01422321 -0.5136201 0.8552106 -0.06934899 -0.5109816 0.854586 -0.09263169 -0.5135283 0.8552668 -0.06933617 -0.5023369 0.8598577 -0.09111791 -0.4972435 0.8546712 -0.149285 -0.4807134 0.8581991 -0.1800248 -0.4919361 0.858013 -0.1476905 -0.4773856 0.8603147 -0.1787776 -0.4679737 0.8544766 -0.2255449 -0.4379184 0.8603419 -0.2608435 -0.4234618 0.8569456 -0.2938103 -0.443004 0.8568027 -0.2638877 -0.4095538 0.8513146 -0.3279161 -0.4146067 0.8554092 -0.3104451 -0.4147629 0.8552438 -0.3106923 -0.3807615 0.8861305 -0.2641847 -0.3898787 0.8570891 -0.3367388 0.4171206 0.8552851 -0.3074047 0.3837086 0.885431 -0.262259 0.3926582 0.8571 -0.3334656 0.4398927 0.8603194 -0.2575749 0.4254308 0.8570065 -0.2907721 0.4448681 0.8568719 -0.2605051 0.4193081 0.8529775 -0.3108216 0.4057067 0.8564038 -0.3193348 0.4715903 0.8776972 0.08514803 0.5120742 0.8588605 0.01177656 0.5132249 0.8534951 -0.09025603 0.5133562 0.8554379 -0.06849342 0.5111191 0.8547981 -0.08987486 0.5045516 0.8607529 -0.0673204 0.4936239 0.8505799 -0.181244 0.4925342 0.8579496 -0.1460565 0.4820104 0.8581047 -0.1769806 0.4844383 0.8629503 -0.1436537 0.4690313 0.8545497 -0.223057 0.4016231 0.856616 0.3238949 0.4013863 0.8567907 0.3237262 0.404372 0.8551204 0.3244265 0.4008566 0.8571704 0.3233772 0.4019653 0.8563717 0.3241167 0.4018368 0.8564633 0.3240339 0.4037961 0.8551814 0.3249821 0.4041803 0.8550123 0.3249496 0.4037094 0.8550007 0.325565 0.4146786 0.8546868 0.3123332 0.4385182 0.8599158 0.2612403 0.4573438 0.8551945 0.2438831 0.4791808 0.8590475 0.1800647 0.4844724 0.8584709 0.168268 0.4796102 0.8587754 0.180219 0.4882575 0.8560667 0.1695712 0.5056915 0.8577019 0.09286296 0.5064076 0.857433 0.09143292 0.5061582 0.8574175 0.09294748 0.5333663 0.8458821 0.002013802 0.4018038 0.8532636 0.3324079 0.4019072 0.8503939 0.3395598 0.3856976 0.8756981 0.2904999 0.3749299 0.8559675 0.3560158 0.3761476 0.8541236 0.3591458 0.4562187 -0.7806723 0.427101 0.701897 -0.1894289 0.6866276 0.6915073 -0.08578908 0.7172572 0.6801437 -0.02847522 0.7325255 0.6810714 -0.2129769 0.7005588 0.6810759 -0.2129672 0.7005573 0.5928804 -0.5411415 0.5963713 0.5217173 -0.7388558 0.426501 0.6279717 -0.4998389 0.5965003 0.6281287 -0.4994964 0.5966219 0.6103984 -0.5407798 0.5787668 0.6706134 -0.490909 0.5561349 0.4532345 -0.748229 0.4844912 0.4599402 -0.780674 0.4230875 0.431567 -0.7758153 0.4602829 0.4640045 -0.7809076 0.4181902 0.4621478 -0.7807958 0.420449 0.9996042 -0.005297422 0.02763229 -0.6282907 0.01588869 0.7778165 0.6935153 0.02398163 0.7200427 0.6283047 0.01629054 0.7777968 0.6286125 0.005516648 0.7776992 0.677096 -0.3039391 0.6701956 0.6862439 0.04583597 0.7259259 0.6935201 0.02397006 0.7200384 0.6794487 0.001542925 0.7337214 0.6789978 5.36186e-4 0.7341402 0.6790005 8.70529e-4 0.7341373 0.7067056 0.009911835 0.7074383 0.7067148 0.009936749 0.7074287 0.7177773 0.0822575 0.6913968 0.6931082 0.02565294 0.720377 -0.7178102 0.08400988 0.6911519 -0.6815654 0.001389861 0.7317559 -0.6815657 0.001195073 0.731756 -0.6816028 0.001295268 0.7317214 -0.7062081 0.009768962 0.707937 -0.6999042 0.01647633 0.7140467 -0.6999149 0.01646375 0.7140365 -0.6932193 0.02491772 0.7202959 -0.6932348 0.02488112 0.7202822 -0.710343 -0.03163772 0.7031443 -0.6285547 0.005475103 0.7777462 -0.6285499 0.005492627 0.77775 -0.7068136 0.009935915 0.70733 -0.7066321 0.009444296 0.7075181 -0.7203165 0.009443402 0.6935813 -0.7106687 0.009095728 0.703468 -0.794199 -0.008381605 0.6075999 -0.8182384 0.01085829 0.5747765 -0.8796387 -0.009925305 0.4755387 -0.9028352 -0.005745351 0.4299486 -0.8796687 -0.005768597 0.475552 -0.9027873 0.01219069 0.4299144 -0.9433131 -0.01104563 0.3317204 -0.9619768 0.009032905 0.2729819 -0.9433303 0.008997976 0.3317335 -0.9619333 0.01309698 0.2729702 -0.9836509 -0.01174074 0.1797028 -0.9940208 0.01357823 0.1083432 -0.9997169 -0.005097448 0.02324151 -0.9997168 -0.005097448 0.02324205 -0.9933794 -0.03837966 0.1082785 -0.9981454 0.01363354 -0.05932766 -0.990938 -0.01185035 -0.1337963 -0.9742725 0.00333625 -0.2253488 -0.9910016 0.003261923 -0.1338103 -0.9741921 0.01326167 -0.2253307 -0.9577071 -0.01126712 -0.2875243 -0.9228309 0.01246649 -0.3850036 -0.9008221 0.002870738 -0.4341788 -0.9008302 0.002870738 -0.4341622 -0.7525475 -0.008756995 -0.6584798 -0.8215758 -0.008820414 -0.5700309 -0.8455114 0.01124393 -0.5338389 -0.9227144 -0.02037924 -0.3849453 -0.5780128 0.02166736 -0.81574 -0.6222133 0.02228188 -0.7825305 -0.6657351 -0.001461207 -0.7461867 -0.7444279 0.00382173 -0.667692 -0.7517176 0.01548099 -0.6593036 -0.7338544 0.02077758 -0.6789889 -0.7339672 0.02065545 -0.6788708 -0.7613557 -0.008769452 -0.6482752 -0.7805787 0.05836272 -0.6223267 -0.7803537 0.3128972 -0.5414273 -0.751624 0.01506149 -0.6594198 -0.7517184 0.01548689 -0.6593024 -0.5781649 0.02166759 -0.8156322 -0.6219537 -0.03593689 -0.7822288 -0.444922 0.03384894 -0.8949294 -0.4827674 -0.002505302 -0.8757451 -0.4451887 -0.002539992 -0.8954332 -0.4826248 -0.02505671 -0.8754687 -0.3012659 0.02351444 -0.9532502 -0.3295689 -0.01477849 -0.9440159 -0.167109 0.009258389 -0.985895 -0.3019055 0.009145498 -0.953294 -0.1671482 0.01153552 -0.9858644 0.7449414 0.01290625 -0.6670051 0.7572776 0.02109217 -0.6527524 0.7446891 0.4328842 -0.5079857 0.7349145 0.02255517 -0.6777846 0.7347412 0.0227226 -0.677967 0.8040096 -0.05546784 -0.5920235 0.7348799 0.02257919 -0.6778213 0.7443952 0.008180677 -0.6676892 0.6722756 -0.002833902 -0.7402957 0.6222172 0.02066224 -0.7825719 0.5853813 0.01737892 -0.8105719 0.6222374 0.01740866 -0.782635 0.5853875 -0.0156883 -0.810602 0.4826881 0.01741558 -0.8756192 0.453056 -0.002290487 -0.891479 0.4827424 -0.00226885 -0.8757595 0.4530073 -0.0118919 -0.8914274 0.3295533 0.01306092 -0.9440466 0.3097403 -0.006996273 -0.9507955 0.1671101 0.007622838 -0.9859089 0.158842 0.007258594 -0.9872774 0.167128 0.00725907 -0.9859085 0.1589854 -0.001006841 -0.9872804 0 0.001083672 -0.9999995 0.004412114 0.003548681 -0.999984 -2.36862e-5 0.003549158 -0.9999937 0.004400014 0.00607866 -0.9999719 -0.1502799 -0.005291283 -0.9886294 0.7786501 0.03589552 -0.626431 0.7723709 -0.007276475 -0.6351301 0.8260906 -0.007305979 -0.56349 0.845507 0.01010245 -0.5338686 0.9038346 -0.009198069 -0.427783 0.922896 0.002237319 -0.3850429 0.9038726 0.002211928 -0.427796 0.9228314 0.01174181 -0.385025 0.9594696 -0.0105856 -0.2816135 0.9741915 0.01287823 -0.2253559 0.9916909 0.004488527 -0.1285653 0.9742619 0.004565358 -0.2253727 0.9916349 -0.01147329 -0.1285627 0.9973909 0.009101271 -0.07161378 0.9995641 -0.01039612 0.02763259 0.9998387 -0.01310658 0.01228624 0.9941011 -0.005241453 0.1083309 0.982602 0.03127598 0.1830714 0.9936 -0.03218257 0.1082741 0.9420406 0.03066611 0.3340943 0.9619764 0.0098055 0.2729566 0.9424542 0.009769141 0.3341926 0.9617056 -0.02567774 0.272879 0.8785974 0.02439373 0.4769399 0.9028488 -0.005689024 0.4299206 0.9028393 -0.005689024 0.4299405 0.700308 0.01605832 0.7136601 0.7064461 0.009503901 0.7077031 0.7106626 0.00950396 0.7034688 0.7201723 0.007294714 0.6937569 0.8182216 -0.01414662 0.5747288 0.793584 0.0186308 0.6081753 0.8788158 -0.01000642 0.4770562 -0.004662632 0.9999892 8.59578e-6 0.003101468 0.9999952 8.72167e-6 -0.08134251 0.9964193 0.02305948 -0.08135002 0.9964188 0.02305746 -0.1583558 0.9873734 0.004147827 -0.2427918 0.9700784 -9.65796e-5 -0.214393 0.9767474 2.11681e-4 -0.214475 0.9767295 2.20285e-4 -0.2144759 0.9767293 2.20288e-4 -0.002663254 0.9982817 0.05853801 -0.1592451 0.9867038 -0.03250616 -0.1371631 0.9903047 -0.02197098 -0.1371805 0.9903023 -0.02197569 -0.0782718 0.9969094 -0.006721258 0.003450512 0.999994 8.76283e-6 0.08142822 0.9964132 -0.02302885 0.08143335 0.9964128 -0.02302747 0.1583784 0.9873698 -0.004143774 0.2428125 0.9700732 1.00151e-4 0.2144931 0.9767255 -2.19699e-4 0.2144873 0.9767268 -2.19089e-4 0.2144873 0.9767267 -2.19089e-4 0.002628922 0.9982814 -0.05854338 0.1592348 0.9867051 0.0325154 0.1372051 0.9902983 0.02199727 0.1371994 0.9902991 0.02199578 0.07827574 0.996909 0.006724357 -0.003484189 0.9999939 8.73446e-6 -0.004245281 -0.999991 0 0.004244625 -0.999991 0 -0.08143991 -0.9964057 -0.02330923 -0.157908 -0.9874445 -0.004276335 -0.2144572 -0.9767334 -7.34923e-6 -0.1925677 -0.9812167 0.01146739 -0.2266606 -0.9739738 1.29548e-5 -0.229642 -0.9732747 8.46456e-4 -0.2014446 -0.9794683 -0.007870256 -0.1976665 -0.9802353 0.008170127 -0.152685 -0.9882749 2.17855e-4 -0.152687 -0.9882746 2.17853e-4 -0.003778517 -0.9999929 9.60373e-7 -0.08738428 -0.9961417 -0.008108794 0.003526687 -0.9998582 0.01646882 -0.07881444 -0.9968883 0.001397728 0.08142858 -0.9964065 0.02331221 0.1579062 -0.9874448 0.004276812 0.2144531 -0.9767343 7.168e-6 0.192563 -0.9812176 -0.01147186 0.2266659 -0.9739726 -1.31454e-5 0.2295866 -0.9732879 -8.29578e-4 0.20144 -0.9794692 0.00787127 0.1976674 -0.980235 -0.008170425 0.1526847 -0.988275 -2.17881e-4 0.1526843 -0.988275 -2.17881e-4 0.003780126 -0.9999928 -9.6053e-7 0.08738428 -0.9961417 0.008108675 -0.003526687 -0.9998582 -0.01646864 0.0788151 -0.9968883 -0.001397609 -0.08008843 0.7131136 0.6964589 -0.03884869 0.716526 0.6964777 0.09538209 0.691978 0.7155897 0.1150959 0.702055 0.7027601 0.2615911 0.6565438 0.7074747 0.2655918 0.6539359 0.7083989 0.2612034 0.6555712 0.7085189 0.2645626 0.6514022 0.711113 0.4008265 0.591175 0.6998931 0.4151202 0.5638738 0.7139477 0.3933061 0.580082 0.7133129 0.4125654 0.5604047 0.7181479 0.5223039 0.4947527 0.6945634 0.5344222 0.4387254 0.7224355 0.6143211 0.3696247 0.6971279 0.5554352 0.4559738 0.6953988 0.6188519 0.3723509 0.6916482 0.6244032 0.2928602 0.7241225 0.6848009 0.2307363 0.691237 0.6889261 0.132313 0.7126529 0.6653996 0.2241976 0.7120245 0.678175 0.1302485 0.7232662 0.7163841 0.07791149 0.6933425 0.7069166 0.02310317 0.7069195 0.7070774 -0.008888781 0.7070802 0.7105316 -0.07727485 0.6994094 0.7180378 -0.05009925 0.6941986 0.7180379 -0.05009829 0.6941986 0.7184889 -0.07814049 0.6911351 0.6714475 -0.1619055 0.7231492 0.6836478 -0.2303476 0.6925067 0.6215134 -0.3247341 0.7129298 0.6652503 -0.2241479 0.7121797 0.6143674 -0.3210002 0.7207715 0.615437 -0.3702962 0.6957858 0.5048999 -0.4782667 0.7185659 0.5275141 -0.4686169 0.7086094 0.5122607 -0.4852393 0.7086126 0.5352846 -0.4755194 0.6981058 0.3952975 -0.5830201 0.7098081 0.3986663 -0.5832403 0.7077401 0.3963901 -0.5846266 0.7078748 0.3987148 -0.5833098 0.7076555 0.2634006 -0.6610856 0.7025568 0.2428935 -0.6557698 0.7148208 0.1160127 -0.7076464 0.6969774 0.07779067 -0.7052226 0.7047055 0.1147027 -0.6996562 0.7052124 0.07611221 -0.6900023 0.7197943 -0.03902041 -0.7196888 0.6931995 -0.09302365 -0.6848646 0.7227081 -0.1856814 -0.6687637 0.719915 -0.09315681 -0.6858471 0.7217587 -0.1933042 -0.6962187 0.6913125 -0.2559155 -0.6409795 0.7236385 -0.3376994 -0.636969 0.6929861 -0.2681831 -0.6717107 0.6905669 -0.3384295 -0.6383455 0.6913613 -0.4043009 -0.5606927 0.7226095 -0.4665106 -0.5492187 0.6933446 -0.5480501 -0.4166182 0.7253071 -0.532005 -0.4491961 0.7177699 -0.5552949 -0.4221242 0.7165604 -0.5529731 -0.4669001 0.6900905 -0.6339214 -0.293283 0.7156318 -0.6349868 -0.3117124 0.706843 -0.6417667 -0.2969133 0.7070912 -0.6398207 -0.3140855 0.7014128 -0.6903543 -0.1519584 0.7073328 -0.6883366 -0.1477745 0.7101799 -0.713558 0 0.7005962 -0.7125395 -0.03174853 0.7009134 -0.7125397 -0.03174382 0.7009133 -0.7227656 0 0.6910933 -0.7093012 0.03211009 0.7041738 -0.6879326 0.1514253 0.7098023 -0.6888425 0.1503435 0.7091494 -0.6885548 0.1515622 0.7091694 -0.6891937 0.15042 0.7087918 -0.6466522 0.2991731 0.7016668 -0.6238499 0.3119657 0.7165814 -0.5686481 0.4322762 0.6998405 -0.6399937 0.3200408 0.6985569 -0.5718367 0.4346989 0.6957296 -0.5239093 0.4526107 0.7215695 -0.4672402 0.5500778 0.6921712 -0.4041312 0.5788803 0.7082199 -0.08008736 0.7131136 0.6964589 -0.03709137 0.6841089 0.7284361 -0.2618075 0.6941773 0.6705033 -0.1877824 0.6763313 0.7122596 -0.2474908 0.6562163 0.7128314 -0.1795811 0.6467928 0.7412218 -0.4355862 0.6239362 0.6488206 -0.315891 0.5958338 0.7383732 -0.4570307 0.5380579 0.708249 -0.3219484 -0.9435635 -0.0776996 -0.5928764 -0.7543314 -0.281925 -0.6036073 -0.7521983 -0.2643027 -0.302942 -0.946833 -0.1083208 -0.3040103 -0.9464516 -0.1086607 -0.3032262 -0.9467547 -0.1082101 -0.3028213 -0.9469 -0.1080725 -0.1337148 -0.9431256 -0.3043594 -0.3929713 0.4232606 -0.816348 -0.3929422 -0.09241789 -0.9149074 -0.3929421 -0.7044168 -0.5910951 -0.6433543 0.6725198 -0.3658038 -0.6562374 0.6666145 -0.3535215 -0.3929547 0.8009625 -0.4517142 -0.3944247 0.8481983 -0.3535372 -0.540844 0.7740864 -0.3290562 -0.2884835 0.9363083 -0.2002595 -0.267125 0.9412167 -0.2067732 -0.2683244 0.9142697 -0.3035013 -0.4159787 0.8665158 -0.2758843 -0.4159758 0.8665166 -0.275886 -0.02082949 0.9779451 -0.207821 -0.1522454 0.9796952 -0.1304554 -0.1522417 0.9796953 -0.1304594 -0.2182401 -0.9588819 -0.1814305 -0.2641042 -0.9423843 -0.2053315 -0.2641046 -0.9423797 -0.2053515 -0.279469 -0.9396488 -0.197376 -0.2787411 -0.9397917 -0.1977245 -0.2823847 -0.9388986 -0.196795 -0.2823341 -0.9389132 -0.196798 -0.5354956 -0.7785732 -0.3272128 -0.5354897 -0.7786488 -0.3270426 -0.5354879 -0.7785773 -0.3272154 -0.6140938 -0.6045778 -0.5073208 -0.6155835 -0.6666828 -0.4202272 -0.6628069 -0.6691321 -0.3360792 -0.6141031 -0.2284493 -0.7554393 -0.614102 -0.3691138 -0.6975914 -0.6140951 -0.3691069 -0.6976011 -0.6140992 -0.3691018 -0.6976002 -0.614099 -0.4960478 -0.6138558 -0.6141133 -0.4960343 -0.6138525 -0.6140984 -0.4960595 -0.613847 -0.6140962 -0.07932424 -0.7852347 -0.6141111 0.07275211 -0.7858593 -0.6140779 0.3632597 -0.7006788 -0.614099 0.3632782 -0.7006506 -0.6140993 0.2221279 -0.7573251 -0.6140968 0.4909027 -0.6179802 -0.6140916 0.4909123 -0.6179776 -0.6140975 0.6003181 -0.51235 -0.6140966 0.6003182 -0.5123509 -0.6140944 0.6003267 -0.5123437 -0.6150771 0.674114 -0.4089625 -0.7240663 0.5819472 -0.3702234 -0.6525575 -0.6711531 -0.3517417 -0.626055 -0.682384 -0.3773689 -0.3929524 -0.8047052 -0.4450144 -0.3944825 -0.8473591 -0.3554798 -0.4088966 -0.8690707 -0.2784238 -0.3929395 -0.5779665 -0.7152295 -0.3929441 -0.5779631 -0.7152298 -0.3929426 -0.4300599 -0.8128005 -0.392947 0.2588166 -0.8823869 -0.6140915 0.2221354 -0.7573291 -0.6141088 0.2221782 -0.7573027 -0.392969 0.5719709 -0.7200171 -0.3929452 0.5719662 -0.7200338 -0.3929473 0.6994521 -0.5969583 -0.4098918 -0.8702871 -0.2731102 -0.3958433 -0.8739368 -0.2820324 -0.133717 -0.9431248 -0.3043604 -0.1336374 -0.9846774 -0.112033 -0.09693092 -0.9744027 -0.2028393 -0.1337162 -0.8672448 -0.4795897 -0.1337099 -0.8672388 -0.4796024 -0.3929607 -0.8046998 -0.4450169 -0.392962 -0.7044028 -0.5910987 -0.6140959 -0.6045717 -0.5073255 -0.614098 -0.6045714 -0.5073235 -0.1337116 -0.6228815 -0.7708047 -0.1337247 -0.6228747 -0.7708079 -0.1337226 -0.7591574 -0.637023 -0.1337254 -0.7591539 -0.6370266 -0.1337221 -0.7591525 -0.6370288 -0.13372 -0.867234 -0.4796084 -0.1337106 -0.4634085 -0.8759989 -0.1337292 -0.4634724 -0.8759623 -0.3929523 -0.4300529 -0.8127995 -0.3929518 -0.2661741 -0.8801932 -0.6141047 -0.2284477 -0.7554383 -0.6140974 -0.2284244 -0.7554513 -0.1337238 -0.4634757 -0.8759613 -0.1337248 -0.2868617 -0.9485926 -0.3929468 -0.2661776 -0.8801945 -0.3929464 -0.09241515 -0.9149057 -0.6141085 -0.07931613 -0.7852259 -0.6140989 0.07296198 -0.7858492 -0.1337264 -0.2868608 -0.9485927 -0.1337204 -0.2868685 -0.9485912 -0.1337209 -0.09959936 -0.9860014 -0.1337263 -0.09959626 -0.986001 -0.1337311 0.09098571 -0.9868322 -0.6141008 0.07275897 -0.7858666 -0.3929423 0.08477461 -0.9156472 -0.3929466 0.08477699 -0.9156451 -0.1337117 0.09136497 -0.9867997 -0.1337276 0.09137386 -0.9867967 -0.133727 0.2789286 -0.9509553 -0.1337261 0.2789297 -0.950955 -0.3929486 0.2588173 -0.8823859 -0.3929493 0.4232534 -0.8163623 -0.6141021 0.3632637 -0.7006555 -0.6141012 0.4909146 -0.6179666 -0.1337205 0.6164174 -0.7759822 -0.1337091 0.6164134 -0.7759873 -0.1337095 0.456214 -0.8797673 -0.1336983 0.4561582 -0.879798 -0.1337186 0.4561458 -0.8798013 -0.1337189 0.2789228 -0.9509581 -0.1337192 0.7538104 -0.6433422 -0.1337206 0.7538087 -0.6433439 -0.3929544 0.6994525 -0.5969531 -0.3929547 0.8009625 -0.4517142 -0.5410382 0.7325345 -0.4131233 -0.5405841 0.7742406 -0.3291208 -0.1520005 0.9796598 -0.1310049 -0.1343142 0.9690439 -0.2071554 -0.1337125 0.9405521 -0.3122222 -0.1337061 0.9405518 -0.3122259 -0.133702 0.8631924 -0.4868497 -0.1337152 0.863208 -0.4868184 -0.1337167 0.8632073 -0.4868193 -0.1337178 0.7538074 -0.6433459 -0.5933439 0.7538173 -0.2823163 -0.6031818 0.7526232 -0.2640647 -0.3033336 0.94669 -0.1084745 -0.3029971 0.9468261 -0.108227 -0.3050419 0.9460501 -0.1092646 -0.3032215 0.9467553 -0.1082183 -0.3042796 0.9463745 -0.108578 -0.3207777 0.9440109 -0.07710486 0.7284998 -0.4748286 0.4937871 0.6112378 -0.7153536 0.3386114 0.6146957 -0.7020986 0.3594536 0.7346507 -0.6341809 0.2410455 0.7346444 -0.6341842 0.2410556 0.7346405 -0.6341776 0.2410855 0.7345 -0.6297054 0.2529445 0.8659319 -0.4754626 0.1552326 0.8430508 -0.5346322 0.05859738 0.8659282 -0.475469 0.1552339 0.8659107 -0.4754848 0.1552834 0.9498618 -0.3121334 0.01831209 0.9500017 -0.3117359 0.01781326 0.9664012 -0.2326468 0.1092885 0.9663961 -0.2326538 0.1093199 0.9664031 -0.2326427 0.1092818 0.9578995 -0.2087569 0.197102 0.957859 -0.2088658 0.1971838 0.9654433 -0.1872535 0.1812608 0.9085703 -0.3799571 0.1735875 0.9249603 -0.3637888 0.1100274 0.9416279 -0.3296477 0.06833297 0.9465557 -0.3209391 0.03210258 0.9489839 -0.3145481 0.02211666 0.8851612 -0.08206868 0.4579896 0.8851866 -0.08191865 0.4579673 0.8645011 -0.2163231 0.4536982 0.8953307 -0.1672289 0.4128165 0.9151909 -0.1052849 0.3890252 0.9407643 -0.1201431 0.3170621 0.9407474 -0.1201562 0.3171072 0.7473078 -0.0153858 0.6642999 0.7473013 -0.01542025 0.6643064 0.624931 0.4581556 0.6321034 0.7704848 -0.1934107 0.607409 0.7918575 -0.1205738 0.598685 0.7812721 -0.1905838 0.5943834 0.7549583 -0.2571796 0.6032385 0.728499 -0.4748458 0.4937717 0.7286248 -0.4745562 0.4938648 0.9549351 -0.09531921 0.2810928 0.9117013 -0.3038831 0.2765066 0.8655807 -0.3310078 0.3757711 0.8539572 -0.4283143 0.2954726 0.7217745 -0.4841324 0.4946286 0.6003276 -0.7190195 0.3501683 0.3693259 0.8094465 -0.4565026 0.3693194 0.4277378 -0.8250112 0.1210476 0.8646251 -0.4876176 0.1210538 0.4568948 -0.8812451 0.121064 0.09113782 -0.988452 0.1210595 -0.0997616 -0.9876195 0.1210324 -0.7603918 -0.6380873 0.1210435 -0.8686699 -0.4803759 0.09631556 0.9736098 -0.2068997 0.6039363 0.6062551 -0.5174127 0.6053639 0.6715683 -0.4272361 0.721893 -0.585413 -0.3690016 0.6049466 -0.6837819 -0.4080221 0.6441331 -0.6813452 -0.3476512 0.6310033 -0.6863235 -0.3616558 0.5212169 -0.7899982 -0.3228557 0.3979966 -0.8775102 -0.2675344 0.2575173 -0.9195739 -0.2967637 0.2575983 -0.9449039 -0.2019896 0.2672523 -0.9448319 -0.189391 0.02128863 -0.9787909 -0.2037528 0.2743154 0.9420876 -0.1929299 0.2727341 0.9425281 -0.1930202 0.2154017 0.9567201 -0.1956755 0.6582311 0.6748944 -0.3335403 0.6479936 0.6767092 -0.349527 0.607403 0.6919396 -0.3902324 0.5278607 0.7849327 -0.3244131 0.5278613 0.7849235 -0.3244341 0.5278677 0.7849265 -0.3244165 0.5264654 0.785588 -0.3250935 0.370698 0.8589985 -0.3531353 0.4041215 0.8738445 -0.2703358 0.3706533 0.881472 -0.2926149 0.2606129 0.9437617 -0.2034573 0.2606128 0.9437621 -0.2034554 0.121046 -0.9446724 -0.3048635 0.1210544 -0.9446728 -0.3048592 0.1215911 -0.9732215 -0.1950784 0.1575979 -0.9829642 -0.09457516 0.1521887 -0.9796561 -0.130815 0.1210532 -0.6239033 -0.7720692 0.1210549 -0.4642425 -0.8773966 0.1210558 -0.09975981 -0.9876201 0.1210555 -0.2873389 -0.9501484 0.1210641 -0.2873288 -0.9501503 0.1210678 -0.2873317 -0.950149 0.1210663 -0.4642359 -0.8773984 0.1210454 0.2793874 -0.9525181 0.1210453 0.09152394 -0.9884187 0.1210504 0.6174315 -0.7772548 0.1210553 0.6174293 -0.7772559 0.1210471 0.7550472 -0.6444001 0.1210553 0.7550436 -0.6444025 0.1210502 0.7550491 -0.6443973 0.1044669 0.9829611 -0.1512421 0.1215109 0.9758954 -0.1812828 0.1210514 0.9420938 -0.312739 0.1210516 0.9420938 -0.3127391 0.1210368 -0.8686642 -0.480388 0.1210368 -0.8686642 -0.480388 0.3693279 -0.8132277 -0.4497306 0.3694004 -0.8836545 -0.2875724 0.5212398 -0.7899851 -0.3228507 0.5222181 -0.7895633 -0.3223015 0.522179 -0.7463158 -0.412725 0.3693313 -0.8132274 -0.4497282 0.3693345 -0.7118726 -0.5973519 0.1210553 -0.7604004 -0.6380727 0.1210525 -0.7604036 -0.6380695 0.3693267 -0.09340238 -0.9245938 0.3693146 -0.09339582 -0.9245993 0.369315 -0.2689933 -0.8895218 0.3693169 -0.2689942 -0.8895207 0.3693174 -0.4346098 -0.8214128 0.3693338 -0.4346153 -0.8214026 0.3693318 -0.5840867 -0.7227978 0.369324 0.2615509 -0.8917348 0.1210539 0.2793793 -0.9525194 0.121052 0.2793803 -0.9525192 0.3693198 0.5780313 -0.7276557 0.3693252 0.5780276 -0.727656 0.3693246 0.7068634 -0.6032773 0.6039348 -0.6105544 -0.5123341 0.6039364 -0.610549 -0.5123384 0.3693191 -0.7118717 -0.5973628 0.3693182 -0.5840839 -0.7228072 0.1210348 -0.6238975 -0.7720767 0.1210319 -0.4641706 -0.8774377 0.603946 -0.6105483 -0.512328 0.6039475 -0.5009424 -0.6199228 0.603942 -0.5009521 -0.6199201 0.6039309 -0.500948 -0.6199343 0.6039294 -0.3727529 -0.7045031 0.6039321 -0.3727535 -0.7045004 0.6039398 -0.3727624 -0.7044892 0.6039405 -0.2307083 -0.7629086 0.6039443 -0.2307046 -0.7629066 0.6039377 -0.2306807 -0.7629192 0.6039364 -0.08010846 -0.7929965 0.6039363 -0.08010834 -0.7929966 0.6039268 0.07368868 -0.7936261 0.1210431 0.09152287 -0.988419 0.3693267 0.08568215 -0.9253412 0.369324 0.08568388 -0.9253422 0.6039293 0.07348889 -0.7936427 0.603954 0.073471 -0.7936256 0.6039537 0.2243307 -0.7647978 0.6039531 0.2243286 -0.764799 0.3693072 0.2615622 -0.8917384 0.3693082 0.4277458 -0.8250122 0.1210439 0.4569002 -0.8812437 0.1210568 0.4569589 -0.8812116 0.6039469 0.2243349 -0.764802 0.6039454 0.3668681 -0.7075717 0.6039347 0.3668574 -0.7075864 0.6039331 0.3668596 -0.7075865 0.6039339 0.4957578 -0.6240897 0.6039276 0.495764 -0.624091 0.6039313 0.4957565 -0.6240934 0.6039329 0.6062555 -0.517416 0.6039362 0.6062552 -0.5174125 0.3693245 0.7068635 -0.6032773 0.3693236 0.809448 -0.4565019 0.1210508 0.8646237 -0.4876192 0.1210524 0.8646255 -0.4876157 0.5933067 -0.7538251 -0.2823734 0.6028723 -0.7526701 -0.2646371 0.304256 -0.9462995 -0.109296 0.3022759 -0.9470646 -0.1081564 0.3042496 -0.9463924 -0.1085056 0.3207495 -0.9440268 -0.0770266 0.3048671 0.9460659 -0.1096147 0.3024604 0.9470414 -0.1078438 0.304321 0.9463846 -0.1083741 0.3207669 0.9440234 -0.0769968 0.3042702 0.9462977 -0.1092712 0.6029006 0.7526646 -0.2645882 0.5933304 0.7538211 -0.2823346 -0.4587296 -0.7710226 0.4416915 -0.8091901 -0.1732118 -0.5614348 -0.4409939 -0.8126819 -0.3808839 -0.5501499 -0.6599795 -0.5116271 -0.5501523 -0.6599758 -0.5116292 -0.6762496 -0.4133609 -0.6097697 -0.7450516 -0.1337598 -0.6534575 -0.7450546 -0.1337873 -0.6534482 -0.7553363 -0.1737232 -0.6318919 -0.7663404 -0.1268023 -0.6297965 -0.6762453 -0.4133737 -0.6097658 -0.8091892 -0.1732101 -0.5614367 -0.8091896 -0.1732248 -0.5614316 -0.8872158 -0.1732214 -0.4276006 -0.8872155 -0.1732083 -0.4276067 -0.8872082 -0.1732205 -0.4276172 -0.9432892 -0.173217 -0.2831985 -0.9432914 -0.1732083 -0.2831964 -0.9688501 -0.1732075 0.176999 -0.9846189 -0.17321 0.0228905 -0.9846189 -0.17321 0.0228905 -0.9846187 -0.1732111 0.02289104 -0.9760287 -0.1732068 -0.1317849 -0.976028 -0.173212 -0.1317832 -0.9760279 -0.173209 -0.1317884 -0.9291122 -0.1732047 0.3267269 -0.9291098 -0.1732069 0.3267328 -0.96885 -0.1732082 0.1769988 -0.7094067 -0.1736333 0.6830765 -0.7822217 -0.1732126 0.5984368 -0.7822218 -0.173214 0.5984364 -0.8663852 -0.1732131 0.4683737 -0.8663849 -0.1732113 0.4683751 -0.8663877 -0.173204 0.4683723 -0.9291122 -0.1732058 0.3267266 -0.7094171 -0.1736135 0.6830708 -0.7094214 -0.1736305 0.6830621 -0.7094233 -0.1736232 0.6830619 -0.6179094 -0.5140274 0.5949486 -0.4587467 -0.7710021 0.4417092 -0.4587438 -0.7710043 0.4417088 -0.5065428 -0.7702211 0.3875227 -0.5065444 -0.77022 0.3875229 -0.5065497 -0.7702065 0.3875427 -0.5610538 -0.770209 0.3033096 -0.6016663 -0.7702151 0.2115807 -0.6016709 -0.770213 0.2115753 -0.5610514 -0.7702117 0.3033071 -0.6273985 -0.7702164 0.11462 -0.6274011 -0.7702144 0.1146193 -0.6016691 -0.7702123 0.211583 -0.6320431 -0.7702195 -0.0853433 -0.6365032 -0.7710719 -0.01766121 -0.6714205 -0.7409122 0.01560938 -0.6362725 -0.770781 0.03246551 -0.6273977 -0.7702172 0.1146188 -0.6320404 -0.7702224 -0.08533793 -0.6320416 -0.7702213 -0.08533859 -0.6108433 -0.7702198 -0.1833902 -0.610843 -0.7702201 -0.18339 -0.6108427 -0.7702202 -0.1833902 -0.5745329 -0.7702191 -0.2769017 -0.574531 -0.7702205 -0.2769014 -0.4751489 -0.8097237 -0.3443561 -0.4932493 -0.7711985 -0.40244 -0.5239967 -0.7702274 -0.3635616 -0.5240031 -0.770219 -0.3635703 -0.5240027 -0.7702201 -0.3635684 -0.6762466 -0.413594 -0.609615 -0.6749381 -0.5141779 -0.5292255 -0.7052202 -0.5130832 -0.4892956 -0.7052221 -0.5130761 -0.4893003 -0.7732211 -0.5130786 -0.3726654 -0.7732176 -0.5130882 -0.3726596 -0.8220863 -0.5130876 -0.2468104 -0.8220863 -0.5130876 -0.2468104 -0.8506181 -0.5130867 -0.1148517 -0.8506169 -0.513089 -0.1148507 -0.8581055 -0.5130858 0.01994931 -0.8581051 -0.5130862 0.01994949 -0.8443627 -0.5130853 0.1542564 -0.844361 -0.513088 0.1542571 -0.8097282 -0.5130892 0.2847449 -0.8097242 -0.5130951 0.2847459 -0.7550567 -0.5130987 0.4081901 -0.7550586 -0.513096 0.40819 -0.6817088 -0.5130985 0.5215392 -0.6817231 -0.5130783 0.5215403 -0.6179102 -0.5140227 0.5949518 -0.6179013 -0.5140342 0.5949512 0.009780406 -0.9987335 -0.04935306 -0.2660544 -0.9287039 -0.2583099 0.302291 -0.9045158 -0.3007844 0.3026015 -0.9042978 -0.3011276 0.1398519 -0.9816151 -0.1298967 0.1398515 -0.9816154 -0.1298958 0.1398425 -0.9816179 -0.1298858 0.446803 -0.7710796 -0.4536553 0.4468008 -0.771084 -0.4536502 0.446792 -0.7710949 -0.4536404 0.5568228 -0.5858197 -0.5888664 0.5568014 -0.5858638 -0.5888428 0.6663696 -0.1323409 -0.7337829 0.6599165 -0.1193582 -0.7417978 0.6599146 -0.1193318 -0.7418037 0.6333788 -0.3613005 -0.6843195 0.6333564 -0.3613868 -0.6842948 0.5803447 -0.1320243 -0.8035979 0.5803319 -0.1320271 -0.8036067 0.5803338 -0.1320356 -0.803604 0.4490907 -0.1320357 -0.8836764 0.4490832 -0.132048 -0.8836785 0.4490732 -0.1320323 -0.8836859 0.3070318 -0.132032 -0.9424961 0.3070356 -0.1320453 -0.942493 0.1574553 -0.1320443 -0.9786583 0.1575887 -0.1320297 -0.9786388 0.1575934 -0.1320435 -0.9786363 0.00437349 -0.1320436 -0.9912342 0.004373133 -0.1320441 -0.9912342 0.004361569 -0.1320284 -0.9912364 -0.1489701 -0.1320285 -0.979988 -0.1489662 -0.1320393 -0.9799871 -0.2992748 -0.1320333 -0.9449877 -0.298721 -0.132013 -0.9451658 -0.2987107 -0.1320402 -0.9451652 -0.4412922 -0.13204 -0.887596 -0.4412844 -0.132026 -0.8876019 -0.4412798 -0.1320328 -0.8876032 -0.6649703 -0.1989025 -0.7198975 -0.5732378 -0.1320329 -0.8086814 -0.573235 -0.1320188 -0.8086858 -0.5730879 -0.1320222 -0.8087894 -0.6442004 -0.1324054 -0.7533093 -0.6652735 -0.03726243 -0.7456693 -0.5755862 -0.4411966 -0.68851 -0.5755577 -0.4412406 -0.6885057 -0.6649921 -0.1988397 -0.7198946 -0.6649719 -0.1989896 -0.7198718 -0.4923106 -0.6501493 -0.5787367 -0.3979902 -0.8113365 -0.4281786 -0.397959 -0.8113589 -0.4281651 -0.3979576 -0.8113604 -0.4281637 -0.1054733 -0.9917045 -0.07346826 -0.2659416 -0.9287705 -0.2581869 -0.08127307 -0.9918795 -0.09782481 -0.05543351 -0.9983139 -0.01722055 -0.03113752 -0.9988122 -0.03747773 -0.03426659 -0.9982429 -0.04834067 -0.02649199 -0.9987796 -0.0416826 -0.009293496 -0.9987269 -0.04957973 -0.01673501 -0.998457 -0.05294978 -0.01650011 -0.9985569 -0.05110728 -0.02193158 -0.9986681 -0.04670161 -0.0230025 -0.9986642 -0.04626774 -0.02529287 -0.9982284 -0.05385297 -0.02649199 -0.9987795 -0.0416826 -0.009289801 -0.9987269 -0.04958063 -0.008776366 -0.9982931 -0.05773866 -0.002846658 -0.9988021 -0.04884868 -0.002845346 -0.9988022 -0.0488488 2.61606e-4 -0.9982311 -0.05945354 0.003351986 -0.998804 -0.04877781 0.008015453 -0.9987282 -0.04977637 0.01237154 -0.9979736 -0.06241434 0.003351688 -0.998804 -0.04877787 0.01781171 -0.9984216 -0.05326342 0.01660019 -0.9985628 -0.05095815 0.02250385 -0.9986584 -0.04663562 0.02250099 -0.9986584 -0.04663676 0.02591854 -0.9983623 -0.05100017 0.02697139 -0.9987753 -0.04147702 0.02697181 -0.9987754 -0.04147678 0.03465598 -0.9982464 -0.04798984 0.03154993 -0.9988079 -0.03724646 0.02838641 -0.9987993 -0.03992694 0.02093786 -0.9994752 -0.02471733 0.3022848 -0.9045167 -0.3007882 0.1438996 -0.9684973 -0.2032384 0.1456865 -0.9685436 -0.2017394 0.1456866 -0.9685435 -0.2017394 0.1127398 -0.9685436 -0.2218403 0.1127407 -0.9685433 -0.221841 0.07707661 -0.9685432 -0.2366074 0.07707828 -0.9685428 -0.2366093 0.03956329 -0.9685427 -0.2456824 0.03956192 -0.9685432 -0.2456803 0.001097321 -0.9685432 -0.2488428 0.001094877 -0.9685446 -0.2488375 -0.03739649 -0.9685447 -0.2460139 -0.03739517 -0.9685435 -0.2460185 -0.0749939 -0.9685435 -0.237275 -0.07499337 -0.9685424 -0.2372794 -0.1107833 -0.9685425 -0.2228285 -0.1107834 -0.9685416 -0.2228322 -0.1439095 -0.9685418 -0.2030194 -0.1439087 -0.9685428 -0.2030151 -0.134965 -0.9682613 -0.2103674 -0.1054682 -0.991706 -0.07345592 0.4467675 -0.7711148 -0.4536308 0.3212174 -0.8522075 -0.4129912 0.3067867 -0.8517092 -0.4248216 0.3067852 -0.8517101 -0.4248209 0.2374089 -0.85171 -0.467148 0.2374039 -0.8517134 -0.4671443 0.1623065 -0.8517135 -0.4982377 0.1623037 -0.8517156 -0.4982349 0.08330488 -0.8517155 -0.5173404 0.08331084 -0.85171 -0.5173485 0.002310991 -0.8517101 -0.5240083 0.002310752 -0.8517104 -0.5240077 -0.078749 -0.8517107 -0.5180615 -0.07874995 -0.8517123 -0.5180585 -0.1579158 -0.8517122 -0.4996487 -0.1579175 -0.8517177 -0.4996389 -0.2332803 -0.8517169 -0.4692105 -0.2332801 -0.8517131 -0.4692176 -0.3030283 -0.851713 -0.4275028 -0.3030269 -0.8517184 -0.4274932 -0.31954 -0.8522615 -0.4141795 -0.2659505 -0.9287661 -0.2581931 0.5568155 -0.5858393 -0.5888538 0.4819979 -0.6529794 -0.5842055 0.4439647 -0.6518818 -0.6147727 0.4439589 -0.6518879 -0.6147704 0.3435553 -0.6518878 -0.6760266 0.3435662 -0.6518755 -0.676033 0.2348892 -0.6518751 -0.7210311 0.2348821 -0.6518841 -0.7210254 0.1205585 -0.6518837 -0.7486743 0.1205548 -0.6518892 -0.7486703 0.003345191 -0.6518892 -0.758307 0.003344357 -0.6518906 -0.7583057 -0.1139671 -0.6518906 -0.7497 -0.1139616 -0.6518773 -0.7497125 -0.2285286 -0.6518777 -0.7230699 -0.2285288 -0.6518784 -0.7230693 -0.33759 -0.651879 -0.6790338 -0.3375917 -0.651894 -0.6790184 -0.4385299 -0.6518931 -0.6186493 -0.4385306 -0.6518775 -0.6186652 -0.4930503 -0.6529686 -0.5749202 -0.4922851 -0.6502311 -0.5786665 0.6333289 -0.3614361 -0.6842941 0.6013427 -0.3994202 -0.6919902 0.5369792 -0.3984345 -0.7435746 0.5369807 -0.3984321 -0.7435749 0.4155367 -0.3984325 -0.8176679 0.4155371 -0.3984317 -0.817668 0.284096 -0.398432 -0.8720902 0.2841002 -0.3984242 -0.8720925 0.1458172 -0.398424 -0.9055361 0.1458179 -0.3984223 -0.9055368 0.004046499 -0.3984223 -0.9171931 0.004046082 -0.3984233 -0.9171927 -0.1378423 -0.3984236 -0.9067845 -0.1378459 -0.3984339 -0.9067794 -0.2764052 -0.3984336 -0.8745576 -0.2764061 -0.3984374 -0.8745554 -0.4083185 -0.3984367 -0.8212941 -0.4083178 -0.3984325 -0.8212965 -0.5304124 -0.3984321 -0.7482744 -0.5304128 -0.3984367 -0.7482717 -0.619111 -0.3990769 -0.6763424 -0.6057882 -0.4422668 -0.6613779 0.7397283 -0.5399567 0.4015581 0.8347029 -0.539963 -0.1082168 0.4965996 -0.7800942 0.3805813 0.5896862 -0.7800929 0.209106 0.6204644 -0.7800981 -0.08044081 0.7563999 -0.0525434 -0.6519957 0.7649444 -0.2610942 -0.5888035 0.6471944 -0.5524634 -0.5252843 0.7227503 -0.2708638 -0.6358183 0.7227628 -0.2708051 -0.635829 0.4773303 -0.7758899 -0.4124932 0.4773025 -0.7759194 -0.4124696 0.4811292 -0.7757018 -0.4084134 0.4747992 -0.7808968 -0.4059137 0.5168599 -0.780102 -0.3525573 0.5168573 -0.780104 -0.3525568 0.5168569 -0.7801048 -0.3525555 0.5655098 -0.7801033 -0.267652 0.5655135 -0.7800996 -0.2676553 0.6003339 -0.7800972 -0.1762039 0.600329 -0.7801008 -0.1762039 0.600332 -0.780099 -0.1762017 0.6150785 -0.7800936 0.1145976 0.6150784 -0.7800935 0.1145976 0.6150779 -0.780094 0.114597 0.625423 -0.7800943 0.01728928 0.6792856 -0.7329902 0.03600674 0.6244102 -0.7809365 -0.01581752 0.4965982 -0.780097 0.380577 0.7071627 -0.1893901 0.6812139 0.449929 -0.780853 0.4333965 0.4499388 -0.7808464 0.4333981 0.6057708 -0.5408955 0.5835013 0.6057523 -0.5409169 0.5835006 0.6057456 -0.5409445 0.583482 0.7071843 -0.1893867 0.6811924 0.7071837 -0.1893854 0.6811934 0.6385633 -0.5534209 -0.5347545 0.6496174 -0.5411031 -0.5340455 0.6953341 -0.5399547 -0.4742988 0.6953368 -0.5399512 -0.474299 0.7607862 -0.5399541 -0.3600749 0.7607771 -0.5399662 -0.3600759 0.8076185 -0.5399653 -0.2370439 0.8413669 -0.5399637 0.02325886 0.841367 -0.5399636 0.02325886 0.8274488 -0.5399645 0.1541652 0.7932917 -0.5399608 0.2813017 0.7397273 -0.5399596 0.4015561 0.5498601 -0.7801018 0.298488 0.5498701 -0.780094 0.29849 0.8875914 -0.1889469 -0.4200958 0.8875903 -0.1889505 -0.4200965 0.8112312 -0.1889543 -0.5533537 0.8112323 -0.1889514 -0.553353 0.8112216 -0.1889387 -0.553373 0.7502448 -0.1894441 -0.6334379 0.7649445 -0.2609844 -0.5888523 0.8875952 -0.1889407 -0.4200908 0.9422412 -0.1889401 -0.2765559 0.8076202 -0.5399631 -0.2370434 0.8347029 -0.5399632 -0.1082168 0.6204628 -0.7800994 -0.08044123 0.6204643 -0.780098 -0.08044368 0.9422405 -0.1889427 -0.2765566 0.9738387 -0.1889402 -0.1262537 0.9738385 -0.1889396 -0.1262553 0.9738387 -0.1889388 -0.126255 0.9816139 -0.1889388 0.02713584 0.9816138 -0.1889391 0.02713578 0.9816139 -0.1889389 0.0271359 0.9653768 -0.1889356 0.1798639 0.8274499 -0.5399626 0.1541661 0.7932912 -0.5399617 0.2813011 0.5896787 -0.7801001 0.2091001 0.5896797 -0.7800997 0.209099 0.9653761 -0.1889412 0.1798619 0.9255093 -0.1889428 0.3282272 0.9255241 -0.1889328 0.3281913 0.9255238 -0.1889372 0.3281896 0.863029 -0.1889365 0.4684912 0.8630289 -0.1889454 0.4684878 0.863029 -0.1889458 0.4684875 0.4966015 -0.7800927 0.3805817 0.6680686 -0.5399547 0.5119894 0.6680644 -0.5399703 0.5119785 0.7794263 -0.1889476 0.5973219 0.7794259 -0.1889392 0.5973251 -0.9905951 0.01495033 0.1360073 -0.9591513 0.278944 0.04710793 -0.6954081 -0.005890488 0.718591 -0.7083938 -0.2030532 0.675979 -0.1210195 -0.9730425 -0.1963226 -0.1520338 -0.9883751 5.41561e-4 -0.5080644 -0.8496155 0.1415064 -0.134577 -0.9888271 0.06411123 -0.2412584 -0.9691817 0.04981333 -0.2249801 -0.9692748 0.09945064 -0.2708919 -0.9589836 0.08347475 -0.2492777 -0.9606538 0.1224946 -0.3537054 -0.9335924 0.05742555 -0.2852182 -0.9455469 0.1568173 -0.4726179 -0.8781635 0.07389885 -0.4287884 -0.8953405 0.1204407 -0.5725823 -0.6874779 0.4466807 -0.511317 -0.8110375 0.2842063 -0.6913031 -0.5812773 0.4292048 -0.6913101 -0.581279 0.4291911 -0.6962472 -0.6489604 0.3067415 -0.5113505 -0.8110045 0.2842399 -0.5113218 -0.8110182 0.2842526 -0.7178943 -0.4565795 0.5255123 -0.7178652 -0.4566074 0.5255278 -0.7915541 -0.254999 0.5553536 -0.763351 -0.2360832 0.6012986 -0.70854 -0.2028574 0.6758846 -0.7577993 -0.1853627 0.6256045 -0.7578732 -0.1855844 0.6254492 -0.6542743 -0.08783763 0.7511389 -0.68987 -0.03419744 0.7231251 -0.6939958 -0.05198657 0.7180997 -0.6939946 -0.05198884 0.7181007 -0.6947057 -0.02120172 0.7189816 -0.6947247 -0.02112418 0.7189655 -0.6969195 -0.02112078 0.7168383 -0.6965792 -0.02205252 0.7171409 -0.6915262 -0.03258228 0.7216162 -0.6949782 -0.009206593 0.7189719 -0.6898153 -0.004837989 0.7239692 -0.6933113 -0.01081764 0.720557 -0.6937484 -0.001743674 0.7202152 -0.691675 -0.008725702 0.7221562 -0.6922603 -0.008740544 0.7215949 -0.7994315 0.03798621 0.5995551 -0.9354212 0.04892343 0.350134 -0.9074385 0.0833891 0.4118275 -0.9277305 0.03874057 0.3712348 -0.8870831 -0.01076352 0.4614844 -0.8870804 -0.0107637 0.4614894 -0.9892859 0.05509907 0.1351944 -0.9574586 0.03870183 0.2859635 -0.9427643 0.04267323 0.3307184 -0.996361 0.01646482 0.08362793 -0.9900164 0.07962429 0.1163079 -0.9666096 0.1933464 0.1681758 -0.9903336 0.127656 0.05425208 -0.9773373 0.1934912 0.08586674 -0.9550862 0.2786007 0.1009555 -0.9671472 0.2364098 0.09346932 -0.97724 0.2098305 0.03119355 -0.9686413 0.2320719 0.08875113 -0.9671453 0.2364166 0.09347271 -0.9585172 0.2809205 0.04825282 -0.9585161 0.2809162 0.048303 -0.9585179 0.2809172 0.04825967 -0.9877876 -0.1226115 0.09613496 -0.987789 -0.1225947 0.09614259 -0.991414 -0.05132079 0.1202684 -0.9055056 -0.4031341 0.1324478 -0.9055059 -0.4031335 0.1324473 -0.9310791 -0.3595007 0.06205517 -0.9298081 -0.3619327 0.06679385 -0.9584729 -0.2519651 0.1335788 -0.9584695 -0.2519773 0.1335813 -0.801878 -0.5927307 0.07524704 -0.8607196 -0.4971869 0.1093934 -0.9055031 -0.4031392 0.13245 -0.7416207 -0.6612607 0.112841 -0.7999034 -0.5930039 0.09220051 -0.7998976 -0.5930111 0.0922048 -0.5080634 -0.849616 0.1415069 -0.5691326 -0.8176617 0.08670288 -0.5911741 -0.8043736 0.05912977 -0.6703596 -0.7320236 0.1214895 -0.7416509 -0.661228 0.1128343 -0.7204931 -0.1199792 0.683004 -0.7800562 -0.237553 0.5788618 -0.8092771 -0.1848886 0.5575723 -0.8066387 -0.1306896 0.5764151 -0.8122231 -0.1157526 0.5717473 -0.8054519 -0.07793581 0.5875145 -0.8089637 -0.06336247 0.5844339 -0.9755048 -0.1858935 0.1176175 -0.9877441 -0.1246472 0.09394001 -0.9183683 -0.06439614 0.3904519 -0.9268144 -0.0460565 0.3726846 -0.8009121 -0.01533043 0.5985857 -0.8012163 0.03164023 0.5975378 -0.7933683 0.00992459 0.6086611 -0.7405183 -0.4532756 0.4961591 -0.7229563 -0.5846613 0.3681104 -0.820198 -0.4840023 0.304987 -0.8464751 -0.3802823 0.3726464 -0.8900503 -0.3026972 0.3408589 -0.9028403 -0.1981794 0.3815813 -0.906427 -0.194999 0.3746537 -0.9250438 -0.1221674 0.3596791 -0.8022077 -0.041664 0.5955895 -0.8045317 -0.02297902 0.5934652 -0.6909846 -0.00239408 0.7228655 -0.6918128 -0.001679658 0.722075 -0.9209354 0.3894854 0.01338368 -0.6873158 0.7047405 0.1758913 -0.484995 0.8230293 0.2956393 -0.4874394 0.8259227 0.2832922 -0.4003975 0.8478406 0.347632 -0.3990488 0.8487959 0.3468509 -0.5949103 0.7727022 0.2213891 -0.4716597 0.8102572 0.34788 -0.5013101 0.8089069 0.3071776 -0.5949157 0.7726991 0.2213854 -0.4324408 0.8551527 0.2858474 -0.4724783 0.8366681 0.2770394 -0.4874488 0.8259098 0.2833136 -0.3867724 0.8582129 0.3374578 -0.4213889 0.8475608 0.3226019 -0.3439878 0.9065909 0.2444695 -0.3995496 0.8654951 0.3021231 -0.4072255 0.8600459 0.3073899 -0.4120047 0.8557245 0.3130301 -0.4099123 0.8601433 0.3035219 -0.4329195 0.8508867 0.2976115 -0.4329279 0.8508784 0.2976229 -0.5316071 0.8330994 0.1527725 -0.5315935 0.8330942 0.1528482 -0.5144016 0.8296073 0.2171238 -0.5144338 0.8295958 0.2170913 -0.4603327 0.8465016 0.2674487 -0.4446156 0.8510621 0.2793034 -0.6841195 0.7252038 0.07784622 -0.684327 0.7254157 0.07394999 -0.6320637 0.7554327 0.1726762 -0.5114618 0.8478049 0.1401204 -0.5316082 0.8330983 0.1527741 -0.6841182 0.7252053 0.07784354 -0.7566365 0.6395185 0.1360785 -0.7885184 0.6137708 0.03903943 -0.7801604 0.5880157 0.2135117 -0.7888593 0.5919524 0.1652068 -0.8183625 0.573299 0.04014039 -0.8083796 0.563131 0.1714814 -0.8372249 0.5457375 0.03500401 -0.8374962 0.5446874 0.0437687 -0.8560084 0.5048373 0.1113051 -0.8385038 0.5431911 0.04306584 -0.8606514 0.4966828 0.1121848 -0.8819627 0.4708367 0.02132296 -0.8906405 0.4493464 0.06962138 -0.893938 0.4457757 0.04646348 -0.9021763 0.4310433 0.01672077 -0.9221588 0.3837912 0.04824519 -0.9188387 0.39343 0.03079247 -0.5545253 -0.8202567 -0.1402884 -0.401868 -0.9081937 -0.1169887 -0.5545175 -0.8202604 -0.1402966 -0.55453 -0.8202525 -0.1402937 -0.4542703 -0.8810838 -0.1316435 -0.4411611 -0.8915528 -0.1025202 -0.4411645 -0.8915517 -0.1025155 -0.679872 -0.7114354 -0.1778588 -0.5498738 -0.8349201 -0.02339076 -0.6018071 -0.7725968 -0.2022927 -0.640859 -0.7477566 -0.173666 -0.6697893 -0.7325792 -0.1212847 -0.6720213 -0.7301265 -0.1237042 -0.6941516 -0.6093598 -0.3831897 -0.6948502 -0.6281287 -0.3501964 -0.7006115 -0.5995749 -0.3868506 -0.7041242 -0.6202923 -0.3456103 -0.6941555 -0.6093571 -0.3831869 -0.6936111 -0.6182359 -0.3697135 -0.6807503 -0.636686 -0.3622292 -0.6674262 -0.6536122 -0.3568379 -0.6673088 -0.6545723 -0.3552943 -0.6673266 -0.654564 -0.3552759 -0.3124607 -0.9452306 -0.0943796 -0.3123294 -0.9452818 -0.09430146 -0.5988321 -0.7529978 -0.2727532 -0.6313003 -0.707577 -0.317482 -0.6308522 -0.7051426 -0.3237273 -0.6410922 -0.7021545 -0.3098062 -0.668031 -0.6490395 -0.3639813 -0.6680471 -0.6489707 -0.3640742 -0.9890337 0.003476202 0.1476488 -0.8690648 -0.004097342 0.4946812 -0.8887759 6.64563e-4 0.4583415 -0.8687974 6.78571e-4 0.4951673 -0.3667829 -6.14596e-4 0.9303064 -0.6331808 0.004514336 0.7739907 -0.6708683 -0.003354728 0.7415689 -0.8886343 0.004369318 0.4585957 0.3094102 0.005856454 0.9509106 0.3661076 -0.005922019 0.9305537 0.01393359 0.004305183 0.9998936 -0.03015667 0.001249969 0.9995445 -5.86069e-6 0.001256883 0.9999992 -0.03025865 0.001246869 0.9995414 0.01401609 -0.003180027 0.9998968 -0.3667145 0.00340712 0.9303273 -0.3258244 -0.004721939 0.9454185 -0.6337586 -3.91632e-4 0.7735308 0.3091525 0.005864858 0.9509944 0.6242097 3.43646e-4 0.7812568 0.3653895 5.81576e-4 0.9308546 0.6243273 -0.004792034 0.7811481 0.661876 0.002693355 0.7496086 0.8596747 -0.002889752 0.5108337 0.8678518 -0.001583456 0.4968206 0.8596333 -0.001585483 0.5109093 0.8677975 -2.12901e-4 0.496918 0.9840876 1.18741e-4 0.1776838 0.9839709 0 0.1783289 0.9857495 0 -0.1682196 0.9890317 0.003553986 -0.1476605 0.8687298 -0.004185974 -0.4952688 0.8887763 6.5362e-4 -0.4583409 0.8684722 6.68087e-4 -0.4957374 0.8886638 0.004434466 -0.4585379 0.6708703 -0.003386795 -0.7415671 0.6328591 0.004535555 -0.7742536 0.3667815 -5.88616e-4 -0.9303069 0.6329348 -3.64554e-4 -0.774205 0.3669806 -0.004228115 -0.930219 0.3257459 -0.003441214 -0.9454511 0.3667461 0.003366351 -0.9303151 -0.01397955 -0.003135442 -0.9998974 0.03015667 0.001277506 -0.9995443 4.05679e-6 0.001287519 -0.9999992 0.03015649 0.001280605 -0.9995444 -0.01390838 0.004334032 -0.9998939 -0.3098598 -0.004271268 -0.9507727 -0.3655148 0.00499165 -0.9307922 -0.6237917 3.64274e-4 -0.7815906 -0.3658175 6.02679e-4 -0.9306864 -0.6243277 -0.004799127 -0.7811478 -0.6619443 0.002693891 -0.7495482 -0.8596748 -0.0028916 -0.5108336 -0.8678886 -0.001579582 -0.4967563 -0.8596331 -0.00158149 -0.5109094 -0.8677856 -2.11019e-4 -0.4969387 -0.9840876 1.20902e-4 -0.177684 -0.9839689 0 -0.1783407 -0.9858199 0 0.1678068 0.8808079 0.2967786 0.3689173 0.5216022 0.7693058 0.3689172 -0.05032032 0.9280992 0.3689171 -0.6017212 0.7084009 0.3689171 -0.9294623 0 0.3689171 -0.7399384 -0.5624867 0.3689171 -0.2486573 -0.8955835 0.3689168 0.5216021 -0.7693057 0.3689174 0.5570707 0.8216184 0.1208947 -0.9694573 0.213394 0.1208948 -0.7902541 -0.6007353 0.120895 -0.2655662 -0.9564827 0.1208945 0.5570711 -0.8216181 0.1208947 0.9868463 -0.1073259 0.1208947 0.9407024 -0.3169596 0.1208947 0.9407026 -0.3169594 0.1208942 0.8505743 -0.5117696 0.1208943 0.8505725 -0.5117725 0.1208947 0.8505724 -0.5117725 0.1208946 0.7206705 -0.6826555 0.1208948 0.7206706 -0.6826555 0.1208947 0.7206706 -0.6826554 0.1208946 0.3674232 -0.9221631 0.1208949 0.3674231 -0.9221631 0.1208949 0.1605969 -0.9795882 0.1208948 0.1605955 -0.9795883 0.1208954 -0.07993823 -0.9817072 0.1728026 0.02687877 -0.9922209 0.121553 0.1605951 -0.9795885 0.1208946 -0.4649727 -0.8770317 0.1208949 -0.4649728 -0.8770318 0.120895 -0.6426379 -0.7565718 0.120895 -0.6426379 -0.7565719 0.1208949 -0.6426378 -0.7565719 0.1208949 -0.9009186 -0.4168095 0.1208946 -0.9009186 -0.4168093 0.1208948 -0.9694577 -0.213392 0.1208948 -0.9694574 -0.2133938 0.1208944 -0.9694573 -0.213394 0.1208948 -0.9926654 0 0.1208948 -0.9694577 0.2133919 0.1208948 -0.9009186 0.4168095 0.1208948 -0.6426379 0.7565719 0.120895 -0.7902541 0.6007353 0.120895 -0.4649728 0.8770319 0.120895 -0.4649727 0.8770317 0.1208949 -0.2655649 0.956483 0.1208949 -0.2655664 0.9564826 0.1208949 -0.05374139 0.9912095 0.120895 -0.05374217 0.9912096 0.1208944 -0.2655662 0.9564827 0.1208945 0.1605955 0.9795883 0.1208954 0.3674231 0.922163 0.1208948 0.3674231 0.922163 0.1208949 0.1605969 0.9795882 0.1208948 0.7206706 0.6826555 0.1208948 0.7206705 0.6826555 0.1208947 0.9407024 0.3169597 0.1208942 0.8505743 0.5117695 0.1208943 0.8505724 0.5117724 0.1208947 0.8505724 0.5117725 0.1208946 0.7206706 0.6826554 0.1208946 0.9868463 0.1073263 0.1208944 0.8808079 -0.2967786 0.3689173 0.8808079 -0.2967786 0.3689174 0.7964164 -0.4791878 0.3689173 0.7964164 -0.4791878 0.3689173 0.6747853 -0.6391907 0.3689173 0.3440293 -0.8634489 0.3689174 0.3440294 -0.8634489 0.3689172 0.1503704 -0.917218 0.3689173 -0.435368 -0.8211912 0.3689169 -0.4353681 -0.8211912 0.3689171 -0.6017212 -0.708401 0.3689171 -0.8435572 -0.3902711 0.3689171 -0.8435572 -0.390271 0.3689173 -0.9077319 -0.1998069 0.3689173 -0.9694574 0.2133938 0.1208944 -0.907732 0.199807 0.3689171 -0.9077319 0.1998071 0.3689173 -0.7399385 0.5624867 0.3689171 -0.7902539 0.6007356 0.1208947 -0.790254 0.6007353 0.1208946 -0.435368 0.8211912 0.3689171 -0.4353681 0.8211912 0.3689169 -0.2486578 0.8955833 0.3689169 0.1503705 0.9172181 0.3689172 0.1503705 0.917218 0.3689172 0.3440293 0.8634489 0.3689172 0.6747853 0.6391907 0.3689172 0.6747853 0.6391906 0.3689174 0.7964164 0.4791878 0.3689173 0.9868463 0.1073259 0.1208952 0.9240138 0.1004924 0.3689173 0.9240139 0.1004928 0.3689166 0.792724 -0.08621418 0.6034532 0.9240137 -0.1004928 0.3689173 0.924014 -0.1004924 0.3689166 0.9868463 -0.1073259 0.1208947 0.9868462 -0.1073262 0.1208952 0.6832566 -0.4111019 0.6034532 0.6832566 -0.4111018 0.6034532 0.7556576 -0.2546098 0.603453 0.7556571 -0.2546104 0.6034532 0.7556572 -0.2546105 0.6034532 0.792724 -0.08621406 0.6034532 0.5789076 -0.5483706 0.6034532 0.5789076 -0.5483705 0.6034532 0.6747854 -0.6391907 0.3689172 0.5216023 -0.7693057 0.3689172 0.557071 -0.8216181 0.1208949 0.5570707 -0.8216184 0.1208948 0.2951476 -0.7407647 0.6034529 0.2951475 -0.7407647 0.603453 0.4474926 -0.6599962 0.603453 0.4474896 -0.659998 0.6034532 0.4474896 -0.6599979 0.6034533 0.5789075 -0.5483705 0.6034533 0.1290047 -0.7868941 0.6034529 0.129005 -0.7868939 0.6034531 0.1503705 -0.917218 0.3689171 -0.05031991 -0.9280992 0.3689172 -0.05358839 -0.9883823 0.1422275 -0.08055996 -0.9893534 0.1212016 0.1290044 -0.7868937 0.6034534 -0.04317045 -0.7962287 0.6034534 -0.05032032 -0.9280989 0.3689177 -0.2486577 -0.895583 0.3689177 -0.2655664 -0.9564826 0.1208949 -0.2655649 -0.956483 0.1208949 -0.04317027 -0.796229 0.6034532 -0.2133262 -0.7683334 0.6034532 -0.2133265 -0.7683334 0.6034532 -0.2133266 -0.7683331 0.6034535 -0.3735081 -0.7045109 0.6034535 -0.373508 -0.7045114 0.6034531 -0.3735082 -0.704511 0.6034533 -0.5162249 -0.6077467 0.6034533 -0.6017212 -0.7084008 0.3689172 -0.7399385 -0.5624867 0.3689172 -0.7902539 -0.6007356 0.1208947 -0.7902541 -0.6007354 0.1208946 -0.5162249 -0.6077467 0.6034533 -0.6348026 -0.4825658 0.6034533 -0.6348033 -0.4825651 0.6034532 -0.6348033 -0.482565 0.6034532 -0.7236992 -0.3348188 0.6034532 -0.7236991 -0.3348186 0.6034535 -0.7236991 -0.3348193 0.6034531 -0.7787557 -0.1714172 0.6034531 -0.907732 -0.1998071 0.3689171 -0.9294623 0 0.3689171 -0.9926654 0 0.1208948 -0.9926654 0 0.1208948 -0.7787556 -0.1714169 0.6034535 -0.7973983 0 0.6034535 -0.7973982 0 0.6034535 -0.7973983 0 0.6034535 -0.7787555 0.1714172 0.6034534 -0.7787557 0.1714171 0.6034532 -0.7787558 0.1714169 0.6034532 -0.9009187 0.4168094 0.1208945 -0.8435571 0.3902711 0.3689174 -0.8435572 0.390271 0.3689171 -0.7236993 0.3348188 0.6034531 -0.7236992 0.3348189 0.6034532 -0.6348029 0.4825657 0.6034532 -0.6348031 0.4825649 0.6034533 -0.7399384 0.5624867 0.3689172 -0.6017212 0.7084009 0.3689172 -0.6426379 0.7565718 0.1208949 -0.6426379 0.7565719 0.1208949 -0.373508 0.704511 0.6034534 -0.3735081 0.704511 0.6034533 -0.516225 0.6077466 0.6034532 -0.5162248 0.6077467 0.6034533 -0.5162248 0.6077468 0.6034532 -0.6348033 0.4825649 0.6034532 -0.2133266 0.7683331 0.6034535 -0.2133265 0.7683333 0.6034533 -0.2486572 0.8955832 0.3689177 -0.05031991 0.9280989 0.3689177 -0.05374169 0.9912095 0.1208946 0.1605951 0.9795885 0.1208946 0.1290046 0.7868942 0.6034529 0.1290049 0.7868937 0.6034534 -0.04317009 0.7962287 0.6034535 -0.04317045 0.7962288 0.6034533 -0.04317039 0.796229 0.6034533 -0.2133266 0.7683333 0.6034531 0.2951477 0.7407646 0.6034529 0.2951475 0.7407647 0.603453 0.3440294 0.8634488 0.3689174 0.5216022 0.7693056 0.3689174 0.557071 0.8216181 0.1208949 0.5570711 0.8216181 0.1208948 0.5789076 0.5483705 0.6034532 0.5789076 0.5483704 0.6034532 0.4474903 0.6599974 0.6034533 0.4474897 0.6599981 0.6034531 0.4474897 0.659998 0.603453 0.2951476 0.7407647 0.603453 0.6832566 0.4111018 0.6034532 0.6832566 0.4111018 0.6034532 0.7964164 0.4791878 0.3689174 0.8808079 0.2967786 0.3689174 0.9407026 0.3169594 0.1208947 0.9868463 0.1073259 0.1208947 0.6832566 0.4111019 0.6034531 0.7556571 0.2546106 0.6034532 0.7556574 0.2546105 0.603453 0.7556576 0.2546091 0.6034533 0.792724 0.08621418 0.6034532 0.7927239 0.08621394 0.6034535 0.7927238 -0.0862137 0.6034535 -0.511054 0.005315542 -0.8595322 -0.6243627 -0.008350551 -0.7810899 -0.7809999 0.007860958 -0.6244817 -0.8490943 -0.003407061 -0.5282303 -0.7806403 -0.003351271 -0.6249716 -0.8489729 -0.005099594 -0.5284118 -0.9507001 0.006171584 -0.3100501 -0.9745336 -0.005855023 -0.2241651 -0.9977487 0.0010553 -0.0670557 0.309431 -0.005810678 -0.9509043 0.3665926 0.00605756 -0.9303618 0.0152778 -0.004379928 -0.9998736 0.06644421 -0.007924079 -0.9977587 -3.37128e-5 -0.007941067 -0.9999684 -0.177214 -0.007793843 -0.9841415 0.01531547 0.0272836 -0.9995104 -0.5087288 -0.02731204 -0.8604936 -0.3207524 0.01110398 -0.947098 -0.6258125 0.005208015 -0.7799561 0.3095926 -0.005805432 -0.9508516 0.6242763 -3.28257e-4 -0.7812036 0.365592 -5.62827e-4 -0.930775 0.6248373 0.004730224 -0.7807407 0.6606323 -0.002436935 -0.7507057 0.8596652 0.002595484 -0.5108512 0.8660918 0.001553714 -0.4998826 0.8596138 0.001554906 -0.5109421 0.8660293 4.8266e-4 -0.4999927 0.9840926 -5.17902e-4 -0.1776561 -0.9996948 0 -0.02470266 -0.9835846 0 0.1804477 -0.9840942 -5.22013e-4 0.1776464 -0.8660008 4.82684e-4 0.5000425 -0.8596135 0.001549959 0.5109424 -0.8661029 0.001548886 0.4998632 -0.8596383 0.002597033 0.5108966 -0.6605951 -0.00242871 0.7507386 -0.6248373 0.00473082 0.7807406 -0.3660871 -5.53001e-4 0.9305804 -0.6246963 -3.19887e-4 0.7808678 -0.3656792 -0.004930496 0.930728 -0.3099151 0.004320561 0.9507544 -0.01527762 -0.00439012 0.9998737 -0.06644594 -0.007934272 0.9977585 3.37506e-5 -0.007951259 0.9999684 0.1772459 -0.007803797 0.9841357 -0.01543962 0.02730631 0.9995079 0.5089103 -0.02733647 0.8603855 0.3203951 0.005144 0.94727 0.5110938 0.007681846 0.8594907 0.6257897 0.005208075 0.7799744 0.5110573 0.005315542 0.8595303 0.6243275 -0.008348405 0.7811181 0.7810311 0.007864296 0.6244426 0.8490931 -0.00339955 0.5282323 0.7804863 -0.003342807 0.6251639 0.8490203 -0.00509876 0.5283357 0.9507172 0.006167531 0.309998 0.9745355 -0.005854547 0.2241571 0.9977501 0.001054704 0.0670343 0.9996952 0 0.02468746 0.9835868 0 -0.1804356 -0.7126593 -0.1735936 0.6796925 -0.4810691 -0.7617973 0.4338633 -0.587755 -0.5536193 0.5899574 -0.6357704 -0.5134677 0.5763218 -0.6203044 -0.547877 0.5612959 -0.6374649 -0.513389 0.5745173 -0.63953 -0.5439713 0.543228 -0.6465262 -0.333478 0.686146 -0.4750086 -0.7704204 0.4252285 -0.4750274 -0.7704008 0.4252431 -0.498076 -0.7595314 0.4183686 -0.7166172 -0.1162408 0.6877119 -0.7166438 -0.1160144 0.6877226 -0.6784685 -0.1737068 0.7137973 -0.819817 -0.2618805 0.5092337 -0.7170094 -0.1159406 0.6873539 -0.6959368 -0.3241103 0.6407999 -0.6804696 -0.2949448 0.6707971 -0.7728548 -0.1039543 0.6260103 -0.7978002 -0.01899212 0.6026228 -0.7173068 -0.1156554 0.6870915 -0.9558244 -0.1959427 0.219103 -0.9587582 -0.2793881 0.05219948 -0.9562548 -0.2763864 0.09585064 -0.9450334 -0.2665814 0.1893305 -0.9686177 -0.1495739 0.1985131 -0.9686157 -0.1495833 0.1985156 -0.9467133 -0.2164439 0.2385079 -0.9178116 -0.2603743 0.2997116 -0.8500641 -0.2943273 0.4367637 -0.9160782 -0.1438722 0.3743014 -0.9160825 -0.143864 0.3742941 -0.9593461 -0.2775475 0.0512095 -0.9604598 -0.2736834 0.05113077 -0.9587599 -0.2793847 0.0521894 -0.9481347 -0.3175898 0.01331883 -0.9342266 -0.3561702 0.01906275 -0.9377605 -0.3456596 0.03353345 -0.9384998 -0.3418858 0.04829436 -0.8902744 -0.4383069 0.1236876 -0.8902735 -0.4383069 0.1236937 -0.8888472 -0.443042 0.1168945 -0.9275009 -0.3656163 0.07789015 -0.9384981 -0.341889 0.04830324 -0.7726585 -0.5493744 0.3180983 -0.7725678 -0.5493021 0.3184437 -0.7939556 -0.5682046 0.2162821 -0.7770495 -0.5294966 0.3403343 -0.8769092 -0.4394143 0.1947956 -0.8769064 -0.4394167 0.194803 -0.669887 -0.5366876 0.5130476 -0.6699087 -0.5366303 0.5130793 -0.6518883 -0.5775682 0.4913825 -0.6269096 -0.5466448 0.5551251 -0.5871933 -0.7802767 0.2153422 -0.5654086 -0.7441228 0.3558012 -0.5672259 -0.7471299 0.3464846 -0.53863 -0.7513513 0.3812466 -0.7156581 -0.5583188 -0.4196588 -0.6968451 -0.5494148 -0.4610317 -0.7095427 -0.595988 -0.3759621 -0.727273 -0.580628 -0.3659852 -0.8698229 -0.3006946 -0.3911406 -0.7166492 -0.5005151 -0.4856938 -0.707072 -0.5449424 -0.4506519 -0.7141188 -0.4919372 -0.4980283 -0.7141243 -0.4919316 -0.4980261 -0.7235671 -0.4795576 -0.4964627 -0.7148605 -0.5344582 -0.4509199 -0.7205574 -0.5355558 -0.4404282 -0.7160205 -0.5347477 -0.4487311 -0.7156606 -0.5582543 -0.4197405 -0.7156607 -0.5583227 -0.4196492 -0.7198653 0.4851828 -0.4963784 -0.7070291 0.5436787 -0.4522427 -0.7136558 0.4931082 -0.4975336 -0.7136656 0.4930981 -0.4975296 -0.8746914 0.2932922 -0.3858685 -0.7219175 0.4939504 -0.4846112 -0.7230311 0.5058507 -0.4704691 -0.5871457 0.5034986 -0.6338367 -0.7253053 0.5336702 -0.4348888 -0.7133191 0.5330846 -0.4549687 -0.7140606 0.5598961 -0.4202783 -0.7013028 0.5422369 -0.4627673 -0.7060778 0.5772605 -0.4101521 -0.7291535 0.5774078 -0.3673356 -0.7114084 0.5928347 -0.3774189 -0.7076751 0.5848285 -0.3964486 -0.7230144 0.505848 -0.4704976 -0.7089418 0.4994484 -0.4979488 -0.7101456 0.4379356 -0.5512763 -0.7064306 0.4282833 -0.5634973 -0.7050471 0.3263997 -0.6295807 -0.7096341 0.3407995 -0.6166647 -0.7098704 0.3242006 -0.6252823 -0.7124705 0.3394119 -0.6141542 -0.7030837 0.2503983 -0.665563 -0.7130214 0.1973361 -0.6727994 -0.7072576 0.1507035 -0.6907063 -0.7068576 0.199132 -0.678748 -0.7032091 0.1515452 -0.6946445 -0.7110188 0.06482011 -0.7001789 -0.7064424 0.04934394 -0.7060484 -0.7057859 0.06549263 -0.7053914 -0.7063232 0.04924231 -0.7061748 -0.7060521 -0.05324447 -0.7061554 -0.7112447 -0.07065171 -0.6993849 -0.7031199 -0.1553799 -0.6938872 -0.7059442 -0.2049919 -0.6779536 -0.7065404 -0.1546366 -0.690571 -0.7130234 -0.2029519 -0.6711245 -0.7031726 -0.2540125 -0.6640979 -0.7111142 -0.3288221 -0.6214439 -0.7097526 -0.3441268 -0.6146772 -0.7100204 -0.3293272 -0.6224265 -0.7062121 -0.3458608 -0.617774 -0.7054232 -0.4454821 -0.5512928 -0.7097774 -0.4293251 -0.5584768 -0.7100527 -0.4425832 -0.5476727 -0.6963961 -0.5146 -0.5002193 -0.7148772 -0.5344683 -0.4508817 0.713968 0.562028 -0.4175813 0.689817 0.5506912 -0.4699913 0.7114171 0.5928284 -0.3774126 0.7291253 0.577434 -0.3673505 0.8705126 0.2996281 -0.390424 0.7168366 0.5001986 -0.4857434 0.707076 0.5448846 -0.4507156 0.7140846 0.4920317 -0.497984 0.7141001 0.4920156 -0.4979777 0.7237441 0.4793755 -0.4963805 0.7155108 0.5323343 -0.4523987 0.7212486 0.5331786 -0.4421774 0.7143994 0.5322477 -0.454253 0.7139703 0.5620414 -0.4175596 0.7139703 0.5620315 -0.4175729 0.7070799 -0.5448815 -0.450713 0.7143429 -0.4918141 -0.4978284 0.7143371 -0.4918201 -0.4978307 0.8706167 -0.299517 -0.3902768 0.7169352 -0.5001259 -0.4856728 0.7270819 -0.5807991 -0.3660935 0.7095279 -0.5960017 -0.3759682 0.6969009 -0.5493741 -0.4609958 0.7231493 -0.5054402 -0.4707283 0.5976428 -0.5039204 -0.6236081 0.7252056 -0.5363321 -0.4317693 0.7151134 -0.5354642 -0.4493228 0.7156661 -0.5582712 -0.4197087 0.7156715 -0.5582794 -0.4196885 0.7231401 -0.5054386 -0.4707444 0.708851 -0.4989278 -0.4985994 0.7100846 -0.4425464 -0.547661 0.7060607 -0.4311472 -0.5617744 0.7056713 -0.3313659 -0.6262784 0.7096576 -0.3434067 -0.6151893 0.7099062 -0.3293918 -0.6225224 0.7118247 -0.3423554 -0.6132687 0.7032018 -0.2529017 -0.6644908 0.7130188 -0.2029535 -0.6711289 0.7065525 -0.1531838 -0.6908823 0.705968 -0.2049831 -0.6779314 0.7030343 -0.153948 -0.6942931 0.7114175 -0.07063424 -0.6992109 0.7057992 -0.05147385 -0.7065395 0.706107 0.06546723 -0.7050723 0.706116 0.06527388 -0.7050813 0.7113983 0.0510652 -0.7009314 0.6968764 0.2018621 -0.6881969 0.7071564 0.1530609 -0.6902914 0.7071563 0.1530528 -0.6902933 0.7129989 0.1973537 -0.672818 0.7029581 0.2529874 -0.664716 0.7116167 0.3233895 -0.6237155 0.7098259 0.3433409 -0.6150318 0.7101237 0.3240727 -0.6250609 0.7055506 0.3454111 -0.6187806 0.706546 0.440174 -0.5541118 0.7095422 0.4290237 -0.5590068 0.7097581 0.438165 -0.5515931 0.6967773 0.5141823 -0.500118 0.7155067 0.5323323 -0.4524073 -0.3646501 -0.6176369 -0.6968178 0.07970857 -0.9626433 -0.2587749 0.7038997 -0.06425309 -0.7073873 -0.1951432 -0.2711699 -0.9425423 -0.6015162 -0.1974852 -0.7740658 -0.4877954 -0.2988188 -0.8202213 -0.4730384 -0.1915248 -0.8599725 -0.492038 -0.1334048 -0.8602916 -0.4831839 -0.1920456 -0.8541966 -0.6523784 -0.03722006 -0.756979 -0.08961093 -0.3823571 -0.9196591 -0.209513 -0.2105276 -0.954873 -0.2093583 -0.2111287 -0.9547742 0.3228607 -0.329869 -0.8871005 0.2218754 -0.2568634 -0.9406341 0.2218546 -0.256822 -0.9406503 0.5396308 -0.1754063 -0.8234266 0.5396044 -0.1754382 -0.8234369 0.6050511 -0.1800533 -0.7755604 0.5932219 -0.1518413 -0.7905897 0.5888071 -0.1770057 -0.7886539 0.5556743 -0.1869766 -0.8101024 0.5398226 -0.1756684 -0.8232449 0.6827437 -0.1891962 -0.7057378 0.6616955 -0.1744399 -0.729198 0.6614901 -0.1715065 -0.7300797 0.6281642 -0.1682109 -0.7596808 0.6321792 -0.1705181 -0.7558261 0.6211905 -0.1799846 -0.7627109 0.605078 -0.1800788 -0.7755335 0.6703251 -0.3568499 -0.6506325 0.6606541 -0.1828855 -0.7280721 0.6097774 -0.3554068 -0.708419 0.08207464 -0.9629769 -0.2567865 0.07804286 -0.9632542 -0.2570035 0.07856917 -0.9641477 -0.2534684 -0.2133696 -0.8712759 -0.4419861 -0.07274651 -0.897723 -0.4345129 -0.07291197 -0.8976335 -0.4346698 -0.01724976 -0.9260708 -0.3769553 -0.175293 -0.9219764 -0.3452997 0.07859426 -0.9641525 -0.2534425 -0.3552255 -0.6330434 -0.6878015 -0.2988535 -0.8016835 -0.5176777 -0.3009511 -0.7591901 -0.5771125 -0.2240813 -0.7857974 -0.5764635 -0.2241119 -0.7857663 -0.5764938 -0.4309712 -0.4277837 -0.7945218 -0.4309883 -0.4277326 -0.7945401 -0.4561445 -0.4610916 -0.7611352 -0.474227 -0.4330493 -0.7665358 -0.3815776 -0.637817 -0.6690202 0.4819938 -0.5234079 -0.7026565 0.4856249 -0.5210103 -0.7019377 0.4149526 -0.4794517 -0.773266 0.4181849 -0.4779989 -0.7724236 0.355078 -0.4181231 -0.8361176 0.357821 -0.4174215 -0.8352983 0.313519 -0.3544269 -0.8809583 0.4627346 -0.2459124 -0.8517063 0.2199657 -0.7983972 -0.560515 0.2242699 -0.7971031 -0.560651 0.1167173 -0.7338542 -0.669205 0.120391 -0.7332702 -0.6691942 0.02399575 -0.6418067 -0.766491 0.0269621 -0.6417499 -0.7664398 -0.05470407 -0.5257613 -0.8488713 -0.05246925 -0.5260323 -0.8488445 -0.1076561 -0.409736 -0.9058292 0.1832667 -0.3086218 -0.9333627 0.07983767 -0.9625993 -0.2588986 0.456753 -0.7462264 -0.4842756 0.3072803 -0.8249385 -0.4743999 0.3880525 -0.7422839 -0.5462873 0.5284374 -0.5370766 -0.6574973 0.4995102 -0.745894 -0.4406039 0.6096341 -0.3558279 -0.7083309 -0.3745796 -0.8541704 0.3606705 -0.4147655 -0.8552413 -0.3106958 -0.3807689 -0.8861258 -0.2641898 -0.3898783 -0.8570907 -0.3367349 -0.4379185 -0.8603419 -0.2608436 -0.4234619 -0.8569455 -0.2938103 -0.4430041 -0.8568025 -0.2638878 -0.4169778 -0.8528817 -0.3142009 -0.403057 -0.8563881 -0.3227144 -0.4695702 -0.8787176 0.0857855 -0.5039559 -0.8633465 0.02571707 -0.5125523 -0.8585382 -0.0142219 -0.5135963 -0.8529661 -0.09310024 -0.5135279 -0.8552666 -0.06934046 -0.5109755 -0.8545839 -0.09268486 -0.5038748 -0.8610933 -0.06803303 -0.493272 -0.8500344 -0.184728 -0.491936 -0.858013 -0.1476913 -0.4807137 -0.858199 -0.1800239 -0.4834305 -0.863267 -0.1451379 -0.4679738 -0.8544765 -0.2255449 -0.5514147 -0.8225287 0.1392419 -0.3860946 -0.8684086 0.3111226 -0.4045825 -0.85507 0.3242967 -0.4019058 -0.8565587 0.3236956 -0.4024663 -0.8561135 0.3241766 -0.3830508 -0.8697446 0.3111532 -0.4018505 -0.8565982 0.3236601 -0.4041053 -0.8551216 0.3247553 -0.4044266 -0.8549799 0.3247286 -0.4039028 -0.8549668 0.3254141 -0.4122191 -0.85476 0.3153738 -0.4391324 -0.8596997 0.2609198 -0.4556836 -0.8553752 0.2463447 -0.4801095 -0.8587095 0.1792009 -0.4843178 -0.8581557 0.1703085 -0.4806349 -0.8583742 0.1793982 -0.4871886 -0.8563264 0.1713249 -0.5067022 -0.8572691 0.09133738 -0.5061159 -0.8574948 0.09246182 -0.5063096 -0.8575089 0.09126377 -0.533356 -0.8458909 -2.91439e-4 -0.3740432 -0.8547648 0.3598179 -0.3740735 -0.8547217 0.3598885 -0.3741428 -0.8546271 0.3600412 -0.4020552 -0.8531888 0.3322962 -0.4022274 -0.8502539 0.3395314 -0.3874829 -0.8729156 0.2964378 -0.3731294 -0.8562358 0.3572601 -0.3739269 -0.8549311 0.3595433 0.5924507 -0.5613349 -0.5778455 0.4768993 -0.7470943 -0.4630519 0.7088856 -0.06425458 -0.7023906 0.6931265 -0.1988122 -0.692856 0.6670693 -0.3568623 -0.6539633 0.6996047 -0.1986199 -0.6863698 0.6684043 -0.3564149 -0.6528432 0.5935932 -0.5607807 -0.5772107 0.6526396 -0.3567665 -0.6684155 0.4774253 -0.7464337 -0.463575 0.1400352 -0.9812774 -0.1322299 0.3946568 -0.8360826 -0.3810667 0.4676201 -0.7463967 -0.4735223 0.1744778 -0.9705364 -0.1661827 0.17405 -0.970567 -0.1664521 0.1741361 -0.9705369 -0.1665374 0.1367748 -0.9812878 -0.1355243 0 -1 0 2.36706e-6 -1 1.06635e-6 3.00529e-7 -1 -3.57524e-7 1.99673e-6 -1 1.45604e-6 -1.96918e-6 -1 1.3931e-6 -2.97565e-7 -1 -3.60087e-7 -2.98588e-7 -1 -3.59397e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.4332432 -0.790158 -0.4335329 -0.04520392 -0.9979354 -0.04562306 -0.4272323 -0.790292 -0.4392166 -0.5273817 -0.6654205 -0.5282842 -0.5485741 -0.6300626 -0.5496251 -0.1501691 -0.9758493 -0.1586419 -0.2534326 -0.9341449 -0.2512872 -0.1558237 -0.9758738 -0.1529361 -0.2556326 -0.9341134 -0.2491671 -0.2555824 -0.9341402 -0.2491181 -0.5304259 -0.6654021 -0.525251 -0.6709278 -0.2409546 -0.7012821 -0.6283405 -0.4504534 -0.6342554 -0.684245 -0.2404547 -0.6884695 -0.6292906 -0.4503697 -0.6333723 -0.6883137 -0.2409228 -0.6842371 -0.6985931 -0.121948 -0.7050507 -0.6443306 -0.2400881 -0.7260824 0.2861784 -0.7513946 -0.5945654 -0.4975742 -0.2044503 -0.8429827 -0.654728 -0.1714557 -0.7361618 -0.5873555 -0.1798639 -0.7890897 -0.5874143 -0.1799182 -0.7890335 -0.6202212 -0.1797757 -0.7635485 -0.6212303 -0.1680322 -0.7654006 -0.6212163 -0.1680243 -0.7654137 -0.5204167 -0.1981683 -0.8305996 -0.5271507 -0.1884075 -0.8286222 -0.5484265 -0.2174123 -0.8074406 -0.5915391 -0.1381913 -0.7943454 -0.5873508 -0.1799257 -0.789079 -0.1517251 -0.338564 -0.9286301 -0.2101152 -0.2611398 -0.9421558 0.2449811 -0.263545 -0.933021 0.1722792 -0.2490867 -0.9530351 0.123455 -0.3896805 -0.9126379 0.5176689 -0.2960742 -0.8027198 0.5223902 -0.3552331 -0.7751889 0.5326895 -0.1163091 -0.8382806 0.5327432 -0.1165425 -0.8382139 0.5327404 -0.1165704 -0.8382118 0.3755288 -0.565765 -0.73409 0.3755718 -0.5657117 -0.7341091 0.5010822 -0.4653133 -0.7296575 0.4513545 -0.348334 -0.8215489 0.4513711 -0.3482747 -0.8215649 0.3755447 -0.5657334 -0.7341061 0.4136428 -0.6246882 -0.6623173 0.280106 -0.7499769 -0.5992288 0.2834591 -0.7544438 -0.5920013 0.2800999 -0.7499999 -0.5992029 0.2801005 -0.7499836 -0.5992231 0.1810882 -0.8912557 -0.4157767 0.1560851 -0.8567315 -0.4915775 0.1254724 -0.8768097 -0.4641782 -0.02200186 -0.9974043 -0.06856 -0.3627644 -0.9218544 -0.1363327 -0.3628558 -0.921823 -0.1363008 -0.04341602 -0.9693556 -0.241795 -0.1516367 -0.9253774 -0.3473947 -0.04548525 -0.9495247 -0.3103772 -0.04548108 -0.9495165 -0.3104031 0.02199161 -0.9265022 -0.3756463 0.06684875 -0.9768543 -0.2031915 0.1249481 -0.8771536 -0.4636697 -0.6708707 -0.2408952 -0.7013573 -0.657373 -0.1876548 -0.7298264 -0.6558155 -0.1883155 -0.7310562 -0.6558581 -0.1883272 -0.731015 0.02486014 -0.2939521 -0.9554969 0.1109771 -0.4203395 -0.9005547 0.06063556 -0.5249734 -0.8489561 0.06180667 -0.5266549 -0.8478292 -0.0191695 -0.6406294 -0.767611 -0.01796257 -0.6427634 -0.7658541 -0.1130593 -0.7321927 -0.6716483 -0.1118896 -0.7347695 -0.6690251 -0.2174935 -0.7963229 -0.564417 -0.216513 -0.7990806 -0.5608853 -0.3516038 -0.8344016 -0.4244393 -0.4457406 -0.6615386 -0.6030605 -0.4722338 -0.6218894 -0.6246989 -0.4457458 -0.6615452 -0.6030496 -0.210983 -0.2649496 -0.9408974 -0.2108978 -0.2647753 -0.9409655 -0.3151749 -0.3295466 -0.8899796 -0.3060216 -0.3548705 -0.8834124 -0.3495618 -0.4162092 -0.8393906 -0.348464 -0.4188292 -0.8385434 -0.410126 -0.4768126 -0.7774615 -0.4091933 -0.4801254 -0.7759125 -0.4777569 -0.5200867 -0.707996 -0.4771825 -0.5238605 -0.7055971 -0.5670524 -0.5483666 -0.6146101 -0.6441941 -0.2406494 -0.7260177 0.5114376 -0.8546004 -0.08994394 0.4014979 -0.8567042 0.3238167 0.4017668 -0.8532611 0.3324589 0.3740041 -0.8545942 0.3602636 0.340408 -0.9033632 0.2608779 0.4018732 -0.8504054 0.3395712 0.4018707 -0.8504096 0.3395634 0.4033524 -0.8553577 0.3250691 0.5138665 -0.8552795 -0.06662082 0.5028575 -0.8598347 -0.08842211 0.4981076 -0.8547012 -0.1462007 0.4818839 -0.8581854 -0.1769341 0.4928552 -0.8580024 -0.1446567 0.4785766 -0.8602831 -0.1757194 0.4695026 -0.8545106 -0.2222138 0.4399097 -0.8603078 -0.2575851 0.425773 -0.8569539 -0.2904258 0.444952 -0.8568138 -0.2605531 0.4121825 -0.851381 -0.3244319 0.4170993 -0.8554361 -0.3070135 0.4172568 -0.8552711 -0.3072591 0.383347 -0.8858161 -0.2614863 0.3927402 -0.8570948 -0.3333824 0.438887 -0.8596609 0.2614598 0.411907 -0.8547993 0.3156751 0.4036998 -0.8550092 0.3255545 0.4041982 -0.8550217 0.3249028 0.4033629 -0.8553531 0.3250682 0.5139465 -0.8552304 -0.06663358 0.5126634 -0.8584916 -0.01298451 0.509713 -0.8603424 0.001924455 0.5150545 -0.8567224 0.02730286 0.5057933 -0.8576401 0.09287995 0.5057838 -0.8574979 0.09423404 0.5060009 -0.8575131 0.09292018 0.5061365 -0.8572825 0.09430021 0.4841436 -0.8558676 0.1819222 0.4838967 -0.8581374 0.1715925 0.4802733 -0.8583507 0.1804762 0.4828788 -0.8587836 0.1712276 0.4552067 -0.8554104 0.2471032 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.4322669 -0.8052504 0.4058538 0.3597936 -0.8574835 0.3677916 0.4829617 -0.8211635 0.3040371 0.487119 -0.8261139 0.283286 0.4339903 -0.8058546 0.4028037 0.4356998 -0.806436 0.3997833 0.4512688 -0.8107591 0.3728622 0.5217354 -0.8068521 0.2770954 0.6402179 -0.7422978 0.1977752 0.6402062 -0.7423059 0.1977828 0.4328839 -0.8512182 0.2967138 0.4328876 -0.8512146 0.2967188 0.432436 -0.8551276 0.2859301 0.4723114 -0.8367391 0.2771095 0.4871163 -0.8261173 0.2832803 0.5312982 -0.8330813 0.1539406 0.531301 -0.8330825 0.1539248 0.5104176 -0.8308913 0.2215706 0.5105293 -0.8308526 0.2214584 0.4593789 -0.8468492 0.2679882 0.4501441 -0.8495036 0.2751615 0.4467093 -0.8504691 0.2777646 0.4213671 -0.85725 0.2959259 0.4067343 -0.8607798 0.3059825 0.3772346 -0.884536 0.2743908 0.3962219 -0.8569695 0.3295626 0.6826761 -0.726508 0.07835566 0.682864 -0.7267037 0.0748232 0.6314965 -0.7558589 0.1728854 0.5109094 -0.8479696 0.1411353 0.5312932 -0.8330857 0.153934 0.8354908 -0.5296037 0.1465435 0.6826766 -0.7265074 0.07835668 0.7541362 -0.6425748 0.1355592 0.7868841 -0.6158351 0.03950446 0.7712599 -0.5816422 0.2585548 0.7971162 -0.5987323 0.07826602 0.8354881 -0.529609 0.1465403 0.8355002 -0.5295731 0.1465998 0.8543108 -0.5163279 0.05965429 0.8543102 -0.5163286 0.05965524 0.8874657 -0.460585 0.01631659 0.9215508 -0.3878127 0.01859247 0.8089771 0.06360858 0.5843886 0.9506242 -0.3096619 0.02056956 0.1505448 0.9886023 0.00138247 0.1514927 0.9884387 -0.006241261 0.1315997 0.9813542 -0.1400904 0.5468333 0.8295549 0.1131904 0.4570265 0.8815958 0.1179648 0.1345335 0.9888339 0.06409698 0.2215782 0.9737415 0.05225503 0.2100033 0.9738326 0.0868836 0.2425182 0.9671955 0.07561594 0.2167952 0.9717481 0.09330344 0.3412941 0.9365854 0.07953751 0.2851723 0.9452831 0.1584824 0.4409603 0.893252 0.08749306 0.3540067 0.9181144 0.1781718 0.4234539 0.899321 0.1091266 0.5418225 0.7596314 0.3597061 0.5109437 0.8113269 0.2840513 0.6910374 0.5817002 0.4290596 0.6910876 0.5817105 0.4289647 0.6959321 0.6493206 0.306694 0.5109398 0.8113299 0.2840503 0.5109435 0.8113281 0.2840486 0.7279476 0.02721858 0.6850923 0.7280578 0.02747225 0.6849651 0.7672587 0.2367773 0.5960291 0.7336305 0.2165323 0.6441274 0.8059937 0.3097803 0.504391 0.7311674 0.4551663 0.5081513 0.7311926 0.4551422 0.5081368 0.6500617 0.03344535 0.7591451 0.6558152 0.08856225 0.7497087 0.699374 0.022991 0.7143861 0.6981569 0.02627867 0.7154623 0.6899175 0.03435921 0.7230722 0.6938694 0.05143916 0.7182614 0.6938566 0.0514636 0.7182719 0.6964402 0.007647573 0.717574 0.6964431 0.007625043 0.7175715 0.6928309 0.008323371 0.721052 0.6935499 0.01361924 0.7202798 0.6912834 0.02287584 0.7222216 0.6922628 0.001213133 0.7216445 0.6814751 0.1539448 0.7154669 0.7432581 0.004235088 0.6689913 0.856641 0.0395596 0.514394 0.9466411 -0.03903746 0.3199166 0.9465622 -0.03902053 0.3201521 0.931424 -0.05216771 0.3601775 0.9314435 -0.05214595 0.3601304 0.8903205 -0.1168513 0.4400852 0.9281134 0.002931654 0.372286 0.8566974 0.03953981 0.5143015 0.8566325 0.03954458 0.5144096 0.9717837 -0.1774836 0.1553575 0.9560922 -0.2317245 0.1794194 0.9936634 -0.05126571 0.1000236 0.9922214 -0.05994158 0.109104 0.9914946 0.01378822 0.1294151 0.9654783 -0.2387982 0.1040539 0.9895536 -0.1253145 0.07127392 0.9770355 -0.1899263 0.09659004 0.9654687 -0.2388362 0.1040555 0.9654805 -0.238792 0.1040479 0.9667203 -0.2363746 0.09787207 0.9771272 -0.2103293 0.03136658 0.9592511 -0.278608 0.04706341 0.9637169 -0.2637324 0.0411691 0.9637193 -0.263724 0.04116797 0.9689221 0.2119906 0.127476 0.9903085 0.08011209 0.1134506 0.9903086 0.08011054 0.1134513 0.9914945 0.01379191 0.1294152 0.92105 0.3773517 0.09629595 0.9210512 0.377349 0.09629362 0.9295915 0.3624786 0.06684958 0.9499931 0.2922391 0.1100429 0.9689136 0.2120245 0.1274832 0.7763487 0.6221841 0.1008449 0.7763587 0.6221728 0.100838 0.7948658 0.6042404 0.05551558 0.8354673 0.5407433 0.09793347 0.8882791 0.4424551 0.1232631 0.54683 0.8295569 0.113192 0.5995757 0.7988763 0.04801702 0.5966498 0.7994287 0.07016366 0.7154981 0.6880415 0.1210839 0.7154949 0.6880447 0.1210846 0.805464 0.078148 0.5874697 0.8122196 0.1160439 0.5716932 0.8066334 0.1309587 0.5763614 0.8092373 0.1852378 0.557514 0.7799805 0.2378945 0.5788235 0.7206832 0.1205628 0.6827008 0.7279617 0.02719002 0.6850785 0.9833329 0.1495586 0.1033856 0.9886361 0.1279788 0.07886761 0.9183499 0.06472605 0.3904409 0.9267795 0.04646241 0.3727209 0.8009043 0.01546072 0.5985927 0.7981538 -0.1056333 0.5931207 0.7018158 0.1542136 0.6954659 0.6906285 0.002624928 0.723205 0.6909723 0.002407193 0.7228773 0.804551 0.02318614 0.593431 0.802219 0.04183918 0.595562 0.9249939 0.1226015 0.3596596 0.9063363 0.1953997 0.3746646 0.9027681 0.198557 0.381556 0.8899053 0.3031292 0.3408535 0.846298 0.3806654 0.3726575 0.8199454 0.4844213 0.3050007 0.7227537 0.5849366 0.3680709 0.7403615 0.453755 0.4959549 0.5539308 0.8207726 -0.1396176 0.3248551 0.9429875 -0.07241392 0.4403876 0.8920038 -0.101922 0.4534108 0.8816758 -0.1306387 0.5539361 0.8207681 -0.1396226 0.5539234 0.8207762 -0.1396254 0.6795248 0.7117475 -0.1779369 0.5488641 0.8356249 -0.02189236 0.6014544 0.7731031 -0.2014054 0.6404141 0.7483273 -0.1728471 0.6691393 0.7332887 -0.1205828 0.6720244 0.730123 -0.1237083 0.6949257 0.6280736 -0.3501456 0.7005659 0.6002288 -0.3859182 0.7040836 0.62032 -0.3456435 0.6668781 0.6554401 -0.3545024 0.6806902 0.6371329 -0.3615559 0.6934316 0.6189376 -0.3688752 0.6939451 0.6101913 -0.3822395 0.6939331 0.6101993 -0.3822482 0.6676127 0.6497315 -0.3635138 0.6670189 0.6542932 -0.3563513 0.6668822 0.6554382 -0.3544982 0.5901135 0.754255 -0.2878638 0.6676151 0.649721 -0.363528 0.6406015 0.7029526 -0.3090106 0.6302431 0.7059767 -0.3230954 0.4403898 0.8920031 -0.101919 0.3687268 0.9207258 -0.1276889 0.6321455 0.7168487 -0.2941427 0.2438096 0.9464179 -0.2117785 0.2427635 0.9467462 -0.2115125 0.8473154 0.528082 -0.05644416 0.998042 0.06253582 0.001196205 0.9190613 0.378652 -0.1093114 0.9737934 0.1940338 -0.1186481 0.9198141 0.3745419 -0.1168773 0.8848095 0.4569587 -0.09111022 0.9140784 0.3275699 -0.2390785 0.8530288 0.2027664 -0.4808613 0.8692469 0.2551894 -0.4234246 0.8473134 0.528085 -0.05644571 0.7351731 0.6576397 -0.1644099 0.7550975 0.5732271 -0.31818 0.8473146 0.5280826 -0.05645072 0.8285396 0.4443268 -0.3407285 0.7644904 0.5883909 -0.263345 0.7587068 0.5943772 -0.2666081 0.76471 0.5635014 -0.3125455 0.8790137 0.4437573 -0.1743975 0.8790093 0.4437643 -0.174401 0.8008299 0.5946218 -0.07138949 0.7792503 0.5916657 -0.2066414 0.7458243 0.6266465 -0.2259656 0.7538952 0.652143 -0.0796982 0.7539005 0.6521385 -0.0796827 0.6675352 -0.6542428 -0.3554759 0.4411659 -0.8915506 -0.1025184 0.6976344 -0.6855919 -0.2080145 0.5545154 -0.8202617 -0.1402981 0.5545242 -0.8202573 -0.1402887 0.5544378 -0.8218234 -0.1311679 0.6408582 -0.7477568 -0.1736679 0.6408551 -0.7477589 -0.1736703 0.4333437 -0.8940784 -0.1133006 0.4815595 -0.86609 -0.1341219 0.5545359 -0.8202486 -0.1402935 0.3248582 -0.9429864 -0.07241469 0.3250424 -0.9429056 -0.07263988 0.3692582 -0.9203854 -0.1286045 0.63302 -0.7156001 -0.2953006 0.5899939 -0.7542712 -0.2880662 0.6675437 -0.6542389 -0.3554673 0.6683003 -0.6484845 -0.3644758 0.6623095 -0.6714492 -0.3324186 0.6311359 -0.7046998 -0.3241383 0.6311438 -0.7046977 -0.3241277 0.6514275 -0.7426863 -0.1551108 0.6622622 -0.7146028 -0.2252812 0.6622372 -0.7146525 -0.2251968 0.6899868 -0.6238365 -0.3670778 0.6979464 -0.6073924 -0.3794013 0.6939172 -0.6101416 -0.3823689 0.7093797 -0.5862216 -0.3913113 0.7073884 -0.5641598 -0.4258233 0.5109409 -0.811299 0.2841361 0.7403265 -0.4538818 0.495891 0.6971141 -0.007600128 0.7169199 0.1505318 -0.9886043 0.001370489 0.1514859 -0.9884397 -0.006245851 0.1344653 -0.988841 0.06413084 0.2215817 -0.9737405 0.05226039 0.1315909 -0.9813524 -0.1401119 0.1968929 -0.9724256 0.1249865 0.2079602 -0.9729668 0.1004401 0.2479664 -0.9648668 0.08686059 0.2162656 -0.9702973 0.1084085 0.343066 -0.9356423 0.08294212 0.3057551 -0.9402738 0.1496624 0.3992035 -0.9167768 0.01252484 0.345087 -0.9197456 0.1870372 0.3541263 -0.9180816 0.1781035 0.4420706 -0.8924961 0.08957904 0.7763628 -0.622166 0.1008477 0.7155016 -0.6880365 0.1210918 0.6105655 -0.787988 -0.07927685 0.5995857 -0.7988678 0.04803371 0.5468378 -0.8295499 0.1132054 0.5468384 -0.8295495 0.1132051 0.9210512 -0.3773446 0.09631043 0.8882847 -0.4424407 0.1232739 0.8045708 -0.5877936 0.08464455 0.8085159 -0.5881983 0.0180279 0.776359 -0.6221703 0.1008503 0.9689136 -0.2120169 0.1274961 0.9689136 -0.212017 0.1274961 0.9321087 -0.3489578 0.09696322 0.9419794 -0.3353359 0.01498204 0.9210527 -0.3773418 0.09630787 0.9903061 -0.08010673 0.1134741 0.98772 -0.12541 0.09317404 0.9951522 -0.09106874 0.03712797 0.983332 -0.1495559 0.1033974 0.9924569 0.05018568 0.1118515 0.9914917 -0.01380759 0.1294354 0.991492 -0.01379144 0.1294351 0.9506599 0.3095326 0.02086603 0.9638659 0.2627822 0.04368102 0.9638716 0.2627614 0.04368084 0.9529795 0.2985625 0.05187022 0.9776483 0.1995763 0.06613069 0.904801 0.07217419 0.4196738 0.9274818 -0.02999442 0.372663 0.9047901 0.07219421 0.4196938 0.9047949 0.07217991 0.4196859 0.94655 0.03898614 0.3201926 0.9465006 0.03897541 0.3203396 0.9927265 0.06034791 0.1041741 0.9558687 0.2324646 0.1796526 0.985401 0.113673 0.1267411 0.9668501 0.2294908 0.1119592 0.9770426 0.1899216 0.09652811 0.9654972 0.2387547 0.1039772 0.9654777 0.2388283 0.1039899 0.8003601 0.0653367 0.5959486 0.7867091 0.08288669 0.6117341 0.8794996 -0.0347855 0.4746267 0.6875103 0.03531885 0.7253153 0.7455661 -0.09435784 0.6597181 0.7455595 -0.09435772 0.6597253 0.6928281 -8.10616e-4 0.7211023 0.692318 -0.001252114 0.7215914 0.6923135 -0.001511335 0.7215953 0.693506 -0.01218962 0.7203477 0.6987113 -0.02554064 0.7149476 0.6987236 -0.02550774 0.7149369 0.6898199 -0.03425681 0.7231701 0.693646 -0.05080741 0.718522 0.7030377 -0.1116206 0.702338 0.7370867 -0.1496275 0.6590256 0.7549415 -0.1742577 0.6322163 0.703121 -0.111674 0.7022461 0.6545761 -0.08795475 0.7508621 0.6846005 -0.06078016 0.7263801 0.6936668 -0.05076742 0.7185047 0.8136983 -0.3485494 0.4651972 0.7530639 -0.2260525 0.6178957 0.7530642 -0.2260526 0.6178954 0.7403316 -0.4537447 0.496009 0.715156 -0.4572459 0.5286571 0.715143 -0.4572548 0.5286668 0.6300495 -0.7642745 0.1375572 0.6609761 -0.7208298 0.2086027 0.6856979 -0.5530412 0.4732482 0.4288156 -0.8954959 0.1191825 0.5421043 -0.7590119 0.3605883 0.5109402 -0.8113024 0.2841278 0.7940454 -0.1624627 0.5857455 0.8234593 -0.156891 0.5452522 0.7799755 -0.237887 0.5788334 0.7885143 -0.2385922 0.5668501 0.7548884 -0.1218532 0.6444342 0.6929837 -0.008390069 0.7209045 0.79984 -0.05880254 0.597326 0.8126387 -0.04749357 0.5808293 0.934319 -0.07415974 0.3486378 0.899087 -0.1018515 0.4257568 0.9267702 -0.04646134 0.3727445 0.805323 -0.01637703 0.5926101 0.8006834 -0.02243262 0.5986675 0.6976299 -0.003556251 0.7164496 0.6870288 -0.00544399 0.7266098 0.6910724 -0.5816664 0.4290492 0.7206229 -0.5867963 0.3692867 0.8448063 -0.4527487 0.2851684 0.821357 -0.4185752 0.3875147 0.9192291 -0.2387431 0.313081 0.8629967 -0.2297589 0.4499418 0.9063246 -0.1953855 0.3747004 0.8205415 -0.09253102 0.5640476 0.7988307 -0.1036417 0.5925605 0.6944786 -0.01941543 0.7192513 0.6935713 -0.02311104 0.7200172 0.6826687 0.7265278 0.07823652 0.7906261 0.6117185 0.02666008 0.7125087 0.662395 0.2314395 0.8885218 0.4585106 0.01723265 0.8755881 0.4818681 0.03389441 0.8523124 0.5192045 0.06316936 0.8523105 0.5192071 0.06317251 0.7993245 0.5999819 0.03319793 0.7986401 0.5996794 0.0505833 0.7950635 0.5899441 0.1408539 0.8183885 0.5707684 0.06681108 0.8395739 0.5210761 0.1536077 0.8395708 0.5210869 0.1535876 0.6828501 0.7267157 0.07483422 0.6828503 0.7267155 0.07483375 0.5960678 0.7787461 0.1955958 0.5314166 0.8330013 0.1539654 0.4083392 0.8600074 0.3060172 0.5068966 0.8306502 0.2303824 0.5069616 0.8306282 0.2303187 0.53142 0.8329989 0.1539666 0.5314196 0.8329986 0.1539692 0.4150389 0.8553678 0.3099818 0.41504 0.8553668 0.3099831 0.4130013 0.8589084 0.3028304 0.4328967 0.8509661 0.2974174 0.4154249 0.8550271 0.3104041 0.4144201 0.8558956 0.3093518 0.4144641 0.8558605 0.3093901 0.4870685 0.8261212 0.2833515 0.4601364 0.8451274 0.2720923 0.4332886 0.8468638 0.3083547 0.4328882 0.8509745 0.297406 0.7170786 0.6789745 0.1574547 0.6393266 0.7429521 0.1982008 0.6393622 0.7429277 0.1981778 0.5212699 0.8069188 0.2777764 0.4487825 0.8106909 0.375998 0.4322729 0.8052524 0.4058431 0.4296154 0.8041889 0.4107442 0.4844662 0.8230448 0.2964621 0.4870635 0.826128 0.28334 -0.7038423 7.90742e-6 -0.7103563 -0.7040271 -3.78314e-4 -0.710173 -0.7038517 0 -0.7103469 -0.7038424 -8.61883e-6 -0.7103562 -0.7038421 -9.05062e-6 -0.7103565 -0.7038437 -6.32218e-6 -0.7103549 -0.7039099 1.66368e-4 -0.7102892 -0.7038462 -1.13945e-5 -0.7103524 -0.7038429 -6.76712e-6 -0.7103557 -0.5431853 -0.1349709 -0.8286933 0.7489133 0.005418241 -0.6626459 0.7176416 0 -0.6964126 0.7290197 0.01142603 -0.6843975 0.5989908 -0.08204609 -0.7965417 0.6958746 0.03035336 -0.7175216 0.7108524 0.03968685 -0.7022206 0.7141175 0.04265099 -0.6987253 0.7121881 0.04090315 -0.700796 -0.6801347 0.08733367 -0.7278665 -0.6926168 0.0256285 -0.7208503 -0.6370095 0.002632439 -0.7708514 -0.7069892 0.03461587 -0.7063768 -0.7100521 0.03738147 -0.7031562 -0.7068597 0.03428435 -0.7065224 -0.74351 0 -0.6687249 -0.6658877 -0.0210222 -0.7457557 -0.7501156 0.002747297 -0.661301 -0.7495865 0.00256139 -0.6619014 0.6961898 0.03054773 -0.7172076 0.6434301 0.008592009 -0.7654567 0.6009903 0.008604526 -0.7992101 0.4659019 -0.02701729 -0.8844238 0.4695922 -0.02992624 -0.8823761 0.03546971 0.007210135 -0.9993448 0.1836058 -0.03922051 -0.9822173 0.1636101 -0.02462136 -0.9862179 0.327544 0.008493363 -0.9447977 0.3275592 0.008493363 -0.9447924 0.03550177 0.007210135 -0.9993435 -0.1553559 -0.0181427 -0.987692 -0.1196054 -0.04615807 -0.991748 -0.5481801 0.002648353 -0.8363562 -0.4173311 -0.05147242 -0.9072956 -0.4585837 -0.01498132 -0.888525 -0.2718999 0.006237328 -0.9623054 -0.2719203 0.006237328 -0.9622996 0.7103428 1.21927e-5 -0.7038558 0.7104337 -1.59323e-4 -0.7037641 0.7103378 3.4482e-5 -0.703861 0.7103536 -2.30315e-6 -0.703845 0.7103489 -1.53232e-5 -0.7038497 0.7105073 2.56057e-4 -0.7036898 0.7103469 -1.10052e-5 -0.7038516 0.710336 -2.19809e-5 -0.7038627 0.7103598 0 -0.7038388 -0.09967386 0.9919663 0.07789772 -0.01300346 0.9998685 -0.009678423 -0.1141989 0.9911264 -0.0680229 -0.1284258 0.9892979 -0.06925594 -0.1050498 0.9913882 -0.07819163 -0.1314157 0.9909551 -0.02716398 -0.1314134 0.9909552 -0.02717226 -0.127591 0.9906754 -0.04778182 -0.130448 0.9903166 -0.04749846 -0.1166675 0.9911766 -0.06290918 -0.1313686 0.9913038 -0.007702112 -0.1414367 0.9899473 -7.72826e-5 -0.1448582 0.9888612 0.03420144 -0.1303375 0.9914051 0.01131749 -0.1303375 0.9914051 0.01131737 -0.2844807 0.9290152 0.2366466 -0.2845593 0.928975 0.23671 -0.130923 0.9900346 0.05186933 -0.1262875 0.9908732 0.04713708 -0.1173766 0.9907836 0.06760507 -0.1192929 0.9903259 0.07087987 -0.1043182 0.9911968 0.08152621 -0.106844 0.9912086 0.0780372 -0.09965187 0.9919697 0.0778827 -0.2845593 0.9289768 0.2367027 -0.3172694 0.9177391 0.2389457 -0.3886691 0.8665122 0.3131979 -0.1130532 0.9913185 -0.06713086 -0.1200148 0.9873456 -0.1036583 -0.1199666 0.9873555 -0.1036199 -0.3705163 0.9184032 -0.1387557 -0.3705168 0.9184031 -0.1387557 -0.3399159 0.9184027 -0.2024689 -0.3399111 0.9184045 -0.2024691 -0.3399103 0.918403 -0.2024771 -0.3125928 0.9189153 -0.2405838 -0.3147302 0.9151196 -0.251994 -0.3705155 0.9184035 -0.1387562 -0.3892922 0.9184037 -0.07061296 -0.1374572 0.9901938 -0.02493309 -0.1313685 0.9913037 -0.007702827 -0.3956439 0.918404 -2.16218e-4 -0.395644 0.9184041 -2.16184e-4 -0.3892974 0.9184047 -0.07057267 -0.3892922 0.9184036 -0.07061296 -0.3893699 0.9184035 0.070185 -0.3893681 0.9184042 0.07018679 -0.130169 0.9912141 0.02346402 -0.1283085 0.9912714 0.03029495 -0.3893682 0.9184041 0.07018691 -0.3706651 0.9184041 0.1383517 -0.3706656 0.918404 0.1383516 -0.3706656 0.9184041 0.138351 -0.3401337 0.9184041 0.2020961 -0.3401355 0.9184029 0.2020987 -0.3074254 0.9187791 0.2476583 -0.3648687 0.9070542 0.2100558 -0.5806152 0.8059284 0.1156086 -0.6600636 0.7511739 -0.00733596 -0.7049258 0.7059505 0.06865584 -0.7102085 0.7038699 0.01308017 -0.7665495 0.640987 0.03921061 -0.7721205 0.6337184 0.04723227 -0.402746 0.90492 0.1375336 -0.420097 0.882051 0.213318 -0.4307993 0.884953 0.176834 -0.461325 0.8838406 0.07749247 -0.5022736 0.8497503 0.1601421 -0.5148344 0.8561626 0.04394441 -0.5873695 0.7975063 0.1377708 -0.5806139 0.8059279 0.115619 -0.3381869 0.9016536 0.2695373 -0.3470933 0.9051007 0.2455993 -0.3473641 0.9051908 0.2448831 -0.3499591 0.9058844 0.2385415 -0.01526427 0.999742 0.01682138 -0.01697105 0.9997862 0.0118131 -0.01698368 0.9997863 0.0117895 -0.04935085 0.9981697 0.03495168 -0.04465538 0.9988496 0.01747465 -0.0446549 0.9988496 0.0174762 -0.1204696 0.9926908 0.007221698 -0.1204695 0.9926908 0.00722301 -0.1094425 0.9928906 0.04680323 -0.08291363 0.9964359 0.01551449 -0.08291351 0.9964359 0.01551496 -0.06348663 0.9979754 0.003805935 -0.06348663 0.9979754 0.003806114 -0.2550836 0.9657469 -0.04759472 -0.1365836 0.9881227 0.07041591 -0.07220095 0.9914836 0.1083847 -0.3247606 0.9264355 0.1903883 -0.3246793 0.926471 0.1903547 -0.3443089 0.9170818 0.2010278 0.04432654 0.8355765 0.5475828 -0.3752959 0.8668002 0.328345 -0.1159767 0.991461 0.05961984 -0.1532945 0.9848031 0.08163213 -0.1722432 0.9839682 0.046247 -0.197393 0.9737283 0.1135302 -0.2263261 0.9737989 0.02218645 -0.2764668 0.9553362 0.1043975 -0.2945598 0.9556093 0.006731092 -0.3570422 0.9298806 0.08855992 -0.3665316 0.9304015 0.002777874 -0.4992769 0.8647528 0.05408537 -0.5003413 0.8652598 0.03136724 -0.7728757 0.6343499 -0.01623535 -0.1660285 0.9861198 0.001578986 -0.1124449 0.9924934 0.04809409 -0.1659463 0.9856137 0.03205353 -0.254171 0.9671056 -0.01019436 -0.5024994 0.8640736 0.02951502 -0.5024988 0.8640739 0.0295152 -0.6065081 0.7950672 0.004001379 -0.7729669 0.6344229 -0.005446434 -0.7874761 0.6163234 -0.005185782 -0.7874764 0.616323 -0.005185782 -0.7729775 0.6344318 -0.001432061 -0.8626531 0.5057959 1.79878e-6 -0.1090858 0.9940323 0 -0.1660226 0.9860848 -0.008552551 -0.6065051 0.7950695 0.004001379 -0.4974616 0.867381 -0.01349681 -0.5026775 0.8643815 -0.01264709 -0.4612292 0.8871837 -0.01313698 -0.5026908 0.8644028 -0.01047688 -0.3262317 0.9452795 0.004406869 -0.16603 0.9861111 0.004346787 -0.3259003 0.9453963 -0.00388354 -0.3259094 0.945393 -0.00388354 0.3066866 0.9191105 0.2473443 0.1043537 0.9909722 0.08416885 0.3066829 0.9191069 0.2473621 0.1147958 0.9910324 0.06838726 0.1061666 0.9909473 0.08217167 0.1033609 0.9914032 0.08022576 0.103467 0.9914039 0.08007943 0.1225492 0.9900543 0.06909573 0.1286022 0.9905182 0.04832404 0.1261683 0.9908152 0.0486502 0.1161878 0.9910647 0.06550639 0.1375971 0.9901659 0.02526724 0.1285635 0.9912739 0.02910989 0.1285629 0.991274 0.0291121 0.1531953 0.9881412 -0.01040256 0.1298063 0.9914883 0.01006507 0.1298063 0.9914883 0.01006489 0.1408 0.9895694 -0.03045719 0.130331 0.9912058 -0.02291709 0.1289989 0.9912521 -0.02790409 0.1287453 0.9905048 -0.04821884 0.289761 0.928023 -0.2341195 0.2897494 0.9280289 -0.2341104 0.1166228 0.9910941 -0.06427681 0.1198901 0.9903021 -0.07020097 0.1052574 0.9913502 -0.07839328 0.1070454 0.9913539 -0.07588475 0.1023194 0.991828 -0.07620996 0.3066899 0.9191033 0.2473672 0.3067189 0.9191004 0.2473418 0.3392465 0.9187316 0.2020992 0.3392435 0.9187327 0.2020989 0.3696424 0.9187331 0.1389029 0.3696419 0.918734 0.1388981 0.3696433 0.9187335 0.1388978 0.3883844 0.9187334 0.07131987 0.3883816 0.9187344 0.07132065 0.3883823 0.9187342 0.07131999 0.3948753 0.9187336 0.00149089 0.1307325 0.9914176 4.93613e-4 0.1299502 0.9914813 -0.008824586 0.3889122 0.9187331 -0.06838601 0.388911 0.9187338 -0.06838518 0.3889097 0.9187334 -0.06839573 0.3948754 0.9187335 0.00149089 0.3706827 0.918733 -0.1361036 0.3706824 0.918733 -0.1361038 0.1273722 0.9907518 -0.04676735 0.1166228 0.9910941 -0.06427681 0.3942759 0.8650071 -0.3103374 0.3163968 0.9192719 -0.234163 0.340758 0.9187316 -0.1995404 0.340759 0.9187335 -0.1995295 0.3407613 0.9187327 -0.1995294 0.3706826 0.9187328 -0.1361042 -0.8709256 0.2602496 -0.416844 -0.8536086 0.2035027 -0.4795197 -0.9143302 0.3270833 -0.2387817 -0.8789258 0.4724829 -0.06518667 -0.8922389 0.4269273 -0.1471155 -0.890088 0.4338593 -0.1396762 -0.9650966 0.2200722 -0.1419744 -0.9408662 0.3092515 -0.1383272 -0.7624386 0.6235976 -0.1726654 -0.7618232 0.59146 -0.264198 -0.7459263 0.6406205 -0.1822069 -0.7596044 0.5151806 -0.3969763 -0.847969 0.5262811 -0.06306141 -0.847966 0.5262859 -0.06306385 -0.8234584 0.5328021 -0.1950339 -0.8470525 0.3822661 -0.3692895 -0.7646924 0.5884743 -0.2625712 -0.7284439 0.6576865 -0.1918805 -0.7284196 0.6576973 -0.1919348 -0.7514243 0.6490396 -0.1187818 -0.7990707 0.5754544 -0.1741786 -0.8188894 0.5508832 -0.1610839 -0.7786958 0.6230213 -0.07401055 -0.8909666 0.4291856 -0.1482508 -0.4383005 0.8932139 -0.1003081 -0.6698178 0.7332054 -0.1172771 -0.5531655 0.8214344 -0.1387563 -0.5531637 0.8214353 -0.1387582 -0.5529217 0.823026 -0.1300223 -0.6403107 0.7484624 -0.172645 -0.6403059 0.7484656 -0.1726486 -0.43014 0.8958365 -0.1116088 -0.480944 0.8665076 -0.1336321 -0.553163 0.8214361 -0.1387569 -0.3248991 0.9429682 -0.07246714 -0.6295608 0.7057916 -0.3248252 -0.6303322 0.7059841 -0.3229053 -0.3253386 0.942773 -0.07303327 -0.3693436 0.9203693 -0.128475 -0.3118251 0.9454851 -0.09393119 -0.6326985 0.7159157 -0.2952244 -0.5900154 0.7542659 -0.2880363 -0.6303072 0.7059909 -0.3229389 -0.6617352 0.6724763 -0.3314848 -0.6675328 0.6493394 -0.3643602 -0.678416 0.6402772 -0.3602733 -0.6667953 0.6557186 -0.3541431 -0.6668103 0.6557115 -0.3541274 -0.6618958 0.714905 -0.2253994 -0.661899 0.7148944 -0.2254236 -0.6618973 0.7148979 -0.2254176 -0.6916473 0.6205083 -0.3695855 -0.6981388 0.6071177 -0.379487 -0.6946814 0.6094688 -0.3820543 -0.7094585 0.5865114 -0.3907338 -0.7074092 0.5641418 -0.4258128 -0.926814 0.04605633 0.3726856 -0.7402657 0.45331 0.4965046 -0.5215708 0.8411952 0.1426692 -0.1553592 0.9844838 0.08157736 -0.1494761 0.9886193 -0.0169906 -0.1500625 0.9885882 -0.01321721 -0.1520398 0.9883742 5.92815e-4 -0.1397648 0.988288 -0.06125837 -0.1787154 0.9830039 0.04200136 -0.1523023 0.9847437 0.0841673 -0.2189736 0.975287 0.02942419 -0.1452431 0.9853873 0.08897376 -0.263818 0.9645725 -2.02232e-4 -0.216033 0.9670358 0.1348015 -0.2353121 0.9663177 0.1042033 -0.3056451 0.9488015 0.07973015 -0.2892871 0.9445483 0.1553753 -0.3703142 0.928193 0.03640347 -0.2979457 0.940449 0.1636582 -0.4791691 0.8755178 0.06217372 -0.8056475 0.5876309 0.07497966 -0.7538731 0.6479555 0.1087616 -0.6872838 0.7147352 0.129594 -0.6314193 0.7627449 0.1397493 -0.6226173 0.7825263 5.22401e-4 -0.5777438 0.8126657 0.07606941 -0.8056688 0.5876039 0.0749638 -0.8048783 0.5873836 0.08456552 -0.870952 0.4778783 0.1143462 -0.9116077 0.3913567 0.125743 -0.9116125 0.3913481 0.1257355 -0.9116054 0.3913625 0.1257416 -0.9898954 0.1140336 0.08428317 -0.9915633 0.04300588 0.1222816 -0.9882969 0.1098268 0.1058651 -0.9779773 0.1751582 0.1134898 -0.9620642 0.2360184 0.1368496 -0.9342597 0.3214265 0.1544144 -0.9496106 0.3093438 -0.05045926 -0.9349445 0.3516751 0.04694145 -0.9773181 -0.1934947 0.08607596 -0.9604315 -0.2537243 0.1148708 -0.9834108 -0.1283326 0.1281948 -0.9875915 -0.09750193 0.1231116 -0.9926577 -0.05908983 0.1055422 -0.9906412 -0.01979207 0.1350485 -0.9906413 -0.01979094 0.1350485 -0.9585109 -0.2809839 0.04801082 -0.9585144 -0.2809722 0.0480076 -0.9585138 -0.2809776 0.04798805 -0.9572136 -0.2715947 0.09989148 -0.967986 -0.2332779 0.09265279 -0.9775687 -0.1971213 0.07417982 -0.9575895 -0.2841137 0.04797548 -0.9592046 -0.2788204 0.04675263 -0.9280581 0.007538437 0.372359 -0.9081366 -0.08145952 0.4106729 -0.9081422 -0.08144861 0.4106627 -0.9354494 -0.04921203 0.3500182 -0.943943 -0.04183727 0.3274464 -0.9591331 -0.04082983 0.279994 -0.8008307 -0.03453129 0.5978945 -0.8008513 -0.03446501 0.5978708 -0.8879549 0.01034092 0.4598141 -0.6946386 0.002042651 0.719356 -0.6914751 0.0108655 0.7223185 -0.6916612 0.001700878 0.72222 -0.6911019 0.002185165 0.722754 -0.6861115 0.00538069 0.7274765 -0.6968903 0.003379821 0.7171698 -0.6963592 0.007587671 0.7176533 -0.6928177 0.00827533 0.7210652 -0.6936169 0.01412981 0.7202055 -0.6936207 0.01411437 0.7202022 -0.6916621 0.01730364 0.722014 -0.6973371 0.02702015 0.7162339 -0.6973509 0.02698296 0.7162218 -0.6899263 0.0342577 0.7230687 -0.6939394 0.05151695 0.7181881 -0.7010852 0.08790296 0.7076389 -0.7325984 0.1261274 0.6688733 -0.732615 0.1261397 0.6688528 -0.654284 0.0878356 0.7511307 -0.6840499 0.06122457 0.7268614 -0.6939322 0.05153059 0.718194 -0.8160044 0.3616852 0.4509108 -0.7680167 0.2570735 0.5865694 -0.7319487 0.2167519 0.6459642 -0.7319222 0.2167351 0.646 -0.7402654 0.4533386 0.4964788 -0.7307221 0.4548279 0.5090941 -0.7308593 0.4547431 0.5089728 -0.6928734 0.5808188 0.4272891 -0.6909264 0.5790702 0.4327799 -0.6932113 0.5809948 0.4265012 -0.6930139 0.5808935 0.4269595 -0.6933003 0.5810238 0.4263169 -0.568809 0.6978149 0.4353281 -0.4561716 0.8729381 0.1728776 -0.4791684 0.8755181 0.06217443 -0.5113223 0.8109843 0.2843484 -0.5113207 0.8109906 0.2843333 -0.6613701 0.7204231 0.2087584 -0.6858968 0.5528232 0.4732147 -0.6858261 0.5524596 0.4737414 -0.987313 0.1236141 0.09966248 -0.9343472 0.07377415 0.348644 -0.8991543 0.1015258 0.4256926 -0.6932469 0.5810106 0.4264214 -0.7259355 0.5820079 0.3664487 -0.8450343 0.4523463 0.2851312 -0.8215687 0.4182056 0.3874648 -0.9193344 0.2383205 0.3130934 -0.8631068 0.2294467 0.4498898 -0.9064342 0.1949918 0.3746404 -0.6928974 0.01089662 0.7209538 -0.8012322 -0.03039562 0.597581 -0.8007199 0.02222055 0.5986267 -0.8053003 0.01623034 0.5926449 -0.799853 0.05858713 0.5973296 -0.8125974 0.04730367 0.5809026 -0.7988414 0.1033858 0.5925908 -0.8205316 0.09225714 0.5641068 -0.7940911 0.1621693 0.5857649 -0.8234732 0.1565725 0.5453228 -0.780056 0.2375538 0.5788615 -0.7928037 0.2385819 0.5608395 -0.7273491 0.03884065 0.6851677 -0.4911043 0.870222 0.03911852 -0.3240453 0.9450638 -0.04299908 -0.324045 0.9450641 -0.04299962 -0.3806939 0.922889 -0.05786293 -0.3237369 0.9448882 -0.04879206 -0.3883584 0.9111187 -0.137987 -0.1068515 0.9839392 0.1429914 -0.3751568 0.9268715 -0.01291406 -0.3751543 0.9268722 -0.01292586 -0.3751564 0.9268716 -0.01291489 -0.407746 0.8445721 0.3470466 -0.4063087 0.8593216 0.310612 -0.491097 0.8702263 0.0391156 0 0 1 -0.08843481 0.00692135 0.9960579 -0.09917128 0 0.9950703 -0.08854031 0.006808698 0.9960494 -0.08958989 0.005293071 0.9959647 -0.08970195 0.005401372 0.995954 -0.05888646 -0.007258951 0.9982383 -0.01005774 0.04432642 0.9989665 -0.04270052 0.009614408 0.9990417 -0.002963006 0.02047377 0.999786 0.06830948 0.01881128 0.9974867 0.03180599 0.03530901 0.9988703 0.03225541 0.03551048 0.9988486 0.04428642 0.04265326 0.9981079 0.03824782 0.0386846 0.9985192 0.03252977 0.03349572 0.9989093 0.01003193 0.01114666 0.9998876 0.2606445 0.95449 0.1449599 0.2316135 0.8961049 0.3786175 0.2327209 0.9614902 0.1462112 0.2730731 0.8843142 0.3787075 0.2327178 0.9615265 0.1459764 0.211633 0.896688 0.3887955 0.2110411 0.8985531 0.3847909 0.2406234 0.9705494 0.01159077 0.2406173 0.9705506 0.01161229 0.2232615 0.9673092 0.1202792 0.6640368 0.7432204 0.08172291 0.6640343 0.7432224 0.08172428 -0.2092199 0.8989093 0.3849534 -0.2420759 0.9701882 0.01158094 -0.2420728 0.9701889 0.01159203 -0.6653521 0.7424786 0.07766616 -0.5625022 0.8161995 0.1319463 -0.6628488 0.7396834 0.1161887 -0.2247843 0.9669437 0.1203821 -0.2617756 0.9541862 0.1449214 -0.2295065 0.8989335 0.3731556 -0.2374762 0.960352 0.1460442 -0.2374801 0.9603867 0.1458101 -0.6918018 0.6803849 0.24184 -0.8279047 0.480789 0.2888181 -0.1170513 0.9878459 0.1022716 -0.1056953 0.5794231 0.8081445 -0.1054295 0.577256 0.8097285 -0.1694002 0.9850262 0.03204292 -0.1053628 0.5765848 0.8102152 -0.12711 0.9916795 0.02036547 -0.1271581 0.9916808 0.02000111 -0.1481871 0.9875774 0.05226308 -0.1483168 0.9875804 0.05183804 -0.1476058 0.9876765 0.05203431 -0.1430247 0.9875479 0.06552076 -0.1396827 0.9879824 0.06617641 -0.1193094 0.987806 0.1000232 -0.1207623 0.9870561 0.1055299 -0.1302437 0.9880716 0.08216494 -0.1317677 0.9880477 0.079993 -0.1336218 0.9874408 0.08429592 -0.1396816 0.9879825 0.06617844 -0.09396243 0.9883058 0.1200942 -0.0894373 0.9874759 0.1299701 -0.06636154 0.9879163 0.1400622 -0.06561547 0.9881911 0.1384657 -0.0114293 0.9996436 0.02412295 -0.1329164 0.9848746 0.1111541 -0.06596356 0.9838787 0.1662274 -0.182308 0.8981075 0.4002084 -0.1183416 0.9108901 0.3953157 -0.1175691 0.9120174 0.3929401 -0.1130121 0.911431 0.3956283 -0.06832778 0.9879453 0.1389077 -0.1903675 0.9022104 0.3870097 -0.182279 0.8981081 0.4002202 -0.2787564 0.8847517 0.3735092 -0.2787939 0.8847523 0.3734799 -0.2556641 0.892525 0.3715305 -0.2747436 0.8917397 0.3596056 -0.2729474 0.8918378 0.3607286 -0.104692 0.9874734 0.1180499 -0.3066204 0.8868178 0.345743 -0.3430592 0.88827 0.3054292 -0.4768363 0.7029587 0.5277085 -0.4360007 0.8222318 0.3658391 -0.5293561 0.7408705 0.4133921 -0.5293721 0.7408608 0.413389 -0.5294109 0.7408626 0.4133363 -0.5628542 0.7525504 0.3418526 -0.6050927 0.7161759 0.3477858 -0.6654842 0.6812743 0.3049524 -0.6546699 0.7076182 0.2658644 -0.6546711 0.7076181 0.2658616 -0.7379415 0.5820907 0.3414863 -0.8201667 0.4978528 0.2819026 -0.86847 0.4483252 0.211576 -0.776691 0.6144605 0.1385258 -0.7766911 0.6144604 0.1385258 -0.9035294 0.3983007 0.1580861 -0.9035312 0.3982968 0.1580856 -0.9455716 0.2672076 0.1857267 -0.8781545 0.4450253 0.1754907 -0.8813457 0.4532062 0.1335439 -0.8684746 0.4483254 0.2115565 -0.8279081 0.4807892 0.2888078 -0.81862 0.4979371 0.2862165 -0.6918233 0.6803475 0.2418842 -0.6650022 0.6801525 0.3084875 -0.678678 0.6761703 0.2866879 -0.6020216 0.7924989 0.09754741 -0.6020131 0.7925057 0.09754496 -0.713942 0.6806938 0.1641427 -0.7766927 0.6144579 0.1385276 -0.776701 0.6144481 0.1385247 -0.362028 0.9290356 0.07634544 -0.1566069 0.9872062 0.02996677 -0.1839975 0.9817957 0.04714095 -0.4785595 0.8700347 0.118408 -0.4785519 0.8700389 0.1184077 -0.5971195 0.7920759 0.126744 -0.8372954 0.5003579 0.2204053 -0.7086594 0.6804435 0.1865438 -0.7086477 0.6804611 0.1865238 -0.34656 0.9335821 0.09121835 -0.6020098 0.7925081 0.0975452 -0.3620312 0.9290342 0.07634657 -0.4493213 0.8856588 0.1171274 -0.438358 0.8856461 0.1532101 -0.4383829 0.8856269 0.1532498 -0.4222972 0.8855728 0.1934577 -0.4223346 0.885539 0.1935312 -0.3972887 0.8854331 0.2411844 -0.3973434 0.8853693 0.2413287 -0.356586 0.8851433 0.2989444 -0.3566585 0.8850058 0.2992647 -0.3113285 0.8856178 0.3446093 -0.4768469 0.7029593 0.527698 1 -8.49903e-7 0 0.9999993 0.001194298 -9.25754e-5 1 0 0 0.9999989 -0.001522839 1.70465e-4 1 -9.60359e-5 3.94274e-4 0.9999909 0.004086971 0.001161515 -1 1.3284e-5 -1.31188e-6 -1 -3.65496e-6 0 -1 0 0 -1 1.79338e-6 -2.00748e-7 -1 3.48839e-6 0 -1 2.81072e-5 4.52579e-6 0.141253 0.9879691 0.0629667 0.8902228 0.2248186 0.3961818 0.8861503 0.4379092 0.15157 0.8691474 0.4743229 0.1400023 0.87721 0.4597553 0.1383033 0.8685438 0.4755455 0.1396009 0.8826204 0.4594839 0.09927594 0.8542657 0.4684779 0.2252966 0.9194185 0.2266367 0.3214116 0.7926186 0.5378206 0.2872362 0.8542679 0.4684778 0.2252886 0.7132921 0.664273 0.2235078 0.6565715 0.6916384 0.3009154 0.5814266 0.7351923 0.3484758 0.581401 0.735194 0.348515 0.5837762 0.7304001 0.3545718 0.6530029 0.7009906 0.2867043 0.6529994 0.7009909 0.2867118 0.4205766 0.756954 0.5001359 0.4206166 0.7569566 0.5000984 0.4593527 0.8002717 0.3854354 0.4967215 0.7649756 0.4099758 0.4967192 0.7649769 0.4099761 0.2488657 0.8906995 0.3804209 0.2481443 0.8907111 0.3808647 0.2544059 0.8935792 0.3698566 0.2481368 0.8907136 0.3808641 0.1870253 0.9058892 0.3799818 0.1522962 0.8980058 0.4127851 0.1232377 0.8972167 0.4240458 0.1471213 0.9085676 0.3909735 0.007675945 0.9997757 0.01974368 0.1186779 0.9857193 0.1194689 0.0688945 0.9849374 0.1585935 0.1130853 0.9126588 0.3927669 0.1193152 0.9878048 0.1000282 0.1258858 0.9869318 0.1005901 0.1022875 0.9880101 0.1156429 0.1024608 0.9880121 0.115472 0.1021844 0.9880372 0.1155026 0.08976894 0.9873751 0.1305066 0.07685965 0.9882358 0.1322214 0.06772965 0.9881685 0.1376072 0.08121347 0.9868556 0.1397157 0.05619144 0.987895 0.144589 0.1406598 0.9879583 0.06444543 0.1434186 0.9875949 0.06393182 0.1331769 0.9879326 0.07907718 0.13247 0.9879193 0.08041995 0.1351211 0.9875748 0.08023858 0.121424 0.9878449 0.09704947 0.2142108 0.9764029 0.0274074 0.2142191 0.976401 0.02740931 0.214213 0.9764024 0.02740842 0.1531531 0.9869977 0.04878294 0.145691 0.9880192 0.05091333 0.1469426 0.9880371 0.04680454 0.1733391 0.9845795 0.02359855 0.2116827 0.9763699 0.04350149 0.8886085 0.4375786 0.1374768 0.8787152 0.4598077 0.1282045 0.8787183 0.4598017 0.1282051 0.6729781 0.7201945 0.1685835 0.6729683 0.720203 0.1685861 0.7195357 0.6805222 0.138412 0.6917964 0.6803909 0.2418391 0.6918402 0.6803537 0.2418181 0.6689779 0.6803978 0.2992113 0.7132866 0.6642763 0.2235158 0.55592 0.8245447 0.1052576 0.5558621 0.824585 0.1052466 0.555867 0.8245816 0.1052474 0.8539761 0.4692576 0.2247712 0.708645 0.6804651 0.1865192 0.7086634 0.680449 0.1865084 0.3947093 0.9129148 0.1038809 0.5524703 0.8241217 0.1248999 0.4580638 0.8813189 0.1159937 0.4580445 0.8813291 0.1159922 0.4580802 0.8813105 0.1159934 0.3296959 0.8822124 0.3361577 0.3296426 0.8822154 0.336202 0.3135635 0.8813621 0.3533819 0.2988403 0.8851582 0.3566361 0.3567967 0.8849986 0.2991213 0.3564659 0.8851376 0.2991046 0.3973944 0.8853677 0.2412504 0.397232 0.8854355 0.2412692 0.422339 0.8855435 0.193501 0.4222499 0.8855811 0.1935227 0.4383823 0.8856362 0.1531976 0.43834 0.8856546 0.1532124 0.4495698 0.8856514 0.1162267 0.4581339 0.8812826 0.1159924 0 1 0 0 1 0 0 1 0 -4.59273e-5 1 -1.08061e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 2.64808e-7 1 1.83252e-6 2.98359e-6 1 1.60896e-6 2.98381e-6 1 1.60892e-6 0 1 0 0 1 0 0 1 0 0 1 0 3.98841e-6 1 1.45225e-6 5.42072e-6 1 1.12084e-6 5.42154e-6 1 1.12065e-6 7.60284e-6 1 4.45796e-7 7.60295e-6 1 4.45761e-7 1.12398e-5 1 -9.75968e-7 1.12398e-5 1 -9.7598e-7 1.81979e-5 1 -4.29657e-6 6.81532e-5 1 -3.12871e-5 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -6.85944e-6 1 -1.68021e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 5.01159e-6 1 0 5.19809e-6 1 0 2.00089e-7 1 2.26167e-7 2.00051e-7 1 2.26171e-7 -4.60322e-6 1 8.21233e-7 0 1 0 5.17663e-5 1 -2.34595e-5 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 4.55338e-6 1 7.61729e-7 -2.52023e-7 1 2.20201e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 9.77751e-6 1 -2.45467e-6 9.46033e-6 1 -2.35444e-6 4.22264e-6 1 -6.00459e-7 1.49422e-6 1 4.75943e-7 -6.88827e-6 1 4.12138e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 4.2477e-6 1 2.48176e-6 -2.36259e-6 1 0 0 1 0 -3.39638e-6 1 0 1.3535e-5 1 7.02188e-6 -2.13398e-6 1 7.52618e-7 -1.37352e-5 1 -3.83982e-6 0.7903282 0.6126831 -9.10838e-4 -0.9225073 0.3859796 -4.90572e-5 -0.9906593 0.1363496 0.001734256 -0.9241735 0.38197 -0.001548111 -0.9992884 0.0377162 5.77217e-4 -0.9953033 0.0968067 0 -0.6457359 0.7205868 0.2525468 0.6516579 0.7293702 0.2082328 0.7778294 0.6284748 -9.15748e-4 0.9774515 0.2109869 0.008560478 0.7903565 0.6126448 -0.001771986 0.9758117 0.2186124 3.64425e-4 0.9758118 0.2186118 3.64425e-4 0.9804687 0.196675 0 0.4527705 0.8916249 -0.001942515 0.6662601 0.7457088 0.003979682 0.02994149 0.9995447 -0.003741204 0.2406333 0.9706152 -0.001381933 0.03001773 0.9995484 -0.001349806 0.2406385 0.9706102 0.002990663 -0.3836349 0.9234811 -0.002674281 -0.9241507 0.3820281 -4.90962e-5 -0.7106673 0.703513 -0.00465095 -0.8233567 0.567524 -5.36386e-4 -0.7105014 0.7036955 -5.59593e-4 -0.6673676 0.7447277 -9.67348e-4 -0.3835212 0.9235318 7.60567e-4 -0.2420889 0.9702536 -9.60693e-4 -0.242092 0.9702528 -9.60692e-4 0.1219917 0.9904395 0.06440299 0.3750455 0.9266784 0.02466064 0.06295323 0.9980127 0.002742648 0.3746024 0.9255379 -0.05525064 0.0616303 0.9972739 0.04057741 0.1248452 0.9921613 0.005438983 0.1281713 0.9917519 7.03012e-4 0.08134824 0.9966055 0.01264828 0.08134824 0.9966055 0.01264846 0.1154779 0.9923328 0.04405158 0.06768125 0.9974155 0.0241149 0.03881645 0.9986549 0.03437423 0.04457092 0.99888 0.01587998 0.01930928 0.999675 0.01664024 0.01711672 0.9997928 0.0110228 0.01711571 0.9997926 0.01102471 0.07521879 0.996487 0.03682231 0.1015077 0.9909904 0.08737337 0.3055102 0.9191429 0.2486762 0.3531081 0.9098879 0.2177584 0.3350705 0.9040718 0.2652961 0.4363223 0.8888876 0.1396486 0.3550379 0.9093309 0.2169455 0.3550039 0.9093293 0.2170081 0.5493249 0.8350278 0.03115916 0.4995013 0.8510735 0.1617791 0.5096609 0.8577269 0.06745529 0.427363 0.886373 0.178056 0.4273643 0.8863731 0.1780518 0.7029547 0.7078455 0.06935018 0.7029547 0.7078455 0.06935 0.6571236 0.7537372 -0.008284032 0.578394 0.807308 0.1171073 0.5783942 0.8073081 0.1171067 0.5958892 0.8025847 0.02781826 0.7772274 0.6281541 -0.03660684 0.7441495 0.6676988 -0.02048933 0.7775062 0.6283885 0.02473956 0.8583941 0.5129908 -2.75252e-4 0.3745829 0.9255461 -0.05524444 0.2506272 0.9680625 0.00640279 0.2521075 0.9664142 -0.04985409 0.1325672 0.9886932 0.07008367 0.1153867 0.993308 0.005023837 0.1182852 0.9928093 0.0183922 0.3389575 0.9170487 0.21007 0.1289827 0.9848803 0.1156474 0.1355711 0.9853345 0.1036164 0.2116001 0.9759302 0.05277919 0.192426 0.9748368 0.1125418 0.2879644 0.9575031 0.01626163 0.2707303 0.9565626 0.1081353 0.3628628 0.9317889 -0.01001125 0.3505923 0.9310817 0.1008555 0.4975287 0.8665024 -0.04048198 0.4952419 0.8675792 0.04518556 0.5954839 0.802042 -0.04612833 -0.6102602 0.7912517 0.03877198 -0.6102541 0.7912562 0.03877687 -0.6032238 0.790768 0.1039565 -0.603227 0.790766 0.1039531 -0.7874236 0.6162823 0.01265901 -0.6102615 0.791251 0.03876495 -0.6567676 0.5656538 0.4986906 -0.6745426 0.7138134 -0.1883153 -0.6102579 0.7912534 0.03877234 -0.8850587 0.3961733 0.2443718 -0.9581664 0.2670797 0.1028857 -0.6567881 0.5656151 0.4987074 -0.8294523 0.5580506 0.02425915 -0.7876562 0.613288 0.05895578 -0.7859787 0.6151507 0.06186383 -0.7872567 0.6134342 0.06265276 -0.8607138 0.5046589 0.06701493 -0.9138824 0.397621 0.0819537 -0.8963928 0.4306825 0.1048453 -0.8963969 0.4306737 0.1048463 -0.9689344 0.2412917 0.0542643 -0.9724073 0.2226961 0.06950181 -0.9738562 0.2256513 0.0261811 -0.9738566 0.2256498 0.0261771 -0.9536191 0.2759636 0.1202272 -0.9411343 0.3244273 -0.09493798 -0.9411342 0.324427 -0.09493923 -0.9252482 0.3727653 0.07044059 -0.9771171 0.1981051 -0.07743835 -0.978897 0.186886 0.0826705 -0.9978696 0.04082369 0.05088818 -0.9010943 -0.4336195 -0.001791715 -0.8716689 0.490095 1.56838e-6 -0.881893 0.4714492 5.92341e-4 -0.8922759 0.4514865 0.001923561 -0.8922743 0.4514896 0.001923203 -0.9023434 0.4309953 0.004408538 -0.9119299 0.4102621 0.008293807 -0.9201558 0.391299 0.0140866 -0.9988921 -0.04632091 0.008310377 -0.9584423 0.2813555 0.04719328 -0.9761645 0.2169289 0.006688475 -0.9761652 0.2169262 0.00668776 -0.9902861 0.1390082 -0.003192007 -0.9954461 0.09505856 0.007140636 -0.9977318 0.06564849 0.01489001 -0.9995952 0.01932865 -0.02087575 -0.9995951 0.01933473 -0.02087658 -0.9721797 0.2338129 0.0140683 -0.9721806 0.23381 0.01406812 -0.955618 0.2942733 0.0140556 -0.9696516 0.2444831 -0.001884102 -0.908796 0.4172377 0.001644551 -0.9010976 -0.4336127 -0.001791715 -0.9300736 -0.3673639 -0.00263977 -0.9603158 -0.2784838 -0.01550769 -0.9980598 -0.06185227 0.007141649 -0.9899086 -0.1416588 0.003702938 -0.9899094 -0.1416531 0.003702938 -0.9603161 -0.2784824 -0.01550805 -0.9603153 -0.2784854 -0.01550704 -0.8969655 -0.4352001 0.07780516 -0.9762626 -0.2149266 0.0267927 -0.9566334 -0.2864022 0.05316394 -0.9931782 -0.1160656 -0.01121747 -0.9531828 -0.3020368 0.01470762 -0.9286785 -0.3682216 0.04437345 -0.8803346 -0.4743137 0.006125867 -0.8803359 -0.4743112 0.006126165 -0.8483857 -0.5293696 -0.003097355 -0.8483858 -0.5293695 -0.003097355 -0.5345694 -0.8447855 0.02394288 -0.6102534 -0.7921966 0.003907859 -0.8279713 -0.5607692 0.00118196 -0.7618421 -0.647757 -0.002735316 -0.7296504 -0.6838167 0.002264916 -0.7632103 -0.6461501 2.8021e-4 -0.7292267 -0.6842631 0.003540098 -0.6909211 -0.7229239 0.003017604 -0.6909356 -0.7229101 0.003017663 -0.4285276 -0.9035218 -0.003517031 -0.4249646 -0.9052001 -0.004207313 -0.4283534 -0.9036032 -0.00380975 -0.4251182 -0.9051274 -0.004355847 -0.5322518 -0.846583 0.002324342 -0.5322574 -0.8465794 0.002323865 -0.6279339 -0.7782022 -0.01001489 -0.7434027 -0.6675456 -0.04165685 -0.4285299 -0.9035208 -0.003517031 -0.325967 -0.9453561 0.006881117 -0.2411885 -0.970171 0.02441895 -0.1608286 -0.986795 0.01922839 -0.5074437 -0.8476669 -0.1547961 -0.2285292 -0.9735371 -1.55071e-4 -0.3288716 -0.9441945 -0.01844453 -0.5028449 -0.8603146 -0.08370018 -0.8499507 -0.5109149 -0.1286461 -0.9143232 -0.3270503 -0.2388541 -0.853605 -0.2034957 -0.479529 -0.8787289 -0.2962363 -0.3742724 -0.8499395 -0.5109314 -0.1286545 -0.7552261 -0.5730919 -0.318118 -0.8499422 -0.5109174 -0.1286927 -0.8287921 -0.4435729 -0.3410964 -0.7646903 -0.5884764 -0.2625723 -0.7589678 -0.5944043 -0.2658033 -0.7649133 -0.5632992 -0.3124127 -0.7538972 -0.6521428 -0.07967966 -0.7353484 -0.6575375 -0.1640338 -0.7459446 -0.62655 -0.2258359 -0.7538944 -0.6521449 -0.07968735 -0.9983024 -0.05817896 0.002745151 -0.9190467 -0.3787078 -0.1092409 -0.9738183 -0.1939232 -0.1186248 -0.9198201 -0.3745254 -0.1168836 -0.8850098 -0.4565422 -0.09125113 -0.8790615 -0.443437 -0.1749694 -0.8255812 -0.5217199 -0.2149975 -0.8061049 -0.5791513 0.1215679 -0.7792438 -0.5916945 -0.2065834 0.9896205 0.1436631 0.003481507 -0.8263633 0.5631353 0.001517415 -0.9766032 0.214967 -0.00594139 0.005177438 0.9999753 -0.004756152 0.004481554 0.9999787 -0.004756212 0.1215026 0.9925221 -0.01169782 0.2799274 0.9594348 0.03354752 0.06862688 0.9974406 -0.0200631 0.1419298 0.9898763 -8.44714e-4 0.06051868 0.9981669 6.04344e-4 0.0051741 0.9999758 -0.004640221 0.1574569 0.9875109 -0.00543344 0.1574581 0.9875108 -0.005433261 0.1822414 0.98325 -0.002706229 0.1666662 0.9859018 0.01483511 0.1666648 0.9859021 0.01483547 0.1250624 0.9917663 0.02755224 0.1250553 0.991767 0.0275557 0.1617756 0.9867896 0.008666336 -0.005899488 0.9995689 0.0287621 -0.05413228 0.9984184 0.01517158 -0.00519061 0.9999731 0.005193471 0.05078029 0.9987088 -0.001475095 -0.2092843 0.9772999 0.03294044 -0.0681867 0.9974928 0.01893836 -0.06817901 0.9974933 0.01893836 -0.05413001 0.9983627 0.0184912 -0.06666553 0.9976618 0.01505351 -0.2673459 0.9628925 -0.03693383 -0.1674956 0.9838164 0.06364244 -0.2092862 0.9772995 0.03293913 -0.2363005 0.9715837 -0.01368695 -0.1919311 0.9809412 -0.03027999 0.004481375 0.9999785 -0.00479114 -0.1379901 0.9903917 0.009114682 -0.0515567 0.9986696 -9.11709e-4 -0.0515446 0.9986702 -9.11707e-4 -0.1919319 0.980941 -0.03027963 -0.1444196 0.9881353 -0.05226355 -0.408087 0.9066597 0.1069254 -0.1330163 0.9903979 -0.03766697 -0.2715586 0.9617745 0.03529489 -0.1373926 0.9905149 -0.001851856 -0.08115768 -0.9966831 0.005999743 -0.011357 -0.9999356 0 0.02707958 -0.9996333 0 0.02931231 -0.9995703 -4.60211e-4 0.1617814 -0.986825 0.001792192 0.105725 -0.9937464 0.03591978 0.1057327 -0.9937457 0.03591603 0.1520013 -0.9882063 0.01854389 0.1520001 -0.9882066 0.01854419 0.1887313 -0.9819725 0.01050823 0.181836 -0.9833227 -0.003504097 0.153559 -0.9881159 -0.006827056 0.1535549 -0.9881165 -0.006827652 0.1146262 -0.9933075 -0.01418238 0.1146154 -0.9933087 -0.01418554 0.3381814 -0.9394814 0.05484551 0.05910617 -0.9979611 -0.02408391 0.1057569 -0.9943805 -0.004778385 -0.07124423 -0.9974501 0.004169523 0.01135772 -0.9999356 -6.39926e-6 -0.07075965 -0.9974934 -3.97074e-6 -0.2044638 -0.9788613 0.005008101 -0.2044651 -0.978861 0.005008399 -0.03060162 -0.9995094 -0.006680428 -0.08740639 -0.9961617 -0.00470823 -0.07062149 -0.9974921 -0.004709064 -0.08610361 -0.9962831 -0.002510786 -0.08610951 -0.9962825 -0.002510011 -0.3364363 -0.9404799 0.04804474 -0.1744555 -0.9839712 -0.03695821 -0.1744619 -0.9839702 -0.03695559 -0.287773 -0.9576618 -0.008401274 -0.2410463 -0.9704042 0.01457768 -0.2029824 -0.9784818 0.0370348 -0.2029822 -0.9784818 0.03703498 -0.1590629 -0.9847217 0.07086664 -0.2673061 -0.9627493 -0.04075866 -0.1067019 -0.9942823 0.004172503 -0.08115273 -0.9966335 0.0116533 -0.05493289 -0.9984276 0.01117318 -0.05492454 -0.9984279 0.01117318 -0.9757682 0.1752094 0.1310656 -0.9451048 0.3267663 8.42824e-4 -0.9741328 0.225955 0.003103673 -0.9741326 0.2259557 0.003103613 -0.9741206 0.2260077 0.003099024 -0.9871438 0.1437105 0.06995922 -0.9957004 0.09075856 0.01854193 -0.9927079 0.1197437 0.01387828 -0.9872476 0.1589382 0.008994638 -0.9451053 0.3267649 8.42825e-4 -0.9766178 0.214968 -0.002572774 -0.9449226 0.3272906 -0.001454353 -0.7960923 0.6051735 0.001524865 -0.8259606 0.5637272 -8.52862e-4 -0.9075752 0.4198892 -5.83518e-4 -0.8303059 0.5566752 0.0265513 -0.8966423 0.4427227 0.005390167 -0.6473832 0.7621586 0.003061413 -0.6355988 0.7720037 0.004941284 -0.7960715 0.6051577 -0.007380604 -0.7364807 0.676379 0.01037114 -0.7364805 0.6763793 0.01037114 -0.2453628 0.9693511 0.01247084 -0.2737065 0.9618123 -0.001443326 -0.2675267 0.9635494 -0.001441717 -0.3944908 0.9188975 -0.002103805 -0.4684082 0.8835118 8.02692e-4 -0.3967781 0.9178104 0.01383119 -0.6472827 0.7620403 -0.017883 -0.5252698 0.8508891 0.008909404 -0.6352412 0.7723078 0.003060221 0.5611496 0.8276344 -0.01150524 0.4092758 0.9124107 -3.15748e-4 0.3701332 0.9289647 0.005093693 0.2762339 0.9610877 -0.002318024 0.1617829 0.9868223 0.002834141 0.2434452 0.9699106 0.002815842 0.2052333 0.9786814 0.007865965 0.7259552 0.6876614 -0.01053446 0.5310664 0.8472977 0.007415175 0.5611865 0.827688 0.001538813 0.5300263 0.8479798 0.001535296 0.4101222 0.9120149 0.005347669 0.8336495 0.5522533 0.006695568 0.7494446 0.6613532 0.0307371 0.8567707 0.5155017 -0.01420885 0.7440933 0.6680754 6.27406e-4 0.7259926 0.6876966 0.002851724 0.7445166 0.6675979 0.002849459 0.6426413 0.7661066 0.009635984 0.9896212 0.1436586 0.003481507 0.9773894 0.2113948 0.004724323 0.9773901 0.211391 0.004724204 0.9773896 0.2113933 0.004724323 0.953024 0.3026536 0.01208621 0.9939999 0.1081038 -0.01666426 0.9524173 0.3047901 0.00206536 0.9476462 0.3192992 0.003853738 0.9040786 0.4273611 -0.002104222 0.8568587 0.5155507 -8.69249e-4 0.9042317 0.4270412 -8.8626e-4 0.8336498 0.5522528 0.006695568 0.9899346 -0.1307791 0.05409544 0.9890701 0.1343113 0.06083375 0.9980576 0.06191319 0.006919801 0.9964326 -0.0842337 0.00519222 0.9988709 -0.04682922 0.007993578 0.9941364 -0.1081191 0.001799166 0.9994801 -0.03224223 0 0.994138 0.1081193 0 0.999257 0.03742641 0.009215176 0.9992568 0.0374301 0.009214758 0.9967569 0.0802825 0.005522787 0.9954554 0.09510523 0.004860341 0.989621 0.1436597 0.003481566 0.9682232 -0.2500209 0.005785822 0.9789522 -0.1704391 0.1122631 0.9934386 -0.1143023 0.003870189 0.9884807 -0.1513066 0.003503799 0.9858124 -0.167814 0.003500521 0.9327824 -0.1990365 0.3005021 0.7259944 -0.6876984 -0.001775741 0.7444301 -0.6676881 -0.004043042 0.856706 -0.5154629 -0.0187866 0.7498593 -0.6610873 0.02597028 0.8834555 -0.4685015 -0.003560602 0.8834557 -0.4685013 -0.003560662 0.8568536 -0.5155476 -0.003551304 0.8833618 -0.4686727 -0.004217088 0.9476464 -0.3192993 0.003764152 0.9403755 -0.3400784 0.006387591 0.994013 -0.1081053 -0.01586109 0.941263 -0.3371855 0.01816463 0.9682234 -0.2500196 0.005785763 0.5611858 -0.827687 -0.002177357 0.5552544 -0.8316799 -0.001008987 0.7258928 -0.6876023 -0.01681673 0.5592469 -0.8287227 0.02148598 0.7448704 -0.6672068 -0.001780211 0.2312526 -0.9728837 0.004433155 0.246909 -0.9690358 0.002355337 0.161783 -0.9868234 0.002384543 0.3701286 -0.9289534 -0.007119536 0.3321271 -0.9432301 0.002944707 0.5611357 -0.8276137 -0.01349776 0.333159 -0.9428032 0.01127916 0.555039 -0.8318215 -0.002177596 -0.453509 -0.8912363 0.005241453 -0.6470357 -0.7617495 -0.03290021 -0.455971 -0.8897454 0.02106094 -0.2166554 -0.9760447 -0.01992994 -0.2721413 -0.9622569 -0.001004278 -0.3306843 -0.943741 -0.001008391 -0.2675259 -0.9635463 -0.002904176 -0.4684072 -0.8835098 0.002282381 -0.7773917 -0.6290013 0.00442487 -0.7773928 -0.629 0.004424691 -0.6864482 -0.726846 0.02199262 -0.7959463 -0.6050625 -0.01921218 -0.5753245 -0.8177849 0.01515561 -0.647381 -0.7621559 0.004038393 -0.5733114 -0.8193277 0.004013121 -0.5733114 -0.8193278 0.004013121 -0.9075669 -0.4198853 0.0043208 -0.8594738 -0.5111752 -0.002178072 -0.796091 -0.6051725 -0.002343297 -0.8602879 -0.5097994 0.003075718 -0.8602875 -0.5097999 0.003075718 -0.9980764 0.06199288 6.60671e-4 -0.9996755 0.02533119 0.002718627 -0.9999901 0 0.004466712 -0.9995247 0.0304048 0.00510323 -0.9996988 -0.02400761 0.005104124 -0.9644297 -0.1884554 0.1853644 -0.994881 -0.09471029 0.03524076 -0.995101 -0.09335291 0.03254306 -0.9951009 -0.09335362 0.03255051 -0.9953532 -0.09528058 0.01390928 -0.9953534 -0.09527862 0.01391172 -0.991943 -0.1265285 -0.006290495 -0.9854341 -0.1700578 -1.47048e-5 -0.9813602 -0.1910048 0.02119988 -0.9579545 -0.2524992 0.136262 -0.9968026 -0.07966512 0.006169557 -0.980822 -0.1940751 0.01798045 -0.9998564 0 -0.01694142 -0.9603745 -0.2785164 0.01046246 -0.9766201 -0.2149707 8.73085e-4 -0.959909 -0.2803105 8.66471e-4 -0.9766203 -0.2149685 -0.001138091 -0.9598061 -0.2806636 -4.66981e-4 -0.9211043 -0.3893151 6.80673e-4 0.7644961 -0.5884177 -0.2632688 0.8528004 -0.2024366 -0.4814051 0.9140667 -0.3275099 -0.2392056 0.8789948 -0.4723049 -0.06554651 0.8918977 -0.4280428 -0.145938 0.8900883 -0.4338608 -0.1396701 0.9650806 -0.2201285 -0.1419959 0.9410465 -0.3086681 -0.1384041 0.7623844 -0.623649 -0.1727193 0.7614734 -0.5915599 -0.2649813 0.7456499 -0.6409118 -0.1823131 0.7594032 -0.5153839 -0.3970971 0.8731695 -0.4684074 -0.1347946 0.8731554 -0.4684302 -0.1348064 0.8293666 -0.4729911 -0.2973726 0.8253875 -0.2728505 -0.4942548 0.821297 -0.4646972 -0.3309499 0.72843 -0.6576995 -0.191888 0.7284184 -0.6577048 -0.1919144 0.7513868 -0.6490609 -0.1189035 0.799027 -0.5756111 -0.1738615 0.818448 -0.551552 -0.1610382 0.7792099 -0.6221293 -0.0760734 0.8908273 -0.4299413 -0.1468923 -0.6858182 -0.72342 0.07947874 -0.8385345 -0.5426982 0.04835808 -0.8373303 -0.5351968 0.1115455 -0.8332368 -0.5228099 0.1799618 -0.8174238 -0.574299 0.04471009 -0.788749 -0.5919874 0.1656073 -0.802725 -0.5955153 0.03153133 -0.7338886 -0.6514153 0.1925247 -0.6948704 -0.6649069 0.27396 -0.9209647 -0.3894184 0.01332014 -0.9187698 -0.3935132 0.03177297 -0.913437 -0.4069124 0.007427513 -0.8951317 -0.4433193 0.04698175 -0.895129 -0.4433235 0.04699188 -0.8981916 -0.4395945 0.002917826 -0.866242 -0.494666 0.07021671 -0.855497 -0.5047354 0.1156163 -0.6840354 -0.7256449 0.07439696 -0.6840302 -0.7256488 0.07440787 -0.683991 -0.7256116 0.07512706 -0.5303429 -0.8340559 0.1519446 -0.4456354 -0.8507711 0.2785632 -0.4527837 -0.8487632 0.2731082 -0.4611701 -0.8463125 0.2666029 -0.5171912 -0.8285524 0.2145091 -0.5172086 -0.8285462 0.2144915 -0.5303082 -0.8340318 0.152197 -0.5303514 -0.8340486 0.1519558 -0.4329215 -0.8509266 0.2974946 -0.4329283 -0.8509199 0.2975038 -0.4094621 -0.8602445 0.3038423 -0.4118769 -0.855753 0.31312 -0.4117634 -0.8558615 0.3129727 -0.3985821 -0.8674327 0.2978134 -0.4191393 -0.8493577 0.320802 -0.3453758 -0.9063335 0.2434653 -0.4108807 -0.8561431 0.3133624 -0.3936286 -0.8679156 0.3029505 -0.5972008 -0.7780253 0.1950073 -0.4603343 -0.8450679 0.2719421 -0.4333147 -0.8468251 0.3084243 -0.5961555 -0.772116 0.2200807 -0.7197355 -0.6761048 0.157681 -0.7907723 -0.6113792 0.02991348 -0.5961477 -0.7721205 0.2200862 -0.507221 -0.8070565 0.302302 -0.4785822 -0.8101503 0.3385492 -0.4852261 -0.823241 0.2946691 -0.4852691 -0.82328 0.2944893 -0.4461992 -0.8098424 0.3808695 -0.4838945 -0.8225257 0.2988268 -0.4849994 -0.823053 0.2955659 -0.4851141 -0.8231377 0.2951418 -0.4874511 -0.8259018 0.283333 -0.4874505 -0.8259026 0.2833316 -0.9955044 -0.01547366 -0.09344381 -0.9986612 0.04432094 0.02667522 -0.9760511 0.1844443 0.1153458 -0.9972616 0.07324719 0.01021373 -0.9955037 -0.01546716 -0.09345042 -0.995506 -0.01546782 -0.09342682 -0.9978486 -0.006865024 -0.06520104 -0.9981776 0.02170932 -0.05630451 -0.9985935 0.02335798 -0.0475986 -0.9985685 0.02373069 -0.04793632 -0.9989295 0.02016109 -0.04163306 -0.998916 0.0140472 -0.04437768 -0.9987381 0.01499104 -0.0479303 -0.9988059 0.01097345 -0.04760724 -0.9987378 0.01499772 -0.04793602 -0.9988059 0.0109722 -0.04760456 -0.998806 0.01097214 -0.0476045 -0.9852434 -0.09417301 -0.142923 -0.981384 -0.1300709 -0.141304 -0.9852423 -0.09417951 -0.142926 -0.9852413 -0.09416711 -0.1429411 -0.9751842 -0.1545793 -0.1584959 -0.9770281 -0.1505867 -0.1507962 -0.9754961 -0.1562989 -0.1548481 -0.9904027 0.1286423 0.05053412 -0.9852438 -0.09417229 -0.1429209 -0.9864121 -0.09087038 -0.1368719 -0.9904419 0.1293556 0.04787367 -0.9760512 0.1844436 0.1153464 -0.9895663 0.1346203 0.05134111 -0.9898851 0.1326028 0.05043828 -0.9899927 0.1310666 0.05230647 -0.9878666 0.1433954 0.0596432 -0.9905453 0.1264346 0.05323666 -0.9977527 0.0629431 0.02297377 -0.9941424 0.04701912 0.09731471 -0.9932049 0.1077674 0.043935 -0.9904918 0.1124396 0.07926666 -0.9907404 0.1217943 0.05999666 -0.9585923 -0.282771 -0.03378194 -0.9760708 -0.1862682 -0.1122052 -0.9762452 -0.176242 -0.1260318 -0.9760662 -0.1864376 -0.111963 -0.210018 0.576332 -0.7897683 -0.9745698 -0.2087448 -0.08148109 -0.9750387 -0.2057021 -0.08358305 -0.7671804 -0.08189475 0.636182 -0.9981858 0.01300716 0.05878609 -0.9981394 -0.03491878 0.04998266 -0.9995446 -0.0268687 0.01373666 -0.9993527 -0.03341066 0.01333785 -0.9978349 -0.06570547 0.002894222 -0.9931544 0.04471862 0.1079105 -0.9965881 -0.01128977 0.08176016 -0.9956891 -0.0685175 0.06251859 -0.9967274 -0.04557824 0.06676167 -0.9981402 -0.0349105 0.04997408 -0.997506 -0.04987323 0.04994446 -0.9996092 0.02224522 0.01692873 -0.8642693 -0.4963413 -0.08175569 -0.8642691 -0.496342 -0.08175253 -0.9552683 -0.2950725 0.01986455 -0.9956923 0.05137324 0.07718539 -0.995692 0.05137699 0.07718586 -0.7796699 0.1334866 -0.6117975 -0.8982368 0.2659522 -0.3499143 -0.9727642 -0.0174281 -0.2311406 -0.9980116 0.002086341 -0.0629965 -0.9126804 0.3187478 -0.2557621 -0.9980668 0.01458781 -0.06041449 -0.9809626 -0.1018959 -0.1653162 -0.9809634 -0.1018762 -0.1653246 -0.75733 -0.5032558 -0.416155 -0.9112624 -0.3125712 -0.2681418 -0.8419824 -0.3917099 -0.3709838 -0.8420148 -0.3916854 -0.3709364 -0.8419806 -0.3917267 -0.37097 -0.9304494 -0.2533859 -0.2646872 -0.9304496 -0.2533838 -0.264689 -0.8985778 -0.3037565 -0.3166863 -0.8953459 -0.3511288 -0.2739787 -0.8830334 -0.3850949 -0.2682421 -0.883853 -0.3589649 -0.2999134 -0.9011133 -0.3111633 -0.3019475 -0.8997789 -0.3099312 -0.3071494 -0.8997721 -0.3099097 -0.3071906 -0.9557321 -0.1788098 -0.2336735 -0.955733 -0.1787718 -0.2336983 -0.9557362 -0.1787813 -0.2336786 -0.9722203 -0.1268547 -0.1967121 -0.9728286 -0.1283652 -0.1926832 -0.9985299 -0.009244263 -0.05340921 -0.9979651 -0.01724708 -0.06138521 -0.9979651 -0.01724714 -0.06138521 -0.9980809 0.01870632 -0.0590316 -0.9558776 0.1729542 -0.2374548 -0.9729824 0.1256291 -0.1937074 -0.973281 0.1356048 -0.1852977 -0.972868 0.08931624 -0.2134256 -0.9990201 -0.04220724 0.01331746 -0.9990202 -0.04220658 0.01331758 -0.9626182 0.1650416 -0.2147735 -0.9558779 0.1729595 -0.2374499 -0.9558775 0.172959 -0.2374517 -0.8886175 0.3605446 -0.2834901 -0.8899461 0.3255512 -0.3193935 -0.8993219 0.3193656 -0.2987066 -0.8993006 0.3193119 -0.2988281 -0.8981474 0.315945 -0.3057942 -0.9248071 0.2729413 -0.2650184 -0.8471977 0.3827738 -0.3684293 -0.8887087 0.3435595 -0.3035848 -0.8587029 0.4390249 -0.2643605 -0.9006356 0.3473552 -0.261151 -0.7642629 0.5517129 -0.3339385 -0.7642745 0.5516895 -0.3339511 -0.8472018 0.3827688 -0.3684253 -0.9982284 -0.004108369 -0.05935567 -0.9983406 0.01355898 -0.05596715 -0.9979502 0.008643984 -0.06340843 -0.9979503 0.008642435 -0.06340861 -0.9983813 -0.02392888 -0.0515958 -0.9943883 -0.03650933 -0.09929311 -0.9732488 -0.08104801 -0.2149836 -0.9729404 -0.1237212 -0.1951411 -0.9728288 -0.1283707 -0.1926792 -0.8982365 -0.2146961 -0.383506 -0.9688736 -0.1209277 -0.21601 -0.9572248 -0.1674683 -0.2359557 -0.8982376 -0.03304618 -0.4382659 -0.8982383 -0.03304535 -0.4382649 -0.8982382 -0.09604251 -0.4288869 -0.8982383 0.2125908 -0.3846728 -0.9689208 0.1196538 -0.2165077 -0.9729855 0.1256874 -0.193654 -0.7648473 -0.5614115 -0.3159518 -0.7776401 -0.531947 -0.3351243 -0.7796621 -0.4493955 -0.4360857 -0.7796639 -0.4493928 -0.4360854 -0.7796635 -0.3816543 -0.4964522 -0.9589331 -0.1728666 -0.2248649 -0.8982383 -0.2678697 -0.348445 -0.8982365 -0.2678737 -0.3484464 -0.7796637 -0.3816549 -0.4964514 -0.7796712 -0.3816421 -0.4964495 -0.7796719 -0.3058954 -0.5463881 -0.7796646 -0.3058922 -0.5464003 -0.8982347 -0.2146999 -0.383508 -0.8982347 -0.1570238 -0.4105095 -0.9727645 -0.08281242 -0.2164977 -0.9727646 -0.05065023 -0.226194 -0.9979664 -0.01392865 -0.06220269 -0.9979761 -0.01084399 -0.06266057 -0.7796626 -0.3059008 -0.5463982 -0.7796626 -0.2237108 -0.584876 -0.8982396 -0.1570143 -0.4105025 -0.8982396 -0.09604007 -0.4288845 -0.972764 -0.05065208 -0.2261961 -0.972764 -0.01742899 -0.2311419 -0.9981607 -0.004558324 -0.06045228 -0.9980115 0.002086699 -0.0629965 -0.7796626 -0.2237107 -0.5848759 -0.7796622 -0.1368337 -0.6110674 -0.7796645 -0.1368381 -0.6110635 -0.7796672 -0.1368329 -0.6110611 -0.7796671 -0.04708272 -0.6244215 -0.7796682 -0.04708158 -0.6244204 -0.7796716 0.04355907 -0.6246718 -0.9982907 0.004073977 -0.05830156 -0.9727643 0.01615804 -0.2312327 -0.9727652 0.01615995 -0.2312285 -0.8982377 0.03064155 -0.4384407 -0.8982343 0.03063762 -0.4384478 -0.7796667 0.04365044 -0.6246716 -0.7796728 0.04365611 -0.6246633 -0.9980615 0.0132659 -0.06080496 -0.9727652 0.04940825 -0.2264654 -0.9727656 0.04940873 -0.2264637 -0.8982344 0.09368777 -0.4294153 -0.8982349 0.09368818 -0.4294142 -0.7796726 0.1334796 -0.6117956 -0.7796639 0.1334735 -0.6118081 -0.9982489 0.02082943 -0.05536371 -0.9727656 0.08162099 -0.2169451 -0.9727645 0.08162033 -0.2169501 -0.898235 0.1547631 -0.4113664 -0.8982386 0.1547649 -0.4113579 -0.7796692 0.2205021 -0.5860841 -0.7796642 0.2204996 -0.5860919 -0.7796643 0.3028905 -0.5480701 -0.7796645 0.3028897 -0.5480704 -0.8982367 0.2125905 -0.3846766 -0.8982369 0.2659522 -0.3499144 -0.955469 0.1785623 -0.2349351 -0.9248071 0.2729419 -0.2650179 -0.7796654 0.3028901 -0.548069 -0.7796657 0.3789151 -0.4985429 -0.779664 0.3789176 -0.4985433 -0.7796665 0.3789263 -0.4985327 -0.7796661 0.4469943 -0.4385394 -0.7796638 0.4469948 -0.4385433 -0.7804538 0.4806719 -0.3998081 0.9888454 0.08719265 0.1207571 0.9887542 0.08764261 0.1211766 0.9952017 0.04887229 0.08476471 0.9977744 -0.06047117 0.02809745 0.9977743 -0.06047433 0.02809721 0.9822553 0.1783355 0.05805855 0.9955604 -0.0937727 0.008138716 0.9939178 -0.09313946 0.05875802 0.9961646 -0.0848816 0.02123993 0.9951117 -0.08667778 0.04732567 0.9774604 0.1879632 0.09613037 0.9929483 0.08634328 0.08123105 0.9671759 -0.25275 0.0262326 0.9907349 0.12181 0.06005656 0.9702528 -0.2405802 -0.02703005 0.3155524 0.02743929 0.9485114 0.656844 -0.07804566 0.7499765 0.964064 -0.2451724 -0.1023287 0.9904896 0.1125349 0.07915884 0.9900015 0.08979213 0.1087859 0.9897508 0.113514 0.08664852 0.971975 -0.229372 -0.05150681 0.1948406 0.5805821 -0.7905451 0.9760758 -0.186402 -0.1119385 0.97608 -0.1862713 -0.1121197 0.9756188 -0.1609521 -0.1492052 0.9987659 0.02067899 -0.04515552 0.9952092 -0.01808828 -0.09607958 0.999314 0.03442376 -0.01365983 0.9993141 0.03442174 -0.01365292 0.9988148 0.0436061 -0.02162241 0.9995464 0.03011816 -1.99187e-4 0.9995464 0.0301181 -2.01993e-4 0.9993657 0.02620774 -0.02411198 0.9950648 -0.04748797 -0.08712607 0.9840095 0.1592051 0.0798676 0.9907975 0.1228475 0.05682295 0.9990671 0.02635037 -0.03421497 0.9982064 0.02157622 -0.05584412 0.9985926 0.02338081 -0.04760479 0.9840093 0.1592083 0.07986426 0.9897429 0.1333345 0.05129289 0.9891446 0.1370568 0.0529949 0.9904536 0.1283894 0.05017912 0.9891443 0.1370589 0.05299234 0.9887603 0.1381049 0.05727219 0.9904799 0.1276313 0.05157446 0.9952087 -0.01808851 -0.09608519 0.995209 -0.01809167 -0.09608197 0.9924919 -0.05679798 -0.1083228 0.9800404 -0.1071999 -0.167419 0.9886756 -0.08363723 -0.1246015 0.988675 -0.08363837 -0.1246048 0.9886787 -0.08366966 -0.1245546 0.9893037 -0.09497344 -0.1107171 0.9581347 -0.1964718 -0.2082706 0.975632 -0.160923 -0.1491504 0.9650025 0.2576819 0.04868727 0.9583525 0.2824503 0.04221659 0.9616267 0.2661977 0.06643092 0.9159936 0.3987592 -0.04412102 0.970229 0.1711994 0.1713077 0.9019991 0.4314019 0.01702708 0.9965231 0.07775717 0.02992546 0.9697418 0.1645792 0.1803178 0.9813728 0.183604 -0.05654263 0.9813711 0.1836231 -0.05651003 0.8749971 -0.4819625 -0.04574233 0.8676682 0.4971439 1.44498e-6 0.9618912 0.2729253 0.01664555 0.9602133 0.2787259 0.0173881 0.9490185 0.3151378 0.007228195 0.8922376 0.4513088 -0.01524972 0.9079576 0.4190617 6.30777e-4 0.9079555 0.4190661 6.3032e-4 0.975396 0.2204489 -0.002242386 0.9959276 0.0891633 0.01333957 0.9977604 0.05711704 0.03481596 0.9902909 0.1389721 0.003272593 0.9600849 0.2792131 0.01664733 0.9600828 0.2792201 0.01664769 0.9617106 0.2736792 0.01456689 0.9753955 0.220451 -0.002242326 0.9953182 -0.09221082 0.02896231 0.9998404 -0.0171982 -0.004835546 0.9998405 -0.01719617 -0.004835844 0.968694 -0.245717 0.03542345 0.9686942 -0.2457172 0.03542351 0.9988853 -0.04698741 -0.004515111 0.9890009 -0.1478695 0.003448963 0.9954015 -0.09572887 0.003437161 0.9849039 -0.1726758 0.01213252 0.9481205 -0.3093479 0.07328838 0.9767189 -0.2139663 -0.01544809 0.9109684 -0.411212 0.03226786 0.9697472 -0.2429462 -0.02382296 0.9697396 -0.2429772 -0.02381318 0.9351882 -0.354151 2.4271e-4 0.8640464 -0.5034123 2.5759e-4 0.8640448 -0.5034149 2.57307e-4 0.73311 -0.6801102 -6.5507e-5 0.8054565 -0.5925678 0.0101605 0.7640228 -0.6448473 -0.02100408 0.7640235 -0.6448464 -0.0210039 0.9150725 -0.3995453 0.05482739 0.8668741 -0.4976626 0.02935034 0.5379495 -0.8429565 -0.005896985 0.6376963 -0.7695825 -0.03295713 0.69629 -0.7154434 -0.05762708 0.501107 -0.8648905 0.02926158 0.5011067 -0.8648906 0.0292617 0.578014 -0.815973 0.009382069 0.6567798 -0.7540824 -2.23911e-4 0.677931 -0.7351256 -2.23708e-4 0.6569482 -0.7539358 6.73176e-5 0.7331078 -0.6801124 -6.55783e-5 0.2228728 -0.9741961 0.03563094 0.4966439 -0.8645206 -0.0771296 0.3168875 -0.9484128 -0.009762942 0.2098838 -0.9776788 0.009641587 0.5090308 -0.8464792 -0.1560784 0.1630617 -0.9864486 0.01816177 0.1593027 -0.9870253 0.02008974 0.5379527 -0.8429543 -0.0058977 0.4176754 -0.9085916 0.002931058 0.3931758 -0.9194608 0.002142727 0.4204593 -0.9073114 2.10214e-4 0.3920462 -0.9199454 2.07777e-4 0.3035925 -0.9527584 0.009114444 0.7571212 0.5033916 -0.4163707 0.9125055 -0.3195532 -0.2553809 0.9554426 0.1791971 -0.234559 0.9554426 0.1791954 -0.2345601 0.955443 0.1791962 -0.2345578 0.9735252 0.1285558 -0.1890024 0.9553003 -0.1743934 -0.2387221 0.9725926 -0.1268416 -0.1948713 0.9727265 -0.137207 -0.187022 0.9727586 -0.08213055 -0.216784 0.9630851 0.1947893 0.1858066 0.9794371 -0.1269065 -0.156836 0.961973 -0.1668856 -0.2162343 0.955302 -0.1743898 -0.2387185 0.9553005 -0.1743868 -0.2387263 0.8982872 -0.3216843 -0.2993316 0.8980024 -0.3206251 -0.3013158 0.8982329 -0.2675948 -0.3486697 0.8982675 -0.3216222 -0.2994574 0.8899518 -0.3271718 -0.3177175 0.8882884 -0.3616077 -0.2831668 0.8883898 -0.3540065 -0.292306 0.8734617 -0.4078506 -0.2659369 0.7646448 -0.5617771 -0.3157924 0.764639 -0.5617898 -0.315784 0.818918 -0.4518792 -0.3538056 0.8668181 -0.3744735 -0.3292352 0.866776 -0.3745303 -0.3292814 0.9105978 0.3112941 -0.2718598 0.8463211 0.3784086 -0.3748968 0.8463497 0.378386 -0.3748548 0.8463292 0.3784114 -0.3748754 0.9365596 0.2382993 -0.2570399 0.9365593 0.2383217 -0.2570203 0.8986554 0.2982891 -0.3216242 0.899449 0.3389085 -0.2759211 0.8821076 0.381269 -0.2766229 0.8826325 0.3582527 -0.3043267 0.9015337 0.3104237 -0.3014535 0.9002482 0.3067661 -0.308946 0.9002383 0.3067361 -0.309005 0.9985159 0.00928837 -0.05366307 0.9979627 0.01724821 -0.06142365 0.9979627 0.01724648 -0.06142419 0.9980023 -0.00208944 -0.06314235 0.9980024 -0.002090394 -0.06314241 0.9982951 -0.004241585 -0.05821502 0.9979529 -0.008638083 -0.063367 0.9981845 -0.02028721 -0.05671125 0.9980751 -0.01873224 -0.05912172 0.9980834 -0.01339644 -0.06041616 0.9983185 -0.01364874 -0.05633687 0.9979529 -0.008636474 -0.06336724 0.9985789 0.02736294 -0.04573369 0.9961697 0.02820265 -0.08276742 0.9741298 0.07743555 -0.2123087 0.9735252 0.128558 -0.1890013 0.9735252 0.1285545 -0.1890034 0.9727635 -0.0501765 -0.2263039 0.9727649 -0.05017834 -0.2262973 0.972765 -0.01684522 -0.2311806 0.9727644 -0.01684415 -0.231183 0.9727644 0.0168454 -0.231183 0.8982355 0.2142251 -0.3837713 0.9688795 0.1206507 -0.2161384 0.9575068 0.1665424 -0.2354662 0.8982335 -0.09514087 -0.4290974 0.8982331 -0.09514051 -0.4290986 0.898233 -0.03193986 -0.4383574 0.8982342 -0.03194129 -0.4383549 0.8982343 0.03193968 -0.4383549 0.8982331 0.03194141 -0.4383572 0.8982331 0.09514111 -0.4290984 0.8982332 -0.2142276 -0.3837757 0.9688814 -0.1206473 -0.2161324 0.9725933 -0.1268585 -0.1948571 0.764636 0.5617922 -0.3157866 0.7776446 0.5318863 -0.3352101 0.7796627 0.4492332 -0.4362518 0.7796621 0.4492342 -0.4362518 0.7796617 0.3812432 -0.4967709 0.9585734 0.1734255 -0.225966 0.898233 0.2675971 -0.3486676 0.8982354 0.2675917 -0.3486657 0.7796643 0.3812507 -0.4967609 0.7796639 0.3812516 -0.496761 0.779664 0.3052182 -0.5467777 0.779667 0.3052196 -0.5467725 0.8982331 0.2142305 -0.3837742 0.8982331 0.1563366 -0.4107753 0.9727636 0.0824508 -0.21664 0.9727636 0.0501796 -0.226303 0.997972 0.01377993 -0.06214559 0.9979814 0.01083278 -0.06257605 0.7796638 0.3052335 -0.5467695 0.7796645 0.2227365 -0.585245 0.8982337 0.1563353 -0.4107743 0.8982335 0.09514027 -0.4290976 0.972765 0.05017513 -0.2262978 0.972765 0.01684397 -0.2311807 0.9982069 0.004349827 -0.05970108 0.9981697 0.004175961 -0.0603317 0.7796601 0.2227424 -0.5852485 0.7796601 0.1355507 -0.611356 0.7796605 0.1355516 -0.6113553 0.7796566 0.1355589 -0.6113587 0.7796567 0.04550647 -0.6245516 0.7796624 0.04550039 -0.624545 0.7796621 -0.045506 -0.6245447 0.7796564 -0.04550093 -0.6245523 0.7796568 -0.1355527 -0.6113598 0.779663 -0.1355569 -0.6113508 0.7796601 -0.135551 -0.611356 0.979251 0.07208144 0.189399 0.9727636 -0.08244901 -0.2166405 0.9727645 -0.08244955 -0.2166367 0.8982337 -0.1563361 -0.4107741 0.8982331 -0.1563358 -0.4107756 0.7796603 -0.2227384 -0.5852499 0.7796647 -0.2227405 -0.5852433 0.7796638 -0.3052326 -0.5467699 0.7796669 -0.3052197 -0.5467727 0.8982356 -0.214228 -0.3837695 0.8982353 -0.2675943 -0.3486639 0.9087621 -0.254078 -0.3310527 0.9065916 -0.3073714 -0.2891618 0.7796641 -0.3052185 -0.5467776 0.7796639 -0.3812513 -0.4967612 0.779664 -0.381251 -0.4967612 0.7796617 -0.3812446 -0.4967697 0.7796621 -0.4492338 -0.4362523 0.7796627 -0.4492337 -0.4362513 0.7804637 -0.4817652 -0.3984705 0.04765903 0 0.9988637 0.05924618 -0.008014798 0.9982113 -0.07789528 0.006489336 0.9969404 -0.06481033 0 0.9978976 0.05839693 -0.01367819 0.9981997 0.05840712 -0.01374197 0.9981982 0.06211811 -0.02673089 0.9977107 -0.06784933 -0.01910579 0.9975126 0.06211054 -0.02672135 0.9977115 0.04892373 -0.01231092 0.9987267 0.04808151 -0.01201021 0.9987712 -0.01883077 -0.06778383 0.9975224 -0.05201488 -0.007493793 0.9986182 -0.04440009 -0.005624115 0.998998 0.00373739 0.003285288 0.9999876 -0.06463491 -0.02124625 0.9976827 -0.06444472 -0.02024 0.997716 -0.06386655 -0.005890846 0.997941 -0.3706651 -0.9184041 0.1383517 -0.01047176 -0.9999142 -0.007868766 -0.3072392 -0.9188424 0.2476542 -0.1049898 -0.9908659 0.0846284 -0.1040115 -0.9912928 0.08074676 -0.1067553 -0.9908443 0.08265042 -0.1171323 -0.9881384 -0.09931147 -0.117125 -0.9881398 -0.09930568 -0.3131448 -0.9160118 -0.2507246 -0.3115864 -0.9188958 -0.2419595 -0.3399103 -0.918403 -0.2024771 -0.3399111 -0.9184045 -0.2024691 -0.3892922 -0.9184037 -0.07061296 -0.3705155 -0.9184035 -0.1387562 -0.3705165 -0.9184032 -0.1387556 -0.3705167 -0.9184031 -0.1387559 -0.3399159 -0.9184026 -0.2024689 -0.3956439 -0.9184041 -2.16185e-4 -0.395644 -0.9184039 -2.16218e-4 -0.3893683 -0.9184041 0.07018685 -0.389368 -0.9184043 0.07018691 -0.3893699 -0.9184035 0.070185 -0.3401331 -0.9184041 0.2020972 -0.3401362 -0.9184029 0.2020975 -0.3074254 -0.9187791 0.2476583 -0.3073428 -0.9187872 0.247731 -0.3073281 -0.918819 0.2476307 -0.1118916 -0.9912734 -0.06969481 -0.1051453 -0.9913129 -0.07901287 -0.1205756 -0.9901027 -0.07182127 -0.1167418 -0.9910757 -0.06434458 -0.1167463 -0.9910758 -0.06433522 -0.1286115 -0.9905248 -0.04816406 -0.1286224 -0.9905228 -0.04817593 -0.1302764 -0.9910771 -0.02818346 -0.1314625 -0.9910342 -0.02384573 -0.3892923 -0.9184037 -0.07061302 -0.3892974 -0.9184047 -0.07057267 -0.1404695 -0.9896187 -0.03038632 -0.130903 -0.9913553 -0.008886814 -0.1316848 -0.9912916 -7.19547e-5 -0.1527087 -0.9882169 -0.01036775 -0.1291511 -0.9911937 0.02924215 -0.1387125 -0.9900169 0.02500408 -0.1305296 -0.9913927 0.01012194 -0.1305296 -0.9913927 0.01012188 -0.1291516 -0.9911937 0.0292406 -0.129749 -0.9903634 0.04842901 -0.3706656 -0.9184039 0.1383516 -0.3706656 -0.9184041 0.138351 -0.1267139 -0.9907351 0.04886066 -0.1170476 -0.9909312 0.06599485 -0.115719 -0.9908994 0.0687564 -0.1231448 -0.9899569 0.06943023 -0.104116 -0.9912936 0.08060258 0.710356 8.94713e-6 -0.7038425 0.7103523 0 -0.7038462 0.7104101 -5.35266e-5 -0.7037878 0.7103533 3.08358e-6 -0.7038453 0.7103516 -3.56192e-7 -0.703847 0.7105979 3.32973e-4 -0.7035983 0.7103536 -8.35872e-5 -0.703845 0.7103406 -5.9051e-5 -0.7038581 0.710227 1.27494e-4 -0.7039728 0.279962 -0.006230771 -0.9599909 -0.7117838 0 -0.7023986 -0.7232931 -0.01145744 -0.6904461 -0.7232434 -0.01141786 -0.6904988 -0.7311049 -0.01755797 -0.6820392 -0.7316924 -0.01788467 -0.6814002 -0.7203406 -0.0116561 -0.6935226 0.6862647 -0.08716797 -0.7221099 0.7128631 -0.03459948 -0.7004492 0.7555605 -0.002724111 -0.6550732 0.7555083 -0.002708196 -0.6551335 0.7551122 -0.002567708 -0.6555906 0.749078 0 -0.6624818 0.7367419 4.77399e-4 -0.6761739 0.6722504 0.007796227 -0.7402828 0.5527388 0.09297949 -0.8281512 -0.6942242 -0.003241419 -0.7197516 -0.6943404 -0.003275752 -0.7196393 -0.5942668 0.008101642 -0.8042272 -0.6369877 -0.008591532 -0.7708261 -0.5942648 -0.008604049 -0.8042234 -0.4584677 0.02701735 -0.8883003 -0.4621642 0.02991777 -0.8862896 -0.3196518 -0.008491694 -0.947497 -0.3196096 -0.008491694 -0.9475113 -0.1553344 0.02462303 -0.987555 -0.1753508 0.03921324 -0.9837248 0.2799723 -0.006230771 -0.9599878 0.1278972 0.0461688 -0.9907124 0.1636327 0.01813769 -0.9863546 -0.02706813 -0.007208228 -0.9996076 -0.0271058 -0.007208228 -0.9996066 0.4254775 0.0102272 -0.9049113 0.4657847 0.03510409 -0.8842015 0.5551815 -0.002649784 -0.8317251 0.6434515 -0.00263375 -0.7654823 0.698651 -0.02563607 -0.7150033 -0.7038629 3.36822e-5 -0.710336 -0.7038 -8.38211e-5 -0.7103982 -0.703867 5.00825e-5 -0.7103319 -0.7038462 1.13945e-5 -0.7103524 -0.7038534 -8.64732e-6 -0.7103453 -0.7039157 -1.14255e-4 -0.7102836 -0.7038343 2.008e-5 -0.7103644 -0.703827 2.72932e-5 -0.7103716 -0.7038567 0 -0.710342 0.3703418 -0.9184114 0.1391664 0.3072801 -0.9187833 0.2478233 0.3101505 -0.9178196 0.2478181 0.3101096 -0.9178416 0.2477878 0.1056045 -0.9905505 0.08750575 0.105586 -0.9905539 0.08749079 0.1208308 -0.9873491 -0.1026718 0.120841 -0.9873471 -0.1026797 0.11366 -0.9913182 -0.06610393 0.01308351 -0.9998686 -0.009566485 0.3398851 -0.9184117 0.2024801 0.3398862 -0.9184109 0.2024818 0.3072983 -0.9187813 0.2478072 0.3891231 -0.9184101 0.07145708 0.3891211 -0.9184111 0.07145482 0.3891208 -0.9184111 0.07145506 0.3956252 -0.9184108 0.001493692 0.3896487 -0.9184114 -0.06851559 0.3896508 -0.9184105 -0.06851494 0.3713861 -0.9184105 -0.1363624 0.3713864 -0.9184103 -0.1363623 0.3713843 -0.9184111 -0.1363624 0.3414056 -0.9184113 -0.1999069 0.3414022 -0.9184126 -0.1999071 0.3414014 -0.9184109 -0.1999164 0.3145933 -0.9189181 -0.2379511 0.3167928 -0.9151322 -0.2493499 0.1175742 -0.9906604 0.06905311 0.1185082 -0.99044 0.07059907 0.1044827 -0.991111 0.08235484 0.1043543 -0.9911099 0.0825318 0.1078541 -0.9905259 0.08500474 0.1241059 -0.9909886 0.05039209 0.1256302 -0.9909533 0.0472083 0.3703416 -0.918412 0.139164 0.3703484 -0.9184094 0.1391624 0.1315551 -0.9898688 0.05341428 0.1277518 -0.9913118 0.03130859 0.1298099 -0.9912524 0.02383714 0.1458967 -0.9886533 0.03575843 0.1302333 -0.9914055 0.01242518 0.1302333 -0.9914056 0.01242548 0.1412304 -0.9899766 5.33297e-4 0.3956256 -0.9184107 0.001493871 0.3896476 -0.9184111 -0.06852585 0.1316158 -0.9912789 -0.006594955 0.1316158 -0.9912788 -0.006594896 0.1372575 -0.9902414 -0.02413493 0.1319128 -0.9909176 -0.02610188 0.1275739 -0.9907224 -0.04684174 0.1310928 -0.99028 -0.04647779 0.1170914 -0.9911922 -0.06186962 0.1146073 -0.9911415 -0.06710797 0.1291154 -0.9892804 -0.06821697 0.1057029 -0.9913895 -0.07728987 0.1249108 -0.9899789 0.06587243 0.01418489 -0.9997766 0.01567023 0.01540124 -0.9998242 0.01070052 0.01540404 -0.9998241 0.01069527 0.04814022 -0.9982705 0.0337392 0.04274928 -0.9989475 0.01663506 0.04274898 -0.9989473 0.01663583 0.1183044 -0.9929525 0.007033824 0.1183044 -0.9929524 0.00703448 0.1078515 -0.9931186 0.04564487 0.08083826 -0.9966138 0.01504319 0.0808382 -0.9966137 0.01504361 0.06250476 -0.9980377 0.003716051 0.06250476 -0.9980378 0.003716289 0.2520543 -0.9665644 -0.0471366 0.1360968 -0.988283 0.06909668 0.1660289 -0.9861197 0.001553773 0.1132686 -0.9924219 0.0476318 0.1659447 -0.985621 0.03183639 0.2511215 -0.9679106 -0.009337365 0.502521 -0.864106 0.0281676 0.5025213 -0.8641059 0.02816748 0.5783942 -0.8073152 0.1170567 0.6571162 -0.7537439 -0.008280932 0.7029885 -0.7078033 0.06943964 0.7076593 -0.7064697 0.01090925 0.7667923 -0.6407029 0.03910613 0.7721387 -0.6337286 0.04679495 0.3993762 -0.9066845 0.1357274 0.4172403 -0.8824529 0.2172269 0.4274017 -0.8863545 0.1780551 0.4586564 -0.8853678 0.07588291 0.4995598 -0.851047 0.1617373 0.5116218 -0.8581485 0.0427125 0.5852532 -0.7987219 0.1397213 0.5783951 -0.8073155 0.1170505 0.2986221 -0.9180427 0.2608112 0.3391683 -0.905065 0.2565581 0.3453935 -0.9070855 0.2406226 0.3438992 -0.9066889 0.2442307 0.3473827 -0.9075307 0.2360367 0.3588088 -0.9087107 0.2133101 0.3167752 -0.9162613 0.2451915 0.3520759 -0.9092172 0.2221859 0.3386109 -0.9160634 0.2148735 0.09766334 -0.9905453 0.09634304 0.124888 -0.9899827 0.06585896 0.1310003 -0.9850389 0.11197 0.1674116 -0.9848813 0.04451984 0.1928803 -0.9749057 0.1111575 0.2213253 -0.9749665 0.02134507 0.2718063 -0.9568485 0.1027735 0.2896476 -0.9571114 0.006491601 0.3523184 -0.9317871 0.08743369 0.3616709 -0.9323015 0.002844095 0.4948293 -0.8673465 0.05342394 0.4957459 -0.8678001 0.0340448 0.7728397 -0.634301 -0.01952344 0.8510399 0.4431463 -0.2816958 -0.7759655 0.5651445 0.2801595 -0.8412246 0.5210784 0.1442864 -0.995701 0.08782815 0.0294218 -0.9964313 0.07604861 0.03662443 -0.9956334 0.09009689 0.02442806 -0.9971414 0.06911319 0.03053623 -0.9970184 0.07296156 0.02511954 -0.9970183 0.07296299 0.02511888 -0.9970183 0.07296276 0.02511912 -0.9945282 0.09935861 0.03227126 -0.9921871 0.1216476 0.02768987 -0.9946714 0.09540468 0.03907483 -0.9909233 0.1282562 0.04026442 -0.9905693 0.1322274 0.03589385 -0.9860967 0.1625452 0.03453165 -0.9902783 0.133492 0.03910219 -0.9846861 0.1653776 0.0551685 -0.9804409 0.1910117 0.04743713 -0.9739586 0.221674 0.04759567 -0.9740028 0.2214789 0.04759728 -0.9784849 0.1944429 0.06898647 -0.9784842 0.1944466 0.06898683 -0.972984 0.2185642 0.07437717 -0.9477785 0.314712 0.05169361 -0.9585255 0.2753769 0.0734604 -0.9480521 0.3044626 0.09219354 -0.9573477 0.2754884 0.08712893 -0.947911 0.3024022 0.1000882 -0.9067142 0.4085548 0.1046539 -0.8638582 0.4887136 0.1220986 -0.9047515 0.4069939 0.1256207 -0.9201162 0.3808583 0.09128582 -0.9201123 0.3808674 0.09128707 -0.7759609 0.5651501 0.280161 -0.7759581 0.5651566 0.2801554 -0.7757289 0.4452493 0.447211 -0.8216518 0.4947823 -0.2829818 -0.8216348 0.494814 -0.2829756 -0.6766488 0.6381362 0.3673263 -0.5915979 0.7406851 0.31843 -0.5916171 0.7406749 0.3184179 -0.5915961 0.7406899 0.3184217 -0.4628068 0.7746253 0.4310052 -0.5101805 0.7876088 0.3455262 -0.4758048 0.8065096 0.3509301 -0.3193252 0.8673213 0.3818182 -0.3384857 0.8469364 0.4100322 -0.2042701 0.9079093 0.3660255 -0.2042614 0.907911 0.3660259 -0.338486 0.8469359 0.4100323 0.08903437 0.9144613 0.3947576 -0.05728411 0.9226192 0.3814345 -0.1088492 0.9186533 0.3797737 -0.06673657 0.8982081 0.4344748 -0.05591028 0.8922318 0.4481033 0.236222 0.9008116 0.364332 0.3740453 0.8547523 0.3598451 0.3740354 0.8547564 0.3598461 0.3189289 0.8539014 0.4112624 0.236253 0.9007968 0.3643479 0.2362228 0.9008113 0.3643319 0.4953958 0.7880595 0.3654385 0.5091423 0.7687135 0.3871095 0.6150146 0.7252494 0.309468 0.6909412 0.5924549 0.4142434 0.6149971 0.7252593 0.3094794 0.6149974 0.7252591 0.3094793 0.7237516 0.6536188 -0.2212829 0.7222948 0.3234645 0.6112781 0.7896525 0.5129834 0.3365961 0.7896413 0.5130181 0.3365696 0.9866638 0.1563634 0.04522216 0.9870404 0.1536052 0.04644036 0.9865981 0.156576 0.04591387 0.9911782 0.1201835 0.05587244 0.989985 0.1409416 -0.008067607 0.9929282 0.1142777 0.03216075 0.9935335 0.1079896 0.03506344 0.9944447 0.09340256 0.04853242 0.9957982 0.0915752 -1.53199e-4 0.9960946 0.08495604 0.02404367 0.9965936 0.07619065 0.03156238 0.9967536 0.07822883 0.01904398 0.9970859 0.07205361 0.02506035 0.9970859 0.07205361 0.02505999 0.9970859 0.07205265 0.02506113 0.7986488 0.5938717 0.09734702 0.8472806 0.5107189 0.1458826 0.9286004 0.3544244 0.1099303 0.8465155 0.5168234 0.1276916 0.8920868 0.4398961 0.1033083 0.912197 0.3892394 0.1280211 0.938964 0.319023 0.1287282 0.9119712 0.3967379 0.1044396 0.9443001 0.3212395 0.07143235 0.954532 0.2882922 0.07587027 0.9435907 0.3209286 0.08149629 0.9542039 0.283882 0.09437131 0.9730765 0.2240369 0.0541262 0.9765054 0.207991 0.05636394 0.9727935 0.2243525 0.05778193 0.9760208 0.2072521 0.06655901 0.9857559 0.1590374 0.05470222 0.9765751 0.2081134 0.0546804 0.9872993 0.1528672 0.043262 0.7629027 0.6305125 0.142945 0.7628704 0.6305502 0.1429522 0.7629046 0.6305108 0.1429426 0.6589365 0.7427676 0.1187396 0.6633968 0.7399873 0.1110112 0.6731556 0.684159 0.2806924 0.7229644 0.6361773 0.269446 0.5492985 0.8239459 0.1392271 0.4971901 0.8607482 0.1091548 0.539963 0.8393153 0.06316465 0.2879239 0.9490711 0.1279219 0.2879324 0.9490686 0.1279205 0.3078329 0.9456056 0.1052084 0.4269052 0.8921297 0.1478394 0.4269123 0.8921265 0.1478386 0.1087595 0.9039567 0.4135621 0.104094 0.9896172 0.09910708 0.1483967 0.9795679 0.1357392 -0.1416077 0.9863896 0.08356392 0.00471121 0.9886403 0.150227 0.004711925 0.9886403 0.1502271 -0.1416289 0.9863874 0.08355271 -0.1052792 0.9848806 0.1375733 -0.2792157 0.9515913 0.1285012 -0.3074415 0.9462571 0.1003845 -0.4121087 0.8987176 0.1499102 -0.6529257 0.7478567 0.1199935 -0.5432569 0.8277718 0.1402349 -0.4960022 0.8626393 0.09917277 -0.4121105 0.8987163 0.1499127 -0.4121171 0.8987135 0.1499119 -0.6716032 0.6602092 0.3362633 -0.6626969 0.7414875 0.1050202 -0.6529276 0.7478553 0.1199922 -0.8412216 0.521083 0.1442874 -0.8412244 0.521078 0.1442884 -0.7986484 0.593904 0.09715354 -0.7540263 0.6402454 0.1467323 -0.7540289 0.6402424 0.1467316 -0.784727 -0.5495648 0.2866741 0.2257247 -0.9036877 0.3638637 0.5791472 -0.794485 0.1827073 -0.07062447 -0.9887909 0.1315478 -0.9971632 -0.07096022 0.02510464 -0.9971639 -0.07094442 0.02512276 -0.9961869 -0.08222895 0.02915447 -0.9970008 -0.07469606 0.0202496 -0.9967041 -0.07713872 0.0251109 -0.9964802 -0.07518428 0.03707695 -0.9621318 -0.2615499 0.07677406 -0.9610697 -0.2652413 0.07740885 -0.9625338 -0.2607107 0.07455593 -0.9612045 -0.2666679 0.07052791 -0.9629073 -0.2605845 0.07003831 -0.9612066 -0.2667227 0.07029145 -0.9816339 -0.1812694 0.05946624 -0.9802085 -0.190921 0.05235129 -0.9822963 -0.1798678 0.05235964 -0.980594 -0.1909636 0.04436421 -0.9903656 -0.1288111 0.05082994 -0.9887996 -0.1429388 0.04293996 -0.9909268 -0.1264073 0.04566442 -0.9903011 -0.1367872 0.02434962 -0.9940098 -0.0982964 0.04777318 -0.9931404 -0.1117506 0.03440988 -0.9946808 -0.09380227 0.04255694 -0.9956023 -0.09302109 0.01110267 -0.996035 -0.08479493 0.02690833 -0.8720951 -0.4711304 0.1322351 -0.9623512 -0.2607801 0.07664185 -0.9278708 -0.3595817 0.09877598 -0.9269254 -0.3615694 0.1003837 -0.9276648 -0.3594187 0.101273 -0.875457 -0.4660156 0.1280798 -0.8006837 -0.5871423 0.1190364 -0.7911407 -0.602823 0.1034442 -0.8723658 -0.467388 0.1432704 -0.8723704 -0.4673789 0.1432722 -0.5936548 -0.7907261 0.1494197 -0.5936574 -0.7907244 0.1494181 -0.6618402 -0.7432988 0.097337 -0.701933 -0.6992402 0.135474 -0.7927422 -0.5973234 0.1215095 -0.344403 -0.92947 0.1321824 -0.3074592 -0.9463123 0.09980845 -0.3444049 -0.9294691 0.1321827 -0.4697144 -0.8732491 0.1296315 -0.4991919 -0.8573125 0.1257885 -0.4646003 -0.8815293 0.08397996 -0.5936547 -0.7907261 0.1494197 -0.07398325 -0.9885495 0.1315156 -0.07398545 -0.9885495 0.1315145 -0.1042345 -0.989338 0.1017124 -0.2137341 -0.9659283 0.1459466 -0.2137392 -0.9659273 0.1459463 0.3445268 -0.9310196 0.1204325 0.3096865 -0.9423546 0.1267362 0.5660136 -0.8218928 0.06419295 0.5660125 -0.8218936 0.06419444 0.3484151 -0.9215092 0.1715451 0.3484061 -0.9215124 0.171546 0.7660454 -0.6177511 0.1776461 0.7660573 -0.6177371 0.1776433 0.7660592 -0.6177351 0.1776421 0.7999185 -0.5899353 0.1100307 0.8939 -0.4222339 0.150537 0.9135624 -0.3814361 0.1411039 0.8939284 -0.4242038 0.1447183 0.8788844 -0.4470073 0.1665735 0.8937664 -0.4187186 0.1607989 0.9358949 -0.343622 0.07761913 0.943501 -0.3239576 0.06969439 0.9353752 -0.3432586 0.08512818 0.9436362 -0.3208379 0.08132475 0.9351631 -0.3431401 0.08789116 0.9676911 -0.2395245 0.0787518 0.9847645 -0.1658543 0.05226176 0.9674782 -0.2388086 0.08340483 0.9666811 -0.2423831 0.08232951 0.9666801 -0.2423874 0.08232986 0.9917859 -0.121368 0.04038232 0.9863177 -0.1587365 0.04449915 0.9914017 -0.1205561 0.05088055 0.9860174 -0.1594364 0.04847568 0.98526 -0.1645167 0.04687213 0.9863933 -0.1585517 0.04346871 0.9684901 -0.2434793 0.0523892 0.9930026 -0.1124396 0.03609967 0.9930032 -0.1124333 0.03610265 0.99266 -0.1163302 0.0330668 0.996329 -0.07876974 0.03352683 0.9962778 -0.08180367 0.02718192 0.9965435 -0.07683092 0.03159034 0.9966445 -0.07792383 0.02504986 0.9966444 -0.07792514 0.02504926 0.9966445 -0.07792448 0.02505004 0.7138909 -0.6383247 0.2879258 0.7890112 -0.5293346 0.3118751 0.7890089 -0.5293409 0.3118701 0.7722244 -0.437146 0.4610563 0.8671371 -0.4640153 -0.1810054 0.8671396 -0.4640101 -0.1810068 0.6617304 -0.7434828 0.09667569 0.6687289 -0.6396787 0.3789629 0.7138962 -0.6383196 0.2879246 0.6111295 -0.72987 0.306285 0.6111313 -0.729869 0.3062838 0.6111321 -0.7298684 0.3062837 0.505469 -0.8406157 0.1945924 0.5100468 -0.7816573 0.3589763 0.4805188 -0.7750921 0.4102851 0.2257193 -0.903689 0.3638641 0.3566235 -0.8316699 0.4256113 0.3190711 -0.8557204 0.4073525 0.3642416 -0.8574484 0.3634699 0.3643134 -0.8574206 0.3634633 0.07903599 -0.9178013 0.3890938 0.1087744 -0.903084 0.4154605 0.1050868 -0.9857795 0.1311314 0.1108643 -0.9841041 0.1387376 -0.2144249 -0.9061681 0.3645292 -0.2144306 -0.9061667 0.3645288 -0.1087999 -0.9019579 0.4178931 -0.06786161 -0.9206748 0.3843863 -0.06776475 -0.9206808 0.3843888 -0.6002697 -0.7352769 0.314713 -0.6002652 -0.7352793 0.3147158 -0.5091306 -0.7671811 0.3901526 -0.4838525 -0.7999672 0.3548792 -0.3194392 -0.8713181 0.3725097 -0.3473781 -0.8401898 0.4164248 -0.3473237 -0.8402254 0.4163984 -0.6724779 -0.6679535 0.3187658 -0.6811817 -0.6265482 0.37872 -0.6002567 -0.7352865 0.3147155 -0.9114565 -0.3916735 0.1258529 -0.8497521 -0.4768273 -0.224849 -0.7390261 -0.6495553 -0.1786568 -0.7527159 -0.3702714 0.5443509 -0.7847266 -0.5495659 0.2866731 -0.9896277 -0.1340543 0.05163866 -0.9896712 -0.133781 0.05151349 -0.9899302 -0.1322782 0.05040496 -0.9951916 -0.09607452 0.01905739 -0.9896277 -0.1340545 0.05163848 -0.9915288 -0.1238108 0.03926193 -0.9955323 -0.0904926 0.02695512 -0.9925128 0.05664461 -0.1082113 -0.9800574 0.1071093 -0.1673775 -0.9885332 0.08403289 -0.1254611 -0.9885328 0.08403408 -0.1254639 -0.9885293 0.08400529 -0.1255111 -0.9890033 0.09186333 -0.1159037 -0.9689301 0.1640874 -0.185067 -0.9932517 -0.03191816 0.1115008 -0.964926 0.1965913 -0.1739811 -0.9649251 0.1965937 -0.1739844 -0.9990091 -0.02402645 -0.03746455 -0.9988642 -0.02530968 -0.04036915 -0.9952198 0.0180006 -0.09598755 -0.9952201 0.01800006 -0.09598368 -0.9952201 0.01800036 -0.09598338 -0.9794788 -0.1701647 0.1080047 -0.9794788 -0.1701656 0.1080039 -0.9991447 -0.03346443 -0.02429085 -0.9983926 -0.02629315 -0.05020803 -0.9988685 -0.01899898 -0.04359775 -0.9994575 -0.001009047 -0.03291785 -0.9994577 -0.001008629 -0.03291225 -0.9986178 -0.0129863 -0.05093067 -0.9997219 -0.01256036 -0.01996582 -0.9988779 -0.02627551 -0.03940403 -0.9957763 -0.08474361 0.03532963 -0.9654564 0.2189325 -0.141289 -0.9654522 0.2190803 -0.1410886 -0.2729525 -0.5663353 -0.7776641 -0.2790307 -0.5643758 -0.776931 -0.6628996 0.0813862 0.7442716 -0.9702413 0.2406437 -0.02687972 -0.9955523 -0.07311969 0.05940592 -0.9899955 -0.08975076 0.1088756 -0.9898748 -0.08087474 0.1166499 -0.9889732 -0.08732622 0.1196084 -0.9768561 0.2138698 -0.003420889 -0.9641344 0.2450525 -0.1019524 -0.8660926 0.4933073 -0.08081799 -0.9666343 0.2541152 0.03230339 -0.9924362 -0.0968514 0.07543414 -0.8660925 0.4933081 -0.08081477 -0.99533 0.07806682 0.05677956 -0.9924361 -0.09685343 0.07543379 -0.9979552 0.06382638 0.003417909 -0.9993606 0.03316444 0.0133599 -0.9995455 0.02683019 0.0137456 -0.9981402 0.0348792 0.04999518 -0.9978564 0.03803437 0.05325394 -0.997808 0.04555326 0.04800236 -0.9995974 -0.02245026 0.01735079 -0.9981788 -0.01329368 0.05884218 -0.9967868 0.0509572 0.0617997 -0.9900441 -0.08986765 0.1083351 1 -4.42392e-6 -4.41404e-7 1 1.27485e-6 0 1 0 0 1 -8.96035e-7 0 1 -1.74078e-6 0 1 -1.38599e-5 2.2282e-6 0.219216 -0.9756053 0.01177227 0.7985667 -0.5984261 -0.06463295 0.6122589 -0.7844202 0.09911626 0.6122662 -0.784415 0.09911251 0.6122441 -0.7844319 0.09911519 0.2128031 -0.8981969 0.3846519 0.2109199 -0.8985724 0.3848123 0.2116102 -0.8966702 0.3888493 0.2329776 -0.9614687 0.1459432 0.2290789 -0.8962651 0.3797783 0.262041 -0.954115 0.14491 0.203081 -0.9734326 0.105769 0.2192264 -0.9756034 0.01173669 -0.1285542 -0.9916315 0.01187419 -0.08918386 -0.9847229 0.1495561 -0.2093744 -0.8988721 0.3849561 -0.236028 -0.9607192 0.1459777 -0.2362132 -0.9666488 0.09896206 -0.5401116 -0.8276124 0.152765 -0.4800351 -0.8661727 0.1389651 -0.5674461 -0.8132743 0.1288017 -0.4835919 -0.8725838 0.06882208 -0.7596882 -0.6496921 0.02781975 0.6152954 -0.7882959 -0.001066625 -0.4521125 -0.8919609 8.78733e-5 -0.4847383 -0.8746592 8.78094e-5 -0.4520913 -0.8919716 -3.10391e-4 -0.484741 -0.8746575 -6.68329e-4 -0.7461796 -0.6381394 0.1897209 -0.9758084 -0.2186276 0 -0.7904855 -0.6124805 5.69179e-4 -0.7904827 -0.6124841 5.69179e-4 -0.8659374 -0.500149 -0.001843392 -0.9758089 -0.2186254 -8.70516e-5 -0.9277279 -0.373257 -1.08245e-4 -0.9962676 -0.08629292 0.0021227 -0.02953565 -0.9995637 -1.08179e-4 -0.1285631 -0.9916994 0.001991868 0.38349 -0.9235411 -0.002662837 0.2192311 -0.9756727 -7.42885e-4 0.3834367 -0.9235668 -7.19626e-4 0.219241 -0.9756682 0.002180218 0.6152734 -0.7883132 -0.001066505 0.6152881 -0.7883013 0.001258015 0.7108136 -0.7033804 -2.21301e-4 0.7108182 -0.7033758 -2.213e-4 0.800253 -0.5996626 2.3274e-5 0.8695636 -0.4938209 -3.92952e-5 0.9241206 -0.3821 8.85673e-4 0.9766061 -0.215036 7.33983e-5 0.9241341 -0.3820683 9.37836e-5 0.9770496 -0.2130089 -0.001144647 0.9953038 -0.09680151 0 0.9541246 0.2977078 0.03187984 0.9977985 -0.06489711 0.01365035 0.9896193 0.1366446 0.04451799 0.9967491 0.03214639 0.07387727 0.9967501 0.03214383 0.07386559 0.997667 0.0311737 0.06073689 0.9965966 0.05706018 0.05949348 0.9931731 -0.04476147 0.1077191 0.9978312 0.01940137 0.06290245 0.997895 0.06410294 0.009817481 0.9978947 0.06410866 0.009813308 0.9978947 0.06410819 0.009813368 0.9941525 -0.04704511 0.09719896 0.9834021 0.1712304 -0.06000441 0.2177133 -0.5825464 -0.7830969 0.2726372 -0.5660713 -0.7779666 0.9654072 0.2192192 -0.1411803 0.9654082 0.2191872 -0.1412238 0.995816 -0.08436179 0.03512436 0.9956004 -0.07275581 0.05904698 0.9946455 -0.07441377 0.07171422 0.9787404 0.2012551 -0.03954476 0.7694124 0.08119314 0.633571 0.9586083 0.2826599 -0.03425532 0.9845083 0.09590488 -0.1467838 0.9845057 0.09587234 -0.1468233 0.9845063 0.09587353 -0.1468178 0.9845012 0.09588336 -0.1468461 0.9867095 0.08965295 -0.135523 0.9952403 -0.09564596 0.01867288 0.985248 0.1104536 -0.1307148 0.9727008 0.1700847 -0.1578745 0.964305 0.188493 -0.1859738 0.9890792 -0.13744 0.05322223 0.9952871 -0.0952174 0.01836115 0.9894738 -0.1364037 0.04832905 0.9954732 -0.09194076 0.0240814 0.9930088 -0.1088132 0.04575359 0.9823738 -0.165528 0.08684605 0.9820146 -0.1698711 0.08240771 0.9905631 -0.128028 0.04892355 0.9890792 -0.1374394 0.05322289 0.9955831 0.0144068 -0.09277349 0.995583 0.0144062 -0.09277415 0.9974603 0.01319223 -0.0699926 0.9981362 -0.0326997 -0.05152451 0.9983521 -0.02132344 -0.05327874 0.9983719 -0.0264399 -0.05054175 0.9991571 -0.01346379 -0.03877842 0.9991516 -0.0126385 -0.03919929 0.9991322 -0.01277774 -0.03964555 0.9991465 -0.012474 -0.03938031 0.9991468 -0.01247298 -0.03937059 0.9991151 -0.01234614 -0.04020601 0.9990068 -0.008368909 -0.04376435 0.9999341 -0.01147878 -2.98342e-4 0.5738314 9.83075e-4 0.8189729 0.7070906 0.006087005 -0.7070968 0.4926369 -0.1087688 -0.8634108 0.6879762 -0.02770072 -0.7252044 0.8436213 -0.1131398 -0.5248833 0.965924 0.002180933 -0.2588168 0.8301452 0.002309024 -0.5575424 0.8299448 0.002308189 -0.5578408 0.1579942 0 -0.9874401 0.06464296 5.14606e-6 -0.9979085 0.2587663 -0.02237528 -0.9656808 0.2554569 -0.02353149 -0.9665341 0.4834849 0.006333708 -0.8753297 -0.2587571 -0.02391809 -0.9656463 -0.2480872 -0.02039277 -0.968523 -0.07362401 -0.001342713 -0.9972851 -0.01613801 -8.45783e-5 -0.9998697 -0.004744291 -6.52049e-6 -0.9999887 0 0 -1 0 0 -1 -0.8305882 0.003623723 -0.5568754 -0.8296445 0.003622889 -0.5582804 -0.6765857 -0.03140896 -0.7356936 -0.7070096 -0.01631253 -0.7070157 -0.4726398 0.005604028 -0.8812379 -0.472624 0.005604028 -0.8812463 -0.8296176 0.003623723 -0.5583203 -0.9658861 -0.009124755 -0.2588067 -0.9441996 -0.03481173 -0.3275291 -0.8155167 0.001615166 0.5787312 -0.9307281 -0.001737833 0.3657075 -0.9657319 -0.01999741 0.2587705 -0.992302 0 0.1238418 -0.9938005 0 -0.1111773 -0.8158308 0.001615166 0.5782883 -0.7071127 0.001328229 0.7070996 -0.7996261 -0.03736716 0.5993345 -0.4737663 0.002812027 0.8806461 -0.4737978 0.002812027 0.8806293 -0.6549236 -0.005814731 0.7556727 -0.0704227 0.001955389 0.9975153 -0.04051619 -0.1699337 0.9846222 -0.30229 0.1697746 0.9379752 -0.2766298 -0.01521986 0.960856 -0.2587941 -0.01215291 0.9658561 0.2588131 9.40261e-4 0.965927 0.5412272 -0.07117992 0.8378584 0.3672577 -0.02822971 0.9296908 0.1641913 -0.003415703 0.9864226 -0.04949122 0.001955628 0.9987726 -0.07406616 0.001954972 0.9972515 0.9384221 -0.03942698 -0.3432341 0.9925268 0 -0.1220276 0.9659249 0 0.2588222 0.9945067 -0.05847448 0.08681696 0.9694556 -0.01733171 0.2446537 0.8845365 0.003993749 0.466454 0.8845288 0.003993749 0.4664683 0.7071081 0.003821134 0.707095 0.8597127 -0.06472665 0.5066602 0.7335247 -0.01874876 0.6794042 0.5796137 0.8148005 0.01217257 0.5026719 0.8638851 0.0319916 0.5026756 0.8638831 0.03199046 0.5379511 0.8429554 -0.005897283 0.4176764 0.908591 0.002931416 0.5379496 0.8429564 -0.005896925 0.6376965 0.7695823 -0.03295725 0.7550788 0.6501953 -0.08427387 0.417679 0.9085898 0.002931475 0.3920426 0.919947 2.07457e-4 0.3920458 0.9199457 2.07457e-4 0.3035926 0.9527583 0.009114146 0.2228734 0.974196 0.03563058 0.4966324 0.8645276 -0.07712501 0.3168916 0.9484115 -0.009763896 0.2098813 0.9776793 0.009641885 0.50904 0.8464726 -0.156085 0.1630413 0.9864519 0.01817107 0.1593262 0.9870219 0.02007633 0.8038572 0.5947909 0.006123363 0.8636007 0.5038513 0.01810497 0.7345973 0.6784967 0.003015756 0.7345969 0.6784971 0.003015756 0.7292317 0.6842579 0.003518879 0.6583222 0.7527317 0.002612113 0.6583218 0.752732 0.002612113 0.8480794 0.5298656 -0.00197649 0.9118489 0.4088695 0.03684413 0.739264 0.6728401 -0.02784371 0.8480796 0.5298652 -0.00197643 0.9008396 0.4341517 -6.76617e-4 0.9008429 0.4341448 -6.76617e-4 0.9157967 0.4016407 -0.001101553 0.9850643 0.1712486 0.01794803 0.9514729 0.3076792 -0.005722343 0.9514776 0.307665 -0.005726993 0.9514731 0.3076789 -0.005722343 0.9689746 0.2437357 0.04100054 0.9689714 0.2437474 0.04100501 0.9887142 0.1491503 -0.01408505 0.9416413 0.3363832 0.01256424 0.9112387 0.4105012 0.03365707 0.998397 0.05524784 0.01229071 0.9954411 0.09491866 0.009357929 0.995441 0.09491872 0.009357929 0.9900968 -0.1403375 -0.003713071 0.9981522 -0.05881923 0.01524382 0.9976035 -0.06849038 0.00980705 0.9998404 0.01719689 -0.004835784 0.9998404 0.01719808 -0.004835605 0.8536826 -0.5191101 0.04184222 0.8536827 -0.5191099 0.04184228 0.8664351 -0.4955216 0.06122565 0.9170972 -0.3628468 0.1651515 0.9562371 -0.2623803 0.1294888 0.9649407 -0.2309403 0.1247243 0.9139427 -0.3857789 0.126029 0.9650973 -0.2331662 0.1192513 0.9132066 -0.3896716 0.1192044 0.9760413 -0.2174448 0.007831275 0.976042 -0.2174416 0.0078305 -1 4.67497e-6 0 -1 -5.72229e-7 2.17958e-7 -1 0 0 -1 4.61848e-7 0 -1 0 0 -1 -7.67368e-5 -6.3051e-6 0.7728551 -0.6343166 0.01837152 0.4235833 -0.9057016 0.01677966 0.7725647 -0.6340753 0.03304874 0.1657887 -0.9846944 0.05376881 0.4213494 -0.9057095 0.046422 0.1660291 -0.9861209 0 0.5023865 -0.8638744 0.03645116 0.421195 -0.9056812 0.04833507 0.5023067 -0.8637375 0.04056531 0.4202082 -0.9054495 0.05988621 0.4202061 -0.9054504 0.05988621 0.8347857 -0.548075 0.0524078 0.08453351 -0.931169 0.3546527 0.05513083 -0.9910679 0.1214289 0.112228 -0.9881144 0.1050468 0.4187259 -0.9049158 0.07613211 0.4574579 -0.8808889 0.1215192 0.1391358 -0.9882193 0.06374686 0.1450801 -0.9866403 0.0741133 0.1439159 -0.9880301 0.05554002 0.1457507 -0.9880094 0.05093395 0.1509819 -0.9868179 0.05826568 0.1495308 -0.9879585 0.03972846 0.1182088 -0.9880316 0.09909695 0.1221508 -0.9859036 0.1143385 0.1260933 -0.9883234 0.08554059 0.130522 -0.9882739 0.07923877 0.1360759 -0.9863887 0.09230768 0.1361087 -0.9882507 0.06953412 0.08863204 -0.9876938 0.1288611 0.09055209 -0.9881958 0.1235689 0.08453983 -0.9311608 0.3546721 0.0917856 -0.9874578 0.1284623 0.06794732 -0.9880939 0.1380349 0.0650655 -0.9875378 0.1433026 0.09286516 -0.98763 0.1263449 0.1657912 -0.8619902 0.4790471 0.1647779 -0.898858 0.4060823 0.1503495 -0.898773 0.4118277 0.1868916 -0.9060475 0.3796702 0.2479745 -0.890026 0.3825735 0.2490654 -0.8900064 0.3819094 0.2479686 -0.8900223 0.3825859 0.2547507 -0.8932644 0.3703792 0.3292327 -0.882529 0.3357802 0.1051055 -0.9873806 0.1184585 0.3131664 -0.8816754 0.3529522 0.329196 -0.8825312 0.3358107 0.4893957 -0.7717283 0.4061124 0.4848953 -0.7741685 0.4068658 0.4682121 -0.799272 0.3767514 0.4167628 -0.7633278 0.4935985 0.5755565 -0.739273 0.3495858 0.5785055 -0.7326779 0.3584889 0.5785121 -0.7326776 0.3584789 0.7135567 -0.6622782 0.2285264 0.713543 -0.6622856 0.2285479 0.6533309 -0.6953451 0.2994229 0.6531362 -0.6959241 0.2985011 0.6531396 -0.6959239 0.2984941 0.8965121 -0.1359837 0.4216331 0.7983472 -0.5336249 0.2790813 0.856642 -0.4635729 0.226417 0.8566367 -0.4635731 0.2264363 0.8559987 -0.4652984 0.2253081 0.8865303 -0.4395042 0.144568 0.886532 -0.439504 0.1445578 0.8889645 -0.4534753 0.06404817 0.8253657 -0.5544851 0.1063849 0.1759823 -0.9831129 -0.0501908 0.4245856 -0.9053862 0.001742124 0.4245846 -0.9053866 0.001741886 0.4167602 -0.7633276 0.493601 0.299499 -0.8851964 0.3559883 0.356647 -0.8850136 0.2992553 0.3565713 -0.8851569 0.2989214 0.3973162 -0.8853825 0.2413249 0.3972582 -0.8854501 0.241172 0.4222945 -0.8855563 0.1935384 0.4222555 -0.8855919 0.1934617 0.4383547 -0.8856465 0.1532173 0.4383305 -0.8856649 0.1531789 0.4489796 -0.8856945 0.1181637 0.2895534 -0.953765 -0.08056783 0.4275546 -0.9021631 -0.05743509 0.8965202 -0.1359845 0.4216156 0.6623643 -0.6799793 0.3144865 0.6918186 -0.6803672 0.2418417 0.6918001 -0.6803996 0.2418037 0.7086508 -0.6804577 0.1865245 0.7086372 -0.6804783 0.1865011 0.728181 -0.6790735 0.0927996 0.4275555 -0.9021627 -0.05743479 0.8469735 -0.5066244 -0.1611448 0.8743304 -0.4817103 -0.05917376 0.8991669 -0.377345 -0.2216072 0.8762512 -0.4789136 -0.05315625 0.9061368 -0.3661369 -0.2118017 0.9147752 -0.3809568 0.1343806 0.9972808 -0.02832925 0.06803232 -0.9959694 -0.08965331 0.002684712 0.9997357 -0.01981872 0.01165807 0.9957063 -0.08000922 0.04655718 0.9957073 -0.07999908 0.04655128 0.9956861 -0.08019232 0.04667276 0.9984038 -0.04811227 0.0295841 0.996766 -0.07474505 0.02951127 0.9876172 -0.1357461 0.07864654 0.9876104 -0.1357835 0.07866656 0.9940995 -0.09371668 0.05462032 0.9920969 -0.1084313 0.06313848 0.9876143 -0.1357618 0.07865434 0.9969496 -0.06996589 0.0345875 0.9969531 -0.06993079 0.03455954 0.996953 -0.06993228 0.03456038 0.9758583 -0.1799764 0.1237292 0.9858402 -0.1597684 0.05092287 0.9540298 -0.2187259 0.2049046 0.9661996 -0.2344287 0.1072451 0.9661998 -0.2344286 0.1072443 0.9534019 -0.2653543 0.1435685 0.9456323 -0.2836021 0.1592148 0.937359 -0.3016896 0.1741881 0.9788641 -0.1777869 0.1010785 0.9788661 -0.1777788 0.1010745 0.9603464 -0.2448254 0.133399 0.9427632 -0.2866256 0.170421 0.9502828 -0.2671173 0.1600347 0.9583901 -0.243922 0.1482921 0.9583914 -0.243918 0.1482901 0.9689183 -0.2094764 0.1315932 0.9689193 -0.2094734 0.1315919 0.9790033 -0.168732 0.1143767 0.979003 -0.1687337 0.1143774 0.9246988 -0.3373386 0.1764509 0.9908056 -0.1075484 0.08208304 0.9257258 -0.337897 0.1698742 0.9603447 -0.2448308 0.1334014 0.9300174 -0.3167182 0.1864332 0.9210763 -0.3355656 0.1975204 0.8648052 -0.4339461 0.2525923 0.7890198 -0.5293526 0.311823 0.8028922 -0.5140943 0.3017802 0.8028846 -0.5141027 0.3017858 0.8028737 -0.5141152 0.3017937 0.877434 -0.4130897 0.2438576 0.8774194 -0.4131129 0.2438706 0.8648045 -0.4339471 0.2525929 0.8648084 -0.4339411 0.2525898 0.9366065 -0.2975013 0.1850983 0.9365989 -0.2975193 0.1851075 0.6999908 -0.6184322 0.3571476 0.5917611 -0.6947134 0.4088913 0.5113818 -0.7398065 0.4372357 0.5916059 -0.6944422 0.4095761 0.6999985 -0.6184263 0.3571429 0.7936005 -0.5344316 0.2908284 0.6194613 -0.6721316 0.4055945 0.6194486 -0.6721394 0.4056012 0.7132433 -0.6036221 0.3562645 0.7132356 -0.6036286 0.3562688 0.8033612 -0.5130831 0.3022525 0.6060993 -0.7202552 0.3374555 0.4776599 -0.7685054 0.4257235 0.3490775 -0.8070949 0.4761751 0.3733901 -0.7875156 0.4903049 0.4160957 -0.7787897 0.4694156 0.4495151 -0.7698437 0.4530749 0.4045723 -0.7928336 0.4557808 0.3615788 -0.8130621 0.4562793 0.4032546 -0.7861185 0.4684051 0.4032577 -0.786117 0.4684048 0.5242232 -0.7193512 0.4557673 0.2716142 -0.8304599 0.4863765 0.2877436 -0.8264153 0.4839848 0.2739288 -0.8303603 0.4852473 0.4032937 -0.7861021 0.4683989 0.4032205 -0.7861334 0.4684096 0.515609 -0.8374252 -0.181291 0.5156405 -0.8373891 -0.1813678 0.07892841 -0.8481816 0.5237923 0.07887345 -0.848168 0.5238227 0.07894974 -0.8481859 0.523782 0.1081576 -0.8519164 0.5123869 0.1248466 -0.8527354 0.5072038 0.2723602 -0.8302782 0.4862696 0.2228687 -0.8424538 0.490511 0.1926078 -0.8498942 0.4904917 0.1247921 -0.8527351 0.5072178 0.1704377 -0.8493356 0.49958 0.1704378 -0.8493355 0.49958 0.178116 -0.8466941 0.5013818 0.302389 -0.7972885 0.5223906 0.3044213 -0.7961723 0.5229125 -0.08702826 -0.8542737 0.5124866 -0.08597397 -0.8544471 0.5123755 0.0169807 -0.8654602 0.50069 -0.03357702 -0.8579177 0.5126888 0.003751337 -0.8583815 0.5129984 -0.03134423 -0.8579678 0.5127462 0.01602172 -0.8582696 0.5129491 0.1088403 -0.8848709 0.4529429 -0.1855779 -0.8450046 0.5015258 -0.1855777 -0.8450046 0.5015257 -0.1197279 -0.8557372 0.5033677 -0.3104764 -0.7937916 0.5229717 -0.3113203 -0.7933413 0.5231531 -0.2024152 -0.8385878 0.5057654 -0.2022967 -0.8386303 0.5057424 -0.08635139 -0.8543887 0.5124094 -0.05467331 -0.8607801 0.5060321 -0.09660845 -0.857881 0.5046851 -0.2489771 -0.8359687 0.4890468 -0.1960195 -0.848654 0.4912868 -0.2128072 -0.840038 0.4990484 -0.1341816 -0.8627285 0.4875395 -0.1959733 -0.8486657 0.491285 -0.41027 -0.7843047 0.4653437 -0.294977 -0.8243356 0.4831764 -0.29492 -0.8243507 0.4831853 -0.2956406 -0.8241587 0.4830724 -0.2949922 -0.8243551 0.4831339 -0.4102366 -0.7843185 0.46535 -0.4103046 -0.7842898 0.4653382 -0.3833377 -0.8030382 0.4562693 -0.5292518 -0.7188422 0.4507312 -0.4102827 -0.7842987 0.4653425 -0.4131008 -0.7796037 0.4707077 -0.3702512 -0.7880964 0.49175 -0.5954136 -0.7258704 0.344376 -0.7176699 -0.5996567 0.3540649 -0.7176908 -0.5996387 0.3540528 -0.6242385 -0.6690374 0.4033799 -0.6242212 -0.6690481 0.4033889 -0.781738 -0.5460633 0.3011652 -0.684098 -0.6306321 0.3664875 -0.4263736 -0.7820375 0.454558 -0.4493618 -0.7699638 0.453023 -0.5174556 -0.7375189 0.4339417 -0.5815981 -0.7007554 0.4131413 -0.5815805 -0.700766 0.4131478 -0.9357379 -0.2989259 0.1871843 -0.8745144 -0.4174672 0.2468717 -0.8745129 -0.4174696 0.246873 -0.8022906 -0.5148407 0.3021073 -0.8022785 -0.5148546 0.3021159 -0.7777386 -0.5415046 0.3192106 -0.8030303 -0.5132924 0.302776 -0.8030056 -0.5133212 0.302793 -0.9357447 -0.2989097 0.187176 -0.8564602 -0.4465476 0.2589812 -0.8564761 -0.4465239 0.2589691 -0.9364275 -0.30394 0.175283 -0.9655609 -0.2211058 0.1371284 -0.9766687 -0.179304 0.1181871 -0.9766664 -0.1793141 0.1181912 -0.9766671 -0.1793113 0.1181899 -0.9563132 -0.250196 0.1512187 -0.9563124 -0.2501983 0.1512198 -0.9476779 -0.2740868 0.1636549 -0.8564673 -0.4465368 0.2589758 -0.9135614 -0.3505888 0.2061389 -0.9290084 -0.319006 0.1875596 -0.9426127 -0.2870417 0.170553 -0.9851364 -0.1377346 0.1026424 -0.9188048 -0.3536177 0.1753638 -0.9546574 -0.2620456 0.1412842 -0.9546692 -0.2620104 0.1412708 -0.9546733 -0.2619982 0.1412652 -0.9756789 -0.190648 0.1081851 -0.9451747 -0.2849362 0.1595497 -0.9569132 -0.2568318 0.1354788 -0.9671699 -0.2345727 0.09776544 -0.9660485 -0.1167308 0.2304868 -0.950558 -0.2485383 0.1861941 -0.9817569 -0.1642509 0.09578615 -0.9871603 -0.1376287 0.08107256 -0.9821104 -0.160135 0.0990749 -0.9756781 -0.1906511 0.1081867 -0.9860261 -0.1440253 0.0837208 -0.9860262 -0.1440253 0.0837208 -0.9910023 -0.1154538 0.06771183 -0.9910023 -0.1154538 0.06771183 -0.9910036 -0.1154451 0.06770682 -0.9980148 -0.05493509 0.03079915 -0.9865446 -0.1415691 0.08177882 -0.9975334 -0.06223261 0.03246891 -0.9982997 -0.05024236 0.02955418 -0.9986516 -0.0444957 0.02674025 -0.9926173 -0.1045407 0.06149917 -0.9926235 -0.1044971 0.06147378 -0.9980975 -0.05313891 0.03126335 -0.9953873 -0.08269 0.04864603 -0.9973654 -0.06626206 0.02952367 -0.4716407 -0.7706385 0.4285691 -0.2897732 -0.8198134 0.4939002 -0.3384489 -0.8104203 0.4781959 -0.2777355 -0.8274042 0.4881242 -0.2771292 -0.8275551 0.4882128 -0.2296745 -0.8370324 0.4966149 -0.1676488 -0.8427515 0.5115308 -0.167654 -0.8427513 0.5115294 -0.06446593 -0.8579354 0.5096969 -0.2055467 -0.8537955 0.4783134 -0.08814692 -0.8501426 0.5191221 -0.2038861 -0.8445537 0.495136 -0.344133 -0.8294218 0.4400362 0.2250742 -0.8382854 0.4966076 0.2751041 -0.8285973 0.4875903 0.3491341 -0.8076154 0.4752503 0.2923927 -0.8189345 0.4938145 0.2903216 -0.8192873 0.494451 -0.02186292 -0.8613632 0.5075191 -0.06814211 -0.8595653 0.5064623 -0.06444442 -0.859777 0.506587 0 -0.8619188 0.5070464 0.07537871 -0.8598753 0.5049084 0 -0.8514108 0.5244995 0.001728832 -0.8516626 0.5240877 0.005848526 -0.8522427 0.5231139 0.02584362 -0.854722 0.5184422 0.216821 -0.8538239 0.4732583 0.08578848 -0.8500373 0.5196893 0.2148907 -0.8436052 0.4920898 0.3556692 -0.8285369 0.4324653 0.1637879 -0.84342 0.5116798 0.163798 -0.8434198 0.511677 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 3.64303e-5 -1 -1.30327e-4 -6.11332e-6 -1 9.35431e-7 2.37239e-7 -1 2.22058e-7 4.76296e-6 -1 -2.19025e-7 0 -1 0 0 -1 0 0 -1 0 -9.09025e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -9.74926e-6 -1 5.09068e-6 -1.39767e-5 -1 6.75917e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 2.30003e-7 -1 0 -4.279e-5 -1 -1.13458e-6 -1.21538e-5 -1 0 -1.54556e-5 -1 3.62795e-5 -1.2653e-5 -1 2.93081e-5 0 -1 0 1.87009e-5 -1 -5.4304e-6 1.32861e-5 -1 -3.72012e-6 3.24968e-6 -1 -7.94118e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.06783217 -0.9881218 0.1378921 -0.8905193 -0.204984 0.4061489 -0.4030454 -0.9090104 0.1060864 -0.614673 -0.7778151 0.1310747 -0.5014328 -0.8568133 0.1201501 -0.3838491 -0.9196926 0.0826174 -0.3838456 -0.9196941 0.08261615 -0.3840905 -0.9195868 0.08267199 -0.619649 -0.7782743 0.1016077 -0.6196385 -0.7782832 0.1016048 -0.6196388 -0.7782828 0.1016049 -0.7899492 -0.5973765 0.1382805 -0.8882994 -0.4346262 0.1484054 -0.9112979 -0.3769648 0.165631 -0.911295 -0.3769713 0.1656318 -0.885415 -0.4277129 0.181939 -0.7899568 -0.5973671 0.1382778 -0.7899615 -0.5973607 0.1382787 -0.8882977 -0.4346265 0.1484152 -0.8530978 -0.4709507 0.2245656 -0.8572158 -0.4596151 0.2322394 -0.9234509 -0.2073601 0.3228628 -0.7826623 -0.5534577 0.2848233 -0.8572153 -0.4596151 0.2322412 -0.7120812 -0.6639859 0.228174 -0.6548308 -0.6936522 0.3000721 -0.580129 -0.7339683 0.3531869 -0.5801392 -0.7339676 0.3531715 -0.5797522 -0.7347828 0.3521103 -0.6530963 -0.6984658 0.2925932 -0.6531052 -0.6984653 0.2925746 -0.4427766 -0.7265876 0.5253755 -0.442786 -0.7265884 0.5253666 -0.446685 -0.8123988 0.3748075 -0.497545 -0.7664713 0.4061658 -0.4975613 -0.7664623 0.406163 -0.2524425 -0.8908944 0.3775974 -0.2529078 -0.8908845 0.3773097 -0.2557843 -0.8924137 0.3717154 -0.2528949 -0.8908832 0.3773213 -0.1874364 -0.9053646 0.3810284 -0.1624347 -0.8983459 0.4081539 -0.162434 -0.898346 0.4081542 -0.1122711 -0.9137496 0.3904571 -0.1021209 -0.9138238 0.3930616 -0.009096622 -0.9997659 0.01963168 -0.1241925 -0.9855629 0.1150735 -0.06911802 -0.9849612 0.1583483 -0.1129863 -0.9127167 0.3926606 -0.1120554 -0.9881101 0.1052711 -0.1051555 -0.9873621 0.1185681 -0.09159904 -0.9881113 0.1234735 -0.08915424 -0.9875552 0.1295623 -0.06565046 -0.9877144 0.1418102 -0.06570076 -0.9877154 0.1417807 -0.1120622 -0.98811 0.1052643 -0.1236805 -0.9868898 0.1036897 -0.1256494 -0.9882199 0.08737152 -0.1448287 -0.9872298 0.06634795 -0.1347512 -0.9883733 0.07043051 -0.1302224 -0.9883282 0.07905405 -0.1485344 -0.9858554 0.07763051 -0.1256494 -0.9882198 0.08737152 -0.1500099 -0.9878557 0.04047203 -0.1500089 -0.9878558 0.0404753 -0.1504735 -0.9872142 0.05259114 -0.1438655 -0.9880482 0.05534929 -0.143866 -0.9880481 0.05534803 -0.3838563 -0.9196894 0.08261895 -0.1467115 -0.9884136 0.03891128 -0.151812 -0.9876073 0.03981053 -0.1472483 -0.9884521 0.03578102 -0.01291841 -0.9999137 0.002412736 -0.789949 -0.5973768 0.1382806 -0.7136862 -0.6806688 0.1653541 -0.7086633 -0.6804388 0.1865453 -0.7086827 -0.6804218 0.1865339 -0.6918115 -0.6803624 0.2418755 -0.6918488 -0.6803309 0.2418578 -0.6659198 -0.6801978 0.3064012 -0.7120946 -0.6639785 0.2281535 -0.3791174 -0.9187593 0.1102329 -0.4504873 -0.8855663 0.1132852 -0.4383836 -0.8856263 0.1532509 -0.4384322 -0.8856052 0.153234 -0.4223141 -0.8855505 0.1935228 -0.4223926 -0.8855172 0.1935036 -0.3972784 -0.8854101 0.2412855 -0.3974305 -0.8853467 0.2412679 -0.3564956 -0.8851166 0.2991309 -0.3568212 -0.88498 0.2991473 -0.2991201 -0.8851517 0.3564178 -0.3132992 -0.8815048 0.3532603 -0.3337587 -0.8825345 0.3312674 -0.3337199 -0.8825371 0.3312997 -0.9944299 -0.1049468 -0.00975281 -0.9486987 -0.3046261 0.08469718 -0.9020021 -0.431396 0.01702076 -0.9020029 -0.4313943 0.01702183 -0.9491068 -0.3073958 0.06858652 -0.9635241 -0.2649139 0.0379728 -0.9731504 -0.2254975 0.04614204 -0.9682228 -0.2376245 0.07796901 -0.9682255 -0.2376174 0.07795608 -0.9781493 -0.195549 0.07060098 -0.9944302 -0.1049451 -0.00975579 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.5697836 -0.8216499 -0.01543343 -0.2181239 -0.974781 0.04715877 -0.3445591 -0.9068721 0.2426147 -0.3478806 -0.9076653 0.2347823 -0.304488 -0.918893 0.2508435 -0.3531411 -0.9095648 0.219051 -0.344367 -0.9068145 0.2431024 -0.3444693 -0.9068484 0.2428311 -0.4401198 -0.8869467 0.1400721 -0.3604757 -0.9087237 0.2104246 -0.3604679 -0.9087235 0.2104388 -0.5499003 -0.8346579 0.03091996 -0.5000185 -0.85116 0.1597123 -0.5109359 -0.8569807 0.06729584 -0.4285371 -0.8860835 0.1766691 -0.4284425 -0.8860731 0.1769506 -0.701288 -0.7091495 0.07281368 -0.7012909 -0.7091493 0.07279032 -0.7016826 -0.7093089 0.0672487 -0.6580872 -0.7528918 -0.008674383 -0.5782262 -0.8073994 0.1173054 -0.5782277 -0.8073999 0.1172947 -0.05162829 -0.9986461 0.006376564 -0.06312692 -0.9980039 0.001795828 -0.06312692 -0.9980039 0.001795828 -0.04568213 -0.9988654 0.01345431 -0.07024437 -0.9970094 0.03221714 -0.1227388 -0.9903255 0.06473577 -0.1227329 -0.9903265 0.06473237 -0.009765803 -0.9999217 0.007816195 -0.02017766 -0.9997328 0.01127946 -0.01749205 -0.9997137 0.01632839 -0.03112673 -0.999364 0.01740092 -0.04568243 -0.9988654 0.01345348 -0.2182819 -0.9755008 0.02740824 -0.2181335 -0.974779 0.04715585 -0.2497245 -0.9677932 0.03184366 -0.252086 -0.9665463 -0.04733854 -0.1343599 -0.9884866 0.06958329 -0.1197717 -0.9926913 0.01479226 -0.1165834 -0.9922133 0.0438295 -0.07912927 -0.9968164 0.009773552 -0.07912957 -0.9968164 0.009771943 -0.7887772 -0.6134596 0.03870356 -0.7459284 -0.6656417 -0.02262431 -0.7885911 -0.6133643 -0.04368525 -0.5694246 -0.8211296 0.03875207 -0.3387728 -0.9168475 0.211243 -0.1293936 -0.9849086 0.1149448 -0.1355692 -0.9853297 0.1036654 -0.2116185 -0.9759247 0.05280774 -0.1924623 -0.9748331 0.1125099 -0.287927 -0.9575134 0.01631814 -0.2707019 -0.9565657 0.1081784 -0.3629233 -0.9317642 -0.01010936 -0.3506425 -0.9310645 0.1008402 -0.4975602 -0.8664844 -0.04048329 -0.4949625 -0.8673929 0.05139756 -0.5697846 -0.8216491 -0.01543378 -0.3908503 -0.919604 0.03955471 -0.3907201 -0.9196896 0.03884261 -0.3907152 -0.9196918 0.03883987 -0.3907124 -0.9196932 0.03883415 -0.1636382 -0.9718987 -0.16922 -0.3741024 -0.9171036 0.1377258 -0.4103977 -0.8981286 0.1579197 -0.1188995 -0.7062043 -0.6979529 -0.1769472 -0.9689156 -0.1728936 -0.177006 -0.968904 -0.1728984 -0.9921268 -0.1208057 -0.03302204 -0.9985995 -0.02308541 0.04760402 -0.9930485 -0.1171145 0.01178723 -0.9875346 -0.1573852 0.002298235 -0.9755641 -0.2196989 -0.002676665 -0.9599646 -0.279668 0.01593232 -0.9599631 -0.2796729 0.01593261 -0.9562727 -0.2917596 0.02046948 -0.9755638 -0.2196998 -0.002676665 -0.9988925 0.04631203 0.008311033 -0.9985998 0.05179506 0.01075255 -0.9994689 -0.02550476 -0.02028417 -0.9032726 0.4233746 0.06965929 -0.933836 0.3556059 0.03866368 -0.9825936 0.1833052 -0.03015089 -0.9608556 0.2733088 0.04537278 -0.9608557 0.2733085 0.04537266 -0.9790439 0.2023671 0.02281761 -0.9915826 0.1294597 0.002020776 -0.9915828 0.1294583 0.002020776 -0.9600028 0.2795431 -0.01582014 -0.960003 0.2795423 -0.01582038 -0.9600025 0.2795444 -0.01581978 -0.8644245 0.5027613 -0.00118488 -0.9248697 0.3802822 -0.001188576 -0.8739063 0.4843896 -0.04067689 -0.8644243 0.5027616 -0.00118494 -0.7644602 0.64428 -0.02244788 -0.7644599 0.6442806 -0.02244806 -0.7771168 0.6293526 0.002183258 -0.7771235 0.6293445 0.002183496 -0.8461701 0.5324369 0.0225203 -0.8978373 0.438292 0.04228854 -0.8978406 0.4382849 0.04229032 -0.684818 0.7284182 -0.02076274 -0.6266484 0.7792702 -0.007065892 -0.5320667 0.8466985 0.002589523 -0.5320693 0.8466968 0.002589344 -0.4274048 0.9040363 -0.006606578 -0.5455376 0.837894 0.01795107 -0.6219403 0.7830644 -6.80637e-4 -0.6780891 0.7349795 -6.78306e-4 -0.622371 0.7827224 7.72648e-5 -0.7046697 0.7095355 -8.74763e-6 -0.1608138 0.9867973 0.01923567 -0.1645852 0.9862089 0.01743012 -0.5040952 0.8501486 -0.1521037 -0.1712386 0.9848092 0.02878129 -0.1812981 0.9831416 0.02374041 -0.3798658 0.9233455 -0.05599099 -0.5772153 0.799472 -0.1663342 -0.2705082 0.962639 0.01230669 -0.2705109 0.9626383 0.01230561 -0.3522289 0.9359042 0.004265069 -0.4419841 0.897019 -0.002633631 -0.4233621 0.9059568 -0.002631902 -0.441259 0.8973715 -0.00385642 -0.4412565 0.8973727 -0.003856718 -0.9599639 -0.2796702 0.01593232 -0.955217 -0.2957324 0.01013875 -0.8923606 -0.4510778 -0.01487737 -0.920133 -0.3913531 0.01407009 -0.9122332 -0.409583 0.008502244 -0.8984004 -0.4391691 0.002736508 -0.8984017 -0.439166 0.002736866 -0.8771386 -0.4802374 1.05298e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.09491479 -0.00305742 -0.9954807 -0.5409931 -0.004862487 -0.841013 -0.7813409 0.003680646 -0.6240935 -0.7070958 -0.004752933 -0.7071019 -0.54948 0.0826776 -0.8314061 -0.6757109 0.0371266 -0.7362312 -0.8689906 -6.63241e-4 -0.4948284 -0.8691402 -6.64828e-4 -0.4945656 -0.9659261 -6.42815e-4 -0.2588173 -0.8800741 0.08852058 -0.4665123 -0.9404243 0.03842931 -0.3378244 0.08474004 -0.003057599 -0.9963984 -0.07949721 0.00186479 -0.9968334 -0.2587714 0.02148419 -0.9656997 -0.2425616 0.02723085 -0.9697538 -0.3977141 0.004725217 -0.9174973 0.4012866 -7.65825e-4 -0.9159522 0.2587223 0.0290054 -0.9655162 0.2480214 0.02621179 -0.9684 0.08482122 -0.00306034 -0.9963915 0.8989402 -0.002989768 -0.4380611 0.898325 -0.002988338 -0.4393214 0.8063488 0.002891302 -0.5914333 0.6874367 0.02844339 -0.7256871 0.7069731 0.01921457 -0.7069793 0.5512045 3.78297e-4 -0.8343701 0.4022562 -7.65827e-4 -0.9155268 0.8989521 -0.002988338 -0.4380368 0.9656751 0.02280431 -0.2587502 0.9632233 0.02504909 -0.2675321 0.8968107 -0.002736508 0.4424058 0.9582821 0.01479822 0.2854405 0.9657356 0.01980096 0.2587714 0.9940322 0 0.1090869 0.9936402 0 -0.1126014 0.5544232 5.95633e-4 0.8322347 0.6730956 0.007826268 0.7395141 0.7840743 0.03476637 0.6196925 0.7070971 0.00679177 0.707084 0.8967837 -0.002737343 0.4424607 0.89622 -0.002737343 0.4436015 0.05885124 4.79931e-4 0.9982666 -0.07846319 -9.18571e-4 0.9969165 0.1945 0.006005108 0.9808841 0.305142 0.02089601 0.9520775 0.2587882 0.01388734 0.9658342 0.4272588 -0.001098155 0.9041286 0.4271793 -0.001098155 0.9041663 -0.3265648 0.02187252 0.9449217 -0.258805 0.007956624 0.9658969 -0.2054049 0.009089529 0.9786348 -0.07838404 -9.19428e-4 0.9969229 -0.09789055 -9.18391e-4 0.9951968 -0.5990115 5.52722e-4 0.8007402 -0.4689778 -1.99412e-4 0.88321 -0.4693831 -1.99412e-4 0.8829946 -0.8562236 -0.003491282 0.5165936 -0.8568177 -0.003489673 0.5156077 -0.7071092 -0.003387153 0.7070962 -0.8348124 0.05233567 0.5480414 -0.7292709 0.01959174 0.6839444 -0.979725 0.01364195 -0.1998821 -0.9964048 0 -0.08472019 -0.9659249 0 0.2588222 -0.9888616 0.03953701 0.14349 -0.9433013 0.007185339 0.3318602 0.4688849 0.8818953 0.04906684 0.4688662 0.881906 0.04905503 0.468917 0.8818756 0.04911464 0.5673341 0.8230941 0.02546066 0.5673396 0.8230904 0.02545696 0.6280626 0.7779004 0.02021044 0.8070184 0.4440832 0.3892449 0.757739 0.5637625 0.3286389 0.8292468 0.4505569 0.3306785 0.7697783 0.557722 0.3104634 0.8214016 0.5022804 0.2702109 0.8070228 0.5881546 0.05280542 0.6280604 0.777902 0.0202139 0.6672881 0.7186818 0.1955071 0.8825233 0.4376595 -0.1720664 0.882523 0.4376531 -0.1720838 0.5673713 0.8230699 0.02541017 0.6672785 0.7186923 0.1955013 0.6525968 0.7469986 -0.1269268 0.5673835 0.8230621 0.02539116 0.4688819 0.8818976 0.0490548 0.2497694 0.9320418 -0.2625133 0.2497547 0.9320321 -0.2625621 0.3034673 0.7282294 0.6144832 0.3034861 0.7281638 0.6145516 0.1212551 0.8602593 0.4952285 0.1141309 0.8594243 0.4983614 0.1207444 0.8563225 0.5021278 0.004999101 0.5887003 0.808336 0.8583942 0.5129908 1.42056e-6 0.8081489 0.5889752 0.001883983 0.777737 0.6285751 -0.004317343 0.6281873 0.7780591 0.002195119 0.7776917 0.6285294 0.01209878 0.5961139 0.8028874 0.004468441 0.6281846 0.7780515 0.004477441 0.5961181 0.8028962 -9.49849e-4 0.3850328 0.9229024 9.67345e-4 0.3751596 0.9269602 -3.31847e-4 0.3850293 0.9229042 -3.31335e-4 0.3751556 0.9269615 -8.16339e-4 0.139365 0.9902407 7.84791e-4 0.375163 0.9269231 0.00813657 0.1393646 0.9902408 8.15185e-4 0.1281712 0.9917515 -0.001064598 0.006358742 0.9999797 0 -0.2183669 -0.9758667 1.85209e-7 -0.1660203 -0.9860785 -0.009302556 -0.2183666 -0.9758206 -0.009500324 -0.1660206 -0.9860484 -0.01207411 -0.218348 -0.975796 -0.01209127 -0.415611 -0.9095374 0.003035783 -0.5698373 -0.8217273 -0.007057368 -0.5075855 -0.8615726 -0.007037997 -0.5698345 -0.8217211 -0.007941246 -0.6188017 -0.7855471 -5.10419e-4 -0.5698527 -0.8217468 -5.27969e-4 -0.6188039 -0.7855438 0.001649618 -0.789358 -0.6139307 -0.001806437 -0.7957454 -0.6056286 -0.001829504 -0.7893649 -0.6139225 -0.001511394 -0.7957453 -0.6056315 2.97149e-6 -0.6326785 -0.7744129 -0.001580655 -0.6326668 -0.7744225 -0.001568913 -0.7457234 -0.585567 0.3178175 -0.6166776 -0.7828266 0.08301436 -0.6166651 -0.7828348 0.08302789 -0.465675 -0.7899813 0.3988437 -0.7954781 -0.6054334 0.02578777 -0.8264132 -0.5620133 0.03438782 -0.7944784 -0.6046704 0.05637335 -0.7996023 -0.5965079 0.0693888 -0.7995998 -0.5965112 0.06938683 -0.8873435 -0.456282 0.06654554 -0.9115859 -0.3769848 0.1639928 -0.8573388 -0.4934886 0.1464217 -0.897819 -0.375596 0.2298885 -0.6404872 -0.767768 -0.01755976 -0.6393734 -0.7559177 -0.1406772 -0.7457239 -0.5855661 0.3178178 -0.6326714 -0.7744189 -0.001576542 -0.514137 -0.8568152 0.03912305 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 1 0 2 0 2 1 1 1 3 1 4 2 5 2 1 2 1 3 5 3 6 3 7 4 8 4 9 4 9 5 8 5 10 5 11 6 12 6 13 6 14 7 15 7 16 7 12 8 11 8 1 8 1 9 11 9 17 9 1 10 17 10 4 10 6 11 18 11 1 11 1 12 18 12 19 12 1 13 19 13 3 13 0 14 20 14 1 14 1 15 20 15 9 15 1 16 9 16 21 16 21 17 9 17 10 17 13 18 22 18 11 18 11 19 22 19 14 19 11 20 14 20 23 20 23 21 14 21 16 21 7 22 24 22 8 22 8 23 24 23 25 23 8 24 25 24 26 24 27 25 28 25 29 25 27 26 29 26 30 26 28 27 27 27 31 27 31 28 27 28 32 28 31 29 32 29 33 29 33 30 32 30 34 30 34 31 32 31 35 31 34 32 35 32 36 32 37 33 38 33 39 33 39 34 38 34 40 34 39 35 40 35 35 35 35 36 40 36 41 36 35 37 41 37 36 37 37 38 39 38 42 38 42 39 39 39 43 39 42 40 43 40 44 40 44 41 43 41 45 41 45 42 43 42 46 42 45 43 46 43 47 43 47 44 46 44 48 44 48 45 46 45 49 45 48 46 49 46 50 46 51 47 52 47 49 47 49 48 52 48 53 48 49 49 53 49 50 49 54 50 55 50 51 50 51 51 55 51 56 51 51 52 56 52 52 52 57 53 58 53 54 53 54 54 58 54 59 54 54 55 59 55 55 55 60 56 61 56 57 56 57 57 61 57 62 57 57 58 62 58 58 58 63 59 64 59 65 59 65 60 64 60 66 60 65 61 66 61 60 61 60 62 66 62 67 62 60 63 67 63 61 63 63 64 65 64 68 64 68 65 65 65 69 65 68 66 69 66 70 66 70 67 69 67 71 67 71 68 69 68 72 68 71 69 72 69 73 69 74 70 75 70 76 70 76 71 75 71 77 71 76 72 77 72 72 72 72 73 77 73 78 73 72 74 78 74 73 74 74 75 76 75 79 75 79 76 76 76 80 76 79 77 80 77 81 77 81 78 80 78 82 78 82 79 80 79 83 79 82 80 83 80 84 80 84 81 83 81 85 81 85 82 83 82 86 82 85 83 86 83 87 83 87 84 86 84 88 84 88 85 86 85 89 85 88 86 89 86 90 86 90 87 89 87 91 87 91 88 89 88 92 88 91 89 92 89 93 89 94 90 95 90 92 90 92 91 95 91 96 91 92 92 96 92 93 92 97 93 98 93 94 93 94 94 98 94 99 94 94 95 99 95 95 95 100 96 101 96 102 96 102 97 101 97 103 97 102 98 103 98 97 98 97 99 103 99 104 99 97 100 104 100 98 100 100 101 102 101 105 101 105 102 102 102 106 102 105 103 106 103 107 103 108 104 109 104 106 104 106 105 109 105 110 105 106 106 110 106 107 106 111 107 112 107 108 107 108 108 112 108 113 108 108 109 113 109 109 109 29 110 114 110 30 110 30 111 114 111 115 111 30 112 115 112 111 112 111 113 115 113 116 113 111 114 116 114 112 114 117 115 118 115 119 115 120 116 121 116 122 116 123 117 124 117 125 117 126 118 127 118 128 118 129 119 130 119 131 119 132 120 133 120 134 120 135 121 136 121 137 121 138 122 139 122 140 122 141 123 142 123 143 123 116 124 115 124 144 124 107 125 110 125 145 125 96 126 95 126 146 126 90 127 91 127 147 127 81 128 82 128 148 128 74 129 79 129 149 129 78 130 77 130 150 130 71 131 73 131 151 131 66 132 64 132 152 132 59 133 58 133 153 133 53 134 52 134 154 134 48 135 50 135 155 135 44 136 45 136 156 136 37 137 42 137 157 137 41 138 40 138 158 138 33 139 34 139 159 139 31 140 142 140 28 140 28 141 142 141 141 141 28 142 141 142 29 142 29 143 141 143 114 143 34 144 36 144 160 144 160 145 36 145 41 145 40 146 38 146 161 146 61 147 67 147 162 147 68 148 70 148 163 148 87 149 139 149 85 149 85 150 139 150 138 150 85 151 138 151 84 151 164 152 88 152 90 152 91 153 93 153 165 153 98 154 104 154 135 154 135 155 104 155 103 155 135 156 103 156 136 156 136 157 103 157 101 157 136 158 101 158 100 158 166 159 105 159 107 159 110 160 109 160 167 160 167 161 109 161 113 161 113 162 112 162 168 162 168 163 112 163 116 163 144 164 115 164 169 164 170 165 143 165 171 165 171 166 143 166 142 166 171 167 142 167 159 167 159 168 142 168 31 168 159 169 31 169 33 169 172 170 140 170 173 170 173 171 140 171 139 171 173 172 139 172 164 172 164 173 139 173 87 173 164 174 87 174 88 174 174 175 175 175 165 175 176 176 137 176 177 176 177 177 137 177 136 177 177 178 136 178 166 178 166 179 136 179 100 179 166 180 100 180 105 180 178 181 144 181 179 181 179 182 144 182 169 182 179 183 169 183 180 183 181 184 182 184 183 184 184 185 185 185 186 185 186 186 185 186 181 186 186 187 181 187 187 187 187 188 181 188 183 188 187 189 183 189 161 189 45 190 47 190 156 190 156 191 47 191 188 191 156 192 188 192 189 192 189 193 188 193 190 193 189 194 190 194 191 194 191 195 190 195 192 195 56 196 55 196 193 196 193 197 55 197 194 197 193 198 194 198 195 198 195 199 194 199 196 199 195 200 196 200 197 200 197 201 196 201 198 201 62 202 61 202 199 202 199 203 61 203 162 203 199 204 162 204 200 204 200 205 162 205 201 205 200 206 201 206 202 206 202 207 201 207 203 207 70 208 71 208 163 208 163 209 71 209 151 209 163 210 151 210 204 210 204 211 151 211 205 211 204 212 205 212 206 212 206 213 205 213 207 213 75 214 74 214 208 214 208 215 74 215 149 215 208 216 149 216 209 216 209 217 149 217 210 217 209 218 210 218 211 218 211 219 210 219 212 219 213 220 175 220 214 220 214 221 175 221 174 221 214 222 174 222 215 222 93 223 96 223 165 223 165 224 96 224 146 224 165 225 146 225 174 225 174 226 146 226 216 226 174 227 216 227 215 227 215 228 216 228 217 228 215 229 217 229 218 229 218 230 217 230 219 230 220 231 178 231 221 231 221 232 178 232 179 232 221 233 179 233 222 233 222 234 179 234 180 234 222 235 180 235 223 235 224 236 225 236 170 236 170 237 225 237 223 237 170 238 223 238 143 238 143 239 223 239 180 239 143 240 180 240 141 240 141 241 180 241 169 241 141 242 169 242 114 242 114 243 169 243 115 243 34 244 160 244 159 244 159 245 160 245 226 245 159 246 226 246 171 246 171 247 226 247 134 247 171 248 134 248 170 248 170 249 134 249 133 249 170 250 133 250 224 250 41 251 158 251 160 251 160 252 158 252 227 252 160 253 227 253 226 253 226 254 227 254 228 254 226 255 228 255 134 255 134 256 228 256 229 256 134 257 229 257 132 257 40 258 161 258 158 258 158 259 161 259 183 259 158 260 183 260 227 260 227 261 183 261 182 261 227 262 182 262 228 262 228 263 182 263 230 263 228 264 230 264 229 264 185 265 231 265 181 265 181 266 231 266 232 266 181 267 232 267 182 267 182 268 232 268 233 268 182 269 233 269 230 269 38 270 37 270 161 270 161 271 37 271 157 271 161 272 157 272 187 272 187 273 157 273 234 273 187 274 234 274 186 274 186 275 234 275 131 275 186 276 131 276 184 276 184 277 131 277 130 277 42 278 44 278 157 278 157 279 44 279 156 279 157 280 156 280 234 280 234 281 156 281 189 281 234 282 189 282 131 282 131 283 189 283 191 283 131 284 191 284 129 284 235 285 236 285 237 285 237 286 236 286 192 286 237 287 192 287 238 287 238 288 192 288 190 288 238 289 190 289 155 289 155 290 190 290 188 290 155 291 188 291 48 291 48 292 188 292 47 292 236 293 239 293 192 293 192 294 239 294 240 294 192 295 240 295 191 295 191 296 240 296 241 296 191 297 241 297 129 297 127 298 235 298 128 298 128 299 235 299 237 299 128 300 237 300 242 300 242 301 237 301 238 301 242 302 238 302 154 302 154 303 238 303 155 303 154 304 155 304 53 304 53 305 155 305 50 305 52 306 56 306 154 306 154 307 56 307 193 307 154 308 193 308 242 308 242 309 193 309 195 309 242 310 195 310 128 310 128 311 195 311 197 311 128 312 197 312 126 312 243 313 244 313 245 313 245 314 244 314 198 314 245 315 198 315 246 315 246 316 198 316 196 316 246 317 196 317 153 317 153 318 196 318 194 318 153 319 194 319 59 319 59 320 194 320 55 320 244 321 247 321 198 321 198 322 247 322 248 322 198 323 248 323 197 323 197 324 248 324 249 324 197 325 249 325 126 325 58 326 62 326 153 326 153 327 62 327 199 327 153 328 199 328 246 328 246 329 199 329 200 329 246 330 200 330 245 330 245 331 200 331 202 331 245 332 202 332 243 332 250 333 251 333 252 333 252 334 251 334 203 334 252 335 203 335 253 335 253 336 203 336 201 336 253 337 201 337 152 337 152 338 201 338 162 338 152 339 162 339 66 339 66 340 162 340 67 340 251 341 254 341 203 341 203 342 254 342 255 342 203 343 255 343 202 343 202 344 255 344 256 344 202 345 256 345 243 345 64 346 63 346 152 346 152 347 63 347 257 347 152 348 257 348 253 348 253 349 257 349 258 349 253 350 258 350 252 350 252 351 258 351 125 351 252 352 125 352 250 352 250 353 125 353 124 353 63 354 68 354 257 354 257 355 68 355 163 355 257 356 163 356 258 356 258 357 163 357 204 357 258 358 204 358 125 358 125 359 204 359 206 359 125 360 206 360 123 360 259 361 260 361 261 361 261 362 260 362 207 362 261 363 207 363 262 363 262 364 207 364 205 364 262 365 205 365 150 365 150 366 205 366 151 366 150 367 151 367 78 367 78 368 151 368 73 368 260 369 263 369 207 369 207 370 263 370 264 370 207 371 264 371 206 371 206 372 264 372 265 372 206 373 265 373 123 373 77 374 75 374 150 374 150 375 75 375 208 375 150 376 208 376 262 376 262 377 208 377 209 377 262 378 209 378 261 378 261 379 209 379 211 379 261 380 211 380 259 380 266 381 267 381 268 381 268 382 267 382 212 382 268 383 212 383 269 383 269 384 212 384 210 384 269 385 210 385 148 385 148 386 210 386 149 386 148 387 149 387 81 387 81 388 149 388 79 388 267 389 270 389 212 389 212 390 270 390 271 390 212 391 271 391 211 391 211 392 271 392 272 392 211 393 272 393 259 393 82 394 84 394 148 394 148 395 84 395 138 395 148 396 138 396 269 396 269 397 138 397 140 397 269 398 140 398 268 398 268 399 140 399 172 399 268 400 172 400 266 400 266 401 172 401 273 401 274 402 275 402 276 402 90 403 147 403 164 403 164 404 147 404 277 404 164 405 277 405 173 405 173 406 277 406 274 406 173 407 274 407 172 407 172 408 274 408 276 408 172 409 276 409 273 409 91 410 165 410 147 410 147 411 165 411 175 411 147 412 175 412 277 412 277 413 175 413 213 413 277 414 213 414 274 414 274 415 213 415 278 415 274 416 278 416 275 416 218 417 279 417 215 417 215 418 279 418 280 418 215 419 280 419 214 419 214 420 280 420 281 420 214 421 281 421 213 421 213 422 281 422 282 422 213 423 282 423 278 423 121 424 219 424 122 424 122 425 219 425 217 425 122 426 217 426 283 426 283 427 217 427 216 427 283 428 216 428 284 428 284 429 216 429 146 429 284 430 146 430 99 430 99 431 146 431 95 431 99 432 98 432 284 432 284 433 98 433 135 433 284 434 135 434 283 434 283 435 135 435 137 435 283 436 137 436 122 436 122 437 137 437 176 437 122 438 176 438 120 438 120 439 176 439 285 439 286 440 287 440 288 440 107 441 145 441 166 441 166 442 145 442 289 442 166 443 289 443 177 443 177 444 289 444 286 444 177 445 286 445 176 445 176 446 286 446 288 446 176 447 288 447 285 447 110 448 167 448 145 448 145 449 167 449 290 449 145 450 290 450 289 450 289 451 290 451 119 451 289 452 119 452 286 452 286 453 119 453 118 453 286 454 118 454 287 454 113 455 168 455 167 455 167 456 168 456 291 456 167 457 291 457 290 457 290 458 291 458 292 458 290 459 292 459 119 459 119 460 292 460 293 460 119 461 293 461 117 461 116 462 144 462 168 462 168 463 144 463 178 463 168 464 178 464 291 464 291 465 178 465 220 465 291 466 220 466 292 466 292 467 220 467 294 467 292 468 294 468 293 468 225 469 295 469 223 469 223 470 295 470 296 470 223 471 296 471 222 471 222 472 296 472 297 472 222 473 297 473 221 473 221 474 297 474 298 474 221 475 298 475 220 475 220 476 298 476 299 476 220 477 299 477 294 477 300 478 297 478 301 478 301 479 297 479 296 479 301 480 296 480 302 480 302 481 296 481 295 481 302 482 295 482 303 482 303 483 295 483 225 483 303 484 225 484 304 484 304 485 225 485 224 485 304 486 224 486 305 486 305 487 224 487 133 487 305 488 133 488 306 488 306 489 133 489 132 489 306 490 132 490 307 490 307 491 132 491 229 491 307 492 229 492 308 492 308 493 229 493 230 493 308 494 230 494 309 494 309 495 230 495 233 495 309 496 233 496 310 496 310 497 233 497 232 497 310 498 232 498 311 498 232 499 231 499 311 499 311 500 231 500 185 500 311 501 185 501 312 501 312 502 185 502 184 502 312 503 184 503 313 503 313 504 184 504 130 504 313 505 130 505 314 505 130 506 129 506 314 506 314 507 129 507 241 507 314 508 241 508 315 508 315 509 241 509 240 509 315 510 240 510 316 510 316 511 240 511 239 511 316 512 239 512 317 512 317 513 239 513 236 513 317 514 236 514 318 514 318 515 236 515 235 515 318 516 235 516 319 516 319 517 235 517 127 517 319 518 127 518 320 518 127 519 126 519 320 519 320 520 126 520 249 520 320 521 249 521 321 521 321 522 249 522 248 522 321 523 248 523 322 523 322 524 248 524 247 524 322 525 247 525 323 525 323 526 247 526 244 526 323 527 244 527 324 527 324 528 244 528 243 528 324 529 243 529 325 529 243 530 256 530 325 530 325 531 256 531 255 531 325 532 255 532 326 532 326 533 255 533 254 533 326 534 254 534 327 534 327 535 254 535 251 535 327 536 251 536 328 536 251 537 250 537 328 537 328 538 250 538 124 538 328 539 124 539 329 539 329 540 124 540 123 540 329 541 123 541 330 541 330 542 123 542 265 542 330 543 265 543 331 543 331 544 265 544 264 544 331 545 264 545 332 545 332 546 264 546 263 546 332 547 263 547 333 547 333 548 263 548 260 548 333 549 260 549 334 549 334 550 260 550 259 550 334 551 259 551 335 551 278 552 336 552 337 552 259 553 272 553 335 553 335 554 272 554 271 554 335 555 271 555 338 555 338 556 271 556 270 556 338 557 270 557 339 557 339 558 270 558 267 558 339 559 267 559 340 559 340 560 267 560 266 560 340 561 266 561 341 561 341 562 266 562 273 562 341 563 273 563 342 563 342 564 273 564 276 564 342 565 276 565 337 565 337 566 276 566 275 566 337 567 275 567 278 567 278 568 282 568 336 568 336 569 282 569 281 569 336 570 281 570 343 570 343 571 281 571 280 571 343 572 280 572 344 572 344 573 280 573 279 573 344 574 279 574 345 574 345 575 279 575 218 575 345 576 218 576 346 576 346 577 218 577 219 577 346 578 219 578 347 578 347 579 219 579 121 579 347 580 121 580 348 580 348 581 121 581 120 581 348 582 120 582 349 582 349 583 120 583 285 583 349 584 285 584 350 584 350 585 285 585 288 585 350 586 288 586 351 586 288 587 287 587 351 587 351 588 287 588 118 588 351 589 118 589 352 589 352 590 118 590 117 590 352 591 117 591 353 591 353 592 117 592 293 592 353 593 293 593 354 593 354 594 293 594 294 594 354 595 294 595 355 595 355 596 294 596 299 596 355 597 299 597 300 597 300 598 299 598 298 598 300 599 298 599 297 599 356 600 357 600 358 600 359 601 360 601 356 601 356 602 360 602 361 602 356 603 361 603 357 603 358 604 362 604 356 604 356 605 362 605 363 605 356 606 363 606 364 606 364 607 365 607 356 607 356 608 365 608 366 608 356 609 366 609 367 609 359 610 368 610 360 610 360 611 368 611 369 611 360 612 369 612 370 612 370 613 371 613 360 613 360 614 371 614 372 614 360 615 372 615 373 615 373 616 374 616 360 616 360 617 374 617 375 617 360 618 375 618 376 618 376 619 377 619 360 619 360 620 377 620 378 620 360 621 378 621 379 621 367 622 380 622 356 622 356 623 380 623 381 623 356 624 381 624 382 624 383 625 384 625 385 625 382 626 386 626 356 626 356 627 386 627 383 627 356 628 383 628 387 628 387 629 383 629 385 629 338 630 339 630 388 630 350 631 351 631 389 631 308 632 309 632 390 632 322 633 323 633 391 633 363 634 362 634 392 634 364 635 363 635 393 635 365 636 364 636 394 636 366 637 365 637 395 637 386 638 382 638 396 638 383 639 386 639 397 639 384 640 383 640 398 640 385 641 384 641 399 641 369 642 368 642 400 642 370 643 369 643 401 643 371 644 370 644 402 644 372 645 371 645 403 645 377 646 376 646 404 646 378 647 377 647 405 647 379 648 378 648 406 648 360 649 379 649 407 649 372 650 408 650 373 650 373 651 408 651 409 651 373 652 409 652 410 652 410 653 409 653 411 653 410 654 411 654 375 654 375 655 411 655 412 655 375 656 412 656 376 656 385 657 413 657 387 657 387 658 413 658 414 658 387 659 414 659 415 659 415 660 414 660 416 660 415 661 416 661 359 661 359 662 416 662 417 662 359 663 417 663 368 663 366 664 418 664 367 664 367 665 418 665 419 665 367 666 419 666 420 666 420 667 419 667 421 667 420 668 421 668 381 668 381 669 421 669 422 669 381 670 422 670 382 670 360 671 423 671 361 671 361 672 423 672 424 672 361 673 424 673 425 673 425 674 424 674 426 674 425 675 426 675 358 675 358 676 426 676 427 676 358 677 427 677 362 677 408 678 428 678 409 678 409 679 428 679 429 679 409 680 429 680 411 680 411 681 429 681 430 681 411 682 430 682 412 682 412 683 430 683 431 683 413 684 432 684 414 684 414 685 432 685 433 685 414 686 433 686 416 686 416 687 433 687 434 687 416 688 434 688 417 688 417 689 434 689 435 689 418 690 436 690 419 690 419 691 436 691 437 691 419 692 437 692 421 692 421 693 437 693 438 693 421 694 438 694 422 694 422 695 438 695 439 695 423 696 440 696 424 696 424 697 440 697 441 697 424 698 441 698 426 698 426 699 441 699 442 699 426 700 442 700 427 700 427 701 442 701 443 701 428 702 444 702 429 702 429 703 444 703 445 703 429 704 445 704 430 704 430 705 445 705 446 705 430 706 446 706 431 706 431 707 446 707 447 707 432 708 448 708 433 708 433 709 448 709 449 709 433 710 449 710 434 710 434 711 449 711 450 711 434 712 450 712 435 712 435 713 450 713 451 713 436 714 452 714 437 714 437 715 452 715 453 715 437 716 453 716 438 716 438 717 453 717 454 717 438 718 454 718 439 718 439 719 454 719 455 719 440 720 456 720 441 720 441 721 456 721 457 721 441 722 457 722 442 722 442 723 457 723 458 723 442 724 458 724 443 724 443 725 458 725 459 725 360 726 407 726 423 726 423 727 407 727 460 727 423 728 460 728 440 728 440 729 460 729 391 729 440 730 391 730 456 730 456 731 391 731 323 731 456 732 323 732 324 732 379 733 406 733 407 733 407 734 406 734 461 734 407 735 461 735 460 735 460 736 461 736 462 736 460 737 462 737 391 737 391 738 462 738 321 738 391 739 321 739 322 739 463 740 319 740 320 740 378 741 405 741 406 741 406 742 405 742 464 742 406 743 464 743 461 743 461 744 464 744 463 744 461 745 463 745 462 745 462 746 463 746 320 746 462 747 320 747 321 747 465 748 317 748 318 748 377 749 404 749 405 749 405 750 404 750 466 750 405 751 466 751 464 751 464 752 466 752 465 752 464 753 465 753 463 753 463 754 465 754 318 754 463 755 318 755 319 755 376 756 412 756 404 756 404 757 412 757 431 757 404 758 431 758 466 758 466 759 431 759 447 759 466 760 447 760 465 760 465 761 447 761 316 761 465 762 316 762 317 762 310 763 311 763 444 763 444 764 311 764 312 764 444 765 312 765 445 765 445 766 312 766 313 766 445 767 313 767 446 767 446 768 313 768 467 768 446 769 467 769 447 769 447 770 467 770 315 770 447 771 315 771 316 771 372 772 403 772 408 772 408 773 403 773 468 773 408 774 468 774 428 774 428 775 468 775 390 775 428 776 390 776 444 776 444 777 390 777 309 777 444 778 309 778 310 778 371 779 402 779 403 779 403 780 402 780 469 780 403 781 469 781 468 781 468 782 469 782 470 782 468 783 470 783 390 783 390 784 470 784 307 784 390 785 307 785 308 785 471 786 305 786 306 786 370 787 401 787 402 787 402 788 401 788 472 788 402 789 472 789 469 789 469 790 472 790 471 790 469 791 471 791 470 791 470 792 471 792 306 792 470 793 306 793 307 793 473 794 303 794 304 794 369 795 400 795 401 795 401 796 400 796 474 796 401 797 474 797 472 797 472 798 474 798 473 798 472 799 473 799 471 799 471 800 473 800 304 800 471 801 304 801 305 801 368 802 417 802 400 802 400 803 417 803 435 803 400 804 435 804 474 804 474 805 435 805 451 805 474 806 451 806 473 806 473 807 451 807 302 807 473 808 302 808 303 808 352 809 353 809 448 809 448 810 353 810 354 810 448 811 354 811 449 811 449 812 354 812 355 812 449 813 355 813 450 813 450 814 355 814 475 814 450 815 475 815 451 815 451 816 475 816 301 816 451 817 301 817 302 817 385 818 399 818 413 818 413 819 399 819 476 819 413 820 476 820 432 820 432 821 476 821 389 821 432 822 389 822 448 822 448 823 389 823 351 823 448 824 351 824 352 824 384 825 398 825 399 825 399 826 398 826 477 826 399 827 477 827 476 827 476 828 477 828 478 828 476 829 478 829 389 829 389 830 478 830 349 830 389 831 349 831 350 831 479 832 347 832 348 832 383 833 397 833 398 833 398 834 397 834 480 834 398 835 480 835 477 835 477 836 480 836 479 836 477 837 479 837 478 837 478 838 479 838 348 838 478 839 348 839 349 839 481 840 345 840 346 840 386 841 396 841 397 841 397 842 396 842 482 842 397 843 482 843 480 843 480 844 482 844 481 844 480 845 481 845 479 845 479 846 481 846 346 846 479 847 346 847 347 847 382 848 422 848 396 848 396 849 422 849 439 849 396 850 439 850 482 850 482 851 439 851 455 851 482 852 455 852 481 852 481 853 455 853 344 853 481 854 344 854 345 854 340 855 341 855 452 855 452 856 341 856 342 856 452 857 342 857 453 857 453 858 342 858 337 858 453 859 337 859 454 859 454 860 337 860 483 860 454 861 483 861 455 861 455 862 483 862 343 862 455 863 343 863 344 863 366 864 395 864 418 864 418 865 395 865 484 865 418 866 484 866 436 866 436 867 484 867 388 867 436 868 388 868 452 868 452 869 388 869 339 869 452 870 339 870 340 870 365 871 394 871 395 871 395 872 394 872 485 872 395 873 485 873 484 873 484 874 485 874 486 874 484 875 486 875 388 875 388 876 486 876 335 876 388 877 335 877 338 877 487 878 333 878 334 878 364 879 393 879 394 879 394 880 393 880 488 880 394 881 488 881 485 881 485 882 488 882 487 882 485 883 487 883 486 883 486 884 487 884 334 884 486 885 334 885 335 885 489 886 331 886 332 886 363 887 392 887 393 887 393 888 392 888 490 888 393 889 490 889 488 889 488 890 490 890 489 890 488 891 489 891 487 891 487 892 489 892 332 892 487 893 332 893 333 893 362 894 427 894 392 894 392 895 427 895 443 895 392 896 443 896 490 896 490 897 443 897 459 897 490 898 459 898 489 898 489 899 459 899 330 899 489 900 330 900 331 900 324 901 325 901 456 901 456 902 325 902 326 902 456 903 326 903 457 903 457 904 326 904 327 904 457 905 327 905 458 905 458 906 327 906 491 906 458 907 491 907 459 907 459 908 491 908 329 908 459 909 329 909 330 909 492 910 493 910 494 910 494 911 493 911 495 911 496 912 497 912 498 912 498 913 497 913 499 913 498 914 499 914 500 914 500 915 501 915 498 915 498 916 501 916 502 916 498 917 502 917 503 917 492 918 496 918 493 918 493 919 496 919 498 919 493 920 498 920 504 920 504 921 498 921 505 921 504 922 505 922 506 922 506 923 505 923 507 923 507 924 505 924 508 924 507 925 508 925 509 925 509 926 510 926 507 926 507 927 510 927 511 927 507 928 511 928 512 928 513 929 514 929 515 929 515 930 516 930 513 930 513 931 516 931 517 931 513 932 517 932 518 932 512 933 519 933 507 933 507 934 519 934 520 934 507 935 520 935 521 935 521 936 520 936 513 936 521 937 513 937 522 937 522 938 513 938 518 938 523 939 524 939 525 939 525 940 524 940 526 940 525 941 526 941 527 941 528 942 529 942 527 942 527 943 529 943 530 943 527 944 530 944 525 944 531 945 532 945 533 945 532 946 534 946 533 946 533 947 534 947 535 947 533 948 535 948 536 948 514 949 523 949 515 949 515 950 523 950 525 950 515 951 525 951 536 951 536 952 525 952 537 952 536 953 537 953 538 953 538 954 539 954 536 954 536 955 539 955 540 955 536 956 540 956 533 956 541 957 542 957 543 957 543 958 542 958 544 958 543 959 544 959 545 959 545 960 546 960 543 960 543 961 546 961 547 961 543 962 547 962 533 962 533 963 547 963 548 963 533 964 548 964 531 964 541 965 543 965 549 965 549 966 543 966 550 966 549 967 550 967 551 967 552 968 553 968 554 968 554 969 555 969 552 969 552 970 555 970 556 970 552 971 556 971 557 971 557 972 558 972 552 972 552 973 558 973 559 973 552 974 559 974 560 974 560 975 561 975 552 975 552 976 561 976 562 976 552 977 562 977 563 977 551 978 564 978 549 978 549 979 564 979 552 979 549 980 552 980 565 980 565 981 552 981 563 981 553 982 566 982 554 982 554 983 566 983 567 983 554 984 567 984 568 984 568 985 569 985 554 985 554 986 569 986 570 986 554 987 570 987 571 987 572 988 573 988 574 988 575 989 576 989 577 989 577 990 576 990 578 990 565 991 579 991 549 991 549 992 579 992 580 992 549 993 580 993 581 993 578 994 572 994 577 994 577 995 572 995 574 995 577 996 574 996 582 996 582 997 574 997 549 997 582 998 549 998 583 998 583 999 549 999 581 999 571 1000 584 1000 554 1000 554 1001 584 1001 585 1001 554 1002 585 1002 586 1002 587 1003 588 1003 589 1003 589 1004 588 1004 590 1004 590 1005 591 1005 589 1005 589 1006 591 1006 554 1006 589 1007 554 1007 592 1007 592 1008 554 1008 586 1008 592 1009 586 1009 593 1009 528 1010 527 1010 594 1010 594 1011 527 1011 595 1011 594 1012 595 1012 596 1012 596 1013 595 1013 597 1013 596 1014 597 1014 598 1014 598 1015 599 1015 596 1015 596 1016 599 1016 600 1016 596 1017 600 1017 601 1017 601 1018 602 1018 596 1018 596 1019 602 1019 603 1019 596 1020 603 1020 604 1020 604 1021 603 1021 605 1021 604 1022 605 1022 606 1022 607 1023 608 1023 609 1023 607 1024 609 1024 610 1024 606 1025 605 1025 611 1025 611 1026 605 1026 612 1026 611 1027 612 1027 613 1027 613 1028 612 1028 614 1028 613 1029 614 1029 615 1029 615 1030 614 1030 616 1030 615 1031 616 1031 617 1031 617 1032 616 1032 618 1032 617 1033 618 1033 619 1033 619 1034 618 1034 620 1034 619 1035 620 1035 621 1035 621 1036 620 1036 609 1036 609 1037 620 1037 622 1037 609 1038 622 1038 610 1038 623 1039 624 1039 625 1039 608 1040 626 1040 609 1040 609 1041 626 1041 627 1041 609 1042 627 1042 624 1042 624 1043 627 1043 628 1043 624 1044 628 1044 625 1044 629 1045 630 1045 625 1045 625 1046 630 1046 631 1046 625 1047 631 1047 623 1047 632 1048 633 1048 634 1048 634 1049 633 1049 635 1049 634 1050 635 1050 636 1050 637 1051 638 1051 635 1051 638 1052 639 1052 635 1052 635 1053 639 1053 640 1053 635 1054 640 1054 636 1054 641 1055 642 1055 643 1055 643 1056 642 1056 644 1056 629 1057 632 1057 630 1057 630 1058 632 1058 634 1058 630 1059 634 1059 644 1059 644 1060 634 1060 645 1060 644 1061 645 1061 643 1061 646 1062 647 1062 643 1062 643 1063 647 1063 648 1063 643 1064 648 1064 641 1064 649 1065 650 1065 651 1065 646 1066 652 1066 647 1066 647 1067 652 1067 653 1067 647 1068 653 1068 650 1068 650 1069 653 1069 654 1069 650 1070 654 1070 651 1070 655 1071 656 1071 651 1071 651 1072 656 1072 657 1072 651 1073 657 1073 649 1073 655 1074 658 1074 656 1074 656 1075 658 1075 659 1075 656 1076 659 1076 660 1076 661 1077 662 1077 663 1077 661 1078 663 1078 664 1078 664 1079 663 1079 665 1079 664 1080 665 1080 666 1080 666 1081 667 1081 664 1081 664 1082 667 1082 668 1082 664 1083 668 1083 669 1083 670 1084 671 1084 672 1084 672 1085 671 1085 673 1085 672 1086 673 1086 674 1086 674 1087 673 1087 675 1087 675 1088 673 1088 676 1088 675 1089 676 1089 677 1089 669 1090 678 1090 664 1090 664 1091 678 1091 679 1091 664 1092 679 1092 680 1092 677 1093 681 1093 675 1093 675 1094 681 1094 682 1094 675 1095 682 1095 683 1095 660 1096 684 1096 656 1096 656 1097 684 1097 675 1097 656 1098 675 1098 685 1098 685 1099 675 1099 683 1099 685 1100 683 1100 686 1100 686 1101 687 1101 685 1101 685 1102 687 1102 688 1102 685 1103 688 1103 689 1103 689 1104 690 1104 685 1104 685 1105 690 1105 691 1105 685 1106 691 1106 692 1106 680 1107 693 1107 664 1107 664 1108 693 1108 694 1108 664 1109 694 1109 695 1109 695 1110 694 1110 685 1110 695 1111 685 1111 696 1111 696 1112 685 1112 692 1112 697 1113 698 1113 699 1113 664 1114 700 1114 661 1114 661 1115 700 1115 697 1115 661 1116 697 1116 701 1116 701 1117 697 1117 699 1117 702 1118 703 1118 704 1118 670 1119 705 1119 671 1119 671 1120 705 1120 702 1120 671 1121 702 1121 706 1121 706 1122 702 1122 704 1122 637 1123 635 1123 707 1123 707 1124 635 1124 708 1124 707 1125 708 1125 709 1125 710 1126 711 1126 712 1126 712 1127 713 1127 710 1127 710 1128 713 1128 714 1128 710 1129 714 1129 715 1129 715 1130 714 1130 716 1130 717 1131 718 1131 719 1131 719 1132 720 1132 717 1132 717 1133 720 1133 721 1133 717 1134 721 1134 722 1134 722 1135 721 1135 723 1135 722 1136 723 1136 710 1136 710 1137 723 1137 724 1137 710 1138 724 1138 711 1138 709 1139 725 1139 707 1139 707 1140 725 1140 723 1140 707 1141 723 1141 726 1141 726 1142 723 1142 721 1142 727 1143 728 1143 716 1143 716 1144 728 1144 729 1144 729 1145 730 1145 716 1145 716 1146 730 1146 731 1146 716 1147 731 1147 715 1147 502 1148 732 1148 503 1148 503 1149 732 1149 728 1149 503 1150 728 1150 733 1150 733 1151 728 1151 727 1151 734 1152 735 1152 736 1152 737 1153 738 1153 739 1153 736 1154 740 1154 734 1154 734 1155 740 1155 741 1155 734 1156 741 1156 742 1156 742 1157 741 1157 743 1157 735 1158 734 1158 739 1158 739 1159 734 1159 744 1159 739 1160 744 1160 737 1160 738 1161 745 1161 739 1161 739 1162 745 1162 746 1162 739 1163 746 1163 747 1163 747 1164 746 1164 748 1164 743 1165 741 1165 749 1165 749 1166 741 1166 750 1166 749 1167 750 1167 751 1167 751 1168 752 1168 749 1168 749 1169 752 1169 753 1169 749 1170 753 1170 754 1170 754 1171 753 1171 755 1171 756 1172 757 1172 758 1172 756 1173 758 1173 759 1173 760 1174 761 1174 758 1174 758 1175 761 1175 762 1175 758 1176 762 1176 759 1176 763 1177 764 1177 765 1177 757 1178 766 1178 767 1178 764 1179 763 1179 768 1179 768 1180 763 1180 769 1180 768 1181 769 1181 770 1181 760 1182 771 1182 761 1182 761 1183 771 1183 763 1183 761 1184 763 1184 772 1184 772 1185 763 1185 765 1185 766 1186 757 1186 773 1186 773 1187 757 1187 774 1187 773 1188 774 1188 775 1188 767 1189 776 1189 757 1189 757 1190 776 1190 777 1190 757 1191 777 1191 758 1191 746 1192 778 1192 748 1192 748 1193 778 1193 779 1193 748 1194 779 1194 747 1194 747 1195 779 1195 780 1195 747 1196 780 1196 739 1196 739 1197 780 1197 781 1197 739 1198 781 1198 735 1198 735 1199 781 1199 782 1199 735 1200 782 1200 736 1200 736 1201 782 1201 783 1201 736 1202 783 1202 740 1202 740 1203 783 1203 784 1203 740 1204 784 1204 741 1204 741 1205 784 1205 785 1205 741 1206 785 1206 750 1206 750 1207 785 1207 786 1207 750 1208 786 1208 751 1208 751 1209 786 1209 787 1209 751 1210 787 1210 752 1210 752 1211 787 1211 788 1211 752 1212 788 1212 753 1212 753 1213 788 1213 789 1213 753 1214 789 1214 755 1214 755 1215 789 1215 790 1215 755 1216 790 1216 754 1216 754 1217 790 1217 791 1217 754 1218 791 1218 749 1218 749 1219 791 1219 792 1219 749 1220 792 1220 743 1220 743 1221 792 1221 793 1221 743 1222 793 1222 742 1222 742 1223 793 1223 794 1223 742 1224 794 1224 734 1224 734 1225 794 1225 795 1225 734 1226 795 1226 744 1226 744 1227 795 1227 796 1227 744 1228 796 1228 737 1228 737 1229 796 1229 797 1229 737 1230 797 1230 738 1230 738 1231 797 1231 798 1231 738 1232 798 1232 745 1232 745 1233 798 1233 799 1233 745 1234 799 1234 746 1234 746 1235 799 1235 778 1235 800 1236 775 1236 801 1236 801 1237 775 1237 774 1237 801 1238 774 1238 802 1238 802 1239 774 1239 757 1239 802 1240 757 1240 803 1240 803 1241 757 1241 756 1241 803 1242 756 1242 804 1242 804 1243 756 1243 759 1243 804 1244 759 1244 805 1244 805 1245 759 1245 762 1245 805 1246 762 1246 806 1246 806 1247 762 1247 761 1247 806 1248 761 1248 807 1248 807 1249 761 1249 772 1249 807 1250 772 1250 808 1250 808 1251 772 1251 765 1251 808 1252 765 1252 809 1252 809 1253 765 1253 764 1253 809 1254 764 1254 810 1254 810 1255 764 1255 768 1255 810 1256 768 1256 811 1256 811 1257 768 1257 770 1257 811 1258 770 1258 812 1258 812 1259 770 1259 769 1259 812 1260 769 1260 813 1260 813 1261 769 1261 763 1261 813 1262 763 1262 814 1262 814 1263 763 1263 771 1263 814 1264 771 1264 815 1264 815 1265 771 1265 760 1265 815 1266 760 1266 816 1266 816 1267 760 1267 758 1267 816 1268 758 1268 817 1268 817 1269 758 1269 777 1269 817 1270 777 1270 818 1270 818 1271 777 1271 776 1271 818 1272 776 1272 819 1272 819 1273 776 1273 767 1273 819 1274 767 1274 820 1274 820 1275 767 1275 766 1275 820 1276 766 1276 821 1276 821 1277 766 1277 773 1277 821 1278 773 1278 800 1278 800 1279 773 1279 775 1279 794 1280 822 1280 795 1280 795 1281 822 1281 823 1281 795 1282 823 1282 796 1282 796 1283 823 1283 824 1283 796 1284 824 1284 797 1284 797 1285 824 1285 825 1285 797 1286 825 1286 798 1286 798 1287 825 1287 826 1287 798 1288 826 1288 799 1288 799 1289 826 1289 827 1289 799 1290 827 1290 778 1290 778 1291 827 1291 828 1291 778 1292 828 1292 779 1292 779 1293 828 1293 829 1293 779 1294 829 1294 780 1294 780 1295 829 1295 830 1295 780 1296 830 1296 781 1296 781 1297 830 1297 831 1297 781 1298 831 1298 782 1298 782 1299 831 1299 832 1299 782 1300 832 1300 783 1300 832 1301 833 1301 783 1301 783 1302 833 1302 834 1302 783 1303 834 1303 784 1303 784 1304 834 1304 835 1304 784 1305 835 1305 785 1305 785 1306 835 1306 836 1306 785 1307 836 1307 786 1307 786 1308 836 1308 837 1308 786 1309 837 1309 787 1309 787 1310 837 1310 838 1310 787 1311 838 1311 788 1311 788 1312 838 1312 839 1312 788 1313 839 1313 789 1313 789 1314 839 1314 840 1314 789 1315 840 1315 790 1315 790 1316 840 1316 841 1316 790 1317 841 1317 791 1317 791 1318 841 1318 842 1318 791 1319 842 1319 792 1319 792 1320 842 1320 843 1320 792 1321 843 1321 793 1321 793 1322 843 1322 844 1322 793 1323 844 1323 794 1323 794 1324 844 1324 845 1324 794 1325 845 1325 822 1325 806 1326 846 1326 805 1326 805 1327 846 1327 847 1327 805 1328 847 1328 804 1328 804 1329 847 1329 848 1329 804 1330 848 1330 803 1330 803 1331 848 1331 849 1331 803 1332 849 1332 802 1332 802 1333 849 1333 850 1333 802 1334 850 1334 801 1334 801 1335 850 1335 851 1335 801 1336 851 1336 800 1336 800 1337 851 1337 852 1337 800 1338 852 1338 821 1338 821 1339 852 1339 853 1339 821 1340 853 1340 820 1340 820 1341 853 1341 854 1341 820 1342 854 1342 819 1342 819 1343 854 1343 855 1343 819 1344 855 1344 818 1344 818 1345 855 1345 856 1345 818 1346 856 1346 817 1346 856 1347 857 1347 817 1347 817 1348 857 1348 858 1348 817 1349 858 1349 816 1349 816 1350 858 1350 859 1350 816 1351 859 1351 815 1351 815 1352 859 1352 860 1352 815 1353 860 1353 814 1353 814 1354 860 1354 861 1354 814 1355 861 1355 813 1355 813 1356 861 1356 862 1356 813 1357 862 1357 812 1357 812 1358 862 1358 863 1358 812 1359 863 1359 811 1359 811 1360 863 1360 864 1360 811 1361 864 1361 810 1361 810 1362 864 1362 865 1362 810 1363 865 1363 809 1363 809 1364 865 1364 866 1364 809 1365 866 1365 808 1365 808 1366 866 1366 867 1366 808 1367 867 1367 807 1367 807 1368 867 1368 868 1368 807 1369 868 1369 806 1369 806 1370 868 1370 869 1370 806 1371 869 1371 846 1371 870 1372 840 1372 871 1372 871 1373 840 1373 839 1373 871 1374 839 1374 872 1374 872 1375 839 1375 838 1375 872 1376 838 1376 873 1376 873 1377 838 1377 837 1377 873 1378 837 1378 874 1378 874 1379 837 1379 836 1379 874 1380 836 1380 875 1380 875 1381 836 1381 835 1381 875 1382 835 1382 876 1382 876 1383 835 1383 877 1383 876 1384 877 1384 878 1384 878 1385 877 1385 833 1385 878 1386 833 1386 879 1386 879 1387 833 1387 832 1387 879 1388 832 1388 880 1388 880 1389 832 1389 831 1389 880 1390 831 1390 881 1390 881 1391 831 1391 830 1391 881 1392 830 1392 882 1392 882 1393 830 1393 829 1393 882 1394 829 1394 883 1394 883 1395 829 1395 828 1395 883 1396 828 1396 884 1396 884 1397 828 1397 827 1397 884 1398 827 1398 885 1398 885 1399 827 1399 826 1399 885 1400 826 1400 886 1400 886 1401 826 1401 825 1401 886 1402 825 1402 887 1402 887 1403 825 1403 824 1403 887 1404 824 1404 888 1404 888 1405 824 1405 823 1405 888 1406 823 1406 889 1406 889 1407 823 1407 890 1407 889 1408 890 1408 891 1408 891 1409 890 1409 845 1409 891 1410 845 1410 892 1410 892 1411 845 1411 844 1411 892 1412 844 1412 893 1412 893 1413 844 1413 843 1413 893 1414 843 1414 894 1414 894 1415 843 1415 842 1415 894 1416 842 1416 895 1416 895 1417 842 1417 841 1417 895 1418 841 1418 870 1418 870 1419 841 1419 840 1419 862 1420 896 1420 863 1420 863 1421 896 1421 897 1421 863 1422 897 1422 864 1422 864 1423 897 1423 898 1423 864 1424 898 1424 865 1424 865 1425 898 1425 899 1425 865 1426 899 1426 866 1426 866 1427 899 1427 900 1427 866 1428 900 1428 867 1428 867 1429 900 1429 901 1429 867 1430 901 1430 868 1430 868 1431 901 1431 902 1431 868 1432 902 1432 903 1432 903 1433 902 1433 904 1433 903 1434 904 1434 846 1434 846 1435 904 1435 905 1435 846 1436 905 1436 847 1436 847 1437 905 1437 906 1437 847 1438 906 1438 848 1438 848 1439 906 1439 907 1439 848 1440 907 1440 849 1440 849 1441 907 1441 908 1441 849 1442 908 1442 850 1442 850 1443 908 1443 909 1443 850 1444 909 1444 851 1444 851 1445 909 1445 910 1445 851 1446 910 1446 852 1446 852 1447 910 1447 911 1447 852 1448 911 1448 853 1448 853 1449 911 1449 912 1449 853 1450 912 1450 854 1450 854 1451 912 1451 913 1451 854 1452 913 1452 855 1452 855 1453 913 1453 914 1453 855 1454 914 1454 856 1454 856 1455 914 1455 915 1455 856 1456 915 1456 916 1456 916 1457 915 1457 917 1457 916 1458 917 1458 858 1458 858 1459 917 1459 918 1459 858 1460 918 1460 859 1460 859 1461 918 1461 919 1461 859 1462 919 1462 860 1462 860 1463 919 1463 920 1463 860 1464 920 1464 861 1464 861 1465 920 1465 921 1465 861 1466 921 1466 862 1466 862 1467 921 1467 896 1467 922 1468 923 1468 924 1468 925 1469 926 1469 927 1469 925 1470 927 1470 928 1470 927 1471 929 1471 928 1471 928 1472 929 1472 930 1472 928 1473 930 1473 931 1473 932 1474 933 1474 925 1474 925 1475 933 1475 934 1475 925 1476 934 1476 926 1476 935 1477 936 1477 925 1477 925 1478 936 1478 937 1478 925 1479 937 1479 938 1479 938 1480 939 1480 925 1480 925 1481 939 1481 940 1481 925 1482 940 1482 932 1482 941 1483 942 1483 928 1483 942 1484 943 1484 928 1484 928 1485 943 1485 944 1485 928 1486 944 1486 925 1486 925 1487 944 1487 945 1487 925 1488 945 1488 935 1488 946 1489 947 1489 924 1489 924 1490 947 1490 948 1490 924 1491 948 1491 928 1491 928 1492 948 1492 949 1492 928 1493 949 1493 941 1493 950 1494 951 1494 924 1494 924 1495 951 1495 952 1495 924 1496 952 1496 946 1496 953 1497 954 1497 955 1497 952 1498 956 1498 946 1498 946 1499 956 1499 953 1499 946 1500 953 1500 957 1500 957 1501 953 1501 955 1501 950 1502 924 1502 958 1502 958 1503 924 1503 923 1503 958 1504 923 1504 959 1504 959 1505 923 1505 960 1505 959 1506 960 1506 961 1506 931 1507 962 1507 928 1507 928 1508 962 1508 963 1508 928 1509 963 1509 924 1509 924 1510 963 1510 964 1510 924 1511 964 1511 922 1511 965 1512 966 1512 967 1512 968 1513 969 1513 970 1513 971 1514 972 1514 973 1514 971 1515 973 1515 974 1515 975 1516 976 1516 977 1516 977 1517 976 1517 969 1517 977 1518 969 1518 978 1518 978 1519 969 1519 968 1519 979 1520 980 1520 970 1520 970 1521 980 1521 981 1521 970 1522 981 1522 968 1522 982 1523 983 1523 984 1523 985 1524 986 1524 984 1524 984 1525 986 1525 987 1525 984 1526 987 1526 982 1526 982 1527 987 1527 988 1527 982 1528 988 1528 989 1528 990 1529 991 1529 992 1529 992 1530 991 1530 993 1530 992 1531 993 1531 994 1531 994 1532 993 1532 995 1532 994 1533 995 1533 996 1533 996 1534 995 1534 997 1534 996 1535 997 1535 998 1535 998 1536 997 1536 999 1536 998 1537 999 1537 1000 1537 1000 1538 999 1538 1001 1538 1002 1539 1003 1539 1004 1539 1005 1540 1006 1540 1002 1540 1002 1541 1006 1541 1007 1541 1002 1542 1007 1542 1008 1542 1008 1543 1009 1543 1002 1543 1002 1544 1009 1544 1010 1544 1002 1545 1010 1545 1003 1545 1003 1546 1010 1546 1011 1546 1005 1547 1002 1547 1012 1547 1012 1548 1002 1548 1013 1548 1012 1549 1013 1549 1014 1549 1014 1550 1013 1550 1015 1550 1015 1551 1013 1551 1016 1551 1015 1552 1016 1552 1017 1552 973 1553 1018 1553 974 1553 974 1554 1018 1554 1019 1554 974 1555 1019 1555 1020 1555 1020 1556 1019 1556 1021 1556 1021 1557 1022 1557 1020 1557 1020 1558 1022 1558 1023 1558 1020 1559 1023 1559 1016 1559 1016 1560 1023 1560 1024 1560 1016 1561 1024 1561 1017 1561 965 1562 967 1562 989 1562 989 1563 967 1563 1025 1563 989 1564 1025 1564 982 1564 982 1565 1025 1565 1026 1565 982 1566 1026 1566 983 1566 998 1567 985 1567 996 1567 996 1568 985 1568 984 1568 996 1569 984 1569 994 1569 994 1570 984 1570 983 1570 994 1571 983 1571 992 1571 992 1572 983 1572 1026 1572 992 1573 1026 1573 990 1573 990 1574 1026 1574 1025 1574 990 1575 1025 1575 979 1575 979 1576 1025 1576 967 1576 979 1577 967 1577 980 1577 980 1578 967 1578 966 1578 976 1579 1027 1579 969 1579 969 1580 1027 1580 1028 1580 969 1581 1028 1581 970 1581 970 1582 1028 1582 1029 1582 970 1583 1029 1583 979 1583 979 1584 1029 1584 1030 1584 979 1585 1030 1585 990 1585 990 1586 1030 1586 1031 1586 990 1587 1031 1587 991 1587 1032 1588 971 1588 975 1588 975 1589 971 1589 974 1589 975 1590 974 1590 976 1590 976 1591 974 1591 1020 1591 976 1592 1020 1592 1027 1592 1027 1593 1020 1593 1016 1593 1027 1594 1016 1594 1028 1594 1028 1595 1016 1595 1013 1595 1028 1596 1013 1596 1029 1596 1029 1597 1013 1597 1002 1597 1029 1598 1002 1598 1030 1598 1030 1599 1002 1599 1004 1599 1030 1600 1004 1600 1031 1600 1033 1601 1034 1601 1035 1601 1035 1602 1034 1602 1036 1602 1036 1603 1037 1603 1035 1603 1035 1604 1037 1604 1038 1604 1035 1605 1038 1605 1039 1605 1039 1606 1040 1606 1035 1606 1035 1607 1040 1607 1041 1607 1035 1608 1041 1608 1042 1608 1043 1609 1044 1609 1045 1609 1045 1610 1044 1610 1046 1610 1045 1611 1046 1611 1034 1611 1034 1612 1046 1612 1047 1612 1034 1613 1047 1613 1036 1613 1043 1614 1045 1614 1048 1614 1048 1615 1045 1615 1049 1615 1048 1616 1049 1616 1050 1616 1051 1617 1052 1617 1053 1617 1053 1618 1052 1618 1054 1618 1053 1619 1054 1619 1049 1619 1049 1620 1054 1620 1055 1620 1049 1621 1055 1621 1050 1621 1056 1622 1057 1622 1058 1622 1058 1623 1057 1623 1059 1623 1058 1624 1059 1624 1060 1624 1061 1625 1062 1625 1053 1625 1053 1626 1062 1626 1063 1626 1053 1627 1063 1627 1051 1627 1064 1628 1065 1628 1066 1628 1064 1629 1066 1629 1058 1629 1058 1630 1066 1630 1067 1630 1058 1631 1067 1631 1056 1631 1068 1632 1069 1632 1070 1632 1070 1633 1069 1633 1071 1633 1070 1634 1071 1634 1064 1634 1064 1635 1071 1635 1072 1635 1064 1636 1072 1636 1065 1636 1068 1637 1073 1637 1069 1637 1069 1638 1073 1638 1074 1638 1069 1639 1074 1639 1075 1639 1075 1640 1074 1640 1076 1640 1077 1641 1078 1641 1079 1641 1080 1642 1081 1642 1082 1642 1082 1643 1081 1643 1083 1643 1082 1644 1083 1644 1084 1644 1082 1645 1085 1645 1086 1645 1086 1646 1085 1646 1087 1646 1086 1647 1087 1647 1088 1647 1082 1648 1086 1648 1080 1648 1080 1649 1086 1649 1088 1649 1080 1650 1088 1650 1089 1650 1089 1651 1088 1651 1090 1651 1089 1652 1090 1652 1091 1652 1092 1653 1093 1653 1082 1653 1082 1654 1093 1654 1094 1654 1082 1655 1094 1655 1085 1655 1095 1656 1096 1656 1097 1656 1097 1657 1096 1657 1098 1657 1097 1658 1098 1658 1099 1658 1099 1659 1098 1659 1100 1659 1101 1660 1102 1660 1103 1660 1103 1661 1102 1661 1104 1661 1103 1662 1104 1662 1077 1662 1077 1663 1104 1663 1105 1663 1077 1664 1105 1664 1078 1664 1060 1665 1101 1665 1058 1665 1058 1666 1101 1666 1103 1666 1058 1667 1103 1667 1064 1667 1064 1668 1103 1668 1077 1668 1064 1669 1077 1669 1070 1669 1070 1670 1077 1670 1079 1670 1070 1671 1079 1671 1068 1671 1106 1672 1107 1672 1108 1672 1108 1673 1107 1673 1095 1673 1108 1674 1095 1674 1109 1674 1109 1675 1095 1675 1097 1675 1109 1676 1097 1676 1110 1676 1110 1677 1097 1677 1099 1677 1110 1678 1099 1678 1092 1678 1092 1679 1099 1679 1100 1679 1092 1680 1100 1680 1093 1680 1059 1681 1061 1681 1060 1681 1060 1682 1061 1682 1053 1682 1060 1683 1053 1683 1111 1683 1111 1684 1053 1684 1049 1684 1111 1685 1049 1685 1112 1685 1112 1686 1049 1686 1045 1686 1112 1687 1045 1687 1113 1687 1113 1688 1045 1688 1034 1688 1113 1689 1034 1689 1114 1689 1114 1690 1034 1690 1033 1690 1114 1691 1115 1691 1113 1691 1113 1692 1115 1692 1106 1692 1113 1693 1106 1693 1112 1693 1112 1694 1106 1694 1108 1694 1112 1695 1108 1695 1111 1695 1111 1696 1108 1696 1109 1696 1111 1697 1109 1697 1060 1697 1060 1698 1109 1698 1110 1698 1060 1699 1110 1699 1101 1699 1101 1700 1110 1700 1092 1700 1101 1701 1092 1701 1102 1701 1102 1702 1092 1702 1082 1702 1102 1703 1082 1703 1104 1703 1104 1704 1082 1704 1084 1704 1104 1705 1084 1705 1105 1705 1116 1706 1117 1706 1118 1706 1119 1707 1120 1707 1121 1707 1122 1708 1123 1708 1124 1708 1125 1709 1126 1709 1127 1709 1128 1710 1129 1710 1130 1710 1131 1711 1132 1711 1133 1711 1134 1712 1135 1712 1136 1712 1137 1713 1138 1713 1139 1713 1140 1714 1141 1714 1142 1714 1143 1715 1144 1715 1145 1715 1146 1716 1147 1716 1148 1716 1149 1717 1150 1717 1151 1717 1152 1718 1153 1718 1154 1718 1154 1719 1153 1719 1155 1719 1154 1720 1155 1720 1156 1720 1157 1721 1158 1721 1159 1721 1159 1722 1160 1722 1157 1722 1157 1723 1160 1723 1161 1723 1157 1724 1161 1724 1154 1724 1154 1725 1161 1725 1162 1725 1154 1726 1162 1726 1152 1726 1163 1727 1164 1727 1165 1727 1165 1728 1164 1728 1166 1728 1165 1729 1166 1729 1157 1729 1157 1730 1166 1730 1167 1730 1157 1731 1167 1731 1158 1731 1163 1732 1165 1732 1168 1732 1168 1733 1165 1733 1169 1733 1168 1734 1169 1734 1170 1734 991 1735 1031 1735 1171 1735 1171 1736 1031 1736 1004 1736 1171 1737 1004 1737 1172 1737 1172 1738 1004 1738 1003 1738 1172 1739 1003 1739 1011 1739 991 1740 1171 1740 993 1740 993 1741 1171 1741 1173 1741 993 1742 1173 1742 995 1742 995 1743 1173 1743 997 1743 997 1744 1173 1744 1174 1744 997 1745 1174 1745 999 1745 1001 1746 999 1746 1175 1746 1175 1747 999 1747 1174 1747 1175 1748 1174 1748 1176 1748 1176 1749 1174 1749 1150 1749 1177 1750 1178 1750 1179 1750 1179 1751 1178 1751 1149 1751 1180 1752 1181 1752 1177 1752 1181 1753 1180 1753 1182 1753 1183 1754 1184 1754 1185 1754 1185 1755 1184 1755 1186 1755 1185 1756 1186 1756 1187 1756 1188 1757 1189 1757 1183 1757 1189 1758 1188 1758 1147 1758 1190 1759 1191 1759 1192 1759 1192 1760 1191 1760 1146 1760 1193 1761 1194 1761 1190 1761 1194 1762 1193 1762 1144 1762 1143 1763 1145 1763 1195 1763 1196 1764 1197 1764 1198 1764 1197 1765 1196 1765 1141 1765 1140 1766 1142 1766 1138 1766 1199 1767 1200 1767 1201 1767 1201 1768 1200 1768 1137 1768 1202 1769 1203 1769 1199 1769 1203 1770 1202 1770 1135 1770 1204 1771 1205 1771 1206 1771 1206 1772 1205 1772 1134 1772 1207 1773 1208 1773 1204 1773 1209 1774 1210 1774 1211 1774 1211 1775 1210 1775 1131 1775 1212 1776 1213 1776 1209 1776 1214 1777 1215 1777 1216 1777 1216 1778 1215 1778 1217 1778 1216 1779 1217 1779 1128 1779 1218 1780 1219 1780 1214 1780 1219 1781 1218 1781 1126 1781 1220 1782 1221 1782 1122 1782 1221 1783 1220 1783 1156 1783 1149 1784 1151 1784 1179 1784 1179 1785 1151 1785 1222 1785 1179 1786 1222 1786 1223 1786 1223 1787 1222 1787 1224 1787 1223 1788 1224 1788 1225 1788 1177 1789 1179 1789 1180 1789 1180 1790 1179 1790 1223 1790 1180 1791 1223 1791 1226 1791 1226 1792 1223 1792 1225 1792 1226 1793 1225 1793 1227 1793 1183 1794 1185 1794 1188 1794 1188 1795 1185 1795 1228 1795 1188 1796 1228 1796 1229 1796 1229 1797 1228 1797 1230 1797 1229 1798 1230 1798 1231 1798 1190 1799 1192 1799 1193 1799 1193 1800 1192 1800 1232 1800 1193 1801 1232 1801 1233 1801 1233 1802 1232 1802 1234 1802 1233 1803 1234 1803 1235 1803 1144 1804 1193 1804 1145 1804 1145 1805 1193 1805 1233 1805 1145 1806 1233 1806 1236 1806 1236 1807 1233 1807 1235 1807 1236 1808 1235 1808 1237 1808 1141 1809 1196 1809 1142 1809 1142 1810 1196 1810 1238 1810 1142 1811 1238 1811 1239 1811 1239 1812 1238 1812 1240 1812 1239 1813 1240 1813 1241 1813 1199 1814 1201 1814 1202 1814 1202 1815 1201 1815 1242 1815 1202 1816 1242 1816 1243 1816 1243 1817 1242 1817 1244 1817 1243 1818 1244 1818 1245 1818 1135 1819 1202 1819 1136 1819 1136 1820 1202 1820 1243 1820 1136 1821 1243 1821 1246 1821 1246 1822 1243 1822 1245 1822 1246 1823 1245 1823 1247 1823 1131 1824 1133 1824 1211 1824 1211 1825 1133 1825 1248 1825 1211 1826 1248 1826 1249 1826 1249 1827 1248 1827 1250 1827 1249 1828 1250 1828 1251 1828 1128 1829 1130 1829 1216 1829 1216 1830 1130 1830 1252 1830 1216 1831 1252 1831 1253 1831 1253 1832 1252 1832 1254 1832 1253 1833 1254 1833 1255 1833 1122 1834 1124 1834 1220 1834 1220 1835 1124 1835 1256 1835 1220 1836 1256 1836 1257 1836 1257 1837 1256 1837 1258 1837 1257 1838 1258 1838 1259 1838 1150 1839 1174 1839 1151 1839 1151 1840 1174 1840 1173 1840 1151 1841 1173 1841 1222 1841 1222 1842 1173 1842 1171 1842 1222 1843 1171 1843 1224 1843 1224 1844 1171 1844 1172 1844 1224 1845 1172 1845 1260 1845 1260 1846 1261 1846 1224 1846 1224 1847 1261 1847 1262 1847 1224 1848 1262 1848 1225 1848 1225 1849 1262 1849 1263 1849 1225 1850 1263 1850 1227 1850 1227 1851 1263 1851 1264 1851 1227 1852 1264 1852 1265 1852 1182 1853 1180 1853 1266 1853 1266 1854 1180 1854 1226 1854 1266 1855 1226 1855 1267 1855 1267 1856 1226 1856 1227 1856 1267 1857 1227 1857 1268 1857 1268 1858 1227 1858 1265 1858 1268 1859 1265 1859 1269 1859 1269 1860 1230 1860 1268 1860 1268 1861 1230 1861 1228 1861 1268 1862 1228 1862 1267 1862 1267 1863 1228 1863 1185 1863 1267 1864 1185 1864 1266 1864 1266 1865 1185 1865 1187 1865 1266 1866 1187 1866 1182 1866 1269 1867 1270 1867 1230 1867 1230 1868 1270 1868 1271 1868 1230 1869 1271 1869 1231 1869 1231 1870 1271 1870 1272 1870 1231 1871 1272 1871 1273 1871 1147 1872 1188 1872 1148 1872 1148 1873 1188 1873 1229 1873 1148 1874 1229 1874 1274 1874 1274 1875 1229 1875 1231 1875 1274 1876 1231 1876 1275 1876 1275 1877 1231 1877 1273 1877 1275 1878 1273 1878 1276 1878 1146 1879 1148 1879 1192 1879 1192 1880 1148 1880 1274 1880 1192 1881 1274 1881 1232 1881 1232 1882 1274 1882 1275 1882 1232 1883 1275 1883 1234 1883 1234 1884 1275 1884 1276 1884 1234 1885 1276 1885 1277 1885 1277 1886 1278 1886 1234 1886 1234 1887 1278 1887 1279 1887 1234 1888 1279 1888 1235 1888 1235 1889 1279 1889 1280 1889 1235 1890 1280 1890 1237 1890 1237 1891 1280 1891 1281 1891 1237 1892 1281 1892 1282 1892 1195 1893 1145 1893 1283 1893 1283 1894 1145 1894 1236 1894 1283 1895 1236 1895 1284 1895 1284 1896 1236 1896 1237 1896 1284 1897 1237 1897 1285 1897 1285 1898 1237 1898 1282 1898 1285 1899 1282 1899 1286 1899 1286 1900 1240 1900 1285 1900 1285 1901 1240 1901 1238 1901 1285 1902 1238 1902 1284 1902 1284 1903 1238 1903 1196 1903 1284 1904 1196 1904 1283 1904 1283 1905 1196 1905 1198 1905 1283 1906 1198 1906 1195 1906 1286 1907 1287 1907 1240 1907 1240 1908 1287 1908 1288 1908 1240 1909 1288 1909 1241 1909 1241 1910 1288 1910 1289 1910 1241 1911 1289 1911 1290 1911 1138 1912 1142 1912 1139 1912 1139 1913 1142 1913 1239 1913 1139 1914 1239 1914 1291 1914 1291 1915 1239 1915 1241 1915 1291 1916 1241 1916 1292 1916 1292 1917 1241 1917 1290 1917 1292 1918 1290 1918 1293 1918 1137 1919 1139 1919 1201 1919 1201 1920 1139 1920 1291 1920 1201 1921 1291 1921 1242 1921 1242 1922 1291 1922 1292 1922 1242 1923 1292 1923 1244 1923 1244 1924 1292 1924 1293 1924 1244 1925 1293 1925 1294 1925 1294 1926 1295 1926 1244 1926 1244 1927 1295 1927 1296 1927 1244 1928 1296 1928 1245 1928 1245 1929 1296 1929 1297 1929 1245 1930 1297 1930 1247 1930 1247 1931 1297 1931 1298 1931 1247 1932 1298 1932 1299 1932 1134 1933 1136 1933 1206 1933 1206 1934 1136 1934 1246 1934 1206 1935 1246 1935 1300 1935 1300 1936 1246 1936 1247 1936 1300 1937 1247 1937 1301 1937 1301 1938 1247 1938 1299 1938 1301 1939 1299 1939 1302 1939 1204 1940 1206 1940 1207 1940 1207 1941 1206 1941 1300 1941 1207 1942 1300 1942 1303 1942 1303 1943 1300 1943 1301 1943 1303 1944 1301 1944 1121 1944 1121 1945 1301 1945 1302 1945 1121 1946 1302 1946 1119 1946 1120 1947 1250 1947 1121 1947 1121 1948 1250 1948 1248 1948 1121 1949 1248 1949 1303 1949 1303 1950 1248 1950 1133 1950 1303 1951 1133 1951 1207 1951 1207 1952 1133 1952 1132 1952 1207 1953 1132 1953 1208 1953 1120 1954 1304 1954 1250 1954 1250 1955 1304 1955 1305 1955 1250 1956 1305 1956 1251 1956 1251 1957 1305 1957 1306 1957 1251 1958 1306 1958 1307 1958 1209 1959 1211 1959 1212 1959 1212 1960 1211 1960 1249 1960 1212 1961 1249 1961 1308 1961 1308 1962 1249 1962 1251 1962 1308 1963 1251 1963 1309 1963 1309 1964 1251 1964 1307 1964 1309 1965 1307 1965 1310 1965 1310 1966 1254 1966 1309 1966 1309 1967 1254 1967 1252 1967 1309 1968 1252 1968 1308 1968 1308 1969 1252 1969 1130 1969 1308 1970 1130 1970 1212 1970 1212 1971 1130 1971 1129 1971 1212 1972 1129 1972 1213 1972 1310 1973 1311 1973 1254 1973 1254 1974 1311 1974 1312 1974 1254 1975 1312 1975 1255 1975 1255 1976 1312 1976 1313 1976 1255 1977 1313 1977 1314 1977 1214 1978 1216 1978 1218 1978 1218 1979 1216 1979 1253 1979 1218 1980 1253 1980 1315 1980 1315 1981 1253 1981 1255 1981 1315 1982 1255 1982 1316 1982 1316 1983 1255 1983 1314 1983 1316 1984 1314 1984 1317 1984 1126 1985 1218 1985 1127 1985 1127 1986 1218 1986 1315 1986 1127 1987 1315 1987 1318 1987 1318 1988 1315 1988 1316 1988 1318 1989 1316 1989 1118 1989 1118 1990 1316 1990 1317 1990 1118 1991 1317 1991 1116 1991 1117 1992 1258 1992 1118 1992 1118 1993 1258 1993 1256 1993 1118 1994 1256 1994 1318 1994 1318 1995 1256 1995 1124 1995 1318 1996 1124 1996 1127 1996 1127 1997 1124 1997 1123 1997 1127 1998 1123 1998 1125 1998 1117 1999 1319 1999 1258 1999 1258 2000 1319 2000 1320 2000 1258 2001 1320 2001 1259 2001 1259 2002 1320 2002 1321 2002 1259 2003 1321 2003 1322 2003 1156 2004 1220 2004 1154 2004 1154 2005 1220 2005 1257 2005 1154 2006 1257 2006 1157 2006 1157 2007 1257 2007 1259 2007 1157 2008 1259 2008 1165 2008 1165 2009 1259 2009 1322 2009 1165 2010 1322 2010 1169 2010 1323 2011 1324 2011 1325 2011 1326 2012 871 2012 1327 2012 1327 2013 871 2013 872 2013 1327 2014 872 2014 1328 2014 1328 2015 872 2015 873 2015 1328 2016 873 2016 1329 2016 1329 2017 873 2017 874 2017 1329 2018 874 2018 1330 2018 1330 2019 874 2019 875 2019 1330 2020 875 2020 1325 2020 1325 2021 875 2021 876 2021 1325 2022 876 2022 1323 2022 1324 2023 1323 2023 1331 2023 1331 2024 1323 2024 879 2024 1331 2025 879 2025 1332 2025 1332 2026 879 2026 880 2026 1332 2027 880 2027 1333 2027 1333 2028 880 2028 881 2028 1333 2029 881 2029 1334 2029 1334 2030 881 2030 882 2030 1334 2031 882 2031 1335 2031 1335 2032 882 2032 883 2032 1335 2033 883 2033 1336 2033 1336 2034 883 2034 884 2034 1336 2035 884 2035 1337 2035 1326 2036 1338 2036 871 2036 871 2037 1338 2037 1339 2037 871 2038 1339 2038 870 2038 870 2039 1339 2039 1340 2039 870 2040 1340 2040 895 2040 895 2041 1340 2041 1341 2041 895 2042 1341 2042 894 2042 894 2043 1341 2043 1342 2043 894 2044 1342 2044 893 2044 893 2045 1342 2045 1343 2045 893 2046 1343 2046 892 2046 892 2047 1343 2047 1344 2047 892 2048 1344 2048 1345 2048 1345 2049 1344 2049 1346 2049 1345 2050 1346 2050 889 2050 889 2051 1346 2051 1347 2051 889 2052 1347 2052 888 2052 888 2053 1347 2053 1348 2053 888 2054 1348 2054 887 2054 887 2055 1348 2055 1349 2055 887 2056 1349 2056 886 2056 886 2057 1349 2057 1350 2057 886 2058 1350 2058 885 2058 885 2059 1350 2059 1351 2059 885 2060 1351 2060 884 2060 884 2061 1351 2061 1352 2061 884 2062 1352 2062 1337 2062 1353 2063 1354 2063 904 2063 904 2064 1354 2064 1355 2064 904 2065 1355 2065 905 2065 905 2066 1355 2066 1356 2066 905 2067 1356 2067 906 2067 906 2068 1356 2068 1357 2068 906 2069 1357 2069 907 2069 907 2070 1357 2070 1358 2070 907 2071 1358 2071 908 2071 908 2072 1358 2072 1359 2072 908 2073 1359 2073 909 2073 909 2074 1359 2074 1360 2074 909 2075 1360 2075 910 2075 910 2076 1360 2076 1361 2076 910 2077 1361 2077 911 2077 911 2078 1361 2078 1362 2078 911 2079 1362 2079 912 2079 912 2080 1362 2080 1363 2080 912 2081 1363 2081 913 2081 913 2082 1363 2082 1364 2082 913 2083 1364 2083 914 2083 914 2084 1364 2084 1365 2084 914 2085 1365 2085 1366 2085 1365 2086 1367 2086 1366 2086 1366 2087 1367 2087 1368 2087 1366 2088 1368 2088 917 2088 917 2089 1368 2089 1369 2089 917 2090 1369 2090 918 2090 918 2091 1369 2091 1370 2091 918 2092 1370 2092 919 2092 919 2093 1370 2093 1371 2093 919 2094 1371 2094 920 2094 920 2095 1371 2095 1372 2095 920 2096 1372 2096 921 2096 921 2097 1372 2097 1373 2097 921 2098 1373 2098 896 2098 896 2099 1373 2099 1374 2099 896 2100 1374 2100 897 2100 897 2101 1374 2101 1375 2101 897 2102 1375 2102 898 2102 898 2103 1375 2103 1376 2103 898 2104 1376 2104 899 2104 899 2105 1376 2105 1377 2105 899 2106 1377 2106 900 2106 900 2107 1377 2107 1378 2107 900 2108 1378 2108 901 2108 901 2109 1378 2109 1379 2109 901 2110 1379 2110 1353 2110 1353 2111 1379 2111 1380 2111 1353 2112 1380 2112 1354 2112 1381 2113 1382 2113 1383 2113 1384 2114 1385 2114 1386 2114 1385 2115 1384 2115 1387 2115 1388 2116 1162 2116 1161 2116 1389 2117 1390 2117 1391 2117 1392 2118 1391 2118 1393 2118 1394 2119 1395 2119 1392 2119 1392 2120 1395 2120 1391 2120 1391 2121 1395 2121 1396 2121 1391 2122 1396 2122 1389 2122 1397 2123 1392 2123 1398 2123 1398 2124 1392 2124 1399 2124 1397 2125 1400 2125 1392 2125 1392 2126 1400 2126 1401 2126 1392 2127 1401 2127 1394 2127 1402 2128 1403 2128 1404 2128 1404 2129 1403 2129 1405 2129 1404 2130 1405 2130 1399 2130 1399 2131 1405 2131 1406 2131 1399 2132 1406 2132 1398 2132 1407 2133 1408 2133 1409 2133 1409 2134 1408 2134 1410 2134 1409 2135 1410 2135 1402 2135 1402 2136 1410 2136 1411 2136 1402 2137 1411 2137 1403 2137 1383 2138 1412 2138 1413 2138 1414 2139 1415 2139 1382 2139 1382 2140 1415 2140 1416 2140 1382 2141 1416 2141 1383 2141 1383 2142 1416 2142 1417 2142 1383 2143 1417 2143 1412 2143 1170 2144 1418 2144 1168 2144 1168 2145 1418 2145 1414 2145 1168 2146 1414 2146 1163 2146 1163 2147 1414 2147 1382 2147 1163 2148 1382 2148 1164 2148 1164 2149 1382 2149 1381 2149 1164 2150 1381 2150 1166 2150 1166 2151 1381 2151 1167 2151 1387 2152 1388 2152 1385 2152 1385 2153 1388 2153 1161 2153 1385 2154 1161 2154 1386 2154 1386 2155 1161 2155 1160 2155 1386 2156 1160 2156 1159 2156 1162 2157 1388 2157 1152 2157 1152 2158 1388 2158 1419 2158 1152 2159 1419 2159 1153 2159 1420 2160 1421 2160 1386 2160 1386 2161 1421 2161 1422 2161 1386 2162 1422 2162 1384 2162 1423 2163 1424 2163 1425 2163 1425 2164 1424 2164 1426 2164 1425 2165 1426 2165 1427 2165 1427 2166 1426 2166 1428 2166 1429 2167 1430 2167 1431 2167 1431 2168 1430 2168 1423 2168 1431 2169 1423 2169 1432 2169 1432 2170 1423 2170 1425 2170 1432 2171 1425 2171 1433 2171 1433 2172 1425 2172 1427 2172 1433 2173 1427 2173 1420 2173 1420 2174 1427 2174 1428 2174 1420 2175 1428 2175 1421 2175 1393 2176 1434 2176 1392 2176 1392 2177 1434 2177 1435 2177 1392 2178 1435 2178 1399 2178 1399 2179 1435 2179 1436 2179 1399 2180 1436 2180 1404 2180 1404 2181 1436 2181 1437 2181 1404 2182 1437 2182 1402 2182 1402 2183 1437 2183 1438 2183 1402 2184 1438 2184 1409 2184 1409 2185 1438 2185 1439 2185 1409 2186 1439 2186 1440 2186 1440 2187 1439 2187 1441 2187 1440 2188 1441 2188 1442 2188 1158 2189 1167 2189 1442 2189 1442 2190 1167 2190 1381 2190 1442 2191 1381 2191 1440 2191 1440 2192 1381 2192 1383 2192 1440 2193 1383 2193 1409 2193 1409 2194 1383 2194 1413 2194 1409 2195 1413 2195 1407 2195 1434 2196 1443 2196 1435 2196 1435 2197 1443 2197 1429 2197 1435 2198 1429 2198 1436 2198 1436 2199 1429 2199 1431 2199 1436 2200 1431 2200 1437 2200 1437 2201 1431 2201 1432 2201 1437 2202 1432 2202 1438 2202 1438 2203 1432 2203 1433 2203 1438 2204 1433 2204 1439 2204 1439 2205 1433 2205 1420 2205 1439 2206 1420 2206 1441 2206 1441 2207 1420 2207 1386 2207 1441 2208 1386 2208 1442 2208 1442 2209 1386 2209 1159 2209 1442 2210 1159 2210 1158 2210 1444 2211 1445 2211 1446 2211 1447 2212 1448 2212 1449 2212 1450 2213 1451 2213 1452 2213 1453 2214 1454 2214 1455 2214 1456 2215 1457 2215 1458 2215 1456 2216 1458 2216 1459 2216 1455 2217 1460 2217 1456 2217 1456 2218 1460 2218 1461 2218 1461 2219 1462 2219 1456 2219 1456 2220 1462 2220 1463 2220 1456 2221 1463 2221 1457 2221 1454 2222 1464 2222 1455 2222 1455 2223 1464 2223 1465 2223 1455 2224 1465 2224 1460 2224 1466 2225 1467 2225 1468 2225 1468 2226 1469 2226 1466 2226 1466 2227 1469 2227 1470 2227 1466 2228 1470 2228 1471 2228 1472 2229 1473 2229 1474 2229 1475 2230 1476 2230 1477 2230 1477 2231 1476 2231 1472 2231 1477 2232 1472 2232 1478 2232 1478 2233 1472 2233 1474 2233 1476 2234 1479 2234 1472 2234 1472 2235 1479 2235 1480 2235 1472 2236 1480 2236 1473 2236 1473 2237 1480 2237 1481 2237 1473 2238 1481 2238 1452 2238 1452 2239 1481 2239 1482 2239 1452 2240 1482 2240 1450 2240 1475 2241 1477 2241 1483 2241 1483 2242 1477 2242 1484 2242 1483 2243 1484 2243 1485 2243 1485 2244 1484 2244 1486 2244 1486 2245 1484 2245 1487 2245 1486 2246 1487 2246 1488 2246 1489 2247 1490 2247 1491 2247 1491 2248 1490 2248 1492 2248 1491 2249 1492 2249 1487 2249 1487 2250 1492 2250 1493 2250 1487 2251 1493 2251 1488 2251 1489 2252 1491 2252 1494 2252 1494 2253 1491 2253 1446 2253 1494 2254 1446 2254 1495 2254 1496 2255 1497 2255 1498 2255 1496 2256 1498 2256 1499 2256 1495 2257 1446 2257 1498 2257 1498 2258 1446 2258 1445 2258 1498 2259 1445 2259 1499 2259 1500 2260 1501 2260 1502 2260 1458 2261 1503 2261 1459 2261 1459 2262 1503 2262 1504 2262 1459 2263 1504 2263 1505 2263 1505 2264 1504 2264 1506 2264 1505 2265 1506 2265 1500 2265 1500 2266 1502 2266 1505 2266 1505 2267 1502 2267 1507 2267 1505 2268 1507 2268 1508 2268 1508 2269 1447 2269 1505 2269 1505 2270 1447 2270 1449 2270 1505 2271 1449 2271 1459 2271 1459 2272 1449 2272 1509 2272 1459 2273 1509 2273 1456 2273 1456 2274 1509 2274 1510 2274 1456 2275 1510 2275 1455 2275 1455 2276 1510 2276 1471 2276 1455 2277 1471 2277 1453 2277 1453 2278 1471 2278 1470 2278 1448 2279 1444 2279 1449 2279 1449 2280 1444 2280 1446 2280 1449 2281 1446 2281 1509 2281 1509 2282 1446 2282 1491 2282 1509 2283 1491 2283 1510 2283 1510 2284 1491 2284 1487 2284 1510 2285 1487 2285 1471 2285 1471 2286 1487 2286 1484 2286 1471 2287 1484 2287 1466 2287 1466 2288 1484 2288 1477 2288 1466 2289 1477 2289 1467 2289 1467 2290 1477 2290 1478 2290 961 2291 1511 2291 959 2291 959 2292 1511 2292 1512 2292 959 2293 1512 2293 958 2293 958 2294 1512 2294 950 2294 950 2295 1512 2295 1513 2295 950 2296 1513 2296 951 2296 951 2297 1513 2297 1514 2297 951 2298 1514 2298 952 2298 952 2299 1514 2299 956 2299 956 2300 1514 2300 1515 2300 956 2301 1515 2301 953 2301 1515 2302 1516 2302 953 2302 953 2303 1516 2303 1517 2303 953 2304 1517 2304 954 2304 1518 2305 1519 2305 1520 2305 1521 2306 1522 2306 1523 2306 1524 2307 1525 2307 1526 2307 1527 2308 1528 2308 1529 2308 1529 2309 1530 2309 1527 2309 1527 2310 1530 2310 1531 2310 1527 2311 1531 2311 1525 2311 1525 2312 1531 2312 1532 2312 1525 2313 1532 2313 1526 2313 1533 2314 1534 2314 1526 2314 1526 2315 1534 2315 1535 2315 1526 2316 1535 2316 1524 2316 1536 2317 1537 2317 1538 2317 1537 2318 1536 2318 1539 2318 1539 2319 1536 2319 1540 2319 1539 2320 1540 2320 1541 2320 1542 2321 1543 2321 1544 2321 1544 2322 1543 2322 1545 2322 1546 2323 1547 2323 1548 2323 1548 2324 1547 2324 1549 2324 1548 2325 1549 2325 1543 2325 1543 2326 1549 2326 1550 2326 1543 2327 1550 2327 1545 2327 1546 2328 1548 2328 1551 2328 1551 2329 1548 2329 1552 2329 1551 2330 1552 2330 1553 2330 1553 2331 1552 2331 1554 2331 1553 2332 1554 2332 1555 2332 1555 2333 1554 2333 1523 2333 1523 2334 1554 2334 1556 2334 1523 2335 1556 2335 1521 2335 1519 2336 1557 2336 1558 2336 1559 2337 1560 2337 1561 2337 1561 2338 1560 2338 1562 2338 1561 2339 1562 2339 1563 2339 1563 2340 1562 2340 1564 2340 1563 2341 1564 2341 1520 2341 1520 2342 1564 2342 1565 2342 1520 2343 1565 2343 1518 2343 1559 2344 1561 2344 1566 2344 1566 2345 1561 2345 1567 2345 1566 2346 1567 2346 1568 2346 1532 2347 1569 2347 1526 2347 1526 2348 1569 2348 1570 2348 1526 2349 1570 2349 1533 2349 1533 2350 1570 2350 1571 2350 1533 2351 1571 2351 1567 2351 1567 2352 1571 2352 1572 2352 1567 2353 1572 2353 1568 2353 1573 2354 1574 2354 1554 2354 1554 2355 1574 2355 1575 2355 1554 2356 1575 2356 1556 2356 1542 2357 1541 2357 1543 2357 1543 2358 1541 2358 1540 2358 1543 2359 1540 2359 1548 2359 1548 2360 1540 2360 1576 2360 1548 2361 1576 2361 1552 2361 1552 2362 1576 2362 1577 2362 1552 2363 1577 2363 1554 2363 1554 2364 1577 2364 1578 2364 1554 2365 1578 2365 1573 2365 1573 2366 1578 2366 1579 2366 1519 2367 1558 2367 1520 2367 1520 2368 1558 2368 1580 2368 1520 2369 1580 2369 1581 2369 1538 2370 1534 2370 1536 2370 1536 2371 1534 2371 1533 2371 1536 2372 1533 2372 1540 2372 1540 2373 1533 2373 1567 2373 1540 2374 1567 2374 1576 2374 1576 2375 1567 2375 1561 2375 1576 2376 1561 2376 1577 2376 1577 2377 1561 2377 1563 2377 1577 2378 1563 2378 1578 2378 1578 2379 1563 2379 1520 2379 1578 2380 1520 2380 1579 2380 1579 2381 1520 2381 1581 2381 1582 2382 1170 2382 1169 2382 1583 2383 1584 2383 1585 2383 1585 2384 1584 2384 1586 2384 1587 2385 1588 2385 1583 2385 1583 2386 1588 2386 1589 2386 1583 2387 1589 2387 1584 2387 1590 2388 1591 2388 1322 2388 1322 2389 1591 2389 1592 2389 1322 2390 1592 2390 1593 2390 1593 2391 1594 2391 1322 2391 1322 2392 1594 2392 1595 2392 1322 2393 1595 2393 1169 2393 1169 2394 1595 2394 1596 2394 1169 2395 1596 2395 1582 2395 1584 2396 1590 2396 1586 2396 1586 2397 1590 2397 1322 2397 1586 2398 1322 2398 1597 2398 1597 2399 1322 2399 1321 2399 1597 2400 1321 2400 1598 2400 1598 2401 1321 2401 1320 2401 1598 2402 1320 2402 1599 2402 1599 2403 1320 2403 1319 2403 1599 2404 1319 2404 1600 2404 1600 2405 1319 2405 1117 2405 1600 2406 1117 2406 1601 2406 1601 2407 1117 2407 1116 2407 1601 2408 1116 2408 1602 2408 1602 2409 1116 2409 1317 2409 1602 2410 1317 2410 1603 2410 1603 2411 1317 2411 1314 2411 1603 2412 1314 2412 1604 2412 1311 2413 1605 2413 1312 2413 1312 2414 1605 2414 1606 2414 1604 2415 1314 2415 1606 2415 1606 2416 1314 2416 1313 2416 1606 2417 1313 2417 1312 2417 1119 2418 1607 2418 1120 2418 1120 2419 1607 2419 1528 2419 1525 2420 1524 2420 1608 2420 1527 2421 1305 2421 1528 2421 1528 2422 1305 2422 1304 2422 1528 2423 1304 2423 1120 2423 1527 2424 1525 2424 1305 2424 1305 2425 1525 2425 1608 2425 1305 2426 1608 2426 1306 2426 1306 2427 1608 2427 1609 2427 1306 2428 1609 2428 1307 2428 1307 2429 1609 2429 1610 2429 1307 2430 1610 2430 1310 2430 1310 2431 1610 2431 1611 2431 1310 2432 1611 2432 1311 2432 1311 2433 1611 2433 1612 2433 1311 2434 1612 2434 1605 2434 1524 2435 1535 2435 1608 2435 1608 2436 1535 2436 1534 2436 1608 2437 1534 2437 1613 2437 1613 2438 1534 2438 1538 2438 1478 2439 1474 2439 1279 2439 1468 2440 1467 2440 1614 2440 1614 2441 1467 2441 1615 2441 1474 2442 1473 2442 1279 2442 1279 2443 1473 2443 1452 2443 1279 2444 1452 2444 1280 2444 1280 2445 1452 2445 1451 2445 1280 2446 1451 2446 1281 2446 1281 2447 1451 2447 1616 2447 1281 2448 1616 2448 1282 2448 1282 2449 1616 2449 1617 2449 1282 2450 1617 2450 1286 2450 1286 2451 1617 2451 1618 2451 1286 2452 1618 2452 1287 2452 1287 2453 1618 2453 1619 2453 1287 2454 1619 2454 1288 2454 1288 2455 1619 2455 1620 2455 1288 2456 1620 2456 1289 2456 1289 2457 1620 2457 1621 2457 1289 2458 1621 2458 1290 2458 1290 2459 1621 2459 1622 2459 1290 2460 1622 2460 1293 2460 1293 2461 1622 2461 1623 2461 1293 2462 1623 2462 1294 2462 1294 2463 1623 2463 1624 2463 1294 2464 1624 2464 1295 2464 1295 2465 1624 2465 1625 2465 1295 2466 1625 2466 1296 2466 1296 2467 1625 2467 1626 2467 1296 2468 1626 2468 1297 2468 1297 2469 1626 2469 1627 2469 1297 2470 1627 2470 1298 2470 1298 2471 1627 2471 1628 2471 1298 2472 1628 2472 1299 2472 1299 2473 1628 2473 1629 2473 1299 2474 1629 2474 1302 2474 1302 2475 1629 2475 1630 2475 1302 2476 1630 2476 1119 2476 1119 2477 1630 2477 1631 2477 1119 2478 1631 2478 1607 2478 1632 2479 1633 2479 1265 2479 1265 2480 1633 2480 1634 2480 1265 2481 1634 2481 1269 2481 1269 2482 1634 2482 1635 2482 1269 2483 1635 2483 1270 2483 1270 2484 1635 2484 1636 2484 1270 2485 1636 2485 1271 2485 1271 2486 1636 2486 1637 2486 1271 2487 1637 2487 1272 2487 1272 2488 1637 2488 1638 2488 1272 2489 1638 2489 1273 2489 1273 2490 1638 2490 1639 2490 1273 2491 1639 2491 1276 2491 1276 2492 1639 2492 1640 2492 1276 2493 1640 2493 1277 2493 1277 2494 1640 2494 1641 2494 1277 2495 1641 2495 1278 2495 1278 2496 1641 2496 1642 2496 1278 2497 1642 2497 1279 2497 1279 2498 1642 2498 1615 2498 1279 2499 1615 2499 1478 2499 1478 2500 1615 2500 1467 2500 1265 2501 1264 2501 1632 2501 1632 2502 1264 2502 1263 2502 1632 2503 1263 2503 1643 2503 1643 2504 1263 2504 1262 2504 1643 2505 1262 2505 1644 2505 1644 2506 1262 2506 1261 2506 1645 2507 1260 2507 1646 2507 1646 2508 1260 2508 1172 2508 1646 2509 1172 2509 1647 2509 1647 2510 1172 2510 1011 2510 1645 2511 1648 2511 1260 2511 1260 2512 1648 2512 1649 2512 1260 2513 1649 2513 1650 2513 1650 2514 1651 2514 1260 2514 1260 2515 1651 2515 1652 2515 1260 2516 1652 2516 1261 2516 1261 2517 1652 2517 1653 2517 1261 2518 1653 2518 1644 2518 1651 2519 1654 2519 1652 2519 1652 2520 1654 2520 1655 2520 1652 2521 1655 2521 1517 2521 1517 2522 1655 2522 1656 2522 1517 2523 1656 2523 954 2523 1657 2524 1658 2524 1659 2524 1659 2525 1658 2525 1660 2525 1659 2526 1660 2526 1661 2526 1660 2527 1662 2527 1661 2527 1661 2528 1662 2528 1663 2528 1661 2529 1663 2529 1664 2529 1664 2530 1663 2530 1665 2530 1659 2531 1666 2531 1657 2531 1657 2532 1666 2532 1667 2532 1657 2533 1667 2533 1668 2533 1668 2534 1669 2534 1657 2534 1657 2535 1669 2535 1670 2535 1657 2536 1670 2536 1671 2536 1671 2537 1672 2537 1657 2537 1657 2538 1672 2538 1673 2538 1657 2539 1673 2539 1674 2539 1674 2540 1675 2540 1657 2540 1657 2541 1675 2541 1676 2541 1657 2542 1676 2542 1677 2542 1678 2543 1679 2543 1680 2543 1680 2544 1679 2544 1681 2544 1680 2545 1681 2545 1682 2545 1663 2546 1683 2546 1665 2546 1665 2547 1683 2547 1679 2547 1665 2548 1679 2548 1684 2548 1684 2549 1679 2549 1678 2549 987 2550 986 2550 1685 2550 1685 2551 986 2551 985 2551 985 2552 998 2552 1685 2552 1685 2553 998 2553 1000 2553 1685 2554 1000 2554 1001 2554 1686 2555 1687 2555 1688 2555 968 2556 981 2556 1686 2556 1686 2557 981 2557 980 2557 1686 2558 989 2558 1685 2558 1685 2559 989 2559 988 2559 1685 2560 988 2560 987 2560 1688 2561 1689 2561 1686 2561 1686 2562 1689 2562 1690 2562 1686 2563 1690 2563 1691 2563 1691 2564 1692 2564 1686 2564 1686 2565 1692 2565 1693 2565 1686 2566 1693 2566 1694 2566 1032 2567 975 2567 1694 2567 1694 2568 975 2568 977 2568 1694 2569 977 2569 1686 2569 1686 2570 977 2570 978 2570 1686 2571 978 2571 968 2571 980 2572 966 2572 1686 2572 1686 2573 966 2573 965 2573 1686 2574 965 2574 989 2574 1096 2575 1095 2575 1695 2575 1696 2576 1091 2576 1090 2576 1106 2577 1697 2577 1107 2577 1107 2578 1697 2578 1095 2578 1697 2579 1698 2579 1095 2579 1095 2580 1698 2580 1699 2580 1095 2581 1699 2581 1695 2581 1695 2582 1699 2582 1700 2582 1695 2583 1700 2583 1701 2583 1087 2584 1085 2584 1695 2584 1695 2585 1085 2585 1094 2585 1695 2586 1094 2586 1093 2586 1106 2587 1115 2587 1697 2587 1697 2588 1115 2588 1114 2588 1697 2589 1114 2589 1702 2589 1702 2590 1114 2590 1033 2590 1701 2591 1703 2591 1695 2591 1695 2592 1703 2592 1704 2592 1695 2593 1704 2593 1705 2593 1696 2594 1090 2594 1695 2594 1695 2595 1090 2595 1088 2595 1695 2596 1088 2596 1087 2596 1093 2597 1100 2597 1695 2597 1695 2598 1100 2598 1098 2598 1695 2599 1098 2599 1096 2599 1706 2600 1707 2600 1708 2600 1709 2601 1710 2601 1711 2601 1712 2602 1713 2602 1714 2602 1715 2603 1716 2603 1717 2603 1718 2604 1719 2604 1720 2604 1721 2605 1722 2605 1723 2605 1723 2606 1722 2606 1724 2606 1723 2607 1724 2607 1725 2607 1718 2608 1726 2608 1719 2608 1719 2609 1726 2609 1727 2609 1719 2610 1727 2610 1723 2610 1723 2611 1727 2611 1728 2611 1723 2612 1728 2612 1721 2612 1729 2613 1730 2613 1720 2613 1720 2614 1730 2614 1731 2614 1720 2615 1731 2615 1718 2615 1732 2616 1733 2616 1734 2616 1735 2617 1736 2617 1737 2617 1737 2618 1736 2618 1738 2618 1737 2619 1738 2619 1739 2619 1740 2620 1735 2620 1717 2620 1717 2621 1735 2621 1737 2621 1717 2622 1737 2622 1715 2622 1715 2623 1737 2623 1741 2623 1715 2624 1741 2624 1742 2624 1742 2625 1741 2625 1713 2625 1742 2626 1713 2626 1743 2626 1743 2627 1713 2627 1712 2627 1744 2628 1745 2628 1714 2628 1714 2629 1745 2629 1746 2629 1714 2630 1746 2630 1712 2630 1747 2631 1748 2631 1749 2631 1750 2632 1751 2632 1749 2632 1749 2633 1751 2633 1752 2633 1749 2634 1752 2634 1747 2634 1747 2635 1752 2635 1753 2635 1747 2636 1753 2636 1754 2636 1755 2637 1756 2637 1757 2637 1757 2638 1756 2638 1758 2638 1757 2639 1758 2639 1759 2639 1759 2640 1758 2640 1760 2640 1759 2641 1760 2641 1708 2641 1708 2642 1760 2642 1761 2642 1708 2643 1761 2643 1706 2643 1706 2644 1761 2644 1762 2644 1763 2645 1723 2645 1764 2645 1764 2646 1723 2646 1725 2646 1764 2647 1725 2647 1765 2647 1765 2648 1725 2648 1766 2648 1765 2649 1766 2649 1767 2649 1733 2650 1729 2650 1734 2650 1734 2651 1729 2651 1720 2651 1734 2652 1720 2652 1768 2652 1768 2653 1720 2653 1769 2653 1769 2654 1720 2654 1719 2654 1769 2655 1719 2655 1770 2655 1770 2656 1719 2656 1723 2656 1770 2657 1723 2657 1771 2657 1771 2658 1723 2658 1763 2658 1771 2659 1763 2659 1772 2659 1739 2660 1732 2660 1737 2660 1737 2661 1732 2661 1734 2661 1737 2662 1734 2662 1741 2662 1741 2663 1734 2663 1768 2663 1741 2664 1768 2664 1713 2664 1713 2665 1768 2665 1769 2665 1713 2666 1769 2666 1714 2666 1714 2667 1769 2667 1770 2667 1714 2668 1770 2668 1744 2668 1744 2669 1770 2669 1771 2669 1744 2670 1771 2670 1755 2670 1755 2671 1771 2671 1772 2671 1755 2672 1772 2672 1756 2672 1709 2673 1711 2673 1754 2673 1754 2674 1711 2674 1773 2674 1754 2675 1773 2675 1747 2675 1747 2676 1773 2676 1774 2676 1747 2677 1774 2677 1748 2677 1710 2678 1745 2678 1711 2678 1711 2679 1745 2679 1744 2679 1711 2680 1744 2680 1773 2680 1773 2681 1744 2681 1755 2681 1773 2682 1755 2682 1774 2682 1774 2683 1755 2683 1757 2683 1774 2684 1757 2684 1748 2684 1748 2685 1757 2685 1759 2685 1748 2686 1759 2686 1749 2686 1749 2687 1759 2687 1708 2687 1749 2688 1708 2688 1750 2688 1750 2689 1708 2689 1707 2689 1775 2690 1331 2690 1332 2690 1144 2691 1143 2691 1342 2691 1141 2692 1140 2692 1344 2692 1336 2693 1337 2693 1215 2693 1351 2694 1209 2694 1213 2694 1351 2695 1213 2695 1352 2695 1213 2696 1129 2696 1352 2696 1352 2697 1129 2697 1128 2697 1352 2698 1128 2698 1337 2698 1337 2699 1128 2699 1217 2699 1337 2700 1217 2700 1215 2700 1209 2701 1351 2701 1210 2701 1210 2702 1351 2702 1350 2702 1210 2703 1350 2703 1131 2703 1349 2704 1204 2704 1208 2704 1349 2705 1208 2705 1350 2705 1350 2706 1208 2706 1132 2706 1350 2707 1132 2707 1131 2707 1204 2708 1349 2708 1205 2708 1205 2709 1349 2709 1348 2709 1205 2710 1348 2710 1134 2710 1347 2711 1199 2711 1203 2711 1347 2712 1203 2712 1348 2712 1348 2713 1203 2713 1135 2713 1348 2714 1135 2714 1134 2714 1199 2715 1347 2715 1200 2715 1200 2716 1347 2716 1776 2716 1200 2717 1776 2717 1137 2717 1344 2718 1140 2718 1776 2718 1776 2719 1140 2719 1138 2719 1776 2720 1138 2720 1137 2720 1141 2721 1344 2721 1197 2721 1197 2722 1344 2722 1343 2722 1197 2723 1343 2723 1198 2723 1342 2724 1143 2724 1343 2724 1343 2725 1143 2725 1195 2725 1343 2726 1195 2726 1198 2726 1144 2727 1342 2727 1194 2727 1194 2728 1342 2728 1341 2728 1194 2729 1341 2729 1190 2729 1340 2730 1146 2730 1341 2730 1341 2731 1146 2731 1191 2731 1341 2732 1191 2732 1190 2732 1339 2733 1189 2733 1340 2733 1340 2734 1189 2734 1147 2734 1340 2735 1147 2735 1146 2735 1182 2736 1187 2736 1326 2736 1326 2737 1187 2737 1186 2737 1326 2738 1186 2738 1338 2738 1338 2739 1186 2739 1184 2739 1338 2740 1184 2740 1339 2740 1339 2741 1184 2741 1183 2741 1339 2742 1183 2742 1189 2742 1182 2743 1326 2743 1181 2743 1181 2744 1326 2744 1327 2744 1181 2745 1327 2745 1177 2745 1177 2746 1327 2746 1178 2746 1178 2747 1327 2747 1328 2747 1178 2748 1328 2748 1149 2748 1329 2749 1176 2749 1328 2749 1328 2750 1176 2750 1150 2750 1328 2751 1150 2751 1149 2751 1685 2752 1001 2752 1329 2752 1329 2753 1001 2753 1175 2753 1329 2754 1175 2754 1176 2754 1687 2755 1686 2755 1325 2755 1325 2756 1686 2756 1685 2756 1325 2757 1685 2757 1330 2757 1330 2758 1685 2758 1329 2758 1324 2759 1777 2759 1778 2759 1778 2760 1779 2760 1324 2760 1324 2761 1779 2761 1780 2761 1324 2762 1780 2762 1325 2762 1325 2763 1780 2763 1781 2763 1325 2764 1781 2764 1687 2764 1782 2765 1783 2765 1324 2765 1324 2766 1783 2766 1784 2766 1324 2767 1784 2767 1777 2767 1775 2768 1785 2768 1331 2768 1331 2769 1785 2769 1786 2769 1331 2770 1786 2770 1324 2770 1324 2771 1786 2771 1787 2771 1324 2772 1787 2772 1782 2772 1156 2773 1155 2773 1333 2773 1333 2774 1155 2774 1153 2774 1333 2775 1153 2775 1332 2775 1332 2776 1153 2776 1788 2776 1332 2777 1788 2777 1775 2777 1156 2778 1333 2778 1221 2778 1221 2779 1333 2779 1334 2779 1221 2780 1334 2780 1122 2780 1335 2781 1125 2781 1334 2781 1334 2782 1125 2782 1123 2782 1334 2783 1123 2783 1122 2783 1215 2784 1214 2784 1336 2784 1336 2785 1214 2785 1219 2785 1336 2786 1219 2786 1335 2786 1335 2787 1219 2787 1126 2787 1335 2788 1126 2788 1125 2788 1789 2789 1356 2789 1355 2789 1790 2790 1791 2790 1370 2790 1792 2791 1375 2791 1793 2791 1793 2792 1375 2792 1374 2792 1794 2793 1795 2793 1373 2793 1373 2794 1795 2794 1796 2794 1373 2795 1796 2795 1374 2795 1374 2796 1796 2796 1797 2796 1374 2797 1797 2797 1793 2797 1794 2798 1373 2798 1798 2798 1798 2799 1373 2799 1372 2799 1798 2800 1372 2800 1799 2800 1799 2801 1372 2801 1800 2801 1800 2802 1372 2802 1371 2802 1800 2803 1371 2803 1801 2803 1370 2804 1791 2804 1371 2804 1371 2805 1791 2805 1802 2805 1371 2806 1802 2806 1801 2806 1790 2807 1370 2807 1803 2807 1803 2808 1370 2808 1369 2808 1803 2809 1369 2809 1804 2809 1368 2810 1367 2810 1805 2810 1805 2811 1806 2811 1368 2811 1368 2812 1806 2812 1807 2812 1368 2813 1807 2813 1369 2813 1369 2814 1807 2814 1808 2814 1369 2815 1808 2815 1804 2815 1809 2816 1810 2816 1365 2816 1365 2817 1810 2817 1811 2817 1365 2818 1811 2818 1367 2818 1367 2819 1811 2819 1812 2819 1367 2820 1812 2820 1805 2820 1809 2821 1365 2821 1813 2821 1813 2822 1365 2822 1364 2822 1813 2823 1364 2823 1814 2823 1814 2824 1364 2824 1815 2824 1815 2825 1364 2825 1363 2825 1815 2826 1363 2826 1816 2826 1361 2827 1817 2827 1818 2827 1361 2828 1818 2828 1362 2828 1818 2829 1819 2829 1362 2829 1362 2830 1819 2830 1820 2830 1362 2831 1820 2831 1363 2831 1363 2832 1820 2832 1821 2832 1363 2833 1821 2833 1816 2833 1359 2834 1822 2834 1823 2834 1359 2835 1823 2835 1360 2835 1823 2836 1824 2836 1360 2836 1360 2837 1824 2837 1825 2837 1360 2838 1825 2838 1361 2838 1361 2839 1825 2839 1826 2839 1361 2840 1826 2840 1817 2840 1358 2841 1827 2841 1359 2841 1359 2842 1827 2842 1828 2842 1359 2843 1828 2843 1822 2843 1357 2844 1829 2844 1358 2844 1358 2845 1829 2845 1830 2845 1358 2846 1830 2846 1827 2846 1789 2847 1762 2847 1356 2847 1356 2848 1762 2848 1831 2848 1356 2849 1831 2849 1357 2849 1357 2850 1831 2850 1832 2850 1357 2851 1832 2851 1829 2851 1833 2852 1354 2852 1834 2852 1834 2853 1354 2853 1835 2853 1833 2854 1836 2854 1354 2854 1354 2855 1836 2855 1837 2855 1354 2856 1837 2856 1355 2856 1355 2857 1837 2857 1838 2857 1355 2858 1838 2858 1789 2858 1380 2859 1839 2859 1840 2859 1840 2860 1841 2860 1380 2860 1380 2861 1841 2861 1842 2861 1380 2862 1842 2862 1354 2862 1354 2863 1842 2863 1843 2863 1354 2864 1843 2864 1835 2864 1695 2865 1705 2865 1380 2865 1705 2866 1844 2866 1380 2866 1380 2867 1844 2867 1845 2867 1380 2868 1845 2868 1839 2868 1091 2869 1696 2869 1378 2869 1378 2870 1696 2870 1695 2870 1378 2871 1695 2871 1379 2871 1379 2872 1695 2872 1380 2872 1377 2873 1376 2873 1846 2873 1846 2874 1847 2874 1377 2874 1377 2875 1847 2875 1848 2875 1377 2876 1848 2876 1378 2876 1378 2877 1848 2877 1849 2877 1378 2878 1849 2878 1091 2878 1792 2879 1850 2879 1375 2879 1375 2880 1850 2880 1851 2880 1375 2881 1851 2881 1376 2881 1376 2882 1851 2882 1852 2882 1376 2883 1852 2883 1846 2883 1434 2884 1393 2884 1853 2884 1775 2885 1853 2885 1854 2885 1153 2886 1419 2886 1788 2886 1788 2887 1419 2887 1388 2887 1788 2888 1388 2888 1387 2888 1428 2889 1775 2889 1421 2889 1421 2890 1775 2890 1788 2890 1428 2891 1426 2891 1775 2891 1775 2892 1426 2892 1424 2892 1775 2893 1424 2893 1423 2893 1387 2894 1384 2894 1788 2894 1788 2895 1384 2895 1422 2895 1788 2896 1422 2896 1421 2896 1854 2897 1855 2897 1775 2897 1775 2898 1855 2898 1856 2898 1775 2899 1856 2899 1857 2899 1785 2900 1775 2900 1858 2900 1858 2901 1775 2901 1859 2901 1857 2902 1860 2902 1775 2902 1775 2903 1860 2903 1861 2903 1775 2904 1861 2904 1859 2904 1423 2905 1430 2905 1775 2905 1775 2906 1430 2906 1429 2906 1775 2907 1429 2907 1853 2907 1853 2908 1429 2908 1443 2908 1853 2909 1443 2909 1434 2909 1837 2910 1862 2910 1838 2910 1838 2911 1862 2911 1863 2911 1838 2912 1863 2912 1864 2912 1838 2913 1746 2913 1745 2913 1716 2914 1715 2914 1865 2914 1865 2915 1715 2915 1742 2915 1745 2916 1710 2916 1838 2916 1838 2917 1710 2917 1709 2917 1838 2918 1709 2918 1754 2918 1751 2919 1750 2919 1838 2919 1838 2920 1750 2920 1707 2920 1838 2921 1707 2921 1789 2921 1789 2922 1707 2922 1706 2922 1789 2923 1706 2923 1762 2923 1865 2924 1746 2924 1866 2924 1866 2925 1746 2925 1838 2925 1866 2926 1838 2926 1867 2926 1867 2927 1838 2927 1864 2927 1742 2928 1743 2928 1865 2928 1865 2929 1743 2929 1712 2929 1865 2930 1712 2930 1746 2930 1754 2931 1753 2931 1838 2931 1838 2932 1753 2932 1752 2932 1838 2933 1752 2933 1751 2933 1583 2934 1585 2934 1868 2934 1587 2935 1583 2935 1869 2935 1869 2936 1583 2936 1868 2936 1869 2937 1868 2937 1870 2937 1870 2938 1868 2938 1871 2938 1872 2939 1873 2939 1874 2939 1874 2940 1873 2940 1875 2940 1876 2941 1873 2941 1877 2941 1877 2942 1873 2942 1872 2942 1877 2943 1872 2943 1878 2943 1876 2944 1879 2944 1873 2944 1873 2945 1879 2945 1880 2945 1873 2946 1880 2946 1871 2946 1871 2947 1880 2947 1881 2947 1871 2948 1881 2948 1870 2948 1480 2949 1479 2949 1882 2949 1883 2950 1884 2950 1885 2950 1568 2951 1572 2951 1886 2951 1532 2952 1531 2952 1887 2952 1887 2953 1531 2953 1530 2953 1887 2954 1530 2954 1529 2954 1571 2955 1570 2955 1888 2955 1888 2956 1570 2956 1569 2956 1568 2957 1886 2957 1566 2957 1565 2958 1564 2958 1889 2958 1564 2959 1562 2959 1889 2959 1889 2960 1562 2960 1560 2960 1889 2961 1560 2961 1559 2961 1890 2962 1557 2962 1891 2962 1891 2963 1557 2963 1519 2963 1891 2964 1519 2964 1518 2964 1892 2965 1893 2965 1891 2965 1891 2966 1893 2966 1894 2966 1891 2967 1894 2967 1890 2967 1895 2968 1896 2968 1897 2968 1895 2969 1897 2969 1898 2969 1897 2970 1899 2970 1898 2970 1898 2971 1899 2971 1900 2971 1898 2972 1900 2972 1892 2972 1892 2973 1900 2973 1901 2973 1892 2974 1901 2974 1893 2974 1896 2975 1895 2975 1902 2975 1902 2976 1895 2976 1903 2976 1902 2977 1903 2977 1904 2977 1904 2978 1903 2978 1905 2978 1905 2979 1903 2979 1906 2979 1905 2980 1906 2980 1907 2980 1885 2981 1884 2981 1906 2981 1906 2982 1884 2982 1908 2982 1906 2983 1908 2983 1907 2983 1883 2984 1885 2984 1909 2984 1909 2985 1885 2985 1910 2985 1909 2986 1910 2986 1911 2986 1911 2987 1910 2987 1912 2987 1912 2988 1910 2988 1913 2988 1912 2989 1913 2989 1914 2989 1489 2990 1494 2990 1915 2990 1915 2991 1494 2991 1495 2991 1915 2992 1495 2992 1498 2992 1914 2993 1913 2993 1916 2993 1916 2994 1913 2994 1915 2994 1916 2995 1915 2995 1917 2995 1917 2996 1915 2996 1498 2996 1917 2997 1498 2997 1497 2997 1486 2998 1488 2998 1918 2998 1488 2999 1493 2999 1918 2999 1918 3000 1493 3000 1492 3000 1918 3001 1492 3001 1490 3001 1476 3002 1475 3002 1919 3002 1919 3003 1475 3003 1483 3003 1919 3004 1483 3004 1485 3004 1920 3005 1450 3005 1482 3005 1480 3006 1882 3006 1481 3006 1451 3007 1450 3007 1616 3007 1616 3008 1450 3008 1920 3008 1616 3009 1920 3009 1617 3009 1617 3010 1920 3010 1921 3010 1617 3011 1921 3011 1618 3011 1618 3012 1921 3012 1619 3012 1619 3013 1921 3013 1922 3013 1619 3014 1922 3014 1620 3014 1620 3015 1922 3015 1621 3015 1621 3016 1922 3016 1923 3016 1621 3017 1923 3017 1622 3017 1622 3018 1923 3018 1924 3018 1622 3019 1924 3019 1623 3019 1623 3020 1924 3020 1624 3020 1624 3021 1924 3021 1925 3021 1624 3022 1925 3022 1625 3022 1625 3023 1925 3023 1626 3023 1626 3024 1925 3024 1926 3024 1626 3025 1926 3025 1627 3025 1627 3026 1926 3026 1927 3026 1627 3027 1927 3027 1628 3027 1628 3028 1927 3028 1629 3028 1629 3029 1927 3029 1928 3029 1629 3030 1928 3030 1630 3030 1630 3031 1928 3031 1631 3031 1631 3032 1928 3032 1887 3032 1631 3033 1887 3033 1607 3033 1607 3034 1887 3034 1529 3034 1607 3035 1529 3035 1528 3035 1569 3036 1532 3036 1888 3036 1888 3037 1532 3037 1887 3037 1888 3038 1887 3038 1929 3038 1929 3039 1887 3039 1928 3039 1929 3040 1928 3040 1930 3040 1930 3041 1928 3041 1927 3041 1930 3042 1927 3042 1931 3042 1931 3043 1927 3043 1926 3043 1931 3044 1926 3044 1932 3044 1932 3045 1926 3045 1925 3045 1932 3046 1925 3046 1933 3046 1933 3047 1925 3047 1924 3047 1933 3048 1924 3048 1934 3048 1934 3049 1924 3049 1923 3049 1934 3050 1923 3050 1935 3050 1935 3051 1923 3051 1922 3051 1935 3052 1922 3052 1936 3052 1936 3053 1922 3053 1921 3053 1936 3054 1921 3054 1882 3054 1882 3055 1921 3055 1920 3055 1882 3056 1920 3056 1481 3056 1481 3057 1920 3057 1482 3057 1572 3058 1571 3058 1886 3058 1886 3059 1571 3059 1888 3059 1886 3060 1888 3060 1937 3060 1937 3061 1888 3061 1929 3061 1937 3062 1929 3062 1938 3062 1938 3063 1929 3063 1930 3063 1938 3064 1930 3064 1939 3064 1939 3065 1930 3065 1931 3065 1939 3066 1931 3066 1940 3066 1940 3067 1931 3067 1932 3067 1940 3068 1932 3068 1941 3068 1941 3069 1932 3069 1933 3069 1941 3070 1933 3070 1942 3070 1942 3071 1933 3071 1934 3071 1942 3072 1934 3072 1943 3072 1943 3073 1934 3073 1935 3073 1943 3074 1935 3074 1944 3074 1944 3075 1935 3075 1936 3075 1944 3076 1936 3076 1919 3076 1919 3077 1936 3077 1882 3077 1919 3078 1882 3078 1476 3078 1476 3079 1882 3079 1479 3079 1559 3080 1566 3080 1889 3080 1889 3081 1566 3081 1886 3081 1889 3082 1886 3082 1945 3082 1945 3083 1886 3083 1937 3083 1945 3084 1937 3084 1946 3084 1946 3085 1937 3085 1938 3085 1946 3086 1938 3086 1947 3086 1947 3087 1938 3087 1939 3087 1947 3088 1939 3088 1948 3088 1948 3089 1939 3089 1940 3089 1948 3090 1940 3090 1949 3090 1949 3091 1940 3091 1941 3091 1949 3092 1941 3092 1950 3092 1950 3093 1941 3093 1942 3093 1950 3094 1942 3094 1951 3094 1951 3095 1942 3095 1943 3095 1951 3096 1943 3096 1952 3096 1952 3097 1943 3097 1944 3097 1952 3098 1944 3098 1918 3098 1918 3099 1944 3099 1919 3099 1918 3100 1919 3100 1486 3100 1486 3101 1919 3101 1485 3101 1518 3102 1565 3102 1891 3102 1891 3103 1565 3103 1889 3103 1891 3104 1889 3104 1892 3104 1892 3105 1889 3105 1945 3105 1892 3106 1945 3106 1898 3106 1898 3107 1945 3107 1946 3107 1898 3108 1946 3108 1895 3108 1895 3109 1946 3109 1947 3109 1895 3110 1947 3110 1903 3110 1903 3111 1947 3111 1948 3111 1903 3112 1948 3112 1906 3112 1906 3113 1948 3113 1949 3113 1906 3114 1949 3114 1885 3114 1885 3115 1949 3115 1950 3115 1885 3116 1950 3116 1910 3116 1910 3117 1950 3117 1951 3117 1910 3118 1951 3118 1913 3118 1913 3119 1951 3119 1952 3119 1913 3120 1952 3120 1915 3120 1915 3121 1952 3121 1918 3121 1915 3122 1918 3122 1489 3122 1489 3123 1918 3123 1490 3123 1953 3124 1954 3124 1955 3124 1615 3125 1642 3125 1956 3125 1516 3126 1515 3126 1957 3126 1514 3127 1513 3127 1958 3127 1512 3128 1511 3128 1959 3128 1517 3129 1516 3129 1652 3129 1652 3130 1516 3130 1957 3130 1652 3131 1957 3131 1653 3131 1653 3132 1957 3132 1960 3132 1653 3133 1960 3133 1644 3133 1636 3134 1635 3134 1961 3134 1961 3135 1635 3135 1634 3135 1961 3136 1634 3136 1962 3136 1962 3137 1634 3137 1633 3137 1962 3138 1633 3138 1963 3138 1963 3139 1633 3139 1632 3139 1963 3140 1632 3140 1960 3140 1960 3141 1632 3141 1643 3141 1960 3142 1643 3142 1644 3142 1636 3143 1961 3143 1637 3143 1637 3144 1961 3144 1964 3144 1637 3145 1964 3145 1638 3145 1638 3146 1964 3146 1965 3146 1638 3147 1965 3147 1639 3147 1639 3148 1965 3148 1966 3148 1639 3149 1966 3149 1640 3149 1956 3150 1642 3150 1966 3150 1966 3151 1642 3151 1641 3151 1966 3152 1641 3152 1640 3152 1955 3153 1470 3153 1614 3153 1614 3154 1470 3154 1469 3154 1614 3155 1469 3155 1468 3155 1465 3156 1464 3156 1955 3156 1465 3157 1955 3157 1460 3157 1460 3158 1955 3158 1954 3158 1460 3159 1954 3159 1461 3159 1464 3160 1454 3160 1955 3160 1955 3161 1454 3161 1453 3161 1955 3162 1453 3162 1470 3162 1457 3163 1463 3163 1954 3163 1954 3164 1463 3164 1462 3164 1954 3165 1462 3165 1461 3165 1967 3166 1968 3166 1969 3166 1969 3167 1968 3167 1970 3167 1969 3168 1970 3168 1971 3168 1971 3169 1970 3169 1972 3169 1972 3170 1970 3170 1973 3170 1972 3171 1973 3171 1974 3171 1974 3172 1973 3172 1975 3172 1974 3173 1975 3173 1976 3173 1976 3174 1975 3174 1977 3174 1976 3175 1977 3175 1978 3175 1513 3176 1512 3176 1958 3176 1958 3177 1512 3177 1959 3177 1958 3178 1959 3178 1977 3178 1977 3179 1959 3179 1979 3179 1977 3180 1979 3180 1978 3180 1515 3181 1514 3181 1957 3181 1957 3182 1514 3182 1958 3182 1957 3183 1958 3183 1960 3183 1960 3184 1958 3184 1977 3184 1960 3185 1977 3185 1963 3185 1963 3186 1977 3186 1975 3186 1963 3187 1975 3187 1962 3187 1962 3188 1975 3188 1973 3188 1962 3189 1973 3189 1961 3189 1961 3190 1973 3190 1970 3190 1961 3191 1970 3191 1964 3191 1964 3192 1970 3192 1968 3192 1964 3193 1968 3193 1965 3193 1965 3194 1968 3194 1980 3194 1965 3195 1980 3195 1966 3195 1966 3196 1980 3196 1981 3196 1966 3197 1981 3197 1956 3197 1967 3198 1982 3198 1968 3198 1968 3199 1982 3199 1983 3199 1968 3200 1983 3200 1980 3200 1980 3201 1983 3201 1984 3201 1980 3202 1984 3202 1981 3202 1981 3203 1984 3203 1985 3203 1985 3204 1986 3204 1981 3204 1981 3205 1986 3205 1953 3205 1981 3206 1953 3206 1956 3206 1956 3207 1953 3207 1955 3207 1956 3208 1955 3208 1615 3208 1615 3209 1955 3209 1614 3209 1458 3210 1457 3210 1987 3210 1987 3211 1457 3211 1954 3211 1987 3212 1954 3212 1988 3212 1988 3213 1954 3213 1953 3213 1988 3214 1953 3214 1989 3214 1989 3215 1953 3215 1986 3215 1990 3216 1991 3216 1992 3216 1993 3217 1994 3217 1995 3217 1599 3218 1600 3218 1992 3218 1604 3219 1606 3219 1996 3219 1605 3220 1612 3220 1995 3220 1545 3221 1550 3221 1997 3221 1998 3222 1999 3222 1875 3222 1546 3223 2000 3223 1547 3223 1547 3224 2000 3224 1997 3224 1547 3225 1997 3225 1549 3225 1549 3226 1997 3226 1550 3226 1537 3227 1539 3227 2001 3227 1539 3228 1541 3228 2001 3228 2001 3229 1541 3229 1542 3229 2001 3230 1542 3230 1997 3230 1997 3231 1542 3231 1544 3231 1997 3232 1544 3232 1545 3232 1538 3233 1537 3233 1613 3233 1613 3234 1537 3234 2001 3234 1613 3235 2001 3235 1608 3235 1608 3236 2001 3236 1609 3236 2002 3237 1611 3237 1610 3237 1605 3238 1995 3238 1606 3238 1601 3239 1602 3239 2003 3239 2003 3240 1602 3240 1603 3240 2004 3241 1598 3241 1599 3241 1586 3242 1597 3242 2005 3242 2005 3243 1597 3243 1598 3243 1585 3244 1586 3244 1868 3244 1868 3245 1586 3245 2005 3245 1868 3246 2005 3246 1871 3246 1871 3247 2005 3247 1998 3247 1871 3248 1998 3248 1873 3248 1873 3249 1998 3249 1875 3249 2006 3250 2002 3250 2007 3250 2007 3251 2002 3251 1610 3251 2007 3252 1610 3252 1609 3252 1606 3253 1995 3253 1996 3253 1996 3254 1995 3254 1994 3254 1996 3255 1994 3255 2008 3255 2009 3256 2003 3256 2010 3256 2010 3257 2003 3257 1603 3257 2010 3258 1603 3258 1604 3258 1599 3259 1992 3259 2004 3259 2004 3260 1992 3260 1991 3260 2004 3261 1991 3261 2011 3261 1609 3262 2001 3262 2007 3262 2007 3263 2001 3263 1997 3263 2007 3264 1997 3264 2006 3264 2006 3265 1997 3265 2000 3265 2006 3266 2000 3266 2012 3266 2012 3267 2013 3267 2006 3267 2006 3268 2013 3268 1993 3268 2006 3269 1993 3269 2002 3269 2002 3270 1993 3270 1995 3270 2002 3271 1995 3271 1611 3271 1611 3272 1995 3272 1612 3272 2013 3273 2014 3273 1993 3273 1993 3274 2014 3274 2015 3274 1993 3275 2015 3275 1994 3275 1994 3276 2015 3276 2016 3276 1994 3277 2016 3277 2008 3277 2008 3278 2016 3278 2017 3278 2008 3279 2017 3279 2018 3279 1604 3280 1996 3280 2010 3280 2010 3281 1996 3281 2008 3281 2010 3282 2008 3282 2009 3282 2009 3283 2008 3283 2018 3283 2009 3284 2018 3284 2019 3284 2019 3285 2020 3285 2009 3285 2009 3286 2020 3286 1990 3286 2009 3287 1990 3287 2003 3287 2003 3288 1990 3288 1992 3288 2003 3289 1992 3289 1601 3289 1601 3290 1992 3290 1600 3290 2020 3291 2021 3291 1990 3291 1990 3292 2021 3292 2022 3292 1990 3293 2022 3293 1991 3293 1991 3294 2022 3294 2023 3294 1991 3295 2023 3295 2011 3295 2011 3296 2023 3296 2024 3296 2011 3297 2024 3297 2025 3297 1598 3298 2004 3298 2005 3298 2005 3299 2004 3299 2011 3299 2005 3300 2011 3300 1998 3300 1998 3301 2011 3301 2025 3301 1998 3302 2025 3302 1999 3302 2026 3303 2027 3303 2028 3303 2029 3304 2030 3304 2031 3304 2032 3305 2033 3305 2034 3305 2035 3306 2036 3306 2037 3306 2038 3307 2039 3307 2040 3307 2041 3308 2042 3308 2043 3308 2044 3309 2045 3309 2046 3309 2047 3310 2048 3310 2049 3310 1089 3311 1091 3311 1849 3311 1089 3312 1849 3312 1080 3312 1080 3313 1849 3313 2050 3313 1080 3314 2050 3314 1081 3314 1068 3315 1079 3315 2051 3315 2051 3316 1079 3316 1078 3316 1078 3317 1105 3317 2051 3317 2051 3318 1105 3318 1084 3318 2051 3319 1084 3319 2050 3319 2050 3320 1084 3320 1083 3320 2050 3321 1083 3321 1081 3321 1068 3322 2051 3322 1073 3322 1073 3323 2051 3323 2052 3323 1073 3324 2052 3324 1074 3324 1074 3325 2052 3325 2053 3325 1074 3326 2053 3326 1076 3326 2054 3327 1756 3327 1772 3327 1765 3328 2055 3328 1764 3328 1764 3329 2055 3329 2054 3329 1764 3330 2054 3330 1763 3330 1763 3331 2054 3331 1772 3331 1756 3332 2054 3332 1758 3332 1758 3333 2054 3333 2056 3333 1758 3334 2056 3334 1760 3334 1760 3335 2056 3335 1761 3335 1761 3336 2056 3336 1831 3336 1761 3337 1831 3337 1762 3337 2057 3338 2058 3338 2059 3338 2058 3339 2057 3339 2048 3339 2047 3340 2049 3340 2060 3340 2061 3341 2062 3341 2063 3341 2063 3342 2062 3342 2064 3342 2065 3343 2066 3343 2061 3343 2066 3344 2065 3344 2067 3344 2068 3345 2069 3345 2070 3345 2070 3346 2069 3346 2071 3346 2072 3347 2073 3347 2068 3347 2073 3348 2072 3348 2074 3348 2075 3349 2076 3349 2077 3349 2078 3350 2079 3350 2080 3350 2080 3351 2079 3351 2081 3351 2045 3352 2082 3352 2028 3352 2083 3353 2084 3353 2085 3353 2085 3354 2084 3354 2041 3354 2086 3355 2087 3355 2083 3355 2088 3356 2089 3356 2090 3356 2090 3357 2089 3357 2038 3357 2091 3358 2092 3358 2088 3358 2092 3359 2091 3359 2036 3359 2093 3360 2094 3360 2095 3360 2095 3361 2094 3361 2035 3361 2096 3362 2097 3362 2098 3362 2098 3363 2097 3363 2093 3363 2099 3364 2100 3364 2096 3364 2033 3365 2101 3365 2102 3365 2102 3366 2101 3366 2103 3366 2102 3367 2103 3367 2104 3367 2105 3368 2106 3368 2032 3368 2107 3369 2108 3369 2109 3369 2108 3370 2107 3370 2030 3370 1765 3371 1767 3371 2055 3371 2055 3372 1767 3372 2110 3372 2055 3373 2110 3373 2029 3373 2111 3374 2080 3374 2075 3374 2075 3375 2080 3375 2081 3375 2075 3376 2081 3376 2076 3376 2048 3377 2057 3377 2049 3377 2049 3378 2057 3378 2112 3378 2049 3379 2112 3379 2113 3379 2113 3380 2112 3380 2114 3380 2113 3381 2114 3381 2115 3381 2061 3382 2063 3382 2065 3382 2065 3383 2063 3383 2116 3383 2065 3384 2116 3384 2117 3384 2117 3385 2116 3385 2118 3385 2117 3386 2118 3386 2119 3386 2068 3387 2070 3387 2072 3387 2072 3388 2070 3388 2120 3388 2072 3389 2120 3389 2121 3389 2121 3390 2120 3390 2122 3390 2121 3391 2122 3391 2123 3391 2124 3392 2111 3392 2125 3392 2125 3393 2111 3393 2075 3393 2125 3394 2075 3394 2126 3394 2126 3395 2075 3395 2077 3395 2126 3396 2077 3396 2074 3396 2127 3397 2027 3397 2128 3397 2128 3398 2027 3398 2026 3398 2128 3399 2026 3399 2129 3399 2041 3400 2043 3400 2085 3400 2085 3401 2043 3401 2130 3401 2085 3402 2130 3402 2131 3402 2131 3403 2130 3403 2132 3403 2131 3404 2132 3404 2133 3404 2038 3405 2040 3405 2090 3405 2090 3406 2040 3406 2134 3406 2090 3407 2134 3407 2135 3407 2135 3408 2134 3408 2136 3408 2135 3409 2136 3409 2137 3409 2035 3410 2037 3410 2095 3410 2095 3411 2037 3411 2138 3411 2095 3412 2138 3412 2139 3412 2139 3413 2138 3413 2140 3413 2139 3414 2140 3414 2141 3414 2093 3415 2095 3415 2098 3415 2098 3416 2095 3416 2139 3416 2098 3417 2139 3417 2142 3417 2142 3418 2139 3418 2141 3418 2142 3419 2141 3419 2143 3419 2033 3420 2102 3420 2034 3420 2034 3421 2102 3421 2144 3421 2034 3422 2144 3422 2145 3422 2145 3423 2144 3423 2146 3423 2145 3424 2146 3424 2147 3424 2030 3425 2107 3425 2031 3425 2031 3426 2107 3426 2148 3426 2031 3427 2148 3427 2149 3427 2149 3428 2148 3428 2150 3428 2149 3429 2150 3429 2151 3429 1849 3430 2114 3430 2050 3430 2050 3431 2114 3431 2112 3431 2050 3432 2112 3432 2051 3432 2051 3433 2112 3433 2057 3433 2051 3434 2057 3434 2052 3434 2052 3435 2057 3435 2059 3435 2052 3436 2059 3436 2053 3436 1849 3437 1848 3437 2114 3437 2114 3438 1848 3438 1847 3438 2114 3439 1847 3439 2115 3439 2115 3440 1847 3440 1846 3440 2115 3441 1846 3441 1852 3441 2060 3442 2049 3442 2152 3442 2152 3443 2049 3443 2113 3443 2152 3444 2113 3444 2153 3444 2153 3445 2113 3445 2115 3445 2153 3446 2115 3446 2154 3446 2154 3447 2115 3447 1852 3447 2154 3448 1852 3448 1851 3448 1851 3449 2118 3449 2154 3449 2154 3450 2118 3450 2116 3450 2154 3451 2116 3451 2153 3451 2153 3452 2116 3452 2063 3452 2153 3453 2063 3453 2152 3453 2152 3454 2063 3454 2064 3454 2152 3455 2064 3455 2060 3455 1851 3456 1850 3456 2118 3456 2118 3457 1850 3457 1792 3457 2118 3458 1792 3458 2119 3458 2119 3459 1792 3459 1793 3459 2119 3460 1793 3460 1797 3460 2067 3461 2065 3461 2155 3461 2155 3462 2065 3462 2117 3462 2155 3463 2117 3463 2156 3463 2156 3464 2117 3464 2119 3464 2156 3465 2119 3465 2157 3465 2157 3466 2119 3466 1797 3466 2157 3467 1797 3467 1796 3467 1796 3468 2122 3468 2157 3468 2157 3469 2122 3469 2120 3469 2157 3470 2120 3470 2156 3470 2156 3471 2120 3471 2070 3471 2156 3472 2070 3472 2155 3472 2155 3473 2070 3473 2071 3473 2155 3474 2071 3474 2067 3474 1796 3475 1795 3475 2122 3475 2122 3476 1795 3476 1794 3476 2122 3477 1794 3477 2123 3477 2123 3478 1794 3478 1798 3478 2123 3479 1798 3479 1799 3479 2074 3480 2072 3480 2126 3480 2126 3481 2072 3481 2121 3481 2126 3482 2121 3482 2125 3482 2125 3483 2121 3483 2123 3483 2125 3484 2123 3484 2124 3484 2124 3485 2123 3485 1799 3485 2124 3486 1799 3486 1800 3486 1800 3487 1801 3487 2124 3487 2124 3488 1801 3488 2129 3488 2124 3489 2129 3489 2111 3489 2111 3490 2129 3490 2026 3490 2111 3491 2026 3491 2080 3491 2080 3492 2026 3492 2028 3492 2080 3493 2028 3493 2078 3493 2078 3494 2028 3494 2082 3494 1801 3495 1802 3495 2129 3495 2129 3496 1802 3496 1791 3496 2129 3497 1791 3497 2128 3497 2128 3498 1791 3498 1790 3498 2128 3499 1790 3499 2127 3499 2127 3500 1790 3500 1803 3500 2127 3501 1803 3501 1804 3501 2045 3502 2028 3502 2046 3502 2046 3503 2028 3503 2027 3503 2046 3504 2027 3504 2158 3504 2158 3505 2027 3505 2127 3505 2158 3506 2127 3506 2159 3506 2159 3507 2127 3507 1804 3507 2159 3508 1804 3508 1808 3508 1808 3509 2132 3509 2159 3509 2159 3510 2132 3510 2130 3510 2159 3511 2130 3511 2158 3511 2158 3512 2130 3512 2043 3512 2158 3513 2043 3513 2046 3513 2046 3514 2043 3514 2042 3514 2046 3515 2042 3515 2044 3515 1808 3516 1807 3516 2132 3516 2132 3517 1807 3517 1806 3517 2132 3518 1806 3518 2133 3518 2133 3519 1806 3519 1805 3519 2133 3520 1805 3520 1812 3520 2083 3521 2085 3521 2086 3521 2086 3522 2085 3522 2131 3522 2086 3523 2131 3523 2160 3523 2160 3524 2131 3524 2133 3524 2160 3525 2133 3525 2161 3525 2161 3526 2133 3526 1812 3526 2161 3527 1812 3527 1811 3527 1811 3528 2136 3528 2161 3528 2161 3529 2136 3529 2134 3529 2161 3530 2134 3530 2160 3530 2160 3531 2134 3531 2040 3531 2160 3532 2040 3532 2086 3532 2086 3533 2040 3533 2039 3533 2086 3534 2039 3534 2087 3534 1811 3535 1810 3535 2136 3535 2136 3536 1810 3536 1809 3536 2136 3537 1809 3537 2137 3537 2137 3538 1809 3538 1813 3538 2137 3539 1813 3539 1814 3539 2088 3540 2090 3540 2091 3540 2091 3541 2090 3541 2135 3541 2091 3542 2135 3542 2162 3542 2162 3543 2135 3543 2137 3543 2162 3544 2137 3544 2163 3544 2163 3545 2137 3545 1814 3545 2163 3546 1814 3546 1815 3546 2036 3547 2091 3547 2037 3547 2037 3548 2091 3548 2162 3548 2037 3549 2162 3549 2138 3549 2138 3550 2162 3550 2163 3550 2138 3551 2163 3551 2140 3551 2140 3552 2163 3552 1815 3552 2140 3553 1815 3553 1816 3553 1816 3554 1821 3554 2140 3554 2140 3555 1821 3555 1820 3555 2140 3556 1820 3556 2141 3556 2141 3557 1820 3557 1819 3557 2141 3558 1819 3558 2143 3558 2143 3559 1819 3559 1818 3559 2143 3560 1818 3560 1817 3560 2096 3561 2098 3561 2099 3561 2099 3562 2098 3562 2142 3562 2099 3563 2142 3563 2164 3563 2164 3564 2142 3564 2143 3564 2164 3565 2143 3565 2165 3565 2165 3566 2143 3566 1817 3566 2165 3567 1817 3567 1826 3567 1826 3568 2146 3568 2165 3568 2165 3569 2146 3569 2144 3569 2165 3570 2144 3570 2164 3570 2164 3571 2144 3571 2102 3571 2164 3572 2102 3572 2099 3572 2099 3573 2102 3573 2104 3573 2099 3574 2104 3574 2100 3574 1826 3575 1825 3575 2146 3575 2146 3576 1825 3576 1824 3576 2146 3577 1824 3577 2147 3577 2147 3578 1824 3578 1823 3578 2147 3579 1823 3579 1822 3579 2032 3580 2034 3580 2105 3580 2105 3581 2034 3581 2145 3581 2105 3582 2145 3582 2166 3582 2166 3583 2145 3583 2147 3583 2166 3584 2147 3584 2167 3584 2167 3585 2147 3585 1822 3585 2167 3586 1822 3586 1828 3586 1828 3587 2150 3587 2167 3587 2167 3588 2150 3588 2148 3588 2167 3589 2148 3589 2166 3589 2166 3590 2148 3590 2107 3590 2166 3591 2107 3591 2105 3591 2105 3592 2107 3592 2109 3592 2105 3593 2109 3593 2106 3593 1828 3594 1827 3594 2150 3594 2150 3595 1827 3595 1830 3595 2150 3596 1830 3596 2151 3596 2151 3597 1830 3597 1829 3597 2151 3598 1829 3598 1832 3598 2029 3599 2031 3599 2055 3599 2055 3600 2031 3600 2149 3600 2055 3601 2149 3601 2054 3601 2054 3602 2149 3602 2151 3602 2054 3603 2151 3603 2056 3603 2056 3604 2151 3604 1832 3604 2056 3605 1832 3605 1831 3605 2168 3606 2169 3606 2170 3606 2171 3607 2172 3607 2173 3607 2174 3608 2175 3608 2176 3608 2177 3609 2178 3609 2179 3609 2180 3610 2181 3610 2169 3610 2169 3611 2181 3611 2182 3611 2169 3612 2182 3612 2170 3612 2183 3613 2184 3613 2185 3613 2185 3614 2184 3614 2177 3614 2185 3615 2177 3615 2186 3615 2186 3616 2177 3616 2179 3616 2187 3617 2188 3617 2189 3617 2189 3618 2188 3618 2190 3618 2189 3619 2190 3619 2178 3619 2178 3620 2190 3620 2191 3620 2178 3621 2191 3621 2179 3621 2176 3622 2192 3622 2174 3622 2174 3623 2192 3623 2193 3623 2174 3624 2193 3624 2187 3624 2187 3625 2193 3625 2194 3625 2187 3626 2194 3626 2188 3626 2195 3627 2196 3627 2197 3627 2197 3628 2196 3628 2198 3628 2197 3629 2198 3629 2175 3629 2175 3630 2198 3630 2199 3630 2175 3631 2199 3631 2176 3631 2173 3632 2200 3632 2171 3632 2171 3633 2200 3633 2201 3633 2171 3634 2201 3634 2195 3634 2195 3635 2201 3635 2202 3635 2195 3636 2202 3636 2196 3636 2170 3637 2203 3637 2168 3637 2168 3638 2203 3638 2204 3638 2168 3639 2204 3639 2205 3639 2205 3640 2204 3640 2206 3640 2205 3641 2206 3641 2172 3641 2172 3642 2206 3642 2207 3642 2172 3643 2207 3643 2173 3643 1659 3644 2180 3644 1666 3644 1666 3645 2180 3645 2169 3645 1666 3646 2169 3646 1667 3646 1667 3647 2169 3647 2168 3647 1667 3648 2168 3648 1668 3648 1668 3649 2168 3649 2205 3649 1668 3650 2205 3650 1669 3650 1669 3651 2205 3651 2172 3651 1669 3652 2172 3652 1670 3652 1670 3653 2172 3653 2171 3653 1670 3654 2171 3654 1671 3654 1671 3655 2171 3655 2195 3655 1671 3656 2195 3656 1672 3656 1672 3657 2195 3657 2197 3657 1672 3658 2197 3658 1673 3658 1673 3659 2197 3659 2175 3659 1673 3660 2175 3660 1674 3660 1674 3661 2175 3661 2174 3661 1674 3662 2174 3662 1675 3662 1675 3663 2174 3663 2187 3663 1675 3664 2187 3664 1676 3664 1676 3665 2187 3665 2189 3665 1676 3666 2189 3666 1677 3666 1677 3667 2189 3667 2178 3667 1677 3668 2178 3668 1657 3668 1657 3669 2178 3669 2177 3669 1657 3670 2177 3670 1658 3670 1658 3671 2177 3671 2184 3671 2208 3672 2209 3672 2210 3672 2211 3673 2212 3673 2213 3673 2214 3674 2215 3674 2216 3674 2184 3675 2183 3675 2217 3675 2181 3676 2218 3676 2219 3676 2219 3677 2218 3677 2220 3677 2219 3678 2220 3678 2221 3678 2221 3679 2220 3679 2222 3679 2216 3680 2223 3680 2214 3680 2214 3681 2223 3681 2224 3681 2214 3682 2224 3682 2222 3682 2222 3683 2224 3683 2225 3683 2222 3684 2225 3684 2221 3684 2226 3685 2227 3685 2228 3685 2228 3686 2227 3686 2229 3686 2228 3687 2229 3687 2215 3687 2215 3688 2229 3688 2230 3688 2215 3689 2230 3689 2216 3689 2213 3690 2231 3690 2211 3690 2211 3691 2231 3691 2232 3691 2211 3692 2232 3692 2226 3692 2226 3693 2232 3693 2233 3693 2226 3694 2233 3694 2227 3694 2234 3695 2235 3695 2236 3695 2236 3696 2235 3696 2237 3696 2236 3697 2237 3697 2212 3697 2212 3698 2237 3698 2238 3698 2212 3699 2238 3699 2213 3699 2210 3700 2239 3700 2208 3700 2208 3701 2239 3701 2240 3701 2208 3702 2240 3702 2234 3702 2234 3703 2240 3703 2241 3703 2234 3704 2241 3704 2235 3704 2184 3705 2217 3705 2242 3705 2242 3706 2217 3706 2243 3706 2242 3707 2243 3707 2209 3707 2209 3708 2243 3708 2244 3708 2209 3709 2244 3709 2210 3709 1658 3710 2184 3710 1660 3710 1660 3711 2184 3711 2242 3711 1660 3712 2242 3712 1662 3712 1662 3713 2242 3713 2209 3713 1662 3714 2209 3714 1663 3714 1663 3715 2209 3715 2208 3715 1663 3716 2208 3716 1683 3716 1683 3717 2208 3717 2234 3717 1683 3718 2234 3718 1679 3718 1679 3719 2234 3719 2236 3719 1679 3720 2236 3720 1681 3720 1681 3721 2236 3721 2212 3721 1681 3722 2212 3722 1682 3722 1682 3723 2212 3723 2211 3723 1682 3724 2211 3724 1680 3724 1680 3725 2211 3725 2226 3725 1680 3726 2226 3726 1678 3726 1678 3727 2226 3727 2228 3727 1678 3728 2228 3728 1684 3728 1684 3729 2228 3729 2215 3729 1684 3730 2215 3730 1665 3730 1665 3731 2215 3731 2214 3731 1665 3732 2214 3732 1664 3732 1664 3733 2214 3733 2222 3733 1664 3734 2222 3734 1661 3734 1661 3735 2222 3735 2220 3735 1661 3736 2220 3736 1659 3736 1659 3737 2220 3737 2218 3737 2245 3738 2246 3738 2247 3738 2248 3739 972 3739 2249 3739 2248 3740 2249 3740 2246 3740 2246 3741 2249 3741 2250 3741 2246 3742 2250 3742 2247 3742 2245 3743 2247 3743 2251 3743 2251 3744 2247 3744 2252 3744 2251 3745 2252 3745 2253 3745 2247 3746 2250 3746 2254 3746 2254 3747 2250 3747 2249 3747 2254 3748 2249 3748 2255 3748 971 3749 1032 3749 2256 3749 2255 3750 2249 3750 2256 3750 2256 3751 2249 3751 972 3751 2256 3752 972 3752 971 3752 2247 3753 2254 3753 2252 3753 2252 3754 2254 3754 2257 3754 2252 3755 2257 3755 2258 3755 1688 3756 1687 3756 1781 3756 2258 3757 2257 3757 2259 3757 2259 3758 2257 3758 2260 3758 2259 3759 2260 3759 2261 3759 2261 3760 2260 3760 2262 3760 1780 3761 2263 3761 1781 3761 1781 3762 2263 3762 2264 3762 1781 3763 2264 3763 2265 3763 2265 3764 2266 3764 1781 3764 1781 3765 2266 3765 2267 3765 1781 3766 2267 3766 2268 3766 2268 3767 2267 3767 2269 3767 2268 3768 2269 3768 2260 3768 2260 3769 2269 3769 2270 3769 2260 3770 2270 3770 2262 3770 1689 3771 2271 3771 1690 3771 1690 3772 2271 3772 1691 3772 1691 3773 2271 3773 1692 3773 1692 3774 2271 3774 2272 3774 1692 3775 2272 3775 2254 3775 2256 3776 1032 3776 1694 3776 2254 3777 2255 3777 1692 3777 1692 3778 2255 3778 2256 3778 1692 3779 2256 3779 1693 3779 1693 3780 2256 3780 1694 3780 1688 3781 1781 3781 1689 3781 1689 3782 1781 3782 2268 3782 1689 3783 2268 3783 2271 3783 2271 3784 2268 3784 2260 3784 2271 3785 2260 3785 2272 3785 2272 3786 2260 3786 2257 3786 2272 3787 2257 3787 2254 3787 1700 3788 1699 3788 2273 3788 2274 3789 1702 3789 1033 3789 2275 3790 2276 3790 1844 3790 1844 3791 2276 3791 2277 3791 2277 3792 2278 3792 1844 3792 1844 3793 2278 3793 2279 3793 1844 3794 2279 3794 1845 3794 2280 3795 2281 3795 2282 3795 2282 3796 2281 3796 2283 3796 2282 3797 2283 3797 2284 3797 2275 3798 2273 3798 2285 3798 2286 3799 2287 3799 2285 3799 2285 3800 2287 3800 2282 3800 2285 3801 2282 3801 2275 3801 2275 3802 2282 3802 2284 3802 2275 3803 2284 3803 2276 3803 2274 3804 1033 3804 2285 3804 2285 3805 1033 3805 2288 3805 2285 3806 2288 3806 2286 3806 2273 3807 1699 3807 2285 3807 2285 3808 1699 3808 1698 3808 2285 3809 1698 3809 2274 3809 2274 3810 1698 3810 1697 3810 2274 3811 1697 3811 1702 3811 1844 3812 1705 3812 1704 3812 1844 3813 1704 3813 2275 3813 2275 3814 1704 3814 1703 3814 2275 3815 1703 3815 2273 3815 2273 3816 1703 3816 1701 3816 2273 3817 1701 3817 1700 3817 2286 3818 2288 3818 2289 3818 1042 3819 2289 3819 1035 3819 1035 3820 2289 3820 2288 3820 1035 3821 2288 3821 1033 3821 2290 3822 2280 3822 2291 3822 2291 3823 2280 3823 2282 3823 2289 3824 2292 3824 2286 3824 2286 3825 2292 3825 2291 3825 2286 3826 2291 3826 2287 3826 2287 3827 2291 3827 2282 3827 2293 3828 2294 3828 1042 3828 1042 3829 2294 3829 2289 3829 2295 3830 2290 3830 2296 3830 2296 3831 2290 3831 2291 3831 2296 3832 2291 3832 2297 3832 2297 3833 2291 3833 2294 3833 2294 3834 2291 3834 2292 3834 2294 3835 2292 3835 2289 3835 1778 3836 1777 3836 2298 3836 2298 3837 1777 3837 2299 3837 1784 3838 1783 3838 2300 3838 2300 3839 2301 3839 1784 3839 1784 3840 2301 3840 2302 3840 1784 3841 2302 3841 1777 3841 2303 3842 1843 3842 1842 3842 1842 3843 1841 3843 2304 3843 2305 3844 2303 3844 2306 3844 2306 3845 2303 3845 1842 3845 2306 3846 1842 3846 2307 3846 2307 3847 1842 3847 2304 3847 2299 3848 1777 3848 2308 3848 2308 3849 1777 3849 2302 3849 2308 3850 2302 3850 2309 3850 2309 3851 2302 3851 2310 3851 2309 3852 2310 3852 2311 3852 2311 3853 2310 3853 2312 3853 2311 3854 2312 3854 2313 3854 2313 3855 2312 3855 2314 3855 2313 3856 2314 3856 2315 3856 2315 3857 2314 3857 2316 3857 2315 3858 2316 3858 2317 3858 2317 3859 2316 3859 2318 3859 2317 3860 2318 3860 2319 3860 2319 3861 2318 3861 2320 3861 2319 3862 2320 3862 2321 3862 2321 3863 2320 3863 2322 3863 2321 3864 2322 3864 2323 3864 2323 3865 2322 3865 2324 3865 2323 3866 2324 3866 2325 3866 2325 3867 2324 3867 2326 3867 2325 3868 2326 3868 2327 3868 2327 3869 2326 3869 2328 3869 2327 3870 2328 3870 2329 3870 2329 3871 2328 3871 2330 3871 2329 3872 2330 3872 2331 3872 2331 3873 2330 3873 2332 3873 2331 3874 2332 3874 2333 3874 2333 3875 2332 3875 2334 3875 2333 3876 2334 3876 2335 3876 2335 3877 2334 3877 2336 3877 2335 3878 2336 3878 2337 3878 2337 3879 2336 3879 2338 3879 2337 3880 2338 3880 2339 3880 2339 3881 2338 3881 2340 3881 2339 3882 2340 3882 2341 3882 2341 3883 2340 3883 2342 3883 2341 3884 2342 3884 2343 3884 2343 3885 2342 3885 2344 3885 2343 3886 2344 3886 2306 3886 2306 3887 2344 3887 2345 3887 2306 3888 2345 3888 2305 3888 2346 3889 1855 3889 2347 3889 2347 3890 1855 3890 1854 3890 1856 3891 2348 3891 1857 3891 1857 3892 2348 3892 1860 3892 1786 3893 1785 3893 1858 3893 1858 3894 1859 3894 1786 3894 1786 3895 1859 3895 1861 3895 1786 3896 1861 3896 2349 3896 2350 3897 1786 3897 2351 3897 2351 3898 1786 3898 2349 3898 2351 3899 2349 3899 2352 3899 2350 3900 2353 3900 1786 3900 1786 3901 2353 3901 2354 3901 1786 3902 2354 3902 1787 3902 2355 3903 2356 3903 2357 3903 2357 3904 2356 3904 2358 3904 1861 3905 1860 3905 2349 3905 2349 3906 1860 3906 2348 3906 2349 3907 2348 3907 2346 3907 2346 3908 2348 3908 1856 3908 2346 3909 1856 3909 1855 3909 2359 3910 2360 3910 2346 3910 2346 3911 2360 3911 2357 3911 2346 3912 2357 3912 2349 3912 2349 3913 2357 3913 2358 3913 2349 3914 2358 3914 2352 3914 1854 3915 1853 3915 2347 3915 2347 3916 1853 3916 1393 3916 2347 3917 1393 3917 2346 3917 2346 3918 1393 3918 2361 3918 2346 3919 2361 3919 2359 3919 2359 3920 2361 3920 2362 3920 1390 3921 2362 3921 1391 3921 1391 3922 2362 3922 2361 3922 1391 3923 2361 3923 1393 3923 2363 3924 2355 3924 2364 3924 2364 3925 2355 3925 2357 3925 2362 3926 2365 3926 2359 3926 2359 3927 2365 3927 2364 3927 2359 3928 2364 3928 2360 3928 2360 3929 2364 3929 2357 3929 2366 3930 2367 3930 2368 3930 1717 3931 1716 3931 2369 3931 2366 3932 2368 3932 2370 3932 2370 3933 2368 3933 2371 3933 2370 3934 2371 3934 2369 3934 2369 3935 2371 3935 1740 3935 2369 3936 1740 3936 1717 3936 2367 3937 2366 3937 2372 3937 2372 3938 2366 3938 2373 3938 2372 3939 2373 3939 2374 3939 1862 3940 1837 3940 1836 3940 1862 3941 1836 3941 1863 3941 1863 3942 1836 3942 2375 3942 1863 3943 2375 3943 1864 3943 2376 3944 1866 3944 2377 3944 2377 3945 1866 3945 1867 3945 2377 3946 1867 3946 1864 3946 1716 3947 1865 3947 2369 3947 2369 3948 1865 3948 1866 3948 2369 3949 1866 3949 2370 3949 2374 3950 2373 3950 2378 3950 2378 3951 2373 3951 2379 3951 2378 3952 2379 3952 2380 3952 2380 3953 2379 3953 2381 3953 1836 3954 1833 3954 2382 3954 2382 3955 2383 3955 1836 3955 1836 3956 2383 3956 2384 3956 1836 3957 2384 3957 2375 3957 2375 3958 2384 3958 2385 3958 2375 3959 2385 3959 2379 3959 2379 3960 2385 3960 2386 3960 2379 3961 2386 3961 2381 3961 1864 3962 2375 3962 2377 3962 2377 3963 2375 3963 2379 3963 2377 3964 2379 3964 2376 3964 2376 3965 2379 3965 2373 3965 2376 3966 2373 3966 1866 3966 1866 3967 2373 3967 2366 3967 1866 3968 2366 3968 2370 3968 2387 3969 2388 3969 1390 3969 1390 3970 2388 3970 2362 3970 2389 3971 2363 3971 2390 3971 2390 3972 2363 3972 2364 3972 2390 3973 2364 3973 2388 3973 2388 3974 2364 3974 2365 3974 2388 3975 2365 3975 2362 3975 2368 3976 2367 3976 2391 3976 2391 3977 2367 3977 2392 3977 2392 3978 2367 3978 2372 3978 2392 3979 2372 3979 2393 3979 2368 3980 2391 3980 2371 3980 2371 3981 2391 3981 2394 3981 2371 3982 2394 3982 1740 3982 2395 3983 2396 3983 2397 3983 2398 3984 2399 3984 2400 3984 2401 3985 1587 3985 1869 3985 1877 3986 1878 3986 2402 3986 2403 3987 2404 3987 2396 3987 2396 3988 2404 3988 2405 3988 2396 3989 2405 3989 2397 3989 2397 3990 2405 3990 2406 3990 2397 3991 2406 3991 2407 3991 2407 3992 2406 3992 2408 3992 2407 3993 2408 3993 2409 3993 2410 3994 2411 3994 2403 3994 2403 3995 2411 3995 2412 3995 2403 3996 2412 3996 2404 3996 2413 3997 2414 3997 2415 3997 2414 3998 2413 3998 2402 3998 2402 3999 2413 3999 1876 3999 2402 4000 1876 4000 1877 4000 1869 4001 1870 4001 2416 4001 1870 4002 1881 4002 2416 4002 2416 4003 1881 4003 1880 4003 2416 4004 1880 4004 2413 4004 2413 4005 1880 4005 1879 4005 2413 4006 1879 4006 1876 4006 1869 4007 2416 4007 2417 4007 2417 4008 2416 4008 2418 4008 2417 4009 2418 4009 2419 4009 2419 4010 2420 4010 2417 4010 2417 4011 2420 4011 2421 4011 2417 4012 2421 4012 1869 4012 1869 4013 2421 4013 2422 4013 1869 4014 2422 4014 2401 4014 2395 4015 2423 4015 2396 4015 2396 4016 2423 4016 2424 4016 2396 4017 2424 4017 2403 4017 2403 4018 2424 4018 2425 4018 2403 4019 2425 4019 2400 4019 2400 4020 2425 4020 2426 4020 2400 4021 2426 4021 2398 4021 2399 4022 2418 4022 2400 4022 2400 4023 2418 4023 2416 4023 2400 4024 2416 4024 2403 4024 2403 4025 2416 4025 2413 4025 2403 4026 2413 4026 2410 4026 2410 4027 2413 4027 2415 4027 2427 4028 2428 4028 1579 4028 1579 4029 2428 4029 1573 4029 2429 4030 1522 4030 1521 4030 2429 4031 1521 4031 2430 4031 2430 4032 1521 4032 1556 4032 2430 4033 1556 4033 2431 4033 2431 4034 1556 4034 1575 4034 2431 4035 1575 4035 2428 4035 2428 4036 1575 4036 1574 4036 2428 4037 1574 4037 1573 4037 2432 4038 2433 4038 1580 4038 2427 4039 1579 4039 2433 4039 2433 4040 1579 4040 1581 4040 2433 4041 1581 4041 1580 4041 1580 4042 1558 4042 2432 4042 2432 4043 1558 4043 1557 4043 2432 4044 1557 4044 2434 4044 1497 4045 2435 4045 1917 4045 1917 4046 2435 4046 2436 4046 1917 4047 2436 4047 1916 4047 1883 4048 1909 4048 2437 4048 1909 4049 1911 4049 2437 4049 2437 4050 1911 4050 1912 4050 2437 4051 1912 4051 2436 4051 2436 4052 1912 4052 1914 4052 2436 4053 1914 4053 1916 4053 1894 4054 2438 4054 1890 4054 1890 4055 2438 4055 2434 4055 1890 4056 2434 4056 1557 4056 2439 4057 1899 4057 1897 4057 1897 4058 1896 4058 2439 4058 2439 4059 1896 4059 1902 4059 2439 4060 1902 4060 2440 4060 2440 4061 1902 4061 1904 4061 2440 4062 1904 4062 1905 4062 1905 4063 1907 4063 2440 4063 2440 4064 1907 4064 1908 4064 2440 4065 1908 4065 2437 4065 2437 4066 1908 4066 1884 4066 2437 4067 1884 4067 1883 4067 1894 4068 1893 4068 2438 4068 2438 4069 1893 4069 1901 4069 2438 4070 1901 4070 2439 4070 2439 4071 1901 4071 1900 4071 2439 4072 1900 4072 1899 4072 2441 4073 2442 4073 1447 4073 2435 4074 1497 4074 1496 4074 1447 4075 2442 4075 1448 4075 1448 4076 2442 4076 2443 4076 1448 4077 2443 4077 1444 4077 2435 4078 1496 4078 2444 4078 2444 4079 1496 4079 1499 4079 2444 4080 1499 4080 2443 4080 2443 4081 1499 4081 1445 4081 2443 4082 1445 4082 1444 4082 1447 4083 1508 4083 2441 4083 2441 4084 1508 4084 1507 4084 2441 4085 1507 4085 2445 4085 2445 4086 1507 4086 1502 4086 2445 4087 1502 4087 2446 4087 2446 4088 1502 4088 1501 4088 2446 4089 1501 4089 2447 4089 2448 4090 2449 4090 1979 4090 1959 4091 1511 4091 2450 4091 2450 4092 2451 4092 1959 4092 1959 4093 2451 4093 2452 4093 1959 4094 2452 4094 1979 4094 1979 4095 2452 4095 2453 4095 1979 4096 2453 4096 2448 4096 2449 4097 2454 4097 2455 4097 2455 4098 2454 4098 2456 4098 2455 4099 2456 4099 2457 4099 2457 4100 2458 4100 2455 4100 2455 4101 2458 4101 2459 4101 2455 4102 2459 4102 2460 4102 2449 4103 2455 4103 1979 4103 1979 4104 2455 4104 2461 4104 1979 4105 2461 4105 1978 4105 1978 4106 2461 4106 2462 4106 1978 4107 2462 4107 1976 4107 1976 4108 2462 4108 1974 4108 1974 4109 2462 4109 2463 4109 1974 4110 2463 4110 1972 4110 1972 4111 2463 4111 2464 4111 1972 4112 2464 4112 1971 4112 1971 4113 2464 4113 2465 4113 1971 4114 2465 4114 1969 4114 1969 4115 2465 4115 2466 4115 1969 4116 2466 4116 1967 4116 1967 4117 2466 4117 2467 4117 1967 4118 2467 4118 1982 4118 1982 4119 2467 4119 1983 4119 1983 4120 2467 4120 2468 4120 1983 4121 2468 4121 1984 4121 1984 4122 2468 4122 2469 4122 1984 4123 2469 4123 1985 4123 1985 4124 2469 4124 2470 4124 1985 4125 2470 4125 1986 4125 1986 4126 2470 4126 2471 4126 1986 4127 2471 4127 1989 4127 1989 4128 2471 4128 2472 4128 1989 4129 2472 4129 1988 4129 1988 4130 2472 4130 2473 4130 1988 4131 2473 4131 2474 4131 2474 4132 1504 4132 1988 4132 1988 4133 1504 4133 1503 4133 1988 4134 1503 4134 1987 4134 1987 4135 1503 4135 1458 4135 1553 4136 2012 4136 1551 4136 1551 4137 2012 4137 2000 4137 1551 4138 2000 4138 1546 4138 2475 4139 2013 4139 2476 4139 2476 4140 2013 4140 2012 4140 2476 4141 2012 4141 2477 4141 2477 4142 2012 4142 1553 4142 2477 4143 1553 4143 2478 4143 2020 4144 2019 4144 2479 4144 2479 4145 2019 4145 2018 4145 2479 4146 2018 4146 2480 4146 2480 4147 2018 4147 2017 4147 2480 4148 2017 4148 2481 4148 2481 4149 2017 4149 2016 4149 2481 4150 2016 4150 2482 4150 2482 4151 2016 4151 2015 4151 2482 4152 2015 4152 2475 4152 2475 4153 2015 4153 2014 4153 2475 4154 2014 4154 2013 4154 2483 4155 2484 4155 2485 4155 2485 4156 2484 4156 2486 4156 2487 4157 2488 4157 2025 4157 2483 4158 2489 4158 2484 4158 2484 4159 2489 4159 2490 4159 2484 4160 2490 4160 2491 4160 2491 4161 2487 4161 2484 4161 2484 4162 2487 4162 2025 4162 2484 4163 2025 4163 2492 4163 2492 4164 2025 4164 2024 4164 2492 4165 2024 4165 2493 4165 2493 4166 2024 4166 2023 4166 2493 4167 2023 4167 2494 4167 2494 4168 2023 4168 2022 4168 2494 4169 2022 4169 2495 4169 2495 4170 2022 4170 2021 4170 2495 4171 2021 4171 2496 4171 2496 4172 2021 4172 2020 4172 2496 4173 2020 4173 2497 4173 2497 4174 2020 4174 2479 4174 2488 4175 2498 4175 2025 4175 2025 4176 2498 4176 2499 4176 2025 4177 2499 4177 1999 4177 1999 4178 2499 4178 2500 4178 1999 4179 2500 4179 1875 4179 2501 4180 2502 4180 2503 4180 2504 4181 2505 4181 2506 4181 2506 4182 2505 4182 2507 4182 2506 4183 2507 4183 2508 4183 2506 4184 2509 4184 2504 4184 2504 4185 2509 4185 2510 4185 2504 4186 2510 4186 2511 4186 2512 4187 2513 4187 2514 4187 2510 4188 2515 4188 2511 4188 2511 4189 2515 4189 2516 4189 2511 4190 2516 4190 2503 4190 2503 4191 2516 4191 2517 4191 2503 4192 2517 4192 2512 4192 2501 4193 2503 4193 2518 4193 2512 4194 2514 4194 2503 4194 2503 4195 2514 4195 2519 4195 2503 4196 2519 4196 2518 4196 2520 4197 2521 4197 2101 4197 2522 4198 1076 4198 2053 4198 2523 4199 2524 4199 2029 4199 1767 4200 2525 4200 2110 4200 2110 4201 2525 4201 2526 4201 2110 4202 2526 4202 2029 4202 2029 4203 2526 4203 2527 4203 2029 4204 2527 4204 2523 4204 2528 4205 2529 4205 2507 4205 2507 4206 2529 4206 2530 4206 2507 4207 2530 4207 2508 4207 2531 4208 2532 4208 2533 4208 2533 4209 2532 4209 2528 4209 2533 4210 2528 4210 2505 4210 2505 4211 2528 4211 2507 4211 2534 4212 2535 4212 2536 4212 2537 4213 2538 4213 2536 4213 2536 4214 2538 4214 2539 4214 2536 4215 2539 4215 2534 4215 2540 4216 2541 4216 2059 4216 2059 4217 2541 4217 2542 4217 2059 4218 2542 4218 2543 4218 2543 4219 2544 4219 2059 4219 2059 4220 2544 4220 2545 4220 2059 4221 2545 4221 2053 4221 2053 4222 2545 4222 2546 4222 2053 4223 2546 4223 2522 4223 2534 4224 2540 4224 2535 4224 2535 4225 2540 4225 2059 4225 2535 4226 2059 4226 2547 4226 2547 4227 2059 4227 2058 4227 2547 4228 2058 4228 2548 4228 2548 4229 2058 4229 2048 4229 2548 4230 2048 4230 2549 4230 2549 4231 2048 4231 2047 4231 2549 4232 2047 4232 2550 4232 2550 4233 2047 4233 2060 4233 2550 4234 2060 4234 2551 4234 2551 4235 2060 4235 2064 4235 2551 4236 2064 4236 2552 4236 2552 4237 2064 4237 2062 4237 2552 4238 2062 4238 2553 4238 2553 4239 2062 4239 2061 4239 2553 4240 2061 4240 2554 4240 2554 4241 2061 4241 2555 4241 2061 4242 2066 4242 2555 4242 2555 4243 2066 4243 2067 4243 2555 4244 2067 4244 2556 4244 2556 4245 2067 4245 2071 4245 2556 4246 2071 4246 2557 4246 2557 4247 2071 4247 2069 4247 2557 4248 2069 4248 2558 4248 2558 4249 2069 4249 2068 4249 2558 4250 2068 4250 2559 4250 2559 4251 2068 4251 2560 4251 2077 4252 2561 4252 2074 4252 2074 4253 2561 4253 2560 4253 2074 4254 2560 4254 2073 4254 2073 4255 2560 4255 2068 4255 2081 4256 2562 4256 2563 4256 2081 4257 2563 4257 2076 4257 2076 4258 2563 4258 2564 4258 2076 4259 2564 4259 2077 4259 2565 4260 2566 4260 2567 4260 2564 4261 2568 4261 2077 4261 2077 4262 2568 4262 2569 4262 2077 4263 2569 4263 2561 4263 2561 4264 2569 4264 2570 4264 2561 4265 2570 4265 2567 4265 2567 4266 2570 4266 2571 4266 2567 4267 2571 4267 2565 4267 2562 4268 2081 4268 2572 4268 2572 4269 2081 4269 2079 4269 2572 4270 2079 4270 2573 4270 2573 4271 2079 4271 2078 4271 2573 4272 2078 4272 2574 4272 2574 4273 2078 4273 2082 4273 2574 4274 2082 4274 2575 4274 2082 4275 2045 4275 2575 4275 2575 4276 2045 4276 2044 4276 2575 4277 2044 4277 2576 4277 2576 4278 2044 4278 2042 4278 2577 4279 2578 4279 2035 4279 2579 4280 2580 4280 2581 4280 2581 4281 2580 4281 2582 4281 2578 4282 2583 4282 2035 4282 2035 4283 2583 4283 2584 4283 2035 4284 2584 4284 2036 4284 2036 4285 2584 4285 2585 4285 2036 4286 2585 4286 2092 4286 2092 4287 2585 4287 2586 4287 2092 4288 2586 4288 2088 4288 2088 4289 2586 4289 2587 4289 2088 4290 2587 4290 2089 4290 2089 4291 2587 4291 2588 4291 2089 4292 2588 4292 2038 4292 2038 4293 2588 4293 2589 4293 2038 4294 2589 4294 2039 4294 2039 4295 2589 4295 2590 4295 2039 4296 2590 4296 2087 4296 2087 4297 2590 4297 2591 4297 2087 4298 2591 4298 2083 4298 2083 4299 2591 4299 2592 4299 2083 4300 2592 4300 2084 4300 2084 4301 2592 4301 2593 4301 2084 4302 2593 4302 2041 4302 2041 4303 2593 4303 2594 4303 2041 4304 2594 4304 2042 4304 2042 4305 2594 4305 2595 4305 2042 4306 2595 4306 2576 4306 2580 4307 2577 4307 2582 4307 2582 4308 2577 4308 2035 4308 2582 4309 2035 4309 2596 4309 2596 4310 2035 4310 2094 4310 2596 4311 2094 4311 2597 4311 2597 4312 2094 4312 2093 4312 2597 4313 2093 4313 2598 4313 2598 4314 2093 4314 2097 4314 2598 4315 2097 4315 2599 4315 2599 4316 2097 4316 2096 4316 2599 4317 2096 4317 2600 4317 2600 4318 2096 4318 2100 4318 2600 4319 2100 4319 2601 4319 2601 4320 2100 4320 2104 4320 2601 4321 2104 4321 2521 4321 2521 4322 2104 4322 2103 4322 2521 4323 2103 4323 2101 4323 2520 4324 2101 4324 2602 4324 2602 4325 2101 4325 2033 4325 2602 4326 2033 4326 2603 4326 2603 4327 2033 4327 2032 4327 2603 4328 2032 4328 2604 4328 2604 4329 2032 4329 2106 4329 2604 4330 2106 4330 2605 4330 2605 4331 2106 4331 2109 4331 2605 4332 2109 4332 2108 4332 2524 4333 2531 4333 2029 4333 2029 4334 2531 4334 2533 4334 2029 4335 2533 4335 2030 4335 2030 4336 2533 4336 2606 4336 2030 4337 2606 4337 2108 4337 2108 4338 2606 4338 2607 4338 2108 4339 2607 4339 2605 4339 2608 4340 2609 4340 2610 4340 2610 4341 2609 4341 2611 4341 2612 4342 2613 4342 2614 4342 2614 4343 2613 4343 2615 4343 2614 4344 2615 4344 2616 4344 2617 4345 2618 4345 2619 4345 2619 4346 2618 4346 2614 4346 2619 4347 2614 4347 2620 4347 2620 4348 2614 4348 2616 4348 2612 4349 2614 4349 2609 4349 2609 4350 2614 4350 2621 4350 2609 4351 2621 4351 2622 4351 2622 4352 2623 4352 2609 4352 2609 4353 2623 4353 2624 4353 2609 4354 2624 4354 2611 4354 2625 4355 2626 4355 2627 4355 2627 4356 2626 4356 2628 4356 2627 4357 2628 4357 2629 4357 2630 4358 2631 4358 2632 4358 2632 4359 2631 4359 2627 4359 2632 4360 2627 4360 2633 4360 2633 4361 2627 4361 2629 4361 2625 4362 2627 4362 2610 4362 2610 4363 2627 4363 2634 4363 2610 4364 2634 4364 2635 4364 2635 4365 2636 4365 2610 4365 2610 4366 2636 4366 2637 4366 2610 4367 2637 4367 2608 4367 2638 4368 2639 4368 2640 4368 2640 4369 2639 4369 2641 4369 2642 4370 2643 4370 2644 4370 2644 4371 2643 4371 2645 4371 2644 4372 2645 4372 2646 4372 2647 4373 2644 4373 2648 4373 2648 4374 2644 4374 2646 4374 2648 4375 2646 4375 2649 4375 2649 4376 2646 4376 2650 4376 2644 4377 2651 4377 2642 4377 2642 4378 2651 4378 2652 4378 2642 4379 2652 4379 2653 4379 2639 4380 2654 4380 2641 4380 2641 4381 2654 4381 2642 4381 2641 4382 2642 4382 2655 4382 2655 4383 2642 4383 2653 4383 2656 4384 2657 4384 2658 4384 2658 4385 2657 4385 2659 4385 2658 4386 2659 4386 2660 4386 2661 4387 2658 4387 2662 4387 2662 4388 2658 4388 2660 4388 2662 4389 2660 4389 2663 4389 2663 4390 2660 4390 2664 4390 2658 4391 2665 4391 2656 4391 2656 4392 2665 4392 2666 4392 2656 4393 2666 4393 2667 4393 2640 4394 2668 4394 2638 4394 2638 4395 2668 4395 2656 4395 2638 4396 2656 4396 2669 4396 2669 4397 2656 4397 2667 4397 2670 4398 2232 4398 2231 4398 2670 4399 2231 4399 2671 4399 2671 4400 2231 4400 2213 4400 2671 4401 2213 4401 2672 4401 2672 4402 2213 4402 2673 4402 2673 4403 2213 4403 2238 4403 2673 4404 2238 4404 2674 4404 2674 4405 2238 4405 2237 4405 2674 4406 2237 4406 2675 4406 2675 4407 2237 4407 2235 4407 2675 4408 2235 4408 2676 4408 2676 4409 2235 4409 2241 4409 2676 4410 2241 4410 2677 4410 2677 4411 2241 4411 2240 4411 2677 4412 2240 4412 2678 4412 2678 4413 2240 4413 2239 4413 2678 4414 2239 4414 2679 4414 2679 4415 2239 4415 2210 4415 2679 4416 2210 4416 2680 4416 2680 4417 2210 4417 2244 4417 2680 4418 2244 4418 2681 4418 2681 4419 2244 4419 2243 4419 2681 4420 2243 4420 2682 4420 2243 4421 2217 4421 2682 4421 2682 4422 2217 4422 2183 4422 2682 4423 2183 4423 2683 4423 2183 4424 2185 4424 2683 4424 2683 4425 2185 4425 2186 4425 2683 4426 2186 4426 2684 4426 2684 4427 2186 4427 2179 4427 2684 4428 2179 4428 2685 4428 2685 4429 2179 4429 2191 4429 2685 4430 2191 4430 2686 4430 2686 4431 2191 4431 2190 4431 2686 4432 2190 4432 2687 4432 2687 4433 2190 4433 2688 4433 2688 4434 2190 4434 2188 4434 2688 4435 2188 4435 2689 4435 2689 4436 2188 4436 2194 4436 2689 4437 2194 4437 2690 4437 2690 4438 2194 4438 2193 4438 2690 4439 2193 4439 2691 4439 2691 4440 2193 4440 2192 4440 2691 4441 2192 4441 2692 4441 2692 4442 2192 4442 2176 4442 2692 4443 2176 4443 2693 4443 2693 4444 2176 4444 2199 4444 2693 4445 2199 4445 2694 4445 2694 4446 2199 4446 2198 4446 2694 4447 2198 4447 2695 4447 2695 4448 2198 4448 2196 4448 2695 4449 2196 4449 2696 4449 2696 4450 2196 4450 2202 4450 2696 4451 2202 4451 2697 4451 2697 4452 2202 4452 2201 4452 2697 4453 2201 4453 2698 4453 2698 4454 2201 4454 2200 4454 2698 4455 2200 4455 2699 4455 2699 4456 2200 4456 2173 4456 2699 4457 2173 4457 2700 4457 2700 4458 2173 4458 2701 4458 2701 4459 2173 4459 2207 4459 2701 4460 2207 4460 2702 4460 2702 4461 2207 4461 2206 4461 2702 4462 2206 4462 2703 4462 2703 4463 2206 4463 2204 4463 2703 4464 2204 4464 2704 4464 2704 4465 2204 4465 2203 4465 2704 4466 2203 4466 2705 4466 2705 4467 2203 4467 2170 4467 2705 4468 2170 4468 2706 4468 2170 4469 2182 4469 2706 4469 2706 4470 2182 4470 2181 4470 2706 4471 2181 4471 2707 4471 2707 4472 2181 4472 2219 4472 2707 4473 2219 4473 2708 4473 2708 4474 2219 4474 2221 4474 2708 4475 2221 4475 2709 4475 2709 4476 2221 4476 2225 4476 2709 4477 2225 4477 2710 4477 2710 4478 2225 4478 2224 4478 2710 4479 2224 4479 2711 4479 2711 4480 2224 4480 2223 4480 2711 4481 2223 4481 2712 4481 2712 4482 2223 4482 2216 4482 2712 4483 2216 4483 2713 4483 2713 4484 2216 4484 2230 4484 2232 4485 2670 4485 2233 4485 2233 4486 2670 4486 2714 4486 2233 4487 2714 4487 2227 4487 2227 4488 2714 4488 2715 4488 2227 4489 2715 4489 2229 4489 2229 4490 2715 4490 2716 4490 2229 4491 2716 4491 2230 4491 2230 4492 2716 4492 2717 4492 2230 4493 2717 4493 2713 4493 2718 4494 2719 4494 2248 4494 2253 4495 2720 4495 2721 4495 2721 4496 2720 4496 2722 4496 2721 4497 2722 4497 2245 4497 2245 4498 2722 4498 2718 4498 2245 4499 2718 4499 2246 4499 2246 4500 2718 4500 2248 4500 2298 4501 2299 4501 2723 4501 2724 4502 2725 4502 2726 4502 2727 4503 2728 4503 2729 4503 2730 4504 2731 4504 2732 4504 2281 4505 2280 4505 2733 4505 2733 4506 2280 4506 2290 4506 2734 4507 2735 4507 2736 4507 2736 4508 2735 4508 2284 4508 2736 4509 2284 4509 2283 4509 2279 4510 2278 4510 2737 4510 2737 4511 2278 4511 2277 4511 2737 4512 2277 4512 2735 4512 2735 4513 2277 4513 2276 4513 2735 4514 2276 4514 2284 4514 1841 4515 1840 4515 2304 4515 2304 4516 1840 4516 1839 4516 2304 4517 1839 4517 1845 4517 1780 4518 1779 4518 2738 4518 2269 4519 2267 4519 2738 4519 2738 4520 2267 4520 2266 4520 2738 4521 2266 4521 2265 4521 2265 4522 2264 4522 2738 4522 2738 4523 2264 4523 2263 4523 2738 4524 2263 4524 1780 4524 2258 4525 2259 4525 2739 4525 2739 4526 2259 4526 2261 4526 2739 4527 2261 4527 2262 4527 2740 4528 2741 4528 2742 4528 2742 4529 2741 4529 2253 4529 2742 4530 2253 4530 2252 4530 2743 4531 2744 4531 2745 4531 2745 4532 2744 4532 2746 4532 2745 4533 2746 4533 2747 4533 2747 4534 2746 4534 2748 4534 2747 4535 2748 4535 2732 4535 2732 4536 2748 4536 2749 4536 2732 4537 2749 4537 2750 4537 2751 4538 2752 4538 2753 4538 2754 4539 2755 4539 2756 4539 2757 4540 2758 4540 2759 4540 2759 4541 2758 4541 2760 4541 2759 4542 2760 4542 2761 4542 2762 4543 2763 4543 2764 4543 2762 4544 2764 4544 2726 4544 2763 4545 2762 4545 2765 4545 2765 4546 2762 4546 2733 4546 2765 4547 2733 4547 2766 4547 2766 4548 2733 4548 2290 4548 2766 4549 2290 4549 2295 4549 2252 4550 2258 4550 2742 4550 2742 4551 2258 4551 2739 4551 2742 4552 2739 4552 2723 4552 2723 4553 2739 4553 2262 4553 2723 4554 2262 4554 2270 4554 2732 4555 2731 4555 2747 4555 2747 4556 2731 4556 2767 4556 2747 4557 2767 4557 2745 4557 2768 4558 2759 4558 2754 4558 2754 4559 2759 4559 2761 4559 2754 4560 2761 4560 2755 4560 2726 4561 2725 4561 2762 4561 2762 4562 2725 4562 2769 4562 2762 4563 2769 4563 2733 4563 2270 4564 2269 4564 2723 4564 2723 4565 2269 4565 2738 4565 2723 4566 2738 4566 2298 4566 2298 4567 2738 4567 1779 4567 2298 4568 1779 4568 1778 4568 2299 4569 2308 4569 2723 4569 2723 4570 2308 4570 2730 4570 2723 4571 2730 4571 2742 4571 2742 4572 2730 4572 2732 4572 2742 4573 2732 4573 2740 4573 2740 4574 2732 4574 2750 4574 2315 4575 2767 4575 2313 4575 2313 4576 2767 4576 2731 4576 2313 4577 2731 4577 2311 4577 2311 4578 2731 4578 2730 4578 2311 4579 2730 4579 2309 4579 2309 4580 2730 4580 2308 4580 2315 4581 2317 4581 2767 4581 2767 4582 2317 4582 2770 4582 2767 4583 2770 4583 2745 4583 2745 4584 2770 4584 2753 4584 2745 4585 2753 4585 2743 4585 2743 4586 2753 4586 2752 4586 2317 4587 2319 4587 2770 4587 2770 4588 2319 4588 2727 4588 2770 4589 2727 4589 2753 4589 2753 4590 2727 4590 2729 4590 2753 4591 2729 4591 2751 4591 2751 4592 2729 4592 2756 4592 2319 4593 2321 4593 2727 4593 2727 4594 2321 4594 2323 4594 2727 4595 2323 4595 2728 4595 2728 4596 2323 4596 2325 4596 2728 4597 2325 4597 2327 4597 2756 4598 2729 4598 2754 4598 2754 4599 2729 4599 2728 4599 2754 4600 2728 4600 2768 4600 2768 4601 2728 4601 2327 4601 2768 4602 2327 4602 2329 4602 2329 4603 2331 4603 2768 4603 2768 4604 2331 4604 2724 4604 2768 4605 2724 4605 2759 4605 2759 4606 2724 4606 2726 4606 2759 4607 2726 4607 2757 4607 2757 4608 2726 4608 2764 4608 2339 4609 2769 4609 2337 4609 2337 4610 2769 4610 2725 4610 2337 4611 2725 4611 2335 4611 2335 4612 2725 4612 2724 4612 2335 4613 2724 4613 2333 4613 2333 4614 2724 4614 2331 4614 2339 4615 2341 4615 2769 4615 2769 4616 2341 4616 2734 4616 2769 4617 2734 4617 2733 4617 2733 4618 2734 4618 2736 4618 2733 4619 2736 4619 2281 4619 2281 4620 2736 4620 2283 4620 1845 4621 2279 4621 2304 4621 2304 4622 2279 4622 2737 4622 2304 4623 2737 4623 2307 4623 2307 4624 2737 4624 2735 4624 2307 4625 2735 4625 2306 4625 2306 4626 2735 4626 2734 4626 2306 4627 2734 4627 2343 4627 2343 4628 2734 4628 2341 4628 2771 4629 2295 4629 2772 4629 2772 4630 2295 4630 2773 4630 2772 4631 2773 4631 2774 4631 2774 4632 2773 4632 2297 4632 2774 4633 2297 4633 2775 4633 2775 4634 2297 4634 2294 4634 2775 4635 2294 4635 2776 4635 2776 4636 2294 4636 2293 4636 2517 4637 2516 4637 2777 4637 2513 4638 2512 4638 2778 4638 2778 4639 2512 4639 2779 4639 2778 4640 2779 4640 2780 4640 2780 4641 2779 4641 2781 4641 2781 4642 2779 4642 2782 4642 2782 4643 2779 4643 2783 4643 2782 4644 2783 4644 2784 4644 2785 4645 2786 4645 2783 4645 2783 4646 2786 4646 2787 4646 2783 4647 2787 4647 2784 4647 2788 4648 2789 4648 2790 4648 2790 4649 2789 4649 2791 4649 2792 4650 2793 4650 2794 4650 2794 4651 2793 4651 2795 4651 2794 4652 2795 4652 2796 4652 2797 4653 2798 4653 2783 4653 2798 4654 2792 4654 2783 4654 2783 4655 2792 4655 2794 4655 2783 4656 2794 4656 2785 4656 2785 4657 2794 4657 2796 4657 2785 4658 2796 4658 2789 4658 2789 4659 2796 4659 2799 4659 2789 4660 2799 4660 2791 4660 2800 4661 2801 4661 2802 4661 2802 4662 2801 4662 2803 4662 2802 4663 2803 4663 2777 4663 2777 4664 2803 4664 2804 4664 2777 4665 2804 4665 2805 4665 2805 4666 2804 4666 2806 4666 2805 4667 2806 4667 2807 4667 2506 4668 2508 4668 2808 4668 2808 4669 2809 4669 2506 4669 2506 4670 2809 4670 2800 4670 2506 4671 2800 4671 2509 4671 2509 4672 2800 4672 2802 4672 2509 4673 2802 4673 2510 4673 2510 4674 2802 4674 2777 4674 2510 4675 2777 4675 2515 4675 2515 4676 2777 4676 2516 4676 2807 4677 2797 4677 2805 4677 2805 4678 2797 4678 2783 4678 2805 4679 2783 4679 2777 4679 2777 4680 2783 4680 2779 4680 2777 4681 2779 4681 2517 4681 2517 4682 2779 4682 2512 4682 2810 4683 2811 4683 2812 4683 2813 4684 2814 4684 2815 4684 2345 4685 2344 4685 2816 4685 2336 4686 2334 4686 2817 4686 2328 4687 2326 4687 2818 4687 2818 4688 2326 4688 2819 4688 2312 4689 2310 4689 2820 4689 2302 4690 2301 4690 2821 4690 1835 4691 1843 4691 2303 4691 2822 4692 2823 4692 2810 4692 2810 4693 2823 4693 2393 4693 2389 4694 2824 4694 2363 4694 2363 4695 2824 4695 2825 4695 2363 4696 2825 4696 2355 4696 2355 4697 2825 4697 2356 4697 2826 4698 2352 4698 2358 4698 2351 4699 2821 4699 2350 4699 2350 4700 2821 4700 2827 4700 2350 4701 2827 4701 2353 4701 2353 4702 2827 4702 2354 4702 2300 4703 1783 4703 1782 4703 2383 4704 2382 4704 2828 4704 2828 4705 2382 4705 1833 4705 2828 4706 1833 4706 1834 4706 2393 4707 2372 4707 2810 4707 2810 4708 2372 4708 2374 4708 2810 4709 2374 4709 2811 4709 2811 4710 2374 4710 2378 4710 2811 4711 2378 4711 2380 4711 2380 4712 2381 4712 2811 4712 2811 4713 2381 4713 2386 4713 2811 4714 2386 4714 2812 4714 2812 4715 2386 4715 2385 4715 2812 4716 2385 4716 2828 4716 2828 4717 2385 4717 2384 4717 2828 4718 2384 4718 2383 4718 2821 4719 2301 4719 2827 4719 2827 4720 2301 4720 2300 4720 2827 4721 2300 4721 2354 4721 2354 4722 2300 4722 1782 4722 2354 4723 1782 4723 1787 4723 2316 4724 2314 4724 2829 4724 2318 4725 2830 4725 2831 4725 2326 4726 2324 4726 2819 4726 2819 4727 2324 4727 2322 4727 2819 4728 2322 4728 2831 4728 2831 4729 2322 4729 2320 4729 2831 4730 2320 4730 2318 4730 2332 4731 2330 4731 2832 4731 2832 4732 2330 4732 2328 4732 2833 4733 2340 4733 2815 4733 2815 4734 2340 4734 2338 4734 2816 4735 2344 4735 2833 4735 2833 4736 2344 4736 2342 4736 2833 4737 2342 4737 2340 4737 1834 4738 1835 4738 2828 4738 2828 4739 1835 4739 2303 4739 2828 4740 2303 4740 2812 4740 2812 4741 2303 4741 2305 4741 2310 4742 2302 4742 2820 4742 2820 4743 2302 4743 2821 4743 2820 4744 2821 4744 2826 4744 2826 4745 2821 4745 2351 4745 2826 4746 2351 4746 2352 4746 2358 4747 2356 4747 2826 4747 2826 4748 2356 4748 2825 4748 2826 4749 2825 4749 2820 4749 2820 4750 2825 4750 2829 4750 2820 4751 2829 4751 2312 4751 2312 4752 2829 4752 2314 4752 2834 4753 2818 4753 2835 4753 2835 4754 2818 4754 2819 4754 2835 4755 2819 4755 2836 4755 2836 4756 2819 4756 2831 4756 2836 4757 2831 4757 2837 4757 2837 4758 2831 4758 2830 4758 2837 4759 2830 4759 2838 4759 2839 4760 2817 4760 2832 4760 2832 4761 2817 4761 2334 4761 2832 4762 2334 4762 2332 4762 2815 4763 2814 4763 2833 4763 2833 4764 2814 4764 2840 4764 2833 4765 2840 4765 2816 4765 2824 4766 2841 4766 2825 4766 2825 4767 2841 4767 2838 4767 2825 4768 2838 4768 2829 4768 2829 4769 2838 4769 2830 4769 2829 4770 2830 4770 2316 4770 2316 4771 2830 4771 2318 4771 2841 4772 2842 4772 2838 4772 2838 4773 2842 4773 2843 4773 2838 4774 2843 4774 2837 4774 2837 4775 2843 4775 2844 4775 2837 4776 2844 4776 2836 4776 2836 4777 2844 4777 2845 4777 2845 4778 2846 4778 2836 4778 2836 4779 2846 4779 2847 4779 2836 4780 2847 4780 2835 4780 2835 4781 2847 4781 2848 4781 2835 4782 2848 4782 2834 4782 2834 4783 2848 4783 2849 4783 2834 4784 2849 4784 2850 4784 2328 4785 2818 4785 2832 4785 2832 4786 2818 4786 2834 4786 2832 4787 2834 4787 2839 4787 2839 4788 2834 4788 2850 4788 2839 4789 2850 4789 2851 4789 2851 4790 2852 4790 2839 4790 2839 4791 2852 4791 2813 4791 2839 4792 2813 4792 2817 4792 2817 4793 2813 4793 2815 4793 2817 4794 2815 4794 2336 4794 2336 4795 2815 4795 2338 4795 2852 4796 2853 4796 2813 4796 2813 4797 2853 4797 2854 4797 2813 4798 2854 4798 2814 4798 2814 4799 2854 4799 2855 4799 2814 4800 2855 4800 2840 4800 2840 4801 2855 4801 2856 4801 2840 4802 2856 4802 2857 4802 2857 4803 2822 4803 2840 4803 2840 4804 2822 4804 2810 4804 2840 4805 2810 4805 2816 4805 2816 4806 2810 4806 2812 4806 2816 4807 2812 4807 2345 4807 2345 4808 2812 4808 2305 4808 2858 4809 2389 4809 2859 4809 2859 4810 2389 4810 2390 4810 2859 4811 2390 4811 2860 4811 2860 4812 2390 4812 2388 4812 2860 4813 2388 4813 2861 4813 2861 4814 2388 4814 2387 4814 2392 4815 2862 4815 2863 4815 2392 4816 2863 4816 2391 4816 2391 4817 2863 4817 2864 4817 2391 4818 2864 4818 2394 4818 2862 4819 2392 4819 2865 4819 2865 4820 2392 4820 2393 4820 2865 4821 2393 4821 2866 4821 2867 4822 2868 4822 2869 4822 2561 4823 2567 4823 2870 4823 2871 4824 2872 4824 2873 4824 2874 4825 2875 4825 2876 4825 2876 4826 2875 4826 2877 4826 2870 4827 2878 4827 2879 4827 2566 4828 2880 4828 2567 4828 2567 4829 2880 4829 2881 4829 2567 4830 2881 4830 2870 4830 2870 4831 2881 4831 2882 4831 2870 4832 2882 4832 2878 4832 2561 4833 2870 4833 2560 4833 2560 4834 2870 4834 2883 4834 2560 4835 2883 4835 2559 4835 2559 4836 2883 4836 2884 4836 2559 4837 2884 4837 2558 4837 2558 4838 2884 4838 2885 4838 2558 4839 2885 4839 2557 4839 2886 4840 2553 4840 2887 4840 2887 4841 2553 4841 2554 4841 2887 4842 2554 4842 2888 4842 2888 4843 2554 4843 2555 4843 2888 4844 2555 4844 2885 4844 2885 4845 2555 4845 2556 4845 2885 4846 2556 4846 2557 4846 2889 4847 2551 4847 2886 4847 2886 4848 2551 4848 2552 4848 2886 4849 2552 4849 2553 4849 2535 4850 2547 4850 2890 4850 2890 4851 2547 4851 2548 4851 2890 4852 2548 4852 2891 4852 2891 4853 2548 4853 2549 4853 2891 4854 2549 4854 2889 4854 2889 4855 2549 4855 2550 4855 2889 4856 2550 4856 2551 4856 2536 4857 2535 4857 2892 4857 2892 4858 2535 4858 2890 4858 2892 4859 2890 4859 2893 4859 2893 4860 2890 4860 2894 4860 2895 4861 2867 4861 2896 4861 2896 4862 2867 4862 2869 4862 2896 4863 2869 4863 2897 4863 2897 4864 2869 4864 2898 4864 2897 4865 2898 4865 2899 4865 2899 4866 2898 4866 2900 4866 2901 4867 2902 4867 2900 4867 2900 4868 2902 4868 2903 4868 2900 4869 2903 4869 2899 4869 2904 4870 2905 4870 2901 4870 2901 4871 2905 4871 2906 4871 2901 4872 2906 4872 2902 4872 2907 4873 2908 4873 2909 4873 2909 4874 2908 4874 2910 4874 2909 4875 2910 4875 2904 4875 2904 4876 2910 4876 2911 4876 2904 4877 2911 4877 2905 4877 2907 4878 2909 4878 2912 4878 2912 4879 2909 4879 2913 4879 2912 4880 2913 4880 2914 4880 2914 4881 2913 4881 2915 4881 2914 4882 2915 4882 2916 4882 2916 4883 2915 4883 2917 4883 2916 4884 2917 4884 2918 4884 2877 4885 2871 4885 2876 4885 2876 4886 2871 4886 2873 4886 2876 4887 2873 4887 2917 4887 2917 4888 2873 4888 2919 4888 2917 4889 2919 4889 2918 4889 2879 4890 2874 4890 2870 4890 2870 4891 2874 4891 2876 4891 2870 4892 2876 4892 2883 4892 2883 4893 2876 4893 2917 4893 2883 4894 2917 4894 2884 4894 2884 4895 2917 4895 2915 4895 2884 4896 2915 4896 2885 4896 2885 4897 2915 4897 2913 4897 2885 4898 2913 4898 2888 4898 2888 4899 2913 4899 2909 4899 2888 4900 2909 4900 2887 4900 2887 4901 2909 4901 2904 4901 2887 4902 2904 4902 2886 4902 2886 4903 2904 4903 2901 4903 2886 4904 2901 4904 2889 4904 2889 4905 2901 4905 2900 4905 2889 4906 2900 4906 2891 4906 2891 4907 2900 4907 2898 4907 2891 4908 2898 4908 2890 4908 2890 4909 2898 4909 2869 4909 2890 4910 2869 4910 2894 4910 2894 4911 2869 4911 2868 4911 2920 4912 2921 4912 2922 4912 2923 4913 2924 4913 2925 4913 2926 4914 2927 4914 2928 4914 2928 4915 2927 4915 2929 4915 2930 4916 2931 4916 2932 4916 2932 4917 2931 4917 2933 4917 2932 4918 2933 4918 2934 4918 2935 4919 2936 4919 2937 4919 2937 4920 2936 4920 2938 4920 2937 4921 2938 4921 2939 4921 2940 4922 2941 4922 2942 4922 2942 4923 2941 4923 2943 4923 2586 4924 2585 4924 2944 4924 2944 4925 2585 4925 2945 4925 2945 4926 2946 4926 2944 4926 2944 4927 2946 4927 2947 4927 2944 4928 2947 4928 2948 4928 2586 4929 2944 4929 2587 4929 2587 4930 2944 4930 2949 4930 2587 4931 2949 4931 2588 4931 2588 4932 2949 4932 2589 4932 2589 4933 2949 4933 2950 4933 2589 4934 2950 4934 2590 4934 2590 4935 2950 4935 2951 4935 2590 4936 2951 4936 2591 4936 2591 4937 2951 4937 2592 4937 2592 4938 2951 4938 2952 4938 2592 4939 2952 4939 2593 4939 2593 4940 2952 4940 2594 4940 2594 4941 2952 4941 2953 4941 2594 4942 2953 4942 2595 4942 2595 4943 2953 4943 2954 4943 2595 4944 2954 4944 2576 4944 2576 4945 2954 4945 2575 4945 2575 4946 2954 4946 2955 4946 2575 4947 2955 4947 2574 4947 2574 4948 2955 4948 2573 4948 2573 4949 2955 4949 2956 4949 2573 4950 2956 4950 2572 4950 2957 4951 2958 4951 2959 4951 2572 4952 2956 4952 2562 4952 2562 4953 2956 4953 2957 4953 2562 4954 2957 4954 2563 4954 2563 4955 2957 4955 2959 4955 2563 4956 2959 4956 2564 4956 2960 4957 2961 4957 2957 4957 2961 4958 2962 4958 2957 4958 2957 4959 2962 4959 2963 4959 2957 4960 2963 4960 2958 4960 2964 4961 2965 4961 2966 4961 2967 4962 2968 4962 2966 4962 2966 4963 2968 4963 2969 4963 2966 4964 2969 4964 2964 4964 2970 4965 2971 4965 2972 4965 2923 4966 2925 4966 2973 4966 2974 4967 2971 4967 2975 4967 2975 4968 2971 4968 2970 4968 2975 4969 2970 4969 2976 4969 2976 4970 2970 4970 2977 4970 2976 4971 2977 4971 2978 4971 2979 4972 2980 4972 2981 4972 2979 4973 2981 4973 2982 4973 2981 4974 2983 4974 2982 4974 2982 4975 2983 4975 2984 4975 2982 4976 2984 4976 2977 4976 2977 4977 2984 4977 2985 4977 2977 4978 2985 4978 2978 4978 2980 4979 2979 4979 2986 4979 2986 4980 2979 4980 2987 4980 2986 4981 2987 4981 2988 4981 2988 4982 2987 4982 2989 4982 2989 4983 2987 4983 2990 4983 2989 4984 2990 4984 2991 4984 2922 4985 2921 4985 2990 4985 2990 4986 2921 4986 2992 4986 2990 4987 2992 4987 2991 4987 2920 4988 2922 4988 2993 4988 2993 4989 2922 4989 2994 4989 2993 4990 2994 4990 2995 4990 2995 4991 2994 4991 2996 4991 2996 4992 2994 4992 2997 4992 2996 4993 2997 4993 2998 4993 2998 4994 2997 4994 2999 4994 2999 4995 2997 4995 2932 4995 2999 4996 2932 4996 3000 4996 3000 4997 2932 4997 2934 4997 3000 4998 2934 4998 3001 4998 2929 4999 2930 4999 2928 4999 2928 5000 2930 5000 2932 5000 2928 5001 2932 5001 3002 5001 3002 5002 2932 5002 2997 5002 3002 5003 2997 5003 3003 5003 3003 5004 2997 5004 2994 5004 3003 5005 2994 5005 3004 5005 3004 5006 2994 5006 2922 5006 3004 5007 2922 5007 3005 5007 3005 5008 2922 5008 2990 5008 3005 5009 2990 5009 3006 5009 3006 5010 2990 5010 2987 5010 3006 5011 2987 5011 3007 5011 3007 5012 2987 5012 2979 5012 3007 5013 2979 5013 3008 5013 3008 5014 2979 5014 2982 5014 3008 5015 2982 5015 3009 5015 3009 5016 2982 5016 2977 5016 3009 5017 2977 5017 2925 5017 2925 5018 2977 5018 2970 5018 2925 5019 2970 5019 2973 5019 2973 5020 2970 5020 2972 5020 2939 5021 2926 5021 2937 5021 2937 5022 2926 5022 2928 5022 2937 5023 2928 5023 3010 5023 3010 5024 2928 5024 3002 5024 3010 5025 3002 5025 3011 5025 3011 5026 3002 5026 3003 5026 3011 5027 3003 5027 3012 5027 3012 5028 3003 5028 3004 5028 3012 5029 3004 5029 3013 5029 3013 5030 3004 5030 3005 5030 3013 5031 3005 5031 3014 5031 3014 5032 3005 5032 3006 5032 3014 5033 3006 5033 3015 5033 3015 5034 3006 5034 3007 5034 3015 5035 3007 5035 3016 5035 3016 5036 3007 5036 3008 5036 3016 5037 3008 5037 3017 5037 3017 5038 3008 5038 3009 5038 3017 5039 3009 5039 2966 5039 2966 5040 3009 5040 2925 5040 2966 5041 2925 5041 2967 5041 2967 5042 2925 5042 2924 5042 2943 5043 2935 5043 2942 5043 2942 5044 2935 5044 2937 5044 2942 5045 2937 5045 3018 5045 3018 5046 2937 5046 3010 5046 3018 5047 3010 5047 3019 5047 3019 5048 3010 5048 3011 5048 3019 5049 3011 5049 3020 5049 3020 5050 3011 5050 3012 5050 3020 5051 3012 5051 3021 5051 3021 5052 3012 5052 3013 5052 3021 5053 3013 5053 3022 5053 3022 5054 3013 5054 3014 5054 3022 5055 3014 5055 3023 5055 3023 5056 3014 5056 3015 5056 3023 5057 3015 5057 3024 5057 3024 5058 3015 5058 3016 5058 3024 5059 3016 5059 3025 5059 3025 5060 3016 5060 3017 5060 3025 5061 3017 5061 3026 5061 3026 5062 3017 5062 2966 5062 3026 5063 2966 5063 3027 5063 3027 5064 2966 5064 2965 5064 2948 5065 2940 5065 2944 5065 2944 5066 2940 5066 2942 5066 2944 5067 2942 5067 2949 5067 2949 5068 2942 5068 3018 5068 2949 5069 3018 5069 2950 5069 2950 5070 3018 5070 3019 5070 2950 5071 3019 5071 2951 5071 2951 5072 3019 5072 3020 5072 2951 5073 3020 5073 2952 5073 2952 5074 3020 5074 3021 5074 2952 5075 3021 5075 2953 5075 2953 5076 3021 5076 3022 5076 2953 5077 3022 5077 2954 5077 2954 5078 3022 5078 3023 5078 2954 5079 3023 5079 2955 5079 2955 5080 3023 5080 3024 5080 2955 5081 3024 5081 2956 5081 2956 5082 3024 5082 3025 5082 2956 5083 3025 5083 2957 5083 2957 5084 3025 5084 3026 5084 2957 5085 3026 5085 2960 5085 2960 5086 3026 5086 3027 5086 3028 5087 3029 5087 3030 5087 3031 5088 3032 5088 3033 5088 3034 5089 3035 5089 3030 5089 3036 5090 3037 5090 3038 5090 3039 5091 3040 5091 3041 5091 3042 5092 2579 5092 3043 5092 3042 5093 3043 5093 3044 5093 3045 5094 3046 5094 3047 5094 3047 5095 3046 5095 3048 5095 3047 5096 3048 5096 3049 5096 3050 5097 3051 5097 3052 5097 3052 5098 3051 5098 3053 5098 3054 5099 3050 5099 3055 5099 3055 5100 3050 5100 3052 5100 3055 5101 3052 5101 3056 5101 3056 5102 3052 5102 3057 5102 3056 5103 3057 5103 3058 5103 3058 5104 3057 5104 3059 5104 3058 5105 3059 5105 3060 5105 3041 5106 3040 5106 3059 5106 3059 5107 3040 5107 3061 5107 3059 5108 3061 5108 3060 5108 3038 5109 3037 5109 3062 5109 3037 5110 3063 5110 3062 5110 3062 5111 3063 5111 3064 5111 3062 5112 3064 5112 3033 5112 3033 5113 3064 5113 3065 5113 3033 5114 3065 5114 3066 5114 3034 5115 3030 5115 3067 5115 3068 5116 3069 5116 2533 5116 2502 5117 3067 5117 2503 5117 2503 5118 3067 5118 3070 5118 2503 5119 3070 5119 2511 5119 2511 5120 3070 5120 3068 5120 2511 5121 3068 5121 2504 5121 2504 5122 3068 5122 2533 5122 2504 5123 2533 5123 2505 5123 3053 5124 3045 5124 3052 5124 3052 5125 3045 5125 3047 5125 3052 5126 3047 5126 3057 5126 3057 5127 3047 5127 3071 5127 3057 5128 3071 5128 3059 5128 3059 5129 3071 5129 3072 5129 3059 5130 3072 5130 3041 5130 3033 5131 3032 5131 3062 5131 3062 5132 3032 5132 3073 5132 3062 5133 3073 5133 3038 5133 3074 5134 3028 5134 3075 5134 3075 5135 3028 5135 3030 5135 3075 5136 3030 5136 3076 5136 3076 5137 3030 5137 3035 5137 2597 5138 3072 5138 3077 5138 3077 5139 3072 5139 3071 5139 3077 5140 3071 5140 2582 5140 2582 5141 3071 5141 3047 5141 2582 5142 3047 5142 3043 5142 3043 5143 3047 5143 3049 5143 3043 5144 3049 5144 3044 5144 2597 5145 3078 5145 3072 5145 3072 5146 3078 5146 3031 5146 3072 5147 3031 5147 3041 5147 3041 5148 3031 5148 3033 5148 3041 5149 3033 5149 3039 5149 3039 5150 3033 5150 3066 5150 3078 5151 3079 5151 3031 5151 3031 5152 3079 5152 2600 5152 3031 5153 2600 5153 3032 5153 3032 5154 2600 5154 3080 5154 3032 5155 3080 5155 3073 5155 3073 5156 3080 5156 2521 5156 2521 5157 3081 5157 3073 5157 3073 5158 3081 5158 3074 5158 3073 5159 3074 5159 3038 5159 3038 5160 3074 5160 3075 5160 3038 5161 3075 5161 3036 5161 3036 5162 3075 5162 3076 5162 3081 5163 3082 5163 3074 5163 3074 5164 3082 5164 2603 5164 3074 5165 2603 5165 3028 5165 3028 5166 2603 5166 3083 5166 3028 5167 3083 5167 3029 5167 3029 5168 3083 5168 2605 5168 3029 5169 2605 5169 3084 5169 3067 5170 3030 5170 3070 5170 3070 5171 3030 5171 3029 5171 3070 5172 3029 5172 3068 5172 3068 5173 3029 5173 3084 5173 3068 5174 3084 5174 3069 5174 3085 5175 3086 5175 3087 5175 939 5176 938 5176 3088 5176 1655 5177 1654 5177 3089 5177 1010 5178 1009 5178 3090 5178 3091 5179 2248 5179 3092 5179 3092 5180 2248 5180 2719 5180 3093 5181 3094 5181 3095 5181 972 5182 2248 5182 973 5182 973 5183 2248 5183 3091 5183 973 5184 3091 5184 1018 5184 1018 5185 3091 5185 3096 5185 1018 5186 3096 5186 1019 5186 1019 5187 3096 5187 3097 5187 1019 5188 3097 5188 1021 5188 3097 5189 3093 5189 1021 5189 1021 5190 3093 5190 3095 5190 1021 5191 3095 5191 1022 5191 1022 5192 3095 5192 1023 5192 1014 5193 1015 5193 3098 5193 3098 5194 1015 5194 1017 5194 3098 5195 1017 5195 3095 5195 3095 5196 1017 5196 1024 5196 3095 5197 1024 5197 1023 5197 3099 5198 1005 5198 1012 5198 1005 5199 3099 5199 1006 5199 1006 5200 3099 5200 3100 5200 1006 5201 3100 5201 3090 5201 1009 5202 1008 5202 3090 5202 3090 5203 1008 5203 1007 5203 3090 5204 1007 5204 1006 5204 1011 5205 1010 5205 3101 5205 3102 5206 1646 5206 3101 5206 3101 5207 1646 5207 1647 5207 3101 5208 1647 5208 1011 5208 1650 5209 1649 5209 3103 5209 3103 5210 1649 5210 1648 5210 3103 5211 1648 5211 3102 5211 3102 5212 1648 5212 1645 5212 3102 5213 1645 5213 1646 5213 3089 5214 1654 5214 3103 5214 3103 5215 1654 5215 1651 5215 3103 5216 1651 5216 1650 5216 954 5217 1656 5217 955 5217 955 5218 1656 5218 3104 5218 955 5219 3104 5219 957 5219 3105 5220 947 5220 946 5220 942 5221 941 5221 3087 5221 3087 5222 941 5222 949 5222 3087 5223 949 5223 3105 5223 3105 5224 949 5224 948 5224 3105 5225 948 5225 947 5225 3086 5226 944 5226 3087 5226 3087 5227 944 5227 943 5227 3087 5228 943 5228 942 5228 3086 5229 3106 5229 944 5229 944 5230 3106 5230 3107 5230 944 5231 3107 5231 945 5231 3107 5232 3108 5232 945 5232 945 5233 3108 5233 3109 5233 945 5234 3109 5234 935 5234 935 5235 3109 5235 936 5235 3088 5236 938 5236 3109 5236 3109 5237 938 5237 937 5237 3109 5238 937 5238 936 5238 939 5239 3088 5239 940 5239 940 5240 3088 5240 3110 5240 940 5241 3110 5241 932 5241 3111 5242 3112 5242 3087 5242 3087 5243 3112 5243 3113 5243 3087 5244 3113 5244 3085 5244 3114 5245 3115 5245 3116 5245 3116 5246 3117 5246 3114 5246 3114 5247 3117 5247 3118 5247 3114 5248 3118 5248 3119 5248 3119 5249 3118 5249 3120 5249 3119 5250 3120 5250 3121 5250 3098 5251 3122 5251 3114 5251 3114 5252 3122 5252 3123 5252 3114 5253 3123 5253 3115 5253 3124 5254 3125 5254 3098 5254 3098 5255 3125 5255 3126 5255 3098 5256 3126 5256 3122 5256 3094 5257 3127 5257 3095 5257 3095 5258 3127 5258 3128 5258 3095 5259 3128 5259 3098 5259 3098 5260 3128 5260 3129 5260 3098 5261 3129 5261 3124 5261 1010 5262 3090 5262 3101 5262 3101 5263 3090 5263 3100 5263 3101 5264 3100 5264 3102 5264 3102 5265 3100 5265 3130 5265 3102 5266 3130 5266 3103 5266 3103 5267 3130 5267 3131 5267 3103 5268 3131 5268 3089 5268 3121 5269 3111 5269 3119 5269 3119 5270 3111 5270 3087 5270 3119 5271 3087 5271 3132 5271 3132 5272 3087 5272 3105 5272 3132 5273 3105 5273 3104 5273 3104 5274 3105 5274 946 5274 3104 5275 946 5275 957 5275 1012 5276 1014 5276 3099 5276 3099 5277 1014 5277 3098 5277 3099 5278 3098 5278 3100 5278 3100 5279 3098 5279 3114 5279 3100 5280 3114 5280 3130 5280 3130 5281 3114 5281 3119 5281 3130 5282 3119 5282 3131 5282 3131 5283 3119 5283 3132 5283 3131 5284 3132 5284 3089 5284 3089 5285 3132 5285 3104 5285 3089 5286 3104 5286 1655 5286 1655 5287 3104 5287 1656 5287 933 5288 932 5288 3133 5288 922 5289 964 5289 3134 5289 2451 5290 3134 5290 2452 5290 2452 5291 3134 5291 2453 5291 2450 5292 1511 5292 961 5292 2450 5293 961 5293 2451 5293 922 5294 3134 5294 923 5294 2451 5295 961 5295 3134 5295 3134 5296 961 5296 960 5296 3134 5297 960 5297 923 5297 3135 5298 2449 5298 3134 5298 3134 5299 2449 5299 2448 5299 3134 5300 2448 5300 2453 5300 3136 5301 2460 5301 2459 5301 2458 5302 3137 5302 2459 5302 2459 5303 3137 5303 3138 5303 2459 5304 3138 5304 3136 5304 2458 5305 2457 5305 3137 5305 3137 5306 2457 5306 2456 5306 3137 5307 2456 5307 3135 5307 3135 5308 2456 5308 2454 5308 3135 5309 2454 5309 2449 5309 3139 5310 3140 5310 3135 5310 3135 5311 3140 5311 3141 5311 3135 5312 3141 5312 3142 5312 3142 5313 3143 5313 3135 5313 3135 5314 3143 5314 3144 5314 3135 5315 3144 5315 3137 5315 3145 5316 3146 5316 3134 5316 3134 5317 3146 5317 3147 5317 3134 5318 3147 5318 3135 5318 3135 5319 3147 5319 3148 5319 3135 5320 3148 5320 3139 5320 3145 5321 3134 5321 3149 5321 3149 5322 3134 5322 964 5322 3149 5323 964 5323 3150 5323 964 5324 963 5324 3150 5324 3150 5325 963 5325 962 5325 3150 5326 962 5326 3151 5326 3151 5327 962 5327 931 5327 3151 5328 931 5328 3152 5328 3152 5329 931 5329 3153 5329 3153 5330 931 5330 930 5330 3153 5331 930 5331 3154 5331 3154 5332 930 5332 929 5332 3154 5333 929 5333 3155 5333 929 5334 927 5334 3155 5334 3155 5335 927 5335 926 5335 3155 5336 926 5336 3133 5336 3133 5337 926 5337 934 5337 3133 5338 934 5338 933 5338 3156 5339 3157 5339 3158 5339 3159 5340 3160 5340 2719 5340 3157 5341 3161 5341 3158 5341 3158 5342 3161 5342 3162 5342 3158 5343 3162 5343 3159 5343 3159 5344 3162 5344 3163 5344 3159 5345 3163 5345 3160 5345 3164 5346 3165 5346 3166 5346 3156 5347 3158 5347 3167 5347 3167 5348 3158 5348 3166 5348 3167 5349 3166 5349 3168 5349 3168 5350 3166 5350 3165 5350 3168 5351 3165 5351 3169 5351 3166 5352 3170 5352 3171 5352 3164 5353 3166 5353 3172 5353 3172 5354 3166 5354 3171 5354 3172 5355 3171 5355 3173 5355 3170 5356 3166 5356 3174 5356 3174 5357 3166 5357 3158 5357 3174 5358 3158 5358 3175 5358 3176 5359 3177 5359 3158 5359 3158 5360 3177 5360 3178 5360 3158 5361 3178 5361 3175 5361 2719 5362 2718 5362 3159 5362 3159 5363 2718 5363 2722 5363 3159 5364 2722 5364 2720 5364 2720 5365 3179 5365 3159 5365 3159 5366 3179 5366 3180 5366 3159 5367 3180 5367 3158 5367 3158 5368 3180 5368 3181 5368 3158 5369 3181 5369 3176 5369 3182 5370 3183 5370 2631 5370 2631 5371 3183 5371 2627 5371 2627 5372 3183 5372 3184 5372 2627 5373 3184 5373 2634 5373 3185 5374 2635 5374 3186 5374 3186 5375 2635 5375 2634 5375 3186 5376 2634 5376 3187 5376 3187 5377 2634 5377 3184 5377 3188 5378 3189 5378 2613 5378 2613 5379 2612 5379 3188 5379 3188 5380 2612 5380 2609 5380 3188 5381 2609 5381 3190 5381 3190 5382 2609 5382 2608 5382 3190 5383 2608 5383 3191 5383 3191 5384 2608 5384 2637 5384 3191 5385 2637 5385 3185 5385 3185 5386 2637 5386 2636 5386 3185 5387 2636 5387 2635 5387 3189 5388 3192 5388 2613 5388 2613 5389 3192 5389 3193 5389 2613 5390 3193 5390 2615 5390 2615 5391 3193 5391 3194 5391 2615 5392 3194 5392 2616 5392 2616 5393 3194 5393 3195 5393 2616 5394 3195 5394 2620 5394 2620 5395 3195 5395 3196 5395 2620 5396 3196 5396 2619 5396 2619 5397 3196 5397 3197 5397 2619 5398 3197 5398 2617 5398 2617 5399 3197 5399 2618 5399 2618 5400 3197 5400 3198 5400 2618 5401 3198 5401 2614 5401 2614 5402 3198 5402 3199 5402 2614 5403 3199 5403 2621 5403 3199 5404 3200 5404 2621 5404 2621 5405 3200 5405 3201 5405 2621 5406 3201 5406 2622 5406 2622 5407 3201 5407 3202 5407 2622 5408 3202 5408 2623 5408 2623 5409 3202 5409 3203 5409 2623 5410 3203 5410 2624 5410 2624 5411 3203 5411 3204 5411 2624 5412 3204 5412 2611 5412 2611 5413 3204 5413 3205 5413 2611 5414 3205 5414 2610 5414 2610 5415 3205 5415 3206 5415 2610 5416 3206 5416 2625 5416 2625 5417 3206 5417 3207 5417 2625 5418 3207 5418 2626 5418 2626 5419 3207 5419 3208 5419 2626 5420 3208 5420 2628 5420 2628 5421 3208 5421 3209 5421 2628 5422 3209 5422 2629 5422 2629 5423 3209 5423 3210 5423 2629 5424 3210 5424 2633 5424 2633 5425 3210 5425 3211 5425 2633 5426 3211 5426 2632 5426 2632 5427 3211 5427 3182 5427 2632 5428 3182 5428 2630 5428 2630 5429 3182 5429 2631 5429 3212 5430 3213 5430 3214 5430 3215 5431 3216 5431 3217 5431 3218 5432 3219 5432 3220 5432 3221 5433 3222 5433 3223 5433 3224 5434 3225 5434 3226 5434 3227 5435 3228 5435 3229 5435 3230 5436 3231 5436 3232 5436 3233 5437 3234 5437 3235 5437 3236 5438 3237 5438 3238 5438 3239 5439 3240 5439 3226 5439 3241 5440 3242 5440 3243 5440 3244 5441 3245 5441 3246 5441 3247 5442 3248 5442 3249 5442 3250 5443 3251 5443 3252 5443 3251 5444 3250 5444 3253 5444 3253 5445 3250 5445 3254 5445 3253 5446 3254 5446 3255 5446 3255 5447 3254 5447 3256 5447 3255 5448 3256 5448 3257 5448 3249 5449 3248 5449 3256 5449 3256 5450 3248 5450 3258 5450 3256 5451 3258 5451 3257 5451 3259 5452 3235 5452 3260 5452 3260 5453 3235 5453 3261 5453 3260 5454 3261 5454 3262 5454 3262 5455 3261 5455 3263 5455 3264 5456 3265 5456 3263 5456 3263 5457 3265 5457 3266 5457 3263 5458 3266 5458 3262 5458 3267 5459 3268 5459 3232 5459 3232 5460 3268 5460 3269 5460 3243 5461 3242 5461 3267 5461 3267 5462 3242 5462 3270 5462 3267 5463 3270 5463 3268 5463 3271 5464 3229 5464 3272 5464 3272 5465 3229 5465 3273 5465 3272 5466 3273 5466 3274 5466 3274 5467 3273 5467 3275 5467 3274 5468 3275 5468 3276 5468 3276 5469 3275 5469 3277 5469 3278 5470 3279 5470 3239 5470 3279 5471 3278 5471 3280 5471 3281 5472 3282 5472 3283 5472 3283 5473 3282 5473 3284 5473 3285 5474 3223 5474 3286 5474 3286 5475 3223 5475 3287 5475 3286 5476 3287 5476 3288 5476 3288 5477 3287 5477 3289 5477 3290 5478 3291 5478 3289 5478 3289 5479 3291 5479 3292 5479 3289 5480 3292 5480 3288 5480 3220 5481 3293 5481 3294 5481 3238 5482 3237 5482 3293 5482 3293 5483 3237 5483 3295 5483 3293 5484 3295 5484 3294 5484 3296 5485 3217 5485 3297 5485 3297 5486 3217 5486 3298 5486 3299 5487 3300 5487 3301 5487 3301 5488 3300 5488 3302 5488 3301 5489 3302 5489 3298 5489 3298 5490 3302 5490 3303 5490 3298 5491 3303 5491 3297 5491 3304 5492 3305 5492 3214 5492 3250 5493 3306 5493 3254 5493 3254 5494 3306 5494 3307 5494 3254 5495 3307 5495 3256 5495 3256 5496 3307 5496 3308 5496 3256 5497 3308 5497 3249 5497 3235 5498 3234 5498 3261 5498 3261 5499 3234 5499 3309 5499 3261 5500 3309 5500 3263 5500 3232 5501 3231 5501 3267 5501 3267 5502 3231 5502 3310 5502 3267 5503 3310 5503 3243 5503 3229 5504 3228 5504 3273 5504 3273 5505 3228 5505 3311 5505 3273 5506 3311 5506 3275 5506 3239 5507 3226 5507 3278 5507 3278 5508 3226 5508 3225 5508 3278 5509 3225 5509 3312 5509 3313 5510 3283 5510 3314 5510 3314 5511 3283 5511 3284 5511 3314 5512 3284 5512 3280 5512 3223 5513 3222 5513 3287 5513 3287 5514 3222 5514 3315 5514 3287 5515 3315 5515 3289 5515 3220 5516 3219 5516 3293 5516 3293 5517 3219 5517 3316 5517 3293 5518 3316 5518 3238 5518 3217 5519 3216 5519 3298 5519 3298 5520 3216 5520 3317 5520 3298 5521 3317 5521 3301 5521 3304 5522 3214 5522 3318 5522 3318 5523 3214 5523 3213 5523 3318 5524 3213 5524 3319 5524 2683 5525 3306 5525 3319 5525 3319 5526 3306 5526 3250 5526 3319 5527 3250 5527 3318 5527 3318 5528 3250 5528 3252 5528 3318 5529 3252 5529 3304 5529 2687 5530 3308 5530 2686 5530 2686 5531 3308 5531 3307 5531 2686 5532 3307 5532 2685 5532 2685 5533 3307 5533 3306 5533 2685 5534 3306 5534 2684 5534 2684 5535 3306 5535 2683 5535 2687 5536 2688 5536 3308 5536 3308 5537 2688 5537 3233 5537 3308 5538 3233 5538 3249 5538 3249 5539 3233 5539 3235 5539 3249 5540 3235 5540 3247 5540 3247 5541 3235 5541 3259 5541 2692 5542 3309 5542 2691 5542 2691 5543 3309 5543 3234 5543 2691 5544 3234 5544 2690 5544 2690 5545 3234 5545 3233 5545 2690 5546 3233 5546 2689 5546 2689 5547 3233 5547 2688 5547 2692 5548 2693 5548 3309 5548 3309 5549 2693 5549 3320 5549 3309 5550 3320 5550 3263 5550 3263 5551 3320 5551 3246 5551 3263 5552 3246 5552 3264 5552 3264 5553 3246 5553 3245 5553 2693 5554 2694 5554 3320 5554 3320 5555 2694 5555 3230 5555 3320 5556 3230 5556 3246 5556 3246 5557 3230 5557 3232 5557 3246 5558 3232 5558 3244 5558 3244 5559 3232 5559 3269 5559 2694 5560 2695 5560 3230 5560 3230 5561 2695 5561 2696 5561 3230 5562 2696 5562 3231 5562 3231 5563 2696 5563 2697 5563 3231 5564 2697 5564 3310 5564 3310 5565 2697 5565 2698 5565 2698 5566 2699 5566 3310 5566 3310 5567 2699 5567 3227 5567 3310 5568 3227 5568 3243 5568 3243 5569 3227 5569 3229 5569 3243 5570 3229 5570 3241 5570 3241 5571 3229 5571 3271 5571 2699 5572 2700 5572 3227 5572 3227 5573 2700 5573 2701 5573 3227 5574 2701 5574 3228 5574 3228 5575 2701 5575 2702 5575 3228 5576 2702 5576 3311 5576 3311 5577 2702 5577 2703 5577 2703 5578 2704 5578 3311 5578 3311 5579 2704 5579 3224 5579 3311 5580 3224 5580 3275 5580 3275 5581 3224 5581 3226 5581 3275 5582 3226 5582 3277 5582 3277 5583 3226 5583 3240 5583 2704 5584 2705 5584 3224 5584 3224 5585 2705 5585 2706 5585 3224 5586 2706 5586 3225 5586 3225 5587 2706 5587 2707 5587 3225 5588 2707 5588 3312 5588 3312 5589 2707 5589 2708 5589 3312 5590 2708 5590 2709 5590 3280 5591 3278 5591 3314 5591 3314 5592 3278 5592 3312 5592 3314 5593 3312 5593 3313 5593 3313 5594 3312 5594 2709 5594 3313 5595 2709 5595 2710 5595 2710 5596 2711 5596 3313 5596 3313 5597 2711 5597 3221 5597 3313 5598 3221 5598 3283 5598 3283 5599 3221 5599 3223 5599 3283 5600 3223 5600 3281 5600 3281 5601 3223 5601 3285 5601 2716 5602 3315 5602 2717 5602 2717 5603 3315 5603 3222 5603 2717 5604 3222 5604 2713 5604 2713 5605 3222 5605 3221 5605 2713 5606 3221 5606 2712 5606 2712 5607 3221 5607 2711 5607 2716 5608 2715 5608 3315 5608 3315 5609 2715 5609 3218 5609 3315 5610 3218 5610 3289 5610 3289 5611 3218 5611 3220 5611 3289 5612 3220 5612 3290 5612 3290 5613 3220 5613 3294 5613 2672 5614 3316 5614 2671 5614 2671 5615 3316 5615 3219 5615 2671 5616 3219 5616 2670 5616 2670 5617 3219 5617 3218 5617 2670 5618 3218 5618 2714 5618 2714 5619 3218 5619 2715 5619 2672 5620 2673 5620 3316 5620 3316 5621 2673 5621 3215 5621 3316 5622 3215 5622 3238 5622 3238 5623 3215 5623 3217 5623 3238 5624 3217 5624 3236 5624 3236 5625 3217 5625 3296 5625 2677 5626 3317 5626 2676 5626 2676 5627 3317 5627 3216 5627 2676 5628 3216 5628 2675 5628 2675 5629 3216 5629 3215 5629 2675 5630 3215 5630 2674 5630 2674 5631 3215 5631 2673 5631 2677 5632 2678 5632 3317 5632 3317 5633 2678 5633 3212 5633 3317 5634 3212 5634 3301 5634 3301 5635 3212 5635 3214 5635 3301 5636 3214 5636 3299 5636 3299 5637 3214 5637 3305 5637 2678 5638 2679 5638 3212 5638 3212 5639 2679 5639 2680 5639 3212 5640 2680 5640 3213 5640 3213 5641 2680 5641 2681 5641 3213 5642 2681 5642 3319 5642 3319 5643 2681 5643 2682 5643 3319 5644 2682 5644 2683 5644 3321 5645 2666 5645 3322 5645 3322 5646 2666 5646 2665 5646 3322 5647 2665 5647 3323 5647 3323 5648 2665 5648 2658 5648 3323 5649 2658 5649 3324 5649 3324 5650 2658 5650 2661 5650 3324 5651 2661 5651 3325 5651 3325 5652 2661 5652 2662 5652 3325 5653 2662 5653 3326 5653 3327 5654 3328 5654 2642 5654 2642 5655 2654 5655 3327 5655 3327 5656 2654 5656 2639 5656 3327 5657 2639 5657 3329 5657 3329 5658 2639 5658 2638 5658 3329 5659 2638 5659 3330 5659 3330 5660 2638 5660 2669 5660 3330 5661 2669 5661 3321 5661 3321 5662 2669 5662 2667 5662 3321 5663 2667 5663 2666 5663 3328 5664 3331 5664 2642 5664 2642 5665 3331 5665 3332 5665 2642 5666 3332 5666 2643 5666 2643 5667 3332 5667 3333 5667 2643 5668 3333 5668 2645 5668 2645 5669 3333 5669 3334 5669 2645 5670 3334 5670 2646 5670 2646 5671 3334 5671 3335 5671 2646 5672 3335 5672 2650 5672 2650 5673 3335 5673 3336 5673 2662 5674 2663 5674 3326 5674 3326 5675 2663 5675 2664 5675 3326 5676 2664 5676 3337 5676 3337 5677 2664 5677 2660 5677 3337 5678 2660 5678 3338 5678 3338 5679 2660 5679 2659 5679 3338 5680 2659 5680 3339 5680 3339 5681 2659 5681 2657 5681 3339 5682 2657 5682 3340 5682 3340 5683 2657 5683 2656 5683 3340 5684 2656 5684 3341 5684 3341 5685 2656 5685 2668 5685 3341 5686 2668 5686 3342 5686 3342 5687 2668 5687 2640 5687 3342 5688 2640 5688 3343 5688 3343 5689 2640 5689 2641 5689 3343 5690 2641 5690 3344 5690 3344 5691 2641 5691 2655 5691 3344 5692 2655 5692 3345 5692 3345 5693 2655 5693 2653 5693 3345 5694 2653 5694 3346 5694 3346 5695 2653 5695 2652 5695 3346 5696 2652 5696 3347 5696 3347 5697 2652 5697 2651 5697 3347 5698 2651 5698 3348 5698 3348 5699 2651 5699 2644 5699 3348 5700 2644 5700 3349 5700 3349 5701 2644 5701 2647 5701 3349 5702 2647 5702 3350 5702 3350 5703 2647 5703 2648 5703 3350 5704 2648 5704 3336 5704 3336 5705 2648 5705 2649 5705 3336 5706 2649 5706 2650 5706 2892 5707 2893 5707 3351 5707 3352 5708 3353 5708 2868 5708 2868 5709 3353 5709 3354 5709 2868 5710 3354 5710 2894 5710 2894 5711 3354 5711 3355 5711 2894 5712 3355 5712 2893 5712 2893 5713 3355 5713 3356 5713 2893 5714 3356 5714 3351 5714 2868 5715 2867 5715 3352 5715 3352 5716 2867 5716 2895 5716 3352 5717 2895 5717 3357 5717 3351 5718 3358 5718 2892 5718 2892 5719 3358 5719 2537 5719 2892 5720 2537 5720 2536 5720 3359 5721 3360 5721 3361 5721 3362 5722 2537 5722 3358 5722 3356 5723 3361 5723 3351 5723 3351 5724 3361 5724 3360 5724 3351 5725 3360 5725 3358 5725 3358 5726 3360 5726 3363 5726 3358 5727 3363 5727 3362 5727 3364 5728 3365 5728 3366 5728 3367 5729 3368 5729 3369 5729 3369 5730 3368 5730 3370 5730 3369 5731 3370 5731 3366 5731 3366 5732 3370 5732 3371 5732 3366 5733 3371 5733 3364 5733 3365 5734 3372 5734 3366 5734 3366 5735 3372 5735 3373 5735 3366 5736 3373 5736 3361 5736 3361 5737 3373 5737 3374 5737 3361 5738 3374 5738 3359 5738 3375 5739 3376 5739 3369 5739 3369 5740 3376 5740 3377 5740 3369 5741 3377 5741 3367 5741 3378 5742 3375 5742 3379 5742 3379 5743 3375 5743 3369 5743 3379 5744 3369 5744 3380 5744 3380 5745 3369 5745 3381 5745 3382 5746 3383 5746 3366 5746 3366 5747 3383 5747 3384 5747 3366 5748 3384 5748 3369 5748 3369 5749 3384 5749 3385 5749 3369 5750 3385 5750 3381 5750 3361 5751 3386 5751 3387 5751 3387 5752 3388 5752 3361 5752 3361 5753 3388 5753 3389 5753 3361 5754 3389 5754 3366 5754 3366 5755 3389 5755 3390 5755 3366 5756 3390 5756 3382 5756 3356 5757 3355 5757 3361 5757 3361 5758 3355 5758 3354 5758 3361 5759 3354 5759 3386 5759 3386 5760 3354 5760 3353 5760 3386 5761 3353 5761 3391 5761 3391 5762 3353 5762 3352 5762 3391 5763 3352 5763 3392 5763 3392 5764 3352 5764 3357 5764 3180 5765 3179 5765 2740 5765 2740 5766 3179 5766 2741 5766 2741 5767 3179 5767 2720 5767 2741 5768 2720 5768 2253 5768 3393 5769 3394 5769 3171 5769 3171 5770 3394 5770 3395 5770 3171 5771 3395 5771 3173 5771 3171 5772 3170 5772 3393 5772 3393 5773 3170 5773 3174 5773 3393 5774 3174 5774 3175 5774 3178 5775 3177 5775 2750 5775 2750 5776 3177 5776 3176 5776 2750 5777 3176 5777 2740 5777 2740 5778 3176 5778 3181 5778 2740 5779 3181 5779 3180 5779 3396 5780 3397 5780 3398 5780 3399 5781 3400 5781 3401 5781 3397 5782 3402 5782 3398 5782 3398 5783 3402 5783 3399 5783 3398 5784 3399 5784 3403 5784 3403 5785 3399 5785 3401 5785 3404 5786 2764 5786 3405 5786 3405 5787 2764 5787 2763 5787 3405 5788 2763 5788 3406 5788 3406 5789 2763 5789 2765 5789 3406 5790 2765 5790 3407 5790 3407 5791 2765 5791 2766 5791 3407 5792 2766 5792 3408 5792 2295 5793 2771 5793 2766 5793 2766 5794 2771 5794 3409 5794 2766 5795 3409 5795 3408 5795 3404 5796 3396 5796 2764 5796 2764 5797 3396 5797 3398 5797 2764 5798 3398 5798 2757 5798 2757 5799 3398 5799 3410 5799 2757 5800 3410 5800 2758 5800 2758 5801 3410 5801 3411 5801 2758 5802 3411 5802 2760 5802 3411 5803 3412 5803 2760 5803 2760 5804 3412 5804 3413 5804 2760 5805 3413 5805 2761 5805 2761 5806 3413 5806 3414 5806 2761 5807 3414 5807 2755 5807 2755 5808 3414 5808 3415 5808 2755 5809 3415 5809 2756 5809 2756 5810 3415 5810 3416 5810 2756 5811 3416 5811 2751 5811 3416 5812 3417 5812 2751 5812 2751 5813 3417 5813 3418 5813 2751 5814 3418 5814 2752 5814 2752 5815 3418 5815 3419 5815 2752 5816 3419 5816 2743 5816 2743 5817 3419 5817 3420 5817 2743 5818 3420 5818 2744 5818 2744 5819 3420 5819 3421 5819 2744 5820 3421 5820 2746 5820 2746 5821 3421 5821 3422 5821 2746 5822 3422 5822 2748 5822 2748 5823 3422 5823 3423 5823 2748 5824 3423 5824 2749 5824 2749 5825 3423 5825 3393 5825 2749 5826 3393 5826 2750 5826 2750 5827 3393 5827 3175 5827 2750 5828 3175 5828 3178 5828 3424 5829 3425 5829 2822 5829 2822 5830 3425 5830 2823 5830 2823 5831 3425 5831 2866 5831 2823 5832 2866 5832 2393 5832 3426 5833 3427 5833 3428 5833 3428 5834 3427 5834 3429 5834 3428 5835 3429 5835 3430 5835 3428 5836 3431 5836 3426 5836 3426 5837 3431 5837 3432 5837 3426 5838 3432 5838 3433 5838 3434 5839 3435 5839 2857 5839 2857 5840 3435 5840 3436 5840 2857 5841 3436 5841 2822 5841 2822 5842 3436 5842 3437 5842 2822 5843 3437 5843 3424 5843 3438 5844 3439 5844 3440 5844 3441 5845 3442 5845 3443 5845 3443 5846 3442 5846 3438 5846 3443 5847 3438 5847 3444 5847 3444 5848 3438 5848 3440 5848 2389 5849 2858 5849 2824 5849 2824 5850 2858 5850 3445 5850 2824 5851 3445 5851 2841 5851 3446 5852 2843 5852 3447 5852 3447 5853 2843 5853 2842 5853 3447 5854 2842 5854 3448 5854 3448 5855 2842 5855 2841 5855 3448 5856 2841 5856 3449 5856 3449 5857 2841 5857 3445 5857 3446 5858 3441 5858 2843 5858 2843 5859 3441 5859 3443 5859 2843 5860 3443 5860 2844 5860 2844 5861 3443 5861 3450 5861 2844 5862 3450 5862 2845 5862 2845 5863 3450 5863 3451 5863 2845 5864 3451 5864 2846 5864 3451 5865 3452 5865 2846 5865 2846 5866 3452 5866 3453 5866 2846 5867 3453 5867 2847 5867 2847 5868 3453 5868 3454 5868 2847 5869 3454 5869 2848 5869 2848 5870 3454 5870 3455 5870 2848 5871 3455 5871 2849 5871 2849 5872 3455 5872 3456 5872 2849 5873 3456 5873 2850 5873 2850 5874 3456 5874 2851 5874 2851 5875 3456 5875 3457 5875 2851 5876 3457 5876 2852 5876 3457 5877 3458 5877 2852 5877 2852 5878 3458 5878 3459 5878 2852 5879 3459 5879 2853 5879 2853 5880 3459 5880 3460 5880 2853 5881 3460 5881 2854 5881 2854 5882 3460 5882 3461 5882 2854 5883 3461 5883 2855 5883 2855 5884 3461 5884 3462 5884 2855 5885 3462 5885 2856 5885 2856 5886 3462 5886 3426 5886 2856 5887 3426 5887 2857 5887 2857 5888 3426 5888 3433 5888 2857 5889 3433 5889 3434 5889 2965 5890 3463 5890 3464 5890 3465 5891 3466 5891 3467 5891 3468 5892 3469 5892 3470 5892 2570 5893 2569 5893 3471 5893 2962 5894 3471 5894 2963 5894 2963 5895 3471 5895 2569 5895 2963 5896 2569 5896 2958 5896 2958 5897 2569 5897 2568 5897 2958 5898 2568 5898 2959 5898 2959 5899 2568 5899 2564 5899 3464 5900 2565 5900 3471 5900 3471 5901 2565 5901 2571 5901 3471 5902 2571 5902 2570 5902 3472 5903 2881 5903 3473 5903 3473 5904 2881 5904 2880 5904 3473 5905 2880 5905 2566 5905 2879 5906 2878 5906 3474 5906 3474 5907 2878 5907 2882 5907 2871 5908 2877 5908 3475 5908 3475 5909 2877 5909 2875 5909 3475 5910 2875 5910 3474 5910 3474 5911 2875 5911 2874 5911 3474 5912 2874 5912 2879 5912 3470 5913 3476 5913 3477 5913 3477 5914 3476 5914 3478 5914 3477 5915 3478 5915 3479 5915 3479 5916 3478 5916 3480 5916 3479 5917 3480 5917 3475 5917 3475 5918 3480 5918 2872 5918 3475 5919 2872 5919 2871 5919 3468 5920 3470 5920 3481 5920 3481 5921 3470 5921 3477 5921 3481 5922 3477 5922 3482 5922 2974 5923 3465 5923 2971 5923 2971 5924 3465 5924 3467 5924 2971 5925 3467 5925 2972 5925 3483 5926 3484 5926 2967 5926 2967 5927 2924 5927 3483 5927 3483 5928 2924 5928 2923 5928 3483 5929 2923 5929 3467 5929 3467 5930 2923 5930 2973 5930 3467 5931 2973 5931 2972 5931 2965 5932 2964 5932 3463 5932 3463 5933 2964 5933 2969 5933 3463 5934 2969 5934 3484 5934 3484 5935 2969 5935 2968 5935 3484 5936 2968 5936 2967 5936 2962 5937 2961 5937 3471 5937 3471 5938 2961 5938 2960 5938 3471 5939 2960 5939 3464 5939 3464 5940 2960 5940 3027 5940 3464 5941 3027 5941 2965 5941 3485 5942 3477 5942 3486 5942 3486 5943 3477 5943 3479 5943 3486 5944 3479 5944 3487 5944 3487 5945 3479 5945 3475 5945 3487 5946 3475 5946 3472 5946 3472 5947 3475 5947 3474 5947 3472 5948 3474 5948 2881 5948 2881 5949 3474 5949 2882 5949 3467 5950 3485 5950 3483 5950 3483 5951 3485 5951 3486 5951 3483 5952 3486 5952 3484 5952 3484 5953 3486 5953 3487 5953 3484 5954 3487 5954 3463 5954 3463 5955 3487 5955 3472 5955 3463 5956 3472 5956 3464 5956 3464 5957 3472 5957 3473 5957 3464 5958 3473 5958 2565 5958 2565 5959 3473 5959 2566 5959 3466 5960 3488 5960 3467 5960 3467 5961 3488 5961 3489 5961 3467 5962 3489 5962 3485 5962 3485 5963 3489 5963 3490 5963 3485 5964 3490 5964 3477 5964 3477 5965 3490 5965 3491 5965 3477 5966 3491 5966 3482 5966 3492 5967 2895 5967 2896 5967 3478 5968 2919 5968 3480 5968 3480 5969 2919 5969 2873 5969 3480 5970 2873 5970 2872 5970 3493 5971 2918 5971 3494 5971 3494 5972 2918 5972 2919 5972 3494 5973 2919 5973 3495 5973 3495 5974 2919 5974 3478 5974 3495 5975 3478 5975 3496 5975 3497 5976 2905 5976 2911 5976 2911 5977 2910 5977 3497 5977 3497 5978 2910 5978 2908 5978 3497 5979 2908 5979 3498 5979 3498 5980 2908 5980 2907 5980 3498 5981 2907 5981 3499 5981 3499 5982 2907 5982 2912 5982 3499 5983 2912 5983 3500 5983 3500 5984 2912 5984 2914 5984 3500 5985 2914 5985 3493 5985 3493 5986 2914 5986 2916 5986 3493 5987 2916 5987 2918 5987 3501 5988 3502 5988 3503 5988 3504 5989 3505 5989 3501 5989 3506 5990 3507 5990 2897 5990 3508 5991 3509 5991 3504 5991 3501 5992 3503 5992 3504 5992 3504 5993 3503 5993 3510 5993 3504 5994 3510 5994 3508 5994 3509 5995 3506 5995 3504 5995 3504 5996 3506 5996 2897 5996 3504 5997 2897 5997 3511 5997 3511 5998 2897 5998 2899 5998 3511 5999 2899 5999 3512 5999 3512 6000 2899 6000 2903 6000 3512 6001 2903 6001 3513 6001 3513 6002 2903 6002 2902 6002 3513 6003 2902 6003 3514 6003 3514 6004 2902 6004 2906 6004 3514 6005 2906 6005 3515 6005 3515 6006 2906 6006 2905 6006 3515 6007 2905 6007 3516 6007 3516 6008 2905 6008 3497 6008 3517 6009 3518 6009 2896 6009 2896 6010 3518 6010 3519 6010 2896 6011 3519 6011 3492 6011 3507 6012 3520 6012 2897 6012 2897 6013 3520 6013 3521 6013 2897 6014 3521 6014 2896 6014 2896 6015 3521 6015 3522 6015 2896 6016 3522 6016 3517 6016 3523 6017 3524 6017 3489 6017 3489 6018 3524 6018 3490 6018 3525 6019 3469 6019 3468 6019 3525 6020 3468 6020 3526 6020 3526 6021 3468 6021 3481 6021 3526 6022 3481 6022 3527 6022 3527 6023 3481 6023 3482 6023 3527 6024 3482 6024 3524 6024 3524 6025 3482 6025 3491 6025 3524 6026 3491 6026 3490 6026 3528 6027 3529 6027 3466 6027 3523 6028 3489 6028 3529 6028 3529 6029 3489 6029 3488 6029 3529 6030 3488 6030 3466 6030 3466 6031 3465 6031 3528 6031 3528 6032 3465 6032 2974 6032 3528 6033 2974 6033 3530 6033 2920 6034 2993 6034 3531 6034 3001 6035 3532 6035 3000 6035 3000 6036 3532 6036 3533 6036 3000 6037 3533 6037 2999 6037 2976 6038 3534 6038 2975 6038 2975 6039 3534 6039 3530 6039 2975 6040 3530 6040 2974 6040 3535 6041 2983 6041 2981 6041 2993 6042 2995 6042 3531 6042 3531 6043 2995 6043 2996 6043 3531 6044 2996 6044 3533 6044 3533 6045 2996 6045 2998 6045 3533 6046 2998 6046 2999 6046 2981 6047 2980 6047 3535 6047 3535 6048 2980 6048 2986 6048 3535 6049 2986 6049 3536 6049 3536 6050 2986 6050 2988 6050 3536 6051 2988 6051 2989 6051 2976 6052 2978 6052 3534 6052 3534 6053 2978 6053 2985 6053 3534 6054 2985 6054 3535 6054 3535 6055 2985 6055 2984 6055 3535 6056 2984 6056 2983 6056 2989 6057 2991 6057 3536 6057 3536 6058 2991 6058 2992 6058 3536 6059 2992 6059 3531 6059 3531 6060 2992 6060 2921 6060 3531 6061 2921 6061 2920 6061 3537 6062 3538 6062 3539 6062 3532 6063 3001 6063 3540 6063 3541 6064 3542 6064 3538 6064 3538 6065 3542 6065 3543 6065 3538 6066 3543 6066 3539 6066 3532 6067 3540 6067 3544 6067 3544 6068 3540 6068 3545 6068 3544 6069 3545 6069 3541 6069 3541 6070 3545 6070 3546 6070 3541 6071 3546 6071 3542 6071 3539 6072 3547 6072 3537 6072 3537 6073 3547 6073 3548 6073 3537 6074 3548 6074 3549 6074 3549 6075 3548 6075 3550 6075 3549 6076 3550 6076 3551 6076 3551 6077 3550 6077 3552 6077 3551 6078 3552 6078 3553 6078 3550 6079 3548 6079 3554 6079 2926 6080 2939 6080 3555 6080 3048 6081 3046 6081 3045 6081 3554 6082 3556 6082 3557 6082 3051 6083 3050 6083 3558 6083 3558 6084 3050 6084 3054 6084 3558 6085 3054 6085 3556 6085 3556 6086 3054 6086 3559 6086 3556 6087 3559 6087 3557 6087 3049 6088 3048 6088 3560 6088 3560 6089 3048 6089 3045 6089 3560 6090 3045 6090 3558 6090 3558 6091 3045 6091 3053 6091 3558 6092 3053 6092 3051 6092 2580 6093 2579 6093 3561 6093 3561 6094 2579 6094 3042 6094 2583 6095 2578 6095 3562 6095 3562 6096 2578 6096 2577 6096 3562 6097 2577 6097 3563 6097 3562 6098 2947 6098 2583 6098 2583 6099 2947 6099 2946 6099 2583 6100 2946 6100 2584 6100 2584 6101 2946 6101 2945 6101 2584 6102 2945 6102 2585 6102 2943 6103 2941 6103 3563 6103 3563 6104 2941 6104 2940 6104 3563 6105 2940 6105 3562 6105 3562 6106 2940 6106 2948 6106 3562 6107 2948 6107 2947 6107 2943 6108 3563 6108 2935 6108 2935 6109 3563 6109 3564 6109 2935 6110 3564 6110 2936 6110 3555 6111 2939 6111 3564 6111 3564 6112 2939 6112 2938 6112 3564 6113 2938 6113 2936 6113 2926 6114 3555 6114 2927 6114 2927 6115 3555 6115 3565 6115 2927 6116 3565 6116 2929 6116 3540 6117 3001 6117 2934 6117 3540 6118 2934 6118 3545 6118 3545 6119 2934 6119 3546 6119 3546 6120 2934 6120 3566 6120 3546 6121 3566 6121 3542 6121 2934 6122 2933 6122 3566 6122 3566 6123 2933 6123 2931 6123 3566 6124 2931 6124 3565 6124 3565 6125 2931 6125 2930 6125 3565 6126 2930 6126 2929 6126 3552 6127 3550 6127 3567 6127 3567 6128 3550 6128 3554 6128 3567 6129 3554 6129 3568 6129 3568 6130 3554 6130 3557 6130 2577 6131 2580 6131 3563 6131 3563 6132 2580 6132 3561 6132 3563 6133 3561 6133 3564 6133 3564 6134 3561 6134 3569 6134 3564 6135 3569 6135 3555 6135 3555 6136 3569 6136 3570 6136 3555 6137 3570 6137 3565 6137 3565 6138 3570 6138 3571 6138 3565 6139 3571 6139 3566 6139 3566 6140 3571 6140 3572 6140 3566 6141 3572 6141 3542 6141 3547 6142 3539 6142 3572 6142 3572 6143 3539 6143 3543 6143 3572 6144 3543 6144 3542 6144 3042 6145 3044 6145 3561 6145 3561 6146 3044 6146 3049 6146 3561 6147 3049 6147 3569 6147 3569 6148 3049 6148 3560 6148 3569 6149 3560 6149 3570 6149 3570 6150 3560 6150 3558 6150 3570 6151 3558 6151 3571 6151 3571 6152 3558 6152 3556 6152 3571 6153 3556 6153 3572 6153 3572 6154 3556 6154 3554 6154 3572 6155 3554 6155 3547 6155 3547 6156 3554 6156 3548 6156 3573 6157 3574 6157 3039 6157 3575 6158 3576 6158 3577 6158 3578 6159 3579 6159 3034 6159 3067 6160 2502 6160 3580 6160 3067 6161 3580 6161 3034 6161 3034 6162 3580 6162 3581 6162 3034 6163 3581 6163 3578 6163 3575 6164 3577 6164 3582 6164 3039 6165 3574 6165 3040 6165 3040 6166 3574 6166 3583 6166 3040 6167 3583 6167 3061 6167 3061 6168 3583 6168 3584 6168 3061 6169 3584 6169 3060 6169 3060 6170 3584 6170 3585 6170 3060 6171 3585 6171 3058 6171 3058 6172 3585 6172 3586 6172 3058 6173 3586 6173 3056 6173 3056 6174 3586 6174 3587 6174 3056 6175 3587 6175 3588 6175 3588 6176 3557 6176 3056 6176 3056 6177 3557 6177 3559 6177 3056 6178 3559 6178 3055 6178 3055 6179 3559 6179 3054 6179 3589 6180 3035 6180 3590 6180 3590 6181 3035 6181 3034 6181 3590 6182 3034 6182 3577 6182 3577 6183 3034 6183 3579 6183 3577 6184 3579 6184 3582 6184 3039 6185 3066 6185 3573 6185 3573 6186 3066 6186 3065 6186 3573 6187 3065 6187 3591 6187 3591 6188 3065 6188 3064 6188 3591 6189 3064 6189 3592 6189 3592 6190 3064 6190 3063 6190 3592 6191 3063 6191 3593 6191 3593 6192 3063 6192 3037 6192 3593 6193 3037 6193 3594 6193 3594 6194 3037 6194 3036 6194 3594 6195 3036 6195 3589 6195 3589 6196 3036 6196 3076 6196 3589 6197 3076 6197 3035 6197 3595 6198 3596 6198 3597 6198 3597 6199 3598 6199 3599 6199 3599 6200 3598 6200 3600 6200 3599 6201 3601 6201 3602 6201 3600 6202 3603 6202 3599 6202 3599 6203 3603 6203 3604 6203 3599 6204 3604 6204 3605 6204 3597 6205 3599 6205 3595 6205 3595 6206 3599 6206 3602 6206 3595 6207 3602 6207 3606 6207 2501 6208 2518 6208 3607 6208 2502 6209 2501 6209 3580 6209 3580 6210 2501 6210 3607 6210 3580 6211 3607 6211 3581 6211 2518 6212 2519 6212 3607 6212 3607 6213 2519 6213 2514 6213 3607 6214 2514 6214 2513 6214 2513 6215 2778 6215 3607 6215 3607 6216 2778 6216 2780 6216 3607 6217 2780 6217 2781 6217 3575 6218 3582 6218 3608 6218 3608 6219 3582 6219 3579 6219 3608 6220 3579 6220 3607 6220 3607 6221 3579 6221 3578 6221 3607 6222 3578 6222 3581 6222 3609 6223 3610 6223 3608 6223 3608 6224 3610 6224 3611 6224 3608 6225 3611 6225 3612 6225 3612 6226 3613 6226 3608 6226 3608 6227 3613 6227 3614 6227 3608 6228 3614 6228 3615 6228 3615 6229 3616 6229 3608 6229 3608 6230 3616 6230 3617 6230 3608 6231 3617 6231 3575 6231 3575 6232 3617 6232 3618 6232 3575 6233 3618 6233 3576 6233 3619 6234 3620 6234 3607 6234 3607 6235 3620 6235 3621 6235 3607 6236 3621 6236 3608 6236 3608 6237 3621 6237 3622 6237 3608 6238 3622 6238 3609 6238 2787 6239 2786 6239 3623 6239 3619 6240 3607 6240 3624 6240 3624 6241 3607 6241 2781 6241 3624 6242 2781 6242 3625 6242 3625 6243 2781 6243 2782 6243 3625 6244 2782 6244 3623 6244 3623 6245 2782 6245 2784 6245 3623 6246 2784 6246 2787 6246 2786 6247 2785 6247 3623 6247 3623 6248 2785 6248 2789 6248 3623 6249 2789 6249 3626 6249 3626 6250 2789 6250 2788 6250 3627 6251 3628 6251 3629 6251 3630 6252 2788 6252 2790 6252 2864 6253 3631 6253 2394 6253 2394 6254 3631 6254 3632 6254 2394 6255 3632 6255 3633 6255 3634 6256 3635 6256 3636 6256 3634 6257 3636 6257 3637 6257 1740 6258 2394 6258 1735 6258 1735 6259 2394 6259 3633 6259 1735 6260 3633 6260 1736 6260 1736 6261 3633 6261 3638 6261 1736 6262 3638 6262 1738 6262 1738 6263 3638 6263 3639 6263 1738 6264 3639 6264 1739 6264 1739 6265 3639 6265 3637 6265 1739 6266 3637 6266 1732 6266 1732 6267 3637 6267 3636 6267 1732 6268 3636 6268 1733 6268 1733 6269 3636 6269 1729 6269 1726 6270 1718 6270 3640 6270 3640 6271 1718 6271 1731 6271 3640 6272 1731 6272 3636 6272 3636 6273 1731 6273 1730 6273 3636 6274 1730 6274 1729 6274 1725 6275 1724 6275 3641 6275 3641 6276 1724 6276 1722 6276 3641 6277 1722 6277 3642 6277 3642 6278 1722 6278 1721 6278 3642 6279 1721 6279 3643 6279 3643 6280 1721 6280 1728 6280 3643 6281 1728 6281 1727 6281 1767 6282 1766 6282 2525 6282 2525 6283 1766 6283 3644 6283 3628 6284 2523 6284 3645 6284 3645 6285 2523 6285 2527 6285 3645 6286 2527 6286 3644 6286 3644 6287 2527 6287 2526 6287 3644 6288 2526 6288 2525 6288 2528 6289 2532 6289 3627 6289 3627 6290 2532 6290 2531 6290 3627 6291 2531 6291 3628 6291 3628 6292 2531 6292 2524 6292 3628 6293 2524 6293 2523 6293 2529 6294 3646 6294 2530 6294 2530 6295 3646 6295 2808 6295 2530 6296 2808 6296 2508 6296 2800 6297 2809 6297 3647 6297 2798 6298 2797 6298 3648 6298 3648 6299 2797 6299 2807 6299 3648 6300 2807 6300 2806 6300 2806 6301 2804 6301 3648 6301 3648 6302 2804 6302 2803 6302 3648 6303 2803 6303 3647 6303 3647 6304 2803 6304 2801 6304 3647 6305 2801 6305 2800 6305 2793 6306 2792 6306 3649 6306 3649 6307 2792 6307 2798 6307 3649 6308 2798 6308 3650 6308 3650 6309 2798 6309 3648 6309 3650 6310 3648 6310 3651 6310 3652 6311 2799 6311 2796 6311 3649 6312 3653 6312 2793 6312 2793 6313 3653 6313 3652 6313 2793 6314 3652 6314 2795 6314 2795 6315 3652 6315 2796 6315 2799 6316 3652 6316 2791 6316 2791 6317 3652 6317 3654 6317 2791 6318 3654 6318 2790 6318 2790 6319 3654 6319 3655 6319 2790 6320 3655 6320 3630 6320 3656 6321 3657 6321 3658 6321 3659 6322 3660 6322 3648 6322 3648 6323 3660 6323 3661 6323 3648 6324 3661 6324 3651 6324 3662 6325 3663 6325 3664 6325 3664 6326 3663 6326 3665 6326 3664 6327 3665 6327 3656 6327 3656 6328 3665 6328 3666 6328 3656 6329 3666 6329 3657 6329 3667 6330 3668 6330 3640 6330 3640 6331 3668 6331 3669 6331 3640 6332 3669 6332 3664 6332 3664 6333 3669 6333 3670 6333 3664 6334 3670 6334 3662 6334 3635 6335 3671 6335 3636 6335 3636 6336 3671 6336 3672 6336 3636 6337 3672 6337 3640 6337 3640 6338 3672 6338 3673 6338 3640 6339 3673 6339 3667 6339 3629 6340 3628 6340 3674 6340 3674 6341 3628 6341 3645 6341 3674 6342 3645 6342 3642 6342 3642 6343 3645 6343 3644 6343 3642 6344 3644 6344 3641 6344 3641 6345 3644 6345 1766 6345 3641 6346 1766 6346 1725 6346 3658 6347 3659 6347 3656 6347 3656 6348 3659 6348 3648 6348 3656 6349 3648 6349 3675 6349 3675 6350 3648 6350 3647 6350 3675 6351 3647 6351 3646 6351 3646 6352 3647 6352 2809 6352 3646 6353 2809 6353 2808 6353 2529 6354 2528 6354 3646 6354 3646 6355 2528 6355 3627 6355 3646 6356 3627 6356 3675 6356 3675 6357 3627 6357 3629 6357 3675 6358 3629 6358 3656 6358 3656 6359 3629 6359 3674 6359 3656 6360 3674 6360 3664 6360 3664 6361 3674 6361 3642 6361 3664 6362 3642 6362 3640 6362 3640 6363 3642 6363 3643 6363 3640 6364 3643 6364 1726 6364 1726 6365 3643 6365 1727 6365 3676 6366 3677 6366 3678 6366 3679 6367 2864 6367 2863 6367 3680 6368 3681 6368 3682 6368 3682 6369 3681 6369 3678 6369 3682 6370 3678 6370 3683 6370 3683 6371 3678 6371 3677 6371 3684 6372 3685 6372 3686 6372 3676 6373 3678 6373 3687 6373 3687 6374 3678 6374 3686 6374 3687 6375 3686 6375 3688 6375 3688 6376 3686 6376 3685 6376 3688 6377 3685 6377 3689 6377 3684 6378 3686 6378 3690 6378 3690 6379 3686 6379 3428 6379 3690 6380 3428 6380 3430 6380 3434 6381 3433 6381 3678 6381 3678 6382 3433 6382 3432 6382 3678 6383 3432 6383 3686 6383 3686 6384 3432 6384 3431 6384 3686 6385 3431 6385 3428 6385 3437 6386 3436 6386 3678 6386 3678 6387 3436 6387 3435 6387 3678 6388 3435 6388 3434 6388 2865 6389 2866 6389 3425 6389 3437 6390 3678 6390 3424 6390 3424 6391 3678 6391 3681 6391 3424 6392 3681 6392 3425 6392 3680 6393 3679 6393 3681 6393 3681 6394 3679 6394 2863 6394 3681 6395 2863 6395 3425 6395 3425 6396 2863 6396 2862 6396 3425 6397 2862 6397 2865 6397 3691 6398 3692 6398 3693 6398 3694 6399 3695 6399 3696 6399 3696 6400 3695 6400 3697 6400 3696 6401 3697 6401 3698 6401 3698 6402 3697 6402 3699 6402 3698 6403 3699 6403 3693 6403 3700 6404 3698 6404 3701 6404 3701 6405 3698 6405 3693 6405 3701 6406 3693 6406 3702 6406 3702 6407 3693 6407 3692 6407 3685 6408 3684 6408 3703 6408 3703 6409 3684 6409 3690 6409 3691 6410 3693 6410 3704 6410 3704 6411 3693 6411 3703 6411 3704 6412 3703 6412 3705 6412 3705 6413 3703 6413 3690 6413 3705 6414 3690 6414 3430 6414 3699 6415 3706 6415 3693 6415 3693 6416 3706 6416 3707 6416 3693 6417 3707 6417 3703 6417 3703 6418 3707 6418 3708 6418 3703 6419 3708 6419 3685 6419 3685 6420 3708 6420 3709 6420 3685 6421 3709 6421 3689 6421 3441 6422 3446 6422 3710 6422 3711 6423 3712 6423 3713 6423 3714 6424 3715 6424 3716 6424 3717 6425 3718 6425 3710 6425 3710 6426 3718 6426 3719 6426 3710 6427 3719 6427 3720 6427 3720 6428 3719 6428 3721 6428 3720 6429 3721 6429 3714 6429 3713 6430 3712 6430 3710 6430 3710 6431 3712 6431 3722 6431 3710 6432 3722 6432 3717 6432 2860 6433 2861 6433 3711 6433 2860 6434 3711 6434 2859 6434 3711 6435 3713 6435 2859 6435 2859 6436 3713 6436 3445 6436 2859 6437 3445 6437 2858 6437 3446 6438 3447 6438 3710 6438 3710 6439 3447 6439 3448 6439 3710 6440 3448 6440 3713 6440 3713 6441 3448 6441 3449 6441 3713 6442 3449 6442 3445 6442 3714 6443 3716 6443 3720 6443 3720 6444 3716 6444 3723 6444 3720 6445 3723 6445 3724 6445 3441 6446 3710 6446 3442 6446 3442 6447 3710 6447 3720 6447 3442 6448 3720 6448 3438 6448 3438 6449 3720 6449 3724 6449 3438 6450 3724 6450 3439 6450 1406 6451 1405 6451 3725 6451 1411 6452 1410 6452 3726 6452 1591 6453 1590 6453 3727 6453 3728 6454 2861 6454 2387 6454 3728 6455 2387 6455 3729 6455 1390 6456 1389 6456 2387 6456 2387 6457 1389 6457 3730 6457 2387 6458 3730 6458 3729 6458 1389 6459 1396 6459 3730 6459 3730 6460 1396 6460 1395 6460 3730 6461 1395 6461 3731 6461 3731 6462 1395 6462 1394 6462 3731 6463 1394 6463 3732 6463 3732 6464 1394 6464 1401 6464 3732 6465 1401 6465 3733 6465 1401 6466 1400 6466 3733 6466 3733 6467 1400 6467 1397 6467 3733 6468 1397 6468 3734 6468 3735 6469 3736 6469 3737 6469 3737 6470 3736 6470 3738 6470 3738 6471 3739 6471 3725 6471 3739 6472 3740 6472 3725 6472 3725 6473 3740 6473 3741 6473 3725 6474 3741 6474 3734 6474 3742 6475 3743 6475 3744 6475 3744 6476 3743 6476 3745 6476 3744 6477 3745 6477 3737 6477 3737 6478 3745 6478 3746 6478 3737 6479 3746 6479 3735 6479 3747 6480 3748 6480 3749 6480 3749 6481 3748 6481 3750 6481 3749 6482 3750 6482 3744 6482 3744 6483 3750 6483 3751 6483 3744 6484 3751 6484 3742 6484 3752 6485 3753 6485 3754 6485 3752 6486 3754 6486 3749 6486 3749 6487 3754 6487 3755 6487 3749 6488 3755 6488 3747 6488 3756 6489 3757 6489 3752 6489 3752 6490 3757 6490 3758 6490 3752 6491 3758 6491 3753 6491 2407 6492 2409 6492 3759 6492 3759 6493 3760 6493 2407 6493 2407 6494 3760 6494 3761 6494 2407 6495 3761 6495 2397 6495 2397 6496 3761 6496 3762 6496 2399 6497 2398 6497 3752 6497 3763 6498 2419 6498 3752 6498 3752 6499 2419 6499 2418 6499 3752 6500 2418 6500 2399 6500 2398 6501 2426 6501 3752 6501 3752 6502 2426 6502 2425 6502 3752 6503 2425 6503 3756 6503 3756 6504 2425 6504 2424 6504 3756 6505 2424 6505 3764 6505 3764 6506 2424 6506 2423 6506 3764 6507 2423 6507 3762 6507 3762 6508 2423 6508 2395 6508 3762 6509 2395 6509 2397 6509 3765 6510 2421 6510 3763 6510 3763 6511 2421 6511 2420 6511 3763 6512 2420 6512 2419 6512 1587 6513 2401 6513 3765 6513 3765 6514 2401 6514 2422 6514 3765 6515 2422 6515 2421 6515 1584 6516 1589 6516 3765 6516 3765 6517 1589 6517 1588 6517 3765 6518 1588 6518 1587 6518 3766 6519 1592 6519 1591 6519 3767 6520 1594 6520 1593 6520 1594 6521 3767 6521 1595 6521 1595 6522 3767 6522 3768 6522 1595 6523 3768 6523 1596 6523 1414 6524 1418 6524 3768 6524 3769 6525 1416 6525 3768 6525 3768 6526 1416 6526 1415 6526 3768 6527 1415 6527 1414 6527 1418 6528 1170 6528 3768 6528 3768 6529 1170 6529 1582 6529 3768 6530 1582 6530 1596 6530 3726 6531 1413 6531 3770 6531 3770 6532 1413 6532 1412 6532 3770 6533 1412 6533 1417 6533 1410 6534 1408 6534 3726 6534 3726 6535 1408 6535 1407 6535 3726 6536 1407 6536 1413 6536 3738 6537 3725 6537 3737 6537 3737 6538 3725 6538 1405 6538 3737 6539 1405 6539 1403 6539 3734 6540 1397 6540 3725 6540 3725 6541 1397 6541 1398 6541 3725 6542 1398 6542 1406 6542 3767 6543 3771 6543 3768 6543 3768 6544 3771 6544 3770 6544 3768 6545 3770 6545 3769 6545 3769 6546 3770 6546 1417 6546 3769 6547 1417 6547 1416 6547 1591 6548 3727 6548 3766 6548 3766 6549 3727 6549 3772 6549 3766 6550 3772 6550 3773 6550 3749 6551 3773 6551 3752 6551 3752 6552 3773 6552 3772 6552 3752 6553 3772 6553 3763 6553 3763 6554 3772 6554 3727 6554 3763 6555 3727 6555 3765 6555 3765 6556 3727 6556 1590 6556 3765 6557 1590 6557 1584 6557 1403 6558 1411 6558 3737 6558 3737 6559 1411 6559 3726 6559 3737 6560 3726 6560 3744 6560 3744 6561 3726 6561 3770 6561 3744 6562 3770 6562 3749 6562 3749 6563 3770 6563 3771 6563 3749 6564 3771 6564 3773 6564 3773 6565 3771 6565 3767 6565 3773 6566 3767 6566 3766 6566 3766 6567 3767 6567 1593 6567 3766 6568 1593 6568 1592 6568 3774 6569 3775 6569 3776 6569 3775 6570 3777 6570 2415 6570 2415 6571 3777 6571 2410 6571 3778 6572 2409 6572 2408 6572 2408 6573 2406 6573 3778 6573 3778 6574 2406 6574 2405 6574 3778 6575 2405 6575 2404 6575 3777 6576 3779 6576 2410 6576 2410 6577 3779 6577 3780 6577 2410 6578 3780 6578 2411 6578 2411 6579 3780 6579 3778 6579 2411 6580 3778 6580 2412 6580 2412 6581 3778 6581 2404 6581 3774 6582 3776 6582 3781 6582 3781 6583 3776 6583 3782 6583 3782 6584 3776 6584 3783 6584 3782 6585 3783 6585 3784 6585 3785 6586 3786 6586 3783 6586 3783 6587 3786 6587 3787 6587 3787 6588 3788 6588 3783 6588 3783 6589 3788 6589 3789 6589 3783 6590 3789 6590 3784 6590 2490 6591 2489 6591 3785 6591 2490 6592 3785 6592 2491 6592 2491 6593 3785 6593 3783 6593 2491 6594 3783 6594 2487 6594 2489 6595 2483 6595 3785 6595 3785 6596 2483 6596 2485 6596 3785 6597 2485 6597 2486 6597 3776 6598 2499 6598 2498 6598 3776 6599 2498 6599 3783 6599 3783 6600 2498 6600 2488 6600 3783 6601 2488 6601 2487 6601 3775 6602 2415 6602 3776 6602 3776 6603 2415 6603 2414 6603 3776 6604 2414 6604 2402 6604 2402 6605 1878 6605 3776 6605 3776 6606 1878 6606 1872 6606 3776 6607 1872 6607 1874 6607 1874 6608 1875 6608 3776 6608 3776 6609 1875 6609 2500 6609 3776 6610 2500 6610 2499 6610 1553 6611 1555 6611 2478 6611 2478 6612 1555 6612 1523 6612 3790 6613 3791 6613 2429 6613 2429 6614 3791 6614 3792 6614 2429 6615 3792 6615 3793 6615 3793 6616 3794 6616 2429 6616 2429 6617 3794 6617 2478 6617 2429 6618 2478 6618 1522 6618 1522 6619 2478 6619 1523 6619 3795 6620 3796 6620 2445 6620 2430 6621 2431 6621 2428 6621 3790 6622 2429 6622 3797 6622 3797 6623 2429 6623 2430 6623 3797 6624 2430 6624 3798 6624 2433 6625 2432 6625 3798 6625 2430 6626 2428 6626 3798 6626 3798 6627 2428 6627 2427 6627 3798 6628 2427 6628 2433 6628 2444 6629 2443 6629 2442 6629 2444 6630 3796 6630 2435 6630 2435 6631 3796 6631 2436 6631 2444 6632 2442 6632 3796 6632 3796 6633 2442 6633 2441 6633 3796 6634 2441 6634 2445 6634 2447 6635 3799 6635 3800 6635 3795 6636 2445 6636 3800 6636 3800 6637 2445 6637 2446 6637 3800 6638 2446 6638 2447 6638 2432 6639 2434 6639 3798 6639 3798 6640 2434 6640 2438 6640 3798 6641 2438 6641 3801 6641 3801 6642 2438 6642 2439 6642 3801 6643 2439 6643 3802 6643 3803 6644 3804 6644 2440 6644 2440 6645 3804 6645 3805 6645 2440 6646 3805 6646 2439 6646 2439 6647 3805 6647 3806 6647 2439 6648 3806 6648 3802 6648 3803 6649 2440 6649 3807 6649 3807 6650 2440 6650 2437 6650 3807 6651 2437 6651 3808 6651 3796 6652 3809 6652 2436 6652 2436 6653 3809 6653 3810 6653 2436 6654 3810 6654 2437 6654 2437 6655 3810 6655 3811 6655 2437 6656 3811 6656 3808 6656 1501 6657 1500 6657 2474 6657 2474 6658 1500 6658 1506 6658 2474 6659 1506 6659 1504 6659 1501 6660 2474 6660 2447 6660 2447 6661 2474 6661 3812 6661 2447 6662 3812 6662 3813 6662 3813 6663 3814 6663 2447 6663 2447 6664 3814 6664 3815 6664 2447 6665 3815 6665 3799 6665 3816 6666 3817 6666 3818 6666 3819 6667 3815 6667 3814 6667 3820 6668 3821 6668 3822 6668 3822 6669 3821 6669 3823 6669 3822 6670 3823 6670 3819 6670 3824 6671 3825 6671 3826 6671 3826 6672 3825 6672 3827 6672 3826 6673 3827 6673 3820 6673 3820 6674 3827 6674 3828 6674 3820 6675 3828 6675 3821 6675 3829 6676 3830 6676 3831 6676 3831 6677 3830 6677 3832 6677 3833 6678 3834 6678 3832 6678 3832 6679 3834 6679 3835 6679 3832 6680 3835 6680 3831 6680 3836 6681 3837 6681 3838 6681 3838 6682 3837 6682 3839 6682 3840 6683 3841 6683 3842 6683 3842 6684 3841 6684 3843 6684 3842 6685 3843 6685 3844 6685 3844 6686 3843 6686 3838 6686 3844 6687 3838 6687 3818 6687 3818 6688 3838 6688 3839 6688 3818 6689 3839 6689 3816 6689 3836 6690 3838 6690 3845 6690 3845 6691 3838 6691 2455 6691 3845 6692 2455 6692 2460 6692 3819 6693 3814 6693 3822 6693 3822 6694 3814 6694 3813 6694 3822 6695 3813 6695 3812 6695 2470 6696 3826 6696 2471 6696 2471 6697 3826 6697 3820 6697 2471 6698 3820 6698 2472 6698 2472 6699 3820 6699 3822 6699 2472 6700 3822 6700 2473 6700 2473 6701 3822 6701 3812 6701 2473 6702 3812 6702 2474 6702 2470 6703 2469 6703 3826 6703 3826 6704 2469 6704 3830 6704 3826 6705 3830 6705 3824 6705 3824 6706 3830 6706 3829 6706 2466 6707 3832 6707 2467 6707 2467 6708 3832 6708 3830 6708 2467 6709 3830 6709 2468 6709 2468 6710 3830 6710 2469 6710 2466 6711 2465 6711 3832 6711 3832 6712 2465 6712 3841 6712 3832 6713 3841 6713 3833 6713 3833 6714 3841 6714 3840 6714 2465 6715 2464 6715 3841 6715 3841 6716 2464 6716 2463 6716 3841 6717 2463 6717 3843 6717 3843 6718 2463 6718 2462 6718 3843 6719 2462 6719 3838 6719 3838 6720 2462 6720 2461 6720 3838 6721 2461 6721 2455 6721 3143 6722 3142 6722 3846 6722 3847 6723 3147 6723 3146 6723 3847 6724 3146 6724 3848 6724 3848 6725 3146 6725 3145 6725 3848 6726 3145 6726 3849 6726 3849 6727 3145 6727 3149 6727 3849 6728 3149 6728 3150 6728 3846 6729 3142 6729 3850 6729 3142 6730 3141 6730 3850 6730 3850 6731 3141 6731 3140 6731 3850 6732 3140 6732 3851 6732 3851 6733 3140 6733 3139 6733 3851 6734 3139 6734 3847 6734 3847 6735 3139 6735 3148 6735 3847 6736 3148 6736 3147 6736 3136 6737 3138 6737 3846 6737 3138 6738 3137 6738 3846 6738 3846 6739 3137 6739 3144 6739 3846 6740 3144 6740 3143 6740 3852 6741 3853 6741 3854 6741 3854 6742 3853 6742 3855 6742 3854 6743 3855 6743 3817 6743 3856 6744 3857 6744 3852 6744 3852 6745 3857 6745 3858 6745 3852 6746 3858 6746 3853 6746 3859 6747 3860 6747 3861 6747 3861 6748 3860 6748 3862 6748 3861 6749 3862 6749 3856 6749 3856 6750 3862 6750 3863 6750 3856 6751 3863 6751 3857 6751 3864 6752 3865 6752 3866 6752 3866 6753 3865 6753 3859 6753 3866 6754 3859 6754 3867 6754 3867 6755 3859 6755 3861 6755 3816 6756 3839 6756 3846 6756 3839 6757 3837 6757 3846 6757 3846 6758 3837 6758 3836 6758 3846 6759 3836 6759 3136 6759 3136 6760 3836 6760 3845 6760 3136 6761 3845 6761 2460 6761 3817 6762 3816 6762 3854 6762 3854 6763 3816 6763 3846 6763 3854 6764 3846 6764 3852 6764 3852 6765 3846 6765 3850 6765 3852 6766 3850 6766 3856 6766 3856 6767 3850 6767 3851 6767 3856 6768 3851 6768 3861 6768 3861 6769 3851 6769 3847 6769 3861 6770 3847 6770 3867 6770 3867 6771 3847 6771 3848 6771 3867 6772 3848 6772 3868 6772 3868 6773 3848 6773 3849 6773 3869 6774 3864 6774 3870 6774 3870 6775 3864 6775 3866 6775 3870 6776 3866 6776 3871 6776 3871 6777 3866 6777 3867 6777 3871 6778 3867 6778 3872 6778 3872 6779 3867 6779 3868 6779 3873 6780 3868 6780 3874 6780 3874 6781 3868 6781 3849 6781 3874 6782 3849 6782 3875 6782 3875 6783 3849 6783 3876 6783 3876 6784 3849 6784 3150 6784 3876 6785 3150 6785 3877 6785 3878 6786 3869 6786 3879 6786 3879 6787 3869 6787 3870 6787 3873 6788 3880 6788 3868 6788 3868 6789 3880 6789 3881 6789 3868 6790 3881 6790 3872 6790 3872 6791 3881 6791 3882 6791 3872 6792 3882 6792 3871 6792 3871 6793 3882 6793 3883 6793 3871 6794 3883 6794 3870 6794 3870 6795 3883 6795 3884 6795 3870 6796 3884 6796 3879 6796 3885 6797 2486 6797 2484 6797 3886 6798 3887 6798 3888 6798 3888 6799 3887 6799 3885 6799 3888 6800 3889 6800 3890 6800 3891 6801 3886 6801 3892 6801 3892 6802 3886 6802 3888 6802 3892 6803 3888 6803 3893 6803 3893 6804 3888 6804 3890 6804 3894 6805 3895 6805 3889 6805 3889 6806 3895 6806 3896 6806 3889 6807 3896 6807 3890 6807 3897 6808 3898 6808 3894 6808 3894 6809 3898 6809 3899 6809 3894 6810 3899 6810 3895 6810 3900 6811 3901 6811 3897 6811 3897 6812 3901 6812 3902 6812 3897 6813 3902 6813 3898 6813 3903 6814 3904 6814 3905 6814 3905 6815 3904 6815 3906 6815 3905 6816 3906 6816 3907 6816 3907 6817 3906 6817 3908 6817 3794 6818 3793 6818 3909 6818 3909 6819 3793 6819 3792 6819 3910 6820 3911 6820 3912 6820 3912 6821 3911 6821 3909 6821 3912 6822 3909 6822 3913 6822 3913 6823 3909 6823 3792 6823 3913 6824 3792 6824 3791 6824 3885 6825 2484 6825 3888 6825 3888 6826 2484 6826 2492 6826 3888 6827 2492 6827 3889 6827 2492 6828 2493 6828 3889 6828 3889 6829 2493 6829 2494 6829 3889 6830 2494 6830 3894 6830 3894 6831 2494 6831 2495 6831 3894 6832 2495 6832 3897 6832 3897 6833 2495 6833 2496 6833 2496 6834 2497 6834 3897 6834 3897 6835 2497 6835 3904 6835 3897 6836 3904 6836 3900 6836 3900 6837 3904 6837 3903 6837 2481 6838 3906 6838 2480 6838 2480 6839 3906 6839 3904 6839 2480 6840 3904 6840 2479 6840 2479 6841 3904 6841 2497 6841 2481 6842 2482 6842 3906 6842 3906 6843 2482 6843 3911 6843 3906 6844 3911 6844 3908 6844 3908 6845 3911 6845 3910 6845 2478 6846 3794 6846 2477 6846 2477 6847 3794 6847 3909 6847 2477 6848 3909 6848 2476 6848 2476 6849 3909 6849 3911 6849 2476 6850 3911 6850 2475 6850 2475 6851 3911 6851 2482 6851 3914 6852 3915 6852 3916 6852 3916 6853 3915 6853 3917 6853 3916 6854 3917 6854 3918 6854 3919 6855 3920 6855 3921 6855 3915 6856 3922 6856 3917 6856 3917 6857 3922 6857 3919 6857 3917 6858 3919 6858 3923 6858 3923 6859 3919 6859 3921 6859 3924 6860 3925 6860 3926 6860 3926 6861 3925 6861 3927 6861 3926 6862 3927 6862 3928 6862 3928 6863 3927 6863 3400 6863 3914 6864 3929 6864 3915 6864 3915 6865 3929 6865 3930 6865 3915 6866 3930 6866 3925 6866 3925 6867 3930 6867 3931 6867 3925 6868 3931 6868 3927 6868 3932 6869 3933 6869 3924 6869 3924 6870 3933 6870 3934 6870 3924 6871 3934 6871 3925 6871 3925 6872 3934 6872 3935 6872 3925 6873 3935 6873 3915 6873 3915 6874 3935 6874 3936 6874 3915 6875 3936 6875 3922 6875 3937 6876 3938 6876 3939 6876 3940 6877 3941 6877 3932 6877 3942 6878 3943 6878 3944 6878 3944 6879 3943 6879 3945 6879 3944 6880 3945 6880 3940 6880 3940 6881 3945 6881 3946 6881 3940 6882 3946 6882 3941 6882 3939 6883 3938 6883 3944 6883 3944 6884 3938 6884 3947 6884 3944 6885 3947 6885 3942 6885 2775 6886 2776 6886 3937 6886 3409 6887 3939 6887 3408 6887 3408 6888 3939 6888 3407 6888 2775 6889 3937 6889 2774 6889 2774 6890 3937 6890 3939 6890 2774 6891 3939 6891 2772 6891 2772 6892 3939 6892 3409 6892 2772 6893 3409 6893 2771 6893 3407 6894 3939 6894 3406 6894 3406 6895 3939 6895 3944 6895 3406 6896 3944 6896 3405 6896 3397 6897 3396 6897 3944 6897 3944 6898 3396 6898 3404 6898 3944 6899 3404 6899 3405 6899 3932 6900 3924 6900 3940 6900 3940 6901 3924 6901 3926 6901 3940 6902 3926 6902 3928 6902 3397 6903 3944 6903 3402 6903 3402 6904 3944 6904 3940 6904 3402 6905 3940 6905 3399 6905 3399 6906 3940 6906 3928 6906 3399 6907 3928 6907 3400 6907 3948 6908 3949 6908 3950 6908 1061 6909 1059 6909 3951 6909 3952 6910 3953 6910 3954 6910 1041 6911 1040 6911 3955 6911 3956 6912 3957 6912 2293 6912 2293 6913 3957 6913 3958 6913 2293 6914 3958 6914 2776 6914 3956 6915 2293 6915 3955 6915 3955 6916 2293 6916 1042 6916 3955 6917 1042 6917 1041 6917 1040 6918 1039 6918 3955 6918 3955 6919 1039 6919 1038 6919 3955 6920 1038 6920 3959 6920 1038 6921 1037 6921 3959 6921 3959 6922 1037 6922 1036 6922 3959 6923 1036 6923 3960 6923 3960 6924 1036 6924 1047 6924 3960 6925 1047 6925 3961 6925 3961 6926 1047 6926 1046 6926 3961 6927 1046 6927 3962 6927 3963 6928 3964 6928 3965 6928 3965 6929 3966 6929 3963 6929 3963 6930 3966 6930 3967 6930 3963 6931 3967 6931 3954 6931 3954 6932 3967 6932 3968 6932 3954 6933 3968 6933 3952 6933 3964 6934 3963 6934 3969 6934 3969 6935 3963 6935 3970 6935 3969 6936 3970 6936 3971 6936 3972 6937 3973 6937 3970 6937 3970 6938 3973 6938 3974 6938 3970 6939 3974 6939 3971 6939 3975 6940 3976 6940 3977 6940 3978 6941 3979 6941 3950 6941 3950 6942 3979 6942 3975 6942 3976 6943 3980 6943 3977 6943 3977 6944 3980 6944 3981 6944 3977 6945 3981 6945 3970 6945 3970 6946 3981 6946 3982 6946 3970 6947 3982 6947 3972 6947 3370 6948 3983 6948 3984 6948 3370 6949 3984 6949 3371 6949 3984 6950 3985 6950 3371 6950 3371 6951 3985 6951 3986 6951 3371 6952 3986 6952 3950 6952 3950 6953 3986 6953 3987 6953 3950 6954 3987 6954 3978 6954 3988 6955 3376 6955 3989 6955 3989 6956 3376 6956 3375 6956 3989 6957 3375 6957 3378 6957 3370 6958 3368 6958 3983 6958 3983 6959 3368 6959 3367 6959 3983 6960 3367 6960 3988 6960 3988 6961 3367 6961 3377 6961 3988 6962 3377 6962 3376 6962 3949 6963 3374 6963 3950 6963 3950 6964 3374 6964 3373 6964 3950 6965 3373 6965 3372 6965 3372 6966 3365 6966 3950 6966 3950 6967 3365 6967 3364 6967 3950 6968 3364 6968 3371 6968 3363 6969 3360 6969 3949 6969 3949 6970 3360 6970 3359 6970 3949 6971 3359 6971 3374 6971 2537 6972 3362 6972 2538 6972 2538 6973 3362 6973 3990 6973 2538 6974 3990 6974 2539 6974 2539 6975 3990 6975 2534 6975 2534 6976 3990 6976 2540 6976 2540 6977 3990 6977 3991 6977 2540 6978 3991 6978 2541 6978 2541 6979 3991 6979 3992 6979 2541 6980 3992 6980 2542 6980 2542 6981 3992 6981 2543 6981 2543 6982 3992 6982 3993 6982 2543 6983 3993 6983 2544 6983 2544 6984 3993 6984 2545 6984 2545 6985 3993 6985 3994 6985 2545 6986 3994 6986 2546 6986 3995 6987 1071 6987 3994 6987 3994 6988 1071 6988 1069 6988 3994 6989 1069 6989 1075 6989 1075 6990 1076 6990 3994 6990 3994 6991 1076 6991 2522 6991 3994 6992 2522 6992 2546 6992 3996 6993 3951 6993 1067 6993 1067 6994 1066 6994 3996 6994 3996 6995 1066 6995 1065 6995 3996 6996 1065 6996 1072 6996 1059 6997 1057 6997 3951 6997 3951 6998 1057 6998 1056 6998 3951 6999 1056 6999 1067 6999 1054 7000 1052 7000 3963 7000 1054 7001 3963 7001 1055 7001 1052 7002 1051 7002 3963 7002 3963 7003 1051 7003 1063 7003 3963 7004 1063 7004 1062 7004 1044 7005 3954 7005 1046 7005 1046 7006 3954 7006 3953 7006 1046 7007 3953 7007 3962 7007 1044 7008 1043 7008 3954 7008 3954 7009 1043 7009 1048 7009 3954 7010 1048 7010 3963 7010 3963 7011 1048 7011 1050 7011 3963 7012 1050 7012 1055 7012 3975 7013 3977 7013 3950 7013 3950 7014 3977 7014 3997 7014 3950 7015 3997 7015 3948 7015 1062 7016 1061 7016 3963 7016 3963 7017 1061 7017 3951 7017 3963 7018 3951 7018 3970 7018 3970 7019 3951 7019 3996 7019 3970 7020 3996 7020 3977 7020 3977 7021 3996 7021 3998 7021 3977 7022 3998 7022 3997 7022 3362 7023 3363 7023 3990 7023 3990 7024 3363 7024 3949 7024 3990 7025 3949 7025 3991 7025 3991 7026 3949 7026 3948 7026 3991 7027 3948 7027 3992 7027 3992 7028 3948 7028 3997 7028 3992 7029 3997 7029 3993 7029 3993 7030 3997 7030 3998 7030 3993 7031 3998 7031 3994 7031 3994 7032 3998 7032 3996 7032 3994 7033 3996 7033 3995 7033 3995 7034 3996 7034 1072 7034 3995 7035 1072 7035 1071 7035 3999 7036 4000 7036 3880 7036 4001 7037 3883 7037 3882 7037 3883 7038 4001 7038 3884 7038 3884 7039 4001 7039 4002 7039 3884 7040 4002 7040 3879 7040 3879 7041 4002 7041 4003 7041 3879 7042 4003 7042 3878 7042 3880 7043 4004 7043 4005 7043 4001 7044 3880 7044 4005 7044 4006 7045 4004 7045 3880 7045 3882 7046 3881 7046 4001 7046 4001 7047 3881 7047 3880 7047 4000 7048 4006 7048 3880 7048 4007 7049 4008 7049 4009 7049 4010 7050 4011 7050 4012 7050 4012 7051 4011 7051 4009 7051 4010 7052 4013 7052 4011 7052 4011 7053 4013 7053 4014 7053 4011 7054 4014 7054 4015 7054 4015 7055 4016 7055 4011 7055 4011 7056 4016 7056 4017 7056 4011 7057 4017 7057 4009 7057 4009 7058 4017 7058 4018 7058 4019 7059 4020 7059 4021 7059 4018 7060 4022 7060 4009 7060 4009 7061 4022 7061 4023 7061 4009 7062 4023 7062 4019 7062 4019 7063 4021 7063 4009 7063 4009 7064 4021 7064 4024 7064 4009 7065 4024 7065 4007 7065 4025 7066 731 7066 4026 7066 4026 7067 731 7067 730 7067 4026 7068 730 7068 4027 7068 728 7069 732 7069 4028 7069 4027 7070 730 7070 4028 7070 4028 7071 730 7071 729 7071 4028 7072 729 7072 728 7072 4029 7073 4030 7073 4025 7073 4025 7074 4030 7074 4031 7074 4025 7075 4031 7075 731 7075 731 7076 4031 7076 4032 7076 731 7077 4032 7077 715 7077 4028 7078 732 7078 502 7078 4029 7079 4025 7079 4033 7079 4033 7080 4025 7080 4034 7080 4034 7081 501 7081 4035 7081 4035 7082 501 7082 500 7082 4035 7083 500 7083 499 7083 4034 7084 4025 7084 501 7084 501 7085 4025 7085 4026 7085 501 7086 4026 7086 502 7086 502 7087 4026 7087 4027 7087 502 7088 4027 7088 4028 7088 4036 7089 4037 7089 4038 7089 659 7090 658 7090 4038 7090 4039 7091 4040 7091 4041 7091 4002 7092 4001 7092 4042 7092 4042 7093 4001 7093 4005 7093 4042 7094 4005 7094 4043 7094 4002 7095 4042 7095 4003 7095 4003 7096 4042 7096 4044 7096 4003 7097 4044 7097 3878 7097 4045 7098 4046 7098 4047 7098 4047 7099 4046 7099 4048 7099 4047 7100 4048 7100 4049 7100 4049 7101 4048 7101 4050 7101 4049 7102 4050 7102 4051 7102 4041 7103 4040 7103 4052 7103 4040 7104 4053 7104 4052 7104 4052 7105 4053 7105 4054 7105 4052 7106 4054 7106 4050 7106 4050 7107 4054 7107 4055 7107 4050 7108 4055 7108 4051 7108 4039 7109 4056 7109 4057 7109 4057 7110 4056 7110 4058 7110 4057 7111 4058 7111 4059 7111 4060 7112 4061 7112 4059 7112 4062 7113 4061 7113 4063 7113 4063 7114 4061 7114 4060 7114 4063 7115 4060 7115 4064 7115 4060 7116 720 7116 719 7116 4064 7117 4060 7117 4065 7117 4065 7118 4060 7118 719 7118 4065 7119 719 7119 718 7119 4059 7120 4058 7120 4060 7120 4060 7121 4058 7121 721 7121 4060 7122 721 7122 720 7122 638 7123 637 7123 4056 7123 4056 7124 637 7124 707 7124 4056 7125 707 7125 4058 7125 4058 7126 707 7126 726 7126 4058 7127 726 7127 721 7127 4039 7128 4041 7128 4056 7128 4056 7129 4041 7129 639 7129 4056 7130 639 7130 638 7130 640 7131 4066 7131 636 7131 636 7132 4066 7132 4067 7132 636 7133 4067 7133 634 7133 634 7134 4067 7134 645 7134 645 7135 4067 7135 643 7135 643 7136 4067 7136 4068 7136 643 7137 4068 7137 646 7137 4036 7138 653 7138 4068 7138 4068 7139 653 7139 652 7139 4068 7140 652 7140 646 7140 654 7141 4069 7141 651 7141 651 7142 4069 7142 655 7142 4070 7143 660 7143 659 7143 4071 7144 4072 7144 4070 7144 4070 7145 4072 7145 4073 7145 4073 7146 4074 7146 675 7146 675 7147 4074 7147 4075 7147 675 7148 4075 7148 674 7148 4073 7149 675 7149 4070 7149 4070 7150 675 7150 684 7150 4070 7151 684 7151 660 7151 658 7152 655 7152 4038 7152 4038 7153 655 7153 4069 7153 4038 7154 4069 7154 4036 7154 4036 7155 4069 7155 654 7155 4036 7156 654 7156 653 7156 4076 7157 4077 7157 4078 7157 4078 7158 4077 7158 4079 7158 4078 7159 4079 7159 4070 7159 4070 7160 4079 7160 4080 7160 4070 7161 4080 7161 4071 7161 4004 7162 4046 7162 4005 7162 4005 7163 4046 7163 4045 7163 4005 7164 4045 7164 4043 7164 4006 7165 4000 7165 4037 7165 4037 7166 4000 7166 3999 7166 4037 7167 3999 7167 4081 7167 659 7168 4038 7168 4070 7168 4070 7169 4038 7169 4037 7169 4070 7170 4037 7170 4078 7170 4078 7171 4037 7171 4081 7171 4078 7172 4081 7172 4076 7172 4004 7173 4006 7173 4046 7173 4046 7174 4006 7174 4037 7174 4046 7175 4037 7175 4048 7175 4048 7176 4037 7176 4036 7176 4048 7177 4036 7177 4050 7177 4050 7178 4036 7178 4068 7178 4050 7179 4068 7179 4052 7179 4052 7180 4068 7180 4067 7180 4052 7181 4067 7181 4041 7181 4041 7182 4067 7182 4066 7182 4041 7183 4066 7183 639 7183 639 7184 4066 7184 640 7184 717 7185 4012 7185 718 7185 718 7186 4012 7186 4065 7186 4012 7187 4009 7187 4062 7187 4012 7188 4062 7188 4065 7188 4065 7189 4062 7189 4063 7189 4065 7190 4063 7190 4064 7190 4082 7191 4007 7191 495 7191 495 7192 4007 7192 494 7192 4008 7193 4007 7193 4083 7193 4083 7194 4007 7194 4082 7194 4083 7195 4082 7195 4084 7195 4084 7196 4082 7196 4085 7196 4086 7197 4087 7197 4088 7197 546 7198 4089 7198 547 7198 542 7199 541 7199 4090 7199 4091 7200 541 7200 549 7200 4091 7201 549 7201 4092 7201 4092 7202 549 7202 574 7202 4092 7203 574 7203 573 7203 4093 7204 544 7204 542 7204 4089 7205 546 7205 4093 7205 4093 7206 546 7206 545 7206 4093 7207 545 7207 544 7207 548 7208 4094 7208 531 7208 531 7209 4094 7209 4095 7209 536 7210 535 7210 4096 7210 4096 7211 535 7211 534 7211 4096 7212 534 7212 4095 7212 4095 7213 534 7213 532 7213 4095 7214 532 7214 531 7214 518 7215 517 7215 4097 7215 4097 7216 517 7216 516 7216 4097 7217 516 7217 4096 7217 4096 7218 516 7218 515 7218 4096 7219 515 7219 536 7219 506 7220 507 7220 4098 7220 4098 7221 507 7221 521 7221 4098 7222 521 7222 4099 7222 506 7223 4098 7223 504 7223 504 7224 4098 7224 4100 7224 504 7225 4100 7225 493 7225 493 7226 4100 7226 4082 7226 493 7227 4082 7227 495 7227 4101 7228 4083 7228 4084 7228 4101 7229 4084 7229 4100 7229 4100 7230 4084 7230 4085 7230 4100 7231 4085 7231 4082 7231 4102 7232 4103 7232 4104 7232 4104 7233 4105 7233 4102 7233 4102 7234 4105 7234 4106 7234 4102 7235 4106 7235 4099 7235 4099 7236 4106 7236 4107 7236 4099 7237 4107 7237 4098 7237 4098 7238 4107 7238 4108 7238 4098 7239 4108 7239 4100 7239 4100 7240 4108 7240 4109 7240 4100 7241 4109 7241 4101 7241 4088 7242 4087 7242 4110 7242 4087 7243 4111 7243 4110 7243 4110 7244 4111 7244 4112 7244 4110 7245 4112 7245 4103 7245 4103 7246 4112 7246 4113 7246 4103 7247 4113 7247 4104 7247 4114 7248 4115 7248 4116 7248 4116 7249 4115 7249 4117 7249 4116 7250 4117 7250 4118 7250 4086 7251 4088 7251 4119 7251 4119 7252 4088 7252 4116 7252 4119 7253 4116 7253 4120 7253 4120 7254 4116 7254 4118 7254 4120 7255 4118 7255 4121 7255 541 7256 4091 7256 4090 7256 4090 7257 4091 7257 4122 7257 4090 7258 4122 7258 4123 7258 4123 7259 4124 7259 4090 7259 4090 7260 4124 7260 4125 7260 4090 7261 4125 7261 4126 7261 4093 7262 4127 7262 4089 7262 4089 7263 4127 7263 4094 7263 4089 7264 4094 7264 547 7264 547 7265 4094 7265 548 7265 4125 7266 4128 7266 4126 7266 4126 7267 4128 7267 4129 7267 4126 7268 4129 7268 4130 7268 542 7269 4090 7269 4093 7269 4093 7270 4090 7270 4126 7270 4093 7271 4126 7271 4127 7271 4127 7272 4126 7272 4130 7272 4127 7273 4130 7273 4131 7273 4131 7274 4132 7274 4127 7274 4127 7275 4132 7275 4133 7275 4127 7276 4133 7276 4134 7276 521 7277 522 7277 4099 7277 4099 7278 522 7278 518 7278 4099 7279 518 7279 4102 7279 4102 7280 518 7280 4097 7280 4102 7281 4097 7281 4103 7281 4103 7282 4097 7282 4096 7282 4103 7283 4096 7283 4110 7283 4110 7284 4096 7284 4095 7284 4110 7285 4095 7285 4088 7285 4088 7286 4095 7286 4094 7286 4088 7287 4094 7287 4116 7287 4116 7288 4094 7288 4127 7288 4116 7289 4127 7289 4114 7289 4114 7290 4127 7290 4134 7290 3913 7291 3791 7291 3790 7291 4061 7292 4062 7292 4009 7292 3853 7293 3799 7293 3855 7293 3855 7294 3799 7294 3817 7294 4135 7295 4136 7295 3790 7295 3790 7296 4136 7296 4137 7296 3790 7297 4137 7297 4138 7297 3853 7298 3858 7298 3799 7298 3799 7299 3858 7299 3857 7299 3799 7300 3857 7300 3863 7300 3863 7301 3862 7301 3799 7301 3799 7302 3862 7302 3860 7302 3799 7303 3860 7303 3859 7303 4138 7304 4139 7304 3790 7304 3790 7305 4139 7305 3891 7305 3790 7306 3891 7306 3892 7306 3913 7307 3790 7307 3912 7307 3802 7308 3806 7308 4009 7308 4140 7309 4141 7309 4008 7309 4008 7310 4141 7310 4142 7310 4008 7311 4142 7311 4143 7311 4143 7312 4144 7312 4008 7312 4008 7313 4144 7313 4145 7313 4008 7314 4145 7314 4135 7314 3815 7315 3819 7315 3799 7315 3799 7316 3819 7316 3823 7316 3799 7317 3823 7317 3817 7317 3817 7318 3823 7318 3821 7318 3817 7319 3821 7319 3828 7319 3802 7320 4009 7320 3801 7320 3796 7321 3795 7321 4009 7321 4009 7322 3795 7322 3800 7322 4009 7323 3800 7323 3799 7323 3828 7324 3827 7324 3817 7324 3817 7325 3827 7325 3825 7325 3817 7326 3825 7326 3824 7326 3824 7327 3829 7327 3817 7327 3817 7328 3829 7328 3831 7328 3817 7329 3831 7329 3835 7329 3835 7330 3834 7330 3817 7330 3817 7331 3834 7331 3833 7331 3817 7332 3833 7332 3818 7332 3892 7333 3893 7333 3790 7333 3790 7334 3893 7334 3890 7334 3790 7335 3890 7335 3896 7335 3896 7336 3895 7336 3790 7336 3790 7337 3895 7337 3899 7337 3790 7338 3899 7338 3898 7338 4049 7339 4051 7339 4009 7339 4009 7340 4051 7340 4055 7340 4009 7341 4055 7341 4054 7341 4135 7342 3790 7342 4008 7342 4008 7343 3790 7343 3797 7343 4008 7344 3797 7344 4009 7344 4009 7345 3797 7345 3798 7345 4009 7346 3798 7346 3801 7346 3898 7347 3902 7347 3790 7347 3790 7348 3902 7348 3901 7348 3790 7349 3901 7349 3900 7349 3806 7350 3805 7350 4009 7350 4009 7351 3805 7351 3804 7351 4009 7352 3804 7352 3803 7352 4083 7353 4101 7353 4008 7353 4008 7354 4101 7354 4109 7354 4109 7355 4108 7355 4008 7355 4008 7356 4108 7356 4107 7356 4008 7357 4107 7357 4106 7357 4106 7358 4105 7358 4008 7358 4008 7359 4105 7359 4104 7359 4008 7360 4104 7360 4113 7360 3818 7361 3833 7361 3844 7361 3844 7362 3833 7362 3840 7362 3844 7363 3840 7363 3842 7363 3900 7364 3903 7364 3790 7364 3790 7365 3903 7365 3905 7365 3790 7366 3905 7366 3907 7366 3859 7367 3865 7367 3799 7367 3799 7368 3865 7368 3864 7368 3799 7369 3864 7369 4009 7369 4009 7370 3864 7370 3869 7370 4009 7371 3869 7371 3878 7371 4054 7372 4053 7372 4009 7372 4009 7373 4053 7373 4040 7373 4009 7374 4040 7374 4039 7374 3803 7375 3807 7375 4009 7375 4009 7376 3807 7376 3808 7376 4009 7377 3808 7377 3811 7377 3811 7378 3810 7378 4009 7378 4009 7379 3810 7379 3809 7379 4009 7380 3809 7380 3796 7380 4113 7381 4112 7381 4008 7381 4008 7382 4112 7382 4111 7382 4008 7383 4111 7383 4087 7383 4087 7384 4086 7384 4008 7384 4008 7385 4086 7385 4119 7385 4008 7386 4119 7386 4120 7386 4120 7387 4121 7387 4008 7387 4008 7388 4121 7388 4146 7388 4008 7389 4146 7389 4140 7389 3907 7390 3908 7390 3790 7390 3790 7391 3908 7391 3910 7391 3790 7392 3910 7392 3912 7392 3878 7393 4044 7393 4009 7393 4009 7394 4044 7394 4042 7394 4009 7395 4042 7395 4043 7395 4039 7396 4057 7396 4009 7396 4009 7397 4057 7397 4059 7397 4009 7398 4059 7398 4061 7398 4043 7399 4045 7399 4009 7399 4009 7400 4045 7400 4047 7400 4009 7401 4047 7401 4049 7401 4015 7402 4014 7402 4032 7402 497 7403 496 7403 4021 7403 4021 7404 496 7404 492 7404 4021 7405 492 7405 4024 7405 4024 7406 492 7406 494 7406 4024 7407 494 7407 4007 7407 4035 7408 499 7408 497 7408 715 7409 4032 7409 710 7409 710 7410 4032 7410 4014 7410 710 7411 4014 7411 722 7411 722 7412 4014 7412 4013 7412 4013 7413 4010 7413 722 7413 722 7414 4010 7414 4012 7414 722 7415 4012 7415 717 7415 4015 7416 4032 7416 4016 7416 4016 7417 4032 7417 4031 7417 4016 7418 4031 7418 4017 7418 4017 7419 4031 7419 4030 7419 4017 7420 4030 7420 4018 7420 4018 7421 4030 7421 4029 7421 4018 7422 4029 7422 4022 7422 4021 7423 4020 7423 497 7423 497 7424 4020 7424 4019 7424 497 7425 4019 7425 4035 7425 4035 7426 4019 7426 4023 7426 4035 7427 4023 7427 4034 7427 4034 7428 4023 7428 4022 7428 4034 7429 4022 7429 4033 7429 4033 7430 4022 7430 4029 7430 3887 7431 3886 7431 4147 7431 4148 7432 4149 7432 4150 7432 4141 7433 4151 7433 4142 7433 4152 7434 4153 7434 4151 7434 4151 7435 4141 7435 4152 7435 4152 7436 4141 7436 4140 7436 4152 7437 4140 7437 4146 7437 4135 7438 4145 7438 4154 7438 4154 7439 4145 7439 4144 7439 4154 7440 4144 7440 4155 7440 4135 7441 4154 7441 4136 7441 4136 7442 4154 7442 4156 7442 4136 7443 4156 7443 4137 7443 4137 7444 4156 7444 4147 7444 4137 7445 4147 7445 4138 7445 4138 7446 4147 7446 4139 7446 4139 7447 4147 7447 3886 7447 4139 7448 3886 7448 3891 7448 2486 7449 3885 7449 3785 7449 3785 7450 3885 7450 4157 7450 3785 7451 4157 7451 3786 7451 4158 7452 3788 7452 4157 7452 4157 7453 3788 7453 3787 7453 4157 7454 3787 7454 3786 7454 4159 7455 3782 7455 4160 7455 4160 7456 3782 7456 3784 7456 4160 7457 3784 7457 4158 7457 4158 7458 3784 7458 3789 7458 4158 7459 3789 7459 3788 7459 3777 7460 3775 7460 4161 7460 4161 7461 3775 7461 3774 7461 4161 7462 3774 7462 4159 7462 4159 7463 3774 7463 3781 7463 4159 7464 3781 7464 3782 7464 4162 7465 4163 7465 4161 7465 4161 7466 4163 7466 4164 7466 4161 7467 4164 7467 3777 7467 3777 7468 4164 7468 4165 7468 3777 7469 4165 7469 3779 7469 4153 7470 4148 7470 4151 7470 4151 7471 4148 7471 4150 7471 4151 7472 4150 7472 4142 7472 4142 7473 4150 7473 4155 7473 4142 7474 4155 7474 4143 7474 4143 7475 4155 7475 4144 7475 3885 7476 3887 7476 4157 7476 4157 7477 3887 7477 4147 7477 4157 7478 4147 7478 4158 7478 4158 7479 4147 7479 4156 7479 4158 7480 4156 7480 4160 7480 4160 7481 4156 7481 4154 7481 4160 7482 4154 7482 4159 7482 4159 7483 4154 7483 4155 7483 4159 7484 4155 7484 4161 7484 4161 7485 4155 7485 4150 7485 4161 7486 4150 7486 4162 7486 4162 7487 4150 7487 4149 7487 3880 7488 4081 7488 3999 7488 4076 7489 4081 7489 3880 7489 3880 7490 3873 7490 4166 7490 4166 7491 3873 7491 3874 7491 4166 7492 3874 7492 3875 7492 4077 7493 4076 7493 3880 7493 4080 7494 4079 7494 4166 7494 4166 7495 4079 7495 3880 7495 4077 7496 3880 7496 4079 7496 4074 7497 4167 7497 4075 7497 4075 7498 4167 7498 674 7498 4080 7499 4166 7499 4071 7499 4071 7500 4166 7500 3875 7500 4071 7501 3875 7501 4072 7501 4072 7502 3875 7502 3876 7502 4072 7503 3876 7503 4073 7503 4073 7504 3876 7504 3877 7504 4073 7505 3877 7505 4074 7505 4074 7506 3877 7506 4168 7506 4074 7507 4168 7507 4167 7507 705 7508 670 7508 4169 7508 672 7509 4170 7509 670 7509 670 7510 4170 7510 4171 7510 670 7511 4171 7511 4169 7511 672 7512 674 7512 4167 7512 4167 7513 4168 7513 672 7513 672 7514 4168 7514 3877 7514 672 7515 3877 7515 4170 7515 705 7516 4169 7516 702 7516 702 7517 4169 7517 4172 7517 702 7518 4172 7518 703 7518 4173 7519 4174 7519 3116 7519 3877 7520 3150 7520 3151 7520 3151 7521 3152 7521 3877 7521 3877 7522 3152 7522 3153 7522 3877 7523 3153 7523 3154 7523 3154 7524 3155 7524 3877 7524 3877 7525 3155 7525 3133 7525 3877 7526 3133 7526 932 7526 4175 7527 703 7527 3085 7527 3110 7528 3088 7528 4172 7528 4172 7529 3088 7529 3109 7529 4172 7530 3109 7530 3108 7530 3108 7531 3107 7531 4172 7531 4172 7532 3107 7532 3106 7532 4172 7533 3106 7533 703 7533 703 7534 3106 7534 3086 7534 703 7535 3086 7535 3085 7535 4172 7536 4169 7536 3110 7536 3110 7537 4169 7537 4171 7537 3110 7538 4171 7538 932 7538 932 7539 4171 7539 4170 7539 932 7540 4170 7540 3877 7540 4174 7541 4176 7541 3116 7541 3116 7542 4176 7542 4177 7542 3116 7543 4177 7543 4178 7543 3085 7544 3113 7544 4175 7544 4175 7545 3113 7545 3112 7545 4175 7546 3112 7546 3111 7546 4178 7547 4179 7547 3116 7547 3116 7548 4179 7548 4180 7548 3116 7549 4180 7549 3117 7549 3111 7550 3121 7550 4175 7550 4175 7551 3121 7551 3120 7551 4175 7552 3120 7552 4180 7552 4180 7553 3120 7553 3118 7553 4180 7554 3118 7554 3117 7554 4181 7555 3115 7555 3123 7555 3115 7556 4181 7556 3116 7556 3116 7557 4181 7557 4182 7557 3116 7558 4182 7558 4173 7558 3128 7559 3127 7559 4183 7559 3128 7560 4183 7560 3129 7560 3123 7561 3122 7561 4181 7561 4181 7562 3122 7562 3126 7562 4181 7563 3126 7563 4184 7563 4184 7564 3126 7564 3125 7564 4184 7565 3125 7565 4183 7565 4183 7566 3125 7566 3124 7566 4183 7567 3124 7567 3129 7567 3093 7568 3161 7568 3094 7568 3094 7569 3161 7569 3157 7569 3094 7570 3157 7570 3127 7570 3127 7571 3157 7571 3156 7571 3127 7572 3156 7572 3167 7572 3167 7573 3168 7573 3127 7573 3127 7574 3168 7574 3169 7574 3127 7575 3169 7575 4183 7575 3093 7576 3097 7576 3161 7576 3161 7577 3097 7577 3096 7577 3161 7578 3096 7578 3091 7578 2719 7579 3160 7579 3092 7579 3092 7580 3160 7580 3163 7580 3092 7581 3163 7581 3091 7581 3091 7582 3163 7582 3162 7582 3091 7583 3162 7583 3161 7583 4185 7584 4186 7584 4187 7584 4188 7585 4189 7585 4190 7585 4190 7586 4189 7586 4187 7586 4190 7587 4187 7587 4191 7587 4191 7588 4187 7588 4186 7588 4192 7589 3164 7589 3172 7589 4185 7590 4187 7590 4193 7590 4193 7591 4187 7591 4192 7591 4193 7592 4192 7592 4194 7592 4194 7593 4192 7593 3172 7593 4194 7594 3172 7594 3173 7594 4183 7595 3169 7595 3165 7595 3164 7596 4192 7596 3165 7596 3165 7597 4192 7597 4184 7597 3165 7598 4184 7598 4183 7598 4195 7599 4176 7599 4196 7599 4196 7600 4176 7600 4174 7600 4196 7601 4174 7601 4189 7601 4189 7602 4174 7602 4173 7602 4189 7603 4173 7603 4187 7603 4187 7604 4173 7604 4182 7604 4187 7605 4182 7605 4192 7605 4192 7606 4182 7606 4181 7606 4192 7607 4181 7607 4184 7607 4197 7608 4198 7608 3305 7608 4199 7609 4200 7609 3284 7609 3240 7610 3239 7610 4201 7610 3188 7611 3190 7611 4202 7611 4202 7612 3190 7612 4203 7612 3187 7613 4204 7613 3186 7613 3186 7614 4204 7614 4205 7614 3186 7615 4205 7615 3185 7615 3185 7616 4205 7616 4203 7616 3185 7617 4203 7617 3191 7617 3191 7618 4203 7618 3190 7618 3187 7619 3184 7619 4204 7619 4204 7620 3184 7620 3183 7620 4204 7621 3183 7621 3182 7621 3209 7622 3294 7622 3210 7622 3210 7623 3294 7623 3211 7623 3209 7624 3208 7624 3294 7624 3294 7625 3208 7625 3207 7625 3294 7626 3207 7626 3290 7626 3204 7627 3291 7627 3205 7627 3205 7628 3291 7628 3290 7628 3205 7629 3290 7629 3206 7629 3206 7630 3290 7630 3207 7630 3199 7631 3198 7631 3288 7631 3204 7632 3203 7632 3291 7632 3291 7633 3203 7633 3202 7633 3291 7634 3202 7634 3292 7634 3292 7635 3202 7635 3201 7635 3292 7636 3201 7636 3288 7636 3288 7637 3201 7637 3200 7637 3288 7638 3200 7638 3199 7638 3197 7639 3196 7639 4206 7639 4206 7640 3196 7640 3195 7640 4202 7641 4207 7641 3188 7641 3188 7642 4207 7642 4208 7642 3188 7643 4208 7643 3189 7643 3189 7644 4208 7644 3192 7644 3195 7645 3194 7645 4206 7645 4206 7646 3194 7646 3193 7646 4206 7647 3193 7647 4209 7647 4209 7648 3193 7648 3192 7648 4209 7649 3192 7649 4210 7649 4210 7650 3192 7650 4208 7650 3264 7651 3327 7651 3265 7651 3265 7652 3327 7652 3329 7652 3265 7653 3329 7653 3266 7653 3266 7654 3329 7654 3330 7654 3266 7655 3330 7655 3262 7655 3262 7656 3330 7656 3321 7656 3262 7657 3321 7657 3322 7657 3322 7658 3323 7658 3262 7658 3262 7659 3323 7659 3324 7659 3262 7660 3324 7660 3325 7660 3326 7661 3337 7661 4211 7661 4211 7662 3337 7662 3338 7662 4211 7663 3338 7663 3339 7663 3339 7664 3340 7664 4211 7664 4211 7665 3340 7665 3341 7665 4211 7666 3341 7666 4212 7666 4212 7667 3341 7667 3342 7667 4212 7668 3342 7668 4213 7668 4213 7669 3342 7669 4214 7669 4214 7670 3342 7670 3343 7670 4214 7671 3343 7671 4215 7671 4216 7672 3347 7672 4217 7672 4217 7673 3347 7673 4218 7673 3343 7674 3344 7674 4215 7674 4215 7675 3344 7675 3345 7675 4215 7676 3345 7676 4216 7676 4216 7677 3345 7677 3346 7677 4216 7678 3346 7678 3347 7678 4218 7679 3347 7679 4219 7679 4219 7680 3347 7680 3348 7680 4219 7681 3348 7681 3349 7681 3350 7682 3336 7682 3244 7682 3244 7683 3336 7683 3335 7683 3244 7684 3335 7684 3334 7684 3334 7685 3333 7685 3244 7685 3244 7686 3333 7686 3332 7686 3244 7687 3332 7687 3245 7687 3245 7688 3332 7688 3331 7688 3245 7689 3331 7689 3264 7689 3264 7690 3331 7690 3328 7690 3264 7691 3328 7691 3327 7691 4220 7692 4221 7692 4222 7692 3239 7693 4223 7693 4224 7693 4224 7694 4225 7694 3239 7694 3239 7695 4225 7695 4226 7695 3239 7696 4226 7696 4227 7696 4228 7697 4201 7697 4222 7697 4222 7698 4201 7698 3239 7698 4222 7699 3239 7699 4220 7699 4220 7700 3239 7700 4227 7700 4223 7701 3239 7701 4229 7701 4229 7702 3239 7702 3279 7702 4229 7703 3279 7703 4230 7703 3284 7704 4200 7704 3280 7704 3280 7705 4200 7705 4231 7705 3280 7706 4231 7706 3279 7706 3279 7707 4231 7707 4232 7707 3279 7708 4232 7708 4230 7708 3281 7709 4233 7709 3282 7709 3282 7710 4233 7710 4234 7710 3282 7711 4234 7711 3284 7711 3284 7712 4234 7712 4235 7712 3284 7713 4235 7713 4199 7713 3198 7714 3197 7714 3288 7714 3288 7715 3197 7715 4206 7715 3288 7716 4206 7716 3286 7716 3286 7717 4206 7717 4236 7717 3286 7718 4236 7718 3285 7718 3285 7719 4236 7719 4237 7719 3285 7720 4237 7720 3281 7720 3281 7721 4237 7721 4238 7721 3281 7722 4238 7722 4233 7722 3236 7723 4239 7723 3237 7723 3237 7724 4239 7724 4240 7724 3237 7725 4240 7725 3295 7725 3295 7726 4240 7726 4204 7726 3295 7727 4204 7727 3294 7727 3294 7728 4204 7728 3182 7728 3294 7729 3182 7729 3211 7729 3297 7730 4241 7730 3296 7730 3296 7731 4241 7731 4242 7731 3296 7732 4242 7732 3236 7732 3236 7733 4242 7733 4243 7733 3236 7734 4243 7734 4239 7734 4244 7735 4245 7735 3302 7735 3302 7736 4245 7736 4246 7736 3302 7737 4246 7737 3303 7737 3303 7738 4246 7738 4247 7738 3303 7739 4247 7739 3297 7739 3297 7740 4247 7740 4248 7740 3297 7741 4248 7741 4241 7741 4198 7742 4249 7742 3305 7742 3305 7743 4249 7743 4250 7743 3305 7744 4250 7744 4251 7744 4251 7745 4252 7745 3305 7745 3305 7746 4252 7746 4253 7746 3305 7747 4253 7747 3299 7747 3299 7748 4253 7748 4254 7748 3299 7749 4254 7749 3300 7749 3300 7750 4254 7750 4255 7750 3300 7751 4255 7751 3302 7751 3302 7752 4255 7752 4256 7752 3302 7753 4256 7753 4244 7753 4257 7754 4258 7754 4259 7754 4260 7755 4261 7755 4262 7755 4263 7756 4260 7756 3305 7756 4257 7757 4259 7757 3252 7757 3252 7758 4259 7758 4264 7758 3252 7759 4264 7759 4265 7759 4265 7760 4264 7760 4266 7760 4265 7761 4266 7761 3305 7761 3305 7762 4266 7762 4267 7762 3305 7763 4267 7763 4263 7763 4260 7764 4262 7764 3305 7764 3305 7765 4262 7765 4268 7765 3305 7766 4268 7766 4197 7766 4269 7767 4270 7767 3252 7767 4271 7768 4257 7768 4272 7768 4272 7769 4257 7769 3252 7769 4272 7770 3252 7770 4273 7770 4273 7771 3252 7771 4270 7771 4273 7772 4270 7772 4274 7772 3258 7773 4275 7773 3257 7773 3257 7774 4275 7774 4276 7774 3257 7775 4276 7775 3255 7775 3255 7776 4276 7776 4277 7776 4277 7777 4278 7777 3255 7777 3255 7778 4278 7778 4279 7778 3255 7779 4279 7779 3253 7779 3253 7780 4279 7780 4280 7780 3253 7781 4280 7781 3251 7781 3251 7782 4280 7782 4281 7782 3251 7783 4281 7783 3252 7783 3252 7784 4281 7784 4282 7784 3252 7785 4282 7785 4269 7785 3247 7786 4283 7786 3248 7786 3248 7787 4283 7787 4284 7787 3248 7788 4284 7788 3258 7788 3258 7789 4284 7789 4285 7789 3258 7790 4285 7790 4275 7790 3325 7791 3326 7791 3262 7791 3262 7792 3326 7792 4211 7792 3262 7793 4211 7793 3260 7793 3260 7794 4211 7794 3259 7794 3259 7795 4211 7795 4286 7795 3259 7796 4286 7796 3247 7796 3247 7797 4286 7797 4287 7797 3247 7798 4287 7798 4283 7798 4288 7799 3268 7799 4289 7799 4289 7800 3268 7800 3270 7800 4289 7801 3270 7801 4290 7801 3349 7802 3350 7802 4219 7802 4219 7803 3350 7803 3244 7803 4219 7804 3244 7804 4288 7804 4288 7805 3244 7805 3269 7805 4288 7806 3269 7806 3268 7806 3241 7807 4291 7807 4292 7807 4292 7808 4293 7808 3241 7808 3241 7809 4293 7809 4294 7809 3241 7810 4294 7810 3242 7810 3242 7811 4294 7811 4295 7811 3242 7812 4295 7812 3270 7812 3270 7813 4295 7813 4296 7813 3270 7814 4296 7814 4290 7814 3272 7815 4297 7815 3271 7815 3271 7816 4297 7816 4298 7816 3271 7817 4298 7817 3241 7817 3241 7818 4298 7818 4299 7818 3241 7819 4299 7819 4291 7819 4201 7820 4300 7820 3240 7820 3240 7821 4300 7821 4301 7821 3240 7822 4301 7822 3277 7822 3277 7823 4301 7823 4302 7823 3277 7824 4302 7824 4303 7824 4304 7825 4305 7825 4306 7825 4303 7826 4307 7826 4308 7826 4308 7827 4307 7827 4309 7827 4308 7828 4309 7828 4310 7828 4310 7829 4311 7829 4308 7829 4308 7830 4311 7830 4312 7830 4308 7831 4312 7831 4304 7831 4304 7832 4306 7832 4308 7832 4308 7833 4306 7833 4313 7833 4308 7834 4313 7834 4314 7834 4303 7835 4308 7835 3277 7835 3277 7836 4308 7836 4314 7836 3277 7837 4314 7837 3276 7837 3276 7838 4314 7838 4315 7838 3276 7839 4315 7839 3274 7839 3274 7840 4315 7840 4316 7840 3274 7841 4316 7841 3272 7841 3272 7842 4316 7842 4317 7842 3272 7843 4317 7843 4297 7843 4318 7844 4319 7844 4320 7844 4321 7845 4322 7845 4323 7845 4323 7846 4322 7846 4324 7846 4325 7847 4326 7847 4327 7847 4321 7848 4328 7848 4322 7848 4322 7849 4328 7849 4325 7849 4322 7850 4325 7850 4329 7850 4329 7851 4325 7851 4327 7851 3716 7852 4320 7852 3723 7852 3723 7853 4320 7853 4319 7853 3723 7854 4319 7854 3724 7854 3724 7855 4319 7855 3439 7855 4323 7856 4330 7856 4321 7856 4321 7857 4330 7857 4331 7857 4321 7858 4331 7858 4320 7858 4320 7859 4331 7859 4332 7859 4320 7860 4332 7860 4318 7860 3715 7861 4333 7861 3716 7861 3716 7862 4333 7862 4334 7862 3716 7863 4334 7863 4320 7863 4320 7864 4334 7864 4335 7864 4320 7865 4335 7865 4321 7865 4321 7866 4335 7866 4336 7866 4321 7867 4336 7867 4328 7867 4337 7868 4338 7868 4339 7868 4340 7869 4341 7869 3383 7869 3383 7870 3382 7870 4340 7870 4340 7871 3382 7871 3390 7871 4340 7872 3390 7872 4342 7872 4342 7873 3390 7873 3389 7873 4342 7874 3389 7874 4343 7874 4343 7875 3389 7875 3388 7875 4343 7876 3388 7876 3387 7876 3378 7877 3379 7877 4344 7877 4344 7878 3379 7878 3380 7878 4344 7879 3380 7879 4345 7879 3380 7880 3381 7880 4345 7880 4345 7881 3381 7881 3385 7881 4345 7882 3385 7882 4341 7882 4341 7883 3385 7883 3384 7883 4341 7884 3384 7884 3383 7884 4346 7885 4347 7885 4339 7885 4339 7886 4347 7886 4348 7886 4339 7887 4348 7887 4337 7887 4349 7888 4350 7888 4346 7888 4349 7889 4351 7889 4352 7889 4352 7890 4353 7890 4349 7890 4349 7891 4353 7891 4354 7891 4349 7892 4354 7892 4355 7892 4355 7893 4356 7893 4349 7893 4349 7894 4356 7894 4357 7894 4349 7895 4357 7895 4350 7895 3507 7896 3506 7896 4349 7896 4349 7897 3506 7897 3509 7897 4349 7898 3509 7898 4351 7898 4351 7899 3509 7899 3508 7899 4351 7900 3508 7900 3510 7900 3510 7901 3503 7901 4351 7901 4351 7902 3503 7902 3502 7902 4351 7903 3502 7903 4358 7903 4358 7904 3502 7904 3501 7904 4358 7905 3501 7905 3505 7905 4346 7906 4339 7906 4349 7906 4349 7907 4339 7907 3520 7907 4349 7908 3520 7908 3507 7908 3386 7909 4339 7909 3387 7909 3387 7910 4339 7910 4338 7910 3387 7911 4338 7911 4343 7911 3386 7912 3391 7912 4339 7912 4339 7913 3391 7913 3392 7913 4339 7914 3392 7914 3357 7914 3518 7915 3517 7915 4339 7915 3518 7916 4339 7916 3519 7916 3357 7917 2895 7917 4339 7917 4339 7918 2895 7918 3492 7918 4339 7919 3492 7919 3519 7919 3517 7920 3522 7920 4339 7920 4339 7921 3522 7921 3521 7921 4339 7922 3521 7922 3520 7922 4359 7923 4360 7923 4361 7923 4362 7924 698 7924 697 7924 691 7925 4361 7925 692 7925 692 7926 4361 7926 696 7926 4360 7927 4363 7927 4361 7927 4361 7928 4363 7928 4364 7928 4361 7929 4364 7929 696 7929 696 7930 4364 7930 4365 7930 696 7931 4365 7931 695 7931 695 7932 4365 7932 4366 7932 695 7933 4366 7933 664 7933 664 7934 4366 7934 4367 7934 664 7935 4367 7935 700 7935 4362 7936 697 7936 4368 7936 700 7937 4367 7937 697 7937 697 7938 4367 7938 4369 7938 697 7939 4369 7939 4368 7939 4370 7940 4371 7940 4372 7940 4373 7941 4374 7941 4370 7941 4370 7942 4374 7942 4375 7942 4370 7943 4375 7943 4371 7943 4188 7944 4373 7944 4376 7944 4376 7945 4373 7945 4370 7945 4376 7946 4370 7946 4377 7946 4377 7947 4370 7947 4378 7947 4372 7948 4359 7948 4370 7948 4370 7949 4359 7949 4361 7949 4370 7950 4361 7950 690 7950 690 7951 4361 7951 691 7951 690 7952 689 7952 4370 7952 4370 7953 689 7953 688 7953 4370 7954 688 7954 4378 7954 4378 7955 688 7955 687 7955 4378 7956 687 7956 686 7956 4379 7957 4380 7957 4378 7957 681 7958 4379 7958 682 7958 682 7959 4379 7959 4378 7959 682 7960 4378 7960 683 7960 683 7961 4378 7961 686 7961 4381 7962 4176 7962 4195 7962 4188 7963 4376 7963 4189 7963 4189 7964 4376 7964 4377 7964 4189 7965 4377 7965 4196 7965 4196 7966 4377 7966 4378 7966 4196 7967 4378 7967 4195 7967 4195 7968 4378 7968 4380 7968 4195 7969 4380 7969 4381 7969 676 7970 673 7970 4382 7970 671 7971 706 7971 4180 7971 4180 7972 706 7972 4175 7972 4175 7973 706 7973 704 7973 4175 7974 704 7974 703 7974 4379 7975 681 7975 677 7975 677 7976 676 7976 4379 7976 4379 7977 676 7977 4382 7977 4379 7978 4382 7978 4177 7978 671 7979 4180 7979 673 7979 673 7980 4180 7980 4179 7980 673 7981 4179 7981 4382 7981 4382 7982 4179 7982 4178 7982 4382 7983 4178 7983 4177 7983 4176 7984 4381 7984 4177 7984 4177 7985 4381 7985 4380 7985 4177 7986 4380 7986 4379 7986 3414 7987 3413 7987 4383 7987 4384 7988 4385 7988 4386 7988 4387 7989 4388 7989 4389 7989 4390 7990 4391 7990 4389 7990 3916 7991 3918 7991 4392 7991 4393 7992 4394 7992 4395 7992 4362 7993 4368 7993 4396 7993 4396 7994 4368 7994 4369 7994 4194 7995 3173 7995 3395 7995 4373 7996 4188 7996 4190 7996 4191 7997 4186 7997 4397 7997 4397 7998 4186 7998 4185 7998 4397 7999 4185 7999 4193 7999 4359 8000 4372 8000 4398 8000 4398 8001 4372 8001 4371 8001 4398 8002 4371 8002 4399 8002 4190 8003 4191 8003 4373 8003 4373 8004 4191 8004 4397 8004 4373 8005 4397 8005 4374 8005 4374 8006 4397 8006 4399 8006 4374 8007 4399 8007 4375 8007 4375 8008 4399 8008 4371 8008 4364 8009 4363 8009 4400 8009 4400 8010 4363 8010 4360 8010 4400 8011 4360 8011 4359 8011 4365 8012 4401 8012 4366 8012 4366 8013 4401 8013 4367 8013 4402 8014 4403 8014 4404 8014 4404 8015 4403 8015 4405 8015 4404 8016 4405 8016 698 8016 4393 8017 4395 8017 4406 8017 4407 8018 4408 8018 4409 8018 4410 8019 4411 8019 4412 8019 4412 8020 4411 8020 4413 8020 4412 8021 4413 8021 4414 8021 4414 8022 4413 8022 4415 8022 4414 8023 4415 8023 4406 8023 4416 8024 4417 8024 4407 8024 4407 8025 4417 8025 4418 8025 4407 8026 4418 8026 4408 8026 4419 8027 4392 8027 4420 8027 4419 8028 4420 8028 4385 8028 4420 8029 4421 8029 4385 8029 4385 8030 4421 8030 4422 8030 4385 8031 4422 8031 4386 8031 4386 8032 4422 8032 4423 8032 4419 8033 3930 8033 3929 8033 4419 8034 3929 8034 4392 8034 4392 8035 3929 8035 3914 8035 4392 8036 3914 8036 3916 8036 3400 8037 3927 8037 4419 8037 4419 8038 3927 8038 3931 8038 4419 8039 3931 8039 3930 8039 4424 8040 4425 8040 4426 8040 4394 8041 4427 8041 4428 8041 4428 8042 4427 8042 4429 8042 4428 8043 4429 8043 4390 8043 698 8044 4362 8044 4404 8044 4404 8045 4362 8045 4396 8045 4404 8046 4396 8046 4401 8046 4401 8047 4396 8047 4369 8047 4401 8048 4369 8048 4367 8048 4430 8049 4401 8049 4400 8049 4400 8050 4401 8050 4365 8050 4400 8051 4365 8051 4364 8051 4431 8052 4388 8052 4432 8052 4432 8053 4388 8053 4387 8053 4432 8054 4387 8054 4433 8054 4434 8055 4407 8055 4412 8055 4412 8056 4407 8056 4409 8056 4412 8057 4409 8057 4410 8057 4193 8058 4194 8058 4397 8058 4397 8059 4194 8059 3395 8059 4397 8060 3395 8060 4399 8060 4399 8061 3395 8061 3394 8061 4399 8062 3394 8062 3393 8062 4359 8063 4398 8063 4400 8063 4400 8064 4398 8064 4399 8064 4400 8065 4399 8065 4430 8065 4430 8066 4399 8066 3393 8066 4430 8067 3393 8067 3423 8067 3423 8068 3422 8068 4430 8068 4430 8069 3422 8069 4435 8069 4430 8070 4435 8070 4401 8070 4401 8071 4435 8071 4436 8071 4401 8072 4436 8072 4404 8072 4404 8073 4436 8073 4426 8073 4404 8074 4426 8074 4402 8074 4402 8075 4426 8075 4425 8075 3422 8076 3421 8076 4435 8076 4435 8077 3421 8077 4433 8077 4435 8078 4433 8078 4436 8078 4436 8079 4433 8079 4387 8079 4436 8080 4387 8080 4426 8080 4426 8081 4387 8081 4389 8081 4426 8082 4389 8082 4424 8082 4424 8083 4389 8083 4391 8083 3421 8084 3420 8084 4433 8084 4433 8085 3420 8085 3419 8085 4433 8086 3419 8086 4432 8086 4432 8087 3419 8087 3418 8087 4432 8088 3418 8088 4431 8088 4431 8089 3418 8089 3417 8089 4431 8090 3417 8090 3416 8090 4390 8091 4389 8091 4428 8091 4428 8092 4389 8092 4388 8092 4428 8093 4388 8093 4437 8093 4437 8094 4388 8094 4431 8094 4437 8095 4431 8095 4438 8095 4438 8096 4431 8096 3416 8096 4438 8097 3416 8097 3415 8097 4394 8098 4428 8098 4395 8098 4395 8099 4428 8099 4437 8099 4395 8100 4437 8100 4439 8100 4439 8101 4437 8101 4438 8101 4439 8102 4438 8102 4383 8102 4383 8103 4438 8103 3415 8103 4383 8104 3415 8104 3414 8104 4406 8105 4395 8105 4414 8105 4414 8106 4395 8106 4439 8106 4414 8107 4439 8107 4412 8107 4412 8108 4439 8108 4383 8108 4412 8109 4383 8109 4434 8109 4434 8110 4383 8110 3413 8110 4434 8111 3413 8111 3412 8111 3412 8112 3411 8112 4434 8112 4434 8113 3411 8113 4384 8113 4434 8114 4384 8114 4407 8114 4407 8115 4384 8115 4386 8115 4407 8116 4386 8116 4416 8116 4416 8117 4386 8117 4423 8117 3411 8118 3410 8118 4384 8118 4384 8119 3410 8119 3398 8119 4384 8120 3398 8120 4385 8120 4385 8121 3398 8121 3403 8121 4385 8122 3403 8122 4419 8122 4419 8123 3403 8123 3401 8123 4419 8124 3401 8124 3400 8124 580 8125 4440 8125 581 8125 581 8126 4440 8126 4441 8126 581 8127 4441 8127 583 8127 4442 8128 4443 8128 577 8128 577 8129 4443 8129 4444 8129 577 8130 4444 8130 575 8130 577 8131 582 8131 4442 8131 4442 8132 582 8132 583 8132 4442 8133 583 8133 4445 8133 4445 8134 583 8134 4441 8134 4445 8135 4441 8135 4446 8135 4446 8136 4441 8136 4447 8136 4446 8137 4447 8137 4326 8137 565 8138 563 8138 4448 8138 4327 8139 4326 8139 4447 8139 4447 8140 4441 8140 4327 8140 4327 8141 4441 8141 4440 8141 4327 8142 4440 8142 4329 8142 565 8143 4448 8143 579 8143 580 8144 579 8144 4440 8144 4440 8145 579 8145 4448 8145 4440 8146 4448 8146 4329 8146 4329 8147 4448 8147 4449 8147 4329 8148 4449 8148 4322 8148 4322 8149 4449 8149 4324 8149 4450 8150 4324 8150 4449 8150 4451 8151 4452 8151 555 8151 4452 8152 4453 8152 4454 8152 555 8153 554 8153 4451 8153 4451 8154 554 8154 591 8154 4451 8155 591 8155 4455 8155 4455 8156 591 8156 4456 8156 4456 8157 591 8157 4457 8157 4457 8158 591 8158 590 8158 4457 8159 590 8159 588 8159 559 8160 558 8160 4454 8160 4454 8161 558 8161 557 8161 4454 8162 557 8162 4452 8162 4452 8163 557 8163 556 8163 4452 8164 556 8164 555 8164 559 8165 4454 8165 560 8165 560 8166 4454 8166 4458 8166 560 8167 4458 8167 561 8167 4458 8168 4449 8168 4448 8168 561 8169 4458 8169 562 8169 562 8170 4458 8170 4448 8170 562 8171 4448 8171 563 8171 4453 8172 4459 8172 4454 8172 4454 8173 4459 8173 4460 8173 4454 8174 4460 8174 4458 8174 4458 8175 4460 8175 4461 8175 4458 8176 4461 8176 4462 8176 4462 8177 4463 8177 4458 8177 4458 8178 4463 8178 4464 8178 4458 8179 4464 8179 4449 8179 4449 8180 4464 8180 4465 8180 4449 8181 4465 8181 4450 8181 4466 8182 4467 8182 572 8182 573 8183 572 8183 4468 8183 4468 8184 572 8184 4467 8184 4468 8185 4467 8185 4469 8185 4469 8186 4467 8186 4470 8186 4469 8187 4470 8187 4471 8187 575 8188 4472 8188 576 8188 576 8189 4472 8189 4466 8189 576 8190 4466 8190 578 8190 578 8191 4466 8191 572 8191 4446 8192 4326 8192 4325 8192 3780 8193 3779 8193 4471 8193 4467 8194 3760 8194 3759 8194 4467 8195 3759 8195 4470 8195 4470 8196 3759 8196 2409 8196 4470 8197 2409 8197 4471 8197 4471 8198 2409 8198 3778 8198 4471 8199 3778 8199 3780 8199 3764 8200 3762 8200 4472 8200 575 8201 3757 8201 4472 8201 4472 8202 3757 8202 3756 8202 4472 8203 3756 8203 3764 8203 4467 8204 4466 8204 3760 8204 3760 8205 4466 8205 4472 8205 3760 8206 4472 8206 3761 8206 3761 8207 4472 8207 3762 8207 3754 8208 3753 8208 575 8208 575 8209 3753 8209 3758 8209 575 8210 3758 8210 3757 8210 3750 8211 3748 8211 4443 8211 4443 8212 3748 8212 3747 8212 575 8213 4444 8213 3754 8213 3754 8214 4444 8214 4443 8214 3754 8215 4443 8215 3755 8215 3755 8216 4443 8216 3747 8216 3750 8217 4443 8217 3751 8217 3751 8218 4443 8218 4442 8218 3751 8219 4442 8219 3742 8219 3742 8220 4442 8220 4445 8220 3742 8221 4445 8221 4446 8221 4446 8222 4325 8222 3742 8222 3742 8223 4325 8223 4328 8223 3742 8224 4328 8224 4336 8224 3735 8225 3746 8225 4334 8225 4334 8226 3746 8226 3745 8226 4336 8227 4335 8227 3742 8227 3742 8228 4335 8228 4334 8228 3742 8229 4334 8229 3743 8229 3743 8230 4334 8230 3745 8230 3721 8231 3734 8231 3714 8231 3714 8232 3734 8232 3715 8232 3715 8233 3734 8233 4333 8233 4333 8234 3734 8234 3741 8234 4333 8235 3741 8235 3740 8235 3740 8236 3739 8236 4333 8236 4333 8237 3739 8237 3738 8237 4333 8238 3738 8238 4334 8238 4334 8239 3738 8239 3736 8239 4334 8240 3736 8240 3735 8240 3730 8241 3731 8241 3717 8241 3717 8242 3722 8242 3730 8242 3730 8243 3722 8243 3712 8243 3730 8244 3712 8244 3729 8244 3729 8245 3712 8245 3711 8245 3729 8246 3711 8246 3728 8246 3728 8247 3711 8247 2861 8247 3721 8248 3719 8248 3734 8248 3734 8249 3719 8249 3718 8249 3734 8250 3718 8250 3733 8250 3733 8251 3718 8251 3717 8251 3733 8252 3717 8252 3732 8252 3732 8253 3717 8253 3731 8253 3705 8254 3430 8254 3429 8254 4323 8255 4324 8255 4450 8255 4473 8256 4474 8256 4475 8256 4475 8257 4474 8257 4476 8257 4475 8258 4476 8258 4477 8258 4478 8259 4479 8259 4480 8259 4481 8260 4453 8260 4452 8260 4451 8261 4455 8261 4482 8261 4482 8262 4455 8262 4456 8262 4482 8263 4456 8263 4483 8263 4483 8264 4456 8264 4457 8264 4462 8265 4461 8265 4481 8265 4461 8266 4460 8266 4481 8266 4481 8267 4460 8267 4459 8267 4481 8268 4459 8268 4453 8268 4464 8269 4463 8269 4484 8269 4484 8270 4463 8270 4485 8270 4484 8271 4485 8271 4486 8271 4464 8272 4484 8272 4465 8272 4465 8273 4484 8273 4487 8273 4465 8274 4487 8274 4450 8274 4450 8275 4487 8275 4330 8275 4450 8276 4330 8276 4323 8276 4319 8277 4318 8277 4487 8277 4319 8278 4487 8278 3439 8278 4318 8279 4332 8279 4487 8279 4487 8280 4332 8280 4331 8280 4487 8281 4331 8281 4330 8281 4488 8282 3700 8282 3701 8282 3702 8283 3692 8283 4489 8283 4489 8284 3692 8284 3691 8284 4489 8285 3691 8285 3704 8285 4477 8286 4490 8286 4491 8286 4491 8287 4490 8287 4492 8287 4491 8288 4492 8288 4493 8288 3701 8289 3702 8289 4488 8289 4488 8290 3702 8290 4489 8290 4488 8291 4489 8291 4494 8291 4494 8292 4489 8292 4493 8292 4494 8293 4493 8293 4495 8293 4495 8294 4493 8294 4492 8294 4496 8295 4497 8295 4498 8295 4498 8296 4497 8296 4499 8296 4498 8297 4499 8297 4500 8297 4501 8298 4502 8298 4503 8298 4502 8299 4501 8299 4504 8299 4504 8300 4501 8300 4505 8300 4504 8301 4505 8301 4506 8301 4457 8302 588 8302 4507 8302 4507 8303 588 8303 4508 8303 4507 8304 4508 8304 4505 8304 4505 8305 4508 8305 4509 8305 4505 8306 4509 8306 4506 8306 4500 8307 4510 8307 4498 8307 4498 8308 4510 8308 4511 8308 4498 8309 4511 8309 4478 8309 4478 8310 4511 8310 4512 8310 4478 8311 4512 8311 4479 8311 4513 8312 4507 8312 4514 8312 4514 8313 4507 8313 4505 8313 4514 8314 4505 8314 4515 8314 4515 8315 4505 8315 4501 8315 4515 8316 4501 8316 4516 8316 4517 8317 4478 8317 4475 8317 4475 8318 4478 8318 4480 8318 4475 8319 4480 8319 4473 8319 4518 8320 4513 8320 4519 8320 4519 8321 4513 8321 4514 8321 4519 8322 4514 8322 4520 8322 4520 8323 4514 8323 4515 8323 4520 8324 4515 8324 4521 8324 4521 8325 4515 8325 4516 8325 4521 8326 4516 8326 4522 8326 4523 8327 4481 8327 4482 8327 4482 8328 4481 8328 4452 8328 4482 8329 4452 8329 4451 8329 3704 8330 3705 8330 4489 8330 4489 8331 3705 8331 3429 8331 4489 8332 3429 8332 4493 8332 4493 8333 3429 8333 3427 8333 4493 8334 3427 8334 3426 8334 4477 8335 4491 8335 4475 8335 4475 8336 4491 8336 4493 8336 4475 8337 4493 8337 4517 8337 4517 8338 4493 8338 3426 8338 4517 8339 3426 8339 3462 8339 3462 8340 3461 8340 4517 8340 4517 8341 3461 8341 4524 8341 4517 8342 4524 8342 4478 8342 4478 8343 4524 8343 4525 8343 4478 8344 4525 8344 4498 8344 4498 8345 4525 8345 4526 8345 4498 8346 4526 8346 4496 8346 4496 8347 4526 8347 4527 8347 3461 8348 3460 8348 4524 8348 4524 8349 3460 8349 4522 8349 4524 8350 4522 8350 4525 8350 4525 8351 4522 8351 4516 8351 4525 8352 4516 8352 4526 8352 4526 8353 4516 8353 4501 8353 4526 8354 4501 8354 4527 8354 4527 8355 4501 8355 4503 8355 3460 8356 3459 8356 4522 8356 4522 8357 3459 8357 3458 8357 4522 8358 3458 8358 4521 8358 4521 8359 3458 8359 3457 8359 4521 8360 3457 8360 4520 8360 4520 8361 3457 8361 4528 8361 4520 8362 4528 8362 4519 8362 4519 8363 4528 8363 3455 8363 4519 8364 3455 8364 4518 8364 4518 8365 3455 8365 3454 8365 4518 8366 3454 8366 3453 8366 4457 8367 4507 8367 4483 8367 4483 8368 4507 8368 4513 8368 4483 8369 4513 8369 4482 8369 4482 8370 4513 8370 4518 8370 4482 8371 4518 8371 4523 8371 4523 8372 4518 8372 3453 8372 4523 8373 3453 8373 3452 8373 3452 8374 3451 8374 4523 8374 4523 8375 3451 8375 4486 8375 4523 8376 4486 8376 4481 8376 4481 8377 4486 8377 4485 8377 4481 8378 4485 8378 4462 8378 4462 8379 4485 8379 4463 8379 3451 8380 3450 8380 4486 8380 4486 8381 3450 8381 3443 8381 4486 8382 3443 8382 4484 8382 4484 8383 3443 8383 3444 8383 4484 8384 3444 8384 4487 8384 4487 8385 3444 8385 3440 8385 4487 8386 3440 8386 3439 8386 4529 8387 4530 8387 4531 8387 4531 8388 4530 8388 4532 8388 4531 8389 4532 8389 4533 8389 4533 8390 4532 8390 4534 8390 4530 8391 4535 8391 4532 8391 4532 8392 4535 8392 4536 8392 4532 8393 4536 8393 4537 8393 4538 8394 4539 8394 4540 8394 4537 8395 4541 8395 4532 8395 4532 8396 4541 8396 4542 8396 4532 8397 4542 8397 4543 8397 4544 8398 4538 8398 4545 8398 4545 8399 4538 8399 4532 8399 4545 8400 4532 8400 4546 8400 4546 8401 4532 8401 4543 8401 4538 8402 4540 8402 4532 8402 4532 8403 4540 8403 4547 8403 4532 8404 4547 8404 4534 8404 3513 8405 3514 8405 4548 8405 4549 8406 4550 8406 4551 8406 4552 8407 4553 8407 4554 8407 4553 8408 4552 8408 4555 8408 4555 8409 4552 8409 4556 8409 4555 8410 4556 8410 4557 8410 4558 8411 4559 8411 4560 8411 4560 8412 4559 8412 4549 8412 3496 8413 4558 8413 3495 8413 3495 8414 4558 8414 4560 8414 3495 8415 4560 8415 3494 8415 3494 8416 4560 8416 4561 8416 3498 8417 3499 8417 4562 8417 4562 8418 3499 8418 3500 8418 4562 8419 3500 8419 4561 8419 4561 8420 3500 8420 3493 8420 4561 8421 3493 8421 3494 8421 4563 8422 3516 8422 4564 8422 4564 8423 3516 8423 3497 8423 4548 8424 3514 8424 4563 8424 4563 8425 3514 8425 3515 8425 4563 8426 3515 8426 3516 8426 3512 8427 4565 8427 3511 8427 3511 8428 4565 8428 4552 8428 3511 8429 4552 8429 3504 8429 3504 8430 4552 8430 4554 8430 3504 8431 4554 8431 3505 8431 4549 8432 4551 8432 4560 8432 4560 8433 4551 8433 4566 8433 4560 8434 4566 8434 4561 8434 4566 8435 4567 8435 4561 8435 4561 8436 4567 8436 4568 8436 4561 8437 4568 8437 4562 8437 4562 8438 4568 8438 4569 8438 4569 8439 4570 8439 4562 8439 4562 8440 4570 8440 4564 8440 4562 8441 4564 8441 3498 8441 3498 8442 4564 8442 3497 8442 4570 8443 4571 8443 4564 8443 4564 8444 4571 8444 4572 8444 4564 8445 4572 8445 4563 8445 4563 8446 4572 8446 4573 8446 4574 8447 4548 8447 4575 8447 4575 8448 4548 8448 4563 8448 4575 8449 4563 8449 4576 8449 4576 8450 4563 8450 4573 8450 4574 8451 4577 8451 4548 8451 4548 8452 4577 8452 4565 8452 4548 8453 4565 8453 3513 8453 3513 8454 4565 8454 3512 8454 4577 8455 4578 8455 4565 8455 4565 8456 4578 8456 4579 8456 4565 8457 4579 8457 4552 8457 4552 8458 4579 8458 4580 8458 4552 8459 4580 8459 4556 8459 3496 8460 3478 8460 3476 8460 4581 8461 4550 8461 3525 8461 3525 8462 4550 8462 4549 8462 3476 8463 3470 8463 3496 8463 3496 8464 3470 8464 3469 8464 3496 8465 3469 8465 4558 8465 4558 8466 3469 8466 3525 8466 4558 8467 3525 8467 4559 8467 4559 8468 3525 8468 4549 8468 4582 8469 4583 8469 3531 8469 4581 8470 3525 8470 4584 8470 4584 8471 3525 8471 3526 8471 4584 8472 3526 8472 3527 8472 3527 8473 3524 8473 4584 8473 4584 8474 3524 8474 3523 8474 4584 8475 3523 8475 3529 8475 3541 8476 3538 8476 3544 8476 3544 8477 3538 8477 4585 8477 3537 8478 3549 8478 4586 8478 3549 8479 3551 8479 4586 8479 4586 8480 3551 8480 3553 8480 4586 8481 3553 8481 4587 8481 3537 8482 4586 8482 3538 8482 3538 8483 4586 8483 4588 8483 3538 8484 4588 8484 4585 8484 3529 8485 3528 8485 4584 8485 4584 8486 3528 8486 3530 8486 4584 8487 3530 8487 4589 8487 4589 8488 3530 8488 3534 8488 4589 8489 3534 8489 4590 8489 4590 8490 3534 8490 3535 8490 4590 8491 3535 8491 4591 8491 4591 8492 3535 8492 4592 8492 4592 8493 3535 8493 4593 8493 4593 8494 3535 8494 3536 8494 4593 8495 3536 8495 4594 8495 4583 8496 4595 8496 3531 8496 3531 8497 4595 8497 4596 8497 3531 8498 4596 8498 3536 8498 3536 8499 4596 8499 4597 8499 3536 8500 4597 8500 4594 8500 4582 8501 3531 8501 4598 8501 4598 8502 3531 8502 3533 8502 4598 8503 3533 8503 4585 8503 4585 8504 3533 8504 3532 8504 4585 8505 3532 8505 3544 8505 3552 8506 3567 8506 3588 8506 3588 8507 3567 8507 3568 8507 3588 8508 3568 8508 3557 8508 3552 8509 3588 8509 3553 8509 3553 8510 3588 8510 4599 8510 3553 8511 4599 8511 4600 8511 4600 8512 4601 8512 3553 8512 3553 8513 4601 8513 4602 8513 3553 8514 4602 8514 4587 8514 3594 8515 3589 8515 4603 8515 3577 8516 3576 8516 4604 8516 4604 8517 3576 8517 4605 8517 4605 8518 4606 8518 4604 8518 4604 8519 4606 8519 4607 8519 4604 8520 4607 8520 4608 8520 4609 8521 4600 8521 4599 8521 4600 8522 4609 8522 4601 8522 4601 8523 4609 8523 4610 8523 4601 8524 4610 8524 4602 8524 4603 8525 3589 8525 4604 8525 4604 8526 3589 8526 3590 8526 4604 8527 3590 8527 3577 8527 3593 8528 4611 8528 3592 8528 3592 8529 4611 8529 4612 8529 3592 8530 4612 8530 3591 8530 3591 8531 4612 8531 3573 8531 3574 8532 4613 8532 3583 8532 3583 8533 4613 8533 4614 8533 3583 8534 4614 8534 3584 8534 3584 8535 4614 8535 3585 8535 3585 8536 4614 8536 4615 8536 3585 8537 4615 8537 3586 8537 3586 8538 4615 8538 4609 8538 3586 8539 4609 8539 3587 8539 3587 8540 4609 8540 4599 8540 3587 8541 4599 8541 3588 8541 4616 8542 4603 8542 4617 8542 4617 8543 4603 8543 4604 8543 4617 8544 4604 8544 4618 8544 4618 8545 4604 8545 4608 8545 4618 8546 4608 8546 4619 8546 4616 8547 4620 8547 4603 8547 4603 8548 4620 8548 4611 8548 4603 8549 4611 8549 3594 8549 3594 8550 4611 8550 3593 8550 4620 8551 4621 8551 4611 8551 4611 8552 4621 8552 4622 8552 4611 8553 4622 8553 4612 8553 4612 8554 4622 8554 4623 8554 4612 8555 4623 8555 4624 8555 4624 8556 4625 8556 4612 8556 4612 8557 4625 8557 4613 8557 4612 8558 4613 8558 3573 8558 3573 8559 4613 8559 3574 8559 4625 8560 4626 8560 4613 8560 4613 8561 4626 8561 4627 8561 4613 8562 4627 8562 4614 8562 4614 8563 4627 8563 4628 8563 4614 8564 4628 8564 4615 8564 4628 8565 4629 8565 4615 8565 4615 8566 4629 8566 4630 8566 4615 8567 4630 8567 4609 8567 4609 8568 4630 8568 4631 8568 4609 8569 4631 8569 4610 8569 4619 8570 4608 8570 4632 8570 4633 8571 4634 8571 4632 8571 4632 8572 4634 8572 4635 8572 4632 8573 4635 8573 4619 8573 4636 8574 4637 8574 4633 8574 4633 8575 4637 8575 4638 8575 4633 8576 4638 8576 4634 8576 4639 8577 4640 8577 4641 8577 4641 8578 4640 8578 4642 8578 4641 8579 4642 8579 4636 8579 4636 8580 4642 8580 4643 8580 4636 8581 4643 8581 4637 8581 4644 8582 4645 8582 4646 8582 4646 8583 4645 8583 4639 8583 4646 8584 4639 8584 4647 8584 4647 8585 4639 8585 4641 8585 4648 8586 4644 8586 4649 8586 4649 8587 4644 8587 4646 8587 4649 8588 4646 8588 4650 8588 4650 8589 4646 8589 4647 8589 4650 8590 4647 8590 4651 8590 4651 8591 4647 8591 4652 8591 4653 8592 3621 8592 3620 8592 4653 8593 3620 8593 4654 8593 4654 8594 3620 8594 3619 8594 4654 8595 3619 8595 4655 8595 4655 8596 3619 8596 3624 8596 4655 8597 3624 8597 3625 8597 4656 8598 4657 8598 3612 8598 3612 8599 3611 8599 4656 8599 4656 8600 3611 8600 3610 8600 4656 8601 3610 8601 4658 8601 4658 8602 3610 8602 3609 8602 4658 8603 3609 8603 4653 8603 4653 8604 3609 8604 3622 8604 4653 8605 3622 8605 3621 8605 4605 8606 3576 8606 3618 8606 3617 8607 3616 8607 4657 8607 4657 8608 3616 8608 3615 8608 3615 8609 3614 8609 4657 8609 4657 8610 3614 8610 3613 8610 4657 8611 3613 8611 3612 8611 3618 8612 3617 8612 4605 8612 4605 8613 3617 8613 4657 8613 4605 8614 4657 8614 4606 8614 4606 8615 4657 8615 4607 8615 4608 8616 4607 8616 4632 8616 4632 8617 4607 8617 4657 8617 4632 8618 4657 8618 4633 8618 4633 8619 4657 8619 4656 8619 4633 8620 4656 8620 4636 8620 4636 8621 4656 8621 4658 8621 4636 8622 4658 8622 4641 8622 4641 8623 4658 8623 4653 8623 4641 8624 4653 8624 4647 8624 4647 8625 4653 8625 4654 8625 4647 8626 4654 8626 4652 8626 4652 8627 4654 8627 4655 8627 550 8628 4659 8628 551 8628 641 8629 648 8629 4660 8629 4232 8630 4231 8630 4661 8630 666 8631 665 8631 4201 8631 4201 8632 665 8632 663 8632 4201 8633 663 8633 4300 8633 4300 8634 663 8634 662 8634 4300 8635 662 8635 4301 8635 4301 8636 662 8636 4662 8636 4301 8637 4662 8637 4302 8637 4201 8638 4228 8638 666 8638 666 8639 4228 8639 4222 8639 666 8640 4222 8640 667 8640 667 8641 4222 8641 4221 8641 667 8642 4221 8642 668 8642 668 8643 4221 8643 4220 8643 668 8644 4220 8644 669 8644 669 8645 4220 8645 4227 8645 669 8646 4227 8646 678 8646 4227 8647 4226 8647 678 8647 678 8648 4226 8648 4225 8648 678 8649 4225 8649 679 8649 679 8650 4225 8650 680 8650 4225 8651 4224 8651 680 8651 680 8652 4224 8652 4223 8652 680 8653 4223 8653 693 8653 693 8654 4223 8654 4229 8654 693 8655 4229 8655 694 8655 694 8656 4229 8656 4230 8656 4661 8657 657 8657 4232 8657 4232 8658 657 8658 656 8658 4232 8659 656 8659 4230 8659 4230 8660 656 8660 685 8660 4230 8661 685 8661 694 8661 648 8662 647 8662 4660 8662 4660 8663 647 8663 650 8663 4660 8664 650 8664 4661 8664 4661 8665 650 8665 649 8665 4661 8666 649 8666 657 8666 4663 8667 642 8667 641 8667 631 8668 630 8668 4663 8668 4663 8669 630 8669 644 8669 4663 8670 644 8670 642 8670 631 8671 4663 8671 623 8671 623 8672 4663 8672 4664 8672 623 8673 4664 8673 624 8673 624 8674 4664 8674 4665 8674 624 8675 4665 8675 609 8675 617 8676 619 8676 4665 8676 4665 8677 619 8677 621 8677 4665 8678 621 8678 609 8678 606 8679 611 8679 4666 8679 4666 8680 611 8680 613 8680 4666 8681 613 8681 4665 8681 4665 8682 613 8682 615 8682 4665 8683 615 8683 617 8683 4667 8684 604 8684 606 8684 529 8685 528 8685 4668 8685 4668 8686 528 8686 594 8686 4668 8687 594 8687 4667 8687 4667 8688 594 8688 596 8688 4667 8689 596 8689 604 8689 529 8690 4668 8690 530 8690 530 8691 4668 8691 4669 8691 530 8692 4669 8692 525 8692 539 8693 538 8693 4669 8693 4669 8694 538 8694 537 8694 4669 8695 537 8695 525 8695 4659 8696 550 8696 4670 8696 550 8697 543 8697 4670 8697 4670 8698 543 8698 533 8698 4670 8699 533 8699 540 8699 569 8700 4198 8700 570 8700 570 8701 4198 8701 4197 8701 570 8702 4197 8702 571 8702 571 8703 4197 8703 584 8703 4197 8704 4268 8704 584 8704 584 8705 4268 8705 4262 8705 584 8706 4262 8706 585 8706 585 8707 4262 8707 586 8707 4262 8708 4261 8708 586 8708 586 8709 4261 8709 4260 8709 586 8710 4260 8710 593 8710 593 8711 4260 8711 4263 8711 593 8712 4263 8712 4671 8712 4671 8713 4263 8713 4267 8713 4671 8714 4267 8714 4266 8714 4670 8715 4245 8715 4659 8715 4659 8716 4245 8716 4244 8716 4659 8717 4244 8717 551 8717 551 8718 4244 8718 4256 8718 551 8719 4256 8719 564 8719 564 8720 4256 8720 4255 8720 564 8721 4255 8721 552 8721 552 8722 4255 8722 4254 8722 552 8723 4254 8723 553 8723 553 8724 4254 8724 4253 8724 553 8725 4253 8725 566 8725 566 8726 4253 8726 4252 8726 566 8727 4252 8727 567 8727 567 8728 4252 8728 4251 8728 567 8729 4251 8729 568 8729 568 8730 4251 8730 4250 8730 568 8731 4250 8731 569 8731 569 8732 4250 8732 4249 8732 569 8733 4249 8733 4198 8733 4248 8734 4247 8734 4670 8734 4670 8735 4247 8735 4246 8735 4670 8736 4246 8736 4245 8736 4241 8737 4248 8737 4669 8737 4669 8738 4248 8738 4670 8738 4669 8739 4670 8739 539 8739 539 8740 4670 8740 540 8740 4241 8741 4669 8741 4242 8741 4242 8742 4669 8742 4668 8742 4242 8743 4668 8743 4243 8743 4205 8744 4204 8744 4667 8744 4667 8745 4204 8745 4240 8745 4667 8746 4240 8746 4668 8746 4668 8747 4240 8747 4239 8747 4668 8748 4239 8748 4243 8748 606 8749 4666 8749 4667 8749 4667 8750 4666 8750 4203 8750 4667 8751 4203 8751 4205 8751 4208 8752 4207 8752 4666 8752 4666 8753 4207 8753 4202 8753 4666 8754 4202 8754 4203 8754 4208 8755 4666 8755 4210 8755 4210 8756 4666 8756 4665 8756 4210 8757 4665 8757 4209 8757 4209 8758 4665 8758 4664 8758 4209 8759 4664 8759 4206 8759 4233 8760 4238 8760 4663 8760 4663 8761 4238 8761 4237 8761 4663 8762 4237 8762 4664 8762 4664 8763 4237 8763 4236 8763 4664 8764 4236 8764 4206 8764 641 8765 4660 8765 4663 8765 4663 8766 4660 8766 4234 8766 4663 8767 4234 8767 4233 8767 4231 8768 4200 8768 4661 8768 4661 8769 4200 8769 4199 8769 4661 8770 4199 8770 4660 8770 4660 8771 4199 8771 4235 8771 4660 8772 4235 8772 4234 8772 4672 8773 4673 8773 4674 8773 4675 8774 4676 8774 4677 8774 4285 8775 4284 8775 4678 8775 4213 8776 4214 8776 4679 8776 4307 8777 4303 8777 4680 8777 4680 8778 4303 8778 4302 8778 4681 8779 4682 8779 4309 8779 4307 8780 4680 8780 4309 8780 4309 8781 4680 8781 662 8781 4309 8782 662 8782 4681 8782 4317 8783 4316 8783 4683 8783 4683 8784 4316 8784 4315 8784 4683 8785 4315 8785 4684 8785 4684 8786 4315 8786 4314 8786 4684 8787 4314 8787 4685 8787 4685 8788 4314 8788 4313 8788 4685 8789 4313 8789 4686 8789 4686 8790 4313 8790 4306 8790 4686 8791 4306 8791 4687 8791 4687 8792 4306 8792 4305 8792 4687 8793 4305 8793 4688 8793 4688 8794 4305 8794 4304 8794 4688 8795 4304 8795 4689 8795 4689 8796 4304 8796 4312 8796 4689 8797 4312 8797 4690 8797 4690 8798 4312 8798 4311 8798 4690 8799 4311 8799 4682 8799 4682 8800 4311 8800 4310 8800 4682 8801 4310 8801 4309 8801 4691 8802 4298 8802 4297 8802 4683 8803 4692 8803 4317 8803 4317 8804 4692 8804 4693 8804 4317 8805 4693 8805 4297 8805 4297 8806 4693 8806 4694 8806 4297 8807 4694 8807 4691 8807 4695 8808 4674 8808 4292 8808 4292 8809 4291 8809 4695 8809 4695 8810 4291 8810 4299 8810 4695 8811 4299 8811 4298 8811 4296 8812 4295 8812 4696 8812 4696 8813 4295 8813 4294 8813 4696 8814 4294 8814 4674 8814 4674 8815 4294 8815 4293 8815 4674 8816 4293 8816 4292 8816 4219 8817 4697 8817 4218 8817 4218 8818 4697 8818 4698 8818 4219 8819 4288 8819 4697 8819 4697 8820 4288 8820 4289 8820 4697 8821 4289 8821 4696 8821 4696 8822 4289 8822 4290 8822 4696 8823 4290 8823 4296 8823 4214 8824 4215 8824 4679 8824 4679 8825 4215 8825 4216 8825 4679 8826 4216 8826 4698 8826 4698 8827 4216 8827 4217 8827 4698 8828 4217 8828 4218 8828 4212 8829 4677 8829 4211 8829 4211 8830 4677 8830 4699 8830 4284 8831 4283 8831 4699 8831 4283 8832 4287 8832 4699 8832 4699 8833 4287 8833 4286 8833 4699 8834 4286 8834 4211 8834 4276 8835 4275 8835 4700 8835 4700 8836 4275 8836 4285 8836 4276 8837 4700 8837 4277 8837 4277 8838 4700 8838 4701 8838 4277 8839 4701 8839 4278 8839 4278 8840 4701 8840 4702 8840 4278 8841 4702 8841 4279 8841 4279 8842 4702 8842 4703 8842 4279 8843 4703 8843 4280 8843 4280 8844 4703 8844 4704 8844 4280 8845 4704 8845 4281 8845 4281 8846 4704 8846 4705 8846 4281 8847 4705 8847 4282 8847 4282 8848 4705 8848 4706 8848 4282 8849 4706 8849 4269 8849 4707 8850 4270 8850 4708 8850 4708 8851 4270 8851 4269 8851 4708 8852 4269 8852 4709 8852 4709 8853 4269 8853 4706 8853 4257 8854 4271 8854 4710 8854 4710 8855 4271 8855 4272 8855 4710 8856 4272 8856 4711 8856 4711 8857 4272 8857 4273 8857 4711 8858 4273 8858 4707 8858 4707 8859 4273 8859 4274 8859 4707 8860 4274 8860 4270 8860 4710 8861 4712 8861 4257 8861 4257 8862 4712 8862 4713 8862 4257 8863 4713 8863 4258 8863 4258 8864 4713 8864 4714 8864 4258 8865 4714 8865 4259 8865 4259 8866 4714 8866 593 8866 4259 8867 593 8867 4264 8867 4264 8868 593 8868 4671 8868 4264 8869 4671 8869 4266 8869 4700 8870 4715 8870 4716 8870 4716 8871 4717 8871 4700 8871 4700 8872 4717 8872 4718 8872 4700 8873 4718 8873 4701 8873 4701 8874 4718 8874 4719 8874 4701 8875 4719 8875 4702 8875 4285 8876 4678 8876 4700 8876 4700 8877 4678 8877 4720 8877 4700 8878 4720 8878 4715 8878 4721 8879 4722 8879 4678 8879 4678 8880 4722 8880 4723 8880 4678 8881 4723 8881 4720 8881 4284 8882 4699 8882 4678 8882 4678 8883 4699 8883 4724 8883 4678 8884 4724 8884 4721 8884 4676 8885 4725 8885 4677 8885 4677 8886 4725 8886 4726 8886 4677 8887 4726 8887 4699 8887 4699 8888 4726 8888 4727 8888 4699 8889 4727 8889 4724 8889 4728 8890 4675 8890 4679 8890 4679 8891 4675 8891 4677 8891 4679 8892 4677 8892 4213 8892 4213 8893 4677 8893 4212 8893 4729 8894 4730 8894 4698 8894 4698 8895 4730 8895 4731 8895 4698 8896 4731 8896 4679 8896 4679 8897 4731 8897 4732 8897 4679 8898 4732 8898 4728 8898 4733 8899 4734 8899 4696 8899 4696 8900 4734 8900 4735 8900 4696 8901 4735 8901 4697 8901 4697 8902 4735 8902 4736 8902 4697 8903 4736 8903 4698 8903 4698 8904 4736 8904 4737 8904 4698 8905 4737 8905 4729 8905 4674 8906 4673 8906 4696 8906 4696 8907 4673 8907 4738 8907 4696 8908 4738 8908 4733 8908 4298 8909 4691 8909 4695 8909 4695 8910 4691 8910 4739 8910 4695 8911 4739 8911 4674 8911 4674 8912 4739 8912 4740 8912 4674 8913 4740 8913 4672 8913 4741 8914 4742 8914 4743 8914 4743 8915 4742 8915 4744 8915 4743 8916 4744 8916 4745 8916 4743 8917 4746 8917 4747 8917 4741 8918 4743 8918 4748 8918 4748 8919 4743 8919 4747 8919 4748 8920 4747 8920 4749 8920 4745 8921 4417 8921 4743 8921 4743 8922 4417 8922 4416 8922 4743 8923 4416 8923 4423 8923 4423 8924 4422 8924 4743 8924 4743 8925 4422 8925 4421 8925 4743 8926 4421 8926 4746 8926 4746 8927 4421 8927 4420 8927 4746 8928 4420 8928 4750 8928 4750 8929 4420 8929 4392 8929 4750 8930 4392 8930 3918 8930 4751 8931 4410 8931 4752 8931 4752 8932 4410 8932 4409 8932 4409 8933 4408 8933 4745 8933 4745 8934 4408 8934 4418 8934 4745 8935 4418 8935 4417 8935 4744 8936 4753 8936 4745 8936 4745 8937 4753 8937 4754 8937 4745 8938 4754 8938 4409 8938 4409 8939 4754 8939 4755 8939 4409 8940 4755 8940 4752 8940 4406 8941 4415 8941 4756 8941 4756 8942 4415 8942 4413 8942 4756 8943 4413 8943 4751 8943 4751 8944 4413 8944 4411 8944 4751 8945 4411 8945 4410 8945 4757 8946 4749 8946 4747 8946 3918 8947 3917 8947 4750 8947 4750 8948 3917 8948 3923 8948 4750 8949 3923 8949 4746 8949 4746 8950 3923 8950 4747 8950 4758 8951 3921 8951 4759 8951 4759 8952 3921 8952 3920 8952 4757 8953 4747 8953 4760 8953 4761 8954 4760 8954 4762 8954 4762 8955 4760 8955 4747 8955 4762 8956 4747 8956 4758 8956 4758 8957 4747 8957 3923 8957 4758 8958 3923 8958 3921 8958 4763 8959 4764 8959 4765 8959 3920 8960 4766 8960 4759 8960 4759 8961 4766 8961 4758 8961 4765 8962 4764 8962 4766 8962 4766 8963 4764 8963 4762 8963 4766 8964 4762 8964 4758 8964 4767 8965 4768 8965 4769 8965 4769 8966 4768 8966 4770 8966 4769 8967 4770 8967 4771 8967 4771 8968 4770 8968 4772 8968 4771 8969 4772 8969 4763 8969 4763 8970 4772 8970 4773 8970 4763 8971 4773 8971 4764 8971 4764 8972 4773 8972 4774 8972 4764 8973 4774 8973 4762 8973 4762 8974 4774 8974 4761 8974 4775 8975 4534 8975 4776 8975 4776 8976 4534 8976 4777 8976 4533 8977 4534 8977 4778 8977 4778 8978 4534 8978 4775 8978 4778 8979 4775 8979 4779 8979 4779 8980 4775 8980 4780 8980 4781 8981 4782 8981 4783 8981 4784 8982 4785 8982 4786 8982 4786 8983 4787 8983 4784 8983 4784 8984 4787 8984 4788 8984 4784 8985 4788 8985 4789 8985 4790 8986 4791 8986 4792 8986 4792 8987 4793 8987 4790 8987 4790 8988 4793 8988 4794 8988 4790 8989 4794 8989 4795 8989 4795 8990 4794 8990 4784 8990 4795 8991 4784 8991 4783 8991 4783 8992 4784 8992 4789 8992 4783 8993 4789 8993 4781 8993 4783 8994 4782 8994 4796 8994 4783 8995 4796 8995 4797 8995 4798 8996 4791 8996 4790 8996 4790 8997 4797 8997 4798 8997 4798 8998 4797 8998 4796 8998 4798 8999 4796 8999 4799 8999 4799 9000 4796 9000 4800 9000 4799 9001 4800 9001 4801 9001 4801 9002 4800 9002 4802 9002 4801 9003 4802 9003 4803 9003 4788 9004 4787 9004 4544 9004 4543 9005 4542 9005 4796 9005 4796 9006 4542 9006 4800 9006 4800 9007 4542 9007 4541 9007 4800 9008 4541 9008 4802 9008 4804 9009 4803 9009 4802 9009 4535 9010 4530 9010 4805 9010 4541 9011 4537 9011 4802 9011 4802 9012 4537 9012 4536 9012 4802 9013 4536 9013 4804 9013 4804 9014 4536 9014 4535 9014 4804 9015 4535 9015 4806 9015 4806 9016 4535 9016 4805 9016 4543 9017 4796 9017 4546 9017 4546 9018 4796 9018 4782 9018 4546 9019 4782 9019 4545 9019 4545 9020 4782 9020 4781 9020 4545 9021 4781 9021 4544 9021 4544 9022 4781 9022 4789 9022 4544 9023 4789 9023 4788 9023 4786 9024 4539 9024 4787 9024 4787 9025 4539 9025 4538 9025 4787 9026 4538 9026 4544 9026 4786 9027 4785 9027 4539 9027 4539 9028 4785 9028 4807 9028 4539 9029 4807 9029 4540 9029 4540 9030 4807 9030 4808 9030 4540 9031 4808 9031 4547 9031 4547 9032 4808 9032 4777 9032 4547 9033 4777 9033 4534 9033 3695 9034 4809 9034 4810 9034 4810 9035 4809 9035 4811 9035 4810 9036 4811 9036 4812 9036 4813 9037 4814 9037 4815 9037 4815 9038 4814 9038 4812 9038 4815 9039 4812 9039 4816 9039 4816 9040 4812 9040 4811 9040 4816 9041 4811 9041 4817 9041 4815 9042 4818 9042 4813 9042 4813 9043 4818 9043 4819 9043 4813 9044 4819 9044 4820 9044 4820 9045 4819 9045 4821 9045 4822 9046 4817 9046 4823 9046 3694 9047 3696 9047 4824 9047 4824 9048 3696 9048 4825 9048 4825 9049 3696 9049 4826 9049 4826 9050 3696 9050 3698 9050 4826 9051 3698 9051 3700 9051 4824 9052 4827 9052 4828 9052 4828 9053 4822 9053 4824 9053 4824 9054 4822 9054 4823 9054 4824 9055 4823 9055 3694 9055 3694 9056 4823 9056 4809 9056 3694 9057 4809 9057 3695 9057 4494 9058 4495 9058 4829 9058 4829 9059 4495 9059 4492 9059 4492 9060 4490 9060 4829 9060 4829 9061 4490 9061 4477 9061 4829 9062 4477 9062 4830 9062 4829 9063 4825 9063 4826 9063 4494 9064 4829 9064 4488 9064 4488 9065 4829 9065 4826 9065 4488 9066 4826 9066 3700 9066 4829 9067 4831 9067 4832 9067 4825 9068 4829 9068 4824 9068 4824 9069 4829 9069 4832 9069 4824 9070 4832 9070 4827 9070 4833 9071 4834 9071 4830 9071 4830 9072 4834 9072 4835 9072 4830 9073 4835 9073 4829 9073 4829 9074 4835 9074 4836 9074 4829 9075 4836 9075 4831 9075 4477 9076 4476 9076 4830 9076 4830 9077 4476 9077 4474 9077 4830 9078 4474 9078 4833 9078 4833 9079 4474 9079 4473 9079 4833 9080 4473 9080 4837 9080 4837 9081 4473 9081 4480 9081 4837 9082 4480 9082 4838 9082 4838 9083 4480 9083 4479 9083 4838 9084 4479 9084 4839 9084 4479 9085 4512 9085 4839 9085 4839 9086 4512 9086 4511 9086 4839 9087 4511 9087 4840 9087 4840 9088 4511 9088 4510 9088 4840 9089 4510 9089 4500 9089 4841 9090 4842 9090 3598 9090 3606 9091 4843 9091 3595 9091 3595 9092 4843 9092 4844 9092 3595 9093 4844 9093 4845 9093 4846 9094 3596 9094 4847 9094 4847 9095 3596 9095 3595 9095 4847 9096 3595 9096 4848 9096 4848 9097 3595 9097 4845 9097 4849 9098 4850 9098 3602 9098 3602 9099 4850 9099 4851 9099 3602 9100 4851 9100 3606 9100 3606 9101 4851 9101 4852 9101 3606 9102 4852 9102 4843 9102 3602 9103 3601 9103 4853 9103 4853 9104 4854 9104 3602 9104 3602 9105 4854 9105 4855 9105 3602 9106 4855 9106 4856 9106 4856 9107 4857 9107 3602 9107 3602 9108 4857 9108 4858 9108 3602 9109 4858 9109 4849 9109 3599 9110 4859 9110 4860 9110 4860 9111 4861 9111 3599 9111 3599 9112 4861 9112 4862 9112 3599 9113 4862 9113 3601 9113 3601 9114 4862 9114 4863 9114 3601 9115 4863 9115 4853 9115 4859 9116 3599 9116 4864 9116 4864 9117 3599 9117 3605 9117 4864 9118 3605 9118 4865 9118 4866 9119 4867 9119 3604 9119 3604 9120 4867 9120 4868 9120 3604 9121 4868 9121 3605 9121 3605 9122 4868 9122 4869 9122 3605 9123 4869 9123 4865 9123 4866 9124 3604 9124 4870 9124 4870 9125 3604 9125 3603 9125 4870 9126 3603 9126 4871 9126 4872 9127 4873 9127 3603 9127 3603 9128 4873 9128 4874 9128 3603 9129 4874 9129 4871 9129 4875 9130 4876 9130 3600 9130 4875 9131 4877 9131 4876 9131 4876 9132 4877 9132 4872 9132 4876 9133 4872 9133 3600 9133 3600 9134 4872 9134 3603 9134 3598 9135 4842 9135 3600 9135 3600 9136 4842 9136 4878 9136 3600 9137 4878 9137 4879 9137 4879 9138 4880 9138 3600 9138 3600 9139 4880 9139 4881 9139 3600 9140 4881 9140 4875 9140 4846 9141 4882 9141 3596 9141 3596 9142 4882 9142 4883 9142 3596 9143 4883 9143 3597 9143 3597 9144 4883 9144 4884 9144 3597 9145 4884 9145 4885 9145 4885 9146 4886 9146 3597 9146 3597 9147 4886 9147 4887 9147 3597 9148 4887 9148 3598 9148 3598 9149 4887 9149 4888 9149 3598 9150 4888 9150 4841 9150 3672 9151 3671 9151 3709 9151 3709 9152 3671 9152 3635 9152 3709 9153 3635 9153 3634 9153 3687 9154 3634 9154 3676 9154 3676 9155 3634 9155 3677 9155 3687 9156 3688 9156 3634 9156 3634 9157 3688 9157 3689 9157 3634 9158 3689 9158 3709 9158 3677 9159 3634 9159 3683 9159 3683 9160 3634 9160 3637 9160 3683 9161 3637 9161 3639 9161 3639 9162 3638 9162 3683 9162 3683 9163 3638 9163 3633 9163 3683 9164 3633 9164 3682 9164 3682 9165 3633 9165 3680 9165 3680 9166 3633 9166 3632 9166 3680 9167 3632 9167 3679 9167 3679 9168 3632 9168 3631 9168 3679 9169 3631 9169 2864 9169 3670 9170 3669 9170 3708 9170 3670 9171 3708 9171 3662 9171 3669 9172 3668 9172 3708 9172 3708 9173 3668 9173 3667 9173 3708 9174 3667 9174 3709 9174 3709 9175 3667 9175 3673 9175 3709 9176 3673 9176 3672 9176 3706 9177 3699 9177 3663 9177 3662 9178 3708 9178 3663 9178 3663 9179 3708 9179 3707 9179 3663 9180 3707 9180 3706 9180 3699 9181 3697 9181 3663 9181 3663 9182 3697 9182 3695 9182 3663 9183 3695 9183 4810 9183 3659 9184 3658 9184 4820 9184 4810 9185 4812 9185 3663 9185 3663 9186 4812 9186 4814 9186 3663 9187 4814 9187 4813 9187 3658 9188 3657 9188 4820 9188 4820 9189 3657 9189 3666 9189 4820 9190 3666 9190 4813 9190 4813 9191 3666 9191 3665 9191 4813 9192 3665 9192 3663 9192 4821 9193 3661 9193 4820 9193 4820 9194 3661 9194 3660 9194 4820 9195 3660 9195 3659 9195 3653 9196 3649 9196 4889 9196 4889 9197 3649 9197 3650 9197 4889 9198 3650 9198 4821 9198 4821 9199 3650 9199 3651 9199 4821 9200 3651 9200 3661 9200 4890 9201 3625 9201 3623 9201 3623 9202 3626 9202 4890 9202 4890 9203 3626 9203 2788 9203 4890 9204 2788 9204 4891 9204 2788 9205 3630 9205 4891 9205 4891 9206 3630 9206 3655 9206 4891 9207 3655 9207 4892 9207 4892 9208 3655 9208 3654 9208 4892 9209 3654 9209 4889 9209 4889 9210 3654 9210 3652 9210 4889 9211 3652 9211 3653 9211 4893 9212 4805 9212 4530 9212 4894 9213 4895 9213 4896 9213 4530 9214 4529 9214 4894 9214 4894 9215 4896 9215 4530 9215 4530 9216 4896 9216 4897 9216 4530 9217 4897 9217 4893 9217 3625 9218 4890 9218 4655 9218 4655 9219 4890 9219 4898 9219 4655 9220 4898 9220 4652 9220 4650 9221 4899 9221 4649 9221 4649 9222 4899 9222 4900 9222 4649 9223 4900 9223 4648 9223 4652 9224 4898 9224 4651 9224 4651 9225 4898 9225 4901 9225 4651 9226 4901 9226 4650 9226 4650 9227 4901 9227 4902 9227 4650 9228 4902 9228 4899 9228 4890 9229 4903 9229 4904 9229 4897 9230 4896 9230 4905 9230 4895 9231 4894 9231 4906 9231 4907 9232 4908 9232 4909 9232 4910 9233 4900 9233 4899 9233 4910 9234 4899 9234 4911 9234 4912 9235 4913 9235 4914 9235 4914 9236 4915 9236 4912 9236 4912 9237 4915 9237 4916 9237 4912 9238 4916 9238 4917 9238 4917 9239 4916 9239 4918 9239 4917 9240 4918 9240 4911 9240 4909 9241 4908 9241 4919 9241 4908 9242 4920 9242 4919 9242 4919 9243 4920 9243 4921 9243 4919 9244 4921 9244 4913 9244 4913 9245 4921 9245 4922 9245 4913 9246 4922 9246 4914 9246 4923 9247 4924 9247 4925 9247 4925 9248 4924 9248 4907 9248 4896 9249 4895 9249 4905 9249 4905 9250 4895 9250 4906 9250 4905 9251 4906 9251 4923 9251 4923 9252 4906 9252 4926 9252 4923 9253 4926 9253 4924 9253 4893 9254 4897 9254 4927 9254 4927 9255 4897 9255 4905 9255 4927 9256 4905 9256 4928 9256 4928 9257 4905 9257 4923 9257 4928 9258 4923 9258 4929 9258 4929 9259 4923 9259 4930 9259 4930 9260 4923 9260 4931 9260 4931 9261 4923 9261 4925 9261 4931 9262 4925 9262 4932 9262 4907 9263 4909 9263 4925 9263 4925 9264 4909 9264 4933 9264 4925 9265 4933 9265 4932 9265 4934 9266 4935 9266 4936 9266 4936 9267 4935 9267 4937 9267 4937 9268 4935 9268 4938 9268 4937 9269 4938 9269 4939 9269 4940 9270 4941 9270 4936 9270 4936 9271 4941 9271 4942 9271 4936 9272 4942 9272 4934 9272 4943 9273 4944 9273 4945 9273 4945 9274 4944 9274 4946 9274 4945 9275 4946 9275 4940 9275 4940 9276 4946 9276 4947 9276 4940 9277 4947 9277 4941 9277 4948 9278 4949 9278 4950 9278 4950 9279 4949 9279 4951 9279 4950 9280 4951 9280 4952 9280 4952 9281 4951 9281 4953 9281 4953 9282 4951 9282 4904 9282 4953 9283 4904 9283 4954 9283 4954 9284 4904 9284 4955 9284 4955 9285 4904 9285 4903 9285 4955 9286 4903 9286 4956 9286 4911 9287 4899 9287 4917 9287 4917 9288 4899 9288 4902 9288 4917 9289 4902 9289 4901 9289 4939 9290 4933 9290 4937 9290 4937 9291 4933 9291 4909 9291 4937 9292 4909 9292 4936 9292 4936 9293 4909 9293 4919 9293 4936 9294 4919 9294 4940 9294 4940 9295 4919 9295 4913 9295 4940 9296 4913 9296 4945 9296 4945 9297 4913 9297 4912 9297 4945 9298 4912 9298 4957 9298 4957 9299 4912 9299 4917 9299 4957 9300 4917 9300 4958 9300 4958 9301 4917 9301 4901 9301 4958 9302 4901 9302 4898 9302 4948 9303 4943 9303 4949 9303 4949 9304 4943 9304 4945 9304 4949 9305 4945 9305 4951 9305 4951 9306 4945 9306 4957 9306 4951 9307 4957 9307 4904 9307 4904 9308 4957 9308 4958 9308 4904 9309 4958 9309 4890 9309 4890 9310 4958 9310 4898 9310 4956 9311 4890 9311 4959 9311 4959 9312 4890 9312 4891 9312 4959 9313 4891 9313 4960 9313 4960 9314 4891 9314 4892 9314 4960 9315 4892 9315 4961 9315 4961 9316 4892 9316 4889 9316 4961 9317 4889 9317 4821 9317 4768 9318 4767 9318 4962 9318 4840 9319 4500 9319 587 9319 4838 9320 4839 9320 592 9320 592 9321 4839 9321 4840 9321 592 9322 4840 9322 589 9322 589 9323 4840 9323 587 9323 592 9324 593 9324 4714 9324 4710 9325 4711 9325 4838 9325 4710 9326 4838 9326 4712 9326 592 9327 4714 9327 4838 9327 4838 9328 4714 9328 4713 9328 4838 9329 4713 9329 4712 9329 4959 9330 4960 9330 4819 9330 4819 9331 4960 9331 4961 9331 4819 9332 4961 9332 4821 9332 4959 9333 4819 9333 4956 9333 4956 9334 4819 9334 4818 9334 4956 9335 4818 9335 4955 9335 4955 9336 4818 9336 4815 9336 4955 9337 4815 9337 4816 9337 4816 9338 4817 9338 4955 9338 4955 9339 4817 9339 4822 9339 4955 9340 4822 9340 4828 9340 4711 9341 4707 9341 4838 9341 4838 9342 4707 9342 4708 9342 4838 9343 4708 9343 4709 9343 4828 9344 4827 9344 4704 9344 4704 9345 4827 9345 4832 9345 4704 9346 4832 9346 4831 9346 4831 9347 4836 9347 4704 9347 4704 9348 4836 9348 4835 9348 4704 9349 4835 9349 4834 9349 4834 9350 4833 9350 4704 9350 4704 9351 4833 9351 4837 9351 4704 9352 4837 9352 4705 9352 4705 9353 4837 9353 4838 9353 4705 9354 4838 9354 4706 9354 4706 9355 4838 9355 4709 9355 4828 9356 4704 9356 4955 9356 4955 9357 4704 9357 4703 9357 4955 9358 4703 9358 4702 9358 4717 9359 4944 9359 4718 9359 4718 9360 4944 9360 4943 9360 4718 9361 4943 9361 4948 9361 4948 9362 4950 9362 4718 9362 4718 9363 4950 9363 4952 9363 4718 9364 4952 9364 4953 9364 4702 9365 4719 9365 4955 9365 4955 9366 4719 9366 4718 9366 4955 9367 4718 9367 4954 9367 4954 9368 4718 9368 4953 9368 4934 9369 4716 9369 4715 9369 4722 9370 4935 9370 4723 9370 4723 9371 4935 9371 4934 9371 4723 9372 4934 9372 4720 9372 4720 9373 4934 9373 4715 9373 4716 9374 4934 9374 4717 9374 4717 9375 4934 9375 4942 9375 4717 9376 4942 9376 4941 9376 4941 9377 4947 9377 4717 9377 4717 9378 4947 9378 4946 9378 4717 9379 4946 9379 4944 9379 4722 9380 4721 9380 4864 9380 4864 9381 4721 9381 4724 9381 4864 9382 4724 9382 4727 9382 4864 9383 4865 9383 4722 9383 4722 9384 4865 9384 4869 9384 4722 9385 4869 9385 4935 9385 4935 9386 4869 9386 4868 9386 4935 9387 4868 9387 4867 9387 4933 9388 4939 9388 4867 9388 4867 9389 4939 9389 4938 9389 4867 9390 4938 9390 4935 9390 4870 9391 4930 9391 4866 9391 4866 9392 4930 9392 4931 9392 4866 9393 4931 9393 4867 9393 4867 9394 4931 9394 4932 9394 4867 9395 4932 9395 4933 9395 4791 9396 4873 9396 4872 9396 4873 9397 4791 9397 4874 9397 4874 9398 4791 9398 4798 9398 4874 9399 4798 9399 4799 9399 4799 9400 4801 9400 4874 9400 4874 9401 4801 9401 4803 9401 4874 9402 4803 9402 4804 9402 4870 9403 4871 9403 4930 9403 4930 9404 4871 9404 4874 9404 4930 9405 4874 9405 4806 9405 4806 9406 4874 9406 4804 9406 4893 9407 4927 9407 4805 9407 4805 9408 4927 9408 4928 9408 4805 9409 4928 9409 4806 9409 4806 9410 4928 9410 4929 9410 4806 9411 4929 9411 4930 9411 4784 9412 4794 9412 4880 9412 4880 9413 4794 9413 4793 9413 4880 9414 4793 9414 4881 9414 4881 9415 4793 9415 4792 9415 4881 9416 4792 9416 4875 9416 4875 9417 4792 9417 4791 9417 4875 9418 4791 9418 4877 9418 4877 9419 4791 9419 4872 9419 4963 9420 4964 9420 4777 9420 4777 9421 4964 9421 4965 9421 4777 9422 4965 9422 4776 9422 4966 9423 4967 9423 4807 9423 4807 9424 4967 9424 4963 9424 4807 9425 4963 9425 4808 9425 4808 9426 4963 9426 4777 9426 4784 9427 4880 9427 4785 9427 4785 9428 4880 9428 4879 9428 4785 9429 4879 9429 4807 9429 4841 9430 4888 9430 4966 9430 4841 9431 4966 9431 4842 9431 4807 9432 4879 9432 4966 9432 4966 9433 4879 9433 4878 9433 4966 9434 4878 9434 4842 9434 4885 9435 4968 9435 4969 9435 4888 9436 4887 9436 4966 9436 4966 9437 4887 9437 4886 9437 4966 9438 4886 9438 4970 9438 4970 9439 4886 9439 4885 9439 4970 9440 4885 9440 4971 9440 4971 9441 4885 9441 4969 9441 4884 9442 4972 9442 4885 9442 4885 9443 4972 9443 4973 9443 4885 9444 4973 9444 4968 9444 4883 9445 4882 9445 4734 9445 4734 9446 4882 9446 4846 9446 4734 9447 4846 9447 4735 9447 4974 9448 4975 9448 4672 9448 4974 9449 4672 9449 4976 9449 4975 9450 4977 9450 4672 9450 4672 9451 4977 9451 4978 9451 4672 9452 4978 9452 4673 9452 4673 9453 4978 9453 4738 9453 4884 9454 4883 9454 4972 9454 4972 9455 4883 9455 4734 9455 4972 9456 4734 9456 4978 9456 4978 9457 4734 9457 4733 9457 4978 9458 4733 9458 4738 9458 4979 9459 4980 9459 4740 9459 4740 9460 4980 9460 4981 9460 4740 9461 4981 9461 4982 9461 4982 9462 4983 9462 4740 9462 4740 9463 4983 9463 4984 9463 4740 9464 4984 9464 4672 9464 4672 9465 4984 9465 4985 9465 4672 9466 4985 9466 4976 9466 4979 9467 4740 9467 4986 9467 4986 9468 4740 9468 4739 9468 4986 9469 4739 9469 4691 9469 4757 9470 4760 9470 4986 9470 4744 9471 4742 9471 4693 9471 4755 9472 4754 9472 4693 9472 4693 9473 4754 9473 4753 9473 4693 9474 4753 9474 4744 9474 4742 9475 4741 9475 4693 9475 4693 9476 4741 9476 4748 9476 4693 9477 4748 9477 4749 9477 4691 9478 4694 9478 4986 9478 4986 9479 4694 9479 4693 9479 4986 9480 4693 9480 4757 9480 4757 9481 4693 9481 4749 9481 4755 9482 4693 9482 4752 9482 4752 9483 4693 9483 4692 9483 4752 9484 4692 9484 4683 9484 4683 9485 4684 9485 4752 9485 4752 9486 4684 9486 4685 9486 4752 9487 4685 9487 4686 9487 4760 9488 4761 9488 4986 9488 4986 9489 4761 9489 4774 9489 4986 9490 4774 9490 4773 9490 4987 9491 4986 9491 4988 9491 4988 9492 4986 9492 4773 9492 4988 9493 4773 9493 4989 9493 4989 9494 4773 9494 4772 9494 4989 9495 4772 9495 4990 9495 4686 9496 4687 9496 4752 9496 4752 9497 4687 9497 4688 9497 4752 9498 4688 9498 4689 9498 4689 9499 4690 9499 4752 9499 4752 9500 4690 9500 4682 9500 4752 9501 4682 9501 4681 9501 4990 9502 4772 9502 4962 9502 4962 9503 4772 9503 4770 9503 4962 9504 4770 9504 4768 9504 699 9505 4406 9505 701 9505 701 9506 4406 9506 4756 9506 4756 9507 4751 9507 701 9507 701 9508 4751 9508 4752 9508 701 9509 4752 9509 661 9509 661 9510 4752 9510 4681 9510 661 9511 4681 9511 662 9511 4735 9512 4846 9512 4736 9512 4736 9513 4846 9513 4847 9513 4736 9514 4847 9514 4737 9514 4737 9515 4847 9515 4848 9515 4737 9516 4848 9516 4845 9516 4845 9517 4844 9517 4737 9517 4737 9518 4844 9518 4843 9518 4737 9519 4843 9519 4852 9519 4732 9520 4731 9520 4851 9520 4851 9521 4731 9521 4730 9521 4851 9522 4730 9522 4852 9522 4852 9523 4730 9523 4729 9523 4852 9524 4729 9524 4737 9524 4862 9525 4861 9525 4726 9525 4726 9526 4861 9526 4860 9526 4726 9527 4860 9527 4727 9527 4727 9528 4860 9528 4859 9528 4727 9529 4859 9529 4864 9529 4851 9530 4850 9530 4732 9530 4732 9531 4850 9531 4849 9531 4732 9532 4849 9532 4728 9532 4728 9533 4849 9533 4858 9533 4728 9534 4858 9534 4675 9534 4675 9535 4858 9535 4857 9535 4675 9536 4857 9536 4856 9536 4856 9537 4855 9537 4675 9537 4675 9538 4855 9538 4854 9538 4675 9539 4854 9539 4676 9539 4676 9540 4854 9540 4853 9540 4676 9541 4853 9541 4725 9541 4725 9542 4853 9542 4726 9542 4726 9543 4853 9543 4863 9543 4726 9544 4863 9544 4862 9544 4573 9545 4572 9545 4533 9545 4551 9546 4550 9546 4581 9546 4991 9547 4533 9547 4992 9547 4992 9548 4533 9548 4993 9548 4566 9549 4551 9549 4533 9549 4598 9550 4585 9550 4533 9550 4587 9551 4619 9551 4635 9551 4635 9552 4634 9552 4587 9552 4587 9553 4634 9553 4638 9553 4587 9554 4638 9554 4637 9554 4991 9555 4994 9555 4533 9555 4533 9556 4994 9556 4995 9556 4533 9557 4995 9557 4557 9557 4920 9558 4908 9558 4529 9558 4529 9559 4908 9559 4907 9559 4529 9560 4907 9560 4924 9560 4924 9561 4926 9561 4529 9561 4529 9562 4926 9562 4906 9562 4529 9563 4906 9563 4894 9563 4648 9564 4900 9564 4910 9564 4996 9565 4997 9565 4533 9565 4533 9566 4997 9566 4998 9566 4598 9567 4533 9567 4582 9567 4585 9568 4588 9568 4533 9568 4533 9569 4588 9569 4586 9569 4533 9570 4586 9570 4531 9570 4531 9571 4586 9571 4587 9571 4531 9572 4587 9572 4529 9572 4533 9573 4778 9573 4999 9573 4998 9574 5000 9574 4533 9574 4533 9575 5000 9575 5001 9575 4533 9576 5001 9576 4993 9576 4574 9577 4575 9577 4533 9577 4533 9578 4575 9578 4576 9578 4533 9579 4576 9579 4573 9579 4910 9580 4911 9580 4529 9580 4529 9581 4911 9581 4918 9581 4572 9582 4571 9582 4533 9582 4533 9583 4571 9583 4570 9583 4533 9584 4570 9584 4569 9584 4551 9585 4581 9585 4533 9585 4533 9586 4581 9586 4584 9586 4533 9587 4584 9587 4589 9587 4624 9588 4619 9588 4625 9588 4625 9589 4619 9589 4626 9589 4624 9590 4623 9590 4619 9590 4619 9591 4623 9591 4622 9591 4619 9592 4622 9592 4618 9592 4637 9593 4643 9593 4587 9593 4587 9594 4643 9594 4642 9594 4587 9595 4642 9595 4640 9595 4529 9596 4587 9596 4910 9596 4910 9597 4587 9597 4644 9597 4910 9598 4644 9598 4648 9598 4557 9599 4556 9599 4533 9599 4533 9600 4556 9600 4580 9600 4533 9601 4580 9601 4579 9601 4918 9602 4916 9602 4529 9602 4529 9603 4916 9603 4915 9603 4529 9604 4915 9604 4914 9604 4914 9605 4922 9605 4529 9605 4529 9606 4922 9606 4921 9606 4529 9607 4921 9607 4920 9607 4569 9608 4568 9608 4533 9608 4533 9609 4568 9609 4567 9609 4533 9610 4567 9610 4566 9610 4596 9611 4595 9611 4533 9611 4533 9612 4595 9612 4583 9612 4533 9613 4583 9613 4582 9613 4629 9614 4628 9614 4619 9614 4619 9615 4628 9615 4627 9615 4619 9616 4627 9616 4626 9616 5002 9617 5003 9617 4533 9617 5004 9618 5005 9618 4533 9618 4533 9619 5005 9619 5006 9619 4533 9620 5006 9620 4996 9620 4579 9621 4578 9621 4533 9621 4533 9622 4578 9622 4577 9622 4533 9623 4577 9623 4574 9623 4533 9624 4592 9624 4593 9624 4602 9625 4610 9625 4587 9625 4587 9626 4610 9626 4631 9626 4587 9627 4631 9627 4619 9627 4619 9628 4631 9628 4630 9628 4619 9629 4630 9629 4629 9629 4622 9630 4621 9630 4618 9630 4618 9631 4621 9631 4620 9631 4618 9632 4620 9632 4617 9632 4617 9633 4620 9633 4616 9633 4640 9634 4639 9634 4587 9634 4587 9635 4639 9635 4645 9635 4587 9636 4645 9636 4644 9636 5003 9637 5007 9637 4533 9637 4533 9638 5007 9638 5008 9638 4533 9639 5008 9639 5004 9639 4589 9640 4590 9640 4533 9640 4533 9641 4590 9641 4591 9641 4533 9642 4591 9642 4592 9642 4593 9643 4594 9643 4533 9643 4533 9644 4594 9644 4597 9644 4533 9645 4597 9645 4596 9645 4999 9646 5009 9646 4533 9646 4533 9647 5009 9647 5010 9647 4533 9648 5010 9648 5011 9648 5011 9649 5012 9649 4533 9649 4533 9650 5012 9650 5013 9650 4533 9651 5013 9651 5014 9651 5014 9652 5015 9652 4533 9652 4533 9653 5015 9653 5016 9653 4533 9654 5016 9654 5002 9654 4497 9655 587 9655 4499 9655 4499 9656 587 9656 4500 9656 4506 9657 4509 9657 587 9657 587 9658 4509 9658 4508 9658 587 9659 4508 9659 588 9659 4497 9660 4496 9660 587 9660 587 9661 4496 9661 4527 9661 587 9662 4527 9662 4503 9662 4503 9663 4502 9663 587 9663 587 9664 4502 9664 4504 9664 587 9665 4504 9665 4506 9665 4999 9666 5017 9666 5018 9666 4983 9667 5019 9667 4984 9667 5020 9668 5021 9668 5022 9668 5022 9669 5021 9669 5023 9669 5022 9670 5023 9670 5024 9670 5025 9671 5026 9671 5027 9671 5027 9672 5026 9672 5028 9672 5027 9673 5028 9673 5029 9673 5030 9674 5031 9674 5020 9674 5020 9675 5031 9675 5032 9675 5020 9676 5032 9676 5021 9676 5033 9677 5034 9677 5035 9677 5033 9678 4979 9678 4986 9678 4987 9679 5036 9679 4986 9679 4986 9680 5036 9680 5037 9680 4986 9681 5037 9681 5033 9681 5033 9682 5037 9682 5038 9682 5033 9683 5038 9683 5034 9683 4979 9684 5033 9684 4980 9684 4980 9685 5033 9685 5039 9685 4980 9686 5039 9686 4981 9686 5019 9687 4983 9687 5039 9687 5039 9688 4983 9688 4982 9688 5039 9689 4982 9689 4981 9689 4985 9690 5040 9690 4976 9690 4976 9691 5040 9691 5041 9691 4978 9692 4977 9692 5042 9692 5042 9693 4977 9693 4975 9693 5042 9694 4975 9694 5041 9694 5041 9695 4975 9695 4974 9695 5041 9696 4974 9696 4976 9696 4969 9697 4968 9697 5043 9697 5043 9698 4968 9698 4973 9698 5043 9699 4973 9699 5042 9699 5042 9700 4973 9700 4972 9700 5042 9701 4972 9701 4978 9701 4967 9702 4966 9702 5018 9702 5018 9703 4966 9703 4970 9703 5018 9704 4970 9704 5044 9704 4967 9705 5018 9705 4963 9705 4963 9706 5018 9706 5017 9706 4963 9707 5017 9707 4964 9707 4964 9708 5017 9708 4965 9708 4965 9709 5017 9709 4775 9709 4965 9710 4775 9710 4776 9710 4999 9711 4778 9711 4779 9711 4999 9712 4779 9712 5017 9712 5017 9713 4779 9713 4780 9713 5017 9714 4780 9714 4775 9714 5045 9715 5012 9715 5011 9715 5045 9716 5011 9716 5044 9716 5044 9717 5011 9717 5010 9717 5044 9718 5010 9718 5018 9718 5018 9719 5010 9719 5009 9719 5018 9720 5009 9720 4999 9720 5012 9721 5045 9721 5013 9721 5013 9722 5045 9722 5046 9722 5013 9723 5046 9723 5014 9723 5047 9724 5002 9724 5048 9724 5048 9725 5002 9725 5016 9725 5048 9726 5016 9726 5046 9726 5046 9727 5016 9727 5015 9727 5046 9728 5015 9728 5014 9728 5004 9729 5008 9729 5027 9729 5027 9730 5008 9730 5007 9730 5027 9731 5007 9731 5047 9731 5047 9732 5007 9732 5003 9732 5047 9733 5003 9733 5002 9733 5029 9734 5049 9734 5027 9734 5027 9735 5049 9735 5050 9735 5027 9736 5050 9736 5004 9736 5004 9737 5050 9737 5051 9737 5004 9738 5051 9738 5005 9738 5035 9739 5030 9739 5033 9739 5033 9740 5030 9740 5020 9740 5033 9741 5020 9741 5039 9741 5039 9742 5020 9742 5022 9742 5039 9743 5022 9743 5019 9743 5019 9744 5022 9744 5040 9744 5019 9745 5040 9745 4984 9745 4984 9746 5040 9746 4985 9746 5024 9747 5025 9747 5022 9747 5022 9748 5025 9748 5027 9748 5022 9749 5027 9749 5040 9749 5040 9750 5027 9750 5047 9750 5040 9751 5047 9751 5041 9751 5041 9752 5047 9752 5048 9752 5041 9753 5048 9753 5042 9753 5042 9754 5048 9754 5046 9754 5042 9755 5046 9755 5043 9755 5043 9756 5046 9756 5045 9756 5043 9757 5045 9757 4969 9757 4969 9758 5045 9758 5044 9758 4969 9759 5044 9759 4971 9759 4971 9760 5044 9760 4970 9760 4962 9761 4767 9761 5052 9761 5053 9762 4987 9762 4988 9762 5054 9763 5055 9763 5056 9763 5056 9764 5053 9764 5054 9764 5054 9765 5053 9765 4988 9765 5054 9766 4988 9766 5057 9766 5057 9767 4988 9767 4989 9767 5057 9768 4989 9768 5058 9768 5058 9769 4989 9769 5052 9769 5052 9770 4989 9770 4990 9770 5052 9771 4990 9771 4962 9771 4403 9772 699 9772 4405 9772 4405 9773 699 9773 698 9773 4429 9774 4427 9774 699 9774 4403 9775 4402 9775 699 9775 699 9776 4402 9776 4425 9776 699 9777 4425 9777 4424 9777 4424 9778 4391 9778 699 9778 699 9779 4391 9779 4390 9779 699 9780 4390 9780 4429 9780 4427 9781 4394 9781 699 9781 699 9782 4394 9782 4393 9782 699 9783 4393 9783 4406 9783 5059 9784 5060 9784 5061 9784 5006 9785 5062 9785 5063 9785 4352 9786 5064 9786 4353 9786 4353 9787 5064 9787 4354 9787 3505 9788 4554 9788 4358 9788 4358 9789 4554 9789 5064 9789 4358 9790 5064 9790 4351 9790 4351 9791 5064 9791 4352 9791 5065 9792 4356 9792 5064 9792 5064 9793 4356 9793 4355 9793 5064 9794 4355 9794 4354 9794 5066 9795 4346 9795 5067 9795 5067 9796 4346 9796 4350 9796 5067 9797 4350 9797 5065 9797 5065 9798 4350 9798 4357 9798 5065 9799 4357 9799 4356 9799 4343 9800 4338 9800 5068 9800 4338 9801 4337 9801 5068 9801 5068 9802 4337 9802 4348 9802 5068 9803 4348 9803 5066 9803 5066 9804 4348 9804 4347 9804 5066 9805 4347 9805 4346 9805 4998 9806 4997 9806 5063 9806 5063 9807 4997 9807 4996 9807 5063 9808 4996 9808 5006 9808 4992 9809 4993 9809 5069 9809 5069 9810 4993 9810 5070 9810 4553 9811 4555 9811 5071 9811 5071 9812 4555 9812 4557 9812 4557 9813 4995 9813 5071 9813 5071 9814 4995 9814 4994 9814 5071 9815 4994 9815 5069 9815 5069 9816 4994 9816 4991 9816 5069 9817 4991 9817 4992 9817 5059 9818 5061 9818 5072 9818 5062 9819 5072 9819 5063 9819 5063 9820 5072 9820 5061 9820 5063 9821 5061 9821 4998 9821 4998 9822 5061 9822 5073 9822 4998 9823 5073 9823 5000 9823 5000 9824 5073 9824 5070 9824 5000 9825 5070 9825 5001 9825 5001 9826 5070 9826 4993 9826 4342 9827 4343 9827 5074 9827 5074 9828 4343 9828 5068 9828 5074 9829 5068 9829 5075 9829 5075 9830 5068 9830 5076 9830 4554 9831 4553 9831 5064 9831 5064 9832 4553 9832 5071 9832 5064 9833 5071 9833 5065 9833 5065 9834 5071 9834 5069 9834 5065 9835 5069 9835 5067 9835 5067 9836 5069 9836 5070 9836 5067 9837 5070 9837 5066 9837 5066 9838 5070 9838 5073 9838 5066 9839 5073 9839 5068 9839 5068 9840 5073 9840 5061 9840 5068 9841 5061 9841 5076 9841 5076 9842 5061 9842 5060 9842 5029 9843 5028 9843 5077 9843 5077 9844 5025 9844 5024 9844 5026 9845 5025 9845 5077 9845 5028 9846 5026 9846 5077 9846 5078 9847 5049 9847 5079 9847 5079 9848 5049 9848 5029 9848 5079 9849 5029 9849 5077 9849 5005 9850 5051 9850 5078 9850 5078 9851 5051 9851 5050 9851 5078 9852 5050 9852 5049 9852 4767 9853 3987 9853 5052 9853 5052 9854 3987 9854 3986 9854 3986 9855 3985 9855 5052 9855 5052 9856 3985 9856 3984 9856 5052 9857 3984 9857 3983 9857 5057 9858 5058 9858 3989 9858 3989 9859 5058 9859 5052 9859 3989 9860 5052 9860 3988 9860 3988 9861 5052 9861 3983 9861 4769 9862 3979 9862 4767 9862 4767 9863 3979 9863 3978 9863 4767 9864 3978 9864 3987 9864 3973 9865 3972 9865 4771 9865 4771 9866 3972 9866 3982 9866 4771 9867 3982 9867 4769 9867 4769 9868 3982 9868 3981 9868 4769 9869 3981 9869 3980 9869 3980 9870 3976 9870 4769 9870 4769 9871 3976 9871 3975 9871 4769 9872 3975 9872 3979 9872 4771 9873 4763 9873 3973 9873 3973 9874 4763 9874 4765 9874 3973 9875 4765 9875 4766 9875 3922 9876 3973 9876 3919 9876 3919 9877 3973 9877 4766 9877 3919 9878 4766 9878 3920 9878 3922 9879 3936 9879 3973 9879 3973 9880 3936 9880 3935 9880 3973 9881 3935 9881 3934 9881 3965 9882 3964 9882 3934 9882 3934 9883 3964 9883 3969 9883 3969 9884 3971 9884 3934 9884 3934 9885 3971 9885 3974 9885 3934 9886 3974 9886 3973 9886 3933 9887 3932 9887 3952 9887 3952 9888 3932 9888 3941 9888 3941 9889 3946 9889 3952 9889 3952 9890 3946 9890 3945 9890 3952 9891 3945 9891 3943 9891 3952 9892 3968 9892 3933 9892 3933 9893 3968 9893 3967 9893 3933 9894 3967 9894 3934 9894 3934 9895 3967 9895 3966 9895 3934 9896 3966 9896 3965 9896 2776 9897 3958 9897 3937 9897 3937 9898 3958 9898 3957 9898 3937 9899 3957 9899 3938 9899 3957 9900 3956 9900 3938 9900 3938 9901 3956 9901 3955 9901 3938 9902 3955 9902 3947 9902 3947 9903 3955 9903 3942 9903 3942 9904 3955 9904 3959 9904 3942 9905 3959 9905 3960 9905 3960 9906 3961 9906 3942 9906 3942 9907 3961 9907 3962 9907 3942 9908 3962 9908 3943 9908 3943 9909 3962 9909 3953 9909 3943 9910 3953 9910 3952 9910 5057 9911 3989 9911 5054 9911 5054 9912 3989 9912 3378 9912 5054 9913 3378 9913 5055 9913 5055 9914 3378 9914 4344 9914 5055 9915 4344 9915 4345 9915 4345 9916 4341 9916 5055 9916 5055 9917 4341 9917 4340 9917 5055 9918 4340 9918 4342 9918 5080 9919 5081 9919 5082 9919 5082 9920 5083 9920 5084 9920 5084 9921 5083 9921 5085 9921 5085 9922 5086 9922 5084 9922 5084 9923 5086 9923 5087 9923 5084 9924 5087 9924 5088 9924 5089 9925 5080 9925 5090 9925 5090 9926 5080 9926 5082 9926 5090 9927 5082 9927 5091 9927 5091 9928 5082 9928 5084 9928 616 9929 614 9929 5087 9929 602 9930 601 9930 5088 9930 599 9931 598 9931 5084 9931 5088 9932 601 9932 5084 9932 5084 9933 601 9933 600 9933 5084 9934 600 9934 599 9934 598 9935 597 9935 5084 9935 5084 9936 597 9936 595 9936 5084 9937 595 9937 5091 9937 5091 9938 595 9938 527 9938 5091 9939 527 9939 526 9939 614 9940 612 9940 5087 9940 5087 9941 612 9941 605 9941 5087 9942 605 9942 5088 9942 5088 9943 605 9943 603 9943 5088 9944 603 9944 602 9944 5086 9945 622 9945 620 9945 5086 9946 620 9946 5087 9946 5087 9947 620 9947 618 9947 5087 9948 618 9948 616 9948 626 9949 5085 9949 627 9949 627 9950 5085 9950 628 9950 626 9951 608 9951 5085 9951 5085 9952 608 9952 607 9952 5085 9953 607 9953 5086 9953 5086 9954 607 9954 610 9954 5086 9955 610 9955 622 9955 628 9956 5085 9956 625 9956 625 9957 5085 9957 5083 9957 625 9958 5083 9958 629 9958 708 9959 635 9959 5082 9959 5082 9960 635 9960 633 9960 5082 9961 633 9961 5083 9961 5083 9962 633 9962 632 9962 5083 9963 632 9963 629 9963 711 9964 724 9964 5081 9964 724 9965 723 9965 5081 9965 5081 9966 723 9966 725 9966 5081 9967 725 9967 5082 9967 5082 9968 725 9968 709 9968 5082 9969 709 9969 708 9969 716 9970 5080 9970 727 9970 727 9971 5080 9971 733 9971 716 9972 714 9972 5080 9972 5080 9973 714 9973 713 9973 5080 9974 713 9974 5081 9974 5081 9975 713 9975 712 9975 5081 9976 712 9976 711 9976 505 9977 5080 9977 508 9977 508 9978 5080 9978 5089 9978 505 9979 498 9979 5080 9979 5080 9980 498 9980 503 9980 5080 9981 503 9981 733 9981 511 9982 510 9982 5089 9982 5089 9983 510 9983 509 9983 5089 9984 509 9984 508 9984 513 9985 520 9985 5090 9985 5090 9986 520 9986 519 9986 5090 9987 519 9987 5089 9987 5089 9988 519 9988 512 9988 5089 9989 512 9989 511 9989 526 9990 524 9990 5091 9990 5091 9991 524 9991 523 9991 5091 9992 523 9992 5090 9992 5090 9993 523 9993 514 9993 5090 9994 514 9994 513 9994 4133 9995 5092 9995 4134 9995 5092 9996 4133 9996 4132 9996 4114 9997 4134 9997 5092 9997 4131 9998 4130 9998 5092 9998 5092 9999 4130 9999 4129 9999 5093 10000 5092 10000 5094 10000 573 10001 4468 10001 4092 10001 4092 10002 4468 10002 4469 10002 4092 10003 4469 10003 4091 10003 4091 10004 4469 10004 4471 10004 4091 10005 4471 10005 5094 10005 5094 10006 4471 10006 5095 10006 5094 10007 5095 10007 5093 10007 4124 10008 4123 10008 5094 10008 5094 10009 4123 10009 4122 10009 5094 10010 4122 10010 4091 10010 5092 10011 4128 10011 4125 10011 4124 10012 5094 10012 4125 10012 4125 10013 5094 10013 5092 10013 4129 10014 4128 10014 5092 10014 4132 10015 4131 10015 5092 10015 5092 10016 4117 10016 4115 10016 4115 10017 4114 10017 5092 10017 5096 10018 4117 10018 5092 10018 5096 10019 5097 10019 4117 10019 4117 10020 5097 10020 5098 10020 4117 10021 5098 10021 4118 10021 4118 10022 5098 10022 5099 10022 4118 10023 5099 10023 4121 10023 4471 10024 3779 10024 4165 10024 4471 10025 4165 10025 5095 10025 5095 10026 4165 10026 4164 10026 5095 10027 4164 10027 5093 10027 4164 10028 4163 10028 5093 10028 5093 10029 4163 10029 4162 10029 5093 10030 4162 10030 5092 10030 5092 10031 4162 10031 4149 10031 5092 10032 4149 10032 5096 10032 5096 10033 4149 10033 4148 10033 5096 10034 4148 10034 5097 10034 5097 10035 4148 10035 4153 10035 5097 10036 4153 10036 5098 10036 5098 10037 4153 10037 4152 10037 5098 10038 4152 10038 5099 10038 5099 10039 4152 10039 4146 10039 5099 10040 4146 10040 4121 10040 5006 10041 5005 10041 5062 10041 5062 10042 5005 10042 5078 10042 5062 10043 5078 10043 5072 10043 5072 10044 5078 10044 5079 10044 5072 10045 5079 10045 5059 10045 5059 10046 5079 10046 5077 10046 5059 10047 5077 10047 5060 10047 5060 10048 5077 10048 5100 10048 5060 10049 5100 10049 5076 10049 5076 10050 5100 10050 5101 10050 5076 10051 5101 10051 5075 10051 5075 10052 5101 10052 5102 10052 5075 10053 5102 10053 5074 10053 5074 10054 5102 10054 5103 10054 5074 10055 5103 10055 4342 10055 4342 10056 5103 10056 5055 10056 5023 10057 5021 10057 5077 10057 5032 10058 5031 10058 5077 10058 5034 10059 5104 10059 5035 10059 5102 10060 5101 10060 5104 10060 5104 10061 5101 10061 5100 10061 5104 10062 5100 10062 5077 10062 5102 10063 5104 10063 5103 10063 5103 10064 5104 10064 5034 10064 5103 10065 5034 10065 5055 10065 5034 10066 5038 10066 5055 10066 5055 10067 5038 10067 5037 10067 5055 10068 5037 10068 5056 10068 5056 10069 5037 10069 5036 10069 5056 10070 5036 10070 5053 10070 5053 10071 5036 10071 4987 10071 5077 10072 5031 10072 5104 10072 5104 10073 5031 10073 5030 10073 5104 10074 5030 10074 5035 10074 5021 10075 5032 10075 5077 10075 5024 10076 5023 10076 5077 10076

+
+
+ 1 +
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_E2M3.dae b/URDFs/sr_description/meshes/components/forearm/forearm_E2M3.dae new file mode 100644 index 0000000..f645a81 --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_E2M3.dae @@ -0,0 +1,202 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///home/guihome/Projets/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_forearm_2011-11-08_envelop_optimized.blend + + 2012-07-09T16:29:53.272413 + 2012-07-09T16:29:53.272436 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.16170 0.16170 0.16170 1 + + + 0.80848 0.80848 0.80848 1 + + + 0.45000 0.45000 0.45000 1 + + + 32.0 + + + 0.00000 0.00000 0.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.04392 0.04392 0.04392 1 + + + 0.21961 0.21961 0.21961 1 + + + 0.45000 0.45000 0.45000 1 + + + 32.0 + + + 0.00000 0.00000 0.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + + + + 7.17713 67.17487 115.17963 12.71432 66.39240 121.26300 17.66439 65.23273 129.38177 21.03388 64.20532 136.54459 23.42433 63.38120 142.56599 25.92417 62.39281 149.58356 28.56717 61.22050 158.01859 -8.39167 67.02483 116.25961 -20.11531 64.48545 134.63857 3.15658 67.48139 15.14060 -4.88166 67.36443 114.90471 0.22082 67.54895 113.18739 38.18585 55.74057 15.14060 43.16133 51.98325 15.14060 40.44064 54.12695 167.24660 -38.10755 55.74084 15.14060 -32.80664 59.02303 15.14060 -29.38590 60.80232 161.02853 32.28355 59.35379 167.24657 -14.83841 65.89346 124.39960 -43.08306 51.98356 15.14060 -36.37764 56.88723 167.24660 -31.98313 59.45261 167.38358 36.45566 56.88707 167.24660 -23.29976 63.40045 142.44263 -42.34181 52.71937 167.25885 -27.22552 61.80210 15.14060 27.30387 61.80191 15.14060 21.49008 64.05412 15.14060 9.36474 66.90607 15.14060 -9.28636 66.90614 15.14060 -3.07818 67.48142 15.14060 44.21853 51.08685 167.24660 -15.41501 65.76057 15.14060 -21.41171 64.05429 15.14060 15.49339 65.76045 15.14060 27.66826 58.50441 176.64101 32.72424 57.00769 176.64059 -32.64592 57.00793 176.64061 -29.16434 58.30711 176.64056 24.23318 61.92471 162.39059 -28.49260 59.99411 171.41660 -17.16329 64.74257 137.73648 22.04004 62.92275 153.65846 27.07872 60.68143 169.38948 -12.19347 66.11095 125.76254 16.67506 64.91975 136.18451 -23.41269 62.27091 159.36348 -42.12696 50.39385 176.64059 37.61055 53.90967 176.64058 42.20524 50.39355 176.64058 -37.53226 53.90995 176.64058 67.17487 -7.17712 115.17963 66.39240 -12.71432 121.26300 65.23273 -17.66438 129.38177 64.20532 -21.03387 136.54459 63.38121 -23.42432 142.56599 62.39281 -25.92416 149.58356 61.22050 -28.56716 158.01859 67.02483 8.39168 116.25961 47.78310 47.69076 167.24660 47.78310 47.69076 15.14060 64.48545 20.11531 134.63857 67.48139 -3.15657 15.14060 67.36443 4.88166 114.90471 67.54895 -0.22082 113.18739 55.74057 -38.18585 15.14060 51.98325 -43.16133 15.14060 54.12696 -40.44064 167.24660 55.74084 38.10755 15.14060 59.02303 32.80664 15.14060 60.80232 29.38591 161.02853 59.02279 -32.88496 15.14060 59.35379 -32.28355 167.24657 65.89346 14.83841 124.39960 51.98356 43.08307 15.14060 56.88723 36.37765 167.24660 59.45261 31.98314 167.38358 56.88708 -36.45565 167.24660 63.40044 23.29977 142.44263 52.71937 42.34181 167.25885 61.80210 27.22553 15.14060 61.80191 -27.30387 15.14060 64.05412 -21.49008 15.14060 66.90607 -9.36474 15.14060 66.90614 9.28636 15.14060 67.48142 3.07819 15.14060 51.08685 -44.21853 167.24660 65.76057 15.41502 15.14060 64.05429 21.41172 15.14060 65.76045 -15.49339 15.14060 58.50441 -27.66826 176.64101 57.00769 -32.72424 176.64059 57.00793 32.64592 176.64061 58.30711 29.16435 176.64056 46.48680 46.39446 176.64058 61.92471 -24.23318 162.39059 59.99411 28.49261 171.41660 64.74257 17.16329 137.73648 62.92276 -22.04003 153.65846 60.68143 -27.07871 169.38948 66.11095 12.19347 125.76254 64.91975 -16.67506 136.18451 62.27090 23.41270 159.36348 50.39385 42.12697 176.64059 53.90968 -37.61055 176.64058 50.39356 -42.20523 176.64058 53.90995 37.53226 176.64058 -7.17714 -67.17487 115.17963 -12.71433 -66.39240 121.26300 -17.66440 -65.23273 129.38177 -21.03389 -64.20532 136.54459 -23.42434 -63.38120 142.56599 -25.92418 -62.39281 149.58356 -28.56718 -61.22049 158.01859 8.39166 -67.02483 116.25961 47.69075 -47.78311 167.24660 47.69075 -47.78311 15.14060 20.11530 -64.48545 134.63857 -3.15659 -67.48139 15.14060 4.88165 -67.36443 114.90471 -0.22083 -67.54895 113.18739 -38.18586 -55.74056 15.14060 -46.47248 -46.48667 176.64058 -43.16134 -51.98324 15.14060 -40.44065 -54.12695 167.24660 38.10754 -55.74085 15.14060 32.80663 -59.02303 15.14060 29.38589 -60.80233 161.02853 -32.88497 -59.02278 15.14060 -32.28356 -59.35379 167.24657 14.83840 -65.89346 124.39960 43.08305 -51.98357 15.14060 36.37764 -56.88724 167.24660 31.98312 -59.45262 167.38358 -36.45567 -56.88707 167.24660 23.29976 -63.40045 142.44263 42.34180 -52.71938 167.25885 27.22552 -61.80211 15.14060 -27.30388 -61.80190 15.14060 -21.49009 -64.05412 15.14060 -9.36475 -66.90607 15.14060 9.28635 -66.90614 15.14060 3.07817 -67.48142 15.14060 -44.21854 -51.08684 167.24660 15.41500 -65.76057 15.14060 21.41171 -64.05429 15.14060 -15.49340 -65.76045 15.14060 -47.76879 -47.78297 15.14060 -47.76879 -47.78297 167.24660 -27.66827 -58.50440 176.64101 -32.72425 -57.00768 176.64059 32.64591 -57.00793 176.64061 29.16434 -58.30711 176.64056 46.39445 -46.48681 176.64058 -24.23319 -61.92471 162.39059 28.49259 -59.99412 171.41660 17.16327 -64.74257 137.73648 -22.04005 -62.92275 153.65846 -27.07873 -60.68143 169.38948 12.19346 -66.11095 125.76254 -16.67507 -64.91975 136.18451 23.41268 -62.27091 159.36348 42.12696 -50.39386 176.64059 -37.61056 -53.90966 176.64058 -42.20525 -50.39355 176.64058 37.53225 -53.90995 176.64058 -67.17487 7.17713 115.17963 -66.39240 12.71433 121.26300 -65.23273 17.66439 129.38177 -64.20532 21.03388 136.54459 -63.38120 23.42433 142.56599 -62.39281 25.92417 149.58356 -61.22050 28.56717 158.01859 -67.02483 -8.39167 116.25961 -64.48545 -20.11530 134.63857 -67.48139 3.15658 15.14060 -67.36443 -4.88165 114.90471 -67.54895 0.22083 113.18739 -55.74057 38.18586 15.14060 -46.48668 46.47248 176.64058 -51.98325 43.16134 15.14060 -54.12695 40.44065 167.24660 -55.74085 -38.10754 15.14060 -59.02303 -32.80663 15.14060 -60.80233 -29.38590 161.02853 -59.02279 32.88497 15.14060 -59.35379 32.28355 167.24657 -65.89346 -14.83840 124.39960 -51.98357 -43.08306 15.14060 -56.88724 -36.37764 167.24660 -59.45261 -31.98313 167.38358 -56.88707 36.45566 167.24660 -63.40045 -23.29976 142.44263 -52.71938 -42.34180 167.25885 -61.80210 -27.22552 15.14060 -61.80190 27.30388 15.14060 -64.05412 21.49009 15.14060 -66.90607 9.36475 15.14060 -66.90614 -9.28635 15.14060 -67.48142 -3.07818 15.14060 -51.08684 44.21854 167.24660 -65.76057 -15.41501 15.14060 -64.05429 -21.41171 15.14060 -65.76045 15.49339 15.14060 -47.78297 47.76878 15.14060 -47.78297 47.76878 167.24660 -58.50440 27.66827 176.64101 -57.00769 32.72424 176.64059 -57.00793 -32.64592 176.64061 -58.30711 -29.16434 176.64056 -61.92471 24.23319 162.39059 -59.99412 -28.49260 171.41660 -64.74257 -17.16328 137.73648 -62.92275 22.04004 153.65846 -60.68143 27.07872 169.38948 -66.11095 -12.19346 125.76254 -64.91975 16.67507 136.18451 -62.27091 -23.41269 159.36348 -50.39386 -42.12696 176.64059 -53.90967 37.61055 176.64058 -50.39355 42.20524 176.64058 -53.90995 -37.53225 176.64058 -0.00000 -0.04141 183.14099 -53.04635 28.57758 183.14099 42.57971 42.59416 183.14099 49.70814 34.80139 183.14099 -42.50149 42.59449 183.14099 38.99327 46.49711 183.14099 52.94740 26.79478 183.14099 -27.12306 52.60657 183.14099 -26.42374 56.95537 181.51089 -26.41711 55.36478 182.76747 -27.96705 53.92234 183.10143 27.76955 53.01282 183.14096 56.65474 26.52336 182.00500 29.68025 56.16982 181.47922 46.29370 41.69096 182.79930 50.40178 36.61524 182.79930 53.48724 30.86809 183.06616 30.49439 52.88017 183.15103 56.08867 29.61147 181.74065 36.96224 52.83199 180.40591 54.66233 26.50967 183.02849 28.48450 54.60997 182.92058 55.85140 32.00412 180.75549 45.58511 45.59955 180.40591 54.76171 31.60175 182.35567 36.60083 50.41629 182.79930 31.18587 54.07935 182.78909 32.00270 55.49564 181.40184 41.43193 49.40447 180.40591 37.38954 51.50259 181.83130 52.81748 36.97663 180.40591 51.48808 37.40394 181.83130 49.39000 41.44634 180.40591 47.29141 42.58905 181.83130 42.57462 47.30587 181.83130 41.67651 46.30817 182.79930 -41.59828 46.30848 182.79930 -36.52257 50.41656 182.79930 -45.50688 45.59989 180.40591 -56.35999 29.73378 181.23782 -46.21550 41.69129 182.79930 -49.31179 41.44670 180.40591 -51.40992 37.40432 181.83130 -36.88396 52.83226 180.40591 -47.21320 42.58939 181.83130 -54.58469 29.11433 182.82649 -31.92075 55.86233 180.75575 -54.41977 31.44848 182.57246 -38.91503 46.49739 183.14099 -37.31126 51.50286 181.83130 -28.94950 55.48401 182.43315 -49.62999 34.80175 183.14099 -52.73932 36.97702 180.40591 -53.47235 27.08091 183.14099 -31.50883 54.77682 182.35626 -56.85705 26.51505 181.50963 -30.77453 53.50130 183.05910 -41.35367 49.40477 180.40591 -55.40284 32.01741 181.40176 -50.32362 36.61562 182.79930 -29.59234 56.46819 181.23573 -55.13115 26.51292 182.91273 -42.49638 47.30618 181.83130 41.43156 -49.29733 180.40591 52.70990 -26.93727 183.14099 49.70789 -34.69430 183.14099 -41.59862 -46.20072 182.79930 -36.88435 -52.72454 180.40591 -46.21581 -41.58350 182.79930 -50.32389 -36.50779 182.79930 -42.50182 -42.48672 183.14099 50.40151 -36.50816 182.79930 42.57938 -42.48705 183.14099 52.81721 -36.86957 180.40591 -45.50722 -45.49211 180.40591 -31.10815 -53.97191 182.78937 -55.91732 -26.40268 182.37001 -56.37806 -29.56747 181.23541 37.38916 -51.39541 181.83130 -41.35403 -49.29702 180.40591 29.05555 -54.90498 182.69682 -26.42026 -55.11211 182.90039 -36.52294 -50.30884 182.79930 -55.42443 -28.59314 182.53864 26.49489 -54.56975 183.02905 -37.31164 -51.39515 181.83130 47.29109 -42.48195 181.83130 26.49623 -56.88210 181.31137 -29.08665 -54.64066 182.66721 36.96185 -52.72482 180.40591 53.64811 -30.85126 183.05443 51.48781 -37.29686 181.83130 49.38969 -41.33926 180.40591 26.49551 -55.88577 182.38503 -46.40469 -38.90030 183.14099 28.41980 -53.48039 183.11678 56.14689 -29.56754 181.48326 55.06837 -24.51105 182.85027 -28.02135 -52.61373 183.14099 31.99164 -55.75695 180.75525 45.58478 -45.49244 180.40591 -53.92846 -27.84713 183.09036 -52.73959 -36.86918 180.40591 29.61964 -55.86559 181.48270 -51.41019 -37.29649 181.83130 -53.40794 -30.75989 183.00000 38.99293 -46.38995 183.14099 46.29340 -41.58384 182.79930 -38.91537 -46.38966 183.14099 -49.31210 -41.33890 180.40591 31.76604 -54.97927 181.94653 -47.21351 -42.48161 181.83130 30.85221 -53.39272 183.05231 36.60046 -50.30911 182.79930 41.67618 -46.20103 182.79930 -54.68454 -31.49423 182.35703 -29.55766 -56.20232 181.49670 -55.76828 -31.90836 180.75568 54.93074 -28.19112 182.77557 -42.49672 -47.19842 181.83130 -31.92451 -55.38761 181.40184 -26.42233 -56.84108 181.50830 55.48079 -31.90999 181.40182 -30.41597 -52.77166 183.14325 42.57428 -47.19873 181.83130 56.93989 -26.40717 181.49879 -56.90122 -26.40343 181.30283 52.82664 -22.84011 183.14099 -51.87558 -30.50192 183.14099 29.23310 -14.16401 196.74178 10.76716 -13.86542 201.64290 21.39861 -14.07537 193.46414 27.46566 -14.16783 194.22713 28.38620 -14.16117 201.17918 28.55589 -14.16393 195.33972 26.57802 -14.08800 203.14841 26.09080 -14.14846 193.49142 29.12671 -29.98901 195.95773 28.15216 -30.70990 194.19757 29.69017 -29.98164 197.55649 25.48671 -30.31977 193.18286 27.11698 -30.73169 193.51234 21.12255 -28.88793 193.14224 21.49174 -35.58555 193.14104 15.37017 -19.99502 188.33481 -21.50867 -35.58535 193.14095 -27.01785 -30.10811 193.73959 -21.49532 -28.98937 193.14095 -28.13104 -30.71404 194.17503 -25.83329 -30.16364 193.28687 -29.20789 -30.24131 196.06596 -15.38700 -19.99488 188.33467 -27.60938 -14.16784 194.22713 -28.52991 -14.16118 201.17918 -29.57075 -14.16784 198.28780 -26.23451 -14.14847 193.49142 -28.69961 -14.16394 195.33972 -21.49527 -19.99485 193.14095 10.70515 -20.04278 200.90141 10.82763 -0.05496 198.86229 -8.13576 -19.99491 225.74516 -1.23421 -19.99494 228.09081 11.73820 -19.99501 222.46021 5.95719 -19.99498 226.90210 -5.97408 -19.99492 226.90208 1.21731 -19.99496 228.09081 -10.08011 -19.99495 224.25127 -11.75508 -19.99489 222.46017 11.60935 -27.98278 222.63715 10.06320 -19.99500 224.25133 -11.76637 -27.98262 222.47229 19.13893 -28.90956 212.83585 -19.56073 -29.16170 212.21548 28.61199 -30.50734 201.16966 -29.58549 -31.27479 199.48630 -28.62001 -31.02658 201.17633 -29.68513 -29.98092 198.69276 0.30527 -20.00591 213.14841 27.08075 -19.99508 203.18613 11.08792 -20.04278 202.32542 12.11914 -14.04642 203.06091 10.88063 -6.11725 201.96809 29.74393 -30.96025 198.37593 27.56346 -30.98839 192.29086 26.96834 -31.01417 183.14105 27.47483 -30.98838 185.86226 -18.46961 13.78698 210.56070 -21.49532 8.98936 185.94095 21.47847 8.98956 185.94104 -15.38701 -0.00513 188.33467 15.37016 -0.00497 188.33481 -6.75985 5.95628 226.09619 -19.33550 12.47244 210.99203 -8.13577 -0.00509 225.74516 -1.23421 -0.00506 228.09081 -0.00831 9.95958 224.84529 17.88496 10.46420 213.56055 3.46709 5.95633 227.33191 1.21730 -0.00504 228.09081 15.97012 12.39993 213.53569 10.52479 8.08447 223.68530 6.17142 8.18819 225.11351 18.30959 13.68390 210.69595 6.74287 5.95635 226.09621 17.12156 15.64486 209.27338 -3.48406 5.95630 227.33188 11.73820 -0.00499 222.46021 -10.60663 7.42227 223.74785 5.95718 -0.00502 226.90210 -5.97409 -0.00508 226.90208 -0.00849 5.95632 227.75179 -11.76637 7.98262 222.47229 -16.29367 12.62307 212.91107 -0.00853 8.18816 226.61609 -10.08011 -0.00506 224.25127 -17.75995 10.64507 213.63457 -6.18846 8.18812 225.11337 -16.56421 15.84821 208.96661 -11.75509 -0.00511 222.46017 0.49007 13.58403 220.12320 11.60934 7.98279 222.63715 13.68506 14.29911 211.31392 15.56888 14.94498 209.91623 12.05915 14.15369 213.03099 10.06319 -0.00500 224.25133 -14.86134 13.86502 212.05777 -13.91902 14.26721 211.63301 16.32755 15.88888 208.88428 15.13303 15.10267 208.11310 5.64490 14.28627 218.79785 14.31331 13.30281 213.88541 9.69361 11.31001 222.84903 -9.71062 11.30990 222.84898 -8.34798 13.16498 221.48550 14.46985 14.12300 211.98051 -14.33889 13.31698 213.88985 -5.66194 14.28621 218.79785 -34.98714 16.48372 183.14093 -33.10577 12.07831 191.39923 34.53139 14.69207 192.98807 33.88874 20.98234 194.50577 32.41469 12.07866 193.33626 -34.11060 23.48006 183.14093 30.25814 21.87187 198.92636 -33.77184 22.32010 194.39073 21.85608 22.07732 193.14104 21.50770 20.57482 193.14104 23.13377 23.71641 201.67004 -28.60559 23.35913 199.77370 24.55461 23.43409 201.78943 33.88875 15.98538 194.50578 15.59797 23.35947 198.69604 -18.99684 24.95138 199.29610 -26.98518 11.01389 183.14095 34.79623 22.32104 191.40607 22.85788 21.89442 183.14104 -30.21933 22.32220 198.88586 -34.42173 22.51174 192.94382 34.98300 20.98681 191.82214 34.96197 15.42036 191.40382 23.87253 24.13467 193.00703 -27.23467 14.78579 192.90695 25.57107 24.78537 199.41846 -25.79275 15.58531 191.14096 23.03796 22.73579 192.90016 -34.88922 21.86153 183.14093 -32.84603 11.88464 186.14093 -25.58381 24.60102 183.14095 -22.51073 15.58533 183.14095 -34.43144 14.03747 192.95056 26.59187 23.15303 201.38879 23.33065 24.83233 199.82864 -34.27790 13.29147 191.40555 29.74393 10.96026 198.37595 -23.89275 24.13781 193.00723 -30.61917 10.96507 191.61710 34.40472 22.51211 192.94395 -23.93853 23.68398 192.64093 33.33868 13.29117 194.06024 -17.29799 23.95095 200.95517 28.25447 24.81621 197.33972 18.98060 24.83241 199.82803 33.76669 22.32434 194.39757 -15.50301 16.01193 207.20984 15.79879 23.79947 193.05174 -22.86767 22.95523 193.00723 -32.11723 24.78397 192.54570 -29.20790 10.24129 196.06596 -18.36642 24.93965 193.14096 31.64711 11.23419 192.17297 34.86427 15.97845 192.65724 -23.93228 24.83510 199.83559 16.44956 23.47284 200.97322 -22.88459 24.13721 201.20796 21.49174 15.58557 193.14104 34.57374 22.71798 183.14105 -32.72465 24.58339 183.14093 16.12519 24.09111 199.50142 22.49384 15.58557 183.14104 25.77583 15.58558 193.14104 -34.67782 14.25417 186.14091 -16.12700 24.11815 199.45534 33.79073 14.87376 194.42796 -34.99195 15.41791 191.61719 -26.32878 24.97958 192.63542 -34.17892 20.98644 194.18275 22.47717 19.97113 192.66757 19.13892 8.90957 212.83585 31.19183 15.35321 197.90845 -21.50867 15.58534 193.14095 -32.14261 14.30173 196.42642 -33.12226 12.36458 193.11902 22.45810 21.41522 192.90215 32.11715 14.30390 196.41859 -34.98714 15.98502 185.94972 -25.04825 24.49428 192.64093 23.91961 23.68204 192.64053 27.44081 14.78608 191.64105 -22.25968 19.97178 192.98602 -29.67965 13.00989 199.79889 -32.04143 11.52369 192.49420 33.26425 12.18998 191.99510 26.57535 14.78608 183.14105 30.00427 11.64074 196.84277 -29.81092 11.35786 198.02908 -33.37424 23.89329 193.25732 -30.50339 12.80341 197.74428 -23.08364 22.60834 192.64093 -33.74797 14.31050 194.36797 28.41702 10.99705 193.69537 -25.79273 15.58530 183.14095 -22.54487 21.34432 192.64096 25.56682 24.60129 183.14105 29.19439 10.89103 195.25938 30.98028 11.09095 186.14105 -21.95733 21.40113 193.15567 -15.57331 23.22389 199.17764 -34.60375 15.97808 193.45425 34.58050 20.99011 193.45148 31.26432 14.32288 197.54027 -29.58550 11.27478 199.48630 -27.23466 14.78579 191.37495 32.83066 11.88598 186.14105 29.83044 11.42817 194.89198 23.94500 24.97985 198.68961 30.84862 12.28300 195.85397 21.12254 8.88795 193.14226 -34.82428 22.32404 191.40811 -31.17939 12.40927 195.65509 27.56345 10.98840 192.29086 27.21774 14.78604 192.90704 10.59446 14.28630 212.63663 -25.76259 24.35805 200.58351 -23.34137 22.76534 183.14095 34.27376 13.32267 192.13808 -30.99624 11.09043 186.14093 -27.01786 10.10810 193.73959 -25.20465 24.97959 192.99817 -34.98717 20.98197 191.39923 19.45186 12.02961 211.11261 -33.85997 23.85172 191.40547 -29.93584 11.48745 195.30075 34.97022 16.48409 183.14105 -21.49532 8.98935 193.14095 34.91357 15.23474 186.14105 -26.13454 15.58531 193.08066 -28.13105 10.71403 194.17503 30.32481 14.30800 199.00562 -28.03135 10.98810 186.06264 26.96833 11.01418 183.14105 27.11698 10.73170 193.51234 14.48270 14.55406 193.14102 -27.91828 24.87933 197.05643 30.97259 24.97988 191.39937 -19.56074 9.16169 212.21548 27.47482 10.98840 185.86226 15.54012 22.73135 199.99940 32.70765 24.58374 183.14105 33.34771 23.88522 193.25357 -17.63467 24.72850 199.51707 -27.12860 10.69656 193.52998 0.00466 14.05591 212.80209 26.31544 24.97986 192.63902 -25.83330 10.16362 193.28687 -15.98162 23.93966 193.10031 -34.87456 20.98974 192.65540 32.35282 24.78691 191.82372 -28.63495 10.96214 193.90012 -31.22917 15.24397 197.88651 -15.23129 15.28555 193.14096 25.02793 24.49245 192.64053 33.84240 23.85223 191.40535 25.18572 24.97985 193.00475 17.70369 24.81411 193.14102 25.77583 15.58558 191.14105 -27.20847 10.97332 192.92822 25.48670 10.31978 193.18286 29.69016 9.98165 197.55649 28.61198 10.50735 201.16966 28.15215 10.70991 194.19757 29.12670 9.98902 195.95773 -28.62002 11.02657 201.17633 -29.68514 9.98091 198.69276 -27.60927 -5.92986 194.22726 -29.27717 -5.93045 201.23506 -29.57054 -5.92983 198.28778 -26.23457 -5.95030 193.49120 -28.69948 -5.93367 195.33980 0.30526 0.00590 213.14841 -21.49528 -0.00516 193.14095 11.52659 -0.05496 202.76472 21.39854 -6.05413 193.66165 26.86400 -0.00491 203.22076 26.09085 -5.95029 193.49120 29.13345 -5.93044 201.40828 29.23282 -5.93372 196.74181 26.69490 -5.97775 203.18219 27.46555 -5.92985 194.22726 28.55576 -5.93366 195.33980 21.47848 -28.98956 185.94104 -21.49532 -28.98937 185.94095 -6.59310 -13.28688 217.65430 -11.67031 -0.05496 202.76472 -26.95345 -0.00519 203.19008 -26.83862 -5.97777 203.18219 -21.54226 -6.05414 193.66165 -11.02435 -6.11725 201.96809 -27.05070 -19.99482 203.06677 -10.91088 -13.86543 201.64290 -11.23163 -20.04278 202.32542 -12.26285 -14.04643 203.06091 -10.97135 -0.05497 198.86229 -10.84887 -20.04279 200.90141 -26.72174 -14.08801 203.14841 -21.54232 -14.07538 193.46414 -27.20847 -30.99855 192.92822 25.77584 -35.61081 191.14105 17.70370 -44.83934 193.14102 25.18573 -45.00508 193.00475 33.84242 -43.87745 191.40535 25.02794 -44.51768 192.64053 -15.23128 -35.31078 193.14096 -31.22916 -35.26921 197.88651 -28.63494 -30.98738 193.90012 30.32481 -34.33322 199.00562 32.35283 -44.81213 191.82372 -34.87455 -41.01498 192.65540 -15.98161 -43.96490 193.10031 -29.81091 -31.38310 198.02908 -29.67964 -33.03514 199.79889 26.31545 -45.00509 192.63902 0.00467 -34.08114 212.80209 -27.12859 -30.72179 193.52998 -17.63465 -44.75374 199.51707 30.25815 -41.89709 198.92636 33.34773 -43.91044 193.25357 32.70767 -44.60896 183.14105 -28.20184 -44.24278 198.90984 15.54013 -42.75657 199.99940 30.97260 -45.00511 191.39937 -27.91827 -44.90458 197.05643 14.48271 -34.57928 193.14102 -28.03135 -31.01334 186.06264 31.26433 -34.34811 197.54027 -26.13453 -35.61054 193.08066 34.91357 -35.25996 186.14105 34.97023 -36.50930 183.14105 -29.93584 -31.51268 195.30075 -33.85996 -43.87696 191.40547 19.45187 -32.05484 211.11261 -34.98717 -41.00721 191.39923 -25.20464 -45.00482 192.99817 -30.99623 -31.11567 186.14093 -30.50338 -32.82864 197.74428 34.27377 -33.34789 192.13808 -23.34136 -42.79058 183.14095 -25.76258 -44.38329 200.58351 10.59447 -34.31153 212.63663 27.21775 -34.81126 192.90704 -31.17938 -32.43450 195.65509 -34.82426 -42.34929 191.40811 30.84863 -32.30822 195.85397 23.94501 -45.00507 198.68961 29.83044 -31.45339 194.89198 32.83066 -31.91120 186.14105 -27.23465 -34.81103 191.37495 34.58051 -41.01534 193.45148 -34.60375 -36.00331 193.45425 -15.57330 -43.24913 199.17764 -21.95732 -41.42637 193.15567 30.98029 -31.11618 186.14105 29.19439 -30.91626 195.25938 32.11715 -34.32912 196.41859 25.56683 -44.62652 183.14105 -22.54486 -41.36955 192.64096 -25.79273 -35.61053 183.14095 28.41703 -31.02227 193.69537 -33.74796 -34.33574 194.36797 -23.08363 -42.63358 192.64093 -33.37422 -43.91854 193.25732 30.00428 -31.66597 196.84277 26.57535 -34.81130 183.14105 33.26425 -32.21520 191.99510 -32.04143 -31.54894 192.49420 -22.25967 -39.99702 192.98602 27.44082 -34.81131 191.64105 23.91962 -43.70727 192.64053 23.13378 -43.74164 201.67004 -25.04824 -44.51952 192.64093 -34.98713 -36.01025 185.94972 22.45811 -41.44044 192.90215 -33.12226 -32.38982 193.11902 -32.14260 -34.32697 196.42642 31.19184 -35.37843 197.90845 22.47717 -39.99635 192.66757 -34.17890 -41.01167 194.18275 -26.32877 -45.00481 192.63542 -34.99195 -35.44315 191.61719 33.79074 -34.89899 194.42796 -16.12698 -44.14339 199.45534 -34.67781 -34.27940 186.14091 25.77583 -35.61081 193.14104 22.49384 -35.61079 183.14104 16.12521 -44.11633 199.50142 -32.72463 -44.60863 183.14093 34.57375 -42.74320 183.14105 -22.88458 -44.16245 201.20796 16.44957 -43.49807 200.97322 -23.93227 -44.86033 199.83559 34.86427 -36.00367 192.65724 31.64712 -31.25940 192.17297 -18.36641 -44.96488 193.14096 -32.11722 -44.80920 192.54570 -22.86766 -42.98047 193.00723 15.79880 -43.82469 193.05174 -15.50300 -36.03717 207.20984 26.59188 -43.17825 201.38879 33.76669 -42.34956 194.39757 18.98061 -44.85764 199.82803 28.25448 -44.84144 197.33972 -17.29797 -43.97618 200.95517 33.33868 -33.31640 194.06024 -23.93851 -43.70922 192.64093 34.40473 -42.53733 192.94395 -30.61916 -30.99030 191.61710 -23.89274 -44.16305 193.00723 -34.27789 -33.31671 191.40555 33.88875 -36.01060 194.50578 23.33066 -44.85756 199.82864 26.64597 -44.28524 200.10481 -34.43144 -34.06271 192.95056 -22.51072 -35.61057 183.14095 -25.58380 -44.62625 183.14095 -32.84603 -31.90988 186.14093 -34.88921 -41.88677 183.14093 23.03797 -42.76101 192.90016 -25.79275 -35.61054 191.14096 -27.23466 -34.81103 192.90695 23.87254 -44.15989 193.00703 34.96198 -35.44559 191.40382 34.98302 -41.01204 191.82214 -34.42172 -42.53698 192.94382 -30.21932 -42.34743 198.88586 22.85789 -41.91965 183.14104 34.79625 -42.34627 191.40607 -26.98517 -31.03913 183.14095 -18.99683 -44.97661 199.29610 15.59798 -43.38470 198.69604 -28.60558 -43.38437 199.77370 21.50771 -40.60004 193.14104 21.85609 -42.10255 193.14104 -33.77182 -42.34534 194.39073 -34.11060 -43.50529 183.14093 32.41470 -32.10388 193.33626 33.88876 -41.00756 194.50577 34.53139 -34.71730 192.98807 -33.10577 -32.10356 191.39923 -34.98714 -36.50895 183.14093 -5.66193 -34.31144 218.79785 -14.33888 -33.34222 213.88985 14.46985 -34.14823 211.98051 5.64491 -34.31150 218.79785 -8.34797 -33.19022 221.48550 -9.71062 -31.33514 222.84898 9.69362 -31.33524 222.84903 14.31332 -33.32804 213.88541 15.13304 -35.12790 208.11310 16.32756 -35.91411 208.88428 -13.91902 -34.29244 211.63301 -14.86134 -33.89025 212.05777 12.05916 -34.17892 213.03099 15.56889 -34.97020 209.91623 13.68507 -34.32434 211.31392 0.49008 -33.60926 220.12320 -16.56420 -35.87345 208.96661 -6.18845 -28.21336 225.11337 -17.75994 -30.67030 213.63457 -0.00852 -28.21339 226.61609 -16.29366 -32.64831 212.91107 -0.00849 -25.98155 227.75179 -10.60662 -27.44750 223.74785 -3.48405 -25.98153 227.33188 17.12157 -35.67009 209.27338 6.74288 -25.98158 226.09621 18.30960 -33.70912 210.69595 6.17142 -28.21342 225.11351 10.52480 -28.10970 223.68530 15.97012 -32.42515 213.53569 3.46709 -25.98156 227.33191 17.88497 -30.48943 213.56055 -0.00830 -29.98481 224.84529 -19.33549 -32.49768 210.99203 -6.75984 -25.98152 226.09619 -18.46960 -33.81222 210.56070 29.88855 -2.94626 0.14060 -66.19735 -12.94628 0.14060 -29.81065 -2.94627 0.14060 -26.99805 -12.94628 0.14060 -62.80806 24.68092 0.14060 -59.55455 -31.64598 0.14060 -29.94435 1.05372 0.14060 25.07615 16.58062 10.14060 19.66905 -64.52888 0.14060 48.37674 47.16753 0.14060 19.94364 64.55222 0.14060 -52.20975 -42.68178 0.14060 -67.45364 -0.94628 0.14060 -24.99785 16.58122 10.14060 64.67866 -19.38757 0.14060 -64.60075 -19.38758 0.14060 27.90535 11.16503 0.14060 -29.54145 5.05372 0.14060 5.20453 42.74233 0.14060 -47.76075 -47.60588 0.14060 -10.21735 41.81262 0.14060 -29.84025 -2.63611 10.14060 -29.13205 7.05731 10.14060 15.23755 40.27813 0.14060 26.26944 62.24863 0.14060 29.88855 3.05372 0.14060 13.41974 66.21413 0.14060 28.92445 8.15497 0.14060 43.44324 51.74813 0.14060 27.94955 -10.94626 0.14060 -37.52395 -56.02908 0.14060 -29.13296 -6.94627 0.14060 60.12025 30.81873 0.14060 0.03895 43.05372 0.14060 67.35355 -4.94628 0.14060 0.03899 -29.94628 0.14060 -48.29885 47.16752 0.14060 65.02655 18.29823 0.14060 56.75694 36.65043 0.14060 9.95314 -28.26076 0.14060 -3.32206 -29.75738 0.14060 -27.41255 -12.04648 10.14060 67.47224 3.05372 0.14060 -23.42537 -18.63925 0.14060 56.23166 -37.34457 0.14060 -67.27565 5.05372 0.14060 26.53895 -14.00867 10.14060 -67.09715 -6.94627 0.14060 -0.30649 5.53084 10.54390 62.45715 -25.64087 0.14060 31.91315 -59.44657 0.14060 -52.75146 42.11822 0.14060 0.03894 67.55373 0.14060 -31.83525 -59.44658 0.14060 29.21085 -6.94627 0.14060 -26.49595 14.05002 0.14060 -32.25645 59.32642 0.14060 -43.36536 51.74812 0.14060 26.57375 14.05033 0.14060 23.16535 19.09483 10.14060 -42.84965 -52.06938 0.14060 66.27525 -12.94627 0.14060 13.23215 -66.14438 0.14060 -25.94143 -14.94691 10.14060 6.76282 67.21803 0.14060 -56.67905 36.65042 0.14060 -64.94865 18.29822 0.14060 -22.95787 19.31890 0.14060 23.03557 19.31910 0.14060 0.03895 25.24342 10.14060 62.88595 24.68093 0.14060 3.15977 43.10341 10.13999 -4.88601 -29.49477 10.14060 3.40005 -29.75737 0.14060 16.39395 39.49302 0.14060 52.28765 -42.68177 0.14060 -56.15375 -37.34458 0.14060 14.27375 30.47312 10.14060 0.03895 -67.44627 0.14060 47.83865 -47.60587 0.14060 -26.79235 13.47312 10.14060 -26.19156 62.24862 0.14060 28.09124 10.56283 10.14060 20.13022 -22.22500 10.14060 6.66763 -67.11997 0.14060 14.06305 29.80373 0.14060 -62.37925 -25.64088 0.14060 -38.00016 55.81462 0.14060 26.87055 13.47253 10.14060 32.79684 59.07212 15.14060 37.60185 -56.02907 0.14060 -6.58973 -67.11997 0.14060 28.67294 -8.89598 10.14060 -9.25984 42.20282 10.14001 -5.12663 42.74233 0.14060 1.83378 -29.89258 10.14060 15.78844 40.00233 10.14021 16.00825 -25.34277 0.14060 -19.86576 64.55222 0.14060 -6.68494 67.21803 0.14060 -13.98546 29.80534 0.14060 -66.44275 11.73412 0.14060 -60.04235 30.81872 0.14060 59.63245 -31.64597 0.14060 -28.84655 8.15478 0.14060 -25.83825 -62.28908 0.14060 -14.08326 27.71662 0.14060 21.34193 21.17674 10.14060 14.00565 28.40123 0.14060 24.72693 -16.99040 10.14060 17.06925 38.26920 0.14060 -17.09755 37.57352 0.14060 -8.48113 -28.71097 10.14060 -18.67477 -23.39396 0.14060 32.33434 59.32643 0.14060 -17.05125 37.03053 10.14291 -14.19585 30.47311 10.14060 38.07804 55.81463 0.14060 13.97235 29.10572 10.14060 29.09395 7.52404 10.14060 -29.37345 -5.85473 10.14060 21.26152 -21.15010 0.14060 -3.08271 43.10331 10.13999 -28.01435 10.56122 10.14060 29.97205 2.05655 10.14060 -28.56105 -9.00385 10.14060 4.49238 -29.52047 10.25291 52.82935 42.11823 0.14060 -6.64069 -29.19318 0.14060 16.89603 36.20391 10.14000 30.02915 -0.71470 10.14060 -13.34186 66.21413 0.14060 -19.59114 -64.52888 0.14060 42.92755 -52.06937 0.14060 10.29525 41.81262 0.14060 25.44953 -15.89310 0.14060 -13.15425 -66.14438 0.14060 -17.22932 -24.47799 10.14060 -20.79073 21.64364 0.14060 -1.75515 -29.89258 10.14060 -22.10432 -20.18680 10.14060 -16.81815 36.20392 10.14292 -27.82755 11.16482 0.14060 66.52065 11.73413 0.14060 9.33692 42.20303 10.14001 17.17624 37.39723 10.14021 14.43386 27.07011 0.14060 -15.21455 40.37392 10.14000 -22.84564 19.45203 10.14060 29.37685 -6.21435 10.14060 14.45012 -26.25819 10.14060 14.16115 27.71701 10.14060 -29.71885 3.85807 10.14060 -29.95585 0.61422 10.14060 7.99297 -28.87258 10.14060 -16.72595 38.92103 0.14060 -16.38056 39.54288 10.13363 -12.98475 -26.97188 0.14060 -17.01304 38.32173 10.14054 16.83693 39.01018 10.13958 25.91615 -62.28907 0.14060 + + + + + + + + + + 0.68052 0.73273 -0.00000 0.60264 0.79802 -0.00047 0.62693 0.77908 0.00023 0.68979 0.72401 -0.00053 0.56939 0.82207 0.00028 0.52584 0.85058 -0.00043 0.50894 0.86080 0.00012 0.44952 0.89327 -0.00034 0.44503 0.89551 -0.00016 0.36123 0.93248 0.00060 0.32582 0.94543 0.00005 0.41162 0.91135 -0.00231 0.36938 0.92928 -0.00070 0.29393 0.95583 -0.00117 0.27368 0.96182 -0.00017 0.18375 0.98297 0.00105 0.23217 0.97267 -0.00262 0.09228 0.99573 0.00191 0.14284 0.98974 -0.00271 0.00000 1.00000 0.00306 0.05442 0.99852 -0.00252 -0.03596 0.99935 0.00052 -0.09227 0.99573 -0.00050 -0.09642 0.99534 -0.00032 -0.18374 0.98297 0.00047 -0.17320 0.98489 -0.00028 -0.27367 0.96182 0.00027 -0.25903 0.96587 -0.00067 -0.36123 0.93248 0.00055 -0.32646 0.94521 -0.00180 -0.44574 0.89516 -0.00047 -0.39129 0.92027 0.00051 -0.52643 0.85022 0.00045 -0.46114 0.88733 -0.00001 -0.50413 0.86363 -0.00078 -0.60263 0.79802 0.00084 -0.57281 0.81969 -0.00117 -0.66764 0.74449 -0.00035 -0.67298 0.73966 0.00000 0.67703 0.71061 0.19148 0.49989 0.84550 0.18771 0.52488 0.82786 0.19786 0.55933 0.80754 0.18718 0.59576 0.77851 0.19749 0.61570 0.76512 0.18842 0.66930 0.71658 0.19633 -0.49956 0.84573 0.18758 -0.65639 0.72977 0.19128 -0.52487 0.82786 0.19787 -0.56254 0.80554 0.18616 -0.59466 0.77708 0.20624 -0.66031 0.72526 0.19490 0.01230 0.98966 0.14288 0.01279 0.99230 0.12317 0.01018 0.99291 0.11845 0.00620 0.99531 0.09658 0.00001 0.99353 0.11354 0.00001 0.99353 0.11354 0.00000 0.99353 0.11355 0.00000 0.99353 0.11355 0.27016 0.96089 0.06085 0.25112 0.96341 0.09375 -0.00331 0.95173 0.30692 -0.00135 0.95774 0.28764 0.21603 0.97471 0.05715 0.20726 0.97573 0.07067 0.20216 0.97715 0.06561 0.17974 0.98169 0.06300 0.15620 0.98561 0.06468 0.15590 0.98543 0.06801 0.12693 0.98985 0.06400 -0.07019 0.99524 0.06763 -0.10847 0.99274 0.05208 -0.11523 0.99118 0.06545 -0.14826 0.98717 0.05934 -0.16060 0.98444 0.07133 -0.16570 0.98406 0.06458 -0.22155 0.97308 0.06348 -0.24276 0.96676 0.08030 -0.20458 0.97114 0.12265 0.27442 0.92692 0.25597 0.32355 0.92147 0.21495 -0.00406 0.98429 0.17650 -0.00547 0.98303 0.18339 -0.38248 0.89973 0.21022 -0.33855 0.90728 0.24946 0.73273 -0.68052 0.00000 0.79802 -0.60264 -0.00047 0.77908 -0.62693 0.00023 0.72401 -0.68979 -0.00053 0.82207 -0.56939 0.00028 0.85021 -0.52644 -0.00042 0.86080 -0.50894 0.00014 0.89327 -0.44952 -0.00034 0.89516 -0.44575 -0.00019 0.93248 -0.36123 0.00060 0.94543 -0.32582 0.00005 0.91135 -0.41162 -0.00231 0.92928 -0.36938 -0.00070 0.95583 -0.29393 -0.00117 0.96182 -0.27368 -0.00017 0.98297 -0.18375 0.00105 0.97267 -0.23217 -0.00262 0.99573 -0.09228 0.00191 0.98974 -0.14284 -0.00271 1.00000 -0.00000 0.00306 0.99852 -0.05442 -0.00252 0.99935 0.03596 0.00052 0.99573 0.09227 -0.00050 0.99534 0.09642 -0.00032 0.98297 0.18374 0.00047 0.98489 0.17320 -0.00028 0.96182 0.27367 0.00027 0.96587 0.25903 -0.00067 0.93248 0.36123 0.00055 0.94521 0.32646 -0.00180 0.89516 0.44574 -0.00047 0.92027 0.39129 0.00051 0.85022 0.52643 0.00045 0.88733 0.46114 -0.00001 0.86363 0.50413 -0.00078 0.79802 0.60263 0.00084 0.81969 0.57281 -0.00117 0.73901 0.67369 -0.00029 0.73489 0.67819 0.00000 0.71061 -0.67703 0.19148 0.84550 -0.49989 0.18771 0.82786 -0.52488 0.19786 0.80754 -0.55933 0.18718 0.77851 -0.59576 0.19749 0.76512 -0.61570 0.18842 0.71658 -0.66930 0.19633 0.84573 0.49956 0.18758 0.72394 0.66279 0.19136 0.82786 0.52487 0.19787 0.80554 0.56254 0.18616 0.77708 0.59466 0.20624 0.72072 0.66556 0.19389 0.98966 -0.01230 0.14288 0.99230 -0.01279 0.12317 0.99291 -0.01018 0.11845 0.99531 -0.00620 0.09658 0.99353 -0.00001 0.11354 0.99353 -0.00001 0.11354 0.99353 -0.00000 0.11355 0.99353 -0.00000 0.11356 0.96089 -0.27016 0.06085 0.96341 -0.25112 0.09375 0.95173 0.00331 0.30692 0.95774 0.00135 0.28764 0.97471 -0.21603 0.05715 0.97573 -0.20726 0.07066 0.97715 -0.20216 0.06561 0.98169 -0.17974 0.06300 0.98561 -0.15620 0.06468 0.98543 -0.15590 0.06801 0.98985 -0.12693 0.06400 0.99524 0.07019 0.06763 0.99274 0.10847 0.05208 0.99118 0.11523 0.06545 0.98717 0.14826 0.05934 0.98444 0.16060 0.07133 0.98406 0.16570 0.06458 0.97308 0.22155 0.06348 0.96676 0.24276 0.08030 0.97114 0.20458 0.12265 0.92692 -0.27442 0.25597 0.92147 -0.32355 0.21495 0.98429 0.00406 0.17650 0.98303 0.00547 0.18339 0.89973 0.38248 0.21022 0.90728 0.33855 0.24946 -0.67370 -0.73901 0.00000 -0.60264 -0.79802 -0.00047 -0.62693 -0.77908 0.00023 -0.68125 -0.73205 -0.00042 -0.56939 -0.82207 0.00028 -0.52644 -0.85021 -0.00042 -0.50894 -0.86080 0.00014 -0.44952 -0.89327 -0.00034 -0.44575 -0.89516 -0.00019 -0.36123 -0.93247 0.00060 -0.32582 -0.94543 0.00005 -0.41162 -0.91135 -0.00231 -0.36938 -0.92928 -0.00070 -0.29393 -0.95583 -0.00117 -0.27368 -0.96182 -0.00017 -0.18375 -0.98297 0.00105 -0.23217 -0.97267 -0.00262 -0.09228 -0.99573 0.00191 -0.14284 -0.98974 -0.00271 -0.00000 -1.00000 0.00306 -0.05442 -0.99852 -0.00252 0.03596 -0.99935 0.00052 0.09227 -0.99573 -0.00050 0.09642 -0.99534 -0.00032 0.18374 -0.98297 0.00047 0.17320 -0.98489 -0.00028 0.27367 -0.96182 0.00027 0.25903 -0.96587 -0.00067 0.36123 -0.93248 0.00055 0.32646 -0.94521 -0.00180 0.44574 -0.89516 -0.00047 0.39129 -0.92027 0.00051 0.52643 -0.85022 0.00045 0.46114 -0.88733 -0.00001 0.50413 -0.86363 -0.00078 0.60263 -0.79802 0.00084 0.57281 -0.81969 -0.00117 0.67369 -0.73901 -0.00029 0.67819 -0.73489 0.00000 -0.66865 -0.71852 0.19142 -0.49989 -0.84550 0.18771 -0.52488 -0.82786 0.19786 -0.55933 -0.80754 0.18718 -0.59576 -0.77851 0.19749 -0.61570 -0.76512 0.18842 -0.66227 -0.72336 0.19532 0.49956 -0.84573 0.18758 0.66279 -0.72394 0.19136 0.52487 -0.82786 0.19787 0.56254 -0.80554 0.18616 0.59466 -0.77708 0.20624 0.66556 -0.72072 0.19389 -0.01230 -0.98966 0.14288 -0.01279 -0.99230 0.12317 -0.01018 -0.99291 0.11845 -0.00620 -0.99531 0.09658 -0.00001 -0.99353 0.11354 -0.00001 -0.99353 0.11354 -0.00000 -0.99353 0.11355 -0.00000 -0.99353 0.11356 -0.27016 -0.96089 0.06085 -0.25112 -0.96341 0.09375 0.00331 -0.95173 0.30692 0.00135 -0.95774 0.28764 -0.21603 -0.97471 0.05715 -0.20726 -0.97573 0.07067 -0.20216 -0.97715 0.06561 -0.17974 -0.98169 0.06300 -0.15620 -0.98561 0.06468 -0.15590 -0.98543 0.06801 -0.12693 -0.98985 0.06400 0.07019 -0.99524 0.06763 0.10847 -0.99274 0.05208 0.11523 -0.99118 0.06545 0.14826 -0.98717 0.05934 0.16060 -0.98444 0.07133 0.16569 -0.98406 0.06458 0.22155 -0.97308 0.06348 0.24276 -0.96676 0.08030 0.20458 -0.97114 0.12265 -0.27442 -0.92692 0.25597 -0.32355 -0.92147 0.21495 0.00406 -0.98429 0.17650 0.00547 -0.98303 0.18338 0.38248 -0.89973 0.21022 0.33855 -0.90728 0.24946 -0.73901 0.67370 0.00000 -0.79802 0.60264 -0.00047 -0.77908 0.62693 0.00023 -0.73205 0.68125 -0.00042 -0.82207 0.56939 0.00028 -0.85021 0.52644 -0.00042 -0.86080 0.50894 0.00014 -0.89327 0.44952 -0.00034 -0.89516 0.44575 -0.00019 -0.93248 0.36123 0.00060 -0.94543 0.32582 0.00005 -0.91135 0.41162 -0.00231 -0.92928 0.36938 -0.00070 -0.95583 0.29393 -0.00117 -0.96182 0.27368 -0.00017 -0.98297 0.18375 0.00105 -0.97267 0.23217 -0.00262 -0.99573 0.09228 0.00191 -0.98974 0.14284 -0.00271 -1.00000 0.00000 0.00306 -0.99852 0.05442 -0.00252 -0.99935 -0.03596 0.00052 -0.99573 -0.09227 -0.00050 -0.99534 -0.09642 -0.00032 -0.98297 -0.18374 0.00047 -0.98489 -0.17320 -0.00028 -0.96182 -0.27367 0.00027 -0.96587 -0.25903 -0.00067 -0.93248 -0.36123 0.00055 -0.94521 -0.32646 -0.00180 -0.89516 -0.44574 -0.00047 -0.92027 -0.39129 0.00051 -0.85022 -0.52643 0.00045 -0.88733 -0.46114 -0.00001 -0.86363 -0.50413 -0.00078 -0.79802 -0.60263 0.00084 -0.81969 -0.57281 -0.00117 -0.74449 -0.66764 -0.00035 -0.73966 -0.67298 -0.00000 -0.71852 0.66865 0.19142 -0.84550 0.49989 0.18771 -0.82786 0.52488 0.19786 -0.80754 0.55933 0.18718 -0.77851 0.59576 0.19749 -0.76512 0.61570 0.18842 -0.72336 0.66227 0.19532 -0.84573 -0.49956 0.18758 -0.72977 -0.65639 0.19128 -0.82786 -0.52487 0.19787 -0.80554 -0.56254 0.18616 -0.77708 -0.59466 0.20624 -0.72526 -0.66031 0.19490 -0.98966 0.01230 0.14288 -0.99230 0.01279 0.12317 -0.99291 0.01018 0.11845 -0.99531 0.00620 0.09658 -0.99353 0.00001 0.11354 -0.99353 0.00001 0.11354 -0.99353 0.00000 0.11355 -0.99353 0.00000 0.11356 -0.96089 0.27016 0.06085 -0.96341 0.25112 0.09375 -0.95173 -0.00331 0.30692 -0.95774 -0.00135 0.28764 -0.97471 0.21603 0.05715 -0.97573 0.20726 0.07066 -0.97715 0.20216 0.06561 -0.98169 0.17974 0.06300 -0.98561 0.15620 0.06468 -0.98543 0.15590 0.06801 -0.98985 0.12693 0.06400 -0.99524 -0.07019 0.06763 -0.99274 -0.10847 0.05208 -0.99118 -0.11523 0.06545 -0.98717 -0.14826 0.05934 -0.98444 -0.16060 0.07133 -0.98406 -0.16570 0.06458 -0.97308 -0.22155 0.06348 -0.96676 -0.24276 0.08030 -0.97114 -0.20458 0.12265 -0.92692 0.27442 0.25597 -0.92147 0.32355 0.21495 -0.98429 -0.00406 0.17650 -0.98303 -0.00547 0.18339 -0.89973 -0.38248 0.21022 -0.90728 -0.33855 0.24946 -0.00403 -0.00694 0.99997 0.03418 0.01383 0.99932 0.06702 0.00945 0.99771 0.45330 0.11457 0.88397 0.51011 0.16576 0.84399 0.74550 0.31563 0.58704 0.46889 0.03996 0.88235 0.00293 0.13540 0.99079 0.09376 0.23774 0.96679 0.15651 0.60291 0.78231 0.20565 0.62169 0.75579 0.15375 0.20320 0.96699 0.09578 0.14434 0.98488 0.13617 0.16824 0.97630 0.13388 0.12303 0.98333 0.11981 0.11981 0.98554 0.11683 0.10687 0.98739 0.15490 0.12537 0.97994 0.15137 0.12678 0.98031 0.36204 0.53731 0.76173 0.30595 0.49988 0.81025 0.36830 0.45504 0.81073 0.36831 0.45505 0.81073 0.41396 0.41396 0.81073 0.41396 0.41396 0.81073 0.45506 0.36830 0.81073 0.45505 0.36830 0.81073 0.49986 0.30598 0.81025 0.34277 0.27459 0.89839 0.67881 0.45470 0.57659 0.48354 0.70772 0.51510 0.53146 0.69305 0.48706 0.52989 0.65468 0.53909 0.59338 0.64769 0.47790 0.59369 0.59368 0.54321 0.64770 0.59338 0.47790 0.65468 0.52988 0.53909 0.69306 0.53145 0.48706 0.71588 0.45200 0.53217 0.27373 0.90585 0.32327 0.26815 0.90572 0.32827 0.50551 0.79730 0.32981 0.49737 0.80763 0.31679 0.57678 0.75371 0.31503 0.57727 0.75280 0.31631 0.64102 0.69970 0.31545 0.65054 0.69649 0.30282 0.70244 0.64352 0.30407 0.70274 0.64339 0.30365 0.75545 0.57930 0.30612 0.75635 0.57879 0.30485 0.80231 0.51119 0.30821 0.80417 0.50985 0.30554 0.90506 0.19812 0.37632 0.89752 0.24105 0.36927 0.89288 0.33318 0.30292 -0.62632 0.16113 0.76273 -0.62295 0.15627 0.76650 -0.17644 0.06961 0.98185 -0.15058 0.04286 0.98767 -0.68410 0.23722 0.68974 -0.63626 0.12776 0.76082 -0.45206 0.71587 0.53214 -0.53145 0.69306 0.48707 -0.52988 0.65468 0.53909 -0.59338 0.64770 0.47790 -0.59368 0.59369 0.54321 -0.64769 0.59338 0.47791 -0.65468 0.52989 0.53909 -0.69305 0.53146 0.48706 -0.70772 0.48351 0.51512 -0.45479 0.67832 0.57710 -0.27278 0.33907 0.90035 -0.30517 0.50042 0.81022 -0.36830 0.45505 0.81073 -0.36830 0.45506 0.81073 -0.41396 0.41396 0.81073 -0.41396 0.41396 0.81072 -0.45505 0.36831 0.81073 -0.45504 0.36830 0.81073 -0.49990 0.30593 0.81025 -0.57868 0.42827 0.69406 -0.13364 0.16675 0.97690 -0.13617 0.16824 0.97630 -0.13388 0.12303 0.98333 -0.11981 0.11981 0.98554 -0.11683 0.10687 0.98739 -0.15489 0.12537 0.97994 -0.19273 0.10998 0.97507 -0.16838 0.09242 0.98138 -0.19940 0.11993 0.97255 -0.91331 0.27039 0.30456 -0.87411 0.34158 0.34535 -0.92009 0.17181 0.35202 -0.17203 0.92000 0.35215 -0.33274 0.89169 0.30687 -0.30085 0.89474 0.33004 -0.16885 0.71506 0.67837 -0.07423 0.61800 0.78266 -0.10799 0.33292 0.93675 -0.06749 0.35633 0.93192 -0.14143 0.41406 0.89920 -0.21285 0.69570 0.68607 -0.31506 0.74583 0.58692 -0.01786 0.01860 0.99967 -0.50857 0.80214 0.31293 -0.51041 0.79949 0.31670 -0.57678 0.75371 0.31503 -0.57727 0.75280 0.31630 -0.63456 0.70549 0.31564 -0.63825 0.69668 0.32753 -0.69650 0.63768 0.32902 -0.69640 0.63800 0.32860 -0.74886 0.57425 0.33083 -0.74977 0.57377 0.32959 -0.80133 0.49716 0.33272 -0.79357 0.50314 0.34219 0.00000 0.00000 1.00000 -0.01522 0.02937 0.99945 0.13759 -0.94136 0.30808 0.31449 -0.84280 0.43678 0.26793 -0.88676 0.37666 -0.11956 -0.57212 0.81141 -0.17619 -0.61720 0.76682 -0.11536 -0.16820 0.97898 -0.21909 -0.54202 0.81131 -0.16626 -0.63966 0.75046 -0.03002 -0.26671 0.96331 0.01647 -0.23578 0.97167 0.62728 -0.16114 0.76194 0.59205 -0.19553 0.78182 0.59431 -0.20504 0.77766 0.17316 0.01973 0.98470 -0.79317 -0.50794 0.33598 -0.74866 -0.57291 0.33359 -0.74774 -0.57339 0.33483 -0.70097 -0.63049 0.33334 -0.69211 -0.63406 0.34490 -0.63374 -0.69220 0.34530 -0.63407 -0.69210 0.34489 -0.57095 -0.74456 0.34590 -0.79705 -0.50534 0.33068 -0.57049 -0.74549 0.34467 -0.49681 -0.79578 0.34629 -0.50099 -0.79018 0.35302 -0.26843 -0.90667 0.32541 -0.18750 -0.91381 0.36028 -0.31716 -0.88031 0.35281 -0.74758 -0.13745 0.64980 -0.73051 -0.11252 0.67357 -0.30749 -0.08435 0.94780 -0.37321 -0.15247 0.91513 -0.70081 -0.22119 0.67818 -0.74637 -0.31461 0.58648 0.46497 -0.71266 0.52528 0.53145 -0.69306 0.48707 0.52988 -0.65468 0.53909 0.59338 -0.64770 0.47790 0.59368 -0.59369 0.54321 0.64769 -0.59338 0.47791 0.65468 -0.52988 0.53909 0.69305 -0.53146 0.48706 0.70772 -0.48352 0.51511 0.46450 -0.69871 0.54410 0.29076 -0.42870 0.85538 0.30439 -0.50095 0.81018 0.36830 -0.45504 0.81073 0.36830 -0.45506 0.81073 0.41396 -0.41396 0.81072 0.41396 -0.41396 0.81073 0.45505 -0.36831 0.81073 0.45504 -0.36830 0.81073 0.49989 -0.30594 0.81025 0.13193 -0.16574 0.97731 0.13617 -0.16824 0.97630 0.13388 -0.12303 0.98333 0.11981 -0.11981 0.98554 0.11683 -0.10687 0.98739 0.15489 -0.12537 0.97994 0.14694 -0.12856 0.98076 0.51813 -0.33290 0.78786 -0.91519 -0.15921 0.37025 -0.88570 -0.33050 0.32605 -0.88807 -0.30231 0.34632 0.11073 -0.02431 0.99355 0.15985 -0.00455 0.98713 0.90331 -0.26743 0.33542 0.90334 -0.26850 0.33449 0.90751 -0.22944 0.35184 0.50666 -0.79914 0.32353 0.50873 -0.79614 0.32765 0.57502 -0.75142 0.32362 0.57551 -0.75051 0.32485 0.63943 -0.69842 0.32148 0.63956 -0.69811 0.32189 0.69245 -0.64677 0.31970 0.69553 -0.63720 0.33198 0.74864 -0.57408 0.33162 0.74956 -0.57361 0.33036 0.80218 -0.49720 0.33059 0.79402 -0.50342 0.34073 0.03518 -0.26811 0.96275 0.22396 -0.46715 0.85534 0.16181 -0.73593 0.65744 0.20901 -0.80028 0.56202 0.19727 -0.71854 0.66692 0.19612 -0.72262 0.66285 0.05889 -0.43878 0.89666 0.09347 -0.24292 0.96553 -0.71584 -0.45218 0.53208 -0.69306 -0.53145 0.48707 -0.65468 -0.52988 0.53909 -0.64770 -0.59338 0.47791 -0.59369 -0.59368 0.54321 -0.59338 -0.64769 0.47791 -0.52989 -0.65468 0.53909 -0.53146 -0.69305 0.48706 -0.48345 -0.70774 0.51515 -0.67849 -0.45490 0.57682 -0.31167 -0.25872 0.91429 -0.50461 -0.29903 0.80991 -0.45505 -0.36830 0.81073 -0.45505 -0.36830 0.81073 -0.41396 -0.41396 0.81073 -0.41396 -0.41396 0.81072 -0.36831 -0.45505 0.81073 -0.36830 -0.45504 0.81074 -0.30590 -0.49992 0.81025 -0.15815 -0.11908 0.98021 -0.16824 -0.13617 0.97630 -0.12303 -0.13388 0.98333 -0.11981 -0.11981 0.98554 -0.13388 -0.12303 0.98333 -0.13617 -0.16824 0.97630 -0.09587 -0.14439 0.98487 -0.36221 -0.53749 0.76151 -0.14980 -0.19915 0.96845 0.02810 -0.04531 0.99858 0.00085 0.00148 1.00000 0.03526 -0.01365 0.99928 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00146 -0.00123 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.08387 -0.04587 0.99542 -0.08251 -0.05375 0.99514 -0.00770 0.01311 0.99988 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.94748 -0.00329 0.31981 -0.95736 -0.00033 0.28888 -0.73521 -0.00204 0.67783 -0.63081 0.00141 0.77594 -0.34345 -0.00453 0.93916 -0.13639 0.00022 0.99065 -0.00047 -0.00092 1.00000 -0.34379 -0.00507 0.93903 -0.00335 0.96308 0.26918 0.01288 0.90264 0.43020 0.00912 0.61990 0.78463 0.00723 0.67565 0.73719 -0.00088 0.13708 0.99056 0.00294 0.22255 0.97492 -0.00022 0.02992 0.99955 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00332 -0.95594 0.29354 0.00047 -0.94631 0.32326 0.00196 -0.73301 0.68022 -0.00158 -0.62714 0.77891 0.00232 -0.43956 0.89821 -0.00143 -0.09677 0.99531 -0.00078 -0.07889 0.99688 0.00043 -0.00023 1.00000 0.95522 0.00332 0.29586 0.95202 0.00220 0.30604 0.45695 -0.00604 0.88947 0.58666 0.00184 0.80983 0.12681 -0.00246 0.99192 0.06544 -0.00016 0.99786 0.00000 0.00000 1.00000 0.55961 -0.03773 0.82789 0.01561 0.99985 -0.00705 -0.00098 1.00000 -0.00083 0.01792 0.99981 -0.00716 -0.00716 0.99997 0.00351 0.94308 0.01013 -0.33242 0.90035 0.01549 -0.43488 0.87263 0.01241 -0.48823 -0.00928 0.01498 -0.99984 0.47180 -0.00080 -0.88171 0.20713 0.03783 -0.97758 0.55145 0.02437 -0.83385 0.71385 0.03087 -0.69961 0.28043 0.01563 -0.95975 0.00611 0.01885 -0.99980 0.00000 0.99999 0.00380 -0.07375 0.00000 -0.99728 -0.37114 0.01462 -0.92846 -0.47189 0.00945 -0.88161 -0.35688 0.00299 -0.93414 -0.01830 0.01231 -0.99976 -0.07329 0.00015 -0.99731 -0.71399 0.02471 -0.69972 -0.86842 0.00506 -0.49581 -0.95887 0.01752 -0.28332 -0.93704 -0.02976 -0.34796 0.00233 1.00000 -0.00103 0.00269 1.00000 -0.00072 0.00101 1.00000 -0.00241 -0.00286 0.99999 -0.00228 0.78238 0.00118 0.62279 -0.00054 1.00000 -0.00051 -0.00040 1.00000 -0.00063 -0.00018 1.00000 -0.00072 0.00000 1.00000 -0.00073 0.00018 1.00000 -0.00071 0.00035 1.00000 -0.00064 0.00043 1.00000 -0.00058 0.00054 1.00000 -0.00048 -0.79630 0.00204 0.60489 -0.76637 -0.06201 0.63940 0.95566 0.04262 0.29137 0.98218 0.01346 0.18745 -0.86858 0.00456 0.49553 -0.98385 0.00253 -0.17900 -0.94079 0.01548 0.33863 -0.98071 0.04160 0.19098 0.03443 0.99939 -0.00552 0.06775 0.99574 0.06251 0.00288 1.00000 -0.00023 -0.00603 0.00587 0.99996 -0.05306 -0.11258 0.99223 0.60868 -0.04217 0.79230 0.73617 0.06695 0.67348 -0.96550 -0.02146 0.25952 -0.72071 0.03905 0.69213 -0.99981 0.00792 0.01761 -0.05490 0.99849 0.00076 0.92031 -0.22018 -0.32334 0.89723 0.31143 0.31304 0.78614 -0.00101 0.61805 0.00319 -0.99999 0.00250 -0.00305 -0.99999 0.00257 -0.00465 -0.99999 0.00083 -0.02952 -0.99941 -0.01748 -0.77052 -0.52487 0.36167 0.00001 -0.25719 -0.96636 0.00000 -0.25718 -0.96636 0.99856 0.02017 0.04964 -0.00000 0.99990 0.01411 -0.07370 -0.00000 -0.99728 -0.03585 -0.02027 -0.99915 0.42513 -0.02360 -0.90483 -0.37110 -0.01455 -0.92848 -0.47212 -0.00939 -0.88148 -0.35688 -0.00296 -0.93414 -1.00000 -0.00000 -0.00000 0.71385 -0.03070 -0.69963 0.55145 -0.02424 -0.83385 0.20708 -0.03762 -0.97760 0.47202 0.00082 -0.88159 0.00189 0.99990 0.01411 -0.23559 0.91060 0.33957 -0.00054 -1.00000 -0.00051 -0.00040 -1.00000 -0.00063 -0.00018 -1.00000 -0.00072 0.00001 -1.00000 -0.00073 0.00018 -1.00000 -0.00071 0.00035 -1.00000 -0.00064 0.00043 -1.00000 -0.00058 0.00054 -1.00000 -0.00048 -0.73538 0.32264 0.59592 -0.71205 0.37256 0.59514 -0.60784 0.62823 0.48566 -0.48343 0.76717 0.42160 -0.53884 0.71875 0.43938 -0.28526 0.90117 0.32636 -0.21299 0.95896 0.18718 -0.02202 0.99960 -0.01769 0.01704 0.99961 -0.02229 0.18634 0.89674 0.40142 0.07410 0.99547 0.05953 0.25313 0.93181 0.26012 0.50063 0.75381 0.42560 0.61730 0.61691 0.48821 0.29993 0.88675 0.35172 0.72867 0.30096 0.61519 0.71741 0.37571 0.58666 0.71682 0.28064 0.63829 0.52037 0.52829 0.67091 0.52372 0.52666 0.66958 0.50333 0.77786 0.37628 0.36930 0.77896 0.50679 -0.12292 0.80535 0.57991 0.38136 0.68298 0.62298 -0.74142 -0.00708 0.67100 -0.73038 -0.00207 0.68303 -0.47110 0.05690 0.88024 -0.35182 0.07971 0.93267 -0.24314 0.03166 0.96948 -0.11955 0.08086 0.98953 -0.00000 0.05678 0.99839 0.73037 0.00612 0.68302 0.69470 -0.00473 0.71928 -0.72611 0.28126 0.62742 -0.43719 0.57656 0.69025 -0.49556 0.54764 0.67417 -0.47071 0.79939 0.37336 -0.26888 0.73654 0.62066 -0.27634 0.73464 0.61963 -0.79630 -0.00204 0.60489 -0.76637 0.06201 0.63940 -0.63176 0.30989 0.71053 0.47043 0.39001 0.79157 0.37539 0.46164 0.80372 0.66915 0.34331 0.65908 -0.50178 0.06502 0.86255 -0.33398 0.45018 0.82813 -0.31538 0.44892 0.83607 -0.19542 0.56207 0.80367 -0.10706 0.45091 0.88612 0.10705 0.45092 0.88612 0.19540 0.56207 0.80368 0.31539 0.44889 0.83608 0.28848 0.44675 0.84687 0.24313 0.03166 0.96948 0.11954 0.08085 0.98953 0.54217 0.02783 0.83981 0.51792 0.04720 0.85412 0.35182 0.07971 0.93267 -0.55261 0.32171 0.76884 -0.36552 0.49866 0.78596 -0.67728 0.55266 0.48565 -0.22717 0.96385 0.13921 -0.63074 0.74486 0.21760 -0.07913 0.76386 0.64051 0.05341 0.98949 0.13438 0.08309 0.98329 0.16196 0.28851 0.92146 0.26015 -0.08985 0.81504 0.57240 0.83376 0.39711 0.38361 0.70089 0.53377 0.47312 -0.07362 0.93939 0.33486 -0.60923 0.01056 0.79293 -0.02864 -0.06670 -0.99736 -0.01899 -0.01469 -0.99971 -0.07169 -0.12216 -0.98992 -0.99926 0.01644 -0.03468 -0.98926 0.14119 0.03780 0.01060 0.99847 0.05423 -0.02160 0.99972 0.00942 0.02459 0.99875 0.04341 0.58789 -0.80894 0.00000 0.95040 -0.31103 0.00223 0.84658 -0.52657 -0.07757 0.74768 -0.66373 -0.02091 0.50937 -0.86052 0.00696 0.39467 -0.91856 -0.02182 0.48493 -0.87455 0.00000 -0.15968 0.00093 -0.98717 0.00003 -0.00018 -1.00000 -0.02111 -0.02396 -0.99949 0.00000 -0.00794 -0.99997 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.02605 -0.03953 -0.99888 -0.01879 0.02649 -0.99947 0.05618 -0.01764 -0.99826 -0.01575 0.00309 -0.99987 0.00434 -0.00432 -0.99998 0.00003 -0.00003 -1.00000 -0.00000 -0.00022 -1.00000 0.00000 -0.00000 -1.00000 0.06946 -0.02333 -0.99731 0.00000 0.00000 -1.00000 0.05688 -0.06186 -0.99646 -0.14951 0.14766 -0.97767 0.02100 0.02197 -0.99954 0.02149 0.01862 -0.99960 -0.01841 -0.01222 -0.99976 -0.07324 -0.00015 -0.99731 0.01302 -0.03728 -0.99922 0.17550 -0.02768 -0.98409 -0.50185 0.86490 -0.00989 0.00000 -0.00000 -1.00000 0.08129 -0.07716 -0.99370 0.49385 -0.86518 0.08702 0.95762 -0.24979 0.14344 0.99961 0.01618 0.02287 0.00238 1.00000 0.00000 0.00000 0.00000 -1.00000 0.00000 -0.00002 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.37479 0.92703 -0.01231 0.15917 0.98715 0.01442 0.38639 0.92218 -0.01706 0.99995 -0.00309 -0.00909 0.99971 -0.02176 0.00982 0.99739 0.06344 -0.03437 -0.93687 -0.02874 -0.34849 -0.98297 -0.06138 -0.17320 0.00001 -1.00000 0.00000 0.00001 -1.00000 0.00000 0.00001 -1.00000 -0.00000 -0.41160 -0.84750 -0.33515 -0.31638 -0.37059 -0.87325 0.00000 -1.00000 -0.00000 -0.19163 -0.97831 0.07862 0.00000 -1.00000 0.00000 0.36080 0.85313 0.37680 0.06977 0.88425 0.46177 -0.36360 -0.93155 0.00371 -0.39452 -0.91888 -0.00224 -0.46962 -0.88282 0.00932 -0.71915 -0.69478 -0.00993 -0.79010 -0.61080 -0.05167 -0.94749 -0.31951 0.01355 -0.98387 -0.17789 -0.01864 -0.05490 -0.99849 0.00076 0.01396 -0.99990 -0.00383 -0.46947 0.88280 -0.01616 -0.25597 0.96558 0.04624 0.99998 0.00687 0.00001 0.25032 -0.00368 -0.96815 0.76328 0.64580 -0.01860 -0.27272 0.86408 0.42308 0.21527 -0.96854 -0.12486 0.05920 -0.99780 -0.02983 0.06006 -0.99819 -0.00083 0.02759 -0.99941 0.02068 -0.03444 -0.99940 0.00198 0.01152 -0.99965 -0.02368 0.00437 -0.99998 -0.00508 0.99941 0.02954 0.01778 0.99468 0.08597 -0.05670 -0.56812 -0.79558 -0.21045 -0.55835 -0.81683 -0.14503 -0.99983 0.01820 0.00323 -0.99985 0.01707 0.00086 -0.99993 0.00040 -0.01182 0.47726 -0.81439 -0.33014 0.56077 -0.82034 -0.11215 -0.00247 0.99977 -0.02116 -0.03393 0.99937 0.01046 -0.03309 0.99855 -0.04241 0.00525 0.99959 0.02820 -0.00656 0.99977 0.02031 -0.00741 0.99997 -0.00266 -0.01351 0.99862 -0.05074 0.00246 0.99920 -0.04002 -0.00000 1.00000 0.00000 -0.02212 0.99975 0.00149 -0.03125 0.99949 -0.00682 -0.00000 1.00000 0.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.48494 -0.87455 -0.00000 -0.41383 -0.90743 -0.07295 -0.44341 -0.89518 0.04515 -0.99256 -0.10341 0.06427 -0.99475 -0.01479 0.10128 0.07096 0.99180 0.10632 0.04891 0.98683 0.15418 0.12344 0.84277 0.52393 0.11439 0.84121 0.52847 0.21957 0.80412 0.55242 0.36047 0.80145 0.47721 0.56552 0.65495 0.50123 -0.82745 0.52266 0.20530 -0.52802 0.84077 0.11962 -0.76910 0.49001 0.41035 -0.88733 0.18386 0.42290 -0.88991 0.20836 0.40576 -0.80404 0.57782 0.14014 -0.95932 0.26943 0.08434 -0.96422 0.11545 0.23864 -0.86887 -0.13305 0.47682 -0.86764 -0.49693 0.01612 -0.90447 -0.41031 0.11652 -0.91751 -0.11820 0.37973 -0.24416 -0.89892 -0.36377 -0.67217 -0.63075 -0.38774 -0.59745 -0.80184 -0.01073 -0.98825 -0.01706 0.15191 -0.96429 -0.18119 -0.19316 -0.87052 -0.34856 0.34743 -0.76955 -0.53426 0.34980 -0.81970 -0.08346 0.56667 -0.86810 -0.19551 0.45626 -0.72471 -0.52184 0.44998 -0.56060 -0.81770 0.13074 -0.71466 -0.69106 0.10818 -0.78043 -0.58988 0.20727 -0.94426 -0.32327 0.06225 -0.95723 -0.14931 0.24781 0.83609 0.00000 0.54859 0.88411 -0.02389 0.46666 0.97068 0.01697 0.23976 0.99657 -0.00993 0.08210 -0.62274 0.78226 -0.01629 -0.90112 0.43350 0.00783 -0.84541 0.53361 -0.02321 -0.99271 0.12048 0.00106 -0.47781 0.87838 0.01213 0.95439 -0.26495 0.13759 0.51253 -0.81941 0.25665 0.63558 -0.69051 0.34530 0.68590 -0.65208 0.32299 0.82637 -0.40092 0.39544 0.81765 -0.34129 0.46365 0.87850 -0.10763 0.46546 0.87887 -0.10999 0.46421 0.96407 -0.20651 0.16709 0.77890 0.12046 0.61547 0.62474 0.56370 0.54032 0.19677 0.88529 0.42137 0.60799 0.65530 0.44825 0.11402 0.99030 0.07946 0.05424 0.99716 0.05229 0.00000 0.99172 0.12843 -0.00006 0.85522 0.51827 0.66280 -0.48886 -0.56719 0.42505 -0.86402 -0.26983 0.50503 -0.80714 -0.30573 0.64436 -0.76472 -0.00248 0.63470 -0.77169 0.04074 0.77146 -0.56565 0.29135 0.69929 -0.46885 0.53961 0.83506 -0.13209 0.53406 0.90777 -0.41828 -0.03150 0.81829 -0.24021 0.52221 0.89799 -0.30952 -0.31275 0.89244 -0.44866 -0.04759 0.92031 0.22019 -0.32334 0.89723 -0.31143 0.31305 0.78463 -0.15894 0.59925 0.23632 -0.89199 -0.38537 -0.79708 -0.02018 0.60353 -0.76750 0.01903 0.64076 -0.76610 0.01859 0.64246 -0.77006 0.03113 0.63721 -0.77240 0.01748 0.63489 0.02658 0.89910 0.43693 -0.01884 0.99890 0.04292 -0.30074 0.06973 -0.95115 -0.35986 0.14496 -0.92168 -0.65079 0.43576 -0.62176 -0.40247 0.55043 -0.73147 -0.40522 0.62779 -0.66459 -0.33354 0.26804 -0.90383 -0.25787 0.11179 -0.95969 -0.23926 0.62972 -0.73906 0.99048 0.11459 -0.07631 0.98145 0.16456 -0.09835 0.55338 0.82217 0.13344 0.83932 0.52291 0.14870 0.95773 0.18427 0.22092 0.95008 0.20605 0.23428 0.76729 0.50015 0.40139 0.79748 0.56805 0.20331 0.80424 0.26951 0.52968 0.90398 0.11541 0.41170 0.77617 -0.11188 0.62052 0.76476 -0.34490 0.54422 0.62364 -0.54738 0.55808 0.58367 -0.69525 0.41948 0.42386 -0.84267 0.33204 0.40378 -0.85302 0.33064 0.15209 -0.97345 0.17107 0.98028 0.19017 -0.05374 0.91976 0.39203 -0.01847 0.78281 0.62216 -0.01096 0.63305 0.77332 -0.03499 0.58953 0.80738 -0.02416 0.35441 0.93504 -0.00947 -0.50680 -0.37233 -0.77751 -0.24699 -0.89988 -0.35946 -0.24989 -0.89186 -0.37701 0.77560 0.00983 0.63114 0.77488 0.01345 0.63197 0.77825 0.01344 0.62781 0.78227 0.01480 0.62277 0.77278 0.00000 0.63468 -0.99600 0.00435 0.08927 -0.97703 -0.01896 0.21224 -0.90991 0.01690 0.41446 0.60110 0.28540 0.74648 0.06549 0.64980 0.75728 0.23355 0.57000 0.78775 0.99099 0.13238 -0.02032 0.84878 0.52873 0.00254 0.14365 0.98948 -0.01728 0.53190 0.84681 0.00192 0.70662 0.70675 -0.03447 -0.99913 -0.00650 -0.04124 -0.35404 0.93518 -0.00937 -0.59007 0.80699 -0.02423 -0.70580 0.70634 -0.05403 -0.73698 0.67444 -0.04455 -0.91548 0.40196 -0.01776 -0.43813 0.00140 -0.89891 -0.59488 0.28099 0.75310 -0.39129 0.47434 0.78860 -0.11616 0.63818 0.76108 -0.79949 -0.08442 0.59472 -0.77544 -0.18416 0.60397 -0.66300 -0.54357 0.51475 -0.66029 -0.54617 0.51547 -0.43980 -0.82646 0.35149 -0.48874 -0.79631 0.35639 -0.25979 -0.94823 0.18266 -0.20174 -0.96384 0.17411 -0.39983 0.83929 0.36841 -0.15375 0.95957 0.23579 -0.03543 0.87962 0.47435 -0.81924 0.57324 0.01554 -0.99919 0.02178 -0.03385 -0.79319 0.47901 0.37603 -0.87979 0.44232 0.17412 0.85087 0.52536 0.00471 0.60527 0.58672 0.53797 0.66088 -0.05093 -0.74876 0.62086 0.26461 -0.73791 0.65414 0.31761 -0.68646 0.53969 0.42893 -0.72440 0.56000 0.48542 -0.67139 0.40179 0.55027 -0.73196 0.40445 0.62312 -0.66944 0.23986 0.62446 -0.74332 -0.97553 0.21978 0.00539 -0.99338 0.05732 -0.09955 -0.77672 0.14137 0.61378 -0.64573 0.56822 0.51006 -0.65559 0.54342 0.52430 -0.39577 0.84531 0.35891 -0.41012 0.83621 0.36409 0.91570 -0.22190 0.33504 0.78814 -0.15187 0.59646 0.23198 -0.14927 -0.96120 0.87264 -0.01234 -0.48821 0.90039 -0.01541 -0.43482 0.94308 -0.01008 -0.33242 0.95568 -0.04238 0.29134 0.99926 0.03201 0.02126 -0.86552 0.03527 0.49963 -0.71398 -0.02458 -0.69974 -0.86842 -0.00504 -0.49581 -0.95887 -0.01742 -0.28330 -0.98385 -0.00253 -0.17900 -0.99504 -0.00969 0.09904 -0.99129 -0.00439 0.13162 -0.00680 -0.99997 0.00324 0.00908 -0.99995 -0.00340 0.02290 -0.99951 0.02140 -0.00310 -0.99999 0.00064 0.01655 -0.99986 -0.00393 0.01695 -0.99985 -0.00389 -0.36487 -0.00000 -0.93106 -0.02970 -0.00561 0.99954 -0.07490 -0.12207 0.98969 0.61973 -0.01931 0.78458 0.58840 -0.02188 0.80827 0.99995 -0.00024 0.00989 -0.91817 -0.00000 -0.39618 -0.98107 0.08144 0.17572 -0.99903 0.01286 0.04215 0.99994 0.00000 0.01062 -0.36487 -0.00000 -0.93106 0.00238 -1.00000 0.00000 -1.00000 0.00000 -0.00000 -0.00000 -0.99990 0.01411 0.99857 -0.01969 0.04963 0.00000 0.25718 -0.96636 0.00001 0.25719 -0.96636 0.36486 0.00000 -0.93106 -1.00000 -0.00000 0.00001 -0.99964 -0.00651 -0.02621 0.99903 0.01286 0.04215 0.98107 0.08145 0.17572 0.92217 0.00000 -0.38679 -0.99998 0.00015 -0.00579 -0.99990 0.00870 0.01088 -0.62407 -0.01303 0.78126 0.03427 -0.08598 -0.99571 -0.61973 -0.01931 0.78458 0.07490 -0.12207 0.98969 0.02782 -0.00079 0.99961 0.36486 0.00000 -0.93106 -0.01695 -0.99985 -0.00389 -0.01625 -0.99986 -0.00395 -0.00038 -1.00000 -0.00017 -0.02290 -0.99951 0.02140 -0.00908 -0.99995 -0.00340 0.00691 -0.99997 0.00335 0.99981 0.00792 0.01761 0.72071 0.03905 0.69213 0.96550 -0.02146 0.25952 -0.73680 0.03170 0.67537 -0.60868 -0.04217 0.79230 0.04616 -0.11379 0.99243 0.00609 -0.01416 0.99988 -0.00288 1.00000 -0.00023 -0.06775 0.99574 0.06251 -0.03443 0.99939 -0.00552 -0.00553 0.99998 -0.00031 0.94012 -0.02889 -0.33961 -0.01792 0.99981 -0.00716 0.00300 1.00000 -0.00056 -0.01562 0.99985 -0.00705 -0.00665 0.05446 -0.99849 -0.78096 0.00407 0.62457 -0.78517 0.00557 0.61926 -0.68593 0.02910 0.72709 -0.78517 -0.00557 0.61926 -0.00319 -0.99999 0.00252 0.00288 -0.99999 0.00254 0.00440 -0.99999 0.00079 0.00274 -0.99999 0.00210 0.00001 -0.99999 -0.00474 0.00292 0.99999 -0.00230 -0.00094 1.00000 -0.00240 -0.00255 1.00000 -0.00069 -0.01241 0.99989 0.00830 -0.09636 0.74004 0.66562 -0.09786 0.72004 0.68700 0.12288 0.63045 0.76644 0.05084 0.87742 0.47703 0.05550 0.70454 0.70749 -0.07282 0.65139 0.75524 0.10102 0.99323 0.05732 -0.11655 0.99060 0.07158 0.01829 0.91613 0.40047 0.05687 0.78908 0.61166 0.01518 0.79240 0.60981 0.03442 0.82152 0.56915 -0.12170 0.54965 0.82648 0.10669 0.50213 0.85818 0.00418 0.59023 0.80722 -0.32772 0.28388 0.90112 0.30290 0.31156 0.90066 0.16947 0.69675 0.69701 -0.16948 0.69676 0.69699 -0.11576 0.71791 0.68644 -0.79848 0.44068 0.41015 -0.79849 -0.44068 0.41015 -0.11576 -0.71791 0.68644 -0.16948 -0.69676 0.69699 0.16947 -0.69675 0.69701 0.30290 -0.31156 0.90066 -0.32772 -0.28388 0.90112 0.00418 -0.59024 0.80722 0.10669 -0.50213 0.85818 -0.12170 -0.54965 0.82648 0.03442 -0.82152 0.56915 0.01518 -0.79240 0.60981 0.05687 -0.78908 0.61166 0.01829 -0.91613 0.40047 -0.11655 -0.99060 0.07158 0.10102 -0.99323 0.05732 -0.07282 -0.65139 0.75524 0.05550 -0.70454 0.70749 0.05084 -0.87742 0.47703 0.12288 -0.63045 0.76644 -0.09786 -0.72004 0.68700 -0.09636 -0.74004 0.66562 0.23179 0.14837 -0.96139 0.78815 0.15187 0.59646 -0.31670 -0.90760 0.27562 -0.41407 -0.84823 0.33024 -0.53956 -0.70968 0.45302 -0.65559 -0.54342 0.52430 -0.64573 -0.56822 0.51006 -0.77672 -0.14137 0.61378 -0.99339 -0.05732 -0.09940 -0.97581 -0.21856 0.00513 0.23986 -0.62446 -0.74332 0.40445 -0.62312 -0.66944 0.40179 -0.55027 -0.73196 0.56001 -0.48542 -0.67138 0.53969 -0.42892 -0.72440 0.65414 -0.31761 -0.68646 0.62086 -0.26461 -0.73791 0.66088 0.05093 -0.74876 0.60527 -0.58672 0.53797 0.85087 -0.52536 0.00471 -0.87979 -0.44232 0.17412 -0.79320 -0.47901 0.37602 -0.99919 -0.02178 -0.03385 -0.81924 -0.57325 0.01554 -0.03542 -0.87962 0.47435 -0.15375 -0.95957 0.23579 -0.25271 -0.92279 0.29084 -0.41170 -0.73535 0.53829 -0.20174 0.96384 0.17411 -0.25980 0.94823 0.18266 -0.48874 0.79631 0.35639 -0.43979 0.82646 0.35149 -0.66029 0.54617 0.51547 -0.66300 0.54356 0.51475 -0.77544 0.18416 0.60397 -0.79949 0.08443 0.59472 -0.11616 -0.63818 0.76108 -0.39129 -0.47434 0.78860 -0.59480 -0.28070 0.75328 -0.43814 -0.00140 -0.89891 -0.91548 -0.40196 -0.01776 -0.73699 -0.67444 -0.04455 -0.70580 -0.70634 -0.05403 -0.59007 -0.80699 -0.02423 -0.35404 -0.93518 -0.00937 -0.99913 0.00649 -0.04124 0.70663 -0.70675 -0.03447 0.53189 -0.84681 0.00192 0.14366 -0.98948 -0.01728 0.84878 -0.52874 0.00254 0.99099 -0.13238 -0.02032 0.16298 -0.61542 0.77116 0.60024 -0.27217 0.75209 -0.90991 -0.01690 0.41446 -0.97703 0.01896 0.21224 -0.99600 -0.00435 0.08927 0.77278 -0.00000 0.63468 0.78227 -0.01480 0.62277 0.77825 -0.01344 0.62781 0.77486 -0.01345 0.63198 0.77561 -0.00976 0.63114 -0.24989 0.89186 -0.37701 -0.25453 0.87766 -0.40611 -0.50303 0.35926 -0.78606 0.35441 -0.93504 -0.00947 0.58953 -0.80738 -0.02416 0.63305 -0.77332 -0.03499 0.78282 -0.62215 -0.01096 0.91976 -0.39204 -0.01847 0.98028 -0.19017 -0.05374 0.15209 0.97345 0.17107 0.40377 0.85302 0.33064 0.42387 0.84267 0.33204 0.58367 0.69525 0.41948 0.62364 0.54738 0.55807 0.76476 0.34491 0.54422 0.77617 0.11187 0.62052 0.90398 -0.11542 0.41170 0.80425 -0.26951 0.52968 0.79749 -0.56805 0.20331 0.76729 -0.50014 0.40140 0.95008 -0.20606 0.23429 0.95772 -0.18428 0.22092 0.83932 -0.52291 0.14871 0.55337 -0.82218 0.13344 0.98164 -0.16367 -0.09795 0.99048 -0.11459 -0.07631 -0.23926 -0.62972 -0.73906 -0.25787 -0.11179 -0.95969 -0.33354 -0.26804 -0.90383 -0.40522 -0.62779 -0.66458 -0.40248 -0.55043 -0.73146 -0.65079 -0.43576 -0.62175 -0.35986 -0.14496 -0.92168 -0.30074 -0.06973 -0.95115 -0.01884 -0.99890 0.04293 0.02658 -0.89910 0.43693 -0.77239 -0.01749 0.63491 -0.77011 -0.03069 0.63717 -0.76610 -0.01859 0.64246 -0.76750 -0.01903 0.64076 -0.79708 0.02017 0.60353 0.25359 0.87568 -0.41094 0.78463 0.15893 0.59925 0.91595 0.22035 0.33539 0.89570 0.44170 -0.05122 0.89887 0.30361 -0.31601 0.81863 0.23852 0.52245 0.90819 0.41687 -0.03766 0.83506 0.13209 0.53406 0.69929 0.46885 0.53961 0.77146 0.56565 0.29135 0.63470 0.77169 0.04074 0.64436 0.76471 -0.00248 0.50503 0.80714 -0.30573 0.45624 0.84334 -0.28394 0.67204 0.47617 -0.56711 -0.00006 -0.85522 0.51827 0.00000 -0.99172 0.12844 0.05424 -0.99716 0.05229 0.11403 -0.99029 0.07946 0.60799 -0.65530 0.44825 0.19677 -0.88529 0.42137 0.62474 -0.56370 0.54032 0.77890 -0.12047 0.61547 0.96407 0.20651 0.16710 0.87887 0.10998 0.46421 0.87850 0.10763 0.46546 0.81765 0.34129 0.46364 0.82637 0.40091 0.39545 0.68590 0.65208 0.32299 0.63558 0.69051 0.34530 0.51254 0.81941 0.25665 0.95439 0.26495 0.13760 -0.47781 -0.87838 0.01213 -0.99271 -0.12049 0.00106 -0.84542 -0.53360 -0.02321 -0.90112 -0.43350 0.00783 -0.62274 -0.78226 -0.01629 0.99657 0.00994 0.08211 0.97068 -0.01696 0.23976 0.88411 0.02390 0.46666 0.83609 -0.00000 0.54859 -0.95723 0.14931 0.24781 -0.94426 0.32328 0.06225 -0.78043 0.58989 0.20726 -0.71466 0.69105 0.10817 -0.56059 0.81771 0.13073 -0.72471 0.52184 0.44998 -0.86810 0.19551 0.45627 -0.81970 0.08346 0.56667 -0.76955 0.53425 0.34980 -0.87052 0.34856 0.34743 -0.96495 0.17789 -0.19295 -0.98829 0.01688 0.15163 -0.59744 0.80184 -0.01073 -0.67548 0.62360 -0.39350 -0.27407 0.88464 -0.37724 -0.91776 0.11650 0.37966 -0.90468 0.41183 0.10934 -0.87199 0.48923 0.01669 -0.86897 0.13121 0.47715 -0.96422 -0.11546 0.23863 -0.95932 -0.26943 0.08434 -0.80404 -0.57783 0.14013 -0.88991 -0.20836 0.40577 -0.88733 -0.18386 0.42291 -0.76909 -0.49001 0.41035 -0.52802 -0.84077 0.11962 -0.82745 -0.52266 0.20531 0.58799 -0.65551 0.47390 0.07571 -0.75362 0.65293 0.17831 -0.83294 0.52384 0.57860 -0.60552 0.54642 0.14977 -0.96702 0.20602 0.11828 -0.95793 0.26150 -0.99475 0.01470 0.10128 -0.99263 0.10273 0.06427 -0.44341 0.89518 0.04515 -0.41383 0.90743 -0.07295 -0.48494 0.87455 -0.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00001 -1.00000 0.00000 -0.03125 -0.99949 -0.00682 -0.02212 -0.99975 0.00149 0.00000 -1.00000 0.00003 0.00246 -0.99920 -0.04002 -0.01351 -0.99862 -0.05074 -0.00741 -0.99997 -0.00266 -0.00656 -0.99977 0.02031 0.00525 -0.99959 0.02820 -0.03309 -0.99855 -0.04241 -0.03393 -0.99937 0.01046 -0.00247 -0.99977 -0.02116 0.56251 0.81911 -0.11246 0.47940 0.81333 -0.32965 -0.99993 -0.00040 -0.01182 -0.99985 -0.01707 0.00086 -0.99983 -0.01821 0.00324 -0.55835 0.81683 -0.14502 -0.56812 0.79558 -0.21045 0.99468 -0.08597 -0.05670 0.99941 -0.02954 0.01778 0.00437 0.99998 -0.00508 0.01152 0.99965 -0.02368 -0.03444 0.99940 0.00198 0.03485 0.99920 0.01987 0.06619 0.99781 -0.00091 0.06576 0.99771 -0.01589 0.23240 0.96544 -0.11794 -0.27272 -0.86408 0.42308 0.76328 -0.64580 -0.01860 0.25026 0.00368 -0.96817 0.99998 -0.00687 0.00001 -0.25597 -0.96558 0.04624 -0.46947 -0.88280 -0.01616 0.01396 0.99990 -0.00383 -0.98387 0.17789 -0.01864 -0.94748 0.31951 0.01355 -0.79010 0.61079 -0.05167 -0.71915 0.69478 -0.00993 -0.46962 0.88282 0.00932 -0.39453 0.91888 -0.00224 -0.36360 0.93155 0.00371 0.06976 -0.88425 0.46177 0.36080 -0.85313 0.37681 0.00495 0.99999 -0.00203 -0.19163 0.97831 0.07862 0.00590 0.99998 0.00000 -0.31877 0.35737 -0.87788 -0.42514 0.84243 -0.33102 0.00001 1.00000 -0.00252 -0.00543 0.99998 -0.00096 -0.00588 0.99998 0.00000 -0.98300 0.06098 -0.17321 -0.93689 0.02856 -0.34846 0.99739 -0.06344 -0.03437 0.99971 0.02177 0.00982 0.99995 0.00310 -0.00909 0.38639 -0.92218 -0.01706 0.15917 -0.98715 0.01442 0.37479 -0.92703 -0.01231 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00002 -1.00000 0.00000 -0.00000 -1.00000 0.99961 -0.01618 0.02287 0.95762 0.24979 0.14344 0.49385 0.86518 0.08702 0.08186 0.07770 -0.99361 0.00000 0.00000 -1.00000 -0.50185 -0.86490 -0.00989 0.17541 0.02756 -0.98411 0.01282 0.03712 -0.99923 0.02149 -0.01862 -0.99960 0.02100 -0.02197 -0.99954 -0.14951 -0.14766 -0.97767 0.05688 0.06186 -0.99646 0.00000 -0.00000 -1.00000 0.06932 0.02322 -0.99732 0.00000 0.00000 -1.00000 -0.00000 0.00022 -1.00000 0.00003 0.00003 -1.00000 0.00436 0.00432 -0.99998 -0.01575 -0.00309 -0.99987 0.05618 0.01764 -0.99826 -0.01879 -0.02649 -0.99947 -0.02605 0.03953 -0.99888 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00005 0.00791 -0.99997 0.00003 0.00018 -1.00000 -0.15969 -0.00092 -0.98717 0.48493 0.87456 0.00000 0.39467 0.91856 -0.02182 0.50937 0.86052 0.00696 0.74768 0.66373 -0.02091 0.84658 0.52657 -0.07757 0.95040 0.31103 0.00223 0.58789 0.80894 0.00000 0.02459 -0.99875 0.04341 -0.02160 -0.99972 0.00942 0.01060 -0.99847 0.05423 -0.98926 -0.14119 0.03780 -0.99926 -0.01644 -0.03468 -0.07169 0.12216 -0.98992 -0.01899 0.01469 -0.99971 -0.02864 0.06670 -0.99736 -0.60923 -0.01052 0.79293 -0.07362 -0.93939 0.33485 0.70089 -0.53377 0.47312 0.83376 -0.39710 0.38360 -0.08985 -0.81504 0.57240 0.28851 -0.92146 0.26015 0.08309 -0.98329 0.16196 0.05341 -0.98949 0.13437 -0.07913 -0.76386 0.64052 -0.63074 -0.74486 0.21761 -0.22717 -0.96386 0.13921 -0.67728 -0.55266 0.48565 -0.36552 -0.49866 0.78596 -0.55485 -0.31922 0.76827 0.35183 -0.07938 0.93269 0.51802 -0.04699 0.85408 0.54217 -0.02774 0.83981 0.11955 -0.08052 0.98956 0.24313 -0.03153 0.96948 0.28848 -0.44675 0.84687 0.31539 -0.44889 0.83608 0.19540 -0.56207 0.80368 0.10705 -0.45092 0.88612 -0.10706 -0.45091 0.88612 -0.19542 -0.56207 0.80367 -0.31538 -0.44892 0.83607 -0.33398 -0.45018 0.82813 -0.50186 -0.06477 0.86252 0.67317 -0.34328 0.65498 0.37539 -0.46164 0.80372 0.52907 -0.36664 0.76528 -0.63512 -0.30996 0.70749 -0.27634 -0.73464 0.61963 -0.26888 -0.73653 0.62066 -0.47071 -0.79939 0.37336 -0.49556 -0.54764 0.67417 -0.43719 -0.57656 0.69025 -0.72759 -0.27897 0.62673 0.69464 0.00473 0.71934 0.73037 -0.00610 0.68302 -0.00000 -0.05654 0.99840 -0.11956 -0.08052 0.98956 -0.24314 -0.03153 0.96948 -0.35183 -0.07938 0.93269 -0.47111 -0.05666 0.88025 -0.73038 0.00207 0.68303 -0.74135 0.00704 0.67108 0.38136 -0.68298 0.62298 -0.12292 -0.80535 0.57991 0.36931 -0.77896 0.50679 0.50333 -0.77786 0.37628 0.52372 -0.52667 0.66959 0.52037 -0.52829 0.67091 0.71853 -0.27783 0.63759 0.71828 -0.37335 0.58710 0.72956 -0.29631 0.61640 0.29993 -0.88675 0.35172 0.61730 -0.61691 0.48821 0.50063 -0.75381 0.42561 0.25313 -0.93181 0.26012 0.07410 -0.99547 0.05953 0.18634 -0.89674 0.40142 0.01704 -0.99961 -0.02229 -0.02202 -0.99960 -0.01769 -0.21299 -0.95896 0.18719 -0.28526 -0.90117 0.32636 -0.53884 -0.71875 0.43938 -0.48343 -0.76717 0.42160 -0.60784 -0.62823 0.48566 -0.71271 -0.37008 0.59589 -0.73677 -0.31838 0.59649 -0.23559 -0.91060 0.33957 0.00189 -0.99990 0.01411 -0.77052 0.52487 0.36167 0.82324 0.01104 0.56758 0.77574 -0.00804 0.63101 0.79035 -0.04252 0.61118 0.67354 0.03209 0.73845 0.77670 -0.00626 0.62983 0.79147 0.02728 0.61060 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.04917 -0.99878 0.00515 -0.14699 -0.98905 -0.01309 -0.18375 -0.98297 -0.00349 -0.24340 -0.96984 -0.01313 -0.27368 -0.96181 -0.00421 -0.33747 -0.94125 -0.01293 -0.36123 -0.93246 -0.00501 -0.42828 -0.90356 -0.01250 -0.44574 -0.89514 -0.00590 -0.51493 -0.85715 -0.01182 -0.52643 -0.85019 -0.00688 -0.59662 -0.80245 -0.01089 -0.67255 -0.73999 -0.00910 -0.74446 -0.66762 -0.00828 -0.74198 -0.67039 -0.00675 -0.79801 -0.60262 -0.00409 -0.80421 -0.59429 -0.00809 -0.85021 -0.52643 -0.00337 -0.85867 -0.51244 -0.00922 -0.89516 -0.44574 -0.00277 -0.90484 -0.42562 -0.01015 -0.93247 -0.36123 -0.00228 -0.94225 -0.33474 -0.01084 -0.96182 -0.27367 -0.00189 -0.97056 -0.24057 -0.01133 -0.98297 -0.18374 -0.00162 -0.09225 -0.99549 -0.02198 -0.98889 -0.14830 -0.01054 -0.99819 -0.05931 -0.01028 -0.99573 -0.09227 -0.00171 -0.99951 0.02965 -0.00996 -1.00000 0.00000 -0.00185 -0.04986 0.99864 0.01518 0.00000 0.99985 -0.01756 -0.14909 0.98865 0.01849 -0.09225 0.99551 -0.02099 -0.24680 0.96882 0.02203 -0.18368 0.98268 -0.02466 -0.43406 0.90088 -0.00310 -0.44574 0.89516 0.00176 -0.52164 0.85316 -0.00188 -0.52643 0.85022 0.00041 -0.60404 0.79695 -0.00040 -0.60263 0.79802 -0.00118 -0.68041 0.73283 0.00130 -0.66762 0.74447 -0.00688 -0.75003 0.66140 -0.00072 -0.73898 0.67367 -0.00900 -0.81218 0.58340 0.00102 -0.79796 0.60259 -0.01176 -0.86626 0.49959 0.00306 -0.85012 0.52638 -0.01473 -0.91170 0.41082 0.00538 -0.89502 0.44568 -0.01790 -0.94807 0.31796 0.00799 -0.93226 0.36115 -0.02125 -0.97500 0.22193 0.01092 -0.96152 0.27360 -0.02483 -0.99222 0.12371 0.01413 0.04986 0.99868 0.01212 0.14912 0.98881 -0.00530 0.18374 0.98296 0.00433 0.24686 0.96904 -0.00482 0.27368 0.96181 0.00372 0.34217 0.93963 -0.00407 0.36123 0.93247 0.00286 0.43406 0.90088 -0.00310 0.44503 0.89551 0.00146 0.52164 0.85316 -0.00162 0.52584 0.85058 0.00042 0.60404 0.79695 -0.00041 0.60264 0.79802 -0.00118 0.68041 0.73283 0.00130 0.75003 0.66140 -0.00025 0.79801 0.60262 0.00623 0.81218 0.58340 -0.00166 0.85020 0.52642 0.00646 0.86626 0.49959 -0.00284 0.89514 0.44573 0.00641 0.91171 0.41082 -0.00381 0.93246 0.36122 0.00610 0.94809 0.31797 -0.00455 0.96181 0.27367 0.00554 0.97505 0.22194 -0.00505 0.98296 0.18374 0.00472 0.99401 0.10897 -0.00776 0.99573 0.09227 -0.00076 0.09227 0.99563 -0.01438 0.99573 -0.09228 0.00252 0.99987 -0.01483 -0.00675 1.00000 -0.00000 -0.00061 0.97061 -0.24058 0.00669 0.93241 -0.36121 -0.01181 0.94230 -0.33475 0.00405 0.89511 -0.44572 -0.01031 0.90489 -0.42565 0.00162 0.85018 -0.52642 -0.00893 0.85871 -0.51246 -0.00063 0.79799 -0.60262 -0.00767 0.80424 -0.59430 -0.00268 0.73271 -0.68051 -0.00689 0.74199 -0.67041 -0.00061 0.67369 -0.73901 -0.00209 0.67258 -0.74002 -0.00274 0.60263 -0.79802 -0.00168 0.59665 -0.80248 -0.00470 0.52643 -0.85022 -0.00141 0.51496 -0.85719 -0.00647 0.44574 -0.89516 -0.00128 0.42830 -0.90360 -0.00805 0.33744 -0.94117 0.01842 0.18366 -0.98257 -0.02859 0.24340 -0.96981 0.01478 0.09224 -0.99539 -0.02629 0.14699 -0.98907 0.01134 -0.00000 -0.99971 -0.02409 0.04916 -0.99876 0.00814 0.77434 -0.60773 0.17624 0.67097 -0.74108 -0.02454 0.73147 -0.68188 0.00087 0.80012 -0.59984 -0.00099 0.83007 -0.55740 0.01674 0.86602 -0.50001 -0.00318 0.90796 -0.41905 0.00274 0.92208 -0.38696 -0.00613 0.94719 -0.32066 -0.00166 0.95269 -0.30389 -0.00615 0.97579 -0.21866 0.00386 0.98358 -0.18041 -0.00412 0.99495 -0.10022 0.00567 0.99937 0.03554 0.00186 0.99944 0.03341 0.00262 0.99734 -0.07287 -0.00206 0.98965 0.14353 -0.00152 0.98593 0.16704 0.00548 0.96829 0.24980 -0.00398 0.94203 0.33519 0.01509 0.89184 0.45235 -0.00374 0.84690 0.53148 0.01684 0.93554 0.35314 0.00700 0.80671 0.59075 -0.01515 0.70732 0.70671 0.01593 0.66067 0.75055 -0.01413 0.53226 0.84645 0.01482 0.43522 0.89945 -0.03958 0.33043 0.94371 0.01531 0.21301 0.97702 -0.00791 -0.18209 0.98328 -0.00337 -0.13826 0.99036 -0.00827 -0.05612 0.99841 0.00471 -0.00000 0.99999 -0.00537 0.05611 0.99841 0.00471 0.12604 0.99200 -0.00634 0.16760 0.98585 0.00032 -0.92277 0.38516 -0.01222 -0.89243 0.45102 0.01223 -0.85456 0.51933 -0.00477 -0.78209 0.62305 0.01185 -0.75133 0.65977 -0.01408 -0.62374 0.78152 0.01344 -0.57888 0.81526 -0.01557 -0.43408 0.90075 0.01482 -0.37524 0.92678 -0.01685 -0.22262 0.97477 0.01600 -0.96723 0.25389 -0.00253 -0.95368 0.30072 0.00733 -0.98594 0.16704 0.00414 -0.99977 -0.02060 0.00629 -0.99990 0.00000 0.01406 -0.99296 0.11777 -0.01232 -0.98259 -0.18570 0.00494 -0.94963 -0.31335 -0.00367 -0.98732 -0.15857 -0.00757 -0.67307 -0.73899 0.02945 -0.66921 -0.74266 0.02462 -0.75225 -0.65885 -0.00501 -0.79616 -0.60508 -0.00324 -0.83006 -0.55742 0.01673 -0.86603 -0.49999 -0.00319 -0.90796 -0.41904 0.00274 -0.92212 -0.38685 -0.00615 -0.94718 -0.32068 -0.00170 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.29359 -0.95589 0.00919 0.14421 -0.98924 0.02479 0.17966 -0.98373 -0.00121 0.06016 -0.99791 0.02373 0.00002 -0.99999 0.00496 -0.06016 -0.99791 0.02373 -0.17966 -0.98373 -0.00121 -0.14419 -0.98924 0.02480 -0.29651 -0.95499 0.00887 -0.32284 -0.94642 -0.00832 0.40498 -0.91155 0.07123 0.90929 0.41608 -0.00865 0.92799 0.37177 0.02498 0.99861 -0.04676 0.02413 0.58002 -0.81403 0.03061 0.88796 -0.45992 -0.00207 0.96395 -0.26583 0.01174 0.99954 -0.02959 -0.00623 0.96241 0.27140 0.01028 -0.90709 0.41507 0.07002 -0.94234 0.33464 -0.00255 -0.97307 0.22849 0.03034 -0.97855 -0.20586 -0.00748 -0.87545 -0.48307 0.01546 -0.68732 -0.72634 -0.00462 -0.56168 -0.82731 0.00813 -0.95194 -0.30623 -0.00615 -0.99086 -0.13472 0.00619 -0.99914 0.04089 -0.00621 -0.97654 0.21525 0.00617 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.14017 -0.84639 -0.51378 0.00000 0.00000 -1.00000 0.01063 0.01095 -0.99988 -0.00000 0.01138 -0.99994 -0.00187 0.01127 -0.99993 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.01298 0.00154 -0.99991 -0.01231 0.00323 -0.99992 -0.01152 0.00481 -0.99992 0.01377 -0.00101 -0.99990 0.01352 0.00048 -0.99991 -0.01335 -0.00028 -0.99991 0.01386 -0.00254 -0.99990 0.01376 -0.00439 -0.99990 -0.01357 -0.00218 -0.99991 0.01352 -0.00568 -0.99989 -0.01342 -0.00443 -0.99990 0.01298 -0.00749 -0.99989 -0.01270 -0.00733 -0.99989 -0.01322 -0.00555 -0.99990 0.01223 -0.00917 -0.99988 -0.01141 -0.00999 -0.99989 -0.00389 -0.02039 -0.99978 -0.01194 -0.00907 -0.99989 0.00520 -0.02055 -0.99978 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.01042 0.00633 -0.99993 -0.00900 0.00790 -0.99993 -0.00677 0.00954 -0.99993 -0.00432 0.01068 -0.99993 0.00018 0.00049 -1.00000 -0.00017 -0.00006 -1.00000 -0.00137 -0.00179 -1.00000 -0.00311 -0.00406 -0.99999 0.00320 0.00318 -0.99999 0.00001 -0.00003 -1.00000 0.00000 -0.00003 -1.00000 0.00000 -0.00003 -1.00000 -0.00000 -0.00003 -1.00000 0.00002 -0.00004 -1.00000 -0.00031 0.00031 -1.00000 0.00022 -0.00034 -1.00000 -0.00018 0.00022 -1.00000 0.00005 -0.00013 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.99573 0.09228 -0.00199 -0.98257 0.18367 -0.02858 -0.60262 -0.79799 -0.00794 -0.67367 -0.73897 -0.00975 0.27354 -0.96136 -0.03099 0.36123 -0.93248 -0.00126 0.96173 -0.27366 -0.01346 0.98297 -0.18375 0.00253 0.99099 -0.13357 -0.00978 0.73900 0.67368 0.00575 0.68052 0.73273 0.00137 -0.27367 0.96182 0.00372 -0.36122 0.93246 -0.00628 -0.34217 0.93963 0.00438 + + + + + + + + + + 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + + +

354 636 1908 358 636 1909 359 636 1910 356 637 1911 352 637 1912 355 637 1913 359 638 1914 358 638 1915 355 638 1916 355 639 1917 352 639 1918 357 639 1919 362 640 1920 360 640 1921 352 640 1922 360 641 1923 357 641 1924 352 641 1925 360 642 1926 361 642 1927 357 642 1928 366 643 1929 354 643 1930 363 643 1931 363 644 1932 359 644 1933 355 644 1934 363 645 1935 355 645 1936 364 645 1937 355 646 1938 361 646 1939 364 646 1940 361 647 1941 355 647 1942 357 647 1943 366 648 1944 365 648 1945 354 648 1946 354 649 1947 359 649 1948 363 649 1949 381 650 1950 367 650 1951 374 650 1952 370 651 1953 378 651 1954 380 651 1955 371 652 1956 375 652 1957 369 652 1958 375 653 1959 378 653 1960 369 653 1961 378 654 1962 372 654 1963 369 654 1964 378 655 1965 368 655 1966 372 655 1967 368 656 1968 378 656 1969 370 656 1970 371 657 1971 379 657 1972 375 657 1973 371 658 1974 373 658 1975 379 658 1976 373 659 1977 377 659 1978 379 659 1979 381 660 1980 382 660 1981 367 660 1982 381 661 1983 374 661 1984 400 661 1985 402 662 1986 381 662 1987 400 662 1988 402 663 1989 400 663 1990 385 663 1991 402 664 1992 385 664 1993 401 664 1994 385 665 1995 391 665 1996 401 665 1997 392 666 1998 385 666 1999 400 666 2000 386 667 2001 392 667 2002 400 667 2003 388 668 2004 386 668 2005 400 668 2006 384 669 2007 388 669 2008 400 669 2009 387 670 2010 384 670 2011 400 670 2012 383 671 2013 387 671 2014 400 671 2015 389 672 2016 383 672 2017 400 672 2018 390 673 2019 389 673 2020 400 673 2021 395 674 2022 393 674 2023 390 674 2024 398 675 2025 395 675 2026 390 675 2027 396 676 2028 362 676 2029 352 676 2030 356 677 2031 396 677 2032 352 677 2033 376 678 2034 397 678 2035 398 678 2036 373 679 2037 399 679 2038 377 679 2039 399 680 2040 376 680 2041 377 680 2042 399 681 2043 397 681 2044 376 681 2045 355 682 2046 358 682 2047 356 682 2048 353 683 2049 403 683 2050 354 683 2051 354 684 2052 403 684 2053 358 684 2054 403 685 2055 401 685 2056 358 685 2057 403 686 2058 402 686 2059 401 686 2060 353 687 2061 354 687 2062 404 687 2063 401 688 2064 356 688 2065 358 688 2066 402 689 2067 353 689 2068 381 689 2069 353 690 2070 402 690 2071 403 690 2072 382 691 2073 381 691 2074 353 691 2075 406 692 2076 408 692 2077 407 692 2078 405 693 2079 360 693 2080 362 693 2081 405 694 2082 362 694 2083 396 694 2084 429 695 2085 635 695 2086 443 695 2087 635 696 2088 429 696 2089 633 696 2090 633 697 2091 429 697 2092 631 697 2093 633 698 2094 631 698 2095 382 698 2096 382 699 2097 631 699 2098 413 699 2099 549 700 2100 542 700 2101 533 700 2102 412 701 2103 411 701 2104 413 701 2105 412 702 2106 410 702 2107 411 702 2108 569 703 2109 634 703 2110 411 703 2111 410 704 2112 569 704 2113 411 704 2114 586 705 2115 632 705 2116 629 705 2117 634 706 2118 619 706 2119 636 706 2120 517 707 2121 634 707 2122 569 707 2123 589 708 2124 579 708 2125 626 708 2126 626 709 2127 579 709 2128 629 709 2129 629 710 2130 579 710 2131 606 710 2132 632 711 2133 586 711 2134 410 711 2135 622 712 2136 641 712 2137 640 712 2138 640 713 2139 593 713 2140 622 713 2141 619 714 2142 593 714 2143 640 714 2144 619 715 2145 640 715 2146 636 715 2147 574 716 2148 444 716 2149 594 716 2150 448 717 2151 458 717 2152 449 717 2153 447 718 2154 631 718 2155 429 718 2156 431 719 2157 631 719 2158 447 719 2159 421 720 2160 631 720 2161 431 720 2162 417 721 2163 631 721 2164 421 721 2165 432 722 2166 631 722 2167 417 722 2168 416 723 2169 631 723 2170 432 723 2171 437 724 2172 631 724 2173 416 724 2174 441 725 2175 631 725 2176 437 725 2177 434 726 2178 438 726 2179 597 726 2180 455 727 2181 438 727 2182 434 727 2183 455 728 2184 435 728 2185 438 728 2186 458 729 2187 435 729 2188 455 729 2189 456 730 2190 458 730 2191 455 730 2192 458 731 2193 459 731 2194 449 731 2195 458 732 2196 456 732 2197 459 732 2198 574 733 2199 604 733 2200 452 733 2201 459 734 2202 604 734 2203 449 734 2204 453 735 2205 457 735 2206 446 735 2207 452 736 2208 446 736 2209 574 736 2210 452 737 2211 453 737 2212 446 737 2213 454 738 2214 422 738 2215 453 738 2216 454 739 2217 419 739 2218 422 739 2219 454 740 2220 453 740 2221 452 740 2222 454 741 2223 530 741 2224 419 741 2225 443 742 2226 530 742 2227 454 742 2228 419 743 2229 530 743 2230 582 743 2231 425 744 2232 419 744 2233 582 744 2234 422 745 2235 419 745 2236 425 745 2237 422 746 2238 457 746 2239 453 746 2240 422 747 2241 445 747 2242 457 747 2243 422 748 2244 427 748 2245 445 748 2246 425 749 2247 427 749 2248 422 749 2249 437 750 2250 430 750 2251 434 750 2252 437 751 2253 434 751 2254 441 751 2255 432 752 2256 414 752 2257 416 752 2258 432 753 2259 428 753 2260 414 753 2261 417 754 2262 428 754 2263 432 754 2264 417 755 2265 433 755 2266 428 755 2267 421 756 2268 433 756 2269 417 756 2270 429 757 2271 423 757 2272 447 757 2273 443 758 2274 423 758 2275 429 758 2276 415 759 2277 597 759 2278 438 759 2279 409 760 2280 438 760 2281 435 760 2282 409 761 2283 415 761 2284 438 761 2285 448 762 2286 435 762 2287 458 762 2288 440 763 2289 435 763 2290 448 763 2291 440 764 2292 409 764 2293 435 764 2294 597 765 2295 441 765 2296 434 765 2297 624 766 2298 441 766 2299 597 766 2300 434 767 2301 430 767 2302 455 767 2303 493 768 2304 582 768 2305 530 768 2306 493 769 2307 425 769 2308 582 769 2309 454 770 2310 423 770 2311 443 770 2312 430 771 2313 416 771 2314 414 771 2315 414 772 2316 439 772 2317 430 772 2318 428 773 2319 439 773 2320 414 773 2321 428 774 2322 436 774 2323 439 774 2324 433 775 2325 436 775 2326 428 775 2327 420 776 2328 436 776 2329 433 776 2330 420 777 2331 424 777 2332 436 777 2333 426 778 2334 424 778 2335 420 778 2336 426 779 2337 423 779 2338 424 779 2339 420 780 2340 421 780 2341 431 780 2342 433 781 2343 421 781 2344 420 781 2345 423 782 2346 431 782 2347 447 782 2348 426 783 2349 431 783 2350 423 783 2351 420 784 2352 431 784 2353 426 784 2354 415 785 2355 471 785 2356 597 785 2357 409 786 2358 471 786 2359 415 786 2360 450 787 2361 599 787 2362 451 787 2363 444 788 2364 445 788 2365 451 788 2366 445 789 2367 450 789 2368 451 789 2369 450 790 2370 445 790 2371 427 790 2372 446 791 2373 444 791 2374 574 791 2375 446 792 2376 457 792 2377 444 792 2378 440 793 2379 449 793 2380 506 793 2381 440 794 2382 448 794 2383 449 794 2384 440 795 2385 559 795 2386 524 795 2387 506 796 2388 559 796 2389 440 796 2390 445 797 2391 444 797 2392 457 797 2393 437 798 2394 416 798 2395 430 798 2396 591 799 2397 578 799 2398 489 799 2399 591 800 2400 489 800 2401 523 800 2402 523 801 2403 537 801 2404 591 801 2405 599 802 2406 507 802 2407 451 802 2408 507 803 2409 594 803 2410 451 803 2411 449 804 2412 604 804 2413 612 804 2414 594 805 2415 604 805 2416 574 805 2417 612 806 2418 604 806 2419 594 806 2420 564 807 2421 588 807 2422 484 807 2423 577 808 2424 587 808 2425 482 808 2426 577 809 2427 565 809 2428 587 809 2429 544 810 2430 565 810 2431 577 810 2432 512 811 2433 565 811 2434 544 811 2435 512 812 2436 557 812 2437 565 812 2438 564 813 2439 553 813 2440 486 813 2441 619 814 2442 522 814 2443 573 814 2444 517 815 2445 569 815 2446 594 815 2447 517 816 2448 619 816 2449 634 816 2450 522 817 2451 619 817 2452 517 817 2453 594 818 2454 468 818 2455 469 818 2456 468 819 2457 594 819 2458 616 819 2459 616 820 2460 483 820 2461 468 820 2462 483 821 2463 616 821 2464 615 821 2465 594 822 2466 507 822 2467 616 822 2468 607 823 2469 586 823 2470 511 823 2471 586 824 2472 607 824 2473 612 824 2474 612 825 2475 569 825 2476 586 825 2477 594 826 2478 569 826 2479 612 826 2480 594 827 2481 469 827 2482 517 827 2483 511 828 2484 532 828 2485 541 828 2486 586 829 2487 532 829 2488 511 829 2489 511 830 2490 558 830 2491 508 830 2492 541 831 2493 558 831 2494 511 831 2495 511 832 2496 497 832 2497 580 832 2498 508 833 2499 497 833 2500 511 833 2501 629 834 2502 606 834 2503 532 834 2504 532 835 2505 586 835 2506 629 835 2507 532 836 2508 606 836 2509 588 836 2510 606 837 2511 484 837 2512 588 837 2513 594 838 2514 444 838 2515 451 838 2516 565 839 2517 557 839 2518 587 839 2519 557 840 2520 598 840 2521 587 840 2522 486 841 2523 588 841 2524 564 841 2525 564 842 2526 476 842 2527 553 842 2528 618 843 2529 476 843 2530 564 843 2531 410 844 2532 586 844 2533 569 844 2534 460 845 2535 576 845 2536 491 845 2537 460 846 2538 491 846 2539 553 846 2540 460 847 2541 553 847 2542 476 847 2543 490 848 2544 465 848 2545 519 848 2546 576 849 2547 465 849 2548 490 849 2549 576 850 2550 488 850 2551 465 850 2552 576 851 2553 460 851 2554 488 851 2555 511 852 2556 602 852 2557 524 852 2558 511 853 2559 475 853 2560 602 853 2561 524 854 2562 607 854 2563 511 854 2564 482 855 2565 587 855 2566 481 855 2567 481 856 2568 587 856 2569 585 856 2570 585 857 2571 518 857 2572 481 857 2573 573 858 2574 572 858 2575 593 858 2576 540 859 2577 572 859 2578 573 859 2579 532 860 2580 486 860 2581 553 860 2582 588 861 2583 486 861 2584 532 861 2585 553 862 2586 491 862 2587 532 862 2588 606 863 2589 603 863 2590 618 863 2591 606 864 2592 579 864 2593 603 864 2594 522 865 2595 517 865 2596 617 865 2597 617 866 2598 521 866 2599 545 866 2600 517 867 2601 521 867 2602 617 867 2603 524 868 2604 602 868 2605 502 868 2606 602 869 2607 475 869 2608 502 869 2609 543 870 2610 578 870 2611 498 870 2612 543 871 2613 489 871 2614 578 871 2615 461 872 2616 489 872 2617 543 872 2618 495 873 2619 489 873 2620 461 873 2621 495 874 2622 523 874 2623 489 874 2624 526 875 2625 523 875 2626 495 875 2627 526 876 2628 537 876 2629 523 876 2630 572 877 2631 592 877 2632 598 877 2633 476 878 2634 618 878 2635 591 878 2636 520 879 2637 616 879 2638 507 879 2639 504 880 2640 616 880 2641 520 880 2642 484 881 2643 618 881 2644 564 881 2645 484 882 2646 606 882 2647 618 882 2648 612 883 2649 506 883 2650 449 883 2651 504 884 2652 520 884 2653 515 884 2654 572 885 2655 552 885 2656 593 885 2657 572 886 2658 512 886 2659 552 886 2660 598 887 2661 512 887 2662 572 887 2663 512 888 2664 598 888 2665 557 888 2666 618 889 2667 578 889 2668 591 889 2669 618 890 2670 498 890 2671 578 890 2672 618 891 2673 610 891 2674 498 891 2675 612 892 2676 559 892 2677 506 892 2678 612 893 2679 607 893 2680 559 893 2681 537 894 2682 476 894 2683 591 894 2684 460 895 2685 476 895 2686 537 895 2687 460 896 2688 537 896 2689 488 896 2690 488 897 2691 537 897 2692 526 897 2693 526 898 2694 581 898 2695 488 898 2696 598 899 2697 585 899 2698 587 899 2699 592 900 2700 585 900 2701 598 900 2702 519 901 2703 509 901 2704 490 901 2705 527 902 2706 509 902 2707 595 902 2708 490 903 2709 509 903 2710 527 903 2711 580 904 2712 595 904 2713 511 904 2714 595 905 2715 580 905 2716 527 905 2717 511 906 2718 595 906 2719 475 906 2720 605 907 2721 596 907 2722 600 907 2723 600 908 2724 555 908 2725 605 908 2726 596 909 2727 605 909 2728 615 909 2729 504 910 2730 615 910 2731 616 910 2732 567 911 2733 615 911 2734 504 911 2735 596 912 2736 615 912 2737 567 912 2738 592 913 2739 545 913 2740 585 913 2741 545 914 2742 478 914 2743 518 914 2744 545 915 2745 521 915 2746 478 915 2747 545 916 2748 518 916 2749 585 916 2750 555 917 2751 518 917 2752 478 917 2753 555 918 2754 600 918 2755 518 918 2756 617 919 2757 573 919 2758 522 919 2759 617 920 2760 540 920 2761 573 920 2762 540 921 2763 617 921 2764 545 921 2765 572 922 2766 545 922 2767 592 922 2768 540 923 2769 545 923 2770 572 923 2771 567 924 2772 485 924 2773 503 924 2774 567 925 2775 494 925 2776 485 925 2777 472 926 2778 494 926 2779 470 926 2780 472 927 2781 485 927 2782 494 927 2783 493 928 2784 485 928 2785 472 928 2786 493 929 2787 503 929 2788 485 929 2789 466 930 2790 503 930 2791 493 930 2792 548 931 2793 583 931 2794 570 931 2795 509 932 2796 583 932 2797 548 932 2798 480 933 2799 467 933 2800 548 933 2801 608 934 2802 467 934 2803 480 934 2804 608 935 2805 528 935 2806 467 935 2807 480 936 2808 548 936 2809 570 936 2810 480 937 2811 581 937 2812 608 937 2813 570 938 2814 581 938 2815 480 938 2816 624 939 2817 542 939 2818 563 939 2819 510 940 2820 547 940 2821 584 940 2822 563 941 2823 549 941 2824 547 941 2825 563 942 2826 542 942 2827 549 942 2828 510 943 2829 610 943 2830 589 943 2831 510 944 2832 584 944 2833 610 944 2834 547 945 2835 571 945 2836 584 945 2837 547 946 2838 625 946 2839 563 946 2840 510 947 2841 625 947 2842 547 947 2843 549 948 2844 571 948 2845 547 948 2846 549 949 2847 533 949 2848 571 949 2849 611 950 2850 533 950 2851 542 950 2852 492 951 2853 551 951 2854 560 951 2855 492 952 2856 534 952 2857 551 952 2858 534 953 2859 461 953 2860 543 953 2861 534 954 2862 495 954 2863 461 954 2864 492 955 2865 495 955 2866 534 955 2867 492 956 2868 526 956 2869 495 956 2870 560 957 2871 526 957 2872 492 957 2873 473 958 2874 561 958 2875 463 958 2876 513 959 2877 561 959 2878 473 959 2879 513 960 2880 481 960 2881 561 960 2882 482 961 2883 481 961 2884 513 961 2885 465 962 2886 583 962 2887 519 962 2888 488 963 2889 583 963 2890 465 963 2891 488 964 2892 570 964 2893 583 964 2894 488 965 2895 581 965 2896 570 965 2897 583 966 2898 509 966 2899 519 966 2900 462 967 2901 577 967 2902 482 967 2903 544 968 2904 464 968 2905 512 968 2906 544 969 2907 501 969 2908 464 969 2909 577 970 2910 501 970 2911 544 970 2912 462 971 2913 501 971 2914 577 971 2915 462 972 2916 525 972 2917 501 972 2918 513 973 2919 525 973 2920 462 973 2921 513 974 2922 473 974 2923 525 974 2924 482 975 2925 513 975 2926 462 975 2927 505 976 2928 466 976 2929 463 976 2930 601 977 2931 466 977 2932 505 977 2933 609 978 2934 466 978 2935 601 978 2936 609 979 2937 503 979 2938 466 979 2939 596 980 2940 503 980 2941 609 980 2942 596 981 2943 567 981 2944 503 981 2945 504 982 2946 494 982 2947 567 982 2948 470 983 2949 494 983 2950 504 983 2951 622 984 2952 556 984 2953 623 984 2954 552 985 2955 556 985 2956 622 985 2957 566 986 2958 556 986 2959 552 986 2960 568 987 2961 556 987 2962 566 987 2963 568 988 2964 546 988 2965 556 988 2966 536 989 2967 546 989 2968 568 989 2969 536 990 2970 562 990 2971 546 990 2972 531 991 2973 590 991 2974 562 991 2975 562 992 2976 496 992 2977 546 992 2978 562 993 2979 590 993 2980 496 993 2981 546 994 2982 623 994 2983 556 994 2984 546 995 2985 496 995 2986 623 995 2987 496 996 2988 620 996 2989 623 996 2990 496 997 2991 621 997 2992 620 997 2993 562 998 2994 536 998 2995 531 998 2996 552 999 2997 622 999 2998 593 999 2999 560 1000 3000 611 1000 3001 528 1000 3002 611 1001 3003 479 1001 3004 528 1001 3005 542 1002 3006 479 1002 3007 611 1002 3008 597 1003 3009 542 1003 3010 624 1003 3011 479 1004 3012 542 1004 3013 597 1004 3014 475 1005 3015 514 1005 3016 516 1005 3017 475 1006 3018 595 1006 3019 514 1006 3020 535 1007 3021 469 1007 3022 468 1007 3023 529 1008 3024 469 1008 3025 535 1008 3026 483 1009 3027 539 1009 3028 487 1009 3029 483 1010 3030 613 1010 3031 539 1010 3032 615 1011 3033 613 1011 3034 483 1011 3035 487 1012 3036 468 1012 3037 483 1012 3038 535 1013 3039 468 1013 3040 487 1013 3041 615 1014 3042 605 1014 3043 613 1014 3044 541 1015 3045 491 1015 3046 576 1015 3047 532 1016 3048 491 1016 3049 541 1016 3050 601 1017 3051 614 1017 3052 609 1017 3053 499 1018 3054 477 1018 3055 614 1018 3056 561 1019 3057 477 1019 3058 499 1019 3059 561 1020 3060 481 1020 3061 477 1020 3062 499 1021 3063 601 1021 3064 505 1021 3065 614 1022 3066 601 1022 3067 499 1022 3068 499 1023 3069 463 1023 3070 561 1023 3071 505 1024 3072 463 1024 3073 499 1024 3074 536 1025 3075 525 1025 3076 473 1025 3077 536 1026 3078 501 1026 3079 525 1026 3080 568 1027 3081 501 1027 3082 536 1027 3083 568 1028 3084 464 1028 3085 501 1028 3086 568 1029 3087 512 1029 3088 464 1029 3089 566 1030 3090 512 1030 3091 568 1030 3092 552 1031 3093 512 1031 3094 566 1031 3095 576 1032 3096 554 1032 3097 541 1032 3098 550 1033 3099 554 1033 3100 576 1033 3101 576 1034 3102 500 1034 3103 550 1034 3104 490 1035 3105 500 1035 3106 576 1035 3107 490 1036 3108 538 1036 3109 500 1036 3110 490 1037 3111 527 1037 3112 538 1037 3113 579 1038 3114 589 1038 3115 603 1038 3116 603 1039 3117 589 1039 3118 610 1039 3119 603 1040 3120 610 1040 3121 618 1040 3122 530 1041 3123 621 1041 3124 590 1041 3125 590 1042 3126 466 1042 3127 530 1042 3128 531 1043 3129 466 1043 3130 590 1043 3131 531 1044 3132 473 1044 3133 466 1044 3134 473 1045 3135 463 1045 3136 466 1045 3137 526 1046 3138 608 1046 3139 581 1046 3140 560 1047 3141 608 1047 3142 526 1047 3143 560 1048 3144 528 1048 3145 608 1048 3146 493 1049 3147 530 1049 3148 466 1049 3149 470 1050 3150 425 1050 3151 472 1050 3152 472 1051 3153 425 1051 3154 493 1051 3155 518 1052 3156 477 1052 3157 481 1052 3158 614 1053 3159 477 1053 3160 518 1053 3161 609 1054 3162 600 1054 3163 596 1054 3164 614 1055 3165 600 1055 3166 609 1055 3167 614 1056 3168 518 1056 3169 600 1056 3170 535 1057 3171 478 1057 3172 529 1057 3173 555 1058 3174 613 1058 3175 605 1058 3176 555 1059 3177 539 1059 3178 613 1059 3179 478 1060 3180 539 1060 3181 555 1060 3182 478 1061 3183 487 1061 3184 539 1061 3185 478 1062 3186 535 1062 3187 487 1062 3188 529 1063 3189 517 1063 3190 469 1063 3191 597 1064 3192 471 1064 3193 479 1064 3194 471 1065 3195 409 1065 3196 575 1065 3197 409 1066 3198 516 1066 3199 575 1066 3200 551 1067 3201 611 1067 3202 560 1067 3203 551 1068 3204 533 1068 3205 611 1068 3206 534 1069 3207 533 1069 3208 551 1069 3209 534 1070 3210 571 1070 3211 533 1070 3212 543 1071 3213 571 1071 3214 534 1071 3215 543 1072 3216 584 1072 3217 571 1072 3218 498 1073 3219 584 1073 3220 543 1073 3221 498 1074 3222 610 1074 3223 584 1074 3224 575 1075 3225 595 1075 3226 471 1075 3227 575 1076 3228 514 1076 3229 595 1076 3230 516 1077 3231 514 1077 3232 575 1077 3233 520 1078 3234 507 1078 3235 474 1078 3236 507 1079 3237 599 1079 3238 474 1079 3239 599 1080 3240 515 1080 3241 520 1080 3242 520 1081 3243 474 1081 3244 599 1081 3245 607 1082 3246 524 1082 3247 559 1082 3248 440 1083 3249 524 1083 3250 502 1083 3251 554 1084 3252 558 1084 3253 541 1084 3254 550 1085 3255 558 1085 3256 554 1085 3257 550 1086 3258 508 1086 3259 558 1086 3260 500 1087 3261 508 1087 3262 550 1087 3263 500 1088 3264 497 1088 3265 508 1088 3266 538 1089 3267 497 1089 3268 500 1089 3269 538 1090 3270 580 1090 3271 497 1090 3272 580 1091 3273 538 1091 3274 527 1091 3275 478 1092 3276 517 1092 3277 529 1092 3278 521 1093 3279 517 1093 3280 478 1093 3281 479 1094 3282 467 1094 3283 528 1094 3284 471 1095 3285 467 1095 3286 479 1095 3287 471 1096 3288 548 1096 3289 467 1096 3290 471 1097 3291 509 1097 3292 548 1097 3293 595 1098 3294 509 1098 3295 471 1098 3296 590 1099 3297 621 1099 3298 496 1099 3299 473 1100 3300 531 1100 3301 536 1100 3302 573 1101 3303 593 1101 3304 619 1101 3305 623 1102 3306 641 1102 3307 622 1102 3308 623 1103 3309 638 1103 3310 641 1103 3311 620 1104 3312 638 1104 3313 623 1104 3314 621 1105 3315 638 1105 3316 620 1105 3317 621 1106 3318 637 1106 3319 638 1106 3320 627 1107 3321 624 1107 3322 563 1107 3323 589 1108 3324 626 1108 3325 630 1108 3326 589 1109 3327 630 1109 3328 510 1109 3329 510 1110 3330 630 1110 3331 628 1110 3332 510 1111 3333 628 1111 3334 625 1111 3335 625 1112 3336 628 1112 3337 627 1112 3338 625 1113 3339 627 1113 3340 563 1113 3341 641 1114 3342 638 1114 3343 640 1114 3344 636 1115 3345 639 1115 3346 404 1115 3347 636 1116 3348 404 1116 3349 634 1116 3350 638 1117 3351 637 1117 3352 640 1117 3353 640 1118 3354 637 1118 3355 639 1118 3356 640 1119 3357 639 1119 3358 636 1119 3359 367 1120 3360 413 1120 3361 411 1120 3362 635 1121 3363 633 1121 3364 639 1121 3365 633 1122 3366 404 1122 3367 639 1122 3368 404 1123 3369 354 1123 3370 634 1123 3371 639 1124 3372 637 1124 3373 635 1124 3374 411 1125 3375 634 1125 3376 354 1125 3377 367 1126 3378 382 1126 3379 413 1126 3380 404 1127 3381 633 1127 3382 382 1127 3383 382 1128 3384 353 1128 3385 404 1128 3386 354 1129 3387 642 1129 3388 411 1129 3389 367 1130 3390 411 1130 3391 642 1130 3392 643 1131 3393 365 1131 3394 370 1131 3395 380 1132 3396 643 1132 3397 370 1132 3398 643 1133 3399 642 1133 3400 365 1133 3401 365 1134 3402 642 1134 3403 354 1134 3404 374 1135 3405 642 1135 3406 643 1135 3407 374 1136 3408 367 1136 3409 642 1136 3410 374 1137 3411 643 1137 3412 410 1137 3413 380 1138 3414 410 1138 3415 643 1138 3416 657 1139 3417 410 1139 3418 380 1139 3419 654 1140 3420 649 1140 3421 651 1140 3422 649 1141 3423 654 1141 3424 645 1141 3425 374 1142 3426 412 1142 3427 654 1142 3428 410 1143 3429 657 1143 3430 648 1143 3431 410 1144 3432 648 1144 3433 632 1144 3434 647 1145 3435 646 1145 3436 627 1145 3437 629 1146 3438 632 1146 3439 648 1146 3440 649 1147 3441 648 1147 3442 657 1147 3443 645 1148 3444 647 1148 3445 649 1148 3446 646 1149 3447 647 1149 3448 645 1149 3449 374 1150 3450 410 1150 3451 412 1150 3452 626 1151 3453 629 1151 3454 647 1151 3455 626 1152 3456 647 1152 3457 627 1152 3458 628 1153 3459 626 1153 3460 627 1153 3461 629 1154 3462 648 1154 3463 649 1154 3464 629 1155 3465 649 1155 3466 647 1155 3467 630 1156 3468 626 1156 3469 628 1156 3470 654 1157 3471 651 1157 3472 655 1157 3473 651 1158 3474 653 1158 3475 652 1158 3476 652 1159 3477 655 1159 3478 651 1159 3479 650 1160 3480 656 1160 3481 376 1160 3482 651 1161 3483 649 1161 3484 657 1161 3485 653 1162 3486 650 1162 3487 652 1162 3488 653 1163 3489 656 1163 3490 650 1163 3491 657 1164 3492 656 1164 3493 653 1164 3494 651 1165 3495 657 1165 3496 653 1165 3497 375 1166 3498 376 1166 3499 656 1166 3500 377 1167 3501 376 1167 3502 379 1167 3503 655 1168 3504 374 1168 3505 654 1168 3506 378 1169 3507 375 1169 3508 656 1169 3509 375 1170 3510 379 1170 3511 376 1170 3512 657 1171 3513 378 1171 3514 656 1171 3515 380 1172 3516 378 1172 3517 657 1172 3518 376 1173 3519 398 1173 3520 650 1173 3521 650 1174 3522 398 1174 3523 390 1174 3524 627 1175 3525 646 1175 3526 624 1175 3527 646 1176 3528 441 1176 3529 624 1176 3530 441 1177 3531 646 1177 3532 645 1177 3533 441 1178 3534 645 1178 3535 631 1178 3536 631 1179 3537 645 1179 3538 654 1179 3539 413 1180 3540 631 1180 3541 654 1180 3542 412 1181 3543 413 1181 3544 654 1181 3545 390 1182 3546 652 1182 3547 650 1182 3548 390 1183 3549 400 1183 3550 652 1183 3551 400 1184 3552 655 1184 3553 652 1184 3554 374 1185 3555 655 1185 3556 400 1185 3557 470 1186 3558 504 1186 3559 515 1186 3560 427 1187 3561 470 1187 3562 515 1187 3563 427 1188 3564 425 1188 3565 470 1188 3566 475 1189 3567 516 1189 3568 502 1189 3569 440 1190 3570 502 1190 3571 516 1190 3572 409 1191 3573 440 1191 3574 516 1191 3575 442 1192 3576 604 1192 3577 459 1192 3578 442 1193 3579 452 1193 3580 604 1193 3581 442 1194 3582 459 1194 3583 456 1194 3584 418 1195 3585 442 1195 3586 456 1195 3587 418 1196 3588 454 1196 3589 442 1196 3590 442 1197 3591 454 1197 3592 452 1197 3593 418 1198 3594 456 1198 3595 439 1198 3596 418 1199 3597 424 1199 3598 454 1199 3599 439 1200 3600 456 1200 3601 455 1200 3602 430 1201 3603 439 1201 3604 455 1201 3605 423 1202 3606 454 1202 3607 424 1202 3608 418 1203 3609 436 1203 3610 424 1203 3611 418 1204 3612 439 1204 3613 436 1204 3614 427 1205 3615 515 1205 3616 450 1205 3617 450 1206 3618 515 1206 3619 599 1206 3620 810 1207 3621 681 1207 3622 750 1207 3623 825 1208 3624 810 1208 3625 750 1208 3626 833 1209 3627 820 1209 3628 818 1209 3629 833 1210 3630 828 1210 3631 820 1210 3632 829 1211 3633 828 1211 3634 807 1211 3635 823 1212 3636 806 1212 3637 818 1212 3638 818 1213 3639 806 1213 3640 805 1213 3641 833 1214 3642 807 1214 3643 828 1214 3644 833 1215 3645 818 1215 3646 805 1215 3647 816 1216 3648 804 1216 3649 807 1216 3650 833 1217 3651 816 1217 3652 807 1217 3653 833 1218 3654 805 1218 3655 816 1218 3656 816 1219 3657 805 1219 3658 801 1219 3659 816 1220 3660 674 1220 3661 804 1220 3662 816 1221 3663 801 1221 3664 674 1221 3665 836 1222 3666 749 1222 3667 817 1222 3668 817 1223 3669 749 1223 3670 763 1223 3671 789 1224 3672 763 1224 3673 749 1224 3674 825 1225 3675 730 1225 3676 827 1225 3677 825 1226 3678 750 1226 3679 730 1226 3680 730 1227 3681 750 1227 3682 761 1227 3683 701 1228 3684 363 1228 3685 364 1228 3686 770 1229 3687 715 1229 3688 736 1229 3689 683 1230 3690 680 1230 3691 755 1230 3692 680 1231 3693 722 1231 3694 755 1231 3695 680 1232 3696 791 1232 3697 722 1232 3698 791 1233 3699 794 1233 3700 722 1233 3701 791 1234 3702 785 1234 3703 794 1234 3704 785 1235 3705 738 1235 3706 794 1235 3707 745 1236 3708 786 1236 3709 366 1236 3710 786 1237 3711 737 1237 3712 366 1237 3713 694 1238 3714 739 1238 3715 731 1238 3716 731 1239 3717 768 1239 3718 694 1239 3719 731 1240 3720 765 1240 3721 768 1240 3722 765 1241 3723 756 1241 3724 768 1241 3725 765 1242 3726 721 1242 3727 756 1242 3728 721 1243 3729 712 1243 3730 756 1243 3731 721 1244 3732 717 1244 3733 712 1244 3734 717 1245 3735 727 1245 3736 712 1245 3737 817 1246 3738 763 1246 3739 742 1246 3740 670 1247 3741 711 1247 3742 742 1247 3743 746 1248 3744 681 1248 3745 790 1248 3746 681 1249 3747 746 1249 3748 750 1249 3749 757 1250 3750 790 1250 3751 681 1250 3752 746 1251 3753 790 1251 3754 757 1251 3755 749 1252 3756 699 1252 3757 751 1252 3758 699 1253 3759 683 1253 3760 751 1253 3761 699 1254 3762 680 1254 3763 683 1254 3764 791 1255 3765 680 1255 3766 699 1255 3767 767 1256 3768 690 1256 3769 666 1256 3770 767 1257 3771 726 1257 3772 690 1257 3773 726 1258 3774 702 1258 3775 690 1258 3776 726 1259 3777 734 1259 3778 702 1259 3779 734 1260 3780 735 1260 3781 702 1260 3782 734 1261 3783 720 1261 3784 735 1261 3785 720 1262 3786 665 1262 3787 735 1262 3788 720 1263 3789 710 1263 3790 665 1263 3791 836 1264 3792 699 1264 3793 749 1264 3794 791 1265 3795 699 1265 3796 836 1265 3797 395 1266 3798 785 1266 3799 791 1266 3800 737 1267 3801 792 1267 3802 366 1267 3803 786 1268 3804 778 1268 3805 733 1268 3806 786 1269 3807 729 1269 3808 778 1269 3809 786 1270 3810 716 1270 3811 729 1270 3812 716 1271 3813 663 1271 3814 729 1271 3815 716 1272 3816 673 1272 3817 663 1272 3818 733 1273 3819 737 1273 3820 786 1273 3821 662 1274 3822 679 1274 3823 748 1274 3824 662 1275 3825 668 1275 3826 679 1275 3827 668 1276 3828 682 1276 3829 679 1276 3830 662 1277 3831 748 1277 3832 787 1277 3833 748 1278 3834 783 1278 3835 787 1278 3836 730 1279 3837 759 1279 3838 827 1279 3839 759 1280 3840 677 1280 3841 692 1280 3842 710 1281 3843 669 1281 3844 738 1281 3845 710 1282 3846 740 1282 3847 669 1282 3848 740 1283 3849 693 1283 3850 669 1283 3851 770 1284 3852 677 1284 3853 797 1284 3854 736 1285 3855 677 1285 3856 770 1285 3857 736 1286 3858 667 1286 3859 677 1286 3860 667 1287 3861 394 1287 3862 677 1287 3863 394 1288 3864 667 1288 3865 396 1288 3866 675 1289 3867 658 1289 3868 666 1289 3869 675 1290 3870 666 1290 3871 371 1290 3872 369 1291 3873 675 1291 3874 371 1291 3875 775 1292 3876 731 1292 3877 739 1292 3878 775 1293 3879 765 1293 3880 731 1293 3881 775 1294 3882 698 1294 3883 765 1294 3884 698 1295 3885 721 1295 3886 765 1295 3887 721 1296 3888 698 1296 3889 717 1296 3890 698 1297 3891 727 1297 3892 717 1297 3893 719 1298 3894 706 1298 3895 753 1298 3896 706 1299 3897 704 1299 3898 753 1299 3899 704 1300 3900 796 1300 3901 753 1300 3902 704 1301 3903 764 1301 3904 796 1301 3905 704 1302 3906 715 1302 3907 764 1302 3908 715 1303 3909 741 1303 3910 764 1303 3911 715 1304 3912 770 1304 3913 741 1304 3914 760 1305 3915 766 1305 3916 797 1305 3917 766 1306 3918 709 1306 3919 797 1306 3920 662 1307 3921 766 1307 3922 678 1307 3923 766 1308 3924 760 1308 3925 678 1308 3926 709 1309 3927 787 1309 3928 783 1309 3929 709 1310 3930 766 1310 3931 787 1310 3932 766 1311 3933 662 1311 3934 787 1311 3935 678 1312 3936 668 1312 3937 662 1312 3938 368 1313 3939 727 1313 3940 774 1313 3941 727 1314 3942 698 1314 3943 774 1314 3944 661 1315 3945 663 1315 3946 673 1315 3947 733 1316 3948 778 1316 3949 793 1316 3950 778 1317 3951 781 1317 3952 793 1317 3953 661 1318 3954 781 1318 3955 663 1318 3956 781 1319 3957 729 1319 3958 663 1319 3959 781 1320 3960 778 1320 3961 729 1320 3962 737 1321 3963 733 1321 3964 792 1321 3965 733 1322 3966 793 1322 3967 792 1322 3968 789 1323 3969 751 1323 3970 683 1323 3971 789 1324 3972 749 1324 3973 751 1324 3974 785 1325 3975 395 1325 3976 672 1325 3977 395 1326 3978 398 1326 3979 672 1326 3980 672 1327 3981 665 1327 3982 785 1327 3983 665 1328 3984 738 1328 3985 785 1328 3986 710 1329 3987 738 1329 3988 665 1329 3989 719 1330 3990 364 1330 3991 361 1330 3992 686 1331 3993 736 1331 3994 715 1331 3995 667 1332 3996 405 1332 3997 396 1332 3998 723 1333 3999 360 1333 4000 405 1333 4001 723 1334 4002 714 1334 4003 360 1334 4004 667 1335 4005 686 1335 4006 405 1335 4007 686 1336 4008 723 1336 4009 405 1336 4010 736 1337 4011 686 1337 4012 667 1337 4013 715 1338 4014 723 1338 4015 686 1338 4016 715 1339 4017 704 1339 4018 723 1339 4019 704 1340 4020 714 1340 4021 723 1340 4022 704 1341 4023 706 1341 4024 714 1341 4025 706 1342 4026 719 1342 4027 714 1342 4028 719 1343 4029 361 1343 4030 714 1343 4031 361 1344 4032 360 1344 4033 714 1344 4034 730 1345 4035 761 1345 4036 771 1345 4037 761 1346 4038 705 1346 4039 771 1346 4040 682 1347 4041 762 1347 4042 705 1347 4043 682 1348 4044 668 1348 4045 762 1348 4046 668 1349 4047 677 1349 4048 762 1349 4049 668 1350 4050 678 1350 4051 677 1350 4052 678 1351 4053 760 1351 4054 677 1351 4055 760 1352 4056 797 1352 4057 677 1352 4058 782 1353 4059 798 1353 4060 752 1353 4061 752 1354 4062 741 1354 4063 770 1354 4064 752 1355 4065 798 1355 4066 741 1355 4067 798 1356 4068 764 1356 4069 741 1356 4070 798 1357 4071 697 1357 4072 764 1357 4073 697 1358 4074 725 1358 4075 764 1358 4076 725 1359 4077 796 1359 4078 764 1359 4079 725 1360 4080 753 1360 4081 796 1360 4082 798 1361 4083 782 1361 4084 697 1361 4085 691 1362 4086 747 1362 4087 755 1362 4088 777 1363 4089 703 1363 4090 693 1363 4091 777 1364 4092 691 1364 4093 703 1364 4094 777 1365 4095 795 1365 4096 691 1365 4097 795 1366 4098 747 1366 4099 691 1366 4100 782 1367 4101 752 1367 4102 783 1367 4103 752 1368 4104 709 1368 4105 783 1368 4106 752 1369 4107 770 1369 4108 709 1369 4109 770 1370 4110 797 1370 4111 709 1370 4112 710 1371 4113 773 1371 4114 740 1371 4115 773 1372 4116 769 1372 4117 740 1372 4118 773 1373 4119 734 1373 4120 769 1373 4121 734 1374 4122 799 1374 4123 769 1374 4124 734 1375 4125 726 1375 4126 799 1375 4127 773 1376 4128 720 1376 4129 734 1376 4130 773 1377 4131 710 1377 4132 720 1377 4133 665 1378 4134 672 1378 4135 735 1378 4136 696 1379 4137 702 1379 4138 735 1379 4139 696 1380 4140 671 1380 4141 702 1380 4142 373 1381 4143 671 1381 4144 399 1381 4145 671 1382 4146 397 1382 4147 399 1382 4148 671 1383 4149 690 1383 4150 702 1383 4151 373 1384 4152 666 1384 4153 690 1384 4154 373 1385 4155 371 1385 4156 666 1385 4157 397 1386 4158 696 1386 4159 672 1386 4160 397 1387 4161 671 1387 4162 696 1387 4163 671 1388 4164 373 1388 4165 690 1388 4166 398 1389 4167 397 1389 4168 672 1389 4169 703 1390 4170 784 1390 4171 693 1390 4172 784 1391 4173 669 1391 4174 693 1391 4175 784 1392 4176 703 1392 4177 722 1392 4178 669 1393 4179 794 1393 4180 738 1393 4181 669 1394 4182 784 1394 4183 794 1394 4184 784 1395 4185 722 1395 4186 794 1395 4187 755 1396 4188 722 1396 4189 691 1396 4190 722 1397 4191 703 1397 4192 691 1397 4193 677 1398 4194 772 1398 4195 762 1398 4196 759 1399 4197 771 1399 4198 772 1399 4199 759 1400 4200 730 1400 4201 771 1400 4202 772 1401 4203 677 1401 4204 759 1401 4205 705 1402 4206 772 1402 4207 771 1402 4208 705 1403 4209 762 1403 4210 772 1403 4211 728 1404 4212 406 1404 4213 724 1404 4214 406 1405 4215 407 1405 4216 724 1405 4217 728 1406 4218 724 1406 4219 659 1406 4220 659 1407 4221 701 1407 4222 728 1407 4223 659 1408 4224 744 1408 4225 701 1408 4226 716 1409 4227 748 1409 4228 679 1409 4229 716 1410 4230 786 1410 4231 748 1410 4232 724 1411 4233 689 1411 4234 748 1411 4235 724 1412 4236 786 1412 4237 745 1412 4238 724 1413 4239 748 1413 4240 786 1413 4241 407 1414 4242 689 1414 4243 724 1414 4244 682 1415 4245 705 1415 4246 661 1415 4247 705 1416 4248 761 1416 4249 661 1416 4250 761 1417 4251 660 1417 4252 661 1417 4253 682 1418 4254 661 1418 4255 673 1418 4256 679 1419 4257 673 1419 4258 716 1419 4259 673 1420 4260 679 1420 4261 682 1420 4262 754 1421 4263 789 1421 4264 683 1421 4265 683 1422 4266 739 1422 4267 694 1422 4268 694 1423 4269 754 1423 4270 683 1423 4271 775 1424 4272 739 1424 4273 755 1424 4274 739 1425 4275 683 1425 4276 755 1425 4277 747 1426 4278 775 1426 4279 755 1426 4280 407 1427 4281 408 1427 4282 689 1427 4283 408 1428 4284 688 1428 4285 689 1428 4286 740 1429 4287 777 1429 4288 693 1429 4289 777 1430 4290 740 1430 4291 732 1430 4292 800 1431 4293 777 1431 4294 732 1431 4295 800 1432 4296 732 1432 4297 788 1432 4298 732 1433 4299 685 1433 4300 788 1433 4301 664 1434 4302 711 1434 4303 670 1434 4304 664 1435 4305 758 1435 4306 711 1435 4307 658 1436 4308 767 1436 4309 666 1436 4310 658 1437 4311 695 1437 4312 767 1437 4313 658 1438 4314 685 1438 4315 695 1438 4316 753 1439 4317 713 1439 4318 408 1439 4319 408 1440 4320 406 1440 4321 753 1440 4322 406 1441 4323 719 1441 4324 753 1441 4325 406 1442 4326 364 1442 4327 719 1442 4328 761 1443 4329 750 1443 4330 746 1443 4331 664 1444 4332 811 1444 4333 758 1444 4334 780 1445 4335 658 1445 4336 372 1445 4337 780 1446 4338 708 1446 4339 658 1446 4340 761 1447 4341 746 1447 4342 660 1447 4343 746 1448 4344 757 1448 4345 660 1448 4346 788 1449 4347 685 1449 4348 658 1449 4349 740 1450 4350 743 1450 4351 732 1450 4352 740 1451 4353 769 1451 4354 743 1451 4355 769 1452 4356 776 1452 4357 743 1452 4358 769 1453 4359 799 1453 4360 776 1453 4361 799 1454 4362 726 1454 4363 776 1454 4364 726 1455 4365 695 1455 4366 776 1455 4367 726 1456 4368 767 1456 4369 695 1456 4370 676 1457 4371 763 1457 4372 789 1457 4373 742 1458 4374 763 1458 4375 676 1458 4376 366 1459 4377 659 1459 4378 745 1459 4379 659 1460 4380 724 1460 4381 745 1460 4382 744 1461 4383 659 1461 4384 366 1461 4385 372 1462 4386 675 1462 4387 369 1462 4388 372 1463 4389 658 1463 4390 675 1463 4391 718 1464 4392 368 1464 4393 774 1464 4394 687 1465 4395 368 1465 4396 779 1465 4397 368 1466 4398 718 1466 4399 779 1466 4400 728 1467 4401 701 1467 4402 406 1467 4403 701 1468 4404 364 1468 4405 406 1468 4406 689 1469 4407 783 1469 4408 748 1469 4409 783 1470 4410 689 1470 4411 688 1470 4412 782 1471 4413 783 1471 4414 688 1471 4415 742 1472 4416 754 1472 4417 670 1472 4418 754 1473 4419 676 1473 4420 789 1473 4421 754 1474 4422 742 1474 4423 676 1474 4424 698 1475 4425 777 1475 4426 800 1475 4427 698 1476 4428 795 1476 4429 777 1476 4430 698 1477 4431 775 1477 4432 795 1477 4433 775 1478 4434 747 1478 4435 795 1478 4436 800 1479 4437 788 1479 4438 718 1479 4439 800 1480 4440 718 1480 4441 774 1480 4442 800 1481 4443 774 1481 4444 698 1481 4445 658 1482 4446 708 1482 4447 788 1482 4448 708 1483 4449 718 1483 4450 788 1483 4451 779 1484 4452 708 1484 4453 687 1484 4454 713 1485 4455 688 1485 4456 408 1485 4457 707 1486 4458 688 1486 4459 713 1486 4460 684 1487 4461 809 1487 4462 815 1487 4463 372 1488 4464 687 1488 4465 780 1488 4466 368 1489 4467 687 1489 4468 372 1489 4469 756 1490 4470 754 1490 4471 768 1490 4472 754 1491 4473 694 1491 4474 768 1491 4475 727 1492 4476 754 1492 4477 712 1492 4478 754 1493 4479 756 1493 4480 712 1493 4481 370 1494 4482 754 1494 4483 368 1494 4484 754 1495 4485 727 1495 4486 368 1495 4487 684 1496 4488 366 1496 4489 792 1496 4490 684 1497 4491 664 1497 4492 365 1497 4493 664 1498 4494 370 1498 4495 365 1498 4496 370 1499 4497 664 1499 4498 670 1499 4499 670 1500 4500 754 1500 4501 370 1500 4502 684 1501 4503 660 1501 4504 757 1501 4505 781 1502 4506 661 1502 4507 660 1502 4508 660 1503 4509 793 1503 4510 781 1503 4511 793 1504 4512 660 1504 4513 684 1504 4514 684 1505 4515 792 1505 4516 793 1505 4517 744 1506 4518 366 1506 4519 363 1506 4520 366 1507 4521 684 1507 4522 365 1507 4523 363 1508 4524 701 1508 4525 744 1508 4526 708 1509 4527 779 1509 4528 718 1509 4529 753 1510 4530 707 1510 4531 713 1510 4532 753 1511 4533 725 1511 4534 707 1511 4535 725 1512 4536 697 1512 4537 707 1512 4538 697 1513 4539 688 1513 4540 707 1513 4541 697 1514 4542 782 1514 4543 688 1514 4544 708 1515 4545 780 1515 4546 687 1515 4547 664 1516 4548 684 1516 4549 674 1516 4550 684 1517 4551 700 1517 4552 674 1517 4553 811 1518 4554 664 1518 4555 674 1518 4556 757 1519 4557 809 1519 4558 684 1519 4559 681 1520 4560 809 1520 4561 757 1520 4562 743 1521 4563 685 1521 4564 732 1521 4565 685 1522 4566 743 1522 4567 776 1522 4568 685 1523 4569 776 1523 4570 695 1523 4571 389 1524 4572 823 1524 4573 383 1524 4574 814 1525 4575 803 1525 4576 815 1525 4577 758 1526 4578 817 1526 4579 711 1526 4580 817 1527 4581 742 1527 4582 711 1527 4583 817 1528 4584 811 1528 4585 812 1528 4586 817 1529 4587 758 1529 4588 811 1529 4589 813 1530 4590 815 1530 4591 803 1530 4592 813 1531 4593 700 1531 4594 815 1531 4595 810 1532 4596 825 1532 4597 814 1532 4598 814 1533 4599 809 1533 4600 810 1533 4601 815 1534 4602 809 1534 4603 814 1534 4604 810 1535 4605 809 1535 4606 681 1535 4607 836 1536 4608 834 1536 4609 791 1536 4610 834 1537 4611 395 1537 4612 791 1537 4613 831 1538 4614 826 1538 4615 386 1538 4616 826 1539 4617 829 1539 4618 386 1539 4619 829 1540 4620 392 1540 4621 386 1540 4622 822 1541 4623 831 1541 4624 388 1541 4625 831 1542 4626 386 1542 4627 388 1542 4628 826 1543 4629 828 1543 4630 829 1543 4631 826 1544 4632 831 1544 4633 828 1544 4634 831 1545 4635 820 1545 4636 828 1545 4637 831 1546 4638 822 1546 4639 820 1546 4640 822 1547 4641 824 1547 4642 820 1547 4643 824 1548 4644 818 1548 4645 820 1548 4646 824 1549 4647 835 1549 4648 818 1549 4649 835 1550 4650 823 1550 4651 818 1550 4652 823 1551 4653 835 1551 4654 383 1551 4655 807 1552 4656 391 1552 4657 829 1552 4658 759 1553 4659 692 1553 4660 827 1553 4661 677 1554 4662 394 1554 4663 692 1554 4664 393 1555 4665 806 1555 4666 823 1555 4667 817 1556 4668 821 1556 4669 836 1556 4670 817 1557 4671 812 1557 4672 821 1557 4673 812 1558 4674 802 1558 4675 821 1558 4676 836 1559 4677 819 1559 4678 834 1559 4679 836 1560 4680 821 1560 4681 819 1560 4682 834 1561 4683 819 1561 4684 395 1561 4685 391 1562 4686 385 1562 4687 829 1562 4688 385 1563 4689 392 1563 4690 829 1563 4691 388 1564 4692 384 1564 4693 822 1564 4694 384 1565 4695 824 1565 4696 822 1565 4697 384 1566 4698 387 1566 4699 824 1566 4700 387 1567 4701 835 1567 4702 824 1567 4703 387 1568 4704 383 1568 4705 835 1568 4706 389 1569 4707 390 1569 4708 393 1569 4709 389 1570 4710 393 1570 4711 823 1570 4712 827 1571 4713 830 1571 4714 825 1571 4715 830 1572 4716 814 1572 4717 825 1572 4718 830 1573 4719 803 1573 4720 814 1573 4721 830 1574 4722 808 1574 4723 803 1574 4724 830 1575 4725 827 1575 4726 832 1575 4727 827 1576 4728 692 1576 4729 832 1576 4730 832 1577 4731 692 1577 4732 394 1577 4733 391 1578 4734 807 1578 4735 394 1578 4736 807 1579 4737 832 1579 4738 394 1579 4739 807 1580 4740 804 1580 4741 808 1580 4742 807 1581 4743 830 1581 4744 832 1581 4745 807 1582 4746 808 1582 4747 830 1582 4748 804 1583 4749 813 1583 4750 808 1583 4751 804 1584 4752 700 1584 4753 813 1584 4754 808 1585 4755 813 1585 4756 803 1585 4757 801 1586 4758 811 1586 4759 674 1586 4760 700 1587 4761 804 1587 4762 674 1587 4763 802 1588 4764 801 1588 4765 805 1588 4766 802 1589 4767 811 1589 4768 801 1589 4769 805 1590 4770 806 1590 4771 802 1590 4772 802 1591 4773 806 1591 4774 821 1591 4775 806 1592 4776 819 1592 4777 821 1592 4778 806 1593 4779 393 1593 4780 819 1593 4781 393 1594 4782 395 1594 4783 819 1594 4784 812 1595 4785 811 1595 4786 802 1595 4787 700 1596 4788 684 1596 4789 815 1596 4790 696 1597 4791 735 1597 4792 672 1597 4793 356 1598 4794 401 1598 4795 396 1598 4796 394 1599 4797 396 1599 4798 401 1599 4799 391 1600 4800 394 1600 4801 401 1600 4802 621 1601 4803 635 1601 4804 637 1601 4805 530 1602 4806 635 1602 4807 621 1602 4808 443 1603 4809 635 1603 4810 530 1603 4811 849 1604 4812 882 1604 4813 854 1604 4814 854 1605 4815 843 1605 4816 838 1605 4817 884 1606 4818 854 1606 4819 838 1606 4820 849 1607 4821 854 1607 4822 884 1607 4823 943 1608 4824 948 1608 4825 937 1608 4826 141 1609 4827 928 1609 4828 915 1609 4829 141 1610 4830 973 1610 4831 928 1610 4832 147 1611 4833 973 1611 4834 141 1611 4835 147 1612 4836 969 1612 4837 973 1612 4838 140 1613 4839 969 1613 4840 147 1613 4841 140 1614 4842 942 1614 4843 969 1614 4844 139 1615 4845 942 1615 4846 140 1615 4847 139 1616 4848 890 1616 4849 942 1616 4850 129 1617 4851 890 1617 4852 139 1617 4853 129 1618 4854 867 1618 4855 890 1618 4856 122 1619 4857 867 1619 4858 129 1619 4859 122 1620 4860 897 1620 4861 867 1620 4862 148 1621 4863 856 1621 4864 897 1621 4865 189 1622 4866 856 1622 4867 148 1622 4868 189 1623 4869 848 1623 4870 856 1623 4871 183 1624 4872 848 1624 4873 189 1624 4874 183 1625 4875 913 1625 4876 848 1625 4877 184 1626 4878 913 1626 4879 183 1626 4880 184 1627 4881 842 1627 4882 913 1627 4883 195 1628 4884 842 1628 4885 184 1628 4886 195 1629 4887 923 1629 4888 842 1629 4889 203 1630 4890 923 1630 4891 195 1630 4892 203 1631 4893 852 1631 4894 923 1631 4895 202 1632 4896 852 1632 4897 203 1632 4898 202 1633 4899 838 1633 4900 852 1633 4901 199 1634 4902 838 1634 4903 202 1634 4904 915 1635 4905 119 1635 4906 141 1635 4907 199 1636 4908 884 1636 4909 838 1636 4910 849 1637 4911 884 1637 4912 200 1637 4913 200 1638 4914 884 1638 4915 199 1638 4916 176 1639 4917 882 1639 4918 849 1639 4919 176 1640 4920 849 1640 4921 200 1640 4922 936 1641 4923 9 1641 4924 889 1641 4925 936 1642 4926 31 1642 4927 9 1642 4928 968 1643 4929 31 1643 4930 936 1643 4931 968 1644 4932 30 1644 4933 31 1644 4934 935 1645 4935 30 1645 4936 968 1645 4937 935 1646 4938 33 1646 4939 30 1646 4940 893 1647 4941 26 1647 4942 918 1647 4943 893 1648 4944 16 1648 4945 26 1648 4946 924 1649 4947 16 1649 4948 893 1649 4949 15 1650 4950 16 1650 4951 924 1650 4952 894 1651 4953 15 1651 4954 924 1651 4955 894 1652 4956 20 1652 4957 15 1652 4958 873 1653 4959 20 1653 4960 894 1653 4961 873 1654 4962 205 1654 4963 20 1654 4964 888 1655 4965 205 1655 4966 873 1655 4967 888 1656 4968 181 1656 4969 205 1656 4970 902 1657 4971 181 1657 4972 888 1657 4973 902 1658 4974 179 1658 4975 181 1658 4976 939 1659 4977 179 1659 4978 902 1659 4979 939 1660 4980 186 1660 4981 179 1660 4982 841 1661 4983 186 1661 4984 939 1661 4985 841 1662 4986 196 1662 4987 186 1662 4988 903 1663 4989 196 1663 4990 841 1663 4991 903 1664 4992 197 1664 4993 196 1664 4994 938 1665 4995 197 1665 4996 903 1665 4997 938 1666 4998 204 1666 4999 197 1666 5000 882 1667 5001 204 1667 5002 938 1667 5003 29 1668 5004 901 1668 5005 889 1668 5006 29 1669 5007 863 1669 5008 901 1669 5009 35 1670 5010 863 1670 5011 29 1670 5012 35 1671 5013 847 1671 5014 863 1671 5015 28 1672 5016 847 1672 5017 35 1672 5018 28 1673 5019 861 1673 5020 847 1673 5021 27 1674 5022 861 1674 5023 28 1674 5024 27 1675 5025 951 1675 5026 861 1675 5027 926 1676 5028 951 1676 5029 27 1676 5030 926 1677 5031 954 1677 5032 951 1677 5033 12 1678 5034 954 1678 5035 926 1678 5036 12 1679 5037 865 1679 5038 954 1679 5039 13 1680 5040 865 1680 5041 12 1680 5042 13 1681 5043 846 1681 5044 865 1681 5045 75 1682 5046 964 1682 5047 846 1682 5048 69 1683 5049 964 1683 5050 75 1683 5051 69 1684 5052 875 1684 5053 964 1684 5054 70 1685 5055 875 1685 5056 69 1685 5057 70 1686 5058 869 1686 5059 875 1686 5060 81 1687 5061 869 1687 5062 70 1687 5063 81 1688 5064 907 1688 5065 869 1688 5066 89 1689 5067 907 1689 5068 81 1689 5069 89 1690 5070 874 1690 5071 907 1690 5072 88 1691 5073 874 1691 5074 89 1691 5075 88 1692 5076 980 1692 5077 874 1692 5078 85 1693 5079 980 1693 5080 88 1693 5081 85 1694 5082 879 1694 5083 980 1694 5084 86 1695 5085 879 1695 5086 85 1695 5087 889 1696 5088 9 1696 5089 29 1696 5090 871 1697 5091 63 1697 5092 84 1697 5093 879 1698 5094 63 1698 5095 871 1698 5096 63 1699 5097 879 1699 5098 86 1699 5099 83 1700 5100 851 1700 5101 898 1700 5102 82 1701 5103 851 1701 5104 83 1701 5105 82 1702 5106 886 1702 5107 851 1702 5108 72 1703 5109 886 1703 5110 82 1703 5111 72 1704 5112 940 1704 5113 886 1704 5114 66 1705 5115 940 1705 5116 72 1705 5117 66 1706 5118 881 1706 5119 940 1706 5120 67 1707 5121 881 1707 5122 66 1707 5123 67 1708 5124 912 1708 5125 881 1708 5126 117 1709 5127 912 1709 5128 67 1709 5129 117 1710 5130 916 1710 5131 912 1710 5132 132 1711 5133 916 1711 5134 117 1711 5135 132 1712 5136 970 1712 5137 916 1712 5138 126 1713 5139 970 1713 5140 132 1713 5141 126 1714 5142 927 1714 5143 970 1714 5144 127 1715 5145 927 1715 5146 126 1715 5147 127 1716 5148 887 1716 5149 927 1716 5150 138 1717 5151 887 1717 5152 127 1717 5153 138 1718 5154 997 1718 5155 887 1718 5156 145 1719 5157 845 1719 5158 997 1719 5159 142 1720 5160 845 1720 5161 145 1720 5162 142 1721 5163 899 1721 5164 845 1721 5165 143 1722 5166 899 1722 5167 142 1722 5168 143 1723 5169 921 1723 5170 899 1723 5171 119 1724 5172 921 1724 5173 143 1724 5174 119 1725 5175 915 1725 5176 921 1725 5177 985 1726 5178 943 1726 5179 953 1726 5180 985 1727 5181 975 1727 5182 943 1727 5183 985 1728 5184 904 1728 5185 975 1728 5186 850 1729 5187 904 1729 5188 985 1729 5189 892 1730 5190 904 1730 5191 850 1730 5192 917 1731 5193 892 1731 5194 850 1731 5195 917 1732 5196 979 1732 5197 892 1732 5198 960 1733 5199 979 1733 5200 917 1733 5201 960 1734 5202 941 1734 5203 979 1734 5204 859 1735 5205 941 1735 5206 960 1735 5207 859 1736 5208 854 1736 5209 941 1736 5210 989 1737 5211 854 1737 5212 859 1737 5213 989 1738 5214 843 1738 5215 854 1738 5216 839 1739 5217 990 1739 5218 858 1739 5219 839 1740 5220 843 1740 5221 990 1740 5222 990 1741 5223 843 1741 5224 989 1741 5225 957 1742 5226 839 1742 5227 858 1742 5228 868 1743 5229 839 1743 5230 957 1743 5231 962 1744 5232 868 1744 5233 957 1744 5234 840 1745 5235 868 1745 5236 962 1745 5237 900 1746 5238 840 1746 5239 878 1746 5240 880 1747 5241 840 1747 5242 900 1747 5243 840 1748 5244 962 1748 5245 878 1748 5246 977 1749 5247 880 1749 5248 900 1749 5249 977 1750 5250 950 1750 5251 880 1750 5252 974 1751 5253 950 1751 5254 977 1751 5255 974 1752 5256 994 1752 5257 950 1752 5258 949 1753 5259 994 1753 5260 974 1753 5261 949 1754 5262 965 1754 5263 994 1754 5264 909 1755 5265 965 1755 5266 949 1755 5267 910 1756 5268 963 1756 5269 991 1756 5270 910 1757 5271 932 1757 5272 963 1757 5273 872 1758 5274 932 1758 5275 910 1758 5276 872 1759 5277 976 1759 5278 932 1759 5279 877 1760 5280 976 1760 5281 872 1760 5282 877 1761 5283 909 1761 5284 976 1761 5285 965 1762 5286 909 1762 5287 877 1762 5288 866 1763 5289 883 1763 5290 929 1763 5291 972 1764 5292 883 1764 5293 866 1764 5294 972 1765 5295 946 1765 5296 883 1765 5297 958 1766 5298 946 1766 5299 972 1766 5300 958 1767 5301 920 1767 5302 946 1767 5303 934 1768 5304 920 1768 5305 958 1768 5306 934 1769 5307 987 1769 5308 920 1769 5309 876 1770 5310 987 1770 5311 934 1770 5312 876 1771 5313 991 1771 5314 987 1771 5315 910 1772 5316 991 1772 5317 876 1772 5318 891 1773 5319 929 1773 5320 986 1773 5321 891 1774 5322 866 1774 5323 929 1774 5324 986 1775 5325 837 1775 5326 891 1775 5327 862 1776 5328 967 1776 5329 961 1776 5330 837 1777 5331 967 1777 5332 862 1777 5333 967 1778 5334 837 1778 5335 986 1778 5336 956 1779 5337 864 1779 5338 862 1779 5339 919 1780 5340 864 1780 5341 956 1780 5342 862 1781 5343 961 1781 5344 956 1781 5345 983 1782 5346 944 1782 5347 988 1782 5348 905 1783 5349 944 1783 5350 983 1783 5351 905 1784 5352 896 1784 5353 944 1784 5354 905 1785 5355 844 1785 5356 896 1785 5357 895 1786 5358 844 1786 5359 905 1786 5360 895 1787 5361 925 1787 5362 844 1787 5363 853 1788 5364 925 1788 5365 895 1788 5366 853 1789 5367 919 1789 5368 925 1789 5369 864 1790 5370 919 1790 5371 853 1790 5372 871 1791 5373 866 1791 5374 879 1791 5375 898 1792 5376 866 1792 5377 871 1792 5378 837 1793 5379 862 1793 5380 879 1793 5381 866 1794 5382 891 1794 5383 879 1794 5384 837 1795 5385 879 1795 5386 891 1795 5387 857 1796 5388 930 1796 5389 984 1796 5390 857 1797 5391 959 1797 5392 930 1797 5393 931 1798 5394 959 1798 5395 857 1798 5396 870 1799 5397 959 1799 5398 931 1799 5399 870 1800 5400 908 1800 5401 959 1800 5402 855 1801 5403 908 1801 5404 870 1801 5405 971 1802 5406 908 1802 5407 855 1802 5408 971 1803 5409 981 1803 5410 908 1803 5411 860 1804 5412 981 1804 5413 971 1804 5414 860 1805 5415 933 1805 5416 981 1805 5417 984 1806 5418 992 1806 5419 857 1806 5420 978 1807 5421 953 1807 5422 937 1807 5423 937 1808 5424 948 1808 5425 978 1808 5426 953 1809 5427 943 1809 5428 937 1809 5429 993 1810 5430 992 1810 5431 984 1810 5432 995 1811 5433 992 1811 5434 993 1811 5435 995 1812 5436 948 1812 5437 992 1812 5438 952 1813 5439 948 1813 5440 995 1813 5441 952 1814 5442 978 1814 5443 948 1814 5444 966 1815 5445 947 1815 5446 914 1815 5447 947 1816 5448 922 1816 5449 914 1816 5450 982 1817 5451 947 1817 5452 966 1817 5453 996 1818 5454 947 1818 5455 982 1818 5456 996 1819 5457 911 1819 5458 947 1819 5459 933 1820 5460 911 1820 5461 996 1820 5462 933 1821 5463 860 1821 5464 911 1821 5465 945 1822 5466 983 1822 5467 988 1822 5468 955 1823 5469 945 1823 5470 988 1823 5471 955 1824 5472 922 1824 5473 945 1824 5474 914 1825 5475 922 1825 5476 955 1825 5477 974 1826 5478 909 1826 5479 949 1826 5480 909 1827 5481 974 1827 5482 977 1827 5483 976 1828 5484 977 1828 5485 900 1828 5486 976 1829 5487 909 1829 5488 977 1829 5489 963 1830 5490 932 1830 5491 991 1830 5492 858 1831 5493 976 1831 5494 957 1831 5495 885 1832 5496 976 1832 5497 858 1832 5498 885 1833 5499 932 1833 5500 976 1833 5501 991 1834 5502 932 1834 5503 885 1834 5504 976 1835 5505 900 1835 5506 878 1835 5507 962 1836 5508 976 1836 5509 878 1836 5510 957 1837 5511 976 1837 5512 962 1837 5513 986 1838 5514 885 1838 5515 967 1838 5516 986 1839 5517 929 1839 5518 885 1839 5519 885 1840 5520 929 1840 5521 883 1840 5522 989 1841 5523 885 1841 5524 990 1841 5525 990 1842 5526 885 1842 5527 858 1842 5528 885 1843 5529 961 1843 5530 967 1843 5531 859 1844 5532 885 1844 5533 989 1844 5534 960 1845 5535 885 1845 5536 859 1845 5537 961 1846 5538 885 1846 5539 956 1846 5540 960 1847 5541 917 1847 5542 885 1847 5543 885 1848 5544 919 1848 5545 956 1848 5546 885 1849 5547 917 1849 5548 850 1849 5549 885 1850 5550 844 1850 5551 925 1850 5552 885 1851 5553 925 1851 5554 919 1851 5555 885 1852 5556 850 1852 5557 985 1852 5558 885 1853 5559 944 1853 5560 896 1853 5561 906 1854 5562 944 1854 5563 885 1854 5564 896 1855 5565 844 1855 5566 885 1855 5567 985 1856 5568 906 1856 5569 885 1856 5570 953 1857 5571 906 1857 5572 985 1857 5573 906 1858 5574 988 1858 5575 944 1858 5576 955 1859 5577 988 1859 5578 906 1859 5579 906 1860 5580 914 1860 5581 955 1860 5582 852 1861 5583 838 1861 5584 840 1861 5585 852 1862 5586 840 1862 5587 880 1862 5588 852 1863 5589 880 1863 5590 923 1863 5591 842 1864 5592 923 1864 5593 880 1864 5594 842 1865 5595 880 1865 5596 913 1865 5597 880 1866 5598 950 1866 5599 913 1866 5600 848 1867 5601 913 1867 5602 950 1867 5603 848 1868 5604 950 1868 5605 856 1868 5606 856 1869 5607 950 1869 5608 897 1869 5609 897 1870 5610 950 1870 5611 994 1870 5612 867 1871 5613 897 1871 5614 994 1871 5615 867 1872 5616 994 1872 5617 890 1872 5618 890 1873 5619 994 1873 5620 942 1873 5621 942 1874 5622 994 1874 5623 965 1874 5624 942 1875 5625 965 1875 5626 969 1875 5627 965 1876 5628 973 1876 5629 969 1876 5630 877 1877 5631 973 1877 5632 965 1877 5633 877 1878 5634 928 1878 5635 973 1878 5636 872 1879 5637 928 1879 5638 877 1879 5639 872 1880 5640 915 1880 5641 928 1880 5642 872 1881 5643 921 1881 5644 915 1881 5645 872 1882 5646 910 1882 5647 921 1882 5648 899 1883 5649 921 1883 5650 910 1883 5651 876 1884 5652 899 1884 5653 910 1884 5654 845 1885 5655 899 1885 5656 876 1885 5657 845 1886 5658 876 1886 5659 997 1886 5660 876 1887 5661 934 1887 5662 997 1887 5663 887 1888 5664 997 1888 5665 934 1888 5666 887 1889 5667 934 1889 5668 927 1889 5669 927 1890 5670 934 1890 5671 970 1890 5672 934 1891 5673 958 1891 5674 970 1891 5675 916 1892 5676 970 1892 5677 958 1892 5678 912 1893 5679 916 1893 5680 958 1893 5681 881 1894 5682 912 1894 5683 958 1894 5684 881 1895 5685 958 1895 5686 972 1895 5687 881 1896 5688 972 1896 5689 940 1896 5690 886 1897 5691 940 1897 5692 972 1897 5693 851 1898 5694 886 1898 5695 972 1898 5696 851 1899 5697 972 1899 5698 866 1899 5699 851 1900 5700 866 1900 5701 898 1900 5702 862 1901 5703 980 1901 5704 879 1901 5705 864 1902 5706 980 1902 5707 862 1902 5708 864 1903 5709 874 1903 5710 980 1903 5711 864 1904 5712 907 1904 5713 874 1904 5714 853 1905 5715 907 1905 5716 864 1905 5717 853 1906 5718 869 1906 5719 907 1906 5720 853 1907 5721 895 1907 5722 869 1907 5723 869 1908 5724 895 1908 5725 875 1908 5726 875 1909 5727 895 1909 5728 905 1909 5729 875 1910 5730 905 1910 5731 964 1910 5732 846 1911 5733 964 1911 5734 905 1911 5735 846 1912 5736 905 1912 5737 983 1912 5738 846 1913 5739 983 1913 5740 865 1913 5741 865 1914 5742 983 1914 5743 954 1914 5744 945 1915 5745 954 1915 5746 983 1915 5747 922 1916 5748 954 1916 5749 945 1916 5750 922 1917 5751 947 1917 5752 954 1917 5753 911 1918 5754 954 1918 5755 947 1918 5756 911 1919 5757 951 1919 5758 954 1919 5759 860 1920 5760 951 1920 5761 911 1920 5762 860 1921 5763 861 1921 5764 951 1921 5765 847 1922 5766 861 1922 5767 860 1922 5768 847 1923 5769 860 1923 5770 971 1923 5771 847 1924 5772 971 1924 5773 863 1924 5774 855 1925 5775 863 1925 5776 971 1925 5777 855 1926 5778 901 1926 5779 863 1926 5780 855 1927 5781 870 1927 5782 901 1927 5783 870 1928 5784 889 1928 5785 901 1928 5786 870 1929 5787 931 1929 5788 889 1929 5789 889 1930 5790 931 1930 5791 936 1930 5792 857 1931 5793 936 1931 5794 931 1931 5795 857 1932 5796 968 1932 5797 936 1932 5798 857 1933 5799 935 1933 5800 968 1933 5801 857 1934 5802 992 1934 5803 935 1934 5804 918 1935 5805 935 1935 5806 992 1935 5807 893 1936 5808 918 1936 5809 992 1936 5810 893 1937 5811 992 1937 5812 948 1937 5813 893 1938 5814 948 1938 5815 924 1938 5816 924 1939 5817 948 1939 5818 943 1939 5819 894 1940 5820 924 1940 5821 943 1940 5822 894 1941 5823 943 1941 5824 975 1941 5825 873 1942 5826 894 1942 5827 975 1942 5828 873 1943 5829 975 1943 5830 904 1943 5831 873 1944 5832 904 1944 5833 888 1944 5834 888 1945 5835 904 1945 5836 892 1945 5837 888 1946 5838 892 1946 5839 902 1946 5840 892 1947 5841 939 1947 5842 902 1947 5843 892 1948 5844 979 1948 5845 939 1948 5846 841 1949 5847 939 1949 5848 979 1949 5849 841 1950 5850 979 1950 5851 941 1950 5852 841 1951 5853 941 1951 5854 903 1951 5855 854 1952 5856 903 1952 5857 941 1952 5858 854 1953 5859 938 1953 5860 903 1953 5861 854 1954 5862 882 1954 5863 938 1954 5864 883 1955 5865 946 1955 5866 885 1955 5867 920 1956 5868 885 1956 5869 946 1956 5870 920 1957 5871 987 1957 5872 885 1957 5873 885 1958 5874 987 1958 5875 991 1958 5876 906 1959 5877 953 1959 5878 978 1959 5879 906 1960 5880 978 1960 5881 952 1960 5882 906 1961 5883 952 1961 5884 995 1961 5885 906 1962 5886 995 1962 5887 993 1962 5888 906 1963 5889 993 1963 5890 984 1963 5891 906 1964 5892 984 1964 5893 930 1964 5894 906 1965 5895 930 1965 5896 959 1965 5897 906 1966 5898 959 1966 5899 908 1966 5900 906 1967 5901 908 1967 5902 981 1967 5903 906 1968 5904 981 1968 5905 933 1968 5906 906 1969 5907 933 1969 5908 996 1969 5909 906 1970 5910 996 1970 5911 982 1970 5912 906 1971 5913 982 1971 5914 966 1971 5915 906 1972 5916 966 1972 5917 914 1972 5918 838 1973 5919 843 1973 5920 839 1973 5921 838 1974 5922 839 1974 5923 868 1974 5924 838 1975 5925 868 1975 5926 840 1975 5927 176 1976 5928 198 1976 5929 882 1976 5930 198 1977 5931 204 1977 5932 882 1977 5933 122 1978 5934 124 1978 5935 897 1978 5936 124 1979 5937 148 1979 5938 897 1979 5939 145 1980 5940 997 1980 5941 146 1980 5942 138 1981 5943 146 1981 5944 997 1981 5945 83 1982 5946 898 1982 5947 90 1982 5948 84 1983 5949 90 1983 5950 898 1983 5951 84 1984 5952 898 1984 5953 871 1984 5954 61 1985 5955 75 1985 5956 846 1985 5957 13 1986 5958 61 1986 5959 846 1986 5960 33 1987 5961 935 1987 5962 34 1987 5963 26 1988 5964 34 1988 5965 935 1988 5966 26 1989 5967 935 1989 5968 918 1989 5969

+
+ + + + +

60 0 0 61 0 1 13 0 2 12 1 3 14 1 4 13 1 5 13 2 6 14 2 7 32 2 8 32 3 9 60 3 10 13 3 11 14 4 12 12 4 13 23 4 14 926 5 15 23 5 16 12 5 17 23 6 18 926 6 19 18 6 20 6 7 21 18 7 22 27 7 23 27 8 24 18 8 25 926 8 26 28 9 27 6 9 28 27 9 29 28 10 30 3 10 31 4 10 32 5 11 33 6 11 34 28 11 35 4 12 36 5 12 37 28 12 38 35 13 39 2 13 40 3 13 41 35 14 42 3 14 43 28 14 44 29 15 45 2 15 46 35 15 47 29 16 48 1 16 49 2 16 50 9 17 51 1 17 52 29 17 53 9 18 54 0 18 55 1 18 56 0 19 57 9 19 58 31 19 59 11 20 60 0 20 61 31 20 62 11 21 63 31 21 64 10 21 65 30 22 66 10 22 67 31 22 68 30 23 69 7 23 70 10 23 71 33 24 72 7 24 73 30 24 74 19 25 75 7 25 76 33 25 77 34 26 78 19 26 79 33 26 80 8 27 81 19 27 82 34 27 83 8 28 84 34 28 85 26 28 86 26 29 87 24 29 88 8 29 89 16 30 90 17 30 91 26 30 92 26 31 93 17 31 94 24 31 95 15 32 96 22 32 97 16 32 98 16 33 99 22 33 100 17 33 101 21 34 102 22 34 103 15 34 104 21 35 105 15 35 106 20 35 107 21 36 108 20 36 109 25 36 110 25 37 111 20 37 112 205 37 113 25 38 114 205 38 115 206 38 116 95 39 117 60 39 118 32 39 119 37 40 120 23 40 121 18 40 122 23 41 123 37 41 124 49 41 125 23 42 126 49 42 127 14 42 128 14 43 129 49 43 130 50 43 131 14 44 132 50 44 133 32 44 134 32 45 135 50 45 136 95 45 137 38 46 138 22 46 139 21 46 140 206 47 141 180 47 142 48 47 143 38 48 144 21 48 145 51 48 146 51 49 147 21 49 148 25 49 149 51 50 150 25 50 151 48 50 152 48 51 153 25 51 154 206 51 155 10 52 156 0 52 157 11 52 158 0 53 159 10 53 160 45 53 161 0 54 162 45 54 163 1 54 164 1 55 165 45 55 166 46 55 167 46 56 168 45 56 169 42 56 170 46 57 171 42 57 172 43 57 173 43 58 174 42 58 175 47 58 176 43 59 177 47 59 178 40 59 179 40 60 180 44 60 181 18 60 182 40 61 183 18 61 184 6 61 185 39 62 186 36 62 187 41 62 188 41 63 189 36 63 190 44 63 191 40 64 192 6 64 193 43 64 194 43 65 195 6 65 196 5 65 197 43 66 198 5 66 199 4 66 200 43 67 201 4 67 202 3 67 203 43 68 204 3 68 205 46 68 206 46 69 207 3 69 208 2 69 209 46 70 210 2 70 211 1 70 212 10 71 213 7 71 214 45 71 215 45 72 216 7 72 217 19 72 218 45 73 219 19 73 220 42 73 221 42 74 222 19 74 223 8 74 224 42 75 225 8 75 226 24 75 227 42 76 228 24 76 229 47 76 230 47 77 231 24 77 232 17 77 233 41 78 234 47 78 235 22 78 236 22 79 237 47 79 238 17 79 239 44 80 240 36 80 241 37 80 242 44 81 243 37 81 244 18 81 245 40 82 246 47 82 247 44 82 248 44 83 249 47 83 250 41 83 251 38 84 252 41 84 253 22 84 254 41 85 255 38 85 256 39 85 257 116 86 258 117 86 259 67 86 260 66 87 261 68 87 262 67 87 263 67 88 264 68 88 265 87 88 266 87 89 267 116 89 268 67 89 269 68 90 270 66 90 271 78 90 272 72 91 273 78 91 274 66 91 275 78 92 276 72 92 277 73 92 278 58 93 279 73 93 280 82 93 281 82 94 282 73 94 283 72 94 284 83 95 285 58 95 286 82 95 287 83 96 288 55 96 289 56 96 290 57 97 291 58 97 292 83 97 293 56 98 294 57 98 295 83 98 296 90 99 297 54 99 298 55 99 299 90 100 300 55 100 301 83 100 302 84 101 303 54 101 304 90 101 305 84 102 306 53 102 307 54 102 308 63 103 309 53 103 310 84 103 311 63 104 312 52 104 313 53 104 314 52 105 315 63 105 316 86 105 317 65 106 318 52 106 319 86 106 320 65 107 321 86 107 322 64 107 323 85 108 324 64 108 325 86 108 326 85 109 327 59 109 328 64 109 329 88 110 330 59 110 331 85 110 332 74 111 333 59 111 334 88 111 335 89 112 336 74 112 337 88 112 338 62 113 339 74 113 340 89 113 341 62 114 342 89 114 343 81 114 344 81 115 345 79 115 346 62 115 347 70 116 348 71 116 349 81 116 350 81 117 351 71 117 352 79 117 353 69 118 354 77 118 355 70 118 356 70 119 357 77 119 358 71 119 359 76 120 360 77 120 361 69 120 362 76 121 363 69 121 364 75 121 365 76 122 366 75 122 367 80 122 368 80 123 369 75 123 370 61 123 371 80 124 372 61 124 373 60 124 374 154 125 375 116 125 376 87 125 377 92 126 378 78 126 379 73 126 380 78 127 381 92 127 382 105 127 383 78 128 384 105 128 385 68 128 386 68 129 387 105 129 388 106 129 389 68 130 390 106 130 391 87 130 392 87 131 393 106 131 394 154 131 395 93 132 396 77 132 397 76 132 398 60 133 399 95 133 400 104 133 401 93 134 402 76 134 403 107 134 404 107 135 405 76 135 406 80 135 407 107 136 408 80 136 409 104 136 410 104 137 411 80 137 412 60 137 413 64 138 414 52 138 415 65 138 416 52 139 417 64 139 418 101 139 419 52 140 420 101 140 421 53 140 422 53 141 423 101 141 424 102 141 425 102 142 426 101 142 427 98 142 428 102 143 429 98 143 430 99 143 431 99 144 432 98 144 433 103 144 434 99 145 435 103 145 436 96 145 437 96 146 438 100 146 439 73 146 440 96 147 441 73 147 442 58 147 443 94 148 444 91 148 445 97 148 446 97 149 447 91 149 448 100 149 449 96 150 450 58 150 451 99 150 452 99 151 453 58 151 454 57 151 455 99 152 456 57 152 457 56 152 458 99 153 459 56 153 460 55 153 461 99 154 462 55 154 463 102 154 464 102 155 465 55 155 466 54 155 467 102 156 468 54 156 469 53 156 470 64 157 471 59 157 472 101 157 473 101 158 474 59 158 475 74 158 476 101 159 477 74 159 478 98 159 479 98 160 480 74 160 481 62 160 482 98 161 483 62 161 484 79 161 485 98 162 486 79 162 487 103 162 488 103 163 489 79 163 490 71 163 491 97 164 492 103 164 493 77 164 494 77 165 495 103 165 496 71 165 497 100 166 498 91 166 499 92 166 500 100 167 501 92 167 502 73 167 503 96 168 504 103 168 505 100 168 506 100 169 507 103 169 508 97 169 509 93 170 510 97 170 511 77 170 512 97 171 513 93 171 514 94 171 515 149 172 516 148 172 517 124 172 518 122 173 519 125 173 520 124 173 521 124 174 522 125 174 523 144 174 524 144 175 525 149 175 526 124 175 527 125 176 528 122 176 529 135 176 530 129 177 531 135 177 532 122 177 533 135 178 534 129 178 535 130 178 536 114 179 537 130 179 538 139 179 539 139 180 540 130 180 541 129 180 542 140 181 543 114 181 544 139 181 545 140 182 546 111 182 547 112 182 548 113 183 549 114 183 550 140 183 551 112 184 552 113 184 553 140 184 554 147 185 555 110 185 556 111 185 557 147 186 558 111 186 559 140 186 560 141 187 561 110 187 562 147 187 563 141 188 564 109 188 565 110 188 566 119 189 567 109 189 568 141 189 569 119 190 570 108 190 571 109 190 572 108 191 573 119 191 574 143 191 575 121 192 576 108 192 577 143 192 578 121 193 579 143 193 580 120 193 581 142 194 582 120 194 583 143 194 584 142 195 585 115 195 586 120 195 587 145 196 588 115 196 589 142 196 590 131 197 591 115 197 592 145 197 593 146 198 594 131 198 595 145 198 596 118 199 597 131 199 598 146 199 599 118 200 600 146 200 601 138 200 602 138 201 603 136 201 604 118 201 605 127 202 606 128 202 607 138 202 608 138 203 609 128 203 610 136 203 611 126 204 612 134 204 613 127 204 614 127 205 615 134 205 616 128 205 617 133 206 618 134 206 619 126 206 620 133 207 621 126 207 622 132 207 623 133 208 624 132 208 625 137 208 626 137 209 627 132 209 628 117 209 629 137 210 630 117 210 631 116 210 632 123 211 633 149 211 634 144 211 635 151 212 636 135 212 637 130 212 638 135 213 639 151 213 640 164 213 641 135 214 642 164 214 643 125 214 644 125 215 645 164 215 646 165 215 647 125 216 648 165 216 649 144 216 650 144 217 651 165 217 652 123 217 653 152 218 654 134 218 655 133 218 656 116 219 657 154 219 658 163 219 659 152 220 660 133 220 661 166 220 662 166 221 663 133 221 664 137 221 665 166 222 666 137 222 667 163 222 668 163 223 669 137 223 670 116 223 671 120 224 672 108 224 673 121 224 674 108 225 675 120 225 676 160 225 677 108 226 678 160 226 679 109 226 680 109 227 681 160 227 682 161 227 683 161 228 684 160 228 685 157 228 686 161 229 687 157 229 688 158 229 689 158 230 690 157 230 691 162 230 692 158 231 693 162 231 694 155 231 695 155 232 696 159 232 697 130 232 698 155 233 699 130 233 700 114 233 701 153 234 702 150 234 703 156 234 704 156 235 705 150 235 706 159 235 707 155 236 708 114 236 709 158 236 710 158 237 711 114 237 712 113 237 713 158 238 714 113 238 715 112 238 716 158 239 717 112 239 718 111 239 719 158 240 720 111 240 721 161 240 722 161 241 723 111 241 724 110 241 725 161 242 726 110 242 727 109 242 728 120 243 729 115 243 730 160 243 731 160 244 732 115 244 733 131 244 734 160 245 735 131 245 736 157 245 737 157 246 738 131 246 739 118 246 740 157 247 741 118 247 742 136 247 743 157 248 744 136 248 745 162 248 746 162 249 747 136 249 748 128 249 749 156 250 750 162 250 751 134 250 752 134 251 753 162 251 754 128 251 755 159 252 756 150 252 757 151 252 758 159 253 759 151 253 760 130 253 761 155 254 762 162 254 763 159 254 764 159 255 765 162 255 766 156 255 767 152 256 768 156 256 769 134 256 770 156 257 771 152 257 772 153 257 773 206 258 774 205 258 775 181 258 776 179 259 777 182 259 778 181 259 779 181 260 780 182 260 781 201 260 782 201 261 783 206 261 784 181 261 785 182 262 786 179 262 787 192 262 788 186 263 789 192 263 790 179 263 791 192 264 792 186 264 793 187 264 794 173 265 795 187 265 796 196 265 797 196 266 798 187 266 799 186 266 800 197 267 801 173 267 802 196 267 803 197 268 804 170 268 805 171 268 806 172 269 807 173 269 808 197 269 809 171 270 810 172 270 811 197 270 812 204 271 813 169 271 814 170 271 815 204 272 816 170 272 817 197 272 818 198 273 819 169 273 820 204 273 821 198 274 822 168 274 823 169 274 824 176 275 825 168 275 826 198 275 827 176 276 828 167 276 829 168 276 830 167 277 831 176 277 832 200 277 833 178 278 834 167 278 835 200 278 836 178 279 837 200 279 838 177 279 839 199 280 840 177 280 841 200 280 842 199 281 843 174 281 844 177 281 845 202 282 846 174 282 847 199 282 848 188 283 849 174 283 850 202 283 851 203 284 852 188 284 853 202 284 854 175 285 855 188 285 856 203 285 857 175 286 858 203 286 859 195 286 860 195 287 861 193 287 862 175 287 863 184 288 864 185 288 865 195 288 866 195 289 867 185 289 868 193 289 869 183 290 870 191 290 871 184 290 872 184 291 873 191 291 874 185 291 875 190 292 876 191 292 877 183 292 878 190 293 879 183 293 880 189 293 881 190 294 882 189 294 883 194 294 884 194 295 885 189 295 886 148 295 887 194 296 888 148 296 889 149 296 890 180 297 891 206 297 892 201 297 893 208 298 894 192 298 895 187 298 896 192 299 897 208 299 898 220 299 899 192 300 900 220 300 901 182 300 902 182 301 903 220 301 904 221 301 905 182 302 906 221 302 907 201 302 908 201 303 909 221 303 910 180 303 911 209 304 912 191 304 913 190 304 914 149 305 915 123 305 916 219 305 917 209 306 918 190 306 919 222 306 920 222 307 921 190 307 922 194 307 923 222 308 924 194 308 925 219 308 926 219 309 927 194 309 928 149 309 929 177 310 930 167 310 931 178 310 932 167 311 933 177 311 934 216 311 935 167 312 936 216 312 937 168 312 938 168 313 939 216 313 940 217 313 941 217 314 942 216 314 943 213 314 944 217 315 945 213 315 946 214 315 947 214 316 948 213 316 949 218 316 950 214 317 951 218 317 952 211 317 953 211 318 954 215 318 955 187 318 956 211 319 957 187 319 958 173 319 959 210 320 960 207 320 961 212 320 962 212 321 963 207 321 964 215 321 965 211 322 966 173 322 967 214 322 968 214 323 969 173 323 970 172 323 971 214 324 972 172 324 973 171 324 974 214 325 975 171 325 976 170 325 977 214 326 978 170 326 979 217 326 980 217 327 981 170 327 982 169 327 983 217 328 984 169 328 985 168 328 986 177 329 987 174 329 988 216 329 989 216 330 990 174 330 991 188 330 992 216 331 993 188 331 994 213 331 995 213 332 996 188 332 997 175 332 998 213 333 999 175 333 1000 193 333 1001 213 334 1002 193 334 1003 218 334 1004 218 335 1005 193 335 1006 185 335 1007 212 336 1008 218 336 1009 191 336 1010 191 337 1011 218 337 1012 185 337 1013 215 338 1014 207 338 1015 208 338 1016 215 339 1017 208 339 1018 187 339 1019 211 340 1020 218 340 1021 215 340 1022 215 341 1023 218 341 1024 212 341 1025 209 342 1026 212 342 1027 191 342 1028 212 343 1029 209 343 1030 210 343 1031 240 344 1032 234 344 1033 228 344 1034 226 345 1035 229 345 1036 239 345 1037 239 346 1038 229 346 1039 243 346 1040 239 347 1041 243 347 1042 235 347 1043 239 348 1044 235 348 1045 241 348 1046 241 349 1047 245 349 1048 247 349 1049 241 350 1050 247 350 1051 239 350 1052 234 351 1053 240 351 1054 244 351 1055 244 352 1056 240 352 1057 249 352 1058 244 353 1059 249 353 1060 236 353 1061 236 354 1062 249 354 1063 250 354 1064 249 355 1065 240 355 1066 228 355 1067 249 356 1068 228 356 1069 248 356 1070 248 357 1071 228 357 1072 258 357 1073 258 358 1074 228 358 1075 225 358 1076 258 359 1077 225 359 1078 237 359 1079 237 360 1080 225 360 1081 226 360 1082 237 361 1083 226 361 1084 238 361 1085 238 362 1086 226 362 1087 239 362 1088 250 363 1089 249 363 1090 248 363 1091 250 364 1092 248 364 1093 252 364 1094 252 365 1095 248 365 1096 258 365 1097 252 366 1098 258 366 1099 257 366 1100 257 367 1101 258 367 1102 237 367 1103 257 368 1104 237 368 1105 256 368 1106 256 369 1107 237 369 1108 238 369 1109 256 370 1110 238 370 1111 254 370 1112 254 371 1113 238 371 1114 239 371 1115 254 372 1116 239 372 1117 247 372 1118 247 373 1119 245 373 1120 253 373 1121 242 374 1122 250 374 1123 252 374 1124 242 375 1125 252 375 1126 251 375 1127 251 376 1128 252 376 1129 257 376 1130 251 377 1131 257 377 1132 246 377 1133 246 378 1134 257 378 1135 256 378 1136 246 379 1137 256 379 1138 255 379 1139 255 380 1140 256 380 1141 254 380 1142 255 381 1143 254 381 1144 253 381 1145 253 382 1146 254 382 1147 247 382 1148 250 383 1149 36 383 1150 236 383 1151 250 384 1152 37 384 1153 36 384 1154 37 385 1155 250 385 1156 49 385 1157 49 386 1158 250 386 1159 242 386 1160 49 387 1161 242 387 1162 50 387 1163 242 388 1164 251 388 1165 50 388 1166 50 389 1167 251 389 1168 246 389 1169 50 390 1170 246 390 1171 95 390 1172 95 391 1173 246 391 1174 255 391 1175 95 392 1176 255 392 1177 104 392 1178 104 393 1179 255 393 1180 253 393 1181 253 394 1182 107 394 1183 104 394 1184 107 395 1185 253 395 1186 245 395 1187 107 396 1188 245 396 1189 93 396 1190 235 397 1191 94 397 1192 241 397 1193 241 398 1194 94 398 1195 245 398 1196 245 399 1197 94 399 1198 93 399 1199 278 400 1200 268 400 1201 262 400 1202 284 401 1203 268 401 1204 278 401 1205 284 402 1206 224 402 1207 268 402 1208 276 403 1209 224 403 1210 284 403 1211 262 404 1212 270 404 1213 281 404 1214 268 405 1215 270 405 1216 262 405 1217 266 406 1218 272 406 1219 277 406 1220 280 407 1221 272 407 1222 266 407 1223 280 408 1224 285 408 1225 272 408 1226 261 409 1227 285 409 1228 280 409 1229 261 410 1230 267 410 1231 285 410 1232 264 411 1233 267 411 1234 261 411 1235 264 412 1236 265 412 1237 267 412 1238 275 413 1239 265 413 1240 264 413 1241 275 414 1242 281 414 1243 265 414 1244 277 415 1245 269 415 1246 266 415 1247 272 416 1248 279 416 1249 277 416 1250 272 417 1251 260 417 1252 279 417 1253 285 418 1254 260 418 1255 272 418 1256 285 419 1257 259 419 1258 260 419 1259 267 420 1260 259 420 1261 285 420 1262 267 421 1263 263 421 1264 259 421 1265 265 422 1266 263 422 1267 267 422 1268 265 423 1269 282 423 1270 263 423 1271 281 424 1272 282 424 1273 265 424 1274 281 425 1275 270 425 1276 282 425 1277 260 426 1278 271 426 1279 279 426 1280 259 427 1281 271 427 1282 260 427 1283 259 428 1284 227 428 1285 271 428 1286 263 429 1287 227 429 1288 259 429 1289 263 430 1290 274 430 1291 227 430 1292 282 431 1293 274 431 1294 263 431 1295 270 432 1296 274 432 1297 282 432 1298 274 433 1299 268 433 1300 224 433 1301 270 434 1302 268 434 1303 274 434 1304 262 435 1305 208 435 1306 207 435 1307 281 436 1308 208 436 1309 262 436 1310 262 437 1311 207 437 1312 278 437 1313 39 438 1314 283 438 1315 231 438 1316 269 439 1317 39 439 1318 38 439 1319 39 440 1320 269 440 1321 283 440 1322 273 441 1323 231 441 1324 283 441 1325 273 442 1326 232 442 1327 231 442 1328 232 443 1329 273 443 1330 233 443 1331 273 444 1332 279 444 1333 233 444 1334 273 445 1335 277 445 1336 279 445 1337 283 446 1338 277 446 1339 273 446 1340 283 447 1341 269 447 1342 277 447 1343 279 448 1344 230 448 1345 233 448 1346 51 449 1347 269 449 1348 38 449 1349 51 450 1350 266 450 1351 269 450 1352 266 451 1353 51 451 1354 48 451 1355 48 452 1356 280 452 1357 266 452 1358 180 453 1359 280 453 1360 48 453 1361 180 454 1362 261 454 1363 280 454 1364 221 455 1365 261 455 1366 180 455 1367 221 456 1368 264 456 1369 261 456 1370 275 457 1371 264 457 1372 221 457 1373 220 458 1374 275 458 1375 221 458 1376 220 459 1377 281 459 1378 275 459 1379 208 460 1380 281 460 1381 220 460 1382 276 461 1383 223 461 1384 224 461 1385 271 462 1386 230 462 1387 279 462 1388 326 463 1389 152 463 1390 322 463 1391 310 464 1392 153 464 1393 152 464 1394 310 465 1395 152 465 1396 326 465 1397 344 466 1398 311 466 1399 339 466 1400 304 467 1401 311 467 1402 344 467 1403 321 468 1404 311 468 1405 304 468 1406 311 469 1407 343 469 1408 339 469 1409 311 470 1410 298 470 1411 343 470 1412 311 471 1413 346 471 1414 298 471 1415 311 472 1416 321 472 1417 346 472 1418 348 473 1419 341 473 1420 319 473 1421 319 474 1422 313 474 1423 345 474 1424 341 475 1425 313 475 1426 319 475 1427 341 476 1428 287 476 1429 313 476 1430 222 477 1431 325 477 1432 340 477 1433 219 478 1434 325 478 1435 222 478 1436 219 479 1437 332 479 1438 325 479 1439 123 480 1440 332 480 1441 219 480 1442 123 481 1443 297 481 1444 332 481 1445 165 482 1446 297 482 1447 123 482 1448 165 483 1449 302 483 1450 297 483 1451 290 484 1452 302 484 1453 165 484 1454 222 485 1455 340 485 1456 209 485 1457 164 486 1458 290 486 1459 165 486 1460 164 487 1461 343 487 1462 290 487 1463 151 488 1464 343 488 1465 164 488 1466 339 489 1467 151 489 1468 150 489 1469 339 490 1470 150 490 1471 344 490 1472 343 491 1473 151 491 1474 339 491 1475 306 492 1476 349 492 1477 300 492 1478 306 493 1479 299 493 1480 349 493 1481 306 494 1482 328 494 1483 324 494 1484 306 495 1485 338 495 1486 328 495 1487 300 496 1488 338 496 1489 306 496 1490 300 497 1491 340 497 1492 338 497 1493 312 498 1494 301 498 1495 333 498 1496 286 499 1497 301 499 1498 312 499 1499 286 500 1500 347 500 1501 301 500 1502 323 501 1503 347 501 1504 286 501 1505 323 502 1506 309 502 1507 347 502 1508 315 503 1509 309 503 1510 323 503 1511 315 504 1512 314 504 1513 309 504 1514 296 505 1515 314 505 1516 315 505 1517 296 506 1518 345 506 1519 314 506 1520 333 507 1521 322 507 1522 312 507 1523 301 508 1524 335 508 1525 333 508 1526 301 509 1527 336 509 1528 335 509 1529 347 510 1530 336 510 1531 301 510 1532 347 511 1533 337 511 1534 336 511 1535 309 512 1536 337 512 1537 347 512 1538 309 513 1539 330 513 1540 337 513 1541 314 514 1542 330 514 1543 309 514 1544 314 515 1545 294 515 1546 330 515 1547 345 516 1548 294 516 1549 314 516 1550 336 517 1551 329 517 1552 335 517 1553 337 518 1554 329 518 1555 336 518 1556 337 519 1557 295 519 1558 329 519 1559 330 520 1560 295 520 1561 337 520 1562 330 521 1563 288 521 1564 295 521 1565 294 522 1566 288 522 1567 330 522 1568 313 523 1569 288 523 1570 294 523 1571 345 524 1572 313 524 1573 294 524 1574 300 525 1575 349 525 1576 210 525 1577 340 526 1578 210 526 1579 209 526 1580 210 527 1581 340 527 1582 300 527 1583 350 528 1584 341 528 1585 320 528 1586 350 529 1587 287 529 1588 341 529 1589 91 530 1590 345 530 1591 92 530 1592 345 531 1593 91 531 1594 319 531 1595 319 532 1596 91 532 1597 348 532 1598 166 533 1599 322 533 1600 152 533 1601 166 534 1602 312 534 1603 322 534 1604 163 535 1605 312 535 1606 166 535 1607 163 536 1608 286 536 1609 312 536 1610 154 537 1611 286 537 1612 163 537 1613 154 538 1614 323 538 1615 286 538 1616 106 539 1617 323 539 1618 154 539 1619 106 540 1620 315 540 1621 323 540 1622 315 541 1623 106 541 1624 296 541 1625 296 542 1626 106 542 1627 105 542 1628 105 543 1629 345 543 1630 296 543 1631 92 544 1632 345 544 1633 105 544 1634 303 545 1635 335 545 1636 318 545 1637 303 546 1638 333 546 1639 335 546 1640 326 547 1641 333 547 1642 303 547 1643 326 548 1644 322 548 1645 333 548 1646 326 549 1647 316 549 1648 310 549 1649 303 550 1650 316 550 1651 326 550 1652 303 551 1653 307 551 1654 316 551 1655 303 552 1656 318 552 1657 307 552 1658 325 553 1659 327 553 1660 338 553 1661 332 554 1662 327 554 1663 325 554 1664 332 555 1665 334 555 1666 327 555 1667 297 556 1668 334 556 1669 332 556 1670 297 557 1671 342 557 1672 334 557 1673 302 558 1674 342 558 1675 297 558 1676 302 559 1677 308 559 1678 342 559 1679 290 560 1680 308 560 1681 302 560 1682 290 561 1683 343 561 1684 308 561 1685 338 562 1686 340 562 1687 325 562 1688 327 563 1689 328 563 1690 338 563 1691 327 564 1692 292 564 1693 328 564 1694 334 565 1695 292 565 1696 327 565 1697 334 566 1698 291 566 1699 292 566 1700 342 567 1701 291 567 1702 334 567 1703 342 568 1704 289 568 1705 291 568 1706 308 569 1707 289 569 1708 342 569 1709 308 570 1710 305 570 1711 289 570 1712 343 571 1713 305 571 1714 308 571 1715 292 572 1716 317 572 1717 328 572 1718 291 573 1719 317 573 1720 292 573 1721 291 574 1722 293 574 1723 317 574 1724 289 575 1725 293 575 1726 291 575 1727 289 576 1728 331 576 1729 293 576 1730 305 577 1731 331 577 1732 289 577 1733 298 578 1734 331 578 1735 305 578 1736 343 579 1737 298 579 1738 305 579 1739 298 580 1740 346 580 1741 331 580 1742 318 581 1743 335 581 1744 329 581 1745 321 582 1746 331 582 1747 346 582 1748 287 583 1749 288 583 1750 313 583 1751 350 584 1752 223 584 1753 287 584 1754 223 585 1755 274 585 1756 224 585 1757 274 586 1758 223 586 1759 227 586 1760 228 587 1761 223 587 1762 225 587 1763 225 588 1764 223 588 1765 226 588 1766 223 589 1767 293 589 1768 331 589 1769 223 590 1770 295 590 1771 288 590 1772 295 591 1773 223 591 1774 329 591 1775 329 592 1776 223 592 1777 318 592 1778 321 593 1779 223 593 1780 331 593 1781 226 594 1782 223 594 1783 229 594 1784 287 595 1785 223 595 1786 288 595 1787 324 596 1788 328 596 1789 351 596 1790 317 597 1791 351 597 1792 328 597 1793 223 598 1794 324 598 1795 351 598 1796 223 599 1797 351 599 1798 317 599 1799 293 600 1800 223 600 1801 317 600 1802 207 601 1803 210 601 1804 278 601 1805 278 602 1806 210 602 1807 349 602 1808 278 603 1809 349 603 1810 299 603 1811 278 604 1812 299 604 1813 284 604 1814 284 605 1815 299 605 1816 324 605 1817 276 606 1818 284 606 1819 324 606 1820 223 607 1821 276 607 1822 324 607 1823 299 608 1824 306 608 1825 324 608 1826 231 609 1827 36 609 1828 39 609 1829 231 610 1830 236 610 1831 36 610 1832 231 611 1833 232 611 1834 236 611 1835 232 612 1836 244 612 1837 236 612 1838 232 613 1839 234 613 1840 244 613 1841 232 614 1842 233 614 1843 234 614 1844 230 615 1845 234 615 1846 233 615 1847 223 616 1848 234 616 1849 230 616 1850 223 617 1851 228 617 1852 234 617 1853 223 618 1854 230 618 1855 271 618 1856 223 619 1857 271 619 1858 227 619 1859 150 620 1860 153 620 1861 310 620 1862 150 621 1863 310 621 1864 344 621 1865 310 622 1866 316 622 1867 344 622 1868 304 623 1869 344 623 1870 316 623 1871 304 624 1872 316 624 1873 307 624 1874 304 625 1875 307 625 1876 321 625 1877 307 626 1878 318 626 1879 321 626 1880 223 627 1881 321 627 1882 318 627 1883 235 628 1884 91 628 1885 94 628 1886 235 629 1887 348 629 1888 91 629 1889 235 630 1890 243 630 1891 348 630 1892 243 631 1893 320 631 1894 348 631 1895 243 632 1896 350 632 1897 320 632 1898 229 633 1899 350 633 1900 243 633 1901 223 634 1902 350 634 1903 229 634 1904 320 635 1905 341 635 1906 348 635 1907

+
+ + +

452 644

+
+
+
+
+ + + + 0.00016 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_E3M5.dae b/URDFs/sr_description/meshes/components/forearm/forearm_E3M5.dae new file mode 100644 index 0000000..febe937 --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_E3M5.dae @@ -0,0 +1,262 @@ + + + + + + Blender User + Blender 3.5.1 commit date:2023-04-24, commit time:18:11, hash:e1ccd9d4a1d3 + + 2023-06-22T12:00:19 + 2023-06-22T12:00:19 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.80848 0.80848 0.80848 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.21961 0.21961 0.21961 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.21961 0.21961 0.21961 1 + + + 1 + + + + + + + + + + + + + + + + + + + + + + + 3.15658 67.48139 15.1406 38.18585 55.74057 15.1406 43.16133 51.98325 15.1406 -38.10755 55.74084 15.1406 -32.80664 59.02303 15.1406 -43.08306 51.98356 15.1406 -27.22552 61.8021 15.1406 27.30387 61.80191 15.1406 21.49008 64.05413 15.1406 9.364743 66.90607 15.1406 -9.28636 66.90615 15.1406 -3.07818 67.48143 15.1406 -15.41501 65.76057 15.1406 -21.41171 64.05429 15.1406 15.49339 65.76045 15.1406 47.7831 47.69076 15.1406 67.48139 -3.15657 15.1406 55.74057 -38.18585 15.1406 51.98325 -43.16133 15.1406 55.74084 38.10755 15.1406 59.02303 32.80664 15.1406 59.02279 -32.88496 15.1406 51.98356 43.08307 15.1406 61.8021 27.22553 15.1406 61.80191 -27.30387 15.1406 64.05413 -21.49008 15.1406 66.90607 -9.364743 15.1406 66.90615 9.28636 15.1406 67.48143 3.07819 15.1406 65.76057 15.41502 15.1406 64.05429 21.41172 15.1406 65.76045 -15.49339 15.1406 47.69075 -47.78311 15.1406 -3.15659 -67.48139 15.1406 -38.18586 -55.74056 15.1406 -43.16134 -51.98324 15.1406 38.10754 -55.74085 15.1406 32.80663 -59.02303 15.1406 -32.88497 -59.02278 15.1406 43.08305 -51.98357 15.1406 27.22552 -61.80211 15.1406 -27.30388 -61.8019 15.1406 -21.49009 -64.05413 15.1406 -9.36475 -66.90607 15.1406 9.286353 -66.90615 15.1406 3.07817 -67.48143 15.1406 15.415 -65.76057 15.1406 21.41171 -64.05429 15.1406 -15.4934 -65.76045 15.1406 -47.76879 -47.78297 15.1406 -67.48139 3.15658 15.1406 -55.74057 38.18586 15.1406 -51.98325 43.16134 15.1406 -55.74085 -38.10754 15.1406 -59.02303 -32.80663 15.1406 -59.02279 32.88497 15.1406 -51.98357 -43.08306 15.1406 -61.8021 -27.22552 15.1406 -61.8019 27.30388 15.1406 -64.05413 21.49009 15.1406 -66.90607 9.36475 15.1406 -66.90615 -9.286353 15.1406 -67.48143 -3.07818 15.1406 -65.76057 -15.41501 15.1406 -64.05429 -21.41171 15.1406 -65.76045 15.49339 15.1406 -47.78297 47.76878 15.1406 29.88855 -2.94626 0.1406 -66.19735 -12.94628 0.1406 -29.81065 -2.94627 0.1406 -26.99805 -12.94628 0.1406 -62.80806 24.68092 0.1406 -59.55455 -31.64598 0.1406 -29.94435 1.05372 0.1406 25.07615 16.58062 10.1406 19.66905 -64.52888 0.1406 48.37674 47.16753 0.1406 19.94364 64.55223 0.1406 -52.20975 -42.68178 0.1406 -67.45365 -0.94628 0.1406 -24.99785 16.58122 10.1406 64.67866 -19.38757 0.1406 -64.60076 -19.38758 0.1406 27.90535 11.16503 0.1406 -29.54145 5.05372 0.1406 5.20453 42.74233 0.1406 -47.76075 -47.60588 0.1406 -10.21735 41.81262 0.1406 -29.84025 -2.63611 10.1406 -29.13205 7.05731 10.1406 15.23755 40.27813 0.1406 26.26944 62.24863 0.1406 29.88855 3.05372 0.1406 13.41974 66.21413 0.1406 28.92445 8.154973 0.1406 43.44324 51.74813 0.1406 27.94955 -10.94626 0.1406 -37.52395 -56.02908 0.1406 -29.13296 -6.94627 0.1406 60.12025 30.81873 0.1406 0.03894984 43.05372 0.1406 67.35356 -4.94628 0.1406 0.03898996 -29.94628 0.1406 -48.29885 47.16752 0.1406 65.02655 18.29823 0.1406 56.75694 36.65043 0.1406 9.953143 -28.26076 0.1406 -3.32206 -29.75738 0.1406 -27.41255 -12.04648 10.1406 67.47224 3.05372 0.1406 -23.42537 -18.63925 0.1406 56.23166 -37.34457 0.1406 -67.27565 5.05372 0.1406 26.53895 -14.00867 10.1406 -67.09716 -6.94627 0.1406 -0.30649 5.53084 10.5439 62.45715 -25.64087 0.1406 31.91315 -59.44657 0.1406 -52.75146 42.11822 0.1406 0.03893995 67.55373 0.1406 -31.83525 -59.44658 0.1406 29.21085 -6.94627 0.1406 -26.49595 14.05002 0.1406 -32.25645 59.32642 0.1406 -43.36536 51.74812 0.1406 26.57375 14.05033 0.1406 23.16535 19.09483 10.1406 -42.84965 -52.06938 0.1406 66.27526 -12.94627 0.1406 13.23215 -66.14438 0.1406 -25.94143 -14.94691 10.1406 6.76282 67.21804 0.1406 -56.67905 36.65042 0.1406 -64.94865 18.29822 0.1406 -22.95787 19.3189 0.1406 23.03557 19.3191 0.1406 0.03894984 25.24342 10.1406 62.88595 24.68093 0.1406 3.15977 43.10341 10.13999 -4.88601 -29.49477 10.1406 3.40005 -29.75737 0.1406 16.39395 39.49302 0.1406 52.28765 -42.68177 0.1406 -56.15375 -37.34458 0.1406 14.27375 30.47312 10.1406 0.03894984 -67.44628 0.1406 47.83865 -47.60587 0.1406 -26.79235 13.47312 10.1406 -26.19156 62.24862 0.1406 28.09124 10.56283 10.1406 20.13022 -22.225 10.1406 6.66763 -67.11997 0.1406 14.06305 29.80373 0.1406 -62.37925 -25.64088 0.1406 -38.00016 55.81462 0.1406 26.87055 13.47253 10.1406 32.79684 59.07212 15.1406 37.60185 -56.02907 0.1406 -6.58973 -67.11997 0.1406 28.67294 -8.89598 10.1406 -9.25984 42.20282 10.14001 -5.12663 42.74233 0.1406 1.83378 -29.89258 10.1406 15.78844 40.00233 10.14021 16.00825 -25.34277 0.1406 -19.86576 64.55223 0.1406 -6.68494 67.21804 0.1406 -13.98546 29.80534 0.1406 -66.44275 11.73412 0.1406 -60.04235 30.81872 0.1406 59.63245 -31.64597 0.1406 -28.84655 8.154783 0.1406 -25.83825 -62.28908 0.1406 -14.08326 27.71662 0.1406 21.34193 21.17674 10.1406 14.00565 28.40123 0.1406 24.72693 -16.9904 10.1406 17.06925 38.2692 0.1406 -17.09755 37.57352 0.1406 -8.48113 -28.71097 10.1406 -18.67477 -23.39396 0.1406 32.33434 59.32643 0.1406 -17.05125 37.03053 10.14291 -14.19585 30.47311 10.1406 38.07804 55.81463 0.1406 13.97235 29.10572 10.1406 29.09395 7.52404 10.1406 -29.37345 -5.85473 10.1406 21.26152 -21.1501 0.1406 -3.08271 43.10331 10.13999 -28.01435 10.56122 10.1406 29.97205 2.05655 10.1406 -28.56105 -9.00385 10.1406 4.49238 -29.52047 10.25291 52.82935 42.11823 0.1406 -6.64069 -29.19318 0.1406 16.89603 36.20391 10.14 30.02915 -0.7147 10.1406 -13.34186 66.21413 0.1406 -19.59114 -64.52888 0.1406 42.92755 -52.06937 0.1406 10.29525 41.81262 0.1406 25.44953 -15.8931 0.1406 -13.15425 -66.14438 0.1406 -17.22932 -24.47799 10.1406 -20.79073 21.64364 0.1406 -1.75515 -29.89258 10.1406 -22.10432 -20.1868 10.1406 -16.81815 36.20392 10.14292 -27.82755 11.16482 0.1406 66.52066 11.73413 0.1406 9.33692 42.20303 10.14001 17.17624 37.39723 10.14021 14.43386 27.07011 0.1406 -15.21455 40.37392 10.14 -22.84564 19.45203 10.1406 29.37685 -6.21435 10.1406 14.45012 -26.25819 10.1406 14.16115 27.71701 10.1406 -29.71885 3.85807 10.1406 -29.95585 0.61422 10.1406 7.99297 -28.87258 10.1406 -16.72595 38.92103 0.1406 -16.38056 39.54288 10.13363 -12.98475 -26.97188 0.1406 -17.01304 38.32173 10.14054 16.83693 39.01018 10.13958 25.91615 -62.28907 0.1406 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.04916781 -0.9987773 0.005146324 -0.1469879 -0.9890517 -0.01308947 -0.1837452 -0.9829677 -0.003493785 -0.2434051 -0.9698358 -0.01313441 -0.2736766 -0.9618126 -0.004205524 -0.337469 -0.9412479 -0.01293218 -0.3612312 -0.9324629 -0.005010128 -0.4282761 -0.9035615 -0.01249933 -0.4457399 -0.8951432 -0.005902945 -0.5149333 -0.8571488 -0.01181811 -0.5264254 -0.8501935 -0.006875932 -0.5966258 -0.8024457 -0.01089286 -0.6725513 -0.7399947 -0.009096682 -0.7444596 -0.6676163 -0.008280873 -0.7419795 -0.6703886 -0.006745934 -0.7980152 -0.6026235 -0.004088521 -0.8042136 -0.5942854 -0.008090734 -0.8502129 -0.5264284 -0.003372848 -0.8586741 -0.5124389 -0.009223997 -0.89516 -0.4457365 -0.002769887 -0.9048432 -0.4256244 -0.01014858 -0.9324749 -0.3612278 -0.0022825 -0.9422483 -0.3347398 -0.01084285 -0.9618215 -0.2736712 -0.001889407 -0.9705653 -0.2405717 -0.01133197 -0.9829736 -0.1837394 -0.001617193 -0.09225469 -0.9954928 -0.02198249 -0.9888861 -0.1483018 -0.01054334 -0.9981868 -0.05931073 -0.01027768 -0.9957328 -0.09226769 -0.001714885 -0.9995107 0.02965128 -0.009959101 -0.9999984 7.83158e-6 -0.001851022 -0.04985654 0.9986411 0.01517665 6.11492e-6 0.9998459 -0.01755702 -0.1490958 0.9886499 0.01848965 -0.09224909 0.9955148 -0.02098661 -0.2467961 0.968817 0.02202945 -0.1836844 0.982676 -0.02465862 -0.4340626 0.9008774 -0.003102719 -0.4457374 0.895162 0.001756191 -0.5216395 0.8531641 -0.001877188 -0.5264329 0.8502166 4.13116e-4 -0.6040424 0.7969521 -4.0426e-4 -0.6026287 0.7980208 -0.001184463 -0.6804111 0.7328296 0.001302778 -0.6676228 0.744468 -0.006880342 -0.7500339 0.6613992 -7.16275e-4 -0.7389752 0.6736725 -0.009002506 -0.8121829 0.5834022 0.001024544 -0.7979614 0.6025939 -0.01175856 -0.8662556 0.4995918 0.003058016 -0.8501212 0.5263813 -0.01472598 -0.9117024 0.4108163 0.005379021 -0.8950168 0.4456734 -0.01789695 -0.9480707 0.3179596 0.00799483 -0.9322645 0.3611528 -0.02125549 -0.975002 0.2219281 0.01091939 -0.9615253 0.2735921 -0.02483075 -0.9922178 0.1237106 0.01412945 0.04985862 0.9986827 0.01212102 0.1491193 0.9888051 -0.005301773 0.1837445 0.9829646 0.004329442 0.2468531 0.9690411 -0.004817008 0.2736773 0.9618144 0.003723263 0.3421748 0.9396275 -0.004074275 0.3612332 0.9324712 0.002859115 0.4340624 0.9008775 -0.003104209 0.4450342 0.8955124 0.001460731 0.5216401 0.8531641 -0.001619756 0.5258399 0.8505836 4.20024e-4 0.6040421 0.7969524 -4.06167e-4 0.6026355 0.7980158 -0.001183211 0.6804102 0.7328304 0.001300692 0.7500334 0.6614 -2.51438e-4 0.7980067 0.6026164 0.006234824 0.8121833 0.5834001 -0.001654863 0.8501981 0.5264235 0.006455421 0.8662552 0.4995938 -0.002845108 0.8951446 0.4457299 0.006406426 0.9117093 0.4108182 -0.003813982 0.93246 0.3612221 0.006098628 0.9480911 0.3179664 -0.004546463 0.9618085 0.2736675 0.00553739 0.9750476 0.2219385 -0.005053639 0.9829636 0.18374 0.004721641 0.9940152 0.1089667 -0.007763743 0.9957337 0.09227043 -7.60801e-4 0.09226739 0.9956306 -0.01437467 0.9957302 -0.09227788 0.002524197 0.9998672 -0.0148316 -0.006751179 0.9999998 -6.52633e-6 -6.12885e-4 0.9706053 -0.2405841 0.00668931 0.9324096 -0.3612104 -0.01180875 0.9422971 -0.3347535 0.004049062 0.8951111 -0.4457241 -0.01031482 0.9048895 -0.4256437 0.001620352 0.8501793 -0.5264177 -0.008926868 0.8587122 -0.5124578 -6.27868e-4 0.7979924 -0.6026186 -0.00767219 0.8042364 -0.5943036 -0.002679705 0.7327088 -0.6805075 -0.006887078 0.7419962 -0.6704039 -6.04868e-4 0.6736933 -0.7390082 -0.002089202 0.6725766 -0.7400225 -0.002739727 0.6026282 -0.7980204 -0.001682519 0.5966536 -0.8024851 -0.004695892 0.5264312 -0.8502168 -0.001411139 0.5149593 -0.8571903 -0.006470322 0.44574 -0.8951616 -0.001274883 0.4282964 -0.9036026 -0.008051812 0.3374416 -0.9411662 0.01841765 0.1836652 -0.982573 -0.02859234 0.243399 -0.9698138 0.01477462 0.09223747 -0.99539 -0.02628672 0.146991 -0.9890729 0.01133942 -6.11156e-6 -0.9997097 -0.02409273 0.04916685 -0.9987574 0.008136868 0.7743389 -0.6077327 0.1762394 0.6709738 -0.741075 -0.02453613 0.7314653 -0.6818782 8.68517e-4 0.8001199 -0.5998393 -9.93936e-4 0.8300756 -0.5573999 0.01673531 0.8660164 -0.5000057 -0.00317645 0.9079599 -0.4190481 0.002737045 0.922078 -0.3869558 -0.006132245 0.9471933 -0.3206591 -0.001661241 0.9526861 -0.3038939 -0.006152391 0.9757936 -0.2186594 0.003861546 0.9835832 -0.1804087 -0.004121541 0.9949496 -0.1002161 0.005668044 0.9993665 0.03554135 0.001855731 0.9994385 0.03340721 0.002617478 0.9973396 -0.07286679 -0.002055585 0.9896446 0.143532 -0.001522302 0.9859352 0.1670385 0.005477666 0.9682901 0.2497971 -0.003979861 0.9420294 0.3351911 0.01509249 0.8918353 0.452345 -0.003735363 0.8469022 0.531482 0.01684445 0.9355447 0.3531392 0.00700283 0.8067144 0.5907474 -0.01515001 0.7073229 0.7067113 0.01592606 0.660665 0.7505477 -0.01413428 0.5322556 0.846454 0.01482343 0.4352185 0.8994544 -0.03958278 0.3304283 0.9437071 0.01530671 0.2130073 0.9770187 -0.007910132 -0.1820928 0.9832756 -0.003365457 -0.1382665 0.9903606 -0.008265078 -0.05611616 0.9984132 0.004710316 0 0.9999856 -0.00537014 0.05611348 0.9984133 0.004705786 0.126045 0.9920043 -0.006337761 0.1676048 0.9858542 3.22968e-4 -0.9227706 0.3851561 -0.01221543 -0.8924322 0.4510156 0.01223289 -0.854564 0.5193244 -0.004765331 -0.7820889 0.6230543 0.01185411 -0.7513319 0.6597744 -0.01407897 -0.6237362 0.7815194 0.01344251 -0.5788823 0.8152627 -0.01556622 -0.434078 0.9007534 0.01482164 -0.3752358 0.9267762 -0.01685065 -0.2226211 0.9747737 0.0160017 -0.9672294 0.2538921 -0.00252676 -0.9536842 0.3007206 0.007332324 -0.9859411 0.1670421 0.004140436 -0.999768 -0.020599 0.006293892 -0.9999012 0 0.01405858 -0.9929642 0.1177732 -0.01232063 -0.9825936 -0.1857029 0.004938125 -0.9496313 -0.313348 -0.003674089 -0.987319 -0.1585685 -0.007567763 -0.6730729 -0.7389896 0.02944964 -0.6692135 -0.7426623 0.02461928 -0.7522541 -0.6588541 -0.005013048 -0.7961584 -0.6050797 -0.003237605 -0.8300631 -0.5574186 0.01673275 -0.8660276 -0.4999863 -0.003185331 -0.9079648 -0.4190377 0.002736508 -0.9221218 -0.386851 -0.006154835 -0.9471845 -0.3206847 -0.001704275 0 0 -1 0 0 -1 0 0 -1 0.2935867 -0.9558883 0.009187877 0.144209 -0.9892366 0.02479338 0.1796569 -0.9837286 -0.001211345 0.06015551 -0.9979071 0.02372848 1.5888e-5 -0.9999877 0.004964172 -0.06015551 -0.9979069 0.02373319 -0.1796568 -0.9837286 -0.001214861 -0.1441912 -0.9892389 0.02480417 -0.2965059 -0.9549899 0.008868932 -0.3228356 -0.9464186 -0.008316457 0.4049757 -0.9115484 0.07123428 0.9092891 0.4160752 -0.008653283 0.9279882 0.371771 0.02498388 0.9986147 -0.04675936 0.02413225 0.5800126 -0.8140324 0.03060775 0.8879591 -0.459918 -0.002070426 0.96395 -0.2658244 0.01174277 0.9995426 -0.02959257 -0.006233096 0.9624128 0.2713963 0.01027792 -0.9070907 0.4150716 0.07001584 -0.9423431 0.3346386 -0.002545058 -0.9730734 0.2284906 0.03033548 -0.9785536 -0.2058565 -0.00748074 -0.8754459 -0.483069 0.01545721 -0.6873169 -0.726343 -0.004623889 -0.5616844 -0.8273117 0.008124887 -0.9519383 -0.3062283 -0.006150066 -0.9908655 -0.1347116 0.006190657 -0.9991444 0.04089224 -0.006207823 -0.9765405 0.2152456 0.006167232 0 0 -1 0 0 -1 -6.84483e-7 0 -1 0.1401688 -0.8464147 -0.5137462 3.92904e-7 0 -1 0.01062613 0.01094919 -0.9998837 0 0.01138436 -0.9999353 -0.001866638 0.01127153 -0.9999347 0 0 -1 -0.01297652 0.001539111 -0.9999147 -0.01230746 0.003230571 -0.9999191 -0.01152145 0.004808962 -0.9999222 0.01376777 -0.001005828 -0.9999048 0.01352137 4.80883e-4 -0.9999085 -0.01335 -2.75069e-4 -0.999911 0.01385504 -0.002541244 -0.9999008 0.0137571 -0.004388332 -0.9998958 -0.0135684 -0.002179145 -0.9999056 0.01352357 -0.005675196 -0.9998925 -0.01341599 -0.004426836 -0.9999003 0.01297825 -0.007493138 -0.9998878 -0.01269626 -0.007329881 -0.9998926 -0.01321768 -0.005545139 -0.9998974 0.0122286 -0.00916773 -0.9998833 -0.01140701 -0.009990572 -0.999885 -0.003891646 -0.02038633 -0.9997847 -0.01193726 -0.009072482 -0.9998877 0.005199432 -0.02054548 -0.9997755 -1.38558e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.01041489 0.006329298 -0.9999258 -0.008999526 0.007902801 -0.9999283 -0.006774663 0.009541034 -0.9999316 -0.004323601 0.01067882 -0.9999337 1.78641e-4 4.86499e-4 -1 -1.77168e-4 -6.16379e-5 -1 -0.001374006 -0.001794755 -0.9999974 -0.003102898 -0.004051268 -0.999987 0.003194987 0.003181397 -0.9999899 1.0507e-5 -2.89645e-5 -1 1.88823e-6 -3.38779e-5 -1 0 -3.41743e-5 -1 -1.75336e-6 -3.38779e-5 -1 1.63012e-5 -4.36613e-5 -1 -3.12347e-4 3.06079e-4 -1 2.22164e-4 -3.4425e-4 -1 -1.78375e-4 2.18321e-4 -1 4.62061e-5 -1.26026e-4 -1 0 0 -1 0 0 -1 -0.9957313 0.092278 -0.001986742 -0.9825724 0.1836702 -0.0285781 -0.6026169 -0.7979912 -0.007939815 -0.6736652 -0.7389723 -0.009754598 0.2735412 -0.961361 -0.03099054 0.3612274 -0.9324769 -0.001260221 0.9617342 -0.2736533 -0.01346099 0.9829703 -0.1837469 0.002535104 0.9909908 -0.1335728 -0.009781718 0.7389967 0.6736846 0.005747079 0.6805227 0.7327257 0.00137335 -0.2736713 0.9618161 0.003723561 -0.361222 0.9324588 -0.006274521 -0.3421755 0.9396258 0.004384338 + + + + + + + + + + 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 + + + + + + + + + + + + + + + + +

79 0 0 112 0 1 84 0 2 84 1 3 73 1 4 68 1 5 114 0 6 84 0 7 68 0 8 79 2 9 84 2 10 114 2 11 173 3 12 178 3 13 167 3 14 43 4 15 158 4 16 145 4 17 43 5 18 203 5 19 158 5 20 48 6 21 203 6 22 43 6 23 48 7 24 199 7 25 203 7 26 42 8 27 199 8 28 48 8 29 42 9 30 172 9 31 199 9 32 41 10 33 172 10 34 42 10 35 41 11 36 120 11 37 172 11 38 38 12 39 120 12 40 41 12 41 38 13 42 97 13 43 120 13 44 34 14 45 97 14 46 38 14 47 34 15 48 127 15 49 97 15 50 49 16 51 86 16 52 127 16 53 56 17 54 86 17 55 49 17 56 56 18 57 78 18 58 86 18 59 53 19 60 78 19 61 56 19 62 53 20 63 143 20 64 78 20 65 54 21 66 143 21 67 53 21 68 54 22 69 72 22 70 143 22 71 57 23 72 72 23 73 54 23 74 57 24 75 153 24 76 72 24 77 64 25 78 153 25 79 57 25 80 64 26 81 82 26 82 153 26 83 63 27 84 82 27 85 64 27 86 63 28 87 68 28 88 82 28 89 61 29 90 68 29 91 63 29 92 145 30 93 33 30 94 43 30 95 61 31 96 114 31 97 68 31 98 79 32 99 114 32 100 62 32 101 62 33 102 114 33 103 61 33 104 50 34 105 112 34 106 79 34 107 50 35 108 79 35 109 62 35 110 166 36 111 0 36 112 119 36 113 166 37 114 11 37 115 0 37 116 198 38 117 11 38 118 166 38 119 198 39 120 10 39 121 11 39 122 165 40 123 10 40 124 198 40 125 165 41 126 12 41 127 10 41 128 123 42 129 6 42 130 148 42 131 123 43 132 4 43 133 6 43 134 154 44 135 4 44 136 123 44 137 3 45 138 4 45 139 154 45 140 124 46 141 3 46 142 154 46 143 124 47 144 5 47 145 3 47 146 103 48 147 5 48 148 124 48 149 103 49 150 66 49 151 5 49 152 118 50 153 66 50 154 103 50 155 118 51 156 52 51 157 66 51 158 132 52 159 52 52 160 118 52 161 132 53 162 51 53 163 52 53 164 169 54 165 51 54 166 132 54 167 169 55 168 55 55 169 51 55 170 71 56 171 55 56 172 169 56 173 71 57 174 58 57 175 55 57 176 133 58 177 58 58 178 71 58 179 133 59 180 59 59 181 58 59 182 168 60 183 59 60 184 133 60 185 168 61 186 65 61 187 59 61 188 112 62 189 65 62 190 168 62 191 9 63 192 131 63 193 119 63 194 9 64 195 93 64 196 131 64 197 14 65 198 93 65 199 9 65 200 14 66 201 77 66 202 93 66 203 8 67 204 77 67 205 14 67 206 8 68 207 91 68 208 77 68 209 7 69 210 91 69 211 8 69 212 7 70 213 181 70 214 91 70 215 156 71 216 181 71 217 7 71 218 156 72 219 184 72 220 181 72 221 1 73 222 184 73 223 156 73 224 1 74 225 95 74 226 184 74 227 2 75 228 95 75 229 1 75 230 2 76 231 76 76 232 95 76 233 22 77 234 194 77 235 76 77 236 19 78 237 194 78 238 22 78 239 19 79 240 105 79 241 194 79 242 20 80 243 105 80 244 19 80 245 20 81 246 99 81 247 105 81 248 23 82 249 99 82 250 20 82 251 23 83 252 137 83 253 99 83 254 30 84 255 137 84 256 23 84 257 30 85 258 104 85 259 137 85 260 29 86 261 104 86 262 30 86 263 29 87 264 210 87 265 104 87 266 27 88 267 210 88 268 29 88 269 27 89 270 109 89 271 210 89 272 28 90 273 109 90 274 27 90 275 119 91 276 0 91 277 9 91 278 101 92 279 16 92 280 26 92 281 109 93 282 16 93 283 101 93 284 16 94 285 109 94 286 28 94 287 25 95 288 81 95 289 128 95 290 24 96 291 81 96 292 25 96 293 24 97 294 116 97 295 81 97 296 21 98 297 116 98 298 24 98 299 21 99 300 170 99 301 116 99 302 17 100 303 170 100 304 21 100 305 17 101 306 111 101 307 170 101 308 18 102 309 111 102 310 17 102 311 18 103 312 142 103 313 111 103 314 32 104 315 142 104 316 18 104 317 32 105 318 146 105 319 142 105 320 39 106 321 146 106 322 32 106 323 39 107 324 200 107 325 146 107 326 36 108 327 200 108 328 39 108 329 36 109 330 157 109 331 200 109 332 37 110 333 157 110 334 36 110 335 37 111 336 117 111 337 157 111 338 40 112 339 117 112 340 37 112 341 40 113 342 227 113 343 117 113 344 46 114 345 75 114 346 227 114 347 44 115 348 75 115 349 46 115 350 44 116 351 129 116 352 75 116 353 45 117 354 129 117 355 44 117 356 45 118 357 151 118 358 129 118 359 33 119 360 151 119 361 45 119 362 33 120 363 145 120 364 151 120 365 215 121 366 173 121 367 183 121 368 215 122 369 205 122 370 173 122 371 215 123 372 134 123 373 205 123 374 80 124 375 134 124 376 215 124 377 122 125 378 134 125 379 80 125 380 147 126 381 122 126 382 80 126 383 147 127 384 209 127 385 122 127 386 190 128 387 209 128 388 147 128 389 190 129 390 171 129 391 209 129 392 89 130 393 171 130 394 190 130 395 89 131 396 84 131 397 171 131 398 219 132 399 84 132 400 89 132 401 219 133 402 73 133 403 84 133 404 69 134 405 220 134 406 88 134 407 69 135 408 73 135 409 220 135 410 220 136 411 73 136 412 219 136 413 187 137 414 69 137 415 88 137 416 98 138 417 69 138 418 187 138 419 192 139 420 98 139 421 187 139 422 70 140 423 98 140 424 192 140 425 130 141 426 70 141 427 108 141 428 110 142 429 70 142 430 130 142 431 70 143 432 192 143 433 108 143 434 207 144 435 110 144 436 130 144 437 207 145 438 180 145 439 110 145 440 204 146 441 180 146 442 207 146 443 204 147 444 224 147 445 180 147 446 179 148 447 224 148 448 204 148 449 179 149 450 195 149 451 224 149 452 139 150 453 195 150 454 179 150 455 140 151 456 193 151 457 221 151 458 140 152 459 162 152 460 193 152 461 102 153 462 162 153 463 140 153 464 102 154 465 206 154 466 162 154 467 107 155 468 206 155 469 102 155 470 107 156 471 139 156 472 206 156 473 195 157 474 139 157 475 107 157 476 96 158 477 113 158 478 159 158 479 202 159 480 113 159 481 96 159 482 202 160 483 176 160 484 113 160 485 188 161 486 176 161 487 202 161 488 188 162 489 150 162 490 176 162 491 164 163 492 150 163 493 188 163 494 164 164 495 217 164 496 150 164 497 106 165 498 217 165 499 164 165 500 106 166 501 221 166 502 217 166 503 140 167 504 221 167 505 106 167 506 121 168 507 159 168 508 216 168 509 121 169 510 96 169 511 159 169 512 216 170 513 67 170 514 121 170 515 92 171 516 197 171 517 191 171 518 67 172 519 197 172 520 92 172 521 197 173 522 67 173 523 216 173 524 186 174 525 94 174 526 92 174 527 149 175 528 94 175 529 186 175 530 92 176 531 191 176 532 186 176 533 213 177 534 174 177 535 218 177 536 135 178 537 174 178 538 213 178 539 135 179 540 126 179 541 174 179 542 135 180 543 74 180 544 126 180 545 125 181 546 74 181 547 135 181 548 125 182 549 155 182 550 74 182 551 83 183 552 155 183 553 125 183 554 83 184 555 149 184 556 155 184 557 94 185 558 149 185 559 83 185 560 101 186 561 96 186 562 109 186 563 128 187 564 96 187 565 101 187 566 67 0 567 92 0 568 109 0 569 96 188 570 121 188 571 109 188 572 67 0 573 109 0 574 121 0 575 87 189 576 160 189 577 214 189 578 87 190 579 189 190 580 160 190 581 161 191 582 189 191 583 87 191 584 100 192 585 189 192 586 161 192 587 100 193 588 138 193 589 189 193 590 85 194 591 138 194 592 100 194 593 201 195 594 138 195 595 85 195 596 201 196 597 211 196 598 138 196 599 90 197 600 211 197 601 201 197 602 90 198 603 163 198 604 211 198 605 214 199 606 222 199 607 87 199 608 208 200 609 183 200 610 167 200 611 167 201 612 178 201 613 208 201 614 183 202 615 173 202 616 167 202 617 223 203 618 222 203 619 214 203 620 225 204 621 222 204 622 223 204 623 225 205 624 178 205 625 222 205 626 182 206 627 178 206 628 225 206 629 182 207 630 208 207 631 178 207 632 196 208 633 177 208 634 144 208 635 177 209 636 152 209 637 144 209 638 212 210 639 177 210 640 196 210 641 226 211 642 177 211 643 212 211 644 226 212 645 141 212 646 177 212 647 163 213 648 141 213 649 226 213 650 163 214 651 90 214 652 141 214 653 175 215 654 213 215 655 218 215 656 185 216 657 175 216 658 218 216 659 185 217 660 152 217 661 175 217 662 144 218 663 152 218 664 185 218 665 204 219 666 139 219 667 179 219 668 139 0 669 204 0 670 207 0 671 206 220 672 207 220 673 130 220 674 206 221 675 139 221 676 207 221 677 193 222 678 162 222 679 221 222 680 88 223 681 206 223 682 187 223 683 115 224 684 206 224 685 88 224 686 115 225 687 162 225 688 206 225 689 221 226 690 162 226 691 115 226 692 206 227 693 130 227 694 108 227 695 192 0 696 206 0 697 108 0 698 187 0 699 206 0 700 192 0 701 216 228 702 115 228 703 197 228 704 216 229 705 159 229 706 115 229 707 115 230 708 159 230 709 113 230 710 219 231 711 115 231 712 220 231 713 220 232 714 115 232 715 88 232 716 115 233 717 191 233 718 197 233 719 89 234 720 115 234 721 219 234 722 190 235 723 115 235 724 89 235 725 191 236 726 115 236 727 186 236 728 190 237 729 147 237 730 115 237 731 115 238 732 149 238 733 186 238 734 115 239 735 147 239 736 80 239 737 115 240 738 74 240 739 155 240 740 115 241 741 155 241 742 149 241 743 115 242 744 80 242 745 215 242 746 115 243 747 174 243 748 126 243 749 136 244 750 174 244 751 115 244 752 126 245 753 74 245 754 115 245 755 215 246 756 136 246 757 115 246 758 183 0 759 136 0 760 215 0 761 136 247 762 218 247 763 174 247 764 185 0 765 218 0 766 136 0 767 136 0 768 144 0 769 185 0 770 82 0 771 68 0 772 70 0 773 82 0 774 70 0 775 110 0 776 82 0 777 110 0 778 153 0 779 72 0 780 153 0 781 110 0 782 72 0 783 110 0 784 143 0 785 110 248 786 180 248 787 143 248 788 78 249 789 143 249 790 180 249 791 78 0 792 180 0 793 86 0 794 86 250 795 180 250 796 127 250 797 127 251 798 180 251 799 224 251 800 97 252 801 127 252 802 224 252 803 97 253 804 224 253 805 120 253 806 120 0 807 224 0 808 172 0 809 172 254 810 224 254 811 195 254 812 172 0 813 195 0 814 199 0 815 195 255 816 203 255 817 199 255 818 107 256 819 203 256 820 195 256 821 107 257 822 158 257 823 203 257 824 102 258 825 158 258 826 107 258 827 102 259 828 145 259 829 158 259 830 102 260 831 151 260 832 145 260 833 102 0 834 140 0 835 151 0 836 129 0 837 151 0 838 140 0 839 106 261 840 129 261 841 140 261 842 75 0 843 129 0 844 106 0 845 75 0 846 106 0 847 227 0 848 106 0 849 164 0 850 227 0 851 117 0 852 227 0 853 164 0 854 117 0 855 164 0 856 157 0 857 157 0 858 164 0 859 200 0 860 164 0 861 188 0 862 200 0 863 146 0 864 200 0 865 188 0 866 142 262 867 146 262 868 188 262 869 111 0 870 142 0 871 188 0 872 111 263 873 188 263 874 202 263 875 111 0 876 202 0 877 170 0 878 116 0 879 170 0 880 202 0 881 81 0 882 116 0 883 202 0 884 81 264 885 202 264 886 96 264 887 81 265 888 96 265 889 128 265 890 92 0 891 210 0 892 109 0 893 94 0 894 210 0 895 92 0 896 94 266 897 104 266 898 210 266 899 94 267 900 137 267 901 104 267 902 83 0 903 137 0 904 94 0 905 83 268 906 99 268 907 137 268 908 83 269 909 125 269 910 99 269 911 99 0 912 125 0 913 105 0 914 105 270 915 125 270 916 135 270 917 105 271 918 135 271 919 194 271 920 76 272 921 194 272 922 135 272 923 76 0 924 135 0 925 213 0 926 76 0 927 213 0 928 95 0 929 95 0 930 213 0 931 184 0 932 175 0 933 184 0 934 213 0 935 152 273 936 184 273 937 175 273 938 152 0 939 177 0 940 184 0 941 141 0 942 184 0 943 177 0 944 141 0 945 181 0 946 184 0 947 90 274 948 181 274 949 141 274 950 90 275 951 91 275 952 181 275 953 77 276 954 91 276 955 90 276 956 77 277 957 90 277 958 201 277 959 77 0 960 201 0 961 93 0 962 85 0 963 93 0 964 201 0 965 85 278 966 131 278 967 93 278 968 85 279 969 100 279 970 131 279 971 100 280 972 119 280 973 131 280 974 100 0 975 161 0 976 119 0 977 119 281 978 161 281 979 166 281 980 87 0 981 166 0 982 161 0 983 87 282 984 198 282 985 166 282 986 87 283 987 165 283 988 198 283 989 87 0 990 222 0 991 165 0 992 148 284 993 165 284 994 222 284 995 123 0 996 148 0 997 222 0 998 123 285 999 222 285 1000 178 285 1001 123 286 1002 178 286 1003 154 286 1004 154 287 1005 178 287 1006 173 287 1007 124 288 1008 154 288 1009 173 288 1010 124 0 1011 173 0 1012 205 0 1013 103 0 1014 124 0 1015 205 0 1016 103 289 1017 205 289 1018 134 289 1019 103 0 1020 134 0 1021 118 0 1022 118 290 1023 134 290 1024 122 290 1025 118 0 1026 122 0 1027 132 0 1028 122 291 1029 169 291 1030 132 291 1031 122 292 1032 209 292 1033 169 292 1034 71 0 1035 169 0 1036 209 0 1037 71 293 1038 209 293 1039 171 293 1040 71 294 1041 171 294 1042 133 294 1043 84 0 1044 133 0 1045 171 0 1046 84 295 1047 168 295 1048 133 295 1049 84 0 1050 112 0 1051 168 0 1052 113 296 1053 176 296 1054 115 296 1055 150 297 1056 115 297 1057 176 297 1058 150 298 1059 217 298 1060 115 298 1061 115 299 1062 217 299 1063 221 299 1064 136 300 1065 183 300 1066 208 300 1067 136 301 1068 208 301 1069 182 301 1070 136 302 1071 182 302 1072 225 302 1073 136 303 1074 225 303 1075 223 303 1076 136 304 1077 223 304 1078 214 304 1079 136 305 1080 214 305 1081 160 305 1082 136 306 1083 160 306 1084 189 306 1085 136 307 1086 189 307 1087 138 307 1088 136 308 1089 138 308 1090 211 308 1091 136 309 1092 211 309 1093 163 309 1094 136 310 1095 163 310 1096 226 310 1097 136 311 1098 226 311 1099 212 311 1100 136 312 1101 212 312 1102 196 312 1103 136 313 1104 196 313 1105 144 313 1106 68 314 1107 73 314 1108 69 314 1109 68 315 1110 69 315 1111 98 315 1112 68 0 1113 98 0 1114 70 0 1115 50 316 1116 60 316 1117 112 316 1118 60 317 1119 65 317 1120 112 317 1121 34 318 1122 35 318 1123 127 318 1124 35 319 1125 49 319 1126 127 319 1127 46 320 1128 227 320 1129 47 320 1130 40 321 1131 47 321 1132 227 321 1133 25 322 1134 128 322 1135 31 322 1136 26 323 1137 31 323 1138 128 323 1139 26 324 1140 128 324 1141 101 324 1142 15 325 1143 22 325 1144 76 325 1145 2 326 1146 15 326 1147 76 326 1148 12 327 1149 165 327 1150 13 327 1151 6 328 1152 13 328 1153 165 328 1154 6 329 1155 165 329 1156 148 329 1157

+
+
+
+ + + + 29.2331 -14.16401 196.7418 10.76716 -13.86542 201.6429 21.39861 -14.07537 193.4641 27.46566 -14.16783 194.2271 28.3862 -14.16117 201.1792 28.55589 -14.16393 195.3397 26.57802 -14.088 203.1484 26.0908 -14.14846 193.4914 29.12671 -29.98901 195.9577 28.15216 -30.7099 194.1976 29.69017 -29.98164 197.5565 25.48671 -30.31977 193.1829 27.11698 -30.73169 193.5123 21.12255 -28.88793 193.1422 21.49174 -35.58555 193.141 15.37017 -19.99502 188.3348 -21.50867 -35.58535 193.141 -27.01785 -30.10811 193.7396 -21.49532 -28.98937 193.141 -28.13104 -30.71404 194.175 -25.83329 -30.16364 193.2869 -29.20789 -30.24131 196.066 -15.387 -19.99488 188.3347 -27.60938 -14.16784 194.2271 -28.52991 -14.16118 201.1792 -29.57075 -14.16784 198.2878 -26.23451 -14.14847 193.4914 -28.69961 -14.16394 195.3397 -21.49527 -19.99485 193.141 10.70515 -20.04278 200.9014 10.82763 -0.05495995 198.8623 -8.135763 -19.99491 225.7452 -1.23421 -19.99494 228.0908 11.7382 -19.99501 222.4602 5.95719 -19.99498 226.9021 -5.97408 -19.99492 226.9021 1.21731 -19.99496 228.0908 -10.08011 -19.99495 224.2513 -11.75508 -19.99489 222.4602 11.60935 -27.98278 222.6372 10.0632 -19.995 224.2513 -11.76637 -27.98262 222.4723 19.13893 -28.90956 212.8358 -19.56073 -29.1617 212.2155 28.61199 -30.50734 201.1697 -29.58549 -31.27479 199.4863 -28.62001 -31.02658 201.1763 -29.68513 -29.98092 198.6928 0.30527 -20.00591 213.1484 27.08075 -19.99508 203.1861 11.08792 -20.04278 202.3254 12.11914 -14.04642 203.0609 10.88063 -6.11725 201.9681 29.74393 -30.96025 198.3759 27.56346 -30.98839 192.2909 26.96834 -31.01417 183.141 27.47483 -30.98838 185.8623 -18.46961 13.78698 210.5607 -21.49532 8.98936 185.941 21.47847 8.989562 185.941 -15.38701 -0.005129933 188.3347 15.37016 -0.004969954 188.3348 -6.75985 5.95628 226.0962 -19.3355 12.47244 210.992 -8.13577 -0.005089998 225.7452 -1.23421 -0.005059957 228.0908 -0.00830996 9.959583 224.8453 17.88496 10.4642 213.5606 3.46709 5.95633 227.3319 1.2173 -0.00503993 228.0908 15.97012 12.39993 213.5357 10.52479 8.08447 223.6853 6.17142 8.188193 225.1135 18.30959 13.6839 210.6959 6.74287 5.95635 226.0962 17.12156 15.64486 209.2734 -3.48406 5.9563 227.3319 11.7382 -0.004989922 222.4602 -10.60663 7.42227 223.7478 5.95718 -0.005019903 226.9021 -5.97409 -0.005079925 226.9021 -0.008489966 5.95632 227.7518 -11.76637 7.98262 222.4723 -16.29367 12.62307 212.9111 -0.008529961 8.18816 226.6161 -10.08011 -0.005059957 224.2513 -17.75995 10.64507 213.6346 -6.18846 8.18812 225.1134 -16.56421 15.84821 208.9666 -11.75509 -0.005109906 222.4602 0.49007 13.58403 220.1232 11.60934 7.98279 222.6372 13.68506 14.29911 211.3139 15.56888 14.94498 209.9162 12.05915 14.15369 213.031 10.06319 -0.004999995 224.2513 -14.86134 13.86502 212.0578 -13.91902 14.26721 211.633 16.32755 15.88888 208.8843 15.13303 15.10267 208.1131 5.6449 14.28627 218.7978 14.31331 13.30281 213.8854 9.693613 11.31001 222.849 -9.71062 11.3099 222.849 -8.34798 13.16498 221.4855 14.46985 14.123 211.9805 -14.33889 13.31698 213.8898 -5.66194 14.28621 218.7978 -34.98714 16.48372 183.1409 -33.10577 12.07831 191.3992 34.53139 14.69207 192.9881 33.88874 20.98234 194.5057 32.41469 12.07866 193.3363 -34.1106 23.48006 183.1409 30.25814 21.87187 198.9264 -33.77184 22.3201 194.3907 21.85608 22.07732 193.141 21.5077 20.57482 193.141 23.13377 23.71641 201.67 -28.60559 23.35913 199.7737 24.55461 23.43409 201.7894 33.88875 15.98538 194.5058 15.59797 23.35947 198.696 -18.99684 24.95138 199.2961 -26.98518 11.01389 183.141 34.79623 22.32104 191.4061 22.85788 21.89442 183.141 -30.21933 22.3222 198.8859 -34.42173 22.51174 192.9438 34.983 20.98681 191.8221 34.96197 15.42036 191.4038 23.87253 24.13467 193.007 -27.23467 14.78579 192.907 25.57107 24.78537 199.4185 -25.79275 15.58531 191.141 23.03796 22.73579 192.9002 -34.88922 21.86153 183.1409 -32.84603 11.88464 186.1409 -25.58381 24.60102 183.141 -22.51073 15.58533 183.141 -34.43144 14.03747 192.9506 26.59187 23.15303 201.3888 23.33065 24.83233 199.8286 -34.2779 13.29147 191.4056 29.74393 10.96026 198.376 -23.89275 24.13781 193.0072 -30.61917 10.96507 191.6171 34.40472 22.51211 192.944 -23.93853 23.68398 192.6409 33.33868 13.29117 194.0602 -17.29799 23.95095 200.9552 28.25447 24.81621 197.3397 18.9806 24.83241 199.828 33.76669 22.32434 194.3975 -15.50301 16.01193 207.2098 15.79879 23.79947 193.0517 -22.86767 22.95523 193.0072 -32.11723 24.78397 192.5457 -29.2079 10.24129 196.066 -18.36642 24.93965 193.141 31.64711 11.23419 192.173 34.86427 15.97845 192.6572 -23.93228 24.8351 199.8356 16.44956 23.47284 200.9732 -22.88459 24.13721 201.208 21.49174 15.58557 193.141 34.57374 22.71798 183.141 -32.72465 24.58339 183.1409 16.12519 24.09111 199.5014 22.49384 15.58557 183.141 25.77583 15.58558 193.141 -34.67782 14.25417 186.1409 -16.127 24.11815 199.4553 33.79073 14.87376 194.428 -34.99195 15.41791 191.6172 -26.32878 24.97958 192.6354 -34.17892 20.98644 194.1828 22.47717 19.97113 192.6676 19.13892 8.90957 212.8358 31.19183 15.35321 197.9084 -21.50867 15.58534 193.141 -32.14261 14.30173 196.4264 -33.12226 12.36458 193.119 22.4581 21.41522 192.9022 32.11715 14.3039 196.4186 -34.98714 15.98502 185.9497 -25.04825 24.49428 192.6409 23.91961 23.68204 192.6405 27.44081 14.78608 191.641 -22.25968 19.97178 192.986 -29.67965 13.00989 199.7989 -32.04143 11.52369 192.4942 33.26425 12.18998 191.9951 26.57535 14.78608 183.141 30.00427 11.64074 196.8428 -29.81092 11.35786 198.0291 -33.37424 23.89329 193.2573 -30.50339 12.80341 197.7443 -23.08364 22.60834 192.6409 -33.74797 14.3105 194.368 28.41702 10.99705 193.6954 -25.79273 15.5853 183.141 -22.54487 21.34432 192.641 25.56682 24.60129 183.141 29.19439 10.89103 195.2594 30.98028 11.09095 186.141 -21.95733 21.40113 193.1557 -15.57331 23.22389 199.1776 -34.60375 15.97808 193.4542 34.5805 20.99011 193.4515 31.26432 14.32288 197.5403 -29.5855 11.27478 199.4863 -27.23466 14.78579 191.375 32.83066 11.88598 186.141 29.83044 11.42817 194.892 23.945 24.97985 198.6896 30.84862 12.283 195.854 21.12254 8.88795 193.1423 -34.82428 22.32404 191.4081 -31.17939 12.40927 195.6551 27.56345 10.9884 192.2909 27.21774 14.78604 192.907 10.59446 14.2863 212.6366 -25.76259 24.35805 200.5835 -23.34137 22.76534 183.141 34.27376 13.32267 192.1381 -30.99624 11.09043 186.1409 -27.01786 10.1081 193.7396 -25.20465 24.97959 192.9981 -34.98717 20.98197 191.3992 19.45186 12.02961 211.1126 -33.85997 23.85172 191.4055 -29.93584 11.48745 195.3008 34.97022 16.48409 183.141 -21.49532 8.989353 193.141 34.91357 15.23474 186.141 -26.13454 15.58531 193.0807 -28.13105 10.71403 194.175 30.32481 14.308 199.0056 -28.03135 10.9881 186.0626 26.96833 11.01418 183.141 27.11698 10.7317 193.5123 14.4827 14.55406 193.141 -27.91828 24.87933 197.0564 30.97259 24.97988 191.3993 -19.56074 9.16169 212.2155 27.47482 10.9884 185.8623 15.54012 22.73135 199.9994 32.70765 24.58374 183.141 33.34771 23.88522 193.2536 -17.63467 24.7285 199.5171 -27.1286 10.69656 193.53 0.004659891 14.05591 212.8021 26.31544 24.97986 192.639 -25.8333 10.16362 193.2869 -15.98162 23.93966 193.1003 -34.87456 20.98974 192.6554 32.35282 24.78691 191.8237 -28.63495 10.96214 193.9001 -31.22917 15.24397 197.8865 -15.23129 15.28555 193.141 25.02793 24.49245 192.6405 33.8424 23.85223 191.4054 25.18572 24.97985 193.0048 17.70369 24.81411 193.141 25.77583 15.58558 191.141 -27.20847 10.97332 192.9282 25.4867 10.31978 193.1829 29.69016 9.981653 197.5565 28.61198 10.50735 201.1697 28.15215 10.70991 194.1976 29.1267 9.989023 195.9577 -28.62002 11.02657 201.1763 -29.68514 9.980913 198.6928 -27.60927 -5.92986 194.2273 -29.27717 -5.93045 201.2351 -29.57054 -5.92983 198.2878 -26.23457 -5.9503 193.4912 -28.69948 -5.93367 195.3398 0.30526 0.005899906 213.1484 -21.49528 -0.005159974 193.141 11.52659 -0.05495995 202.7647 21.39854 -6.05413 193.6616 26.864 -0.004909992 203.2208 26.09085 -5.95029 193.4912 29.13345 -5.93044 201.4083 29.23282 -5.93372 196.7418 26.6949 -5.97775 203.1822 27.46555 -5.92985 194.2273 28.55576 -5.93366 195.3398 21.47848 -28.98956 185.941 -21.49532 -28.98937 185.941 -11.67031 -0.05495995 202.7647 -26.95345 -0.005189955 203.1901 -26.83862 -5.97777 203.1822 -21.54226 -6.05414 193.6616 -11.02435 -6.11725 201.9681 -27.0507 -19.99482 203.0668 -10.91088 -13.86543 201.6429 -11.23163 -20.04278 202.3254 -12.26285 -14.04643 203.0609 -10.97135 -0.05496984 198.8623 -10.84887 -20.04279 200.9014 -26.72174 -14.08801 203.1484 -21.54232 -14.07538 193.4641 -27.20847 -30.99855 192.9282 25.77584 -35.61081 191.141 17.7037 -44.83934 193.141 25.18573 -45.00508 193.0048 33.84242 -43.87745 191.4054 25.02794 -44.51768 192.6405 -15.23128 -35.31078 193.141 -31.22916 -35.26921 197.8865 -28.63494 -30.98738 193.9001 30.32481 -34.33322 199.0056 32.35283 -44.81213 191.8237 -34.87455 -41.01498 192.6554 -15.98161 -43.9649 193.1003 -29.81091 -31.3831 198.0291 -29.67964 -33.03514 199.7989 26.31545 -45.00509 192.639 0.004669964 -34.08114 212.8021 -27.12859 -30.72179 193.53 -17.63465 -44.75374 199.5171 30.25815 -41.89709 198.9264 33.34773 -43.91044 193.2536 32.70767 -44.60896 183.141 -28.20184 -44.24278 198.9098 15.54013 -42.75657 199.9994 30.9726 -45.00511 191.3993 -27.91827 -44.90458 197.0564 14.48271 -34.57928 193.141 -28.03135 -31.01334 186.0626 31.26433 -34.34811 197.5403 -26.13453 -35.61054 193.0807 34.91357 -35.25996 186.141 34.97023 -36.5093 183.141 -29.93584 -31.51268 195.3008 -33.85996 -43.87696 191.4055 19.45187 -32.05484 211.1126 -34.98717 -41.00721 191.3992 -25.20464 -45.00482 192.9981 -30.99623 -31.11567 186.1409 -30.50338 -32.82864 197.7443 34.27377 -33.34789 192.1381 -23.34136 -42.79058 183.141 -25.76258 -44.38329 200.5835 10.59447 -34.31153 212.6366 27.21775 -34.81126 192.907 -31.17938 -32.4345 195.6551 -34.82426 -42.34929 191.4081 30.84863 -32.30822 195.854 23.94501 -45.00507 198.6896 29.83044 -31.45339 194.892 32.83066 -31.9112 186.141 -27.23465 -34.81103 191.375 34.58051 -41.01534 193.4515 -34.60375 -36.00331 193.4542 -15.5733 -43.24913 199.1776 -21.95732 -41.42637 193.1557 30.98029 -31.11618 186.141 29.19439 -30.91626 195.2594 32.11715 -34.32912 196.4186 25.56683 -44.62652 183.141 -22.54486 -41.36955 192.641 -25.79273 -35.61053 183.141 28.41703 -31.02227 193.6954 -33.74796 -34.33574 194.368 -23.08363 -42.63358 192.6409 -33.37422 -43.91854 193.2573 30.00428 -31.66597 196.8428 26.57535 -34.8113 183.141 33.26425 -32.2152 191.9951 -32.04143 -31.54894 192.4942 -22.25967 -39.99702 192.986 27.44082 -34.81131 191.641 23.91962 -43.70727 192.6405 23.13378 -43.74164 201.67 -25.04824 -44.51952 192.6409 -34.98713 -36.01025 185.9497 22.45811 -41.44044 192.9022 -33.12226 -32.38982 193.119 -32.1426 -34.32697 196.4264 31.19184 -35.37843 197.9084 22.47717 -39.99635 192.6676 -34.1789 -41.01167 194.1828 -26.32877 -45.00481 192.6354 -34.99195 -35.44315 191.6172 33.79074 -34.89899 194.428 -16.12698 -44.14339 199.4553 -34.67781 -34.2794 186.1409 25.77583 -35.61081 193.141 22.49384 -35.61079 183.141 16.12521 -44.11633 199.5014 -32.72463 -44.60863 183.1409 34.57375 -42.7432 183.141 -22.88458 -44.16245 201.208 16.44957 -43.49807 200.9732 -23.93227 -44.86033 199.8356 34.86427 -36.00367 192.6572 31.64712 -31.2594 192.173 -18.36641 -44.96488 193.141 -32.11722 -44.8092 192.5457 -22.86766 -42.98047 193.0072 15.7988 -43.82469 193.0517 -15.503 -36.03717 207.2098 26.59188 -43.17825 201.3888 33.76669 -42.34956 194.3975 18.98061 -44.85764 199.828 28.25448 -44.84144 197.3397 -17.29797 -43.97618 200.9552 33.33868 -33.3164 194.0602 -23.93851 -43.70922 192.6409 34.40473 -42.53733 192.944 -30.61916 -30.9903 191.6171 -23.89274 -44.16305 193.0072 -34.27789 -33.31671 191.4056 33.88875 -36.0106 194.5058 23.33066 -44.85756 199.8286 26.64597 -44.28524 200.1048 -34.43144 -34.06271 192.9506 -22.51072 -35.61057 183.141 -25.5838 -44.62625 183.141 -32.84603 -31.90988 186.1409 -34.88921 -41.88677 183.1409 23.03797 -42.76101 192.9002 -25.79275 -35.61054 191.141 -27.23466 -34.81103 192.907 23.87254 -44.15989 193.007 34.96198 -35.44559 191.4038 34.98302 -41.01204 191.8221 -34.42172 -42.53698 192.9438 -30.21932 -42.34743 198.8859 22.85789 -41.91965 183.141 34.79625 -42.34627 191.4061 -26.98517 -31.03913 183.141 -18.99683 -44.97661 199.2961 15.59798 -43.3847 198.696 -28.60558 -43.38437 199.7737 21.50771 -40.60004 193.141 21.85609 -42.10255 193.141 -33.77182 -42.34534 194.3907 -34.1106 -43.50529 183.1409 32.4147 -32.10388 193.3363 33.88876 -41.00756 194.5057 34.53139 -34.7173 192.9881 -33.10577 -32.10356 191.3992 -34.98714 -36.50895 183.1409 -5.66193 -34.31144 218.7978 -14.33888 -33.34222 213.8898 14.46985 -34.14823 211.9805 5.64491 -34.3115 218.7978 -8.34797 -33.19022 221.4855 -9.71062 -31.33514 222.849 9.69362 -31.33524 222.849 14.31332 -33.32804 213.8854 15.13304 -35.1279 208.1131 16.32756 -35.91411 208.8843 -13.91902 -34.29244 211.633 -14.86134 -33.89025 212.0578 12.05916 -34.17892 213.031 15.56889 -34.9702 209.9162 13.68507 -34.32434 211.3139 0.49008 -33.60926 220.1232 -16.5642 -35.87345 208.9666 -6.18845 -28.21336 225.1134 -17.75994 -30.6703 213.6346 -0.008519947 -28.21339 226.6161 -16.29366 -32.64831 212.9111 -0.008489966 -25.98155 227.7518 -10.60662 -27.4475 223.7478 -3.48405 -25.98153 227.3319 17.12157 -35.67009 209.2734 6.74288 -25.98158 226.0962 18.3096 -33.70912 210.6959 6.17142 -28.21342 225.1135 10.5248 -28.1097 223.6853 15.97012 -32.42515 213.5357 3.46709 -25.98156 227.3319 17.88497 -30.48943 213.5606 -0.008299946 -29.98481 224.8453 -19.33549 -32.49768 210.992 -6.75984 -25.98152 226.0962 -18.4696 -33.81222 210.5607 + + + + + + + + + + 0.01561552 0.9998533 -0.007047474 -9.83374e-4 0.9999992 -8.28155e-4 0.0179196 0.9998139 -0.007163643 -0.007168531 0.9999681 0.003523528 0.9430803 0.01013004 -0.3324108 0.9003587 0.01549392 -0.4348724 0.8726164 0.01240891 -0.4882485 -0.009253084 0.01497787 -0.9998451 0.4717823 -8.03786e-4 -0.8817148 0.2070965 0.03782767 -0.9775889 0.5514918 0.02437365 -0.8338242 0.7138675 0.03087198 -0.6996 0.2803763 0.01563024 -0.9597629 0.006108462 0.01884508 -0.9998038 4.5718e-6 0.9999929 0.00380212 -0.07373255 4.01605e-7 -0.9972781 -0.3711361 0.01462346 -0.9284633 -0.4718902 0.009450912 -0.8816067 -0.3568481 0.00298798 -0.9341576 -0.01830124 0.01230752 -0.9997568 -0.0732674 1.48331e-4 -0.9973124 -0.7139815 0.02471327 -0.6997284 -0.8684197 0.005056619 -0.4958041 -0.9588694 0.01751494 -0.283307 -0.937036 -0.02975642 -0.347963 0.002332031 0.9999969 -0.001030385 0.002692818 0.9999962 -7.23134e-4 0.00100547 0.9999967 -0.002405107 -0.00285989 0.9999933 -0.002279937 0.7823848 0.001180171 0.6227942 -5.38646e-4 0.9999998 -5.09263e-4 -4.01403e-4 0.9999997 -6.29528e-4 -1.76652e-4 0.9999998 -7.22099e-4 7.78423e-6 0.9999998 -7.33227e-4 1.83785e-4 0.9999997 -7.1537e-4 3.47216e-4 0.9999998 -6.40118e-4 4.2929e-4 0.9999998 -5.85633e-4 5.45349e-4 0.9999998 -4.78294e-4 -0.7963042 0.002041757 0.6048931 -0.7663735 -0.06200253 0.6393962 0.9556614 0.04262202 0.2913672 0.9821822 0.01345783 0.1874488 -0.8685721 0.004554927 0.4955421 -0.9838455 0.002532005 -0.179002 -0.9407939 0.01547765 0.3386259 -0.980711 0.04160088 0.1909852 0.03443318 0.9993918 -0.00551629 0.06774985 0.9957424 0.06250667 0.002877116 0.9999958 -2.34614e-4 -0.006032586 0.00586915 0.9999647 -0.05306607 -0.1125792 0.9922248 0.6086811 -0.0421673 0.7922937 0.7361648 0.06695115 0.6734828 -0.9654965 -0.02146059 0.2595301 -0.7207093 0.03904652 0.6921369 -0.9998136 0.007922708 0.01760703 -0.05492252 0.9984904 7.58672e-4 0.920313 -0.220179 -0.3233347 0.8972351 0.3114074 0.3130409 0.7861373 -0.001013457 0.6180511 0.003188788 -0.9999918 0.002502799 -0.003045499 -0.9999921 0.002569794 -0.00465238 -0.9999889 8.33297e-4 -0.02951377 -0.9994115 -0.01748067 -0.7705227 -0.5248699 0.3616716 5.11691e-6 -0.257188 -0.9663615 1.24225e-6 -0.2571765 -0.9663645 0.9985636 0.02016961 0.04963934 -4.69601e-6 0.9999005 0.01410865 -0.07368081 -3.12358e-7 -0.997282 -0.03583323 -0.02026367 -0.9991524 0.4249283 -0.02359986 -0.9049193 -0.3710723 -0.01455062 -0.92849 -0.472149 -0.009394407 -0.8814687 -0.3568308 -0.002956986 -0.9341644 -1 -4.24114e-6 0 0.7138376 -0.03070336 -0.6996379 0.5515098 -0.02424395 -0.8338161 0.2070288 -0.03762084 -0.9776113 0.4720516 8.22893e-4 -0.8815706 0.001894712 0.9998987 0.01411074 -0.2355772 0.9105972 0.3395823 -5.38076e-4 -0.9999998 -5.08822e-4 -4.01263e-4 -0.9999997 -6.29058e-4 -1.76679e-4 -0.9999998 -7.2135e-4 8.17477e-6 -0.9999997 -7.32632e-4 1.83417e-4 -0.9999997 -7.14577e-4 3.471e-4 -0.9999998 -6.39847e-4 4.32299e-4 -0.9999998 -5.82755e-4 5.42617e-4 -0.9999998 -4.79558e-4 -0.73538 0.322638 0.5959203 -0.7120482 0.3725554 0.5951384 -0.6078385 0.6282297 0.4856539 -0.48342 0.7671771 0.4215977 -0.5388346 0.7187522 0.4393776 -0.2852668 0.9011696 0.3263683 -0.2129948 0.9589554 0.1871842 -0.02202355 0.999601 -0.01768767 0.01704108 0.9996063 -0.02229034 0.1863371 0.896737 0.4014243 0.07409763 0.9954727 0.05953019 0.2531335 0.9318023 0.260131 0.5006238 0.753816 0.4256023 0.6172994 0.6169198 0.4882124 0.2999255 0.8867565 0.351721 0.7286733 0.3009263 0.6152061 0.7174099 0.3757179 0.5866508 0.7168346 0.2806226 0.6382783 0.520361 0.5283061 0.6709077 0.523715 0.5266789 0.6695759 0.5033223 0.7778653 0.3762877 0.3692883 0.7789661 0.5067921 -0.1229239 0.8053518 0.5799122 0.3813698 0.6829724 0.6229814 -0.741412 -0.007068693 0.6710129 -0.7303746 -0.002066254 0.6830437 -0.471109 0.05690366 0.8802376 -0.3518304 0.07971221 0.9326636 -0.243121 0.03165817 0.9694792 -0.1195573 0.08084994 0.9895299 0 0.05677258 0.9983872 0.7303774 0.006114065 0.6830164 0.694662 -0.004732429 0.7193207 -0.7261114 0.2812638 0.6274177 -0.4371832 0.5765635 0.6902503 -0.4955929 0.5476281 0.6741597 -0.4707143 0.799388 0.3733726 -0.2689011 0.7365325 0.6206546 -0.2763309 0.7346469 0.6196251 -0.7963036 -0.002040565 0.6048938 -0.7663729 0.06200355 0.6393969 -0.6317504 0.3098716 0.7105429 0.4704322 0.3900039 0.7915747 0.3753774 0.4616464 0.8037253 0.6691301 0.3433059 0.6590948 -0.5017848 0.06503021 0.8625445 -0.3340008 0.4501765 0.8281211 -0.3153828 0.4489123 0.8360691 -0.1954229 0.5620726 0.8036692 -0.1070548 0.4509173 0.8861225 0.1070474 0.4509207 0.8861216 0.1954076 0.5620625 0.8036802 0.3153811 0.4488871 0.8360834 0.2884777 0.4467479 0.8468748 0.2431266 0.03166055 0.9694777 0.1195609 0.08085137 0.9895293 0.5421731 0.02782279 0.8398061 0.5179169 0.04720693 0.8541274 0.351823 0.07971644 0.9326661 -0.5526021 0.3217239 0.7688463 -0.3655399 0.4986488 0.7859581 -0.6772923 0.5526573 0.4856389 -0.2271692 0.9638545 0.1392075 -0.6307378 0.7448603 0.2176074 -0.07914316 0.7638497 0.6405232 0.05340451 0.9894914 0.1343678 0.0830931 0.9832947 0.1619484 0.2885079 0.921459 0.2601472 -0.08982717 0.8150457 0.5723913 0.8337591 0.3971052 0.3836059 0.7008895 0.5337672 0.4731242 -0.07362639 0.9393897 0.3348526 -0.6092302 0.01056563 0.7929231 -0.02864557 -0.06671625 -0.9973607 -0.01899331 -0.01468348 -0.9997118 -0.07170587 -0.1221694 -0.9899156 -0.9992634 0.01644247 -0.03467571 -0.9892613 0.1411869 0.03779631 0.01059871 0.9984721 0.05423283 -0.02160245 0.9997224 0.009422302 0.02458703 0.9987548 0.04341065 0.5879015 -0.8089326 3.66184e-6 0.9503999 -0.3110228 0.002229988 0.8465853 -0.5265705 -0.07756859 0.7476761 -0.6637343 -0.02091056 0.5093628 -0.8605239 0.006959497 0.3946705 -0.9185638 -0.0218169 0.4849303 -0.8745529 2.15127e-6 -0.1596977 9.15928e-4 -0.9871655 2.62161e-5 -1.92937e-4 -1 -0.02109515 -0.02395379 -0.9994905 5.41095e-6 -0.007953941 -0.9999685 0 0 -1 -0.02604895 -0.03952682 -0.998879 -0.01878607 0.0265699 -0.9994705 0.05621528 -0.01764327 -0.9982628 -0.01577299 0.003093779 -0.9998708 0.004353761 -0.004326999 -0.9999812 2.9628e-5 -2.98508e-5 -1 -5.97265e-6 -2.32931e-4 -1 -3.49237e-6 0 -1 0.06948161 -0.02334308 -0.9973102 0.05688816 -0.06188285 -0.9964609 -0.149518 0.1477029 -0.9776647 0.02101701 0.02193903 -0.9995384 0.02149832 0.01863515 -0.9995953 -0.01842051 -0.01221692 -0.9997557 -0.07321709 -1.48202e-4 -0.997316 0.01302427 -0.03728014 -0.9992201 0.1754911 -0.02767938 -0.9840918 -0.5018509 0.8648977 -0.009893178 0.08127123 -0.07713711 -0.9937026 0.4938455 -0.8651844 0.08702135 0.9576157 -0.2497935 0.1434417 0.9996075 0.0161854 0.02287256 0.002379298 0.9999973 9.94546e-7 1.09931e-5 9.98728e-7 -1 2.9185e-6 -1.18877e-4 -1 1.13283e-5 -2.95498e-6 -1 1.94274e-5 -1.88479e-5 -1 1.00795e-5 1.31849e-5 -1 1.018e-5 -4.62368e-6 -1 9.84221e-6 -1.6866e-7 -1 0.3747807 0.9270318 -0.01231205 0.1591798 0.9871444 0.01442277 0.3863968 0.9221749 -0.01706165 0.999954 -0.003096759 -0.00908643 0.9997152 -0.02175867 0.009814977 0.997394 0.06343418 -0.03437125 -0.936868 -0.02874648 -0.3485 -0.9829717 -0.06138265 -0.1732013 6.28868e-6 -1 1.39816e-6 6.37632e-6 -1 1.69668e-6 9.29848e-6 -1 2.32462e-7 -0.411606 -0.8475078 -0.3351284 -0.3163666 -0.3705716 -0.8732634 2.44869e-6 -1 0 -0.1916322 -0.9783129 0.0786184 2.56887e-6 -1 1.86827e-7 0.3608216 0.8531318 0.3767942 0.06977778 0.8842558 0.4617605 -0.3635968 -0.9315491 0.003710746 -0.3945259 -0.9188822 -0.002241134 -0.4696127 -0.8828235 0.009317815 -0.7191555 -0.6947782 -0.009934186 -0.7901011 -0.6107949 -0.05167198 -0.9474853 -0.3195125 0.01354765 -0.9838739 -0.1778907 -0.01863515 -0.0548895 -0.9984923 7.56458e-4 0.01396352 -0.9998953 -0.003825962 -0.4694667 0.8828023 -0.01616048 -0.2559659 0.9655795 0.04623579 0.9999764 0.006870687 6.22494e-6 0.2503749 -0.003657698 -0.9681421 0.763278 0.6458025 -0.01860147 -0.2727189 0.8640754 0.4230818 0.2152742 -0.9685378 -0.1248667 0.05919623 -0.9978007 -0.02983027 0.06005632 -0.9981946 -8.2818e-4 0.02759218 -0.9994053 0.02068221 -0.03444087 -0.9994049 0.00197637 0.01151961 -0.9996533 -0.0236774 0.004373311 -0.9999776 -0.005082786 0.9994055 0.02954089 0.0177769 0.9946824 0.08597451 -0.05670303 -0.568115 -0.795584 -0.2104555 -0.5583503 -0.8168305 -0.1450276 -0.9998291 0.01820641 0.003232419 -0.999854 0.01707386 8.59636e-4 -0.9999301 3.94797e-4 -0.01181763 0.4772557 -0.8143917 -0.3301413 0.5607668 -0.8203443 -0.1121422 -0.00246793 0.9997731 -0.02116316 -0.03393405 0.9993694 0.01046085 -0.03308695 0.9985523 -0.04241055 0.005249023 0.9995884 0.02820628 -0.006562709 0.9997723 0.02031064 -0.007406949 0.9999691 -0.002665102 -0.01351153 0.9986205 -0.05074167 0.002455651 0.9991959 -0.04001909 2.37993e-5 1 8.81335e-5 -0.02211898 0.9997543 0.001488208 -0.03124815 0.9994884 -0.006819605 -5.61348e-6 1 -8.64025e-7 3.53451e-7 0 -1 -9.37535e-6 0 -1 4.60591e-6 0 -1 1.03512e-6 0 -1 -0.4849405 -0.8745471 0 -0.4138299 -0.9074271 -0.07294458 -0.4434108 -0.8951808 0.04514765 -0.9925606 -0.1034097 0.06426614 -0.9947476 -0.01479196 0.1012839 0.07096368 0.9917967 0.1063174 0.04890638 0.9868294 0.1541952 0.1234307 0.8427708 0.5239298 0.1143648 0.841211 0.528474 0.219567 0.8041195 0.552433 0.3604821 0.8014485 0.4772137 0.5655164 0.6549519 0.5012278 -0.8274569 0.5226513 0.2053067 -0.5280175 0.8407658 0.1196261 -0.7690887 0.4900162 0.4103495 -0.8873252 0.1838574 0.4229074 -0.8899116 0.2083881 0.4057484 -0.8040372 0.5778281 0.1401391 -0.9593175 0.2694405 0.08433115 -0.9642212 0.1154479 0.2386404 -0.8688678 -0.1330495 0.4768297 -0.8676385 -0.4969342 0.01612305 -0.9044708 -0.4103116 0.116521 -0.9175149 -0.1181952 0.379732 -0.2441689 -0.8989203 -0.3637636 -0.6721805 -0.6307423 -0.3877339 -0.5974522 -0.8018327 -0.01073169 -0.9882476 -0.01705551 0.1519078 -0.9642937 -0.1811885 -0.1931539 -0.8705127 -0.348563 0.347436 -0.7695573 -0.5342514 0.3497957 -0.81971 -0.08346235 0.5666653 -0.8681145 -0.1954786 0.4562517 -0.7247098 -0.5218476 0.4499677 -0.5606065 -0.8176971 0.1307356 -0.7146515 -0.691065 0.1081783 -0.7804269 -0.589892 0.2072712 -0.9442567 -0.3232704 0.06225353 -0.9572325 -0.1493089 0.2478163 0.8360711 1.33197e-5 0.5486212 0.8841178 -0.02389752 0.4666528 0.9706866 0.01696532 0.2397498 0.9965743 -0.009937644 0.08210355 -0.6227433 0.7822567 -0.01629316 -0.9011184 0.4335024 0.007832765 -0.8454152 0.5336051 -0.02321231 -0.9927151 0.1204811 0.001057386 -0.4778087 0.8783803 0.01212602 0.9543956 -0.2649516 0.1375851 0.5125366 -0.8194128 0.2566494 0.6355918 -0.690502 0.3452972 0.6859034 -0.6520827 0.3229935 0.8263667 -0.4009248 0.3954462 0.8176549 -0.3412975 0.4636341 0.8785032 -0.1076066 0.4654601 0.8788756 -0.109982 0.4641999 0.9640756 -0.206492 0.1670908 0.7789077 0.1204649 0.6154601 0.6247628 0.5636731 0.5403186 0.1967519 0.8852924 0.4213624 0.6079871 0.655305 0.448249 0.1140219 0.9902958 0.0794565 0.05424469 0.9971574 0.05229395 7.63476e-7 0.9917173 0.1284403 -5.57107e-5 0.855217 0.5182702 0.6628006 -0.4888523 -0.5672027 0.4250437 -0.8640182 -0.2698344 0.5050352 -0.8071358 -0.3057305 0.6443608 -0.7647176 -0.002474963 0.6346895 -0.7716925 0.04074215 0.7714651 -0.5656436 0.2913568 0.6992948 -0.4688475 0.5396007 0.8350618 -0.1320554 0.5340725 0.9077774 -0.4182678 -0.03150045 0.8182771 -0.2402003 0.5222321 0.8979862 -0.3095173 -0.3127618 0.892437 -0.4486555 -0.04758852 0.92031 0.2202008 -0.3233284 0.8972207 -0.3114482 0.313042 0.7846387 -0.1588892 0.5992466 0.2363368 -0.8919925 -0.3853499 -0.7970869 -0.02018803 0.6035272 -0.7675027 0.01902532 0.6407633 -0.7661004 0.01858872 0.6424521 -0.7700661 0.03111505 0.6372049 -0.7724037 0.01748228 0.6348912 0.02658361 0.899107 0.4369211 -0.01884251 0.9989008 0.04292184 -0.3006139 0.06971323 -0.9511948 -0.3598193 0.1449738 -0.9216901 -0.6508402 0.4357442 -0.6217188 -0.4024789 0.5504338 -0.7314598 -0.4052345 0.6278684 -0.6645046 -0.3334318 0.2679589 -0.9038923 -0.2578296 0.1117492 -0.9597063 -0.2392701 0.6298083 -0.73898 0.990478 0.1145869 -0.07631158 0.9814518 0.1645613 -0.09834754 0.5533722 0.8221759 0.1334404 0.8393178 0.5229089 0.1487008 0.9577251 0.1842736 0.2209207 0.9500852 0.2060413 0.2342758 0.7672755 0.500145 0.4014268 0.7974837 0.5680521 0.2033138 0.8042327 0.2694952 0.5297001 0.9039701 0.115408 0.4117271 0.7761536 -0.111862 0.6205422 0.7647511 -0.3449332 0.5442214 0.6236506 -0.5473755 0.5580683 0.5836703 -0.6952409 0.4194869 0.423861 -0.8426687 0.3320413 0.4037796 -0.8530196 0.3306353 0.1520934 -0.9734494 0.1710667 0.9802788 0.1901723 -0.05374163 0.9197636 0.3920379 -0.01847422 0.7828142 0.6221591 -0.01095563 0.6330473 0.7733222 -0.03498685 0.5895365 0.8073804 -0.02416431 0.3544063 0.9350436 -0.009473919 -0.5067823 -0.3723047 -0.7775353 -0.2469734 -0.8998813 -0.3594689 -0.2498766 -0.8918724 -0.376995 0.7756012 0.009838342 0.6311467 0.7748757 0.01344811 0.6319707 0.7782664 0.01343435 0.6277906 0.7822631 0.01479077 0.6227727 0.7727896 1.38788e-5 0.6346625 -0.9959989 0.004353165 0.08926069 -0.9770304 -0.01896309 0.2122547 -0.9099169 0.01688849 0.4144468 0.6010963 0.285396 0.74648 0.06548047 0.649806 0.7572744 0.2335387 0.5700045 0.7877528 0.9909892 0.1323928 -0.02031874 0.8487841 0.5287336 0.002544105 0.143653 0.9894773 -0.01728206 0.5318949 0.8468082 0.001921951 0.7066237 0.7067496 -0.03446674 -0.9991282 -0.006493687 -0.04123902 -0.3540402 0.9351833 -0.009369313 -0.5900734 0.806986 -0.02422761 -0.705804 0.7063435 -0.05403476 -0.7369824 0.6744424 -0.04454702 -0.9154844 0.4019613 -0.01776158 -0.4381065 0.001401245 -0.898922 -0.5948804 0.2809926 0.7531007 -0.3912907 0.474345 0.788599 -0.1161795 0.6381697 0.7610795 -0.7994903 -0.08438038 0.5947229 -0.7754129 -0.1842107 0.6039879 -0.6629921 -0.5435766 0.5147485 -0.6602965 -0.5461651 0.5154729 -0.4397987 -0.8264575 0.3514901 -0.4887438 -0.7963126 0.3563928 -0.2597916 -0.948232 0.182659 -0.2017438 -0.9638398 0.1741042 -0.3998326 0.8392901 0.3684103 -0.1537533 0.9595644 0.2357882 -0.0354377 0.8796215 0.4743524 -0.8192392 0.5732416 0.01553893 -0.9991894 0.02178466 -0.03385227 -0.7931811 0.4790177 0.3760396 -0.8798047 0.442303 0.1741027 0.8508662 0.5253615 0.004709303 0.6052916 0.586708 0.5379554 0.6608806 -0.05089694 -0.7487632 0.6208562 0.2645697 -0.7379299 0.6541627 0.3175907 -0.6864455 0.5396941 0.4289317 -0.7243949 0.5600119 0.4854119 -0.671388 0.4017937 0.5502665 -0.7319622 0.4044627 0.6230685 -0.6694743 0.2398301 0.6244189 -0.743359 -0.9755337 0.2197839 0.005385875 -0.9933806 0.05732041 -0.09954684 -0.7767203 0.1414058 0.6137671 -0.6457282 0.5682321 0.5100466 -0.655591 0.5434229 0.5243015 -0.3957766 0.845305 0.3589156 -0.4101067 0.8362125 0.3640896 0.9156996 -0.2218957 0.3350471 0.7881427 -0.1518562 0.5964654 0.2319261 -0.1492663 -0.9612128 0.8726262 -0.01234394 -0.4882329 0.9003875 -0.01541072 -0.4348161 0.9430808 -0.01008367 -0.332411 0.9556811 -0.0423755 0.2913385 0.9992616 0.032009 0.02125591 -0.8655185 0.03527402 0.4996334 -0.7139762 -0.02458065 -0.6997385 -0.8684329 -0.005037248 -0.4957812 -0.9588723 -0.01742041 -0.283303 -0.9838462 -0.002529859 -0.1789985 -0.9950361 -0.00968796 0.09904223 -0.9912891 -0.004385292 0.1316314 -0.006805241 -0.9999716 0.003245055 0.009081721 -0.999953 -0.00339955 0.02289599 -0.9995089 0.02139681 -0.003095984 -0.9999951 6.3684e-4 0.01654303 -0.9998555 -0.003924548 0.01694923 -0.9998489 -0.003889501 -0.3648713 -2.32697e-7 -0.9310581 -0.02970188 -0.005619406 0.999543 -0.07490563 -0.1220666 0.9896913 0.6197327 -0.01931172 0.7845754 0.5883926 -0.02188336 0.8082793 0.999951 -2.34747e-4 0.009894788 -0.9181715 -5.32592e-7 -0.3961832 -0.9810655 0.0814464 0.1757188 -0.9990285 0.01286119 0.04215216 0.9999437 3.20412e-7 0.01061564 -0.3648695 0 -0.9310587 0.002380132 -0.9999972 0 -1 5.65485e-6 0 -4.43723e-6 -0.9999005 0.01411229 0.9985735 -0.01968896 0.04963397 8.95525e-7 0.2571764 -0.9663645 5.1169e-6 0.2571879 -0.9663615 0.3648553 0 -0.9310643 -1 0 6.88764e-6 -0.9996351 -0.006514608 -0.02621853 0.9990285 0.01286178 0.04215323 0.9810658 0.08144563 0.1757177 0.9221678 4.01184e-7 -0.3867903 -0.9999833 1.49927e-4 -0.005787253 -0.9999031 0.008701324 0.01087605 -0.6240751 -0.01303207 0.7812559 0.0342608 -0.08595836 -0.9957095 -0.6197327 -0.01931256 0.7845754 0.07490497 -0.1220666 0.9896914 0.02782058 -7.8799e-4 0.9996127 0.364862 1.74527e-7 -0.9310616 -0.01694965 -0.9998488 -0.003890633 -0.01624745 -0.9998602 -0.003951251 -3.73537e-4 -1 -1.7318e-4 -0.02289587 -0.9995089 0.02139723 -0.009080529 -0.9999531 -0.003400564 0.006906628 -0.9999706 0.003343224 0.9998136 0.007922589 0.01760774 0.7207027 0.03904807 0.6921437 0.9655002 -0.02145862 0.2595167 -0.7367969 0.03170281 0.6753705 -0.6086808 -0.04216694 0.7922939 0.04616856 -0.1137907 0.9924315 0.006091892 -0.01415282 0.9998814 -0.002877116 0.9999959 -2.34832e-4 -0.06774985 0.9957424 0.06250584 -0.03443318 0.9993919 -0.005516827 -0.005532741 0.9999846 -3.11838e-4 0.9401224 -0.0288853 -0.3396108 -0.01791948 0.9998138 -0.007163763 0.003006219 0.9999954 -5.59963e-4 -0.01561576 0.9998533 -0.007047951 -0.00665456 0.05444574 -0.9984946 -0.7809695 0.004064798 0.624556 -0.7851648 0.005571246 0.6192618 -0.6859233 0.02910339 0.7270916 -0.7851656 -0.00557214 0.6192607 -0.003186404 -0.9999918 0.002517282 0.002876639 -0.9999927 0.002543389 0.004396855 -0.9999901 7.90079e-4 0.002737402 -0.9999941 0.00209999 5.21896e-6 -0.9999889 -0.004736304 0.002923846 0.9999931 -0.002302467 -9.41666e-4 0.9999967 -0.002402782 -0.002547204 0.9999966 -6.90574e-4 -0.01241379 0.9998887 0.008295118 -0.09635287 0.7400428 0.6656221 -0.09785389 0.7200407 0.6869979 0.1229031 0.630445 0.7664425 0.05083739 0.87742 0.477022 0.05550712 0.7045406 0.7074896 -0.07282197 0.6513915 0.7552391 0.1010162 0.9932321 0.05732083 -0.1165456 0.9906029 0.07157623 0.0182901 0.9161313 0.400461 0.05686694 0.7890757 0.6116582 0.01517885 0.7924019 0.6098105 0.03442543 0.8215216 0.5691373 -0.1216966 0.5496576 0.8264784 0.1066866 0.5021322 0.8581848 0.004188001 0.5902419 0.8072156 -0.3277313 0.2838617 0.9011186 0.3029007 0.3115628 0.9006553 0.1694651 0.6967463 0.6970124 -0.169481 0.696765 0.6969898 -0.1157587 0.7179153 0.6864384 -0.798479 0.4406887 0.410152 -0.7984801 -0.4406876 0.4101511 -0.1157594 -0.7179127 0.686441 -0.1694784 -0.6967654 0.69699 0.1694658 -0.6967464 0.6970121 0.3029071 -0.3115618 0.9006535 -0.3277247 -0.2838609 0.9011212 0.004183411 -0.5902422 0.8072155 0.1066867 -0.5021319 0.8581851 -0.1216967 -0.5496581 0.8264781 0.03442543 -0.8215218 0.569137 0.01517879 -0.792401 0.6098119 0.05686688 -0.7890751 0.6116589 0.01828736 -0.9161332 0.4004566 -0.1165456 -0.9906029 0.07157582 0.1010162 -0.9932321 0.05732148 -0.07281565 -0.6513924 0.755239 0.0555076 -0.7045409 0.7074893 0.05084019 -0.8774212 0.4770193 0.1229027 -0.6304432 0.766444 -0.09785425 -0.7200406 0.686998 -0.09635329 -0.7400448 0.6656199 0.2317361 0.1483667 -0.9613979 0.7881434 0.15186 0.5964634 -0.3167011 -0.9075972 0.2756226 -0.4140712 -0.8482246 0.3302423 -0.5395525 -0.7096875 0.4530196 -0.6555927 -0.5434225 0.5242998 -0.6457279 -0.5682289 0.5100505 -0.776723 -0.1414021 0.6137645 -0.9933947 -0.05732291 -0.0994032 -0.9758101 -0.21856 0.005127072 0.2398105 -0.6244221 -0.7433626 0.4044717 -0.6230846 -0.6694537 0.4018092 -0.550262 -0.7319571 0.5600175 -0.4854167 -0.6713799 0.5396963 -0.4289281 -0.7243953 0.6541643 -0.3175924 -0.6864432 0.6208423 -0.2645666 -0.7379427 0.6608842 0.05089545 -0.7487602 0.605291 -0.5867071 0.5379568 0.8508697 -0.5253557 0.004708409 -0.8797973 -0.4423131 0.1741145 -0.7931867 -0.4790179 0.3760278 -0.9991895 -0.02178269 -0.03385305 -0.8192293 -0.5732556 0.01553922 -0.03543365 -0.8796225 0.4743509 -0.1537479 -0.9595668 0.235782 -0.2527154 -0.9227926 0.2908416 -0.4116985 -0.7353618 0.5382819 -0.2017378 0.9638411 0.1741042 -0.2598019 0.9482291 0.1826599 -0.4887523 0.7963092 0.3563887 -0.4397916 0.8264623 0.3514876 -0.6602929 0.5461685 0.515474 -0.6629944 0.5435734 0.514749 -0.7754171 0.1842058 0.603984 -0.7994899 0.08438801 0.5947225 -0.1161795 -0.6381701 0.7610791 -0.3912903 -0.4743452 0.7885991 -0.5947979 -0.2807018 0.7532742 -0.4381141 -0.001394927 -0.8989183 -0.9154844 -0.4019613 -0.01776087 -0.7369866 -0.6744379 -0.04454606 -0.7058036 -0.7063439 -0.05403476 -0.5900745 -0.8069853 -0.02422738 -0.354041 -0.9351831 -0.009369909 -0.9991283 0.006489396 -0.04123884 0.7066251 -0.7067482 -0.0344668 0.5318939 -0.8468089 0.001921832 0.1436579 -0.9894766 -0.01728206 0.8487824 -0.5287364 0.002543389 0.9909892 -0.1323919 -0.02031975 0.1629773 -0.6154218 0.7711644 0.6002393 -0.2721695 0.7520882 -0.9099137 -0.01689112 0.4144537 -0.9770304 0.01896232 0.2122544 -0.9959983 -0.004354298 0.08926653 0.7727872 -1.17436e-5 0.6346653 0.7822638 -0.01479077 0.6227717 0.7782727 -0.0134325 0.6277828 0.7748641 -0.0134468 0.6319847 0.7756067 -0.009769678 0.6311409 -0.2498764 0.8918737 -0.3769922 -0.2545314 0.8776582 -0.4061159 -0.5030127 0.3592442 -0.78608 0.3544009 -0.9350457 -0.009474277 0.589532 -0.8073836 -0.02416473 0.6330451 -0.7733238 -0.03498852 0.7828165 -0.6221563 -0.01095533 0.9197658 -0.3920325 -0.01847434 0.9802774 -0.1901789 -0.05374157 0.1520909 0.9734491 0.1710709 0.4037771 0.8530201 0.3306369 0.4238623 0.8426662 0.3320458 0.5836796 0.695232 0.4194886 0.6236494 0.5473738 0.5580713 0.764749 0.344937 0.5442218 0.7761544 0.1118572 0.620542 0.9039669 -0.1154219 0.4117301 0.8042307 -0.2694995 0.5297009 0.7974857 -0.5680493 0.2033143 0.7672784 -0.5001384 0.4014297 0.9500834 -0.2060435 0.2342812 0.9577237 -0.1842757 0.2209249 0.839318 -0.5229063 0.1487089 0.5533696 -0.8221775 0.1334397 0.9816411 -0.1636645 -0.09795272 0.990478 -0.1145861 -0.07631123 -0.2392714 -0.629809 -0.7389789 -0.2578273 -0.1117475 -0.959707 -0.333428 -0.267957 -0.9038943 -0.4052199 -0.6278792 -0.6645033 -0.4024835 -0.55044 -0.7314526 -0.6508463 -0.4357496 -0.6217085 -0.3598049 -0.1449792 -0.9216949 -0.3006575 -0.06971067 -0.9511811 -0.01884192 -0.9989006 0.04292756 0.02657991 -0.8991083 0.4369187 -0.7723858 -0.01748555 0.634913 -0.7701148 -0.03067618 0.6371673 -0.7661063 -0.01858836 0.6424451 -0.7675042 -0.01902604 0.6407616 -0.7970856 0.02018475 0.6035291 0.2535958 0.8756906 -0.4109198 0.7846361 0.1588929 0.5992489 0.9159475 0.2203544 0.3353866 0.8957033 0.4416928 -0.05121588 0.8988689 0.3035946 -0.3160145 0.8186227 0.2385198 0.5224609 0.9081901 0.41686 -0.03766542 0.8350587 0.132052 0.534078 0.6992965 0.468846 0.5395998 0.7714607 0.5656477 0.2913608 0.6346947 0.7716882 0.04074245 0.6443302 0.7647435 -0.002476513 0.5050375 0.8071385 -0.3057201 0.4562367 0.8433465 -0.2839275 0.6720523 0.4761483 -0.5671231 -5.57107e-5 -0.8552163 0.5182714 0 -0.9917175 0.1284381 0.05424267 -0.9971575 0.05229395 0.114026 -0.9902949 0.07946074 0.6079872 -0.655304 0.4482503 0.1967505 -0.8852941 0.4213593 0.624763 -0.5636701 0.5403214 0.7789117 -0.1204689 0.6154542 0.9640727 0.206499 0.1670988 0.8788765 0.1099736 0.4642002 0.8785071 0.1076032 0.4654534 0.8176548 0.3413038 0.4636294 0.8263599 0.4009275 0.3954572 0.6858997 0.6520839 0.3229989 0.635596 0.6904995 0.3452945 0.5125473 0.819407 0.2566469 0.954396 0.2649465 0.137593 -0.4778034 -0.8783832 0.01212602 -0.9927139 -0.1204916 0.001057803 -0.8454159 -0.533604 -0.02321141 -0.9011201 -0.433499 0.007833063 -0.6227384 -0.7822605 -0.01629376 0.9965736 0.009937465 0.08211195 0.9706856 -0.01696079 0.2397538 0.8841198 0.02389872 0.4666489 0.8360694 -8.47633e-6 0.5486238 -0.957233 0.149309 0.2478142 -0.944256 0.3232735 0.06224888 -0.7804265 0.5898939 0.2072667 -0.7146556 0.6910612 0.108175 -0.5606067 0.8176974 0.1307339 -0.7247087 0.5218446 0.4499728 -0.8681064 0.1954864 0.4562637 -0.819703 0.08345621 0.5666765 -0.7695608 0.5342481 0.3497934 -0.8705136 0.3485633 0.3474332 -0.9649506 0.1778831 -0.1929459 -0.9882927 0.01688498 0.1516331 -0.5974515 0.8018334 -0.01072555 -0.6754906 0.6236003 -0.3934912 -0.2740764 0.884638 -0.3772238 -0.9177595 0.1165055 0.3796631 -0.9046795 0.4118255 0.1093373 -0.8719916 0.4892361 0.01669174 -0.8689638 0.1312093 0.4771648 -0.9642225 -0.1154589 0.2386301 -0.9593179 -0.2694368 0.08433866 -0.8040369 -0.5778309 0.1401301 -0.8899129 -0.2083746 0.4057527 -0.8873223 -0.1838634 0.4229105 -0.7690857 -0.4900171 0.4103543 -0.5280125 -0.8407688 0.1196268 -0.827458 -0.5226476 0.2053114 0.5879882 -0.6555112 0.4738934 0.07571399 -0.7536299 0.6529237 0.1782882 -0.8329461 0.5238456 0.5785899 -0.6055189 0.5464254 0.1497783 -0.9670164 0.2060241 0.1182811 -0.9579306 0.2614931 -0.994749 0.01469337 0.101285 -0.9926303 0.1027346 0.06427264 -0.4434116 0.8951804 0.04515022 -0.4138267 0.9074281 -0.07295143 -0.4849444 0.874545 -2.31367e-6 -1.4138e-6 0 -1 -5.21713e-6 -1 -9.87456e-7 -0.0312457 -0.9994885 -0.006819605 -0.0221188 -0.9997543 0.001488804 2.37993e-5 -1 5.0362e-5 0.002456784 -0.9991959 -0.04001933 -0.01351159 -0.9986205 -0.05074238 -0.007404625 -0.9999691 -0.002663493 -0.006559848 -0.9997721 0.02031409 0.005249023 -0.9995886 0.02819651 -0.03308689 -0.9985523 -0.04241108 -0.03393387 -0.9993694 0.01045912 -0.002466559 -0.9997731 -0.02116179 0.5625076 0.8191086 -0.112456 0.4793964 0.8133304 -0.3296559 -0.9999302 -3.97464e-4 -0.01181858 -0.999854 -0.01707005 8.57435e-4 -0.9998291 -0.01820611 0.003236711 -0.5583469 0.816833 -0.1450268 -0.5681154 0.7955833 -0.2104571 0.9946826 -0.08597427 -0.05670309 0.9994055 -0.02954083 0.01777702 0.004370391 0.9999776 -0.00507766 0.01152008 0.9996532 -0.02367955 -0.03444099 0.9994048 0.001975238 0.03484785 0.999195 0.01987296 0.06619232 0.9978065 -9.11919e-4 0.06575399 0.9977093 -0.01589393 0.2324028 0.9654414 -0.1179484 -0.272727 -0.8640773 0.4230725 0.7632826 -0.645797 -0.01860153 0.2503061 0.00365889 -0.9681599 0.9999764 -0.006869375 6.22494e-6 -0.2559697 -0.9655786 0.04623591 -0.4694701 -0.8828005 -0.01615875 0.01395988 0.9998953 -0.003827512 -0.9838749 0.1778851 -0.01863652 -0.9474848 0.319514 0.01354771 -0.7900997 0.6107968 -0.0516709 -0.7191565 0.6947773 -0.009933114 -0.4696145 0.8828225 0.009318947 -0.3945242 0.9188829 -0.002240538 -0.3636043 0.9315462 0.003709852 0.06976252 -0.8842528 0.4617686 0.3608219 -0.8531297 0.376799 0.00494951 0.9999857 -0.002028107 -0.1916331 0.9783127 0.07862019 0.005896329 0.9999827 -3.56167e-6 -0.3187491 0.3573514 -0.8778947 -0.4251361 0.8424407 -0.3309882 1.16521e-5 0.9999969 -0.002523541 -0.005432426 0.9999849 -9.56914e-4 -0.005879878 0.9999827 1.81246e-6 -0.9829964 0.06097781 -0.1732048 -0.9368816 0.0285623 -0.3484786 0.997394 -0.063434 -0.03437215 0.999715 0.02176302 0.009816706 0.9999539 0.003097832 -0.009088635 0.3863917 -0.922177 -0.0170626 0.1591699 -0.9871459 0.01442086 0.3747824 -0.927031 -0.01231426 1.18106e-5 1.68675e-7 -1 1.01801e-5 4.6237e-6 -1 1.17595e-5 -1.3185e-5 -1 1.55417e-5 1.88478e-5 -1 8.49626e-6 2.95496e-6 -1 -1.5263e-6 1.18872e-4 -1 5.49652e-6 -9.98732e-7 -1 0.9996075 -0.01618295 0.02287381 0.9576163 0.2497914 0.1434407 0.4938477 0.8651834 0.08701807 0.08183103 0.07767653 -0.9936147 -0.5018499 -0.8648982 -0.009893476 0.1753887 0.02755653 -0.9841135 0.0128324 0.03711909 -0.9992285 0.02149415 -0.01863509 -0.9995953 0.02101212 -0.02193951 -0.9995386 -0.1495462 -0.1477016 -0.9776606 0.05689537 0.06188315 -0.9964604 1.17085e-5 0 -1 0.06935995 0.02323383 -0.9973211 -4.45904e-6 2.15306e-4 -1 2.74334e-5 2.76083e-5 -1 0.00436896 0.004325568 -0.9999811 -0.01578551 -0.003089249 -0.9998707 0.05621349 0.01764327 -0.998263 -0.01879006 -0.0265693 -0.9994704 -0.02604907 0.03952699 -0.9988789 7.21659e-6 0 -1 4.84819e-5 0.007918596 -0.9999687 2.09687e-5 1.7912e-4 -1 -0.1596896 -9.11323e-4 -0.987167 0.4849263 0.8745551 2.80999e-6 0.3946677 0.9185648 -0.0218203 0.5093696 0.8605198 0.006959199 0.747671 0.6637401 -0.02090996 0.8465863 0.5265686 -0.07757008 0.9503988 0.3110259 0.002228796 0.5879024 0.808932 3.66185e-6 0.02458733 -0.9987548 0.0434103 -0.02160239 -0.9997223 0.00942111 0.01059871 -0.9984721 0.05423325 -0.9892613 -0.1411867 0.03779608 -0.9992634 -0.01644313 -0.03467535 -0.07170575 0.1221691 -0.9899157 -0.01898711 0.01468348 -0.9997119 -0.02864581 0.06671714 -0.9973607 -0.609218 -0.010531 0.792933 -0.07362383 -0.9393891 0.3348549 0.7008909 -0.5337646 0.4731252 0.8337613 -0.3971043 0.3836021 -0.08983391 -0.815045 0.5723912 0.2885083 -0.9214586 0.2601485 0.08309364 -0.9832934 0.1619556 0.0534023 -0.9894925 0.1343609 -0.07914286 -0.7638472 0.6405263 -0.6307367 -0.7448605 0.2176102 -0.2271678 -0.9638542 0.1392116 -0.6772837 -0.5526646 0.4856425 -0.3655392 -0.49865 0.7859577 -0.5548316 -0.3192333 0.7682785 0.3518245 -0.07938301 0.9326938 0.5180169 -0.0469895 0.8540788 0.5421748 -0.02773648 0.8398078 0.1195595 -0.080513 0.9895571 0.2431306 -0.03152769 0.9694812 0.2884729 -0.4467502 0.8468753 0.3153802 -0.4488881 0.8360831 0.1954076 -0.5620622 0.8036804 0.1070545 -0.4509208 0.8861206 -0.1070554 -0.4509189 0.8861216 -0.1954215 -0.5620718 0.8036702 -0.3153825 -0.4489117 0.8360695 -0.3340011 -0.4501768 0.8281209 -0.5018664 -0.0647763 0.8625163 0.6731516 -0.3432823 0.6549994 0.375369 -0.4616496 0.8037274 0.5290802 -0.3666331 0.7652806 -0.6351261 -0.3099389 0.7074976 -0.2763308 -0.7346482 0.6196236 -0.2688961 -0.7365332 0.6206559 -0.4707093 -0.7993911 0.373372 -0.4955915 -0.5476307 0.6741585 -0.4371829 -0.5765613 0.6902524 -0.7275909 -0.2789816 0.6267223 0.6946297 0.00473541 0.719352 0.7303734 -0.006094932 0.6830209 -1.66085e-5 -0.05653405 0.9984008 -0.1195588 -0.08051151 0.9895573 -0.2431238 -0.03152507 0.9694829 -0.3518372 -0.07937836 0.9326896 -0.4711071 -0.056665 0.8802541 -0.7303768 0.002067029 0.6830414 -0.7413413 0.007032275 0.6710914 0.3813788 -0.6829662 0.6229828 -0.1229404 -0.8053502 0.579911 0.3693046 -0.7789613 0.5067873 0.5033299 -0.7778624 0.3762835 0.5237146 -0.5266814 0.6695744 0.5203624 -0.5283064 0.6709066 0.7185439 -0.2778205 0.6375818 0.718279 -0.3733571 0.5870944 0.7295628 -0.2962683 0.6164117 0.2999265 -0.8867561 0.3517212 0.6172964 -0.6169246 0.4882102 0.5006275 -0.7538118 0.4256053 0.2531336 -0.9318027 0.260129 0.07409596 -0.9954726 0.05953264 0.1863412 -0.8967377 0.4014205 0.01704108 -0.9996064 -0.02228999 -0.02202343 -0.9996011 -0.0176872 -0.2129934 -0.9589563 0.1871813 -0.2852635 -0.9011706 0.3263683 -0.5388355 -0.7187525 0.439376 -0.4834186 -0.7671775 0.4215983 -0.6078405 -0.6282277 0.4856542 -0.7127113 -0.3700712 0.5958943 -0.7367714 -0.3183754 0.596494 -0.2355777 -0.9105976 0.3395808 0.001893043 -0.9998987 0.01411026 -0.7705341 0.524855 0.361669 0.8232404 0.01104104 0.5675857 0.775734 -0.00804162 0.6310089 0.7903486 -0.04252731 0.6111796 0.6735427 0.03208643 0.7384517 0.7767007 -0.006259262 0.6298387 0.7914705 0.02728754 0.6105979 + + + + + + + + + + 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 + + + + + + + + + + + + + + + + +

2 0 0 6 0 1 7 0 2 4 1 3 0 1 4 3 1 5 7 2 6 6 2 7 3 2 8 3 3 9 0 3 10 5 3 11 10 4 12 8 4 13 0 4 14 8 5 15 5 5 16 0 5 17 8 6 18 9 6 19 5 6 20 14 7 21 2 7 22 11 7 23 11 8 24 7 8 25 3 8 26 11 9 27 3 9 28 12 9 29 3 10 30 9 10 31 12 10 32 9 11 33 3 11 34 5 11 35 14 12 36 13 12 37 2 12 38 2 13 39 7 13 40 11 13 41 29 14 42 15 14 43 22 14 44 18 15 45 26 15 46 28 15 47 19 16 48 23 16 49 17 16 50 23 17 51 26 17 52 17 17 53 26 18 54 20 18 55 17 18 56 26 19 57 16 19 58 20 19 59 16 20 60 26 20 61 18 20 62 19 21 63 27 21 64 23 21 65 19 22 66 21 22 67 27 22 68 21 23 69 25 23 70 27 23 71 29 24 72 30 24 73 15 24 74 29 25 75 22 25 76 48 25 77 50 26 78 29 26 79 48 26 80 50 27 81 48 27 82 33 27 83 50 28 84 33 28 85 49 28 86 33 29 87 39 29 88 49 29 89 40 30 90 33 30 91 48 30 92 34 31 93 40 31 94 48 31 95 36 32 96 34 32 97 48 32 98 32 33 99 36 33 100 48 33 101 35 34 102 32 34 103 48 34 104 31 35 105 35 35 106 48 35 107 37 36 108 31 36 109 48 36 110 38 37 111 37 37 112 48 37 113 43 38 114 41 38 115 38 38 116 46 39 117 43 39 118 38 39 119 44 40 120 10 40 121 0 40 122 4 41 123 44 41 124 0 41 125 24 42 126 45 42 127 46 42 128 21 43 129 47 43 130 25 43 131 47 44 132 24 44 133 25 44 134 47 45 135 45 45 136 24 45 137 3 46 138 6 46 139 4 46 140 1 47 141 51 47 142 2 47 143 2 48 144 51 48 145 6 48 146 51 49 147 49 49 148 6 49 149 51 50 150 50 50 151 49 50 152 1 51 153 2 51 154 52 51 155 49 52 156 4 52 157 6 52 158 50 53 159 1 53 160 29 53 161 1 54 162 50 54 163 51 54 164 30 55 165 29 55 166 1 55 167 54 56 168 56 56 169 55 56 170 53 57 171 8 57 172 10 57 173 53 58 174 10 58 175 44 58 176 77 59 177 283 59 178 91 59 179 283 60 180 77 60 181 281 60 182 281 61 183 77 61 184 279 61 185 281 62 186 279 62 187 30 62 188 30 63 189 279 63 190 61 63 191 197 64 192 190 64 193 181 64 194 60 65 195 59 65 196 61 65 197 60 66 198 58 66 199 59 66 200 217 67 201 282 67 202 59 67 203 58 68 204 217 68 205 59 68 206 234 69 207 280 69 208 277 69 209 282 70 210 267 70 211 284 70 212 165 71 213 282 71 214 217 71 215 237 72 216 227 72 217 274 72 218 274 73 219 227 73 220 277 73 221 277 74 222 227 74 223 254 74 224 280 75 225 234 75 226 58 75 227 270 76 228 289 76 229 288 76 230 288 77 231 241 77 232 270 77 233 267 78 234 241 78 235 288 78 236 267 79 237 288 79 238 284 79 239 222 80 240 92 80 241 242 80 242 96 81 243 106 81 244 97 81 245 95 82 246 279 82 247 77 82 248 79 83 249 279 83 250 95 83 251 69 84 252 279 84 253 79 84 254 65 85 255 279 85 256 69 85 257 80 86 258 279 86 259 65 86 260 64 87 261 279 87 262 80 87 263 85 88 264 279 88 265 64 88 266 89 89 267 279 89 268 85 89 269 82 90 270 86 90 271 245 90 272 103 91 273 86 91 274 82 91 275 103 92 276 83 92 277 86 92 278 106 93 279 83 93 280 103 93 281 104 94 282 106 94 283 103 94 284 106 95 285 107 95 286 97 95 287 106 96 288 104 96 289 107 96 290 222 97 291 252 97 292 100 97 293 107 98 294 252 98 295 97 98 296 101 99 297 105 99 298 94 99 299 100 100 300 94 100 301 222 100 302 100 101 303 101 101 304 94 101 305 102 102 306 70 102 307 101 102 308 102 103 309 67 103 310 70 103 311 102 104 312 101 104 313 100 104 314 102 105 315 178 105 316 67 105 317 91 106 318 178 106 319 102 106 320 67 107 321 178 107 322 230 107 323 73 108 324 67 108 325 230 108 326 70 109 327 67 109 328 73 109 329 70 110 330 105 110 331 101 110 332 70 111 333 93 111 334 105 111 335 70 112 336 75 112 337 93 112 338 73 113 339 75 113 340 70 113 341 85 114 342 78 114 343 82 114 344 85 115 345 82 115 346 89 115 347 80 116 348 62 116 349 64 116 350 80 117 351 76 117 352 62 117 353 65 118 354 76 118 355 80 118 356 65 119 357 81 119 358 76 119 359 69 120 360 81 120 361 65 120 362 77 121 363 71 121 364 95 121 365 91 122 366 71 122 367 77 122 368 63 123 369 245 123 370 86 123 371 57 124 372 86 124 373 83 124 374 57 125 375 63 125 376 86 125 377 96 126 378 83 126 379 106 126 380 88 127 381 83 127 382 96 127 383 88 128 384 57 128 385 83 128 386 245 129 387 89 129 388 82 129 389 272 130 390 89 130 391 245 130 392 82 131 393 78 131 394 103 131 395 141 132 396 230 132 397 178 132 398 141 133 399 73 133 400 230 133 401 102 134 402 71 134 403 91 134 404 78 135 405 64 135 406 62 135 407 62 136 408 87 136 409 78 136 410 76 137 411 87 137 412 62 137 413 76 138 414 84 138 415 87 138 416 81 139 417 84 139 418 76 139 419 68 140 420 84 140 421 81 140 422 68 141 423 72 141 424 84 141 425 74 142 426 72 142 427 68 142 428 74 143 429 71 143 430 72 143 431 68 144 432 69 144 433 79 144 434 81 145 435 69 145 436 68 145 437 71 146 438 79 146 439 95 146 440 74 147 441 79 147 442 71 147 443 68 148 444 79 148 445 74 148 446 63 149 447 119 149 448 245 149 449 57 150 450 119 150 451 63 150 452 98 151 453 247 151 454 99 151 455 92 152 456 93 152 457 99 152 458 93 153 459 98 153 460 99 153 461 98 154 462 93 154 463 75 154 464 94 155 465 92 155 466 222 155 467 94 156 468 105 156 469 92 156 470 88 157 471 97 157 472 154 157 473 88 158 474 96 158 475 97 158 476 88 159 477 207 159 478 172 159 479 154 160 480 207 160 481 88 160 482 93 161 483 92 161 484 105 161 485 85 162 486 64 162 487 78 162 488 239 163 489 226 163 490 137 163 491 239 164 492 137 164 493 171 164 494 171 165 495 185 165 496 239 165 497 247 166 498 155 166 499 99 166 500 155 167 501 242 167 502 99 167 503 97 168 504 252 168 505 260 168 506 242 169 507 252 169 508 222 169 509 260 170 510 252 170 511 242 170 512 212 171 513 236 171 514 132 171 515 225 172 516 235 172 517 130 172 518 225 173 519 213 173 520 235 173 521 192 174 522 213 174 523 225 174 524 160 175 525 213 175 526 192 175 527 160 176 528 205 176 529 213 176 530 212 177 531 201 177 532 134 177 533 267 178 534 170 178 535 221 178 536 165 179 537 217 179 538 242 179 539 165 180 540 267 180 541 282 180 542 170 181 543 267 181 544 165 181 545 242 182 546 116 182 547 117 182 548 116 182 549 242 182 550 264 182 551 264 183 552 131 183 553 116 183 554 131 184 555 264 184 556 263 184 557 242 185 558 155 185 559 264 185 560 255 186 561 234 186 562 159 186 563 234 187 564 255 187 565 260 187 566 260 188 567 217 188 568 234 188 569 242 189 570 217 189 571 260 189 572 242 190 573 117 190 574 165 190 575 159 191 576 180 191 577 189 191 578 234 182 579 180 182 580 159 182 581 159 192 582 206 192 583 156 192 584 189 193 585 206 193 586 159 193 587 159 194 588 145 194 589 228 194 590 156 195 591 145 195 592 159 195 593 277 196 594 254 196 595 180 196 596 180 197 597 234 197 598 277 197 599 180 198 600 254 198 601 236 198 602 254 199 603 132 199 604 236 199 605 242 200 606 92 200 607 99 200 608 213 182 609 205 182 610 235 182 611 205 201 612 246 201 613 235 201 614 134 202 615 236 202 616 212 202 617 212 203 618 124 203 619 201 203 620 266 204 621 124 204 622 212 204 623 58 205 624 234 205 625 217 205 626 108 206 627 224 206 628 139 206 629 108 207 630 139 207 631 201 207 632 108 208 633 201 208 634 124 208 635 138 209 636 113 209 637 167 209 638 224 210 639 113 210 640 138 210 641 224 211 642 136 211 643 113 211 644 224 212 645 108 212 646 136 212 647 159 213 648 250 213 649 172 213 650 159 214 651 123 214 652 250 214 653 172 215 654 255 215 655 159 215 656 130 216 657 235 216 658 129 216 659 129 217 660 235 217 661 233 217 662 233 218 663 166 218 664 129 218 665 221 219 666 220 219 667 241 219 668 188 220 669 220 220 670 221 220 671 180 221 672 134 221 673 201 221 674 236 222 675 134 222 676 180 222 677 201 223 678 139 223 679 180 223 680 254 224 681 251 224 682 266 224 683 254 225 684 227 225 685 251 225 686 170 226 687 165 226 688 265 226 689 265 227 690 169 227 691 193 227 692 165 228 693 169 228 694 265 228 695 172 229 696 250 229 697 150 229 698 250 230 699 123 230 700 150 230 701 191 231 702 226 231 703 146 231 704 191 232 705 137 232 706 226 232 707 109 233 708 137 233 709 191 233 710 143 234 711 137 234 712 109 234 713 143 235 714 171 235 715 137 235 716 174 236 717 171 236 718 143 236 719 174 237 720 185 237 721 171 237 722 220 238 723 240 238 724 246 238 725 124 239 726 266 239 727 239 239 728 168 240 729 264 240 730 155 240 731 152 241 732 264 241 733 168 241 734 132 242 735 266 242 736 212 242 737 132 243 738 254 243 739 266 243 740 260 244 741 154 244 742 97 244 743 152 245 744 168 245 745 163 245 746 220 246 747 200 246 748 241 246 749 220 247 750 160 247 751 200 247 752 246 248 753 160 248 754 220 248 755 160 249 756 246 249 757 205 249 758 266 250 759 226 250 760 239 250 761 266 251 762 146 251 763 226 251 764 266 252 765 258 252 766 146 252 767 260 253 768 207 253 769 154 253 770 260 254 771 255 254 772 207 254 773 185 255 774 124 255 775 239 255 776 108 256 777 124 256 778 185 256 779 108 257 780 185 257 781 136 257 782 136 258 783 185 258 784 174 258 785 174 259 786 229 259 787 136 259 788 246 260 789 233 260 790 235 260 791 240 261 792 233 261 793 246 261 794 167 262 795 157 262 796 138 262 797 175 263 798 157 263 799 243 263 800 138 264 801 157 264 802 175 264 803 228 265 804 243 265 805 159 265 806 243 266 807 228 266 808 175 266 809 159 267 810 243 267 811 123 267 812 253 268 813 244 268 814 248 268 815 248 269 816 203 269 817 253 269 818 244 270 819 253 270 820 263 270 821 152 271 822 263 271 823 264 271 824 215 272 825 263 272 826 152 272 827 244 273 828 263 273 829 215 273 830 240 182 831 193 182 832 233 182 833 193 274 834 126 274 835 166 274 836 193 275 837 169 275 838 126 275 839 193 276 840 166 276 841 233 276 842 203 277 843 166 277 844 126 277 845 203 182 846 248 182 847 166 182 848 265 278 849 221 278 850 170 278 851 265 279 852 188 279 853 221 279 854 188 280 855 265 280 856 193 280 857 220 281 858 193 281 859 240 281 860 188 282 861 193 282 862 220 282 863 215 283 864 133 283 865 151 283 866 215 284 867 142 284 868 133 284 869 120 285 870 142 285 871 118 285 872 120 286 873 133 286 874 142 286 875 141 287 876 133 287 877 120 287 878 141 288 879 151 288 880 133 288 881 114 289 882 151 289 883 141 289 884 196 290 885 231 290 886 218 290 887 157 291 888 231 291 889 196 291 890 128 292 891 115 292 892 196 292 893 256 293 894 115 293 895 128 293 896 256 294 897 176 294 898 115 294 899 128 295 900 196 295 901 218 295 902 128 296 903 229 296 904 256 296 905 218 297 906 229 297 907 128 297 908 272 298 909 190 298 910 211 298 911 158 299 912 195 299 913 232 299 914 211 300 915 197 300 916 195 300 917 211 301 918 190 301 919 197 301 920 158 302 921 258 302 922 237 302 923 158 303 924 232 303 925 258 303 926 195 304 927 219 304 928 232 304 929 195 305 930 273 305 931 211 305 932 158 306 933 273 306 934 195 306 935 197 307 936 219 307 937 195 307 938 197 308 939 181 308 940 219 308 941 259 309 942 181 309 943 190 309 944 140 310 945 199 310 946 208 310 947 140 311 948 182 311 949 199 311 950 182 312 951 109 312 952 191 312 953 182 313 954 143 313 955 109 313 956 140 314 957 143 314 958 182 314 959 140 315 960 174 315 961 143 315 962 208 316 963 174 316 964 140 316 965 121 317 966 209 317 967 111 317 968 161 318 969 209 318 970 121 318 971 161 319 972 129 319 973 209 319 974 130 320 975 129 320 976 161 320 977 113 321 978 231 321 979 167 321 980 136 322 981 231 322 982 113 322 983 136 323 984 218 323 985 231 323 986 136 324 987 229 324 988 218 324 989 231 325 990 157 325 991 167 325 992 110 326 993 225 326 994 130 326 995 192 327 996 112 327 997 160 327 998 192 328 999 149 328 1000 112 328 1001 225 329 1002 149 329 1003 192 329 1004 110 330 1005 149 330 1006 225 330 1007 110 331 1008 173 331 1009 149 331 1010 161 332 1011 173 332 1012 110 332 1013 161 333 1014 121 333 1015 173 333 1016 130 334 1017 161 334 1018 110 334 1019 153 335 1020 114 335 1021 111 335 1022 249 336 1023 114 336 1024 153 336 1025 257 337 1026 114 337 1027 249 337 1028 257 338 1029 151 338 1030 114 338 1031 244 339 1032 151 339 1033 257 339 1034 244 340 1035 215 340 1036 151 340 1037 152 341 1038 142 341 1039 215 341 1040 118 342 1041 142 342 1042 152 342 1043 270 343 1044 204 343 1045 271 343 1046 200 344 1047 204 344 1048 270 344 1049 214 345 1050 204 345 1051 200 345 1052 216 346 1053 204 346 1054 214 346 1055 216 347 1056 194 347 1057 204 347 1058 184 348 1059 194 348 1060 216 348 1061 184 349 1062 210 349 1063 194 349 1064 179 350 1065 238 350 1066 210 350 1067 210 351 1068 144 351 1069 194 351 1070 210 352 1071 238 352 1072 144 352 1073 194 353 1074 271 353 1075 204 353 1076 194 354 1077 144 354 1078 271 354 1079 144 355 1080 268 355 1081 271 355 1082 144 356 1083 269 356 1084 268 356 1085 210 357 1086 184 357 1087 179 357 1088 200 358 1089 270 358 1090 241 358 1091 208 359 1092 259 359 1093 176 359 1094 259 360 1095 127 360 1096 176 360 1097 190 361 1098 127 361 1099 259 361 1100 245 362 1101 190 362 1102 272 362 1103 127 363 1104 190 363 1105 245 363 1106 123 364 1107 162 364 1108 164 364 1109 123 365 1110 243 365 1111 162 365 1112 183 366 1113 117 366 1114 116 366 1115 177 367 1116 117 367 1117 183 367 1118 131 368 1119 187 368 1120 135 368 1121 131 369 1122 261 369 1123 187 369 1124 263 370 1125 261 370 1126 131 370 1127 135 371 1128 116 371 1129 131 371 1130 183 372 1131 116 372 1132 135 372 1133 263 373 1134 253 373 1135 261 373 1136 189 374 1137 139 374 1138 224 374 1139 180 375 1140 139 375 1141 189 375 1142 249 376 1143 262 376 1144 257 376 1145 147 377 1146 125 377 1147 262 377 1148 209 378 1149 125 378 1150 147 378 1151 209 379 1152 129 379 1153 125 379 1154 147 380 1155 249 380 1156 153 380 1157 262 381 1158 249 381 1159 147 381 1160 147 382 1161 111 382 1162 209 382 1163 153 383 1164 111 383 1165 147 383 1166 184 384 1167 173 384 1168 121 384 1169 184 385 1170 149 385 1171 173 385 1172 216 386 1173 149 386 1174 184 386 1175 216 387 1176 112 387 1177 149 387 1178 216 388 1179 160 388 1180 112 388 1181 214 389 1182 160 389 1183 216 389 1184 200 390 1185 160 390 1186 214 390 1187 224 391 1188 202 391 1189 189 391 1190 198 392 1191 202 392 1192 224 392 1193 224 393 1194 148 393 1195 198 393 1196 138 394 1197 148 394 1198 224 394 1199 138 395 1200 186 395 1201 148 395 1202 138 396 1203 175 396 1204 186 396 1205 227 397 1206 237 397 1207 251 397 1208 251 398 1209 237 398 1210 258 398 1211 251 399 1212 258 399 1213 266 399 1214 178 400 1215 269 400 1216 238 400 1217 238 401 1218 114 401 1219 178 401 1220 179 402 1221 114 402 1222 238 402 1223 179 403 1224 121 403 1225 114 403 1226 121 404 1227 111 404 1228 114 404 1229 174 405 1230 256 405 1231 229 405 1232 208 406 1233 256 406 1234 174 406 1235 208 407 1236 176 407 1237 256 407 1238 141 408 1239 178 408 1240 114 408 1241 118 409 1242 73 409 1243 120 409 1244 120 410 1245 73 410 1246 141 410 1247 166 411 1248 125 411 1249 129 411 1250 262 412 1251 125 412 1252 166 412 1253 257 413 1254 248 413 1255 244 413 1256 262 414 1257 248 414 1258 257 414 1259 262 415 1260 166 415 1261 248 415 1262 183 416 1263 126 416 1264 177 416 1265 203 417 1266 261 417 1267 253 417 1268 203 418 1269 187 418 1270 261 418 1271 126 419 1272 187 419 1273 203 419 1274 126 420 1275 135 420 1276 187 420 1277 126 421 1278 183 421 1279 135 421 1280 177 422 1281 165 422 1282 117 422 1283 245 423 1284 119 423 1285 127 423 1286 119 424 1287 57 424 1288 223 424 1289 57 425 1290 164 425 1291 223 425 1292 199 426 1293 259 426 1294 208 426 1295 199 427 1296 181 427 1297 259 427 1298 182 428 1299 181 428 1300 199 428 1301 182 429 1302 219 429 1303 181 429 1304 191 430 1305 219 430 1306 182 430 1307 191 431 1308 232 431 1309 219 431 1310 146 432 1311 232 432 1312 191 432 1313 146 433 1314 258 433 1315 232 433 1316 223 434 1317 243 434 1318 119 434 1319 223 435 1320 162 435 1321 243 435 1322 164 436 1323 162 436 1324 223 436 1325 168 437 1326 155 437 1327 122 437 1328 155 438 1329 247 438 1330 122 438 1331 247 439 1332 163 439 1333 168 439 1334 168 440 1335 122 440 1336 247 440 1337 255 441 1338 172 441 1339 207 441 1340 88 442 1341 172 442 1342 150 442 1343 202 443 1344 206 443 1345 189 443 1346 198 444 1347 206 444 1348 202 444 1349 198 445 1350 156 445 1351 206 445 1352 148 446 1353 156 446 1354 198 446 1355 148 447 1356 145 447 1357 156 447 1358 186 448 1359 145 448 1360 148 448 1361 186 449 1362 228 449 1363 145 449 1364 228 450 1365 186 450 1366 175 450 1367 126 451 1368 165 451 1369 177 451 1370 169 452 1371 165 452 1372 126 452 1373 127 453 1374 115 453 1375 176 453 1376 119 454 1377 115 454 1378 127 454 1379 119 455 1380 196 455 1381 115 455 1382 119 456 1383 157 456 1384 196 456 1385 243 457 1386 157 457 1387 119 457 1388 238 458 1389 269 458 1390 144 458 1391 121 459 1392 179 459 1393 184 459 1394 221 460 1395 241 460 1396 267 460 1397 271 461 1398 289 461 1399 270 461 1400 271 462 1401 286 462 1402 289 462 1403 268 463 1404 286 463 1405 271 463 1406 269 464 1407 286 464 1408 268 464 1409 269 465 1410 285 465 1411 286 465 1412 275 466 1413 272 466 1414 211 466 1415 237 467 1416 274 467 1417 278 467 1418 237 468 1419 278 468 1420 158 468 1421 158 469 1422 278 469 1423 276 469 1424 158 470 1425 276 470 1426 273 470 1427 273 471 1428 276 471 1429 275 471 1430 273 472 1431 275 472 1432 211 472 1433 289 473 1434 286 473 1435 288 473 1436 284 474 1437 287 474 1438 52 474 1439 284 475 1440 52 475 1441 282 475 1442 286 476 1443 285 476 1444 288 476 1445 288 477 1446 285 477 1447 287 477 1448 288 478 1449 287 478 1450 284 478 1451 15 479 1452 61 479 1453 59 479 1454 283 480 1455 281 480 1456 287 480 1457 281 481 1458 52 481 1459 287 481 1460 52 482 1461 2 482 1462 282 482 1463 287 483 1464 285 483 1465 283 483 1466 59 484 1467 282 484 1468 2 484 1469 15 485 1470 30 485 1471 61 485 1472 52 486 1473 281 486 1474 30 486 1475 30 487 1476 1 487 1477 52 487 1478 2 488 1479 290 488 1480 59 488 1481 15 489 1482 59 489 1483 290 489 1484 291 490 1485 13 490 1486 18 490 1487 28 491 1488 291 491 1489 18 491 1490 291 492 1491 290 492 1492 13 492 1493 13 493 1494 290 493 1495 2 493 1496 22 494 1497 290 494 1498 291 494 1499 22 495 1500 15 495 1501 290 495 1502 22 496 1503 291 496 1504 58 496 1505 28 497 1506 58 497 1507 291 497 1508 304 498 1509 58 498 1510 28 498 1511 301 499 1512 296 499 1513 298 499 1514 296 500 1515 301 500 1516 292 500 1517 22 501 1518 60 501 1519 301 501 1520 58 502 1521 304 502 1522 295 502 1523 58 503 1524 295 503 1525 280 503 1526 294 504 1527 293 504 1528 275 504 1529 277 505 1530 280 505 1531 295 505 1532 296 506 1533 295 506 1534 304 506 1535 292 507 1536 294 507 1537 296 507 1538 293 508 1539 294 508 1540 292 508 1541 22 509 1542 58 509 1543 60 509 1544 274 510 1545 277 510 1546 294 510 1547 274 511 1548 294 511 1549 275 511 1550 276 512 1551 274 512 1552 275 512 1553 277 513 1554 295 513 1555 296 513 1556 277 514 1557 296 514 1558 294 514 1559 278 515 1560 274 515 1561 276 515 1562 301 516 1563 298 516 1564 302 516 1565 298 517 1566 300 517 1567 299 517 1568 299 518 1569 302 518 1570 298 518 1571 297 519 1572 303 519 1573 24 519 1574 298 520 1575 296 520 1576 304 520 1577 300 521 1578 297 521 1579 299 521 1580 300 522 1581 303 522 1582 297 522 1583 304 523 1584 303 523 1585 300 523 1586 298 524 1587 304 524 1588 300 524 1589 23 525 1590 24 525 1591 303 525 1592 25 526 1593 24 526 1594 27 526 1595 302 527 1596 22 527 1597 301 527 1598 26 528 1599 23 528 1600 303 528 1601 23 529 1602 27 529 1603 24 529 1604 304 530 1605 26 530 1606 303 530 1607 28 531 1608 26 531 1609 304 531 1610 24 532 1611 46 532 1612 297 532 1613 297 533 1614 46 533 1615 38 533 1616 275 534 1617 293 534 1618 272 534 1619 293 535 1620 89 535 1621 272 535 1622 89 536 1623 293 536 1624 292 536 1625 89 537 1626 292 537 1627 279 537 1628 279 538 1629 292 538 1630 301 538 1631 61 539 1632 279 539 1633 301 539 1634 60 540 1635 61 540 1636 301 540 1637 38 541 1638 299 541 1639 297 541 1640 38 542 1641 48 542 1642 299 542 1643 48 543 1644 302 543 1645 299 543 1646 22 544 1647 302 544 1648 48 544 1649 118 545 1650 152 545 1651 163 545 1652 75 546 1653 118 546 1654 163 546 1655 75 547 1656 73 547 1657 118 547 1658 123 548 1659 164 548 1660 150 548 1661 88 549 1662 150 549 1663 164 549 1664 57 550 1665 88 550 1666 164 550 1667 90 551 1668 252 551 1669 107 551 1670 90 552 1671 100 552 1672 252 552 1673 90 553 1674 107 553 1675 104 553 1676 66 554 1677 90 554 1678 104 554 1679 66 555 1680 102 555 1681 90 555 1682 90 556 1683 102 556 1684 100 556 1685 66 557 1686 104 557 1687 87 557 1688 66 558 1689 72 558 1690 102 558 1691 87 559 1692 104 559 1693 103 559 1694 78 560 1695 87 560 1696 103 560 1697 71 561 1698 102 561 1699 72 561 1700 66 562 1701 84 562 1702 72 562 1703 66 563 1704 87 563 1705 84 563 1706 75 564 1707 163 564 1708 98 564 1709 98 565 1710 163 565 1711 247 565 1712 457 566 1713 328 566 1714 397 566 1715 472 567 1716 457 567 1717 397 567 1718 480 568 1719 467 568 1720 465 568 1721 480 569 1722 475 569 1723 467 569 1724 476 570 1725 475 570 1726 454 570 1727 470 571 1728 453 571 1729 465 571 1730 465 572 1731 453 572 1732 452 572 1733 480 573 1734 454 573 1735 475 573 1736 480 574 1737 465 574 1738 452 574 1739 463 575 1740 451 575 1741 454 575 1742 480 576 1743 463 576 1744 454 576 1745 480 577 1746 452 577 1747 463 577 1748 463 578 1749 452 578 1750 448 578 1751 463 579 1752 321 579 1753 451 579 1754 463 580 1755 448 580 1756 321 580 1757 483 581 1758 396 581 1759 464 581 1760 464 582 1761 396 582 1762 410 582 1763 436 583 1764 410 583 1765 396 583 1766 472 584 1767 377 584 1768 474 584 1769 472 585 1770 397 585 1771 377 585 1772 377 586 1773 397 586 1774 408 586 1775 348 587 1776 11 587 1777 12 587 1778 417 588 1779 362 588 1780 383 588 1781 330 589 1782 327 589 1783 402 589 1784 327 590 1785 369 590 1786 402 590 1787 327 591 1788 438 591 1789 369 591 1790 438 592 1791 441 592 1792 369 592 1793 438 593 1794 432 593 1795 441 593 1796 432 594 1797 385 594 1798 441 594 1799 392 595 1800 433 595 1801 14 595 1802 433 596 1803 384 596 1804 14 596 1805 341 597 1806 386 597 1807 378 597 1808 378 598 1809 415 598 1810 341 598 1811 378 599 1812 412 599 1813 415 599 1814 412 600 1815 403 600 1816 415 600 1817 412 601 1818 368 601 1819 403 601 1820 368 602 1821 359 602 1822 403 602 1823 368 603 1824 364 603 1825 359 603 1826 364 604 1827 374 604 1828 359 604 1829 464 605 1830 410 605 1831 389 605 1832 317 606 1833 358 606 1834 389 606 1835 393 607 1836 328 607 1837 437 607 1838 328 608 1839 393 608 1840 397 608 1841 404 609 1842 437 609 1843 328 609 1844 393 610 1845 437 610 1846 404 610 1847 396 611 1848 346 611 1849 398 611 1850 346 612 1851 330 612 1852 398 612 1853 346 613 1854 327 613 1855 330 613 1856 438 614 1857 327 614 1858 346 614 1859 414 615 1860 337 615 1861 313 615 1862 414 616 1863 373 616 1864 337 616 1865 373 617 1866 349 617 1867 337 617 1868 373 618 1869 381 618 1870 349 618 1871 381 619 1872 382 619 1873 349 619 1874 381 620 1875 367 620 1876 382 620 1877 367 621 1878 312 621 1879 382 621 1880 367 622 1881 357 622 1882 312 622 1883 483 623 1884 346 623 1885 396 623 1886 438 624 1887 346 624 1888 483 624 1889 43 625 1890 432 625 1891 438 625 1892 384 626 1893 439 626 1894 14 626 1895 433 627 1896 425 627 1897 380 627 1898 433 628 1899 376 628 1900 425 628 1901 433 629 1902 363 629 1903 376 629 1904 363 630 1905 310 630 1906 376 630 1907 363 631 1908 320 631 1909 310 631 1910 380 632 1911 384 632 1912 433 632 1913 309 633 1914 326 633 1915 395 633 1916 309 634 1917 315 634 1918 326 634 1919 315 635 1920 329 635 1921 326 635 1922 309 636 1923 395 636 1924 434 636 1925 395 637 1926 430 637 1927 434 637 1928 377 638 1929 406 638 1930 474 638 1931 406 639 1932 324 639 1933 339 639 1934 357 640 1935 316 640 1936 385 640 1937 357 641 1938 387 641 1939 316 641 1940 387 642 1941 340 642 1942 316 642 1943 417 643 1944 324 643 1945 444 643 1946 383 644 1947 324 644 1948 417 644 1949 383 645 1950 314 645 1951 324 645 1952 314 646 1953 42 646 1954 324 646 1955 42 647 1956 314 647 1957 44 647 1958 322 648 1959 305 648 1960 313 648 1961 322 649 1962 313 649 1963 19 649 1964 17 650 1965 322 650 1966 19 650 1967 422 651 1968 378 651 1969 386 651 1970 422 652 1971 412 652 1972 378 652 1973 422 653 1974 345 653 1975 412 653 1976 345 654 1977 368 654 1978 412 654 1979 368 655 1980 345 655 1981 364 655 1982 345 656 1983 374 656 1984 364 656 1985 366 657 1986 353 657 1987 400 657 1988 353 658 1989 351 658 1990 400 658 1991 351 659 1992 443 659 1993 400 659 1994 351 660 1995 411 660 1996 443 660 1997 351 661 1998 362 661 1999 411 661 2000 362 662 2001 388 662 2002 411 662 2003 362 663 2004 417 663 2005 388 663 2006 407 664 2007 413 664 2008 444 664 2009 413 665 2010 356 665 2011 444 665 2012 309 666 2013 413 666 2014 325 666 2015 413 667 2016 407 667 2017 325 667 2018 356 668 2019 434 668 2020 430 668 2021 356 669 2022 413 669 2023 434 669 2024 413 670 2025 309 670 2026 434 670 2027 325 671 2028 315 671 2029 309 671 2030 16 672 2031 374 672 2032 421 672 2033 374 673 2034 345 673 2035 421 673 2036 308 674 2037 310 674 2038 320 674 2039 380 675 2040 425 675 2041 440 675 2042 425 676 2043 428 676 2044 440 676 2045 308 677 2046 428 677 2047 310 677 2048 428 678 2049 376 678 2050 310 678 2051 428 679 2052 425 679 2053 376 679 2054 384 680 2055 380 680 2056 439 680 2057 380 681 2058 440 681 2059 439 681 2060 436 682 2061 398 682 2062 330 682 2063 436 683 2064 396 683 2065 398 683 2066 432 684 2067 43 684 2068 319 684 2069 43 685 2070 46 685 2071 319 685 2072 319 686 2073 312 686 2074 432 686 2075 312 687 2076 385 687 2077 432 687 2078 357 688 2079 385 688 2080 312 688 2081 366 689 2082 12 689 2083 9 689 2084 333 690 2085 383 690 2086 362 690 2087 314 691 2088 53 691 2089 44 691 2090 370 692 2091 8 692 2092 53 692 2093 370 693 2094 361 693 2095 8 693 2096 314 694 2097 333 694 2098 53 694 2099 333 695 2100 370 695 2101 53 695 2102 383 696 2103 333 696 2104 314 696 2105 362 697 2106 370 697 2107 333 697 2108 362 698 2109 351 698 2110 370 698 2111 351 699 2112 361 699 2113 370 699 2114 351 700 2115 353 700 2116 361 700 2117 353 701 2118 366 701 2119 361 701 2120 366 702 2121 9 702 2122 361 702 2123 9 703 2124 8 703 2125 361 703 2126 377 704 2127 408 704 2128 418 704 2129 408 705 2130 352 705 2131 418 705 2132 329 706 2133 409 706 2134 352 706 2135 329 707 2136 315 707 2137 409 707 2138 315 708 2139 324 708 2140 409 708 2141 315 709 2142 325 709 2143 324 709 2144 325 710 2145 407 710 2146 324 710 2147 407 711 2148 444 711 2149 324 711 2150 429 712 2151 445 712 2152 399 712 2153 399 713 2154 388 713 2155 417 713 2156 399 714 2157 445 714 2158 388 714 2159 445 715 2160 411 715 2161 388 715 2162 445 716 2163 344 716 2164 411 716 2165 344 717 2166 372 717 2167 411 717 2168 372 718 2169 443 718 2170 411 718 2171 372 719 2172 400 719 2173 443 719 2174 445 720 2175 429 720 2176 344 720 2177 338 721 2178 394 721 2179 402 721 2180 424 722 2181 350 722 2182 340 722 2183 424 723 2184 338 723 2185 350 723 2186 424 724 2187 442 724 2188 338 724 2189 442 725 2190 394 725 2191 338 725 2192 429 726 2193 399 726 2194 430 726 2195 399 727 2196 356 727 2197 430 727 2198 399 728 2199 417 728 2200 356 728 2201 417 729 2202 444 729 2203 356 729 2204 357 730 2205 420 730 2206 387 730 2207 420 731 2208 416 731 2209 387 731 2210 420 732 2211 381 732 2212 416 732 2213 381 733 2214 446 733 2215 416 733 2216 381 734 2217 373 734 2218 446 734 2219 420 735 2220 367 735 2221 381 735 2222 420 736 2223 357 736 2224 367 736 2225 312 737 2226 319 737 2227 382 737 2228 343 738 2229 349 738 2230 382 738 2231 343 739 2232 318 739 2233 349 739 2234 21 740 2235 318 740 2236 47 740 2237 318 741 2238 45 741 2239 47 741 2240 318 742 2241 337 742 2242 349 742 2243 21 743 2244 313 743 2245 337 743 2246 21 744 2247 19 744 2248 313 744 2249 45 745 2250 343 745 2251 319 745 2252 45 746 2253 318 746 2254 343 746 2255 318 747 2256 21 747 2257 337 747 2258 46 748 2259 45 748 2260 319 748 2261 350 749 2262 431 749 2263 340 749 2264 431 750 2265 316 750 2266 340 750 2267 431 751 2268 350 751 2269 369 751 2270 316 752 2271 441 752 2272 385 752 2273 316 753 2274 431 753 2275 441 753 2276 431 754 2277 369 754 2278 441 754 2279 402 755 2280 369 755 2281 338 755 2282 369 756 2283 350 756 2284 338 756 2285 324 757 2286 419 757 2287 409 757 2288 406 758 2289 418 758 2290 419 758 2291 406 759 2292 377 759 2293 418 759 2294 419 760 2295 324 760 2296 406 760 2297 352 761 2298 419 761 2299 418 761 2300 352 762 2301 409 762 2302 419 762 2303 375 763 2304 54 763 2305 371 763 2306 54 764 2307 55 764 2308 371 764 2309 375 765 2310 371 765 2311 306 765 2312 306 766 2313 348 766 2314 375 766 2315 306 767 2316 391 767 2317 348 767 2318 363 182 2319 395 182 2320 326 182 2321 363 182 2322 433 182 2323 395 182 2324 371 182 2325 336 182 2326 395 182 2327 371 182 2328 433 182 2329 392 182 2330 371 768 2331 395 768 2332 433 768 2333 55 182 2334 336 182 2335 371 182 2336 329 769 2337 352 769 2338 308 769 2339 352 770 2340 408 770 2341 308 770 2342 408 771 2343 307 771 2344 308 771 2345 329 772 2346 308 772 2347 320 772 2348 326 773 2349 320 773 2350 363 773 2351 320 774 2352 326 774 2353 329 774 2354 401 775 2355 436 775 2356 330 775 2357 330 776 2358 386 776 2359 341 776 2360 341 777 2361 401 777 2362 330 777 2363 422 778 2364 386 778 2365 402 778 2366 386 779 2367 330 779 2368 402 779 2369 394 780 2370 422 780 2371 402 780 2372 55 781 2373 56 781 2374 336 781 2375 56 782 2376 335 782 2377 336 782 2378 387 783 2379 424 783 2380 340 783 2381 424 784 2382 387 784 2383 379 784 2384 447 785 2385 424 785 2386 379 785 2387 447 786 2388 379 786 2389 435 786 2390 379 787 2391 332 787 2392 435 787 2393 311 788 2394 358 788 2395 317 788 2396 311 789 2397 405 789 2398 358 789 2399 305 790 2400 414 790 2401 313 790 2402 305 791 2403 342 791 2404 414 791 2405 305 792 2406 332 792 2407 342 792 2408 400 793 2409 360 793 2410 56 793 2411 56 794 2412 54 794 2413 400 794 2414 54 795 2415 366 795 2416 400 795 2417 54 796 2418 12 796 2419 366 796 2420 408 797 2421 397 797 2422 393 797 2423 311 798 2424 458 798 2425 405 798 2426 427 799 2427 305 799 2428 20 799 2429 427 800 2430 355 800 2431 305 800 2432 408 801 2433 393 801 2434 307 801 2435 393 802 2436 404 802 2437 307 802 2438 435 803 2439 332 803 2440 305 803 2441 387 804 2442 390 804 2443 379 804 2444 387 805 2445 416 805 2446 390 805 2447 416 806 2448 423 806 2449 390 806 2450 416 807 2451 446 807 2452 423 807 2453 446 808 2454 373 808 2455 423 808 2456 373 809 2457 342 809 2458 423 809 2459 373 810 2460 414 810 2461 342 810 2462 323 811 2463 410 811 2464 436 811 2465 389 812 2466 410 812 2467 323 812 2468 14 813 2469 306 813 2470 392 813 2471 306 814 2472 371 814 2473 392 814 2474 391 815 2475 306 815 2476 14 815 2477 20 816 2478 322 816 2479 17 816 2480 20 817 2481 305 817 2482 322 817 2483 365 818 2484 16 818 2485 421 818 2486 334 819 2487 16 819 2488 426 819 2489 16 820 2490 365 820 2491 426 820 2492 375 821 2493 348 821 2494 54 821 2495 348 822 2496 12 822 2497 54 822 2498 336 823 2499 430 823 2500 395 823 2501 430 824 2502 336 824 2503 335 824 2504 429 825 2505 430 825 2506 335 825 2507 389 826 2508 401 826 2509 317 826 2510 401 827 2511 323 827 2512 436 827 2513 401 828 2514 389 828 2515 323 828 2516 345 829 2517 424 829 2518 447 829 2519 345 830 2520 442 830 2521 424 830 2522 345 831 2523 422 831 2524 442 831 2525 422 832 2526 394 832 2527 442 832 2528 447 833 2529 435 833 2530 365 833 2531 447 834 2532 365 834 2533 421 834 2534 447 835 2535 421 835 2536 345 835 2537 305 836 2538 355 836 2539 435 836 2540 355 837 2541 365 837 2542 435 837 2543 426 838 2544 355 838 2545 334 838 2546 360 839 2547 335 839 2548 56 839 2549 354 182 2550 335 182 2551 360 182 2552 331 840 2553 456 840 2554 462 840 2555 20 841 2556 334 841 2557 427 841 2558 16 842 2559 334 842 2560 20 842 2561 403 843 2562 401 843 2563 415 843 2564 401 844 2565 341 844 2566 415 844 2567 374 845 2568 401 845 2569 359 845 2570 401 846 2571 403 846 2572 359 846 2573 18 847 2574 401 847 2575 16 847 2576 401 848 2577 374 848 2578 16 848 2579 331 182 2580 14 182 2581 439 182 2582 331 849 2583 311 849 2584 13 849 2585 311 850 2586 18 850 2587 13 850 2588 18 851 2589 311 851 2590 317 851 2591 317 852 2592 401 852 2593 18 852 2594 331 853 2595 307 853 2596 404 853 2597 428 854 2598 308 854 2599 307 854 2600 307 855 2601 440 855 2602 428 855 2603 440 182 2604 307 182 2605 331 182 2606 331 856 2607 439 856 2608 440 856 2609 391 857 2610 14 857 2611 11 857 2612 14 858 2613 331 858 2614 13 858 2615 11 859 2616 348 859 2617 391 859 2618 355 860 2619 426 860 2620 365 860 2621 400 861 2622 354 861 2623 360 861 2624 400 862 2625 372 862 2626 354 862 2627 372 863 2628 344 863 2629 354 863 2630 344 864 2631 335 864 2632 354 864 2633 344 865 2634 429 865 2635 335 865 2636 355 866 2637 427 866 2638 334 866 2639 311 867 2640 331 867 2641 321 867 2642 331 868 2643 347 868 2644 321 868 2645 458 869 2646 311 869 2647 321 869 2648 404 870 2649 456 870 2650 331 870 2651 328 871 2652 456 871 2653 404 871 2654 390 872 2655 332 872 2656 379 872 2657 332 873 2658 390 873 2659 423 873 2660 332 874 2661 423 874 2662 342 874 2663 37 875 2664 470 875 2665 31 875 2666 461 876 2667 450 876 2668 462 876 2669 405 877 2670 464 877 2671 358 877 2672 464 878 2673 389 878 2674 358 878 2675 464 879 2676 458 879 2677 459 879 2678 464 880 2679 405 880 2680 458 880 2681 460 881 2682 462 881 2683 450 881 2684 460 882 2685 347 882 2686 462 882 2687 457 883 2688 472 883 2689 461 883 2690 461 884 2691 456 884 2692 457 884 2693 462 885 2694 456 885 2695 461 885 2696 457 886 2697 456 886 2698 328 886 2699 483 887 2700 481 887 2701 438 887 2702 481 888 2703 43 888 2704 438 888 2705 478 889 2706 473 889 2707 34 889 2708 473 890 2709 476 890 2710 34 890 2711 476 891 2712 40 891 2713 34 891 2714 469 892 2715 478 892 2716 36 892 2717 478 893 2718 34 893 2719 36 893 2720 473 894 2721 475 894 2722 476 894 2723 473 895 2724 478 895 2725 475 895 2726 478 896 2727 467 896 2728 475 896 2729 478 897 2730 469 897 2731 467 897 2732 469 898 2733 471 898 2734 467 898 2735 471 899 2736 465 899 2737 467 899 2738 471 900 2739 482 900 2740 465 900 2741 482 901 2742 470 901 2743 465 901 2744 470 902 2745 482 902 2746 31 902 2747 454 903 2748 39 903 2749 476 903 2750 406 904 2751 339 904 2752 474 904 2753 324 905 2754 42 905 2755 339 905 2756 41 906 2757 453 906 2758 470 906 2759 464 907 2760 468 907 2761 483 907 2762 464 908 2763 459 908 2764 468 908 2765 459 909 2766 449 909 2767 468 909 2768 483 910 2769 466 910 2770 481 910 2771 483 911 2772 468 911 2773 466 911 2774 481 912 2775 466 912 2776 43 912 2777 39 913 2778 33 913 2779 476 913 2780 33 914 2781 40 914 2782 476 914 2783 36 915 2784 32 915 2785 469 915 2786 32 916 2787 471 916 2788 469 916 2789 32 917 2790 35 917 2791 471 917 2792 35 918 2793 482 918 2794 471 918 2795 35 919 2796 31 919 2797 482 919 2798 37 920 2799 38 920 2800 41 920 2801 37 921 2802 41 921 2803 470 921 2804 474 922 2805 477 922 2806 472 922 2807 477 923 2808 461 923 2809 472 923 2810 477 924 2811 450 924 2812 461 924 2813 477 925 2814 455 925 2815 450 925 2816 477 926 2817 474 926 2818 479 926 2819 474 927 2820 339 927 2821 479 927 2822 479 928 2823 339 928 2824 42 928 2825 39 929 2826 454 929 2827 42 929 2828 454 930 2829 479 930 2830 42 930 2831 454 931 2832 451 931 2833 455 931 2834 454 932 2835 477 932 2836 479 932 2837 454 933 2838 455 933 2839 477 933 2840 451 934 2841 460 934 2842 455 934 2843 451 935 2844 347 935 2845 460 935 2846 455 936 2847 460 936 2848 450 936 2849 448 937 2850 458 937 2851 321 937 2852 347 938 2853 451 938 2854 321 938 2855 449 939 2856 448 939 2857 452 939 2858 449 940 2859 458 940 2860 448 940 2861 452 941 2862 453 941 2863 449 941 2864 449 942 2865 453 942 2866 468 942 2867 453 943 2868 466 943 2869 468 943 2870 453 944 2871 41 944 2872 466 944 2873 41 945 2874 43 945 2875 466 945 2876 459 946 2877 458 946 2878 449 946 2879 347 947 2880 331 947 2881 462 947 2882 343 948 2883 382 948 2884 319 948 2885 4 949 2886 49 949 2887 44 949 2888 42 950 2889 44 950 2890 49 950 2891 39 951 2892 42 951 2893 49 951 2894 269 952 2895 283 952 2896 285 952 2897 178 953 2898 283 953 2899 269 953 2900 91 954 2901 283 954 2902 178 954 2903

+
+
+
+ + + + -54.17936 -40.25974 125.3859 -57.38965 -35.53417 125.3859 -57.38965 -35.53417 79.0371 18.04209 65.04409 66.9738 18.44659 64.93053 66.73791 18.47225 64.92324 15 -18.04209 -65.04409 66.9738 -18.44659 -64.93053 66.73791 -18.47225 -64.92324 15 -23.49403 63.27938 69.96601 -23.08418 63.43005 68.30575 -30.08734 60.42352 15 -23.49403 63.27938 78.91601 -30.08734 60.42352 79.0371 -21.94408 63.83344 67.02143 -20.37948 64.35003 66.41958 -18.47225 64.92324 15 -21.70596 63.9148 82.01303 -23.01492 63.45521 80.70408 -23.49198 63.28014 79.0371 -28.92978 60.98621 133.4487 -23.3922 63.3171 142.3103 -20.14017 64.42533 134.3371 -30.03421 60.44995 131.41 -18.52465 64.9083 130.8625 -18.47225 64.92324 82.18693 -19.91789 64.4944 82.49215 -6.351152 67.20054 87.05348 -6.836795 67.15287 89.04183 -6.237826 67.21116 114.2949 -8.083147 67.01427 90.44866 -9.560538 66.81951 91.00827 -6.4509 67.19104 114.4395 -9.958945 66.76129 91.03259 -8.88943 66.9121 116.4459 -11.44137 66.52327 119.2432 -11.50216 66.51279 90.64778 -14.14855 66.00052 123.0042 -12.68605 66.29717 120.8699 -13.56674 66.12256 87.05348 -13.56674 66.12256 79.0371 -16.3438 65.49146 79.0371 -16.82086 65.37055 80.70408 -17.39274 65.22072 81.44828 -13.5213 66.13187 87.68331 -18.13161 65.01919 82.01407 -12.81971 66.27145 89.47142 -17.01175 65.32113 127.8924 -13.08109 66.22035 68.38063 -16.37146 65.48455 69.50442 -13.56674 66.12256 70.36898 -16.34175 65.49197 69.96601 -16.34175 65.49197 78.91601 -19.91789 64.4944 66.38987 -18.25763 64.98391 66.79972 -16.97331 65.33113 67.93982 -11.83474 66.45441 66.9738 -10.35735 66.70064 66.41419 -6.228115 67.21206 15 -9.958945 66.76129 66.38987 -8.415726 66.97332 66.77468 -7.098176 67.12575 67.95104 -6.396586 67.19624 69.73914 -6.351152 67.20054 70.36898 -6.228115 67.21206 79.0371 -6.351152 67.20054 79.0371 23.49403 -63.27938 69.96601 23.08418 -63.43005 68.30575 30.08734 -60.42352 15 21.94408 -63.83344 67.02143 20.37948 -64.35003 66.41958 18.47225 -64.92324 15 28.92978 -60.98621 133.4487 23.3922 -63.3171 142.3103 20.14017 -64.42533 134.3371 30.03421 -60.44995 131.41 21.70596 -63.9148 82.81304 19.91789 -64.4944 83.29216 18.45389 -64.92845 82.97875 18.52465 -64.9083 130.8625 23.01492 -63.45521 81.50408 23.37139 -63.32479 80.64452 30.08734 -60.42352 79.0371 23.49403 -63.27938 79.71601 23.49403 -63.27938 79.0371 6.351152 -67.20054 87.05348 6.836795 -67.15287 89.04183 6.237826 -67.21116 114.2949 8.083147 -67.01427 90.44866 9.560538 -66.81951 91.00827 6.4509 -67.19104 114.4395 9.958945 -66.76129 91.03259 8.88943 -66.9121 116.4459 11.44137 -66.52327 119.2432 11.50216 -66.51279 90.64778 14.14855 -66.00052 123.0042 12.68605 -66.29717 120.8699 16.34175 -65.49197 79.71601 16.46446 -65.46122 80.64478 13.56674 -66.12256 79.0371 13.56674 -66.12256 87.05348 16.82086 -65.37055 81.50408 17.39271 -65.22073 82.24826 13.5213 -66.13187 87.68331 18.12982 -65.01969 82.81304 12.81971 -66.27145 89.47142 17.01175 -65.32113 127.8924 13.08109 -66.22035 68.38063 16.37146 -65.48455 69.50442 13.56674 -66.12256 70.36898 16.34175 -65.49197 69.96601 16.34175 -65.49197 79.0371 19.91789 -64.4944 66.38987 18.25763 -64.98391 66.79972 16.97331 -65.33113 67.93982 11.83474 -66.45441 66.9738 10.35735 -66.70064 66.41419 6.228115 -67.21206 15 9.958945 -66.76129 66.38987 8.415726 -66.97332 66.77468 7.098176 -67.12575 67.95104 6.396586 -67.19624 69.73914 6.351152 -67.20054 70.36898 6.228115 -67.21206 79.0371 6.351152 -67.20054 79.0371 -18.47225 -64.92324 79.0371 -13.56674 -66.12256 79.0371 -13.56674 -66.12256 87.05348 -18.52401 -64.9085 130.8614 -13.08109 -66.22035 89.04183 -11.83474 -66.45441 90.44866 -10.35735 -66.70064 91.00827 -11.05462 -66.58863 118.773 -11.94758 -66.43422 119.884 -14.7961 -65.85837 124.0268 -15.61132 -65.66991 125.3859 -17.07484 -65.30467 128.0111 -8.408018 -66.97429 115.9986 -9.958945 -66.76129 91.03259 -6.252565 -67.20979 114.3045 -8.415726 -66.97332 90.64778 -7.098176 -67.12575 89.47142 -6.396586 -67.19624 87.68331 -6.351152 -67.20054 87.05348 -6.228115 -67.21206 79.0371 -13.56674 -66.12256 70.36898 -16.3101 -65.49985 70.36898 -13.5213 -66.13187 69.73914 -16.79574 -65.37701 68.38063 -6.351152 -67.20054 79.0371 -6.351152 -67.20054 70.36898 -6.228115 -67.21206 15 -6.836795 -67.15287 68.38063 -8.083147 -67.01427 66.9738 -9.560538 -66.81951 66.41419 -9.958945 -66.76129 66.38987 -11.50216 -66.51279 66.77468 -12.81971 -66.27145 67.95104 -1.167233 -67.48991 112.2894 -0.3984075 -67.49883 93.80031 -2.45114e-4 -67.5 112.2894 0 -67.5 93.82463 1.169559 -67.48987 112.2894 5.554087 -67.27111 113.8638 4.24417 -67.36644 113.178 1.543219 -67.48236 93.43982 2.90683 -67.43738 112.6674 1.823095 -67.47538 112.3938 2.860769 -67.43935 92.26345 3.562358 -67.40593 90.47535 3.607792 -67.40352 89.84552 -3.607792 -67.40352 89.84552 -3.12215 -67.42776 91.83387 -6.183443 -67.21618 112.2894 -1.875798 -67.47393 93.24069 -6.111258 -67.22278 112.2894 -6.039067 -67.22931 112.2894 -2.534783 -67.45239 112.5594 -3.446495 -67.41195 112.8504 -5.273652 -67.29367 113.7011 -6.11135 -67.22277 112.2962 -3.607792 -67.40352 79.0371 -5.810872 -67.24942 114.0195 3.12215 -67.42776 68.38063 3.607792 -67.40352 70.36898 3.607792 -67.40352 79.0371 1.875798 -67.47393 66.9738 0.3984075 -67.49883 66.41419 0 -67.5 66.38987 -1.543219 -67.48236 66.77468 -2.860769 -67.43935 67.95104 -3.562358 -67.40593 69.73914 -3.607792 -67.40352 70.36898 -64.4944 -19.91789 83.28839 -65.95397 -14.364 123.3469 -66.3454 -12.43134 120.5131 -64.95092 -18.37467 82.90358 -63.88494 -21.79369 82.70446 -62.91778 -24.4459 140.7922 -64.37001 -20.3163 83.26406 -63.3171 -23.3922 142.3103 -64.42533 -20.14017 134.3371 -65.32113 -17.01175 127.8924 -65.66991 -15.61132 125.3859 -63.2845 -23.48025 69.73914 -63.5404 -22.77866 67.95104 -62.94188 -24.38381 15 -63.26763 -23.52568 70.36898 -63.44609 -23.04004 81.29763 -63.26763 -23.52568 79.30928 -62.94188 -24.38381 79.0371 -63.26763 -23.52568 79.0371 -63.99742 -21.46111 66.77468 -64.4944 -19.91789 66.38987 -66.35069 -12.40309 15 -65.37701 -16.79574 68.38063 -66.33957 -12.4624 67.50989 -65.04409 -18.04209 66.9738 -64.6161 -19.51948 66.41419 -65.49985 -16.3101 70.36898 -65.49985 -16.3101 79.0371 -66.12256 -13.56674 79.0371 -66.12256 -13.56674 70.36898 -66.13187 -13.5213 69.73914 -66.27145 -12.81971 67.95104 -65.49985 -16.3101 79.30928 -65.48853 -16.35553 79.9391 -66.12256 -13.56674 87.05348 -65.30931 -17.05712 81.72721 -66.22035 -13.08109 89.04183 -66.33482 -12.4877 89.88534 -67.21618 -6.183443 112.2894 -67.22278 -6.111258 112.2894 -67.49883 -0.3984075 93.80031 -67.47393 -1.875798 93.24069 -67.42776 -3.12215 91.83387 -67.12575 -7.098176 89.47142 -66.97332 -8.415726 90.64778 -67.19624 -6.396586 87.68331 -67.40352 -3.607792 89.84552 -67.20054 -6.351152 87.05348 -66.76129 -9.958945 91.03259 -66.70064 -10.35735 91.00827 -66.45441 -11.83474 90.44866 -67.48991 -1.167233 112.2894 -67.22931 -6.039067 112.2894 -67.45239 -2.534797 112.5594 -67.41081 -3.468934 112.8586 -66.43422 -11.94758 119.884 -66.82285 -9.537212 117.0881 -66.97679 -8.388092 115.9806 -67.11339 -7.214129 114.9977 -67.1584 -6.782433 114.6742 -67.22277 -6.11135 112.2962 -67.25167 -5.784763 114.0033 -67.29368 -5.27362 113.7011 -66.51279 -11.50216 66.77468 -66.76129 -9.958945 66.38987 -67.5 0 15 -66.81951 -9.560538 66.41419 -67.01427 -8.083147 66.9738 -67.15287 -6.836795 68.38063 -67.40593 -3.562358 69.73914 -67.20054 -6.351152 70.36898 -67.20054 -6.351152 79.0371 -67.40352 -3.607792 79.0371 -67.40352 -3.607792 70.36898 -67.43935 2.860769 92.26345 -67.48236 1.543219 93.43982 -67.01427 8.083147 90.44866 -66.81951 9.560538 91.00827 -66.33957 12.4624 89.91257 -66.51279 11.50216 90.64778 -66.34278 12.44536 120.5421 -66.76129 9.958945 91.03259 -67.43739 2.906622 112.6673 -67.36627 4.246928 113.1792 -67.46885 2.050065 112.4406 -67.5 0 93.82463 -67.5 0 112.2894 -67.48987 1.169559 112.2894 -67.27111 5.554144 113.8638 -67.16238 6.74278 114.6455 -66.89817 8.993705 116.5461 -66.51738 11.47558 119.2859 -67.43935 -2.860769 67.95104 -67.48236 -1.543219 66.77468 -67.5 0 66.38987 -66.35069 12.40309 15 -67.49883 0.3984075 66.41419 -67.47393 1.875798 66.9738 -67.42776 3.12215 68.38063 -66.97332 8.415726 66.77468 -66.76129 9.958945 66.38987 -66.70064 10.35735 66.41419 -66.45441 11.83474 66.9738 -66.33482 12.4877 67.53711 -67.40352 3.607792 70.36898 -67.19624 6.396586 69.73914 -67.12575 7.098176 67.95104 -67.40593 3.562358 90.47535 -67.15287 6.836795 89.04183 -67.40352 3.607792 89.84552 -67.20054 6.351152 87.05348 -67.40352 3.607792 79.0371 -67.20054 6.351152 79.0371 -67.20054 6.351152 70.36898 -66.13187 13.5213 87.68331 -66.27145 12.81971 89.47142 -62.91778 24.4459 140.7922 -62.94188 24.38381 79.0371 -66.12256 13.56674 87.05348 -66.12256 13.56674 79.0371 -66.2972 12.68595 120.87 -65.99694 14.16532 123.0301 -63.3171 23.3922 142.3103 -64.40789 20.19592 134.4627 -65.30467 17.07484 128.0111 -64.4944 19.91789 66.38987 -62.94188 24.38381 15 -64.2875 20.5759 66.45066 -63.76339 22.14678 67.17219 -63.35965 23.27671 71.1933 -63.5103 22.86247 71.9922 -63.62635 22.53746 67.53502 -63.33151 23.35317 68.97166 -63.28537 23.47789 70.30688 -64.69395 19.25988 73.48136 -64.4944 19.91789 73.54216 -63.95806 21.57815 73.1323 -65.14099 17.689 72.75983 -65.24583 17.29832 72.397 -66.12256 13.56674 70.36898 -65.45665 16.48261 70.96036 -66.22035 13.08109 68.38063 -65.48794 16.35789 69.62514 -65.33113 16.97331 67.93982 -64.98391 18.25763 66.79972 64.4944 19.91789 83.28839 65.95397 14.364 123.3469 66.3454 12.43134 120.5131 64.95092 18.37467 82.90358 63.88494 21.79369 82.70446 62.91778 24.4459 140.7922 64.37001 20.3163 83.26406 63.3171 23.3922 142.3103 64.42533 20.14017 134.3371 65.32113 17.01175 127.8924 65.66991 15.61132 125.3859 63.2845 23.48025 69.73914 63.5404 22.77866 67.95104 62.94188 24.38381 15 63.26763 23.52568 70.36898 63.44609 23.04004 81.29763 63.26763 23.52568 79.30928 62.94188 24.38381 79.0371 63.26763 23.52568 79.0371 63.99742 21.46111 66.77468 64.4944 19.91789 66.38987 66.35069 12.40309 15 65.37701 16.79574 68.38063 66.33957 12.4624 67.50989 65.04409 18.04209 66.9738 64.6161 19.51948 66.41419 65.49985 16.3101 70.36898 65.49985 16.3101 79.0371 66.12256 13.56674 79.0371 66.12256 13.56674 70.36898 66.13187 13.5213 69.73914 66.27145 12.81971 67.95104 65.49985 16.3101 79.30928 65.48853 16.35553 79.9391 66.12256 13.56674 87.05348 65.30931 17.05712 81.72721 66.22035 13.08109 89.04183 66.33482 12.4877 89.88534 67.21618 6.183443 112.2894 67.22278 6.111258 112.2894 67.49883 0.3984075 93.80031 67.47393 1.875798 93.24069 67.42776 3.12215 91.83387 67.12575 7.098176 89.47142 66.97332 8.415726 90.64778 67.19624 6.396586 87.68331 67.40352 3.607792 89.84552 67.20054 6.351152 87.05348 66.76129 9.958945 91.03259 66.70064 10.35735 91.00827 66.45441 11.83474 90.44866 67.48991 1.167233 112.2894 67.22931 6.039067 112.2894 67.45239 2.534797 112.5594 67.41081 3.468934 112.8586 66.43422 11.94758 119.884 66.82285 9.537212 117.0881 66.97679 8.388092 115.9806 67.11339 7.214129 114.9977 67.1584 6.782433 114.6742 67.22277 6.11135 112.2962 67.25167 5.784763 114.0033 67.29368 5.27362 113.7011 66.51279 11.50216 66.77468 66.76129 9.958945 66.38987 67.5 0 15 66.81951 9.560538 66.41419 67.01427 8.083147 66.9738 67.15287 6.836795 68.38063 67.40593 3.562358 69.73914 67.20054 6.351152 70.36898 67.20054 6.351152 79.0371 67.40352 3.607792 79.0371 67.40352 3.607792 70.36898 67.43935 -2.860769 92.26345 67.48236 -1.543219 93.43982 67.01427 -8.083147 90.44866 66.81951 -9.560538 91.00827 66.33957 -12.4624 89.91257 66.51279 -11.50216 90.64778 66.34278 -12.44536 120.5421 66.76129 -9.958945 91.03259 67.43739 -2.906622 112.6673 67.36627 -4.246928 113.1792 67.46885 -2.050065 112.4406 67.5 0 93.82463 67.5 0 112.2894 67.48987 -1.169559 112.2894 67.27111 -5.554144 113.8638 67.16238 -6.74278 114.6455 66.89817 -8.993705 116.5461 66.51738 -11.47558 119.2859 67.43935 2.860769 67.95104 67.48236 1.543219 66.77468 67.5 0 66.38987 66.35069 -12.40309 15 67.49883 -0.3984075 66.41419 67.47393 -1.875798 66.9738 67.42776 -3.12215 68.38063 66.97332 -8.415726 66.77468 66.76129 -9.958945 66.38987 66.70064 -10.35735 66.41419 66.45441 -11.83474 66.9738 66.33482 -12.4877 67.53711 67.40352 -3.607792 70.36898 67.19624 -6.396586 69.73914 67.12575 -7.098176 67.95104 67.40593 -3.562358 90.47535 67.15287 -6.836795 89.04183 67.40352 -3.607792 89.84552 67.20054 -6.351152 87.05348 67.40352 -3.607792 79.0371 67.20054 -6.351152 79.0371 67.20054 -6.351152 70.36898 66.13187 -13.5213 87.68331 66.27145 -12.81971 89.47142 62.91778 -24.4459 140.7922 62.94188 -24.38381 79.0371 66.12256 -13.56674 87.05348 66.12256 -13.56674 79.0371 66.2972 -12.68595 120.87 65.99694 -14.16532 123.0301 63.3171 -23.3922 142.3103 64.40789 -20.19592 134.4627 65.30467 -17.07484 128.0111 64.4944 -19.91789 66.38987 62.94188 -24.38381 15 64.2875 -20.5759 66.45066 63.76339 -22.14678 67.17219 63.35965 -23.27671 71.1933 63.5103 -22.86247 71.9922 63.62635 -22.53746 67.53502 63.33151 -23.35317 68.97166 63.28537 -23.47789 70.30688 64.69395 -19.25988 73.48136 64.4944 -19.91789 73.54216 63.95806 -21.57815 73.1323 65.14099 -17.689 72.75983 65.24583 -17.29832 72.397 66.12256 -13.56674 70.36898 65.45665 -16.48261 70.96036 66.22035 -13.08109 68.38063 65.48794 -16.35789 69.62514 65.33113 -16.97331 67.93982 64.98391 -18.25763 66.79972 18.47225 64.92324 79.0371 13.56674 66.12256 79.0371 13.56674 66.12256 87.05348 18.52401 64.9085 130.8614 13.08109 66.22035 89.04183 11.83474 66.45441 90.44866 10.35735 66.70064 91.00827 11.05462 66.58863 118.773 11.94758 66.43422 119.884 14.7961 65.85837 124.0268 15.61132 65.66991 125.3859 17.07484 65.30467 128.0111 8.408018 66.97429 115.9986 9.958945 66.76129 91.03259 6.252565 67.20979 114.3045 8.415726 66.97332 90.64778 7.098176 67.12575 89.47142 6.396586 67.19624 87.68331 6.351152 67.20054 87.05348 6.228115 67.21206 79.0371 13.56674 66.12256 70.36898 16.7965 65.37681 72.35877 16.53583 65.44323 71.75149 16.3101 65.49985 70.36898 13.5213 66.13187 69.73914 16.79574 65.37701 68.38063 6.351152 67.20054 79.0371 6.351152 67.20054 70.36898 6.228115 67.21206 15 6.836795 67.15287 68.38063 8.083147 67.01427 66.9738 9.560538 66.81951 66.41419 9.958945 66.76129 66.38987 11.50216 66.51279 66.77468 12.81971 66.27145 67.95104 1.167233 67.48991 112.2894 0.3984075 67.49883 93.80031 2.45114e-4 67.5 112.2894 0 67.5 93.82463 -1.169559 67.48987 112.2894 -5.554087 67.27111 113.8638 -4.24417 67.36644 113.178 -1.543219 67.48236 93.43982 -2.90683 67.43738 112.6674 -1.823095 67.47538 112.3938 -2.860769 67.43935 92.26345 -3.562358 67.40593 90.47535 -3.607792 67.40352 89.84552 3.607792 67.40352 89.84552 3.12215 67.42776 91.83387 6.183443 67.21618 112.2894 1.875798 67.47393 93.24069 6.111258 67.22278 112.2894 6.039067 67.22931 112.2894 2.534783 67.45239 112.5594 3.446495 67.41195 112.8504 5.273652 67.29367 113.7011 6.11135 67.22277 112.2962 3.607792 67.40352 79.0371 5.810872 67.24942 114.0195 -3.12215 67.42776 68.38063 -3.607792 67.40352 70.36898 -3.607792 67.40352 79.0371 -1.875798 67.47393 66.9738 -0.3984075 67.49883 66.41419 0 67.5 66.38987 1.543219 67.48236 66.77468 2.860769 67.43935 67.95104 3.562358 67.40593 69.73914 3.607792 67.40352 70.36898 -60.44995 30.03421 131.41 -59.67585 31.5443 128.6687 -59.26321 32.31287 127.4972 -58.70201 33.32153 126.3137 -60.98621 28.92978 133.4487 -58.37377 33.89326 125.8438 -57.84279 34.79169 125.3859 -57.38965 35.53417 79.0371 -57.84279 -34.79169 125.3859 -58.37377 -33.89326 125.8438 -58.70201 -33.32153 126.3137 -59.26321 -32.31287 127.4972 -59.67585 -31.5443 128.6687 -60.44995 -30.03421 131.41 -60.98621 -28.92978 133.4487 -51.09124 -44.11276 125.3859 -49.8831 -45.47445 79.0371 -49.8831 -45.47445 125.3859 -47.72971 -47.72971 125.3859 -40.67784 -53.86616 79.0371 -44.11276 -51.09124 125.3859 -33.32153 -58.70201 126.3137 -33.89326 -58.37377 125.8438 -30.08734 -60.42352 79.0371 -30.03421 -60.44995 131.41 -31.5443 -59.67585 128.6687 -32.31287 -59.26321 127.4972 -34.79169 -57.84279 125.3859 -40.25974 -54.17936 125.3859 -40.67784 -53.86616 125.3859 -23.3922 -63.3171 142.3103 -28.92978 -60.98621 133.4487 -20.19592 -64.40789 134.4627 34.79169 -57.84279 125.3859 40.25974 -54.17936 125.3859 40.67784 -53.86616 79.0371 33.89326 -58.37377 125.8438 33.32153 -58.70201 126.3137 32.31287 -59.26321 127.4972 31.5443 -59.67585 128.6687 49.8831 -45.47445 125.3859 47.72971 -47.72971 125.3859 49.8831 -45.47445 79.0371 44.11276 -51.09124 125.3859 40.67784 -53.86616 125.3859 57.38965 -35.53417 79.0371 54.17936 -40.25974 125.3859 51.09124 -44.11276 125.3859 60.44995 -30.03421 131.41 59.67585 -31.5443 128.6687 59.26321 -32.31287 127.4972 58.70201 -33.32153 126.3137 60.98621 -28.92978 133.4487 58.37377 -33.89326 125.8438 57.84279 -34.79169 125.3859 57.38965 -35.53417 125.3859 58.37377 33.89326 125.8438 58.70201 33.32153 126.3137 59.26321 32.31287 127.4972 59.67585 31.5443 128.6687 60.44995 30.03421 131.41 60.98621 28.92978 133.4487 49.8831 45.47445 125.3859 51.09124 44.11276 125.3859 49.8831 45.47445 79.0371 54.17936 40.25974 125.3859 57.38965 35.53417 79.0371 57.38965 35.53417 125.3859 57.84279 34.79169 125.3859 47.72971 47.72971 125.3859 40.67784 53.86616 79.0371 44.11276 51.09124 125.3859 33.32153 58.70201 126.3137 33.89326 58.37377 125.8438 30.08734 60.42352 79.0371 30.03421 60.44995 131.41 31.5443 59.67585 128.6687 32.31287 59.26321 127.4972 34.79169 57.84279 125.3859 40.25974 54.17936 125.3859 40.67784 53.86616 125.3859 23.3922 63.3171 142.3103 28.92978 60.98621 133.4487 20.19592 64.40789 134.4627 -34.79169 57.84279 125.3859 -40.25974 54.17936 125.3859 -40.67784 53.86616 79.0371 -33.89326 58.37377 125.8438 -33.32153 58.70201 126.3137 -32.31287 59.26321 127.4972 -31.5443 59.67585 128.6687 -49.8831 45.47445 125.3859 -47.72971 47.72971 125.3859 -49.8831 45.47445 79.0371 -44.11276 51.09124 125.3859 -40.67784 53.86616 125.3859 -57.38965 35.53417 125.3859 -54.17936 40.25974 125.3859 -51.09124 44.11276 125.3859 -19.51948 -64.6161 66.41419 -19.91789 -64.4944 66.38987 -30.08734 -60.42352 15 -21.46111 -63.99742 66.77468 -22.77866 -63.5404 67.95104 -23.48025 -63.2845 69.73914 -23.52568 -63.26763 70.36898 -23.31173 -63.34677 71.71619 -23.03884 -63.44653 72.35961 -19.91789 -64.4944 74.34809 -19.34998 -64.66706 74.29843 -18.19425 -65.00169 73.86145 -17.19825 -65.27228 72.97701 -16.53583 -65.44323 71.75149 -22.68825 -63.57274 72.91138 -21.72584 -63.90804 73.80889 -20.55556 -64.29401 74.28534 19.51948 64.6161 66.41419 19.91789 64.4944 66.38987 30.08734 60.42352 15 23.31173 63.34677 71.71619 22.68825 63.57274 72.91138 23.52568 63.26763 70.36898 21.46111 63.99742 66.77468 22.77866 63.5404 67.95104 23.48025 63.2845 69.73914 19.91789 64.4944 74.34809 19.34998 64.66706 74.29843 18.19425 65.00169 73.86145 17.19825 65.27228 72.97701 21.72584 63.90804 73.80889 21.46014 63.99775 73.96379 20.55556 64.29401 74.28534 40.67784 -53.86616 15 49.8831 -45.47445 15 57.38965 -35.53417 15 -57.38965 -35.53417 15 -49.8831 -45.47445 15 -40.67784 -53.86616 15 -40.67784 53.86616 15 -49.8831 45.47445 15 -57.38965 35.53417 15 57.38965 35.53417 15 49.8831 45.47445 15 40.67784 53.86616 15 -19.91789 61.34759 66.38987 -18.25763 61.86201 66.79972 -16.97331 62.22666 67.93982 -16.37146 62.3877 69.50442 -16.34175 62.39549 69.96601 23.52568 60.05657 70.36898 16.3101 62.40377 70.36898 16.79574 62.27482 72.35733 18.04209 61.92522 73.76416 19.51948 61.47552 74.32377 21.73138 60.72888 72.35853 19.91789 61.34759 74.34809 21.46111 60.82492 73.96328 22.77866 60.34387 72.78691 23.48025 60.07435 70.99881 23.48025 60.07435 69.73914 21.73138 60.72888 68.37943 22.77866 60.34387 67.95104 16.79574 62.27482 68.38063 18.04209 61.92522 66.9738 19.51948 61.47552 66.41419 19.91789 61.34759 66.38987 21.46111 60.82492 66.77468 19.91789 -61.34759 66.38987 18.25763 -61.86201 66.79972 16.97331 -62.22666 67.93982 16.37146 -62.3877 69.50442 16.34175 -62.39549 69.96601 31.78346 60.38682 163.0988 31.55347 60.50772 162.9781 31.28062 60.03408 163.7294 31.06068 60.15168 163.6045 30.87703 60.02382 164.5117 30.66177 60.13317 164.3808 35.32075 63.98178 158.4084 35.3044 63.58478 158.8612 36.09204 63.13451 158.8612 35.45715 64.71302 157.0632 36.68735 64.17587 156.6277 35.53745 64.9111 156.3762 36.72098 64.23468 156.376 35.57065 64.96789 156.081 35.62046 65.02685 155.6084 36.79262 64.36 154.0127 35.74411 64.94372 153.9078 35.75244 64.88057 153.5937 36.72977 64.25007 153.2964 35.75524 64.80696 153.2964 35.3044 61.75672 160.693 34.41383 58.0688 165.5978 34.50201 58.17895 164.8999 32.74604 59.21495 164.4735 34.69798 58.47667 164.3167 33.14228 59.53355 163.8373 34.41276 58.06903 165.6352 32.46221 59.18154 165.236 35.75533 62.54551 144.9456 32.82767 58.84353 169.3912 31.15954 59.0004 172.4238 33.09008 58.29442 171.7254 30.18883 58.64705 174.5521 32.93176 57.50651 174.595 27.41092 59.50946 172.9661 27.29728 59.50672 172.977 27.27444 59.11188 174.2801 27.0103 59.90027 171.6782 29.39522 59.38836 172.724 30.0237 59.77579 170.6217 27.38759 59.10691 174.2946 30.39362 59.90347 169.3411 32.57001 59.0886 168.1951 28.74721 60.16313 170.1029 26.8957 60.13811 170.8685 26.61948 60.3533 170.0945 26.51206 60.34035 170.1445 26.78428 60.12715 170.9089 32.2444 59.3005 167.0055 29.49382 60.26657 168.6383 24.20895 61.86205 162.2315 25.03869 61.33389 165.7647 27.71584 61.11264 165.3099 29.66788 60.6006 163.8167 27.66046 61.33748 162.917 25.9414 61.72346 162.4318 30.44587 61.02665 162.4581 30.02029 60.66045 163.0684 28.1779 61.84941 161.6337 27.89956 61.46664 162.2169 26.2097 62.28138 161.2008 26.06681 61.89195 161.7643 24.20895 62.43314 161.0488 24.20895 62.04775 161.5919 35.25986 61.6238 160.8517 31.55347 64.10159 159.377 33.77477 63.96089 159.2285 33.51736 64.49612 158.7755 31.53376 64.61627 158.8612 33.51281 66.03776 154.8087 33.43301 65.86785 153.3504 32.94177 65.96964 153.3255 33.54008 65.85172 156.2695 33.53008 65.33204 157.6335 34.83745 65.35348 153.4774 31.47326 65.14685 158.2487 31.27499 65.94998 156.7648 31.05907 66.28945 155.0798 30.92849 66.09627 153.2964 33.43893 65.78018 153.0356 30.92411 66.00833 152.971 27.13137 58.80586 175.2901 26.98827 58.49984 176.3 29.9433 58.11686 176.3 32.69881 56.98496 176.3 32.81539 57.24568 175.4475 30.18883 58.64706 174.5521 58.94332 42.59445 158.8612 63.13451 36.09204 158.8612 64.17587 36.68735 156.6277 54.08511 48.61485 158.8612 59.91554 43.29701 156.6277 43.29701 59.91554 156.6277 42.59445 58.94332 158.8612 49.41671 54.97719 156.6277 48.61485 54.08511 158.8612 54.97719 49.41671 156.6277 51.42277 51.42277 158.8612 55.13493 49.5585 154.0127 49.5585 55.13493 154.0127 43.42124 60.08745 154.0127 64.23468 36.72098 156.376 60.08745 43.42124 154.0127 64.36 36.79262 154.0127 64.25007 36.72977 153.2964 59.98481 43.34707 153.2964 43.34707 59.98481 153.2964 49.47385 55.04076 153.2964 52.33138 52.33138 153.2964 55.04076 49.47385 153.2964 40.55106 54.5714 164.3255 58.47667 34.69798 164.3167 61.36949 35.19147 161.1456 61.75672 35.3044 160.693 44.43195 51.46094 164.3255 48.07508 48.07508 164.3255 51.46094 44.43195 164.3255 54.5714 40.55106 164.3255 58.0688 34.41383 165.5978 58.17895 34.50201 164.8999 54.28056 40.33494 164.9363 40.25974 54.17936 165.6352 58.06903 34.41276 165.6352 54.17936 40.25974 165.6352 51.09124 44.11276 165.6352 51.18667 44.19515 164.9363 47.72971 47.72971 165.6352 47.81886 47.81886 164.9363 44.11276 51.09124 165.6352 44.19515 51.18667 164.9363 40.33494 54.28056 164.9363 34.65184 57.92668 167.0055 38.81745 55.22187 167.0055 43.43542 51.66831 167.0055 47.72971 47.72971 167.0055 51.66831 43.43542 167.0055 55.22187 38.81745 167.0055 57.92668 34.65184 167.0055 59.18154 32.46221 165.236 59.3005 32.2444 167.0055 60.02382 30.87703 164.5117 58.2919 33.09074 171.7348 58.84353 32.82767 169.3912 59.0886 32.57001 168.1951 56.86975 34.01958 174.595 57.50651 32.93176 174.595 57.65753 34.49084 170.8728 54.96529 38.6371 170.8728 54.21429 38.10919 174.595 51.42824 43.23361 170.8728 50.72557 42.6429 174.595 47.50794 47.50794 170.8728 46.85883 46.85883 174.595 43.23361 51.42824 170.8728 42.6429 50.72557 174.595 38.6371 54.96529 170.8728 38.10919 54.21429 174.595 34.49084 57.65753 170.8728 34.01958 56.86975 174.595 42.11855 50.42346 176.3 57.24568 32.81539 175.4475 50.42346 42.11855 176.3 56.98496 32.69881 176.3 23.20245 63.53452 143.8368 24.08531 63.26271 142.8331 23.73025 63.24323 142.5781 19.50971 63.88028 144.5726 19.50971 63.93689 145.3225 20.86254 63.89125 145.154 20.67897 63.83751 144.46 22.11971 63.75252 144.6417 21.75208 63.72028 144.0062 22.66269 63.53997 143.2591 29.34397 60.86169 133.7189 30.46326 60.3138 131.6807 30.92411 60.3106 131.9328 29.78696 60.86275 133.9716 32.29798 59.52149 129.1894 32.9263 59.11747 128.0122 33.72265 58.59564 126.8136 35.30989 60.54995 136.648 35.00454 58.68065 129.1401 34.18051 58.30122 126.3319 34.87965 57.8614 125.8786 34.02798 58.31922 126.0903 34.87483 57.8547 125.8436 33.5115 58.62471 126.567 32.60567 59.15124 127.7602 31.90546 59.54679 128.9364 57.8614 34.87965 125.8786 57.8547 34.87483 125.8436 54.22198 40.2914 125.8436 40.2914 54.22198 125.8436 62.54551 35.75533 144.9456 60.24984 35.25805 135.4346 58.68065 35.00454 129.1401 44.14745 51.13142 125.8436 47.76725 47.76725 125.8436 51.13142 44.14745 125.8436 -26.98827 58.49984 176.3 -27.13137 58.80586 175.2901 -27.27444 59.11188 174.2801 -27.0103 59.90027 171.6782 -27.29728 59.50672 172.977 -24.20895 61.86205 162.2315 -25.05305 61.32456 165.8155 -26.51206 60.34035 170.1445 -26.78428 60.12715 170.9089 -24.20895 62.43314 161.0488 -24.20895 62.04775 161.5919 -31.55347 60.50772 162.9781 -30.44587 61.02665 162.4581 -31.55347 64.10159 159.377 -28.1779 61.84941 161.6337 -31.53376 64.61627 158.8612 -26.2097 62.28138 161.2008 -31.46271 65.21908 158.1503 -31.27001 65.96113 156.7341 -31.04291 66.29548 154.8999 -30.92849 66.09627 153.2964 -19.50971 63.93689 145.3225 -20.86254 63.89125 145.154 -22.11971 63.75252 144.6417 -30.92411 66.00833 152.971 -23.20245 63.53452 143.8368 -24.08531 63.26271 142.8331 -29.78696 60.86275 133.9716 -30.92411 60.3106 131.9328 -19.50971 63.88028 144.5726 17.3095 64.65409 137.8018 12.16378 66.07304 125.3859 12.02586 66.10384 125.1164 -17.94182 64.44231 139.6548 15.83876 65.11434 133.7745 -11.03618 66.31406 123.277 -14.01748 65.62306 129.3233 -15.04126 65.34533 131.7533 -7.622066 66.89653 118.1804 -10.43085 66.43339 122.2329 8.211158 66.81163 118.9233 9.70931 66.56651 121.0681 -7.272554 66.94385 117.7663 6.896834 66.99221 117.3432 4.767905 67.21722 115.3744 -1.179931 67.40985 113.6889 4.335757 67.25278 115.0632 1.92587e-4 67.4224 113.5791 1.902435 67.38977 113.8645 -2.389749 67.37091 114.0295 -4.158677 67.26637 114.9443 -4.5666 67.2342 115.2257 19.40907 64.53045 137.0567 14.6184 65.87027 125.3859 17.91459 64.99813 132.9645 -30.87703 60.02382 164.5117 -30.66177 60.13317 164.3808 -31.28062 60.03408 163.7294 -31.06068 60.15168 163.6045 -31.78346 60.38682 163.0988 -35.75524 64.80696 153.2964 -36.72977 64.25007 153.2964 -35.75244 64.88057 153.5937 -36.79262 64.36 154.0127 -35.64012 65.03868 155.426 -36.72098 64.23468 156.376 -35.53733 64.91136 156.3759 -36.68735 64.17587 156.6277 -35.47148 64.75641 156.9391 -35.32075 63.98178 158.4084 -36.09204 63.13451 158.8612 -35.3044 63.58478 158.8612 -35.3044 61.75672 160.693 -34.41383 58.0688 165.5978 -34.41276 58.06903 165.6352 -32.46221 59.18154 165.236 -34.50201 58.17895 164.8999 -32.74604 59.21495 164.4735 -34.69798 58.47667 164.3167 -33.14228 59.53355 163.8373 -35.75533 62.54551 144.9456 -27.38759 59.10691 174.2946 -31.15954 59.0004 172.4238 -30.0237 59.77579 170.6217 -33.09074 58.2919 171.7348 -32.82767 58.84353 169.3912 -29.39522 59.38836 172.724 -27.41092 59.50946 172.9661 -32.93176 57.50651 174.595 -30.18883 58.64705 174.5521 -28.74721 60.16313 170.1029 -30.39362 59.90347 169.3411 -29.49382 60.26657 168.6383 -32.57001 59.0886 168.1951 -32.2444 59.3005 167.0055 -26.8957 60.13811 170.8685 -26.61948 60.3533 170.0945 -27.71584 61.11264 165.3099 -25.9414 61.72346 162.4318 -27.66046 61.33748 162.917 -29.66788 60.6006 163.8167 -30.02029 60.66045 163.0684 -27.89956 61.46664 162.2169 -26.06681 61.89195 161.7643 -35.19147 61.36949 161.1456 -33.86106 63.94409 159.2149 -33.51735 64.49607 158.7754 -33.53008 65.33204 157.6335 -33.43306 65.86829 153.3517 -34.78545 65.37866 153.4737 -33.51281 66.03776 154.8087 -33.54008 65.85172 156.2695 -32.92477 65.9726 153.3248 -33.43893 65.78018 153.0356 -29.93232 58.11977 176.3 -30.18883 58.64706 174.5521 -32.81539 57.24568 175.4475 -29.9433 58.11686 176.3 -32.69881 56.98496 176.3 -42.59445 58.94332 158.8612 -48.61485 54.08511 158.8612 -43.29701 59.91554 156.6277 -64.17587 36.68735 156.6277 -63.13451 36.09204 158.8612 -59.91554 43.29701 156.6277 -58.94332 42.59445 158.8612 -54.97719 49.41671 156.6277 -54.08511 48.61485 158.8612 -49.41671 54.97719 156.6277 -51.42277 51.42277 158.8612 -49.5585 55.13493 154.0127 -55.13493 49.5585 154.0127 -60.08745 43.42124 154.0127 -64.36 36.79262 154.0127 -64.23468 36.72098 156.376 -43.42124 60.08745 154.0127 -43.34707 59.98481 153.2964 -64.25007 36.72977 153.2964 -59.98481 43.34707 153.2964 -55.04076 49.47385 153.2964 -52.33138 52.33138 153.2964 -49.47385 55.04076 153.2964 -61.6238 35.25986 160.8517 -58.47667 34.69798 164.3167 -54.5714 40.55106 164.3255 -61.75672 35.3044 160.693 -51.46094 44.43195 164.3255 -48.07508 48.07508 164.3255 -44.43195 51.46094 164.3255 -40.55106 54.5714 164.3255 -58.0688 34.41383 165.5978 -58.06903 34.41276 165.6352 -54.17936 40.25974 165.6352 -40.33494 54.28056 164.9363 -58.17895 34.50201 164.8999 -40.25974 54.17936 165.6352 -44.11276 51.09124 165.6352 -44.19515 51.18667 164.9363 -47.72971 47.72971 165.6352 -47.81886 47.81886 164.9363 -51.09124 44.11276 165.6352 -51.18667 44.19515 164.9363 -54.28056 40.33494 164.9363 -59.18154 32.46221 165.236 -60.02382 30.87703 164.5117 -59.3005 32.2444 167.0055 -57.92668 34.65184 167.0055 -55.22187 38.81745 167.0055 -51.66831 43.43542 167.0055 -47.72971 47.72971 167.0055 -43.43542 51.66831 167.0055 -38.81745 55.22187 167.0055 -34.65184 57.92668 167.0055 -34.01958 56.86975 174.595 -34.49084 57.65753 170.8728 -38.6371 54.96529 170.8728 -38.10919 54.21429 174.595 -43.23361 51.42824 170.8728 -42.6429 50.72557 174.595 -47.50794 47.50794 170.8728 -46.85883 46.85883 174.595 -51.42824 43.23361 170.8728 -50.72557 42.6429 174.595 -54.96529 38.6371 170.8728 -54.21429 38.10919 174.595 -57.65753 34.49084 170.8728 -56.86975 34.01958 174.595 -58.29442 33.09008 171.7254 -57.50651 32.93176 174.595 -58.84353 32.82767 169.3912 -59.0886 32.57001 168.1951 -57.24568 32.81539 175.4475 -56.98496 32.69881 176.3 -50.42346 42.11855 176.3 -42.11855 50.42346 176.3 -23.73025 63.24324 142.5781 -20.67897 63.83751 144.46 -21.75208 63.72028 144.0062 -22.66269 63.53997 143.2591 -29.34397 60.86169 133.7189 -30.46326 60.3138 131.6807 -32.29798 59.52149 129.1894 -32.9263 59.11747 128.0122 -33.72265 58.59564 126.8136 -34.18051 58.30122 126.3319 -34.87965 57.8614 125.8786 -35.00454 58.68065 129.1401 -35.25805 60.24984 135.4346 -34.02798 58.31922 126.0903 -34.87483 57.8547 125.8436 -33.5115 58.62471 126.567 -32.60567 59.15124 127.7602 -31.90546 59.54679 128.9364 -62.54551 35.75533 144.9456 -40.2914 54.22198 125.8436 -57.8547 34.87483 125.8436 -57.8614 34.87965 125.8786 -54.22198 40.2914 125.8436 -58.68065 35.00454 129.1401 -60.54995 35.30989 136.648 -51.13142 44.14745 125.8436 -47.76725 47.76725 125.8436 -44.14745 51.13142 125.8436 11.58134 66.49624 119.8559 -20.05005 64.31578 138.935 -16.05472 65.51758 128.4193 -12.34145 66.35601 121.0829 14.6184 65.87027 125.3859 0 0 15 67.5 0 15 6.039067 65.72313 112.2894 6.11135 65.71645 112.2962 6.111258 65.71646 112.2894 6.183443 65.7097 112.2894 -23.49403 60.06896 69.96601 -23.08418 60.22766 68.30575 -21.94408 60.65235 67.02143 -20.37948 61.1958 66.41958 -19.91789 61.34759 82.49215 -18.12982 61.89959 82.01303 -19.95183 61.33657 78.91601 -17.39305 62.11064 81.44859 -16.82086 62.26803 80.70408 -16.46451 62.36321 79.84497 -16.34175 62.39549 78.91601 -21.70596 60.73797 82.01303 -23.01492 60.25416 80.70408 -23.37128 60.11683 79.84494 -23.49403 60.06896 78.91601 -18.13739 61.89737 68.17794 -13.56674 63.05706 70.36898 -13.56674 63.05706 87.05348 -9.958945 63.72652 91.03259 -11.50216 63.46613 90.64778 -12.81971 63.21317 89.47142 -13.5213 63.06682 87.68331 -6.351152 64.18656 87.05348 -6.836795 64.13665 89.04183 -8.083147 63.9915 90.44866 -9.560538 63.7875 91.00827 -6.351152 64.18656 70.36898 -9.958945 63.72652 66.38987 -8.415726 63.94861 66.77468 -7.098176 64.10824 67.95104 -6.396586 64.18204 69.73914 -13.08109 63.1596 68.38063 -11.83474 63.40496 66.9738 -10.35735 63.66298 66.41419 -11.7676 63.41746 89.04303 -8.158292 63.98196 68.37943 -3.607792 64.39902 89.84552 -3.607792 64.39902 70.36898 0 64.5 93.82463 -1.543219 64.48154 93.43982 -2.860769 64.43653 92.26345 -3.562358 64.40155 90.47535 3.607792 64.39902 89.84552 3.12215 64.42439 91.83387 1.875798 64.47272 93.24069 0.3984075 64.49877 93.80031 3.607792 64.39902 70.36898 0 64.5 66.38987 1.543219 64.48154 66.77468 2.860769 64.43653 67.95104 3.562358 64.40155 69.73914 -3.12215 64.42439 68.38063 -1.875798 64.47272 66.9738 -0.3984075 64.49877 66.41419 6.351152 64.18656 70.36898 6.351152 64.18656 87.05348 9.958945 63.72652 91.03259 8.415726 63.94861 90.64778 7.098176 64.10824 89.47142 6.396586 64.18204 87.68331 13.56674 63.05706 87.05348 13.08109 63.1596 89.04183 11.83474 63.40496 90.44866 10.35735 63.66298 91.00827 13.56674 63.05706 70.36898 9.958945 63.72652 66.38987 11.50216 63.46613 66.77468 12.81971 63.21317 67.95104 13.5213 63.06682 69.73914 6.836795 64.13665 68.38063 8.083147 63.9915 66.9738 9.560538 63.7875 66.41419 11.7676 63.41746 68.37943 8.158292 63.98196 89.04303 60.13317 30.66177 164.3808 60.03408 31.28062 163.7294 60.15168 31.06068 163.6045 60.38682 31.78346 163.0988 60.50772 31.55347 162.9781 64.80696 35.75524 153.2964 64.88057 35.75244 153.5937 65.03868 35.64012 155.426 64.91136 35.53733 156.3759 64.75641 35.47148 156.9391 63.98178 35.32075 158.4084 63.58478 35.3044 158.8612 59.21495 32.74604 164.4735 59.53355 33.14228 163.8373 59.10691 27.38759 174.2946 59.11188 27.27444 174.2801 59.50672 27.29728 172.977 59.0004 31.15954 172.4238 59.77579 30.0237 170.6217 59.38836 29.39522 172.724 59.50946 27.41092 172.9661 59.90027 27.0103 171.6782 58.64705 30.18883 174.5521 60.16313 28.74721 170.1029 59.90347 30.39362 169.3411 60.26657 29.49382 168.6383 60.13811 26.8957 170.8685 60.12715 26.78428 170.9089 60.34035 26.51206 170.1445 60.3533 26.61948 170.0945 61.32456 25.05305 165.8155 61.11264 27.71584 165.3099 61.72346 25.9414 162.4318 61.33748 27.66046 162.917 60.6006 29.66788 163.8167 61.86205 24.20895 162.2315 60.66045 30.02029 163.0684 61.46664 27.89956 162.2169 61.89195 26.06681 161.7643 62.04775 24.20895 161.5919 61.02665 30.44587 162.4581 61.84941 28.1779 161.6337 62.28138 26.2097 161.2008 62.43314 24.20895 161.0488 63.94409 33.86106 159.2149 64.10159 31.55347 159.377 64.61627 31.53376 158.8612 64.49607 33.51735 158.7754 65.33204 33.53008 157.6335 65.86829 33.43306 153.3517 65.37866 34.78545 153.4737 66.03776 33.51281 154.8087 65.85172 33.54008 156.2695 66.29548 31.04291 154.8999 66.09627 30.92849 153.2964 65.9726 32.92477 153.3248 65.21908 31.46271 158.1503 65.96113 31.27001 156.7341 66.00833 30.92411 152.971 65.78018 33.43893 153.0356 58.11977 29.93232 176.3 58.49984 26.98827 176.3 58.80586 27.13137 175.2901 58.64706 30.18883 174.5521 58.11686 29.9433 176.3 63.24324 23.73025 142.5781 63.26271 24.08531 142.8331 63.53452 23.20245 143.8368 63.93689 19.50971 145.3225 63.88028 19.50971 144.5726 63.83751 20.67897 144.46 63.89125 20.86254 145.154 63.72028 21.75208 144.0062 63.75252 22.11971 144.6417 63.53997 22.66269 143.2591 60.3138 30.46326 131.6807 60.86169 29.34397 133.7189 60.3106 30.92411 131.9328 60.86275 29.78696 133.9716 59.52149 32.29798 129.1894 59.11747 32.9263 128.0122 58.59564 33.72265 126.8136 58.30122 34.18051 126.3319 58.31922 34.02798 126.0903 58.62471 33.5115 126.567 59.15124 32.60567 127.7602 59.54679 31.90546 128.9364 58.49984 -26.98827 176.3 58.80586 -27.13137 175.2901 59.90027 -27.0103 171.6782 59.50672 -27.29728 172.977 59.11188 -27.27444 174.2801 60.12715 -26.78428 170.9089 61.86205 -24.20895 162.2315 61.33389 -25.03869 165.7647 60.34035 -26.51206 170.1445 62.43314 -24.20895 161.0488 62.04775 -24.20895 161.5919 64.61627 -31.53376 158.8612 62.28138 -26.2097 161.2008 61.84941 -28.1779 161.6337 64.10159 -31.55347 159.377 61.02665 -30.44587 162.4581 60.50772 -31.55347 162.9781 65.14685 -31.47326 158.2487 65.94998 -31.27499 156.7648 66.28945 -31.05907 155.0798 66.09627 -30.92849 153.2964 63.75252 -22.11971 144.6417 63.53452 -23.20245 143.8368 66.00833 -30.92411 152.971 63.89125 -20.86254 145.154 63.93689 -19.50971 145.3225 60.3106 -30.92411 131.9328 60.86275 -29.78696 133.9716 63.26271 -24.08531 142.8331 63.88028 -19.50971 144.5726 66.07304 12.16378 125.3859 64.44231 -17.94182 139.6548 66.10384 12.02586 125.1164 65.34533 -15.04126 131.7533 65.62306 -14.01748 129.3233 64.65409 17.3095 137.8018 65.11434 15.83876 133.7745 66.31406 -11.03618 123.277 66.43339 -10.43085 122.2329 66.56651 9.70931 121.0681 66.81163 8.211158 118.9233 66.89653 -7.622066 118.1804 66.94385 -7.272554 117.7663 66.99221 6.896834 117.3432 67.21722 4.767905 115.3744 67.2342 -4.5666 115.2257 67.26637 -4.158677 114.9443 67.25278 4.335757 115.0632 67.37091 -2.389749 114.0295 67.40985 -1.179931 113.6889 67.4224 1.92587e-4 113.5791 67.38977 1.902435 113.8645 64.53045 19.40907 137.0567 64.99813 17.91459 132.9645 65.87027 14.6184 125.3859 60.38682 -31.78346 163.0988 60.03408 -31.28062 163.7294 60.15168 -31.06068 163.6045 60.02382 -30.87703 164.5117 60.13317 -30.66177 164.3808 63.98178 -35.32075 158.4084 63.58478 -35.3044 158.8612 63.13451 -36.09204 158.8612 64.71302 -35.45715 157.0632 64.17587 -36.68735 156.6277 64.9111 -35.53745 156.3762 64.23468 -36.72098 156.376 64.96789 -35.57065 156.081 65.02685 -35.62046 155.6084 64.36 -36.79262 154.0127 64.94372 -35.74411 153.9078 64.88057 -35.75244 153.5937 64.25007 -36.72977 153.2964 64.80696 -35.75524 153.2964 61.75672 -35.3044 160.693 58.0688 -34.41383 165.5978 58.17895 -34.50201 164.8999 59.21495 -32.74604 164.4735 58.47667 -34.69798 164.3167 59.53355 -33.14228 163.8373 58.06903 -34.41276 165.6352 59.18154 -32.46221 165.236 62.54551 -35.75533 144.9456 58.84353 -32.82767 169.3912 59.0004 -31.15954 172.4238 58.29442 -33.09008 171.7254 58.64705 -30.18883 174.5521 57.50651 -32.93176 174.595 59.50946 -27.41092 172.9661 59.38836 -29.39522 172.724 59.77579 -30.0237 170.6217 59.10691 -27.38759 174.2946 59.90347 -30.39362 169.3411 59.0886 -32.57001 168.1951 60.16313 -28.74721 170.1029 60.13811 -26.8957 170.8685 60.3533 -26.61948 170.0945 59.3005 -32.2444 167.0055 60.26657 -29.49382 168.6383 61.11264 -27.71584 165.3099 60.6006 -29.66788 163.8167 61.33748 -27.66046 162.917 61.72346 -25.9414 162.4318 60.66045 -30.02029 163.0684 61.46664 -27.89956 162.2169 61.89195 -26.06681 161.7643 61.6238 -35.25986 160.8517 63.96089 -33.77477 159.2285 64.49612 -33.51736 158.7755 66.03776 -33.51281 154.8087 65.86785 -33.43301 153.3504 65.96964 -32.94177 153.3255 65.85172 -33.54008 156.2695 65.33204 -33.53008 157.6335 65.35348 -34.83745 153.4774 65.78018 -33.43893 153.0356 58.11686 -29.9433 176.3 56.98496 -32.69881 176.3 57.24568 -32.81539 175.4475 58.64706 -30.18883 174.5521 42.59445 -58.94332 158.8612 36.09204 -63.13451 158.8612 36.68735 -64.17587 156.6277 48.61485 -54.08511 158.8612 43.29701 -59.91554 156.6277 59.91554 -43.29701 156.6277 58.94332 -42.59445 158.8612 54.97719 -49.41671 156.6277 54.08511 -48.61485 158.8612 49.41671 -54.97719 156.6277 51.42277 -51.42277 158.8612 49.5585 -55.13493 154.0127 55.13493 -49.5585 154.0127 60.08745 -43.42124 154.0127 36.72098 -64.23468 156.376 43.42124 -60.08745 154.0127 36.79262 -64.36 154.0127 36.72977 -64.25007 153.2964 43.34707 -59.98481 153.2964 59.98481 -43.34707 153.2964 55.04076 -49.47385 153.2964 52.33138 -52.33138 153.2964 49.47385 -55.04076 153.2964 54.5714 -40.55106 164.3255 34.69798 -58.47667 164.3167 35.19147 -61.36949 161.1456 35.3044 -61.75672 160.693 51.46094 -44.43195 164.3255 48.07508 -48.07508 164.3255 44.43195 -51.46094 164.3255 40.55106 -54.5714 164.3255 34.41383 -58.0688 165.5978 34.50201 -58.17895 164.8999 40.33494 -54.28056 164.9363 54.17936 -40.25974 165.6352 34.41276 -58.06903 165.6352 40.25974 -54.17936 165.6352 44.11276 -51.09124 165.6352 44.19515 -51.18667 164.9363 47.72971 -47.72971 165.6352 47.81886 -47.81886 164.9363 51.09124 -44.11276 165.6352 51.18667 -44.19515 164.9363 54.28056 -40.33494 164.9363 57.92668 -34.65184 167.0055 55.22187 -38.81745 167.0055 51.66831 -43.43542 167.0055 47.72971 -47.72971 167.0055 43.43542 -51.66831 167.0055 38.81745 -55.22187 167.0055 34.65184 -57.92668 167.0055 32.46221 -59.18154 165.236 32.2444 -59.3005 167.0055 30.87703 -60.02382 164.5117 33.09074 -58.2919 171.7348 32.82767 -58.84353 169.3912 32.57001 -59.0886 168.1951 34.01958 -56.86975 174.595 32.93176 -57.50651 174.595 34.49084 -57.65753 170.8728 38.6371 -54.96529 170.8728 38.10919 -54.21429 174.595 43.23361 -51.42824 170.8728 42.6429 -50.72557 174.595 47.50794 -47.50794 170.8728 46.85883 -46.85883 174.595 51.42824 -43.23361 170.8728 50.72557 -42.6429 174.595 54.96529 -38.6371 170.8728 54.21429 -38.10919 174.595 57.65753 -34.49084 170.8728 56.86975 -34.01958 174.595 50.42346 -42.11855 176.3 32.81539 -57.24568 175.4475 42.11855 -50.42346 176.3 32.69881 -56.98496 176.3 63.24323 -23.73025 142.5781 63.83751 -20.67897 144.46 63.72028 -21.75208 144.0062 63.53997 -22.66269 143.2591 60.86169 -29.34397 133.7189 60.3138 -30.46326 131.6807 59.52149 -32.29798 129.1894 59.11747 -32.9263 128.0122 58.59564 -33.72265 126.8136 60.54995 -35.30989 136.648 58.68065 -35.00454 129.1401 58.30122 -34.18051 126.3319 57.8614 -34.87965 125.8786 58.31922 -34.02798 126.0903 57.8547 -34.87483 125.8436 58.62471 -33.5115 126.567 59.15124 -32.60567 127.7602 59.54679 -31.90546 128.9364 34.87965 -57.8614 125.8786 34.87483 -57.8547 125.8436 40.2914 -54.22198 125.8436 54.22198 -40.2914 125.8436 35.75533 -62.54551 144.9456 35.25805 -60.24984 135.4346 35.00454 -58.68065 129.1401 51.13142 -44.14745 125.8436 47.76725 -47.76725 125.8436 44.14745 -51.13142 125.8436 66.49624 11.58134 119.8559 65.87027 14.6184 125.3859 66.35601 -12.34145 121.0829 64.31578 -20.05005 138.935 65.51758 -16.05472 128.4193 65.7097 6.183443 112.2894 65.71645 6.11135 112.2962 65.71646 6.111258 112.2894 65.72313 6.039067 112.2894 61.34759 -19.91789 66.38987 61.86201 -18.25763 66.79972 62.22666 -16.97331 67.93982 62.39126 -16.35789 69.62514 62.35843 -16.48261 70.96036 62.13709 -17.29832 72.397 62.027 -17.689 72.75983 61.55735 -19.25988 73.48136 61.34759 -19.91789 73.54216 60.7835 -21.57815 73.1323 60.31217 -22.86247 71.9922 60.15355 -23.27661 71.19358 60.07527 -23.47789 70.30688 60.12387 -23.35317 68.97166 60.43437 -22.53746 67.53502 60.57863 -22.14678 67.17219 61.13004 -20.5759 66.45066 60.36873 -22.71269 69.18289 63.05706 -13.56674 70.36898 63.05706 -13.56674 87.05348 63.72652 -9.958945 91.03259 63.46613 -11.50216 90.64778 63.21317 -12.81971 89.47142 63.06682 -13.5213 87.68331 64.18656 -6.351152 87.05348 64.13665 -6.836795 89.04183 63.9915 -8.083147 90.44866 63.7875 -9.560538 91.00827 64.18656 -6.351152 70.36898 63.72652 -9.958945 66.38987 63.94861 -8.415726 66.77468 64.10824 -7.098176 67.95104 64.18204 -6.396586 69.73914 63.40496 -11.83474 66.9738 63.1596 -13.08109 68.38063 63.66298 -10.35735 66.41419 63.98196 -8.158292 68.37943 63.41746 -11.7676 89.04303 64.39902 -3.607792 89.84552 64.39902 -3.607792 70.36898 64.5 0 93.82463 64.48154 -1.543219 93.43982 64.43653 -2.860769 92.26345 64.40155 -3.562358 90.47535 64.39902 3.607792 89.84552 64.42439 3.12215 91.83387 64.47272 1.875798 93.24069 64.49877 0.3984075 93.80031 64.39902 3.607792 70.36898 64.5 0 66.38987 64.48154 1.543219 66.77468 64.43653 2.860769 67.95104 64.40155 3.562358 69.73914 64.42439 -3.12215 68.38063 64.47272 -1.875798 66.9738 64.49877 -0.3984075 66.41419 64.18656 6.351152 70.36898 64.18656 6.351152 87.05348 63.72652 9.958945 91.03259 63.94861 8.415726 90.64778 64.10824 7.098176 89.47142 64.18204 6.396586 87.68331 63.05706 13.56674 87.05348 63.40496 11.83474 90.44866 63.1596 13.08109 89.04183 63.66298 10.35735 91.00827 63.05706 13.56674 70.36898 63.72652 9.958945 66.38987 63.46613 11.50216 66.77468 63.21317 12.81971 67.95104 63.06682 13.5213 69.73914 64.13665 6.836795 68.38063 63.9915 8.083147 66.9738 63.7875 9.560538 66.41419 63.98196 8.158292 89.04303 63.41746 11.7676 68.37943 62.40377 16.3101 70.36898 62.40377 16.3101 79.30928 61.34759 19.91789 83.28839 61.82735 18.37467 82.90358 62.20373 17.05712 81.72721 62.39188 16.35553 79.9391 60.05657 23.52568 79.30928 60.24456 23.04004 81.29763 60.70655 21.79369 82.70446 61.21681 20.3163 83.26406 60.05657 23.52568 70.36898 61.34759 19.91789 66.38987 60.82492 21.46111 66.77468 60.34387 22.77866 67.95104 60.07435 23.48025 69.73914 62.27482 16.79574 68.38063 61.92522 18.04209 66.9738 61.47552 19.51948 66.41419 61.90197 18.12169 81.29883 60.72888 21.73138 68.37943 -60.02382 -30.87703 164.5117 -60.13317 -30.66177 164.3808 -60.03408 -31.28062 163.7294 -60.15168 -31.06068 163.6045 -60.38682 -31.78346 163.0988 -60.50772 -31.55347 162.9781 -64.80696 -35.75524 153.2964 -64.25007 -36.72977 153.2964 -64.88057 -35.75244 153.5937 -64.36 -36.79262 154.0127 -65.03868 -35.64012 155.426 -64.23468 -36.72098 156.376 -64.91136 -35.53733 156.3759 -64.17587 -36.68735 156.6277 -64.75641 -35.47148 156.9391 -63.98178 -35.32075 158.4084 -63.13451 -36.09204 158.8612 -63.58478 -35.3044 158.8612 -61.75672 -35.3044 160.693 -58.0688 -34.41383 165.5978 -58.06903 -34.41276 165.6352 -59.18154 -32.46221 165.236 -58.17895 -34.50201 164.8999 -59.21495 -32.74604 164.4735 -58.47667 -34.69798 164.3167 -59.53355 -33.14228 163.8373 -62.54551 -35.75533 144.9456 -59.10691 -27.38759 174.2946 -59.11188 -27.27444 174.2801 -59.50672 -27.29728 172.977 -59.0004 -31.15954 172.4238 -59.77579 -30.0237 170.6217 -58.2919 -33.09074 171.7348 -58.84353 -32.82767 169.3912 -59.38836 -29.39522 172.724 -59.50946 -27.41092 172.9661 -59.90027 -27.0103 171.6782 -57.50651 -32.93176 174.595 -58.64705 -30.18883 174.5521 -60.16313 -28.74721 170.1029 -59.90347 -30.39362 169.3411 -60.26657 -29.49382 168.6383 -59.0886 -32.57001 168.1951 -59.3005 -32.2444 167.0055 -60.13811 -26.8957 170.8685 -60.12715 -26.78428 170.9089 -60.34035 -26.51206 170.1445 -60.3533 -26.61948 170.0945 -61.32456 -25.05305 165.8155 -61.11264 -27.71584 165.3099 -61.72346 -25.9414 162.4318 -61.33748 -27.66046 162.917 -60.6006 -29.66788 163.8167 -61.86205 -24.20895 162.2315 -60.66045 -30.02029 163.0684 -61.46664 -27.89956 162.2169 -61.89195 -26.06681 161.7643 -62.04775 -24.20895 161.5919 -61.02665 -30.44587 162.4581 -61.84941 -28.1779 161.6337 -62.28138 -26.2097 161.2008 -62.43314 -24.20895 161.0488 -61.36949 -35.19147 161.1456 -63.94409 -33.86106 159.2149 -64.10159 -31.55347 159.377 -64.61627 -31.53376 158.8612 -64.49607 -33.51735 158.7754 -65.33204 -33.53008 157.6335 -65.86829 -33.43306 153.3517 -65.37866 -34.78545 153.4737 -66.03776 -33.51281 154.8087 -65.85172 -33.54008 156.2695 -66.29548 -31.04291 154.8999 -66.09627 -30.92849 153.2964 -65.9726 -32.92477 153.3248 -65.21908 -31.46271 158.1503 -65.96113 -31.27001 156.7341 -66.00833 -30.92411 152.971 -65.78018 -33.43893 153.0356 -58.11977 -29.93232 176.3 -58.49984 -26.98827 176.3 -58.80586 -27.13137 175.2901 -58.64706 -30.18883 174.5521 -57.24568 -32.81539 175.4475 -58.11686 -29.9433 176.3 -56.98496 -32.69881 176.3 -58.94332 -42.59445 158.8612 -54.08511 -48.61485 158.8612 -59.91554 -43.29701 156.6277 -54.97719 -49.41671 156.6277 -49.41671 -54.97719 156.6277 -51.42277 -51.42277 158.8612 -36.68735 -64.17587 156.6277 -36.09204 -63.13451 158.8612 -43.29701 -59.91554 156.6277 -42.59445 -58.94332 158.8612 -48.61485 -54.08511 158.8612 -55.13493 -49.5585 154.0127 -49.5585 -55.13493 154.0127 -43.42124 -60.08745 154.0127 -36.79262 -64.36 154.0127 -36.72098 -64.23468 156.376 -60.08745 -43.42124 154.0127 -59.98481 -43.34707 153.2964 -36.72977 -64.25007 153.2964 -43.34707 -59.98481 153.2964 -49.47385 -55.04076 153.2964 -52.33138 -52.33138 153.2964 -55.04076 -49.47385 153.2964 -35.25986 -61.6238 160.8517 -34.69798 -58.47667 164.3167 -40.55106 -54.5714 164.3255 -35.3044 -61.75672 160.693 -44.43195 -51.46094 164.3255 -48.07508 -48.07508 164.3255 -51.46094 -44.43195 164.3255 -54.5714 -40.55106 164.3255 -54.28056 -40.33494 164.9363 -34.41383 -58.0688 165.5978 -34.41276 -58.06903 165.6352 -40.25974 -54.17936 165.6352 -34.50201 -58.17895 164.8999 -54.17936 -40.25974 165.6352 -51.09124 -44.11276 165.6352 -51.18667 -44.19515 164.9363 -47.72971 -47.72971 165.6352 -47.81886 -47.81886 164.9363 -44.11276 -51.09124 165.6352 -44.19515 -51.18667 164.9363 -40.33494 -54.28056 164.9363 -32.46221 -59.18154 165.236 -30.87703 -60.02382 164.5117 -32.2444 -59.3005 167.0055 -34.65184 -57.92668 167.0055 -38.81745 -55.22187 167.0055 -43.43542 -51.66831 167.0055 -47.72971 -47.72971 167.0055 -51.66831 -43.43542 167.0055 -55.22187 -38.81745 167.0055 -57.92668 -34.65184 167.0055 -56.86975 -34.01958 174.595 -57.65753 -34.49084 170.8728 -54.96529 -38.6371 170.8728 -54.21429 -38.10919 174.595 -51.42824 -43.23361 170.8728 -50.72557 -42.6429 174.595 -47.50794 -47.50794 170.8728 -46.85883 -46.85883 174.595 -43.23361 -51.42824 170.8728 -42.6429 -50.72557 174.595 -38.6371 -54.96529 170.8728 -38.10919 -54.21429 174.595 -34.49084 -57.65753 170.8728 -34.01958 -56.86975 174.595 -33.09008 -58.29442 171.7254 -32.93176 -57.50651 174.595 -32.82767 -58.84353 169.3912 -32.57001 -59.0886 168.1951 -32.81539 -57.24568 175.4475 -32.69881 -56.98496 176.3 -42.11855 -50.42346 176.3 -50.42346 -42.11855 176.3 -63.24324 -23.73025 142.5781 -63.26271 -24.08531 142.8331 -63.53452 -23.20245 143.8368 -63.93689 -19.50971 145.3225 -63.88028 -19.50971 144.5726 -63.83751 -20.67897 144.46 -63.89125 -20.86254 145.154 -63.72028 -21.75208 144.0062 -63.75252 -22.11971 144.6417 -63.53997 -22.66269 143.2591 -60.3138 -30.46326 131.6807 -60.86169 -29.34397 133.7189 -60.3106 -30.92411 131.9328 -60.86275 -29.78696 133.9716 -59.52149 -32.29798 129.1894 -59.11747 -32.9263 128.0122 -58.59564 -33.72265 126.8136 -58.30122 -34.18051 126.3319 -57.8614 -34.87965 125.8786 -58.68065 -35.00454 129.1401 -60.24984 -35.25805 135.4346 -58.31922 -34.02798 126.0903 -57.8547 -34.87483 125.8436 -58.62471 -33.5115 126.567 -59.15124 -32.60567 127.7602 -59.54679 -31.90546 128.9364 -35.75533 -62.54551 144.9456 -54.22198 -40.2914 125.8436 -34.87483 -57.8547 125.8436 -34.87965 -57.8614 125.8786 -40.2914 -54.22198 125.8436 -35.00454 -58.68065 129.1401 -35.30989 -60.54995 136.648 -44.14745 -51.13142 125.8436 -47.76725 -47.76725 125.8436 -51.13142 -44.14745 125.8436 -58.49984 26.98827 176.3 -58.80586 27.13137 175.2901 -59.90027 27.0103 171.6782 -59.50672 27.29728 172.977 -59.11188 27.27444 174.2801 -60.12715 26.78428 170.9089 -61.86205 24.20895 162.2315 -61.33389 25.03869 165.7647 -60.34035 26.51206 170.1445 -62.43314 24.20895 161.0488 -62.04775 24.20895 161.5919 -64.61627 31.53376 158.8612 -62.28138 26.2097 161.2008 -61.84941 28.1779 161.6337 -64.10159 31.55347 159.377 -61.02665 30.44587 162.4581 -60.50772 31.55347 162.9781 -65.14685 31.47326 158.2487 -65.94998 31.27499 156.7648 -66.28945 31.05907 155.0798 -66.09627 30.92849 153.2964 -63.75252 22.11971 144.6417 -63.53452 23.20245 143.8368 -66.00833 30.92411 152.971 -63.89125 20.86254 145.154 -63.93689 19.50971 145.3225 -60.3106 30.92411 131.9328 -60.86275 29.78696 133.9716 -63.26271 24.08531 142.8331 -63.88028 19.50971 144.5726 -66.07304 -12.16378 125.3859 -64.44231 17.94182 139.6548 -66.10384 -12.02586 125.1164 -65.34533 15.04126 131.7533 -65.62306 14.01748 129.3233 -64.65409 -17.3095 137.8018 -65.11434 -15.83876 133.7745 -66.31406 11.03618 123.277 -66.43339 10.43085 122.2329 -66.56651 -9.70931 121.0681 -66.81163 -8.211158 118.9233 -66.89653 7.622066 118.1804 -66.94385 7.272554 117.7663 -66.99221 -6.896834 117.3432 -67.21722 -4.767905 115.3744 -67.2342 4.5666 115.2257 -67.26637 4.158677 114.9443 -67.25278 -4.335757 115.0632 -67.37091 2.389749 114.0295 -67.40985 1.179931 113.6889 -67.4224 -1.92587e-4 113.5791 -67.38977 -1.902435 113.8645 -64.53045 -19.40907 137.0567 -64.99813 -17.91459 132.9645 -65.87027 -14.6184 125.3859 -60.38682 31.78346 163.0988 -60.03408 31.28062 163.7294 -60.15168 31.06068 163.6045 -60.13317 30.66177 164.3808 -63.98178 35.32075 158.4084 -63.58478 35.3044 158.8612 -64.71302 35.45715 157.0632 -64.9111 35.53745 156.3762 -64.96789 35.57065 156.081 -65.02685 35.62046 155.6084 -64.94372 35.74411 153.9078 -64.88057 35.75244 153.5937 -64.80696 35.75524 153.2964 -59.21495 32.74604 164.4735 -59.53355 33.14228 163.8373 -59.0004 31.15954 172.4238 -58.64705 30.18883 174.5521 -59.50946 27.41092 172.9661 -59.38836 29.39522 172.724 -59.77579 30.0237 170.6217 -59.10691 27.38759 174.2946 -59.90347 30.39362 169.3411 -60.16313 28.74721 170.1029 -60.13811 26.8957 170.8685 -60.3533 26.61948 170.0945 -60.26657 29.49382 168.6383 -61.11264 27.71584 165.3099 -60.6006 29.66788 163.8167 -61.33748 27.66046 162.917 -61.72346 25.9414 162.4318 -60.66045 30.02029 163.0684 -61.46664 27.89956 162.2169 -61.89195 26.06681 161.7643 -63.96089 33.77477 159.2285 -64.49612 33.51736 158.7755 -66.03776 33.51281 154.8087 -65.86785 33.43301 153.3504 -65.96964 32.94177 153.3255 -65.85172 33.54008 156.2695 -65.33204 33.53008 157.6335 -65.35348 34.83745 153.4774 -65.78018 33.43893 153.0356 -58.11686 29.9433 176.3 -58.64706 30.18883 174.5521 -63.24323 23.73025 142.5781 -63.83751 20.67897 144.46 -63.72028 21.75208 144.0062 -63.53997 22.66269 143.2591 -60.86169 29.34397 133.7189 -60.3138 30.46326 131.6807 -59.52149 32.29798 129.1894 -59.11747 32.9263 128.0122 -58.59564 33.72265 126.8136 -58.30122 34.18051 126.3319 -58.31922 34.02798 126.0903 -58.62471 33.5115 126.567 -59.15124 32.60567 127.7602 -59.54679 31.90546 128.9364 -66.49624 -11.58134 119.8559 -65.87027 -14.6184 125.3859 -66.35601 12.34145 121.0829 -64.31578 20.05005 138.935 -65.51758 16.05472 128.4193 -65.7097 -6.183443 112.2894 -65.71645 -6.11135 112.2962 -65.71646 -6.111258 112.2894 -65.72313 -6.039067 112.2894 -61.34759 19.91789 66.38987 -61.86201 18.25763 66.79972 -62.22666 16.97331 67.93982 -62.39126 16.35789 69.62514 -62.35843 16.48261 70.96036 -62.13709 17.29832 72.397 -62.027 17.689 72.75983 -61.55735 19.25988 73.48136 -61.34759 19.91789 73.54216 -60.7835 21.57815 73.1323 -60.31217 22.86247 71.9922 -60.15355 23.27661 71.19358 -60.07527 23.47789 70.30688 -60.12387 23.35317 68.97166 -60.43437 22.53746 67.53502 -60.57863 22.14678 67.17219 -61.13004 20.5759 66.45066 -60.36873 22.71269 69.18289 -63.05706 13.56674 70.36898 -63.05706 13.56674 87.05348 -63.72652 9.958945 91.03259 -63.46613 11.50216 90.64778 -63.21317 12.81971 89.47142 -63.06682 13.5213 87.68331 -64.18656 6.351152 87.05348 -64.13665 6.836795 89.04183 -63.9915 8.083147 90.44866 -63.7875 9.560538 91.00827 -64.18656 6.351152 70.36898 -63.72652 9.958945 66.38987 -63.94861 8.415726 66.77468 -64.10824 7.098176 67.95104 -64.18204 6.396586 69.73914 -63.40496 11.83474 66.9738 -63.1596 13.08109 68.38063 -63.66298 10.35735 66.41419 -63.98196 8.158292 68.37943 -63.41746 11.7676 89.04303 -64.39902 3.607792 89.84552 -64.39902 3.607792 70.36898 -64.5 0 93.82463 -64.48154 1.543219 93.43982 -64.43653 2.860769 92.26345 -64.40155 3.562358 90.47535 -64.39902 -3.607792 89.84552 -64.42439 -3.12215 91.83387 -64.47272 -1.875798 93.24069 -64.49877 -0.3984075 93.80031 -64.39902 -3.607792 70.36898 -64.5 0 66.38987 -64.48154 -1.543219 66.77468 -64.43653 -2.860769 67.95104 -64.40155 -3.562358 69.73914 -64.42439 3.12215 68.38063 -64.47272 1.875798 66.9738 -64.49877 0.3984075 66.41419 -64.18656 -6.351152 70.36898 -64.18656 -6.351152 87.05348 -63.72652 -9.958945 91.03259 -63.94861 -8.415726 90.64778 -64.10824 -7.098176 89.47142 -64.18204 -6.396586 87.68331 -63.05706 -13.56674 87.05348 -63.40496 -11.83474 90.44866 -63.1596 -13.08109 89.04183 -63.66298 -10.35735 91.00827 -63.05706 -13.56674 70.36898 -63.72652 -9.958945 66.38987 -63.46613 -11.50216 66.77468 -63.21317 -12.81971 67.95104 -63.06682 -13.5213 69.73914 -64.13665 -6.836795 68.38063 -63.9915 -8.083147 66.9738 -63.7875 -9.560538 66.41419 -63.98196 -8.158292 89.04303 -63.41746 -11.7676 68.37943 -62.40377 -16.3101 70.36898 -62.40377 -16.3101 79.30928 -61.34759 -19.91789 83.28839 -61.82735 -18.37467 82.90358 -62.20373 -17.05712 81.72721 -62.39188 -16.35553 79.9391 -60.05657 -23.52568 79.30928 -60.24456 -23.04004 81.29763 -60.70655 -21.79369 82.70446 -61.21681 -20.3163 83.26406 -60.05657 -23.52568 70.36898 -61.34759 -19.91789 66.38987 -60.82492 -21.46111 66.77468 -60.34387 -22.77866 67.95104 -60.07435 -23.48025 69.73914 -62.27482 -16.79574 68.38063 -61.92522 -18.04209 66.9738 -61.47552 -19.51948 66.41419 -61.90197 -18.12169 81.29883 -60.72888 -21.73138 68.37943 -31.78346 -60.38682 163.0988 -31.55347 -60.50772 162.9781 -31.28062 -60.03408 163.7294 -31.06068 -60.15168 163.6045 -30.66177 -60.13317 164.3808 -35.32075 -63.98178 158.4084 -35.3044 -63.58478 158.8612 -35.45715 -64.71302 157.0632 -35.53745 -64.9111 156.3762 -35.57065 -64.96789 156.081 -35.62046 -65.02685 155.6084 -35.74411 -64.94372 153.9078 -35.75244 -64.88057 153.5937 -35.75524 -64.80696 153.2964 -32.74604 -59.21495 164.4735 -33.14228 -59.53355 163.8373 -31.15954 -59.0004 172.4238 -30.18883 -58.64705 174.5521 -27.41092 -59.50946 172.9661 -27.29728 -59.50672 172.977 -27.27444 -59.11188 174.2801 -27.0103 -59.90027 171.6782 -29.39522 -59.38836 172.724 -30.0237 -59.77579 170.6217 -27.38759 -59.10691 174.2946 -30.39362 -59.90347 169.3411 -28.74721 -60.16313 170.1029 -26.8957 -60.13811 170.8685 -26.61948 -60.3533 170.0945 -26.51206 -60.34035 170.1445 -26.78428 -60.12715 170.9089 -29.49382 -60.26657 168.6383 -24.20895 -61.86205 162.2315 -25.03869 -61.33389 165.7647 -27.71584 -61.11264 165.3099 -29.66788 -60.6006 163.8167 -27.66046 -61.33748 162.917 -25.9414 -61.72346 162.4318 -30.44587 -61.02665 162.4581 -30.02029 -60.66045 163.0684 -28.1779 -61.84941 161.6337 -27.89956 -61.46664 162.2169 -26.2097 -62.28138 161.2008 -26.06681 -61.89195 161.7643 -24.20895 -62.43314 161.0488 -24.20895 -62.04775 161.5919 -31.55347 -64.10159 159.377 -33.77477 -63.96089 159.2285 -33.51736 -64.49612 158.7755 -31.53376 -64.61627 158.8612 -33.51281 -66.03776 154.8087 -33.43301 -65.86785 153.3504 -32.94177 -65.96964 153.3255 -33.54008 -65.85172 156.2695 -33.53008 -65.33204 157.6335 -34.83745 -65.35348 153.4774 -31.47326 -65.14685 158.2487 -31.27499 -65.94998 156.7648 -31.05907 -66.28945 155.0798 -30.92849 -66.09627 153.2964 -33.43893 -65.78018 153.0356 -30.92411 -66.00833 152.971 -27.13137 -58.80586 175.2901 -26.98827 -58.49984 176.3 -29.9433 -58.11686 176.3 -30.18883 -58.64706 174.5521 -23.20245 -63.53452 143.8368 -24.08531 -63.26271 142.8331 -23.73025 -63.24323 142.5781 -19.50971 -63.88028 144.5726 -19.50971 -63.93689 145.3225 -20.86254 -63.89125 145.154 -20.67897 -63.83751 144.46 -22.11971 -63.75252 144.6417 -21.75208 -63.72028 144.0062 -22.66269 -63.53997 143.2591 -29.34397 -60.86169 133.7189 -30.46326 -60.3138 131.6807 -30.92411 -60.3106 131.9328 -29.78696 -60.86275 133.9716 -32.29798 -59.52149 129.1894 -32.9263 -59.11747 128.0122 -33.72265 -58.59564 126.8136 -34.18051 -58.30122 126.3319 -34.02798 -58.31922 126.0903 -33.5115 -58.62471 126.567 -32.60567 -59.15124 127.7602 -31.90546 -59.54679 128.9364 26.98827 -58.49984 176.3 27.13137 -58.80586 175.2901 27.27444 -59.11188 174.2801 27.0103 -59.90027 171.6782 27.29728 -59.50672 172.977 24.20895 -61.86205 162.2315 25.05305 -61.32456 165.8155 26.51206 -60.34035 170.1445 26.78428 -60.12715 170.9089 24.20895 -62.43314 161.0488 24.20895 -62.04775 161.5919 31.55347 -60.50772 162.9781 30.44587 -61.02665 162.4581 31.55347 -64.10159 159.377 28.1779 -61.84941 161.6337 31.53376 -64.61627 158.8612 26.2097 -62.28138 161.2008 31.46271 -65.21908 158.1503 31.27001 -65.96113 156.7341 31.04291 -66.29548 154.8999 30.92849 -66.09627 153.2964 19.50971 -63.93689 145.3225 20.86254 -63.89125 145.154 22.11971 -63.75252 144.6417 30.92411 -66.00833 152.971 23.20245 -63.53452 143.8368 24.08531 -63.26271 142.8331 29.78696 -60.86275 133.9716 30.92411 -60.3106 131.9328 19.50971 -63.88028 144.5726 -17.3095 -64.65409 137.8018 -12.16378 -66.07304 125.3859 -12.02586 -66.10384 125.1164 17.94182 -64.44231 139.6548 -15.83876 -65.11434 133.7745 11.03618 -66.31406 123.277 14.01748 -65.62306 129.3233 15.04126 -65.34533 131.7533 7.622066 -66.89653 118.1804 10.43085 -66.43339 122.2329 -8.211158 -66.81163 118.9233 -9.70931 -66.56651 121.0681 7.272554 -66.94385 117.7663 -6.896834 -66.99221 117.3432 -4.767905 -67.21722 115.3744 1.179931 -67.40985 113.6889 -4.335757 -67.25278 115.0632 -1.92587e-4 -67.4224 113.5791 -1.902435 -67.38977 113.8645 2.389749 -67.37091 114.0295 4.158677 -67.26637 114.9443 4.5666 -67.2342 115.2257 -19.40907 -64.53045 137.0567 -14.6184 -65.87027 125.3859 -17.91459 -64.99813 132.9645 30.66177 -60.13317 164.3808 31.28062 -60.03408 163.7294 31.06068 -60.15168 163.6045 31.78346 -60.38682 163.0988 35.75524 -64.80696 153.2964 35.75244 -64.88057 153.5937 35.64012 -65.03868 155.426 35.53733 -64.91136 156.3759 35.47148 -64.75641 156.9391 35.32075 -63.98178 158.4084 35.3044 -63.58478 158.8612 32.74604 -59.21495 164.4735 33.14228 -59.53355 163.8373 27.38759 -59.10691 174.2946 31.15954 -59.0004 172.4238 30.0237 -59.77579 170.6217 29.39522 -59.38836 172.724 27.41092 -59.50946 172.9661 30.18883 -58.64705 174.5521 28.74721 -60.16313 170.1029 30.39362 -59.90347 169.3411 29.49382 -60.26657 168.6383 26.8957 -60.13811 170.8685 26.61948 -60.3533 170.0945 27.71584 -61.11264 165.3099 25.9414 -61.72346 162.4318 27.66046 -61.33748 162.917 29.66788 -60.6006 163.8167 30.02029 -60.66045 163.0684 27.89956 -61.46664 162.2169 26.06681 -61.89195 161.7643 33.86106 -63.94409 159.2149 33.51735 -64.49607 158.7754 33.53008 -65.33204 157.6335 33.43306 -65.86829 153.3517 34.78545 -65.37866 153.4737 33.51281 -66.03776 154.8087 33.54008 -65.85172 156.2695 32.92477 -65.9726 153.3248 33.43893 -65.78018 153.0356 29.93232 -58.11977 176.3 30.18883 -58.64706 174.5521 29.9433 -58.11686 176.3 23.73025 -63.24324 142.5781 20.67897 -63.83751 144.46 21.75208 -63.72028 144.0062 22.66269 -63.53997 143.2591 29.34397 -60.86169 133.7189 30.46326 -60.3138 131.6807 32.29798 -59.52149 129.1894 32.9263 -59.11747 128.0122 33.72265 -58.59564 126.8136 34.18051 -58.30122 126.3319 34.02798 -58.31922 126.0903 33.5115 -58.62471 126.567 32.60567 -59.15124 127.7602 31.90546 -59.54679 128.9364 -11.58134 -66.49624 119.8559 20.05005 -64.31578 138.935 16.05472 -65.51758 128.4193 12.34145 -66.35601 121.0829 -14.6184 -65.87027 125.3859 -6.039067 -65.72313 112.2894 -6.11135 -65.71645 112.2962 -6.111258 -65.71646 112.2894 -6.183443 -65.7097 112.2894 23.49403 -60.06896 69.96601 23.08418 -60.22766 68.30575 21.94408 -60.65235 67.02143 20.37948 -61.1958 66.41958 19.91789 -61.34759 83.29216 18.12982 -61.89959 82.81304 19.95183 -61.33657 79.71601 17.39306 -62.11064 82.2486 16.82086 -62.26803 81.50408 16.46393 -62.36336 80.64279 16.34175 -62.39549 79.71601 21.70596 -60.73797 82.81304 23.01492 -60.25416 81.50408 23.37079 -60.11702 80.64675 23.49403 -60.06896 79.71601 18.13739 -61.89737 68.17794 13.56674 -63.05706 70.36898 13.56674 -63.05706 87.05348 9.958945 -63.72652 91.03259 11.50216 -63.46613 90.64778 12.81971 -63.21317 89.47142 13.5213 -63.06682 87.68331 6.351152 -64.18656 87.05348 6.836795 -64.13665 89.04183 8.083147 -63.9915 90.44866 9.560538 -63.7875 91.00827 6.351152 -64.18656 70.36898 9.958945 -63.72652 66.38987 8.415726 -63.94861 66.77468 7.098176 -64.10824 67.95104 6.396586 -64.18204 69.73914 13.08109 -63.1596 68.38063 11.83474 -63.40496 66.9738 10.35735 -63.66298 66.41419 11.7676 -63.41746 89.04303 8.158292 -63.98196 68.37943 3.607792 -64.39902 89.84552 3.607792 -64.39902 70.36898 0 -64.5 93.82463 1.543219 -64.48154 93.43982 2.860769 -64.43653 92.26345 3.562358 -64.40155 90.47535 -3.607792 -64.39902 89.84552 -3.12215 -64.42439 91.83387 -1.875798 -64.47272 93.24069 -0.3984075 -64.49877 93.80031 -3.607792 -64.39902 70.36898 0 -64.5 66.38987 -1.543219 -64.48154 66.77468 -2.860769 -64.43653 67.95104 -3.562358 -64.40155 69.73914 3.12215 -64.42439 68.38063 1.875798 -64.47272 66.9738 0.3984075 -64.49877 66.41419 -6.351152 -64.18656 70.36898 -6.351152 -64.18656 87.05348 -9.958945 -63.72652 91.03259 -8.415726 -63.94861 90.64778 -7.098176 -64.10824 89.47142 -6.396586 -64.18204 87.68331 -13.56674 -63.05706 87.05348 -13.08109 -63.1596 89.04183 -11.83474 -63.40496 90.44866 -10.35735 -63.66298 91.00827 -13.56674 -63.05706 70.36898 -9.958945 -63.72652 66.38987 -11.50216 -63.46613 66.77468 -12.81971 -63.21317 67.95104 -13.5213 -63.06682 69.73914 -6.836795 -64.13665 68.38063 -8.083147 -63.9915 66.9738 -9.560538 -63.7875 66.41419 -11.7676 -63.41746 68.37943 -8.158292 -63.98196 89.04303 -19.91789 -61.34759 66.38987 -21.46111 -60.82492 66.77468 -22.77866 -60.34387 67.95104 -23.48025 -60.07435 69.73914 -23.52568 -60.05657 70.36898 -16.3101 -62.40377 70.36898 -16.79574 -62.27482 68.38063 -18.04209 -61.92522 66.9738 -19.51948 -61.47552 66.41419 -20.3163 -61.21681 74.32377 -19.91789 -61.34759 74.34809 -18.37467 -61.82735 73.96328 -17.05712 -62.20373 72.78691 -16.35553 -62.39188 70.99881 -21.79369 -60.70655 73.76416 -23.04004 -60.24456 72.35733 -32.69881 56.98496 183 -29.9433 58.11686 183 -26.98827 58.49984 183 -42.18662 50.36653 183 -50.36653 42.18662 183 -56.98496 32.69881 183 -58.11686 29.9433 183 -58.49984 26.98827 183 -58.49984 -26.98827 183 -56.98496 -32.69881 183 -58.11686 -29.9433 183 -50.36653 -42.18662 183 -42.18662 -50.36653 183 -32.69881 -56.98496 183 -29.9433 -58.11686 183 -26.98827 -58.49984 183 26.98827 -58.49984 183 32.69881 -56.98496 183 29.9433 -58.11686 183 42.18662 -50.36653 183 50.36653 -42.18662 183 56.98496 -32.69881 183 58.11686 -29.9433 183 58.49984 -26.98827 183 58.49984 26.98827 183 56.98496 32.69881 183 58.11686 29.9433 183 50.36653 42.18662 183 42.18662 50.36653 183 32.69881 56.98496 183 29.9433 58.11686 183 26.98827 58.49984 183 -29.73205 -37 183 -29 -36.26795 183 -30 -38 183 29 -36.26795 183 30 18 183 28 -36 183 27 -36.26795 183 -26.26795 19 183 28 16 183 -27 19.73205 183 27 16.26795 183 -28 20 183 26.26795 17 183 26 18 183 -30 18 183 -29.73205 19 183 29.73205 -39 183 30 -38 183 29.73205 -37 183 -29 19.73205 183 29.73205 19 183 27 -39.73205 183 28 -40 183 29 -39.73205 183 26.26795 -39 183 26 -38 183 -27 -36.26795 183 -28 -36 183 26.26795 19 183 29 19.73205 183 28 20 183 27 19.73205 183 -26.26795 -37 183 26.26795 -37 183 29.73205 17 183 29 16.26795 183 -26 -38 183 -26.26795 -39 183 -27 -39.73205 183 -28 -40 183 -29 -39.73205 183 -26 18 183 -26.26795 17 183 -27 16.26795 183 -28 16 183 -29 16.26795 183 -29.73205 17 183 -29.73205 -39 183 29.73205 -39 184 29 -39.73205 184 28 -40 184 27 -39.73205 184 26.26795 -39 184 26 -38 184 26.26795 -37 184 27 -36.26795 184 28 -36 184 29 -36.26795 184 29.73205 -37 184 30 -38 184 28 -38 184 -26.26795 -39 184 -27 -39.73205 184 -28 -40 184 -29 -39.73205 184 -29.73205 -39 184 -30 -38 184 -29.73205 -37 184 -29 -36.26795 184 -28 -36 184 -27 -36.26795 184 -26.26795 -37 184 -26 -38 184 -28 -38 184 29.73205 17 184 29 16.26795 184 28 16 184 27 16.26795 184 26.26795 17 184 26 18 184 26.26795 19 184 27 19.73205 184 28 20 184 29 19.73205 184 29.73205 19 184 30 18 184 28 18 184 -26.26795 17 184 -27 16.26795 184 -28 16 184 -29 16.26795 184 -29.73205 17 184 -30 18 184 -29.73205 19 184 -29 19.73205 184 -28 20 184 -27 19.73205 184 -26.26795 19 184 -26 18 184 -28 18 184 + + + + + + + + + + -0.827178 -0.5619401 0 0.2702798 0.9627819 -1.81028e-6 -0.2702798 -0.9627819 -1.81028e-6 -0.3625612 0.9319469 -0.004931151 -0.3974622 0.9176186 0 -0.3416614 0.9397881 -0.008119583 -0.3178 0.9480768 -0.01239699 -0.36124 0.9324681 -0.003004074 -0.4105707 0.9071704 0.09205174 -0.3973875 0.9174866 0.01737022 -0.3974425 0.9176265 0.001021325 -0.3626953 0.9317256 -0.01842832 -0.3594902 0.9317896 -0.05034941 -0.2864558 0.9580936 -1.39757e-5 -0.2843801 0.9587117 5.78267e-5 -0.3727341 0.9279382 -3.61695e-4 -0.09761238 0.9952245 1.80584e-5 -0.1101702 0.9939128 3.19116e-4 -0.1300007 0.9915122 0.001872837 -0.09604603 0.9953724 -0.003030717 -0.1443867 0.9895153 0.003469109 -0.1145234 0.99342 -0.001074731 -0.150142 0.9886645 4.51163e-4 -0.1596029 0.987178 0.002574384 -0.2035086 0.9790675 -0.003369331 -0.1802122 0.9836272 -0.001171231 -0.2216053 0.9751365 0 -0.2325434 0.9725779 0.003995478 -0.2421925 0.9701845 0.009215652 -0.2327821 0.972526 0.002409994 -0.2522411 0.9675447 0.01522994 -0.2605139 0.96521 0.0224108 -0.2685986 0.9627771 0.0302484 -0.232066 0.9727001 4.83461e-5 -0.1859777 0.982531 0.006725728 -0.2838422 0.9588043 -0.01131361 -0.2373896 0.9714062 -0.004036128 -0.2201111 0.9754577 -0.005783319 -0.2214018 0.9751816 -0.001449644 -0.2215901 0.9751399 0 -0.2215904 0.9751399 0 -0.221611 0.9751351 3.93723e-4 -0.2985343 0.9543988 -4.34218e-4 -0.2828146 0.9591746 4.8211e-5 -0.2322688 0.9726517 -1.76898e-4 -0.216731 0.9748066 -0.05272561 -0.2215963 0.9750833 -0.01037383 -0.1896864 0.9818335 -0.004700124 -0.1672263 0.9858886 -0.007688581 -0.1837472 0.982961 -0.004980027 -0.150623 0.9885887 -0.002264499 -0.1358331 0.9907311 -0.001170754 -0.1146899 0.9934013 -2.65307e-4 -0.09991556 0.994996 -2.0103e-5 -0.09425622 0.995548 -2.3799e-6 -0.09322512 0.9956451 0 -0.09322541 0.9956451 0 0.3625612 -0.9319469 -0.004931151 0.3416614 -0.9397881 -0.008119583 0.3178 -0.9480768 -0.01239699 0.36124 -0.9324681 -0.003004074 0.3626953 -0.9317256 -0.01842832 0.3594902 -0.9317896 -0.05034941 0.3117874 -0.9500443 0.01430296 0.3727328 -0.9279387 -3.67356e-4 0.2842418 -0.9587527 5.93719e-5 0.2864671 -0.9580901 -1.97171e-5 0.4020345 -0.9152008 0.02785575 0.3981172 -0.917302 0.00774163 0.3974663 -0.9176168 0 0.3974622 -0.9176186 0 0.09761238 -0.9952245 1.80584e-5 0.1101702 -0.9939128 3.19116e-4 0.1300007 -0.9915122 0.001872837 0.09604603 -0.9953724 -0.003030717 0.1443867 -0.9895153 0.003469109 0.1145234 -0.99342 -0.001074731 0.150142 -0.9886645 4.51163e-4 0.1596029 -0.987178 0.002574384 0.2035086 -0.9790675 -0.003369331 0.1802122 -0.9836272 -0.001171231 0.2208675 -0.9752988 0.00312668 0.2225055 -0.9749314 0 0.2340583 -0.972207 0.005506217 0.2412657 -0.9704079 0.009966671 0.2322669 -0.9726493 0.002370357 0.2511762 -0.9677976 0.01668292 0.259177 -0.9655125 0.02475482 0.2613758 -0.9648528 0.02724003 0.2319423 -0.9727296 6.64534e-5 0.1859777 -0.982531 0.006725728 0.2838422 -0.9588043 -0.01131361 0.2373896 -0.9714062 -0.004036128 0.2201111 -0.9754577 -0.005783319 0.2214018 -0.9751816 -0.001449644 0.2215901 -0.9751399 0 0.2215905 -0.9751398 0 0.2215932 -0.9751392 0 0.2985343 -0.9543988 -4.34218e-4 0.2828146 -0.9591746 4.8211e-5 0.2322688 -0.9726517 -1.76898e-4 0.216731 -0.9748066 -0.05272561 0.2215963 -0.9750833 -0.01037383 0.1896864 -0.9818335 -0.004700124 0.1672263 -0.9858886 -0.007688581 0.1837472 -0.982961 -0.004980027 0.150623 -0.9885887 -0.002264499 0.1358331 -0.9907311 -0.001170754 0.1146899 -0.9934013 -2.65307e-4 0.09991556 -0.994996 -2.0103e-5 0.09425622 -0.995548 -2.3799e-6 0.09322512 -0.9956451 0 0.09322541 -0.9956451 0 -0.2374902 -0.97139 0 -0.2375506 -0.9713752 3.88827e-5 -0.2103406 -0.9776226 0.003292798 -0.1910228 -0.9815677 0.00592941 -0.168035 -0.9857314 0.009893596 -0.1707621 -0.9853122 -3.13611e-4 -0.2009855 -0.9795921 -0.002030372 -0.2362546 -0.9716663 -0.006971418 -0.2603991 -0.9654402 -0.01085156 -0.2958783 -0.9550619 -0.0176835 -0.1438068 -0.9896058 3.81156e-4 -0.1505428 -0.9886032 9.14934e-4 -0.1098937 -0.993942 -0.001653611 -0.1355108 -0.9907728 0.002487957 -0.1144517 -0.9934287 5.34606e-4 -0.09988021 -0.9949995 3.37773e-5 -0.0942443 -0.9955492 3.28598e-6 -0.09325563 -0.9956423 -4.5835e-7 -0.2213561 -0.9751918 -0.001550137 -0.2222968 -0.974961 -0.005935072 -0.09322547 -0.9956451 0 -0.09322541 -0.9956451 0 -0.0932253 -0.9956451 0 -0.09764599 -0.9952213 -1.00739e-5 -0.1103516 -0.9938927 -1.56636e-4 -0.1303706 -0.991465 -8.79832e-4 -0.1444875 -0.9895051 -0.001809239 -0.1596897 -0.9871629 -0.002933442 -0.1837494 -0.9829728 -7.64969e-4 -0.2193741 -0.9755978 -0.009170711 -0.2200125 -0.9748407 -0.03578007 -0.2245025 -0.9730954 -0.05180817 -0.2205295 -0.9753249 -0.01039969 -0.008648991 -0.9999626 1.23047e-4 -0.002948999 -0.9999957 5.18546e-7 0.008660793 -0.9999625 7.06395e-7 0.07487374 -0.9971834 -0.004387915 0.05352556 -0.9985654 -0.001459836 0.01180386 -0.9999292 0.001502633 0.03559118 -0.9993641 -0.002168595 0.02230137 -0.999751 -8.64578e-4 0.09221965 -0.9957081 -0.007817924 0.03682613 -0.9993106 0.004707038 0.05315601 -0.9985839 0.002194225 0.09322547 -0.9956451 0 0.09324258 -0.9956435 -4.45767e-7 0.07289505 -0.9973396 4.93607e-6 0.06494444 -0.9978885 8.69356e-4 -0.05711299 -0.9983662 0.001779973 -0.04164421 -0.9991241 0.00410068 -0.0910421 -0.995822 -0.007072508 -0.02014273 -0.9997593 0.008700788 -0.0900914 -0.9958496 -0.01293277 -0.05341416 -0.998571 -0.001739442 -0.05295497 -0.9900161 -0.1306298 -0.05972403 -0.9970319 -0.04858452 -0.06847161 -0.9976181 -0.008358716 -0.08978021 -0.9959565 0.003186821 -0.07287287 -0.9973412 0 -0.07276701 -0.997349 -2.59936e-5 -0.0920909 -0.9957507 3.9758e-7 -0.09105724 -0.9958457 3.90957e-5 -0.08927142 -0.9960075 1.66015e-4 -0.08267688 -0.996576 -9.82587e-4 0.05359178 -0.9985625 -9.16121e-4 0.07287293 -0.9973412 0 0.07287305 -0.9973412 0 0.07287287 -0.9973412 0 0.03901356 -0.9992371 -0.001767694 0.01817905 -0.9998286 -0.003515481 0 -0.9999845 -0.005577325 0.003315448 -0.9999765 -0.00600928 -0.01244992 -0.9999142 -0.004093408 -0.03449916 -0.9994025 -0.002094864 -0.05033701 -0.9987318 -0.001086354 -0.07253473 -0.9973659 0 -0.07908523 -0.9968661 -0.001884222 -0.07287305 -0.9973412 0 -0.9780926 -0.2080597 -0.006792128 -0.9594869 -0.2816117 0.008925914 -0.9499251 -0.3124739 0.001549005 -0.9358966 -0.352271 -0.001662552 -0.9466117 -0.3223763 8.62696e-5 -0.9613147 -0.2754523 -9.14771e-5 -0.9545236 -0.2981304 0.001733362 -0.9695089 -0.2450481 -0.002004086 -0.9736449 -0.2280368 -0.003858506 -0.9392846 -0.343139 -2.14922e-4 -0.9369701 -0.3494095 -9.82433e-5 -0.9345911 -0.3557115 0.002999305 -0.9349058 -0.3548959 0 -0.9349084 -0.3548894 0 -0.9445733 -0.3282998 -7.24737e-4 -0.9517062 -0.3070032 -0.002072334 -0.9618121 -0.2736598 -0.005275189 -0.9742532 -0.223034 -0.03296279 -0.9740914 -0.2261552 -4.92291e-5 -0.9610771 -0.2762193 -0.00580734 -0.9564877 -0.2916603 -0.008101701 -0.975192 -0.2213607 0 -0.9751931 -0.2213562 0 -0.9751918 -0.2213565 -0.00155723 -0.974962 -0.2222923 -0.005938887 -0.9753249 -0.22053 -0.01039433 -0.9744976 -0.2224276 -0.02967363 -0.9751917 -0.2213622 0 -0.975225 -0.2212094 0.001573443 -0.9751161 -0.221695 0 -0.9720614 -0.2346658 0.005356252 -0.9696705 -0.2441238 0.01194226 -0.9681783 -0.2498001 0.01519227 -0.9008226 -0.4030981 0.1613402 -0.9734418 -0.2289343 8.49341e-5 -0.990411 -0.1381526 -8.79817e-5 -0.9957382 -0.09126687 -0.01326322 -0.9997555 -0.02022641 0.008951485 -0.9991242 -0.04164439 0.004101932 -0.9954575 -0.09141665 0.02659815 -0.9967382 -0.08032804 0.007773697 -0.9967862 -0.07977318 0.00733304 -0.997168 -0.07519447 0.001388311 -0.9882057 -0.1089472 0.1076112 -0.7081769 -0.1499081 0.6899371 -0.9950296 -0.09947407 -0.004594862 -0.9857954 -0.1677088 0.009012639 -0.9810078 -0.1933238 0.01580244 -0.9900156 -0.05295944 -0.1306314 -0.9970553 -0.05977511 -0.04803848 -0.2079486 -0.7890436 -0.5780725 -0.9331321 -0.3261033 -0.1513977 -0.9855092 -0.1659279 -0.03521031 -0.992341 -0.1231855 -0.009214341 -0.994417 -0.1054953 -0.002394437 -0.9958357 -0.09115833 0.001230418 -0.9957108 -0.09251743 8.44442e-4 -0.9959204 -0.09023576 3.67367e-4 -0.9966042 -0.0823388 -7.81695e-4 -0.9976088 -0.06861561 -0.00828427 -0.9841175 -0.1775185 7.83375e-6 -0.9872683 -0.1590638 -3.23333e-4 -0.9957278 -0.09226822 -0.003567397 -0.9895216 -0.14374 -0.013637 -0.9918732 -0.1268011 -0.01045048 -0.9946575 -0.1030116 -0.006726324 -0.9971886 -0.07471907 -0.005656719 -0.9972739 -0.07378941 0 -0.9972741 -0.07378637 0 -0.9972738 -0.07379049 0 -0.9972742 -0.07378548 0 -0.9972731 -0.07378476 -0.001505374 -0.9898397 0.1113094 0.08847457 -0.9920361 0.1037012 0.07148826 -0.9841167 0.1775227 -4.45337e-6 -0.987258 0.159127 5.93995e-4 -0.9985648 0.05353665 -0.001460671 -0.999323 0.03679162 -2.70459e-4 -0.9958594 -0.08997797 -0.01296716 -0.9985709 -0.05341589 -0.001739382 -0.9999957 -0.002942264 3.58839e-4 -0.9999626 -0.008653938 0 -0.9999347 0.01142865 0 -0.9999626 0.00865978 -2.2654e-4 -0.9997155 0.0238564 7.46597e-5 -0.9971809 0.0749076 -0.004394412 -0.9952701 0.09675621 -0.008708536 -0.9912603 0.1308062 -0.01711416 -0.9895036 0.1444963 0.001859068 -0.9963723 0.08474355 0.007805168 -0.9654826 0.2531676 -0.06123369 -0.9808682 0.1911551 -0.03684037 -0.9972871 -0.07293194 -0.00997895 -0.995765 -0.07715278 -0.04999607 -0.9980385 -0.06258529 -0.001525342 -0.9999347 -0.0114305 0 -0.9957342 0.09226876 0 -0.9997635 0.004218161 -0.02133351 -0.9995871 0.02324378 -0.01689493 -0.9986863 0.04994177 -0.01146757 -0.9964615 0.08386856 -0.005524337 -0.9907411 0.1357578 -0.001458883 -0.9886058 0.1505264 -7.394e-4 -0.9863818 0.1644721 -1.70054e-4 -0.9836416 0.180137 7.00337e-6 -0.9973269 0.07285165 -0.005636692 -0.9971591 0.07465708 -0.01001471 -0.9962554 0.07022398 -0.05043792 -0.9961441 0.0863924 0.01528114 -0.9960255 0.08641833 0.02156889 -0.9969645 0.07783734 0.001798748 -0.9968987 0.07855516 0.004712522 -0.9972741 0.07378637 0 -0.9972739 0.07378941 0 -0.9972742 0.07378542 0 -0.9972738 0.0737906 0 -0.9972724 0.07379364 -0.001490414 -0.9741129 0.2257152 0.01252228 -0.9580473 0.2865364 0.006509363 -0.9593849 0.2821003 0 -0.9823096 0.187264 1.18847e-6 -0.9825105 0.1862074 -1.264e-5 -0.9800294 0.1988531 4.3413e-5 -0.9393348 0.3428815 -0.009089887 -0.9338982 0.356988 -0.01984536 -0.956436 0.2918259 -0.008227348 -0.9722919 0.2337662 -0.001419961 -0.9618121 0.2736598 -0.005275189 -0.9538798 0.3001767 -0.002730488 -0.9484117 0.3170388 -0.001339673 -0.9388931 0.3442059 0.001424849 -0.943433 0.3315629 -6.40325e-4 -0.9402895 0.3403757 -2.88141e-4 -0.937453 0.348112 -1.20967e-4 -0.9571134 0.2858961 0.0468778 -0.9585486 0.2818536 0.04175257 -0.9503119 0.3108972 0.01582092 -0.9430645 0.332583 0.004270434 -0.9642495 0.26403 0.02260661 -0.9684868 0.2487791 0.01193875 -0.9734916 0.2287233 0 -0.9755515 0.2189627 0.01883226 -0.9745796 0.2239398 -0.006763339 -0.9761222 0.2172068 0.002585649 -0.9731541 0.2283703 -0.02860492 -0.975607 0.2192633 -0.01070708 -0.9758686 0.2183591 -5.68838e-5 -0.9661491 0.2579584 -0.003661811 -0.9595918 0.2813212 -0.006476759 0.9780926 0.2080597 -0.006792128 0.9594869 0.2816117 0.008925914 0.9499251 0.3124739 0.001549005 0.9358966 0.352271 -0.001662552 0.9466117 0.3223763 8.62696e-5 0.9613147 0.2754523 -9.14771e-5 0.9545236 0.2981304 0.001733362 0.9695089 0.2450481 -0.002004086 0.9736449 0.2280368 -0.003858506 0.9392846 0.343139 -2.14922e-4 0.9369701 0.3494095 -9.82433e-5 0.9345911 0.3557115 0.002999305 0.9349058 0.3548959 0 0.9349084 0.3548894 0 0.9445733 0.3282998 -7.24737e-4 0.9517062 0.3070032 -0.002072334 0.9618121 0.2736598 -0.005275189 0.9742532 0.223034 -0.03296279 0.9740914 0.2261552 -4.92291e-5 0.9610771 0.2762193 -0.00580734 0.9564877 0.2916603 -0.008101701 0.975192 0.2213607 0 0.9751931 0.2213562 0 0.9751918 0.2213565 -0.00155723 0.974962 0.2222923 -0.005938887 0.9753249 0.22053 -0.01039433 0.9744976 0.2224276 -0.02967363 0.9751917 0.2213622 0 0.975225 0.2212094 0.001573443 0.9751161 0.221695 0 0.9720614 0.2346658 0.005356252 0.9696705 0.2441238 0.01194226 0.9681783 0.2498001 0.01519227 0.9008226 0.4030981 0.1613402 0.9734418 0.2289343 8.49341e-5 0.990411 0.1381526 -8.79817e-5 0.9957382 0.09126687 -0.01326322 0.9997555 0.02022641 0.008951485 0.9991242 0.04164439 0.004101932 0.9954575 0.09141665 0.02659815 0.9967382 0.08032804 0.007773697 0.9967862 0.07977318 0.00733304 0.997168 0.07519447 0.001388311 0.9882057 0.1089472 0.1076112 0.7081769 0.1499081 0.6899371 0.9950296 0.09947407 -0.004594862 0.9857954 0.1677088 0.009012639 0.9810078 0.1933238 0.01580244 0.9900156 0.05295944 -0.1306314 0.9970553 0.05977511 -0.04803848 0.2079486 0.7890436 -0.5780725 0.9331321 0.3261033 -0.1513977 0.9855092 0.1659279 -0.03521031 0.992341 0.1231855 -0.009214341 0.994417 0.1054953 -0.002394437 0.9958357 0.09115833 0.001230418 0.9957108 0.09251743 8.44442e-4 0.9959204 0.09023576 3.67367e-4 0.9966042 0.0823388 -7.81695e-4 0.9976088 0.06861561 -0.00828427 0.9841175 0.1775185 7.83375e-6 0.9872683 0.1590638 -3.23333e-4 0.9957278 0.09226822 -0.003567397 0.9895216 0.14374 -0.013637 0.9918732 0.1268011 -0.01045048 0.9946575 0.1030116 -0.006726324 0.9971886 0.07471907 -0.005656719 0.9972739 0.07378941 0 0.9972741 0.07378637 0 0.9972738 0.07379049 0 0.9972742 0.07378548 0 0.9972731 0.07378476 -0.001505374 0.9898397 -0.1113094 0.08847457 0.9920361 -0.1037012 0.07148826 0.9841167 -0.1775227 -4.45337e-6 0.987258 -0.159127 5.93995e-4 0.9985648 -0.05353665 -0.001460671 0.999323 -0.03679162 -2.70459e-4 0.9958594 0.08997797 -0.01296716 0.9985709 0.05341589 -0.001739382 0.9999957 0.002942264 3.58839e-4 0.9999626 0.008653938 0 0.9999347 -0.01142865 0 0.9999626 -0.00865978 -2.2654e-4 0.9997155 -0.0238564 7.46597e-5 0.9971809 -0.0749076 -0.004394412 0.9952701 -0.09675621 -0.008708536 0.9912603 -0.1308062 -0.01711416 0.9895036 -0.1444963 0.001859068 0.9963723 -0.08474355 0.007805168 0.9654826 -0.2531676 -0.06123369 0.9808682 -0.1911551 -0.03684037 0.9972871 0.07293194 -0.00997895 0.995765 0.07715278 -0.04999607 0.9980385 0.06258529 -0.001525342 0.9999347 0.0114305 0 0.9957342 -0.09226876 0 0.9997635 -0.004218161 -0.02133351 0.9995871 -0.02324378 -0.01689493 0.9986863 -0.04994177 -0.01146757 0.9964615 -0.08386856 -0.005524337 0.9907411 -0.1357578 -0.001458883 0.9886058 -0.1505264 -7.394e-4 0.9863818 -0.1644721 -1.70054e-4 0.9836416 -0.180137 7.00337e-6 0.9973269 -0.07285165 -0.005636692 0.9971591 -0.07465708 -0.01001471 0.9962554 -0.07022398 -0.05043792 0.9961441 -0.0863924 0.01528114 0.9960255 -0.08641833 0.02156889 0.9969645 -0.07783734 0.001798748 0.9968987 -0.07855516 0.004712522 0.9972741 -0.07378637 0 0.9972739 -0.07378941 0 0.9972742 -0.07378542 0 0.9972738 -0.0737906 0 0.9972724 -0.07379364 -0.001490414 0.9741129 -0.2257152 0.01252228 0.9580473 -0.2865364 0.006509363 0.9593849 -0.2821003 0 0.9823096 -0.187264 1.18847e-6 0.9825105 -0.1862074 -1.264e-5 0.9800294 -0.1988531 4.3413e-5 0.9393348 -0.3428815 -0.009089887 0.9338982 -0.356988 -0.01984536 0.956436 -0.2918259 -0.008227348 0.9722919 -0.2337662 -0.001419961 0.9618121 -0.2736598 -0.005275189 0.9538798 -0.3001767 -0.002730488 0.9484117 -0.3170388 -0.001339673 0.9388931 -0.3442059 0.001424849 0.943433 -0.3315629 -6.40325e-4 0.9402895 -0.3403757 -2.88141e-4 0.937453 -0.348112 -1.20967e-4 0.9571134 -0.2858961 0.0468778 0.9585486 -0.2818536 0.04175257 0.9503119 -0.3108972 0.01582092 0.9430645 -0.332583 0.004270434 0.9642495 -0.26403 0.02260661 0.9684868 -0.2487791 0.01193875 0.9734916 -0.2287233 0 0.9755515 -0.2189627 0.01883226 0.9745796 -0.2239398 -0.006763339 0.9761222 -0.2172068 0.002585649 0.9731541 -0.2283703 -0.02860492 0.975607 -0.2192633 -0.01070708 0.9758686 -0.2183591 -5.68838e-5 0.9661491 -0.2579584 -0.003661811 0.9595918 -0.2813212 -0.006476759 0.2374902 0.97139 0 0.2375506 0.9713752 3.88827e-5 0.2103406 0.9776226 0.003292798 0.1910228 0.9815677 0.00592941 0.168035 0.9857314 0.009893596 0.1707621 0.9853122 -3.13611e-4 0.2009855 0.9795921 -0.002030372 0.2362546 0.9716663 -0.006971418 0.2603991 0.9654402 -0.01085156 0.2958783 0.9550619 -0.0176835 0.1438068 0.9896058 3.81156e-4 0.1505428 0.9886032 9.14934e-4 0.1098937 0.993942 -0.001653611 0.1355108 0.9907728 0.002487957 0.1144517 0.9934287 5.34606e-4 0.09988021 0.9949995 3.37773e-5 0.0942443 0.9955492 3.28598e-6 0.09325563 0.9956423 -4.5835e-7 0.2249801 0.9743634 0 0.2169895 0.9760786 0.01364797 0.2213543 0.9751861 0.003790378 0.2213561 0.9751918 -0.001550137 0.2222968 0.974961 -0.005935072 0.09322547 0.9956451 0 0.09322541 0.9956451 0 0.0932253 0.9956451 0 0.09764599 0.9952213 -1.00739e-5 0.1103516 0.9938927 -1.56636e-4 0.1303706 0.991465 -8.79832e-4 0.1444875 0.9895051 -0.001809239 0.1596897 0.9871629 -0.002933442 0.1837494 0.9829728 -7.64969e-4 0.2193741 0.9755978 -0.009170711 0.2200125 0.9748407 -0.03578007 0.2245025 0.9730954 -0.05180817 0.2205295 0.9753249 -0.01039969 0.008648991 0.9999626 1.23047e-4 0.002948999 0.9999957 5.18546e-7 -0.008660793 0.9999625 7.06395e-7 -0.07487374 0.9971834 -0.004387915 -0.05352556 0.9985654 -0.001459836 -0.01180386 0.9999292 0.001502633 -0.03559118 0.9993641 -0.002168595 -0.02230137 0.999751 -8.64578e-4 -0.09221965 0.9957081 -0.007817924 -0.03682613 0.9993106 0.004707038 -0.05315601 0.9985839 0.002194225 -0.09322547 0.9956451 0 -0.09324258 0.9956435 -4.45767e-7 -0.07289505 0.9973396 4.93607e-6 -0.06494444 0.9978885 8.69356e-4 0.05711299 0.9983662 0.001779973 0.04164421 0.9991241 0.00410068 0.0910421 0.995822 -0.007072508 0.02014273 0.9997593 0.008700788 0.0900914 0.9958496 -0.01293277 0.05341416 0.998571 -0.001739442 0.05295497 0.9900161 -0.1306298 0.05972403 0.9970319 -0.04858452 0.06847161 0.9976181 -0.008358716 0.08978021 0.9959565 0.003186821 0.07287287 0.9973412 0 0.07276701 0.997349 -2.59936e-5 0.0920909 0.9957507 3.9758e-7 0.09105724 0.9958457 3.90957e-5 0.08927142 0.9960075 1.66015e-4 0.08267688 0.996576 -9.82587e-4 -0.05359178 0.9985625 -9.16121e-4 -0.07287293 0.9973412 0 -0.07287305 0.9973412 0 -0.07287287 0.9973412 0 -0.03901356 0.9992371 -0.001767694 -0.01817905 0.9998286 -0.003515481 0 0.9999845 -0.005577325 -0.003315448 0.9999765 -0.00600928 0.01244992 0.9999142 -0.004093408 0.03449916 0.9994025 -0.002094864 0.05033701 0.9987318 -0.001086354 0.07253473 0.9973659 0 0.07908523 0.9968661 -0.001884222 0.07287305 0.9973412 0 -0.8940931 0.4478439 -0.005775451 -0.8863416 0.4629544 -0.008466422 -0.8793001 0.4761375 -0.01115751 -0.9594622 0.2818374 9.09818e-5 -0.9184316 0.3955799 -3.94112e-5 -0.9021648 0.4313766 -0.003614842 -0.872148 0.4890353 -0.01423275 -0.8646643 0.5020414 -0.01761096 -0.8951619 0.4457383 -0.001611173 -0.895163 -0.4457389 0 -0.8533648 -0.5208035 -0.02306711 -0.8646643 -0.5020414 -0.01761096 -0.8721497 -0.4890323 -0.01423239 -0.8792997 -0.4761382 -0.01115751 -0.8863416 -0.4629544 -0.008466422 -0.8940928 -0.4478446 -0.005775392 -0.9430565 -0.3326326 5.13969e-4 -0.9362536 -0.3513249 1.20518e-5 -0.9184314 -0.3955805 -3.94112e-5 -0.9021655 -0.431375 -0.003614842 -0.7802686 -0.6253691 -0.009716331 -0.7980132 -0.6026321 -0.003096282 -0.7480254 -0.6636701 0 -0.72325 -0.6905863 0 -0.6736888 -0.7390006 -0.004658579 -0.6807552 -0.7324813 -0.006596922 -0.4964385 -0.8680687 -0.002352237 -0.4561947 -0.88988 1.37604e-5 -0.4723288 -0.8814223 -5.87389e-4 -0.4850029 -0.8745115 -0.001334667 -0.5074523 -0.8616728 -0.003526866 -0.5565698 -0.8307378 -0.01023519 -0.526432 -0.8502168 -9.96445e-4 -0.599543 -0.8003426 0 -0.6284142 -0.7778789 0 -0.3628717 -0.9316595 -0.0182994 -0.3592197 -0.9318845 -0.05052298 -0.3625416 -0.9311566 -0.03887248 -0.3612085 -0.9324851 -1.04219e-4 -0.3612418 -0.9324722 -9.54951e-5 0.5565698 -0.8307378 -0.01023536 0.526432 -0.8502168 -9.96511e-4 0.5074523 -0.8616728 -0.003526866 0.4964385 -0.8680688 -0.002352237 0.4850029 -0.8745115 -0.001334667 0.3392149 -0.9406666 0.008934974 0.3939716 -0.9191227 -6.40874e-5 0.4561947 -0.88988 1.37604e-5 0.472328 -0.8814226 -5.87219e-4 0.72325 -0.6905863 0 0.6807661 -0.7324899 -0.00401324 0.6736847 -0.7389972 -0.005682826 0.6284142 -0.7778789 0 0.599543 -0.8003426 0 0.7980023 -0.6026229 -0.006168723 0.780303 -0.6253987 -0.001965701 0.7480254 -0.6636701 0 0.8940931 -0.4478439 -0.005775451 0.8863416 -0.4629544 -0.008466422 0.8793001 -0.4761375 -0.01115751 0.9594622 -0.2818374 9.09818e-5 0.9184316 -0.3955799 -3.94112e-5 0.9021648 -0.4313766 -0.003614842 0.872148 -0.4890353 -0.01423275 0.8646643 -0.5020414 -0.01761096 0.8951619 -0.4457383 -0.001611173 0.8535915 -0.5209432 0 0.827178 -0.5619401 0 0.8721497 0.4890323 -0.01423239 0.8792997 0.4761382 -0.01115751 0.8863416 0.4629544 -0.008466422 0.8940928 0.4478446 -0.005775392 0.9430565 0.3326326 5.13969e-4 0.9362536 0.3513249 1.20518e-5 0.9184314 0.3955805 -3.94112e-5 0.9021655 0.431375 -0.003614842 0.7480254 0.6636701 0 0.780303 0.6253987 -0.001965701 0.7980023 0.6026229 -0.006168782 0.827178 0.5619401 0 0.895163 0.4457389 0 0.8533651 0.5208034 -0.02306711 0.8646643 0.5020414 -0.01761096 0.72325 0.6905863 0 0.6736888 0.7390006 -0.004658579 0.6807552 0.7324813 -0.006596922 0.4964385 0.8680687 -0.002352237 0.4561947 0.88988 1.37604e-5 0.4723288 0.8814223 -5.87389e-4 0.4850029 0.8745115 -0.001334667 0.5074523 0.8616728 -0.003526866 0.5565698 0.8307378 -0.01023519 0.526432 0.8502168 -9.96445e-4 0.599543 0.8003426 0 0.6284142 0.7778789 0 0.3628717 0.9316595 -0.0182994 0.3592197 0.9318845 -0.05052298 0.3625416 0.9311566 -0.03887248 0.3612085 0.9324851 -1.04219e-4 0.3612418 0.9324722 -9.54951e-5 -0.5565698 0.8307378 -0.01023536 -0.526432 0.8502168 -9.96511e-4 -0.5074523 0.8616728 -0.003526866 -0.4964385 0.8680688 -0.002352237 -0.4850029 0.8745115 -0.001334667 -0.3117362 0.9500644 0.01408171 -0.3845019 0.9231242 -7.57577e-5 -0.4561947 0.88988 1.37604e-5 -0.472328 0.8814226 -5.87219e-4 -0.72325 0.6905863 0 -0.6807661 0.7324899 -0.00401324 -0.6736847 0.7389972 -0.005682826 -0.6284142 0.7778789 0 -0.599543 0.8003426 0 -0.8535915 0.5209432 0 -0.827178 0.5619401 0 -0.7980023 0.6026229 -0.006168723 -0.780303 0.6253987 -0.001965701 -0.7480254 0.6636701 0 -0.2812415 -0.959637 4.22133e-6 -0.2921183 -0.9563823 -2.37833e-4 -0.3612409 -0.9324696 -0.002380609 -0.3096725 -0.9507398 -0.01403236 -0.3350402 -0.9421588 -0.009214758 -0.355866 -0.9345185 -0.005889534 -0.3891251 -0.921153 0.007675409 -0.3798695 -0.9248704 0.01772135 -0.2907105 -0.9568088 0.002130091 -0.2782477 -0.9605093 -3.87653e-4 -0.2374897 -0.9713881 0.001968562 -0.2503765 -0.9680443 0.01421421 -0.2279739 -0.9736673 0 -0.2138471 -0.9766489 0.02065545 -0.2213543 -0.9751861 0.003790378 -0.3736703 -0.9272153 0.02534341 -0.3624782 -0.9310967 0.04084861 -0.3608969 -0.9315814 0.04369854 -0.318333 -0.9478749 0.0140509 -0.3002761 -0.9538374 0.005341112 0.2812415 0.959637 4.22133e-6 0.2921183 0.9563823 -2.37833e-4 0.3612409 0.9324696 -0.002380609 0.3765388 0.9261554 0.02132529 0.3891251 0.921153 0.007675409 0.3096725 0.9507398 -0.01403236 0.3350402 0.9421588 -0.009214758 0.355866 0.9345185 -0.005889534 0.2907105 0.9568088 0.002130091 0.2782477 0.9605093 -3.87653e-4 0.2374897 0.9713881 0.001968562 0.2503765 0.9680443 0.01421421 0.240417 0.9706377 0.007875621 0.362479 0.9310965 0.04084461 0.3511294 0.934329 0.06113666 0.3609136 0.9316254 0.04260808 0.31524 0.948929 0.01255631 0.3002761 0.9538374 0.005341112 0.3974624 -0.9176185 0 0.5264325 -0.8502171 0 0.5264322 -0.8502172 0 0.6736957 -0.7390089 0 0.6736956 -0.739009 0 0.7980175 -0.6026345 0 0.7980174 -0.6026344 0 0.8951631 -0.4457388 0 0.9350445 -0.3545305 0 0.9371374 -0.3489601 6.64518e-4 -0.934908 -0.3548901 0 -0.8951631 -0.4457388 0 -0.7980175 -0.6026345 0 -0.7980174 -0.6026344 0 -0.6736957 -0.7390089 0 -0.6736956 -0.739009 0 -0.5264322 -0.8502172 0 -0.5264325 -0.8502171 0 -0.3973623 -0.9176618 0 -0.4027113 -0.9153159 -0.004515886 -0.3974624 0.9176185 0 -0.5264325 0.8502171 0 -0.5264322 0.8502172 0 -0.6736957 0.7390089 0 -0.6736956 0.739009 0 -0.7980175 0.6026345 0 -0.7980174 0.6026344 0 -0.8951631 0.4457388 0 -0.9350445 0.3545305 0 -0.9371374 0.3489601 6.64518e-4 0.934908 0.3548901 0 0.8951631 0.4457388 0 0.7980175 0.6026345 0 0.7980174 0.6026344 0 0.6736957 0.7390089 0 0.6736956 0.739009 0 0.5264322 0.8502172 0 0.5264325 0.8502171 0 0.3973623 0.9176618 0 0.4027113 0.9153159 -0.004515886 -0.239669 0 0.9708548 -0.2396656 0 0.9708555 -0.6638656 0 0.7478519 -0.663872 0 0.7478463 -0.9333294 0 0.3590214 -0.9333277 0 0.3590258 -0.9979351 0 0.06423181 -0.997935 0 0.06423228 0.3093097 0.9508601 -0.01388382 0.3041113 0.9520707 -0.0328294 0.3030341 0.9523471 -0.03471732 0.1820964 0.9696074 -0.1634088 0.3065798 0.951702 -0.01650035 0.3201732 0.947355 -0.002779901 0.3443942 0.9388234 0.001810133 0.3466224 0.9379947 -0.004358112 0.3572717 0.9340004 -6.12511e-4 0.3496845 0.9368667 0.001209914 0.3469338 0.937875 0.005241751 0.2751523 0.9613885 0.004846334 0.3092526 0.9506831 0.02376359 0.3030348 0.952347 0.03471559 0.182081 0.9696072 0.1634271 0.3065938 0.9516974 0.01650458 0.3390443 0.9406254 -0.01652288 0.3118158 0.9493421 0.03899353 0.239669 0 0.9708548 0.2396656 0 0.9708555 0.6638656 0 0.7478519 0.663872 0 0.7478463 0.9333294 0 0.3590214 0.9333277 0 0.3590258 0.9979351 0 0.06423181 0.997935 0 0.06423228 0.1335391 0.8157719 0.5627464 0.1200522 0.8195676 0.5602648 0.369751 0.9067608 0.2026556 0.3448712 0.9172899 0.1991056 0.3915711 0.6848796 0.6145015 0.5303818 0.7210922 0.4457817 0.4877804 0.7341691 0.4722987 0.4681341 0.8329975 0.2948998 0.4791276 0.8383847 0.2599001 0.4843785 0.8473942 0.2174874 0.5013672 0.8505138 0.1589258 0.5548353 0.8297348 0.0608136 0.4869621 0.8733927 -0.007286548 0.4923255 0.8557715 -0.1589677 0.4959098 0.8507503 -0.1740621 0.4854797 0.8496754 -0.2058187 0.37509 0.6561369 0.6548219 0.4628214 0.8647462 0.1949629 0.3658441 0.7733761 0.5177331 0.4940934 0.8693656 0.008680939 0.4552541 0.8658698 0.2073965 0.3934304 0.9003623 0.1859042 0.3916815 0.8949133 0.2138126 0.308937 0.7593215 0.572703 0.2159355 0.812539 0.5414355 0.1572021 0.8031915 0.574605 0.4829763 0.8451912 -0.2288792 0.3917821 0.9044549 0.1687251 0.428064 0.8395156 0.3346266 0.3666668 0.8917862 0.2650905 0.004741728 0.9569926 0.2900737 0.004748225 0.957306 0.2890378 0.09073036 0.9604577 0.2632281 0.1148036 0.9702574 0.2131217 0.3732957 0.9141504 0.1580489 0.2479822 0.9368086 0.2467682 0.2502361 0.9301873 0.268577 0.0982691 0.9363462 0.3370445 0.1290724 0.9483924 0.2896414 0.004845976 0.9569929 0.2900709 0.4393041 0.8725008 0.2139024 0.35773 0.926979 0.1128676 0.2260396 0.9607066 0.1610865 0.1352514 0.924173 0.3572275 0.1314294 0.9560149 0.2622248 0.007759153 0.9639093 0.2661179 0.3780418 0.9237717 0.06107652 0.3499314 0.9360976 0.03562623 0.2374393 0.9529656 0.1883589 0.08798718 0.9894905 0.1147478 0.08552825 0.967388 0.2384228 0.00203824 0.9636537 0.2671468 0.007334887 0.9597126 0.2808877 0.1025437 0.9870361 0.1234689 0.3596771 0.9166847 0.1741312 0.3528952 0.9244672 0.1443104 0.3109382 0.9469056 0.08177632 0.1947205 0.9769669 0.08729147 0.0587179 0.9832629 0.1724716 0.366426 0.9279419 0.06823384 0.3381921 0.9392817 0.05810493 0.1220366 0.9755487 0.1827892 0.1114425 0.9772179 0.1806268 -0.01256567 0.9742254 0.2252268 0.1206582 0.8192718 0.5605672 0.3456158 0.916929 0.1994769 0.1081745 0.8173815 0.5658497 0.09500366 0.8229948 0.5600483 0.07977455 0.8154481 0.5733066 0.05591225 0.8222495 0.5663743 0.04716569 0.8161038 0.5759773 0.01876413 0.8202723 0.5716654 0.01468044 0.815453 0.5786373 0.3101087 0.9248908 0.2200222 0.2749436 0.9394317 0.2046314 0.2317196 0.9394589 0.2524342 0.1648581 0.9583798 0.2330883 0.1388004 0.9536961 0.2668303 0.05733895 0.9653793 0.2544702 0.04454702 0.9593876 0.2785519 0.1886852 0.6951028 0.6937074 0.1038269 0.7946683 0.5980989 0.1363479 0.7635092 0.6312392 0.2634668 0.6924473 0.6716412 0.09121924 0.6065192 0.7898188 0.3388147 0.6723292 0.6581627 0.324985 0.6693967 0.6680516 0.324723 0.7053748 0.6300805 0.3285492 0.6972536 0.6370972 0.07240122 0.6644074 0.7438554 0.09166306 0.7066317 0.7016193 0.2073464 0.970326 -0.124399 0.3761669 0.8649242 0.3322719 0.4692899 0.8680394 -0.1620949 0.3199985 0.9246876 0.206286 0.3749735 0.9268598 -0.01804983 0.4678511 0.8745623 -0.1274999 0.3792657 0.9124175 0.1537919 0.4051741 0.9078329 0.1080445 0.4064574 0.8876501 0.2164942 0.3938151 0.8699329 0.296861 0.07390934 0.7573713 0.6487883 0.3294669 0.8151015 0.4765096 0.3982772 0.7380335 0.5446853 0.1037276 0.802007 0.5882393 0.02237838 0.9341912 0.3560703 0.1380848 0.8786395 0.4570835 0.07021564 0.9897031 0.1247307 0.1201506 0.9760686 0.1812568 0.09280246 0.9923584 -0.08131796 0.06399345 0.9916356 -0.112089 0.4698336 0.8579006 -0.2079977 0.3880971 0.8020833 -0.4539197 0.3528698 0.903061 -0.2448752 0.2085181 0.9431672 -0.2587587 0.09254634 0.8987259 -0.4286339 0.06435233 0.9631395 -0.2611918 0.1224651 0.9448786 0.3036555 0.3603001 0.8771286 0.3175362 0.00470525 0.9568381 0.2905835 0.1175913 0.9417518 0.3150807 0.127025 0.9440984 0.3042088 0.3601714 0.8774656 0.3167502 0.3598425 0.8773167 0.3175354 0.7407342 0.4774461 0.4726078 0.6858224 0.5534329 0.4726096 0.4774443 0.7407349 0.4726087 0.4774504 0.7407321 0.4726067 0.5534351 0.6858214 0.4726085 0.5534322 0.6858243 0.4726076 0.6231577 0.6231547 0.472602 0.6290335 0.6634355 0.4051793 0.7047974 0.7048004 0.08072912 0.5407664 0.8389669 0.06088024 0.7047991 0.7047984 0.08073133 0.6259425 0.7756793 0.0807318 0.6259393 0.7756825 0.08072608 0.5450227 0.8345236 0.08075112 0.5232371 0.8116993 0.2595524 0.7407318 0.4774489 0.4726087 0.811755 0.5231651 0.2595228 0.8345232 0.545023 0.08075261 0.8389675 0.5407654 0.06088107 0.8277363 0.5335161 -0.1738198 0.8277287 0.5335218 -0.1738382 0.7663729 0.6184301 -0.1738303 0.7756794 0.6259429 0.08072763 0.7756794 0.6259432 0.08072721 0.6858268 0.5534312 0.4726053 0.639364 0.606212 0.4729912 0.5335295 0.827728 -0.173818 0.5335157 0.8277319 -0.1738415 0.6184179 0.7663823 -0.1738314 0.6184353 0.7663666 -0.1738398 0.6775403 0.7146022 -0.1740195 0.7067835 0.7067822 -0.03027004 0.7145963 0.6775467 -0.1740196 0.7663761 0.6184254 -0.1738329 0.4230648 0.6355397 0.645837 0.4097068 0.6356455 0.6542899 0.6410564 0.4102476 0.6486474 0.6399092 0.4102269 0.6497924 0.6356356 0.4097139 0.6542951 0.4101639 0.6392371 0.6504935 0.4094753 0.6315327 0.6584045 0.4767252 0.59077 0.6509409 0.4757032 0.5935268 0.6491783 0.5177562 0.546071 0.6585857 0.5146641 0.5537672 0.6545708 0.5485309 0.5200935 0.6546882 0.551835 0.5128651 0.6576075 0.5916541 0.4774406 0.6496122 0.5921497 0.4745934 0.6512449 0.6270306 0.4173686 0.6577507 0.8155972 0.5438897 0.1974474 0.5537795 0.8325918 0.01092678 0.5421668 0.8167541 0.1974035 0.8324588 0.5539837 0.01069635 0.8199004 0.5443603 0.1772999 0.7679241 0.6154789 0.1774207 0.7679206 0.615481 0.1774296 0.7208667 0.6699771 0.1774317 0.7208901 0.6699558 0.1774167 0.6699661 0.7208772 0.1774305 0.6699841 0.7208619 0.1774249 0.6154691 0.7679298 0.177431 0.6154787 0.7679227 0.1774283 0.5460812 0.8187467 0.1773391 0.4730439 0.7101378 0.5214728 0.4758712 0.7167734 0.5096887 0.5379573 0.671213 0.5099757 0.5379695 0.6712086 0.5099685 0.5855997 0.6300829 0.5099693 0.5855764 0.6301017 0.5099728 0.6300792 0.5855964 0.5099777 0.6300831 0.5855966 0.5099725 0.6712098 0.5379619 0.509975 0.6712164 0.537957 0.5099716 0.7160211 0.4769615 0.509727 0.7109252 0.4718686 0.5214648 0.4697639 0.8827909 -0.001523077 0.4950443 0.8688642 0.002529084 0.4956301 0.8685258 0.003743946 0.553857 0.8325502 -0.01014101 0.5434432 0.8369454 -0.06474566 0.6241039 0.7786773 0.06446808 0.6095265 0.7921078 -0.03229385 0.6805067 0.7322061 0.0280193 0.6759201 0.7369749 0 0.7324969 0.6807704 0 0.7367646 0.6757324 0.02374267 0.7801566 0.6252815 -0.01946872 0.7919161 0.6093889 0.03891217 0.8315365 0.55318 -0.05038899 0.8386791 0.5445688 -0.007891416 0.8689759 0.4948387 0.003935575 0.8685314 0.4956272 0.002619445 0.8827918 0.469762 -0.001523077 0.8101045 0.5724949 0.126414 0.8552552 0.5141807 0.0644738 0.8683718 0.4955482 0.01904314 0.8342147 0.4883036 0.2562136 0.8204814 0.5191428 0.2393762 0.8143389 0.5287638 0.2392927 0.8143378 0.5287658 0.2392926 0.7695042 0.5921397 0.2392361 0.7695034 0.5921411 0.2392356 0.7155691 0.6562984 0.2392349 0.715566 0.6563012 0.2392361 0.656302 0.7155658 0.2392347 0.6562973 0.7155695 0.2392366 0.5921393 0.7695041 0.2392379 0.5921374 0.7695068 0.2392341 0.528765 0.8143384 0.2392915 0.5287647 0.8143384 0.2392926 0.5188475 0.8206684 0.239376 0.4883412 0.8342562 0.2560068 0.5141814 0.8552549 0.06447213 0.4955377 0.8683778 0.0190438 0.8882982 0.4521313 0.08064496 0.8359658 0.5428038 0.08077907 0.8359624 0.5428093 0.08077871 0.7899293 0.6078569 0.08075773 0.7899292 0.607857 0.08075761 0.7345626 0.673718 0.08075761 0.7345606 0.6737202 0.08075815 0.6737209 0.73456 0.08075743 0.6737172 0.7345633 0.08075857 0.6078602 0.7899269 0.08075624 0.607854 0.7899316 0.08075791 0.5428071 0.8359636 0.08078014 0.5428038 0.8359661 0.08077728 0.5299715 0.8441561 0.08081364 0.4828884 0.8629609 0.1487188 0.5429103 0.7794379 0.31261 0.4792882 0.8188163 0.3159473 0.8188039 0.4793062 0.315952 0.7788758 0.5057426 0.3709137 0.569162 0.4379845 0.6958622 0.6689023 0.6689102 0.3242359 0.781246 0.544195 0.3057888 0.7788323 0.5438154 0.3125461 0.6219181 0.5704009 0.5365266 0.64025 0.6980715 0.3205873 0.5446377 0.7809082 0.3058633 0.4379692 0.5691764 0.6958602 0.5057364 0.7788835 0.3709061 0.08370447 0.9779698 -0.1912292 0.0242545 0.9968696 -0.07525146 0.02828818 0.9960128 -0.08460664 0.07062256 0.9929134 -0.0955795 0.07006496 0.9933906 -0.09091824 0.1129184 0.9868831 -0.1153747 0.1151235 0.988481 -0.09824436 0.1731204 0.9730084 -0.1525909 0.2436742 0.9690206 -0.04027628 0.2751333 0.957807 -0.08311182 0.3393372 0.9383541 -0.06589269 0.3286302 0.9418818 -0.06972008 0.3176598 0.9468554 -0.05057007 0.1156363 0.9731422 -0.1990545 0.1118592 0.9733447 -0.2002193 0.1084525 0.9749363 -0.1942609 0.09258371 0.974716 -0.2033645 0.03237468 0.9647217 -0.261274 0.09385919 0.9618586 -0.2569408 0.1329034 0.9570806 -0.2575531 0.2317687 0.9388298 -0.2547193 0.3988804 0.8851229 -0.2396916 0.4125635 0.8803923 -0.2338821 0.3888183 0.8896297 -0.2395402 0.3732446 0.8965765 -0.2384097 0.3482758 0.9099556 -0.2251331 0.40227 0.8841788 -0.2375015 0.454419 0.8845123 -0.1055533 0.4097611 0.8838574 -0.2255927 0.4810618 0.8739241 -0.06954413 0.4617638 0.8852016 -0.05650132 0.4573421 0.8863299 -0.07250851 0.4367892 0.8979682 -0.05355745 0.4187754 0.9044548 -0.08117109 0.4018269 0.9138593 -0.05828082 0.3867048 0.9188326 -0.07878029 0.3726805 0.9262528 -0.05625939 0.3465377 0.934693 -0.07912319 0.4249389 0.882261 -0.2025895 0.3792548 0.9092103 -0.1717625 0.3661429 0.9073411 -0.2065713 0.3225209 0.9318285 -0.166361 0.2748581 0.9349319 -0.2244002 0.240309 0.9542651 -0.1778478 0.2028653 0.9543389 -0.2192785 0.1768761 0.9680764 -0.1776034 0.1248699 0.9683737 -0.2160095 0.8082535 0.5422549 -0.2295346 0.5274279 0.8182756 -0.2285715 0.5420657 0.8084254 -0.2293756 0.5428604 0.8093732 -0.224093 0.5249384 0.8207083 -0.2255606 0.8093985 0.5429624 -0.223754 0.8093329 0.5431085 -0.2236372 0.8093748 0.5428585 -0.2240923 0.5431304 0.8093298 -0.2235947 0.5340683 0.8134944 -0.230213 0.6090308 0.7598786 -0.227302 0.6116546 0.757975 -0.2266111 0.6625102 0.7128506 -0.2300527 0.6697933 0.7064186 -0.228801 0.7130784 0.662722 -0.2287328 0.7061348 0.6695247 -0.2304569 0.7600396 0.609158 -0.2264208 0.7578742 0.6115742 -0.2271645 0.8168373 0.528887 -0.2303379 0.818275 0.5274292 -0.2285709 0 0.9570302 0.2899883 0 0.957032 0.2899826 0 0.95703 0.2899892 0 0.9570307 0.2899867 0 0.9570292 0.2899919 0 0.9570319 0.2899831 0 0.9570293 0.2899914 -2.06056e-7 0.9570315 0.2899842 0 0.9591582 0.2828707 0 0.9890106 0.1478453 -3.37975e-5 0.9889416 0.1483055 4.33794e-5 0.9751136 0.2217057 -2.19064e-4 0.9632103 0.268749 -0.001663386 0.9751018 0.2217515 0.005914092 0.9586699 0.2844592 0.004392981 0.9628177 0.2701163 0 0.8155377 0.5787039 0 0.8155446 0.5786942 0 0.9603472 0.2788071 0 0.9603371 0.2788417 2.16628e-5 0.7078146 0.7063984 2.73394e-6 0.7078173 0.7063956 7.25889e-5 0.7078625 0.7063503 0 0.7078297 0.7063832 0 0.707827 0.7063859 7.86841e-6 0.7078264 0.7063865 -6.25265e-6 0.7078223 0.7063905 -7.86841e-6 0.7078264 0.7063865 7.81581e-6 0.7078215 0.7063914 -4.83926e-5 0.7078625 0.7063503 -2.73394e-6 0.7078173 0.7063956 -2.16628e-5 0.7078149 0.706398 0 0.7558314 0.6547662 -1.35796e-4 0.7627139 0.6467362 2.65023e-4 0.8794671 0.4759596 -7.01787e-5 0.8857824 0.4641008 7.7573e-5 0.9803047 0.1974911 -4.23747e-4 0.9837967 0.1792875 4.08666e-4 0.9941809 -0.1077232 0 0.992371 -0.1232877 1.07366e-5 0.9652304 -0.2614007 -6.40499e-4 0.9653664 -0.2608973 4.92508e-6 0.9652279 -0.2614099 0 0.9652279 -0.2614101 8.84773e-6 0.9652274 -0.2614119 0 0.9652327 -0.2613923 0 0.9652334 -0.2613898 0 0.9652289 -0.2614061 0 0.9652322 -0.261394 -9.56816e-7 0.9652326 -0.2613924 4.79184e-4 0.9653474 -0.2609677 4.11517e-6 0.9652301 -0.2614017 -7.45073e-6 0.9652272 -0.2614126 -4.92508e-6 0.965228 -0.2614098 0 0.9971628 -0.07527673 0 0.997164 -0.07526016 0 0.9935327 0.1135461 6.0155e-6 0.9935352 0.1135244 0 0.993533 0.1135448 0 0.9935332 0.113542 0 0.9935325 0.1135488 3.66128e-7 0.993533 0.113544 5.14085e-7 0.9935317 0.1135559 0 0.9935328 0.1135461 -2.28832e-7 0.9935325 0.113548 3.00869e-7 0.9935312 0.1135598 1.79979e-7 0.993533 0.1135448 3.3734e-7 0.9935331 0.1135433 0 0.9935353 0.1135237 0 0.9935324 0.1135491 -1.31607e-7 0.9935321 0.1135519 -1.70155e-6 0.9935318 0.1135544 4.77996e-6 0.9935342 0.1135336 -2.67543e-6 0.9935314 0.1135581 0 0.9935338 0.1135373 -7.31165e-7 0.9935353 0.1135236 -8.81391e-7 0.9935362 0.1135161 -6.2859e-7 0.9935329 0.1135448 0.552439 0.8246107 -0.1217722 0.5532982 0.8249946 -0.1150868 0.5955372 0.7950268 -0.1151871 0.6266835 0.7757564 -0.07395774 0.6212463 0.775114 -0.1151151 0.6762437 0.7276289 -0.1151124 0.6762443 0.7276257 -0.1151285 0.7184371 0.6859908 -0.1151733 0.7322971 0.6805607 -0.02404665 0.7430309 0.6592693 -0.1151924 0.7751036 0.6212568 -0.1151282 0.775128 0.6212267 -0.1151261 0.8216713 0.5582174 -0.115107 0.8298035 0.556517 -0.04141455 0.8478137 0.5174449 -0.1160287 0.1371202 0.9881505 0.06896883 0.2240131 0.9738449 0.03800523 0.1977401 0.9799071 0.02609914 0.1964428 0.9801336 0.0273562 0.2218007 0.9748272 0.02272826 0.2328853 0.9721552 0.02605301 0.235734 0.9714803 0.02560663 0.242407 0.9697791 0.02770406 0.3029322 0.952969 0.009080171 0.08207184 0.9935194 0.07863444 0.0853337 0.993438 0.07615303 0.08740621 0.9928299 0.08154165 0.08740276 0.99283 0.08154374 0.08622759 0.9932038 0.07817316 0.04585331 0.9940599 0.09870332 -0.3490538 0.9171992 0.1921124 -0.3658224 0.9067682 0.2096318 -0.1227381 0.8212444 0.5572191 -0.1310226 0.814086 0.5657714 -0.4854805 0.8496748 -0.205819 -0.4959098 0.8507503 -0.1740621 -0.4624466 0.8853443 -0.04804652 -0.5607891 0.825724 0.06079113 -0.4892949 0.8558533 0.1676474 -0.4792039 0.8383305 0.2599342 -0.4714445 0.8346603 0.2847496 -0.4760718 0.7568182 0.4478638 -0.5120953 0.7180905 0.4712796 -0.3915711 0.6848796 0.6145015 -0.375096 0.6561353 0.6548203 -0.4940934 0.8693656 0.008680939 -0.3390396 0.7868841 0.5156216 -0.3287898 0.7464017 0.5786033 -0.3825755 0.8999319 0.2091861 -0.1787809 0.7910696 0.5850182 -0.1909312 0.8248965 0.532063 -0.4039672 0.894915 0.1895729 -0.4588771 0.8636529 0.2086519 -0.4583284 0.8671769 0.1947804 -0.4829764 0.8451912 -0.2288794 -0.004743158 0.9569916 0.2900768 -0.3867194 0.9102578 0.1479147 -0.3778499 0.9098018 0.1717268 -0.2479822 0.9368086 0.2467682 -0.08451586 0.975115 0.2049584 -0.1277756 0.959414 0.2513924 -0.4134839 0.8718823 0.2623972 -0.3608018 0.8794102 0.3105798 -0.2502361 0.9301873 0.268577 -0.1238614 0.9371308 0.3262581 -0.09352934 0.9523779 0.2902216 -0.004844546 0.9569939 0.2900679 -0.004748225 0.957306 0.2890378 -0.1519721 0.9339832 0.3233882 -0.3601621 0.9326583 0.02078455 -0.3650524 0.9286805 0.06549394 -0.09776824 0.9585208 0.2677296 -0.007334887 0.9597126 0.2808877 -0.002293348 0.9634432 0.2679034 -0.007434368 0.9641201 0.2653625 -0.1398696 0.9657459 0.2185667 -0.01982712 0.996557 0.08050602 -0.2374398 0.9529655 0.1883592 -0.226039 0.9607061 0.1610901 -0.4393075 0.8724994 0.2139014 -0.3577283 0.9269796 0.1128696 0.01232194 0.9741274 0.2256636 -0.3323653 0.9411313 0.06168609 -0.4101837 0.9081192 0.08407682 -0.3664265 0.9279417 0.06823396 -0.1947203 0.9769669 0.08729034 -0.3109378 0.9469058 0.08177536 -0.3528952 0.9244672 0.1443104 -0.1220366 0.9755487 0.1827892 -0.1120851 0.9771205 0.1807555 -0.1055936 0.9839683 0.1437236 -0.06370502 0.9890237 0.1333191 -0.3273142 0.9255573 0.1902872 -0.1147673 0.8221668 0.5575575 -0.3300296 0.9158549 0.2286712 -0.2586218 0.9455857 0.1974402 -0.2511208 0.9329807 0.257848 -0.1512434 0.9615993 0.2290249 -0.1542203 0.9507168 0.2689867 -0.04805374 0.9662807 0.2529672 -0.05457854 0.9589132 0.2784004 -0.1146497 0.8145364 0.5686705 -0.08975565 0.8251747 0.5577012 -0.08610755 0.8135532 0.5750797 -0.05155032 0.8234265 0.5650767 -0.05212986 0.8153072 0.5766773 -0.01580303 0.8206667 0.5711887 -0.01787924 0.8154109 0.5786066 -0.1392751 0.7655166 0.6281615 -0.263009 0.6920379 0.6722424 -0.3297724 0.6682261 0.6668763 -0.3414394 0.6704286 0.6587447 -0.09710294 0.6287456 0.7715245 -0.1919283 0.7005204 0.6873388 -0.001519203 0.7078147 0.7063965 -0.09746474 0.7063555 0.7011153 -0.07205438 0.6483319 0.7579407 -0.3289471 0.7050448 0.6282561 -0.3294321 0.7040603 0.6291055 -0.0742278 0.8042653 0.5896164 -0.347791 0.9289188 -0.1270879 -0.5359092 0.8387064 0.09681379 -0.3290878 0.8209704 0.466593 -0.4111335 0.7333467 0.5414534 -0.3650935 0.8858134 0.2864288 -0.3875241 0.8605128 0.3306702 -0.4129574 0.8957241 0.164756 -0.3623273 0.9320437 0.00368762 -0.462086 0.8855304 -0.04808932 -0.06313472 0.9898302 -0.1274762 -0.117143 0.7631942 0.6354621 -0.06551855 0.8875113 0.4561043 -0.1172281 0.9277536 0.3543034 -0.08191478 0.9822227 0.1689037 -0.1075015 0.9864881 0.1236319 -0.1003746 0.9914548 -0.08332079 -0.2057823 0.9706888 -0.1241649 -0.06338363 0.9632073 -0.2611789 -0.09247839 0.8969241 -0.4324059 -0.2073257 0.9433416 -0.2590806 -0.3495092 0.9041956 -0.245507 -0.3876237 0.7997292 -0.4584552 -0.4681102 0.8587863 -0.2082283 -0.1219934 0.9449549 0.3036081 -0.004678785 0.9568361 0.2905906 -0.3598425 0.8773167 0.3175354 -0.1171231 0.9418388 0.3149949 -0.1271232 0.9443084 0.303515 -0.2430689 0.9182602 0.3125953 -0.3601714 0.8774656 0.3167502 -0.3603001 0.8771286 0.3175362 -0.4774461 0.7407342 0.4726078 -0.5534309 0.6858238 0.4726098 -0.7407316 0.4774472 0.4726108 -0.7407381 0.4774442 0.4726036 -0.6858255 0.5534313 0.4726068 -0.6858193 0.5534362 0.4726101 -0.6231569 0.6231538 0.4726044 -0.6634364 0.6290362 0.4051737 -0.7048004 0.7047975 0.08072876 -0.8389675 0.5407654 0.06088107 -0.7047979 0.7047997 0.0807299 -0.7756794 0.6259428 0.08072912 -0.7756795 0.6259431 0.08072561 -0.8345232 0.545023 0.08075261 -0.811755 0.5231651 0.2595228 -0.4774463 0.7407341 0.4726077 -0.5232371 0.8116993 0.2595524 -0.5450227 0.8345236 0.08075112 -0.5407664 0.8389669 0.06088024 -0.5335195 0.8277336 -0.1738221 -0.5335239 0.8277277 -0.1738364 -0.6184227 0.7663785 -0.1738316 -0.625943 0.7756793 0.08072894 -0.6259391 0.7756825 0.08072876 -0.5534348 0.6858237 0.4726054 -0.6062164 0.6393575 0.4729945 -0.8277305 0.5335235 -0.173824 -0.8277339 0.5335151 -0.1738339 -0.7663679 0.6184361 -0.1738305 -0.766381 0.6184194 -0.1738327 -0.7145919 0.6775514 -0.1740189 -0.7067835 0.7067822 -0.03027004 -0.6775423 0.7146015 -0.1740149 -0.6184305 0.7663704 -0.1738396 -0.6355385 0.4230661 0.6458375 -0.4102497 0.6410561 0.6486467 -0.4102283 0.6399037 0.649797 -0.4097068 0.6356455 0.6542899 -0.6356356 0.4097139 0.6542951 -0.6392474 0.4101323 0.6505031 -0.6315339 0.4094748 0.6584036 -0.5907711 0.4767265 0.6509388 -0.5935276 0.4756987 0.649181 -0.5460676 0.5177589 0.6585863 -0.5537718 0.514662 0.6545685 -0.5200926 0.548531 0.654689 -0.5128644 0.5518351 0.6576079 -0.477442 0.5916532 0.649612 -0.4745933 0.5921483 0.6512462 -0.4173704 0.6270278 0.6577523 -0.8324588 0.5539837 0.01069635 -0.5438679 0.8156087 0.1974591 -0.8167666 0.5421456 0.1974096 -0.5537795 0.8325918 0.01092678 -0.5443733 0.8198916 0.1773002 -0.6154573 0.7679368 0.1774414 -0.6154904 0.7679156 0.177418 -0.669965 0.7208803 0.1774215 -0.6699852 0.7208586 0.1774338 -0.7208667 0.6699771 0.1774317 -0.7208901 0.6699558 0.1774167 -0.7679087 0.6154946 0.177434 -0.767936 0.6154655 0.1774165 -0.818731 0.5461109 0.1773202 -0.7101582 0.4730237 0.5214633 -0.7167759 0.4758607 0.5096951 -0.6712094 0.5379626 0.5099747 -0.6712167 0.5379562 0.5099719 -0.6300812 0.5856004 0.5099707 -0.6300811 0.5855926 0.5099796 -0.5855913 0.6300914 0.5099684 -0.5855734 0.6300996 0.5099788 -0.5379822 0.6711999 0.5099666 -0.5379567 0.6712155 0.5099729 -0.4769657 0.716013 0.5097344 -0.4718955 0.7109107 0.5214602 -0.8827918 0.469762 -0.001523077 -0.8688586 0.495054 0.002525389 -0.8685319 0.4956193 0.00374794 -0.8325514 0.5538551 -0.01014113 -0.8369505 0.5434347 -0.06475162 -0.7786801 0.6241003 0.06446844 -0.7921097 0.6095242 -0.03228956 -0.7322094 0.6805032 0.02801483 -0.7369723 0.6759229 0 -0.6807723 0.7324952 0 -0.675731 0.7367658 0.02374678 -0.6252803 0.7801574 -0.01947546 -0.6093831 0.7919204 0.03891611 -0.553177 0.8315384 -0.05039012 -0.5445694 0.8386788 -0.007886886 -0.4948171 0.8689883 0.00393033 -0.4956353 0.8685268 0.002625644 -0.4697639 0.8827909 -0.001523077 -0.5724915 0.8101073 0.1264107 -0.5141798 0.8552561 0.06446993 -0.4955412 0.8683757 0.01904493 -0.4883147 0.8342073 0.2562166 -0.5191429 0.8204817 0.239375 -0.5287673 0.8143362 0.2392943 -0.5287623 0.8143405 0.2392905 -0.5921401 0.7695038 0.2392368 -0.5921384 0.7695057 0.2392343 -0.6563012 0.7155663 0.2392358 -0.6563003 0.7155677 0.239234 -0.7155693 0.6562986 0.2392336 -0.7155663 0.6563008 0.2392367 -0.7695048 0.5921388 0.2392363 -0.7695027 0.5921421 0.2392347 -0.81434 0.5287629 0.2392914 -0.8143364 0.5287671 0.239294 -0.8206703 0.5188436 0.2393773 -0.8342559 0.4883421 0.2560063 -0.8552577 0.5141766 0.06447327 -0.8683701 0.4955511 0.01904416 -0.4521335 0.8882969 0.08064711 -0.5428079 0.8359633 0.0807771 -0.5428035 0.8359659 0.0807802 -0.6078594 0.7899274 0.08075749 -0.6078568 0.7899295 0.08075702 -0.6737216 0.7345594 0.08075755 -0.6737175 0.7345631 0.08075755 -0.7345626 0.673718 0.08075761 -0.7345603 0.6737205 0.08075803 -0.7899286 0.6078577 0.08075761 -0.7899288 0.6078574 0.08075809 -0.8359665 0.5428027 0.08077919 -0.8359617 0.5428103 0.08077847 -0.8441595 0.5299662 0.08081293 -0.8629507 0.4829062 0.1487205 -0.7794299 0.5429194 0.3126143 -0.4792825 0.8188182 0.3159514 -0.5057364 0.7788835 0.3709061 -0.4379692 0.5691764 0.6958602 -0.8188039 0.4793062 0.315952 -0.7788866 0.5057319 0.3709058 -0.5691499 0.4379891 0.6958693 -0.7809158 0.5446293 0.3058587 -0.6980732 0.6402477 0.3205884 -0.6355777 0.6355879 0.4382569 -0.6402529 0.6980697 0.3205854 -0.5441901 0.7812512 0.3057841 -0.5438334 0.7788147 0.3125585 -0.08371353 0.9779689 -0.1912297 -0.02921217 0.9967387 -0.07522511 -0.02323579 0.9962533 -0.0833044 -0.0683214 0.9931313 -0.09498745 -0.07207518 0.9931408 -0.09206962 -0.1048052 0.9883052 -0.1107649 -0.1213726 0.9871351 -0.1040819 -0.1409388 0.9824204 -0.1224197 -0.2873267 0.9526035 -0.09995114 -0.1122755 0.973146 -0.2009508 -0.1152452 0.9733341 -0.1983413 -0.273644 0.9584073 -0.08108359 -0.338169 0.938921 -0.06378889 -0.3298709 0.9412859 -0.07187664 -0.3187263 0.946394 -0.05246013 -0.1080951 0.9751006 -0.1936341 -0.09310662 0.9745298 -0.2040175 -0.09386014 0.9609667 -0.2602562 -0.04431635 0.9657672 -0.2555974 -0.1329028 0.9570807 -0.2575528 -0.2317705 0.9388294 -0.254719 -0.40227 0.8841788 -0.2375015 -0.3482764 0.9099544 -0.2251369 -0.3734635 0.8964545 -0.2385255 -0.3869854 0.8903686 -0.2397628 -0.4120756 0.8805657 -0.2340888 -0.3988804 0.8851229 -0.2396916 -0.4171475 0.8803255 -0.225865 -0.4647377 0.8789242 -0.1072902 -0.4242546 0.8826933 -0.2021399 -0.3912432 0.9025567 -0.179778 -0.3570264 0.9128345 -0.1981554 -0.3363333 0.9245637 -0.1790586 -0.2662479 0.9401361 -0.2127352 -0.2507392 0.9488556 -0.1918411 -0.1948766 0.9588536 -0.2064537 -0.1823498 0.9654106 -0.1863623 -0.1204907 0.9706858 -0.2079693 -0.4666617 0.8824139 -0.05977213 -0.4667076 0.8823867 -0.05981445 -0.4534814 0.8885949 -0.06894713 -0.4425847 0.8947928 -0.05886262 -0.4150732 0.9065968 -0.07613378 -0.406476 0.911381 -0.06451416 -0.3831236 0.9208095 -0.07298254 -0.3756889 0.9247347 -0.06102329 -0.3441367 0.935942 -0.07471728 -0.818275 0.5274292 -0.2285709 -0.5420657 0.8084254 -0.2293756 -0.5429624 0.8093985 -0.2237547 -0.5431053 0.809335 -0.2236371 -0.5428604 0.8093732 -0.224093 -0.8082535 0.5422549 -0.2295346 -0.8093748 0.5428585 -0.2240923 -0.8207091 0.5249373 -0.2255602 -0.8093298 0.5431304 -0.2235947 -0.8134945 0.534068 -0.2302129 -0.7598807 0.609028 -0.227302 -0.757974 0.6116558 -0.2266111 -0.7128499 0.6625112 -0.2300522 -0.7064188 0.6697929 -0.2288014 -0.6627228 0.7130779 -0.2287327 -0.6695237 0.7061355 -0.2304576 -0.6091588 0.7600392 -0.2264203 -0.6115736 0.7578747 -0.2271645 -0.5288879 0.8168368 -0.2303376 -0.5274279 0.8182756 -0.2285715 -0.5528497 0.8243231 -0.121856 -0.7322972 0.6805608 -0.02403992 -0.7430287 0.6592724 -0.1151887 -0.7751173 0.6212397 -0.1151285 -0.7751143 0.6212438 -0.1151258 -0.824998 0.5532954 -0.1150761 -0.8267741 0.5616827 -0.03093987 -0.847811 0.5174491 -0.1160302 -0.5528892 0.825272 -0.1150643 -0.5955372 0.7950268 -0.1151871 -0.6234824 0.7779039 -0.07832866 -0.6242244 0.7727124 -0.1151505 -0.6762599 0.7276136 -0.1151132 -0.6762281 0.7276409 -0.1151278 -0.7184371 0.6859908 -0.1151733 0.1667418 0.985996 0.003034114 -0.231156 0.9725223 0.02770406 -0.1374903 0.9880353 0.0698772 -0.2600343 0.9651907 0.02809405 -0.2888653 0.9573658 -0.002773523 -0.2247216 0.9736459 0.03890979 -0.2083775 0.9779502 0.01386874 -0.1606504 0.9865109 0.03143095 -0.1774246 0.9840173 0.01517933 -0.07742959 0.9950876 0.06168848 -0.1128686 0.9929912 0.03506392 -0.1716763 0.9851377 0.005588889 -0.07361733 0.995312 0.06272572 -0.06661576 0.9961144 0.05760771 -0.06657832 0.996119 0.05757004 -0.04871904 0.9968839 0.06204026 -0.02901083 0.9978981 0.05794763 -0.04194408 0.9974036 0.05853968 -0.04000449 0.9976271 0.05603486 -0.04829055 0.9969053 0.06203228 -0.04996114 0.9966284 0.06508278 -0.01570612 0.9981756 0.05830019 -0.02071732 0.9981837 0.05656903 -0.02998685 0.9977438 0.06006866 0.02509939 0.9978808 0.06003409 0.01636534 0.9983066 0.05582165 0.008170187 0.9981861 0.05964666 0.008632957 0.998157 0.06006908 -0.005028545 0.998182 0.0600627 -0.008646428 0.9983362 0.05701136 -0.0130282 0.9982906 0.05697661 0.03182548 0.9970204 0.07026773 0.03093856 0.9982051 0.0512799 0.04573005 0.9970643 0.06141263 0.04183018 0.9975592 0.05591022 0.0495491 0.9968562 0.06182867 0.04895204 0.9969362 0.06100869 0.06333714 0.9963105 0.05791211 0.1651667 0.9859864 0.02346813 0.1765228 0.9841904 0.01446384 0.1977795 0.9800943 0.01727676 0.07294344 0.9949654 0.06872457 0.08055555 0.9956514 0.04679012 0.08050644 0.9957023 0.0457769 0.07643544 0.9952462 0.06035506 0.08129578 0.9943734 0.06791603 0.08268892 0.9943661 0.06632143 0.08211791 0.9940464 0.07161277 -0.2148543 0.976293 0.02626019 -0.2092369 0.9773348 0.03219908 -0.08704942 0.9929537 0.08040684 -0.08565378 0.9934033 0.07624495 -0.04587781 0.9940322 0.0989719 -0.09261965 0.9925282 0.0794332 -0.08576852 0.9933055 0.07738161 -0.08318567 0.9939662 0.0714941 -0.08691835 0.9937028 0.07070958 -0.08056956 0.9944984 0.06694298 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.45806e-7 0 -1 0.09194487 0.9957638 -8.48445e-4 0.09277933 0.9956849 -0.001917898 -2.80665e-4 0 1 1.66629e-4 0 1 0 0 1 1.20585e-5 0 1 -0.09466457 0 -0.9955093 -0.09483629 0 -0.9954929 0.09452426 0 -0.9955226 0.09432017 0 -0.9955419 0.9708555 0 0.2396658 0.9708557 0 0.239665 0.7478474 0 0.6638706 0.7478449 0 0.6638734 0.3590249 0 0.9333281 0.3590168 0 0.9333311 0.06422358 0 0.9979355 0.06424146 0 0.9979344 -0.2950103 0.9554941 -1.50103e-4 -0.2815776 0.9594984 -0.008774995 -0.2790911 0.9601957 -0.01150572 -0.2799895 0.9599532 -0.009788215 -0.2814661 0.9595634 -0.003851294 -0.3135378 0.9488482 -0.03716415 -0.3330498 0.9429093 2.52835e-4 -0.3383729 0.9409586 -0.01004976 -0.3369311 0.9415209 -0.003999292 -0.2814658 0.9595714 0 -0.3093076 0.950883 -0.01225697 -0.3369327 0.9415288 0 -0.2711932 0.9625107 0.005247831 -0.2682564 0.963347 0.001023232 -0.3444024 0.9388103 0.004717469 -0.3092297 0.9506436 0.02556961 -0.3149057 0.9483734 0.0377134 -0.401502 0.9032219 0.1516131 -0.3112903 0.9501476 0.01782852 -0.2760365 0.9609266 -0.02059453 -0.3044024 0.9517654 0.03849434 1 0 0 0.2419487 0 -0.9702891 0.2419428 0 -0.9702905 0.6660066 0 -0.7459458 0.6660089 0 -0.7459438 0.9309082 0 -0.3652535 0.930907 0 -0.3652564 0.9974083 0 -0.07195073 0.9974082 0 -0.0719521 -0.9714434 0 -0.2372719 -0.9714441 0 -0.2372689 -0.7485076 0 -0.6631264 -0.3542215 0 -0.9351616 -0.3542191 0 -0.9351626 -0.06092584 0 -0.9981424 -0.06091815 0 -0.9981428 -1 0 0 -1 -3.03435e-7 0 -0.2419475 0 0.9702893 -0.2419415 0 0.9702909 -0.6660103 0 0.7459426 -0.6660131 0 0.7459401 -0.9309072 0 0.3652558 -0.9309061 0 0.3652586 -0.9974085 0 0.0719484 -0.9974083 0 0.07194942 0.9714434 0 0.2372714 0.9714444 0 0.2372676 0.7485094 0 0.6631242 0.7485091 0 0.6631246 0.3542284 0 0.935159 0.3542147 0 0.9351642 0.06093484 0 0.9981418 0.06091815 0 0.9981428 -0.1546515 0.9879691 0 -0.1546515 0.9879692 0 -0.1924842 0.9812884 -0.004790186 -0.1952245 0.980758 -0.001133739 -0.1207708 0.9926699 -0.004582107 -0.1546137 0.9877272 -0.0221278 -0.1486028 0.9883784 -0.03202211 -0.03230518 0.9881947 -0.1497585 -0.1522015 0.9882333 -0.01515793 -0.1846254 0.9826918 0.01518273 -0.1576173 0.9868556 -0.03567761 -0.1164088 0.9931904 0.004685521 -0.1136604 0.9935191 0.001070618 -0.1880198 0.9821538 0.004733979 -0.1546124 0.9877228 0.02233439 -0.1602751 0.9865616 0.03175091 -0.2688055 0.9520275 0.1462436 -0.1565869 0.9875513 0.01493489 -0.1242217 0.9921419 -0.01495736 -0.1508938 0.9879318 0.03495609 0.2419508 0 -0.9702886 0.2419421 0 -0.9702907 0.6660136 0 -0.7459397 0.6660165 0 -0.7459371 0.9309055 0 -0.3652602 0.9309085 0 -0.3652526 0.9974083 0 -0.0719487 0.9974083 0 -0.07194989 -0.9714441 0 -0.2372689 -0.9714447 0 -0.2372663 -0.7485057 0 -0.6631284 -0.7485072 0 -0.6631267 -0.3542307 0 -0.9351581 -0.3542291 0 -0.9351587 -0.06092977 0 -0.9981421 -0.06091052 0 -0.9981433 -1 2.34939e-7 0 -0.2419475 0 0.9702894 -0.241936 0 0.9702922 -0.6660081 0 0.7459446 -0.6660133 0 0.7459399 -0.9309071 0 0.365256 -0.9309064 0 0.365258 -0.9974083 0 0.07194942 -0.9974083 0 0.0719487 0.9714437 0 0.2372707 0.9714444 0 0.2372674 0.7485072 0 0.6631268 0.7485096 0 0.663124 0.3542244 0 0.9351605 0.3542178 0 0.9351629 0.06094563 0 0.9981411 0.06088513 0 0.9981448 0 1 0 0.02569746 0.9996249 0.009477257 -0.0336377 0.9994239 0.004528343 0 0.9997646 0.02170252 -0.005833983 0.9994988 0.03111845 0.0225268 0.9997434 0.002406775 -0.001227557 0.9995287 0.03067511 0.006305336 0.999723 0.02267789 -0.02569878 0.9996249 -0.009477257 0.0336374 0.9994239 -0.004528284 0 0.9997646 -0.02170252 0.005834162 0.9994988 -0.03111833 -0.02252775 0.9997434 -0.002406775 0.001228928 0.9995287 -0.03067499 -0.006305575 0.999723 -0.02267783 1 -2.92028e-7 0 0.2419524 0 -0.9702882 0.2419356 0 -0.9702924 0.6660061 0 -0.7459463 0.6660162 0 -0.7459373 0.9309075 0 -0.3652553 0.9309075 0 -0.3652551 0.9974084 0 -0.07194846 0.9974081 0 -0.07195168 -0.9714438 0 -0.2372698 -0.9714438 0 -0.2372698 -0.748512 0 -0.6631213 -0.7485067 0 -0.6631273 -0.3542249 0 -0.9351602 -0.3542203 0 -0.9351621 -0.06093716 0 -0.9981416 -0.2419494 0 0.9702889 -0.2419428 0 0.9702905 -0.6660071 0 0.7459455 -0.6660152 0 0.7459382 -0.9309073 0 0.365256 -0.9309063 0 0.3652581 -0.9974082 0 0.07195073 -0.9974082 0 0.07195097 0.9714436 0 0.2372709 0.9714443 0 0.2372678 0.7485063 0 0.6631278 0.7485099 0 0.6631237 0.3542258 0 0.93516 0.3542135 0 0.9351646 0.06095564 0 0.9981405 0.06089305 0 0.9981444 0.1546515 0.9879691 0 0.1546515 0.9879692 0 0.1924865 0.981288 0.004790186 0.1952217 0.9807585 0.001133739 0.1207677 0.9926702 0.004582107 0.1546131 0.9877273 0.0221278 0.148601 0.9883787 0.03202211 0.03231394 0.9881944 0.1497585 0.1522015 0.9882333 0.01515793 0.1846254 0.9826918 -0.01518273 0.1576173 0.9868556 0.03567761 0.1164075 0.9931905 -0.004685521 0.1136634 0.9935188 -0.001070618 0.1880177 0.9821543 -0.004733979 0.1546124 0.9877228 -0.02233439 0.160276 0.9865615 -0.03175091 0.2688015 0.9520287 -0.1462438 0.1565825 0.9875521 -0.01493489 0.1242197 0.9921421 0.01495736 0.1508966 0.9879313 -0.03495609 -0.2419487 0 0.970289 -0.2419379 0 0.9702918 -0.6660107 0 0.7459422 -0.6660122 0 0.7459409 -0.9309074 0 0.3652556 -0.9309062 0 0.3652585 -0.9974084 0 0.07194757 -0.9974084 0 0.07194769 0.9714434 0 0.237272 0.9714442 0 0.2372684 0.7485068 0 0.6631271 0.7485093 0 0.6631244 0.5037653 0 0.8638406 0.3606562 0.02463769 0.9323734 0.2888793 0 0.9573656 0.06093358 0 0.9981418 0.06091153 0 0.9981433 0.917203 0.3490356 0.1921277 0.9067772 0.36581 0.2096146 0.821251 0.1227212 0.5572131 0.8140929 0.1310238 0.565761 0.849633 0.4855493 -0.2058292 0.8507686 0.4958811 -0.1740541 0.8853495 0.4624369 -0.04804801 0.825712 0.5608075 0.06078594 0.8558632 0.4892756 0.1676535 0.8382955 0.4792637 0.2599366 0.834644 0.4714598 0.2847722 0.7568342 0.4760652 0.4478438 0.7180763 0.5121048 0.471291 0.6849124 0.3915219 0.6144963 0.6561298 0.3750969 0.6548252 0.8694472 0.4939465 0.008860826 0.7868865 0.3390421 0.5156165 0.7463894 0.328795 0.5786162 0.8999223 0.3825964 0.2091884 0.7910663 0.1787652 0.5850275 0.8249013 0.1909362 0.5320538 0.8949131 0.4039707 0.1895737 0.8636583 0.4588726 0.2086398 0.867173 0.4583357 0.1947805 0.845195 0.4829704 -0.228878 0.9569957 0.004841744 0.2900621 0.9102603 0.3867146 0.147912 0.9098017 0.3778498 0.1717274 0.9368071 0.2479864 0.2467699 0.9751145 0.0845133 0.2049618 0.9594151 0.1277764 0.2513881 0.8718823 0.4134814 0.2624012 0.8794103 0.360805 0.3105759 0.9301859 0.2502439 0.2685745 0.9371316 0.1238582 0.3262571 0.9523782 0.09352898 0.290221 0.9569959 0.004844427 0.2900611 0.9573063 0.004651308 0.2890379 0.9339845 0.1519668 0.323387 0.9326713 0.3601284 0.02077823 0.9286774 0.3650594 0.06549787 0.9585192 0.09776699 0.2677365 0.9597147 0.007412075 0.2808787 0.9634463 0.002216696 0.2678925 0.9641045 0.007510721 0.265417 0.9657477 0.1398575 0.2185666 0.9965574 0.01983261 0.08049935 0.9529658 0.2374404 0.1883566 0.9607027 0.226051 0.1610937 0.872496 0.4393129 0.213904 0.9269784 0.3577306 0.1128716 0.9741371 -0.01226645 0.2256249 0.9411327 0.3323615 0.06168693 0.9081042 0.4102186 0.08406919 0.9279438 0.3664214 0.0682339 0.9769678 0.1947165 0.08728998 0.9469058 0.3109373 0.08177751 0.9244728 0.3528828 0.1443046 0.9755473 0.1220447 0.1827909 0.9771209 0.1120774 0.1807577 0.9839683 0.1055961 0.1437219 0.9890235 0.06370753 0.1333194 0.9255575 0.3273168 0.1902816 0.8221802 0.1147502 0.5575411 0.9158477 0.3300394 0.2286859 0.9455893 0.2586166 0.1974293 0.9329752 0.2511289 0.2578595 0.9615921 0.1512606 0.2290439 0.950723 0.1542077 0.2689718 0.9662827 0.04805326 0.25296 0.9589101 0.05457496 0.2784116 0.81452 0.1146591 0.5686919 0.8251773 0.08974456 0.5576992 0.8135562 0.0860961 0.5750772 0.8234255 0.05156135 0.565077 0.8153157 0.05211824 0.5766664 0.8206747 0.01580452 0.5711772 0.8154143 0.0178734 0.5786019 0.7655149 0.1392748 0.6281635 0.6920394 0.2630088 0.6722409 0.6682317 0.3297578 0.666878 0.6704211 0.3414404 0.6587519 0.628744 0.09710538 0.7715256 0.7005184 0.1919326 0.6873397 0.7078218 0.001379013 0.7063897 0.7063685 0.09745824 0.7011031 0.6483257 0.07206332 0.7579452 0.7050433 0.3289374 0.6282629 0.7040532 0.3294333 0.6291127 0.8042626 0.07423788 0.5896191 0.9289278 0.347766 -0.1270903 0.8386996 0.5359203 0.0968129 0.8209695 0.3290898 0.4665931 0.7333536 0.4111121 0.5414603 0.8858145 0.3651069 0.2864082 0.8605135 0.3875195 0.3306739 0.8957281 0.4129524 0.1647472 0.9320434 0.3623279 0.003688335 0.8855288 0.4620891 -0.0480864 0.9898298 0.06314277 -0.1274756 0.7631915 0.1171458 0.6354649 0.8875115 0.06551808 0.4561039 0.927749 0.1172403 0.3543116 0.9822224 0.08191269 0.1689066 0.9864879 0.1075047 0.1236299 0.9914555 0.1003733 -0.08331453 0.9706866 0.2057866 -0.1241747 0.9631904 0.06338536 -0.2612404 0.8969492 0.09246188 -0.4323576 0.943338 0.2073439 -0.2590793 0.9042032 0.3494904 -0.2455058 0.7997453 0.3876306 -0.4584211 0.8587275 0.4682096 -0.2082476 0.9449538 0.121996 0.3036104 0.9568325 0.004730701 0.2906017 0.8773194 0.3598294 0.3175429 0.9418413 0.1171264 0.3149863 0.9443048 0.1271284 0.3035242 0.9182029 0.2431503 0.3127001 0.8774636 0.3601773 0.3167492 0.8771311 0.3603057 0.3175233 0.9779725 0.08371108 -0.1912129 0.9967373 0.0292173 -0.07524126 0.9962539 0.02323222 -0.08329874 0.9931313 0.06831872 -0.09498775 0.9931385 0.07209187 -0.09208029 0.9883032 0.1048141 -0.1107741 0.9871355 0.121367 -0.1040844 0.9824222 0.1409344 -0.1224103 0.9525997 0.2873339 -0.09996545 0.9389214 0.3381714 -0.063771 0.9412819 0.3298821 -0.07187634 0.9460658 0.3194825 -0.05376297 0.9368724 0.3482782 -0.03118187 0.9617955 0.2649011 -0.06911659 0.9733291 0.115261 -0.1983569 0.9731518 0.1122579 -0.2009323 0.9751008 0.1080945 -0.1936336 0.9745256 0.09312105 -0.2040303 0.960967 0.09385806 -0.2602561 0.9657672 0.04432278 -0.2555959 0.9570805 0.1329003 -0.2575546 0.9388282 0.2317744 -0.2547199 0.884185 0.402258 -0.2374987 0.9099553 0.3482716 -0.2251405 0.896453 0.3734695 -0.2385221 0.8903709 0.3869791 -0.2397642 0.8805627 0.4120825 -0.2340884 0.8851241 0.3988776 -0.2396916 0.8803401 0.4170539 -0.2259811 0.878911 0.4647625 -0.1072908 0.8826916 0.4242537 -0.2021495 0.902558 0.3912307 -0.1797989 0.912839 0.3570225 -0.1981414 0.9245559 0.3363534 -0.1790614 0.9401364 0.266252 -0.2127287 0.9488594 0.2507268 -0.1918385 0.9588511 0.1948931 -0.2064489 0.9654115 0.1823435 -0.1863638 0.9706849 0.1205005 -0.2079675 0.8824335 0.4666262 -0.05976074 0.8823939 0.4666939 -0.05981492 0.8885909 0.4534901 -0.06894153 0.8947953 0.4425783 -0.05887323 0.9065936 0.4150797 -0.07613873 0.9113852 0.4064662 -0.06451588 0.9208168 0.3831058 -0.0729832 0.9247445 0.375664 -0.0610277 0.935943 0.3441336 -0.07471811 0.9570344 0 0.2899745 0.957031 0 0.2899857 0.9570306 0 0.2899872 0.9570326 0 0.2899804 0.9570304 4.12547e-7 0.2899875 0.9570307 -5.29125e-7 0.2899869 0.957029 2.0465e-7 0.2899925 0.9570307 -2.06054e-7 0.2899867 0.9591575 0 0.2828728 0.9890108 0 0.1478437 0.9889419 3.37977e-5 0.1483042 0.9751135 -4.33793e-5 0.2217063 0.9632125 2.19067e-4 0.2687409 0.9751012 0.00166285 0.2217542 0.9586704 -0.005913972 0.2844575 0.9628168 -0.004392266 0.2701196 0.8155433 0 0.5786963 0.8155459 0 0.5786924 0.9603434 0 0.2788202 0.9603372 0 0.2788416 0.7078166 -3.90796e-7 0.7063964 0.7078746 6.04897e-5 0.7063381 0.7078205 1.36697e-6 0.7063924 0.7078169 -2.03088e-6 0.706396 0.7078173 0 0.7063957 0.7078205 -1.36697e-6 0.7063924 0.7078746 -6.04897e-5 0.7063381 0.7078138 0 0.7063991 0.7078227 4.42596e-6 0.7063902 0.70783 0 0.7063828 0.7078291 0 0.7063838 0.7078227 -4.42596e-6 0.7063902 0.755844 0 0.6547518 0.762703 1.35945e-4 0.6467489 0.8794702 -2.6502e-4 0.4759539 0.8857759 7.01821e-5 0.4641135 0.980306 -7.77857e-5 0.1974849 0.9837976 4.23927e-4 0.1792826 0.9941815 -4.08806e-4 -0.1077175 0.9923714 0 -0.1232852 0.9652289 -7.31578e-6 -0.2614064 0.9653553 -4.68795e-4 -0.260939 0.9652332 0 -0.2613905 0.9652303 -7.15781e-6 -0.2614013 0.9653641 6.31524e-4 -0.2609056 0.9652308 -7.38665e-6 -0.2613996 0.9652331 0 -0.2613908 0.9652333 0 -0.26139 0.9652308 7.38665e-6 -0.2613996 0.9652267 7.45084e-6 -0.2614146 0.9652281 -9.95104e-7 -0.2614095 0.9652277 3.69381e-6 -0.2614107 0.9652276 0 -0.2614111 0.9652281 9.95104e-7 -0.2614095 0.9652266 -7.91654e-6 -0.261415 0.9971628 0 -0.07527577 0.9971632 0 -0.07527077 0.9935318 -1.20311e-5 0.1135554 0.9935328 -6.2317e-7 0.1135463 0.9935323 1.54225e-6 0.1135499 0.9935327 0 0.1135464 0.9935328 0 0.1135454 0.9935327 -4.19102e-7 0.1135467 0.9935327 7.95333e-7 0.1135464 0.9935327 0 0.1135464 0.9935326 -1.20349e-6 0.1135475 0.9935327 1.79978e-7 0.1135464 0.9935326 1.34934e-6 0.1135471 0.9935327 -8.00914e-7 0.1135463 0.9935325 5.56049e-7 0.1135485 0.993533 -8.25883e-7 0.1135441 0.9935324 1.05286e-6 0.1135489 0.9935328 -2.59296e-6 0.1135452 0.993532 0 0.113553 0.993532 -7.31226e-7 0.1135533 0.993534 -1.89939e-6 0.1135358 0.9935321 -4.28069e-6 0.113552 0.9935315 8.08239e-6 0.1135568 0.9935339 -2.39005e-6 0.1135358 0.9738438 0.2240178 0.0380038 0.9940594 0.04585939 0.098706 0.9798912 0.1977298 0.02676451 0.9805324 0.1943735 0.02784609 0.9710924 0.2379071 0.01949441 0.9718061 0.2344036 0.02545458 0.9667653 0.2537966 0.0308597 0.9564832 0.2917873 -3.20097e-4 0.9936006 0.08207732 0.07759654 0.9933388 0.08568221 0.07704907 0.9928299 0.08740162 0.08154606 0.9928295 0.08740609 0.08154612 0.9932044 0.08622395 0.07817035 0.9881511 0.1371167 0.06896799 0.8157632 -0.1335099 0.5627659 0.8195922 -0.120078 0.5602231 0.9067441 -0.369788 0.2026627 0.9173036 -0.3448344 0.1991066 0.6849124 -0.3915219 0.6144963 0.7210835 -0.5303928 0.4457826 0.7341691 -0.4877804 0.4722987 0.8330035 -0.4681212 0.294903 0.8383125 -0.4792428 0.2599201 0.8474211 -0.4843345 0.2174801 0.8505155 -0.5013635 0.1589283 0.829732 -0.554839 0.06081789 0.8733918 -0.4869639 -0.007284522 0.8557638 -0.4923311 -0.1589925 0.8507686 -0.4958811 -0.1740541 0.8496345 -0.4855466 -0.2058296 0.6561298 -0.3750969 0.6548252 0.8647277 -0.4628549 0.1949648 0.7733598 -0.3658744 0.517736 0.8694472 -0.4939465 0.008860826 0.8658807 -0.4552385 0.2073848 0.9003438 -0.3934718 0.1859057 0.8949239 -0.3916637 0.2138012 0.7593322 -0.3089151 0.5727009 0.8125305 -0.2159482 0.5414432 0.8031994 -0.1571953 0.574596 0.8451951 -0.4829699 -0.2288785 0.9044533 -0.3917864 0.1687241 0.8395159 -0.4280623 0.3346278 0.8917881 -0.3666626 0.2650899 0.9569976 -0.004840195 0.2900556 0.9573063 -0.004651308 0.2890379 0.9604588 -0.09073084 0.263224 0.9702571 -0.1148046 0.2131223 0.914153 -0.3732911 0.1580446 0.9368071 -0.2479864 0.2467699 0.9301859 -0.2502439 0.2685745 0.9363463 -0.09826332 0.3370459 0.9483924 -0.1290736 0.2896412 0.956995 -0.004845857 0.2900642 0.872496 -0.4393129 0.213904 0.9269794 -0.357728 0.1128708 0.9607034 -0.2260482 0.1610934 0.924176 -0.1352413 0.3572233 0.9560122 -0.1314352 0.2622318 0.9639148 -0.007682383 0.2661002 0.9237786 -0.3780254 0.06107306 0.9360987 -0.3499287 0.03562486 0.9529657 -0.2374423 0.1883547 0.9894908 -0.08798295 0.1147478 0.9673906 -0.08552163 0.2384145 0.9636388 -0.002113819 0.2672004 0.9597147 -0.007412075 0.2808787 0.9870361 -0.1025457 0.1234669 0.916647 -0.3597428 0.1741937 0.9244728 -0.3528828 0.1443046 0.9469067 -0.3109347 0.08177727 0.976967 -0.19472 0.08728992 0.9832627 -0.05871695 0.1724725 0.9279438 -0.3664214 0.0682339 0.9392815 -0.3381928 0.05810433 0.9755473 -0.1220447 0.1827909 0.9772183 -0.1114385 0.1806265 0.9742284 0.01256573 0.2252138 0.8192565 -0.1206904 0.5605825 0.9169241 -0.3456273 0.1994796 0.8173938 -0.1081367 0.565839 0.8230111 -0.09498006 0.5600281 0.8154346 -0.07978564 0.5733243 0.8222675 -0.05590248 0.5663489 0.8161054 -0.04717713 0.5759742 0.8202718 -0.01876455 0.5716663 0.8154654 -0.01468002 0.5786197 0.9248896 -0.3101083 0.2200278 0.9394271 -0.2749618 0.2046289 0.9394629 -0.2317101 0.2524282 0.9583817 -0.1648486 0.2330871 0.9536914 -0.1388165 0.2668383 0.9653745 -0.05733948 0.2544883 0.9593885 -0.04454326 0.2785493 0.6951002 -0.1886783 0.6937119 0.794663 -0.1038521 0.5981015 0.7635127 -0.1363517 0.6312342 0.6924451 -0.2634654 0.6716442 0.6065222 -0.091219 0.7898165 0.6724044 -0.3386763 0.6581571 0.6693996 -0.3249883 0.6680471 0.7053613 -0.3247272 0.6300934 0.6972739 -0.3285402 0.6370798 0.6644297 -0.07239395 0.7438362 0.7066225 -0.09166514 0.7016283 0.9703297 -0.2073254 -0.1244052 0.8649237 -0.3761688 0.332271 0.8680693 -0.4692397 -0.1620798 0.924676 -0.3200277 0.2062927 0.9268655 -0.3749601 -0.01804161 0.8745577 -0.4678593 -0.1275016 0.9124051 -0.3792908 0.1538034 0.9078317 -0.4051738 0.1080549 0.8876683 -0.4064356 0.2164605 0.8699445 -0.3937976 0.2968503 0.7573525 -0.07392096 0.6488088 0.8150995 -0.329472 0.4765094 0.7380253 -0.3982765 0.5446968 0.8020151 -0.103723 0.5882291 0.9341938 -0.02239376 0.3560626 0.8786344 -0.1380816 0.4570944 0.9897021 -0.07021898 0.1247355 0.9760714 -0.1201468 0.181244 0.9923587 -0.09280598 -0.08131074 0.9916346 -0.06399363 -0.112097 0.8578903 -0.4698483 -0.2080069 0.8020782 -0.3881187 -0.4539101 0.9030525 -0.3528736 -0.2449011 0.9431691 -0.2085005 -0.2587659 0.8987315 -0.09254133 -0.4286232 0.963133 -0.06435084 -0.2612163 0.9448782 -0.1224625 0.3036581 0.8771311 -0.3603057 0.3175233 0.9568311 -0.004705369 0.2906066 0.941755 -0.1175854 0.3150736 0.9440956 -0.1270294 0.3042158 0.8774634 -0.3601772 0.3167498 0.8773194 -0.3598294 0.3175429 0.4774461 -0.7407342 0.4726078 0.5534309 -0.6858238 0.4726098 0.7407316 -0.4774472 0.4726108 0.7407381 -0.4774442 0.4726036 0.6858255 -0.5534313 0.4726068 0.6858193 -0.5534362 0.4726101 0.6231569 -0.6231538 0.4726044 0.6634364 -0.6290362 0.4051737 0.7048004 -0.7047975 0.08072876 0.8389675 -0.5407654 0.06088107 0.7047979 -0.7047997 0.0807299 0.7756794 -0.6259428 0.08072912 0.7756795 -0.6259431 0.08072561 0.8345232 -0.545023 0.08075261 0.811755 -0.5231651 0.2595228 0.4774463 -0.7407341 0.4726077 0.5232371 -0.8116993 0.2595524 0.5450227 -0.8345236 0.08075112 0.5407664 -0.8389669 0.06088024 0.5335195 -0.8277336 -0.1738221 0.5335239 -0.8277277 -0.1738364 0.6184227 -0.7663785 -0.1738316 0.625943 -0.7756793 0.08072894 0.6259391 -0.7756825 0.08072876 0.5534348 -0.6858237 0.4726054 0.6062164 -0.6393575 0.4729945 0.8277305 -0.5335235 -0.173824 0.8277339 -0.5335151 -0.1738339 0.7663679 -0.6184361 -0.1738305 0.766381 -0.6184194 -0.1738327 0.7145919 -0.6775514 -0.1740189 0.7067835 -0.7067822 -0.03027004 0.6775423 -0.7146015 -0.1740149 0.6184305 -0.7663704 -0.1738396 0.6355385 -0.4230661 0.6458375 0.6356356 -0.4097139 0.6542951 0.4102497 -0.6410561 0.6486467 0.4102283 -0.6399037 0.649797 0.4097068 -0.6356455 0.6542899 0.6392474 -0.4101323 0.6505031 0.6315339 -0.4094748 0.6584036 0.5907711 -0.4767265 0.6509388 0.5935276 -0.4756987 0.649181 0.5460676 -0.5177589 0.6585863 0.5537718 -0.514662 0.6545685 0.5200926 -0.548531 0.654689 0.5128644 -0.5518351 0.6576079 0.477442 -0.5916532 0.649612 0.4745933 -0.5921483 0.6512462 0.4173704 -0.6270278 0.6577523 0.5438679 -0.8156087 0.1974591 0.8324588 -0.5539837 0.01069635 0.8167666 -0.5421456 0.1974096 0.5537795 -0.8325918 0.01092678 0.5443733 -0.8198916 0.1773002 0.6154573 -0.7679368 0.1774414 0.6154904 -0.7679156 0.177418 0.669965 -0.7208803 0.1774215 0.6699852 -0.7208586 0.1774338 0.7208667 -0.6699771 0.1774317 0.7208901 -0.6699558 0.1774167 0.7679087 -0.6154946 0.177434 0.767936 -0.6154655 0.1774165 0.818731 -0.5461109 0.1773202 0.7101582 -0.4730237 0.5214633 0.7167759 -0.4758607 0.5096951 0.6712094 -0.5379626 0.5099747 0.6712167 -0.5379562 0.5099719 0.6300812 -0.5856004 0.5099707 0.6300811 -0.5855926 0.5099796 0.5855913 -0.6300914 0.5099684 0.5855734 -0.6300996 0.5099788 0.5379822 -0.6711999 0.5099666 0.5379567 -0.6712155 0.5099729 0.4769657 -0.716013 0.5097344 0.4718955 -0.7109107 0.5214602 0.8827918 -0.469762 -0.001523077 0.8688586 -0.495054 0.002525389 0.8685319 -0.4956193 0.00374794 0.8325514 -0.5538551 -0.01014113 0.8369505 -0.5434347 -0.06475162 0.7786801 -0.6241003 0.06446844 0.7921097 -0.6095242 -0.03228956 0.7322094 -0.6805032 0.02801483 0.7369723 -0.6759229 0 0.6807723 -0.7324952 0 0.675731 -0.7367658 0.02374678 0.6252803 -0.7801574 -0.01947546 0.6093831 -0.7919204 0.03891611 0.553177 -0.8315384 -0.05039012 0.5445694 -0.8386788 -0.007886886 0.4948171 -0.8689883 0.00393033 0.4956353 -0.8685268 0.002625644 0.4697639 -0.8827909 -0.001523077 0.5724915 -0.8101073 0.1264107 0.5141798 -0.8552561 0.06446993 0.4955412 -0.8683757 0.01904493 0.4883147 -0.8342073 0.2562166 0.5191429 -0.8204817 0.239375 0.5287673 -0.8143362 0.2392943 0.5287623 -0.8143405 0.2392905 0.5921401 -0.7695038 0.2392368 0.5921384 -0.7695057 0.2392343 0.6563012 -0.7155663 0.2392358 0.6563003 -0.7155677 0.239234 0.7155693 -0.6562986 0.2392336 0.7155663 -0.6563008 0.2392367 0.7695048 -0.5921388 0.2392363 0.7695027 -0.5921421 0.2392347 0.81434 -0.5287629 0.2392914 0.8143364 -0.5287671 0.239294 0.8206703 -0.5188436 0.2393773 0.8342559 -0.4883421 0.2560063 0.8552577 -0.5141766 0.06447327 0.8683701 -0.4955511 0.01904416 0.4521335 -0.8882969 0.08064711 0.5428079 -0.8359633 0.0807771 0.5428035 -0.8359659 0.0807802 0.6078594 -0.7899274 0.08075749 0.6078568 -0.7899295 0.08075702 0.6737216 -0.7345594 0.08075755 0.6737175 -0.7345631 0.08075755 0.7345626 -0.673718 0.08075761 0.7345603 -0.6737205 0.08075803 0.7899286 -0.6078577 0.08075761 0.7899288 -0.6078574 0.08075809 0.8359665 -0.5428027 0.08077919 0.8359617 -0.5428103 0.08077847 0.8441595 -0.5299662 0.08081293 0.8629507 -0.4829062 0.1487205 0.7794299 -0.5429194 0.3126143 0.8188039 -0.4793062 0.315952 0.4792825 -0.8188182 0.3159514 0.5057364 -0.7788835 0.3709061 0.4379692 -0.5691764 0.6958602 0.6688989 -0.6689133 0.3242366 0.5441901 -0.7812512 0.3057841 0.5438334 -0.7788147 0.3125585 0.5704098 -0.6219124 0.5365236 0.6980732 -0.6402477 0.3205884 0.7809154 -0.5446291 0.3058601 0.569162 -0.4379845 0.6958622 0.7788758 -0.5057426 0.3709137 0.9779682 -0.08371931 -0.1912311 0.9968695 -0.02426087 -0.07525122 0.996012 -0.02828407 -0.08461737 0.9929127 -0.07063227 -0.09557962 0.9933892 -0.07006853 -0.09093123 0.9868823 -0.1129116 -0.1153879 0.9884803 -0.1151328 -0.09824115 0.9730062 -0.1731391 -0.1525837 0.9690285 -0.243643 -0.04027408 0.9617913 -0.2649184 -0.06910675 0.9368665 -0.3482955 -0.03116899 0.9383504 -0.339348 -0.06588941 0.9418852 -0.328621 -0.06971764 0.9460658 -0.3194825 -0.05376297 0.9731402 -0.1156482 -0.1990572 0.9733477 -0.1118324 -0.2002192 0.974936 -0.1084519 -0.1942625 0.9747151 -0.09259974 -0.2033613 0.9647221 -0.03237456 -0.2612723 0.9618584 -0.09386163 -0.2569406 0.95708 -0.1329038 -0.2575548 0.9388284 -0.2317745 -0.2547196 0.8851239 -0.398878 -0.2396918 0.880392 -0.4125648 -0.2338814 0.8896304 -0.3888157 -0.2395417 0.8965738 -0.3732526 -0.2384074 0.909954 -0.3482742 -0.225142 0.884185 -0.402258 -0.2374987 0.8845013 -0.45444 -0.1055544 0.8839061 -0.4096128 -0.2256711 0.8739387 -0.4810365 -0.06953436 0.8852042 -0.4617601 -0.0564906 0.8863343 -0.457333 -0.07251328 0.8979634 -0.4368008 -0.05354458 0.904448 -0.4187862 -0.08119171 0.9138799 -0.4017808 -0.05827325 0.9188253 -0.38672 -0.07878881 0.9262616 -0.3726577 -0.05626559 0.9346947 -0.3465338 -0.07912182 0.8822558 -0.4249427 -0.2026045 0.9092175 -0.3792505 -0.1717342 0.9073511 -0.3661145 -0.206577 0.9318317 -0.3225168 -0.1663514 0.9349271 -0.2748681 -0.2244079 0.9542521 -0.2403517 -0.1778602 0.9543437 -0.2028474 -0.219274 0.9680722 -0.1768977 -0.1776045 0.9683769 -0.1248539 -0.2160037 0.5420657 -0.8084254 -0.2293756 0.818275 -0.5274292 -0.2285709 0.8082535 -0.5422549 -0.2295346 0.8093748 -0.5428585 -0.2240923 0.8207091 -0.5249373 -0.2255602 0.5429624 -0.8093985 -0.2237547 0.5431053 -0.809335 -0.2236371 0.5428604 -0.8093732 -0.224093 0.8093298 -0.5431304 -0.2235947 0.8134945 -0.534068 -0.2302129 0.7598807 -0.609028 -0.227302 0.757974 -0.6116558 -0.2266111 0.7128499 -0.6625112 -0.2300522 0.7064188 -0.6697929 -0.2288014 0.6627228 -0.7130779 -0.2287327 0.6695237 -0.7061355 -0.2304576 0.6091588 -0.7600392 -0.2264203 0.6115736 -0.7578747 -0.2271645 0.5288879 -0.8168368 -0.2303376 0.5274279 -0.8182756 -0.2285715 0.5528497 -0.8243231 -0.121856 0.7322972 -0.6805608 -0.02403992 0.7430287 -0.6592724 -0.1151887 0.7751173 -0.6212397 -0.1151285 0.7751143 -0.6212438 -0.1151258 0.824998 -0.5532954 -0.1150761 0.8267741 -0.5616827 -0.03093987 0.847811 -0.5174491 -0.1160302 0.5528892 -0.825272 -0.1150643 0.5955372 -0.7950268 -0.1151871 0.6234824 -0.7779039 -0.07832866 0.6242244 -0.7727124 -0.1151505 0.6762599 -0.7276136 -0.1151132 0.6762281 -0.7276409 -0.1151278 0.7184371 -0.6859908 -0.1151733 0.9858421 0.1675142 -0.007380247 0.9860355 0.1661378 0.01149612 0.9876389 0.1544028 0.02700632 0.9849865 0.1715804 0.01902419 0.9801201 0.1977939 0.0155574 0.9969524 0.0499351 0.05993676 0.9964646 0.0593093 0.0595054 0.9960349 0.06540411 0.06030756 0.9960949 0.0649411 0.05981338 0.9953417 0.07515853 0.06038373 0.9952691 0.07576006 0.06082636 0.9951996 0.07670414 0.06078106 0.9944419 0.08093512 0.0673415 0.994316 0.08259105 0.06719112 0.994049 0.08211129 0.07158583 0.9977808 0.02596974 0.06131076 0.9976683 0.03841978 0.05640882 0.9975079 0.04045176 0.05780899 0.9971264 0.04667472 0.05967074 0.996724 0.05093705 0.06282317 0.9981863 0.008171737 0.05964356 0.9983066 0.01635217 0.05582582 0.9978761 0.0251888 0.06007486 0.9981828 -0.01575797 0.05816298 0.9982765 -0.01405262 0.05697834 0.9983574 -0.005298018 0.05704736 0.9981572 -0.00864309 0.06006252 0.9981574 0.008630216 0.06006205 0.9969354 -0.06109565 0.04885959 0.9957258 -0.05302524 0.07562196 0.996771 -0.04971635 0.06305336 0.997627 -0.03999859 0.0560401 0.997403 -0.04194033 0.05855208 0.9978986 -0.02901774 0.05793422 0.9977435 -0.02999186 0.06007063 0.9981459 -0.0215981 0.05690753 0.9847258 -0.1738626 0.009317934 0.9961074 -0.06701642 0.05726188 0.9951612 -0.07476615 0.06375151 0.9927758 -0.1151667 0.03366017 0.9859056 -0.1671113 0.007996976 0.9880357 -0.1374881 0.06987577 0.9736457 -0.2247223 0.03890967 0.9840205 -0.1773998 0.01526767 0.9865031 -0.1607019 0.03141283 0.977721 -0.2094727 0.01352775 0.9760392 -0.215566 0.02964586 0.9743389 -0.2234177 0.0273537 0.9699023 -0.2418951 0.02786499 0.9529702 -0.3029282 0.009075284 0.9940315 -0.04588305 0.09897607 0.9934037 -0.08565223 0.07624173 0.9928453 -0.08737105 0.08139169 0.992728 -0.09090042 0.07891923 0.995211 -0.076743 0.06054526 0.9944992 -0.08055824 0.0669471 0.9938347 -0.08589583 0.0701034 0.9938699 -0.08357203 0.0723766 0.9933053 -0.08576452 0.07738894 0.995649 0.09318327 -1.34359e-4 0.9957557 0.09203559 -1.19682e-4 2.53789e-6 0 1 0 0.09446334 -0.9955284 0 0.09446442 -0.9955283 0 -0.09471207 -0.9955048 0 -0.09470927 -0.995505 0 -0.2396654 0.9708555 0 -0.2396656 0.9708555 0 -0.6638678 0.74785 0 -0.6638697 0.7478483 0 -0.9393307 0.3430131 0 -0.9393306 0.3430132 0 -0.9956658 -0.09300428 0 -0.9956658 -0.09300369 0 -0.8696046 -0.4937489 0 -0.8696049 -0.4937483 0 -0.6804974 -0.7327505 0 -0.6805054 -0.7327431 0 -0.4173951 -0.9087252 0 -0.4173959 -0.9087247 0 -0.0919947 -0.9957595 0 -0.09199392 -0.9957596 0 0.2396697 -0.9708545 0 0.2396703 -0.9708544 0 0.6638718 -0.7478465 0 0.6638678 -0.74785 0 0.8877367 -0.4603517 -1.05772e-5 0.8877567 -0.4603131 1.17771e-5 0.9751905 -0.2213675 0 0.9751989 -0.2213302 0 0.9956657 0.09300482 0 0.9956662 0.0929988 0 0.8696043 0.4937493 0 0.8696033 0.493751 0 0.6805033 0.7327451 0 0.6804961 0.7327517 0 0.4173971 0.9087242 0 0.4173951 0.9087252 0 0.0919823 0.9957606 0 0.0919823 0.9957607 0.9517651 -0.3044024 0.03850263 0.9504616 -0.3094607 -0.02927458 0.950781 -0.3069931 -0.04208052 0.949059 -0.3125095 -0.04031157 0.9466015 -0.3217094 -0.02117919 0.9506474 -0.3071215 -0.04411286 0.9509623 -0.3057632 -0.04668688 0.9332778 -0.3591546 -8.54877e-4 0.9339932 -0.3572905 6.16366e-4 0.9341479 -0.3568854 -7.40875e-4 0.9382714 -0.3458997 5.91428e-4 0.9444077 -0.3287209 0.006066858 0.9498161 -0.3121333 0.02055209 0.9529253 -0.3014801 0.03229576 0.952302 -0.3047134 0.01645463 0.9525048 -0.3039926 0.01797896 0.9510954 -0.3088493 -0.005464553 0 0.2419432 -0.9702905 0 0.2419432 -0.9702905 0 0.6079278 -0.7939924 0.02989351 0.6625133 -0.7484534 0 0.7770803 -0.6294016 0 0.9309081 -0.3652537 0 0.9309065 -0.3652575 0 0.9974081 -0.07195287 0 0.9974081 -0.07195198 0 -0.9714444 -0.2372677 0 -0.9714437 -0.2372701 0 -0.7485084 -0.6631254 0 -0.3542217 -0.9351615 0 -0.3542222 -0.9351614 0 -0.06091654 -0.998143 0 -0.06091713 -0.9981429 0 -1 0 0 -0.2419428 0.9702906 0 -0.2419432 0.9702904 0 -0.6660092 0.7459436 0 -0.6660124 0.7459408 0 -0.930907 0.3652565 0 -0.9309064 0.3652581 0 -0.9974082 0.07195037 0 -0.9974084 0.07194864 0 0.9714438 0.2372699 0.06928241 0.8114771 0.580263 0 0.7485083 0.6631255 0 0.971444 0.2372692 0 0.6532236 0.7571651 0 0.3542221 0.9351614 0 0.3542205 0.935162 0 0.06091648 0.998143 0 0.06091696 0.9981429 0.9878833 -0.1546386 0.01317399 0.9867008 -0.1596275 0.03066956 0.987551 -0.1565899 0.01492178 0.9865626 -0.1602699 0.03174787 0.9520223 -0.2688167 0.1462574 0.993519 -0.1136624 0.001074433 0.989715 -0.1430342 0.002377569 0.9929047 -0.1189026 -0.001559615 0.9931888 -0.1164219 0.004683852 0.9882878 -0.1495219 -0.03050541 0.988234 -0.1521968 -0.01515614 0.988379 -0.1486001 -0.03201842 0.9881899 -0.03234851 -0.149781 0.9807608 -0.1952106 -0.001117587 0.9861597 -0.1657798 -0.002492249 0.9817917 -0.1899539 0.001642048 0.981288 -0.1924865 -0.00478655 0.9879692 -0.1546515 0 0.9879692 -0.1546513 0 0.987886 -0.1546385 -0.01297181 0 0.2419432 -0.9702905 0 0.2419432 -0.9702904 0 0.666014 -0.7459393 0 0.6660124 -0.7459408 0 0.9309065 -0.3652576 0 0.9309068 -0.3652569 0 0.9974083 -0.07195055 0 0.9974084 -0.07194828 0 -0.971444 -0.2372692 0 -0.9714444 -0.2372675 0 -0.748506 -0.663128 0 -0.7485074 -0.6631265 0 -0.3542247 -0.9351604 0 -0.3542268 -0.9351595 0 -0.06091678 -0.9981429 0 -0.06091684 -0.9981428 0 -0.2419432 0.9702905 0 -0.2419432 0.9702904 0 -0.6660108 0.7459422 0 -0.6660124 0.7459408 0 -0.9309065 0.3652576 0 -0.9309068 0.3652569 0 -0.9974083 0.07195055 0 -0.9974084 0.07194828 0 0.9714438 0.2372703 0 0.9714441 0.2372686 0 0.7485084 0.6631253 0 0.7485098 0.6631238 0 0.3542205 0.935162 0 0.3542226 0.9351611 0 0.06091678 0.9981429 0 0.06091684 0.9981428 0.9999186 0 -0.01275712 0.9993998 -0.003356635 -0.03447872 0.9997975 -0.01464831 -0.01380687 0.9995282 0.001223623 -0.03068864 0.9997435 -0.02252739 -0.002395391 0.9994986 0.005836606 -0.03111928 0.9995413 0.005055725 -0.02986115 0.9993999 0.003368377 0.03447955 0.9997975 0.01464855 0.01380711 0.9995284 -0.001223504 0.03068602 0.9997434 0.02252835 0.00239551 0.9994987 -0.005836546 0.03111886 0.9995414 -0.005055785 0.02986145 0.9999187 0 0.01275712 0 0.2419428 -0.9702906 0 0.2419432 -0.9702904 0 0.6660092 -0.7459436 0 0.6660124 -0.7459408 0 0.9309077 -0.3652547 0 0.930907 -0.3652563 0 0.9974082 -0.07195091 0 0.9974083 -0.07194954 0 -0.9714438 -0.2372699 0.06927782 -0.8114756 -0.5802655 0 -0.7485083 -0.6631255 0 -0.971444 -0.2372692 0 -0.6532269 -0.7571622 0 -0.3542221 -0.9351614 0 -0.3542205 -0.935162 0 -0.06091648 -0.998143 0 -0.06091696 -0.9981429 0 -0.2419432 0.9702905 0 -0.2419432 0.9702905 0 -0.6079278 0.7939924 0.02989137 -0.6625134 0.7484535 0 -0.7770803 0.6294016 0 -0.9309078 0.3652546 0 -0.9309059 0.3652592 0 -0.9974081 0.07195198 0 -0.9974082 0.07195115 0 0.9714444 0.2372677 0 0.9714437 0.2372701 0 0.7485084 0.6631254 0 0.3542217 0.9351615 0 0.3542222 0.9351614 0 0.06091654 0.998143 0 0.06091713 0.9981429 0.9878833 0.1546386 -0.01317399 0.9867008 0.1596275 -0.03066956 0.9875515 0.1565872 -0.01492154 0.9865626 0.1602699 -0.03174787 0.9520256 0.2688077 -0.1462524 0.9935204 0.1136497 -0.001074492 0.9897147 0.1430355 -0.002377629 0.9929047 0.1189026 0.001559615 0.9931889 0.1164215 -0.004683852 0.9882878 0.1495219 0.03050541 0.9882344 0.1521941 0.01515585 0.988379 0.1486001 0.03201842 0.9881891 0.03234964 0.1497862 0.9807558 0.1952355 0.001117587 0.9861597 0.1657798 0.002492249 0.981792 0.1899524 -0.001642048 0.9812892 0.1924805 0.00478655 0.9879692 0.1546513 0 0.9879692 0.1546515 0 0.9878861 0.1546381 0.01297181 0 0.2419422 -0.9702908 0 0.2419444 -0.9702901 0 0.666013 -0.7459402 0 0.666012 -0.7459411 0 0.9309068 -0.3652567 0 0.9309085 -0.3652528 0 0.997408 -0.07195323 0 0.9974082 -0.07195228 0 -0.971444 -0.2372692 0 -0.9714438 -0.2372701 0 -0.7485084 -0.6631253 0 -0.7485091 -0.6631246 0 -0.3542224 -0.9351613 0 -0.3542219 -0.9351615 0 -0.06093585 -0.9981417 0 -0.06093555 -0.9981417 0 -0.2419433 0.9702904 0 -0.2419428 0.9702906 0 -0.6660116 0.7459414 0 -0.666012 0.7459411 0 -0.9309068 0.3652569 0 -0.9309061 0.3652588 0 -0.9974087 0.07194471 0 -0.9974084 0.0719484 0 0.9714443 0.2372683 0 0.9714437 0.2372706 0 0.7485077 0.6631262 0 0.7485079 0.663126 0 0.3542233 0.9351609 0 0.354222 0.9351614 0 0.06091678 0.9981428 0 0.06091701 0.9981428 0.9508539 0.3093074 -0.01434791 0.9487724 0.3142114 -0.03320032 0.950289 0.3109608 -0.0159524 0.9485758 0.3147083 -0.03410047 0.8948192 0.4185138 -0.1553865 0.9633821 0.2681301 -0.001154303 0.954742 0.2974252 -0.002491891 0.9619207 0.2733237 0.001641511 0.9626103 0.2708446 -0.004987359 0.9520705 0.304112 0.03282886 0.9523478 0.3030318 0.03472012 0.9696052 0.1820907 0.1634282 0.9517012 0.3065819 0.01650106 0.9473534 0.320178 0.002772688 0.9388225 0.344397 -0.00181812 0.9379913 0.3466312 0.004359662 0.9340111 0.3572439 5.95242e-4 0.950952 0.3093386 0 0.950951 0.3093413 0 0.95086 0.30931 0.01388198 -0.917203 -0.3490356 0.1921277 -0.9067772 -0.36581 0.2096146 -0.821251 -0.1227212 0.5572131 -0.8140929 -0.1310238 0.565761 -0.849633 -0.4855493 -0.2058292 -0.8507686 -0.4958811 -0.1740541 -0.8853495 -0.4624369 -0.04804801 -0.825712 -0.5608075 0.06078594 -0.8558632 -0.4892756 0.1676535 -0.8382955 -0.4792637 0.2599366 -0.834644 -0.4714598 0.2847722 -0.7568342 -0.4760652 0.4478438 -0.7180763 -0.5121048 0.471291 -0.6849124 -0.3915219 0.6144963 -0.6561298 -0.3750969 0.6548252 -0.8694472 -0.4939465 0.008860826 -0.7868865 -0.3390421 0.5156165 -0.7463894 -0.328795 0.5786162 -0.8999223 -0.3825964 0.2091884 -0.7910663 -0.1787652 0.5850275 -0.8249013 -0.1909362 0.5320538 -0.8949131 -0.4039707 0.1895737 -0.8636583 -0.4588726 0.2086398 -0.867173 -0.4583357 0.1947805 -0.845195 -0.4829704 -0.228878 -0.9569957 -0.004841744 0.2900621 -0.9102603 -0.3867146 0.147912 -0.9098017 -0.3778498 0.1717274 -0.9368071 -0.2479864 0.2467699 -0.9751145 -0.0845133 0.2049618 -0.9594151 -0.1277764 0.2513881 -0.8718823 -0.4134814 0.2624012 -0.8794103 -0.360805 0.3105759 -0.9301859 -0.2502439 0.2685745 -0.9371316 -0.1238582 0.3262571 -0.9523782 -0.09352898 0.290221 -0.9569959 -0.004844427 0.2900611 -0.9573063 -0.004651308 0.2890379 -0.9339845 -0.1519668 0.323387 -0.9326713 -0.3601284 0.02077823 -0.9286774 -0.3650594 0.06549787 -0.9585192 -0.09776699 0.2677365 -0.9597147 -0.007412075 0.2808787 -0.9634463 -0.002216696 0.2678925 -0.9641045 -0.007510721 0.265417 -0.9657477 -0.1398575 0.2185666 -0.9965574 -0.01983261 0.08049935 -0.9529658 -0.2374404 0.1883566 -0.9607027 -0.226051 0.1610937 -0.872496 -0.4393129 0.213904 -0.9269784 -0.3577306 0.1128716 -0.9741371 0.01226645 0.2256249 -0.9411327 -0.3323615 0.06168693 -0.9081042 -0.4102186 0.08406919 -0.9279438 -0.3664214 0.0682339 -0.9769678 -0.1947165 0.08728998 -0.9469058 -0.3109373 0.08177751 -0.9244728 -0.3528828 0.1443046 -0.9755473 -0.1220447 0.1827909 -0.9771209 -0.1120774 0.1807577 -0.9839683 -0.1055961 0.1437219 -0.9890235 -0.06370753 0.1333194 -0.9255575 -0.3273168 0.1902816 -0.8221802 -0.1147502 0.5575411 -0.9158477 -0.3300394 0.2286859 -0.9455893 -0.2586166 0.1974293 -0.9329752 -0.2511289 0.2578595 -0.9615921 -0.1512606 0.2290439 -0.950723 -0.1542077 0.2689718 -0.9662827 -0.04805326 0.25296 -0.9589101 -0.05457496 0.2784116 -0.81452 -0.1146591 0.5686919 -0.8251773 -0.08974456 0.5576992 -0.8135562 -0.0860961 0.5750772 -0.8234255 -0.05156135 0.565077 -0.8153157 -0.05211824 0.5766664 -0.8206747 -0.01580452 0.5711772 -0.8154143 -0.0178734 0.5786019 -0.7655149 -0.1392748 0.6281635 -0.6920394 -0.2630088 0.6722409 -0.6682317 -0.3297578 0.666878 -0.6704211 -0.3414404 0.6587519 -0.628744 -0.09710538 0.7715256 -0.7005184 -0.1919326 0.6873397 -0.7078218 -0.001379013 0.7063897 -0.7063685 -0.09745824 0.7011031 -0.6483257 -0.07206332 0.7579452 -0.7050433 -0.3289374 0.6282629 -0.7040532 -0.3294333 0.6291127 -0.8042626 -0.07423788 0.5896191 -0.9289278 -0.347766 -0.1270903 -0.8386996 -0.5359203 0.0968129 -0.8209695 -0.3290898 0.4665931 -0.7333536 -0.4111121 0.5414603 -0.8858145 -0.3651069 0.2864082 -0.8605135 -0.3875195 0.3306739 -0.8957281 -0.4129524 0.1647472 -0.9320434 -0.3623279 0.003688335 -0.8855288 -0.4620891 -0.0480864 -0.9898298 -0.06314277 -0.1274756 -0.7631915 -0.1171458 0.6354649 -0.8875115 -0.06551808 0.4561039 -0.927749 -0.1172403 0.3543116 -0.9822224 -0.08191269 0.1689066 -0.9864879 -0.1075047 0.1236299 -0.9914555 -0.1003733 -0.08331453 -0.9706866 -0.2057866 -0.1241747 -0.9631904 -0.06338536 -0.2612404 -0.8969492 -0.09246188 -0.4323576 -0.943338 -0.2073439 -0.2590793 -0.9042032 -0.3494904 -0.2455058 -0.7997453 -0.3876306 -0.4584211 -0.8587275 -0.4682096 -0.2082476 -0.9449538 -0.121996 0.3036104 -0.9568325 -0.004730701 0.2906017 -0.8773194 -0.3598294 0.3175429 -0.9418413 -0.1171264 0.3149863 -0.9443048 -0.1271284 0.3035242 -0.9182029 -0.2431503 0.3127001 -0.8774636 -0.3601773 0.3167492 -0.8771311 -0.3603057 0.3175233 -0.7407342 -0.4774461 0.4726078 -0.6858224 -0.5534329 0.4726096 -0.6349263 -0.6349295 0.4401513 -0.4774443 -0.7407349 0.4726087 -0.4774504 -0.7407321 0.4726067 -0.5534351 -0.6858214 0.4726085 -0.5534322 -0.6858243 0.4726076 -0.606213 -0.6393603 0.4729951 -0.7047974 -0.7048004 0.08072912 -0.5407664 -0.8389669 0.06088024 -0.7047991 -0.7047984 0.08073133 -0.6259425 -0.7756793 0.0807318 -0.6259393 -0.7756825 0.08072608 -0.5450227 -0.8345236 0.08075112 -0.5232371 -0.8116993 0.2595524 -0.7407318 -0.4774489 0.4726087 -0.811755 -0.5231651 0.2595228 -0.8345232 -0.545023 0.08075261 -0.8389675 -0.5407654 0.06088107 -0.8277363 -0.5335161 -0.1738198 -0.8277287 -0.5335218 -0.1738382 -0.7663729 -0.6184301 -0.1738303 -0.7756794 -0.6259429 0.08072763 -0.7756794 -0.6259432 0.08072721 -0.6858268 -0.5534312 0.4726053 -0.639364 -0.606212 0.4729912 -0.5335295 -0.827728 -0.173818 -0.5335157 -0.8277319 -0.1738415 -0.6184179 -0.7663823 -0.1738314 -0.6184353 -0.7663666 -0.1738398 -0.6775403 -0.7146022 -0.1740195 -0.7067835 -0.7067822 -0.03027004 -0.7145963 -0.6775467 -0.1740196 -0.7663761 -0.6184254 -0.1738329 -0.4230648 -0.6355397 0.645837 -0.4097068 -0.6356455 0.6542899 -0.6410564 -0.4102476 0.6486474 -0.6399092 -0.4102269 0.6497924 -0.6356356 -0.4097139 0.6542951 -0.4101639 -0.6392371 0.6504935 -0.4094753 -0.6315327 0.6584045 -0.4767252 -0.59077 0.6509409 -0.4757032 -0.5935268 0.6491783 -0.5177562 -0.546071 0.6585857 -0.5146641 -0.5537672 0.6545708 -0.5485309 -0.5200935 0.6546882 -0.551835 -0.5128651 0.6576075 -0.5916541 -0.4774406 0.6496122 -0.5921497 -0.4745934 0.6512449 -0.6270306 -0.4173686 0.6577507 -0.8155972 -0.5438897 0.1974474 -0.5537795 -0.8325918 0.01092678 -0.5421668 -0.8167541 0.1974035 -0.8324588 -0.5539837 0.01069635 -0.8199004 -0.5443603 0.1772999 -0.7679241 -0.6154789 0.1774207 -0.7679206 -0.615481 0.1774296 -0.7208667 -0.6699771 0.1774317 -0.7208901 -0.6699558 0.1774167 -0.6699661 -0.7208772 0.1774305 -0.6699841 -0.7208619 0.1774249 -0.6154691 -0.7679298 0.177431 -0.6154787 -0.7679227 0.1774283 -0.5460812 -0.8187467 0.1773391 -0.4730439 -0.7101378 0.5214728 -0.4758712 -0.7167734 0.5096887 -0.5379573 -0.671213 0.5099757 -0.5379695 -0.6712086 0.5099685 -0.5855997 -0.6300829 0.5099693 -0.5855764 -0.6301017 0.5099728 -0.6300792 -0.5855964 0.5099777 -0.6300831 -0.5855966 0.5099725 -0.6712098 -0.5379619 0.509975 -0.6712164 -0.537957 0.5099716 -0.7160211 -0.4769615 0.509727 -0.7109252 -0.4718686 0.5214648 -0.4697639 -0.8827909 -0.001523077 -0.4950443 -0.8688642 0.002529084 -0.4956301 -0.8685258 0.003743946 -0.553857 -0.8325502 -0.01014101 -0.5434432 -0.8369454 -0.06474566 -0.6241039 -0.7786773 0.06446808 -0.6095265 -0.7921078 -0.03229385 -0.6805067 -0.7322061 0.0280193 -0.6759201 -0.7369749 0 -0.7324969 -0.6807704 0 -0.7367646 -0.6757324 0.02374267 -0.7801566 -0.6252815 -0.01946872 -0.7919161 -0.6093889 0.03891217 -0.8315365 -0.55318 -0.05038899 -0.8386791 -0.5445688 -0.007891416 -0.8689759 -0.4948387 0.003935575 -0.8685314 -0.4956272 0.002619445 -0.8827918 -0.469762 -0.001523077 -0.8101045 -0.5724949 0.126414 -0.8552552 -0.5141807 0.0644738 -0.8683718 -0.4955482 0.01904314 -0.8342147 -0.4883036 0.2562136 -0.8204814 -0.5191428 0.2393762 -0.8143389 -0.5287638 0.2392927 -0.8143378 -0.5287658 0.2392926 -0.7695042 -0.5921397 0.2392361 -0.7695034 -0.5921411 0.2392356 -0.7155691 -0.6562984 0.2392349 -0.715566 -0.6563012 0.2392361 -0.656302 -0.7155658 0.2392347 -0.6562973 -0.7155695 0.2392366 -0.5921393 -0.7695041 0.2392379 -0.5921374 -0.7695068 0.2392341 -0.528765 -0.8143384 0.2392915 -0.5287647 -0.8143384 0.2392926 -0.5188475 -0.8206684 0.239376 -0.4883412 -0.8342562 0.2560068 -0.5141814 -0.8552549 0.06447213 -0.4955377 -0.8683778 0.0190438 -0.8882982 -0.4521313 0.08064496 -0.8359658 -0.5428038 0.08077907 -0.8359624 -0.5428093 0.08077871 -0.7899293 -0.6078569 0.08075773 -0.7899292 -0.607857 0.08075761 -0.7345626 -0.673718 0.08075761 -0.7345606 -0.6737202 0.08075815 -0.6737209 -0.73456 0.08075743 -0.6737172 -0.7345633 0.08075857 -0.6078602 -0.7899269 0.08075624 -0.607854 -0.7899316 0.08075791 -0.5428071 -0.8359636 0.08078014 -0.5428038 -0.8359661 0.08077728 -0.5299715 -0.8441561 0.08081364 -0.4828884 -0.8629609 0.1487188 -0.5429103 -0.7794379 0.31261 -0.4792882 -0.8188163 0.3159473 -0.5057465 -0.778878 0.3709035 -0.8188039 -0.4793062 0.315952 -0.7788758 -0.5057426 0.3709137 -0.569162 -0.4379845 0.6958622 -0.4379532 -0.5691791 0.6958679 -0.5446372 -0.7809075 0.305866 -0.64025 -0.6980715 0.3205873 -0.6355777 -0.6355879 0.4382569 -0.6980761 -0.6402449 0.3205875 -0.781246 -0.544195 0.3057888 -0.7788323 -0.5438154 0.3125461 -0.9779725 -0.08371108 -0.1912129 -0.9967373 -0.0292173 -0.07524126 -0.9962539 -0.02323222 -0.08329874 -0.9931313 -0.06831872 -0.09498775 -0.9931385 -0.07209187 -0.09208029 -0.9883032 -0.1048141 -0.1107741 -0.9871355 -0.121367 -0.1040844 -0.9824222 -0.1409344 -0.1224103 -0.9525997 -0.2873339 -0.09996545 -0.9389214 -0.3381714 -0.063771 -0.9412819 -0.3298821 -0.07187634 -0.9460658 -0.3194825 -0.05376297 -0.9368724 -0.3482782 -0.03118187 -0.9617955 -0.2649011 -0.06911659 -0.9733291 -0.115261 -0.1983569 -0.9731518 -0.1122579 -0.2009323 -0.9751008 -0.1080945 -0.1936336 -0.9745256 -0.09312105 -0.2040303 -0.960967 -0.09385806 -0.2602561 -0.9657672 -0.04432278 -0.2555959 -0.9570805 -0.1329003 -0.2575546 -0.9388282 -0.2317744 -0.2547199 -0.884185 -0.402258 -0.2374987 -0.9099553 -0.3482716 -0.2251405 -0.896453 -0.3734695 -0.2385221 -0.8903709 -0.3869791 -0.2397642 -0.8805627 -0.4120825 -0.2340884 -0.8851241 -0.3988776 -0.2396916 -0.8803401 -0.4170539 -0.2259811 -0.878911 -0.4647625 -0.1072908 -0.8826916 -0.4242537 -0.2021495 -0.902558 -0.3912307 -0.1797989 -0.912839 -0.3570225 -0.1981414 -0.9245559 -0.3363534 -0.1790614 -0.9401364 -0.266252 -0.2127287 -0.9488594 -0.2507268 -0.1918385 -0.9588511 -0.1948931 -0.2064489 -0.9654115 -0.1823435 -0.1863638 -0.9706849 -0.1205005 -0.2079675 -0.8824335 -0.4666262 -0.05976074 -0.8823939 -0.4666939 -0.05981492 -0.8885909 -0.4534901 -0.06894153 -0.8947953 -0.4425783 -0.05887323 -0.9065936 -0.4150797 -0.07613873 -0.9113852 -0.4064662 -0.06451588 -0.9208168 -0.3831058 -0.0729832 -0.9247445 -0.375664 -0.0610277 -0.935943 -0.3441336 -0.07471811 -0.5274279 -0.8182756 -0.2285715 -0.8082535 -0.5422549 -0.2295346 -0.8093985 -0.5429624 -0.223754 -0.8093329 -0.5431085 -0.2236372 -0.8093748 -0.5428585 -0.2240923 -0.5420657 -0.8084254 -0.2293756 -0.5428604 -0.8093732 -0.224093 -0.5249384 -0.8207083 -0.2255606 -0.5431304 -0.8093298 -0.2235947 -0.5340683 -0.8134944 -0.230213 -0.6090308 -0.7598786 -0.227302 -0.6116546 -0.757975 -0.2266111 -0.6625102 -0.7128506 -0.2300527 -0.6697933 -0.7064186 -0.228801 -0.7130784 -0.662722 -0.2287328 -0.7061348 -0.6695247 -0.2304569 -0.7600396 -0.609158 -0.2264208 -0.7578742 -0.6115742 -0.2271645 -0.8168373 -0.528887 -0.2303379 -0.818275 -0.5274292 -0.2285709 -0.9570344 0 0.2899745 -0.957031 0 0.2899857 -0.9570306 0 0.2899872 -0.9570326 0 0.2899804 -0.9570304 -4.12547e-7 0.2899875 -0.9570307 5.29125e-7 0.2899869 -0.957029 -2.0465e-7 0.2899925 -0.9570307 2.06054e-7 0.2899867 -0.9591575 0 0.2828728 -0.9890108 0 0.1478437 -0.9889419 -3.37977e-5 0.1483042 -0.9751135 4.33793e-5 0.2217063 -0.9632125 -2.19067e-4 0.2687409 -0.9751012 -0.00166285 0.2217542 -0.9586704 0.005913972 0.2844575 -0.9628168 0.004392266 0.2701196 -0.8155433 0 0.5786963 -0.8155459 0 0.5786924 -0.9603434 0 0.2788202 -0.9603372 0 0.2788416 -0.7078166 3.90796e-7 0.7063964 -0.7078746 -6.04897e-5 0.7063381 -0.7078205 -1.36697e-6 0.7063924 -0.7078169 2.03088e-6 0.706396 -0.7078173 0 0.7063957 -0.7078205 1.36697e-6 0.7063924 -0.7078746 6.04897e-5 0.7063381 -0.7078138 0 0.7063991 -0.7078227 -4.42596e-6 0.7063902 -0.70783 0 0.7063828 -0.7078291 0 0.7063838 -0.7078227 4.42596e-6 0.7063902 -0.755844 0 0.6547518 -0.762703 -1.35945e-4 0.6467489 -0.8794702 2.6502e-4 0.4759539 -0.8857759 -7.01821e-5 0.4641135 -0.980306 7.77857e-5 0.1974849 -0.9837976 -4.23927e-4 0.1792826 -0.9941815 4.08806e-4 -0.1077175 -0.9923714 0 -0.1232852 -0.9652289 7.31578e-6 -0.2614064 -0.9653553 4.68795e-4 -0.260939 -0.9652332 0 -0.2613905 -0.9652303 7.15781e-6 -0.2614013 -0.9653641 -6.31524e-4 -0.2609056 -0.9652308 7.38665e-6 -0.2613996 -0.9652331 0 -0.2613908 -0.9652333 0 -0.26139 -0.9652308 -7.38665e-6 -0.2613996 -0.9652267 -7.45084e-6 -0.2614146 -0.9652281 9.95104e-7 -0.2614095 -0.9652277 -3.69381e-6 -0.2614107 -0.9652276 0 -0.2614111 -0.9652281 -9.95104e-7 -0.2614095 -0.9652266 7.91654e-6 -0.261415 -0.9971628 0 -0.07527577 -0.9971632 0 -0.07527077 -0.9935318 1.20311e-5 0.1135554 -0.9935328 6.2317e-7 0.1135463 -0.9935323 -1.54225e-6 0.1135499 -0.9935327 0 0.1135464 -0.9935328 0 0.1135454 -0.9935327 4.19102e-7 0.1135467 -0.9935327 -7.95333e-7 0.1135464 -0.9935327 0 0.1135464 -0.9935326 1.20349e-6 0.1135475 -0.9935327 -1.79978e-7 0.1135464 -0.9935326 -1.34934e-6 0.1135471 -0.9935327 8.00914e-7 0.1135463 -0.9935325 -5.56049e-7 0.1135485 -0.993533 8.25883e-7 0.1135441 -0.9935324 -1.05286e-6 0.1135489 -0.9935328 2.59296e-6 0.1135452 -0.993532 0 0.113553 -0.993532 7.31226e-7 0.1135533 -0.993534 1.89939e-6 0.1135358 -0.9935321 4.28069e-6 0.113552 -0.9935315 -8.08239e-6 0.1135568 -0.9935339 2.39005e-6 0.1135358 -0.552439 -0.8246107 -0.1217722 -0.5532982 -0.8249946 -0.1150868 -0.5955372 -0.7950268 -0.1151871 -0.6266835 -0.7757564 -0.07395774 -0.6212463 -0.775114 -0.1151151 -0.6762437 -0.7276289 -0.1151124 -0.6762443 -0.7276257 -0.1151285 -0.7184371 -0.6859908 -0.1151733 -0.7322971 -0.6805607 -0.02404665 -0.7430309 -0.6592693 -0.1151924 -0.7751036 -0.6212568 -0.1151282 -0.775128 -0.6212267 -0.1151261 -0.8216713 -0.5582174 -0.115107 -0.8298035 -0.556517 -0.04141455 -0.8478137 -0.5174449 -0.1160287 -0.9738438 -0.2240178 0.0380038 -0.9940594 -0.04585939 0.098706 -0.9798912 -0.1977298 0.02676451 -0.9805324 -0.1943735 0.02784609 -0.9710924 -0.2379071 0.01949441 -0.9718061 -0.2344036 0.02545458 -0.9667653 -0.2537966 0.0308597 -0.9564832 -0.2917873 -3.20097e-4 -0.9936006 -0.08207732 0.07759654 -0.9933388 -0.08568221 0.07704907 -0.9928299 -0.08740162 0.08154606 -0.9928295 -0.08740609 0.08154612 -0.9932044 -0.08622395 0.07817035 -0.9881511 -0.1371167 0.06896799 -0.8157632 0.1335099 0.5627659 -0.8195922 0.120078 0.5602231 -0.9067441 0.369788 0.2026627 -0.9173036 0.3448344 0.1991066 -0.6849124 0.3915219 0.6144963 -0.7210835 0.5303928 0.4457826 -0.7341691 0.4877804 0.4722987 -0.8330035 0.4681212 0.294903 -0.8383125 0.4792428 0.2599201 -0.8474211 0.4843345 0.2174801 -0.8505155 0.5013635 0.1589283 -0.829732 0.554839 0.06081789 -0.8733918 0.4869639 -0.007284522 -0.8557638 0.4923311 -0.1589925 -0.8507686 0.4958811 -0.1740541 -0.8496345 0.4855466 -0.2058296 -0.6561298 0.3750969 0.6548252 -0.8647277 0.4628549 0.1949648 -0.7733598 0.3658744 0.517736 -0.8694472 0.4939465 0.008860826 -0.8658807 0.4552385 0.2073848 -0.9003438 0.3934718 0.1859057 -0.8949239 0.3916637 0.2138012 -0.7593322 0.3089151 0.5727009 -0.8125305 0.2159482 0.5414432 -0.8031994 0.1571953 0.574596 -0.8451951 0.4829699 -0.2288785 -0.9044533 0.3917864 0.1687241 -0.8395159 0.4280623 0.3346278 -0.8917881 0.3666626 0.2650899 -0.9569976 0.004840195 0.2900556 -0.9573063 0.004651308 0.2890379 -0.9604588 0.09073084 0.263224 -0.9702571 0.1148046 0.2131223 -0.914153 0.3732911 0.1580446 -0.9368071 0.2479864 0.2467699 -0.9301859 0.2502439 0.2685745 -0.9363463 0.09826332 0.3370459 -0.9483924 0.1290736 0.2896412 -0.956995 0.004845857 0.2900642 -0.872496 0.4393129 0.213904 -0.9269794 0.357728 0.1128708 -0.9607034 0.2260482 0.1610934 -0.924176 0.1352413 0.3572233 -0.9560122 0.1314352 0.2622318 -0.9639148 0.007682383 0.2661002 -0.9237786 0.3780254 0.06107306 -0.9360987 0.3499287 0.03562486 -0.9529657 0.2374423 0.1883547 -0.9894908 0.08798295 0.1147478 -0.9673906 0.08552163 0.2384145 -0.9636388 0.002113819 0.2672004 -0.9597147 0.007412075 0.2808787 -0.9870361 0.1025457 0.1234669 -0.916647 0.3597428 0.1741937 -0.9244728 0.3528828 0.1443046 -0.9469067 0.3109347 0.08177727 -0.976967 0.19472 0.08728992 -0.9832627 0.05871695 0.1724725 -0.9279438 0.3664214 0.0682339 -0.9392815 0.3381928 0.05810433 -0.9755473 0.1220447 0.1827909 -0.9772183 0.1114385 0.1806265 -0.9742284 -0.01256573 0.2252138 -0.8192565 0.1206904 0.5605825 -0.9169241 0.3456273 0.1994796 -0.8173938 0.1081367 0.565839 -0.8230111 0.09498006 0.5600281 -0.8154346 0.07978564 0.5733243 -0.8222675 0.05590248 0.5663489 -0.8161054 0.04717713 0.5759742 -0.8202718 0.01876455 0.5716663 -0.8154654 0.01468002 0.5786197 -0.9248896 0.3101083 0.2200278 -0.9394271 0.2749618 0.2046289 -0.9394629 0.2317101 0.2524282 -0.9583817 0.1648486 0.2330871 -0.9536914 0.1388165 0.2668383 -0.9653745 0.05733948 0.2544883 -0.9593885 0.04454326 0.2785493 -0.6951002 0.1886783 0.6937119 -0.794663 0.1038521 0.5981015 -0.7635127 0.1363517 0.6312342 -0.6924451 0.2634654 0.6716442 -0.6065222 0.091219 0.7898165 -0.6724044 0.3386763 0.6581571 -0.6693996 0.3249883 0.6680471 -0.7053613 0.3247272 0.6300934 -0.6972739 0.3285402 0.6370798 -0.6644297 0.07239395 0.7438362 -0.7066225 0.09166514 0.7016283 -0.9703297 0.2073254 -0.1244052 -0.8649237 0.3761688 0.332271 -0.8680693 0.4692397 -0.1620798 -0.924676 0.3200277 0.2062927 -0.9268655 0.3749601 -0.01804161 -0.8745577 0.4678593 -0.1275016 -0.9124051 0.3792908 0.1538034 -0.9078317 0.4051738 0.1080549 -0.8876683 0.4064356 0.2164605 -0.8699445 0.3937976 0.2968503 -0.7573525 0.07392096 0.6488088 -0.8150995 0.329472 0.4765094 -0.7380253 0.3982765 0.5446968 -0.8020151 0.103723 0.5882291 -0.9341938 0.02239376 0.3560626 -0.8786344 0.1380816 0.4570944 -0.9897021 0.07021898 0.1247355 -0.9760714 0.1201468 0.181244 -0.9923587 0.09280598 -0.08131074 -0.9916346 0.06399363 -0.112097 -0.8578903 0.4698483 -0.2080069 -0.8020782 0.3881187 -0.4539101 -0.9030525 0.3528736 -0.2449011 -0.9431691 0.2085005 -0.2587659 -0.8987315 0.09254133 -0.4286232 -0.963133 0.06435084 -0.2612163 -0.9448782 0.1224625 0.3036581 -0.8771311 0.3603057 0.3175233 -0.9568311 0.004705369 0.2906066 -0.941755 0.1175854 0.3150736 -0.9440956 0.1270294 0.3042158 -0.8774634 0.3601772 0.3167498 -0.8773194 0.3598294 0.3175429 -0.9779682 0.08371931 -0.1912311 -0.9968695 0.02426087 -0.07525122 -0.996012 0.02828407 -0.08461737 -0.9929127 0.07063227 -0.09557962 -0.9933892 0.07006853 -0.09093123 -0.9868823 0.1129116 -0.1153879 -0.9884803 0.1151328 -0.09824115 -0.9730062 0.1731391 -0.1525837 -0.9690285 0.243643 -0.04027408 -0.9617913 0.2649184 -0.06910675 -0.9368665 0.3482955 -0.03116899 -0.9383504 0.339348 -0.06588941 -0.9418852 0.328621 -0.06971764 -0.9460658 0.3194825 -0.05376297 -0.9731402 0.1156482 -0.1990572 -0.9733477 0.1118324 -0.2002192 -0.974936 0.1084519 -0.1942625 -0.9747151 0.09259974 -0.2033613 -0.9647221 0.03237456 -0.2612723 -0.9618584 0.09386163 -0.2569406 -0.95708 0.1329038 -0.2575548 -0.9388284 0.2317745 -0.2547196 -0.8851239 0.398878 -0.2396918 -0.880392 0.4125648 -0.2338814 -0.8896304 0.3888157 -0.2395417 -0.8965738 0.3732526 -0.2384074 -0.909954 0.3482742 -0.225142 -0.884185 0.402258 -0.2374987 -0.8845013 0.45444 -0.1055544 -0.8839061 0.4096128 -0.2256711 -0.8739387 0.4810365 -0.06953436 -0.8852042 0.4617601 -0.0564906 -0.8863343 0.457333 -0.07251328 -0.8979634 0.4368008 -0.05354458 -0.904448 0.4187862 -0.08119171 -0.9138799 0.4017808 -0.05827325 -0.9188253 0.38672 -0.07878881 -0.9262616 0.3726577 -0.05626559 -0.9346947 0.3465338 -0.07912182 -0.8822558 0.4249427 -0.2026045 -0.9092175 0.3792505 -0.1717342 -0.9073511 0.3661145 -0.206577 -0.9318317 0.3225168 -0.1663514 -0.9349271 0.2748681 -0.2244079 -0.9542521 0.2403517 -0.1778602 -0.9543437 0.2028474 -0.219274 -0.9680722 0.1768977 -0.1776045 -0.9683769 0.1248539 -0.2160037 -0.9858421 -0.1675142 -0.007380247 -0.9860355 -0.1661378 0.01149612 -0.9876389 -0.1544028 0.02700632 -0.9849865 -0.1715804 0.01902419 -0.9801201 -0.1977939 0.0155574 -0.9969524 -0.0499351 0.05993676 -0.9964646 -0.0593093 0.0595054 -0.9960349 -0.06540411 0.06030756 -0.9960949 -0.0649411 0.05981338 -0.9953417 -0.07515853 0.06038373 -0.9952691 -0.07576006 0.06082636 -0.9951996 -0.07670414 0.06078106 -0.9944419 -0.08093512 0.0673415 -0.994316 -0.08259105 0.06719112 -0.994049 -0.08211129 0.07158583 -0.9977808 -0.02596974 0.06131076 -0.9976683 -0.03841978 0.05640882 -0.9975079 -0.04045176 0.05780899 -0.9971264 -0.04667472 0.05967074 -0.996724 -0.05093705 0.06282317 -0.9981863 -0.008171737 0.05964356 -0.9983066 -0.01635217 0.05582582 -0.9978761 -0.0251888 0.06007486 -0.9981828 0.01575797 0.05816298 -0.9982765 0.01405262 0.05697834 -0.9983574 0.005298018 0.05704736 -0.9981572 0.00864309 0.06006252 -0.9981574 -0.008630216 0.06006205 -0.9969354 0.06109565 0.04885959 -0.9957258 0.05302524 0.07562196 -0.996771 0.04971635 0.06305336 -0.997627 0.03999859 0.0560401 -0.997403 0.04194033 0.05855208 -0.9978986 0.02901774 0.05793422 -0.9977435 0.02999186 0.06007063 -0.9981459 0.0215981 0.05690753 -0.9847258 0.1738626 0.009317934 -0.9961074 0.06701642 0.05726188 -0.9951612 0.07476615 0.06375151 -0.9927758 0.1151667 0.03366017 -0.9859056 0.1671113 0.007996976 -0.9880357 0.1374881 0.06987577 -0.9736457 0.2247223 0.03890967 -0.9840205 0.1773998 0.01526767 -0.9865031 0.1607019 0.03141283 -0.977721 0.2094727 0.01352775 -0.9760392 0.215566 0.02964586 -0.9743389 0.2234177 0.0273537 -0.9699023 0.2418951 0.02786499 -0.9529702 0.3029282 0.009075284 -0.9940315 0.04588305 0.09897607 -0.9934037 0.08565223 0.07624173 -0.9928453 0.08737105 0.08139169 -0.992728 0.09090042 0.07891923 -0.995211 0.076743 0.06054526 -0.9944992 0.08055824 0.0669471 -0.9938347 0.08589583 0.0701034 -0.9938699 0.08357203 0.0723766 -0.9933053 0.08576452 0.07738894 -0.995649 -0.09318327 -1.34359e-4 -0.9957557 -0.09203559 -1.19682e-4 -2.53789e-6 0 1 0 -0.09446334 -0.9955284 0 -0.09446442 -0.9955283 0 0.09471207 -0.9955048 0 0.09470927 -0.995505 0 0.2396654 0.9708555 0 0.2396656 0.9708555 0 0.6638678 0.74785 0 0.6638697 0.7478483 0 0.9393307 0.3430131 0 0.9393306 0.3430132 0 0.9956658 -0.09300428 0 0.9956658 -0.09300369 0 0.8696046 -0.4937489 0 0.8696049 -0.4937483 0 0.6804974 -0.7327505 0 0.6805054 -0.7327431 0 0.4173951 -0.9087252 0 0.4173959 -0.9087247 0 0.0919947 -0.9957595 0 0.09199392 -0.9957596 0 -0.2396697 -0.9708545 0 -0.2396703 -0.9708544 0 -0.6638718 -0.7478465 0 -0.6638678 -0.74785 0 -0.8877367 -0.4603517 1.05772e-5 -0.8877567 -0.4603131 -1.17771e-5 -0.9751905 -0.2213675 0 -0.9751989 -0.2213302 0 -0.9956657 0.09300482 0 -0.9956662 0.0929988 0 -0.8696043 0.4937493 0 -0.8696033 0.493751 0 -0.6805033 0.7327451 0 -0.6804961 0.7327517 0 -0.4173971 0.9087242 0 -0.4173951 0.9087252 0 -0.0919823 0.9957606 0 -0.0919823 0.9957607 -0.9517651 0.3044024 0.03850263 -0.9504616 0.3094607 -0.02927458 -0.950781 0.3069931 -0.04208052 -0.949059 0.3125095 -0.04031157 -0.9466015 0.3217094 -0.02117919 -0.9506474 0.3071215 -0.04411286 -0.9509623 0.3057632 -0.04668688 -0.9332778 0.3591546 -8.54877e-4 -0.9339932 0.3572905 6.16366e-4 -0.9341479 0.3568854 -7.40875e-4 -0.9382714 0.3458997 5.91428e-4 -0.9444077 0.3287209 0.006066858 -0.9498161 0.3121333 0.02055209 -0.9529253 0.3014801 0.03229576 -0.952302 0.3047134 0.01645463 -0.9525048 0.3039926 0.01797896 -0.9510954 0.3088493 -0.005464553 0 -0.2419432 -0.9702905 0 -0.2419432 -0.9702905 0 -0.6079278 -0.7939924 -0.02989351 -0.6625133 -0.7484534 0 -0.7770803 -0.6294016 0 -0.9309081 -0.3652537 0 -0.9309065 -0.3652575 0 -0.9974081 -0.07195287 0 -0.9974081 -0.07195198 0 0.9714444 -0.2372677 0 0.9714437 -0.2372701 0 0.7485084 -0.6631254 0 0.3542217 -0.9351615 0 0.3542222 -0.9351614 0 0.06091654 -0.998143 0 0.06091713 -0.9981429 0 0.2419428 0.9702906 0 0.2419432 0.9702904 0 0.6660092 0.7459436 0 0.6660124 0.7459408 0 0.930907 0.3652565 0 0.9309064 0.3652581 0 0.9974082 0.07195037 0 0.9974084 0.07194864 0 -0.9714438 0.2372699 -0.06928241 -0.8114771 0.580263 0 -0.7485083 0.6631255 0 -0.971444 0.2372692 0 -0.6532236 0.7571651 0 -0.3542221 0.9351614 0 -0.3542205 0.935162 0 -0.06091648 0.998143 0 -0.06091696 0.9981429 -0.9878833 0.1546386 0.01317399 -0.9867008 0.1596275 0.03066956 -0.987551 0.1565899 0.01492178 -0.9865626 0.1602699 0.03174787 -0.9520223 0.2688167 0.1462574 -0.993519 0.1136624 0.001074433 -0.989715 0.1430342 0.002377569 -0.9929047 0.1189026 -0.001559615 -0.9931888 0.1164219 0.004683852 -0.9882878 0.1495219 -0.03050541 -0.988234 0.1521968 -0.01515614 -0.988379 0.1486001 -0.03201842 -0.9881899 0.03234851 -0.149781 -0.9807608 0.1952106 -0.001117587 -0.9861597 0.1657798 -0.002492249 -0.9817917 0.1899539 0.001642048 -0.981288 0.1924865 -0.00478655 -0.9879692 0.1546515 0 -0.9879692 0.1546513 0 -0.987886 0.1546385 -0.01297181 0 -0.2419432 -0.9702905 0 -0.2419432 -0.9702904 0 -0.666014 -0.7459393 0 -0.6660124 -0.7459408 0 -0.9309065 -0.3652576 0 -0.9309068 -0.3652569 0 -0.9974083 -0.07195055 0 -0.9974084 -0.07194828 0 0.971444 -0.2372692 0 0.9714444 -0.2372675 0 0.748506 -0.663128 0 0.7485074 -0.6631265 0 0.3542247 -0.9351604 0 0.3542268 -0.9351595 0 0.06091678 -0.9981429 0 0.06091684 -0.9981428 0 0.2419432 0.9702905 0 0.2419432 0.9702904 0 0.6660108 0.7459422 0 0.6660124 0.7459408 0 0.9309065 0.3652576 0 0.9309068 0.3652569 0 0.9974083 0.07195055 0 0.9974084 0.07194828 0 -0.9714438 0.2372703 0 -0.9714441 0.2372686 0 -0.7485084 0.6631253 0 -0.7485098 0.6631238 0 -0.3542205 0.935162 0 -0.3542226 0.9351611 0 -0.06091678 0.9981429 0 -0.06091684 0.9981428 -0.9999186 0 -0.01275712 -0.9993998 0.003356635 -0.03447872 -0.9997975 0.01464831 -0.01380687 -0.9995282 -0.001223623 -0.03068864 -0.9997435 0.02252739 -0.002395391 -0.9994986 -0.005836606 -0.03111928 -0.9995413 -0.005055725 -0.02986115 -0.9993999 -0.003368377 0.03447955 -0.9997975 -0.01464855 0.01380711 -0.9995284 0.001223504 0.03068602 -0.9997434 -0.02252835 0.00239551 -0.9994987 0.005836546 0.03111886 -0.9995414 0.005055785 0.02986145 -0.9999187 0 0.01275712 0 -0.2419428 -0.9702906 0 -0.2419432 -0.9702904 0 -0.6660092 -0.7459436 0 -0.6660124 -0.7459408 0 -0.9309077 -0.3652547 0 -0.930907 -0.3652563 0 -0.9974082 -0.07195091 0 -0.9974083 -0.07194954 0 0.9714438 -0.2372699 -0.06927782 0.8114756 -0.5802655 0 0.7485083 -0.6631255 0 0.971444 -0.2372692 0 0.6532269 -0.7571622 0 0.3542221 -0.9351614 0 0.3542205 -0.935162 0 0.06091648 -0.998143 0 0.06091696 -0.9981429 0 0.2419432 0.9702905 0 0.2419432 0.9702905 0 0.6079278 0.7939924 -0.02989137 0.6625134 0.7484535 0 0.7770803 0.6294016 0 0.9309078 0.3652546 0 0.9309059 0.3652592 0 0.9974081 0.07195198 0 0.9974082 0.07195115 0 -0.9714444 0.2372677 0 -0.9714437 0.2372701 0 -0.7485084 0.6631254 0 -0.3542217 0.9351615 0 -0.3542222 0.9351614 0 -0.06091654 0.998143 0 -0.06091713 0.9981429 -0.9878833 -0.1546386 -0.01317399 -0.9867008 -0.1596275 -0.03066956 -0.9875515 -0.1565872 -0.01492154 -0.9865626 -0.1602699 -0.03174787 -0.9520256 -0.2688077 -0.1462524 -0.9935204 -0.1136497 -0.001074492 -0.9897147 -0.1430355 -0.002377629 -0.9929047 -0.1189026 0.001559615 -0.9931889 -0.1164215 -0.004683852 -0.9882878 -0.1495219 0.03050541 -0.9882344 -0.1521941 0.01515585 -0.988379 -0.1486001 0.03201842 -0.9881891 -0.03234964 0.1497862 -0.9807558 -0.1952355 0.001117587 -0.9861597 -0.1657798 0.002492249 -0.981792 -0.1899524 -0.001642048 -0.9812892 -0.1924805 0.00478655 -0.9879692 -0.1546513 0 -0.9879692 -0.1546515 0 -0.9878861 -0.1546381 0.01297181 0 -0.2419422 -0.9702908 0 -0.2419444 -0.9702901 0 -0.666013 -0.7459402 0 -0.666012 -0.7459411 0 -0.9309068 -0.3652567 0 -0.9309085 -0.3652528 0 -0.997408 -0.07195323 0 -0.9974082 -0.07195228 0 0.971444 -0.2372692 0 0.9714438 -0.2372701 0 0.7485084 -0.6631253 0 0.7485091 -0.6631246 0 0.3542224 -0.9351613 0 0.3542219 -0.9351615 0 0.06093585 -0.9981417 0 0.06093555 -0.9981417 0 0.2419433 0.9702904 0 0.2419428 0.9702906 0 0.6660116 0.7459414 0 0.666012 0.7459411 0 0.9309068 0.3652569 0 0.9309061 0.3652588 0 0.9974087 0.07194471 0 0.9974084 0.0719484 0 -0.9714443 0.2372683 0 -0.9714437 0.2372706 0 -0.7485077 0.6631262 0 -0.7485079 0.663126 0 -0.3542233 0.9351609 0 -0.354222 0.9351614 0 -0.06091678 0.9981428 0 -0.06091701 0.9981428 -0.9508539 -0.3093074 -0.01434791 -0.9487724 -0.3142114 -0.03320032 -0.950289 -0.3109608 -0.0159524 -0.9485758 -0.3147083 -0.03410047 -0.8948192 -0.4185138 -0.1553865 -0.9633821 -0.2681301 -0.001154303 -0.954742 -0.2974252 -0.002491891 -0.9619207 -0.2733237 0.001641511 -0.9626103 -0.2708446 -0.004987359 -0.9520705 -0.304112 0.03282886 -0.9523478 -0.3030318 0.03472012 -0.9696052 -0.1820907 0.1634282 -0.9517012 -0.3065819 0.01650106 -0.9473534 -0.320178 0.002772688 -0.9388225 -0.344397 -0.00181812 -0.9379913 -0.3466312 0.004359662 -0.9340111 -0.3572439 5.95242e-4 -0.950952 -0.3093386 0 -0.950951 -0.3093413 0 -0.95086 -0.30931 0.01388198 -0.1335391 -0.8157719 0.5627464 -0.1200522 -0.8195676 0.5602648 -0.369751 -0.9067608 0.2026556 -0.3448712 -0.9172899 0.1991056 -0.3915711 -0.6848796 0.6145015 -0.5303818 -0.7210922 0.4457817 -0.4877804 -0.7341691 0.4722987 -0.4681341 -0.8329975 0.2948998 -0.4791276 -0.8383847 0.2599001 -0.4843785 -0.8473942 0.2174874 -0.5013672 -0.8505138 0.1589258 -0.5548353 -0.8297348 0.0608136 -0.4869621 -0.8733927 -0.007286548 -0.4923255 -0.8557715 -0.1589677 -0.4959098 -0.8507503 -0.1740621 -0.4854797 -0.8496754 -0.2058187 -0.37509 -0.6561369 0.6548219 -0.4628214 -0.8647462 0.1949629 -0.3658441 -0.7733761 0.5177331 -0.4940934 -0.8693656 0.008680939 -0.4552541 -0.8658698 0.2073965 -0.3934304 -0.9003623 0.1859042 -0.3916815 -0.8949133 0.2138126 -0.308937 -0.7593215 0.572703 -0.2159355 -0.812539 0.5414355 -0.1572021 -0.8031915 0.574605 -0.4829763 -0.8451912 -0.2288792 -0.3917821 -0.9044549 0.1687251 -0.428064 -0.8395156 0.3346266 -0.3666668 -0.8917862 0.2650905 -0.004741728 -0.9569926 0.2900737 -0.004748225 -0.957306 0.2890378 -0.09073036 -0.9604577 0.2632281 -0.1148036 -0.9702574 0.2131217 -0.3732957 -0.9141504 0.1580489 -0.2479822 -0.9368086 0.2467682 -0.2502361 -0.9301873 0.268577 -0.0982691 -0.9363462 0.3370445 -0.1290724 -0.9483924 0.2896414 -0.004845976 -0.9569929 0.2900709 -0.4393041 -0.8725008 0.2139024 -0.35773 -0.926979 0.1128676 -0.2260396 -0.9607066 0.1610865 -0.1352514 -0.924173 0.3572275 -0.1314294 -0.9560149 0.2622248 -0.007759153 -0.9639093 0.2661179 -0.3780418 -0.9237717 0.06107652 -0.3499314 -0.9360976 0.03562623 -0.2374393 -0.9529656 0.1883589 -0.08798718 -0.9894905 0.1147478 -0.08552825 -0.967388 0.2384228 -0.00203824 -0.9636537 0.2671468 -0.007334887 -0.9597126 0.2808877 -0.1025437 -0.9870361 0.1234689 -0.3596771 -0.9166847 0.1741312 -0.3528952 -0.9244672 0.1443104 -0.3109382 -0.9469056 0.08177632 -0.1947205 -0.9769669 0.08729147 -0.0587179 -0.9832629 0.1724716 -0.366426 -0.9279419 0.06823384 -0.3381921 -0.9392817 0.05810493 -0.1220366 -0.9755487 0.1827892 -0.1114425 -0.9772179 0.1806268 0.01256567 -0.9742254 0.2252268 -0.1206582 -0.8192718 0.5605672 -0.3456158 -0.916929 0.1994769 -0.1081745 -0.8173815 0.5658497 -0.09500366 -0.8229948 0.5600483 -0.07977455 -0.8154481 0.5733066 -0.05591225 -0.8222495 0.5663743 -0.04716569 -0.8161038 0.5759773 -0.01876413 -0.8202723 0.5716654 -0.01468044 -0.815453 0.5786373 -0.3101087 -0.9248908 0.2200222 -0.2749436 -0.9394317 0.2046314 -0.2317196 -0.9394589 0.2524342 -0.1648581 -0.9583798 0.2330883 -0.1388004 -0.9536961 0.2668303 -0.05733895 -0.9653793 0.2544702 -0.04454702 -0.9593876 0.2785519 -0.1886852 -0.6951028 0.6937074 -0.1038269 -0.7946683 0.5980989 -0.1363479 -0.7635092 0.6312392 -0.2634668 -0.6924473 0.6716412 -0.09121924 -0.6065192 0.7898188 -0.3388147 -0.6723292 0.6581627 -0.324985 -0.6693967 0.6680516 -0.324723 -0.7053748 0.6300805 -0.3285492 -0.6972536 0.6370972 -0.07240122 -0.6644074 0.7438554 -0.09166306 -0.7066317 0.7016193 -0.2073464 -0.970326 -0.124399 -0.3761669 -0.8649242 0.3322719 -0.4692899 -0.8680394 -0.1620949 -0.3199985 -0.9246876 0.206286 -0.3749735 -0.9268598 -0.01804983 -0.4678511 -0.8745623 -0.1274999 -0.3792657 -0.9124175 0.1537919 -0.4051741 -0.9078329 0.1080445 -0.4064574 -0.8876501 0.2164942 -0.3938151 -0.8699329 0.296861 -0.07390934 -0.7573713 0.6487883 -0.3294669 -0.8151015 0.4765096 -0.3982772 -0.7380335 0.5446853 -0.1037276 -0.802007 0.5882393 -0.02237838 -0.9341912 0.3560703 -0.1380848 -0.8786395 0.4570835 -0.07021564 -0.9897031 0.1247307 -0.1201506 -0.9760686 0.1812568 -0.09280246 -0.9923584 -0.08131796 -0.06399345 -0.9916356 -0.112089 -0.4698336 -0.8579006 -0.2079977 -0.3880971 -0.8020833 -0.4539197 -0.3528698 -0.903061 -0.2448752 -0.2085181 -0.9431672 -0.2587587 -0.09254634 -0.8987259 -0.4286339 -0.06435233 -0.9631395 -0.2611918 -0.1224651 -0.9448786 0.3036555 -0.3603001 -0.8771286 0.3175362 -0.00470525 -0.9568381 0.2905835 -0.1175913 -0.9417518 0.3150807 -0.127025 -0.9440984 0.3042088 -0.3601714 -0.8774656 0.3167502 -0.3598425 -0.8773167 0.3175354 -0.08370447 -0.9779698 -0.1912292 -0.0242545 -0.9968696 -0.07525146 -0.02828818 -0.9960128 -0.08460664 -0.07062256 -0.9929134 -0.0955795 -0.07006496 -0.9933906 -0.09091824 -0.1129184 -0.9868831 -0.1153747 -0.1151235 -0.988481 -0.09824436 -0.1731204 -0.9730084 -0.1525909 -0.2436742 -0.9690206 -0.04027628 -0.2751333 -0.957807 -0.08311182 -0.3393372 -0.9383541 -0.06589269 -0.3286302 -0.9418818 -0.06972008 -0.3176598 -0.9468554 -0.05057007 -0.1156363 -0.9731422 -0.1990545 -0.1118592 -0.9733447 -0.2002193 -0.1084525 -0.9749363 -0.1942609 -0.09258371 -0.974716 -0.2033645 -0.03237468 -0.9647217 -0.261274 -0.09385919 -0.9618586 -0.2569408 -0.1329034 -0.9570806 -0.2575531 -0.2317687 -0.9388298 -0.2547193 -0.3988804 -0.8851229 -0.2396916 -0.4125635 -0.8803923 -0.2338821 -0.3888183 -0.8896297 -0.2395402 -0.3732446 -0.8965765 -0.2384097 -0.3482758 -0.9099556 -0.2251331 -0.40227 -0.8841788 -0.2375015 -0.454419 -0.8845123 -0.1055533 -0.4097611 -0.8838574 -0.2255927 -0.4810618 -0.8739241 -0.06954413 -0.4617638 -0.8852016 -0.05650132 -0.4573421 -0.8863299 -0.07250851 -0.4367892 -0.8979682 -0.05355745 -0.4187754 -0.9044548 -0.08117109 -0.4018269 -0.9138593 -0.05828082 -0.3867048 -0.9188326 -0.07878029 -0.3726805 -0.9262528 -0.05625939 -0.3465377 -0.934693 -0.07912319 -0.4249389 -0.882261 -0.2025895 -0.3792548 -0.9092103 -0.1717625 -0.3661429 -0.9073411 -0.2065713 -0.3225209 -0.9318285 -0.166361 -0.2748581 -0.9349319 -0.2244002 -0.240309 -0.9542651 -0.1778478 -0.2028653 -0.9543389 -0.2192785 -0.1768761 -0.9680764 -0.1776034 -0.1248699 -0.9683737 -0.2160095 0 -0.9570302 0.2899883 0 -0.957032 0.2899826 0 -0.95703 0.2899892 0 -0.9570307 0.2899867 0 -0.9570292 0.2899919 0 -0.9570319 0.2899831 0 -0.9570293 0.2899914 2.06056e-7 -0.9570315 0.2899842 0 -0.9591582 0.2828707 0 -0.9890106 0.1478453 3.37975e-5 -0.9889416 0.1483055 -4.33794e-5 -0.9751136 0.2217057 2.19064e-4 -0.9632103 0.268749 0.001663386 -0.9751018 0.2217515 -0.005914092 -0.9586699 0.2844592 -0.004392981 -0.9628177 0.2701163 0 -0.8155377 0.5787039 0 -0.8155446 0.5786942 0 -0.9603472 0.2788071 0 -0.9603371 0.2788417 -2.16628e-5 -0.7078146 0.7063984 -2.73394e-6 -0.7078173 0.7063956 -7.25889e-5 -0.7078625 0.7063503 0 -0.7078297 0.7063832 0 -0.707827 0.7063859 -7.86841e-6 -0.7078264 0.7063865 6.25265e-6 -0.7078223 0.7063905 7.86841e-6 -0.7078264 0.7063865 -7.81581e-6 -0.7078215 0.7063914 4.83926e-5 -0.7078625 0.7063503 2.73394e-6 -0.7078173 0.7063956 2.16628e-5 -0.7078149 0.706398 0 -0.7558314 0.6547662 1.35796e-4 -0.7627139 0.6467362 -2.65023e-4 -0.8794671 0.4759596 7.01787e-5 -0.8857824 0.4641008 -7.7573e-5 -0.9803047 0.1974911 4.23747e-4 -0.9837967 0.1792875 -4.08666e-4 -0.9941809 -0.1077232 0 -0.992371 -0.1232877 -1.07366e-5 -0.9652304 -0.2614007 6.40499e-4 -0.9653664 -0.2608973 -4.92508e-6 -0.9652279 -0.2614099 0 -0.9652279 -0.2614101 -8.84773e-6 -0.9652274 -0.2614119 0 -0.9652327 -0.2613923 0 -0.9652334 -0.2613898 0 -0.9652289 -0.2614061 0 -0.9652322 -0.261394 9.56816e-7 -0.9652326 -0.2613924 -4.79184e-4 -0.9653474 -0.2609677 -4.11517e-6 -0.9652301 -0.2614017 7.45073e-6 -0.9652272 -0.2614126 4.92508e-6 -0.965228 -0.2614098 0 -0.9971628 -0.07527673 0 -0.997164 -0.07526016 0 -0.9935327 0.1135461 -6.0155e-6 -0.9935352 0.1135244 0 -0.993533 0.1135448 0 -0.9935332 0.113542 0 -0.9935325 0.1135488 -3.66128e-7 -0.993533 0.113544 -5.14085e-7 -0.9935317 0.1135559 0 -0.9935328 0.1135461 2.28832e-7 -0.9935325 0.113548 -3.00869e-7 -0.9935312 0.1135598 -1.79979e-7 -0.993533 0.1135448 -3.3734e-7 -0.9935331 0.1135433 0 -0.9935353 0.1135237 0 -0.9935324 0.1135491 1.31607e-7 -0.9935321 0.1135519 1.70155e-6 -0.9935318 0.1135544 -4.77996e-6 -0.9935342 0.1135336 2.67543e-6 -0.9935314 0.1135581 0 -0.9935338 0.1135373 7.31165e-7 -0.9935353 0.1135236 8.81391e-7 -0.9935362 0.1135161 6.2859e-7 -0.9935329 0.1135448 -0.1371202 -0.9881505 0.06896883 -0.2240131 -0.9738449 0.03800523 -0.1977401 -0.9799071 0.02609914 -0.1964428 -0.9801336 0.0273562 -0.2218007 -0.9748272 0.02272826 -0.2328853 -0.9721552 0.02605301 -0.235734 -0.9714803 0.02560663 -0.242407 -0.9697791 0.02770406 -0.3029322 -0.952969 0.009080171 -0.08207184 -0.9935194 0.07863444 -0.0853337 -0.993438 0.07615303 -0.08740621 -0.9928299 0.08154165 -0.08740276 -0.99283 0.08154374 -0.08622759 -0.9932038 0.07817316 -0.04585331 -0.9940599 0.09870332 0.3490538 -0.9171992 0.1921124 0.3658224 -0.9067682 0.2096318 0.1227381 -0.8212444 0.5572191 0.1310226 -0.814086 0.5657714 0.4854805 -0.8496748 -0.205819 0.4959098 -0.8507503 -0.1740621 0.4624466 -0.8853443 -0.04804652 0.5607891 -0.825724 0.06079113 0.4892949 -0.8558533 0.1676474 0.4792039 -0.8383305 0.2599342 0.4714445 -0.8346603 0.2847496 0.4760718 -0.7568182 0.4478638 0.5120953 -0.7180905 0.4712796 0.3915711 -0.6848796 0.6145015 0.375096 -0.6561353 0.6548203 0.4940934 -0.8693656 0.008680939 0.3390396 -0.7868841 0.5156216 0.3287898 -0.7464017 0.5786033 0.3825755 -0.8999319 0.2091861 0.1787809 -0.7910696 0.5850182 0.1909312 -0.8248965 0.532063 0.4039672 -0.894915 0.1895729 0.4588771 -0.8636529 0.2086519 0.4583284 -0.8671769 0.1947804 0.4829764 -0.8451912 -0.2288794 0.004743158 -0.9569916 0.2900768 0.3867194 -0.9102578 0.1479147 0.3778499 -0.9098018 0.1717268 0.2479822 -0.9368086 0.2467682 0.08451586 -0.975115 0.2049584 0.1277756 -0.959414 0.2513924 0.4134839 -0.8718823 0.2623972 0.3608018 -0.8794102 0.3105798 0.2502361 -0.9301873 0.268577 0.1238614 -0.9371308 0.3262581 0.09352934 -0.9523779 0.2902216 0.004844546 -0.9569939 0.2900679 0.004748225 -0.957306 0.2890378 0.1519721 -0.9339832 0.3233882 0.3601621 -0.9326583 0.02078455 0.3650524 -0.9286805 0.06549394 0.09776824 -0.9585208 0.2677296 0.007334887 -0.9597126 0.2808877 0.002293348 -0.9634432 0.2679034 0.007434368 -0.9641201 0.2653625 0.1398696 -0.9657459 0.2185667 0.01982712 -0.996557 0.08050602 0.2374398 -0.9529655 0.1883592 0.226039 -0.9607061 0.1610901 0.4393075 -0.8724994 0.2139014 0.3577283 -0.9269796 0.1128696 -0.01232194 -0.9741274 0.2256636 0.3323653 -0.9411313 0.06168609 0.4101837 -0.9081192 0.08407682 0.3664265 -0.9279417 0.06823396 0.1947203 -0.9769669 0.08729034 0.3109378 -0.9469058 0.08177536 0.3528952 -0.9244672 0.1443104 0.1220366 -0.9755487 0.1827892 0.1120851 -0.9771205 0.1807555 0.1055936 -0.9839683 0.1437236 0.06370502 -0.9890237 0.1333191 0.3273142 -0.9255573 0.1902872 0.1147673 -0.8221668 0.5575575 0.3300296 -0.9158549 0.2286712 0.2586218 -0.9455857 0.1974402 0.2511208 -0.9329807 0.257848 0.1512434 -0.9615993 0.2290249 0.1542203 -0.9507168 0.2689867 0.04805374 -0.9662807 0.2529672 0.05457854 -0.9589132 0.2784004 0.1146497 -0.8145364 0.5686705 0.08975565 -0.8251747 0.5577012 0.08610755 -0.8135532 0.5750797 0.05155032 -0.8234265 0.5650767 0.05212986 -0.8153072 0.5766773 0.01580303 -0.8206667 0.5711887 0.01787924 -0.8154109 0.5786066 0.1392751 -0.7655166 0.6281615 0.263009 -0.6920379 0.6722424 0.3297724 -0.6682261 0.6668763 0.3414394 -0.6704286 0.6587447 0.09710294 -0.6287456 0.7715245 0.1919283 -0.7005204 0.6873388 0.001519203 -0.7078147 0.7063965 0.09746474 -0.7063555 0.7011153 0.07205438 -0.6483319 0.7579407 0.3289471 -0.7050448 0.6282561 0.3294321 -0.7040603 0.6291055 0.0742278 -0.8042653 0.5896164 0.347791 -0.9289188 -0.1270879 0.5359092 -0.8387064 0.09681379 0.3290878 -0.8209704 0.466593 0.4111335 -0.7333467 0.5414534 0.3650935 -0.8858134 0.2864288 0.3875241 -0.8605128 0.3306702 0.4129574 -0.8957241 0.164756 0.3623273 -0.9320437 0.00368762 0.462086 -0.8855304 -0.04808932 0.06313472 -0.9898302 -0.1274762 0.117143 -0.7631942 0.6354621 0.06551855 -0.8875113 0.4561043 0.1172281 -0.9277536 0.3543034 0.08191478 -0.9822227 0.1689037 0.1075015 -0.9864881 0.1236319 0.1003746 -0.9914548 -0.08332079 0.2057823 -0.9706888 -0.1241649 0.06338363 -0.9632073 -0.2611789 0.09247839 -0.8969241 -0.4324059 0.2073257 -0.9433416 -0.2590806 0.3495092 -0.9041956 -0.245507 0.3876237 -0.7997292 -0.4584552 0.4681102 -0.8587863 -0.2082283 0.1219934 -0.9449549 0.3036081 0.004678785 -0.9568361 0.2905906 0.3598425 -0.8773167 0.3175354 0.1171231 -0.9418388 0.3149949 0.1271232 -0.9443084 0.303515 0.2430689 -0.9182602 0.3125953 0.3601714 -0.8774656 0.3167502 0.3603001 -0.8771286 0.3175362 0.08371353 -0.9779689 -0.1912297 0.02921217 -0.9967387 -0.07522511 0.02323579 -0.9962533 -0.0833044 0.0683214 -0.9931313 -0.09498745 0.07207518 -0.9931408 -0.09206962 0.1048052 -0.9883052 -0.1107649 0.1213726 -0.9871351 -0.1040819 0.1409388 -0.9824204 -0.1224197 0.2873267 -0.9526035 -0.09995114 0.1122755 -0.973146 -0.2009508 0.1152452 -0.9733341 -0.1983413 0.273644 -0.9584073 -0.08108359 0.338169 -0.938921 -0.06378889 0.3298709 -0.9412859 -0.07187664 0.3187263 -0.946394 -0.05246013 0.1080951 -0.9751006 -0.1936341 0.09310662 -0.9745298 -0.2040175 0.09386014 -0.9609667 -0.2602562 0.04431635 -0.9657672 -0.2555974 0.1329028 -0.9570807 -0.2575528 0.2317705 -0.9388294 -0.254719 0.40227 -0.8841788 -0.2375015 0.3482764 -0.9099544 -0.2251369 0.3734635 -0.8964545 -0.2385255 0.3869854 -0.8903686 -0.2397628 0.4120756 -0.8805657 -0.2340888 0.3988804 -0.8851229 -0.2396916 0.4171475 -0.8803255 -0.225865 0.4647377 -0.8789242 -0.1072902 0.4242546 -0.8826933 -0.2021399 0.3912432 -0.9025567 -0.179778 0.3570264 -0.9128345 -0.1981554 0.3363333 -0.9245637 -0.1790586 0.2662479 -0.9401361 -0.2127352 0.2507392 -0.9488556 -0.1918411 0.1948766 -0.9588536 -0.2064537 0.1823498 -0.9654106 -0.1863623 0.1204907 -0.9706858 -0.2079693 0.4666617 -0.8824139 -0.05977213 0.4667076 -0.8823867 -0.05981445 0.4534814 -0.8885949 -0.06894713 0.4425847 -0.8947928 -0.05886262 0.4150732 -0.9065968 -0.07613378 0.406476 -0.911381 -0.06451416 0.3831236 -0.9208095 -0.07298254 0.3756889 -0.9247347 -0.06102329 0.3441367 -0.935942 -0.07471728 -0.1667418 -0.985996 0.003034114 0.231156 -0.9725223 0.02770406 0.1374903 -0.9880353 0.0698772 0.2600343 -0.9651907 0.02809405 0.2888653 -0.9573658 -0.002773523 0.2247216 -0.9736459 0.03890979 0.2083775 -0.9779502 0.01386874 0.1606504 -0.9865109 0.03143095 0.1774246 -0.9840173 0.01517933 0.07742959 -0.9950876 0.06168848 0.1128686 -0.9929912 0.03506392 0.1716763 -0.9851377 0.005588889 0.07361733 -0.995312 0.06272572 0.06661576 -0.9961144 0.05760771 0.06657832 -0.996119 0.05757004 0.04871904 -0.9968839 0.06204026 0.02901083 -0.9978981 0.05794763 0.04194408 -0.9974036 0.05853968 0.04000449 -0.9976271 0.05603486 0.04829055 -0.9969053 0.06203228 0.04996114 -0.9966284 0.06508278 0.01570612 -0.9981756 0.05830019 0.02071732 -0.9981837 0.05656903 0.02998685 -0.9977438 0.06006866 -0.02509939 -0.9978808 0.06003409 -0.01636534 -0.9983066 0.05582165 -0.008170187 -0.9981861 0.05964666 -0.008632957 -0.998157 0.06006908 0.005028545 -0.998182 0.0600627 0.008646428 -0.9983362 0.05701136 0.0130282 -0.9982906 0.05697661 -0.03182548 -0.9970204 0.07026773 -0.03093856 -0.9982051 0.0512799 -0.04573005 -0.9970643 0.06141263 -0.04183018 -0.9975592 0.05591022 -0.0495491 -0.9968562 0.06182867 -0.04895204 -0.9969362 0.06100869 -0.06333714 -0.9963105 0.05791211 -0.1651667 -0.9859864 0.02346813 -0.1765228 -0.9841904 0.01446384 -0.1977795 -0.9800943 0.01727676 -0.07294344 -0.9949654 0.06872457 -0.08055555 -0.9956514 0.04679012 -0.08050644 -0.9957023 0.0457769 -0.07643544 -0.9952462 0.06035506 -0.08129578 -0.9943734 0.06791603 -0.08268892 -0.9943661 0.06632143 -0.08211791 -0.9940464 0.07161277 0.2148543 -0.976293 0.02626019 0.2092369 -0.9773348 0.03219908 0.08704942 -0.9929537 0.08040684 0.08565378 -0.9934033 0.07624495 0.04587781 -0.9940322 0.0989719 0.09261965 -0.9925282 0.0794332 0.08576852 -0.9933055 0.07738161 0.08318567 -0.9939662 0.0714941 0.08691835 -0.9937028 0.07070958 0.08056956 -0.9944984 0.06694298 -0.09194487 -0.9957638 -8.48445e-4 -0.09277933 -0.9956849 -0.001917898 2.80665e-4 0 1 -1.66629e-4 0 1 -1.20585e-5 0 1 0.09466457 0 -0.9955093 0.09483629 0 -0.9954929 -0.09452426 0 -0.9955226 -0.09432017 0 -0.9955419 -0.9708555 0 0.2396658 -0.9708557 0 0.239665 -0.7478474 0 0.6638706 -0.7478449 0 0.6638734 -0.3590249 0 0.9333281 -0.3590168 0 0.9333311 -0.06422358 0 0.9979355 -0.06424146 0 0.9979344 0.2950118 -0.9554936 -1.50103e-4 0.281578 -0.9594982 -0.008783996 0.2790892 -0.9601963 -0.01150548 0.2799974 -0.9599511 -0.009776115 0.2814611 -0.959565 -0.003849923 0.3135353 -0.9488491 -0.03716385 0.3330509 -0.9429088 2.52834e-4 0.3383769 -0.940957 -0.01006072 0.3369264 -0.9415226 -0.004000246 0.2814661 -0.9595713 0 0.3093109 -0.9508945 -0.01125138 0.3369329 -0.9415287 0 0.2711932 -0.9625107 0.005247831 0.2682564 -0.963347 0.001023232 0.3444024 -0.9388103 0.004717469 0.3092297 -0.9506436 0.02556961 0.3149057 -0.9483734 0.0377134 0.401502 -0.9032219 0.1516131 0.3112903 -0.9501476 0.01782852 0.2760365 -0.9609266 -0.02059453 0.3044024 -0.9517654 0.03849434 -0.2419487 0 -0.9702891 -0.2419428 0 -0.9702905 -0.6660066 0 -0.7459458 -0.6660089 0 -0.7459438 -0.9309082 0 -0.3652535 -0.930907 0 -0.3652564 -0.9974083 0 -0.07195073 -0.9974082 0 -0.0719521 0.9714434 0 -0.2372719 0.9714441 0 -0.2372689 0.7485076 0 -0.6631264 0.3542215 0 -0.9351616 0.3542191 0 -0.9351626 0.06092584 0 -0.9981424 0.06091815 0 -0.9981428 1 3.03435e-7 0 0.2419475 0 0.9702893 0.2419415 0 0.9702909 0.6660103 0 0.7459426 0.6660131 0 0.7459401 0.9309072 0 0.3652558 0.9309061 0 0.3652586 0.9974085 0 0.0719484 0.9974083 0 0.07194942 -0.9714434 0 0.2372714 -0.9714444 0 0.2372676 -0.7485094 0 0.6631242 -0.7485091 0 0.6631246 -0.3542284 0 0.935159 -0.3542147 0 0.9351642 -0.06093484 0 0.9981418 -0.06091815 0 0.9981428 0.1546515 -0.9879691 0 0.1546515 -0.9879692 0 0.1924842 -0.9812884 -0.004790186 0.1952245 -0.980758 -0.001133739 0.1207708 -0.9926699 -0.004582107 0.1546137 -0.9877272 -0.0221278 0.1486028 -0.9883784 -0.03202211 0.03230518 -0.9881947 -0.1497585 0.1522015 -0.9882333 -0.01515793 0.1846254 -0.9826918 0.01518273 0.1576173 -0.9868556 -0.03567761 0.1164088 -0.9931904 0.004685521 0.1136604 -0.9935191 0.001070618 0.1880198 -0.9821538 0.004733979 0.1546124 -0.9877228 0.02233439 0.1602751 -0.9865616 0.03175091 0.2688055 -0.9520275 0.1462436 0.1565869 -0.9875513 0.01493489 0.1242217 -0.9921419 -0.01495736 0.1508938 -0.9879318 0.03495609 -0.2419508 0 -0.9702886 -0.2419421 0 -0.9702907 -0.6660136 0 -0.7459397 -0.6660165 0 -0.7459371 -0.9309055 0 -0.3652602 -0.9309085 0 -0.3652526 -0.9974083 0 -0.0719487 -0.9974083 0 -0.07194989 0.9714441 0 -0.2372689 0.9714447 0 -0.2372663 0.7485057 0 -0.6631284 0.7485072 0 -0.6631267 0.3542307 0 -0.9351581 0.3542291 0 -0.9351587 0.06092977 0 -0.9981421 0.06091052 0 -0.9981433 1 -2.34939e-7 0 0.2419475 0 0.9702894 0.241936 0 0.9702922 0.6660081 0 0.7459446 0.6660133 0 0.7459399 0.9309071 0 0.365256 0.9309064 0 0.365258 0.9974083 0 0.07194942 0.9974083 0 0.0719487 -0.9714437 0 0.2372707 -0.9714444 0 0.2372674 -0.7485072 0 0.6631268 -0.7485096 0 0.663124 -0.3542244 0 0.9351605 -0.3542178 0 0.9351629 -0.06094563 0 0.9981411 -0.06088513 0 0.9981448 -0.02569746 -0.9996249 0.009477257 0.0336377 -0.9994239 0.004528343 0 -0.9997646 0.02170252 0.005833983 -0.9994988 0.03111845 -0.0225268 -0.9997434 0.002406775 0.001227557 -0.9995287 0.03067511 -0.006305336 -0.999723 0.02267789 0.02569878 -0.9996249 -0.009477257 -0.0336374 -0.9994239 -0.004528284 0 -0.9997646 -0.02170252 -0.005834162 -0.9994988 -0.03111833 0.02252775 -0.9997434 -0.002406775 -0.001228928 -0.9995287 -0.03067499 0.006305575 -0.999723 -0.02267783 -1 2.92028e-7 0 -0.2419524 0 -0.9702882 -0.2419356 0 -0.9702924 -0.6660061 0 -0.7459463 -0.6660162 0 -0.7459373 -0.9309075 0 -0.3652553 -0.9309075 0 -0.3652551 -0.9974084 0 -0.07194846 -0.9974081 0 -0.07195168 0.9714438 0 -0.2372698 0.9714438 0 -0.2372698 0.748512 0 -0.6631213 0.7485067 0 -0.6631273 0.3542249 0 -0.9351602 0.3542203 0 -0.9351621 0.06093716 0 -0.9981416 0.2419494 0 0.9702889 0.2419428 0 0.9702905 0.6660071 0 0.7459455 0.6660152 0 0.7459382 0.9309073 0 0.365256 0.9309063 0 0.3652581 0.9974082 0 0.07195073 0.9974082 0 0.07195097 -0.9714436 0 0.2372709 -0.9714443 0 0.2372678 -0.7485063 0 0.6631278 -0.7485099 0 0.6631237 -0.3542258 0 0.93516 -0.3542135 0 0.9351646 -0.06095564 0 0.9981405 -0.06089305 0 0.9981444 -0.1546515 -0.9879691 0 -0.1546515 -0.9879692 0 -0.1924865 -0.981288 0.004790186 -0.1952217 -0.9807585 0.001133739 -0.1207677 -0.9926702 0.004582107 -0.1546131 -0.9877273 0.0221278 -0.148601 -0.9883787 0.03202211 -0.03231394 -0.9881944 0.1497585 -0.1522015 -0.9882333 0.01515793 -0.1846254 -0.9826918 -0.01518273 -0.1576173 -0.9868556 0.03567761 -0.1164075 -0.9931905 -0.004685521 -0.1136634 -0.9935188 -0.001070618 -0.1880177 -0.9821543 -0.004733979 -0.1546124 -0.9877228 -0.02233439 -0.160276 -0.9865615 -0.03175091 -0.2688015 -0.9520287 -0.1462438 -0.1565825 -0.9875521 -0.01493489 -0.1242197 -0.9921421 0.01495736 -0.1508966 -0.9879313 -0.03495609 0.2419487 0 0.970289 0.2419379 0 0.9702918 0.6660107 0 0.7459422 0.6660122 0 0.7459409 0.9309074 0 0.3652556 0.9309062 0 0.3652585 0.9974084 0 0.07194757 0.9974084 0 0.07194769 -0.9714434 0 0.237272 -0.9714442 0 0.2372684 -0.7485068 0 0.6631271 -0.7485093 0 0.6631244 -0.5037653 0 0.8638406 -0.3606562 -0.02463769 0.9323734 -0.2888793 0 0.9573656 -0.06093358 0 0.9981418 -0.06091153 0 0.9981433 -0.3057402 -0.952115 3.43661e-4 -0.3118701 -0.9501247 -3.41796e-4 -0.3015668 -0.9529627 0.03032511 -0.2868456 -0.957944 0.007939636 -0.305122 -0.951583 -0.03728777 -0.2861647 -0.95818 0.001080691 -0.2712762 -0.9624878 -0.005166888 -0.2758461 -0.9612003 -0.00174582 -0.315456 -0.9484012 -0.03198254 -0.3307616 -0.9436768 -0.008425831 -0.3420126 -0.9396937 0.001849234 -0.3465435 -0.9380184 0.005409717 -0.3407086 -0.9401646 0.002863287 -0.3209036 -0.9471118 -5.02029e-4 -0.08709901 0 -0.9961997 -0.2501199 -0.02831637 -0.9678007 -0.3511006 0.01008218 -0.9362835 -0.6681882 -0.01411467 -0.7438585 -0.6662658 -0.01554256 -0.7455524 -0.9300023 0.02003729 -0.3670074 -0.881612 -0.06327861 -0.467714 -0.9965155 0.04095864 -0.07265788 -0.9869314 0 -0.1611409 0.9876234 0 -0.1568439 0.9700645 -0.03530073 -0.2402684 0.9206264 6.76255e-5 -0.3904447 0.8440263 -6.47058e-5 -0.5363019 0.7427291 -0.03282827 -0.6687869 0.6828095 0.004264593 -0.730584 0.3525223 -0.00560218 -0.9357867 0.3721023 -0.01734316 -0.9280298 0.06339704 0.007534921 -0.99796 0.09792488 0 -0.9951938 -0.9913467 0 -0.1312699 -0.9913887 -9.26863e-5 -0.130952 -0.9235972 9.35126e-5 -0.3833646 -0.9237155 0 -0.3830792 -0.707112 0 -0.7071017 -0.7071042 0 -0.7071094 -0.258824 0 -0.9659246 -0.258822 0 -0.9659251 0.2093342 0 -0.9778442 0.2657384 -0.02429682 -0.9637389 0.4552698 0 -0.8903536 0.6081557 0 -0.7938178 0.6081989 1.78322e-5 -0.7937847 0.7928948 -2.35125e-5 -0.6093586 0.7929299 0 -0.609313 0.9238122 0 -0.3828459 0.9237038 -8.66966e-5 -0.3831077 0.9914217 8.69381e-5 -0.1307026 0.9913847 0 -0.1309829 -0.9974085 0 -0.07194727 -0.9876372 -0.0166912 -0.1558666 -0.9286866 0.03315204 -0.3693811 -0.8871396 -0.007051348 -0.4614475 -0.6802715 0.009203672 -0.7329025 -0.6619546 0.01931613 -0.749295 -0.5036439 -1.44546e-5 -0.8639114 -0.3349255 4.94733e-5 -0.9422447 -0.2323907 0.02959233 -0.9721723 -0.09792488 0 -0.9951938 0.06094044 0 -0.9981414 0.08608454 -0.003337085 -0.9962823 0.3572713 0.01156049 -0.9339292 0.3566555 0.01189953 -0.9341602 0.6625845 -0.009088397 -0.7489321 0.7523484 0.03496819 -0.6578367 0.8385095 4.63951e-5 -0.5448871 0.9189153 -4.18677e-5 -0.3944548 0.9713749 0.03474861 -0.2349967 0.9869314 0 -0.1611409 -0.9998567 0 -0.01692968 -0.9913911 0.004461407 -0.1308584 -0.9601643 -0.03455901 -0.2772911 -0.923693 0 -0.3831339 -0.7929226 0 -0.6093225 -0.7928903 1.7635e-5 -0.6093645 -0.6079645 -1.84529e-5 -0.7939643 -0.6081414 -8.43069e-5 -0.7938289 -0.452501 3.7208e-5 -0.8917639 -0.2660276 0.02529394 -0.9636336 -0.2065742 0 -0.9784311 0.2588232 0 -0.9659248 0.2588253 0 -0.9659242 0.7071042 0 -0.7071094 0.7071043 0 -0.7071094 0.9236923 0 -0.3831353 0.9617937 -0.03271615 -0.2718139 0.9913434 0.004314899 -0.1312234 0.9998565 0 -0.01694554 -0.3799708 0.9249985 0 -0.1280377 0.9917693 0 -0.128528 0.991706 2.18788e-4 -0.2555665 0.9667915 0 -0.3799676 0.9249998 0 -0.5715703 0.8205531 0 -0.5721256 0.8201653 0.001157581 -0.7071055 0.7071071 -0.001174271 -0.7071072 0.7071054 -0.001175642 -0.8205522 0.5715706 0.001165688 -0.8201668 0.5721246 0 -0.9249989 0.3799701 0 -0.9249998 0.3799679 0 -0.9917059 0.1285284 0 -0.9917063 0.1285254 0 -0.9249998 -0.3799679 0 -0.9917698 -0.1280343 0 -0.9917059 -0.1285281 2.19134e-4 -0.9667078 -0.2558828 0 -0.9249989 -0.3799701 0 -0.820552 -0.571572 0 -0.8201667 -0.5721238 0.001156687 -0.7071055 -0.7071071 -0.001175045 -0.7071065 -0.7071061 -0.001174926 -0.5715702 -0.8205525 0.001166462 -0.5721254 -0.8201661 0 -0.3799682 -0.9249997 0 -0.3799703 -0.9249987 0 -0.1285269 -0.9917061 0 -0.1285284 -0.9917059 0 0.3799708 -0.9249985 0 0.1280377 -0.9917693 0 0.128528 -0.991706 2.18788e-4 0.2555665 -0.9667915 0 0.3799676 -0.9249998 0 0.5715703 -0.8205531 0 0.5721256 -0.8201653 0.001157581 0.7071055 -0.7071071 -0.001174271 0.7071072 -0.7071054 -0.001175642 0.8205522 -0.5715706 0.001165688 0.8201668 -0.5721246 0 0.9249989 -0.3799701 0 0.9249998 -0.3799679 0 0.9917059 -0.1285284 0 0.9917063 -0.1285254 0 0.9249998 0.3799679 0 0.9917698 0.1280343 0 0.9917059 0.1285281 2.19134e-4 0.9667078 0.2558828 0 0.9249989 0.3799701 0 0.820552 0.571572 0 0.8201667 0.5721238 0.001156687 0.7071055 0.7071071 -0.001175045 0.7071065 0.7071061 -0.001174926 0.5715702 0.8205525 0.001166462 0.5721254 0.8201661 0 0.3799682 0.9249997 0 0.3799703 0.9249987 0 0.1285269 0.9917061 0 0.1285284 0.9917059 0 1.57227e-7 0 1 1.50379e-6 0 1 -1.3865e-6 0 1 8.13137e-7 0 1 7.79577e-6 0 1 -6.99072e-7 0 1 -6.73667e-7 0 1 -1.50379e-6 0 1 -1.58776e-7 0 1 1.39254e-6 0 1 -7.79578e-6 0 1 1.68667e-6 0 1 -5.89971e-6 0 1 3.18353e-5 0 1 2.5535e-5 0 1 -2.58399e-6 0 1 6.81096e-7 0 1 6.99072e-7 0 1 -6.81096e-7 0 1 8.07481e-7 0 1 -6.67688e-7 0 1 1.78036e-6 0 1 2.1004e-5 0 1 1.54496e-5 0 1 -1.11307e-5 0 1 9.34829e-6 0 1 -9.41518e-6 0 1 7.38402e-6 0 1 -1.14441e-5 0 1 1.13274e-5 0 1 -1.5753e-7 0 1 -6.65954e-6 0 1 -1.29743e-6 0 1 5.89971e-6 0 1 0.9659262 -0.2588181 0 0.7071086 -0.7071049 0 0.7071105 -0.7071031 0 0.2588147 -0.9659271 0 0.2588216 -0.9659252 0 -0.2588147 -0.9659271 0 -0.2588216 -0.9659252 0 -0.7071105 -0.7071031 0 -0.7071086 -0.7071049 0 -0.9659262 -0.2588181 0 -0.9659252 -0.2588216 0 -0.9659252 0.2588216 0 -0.9659262 0.2588181 0 -0.7071086 0.7071049 0 -0.7071105 0.7071031 0 -0.2588147 0.9659271 0 -0.2588216 0.9659252 0 0.2588147 0.9659271 0 0.2588216 0.9659252 0 0.7071105 0.7071031 0 0.7071086 0.7071049 0 0.9659262 0.2588181 0 0.9659252 0.2588216 0 0.9659252 -0.2588216 0 -1.52588e-5 0 1 1.52588e-5 0 1 1.52588e-5 0 1 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 11 3 12 4 9 4 13 4 10 5 14 5 11 5 11 6 14 6 15 6 11 7 15 7 16 7 17 8 18 8 13 8 13 9 18 9 19 9 13 10 19 10 12 10 20 11 21 11 22 11 20 12 22 12 23 12 24 13 25 13 22 13 22 14 25 14 26 14 22 15 26 15 23 15 27 16 28 16 29 16 28 17 30 17 29 17 29 18 30 18 31 18 29 19 31 19 32 19 32 20 31 20 33 20 32 21 33 21 34 21 34 22 33 22 35 22 36 23 37 23 33 23 33 24 37 24 38 24 33 25 38 25 35 25 39 26 40 26 41 26 41 27 42 27 39 27 39 28 42 28 43 28 39 29 43 29 44 29 43 30 45 30 44 30 44 31 45 31 25 31 44 32 25 32 46 32 46 33 25 33 24 33 46 34 24 34 36 34 36 35 24 35 47 35 36 36 47 36 37 36 48 37 49 37 50 37 50 38 49 38 51 38 50 39 51 39 40 39 40 40 51 40 52 40 40 41 52 41 41 41 15 42 53 42 16 42 16 43 53 43 54 43 16 44 54 44 48 44 48 45 54 45 55 45 48 46 55 46 49 46 48 47 56 47 16 47 16 48 56 48 57 48 16 49 57 49 58 49 57 50 59 50 58 50 58 51 59 51 60 51 58 52 60 52 61 52 61 53 62 53 58 53 58 54 62 54 63 54 58 55 63 55 64 55 64 56 63 56 65 56 66 57 67 57 68 57 67 58 69 58 68 58 68 59 69 59 70 59 68 60 70 60 71 60 72 61 73 61 74 61 72 62 74 62 75 62 76 63 75 63 77 63 77 64 75 64 74 64 77 65 74 65 78 65 78 66 74 66 79 66 80 67 81 67 82 67 81 68 83 68 82 68 82 69 83 69 84 69 82 70 84 70 66 70 85 71 86 71 87 71 86 72 88 72 87 72 87 73 88 73 89 73 87 74 89 74 90 74 90 75 89 75 91 75 90 76 91 76 92 76 92 77 91 77 93 77 94 78 95 78 91 78 91 79 95 79 96 79 91 80 96 80 93 80 97 81 98 81 99 81 99 82 98 82 100 82 98 83 101 83 100 83 100 84 101 84 102 84 100 85 102 85 103 85 102 86 104 86 103 86 103 87 104 87 78 87 103 88 78 88 105 88 105 89 78 89 79 89 105 90 79 90 94 90 94 91 79 91 106 91 94 92 106 92 95 92 107 93 108 93 109 93 109 94 108 94 110 94 109 95 110 95 99 95 99 96 110 96 111 96 99 97 111 97 97 97 70 98 112 98 71 98 71 99 112 99 113 99 71 100 113 100 107 100 107 101 113 101 114 101 107 102 114 102 108 102 107 103 115 103 71 103 71 104 115 104 116 104 71 105 116 105 117 105 116 106 118 106 117 106 117 107 118 107 119 107 117 108 119 108 120 108 120 109 121 109 117 109 117 110 121 110 122 110 117 111 122 111 123 111 123 112 122 112 124 112 125 113 126 113 127 113 125 114 127 114 128 114 127 115 129 115 128 115 128 116 129 116 130 116 128 117 130 117 131 117 132 118 133 118 131 118 131 119 133 119 134 119 134 120 135 120 131 120 131 121 135 121 136 121 131 122 136 122 128 122 132 123 131 123 137 123 137 124 131 124 138 124 137 125 138 125 139 125 139 126 138 126 140 126 139 127 140 127 141 127 141 128 142 128 139 128 139 129 142 129 143 129 139 130 143 130 144 130 145 131 146 131 147 131 147 132 146 132 148 132 143 133 149 133 144 133 144 134 149 134 150 134 144 135 150 135 151 135 151 136 150 136 152 136 151 137 152 137 153 137 153 138 154 138 151 138 151 139 154 139 155 139 151 140 155 140 156 140 8 141 151 141 6 141 6 142 151 142 156 142 6 143 156 143 148 143 148 144 156 144 157 144 148 145 157 145 147 145 158 146 159 146 160 146 160 147 159 147 161 147 160 148 161 148 162 148 163 149 164 149 165 149 165 150 164 150 166 150 165 151 166 151 161 151 161 152 166 152 167 152 161 153 167 153 162 153 163 154 165 154 87 154 87 155 165 155 168 155 87 156 168 156 169 156 124 157 85 157 123 157 123 158 85 158 87 158 123 159 87 159 170 159 170 160 87 160 169 160 171 161 172 161 173 161 173 162 172 162 174 162 173 163 174 163 175 163 175 164 174 164 159 164 175 165 159 165 176 165 176 166 159 166 158 166 176 167 158 167 177 167 177 168 178 168 176 168 176 169 178 169 179 169 176 170 179 170 180 170 181 171 171 171 144 171 144 172 171 172 173 172 144 173 173 173 139 173 139 174 173 174 180 174 139 175 180 175 182 175 182 176 180 176 179 176 183 177 117 177 184 177 184 178 117 178 123 178 184 179 123 179 185 179 185 180 123 180 170 180 183 181 186 181 117 181 117 182 186 182 187 182 117 183 187 183 151 183 151 184 187 184 188 184 151 185 188 185 189 185 189 186 190 186 151 186 151 187 190 187 191 187 151 188 191 188 144 188 144 189 191 189 192 189 144 190 192 190 181 190 193 191 194 191 195 191 193 192 195 192 196 192 197 193 198 193 199 193 199 194 198 194 200 194 200 195 201 195 199 195 199 196 201 196 202 196 199 197 202 197 193 197 193 198 202 198 203 198 193 199 203 199 194 199 204 200 205 200 206 200 204 201 206 201 207 201 208 202 209 202 210 202 210 203 209 203 211 203 210 204 211 204 207 204 205 205 212 205 206 205 206 206 212 206 213 206 206 207 213 207 214 207 215 208 216 208 217 208 217 209 216 209 214 209 217 210 214 210 218 210 218 211 214 211 213 211 219 212 220 212 221 212 221 213 222 213 219 213 219 214 222 214 223 214 219 215 223 215 215 215 215 216 223 216 224 216 215 217 224 217 216 217 220 218 225 218 221 218 221 219 225 219 226 219 221 220 226 220 227 220 227 221 226 221 228 221 227 222 228 222 229 222 229 223 228 223 196 223 229 224 196 224 230 224 230 225 196 225 195 225 230 226 195 226 231 226 232 227 233 227 231 227 231 228 233 228 234 228 231 229 234 229 235 229 236 230 237 230 235 230 236 231 235 231 238 231 238 232 235 232 239 232 238 233 239 233 240 233 237 234 241 234 235 234 235 235 241 235 242 235 235 236 242 236 231 236 231 237 242 237 243 237 231 238 243 238 230 238 244 239 245 239 246 239 246 240 245 240 247 240 195 241 248 241 231 241 231 242 248 242 249 242 231 243 249 243 250 243 250 244 251 244 231 244 231 245 251 245 252 245 231 246 252 246 253 246 253 247 252 247 254 247 253 248 254 248 245 248 245 249 254 249 255 249 245 250 255 250 247 250 216 251 256 251 214 251 214 252 256 252 257 252 214 253 257 253 258 253 257 254 259 254 258 254 258 255 259 255 260 255 258 256 260 256 261 256 262 257 261 257 263 257 240 258 239 258 264 258 264 259 239 259 265 259 264 260 265 260 263 260 263 261 265 261 266 261 263 262 266 262 262 262 267 263 268 263 269 263 269 264 268 264 270 264 271 265 272 265 273 265 273 266 272 266 274 266 275 267 276 267 268 267 275 268 268 268 277 268 232 269 245 269 233 269 233 270 245 270 244 270 233 271 244 271 278 271 278 272 244 272 279 272 278 273 279 273 268 273 268 274 279 274 280 274 268 275 280 275 277 275 276 276 281 276 268 276 268 277 281 277 282 277 268 278 282 278 283 278 274 279 270 279 273 279 273 280 270 280 268 280 273 281 268 281 284 281 284 282 268 282 283 282 262 283 285 283 261 283 261 284 285 284 286 284 261 285 286 285 258 285 258 286 286 286 287 286 258 287 287 287 288 287 288 288 287 288 289 288 288 289 289 289 290 289 290 290 291 290 288 290 288 291 291 291 292 291 288 292 292 292 293 292 293 293 294 293 288 293 288 294 294 294 295 294 288 295 295 295 296 295 297 296 298 296 291 296 291 297 298 297 299 297 291 298 299 298 292 298 267 299 269 299 300 299 300 300 269 300 301 300 300 301 301 301 302 301 302 302 301 302 303 302 302 303 303 303 304 303 304 304 303 304 305 304 304 305 305 305 297 305 297 306 305 306 306 306 297 307 306 307 298 307 307 308 308 308 309 308 307 309 310 309 311 309 311 310 310 310 312 310 271 311 273 311 308 311 308 312 273 312 313 312 308 313 313 313 314 313 315 314 309 314 316 314 316 315 309 315 308 315 316 316 308 316 317 316 317 317 308 317 314 317 288 318 318 318 319 318 319 319 318 319 320 319 319 320 320 320 321 320 322 321 323 321 310 321 321 322 324 322 319 322 319 323 324 323 325 323 319 324 325 324 326 324 327 325 312 325 328 325 328 326 312 326 310 326 328 327 310 327 329 327 329 328 310 328 323 328 327 329 330 329 312 329 312 330 330 330 331 330 312 331 331 331 332 331 332 332 331 332 333 332 332 333 333 333 334 333 334 334 333 334 335 334 334 335 335 335 296 335 296 336 335 336 336 336 296 337 336 337 288 337 288 338 336 338 337 338 288 339 337 339 318 339 338 340 339 340 340 340 338 341 340 341 341 341 342 342 343 342 344 342 344 343 343 343 345 343 345 344 346 344 344 344 344 345 346 345 347 345 344 346 347 346 338 346 338 347 347 347 348 347 338 348 348 348 339 348 349 349 350 349 351 349 349 350 351 350 352 350 353 351 354 351 355 351 355 352 354 352 356 352 355 353 356 353 352 353 350 354 357 354 351 354 351 355 357 355 358 355 351 356 358 356 359 356 360 357 361 357 362 357 362 358 361 358 359 358 362 359 359 359 363 359 363 360 359 360 358 360 364 361 365 361 366 361 366 362 367 362 364 362 364 363 367 363 368 363 364 364 368 364 360 364 360 365 368 365 369 365 360 366 369 366 361 366 365 367 370 367 366 367 366 368 370 368 371 368 366 369 371 369 372 369 372 370 371 370 373 370 372 371 373 371 374 371 374 372 373 372 341 372 374 373 341 373 375 373 375 374 341 374 340 374 375 375 340 375 376 375 377 376 378 376 376 376 376 377 378 377 379 377 376 378 379 378 380 378 381 379 382 379 380 379 381 380 380 380 383 380 383 381 380 381 384 381 383 382 384 382 385 382 382 383 386 383 380 383 380 384 386 384 387 384 380 385 387 385 376 385 376 386 387 386 388 386 376 387 388 387 375 387 389 388 390 388 391 388 391 389 390 389 392 389 340 390 393 390 376 390 376 391 393 391 394 391 376 392 394 392 395 392 395 393 396 393 376 393 376 394 396 394 397 394 376 395 397 395 398 395 398 396 397 396 399 396 398 397 399 397 390 397 390 398 399 398 400 398 390 399 400 399 392 399 361 400 401 400 359 400 359 401 401 401 402 401 359 402 402 402 403 402 402 403 404 403 403 403 403 404 404 404 405 404 403 405 405 405 406 405 407 406 406 406 408 406 385 407 384 407 409 407 409 408 384 408 410 408 409 409 410 409 408 409 408 410 410 410 411 410 408 411 411 411 407 411 412 412 413 412 414 412 414 413 413 413 415 413 416 414 417 414 418 414 418 415 417 415 419 415 420 416 421 416 413 416 420 417 413 417 422 417 377 418 390 418 378 418 378 419 390 419 389 419 378 420 389 420 423 420 423 421 389 421 424 421 423 422 424 422 413 422 413 423 424 423 425 423 413 424 425 424 422 424 421 425 426 425 413 425 413 426 426 426 427 426 413 427 427 427 428 427 419 428 415 428 418 428 418 429 415 429 413 429 418 430 413 430 429 430 429 431 413 431 428 431 407 432 430 432 406 432 406 433 430 433 431 433 406 434 431 434 403 434 403 435 431 435 432 435 403 436 432 436 433 436 433 437 432 437 434 437 433 438 434 438 435 438 435 439 436 439 433 439 433 440 436 440 437 440 433 441 437 441 438 441 438 442 439 442 433 442 433 443 439 443 440 443 433 444 440 444 441 444 442 445 443 445 436 445 436 446 443 446 444 446 436 447 444 447 437 447 412 448 414 448 445 448 445 449 414 449 446 449 445 450 446 450 447 450 447 451 446 451 448 451 447 452 448 452 449 452 449 453 448 453 450 453 449 454 450 454 442 454 442 455 450 455 451 455 442 456 451 456 443 456 452 457 453 457 454 457 452 458 455 458 456 458 456 459 455 459 457 459 416 460 418 460 453 460 453 461 418 461 458 461 453 462 458 462 459 462 460 463 454 463 461 463 461 464 454 464 453 464 461 465 453 465 462 465 462 466 453 466 459 466 433 467 463 467 464 467 464 468 463 468 465 468 464 469 465 469 466 469 467 470 468 470 455 470 466 471 469 471 464 471 464 472 469 472 470 472 464 473 470 473 471 473 472 474 457 474 473 474 473 475 457 475 455 475 473 476 455 476 474 476 474 477 455 477 468 477 472 478 475 478 457 478 457 479 475 479 476 479 457 480 476 480 477 480 477 481 476 481 478 481 477 482 478 482 479 482 479 483 478 483 480 483 479 484 480 484 441 484 441 485 480 485 481 485 441 486 481 486 433 486 433 487 481 487 482 487 433 488 482 488 463 488 483 489 484 489 485 489 483 490 485 490 486 490 485 491 487 491 486 491 486 492 487 492 488 492 486 493 488 493 489 493 490 494 491 494 489 494 489 495 491 495 492 495 492 496 493 496 489 496 489 497 493 497 494 497 489 498 494 498 486 498 490 499 489 499 495 499 495 500 489 500 496 500 495 501 496 501 497 501 497 502 496 502 498 502 497 503 498 503 499 503 499 504 500 504 497 504 497 505 500 505 501 505 497 506 501 506 502 506 503 507 484 507 504 507 504 508 505 508 503 508 503 509 505 509 506 509 503 510 506 510 507 510 507 511 506 511 508 511 501 512 509 512 502 512 502 513 509 513 510 513 502 514 510 514 511 514 511 515 510 515 512 515 511 516 512 516 513 516 513 517 514 517 511 517 511 518 514 518 515 518 511 519 515 519 516 519 5 520 511 520 3 520 3 521 511 521 516 521 3 522 516 522 508 522 508 523 516 523 517 523 508 524 517 524 507 524 518 525 519 525 520 525 520 526 519 526 521 526 520 527 521 527 522 527 523 528 524 528 525 528 525 529 524 529 526 529 525 530 526 530 521 530 521 531 526 531 527 531 521 532 527 532 522 532 523 533 525 533 29 533 29 534 525 534 528 534 29 535 528 535 529 535 65 536 27 536 64 536 64 537 27 537 29 537 64 538 29 538 530 538 530 539 29 539 529 539 531 540 532 540 533 540 533 541 532 541 534 541 533 542 534 542 535 542 535 543 534 543 519 543 535 544 519 544 536 544 536 545 519 545 518 545 536 546 518 546 537 546 537 547 538 547 536 547 536 548 538 548 539 548 536 549 539 549 540 549 541 550 531 550 502 550 502 551 531 551 533 551 502 552 533 552 497 552 497 553 533 553 540 553 497 554 540 554 542 554 542 555 540 555 539 555 543 556 58 556 544 556 544 557 58 557 64 557 544 558 64 558 545 558 545 559 64 559 530 559 543 560 546 560 58 560 58 561 546 561 547 561 58 562 547 562 511 562 511 563 547 563 548 563 511 564 548 564 549 564 549 565 550 565 511 565 511 566 550 566 551 566 511 567 551 567 502 567 502 568 551 568 552 568 502 569 552 569 541 569 553 570 554 570 310 570 310 571 554 571 555 571 310 572 555 572 556 572 307 573 309 573 310 573 310 574 309 574 557 574 310 575 557 575 553 575 556 576 558 576 310 576 310 577 558 577 559 577 310 578 559 578 560 578 2 579 1 579 210 579 1 580 561 580 210 580 210 581 561 581 562 581 210 582 562 582 563 582 563 583 564 583 210 583 210 584 564 584 565 584 210 585 565 585 566 585 197 586 208 586 198 586 198 587 208 587 210 587 198 588 210 588 567 588 567 589 210 589 566 589 0 590 2 590 568 590 568 591 2 591 569 591 568 592 569 592 570 592 570 593 569 593 571 593 571 594 569 594 572 594 571 595 572 595 573 595 574 596 575 596 576 596 577 597 578 597 576 597 576 598 578 598 579 598 576 599 579 599 574 599 575 600 580 600 576 600 576 601 580 601 581 601 576 602 581 602 572 602 572 603 581 603 582 603 572 604 582 604 573 604 583 605 584 605 585 605 585 606 584 606 577 606 585 607 577 607 128 607 128 608 577 608 576 608 128 609 576 609 125 609 586 610 82 610 587 610 587 611 82 611 588 611 586 612 589 612 82 612 82 613 589 613 590 613 82 614 590 614 591 614 76 615 80 615 75 615 75 616 80 616 82 616 75 617 82 617 592 617 592 618 82 618 591 618 593 619 594 619 595 619 595 620 594 620 596 620 595 621 596 621 588 621 588 622 596 622 597 622 588 623 597 623 587 623 598 624 599 624 595 624 595 625 599 625 600 625 595 626 600 626 593 626 601 627 602 627 455 627 455 628 602 628 603 628 455 629 603 629 604 629 452 630 454 630 455 630 455 631 454 631 605 631 455 632 605 632 601 632 604 633 606 633 455 633 455 634 606 634 607 634 455 635 607 635 598 635 598 636 607 636 608 636 598 637 608 637 599 637 355 638 609 638 610 638 610 639 611 639 355 639 355 640 611 640 612 640 355 641 612 641 613 641 342 642 353 642 343 642 343 643 353 643 355 643 343 644 355 644 614 644 614 645 355 645 613 645 615 646 616 646 617 646 617 647 616 647 618 647 617 648 618 648 619 648 619 649 618 649 620 649 619 650 620 650 355 650 355 651 620 651 621 651 355 652 621 652 609 652 615 653 617 653 622 653 622 654 617 654 623 654 622 655 623 655 624 655 625 656 626 656 627 656 628 657 629 657 627 657 627 658 629 658 630 658 627 659 630 659 625 659 626 660 631 660 627 660 627 661 631 661 632 661 627 662 632 662 623 662 623 663 632 663 633 663 623 664 633 664 624 664 634 665 635 665 636 665 636 666 635 666 628 666 636 667 628 667 486 667 486 668 628 668 627 668 486 669 627 669 483 669 637 670 13 670 638 670 638 671 13 671 639 671 637 672 640 672 13 672 13 673 640 673 641 673 13 674 641 674 642 674 26 675 17 675 23 675 23 676 17 676 13 676 23 677 13 677 643 677 643 678 13 678 642 678 644 679 645 679 646 679 646 680 645 680 647 680 646 681 647 681 639 681 639 682 647 682 648 682 639 683 648 683 638 683 559 684 649 684 560 684 560 685 649 685 650 685 560 686 650 686 646 686 646 687 650 687 651 687 646 688 651 688 644 688 7 689 652 689 8 689 8 690 652 690 653 690 8 691 653 691 654 691 653 692 655 692 654 692 654 693 655 693 656 693 654 694 656 694 657 694 658 695 659 695 576 695 576 696 659 696 660 696 661 697 662 697 125 697 125 698 662 698 663 698 125 699 663 699 126 699 126 700 663 700 664 700 126 701 664 701 145 701 145 702 664 702 665 702 145 703 665 703 146 703 660 704 666 704 576 704 576 705 666 705 667 705 576 706 667 706 125 706 125 707 667 707 668 707 125 708 668 708 661 708 4 709 669 709 5 709 5 710 669 710 670 710 5 711 670 711 671 711 672 712 673 712 627 712 672 713 627 713 674 713 670 714 675 714 671 714 671 715 675 715 676 715 671 716 676 716 677 716 678 717 679 717 483 717 483 718 679 718 680 718 483 719 680 719 484 719 484 720 680 720 681 720 484 721 681 721 504 721 673 722 682 722 627 722 627 723 682 723 683 723 627 724 683 724 483 724 483 725 683 725 684 725 483 726 684 726 678 726 66 727 68 727 82 727 82 728 68 728 685 728 82 729 685 729 588 729 588 730 685 730 686 730 588 731 686 731 595 731 595 732 686 732 687 732 595 733 687 733 598 733 598 734 687 734 464 734 598 734 464 734 455 734 455 735 464 735 471 735 455 736 471 736 467 736 207 737 206 737 210 737 210 738 206 738 688 738 210 738 688 738 2 738 2 739 688 739 689 739 2 740 689 740 569 740 569 741 689 741 690 741 569 742 690 742 572 742 572 743 690 743 654 743 572 744 654 744 576 744 576 745 654 745 657 745 576 746 657 746 658 746 9 747 11 747 13 747 13 748 11 748 691 748 13 749 691 749 639 749 639 750 691 750 692 750 639 751 692 751 646 751 646 752 692 752 693 752 646 753 693 753 560 753 560 754 693 754 319 754 560 754 319 754 310 754 310 755 319 755 326 755 310 756 326 756 322 756 352 757 351 757 355 757 355 758 351 758 694 758 355 758 694 758 619 758 619 759 694 759 695 759 619 760 695 760 617 760 617 761 695 761 696 761 617 762 696 762 623 762 623 763 696 763 671 763 623 764 671 764 627 764 627 765 671 765 677 765 627 766 677 766 674 766 53 767 697 767 698 767 53 768 698 768 54 768 54 769 698 769 699 769 54 770 699 770 55 770 55 771 699 771 700 771 55 772 700 772 49 772 49 773 700 773 701 773 49 774 701 774 51 774 702 775 703 775 704 775 704 776 705 776 702 776 702 777 705 777 706 777 702 778 706 778 707 778 707 779 706 779 708 779 708 780 709 780 707 780 707 781 709 781 710 781 707 782 710 782 702 782 702 783 710 783 711 783 702 784 712 784 713 784 713 785 712 785 714 785 715 786 703 786 716 786 716 787 703 787 702 787 716 788 702 788 717 788 717 789 702 789 713 789 717 790 713 790 718 790 718 791 713 791 714 791 718 792 714 792 719 792 112 793 720 793 721 793 112 794 721 794 113 794 113 795 721 795 722 795 113 796 722 796 114 796 114 797 722 797 723 797 114 798 723 798 108 798 108 799 723 799 724 799 108 800 724 800 110 800 725 801 726 801 727 801 727 802 726 802 728 802 727 803 728 803 729 803 729 804 728 804 730 804 731 805 732 805 733 805 731 806 733 806 734 806 734 807 733 807 735 807 734 808 735 808 736 808 736 809 735 809 737 809 736 810 737 810 738 810 738 811 737 811 739 811 739 812 737 812 740 812 739 813 740 813 741 813 741 814 740 814 742 814 742 815 740 815 743 815 742 816 743 816 744 816 733 817 732 817 745 817 746 818 747 818 748 818 747 819 749 819 750 819 751 820 746 820 752 820 752 821 746 821 748 821 752 822 748 822 729 822 729 823 748 823 727 823 747 824 750 824 748 824 748 825 750 825 725 825 748 826 725 826 727 826 743 827 753 827 744 827 754 828 755 828 756 828 756 829 755 829 757 829 756 830 757 830 758 830 759 831 760 831 761 831 760 832 759 832 762 832 762 833 759 833 763 833 762 834 763 834 764 834 754 835 764 835 755 835 755 836 764 836 763 836 755 837 763 837 757 837 757 838 763 838 759 838 757 839 759 839 765 839 765 840 759 840 761 840 766 841 764 841 767 841 767 842 764 842 754 842 766 843 768 843 764 843 764 844 768 844 769 844 764 845 769 845 762 845 770 846 771 846 772 846 767 847 773 847 766 847 766 848 773 848 774 848 766 849 774 849 768 849 768 850 774 850 770 850 768 851 770 851 769 851 769 852 770 852 772 852 769 853 772 853 762 853 775 854 776 854 777 854 729 855 730 855 777 855 777 856 730 856 778 856 778 857 779 857 777 857 777 858 779 858 780 858 777 859 780 859 775 859 773 860 729 860 774 860 774 861 729 861 777 861 774 862 777 862 770 862 770 863 777 863 776 863 770 864 776 864 771 864 728 865 726 865 781 865 730 866 728 866 782 866 728 867 781 867 782 867 782 868 781 868 783 868 782 869 783 869 784 869 784 870 783 870 785 870 784 871 785 871 786 871 786 872 785 872 787 872 786 873 787 873 788 873 730 874 782 874 778 874 778 875 782 875 784 875 778 876 784 876 779 876 779 877 784 877 786 877 779 878 786 878 780 878 780 879 786 879 788 879 780 880 788 880 775 880 789 881 790 881 726 881 726 882 725 882 789 882 789 883 725 883 750 883 789 884 750 884 749 884 790 885 789 885 791 885 791 886 789 886 745 886 791 887 745 887 732 887 791 888 732 888 731 888 731 889 792 889 791 889 791 890 792 890 793 890 791 891 793 891 790 891 794 892 795 892 796 892 797 893 798 893 734 893 742 894 799 894 741 894 741 895 799 895 795 895 741 896 795 896 739 896 739 897 795 897 794 897 739 898 794 898 738 898 738 899 794 899 797 899 738 900 797 900 736 900 736 901 797 901 734 901 800 902 793 902 792 902 731 903 734 903 792 903 792 904 734 904 798 904 792 905 798 905 800 905 800 906 798 906 797 906 800 907 797 907 801 907 801 908 797 908 794 908 801 909 794 909 802 909 802 910 794 910 796 910 802 911 796 911 803 911 742 912 744 912 799 912 799 913 744 913 804 913 799 914 804 914 795 914 795 915 804 915 796 915 796 916 804 916 805 916 796 917 805 917 803 917 806 918 807 918 808 918 808 919 809 919 810 919 761 920 806 920 765 920 765 921 806 921 808 921 765 922 808 922 811 922 811 923 808 923 810 923 811 924 810 924 758 924 812 925 813 925 814 925 815 926 812 926 816 926 735 927 733 927 817 927 817 928 733 928 818 928 817 929 818 929 819 929 819 930 818 930 820 930 819 931 820 931 821 931 821 932 820 932 822 932 821 933 823 933 824 933 825 934 740 934 737 934 821 935 824 935 819 935 819 936 824 936 825 936 819 937 825 937 817 937 817 938 825 938 737 938 817 939 737 939 735 939 812 940 814 940 816 940 816 941 814 941 826 941 816 942 826 942 827 942 827 943 826 943 828 943 827 944 828 944 829 944 829 945 830 945 827 945 827 946 830 946 823 946 827 947 823 947 816 947 816 948 823 948 821 948 816 949 821 949 815 949 815 950 821 950 822 950 743 951 740 951 831 951 831 952 740 952 825 952 831 953 825 953 832 953 832 954 825 954 824 954 832 955 824 955 833 955 833 956 824 956 823 956 833 957 823 957 834 957 834 958 823 958 830 958 789 959 749 959 835 959 818 960 733 960 745 960 836 961 837 961 812 961 812 962 837 962 838 962 812 963 838 963 813 963 745 964 789 964 818 964 818 965 789 965 835 965 818 966 835 966 820 966 820 967 835 967 839 967 820 968 839 968 822 968 822 969 839 969 840 969 822 970 840 970 815 970 815 971 840 971 841 971 815 972 841 972 812 972 812 973 841 973 842 973 812 974 842 974 836 974 843 975 844 975 845 975 746 976 751 976 846 976 746 977 846 977 747 977 847 978 843 978 848 978 848 979 843 979 845 979 848 980 845 980 849 980 849 981 845 981 850 981 849 982 850 982 851 982 851 983 850 983 852 983 851 984 852 984 853 984 853 985 852 985 854 985 853 986 854 986 846 986 846 987 854 987 855 987 846 988 855 988 747 988 749 989 747 989 835 989 835 990 747 990 855 990 835 991 855 991 839 991 839 992 855 992 854 992 839 993 854 993 840 993 840 994 854 994 852 994 840 995 852 995 841 995 841 996 852 996 850 996 841 997 850 997 842 997 842 998 850 998 845 998 842 999 845 999 836 999 836 1000 845 1000 844 1000 752 1001 729 1001 773 1001 752 1002 773 1002 751 1002 751 1003 773 1003 856 1003 751 1004 856 1004 846 1004 846 1005 856 1005 857 1005 846 1006 857 1006 853 1006 853 1007 857 1007 858 1007 853 1008 858 1008 851 1008 851 1009 858 1009 859 1009 851 1010 859 1010 849 1010 849 1011 859 1011 860 1011 849 1012 860 1012 848 1012 848 1013 860 1013 861 1013 848 1014 861 1014 847 1014 847 1015 861 1015 862 1015 847 1016 862 1016 863 1016 863 1017 862 1017 864 1017 863 1018 864 1018 865 1018 866 1019 867 1019 862 1019 862 1020 867 1020 868 1020 862 1021 868 1021 864 1021 869 1022 870 1022 866 1022 866 1023 871 1023 869 1023 869 1024 871 1024 872 1024 869 1025 872 1025 873 1025 873 1026 872 1026 874 1026 873 1027 874 1027 875 1027 875 1028 874 1028 876 1028 875 1029 876 1029 877 1029 877 1030 876 1030 878 1030 877 1031 878 1031 879 1031 879 1032 878 1032 880 1032 879 1033 880 1033 881 1033 881 1034 880 1034 882 1034 881 1035 882 1035 883 1035 883 1036 882 1036 756 1036 883 1037 756 1037 758 1037 754 1038 856 1038 767 1038 767 1039 856 1039 773 1039 866 1040 862 1040 871 1040 871 1041 862 1041 861 1041 871 1042 861 1042 872 1042 872 1043 861 1043 860 1043 872 1044 860 1044 874 1044 874 1045 860 1045 859 1045 874 1046 859 1046 876 1046 876 1047 859 1047 858 1047 876 1048 858 1048 878 1048 878 1049 858 1049 857 1049 878 1050 857 1050 880 1050 880 1051 857 1051 856 1051 880 1052 856 1052 882 1052 882 1053 856 1053 754 1053 882 1054 754 1054 756 1054 810 1055 809 1055 884 1055 883 1056 758 1056 810 1056 870 1057 869 1057 885 1057 885 1058 869 1058 873 1058 885 1059 873 1059 875 1059 884 1060 886 1060 875 1060 875 1061 886 1061 887 1061 875 1062 887 1062 885 1062 875 1063 877 1063 884 1063 884 1064 877 1064 879 1064 884 1065 879 1065 810 1065 810 1066 879 1066 881 1066 810 1067 881 1067 883 1067 888 1068 889 1068 890 1068 891 1069 892 1069 893 1069 891 1070 893 1070 894 1070 894 1071 893 1071 895 1071 894 1072 895 1072 896 1072 896 1073 895 1073 888 1073 896 1074 888 1074 897 1074 897 1075 888 1075 890 1075 897 1076 890 1076 634 1076 634 1077 890 1077 898 1077 899 1078 628 1078 898 1078 898 1079 628 1079 635 1079 898 1080 635 1080 634 1080 900 1081 899 1081 901 1081 901 1082 899 1082 898 1082 901 1083 898 1083 889 1083 889 1084 898 1084 890 1084 900 1085 805 1085 902 1085 902 1086 805 1086 804 1086 902 1087 804 1087 903 1087 903 1088 804 1088 904 1088 744 1089 753 1089 804 1089 804 1090 753 1090 905 1090 804 1091 905 1091 904 1091 904 1092 905 1092 906 1092 904 1093 906 1093 907 1093 907 1094 906 1094 908 1094 909 1095 910 1095 631 1095 907 1096 908 1096 910 1096 631 1097 626 1097 909 1097 909 1098 626 1098 625 1098 909 1099 625 1099 911 1099 911 1100 625 1100 630 1100 911 1101 630 1101 912 1101 912 1102 630 1102 629 1102 912 1103 629 1103 913 1103 913 1104 629 1104 628 1104 913 1105 628 1105 899 1105 910 1106 909 1106 907 1106 907 1107 909 1107 911 1107 907 1108 911 1108 904 1108 904 1109 911 1109 912 1109 904 1110 912 1110 903 1110 903 1111 912 1111 913 1111 903 1112 913 1112 902 1112 902 1113 913 1113 899 1113 902 1114 899 1114 900 1114 914 1115 915 1115 916 1115 753 1116 743 1116 831 1116 910 1117 908 1117 917 1117 917 1118 908 1118 906 1118 753 1119 831 1119 905 1119 918 1120 919 1120 916 1120 916 1121 919 1121 920 1121 916 1122 920 1122 914 1122 906 1123 905 1123 917 1123 917 1124 905 1124 831 1124 917 1125 831 1125 921 1125 921 1126 831 1126 832 1126 921 1127 832 1127 922 1127 922 1128 832 1128 833 1128 922 1129 833 1129 923 1129 923 1130 833 1130 834 1130 923 1131 834 1131 916 1131 916 1132 834 1132 830 1132 916 1133 830 1133 918 1133 918 1134 830 1134 829 1134 924 1135 807 1135 925 1135 925 1136 807 1136 806 1136 925 1137 806 1137 926 1137 762 1138 927 1138 760 1138 760 1139 927 1139 761 1139 761 1140 927 1140 806 1140 806 1141 927 1141 928 1141 806 1142 928 1142 926 1142 927 1143 762 1143 772 1143 775 1144 929 1144 776 1144 776 1145 929 1145 930 1145 776 1146 930 1146 931 1146 772 1147 771 1147 927 1147 927 1148 771 1148 776 1148 927 1149 776 1149 932 1149 932 1150 776 1150 931 1150 787 1151 933 1151 788 1151 788 1152 933 1152 934 1152 788 1153 934 1153 775 1153 775 1154 934 1154 929 1154 935 1155 936 1155 937 1155 937 1156 936 1156 938 1156 937 1157 938 1157 939 1157 787 1158 793 1158 933 1158 933 1159 793 1159 939 1159 933 1160 939 1160 940 1160 940 1161 939 1161 938 1161 787 1162 785 1162 793 1162 793 1163 785 1163 783 1163 793 1164 783 1164 790 1164 790 1165 783 1165 781 1165 790 1166 781 1166 726 1166 939 1167 793 1167 800 1167 939 1168 800 1168 941 1168 941 1169 800 1169 801 1169 941 1170 801 1170 942 1170 942 1171 801 1171 802 1171 942 1172 802 1172 943 1172 943 1173 802 1173 803 1173 943 1174 803 1174 944 1174 895 1175 803 1175 888 1175 888 1176 803 1176 805 1176 900 1177 901 1177 805 1177 805 1178 901 1178 889 1178 805 1179 889 1179 888 1179 945 1180 944 1180 892 1180 892 1181 944 1181 803 1181 892 1182 803 1182 893 1182 893 1183 803 1183 895 1183 945 1182 946 1182 944 1182 944 1184 946 1184 947 1184 944 1185 947 1185 948 1185 948 1186 947 1186 949 1186 949 1187 950 1187 948 1187 948 1178 950 1178 951 1178 948 1188 951 1188 952 1188 891 1189 953 1189 892 1189 892 1190 953 1190 945 1190 953 1191 891 1191 954 1191 955 1192 956 1192 957 1192 953 1193 954 1193 957 1193 957 1194 954 1194 958 1194 957 1195 958 1195 955 1195 959 1196 960 1196 956 1196 956 1197 960 1197 961 1197 956 1198 961 1198 957 1198 962 1199 963 1199 964 1199 959 1200 956 1200 963 1200 963 1201 956 1201 965 1201 963 1202 965 1202 964 1202 962 1203 964 1203 966 1203 966 1204 964 1204 967 1204 966 1205 967 1205 968 1205 969 1206 970 1206 971 1206 971 1207 970 1207 972 1207 969 1208 973 1208 970 1208 970 1209 973 1209 974 1209 970 1210 974 1210 968 1210 968 1211 974 1211 975 1211 968 1212 975 1212 966 1212 631 1213 910 1213 632 1213 632 1214 910 1214 917 1214 632 1215 917 1215 633 1215 633 1216 917 1216 624 1216 624 1217 917 1217 921 1217 624 1218 921 1218 622 1218 622 1219 921 1219 922 1219 622 1220 922 1220 615 1220 615 1221 922 1221 923 1221 615 1222 923 1222 616 1222 616 1223 923 1223 618 1223 618 1224 923 1224 916 1224 618 1225 916 1225 620 1225 620 1226 916 1226 915 1226 620 1227 915 1227 621 1227 894 1228 896 1228 976 1228 976 1229 896 1229 897 1229 493 1230 977 1230 494 1230 494 1231 977 1231 978 1231 494 1232 978 1232 486 1232 486 1233 978 1233 976 1233 486 1234 976 1234 636 1234 636 1235 976 1235 897 1235 636 1236 897 1236 634 1236 977 1237 955 1237 978 1237 978 1238 955 1238 958 1238 978 1239 958 1239 976 1239 976 1240 958 1240 954 1240 976 1241 954 1241 894 1241 894 1242 954 1242 891 1242 979 1243 980 1243 981 1243 981 1244 980 1244 982 1244 981 1245 982 1245 983 1245 983 1246 982 1246 935 1246 984 1247 985 1247 986 1247 986 1248 985 1248 987 1248 986 1249 987 1249 988 1249 988 1250 987 1250 989 1250 988 1251 989 1251 990 1251 990 1252 989 1252 991 1252 990 1253 991 1253 992 1253 992 1254 991 1254 993 1254 993 1255 991 1255 994 1255 993 1256 994 1256 995 1256 996 1257 995 1257 994 1257 997 1258 998 1258 999 1258 1000 1259 1001 1259 1002 1259 1002 1260 1001 1260 1003 1260 999 1261 979 1261 981 1261 983 1262 1003 1262 981 1262 981 1263 1003 1263 1001 1263 981 1264 1001 1264 999 1264 999 1265 1001 1265 1000 1265 999 1266 1000 1266 997 1266 984 1267 1004 1267 985 1267 1005 1268 926 1268 928 1268 1006 1269 1007 1269 1008 1269 1008 1270 1007 1270 1009 1270 1006 1271 1010 1271 1007 1271 1007 1272 1010 1272 1011 1272 1007 1273 1011 1273 927 1273 1008 1274 1012 1274 1006 1274 1006 1275 1012 1275 1013 1275 1006 1276 1013 1276 1010 1276 1010 1277 1013 1277 1005 1277 1010 1278 1005 1278 1011 1278 1011 1279 1005 1279 928 1279 1011 1280 928 1280 927 1280 1014 1281 1007 1281 927 1281 1015 1282 1016 1282 1017 1282 1017 1283 1016 1283 1018 1283 1014 1284 927 1284 1019 1284 1019 1285 927 1285 932 1285 1019 1286 932 1286 931 1286 931 1287 1020 1287 1019 1287 1019 1288 1020 1288 1016 1288 1019 1289 1016 1289 1014 1289 1014 1290 1016 1290 1015 1290 1014 1291 1015 1291 1007 1291 1007 1292 1015 1292 1017 1292 1007 1293 1017 1293 1009 1293 1020 1294 931 1294 930 1294 1021 1295 980 1295 1016 1295 1016 1296 980 1296 979 1296 1016 1297 979 1297 1018 1297 1022 1298 1023 1298 1021 1298 1021 1299 1023 1299 1024 1299 1021 1300 1024 1300 980 1300 1016 1301 1020 1301 1021 1301 1021 1302 1020 1302 930 1302 1021 1303 930 1303 1022 1303 1022 1304 930 1304 929 1304 982 1305 980 1305 1024 1305 935 1306 982 1306 1025 1306 982 1307 1024 1307 1025 1307 1025 1308 1024 1308 1023 1308 1025 1309 1023 1309 1026 1309 1026 1310 1023 1310 1022 1310 1026 1311 1022 1311 1027 1311 1027 1312 1022 1312 929 1312 1027 1313 929 1313 934 1313 935 1314 1025 1314 936 1314 936 1315 1025 1315 1026 1315 936 1316 1026 1316 938 1316 938 1317 1026 1317 1027 1317 938 1318 1027 1318 940 1318 940 1319 1027 1319 934 1319 940 1320 934 1320 933 1320 983 1321 1028 1321 1003 1321 1003 1322 1028 1322 1002 1322 995 1323 996 1323 1029 1323 1029 1324 996 1324 1028 1324 1029 1325 1028 1325 937 1325 937 1326 1028 1326 983 1326 937 1327 983 1327 935 1327 1029 1328 937 1328 939 1328 939 1329 1030 1329 1029 1329 1029 1330 1030 1330 993 1330 1029 1331 993 1331 995 1331 1031 1332 1030 1332 939 1332 1032 1333 1033 1333 1034 1333 1034 1334 1033 1334 1035 1334 993 1335 1030 1335 992 1335 992 1336 1030 1336 1031 1336 992 1337 1031 1337 990 1337 990 1338 1031 1338 1035 1338 990 1339 1035 1339 988 1339 988 1340 1035 1340 1033 1340 988 1341 1033 1341 986 1341 943 1342 944 1342 1036 1342 939 1343 941 1343 1031 1343 1031 1344 941 1344 942 1344 1031 1345 942 1345 1035 1345 1035 1346 942 1346 943 1346 1035 1347 943 1347 1034 1347 1034 1348 943 1348 1036 1348 1034 1349 1036 1349 1032 1349 944 1350 948 1350 1036 1350 1036 1351 948 1351 1037 1351 1036 1352 1037 1352 1032 1352 1032 1353 1037 1353 1033 1353 1033 1354 1037 1354 984 1354 1033 1355 984 1355 986 1355 1038 1356 924 1356 925 1356 925 1357 926 1357 1005 1357 1039 1358 1012 1358 1040 1358 925 1359 1005 1359 1038 1359 1038 1360 1005 1360 1039 1360 1038 1361 1039 1361 1041 1361 1041 1362 1039 1362 1040 1362 1041 1363 1040 1363 1042 1363 1043 1364 994 1364 991 1364 1044 1365 1043 1365 1045 1365 1046 1366 1047 1366 1048 1366 1048 1367 1047 1367 1049 1367 1048 1368 1049 1368 1050 1368 1050 1369 1049 1369 1051 1369 1050 1370 1051 1370 1052 1370 1052 1371 1051 1371 1053 1371 1052 1372 1054 1372 1055 1372 1056 1373 1057 1373 1058 1373 1052 1374 1055 1374 1050 1374 1050 1375 1055 1375 1056 1375 1050 1376 1056 1376 1048 1376 1048 1377 1056 1377 1058 1377 1048 1378 1058 1378 1046 1378 1043 1379 991 1379 1045 1379 1045 1380 991 1380 989 1380 1045 1381 989 1381 1059 1381 1059 1382 989 1382 987 1382 1059 1383 987 1383 985 1383 985 1384 1060 1384 1059 1384 1059 1385 1060 1385 1054 1385 1059 1386 1054 1386 1045 1386 1045 1387 1054 1387 1052 1387 1045 1388 1052 1388 1044 1388 1044 1389 1052 1389 1053 1389 1061 1390 1057 1390 1062 1390 1062 1391 1057 1391 1056 1391 1062 1392 1056 1392 1063 1392 1063 1393 1056 1393 1055 1393 1063 1394 1055 1394 1064 1394 1064 1395 1055 1395 1054 1395 1064 1396 1054 1396 1065 1396 1065 1397 1054 1397 1060 1397 1066 1398 1067 1398 1068 1398 1002 1399 1028 1399 1043 1399 1043 1400 1028 1400 996 1400 1043 1401 996 1401 994 1401 1049 1402 1047 1402 1069 1402 1069 1403 1066 1403 1049 1403 1049 1404 1066 1404 1068 1404 1049 1405 1068 1405 1051 1405 1051 1406 1068 1406 1070 1406 1051 1407 1070 1407 1053 1407 1053 1408 1070 1408 1071 1408 1053 1409 1071 1409 1044 1409 1044 1410 1071 1410 1072 1410 1044 1411 1072 1411 1043 1411 1043 1412 1072 1412 1073 1412 1043 1413 1073 1413 1002 1413 1074 1414 1075 1414 1076 1414 997 1415 1000 1415 1077 1415 1074 1416 1076 1416 1078 1416 998 1417 997 1417 1079 1417 1079 1418 997 1418 1077 1418 1079 1419 1077 1419 1080 1419 1080 1420 1077 1420 1081 1420 1080 1421 1081 1421 1082 1421 1082 1422 1081 1422 1083 1422 1082 1423 1083 1423 1084 1423 1084 1424 1083 1424 1085 1424 1084 1425 1085 1425 1076 1425 1076 1426 1085 1426 1086 1426 1076 1427 1086 1427 1078 1427 1067 1428 1078 1428 1068 1428 1068 1429 1078 1429 1086 1429 1068 1430 1086 1430 1070 1430 1070 1431 1086 1431 1085 1431 1070 1432 1085 1432 1071 1432 1071 1433 1085 1433 1083 1433 1071 1434 1083 1434 1072 1434 1072 1435 1083 1435 1081 1435 1072 1436 1081 1436 1073 1436 1073 1437 1081 1437 1077 1437 1073 1438 1077 1438 1002 1438 1002 1439 1077 1439 1000 1439 1087 1440 1088 1440 1089 1440 1087 1441 1089 1441 1075 1441 1075 1442 1089 1442 1090 1442 1075 1443 1090 1443 1076 1443 1076 1444 1090 1444 1091 1444 1076 1445 1091 1445 1084 1445 1084 1446 1091 1446 1092 1446 1084 1447 1092 1447 1082 1447 1082 1448 1092 1448 1093 1448 1082 1449 1093 1449 1080 1449 1080 1450 1093 1450 1094 1450 1080 1451 1094 1451 1079 1451 1079 1452 1094 1452 1095 1452 1079 1453 1095 1453 998 1453 998 1454 1095 1454 1096 1454 998 1455 1096 1455 999 1455 999 1456 1096 1456 1018 1456 999 1457 1018 1457 979 1457 1008 1458 1009 1458 1096 1458 1096 1459 1009 1459 1017 1459 1096 1460 1017 1460 1018 1460 1097 1461 1012 1461 1008 1461 1008 1462 1098 1462 1097 1462 1097 1463 1098 1463 1099 1463 1097 1464 1099 1464 1100 1464 1100 1465 1099 1465 1101 1465 1100 1466 1101 1466 1102 1466 1102 1467 1101 1467 1103 1467 1102 1468 1103 1468 1104 1468 1104 1469 1103 1469 1105 1469 1104 1470 1105 1470 1106 1470 1106 1471 1105 1471 1107 1471 1106 1472 1107 1472 1108 1472 1108 1473 1107 1473 1109 1473 1108 1474 1109 1474 1110 1474 1110 1475 1109 1475 1111 1475 1110 1476 1111 1476 1112 1476 1113 1477 1090 1477 1114 1477 1114 1478 1090 1478 1089 1478 1008 1479 1096 1479 1098 1479 1098 1480 1096 1480 1095 1480 1098 1481 1095 1481 1099 1481 1099 1482 1095 1482 1094 1482 1099 1483 1094 1483 1101 1483 1101 1484 1094 1484 1093 1484 1101 1485 1093 1485 1103 1485 1103 1486 1093 1486 1092 1486 1103 1487 1092 1487 1105 1487 1105 1488 1092 1488 1091 1488 1105 1489 1091 1489 1107 1489 1107 1490 1091 1490 1090 1490 1107 1491 1090 1491 1109 1491 1109 1492 1090 1492 1113 1492 1109 1493 1113 1493 1111 1493 1115 1494 1116 1494 1117 1494 1012 1495 1097 1495 1040 1495 1040 1496 1097 1496 1100 1496 1040 1497 1100 1497 1102 1497 1110 1498 1112 1498 1115 1498 1110 1499 1115 1499 1108 1499 1108 1500 1115 1500 1106 1500 1106 1501 1115 1501 1117 1501 1106 1502 1117 1502 1104 1502 1104 1503 1117 1503 1118 1503 1104 1504 1118 1504 1102 1504 1102 1505 1118 1505 1042 1505 1102 1506 1042 1506 1040 1506 1119 1507 950 1507 949 1507 945 1508 953 1508 1120 1508 945 1509 1120 1509 946 1509 946 1510 1120 1510 1121 1510 946 1511 1121 1511 947 1511 947 1512 1121 1512 1122 1512 947 1513 1122 1513 949 1513 949 1514 1122 1514 21 1514 949 1515 21 1515 1119 1515 951 1516 1123 1516 952 1516 952 1517 1123 1517 1124 1517 1119 1518 21 1518 20 1518 23 1519 1124 1519 20 1519 20 1520 1124 1520 1123 1520 20 1521 1123 1521 1119 1521 1119 1522 1123 1522 951 1522 1119 1523 951 1523 950 1523 1037 1524 948 1524 952 1524 952 1525 1125 1525 1037 1525 1037 1526 1125 1526 1126 1526 1037 1527 1126 1527 1127 1527 1128 1528 1129 1528 1130 1528 1128 1529 1130 1529 1127 1529 1127 1530 1130 1530 1131 1530 1127 1531 1131 1531 1037 1531 1037 1532 1131 1532 1004 1532 1037 1533 1004 1533 984 1533 1132 1534 1133 1534 1129 1534 640 1535 637 1535 1133 1535 1129 1536 1128 1536 1132 1536 1132 1537 1128 1537 1127 1537 1132 1538 1127 1538 1134 1538 1134 1539 1127 1539 1126 1539 1134 1540 1126 1540 1135 1540 1135 1541 1126 1541 1125 1541 1135 1542 1125 1542 1136 1542 1136 1543 1125 1543 952 1543 1136 1544 952 1544 1124 1544 1133 1545 1132 1545 640 1545 640 1546 1132 1546 1134 1546 640 1547 1134 1547 641 1547 641 1548 1134 1548 1135 1548 641 1549 1135 1549 642 1549 642 1550 1135 1550 1136 1550 642 1551 1136 1551 643 1551 643 1552 1136 1552 1124 1552 643 1553 1124 1553 23 1553 1137 1554 1061 1554 1062 1554 1129 1555 1133 1555 1138 1555 1004 1556 1131 1556 1138 1556 1138 1557 1131 1557 1130 1557 1138 1558 1130 1558 1129 1558 1139 1559 1140 1559 1141 1559 1141 1560 1140 1560 1142 1560 1137 1561 1062 1561 1143 1561 1142 1562 1143 1562 1141 1562 1141 1563 1143 1563 1062 1563 1141 1564 1062 1564 1144 1564 1144 1565 1062 1565 1063 1565 1144 1566 1063 1566 1145 1566 1145 1567 1063 1567 1064 1567 1145 1568 1064 1568 1146 1568 1146 1569 1064 1569 1065 1569 1146 1570 1065 1570 1138 1570 1138 1571 1065 1571 1060 1571 1138 1572 1060 1572 1004 1572 1004 1573 1060 1573 985 1573 1138 1574 1133 1574 637 1574 1145 1575 644 1575 1144 1575 1144 1576 644 1576 651 1576 1144 1577 651 1577 1141 1577 1141 1578 651 1578 650 1578 1141 1579 650 1579 1139 1579 1139 1580 650 1580 649 1580 1139 1581 649 1581 559 1581 637 1582 638 1582 1138 1582 1138 1583 638 1583 648 1583 1138 1584 648 1584 1146 1584 1146 1585 648 1585 647 1585 1146 1586 647 1586 1145 1586 1145 1587 647 1587 645 1587 1145 1588 645 1588 644 1588 490 1589 1147 1589 491 1589 24 1590 22 1590 1148 1590 1148 1591 1121 1591 1120 1591 22 1592 21 1592 1148 1592 1148 1593 21 1593 1122 1593 1148 1594 1122 1594 1121 1594 47 1595 1149 1595 37 1595 37 1596 1149 1596 1150 1596 37 1597 1150 1597 38 1597 963 1598 34 1598 1150 1598 1150 1599 34 1599 35 1599 1150 1600 35 1600 38 1600 963 1601 962 1601 34 1601 34 1602 962 1602 966 1602 34 1603 966 1603 32 1603 32 1604 966 1604 975 1604 973 1605 524 1605 974 1605 974 1606 524 1606 523 1606 974 1607 523 1607 975 1607 975 1608 523 1608 29 1608 975 1609 29 1609 32 1609 969 1610 527 1610 973 1610 973 1611 527 1611 526 1611 973 1612 526 1612 524 1612 538 1613 537 1613 972 1613 972 1614 537 1614 518 1614 972 1615 518 1615 971 1615 971 1616 518 1616 520 1616 971 1617 520 1617 969 1617 969 1618 520 1618 522 1618 969 1619 522 1619 527 1619 538 1620 972 1620 539 1620 539 1621 972 1621 970 1621 539 1622 970 1622 542 1622 542 1623 970 1623 968 1623 542 1624 968 1624 497 1624 497 1625 968 1625 967 1625 497 1626 967 1626 495 1626 491 1627 1147 1627 492 1627 492 1628 1147 1628 1151 1628 492 1629 1151 1629 493 1629 495 1630 967 1630 490 1630 490 1631 967 1631 964 1631 490 1632 964 1632 1147 1632 1147 1633 964 1633 965 1633 1147 1634 965 1634 1151 1634 1151 1635 965 1635 956 1635 1151 1636 956 1636 955 1636 47 1637 24 1637 1149 1637 1149 1638 24 1638 1148 1638 1149 1639 1148 1639 957 1639 957 1640 1148 1640 1120 1640 957 1641 1120 1641 953 1641 957 1642 961 1642 1149 1642 1149 1643 961 1643 960 1643 1149 1644 960 1644 1150 1644 1150 1645 960 1645 959 1645 1150 1646 959 1646 963 1646 258 1647 288 1647 1152 1647 688 1647 206 1647 1152 1647 1152 1647 206 1647 214 1647 1152 1647 214 1647 258 1647 654 1647 690 1647 1152 1647 1152 1648 690 1648 689 1648 1152 1649 689 1649 688 1649 117 1647 151 1647 1152 1647 1152 1650 151 1650 8 1650 1152 1651 8 1651 654 1651 685 1647 68 1647 1152 1647 1152 1648 68 1648 71 1648 1152 1652 71 1652 117 1652 464 1647 687 1647 1152 1647 1152 1653 687 1653 686 1653 1152 1651 686 1651 685 1651 359 1654 1153 1654 1152 1654 1152 1647 1153 1647 433 1647 1152 1647 433 1647 464 1647 695 1655 694 1655 1152 1655 1152 1647 694 1647 351 1647 1152 1647 351 1647 359 1647 5 1647 671 1647 1152 1647 1152 1651 671 1651 696 1651 1152 1651 696 1651 695 1651 16 1647 58 1647 1152 1647 1152 1647 58 1647 511 1647 1152 1652 511 1652 5 1652 692 1647 691 1647 1152 1647 1152 1648 691 1648 11 1648 1152 1651 11 1651 16 1651 288 1647 319 1647 1152 1647 1152 1647 319 1647 693 1647 1152 1649 693 1649 692 1649 1154 1656 1155 1656 1156 1656 1156 1657 1155 1657 1157 1657 536 1658 1154 1658 535 1658 535 1659 1154 1659 1156 1659 535 1660 1156 1660 533 1660 533 1661 1156 1661 1157 1661 533 1662 1157 1662 1155 1662 533 1663 1155 1663 540 1663 540 1664 1155 1664 1154 1664 540 1665 1154 1665 536 1665 9 1666 1158 1666 1159 1666 9 1667 1159 1667 10 1667 10 1668 1159 1668 1160 1668 10 1669 1160 1669 14 1669 14 1670 1160 1670 1161 1670 14 1671 1161 1671 15 1671 15 1672 1161 1672 697 1672 15 1673 697 1673 53 1673 1162 1674 1163 1674 1164 1674 1164 1675 1163 1675 1165 1675 1165 1676 1166 1676 1164 1676 1164 1677 1166 1677 1167 1677 1164 1678 1167 1678 1168 1678 1169 1679 1162 1679 1170 1679 1170 1680 1162 1680 1164 1680 1170 1681 1164 1681 1171 1681 1171 1682 1164 1682 1172 1682 1168 1683 701 1683 1164 1683 1164 1684 701 1684 1158 1684 1164 1685 1158 1685 1172 1685 699 1686 1173 1686 700 1686 700 1687 1173 1687 701 1687 1159 1688 1158 1688 1160 1688 1160 1689 1158 1689 701 1689 1160 1690 701 1690 1161 1690 1161 1691 701 1691 1173 1691 1161 1692 1173 1692 697 1692 697 1693 1173 1693 699 1693 697 1694 699 1694 698 1694 1174 1695 50 1695 1175 1695 1175 1695 50 1695 40 1695 1175 1695 40 1695 39 1695 33 1696 1176 1696 1177 1696 33 1697 1177 1697 36 1697 36 1698 1177 1698 1178 1698 36 1699 1178 1699 46 1699 46 1700 1178 1700 1179 1700 46 1701 1179 1701 44 1701 44 1702 1179 1702 1175 1702 44 1703 1175 1703 39 1703 27 1704 1180 1704 1181 1704 27 1705 1181 1705 28 1705 28 1706 1181 1706 1182 1706 28 1706 1182 1706 30 1706 30 1707 1182 1707 1183 1707 30 1708 1183 1708 31 1708 31 1709 1183 1709 1176 1709 31 1710 1176 1710 33 1710 63 1711 1184 1711 65 1711 65 1712 1184 1712 1180 1712 65 1711 1180 1711 27 1711 59 1713 1185 1713 1186 1713 59 1714 1186 1714 60 1714 60 1715 1186 1715 1187 1715 60 1716 1187 1716 61 1716 61 1717 1187 1717 1188 1717 61 1718 1188 1718 62 1718 62 1719 1188 1719 1184 1719 62 1720 1184 1720 63 1720 50 1721 1174 1721 1189 1721 50 1722 1189 1722 48 1722 48 1723 1189 1723 1190 1723 48 1724 1190 1724 56 1724 56 1725 1190 1725 1191 1725 56 1726 1191 1726 57 1726 57 1727 1191 1727 1185 1727 57 1728 1185 1728 59 1728 1184 1729 1174 1729 1180 1729 1180 1730 1174 1730 1175 1730 1178 1731 1192 1731 1179 1731 1179 1732 1192 1732 1175 1732 1181 1733 1180 1733 1182 1733 1182 1734 1180 1734 1175 1734 1182 1735 1175 1735 1183 1735 1183 1736 1175 1736 1192 1736 1183 1737 1192 1737 1176 1737 1176 1738 1192 1738 1178 1738 1176 1739 1178 1739 1177 1739 1187 1740 1193 1740 1188 1740 1188 1741 1193 1741 1184 1741 1189 1742 1174 1742 1190 1742 1190 1743 1174 1743 1184 1743 1190 1744 1184 1744 1191 1744 1191 1745 1184 1745 1193 1745 1191 1746 1193 1746 1185 1746 1185 1747 1193 1747 1187 1747 1185 1748 1187 1748 1186 1748 530 1695 1194 1695 545 1695 545 1695 1194 1695 1195 1695 545 1695 1195 1695 544 1695 521 1749 1196 1749 1197 1749 521 1750 1197 1750 525 1750 525 1751 1197 1751 1198 1751 525 1752 1198 1752 528 1752 528 1753 1198 1753 1199 1753 528 1754 1199 1754 529 1754 529 1755 1199 1755 1194 1755 529 1756 1194 1756 530 1756 531 1757 1200 1757 1201 1757 531 1758 1201 1758 532 1758 532 1759 1201 1759 1202 1759 532 1760 1202 1760 534 1760 534 1761 1202 1761 1203 1761 534 1762 1203 1762 519 1762 519 1763 1203 1763 1196 1763 519 1764 1196 1764 521 1764 1200 1711 531 1711 1204 1711 1204 1765 531 1765 541 1765 1204 1711 541 1711 552 1711 548 1766 1205 1766 1206 1766 548 1767 1206 1767 549 1767 549 1768 1206 1768 1207 1768 549 1769 1207 1769 550 1769 550 1770 1207 1770 1208 1770 550 1771 1208 1771 551 1771 551 1772 1208 1772 1204 1772 551 1773 1204 1773 552 1773 544 1774 1195 1774 1209 1774 544 1775 1209 1775 543 1775 543 1776 1209 1776 1210 1776 543 1777 1210 1777 546 1777 546 1778 1210 1778 1211 1778 546 1779 1211 1779 547 1779 547 1780 1211 1780 1205 1780 547 1781 1205 1781 548 1781 1194 1782 1200 1782 1195 1782 1195 1782 1200 1782 1204 1782 1208 1783 1207 1783 1206 1783 1209 1784 1195 1784 1210 1784 1210 1785 1195 1785 1204 1785 1210 1786 1204 1786 1211 1786 1211 1787 1204 1787 1208 1787 1211 1788 1208 1788 1205 1788 1205 1789 1208 1789 1206 1789 1199 1790 1198 1790 1197 1790 1201 1791 1200 1791 1202 1791 1202 1792 1200 1792 1194 1792 1202 1793 1194 1793 1203 1793 1203 1794 1194 1794 1199 1794 1203 1795 1199 1795 1196 1795 1196 1796 1199 1796 1197 1796 1212 1695 510 1695 1213 1695 1213 1797 510 1797 509 1797 1213 1695 509 1695 501 1695 496 1798 1214 1798 1215 1798 496 1799 1215 1799 498 1799 498 1800 1215 1800 1216 1800 498 1801 1216 1801 499 1801 499 1802 1216 1802 1217 1802 499 1803 1217 1803 500 1803 500 1804 1217 1804 1213 1804 500 1805 1213 1805 501 1805 485 1806 1218 1806 1219 1806 485 1807 1219 1807 487 1807 487 1808 1219 1808 1220 1808 487 1809 1220 1809 488 1809 488 1810 1220 1810 1221 1810 488 1811 1221 1811 489 1811 489 1812 1221 1812 1214 1812 489 1710 1214 1710 496 1710 503 1711 1222 1711 484 1711 484 1711 1222 1711 1218 1711 484 1711 1218 1711 485 1711 515 1813 1223 1813 1224 1813 515 1814 1224 1814 516 1814 516 1815 1224 1815 1225 1815 516 1816 1225 1816 517 1816 517 1817 1225 1817 1226 1817 517 1818 1226 1818 507 1818 507 1819 1226 1819 1222 1819 507 1820 1222 1820 503 1820 510 1821 1212 1821 1227 1821 510 1822 1227 1822 512 1822 512 1823 1227 1823 1228 1823 512 1824 1228 1824 513 1824 513 1825 1228 1825 1229 1825 513 1826 1229 1826 514 1826 514 1827 1229 1827 1223 1827 514 1828 1223 1828 515 1828 1213 1829 1218 1829 1212 1829 1212 1830 1218 1830 1222 1830 1225 1831 1230 1831 1226 1831 1226 1832 1230 1832 1222 1832 1227 1833 1212 1833 1228 1833 1228 1834 1212 1834 1222 1834 1228 1835 1222 1835 1229 1835 1229 1836 1222 1836 1230 1836 1229 1837 1230 1837 1223 1837 1223 1838 1230 1838 1225 1838 1223 1839 1225 1839 1224 1839 1216 1840 1231 1840 1217 1840 1217 1841 1231 1841 1213 1841 1219 1842 1218 1842 1220 1842 1220 1843 1218 1843 1213 1843 1220 1844 1213 1844 1221 1844 1221 1845 1213 1845 1231 1845 1221 1846 1231 1846 1214 1846 1214 1847 1231 1847 1216 1847 1214 1848 1216 1848 1215 1848 670 1849 718 1849 719 1849 670 1850 719 1850 675 1850 675 1851 719 1851 714 1851 675 1852 714 1852 676 1852 676 1853 714 1853 712 1853 676 1854 712 1854 677 1854 677 1855 712 1855 702 1855 677 1856 702 1856 674 1856 506 1857 703 1857 715 1857 506 1858 715 1858 508 1858 508 1859 715 1859 716 1859 508 1860 716 1860 3 1860 3 1861 716 1861 4 1861 4 1862 716 1862 717 1862 4 1863 717 1863 669 1863 669 1864 717 1864 718 1864 669 1865 718 1865 670 1865 865 1866 1232 1866 1233 1866 1233 1867 1232 1867 1234 1867 1233 1868 1234 1868 1235 1868 1235 1869 1234 1869 1236 1869 1237 1870 829 1870 1238 1870 1238 1871 829 1871 828 1871 1238 1872 828 1872 1239 1872 1239 1873 828 1873 826 1873 1239 1874 826 1874 1240 1874 1240 1875 826 1875 814 1875 1240 1876 814 1876 1241 1876 1241 1877 814 1877 1242 1877 1242 1878 814 1878 813 1878 1242 1879 813 1879 1243 1879 838 1880 1243 1880 813 1880 843 1881 847 1881 863 1881 844 1882 1244 1882 836 1882 836 1883 1244 1883 1245 1883 863 1884 865 1884 1233 1884 1235 1885 1245 1885 1233 1885 1233 1886 1245 1886 1244 1886 1233 1887 1244 1887 863 1887 863 1888 1244 1888 844 1888 863 1889 844 1889 843 1889 1237 1890 918 1890 829 1890 1246 1891 1247 1891 1248 1891 1249 1892 1250 1892 866 1892 866 1893 1250 1893 867 1893 1249 1894 1251 1894 1250 1894 1250 1895 1251 1895 1252 1895 1250 1896 1252 1896 1253 1896 866 1897 870 1897 1249 1897 1249 1898 870 1898 1254 1898 1249 1899 1254 1899 1251 1899 1251 1900 1254 1900 1246 1900 1251 1901 1246 1901 1252 1901 1252 1902 1246 1902 1248 1902 1252 1903 1248 1903 1253 1903 1255 1904 1250 1904 1253 1904 1256 1905 1257 1905 868 1905 868 1906 1257 1906 864 1906 1255 1907 1253 1907 1258 1907 1258 1908 1253 1908 1259 1908 1258 1909 1259 1909 1260 1909 1260 1910 1261 1910 1258 1910 1258 1911 1261 1911 1257 1911 1258 1912 1257 1912 1255 1912 1255 1913 1257 1913 1256 1913 1255 1914 1256 1914 1250 1914 1250 1915 1256 1915 868 1915 1250 1916 868 1916 867 1916 1261 1917 1260 1917 1262 1917 1263 1918 1232 1918 1257 1918 1257 1919 1232 1919 865 1919 1257 1920 865 1920 864 1920 1264 1921 1265 1921 1263 1921 1263 1922 1265 1922 1266 1922 1263 1923 1266 1923 1232 1923 1257 1924 1261 1924 1263 1924 1263 1925 1261 1925 1262 1925 1263 1926 1262 1926 1264 1926 1264 1927 1262 1927 1267 1927 1234 1928 1232 1928 1266 1928 1236 1929 1234 1929 1268 1929 1234 1930 1266 1930 1268 1930 1268 1931 1266 1931 1265 1931 1268 1932 1265 1932 1269 1932 1269 1933 1265 1933 1264 1933 1269 1934 1264 1934 1270 1934 1270 1935 1264 1935 1267 1935 1270 1936 1267 1936 1271 1936 1236 1937 1268 1937 1272 1937 1272 1938 1268 1938 1269 1938 1272 1939 1269 1939 1273 1939 1273 1940 1269 1940 1270 1940 1273 1941 1270 1941 1274 1941 1274 1942 1270 1942 1271 1942 1274 1943 1271 1943 1275 1943 1235 1944 837 1944 1245 1944 1245 1945 837 1945 836 1945 1243 1946 838 1946 1276 1946 1276 1947 838 1947 837 1947 1276 1948 837 1948 1277 1948 1277 1949 837 1949 1235 1949 1277 1950 1235 1950 1236 1950 1276 1951 1277 1951 1278 1951 1278 1952 1279 1952 1276 1952 1276 1953 1279 1953 1242 1953 1276 1954 1242 1954 1243 1954 1280 1955 1279 1955 1278 1955 1281 1956 1282 1956 1283 1956 1283 1957 1282 1957 1284 1957 1242 1958 1279 1958 1241 1958 1241 1959 1279 1959 1280 1959 1241 1960 1280 1960 1240 1960 1240 1961 1280 1961 1284 1961 1240 1962 1284 1962 1239 1962 1239 1963 1284 1963 1282 1963 1239 1964 1282 1964 1238 1964 1285 1965 1286 1965 1287 1965 1278 1966 1288 1966 1280 1966 1280 1967 1288 1967 1289 1967 1280 1968 1289 1968 1284 1968 1284 1969 1289 1969 1285 1969 1284 1970 1285 1970 1283 1970 1283 1971 1285 1971 1287 1971 1283 1972 1287 1972 1281 1972 1286 1973 1290 1973 1287 1973 1287 1974 1290 1974 1291 1974 1287 1975 1291 1975 1281 1975 1281 1976 1291 1976 1282 1976 1282 1977 1291 1977 1237 1977 1282 1978 1237 1978 1238 1978 1292 1979 1293 1979 1294 1979 1294 1980 1247 1980 1246 1980 1295 1981 870 1981 885 1981 1294 1982 1246 1982 1292 1982 1292 1983 1246 1983 1295 1983 1292 1984 1295 1984 1296 1984 1296 1985 1295 1985 885 1985 1296 1986 885 1986 887 1986 1297 1987 1298 1987 1299 1987 1300 1988 1301 1988 1302 1988 1300 1989 1302 1989 1303 1989 1303 1990 1302 1990 1304 1990 1303 1991 1304 1991 1305 1991 1305 1992 1304 1992 1306 1992 1305 1993 1306 1993 1299 1993 1299 1994 1306 1994 345 1994 1299 1995 345 1995 1297 1995 613 1996 1307 1996 614 1996 614 1997 1307 1997 1308 1997 614 1998 1308 1998 343 1998 343 1999 1308 1999 1297 1999 343 2000 1297 2000 345 2000 1307 2001 1309 2001 1308 2001 1308 2002 1309 2002 1310 2002 1308 2003 1310 2003 1297 2003 1297 2004 1310 2004 1298 2004 1291 2005 1290 2005 1309 2005 1309 2006 1311 2006 1291 2006 1291 2007 1311 2007 1312 2007 1291 2008 1312 2008 1313 2008 1314 2009 914 2009 920 2009 1314 2010 920 2010 1313 2010 1313 2011 920 2011 919 2011 1313 2012 919 2012 1291 2012 1291 2013 919 2013 918 2013 1291 2014 918 2014 1237 2014 1315 2015 915 2015 914 2015 609 2016 621 2016 915 2016 914 2017 1314 2017 1315 2017 1315 2018 1314 2018 1313 2018 1315 2019 1313 2019 1316 2019 1316 2020 1313 2020 1312 2020 1316 2021 1312 2021 1317 2021 1317 2022 1312 2022 1311 2022 1317 2023 1311 2023 1318 2023 1318 2024 1311 2024 1309 2024 1318 2025 1309 2025 1307 2025 915 2026 1315 2026 609 2026 609 2027 1315 2027 1316 2027 609 2028 1316 2028 610 2028 610 2029 1316 2029 1317 2029 610 2030 1317 2030 611 2030 611 2031 1317 2031 1318 2031 611 2032 1318 2032 612 2032 612 2033 1318 2033 1307 2033 612 2034 1307 2034 613 2034 1293 2035 1319 2035 1294 2035 1294 2036 1319 2036 1320 2036 1294 2037 1320 2037 1247 2037 1321 2038 1253 2038 1322 2038 1322 2039 1253 2039 1323 2039 1323 2040 1253 2040 1320 2040 1320 2041 1253 2041 1248 2041 1320 2042 1248 2042 1247 2042 1253 2043 1321 2043 1324 2043 1325 2044 1267 2044 1326 2044 1326 2045 1267 2045 1262 2045 1326 2046 1262 2046 1260 2046 1324 2047 1327 2047 1253 2047 1253 2048 1327 2048 1326 2048 1253 2049 1326 2049 1259 2049 1259 2050 1326 2050 1260 2050 1328 2051 1275 2051 1329 2051 1329 2052 1275 2052 1271 2052 1329 2053 1271 2053 1325 2053 1325 2054 1271 2054 1267 2054 1330 2055 1331 2055 1332 2055 1330 2056 1332 2056 1333 2056 1333 2057 1332 2057 1334 2057 1333 2058 1334 2058 1335 2058 1236 2059 1272 2059 1277 2059 1277 2060 1272 2060 1273 2060 1277 2061 1273 2061 1278 2061 1273 2062 1274 2062 1278 2062 1278 2063 1274 2063 1275 2063 1278 2064 1275 2064 1330 2064 1330 2065 1275 2065 1328 2065 1330 2066 1328 2066 1331 2066 1278 2067 1330 2067 1336 2067 1278 2068 1336 2068 1288 2068 1288 2069 1336 2069 1337 2069 1288 2070 1337 2070 1289 2070 1289 2071 1337 2071 1338 2071 1289 2072 1338 2072 1285 2072 1285 2073 1338 2073 1339 2073 1285 2074 1339 2074 1286 2074 1299 2075 1290 2075 1305 2075 1305 2076 1290 2076 1286 2076 1305 2077 1286 2077 1303 2077 1340 2078 1339 2078 1341 2078 1341 2079 1339 2079 1342 2079 1340 2077 1343 2077 1339 2077 1339 2080 1343 2080 1344 2080 1339 2081 1344 2081 1286 2081 1286 2082 1344 2082 1300 2082 1286 2083 1300 2083 1303 2083 1299 2084 1298 2084 1290 2084 1290 2085 1298 2085 1310 2085 1290 2086 1310 2086 1309 2086 1345 2087 1346 2087 1342 2087 1342 2088 1346 2088 1347 2088 1342 2089 1347 2089 1341 2089 1300 2090 1344 2090 1301 2090 1301 2091 1344 2091 1348 2091 1349 2092 1350 2092 1351 2092 1351 2093 1350 2093 1352 2093 1351 2094 1352 2094 1353 2094 1301 2095 1348 2095 1354 2095 1354 2096 1348 2096 1350 2096 1354 2097 1350 2097 1355 2097 1355 2098 1350 2098 1349 2098 1353 2099 1356 2099 1351 2099 1351 2100 1356 2100 1357 2100 1351 2101 1357 2101 1358 2101 1358 2102 1357 2102 1359 2102 1357 2103 1360 2103 1359 2103 1359 2104 1360 2104 1361 2104 1359 2105 1361 2105 1362 2105 1362 2106 1361 2106 1363 2106 1361 2107 1364 2107 1363 2107 1363 2108 1364 2108 1365 2108 1363 2109 1365 2109 1366 2109 1366 2110 1365 2110 1367 2110 1367 2111 1368 2111 1366 2111 1366 2112 1368 2112 1369 2112 1366 2113 1369 2113 1370 2113 1306 2114 1304 2114 1371 2114 1302 2115 1301 2115 1354 2115 1372 2116 1373 2116 348 2116 348 2117 347 2117 1372 2117 1372 2118 347 2118 346 2118 1372 2119 346 2119 1371 2119 1371 2120 346 2120 345 2120 1371 2121 345 2121 1306 2121 1349 2122 1373 2122 1355 2122 1355 2123 1373 2123 1372 2123 1355 2124 1372 2124 1354 2124 1354 2125 1372 2125 1371 2125 1354 2126 1371 2126 1302 2126 1302 2127 1371 2127 1304 2127 1374 2128 1335 2128 1375 2128 1375 2129 1335 2129 1376 2129 1375 2130 1376 2130 1377 2130 1377 2131 1376 2131 1378 2131 1379 2132 1380 2132 1381 2132 1379 2133 1381 2133 1382 2133 1382 2134 1381 2134 1383 2134 1382 2135 1383 2135 1384 2135 1384 2136 1383 2136 1385 2136 1384 2137 1385 2137 1386 2137 1386 2138 1385 2138 1387 2138 1387 2139 1385 2139 1388 2139 1387 2140 1388 2140 1389 2140 1389 2141 1388 2141 1390 2141 1390 2142 1388 2142 1391 2142 1390 2143 1391 2143 1392 2143 1381 2144 1380 2144 1393 2144 1394 2145 1395 2145 1396 2145 1395 2146 1397 2146 1398 2146 1399 2147 1394 2147 1400 2147 1400 2148 1394 2148 1396 2148 1400 2149 1396 2149 1377 2149 1377 2150 1396 2150 1375 2150 1395 2151 1398 2151 1396 2151 1396 2152 1398 2152 1374 2152 1396 2153 1374 2153 1375 2153 1391 2154 1401 2154 1392 2154 1402 2155 1403 2155 1404 2155 1404 2156 1403 2156 1405 2156 1404 2157 1405 2157 1406 2157 1407 2158 1322 2158 1323 2158 1322 2159 1407 2159 1321 2159 1321 2160 1407 2160 1408 2160 1321 2161 1408 2161 1409 2161 1402 2162 1409 2162 1403 2162 1403 2163 1409 2163 1408 2163 1403 2164 1408 2164 1405 2164 1405 2165 1408 2165 1407 2165 1405 2166 1407 2166 1410 2166 1410 2167 1407 2167 1323 2167 1411 2168 1409 2168 1412 2168 1412 2169 1409 2169 1402 2169 1411 2170 1413 2170 1409 2170 1409 2171 1413 2171 1414 2171 1409 2172 1414 2172 1321 2172 1415 2173 1327 2173 1324 2173 1412 2174 1416 2174 1411 2174 1411 2175 1416 2175 1417 2175 1411 2176 1417 2176 1413 2176 1413 2177 1417 2177 1415 2177 1413 2178 1415 2178 1414 2178 1414 2179 1415 2179 1324 2179 1414 2180 1324 2180 1321 2180 1325 2181 1326 2181 1418 2181 1377 2182 1378 2182 1418 2182 1418 2183 1378 2183 1419 2183 1419 2184 1420 2184 1418 2184 1418 2185 1420 2185 1421 2185 1418 2186 1421 2186 1325 2186 1416 2187 1377 2187 1417 2187 1417 2188 1377 2188 1418 2188 1417 2189 1418 2189 1415 2189 1415 2190 1418 2190 1326 2190 1415 2191 1326 2191 1327 2191 1376 2192 1335 2192 1334 2192 1378 2193 1376 2193 1422 2193 1376 2194 1334 2194 1422 2194 1422 2195 1334 2195 1332 2195 1422 2196 1332 2196 1423 2196 1423 2197 1332 2197 1331 2197 1423 2198 1331 2198 1424 2198 1424 2199 1331 2199 1328 2199 1424 2200 1328 2200 1329 2200 1378 2201 1422 2201 1419 2201 1419 2202 1422 2202 1423 2202 1419 2203 1423 2203 1420 2203 1420 2204 1423 2204 1424 2204 1420 2205 1424 2205 1421 2205 1421 2206 1424 2206 1329 2206 1421 2207 1329 2207 1325 2207 1425 2208 1333 2208 1335 2208 1335 2209 1374 2209 1425 2209 1425 2210 1374 2210 1398 2210 1425 2211 1398 2211 1397 2211 1333 2212 1425 2212 1426 2212 1426 2213 1425 2213 1393 2213 1426 2214 1393 2214 1380 2214 1426 2215 1380 2215 1379 2215 1379 2216 1427 2216 1426 2216 1426 2217 1427 2217 1330 2217 1426 2218 1330 2218 1333 2218 1428 2219 1429 2219 1430 2219 1431 2220 1432 2220 1382 2220 1390 2221 1433 2221 1389 2221 1389 2222 1433 2222 1429 2222 1389 2223 1429 2223 1387 2223 1387 2224 1429 2224 1428 2224 1387 2225 1428 2225 1386 2225 1386 2226 1428 2226 1431 2226 1386 2227 1431 2227 1384 2227 1384 2228 1431 2228 1382 2228 1336 2229 1330 2229 1427 2229 1379 2230 1382 2230 1427 2230 1427 2231 1382 2231 1432 2231 1427 2232 1432 2232 1336 2232 1336 2233 1432 2233 1431 2233 1336 2234 1431 2234 1337 2234 1337 2235 1431 2235 1428 2235 1337 2236 1428 2236 1338 2236 1338 2237 1428 2237 1430 2237 1338 2238 1430 2238 1339 2238 1390 2239 1392 2239 1433 2239 1433 2240 1392 2240 1434 2240 1433 2241 1434 2241 1429 2241 1429 2242 1434 2242 1430 2242 1430 2243 1434 2243 1342 2243 1430 2244 1342 2244 1339 2244 1320 2245 1319 2245 1435 2245 1435 2246 1436 2246 1437 2246 1323 2247 1320 2247 1410 2247 1410 2248 1320 2248 1435 2248 1410 2249 1435 2249 1438 2249 1438 2250 1435 2250 1437 2250 1438 2251 1437 2251 1406 2251 1439 2252 1440 2252 1441 2252 1442 2253 1439 2253 1443 2253 1383 2254 1381 2254 1444 2254 1444 2255 1381 2255 1445 2255 1444 2256 1445 2256 1446 2256 1446 2257 1445 2257 1447 2257 1446 2258 1447 2258 1448 2258 1448 2259 1447 2259 1449 2259 1448 2260 1450 2260 1451 2260 1452 2261 1388 2261 1385 2261 1448 2262 1451 2262 1446 2262 1446 2263 1451 2263 1452 2263 1446 2264 1452 2264 1444 2264 1444 2265 1452 2265 1385 2265 1444 2266 1385 2266 1383 2266 1439 2267 1441 2267 1443 2267 1443 2268 1441 2268 1453 2268 1443 2269 1453 2269 1454 2269 1454 2270 1453 2270 1455 2270 1454 2271 1455 2271 1456 2271 1456 2272 1457 2272 1454 2272 1454 2273 1457 2273 1450 2273 1454 2274 1450 2274 1443 2274 1443 2275 1450 2275 1448 2275 1443 2276 1448 2276 1442 2276 1442 2277 1448 2277 1449 2277 1391 2278 1388 2278 1458 2278 1458 2279 1388 2279 1452 2279 1458 2280 1452 2280 1459 2280 1459 2281 1452 2281 1451 2281 1459 2282 1451 2282 1460 2282 1460 2283 1451 2283 1450 2283 1460 2284 1450 2284 1461 2284 1461 2285 1450 2285 1457 2285 1425 2286 1397 2286 1462 2286 1445 2287 1381 2287 1393 2287 1463 2288 1464 2288 1439 2288 1439 2289 1464 2289 1465 2289 1439 2290 1465 2290 1440 2290 1393 2291 1425 2291 1445 2291 1445 2292 1425 2292 1462 2292 1445 2293 1462 2293 1447 2293 1447 2294 1462 2294 1466 2294 1447 2295 1466 2295 1449 2295 1449 2296 1466 2296 1467 2296 1449 2297 1467 2297 1442 2297 1442 2298 1467 2298 1468 2298 1442 2299 1468 2299 1439 2299 1439 2300 1468 2300 1469 2300 1439 2301 1469 2301 1463 2301 1470 2302 1471 2302 1472 2302 1394 2303 1399 2303 1473 2303 1394 2304 1473 2304 1395 2304 1474 2305 1470 2305 1475 2305 1475 2306 1470 2306 1472 2306 1475 2307 1472 2307 1476 2307 1476 2308 1472 2308 1477 2308 1476 2309 1477 2309 1478 2309 1478 2310 1477 2310 1479 2310 1478 2311 1479 2311 1480 2311 1480 2312 1479 2312 1481 2312 1480 2313 1481 2313 1473 2313 1473 2314 1481 2314 1482 2314 1473 2315 1482 2315 1395 2315 1397 2316 1395 2316 1462 2316 1462 2317 1395 2317 1482 2317 1462 2318 1482 2318 1466 2318 1466 2319 1482 2319 1481 2319 1466 2320 1481 2320 1467 2320 1467 2321 1481 2321 1479 2321 1467 2322 1479 2322 1468 2322 1468 2323 1479 2323 1477 2323 1468 2324 1477 2324 1469 2324 1469 2325 1477 2325 1472 2325 1469 2326 1472 2326 1463 2326 1463 2327 1472 2327 1471 2327 1400 2328 1377 2328 1416 2328 1400 2329 1416 2329 1399 2329 1399 2330 1416 2330 1483 2330 1399 2331 1483 2331 1473 2331 1473 2332 1483 2332 1484 2332 1473 2333 1484 2333 1480 2333 1480 2334 1484 2334 1485 2334 1480 2335 1485 2335 1478 2335 1478 2336 1485 2336 1486 2336 1478 2337 1486 2337 1476 2337 1476 2338 1486 2338 1487 2338 1476 2339 1487 2339 1475 2339 1475 2340 1487 2340 1488 2340 1475 2341 1488 2341 1474 2341 1474 2342 1488 2342 1489 2342 1474 2343 1489 2343 1490 2343 1490 2344 1489 2344 1491 2344 1490 2345 1491 2345 1492 2345 1493 2346 1494 2346 1489 2346 1489 2347 1494 2347 1495 2347 1489 2348 1495 2348 1491 2348 1496 2349 1497 2349 1493 2349 1493 2350 1498 2350 1496 2350 1496 2351 1498 2351 1499 2351 1496 2352 1499 2352 1500 2352 1500 2353 1499 2353 1501 2353 1500 2354 1501 2354 1502 2354 1502 2355 1501 2355 1503 2355 1502 2356 1503 2356 1504 2356 1504 2357 1503 2357 1505 2357 1504 2358 1505 2358 1506 2358 1506 2359 1505 2359 1507 2359 1506 2360 1507 2360 1508 2360 1508 2361 1507 2361 1509 2361 1508 2362 1509 2362 1510 2362 1510 2363 1509 2363 1404 2363 1510 2364 1404 2364 1406 2364 1402 2365 1483 2365 1412 2365 1412 2366 1483 2366 1416 2366 1493 2367 1489 2367 1498 2367 1498 2368 1489 2368 1488 2368 1498 2369 1488 2369 1499 2369 1499 2370 1488 2370 1487 2370 1499 2371 1487 2371 1501 2371 1501 2372 1487 2372 1486 2372 1501 2373 1486 2373 1503 2373 1503 2374 1486 2374 1485 2374 1503 2375 1485 2375 1505 2375 1505 2376 1485 2376 1484 2376 1505 2377 1484 2377 1507 2377 1507 2378 1484 2378 1483 2378 1507 2379 1483 2379 1509 2379 1509 2380 1483 2380 1402 2380 1509 2381 1402 2381 1404 2381 1437 2382 1436 2382 1511 2382 1510 2383 1406 2383 1437 2383 1497 2384 1496 2384 1512 2384 1512 2385 1496 2385 1500 2385 1512 2386 1500 2386 1502 2386 1511 2387 1513 2387 1502 2387 1502 2388 1513 2388 1514 2388 1502 2389 1514 2389 1512 2389 1502 2390 1504 2390 1511 2390 1511 2391 1504 2391 1506 2391 1511 2392 1506 2392 1437 2392 1437 2393 1506 2393 1508 2393 1437 2394 1508 2394 1510 2394 1341 2395 1347 2395 1515 2395 1348 2396 1344 2396 1343 2396 1348 2397 1343 2397 1516 2397 1516 2398 1343 2398 1340 2398 1516 2399 1340 2399 1517 2399 1517 2400 1340 2400 1341 2400 1517 2401 1341 2401 1518 2401 1518 2402 1341 2402 1515 2402 1518 2403 1515 2403 460 2403 460 2404 1515 2404 454 2404 454 2405 1515 2405 1519 2405 1520 2406 601 2406 1519 2406 1519 2407 601 2407 605 2407 1519 2408 605 2408 454 2408 1345 2409 1520 2409 1346 2409 1346 2410 1520 2410 1519 2410 1346 2411 1519 2411 1347 2411 1347 2412 1519 2412 1515 2412 1345 2413 1342 2413 1521 2413 1521 2414 1342 2414 1434 2414 1521 2415 1434 2415 1522 2415 1522 2416 1434 2416 1523 2416 1392 2417 1401 2417 1434 2417 1434 2418 1401 2418 1524 2418 1434 2419 1524 2419 1523 2419 1523 2420 1524 2420 1525 2420 1523 2421 1525 2421 1526 2421 1526 2422 1525 2422 1527 2422 1528 2423 1529 2423 607 2423 1526 2424 1527 2424 1529 2424 607 2425 606 2425 1528 2425 1528 2426 606 2426 604 2426 1528 2427 604 2427 1530 2427 1530 2428 604 2428 603 2428 1530 2429 603 2429 1531 2429 1531 2430 603 2430 602 2430 1531 2431 602 2431 1532 2431 1532 2432 602 2432 601 2432 1532 2433 601 2433 1520 2433 1529 2434 1528 2434 1526 2434 1526 2435 1528 2435 1530 2435 1526 2436 1530 2436 1523 2436 1523 2437 1530 2437 1531 2437 1523 2438 1531 2438 1522 2438 1522 2439 1531 2439 1532 2439 1522 2440 1532 2440 1521 2440 1521 2441 1532 2441 1520 2441 1521 2442 1520 2442 1345 2442 1533 2443 1534 2443 1535 2443 1401 2444 1391 2444 1458 2444 1529 2445 1527 2445 1536 2445 1536 2446 1527 2446 1525 2446 1401 2447 1458 2447 1524 2447 1537 2448 1538 2448 1535 2448 1535 2449 1538 2449 1539 2449 1535 2450 1539 2450 1533 2450 1525 2451 1524 2451 1536 2451 1536 2452 1524 2452 1458 2452 1536 2453 1458 2453 1540 2453 1540 2454 1458 2454 1459 2454 1540 2455 1459 2455 1541 2455 1541 2456 1459 2456 1460 2456 1541 2457 1460 2457 1542 2457 1542 2458 1460 2458 1461 2458 1542 2459 1461 2459 1535 2459 1535 2460 1461 2460 1457 2460 1535 2461 1457 2461 1537 2461 1537 2462 1457 2462 1456 2462 1535 2463 1534 2463 586 2463 1541 2464 593 2464 1540 2464 1540 2465 593 2465 600 2465 1540 2466 600 2466 1536 2466 1536 2467 600 2467 599 2467 1536 2468 599 2468 1529 2468 1529 2469 599 2469 608 2469 1529 2470 608 2470 607 2470 586 2471 587 2471 1535 2471 1535 2472 587 2472 597 2472 1535 2473 597 2473 1542 2473 1542 2474 597 2474 596 2474 1542 2475 596 2475 1541 2475 1541 2476 596 2476 594 2476 1541 2477 594 2477 593 2477 394 2478 393 2478 1543 2478 1543 2479 393 2479 340 2479 1543 2480 340 2480 1544 2480 1544 2481 340 2481 339 2481 1544 2482 339 2482 348 2482 1362 2483 1363 2483 397 2483 397 2484 396 2484 1362 2484 1362 2485 396 2485 395 2485 1362 2486 395 2486 1359 2486 1359 2487 395 2487 394 2487 1359 2488 394 2488 1358 2488 1358 2489 394 2489 1543 2489 1358 2490 1543 2490 1351 2490 1351 2491 1543 2491 1544 2491 1351 2492 1544 2492 1349 2492 1370 2493 392 2493 1366 2493 1366 2494 392 2494 400 2494 1366 2495 400 2495 1363 2495 1363 2496 400 2496 399 2496 1363 2497 399 2497 397 2497 1369 2498 389 2498 1370 2498 1370 2499 389 2499 391 2499 1370 2500 391 2500 392 2500 1367 2501 422 2501 1368 2501 1368 2502 422 2502 425 2502 1368 2503 425 2503 1369 2503 1369 2504 425 2504 424 2504 1369 2505 424 2505 389 2505 1364 2506 1361 2506 428 2506 428 2507 427 2507 1364 2507 1364 2508 427 2508 426 2508 1364 2509 426 2509 1365 2509 1365 2510 426 2510 421 2510 1365 2511 421 2511 1367 2511 1367 2512 421 2512 420 2512 1367 2513 420 2513 422 2513 1545 2514 458 2514 418 2514 1361 2515 1360 2515 428 2515 428 2516 1360 2516 1545 2516 428 2517 1545 2517 429 2517 429 2518 1545 2518 418 2518 1516 2519 1517 2519 1546 2519 1546 2520 1517 2520 1518 2520 458 2521 1545 2521 459 2521 459 2522 1545 2522 1547 2522 459 2523 1547 2523 462 2523 462 2524 1547 2524 1546 2524 462 2525 1546 2525 461 2525 461 2526 1546 2526 1518 2526 461 2527 1518 2527 460 2527 1348 2528 1516 2528 1350 2528 1350 2529 1516 2529 1546 2529 1350 2530 1546 2530 1352 2530 1352 2531 1546 2531 1547 2531 1360 2532 1357 2532 1545 2532 1545 2533 1357 2533 1356 2533 1545 2534 1356 2534 1547 2534 1547 2535 1356 2535 1353 2535 1547 2536 1353 2536 1352 2536 1548 2537 1549 2537 1550 2537 1550 2538 1549 2538 1551 2538 376 1660 1548 1660 1550 1660 376 2539 1550 2539 377 2539 377 1660 1550 1660 1551 1660 377 1660 1551 1660 390 1660 390 2540 1551 2540 398 2540 398 2541 1551 2541 1549 2541 398 2542 1549 2542 376 2542 376 2543 1549 2543 1548 2543 1552 2544 463 2544 482 2544 1552 2545 482 2545 1553 2545 1553 2546 482 2546 481 2546 1553 2547 481 2547 1554 2547 1554 2548 481 2548 480 2548 1554 2549 480 2549 1555 2549 1555 2550 480 2550 478 2550 1555 2551 478 2551 1556 2551 1556 2552 478 2552 476 2552 1556 2553 476 2553 1557 2553 1557 2554 476 2554 475 2554 1557 2555 475 2555 1558 2555 1558 2556 475 2556 472 2556 1558 2557 472 2557 1559 2557 1559 2558 472 2558 473 2558 1559 2559 473 2559 1560 2559 1560 2560 473 2560 474 2560 1560 2561 474 2561 1561 2561 1561 2562 474 2562 468 2562 1561 2563 468 2563 1562 2563 1562 2564 468 2564 1563 2564 1563 2565 468 2565 467 2565 1563 2566 467 2566 1564 2566 467 2567 471 2567 1564 2567 1564 2568 471 2568 470 2568 1564 2569 470 2569 1565 2569 1565 2570 470 2570 469 2570 1565 2571 469 2571 1566 2571 1566 2572 469 2572 466 2572 1566 2573 466 2573 1567 2573 1567 2574 466 2574 465 2574 1567 2575 465 2575 1568 2575 1568 2576 465 2576 463 2576 1568 2577 463 2577 1552 2577 1552 2578 1553 2578 1554 2578 1556 2579 1557 2579 1563 2579 1563 2580 1557 2580 1558 2580 1561 2581 1562 2581 1560 2581 1560 2582 1562 2582 1563 2582 1560 2583 1563 2583 1559 2583 1559 2584 1563 2584 1558 2584 1563 2585 1564 2585 1569 2585 1569 2586 1564 2586 1565 2586 1565 2587 1566 2587 1569 2587 1569 2588 1566 2588 1567 2588 1569 2589 1567 2589 1568 2589 1568 2590 1552 2590 1569 2590 1569 2591 1552 2591 1554 2591 1569 2592 1554 2592 1563 2592 1563 2593 1554 2593 1555 2593 1563 2594 1555 2594 1556 2594 477 1782 1570 1782 457 1782 457 1782 1570 1782 1571 1782 457 1782 1571 1782 456 1782 1572 2595 419 2595 417 2595 1572 2596 417 2596 1573 2596 1573 2597 417 2597 416 2597 1573 2598 416 2598 1574 2598 416 2599 453 2599 1574 2599 1574 2600 453 2600 452 2600 1574 2601 452 2601 1575 2601 1575 2602 452 2602 456 2602 1575 2603 456 2603 1571 2603 1576 2604 448 2604 446 2604 1576 2605 446 2605 1577 2605 1577 2606 446 2606 414 2606 1577 2606 414 2606 1578 2606 1578 2607 414 2607 415 2607 1578 2608 415 2608 1579 2608 1579 2609 415 2609 419 2609 1579 2610 419 2610 1572 2610 1580 2611 451 2611 1576 2611 1576 2611 451 2611 450 2611 1576 2611 450 2611 448 2611 1581 2612 438 2612 437 2612 1581 2613 437 2613 1582 2613 1582 2614 437 2614 444 2614 1582 2615 444 2615 1583 2615 1583 2616 444 2616 443 2616 1583 2617 443 2617 1584 2617 1584 2618 443 2618 451 2618 1584 2619 451 2619 1580 2619 1570 2620 477 2620 479 2620 441 2621 1585 2621 479 2621 479 2622 1585 2622 1586 2622 479 2623 1586 2623 1570 2623 441 2624 440 2624 1585 2624 1585 2625 440 2625 439 2625 1585 2626 439 2626 1587 2626 1587 2627 439 2627 438 2627 1587 2628 438 2628 1581 2628 1570 2629 1586 2629 1580 2629 1580 2630 1586 2630 1585 2630 1587 2631 1581 2631 1588 2631 1585 2632 1587 2632 1580 2632 1580 2633 1587 2633 1588 2633 1580 2634 1588 2634 1584 2634 1581 2635 1582 2635 1588 2635 1588 2636 1582 2636 1583 2636 1588 2637 1583 2637 1584 2637 1577 2638 1578 2638 1571 2638 1579 2639 1572 2639 1589 2639 1578 2640 1579 2640 1571 2640 1571 2641 1579 2641 1589 2641 1571 2642 1589 2642 1575 2642 1572 2643 1573 2643 1589 2643 1589 2644 1573 2644 1574 2644 1589 2645 1574 2645 1575 2645 1570 2646 1580 2646 1571 2646 1571 2647 1580 2647 1576 2647 1571 2648 1576 2648 1577 2648 1590 1782 447 1782 1591 1782 1591 1782 447 1782 449 1782 1591 1782 449 1782 442 1782 1592 2649 423 2649 413 2649 1592 2650 413 2650 1593 2650 1593 2651 413 2651 412 2651 1593 2652 412 2652 1594 2652 1594 2653 412 2653 445 2653 1594 2654 445 2654 1595 2654 1595 2655 445 2655 447 2655 1595 2656 447 2656 1590 2656 1596 2657 384 2657 380 2657 1596 2658 380 2658 1597 2658 1597 2659 380 2659 379 2659 1597 2660 379 2660 1598 2660 1598 2661 379 2661 378 2661 1598 2662 378 2662 1599 2662 1599 2663 378 2663 423 2663 1599 2664 423 2664 1592 2664 384 2611 1596 2611 410 2611 410 2611 1596 2611 1600 2611 410 2611 1600 2611 411 2611 1601 2665 432 2665 431 2665 1601 2666 431 2666 1602 2666 1602 2667 431 2667 430 2667 1602 2668 430 2668 1603 2668 1603 2669 430 2669 407 2669 1603 2670 407 2670 1604 2670 1604 2671 407 2671 411 2671 1604 2672 411 2672 1600 2672 1591 2673 442 2673 436 2673 1591 2674 436 2674 1605 2674 1605 2675 436 2675 435 2675 1605 2676 435 2676 1606 2676 1606 2677 435 2677 434 2677 1606 2678 434 2678 1607 2678 1607 2679 434 2679 432 2679 1607 2680 432 2680 1601 2680 1590 2681 1596 2681 1597 2681 1593 2682 1594 2682 1592 2682 1592 2683 1594 2683 1595 2683 1592 2684 1595 2684 1599 2684 1599 2685 1595 2685 1590 2685 1599 2686 1590 2686 1598 2686 1598 2687 1590 2687 1597 2687 1602 2688 1603 2688 1601 2688 1601 2689 1603 2689 1604 2689 1601 2690 1604 2690 1607 2690 1607 2691 1604 2691 1600 2691 1607 2692 1600 2692 1606 2692 1606 2693 1600 2693 1605 2693 1596 1695 1590 1695 1600 1695 1600 1695 1590 1695 1591 1695 1600 2694 1591 2694 1605 2694 408 1782 1608 1782 409 1782 409 1782 1608 1782 1609 1782 409 1782 1609 1782 385 1782 1610 2695 386 2695 382 2695 1610 2696 382 2696 1611 2696 1611 2697 382 2697 381 2697 1611 2698 381 2698 1612 2698 1612 2699 381 2699 383 2699 1612 2700 383 2700 1613 2700 1613 2701 383 2701 385 2701 1613 2702 385 2702 1609 2702 1614 2703 372 2703 374 2703 375 2704 1615 2704 374 2704 374 2705 1615 2705 1616 2705 374 2706 1616 2706 1614 2706 375 2707 388 2707 1615 2707 1615 2708 388 2708 387 2708 1615 2709 387 2709 1617 2709 1617 2710 387 2710 386 2710 1617 2711 386 2711 1610 2711 1618 2611 367 2611 1614 2611 1614 2611 367 2611 366 2611 1614 2611 366 2611 372 2611 1619 2712 402 2712 401 2712 1619 2713 401 2713 1620 2713 1620 2714 401 2714 361 2714 1620 2715 361 2715 1621 2715 361 2716 369 2716 1621 2716 1621 2717 369 2717 368 2717 1621 2718 368 2718 1622 2718 1622 2719 368 2719 367 2719 1622 2720 367 2720 1618 2720 1608 2721 408 2721 406 2721 1608 2722 406 2722 1623 2722 1623 2723 406 2723 405 2723 1623 2723 405 2723 1624 2723 1624 2724 405 2724 404 2724 1624 2725 404 2725 1625 2725 1625 2726 404 2726 402 2726 1625 2727 402 2727 1619 2727 1614 2728 1616 2728 1609 2728 1609 2729 1616 2729 1615 2729 1617 2730 1610 2730 1626 2730 1615 2731 1617 2731 1609 2731 1609 2732 1617 2732 1626 2732 1609 2733 1626 2733 1613 2733 1610 2734 1611 2734 1626 2734 1626 2735 1611 2735 1612 2735 1626 2736 1612 2736 1613 2736 1623 2737 1624 2737 1618 2737 1625 2738 1619 2738 1627 2738 1624 2739 1625 2739 1618 2739 1618 2740 1625 2740 1627 2740 1618 2741 1627 2741 1622 2741 1619 2742 1620 2742 1627 2742 1627 2743 1620 2743 1621 2743 1627 2744 1621 2744 1622 2744 1614 2745 1609 2745 1618 2745 1618 2746 1609 2746 1608 2746 1618 2747 1608 2747 1623 2747 364 1782 1628 1782 365 1782 365 1782 1628 1782 1629 1782 365 1782 1629 1782 370 1782 1630 2748 338 2748 341 2748 1630 2749 341 2749 1631 2749 1631 2750 341 2750 373 2750 1631 2751 373 2751 1632 2751 1632 2752 373 2752 371 2752 1632 2753 371 2753 1633 2753 1633 2754 371 2754 370 2754 1633 2755 370 2755 1629 2755 1634 2756 354 2756 353 2756 1634 2757 353 2757 1635 2757 1635 2758 353 2758 342 2758 1635 2759 342 2759 1636 2759 1636 2760 342 2760 344 2760 1636 2761 344 2761 1637 2761 1637 2762 344 2762 338 2762 1637 2763 338 2763 1630 2763 354 2611 1634 2611 356 2611 356 2611 1634 2611 1638 2611 356 2611 1638 2611 352 2611 1639 2764 358 2764 357 2764 1639 2765 357 2765 1640 2765 1640 2766 357 2766 350 2766 1640 2767 350 2767 1641 2767 1641 2768 350 2768 349 2768 1641 2769 349 2769 1642 2769 1642 2770 349 2770 352 2770 1642 2771 352 2771 1638 2771 1628 2772 364 2772 360 2772 1628 2773 360 2773 1643 2773 1643 2774 360 2774 362 2774 1643 2775 362 2775 1644 2775 1644 2776 362 2776 363 2776 1644 2777 363 2777 1645 2777 1645 2778 363 2778 358 2778 1645 2779 358 2779 1639 2779 1634 2780 1635 2780 1629 2780 1629 2781 1635 2781 1636 2781 1637 2782 1630 2782 1646 2782 1636 2783 1637 2783 1629 2783 1629 2784 1637 2784 1646 2784 1629 2785 1646 2785 1633 2785 1630 2786 1631 2786 1646 2786 1646 2787 1631 2787 1632 2787 1646 2788 1632 2788 1633 2788 1643 2789 1644 2789 1638 2789 1638 2790 1644 2790 1645 2790 1638 2791 1645 2791 1647 2791 1647 2792 1645 2792 1639 2792 1639 2793 1640 2793 1647 2793 1647 2794 1640 2794 1641 2794 1647 2795 1641 2795 1638 2795 1638 2796 1641 2796 1642 2796 1634 2797 1629 2797 1638 2797 1638 2798 1629 2798 1628 2798 1638 2799 1628 2799 1643 2799 1648 2800 1649 2800 1650 2800 1650 2801 1649 2801 1651 2801 1650 2802 1651 2802 1652 2802 1652 2803 1651 2803 1653 2803 1654 2804 1655 2804 1656 2804 1656 2805 1655 2805 1657 2805 1656 2806 1657 2806 1658 2806 1658 2807 1657 2807 1659 2807 1658 2808 1659 2808 1660 2808 1660 2809 1659 2809 1661 2809 1660 2810 1661 2810 1662 2810 1662 2811 1661 2811 1663 2811 1663 2812 1661 2812 1664 2812 1663 2813 1664 2813 1665 2813 1666 2814 1665 2814 1664 2814 1667 2815 1668 2815 1669 2815 1670 2816 1671 2816 1672 2816 1672 2817 1671 2817 1673 2817 1669 2818 1648 2818 1650 2818 1652 2819 1673 2819 1650 2819 1650 2820 1673 2820 1671 2820 1650 2821 1671 2821 1669 2821 1669 2822 1671 2822 1670 2822 1669 2823 1670 2823 1667 2823 1654 2824 1674 2824 1655 2824 1675 2825 1676 2825 1677 2825 1678 2826 1679 2826 1680 2826 1680 2827 1679 2827 1681 2827 1678 2828 1682 2828 1679 2828 1679 2829 1682 2829 1683 2829 1679 2830 1683 2830 1684 2830 1680 2831 1685 2831 1678 2831 1678 2832 1685 2832 1686 2832 1678 2833 1686 2833 1682 2833 1682 2834 1686 2834 1675 2834 1682 2835 1675 2835 1683 2835 1683 2836 1675 2836 1677 2836 1683 2837 1677 2837 1684 2837 1687 2838 1679 2838 1684 2838 1688 2839 1689 2839 1690 2839 1690 2840 1689 2840 1691 2840 1687 2841 1684 2841 1692 2841 1692 2842 1684 2842 1693 2842 1692 2843 1693 2843 1694 2843 1694 2844 1695 2844 1692 2844 1692 2845 1695 2845 1689 2845 1692 2846 1689 2846 1687 2846 1687 2847 1689 2847 1688 2847 1687 2848 1688 2848 1679 2848 1679 2849 1688 2849 1690 2849 1679 2850 1690 2850 1681 2850 1695 2851 1694 2851 1696 2851 1697 2852 1649 2852 1689 2852 1689 2853 1649 2853 1648 2853 1689 2854 1648 2854 1691 2854 1698 2855 1699 2855 1697 2855 1697 2856 1699 2856 1700 2856 1697 2857 1700 2857 1649 2857 1689 2858 1695 2858 1697 2858 1697 2859 1695 2859 1696 2859 1697 2860 1696 2860 1698 2860 1698 2861 1696 2861 1701 2861 1651 2862 1649 2862 1700 2862 1653 2863 1651 2863 1702 2863 1651 2864 1700 2864 1702 2864 1702 2865 1700 2865 1699 2865 1702 2866 1699 2866 1703 2866 1703 2867 1699 2867 1698 2867 1703 2868 1698 2868 1704 2868 1704 2869 1698 2869 1701 2869 1704 2870 1701 2870 1705 2870 1653 2871 1702 2871 1706 2871 1706 2872 1702 2872 1703 2872 1706 2873 1703 2873 1707 2873 1707 2874 1703 2874 1704 2874 1707 2875 1704 2875 1708 2875 1708 2876 1704 2876 1705 2876 1708 2877 1705 2877 1709 2877 1652 2878 1710 2878 1673 2878 1673 2879 1710 2879 1672 2879 1665 2880 1666 2880 1711 2880 1711 2881 1666 2881 1710 2881 1711 2882 1710 2882 1712 2882 1712 2883 1710 2883 1652 2883 1712 2884 1652 2884 1653 2884 1711 2885 1712 2885 1713 2885 1713 2886 1714 2886 1711 2886 1711 2887 1714 2887 1663 2887 1711 2888 1663 2888 1665 2888 1715 2889 1714 2889 1713 2889 1716 2890 1717 2890 1718 2890 1718 2891 1717 2891 1719 2891 1663 2892 1714 2892 1662 2892 1662 2893 1714 2893 1715 2893 1662 2894 1715 2894 1660 2894 1660 2895 1715 2895 1719 2895 1660 2896 1719 2896 1658 2896 1658 2897 1719 2897 1717 2897 1658 2898 1717 2898 1656 2898 1720 2899 1721 2899 1722 2899 1713 2900 1723 2900 1715 2900 1715 2901 1723 2901 1724 2901 1715 2902 1724 2902 1719 2902 1719 2903 1724 2903 1720 2903 1719 2904 1720 2904 1718 2904 1718 2905 1720 2905 1722 2905 1718 2906 1722 2906 1716 2906 1721 2907 1725 2907 1722 2907 1722 2908 1725 2908 1726 2908 1722 2909 1726 2909 1716 2909 1716 2910 1726 2910 1717 2910 1717 2911 1726 2911 1654 2911 1717 2912 1654 2912 1656 2912 1727 2913 1728 2913 1729 2913 1729 2914 1676 2914 1675 2914 1730 2915 1685 2915 1731 2915 1729 2916 1675 2916 1727 2916 1727 2917 1675 2917 1730 2917 1727 2918 1730 2918 1732 2918 1732 2919 1730 2919 1731 2919 1732 2920 1731 2920 1733 2920 1734 2921 1664 2921 1661 2921 1735 2922 1734 2922 1736 2922 1737 2923 1738 2923 1739 2923 1740 2924 1741 2924 1742 2924 1742 2925 1741 2925 1743 2925 1742 2926 1743 2926 1738 2926 1738 2927 1743 2927 1744 2927 1738 2928 1744 2928 1739 2928 1737 2929 1745 2929 1746 2929 1747 2930 1748 2930 1749 2930 1737 2931 1746 2931 1738 2931 1738 2932 1746 2932 1747 2932 1738 2933 1747 2933 1742 2933 1742 2934 1747 2934 1749 2934 1742 2935 1749 2935 1740 2935 1734 2936 1661 2936 1736 2936 1736 2937 1661 2937 1659 2937 1736 2938 1659 2938 1750 2938 1750 2939 1659 2939 1657 2939 1750 2940 1657 2940 1655 2940 1655 2941 1751 2941 1750 2941 1750 2942 1751 2942 1745 2942 1750 2943 1745 2943 1736 2943 1736 2944 1745 2944 1737 2944 1736 2945 1737 2945 1735 2945 1735 2946 1737 2946 1739 2946 1752 2947 1748 2947 1753 2947 1753 2948 1748 2948 1747 2948 1753 2949 1747 2949 1754 2949 1754 2950 1747 2950 1746 2950 1754 2951 1746 2951 1755 2951 1755 2952 1746 2952 1745 2952 1755 2953 1745 2953 1756 2953 1756 2954 1745 2954 1751 2954 1757 2955 1758 2955 1759 2955 1743 2956 1741 2956 1760 2956 1672 2957 1710 2957 1734 2957 1734 2958 1710 2958 1666 2958 1734 2959 1666 2959 1664 2959 1760 2960 1757 2960 1743 2960 1743 2961 1757 2961 1759 2961 1743 2962 1759 2962 1744 2962 1744 2963 1759 2963 1761 2963 1744 2964 1761 2964 1739 2964 1739 2965 1761 2965 1762 2965 1739 2966 1762 2966 1735 2966 1735 2967 1762 2967 1763 2967 1735 2968 1763 2968 1734 2968 1734 2969 1763 2969 1764 2969 1734 2970 1764 2970 1672 2970 1667 2971 1670 2971 1765 2971 1766 2972 1767 2972 1768 2972 1766 2973 1768 2973 1769 2973 1668 2974 1667 2974 1770 2974 1770 2975 1667 2975 1765 2975 1770 2976 1765 2976 1771 2976 1771 2977 1765 2977 1772 2977 1771 2978 1772 2978 1773 2978 1773 2979 1772 2979 1774 2979 1773 2980 1774 2980 1775 2980 1775 2981 1774 2981 1776 2981 1775 2982 1776 2982 1768 2982 1768 2983 1776 2983 1777 2983 1768 2984 1777 2984 1769 2984 1758 2985 1769 2985 1759 2985 1759 2986 1769 2986 1777 2986 1759 2987 1777 2987 1761 2987 1761 2988 1777 2988 1776 2988 1761 2989 1776 2989 1762 2989 1762 2990 1776 2990 1774 2990 1762 2991 1774 2991 1763 2991 1763 2992 1774 2992 1772 2992 1763 2993 1772 2993 1764 2993 1764 2994 1772 2994 1765 2994 1764 2995 1765 2995 1672 2995 1672 2996 1765 2996 1670 2996 1778 2997 1779 2997 1780 2997 1778 2998 1780 2998 1767 2998 1767 2999 1780 2999 1781 2999 1767 3000 1781 3000 1768 3000 1768 3001 1781 3001 1782 3001 1768 3002 1782 3002 1775 3002 1775 3003 1782 3003 1783 3003 1775 3004 1783 3004 1773 3004 1773 3005 1783 3005 1784 3005 1773 3006 1784 3006 1771 3006 1771 3007 1784 3007 1785 3007 1771 3008 1785 3008 1770 3008 1770 3009 1785 3009 1786 3009 1770 3010 1786 3010 1668 3010 1668 3011 1786 3011 1787 3011 1668 3012 1787 3012 1669 3012 1669 3013 1787 3013 1691 3013 1669 3014 1691 3014 1648 3014 1680 3015 1681 3015 1787 3015 1787 3016 1681 3016 1690 3016 1787 3017 1690 3017 1691 3017 1788 3018 1685 3018 1680 3018 1680 3019 1789 3019 1788 3019 1788 3020 1789 3020 1790 3020 1788 3021 1790 3021 1791 3021 1791 3022 1790 3022 1792 3022 1791 3023 1792 3023 1793 3023 1793 3024 1792 3024 1794 3024 1793 3025 1794 3025 1795 3025 1795 3026 1794 3026 1796 3026 1795 3027 1796 3027 1797 3027 1797 3028 1796 3028 1798 3028 1797 3029 1798 3029 1799 3029 1799 3030 1798 3030 1800 3030 1799 3031 1800 3031 1801 3031 1801 3032 1800 3032 1802 3032 1801 3033 1802 3033 1803 3033 1804 3034 1781 3034 1805 3034 1805 3035 1781 3035 1780 3035 1680 3036 1787 3036 1789 3036 1789 3037 1787 3037 1786 3037 1789 3038 1786 3038 1790 3038 1790 3039 1786 3039 1785 3039 1790 3040 1785 3040 1792 3040 1792 3041 1785 3041 1784 3041 1792 3042 1784 3042 1794 3042 1794 3043 1784 3043 1783 3043 1794 3044 1783 3044 1796 3044 1796 3045 1783 3045 1782 3045 1796 3046 1782 3046 1798 3046 1798 3047 1782 3047 1781 3047 1798 3048 1781 3048 1800 3048 1800 3049 1781 3049 1804 3049 1800 3050 1804 3050 1802 3050 1806 3051 1807 3051 1808 3051 1801 3052 1803 3052 1806 3052 1801 3053 1806 3053 1799 3053 1685 3054 1788 3054 1731 3054 1731 3055 1788 3055 1791 3055 1731 3056 1791 3056 1793 3056 1799 3057 1806 3057 1797 3057 1797 3058 1806 3058 1808 3058 1797 3059 1808 3059 1795 3059 1795 3060 1808 3060 1809 3060 1795 3061 1809 3061 1793 3061 1793 3062 1809 3062 1733 3062 1793 3063 1733 3063 1731 3063 1810 3064 1811 3064 1812 3064 1813 3065 1814 3065 1815 3065 1813 3066 1815 3066 1816 3066 1816 3067 1815 3067 1817 3067 1816 3068 1817 3068 1818 3068 1818 3069 1817 3069 1819 3069 1818 3070 1819 3070 1812 3070 1812 3071 1819 3071 200 3071 1812 3072 200 3072 1810 3072 566 3073 1820 3073 567 3073 567 3074 1820 3074 1821 3074 567 3075 1821 3075 198 3075 198 3076 1821 3076 1810 3076 198 3077 1810 3077 200 3077 1820 3078 1822 3078 1821 3078 1821 3079 1822 3079 1823 3079 1821 3080 1823 3080 1810 3080 1810 3081 1823 3081 1811 3081 1726 3082 1725 3082 1822 3082 1822 3083 1824 3083 1726 3083 1726 3084 1824 3084 1825 3084 1726 3085 1825 3085 1826 3085 1827 3086 1828 3086 1829 3086 1827 3087 1829 3087 1826 3087 1826 3088 1829 3088 1830 3088 1826 3089 1830 3089 1726 3089 1726 3090 1830 3090 1674 3090 1726 3091 1674 3091 1654 3091 1831 3092 1832 3092 1828 3092 562 3093 561 3093 1832 3093 1828 3094 1827 3094 1831 3094 1831 3095 1827 3095 1826 3095 1831 3096 1826 3096 1833 3096 1833 3097 1826 3097 1825 3097 1833 3098 1825 3098 1834 3098 1834 3099 1825 3099 1824 3099 1834 3100 1824 3100 1835 3100 1835 3101 1824 3101 1822 3101 1835 3102 1822 3102 1820 3102 1832 3103 1831 3103 562 3103 562 3104 1831 3104 1833 3104 562 3105 1833 3105 563 3105 563 3106 1833 3106 1834 3106 563 3107 1834 3107 564 3107 564 3108 1834 3108 1835 3108 564 3109 1835 3109 565 3109 565 3110 1835 3110 1820 3110 565 3111 1820 3111 566 3111 1836 3112 1752 3112 1753 3112 1828 3113 1832 3113 1837 3113 1674 3114 1830 3114 1837 3114 1837 3115 1830 3115 1829 3115 1837 3116 1829 3116 1828 3116 1838 3117 1839 3117 1840 3117 1840 3118 1839 3118 1841 3118 1836 3119 1753 3119 1842 3119 1841 3120 1842 3120 1840 3120 1840 3121 1842 3121 1753 3121 1840 3122 1753 3122 1843 3122 1843 3123 1753 3123 1754 3123 1843 3124 1754 3124 1844 3124 1844 3125 1754 3125 1755 3125 1844 3126 1755 3126 1845 3126 1845 3127 1755 3127 1756 3127 1845 3128 1756 3128 1837 3128 1837 3129 1756 3129 1751 3129 1837 3130 1751 3130 1674 3130 1674 3131 1751 3131 1655 3131 1728 3132 1846 3132 1729 3132 1729 3133 1846 3133 1847 3133 1729 3134 1847 3134 1676 3134 1848 3135 1684 3135 1849 3135 1849 3136 1684 3136 1850 3136 1850 3137 1684 3137 1847 3137 1847 3138 1684 3138 1677 3138 1847 3139 1677 3139 1676 3139 1684 3140 1848 3140 1851 3140 1852 3141 1701 3141 1853 3141 1853 3142 1701 3142 1696 3142 1853 3143 1696 3143 1694 3143 1851 3144 1854 3144 1684 3144 1684 3145 1854 3145 1853 3145 1684 3146 1853 3146 1693 3146 1693 3147 1853 3147 1694 3147 1855 3148 1709 3148 1856 3148 1856 3149 1709 3149 1705 3149 1856 3150 1705 3150 1852 3150 1852 3151 1705 3151 1701 3151 1857 3152 1858 3152 1859 3152 1857 3153 1859 3153 1860 3153 1860 3154 1859 3154 1861 3154 1860 3155 1861 3155 1862 3155 1653 3156 1706 3156 1712 3156 1712 3157 1706 3157 1707 3157 1712 3158 1707 3158 1713 3158 1707 3159 1708 3159 1713 3159 1713 3160 1708 3160 1709 3160 1713 3161 1709 3161 1857 3161 1857 3162 1709 3162 1855 3162 1857 3163 1855 3163 1858 3163 1713 3164 1857 3164 1863 3164 1713 3165 1863 3165 1723 3165 1723 3166 1863 3166 1864 3166 1723 3167 1864 3167 1724 3167 1724 3168 1864 3168 1865 3168 1724 3169 1865 3169 1720 3169 1720 3170 1865 3170 1866 3170 1720 3171 1866 3171 1721 3171 1812 3172 1725 3172 1818 3172 1818 3173 1725 3173 1721 3173 1818 3174 1721 3174 1816 3174 1867 3175 1866 3175 1868 3175 1868 3176 1866 3176 1869 3176 1867 3174 1870 3174 1866 3174 1866 3177 1870 3177 1871 3177 1866 3178 1871 3178 1721 3178 1721 3179 1871 3179 1813 3179 1721 3180 1813 3180 1816 3180 1812 3181 1811 3181 1725 3181 1725 3182 1811 3182 1823 3182 1725 3183 1823 3183 1822 3183 1872 3184 1873 3184 1869 3184 1869 3185 1873 3185 1874 3185 1869 3186 1874 3186 1868 3186 1813 3187 1871 3187 1814 3187 1814 3188 1871 3188 1875 3188 1876 3189 1877 3189 1878 3189 1878 3190 1877 3190 1879 3190 1878 3191 1879 3191 1880 3191 1814 3192 1875 3192 1881 3192 1881 3193 1875 3193 1877 3193 1881 3194 1877 3194 1882 3194 1882 3195 1877 3195 1876 3195 1880 3196 1883 3196 1878 3196 1878 3197 1883 3197 1884 3197 1878 3198 1884 3198 1885 3198 1885 3199 1884 3199 1886 3199 1884 3200 1887 3200 1886 3200 1886 3201 1887 3201 1888 3201 1886 3202 1888 3202 1889 3202 1889 3203 1888 3203 1890 3203 1888 3204 1891 3204 1890 3204 1890 3205 1891 3205 1892 3205 1890 3206 1892 3206 1893 3206 1893 3207 1892 3207 1894 3207 1894 3208 1895 3208 1893 3208 1893 3209 1895 3209 1896 3209 1893 3210 1896 3210 1897 3210 580 3211 1838 3211 581 3211 581 3212 1838 3212 1840 3212 581 3213 1840 3213 582 3213 582 3214 1840 3214 573 3214 573 3215 1840 3215 1843 3215 573 3216 1843 3216 571 3216 571 3217 1843 3217 1844 3217 571 3218 1844 3218 570 3218 570 3219 1844 3219 1845 3219 570 3220 1845 3220 568 3220 568 3221 1845 3221 0 3221 0 3222 1845 3222 1837 3222 0 3223 1837 3223 1 3223 1 3224 1837 3224 1832 3224 1 3225 1832 3225 561 3225 1819 3226 1817 3226 1898 3226 1815 3227 1814 3227 1881 3227 1899 3228 1900 3228 203 3228 203 3229 202 3229 1899 3229 1899 3230 202 3230 201 3230 1899 3231 201 3231 1898 3231 1898 3232 201 3232 200 3232 1898 3233 200 3233 1819 3233 1876 3234 1900 3234 1882 3234 1882 3235 1900 3235 1899 3235 1882 3236 1899 3236 1881 3236 1881 3237 1899 3237 1898 3237 1881 3238 1898 3238 1815 3238 1815 3239 1898 3239 1817 3239 1901 3240 1862 3240 1902 3240 1902 3241 1862 3241 1903 3241 1902 3242 1903 3242 1088 3242 1088 3243 1903 3243 1904 3243 1905 3244 1906 3244 1047 3244 1905 3245 1047 3245 1907 3245 1907 3246 1047 3246 1046 3246 1907 3247 1046 3247 1908 3247 1908 3248 1046 3248 1058 3248 1908 3249 1058 3249 1909 3249 1909 3250 1058 3250 1910 3250 1910 3251 1058 3251 1057 3251 1910 3252 1057 3252 1911 3252 1911 3253 1057 3253 1912 3253 1912 3254 1057 3254 1061 3254 1912 3255 1061 3255 1913 3255 1047 3256 1906 3256 1069 3256 1074 3257 1078 3257 1914 3257 1078 3258 1067 3258 1915 3258 1075 3259 1074 3259 1087 3259 1087 3260 1074 3260 1914 3260 1087 3261 1914 3261 1088 3261 1088 3262 1914 3262 1902 3262 1078 3263 1915 3263 1914 3263 1914 3264 1915 3264 1901 3264 1914 3265 1901 3265 1902 3265 1061 3266 1137 3266 1913 3266 1113 3267 1916 3267 1111 3267 1111 3268 1916 3268 1917 3268 1111 3269 1917 3269 1112 3269 1918 3270 1849 3270 1850 3270 1849 3271 1918 3271 1848 3271 1848 3272 1918 3272 1919 3272 1848 3273 1919 3273 1920 3273 1113 3274 1920 3274 1916 3274 1916 3275 1920 3275 1919 3275 1916 3276 1919 3276 1917 3276 1917 3277 1919 3277 1918 3277 1917 3278 1918 3278 1921 3278 1921 3279 1918 3279 1850 3279 1922 3280 1920 3280 1114 3280 1114 3281 1920 3281 1113 3281 1922 3282 1923 3282 1920 3282 1920 3283 1923 3283 1924 3283 1920 3284 1924 3284 1848 3284 1925 3285 1854 3285 1851 3285 1114 3286 1089 3286 1922 3286 1922 3287 1089 3287 1926 3287 1922 3288 1926 3288 1923 3288 1923 3289 1926 3289 1925 3289 1923 3290 1925 3290 1924 3290 1924 3291 1925 3291 1851 3291 1924 3292 1851 3292 1848 3292 1852 3293 1853 3293 1927 3293 1088 3294 1904 3294 1927 3294 1927 3295 1904 3295 1928 3295 1928 3296 1929 3296 1927 3296 1927 3297 1929 3297 1930 3297 1927 3298 1930 3298 1852 3298 1089 3299 1088 3299 1926 3299 1926 3300 1088 3300 1927 3300 1926 3301 1927 3301 1925 3301 1925 3302 1927 3302 1853 3302 1925 3303 1853 3303 1854 3303 1903 3304 1862 3304 1861 3304 1904 3305 1903 3305 1931 3305 1903 3306 1861 3306 1931 3306 1931 3307 1861 3307 1859 3307 1931 3308 1859 3308 1932 3308 1932 3309 1859 3309 1858 3309 1932 3310 1858 3310 1933 3310 1933 3311 1858 3311 1855 3311 1933 3312 1855 3312 1856 3312 1904 3313 1931 3313 1928 3313 1928 3314 1931 3314 1932 3314 1928 3315 1932 3315 1929 3315 1929 3316 1932 3316 1933 3316 1929 3317 1933 3317 1930 3317 1930 3318 1933 3318 1856 3318 1930 3319 1856 3319 1852 3319 1066 3320 1860 3320 1862 3320 1862 3321 1901 3321 1066 3321 1066 3322 1901 3322 1915 3322 1066 3323 1915 3323 1067 3323 1860 3324 1066 3324 1934 3324 1934 3325 1066 3325 1069 3325 1934 3326 1069 3326 1906 3326 1934 3327 1906 3327 1905 3327 1905 3328 1935 3328 1934 3328 1934 3329 1935 3329 1857 3329 1934 3330 1857 3330 1860 3330 1936 3331 1937 3331 1938 3331 1939 3332 1940 3332 1907 3332 1912 3333 1941 3333 1911 3333 1911 3334 1941 3334 1937 3334 1911 3335 1937 3335 1910 3335 1910 3336 1937 3336 1936 3336 1910 3337 1936 3337 1909 3337 1909 3338 1936 3338 1939 3338 1909 3339 1939 3339 1908 3339 1908 3340 1939 3340 1907 3340 1863 3341 1857 3341 1935 3341 1905 3342 1907 3342 1935 3342 1935 3343 1907 3343 1940 3343 1935 3344 1940 3344 1863 3344 1863 3345 1940 3345 1939 3345 1863 3346 1939 3346 1864 3346 1864 3347 1939 3347 1936 3347 1864 3348 1936 3348 1865 3348 1865 3349 1936 3349 1938 3349 1865 3350 1938 3350 1866 3350 1912 3351 1913 3351 1941 3351 1941 3352 1913 3352 1942 3352 1941 3353 1942 3353 1937 3353 1937 3354 1942 3354 1938 3354 1938 3355 1942 3355 1869 3355 1938 3356 1869 3356 1866 3356 1847 3357 1846 3357 1943 3357 1943 3358 1116 3358 1115 3358 1850 3359 1847 3359 1921 3359 1921 3360 1847 3360 1943 3360 1921 3361 1943 3361 1944 3361 1944 3362 1943 3362 1115 3362 1944 3363 1115 3363 1112 3363 1868 3364 1874 3364 1945 3364 1875 3365 1871 3365 1870 3365 1875 3366 1870 3366 1946 3366 1946 3367 1870 3367 1867 3367 1946 3368 1867 3368 1947 3368 1947 3369 1867 3369 1868 3369 1947 3370 1868 3370 1948 3370 1948 3371 1868 3371 1945 3371 1948 3372 1945 3372 315 3372 315 3373 1945 3373 309 3373 309 3374 1945 3374 1949 3374 1950 3375 553 3375 1949 3375 1949 3376 553 3376 557 3376 1949 3377 557 3377 309 3377 1872 3378 1950 3378 1873 3378 1873 3379 1950 3379 1949 3379 1873 3380 1949 3380 1874 3380 1874 3381 1949 3381 1945 3381 1872 3382 1869 3382 1951 3382 1951 3383 1869 3383 1942 3383 1951 3384 1942 3384 1952 3384 1952 3385 1942 3385 1953 3385 1913 3386 1137 3386 1942 3386 1942 3387 1137 3387 1143 3387 1942 3388 1143 3388 1953 3388 1953 3389 1143 3389 1142 3389 1953 3390 1142 3390 1954 3390 1954 3391 1142 3391 1140 3391 1955 3392 1139 3392 559 3392 1954 3393 1140 3393 1139 3393 559 3394 558 3394 1955 3394 1955 3395 558 3395 556 3395 1955 3396 556 3396 1956 3396 1956 3397 556 3397 555 3397 1956 3398 555 3398 1957 3398 1957 3399 555 3399 554 3399 1957 3400 554 3400 1958 3400 1958 3401 554 3401 553 3401 1958 3402 553 3402 1950 3402 1139 3403 1955 3403 1954 3403 1954 3404 1955 3404 1956 3404 1954 3405 1956 3405 1953 3405 1953 3406 1956 3406 1957 3406 1953 3407 1957 3407 1952 3407 1952 3408 1957 3408 1958 3408 1952 3409 1958 3409 1951 3409 1951 3410 1958 3410 1950 3410 1951 3411 1950 3411 1872 3411 249 3412 248 3412 1959 3412 1959 3413 248 3413 195 3413 1959 3414 195 3414 1960 3414 1960 3415 195 3415 194 3415 1960 3416 194 3416 203 3416 1889 3417 1890 3417 252 3417 252 3418 251 3418 1889 3418 1889 3419 251 3419 250 3419 1889 3420 250 3420 1886 3420 1886 3421 250 3421 249 3421 1886 3422 249 3422 1885 3422 1885 3423 249 3423 1959 3423 1885 3424 1959 3424 1878 3424 1878 3425 1959 3425 1960 3425 1878 3426 1960 3426 1876 3426 1897 3427 247 3427 1893 3427 1893 3428 247 3428 255 3428 1893 3429 255 3429 1890 3429 1890 3430 255 3430 254 3430 1890 3431 254 3431 252 3431 1896 3432 244 3432 1897 3432 1897 3433 244 3433 246 3433 1897 3434 246 3434 247 3434 1894 3435 277 3435 1895 3435 1895 3436 277 3436 280 3436 1895 3437 280 3437 1896 3437 1896 3438 280 3438 279 3438 1896 3439 279 3439 244 3439 1891 3440 1888 3440 283 3440 283 3441 282 3441 1891 3441 1891 3442 282 3442 281 3442 1891 3443 281 3443 1892 3443 1892 3444 281 3444 276 3444 1892 3445 276 3445 1894 3445 1894 3446 276 3446 275 3446 1894 3447 275 3447 277 3447 1961 3448 313 3448 273 3448 1888 3449 1887 3449 283 3449 283 3450 1887 3450 1961 3450 283 3451 1961 3451 284 3451 284 3452 1961 3452 273 3452 1946 3453 1947 3453 1962 3453 1962 3454 1947 3454 1948 3454 313 3455 1961 3455 314 3455 314 3456 1961 3456 1963 3456 314 3457 1963 3457 317 3457 317 3458 1963 3458 1962 3458 317 3459 1962 3459 316 3459 316 3460 1962 3460 1948 3460 316 3461 1948 3461 315 3461 1875 3462 1946 3462 1877 3462 1877 3463 1946 3463 1962 3463 1877 3464 1962 3464 1879 3464 1879 3465 1962 3465 1963 3465 1887 3466 1884 3466 1961 3466 1961 3467 1884 3467 1883 3467 1961 3468 1883 3468 1963 3468 1963 3469 1883 3469 1880 3469 1963 3470 1880 3470 1879 3470 1964 3471 1965 3471 1966 3471 1966 3472 1965 3472 1967 3472 231 1660 1964 1660 1966 1660 231 3473 1966 3473 232 3473 232 1660 1966 1660 1967 1660 232 1660 1967 1660 245 1660 245 3474 1967 3474 253 3474 253 3475 1967 3475 1965 3475 253 3476 1965 3476 231 3476 231 3477 1965 3477 1964 3477 1968 3478 318 3478 337 3478 1968 3479 337 3479 1969 3479 1969 3480 337 3480 336 3480 1969 3481 336 3481 1970 3481 1970 3482 336 3482 335 3482 1970 3483 335 3483 1971 3483 1971 3484 335 3484 333 3484 1971 3485 333 3485 1972 3485 1972 3486 333 3486 331 3486 1972 3487 331 3487 1973 3487 1973 3488 331 3488 330 3488 1973 3489 330 3489 1974 3489 1974 3490 330 3490 327 3490 1974 3491 327 3491 1975 3491 1975 3492 327 3492 328 3492 1975 3493 328 3493 1976 3493 1976 3494 328 3494 329 3494 1976 3495 329 3495 1977 3495 1977 3496 329 3496 323 3496 1977 3497 323 3497 1978 3497 1978 3498 323 3498 1979 3498 1979 3499 323 3499 322 3499 1979 3500 322 3500 1980 3500 322 3501 326 3501 1980 3501 1980 3502 326 3502 325 3502 1980 3503 325 3503 1981 3503 1981 3504 325 3504 324 3504 1981 3505 324 3505 1982 3505 1982 3506 324 3506 321 3506 1982 3507 321 3507 1983 3507 1983 3508 321 3508 320 3508 1983 3509 320 3509 1984 3509 1984 3510 320 3510 318 3510 1984 3511 318 3511 1968 3511 1968 3512 1969 3512 1970 3512 1972 3513 1973 3513 1979 3513 1979 3514 1973 3514 1974 3514 1977 3515 1978 3515 1976 3515 1976 3516 1978 3516 1979 3516 1976 3517 1979 3517 1975 3517 1975 3518 1979 3518 1974 3518 1979 3519 1980 3519 1985 3519 1985 3520 1980 3520 1981 3520 1981 3521 1982 3521 1985 3521 1985 3522 1982 3522 1983 3522 1985 3523 1983 3523 1984 3523 1984 3524 1968 3524 1985 3524 1985 3525 1968 3525 1970 3525 1985 3526 1970 3526 1979 3526 1979 3527 1970 3527 1971 3527 1979 3528 1971 3528 1972 3528 332 2611 1986 2611 312 2611 312 2611 1986 2611 1987 2611 312 2611 1987 2611 311 2611 1988 3529 274 3529 272 3529 1988 3530 272 3530 1989 3530 1989 3531 272 3531 271 3531 1989 3532 271 3532 1990 3532 271 3533 308 3533 1990 3533 1990 3534 308 3534 307 3534 1990 3535 307 3535 1991 3535 1991 3536 307 3536 311 3536 1991 3537 311 3537 1987 3537 1992 3538 303 3538 301 3538 1992 3539 301 3539 1993 3539 1993 3540 301 3540 269 3540 1993 3540 269 3540 1994 3540 1994 3541 269 3541 270 3541 1994 3542 270 3542 1995 3542 1995 3543 270 3543 274 3543 1995 3544 274 3544 1988 3544 1996 1782 306 1782 1992 1782 1992 1782 306 1782 305 1782 1992 1782 305 1782 303 1782 1997 3545 293 3545 292 3545 1997 3546 292 3546 1998 3546 1998 3547 292 3547 299 3547 1998 3548 299 3548 1999 3548 1999 3549 299 3549 298 3549 1999 3550 298 3550 2000 3550 2000 3551 298 3551 306 3551 2000 3552 306 3552 1996 3552 1986 3553 332 3553 334 3553 296 3554 2001 3554 334 3554 334 3555 2001 3555 2002 3555 334 3556 2002 3556 1986 3556 296 3557 295 3557 2001 3557 2001 3558 295 3558 294 3558 2001 3559 294 3559 2003 3559 2003 3560 294 3560 293 3560 2003 3561 293 3561 1997 3561 1986 3562 2002 3562 1996 3562 1996 3563 2002 3563 2001 3563 2003 3564 1997 3564 2004 3564 2001 3565 2003 3565 1996 3565 1996 3566 2003 3566 2004 3566 1996 3567 2004 3567 2000 3567 1997 3568 1998 3568 2004 3568 2004 3569 1998 3569 1999 3569 2004 3570 1999 3570 2000 3570 1993 3571 1994 3571 1987 3571 1995 3572 1988 3572 2005 3572 1994 3573 1995 3573 1987 3573 1987 3574 1995 3574 2005 3574 1987 3575 2005 3575 1991 3575 1988 3576 1989 3576 2005 3576 2005 3577 1989 3577 1990 3577 2005 3578 1990 3578 1991 3578 1986 3579 1996 3579 1987 3579 1987 3580 1996 3580 1992 3580 1987 3581 1992 3581 1993 3581 2006 2611 302 2611 2007 2611 2007 2611 302 2611 304 2611 2007 2611 304 2611 297 2611 2008 3582 278 3582 268 3582 2008 3583 268 3583 2009 3583 2009 3584 268 3584 267 3584 2009 3585 267 3585 2010 3585 2010 3586 267 3586 300 3586 2010 3587 300 3587 2011 3587 2011 3588 300 3588 302 3588 2011 3589 302 3589 2006 3589 2012 3590 239 3590 235 3590 2012 3591 235 3591 2013 3591 2013 3592 235 3592 234 3592 2013 3593 234 3593 2014 3593 2014 3594 234 3594 233 3594 2014 3595 233 3595 2015 3595 2015 3596 233 3596 278 3596 2015 3597 278 3597 2008 3597 239 1782 2012 1782 265 1782 265 1782 2012 1782 2016 1782 265 1782 2016 1782 266 1782 2017 3598 287 3598 286 3598 2017 3599 286 3599 2018 3599 2018 3600 286 3600 285 3600 2018 3601 285 3601 2019 3601 2019 3602 285 3602 262 3602 2019 3603 262 3603 2020 3603 2020 3604 262 3604 266 3604 2020 3605 266 3605 2016 3605 2007 3606 297 3606 291 3606 2007 3607 291 3607 2021 3607 2021 3608 291 3608 290 3608 2021 3609 290 3609 2022 3609 2022 3610 290 3610 289 3610 2022 3611 289 3611 2023 3611 2023 3612 289 3612 287 3612 2023 3613 287 3613 2017 3613 2006 3614 2012 3614 2013 3614 2009 3615 2010 3615 2008 3615 2008 3616 2010 3616 2011 3616 2008 3617 2011 3617 2015 3617 2015 3618 2011 3618 2006 3618 2015 3619 2006 3619 2014 3619 2014 3620 2006 3620 2013 3620 2018 3621 2019 3621 2017 3621 2017 3622 2019 3622 2020 3622 2017 3623 2020 3623 2023 3623 2023 3624 2020 3624 2016 3624 2023 3625 2016 3625 2022 3625 2022 3626 2016 3626 2021 3626 2012 1711 2006 1711 2016 1711 2016 1711 2006 1711 2007 1711 2016 3627 2007 3627 2021 3627 263 2611 2024 2611 264 2611 264 2611 2024 2611 2025 2611 264 2611 2025 2611 240 2611 2026 3628 241 3628 237 3628 2026 3629 237 3629 2027 3629 2027 3630 237 3630 236 3630 2027 3631 236 3631 2028 3631 2028 3632 236 3632 238 3632 2028 3633 238 3633 2029 3633 2029 3634 238 3634 240 3634 2029 3635 240 3635 2025 3635 2030 3636 227 3636 229 3636 230 3637 2031 3637 229 3637 229 3638 2031 3638 2032 3638 229 3639 2032 3639 2030 3639 230 3640 243 3640 2031 3640 2031 3641 243 3641 242 3641 2031 3642 242 3642 2033 3642 2033 3643 242 3643 241 3643 2033 3644 241 3644 2026 3644 2034 1782 222 1782 2030 1782 2030 1782 222 1782 221 1782 2030 1782 221 1782 227 1782 2035 3645 257 3645 256 3645 2035 3646 256 3646 2036 3646 2036 3647 256 3647 216 3647 2036 3648 216 3648 2037 3648 216 3649 224 3649 2037 3649 2037 3650 224 3650 223 3650 2037 3651 223 3651 2038 3651 2038 3652 223 3652 222 3652 2038 3653 222 3653 2034 3653 2024 3654 263 3654 261 3654 2024 3655 261 3655 2039 3655 2039 3656 261 3656 260 3656 2039 3656 260 3656 2040 3656 2040 3657 260 3657 259 3657 2040 3658 259 3658 2041 3658 2041 3659 259 3659 257 3659 2041 3660 257 3660 2035 3660 2030 3661 2032 3661 2025 3661 2025 3662 2032 3662 2031 3662 2033 3663 2026 3663 2042 3663 2031 3664 2033 3664 2025 3664 2025 3665 2033 3665 2042 3665 2025 3666 2042 3666 2029 3666 2026 3667 2027 3667 2042 3667 2042 3668 2027 3668 2028 3668 2042 3669 2028 3669 2029 3669 2039 3670 2040 3670 2034 3670 2041 3671 2035 3671 2043 3671 2040 3672 2041 3672 2034 3672 2034 3673 2041 3673 2043 3673 2034 3674 2043 3674 2038 3674 2035 3675 2036 3675 2043 3675 2043 3676 2036 3676 2037 3676 2043 3677 2037 3677 2038 3677 2030 3678 2025 3678 2034 3678 2034 3679 2025 3679 2024 3679 2034 3680 2024 3680 2039 3680 219 2611 2044 2611 220 2611 220 2611 2044 2611 2045 2611 220 2611 2045 2611 225 2611 2046 3681 193 3681 196 3681 2046 3682 196 3682 2047 3682 2047 3683 196 3683 228 3683 2047 3684 228 3684 2048 3684 2048 3685 228 3685 226 3685 2048 3686 226 3686 2049 3686 2049 3687 226 3687 225 3687 2049 3688 225 3688 2045 3688 2050 3689 209 3689 208 3689 2050 3690 208 3690 2051 3690 2051 3691 208 3691 197 3691 2051 3692 197 3692 2052 3692 2052 3693 197 3693 199 3693 2052 3694 199 3694 2053 3694 2053 3695 199 3695 193 3695 2053 3696 193 3696 2046 3696 209 1782 2050 1782 211 1782 211 1782 2050 1782 2054 1782 211 1782 2054 1782 207 1782 2055 3697 213 3697 212 3697 2055 3698 212 3698 2056 3698 2056 3699 212 3699 205 3699 2056 3700 205 3700 2057 3700 2057 3701 205 3701 204 3701 2057 3702 204 3702 2058 3702 2058 3703 204 3703 207 3703 2058 3704 207 3704 2054 3704 2044 3705 219 3705 215 3705 2044 3706 215 3706 2059 3706 2059 3707 215 3707 217 3707 2059 3708 217 3708 2060 3708 2060 3709 217 3709 218 3709 2060 3710 218 3710 2061 3710 2061 3711 218 3711 213 3711 2061 3712 213 3712 2055 3712 2050 3713 2051 3713 2045 3713 2045 3714 2051 3714 2052 3714 2053 3715 2046 3715 2062 3715 2052 3716 2053 3716 2045 3716 2045 3717 2053 3717 2062 3717 2045 3718 2062 3718 2049 3718 2046 3719 2047 3719 2062 3719 2062 3720 2047 3720 2048 3720 2062 3721 2048 3721 2049 3721 2059 3722 2060 3722 2054 3722 2054 3723 2060 3723 2061 3723 2054 3724 2061 3724 2063 3724 2063 3725 2061 3725 2055 3725 2055 3726 2056 3726 2063 3726 2063 3727 2056 3727 2057 3727 2063 3728 2057 3728 2054 3728 2054 3729 2057 3729 2058 3729 2050 3730 2045 3730 2054 3730 2054 3731 2045 3731 2044 3731 2054 3732 2044 3732 2059 3732 2064 3733 2065 3733 2066 3733 2066 3734 2065 3734 2067 3734 2066 3735 2067 3735 1779 3735 1779 3736 2067 3736 2068 3736 2069 3737 2070 3737 1741 3737 2069 3738 1741 3738 2071 3738 2071 3739 1741 3739 1740 3739 2071 3740 1740 3740 2072 3740 2072 3741 1740 3741 1749 3741 2072 3742 1749 3742 2073 3742 2073 3743 1749 3743 2074 3743 2074 3744 1749 3744 1748 3744 2074 3745 1748 3745 2075 3745 2075 3746 1748 3746 2076 3746 2076 3747 1748 3747 1752 3747 2076 3748 1752 3748 2077 3748 1741 3749 2070 3749 1760 3749 1766 3750 1769 3750 2078 3750 1769 3751 1758 3751 2079 3751 1767 3752 1766 3752 1778 3752 1778 3753 1766 3753 2078 3753 1778 3754 2078 3754 1779 3754 1779 3755 2078 3755 2066 3755 1769 3756 2079 3756 2078 3756 2078 3757 2079 3757 2064 3757 2078 3758 2064 3758 2066 3758 1752 3759 1836 3759 2077 3759 1804 3760 2080 3760 1802 3760 1802 3761 2080 3761 2081 3761 1802 3762 2081 3762 1803 3762 2082 3763 2083 3763 2084 3763 2083 3764 2082 3764 2085 3764 2085 3765 2082 3765 2086 3765 2085 3766 2086 3766 2087 3766 1804 3767 2087 3767 2080 3767 2080 3768 2087 3768 2086 3768 2080 3769 2086 3769 2081 3769 2081 3770 2086 3770 2082 3770 2081 3771 2082 3771 2088 3771 2088 3772 2082 3772 2084 3772 2089 3773 2087 3773 1805 3773 1805 3774 2087 3774 1804 3774 2089 3775 2090 3775 2087 3775 2087 3776 2090 3776 2091 3776 2087 3777 2091 3777 2085 3777 2092 3778 2093 3778 2094 3778 1805 3779 1780 3779 2089 3779 2089 3780 1780 3780 2095 3780 2089 3781 2095 3781 2090 3781 2090 3782 2095 3782 2092 3782 2090 3783 2092 3783 2091 3783 2091 3784 2092 3784 2094 3784 2091 3785 2094 3785 2085 3785 2096 3786 2097 3786 2098 3786 1779 3787 2068 3787 2098 3787 2098 3788 2068 3788 2099 3788 2099 3789 2100 3789 2098 3789 2098 3790 2100 3790 2101 3790 2098 3791 2101 3791 2096 3791 1780 3792 1779 3792 2095 3792 2095 3793 1779 3793 2098 3793 2095 3794 2098 3794 2092 3794 2092 3795 2098 3795 2097 3795 2092 3796 2097 3796 2093 3796 2067 3797 2065 3797 2102 3797 2068 3798 2067 3798 2103 3798 2067 3799 2102 3799 2103 3799 2103 3800 2102 3800 2104 3800 2103 3801 2104 3801 2105 3801 2105 3802 2104 3802 2106 3802 2105 3803 2106 3803 2107 3803 2107 3804 2106 3804 2108 3804 2107 3805 2108 3805 2109 3805 2068 3806 2103 3806 2099 3806 2099 3807 2103 3807 2105 3807 2099 3808 2105 3808 2100 3808 2100 3809 2105 3809 2107 3809 2100 3810 2107 3810 2101 3810 2101 3811 2107 3811 2109 3811 2101 3812 2109 3812 2096 3812 1757 3813 2110 3813 2065 3813 2065 3814 2064 3814 1757 3814 1757 3815 2064 3815 2079 3815 1757 3816 2079 3816 1758 3816 2110 3817 1757 3817 2111 3817 2111 3818 1757 3818 1760 3818 2111 3819 1760 3819 2070 3819 2111 3820 2070 3820 2069 3820 2069 3821 2112 3821 2111 3821 2111 3822 2112 3822 2113 3822 2111 3823 2113 3823 2110 3823 2114 3824 2115 3824 2116 3824 2117 3825 2118 3825 2071 3825 2076 3826 2119 3826 2075 3826 2075 3827 2119 3827 2115 3827 2075 3828 2115 3828 2074 3828 2074 3829 2115 3829 2114 3829 2074 3830 2114 3830 2073 3830 2073 3831 2114 3831 2117 3831 2073 3832 2117 3832 2072 3832 2072 3833 2117 3833 2071 3833 2120 3834 2113 3834 2112 3834 2069 3835 2071 3835 2112 3835 2112 3836 2071 3836 2118 3836 2112 3837 2118 3837 2120 3837 2120 3838 2118 3838 2117 3838 2120 3839 2117 3839 2121 3839 2121 3840 2117 3840 2114 3840 2121 3841 2114 3841 2122 3841 2122 3842 2114 3842 2116 3842 2122 3843 2116 3843 2123 3843 2076 3844 2077 3844 2119 3844 2119 3845 2077 3845 2124 3845 2119 3846 2124 3846 2115 3846 2115 3847 2124 3847 2116 3847 2116 3848 2124 3848 2125 3848 2116 3849 2125 3849 2123 3849 2126 3850 2127 3850 2128 3850 2128 3851 1807 3851 1806 3851 2084 3852 2126 3852 2088 3852 2088 3853 2126 3853 2128 3853 2088 3854 2128 3854 2129 3854 2129 3855 2128 3855 1806 3855 2129 3856 1806 3856 1803 3856 2130 3857 2131 3857 2132 3857 2133 3858 2134 3858 2135 3858 2133 3859 2135 3859 2136 3859 2136 3860 2135 3860 2137 3860 2136 3861 2137 3861 2138 3861 2138 3862 2137 3862 2130 3862 2138 3863 2130 3863 2139 3863 2139 3864 2130 3864 2132 3864 2139 3865 2132 3865 583 3865 583 3866 2132 3866 2140 3866 2141 3867 577 3867 2140 3867 2140 3868 577 3868 584 3868 2140 3869 584 3869 583 3869 2142 3870 2141 3870 2143 3870 2143 3871 2141 3871 2140 3871 2143 3872 2140 3872 2131 3872 2131 3873 2140 3873 2132 3873 2142 3874 2125 3874 2144 3874 2144 3875 2125 3875 2124 3875 2144 3876 2124 3876 2145 3876 2145 3877 2124 3877 2146 3877 2077 3878 1836 3878 2124 3878 2124 3879 1836 3879 1842 3879 2124 3880 1842 3880 2146 3880 2146 3881 1842 3881 1841 3881 2146 3882 1841 3882 2147 3882 2147 3883 1841 3883 1839 3883 2148 3884 1838 3884 580 3884 2147 3885 1839 3885 1838 3885 580 3886 575 3886 2148 3886 2148 3887 575 3887 574 3887 2148 3888 574 3888 2149 3888 2149 3889 574 3889 579 3889 2149 3890 579 3890 2150 3890 2150 3891 579 3891 578 3891 2150 3892 578 3892 2151 3892 2151 3893 578 3893 577 3893 2151 3894 577 3894 2141 3894 1838 3895 2148 3895 2147 3895 2147 3896 2148 3896 2149 3896 2147 3897 2149 3897 2146 3897 2146 3898 2149 3898 2150 3898 2146 3899 2150 3899 2145 3899 2145 3900 2150 3900 2151 3900 2145 3901 2151 3901 2144 3901 2144 3902 2151 3902 2141 3902 2144 3903 2141 3903 2142 3903 2152 3904 2127 3904 2153 3904 2153 3905 2127 3905 2126 3905 2153 3906 2126 3906 2154 3906 2085 3907 2155 3907 2083 3907 2083 3908 2155 3908 2084 3908 2084 3909 2155 3909 2126 3909 2126 3910 2155 3910 2156 3910 2126 3911 2156 3911 2154 3911 2155 3912 2085 3912 2094 3912 2096 3913 2157 3913 2097 3913 2097 3914 2157 3914 2158 3914 2097 3915 2158 3915 2159 3915 2094 3916 2093 3916 2155 3916 2155 3917 2093 3917 2097 3917 2155 3918 2097 3918 2160 3918 2160 3919 2097 3919 2159 3919 2108 3920 2161 3920 2109 3920 2109 3921 2161 3921 2162 3921 2109 3922 2162 3922 2096 3922 2096 3923 2162 3923 2157 3923 2163 3924 2164 3924 2165 3924 2165 3925 2164 3925 2166 3925 2165 3926 2166 3926 2167 3926 2108 3927 2113 3927 2161 3927 2161 3928 2113 3928 2167 3928 2161 3929 2167 3929 2168 3929 2168 3930 2167 3930 2166 3930 2108 3931 2106 3931 2113 3931 2113 3932 2106 3932 2104 3932 2113 3933 2104 3933 2110 3933 2110 3934 2104 3934 2102 3934 2110 3935 2102 3935 2065 3935 2167 3936 2113 3936 2120 3936 2167 3937 2120 3937 2169 3937 2169 3938 2120 3938 2121 3938 2169 3939 2121 3939 2170 3939 2170 3940 2121 3940 2122 3940 2170 3941 2122 3941 2171 3941 2171 3942 2122 3942 2123 3942 2171 3943 2123 3943 2172 3943 2137 3944 2123 3944 2130 3944 2130 3945 2123 3945 2125 3945 2142 3946 2143 3946 2125 3946 2125 3947 2143 3947 2131 3947 2125 3948 2131 3948 2130 3948 2173 3949 2172 3949 2134 3949 2134 3950 2172 3950 2123 3950 2134 3951 2123 3951 2135 3951 2135 3952 2123 3952 2137 3952 2173 3951 2174 3951 2172 3951 2172 3953 2174 3953 2175 3953 2172 3954 2175 3954 2176 3954 2176 3955 2175 3955 2177 3955 2177 3956 2178 3956 2176 3956 2176 3947 2178 3947 2179 3947 2176 3957 2179 3957 2180 3957 2133 3958 2181 3958 2134 3958 2134 3959 2181 3959 2173 3959 2181 3960 2133 3960 2182 3960 2183 3961 2184 3961 2185 3961 2181 3962 2182 3962 2185 3962 2185 3963 2182 3963 2186 3963 2185 3964 2186 3964 2183 3964 2187 3965 2188 3965 2184 3965 2184 3966 2188 3966 2189 3966 2184 3967 2189 3967 2185 3967 2190 3968 2191 3968 2192 3968 2187 3969 2184 3969 2191 3969 2191 3970 2184 3970 2193 3970 2191 3971 2193 3971 2192 3971 2190 3972 2192 3972 2194 3972 2194 3973 2192 3973 2195 3973 2194 3974 2195 3974 2196 3974 2197 3975 2198 3975 2199 3975 2199 3976 2198 3976 2200 3976 2197 3977 2201 3977 2198 3977 2198 3978 2201 3978 2202 3978 2198 3979 2202 3979 2196 3979 2196 3980 2202 3980 2203 3980 2196 3981 2203 3981 2194 3981 2136 3982 2138 3982 2204 3982 2204 3983 2138 3983 2139 3983 135 3984 2205 3984 136 3984 136 3985 2205 3985 2206 3985 136 3986 2206 3986 128 3986 128 3987 2206 3987 2204 3987 128 3988 2204 3988 585 3988 585 3989 2204 3989 2139 3989 585 3990 2139 3990 583 3990 2205 3991 2183 3991 2206 3991 2206 3992 2183 3992 2186 3992 2206 3993 2186 3993 2204 3993 2204 3994 2186 3994 2182 3994 2204 3995 2182 3995 2136 3995 2136 3996 2182 3996 2133 3996 1492 3997 2207 3997 2208 3997 2208 3998 2207 3998 2209 3998 2208 3999 2209 3999 2210 3999 2210 4000 2209 4000 2163 4000 2211 4001 1456 4001 2212 4001 2212 4002 1456 4002 1455 4002 2212 4003 1455 4003 2213 4003 2213 4004 1455 4004 1453 4004 2213 4005 1453 4005 2214 4005 2214 4006 1453 4006 1441 4006 2214 4007 1441 4007 2215 4007 2215 4008 1441 4008 2216 4008 2216 4009 1441 4009 1440 4009 2216 4010 1440 4010 2217 4010 1465 4011 2217 4011 1440 4011 1470 4012 1474 4012 1490 4012 1471 4013 2218 4013 1463 4013 1463 4014 2218 4014 2219 4014 1490 4015 1492 4015 2208 4015 2210 4016 2219 4016 2208 4016 2208 4017 2219 4017 2218 4017 2208 4018 2218 4018 1490 4018 1490 4019 2218 4019 1471 4019 1490 4020 1471 4020 1470 4020 2211 4021 1537 4021 1456 4021 2220 4022 2154 4022 2156 4022 2221 4023 2222 4023 1493 4023 1493 4024 2222 4024 1494 4024 2221 4025 2223 4025 2222 4025 2222 4026 2223 4026 2224 4026 2222 4027 2224 4027 2155 4027 1493 4028 1497 4028 2221 4028 2221 4029 1497 4029 2225 4029 2221 4030 2225 4030 2223 4030 2223 4031 2225 4031 2220 4031 2223 4032 2220 4032 2224 4032 2224 4033 2220 4033 2156 4033 2224 4034 2156 4034 2155 4034 2226 4035 2222 4035 2155 4035 2227 4036 2228 4036 1495 4036 1495 4037 2228 4037 1491 4037 2226 4038 2155 4038 2229 4038 2229 4039 2155 4039 2160 4039 2229 4040 2160 4040 2159 4040 2159 4041 2230 4041 2229 4041 2229 4042 2230 4042 2228 4042 2229 4043 2228 4043 2226 4043 2226 4044 2228 4044 2227 4044 2226 4045 2227 4045 2222 4045 2222 4046 2227 4046 1495 4046 2222 4047 1495 4047 1494 4047 2230 4048 2159 4048 2158 4048 2231 4049 2207 4049 2228 4049 2228 4050 2207 4050 1492 4050 2228 4051 1492 4051 1491 4051 2232 4052 2233 4052 2231 4052 2231 4053 2233 4053 2234 4053 2231 4054 2234 4054 2207 4054 2228 4055 2230 4055 2231 4055 2231 4056 2230 4056 2158 4056 2231 4057 2158 4057 2232 4057 2232 4058 2158 4058 2157 4058 2209 4059 2207 4059 2234 4059 2163 4060 2209 4060 2235 4060 2209 4061 2234 4061 2235 4061 2235 4062 2234 4062 2233 4062 2235 4063 2233 4063 2236 4063 2236 4064 2233 4064 2232 4064 2236 4065 2232 4065 2237 4065 2237 4066 2232 4066 2157 4066 2237 4067 2157 4067 2162 4067 2163 4068 2235 4068 2164 4068 2164 4069 2235 4069 2236 4069 2164 4070 2236 4070 2166 4070 2166 4071 2236 4071 2237 4071 2166 4072 2237 4072 2168 4072 2168 4073 2237 4073 2162 4073 2168 4074 2162 4074 2161 4074 2210 4075 1464 4075 2219 4075 2219 4076 1464 4076 1463 4076 2217 4077 1465 4077 2238 4077 2238 4078 1465 4078 1464 4078 2238 4079 1464 4079 2165 4079 2165 4080 1464 4080 2210 4080 2165 4081 2210 4081 2163 4081 2238 4082 2165 4082 2167 4082 2167 4083 2239 4083 2238 4083 2238 4084 2239 4084 2216 4084 2238 4085 2216 4085 2217 4085 2240 4086 2239 4086 2167 4086 2241 4087 2242 4087 2243 4087 2243 4088 2242 4088 2244 4088 2216 4089 2239 4089 2215 4089 2215 4090 2239 4090 2240 4090 2215 4091 2240 4091 2214 4091 2214 4092 2240 4092 2244 4092 2214 4093 2244 4093 2213 4093 2213 4094 2244 4094 2242 4094 2213 4095 2242 4095 2212 4095 2171 4096 2172 4096 2245 4096 2167 4097 2169 4097 2240 4097 2240 4098 2169 4098 2170 4098 2240 4099 2170 4099 2244 4099 2244 4100 2170 4100 2171 4100 2244 4101 2171 4101 2243 4101 2243 4102 2171 4102 2245 4102 2243 4103 2245 4103 2241 4103 2172 4104 2176 4104 2245 4104 2245 4105 2176 4105 2246 4105 2245 4106 2246 4106 2241 4106 2241 4107 2246 4107 2242 4107 2242 4108 2246 4108 2211 4108 2242 4109 2211 4109 2212 4109 2247 4110 2152 4110 2153 4110 2153 4111 2154 4111 2220 4111 2248 4112 1497 4112 1512 4112 2153 4113 2220 4113 2247 4113 2247 4114 2220 4114 2248 4114 2247 4115 2248 4115 2249 4115 2249 4116 2248 4116 1512 4116 2249 4117 1512 4117 1514 4117 2250 4118 2178 4118 2177 4118 2173 4119 2181 4119 2251 4119 2173 4120 2251 4120 2174 4120 2174 4121 2251 4121 2252 4121 2174 4122 2252 4122 2175 4122 2175 4123 2252 4123 2253 4123 2175 4124 2253 4124 2177 4124 2177 4125 2253 4125 73 4125 2177 4126 73 4126 2250 4126 2179 4127 2254 4127 2180 4127 2180 4128 2254 4128 2255 4128 2250 4129 73 4129 72 4129 75 4130 2255 4130 72 4130 72 4131 2255 4131 2254 4131 72 4132 2254 4132 2250 4132 2250 4133 2254 4133 2179 4133 2250 4134 2179 4134 2178 4134 2246 4135 2176 4135 2180 4135 2180 4136 2256 4136 2246 4136 2246 4137 2256 4137 2257 4137 2246 4138 2257 4138 2258 4138 2259 4139 1533 4139 1539 4139 2259 4140 1539 4140 2258 4140 2258 4141 1539 4141 1538 4141 2258 4142 1538 4142 2246 4142 2246 4143 1538 4143 1537 4143 2246 4144 1537 4144 2211 4144 2260 4145 1534 4145 1533 4145 589 4146 586 4146 1534 4146 1533 4147 2259 4147 2260 4147 2260 4148 2259 4148 2258 4148 2260 4149 2258 4149 2261 4149 2261 4150 2258 4150 2257 4150 2261 4151 2257 4151 2262 4151 2262 4152 2257 4152 2256 4152 2262 4153 2256 4153 2263 4153 2263 4154 2256 4154 2180 4154 2263 4155 2180 4155 2255 4155 1534 4156 2260 4156 589 4156 589 4157 2260 4157 2261 4157 589 4158 2261 4158 590 4158 590 4159 2261 4159 2262 4159 590 4160 2262 4160 591 4160 591 4161 2262 4161 2263 4161 591 4162 2263 4162 592 4162 592 4163 2263 4163 2255 4163 592 4164 2255 4164 75 4164 132 4165 2264 4165 133 4165 79 4166 74 4166 2265 4166 2265 4167 2252 4167 2251 4167 74 4168 73 4168 2265 4168 2265 4169 73 4169 2253 4169 2265 4170 2253 4170 2252 4170 106 4171 2266 4171 95 4171 95 4172 2266 4172 2267 4172 95 4173 2267 4173 96 4173 2191 4174 92 4174 2267 4174 2267 4175 92 4175 93 4175 2267 4176 93 4176 96 4176 2191 4177 2190 4177 92 4177 92 4178 2190 4178 2194 4178 92 4179 2194 4179 90 4179 90 4180 2194 4180 2203 4180 2201 4181 164 4181 2202 4181 2202 4182 164 4182 163 4182 2202 4183 163 4183 2203 4183 2203 4184 163 4184 87 4184 2203 4185 87 4185 90 4185 2197 4186 167 4186 2201 4186 2201 4187 167 4187 166 4187 2201 4188 166 4188 164 4188 178 4189 177 4189 2200 4189 2200 4190 177 4190 158 4190 2200 4191 158 4191 2199 4191 2199 4192 158 4192 160 4192 2199 4193 160 4193 2197 4193 2197 4194 160 4194 162 4194 2197 4195 162 4195 167 4195 178 4196 2200 4196 179 4196 179 4197 2200 4197 2198 4197 179 4198 2198 4198 182 4198 182 4199 2198 4199 2196 4199 182 4200 2196 4200 139 4200 139 4201 2196 4201 2195 4201 139 4202 2195 4202 137 4202 133 4203 2264 4203 134 4203 134 4204 2264 4204 2268 4204 134 4205 2268 4205 135 4205 137 4206 2195 4206 132 4206 132 4207 2195 4207 2192 4207 132 4208 2192 4208 2264 4208 2264 4209 2192 4209 2193 4209 2264 4210 2193 4210 2268 4210 2268 4211 2193 4211 2184 4211 2268 4212 2184 4212 2183 4212 106 4213 79 4213 2266 4213 2266 4214 79 4214 2265 4214 2266 4215 2265 4215 2185 4215 2185 4216 2265 4216 2251 4216 2185 4217 2251 4217 2181 4217 2185 4218 2189 4218 2266 4218 2266 4219 2189 4219 2188 4219 2266 4220 2188 4220 2267 4220 2267 4221 2188 4221 2187 4221 2267 4222 2187 4222 2191 4222 2269 4223 2270 4223 2271 4223 2271 4224 2270 4224 2272 4224 176 4225 2269 4225 175 4225 175 4226 2269 4226 2271 4226 175 1660 2271 1660 173 1660 173 4227 2271 4227 2272 4227 173 4228 2272 4228 2270 4228 173 4229 2270 4229 180 4229 180 4230 2270 4230 2269 4230 180 4231 2269 4231 176 4231 66 4232 2273 4232 2274 4232 66 4233 2274 4233 67 4233 67 4234 2274 4234 2275 4234 67 4235 2275 4235 69 4235 69 4236 2275 4236 2276 4236 69 4237 2276 4237 70 4237 70 4238 2276 4238 720 4238 70 4239 720 4239 112 4239 2277 4240 2278 4240 2279 4240 2279 4241 2278 4241 2280 4241 2280 4242 2281 4242 2279 4242 2279 4243 2281 4243 2282 4243 2279 4244 2282 4244 2283 4244 2284 4245 2277 4245 2285 4245 2285 4246 2277 4246 2279 4246 2285 4247 2279 4247 2286 4247 2286 4248 2279 4248 2287 4248 2283 4249 724 4249 2279 4249 2279 4250 724 4250 2273 4250 2279 4251 2273 4251 2287 4251 722 4252 2288 4252 723 4252 723 4253 2288 4253 724 4253 2274 4254 2273 4254 2275 4254 2275 4255 2273 4255 724 4255 2275 4256 724 4256 2276 4256 2276 4257 724 4257 2288 4257 2276 4258 2288 4258 720 4258 720 4259 2288 4259 722 4259 720 4260 722 4260 721 4260 2289 1711 109 1711 2290 1711 2290 1711 109 1711 99 1711 2290 1711 99 1711 100 1711 91 4261 2291 4261 2292 4261 91 4262 2292 4262 94 4262 94 4263 2292 4263 2293 4263 94 4264 2293 4264 105 4264 105 4265 2293 4265 2294 4265 105 4266 2294 4266 103 4266 103 4267 2294 4267 2290 4267 103 4268 2290 4268 100 4268 85 4269 2295 4269 2296 4269 85 4270 2296 4270 86 4270 86 4271 2296 4271 2297 4271 86 4271 2297 4271 88 4271 88 4272 2297 4272 2298 4272 88 4273 2298 4273 89 4273 89 4274 2298 4274 2291 4274 89 4275 2291 4275 91 4275 122 1695 2299 1695 124 1695 124 4276 2299 4276 2295 4276 124 1695 2295 1695 85 1695 118 4277 2300 4277 2301 4277 118 4278 2301 4278 119 4278 119 4279 2301 4279 2302 4279 119 4280 2302 4280 120 4280 120 4281 2302 4281 2303 4281 120 4282 2303 4282 121 4282 121 4283 2303 4283 2299 4283 121 4284 2299 4284 122 4284 109 4285 2289 4285 2304 4285 109 4286 2304 4286 107 4286 107 4287 2304 4287 2305 4287 107 4288 2305 4288 115 4288 115 4289 2305 4289 2306 4289 115 4290 2306 4290 116 4290 116 4291 2306 4291 2300 4291 116 4292 2300 4292 118 4292 2299 4293 2289 4293 2295 4293 2295 4294 2289 4294 2290 4294 2293 4295 2307 4295 2294 4295 2294 4296 2307 4296 2290 4296 2296 4297 2295 4297 2297 4297 2297 4298 2295 4298 2290 4298 2297 4299 2290 4299 2298 4299 2298 4300 2290 4300 2307 4300 2298 4301 2307 4301 2291 4301 2291 4302 2307 4302 2293 4302 2291 4303 2293 4303 2292 4303 2302 4304 2308 4304 2303 4304 2303 4305 2308 4305 2299 4305 2304 4306 2289 4306 2305 4306 2305 4307 2289 4307 2299 4307 2305 4308 2299 4308 2306 4308 2306 4309 2299 4309 2308 4309 2306 4310 2308 4310 2300 4310 2300 4311 2308 4311 2302 4311 2300 4312 2302 4312 2301 4312 170 1711 2309 1711 185 1711 185 1711 2309 1711 2310 1711 185 1711 2310 1711 184 1711 161 4313 2311 4313 2312 4313 161 4314 2312 4314 165 4314 165 4315 2312 4315 2313 4315 165 4316 2313 4316 168 4316 168 4317 2313 4317 2314 4317 168 4318 2314 4318 169 4318 169 4319 2314 4319 2309 4319 169 4320 2309 4320 170 4320 171 4321 2315 4321 2316 4321 171 4322 2316 4322 172 4322 172 4323 2316 4323 2317 4323 172 4324 2317 4324 174 4324 174 4325 2317 4325 2318 4325 174 4326 2318 4326 159 4326 159 4327 2318 4327 2311 4327 159 4328 2311 4328 161 4328 2315 1695 171 1695 2319 1695 2319 4329 171 4329 181 4329 2319 1695 181 1695 192 1695 188 4330 2320 4330 2321 4330 188 4331 2321 4331 189 4331 189 4332 2321 4332 2322 4332 189 4333 2322 4333 190 4333 190 4334 2322 4334 2323 4334 190 4335 2323 4335 191 4335 191 4336 2323 4336 2319 4336 191 4337 2319 4337 192 4337 184 4338 2310 4338 2324 4338 184 4339 2324 4339 183 4339 183 4340 2324 4340 2325 4340 183 4341 2325 4341 186 4341 186 4342 2325 4342 2326 4342 186 4343 2326 4343 187 4343 187 4344 2326 4344 2320 4344 187 4345 2320 4345 188 4345 2309 2611 2315 2611 2310 2611 2310 2611 2315 2611 2319 2611 2323 4346 2322 4346 2321 4346 2324 4347 2310 4347 2325 4347 2325 4348 2310 4348 2319 4348 2325 4349 2319 4349 2326 4349 2326 4350 2319 4350 2323 4350 2326 4351 2323 4351 2320 4351 2320 4352 2323 4352 2321 4352 2314 4353 2313 4353 2312 4353 2316 4354 2315 4354 2317 4354 2317 4355 2315 4355 2309 4355 2317 4356 2309 4356 2318 4356 2318 4357 2309 4357 2314 4357 2318 4358 2314 4358 2311 4358 2311 4359 2314 4359 2312 4359 2327 1711 150 1711 2328 1711 2328 4360 150 4360 149 4360 2328 1711 149 1711 143 1711 138 4361 2329 4361 2330 4361 138 4362 2330 4362 140 4362 140 4363 2330 4363 2331 4363 140 4364 2331 4364 141 4364 141 4365 2331 4365 2332 4365 141 4366 2332 4366 142 4366 142 4367 2332 4367 2328 4367 142 4368 2328 4368 143 4368 127 4369 2333 4369 2334 4369 127 4370 2334 4370 129 4370 129 4371 2334 4371 2335 4371 129 4372 2335 4372 130 4372 130 4373 2335 4373 2336 4373 130 4374 2336 4374 131 4374 131 4375 2336 4375 2329 4375 131 4275 2329 4275 138 4275 145 1695 2337 1695 126 1695 126 1695 2337 1695 2333 1695 126 1695 2333 1695 127 1695 155 4376 2338 4376 2339 4376 155 4377 2339 4377 156 4377 156 4378 2339 4378 2340 4378 156 4379 2340 4379 157 4379 157 4380 2340 4380 2341 4380 157 4381 2341 4381 147 4381 147 4382 2341 4382 2337 4382 147 4383 2337 4383 145 4383 150 4384 2327 4384 2342 4384 150 4385 2342 4385 152 4385 152 4386 2342 4386 2343 4386 152 4387 2343 4387 153 4387 153 4388 2343 4388 2344 4388 153 4389 2344 4389 154 4389 154 4390 2344 4390 2338 4390 154 4391 2338 4391 155 4391 2328 4392 2333 4392 2327 4392 2327 4393 2333 4393 2337 4393 2340 4394 2345 4394 2341 4394 2341 4395 2345 4395 2337 4395 2342 4396 2327 4396 2343 4396 2343 4397 2327 4397 2337 4397 2343 4398 2337 4398 2344 4398 2344 4399 2337 4399 2345 4399 2344 4400 2345 4400 2338 4400 2338 4401 2345 4401 2340 4401 2338 4402 2340 4402 2339 4402 2331 4403 2346 4403 2332 4403 2332 4404 2346 4404 2328 4404 2334 4405 2333 4405 2335 4405 2335 4406 2333 4406 2328 4406 2335 4407 2328 4407 2336 4407 2336 4408 2328 4408 2346 4408 2336 4409 2346 4409 2329 4409 2329 4410 2346 4410 2331 4410 2329 4411 2331 4411 2330 4411 653 4412 2347 4412 2348 4412 653 4413 2348 4413 655 4413 655 4414 2348 4414 2349 4414 655 4415 2349 4415 656 4415 656 4416 2349 4416 2350 4416 656 4417 2350 4417 657 4417 657 4418 2350 4418 2351 4418 657 4419 2351 4419 658 4419 146 4420 2352 4420 2353 4420 146 4421 2353 4421 148 4421 148 4422 2353 4422 2354 4422 148 4423 2354 4423 6 4423 6 4424 2354 4424 7 4424 7 4425 2354 4425 2355 4425 7 4426 2355 4426 652 4426 652 4427 2355 4427 2347 4427 652 4428 2347 4428 653 4428 2347 4429 2355 4429 2356 4429 2356 4430 2355 4430 2357 4430 2354 4431 2353 4431 2355 4431 2355 4432 2353 4432 2352 4432 2358 4433 2357 4433 2359 4433 2359 4434 2357 4434 2355 4434 2359 4435 2355 4435 2360 4435 2360 4436 2355 4436 2352 4436 2361 4437 2362 4437 2356 4437 2356 4438 2362 4438 2351 4438 2356 4439 2351 4439 2350 4439 2350 4440 2349 4440 2356 4440 2356 4441 2349 4441 2348 4441 2356 4442 2348 4442 2347 4442 661 4443 2357 4443 662 4443 662 4444 2357 4444 2358 4444 662 4445 2358 4445 663 4445 663 4446 2358 4446 2359 4446 663 4447 2359 4447 664 4447 664 4448 2359 4448 2360 4448 664 4449 2360 4449 665 4449 665 4450 2360 4450 2352 4450 665 4451 2352 4451 146 4451 658 4452 2351 4452 659 4452 659 4453 2351 4453 2362 4453 659 4454 2362 4454 660 4454 660 4455 2362 4455 666 4455 666 4456 2362 4456 2361 4456 666 4457 2361 4457 667 4457 667 4458 2361 4458 2356 4458 667 4459 2356 4459 668 4459 668 4460 2356 4460 2357 4460 668 4461 2357 4461 661 4461 110 1695 724 1695 111 1695 111 1695 724 1695 2283 1695 111 1695 2283 1695 97 1695 2287 4462 83 4462 2286 4462 2286 4463 83 4463 81 4463 2286 4464 81 4464 2285 4464 81 4465 80 4465 2285 4465 2285 4466 80 4466 76 4466 2285 4467 76 4467 2284 4467 2284 4468 76 4468 77 4468 2284 4469 77 4469 2277 4469 2277 4470 77 4470 78 4470 2277 4471 78 4471 2278 4471 2278 4472 78 4472 104 4472 2278 4473 104 4473 2280 4473 2280 4474 104 4474 102 4474 2280 4475 102 4475 2281 4475 2281 4476 102 4476 101 4476 2281 4477 101 4477 2282 4477 2282 4478 101 4478 98 4478 2282 4479 98 4479 2283 4479 2283 4480 98 4480 97 4480 83 1711 2287 1711 84 1711 84 1711 2287 1711 2273 1711 84 1711 2273 1711 66 1711 674 4481 702 4481 711 4481 674 4482 711 4482 672 4482 672 4483 711 4483 710 4483 672 4484 710 4484 673 4484 673 4485 710 4485 682 4485 682 4486 710 4486 709 4486 682 4487 709 4487 683 4487 683 4488 709 4488 684 4488 684 4489 709 4489 708 4489 684 4490 708 4490 678 4490 678 4491 708 4491 706 4491 678 4492 706 4492 679 4492 679 4493 706 4493 705 4493 679 4494 705 4494 680 4494 680 4495 705 4495 681 4495 681 4496 705 4496 704 4496 681 4497 704 4497 504 4497 504 4498 704 4498 505 4498 505 4499 704 4499 703 4499 505 4500 703 4500 506 4500 1168 1711 52 1711 701 1711 701 1711 52 1711 51 1711 52 4501 1168 4501 41 4501 41 4502 1168 4502 1167 4502 41 4503 1167 4503 42 4503 42 4504 1167 4504 1166 4504 42 4505 1166 4505 43 4505 43 4506 1166 4506 1165 4506 43 4507 1165 4507 45 4507 45 4508 1165 4508 1163 4508 45 4509 1163 4509 25 4509 25 4510 1163 4510 1162 4510 25 4511 1162 4511 26 4511 26 4512 1162 4512 1169 4512 26 4513 1169 4513 17 4513 17 4514 1169 4514 1170 4514 17 4515 1170 4515 18 4515 18 4516 1170 4516 1171 4516 18 4517 1171 4517 19 4517 19 4518 1171 4518 1172 4518 19 4519 1172 4519 12 4519 1172 1695 1158 1695 12 1695 12 1695 1158 1695 9 1695 1042 4520 2363 4520 2364 4520 2365 4521 924 4521 1038 4521 2365 4522 1038 4522 2364 4522 2364 4523 1038 4523 1041 4523 2364 4524 1041 4524 1042 4524 2363 4525 1042 4525 1118 4525 2363 4526 1118 4526 2366 4526 2366 4527 1118 4527 1117 4527 2366 4528 1117 4528 2367 4528 2367 4529 1117 4529 1116 4529 2367 4530 1116 4530 2368 4530 2368 4531 1116 4531 1943 4531 2368 4532 1943 4532 2369 4532 2369 4533 1943 4533 1846 4533 2369 4534 1846 4534 2370 4534 2371 1711 2370 1711 1728 1711 1728 1711 2370 1711 1846 1711 1733 4535 2372 4535 2373 4535 2371 4536 1728 4536 1727 4536 2371 4537 1727 4537 2373 4537 2373 4538 1727 4538 1732 4538 2373 4539 1732 4539 1733 4539 2372 4540 1733 4540 1809 4540 2372 4541 1809 4541 2374 4541 2374 4542 1809 4542 1808 4542 2374 4543 1808 4543 2375 4543 2375 4544 1808 4544 1807 4544 2375 4545 1807 4545 2376 4545 2376 4546 1807 4546 2128 4546 2376 4547 2128 4547 2377 4547 2377 4548 2128 4548 2127 4548 2377 4549 2127 4549 2378 4549 2379 2611 2378 2611 2152 2611 2152 2611 2378 2611 2127 2611 1514 4550 2380 4550 2381 4550 2379 4551 2152 4551 2247 4551 2379 4552 2247 4552 2381 4552 2381 4553 2247 4553 2249 4553 2381 4554 2249 4554 1514 4554 2380 4555 1514 4555 1513 4555 2380 4556 1513 4556 2382 4556 2382 4557 1513 4557 1511 4557 2382 4558 1511 4558 2383 4558 2383 4559 1511 4559 1436 4559 2383 4560 1436 4560 2384 4560 2384 4561 1436 4561 1435 4561 2384 4562 1435 4562 2385 4562 2385 4563 1435 4563 1319 4563 2385 4564 1319 4564 2386 4564 2387 1695 2386 1695 1293 1695 1293 1695 2386 1695 1319 1695 887 4565 2388 4565 2389 4565 2387 4566 1293 4566 1292 4566 2387 4567 1292 4567 2389 4567 2389 4568 1292 4568 1296 4568 2389 4569 1296 4569 887 4569 2388 4570 887 4570 886 4570 2388 4571 886 4571 2390 4571 2390 4572 886 4572 884 4572 2390 4573 884 4573 2391 4573 2391 4574 884 4574 809 4574 2391 4575 809 4575 2392 4575 2392 4576 809 4576 808 4576 2392 4577 808 4577 2393 4577 2393 4578 808 4578 807 4578 2393 4579 807 4579 2394 4579 2365 1782 2394 1782 924 1782 924 1782 2394 1782 807 1782 2395 1660 2396 1660 2370 1660 2370 4580 2371 4580 2395 4580 2395 4581 2371 4581 2373 4581 2395 1660 2373 1660 2397 1660 2398 1660 2399 1660 2400 1660 2400 1660 2399 1660 2401 1660 2402 1660 2403 1660 2404 1660 2404 4582 2403 4582 2405 4582 2404 1660 2405 1660 2406 1660 2406 4583 2405 4583 2407 4583 2406 1660 2407 1660 2408 1660 2370 1660 2409 1660 2369 1660 2369 4584 2409 4584 2410 4584 2411 1660 2383 1660 2412 1660 2412 1660 2383 1660 2384 1660 2412 1660 2384 1660 2413 1660 2414 1660 2367 1660 2410 1660 2410 4585 2367 4585 2368 4585 2410 4586 2368 4586 2369 4586 2384 1660 2385 1660 2413 1660 2413 4587 2385 4587 2386 4587 2413 1660 2386 1660 2398 1660 2398 1660 2386 1660 2387 1660 2398 4588 2387 4588 2399 4588 2399 4589 2387 4589 2389 4589 2399 4590 2389 4590 2415 4590 2416 1660 2379 1660 2417 1660 2417 4591 2379 4591 2381 4591 2417 1660 2381 1660 2418 1660 2418 4592 2381 4592 2380 4592 2418 4593 2380 4593 2411 4593 2411 1660 2380 1660 2382 1660 2411 1660 2382 1660 2383 1660 2419 1660 2420 1660 2421 1660 2421 1660 2420 1660 2422 1660 2408 1660 2423 1660 2406 1660 2406 1660 2423 1660 2363 1660 2406 4594 2363 4594 2414 4594 2414 4595 2363 4595 2366 4595 2414 4596 2366 4596 2367 4596 2389 1660 2388 1660 2415 1660 2415 4597 2388 4597 2390 4597 2415 1660 2390 1660 2424 1660 2424 4598 2390 4598 2391 4598 2424 1660 2391 1660 2425 1660 2425 1660 2391 1660 2392 1660 2392 1660 2393 1660 2425 1660 2425 4599 2393 4599 2394 4599 2425 1660 2394 1660 2426 1660 2426 1660 2394 1660 2365 1660 2426 1660 2365 1660 2423 1660 2423 4600 2365 4600 2364 4600 2423 4601 2364 4601 2363 4601 2427 4602 2379 4602 2421 4602 2421 1660 2379 1660 2416 1660 2421 1660 2416 1660 2419 1660 2401 1660 2399 1660 2428 1660 2428 1660 2399 1660 2429 1660 2428 1660 2429 1660 2420 1660 2420 4603 2429 4603 2430 4603 2420 4604 2430 4604 2403 4604 2427 1660 2431 1660 2379 1660 2379 1660 2431 1660 2432 1660 2379 1660 2432 1660 2378 1660 2432 1660 2433 1660 2378 1660 2378 4605 2433 4605 2434 4605 2378 1660 2434 1660 2377 1660 2377 4606 2434 4606 2435 4606 2402 1660 2436 1660 2403 1660 2403 1660 2436 1660 2437 1660 2403 1660 2437 1660 2420 1660 2420 4607 2437 4607 2438 4607 2420 1660 2438 1660 2422 1660 2422 4608 2438 4608 2439 4608 2422 1660 2439 1660 2396 1660 2396 4609 2439 4609 2440 4609 2396 4610 2440 4610 2370 4610 2370 4611 2440 4611 2441 4611 2370 1660 2441 1660 2409 1660 2373 1660 2372 1660 2397 1660 2397 1660 2372 1660 2374 1660 2397 1660 2374 1660 2442 1660 2442 1660 2374 1660 2375 1660 2442 1660 2375 1660 2435 1660 2435 4612 2375 4612 2376 4612 2435 4613 2376 4613 2377 4613 2412 4614 2443 4614 2411 4614 2411 4615 2443 4615 2444 4615 2411 4616 2444 4616 2418 4616 2418 4617 2444 4617 2445 4617 2418 4618 2445 4618 2417 4618 2417 4619 2445 4619 2446 4619 2417 4620 2446 4620 2416 4620 2416 4621 2446 4621 2447 4621 2416 4622 2447 4622 2419 4622 2419 4623 2447 4623 2448 4623 2419 4624 2448 4624 2420 4624 2420 4625 2448 4625 2449 4625 2420 4626 2449 4626 2428 4626 2428 4627 2449 4627 2450 4627 2428 4628 2450 4628 2401 4628 2401 4629 2450 4629 2451 4629 2401 4630 2451 4630 2400 4630 2400 4631 2451 4631 2452 4631 2400 4632 2452 4632 2398 4632 2398 4633 2452 4633 2453 4633 2398 4634 2453 4634 2413 4634 2413 4635 2453 4635 2454 4635 2413 4636 2454 4636 2412 4636 2412 4637 2454 4637 2443 4637 2450 1660 2449 1660 2455 1660 2455 1660 2449 1660 2448 1660 2455 1660 2448 1660 2447 1660 2453 1660 2452 1660 2455 1660 2455 1660 2452 1660 2451 1660 2455 1660 2451 1660 2450 1660 2444 1660 2443 1660 2455 1660 2455 1660 2443 1660 2454 1660 2455 1660 2454 1660 2453 1660 2447 1660 2446 1660 2455 1660 2455 1660 2446 1660 2445 1660 2455 1660 2445 1660 2444 1660 2431 4614 2456 4614 2432 4614 2432 4615 2456 4615 2457 4615 2432 4616 2457 4616 2433 4616 2433 4617 2457 4617 2458 4617 2433 4618 2458 4618 2434 4618 2434 4619 2458 4619 2459 4619 2434 4620 2459 4620 2435 4620 2435 4621 2459 4621 2460 4621 2435 4622 2460 4622 2442 4622 2442 4623 2460 4623 2461 4623 2442 4624 2461 4624 2397 4624 2397 4625 2461 4625 2462 4625 2397 4626 2462 4626 2395 4626 2395 4627 2462 4627 2463 4627 2395 4628 2463 4628 2396 4628 2396 4629 2463 4629 2464 4629 2396 4630 2464 4630 2422 4630 2422 4631 2464 4631 2465 4631 2422 4632 2465 4632 2421 4632 2421 4633 2465 4633 2466 4633 2421 4634 2466 4634 2427 4634 2427 4635 2466 4635 2467 4635 2427 4636 2467 4636 2431 4636 2431 4637 2467 4637 2456 4637 2463 1660 2462 1660 2468 1660 2468 1660 2462 1660 2461 1660 2468 1660 2461 1660 2460 1660 2466 1660 2465 1660 2468 1660 2468 1660 2465 1660 2464 1660 2468 1660 2464 1660 2463 1660 2457 1660 2456 1660 2468 1660 2468 1660 2456 1660 2467 1660 2468 1660 2467 1660 2466 1660 2460 1660 2459 1660 2468 1660 2468 1660 2459 1660 2458 1660 2468 1660 2458 1660 2457 1660 2399 4614 2469 4614 2429 4614 2429 4615 2469 4615 2470 4615 2429 4616 2470 4616 2430 4616 2430 4618 2470 4618 2471 4618 2430 4618 2471 4618 2403 4618 2403 4620 2471 4620 2472 4620 2403 4620 2472 4620 2405 4620 2405 4621 2472 4621 2473 4621 2405 4622 2473 4622 2407 4622 2407 4623 2473 4623 2474 4623 2407 4624 2474 4624 2408 4624 2408 4625 2474 4625 2475 4625 2408 4626 2475 4626 2423 4626 2423 4627 2475 4627 2476 4627 2423 4628 2476 4628 2426 4628 2426 4630 2476 4630 2477 4630 2426 4630 2477 4630 2425 4630 2425 4632 2477 4632 2478 4632 2425 4632 2478 4632 2424 4632 2424 4633 2478 4633 2479 4633 2424 4634 2479 4634 2415 4634 2415 4635 2479 4635 2480 4635 2415 4636 2480 4636 2399 4636 2399 4637 2480 4637 2469 4637 2476 4638 2475 4638 2481 4638 2481 1660 2475 1660 2474 1660 2481 1660 2474 1660 2473 1660 2479 1660 2478 1660 2481 1660 2481 4638 2478 4638 2477 4638 2481 4639 2477 4639 2476 4639 2470 4640 2469 4640 2481 4640 2481 1660 2469 1660 2480 1660 2481 1660 2480 1660 2479 1660 2473 1660 2472 1660 2481 1660 2481 4639 2472 4639 2471 4639 2481 4638 2471 4638 2470 4638 2436 4614 2482 4614 2437 4614 2437 4615 2482 4615 2483 4615 2437 4616 2483 4616 2438 4616 2438 4618 2483 4618 2484 4618 2438 4618 2484 4618 2439 4618 2439 4620 2484 4620 2485 4620 2439 4620 2485 4620 2440 4620 2440 4621 2485 4621 2486 4621 2440 4622 2486 4622 2441 4622 2441 4623 2486 4623 2487 4623 2441 4624 2487 4624 2409 4624 2409 4625 2487 4625 2488 4625 2409 4626 2488 4626 2410 4626 2410 4627 2488 4627 2489 4627 2410 4628 2489 4628 2414 4628 2414 4630 2489 4630 2490 4630 2414 4630 2490 4630 2406 4630 2406 4632 2490 4632 2491 4632 2406 4632 2491 4632 2404 4632 2404 4633 2491 4633 2492 4633 2404 4634 2492 4634 2402 4634 2402 4635 2492 4635 2493 4635 2402 4636 2493 4636 2436 4636 2436 4637 2493 4637 2482 4637 2489 4638 2488 4638 2494 4638 2494 1660 2488 1660 2487 1660 2494 1660 2487 1660 2486 1660 2492 1660 2491 1660 2494 1660 2494 4638 2491 4638 2490 4638 2494 4639 2490 4639 2489 4639 2483 4640 2482 4640 2494 4640 2494 1660 2482 1660 2493 1660 2494 1660 2493 1660 2492 1660 2486 1660 2485 1660 2494 1660 2494 4639 2485 4639 2484 4639 2494 4638 2484 4638 2483 4638

+
+
+
+
+ + + + 1 0 0 1.6e-4 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + 1 0 0 1.6e-4 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_E3M5_scaled.dae b/URDFs/sr_description/meshes/components/forearm/forearm_E3M5_scaled.dae new file mode 100644 index 0000000..2901dce --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_E3M5_scaled.dae @@ -0,0 +1,299 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:26:38 + 2025-02-20T09:26:38 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.21961 0.21961 0.21961 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.80848 0.80848 0.80848 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.21961 0.21961 0.21961 1 + + + 1 + + + + + + + + + + + + + + + + + + + + + + + -54.17936 -40.25974 125.3859 -57.38965 -35.53417 125.3859 -57.38965 -35.53417 79.0371 18.04209 65.04409 66.9738 18.44659 64.93053 66.73791 18.47225 64.92324 15 -18.04209 -65.04409 66.9738 -18.44659 -64.93053 66.73791 -18.47225 -64.92324 15 -23.49403 63.27938 69.96601 -23.08418 63.43005 68.30575 -30.08734 60.42352 15 -23.49403 63.27938 78.91601 -30.08734 60.42352 79.0371 -21.94408 63.83344 67.02143 -20.37948 64.35003 66.41958 -18.47225 64.92324 15 -21.70596 63.9148 82.01303 -23.01492 63.45521 80.70408 -23.49198 63.28014 79.0371 -28.92978 60.98621 133.4487 -23.3922 63.3171 142.3103 -20.14017 64.42533 134.3371 -30.03421 60.44995 131.41 -18.52465 64.9083 130.8625 -18.47225 64.92324 82.18693 -19.91789 64.4944 82.49215 -6.351152 67.20054 87.05348 -6.836795 67.15287 89.04183 -6.237826 67.21116 114.2949 -8.083148 67.01427 90.44866 -9.560539 66.81951 91.00827 -6.4509 67.19104 114.4395 -9.958946 66.76129 91.03259 -8.88943 66.9121 116.4459 -11.44137 66.52327 119.2432 -11.50216 66.51279 90.64778 -14.14855 66.00052 123.0042 -12.68605 66.29717 120.8699 -13.56674 66.12256 87.05348 -13.56674 66.12256 79.0371 -16.3438 65.49146 79.0371 -16.82086 65.37055 80.70408 -17.39274 65.22072 81.44828 -13.5213 66.13187 87.68331 -18.13161 65.01919 82.01407 -12.81971 66.27145 89.47142 -17.01175 65.32113 127.8924 -13.08109 66.22035 68.38063 -16.37146 65.48455 69.50442 -13.56674 66.12256 70.36898 -16.34175 65.49197 69.96601 -16.34175 65.49197 78.91601 -19.91789 64.4944 66.38987 -18.25763 64.98391 66.79972 -16.97331 65.33113 67.93982 -11.83474 66.45441 66.9738 -10.35735 66.70064 66.41419 -6.228115 67.21206 15 -9.958946 66.76129 66.38987 -8.415726 66.97332 66.77468 -7.098176 67.12575 67.95104 -6.396586 67.19624 69.73914 -6.351152 67.20054 70.36898 -6.228115 67.21206 79.0371 -6.351152 67.20054 79.0371 23.49403 -63.27938 69.96601 23.08418 -63.43005 68.30575 30.08734 -60.42352 15 21.94408 -63.83344 67.02143 20.37948 -64.35003 66.41958 18.47225 -64.92324 15 28.92978 -60.98621 133.4487 23.3922 -63.3171 142.3103 20.14017 -64.42533 134.3371 30.03421 -60.44995 131.41 21.70596 -63.9148 82.81304 19.91789 -64.4944 83.29216 18.45389 -64.92845 82.97875 18.52465 -64.9083 130.8625 23.01492 -63.45521 81.50408 23.37139 -63.32479 80.64452 30.08734 -60.42352 79.0371 23.49403 -63.27938 79.71601 23.49403 -63.27938 79.0371 6.351152 -67.20054 87.05348 6.836795 -67.15287 89.04183 6.237826 -67.21116 114.2949 8.083148 -67.01427 90.44866 9.560539 -66.81951 91.00827 6.4509 -67.19104 114.4395 9.958946 -66.76129 91.03259 8.88943 -66.9121 116.4459 11.44137 -66.52327 119.2432 11.50216 -66.51279 90.64778 14.14855 -66.00052 123.0042 12.68605 -66.29717 120.8699 16.34175 -65.49197 79.71601 16.46446 -65.46122 80.64478 13.56674 -66.12256 79.0371 13.56674 -66.12256 87.05348 16.82086 -65.37055 81.50408 17.39271 -65.22073 82.24826 13.5213 -66.13187 87.68331 18.12982 -65.01969 82.81304 12.81971 -66.27145 89.47142 17.01175 -65.32113 127.8924 13.08109 -66.22035 68.38063 16.37146 -65.48455 69.50442 13.56674 -66.12256 70.36898 16.34175 -65.49197 69.96601 16.34175 -65.49197 79.0371 19.91789 -64.4944 66.38987 18.25763 -64.98391 66.79972 16.97331 -65.33113 67.93982 11.83474 -66.45441 66.9738 10.35735 -66.70064 66.41419 6.228115 -67.21206 15 9.958946 -66.76129 66.38987 8.415726 -66.97332 66.77468 7.098176 -67.12575 67.95104 6.396586 -67.19624 69.73914 6.351152 -67.20054 70.36898 6.228115 -67.21206 79.0371 6.351152 -67.20054 79.0371 -18.47225 -64.92324 79.0371 -13.56674 -66.12256 79.0371 -13.56674 -66.12256 87.05348 -18.52401 -64.9085 130.8614 -13.08109 -66.22035 89.04183 -11.83474 -66.45441 90.44866 -10.35735 -66.70064 91.00827 -11.05462 -66.58863 118.773 -11.94758 -66.43422 119.884 -14.7961 -65.85837 124.0268 -15.61132 -65.66991 125.3859 -17.07484 -65.30467 128.0111 -8.408019 -66.97429 115.9986 -9.958946 -66.76129 91.03259 -6.252565 -67.20979 114.3045 -8.415726 -66.97332 90.64778 -7.098176 -67.12575 89.47142 -6.396586 -67.19624 87.68331 -6.351152 -67.20054 87.05348 -6.228115 -67.21206 79.0371 -13.56674 -66.12256 70.36898 -16.3101 -65.49985 70.36898 -13.5213 -66.13187 69.73914 -16.79574 -65.37701 68.38063 -6.351152 -67.20054 79.0371 -6.351152 -67.20054 70.36898 -6.228115 -67.21206 15 -6.836795 -67.15287 68.38063 -8.083148 -67.01427 66.9738 -9.560539 -66.81951 66.41419 -9.958946 -66.76129 66.38987 -11.50216 -66.51279 66.77468 -12.81971 -66.27145 67.95104 -1.167233 -67.48991 112.2894 -0.3984075 -67.49883 93.80031 -2.45114e-4 -67.5 112.2894 0 -67.5 93.82463 1.169559 -67.48987 112.2894 5.554087 -67.27111 113.8638 4.24417 -67.36644 113.178 1.543219 -67.48236 93.43982 2.90683 -67.43738 112.6674 1.823095 -67.47538 112.3938 2.860769 -67.43935 92.26345 3.562358 -67.40593 90.47535 3.607792 -67.40352 89.84552 -3.607792 -67.40352 89.84552 -3.12215 -67.42776 91.83387 -6.183443 -67.21618 112.2894 -1.875798 -67.47393 93.24069 -6.111258 -67.22278 112.2894 -6.039067 -67.22931 112.2894 -2.534783 -67.45239 112.5594 -3.446495 -67.41195 112.8504 -5.273652 -67.29367 113.7011 -6.11135 -67.22277 112.2962 -3.607792 -67.40352 79.0371 -5.810872 -67.24942 114.0195 3.12215 -67.42776 68.38063 3.607792 -67.40352 70.36898 3.607792 -67.40352 79.0371 1.875798 -67.47393 66.9738 0.3984075 -67.49883 66.41419 0 -67.5 66.38987 -1.543219 -67.48236 66.77468 -2.860769 -67.43935 67.95104 -3.562358 -67.40593 69.73914 -3.607792 -67.40352 70.36898 -64.4944 -19.91789 83.28839 -65.95397 -14.364 123.3469 -66.3454 -12.43134 120.5131 -64.95092 -18.37467 82.90358 -63.88494 -21.79369 82.70446 -62.91778 -24.4459 140.7922 -64.37001 -20.3163 83.26406 -63.3171 -23.3922 142.3103 -64.42533 -20.14017 134.3371 -65.32113 -17.01175 127.8924 -65.66991 -15.61132 125.3859 -63.2845 -23.48025 69.73914 -63.5404 -22.77866 67.95104 -62.94188 -24.38381 15 -63.26763 -23.52568 70.36898 -63.44609 -23.04004 81.29763 -63.26763 -23.52568 79.30928 -62.94188 -24.38381 79.0371 -63.26763 -23.52568 79.0371 -63.99742 -21.46111 66.77468 -64.4944 -19.91789 66.38987 -66.35069 -12.40309 15 -65.37701 -16.79574 68.38063 -66.33957 -12.4624 67.50989 -65.04409 -18.04209 66.9738 -64.6161 -19.51948 66.41419 -65.49985 -16.3101 70.36898 -65.49985 -16.3101 79.0371 -66.12256 -13.56674 79.0371 -66.12256 -13.56674 70.36898 -66.13187 -13.5213 69.73914 -66.27145 -12.81971 67.95104 -65.49985 -16.3101 79.30928 -65.48853 -16.35553 79.9391 -66.12256 -13.56674 87.05348 -65.30931 -17.05712 81.72721 -66.22035 -13.08109 89.04183 -66.33482 -12.4877 89.88534 -67.21618 -6.183443 112.2894 -67.22278 -6.111258 112.2894 -67.49883 -0.3984075 93.80031 -67.47393 -1.875798 93.24069 -67.42776 -3.12215 91.83387 -67.12575 -7.098176 89.47142 -66.97332 -8.415726 90.64778 -67.19624 -6.396586 87.68331 -67.40352 -3.607792 89.84552 -67.20054 -6.351152 87.05348 -66.76129 -9.958946 91.03259 -66.70064 -10.35735 91.00827 -66.45441 -11.83474 90.44866 -67.48991 -1.167233 112.2894 -67.22931 -6.039067 112.2894 -67.45239 -2.534797 112.5594 -67.41081 -3.468934 112.8586 -66.43422 -11.94758 119.884 -66.82285 -9.537213 117.0881 -66.97679 -8.388092 115.9806 -67.11339 -7.214129 114.9977 -67.1584 -6.782433 114.6742 -67.22277 -6.11135 112.2962 -67.25167 -5.784763 114.0033 -67.29368 -5.27362 113.7011 -66.51279 -11.50216 66.77468 -66.76129 -9.958946 66.38987 -67.5 0 15 -66.81951 -9.560539 66.41419 -67.01427 -8.083148 66.9738 -67.15287 -6.836795 68.38063 -67.40593 -3.562358 69.73914 -67.20054 -6.351152 70.36898 -67.20054 -6.351152 79.0371 -67.40352 -3.607792 79.0371 -67.40352 -3.607792 70.36898 -67.43935 2.860769 92.26345 -67.48236 1.543219 93.43982 -67.01427 8.083148 90.44866 -66.81951 9.560539 91.00827 -66.33957 12.4624 89.91257 -66.51279 11.50216 90.64778 -66.34278 12.44536 120.5421 -66.76129 9.958946 91.03259 -67.43739 2.906622 112.6673 -67.36627 4.246928 113.1792 -67.46885 2.050065 112.4406 -67.5 0 93.82463 -67.5 0 112.2894 -67.48987 1.169559 112.2894 -67.27111 5.554144 113.8638 -67.16238 6.74278 114.6455 -66.89817 8.993705 116.5461 -66.51738 11.47558 119.2859 -67.43935 -2.860769 67.95104 -67.48236 -1.543219 66.77468 -67.5 0 66.38987 -66.35069 12.40309 15 -67.49883 0.3984075 66.41419 -67.47393 1.875798 66.9738 -67.42776 3.12215 68.38063 -66.97332 8.415726 66.77468 -66.76129 9.958946 66.38987 -66.70064 10.35735 66.41419 -66.45441 11.83474 66.9738 -66.33482 12.4877 67.53711 -67.40352 3.607792 70.36898 -67.19624 6.396586 69.73914 -67.12575 7.098176 67.95104 -67.40593 3.562358 90.47535 -67.15287 6.836795 89.04183 -67.40352 3.607792 89.84552 -67.20054 6.351152 87.05348 -67.40352 3.607792 79.0371 -67.20054 6.351152 79.0371 -67.20054 6.351152 70.36898 -66.13187 13.5213 87.68331 -66.27145 12.81971 89.47142 -62.91778 24.4459 140.7922 -62.94188 24.38381 79.0371 -66.12256 13.56674 87.05348 -66.12256 13.56674 79.0371 -66.2972 12.68595 120.87 -65.99694 14.16532 123.0301 -63.3171 23.3922 142.3103 -64.40789 20.19592 134.4627 -65.30467 17.07484 128.0111 -64.4944 19.91789 66.38987 -62.94188 24.38381 15 -64.2875 20.5759 66.45066 -63.76339 22.14678 67.17219 -63.35965 23.27671 71.1933 -63.5103 22.86247 71.9922 -63.62635 22.53746 67.53502 -63.33151 23.35317 68.97166 -63.28537 23.47789 70.30688 -64.69395 19.25988 73.48136 -64.4944 19.91789 73.54216 -63.95806 21.57815 73.1323 -65.14099 17.689 72.75983 -65.24583 17.29832 72.39701 -66.12256 13.56674 70.36898 -65.45665 16.48261 70.96036 -66.22035 13.08109 68.38063 -65.48794 16.35789 69.62514 -65.33113 16.97331 67.93982 -64.98391 18.25763 66.79972 64.4944 19.91789 83.28839 65.95397 14.364 123.3469 66.3454 12.43134 120.5131 64.95092 18.37467 82.90358 63.88494 21.79369 82.70446 62.91778 24.4459 140.7922 64.37001 20.3163 83.26406 63.3171 23.3922 142.3103 64.42533 20.14017 134.3371 65.32113 17.01175 127.8924 65.66991 15.61132 125.3859 63.2845 23.48025 69.73914 63.5404 22.77866 67.95104 62.94188 24.38381 15 63.26763 23.52568 70.36898 63.44609 23.04004 81.29763 63.26763 23.52568 79.30928 62.94188 24.38381 79.0371 63.26763 23.52568 79.0371 63.99742 21.46111 66.77468 64.4944 19.91789 66.38987 66.35069 12.40309 15 65.37701 16.79574 68.38063 66.33957 12.4624 67.50989 65.04409 18.04209 66.9738 64.6161 19.51948 66.41419 65.49985 16.3101 70.36898 65.49985 16.3101 79.0371 66.12256 13.56674 79.0371 66.12256 13.56674 70.36898 66.13187 13.5213 69.73914 66.27145 12.81971 67.95104 65.49985 16.3101 79.30928 65.48853 16.35553 79.9391 66.12256 13.56674 87.05348 65.30931 17.05712 81.72721 66.22035 13.08109 89.04183 66.33482 12.4877 89.88534 67.21618 6.183443 112.2894 67.22278 6.111258 112.2894 67.49883 0.3984075 93.80031 67.47393 1.875798 93.24069 67.42776 3.12215 91.83387 67.12575 7.098176 89.47142 66.97332 8.415726 90.64778 67.19624 6.396586 87.68331 67.40352 3.607792 89.84552 67.20054 6.351152 87.05348 66.76129 9.958946 91.03259 66.70064 10.35735 91.00827 66.45441 11.83474 90.44866 67.48991 1.167233 112.2894 67.22931 6.039067 112.2894 67.45239 2.534797 112.5594 67.41081 3.468934 112.8586 66.43422 11.94758 119.884 66.82285 9.537213 117.0881 66.97679 8.388092 115.9806 67.11339 7.214129 114.9977 67.1584 6.782433 114.6742 67.22277 6.11135 112.2962 67.25167 5.784763 114.0033 67.29368 5.27362 113.7011 66.51279 11.50216 66.77468 66.76129 9.958946 66.38987 67.5 0 15 66.81951 9.560539 66.41419 67.01427 8.083148 66.9738 67.15287 6.836795 68.38063 67.40593 3.562358 69.73914 67.20054 6.351152 70.36898 67.20054 6.351152 79.0371 67.40352 3.607792 79.0371 67.40352 3.607792 70.36898 67.43935 -2.860769 92.26345 67.48236 -1.543219 93.43982 67.01427 -8.083148 90.44866 66.81951 -9.560539 91.00827 66.33957 -12.4624 89.91257 66.51279 -11.50216 90.64778 66.34278 -12.44536 120.5421 66.76129 -9.958946 91.03259 67.43739 -2.906622 112.6673 67.36627 -4.246928 113.1792 67.46885 -2.050065 112.4406 67.5 0 93.82463 67.5 0 112.2894 67.48987 -1.169559 112.2894 67.27111 -5.554144 113.8638 67.16238 -6.74278 114.6455 66.89817 -8.993705 116.5461 66.51738 -11.47558 119.2859 67.43935 2.860769 67.95104 67.48236 1.543219 66.77468 67.5 0 66.38987 66.35069 -12.40309 15 67.49883 -0.3984075 66.41419 67.47393 -1.875798 66.9738 67.42776 -3.12215 68.38063 66.97332 -8.415726 66.77468 66.76129 -9.958946 66.38987 66.70064 -10.35735 66.41419 66.45441 -11.83474 66.9738 66.33482 -12.4877 67.53711 67.40352 -3.607792 70.36898 67.19624 -6.396586 69.73914 67.12575 -7.098176 67.95104 67.40593 -3.562358 90.47535 67.15287 -6.836795 89.04183 67.40352 -3.607792 89.84552 67.20054 -6.351152 87.05348 67.40352 -3.607792 79.0371 67.20054 -6.351152 79.0371 67.20054 -6.351152 70.36898 66.13187 -13.5213 87.68331 66.27145 -12.81971 89.47142 62.91778 -24.4459 140.7922 62.94188 -24.38381 79.0371 66.12256 -13.56674 87.05348 66.12256 -13.56674 79.0371 66.2972 -12.68595 120.87 65.99694 -14.16532 123.0301 63.3171 -23.3922 142.3103 64.40789 -20.19592 134.4627 65.30467 -17.07484 128.0111 64.4944 -19.91789 66.38987 62.94188 -24.38381 15 64.2875 -20.5759 66.45066 63.76339 -22.14678 67.17219 63.35965 -23.27671 71.1933 63.5103 -22.86247 71.9922 63.62635 -22.53746 67.53502 63.33151 -23.35317 68.97166 63.28537 -23.47789 70.30688 64.69395 -19.25988 73.48136 64.4944 -19.91789 73.54216 63.95806 -21.57815 73.1323 65.14099 -17.689 72.75983 65.24583 -17.29832 72.39701 66.12256 -13.56674 70.36898 65.45665 -16.48261 70.96036 66.22035 -13.08109 68.38063 65.48794 -16.35789 69.62514 65.33113 -16.97331 67.93982 64.98391 -18.25763 66.79972 18.47225 64.92324 79.0371 13.56674 66.12256 79.0371 13.56674 66.12256 87.05348 18.52401 64.9085 130.8614 13.08109 66.22035 89.04183 11.83474 66.45441 90.44866 10.35735 66.70064 91.00827 11.05462 66.58863 118.773 11.94758 66.43422 119.884 14.7961 65.85837 124.0268 15.61132 65.66991 125.3859 17.07484 65.30467 128.0111 8.408019 66.97429 115.9986 9.958946 66.76129 91.03259 6.252565 67.20979 114.3045 8.415726 66.97332 90.64778 7.098176 67.12575 89.47142 6.396586 67.19624 87.68331 6.351152 67.20054 87.05348 6.228115 67.21206 79.0371 13.56674 66.12256 70.36898 16.7965 65.37681 72.35877 16.53583 65.44323 71.75149 16.3101 65.49985 70.36898 13.5213 66.13187 69.73914 16.79574 65.37701 68.38063 6.351152 67.20054 79.0371 6.351152 67.20054 70.36898 6.228115 67.21206 15 6.836795 67.15287 68.38063 8.083148 67.01427 66.9738 9.560539 66.81951 66.41419 9.958946 66.76129 66.38987 11.50216 66.51279 66.77468 12.81971 66.27145 67.95104 1.167233 67.48991 112.2894 0.3984075 67.49883 93.80031 2.45114e-4 67.5 112.2894 0 67.5 93.82463 -1.169559 67.48987 112.2894 -5.554087 67.27111 113.8638 -4.24417 67.36644 113.178 -1.543219 67.48236 93.43982 -2.90683 67.43738 112.6674 -1.823095 67.47538 112.3938 -2.860769 67.43935 92.26345 -3.562358 67.40593 90.47535 -3.607792 67.40352 89.84552 3.607792 67.40352 89.84552 3.12215 67.42776 91.83387 6.183443 67.21618 112.2894 1.875798 67.47393 93.24069 6.111258 67.22278 112.2894 6.039067 67.22931 112.2894 2.534783 67.45239 112.5594 3.446495 67.41195 112.8504 5.273652 67.29367 113.7011 6.11135 67.22277 112.2962 3.607792 67.40352 79.0371 5.810872 67.24942 114.0195 -3.12215 67.42776 68.38063 -3.607792 67.40352 70.36898 -3.607792 67.40352 79.0371 -1.875798 67.47393 66.9738 -0.3984075 67.49883 66.41419 0 67.5 66.38987 1.543219 67.48236 66.77468 2.860769 67.43935 67.95104 3.562358 67.40593 69.73914 3.607792 67.40352 70.36898 -60.44995 30.03421 131.41 -59.67585 31.5443 128.6687 -59.26321 32.31287 127.4972 -58.70201 33.32153 126.3137 -60.98621 28.92978 133.4487 -58.37377 33.89326 125.8438 -57.84279 34.79169 125.3859 -57.38965 35.53417 79.0371 -57.84279 -34.79169 125.3859 -58.37377 -33.89326 125.8438 -58.70201 -33.32153 126.3137 -59.26321 -32.31287 127.4972 -59.67585 -31.5443 128.6687 -60.44995 -30.03421 131.41 -60.98621 -28.92978 133.4487 -51.09124 -44.11276 125.3859 -49.8831 -45.47445 79.0371 -49.8831 -45.47445 125.3859 -47.72971 -47.72971 125.3859 -40.67784 -53.86616 79.0371 -44.11276 -51.09124 125.3859 -33.32153 -58.70201 126.3137 -33.89326 -58.37377 125.8438 -30.08734 -60.42352 79.0371 -30.03421 -60.44995 131.41 -31.5443 -59.67585 128.6687 -32.31287 -59.26321 127.4972 -34.79169 -57.84279 125.3859 -40.25974 -54.17936 125.3859 -40.67784 -53.86616 125.3859 -23.3922 -63.3171 142.3103 -28.92978 -60.98621 133.4487 -20.19592 -64.40789 134.4627 34.79169 -57.84279 125.3859 40.25974 -54.17936 125.3859 40.67784 -53.86616 79.0371 33.89326 -58.37377 125.8438 33.32153 -58.70201 126.3137 32.31287 -59.26321 127.4972 31.5443 -59.67585 128.6687 49.8831 -45.47445 125.3859 47.72971 -47.72971 125.3859 49.8831 -45.47445 79.0371 44.11276 -51.09124 125.3859 40.67784 -53.86616 125.3859 57.38965 -35.53417 79.0371 54.17936 -40.25974 125.3859 51.09124 -44.11276 125.3859 60.44995 -30.03421 131.41 59.67585 -31.5443 128.6687 59.26321 -32.31287 127.4972 58.70201 -33.32153 126.3137 60.98621 -28.92978 133.4487 58.37377 -33.89326 125.8438 57.84279 -34.79169 125.3859 57.38965 -35.53417 125.3859 58.37377 33.89326 125.8438 58.70201 33.32153 126.3137 59.26321 32.31287 127.4972 59.67585 31.5443 128.6687 60.44995 30.03421 131.41 60.98621 28.92978 133.4487 49.8831 45.47445 125.3859 51.09124 44.11276 125.3859 49.8831 45.47445 79.0371 54.17936 40.25974 125.3859 57.38965 35.53417 79.0371 57.38965 35.53417 125.3859 57.84279 34.79169 125.3859 47.72971 47.72971 125.3859 40.67784 53.86616 79.0371 44.11276 51.09124 125.3859 33.32153 58.70201 126.3137 33.89326 58.37377 125.8438 30.08734 60.42352 79.0371 30.03421 60.44995 131.41 31.5443 59.67585 128.6687 32.31287 59.26321 127.4972 34.79169 57.84279 125.3859 40.25974 54.17936 125.3859 40.67784 53.86616 125.3859 23.3922 63.3171 142.3103 28.92978 60.98621 133.4487 20.19592 64.40789 134.4627 -34.79169 57.84279 125.3859 -40.25974 54.17936 125.3859 -40.67784 53.86616 79.0371 -33.89326 58.37377 125.8438 -33.32153 58.70201 126.3137 -32.31287 59.26321 127.4972 -31.5443 59.67585 128.6687 -49.8831 45.47445 125.3859 -47.72971 47.72971 125.3859 -49.8831 45.47445 79.0371 -44.11276 51.09124 125.3859 -40.67784 53.86616 125.3859 -57.38965 35.53417 125.3859 -54.17936 40.25974 125.3859 -51.09124 44.11276 125.3859 -19.51948 -64.6161 66.41419 -19.91789 -64.4944 66.38987 -30.08734 -60.42352 15 -21.46111 -63.99742 66.77468 -22.77866 -63.5404 67.95104 -23.48025 -63.2845 69.73914 -23.52568 -63.26763 70.36898 -23.31173 -63.34677 71.71619 -23.03884 -63.44653 72.35961 -19.91789 -64.4944 74.34809 -19.34998 -64.66706 74.29843 -18.19425 -65.00169 73.86145 -17.19825 -65.27228 72.97701 -16.53583 -65.44323 71.75149 -22.68825 -63.57274 72.91138 -21.72584 -63.90804 73.80889 -20.55556 -64.29401 74.28534 19.51948 64.6161 66.41419 19.91789 64.4944 66.38987 30.08734 60.42352 15 23.31173 63.34677 71.71619 22.68825 63.57274 72.91138 23.52568 63.26763 70.36898 21.46111 63.99742 66.77468 22.77866 63.5404 67.95104 23.48025 63.2845 69.73914 19.91789 64.4944 74.34809 19.34998 64.66706 74.29843 18.19425 65.00169 73.86145 17.19825 65.27228 72.97701 21.72584 63.90804 73.80889 21.46014 63.99775 73.96379 20.55556 64.29401 74.28534 40.67784 -53.86616 15 49.8831 -45.47445 15 57.38965 -35.53417 15 -57.38965 -35.53417 15 -49.8831 -45.47445 15 -40.67784 -53.86616 15 -40.67784 53.86616 15 -49.8831 45.47445 15 -57.38965 35.53417 15 57.38965 35.53417 15 49.8831 45.47445 15 40.67784 53.86616 15 -19.91789 61.34759 66.38987 -18.25763 61.86201 66.79972 -16.97331 62.22666 67.93982 -16.37146 62.3877 69.50442 -16.34175 62.39549 69.96601 23.52568 60.05657 70.36898 16.3101 62.40377 70.36898 16.79574 62.27482 72.35733 18.04209 61.92522 73.76416 19.51948 61.47552 74.32377 21.73138 60.72888 72.35853 19.91789 61.34759 74.34809 21.46111 60.82492 73.96328 22.77866 60.34387 72.78691 23.48025 60.07435 70.99881 23.48025 60.07435 69.73914 21.73138 60.72888 68.37943 22.77866 60.34387 67.95104 16.79574 62.27482 68.38063 18.04209 61.92522 66.9738 19.51948 61.47552 66.41419 19.91789 61.34759 66.38987 21.46111 60.82492 66.77468 19.91789 -61.34759 66.38987 18.25763 -61.86201 66.79972 16.97331 -62.22666 67.93982 16.37146 -62.3877 69.50442 16.34175 -62.39549 69.96601 31.78346 60.38682 163.0988 31.55347 60.50772 162.9781 31.28062 60.03408 163.7294 31.06068 60.15168 163.6045 30.87703 60.02382 164.5117 30.66177 60.13317 164.3808 35.32075 63.98178 158.4084 35.3044 63.58478 158.8612 36.09204 63.13451 158.8612 35.45715 64.71302 157.0632 36.68735 64.17587 156.6277 35.53745 64.9111 156.3762 36.72098 64.23468 156.376 35.57065 64.96789 156.081 35.62046 65.02685 155.6084 36.79262 64.36 154.0127 35.74411 64.94372 153.9078 35.75244 64.88057 153.5937 36.72977 64.25007 153.2964 35.75524 64.80696 153.2964 35.3044 61.75672 160.693 34.41383 58.0688 165.5978 34.50201 58.17895 164.8999 32.74604 59.21495 164.4735 34.69798 58.47667 164.3167 33.14228 59.53355 163.8373 34.41276 58.06903 165.6352 32.46221 59.18154 165.236 35.75533 62.54551 144.9456 32.82767 58.84353 169.3912 31.15954 59.0004 172.4238 33.09008 58.29442 171.7254 30.18883 58.64705 174.5521 32.93176 57.50651 174.595 27.41092 59.50946 172.9661 27.29728 59.50672 172.977 27.27444 59.11188 174.2801 27.0103 59.90027 171.6782 29.39522 59.38836 172.724 30.0237 59.77579 170.6217 27.38759 59.10691 174.2946 30.39362 59.90347 169.3411 32.57001 59.0886 168.1951 28.74721 60.16313 170.1029 26.8957 60.13811 170.8685 26.61948 60.3533 170.0945 26.51206 60.34035 170.1445 26.78428 60.12715 170.9089 32.2444 59.3005 167.0055 29.49382 60.26657 168.6383 24.20895 61.86205 162.2315 25.03869 61.33389 165.7647 27.71584 61.11264 165.3099 29.66788 60.6006 163.8167 27.66046 61.33748 162.917 25.9414 61.72346 162.4318 30.44587 61.02665 162.4581 30.02029 60.66045 163.0684 28.1779 61.84941 161.6337 27.89956 61.46664 162.2169 26.2097 62.28138 161.2008 26.06681 61.89195 161.7643 24.20895 62.43314 161.0488 24.20895 62.04775 161.5919 35.25986 61.6238 160.8517 31.55347 64.10159 159.377 33.77477 63.96089 159.2285 33.51736 64.49612 158.7755 31.53376 64.61627 158.8612 33.51281 66.03776 154.8087 33.43301 65.86785 153.3504 32.94177 65.96964 153.3255 33.54008 65.85172 156.2695 33.53008 65.33204 157.6335 34.83745 65.35348 153.4774 31.47326 65.14685 158.2487 31.27499 65.94998 156.7648 31.05907 66.28945 155.0798 30.92849 66.09627 153.2964 33.43893 65.78018 153.0356 30.92411 66.00833 152.971 27.13137 58.80586 175.2901 26.98827 58.49984 176.3 29.9433 58.11686 176.3 32.69881 56.98496 176.3 32.81539 57.24568 175.4475 30.18883 58.64706 174.5521 58.94332 42.59445 158.8612 63.13451 36.09204 158.8612 64.17587 36.68735 156.6277 54.08511 48.61485 158.8612 59.91554 43.29701 156.6277 43.29701 59.91554 156.6277 42.59445 58.94332 158.8612 49.41671 54.97719 156.6277 48.61485 54.08511 158.8612 54.97719 49.41671 156.6277 51.42277 51.42277 158.8612 55.13493 49.5585 154.0127 49.5585 55.13493 154.0127 43.42124 60.08745 154.0127 64.23468 36.72098 156.376 60.08745 43.42124 154.0127 64.36 36.79262 154.0127 64.25007 36.72977 153.2964 59.98481 43.34707 153.2964 43.34707 59.98481 153.2964 49.47385 55.04076 153.2964 52.33138 52.33138 153.2964 55.04076 49.47385 153.2964 40.55106 54.5714 164.3255 58.47667 34.69798 164.3167 61.36949 35.19147 161.1456 61.75672 35.3044 160.693 44.43195 51.46094 164.3255 48.07508 48.07508 164.3255 51.46094 44.43195 164.3255 54.5714 40.55106 164.3255 58.0688 34.41383 165.5978 58.17895 34.50201 164.8999 54.28056 40.33494 164.9363 40.25974 54.17936 165.6352 58.06903 34.41276 165.6352 54.17936 40.25974 165.6352 51.09124 44.11276 165.6352 51.18667 44.19515 164.9363 47.72971 47.72971 165.6352 47.81886 47.81886 164.9363 44.11276 51.09124 165.6352 44.19515 51.18667 164.9363 40.33494 54.28056 164.9363 34.65184 57.92668 167.0055 38.81745 55.22187 167.0055 43.43542 51.66831 167.0055 47.72971 47.72971 167.0055 51.66831 43.43542 167.0055 55.22187 38.81745 167.0055 57.92668 34.65184 167.0055 59.18154 32.46221 165.236 59.3005 32.2444 167.0055 60.02382 30.87703 164.5117 58.2919 33.09074 171.7348 58.84353 32.82767 169.3912 59.0886 32.57001 168.1951 56.86975 34.01958 174.595 57.50651 32.93176 174.595 57.65753 34.49084 170.8728 54.96529 38.6371 170.8728 54.21429 38.10919 174.595 51.42824 43.23361 170.8728 50.72557 42.6429 174.595 47.50794 47.50794 170.8728 46.85883 46.85883 174.595 43.23361 51.42824 170.8728 42.6429 50.72557 174.595 38.6371 54.96529 170.8728 38.10919 54.21429 174.595 34.49084 57.65753 170.8728 34.01958 56.86975 174.595 42.11855 50.42346 176.3 57.24568 32.81539 175.4475 50.42346 42.11855 176.3 56.98496 32.69881 176.3 23.20245 63.53452 143.8368 24.08531 63.26271 142.8331 23.73025 63.24323 142.5781 19.50971 63.88028 144.5726 19.50971 63.93689 145.3225 20.86254 63.89125 145.154 20.67897 63.83751 144.46 22.11971 63.75252 144.6417 21.75208 63.72028 144.0062 22.66269 63.53997 143.2591 29.34397 60.86169 133.7189 30.46326 60.3138 131.6807 30.92411 60.3106 131.9328 29.78696 60.86275 133.9716 32.29798 59.52149 129.1894 32.9263 59.11747 128.0122 33.72265 58.59564 126.8136 35.30989 60.54995 136.648 35.00454 58.68065 129.1401 34.18051 58.30122 126.3319 34.87965 57.8614 125.8786 34.02798 58.31922 126.0903 34.87483 57.8547 125.8436 33.5115 58.62471 126.567 32.60567 59.15124 127.7602 31.90546 59.54679 128.9364 57.8614 34.87965 125.8786 57.8547 34.87483 125.8436 54.22198 40.2914 125.8436 40.2914 54.22198 125.8436 62.54551 35.75533 144.9456 60.24984 35.25805 135.4346 58.68065 35.00454 129.1401 44.14745 51.13142 125.8436 47.76725 47.76725 125.8436 51.13142 44.14745 125.8436 -26.98827 58.49984 176.3 -27.13137 58.80586 175.2901 -27.27444 59.11188 174.2801 -27.0103 59.90027 171.6782 -27.29728 59.50672 172.977 -24.20895 61.86205 162.2315 -25.05305 61.32456 165.8155 -26.51206 60.34035 170.1445 -26.78428 60.12715 170.9089 -24.20895 62.43314 161.0488 -24.20895 62.04775 161.5919 -31.55347 60.50772 162.9781 -30.44587 61.02665 162.4581 -31.55347 64.10159 159.377 -28.1779 61.84941 161.6337 -31.53376 64.61627 158.8612 -26.2097 62.28138 161.2008 -31.46271 65.21908 158.1503 -31.27001 65.96113 156.7341 -31.04291 66.29548 154.8999 -30.92849 66.09627 153.2964 -19.50971 63.93689 145.3225 -20.86254 63.89125 145.154 -22.11971 63.75252 144.6417 -30.92411 66.00833 152.971 -23.20245 63.53452 143.8368 -24.08531 63.26271 142.8331 -29.78696 60.86275 133.9716 -30.92411 60.3106 131.9328 -19.50971 63.88028 144.5726 17.3095 64.65409 137.8018 12.16378 66.07304 125.3859 12.02586 66.10384 125.1164 -17.94182 64.44231 139.6548 15.83876 65.11434 133.7745 -11.03618 66.31406 123.277 -14.01748 65.62306 129.3233 -15.04126 65.34533 131.7533 -7.622066 66.89653 118.1804 -10.43085 66.43339 122.2329 8.211158 66.81163 118.9233 9.70931 66.56651 121.0681 -7.272554 66.94385 117.7663 6.896834 66.99221 117.3432 4.767905 67.21722 115.3744 -1.179931 67.40985 113.6889 4.335757 67.25278 115.0632 1.92587e-4 67.4224 113.5791 1.902435 67.38977 113.8645 -2.389749 67.37091 114.0295 -4.158677 67.26637 114.9443 -4.5666 67.2342 115.2257 19.40907 64.53045 137.0567 14.6184 65.87027 125.3859 17.91459 64.99813 132.9645 -30.87703 60.02382 164.5117 -30.66177 60.13317 164.3808 -31.28062 60.03408 163.7294 -31.06068 60.15168 163.6045 -31.78346 60.38682 163.0988 -35.75524 64.80696 153.2964 -36.72977 64.25007 153.2964 -35.75244 64.88057 153.5937 -36.79262 64.36 154.0127 -35.64012 65.03868 155.426 -36.72098 64.23468 156.376 -35.53733 64.91136 156.3759 -36.68735 64.17587 156.6277 -35.47148 64.75641 156.9391 -35.32075 63.98178 158.4084 -36.09204 63.13451 158.8612 -35.3044 63.58478 158.8612 -35.3044 61.75672 160.693 -34.41383 58.0688 165.5978 -34.41276 58.06903 165.6352 -32.46221 59.18154 165.236 -34.50201 58.17895 164.8999 -32.74604 59.21495 164.4735 -34.69798 58.47667 164.3167 -33.14228 59.53355 163.8373 -35.75533 62.54551 144.9456 -27.38759 59.10691 174.2946 -31.15954 59.0004 172.4238 -30.0237 59.77579 170.6217 -33.09074 58.2919 171.7348 -32.82767 58.84353 169.3912 -29.39522 59.38836 172.724 -27.41092 59.50946 172.9661 -32.93176 57.50651 174.595 -30.18883 58.64705 174.5521 -28.74721 60.16313 170.1029 -30.39362 59.90347 169.3411 -29.49382 60.26657 168.6383 -32.57001 59.0886 168.1951 -32.2444 59.3005 167.0055 -26.8957 60.13811 170.8685 -26.61948 60.3533 170.0945 -27.71584 61.11264 165.3099 -25.9414 61.72346 162.4318 -27.66046 61.33748 162.917 -29.66788 60.6006 163.8167 -30.02029 60.66045 163.0684 -27.89956 61.46664 162.2169 -26.06681 61.89195 161.7643 -35.19147 61.36949 161.1456 -33.86106 63.94409 159.2149 -33.51735 64.49607 158.7754 -33.53008 65.33204 157.6335 -33.43306 65.86829 153.3517 -34.78545 65.37866 153.4737 -33.51281 66.03776 154.8087 -33.54008 65.85172 156.2695 -32.92477 65.9726 153.3248 -33.43893 65.78018 153.0356 -29.93232 58.11977 176.3 -30.18883 58.64706 174.5521 -32.81539 57.24568 175.4475 -29.9433 58.11686 176.3 -32.69881 56.98496 176.3 -42.59445 58.94332 158.8612 -48.61485 54.08511 158.8612 -43.29701 59.91554 156.6277 -64.17587 36.68735 156.6277 -63.13451 36.09204 158.8612 -59.91554 43.29701 156.6277 -58.94332 42.59445 158.8612 -54.97719 49.41671 156.6277 -54.08511 48.61485 158.8612 -49.41671 54.97719 156.6277 -51.42277 51.42277 158.8612 -49.5585 55.13493 154.0127 -55.13493 49.5585 154.0127 -60.08745 43.42124 154.0127 -64.36 36.79262 154.0127 -64.23468 36.72098 156.376 -43.42124 60.08745 154.0127 -43.34707 59.98481 153.2964 -64.25007 36.72977 153.2964 -59.98481 43.34707 153.2964 -55.04076 49.47385 153.2964 -52.33138 52.33138 153.2964 -49.47385 55.04076 153.2964 -61.6238 35.25986 160.8517 -58.47667 34.69798 164.3167 -54.5714 40.55106 164.3255 -61.75672 35.3044 160.693 -51.46094 44.43195 164.3255 -48.07508 48.07508 164.3255 -44.43195 51.46094 164.3255 -40.55106 54.5714 164.3255 -58.0688 34.41383 165.5978 -58.06903 34.41276 165.6352 -54.17936 40.25974 165.6352 -40.33494 54.28056 164.9363 -58.17895 34.50201 164.8999 -40.25974 54.17936 165.6352 -44.11276 51.09124 165.6352 -44.19515 51.18667 164.9363 -47.72971 47.72971 165.6352 -47.81886 47.81886 164.9363 -51.09124 44.11276 165.6352 -51.18667 44.19515 164.9363 -54.28056 40.33494 164.9363 -59.18154 32.46221 165.236 -60.02382 30.87703 164.5117 -59.3005 32.2444 167.0055 -57.92668 34.65184 167.0055 -55.22187 38.81745 167.0055 -51.66831 43.43542 167.0055 -47.72971 47.72971 167.0055 -43.43542 51.66831 167.0055 -38.81745 55.22187 167.0055 -34.65184 57.92668 167.0055 -34.01958 56.86975 174.595 -34.49084 57.65753 170.8728 -38.6371 54.96529 170.8728 -38.10919 54.21429 174.595 -43.23361 51.42824 170.8728 -42.6429 50.72557 174.595 -47.50794 47.50794 170.8728 -46.85883 46.85883 174.595 -51.42824 43.23361 170.8728 -50.72557 42.6429 174.595 -54.96529 38.6371 170.8728 -54.21429 38.10919 174.595 -57.65753 34.49084 170.8728 -56.86975 34.01958 174.595 -58.29442 33.09008 171.7254 -57.50651 32.93176 174.595 -58.84353 32.82767 169.3912 -59.0886 32.57001 168.1951 -57.24568 32.81539 175.4475 -56.98496 32.69881 176.3 -50.42346 42.11855 176.3 -42.11855 50.42346 176.3 -23.73025 63.24324 142.5781 -20.67897 63.83751 144.46 -21.75208 63.72028 144.0062 -22.66269 63.53997 143.2591 -29.34397 60.86169 133.7189 -30.46326 60.3138 131.6807 -32.29798 59.52149 129.1894 -32.9263 59.11747 128.0122 -33.72265 58.59564 126.8136 -34.18051 58.30122 126.3319 -34.87965 57.8614 125.8786 -35.00454 58.68065 129.1401 -35.25805 60.24984 135.4346 -34.02798 58.31922 126.0903 -34.87483 57.8547 125.8436 -33.5115 58.62471 126.567 -32.60567 59.15124 127.7602 -31.90546 59.54679 128.9364 -62.54551 35.75533 144.9456 -40.2914 54.22198 125.8436 -57.8547 34.87483 125.8436 -57.8614 34.87965 125.8786 -54.22198 40.2914 125.8436 -58.68065 35.00454 129.1401 -60.54995 35.30989 136.648 -51.13142 44.14745 125.8436 -47.76725 47.76725 125.8436 -44.14745 51.13142 125.8436 11.58134 66.49624 119.8559 -20.05005 64.31578 138.935 -16.05472 65.51758 128.4193 -12.34145 66.35601 121.0829 14.6184 65.87027 125.3859 0 0 15 67.5 0 15 6.039067 65.72313 112.2894 6.11135 65.71645 112.2962 6.111258 65.71646 112.2894 6.183443 65.7097 112.2894 -23.49403 60.06896 69.96601 -23.08418 60.22766 68.30575 -21.94408 60.65235 67.02143 -20.37948 61.1958 66.41958 -19.91789 61.34759 82.49215 -18.12982 61.89959 82.01303 -19.95183 61.33657 78.91601 -17.39305 62.11064 81.44859 -16.82086 62.26803 80.70408 -16.46451 62.36321 79.84497 -16.34175 62.39549 78.91601 -21.70596 60.73797 82.01303 -23.01492 60.25416 80.70408 -23.37128 60.11683 79.84494 -23.49403 60.06896 78.91601 -18.13739 61.89737 68.17794 -13.56674 63.05706 70.36898 -13.56674 63.05706 87.05348 -9.958946 63.72652 91.03259 -11.50216 63.46613 90.64778 -12.81971 63.21317 89.47142 -13.5213 63.06682 87.68331 -6.351152 64.18656 87.05348 -6.836795 64.13665 89.04183 -8.083148 63.9915 90.44866 -9.560539 63.7875 91.00827 -6.351152 64.18656 70.36898 -9.958946 63.72652 66.38987 -8.415726 63.94861 66.77468 -7.098176 64.10824 67.95104 -6.396586 64.18204 69.73914 -13.08109 63.1596 68.38063 -11.83474 63.40496 66.9738 -10.35735 63.66298 66.41419 -11.7676 63.41746 89.04303 -8.158292 63.98196 68.37943 -3.607792 64.39902 89.84552 -3.607792 64.39902 70.36898 0 64.5 93.82463 -1.543219 64.48154 93.43982 -2.860769 64.43653 92.26345 -3.562358 64.40155 90.47535 3.607792 64.39902 89.84552 3.12215 64.42439 91.83387 1.875798 64.47272 93.24069 0.3984075 64.49877 93.80031 3.607792 64.39902 70.36898 0 64.5 66.38987 1.543219 64.48154 66.77468 2.860769 64.43653 67.95104 3.562358 64.40155 69.73914 -3.12215 64.42439 68.38063 -1.875798 64.47272 66.9738 -0.3984075 64.49877 66.41419 6.351152 64.18656 70.36898 6.351152 64.18656 87.05348 9.958946 63.72652 91.03259 8.415726 63.94861 90.64778 7.098176 64.10824 89.47142 6.396586 64.18204 87.68331 13.56674 63.05706 87.05348 13.08109 63.1596 89.04183 11.83474 63.40496 90.44866 10.35735 63.66298 91.00827 13.56674 63.05706 70.36898 9.958946 63.72652 66.38987 11.50216 63.46613 66.77468 12.81971 63.21317 67.95104 13.5213 63.06682 69.73914 6.836795 64.13665 68.38063 8.083148 63.9915 66.9738 9.560539 63.7875 66.41419 11.7676 63.41746 68.37943 8.158292 63.98196 89.04303 60.13317 30.66177 164.3808 60.03408 31.28062 163.7294 60.15168 31.06068 163.6045 60.38682 31.78346 163.0988 60.50772 31.55347 162.9781 64.80696 35.75524 153.2964 64.88057 35.75244 153.5937 65.03868 35.64012 155.426 64.91136 35.53733 156.3759 64.75641 35.47148 156.9391 63.98178 35.32075 158.4084 63.58478 35.3044 158.8612 59.21495 32.74604 164.4735 59.53355 33.14228 163.8373 59.10691 27.38759 174.2946 59.11188 27.27444 174.2801 59.50672 27.29728 172.977 59.0004 31.15954 172.4238 59.77579 30.0237 170.6217 59.38836 29.39522 172.724 59.50946 27.41092 172.9661 59.90027 27.0103 171.6782 58.64705 30.18883 174.5521 60.16313 28.74721 170.1029 59.90347 30.39362 169.3411 60.26657 29.49382 168.6383 60.13811 26.8957 170.8685 60.12715 26.78428 170.9089 60.34035 26.51206 170.1445 60.3533 26.61948 170.0945 61.32456 25.05305 165.8155 61.11264 27.71584 165.3099 61.72346 25.9414 162.4318 61.33748 27.66046 162.917 60.6006 29.66788 163.8167 61.86205 24.20895 162.2315 60.66045 30.02029 163.0684 61.46664 27.89956 162.2169 61.89195 26.06681 161.7643 62.04775 24.20895 161.5919 61.02665 30.44587 162.4581 61.84941 28.1779 161.6337 62.28138 26.2097 161.2008 62.43314 24.20895 161.0488 63.94409 33.86106 159.2149 64.10159 31.55347 159.377 64.61627 31.53376 158.8612 64.49607 33.51735 158.7754 65.33204 33.53008 157.6335 65.86829 33.43306 153.3517 65.37866 34.78545 153.4737 66.03776 33.51281 154.8087 65.85172 33.54008 156.2695 66.29548 31.04291 154.8999 66.09627 30.92849 153.2964 65.9726 32.92477 153.3248 65.21908 31.46271 158.1503 65.96113 31.27001 156.7341 66.00833 30.92411 152.971 65.78018 33.43893 153.0356 58.11977 29.93232 176.3 58.49984 26.98827 176.3 58.80586 27.13137 175.2901 58.64706 30.18883 174.5521 58.11686 29.9433 176.3 63.24324 23.73025 142.5781 63.26271 24.08531 142.8331 63.53452 23.20245 143.8368 63.93689 19.50971 145.3225 63.88028 19.50971 144.5726 63.83751 20.67897 144.46 63.89125 20.86254 145.154 63.72028 21.75208 144.0062 63.75252 22.11971 144.6417 63.53997 22.66269 143.2591 60.3138 30.46326 131.6807 60.86169 29.34397 133.7189 60.3106 30.92411 131.9328 60.86275 29.78696 133.9716 59.52149 32.29798 129.1894 59.11747 32.9263 128.0122 58.59564 33.72265 126.8136 58.30122 34.18051 126.3319 58.31922 34.02798 126.0903 58.62471 33.5115 126.567 59.15124 32.60567 127.7602 59.54679 31.90546 128.9364 58.49984 -26.98827 176.3 58.80586 -27.13137 175.2901 59.90027 -27.0103 171.6782 59.50672 -27.29728 172.977 59.11188 -27.27444 174.2801 60.12715 -26.78428 170.9089 61.86205 -24.20895 162.2315 61.33389 -25.03869 165.7647 60.34035 -26.51206 170.1445 62.43314 -24.20895 161.0488 62.04775 -24.20895 161.5919 64.61627 -31.53376 158.8612 62.28138 -26.2097 161.2008 61.84941 -28.1779 161.6337 64.10159 -31.55347 159.377 61.02665 -30.44587 162.4581 60.50772 -31.55347 162.9781 65.14685 -31.47326 158.2487 65.94998 -31.27499 156.7648 66.28945 -31.05907 155.0798 66.09627 -30.92849 153.2964 63.75252 -22.11971 144.6417 63.53452 -23.20245 143.8368 66.00833 -30.92411 152.971 63.89125 -20.86254 145.154 63.93689 -19.50971 145.3225 60.3106 -30.92411 131.9328 60.86275 -29.78696 133.9716 63.26271 -24.08531 142.8331 63.88028 -19.50971 144.5726 66.07304 12.16378 125.3859 64.44231 -17.94182 139.6548 66.10384 12.02586 125.1164 65.34533 -15.04126 131.7533 65.62306 -14.01748 129.3233 64.65409 17.3095 137.8018 65.11434 15.83876 133.7745 66.31406 -11.03618 123.277 66.43339 -10.43085 122.2329 66.56651 9.70931 121.0681 66.81163 8.211158 118.9233 66.89653 -7.622066 118.1804 66.94385 -7.272554 117.7663 66.99221 6.896834 117.3432 67.21722 4.767905 115.3744 67.2342 -4.5666 115.2257 67.26637 -4.158677 114.9443 67.25278 4.335757 115.0632 67.37091 -2.389749 114.0295 67.40985 -1.179931 113.6889 67.4224 1.92587e-4 113.5791 67.38977 1.902435 113.8645 64.53045 19.40907 137.0567 64.99813 17.91459 132.9645 65.87027 14.6184 125.3859 60.38682 -31.78346 163.0988 60.03408 -31.28062 163.7294 60.15168 -31.06068 163.6045 60.02382 -30.87703 164.5117 60.13317 -30.66177 164.3808 63.98178 -35.32075 158.4084 63.58478 -35.3044 158.8612 63.13451 -36.09204 158.8612 64.71302 -35.45715 157.0632 64.17587 -36.68735 156.6277 64.9111 -35.53745 156.3762 64.23468 -36.72098 156.376 64.96789 -35.57065 156.081 65.02685 -35.62046 155.6084 64.36 -36.79262 154.0127 64.94372 -35.74411 153.9078 64.88057 -35.75244 153.5937 64.25007 -36.72977 153.2964 64.80696 -35.75524 153.2964 61.75672 -35.3044 160.693 58.0688 -34.41383 165.5978 58.17895 -34.50201 164.8999 59.21495 -32.74604 164.4735 58.47667 -34.69798 164.3167 59.53355 -33.14228 163.8373 58.06903 -34.41276 165.6352 59.18154 -32.46221 165.236 62.54551 -35.75533 144.9456 58.84353 -32.82767 169.3912 59.0004 -31.15954 172.4238 58.29442 -33.09008 171.7254 58.64705 -30.18883 174.5521 57.50651 -32.93176 174.595 59.50946 -27.41092 172.9661 59.38836 -29.39522 172.724 59.77579 -30.0237 170.6217 59.10691 -27.38759 174.2946 59.90347 -30.39362 169.3411 59.0886 -32.57001 168.1951 60.16313 -28.74721 170.1029 60.13811 -26.8957 170.8685 60.3533 -26.61948 170.0945 59.3005 -32.2444 167.0055 60.26657 -29.49382 168.6383 61.11264 -27.71584 165.3099 60.6006 -29.66788 163.8167 61.33748 -27.66046 162.917 61.72346 -25.9414 162.4318 60.66045 -30.02029 163.0684 61.46664 -27.89956 162.2169 61.89195 -26.06681 161.7643 61.6238 -35.25986 160.8517 63.96089 -33.77477 159.2285 64.49612 -33.51736 158.7755 66.03776 -33.51281 154.8087 65.86785 -33.43301 153.3504 65.96964 -32.94177 153.3255 65.85172 -33.54008 156.2695 65.33204 -33.53008 157.6335 65.35348 -34.83745 153.4774 65.78018 -33.43893 153.0356 58.11686 -29.9433 176.3 56.98496 -32.69881 176.3 57.24568 -32.81539 175.4475 58.64706 -30.18883 174.5521 42.59445 -58.94332 158.8612 36.09204 -63.13451 158.8612 36.68735 -64.17587 156.6277 48.61485 -54.08511 158.8612 43.29701 -59.91554 156.6277 59.91554 -43.29701 156.6277 58.94332 -42.59445 158.8612 54.97719 -49.41671 156.6277 54.08511 -48.61485 158.8612 49.41671 -54.97719 156.6277 51.42277 -51.42277 158.8612 49.5585 -55.13493 154.0127 55.13493 -49.5585 154.0127 60.08745 -43.42124 154.0127 36.72098 -64.23468 156.376 43.42124 -60.08745 154.0127 36.79262 -64.36 154.0127 36.72977 -64.25007 153.2964 43.34707 -59.98481 153.2964 59.98481 -43.34707 153.2964 55.04076 -49.47385 153.2964 52.33138 -52.33138 153.2964 49.47385 -55.04076 153.2964 54.5714 -40.55106 164.3255 34.69798 -58.47667 164.3167 35.19147 -61.36949 161.1456 35.3044 -61.75672 160.693 51.46094 -44.43195 164.3255 48.07508 -48.07508 164.3255 44.43195 -51.46094 164.3255 40.55106 -54.5714 164.3255 34.41383 -58.0688 165.5978 34.50201 -58.17895 164.8999 40.33494 -54.28056 164.9363 54.17936 -40.25974 165.6352 34.41276 -58.06903 165.6352 40.25974 -54.17936 165.6352 44.11276 -51.09124 165.6352 44.19515 -51.18667 164.9363 47.72971 -47.72971 165.6352 47.81886 -47.81886 164.9363 51.09124 -44.11276 165.6352 51.18667 -44.19515 164.9363 54.28056 -40.33494 164.9363 57.92668 -34.65184 167.0055 55.22187 -38.81745 167.0055 51.66831 -43.43542 167.0055 47.72971 -47.72971 167.0055 43.43542 -51.66831 167.0055 38.81745 -55.22187 167.0055 34.65184 -57.92668 167.0055 32.46221 -59.18154 165.236 32.2444 -59.3005 167.0055 30.87703 -60.02382 164.5117 33.09074 -58.2919 171.7348 32.82767 -58.84353 169.3912 32.57001 -59.0886 168.1951 34.01958 -56.86975 174.595 32.93176 -57.50651 174.595 34.49084 -57.65753 170.8728 38.6371 -54.96529 170.8728 38.10919 -54.21429 174.595 43.23361 -51.42824 170.8728 42.6429 -50.72557 174.595 47.50794 -47.50794 170.8728 46.85883 -46.85883 174.595 51.42824 -43.23361 170.8728 50.72557 -42.6429 174.595 54.96529 -38.6371 170.8728 54.21429 -38.10919 174.595 57.65753 -34.49084 170.8728 56.86975 -34.01958 174.595 50.42346 -42.11855 176.3 32.81539 -57.24568 175.4475 42.11855 -50.42346 176.3 32.69881 -56.98496 176.3 63.24323 -23.73025 142.5781 63.83751 -20.67897 144.46 63.72028 -21.75208 144.0062 63.53997 -22.66269 143.2591 60.86169 -29.34397 133.7189 60.3138 -30.46326 131.6807 59.52149 -32.29798 129.1894 59.11747 -32.9263 128.0122 58.59564 -33.72265 126.8136 60.54995 -35.30989 136.648 58.68065 -35.00454 129.1401 58.30122 -34.18051 126.3319 57.8614 -34.87965 125.8786 58.31922 -34.02798 126.0903 57.8547 -34.87483 125.8436 58.62471 -33.5115 126.567 59.15124 -32.60567 127.7602 59.54679 -31.90546 128.9364 34.87965 -57.8614 125.8786 34.87483 -57.8547 125.8436 40.2914 -54.22198 125.8436 54.22198 -40.2914 125.8436 35.75533 -62.54551 144.9456 35.25805 -60.24984 135.4346 35.00454 -58.68065 129.1401 51.13142 -44.14745 125.8436 47.76725 -47.76725 125.8436 44.14745 -51.13142 125.8436 66.49624 11.58134 119.8559 65.87027 14.6184 125.3859 66.35601 -12.34145 121.0829 64.31578 -20.05005 138.935 65.51758 -16.05472 128.4193 65.7097 6.183443 112.2894 65.71645 6.11135 112.2962 65.71646 6.111258 112.2894 65.72313 6.039067 112.2894 61.34759 -19.91789 66.38987 61.86201 -18.25763 66.79972 62.22666 -16.97331 67.93982 62.39126 -16.35789 69.62514 62.35843 -16.48261 70.96036 62.13709 -17.29832 72.39701 62.027 -17.689 72.75983 61.55735 -19.25988 73.48136 61.34759 -19.91789 73.54216 60.7835 -21.57815 73.1323 60.31217 -22.86247 71.9922 60.15355 -23.27661 71.19358 60.07527 -23.47789 70.30688 60.12387 -23.35317 68.97166 60.43437 -22.53746 67.53502 60.57863 -22.14678 67.17219 61.13004 -20.5759 66.45066 60.36873 -22.71269 69.18289 63.05706 -13.56674 70.36898 63.05706 -13.56674 87.05348 63.72652 -9.958946 91.03259 63.46613 -11.50216 90.64778 63.21317 -12.81971 89.47142 63.06682 -13.5213 87.68331 64.18656 -6.351152 87.05348 64.13665 -6.836795 89.04183 63.9915 -8.083148 90.44866 63.7875 -9.560539 91.00827 64.18656 -6.351152 70.36898 63.72652 -9.958946 66.38987 63.94861 -8.415726 66.77468 64.10824 -7.098176 67.95104 64.18204 -6.396586 69.73914 63.40496 -11.83474 66.9738 63.1596 -13.08109 68.38063 63.66298 -10.35735 66.41419 63.98196 -8.158292 68.37943 63.41746 -11.7676 89.04303 64.39902 -3.607792 89.84552 64.39902 -3.607792 70.36898 64.5 0 93.82463 64.48154 -1.543219 93.43982 64.43653 -2.860769 92.26345 64.40155 -3.562358 90.47535 64.39902 3.607792 89.84552 64.42439 3.12215 91.83387 64.47272 1.875798 93.24069 64.49877 0.3984075 93.80031 64.39902 3.607792 70.36898 64.5 0 66.38987 64.48154 1.543219 66.77468 64.43653 2.860769 67.95104 64.40155 3.562358 69.73914 64.42439 -3.12215 68.38063 64.47272 -1.875798 66.9738 64.49877 -0.3984075 66.41419 64.18656 6.351152 70.36898 64.18656 6.351152 87.05348 63.72652 9.958946 91.03259 63.94861 8.415726 90.64778 64.10824 7.098176 89.47142 64.18204 6.396586 87.68331 63.05706 13.56674 87.05348 63.40496 11.83474 90.44866 63.1596 13.08109 89.04183 63.66298 10.35735 91.00827 63.05706 13.56674 70.36898 63.72652 9.958946 66.38987 63.46613 11.50216 66.77468 63.21317 12.81971 67.95104 63.06682 13.5213 69.73914 64.13665 6.836795 68.38063 63.9915 8.083148 66.9738 63.7875 9.560539 66.41419 63.98196 8.158292 89.04303 63.41746 11.7676 68.37943 62.40377 16.3101 70.36898 62.40377 16.3101 79.30928 61.34759 19.91789 83.28839 61.82735 18.37467 82.90358 62.20373 17.05712 81.72721 62.39188 16.35553 79.9391 60.05657 23.52568 79.30928 60.24456 23.04004 81.29763 60.70655 21.79369 82.70446 61.21681 20.3163 83.26406 60.05657 23.52568 70.36898 61.34759 19.91789 66.38987 60.82492 21.46111 66.77468 60.34387 22.77866 67.95104 60.07435 23.48025 69.73914 62.27482 16.79574 68.38063 61.92522 18.04209 66.9738 61.47552 19.51948 66.41419 61.90197 18.12169 81.29883 60.72888 21.73138 68.37943 -60.02382 -30.87703 164.5117 -60.13317 -30.66177 164.3808 -60.03408 -31.28062 163.7294 -60.15168 -31.06068 163.6045 -60.38682 -31.78346 163.0988 -60.50772 -31.55347 162.9781 -64.80696 -35.75524 153.2964 -64.25007 -36.72977 153.2964 -64.88057 -35.75244 153.5937 -64.36 -36.79262 154.0127 -65.03868 -35.64012 155.426 -64.23468 -36.72098 156.376 -64.91136 -35.53733 156.3759 -64.17587 -36.68735 156.6277 -64.75641 -35.47148 156.9391 -63.98178 -35.32075 158.4084 -63.13451 -36.09204 158.8612 -63.58478 -35.3044 158.8612 -61.75672 -35.3044 160.693 -58.0688 -34.41383 165.5978 -58.06903 -34.41276 165.6352 -59.18154 -32.46221 165.236 -58.17895 -34.50201 164.8999 -59.21495 -32.74604 164.4735 -58.47667 -34.69798 164.3167 -59.53355 -33.14228 163.8373 -62.54551 -35.75533 144.9456 -59.10691 -27.38759 174.2946 -59.11188 -27.27444 174.2801 -59.50672 -27.29728 172.977 -59.0004 -31.15954 172.4238 -59.77579 -30.0237 170.6217 -58.2919 -33.09074 171.7348 -58.84353 -32.82767 169.3912 -59.38836 -29.39522 172.724 -59.50946 -27.41092 172.9661 -59.90027 -27.0103 171.6782 -57.50651 -32.93176 174.595 -58.64705 -30.18883 174.5521 -60.16313 -28.74721 170.1029 -59.90347 -30.39362 169.3411 -60.26657 -29.49382 168.6383 -59.0886 -32.57001 168.1951 -59.3005 -32.2444 167.0055 -60.13811 -26.8957 170.8685 -60.12715 -26.78428 170.9089 -60.34035 -26.51206 170.1445 -60.3533 -26.61948 170.0945 -61.32456 -25.05305 165.8155 -61.11264 -27.71584 165.3099 -61.72346 -25.9414 162.4318 -61.33748 -27.66046 162.917 -60.6006 -29.66788 163.8167 -61.86205 -24.20895 162.2315 -60.66045 -30.02029 163.0684 -61.46664 -27.89956 162.2169 -61.89195 -26.06681 161.7643 -62.04775 -24.20895 161.5919 -61.02665 -30.44587 162.4581 -61.84941 -28.1779 161.6337 -62.28138 -26.2097 161.2008 -62.43314 -24.20895 161.0488 -61.36949 -35.19147 161.1456 -63.94409 -33.86106 159.2149 -64.10159 -31.55347 159.377 -64.61627 -31.53376 158.8612 -64.49607 -33.51735 158.7754 -65.33204 -33.53008 157.6335 -65.86829 -33.43306 153.3517 -65.37866 -34.78545 153.4737 -66.03776 -33.51281 154.8087 -65.85172 -33.54008 156.2695 -66.29548 -31.04291 154.8999 -66.09627 -30.92849 153.2964 -65.9726 -32.92477 153.3248 -65.21908 -31.46271 158.1503 -65.96113 -31.27001 156.7341 -66.00833 -30.92411 152.971 -65.78018 -33.43893 153.0356 -58.11977 -29.93232 176.3 -58.49984 -26.98827 176.3 -58.80586 -27.13137 175.2901 -58.64706 -30.18883 174.5521 -57.24568 -32.81539 175.4475 -58.11686 -29.9433 176.3 -56.98496 -32.69881 176.3 -58.94332 -42.59445 158.8612 -54.08511 -48.61485 158.8612 -59.91554 -43.29701 156.6277 -54.97719 -49.41671 156.6277 -49.41671 -54.97719 156.6277 -51.42277 -51.42277 158.8612 -36.68735 -64.17587 156.6277 -36.09204 -63.13451 158.8612 -43.29701 -59.91554 156.6277 -42.59445 -58.94332 158.8612 -48.61485 -54.08511 158.8612 -55.13493 -49.5585 154.0127 -49.5585 -55.13493 154.0127 -43.42124 -60.08745 154.0127 -36.79262 -64.36 154.0127 -36.72098 -64.23468 156.376 -60.08745 -43.42124 154.0127 -59.98481 -43.34707 153.2964 -36.72977 -64.25007 153.2964 -43.34707 -59.98481 153.2964 -49.47385 -55.04076 153.2964 -52.33138 -52.33138 153.2964 -55.04076 -49.47385 153.2964 -35.25986 -61.6238 160.8517 -34.69798 -58.47667 164.3167 -40.55106 -54.5714 164.3255 -35.3044 -61.75672 160.693 -44.43195 -51.46094 164.3255 -48.07508 -48.07508 164.3255 -51.46094 -44.43195 164.3255 -54.5714 -40.55106 164.3255 -54.28056 -40.33494 164.9363 -34.41383 -58.0688 165.5978 -34.41276 -58.06903 165.6352 -40.25974 -54.17936 165.6352 -34.50201 -58.17895 164.8999 -54.17936 -40.25974 165.6352 -51.09124 -44.11276 165.6352 -51.18667 -44.19515 164.9363 -47.72971 -47.72971 165.6352 -47.81886 -47.81886 164.9363 -44.11276 -51.09124 165.6352 -44.19515 -51.18667 164.9363 -40.33494 -54.28056 164.9363 -32.46221 -59.18154 165.236 -30.87703 -60.02382 164.5117 -32.2444 -59.3005 167.0055 -34.65184 -57.92668 167.0055 -38.81745 -55.22187 167.0055 -43.43542 -51.66831 167.0055 -47.72971 -47.72971 167.0055 -51.66831 -43.43542 167.0055 -55.22187 -38.81745 167.0055 -57.92668 -34.65184 167.0055 -56.86975 -34.01958 174.595 -57.65753 -34.49084 170.8728 -54.96529 -38.6371 170.8728 -54.21429 -38.10919 174.595 -51.42824 -43.23361 170.8728 -50.72557 -42.6429 174.595 -47.50794 -47.50794 170.8728 -46.85883 -46.85883 174.595 -43.23361 -51.42824 170.8728 -42.6429 -50.72557 174.595 -38.6371 -54.96529 170.8728 -38.10919 -54.21429 174.595 -34.49084 -57.65753 170.8728 -34.01958 -56.86975 174.595 -33.09008 -58.29442 171.7254 -32.93176 -57.50651 174.595 -32.82767 -58.84353 169.3912 -32.57001 -59.0886 168.1951 -32.81539 -57.24568 175.4475 -32.69881 -56.98496 176.3 -42.11855 -50.42346 176.3 -50.42346 -42.11855 176.3 -63.24324 -23.73025 142.5781 -63.26271 -24.08531 142.8331 -63.53452 -23.20245 143.8368 -63.93689 -19.50971 145.3225 -63.88028 -19.50971 144.5726 -63.83751 -20.67897 144.46 -63.89125 -20.86254 145.154 -63.72028 -21.75208 144.0062 -63.75252 -22.11971 144.6417 -63.53997 -22.66269 143.2591 -60.3138 -30.46326 131.6807 -60.86169 -29.34397 133.7189 -60.3106 -30.92411 131.9328 -60.86275 -29.78696 133.9716 -59.52149 -32.29798 129.1894 -59.11747 -32.9263 128.0122 -58.59564 -33.72265 126.8136 -58.30122 -34.18051 126.3319 -57.8614 -34.87965 125.8786 -58.68065 -35.00454 129.1401 -60.24984 -35.25805 135.4346 -58.31922 -34.02798 126.0903 -57.8547 -34.87483 125.8436 -58.62471 -33.5115 126.567 -59.15124 -32.60567 127.7602 -59.54679 -31.90546 128.9364 -35.75533 -62.54551 144.9456 -54.22198 -40.2914 125.8436 -34.87483 -57.8547 125.8436 -34.87965 -57.8614 125.8786 -40.2914 -54.22198 125.8436 -35.00454 -58.68065 129.1401 -35.30989 -60.54995 136.648 -44.14745 -51.13142 125.8436 -47.76725 -47.76725 125.8436 -51.13142 -44.14745 125.8436 -58.49984 26.98827 176.3 -58.80586 27.13137 175.2901 -59.90027 27.0103 171.6782 -59.50672 27.29728 172.977 -59.11188 27.27444 174.2801 -60.12715 26.78428 170.9089 -61.86205 24.20895 162.2315 -61.33389 25.03869 165.7647 -60.34035 26.51206 170.1445 -62.43314 24.20895 161.0488 -62.04775 24.20895 161.5919 -64.61627 31.53376 158.8612 -62.28138 26.2097 161.2008 -61.84941 28.1779 161.6337 -64.10159 31.55347 159.377 -61.02665 30.44587 162.4581 -60.50772 31.55347 162.9781 -65.14685 31.47326 158.2487 -65.94998 31.27499 156.7648 -66.28945 31.05907 155.0798 -66.09627 30.92849 153.2964 -63.75252 22.11971 144.6417 -63.53452 23.20245 143.8368 -66.00833 30.92411 152.971 -63.89125 20.86254 145.154 -63.93689 19.50971 145.3225 -60.3106 30.92411 131.9328 -60.86275 29.78696 133.9716 -63.26271 24.08531 142.8331 -63.88028 19.50971 144.5726 -66.07304 -12.16378 125.3859 -64.44231 17.94182 139.6548 -66.10384 -12.02586 125.1164 -65.34533 15.04126 131.7533 -65.62306 14.01748 129.3233 -64.65409 -17.3095 137.8018 -65.11434 -15.83876 133.7745 -66.31406 11.03618 123.277 -66.43339 10.43085 122.2329 -66.56651 -9.70931 121.0681 -66.81163 -8.211158 118.9233 -66.89653 7.622066 118.1804 -66.94385 7.272554 117.7663 -66.99221 -6.896834 117.3432 -67.21722 -4.767905 115.3744 -67.2342 4.5666 115.2257 -67.26637 4.158677 114.9443 -67.25278 -4.335757 115.0632 -67.37091 2.389749 114.0295 -67.40985 1.179931 113.6889 -67.4224 -1.92587e-4 113.5791 -67.38977 -1.902435 113.8645 -64.53045 -19.40907 137.0567 -64.99813 -17.91459 132.9645 -65.87027 -14.6184 125.3859 -60.38682 31.78346 163.0988 -60.03408 31.28062 163.7294 -60.15168 31.06068 163.6045 -60.13317 30.66177 164.3808 -63.98178 35.32075 158.4084 -63.58478 35.3044 158.8612 -64.71302 35.45715 157.0632 -64.9111 35.53745 156.3762 -64.96789 35.57065 156.081 -65.02685 35.62046 155.6084 -64.94372 35.74411 153.9078 -64.88057 35.75244 153.5937 -64.80696 35.75524 153.2964 -59.21495 32.74604 164.4735 -59.53355 33.14228 163.8373 -59.0004 31.15954 172.4238 -58.64705 30.18883 174.5521 -59.50946 27.41092 172.9661 -59.38836 29.39522 172.724 -59.77579 30.0237 170.6217 -59.10691 27.38759 174.2946 -59.90347 30.39362 169.3411 -60.16313 28.74721 170.1029 -60.13811 26.8957 170.8685 -60.3533 26.61948 170.0945 -60.26657 29.49382 168.6383 -61.11264 27.71584 165.3099 -60.6006 29.66788 163.8167 -61.33748 27.66046 162.917 -61.72346 25.9414 162.4318 -60.66045 30.02029 163.0684 -61.46664 27.89956 162.2169 -61.89195 26.06681 161.7643 -63.96089 33.77477 159.2285 -64.49612 33.51736 158.7755 -66.03776 33.51281 154.8087 -65.86785 33.43301 153.3504 -65.96964 32.94177 153.3255 -65.85172 33.54008 156.2695 -65.33204 33.53008 157.6335 -65.35348 34.83745 153.4774 -65.78018 33.43893 153.0356 -58.11686 29.9433 176.3 -58.64706 30.18883 174.5521 -63.24323 23.73025 142.5781 -63.83751 20.67897 144.46 -63.72028 21.75208 144.0062 -63.53997 22.66269 143.2591 -60.86169 29.34397 133.7189 -60.3138 30.46326 131.6807 -59.52149 32.29798 129.1894 -59.11747 32.9263 128.0122 -58.59564 33.72265 126.8136 -58.30122 34.18051 126.3319 -58.31922 34.02798 126.0903 -58.62471 33.5115 126.567 -59.15124 32.60567 127.7602 -59.54679 31.90546 128.9364 -66.49624 -11.58134 119.8559 -65.87027 -14.6184 125.3859 -66.35601 12.34145 121.0829 -64.31578 20.05005 138.935 -65.51758 16.05472 128.4193 -65.7097 -6.183443 112.2894 -65.71645 -6.11135 112.2962 -65.71646 -6.111258 112.2894 -65.72313 -6.039067 112.2894 -61.34759 19.91789 66.38987 -61.86201 18.25763 66.79972 -62.22666 16.97331 67.93982 -62.39126 16.35789 69.62514 -62.35843 16.48261 70.96036 -62.13709 17.29832 72.39701 -62.027 17.689 72.75983 -61.55735 19.25988 73.48136 -61.34759 19.91789 73.54216 -60.7835 21.57815 73.1323 -60.31217 22.86247 71.9922 -60.15355 23.27661 71.19358 -60.07527 23.47789 70.30688 -60.12387 23.35317 68.97166 -60.43437 22.53746 67.53502 -60.57863 22.14678 67.17219 -61.13004 20.5759 66.45066 -60.36873 22.71269 69.18289 -63.05706 13.56674 70.36898 -63.05706 13.56674 87.05348 -63.72652 9.958946 91.03259 -63.46613 11.50216 90.64778 -63.21317 12.81971 89.47142 -63.06682 13.5213 87.68331 -64.18656 6.351152 87.05348 -64.13665 6.836795 89.04183 -63.9915 8.083148 90.44866 -63.7875 9.560539 91.00827 -64.18656 6.351152 70.36898 -63.72652 9.958946 66.38987 -63.94861 8.415726 66.77468 -64.10824 7.098176 67.95104 -64.18204 6.396586 69.73914 -63.40496 11.83474 66.9738 -63.1596 13.08109 68.38063 -63.66298 10.35735 66.41419 -63.98196 8.158292 68.37943 -63.41746 11.7676 89.04303 -64.39902 3.607792 89.84552 -64.39902 3.607792 70.36898 -64.5 0 93.82463 -64.48154 1.543219 93.43982 -64.43653 2.860769 92.26345 -64.40155 3.562358 90.47535 -64.39902 -3.607792 89.84552 -64.42439 -3.12215 91.83387 -64.47272 -1.875798 93.24069 -64.49877 -0.3984075 93.80031 -64.39902 -3.607792 70.36898 -64.5 0 66.38987 -64.48154 -1.543219 66.77468 -64.43653 -2.860769 67.95104 -64.40155 -3.562358 69.73914 -64.42439 3.12215 68.38063 -64.47272 1.875798 66.9738 -64.49877 0.3984075 66.41419 -64.18656 -6.351152 70.36898 -64.18656 -6.351152 87.05348 -63.72652 -9.958946 91.03259 -63.94861 -8.415726 90.64778 -64.10824 -7.098176 89.47142 -64.18204 -6.396586 87.68331 -63.05706 -13.56674 87.05348 -63.40496 -11.83474 90.44866 -63.1596 -13.08109 89.04183 -63.66298 -10.35735 91.00827 -63.05706 -13.56674 70.36898 -63.72652 -9.958946 66.38987 -63.46613 -11.50216 66.77468 -63.21317 -12.81971 67.95104 -63.06682 -13.5213 69.73914 -64.13665 -6.836795 68.38063 -63.9915 -8.083148 66.9738 -63.7875 -9.560539 66.41419 -63.98196 -8.158292 89.04303 -63.41746 -11.7676 68.37943 -62.40377 -16.3101 70.36898 -62.40377 -16.3101 79.30928 -61.34759 -19.91789 83.28839 -61.82735 -18.37467 82.90358 -62.20373 -17.05712 81.72721 -62.39188 -16.35553 79.9391 -60.05657 -23.52568 79.30928 -60.24456 -23.04004 81.29763 -60.70655 -21.79369 82.70446 -61.21681 -20.3163 83.26406 -60.05657 -23.52568 70.36898 -61.34759 -19.91789 66.38987 -60.82492 -21.46111 66.77468 -60.34387 -22.77866 67.95104 -60.07435 -23.48025 69.73914 -62.27482 -16.79574 68.38063 -61.92522 -18.04209 66.9738 -61.47552 -19.51948 66.41419 -61.90197 -18.12169 81.29883 -60.72888 -21.73138 68.37943 -31.78346 -60.38682 163.0988 -31.55347 -60.50772 162.9781 -31.28062 -60.03408 163.7294 -31.06068 -60.15168 163.6045 -30.66177 -60.13317 164.3808 -35.32075 -63.98178 158.4084 -35.3044 -63.58478 158.8612 -35.45715 -64.71302 157.0632 -35.53745 -64.9111 156.3762 -35.57065 -64.96789 156.081 -35.62046 -65.02685 155.6084 -35.74411 -64.94372 153.9078 -35.75244 -64.88057 153.5937 -35.75524 -64.80696 153.2964 -32.74604 -59.21495 164.4735 -33.14228 -59.53355 163.8373 -31.15954 -59.0004 172.4238 -30.18883 -58.64705 174.5521 -27.41092 -59.50946 172.9661 -27.29728 -59.50672 172.977 -27.27444 -59.11188 174.2801 -27.0103 -59.90027 171.6782 -29.39522 -59.38836 172.724 -30.0237 -59.77579 170.6217 -27.38759 -59.10691 174.2946 -30.39362 -59.90347 169.3411 -28.74721 -60.16313 170.1029 -26.8957 -60.13811 170.8685 -26.61948 -60.3533 170.0945 -26.51206 -60.34035 170.1445 -26.78428 -60.12715 170.9089 -29.49382 -60.26657 168.6383 -24.20895 -61.86205 162.2315 -25.03869 -61.33389 165.7647 -27.71584 -61.11264 165.3099 -29.66788 -60.6006 163.8167 -27.66046 -61.33748 162.917 -25.9414 -61.72346 162.4318 -30.44587 -61.02665 162.4581 -30.02029 -60.66045 163.0684 -28.1779 -61.84941 161.6337 -27.89956 -61.46664 162.2169 -26.2097 -62.28138 161.2008 -26.06681 -61.89195 161.7643 -24.20895 -62.43314 161.0488 -24.20895 -62.04775 161.5919 -31.55347 -64.10159 159.377 -33.77477 -63.96089 159.2285 -33.51736 -64.49612 158.7755 -31.53376 -64.61627 158.8612 -33.51281 -66.03776 154.8087 -33.43301 -65.86785 153.3504 -32.94177 -65.96964 153.3255 -33.54008 -65.85172 156.2695 -33.53008 -65.33204 157.6335 -34.83745 -65.35348 153.4774 -31.47326 -65.14685 158.2487 -31.27499 -65.94998 156.7648 -31.05907 -66.28945 155.0798 -30.92849 -66.09627 153.2964 -33.43893 -65.78018 153.0356 -30.92411 -66.00833 152.971 -27.13137 -58.80586 175.2901 -26.98827 -58.49984 176.3 -29.9433 -58.11686 176.3 -30.18883 -58.64706 174.5521 -23.20245 -63.53452 143.8368 -24.08531 -63.26271 142.8331 -23.73025 -63.24323 142.5781 -19.50971 -63.88028 144.5726 -19.50971 -63.93689 145.3225 -20.86254 -63.89125 145.154 -20.67897 -63.83751 144.46 -22.11971 -63.75252 144.6417 -21.75208 -63.72028 144.0062 -22.66269 -63.53997 143.2591 -29.34397 -60.86169 133.7189 -30.46326 -60.3138 131.6807 -30.92411 -60.3106 131.9328 -29.78696 -60.86275 133.9716 -32.29798 -59.52149 129.1894 -32.9263 -59.11747 128.0122 -33.72265 -58.59564 126.8136 -34.18051 -58.30122 126.3319 -34.02798 -58.31922 126.0903 -33.5115 -58.62471 126.567 -32.60567 -59.15124 127.7602 -31.90546 -59.54679 128.9364 26.98827 -58.49984 176.3 27.13137 -58.80586 175.2901 27.27444 -59.11188 174.2801 27.0103 -59.90027 171.6782 27.29728 -59.50672 172.977 24.20895 -61.86205 162.2315 25.05305 -61.32456 165.8155 26.51206 -60.34035 170.1445 26.78428 -60.12715 170.9089 24.20895 -62.43314 161.0488 24.20895 -62.04775 161.5919 31.55347 -60.50772 162.9781 30.44587 -61.02665 162.4581 31.55347 -64.10159 159.377 28.1779 -61.84941 161.6337 31.53376 -64.61627 158.8612 26.2097 -62.28138 161.2008 31.46271 -65.21908 158.1503 31.27001 -65.96113 156.7341 31.04291 -66.29548 154.8999 30.92849 -66.09627 153.2964 19.50971 -63.93689 145.3225 20.86254 -63.89125 145.154 22.11971 -63.75252 144.6417 30.92411 -66.00833 152.971 23.20245 -63.53452 143.8368 24.08531 -63.26271 142.8331 29.78696 -60.86275 133.9716 30.92411 -60.3106 131.9328 19.50971 -63.88028 144.5726 -17.3095 -64.65409 137.8018 -12.16378 -66.07304 125.3859 -12.02586 -66.10384 125.1164 17.94182 -64.44231 139.6548 -15.83876 -65.11434 133.7745 11.03618 -66.31406 123.277 14.01748 -65.62306 129.3233 15.04126 -65.34533 131.7533 7.622066 -66.89653 118.1804 10.43085 -66.43339 122.2329 -8.211158 -66.81163 118.9233 -9.70931 -66.56651 121.0681 7.272554 -66.94385 117.7663 -6.896834 -66.99221 117.3432 -4.767905 -67.21722 115.3744 1.179931 -67.40985 113.6889 -4.335757 -67.25278 115.0632 -1.92587e-4 -67.4224 113.5791 -1.902435 -67.38977 113.8645 2.389749 -67.37091 114.0295 4.158677 -67.26637 114.9443 4.5666 -67.2342 115.2257 -19.40907 -64.53045 137.0567 -14.6184 -65.87027 125.3859 -17.91459 -64.99813 132.9645 30.66177 -60.13317 164.3808 31.28062 -60.03408 163.7294 31.06068 -60.15168 163.6045 31.78346 -60.38682 163.0988 35.75524 -64.80696 153.2964 35.75244 -64.88057 153.5937 35.64012 -65.03868 155.426 35.53733 -64.91136 156.3759 35.47148 -64.75641 156.9391 35.32075 -63.98178 158.4084 35.3044 -63.58478 158.8612 32.74604 -59.21495 164.4735 33.14228 -59.53355 163.8373 27.38759 -59.10691 174.2946 31.15954 -59.0004 172.4238 30.0237 -59.77579 170.6217 29.39522 -59.38836 172.724 27.41092 -59.50946 172.9661 30.18883 -58.64705 174.5521 28.74721 -60.16313 170.1029 30.39362 -59.90347 169.3411 29.49382 -60.26657 168.6383 26.8957 -60.13811 170.8685 26.61948 -60.3533 170.0945 27.71584 -61.11264 165.3099 25.9414 -61.72346 162.4318 27.66046 -61.33748 162.917 29.66788 -60.6006 163.8167 30.02029 -60.66045 163.0684 27.89956 -61.46664 162.2169 26.06681 -61.89195 161.7643 33.86106 -63.94409 159.2149 33.51735 -64.49607 158.7754 33.53008 -65.33204 157.6335 33.43306 -65.86829 153.3517 34.78545 -65.37866 153.4737 33.51281 -66.03776 154.8087 33.54008 -65.85172 156.2695 32.92477 -65.9726 153.3248 33.43893 -65.78018 153.0356 29.93232 -58.11977 176.3 30.18883 -58.64706 174.5521 29.9433 -58.11686 176.3 23.73025 -63.24324 142.5781 20.67897 -63.83751 144.46 21.75208 -63.72028 144.0062 22.66269 -63.53997 143.2591 29.34397 -60.86169 133.7189 30.46326 -60.3138 131.6807 32.29798 -59.52149 129.1894 32.9263 -59.11747 128.0122 33.72265 -58.59564 126.8136 34.18051 -58.30122 126.3319 34.02798 -58.31922 126.0903 33.5115 -58.62471 126.567 32.60567 -59.15124 127.7602 31.90546 -59.54679 128.9364 -11.58134 -66.49624 119.8559 20.05005 -64.31578 138.935 16.05472 -65.51758 128.4193 12.34145 -66.35601 121.0829 -14.6184 -65.87027 125.3859 -6.039067 -65.72313 112.2894 -6.11135 -65.71645 112.2962 -6.111258 -65.71646 112.2894 -6.183443 -65.7097 112.2894 23.49403 -60.06896 69.96601 23.08418 -60.22766 68.30575 21.94408 -60.65235 67.02143 20.37948 -61.1958 66.41958 19.91789 -61.34759 83.29216 18.12982 -61.89959 82.81304 19.95183 -61.33657 79.71601 17.39306 -62.11064 82.2486 16.82086 -62.26803 81.50408 16.46393 -62.36336 80.64279 16.34175 -62.39549 79.71601 21.70596 -60.73797 82.81304 23.01492 -60.25416 81.50408 23.37079 -60.11702 80.64675 23.49403 -60.06896 79.71601 18.13739 -61.89737 68.17794 13.56674 -63.05706 70.36898 13.56674 -63.05706 87.05348 9.958946 -63.72652 91.03259 11.50216 -63.46613 90.64778 12.81971 -63.21317 89.47142 13.5213 -63.06682 87.68331 6.351152 -64.18656 87.05348 6.836795 -64.13665 89.04183 8.083148 -63.9915 90.44866 9.560539 -63.7875 91.00827 6.351152 -64.18656 70.36898 9.958946 -63.72652 66.38987 8.415726 -63.94861 66.77468 7.098176 -64.10824 67.95104 6.396586 -64.18204 69.73914 13.08109 -63.1596 68.38063 11.83474 -63.40496 66.9738 10.35735 -63.66298 66.41419 11.7676 -63.41746 89.04303 8.158292 -63.98196 68.37943 3.607792 -64.39902 89.84552 3.607792 -64.39902 70.36898 0 -64.5 93.82463 1.543219 -64.48154 93.43982 2.860769 -64.43653 92.26345 3.562358 -64.40155 90.47535 -3.607792 -64.39902 89.84552 -3.12215 -64.42439 91.83387 -1.875798 -64.47272 93.24069 -0.3984075 -64.49877 93.80031 -3.607792 -64.39902 70.36898 0 -64.5 66.38987 -1.543219 -64.48154 66.77468 -2.860769 -64.43653 67.95104 -3.562358 -64.40155 69.73914 3.12215 -64.42439 68.38063 1.875798 -64.47272 66.9738 0.3984075 -64.49877 66.41419 -6.351152 -64.18656 70.36898 -6.351152 -64.18656 87.05348 -9.958946 -63.72652 91.03259 -8.415726 -63.94861 90.64778 -7.098176 -64.10824 89.47142 -6.396586 -64.18204 87.68331 -13.56674 -63.05706 87.05348 -13.08109 -63.1596 89.04183 -11.83474 -63.40496 90.44866 -10.35735 -63.66298 91.00827 -13.56674 -63.05706 70.36898 -9.958946 -63.72652 66.38987 -11.50216 -63.46613 66.77468 -12.81971 -63.21317 67.95104 -13.5213 -63.06682 69.73914 -6.836795 -64.13665 68.38063 -8.083148 -63.9915 66.9738 -9.560539 -63.7875 66.41419 -11.7676 -63.41746 68.37943 -8.158292 -63.98196 89.04303 -19.91789 -61.34759 66.38987 -21.46111 -60.82492 66.77468 -22.77866 -60.34387 67.95104 -23.48025 -60.07435 69.73914 -23.52568 -60.05657 70.36898 -16.3101 -62.40377 70.36898 -16.79574 -62.27482 68.38063 -18.04209 -61.92522 66.9738 -19.51948 -61.47552 66.41419 -20.3163 -61.21681 74.32377 -19.91789 -61.34759 74.34809 -18.37467 -61.82735 73.96328 -17.05712 -62.20373 72.78691 -16.35553 -62.39188 70.99881 -21.79369 -60.70655 73.76416 -23.04004 -60.24456 72.35733 -32.69881 56.98496 183 -29.9433 58.11686 183 -26.98827 58.49984 183 -42.18662 50.36653 183 -50.36653 42.18662 183 -56.98496 32.69881 183 -58.11686 29.9433 183 -58.49984 26.98827 183 -58.49984 -26.98827 183 -56.98496 -32.69881 183 -58.11686 -29.9433 183 -50.36653 -42.18662 183 -42.18662 -50.36653 183 -32.69881 -56.98496 183 -29.9433 -58.11686 183 -26.98827 -58.49984 183 26.98827 -58.49984 183 32.69881 -56.98496 183 29.9433 -58.11686 183 42.18662 -50.36653 183 50.36653 -42.18662 183 56.98496 -32.69881 183 58.11686 -29.9433 183 58.49984 -26.98827 183 58.49984 26.98827 183 56.98496 32.69881 183 58.11686 29.9433 183 50.36653 42.18662 183 42.18662 50.36653 183 32.69881 56.98496 183 29.9433 58.11686 183 26.98827 58.49984 183 -29.73205 -37 183 -29 -36.26795 183 -30 -38 183 29 -36.26795 183 30 18 183 28 -36 183 27 -36.26795 183 -26.26795 19 183 28 16 183 -27 19.73205 183 27 16.26795 183 -28 20 183 26.26795 17 183 26 18 183 -30 18 183 -29.73205 19 183 29.73205 -39 183 30 -38 183 29.73205 -37 183 -29 19.73205 183 29.73205 19 183 27 -39.73205 183 28 -40 183 29 -39.73205 183 26.26795 -39 183 26 -38 183 -27 -36.26795 183 -28 -36 183 26.26795 19 183 29 19.73205 183 28 20 183 27 19.73205 183 -26.26795 -37 183 26.26795 -37 183 29.73205 17 183 29 16.26795 183 -26 -38 183 -26.26795 -39 183 -27 -39.73205 183 -28 -40 183 -29 -39.73205 183 -26 18 183 -26.26795 17 183 -27 16.26795 183 -28 16 183 -29 16.26795 183 -29.73205 17 183 -29.73205 -39 183 29.73205 -39 184 29 -39.73205 184 28 -40 184 27 -39.73205 184 26.26795 -39 184 26 -38 184 26.26795 -37 184 27 -36.26795 184 28 -36 184 29 -36.26795 184 29.73205 -37 184 30 -38 184 28 -38 184 -26.26795 -39 184 -27 -39.73205 184 -28 -40 184 -29 -39.73205 184 -29.73205 -39 184 -30 -38 184 -29.73205 -37 184 -29 -36.26795 184 -28 -36 184 -27 -36.26795 184 -26.26795 -37 184 -26 -38 184 -28 -38 184 29.73205 17 184 29 16.26795 184 28 16 184 27 16.26795 184 26.26795 17 184 26 18 184 26.26795 19 184 27 19.73205 184 28 20 184 29 19.73205 184 29.73205 19 184 30 18 184 28 18 184 -26.26795 17 184 -27 16.26795 184 -28 16 184 -29 16.26795 184 -29.73205 17 184 -30 18 184 -29.73205 19 184 -29 19.73205 184 -28 20 184 -27 19.73205 184 -26.26795 19 184 -26 18 184 -28 18 184 + + + + + + + + + + -0.8271787 -0.5619391 0 0.2702996 0.9627763 -1.45921e-6 -0.2702996 -0.9627763 -1.45921e-6 -0.3625738 0.9319421 -0.004929423 -0.3974618 0.9176188 0 -0.3416614 0.9397881 -0.008119583 -0.3178 0.9480768 -0.01239836 -0.3612409 0.9324678 -0.003003954 -0.410571 0.9071711 0.09204399 -0.3973876 0.9174865 0.01737022 -0.3974502 0.9176234 9.54349e-4 -0.362695 0.9317258 -0.01842606 -0.359493 0.9317881 -0.05035746 -0.2864552 0.9580937 -1.39757e-5 -0.2843831 0.9587108 5.78263e-5 -0.3727346 0.927938 -3.61695e-4 -0.09761238 0.9952245 1.80584e-5 -0.1101703 0.9939128 3.18647e-4 -0.1299953 0.9915129 0.001873254 -0.09604674 0.9953722 -0.003041923 -0.1443872 0.9895153 0.003476738 -0.1145204 0.9934204 -0.0010764 -0.1501448 0.988664 4.52274e-4 -0.1596074 0.9871773 0.002575576 -0.2035089 0.9790674 -0.003372132 -0.1802124 0.983627 -0.001170337 -0.2216054 0.9751364 0 -0.2325429 0.9725779 0.003995537 -0.242192 0.9701847 0.009215652 -0.2327917 0.9725236 0.002423822 -0.2522405 0.9675448 0.01522988 -0.2605009 0.965214 0.02238941 -0.2685991 0.962777 0.0302481 -0.2320648 0.9727004 4.87804e-5 -0.1859779 0.9825309 0.006724774 -0.2838398 0.958805 -0.011312 -0.2373901 0.9714061 -0.004036128 -0.220111 0.9754577 -0.005793213 -0.2213934 0.9751836 -0.001426517 -0.2215905 0.9751398 0 -0.2215904 0.9751399 0 -0.2216113 0.9751351 3.93724e-4 -0.2985314 0.9543998 -4.33599e-4 -0.2828146 0.9591746 4.85517e-5 -0.2322674 0.972652 -1.76898e-4 -0.2167274 0.9748067 -0.05273717 -0.2215907 0.9750847 -0.01036232 -0.1896912 0.9818326 -0.004698455 -0.1672266 0.9858885 -0.007690072 -0.1837466 0.982961 -0.004979431 -0.1506423 0.9885858 -0.00226897 -0.1358282 0.9907318 -0.001170337 -0.11469 0.9934013 -2.65307e-4 -0.09991544 0.994996 -2.0152e-5 -0.09425723 0.995548 -2.37992e-6 -0.09322547 0.9956451 0 -0.09322649 0.995645 0 0.3625738 -0.9319421 -0.004929423 0.3416614 -0.9397881 -0.008119583 0.3178 -0.9480768 -0.01239836 0.3612409 -0.9324678 -0.003003954 0.362695 -0.9317258 -0.01842606 0.359493 -0.9317881 -0.05035746 0.3117882 -0.950044 0.01430302 0.3727331 -0.9279385 -3.67357e-4 0.2842417 -0.9587527 5.93719e-5 0.2864662 -0.9580904 -1.95274e-5 0.4020368 -0.9151991 0.02787703 0.3981195 -0.9173012 0.007713854 0.3974575 -0.9176207 0 0.3974621 -0.9176187 0 0.09761238 -0.9952245 1.80584e-5 0.1101703 -0.9939128 3.18647e-4 0.1299953 -0.9915129 0.001873254 0.09604674 -0.9953722 -0.003041923 0.1443872 -0.9895153 0.003476738 0.1145204 -0.9934204 -0.0010764 0.1501448 -0.988664 4.52274e-4 0.1596074 -0.9871773 0.002575576 0.2035089 -0.9790674 -0.003372132 0.1802124 -0.983627 -0.001170337 0.2208691 -0.9752985 0.00312668 0.2225056 -0.9749314 0 0.234059 -0.9722068 0.005506157 0.241264 -0.9704083 0.009967923 0.2322683 -0.9726489 0.002383947 0.2511762 -0.9677976 0.01668292 0.2591725 -0.9655138 0.02475559 0.2613763 -0.9648526 0.02723979 0.2319422 -0.9727296 6.64259e-5 0.1859779 -0.9825309 0.006724774 0.2838398 -0.958805 -0.011312 0.2373901 -0.9714061 -0.004036128 0.220111 -0.9754577 -0.005793213 0.2213934 -0.9751836 -0.001426517 0.2215905 -0.9751398 0 0.2215905 -0.9751398 0 0.2215909 -0.9751397 0 0.2985314 -0.9543998 -4.33599e-4 0.2828146 -0.9591746 4.85517e-5 0.2322674 -0.972652 -1.76898e-4 0.2167274 -0.9748067 -0.05273717 0.2215907 -0.9750847 -0.01036232 0.1896912 -0.9818326 -0.004698455 0.1672266 -0.9858885 -0.007690072 0.1837466 -0.982961 -0.004979431 0.1506423 -0.9885858 -0.00226897 0.1358282 -0.9907318 -0.001170337 0.11469 -0.9934013 -2.65307e-4 0.09991544 -0.994996 -2.0152e-5 0.09425723 -0.995548 -2.37992e-6 0.09322547 -0.9956451 0 0.09322649 -0.995645 0 -0.2374892 -0.9713902 0 -0.2375492 -0.9713756 3.88828e-5 -0.2103264 -0.9776257 0.003294706 -0.1910284 -0.9815666 0.005927205 -0.1680352 -0.9857314 0.009895503 -0.1707713 -0.9853107 -3.14237e-4 -0.2009853 -0.9795922 -0.002030372 -0.2362546 -0.9716662 -0.00697422 -0.2604045 -0.9654387 -0.01084983 -0.2958633 -0.9550666 -0.01768523 -0.1438046 -0.9896061 3.80736e-4 -0.1505619 -0.9886001 9.17981e-4 -0.1098936 -0.993942 -0.001654148 -0.1355059 -0.9907735 0.002488732 -0.1144517 -0.9934287 5.35055e-4 -0.09988021 -0.9949995 3.37773e-5 -0.094244 -0.9955492 3.28596e-6 -0.09325647 -0.9956422 -4.58354e-7 -0.2213535 -0.9751924 -0.001567304 -0.2222949 -0.9749614 -0.005933761 -0.09322619 -0.9956451 0 -0.09322649 -0.995645 0 -0.0932253 -0.9956451 0 -0.09764575 -0.9952213 -9.79402e-6 -0.1103516 -0.9938927 -1.56636e-4 -0.1303656 -0.9914657 -8.79444e-4 -0.1444875 -0.9895051 -0.001808285 -0.159695 -0.9871621 -0.002934813 -0.1837489 -0.982973 -7.64781e-4 -0.2193728 -0.9755981 -0.009170353 -0.2200124 -0.9748409 -0.03577375 -0.2245067 -0.9730952 -0.0517947 -0.2205306 -0.9753247 -0.01040071 -0.008648991 -0.9999626 1.23754e-4 -0.002948999 -0.9999957 0 0.008660793 -0.9999625 7.06394e-7 0.07486754 -0.9971839 -0.004385352 0.05352544 -0.9985654 -0.001461088 0.01180386 -0.9999292 0.001502633 0.03559106 -0.9993641 -0.002168595 0.02230143 -0.9997509 -8.64578e-4 0.09223252 -0.9957068 -0.007822871 0.03682607 -0.9993106 0.004707932 0.05315613 -0.9985838 0.002193868 0.09322619 -0.9956451 0 0.09324252 -0.9956435 0 0.07289499 -0.9973396 4.93607e-6 0.0649445 -0.9978886 8.69375e-4 -0.05711305 -0.9983661 0.001776218 -0.04164421 -0.9991241 0.004103779 -0.09104102 -0.9958215 -0.007160842 -0.02014291 -0.9997593 0.008702754 -0.09008854 -0.9958498 -0.01293277 -0.0534141 -0.9985709 -0.001738965 -0.05295377 -0.9900078 -0.1306923 -0.0597288 -0.9970321 -0.04857617 -0.06847083 -0.9976182 -0.008354425 -0.08978778 -0.9959558 0.003188312 -0.07287287 -0.9973412 0 -0.07276701 -0.997349 -2.59936e-5 -0.09209024 -0.9957507 3.97577e-7 -0.09105736 -0.9958457 3.25813e-5 -0.08927094 -0.9960074 1.66012e-4 -0.08267843 -0.9965758 -9.82539e-4 0.0535919 -0.9985625 -9.16123e-4 0.07287287 -0.9973412 0 0.07287287 -0.9973412 0 0.03901356 -0.9992371 -0.001767694 0.01817911 -0.9998286 -0.003515481 0 -0.9999845 -0.005577325 0.003315448 -0.9999765 -0.006009459 -0.01244992 -0.9999141 -0.00409305 -0.0344991 -0.9994025 -0.002095699 -0.05033707 -0.9987317 -0.001086175 -0.07253468 -0.9973659 0 -0.07908689 -0.996866 -0.001883089 -0.07287287 -0.9973412 0 -0.978093 -0.2080577 -0.006792247 -0.9594848 -0.2816194 0.008926749 -0.9499251 -0.3124739 0.001548945 -0.9358961 -0.3522724 -0.001662373 -0.9466098 -0.3223817 8.64017e-5 -0.9613165 -0.2754466 -9.13404e-5 -0.9545233 -0.2981314 0.001732051 -0.9695091 -0.245047 -0.002004027 -0.9736444 -0.2280393 -0.003858327 -0.9392846 -0.343139 -2.15056e-4 -0.9369628 -0.3494294 -9.79565e-5 -0.9345881 -0.3557195 0.003000974 -0.9349085 -0.354889 0 -0.9349028 -0.3549041 0 -0.9445754 -0.3282939 -7.2494e-4 -0.9517063 -0.3070032 -0.002071917 -0.9618121 -0.2736599 -0.005275189 -0.9742534 -0.223034 -0.03295862 -0.9740914 -0.2261553 -4.92417e-5 -0.9610771 -0.2762193 -0.005808055 -0.9564884 -0.291658 -0.008101463 -0.9751931 -0.2213562 0 -0.9751919 -0.2213613 0 -0.9751911 -0.2213595 -0.001558303 -0.9749622 -0.2222912 -0.005939126 -0.9753249 -0.22053 -0.01039421 -0.974498 -0.2224255 -0.02967292 -0.9751896 -0.2213717 0 -0.9752269 -0.2212015 0.001574516 -0.9751171 -0.2216908 0 -0.9720639 -0.2346556 0.005354166 -0.969664 -0.2441493 0.01194852 -0.9681794 -0.2497954 0.01519364 -0.9008443 -0.4030779 0.1612696 -0.9734426 -0.2289316 8.49341e-5 -0.990411 -0.1381524 -8.79718e-5 -0.9957389 -0.09125858 -0.01326203 -0.9997554 -0.02022796 0.008951425 -0.9991242 -0.04164302 0.004101932 -0.9954577 -0.09141469 0.02659821 -0.9967383 -0.08032751 0.007773578 -0.9967865 -0.0797674 0.007333159 -0.9971681 -0.07519322 0.00138843 -0.9882081 -0.1089381 0.1075978 -0.7080773 -0.1499321 0.6900341 -0.7080773 -0.149932 0.690034 -0.7080773 -0.149932 0.690034 -0.9950294 -0.0994755 -0.004594862 -0.985798 -0.1676939 0.009012639 -0.9810051 -0.1933377 0.01580178 -0.9900134 -0.05295521 -0.1306493 -0.9970555 -0.05976903 -0.04804313 -0.2078769 -0.7890561 -0.5780811 -0.2078772 -0.7890561 -0.578081 -0.2078774 -0.7890561 -0.578081 -0.9331313 -0.326107 -0.151394 -0.9855086 -0.1659307 -0.03521239 -0.9923415 -0.1231812 -0.009214043 -0.9944174 -0.1054903 -0.002403914 -0.9958342 -0.091174 0.001227259 -0.9957106 -0.09251987 8.43193e-4 -0.9959301 -0.09012937 3.67663e-4 -0.9966024 -0.08235931 -7.81638e-4 -0.997609 -0.06861454 -0.008284389 -0.9841176 -0.1775178 7.82441e-6 -0.9872682 -0.1590647 -3.23246e-4 -0.9957278 -0.09226822 -0.003567516 -0.989515 -0.1437857 -0.01363706 -0.9918748 -0.1267887 -0.0104497 -0.9946574 -0.1030114 -0.006726264 -0.9971886 -0.07471948 -0.005656719 -0.9972738 -0.07378947 0 -0.9972741 -0.07378631 0 -0.9972738 -0.0737906 0 -0.9972742 -0.0737856 0 -0.9972732 -0.07378357 -0.001505434 -0.9898377 0.1113201 0.08848303 -0.9920374 0.1036944 0.07147997 -0.9841169 0.1775218 -4.43738e-6 -0.987258 0.1591273 5.93804e-4 -0.9985648 0.05353641 -0.001460671 -0.999323 0.03679174 -2.70461e-4 -0.9958586 -0.08998608 -0.01296836 -0.9985709 -0.05341577 -0.001739382 -0.9999957 -0.002942264 3.58838e-4 -0.9999626 -0.008653938 0 -0.9999346 0.01143723 0 -0.9999625 0.00865978 -2.26539e-4 -0.9997156 0.02385383 7.46596e-5 -0.9971824 0.07488775 -0.004393577 -0.9952682 0.09677463 -0.008710384 -0.9912601 0.1308074 -0.01711434 -0.9895036 0.144497 0.001859307 -0.9963722 0.08474457 0.007805526 -0.9654814 0.2531722 -0.06123459 -0.9808675 0.191159 -0.0368399 -0.997287 -0.07293301 -0.00997895 -0.9957653 -0.07714885 -0.04999589 -0.9980384 -0.06258529 -0.001525342 -0.9999347 -0.01143115 0 -0.9957342 0.09226882 0 -0.9997636 0.004218161 -0.02133351 -0.9995871 0.02324438 -0.01689493 -0.9986863 0.04994177 -0.01146757 -0.9964615 0.08386856 -0.005524337 -0.9907411 0.1357572 -0.00145924 -0.9886056 0.1505278 -7.38649e-4 -0.9863817 0.1644726 -1.70048e-4 -0.983642 0.1801347 6.98963e-6 -0.997327 0.07284945 -0.005636692 -0.9971591 0.07465606 -0.01001453 -0.9962553 0.07022505 -0.0504387 -0.9961438 0.08639472 0.01528114 -0.9960252 0.08642113 0.02156895 -0.9969652 0.07782745 0.00179857 -0.9968986 0.07855546 0.004712581 -0.9972741 0.07378637 0 -0.9972739 0.07378941 0 -0.9972742 0.07378548 0 -0.9972738 0.07379066 0 -0.9972729 0.07378792 -0.001490533 -0.9741151 0.2257054 0.01252257 -0.9580473 0.2865364 0.006512761 -0.9593852 0.2820994 0 -0.9823094 0.1872659 1.17778e-6 -0.9825131 0.1861938 -1.2625e-5 -0.9800307 0.1988466 4.3413e-5 -0.9393347 0.3428815 -0.009088814 -0.9338941 0.3569985 -0.01984626 -0.9564385 0.2918183 -0.008226633 -0.9722908 0.2337704 -0.001420438 -0.9618121 0.2736599 -0.005275189 -0.9538795 0.3001773 -0.002730488 -0.9484104 0.3170428 -0.001339673 -0.9388927 0.3442071 0.001425266 -0.9434378 0.3315491 -6.4e-4 -0.9402903 0.3403738 -2.88238e-4 -0.9374529 0.3481123 -1.20691e-4 -0.9571093 0.2859095 0.0468803 -0.9585489 0.2818527 0.04175257 -0.9503104 0.3109019 0.01581889 -0.9430675 0.3325743 0.004271507 -0.9642496 0.2640301 0.02260571 -0.9684878 0.2487745 0.01194089 -0.973491 0.2287254 0 -0.9755516 0.2189627 0.0188294 -0.9745801 0.223937 -0.006768107 -0.9761239 0.2171992 0.002586424 -0.9731545 0.2283703 -0.02858841 -0.9756075 0.2192617 -0.0107069 -0.9758685 0.2183593 -5.68997e-5 -0.966149 0.2579585 -0.003661811 -0.959592 0.2813207 -0.0064767 0.978093 0.2080577 -0.006792247 0.9594848 0.2816194 0.008926749 0.9499251 0.3124739 0.001548945 0.9358961 0.3522724 -0.001662373 0.9466098 0.3223817 8.64017e-5 0.9613165 0.2754466 -9.13404e-5 0.9545233 0.2981314 0.001732051 0.9695091 0.245047 -0.002004027 0.9736444 0.2280393 -0.003858327 0.9392846 0.343139 -2.15056e-4 0.9369628 0.3494294 -9.79565e-5 0.9345881 0.3557195 0.003000974 0.9349085 0.354889 0 0.9349028 0.3549041 0 0.9445754 0.3282939 -7.2494e-4 0.9517063 0.3070032 -0.002071917 0.9618121 0.2736599 -0.005275189 0.9742534 0.223034 -0.03295862 0.9740914 0.2261553 -4.92417e-5 0.9610771 0.2762193 -0.005808055 0.9564884 0.291658 -0.008101463 0.9751931 0.2213562 0 0.9751919 0.2213613 0 0.9751911 0.2213595 -0.001558303 0.9749622 0.2222912 -0.005939126 0.9753249 0.22053 -0.01039421 0.974498 0.2224255 -0.02967292 0.9751896 0.2213717 0 0.9752269 0.2212015 0.001574516 0.9751171 0.2216908 0 0.9720639 0.2346556 0.005354166 0.969664 0.2441493 0.01194852 0.9681794 0.2497954 0.01519364 0.9008443 0.4030779 0.1612696 0.9734426 0.2289316 8.49341e-5 0.990411 0.1381524 -8.79718e-5 0.9957389 0.09125858 -0.01326203 0.9997554 0.02022796 0.008951425 0.9991242 0.04164302 0.004101932 0.9954577 0.09141469 0.02659821 0.9967383 0.08032751 0.007773578 0.9967865 0.0797674 0.007333159 0.9971681 0.07519322 0.00138843 0.9882081 0.1089381 0.1075978 0.7080773 0.1499321 0.6900341 0.7080773 0.149932 0.690034 0.7080773 0.149932 0.690034 0.9950294 0.0994755 -0.004594862 0.985798 0.1676939 0.009012639 0.9810051 0.1933377 0.01580178 0.9900134 0.05295521 -0.1306493 0.9970555 0.05976903 -0.04804313 0.2078769 0.7890561 -0.5780811 0.2078772 0.7890561 -0.578081 0.2078774 0.7890561 -0.578081 0.9331313 0.326107 -0.151394 0.9855086 0.1659307 -0.03521239 0.9923415 0.1231812 -0.009214043 0.9944174 0.1054903 -0.002403914 0.9958342 0.091174 0.001227259 0.9957106 0.09251987 8.43193e-4 0.9959301 0.09012937 3.67663e-4 0.9966024 0.08235931 -7.81638e-4 0.997609 0.06861454 -0.008284389 0.9841176 0.1775178 7.82441e-6 0.9872682 0.1590647 -3.23246e-4 0.9957278 0.09226822 -0.003567516 0.989515 0.1437857 -0.01363706 0.9918748 0.1267887 -0.0104497 0.9946574 0.1030114 -0.006726264 0.9971886 0.07471948 -0.005656719 0.9972738 0.07378947 0 0.9972741 0.07378631 0 0.9972738 0.0737906 0 0.9972742 0.0737856 0 0.9972732 0.07378357 -0.001505434 0.9898377 -0.1113201 0.08848303 0.9920374 -0.1036944 0.07147997 0.9841169 -0.1775218 -4.43738e-6 0.987258 -0.1591273 5.93804e-4 0.9985648 -0.05353641 -0.001460671 0.999323 -0.03679174 -2.70461e-4 0.9958586 0.08998608 -0.01296836 0.9985709 0.05341577 -0.001739382 0.9999957 0.002942264 3.58838e-4 0.9999626 0.008653938 0 0.9999346 -0.01143723 0 0.9999625 -0.00865978 -2.26539e-4 0.9997156 -0.02385383 7.46596e-5 0.9971824 -0.07488775 -0.004393577 0.9952682 -0.09677463 -0.008710384 0.9912601 -0.1308074 -0.01711434 0.9895036 -0.144497 0.001859307 0.9963722 -0.08474457 0.007805526 0.9654814 -0.2531722 -0.06123459 0.9808675 -0.191159 -0.0368399 0.997287 0.07293301 -0.00997895 0.9957653 0.07714885 -0.04999589 0.9980384 0.06258529 -0.001525342 0.9999347 0.01143115 0 0.9957342 -0.09226882 0 0.9997636 -0.004218161 -0.02133351 0.9995871 -0.02324438 -0.01689493 0.9986863 -0.04994177 -0.01146757 0.9964615 -0.08386856 -0.005524337 0.9907411 -0.1357572 -0.00145924 0.9886056 -0.1505278 -7.38649e-4 0.9863817 -0.1644726 -1.70048e-4 0.983642 -0.1801347 6.98963e-6 0.997327 -0.07284945 -0.005636692 0.9971591 -0.07465606 -0.01001453 0.9962553 -0.07022505 -0.0504387 0.9961438 -0.08639472 0.01528114 0.9960252 -0.08642113 0.02156895 0.9969652 -0.07782745 0.00179857 0.9968986 -0.07855546 0.004712581 0.9972741 -0.07378637 0 0.9972739 -0.07378941 0 0.9972742 -0.07378548 0 0.9972738 -0.07379066 0 0.9972729 -0.07378792 -0.001490533 0.9741151 -0.2257054 0.01252257 0.9580473 -0.2865364 0.006512761 0.9593852 -0.2820994 0 0.9823094 -0.1872659 1.17778e-6 0.9825131 -0.1861938 -1.2625e-5 0.9800307 -0.1988466 4.3413e-5 0.9393347 -0.3428815 -0.009088814 0.9338941 -0.3569985 -0.01984626 0.9564385 -0.2918183 -0.008226633 0.9722908 -0.2337704 -0.001420438 0.9618121 -0.2736599 -0.005275189 0.9538795 -0.3001773 -0.002730488 0.9484104 -0.3170428 -0.001339673 0.9388927 -0.3442071 0.001425266 0.9434378 -0.3315491 -6.4e-4 0.9402903 -0.3403738 -2.88238e-4 0.9374529 -0.3481123 -1.20691e-4 0.9571093 -0.2859095 0.0468803 0.9585489 -0.2818527 0.04175257 0.9503104 -0.3109019 0.01581889 0.9430675 -0.3325743 0.004271507 0.9642496 -0.2640301 0.02260571 0.9684878 -0.2487745 0.01194089 0.973491 -0.2287254 0 0.9755516 -0.2189627 0.0188294 0.9745801 -0.223937 -0.006768107 0.9761239 -0.2171992 0.002586424 0.9731545 -0.2283703 -0.02858841 0.9756075 -0.2192617 -0.0107069 0.9758685 -0.2183593 -5.68997e-5 0.966149 -0.2579585 -0.003661811 0.959592 -0.2813207 -0.0064767 0.2374892 0.9713902 0 0.2375492 0.9713756 3.88828e-5 0.2103264 0.9776257 0.003294706 0.1910284 0.9815666 0.005927205 0.1680352 0.9857314 0.009895503 0.1707713 0.9853107 -3.14237e-4 0.2009853 0.9795922 -0.002030372 0.2362546 0.9716662 -0.00697422 0.2604045 0.9654387 -0.01084983 0.2958633 0.9550666 -0.01768523 0.1438046 0.9896061 3.80736e-4 0.1505619 0.9886001 9.17981e-4 0.1098936 0.993942 -0.001654148 0.1355059 0.9907735 0.002488732 0.1144517 0.9934287 5.35055e-4 0.09988021 0.9949995 3.37773e-5 0.094244 0.9955492 3.28596e-6 0.09325647 0.9956422 -4.58354e-7 0.2249801 0.9743634 0 0.2169879 0.976079 0.01364785 0.2213575 0.9751854 0.003791868 0.2213535 0.9751924 -0.001567304 0.2222949 0.9749614 -0.005933761 0.09322619 0.9956451 0 0.09322649 0.995645 0 0.0932253 0.9956451 0 0.09764575 0.9952213 -9.79402e-6 0.1103516 0.9938927 -1.56636e-4 0.1303656 0.9914657 -8.79444e-4 0.1444875 0.9895051 -0.001808285 0.159695 0.9871621 -0.002934813 0.1837489 0.982973 -7.64781e-4 0.2193728 0.9755981 -0.009170353 0.2200124 0.9748409 -0.03577375 0.2245067 0.9730952 -0.0517947 0.2205306 0.9753247 -0.01040071 0.008648991 0.9999626 1.23754e-4 0.002948999 0.9999957 0 -0.008660793 0.9999625 7.06394e-7 -0.07486754 0.9971839 -0.004385352 -0.05352544 0.9985654 -0.001461088 -0.01180386 0.9999292 0.001502633 -0.03559106 0.9993641 -0.002168595 -0.02230143 0.9997509 -8.64578e-4 -0.09223252 0.9957068 -0.007822871 -0.03682607 0.9993106 0.004707932 -0.05315613 0.9985838 0.002193868 -0.09322619 0.9956451 0 -0.09324252 0.9956435 0 -0.07289499 0.9973396 4.93607e-6 -0.0649445 0.9978886 8.69375e-4 0.05711305 0.9983661 0.001776218 0.04164421 0.9991241 0.004103779 0.09104102 0.9958215 -0.007160842 0.02014291 0.9997593 0.008702754 0.09008854 0.9958498 -0.01293277 0.0534141 0.9985709 -0.001738965 0.05295377 0.9900078 -0.1306923 0.0597288 0.9970321 -0.04857617 0.06847083 0.9976182 -0.008354425 0.08978778 0.9959558 0.003188312 0.07287287 0.9973412 0 0.07276701 0.997349 -2.59936e-5 0.09209024 0.9957507 3.97577e-7 0.09105736 0.9958457 3.25813e-5 0.08927094 0.9960074 1.66012e-4 0.08267843 0.9965758 -9.82539e-4 -0.0535919 0.9985625 -9.16123e-4 -0.07287287 0.9973412 0 -0.07287287 0.9973412 0 -0.03901356 0.9992371 -0.001767694 -0.01817911 0.9998286 -0.003515481 0 0.9999845 -0.005577325 -0.003315448 0.9999765 -0.006009459 0.01244992 0.9999141 -0.00409305 0.0344991 0.9994025 -0.002095699 0.05033707 0.9987317 -0.001086175 0.07253468 0.9973659 0 0.07908689 0.996866 -0.001883089 0.07287287 0.9973412 0 -0.8940929 0.4478445 -0.005775451 -0.88634 0.4629577 -0.008466958 -0.8793008 0.4761362 -0.01115721 -0.9594622 0.2818376 9.1078e-5 -0.918432 0.3955788 -3.9285e-5 -0.9021668 0.4313725 -0.003614902 -0.8721522 0.4890278 -0.01423209 -0.8646619 0.5020456 -0.01761102 -0.8951617 0.4457386 -0.001611292 -0.8951629 -0.4457394 0 -0.8533612 -0.5208097 -0.02306836 -0.8646619 -0.5020456 -0.01761102 -0.872152 -0.4890279 -0.01423251 -0.879302 -0.4761341 -0.01115733 -0.88634 -0.4629577 -0.008466958 -0.8940925 -0.4478452 -0.005775392 -0.9430523 -0.3326444 5.14039e-4 -0.9362552 -0.3513209 1.21808e-5 -0.9184319 -0.3955792 -3.9285e-5 -0.9021661 -0.4313738 -0.003614842 -0.7802676 -0.6253704 -0.009716331 -0.7980136 -0.6026315 -0.003096282 -0.7480244 -0.6636712 0 -0.7232525 -0.6905838 0 -0.6736886 -0.7390007 -0.004658758 -0.6807556 -0.732481 -0.006596922 -0.4964379 -0.8680691 -0.002352237 -0.4561929 -0.889881 1.37605e-5 -0.4723325 -0.8814203 -5.87388e-4 -0.485 -0.8745132 -0.001334547 -0.5074544 -0.8616715 -0.003528118 -0.5565696 -0.830738 -0.01023513 -0.5264322 -0.8502166 -9.9665e-4 -0.5995431 -0.8003425 0 -0.6284131 -0.7778798 0 -0.3628742 -0.9316586 -0.01829791 -0.3592166 -0.9318853 -0.05052959 -0.362543 -0.931156 -0.0388717 -0.3612091 -0.9324849 -1.0426e-4 -0.3612425 -0.9324719 -9.54952e-5 0.5565696 -0.830738 -0.01023495 0.5264322 -0.8502167 -9.96723e-4 0.5074544 -0.8616715 -0.003527522 0.4964392 -0.8680684 -0.002352237 0.485 -0.8745132 -0.001334547 0.3392133 -0.9406672 0.00893414 0.3939719 -0.9191225 -6.40874e-5 0.4561929 -0.889881 1.37605e-5 0.472332 -0.8814206 -5.87218e-4 0.7232525 -0.6905838 0 0.6807648 -0.7324911 -0.004013359 0.6736851 -0.7389968 -0.005682945 0.6284131 -0.7778798 0 0.5995431 -0.8003425 0 0.7980018 -0.6026235 -0.006168782 0.780304 -0.6253974 -0.00196588 0.7480244 -0.6636712 0 0.8940929 -0.4478445 -0.005775451 0.88634 -0.4629577 -0.008466958 0.8793008 -0.4761362 -0.01115721 0.9594622 -0.2818376 9.1078e-5 0.918432 -0.3955788 -3.9285e-5 0.9021668 -0.4313725 -0.003614902 0.8721522 -0.4890278 -0.01423209 0.8646619 -0.5020456 -0.01761102 0.8951617 -0.4457386 -0.001611292 0.8535873 -0.52095 0 0.8271787 -0.5619391 0 0.872152 0.4890279 -0.01423251 0.879302 0.4761341 -0.01115733 0.88634 0.4629577 -0.008466958 0.8940925 0.4478452 -0.005775392 0.9430523 0.3326444 5.14039e-4 0.9362552 0.3513209 1.21808e-5 0.9184319 0.3955792 -3.9285e-5 0.9021661 0.4313738 -0.003614842 0.7480244 0.6636712 0 0.780304 0.6253974 -0.00196588 0.7980018 0.6026235 -0.006168782 0.8271787 0.5619391 0 0.8951629 0.4457394 0 0.8533613 0.5208095 -0.02306872 0.8646619 0.5020456 -0.01761102 0.7232525 0.6905838 0 0.6736886 0.7390007 -0.004658758 0.6807556 0.732481 -0.006596922 0.4964379 0.8680691 -0.002352237 0.4561929 0.889881 1.37605e-5 0.4723325 0.8814203 -5.87388e-4 0.485 0.8745132 -0.001334547 0.5074544 0.8616715 -0.003528118 0.5565696 0.830738 -0.01023513 0.5264322 0.8502166 -9.9665e-4 0.5995431 0.8003425 0 0.6284131 0.7778798 0 0.3628742 0.9316586 -0.01829791 0.3592166 0.9318853 -0.05052959 0.362543 0.931156 -0.0388717 0.3612091 0.9324849 -1.0426e-4 0.3612425 0.9324719 -9.54952e-5 -0.5565696 0.830738 -0.01023495 -0.5264322 0.8502167 -9.96723e-4 -0.5074544 0.8616715 -0.003527522 -0.4964392 0.8680684 -0.002352237 -0.485 0.8745132 -0.001334547 -0.3117362 0.9500644 0.01408171 -0.3845021 0.9231241 -7.57576e-5 -0.4561929 0.889881 1.37605e-5 -0.472332 0.8814206 -5.87218e-4 -0.7232525 0.6905838 0 -0.6807648 0.7324911 -0.004013359 -0.6736851 0.7389968 -0.005682945 -0.6284131 0.7778798 0 -0.5995431 0.8003425 0 -0.8535873 0.52095 0 -0.8271787 0.5619391 0 -0.7980018 0.6026235 -0.006168782 -0.780304 0.6253974 -0.00196588 -0.7480244 0.6636712 0 -0.2812399 -0.9596375 4.2213e-6 -0.29212 -0.9563817 -2.373e-4 -0.3612415 -0.9324693 -0.002380847 -0.3096769 -0.9507383 -0.01403236 -0.3350347 -0.9421608 -0.009213685 -0.3558669 -0.9345181 -0.005890667 -0.3891202 -0.921155 0.007680773 -0.3798787 -0.9248666 0.01772135 -0.2907108 -0.9568087 0.002122104 -0.2782494 -0.9605088 -3.87653e-4 -0.2374885 -0.9713885 0.001966238 -0.2503765 -0.9680442 0.01421254 -0.2279743 -0.9736672 0 -0.2138409 -0.9766501 0.02066087 -0.2213575 -0.9751854 0.003791868 -0.3736688 -0.9272162 0.02533423 -0.3624789 -0.9310964 0.04084771 -0.3608978 -0.9315811 0.04369902 -0.3183345 -0.9478744 0.01405084 -0.3002793 -0.9538365 0.005336105 0.2812399 0.9596375 4.2213e-6 0.29212 0.9563817 -2.373e-4 0.3612415 0.9324693 -0.002380847 0.3765408 0.9261548 0.02132081 0.3891202 0.921155 0.007680773 0.3096769 0.9507383 -0.01403236 0.3350347 0.9421608 -0.009213685 0.3558669 0.9345181 -0.005890667 0.2907108 0.9568087 0.002122104 0.2782494 0.9605088 -3.87653e-4 0.2374885 0.9713885 0.001966238 0.2503765 0.9680442 0.01421254 0.240417 0.9706377 0.007880389 0.3624807 0.9310959 0.04084426 0.3511253 0.9343275 0.0611813 0.3609147 0.9316251 0.04260659 0.315243 0.9489281 0.01255226 0.3002793 0.9538365 0.005336105 0.3974617 -0.9176188 0 0.5264325 -0.8502171 0 0.5264322 -0.8502172 0 0.6736961 -0.7390086 0 0.6736956 -0.739009 0 0.7980173 -0.6026346 0 0.7980177 -0.6026342 0 0.8951629 -0.4457392 0 0.9350438 -0.3545324 0 0.9371377 -0.3489596 6.63556e-4 -0.9349079 -0.3548908 0 -0.8951629 -0.4457392 0 -0.7980176 -0.6026342 0 -0.7980173 -0.6026346 0 -0.6736957 -0.7390089 0 -0.6736959 -0.7390087 0 -0.5264322 -0.8502172 0 -0.5264325 -0.8502171 0 -0.3973628 -0.9176617 0 -0.4027178 -0.9153132 -0.004517197 -0.3974617 0.9176188 0 -0.5264325 0.8502171 0 -0.5264322 0.8502172 0 -0.6736961 0.7390086 0 -0.6736956 0.739009 0 -0.7980173 0.6026346 0 -0.7980177 0.6026342 0 -0.8951629 0.4457392 0 -0.9350438 0.3545324 0 -0.9371377 0.3489596 6.63556e-4 0.9349079 0.3548908 0 0.8951629 0.4457392 0 0.7980176 0.6026342 0 0.7980173 0.6026346 0 0.6736957 0.7390089 0 0.6736959 0.7390087 0 0.5264322 0.8502172 0 0.5264325 0.8502171 0 0.3973628 0.9176617 0 0.4027178 0.9153132 -0.004517197 -0.239663 0 0.9708562 -0.239665 0 0.9708557 -0.6638694 0 0.7478486 -0.6638734 0 0.747845 -0.9333302 0 0.3590192 -0.9333277 0 0.3590258 -0.9979351 0 0.06423193 -0.997935 0 0.06423264 0.3093112 0.9508596 -0.01388436 0.3041117 0.9520708 -0.03282457 0.3030318 0.9523475 -0.03472828 0.1821016 0.9696069 -0.1634058 0.3065984 0.9516961 -0.01649534 0.3201653 0.9473577 -0.002775311 0.3443932 0.9388238 0.00181812 0.3466196 0.9379957 -0.004363119 0.3572758 0.9339988 -5.92727e-4 0.3496838 0.936867 0.001223623 0.3469302 0.9378764 0.005238473 0.2751523 0.9613884 0.004862666 0.3092537 0.9506827 0.02376121 0.3030336 0.952347 0.03472626 0.1821083 0.969606 0.1634042 0.3065992 0.9516959 0.01648706 0.3390376 0.9406278 -0.01652038 0.3118268 0.9493394 0.03897207 0.239663 0 0.9708562 0.239665 0 0.9708557 0.6638694 0 0.7478486 0.6638734 0 0.747845 0.9333302 0 0.3590192 0.9333277 0 0.3590258 0.9979351 0 0.06423193 0.997935 0 0.06423264 0.1334748 0.8157937 0.56273 0.1200213 0.8195706 0.5602669 0.3697534 0.9067596 0.2026561 0.3449065 0.9172778 0.1991009 0.3914953 0.6848384 0.6145957 0.5304411 0.7210667 0.4457525 0.4877663 0.7341705 0.4723111 0.4681163 0.8330134 0.2948828 0.4791707 0.8383461 0.2599447 0.4843467 0.8474032 0.2175229 0.5013722 0.8505092 0.1589348 0.5548309 0.8297376 0.06081384 0.4869632 0.8733921 -0.007286489 0.4923287 0.855777 -0.1589292 0.4959021 0.8507526 -0.1740726 0.4854963 0.8496689 -0.2058067 0.3751079 0.6561474 0.6548012 0.4628296 0.8647433 0.1949558 0.3658379 0.773369 0.5177479 0.4939566 0.8694414 0.008859395 0.4552457 0.8658755 0.2073912 0.3934645 0.9003461 0.1859111 0.3916662 0.8949241 0.2137957 0.3089507 0.7593363 0.5726762 0.2159704 0.8125358 0.5414263 0.1571872 0.8031857 0.5746171 0.4829763 0.8451912 -0.2288792 0.391786 0.904454 0.1687213 0.4280547 0.8395238 0.3346177 0.3666675 0.8917867 0.2650876 0.004741251 0.9570005 0.2900477 0.004651725 0.9572983 0.2890647 0.09072738 0.9604582 0.2632275 0.1148049 0.9702567 0.2131241 0.3732945 0.9141511 0.1580477 0.247996 0.9368035 0.2467738 0.2502458 0.9301868 0.2685698 0.09826099 0.9363488 0.3370398 0.1290645 0.9483916 0.2896475 0.004846215 0.9569922 0.2900732 0.439305 0.8725029 0.2138919 0.3577304 0.9269779 0.1128754 0.226046 0.9607049 0.1610877 0.1352332 0.9241654 0.3572539 0.1314283 0.9560157 0.2622229 0.007759571 0.9639164 0.2660921 0.3780367 0.9237735 0.06108045 0.3499168 0.9361034 0.035618 0.2374438 0.9529673 0.1883451 0.08798491 0.9894914 0.1147417 0.08552175 0.9673891 0.2384207 0.002038061 0.9636494 0.2671625 0.007411181 0.9597161 0.2808741 0.1025474 0.9870364 0.1234638 0.3597598 0.9166446 0.1741713 0.3528798 0.9244741 0.1443036 0.3109368 0.9469059 0.08177804 0.1947193 0.976967 0.08729255 0.05871695 0.9832616 0.1724792 0.3664222 0.9279432 0.0682373 0.3381885 0.9392828 0.05810755 0.1220421 0.9755482 0.1827882 0.1114483 0.977217 0.1806274 -0.012676 0.9742258 0.2252185 0.1206737 0.8192618 0.5605784 0.3456187 0.9169325 0.1994559 0.1081119 0.8173784 0.5658662 0.09497827 0.8229932 0.5600548 0.07980847 0.8154516 0.573297 0.05589169 0.8222634 0.5663561 0.0471704 0.8161129 0.5759643 0.01880198 0.8202767 0.571658 0.01468098 0.8154386 0.5786573 0.3101063 0.9248912 0.2200238 0.2749571 0.9394281 0.2046302 0.2317241 0.9394575 0.2524354 0.1648347 0.9583836 0.2330893 0.1388298 0.9536926 0.2668274 0.05734127 0.9653864 0.2544429 0.04453527 0.9593895 0.2785469 0.1886851 0.6951001 0.6937102 0.103797 0.7946895 0.598076 0.1363626 0.7634964 0.6312517 0.2634465 0.69245 0.6716465 0.09120929 0.6065269 0.7898139 0.3387274 0.6723328 0.6582039 0.325006 0.6694071 0.6680309 0.3247447 0.7053136 0.6301378 0.3285466 0.6972466 0.6371062 0.07238119 0.6643993 0.7438646 0.09166944 0.706651 0.701599 0.2073553 0.9703261 -0.1243836 0.3761702 0.8649188 0.3322824 0.4692471 0.8680623 -0.162096 0.3199706 0.9247077 0.2062391 0.3749771 0.9268585 -0.01804262 0.4678497 0.8745635 -0.1274963 0.3792613 0.9124178 0.153801 0.4051786 0.9078306 0.1080467 0.4064354 0.8876623 0.2164854 0.3938244 0.8699279 0.2968632 0.07389813 0.7573691 0.6487921 0.3294654 0.8151069 0.4765011 0.3982672 0.7380465 0.5446748 0.1037311 0.8020267 0.5882117 0.02238976 0.9341822 0.3560933 0.1380708 0.8786383 0.45709 0.07021266 0.9897028 0.1247342 0.1201485 0.9760689 0.1812563 0.09280711 0.9923588 -0.08130836 0.06399214 0.9916335 -0.1121073 0.4698505 0.8578947 -0.2079839 0.3881258 0.802096 -0.4538727 0.3529068 0.9030608 -0.2448224 0.2085363 0.9431551 -0.2587878 0.0925424 0.898735 -0.4286157 0.06435275 0.9631514 -0.2611477 0.122461 0.9448779 0.3036596 0.3603028 0.8771365 0.3175112 0.004768013 0.9568422 0.2905691 0.117605 0.9417546 0.3150671 0.1270149 0.944096 0.3042203 0.3601855 0.8774569 0.3167584 0.3598226 0.8773224 0.3175423 0.7407279 0.4774447 0.4726191 0.6858221 0.5534273 0.4726166 0.4774442 0.7407291 0.4726177 0.477448 0.7407274 0.4726166 0.5534293 0.6858186 0.4726193 0.5534271 0.6858225 0.4726161 0.6231485 0.623153 0.4726166 0.6290387 0.66343 0.4051803 0.704795 0.7048024 0.0807318 0.5407668 0.8389666 0.06088036 0.704802 0.7047957 0.08073014 0.6259407 0.7756808 0.08073157 0.6259421 0.77568 0.08072954 0.5450252 0.834522 0.08075058 0.5231856 0.8117076 0.2596303 0.7407301 0.4774435 0.472617 0.8116981 0.5232203 0.2595892 0.8345213 0.5450261 0.08075243 0.8389668 0.5407665 0.06088101 0.8277359 0.5335111 -0.1738372 0.8277165 0.5335358 -0.1738528 0.7663722 0.6184253 -0.1738504 0.7756795 0.6259427 0.08072853 0.7756816 0.62594 0.0807299 0.6858201 0.5534308 0.4726154 0.6393581 0.6062086 0.4730038 0.5335218 0.8277283 -0.1738401 0.5335234 0.8277249 -0.173851 0.6184284 0.7663719 -0.1738404 0.618446 0.7663582 -0.1738381 0.6775289 0.7146124 -0.1740223 0.7067848 0.7067807 -0.03027194 0.7145856 0.6775577 -0.1740201 0.7663626 0.618442 -0.1738331 0.423074 0.6355333 0.6458374 0.4097163 0.6356566 0.6542732 0.6410589 0.4102517 0.6486424 0.6398575 0.4102362 0.6498375 0.635654 0.4097185 0.6542742 0.4101456 0.6392197 0.6505219 0.4094768 0.6315314 0.6584049 0.4767282 0.59077 0.6509387 0.475699 0.593527 0.6491812 0.5177594 0.5460704 0.6585837 0.5146644 0.5537675 0.6545702 0.5485324 0.5200918 0.6546883 0.5518329 0.5128663 0.6576083 0.5916557 0.4774381 0.6496125 0.5921485 0.4745951 0.6512448 0.6270302 0.417371 0.6577497 0.8156173 0.5438597 0.1974465 0.5539439 0.8324825 0.01092082 0.5421557 0.8167573 0.1974205 0.8323731 0.5541124 0.01070088 0.8323731 0.5541125 0.01070088 0.8323732 0.5541124 0.01070082 0.8198824 0.5443891 0.1772952 0.7679414 0.6154609 0.1774086 0.7679237 0.6154817 0.1774136 0.7208876 0.6699601 0.1774109 0.7208599 0.6699904 0.1774091 0.6699908 0.7208614 0.1774011 0.6699513 0.7208943 0.1774167 0.6154968 0.7679123 0.1774103 0.6154648 0.7679368 0.1774156 0.5461021 0.81874 0.1773055 0.4730507 0.7101464 0.5214549 0.4758406 0.7167809 0.5097067 0.5379537 0.6712248 0.5099638 0.5379716 0.6712048 0.5099714 0.585574 0.6301075 0.5099684 0.5856083 0.6300775 0.509966 0.6300728 0.5856077 0.5099725 0.6300969 0.5855891 0.5099642 0.671204 0.5379734 0.5099705 0.6712154 0.5379671 0.5099622 0.7160034 0.4769828 0.5097318 0.710912 0.4718785 0.5214738 0.4697693 0.8827879 -0.001527607 0.4950443 0.8688641 0.002521574 0.4956344 0.8685232 0.003752112 0.5538562 0.8325506 -0.01014757 0.5434459 0.8369432 -0.0647515 0.6240907 0.7786877 0.06447046 0.6095355 0.7921013 -0.03228282 0.6805031 0.7322092 0.02802437 0.6759204 0.7369747 0 0.7324965 0.6807709 0 0.7367643 0.6757328 0.02374315 0.7801502 0.6252894 -0.01946496 0.7919177 0.6093866 0.03891682 0.8315424 0.5531712 -0.05038774 0.838678 0.5445708 -0.00788933 0.8689877 0.4948182 0.003938078 0.8685227 0.4956427 0.002616405 0.8827939 0.4697583 -0.001526474 0.8101078 0.57249 0.1264142 0.8552509 0.5141879 0.06447356 0.8683749 0.4955427 0.01904475 0.834215 0.4883054 0.2562091 0.8204873 0.5191325 0.2393787 0.8143367 0.5287652 0.2392977 0.8143374 0.5287644 0.2392967 0.7695033 0.5921392 0.2392406 0.7695054 0.5921381 0.2392367 0.7155669 0.6562997 0.2392379 0.7155668 0.6562994 0.239239 0.6563003 0.7155663 0.2392381 0.6563003 0.7155669 0.2392362 0.5921404 0.7695032 0.2392379 0.5921376 0.7695045 0.2392402 0.5287612 0.8143393 0.2392974 0.5287649 0.8143373 0.239296 0.5188426 0.82067 0.2393811 0.4883316 0.834262 0.256006 0.5141794 0.8552561 0.0644719 0.4955377 0.8683777 0.01904344 0.8883014 0.452125 0.08064544 0.835962 0.54281 0.08077734 0.8359671 0.5428025 0.08077478 0.7899316 0.6078542 0.08075571 0.7899284 0.6078584 0.08075439 0.7345634 0.6737173 0.08075726 0.7345603 0.6737207 0.08075779 0.6737224 0.7345588 0.08075702 0.6737174 0.7345633 0.08075702 0.6078591 0.7899278 0.080756 0.6078543 0.7899315 0.08075612 0.5428075 0.8359639 0.08077561 0.5428072 0.8359637 0.08077698 0.5299693 0.8441576 0.08081209 0.4828956 0.8629566 0.1487205 0.542925 0.779425 0.3126167 0.4792878 0.8188155 0.3159504 0.8187968 0.4793111 0.315963 0.778885 0.5057325 0.3709084 0.5691781 0.4379819 0.6958508 0.6688981 0.6689118 0.3242412 0.7812409 0.5442005 0.3057914 0.7788335 0.543815 0.312544 0.6219276 0.5704013 0.5365151 0.6402488 0.6980701 0.3205927 0.5446295 0.7809132 0.3058653 0.4379904 0.5691812 0.6958428 0.5057443 0.7788739 0.3709155 0.0836941 0.9779709 -0.1912284 0.02426105 0.9968693 -0.07525449 0.02828532 0.9960137 -0.084598 0.07062864 0.9929137 -0.09557181 0.07007026 0.9933887 -0.09093427 0.1129222 0.9868826 -0.1153746 0.1151257 0.9884794 -0.09825813 0.1731155 0.9730111 -0.152579 0.2436602 0.9690235 -0.04028886 0.2751313 0.9578065 -0.08312422 0.3393397 0.9383536 -0.06588828 0.3286434 0.9418773 -0.0697202 0.3176547 0.946857 -0.05056923 0.1156426 0.9731422 -0.1990507 0.1118778 0.9733449 -0.2002077 0.1084686 0.9749368 -0.1942499 0.09258371 0.974716 -0.2033645 0.03238296 0.9647215 -0.2612735 0.09385901 0.9618587 -0.2569407 0.1328794 0.9570844 -0.257551 0.2318092 0.9388191 -0.254722 0.3988847 0.8851207 -0.2396925 0.4125763 0.8803868 -0.2338802 0.3888137 0.8896312 -0.2395419 0.3732216 0.8965866 -0.2384077 0.3482616 0.9099583 -0.225144 0.4022462 0.8841888 -0.2375043 0.4544272 0.8845062 -0.1055696 0.4096327 0.8838676 -0.2257857 0.4810503 0.8739315 -0.0695309 0.4617542 0.885208 -0.05647921 0.4573381 0.8863312 -0.07251954 0.4367662 0.8979794 -0.05355811 0.418803 0.9044428 -0.08116358 0.4018316 0.9138571 -0.05828148 0.3867225 0.918826 -0.07876884 0.3726997 0.9262452 -0.05625766 0.3465213 0.9346989 -0.07912653 0.4249476 0.8822729 -0.2025192 0.3792952 0.9091987 -0.1717348 0.3661599 0.9073429 -0.2065328 0.3225358 0.9318301 -0.1663234 0.2748508 0.9349272 -0.2244288 0.2403106 0.9542589 -0.1778787 0.2028309 0.9543476 -0.2192726 0.176875 0.9680749 -0.1776125 0.1248769 0.9683718 -0.2160136 0.8083826 0.5421093 -0.2294234 0.5274284 0.8182755 -0.2285709 0.5419086 0.8085034 -0.2294719 0.5419086 0.8085035 -0.2294719 0.5419086 0.8085035 -0.2294719 0.5428586 0.8093745 -0.224093 0.5249381 0.8207091 -0.225559 0.8093984 0.542963 -0.2237534 0.8093329 0.5431087 -0.2236366 0.8093745 0.5428586 -0.2240927 0.5431316 0.8093292 -0.2235942 0.5340686 0.8134943 -0.2302123 0.6090305 0.7598792 -0.2273008 0.6116533 0.7579762 -0.2266111 0.6625096 0.7128515 -0.2300517 0.6697938 0.7064184 -0.2288 0.7130802 0.6627204 -0.2287319 0.7061346 0.6695252 -0.2304564 0.76004 0.6091577 -0.2264202 0.7578752 0.6115734 -0.2271637 0.8168371 0.5288874 -0.2303373 0.8182757 0.5274283 -0.2285701 0 0.9570289 0.2899925 0 0.9570259 0.2900025 0 0.957036 0.2899693 0 0.9570289 0.289993 0 0.957032 0.2899827 1.0582e-6 0.9570402 0.2899556 -6.1395e-7 0.9570292 0.2899914 -2.06048e-7 0.9570308 0.2899864 0 0.9591551 0.2828807 0 0.9890112 0.1478413 -3.37976e-5 0.9889418 0.1483048 4.33797e-5 0.9751138 0.2217049 -2.19773e-4 0.9632175 0.268723 -0.001663029 0.9751006 0.221757 0.005913972 0.9586682 0.284465 0.004392087 0.962816 0.2701222 0 0.8155223 0.5787256 0 0.8155295 0.5787156 0 0.9603426 0.2788227 1.08314e-5 0.7078159 0.706397 2.73396e-6 0.7078132 0.7063997 9.67819e-5 0.7078746 0.7063382 0 0.7078321 0.7063808 0 0.7078295 0.7063834 -1.57373e-5 0.707795 0.706418 1.25051e-5 0.7078357 0.7063772 1.57373e-5 0.707795 0.706418 -1.40683e-5 0.707836 0.7063769 -1.20977e-4 0.7078746 0.7063382 -2.73396e-6 0.7078132 0.7063997 -1.62471e-5 0.7078152 0.7063977 0 0.7558396 0.654757 -1.35925e-4 0.7627097 0.646741 2.65312e-4 0.8794641 0.4759652 -7.00277e-5 0.8857823 0.464101 7.77852e-5 0.9803047 0.1974914 -4.23873e-4 0.9837987 0.1792765 4.08605e-4 0.9941815 -0.1077184 0 0.9923709 -0.1232889 1.07368e-5 0.965229 -0.2614061 -6.73199e-4 0.965372 -0.2608764 -1.47753e-5 0.9652277 -0.2614105 2.98533e-6 0.9652275 -0.2614116 -9.31317e-6 0.9652301 -0.2614017 0 0.9652327 -0.2613922 0 0.9652334 -0.2613899 9.26939e-6 0.9652289 -0.2614061 -7.65439e-6 0.9652335 -0.2613896 -9.26939e-6 0.9652289 -0.2614061 5.98e-6 0.9652339 -0.2613881 5.41638e-4 0.965365 -0.2609027 -3.658e-6 0.9652267 -0.2614147 7.45055e-6 0.9652299 -0.2614026 -2.98533e-6 0.9652275 -0.2614116 1.72378e-5 0.9652279 -0.26141 0 0.9971625 -0.07527977 0 0.9971638 -0.0752632 0 0.9935327 0.113546 -3.00753e-6 0.9935334 0.1135402 -3.55759e-7 0.9935323 0.1135497 -5.23871e-7 0.9935339 0.1135362 0 0.9935325 0.1135485 3.13823e-7 0.9935328 0.1135452 1.92784e-6 0.9935315 0.1135571 -3.11583e-7 0.993533 0.1135438 0 0.9935331 0.1135433 -3.00881e-7 0.9935296 0.113574 2.69972e-7 0.9935329 0.1135451 0 0.9935322 0.1135505 1.11207e-6 0.9935358 0.1135199 -6.60713e-7 0.993532 0.1135528 -5.26439e-7 0.993533 0.1135444 0 0.9935354 0.1135236 1.07553e-5 0.9935316 0.1135563 -5.35119e-6 0.9935306 0.113565 0 0.9935328 0.1135452 0 0.993537 0.1135092 -1.41029e-6 0.9935331 0.1135438 -9.42888e-7 0.9935329 0.113545 0.5524675 0.8245871 -0.1218031 0.5532864 0.8250005 -0.1151013 0.5955327 0.7950261 -0.1152142 0.6267083 0.775736 -0.07396417 0.6212415 0.7751178 -0.1151157 0.6762275 0.7276414 -0.1151279 0.6762419 0.7276258 -0.1151418 0.7184374 0.6859899 -0.1151764 0.7322871 0.6805708 -0.02406334 0.7430347 0.659261 -0.115215 0.775119 0.6212383 -0.115125 0.7751085 0.6212481 -0.1151431 0.8216723 0.5582144 -0.1151143 0.8298071 0.5565103 -0.04142904 0.8478164 0.5174351 -0.1160526 0.1371134 0.9881511 0.06897342 0.2240136 0.9738447 0.03800666 0.19774 0.9799067 0.02611142 0.1964518 0.9801321 0.02734678 0.221794 0.9748288 0.02272492 0.2328862 0.972155 0.02605241 0.2357297 0.9714813 0.02560412 0.2424012 0.9697804 0.02771061 0.3029401 0.9529664 0.009074151 0.08207052 0.9935193 0.07863801 0.08533072 0.9934384 0.07615154 0.0874021 0.9928298 0.08154702 0.08740627 0.9928299 0.08154177 0.08622902 0.9932041 0.07816898 0.04586702 0.9940588 0.09870827 -0.3490892 0.9171816 0.1921319 -0.3658248 0.9067747 0.2095995 -0.1227012 0.8212678 0.5571928 -0.1309627 0.8140924 0.5657759 -0.4854963 0.8496689 -0.2058067 -0.4959021 0.8507526 -0.1740726 -0.4624398 0.885348 -0.04804658 -0.560786 0.8257265 0.06078624 -0.4892749 0.8558616 0.1676641 -0.4792546 0.8382997 0.2599399 -0.4714519 0.834656 0.2847501 -0.4760635 0.7568301 0.4478524 -0.5121196 0.7180652 0.4712918 -0.3914953 0.6848384 0.6145957 -0.3751079 0.6561474 0.6548012 -0.4939566 0.8694414 0.008859395 -0.3390473 0.7868769 0.5156277 -0.328792 0.7464184 0.5785806 -0.3825978 0.8999222 0.2091868 -0.1787851 0.7910514 0.5850417 -0.1909445 0.8249115 0.5320352 -0.4039566 0.8949177 0.1895827 -0.4588691 0.8636584 0.2086466 -0.4583247 0.8671782 0.1947839 -0.4829788 0.8451899 -0.228879 -0.00474298 0.9569988 0.2900532 -0.3867059 0.9102629 0.1479194 -0.3778603 0.9097974 0.1717279 -0.247996 0.9368035 0.2467738 -0.08451455 0.9751125 0.2049709 -0.1277731 0.9594174 0.2513815 -0.4134804 0.8718847 0.262395 -0.3608088 0.8794108 0.3105702 -0.2502458 0.9301868 0.2685698 -0.1238504 0.9371322 0.326258 -0.09352916 0.9523788 0.290219 -0.004844546 0.9569939 0.2900679 -0.004651725 0.9572983 0.2890647 -0.1519669 0.9339766 0.3234098 -0.3601485 0.9326639 0.0207628 -0.3650518 0.9286803 0.0654999 -0.09775674 0.9585237 0.2677239 -0.007411181 0.9597161 0.2808741 -0.002369523 0.963461 0.2678382 -0.007358908 0.9640958 0.2654526 -0.1398794 0.9657414 0.2185801 -0.01981335 0.9965597 0.08047562 -0.2374438 0.9529673 0.1883451 -0.2260502 0.9607043 0.1610858 -0.4392994 0.8725059 0.2138919 -0.3577288 0.9269788 0.1128731 0.01237785 0.974124 0.2256756 -0.3323644 0.9411315 0.06168794 -0.4101819 0.9081208 0.08406788 -0.3664221 0.9279432 0.06823742 -0.1947196 0.9769667 0.08729416 -0.3109359 0.946906 0.08177947 -0.3528798 0.9244741 0.1443036 -0.1220421 0.9755482 0.1827882 -0.1120873 0.9771202 0.1807562 -0.1055979 0.983968 0.1437228 -0.06370568 0.9890234 0.1333204 -0.3273013 0.9255695 0.1902503 -0.1147418 0.8221596 0.5575734 -0.3300447 0.9158448 0.2286894 -0.2586191 0.9455901 0.1974223 -0.2511268 0.932969 0.2578839 -0.1512563 0.9615892 0.2290583 -0.1542079 0.9507288 0.2689509 -0.04805105 0.9662912 0.2529281 -0.0545727 0.9589123 0.2784047 -0.1146315 0.8145273 0.568687 -0.08975905 0.8251601 0.5577222 -0.08610785 0.8135701 0.5750558 -0.05154943 0.8234402 0.5650566 -0.05210769 0.8153167 0.5766658 -0.01581734 0.8206734 0.5711786 -0.01789706 0.8153959 0.5786272 -0.1392865 0.7655023 0.6281765 -0.2630004 0.6920449 0.6722387 -0.3297656 0.6682394 0.6668664 -0.341368 0.6704235 0.658787 -0.09711945 0.6287523 0.771517 -0.1919414 0.7005198 0.6873358 -0.001792967 0.7078084 0.7064022 -0.001792967 0.7078085 0.7064022 -0.001792967 0.7078084 0.7064022 -0.09746921 0.7063673 0.7011027 -0.07207423 0.6483584 0.7579161 -0.3289274 0.7050467 0.6282643 -0.3294373 0.7040065 0.6291629 -0.07424819 0.8042634 0.5896165 -0.3477863 0.9289216 -0.1270809 -0.5359128 0.8387044 0.096812 -0.3290753 0.8209778 0.4665889 -0.4111082 0.7333559 0.5414603 -0.3650853 0.8858138 0.2864381 -0.3875309 0.8605044 0.3306844 -0.412959 0.8957248 0.1647481 -0.3623214 0.9320459 0.00369054 -0.4620994 0.8855235 -0.0480861 -0.0631352 0.9898301 -0.1274772 -0.1171465 0.7631956 0.63546 -0.06551975 0.8875076 0.4561111 -0.1172334 0.9277455 0.3543227 -0.08191025 0.9822226 0.1689068 -0.1074983 0.9864875 0.123639 -0.1003763 0.9914547 -0.08332043 -0.2057721 0.9706919 -0.1241587 -0.06339395 0.9632124 -0.2611572 -0.09248447 0.8969504 -0.4323503 -0.2072947 0.943348 -0.259082 -0.3495219 0.9041883 -0.245516 -0.3876075 0.7997232 -0.4584795 -0.4682008 0.8587419 -0.2082079 -0.1219913 0.9449512 0.3036203 -0.004741489 0.9568411 0.2905733 -0.3598226 0.8773224 0.3175423 -0.1171378 0.9418471 0.3149647 -0.1271131 0.9443067 0.3035245 -0.2431434 0.9181767 0.3127825 -0.3601855 0.8774569 0.3167584 -0.3603028 0.8771365 0.3175112 -0.4774463 0.7407271 0.4726188 -0.5534279 0.6858196 0.4726192 -0.7407296 0.477443 0.4726181 -0.7407262 0.4774466 0.4726198 -0.6858241 0.5534254 0.4726157 -0.6858196 0.5534309 0.4726158 -0.6231531 0.6231516 0.4726125 -0.6634249 0.6290382 0.4051896 -0.704796 0.7048019 0.08072894 -0.8389668 0.5407665 0.06088101 -0.7048017 0.7047958 0.08073121 -0.7756804 0.6259418 0.0807271 -0.7756823 0.6259389 0.08073079 -0.8345213 0.5450261 0.08075243 -0.8116981 0.5232203 0.2595892 -0.4774448 0.7407302 0.4726153 -0.5231856 0.8117076 0.2596303 -0.5450252 0.834522 0.08075058 -0.5407668 0.8389666 0.06088036 -0.5335389 0.8277171 -0.1738407 -0.5335107 0.8277338 -0.1738486 -0.618444 0.7663552 -0.1738589 -0.6259404 0.7756811 0.08073157 -0.6259412 0.7756807 0.08072841 -0.5534301 0.6858215 0.4726141 -0.6062142 0.6393526 0.4730039 -0.8277177 0.5335369 -0.1738446 -0.8277338 0.5335106 -0.1738481 -0.7663605 0.6184403 -0.1738487 -0.7663744 0.618427 -0.173835 -0.7145826 0.6775606 -0.1740216 -0.7067848 0.7067807 -0.03027194 -0.6775349 0.7146075 -0.1740191 -0.6184304 0.7663751 -0.1738196 -0.6355387 0.4230669 0.6458367 -0.4102509 0.6410555 0.6486464 -0.4102184 0.6398776 0.6498289 -0.4097163 0.6356566 0.6542732 -0.635654 0.4097185 0.6542742 -0.6392734 0.4101218 0.6504843 -0.6315294 0.4094803 0.6584045 -0.5907716 0.4767258 0.6509389 -0.5935254 0.4756997 0.6491822 -0.5460672 0.5177607 0.6585853 -0.5537697 0.5146614 0.6545708 -0.5200955 0.5485317 0.654686 -0.5128643 0.5518342 0.6576087 -0.4774416 0.5916538 0.6496117 -0.4745928 0.5921489 0.6512461 -0.4173715 0.6270268 0.6577526 -0.8323731 0.5541125 0.01070088 -0.8323732 0.5541124 0.01070094 -0.5438958 0.8155959 0.1974359 -0.8167557 0.5421586 0.1974188 -0.5539439 0.8324825 0.01092082 -0.5443558 0.819902 0.1773067 -0.6154856 0.7679189 0.1774207 -0.615476 0.7679302 0.1774051 -0.6699695 0.7208782 0.1774134 -0.6699725 0.7208776 0.1774044 -0.7208709 0.6699768 0.1774154 -0.7208766 0.6699736 0.1774047 -0.7679421 0.6154615 0.1774045 -0.7679237 0.6154817 0.1774136 -0.8187437 0.5460963 0.177307 -0.7101314 0.4730444 0.5214809 -0.7167711 0.4758714 0.5096917 -0.6712077 0.5379742 0.5099647 -0.6712117 0.5379663 0.509968 -0.6300736 0.5856063 0.5099732 -0.630096 0.5855904 0.5099636 -0.5855879 0.6301039 0.5099568 -0.5856083 0.6300775 0.509966 -0.5379518 0.6712213 0.5099705 -0.5379859 0.671202 0.5099598 -0.4769663 0.7160297 0.5097105 -0.4718698 0.7109093 0.5214853 -0.8827939 0.4697583 -0.001526474 -0.8688607 0.4950504 0.002523481 -0.8685235 0.495634 0.003748118 -0.8325565 0.5538474 -0.01014435 -0.8369452 0.5434435 -0.06474506 -0.7786815 0.6240979 0.06447452 -0.7920992 0.609538 -0.03228336 -0.7322173 0.6804947 0.02801513 -0.7369651 0.6759309 0 -0.680771 0.7324963 0 -0.6757293 0.7367672 0.02375108 -0.6252792 0.7801582 -0.01947146 -0.6093909 0.7919143 0.03891658 -0.5531766 0.8315385 -0.05039125 -0.5445718 0.8386772 -0.007891535 -0.4948248 0.8689839 0.003930389 -0.4956293 0.8685303 0.002619445 -0.4697693 0.8827879 -0.001527607 -0.5724992 0.810101 0.1264163 -0.5141777 0.8552572 0.06447023 -0.4955394 0.8683767 0.01904344 -0.4883146 0.8342095 0.2562097 -0.5191277 0.8204905 0.2393776 -0.5287624 0.8143389 0.2392963 -0.5287635 0.8143377 0.2392979 -0.5921409 0.7695024 0.2392393 -0.5921376 0.769505 0.2392386 -0.6563006 0.7155666 0.2392368 -0.6563007 0.7155665 0.2392368 -0.7155676 0.6562989 0.2392381 -0.7155659 0.6563007 0.2392383 -0.7695044 0.5921387 0.2392382 -0.7695028 0.5921402 0.2392395 -0.8143385 0.5287622 0.2392979 -0.8143365 0.528766 0.239296 -0.8206714 0.5188423 0.2393766 -0.8342592 0.4883347 0.2560097 -0.8552527 0.5141848 0.06447434 -0.8683731 0.4955456 0.01904571 -0.4521284 0.8882998 0.0806455 -0.5428074 0.8359637 0.08077716 -0.5428076 0.8359637 0.08077579 -0.6078585 0.7899283 0.08075594 -0.6078551 0.7899307 0.08075702 -0.6737194 0.7345615 0.08075731 -0.673718 0.7345628 0.08075749 -0.7345608 0.67372 0.08075892 -0.7345625 0.6737183 0.08075654 -0.7899294 0.6078567 0.08075743 -0.7899301 0.6078565 0.08075356 -0.8359628 0.5428089 0.08077663 -0.8359658 0.5428044 0.08077615 -0.8441587 0.5299675 0.08081233 -0.8629605 0.4828882 0.1487224 -0.7794314 0.5429204 0.312609 -0.4792929 0.8188128 0.3159493 -0.5057443 0.7788739 0.3709155 -0.4379904 0.5691812 0.6958428 -0.8188014 0.4793059 0.3159596 -0.778885 0.5057325 0.3709084 -0.5691781 0.4379819 0.6958508 -0.7809106 0.5446338 0.3058642 -0.6980732 0.6402477 0.3205884 -0.6355777 0.6355879 0.4382569 -0.6402511 0.6980685 0.3205916 -0.5441896 0.7812505 0.3057867 -0.5438338 0.7788153 0.312557 -0.08369761 0.9779717 -0.1912227 -0.02921217 0.9967385 -0.07522791 -0.0232408 0.9962537 -0.08329772 -0.06833493 0.9931309 -0.09498083 -0.07207059 0.9931399 -0.09208148 -0.1048172 0.9883036 -0.1107682 -0.1213686 0.9871346 -0.104092 -0.140931 0.9824223 -0.1224129 -0.2873252 0.9526032 -0.09995698 -0.1122922 0.9731497 -0.2009237 -0.1152541 0.9733317 -0.198348 -0.2736472 0.9584052 -0.08109754 -0.3381692 0.9389223 -0.0637691 -0.3298835 0.9412817 -0.0718739 -0.3187382 0.9463914 -0.05243617 -0.1081028 0.9751002 -0.1936324 -0.09310638 0.9745272 -0.2040299 -0.09386235 0.9609665 -0.2602562 -0.04431968 0.9657672 -0.2555966 -0.1328803 0.9570841 -0.2575518 -0.2318068 0.9388197 -0.2547217 -0.4022462 0.8841888 -0.2375043 -0.3482642 0.9099569 -0.2251458 -0.373447 0.8964621 -0.2385228 -0.3869798 0.8903706 -0.2397646 -0.4120845 0.8805624 -0.2340863 -0.3988823 0.8851217 -0.2396928 -0.4170561 0.8803792 -0.2258245 -0.4647563 0.8789127 -0.1073039 -0.4242613 0.8827003 -0.2020957 -0.3912604 0.9025546 -0.1797516 -0.3570693 0.912823 -0.1981307 -0.3363851 0.9245491 -0.1790371 -0.2662118 0.9401438 -0.2127463 -0.2507133 0.9488596 -0.1918554 -0.1948711 0.9588547 -0.2064529 -0.1823371 0.9654114 -0.1863704 -0.1205078 0.9706824 -0.2079752 -0.4666258 0.882434 -0.05975538 -0.4667241 0.8823788 -0.05980348 -0.4534816 0.8885948 -0.0689482 -0.4425906 0.8947898 -0.0588634 -0.4150859 0.9065917 -0.07612586 -0.406476 0.911381 -0.06451416 -0.3831412 0.9208029 -0.07297182 -0.3756855 0.9247367 -0.0610125 -0.3441409 0.9359396 -0.07472789 -0.8182757 0.5274283 -0.2285701 -0.5419086 0.8085035 -0.2294719 -0.5419086 0.8085035 -0.2294719 -0.5419086 0.8085035 -0.2294719 -0.5429612 0.8093995 -0.2237535 -0.5431081 0.8093331 -0.2236374 -0.5428586 0.8093745 -0.224093 -0.8083826 0.5421093 -0.2294234 -0.8093745 0.5428586 -0.2240927 -0.8207088 0.5249383 -0.2255596 -0.80933 0.5431305 -0.2235941 -0.8134942 0.5340688 -0.2302125 -0.7598797 0.6090295 -0.2273014 -0.7579755 0.6116543 -0.2266107 -0.7128525 0.6625086 -0.2300515 -0.7064175 0.6697945 -0.2288005 -0.6627215 0.7130793 -0.2287316 -0.6695249 0.7061348 -0.2304564 -0.6091578 0.7600399 -0.2264202 -0.6115728 0.7578756 -0.2271637 -0.5288885 0.8168365 -0.2303368 -0.5274284 0.8182755 -0.2285709 -0.5528478 0.8243215 -0.1218747 -0.7322809 0.6805775 -0.02406358 -0.7430323 0.659263 -0.1152188 -0.7751097 0.621249 -0.1151298 -0.7751177 0.6212373 -0.1151382 -0.8249893 0.5533052 -0.1150919 -0.826789 0.5616603 -0.03094798 -0.847818 0.5174332 -0.116051 -0.5528995 0.8252613 -0.1150918 -0.5955327 0.7950261 -0.1152142 -0.6234771 0.7779071 -0.07833814 -0.6242507 0.7726941 -0.1151309 -0.6762292 0.7276393 -0.1151308 -0.6762402 0.7276279 -0.115139 -0.7184374 0.6859899 -0.1151764 0.1667311 0.9859977 0.003053963 -0.2311571 0.9725221 0.02769988 -0.1374857 0.9880357 0.06988006 -0.2600389 0.9651893 0.02809602 -0.288877 0.9573622 -0.002772092 -0.2247216 0.9736459 0.0389108 -0.2083789 0.9779498 0.0138688 -0.1606507 0.9865108 0.03143197 -0.1774284 0.9840166 0.01518356 -0.07743245 0.9950871 0.06169265 -0.1128765 0.9929911 0.03503638 -0.1716671 0.9851393 0.005589127 -0.07361674 0.9953122 0.06272286 -0.06660187 0.9961147 0.05761742 -0.06657409 0.996119 0.0575751 -0.04871898 0.9968839 0.06204015 -0.02901083 0.9978981 0.05794858 -0.04193764 0.9974038 0.05853968 -0.04000365 0.9976271 0.05603682 -0.04829668 0.9969052 0.06202834 -0.04996407 0.9966278 0.06509083 -0.01571261 0.9981755 0.05830067 -0.02071976 0.9981831 0.05657887 -0.02998894 0.9977437 0.06006914 0.02509617 0.9978811 0.06002968 0.0163691 0.9983066 0.05582112 0.008174061 0.9981864 0.05964231 0.008633315 0.9981581 0.06005001 -0.005027413 0.998182 0.06006377 -0.008645832 0.9983361 0.05701106 -0.01302868 0.9982905 0.05697637 0.03182643 0.9970209 0.07026153 0.03094023 0.9982053 0.0512737 0.04572409 0.9970639 0.06142425 0.04182684 0.9975596 0.05590432 0.04955106 0.9968558 0.06183242 0.04894942 0.9969367 0.0610032 0.06333994 0.9963104 0.05791246 0.1651583 0.9859883 0.02344894 0.176522 0.9841905 0.01446402 0.1977745 0.9800954 0.017277 0.0729447 0.9949653 0.06872481 0.08055645 0.9956521 0.04677122 0.08050876 0.9957009 0.04580569 0.07643711 0.9952467 0.06034445 0.08129715 0.9943734 0.06791448 0.08268922 0.9943661 0.06632292 0.08211666 0.9940446 0.07164108 -0.2148581 0.976292 0.02626889 -0.2092403 0.9773342 0.03219509 -0.0870462 0.9929538 0.08040934 -0.08565026 0.9934037 0.07624518 -0.04589259 0.9940317 0.09896951 -0.09261673 0.9925283 0.07943361 -0.08577209 0.9933046 0.07739031 -0.08318763 0.9939663 0.07149124 -0.08691787 0.9937031 0.07070714 -0.08057337 0.9944979 0.06694722 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.45806e-7 0 -1 0.09194439 0.9957638 -8.09322e-4 0.09194439 0.9957638 -8.09029e-4 0.09194439 0.9957639 -8.09438e-4 0.09279084 0.9956839 -0.00187999 0.09279119 0.9956838 -0.001878738 0.09279096 0.9956838 -0.001879692 0 0 1 -1.4909e-4 0 1 5.7003e-5 0 1 -0.09459853 0 -0.9955155 -0.09459853 0 -0.9955156 -0.09459853 0 -0.9955155 -0.09476804 0 -0.9954994 -0.0947681 0 -0.9954994 -0.0947681 0 -0.9954994 0.09451347 0 -0.9955236 0.09451341 0 -0.9955237 0.09451359 0 -0.9955236 0.0942443 0 -0.9955492 0.09424424 0 -0.9955492 0.09424424 0 -0.9955492 0.9708558 0 0.2396646 0.9708557 0 0.239665 0.7478474 0 0.6638706 0.7478464 0 0.6638719 0.3590212 0 0.9333295 0.3590208 0 0.9333296 0.06422311 0 0.9979356 0.06422024 0 0.9979358 -0.2950124 0.9554935 -1.45554e-4 -0.2815759 0.9594989 -0.00877726 -0.2790899 0.9601961 -0.01150566 -0.2799905 0.9599529 -0.00978595 -0.2814677 0.959563 -0.003854811 -0.3135302 0.9488508 -0.03716427 -0.3330495 0.9429093 2.55448e-4 -0.3383725 0.9409586 -0.01005858 -0.3369349 0.9415195 -0.003999292 -0.2814648 0.9595715 0 -0.3093076 0.950883 -0.01225876 -0.3369345 0.9415281 0 -0.2711956 0.9625099 0.005255281 -0.268244 0.9633505 9.85355e-4 -0.3443977 0.938812 0.004727959 -0.3092309 0.950643 0.0255751 -0.3149041 0.9483741 0.03770983 -0.4015144 0.9032151 0.1516208 -0.3112953 0.9501463 0.01781189 -0.276039 0.9609259 -0.02058839 -0.3043982 0.9517663 0.03850507 1 0 0 1 5.74241e-7 0 0.2419487 0 -0.9702891 0.241931 0 -0.9702935 0.66601 0 -0.7459428 0.6660089 0 -0.7459438 0.9309084 0 -0.365253 0.9309057 0 -0.3652597 0.9974076 0 -0.07195985 0.9974077 0 -0.07195866 -0.9714441 0 -0.2372684 -0.9714435 0 -0.2372713 -0.7485108 0 -0.6631227 -0.7485062 0 -0.6631278 -0.354217 0 -0.9351633 -0.3542292 0 -0.9351587 -0.06094449 0 -0.9981412 -0.06086736 0 -0.9981459 -1 0 0 -0.2419472 0 0.9702894 -0.2419468 0 0.9702897 -0.6660061 0 0.7459463 -0.6660099 0 0.745943 -0.9309073 0 0.3652559 -0.9309064 0 0.365258 -0.9974085 0 0.07194769 -0.9974084 0 0.07194894 0.9714429 0 0.2372736 0.9714431 0 0.2372727 0.7485088 0 0.6631249 0.7485104 0 0.6631231 0.3542256 0 0.93516 0.3542258 0 0.9351599 0.06093519 0 0.9981418 0.06089323 0 0.9981443 -0.1546529 0.9879689 0 -0.154653 0.9879689 0 -0.1924846 0.9812884 -0.004796981 -0.195241 0.9807547 -0.00110501 -0.1207786 0.9926689 -0.004582107 -0.1546155 0.987727 -0.02212536 -0.1486001 0.9883791 -0.03201448 -0.03230041 0.9881844 -0.1498274 -0.1521927 0.9882346 -0.01515799 -0.1846246 0.9826917 0.01519834 -0.1576198 0.9868552 -0.03567814 -0.1164157 0.9931896 0.004678606 -0.113659 0.9935193 0.001070618 -0.1880105 0.9821557 0.004725635 -0.1546148 0.9877224 0.02233439 -0.1602736 0.9865621 0.0317434 -0.2687625 0.95204 0.1462418 -0.1565884 0.9875513 0.01491701 -0.1242238 0.9921417 -0.01494681 -0.1508948 0.9879324 0.03493398 0.2419388 0 -0.9702916 0.241954 0 -0.9702877 0.6660123 0 -0.7459408 0.6660101 0 -0.7459428 0.9309067 0 -0.3652572 0.9309089 0 -0.3652515 0.9974085 0 -0.07194823 0.9974081 0 -0.07195192 -0.9714435 0 -0.2372711 -0.9714447 0 -0.2372663 -0.7485057 0 -0.6631284 -0.7485072 0 -0.6631267 -0.3542247 0 -0.9351604 -0.3542414 0 -0.935154 -0.06090712 0 -0.9981434 -0.06091052 0 -0.9981433 -1 -2.34939e-7 0 -0.2419475 0 0.9702894 -0.2419421 0 0.9702907 -0.6660038 0 0.7459483 -0.6660101 0 0.7459428 -0.930907 0 0.3652567 -0.9309075 0 0.3652551 -0.9974085 0 0.07194775 -0.9974083 0 0.07194846 0.9714438 0 0.2372695 0.9714441 0 0.2372686 0.7485072 0 0.6631268 0.7485096 0 0.663124 0.3542234 0 0.9351609 0.3542302 0 0.9351583 0.06092578 0 0.9981423 0.06088513 0 0.9981448 0 1 0 0.0256834 0.9996252 0.009477078 -0.0336377 0.9994239 0.004528343 0 0.9997646 0.02170252 -0.005837261 0.9994984 0.03112584 0.0225293 0.9997434 0.002393722 -0.001209437 0.9995294 0.03065365 0.006305158 0.999723 0.02267807 -0.02568358 0.9996253 -0.009477198 0.03363752 0.9994239 -0.004528284 0 0.9997645 -0.02170264 0.005837023 0.9994984 -0.03112578 -0.02252882 0.9997434 -0.002393782 0.001208782 0.9995294 -0.03065294 -0.006305098 0.999723 -0.02267795 1 2.92028e-7 0 0.2419487 0 -0.9702891 0.2419348 0 -0.9702925 0.6660093 0 -0.7459434 0.6660099 0 -0.745943 0.9309089 0 -0.3652517 0.930907 0 -0.3652562 0.9974083 0 -0.07194858 0.9974084 0 -0.07194894 -0.9714434 0 -0.2372715 -0.9714426 0 -0.237275 -0.7485105 0 -0.6631229 -0.748508 0 -0.6631258 -0.3542277 0 -0.9351593 -0.3542203 0 -0.9351621 -0.06093752 0 -0.9981416 -0.06091833 0 -0.9981428 -0.2419494 0 0.9702889 -0.2419487 0 0.9702891 -0.6660021 0 0.7459499 -0.6660089 0 0.7459438 -0.9309076 0 0.3652548 -0.9309057 0 0.3652597 -0.9974077 0 0.0719583 -0.9974076 0 0.07195979 0.9714441 0 0.2372686 0.9714435 0 0.2372713 0.7485095 0 0.6631242 0.7485062 0 0.6631278 0.3542292 0 0.9351587 0.3542236 0 0.9351608 0.06094056 0 0.9981415 0.06089246 0 0.9981443 0.154653 0.9879689 0 0.1546529 0.9879689 0 0.1924881 0.9812876 0.004796981 0.1952355 0.9807558 0.00110501 0.1207796 0.9926688 0.004582107 0.1546155 0.987727 0.02212536 0.1486001 0.9883791 0.03201448 0.032296 0.9881846 0.1498275 0.1521927 0.9882346 0.01515799 0.1846246 0.9826917 -0.01519834 0.1576194 0.9868553 0.03567874 0.1164153 0.9931896 -0.004678606 0.1136586 0.9935194 -0.001070618 0.1880105 0.9821557 -0.004725635 0.1546142 0.9877225 -0.02233439 0.1602746 0.986562 -0.0317434 0.2687625 0.95204 -0.1462418 0.156584 0.9875521 -0.01491701 0.1242251 0.9921416 0.01494681 0.1508865 0.9879336 -0.03493338 -0.2419459 0 0.9702898 -0.2419435 0 0.9702903 -0.6660034 0 0.7459488 -0.6660105 0 0.7459424 -0.9309069 0 0.3652567 -0.9309068 0 0.3652569 -0.9974091 0 0.07193958 -0.9974089 0 0.07194209 0.9714443 0 0.237268 0.9714438 0 0.23727 0.7485084 0 0.6631253 0.7485113 0 0.6631221 0.5037653 0 0.8638406 0.3606597 0.02463936 0.9323721 0.288878 0 0.9573659 0.06094819 0 0.998141 0.06088674 0 0.9981448 0.9171848 0.3490844 0.1921253 0.9067778 0.3658223 0.2095906 0.8212448 0.1226581 0.5572361 0.8140892 0.1309927 0.5657737 0.8496395 0.4855466 -0.2058091 0.8507695 0.4958709 -0.1740786 0.8853521 0.4624314 -0.04804986 0.8257209 0.5607943 0.0607866 0.8558644 0.4892714 0.1676599 0.8383134 0.4792325 0.2599363 0.8346529 0.471455 0.2847538 0.756825 0.4760744 0.4478495 0.7180638 0.5121115 0.4713028 0.6848512 0.3914974 0.6145802 0.6561471 0.3750939 0.6548096 0.8693509 0.4941178 0.008769392 0.7868868 0.3390368 0.5156194 0.7464136 0.3287952 0.578585 0.8999211 0.3825991 0.2091886 0.7910619 0.178771 0.5850316 0.8249002 0.1909541 0.5320491 0.8949123 0.4039701 0.1895792 0.8636605 0.4588659 0.2086445 0.8671737 0.4583342 0.1947813 0.8451889 0.4829813 -0.2288771 0.9569972 0.004841864 0.2900568 0.9102581 0.3867183 0.1479159 0.9098007 0.3778514 0.1717302 0.9368067 0.2479855 0.2467725 0.9751146 0.08451664 0.2049602 0.959417 0.1277651 0.2513864 0.8718859 0.4134786 0.2623938 0.8794096 0.3608133 0.3105682 0.9301882 0.2502421 0.2685682 0.9371327 0.1238543 0.3262552 0.9523767 0.09353035 0.2902252 0.956993 0.004747509 0.2900724 0.9573054 0.004554867 0.2890427 0.9339739 0.1519728 0.3234145 0.9326695 0.3601337 0.0207681 0.9286751 0.3650644 0.06550341 0.9585237 0.09775376 0.267725 0.9597218 0.007410943 0.2808548 0.9634593 0.002445697 0.2678441 0.9640959 0.007283627 0.2654545 0.965741 0.1398718 0.2185873 0.9965589 0.01982372 0.08048242 0.952967 0.2374446 0.1883458 0.9607063 0.2260438 0.1610833 0.8724976 0.4393136 0.2138962 0.9269798 0.357728 0.1128681 0.974151 -0.0120508 0.2255765 0.974151 -0.0120508 0.2255765 0.974151 -0.0120508 0.2255765 0.9411324 0.3323622 0.06168806 0.9081269 0.4101668 0.08407604 0.9279441 0.3664203 0.06823486 0.9769681 0.194714 0.08729237 0.9469045 0.3109409 0.08177846 0.92447 0.35289 0.1443048 0.975548 0.1220433 0.1827888 0.9771201 0.1120871 0.1807569 0.9839671 0.1056042 0.1437237 0.9890236 0.06370753 0.1333181 0.9255639 0.3273103 0.190262 0.822163 0.1147418 0.5575683 0.9158545 0.3300263 0.228677 0.9455845 0.2586319 0.197433 0.9329782 0.251112 0.2578654 0.9615956 0.1512486 0.2290369 0.9507207 0.154221 0.2689723 0.9662871 0.04805725 0.2529426 0.9589077 0.05458134 0.2784187 0.814526 0.1146442 0.5686864 0.8251588 0.08974915 0.5577259 0.8135638 0.08610278 0.5750655 0.8234412 0.05155181 0.565055 0.8153389 0.05209976 0.5766351 0.8207049 0.01581794 0.5711335 0.8153865 0.01789182 0.5786404 0.7655134 0.1392881 0.6281623 0.6920401 0.2629902 0.6722475 0.6682377 0.3297725 0.6668648 0.6704238 0.3413689 0.6587864 0.6287462 0.09711807 0.7715221 0.7005183 0.1919391 0.6873379 0.7078089 0.001312196 0.7064029 0.7063886 0.09746879 0.7010813 0.6483468 0.07207661 0.7579258 0.7050604 0.3289119 0.628257 0.7040061 0.329433 0.6291657 0.8042658 0.07423681 0.5896146 0.9289265 0.3477727 -0.1270822 0.8387035 0.5359141 0.09681344 0.8209751 0.3290728 0.4665951 0.7333481 0.4111149 0.5414657 0.8858186 0.3651002 0.2864041 0.8605095 0.387519 0.3306852 0.8957259 0.4129573 0.1647467 0.9320423 0.362331 0.00369203 0.8855224 0.4621014 -0.04808604 0.9898294 0.06314355 -0.1274783 0.7631895 0.1171571 0.6354652 0.8875039 0.06552487 0.4561178 0.9277471 0.1172332 0.3543187 0.9822226 0.08191531 0.1689048 0.9864883 0.1075006 0.1236305 0.9914555 0.1003733 -0.08331406 0.9706904 0.2057706 -0.124172 0.9632149 0.06338608 -0.26115 0.8969498 0.09247541 -0.4323533 0.9433483 0.2072982 -0.259078 0.9041975 0.3494969 -0.2455177 0.7997144 0.3876329 -0.4584731 0.858757 0.4681719 -0.2082106 0.9449526 0.1219888 0.3036172 0.9568409 0.004822909 0.2905724 0.8773148 0.3598384 0.3175454 0.9418436 0.1171385 0.3149749 0.9443079 0.1271145 0.3035204 0.9181603 0.243282 0.3127229 0.9181603 0.243282 0.3127229 0.9181603 0.2432819 0.3127229 0.8774612 0.3601753 0.3167579 0.8771327 0.3603058 0.3175184 0.9779713 0.08371096 -0.1912191 0.996737 0.02921503 -0.07524645 0.9962548 0.02323752 -0.08328521 0.9931332 0.06832247 -0.09496706 0.9931401 0.072075 -0.09207564 0.9883041 0.1048105 -0.1107691 0.9871339 0.1213738 -0.1040921 0.9824235 0.140922 -0.1224135 0.9525988 0.2873362 -0.09996718 0.9389197 0.3381761 -0.06377112 0.9412809 0.3298855 -0.07187432 0.9460577 0.319507 -0.05376082 0.9368761 0.348268 -0.03118485 0.9617962 0.2648966 -0.06912237 0.9733324 0.1152528 -0.1983457 0.973153 0.1122773 -0.2009161 0.975104 0.1080899 -0.1936198 0.9745273 0.0930953 -0.2040339 0.9609665 0.09386235 -0.2602562 0.9657668 0.04432302 -0.2555975 0.9570843 0.1328711 -0.2575557 0.9388208 0.2318081 -0.2547163 0.8841905 0.4022447 -0.2375006 0.9099586 0.3482627 -0.2251413 0.8964623 0.3734449 -0.238525 0.890372 0.3869758 -0.2397654 0.8805587 0.4120921 -0.2340868 0.8851248 0.3988749 -0.2396933 0.8802873 0.417145 -0.2260185 0.8789119 0.4647595 -0.1072955 0.8826925 0.4242805 -0.202089 0.9025582 0.3912432 -0.179771 0.9128326 0.3570453 -0.1981301 0.9245611 0.3363524 -0.1790364 0.9401353 0.2662394 -0.2127496 0.9488679 0.2506948 -0.1918381 0.9588584 0.1948567 -0.2064494 0.9654101 0.1823433 -0.1863713 0.9706847 0.1204935 -0.2079731 0.8824257 0.4666428 -0.05974578 0.8824015 0.4666824 -0.05979388 0.8885827 0.4535079 -0.06893223 0.8947953 0.4425783 -0.05887323 0.9065992 0.4150682 -0.07613426 0.9113669 0.4065079 -0.06451171 0.9208037 0.3831394 -0.07297116 0.9247378 0.3756818 -0.06101959 0.935939 0.3441447 -0.07471877 0.9570315 0 0.2899839 0.9570252 0 0.2900046 0.9570373 0 0.289965 0.957032 0 0.2899826 0.957029 -4.12547e-7 0.2899926 0.9570403 -1.05815e-6 0.2899554 0.9570284 6.13965e-7 0.2899946 0.957032 4.12094e-7 0.2899822 0.9591585 0 0.282869 0.9890111 0 0.1478421 0.9889419 3.37977e-5 0.1483035 0.9751131 -4.3105e-5 0.2217084 0.9632125 2.19423e-4 0.2687409 0.9751009 0.001662909 0.2217559 0.9586691 -0.005913972 0.284462 0.9628168 -0.004392266 0.2701198 0.8155331 0 0.5787105 0.815523 0 0.5787248 0.9603418 0 0.2788255 0.9603441 0 0.2788174 0.7078359 1.48499e-5 0.706377 0.7078776 9.67839e-5 0.7063351 0.707814 6.83487e-7 0.7063989 0.7078146 5.41569e-6 0.7063984 0.7078146 -5.41569e-6 0.7063984 0.707814 -6.83487e-7 0.7063989 0.7078776 -9.67839e-5 0.7063351 0.7078387 -1.56314e-5 0.7063741 0.7077967 1.8442e-5 0.7064162 0.707825 0 0.7063879 0.7078323 0 0.7063806 0.7077967 -1.8442e-5 0.7064162 0.7558455 0 0.6547501 0.762717 1.35746e-4 0.6467324 0.8794667 -2.6517e-4 0.4759604 0.8857759 7.00534e-5 0.4641135 0.980305 -7.76438e-5 0.1974894 0.9837981 4.23854e-4 0.1792795 0.9941811 -4.08669e-4 -0.1077216 0.992371 0 -0.1232876 0.9652258 7.31609e-6 -0.2614175 0.9653762 -5.12958e-4 -0.2608614 0.9652333 -7.65451e-6 -0.2613904 0.9652303 -2.14734e-5 -0.2614013 0.9653686 6.82183e-4 -0.2608888 0.9652333 7.65451e-6 -0.2613904 0.9652298 -7.38657e-6 -0.261403 0.9652331 0 -0.2613908 0.9652333 0 -0.2613901 0.9652298 7.38657e-6 -0.261403 0.9652295 -1.4901e-5 -0.2614042 0.9652276 1.99022e-6 -0.2614112 0.9652276 -9.23453e-6 -0.261411 0.9652276 9.85017e-6 -0.2614111 0.9652276 -1.99022e-6 -0.2614112 0.9652298 1.86262e-5 -0.2614031 0.9971628 0 -0.07527577 0.9971626 0 -0.07527828 0.993533 -2.406e-5 0.1135449 0.9935328 -6.23168e-7 0.1135458 0.9935317 2.57046e-6 0.1135551 0.9935326 0 0.1135471 0.9935328 0 0.1135457 0.9935332 -8.38187e-7 0.1135427 0.9935327 7.95333e-7 0.1135464 0.993533 5.23037e-7 0.1135448 0.993532 -1.20355e-6 0.1135529 0.9935325 3.59963e-7 0.1135484 0.9935325 6.74654e-7 0.113548 0.9935328 -5.72071e-7 0.113546 0.993535 1.11206e-6 0.1135268 0.9935327 1.6518e-7 0.1135469 0.9935327 0 0.1135467 0.9935328 -3.14298e-6 0.1135452 0.9935314 -1.41023e-6 0.1135581 0.9935344 -7.3109e-7 0.1135322 0.9935335 0 0.1135401 0.9935296 -4.28098e-6 0.1135739 0.9935312 5.52998e-6 0.1135592 0.9935355 2.39001e-6 0.1135222 0.9738432 0.2240204 0.03800457 0.9940599 0.04585772 0.0987026 0.9798867 0.1977521 0.02676343 0.9805354 0.1943587 0.02784401 0.9710927 0.2379058 0.01949208 0.9718039 0.2344131 0.02545464 0.9667653 0.2537965 0.03085947 0.9564817 0.2917923 -3.22485e-4 0.9936006 0.08207744 0.0775966 0.9933396 0.08567267 0.07704997 0.9928302 0.08740067 0.08154499 0.9928297 0.08740472 0.08154505 0.9932031 0.08623695 0.0781719 0.9881525 0.1371048 0.06897044 0.8157596 -0.1334791 0.5627785 0.81955 -0.1200275 0.5602957 0.9067606 -0.3697567 0.2026455 0.9172851 -0.3448913 0.1990936 0.6848512 -0.3914974 0.6145802 0.7210782 -0.5304195 0.4457595 0.7341614 -0.4877722 0.4723192 0.8330194 -0.4681086 0.294878 0.8383557 -0.4791662 0.2599223 0.8474174 -0.4843244 0.2175171 0.8505208 -0.5013476 0.1589496 0.8297407 -0.5548258 0.06081736 0.8733907 -0.4869657 -0.007286369 0.8557849 -0.4922977 -0.1589818 0.8507695 -0.4958709 -0.1740786 0.8496395 -0.4855466 -0.2058091 0.6561478 -0.3750943 0.6548086 0.8647425 -0.46283 0.1949588 0.7733759 -0.3658473 0.517731 0.8693509 -0.4941178 0.008769392 0.8658787 -0.4552391 0.2073919 0.9003446 -0.3934673 0.1859115 0.8949189 -0.3916745 0.2138022 0.7593408 -0.3089363 0.5726779 0.8125358 -0.2159704 0.5414263 0.8031877 -0.1571862 0.5746147 0.845189 -0.4829809 -0.2288777 0.904453 -0.3917863 0.1687256 0.8395236 -0.4280583 0.3346138 0.8917861 -0.3666676 0.2650896 0.956996 -0.004741311 0.2900627 0.9573054 -0.004554867 0.2890427 0.9604584 -0.09073221 0.263225 0.9702579 -0.1148006 0.2131206 0.9141508 -0.3732947 0.1580491 0.9368067 -0.2479855 0.2467725 0.9301882 -0.2502421 0.2685682 0.9363454 -0.098266 0.3370477 0.9483938 -0.1290653 0.28964 0.9569942 -0.004846096 0.2900665 0.8724976 -0.4393136 0.2138962 0.926979 -0.3577299 0.1128687 0.9607058 -0.2260457 0.161083 0.9241675 -0.1352341 0.3572483 0.9560147 -0.1314318 0.2622247 0.9639124 -0.007682383 0.2661092 0.9237784 -0.3780253 0.06107658 0.9360961 -0.3499361 0.0356208 0.9529659 -0.2374483 0.188346 0.9894918 -0.08798444 0.114738 0.9673856 -0.0855211 0.238435 0.9636442 -0.00211364 0.2671809 0.9597218 -0.007410943 0.2808548 0.9870361 -0.1025491 0.1234644 0.9166995 -0.3596186 0.1741736 0.92447 -0.35289 0.1443048 0.946905 -0.3109395 0.0817787 0.9769684 -0.1947124 0.08729267 0.9832619 -0.05871772 0.1724769 0.9279441 -0.3664203 0.06823486 0.9392814 -0.3381927 0.05810642 0.975548 -0.1220433 0.1827888 0.9772174 -0.1114467 0.1806261 0.9742213 0.01256704 0.2252442 0.8192674 -0.1206651 0.560572 0.9169332 -0.3456134 0.199462 0.8173793 -0.1081332 0.5658608 0.822993 -0.09497743 0.5600553 0.8154421 -0.0798012 0.5733115 0.8222708 -0.05589526 0.5663449 0.8161288 -0.04715752 0.5759426 0.8202997 -0.01878905 0.5716253 0.8154357 -0.01468729 0.5786614 0.9248964 -0.3100981 0.2200135 0.9394316 -0.2749504 0.2046233 0.9394592 -0.2317124 0.2524397 0.9583796 -0.1648449 0.2330981 0.9536972 -0.1388236 0.2668142 0.9653814 -0.05734604 0.2544608 0.9593867 -0.0445435 0.2785555 0.6950998 -0.188675 0.6937132 0.7947034 -0.1038179 0.5980539 0.763498 -0.1363626 0.6312497 0.6924479 -0.2634515 0.6716468 0.6065158 -0.09122431 0.7898207 0.6723631 -0.3386905 0.6581921 0.6694053 -0.3250096 0.668031 0.7053132 -0.3247406 0.6301404 0.6972371 -0.3285496 0.6371151 0.6644058 -0.07238239 0.7438588 0.7066626 -0.0916692 0.7015874 0.9703279 -0.207338 -0.1243978 0.8649225 -0.3761607 0.3322836 0.8680319 -0.4693073 -0.1620841 0.9246803 -0.3200542 0.2062319 0.926861 -0.374971 -0.01804268 0.8745671 -0.4678431 -0.1274968 0.9124145 -0.3792678 0.153805 0.9078351 -0.4051668 0.1080523 0.8876324 -0.4064832 0.2165185 0.8699375 -0.3938185 0.2968431 0.7573673 -0.07390213 0.6487938 0.8151147 -0.3294685 0.4764856 0.7380324 -0.3982769 0.5446868 0.8020209 -0.1037262 0.5882205 0.9341887 -0.02239441 0.3560758 0.8786339 -0.1380742 0.4570972 0.9897027 -0.07021397 0.1247344 0.9760705 -0.1201494 0.1812474 0.992358 -0.09281277 -0.08131068 0.9916346 -0.06398552 -0.1121017 0.8579018 -0.4698259 -0.2080104 0.8021025 -0.388113 -0.4538725 0.9030711 -0.3528672 -0.2448416 0.9431761 -0.2085074 -0.2587342 0.8987328 -0.09254151 -0.4286204 0.9631435 -0.06436324 -0.2611745 0.9448788 -0.1224554 0.3036589 0.8771327 -0.3603058 0.3175184 0.9568392 -0.004830896 0.2905777 0.9417548 -0.1175995 0.3150688 0.9440961 -0.1270204 0.3042176 0.877461 -0.3601753 0.3167585 0.8773148 -0.3598384 0.3175454 0.4774463 -0.7407271 0.4726188 0.5534279 -0.6858196 0.4726192 0.7407296 -0.477443 0.4726181 0.7407262 -0.4774466 0.4726198 0.6858241 -0.5534254 0.4726157 0.6858196 -0.5534309 0.4726158 0.6231531 -0.6231516 0.4726125 0.6634249 -0.6290382 0.4051896 0.704796 -0.7048019 0.08072894 0.8389668 -0.5407665 0.06088101 0.7048017 -0.7047958 0.08073121 0.7756804 -0.6259418 0.0807271 0.7756823 -0.6259389 0.08073079 0.8345213 -0.5450261 0.08075243 0.8116981 -0.5232203 0.2595892 0.4774448 -0.7407302 0.4726153 0.5231856 -0.8117076 0.2596303 0.5450252 -0.834522 0.08075058 0.5407668 -0.8389666 0.06088036 0.5335389 -0.8277171 -0.1738407 0.5335107 -0.8277338 -0.1738486 0.618444 -0.7663552 -0.1738589 0.6259404 -0.7756811 0.08073157 0.6259412 -0.7756807 0.08072841 0.5534301 -0.6858215 0.4726141 0.6062142 -0.6393526 0.4730039 0.8277177 -0.5335369 -0.1738446 0.8277338 -0.5335106 -0.1738481 0.7663605 -0.6184403 -0.1738487 0.7663744 -0.618427 -0.173835 0.7145826 -0.6775606 -0.1740216 0.7067848 -0.7067807 -0.03027194 0.6775349 -0.7146075 -0.1740191 0.6184304 -0.7663751 -0.1738196 0.6355387 -0.4230669 0.6458367 0.635654 -0.4097185 0.6542742 0.4102509 -0.6410555 0.6486464 0.4102184 -0.6398776 0.6498289 0.4097163 -0.6356566 0.6542732 0.6392734 -0.4101218 0.6504843 0.6315294 -0.4094803 0.6584045 0.5907716 -0.4767258 0.6509389 0.5935254 -0.4756997 0.6491822 0.5460672 -0.5177607 0.6585853 0.5537697 -0.5146614 0.6545708 0.5200955 -0.5485317 0.654686 0.5128643 -0.5518342 0.6576087 0.4774416 -0.5916538 0.6496117 0.4745928 -0.5921489 0.6512461 0.4173715 -0.6270268 0.6577526 0.5438958 -0.8155959 0.1974359 0.8323731 -0.5541125 0.01070088 0.8323732 -0.5541124 0.01070094 0.8167557 -0.5421586 0.1974188 0.5539439 -0.8324825 0.01092082 0.5443558 -0.819902 0.1773067 0.6154856 -0.7679189 0.1774207 0.615476 -0.7679302 0.1774051 0.6699695 -0.7208782 0.1774134 0.6699725 -0.7208776 0.1774044 0.7208709 -0.6699768 0.1774154 0.7208766 -0.6699736 0.1774047 0.7679421 -0.6154615 0.1774045 0.7679237 -0.6154817 0.1774136 0.8187437 -0.5460963 0.177307 0.7101314 -0.4730444 0.5214809 0.7167711 -0.4758714 0.5096917 0.6712077 -0.5379742 0.5099647 0.6712117 -0.5379663 0.509968 0.6300736 -0.5856063 0.5099732 0.630096 -0.5855904 0.5099636 0.5855879 -0.6301039 0.5099568 0.5856083 -0.6300775 0.509966 0.5379518 -0.6712213 0.5099705 0.5379859 -0.671202 0.5099598 0.4769663 -0.7160297 0.5097105 0.4718698 -0.7109093 0.5214853 0.8827939 -0.4697583 -0.001526474 0.8688607 -0.4950504 0.002523481 0.8685235 -0.495634 0.003748118 0.8325565 -0.5538474 -0.01014435 0.8369452 -0.5434435 -0.06474506 0.7786815 -0.6240979 0.06447452 0.7920992 -0.609538 -0.03228336 0.7322173 -0.6804947 0.02801513 0.7369651 -0.6759309 0 0.680771 -0.7324963 0 0.6757293 -0.7367672 0.02375108 0.6252792 -0.7801582 -0.01947146 0.6093909 -0.7919143 0.03891658 0.5531766 -0.8315385 -0.05039125 0.5445718 -0.8386772 -0.007891535 0.4948248 -0.8689839 0.003930389 0.4956293 -0.8685303 0.002619445 0.4697693 -0.8827879 -0.001527607 0.5724992 -0.810101 0.1264163 0.5141777 -0.8552572 0.06447023 0.4955394 -0.8683767 0.01904344 0.4883146 -0.8342095 0.2562097 0.5191277 -0.8204905 0.2393776 0.5287624 -0.8143389 0.2392963 0.5287635 -0.8143377 0.2392979 0.5921409 -0.7695024 0.2392393 0.5921376 -0.769505 0.2392386 0.6563006 -0.7155666 0.2392368 0.6563007 -0.7155665 0.2392368 0.7155676 -0.6562989 0.2392381 0.7155659 -0.6563007 0.2392383 0.7695044 -0.5921387 0.2392382 0.7695028 -0.5921402 0.2392395 0.8143385 -0.5287622 0.2392979 0.8143365 -0.528766 0.239296 0.8206714 -0.5188423 0.2393766 0.8342592 -0.4883347 0.2560097 0.8552527 -0.5141848 0.06447434 0.8683731 -0.4955456 0.01904571 0.4521284 -0.8882998 0.0806455 0.5428074 -0.8359637 0.08077716 0.5428076 -0.8359637 0.08077579 0.6078585 -0.7899283 0.08075594 0.6078551 -0.7899307 0.08075702 0.6737194 -0.7345615 0.08075731 0.673718 -0.7345628 0.08075749 0.7345608 -0.67372 0.08075892 0.7345625 -0.6737183 0.08075654 0.7899294 -0.6078567 0.08075743 0.7899301 -0.6078565 0.08075356 0.8359628 -0.5428089 0.08077663 0.8359658 -0.5428044 0.08077615 0.8441587 -0.5299675 0.08081233 0.8629605 -0.4828882 0.1487224 0.7794314 -0.5429204 0.312609 0.8188014 -0.4793059 0.3159596 0.4792929 -0.8188128 0.3159493 0.5057443 -0.7788739 0.3709155 0.4379904 -0.5691812 0.6958428 0.6688983 -0.6689131 0.3242383 0.5441896 -0.7812505 0.3057867 0.5438338 -0.7788153 0.312557 0.5704098 -0.6219124 0.5365236 0.6980732 -0.6402477 0.3205884 0.7809106 -0.5446338 0.3058642 0.5691781 -0.4379819 0.6958508 0.778885 -0.5057325 0.3709084 0.977972 -0.08367788 -0.1912296 0.9968692 -0.02426236 -0.07525545 0.9960132 -0.02828961 -0.08460175 0.9929151 -0.07062351 -0.09556096 0.9933897 -0.07006669 -0.09092688 0.9868806 -0.1129267 -0.1153877 0.9884812 -0.1151205 -0.0982455 0.9730077 -0.1731313 -0.1525825 0.9690273 -0.2436463 -0.04028135 0.9617956 -0.2649011 -0.06911283 0.9368764 -0.3482682 -0.03117513 0.9383539 -0.3393381 -0.06589066 0.9418738 -0.3286548 -0.06971371 0.9460577 -0.319507 -0.05376082 0.9731481 -0.1156134 -0.1990389 0.9733442 -0.1118792 -0.2002102 0.9749393 -0.1084473 -0.1942487 0.9747152 -0.09259724 -0.2033624 0.9647214 -0.0323829 -0.2612738 0.9618583 -0.09386163 -0.2569411 0.957084 -0.1328737 -0.2575556 0.9388211 -0.2318067 -0.2547168 0.8851247 -0.3988753 -0.2396935 0.8803901 -0.4125696 -0.2338795 0.8896291 -0.3888178 -0.2395427 0.8965871 -0.3732191 -0.2384095 0.9099586 -0.3482627 -0.2251411 0.8841905 -0.4022447 -0.2375006 0.8845129 -0.4544161 -0.1055606 0.8839665 -0.4094721 -0.2256899 0.8839665 -0.4094721 -0.2256899 0.8839666 -0.4094721 -0.22569 0.8739153 -0.4810808 -0.06952267 0.8851962 -0.4617768 -0.05647796 0.8863361 -0.4573325 -0.0724945 0.8979738 -0.4367781 -0.05355608 0.9044461 -0.4187923 -0.08118176 0.9138664 -0.4018117 -0.05827403 0.9188162 -0.3867464 -0.07876592 0.9262468 -0.3726963 -0.05625212 0.9346974 -0.3465248 -0.07912862 0.8822582 -0.4249626 -0.2025522 0.9092 -0.37929 -0.1717395 0.9073548 -0.3661253 -0.2065421 0.9318249 -0.3225444 -0.1663353 0.9349302 -0.2748476 -0.22442 0.9542706 -0.2402773 -0.1778604 0.9543444 -0.2028442 -0.2192741 0.9680723 -0.1768847 -0.1776171 0.9683762 -0.1248605 -0.2160034 0.5419086 -0.8085035 -0.2294719 0.5419086 -0.8085035 -0.2294719 0.5419086 -0.8085035 -0.2294719 0.8182757 -0.5274283 -0.2285701 0.8083826 -0.5421093 -0.2294234 0.8093745 -0.5428586 -0.2240927 0.8207088 -0.5249383 -0.2255596 0.5429612 -0.8093995 -0.2237535 0.5431081 -0.8093331 -0.2236374 0.5428586 -0.8093745 -0.224093 0.80933 -0.5431305 -0.2235941 0.8134942 -0.5340688 -0.2302125 0.7598797 -0.6090295 -0.2273014 0.7579755 -0.6116543 -0.2266107 0.7128525 -0.6625086 -0.2300515 0.7064175 -0.6697945 -0.2288005 0.6627215 -0.7130793 -0.2287316 0.6695249 -0.7061348 -0.2304564 0.6091578 -0.7600399 -0.2264202 0.6115728 -0.7578756 -0.2271637 0.5288885 -0.8168365 -0.2303368 0.5274284 -0.8182755 -0.2285709 0.5528478 -0.8243215 -0.1218747 0.7322809 -0.6805775 -0.02406358 0.7430323 -0.659263 -0.1152188 0.7751097 -0.621249 -0.1151298 0.7751177 -0.6212373 -0.1151382 0.8249893 -0.5533052 -0.1150919 0.826789 -0.5616603 -0.03094798 0.847818 -0.5174332 -0.116051 0.5528995 -0.8252613 -0.1150918 0.5955327 -0.7950261 -0.1152142 0.6234771 -0.7779071 -0.07833814 0.6242507 -0.7726941 -0.1151309 0.6762292 -0.7276393 -0.1151308 0.6762402 -0.7276279 -0.115139 0.7184374 -0.6859899 -0.1151764 0.9858434 0.1675068 -0.007381618 0.9860413 0.166104 0.01149404 0.9876406 0.1543912 0.02700889 0.9849841 0.1715938 0.01902449 0.9801201 0.1977939 0.01555788 0.9969524 0.04993653 0.05993688 0.996463 0.05933648 0.05950462 0.9960354 0.06539618 0.06030654 0.996095 0.06494212 0.05981194 0.9953422 0.07515203 0.0603829 0.9952684 0.07577037 0.0608257 0.9951996 0.07670414 0.060781 0.9944421 0.08093422 0.06734055 0.9943161 0.08259063 0.06719076 0.9940496 0.08210951 0.07157856 0.9977807 0.02597635 0.06130969 0.9976686 0.0384131 0.05640941 0.9975081 0.04045033 0.05780708 0.9971274 0.04665482 0.05966943 0.9967236 0.05094635 0.06282168 0.9981862 0.008183062 0.05964416 0.9983066 0.01635605 0.05582582 0.9978759 0.02519416 0.06007486 0.9981828 -0.01576572 0.05815911 0.9982769 -0.01404953 0.05697292 0.9983577 -0.005307257 0.05704194 0.9981576 -0.00864309 0.06005662 0.9981577 0.008620142 0.06005614 0.9969354 -0.06109488 0.04886054 0.995726 -0.05302298 0.07562071 0.9967709 -0.04971063 0.06306105 0.9976267 -0.04000002 0.05604583 0.9974031 -0.04193925 0.05855029 0.9978986 -0.02901983 0.05793368 0.9977436 -0.02998864 0.06007152 0.9981458 -0.02160227 0.05690687 0.9847249 -0.1738678 0.009320855 0.9961087 -0.06700497 0.05725204 0.9951612 -0.07476586 0.06375139 0.9927777 -0.1151502 0.03366023 0.9859043 -0.1671195 0.007997572 0.9880353 -0.1374887 0.06987911 0.9736463 -0.2247194 0.03891086 0.9840139 -0.1774372 0.01526308 0.9865067 -0.1606779 0.03141814 0.9777175 -0.2094889 0.01352643 0.9760382 -0.2155712 0.02964192 0.9743389 -0.2234181 0.027354 0.969905 -0.2418838 0.02786535 0.9529663 -0.3029403 0.009074687 0.994031 -0.04590213 0.09897136 0.9934039 -0.08564776 0.07624441 0.9928448 -0.08737689 0.08139234 0.9927284 -0.0908963 0.0789197 0.9952105 -0.07675027 0.06054461 0.9944984 -0.0805661 0.06694883 0.9938351 -0.08589243 0.07010322 0.9938699 -0.08357572 0.07237392 0.993305 -0.08576577 0.07739168 0.9956492 0.09318053 -1.79432e-4 0.9956493 0.09318059 -1.7942e-4 0.9956493 0.09318059 -1.79423e-4 0.9957573 0.09201937 -4.83033e-5 0.9957573 0.09201943 -4.82766e-5 0.9957573 0.09201949 -4.84637e-5 0 0.0943939 -0.995535 0 0.0943939 -0.995535 0 0.0943939 -0.995535 0 0.09429907 -0.995544 0 0.09429907 -0.995544 0 0.09429907 -0.995544 0 -0.0944491 -0.9955298 0 -0.0944491 -0.9955298 0 -0.0944491 -0.9955298 0 -0.09473329 -0.9955027 0 -0.09473329 -0.9955027 0 -0.09473329 -0.9955027 0 -0.2396649 0.9708557 0 -0.2396647 0.9708558 0 -0.6638689 0.7478491 0 -0.6638695 0.7478485 0 -0.9393302 0.3430141 0 -0.9393311 0.343012 0 -0.9956658 -0.09300422 0 -0.9956662 -0.09300005 0 -0.8696034 -0.4937509 0 -0.8696038 -0.4937502 0 -0.6804981 -0.7327499 0 -0.6804968 -0.7327511 0 -0.4173946 -0.9087254 0 -0.4173949 -0.9087253 0 -0.09200632 -0.9957584 0 -0.0920062 -0.9957585 0 0.2396684 -0.9708548 0 0.2396696 -0.9708546 0 0.6638709 -0.7478473 0 0.6638737 -0.7478448 0 0.8877345 -0.4603561 -1.32214e-5 0.8877567 -0.4603131 1.11227e-5 0.9751887 -0.2213752 0 0.9752001 -0.2213252 0 0.9956658 0.09300345 0 0.9956656 0.09300583 0 0.8696039 0.4937503 0 0.8696021 0.4937532 0 0.6805134 0.7327357 0 0.6805039 0.7327445 0 0.4173918 0.9087267 0 0.4173896 0.9087278 0 0.09199476 0.9957596 0 0.09199392 0.9957596 0.9517644 -0.3044056 0.0384944 0.9504618 -0.3094603 -0.02927362 0.9507818 -0.3069905 -0.04208248 0.9490584 -0.3125093 -0.0403248 0.9466028 -0.3217057 -0.02118372 0.9506533 -0.3071068 -0.04409033 0.9509632 -0.30576 -0.04668825 0.9332694 -0.3591762 -8.58826e-4 0.9339953 -0.357285 6.21157e-4 0.9341427 -0.356899 -7.40876e-4 0.9382677 -0.3459097 5.91445e-4 0.9444099 -0.3287148 0.006070196 0.9498159 -0.3121333 0.02055644 0.952925 -0.3014816 0.03229218 0.9523026 -0.3047118 0.01645326 0.9525048 -0.3039923 0.01797878 0.9510945 -0.308852 -0.005463778 0 0.2419432 -0.9702905 0 0.2419439 -0.9702903 0 0.6079269 -0.793993 0.02989494 0.662511 -0.7484555 0 0.7770802 -0.6294017 0 0.9309084 -0.3652529 0 0.9309071 -0.365256 0 0.9974076 -0.07195955 0 0.9974079 -0.07195538 0 -0.9714441 -0.2372689 0 -0.9714437 -0.2372701 0 -0.748509 -0.6631246 0 -0.7485077 -0.6631261 0 -0.3542262 -0.9351598 0 -0.3542253 -0.9351601 0 -0.06091672 -0.9981428 0 -0.06091713 -0.9981428 0 -1 0 0 -0.2419487 0.9702891 0 -0.2419468 0.9702897 0 -0.6660053 0.7459471 0 -0.666006 0.7459465 0 -0.9309074 0.3652552 0 -0.9309068 0.3652569 0 -0.9974085 0.07194721 0 -0.9974083 0.07194977 0 0.9714431 0.2372726 0.069287 0.8114835 0.5802533 0 0.7485091 0.6631246 0 0.9714429 0.2372735 0 0.6532127 0.7571745 0 0.3542273 0.9351594 0 0.3542258 0.9351599 0 0.06091731 0.9981428 0 0.06091713 0.9981429 0.9878834 -0.1546383 0.01317453 0.9867005 -0.1596298 0.03066694 0.9875515 -0.1565872 0.01492494 0.9865618 -0.1602746 0.03174614 0.9520459 -0.2687605 0.1462076 0.9935193 -0.1136592 0.001062214 0.9897158 -0.1430282 0.00237739 0.9929047 -0.1189026 -0.001558542 0.993189 -0.1164211 0.004686236 0.9882871 -0.1495276 -0.03050035 0.9882357 -0.1521859 -0.01516181 0.9883788 -0.1486012 -0.03201609 0.9881882 -0.03227907 -0.1498076 0.9807592 -0.195219 -0.00110948 0.9861606 -0.1657744 -0.002489507 0.9817898 -0.1899635 0.00164467 0.981287 -0.1924918 -0.004790246 0.9879691 -0.1546514 0 0.9879689 -0.1546534 0 0.987886 -0.1546384 -0.01297187 0 0.2419477 -0.9702893 0 0.2419476 -0.9702893 0 0.6660109 -0.745942 0 0.6660134 -0.7459399 0 0.9309069 -0.3652568 0 0.930908 -0.3652539 0 0.9974083 -0.07195043 0 0.9974083 -0.07195019 0 -0.9714438 -0.2372703 0 -0.9714441 -0.2372686 0 -0.7485048 -0.6631295 0 -0.7485063 -0.6631278 0 -0.354229 -0.9351588 0 -0.3542306 -0.9351581 0 -0.06093573 -0.9981417 0 -0.06093585 -0.9981418 0 -0.2419477 0.9702893 0 -0.2419476 0.9702893 0 -0.6660062 0.7459463 0 -0.6660086 0.7459442 0 -0.9309069 0.3652568 0 -0.930908 0.3652539 0 -0.9974085 0.0719484 0 -0.9974083 0.0719487 0 0.9714438 0.2372703 0 0.9714441 0.2372686 0 0.7485083 0.6631255 0 0.7485098 0.6631238 0 0.3542248 0.9351603 0 0.3542264 0.9351598 0 0.06091654 0.998143 0 0.06091678 0.9981428 0.9999186 0 -0.01275724 0.9994002 -0.003368139 -0.03446811 0.9997974 -0.01464492 -0.01381397 0.999529 0.001180589 -0.03066694 0.9997433 -0.02253168 -0.002395391 0.9994986 0.005840361 -0.03112423 0.9995414 0.005055785 -0.02986145 0.9994001 0.003356635 0.03446972 0.9997974 0.01464849 0.01381379 0.999529 -0.001180589 0.03066694 0.9997435 0.02252477 0.002395331 0.9994986 -0.005840361 0.03112423 0.9995412 -0.005055844 0.02986156 0.9999186 0 0.01275706 0 0.2419442 -0.9702902 0 0.2419422 -0.9702907 0 0.6660084 -0.7459443 0 0.6660076 -0.745945 0 0.9309082 -0.3652535 0 0.9309071 -0.365256 0 0.9974085 -0.07194834 0 0.9974083 -0.07195067 0 -0.9714431 -0.2372726 0.06928271 -0.8114805 -0.5802581 0 -0.7485091 -0.6631246 0 -0.9714429 -0.2372735 0 -0.6532194 -0.7571688 0 -0.3542273 -0.9351594 0 -0.3542258 -0.9351599 0 -0.06091731 -0.9981428 0 -0.06091713 -0.9981429 0 -0.2419484 0.9702891 0 -0.2419484 0.9702891 0 -0.6079229 0.7939961 0.02988934 -0.6625095 0.748457 0 -0.7770802 0.6294017 0 -0.9309077 0.3652547 0 -0.9309068 0.3652569 0 -0.9974076 0.07195872 0 -0.9974079 0.07195448 0 0.9714441 0.2372689 0 0.9714437 0.2372701 0 0.748509 0.6631246 0 0.7485077 0.6631261 0 0.3542262 0.9351598 0 0.3542253 0.9351601 0 0.06091672 0.9981428 0 0.06091713 0.9981428 0.9878834 0.1546383 -0.01317453 0.9867005 0.1596298 -0.03066694 0.9875505 0.1565927 -0.01492542 0.9865618 0.1602746 -0.03174614 0.9520459 0.2687605 -0.1462076 0.9935194 0.1136575 -0.001062214 0.9897159 0.1430276 -0.00237739 0.9929046 0.1189036 0.001558601 0.9931889 0.1164215 -0.004686295 0.9882871 0.1495276 0.03050035 0.9882352 0.1521887 0.01516205 0.9883791 0.1486001 0.03201586 0.9881882 0.03227907 0.1498076 0.9807563 0.1952328 0.00110948 0.9861605 0.1657755 0.002489507 0.9817886 0.1899699 -0.00164467 0.981287 0.1924911 0.004790246 0.9879692 0.1546515 0 0.9879688 0.1546533 0 0.987886 0.1546388 0.01297193 0 0.2419471 -0.9702895 0 0.2419477 -0.9702894 0 0.6660097 -0.7459431 0 0.6660106 -0.7459423 0 0.9309088 -0.3652517 0 0.9309074 -0.3652552 0 0.9974084 -0.07194745 0 0.9974086 -0.0719456 0 -0.9714441 -0.237269 0 -0.971444 -0.2372689 0 -0.748508 -0.6631258 0 -0.7485104 -0.6631231 0 -0.3542183 -0.9351629 0 -0.3542168 -0.9351634 0 -0.0609548 -0.9981406 0 -0.06095427 -0.9981406 0 -0.2419486 0.9702891 0 -0.2419471 0.9702894 0 -0.6660058 0.7459466 0 -0.666006 0.7459464 0 -0.9309065 0.3652577 0 -0.9309082 0.3652532 0 -0.9974088 0.07194364 0 -0.997409 0.07193982 0 0.9714441 0.2372683 0 0.9714439 0.2372695 0 0.7485088 0.663125 0 0.748509 0.6631247 0 0.354227 0.9351595 0 0.3542261 0.9351598 0 0.0609166 0.9981429 0 0.0609166 0.9981429 0.9508531 0.3093098 -0.01435357 0.9487741 0.3142063 -0.03320002 0.9502857 0.310971 -0.01594424 0.9485759 0.3147084 -0.03409689 0.8948326 0.4184885 -0.1553771 0.9633816 0.2681315 -0.001159608 0.9547379 0.2974385 -0.002491831 0.9619235 0.2733141 0.001642525 0.9626107 0.2708429 -0.004982531 0.9520698 0.3041142 0.03282886 0.952347 0.3030341 0.03472113 0.9695973 0.1821442 0.1634154 0.9517008 0.3065842 0.01649415 0.9473552 0.3201726 0.002774059 0.938824 0.3443925 -0.001817166 0.9379958 0.3466191 0.004365265 0.9339872 0.3573062 6.00154e-4 0.950951 0.3093413 0 0.9509514 0.3093405 0 0.9508602 0.3093093 0.01388192 -0.9171848 -0.3490844 0.1921253 -0.9067778 -0.3658223 0.2095906 -0.8212448 -0.1226581 0.5572361 -0.8140892 -0.1309927 0.5657737 -0.8496395 -0.4855466 -0.2058091 -0.8507695 -0.4958709 -0.1740786 -0.8853521 -0.4624314 -0.04804986 -0.8257209 -0.5607943 0.0607866 -0.8558644 -0.4892714 0.1676599 -0.8383134 -0.4792325 0.2599363 -0.8346529 -0.471455 0.2847538 -0.756825 -0.4760744 0.4478495 -0.7180638 -0.5121115 0.4713028 -0.6848512 -0.3914974 0.6145802 -0.6561471 -0.3750939 0.6548096 -0.8693509 -0.4941178 0.008769392 -0.7868868 -0.3390368 0.5156194 -0.7464136 -0.3287952 0.578585 -0.8999211 -0.3825991 0.2091886 -0.7910619 -0.178771 0.5850316 -0.8249002 -0.1909541 0.5320491 -0.8949123 -0.4039701 0.1895792 -0.8636605 -0.4588659 0.2086445 -0.8671737 -0.4583342 0.1947813 -0.8451889 -0.4829813 -0.2288771 -0.9569972 -0.004841864 0.2900568 -0.9102581 -0.3867183 0.1479159 -0.9098007 -0.3778514 0.1717302 -0.9368067 -0.2479855 0.2467725 -0.9751146 -0.08451664 0.2049602 -0.959417 -0.1277651 0.2513864 -0.8718859 -0.4134786 0.2623938 -0.8794096 -0.3608133 0.3105682 -0.9301882 -0.2502421 0.2685682 -0.9371327 -0.1238543 0.3262552 -0.9523767 -0.09353035 0.2902252 -0.956993 -0.004747509 0.2900724 -0.9573054 -0.004554867 0.2890427 -0.9339739 -0.1519728 0.3234145 -0.9326695 -0.3601337 0.0207681 -0.9286751 -0.3650644 0.06550341 -0.9585237 -0.09775376 0.267725 -0.9597218 -0.007410943 0.2808548 -0.9634593 -0.002445697 0.2678441 -0.9640959 -0.007283627 0.2654545 -0.965741 -0.1398718 0.2185873 -0.9965589 -0.01982372 0.08048242 -0.952967 -0.2374446 0.1883458 -0.9607063 -0.2260438 0.1610833 -0.8724976 -0.4393136 0.2138962 -0.9269798 -0.357728 0.1128681 -0.974151 0.0120508 0.2255765 -0.974151 0.0120508 0.2255765 -0.974151 0.0120508 0.2255765 -0.9411324 -0.3323622 0.06168806 -0.9081269 -0.4101668 0.08407604 -0.9279441 -0.3664203 0.06823486 -0.9769681 -0.194714 0.08729237 -0.9469045 -0.3109409 0.08177846 -0.92447 -0.35289 0.1443048 -0.975548 -0.1220433 0.1827888 -0.9771201 -0.1120871 0.1807569 -0.9839671 -0.1056042 0.1437237 -0.9890236 -0.06370753 0.1333181 -0.9255639 -0.3273103 0.190262 -0.822163 -0.1147418 0.5575683 -0.9158545 -0.3300263 0.228677 -0.9455845 -0.2586319 0.197433 -0.9329782 -0.251112 0.2578654 -0.9615956 -0.1512486 0.2290369 -0.9507207 -0.154221 0.2689723 -0.9662871 -0.04805725 0.2529426 -0.9589077 -0.05458134 0.2784187 -0.814526 -0.1146442 0.5686864 -0.8251588 -0.08974915 0.5577259 -0.8135638 -0.08610278 0.5750655 -0.8234412 -0.05155181 0.565055 -0.8153389 -0.05209976 0.5766351 -0.8207049 -0.01581794 0.5711335 -0.8153865 -0.01789182 0.5786404 -0.7655134 -0.1392881 0.6281623 -0.6920401 -0.2629902 0.6722475 -0.6682377 -0.3297725 0.6668648 -0.6704238 -0.3413689 0.6587864 -0.6287462 -0.09711807 0.7715221 -0.7005183 -0.1919391 0.6873379 -0.7078089 -0.001312196 0.7064029 -0.7063886 -0.09746879 0.7010813 -0.6483468 -0.07207661 0.7579258 -0.7050604 -0.3289119 0.628257 -0.7040061 -0.329433 0.6291657 -0.8042658 -0.07423681 0.5896146 -0.9289265 -0.3477727 -0.1270822 -0.8387035 -0.5359141 0.09681344 -0.8209751 -0.3290728 0.4665951 -0.7333481 -0.4111149 0.5414657 -0.8858186 -0.3651002 0.2864041 -0.8605095 -0.387519 0.3306852 -0.8957259 -0.4129573 0.1647467 -0.9320423 -0.362331 0.00369203 -0.8855224 -0.4621014 -0.04808604 -0.9898294 -0.06314355 -0.1274783 -0.7631895 -0.1171571 0.6354652 -0.8875039 -0.06552487 0.4561178 -0.9277471 -0.1172332 0.3543187 -0.9822226 -0.08191531 0.1689048 -0.9864883 -0.1075006 0.1236305 -0.9914555 -0.1003733 -0.08331406 -0.9706904 -0.2057706 -0.124172 -0.9632149 -0.06338608 -0.26115 -0.8969498 -0.09247541 -0.4323533 -0.9433483 -0.2072982 -0.259078 -0.9041975 -0.3494969 -0.2455177 -0.7997144 -0.3876329 -0.4584731 -0.858757 -0.4681719 -0.2082106 -0.9449526 -0.1219888 0.3036172 -0.9568409 -0.004822909 0.2905724 -0.8773148 -0.3598384 0.3175454 -0.9418436 -0.1171385 0.3149749 -0.9443079 -0.1271145 0.3035204 -0.9181603 -0.243282 0.3127229 -0.9181603 -0.243282 0.3127229 -0.9181603 -0.2432819 0.3127229 -0.8774612 -0.3601753 0.3167579 -0.8771327 -0.3603058 0.3175184 -0.7407279 -0.4774447 0.4726191 -0.6858221 -0.5534273 0.4726166 -0.6349226 -0.6349265 0.4401609 -0.4774442 -0.7407291 0.4726177 -0.477448 -0.7407274 0.4726166 -0.5534293 -0.6858186 0.4726193 -0.5534271 -0.6858225 0.4726161 -0.6062102 -0.639355 0.4730057 -0.704795 -0.7048024 0.0807318 -0.5407668 -0.8389666 0.06088036 -0.704802 -0.7047957 0.08073014 -0.6259407 -0.7756808 0.08073157 -0.6259421 -0.77568 0.08072954 -0.5450252 -0.834522 0.08075058 -0.5231856 -0.8117076 0.2596303 -0.7407301 -0.4774435 0.472617 -0.8116981 -0.5232203 0.2595892 -0.8345213 -0.5450261 0.08075243 -0.8389668 -0.5407665 0.06088101 -0.8277359 -0.5335111 -0.1738372 -0.8277165 -0.5335358 -0.1738528 -0.7663722 -0.6184253 -0.1738504 -0.7756795 -0.6259427 0.08072853 -0.7756816 -0.62594 0.0807299 -0.6858201 -0.5534308 0.4726154 -0.6393581 -0.6062086 0.4730038 -0.5335218 -0.8277283 -0.1738401 -0.5335234 -0.8277249 -0.173851 -0.6184284 -0.7663719 -0.1738404 -0.618446 -0.7663582 -0.1738381 -0.6775289 -0.7146124 -0.1740223 -0.7067848 -0.7067807 -0.03027194 -0.7145856 -0.6775577 -0.1740201 -0.7663626 -0.618442 -0.1738331 -0.423074 -0.6355333 0.6458374 -0.4097163 -0.6356566 0.6542732 -0.6410589 -0.4102517 0.6486424 -0.6398575 -0.4102362 0.6498375 -0.635654 -0.4097185 0.6542742 -0.4101456 -0.6392197 0.6505219 -0.4094768 -0.6315314 0.6584049 -0.4767282 -0.59077 0.6509387 -0.475699 -0.593527 0.6491812 -0.5177594 -0.5460704 0.6585837 -0.5146644 -0.5537675 0.6545702 -0.5485324 -0.5200918 0.6546883 -0.5518329 -0.5128663 0.6576083 -0.5916557 -0.4774381 0.6496125 -0.5921485 -0.4745951 0.6512448 -0.6270302 -0.417371 0.6577497 -0.8156173 -0.5438597 0.1974465 -0.5539439 -0.8324825 0.01092082 -0.5421557 -0.8167573 0.1974205 -0.8323731 -0.5541124 0.01070088 -0.8323731 -0.5541125 0.01070088 -0.8323732 -0.5541124 0.01070082 -0.8198824 -0.5443891 0.1772952 -0.7679414 -0.6154609 0.1774086 -0.7679237 -0.6154817 0.1774136 -0.7208876 -0.6699601 0.1774109 -0.7208599 -0.6699904 0.1774091 -0.6699908 -0.7208614 0.1774011 -0.6699513 -0.7208943 0.1774167 -0.6154968 -0.7679123 0.1774103 -0.6154648 -0.7679368 0.1774156 -0.5461021 -0.81874 0.1773055 -0.4730507 -0.7101464 0.5214549 -0.4758406 -0.7167809 0.5097067 -0.5379537 -0.6712248 0.5099638 -0.5379716 -0.6712048 0.5099714 -0.585574 -0.6301075 0.5099684 -0.5856083 -0.6300775 0.509966 -0.6300728 -0.5856077 0.5099725 -0.6300969 -0.5855891 0.5099642 -0.671204 -0.5379734 0.5099705 -0.6712154 -0.5379671 0.5099622 -0.7160034 -0.4769828 0.5097318 -0.710912 -0.4718785 0.5214738 -0.4697693 -0.8827879 -0.001527607 -0.4950443 -0.8688641 0.002521574 -0.4956344 -0.8685232 0.003752112 -0.5538562 -0.8325506 -0.01014757 -0.5434459 -0.8369432 -0.0647515 -0.6240907 -0.7786877 0.06447046 -0.6095355 -0.7921013 -0.03228282 -0.6805031 -0.7322092 0.02802437 -0.6759204 -0.7369747 0 -0.7324965 -0.6807709 0 -0.7367643 -0.6757328 0.02374315 -0.7801502 -0.6252894 -0.01946496 -0.7919177 -0.6093866 0.03891682 -0.8315424 -0.5531712 -0.05038774 -0.838678 -0.5445708 -0.00788933 -0.8689877 -0.4948182 0.003938078 -0.8685227 -0.4956427 0.002616405 -0.8827939 -0.4697583 -0.001526474 -0.8101078 -0.57249 0.1264142 -0.8552509 -0.5141879 0.06447356 -0.8683749 -0.4955427 0.01904475 -0.834215 -0.4883054 0.2562091 -0.8204873 -0.5191325 0.2393787 -0.8143367 -0.5287652 0.2392977 -0.8143374 -0.5287644 0.2392967 -0.7695033 -0.5921392 0.2392406 -0.7695054 -0.5921381 0.2392367 -0.7155669 -0.6562997 0.2392379 -0.7155668 -0.6562994 0.239239 -0.6563003 -0.7155663 0.2392381 -0.6563003 -0.7155669 0.2392362 -0.5921404 -0.7695032 0.2392379 -0.5921376 -0.7695045 0.2392402 -0.5287612 -0.8143393 0.2392974 -0.5287649 -0.8143373 0.239296 -0.5188426 -0.82067 0.2393811 -0.4883316 -0.834262 0.256006 -0.5141794 -0.8552561 0.0644719 -0.4955377 -0.8683777 0.01904344 -0.8883014 -0.452125 0.08064544 -0.835962 -0.54281 0.08077734 -0.8359671 -0.5428025 0.08077478 -0.7899316 -0.6078542 0.08075571 -0.7899284 -0.6078584 0.08075439 -0.7345634 -0.6737173 0.08075726 -0.7345603 -0.6737207 0.08075779 -0.6737224 -0.7345588 0.08075702 -0.6737174 -0.7345633 0.08075702 -0.6078591 -0.7899278 0.080756 -0.6078543 -0.7899315 0.08075612 -0.5428075 -0.8359639 0.08077561 -0.5428072 -0.8359637 0.08077698 -0.5299693 -0.8441576 0.08081209 -0.4828956 -0.8629566 0.1487205 -0.542925 -0.779425 0.3126167 -0.4792878 -0.8188155 0.3159504 -0.5057443 -0.7788739 0.3709155 -0.8187968 -0.4793111 0.315963 -0.778885 -0.5057325 0.3709084 -0.5691781 -0.4379819 0.6958508 -0.4379876 -0.5691776 0.6958475 -0.5446295 -0.7809132 0.3058653 -0.6402488 -0.6980701 0.3205927 -0.6355777 -0.6355879 0.4382569 -0.6980754 -0.6402456 0.3205875 -0.7812409 -0.5442005 0.3057914 -0.7788335 -0.543815 0.312544 -0.9779713 -0.08371096 -0.1912191 -0.996737 -0.02921503 -0.07524645 -0.9962548 -0.02323752 -0.08328521 -0.9931332 -0.06832247 -0.09496706 -0.9931401 -0.072075 -0.09207564 -0.9883041 -0.1048105 -0.1107691 -0.9871339 -0.1213738 -0.1040921 -0.9824235 -0.140922 -0.1224135 -0.9525988 -0.2873362 -0.09996718 -0.9389197 -0.3381761 -0.06377112 -0.9412809 -0.3298855 -0.07187432 -0.9460577 -0.319507 -0.05376082 -0.9368761 -0.348268 -0.03118485 -0.9617962 -0.2648966 -0.06912237 -0.9733324 -0.1152528 -0.1983457 -0.973153 -0.1122773 -0.2009161 -0.975104 -0.1080899 -0.1936198 -0.9745273 -0.0930953 -0.2040339 -0.9609665 -0.09386235 -0.2602562 -0.9657668 -0.04432302 -0.2555975 -0.9570843 -0.1328711 -0.2575557 -0.9388208 -0.2318081 -0.2547163 -0.8841905 -0.4022447 -0.2375006 -0.9099586 -0.3482627 -0.2251413 -0.8964623 -0.3734449 -0.238525 -0.890372 -0.3869758 -0.2397654 -0.8805587 -0.4120921 -0.2340868 -0.8851248 -0.3988749 -0.2396933 -0.8802873 -0.417145 -0.2260185 -0.8789119 -0.4647595 -0.1072955 -0.8826925 -0.4242805 -0.202089 -0.9025582 -0.3912432 -0.179771 -0.9128326 -0.3570453 -0.1981301 -0.9245611 -0.3363524 -0.1790364 -0.9401353 -0.2662394 -0.2127496 -0.9488679 -0.2506948 -0.1918381 -0.9588584 -0.1948567 -0.2064494 -0.9654101 -0.1823433 -0.1863713 -0.9706847 -0.1204935 -0.2079731 -0.8824257 -0.4666428 -0.05974578 -0.8824015 -0.4666824 -0.05979388 -0.8885827 -0.4535079 -0.06893223 -0.8947953 -0.4425783 -0.05887323 -0.9065992 -0.4150682 -0.07613426 -0.9113669 -0.4065079 -0.06451171 -0.9208037 -0.3831394 -0.07297116 -0.9247378 -0.3756818 -0.06101959 -0.935939 -0.3441447 -0.07471877 -0.5274284 -0.8182755 -0.2285709 -0.8083826 -0.5421093 -0.2294234 -0.8093984 -0.542963 -0.2237534 -0.8093329 -0.5431087 -0.2236366 -0.8093745 -0.5428586 -0.2240927 -0.5419086 -0.8085034 -0.2294719 -0.5419086 -0.8085035 -0.2294719 -0.5419086 -0.8085035 -0.2294719 -0.5428586 -0.8093745 -0.224093 -0.5249381 -0.8207091 -0.225559 -0.5431316 -0.8093292 -0.2235942 -0.5340686 -0.8134943 -0.2302123 -0.6090305 -0.7598792 -0.2273008 -0.6116533 -0.7579762 -0.2266111 -0.6625096 -0.7128515 -0.2300517 -0.6697938 -0.7064184 -0.2288 -0.7130802 -0.6627204 -0.2287319 -0.7061346 -0.6695252 -0.2304564 -0.76004 -0.6091577 -0.2264202 -0.7578752 -0.6115734 -0.2271637 -0.8168371 -0.5288874 -0.2303373 -0.8182757 -0.5274283 -0.2285701 -0.9570315 0 0.2899839 -0.9570252 0 0.2900046 -0.9570373 0 0.289965 -0.957032 0 0.2899826 -0.957029 4.12547e-7 0.2899926 -0.9570403 1.05815e-6 0.2899554 -0.9570284 -6.13965e-7 0.2899946 -0.957032 -4.12094e-7 0.2899822 -0.9591585 0 0.282869 -0.9890111 0 0.1478421 -0.9889419 -3.37977e-5 0.1483035 -0.9751131 4.3105e-5 0.2217084 -0.9632125 -2.19423e-4 0.2687409 -0.9751009 -0.001662909 0.2217559 -0.9586691 0.005913972 0.284462 -0.9628168 0.004392266 0.2701198 -0.8155331 0 0.5787105 -0.815523 0 0.5787248 -0.9603418 0 0.2788255 -0.9603441 0 0.2788174 -0.7078359 -1.48499e-5 0.706377 -0.7078776 -9.67839e-5 0.7063351 -0.707814 -6.83487e-7 0.7063989 -0.7078146 -5.41569e-6 0.7063984 -0.7078146 5.41569e-6 0.7063984 -0.707814 6.83487e-7 0.7063989 -0.7078776 9.67839e-5 0.7063351 -0.7078387 1.56314e-5 0.7063741 -0.7077967 -1.8442e-5 0.7064162 -0.707825 0 0.7063879 -0.7078323 0 0.7063806 -0.7077967 1.8442e-5 0.7064162 -0.7558455 0 0.6547501 -0.762717 -1.35746e-4 0.6467324 -0.8794667 2.6517e-4 0.4759604 -0.8857759 -7.00534e-5 0.4641135 -0.980305 7.76438e-5 0.1974894 -0.9837981 -4.23854e-4 0.1792795 -0.9941811 4.08669e-4 -0.1077216 -0.992371 0 -0.1232876 -0.9652258 -7.31609e-6 -0.2614175 -0.9653762 5.12958e-4 -0.2608614 -0.9652333 7.65451e-6 -0.2613904 -0.9652303 2.14734e-5 -0.2614013 -0.9653686 -6.82183e-4 -0.2608888 -0.9652333 -7.65451e-6 -0.2613904 -0.9652298 7.38657e-6 -0.261403 -0.9652331 0 -0.2613908 -0.9652333 0 -0.2613901 -0.9652298 -7.38657e-6 -0.261403 -0.9652295 1.4901e-5 -0.2614042 -0.9652276 -1.99022e-6 -0.2614112 -0.9652276 9.23453e-6 -0.261411 -0.9652276 -9.85017e-6 -0.2614111 -0.9652276 1.99022e-6 -0.2614112 -0.9652298 -1.86262e-5 -0.2614031 -0.9971628 0 -0.07527577 -0.9971626 0 -0.07527828 -0.993533 2.406e-5 0.1135449 -0.9935328 6.23168e-7 0.1135458 -0.9935317 -2.57046e-6 0.1135551 -0.9935326 0 0.1135471 -0.9935328 0 0.1135457 -0.9935332 8.38187e-7 0.1135427 -0.9935327 -7.95333e-7 0.1135464 -0.993533 -5.23037e-7 0.1135448 -0.993532 1.20355e-6 0.1135529 -0.9935325 -3.59963e-7 0.1135484 -0.9935325 -6.74654e-7 0.113548 -0.9935328 5.72071e-7 0.113546 -0.993535 -1.11206e-6 0.1135268 -0.9935327 -1.6518e-7 0.1135469 -0.9935327 0 0.1135467 -0.9935328 3.14298e-6 0.1135452 -0.9935314 1.41023e-6 0.1135581 -0.9935344 7.3109e-7 0.1135322 -0.9935335 0 0.1135401 -0.9935296 4.28098e-6 0.1135739 -0.9935312 -5.52998e-6 0.1135592 -0.9935355 -2.39001e-6 0.1135222 -0.5524675 -0.8245871 -0.1218031 -0.5532864 -0.8250005 -0.1151013 -0.5955327 -0.7950261 -0.1152142 -0.6267083 -0.775736 -0.07396417 -0.6212415 -0.7751178 -0.1151157 -0.6762275 -0.7276414 -0.1151279 -0.6762419 -0.7276258 -0.1151418 -0.7184374 -0.6859899 -0.1151764 -0.7322871 -0.6805708 -0.02406334 -0.7430347 -0.659261 -0.115215 -0.775119 -0.6212383 -0.115125 -0.7751085 -0.6212481 -0.1151431 -0.8216723 -0.5582144 -0.1151143 -0.8298071 -0.5565103 -0.04142904 -0.8478164 -0.5174351 -0.1160526 -0.9738432 -0.2240204 0.03800457 -0.9940599 -0.04585772 0.0987026 -0.9798867 -0.1977521 0.02676343 -0.9805354 -0.1943587 0.02784401 -0.9710927 -0.2379058 0.01949208 -0.9718039 -0.2344131 0.02545464 -0.9667653 -0.2537965 0.03085947 -0.9564817 -0.2917923 -3.22485e-4 -0.9936006 -0.08207744 0.0775966 -0.9933396 -0.08567267 0.07704997 -0.9928302 -0.08740067 0.08154499 -0.9928297 -0.08740472 0.08154505 -0.9932031 -0.08623695 0.0781719 -0.9881525 -0.1371048 0.06897044 -0.8157596 0.1334791 0.5627785 -0.81955 0.1200275 0.5602957 -0.9067606 0.3697567 0.2026455 -0.9172851 0.3448913 0.1990936 -0.6848512 0.3914974 0.6145802 -0.7210782 0.5304195 0.4457595 -0.7341614 0.4877722 0.4723192 -0.8330194 0.4681086 0.294878 -0.8383557 0.4791662 0.2599223 -0.8474174 0.4843244 0.2175171 -0.8505208 0.5013476 0.1589496 -0.8297407 0.5548258 0.06081736 -0.8733907 0.4869657 -0.007286369 -0.8557849 0.4922977 -0.1589818 -0.8507695 0.4958709 -0.1740786 -0.8496395 0.4855466 -0.2058091 -0.6561478 0.3750943 0.6548086 -0.8647425 0.46283 0.1949588 -0.7733759 0.3658473 0.517731 -0.8693509 0.4941178 0.008769392 -0.8658787 0.4552391 0.2073919 -0.9003446 0.3934673 0.1859115 -0.8949189 0.3916745 0.2138022 -0.7593408 0.3089363 0.5726779 -0.8125358 0.2159704 0.5414263 -0.8031877 0.1571862 0.5746147 -0.845189 0.4829809 -0.2288777 -0.904453 0.3917863 0.1687256 -0.8395236 0.4280583 0.3346138 -0.8917861 0.3666676 0.2650896 -0.956996 0.004741311 0.2900627 -0.9573054 0.004554867 0.2890427 -0.9604584 0.09073221 0.263225 -0.9702579 0.1148006 0.2131206 -0.9141508 0.3732947 0.1580491 -0.9368067 0.2479855 0.2467725 -0.9301882 0.2502421 0.2685682 -0.9363454 0.098266 0.3370477 -0.9483938 0.1290653 0.28964 -0.9569942 0.004846096 0.2900665 -0.8724976 0.4393136 0.2138962 -0.926979 0.3577299 0.1128687 -0.9607058 0.2260457 0.161083 -0.9241675 0.1352341 0.3572483 -0.9560147 0.1314318 0.2622247 -0.9639124 0.007682383 0.2661092 -0.9237784 0.3780253 0.06107658 -0.9360961 0.3499361 0.0356208 -0.9529659 0.2374483 0.188346 -0.9894918 0.08798444 0.114738 -0.9673856 0.0855211 0.238435 -0.9636442 0.00211364 0.2671809 -0.9597218 0.007410943 0.2808548 -0.9870361 0.1025491 0.1234644 -0.9166995 0.3596186 0.1741736 -0.92447 0.35289 0.1443048 -0.946905 0.3109395 0.0817787 -0.9769684 0.1947124 0.08729267 -0.9832619 0.05871772 0.1724769 -0.9279441 0.3664203 0.06823486 -0.9392814 0.3381927 0.05810642 -0.975548 0.1220433 0.1827888 -0.9772174 0.1114467 0.1806261 -0.9742213 -0.01256704 0.2252442 -0.8192674 0.1206651 0.560572 -0.9169332 0.3456134 0.199462 -0.8173793 0.1081332 0.5658608 -0.822993 0.09497743 0.5600553 -0.8154421 0.0798012 0.5733115 -0.8222708 0.05589526 0.5663449 -0.8161288 0.04715752 0.5759426 -0.8202997 0.01878905 0.5716253 -0.8154357 0.01468729 0.5786614 -0.9248964 0.3100981 0.2200135 -0.9394316 0.2749504 0.2046233 -0.9394592 0.2317124 0.2524397 -0.9583796 0.1648449 0.2330981 -0.9536972 0.1388236 0.2668142 -0.9653814 0.05734604 0.2544608 -0.9593867 0.0445435 0.2785555 -0.6950998 0.188675 0.6937132 -0.7947034 0.1038179 0.5980539 -0.763498 0.1363626 0.6312497 -0.6924479 0.2634515 0.6716468 -0.6065158 0.09122431 0.7898207 -0.6723631 0.3386905 0.6581921 -0.6694053 0.3250096 0.668031 -0.7053132 0.3247406 0.6301404 -0.6972371 0.3285496 0.6371151 -0.6644058 0.07238239 0.7438588 -0.7066626 0.0916692 0.7015874 -0.9703279 0.207338 -0.1243978 -0.8649225 0.3761607 0.3322836 -0.8680319 0.4693073 -0.1620841 -0.9246803 0.3200542 0.2062319 -0.926861 0.374971 -0.01804268 -0.8745671 0.4678431 -0.1274968 -0.9124145 0.3792678 0.153805 -0.9078351 0.4051668 0.1080523 -0.8876324 0.4064832 0.2165185 -0.8699375 0.3938185 0.2968431 -0.7573673 0.07390213 0.6487938 -0.8151147 0.3294685 0.4764856 -0.7380324 0.3982769 0.5446868 -0.8020209 0.1037262 0.5882205 -0.9341887 0.02239441 0.3560758 -0.8786339 0.1380742 0.4570972 -0.9897027 0.07021397 0.1247344 -0.9760705 0.1201494 0.1812474 -0.992358 0.09281277 -0.08131068 -0.9916346 0.06398552 -0.1121017 -0.8579018 0.4698259 -0.2080104 -0.8021025 0.388113 -0.4538725 -0.9030711 0.3528672 -0.2448416 -0.9431761 0.2085074 -0.2587342 -0.8987328 0.09254151 -0.4286204 -0.9631435 0.06436324 -0.2611745 -0.9448788 0.1224554 0.3036589 -0.8771327 0.3603058 0.3175184 -0.9568392 0.004830896 0.2905777 -0.9417548 0.1175995 0.3150688 -0.9440961 0.1270204 0.3042176 -0.877461 0.3601753 0.3167585 -0.8773148 0.3598384 0.3175454 -0.977972 0.08367788 -0.1912296 -0.9968692 0.02426236 -0.07525545 -0.9960132 0.02828961 -0.08460175 -0.9929151 0.07062351 -0.09556096 -0.9933897 0.07006669 -0.09092688 -0.9868806 0.1129267 -0.1153877 -0.9884812 0.1151205 -0.0982455 -0.9730077 0.1731313 -0.1525825 -0.9690273 0.2436463 -0.04028135 -0.9617956 0.2649011 -0.06911283 -0.9368764 0.3482682 -0.03117513 -0.9383539 0.3393381 -0.06589066 -0.9418738 0.3286548 -0.06971371 -0.9460577 0.319507 -0.05376082 -0.9731481 0.1156134 -0.1990389 -0.9733442 0.1118792 -0.2002102 -0.9749393 0.1084473 -0.1942487 -0.9747152 0.09259724 -0.2033624 -0.9647214 0.0323829 -0.2612738 -0.9618583 0.09386163 -0.2569411 -0.957084 0.1328737 -0.2575556 -0.9388211 0.2318067 -0.2547168 -0.8851247 0.3988753 -0.2396935 -0.8803901 0.4125696 -0.2338795 -0.8896291 0.3888178 -0.2395427 -0.8965871 0.3732191 -0.2384095 -0.9099586 0.3482627 -0.2251411 -0.8841905 0.4022447 -0.2375006 -0.8845129 0.4544161 -0.1055606 -0.8839665 0.4094721 -0.2256899 -0.8839665 0.4094721 -0.2256899 -0.8839666 0.4094721 -0.22569 -0.8739153 0.4810808 -0.06952267 -0.8851962 0.4617768 -0.05647796 -0.8863361 0.4573325 -0.0724945 -0.8979738 0.4367781 -0.05355608 -0.9044461 0.4187923 -0.08118176 -0.9138664 0.4018117 -0.05827403 -0.9188162 0.3867464 -0.07876592 -0.9262468 0.3726963 -0.05625212 -0.9346974 0.3465248 -0.07912862 -0.8822582 0.4249626 -0.2025522 -0.9092 0.37929 -0.1717395 -0.9073548 0.3661253 -0.2065421 -0.9318249 0.3225444 -0.1663353 -0.9349302 0.2748476 -0.22442 -0.9542706 0.2402773 -0.1778604 -0.9543444 0.2028442 -0.2192741 -0.9680723 0.1768847 -0.1776171 -0.9683762 0.1248605 -0.2160034 -0.9858434 -0.1675068 -0.007381618 -0.9860413 -0.166104 0.01149404 -0.9876406 -0.1543912 0.02700889 -0.9849841 -0.1715938 0.01902449 -0.9801201 -0.1977939 0.01555788 -0.9969524 -0.04993653 0.05993688 -0.996463 -0.05933648 0.05950462 -0.9960354 -0.06539618 0.06030654 -0.996095 -0.06494212 0.05981194 -0.9953422 -0.07515203 0.0603829 -0.9952684 -0.07577037 0.0608257 -0.9951996 -0.07670414 0.060781 -0.9944421 -0.08093422 0.06734055 -0.9943161 -0.08259063 0.06719076 -0.9940496 -0.08210951 0.07157856 -0.9977807 -0.02597635 0.06130969 -0.9976686 -0.0384131 0.05640941 -0.9975081 -0.04045033 0.05780708 -0.9971274 -0.04665482 0.05966943 -0.9967236 -0.05094635 0.06282168 -0.9981862 -0.008183062 0.05964416 -0.9983066 -0.01635605 0.05582582 -0.9978759 -0.02519416 0.06007486 -0.9981828 0.01576572 0.05815911 -0.9982769 0.01404953 0.05697292 -0.9983577 0.005307257 0.05704194 -0.9981576 0.00864309 0.06005662 -0.9981577 -0.008620142 0.06005614 -0.9969354 0.06109488 0.04886054 -0.995726 0.05302298 0.07562071 -0.9967709 0.04971063 0.06306105 -0.9976267 0.04000002 0.05604583 -0.9974031 0.04193925 0.05855029 -0.9978986 0.02901983 0.05793368 -0.9977436 0.02998864 0.06007152 -0.9981458 0.02160227 0.05690687 -0.9847249 0.1738678 0.009320855 -0.9961087 0.06700497 0.05725204 -0.9951612 0.07476586 0.06375139 -0.9927777 0.1151502 0.03366023 -0.9859043 0.1671195 0.007997572 -0.9880353 0.1374887 0.06987911 -0.9736463 0.2247194 0.03891086 -0.9840139 0.1774372 0.01526308 -0.9865067 0.1606779 0.03141814 -0.9777175 0.2094889 0.01352643 -0.9760382 0.2155712 0.02964192 -0.9743389 0.2234181 0.027354 -0.969905 0.2418838 0.02786535 -0.9529663 0.3029403 0.009074687 -0.994031 0.04590213 0.09897136 -0.9934039 0.08564776 0.07624441 -0.9928448 0.08737689 0.08139234 -0.9927284 0.0908963 0.0789197 -0.9952105 0.07675027 0.06054461 -0.9944984 0.0805661 0.06694883 -0.9938351 0.08589243 0.07010322 -0.9938699 0.08357572 0.07237392 -0.993305 0.08576577 0.07739168 -0.9956492 -0.09318053 -1.79432e-4 -0.9956493 -0.09318059 -1.7942e-4 -0.9956493 -0.09318059 -1.79423e-4 -0.9957573 -0.09201937 -4.83033e-5 -0.9957573 -0.09201943 -4.82766e-5 -0.9957573 -0.09201949 -4.84637e-5 0 -0.0943939 -0.995535 0 -0.0943939 -0.995535 0 -0.0943939 -0.995535 0 -0.09429907 -0.995544 0 -0.09429907 -0.995544 0 -0.09429907 -0.995544 0 0.0944491 -0.9955298 0 0.0944491 -0.9955298 0 0.0944491 -0.9955298 0 0.09473329 -0.9955027 0 0.09473329 -0.9955027 0 0.09473329 -0.9955027 0 0.2396649 0.9708557 0 0.2396647 0.9708558 0 0.6638689 0.7478491 0 0.6638695 0.7478485 0 0.9393302 0.3430141 0 0.9393311 0.343012 0 0.9956658 -0.09300422 0 0.9956662 -0.09300005 0 0.8696034 -0.4937509 0 0.8696038 -0.4937502 0 0.6804981 -0.7327499 0 0.6804968 -0.7327511 0 0.4173946 -0.9087254 0 0.4173949 -0.9087253 0 0.09200632 -0.9957584 0 0.0920062 -0.9957585 0 -0.2396684 -0.9708548 0 -0.2396696 -0.9708546 0 -0.6638709 -0.7478473 0 -0.6638737 -0.7478448 0 -0.8877345 -0.4603561 1.32214e-5 -0.8877567 -0.4603131 -1.11227e-5 -0.9751887 -0.2213752 0 -0.9752001 -0.2213252 0 -0.9956658 0.09300345 0 -0.9956656 0.09300583 0 -0.8696039 0.4937503 0 -0.8696021 0.4937532 0 -0.6805134 0.7327357 0 -0.6805039 0.7327445 0 -0.4173918 0.9087267 0 -0.4173896 0.9087278 0 -0.09199476 0.9957596 0 -0.09199392 0.9957596 -0.9517644 0.3044056 0.0384944 -0.9504618 0.3094603 -0.02927362 -0.9507818 0.3069905 -0.04208248 -0.9490584 0.3125093 -0.0403248 -0.9466028 0.3217057 -0.02118372 -0.9506533 0.3071068 -0.04409033 -0.9509632 0.30576 -0.04668825 -0.9332694 0.3591762 -8.58826e-4 -0.9339953 0.357285 6.21157e-4 -0.9341427 0.356899 -7.40876e-4 -0.9382677 0.3459097 5.91445e-4 -0.9444099 0.3287148 0.006070196 -0.9498159 0.3121333 0.02055644 -0.952925 0.3014816 0.03229218 -0.9523026 0.3047118 0.01645326 -0.9525048 0.3039923 0.01797878 -0.9510945 0.308852 -0.005463778 0 -0.2419432 -0.9702905 0 -0.2419439 -0.9702903 0 -0.6079269 -0.793993 -0.02989494 -0.662511 -0.7484555 0 -0.7770802 -0.6294017 0 -0.9309084 -0.3652529 0 -0.9309071 -0.365256 0 -0.9974076 -0.07195955 0 -0.9974079 -0.07195538 0 0.9714441 -0.2372689 0 0.9714437 -0.2372701 0 0.748509 -0.6631246 0 0.7485077 -0.6631261 0 0.3542262 -0.9351598 0 0.3542253 -0.9351601 0 0.06091672 -0.9981428 0 0.06091713 -0.9981428 0 0.2419487 0.9702891 0 0.2419468 0.9702897 0 0.6660053 0.7459471 0 0.666006 0.7459465 0 0.9309074 0.3652552 0 0.9309068 0.3652569 0 0.9974085 0.07194721 0 0.9974083 0.07194977 0 -0.9714431 0.2372726 -0.069287 -0.8114835 0.5802533 0 -0.7485091 0.6631246 0 -0.9714429 0.2372735 0 -0.6532127 0.7571745 0 -0.3542273 0.9351594 0 -0.3542258 0.9351599 0 -0.06091731 0.9981428 0 -0.06091713 0.9981429 -0.9878834 0.1546383 0.01317453 -0.9867005 0.1596298 0.03066694 -0.9875515 0.1565872 0.01492494 -0.9865618 0.1602746 0.03174614 -0.9520459 0.2687605 0.1462076 -0.9935193 0.1136592 0.001062214 -0.9897158 0.1430282 0.00237739 -0.9929047 0.1189026 -0.001558542 -0.993189 0.1164211 0.004686236 -0.9882871 0.1495276 -0.03050035 -0.9882357 0.1521859 -0.01516181 -0.9883788 0.1486012 -0.03201609 -0.9881882 0.03227907 -0.1498076 -0.9807592 0.195219 -0.00110948 -0.9861606 0.1657744 -0.002489507 -0.9817898 0.1899635 0.00164467 -0.981287 0.1924918 -0.004790246 -0.9879691 0.1546514 0 -0.9879689 0.1546534 0 -0.987886 0.1546384 -0.01297187 0 -0.2419477 -0.9702893 0 -0.2419476 -0.9702893 0 -0.6660109 -0.745942 0 -0.6660134 -0.7459399 0 -0.9309069 -0.3652568 0 -0.930908 -0.3652539 0 -0.9974083 -0.07195043 0 -0.9974083 -0.07195019 0 0.9714438 -0.2372703 0 0.9714441 -0.2372686 0 0.7485048 -0.6631295 0 0.7485063 -0.6631278 0 0.354229 -0.9351588 0 0.3542306 -0.9351581 0 0.06093573 -0.9981417 0 0.06093585 -0.9981418 0 0.2419477 0.9702893 0 0.2419476 0.9702893 0 0.6660062 0.7459463 0 0.6660086 0.7459442 0 0.9309069 0.3652568 0 0.930908 0.3652539 0 0.9974085 0.0719484 0 0.9974083 0.0719487 0 -0.9714438 0.2372703 0 -0.9714441 0.2372686 0 -0.7485083 0.6631255 0 -0.7485098 0.6631238 0 -0.3542248 0.9351603 0 -0.3542264 0.9351598 0 -0.06091654 0.998143 0 -0.06091678 0.9981428 -0.9999186 0 -0.01275724 -0.9994002 0.003368139 -0.03446811 -0.9997974 0.01464492 -0.01381397 -0.999529 -0.001180589 -0.03066694 -0.9997433 0.02253168 -0.002395391 -0.9994986 -0.005840361 -0.03112423 -0.9995414 -0.005055785 -0.02986145 -0.9994001 -0.003356635 0.03446972 -0.9997974 -0.01464849 0.01381379 -0.999529 0.001180589 0.03066694 -0.9997435 -0.02252477 0.002395331 -0.9994986 0.005840361 0.03112423 -0.9995412 0.005055844 0.02986156 -0.9999186 0 0.01275706 0 -0.2419442 -0.9702902 0 -0.2419422 -0.9702907 0 -0.6660084 -0.7459443 0 -0.6660076 -0.745945 0 -0.9309082 -0.3652535 0 -0.9309071 -0.365256 0 -0.9974085 -0.07194834 0 -0.9974083 -0.07195067 0 0.9714431 -0.2372726 -0.06928271 0.8114805 -0.5802581 0 0.7485091 -0.6631246 0 0.9714429 -0.2372735 0 0.6532194 -0.7571688 0 0.3542273 -0.9351594 0 0.3542258 -0.9351599 0 0.06091731 -0.9981428 0 0.06091713 -0.9981429 0 0.2419484 0.9702891 0 0.2419484 0.9702891 0 0.6079229 0.7939961 -0.02988934 0.6625095 0.748457 0 0.7770802 0.6294017 0 0.9309077 0.3652547 0 0.9309068 0.3652569 0 0.9974076 0.07195872 0 0.9974079 0.07195448 0 -0.9714441 0.2372689 0 -0.9714437 0.2372701 0 -0.748509 0.6631246 0 -0.7485077 0.6631261 0 -0.3542262 0.9351598 0 -0.3542253 0.9351601 0 -0.06091672 0.9981428 0 -0.06091713 0.9981428 -0.9878834 -0.1546383 -0.01317453 -0.9867005 -0.1596298 -0.03066694 -0.9875505 -0.1565927 -0.01492542 -0.9865618 -0.1602746 -0.03174614 -0.9520459 -0.2687605 -0.1462076 -0.9935194 -0.1136575 -0.001062214 -0.9897159 -0.1430276 -0.00237739 -0.9929046 -0.1189036 0.001558601 -0.9931889 -0.1164215 -0.004686295 -0.9882871 -0.1495276 0.03050035 -0.9882352 -0.1521887 0.01516205 -0.9883791 -0.1486001 0.03201586 -0.9881882 -0.03227907 0.1498076 -0.9807563 -0.1952328 0.00110948 -0.9861605 -0.1657755 0.002489507 -0.9817886 -0.1899699 -0.00164467 -0.981287 -0.1924911 0.004790246 -0.9879692 -0.1546515 0 -0.9879688 -0.1546533 0 -0.987886 -0.1546388 0.01297193 0 -0.2419471 -0.9702895 0 -0.2419477 -0.9702894 0 -0.6660097 -0.7459431 0 -0.6660106 -0.7459423 0 -0.9309088 -0.3652517 0 -0.9309074 -0.3652552 0 -0.9974084 -0.07194745 0 -0.9974086 -0.0719456 0 0.9714441 -0.237269 0 0.971444 -0.2372689 0 0.748508 -0.6631258 0 0.7485104 -0.6631231 0 0.3542183 -0.9351629 0 0.3542168 -0.9351634 0 0.0609548 -0.9981406 0 0.06095427 -0.9981406 0 0.2419486 0.9702891 0 0.2419471 0.9702894 0 0.6660058 0.7459466 0 0.666006 0.7459464 0 0.9309065 0.3652577 0 0.9309082 0.3652532 0 0.9974088 0.07194364 0 0.997409 0.07193982 0 -0.9714441 0.2372683 0 -0.9714439 0.2372695 0 -0.7485088 0.663125 0 -0.748509 0.6631247 0 -0.354227 0.9351595 0 -0.3542261 0.9351598 0 -0.0609166 0.9981429 0 -0.0609166 0.9981429 -0.9508531 -0.3093098 -0.01435357 -0.9487741 -0.3142063 -0.03320002 -0.9502857 -0.310971 -0.01594424 -0.9485759 -0.3147084 -0.03409689 -0.8948326 -0.4184885 -0.1553771 -0.9633816 -0.2681315 -0.001159608 -0.9547379 -0.2974385 -0.002491831 -0.9619235 -0.2733141 0.001642525 -0.9626107 -0.2708429 -0.004982531 -0.9520698 -0.3041142 0.03282886 -0.952347 -0.3030341 0.03472113 -0.9695973 -0.1821442 0.1634154 -0.9517008 -0.3065842 0.01649415 -0.9473552 -0.3201726 0.002774059 -0.938824 -0.3443925 -0.001817166 -0.9379958 -0.3466191 0.004365265 -0.9339872 -0.3573062 6.00154e-4 -0.950951 -0.3093413 0 -0.9509514 -0.3093405 0 -0.9508602 -0.3093093 0.01388192 -0.1334748 -0.8157937 0.56273 -0.1200213 -0.8195706 0.5602669 -0.3697534 -0.9067596 0.2026561 -0.3449065 -0.9172778 0.1991009 -0.3914953 -0.6848384 0.6145957 -0.5304411 -0.7210667 0.4457525 -0.4877663 -0.7341705 0.4723111 -0.4681163 -0.8330134 0.2948828 -0.4791707 -0.8383461 0.2599447 -0.4843467 -0.8474032 0.2175229 -0.5013722 -0.8505092 0.1589348 -0.5548309 -0.8297376 0.06081384 -0.4869632 -0.8733921 -0.007286489 -0.4923287 -0.855777 -0.1589292 -0.4959021 -0.8507526 -0.1740726 -0.4854963 -0.8496689 -0.2058067 -0.3751079 -0.6561474 0.6548012 -0.4628296 -0.8647433 0.1949558 -0.3658379 -0.773369 0.5177479 -0.4939566 -0.8694414 0.008859395 -0.4552457 -0.8658755 0.2073912 -0.3934645 -0.9003461 0.1859111 -0.3916662 -0.8949241 0.2137957 -0.3089507 -0.7593363 0.5726762 -0.2159704 -0.8125358 0.5414263 -0.1571872 -0.8031857 0.5746171 -0.4829763 -0.8451912 -0.2288792 -0.391786 -0.904454 0.1687213 -0.4280547 -0.8395238 0.3346177 -0.3666675 -0.8917867 0.2650876 -0.004741251 -0.9570005 0.2900477 -0.004651725 -0.9572983 0.2890647 -0.09072738 -0.9604582 0.2632275 -0.1148049 -0.9702567 0.2131241 -0.3732945 -0.9141511 0.1580477 -0.247996 -0.9368035 0.2467738 -0.2502458 -0.9301868 0.2685698 -0.09826099 -0.9363488 0.3370398 -0.1290645 -0.9483916 0.2896475 -0.004846215 -0.9569922 0.2900732 -0.439305 -0.8725029 0.2138919 -0.3577304 -0.9269779 0.1128754 -0.226046 -0.9607049 0.1610877 -0.1352332 -0.9241654 0.3572539 -0.1314283 -0.9560157 0.2622229 -0.007759571 -0.9639164 0.2660921 -0.3780367 -0.9237735 0.06108045 -0.3499168 -0.9361034 0.035618 -0.2374438 -0.9529673 0.1883451 -0.08798491 -0.9894914 0.1147417 -0.08552175 -0.9673891 0.2384207 -0.002038061 -0.9636494 0.2671625 -0.007411181 -0.9597161 0.2808741 -0.1025474 -0.9870364 0.1234638 -0.3597598 -0.9166446 0.1741713 -0.3528798 -0.9244741 0.1443036 -0.3109368 -0.9469059 0.08177804 -0.1947193 -0.976967 0.08729255 -0.05871695 -0.9832616 0.1724792 -0.3664222 -0.9279432 0.0682373 -0.3381885 -0.9392828 0.05810755 -0.1220421 -0.9755482 0.1827882 -0.1114483 -0.977217 0.1806274 0.012676 -0.9742258 0.2252185 -0.1206737 -0.8192618 0.5605784 -0.3456187 -0.9169325 0.1994559 -0.1081119 -0.8173784 0.5658662 -0.09497827 -0.8229932 0.5600548 -0.07980847 -0.8154516 0.573297 -0.05589169 -0.8222634 0.5663561 -0.0471704 -0.8161129 0.5759643 -0.01880198 -0.8202767 0.571658 -0.01468098 -0.8154386 0.5786573 -0.3101063 -0.9248912 0.2200238 -0.2749571 -0.9394281 0.2046302 -0.2317241 -0.9394575 0.2524354 -0.1648347 -0.9583836 0.2330893 -0.1388298 -0.9536926 0.2668274 -0.05734127 -0.9653864 0.2544429 -0.04453527 -0.9593895 0.2785469 -0.1886851 -0.6951001 0.6937102 -0.103797 -0.7946895 0.598076 -0.1363626 -0.7634964 0.6312517 -0.2634465 -0.69245 0.6716465 -0.09120929 -0.6065269 0.7898139 -0.3387274 -0.6723328 0.6582039 -0.325006 -0.6694071 0.6680309 -0.3247447 -0.7053136 0.6301378 -0.3285466 -0.6972466 0.6371062 -0.07238119 -0.6643993 0.7438646 -0.09166944 -0.706651 0.701599 -0.2073553 -0.9703261 -0.1243836 -0.3761702 -0.8649188 0.3322824 -0.4692471 -0.8680623 -0.162096 -0.3199706 -0.9247077 0.2062391 -0.3749771 -0.9268585 -0.01804262 -0.4678497 -0.8745635 -0.1274963 -0.3792613 -0.9124178 0.153801 -0.4051786 -0.9078306 0.1080467 -0.4064354 -0.8876623 0.2164854 -0.3938244 -0.8699279 0.2968632 -0.07389813 -0.7573691 0.6487921 -0.3294654 -0.8151069 0.4765011 -0.3982672 -0.7380465 0.5446748 -0.1037311 -0.8020267 0.5882117 -0.02238976 -0.9341822 0.3560933 -0.1380708 -0.8786383 0.45709 -0.07021266 -0.9897028 0.1247342 -0.1201485 -0.9760689 0.1812563 -0.09280711 -0.9923588 -0.08130836 -0.06399214 -0.9916335 -0.1121073 -0.4698505 -0.8578947 -0.2079839 -0.3881258 -0.802096 -0.4538727 -0.3529068 -0.9030608 -0.2448224 -0.2085363 -0.9431551 -0.2587878 -0.0925424 -0.898735 -0.4286157 -0.06435275 -0.9631514 -0.2611477 -0.122461 -0.9448779 0.3036596 -0.3603028 -0.8771365 0.3175112 -0.004768013 -0.9568422 0.2905691 -0.117605 -0.9417546 0.3150671 -0.1270149 -0.944096 0.3042203 -0.3601855 -0.8774569 0.3167584 -0.3598226 -0.8773224 0.3175423 -0.0836941 -0.9779709 -0.1912284 -0.02426105 -0.9968693 -0.07525449 -0.02828532 -0.9960137 -0.084598 -0.07062864 -0.9929137 -0.09557181 -0.07007026 -0.9933887 -0.09093427 -0.1129222 -0.9868826 -0.1153746 -0.1151257 -0.9884794 -0.09825813 -0.1731155 -0.9730111 -0.152579 -0.2436602 -0.9690235 -0.04028886 -0.2751313 -0.9578065 -0.08312422 -0.3393397 -0.9383536 -0.06588828 -0.3286434 -0.9418773 -0.0697202 -0.3176547 -0.946857 -0.05056923 -0.1156426 -0.9731422 -0.1990507 -0.1118778 -0.9733449 -0.2002077 -0.1084686 -0.9749368 -0.1942499 -0.09258371 -0.974716 -0.2033645 -0.03238296 -0.9647215 -0.2612735 -0.09385901 -0.9618587 -0.2569407 -0.1328794 -0.9570844 -0.257551 -0.2318092 -0.9388191 -0.254722 -0.3988847 -0.8851207 -0.2396925 -0.4125763 -0.8803868 -0.2338802 -0.3888137 -0.8896312 -0.2395419 -0.3732216 -0.8965866 -0.2384077 -0.3482616 -0.9099583 -0.225144 -0.4022462 -0.8841888 -0.2375043 -0.4544272 -0.8845062 -0.1055696 -0.4096327 -0.8838676 -0.2257857 -0.4810503 -0.8739315 -0.0695309 -0.4617542 -0.885208 -0.05647921 -0.4573381 -0.8863312 -0.07251954 -0.4367662 -0.8979794 -0.05355811 -0.418803 -0.9044428 -0.08116358 -0.4018316 -0.9138571 -0.05828148 -0.3867225 -0.918826 -0.07876884 -0.3726997 -0.9262452 -0.05625766 -0.3465213 -0.9346989 -0.07912653 -0.4249476 -0.8822729 -0.2025192 -0.3792952 -0.9091987 -0.1717348 -0.3661599 -0.9073429 -0.2065328 -0.3225358 -0.9318301 -0.1663234 -0.2748508 -0.9349272 -0.2244288 -0.2403106 -0.9542589 -0.1778787 -0.2028309 -0.9543476 -0.2192726 -0.176875 -0.9680749 -0.1776125 -0.1248769 -0.9683718 -0.2160136 0 -0.9570289 0.2899925 0 -0.9570259 0.2900025 0 -0.957036 0.2899693 0 -0.9570289 0.289993 0 -0.957032 0.2899827 -1.0582e-6 -0.9570402 0.2899556 6.1395e-7 -0.9570292 0.2899914 2.06048e-7 -0.9570308 0.2899864 0 -0.9591551 0.2828807 0 -0.9890112 0.1478413 3.37976e-5 -0.9889418 0.1483048 -4.33797e-5 -0.9751138 0.2217049 2.19773e-4 -0.9632175 0.268723 0.001663029 -0.9751006 0.221757 -0.005913972 -0.9586682 0.284465 -0.004392087 -0.962816 0.2701222 0 -0.8155223 0.5787256 0 -0.8155295 0.5787156 0 -0.9603426 0.2788227 -1.08314e-5 -0.7078159 0.706397 -2.73396e-6 -0.7078132 0.7063997 -9.67819e-5 -0.7078746 0.7063382 0 -0.7078321 0.7063808 0 -0.7078295 0.7063834 1.57373e-5 -0.707795 0.706418 -1.25051e-5 -0.7078357 0.7063772 -1.57373e-5 -0.707795 0.706418 1.40683e-5 -0.707836 0.7063769 1.20977e-4 -0.7078746 0.7063382 2.73396e-6 -0.7078132 0.7063997 1.62471e-5 -0.7078152 0.7063977 0 -0.7558396 0.654757 1.35925e-4 -0.7627097 0.646741 -2.65312e-4 -0.8794641 0.4759652 7.00277e-5 -0.8857823 0.464101 -7.77852e-5 -0.9803047 0.1974914 4.23873e-4 -0.9837987 0.1792765 -4.08605e-4 -0.9941815 -0.1077184 0 -0.9923709 -0.1232889 -1.07368e-5 -0.965229 -0.2614061 6.73199e-4 -0.965372 -0.2608764 1.47753e-5 -0.9652277 -0.2614105 -2.98533e-6 -0.9652275 -0.2614116 9.31317e-6 -0.9652301 -0.2614017 0 -0.9652327 -0.2613922 0 -0.9652334 -0.2613899 -9.26939e-6 -0.9652289 -0.2614061 7.65439e-6 -0.9652335 -0.2613896 9.26939e-6 -0.9652289 -0.2614061 -5.98e-6 -0.9652339 -0.2613881 -5.41638e-4 -0.965365 -0.2609027 3.658e-6 -0.9652267 -0.2614147 -7.45055e-6 -0.9652299 -0.2614026 2.98533e-6 -0.9652275 -0.2614116 -1.72378e-5 -0.9652279 -0.26141 0 -0.9971625 -0.07527977 0 -0.9971638 -0.0752632 0 -0.9935327 0.113546 3.00753e-6 -0.9935334 0.1135402 3.55759e-7 -0.9935323 0.1135497 5.23871e-7 -0.9935339 0.1135362 0 -0.9935325 0.1135485 -3.13823e-7 -0.9935328 0.1135452 -1.92784e-6 -0.9935315 0.1135571 3.11583e-7 -0.993533 0.1135438 0 -0.9935331 0.1135433 3.00881e-7 -0.9935296 0.113574 -2.69972e-7 -0.9935329 0.1135451 0 -0.9935322 0.1135505 -1.11207e-6 -0.9935358 0.1135199 6.60713e-7 -0.993532 0.1135528 5.26439e-7 -0.993533 0.1135444 0 -0.9935354 0.1135236 -1.07553e-5 -0.9935316 0.1135563 5.35119e-6 -0.9935306 0.113565 0 -0.9935328 0.1135452 0 -0.993537 0.1135092 1.41029e-6 -0.9935331 0.1135438 9.42888e-7 -0.9935329 0.113545 -0.1371134 -0.9881511 0.06897342 -0.2240136 -0.9738447 0.03800666 -0.19774 -0.9799067 0.02611142 -0.1964518 -0.9801321 0.02734678 -0.221794 -0.9748288 0.02272492 -0.2328862 -0.972155 0.02605241 -0.2357297 -0.9714813 0.02560412 -0.2424012 -0.9697804 0.02771061 -0.3029401 -0.9529664 0.009074151 -0.08207052 -0.9935193 0.07863801 -0.08533072 -0.9934384 0.07615154 -0.0874021 -0.9928298 0.08154702 -0.08740627 -0.9928299 0.08154177 -0.08622902 -0.9932041 0.07816898 -0.04586702 -0.9940588 0.09870827 0.3490892 -0.9171816 0.1921319 0.3658248 -0.9067747 0.2095995 0.1227012 -0.8212678 0.5571928 0.1309627 -0.8140924 0.5657759 0.4854963 -0.8496689 -0.2058067 0.4959021 -0.8507526 -0.1740726 0.4624398 -0.885348 -0.04804658 0.560786 -0.8257265 0.06078624 0.4892749 -0.8558616 0.1676641 0.4792546 -0.8382997 0.2599399 0.4714519 -0.834656 0.2847501 0.4760635 -0.7568301 0.4478524 0.5121196 -0.7180652 0.4712918 0.3914953 -0.6848384 0.6145957 0.3751079 -0.6561474 0.6548012 0.4939566 -0.8694414 0.008859395 0.3390473 -0.7868769 0.5156277 0.328792 -0.7464184 0.5785806 0.3825978 -0.8999222 0.2091868 0.1787851 -0.7910514 0.5850417 0.1909445 -0.8249115 0.5320352 0.4039566 -0.8949177 0.1895827 0.4588691 -0.8636584 0.2086466 0.4583247 -0.8671782 0.1947839 0.4829788 -0.8451899 -0.228879 0.00474298 -0.9569988 0.2900532 0.3867059 -0.9102629 0.1479194 0.3778603 -0.9097974 0.1717279 0.247996 -0.9368035 0.2467738 0.08451455 -0.9751125 0.2049709 0.1277731 -0.9594174 0.2513815 0.4134804 -0.8718847 0.262395 0.3608088 -0.8794108 0.3105702 0.2502458 -0.9301868 0.2685698 0.1238504 -0.9371322 0.326258 0.09352916 -0.9523788 0.290219 0.004844546 -0.9569939 0.2900679 0.004651725 -0.9572983 0.2890647 0.1519669 -0.9339766 0.3234098 0.3601485 -0.9326639 0.0207628 0.3650518 -0.9286803 0.0654999 0.09775674 -0.9585237 0.2677239 0.007411181 -0.9597161 0.2808741 0.002369523 -0.963461 0.2678382 0.007358908 -0.9640958 0.2654526 0.1398794 -0.9657414 0.2185801 0.01981335 -0.9965597 0.08047562 0.2374438 -0.9529673 0.1883451 0.2260502 -0.9607043 0.1610858 0.4392994 -0.8725059 0.2138919 0.3577288 -0.9269788 0.1128731 -0.01237785 -0.974124 0.2256756 0.3323644 -0.9411315 0.06168794 0.4101819 -0.9081208 0.08406788 0.3664221 -0.9279432 0.06823742 0.1947196 -0.9769667 0.08729416 0.3109359 -0.946906 0.08177947 0.3528798 -0.9244741 0.1443036 0.1220421 -0.9755482 0.1827882 0.1120873 -0.9771202 0.1807562 0.1055979 -0.983968 0.1437228 0.06370568 -0.9890234 0.1333204 0.3273013 -0.9255695 0.1902503 0.1147418 -0.8221596 0.5575734 0.3300447 -0.9158448 0.2286894 0.2586191 -0.9455901 0.1974223 0.2511268 -0.932969 0.2578839 0.1512563 -0.9615892 0.2290583 0.1542079 -0.9507288 0.2689509 0.04805105 -0.9662912 0.2529281 0.0545727 -0.9589123 0.2784047 0.1146315 -0.8145273 0.568687 0.08975905 -0.8251601 0.5577222 0.08610785 -0.8135701 0.5750558 0.05154943 -0.8234402 0.5650566 0.05210769 -0.8153167 0.5766658 0.01581734 -0.8206734 0.5711786 0.01789706 -0.8153959 0.5786272 0.1392865 -0.7655023 0.6281765 0.2630004 -0.6920449 0.6722387 0.3297656 -0.6682394 0.6668664 0.341368 -0.6704235 0.658787 0.09711945 -0.6287523 0.771517 0.1919414 -0.7005198 0.6873358 0.001792967 -0.7078084 0.7064022 0.001792967 -0.7078085 0.7064022 0.001792967 -0.7078084 0.7064022 0.09746921 -0.7063673 0.7011027 0.07207423 -0.6483584 0.7579161 0.3289274 -0.7050467 0.6282643 0.3294373 -0.7040065 0.6291629 0.07424819 -0.8042634 0.5896165 0.3477863 -0.9289216 -0.1270809 0.5359128 -0.8387044 0.096812 0.3290753 -0.8209778 0.4665889 0.4111082 -0.7333559 0.5414603 0.3650853 -0.8858138 0.2864381 0.3875309 -0.8605044 0.3306844 0.412959 -0.8957248 0.1647481 0.3623214 -0.9320459 0.00369054 0.4620994 -0.8855235 -0.0480861 0.0631352 -0.9898301 -0.1274772 0.1171465 -0.7631956 0.63546 0.06551975 -0.8875076 0.4561111 0.1172334 -0.9277455 0.3543227 0.08191025 -0.9822226 0.1689068 0.1074983 -0.9864875 0.123639 0.1003763 -0.9914547 -0.08332043 0.2057721 -0.9706919 -0.1241587 0.06339395 -0.9632124 -0.2611572 0.09248447 -0.8969504 -0.4323503 0.2072947 -0.943348 -0.259082 0.3495219 -0.9041883 -0.245516 0.3876075 -0.7997232 -0.4584795 0.4682008 -0.8587419 -0.2082079 0.1219913 -0.9449512 0.3036203 0.004741489 -0.9568411 0.2905733 0.3598226 -0.8773224 0.3175423 0.1171378 -0.9418471 0.3149647 0.1271131 -0.9443067 0.3035245 0.2431434 -0.9181767 0.3127825 0.3601855 -0.8774569 0.3167584 0.3603028 -0.8771365 0.3175112 0.08369761 -0.9779717 -0.1912227 0.02921217 -0.9967385 -0.07522791 0.0232408 -0.9962537 -0.08329772 0.06833493 -0.9931309 -0.09498083 0.07207059 -0.9931399 -0.09208148 0.1048172 -0.9883036 -0.1107682 0.1213686 -0.9871346 -0.104092 0.140931 -0.9824223 -0.1224129 0.2873252 -0.9526032 -0.09995698 0.1122922 -0.9731497 -0.2009237 0.1152541 -0.9733317 -0.198348 0.2736472 -0.9584052 -0.08109754 0.3381692 -0.9389223 -0.0637691 0.3298835 -0.9412817 -0.0718739 0.3187382 -0.9463914 -0.05243617 0.1081028 -0.9751002 -0.1936324 0.09310638 -0.9745272 -0.2040299 0.09386235 -0.9609665 -0.2602562 0.04431968 -0.9657672 -0.2555966 0.1328803 -0.9570841 -0.2575518 0.2318068 -0.9388197 -0.2547217 0.4022462 -0.8841888 -0.2375043 0.3482642 -0.9099569 -0.2251458 0.373447 -0.8964621 -0.2385228 0.3869798 -0.8903706 -0.2397646 0.4120845 -0.8805624 -0.2340863 0.3988823 -0.8851217 -0.2396928 0.4170561 -0.8803792 -0.2258245 0.4647563 -0.8789127 -0.1073039 0.4242613 -0.8827003 -0.2020957 0.3912604 -0.9025546 -0.1797516 0.3570693 -0.912823 -0.1981307 0.3363851 -0.9245491 -0.1790371 0.2662118 -0.9401438 -0.2127463 0.2507133 -0.9488596 -0.1918554 0.1948711 -0.9588547 -0.2064529 0.1823371 -0.9654114 -0.1863704 0.1205078 -0.9706824 -0.2079752 0.4666258 -0.882434 -0.05975538 0.4667241 -0.8823788 -0.05980348 0.4534816 -0.8885948 -0.0689482 0.4425906 -0.8947898 -0.0588634 0.4150859 -0.9065917 -0.07612586 0.406476 -0.911381 -0.06451416 0.3831412 -0.9208029 -0.07297182 0.3756855 -0.9247367 -0.0610125 0.3441409 -0.9359396 -0.07472789 -0.1667311 -0.9859977 0.003053963 0.2311571 -0.9725221 0.02769988 0.1374857 -0.9880357 0.06988006 0.2600389 -0.9651893 0.02809602 0.288877 -0.9573622 -0.002772092 0.2247216 -0.9736459 0.0389108 0.2083789 -0.9779498 0.0138688 0.1606507 -0.9865108 0.03143197 0.1774284 -0.9840166 0.01518356 0.07743245 -0.9950871 0.06169265 0.1128765 -0.9929911 0.03503638 0.1716671 -0.9851393 0.005589127 0.07361674 -0.9953122 0.06272286 0.06660187 -0.9961147 0.05761742 0.06657409 -0.996119 0.0575751 0.04871898 -0.9968839 0.06204015 0.02901083 -0.9978981 0.05794858 0.04193764 -0.9974038 0.05853968 0.04000365 -0.9976271 0.05603682 0.04829668 -0.9969052 0.06202834 0.04996407 -0.9966278 0.06509083 0.01571261 -0.9981755 0.05830067 0.02071976 -0.9981831 0.05657887 0.02998894 -0.9977437 0.06006914 -0.02509617 -0.9978811 0.06002968 -0.0163691 -0.9983066 0.05582112 -0.008174061 -0.9981864 0.05964231 -0.008633315 -0.9981581 0.06005001 0.005027413 -0.998182 0.06006377 0.008645832 -0.9983361 0.05701106 0.01302868 -0.9982905 0.05697637 -0.03182643 -0.9970209 0.07026153 -0.03094023 -0.9982053 0.0512737 -0.04572409 -0.9970639 0.06142425 -0.04182684 -0.9975596 0.05590432 -0.04955106 -0.9968558 0.06183242 -0.04894942 -0.9969367 0.0610032 -0.06333994 -0.9963104 0.05791246 -0.1651583 -0.9859883 0.02344894 -0.176522 -0.9841905 0.01446402 -0.1977745 -0.9800954 0.017277 -0.0729447 -0.9949653 0.06872481 -0.08055645 -0.9956521 0.04677122 -0.08050876 -0.9957009 0.04580569 -0.07643711 -0.9952467 0.06034445 -0.08129715 -0.9943734 0.06791448 -0.08268922 -0.9943661 0.06632292 -0.08211666 -0.9940446 0.07164108 0.2148581 -0.976292 0.02626889 0.2092403 -0.9773342 0.03219509 0.0870462 -0.9929538 0.08040934 0.08565026 -0.9934037 0.07624518 0.04589259 -0.9940317 0.09896951 0.09261673 -0.9925283 0.07943361 0.08577209 -0.9933046 0.07739031 0.08318763 -0.9939663 0.07149124 0.08691787 -0.9937031 0.07070714 0.08057337 -0.9944979 0.06694722 -0.09194439 -0.9957638 -8.09322e-4 -0.09194439 -0.9957638 -8.09029e-4 -0.09194439 -0.9957639 -8.09438e-4 -0.09279084 -0.9956839 -0.00187999 -0.09279119 -0.9956838 -0.001878738 -0.09279096 -0.9956838 -0.001879692 1.4909e-4 0 1 -5.7003e-5 0 1 0.09459853 0 -0.9955155 0.09459853 0 -0.9955156 0.09459853 0 -0.9955155 0.09476804 0 -0.9954994 0.0947681 0 -0.9954994 0.0947681 0 -0.9954994 -0.09451347 0 -0.9955236 -0.09451341 0 -0.9955237 -0.09451359 0 -0.9955236 -0.0942443 0 -0.9955492 -0.09424424 0 -0.9955492 -0.09424424 0 -0.9955492 -0.9708558 0 0.2396646 -0.9708557 0 0.239665 -0.7478474 0 0.6638706 -0.7478464 0 0.6638719 -0.3590212 0 0.9333295 -0.3590208 0 0.9333296 -0.06422311 0 0.9979356 -0.06422024 0 0.9979358 0.2950118 -0.9554936 -1.45554e-4 0.2815796 -0.9594978 -0.008779525 0.279083 -0.9601981 -0.0115056 0.2800002 -0.95995 -0.009795784 0.28146 -0.9595654 -0.003830552 0.3135429 -0.9488465 -0.03716373 0.3330479 -0.9429099 2.55447e-4 0.3383769 -0.940957 -0.01006072 0.3369345 -0.9415196 -0.004000246 0.2814652 -0.9595715 0 0.3093113 -0.9508942 -0.01125305 0.336935 -0.9415279 0 0.2711956 -0.9625099 0.005255281 0.268244 -0.9633505 9.85355e-4 0.3443977 -0.938812 0.004727959 0.3092309 -0.950643 0.0255751 0.3149041 -0.9483741 0.03770983 0.4015144 -0.9032151 0.1516208 0.3112953 -0.9501463 0.01781189 0.276039 -0.9609259 -0.02058839 0.3043982 -0.9517663 0.03850507 -1 -5.74241e-7 0 -0.2419487 0 -0.9702891 -0.241931 0 -0.9702935 -0.66601 0 -0.7459428 -0.6660089 0 -0.7459438 -0.9309084 0 -0.365253 -0.9309057 0 -0.3652597 -0.9974076 0 -0.07195985 -0.9974077 0 -0.07195866 0.9714441 0 -0.2372684 0.9714435 0 -0.2372713 0.7485108 0 -0.6631227 0.7485062 0 -0.6631278 0.354217 0 -0.9351633 0.3542292 0 -0.9351587 0.06094449 0 -0.9981412 0.06086736 0 -0.9981459 0.2419472 0 0.9702894 0.2419468 0 0.9702897 0.6660061 0 0.7459463 0.6660099 0 0.745943 0.9309073 0 0.3652559 0.9309064 0 0.365258 0.9974085 0 0.07194769 0.9974084 0 0.07194894 -0.9714429 0 0.2372736 -0.9714431 0 0.2372727 -0.7485088 0 0.6631249 -0.7485104 0 0.6631231 -0.3542256 0 0.93516 -0.3542258 0 0.9351599 -0.06093519 0 0.9981418 -0.06089323 0 0.9981443 0.1546529 -0.9879689 0 0.154653 -0.9879689 0 0.1924846 -0.9812884 -0.004796981 0.195241 -0.9807547 -0.00110501 0.1207786 -0.9926689 -0.004582107 0.1546155 -0.987727 -0.02212536 0.1486001 -0.9883791 -0.03201448 0.03230041 -0.9881844 -0.1498274 0.1521927 -0.9882346 -0.01515799 0.1846246 -0.9826917 0.01519834 0.1576198 -0.9868552 -0.03567814 0.1164157 -0.9931896 0.004678606 0.113659 -0.9935193 0.001070618 0.1880105 -0.9821557 0.004725635 0.1546148 -0.9877224 0.02233439 0.1602736 -0.9865621 0.0317434 0.2687625 -0.95204 0.1462418 0.1565884 -0.9875513 0.01491701 0.1242238 -0.9921417 -0.01494681 0.1508948 -0.9879324 0.03493398 -0.2419388 0 -0.9702916 -0.241954 0 -0.9702877 -0.6660123 0 -0.7459408 -0.6660101 0 -0.7459428 -0.9309067 0 -0.3652572 -0.9309089 0 -0.3652515 -0.9974085 0 -0.07194823 -0.9974081 0 -0.07195192 0.9714435 0 -0.2372711 0.9714447 0 -0.2372663 0.7485057 0 -0.6631284 0.7485072 0 -0.6631267 0.3542247 0 -0.9351604 0.3542414 0 -0.935154 0.06090712 0 -0.9981434 0.06091052 0 -0.9981433 1 2.34939e-7 0 0.2419475 0 0.9702894 0.2419421 0 0.9702907 0.6660038 0 0.7459483 0.6660101 0 0.7459428 0.930907 0 0.3652567 0.9309075 0 0.3652551 0.9974085 0 0.07194775 0.9974083 0 0.07194846 -0.9714438 0 0.2372695 -0.9714441 0 0.2372686 -0.7485072 0 0.6631268 -0.7485096 0 0.663124 -0.3542234 0 0.9351609 -0.3542302 0 0.9351583 -0.06092578 0 0.9981423 -0.06088513 0 0.9981448 -0.0256834 -0.9996252 0.009477078 0.0336377 -0.9994239 0.004528343 0 -0.9997646 0.02170252 0.005837261 -0.9994984 0.03112584 -0.0225293 -0.9997434 0.002393722 0.001209437 -0.9995294 0.03065365 -0.006305158 -0.999723 0.02267807 0.02568358 -0.9996253 -0.009477198 -0.03363752 -0.9994239 -0.004528284 0 -0.9997645 -0.02170264 -0.005837023 -0.9994984 -0.03112578 0.02252882 -0.9997434 -0.002393782 -0.001208782 -0.9995294 -0.03065294 0.006305098 -0.999723 -0.02267795 -1 -2.92028e-7 0 -0.2419487 0 -0.9702891 -0.2419348 0 -0.9702925 -0.6660093 0 -0.7459434 -0.6660099 0 -0.745943 -0.9309089 0 -0.3652517 -0.930907 0 -0.3652562 -0.9974083 0 -0.07194858 -0.9974084 0 -0.07194894 0.9714434 0 -0.2372715 0.9714426 0 -0.237275 0.7485105 0 -0.6631229 0.748508 0 -0.6631258 0.3542277 0 -0.9351593 0.3542203 0 -0.9351621 0.06093752 0 -0.9981416 0.06091833 0 -0.9981428 0.2419494 0 0.9702889 0.2419487 0 0.9702891 0.6660021 0 0.7459499 0.6660089 0 0.7459438 0.9309076 0 0.3652548 0.9309057 0 0.3652597 0.9974077 0 0.0719583 0.9974076 0 0.07195979 -0.9714441 0 0.2372686 -0.9714435 0 0.2372713 -0.7485095 0 0.6631242 -0.7485062 0 0.6631278 -0.3542292 0 0.9351587 -0.3542236 0 0.9351608 -0.06094056 0 0.9981415 -0.06089246 0 0.9981443 -0.154653 -0.9879689 0 -0.1546529 -0.9879689 0 -0.1924881 -0.9812876 0.004796981 -0.1952355 -0.9807558 0.00110501 -0.1207796 -0.9926688 0.004582107 -0.1546155 -0.987727 0.02212536 -0.1486001 -0.9883791 0.03201448 -0.032296 -0.9881846 0.1498275 -0.1521927 -0.9882346 0.01515799 -0.1846246 -0.9826917 -0.01519834 -0.1576194 -0.9868553 0.03567874 -0.1164153 -0.9931896 -0.004678606 -0.1136586 -0.9935194 -0.001070618 -0.1880105 -0.9821557 -0.004725635 -0.1546142 -0.9877225 -0.02233439 -0.1602746 -0.986562 -0.0317434 -0.2687625 -0.95204 -0.1462418 -0.156584 -0.9875521 -0.01491701 -0.1242251 -0.9921416 0.01494681 -0.1508865 -0.9879336 -0.03493338 0.2419459 0 0.9702898 0.2419435 0 0.9702903 0.6660034 0 0.7459488 0.6660105 0 0.7459424 0.9309069 0 0.3652567 0.9309068 0 0.3652569 0.9974091 0 0.07193958 0.9974089 0 0.07194209 -0.9714443 0 0.237268 -0.9714438 0 0.23727 -0.7485084 0 0.6631253 -0.7485113 0 0.6631221 -0.5037653 0 0.8638406 -0.3606597 -0.02463936 0.9323721 -0.288878 0 0.9573659 -0.06094819 0 0.998141 -0.06088674 0 0.9981448 -0.3057458 -0.9521131 3.41366e-4 -0.3118629 -0.9501271 -3.40654e-4 -0.3015697 -0.9529612 0.03034645 -0.2868461 -0.9579439 0.007934749 -0.3051247 -0.9515831 -0.03726595 -0.2861644 -0.95818 0.001079857 -0.2712792 -0.9624869 -0.00516355 -0.2758409 -0.9612017 -0.001759171 -0.3154448 -0.9484041 -0.03200346 -0.3307576 -0.943678 -0.008434772 -0.3420093 -0.9396948 0.001848638 -0.3465471 -0.9380171 0.005416154 -0.3407078 -0.940165 0.002860724 -0.3209018 -0.9471124 -5.03224e-4 -0.08713316 0 -0.9961968 -0.250122 -0.02831488 -0.9678002 -0.3510857 0.01008027 -0.9362892 -0.6681876 -0.01411467 -0.743859 -0.6662706 -0.01554232 -0.7455481 -0.9300023 0.02003604 -0.3670073 -0.8816136 -0.063277 -0.467711 -0.9965156 0.04096245 -0.07265424 -0.9869313 0 -0.1611422 0.9876237 0 -0.1568427 0.9700644 -0.03530097 -0.2402689 0.9206271 6.59241e-5 -0.390443 0.8440196 -6.56178e-5 -0.5363124 0.7427321 -0.03282696 -0.6687836 0.6828089 0.004263699 -0.7305846 0.3525207 -0.00560373 -0.9357873 0.3720957 -0.01734226 -0.9280324 0.06340873 0.00753349 -0.9979592 0.09795522 0 -0.9951908 1 -1.01083e-6 0 -0.9913472 0 -0.1312664 -0.9913889 -9.3958e-5 -0.1309511 -0.9235972 9.47936e-5 -0.3833646 -0.9237181 0 -0.383073 -0.70711 0 -0.7071036 -0.7071055 0 -0.7071081 -0.2588143 0 -0.9659271 -0.2588311 0 -0.9659226 0.2093335 0 -0.9778443 0.2657385 -0.02429187 -0.963739 0.4552485 0 -0.8903645 0.6081519 0 -0.7938207 0.6082059 1.71716e-5 -0.7937794 0.7928832 -2.41663e-5 -0.6093738 0.7929359 0 -0.6093052 0.9238132 0 -0.3828437 0.9237074 -8.66949e-5 -0.3830988 0.9914214 8.56209e-5 -0.1307045 0.9913843 0 -0.130986 -0.9974089 0 -0.07194167 -0.9876372 -0.01669132 -0.155866 -0.9286857 0.03315073 -0.3693833 -0.8871388 -0.007053077 -0.4614489 -0.6802732 0.009202778 -0.7329008 -0.6619573 0.01931732 -0.7492926 -0.5036283 -1.44551e-5 -0.8639205 -0.334944 4.94731e-5 -0.9422381 -0.2323806 0.0295909 -0.9721747 -0.09795522 0 -0.9951908 0.06094896 0 -0.9981409 0.08611869 -0.003336369 -0.9962793 0.3572669 0.0115602 -0.9339309 0.3566545 0.01190191 -0.9341605 0.6625859 -0.009086966 -0.7489309 0.7523484 0.03496819 -0.6578367 0.8385111 4.55613e-5 -0.5448846 0.918916 -4.37285e-5 -0.3944532 0.9713749 0.0347476 -0.2349967 0.9869313 0 -0.1611422 -0.9998567 0 -0.01692968 -0.9913915 0.004461467 -0.1308547 -0.9601647 -0.03455901 -0.2772898 -0.9236918 0 -0.3831368 -0.7929264 0 -0.6093174 -0.7928865 1.82881e-5 -0.6093695 -0.6079632 -1.71348e-5 -0.7939653 -0.6081373 -8.49659e-5 -0.793832 -0.4525213 3.72076e-5 -0.8917536 -0.2660245 0.02529424 -0.9636344 -0.2065734 0 -0.9784311 0.2588201 0 -0.9659256 0.2588253 0 -0.9659242 0.7071042 0 -0.7071094 0.707103 0 -0.7071107 0.9236919 0 -0.3831361 0.9617937 -0.03271681 -0.2718138 0.9913439 0.004314899 -0.1312202 0.9998568 0 -0.0169298 -0.3799703 0.9249987 0 -0.1280349 0.9917697 0 -0.1285282 0.9917058 2.20317e-4 -0.2555457 0.9667971 0 -0.2555456 0.9667971 0 -0.2555457 0.9667971 0 -0.3799676 0.9249998 0 -0.5715703 0.8205531 0 -0.5721247 0.8201659 0.001156032 -0.7071059 0.7071067 -0.00117582 -0.7071072 0.7071054 -0.001175403 -0.8205522 0.5715706 0.00116527 -0.8201668 0.5721246 0 -0.9249982 0.3799716 0 -0.9250004 0.3799663 0 -0.9917058 0.1285292 0 -0.9917059 0.1285284 0 -0.9249982 -0.3799716 0 -0.9917698 -0.1280343 0 -0.9917058 -0.1285288 2.20234e-4 -0.9667303 -0.2557982 0 -0.9667303 -0.2557982 0 -0.9667304 -0.2557981 0 -0.9250004 -0.3799663 0 -0.8205516 -0.5715725 0 -0.820167 -0.5721232 0.001156508 -0.7071059 -0.7071067 -0.00117582 -0.7071072 -0.7071055 -0.001175701 -0.5715702 -0.8205525 0.001164913 -0.5721254 -0.8201661 0 -0.3799676 -0.9249998 0 -0.3799703 -0.9249987 0 -0.1285271 -0.991706 0 -0.1285284 -0.9917059 0 0.3799703 -0.9249987 0 0.1280349 -0.9917697 0 0.1285282 -0.9917058 2.20317e-4 0.2555457 -0.9667971 0 0.2555456 -0.9667971 0 0.2555457 -0.9667971 0 0.3799676 -0.9249998 0 0.5715703 -0.8205531 0 0.5721247 -0.8201659 0.001156032 0.7071059 -0.7071067 -0.00117582 0.7071072 -0.7071054 -0.001175403 0.8205522 -0.5715706 0.00116527 0.8201668 -0.5721246 0 0.9249982 -0.3799716 0 0.9250004 -0.3799663 0 0.9917058 -0.1285292 0 0.9917059 -0.1285284 0 0.9249982 0.3799716 0 0.9917698 0.1280343 0 0.9917058 0.1285288 2.20234e-4 0.9667303 0.2557982 0 0.9667303 0.2557982 0 0.9667304 0.2557981 0 0.9250004 0.3799663 0 0.8205516 0.5715725 0 0.820167 0.5721232 0.001156508 0.7071059 0.7071067 -0.00117582 0.7071072 0.7071055 -0.001175701 0.5715702 0.8205525 0.001164913 0.5721254 0.8201661 0 0.3799676 0.9249998 0 0.3799703 0.9249987 0 0.1285271 0.991706 0 0.1285284 0.9917059 0 1.57228e-7 0 1 1.50379e-6 0 1 -1.3865e-6 0 1 8.13137e-7 0 1 -6.99073e-7 0 1 -1.34733e-6 0 1 -1.50379e-6 0 1 -1.58776e-7 0 1 -1.39254e-6 0 1 1.68667e-6 0 1 -5.89971e-6 0 1 3.18353e-5 0 1 -1.25294e-6 0 1 -2.55351e-5 0 1 2.58399e-6 0 1 6.99073e-7 0 1 8.07481e-7 0 1 2.5188e-5 0 1 -1.43819e-5 0 1 -6.67689e-7 0 1 1.78035e-6 0 1 1.64982e-6 0 1 1.54496e-5 0 1 -1.11307e-5 0 1 5.69026e-6 0 1 -5.73098e-6 0 1 7.38402e-6 0 1 -1.14441e-5 0 1 1.13274e-5 0 1 -1.5753e-7 0 1 -6.65954e-6 0 1 -1.78578e-6 0 1 1.25294e-6 0 1 -1.40003e-5 0 1 -1.29743e-6 0 1 5.89971e-6 0 1 0.9659262 -0.2588181 0 0.7071086 -0.7071049 0 0.7071105 -0.7071031 0 0.2588216 -0.9659252 0 -0.2588216 -0.9659252 0 -0.7071105 -0.7071031 0 -0.7071086 -0.7071049 0 -0.9659262 -0.2588181 0 -0.9659252 -0.2588216 0 -0.9659252 0.2588216 0 -0.9659262 0.2588181 0 -0.7071086 0.7071049 0 -0.7071105 0.7071031 0 -0.2588147 0.9659271 0 -0.2588216 0.9659252 0 0.2588147 0.9659271 0 0.2588216 0.9659252 0 0.7071105 0.7071031 0 0.7071086 0.7071049 0 0.9659262 0.2588181 0 0.9659252 0.2588216 0 0.9659252 -0.2588216 0 -1.52588e-5 0 1 1.52588e-5 0 1 1.52588e-5 0 1 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 11 3 12 4 9 4 13 4 10 5 14 5 11 5 11 6 14 6 15 6 11 7 15 7 16 7 17 8 18 8 13 8 13 9 18 9 19 9 13 10 19 10 12 10 20 11 21 11 22 11 20 12 22 12 23 12 24 13 25 13 22 13 22 14 25 14 26 14 22 15 26 15 23 15 27 16 28 16 29 16 28 17 30 17 29 17 29 18 30 18 31 18 29 19 31 19 32 19 32 20 31 20 33 20 32 21 33 21 34 21 34 22 33 22 35 22 36 23 37 23 33 23 33 24 37 24 38 24 33 25 38 25 35 25 39 26 40 26 41 26 41 27 42 27 39 27 39 28 42 28 43 28 39 29 43 29 44 29 43 30 45 30 44 30 44 31 45 31 25 31 44 32 25 32 46 32 46 33 25 33 24 33 46 34 24 34 36 34 36 35 24 35 47 35 36 36 47 36 37 36 48 37 49 37 50 37 50 38 49 38 51 38 50 39 51 39 40 39 40 40 51 40 52 40 40 41 52 41 41 41 15 42 53 42 16 42 16 43 53 43 54 43 16 44 54 44 48 44 48 45 54 45 55 45 48 46 55 46 49 46 48 47 56 47 16 47 16 48 56 48 57 48 16 49 57 49 58 49 57 50 59 50 58 50 58 51 59 51 60 51 58 52 60 52 61 52 61 53 62 53 58 53 58 54 62 54 63 54 58 55 63 55 64 55 64 56 63 56 65 56 66 57 67 57 68 57 67 58 69 58 68 58 68 59 69 59 70 59 68 60 70 60 71 60 72 61 73 61 74 61 72 62 74 62 75 62 76 63 75 63 77 63 77 64 75 64 74 64 77 65 74 65 78 65 78 66 74 66 79 66 80 67 81 67 82 67 81 68 83 68 82 68 82 69 83 69 84 69 82 70 84 70 66 70 85 71 86 71 87 71 86 72 88 72 87 72 87 73 88 73 89 73 87 74 89 74 90 74 90 75 89 75 91 75 90 76 91 76 92 76 92 77 91 77 93 77 94 78 95 78 91 78 91 79 95 79 96 79 91 80 96 80 93 80 97 81 98 81 99 81 99 82 98 82 100 82 98 83 101 83 100 83 100 84 101 84 102 84 100 85 102 85 103 85 102 86 104 86 103 86 103 87 104 87 78 87 103 88 78 88 105 88 105 89 78 89 79 89 105 90 79 90 94 90 94 91 79 91 106 91 94 92 106 92 95 92 107 93 108 93 109 93 109 94 108 94 110 94 109 95 110 95 99 95 99 96 110 96 111 96 99 97 111 97 97 97 70 98 112 98 71 98 71 99 112 99 113 99 71 100 113 100 107 100 107 101 113 101 114 101 107 102 114 102 108 102 107 103 115 103 71 103 71 104 115 104 116 104 71 105 116 105 117 105 116 106 118 106 117 106 117 107 118 107 119 107 117 108 119 108 120 108 120 109 121 109 117 109 117 110 121 110 122 110 117 111 122 111 123 111 123 112 122 112 124 112 125 113 126 113 127 113 125 114 127 114 128 114 127 115 129 115 128 115 128 116 129 116 130 116 128 117 130 117 131 117 132 118 133 118 131 118 131 119 133 119 134 119 134 120 135 120 131 120 131 121 135 121 136 121 131 122 136 122 128 122 132 123 131 123 137 123 137 124 131 124 138 124 137 125 138 125 139 125 139 126 138 126 140 126 139 127 140 127 141 127 141 128 142 128 139 128 139 129 142 129 143 129 139 130 143 130 144 130 145 131 146 131 147 131 147 132 146 132 148 132 143 133 149 133 144 133 144 134 149 134 150 134 144 135 150 135 151 135 151 136 150 136 152 136 151 137 152 137 153 137 153 138 154 138 151 138 151 139 154 139 155 139 151 140 155 140 156 140 8 141 151 141 6 141 6 142 151 142 156 142 6 143 156 143 148 143 148 144 156 144 157 144 148 145 157 145 147 145 158 146 159 146 160 146 160 147 159 147 161 147 160 148 161 148 162 148 163 149 164 149 165 149 165 150 164 150 166 150 165 151 166 151 161 151 161 152 166 152 167 152 161 153 167 153 162 153 163 154 165 154 87 154 87 155 165 155 168 155 87 156 168 156 169 156 124 157 85 157 123 157 123 158 85 158 87 158 123 159 87 159 170 159 170 160 87 160 169 160 171 161 172 161 173 161 173 162 172 162 174 162 173 163 174 163 175 163 175 164 174 164 159 164 175 165 159 165 176 165 176 166 159 166 158 166 176 167 158 167 177 167 177 168 178 168 176 168 176 169 178 169 179 169 176 170 179 170 180 170 181 171 171 171 144 171 144 172 171 172 173 172 144 173 173 173 139 173 139 174 173 174 180 174 139 175 180 175 182 175 182 176 180 176 179 176 183 177 117 177 184 177 184 178 117 178 123 178 184 178 123 178 185 178 185 179 123 179 170 179 183 180 186 180 117 180 117 181 186 181 187 181 117 182 187 182 151 182 151 183 187 183 188 183 151 184 188 184 189 184 189 185 190 185 151 185 151 186 190 186 191 186 151 187 191 187 144 187 144 188 191 188 192 188 144 189 192 189 181 189 193 190 194 190 195 190 193 191 195 191 196 191 197 192 198 192 199 192 199 193 198 193 200 193 200 194 201 194 199 194 199 195 201 195 202 195 199 196 202 196 193 196 193 197 202 197 203 197 193 198 203 198 194 198 204 199 205 199 206 199 204 200 206 200 207 200 208 201 209 201 210 201 210 202 209 202 211 202 210 203 211 203 207 203 205 204 212 204 206 204 206 205 212 205 213 205 206 206 213 206 214 206 215 207 216 207 217 207 217 208 216 208 214 208 217 209 214 209 218 209 218 210 214 210 213 210 219 211 220 211 221 211 221 212 222 212 219 212 219 213 222 213 223 213 219 214 223 214 215 214 215 215 223 215 224 215 215 216 224 216 216 216 220 217 225 217 221 217 221 218 225 218 226 218 221 219 226 219 227 219 227 220 226 220 228 220 227 221 228 221 229 221 229 222 228 222 196 222 229 223 196 223 230 223 230 224 196 224 195 224 230 225 195 225 231 225 232 226 233 226 231 226 231 227 233 227 234 227 231 228 234 228 235 228 236 229 237 229 235 229 236 230 235 230 238 230 238 231 235 231 239 231 238 232 239 232 240 232 237 233 241 233 235 233 235 234 241 235 242 236 235 237 242 237 231 237 231 238 242 238 243 238 231 239 243 239 230 239 244 240 245 240 246 240 246 241 245 241 247 241 195 242 248 243 231 244 231 245 248 245 249 245 231 246 249 246 250 246 250 247 251 247 231 247 231 248 251 248 252 248 231 249 252 249 253 249 253 250 252 250 254 250 253 251 254 251 245 251 245 252 254 252 255 252 245 253 255 253 247 253 216 254 256 254 214 254 214 255 256 255 257 255 214 256 257 256 258 256 257 257 259 257 258 257 258 258 259 258 260 258 258 259 260 259 261 259 262 260 261 260 263 260 240 261 239 261 264 261 264 262 239 262 265 262 264 263 265 263 263 263 263 264 265 264 266 264 263 265 266 265 262 265 267 266 268 266 269 266 269 267 268 267 270 267 271 268 272 268 273 268 273 269 272 269 274 269 275 270 276 270 268 270 275 271 268 271 277 271 232 272 245 272 233 272 233 273 245 273 244 273 233 274 244 274 278 274 278 275 244 275 279 275 278 276 279 276 268 276 268 277 279 277 280 277 268 278 280 278 277 278 276 279 281 279 268 279 268 280 281 280 282 280 268 281 282 281 283 281 274 282 270 282 273 282 273 283 270 283 268 283 273 284 268 284 284 284 284 285 268 285 283 285 262 286 285 286 261 286 261 287 285 287 286 287 261 288 286 288 258 288 258 289 286 289 287 289 258 290 287 290 288 290 288 291 287 291 289 291 288 292 289 292 290 292 290 293 291 293 288 293 288 294 291 294 292 294 288 295 292 295 293 295 293 296 294 296 288 296 288 297 294 297 295 297 288 298 295 298 296 298 297 299 298 299 291 299 291 300 298 300 299 300 291 301 299 301 292 301 267 302 269 302 300 302 300 303 269 303 301 303 300 304 301 304 302 304 302 305 301 305 303 305 302 306 303 306 304 306 304 307 303 307 305 307 304 308 305 308 297 308 297 309 305 309 306 309 297 310 306 310 298 310 307 311 308 311 309 311 307 312 310 312 311 312 311 313 310 313 312 313 271 314 273 314 308 314 308 315 273 315 313 315 308 316 313 316 314 316 315 317 309 317 316 317 316 318 309 318 308 318 316 319 308 319 317 319 317 320 308 320 314 320 288 321 318 321 319 321 319 322 318 322 320 322 319 323 320 323 321 323 322 324 323 324 310 324 321 325 324 325 319 325 319 326 324 326 325 326 319 327 325 327 326 327 327 328 312 328 328 328 328 329 312 329 310 329 328 330 310 330 329 330 329 331 310 331 323 331 327 332 330 332 312 332 312 333 330 333 331 333 312 334 331 334 332 334 332 335 331 335 333 335 332 336 333 336 334 336 334 337 333 337 335 337 334 338 335 338 296 338 296 339 335 339 336 339 296 340 336 340 288 340 288 341 336 341 337 341 288 342 337 342 318 342 338 343 339 343 340 343 338 344 340 344 341 344 342 345 343 345 344 345 344 346 343 346 345 346 345 347 346 347 344 347 344 348 346 348 347 348 344 349 347 349 338 349 338 350 347 350 348 350 338 351 348 351 339 351 349 352 350 352 351 352 349 353 351 353 352 353 353 354 354 354 355 354 355 355 354 355 356 355 355 356 356 356 352 356 350 357 357 357 351 357 351 358 357 358 358 358 351 359 358 359 359 359 360 360 361 360 362 360 362 361 361 361 359 361 362 362 359 362 363 362 363 363 359 363 358 363 364 364 365 364 366 364 366 365 367 365 364 365 364 366 367 366 368 366 364 367 368 367 360 367 360 368 368 368 369 368 360 369 369 369 361 369 365 370 370 370 366 370 366 371 370 371 371 371 366 372 371 372 372 372 372 373 371 373 373 373 372 374 373 374 374 374 374 375 373 375 341 375 374 376 341 376 375 376 375 377 341 377 340 377 375 378 340 378 376 378 377 379 378 379 376 379 376 380 378 380 379 380 376 381 379 381 380 381 381 382 382 382 380 382 381 383 380 383 383 383 383 384 380 384 384 384 383 385 384 385 385 385 382 386 386 386 380 386 380 387 386 388 387 389 380 390 387 390 376 390 376 391 387 391 388 391 376 392 388 392 375 392 389 393 390 393 391 393 391 394 390 394 392 394 340 395 393 396 376 397 376 398 393 398 394 398 376 399 394 399 395 399 395 400 396 400 376 400 376 401 396 401 397 401 376 402 397 402 398 402 398 403 397 403 399 403 398 404 399 404 390 404 390 405 399 405 400 405 390 406 400 406 392 406 361 407 401 407 359 407 359 408 401 408 402 408 359 409 402 409 403 409 402 410 404 410 403 410 403 411 404 411 405 411 403 412 405 412 406 412 407 413 406 413 408 413 385 414 384 414 409 414 409 415 384 415 410 415 409 416 410 416 408 416 408 417 410 417 411 417 408 418 411 418 407 418 412 419 413 419 414 419 414 420 413 420 415 420 416 421 417 421 418 421 418 422 417 422 419 422 420 423 421 423 413 423 420 424 413 424 422 424 377 425 390 425 378 425 378 426 390 426 389 426 378 427 389 427 423 427 423 428 389 428 424 428 423 429 424 429 413 429 413 430 424 430 425 430 413 431 425 431 422 431 421 432 426 432 413 432 413 433 426 433 427 433 413 434 427 434 428 434 419 435 415 435 418 435 418 436 415 436 413 436 418 437 413 437 429 437 429 438 413 438 428 438 407 439 430 439 406 439 406 440 430 440 431 440 406 441 431 441 403 441 403 442 431 442 432 442 403 443 432 443 433 443 433 444 432 444 434 444 433 445 434 445 435 445 435 446 436 446 433 446 433 447 436 447 437 447 433 448 437 448 438 448 438 449 439 449 433 449 433 450 439 450 440 450 433 451 440 451 441 451 442 452 443 452 436 452 436 453 443 453 444 453 436 454 444 454 437 454 412 455 414 455 445 455 445 456 414 456 446 456 445 457 446 457 447 457 447 458 446 458 448 458 447 459 448 459 449 459 449 460 448 460 450 460 449 461 450 461 442 461 442 462 450 462 451 462 442 463 451 463 443 463 452 464 453 464 454 464 452 465 455 465 456 465 456 466 455 466 457 466 416 467 418 467 453 467 453 468 418 468 458 468 453 469 458 469 459 469 460 470 454 470 461 470 461 471 454 471 453 471 461 472 453 472 462 472 462 473 453 473 459 473 433 474 463 474 464 474 464 475 463 475 465 475 464 476 465 476 466 476 467 477 468 477 455 477 466 478 469 478 464 478 464 479 469 479 470 479 464 480 470 480 471 480 472 481 457 481 473 481 473 482 457 482 455 482 473 483 455 483 474 483 474 484 455 484 468 484 472 485 475 485 457 485 457 486 475 486 476 486 457 487 476 487 477 487 477 488 476 488 478 488 477 489 478 489 479 489 479 490 478 490 480 490 479 491 480 491 441 491 441 492 480 492 481 492 441 493 481 493 433 493 433 494 481 494 482 494 433 495 482 495 463 495 483 496 484 496 485 496 483 497 485 497 486 497 485 498 487 498 486 498 486 499 487 499 488 499 486 500 488 500 489 500 490 501 491 501 489 501 489 502 491 502 492 502 492 503 493 503 489 503 489 504 493 504 494 504 489 505 494 505 486 505 490 506 489 506 495 506 495 507 489 507 496 507 495 508 496 508 497 508 497 509 496 509 498 509 497 510 498 510 499 510 499 511 500 511 497 511 497 512 500 512 501 512 497 513 501 513 502 513 503 514 484 514 504 514 504 515 505 515 503 515 503 516 505 516 506 516 503 517 506 517 507 517 507 518 506 518 508 518 501 519 509 519 502 519 502 520 509 520 510 520 502 521 510 521 511 521 511 522 510 522 512 522 511 523 512 523 513 523 513 524 514 524 511 524 511 525 514 525 515 525 511 526 515 526 516 526 5 527 511 527 3 527 3 528 511 528 516 528 3 529 516 529 508 529 508 530 516 530 517 530 508 531 517 531 507 531 518 532 519 532 520 532 520 533 519 533 521 533 520 534 521 534 522 534 523 535 524 535 525 535 525 536 524 536 526 536 525 537 526 537 521 537 521 538 526 538 527 538 521 539 527 539 522 539 523 540 525 540 29 540 29 541 525 541 528 541 29 542 528 542 529 542 65 543 27 543 64 543 64 544 27 544 29 544 64 545 29 545 530 545 530 546 29 546 529 546 531 547 532 547 533 547 533 548 532 548 534 548 533 549 534 549 535 549 535 550 534 550 519 550 535 551 519 551 536 551 536 552 519 552 518 552 536 553 518 553 537 553 537 554 538 554 536 554 536 555 538 555 539 555 536 556 539 556 540 556 541 557 531 557 502 557 502 558 531 558 533 558 502 559 533 559 497 559 497 560 533 560 540 560 497 561 540 561 542 561 542 562 540 562 539 562 543 563 58 563 544 563 544 564 58 564 64 564 544 564 64 564 545 564 545 565 64 565 530 565 543 566 546 566 58 566 58 567 546 567 547 567 58 568 547 568 511 568 511 569 547 569 548 569 511 570 548 570 549 570 549 571 550 571 511 571 511 572 550 572 551 572 511 573 551 573 502 573 502 574 551 574 552 574 502 575 552 575 541 575 553 576 554 576 310 576 310 577 554 577 555 577 310 578 555 578 556 578 307 579 309 579 310 579 310 580 309 580 557 580 310 581 557 581 553 581 556 582 558 582 310 582 310 583 558 583 559 583 310 584 559 584 560 584 2 585 1 585 210 585 1 586 561 586 210 586 210 587 561 587 562 587 210 588 562 588 563 588 563 589 564 589 210 589 210 590 564 590 565 590 210 591 565 591 566 591 197 592 208 592 198 592 198 593 208 593 210 593 198 594 210 594 567 594 567 595 210 595 566 595 0 596 2 596 568 596 568 597 2 597 569 597 568 598 569 598 570 598 570 599 569 599 571 599 571 600 569 600 572 600 571 601 572 601 573 601 574 602 575 602 576 602 577 603 578 603 576 603 576 604 578 604 579 604 576 605 579 605 574 605 575 606 580 606 576 606 576 607 580 607 581 607 576 608 581 608 572 608 572 609 581 609 582 609 572 610 582 610 573 610 583 611 584 611 585 611 585 612 584 612 577 612 585 613 577 613 128 613 128 614 577 614 576 614 128 615 576 615 125 615 586 616 82 616 587 616 587 617 82 617 588 617 586 618 589 618 82 618 82 619 589 619 590 619 82 620 590 620 591 620 76 621 80 621 75 621 75 622 80 622 82 622 75 623 82 623 592 623 592 624 82 624 591 624 593 625 594 625 595 625 595 626 594 626 596 626 595 627 596 627 588 627 588 628 596 628 597 628 588 629 597 629 587 629 598 630 599 630 595 630 595 631 599 631 600 631 595 632 600 632 593 632 601 633 602 633 455 633 455 634 602 634 603 634 455 635 603 635 604 635 452 636 454 636 455 636 455 637 454 637 605 637 455 638 605 638 601 638 604 639 606 639 455 639 455 640 606 640 607 640 455 641 607 641 598 641 598 642 607 642 608 642 598 643 608 643 599 643 355 644 609 644 610 644 610 645 611 645 355 645 355 646 611 646 612 646 355 647 612 647 613 647 342 648 353 648 343 648 343 649 353 649 355 649 343 650 355 650 614 650 614 651 355 651 613 651 615 652 616 652 617 652 617 653 616 653 618 653 617 654 618 654 619 654 619 655 618 655 620 655 619 656 620 656 355 656 355 657 620 657 621 657 355 658 621 658 609 658 615 659 617 659 622 659 622 660 617 660 623 660 622 661 623 661 624 661 625 662 626 662 627 662 628 663 629 663 627 663 627 664 629 664 630 664 627 665 630 665 625 665 626 666 631 666 627 666 627 667 631 667 632 667 627 668 632 668 623 668 623 669 632 669 633 669 623 670 633 670 624 670 634 671 635 671 636 671 636 672 635 672 628 672 636 673 628 673 486 673 486 674 628 674 627 674 486 675 627 675 483 675 637 676 13 676 638 676 638 677 13 677 639 677 637 678 640 678 13 678 13 679 640 679 641 679 13 680 641 680 642 680 26 681 17 681 23 681 23 682 17 682 13 682 23 683 13 683 643 683 643 684 13 684 642 684 644 685 645 685 646 685 646 686 645 686 647 686 646 687 647 687 639 687 639 688 647 688 648 688 639 689 648 689 638 689 559 690 649 690 560 690 560 691 649 691 650 691 560 692 650 692 646 692 646 693 650 693 651 693 646 694 651 694 644 694 7 695 652 695 8 695 8 696 652 696 653 696 8 697 653 697 654 697 653 698 655 698 654 698 654 699 655 699 656 699 654 700 656 700 657 700 658 701 659 701 576 701 576 702 659 702 660 702 661 703 662 703 125 703 125 704 662 704 663 704 125 705 663 705 126 705 126 706 663 706 664 706 126 707 664 707 145 707 145 708 664 708 665 708 145 709 665 709 146 709 660 710 666 710 576 710 576 711 666 711 667 711 576 712 667 712 125 712 125 713 667 713 668 713 125 714 668 714 661 714 4 715 669 715 5 715 5 716 669 716 670 716 5 717 670 717 671 717 672 718 673 718 627 718 672 719 627 719 674 719 670 720 675 720 671 720 671 721 675 721 676 721 671 722 676 722 677 722 678 723 679 723 483 723 483 724 679 724 680 724 483 725 680 725 484 725 484 726 680 726 681 726 484 727 681 727 504 727 673 728 682 728 627 728 627 729 682 729 683 729 627 730 683 730 483 730 483 731 683 731 684 731 483 732 684 732 678 732 66 733 68 733 82 733 82 734 68 734 685 734 82 735 685 735 588 735 588 736 685 736 686 736 588 737 686 737 595 737 595 738 686 738 687 738 595 739 687 739 598 739 598 740 687 740 464 740 598 740 464 740 455 740 455 741 464 741 471 741 455 742 471 742 467 742 207 743 206 743 210 743 210 744 206 744 688 744 210 744 688 744 2 744 2 745 688 745 689 745 2 746 689 746 569 746 569 747 689 747 690 747 569 748 690 748 572 748 572 749 690 749 654 749 572 750 654 750 576 750 576 751 654 751 657 751 576 752 657 752 658 752 9 753 11 753 13 753 13 754 11 754 691 754 13 755 691 755 639 755 639 756 691 756 692 756 639 757 692 757 646 757 646 758 692 758 693 758 646 759 693 759 560 759 560 760 693 760 319 760 560 760 319 760 310 760 310 761 319 761 326 761 310 762 326 762 322 762 352 763 351 763 355 763 355 764 351 764 694 764 355 764 694 764 619 764 619 765 694 765 695 765 619 766 695 766 617 766 617 767 695 767 696 767 617 768 696 768 623 768 623 769 696 769 671 769 623 770 671 770 627 770 627 771 671 771 677 771 627 772 677 772 674 772 53 773 697 773 698 773 53 774 698 774 54 774 54 775 698 775 699 775 54 776 699 776 55 776 55 777 699 777 700 777 55 778 700 778 49 778 49 779 700 779 701 779 49 780 701 780 51 780 702 781 703 781 704 781 704 782 705 782 702 782 702 783 705 783 706 783 702 784 706 784 707 784 707 785 706 785 708 785 708 786 709 786 707 786 707 787 709 787 710 787 707 788 710 788 702 788 702 789 710 789 711 789 702 790 712 790 713 790 713 791 712 791 714 791 715 792 703 792 716 792 716 793 703 793 702 793 716 794 702 794 717 794 717 795 702 795 713 795 717 796 713 796 718 796 718 797 713 797 714 797 718 798 714 798 719 798 112 799 720 799 721 799 112 800 721 800 113 800 113 801 721 801 722 801 113 802 722 802 114 802 114 803 722 803 723 803 114 804 723 804 108 804 108 805 723 805 724 805 108 806 724 806 110 806 725 807 726 807 727 807 727 808 726 808 728 808 727 809 728 809 729 809 729 810 728 810 730 810 731 811 732 811 733 811 731 812 733 812 734 812 734 813 733 813 735 813 734 814 735 814 736 814 736 815 735 815 737 815 736 816 737 816 738 816 738 817 737 817 739 817 739 818 737 818 740 818 739 819 740 819 741 819 741 820 740 820 742 820 742 821 740 821 743 821 742 822 743 822 744 822 733 823 732 823 745 823 746 824 747 824 748 824 747 825 749 825 750 825 751 826 746 826 752 826 752 827 746 827 748 827 752 828 748 828 729 828 729 829 748 829 727 829 747 830 750 830 748 830 748 831 750 831 725 831 748 832 725 832 727 832 743 833 753 833 744 833 754 834 755 834 756 834 756 835 755 835 757 835 756 836 757 836 758 836 759 837 760 837 761 837 760 838 759 838 762 838 762 839 759 839 763 839 762 840 763 840 764 840 754 841 764 841 755 841 755 842 764 842 763 842 755 843 763 843 757 843 757 844 763 844 759 844 757 845 759 845 765 845 765 846 759 846 761 846 766 847 764 847 767 847 767 848 764 848 754 848 766 849 768 849 764 849 764 850 768 850 769 850 764 851 769 851 762 851 770 852 771 852 772 852 767 853 773 853 766 853 766 854 773 854 774 854 766 855 774 855 768 855 768 856 774 856 770 856 768 857 770 857 769 857 769 858 770 858 772 858 769 859 772 859 762 859 775 860 776 860 777 860 729 861 730 861 777 861 777 862 730 862 778 862 778 863 779 863 777 863 777 864 779 864 780 864 777 865 780 865 775 865 773 866 729 866 774 866 774 867 729 867 777 867 774 868 777 868 770 868 770 869 777 869 776 869 770 870 776 870 771 870 728 871 726 871 781 871 730 872 728 872 782 872 728 873 781 873 782 873 782 874 781 874 783 874 782 875 783 875 784 875 784 876 783 876 785 876 784 877 785 877 786 877 786 878 785 878 787 878 786 879 787 879 788 879 730 880 782 880 778 880 778 881 782 881 784 881 778 882 784 882 779 882 779 883 784 883 786 883 779 884 786 884 780 884 780 885 786 885 788 885 780 886 788 886 775 886 789 887 790 887 726 887 726 888 725 888 789 888 789 889 725 889 750 889 789 890 750 890 749 890 790 891 789 891 791 891 791 892 789 892 745 892 791 893 745 893 732 893 791 894 732 894 731 894 731 895 792 895 791 895 791 896 792 896 793 896 791 897 793 897 790 897 794 898 795 898 796 898 797 899 798 899 734 899 742 900 799 900 741 900 741 901 799 901 795 901 741 902 795 902 739 902 739 903 795 903 794 903 739 904 794 904 738 904 738 905 794 905 797 905 738 906 797 906 736 906 736 907 797 907 734 907 800 908 793 908 792 908 731 909 734 909 792 909 792 910 734 910 798 910 792 911 798 911 800 911 800 912 798 912 797 912 800 913 797 913 801 913 801 914 797 914 794 914 801 915 794 915 802 915 802 916 794 916 796 916 802 917 796 917 803 917 742 918 744 918 799 918 799 919 744 919 804 919 799 920 804 920 795 920 795 921 804 921 796 921 796 922 804 922 805 922 796 923 805 923 803 923 806 924 807 924 808 924 808 925 809 925 810 925 761 926 806 926 765 926 765 927 806 927 808 927 765 928 808 928 811 928 811 929 808 929 810 929 811 930 810 930 758 930 812 931 813 931 814 931 815 932 812 932 816 932 735 933 733 933 817 933 817 934 733 934 818 934 817 935 818 935 819 935 819 936 818 936 820 936 819 937 820 937 821 937 821 938 820 938 822 938 821 939 823 939 824 939 825 940 740 940 737 940 821 941 824 941 819 941 819 942 824 942 825 942 819 943 825 943 817 943 817 944 825 944 737 944 817 945 737 945 735 945 812 946 814 946 816 946 816 947 814 947 826 947 816 948 826 948 827 948 827 949 826 949 828 949 827 950 828 950 829 950 829 951 830 951 827 951 827 952 830 952 823 952 827 953 823 953 816 953 816 954 823 954 821 954 816 955 821 955 815 955 815 956 821 956 822 956 743 957 740 957 831 957 831 958 740 958 825 958 831 959 825 959 832 959 832 960 825 960 824 960 832 961 824 961 833 961 833 962 824 962 823 962 833 963 823 963 834 963 834 964 823 964 830 964 789 965 749 965 835 965 818 966 733 966 745 966 836 967 837 967 812 967 812 968 837 968 838 968 812 969 838 969 813 969 745 970 789 970 818 970 818 971 789 971 835 971 818 972 835 972 820 972 820 973 835 973 839 973 820 974 839 974 822 974 822 975 839 975 840 975 822 976 840 976 815 976 815 977 840 977 841 977 815 978 841 978 812 978 812 979 841 979 842 979 812 980 842 980 836 980 843 981 844 981 845 981 746 982 751 982 846 982 746 983 846 983 747 983 847 984 843 985 848 986 848 987 843 987 845 987 848 988 845 988 849 988 849 989 845 989 850 989 849 990 850 990 851 990 851 991 850 991 852 991 851 992 852 992 853 992 853 993 852 993 854 993 853 994 854 994 846 994 846 995 854 995 855 995 846 996 855 996 747 996 749 997 747 997 835 997 835 998 747 998 855 998 835 999 855 999 839 999 839 1000 855 1000 854 1000 839 1001 854 1001 840 1001 840 1002 854 1002 852 1002 840 1003 852 1003 841 1003 841 1004 852 1004 850 1004 841 1005 850 1005 842 1005 842 1006 850 1006 845 1006 842 1007 845 1007 836 1007 836 1008 845 1008 844 1008 752 1009 729 1009 773 1009 752 1010 773 1010 751 1010 751 1011 773 1011 856 1011 751 1012 856 1012 846 1012 846 1013 856 1013 857 1013 846 1014 857 1014 853 1014 853 1015 857 1015 858 1015 853 1016 858 1016 851 1016 851 1017 858 1017 859 1017 851 1018 859 1018 849 1018 849 1019 859 1019 860 1019 849 1020 860 1020 848 1020 848 1021 860 1021 861 1021 848 1022 861 1022 847 1022 847 1023 861 1023 862 1023 847 1024 862 1024 863 1024 863 1025 862 1025 864 1025 863 1026 864 1026 865 1026 866 1027 867 1027 862 1027 862 1028 867 1028 868 1028 862 1029 868 1029 864 1029 869 1030 870 1030 866 1030 866 1031 871 1031 869 1031 869 1032 871 1032 872 1032 869 1033 872 1033 873 1033 873 1034 872 1034 874 1034 873 1035 874 1035 875 1035 875 1036 874 1036 876 1036 875 1037 876 1037 877 1037 877 1038 876 1038 878 1038 877 1039 878 1039 879 1039 879 1040 878 1040 880 1040 879 1041 880 1041 881 1041 881 1042 880 1042 882 1042 881 1043 882 1043 883 1043 883 1044 882 1044 756 1044 883 1045 756 1045 758 1045 754 1046 856 1046 767 1046 767 1047 856 1047 773 1047 866 1048 862 1048 871 1048 871 1049 862 1049 861 1049 871 1050 861 1050 872 1050 872 1051 861 1051 860 1051 872 1052 860 1052 874 1052 874 1053 860 1053 859 1053 874 1054 859 1054 876 1054 876 1055 859 1055 858 1055 876 1056 858 1056 878 1056 878 1057 858 1057 857 1057 878 1058 857 1058 880 1058 880 1059 857 1059 856 1059 880 1060 856 1060 882 1060 882 1061 856 1061 754 1061 882 1062 754 1062 756 1062 810 1063 809 1063 884 1063 883 1064 758 1064 810 1064 870 1065 869 1065 885 1065 885 1066 869 1066 873 1066 885 1067 873 1067 875 1067 884 1068 886 1068 875 1068 875 1069 886 1069 887 1069 875 1070 887 1070 885 1070 875 1071 877 1071 884 1071 884 1072 877 1072 879 1072 884 1073 879 1073 810 1073 810 1074 879 1074 881 1074 810 1075 881 1075 883 1075 888 1076 889 1076 890 1076 891 1077 892 1077 893 1077 891 1078 893 1078 894 1078 894 1079 893 1079 895 1079 894 1080 895 1080 896 1080 896 1081 895 1081 888 1081 896 1082 888 1082 897 1082 897 1083 888 1083 890 1083 897 1084 890 1084 634 1084 634 1085 890 1085 898 1085 899 1086 628 1086 898 1086 898 1087 628 1087 635 1087 898 1088 635 1088 634 1088 900 1089 899 1089 901 1089 901 1090 899 1090 898 1090 901 1091 898 1091 889 1091 889 1092 898 1092 890 1092 900 1093 805 1093 902 1093 902 1094 805 1094 804 1094 902 1095 804 1095 903 1095 903 1096 804 1096 904 1096 744 1097 753 1097 804 1097 804 1098 753 1098 905 1098 804 1099 905 1099 904 1099 904 1100 905 1100 906 1100 904 1101 906 1101 907 1101 907 1102 906 1102 908 1102 909 1103 910 1103 631 1103 907 1104 908 1104 910 1104 631 1105 626 1105 909 1105 909 1106 626 1106 625 1106 909 1107 625 1107 911 1107 911 1108 625 1108 630 1108 911 1109 630 1109 912 1109 912 1110 630 1110 629 1110 912 1111 629 1111 913 1111 913 1112 629 1112 628 1112 913 1113 628 1113 899 1113 910 1114 909 1114 907 1114 907 1115 909 1115 911 1115 907 1116 911 1116 904 1116 904 1117 911 1117 912 1117 904 1118 912 1118 903 1118 903 1119 912 1119 913 1119 903 1120 913 1120 902 1120 902 1121 913 1121 899 1121 902 1122 899 1122 900 1122 914 1123 915 1123 916 1123 753 1124 743 1124 831 1124 910 1125 908 1126 917 1127 917 1128 908 1128 906 1128 753 1129 831 1129 905 1129 918 1130 919 1130 916 1130 916 1131 919 1131 920 1131 916 1132 920 1132 914 1132 906 1133 905 1133 917 1133 917 1134 905 1134 831 1134 917 1135 831 1135 921 1135 921 1136 831 1136 832 1136 921 1137 832 1137 922 1137 922 1138 832 1138 833 1138 922 1139 833 1139 923 1139 923 1140 833 1140 834 1140 923 1141 834 1141 916 1141 916 1142 834 1142 830 1142 916 1143 830 1143 918 1143 918 1144 830 1144 829 1144 924 1145 807 1145 925 1145 925 1146 807 1146 806 1146 925 1147 806 1147 926 1147 762 1148 927 1148 760 1148 760 1149 927 1149 761 1149 761 1150 927 1150 806 1150 806 1151 927 1151 928 1151 806 1152 928 1152 926 1152 927 1153 762 1153 772 1153 775 1154 929 1154 776 1154 776 1155 929 1155 930 1155 776 1156 930 1156 931 1156 772 1157 771 1157 927 1157 927 1158 771 1158 776 1158 927 1159 776 1159 932 1159 932 1160 776 1160 931 1160 787 1161 933 1161 788 1161 788 1162 933 1162 934 1162 788 1163 934 1163 775 1163 775 1163 934 1163 929 1163 935 1164 936 1164 937 1164 937 1165 936 1165 938 1165 937 1166 938 1166 939 1166 787 1167 793 1167 933 1167 933 1168 793 1168 939 1168 933 1169 939 1169 940 1169 940 1170 939 1170 938 1170 787 1171 785 1171 793 1171 793 1172 785 1172 783 1172 793 1173 783 1173 790 1173 790 1174 783 1174 781 1174 790 1175 781 1175 726 1175 939 1176 793 1176 800 1176 939 1177 800 1177 941 1177 941 1178 800 1178 801 1178 941 1179 801 1179 942 1179 942 1180 801 1180 802 1180 942 1181 802 1181 943 1181 943 1182 802 1182 803 1182 943 1183 803 1183 944 1183 895 1184 803 1184 888 1184 888 1185 803 1185 805 1185 900 1186 901 1186 805 1186 805 1187 901 1187 889 1187 805 1188 889 1188 888 1188 945 1189 944 1189 892 1189 892 1190 944 1190 803 1190 892 1191 803 1191 893 1191 893 1192 803 1192 895 1192 945 1193 946 1193 944 1193 944 1194 946 1194 947 1194 944 1195 947 1195 948 1195 948 1196 947 1196 949 1196 949 1197 950 1197 948 1197 948 1198 950 1198 951 1198 948 1199 951 1199 952 1199 891 1200 953 1200 892 1200 892 1201 953 1201 945 1201 953 1202 891 1202 954 1202 955 1203 956 1203 957 1203 953 1204 954 1204 957 1204 957 1205 954 1205 958 1205 957 1206 958 1206 955 1206 959 1207 960 1207 956 1207 956 1208 960 1208 961 1208 956 1209 961 1209 957 1209 962 1210 963 1210 964 1210 959 1211 956 1211 963 1211 963 1212 956 1212 965 1212 963 1213 965 1213 964 1213 962 1214 964 1214 966 1214 966 1215 964 1215 967 1215 966 1216 967 1216 968 1216 969 1217 970 1217 971 1217 971 1218 970 1218 972 1218 969 1219 973 1219 970 1219 970 1220 973 1220 974 1220 970 1221 974 1221 968 1221 968 1222 974 1222 975 1222 968 1223 975 1223 966 1223 631 1224 910 1224 632 1224 632 1225 910 1225 917 1225 632 1226 917 1226 633 1226 633 1227 917 1227 624 1227 624 1228 917 1228 921 1228 624 1229 921 1229 622 1229 622 1230 921 1230 922 1230 622 1231 922 1231 615 1231 615 1232 922 1232 923 1232 615 1233 923 1233 616 1233 616 1234 923 1234 618 1234 618 1235 923 1235 916 1235 618 1236 916 1236 620 1236 620 1237 916 1237 915 1237 620 1238 915 1238 621 1238 894 1239 896 1239 976 1239 976 1240 896 1240 897 1240 493 1241 977 1241 494 1241 494 1242 977 1242 978 1242 494 1243 978 1243 486 1243 486 1244 978 1244 976 1244 486 1245 976 1245 636 1245 636 1246 976 1246 897 1246 636 1247 897 1247 634 1247 977 1248 955 1248 978 1248 978 1249 955 1249 958 1249 978 1250 958 1250 976 1250 976 1251 958 1251 954 1251 976 1252 954 1252 894 1252 894 1253 954 1253 891 1253 979 1254 980 1254 981 1254 981 1255 980 1255 982 1255 981 1256 982 1256 983 1256 983 1257 982 1257 935 1257 984 1258 985 1258 986 1258 986 1259 985 1259 987 1259 986 1260 987 1260 988 1260 988 1261 987 1261 989 1261 988 1262 989 1262 990 1262 990 1263 989 1263 991 1263 990 1264 991 1264 992 1264 992 1265 991 1265 993 1265 993 1266 991 1266 994 1266 993 1267 994 1267 995 1267 996 1268 995 1268 994 1268 997 1269 998 1269 999 1269 1000 1270 1001 1270 1002 1270 1002 1271 1001 1271 1003 1271 999 1272 979 1272 981 1272 983 1273 1003 1273 981 1273 981 1274 1003 1274 1001 1274 981 1275 1001 1275 999 1275 999 1276 1001 1276 1000 1276 999 1277 1000 1277 997 1277 984 1278 1004 1278 985 1278 1005 1279 926 1279 928 1279 1006 1280 1007 1280 1008 1280 1008 1281 1007 1281 1009 1281 1006 1282 1010 1282 1007 1282 1007 1283 1010 1283 1011 1283 1007 1284 1011 1284 927 1284 1008 1285 1012 1285 1006 1285 1006 1286 1012 1286 1013 1286 1006 1287 1013 1287 1010 1287 1010 1288 1013 1288 1005 1288 1010 1289 1005 1289 1011 1289 1011 1290 1005 1290 928 1290 1011 1291 928 1291 927 1291 1014 1292 1007 1292 927 1292 1015 1293 1016 1293 1017 1293 1017 1294 1016 1294 1018 1294 1014 1295 927 1295 1019 1295 1019 1296 927 1296 932 1296 1019 1297 932 1297 931 1297 931 1298 1020 1298 1019 1298 1019 1299 1020 1299 1016 1299 1019 1300 1016 1300 1014 1300 1014 1301 1016 1301 1015 1301 1014 1302 1015 1302 1007 1302 1007 1303 1015 1303 1017 1303 1007 1304 1017 1304 1009 1304 1020 1305 931 1305 930 1305 1021 1306 980 1306 1016 1306 1016 1307 980 1307 979 1307 1016 1308 979 1308 1018 1308 1022 1309 1023 1309 1021 1309 1021 1310 1023 1310 1024 1310 1021 1311 1024 1311 980 1311 1016 1312 1020 1312 1021 1312 1021 1313 1020 1313 930 1313 1021 1314 930 1314 1022 1314 1022 1315 930 1315 929 1315 982 1316 980 1316 1024 1316 935 1317 982 1317 1025 1317 982 1318 1024 1318 1025 1318 1025 1319 1024 1319 1023 1319 1025 1320 1023 1320 1026 1320 1026 1321 1023 1321 1022 1321 1026 1322 1022 1322 1027 1322 1027 1323 1022 1323 929 1323 1027 1324 929 1324 934 1324 935 1325 1025 1325 936 1325 936 1326 1025 1326 1026 1326 936 1327 1026 1327 938 1327 938 1328 1026 1328 1027 1328 938 1329 1027 1329 940 1329 940 1330 1027 1330 934 1330 940 1331 934 1331 933 1331 983 1332 1028 1332 1003 1332 1003 1333 1028 1333 1002 1333 995 1334 996 1334 1029 1334 1029 1335 996 1335 1028 1335 1029 1336 1028 1336 937 1336 937 1337 1028 1337 983 1337 937 1338 983 1339 935 1340 1029 1341 937 1341 939 1341 939 1342 1030 1342 1029 1342 1029 1343 1030 1343 993 1343 1029 1344 993 1344 995 1344 1031 1345 1030 1345 939 1345 1032 1346 1033 1346 1034 1346 1034 1347 1033 1347 1035 1347 993 1348 1030 1348 992 1348 992 1349 1030 1349 1031 1349 992 1350 1031 1350 990 1350 990 1351 1031 1351 1035 1351 990 1352 1035 1352 988 1352 988 1353 1035 1353 1033 1353 988 1354 1033 1354 986 1354 943 1355 944 1355 1036 1355 939 1356 941 1356 1031 1356 1031 1357 941 1357 942 1357 1031 1358 942 1358 1035 1358 1035 1359 942 1359 943 1359 1035 1360 943 1360 1034 1360 1034 1361 943 1361 1036 1361 1034 1362 1036 1362 1032 1362 944 1363 948 1363 1036 1363 1036 1364 948 1364 1037 1364 1036 1365 1037 1365 1032 1365 1032 1366 1037 1366 1033 1366 1033 1367 1037 1367 984 1367 1033 1368 984 1368 986 1368 1038 1369 924 1369 925 1369 925 1370 926 1370 1005 1370 1039 1371 1012 1371 1040 1371 925 1372 1005 1372 1038 1372 1038 1373 1005 1373 1039 1373 1038 1374 1039 1374 1041 1374 1041 1375 1039 1375 1040 1375 1041 1376 1040 1376 1042 1376 1043 1377 994 1377 991 1377 1044 1378 1043 1378 1045 1378 1046 1379 1047 1379 1048 1379 1048 1380 1047 1380 1049 1380 1048 1381 1049 1381 1050 1381 1050 1382 1049 1382 1051 1382 1050 1383 1051 1383 1052 1383 1052 1384 1051 1384 1053 1384 1052 1385 1054 1385 1055 1385 1056 1386 1057 1386 1058 1386 1052 1387 1055 1387 1050 1387 1050 1388 1055 1388 1056 1388 1050 1389 1056 1389 1048 1389 1048 1390 1056 1390 1058 1390 1048 1391 1058 1391 1046 1391 1043 1392 991 1392 1045 1392 1045 1393 991 1393 989 1393 1045 1394 989 1394 1059 1394 1059 1395 989 1395 987 1395 1059 1396 987 1396 985 1396 985 1397 1060 1397 1059 1397 1059 1398 1060 1398 1054 1398 1059 1399 1054 1399 1045 1399 1045 1400 1054 1400 1052 1400 1045 1401 1052 1401 1044 1401 1044 1402 1052 1402 1053 1402 1061 1403 1057 1403 1062 1403 1062 1404 1057 1404 1056 1404 1062 1405 1056 1405 1063 1405 1063 1406 1056 1406 1055 1406 1063 1407 1055 1407 1064 1407 1064 1408 1055 1408 1054 1408 1064 1409 1054 1409 1065 1409 1065 1410 1054 1410 1060 1410 1066 1411 1067 1411 1068 1411 1002 1412 1028 1412 1043 1412 1043 1413 1028 1413 996 1413 1043 1414 996 1414 994 1414 1049 1415 1047 1415 1069 1415 1069 1416 1066 1416 1049 1416 1049 1417 1066 1417 1068 1417 1049 1418 1068 1418 1051 1418 1051 1419 1068 1419 1070 1419 1051 1420 1070 1420 1053 1420 1053 1421 1070 1421 1071 1421 1053 1422 1071 1422 1044 1422 1044 1423 1071 1423 1072 1423 1044 1424 1072 1424 1043 1424 1043 1425 1072 1425 1073 1425 1043 1426 1073 1426 1002 1426 1074 1427 1075 1427 1076 1428 997 1429 1000 1429 1077 1429 1074 1430 1076 1430 1078 1430 998 1431 997 1431 1079 1431 1079 1432 997 1432 1077 1432 1079 1433 1077 1433 1080 1433 1080 1434 1077 1434 1081 1434 1080 1435 1081 1435 1082 1435 1082 1436 1081 1436 1083 1436 1082 1437 1083 1437 1084 1437 1084 1438 1083 1438 1085 1438 1084 1439 1085 1439 1076 1439 1076 1440 1085 1440 1086 1440 1076 1441 1086 1441 1078 1441 1067 1442 1078 1442 1068 1442 1068 1443 1078 1443 1086 1443 1068 1444 1086 1444 1070 1444 1070 1445 1086 1445 1085 1445 1070 1446 1085 1446 1071 1446 1071 1447 1085 1447 1083 1447 1071 1448 1083 1448 1072 1448 1072 1449 1083 1449 1081 1449 1072 1450 1081 1450 1073 1450 1073 1451 1081 1451 1077 1451 1073 1452 1077 1452 1002 1452 1002 1453 1077 1453 1000 1453 1087 1454 1088 1454 1089 1454 1087 1455 1089 1455 1075 1455 1075 1456 1089 1456 1090 1456 1075 1457 1090 1457 1076 1457 1076 1458 1090 1458 1091 1458 1076 1459 1091 1459 1084 1459 1084 1460 1091 1460 1092 1460 1084 1461 1092 1461 1082 1461 1082 1462 1092 1462 1093 1462 1082 1463 1093 1463 1080 1463 1080 1464 1093 1464 1094 1464 1080 1465 1094 1465 1079 1465 1079 1466 1094 1466 1095 1466 1079 1467 1095 1467 998 1467 998 1468 1095 1468 1096 1468 998 1469 1096 1469 999 1469 999 1470 1096 1470 1018 1470 999 1471 1018 1471 979 1471 1008 1472 1009 1472 1096 1472 1096 1473 1009 1473 1017 1473 1096 1474 1017 1474 1018 1474 1097 1475 1012 1475 1008 1475 1008 1476 1098 1476 1097 1476 1097 1477 1098 1477 1099 1477 1097 1478 1099 1478 1100 1478 1100 1479 1099 1479 1101 1479 1100 1480 1101 1480 1102 1480 1102 1481 1101 1481 1103 1481 1102 1482 1103 1482 1104 1482 1104 1483 1103 1483 1105 1483 1104 1484 1105 1484 1106 1484 1106 1485 1105 1485 1107 1485 1106 1486 1107 1486 1108 1486 1108 1487 1107 1487 1109 1487 1108 1488 1109 1488 1110 1488 1110 1489 1109 1489 1111 1489 1110 1490 1111 1490 1112 1490 1113 1491 1090 1491 1114 1491 1114 1492 1090 1492 1089 1492 1008 1493 1096 1493 1098 1493 1098 1494 1096 1494 1095 1494 1098 1495 1095 1495 1099 1495 1099 1496 1095 1496 1094 1496 1099 1497 1094 1497 1101 1497 1101 1498 1094 1498 1093 1498 1101 1499 1093 1499 1103 1499 1103 1500 1093 1500 1092 1500 1103 1501 1092 1501 1105 1501 1105 1502 1092 1502 1091 1502 1105 1503 1091 1503 1107 1503 1107 1504 1091 1504 1090 1504 1107 1505 1090 1505 1109 1505 1109 1506 1090 1506 1113 1506 1109 1507 1113 1507 1111 1507 1115 1508 1116 1508 1117 1508 1012 1509 1097 1509 1040 1509 1040 1510 1097 1510 1100 1510 1040 1511 1100 1511 1102 1511 1110 1512 1112 1512 1115 1512 1110 1513 1115 1513 1108 1513 1108 1514 1115 1514 1106 1514 1106 1515 1115 1515 1117 1515 1106 1516 1117 1516 1104 1516 1104 1517 1117 1517 1118 1517 1104 1518 1118 1518 1102 1518 1102 1519 1118 1519 1042 1519 1102 1520 1042 1520 1040 1520 1119 1521 950 1521 949 1521 945 1522 953 1522 1120 1522 945 1523 1120 1523 946 1523 946 1524 1120 1524 1121 1524 946 1525 1121 1525 947 1525 947 1526 1121 1526 1122 1526 947 1527 1122 1527 949 1527 949 1528 1122 1528 21 1528 949 1529 21 1529 1119 1529 951 1530 1123 1530 952 1530 952 1531 1123 1531 1124 1531 1119 1532 21 1532 20 1532 23 1533 1124 1533 20 1533 20 1534 1124 1534 1123 1534 20 1535 1123 1535 1119 1535 1119 1536 1123 1536 951 1536 1119 1537 951 1537 950 1537 1037 1538 948 1538 952 1538 952 1539 1125 1539 1037 1539 1037 1540 1125 1540 1126 1540 1037 1541 1126 1541 1127 1541 1128 1542 1129 1542 1130 1542 1128 1543 1130 1543 1127 1543 1127 1544 1130 1544 1131 1544 1127 1545 1131 1545 1037 1545 1037 1546 1131 1546 1004 1546 1037 1547 1004 1547 984 1547 1132 1548 1133 1548 1129 1548 640 1549 637 1549 1133 1549 1129 1550 1128 1550 1132 1550 1132 1551 1128 1551 1127 1551 1132 1552 1127 1552 1134 1552 1134 1553 1127 1553 1126 1553 1134 1554 1126 1554 1135 1554 1135 1555 1126 1555 1125 1555 1135 1556 1125 1556 1136 1556 1136 1557 1125 1557 952 1557 1136 1558 952 1558 1124 1558 1133 1559 1132 1559 640 1559 640 1560 1132 1560 1134 1560 640 1561 1134 1561 641 1561 641 1562 1134 1562 1135 1562 641 1563 1135 1563 642 1563 642 1564 1135 1564 1136 1564 642 1565 1136 1565 643 1565 643 1566 1136 1566 1124 1566 643 1567 1124 1567 23 1567 1137 1568 1061 1568 1062 1568 1129 1569 1133 1570 1138 1571 1004 1572 1131 1572 1138 1572 1138 1573 1131 1573 1130 1573 1138 1574 1130 1574 1129 1574 1139 1575 1140 1575 1141 1575 1141 1576 1140 1576 1142 1576 1137 1577 1062 1577 1143 1577 1142 1578 1143 1578 1141 1578 1141 1579 1143 1579 1062 1579 1141 1580 1062 1580 1144 1580 1144 1581 1062 1581 1063 1581 1144 1582 1063 1582 1145 1582 1145 1583 1063 1583 1064 1583 1145 1584 1064 1584 1146 1584 1146 1585 1064 1585 1065 1585 1146 1586 1065 1586 1138 1586 1138 1587 1065 1587 1060 1587 1138 1588 1060 1588 1004 1588 1004 1589 1060 1589 985 1589 1138 1590 1133 1590 637 1590 1145 1591 644 1591 1144 1591 1144 1592 644 1592 651 1592 1144 1593 651 1593 1141 1593 1141 1594 651 1594 650 1594 1141 1595 650 1595 1139 1595 1139 1596 650 1596 649 1596 1139 1597 649 1597 559 1597 637 1598 638 1598 1138 1598 1138 1599 638 1599 648 1599 1138 1600 648 1600 1146 1600 1146 1601 648 1601 647 1601 1146 1602 647 1602 1145 1602 1145 1603 647 1603 645 1603 1145 1604 645 1604 644 1604 490 1605 1147 1605 491 1605 24 1606 22 1606 1148 1606 1148 1607 1121 1607 1120 1607 22 1608 21 1608 1148 1608 1148 1609 21 1609 1122 1609 1148 1610 1122 1610 1121 1610 47 1611 1149 1611 37 1611 37 1612 1149 1612 1150 1612 37 1613 1150 1613 38 1613 963 1614 34 1614 1150 1614 1150 1615 34 1615 35 1615 1150 1616 35 1616 38 1616 963 1617 962 1617 34 1617 34 1618 962 1618 966 1618 34 1619 966 1619 32 1619 32 1620 966 1620 975 1620 973 1621 524 1621 974 1621 974 1622 524 1622 523 1622 974 1623 523 1623 975 1623 975 1624 523 1624 29 1624 975 1625 29 1625 32 1625 969 1626 527 1626 973 1626 973 1627 527 1627 526 1627 973 1628 526 1628 524 1628 538 1629 537 1629 972 1629 972 1630 537 1630 518 1630 972 1631 518 1631 971 1631 971 1632 518 1632 520 1632 971 1633 520 1633 969 1633 969 1634 520 1634 522 1634 969 1635 522 1635 527 1635 538 1636 972 1636 539 1636 539 1637 972 1637 970 1637 539 1638 970 1638 542 1638 542 1639 970 1639 968 1639 542 1640 968 1640 497 1640 497 1641 968 1641 967 1641 497 1642 967 1642 495 1642 491 1643 1147 1643 492 1643 492 1644 1147 1644 1151 1644 492 1645 1151 1645 493 1645 495 1646 967 1646 490 1646 490 1647 967 1647 964 1647 490 1648 964 1648 1147 1648 1147 1649 964 1649 965 1649 1147 1650 965 1650 1151 1650 1151 1651 965 1651 956 1651 1151 1652 956 1652 955 1652 47 1653 24 1653 1149 1653 1149 1654 24 1654 1148 1654 1149 1655 1148 1655 957 1655 957 1656 1148 1656 1120 1656 957 1657 1120 1657 953 1657 957 1658 961 1658 1149 1658 1149 1659 961 1659 960 1659 1149 1660 960 1660 1150 1660 1150 1661 960 1661 959 1661 1150 1662 959 1662 963 1662 258 1663 288 1663 1152 1663 688 1663 206 1663 1152 1663 1152 1664 206 1664 214 1664 1152 1663 214 1663 258 1663 654 1663 690 1663 1152 1663 1152 1665 690 1665 689 1665 1152 1666 689 1666 688 1666 117 1663 151 1663 1152 1663 1152 1663 151 1663 8 1663 1152 1667 8 1667 654 1667 685 1663 68 1663 1152 1663 1152 1668 68 1668 71 1668 1152 1663 71 1663 117 1663 464 1663 687 1663 1152 1663 1152 1669 687 1669 686 1669 1152 1670 686 1670 685 1670 359 1663 1153 1663 1152 1663 1152 1663 1153 1663 433 1663 1152 1671 433 1671 464 1671 695 1672 694 1672 1152 1672 1152 1663 694 1663 351 1663 1152 1671 351 1671 359 1671 5 1663 671 1663 1152 1663 1152 1671 671 1671 696 1671 1152 1670 696 1670 695 1670 16 1663 58 1663 1152 1663 1152 1663 58 1663 511 1663 1152 1663 511 1663 5 1663 692 1663 691 1663 1152 1663 1152 1664 691 1664 11 1664 1152 1667 11 1667 16 1667 288 1663 319 1663 1152 1663 1152 1663 319 1663 693 1663 1152 1666 693 1666 692 1666 1154 1673 1155 1674 1156 1675 1156 1676 1155 1677 1157 1678 536 1679 1154 1679 535 1679 535 1680 1154 1680 1156 1680 535 1679 1156 1679 533 1679 533 1681 1156 1681 1157 1681 533 1682 1157 1683 1155 1684 533 1685 1155 1686 540 1687 540 1688 1155 1689 1154 1690 540 1691 1154 1692 536 1693 9 1694 1158 1694 1159 1694 9 1695 1159 1695 10 1695 10 1696 1159 1696 1160 1696 10 1697 1160 1697 14 1697 14 1698 1160 1698 1161 1698 14 1699 1161 1699 15 1699 15 1700 1161 1700 697 1700 15 1701 697 1701 53 1701 1162 1702 1163 1702 1164 1702 1164 1703 1163 1703 1165 1703 1165 1704 1166 1704 1164 1704 1164 1705 1166 1705 1167 1705 1164 1706 1167 1706 1168 1706 1169 1707 1162 1707 1170 1707 1170 1708 1162 1708 1164 1708 1170 1709 1164 1709 1171 1709 1171 1710 1164 1710 1172 1710 1168 1711 701 1711 1164 1711 1164 1712 701 1712 1158 1712 1164 1713 1158 1713 1172 1713 699 1714 1173 1714 700 1714 700 1715 1173 1715 701 1715 1159 1716 1158 1716 1160 1716 1160 1717 1158 1717 701 1717 1160 1718 701 1718 1161 1718 1161 1719 701 1719 1173 1719 1161 1720 1173 1720 697 1720 697 1721 1173 1721 699 1721 697 1722 699 1722 698 1722 1174 1723 50 1723 1175 1723 1175 1724 50 1724 40 1724 1175 1723 40 1723 39 1723 33 1725 1176 1725 1177 1725 33 1726 1177 1726 36 1726 36 1727 1177 1727 1178 1727 36 1728 1178 1728 46 1728 46 1729 1178 1729 1179 1729 46 1730 1179 1730 44 1730 44 1731 1179 1731 1175 1731 44 1732 1175 1732 39 1732 27 1733 1180 1733 1181 1733 27 1734 1181 1734 28 1734 28 1735 1181 1735 1182 1735 28 1736 1182 1736 30 1736 30 1737 1182 1737 1183 1737 30 1738 1183 1738 31 1738 31 1739 1183 1739 1176 1739 31 1740 1176 1740 33 1740 63 1741 1184 1741 65 1741 65 1741 1184 1741 1180 1741 65 1741 1180 1741 27 1741 59 1742 1185 1742 1186 1742 59 1743 1186 1743 60 1743 60 1744 1186 1744 1187 1744 60 1745 1187 1745 61 1745 61 1746 1187 1746 1188 1746 61 1747 1188 1747 62 1747 62 1748 1188 1748 1184 1748 62 1749 1184 1749 63 1749 50 1750 1174 1750 1189 1750 50 1751 1189 1751 48 1751 48 1752 1189 1752 1190 1752 48 1753 1190 1753 56 1753 56 1754 1190 1754 1191 1754 56 1755 1191 1755 57 1755 57 1756 1191 1756 1185 1756 57 1757 1185 1757 59 1757 1184 1758 1174 1758 1180 1758 1180 1759 1174 1759 1175 1759 1178 1760 1192 1760 1179 1760 1179 1761 1192 1761 1175 1761 1181 1762 1180 1762 1182 1762 1182 1763 1180 1763 1175 1763 1182 1764 1175 1764 1183 1764 1183 1765 1175 1765 1192 1765 1183 1766 1192 1766 1176 1766 1176 1767 1192 1767 1178 1767 1176 1768 1178 1768 1177 1768 1187 1769 1193 1769 1188 1769 1188 1770 1193 1770 1184 1770 1189 1771 1174 1771 1190 1771 1190 1772 1174 1772 1184 1772 1190 1773 1184 1773 1191 1773 1191 1774 1184 1774 1193 1774 1191 1775 1193 1775 1185 1775 1185 1776 1193 1776 1187 1776 1185 1777 1187 1777 1186 1777 530 1723 1194 1723 545 1723 545 1723 1194 1723 1195 1723 545 1723 1195 1723 544 1723 521 1778 1196 1778 1197 1778 521 1779 1197 1779 525 1779 525 1780 1197 1780 1198 1780 525 1781 1198 1781 528 1781 528 1782 1198 1782 1199 1782 528 1783 1199 1783 529 1783 529 1784 1199 1784 1194 1784 529 1785 1194 1785 530 1785 531 1786 1200 1786 1201 1786 531 1787 1201 1787 532 1787 532 1788 1201 1788 1202 1788 532 1789 1202 1789 534 1789 534 1790 1202 1790 1203 1790 534 1791 1203 1791 519 1791 519 1792 1203 1792 1196 1792 519 1793 1196 1793 521 1793 1200 1741 531 1741 1204 1741 1204 1794 531 1794 541 1794 1204 1741 541 1741 552 1741 548 1795 1205 1795 1206 1795 548 1796 1206 1796 549 1796 549 1797 1206 1797 1207 1797 549 1798 1207 1798 550 1798 550 1799 1207 1799 1208 1799 550 1800 1208 1800 551 1800 551 1801 1208 1801 1204 1801 551 1802 1204 1802 552 1802 544 1803 1195 1803 1209 1803 544 1804 1209 1804 543 1804 543 1805 1209 1805 1210 1805 543 1806 1210 1806 546 1806 546 1807 1210 1807 1211 1807 546 1808 1211 1808 547 1808 547 1809 1211 1809 1205 1809 547 1810 1205 1810 548 1810 1194 1811 1200 1811 1195 1811 1195 1811 1200 1811 1204 1811 1208 1812 1207 1812 1206 1812 1209 1813 1195 1813 1210 1813 1210 1814 1195 1814 1204 1814 1210 1815 1204 1815 1211 1815 1211 1816 1204 1816 1208 1816 1211 1817 1208 1817 1205 1817 1205 1818 1208 1818 1206 1818 1199 1819 1198 1819 1197 1819 1201 1820 1200 1820 1202 1820 1202 1821 1200 1821 1194 1821 1202 1822 1194 1822 1203 1822 1203 1823 1194 1823 1199 1823 1203 1824 1199 1824 1196 1824 1196 1825 1199 1825 1197 1825 1212 1723 510 1723 1213 1723 1213 1826 510 1826 509 1826 1213 1723 509 1723 501 1723 496 1827 1214 1827 1215 1827 496 1828 1215 1828 498 1828 498 1829 1215 1829 1216 1829 498 1830 1216 1830 499 1830 499 1831 1216 1831 1217 1831 499 1832 1217 1832 500 1832 500 1833 1217 1833 1213 1833 500 1834 1213 1834 501 1834 485 1835 1218 1835 1219 1835 485 1836 1219 1836 487 1836 487 1837 1219 1837 1220 1837 487 1838 1220 1838 488 1838 488 1839 1220 1839 1221 1839 488 1840 1221 1840 489 1840 489 1841 1221 1841 1214 1841 489 1842 1214 1842 496 1842 503 1741 1222 1741 484 1741 484 1741 1222 1741 1218 1741 484 1741 1218 1741 485 1741 515 1843 1223 1843 1224 1843 515 1844 1224 1844 516 1844 516 1845 1224 1845 1225 1845 516 1846 1225 1846 517 1846 517 1847 1225 1847 1226 1847 517 1848 1226 1848 507 1848 507 1849 1226 1849 1222 1849 507 1850 1222 1850 503 1850 510 1851 1212 1851 1227 1851 510 1852 1227 1852 512 1852 512 1853 1227 1853 1228 1853 512 1854 1228 1854 513 1854 513 1855 1228 1855 1229 1855 513 1856 1229 1856 514 1856 514 1857 1229 1857 1223 1857 514 1858 1223 1858 515 1858 1213 1859 1218 1859 1212 1859 1212 1860 1218 1860 1222 1860 1225 1861 1230 1861 1226 1861 1226 1862 1230 1862 1222 1862 1227 1863 1212 1863 1228 1863 1228 1864 1212 1864 1222 1864 1228 1865 1222 1865 1229 1865 1229 1866 1222 1866 1230 1866 1229 1867 1230 1867 1223 1867 1223 1868 1230 1868 1225 1868 1223 1869 1225 1869 1224 1869 1216 1870 1231 1870 1217 1870 1217 1871 1231 1871 1213 1871 1219 1872 1218 1872 1220 1872 1220 1873 1218 1873 1213 1873 1220 1874 1213 1874 1221 1874 1221 1875 1213 1875 1231 1875 1221 1876 1231 1876 1214 1876 1214 1877 1231 1877 1216 1877 1214 1878 1216 1878 1215 1878 670 1879 718 1879 719 1879 670 1880 719 1880 675 1880 675 1881 719 1881 714 1881 675 1882 714 1882 676 1882 676 1883 714 1883 712 1883 676 1884 712 1884 677 1884 677 1885 712 1885 702 1885 677 1886 702 1886 674 1886 506 1887 703 1887 715 1887 506 1888 715 1888 508 1888 508 1889 715 1889 716 1889 508 1890 716 1890 3 1890 3 1891 716 1891 4 1891 4 1892 716 1892 717 1892 4 1893 717 1893 669 1893 669 1894 717 1894 718 1894 669 1895 718 1895 670 1895 865 1896 1232 1896 1233 1896 1233 1897 1232 1897 1234 1897 1233 1898 1234 1898 1235 1898 1235 1899 1234 1899 1236 1899 1237 1900 829 1900 1238 1900 1238 1901 829 1901 828 1901 1238 1902 828 1902 1239 1902 1239 1903 828 1903 826 1903 1239 1904 826 1904 1240 1904 1240 1905 826 1905 814 1905 1240 1906 814 1906 1241 1906 1241 1907 814 1907 1242 1907 1242 1908 814 1908 813 1908 1242 1909 813 1909 1243 1909 838 1910 1243 1910 813 1910 843 1911 847 1911 863 1911 844 1912 1244 1912 836 1912 836 1913 1244 1913 1245 1913 863 1914 865 1914 1233 1914 1235 1915 1245 1915 1233 1915 1233 1916 1245 1916 1244 1916 1233 1917 1244 1917 863 1917 863 1918 1244 1918 844 1918 863 1919 844 1919 843 1919 1237 1920 918 1920 829 1920 1246 1921 1247 1921 1248 1921 1249 1922 1250 1922 866 1922 866 1923 1250 1923 867 1923 1249 1924 1251 1924 1250 1924 1250 1925 1251 1925 1252 1925 1250 1926 1252 1926 1253 1926 866 1927 870 1927 1249 1927 1249 1928 870 1928 1254 1928 1249 1929 1254 1929 1251 1929 1251 1930 1254 1930 1246 1930 1251 1931 1246 1931 1252 1931 1252 1932 1246 1932 1248 1932 1252 1933 1248 1933 1253 1933 1255 1934 1250 1934 1253 1934 1256 1935 1257 1935 868 1935 868 1936 1257 1936 864 1936 1255 1937 1253 1937 1258 1937 1258 1938 1253 1938 1259 1938 1258 1939 1259 1939 1260 1939 1260 1940 1261 1940 1258 1940 1258 1941 1261 1941 1257 1941 1258 1942 1257 1942 1255 1942 1255 1943 1257 1943 1256 1943 1255 1944 1256 1944 1250 1944 1250 1945 1256 1945 868 1945 1250 1946 868 1946 867 1946 1261 1947 1260 1948 1262 1949 1263 1950 1232 1950 1257 1950 1257 1951 1232 1951 865 1951 1257 1952 865 1952 864 1952 1264 1953 1265 1953 1263 1953 1263 1954 1265 1954 1266 1954 1263 1955 1266 1955 1232 1955 1257 1956 1261 1956 1263 1956 1263 1957 1261 1957 1262 1957 1263 1958 1262 1958 1264 1958 1264 1959 1262 1959 1267 1959 1234 1960 1232 1960 1266 1960 1236 1961 1234 1961 1268 1961 1234 1962 1266 1962 1268 1962 1268 1963 1266 1963 1265 1963 1268 1964 1265 1964 1269 1964 1269 1965 1265 1965 1264 1965 1269 1966 1264 1966 1270 1966 1270 1967 1264 1967 1267 1967 1270 1968 1267 1968 1271 1968 1236 1969 1268 1969 1272 1969 1272 1970 1268 1970 1269 1970 1272 1971 1269 1971 1273 1971 1273 1972 1269 1972 1270 1972 1273 1973 1270 1973 1274 1973 1274 1974 1270 1974 1271 1974 1274 1975 1271 1975 1275 1975 1235 1976 837 1976 1245 1976 1245 1977 837 1977 836 1977 1243 1978 838 1978 1276 1978 1276 1979 838 1979 837 1979 1276 1980 837 1980 1277 1980 1277 1981 837 1981 1235 1981 1277 1982 1235 1982 1236 1982 1276 1983 1277 1983 1278 1983 1278 1984 1279 1984 1276 1984 1276 1985 1279 1985 1242 1985 1276 1986 1242 1986 1243 1986 1280 1987 1279 1987 1278 1987 1281 1988 1282 1988 1283 1988 1283 1989 1282 1989 1284 1989 1242 1990 1279 1990 1241 1990 1241 1991 1279 1991 1280 1991 1241 1992 1280 1992 1240 1992 1240 1993 1280 1993 1284 1993 1240 1994 1284 1994 1239 1994 1239 1995 1284 1995 1282 1995 1239 1996 1282 1996 1238 1996 1285 1997 1286 1997 1287 1997 1278 1998 1288 1998 1280 1998 1280 1999 1288 1999 1289 1999 1280 2000 1289 2000 1284 2000 1284 2001 1289 2001 1285 2001 1284 2002 1285 2002 1283 2002 1283 2003 1285 2003 1287 2003 1283 2004 1287 2004 1281 2004 1286 2005 1290 2005 1287 2005 1287 2006 1290 2006 1291 2006 1287 2007 1291 2007 1281 2007 1281 2008 1291 2008 1282 2008 1282 2009 1291 2009 1237 2009 1282 2010 1237 2010 1238 2010 1292 2011 1293 2011 1294 2011 1294 2012 1247 2012 1246 2012 1295 2013 870 2013 885 2013 1294 2014 1246 2014 1292 2014 1292 2015 1246 2015 1295 2015 1292 2016 1295 2017 1296 2018 1296 2019 1295 2019 885 2019 1296 2020 885 2020 887 2020 1297 2021 1298 2021 1299 2021 1300 2022 1301 2022 1302 2022 1300 2023 1302 2023 1303 2023 1303 2024 1302 2024 1304 2024 1303 2025 1304 2025 1305 2025 1305 2026 1304 2026 1306 2026 1305 2027 1306 2027 1299 2027 1299 2028 1306 2028 345 2028 1299 2029 345 2029 1297 2029 613 2030 1307 2030 614 2030 614 2031 1307 2031 1308 2031 614 2032 1308 2032 343 2032 343 2033 1308 2033 1297 2033 343 2034 1297 2034 345 2034 1307 2035 1309 2035 1308 2035 1308 2036 1309 2036 1310 2036 1308 2037 1310 2037 1297 2037 1297 2038 1310 2038 1298 2038 1291 2039 1290 2039 1309 2039 1309 2040 1311 2040 1291 2040 1291 2041 1311 2041 1312 2041 1291 2042 1312 2042 1313 2042 1314 2043 914 2043 920 2043 1314 2044 920 2044 1313 2044 1313 2045 920 2045 919 2045 1313 2046 919 2046 1291 2046 1291 2047 919 2047 918 2047 1291 2048 918 2048 1237 2048 1315 2049 915 2049 914 2049 609 2050 621 2050 915 2050 914 2051 1314 2051 1315 2051 1315 2052 1314 2052 1313 2052 1315 2053 1313 2053 1316 2053 1316 2054 1313 2054 1312 2054 1316 2055 1312 2055 1317 2055 1317 2056 1312 2056 1311 2056 1317 2057 1311 2057 1318 2057 1318 2058 1311 2058 1309 2058 1318 2059 1309 2059 1307 2059 915 2060 1315 2060 609 2060 609 2061 1315 2061 1316 2061 609 2062 1316 2062 610 2062 610 2063 1316 2063 1317 2063 610 2064 1317 2064 611 2064 611 2065 1317 2065 1318 2065 611 2066 1318 2066 612 2066 612 2067 1318 2067 1307 2067 612 2068 1307 2068 613 2068 1293 2069 1319 2069 1294 2069 1294 2070 1319 2070 1320 2070 1294 2071 1320 2071 1247 2071 1321 2072 1253 2072 1322 2072 1322 2073 1253 2073 1323 2073 1323 2074 1253 2074 1320 2074 1320 2075 1253 2075 1248 2075 1320 2076 1248 2076 1247 2076 1253 2077 1321 2077 1324 2077 1325 2078 1267 2078 1326 2078 1326 2079 1267 2079 1262 2079 1326 2080 1262 2080 1260 2080 1324 2081 1327 2081 1253 2081 1253 2082 1327 2082 1326 2082 1253 2083 1326 2083 1259 2083 1259 2084 1326 2084 1260 2084 1328 2085 1275 2085 1329 2085 1329 2086 1275 2086 1271 2086 1329 2087 1271 2087 1325 2087 1325 2088 1271 2088 1267 2088 1330 2089 1331 2089 1332 2089 1330 2090 1332 2090 1333 2090 1333 2091 1332 2091 1334 2091 1333 2092 1334 2092 1335 2092 1236 2093 1272 2093 1277 2093 1277 2094 1272 2094 1273 2094 1277 2095 1273 2095 1278 2095 1273 2096 1274 2096 1278 2096 1278 2097 1274 2097 1275 2097 1278 2098 1275 2098 1330 2098 1330 2099 1275 2099 1328 2099 1330 2100 1328 2100 1331 2100 1278 2101 1330 2101 1336 2101 1278 2102 1336 2102 1288 2102 1288 2103 1336 2103 1337 2103 1288 2104 1337 2104 1289 2104 1289 2105 1337 2105 1338 2105 1289 2106 1338 2106 1285 2106 1285 2107 1338 2107 1339 2107 1285 2108 1339 2108 1286 2108 1299 2109 1290 2109 1305 2109 1305 2110 1290 2110 1286 2110 1305 2111 1286 2111 1303 2111 1340 2112 1339 2112 1341 2112 1341 2113 1339 2113 1342 2113 1340 2114 1343 2114 1339 2114 1339 2115 1343 2115 1344 2115 1339 2116 1344 2116 1286 2116 1286 2117 1344 2117 1300 2117 1286 2118 1300 2118 1303 2118 1299 2119 1298 2119 1290 2119 1290 2120 1298 2120 1310 2120 1290 2121 1310 2121 1309 2121 1345 2122 1346 2122 1342 2122 1342 2123 1346 2123 1347 2123 1342 2124 1347 2124 1341 2124 1300 2125 1344 2125 1301 2125 1301 2126 1344 2126 1348 2126 1349 2127 1350 2127 1351 2127 1351 2128 1350 2128 1352 2128 1351 2129 1352 2129 1353 2129 1301 2130 1348 2130 1354 2130 1354 2131 1348 2131 1350 2131 1354 2132 1350 2132 1355 2132 1355 2133 1350 2133 1349 2133 1353 2134 1356 2134 1351 2134 1351 2135 1356 2135 1357 2135 1351 2136 1357 2136 1358 2136 1358 2137 1357 2137 1359 2137 1357 2138 1360 2138 1359 2138 1359 2139 1360 2139 1361 2139 1359 2140 1361 2140 1362 2140 1362 2141 1361 2141 1363 2141 1361 2142 1364 2142 1363 2142 1363 2143 1364 2143 1365 2143 1363 2144 1365 2144 1366 2144 1366 2145 1365 2145 1367 2145 1367 2146 1368 2146 1366 2146 1366 2147 1368 2147 1369 2147 1366 2148 1369 2148 1370 2148 1306 2149 1304 2149 1371 2149 1302 2150 1301 2150 1354 2150 1372 2151 1373 2151 348 2151 348 2152 347 2152 1372 2152 1372 2153 347 2153 346 2153 1372 2154 346 2154 1371 2154 1371 2155 346 2155 345 2155 1371 2156 345 2156 1306 2156 1349 2157 1373 2157 1355 2157 1355 2158 1373 2158 1372 2158 1355 2159 1372 2159 1354 2159 1354 2160 1372 2160 1371 2160 1354 2161 1371 2161 1302 2161 1302 2162 1371 2162 1304 2162 1374 2163 1335 2163 1375 2163 1375 2164 1335 2164 1376 2164 1375 2165 1376 2165 1377 2165 1377 2166 1376 2166 1378 2166 1379 2167 1380 2167 1381 2167 1379 2168 1381 2168 1382 2168 1382 2169 1381 2169 1383 2169 1382 2170 1383 2170 1384 2170 1384 2171 1383 2171 1385 2171 1384 2172 1385 2172 1386 2172 1386 2173 1385 2173 1387 2173 1387 2174 1385 2174 1388 2174 1387 2175 1388 2175 1389 2175 1389 2176 1388 2176 1390 2176 1390 2177 1388 2177 1391 2177 1390 2178 1391 2178 1392 2178 1381 2179 1380 2179 1393 2179 1394 2180 1395 2180 1396 2180 1395 2181 1397 2181 1398 2181 1399 2182 1394 2182 1400 2182 1400 2183 1394 2183 1396 2183 1400 2184 1396 2184 1377 2184 1377 2185 1396 2185 1375 2185 1395 2186 1398 2186 1396 2186 1396 2187 1398 2187 1374 2187 1396 2188 1374 2188 1375 2188 1391 2189 1401 2189 1392 2189 1402 2190 1403 2190 1404 2190 1404 2191 1403 2191 1405 2191 1404 2192 1405 2192 1406 2192 1407 2193 1322 2193 1323 2193 1322 2194 1407 2194 1321 2194 1321 2195 1407 2195 1408 2195 1321 2196 1408 2196 1409 2196 1402 2197 1409 2197 1403 2197 1403 2198 1409 2198 1408 2198 1403 2199 1408 2199 1405 2199 1405 2200 1408 2200 1407 2200 1405 2201 1407 2201 1410 2201 1410 2202 1407 2202 1323 2202 1411 2203 1409 2203 1412 2203 1412 2204 1409 2204 1402 2204 1411 2205 1413 2205 1409 2205 1409 2206 1413 2206 1414 2206 1409 2207 1414 2207 1321 2207 1415 2208 1327 2208 1324 2208 1412 2209 1416 2209 1411 2209 1411 2210 1416 2210 1417 2210 1411 2211 1417 2211 1413 2211 1413 2212 1417 2212 1415 2212 1413 2213 1415 2213 1414 2213 1414 2214 1415 2214 1324 2214 1414 2215 1324 2215 1321 2215 1325 2216 1326 2216 1418 2216 1377 2217 1378 2217 1418 2217 1418 2218 1378 2218 1419 2218 1419 2219 1420 2219 1418 2219 1418 2220 1420 2220 1421 2220 1418 2221 1421 2221 1325 2221 1416 2222 1377 2222 1417 2222 1417 2223 1377 2223 1418 2223 1417 2224 1418 2224 1415 2224 1415 2225 1418 2225 1326 2225 1415 2226 1326 2226 1327 2226 1376 2227 1335 2227 1334 2227 1378 2228 1376 2228 1422 2228 1376 2229 1334 2229 1422 2229 1422 2230 1334 2230 1332 2230 1422 2231 1332 2231 1423 2231 1423 2232 1332 2232 1331 2232 1423 2233 1331 2233 1424 2233 1424 2234 1331 2234 1328 2234 1424 2235 1328 2235 1329 2235 1378 2236 1422 2236 1419 2236 1419 2237 1422 2237 1423 2237 1419 2238 1423 2238 1420 2238 1420 2239 1423 2239 1424 2239 1420 2240 1424 2240 1421 2240 1421 2241 1424 2241 1329 2241 1421 2242 1329 2242 1325 2242 1425 2243 1333 2243 1335 2243 1335 2244 1374 2244 1425 2244 1425 2245 1374 2245 1398 2245 1425 2246 1398 2246 1397 2246 1333 2247 1425 2247 1426 2247 1426 2248 1425 2248 1393 2248 1426 2249 1393 2249 1380 2249 1426 2250 1380 2250 1379 2250 1379 2251 1427 2251 1426 2251 1426 2252 1427 2252 1330 2252 1426 2253 1330 2253 1333 2253 1428 2254 1429 2254 1430 2254 1431 2255 1432 2255 1382 2255 1390 2256 1433 2256 1389 2256 1389 2257 1433 2257 1429 2257 1389 2258 1429 2258 1387 2258 1387 2259 1429 2259 1428 2259 1387 2260 1428 2260 1386 2260 1386 2261 1428 2261 1431 2261 1386 2262 1431 2262 1384 2262 1384 2263 1431 2263 1382 2263 1336 2264 1330 2264 1427 2264 1379 2265 1382 2265 1427 2265 1427 2266 1382 2266 1432 2266 1427 2267 1432 2267 1336 2267 1336 2268 1432 2268 1431 2268 1336 2269 1431 2269 1337 2269 1337 2270 1431 2270 1428 2270 1337 2271 1428 2271 1338 2271 1338 2272 1428 2272 1430 2272 1338 2273 1430 2273 1339 2273 1390 2274 1392 2274 1433 2274 1433 2275 1392 2275 1434 2275 1433 2276 1434 2276 1429 2276 1429 2277 1434 2277 1430 2277 1430 2278 1434 2278 1342 2278 1430 2279 1342 2279 1339 2279 1320 2280 1319 2280 1435 2280 1435 2281 1436 2281 1437 2281 1323 2282 1320 2282 1410 2282 1410 2283 1320 2283 1435 2283 1410 2284 1435 2284 1438 2284 1438 2285 1435 2285 1437 2285 1438 2286 1437 2286 1406 2286 1439 2287 1440 2287 1441 2287 1442 2288 1439 2288 1443 2288 1383 2289 1381 2289 1444 2289 1444 2290 1381 2290 1445 2290 1444 2291 1445 2291 1446 2291 1446 2292 1445 2292 1447 2292 1446 2293 1447 2293 1448 2293 1448 2294 1447 2294 1449 2294 1448 2295 1450 2295 1451 2295 1452 2296 1388 2296 1385 2296 1448 2297 1451 2297 1446 2297 1446 2298 1451 2298 1452 2298 1446 2299 1452 2299 1444 2299 1444 2300 1452 2300 1385 2300 1444 2301 1385 2301 1383 2301 1439 2302 1441 2302 1443 2302 1443 2303 1441 2303 1453 2303 1443 2304 1453 2304 1454 2304 1454 2305 1453 2305 1455 2305 1454 2306 1455 2306 1456 2306 1456 2307 1457 2307 1454 2307 1454 2308 1457 2308 1450 2308 1454 2309 1450 2309 1443 2309 1443 2310 1450 2310 1448 2310 1443 2311 1448 2311 1442 2311 1442 2312 1448 2312 1449 2312 1391 2313 1388 2313 1458 2313 1458 2314 1388 2314 1452 2314 1458 2315 1452 2315 1459 2315 1459 2316 1452 2316 1451 2316 1459 2317 1451 2317 1460 2317 1460 2318 1451 2318 1450 2318 1460 2319 1450 2319 1461 2319 1461 2320 1450 2320 1457 2320 1425 2321 1397 2321 1462 2321 1445 2322 1381 2322 1393 2322 1463 2323 1464 2323 1439 2323 1439 2324 1464 2324 1465 2324 1439 2325 1465 2325 1440 2325 1393 2326 1425 2326 1445 2326 1445 2327 1425 2327 1462 2327 1445 2328 1462 2328 1447 2328 1447 2329 1462 2329 1466 2329 1447 2330 1466 2330 1449 2330 1449 2331 1466 2331 1467 2331 1449 2332 1467 2332 1442 2332 1442 2333 1467 2333 1468 2333 1442 2334 1468 2334 1439 2334 1439 2335 1468 2335 1469 2335 1439 2336 1469 2336 1463 2336 1470 2337 1471 2337 1472 2337 1394 2338 1399 2338 1473 2339 1394 2340 1473 2340 1395 2340 1474 2341 1470 2341 1475 2341 1475 2342 1470 2342 1472 2342 1475 2343 1472 2343 1476 2343 1476 2344 1472 2344 1477 2344 1476 2345 1477 2345 1478 2345 1478 2346 1477 2346 1479 2346 1478 2347 1479 2347 1480 2347 1480 2348 1479 2348 1481 2348 1480 2349 1481 2349 1473 2349 1473 2350 1481 2350 1482 2350 1473 2351 1482 2351 1395 2351 1397 2352 1395 2352 1462 2352 1462 2353 1395 2353 1482 2353 1462 2354 1482 2354 1466 2354 1466 2355 1482 2355 1481 2355 1466 2356 1481 2356 1467 2356 1467 2357 1481 2357 1479 2357 1467 2358 1479 2358 1468 2358 1468 2359 1479 2359 1477 2359 1468 2360 1477 2360 1469 2360 1469 2361 1477 2361 1472 2361 1469 2362 1472 2362 1463 2362 1463 2363 1472 2363 1471 2363 1400 2364 1377 2364 1416 2364 1400 2365 1416 2365 1399 2365 1399 2366 1416 2366 1483 2366 1399 2367 1483 2367 1473 2367 1473 2368 1483 2368 1484 2368 1473 2369 1484 2369 1480 2369 1480 2370 1484 2370 1485 2370 1480 2371 1485 2371 1478 2371 1478 2372 1485 2372 1486 2372 1478 2373 1486 2373 1476 2373 1476 2374 1486 2374 1487 2374 1476 2375 1487 2375 1475 2375 1475 2376 1487 2376 1488 2376 1475 2377 1488 2377 1474 2377 1474 2378 1488 2378 1489 2378 1474 2379 1489 2379 1490 2379 1490 2380 1489 2380 1491 2380 1490 2381 1491 2381 1492 2381 1493 2382 1494 2382 1489 2382 1489 2383 1494 2383 1495 2383 1489 2384 1495 2384 1491 2384 1496 2385 1497 2385 1493 2385 1493 2386 1498 2386 1496 2386 1496 2387 1498 2387 1499 2387 1496 2388 1499 2388 1500 2388 1500 2389 1499 2389 1501 2389 1500 2390 1501 2390 1502 2390 1502 2391 1501 2391 1503 2391 1502 2392 1503 2392 1504 2392 1504 2393 1503 2393 1505 2393 1504 2394 1505 2394 1506 2394 1506 2395 1505 2395 1507 2395 1506 2396 1507 2396 1508 2396 1508 2397 1507 2397 1509 2397 1508 2398 1509 2398 1510 2398 1510 2399 1509 2399 1404 2399 1510 2400 1404 2400 1406 2400 1402 2401 1483 2401 1412 2401 1412 2402 1483 2402 1416 2402 1493 2403 1489 2403 1498 2403 1498 2404 1489 2404 1488 2404 1498 2405 1488 2405 1499 2405 1499 2406 1488 2406 1487 2406 1499 2407 1487 2407 1501 2407 1501 2408 1487 2408 1486 2408 1501 2409 1486 2409 1503 2409 1503 2410 1486 2410 1485 2410 1503 2411 1485 2411 1505 2411 1505 2412 1485 2412 1484 2412 1505 2413 1484 2413 1507 2413 1507 2414 1484 2414 1483 2414 1507 2415 1483 2415 1509 2415 1509 2416 1483 2416 1402 2416 1509 2417 1402 2417 1404 2417 1437 2418 1436 2418 1511 2418 1510 2419 1406 2419 1437 2419 1497 2420 1496 2420 1512 2420 1512 2421 1496 2421 1500 2421 1512 2422 1500 2422 1502 2422 1511 2423 1513 2423 1502 2423 1502 2424 1513 2424 1514 2424 1502 2425 1514 2425 1512 2425 1502 2426 1504 2426 1511 2426 1511 2427 1504 2427 1506 2427 1511 2428 1506 2428 1437 2428 1437 2429 1506 2429 1508 2429 1437 2430 1508 2430 1510 2430 1341 2431 1347 2431 1515 2431 1348 2432 1344 2432 1343 2432 1348 2433 1343 2433 1516 2433 1516 2434 1343 2434 1340 2434 1516 2435 1340 2435 1517 2435 1517 2436 1340 2436 1341 2436 1517 2437 1341 2437 1518 2437 1518 2438 1341 2438 1515 2438 1518 2439 1515 2439 460 2439 460 2440 1515 2440 454 2440 454 2441 1515 2441 1519 2441 1520 2442 601 2442 1519 2442 1519 2443 601 2443 605 2443 1519 2444 605 2444 454 2444 1345 2445 1520 2445 1346 2445 1346 2446 1520 2446 1519 2446 1346 2447 1519 2447 1347 2447 1347 2448 1519 2448 1515 2448 1345 2449 1342 2449 1521 2449 1521 2450 1342 2450 1434 2450 1521 2451 1434 2451 1522 2451 1522 2452 1434 2452 1523 2452 1392 2453 1401 2453 1434 2453 1434 2454 1401 2454 1524 2454 1434 2455 1524 2455 1523 2455 1523 2456 1524 2456 1525 2456 1523 2457 1525 2457 1526 2457 1526 2458 1525 2458 1527 2458 1528 2459 1529 2459 607 2459 1526 2460 1527 2461 1529 2462 607 2463 606 2463 1528 2463 1528 2464 606 2464 604 2464 1528 2465 604 2465 1530 2465 1530 2466 604 2466 603 2466 1530 2467 603 2467 1531 2467 1531 2468 603 2468 602 2468 1531 2469 602 2469 1532 2469 1532 2470 602 2470 601 2470 1532 2471 601 2471 1520 2471 1529 2472 1528 2472 1526 2472 1526 2473 1528 2473 1530 2473 1526 2474 1530 2474 1523 2474 1523 2475 1530 2475 1531 2475 1523 2476 1531 2476 1522 2476 1522 2477 1531 2477 1532 2477 1522 2478 1532 2478 1521 2478 1521 2479 1532 2479 1520 2479 1521 2480 1520 2480 1345 2480 1533 2481 1534 2482 1535 2483 1401 2484 1391 2484 1458 2484 1529 2485 1527 2485 1536 2485 1536 2486 1527 2486 1525 2486 1401 2487 1458 2487 1524 2487 1537 2488 1538 2488 1535 2488 1535 2489 1538 2489 1539 2489 1535 2490 1539 2490 1533 2490 1525 2491 1524 2491 1536 2491 1536 2492 1524 2492 1458 2492 1536 2493 1458 2493 1540 2493 1540 2494 1458 2494 1459 2494 1540 2495 1459 2495 1541 2495 1541 2496 1459 2496 1460 2496 1541 2497 1460 2497 1542 2497 1542 2498 1460 2498 1461 2498 1542 2499 1461 2499 1535 2499 1535 2500 1461 2500 1457 2500 1535 2501 1457 2501 1537 2501 1537 2502 1457 2502 1456 2502 1535 2503 1534 2503 586 2503 1541 2504 593 2504 1540 2504 1540 2505 593 2505 600 2505 1540 2506 600 2506 1536 2506 1536 2507 600 2507 599 2507 1536 2508 599 2508 1529 2508 1529 2509 599 2509 608 2509 1529 2510 608 2510 607 2510 586 2511 587 2511 1535 2511 1535 2512 587 2512 597 2512 1535 2513 597 2513 1542 2513 1542 2514 597 2514 596 2514 1542 2515 596 2515 1541 2515 1541 2516 596 2516 594 2516 1541 2517 594 2517 593 2517 394 2518 393 2518 1543 2518 1543 2519 393 2519 340 2519 1543 2520 340 2520 1544 2520 1544 2521 340 2521 339 2521 1544 2522 339 2522 348 2522 1362 2523 1363 2523 397 2523 397 2524 396 2524 1362 2524 1362 2525 396 2525 395 2525 1362 2526 395 2526 1359 2526 1359 2527 395 2527 394 2527 1359 2528 394 2528 1358 2528 1358 2529 394 2529 1543 2529 1358 2530 1543 2530 1351 2530 1351 2531 1543 2531 1544 2531 1351 2532 1544 2532 1349 2532 1370 2533 392 2533 1366 2533 1366 2534 392 2534 400 2534 1366 2535 400 2535 1363 2535 1363 2536 400 2536 399 2536 1363 2537 399 2537 397 2537 1369 2538 389 2538 1370 2538 1370 2539 389 2539 391 2539 1370 2540 391 2540 392 2540 1367 2541 422 2541 1368 2541 1368 2542 422 2542 425 2542 1368 2543 425 2543 1369 2543 1369 2544 425 2544 424 2544 1369 2545 424 2545 389 2545 1364 2546 1361 2546 428 2546 428 2547 427 2547 1364 2547 1364 2548 427 2548 426 2548 1364 2549 426 2549 1365 2549 1365 2550 426 2550 421 2550 1365 2551 421 2551 1367 2551 1367 2552 421 2552 420 2552 1367 2553 420 2553 422 2553 1545 2554 458 2554 418 2554 1361 2555 1360 2555 428 2555 428 2556 1360 2556 1545 2556 428 2557 1545 2557 429 2557 429 2558 1545 2558 418 2558 1516 2559 1517 2559 1546 2559 1546 2560 1517 2560 1518 2560 458 2561 1545 2561 459 2561 459 2562 1545 2562 1547 2562 459 2563 1547 2563 462 2563 462 2564 1547 2564 1546 2564 462 2565 1546 2565 461 2565 461 2566 1546 2566 1518 2566 461 2567 1518 2567 460 2567 1348 2568 1516 2568 1350 2568 1350 2569 1516 2569 1546 2569 1350 2570 1546 2570 1352 2570 1352 2571 1546 2571 1547 2571 1360 2572 1357 2572 1545 2572 1545 2573 1357 2573 1356 2573 1545 2574 1356 2574 1547 2574 1547 2575 1356 2575 1353 2575 1547 2576 1353 2576 1352 2576 1548 2577 1549 2578 1550 2579 1550 2580 1549 2581 1551 2582 376 1679 1548 1679 1550 1679 376 1679 1550 1679 377 1679 377 1679 1550 1679 1551 1679 377 1679 1551 1679 390 1679 390 2583 1551 2584 398 2585 398 2586 1551 2587 1549 2588 398 2589 1549 2590 376 2591 376 2592 1549 2593 1548 2594 1552 2595 463 2595 482 2595 1552 2596 482 2596 1553 2596 1553 2597 482 2597 481 2597 1553 2598 481 2598 1554 2598 1554 2599 481 2599 480 2599 1554 2600 480 2600 1555 2600 1555 2601 480 2601 478 2601 1555 2602 478 2602 1556 2602 1556 2603 478 2603 476 2603 1556 2604 476 2604 1557 2604 1557 2605 476 2605 475 2605 1557 2606 475 2606 1558 2606 1558 2607 475 2607 472 2607 1558 2608 472 2608 1559 2608 1559 2609 472 2609 473 2609 1559 2610 473 2610 1560 2610 1560 2611 473 2611 474 2611 1560 2612 474 2612 1561 2612 1561 2613 474 2613 468 2613 1561 2614 468 2614 1562 2614 1562 2615 468 2615 1563 2615 1563 2616 468 2616 467 2616 1563 2617 467 2617 1564 2617 467 2618 471 2618 1564 2618 1564 2619 471 2619 470 2619 1564 2620 470 2620 1565 2620 1565 2621 470 2621 469 2621 1565 2622 469 2622 1566 2622 1566 2623 469 2623 466 2623 1566 2624 466 2624 1567 2624 1567 2625 466 2625 465 2625 1567 2626 465 2626 1568 2626 1568 2627 465 2627 463 2627 1568 2628 463 2628 1552 2628 1552 2629 1553 2629 1554 2629 1556 2630 1557 2630 1563 2630 1563 2631 1557 2631 1558 2631 1561 2632 1562 2632 1560 2632 1560 2633 1562 2633 1563 2633 1560 2634 1563 2634 1559 2634 1559 2635 1563 2635 1558 2635 1563 2636 1564 2636 1569 2636 1569 2637 1564 2637 1565 2637 1565 2638 1566 2638 1569 2638 1569 2639 1566 2639 1567 2639 1569 2640 1567 2640 1568 2640 1568 2641 1552 2641 1569 2641 1569 2642 1552 2642 1554 2642 1569 2643 1554 2643 1563 2643 1563 2644 1554 2644 1555 2644 1563 2645 1555 2645 1556 2645 477 1811 1570 1811 457 1811 457 1811 1570 1811 1571 1811 457 1811 1571 1811 456 1811 1572 2646 419 2646 417 2646 1572 2647 417 2647 1573 2647 1573 2648 417 2648 416 2648 1573 2649 416 2649 1574 2649 416 2650 453 2650 1574 2650 1574 2651 453 2651 452 2651 1574 2652 452 2652 1575 2652 1575 2653 452 2653 456 2653 1575 2654 456 2654 1571 2654 1576 2655 448 2655 446 2655 1576 2656 446 2656 1577 2656 1577 2657 446 2657 414 2657 1577 2658 414 2658 1578 2658 1578 2659 414 2659 415 2659 1578 2660 415 2660 1579 2660 1579 2661 415 2661 419 2661 1579 2662 419 2662 1572 2662 1580 2663 451 2663 1576 2663 1576 2663 451 2663 450 2663 1576 2663 450 2663 448 2663 1581 2664 438 2664 437 2664 1581 2665 437 2665 1582 2665 1582 2666 437 2666 444 2666 1582 2667 444 2667 1583 2667 1583 2668 444 2668 443 2668 1583 2669 443 2669 1584 2669 1584 2670 443 2670 451 2670 1584 2671 451 2671 1580 2671 1570 2672 477 2672 479 2672 441 2673 1585 2673 479 2673 479 2674 1585 2674 1586 2674 479 2675 1586 2675 1570 2675 441 2676 440 2676 1585 2676 1585 2677 440 2677 439 2677 1585 2678 439 2678 1587 2678 1587 2679 439 2679 438 2679 1587 2680 438 2680 1581 2680 1570 2681 1586 2681 1580 2681 1580 2682 1586 2682 1585 2682 1587 2683 1581 2683 1588 2683 1585 2684 1587 2684 1580 2684 1580 2685 1587 2685 1588 2685 1580 2686 1588 2686 1584 2686 1581 2687 1582 2687 1588 2687 1588 2688 1582 2688 1583 2688 1588 2689 1583 2689 1584 2689 1577 2690 1578 2690 1571 2690 1579 2691 1572 2691 1589 2691 1578 2692 1579 2692 1571 2692 1571 2693 1579 2693 1589 2693 1571 2694 1589 2694 1575 2694 1572 2695 1573 2695 1589 2695 1589 2696 1573 2696 1574 2696 1589 2697 1574 2697 1575 2697 1570 2698 1580 2698 1571 2698 1571 2699 1580 2699 1576 2699 1571 2700 1576 2700 1577 2700 1590 1811 447 1811 1591 1811 1591 1811 447 1811 449 1811 1591 1811 449 1811 442 1811 1592 2701 423 2701 413 2701 1592 2702 413 2702 1593 2702 1593 2703 413 2703 412 2703 1593 2704 412 2704 1594 2704 1594 2705 412 2705 445 2705 1594 2706 445 2706 1595 2706 1595 2707 445 2707 447 2707 1595 2708 447 2708 1590 2708 1596 2709 384 2709 380 2709 1596 2710 380 2710 1597 2710 1597 2711 380 2711 379 2711 1597 2712 379 2712 1598 2712 1598 2713 379 2713 378 2713 1598 2714 378 2714 1599 2714 1599 2715 378 2715 423 2715 1599 2716 423 2716 1592 2716 384 2663 1596 2663 410 2663 410 2663 1596 2663 1600 2663 410 2663 1600 2663 411 2663 1601 2717 432 2717 431 2717 1601 2718 431 2718 1602 2718 1602 2719 431 2719 430 2719 1602 2720 430 2720 1603 2720 1603 2721 430 2721 407 2721 1603 2722 407 2722 1604 2722 1604 2723 407 2723 411 2723 1604 2724 411 2724 1600 2724 1591 2725 442 2725 436 2725 1591 2726 436 2726 1605 2726 1605 2727 436 2727 435 2727 1605 2728 435 2728 1606 2728 1606 2729 435 2729 434 2729 1606 2730 434 2730 1607 2730 1607 2731 434 2731 432 2731 1607 2732 432 2732 1601 2732 1590 2733 1596 2733 1597 2733 1593 2734 1594 2734 1592 2734 1592 2735 1594 2735 1595 2735 1592 2736 1595 2736 1599 2736 1599 2737 1595 2737 1590 2737 1599 2738 1590 2738 1598 2738 1598 2739 1590 2739 1597 2739 1602 2740 1603 2740 1601 2740 1601 2741 1603 2741 1604 2741 1601 2742 1604 2742 1607 2742 1607 2743 1604 2743 1600 2743 1607 2744 1600 2744 1606 2744 1606 2745 1600 2745 1605 2745 1596 1723 1590 1723 1600 1723 1600 1723 1590 1723 1591 1723 1600 2746 1591 2746 1605 2746 408 1811 1608 1811 409 1811 409 1811 1608 1811 1609 1811 409 1811 1609 1811 385 1811 1610 2747 386 2747 382 2747 1610 2748 382 2748 1611 2748 1611 2749 382 2749 381 2749 1611 2750 381 2750 1612 2750 1612 2751 381 2751 383 2751 1612 2752 383 2752 1613 2752 1613 2753 383 2753 385 2753 1613 2754 385 2754 1609 2754 1614 2755 372 2755 374 2755 375 2756 1615 2756 374 2756 374 2757 1615 2757 1616 2757 374 2758 1616 2758 1614 2758 375 2759 388 2759 1615 2759 1615 2760 388 2760 387 2760 1615 2761 387 2761 1617 2761 1617 2762 387 2762 386 2762 1617 2763 386 2763 1610 2763 1618 2663 367 2663 1614 2663 1614 2663 367 2663 366 2663 1614 2663 366 2663 372 2663 1619 2764 402 2764 401 2764 1619 2765 401 2765 1620 2765 1620 2766 401 2766 361 2766 1620 2767 361 2767 1621 2767 361 2768 369 2768 1621 2768 1621 2769 369 2769 368 2769 1621 2770 368 2770 1622 2770 1622 2771 368 2771 367 2771 1622 2772 367 2772 1618 2772 1608 2773 408 2773 406 2773 1608 2774 406 2774 1623 2774 1623 2775 406 2775 405 2775 1623 2776 405 2776 1624 2776 1624 2777 405 2777 404 2777 1624 2778 404 2778 1625 2778 1625 2779 404 2779 402 2779 1625 2780 402 2780 1619 2780 1614 2781 1616 2781 1609 2781 1609 2782 1616 2782 1615 2782 1617 2783 1610 2783 1626 2783 1615 2784 1617 2784 1609 2784 1609 2785 1617 2785 1626 2785 1609 2786 1626 2786 1613 2786 1610 2787 1611 2787 1626 2787 1626 2788 1611 2788 1612 2788 1626 2789 1612 2789 1613 2789 1623 2790 1624 2790 1618 2790 1625 2791 1619 2791 1627 2791 1624 2792 1625 2792 1618 2792 1618 2793 1625 2793 1627 2793 1618 2794 1627 2794 1622 2794 1619 2795 1620 2795 1627 2795 1627 2796 1620 2796 1621 2796 1627 2797 1621 2797 1622 2797 1614 2798 1609 2798 1618 2798 1618 2799 1609 2799 1608 2799 1618 2800 1608 2800 1623 2800 364 1811 1628 1811 365 1811 365 1811 1628 1811 1629 1811 365 1811 1629 1811 370 1811 1630 2801 338 2801 341 2801 1630 2802 341 2802 1631 2802 1631 2803 341 2803 373 2803 1631 2804 373 2804 1632 2804 1632 2805 373 2805 371 2805 1632 2806 371 2806 1633 2806 1633 2807 371 2807 370 2807 1633 2808 370 2808 1629 2808 1634 2809 354 2809 353 2809 1634 2810 353 2810 1635 2810 1635 2811 353 2811 342 2811 1635 2812 342 2812 1636 2812 1636 2813 342 2813 344 2813 1636 2814 344 2814 1637 2814 1637 2815 344 2815 338 2815 1637 2816 338 2816 1630 2816 354 2663 1634 2663 356 2663 356 2663 1634 2663 1638 2663 356 2663 1638 2663 352 2663 1639 2817 358 2817 357 2817 1639 2818 357 2818 1640 2818 1640 2819 357 2819 350 2819 1640 2820 350 2820 1641 2820 1641 2821 350 2821 349 2821 1641 2822 349 2822 1642 2822 1642 2823 349 2823 352 2823 1642 2824 352 2824 1638 2824 1628 2825 364 2825 360 2825 1628 2826 360 2826 1643 2826 1643 2827 360 2827 362 2827 1643 2828 362 2828 1644 2828 1644 2829 362 2829 363 2829 1644 2830 363 2830 1645 2830 1645 2831 363 2831 358 2831 1645 2832 358 2832 1639 2832 1634 2833 1635 2833 1629 2833 1629 2834 1635 2834 1636 2834 1637 2835 1630 2835 1646 2835 1636 2836 1637 2836 1629 2836 1629 2837 1637 2837 1646 2837 1629 2838 1646 2838 1633 2838 1630 2839 1631 2839 1646 2839 1646 2840 1631 2840 1632 2840 1646 2841 1632 2841 1633 2841 1643 2842 1644 2842 1638 2842 1638 2843 1644 2843 1645 2843 1638 2844 1645 2844 1647 2844 1647 2845 1645 2845 1639 2845 1639 2846 1640 2846 1647 2846 1647 2847 1640 2847 1641 2847 1647 2848 1641 2848 1638 2848 1638 2849 1641 2849 1642 2849 1634 2850 1629 2850 1638 2850 1638 2851 1629 2851 1628 2851 1638 2852 1628 2852 1643 2852 1648 2853 1649 2853 1650 2853 1650 2854 1649 2854 1651 2854 1650 2855 1651 2855 1652 2855 1652 2856 1651 2856 1653 2856 1654 2857 1655 2857 1656 2857 1656 2858 1655 2858 1657 2858 1656 2859 1657 2859 1658 2859 1658 2860 1657 2860 1659 2860 1658 2861 1659 2861 1660 2861 1660 2862 1659 2862 1661 2862 1660 2863 1661 2863 1662 2863 1662 2864 1661 2864 1663 2864 1663 2865 1661 2865 1664 2865 1663 2866 1664 2866 1665 2866 1666 2867 1665 2867 1664 2867 1667 2868 1668 2868 1669 2868 1670 2869 1671 2869 1672 2869 1672 2870 1671 2870 1673 2870 1669 2871 1648 2871 1650 2871 1652 2872 1673 2872 1650 2872 1650 2873 1673 2873 1671 2873 1650 2874 1671 2874 1669 2874 1669 2875 1671 2875 1670 2875 1669 2876 1670 2876 1667 2876 1654 2877 1674 2877 1655 2877 1675 2878 1676 2878 1677 2878 1678 2879 1679 2879 1680 2879 1680 2880 1679 2880 1681 2880 1678 2881 1682 2881 1679 2881 1679 2882 1682 2882 1683 2882 1679 2883 1683 2883 1684 2883 1680 2884 1685 2884 1678 2884 1678 2885 1685 2885 1686 2885 1678 2886 1686 2886 1682 2886 1682 2887 1686 2887 1675 2887 1682 2888 1675 2888 1683 2888 1683 2889 1675 2889 1677 2889 1683 2890 1677 2890 1684 2890 1687 2891 1679 2891 1684 2891 1688 2892 1689 2892 1690 2892 1690 2893 1689 2893 1691 2893 1687 2894 1684 2894 1692 2894 1692 2895 1684 2895 1693 2895 1692 2896 1693 2896 1694 2896 1694 2897 1695 2897 1692 2897 1692 2898 1695 2898 1689 2898 1692 2899 1689 2899 1687 2899 1687 2900 1689 2900 1688 2900 1687 2901 1688 2901 1679 2901 1679 2902 1688 2902 1690 2902 1679 2903 1690 2903 1681 2903 1695 2904 1694 2905 1696 2906 1697 2907 1649 2907 1689 2907 1689 2908 1649 2908 1648 2908 1689 2909 1648 2909 1691 2909 1698 2910 1699 2910 1697 2910 1697 2911 1699 2911 1700 2911 1697 2912 1700 2912 1649 2912 1689 2913 1695 2913 1697 2913 1697 2914 1695 2914 1696 2914 1697 2915 1696 2915 1698 2915 1698 2916 1696 2916 1701 2916 1651 2917 1649 2917 1700 2917 1653 2918 1651 2918 1702 2918 1651 2919 1700 2919 1702 2919 1702 2920 1700 2920 1699 2920 1702 2921 1699 2921 1703 2921 1703 2922 1699 2922 1698 2922 1703 2923 1698 2923 1704 2923 1704 2924 1698 2924 1701 2924 1704 2925 1701 2925 1705 2925 1653 2926 1702 2926 1706 2926 1706 2927 1702 2927 1703 2927 1706 2928 1703 2928 1707 2928 1707 2929 1703 2929 1704 2929 1707 2930 1704 2930 1708 2930 1708 2931 1704 2931 1705 2931 1708 2932 1705 2932 1709 2932 1652 2933 1710 2933 1673 2933 1673 2934 1710 2934 1672 2934 1665 2935 1666 2935 1711 2935 1711 2936 1666 2936 1710 2936 1711 2937 1710 2937 1712 2937 1712 2938 1710 2938 1652 2938 1712 2939 1652 2939 1653 2939 1711 2940 1712 2940 1713 2940 1713 2941 1714 2941 1711 2941 1711 2942 1714 2942 1663 2942 1711 2943 1663 2943 1665 2943 1715 2944 1714 2944 1713 2944 1716 2945 1717 2945 1718 2945 1718 2946 1717 2946 1719 2946 1663 2947 1714 2947 1662 2947 1662 2948 1714 2948 1715 2948 1662 2949 1715 2949 1660 2949 1660 2950 1715 2950 1719 2950 1660 2951 1719 2951 1658 2951 1658 2952 1719 2952 1717 2952 1658 2953 1717 2953 1656 2953 1720 2954 1721 2954 1722 2954 1713 2955 1723 2955 1715 2955 1715 2956 1723 2956 1724 2956 1715 2957 1724 2957 1719 2957 1719 2958 1724 2958 1720 2958 1719 2959 1720 2959 1718 2959 1718 2960 1720 2960 1722 2960 1718 2961 1722 2961 1716 2961 1721 2962 1725 2962 1722 2962 1722 2963 1725 2963 1726 2963 1722 2964 1726 2964 1716 2964 1716 2965 1726 2965 1717 2965 1717 2966 1726 2966 1654 2966 1717 2967 1654 2967 1656 2967 1727 2968 1728 2968 1729 2968 1729 2969 1676 2969 1675 2969 1730 2970 1685 2970 1731 2970 1729 2971 1675 2971 1727 2971 1727 2972 1675 2972 1730 2972 1727 2973 1730 2974 1732 2975 1732 2976 1730 2976 1731 2976 1732 2977 1731 2977 1733 2977 1734 2978 1664 2978 1661 2978 1735 2979 1734 2979 1736 2979 1737 2980 1738 2980 1739 2980 1740 2981 1741 2981 1742 2981 1742 2982 1741 2982 1743 2982 1742 2983 1743 2983 1738 2983 1738 2984 1743 2984 1744 2984 1738 2985 1744 2985 1739 2985 1737 2986 1745 2986 1746 2986 1747 2987 1748 2987 1749 2987 1737 2988 1746 2988 1738 2988 1738 2989 1746 2989 1747 2989 1738 2990 1747 2990 1742 2990 1742 2991 1747 2991 1749 2991 1742 2992 1749 2992 1740 2992 1734 2993 1661 2993 1736 2993 1736 2994 1661 2994 1659 2994 1736 2995 1659 2995 1750 2995 1750 2996 1659 2996 1657 2996 1750 2997 1657 2997 1655 2997 1655 2998 1751 2998 1750 2998 1750 2999 1751 2999 1745 2999 1750 3000 1745 3000 1736 3000 1736 3001 1745 3001 1737 3001 1736 3002 1737 3002 1735 3002 1735 3003 1737 3003 1739 3003 1752 3004 1748 3004 1753 3004 1753 3005 1748 3005 1747 3005 1753 3006 1747 3006 1754 3006 1754 3007 1747 3007 1746 3007 1754 3008 1746 3008 1755 3008 1755 3009 1746 3009 1745 3009 1755 3010 1745 3010 1756 3010 1756 3011 1745 3011 1751 3011 1757 3012 1758 3012 1759 3012 1743 3013 1741 3013 1760 3013 1672 3014 1710 3014 1734 3014 1734 3015 1710 3015 1666 3015 1734 3016 1666 3016 1664 3016 1760 3017 1757 3017 1743 3017 1743 3018 1757 3018 1759 3018 1743 3019 1759 3019 1744 3019 1744 3020 1759 3020 1761 3020 1744 3021 1761 3021 1739 3021 1739 3022 1761 3022 1762 3022 1739 3023 1762 3023 1735 3023 1735 3024 1762 3024 1763 3024 1735 3025 1763 3025 1734 3025 1734 3026 1763 3026 1764 3026 1734 3027 1764 3027 1672 3027 1667 3028 1670 3028 1765 3028 1766 3029 1767 3029 1768 3029 1766 3030 1768 3030 1769 3030 1668 3031 1667 3032 1770 3033 1770 3034 1667 3034 1765 3034 1770 3035 1765 3035 1771 3035 1771 3036 1765 3036 1772 3036 1771 3037 1772 3037 1773 3037 1773 3038 1772 3038 1774 3038 1773 3039 1774 3039 1775 3039 1775 3040 1774 3040 1776 3040 1775 3041 1776 3041 1768 3041 1768 3042 1776 3042 1777 3042 1768 3043 1777 3043 1769 3043 1758 3044 1769 3044 1759 3044 1759 3045 1769 3045 1777 3045 1759 3046 1777 3046 1761 3046 1761 3047 1777 3047 1776 3047 1761 3048 1776 3048 1762 3048 1762 3049 1776 3049 1774 3049 1762 3050 1774 3050 1763 3050 1763 3051 1774 3051 1772 3051 1763 3052 1772 3052 1764 3052 1764 3053 1772 3053 1765 3053 1764 3054 1765 3054 1672 3054 1672 3055 1765 3055 1670 3055 1778 3056 1779 3056 1780 3056 1778 3057 1780 3057 1767 3057 1767 3058 1780 3058 1781 3058 1767 3059 1781 3059 1768 3059 1768 3060 1781 3060 1782 3060 1768 3061 1782 3061 1775 3061 1775 3062 1782 3062 1783 3062 1775 3063 1783 3063 1773 3063 1773 3064 1783 3064 1784 3064 1773 3065 1784 3065 1771 3065 1771 3066 1784 3066 1785 3066 1771 3067 1785 3067 1770 3067 1770 3068 1785 3068 1786 3068 1770 3069 1786 3069 1668 3069 1668 3070 1786 3070 1787 3070 1668 3071 1787 3071 1669 3071 1669 3072 1787 3072 1691 3072 1669 3073 1691 3073 1648 3073 1680 3074 1681 3074 1787 3074 1787 3075 1681 3075 1690 3075 1787 3076 1690 3076 1691 3076 1788 3077 1685 3077 1680 3077 1680 3078 1789 3078 1788 3078 1788 3079 1789 3079 1790 3079 1788 3080 1790 3080 1791 3080 1791 3081 1790 3081 1792 3081 1791 3082 1792 3082 1793 3082 1793 3083 1792 3083 1794 3083 1793 3084 1794 3084 1795 3084 1795 3085 1794 3085 1796 3085 1795 3086 1796 3086 1797 3086 1797 3087 1796 3087 1798 3087 1797 3088 1798 3088 1799 3088 1799 3089 1798 3089 1800 3089 1799 3090 1800 3090 1801 3090 1801 3091 1800 3091 1802 3091 1801 3092 1802 3092 1803 3092 1804 3093 1781 3093 1805 3093 1805 3094 1781 3094 1780 3094 1680 3095 1787 3095 1789 3095 1789 3096 1787 3096 1786 3096 1789 3097 1786 3097 1790 3097 1790 3098 1786 3098 1785 3098 1790 3099 1785 3099 1792 3099 1792 3100 1785 3100 1784 3100 1792 3101 1784 3101 1794 3101 1794 3102 1784 3102 1783 3102 1794 3103 1783 3103 1796 3103 1796 3104 1783 3104 1782 3104 1796 3105 1782 3105 1798 3105 1798 3106 1782 3106 1781 3106 1798 3107 1781 3107 1800 3107 1800 3108 1781 3108 1804 3108 1800 3109 1804 3109 1802 3109 1806 3110 1807 3110 1808 3110 1801 3111 1803 3111 1806 3111 1801 3112 1806 3112 1799 3112 1685 3113 1788 3113 1731 3113 1731 3114 1788 3114 1791 3114 1731 3115 1791 3115 1793 3115 1799 3116 1806 3116 1797 3116 1797 3117 1806 3117 1808 3117 1797 3118 1808 3118 1795 3118 1795 3119 1808 3119 1809 3119 1795 3120 1809 3120 1793 3120 1793 3121 1809 3121 1733 3121 1793 3122 1733 3122 1731 3122 1810 3123 1811 3123 1812 3123 1813 3124 1814 3124 1815 3124 1813 3125 1815 3125 1816 3125 1816 3126 1815 3126 1817 3126 1816 3127 1817 3127 1818 3127 1818 3128 1817 3128 1819 3128 1818 3129 1819 3129 1812 3129 1812 3130 1819 3130 200 3130 1812 3131 200 3131 1810 3131 566 3132 1820 3132 567 3132 567 3133 1820 3133 1821 3133 567 3134 1821 3134 198 3134 198 3135 1821 3135 1810 3135 198 3136 1810 3136 200 3136 1820 3137 1822 3137 1821 3137 1821 3138 1822 3138 1823 3138 1821 3139 1823 3139 1810 3139 1810 3140 1823 3140 1811 3140 1726 3141 1725 3141 1822 3141 1822 3142 1824 3142 1726 3142 1726 3143 1824 3143 1825 3143 1726 3144 1825 3144 1826 3144 1827 3145 1828 3145 1829 3145 1827 3146 1829 3146 1826 3146 1826 3147 1829 3147 1830 3147 1826 3148 1830 3148 1726 3148 1726 3149 1830 3149 1674 3149 1726 3150 1674 3150 1654 3150 1831 3151 1832 3151 1828 3151 562 3152 561 3152 1832 3152 1828 3153 1827 3153 1831 3153 1831 3154 1827 3154 1826 3154 1831 3155 1826 3155 1833 3155 1833 3156 1826 3156 1825 3156 1833 3157 1825 3157 1834 3157 1834 3158 1825 3158 1824 3158 1834 3159 1824 3159 1835 3159 1835 3160 1824 3160 1822 3160 1835 3161 1822 3161 1820 3161 1832 3162 1831 3162 562 3162 562 3163 1831 3163 1833 3163 562 3164 1833 3164 563 3164 563 3165 1833 3165 1834 3165 563 3166 1834 3166 564 3166 564 3167 1834 3167 1835 3167 564 3168 1835 3168 565 3168 565 3169 1835 3169 1820 3169 565 3170 1820 3170 566 3170 1836 3171 1752 3171 1753 3171 1828 3172 1832 3172 1837 3172 1674 3173 1830 3173 1837 3173 1837 3174 1830 3174 1829 3174 1837 3175 1829 3175 1828 3175 1838 3176 1839 3177 1840 3178 1840 3179 1839 3179 1841 3179 1836 3180 1753 3180 1842 3180 1841 3181 1842 3181 1840 3181 1840 3182 1842 3182 1753 3182 1840 3183 1753 3183 1843 3183 1843 3184 1753 3184 1754 3184 1843 3185 1754 3185 1844 3185 1844 3186 1754 3186 1755 3186 1844 3187 1755 3187 1845 3187 1845 3188 1755 3188 1756 3188 1845 3189 1756 3189 1837 3189 1837 3190 1756 3190 1751 3190 1837 3191 1751 3191 1674 3191 1674 3192 1751 3192 1655 3192 1728 3193 1846 3193 1729 3193 1729 3194 1846 3194 1847 3194 1729 3195 1847 3195 1676 3195 1848 3196 1684 3196 1849 3196 1849 3197 1684 3197 1850 3197 1850 3198 1684 3198 1847 3198 1847 3199 1684 3199 1677 3199 1847 3200 1677 3200 1676 3200 1684 3201 1848 3201 1851 3201 1852 3202 1701 3202 1853 3202 1853 3203 1701 3203 1696 3203 1853 3204 1696 3204 1694 3204 1851 3205 1854 3205 1684 3205 1684 3206 1854 3206 1853 3206 1684 3207 1853 3207 1693 3207 1693 3208 1853 3208 1694 3208 1855 3209 1709 3209 1856 3209 1856 3210 1709 3210 1705 3210 1856 3211 1705 3211 1852 3211 1852 3212 1705 3212 1701 3212 1857 3213 1858 3213 1859 3213 1857 3214 1859 3214 1860 3214 1860 3215 1859 3215 1861 3215 1860 3216 1861 3216 1862 3216 1653 3217 1706 3217 1712 3217 1712 3218 1706 3218 1707 3218 1712 3219 1707 3219 1713 3219 1707 3220 1708 3220 1713 3220 1713 3221 1708 3221 1709 3221 1713 3222 1709 3222 1857 3222 1857 3223 1709 3223 1855 3223 1857 3224 1855 3224 1858 3224 1713 3225 1857 3225 1863 3225 1713 3226 1863 3226 1723 3226 1723 3227 1863 3227 1864 3227 1723 3228 1864 3228 1724 3228 1724 3229 1864 3229 1865 3229 1724 3230 1865 3230 1720 3230 1720 3231 1865 3231 1866 3231 1720 3232 1866 3232 1721 3232 1812 3233 1725 3233 1818 3233 1818 3234 1725 3234 1721 3234 1818 3235 1721 3235 1816 3235 1867 3236 1866 3236 1868 3236 1868 3237 1866 3237 1869 3237 1867 3238 1870 3238 1866 3238 1866 3239 1870 3239 1871 3239 1866 3240 1871 3240 1721 3240 1721 3241 1871 3241 1813 3241 1721 3242 1813 3242 1816 3242 1812 3243 1811 3243 1725 3243 1725 3244 1811 3244 1823 3244 1725 3245 1823 3245 1822 3245 1872 3246 1873 3246 1869 3246 1869 3247 1873 3247 1874 3247 1869 3248 1874 3248 1868 3248 1813 3249 1871 3249 1814 3249 1814 3250 1871 3250 1875 3250 1876 3251 1877 3251 1878 3251 1878 3252 1877 3252 1879 3252 1878 3253 1879 3253 1880 3253 1814 3254 1875 3254 1881 3254 1881 3255 1875 3255 1877 3255 1881 3256 1877 3256 1882 3256 1882 3257 1877 3257 1876 3257 1880 3258 1883 3258 1878 3258 1878 3259 1883 3259 1884 3259 1878 3260 1884 3260 1885 3260 1885 3261 1884 3261 1886 3261 1884 3262 1887 3262 1886 3262 1886 3263 1887 3263 1888 3263 1886 3264 1888 3264 1889 3264 1889 3265 1888 3265 1890 3265 1888 3266 1891 3266 1890 3266 1890 3267 1891 3267 1892 3267 1890 3268 1892 3268 1893 3268 1893 3269 1892 3269 1894 3269 1894 3270 1895 3270 1893 3270 1893 3271 1895 3271 1896 3271 1893 3272 1896 3272 1897 3272 580 3273 1838 3273 581 3273 581 3274 1838 3274 1840 3274 581 3275 1840 3275 582 3275 582 3276 1840 3276 573 3276 573 3277 1840 3277 1843 3277 573 3278 1843 3278 571 3278 571 3279 1843 3279 1844 3279 571 3280 1844 3280 570 3280 570 3281 1844 3281 1845 3281 570 3282 1845 3282 568 3282 568 3283 1845 3283 0 3283 0 3284 1845 3284 1837 3284 0 3285 1837 3285 1 3285 1 3286 1837 3286 1832 3286 1 3287 1832 3287 561 3287 1819 3288 1817 3288 1898 3288 1815 3289 1814 3289 1881 3289 1899 3290 1900 3290 203 3290 203 3291 202 3291 1899 3291 1899 3292 202 3292 201 3292 1899 3293 201 3293 1898 3293 1898 3294 201 3294 200 3294 1898 3295 200 3295 1819 3295 1876 3296 1900 3296 1882 3296 1882 3297 1900 3297 1899 3297 1882 3298 1899 3298 1881 3298 1881 3299 1899 3299 1898 3299 1881 3300 1898 3300 1815 3300 1815 3301 1898 3301 1817 3301 1901 3302 1862 3302 1902 3302 1902 3303 1862 3303 1903 3303 1902 3304 1903 3304 1088 3304 1088 3305 1903 3305 1904 3305 1905 3306 1906 3306 1047 3306 1905 3307 1047 3307 1907 3307 1907 3308 1047 3308 1046 3308 1907 3309 1046 3309 1908 3309 1908 3310 1046 3310 1058 3310 1908 3311 1058 3311 1909 3311 1909 3312 1058 3312 1910 3312 1910 3313 1058 3313 1057 3313 1910 3314 1057 3314 1911 3314 1911 3315 1057 3315 1912 3315 1912 3316 1057 3316 1061 3316 1912 3317 1061 3317 1913 3317 1047 3318 1906 3318 1069 3318 1074 3319 1078 3319 1914 3319 1078 3320 1067 3320 1915 3320 1075 3321 1074 3321 1087 3321 1087 3322 1074 3322 1914 3322 1087 3323 1914 3323 1088 3323 1088 3324 1914 3324 1902 3324 1078 3325 1915 3325 1914 3325 1914 3326 1915 3326 1901 3326 1914 3327 1901 3327 1902 3327 1061 3328 1137 3328 1913 3328 1113 3329 1916 3329 1111 3329 1111 3330 1916 3330 1917 3330 1111 3331 1917 3331 1112 3331 1918 3332 1849 3332 1850 3332 1849 3333 1918 3333 1848 3333 1848 3334 1918 3334 1919 3334 1848 3335 1919 3335 1920 3335 1113 3336 1920 3336 1916 3336 1916 3337 1920 3337 1919 3337 1916 3338 1919 3338 1917 3338 1917 3339 1919 3339 1918 3339 1917 3340 1918 3340 1921 3340 1921 3341 1918 3341 1850 3341 1922 3342 1920 3342 1114 3342 1114 3343 1920 3343 1113 3343 1922 3344 1923 3344 1920 3344 1920 3345 1923 3345 1924 3345 1920 3346 1924 3346 1848 3346 1925 3347 1854 3347 1851 3347 1114 3348 1089 3348 1922 3348 1922 3349 1089 3349 1926 3349 1922 3350 1926 3350 1923 3350 1923 3351 1926 3351 1925 3351 1923 3352 1925 3352 1924 3352 1924 3353 1925 3353 1851 3353 1924 3354 1851 3354 1848 3354 1852 3355 1853 3355 1927 3355 1088 3356 1904 3356 1927 3356 1927 3357 1904 3357 1928 3357 1928 3358 1929 3358 1927 3358 1927 3359 1929 3359 1930 3359 1927 3360 1930 3360 1852 3360 1089 3361 1088 3361 1926 3361 1926 3362 1088 3362 1927 3362 1926 3363 1927 3363 1925 3363 1925 3364 1927 3364 1853 3364 1925 3365 1853 3365 1854 3365 1903 3366 1862 3366 1861 3366 1904 3367 1903 3367 1931 3367 1903 3368 1861 3368 1931 3368 1931 3369 1861 3369 1859 3369 1931 3370 1859 3370 1932 3370 1932 3371 1859 3371 1858 3371 1932 3372 1858 3372 1933 3372 1933 3373 1858 3373 1855 3373 1933 3374 1855 3374 1856 3374 1904 3375 1931 3375 1928 3375 1928 3376 1931 3376 1932 3376 1928 3377 1932 3377 1929 3377 1929 3378 1932 3378 1933 3378 1929 3379 1933 3379 1930 3379 1930 3380 1933 3380 1856 3380 1930 3381 1856 3381 1852 3381 1066 3382 1860 3382 1862 3382 1862 3383 1901 3383 1066 3383 1066 3384 1901 3384 1915 3384 1066 3385 1915 3385 1067 3385 1860 3386 1066 3386 1934 3386 1934 3387 1066 3387 1069 3387 1934 3388 1069 3388 1906 3388 1934 3389 1906 3389 1905 3389 1905 3390 1935 3390 1934 3390 1934 3391 1935 3391 1857 3391 1934 3392 1857 3392 1860 3392 1936 3393 1937 3393 1938 3393 1939 3394 1940 3394 1907 3394 1912 3395 1941 3395 1911 3395 1911 3396 1941 3396 1937 3396 1911 3397 1937 3397 1910 3397 1910 3398 1937 3398 1936 3398 1910 3399 1936 3399 1909 3399 1909 3400 1936 3400 1939 3400 1909 3401 1939 3401 1908 3401 1908 3402 1939 3402 1907 3402 1863 3403 1857 3403 1935 3403 1905 3404 1907 3404 1935 3404 1935 3405 1907 3405 1940 3405 1935 3406 1940 3406 1863 3406 1863 3407 1940 3407 1939 3407 1863 3408 1939 3408 1864 3408 1864 3409 1939 3409 1936 3409 1864 3410 1936 3410 1865 3410 1865 3411 1936 3411 1938 3411 1865 3412 1938 3412 1866 3412 1912 3413 1913 3413 1941 3413 1941 3414 1913 3414 1942 3414 1941 3415 1942 3415 1937 3415 1937 3416 1942 3416 1938 3416 1938 3417 1942 3417 1869 3417 1938 3418 1869 3418 1866 3418 1847 3419 1846 3419 1943 3419 1943 3420 1116 3420 1115 3420 1850 3421 1847 3421 1921 3421 1921 3422 1847 3422 1943 3422 1921 3423 1943 3423 1944 3423 1944 3424 1943 3424 1115 3424 1944 3425 1115 3425 1112 3425 1868 3426 1874 3426 1945 3426 1875 3427 1871 3427 1870 3427 1875 3428 1870 3428 1946 3428 1946 3429 1870 3429 1867 3429 1946 3430 1867 3430 1947 3430 1947 3431 1867 3431 1868 3431 1947 3432 1868 3432 1948 3432 1948 3433 1868 3433 1945 3433 1948 3434 1945 3434 315 3434 315 3435 1945 3435 309 3435 309 3436 1945 3436 1949 3436 1950 3437 553 3437 1949 3437 1949 3438 553 3438 557 3438 1949 3439 557 3439 309 3439 1872 3440 1950 3440 1873 3440 1873 3441 1950 3441 1949 3441 1873 3442 1949 3442 1874 3442 1874 3443 1949 3443 1945 3443 1872 3444 1869 3444 1951 3444 1951 3445 1869 3445 1942 3445 1951 3446 1942 3446 1952 3446 1952 3447 1942 3447 1953 3447 1913 3448 1137 3448 1942 3448 1942 3449 1137 3449 1143 3449 1942 3450 1143 3450 1953 3450 1953 3451 1143 3451 1142 3451 1953 3452 1142 3452 1954 3452 1954 3453 1142 3453 1140 3453 1955 3454 1139 3454 559 3454 1954 3455 1140 3456 1139 3457 559 3458 558 3458 1955 3458 1955 3459 558 3459 556 3459 1955 3460 556 3460 1956 3460 1956 3461 556 3461 555 3461 1956 3462 555 3462 1957 3462 1957 3463 555 3463 554 3463 1957 3464 554 3464 1958 3464 1958 3465 554 3465 553 3465 1958 3466 553 3466 1950 3466 1139 3467 1955 3467 1954 3467 1954 3468 1955 3468 1956 3468 1954 3469 1956 3469 1953 3469 1953 3470 1956 3470 1957 3470 1953 3471 1957 3471 1952 3471 1952 3472 1957 3472 1958 3472 1952 3473 1958 3473 1951 3473 1951 3474 1958 3474 1950 3474 1951 3475 1950 3475 1872 3475 249 3476 248 3476 1959 3476 1959 3477 248 3477 195 3477 1959 3478 195 3478 1960 3478 1960 3479 195 3479 194 3479 1960 3480 194 3480 203 3480 1889 3481 1890 3481 252 3481 252 3482 251 3482 1889 3482 1889 3483 251 3483 250 3483 1889 3484 250 3484 1886 3484 1886 3485 250 3485 249 3485 1886 3486 249 3486 1885 3486 1885 3487 249 3487 1959 3487 1885 3488 1959 3488 1878 3488 1878 3489 1959 3489 1960 3489 1878 3490 1960 3490 1876 3490 1897 3491 247 3491 1893 3491 1893 3492 247 3492 255 3492 1893 3493 255 3493 1890 3493 1890 3494 255 3494 254 3494 1890 3495 254 3495 252 3495 1896 3496 244 3496 1897 3496 1897 3497 244 3497 246 3497 1897 3498 246 3498 247 3498 1894 3499 277 3499 1895 3499 1895 3500 277 3500 280 3500 1895 3501 280 3501 1896 3501 1896 3502 280 3502 279 3502 1896 3503 279 3503 244 3503 1891 3504 1888 3504 283 3504 283 3505 282 3505 1891 3505 1891 3506 282 3506 281 3506 1891 3507 281 3507 1892 3507 1892 3508 281 3508 276 3508 1892 3509 276 3509 1894 3509 1894 3510 276 3510 275 3510 1894 3511 275 3511 277 3511 1961 3512 313 3512 273 3512 1888 3513 1887 3513 283 3513 283 3514 1887 3514 1961 3514 283 3515 1961 3515 284 3515 284 3516 1961 3516 273 3516 1946 3517 1947 3517 1962 3517 1962 3518 1947 3518 1948 3518 313 3519 1961 3519 314 3519 314 3520 1961 3520 1963 3520 314 3521 1963 3521 317 3521 317 3522 1963 3522 1962 3522 317 3523 1962 3523 316 3523 316 3524 1962 3524 1948 3524 316 3525 1948 3525 315 3525 1875 3526 1946 3526 1877 3526 1877 3527 1946 3527 1962 3527 1877 3528 1962 3528 1879 3528 1879 3529 1962 3529 1963 3529 1887 3530 1884 3530 1961 3530 1961 3531 1884 3531 1883 3531 1961 3532 1883 3532 1963 3532 1963 3533 1883 3533 1880 3533 1963 3534 1880 3534 1879 3534 1964 3535 1965 3536 1966 3537 1966 3538 1965 3539 1967 3540 231 1679 1964 1679 1966 1679 231 1679 1966 1679 232 1679 232 1679 1966 1679 1967 1679 232 1679 1967 1679 245 1679 245 3541 1967 3542 253 3543 253 3544 1967 3545 1965 3546 253 3547 1965 3548 231 3549 231 3550 1965 3551 1964 3552 1968 3553 318 3553 337 3553 1968 3554 337 3554 1969 3554 1969 3555 337 3555 336 3555 1969 3556 336 3556 1970 3556 1970 3557 336 3557 335 3557 1970 3558 335 3558 1971 3558 1971 3559 335 3559 333 3559 1971 3560 333 3560 1972 3560 1972 3561 333 3561 331 3561 1972 3562 331 3562 1973 3562 1973 3563 331 3563 330 3563 1973 3564 330 3564 1974 3564 1974 3565 330 3565 327 3565 1974 3566 327 3566 1975 3566 1975 3567 327 3567 328 3567 1975 3568 328 3568 1976 3568 1976 3569 328 3569 329 3569 1976 3570 329 3570 1977 3570 1977 3571 329 3571 323 3571 1977 3572 323 3572 1978 3572 1978 3573 323 3573 1979 3573 1979 3574 323 3574 322 3574 1979 3575 322 3575 1980 3575 322 3576 326 3576 1980 3576 1980 3577 326 3577 325 3577 1980 3578 325 3578 1981 3578 1981 3579 325 3579 324 3579 1981 3580 324 3580 1982 3580 1982 3581 324 3581 321 3581 1982 3582 321 3582 1983 3582 1983 3583 321 3583 320 3583 1983 3584 320 3584 1984 3584 1984 3585 320 3585 318 3585 1984 3586 318 3586 1968 3586 1968 3587 1969 3587 1970 3587 1972 3588 1973 3588 1979 3588 1979 3589 1973 3589 1974 3589 1977 3590 1978 3590 1976 3590 1976 3591 1978 3591 1979 3591 1976 3592 1979 3592 1975 3592 1975 3593 1979 3593 1974 3593 1979 3594 1980 3594 1985 3594 1985 3595 1980 3595 1981 3595 1981 3596 1982 3596 1985 3596 1985 3597 1982 3597 1983 3597 1985 3598 1983 3598 1984 3598 1984 3599 1968 3599 1985 3599 1985 3600 1968 3600 1970 3600 1985 3601 1970 3601 1979 3601 1979 3602 1970 3602 1971 3602 1979 3603 1971 3603 1972 3603 332 2663 1986 2663 312 2663 312 2663 1986 2663 1987 2663 312 2663 1987 2663 311 2663 1988 3604 274 3604 272 3604 1988 3605 272 3605 1989 3605 1989 3606 272 3606 271 3606 1989 3607 271 3607 1990 3607 271 3608 308 3608 1990 3608 1990 3609 308 3609 307 3609 1990 3610 307 3610 1991 3610 1991 3611 307 3611 311 3611 1991 3612 311 3612 1987 3612 1992 3613 303 3613 301 3613 1992 3614 301 3614 1993 3614 1993 3615 301 3615 269 3615 1993 3616 269 3616 1994 3616 1994 3617 269 3617 270 3617 1994 3618 270 3618 1995 3618 1995 3619 270 3619 274 3619 1995 3620 274 3620 1988 3620 1996 1811 306 1811 1992 1811 1992 1811 306 1811 305 1811 1992 1811 305 1811 303 1811 1997 3621 293 3621 292 3621 1997 3622 292 3622 1998 3622 1998 3623 292 3623 299 3623 1998 3624 299 3624 1999 3624 1999 3625 299 3625 298 3625 1999 3626 298 3626 2000 3626 2000 3627 298 3627 306 3627 2000 3628 306 3628 1996 3628 1986 3629 332 3629 334 3629 296 3630 2001 3630 334 3630 334 3631 2001 3631 2002 3631 334 3632 2002 3632 1986 3632 296 3633 295 3633 2001 3633 2001 3634 295 3634 294 3634 2001 3635 294 3635 2003 3635 2003 3636 294 3636 293 3636 2003 3637 293 3637 1997 3637 1986 3638 2002 3638 1996 3638 1996 3639 2002 3639 2001 3639 2003 3640 1997 3640 2004 3640 2001 3641 2003 3641 1996 3641 1996 3642 2003 3642 2004 3642 1996 3643 2004 3643 2000 3643 1997 3644 1998 3644 2004 3644 2004 3645 1998 3645 1999 3645 2004 3646 1999 3646 2000 3646 1993 3647 1994 3647 1987 3647 1995 3648 1988 3648 2005 3648 1994 3649 1995 3649 1987 3649 1987 3650 1995 3650 2005 3650 1987 3651 2005 3651 1991 3651 1988 3652 1989 3652 2005 3652 2005 3653 1989 3653 1990 3653 2005 3654 1990 3654 1991 3654 1986 3655 1996 3655 1987 3655 1987 3656 1996 3656 1992 3656 1987 3657 1992 3657 1993 3657 2006 2663 302 2663 2007 2663 2007 2663 302 2663 304 2663 2007 2663 304 2663 297 2663 2008 3658 278 3658 268 3658 2008 3659 268 3659 2009 3659 2009 3660 268 3660 267 3660 2009 3661 267 3661 2010 3661 2010 3662 267 3662 300 3662 2010 3663 300 3663 2011 3663 2011 3664 300 3664 302 3664 2011 3665 302 3665 2006 3665 2012 3666 239 3666 235 3666 2012 3667 235 3667 2013 3667 2013 3668 235 3668 234 3668 2013 3669 234 3669 2014 3669 2014 3670 234 3670 233 3670 2014 3671 233 3671 2015 3671 2015 3672 233 3672 278 3672 2015 3673 278 3673 2008 3673 239 1811 2012 1811 265 1811 265 1811 2012 1811 2016 1811 265 1811 2016 1811 266 1811 2017 3674 287 3674 286 3674 2017 3675 286 3675 2018 3675 2018 3676 286 3676 285 3676 2018 3677 285 3677 2019 3677 2019 3678 285 3678 262 3678 2019 3679 262 3679 2020 3679 2020 3680 262 3680 266 3680 2020 3681 266 3681 2016 3681 2007 3682 297 3682 291 3682 2007 3683 291 3683 2021 3683 2021 3684 291 3684 290 3684 2021 3685 290 3685 2022 3685 2022 3686 290 3686 289 3686 2022 3687 289 3687 2023 3687 2023 3688 289 3688 287 3688 2023 3689 287 3689 2017 3689 2006 3690 2012 3690 2013 3690 2009 3691 2010 3691 2008 3691 2008 3692 2010 3692 2011 3692 2008 3693 2011 3693 2015 3693 2015 3694 2011 3694 2006 3694 2015 3695 2006 3695 2014 3695 2014 3696 2006 3696 2013 3696 2018 3697 2019 3697 2017 3697 2017 3698 2019 3698 2020 3698 2017 3699 2020 3699 2023 3699 2023 3700 2020 3700 2016 3700 2023 3701 2016 3701 2022 3701 2022 3702 2016 3702 2021 3702 2012 1741 2006 1741 2016 1741 2016 1741 2006 1741 2007 1741 2016 3703 2007 3703 2021 3703 263 2663 2024 2663 264 2663 264 2663 2024 2663 2025 2663 264 2663 2025 2663 240 2663 2026 3704 241 3704 237 3704 2026 3705 237 3705 2027 3705 2027 3706 237 3706 236 3706 2027 3707 236 3707 2028 3707 2028 3708 236 3708 238 3708 2028 3709 238 3709 2029 3709 2029 3710 238 3710 240 3710 2029 3711 240 3711 2025 3711 2030 3712 227 3712 229 3712 230 3713 2031 3713 229 3713 229 3714 2031 3714 2032 3714 229 3715 2032 3715 2030 3715 230 3716 243 3716 2031 3716 2031 3717 243 3717 242 3717 2031 3718 242 3718 2033 3718 2033 3719 242 3719 241 3719 2033 3720 241 3720 2026 3720 2034 1811 222 1811 2030 1811 2030 1811 222 1811 221 1811 2030 1811 221 1811 227 1811 2035 3721 257 3721 256 3721 2035 3722 256 3722 2036 3722 2036 3723 256 3723 216 3723 2036 3724 216 3724 2037 3724 216 3725 224 3725 2037 3725 2037 3726 224 3726 223 3726 2037 3727 223 3727 2038 3727 2038 3728 223 3728 222 3728 2038 3729 222 3729 2034 3729 2024 3730 263 3730 261 3730 2024 3731 261 3731 2039 3731 2039 3732 261 3732 260 3732 2039 3733 260 3733 2040 3733 2040 3734 260 3734 259 3734 2040 3735 259 3735 2041 3735 2041 3736 259 3736 257 3736 2041 3737 257 3737 2035 3737 2030 3738 2032 3738 2025 3738 2025 3739 2032 3739 2031 3739 2033 3740 2026 3740 2042 3740 2031 3741 2033 3741 2025 3741 2025 3742 2033 3742 2042 3742 2025 3743 2042 3743 2029 3743 2026 3744 2027 3744 2042 3744 2042 3745 2027 3745 2028 3745 2042 3746 2028 3746 2029 3746 2039 3747 2040 3747 2034 3747 2041 3748 2035 3748 2043 3748 2040 3749 2041 3749 2034 3749 2034 3750 2041 3750 2043 3750 2034 3751 2043 3751 2038 3751 2035 3752 2036 3752 2043 3752 2043 3753 2036 3753 2037 3753 2043 3754 2037 3754 2038 3754 2030 3755 2025 3755 2034 3755 2034 3756 2025 3756 2024 3756 2034 3757 2024 3757 2039 3757 219 2663 2044 2663 220 2663 220 2663 2044 2663 2045 2663 220 2663 2045 2663 225 2663 2046 3758 193 3758 196 3758 2046 3759 196 3759 2047 3759 2047 3760 196 3760 228 3760 2047 3761 228 3761 2048 3761 2048 3762 228 3762 226 3762 2048 3763 226 3763 2049 3763 2049 3764 226 3764 225 3764 2049 3765 225 3765 2045 3765 2050 3766 209 3766 208 3766 2050 3767 208 3767 2051 3767 2051 3768 208 3768 197 3768 2051 3769 197 3769 2052 3769 2052 3770 197 3770 199 3770 2052 3771 199 3771 2053 3771 2053 3772 199 3772 193 3772 2053 3773 193 3773 2046 3773 209 1811 2050 1811 211 1811 211 1811 2050 1811 2054 1811 211 1811 2054 1811 207 1811 2055 3774 213 3774 212 3774 2055 3775 212 3775 2056 3775 2056 3776 212 3776 205 3776 2056 3777 205 3777 2057 3777 2057 3778 205 3778 204 3778 2057 3779 204 3779 2058 3779 2058 3780 204 3780 207 3780 2058 3781 207 3781 2054 3781 2044 3782 219 3782 215 3782 2044 3783 215 3783 2059 3783 2059 3784 215 3784 217 3784 2059 3785 217 3785 2060 3785 2060 3786 217 3786 218 3786 2060 3787 218 3787 2061 3787 2061 3788 218 3788 213 3788 2061 3789 213 3789 2055 3789 2050 3790 2051 3790 2045 3790 2045 3791 2051 3791 2052 3791 2053 3792 2046 3792 2062 3792 2052 3793 2053 3793 2045 3793 2045 3794 2053 3794 2062 3794 2045 3795 2062 3795 2049 3795 2046 3796 2047 3796 2062 3796 2062 3797 2047 3797 2048 3797 2062 3798 2048 3798 2049 3798 2059 3799 2060 3799 2054 3799 2054 3800 2060 3800 2061 3800 2054 3801 2061 3801 2063 3801 2063 3802 2061 3802 2055 3802 2055 3803 2056 3803 2063 3803 2063 3804 2056 3804 2057 3804 2063 3805 2057 3805 2054 3805 2054 3806 2057 3806 2058 3806 2050 3807 2045 3807 2054 3807 2054 3808 2045 3808 2044 3808 2054 3809 2044 3809 2059 3809 2064 3810 2065 3810 2066 3810 2066 3811 2065 3811 2067 3811 2066 3812 2067 3812 1779 3812 1779 3813 2067 3813 2068 3813 2069 3814 2070 3814 1741 3814 2069 3815 1741 3815 2071 3815 2071 3816 1741 3816 1740 3816 2071 3817 1740 3817 2072 3817 2072 3818 1740 3818 1749 3818 2072 3819 1749 3819 2073 3819 2073 3820 1749 3820 2074 3820 2074 3821 1749 3821 1748 3821 2074 3822 1748 3822 2075 3822 2075 3823 1748 3823 2076 3823 2076 3824 1748 3824 1752 3824 2076 3825 1752 3825 2077 3825 1741 3826 2070 3826 1760 3826 1766 3827 1769 3827 2078 3827 1769 3828 1758 3828 2079 3828 1767 3829 1766 3829 1778 3829 1778 3830 1766 3830 2078 3830 1778 3831 2078 3831 1779 3831 1779 3832 2078 3832 2066 3832 1769 3833 2079 3833 2078 3833 2078 3834 2079 3834 2064 3834 2078 3835 2064 3835 2066 3835 1752 3836 1836 3836 2077 3836 1804 3837 2080 3837 1802 3837 1802 3838 2080 3838 2081 3838 1802 3839 2081 3839 1803 3839 2082 3840 2083 3840 2084 3840 2083 3841 2082 3841 2085 3841 2085 3842 2082 3842 2086 3842 2085 3843 2086 3843 2087 3843 1804 3844 2087 3844 2080 3844 2080 3845 2087 3845 2086 3845 2080 3846 2086 3846 2081 3846 2081 3847 2086 3847 2082 3847 2081 3848 2082 3848 2088 3848 2088 3849 2082 3849 2084 3849 2089 3850 2087 3850 1805 3850 1805 3851 2087 3851 1804 3851 2089 3852 2090 3852 2087 3852 2087 3853 2090 3853 2091 3853 2087 3854 2091 3854 2085 3854 2092 3855 2093 3855 2094 3855 1805 3856 1780 3856 2089 3856 2089 3857 1780 3857 2095 3857 2089 3858 2095 3858 2090 3858 2090 3859 2095 3859 2092 3859 2090 3860 2092 3860 2091 3860 2091 3861 2092 3861 2094 3861 2091 3862 2094 3862 2085 3862 2096 3863 2097 3863 2098 3863 1779 3864 2068 3864 2098 3864 2098 3865 2068 3865 2099 3865 2099 3866 2100 3866 2098 3866 2098 3867 2100 3867 2101 3867 2098 3868 2101 3868 2096 3868 1780 3869 1779 3869 2095 3869 2095 3870 1779 3870 2098 3870 2095 3871 2098 3871 2092 3871 2092 3872 2098 3872 2097 3872 2092 3873 2097 3873 2093 3873 2067 3874 2065 3874 2102 3874 2068 3875 2067 3875 2103 3875 2067 3876 2102 3876 2103 3876 2103 3877 2102 3877 2104 3877 2103 3878 2104 3878 2105 3878 2105 3879 2104 3879 2106 3879 2105 3880 2106 3880 2107 3880 2107 3881 2106 3881 2108 3881 2107 3882 2108 3882 2109 3882 2068 3883 2103 3883 2099 3883 2099 3884 2103 3884 2105 3884 2099 3885 2105 3885 2100 3885 2100 3886 2105 3886 2107 3886 2100 3887 2107 3887 2101 3887 2101 3888 2107 3888 2109 3888 2101 3889 2109 3889 2096 3889 1757 3890 2110 3890 2065 3890 2065 3891 2064 3891 1757 3891 1757 3892 2064 3892 2079 3892 1757 3893 2079 3893 1758 3893 2110 3894 1757 3894 2111 3894 2111 3895 1757 3895 1760 3895 2111 3896 1760 3896 2070 3896 2111 3897 2070 3897 2069 3897 2069 3898 2112 3898 2111 3898 2111 3899 2112 3899 2113 3899 2111 3900 2113 3900 2110 3900 2114 3901 2115 3901 2116 3901 2117 3902 2118 3902 2071 3902 2076 3903 2119 3903 2075 3903 2075 3904 2119 3904 2115 3904 2075 3905 2115 3905 2074 3905 2074 3906 2115 3906 2114 3906 2074 3907 2114 3907 2073 3907 2073 3908 2114 3908 2117 3908 2073 3909 2117 3909 2072 3909 2072 3910 2117 3910 2071 3910 2120 3911 2113 3911 2112 3911 2069 3912 2071 3912 2112 3912 2112 3913 2071 3913 2118 3913 2112 3914 2118 3914 2120 3914 2120 3915 2118 3915 2117 3915 2120 3916 2117 3916 2121 3916 2121 3917 2117 3917 2114 3917 2121 3918 2114 3918 2122 3918 2122 3919 2114 3919 2116 3919 2122 3920 2116 3920 2123 3920 2076 3921 2077 3921 2119 3921 2119 3922 2077 3922 2124 3922 2119 3923 2124 3923 2115 3923 2115 3924 2124 3924 2116 3924 2116 3925 2124 3925 2125 3925 2116 3926 2125 3926 2123 3926 2126 3927 2127 3927 2128 3927 2128 3928 1807 3928 1806 3928 2084 3929 2126 3929 2088 3929 2088 3930 2126 3930 2128 3930 2088 3931 2128 3931 2129 3931 2129 3932 2128 3932 1806 3932 2129 3933 1806 3933 1803 3933 2130 3934 2131 3934 2132 3934 2133 3935 2134 3935 2135 3935 2133 3936 2135 3936 2136 3936 2136 3937 2135 3937 2137 3937 2136 3938 2137 3938 2138 3938 2138 3939 2137 3939 2130 3939 2138 3940 2130 3940 2139 3940 2139 3941 2130 3941 2132 3941 2139 3942 2132 3942 583 3942 583 3943 2132 3943 2140 3943 2141 3944 577 3944 2140 3944 2140 3945 577 3945 584 3945 2140 3946 584 3946 583 3946 2142 3947 2141 3947 2143 3947 2143 3948 2141 3948 2140 3948 2143 3949 2140 3949 2131 3949 2131 3950 2140 3950 2132 3950 2142 3951 2125 3951 2144 3951 2144 3952 2125 3952 2124 3952 2144 3953 2124 3953 2145 3953 2145 3954 2124 3954 2146 3954 2077 3955 1836 3955 2124 3955 2124 3956 1836 3956 1842 3956 2124 3957 1842 3957 2146 3957 2146 3958 1842 3958 1841 3958 2146 3959 1841 3959 2147 3959 2147 3960 1841 3960 1839 3960 2148 3961 1838 3961 580 3961 2147 3962 1839 3962 1838 3962 580 3963 575 3963 2148 3963 2148 3964 575 3964 574 3964 2148 3965 574 3965 2149 3965 2149 3966 574 3966 579 3966 2149 3967 579 3967 2150 3967 2150 3968 579 3968 578 3968 2150 3969 578 3969 2151 3969 2151 3970 578 3970 577 3970 2151 3971 577 3971 2141 3971 1838 3972 2148 3972 2147 3972 2147 3973 2148 3973 2149 3973 2147 3974 2149 3974 2146 3974 2146 3975 2149 3975 2150 3975 2146 3976 2150 3976 2145 3976 2145 3977 2150 3977 2151 3977 2145 3978 2151 3978 2144 3978 2144 3979 2151 3979 2141 3979 2144 3980 2141 3980 2142 3980 2152 3981 2127 3981 2153 3981 2153 3982 2127 3982 2126 3982 2153 3983 2126 3983 2154 3983 2085 3984 2155 3984 2083 3984 2083 3985 2155 3985 2084 3985 2084 3986 2155 3986 2126 3986 2126 3987 2155 3987 2156 3987 2126 3988 2156 3988 2154 3988 2155 3989 2085 3989 2094 3989 2096 3990 2157 3990 2097 3990 2097 3991 2157 3991 2158 3991 2097 3992 2158 3992 2159 3992 2094 3993 2093 3993 2155 3993 2155 3994 2093 3994 2097 3994 2155 3995 2097 3995 2160 3995 2160 3996 2097 3996 2159 3996 2108 3997 2161 3997 2109 3997 2109 3998 2161 3998 2162 3998 2109 3999 2162 3999 2096 3999 2096 3999 2162 3999 2157 3999 2163 4000 2164 4000 2165 4000 2165 4001 2164 4001 2166 4001 2165 4002 2166 4002 2167 4002 2108 4003 2113 4003 2161 4003 2161 4004 2113 4004 2167 4004 2161 4005 2167 4005 2168 4005 2168 4006 2167 4006 2166 4006 2108 4007 2106 4007 2113 4007 2113 4008 2106 4008 2104 4008 2113 4009 2104 4009 2110 4009 2110 4010 2104 4010 2102 4010 2110 4011 2102 4011 2065 4011 2167 4012 2113 4012 2120 4012 2167 4013 2120 4013 2169 4013 2169 4014 2120 4014 2121 4014 2169 4015 2121 4015 2170 4015 2170 4016 2121 4016 2122 4016 2170 4017 2122 4017 2171 4017 2171 4018 2122 4018 2123 4018 2171 4019 2123 4019 2172 4019 2137 4020 2123 4020 2130 4020 2130 4021 2123 4021 2125 4021 2142 4022 2143 4022 2125 4022 2125 4023 2143 4023 2131 4023 2125 4024 2131 4024 2130 4024 2173 4025 2172 4025 2134 4025 2134 4026 2172 4026 2123 4026 2134 4027 2123 4027 2135 4027 2135 4028 2123 4028 2137 4028 2173 4029 2174 4029 2172 4029 2172 4030 2174 4030 2175 4030 2172 4031 2175 4031 2176 4031 2176 4032 2175 4032 2177 4032 2177 4033 2178 4033 2176 4033 2176 4034 2178 4034 2179 4034 2176 4035 2179 4035 2180 4035 2133 4036 2181 4036 2134 4036 2134 4037 2181 4037 2173 4037 2181 4038 2133 4038 2182 4038 2183 4039 2184 4039 2185 4039 2181 4040 2182 4040 2185 4040 2185 4041 2182 4041 2186 4041 2185 4042 2186 4042 2183 4042 2187 4043 2188 4043 2184 4043 2184 4044 2188 4044 2189 4044 2184 4045 2189 4045 2185 4045 2190 4046 2191 4046 2192 4046 2187 4047 2184 4047 2191 4047 2191 4048 2184 4048 2193 4048 2191 4049 2193 4049 2192 4049 2190 4050 2192 4050 2194 4050 2194 4051 2192 4051 2195 4051 2194 4052 2195 4052 2196 4052 2197 4053 2198 4053 2199 4053 2199 4054 2198 4054 2200 4054 2197 4055 2201 4055 2198 4055 2198 4056 2201 4056 2202 4056 2198 4057 2202 4057 2196 4057 2196 4058 2202 4058 2203 4058 2196 4059 2203 4059 2194 4059 2136 4060 2138 4060 2204 4060 2204 4061 2138 4061 2139 4061 135 4062 2205 4062 136 4062 136 4063 2205 4063 2206 4063 136 4064 2206 4064 128 4064 128 4065 2206 4065 2204 4065 128 4066 2204 4066 585 4066 585 4067 2204 4067 2139 4067 585 4068 2139 4068 583 4068 2205 4069 2183 4069 2206 4069 2206 4070 2183 4070 2186 4070 2206 4071 2186 4071 2204 4071 2204 4072 2186 4072 2182 4072 2204 4073 2182 4073 2136 4073 2136 4074 2182 4074 2133 4074 1492 4075 2207 4075 2208 4075 2208 4076 2207 4076 2209 4076 2208 4077 2209 4077 2210 4077 2210 4078 2209 4078 2163 4078 2211 4079 1456 4079 2212 4079 2212 4080 1456 4080 1455 4080 2212 4081 1455 4081 2213 4081 2213 4082 1455 4082 1453 4082 2213 4083 1453 4083 2214 4083 2214 4084 1453 4084 1441 4084 2214 4085 1441 4085 2215 4085 2215 4086 1441 4086 2216 4086 2216 4087 1441 4087 1440 4087 2216 4088 1440 4088 2217 4088 1465 4089 2217 4089 1440 4089 1470 4090 1474 4090 1490 4090 1471 4091 2218 4091 1463 4091 1463 4092 2218 4092 2219 4092 1490 4093 1492 4093 2208 4093 2210 4094 2219 4094 2208 4094 2208 4095 2219 4095 2218 4095 2208 4096 2218 4096 1490 4096 1490 4097 2218 4097 1471 4097 1490 4098 1471 4098 1470 4098 2211 4099 1537 4099 1456 4099 2220 4100 2154 4100 2156 4100 2221 4101 2222 4101 1493 4101 1493 4102 2222 4102 1494 4102 2221 4103 2223 4103 2222 4103 2222 4104 2223 4104 2224 4104 2222 4105 2224 4105 2155 4105 1493 4106 1497 4106 2221 4106 2221 4107 1497 4107 2225 4107 2221 4108 2225 4108 2223 4108 2223 4109 2225 4109 2220 4109 2223 4110 2220 4110 2224 4110 2224 4111 2220 4111 2156 4111 2224 4112 2156 4112 2155 4112 2226 4113 2222 4113 2155 4113 2227 4114 2228 4114 1495 4114 1495 4115 2228 4115 1491 4115 2226 4116 2155 4116 2229 4116 2229 4117 2155 4117 2160 4117 2229 4118 2160 4118 2159 4118 2159 4119 2230 4119 2229 4119 2229 4120 2230 4120 2228 4120 2229 4121 2228 4121 2226 4121 2226 4122 2228 4122 2227 4122 2226 4123 2227 4123 2222 4123 2222 4124 2227 4124 1495 4124 2222 4125 1495 4125 1494 4125 2230 4126 2159 4126 2158 4126 2231 4127 2207 4127 2228 4127 2228 4128 2207 4128 1492 4128 2228 4129 1492 4129 1491 4129 2232 4130 2233 4130 2231 4130 2231 4131 2233 4131 2234 4131 2231 4132 2234 4132 2207 4132 2228 4133 2230 4133 2231 4133 2231 4134 2230 4134 2158 4134 2231 4135 2158 4135 2232 4135 2232 4136 2158 4136 2157 4136 2209 4137 2207 4137 2234 4137 2163 4138 2209 4138 2235 4138 2209 4139 2234 4139 2235 4139 2235 4140 2234 4140 2233 4140 2235 4141 2233 4141 2236 4141 2236 4142 2233 4142 2232 4142 2236 4143 2232 4143 2237 4143 2237 4144 2232 4144 2157 4144 2237 4145 2157 4145 2162 4145 2163 4146 2235 4146 2164 4146 2164 4147 2235 4147 2236 4147 2164 4148 2236 4148 2166 4148 2166 4149 2236 4149 2237 4149 2166 4150 2237 4150 2168 4150 2168 4151 2237 4151 2162 4151 2168 4152 2162 4152 2161 4152 2210 4153 1464 4153 2219 4153 2219 4154 1464 4154 1463 4154 2217 4155 1465 4155 2238 4155 2238 4156 1465 4156 1464 4156 2238 4157 1464 4157 2165 4157 2165 4158 1464 4158 2210 4158 2165 4159 2210 4160 2163 4161 2238 4162 2165 4162 2167 4162 2167 4163 2239 4163 2238 4163 2238 4164 2239 4164 2216 4164 2238 4165 2216 4165 2217 4165 2240 4166 2239 4166 2167 4166 2241 4167 2242 4167 2243 4167 2243 4168 2242 4168 2244 4168 2216 4169 2239 4169 2215 4169 2215 4170 2239 4170 2240 4170 2215 4171 2240 4171 2214 4171 2214 4172 2240 4172 2244 4172 2214 4173 2244 4173 2213 4173 2213 4174 2244 4174 2242 4174 2213 4175 2242 4175 2212 4175 2171 4176 2172 4176 2245 4176 2167 4177 2169 4177 2240 4177 2240 4178 2169 4178 2170 4178 2240 4179 2170 4179 2244 4179 2244 4180 2170 4180 2171 4180 2244 4181 2171 4181 2243 4181 2243 4182 2171 4182 2245 4182 2243 4183 2245 4183 2241 4183 2172 4184 2176 4184 2245 4184 2245 4185 2176 4185 2246 4185 2245 4186 2246 4186 2241 4186 2241 4187 2246 4187 2242 4187 2242 4188 2246 4188 2211 4188 2242 4189 2211 4189 2212 4189 2247 4190 2152 4190 2153 4190 2153 4191 2154 4191 2220 4191 2248 4192 1497 4192 1512 4192 2153 4193 2220 4193 2247 4193 2247 4194 2220 4194 2248 4194 2247 4195 2248 4195 2249 4195 2249 4196 2248 4196 1512 4196 2249 4197 1512 4197 1514 4197 2250 4198 2178 4198 2177 4198 2173 4199 2181 4199 2251 4199 2173 4200 2251 4200 2174 4200 2174 4201 2251 4201 2252 4201 2174 4202 2252 4202 2175 4202 2175 4203 2252 4203 2253 4203 2175 4204 2253 4204 2177 4204 2177 4205 2253 4205 73 4205 2177 4206 73 4206 2250 4206 2179 4207 2254 4207 2180 4207 2180 4208 2254 4208 2255 4208 2250 4209 73 4209 72 4209 75 4210 2255 4210 72 4210 72 4211 2255 4211 2254 4211 72 4212 2254 4212 2250 4212 2250 4213 2254 4213 2179 4213 2250 4214 2179 4214 2178 4214 2246 4215 2176 4215 2180 4215 2180 4216 2256 4216 2246 4216 2246 4217 2256 4217 2257 4217 2246 4218 2257 4218 2258 4218 2259 4219 1533 4219 1539 4219 2259 4220 1539 4220 2258 4220 2258 4221 1539 4221 1538 4221 2258 4222 1538 4222 2246 4222 2246 4223 1538 4223 1537 4223 2246 4224 1537 4224 2211 4224 2260 4225 1534 4225 1533 4225 589 4226 586 4226 1534 4226 1533 4227 2259 4227 2260 4227 2260 4228 2259 4228 2258 4228 2260 4229 2258 4229 2261 4229 2261 4230 2258 4230 2257 4230 2261 4231 2257 4231 2262 4231 2262 4232 2257 4232 2256 4232 2262 4233 2256 4233 2263 4233 2263 4234 2256 4234 2180 4234 2263 4235 2180 4235 2255 4235 1534 4236 2260 4236 589 4236 589 4237 2260 4237 2261 4237 589 4238 2261 4238 590 4238 590 4239 2261 4239 2262 4239 590 4240 2262 4240 591 4240 591 4241 2262 4241 2263 4241 591 4242 2263 4242 592 4242 592 4243 2263 4243 2255 4243 592 4244 2255 4244 75 4244 132 4245 2264 4245 133 4245 79 4246 74 4246 2265 4246 2265 4247 2252 4247 2251 4247 74 4248 73 4248 2265 4248 2265 4249 73 4249 2253 4249 2265 4250 2253 4250 2252 4250 106 4251 2266 4251 95 4251 95 4252 2266 4252 2267 4252 95 4253 2267 4253 96 4253 2191 4254 92 4254 2267 4254 2267 4255 92 4255 93 4255 2267 4256 93 4256 96 4256 2191 4257 2190 4257 92 4257 92 4258 2190 4258 2194 4258 92 4259 2194 4259 90 4259 90 4260 2194 4260 2203 4260 2201 4261 164 4261 2202 4261 2202 4262 164 4262 163 4262 2202 4263 163 4263 2203 4263 2203 4264 163 4264 87 4264 2203 4265 87 4265 90 4265 2197 4266 167 4266 2201 4266 2201 4267 167 4267 166 4267 2201 4268 166 4268 164 4268 178 4269 177 4269 2200 4269 2200 4270 177 4270 158 4270 2200 4271 158 4271 2199 4271 2199 4272 158 4272 160 4272 2199 4273 160 4273 2197 4273 2197 4274 160 4274 162 4274 2197 4275 162 4275 167 4275 178 4276 2200 4276 179 4276 179 4277 2200 4277 2198 4277 179 4278 2198 4278 182 4278 182 4279 2198 4279 2196 4279 182 4280 2196 4280 139 4280 139 4281 2196 4281 2195 4281 139 4282 2195 4282 137 4282 133 4283 2264 4283 134 4283 134 4284 2264 4284 2268 4284 134 4285 2268 4285 135 4285 137 4286 2195 4286 132 4286 132 4287 2195 4287 2192 4287 132 4288 2192 4288 2264 4288 2264 4289 2192 4289 2193 4289 2264 4290 2193 4290 2268 4290 2268 4291 2193 4291 2184 4291 2268 4292 2184 4292 2183 4292 106 4293 79 4293 2266 4293 2266 4294 79 4294 2265 4294 2266 4295 2265 4295 2185 4295 2185 4296 2265 4296 2251 4296 2185 4297 2251 4297 2181 4297 2185 4298 2189 4298 2266 4298 2266 4299 2189 4299 2188 4299 2266 4300 2188 4300 2267 4300 2267 4301 2188 4301 2187 4301 2267 4302 2187 4302 2191 4302 2269 4303 2270 4304 2271 4305 2271 4306 2270 4307 2272 4308 176 1679 2269 1679 175 1679 175 4309 2269 4309 2271 4309 175 1679 2271 1679 173 1679 173 4310 2271 4310 2272 4310 173 4311 2272 4312 2270 4313 173 4314 2270 4315 180 4316 180 4317 2270 4318 2269 4319 180 4320 2269 4321 176 4322 66 4323 2273 4323 2274 4323 66 4324 2274 4324 67 4324 67 4325 2274 4325 2275 4325 67 4326 2275 4326 69 4326 69 4327 2275 4327 2276 4327 69 4328 2276 4328 70 4328 70 4329 2276 4329 720 4329 70 4330 720 4330 112 4330 2277 4331 2278 4331 2279 4331 2279 4332 2278 4332 2280 4332 2280 4333 2281 4333 2279 4333 2279 4334 2281 4334 2282 4334 2279 4335 2282 4335 2283 4335 2284 4336 2277 4336 2285 4336 2285 4337 2277 4337 2279 4337 2285 4338 2279 4338 2286 4338 2286 4339 2279 4339 2287 4339 2283 4340 724 4340 2279 4340 2279 4341 724 4341 2273 4341 2279 4342 2273 4342 2287 4342 722 4343 2288 4343 723 4343 723 4344 2288 4344 724 4344 2274 4345 2273 4345 2275 4345 2275 4346 2273 4346 724 4346 2275 4347 724 4347 2276 4347 2276 4348 724 4348 2288 4348 2276 4349 2288 4349 720 4349 720 4350 2288 4350 722 4350 720 4351 722 4351 721 4351 2289 1741 109 1741 2290 1741 2290 4352 109 4352 99 4352 2290 1741 99 1741 100 1741 91 4353 2291 4353 2292 4353 91 4354 2292 4354 94 4354 94 4355 2292 4355 2293 4355 94 4356 2293 4356 105 4356 105 4357 2293 4357 2294 4357 105 4358 2294 4358 103 4358 103 4359 2294 4359 2290 4359 103 4360 2290 4360 100 4360 85 4361 2295 4361 2296 4361 85 4362 2296 4362 86 4362 86 4363 2296 4363 2297 4363 86 4364 2297 4364 88 4364 88 4365 2297 4365 2298 4365 88 4366 2298 4366 89 4366 89 4367 2298 4367 2291 4367 89 4368 2291 4368 91 4368 122 1723 2299 1723 124 1723 124 1723 2299 1723 2295 1723 124 1723 2295 1723 85 1723 118 4369 2300 4369 2301 4369 118 4370 2301 4370 119 4370 119 4371 2301 4371 2302 4371 119 4372 2302 4372 120 4372 120 4373 2302 4373 2303 4373 120 4374 2303 4374 121 4374 121 4375 2303 4375 2299 4375 121 4376 2299 4376 122 4376 109 4377 2289 4377 2304 4377 109 4378 2304 4378 107 4378 107 4379 2304 4379 2305 4379 107 4380 2305 4380 115 4380 115 4381 2305 4381 2306 4381 115 4382 2306 4382 116 4382 116 4383 2306 4383 2300 4383 116 4384 2300 4384 118 4384 2299 4385 2289 4385 2295 4385 2295 4386 2289 4386 2290 4386 2293 4387 2307 4387 2294 4387 2294 4388 2307 4388 2290 4388 2296 4389 2295 4389 2297 4389 2297 4390 2295 4390 2290 4390 2297 4391 2290 4391 2298 4391 2298 4392 2290 4392 2307 4392 2298 4393 2307 4393 2291 4393 2291 4394 2307 4394 2293 4394 2291 4395 2293 4395 2292 4395 2302 4396 2308 4396 2303 4396 2303 4397 2308 4397 2299 4397 2304 4398 2289 4398 2305 4398 2305 4399 2289 4399 2299 4399 2305 4400 2299 4400 2306 4400 2306 4401 2299 4401 2308 4401 2306 4402 2308 4402 2300 4402 2300 4403 2308 4403 2302 4403 2300 4404 2302 4404 2301 4404 170 1741 2309 1741 185 1741 185 1741 2309 1741 2310 1741 185 1741 2310 1741 184 1741 161 4405 2311 4405 2312 4405 161 4406 2312 4406 165 4406 165 4407 2312 4407 2313 4407 165 4408 2313 4408 168 4408 168 4409 2313 4409 2314 4409 168 4410 2314 4410 169 4410 169 4411 2314 4411 2309 4411 169 4412 2309 4412 170 4412 171 4413 2315 4413 2316 4413 171 4414 2316 4414 172 4414 172 4415 2316 4415 2317 4415 172 4416 2317 4416 174 4416 174 4417 2317 4417 2318 4417 174 4418 2318 4418 159 4418 159 4419 2318 4419 2311 4419 159 4420 2311 4420 161 4420 2315 1723 171 1723 2319 1723 2319 4421 171 4421 181 4421 2319 1723 181 1723 192 1723 188 4422 2320 4422 2321 4422 188 4423 2321 4423 189 4423 189 4424 2321 4424 2322 4424 189 4425 2322 4425 190 4425 190 4426 2322 4426 2323 4426 190 4427 2323 4427 191 4427 191 4428 2323 4428 2319 4428 191 4429 2319 4429 192 4429 184 4430 2310 4430 2324 4430 184 4431 2324 4431 183 4431 183 4432 2324 4432 2325 4432 183 4433 2325 4433 186 4433 186 4434 2325 4434 2326 4434 186 4435 2326 4435 187 4435 187 4436 2326 4436 2320 4436 187 4437 2320 4437 188 4437 2309 2663 2315 2663 2310 2663 2310 2663 2315 2663 2319 2663 2323 4438 2322 4438 2321 4438 2324 4439 2310 4439 2325 4439 2325 4440 2310 4440 2319 4440 2325 4441 2319 4441 2326 4441 2326 4442 2319 4442 2323 4442 2326 4443 2323 4443 2320 4443 2320 4444 2323 4444 2321 4444 2314 4445 2313 4445 2312 4445 2316 4446 2315 4446 2317 4446 2317 4447 2315 4447 2309 4447 2317 4448 2309 4448 2318 4448 2318 4449 2309 4449 2314 4449 2318 4450 2314 4450 2311 4450 2311 4451 2314 4451 2312 4451 2327 1741 150 1741 2328 1741 2328 4452 150 4452 149 4452 2328 1741 149 1741 143 1741 138 4453 2329 4453 2330 4453 138 4454 2330 4454 140 4454 140 4455 2330 4455 2331 4455 140 4456 2331 4456 141 4456 141 4457 2331 4457 2332 4457 141 4458 2332 4458 142 4458 142 4459 2332 4459 2328 4459 142 4460 2328 4460 143 4460 127 4461 2333 4461 2334 4461 127 4462 2334 4462 129 4462 129 4463 2334 4463 2335 4463 129 4464 2335 4464 130 4464 130 4465 2335 4465 2336 4465 130 4466 2336 4466 131 4466 131 4467 2336 4467 2329 4467 131 4468 2329 4468 138 4468 145 1723 2337 1723 126 1723 126 1723 2337 1723 2333 1723 126 1723 2333 1723 127 1723 155 4469 2338 4469 2339 4469 155 4470 2339 4470 156 4470 156 4471 2339 4471 2340 4471 156 4472 2340 4472 157 4472 157 4473 2340 4473 2341 4473 157 4474 2341 4474 147 4474 147 4475 2341 4475 2337 4475 147 4476 2337 4476 145 4476 150 4477 2327 4477 2342 4477 150 4478 2342 4478 152 4478 152 4479 2342 4479 2343 4479 152 4480 2343 4480 153 4480 153 4481 2343 4481 2344 4481 153 4482 2344 4482 154 4482 154 4483 2344 4483 2338 4483 154 4484 2338 4484 155 4484 2328 4485 2333 4485 2327 4485 2327 4486 2333 4486 2337 4486 2340 4487 2345 4487 2341 4487 2341 4488 2345 4488 2337 4488 2342 4489 2327 4489 2343 4489 2343 4490 2327 4490 2337 4490 2343 4491 2337 4491 2344 4491 2344 4492 2337 4492 2345 4492 2344 4493 2345 4493 2338 4493 2338 4494 2345 4494 2340 4494 2338 4495 2340 4495 2339 4495 2331 4496 2346 4496 2332 4496 2332 4497 2346 4497 2328 4497 2334 4498 2333 4498 2335 4498 2335 4499 2333 4499 2328 4499 2335 4500 2328 4500 2336 4500 2336 4501 2328 4501 2346 4501 2336 4502 2346 4502 2329 4502 2329 4503 2346 4503 2331 4503 2329 4504 2331 4504 2330 4504 653 4505 2347 4505 2348 4505 653 4506 2348 4506 655 4506 655 4507 2348 4507 2349 4507 655 4508 2349 4508 656 4508 656 4509 2349 4509 2350 4509 656 4510 2350 4510 657 4510 657 4511 2350 4511 2351 4511 657 4512 2351 4512 658 4512 146 4513 2352 4513 2353 4513 146 4514 2353 4514 148 4514 148 4515 2353 4515 2354 4515 148 4516 2354 4516 6 4516 6 4517 2354 4517 7 4517 7 4518 2354 4518 2355 4518 7 4519 2355 4519 652 4519 652 4520 2355 4520 2347 4520 652 4521 2347 4521 653 4521 2347 4522 2355 4522 2356 4522 2356 4523 2355 4523 2357 4523 2354 4524 2353 4524 2355 4524 2355 4525 2353 4525 2352 4525 2358 4526 2357 4526 2359 4526 2359 4527 2357 4527 2355 4527 2359 4528 2355 4528 2360 4528 2360 4529 2355 4529 2352 4529 2361 4530 2362 4530 2356 4530 2356 4531 2362 4531 2351 4531 2356 4532 2351 4532 2350 4532 2350 4533 2349 4533 2356 4533 2356 4534 2349 4534 2348 4534 2356 4535 2348 4535 2347 4535 661 4536 2357 4536 662 4536 662 4537 2357 4537 2358 4537 662 4538 2358 4538 663 4538 663 4539 2358 4539 2359 4539 663 4540 2359 4540 664 4540 664 4541 2359 4541 2360 4541 664 4542 2360 4542 665 4542 665 4543 2360 4543 2352 4543 665 4544 2352 4544 146 4544 658 4545 2351 4545 659 4545 659 4546 2351 4546 2362 4546 659 4547 2362 4547 660 4547 660 4548 2362 4548 666 4548 666 4549 2362 4549 2361 4549 666 4550 2361 4550 667 4550 667 4551 2361 4551 2356 4551 667 4552 2356 4552 668 4552 668 4553 2356 4553 2357 4553 668 4554 2357 4554 661 4554 110 1723 724 1723 111 1723 111 4555 724 4555 2283 4555 111 1723 2283 1723 97 1723 2287 4556 83 4556 2286 4556 2286 4557 83 4557 81 4557 2286 4558 81 4558 2285 4558 81 4559 80 4559 2285 4559 2285 4560 80 4560 76 4560 2285 4561 76 4561 2284 4561 2284 4562 76 4562 77 4562 2284 4563 77 4563 2277 4563 2277 4564 77 4564 78 4564 2277 4565 78 4565 2278 4565 2278 4566 78 4566 104 4566 2278 4567 104 4567 2280 4567 2280 4568 104 4568 102 4568 2280 4569 102 4569 2281 4569 2281 4570 102 4570 101 4570 2281 4571 101 4571 2282 4571 2282 4572 101 4572 98 4572 2282 4573 98 4573 2283 4573 2283 4574 98 4574 97 4574 83 1741 2287 1741 84 1741 84 1741 2287 1741 2273 1741 84 1741 2273 1741 66 1741 674 4575 702 4575 711 4575 674 4576 711 4576 672 4576 672 4577 711 4577 710 4577 672 4578 710 4578 673 4578 673 4579 710 4579 682 4579 682 4580 710 4580 709 4580 682 4581 709 4581 683 4581 683 4582 709 4582 684 4582 684 4583 709 4583 708 4583 684 4584 708 4584 678 4584 678 4585 708 4585 706 4585 678 4586 706 4586 679 4586 679 4587 706 4587 705 4587 679 4588 705 4588 680 4588 680 4589 705 4589 681 4589 681 4590 705 4590 704 4590 681 4591 704 4591 504 4591 504 4592 704 4592 505 4592 505 4593 704 4593 703 4593 505 4594 703 4594 506 4594 1168 1741 52 1741 701 1741 701 1741 52 1741 51 1741 52 4595 1168 4595 41 4595 41 4596 1168 4596 1167 4596 41 4597 1167 4597 42 4597 42 4598 1167 4598 1166 4598 42 4599 1166 4599 43 4599 43 4600 1166 4600 1165 4600 43 4601 1165 4601 45 4601 45 4602 1165 4602 1163 4602 45 4603 1163 4603 25 4603 25 4604 1163 4604 1162 4604 25 4605 1162 4605 26 4605 26 4606 1162 4606 1169 4606 26 4607 1169 4607 17 4607 17 4608 1169 4608 1170 4608 17 4609 1170 4609 18 4609 18 4610 1170 4610 1171 4610 18 4611 1171 4611 19 4611 19 4612 1171 4612 1172 4612 19 4613 1172 4613 12 4613 1172 1723 1158 1723 12 1723 12 1723 1158 1723 9 1723 1042 4614 2363 4614 2364 4614 2365 4615 924 4615 1038 4615 2365 4616 1038 4616 2364 4616 2364 4617 1038 4618 1041 4619 2364 4620 1041 4620 1042 4620 2363 4621 1042 4621 1118 4621 2363 4622 1118 4622 2366 4622 2366 4623 1118 4623 1117 4623 2366 4624 1117 4624 2367 4624 2367 4625 1117 4625 1116 4625 2367 4626 1116 4626 2368 4626 2368 4627 1116 4627 1943 4627 2368 4628 1943 4628 2369 4628 2369 4629 1943 4629 1846 4629 2369 4630 1846 4630 2370 4630 2371 1741 2370 1741 1728 1741 1728 1741 2370 1741 1846 1741 1733 4631 2372 4631 2373 4631 2371 4632 1728 4632 1727 4632 2371 4633 1727 4633 2373 4633 2373 4634 1727 4635 1732 4636 2373 4637 1732 4637 1733 4637 2372 4638 1733 4638 1809 4638 2372 4639 1809 4639 2374 4639 2374 4640 1809 4640 1808 4640 2374 4641 1808 4641 2375 4641 2375 4642 1808 4642 1807 4642 2375 4643 1807 4643 2376 4643 2376 4644 1807 4644 2128 4644 2376 4645 2128 4645 2377 4645 2377 4646 2128 4646 2127 4646 2377 4647 2127 4647 2378 4647 2379 2663 2378 2663 2152 2663 2152 2663 2378 2663 2127 2663 1514 4648 2380 4648 2381 4648 2379 4649 2152 4649 2247 4649 2379 4650 2247 4650 2381 4650 2381 4651 2247 4652 2249 4653 2381 4654 2249 4654 1514 4654 2380 4655 1514 4655 1513 4655 2380 4656 1513 4656 2382 4656 2382 4657 1513 4657 1511 4657 2382 4658 1511 4658 2383 4658 2383 4659 1511 4659 1436 4659 2383 4660 1436 4660 2384 4660 2384 4661 1436 4661 1435 4661 2384 4662 1435 4662 2385 4662 2385 4663 1435 4663 1319 4663 2385 4664 1319 4664 2386 4664 2387 1723 2386 1723 1293 1723 1293 1723 2386 1723 1319 1723 887 4665 2388 4665 2389 4665 2387 4666 1293 4666 1292 4666 2387 4667 1292 4667 2389 4667 2389 4668 1292 4669 1296 4670 2389 4671 1296 4671 887 4671 2388 4672 887 4672 886 4672 2388 4673 886 4673 2390 4673 2390 4674 886 4674 884 4674 2390 4675 884 4675 2391 4675 2391 4676 884 4676 809 4676 2391 4677 809 4677 2392 4677 2392 4678 809 4678 808 4678 2392 4679 808 4679 2393 4679 2393 4680 808 4680 807 4680 2393 4681 807 4681 2394 4681 2365 1811 2394 1811 924 1811 924 1811 2394 1811 807 1811 2395 1679 2396 1679 2370 1679 2370 4682 2371 4682 2395 4682 2395 4683 2371 4683 2373 4683 2395 1679 2373 1679 2397 1679 2398 1679 2399 1679 2400 1679 2400 1679 2399 1679 2401 1679 2402 1679 2403 1679 2404 1679 2404 4684 2403 4684 2405 4684 2404 1679 2405 1679 2406 1679 2406 4685 2405 4685 2407 4685 2406 1679 2407 1679 2408 1679 2370 1679 2409 1679 2369 1679 2369 1679 2409 1679 2410 1679 2411 1679 2383 1679 2412 1679 2412 1679 2383 1679 2384 1679 2412 1679 2384 1679 2413 1679 2414 1679 2367 1679 2410 1679 2410 4686 2367 4686 2368 4686 2410 4687 2368 4687 2369 4687 2384 1679 2385 1679 2413 1679 2413 4688 2385 4688 2386 4688 2413 1679 2386 1679 2398 1679 2398 1679 2386 1679 2387 1679 2398 4689 2387 4689 2399 4689 2399 4690 2387 4690 2389 4690 2399 1679 2389 1679 2415 1679 2416 1679 2379 1679 2417 1679 2417 4691 2379 4691 2381 4691 2417 1679 2381 1679 2418 1679 2418 4692 2381 4692 2380 4692 2418 4693 2380 4693 2411 4693 2411 1679 2380 1679 2382 1679 2411 4694 2382 4694 2383 4694 2419 1679 2420 1679 2421 1679 2421 1679 2420 1679 2422 1679 2408 1679 2423 1679 2406 1679 2406 1679 2423 1679 2363 1679 2406 4695 2363 4695 2414 4695 2414 4696 2363 4696 2366 4696 2414 1679 2366 1679 2367 1679 2389 1679 2388 1679 2415 1679 2415 4697 2388 4697 2390 4697 2415 1679 2390 1679 2424 1679 2424 1679 2390 1679 2391 1679 2424 1679 2391 1679 2425 1679 2425 1679 2391 1679 2392 1679 2392 1679 2393 1679 2425 1679 2425 4698 2393 4698 2394 4698 2425 4699 2394 4699 2426 4699 2426 1679 2394 1679 2365 1679 2426 4700 2365 4700 2423 4700 2423 4701 2365 4701 2364 4701 2423 4702 2364 4702 2363 4702 2427 1679 2379 1679 2421 1679 2421 1679 2379 1679 2416 1679 2421 4703 2416 4703 2419 4703 2401 1679 2399 1679 2428 1679 2428 1679 2399 1679 2429 1679 2428 1679 2429 1679 2420 1679 2420 4704 2429 4704 2430 4704 2420 4705 2430 4705 2403 4705 2427 1679 2431 1679 2379 1679 2379 1679 2431 1679 2432 1679 2379 1679 2432 1679 2378 1679 2432 1679 2433 1679 2378 1679 2378 4706 2433 4706 2434 4706 2378 1679 2434 1679 2377 1679 2377 4707 2434 4707 2435 4707 2402 1679 2436 1679 2403 1679 2403 1679 2436 1679 2437 1679 2403 1679 2437 1679 2420 1679 2420 4708 2437 4708 2438 4708 2420 1679 2438 1679 2422 1679 2422 4709 2438 4709 2439 4709 2422 1679 2439 1679 2396 1679 2396 4710 2439 4710 2440 4710 2396 4711 2440 4711 2370 4711 2370 4712 2440 4712 2441 4712 2370 1679 2441 1679 2409 1679 2373 4713 2372 4713 2397 4713 2397 1679 2372 1679 2374 1679 2397 1679 2374 1679 2442 1679 2442 4714 2374 4714 2375 4714 2442 4715 2375 4715 2435 4715 2435 4716 2375 4716 2376 4716 2435 4717 2376 4717 2377 4717 2412 4718 2443 4718 2411 4718 2411 4719 2443 4719 2444 4719 2411 4720 2444 4720 2418 4720 2418 4721 2444 4721 2445 4721 2418 4721 2445 4721 2417 4721 2417 4722 2445 4722 2446 4722 2417 4722 2446 4722 2416 4722 2416 4723 2446 4723 2447 4723 2416 4724 2447 4724 2419 4724 2419 4725 2447 4725 2448 4725 2419 4726 2448 4726 2420 4726 2420 4727 2448 4727 2449 4727 2420 4728 2449 4728 2428 4728 2428 4729 2449 4729 2450 4729 2428 4730 2450 4730 2401 4730 2401 4731 2450 4731 2451 4731 2401 4732 2451 4732 2400 4732 2400 4733 2451 4733 2452 4733 2400 4734 2452 4734 2398 4734 2398 4735 2452 4735 2453 4735 2398 4736 2453 4736 2413 4736 2413 4737 2453 4737 2454 4737 2413 4738 2454 4738 2412 4738 2412 4739 2454 4739 2443 4739 2450 1679 2449 1679 2455 1679 2455 1679 2449 1679 2448 1679 2455 1679 2448 1679 2447 1679 2453 1679 2452 1679 2455 1679 2455 1679 2452 1679 2451 1679 2455 1679 2451 1679 2450 1679 2444 1679 2443 1679 2455 1679 2455 1679 2443 1679 2454 1679 2455 1679 2454 1679 2453 1679 2447 1679 2446 1679 2455 1679 2455 1679 2446 1679 2445 1679 2455 1679 2445 1679 2444 1679 2431 4718 2456 4718 2432 4718 2432 4719 2456 4719 2457 4719 2432 4720 2457 4720 2433 4720 2433 4721 2457 4721 2458 4721 2433 4721 2458 4721 2434 4721 2434 4722 2458 4722 2459 4722 2434 4722 2459 4722 2435 4722 2435 4723 2459 4723 2460 4723 2435 4724 2460 4724 2442 4724 2442 4725 2460 4725 2461 4725 2442 4726 2461 4726 2397 4726 2397 4727 2461 4727 2462 4727 2397 4728 2462 4728 2395 4728 2395 4729 2462 4729 2463 4729 2395 4730 2463 4730 2396 4730 2396 4731 2463 4731 2464 4731 2396 4732 2464 4732 2422 4732 2422 4733 2464 4733 2465 4733 2422 4734 2465 4734 2421 4734 2421 4735 2465 4735 2466 4735 2421 4736 2466 4736 2427 4736 2427 4737 2466 4737 2467 4737 2427 4738 2467 4738 2431 4738 2431 4739 2467 4739 2456 4739 2463 1679 2462 1679 2468 1679 2468 1679 2462 1679 2461 1679 2468 1679 2461 1679 2460 1679 2466 1679 2465 1679 2468 1679 2468 1679 2465 1679 2464 1679 2468 1679 2464 1679 2463 1679 2457 1679 2456 1679 2468 1679 2468 1679 2456 1679 2467 1679 2468 1679 2467 1679 2466 1679 2460 1679 2459 1679 2468 1679 2468 1679 2459 1679 2458 1679 2468 1679 2458 1679 2457 1679 2399 4718 2469 4718 2429 4718 2429 4719 2469 4719 2470 4719 2429 4720 2470 4720 2430 4720 2430 4721 2470 4721 2471 4721 2430 4721 2471 4721 2403 4721 2403 4722 2471 4722 2472 4722 2403 4722 2472 4722 2405 4722 2405 4723 2472 4723 2473 4723 2405 4724 2473 4724 2407 4724 2407 4725 2473 4725 2474 4725 2407 4726 2474 4726 2408 4726 2408 4727 2474 4727 2475 4727 2408 4728 2475 4728 2423 4728 2423 4729 2475 4729 2476 4729 2423 4730 2476 4730 2426 4730 2426 4732 2476 4732 2477 4732 2426 4732 2477 4732 2425 4732 2425 4734 2477 4734 2478 4734 2425 4734 2478 4734 2424 4734 2424 4735 2478 4735 2479 4735 2424 4736 2479 4736 2415 4736 2415 4737 2479 4737 2480 4737 2415 4738 2480 4738 2399 4738 2399 4739 2480 4739 2469 4739 2476 4740 2475 4740 2481 4740 2481 1679 2475 1679 2474 1679 2481 1679 2474 1679 2473 1679 2479 1679 2478 1679 2481 1679 2481 4740 2478 4740 2477 4740 2481 4741 2477 4741 2476 4741 2470 4742 2469 4742 2481 4742 2481 1679 2469 1679 2480 1679 2481 1679 2480 1679 2479 1679 2473 1679 2472 1679 2481 1679 2481 4741 2472 4741 2471 4741 2481 4740 2471 4740 2470 4740 2436 4718 2482 4718 2437 4718 2437 4719 2482 4719 2483 4719 2437 4720 2483 4720 2438 4720 2438 4721 2483 4721 2484 4721 2438 4721 2484 4721 2439 4721 2439 4722 2484 4722 2485 4722 2439 4722 2485 4722 2440 4722 2440 4723 2485 4723 2486 4723 2440 4724 2486 4724 2441 4724 2441 4725 2486 4725 2487 4725 2441 4726 2487 4726 2409 4726 2409 4727 2487 4727 2488 4727 2409 4728 2488 4728 2410 4728 2410 4729 2488 4729 2489 4729 2410 4730 2489 4730 2414 4730 2414 4732 2489 4732 2490 4732 2414 4732 2490 4732 2406 4732 2406 4734 2490 4734 2491 4734 2406 4734 2491 4734 2404 4734 2404 4735 2491 4735 2492 4735 2404 4736 2492 4736 2402 4736 2402 4737 2492 4737 2493 4737 2402 4738 2493 4738 2436 4738 2436 4739 2493 4739 2482 4739 2489 4740 2488 4740 2494 4740 2494 1679 2488 1679 2487 1679 2494 1679 2487 1679 2486 1679 2492 1679 2491 1679 2494 1679 2494 4740 2491 4740 2490 4740 2494 4741 2490 4741 2489 4741 2483 4742 2482 4742 2494 4742 2494 1679 2482 1679 2493 1679 2494 1679 2493 1679 2492 1679 2486 1679 2485 1679 2494 1679 2494 4741 2485 4741 2484 4741 2494 4740 2484 4740 2483 4740

+
+
+
+ + + + 29.2331 -14.16401 196.7418 10.76716 -13.86542 201.6429 21.39861 -14.07537 193.4641 27.46566 -14.16783 194.2271 28.3862 -14.16117 201.1792 28.55589 -14.16393 195.3397 26.57802 -14.088 203.1484 26.0908 -14.14846 193.4914 29.12671 -29.98901 195.9577 28.15216 -30.7099 194.1976 29.69017 -29.98164 197.5565 25.48671 -30.31977 193.1829 27.11698 -30.73169 193.5123 21.12255 -28.88793 193.1422 21.49174 -35.58555 193.141 15.37017 -19.99502 188.3348 -21.50867 -35.58535 193.141 -27.01785 -30.10811 193.7396 -21.49532 -28.98937 193.141 -28.13104 -30.71404 194.175 -25.83329 -30.16364 193.2869 -29.20789 -30.24131 196.066 -15.387 -19.99488 188.3347 -27.60938 -14.16784 194.2271 -28.52991 -14.16118 201.1792 -29.57075 -14.16784 198.2878 -26.23451 -14.14847 193.4914 -28.69961 -14.16394 195.3397 -21.49527 -19.99485 193.141 10.70515 -20.04278 200.9014 10.82763 -0.05495995 198.8623 -8.135764 -19.99491 225.7452 -1.23421 -19.99494 228.0908 11.7382 -19.99501 222.4602 5.95719 -19.99498 226.9021 -5.97408 -19.99492 226.9021 1.21731 -19.99496 228.0908 -10.08011 -19.99495 224.2513 -11.75508 -19.99489 222.4602 11.60935 -27.98278 222.6372 10.0632 -19.995 224.2513 -11.76637 -27.98262 222.4723 19.13893 -28.90956 212.8358 -19.56073 -29.1617 212.2155 28.61199 -30.50734 201.1697 -29.58549 -31.27479 199.4863 -28.62001 -31.02658 201.1763 -29.68513 -29.98092 198.6928 0.30527 -20.00591 213.1484 27.08075 -19.99508 203.1861 11.08792 -20.04278 202.3254 12.11914 -14.04642 203.0609 10.88063 -6.11725 201.9681 29.74393 -30.96025 198.3759 27.56346 -30.98839 192.2909 26.96834 -31.01417 183.141 27.47483 -30.98838 185.8623 -18.46961 13.78698 210.5607 -21.49532 8.98936 185.941 21.47847 8.989562 185.941 -15.38701 -0.005129933 188.3347 15.37016 -0.004969954 188.3348 -6.75985 5.95628 226.0962 -19.3355 12.47244 210.992 -8.13577 -0.005089998 225.7452 -1.23421 -0.005059957 228.0908 -0.00830996 9.959584 224.8453 17.88496 10.4642 213.5606 3.46709 5.95633 227.3319 1.2173 -0.00503993 228.0908 15.97012 12.39993 213.5357 10.52479 8.08447 223.6853 6.17142 8.188194 225.1135 18.30959 13.6839 210.6959 6.74287 5.95635 226.0962 17.12156 15.64486 209.2734 -3.48406 5.9563 227.3319 11.7382 -0.004989922 222.4602 -10.60663 7.42227 223.7478 5.95718 -0.005019903 226.9021 -5.97409 -0.005079925 226.9021 -0.008489966 5.95632 227.7518 -11.76637 7.98262 222.4723 -16.29367 12.62307 212.9111 -0.008529961 8.18816 226.6161 -10.08011 -0.005059957 224.2513 -17.75995 10.64507 213.6346 -6.18846 8.18812 225.1134 -16.56421 15.84821 208.9666 -11.75509 -0.005109906 222.4602 0.49007 13.58403 220.1232 11.60934 7.98279 222.6372 13.68506 14.29911 211.3139 15.56888 14.94498 209.9162 12.05915 14.15369 213.031 10.06319 -0.004999995 224.2513 -14.86134 13.86502 212.0578 -13.91902 14.26721 211.633 16.32755 15.88888 208.8843 15.13303 15.10267 208.1131 5.6449 14.28627 218.7978 14.31331 13.30281 213.8854 9.693614 11.31001 222.849 -9.71062 11.3099 222.849 -8.34798 13.16498 221.4855 14.46985 14.123 211.9805 -14.33889 13.31698 213.8898 -5.66194 14.28621 218.7978 -34.98714 16.48372 183.1409 -33.10577 12.07831 191.3992 34.53139 14.69207 192.9881 33.88874 20.98234 194.5057 32.41469 12.07866 193.3363 -34.1106 23.48006 183.1409 30.25814 21.87187 198.9264 -33.77184 22.3201 194.3907 21.85608 22.07732 193.141 21.5077 20.57482 193.141 23.13377 23.71641 201.67 -28.60559 23.35913 199.7737 24.55461 23.43409 201.7894 33.88875 15.98538 194.5058 15.59797 23.35947 198.696 -18.99684 24.95138 199.2961 -26.98518 11.01389 183.141 34.79623 22.32104 191.4061 22.85788 21.89442 183.141 -30.21933 22.3222 198.8859 -34.42173 22.51174 192.9438 34.983 20.98681 191.8221 34.96197 15.42036 191.4038 23.87253 24.13467 193.007 -27.23467 14.78579 192.907 25.57107 24.78537 199.4185 -25.79275 15.58531 191.141 23.03796 22.73579 192.9002 -34.88922 21.86153 183.1409 -32.84603 11.88464 186.1409 -25.58381 24.60102 183.141 -22.51073 15.58533 183.141 -34.43144 14.03747 192.9506 26.59187 23.15303 201.3888 23.33065 24.83233 199.8286 -34.2779 13.29147 191.4056 29.74393 10.96026 198.376 -23.89275 24.13781 193.0072 -30.61917 10.96507 191.6171 34.40472 22.51211 192.944 -23.93853 23.68398 192.6409 33.33868 13.29117 194.0602 -17.29799 23.95095 200.9552 28.25447 24.81621 197.3397 18.9806 24.83241 199.828 33.76669 22.32434 194.3975 -15.50301 16.01193 207.2098 15.79879 23.79947 193.0517 -22.86767 22.95523 193.0072 -32.11723 24.78397 192.5457 -29.2079 10.24129 196.066 -18.36642 24.93965 193.141 31.64711 11.23419 192.173 34.86427 15.97845 192.6572 -23.93228 24.8351 199.8356 16.44956 23.47284 200.9732 -22.88459 24.13721 201.208 21.49174 15.58557 193.141 34.57374 22.71798 183.141 -32.72465 24.58339 183.1409 16.12519 24.09111 199.5014 22.49384 15.58557 183.141 25.77583 15.58558 193.141 -34.67782 14.25417 186.1409 -16.127 24.11815 199.4553 33.79073 14.87376 194.428 -34.99195 15.41791 191.6172 -26.32878 24.97958 192.6354 -34.17892 20.98644 194.1828 22.47717 19.97113 192.6676 19.13892 8.90957 212.8358 31.19183 15.35321 197.9084 -21.50867 15.58534 193.141 -32.14261 14.30173 196.4264 -33.12226 12.36458 193.119 22.4581 21.41522 192.9022 32.11715 14.3039 196.4186 -34.98714 15.98502 185.9497 -25.04825 24.49428 192.6409 23.91961 23.68204 192.6405 27.44081 14.78608 191.641 -22.25968 19.97178 192.986 -29.67965 13.00989 199.7989 -32.04143 11.52369 192.4942 33.26425 12.18998 191.9951 26.57535 14.78608 183.141 30.00427 11.64074 196.8428 -29.81092 11.35786 198.0291 -33.37424 23.89329 193.2573 -30.50339 12.80341 197.7443 -23.08364 22.60834 192.6409 -33.74797 14.3105 194.368 28.41702 10.99705 193.6954 -25.79273 15.5853 183.141 -22.54487 21.34432 192.641 25.56682 24.60129 183.141 29.19439 10.89103 195.2594 30.98028 11.09095 186.141 -21.95733 21.40113 193.1557 -15.57331 23.22389 199.1776 -34.60375 15.97808 193.4542 34.5805 20.99011 193.4515 31.26432 14.32288 197.5403 -29.5855 11.27478 199.4863 -27.23466 14.78579 191.375 32.83066 11.88598 186.141 29.83044 11.42817 194.892 23.945 24.97985 198.6896 30.84862 12.283 195.854 21.12254 8.88795 193.1423 -34.82428 22.32404 191.4081 -31.17939 12.40927 195.6551 27.56345 10.9884 192.2909 27.21774 14.78604 192.907 10.59446 14.2863 212.6366 -25.76259 24.35805 200.5835 -23.34137 22.76534 183.141 34.27376 13.32267 192.1381 -30.99624 11.09043 186.1409 -27.01786 10.1081 193.7396 -25.20465 24.97959 192.9981 -34.98717 20.98197 191.3992 19.45186 12.02961 211.1126 -33.85997 23.85172 191.4055 -29.93584 11.48745 195.3008 34.97022 16.48409 183.141 -21.49532 8.989354 193.141 34.91357 15.23474 186.141 -26.13454 15.58531 193.0807 -28.13105 10.71403 194.175 30.32481 14.308 199.0056 -28.03135 10.9881 186.0626 26.96833 11.01418 183.141 27.11698 10.7317 193.5123 14.4827 14.55406 193.141 -27.91828 24.87933 197.0564 30.97259 24.97988 191.3993 -19.56074 9.16169 212.2155 27.47482 10.9884 185.8623 15.54012 22.73135 199.9994 32.70765 24.58374 183.141 33.34771 23.88522 193.2536 -17.63467 24.7285 199.5171 -27.1286 10.69656 193.53 0.004659891 14.05591 212.8021 26.31544 24.97986 192.639 -25.8333 10.16362 193.2869 -15.98162 23.93966 193.1003 -34.87456 20.98974 192.6554 32.35282 24.78691 191.8237 -28.63495 10.96214 193.9001 -31.22917 15.24397 197.8865 -15.23129 15.28555 193.141 25.02793 24.49245 192.6405 33.8424 23.85223 191.4054 25.18572 24.97985 193.0048 17.70369 24.81411 193.141 25.77583 15.58558 191.141 -27.20847 10.97332 192.9282 25.4867 10.31978 193.1829 29.69016 9.981654 197.5565 28.61198 10.50735 201.1697 28.15215 10.70991 194.1976 29.1267 9.989024 195.9577 -28.62002 11.02657 201.1763 -29.68514 9.980914 198.6928 -27.60927 -5.92986 194.2273 -29.27717 -5.93045 201.2351 -29.57054 -5.92983 198.2878 -26.23457 -5.9503 193.4912 -28.69948 -5.93367 195.3398 0.30526 0.005899906 213.1484 -21.49528 -0.005159974 193.141 11.52659 -0.05495995 202.7647 21.39854 -6.05413 193.6616 26.864 -0.004909992 203.2208 26.09085 -5.95029 193.4912 29.13345 -5.93044 201.4083 29.23282 -5.93372 196.7418 26.6949 -5.97775 203.1822 27.46555 -5.92985 194.2273 28.55576 -5.93366 195.3398 21.47848 -28.98956 185.941 -21.49532 -28.98937 185.941 -11.67031 -0.05495995 202.7647 -26.95345 -0.005189955 203.1901 -26.83862 -5.97777 203.1822 -21.54226 -6.05414 193.6616 -11.02435 -6.11725 201.9681 -27.0507 -19.99482 203.0668 -10.91088 -13.86543 201.6429 -11.23163 -20.04278 202.3254 -12.26285 -14.04643 203.0609 -10.97135 -0.05496978 198.8623 -10.84887 -20.04279 200.9014 -26.72174 -14.08801 203.1484 -21.54232 -14.07538 193.4641 -27.20847 -30.99855 192.9282 25.77584 -35.61081 191.141 17.7037 -44.83934 193.141 25.18573 -45.00508 193.0048 33.84242 -43.87745 191.4054 25.02794 -44.51768 192.6405 -15.23128 -35.31078 193.141 -31.22916 -35.26921 197.8865 -28.63494 -30.98738 193.9001 30.32481 -34.33322 199.0056 32.35283 -44.81213 191.8237 -34.87455 -41.01498 192.6554 -15.98161 -43.9649 193.1003 -29.81091 -31.3831 198.0291 -29.67964 -33.03514 199.7989 26.31545 -45.00509 192.639 0.004669964 -34.08114 212.8021 -27.12859 -30.72179 193.53 -17.63465 -44.75374 199.5171 30.25815 -41.89709 198.9264 33.34773 -43.91044 193.2536 32.70767 -44.60896 183.141 -28.20184 -44.24278 198.9098 15.54013 -42.75657 199.9994 30.9726 -45.00511 191.3993 -27.91827 -44.90458 197.0564 14.48271 -34.57928 193.141 -28.03135 -31.01334 186.0626 31.26433 -34.34811 197.5403 -26.13453 -35.61054 193.0807 34.91357 -35.25996 186.141 34.97023 -36.5093 183.141 -29.93584 -31.51268 195.3008 -33.85996 -43.87696 191.4055 19.45187 -32.05484 211.1126 -34.98717 -41.00721 191.3992 -25.20464 -45.00482 192.9981 -30.99623 -31.11567 186.1409 -30.50338 -32.82864 197.7443 34.27377 -33.34789 192.1381 -23.34136 -42.79058 183.141 -25.76258 -44.38329 200.5835 10.59447 -34.31153 212.6366 27.21775 -34.81126 192.907 -31.17938 -32.4345 195.6551 -34.82426 -42.34929 191.4081 30.84863 -32.30822 195.854 23.94501 -45.00507 198.6896 29.83044 -31.45339 194.892 32.83066 -31.9112 186.141 -27.23465 -34.81103 191.375 34.58051 -41.01534 193.4515 -34.60375 -36.00331 193.4542 -15.5733 -43.24913 199.1776 -21.95732 -41.42637 193.1557 30.98029 -31.11618 186.141 29.19439 -30.91626 195.2594 32.11715 -34.32912 196.4186 25.56683 -44.62652 183.141 -22.54486 -41.36955 192.641 -25.79273 -35.61053 183.141 28.41703 -31.02227 193.6954 -33.74796 -34.33574 194.368 -23.08363 -42.63358 192.6409 -33.37422 -43.91854 193.2573 30.00428 -31.66597 196.8428 26.57535 -34.8113 183.141 33.26425 -32.2152 191.9951 -32.04143 -31.54894 192.4942 -22.25967 -39.99702 192.986 27.44082 -34.81131 191.641 23.91962 -43.70727 192.6405 23.13378 -43.74164 201.67 -25.04824 -44.51952 192.6409 -34.98713 -36.01025 185.9497 22.45811 -41.44044 192.9022 -33.12226 -32.38982 193.119 -32.1426 -34.32697 196.4264 31.19184 -35.37843 197.9084 22.47717 -39.99635 192.6676 -34.1789 -41.01167 194.1828 -26.32877 -45.00481 192.6354 -34.99195 -35.44315 191.6172 33.79074 -34.89899 194.428 -16.12698 -44.14339 199.4553 -34.67781 -34.2794 186.1409 25.77583 -35.61081 193.141 22.49384 -35.61079 183.141 16.12521 -44.11633 199.5014 -32.72463 -44.60863 183.1409 34.57375 -42.7432 183.141 -22.88458 -44.16245 201.208 16.44957 -43.49807 200.9732 -23.93227 -44.86033 199.8356 34.86427 -36.00367 192.6572 31.64712 -31.2594 192.173 -18.36641 -44.96488 193.141 -32.11722 -44.8092 192.5457 -22.86766 -42.98047 193.0072 15.7988 -43.82469 193.0517 -15.503 -36.03717 207.2098 26.59188 -43.17825 201.3888 33.76669 -42.34956 194.3975 18.98061 -44.85764 199.828 28.25448 -44.84144 197.3397 -17.29797 -43.97618 200.9552 33.33868 -33.3164 194.0602 -23.93851 -43.70922 192.6409 34.40473 -42.53733 192.944 -30.61916 -30.9903 191.6171 -23.89274 -44.16305 193.0072 -34.27789 -33.31671 191.4056 33.88875 -36.0106 194.5058 23.33066 -44.85756 199.8286 26.64597 -44.28524 200.1048 -34.43144 -34.06271 192.9506 -22.51072 -35.61057 183.141 -25.5838 -44.62625 183.141 -32.84603 -31.90988 186.1409 -34.88921 -41.88677 183.1409 23.03797 -42.76101 192.9002 -25.79275 -35.61054 191.141 -27.23466 -34.81103 192.907 23.87254 -44.15989 193.007 34.96198 -35.44559 191.4038 34.98302 -41.01204 191.8221 -34.42172 -42.53698 192.9438 -30.21932 -42.34743 198.8859 22.85789 -41.91965 183.141 34.79625 -42.34627 191.4061 -26.98517 -31.03913 183.141 -18.99683 -44.97661 199.2961 15.59798 -43.3847 198.696 -28.60558 -43.38437 199.7737 21.50771 -40.60004 193.141 21.85609 -42.10255 193.141 -33.77182 -42.34534 194.3907 -34.1106 -43.50529 183.1409 32.4147 -32.10388 193.3363 33.88876 -41.00756 194.5057 34.53139 -34.7173 192.9881 -33.10577 -32.10356 191.3992 -34.98714 -36.50895 183.1409 -5.66193 -34.31144 218.7978 -14.33888 -33.34222 213.8898 14.46985 -34.14823 211.9805 5.64491 -34.3115 218.7978 -8.34797 -33.19022 221.4855 -9.71062 -31.33514 222.849 9.69362 -31.33524 222.849 14.31332 -33.32804 213.8854 15.13304 -35.1279 208.1131 16.32756 -35.91411 208.8843 -13.91902 -34.29244 211.633 -14.86134 -33.89025 212.0578 12.05916 -34.17892 213.031 15.56889 -34.9702 209.9162 13.68507 -34.32434 211.3139 0.49008 -33.60926 220.1232 -16.5642 -35.87345 208.9666 -6.18845 -28.21336 225.1134 -17.75994 -30.6703 213.6346 -0.008519947 -28.21339 226.6161 -16.29366 -32.64831 212.9111 -0.008489966 -25.98155 227.7518 -10.60662 -27.4475 223.7478 -3.48405 -25.98153 227.3319 17.12157 -35.67009 209.2734 6.74288 -25.98158 226.0962 18.3096 -33.70912 210.6959 6.17142 -28.21342 225.1135 10.5248 -28.1097 223.6853 15.97012 -32.42515 213.5357 3.46709 -25.98156 227.3319 17.88497 -30.48943 213.5606 -0.008299946 -29.98481 224.8453 -19.33549 -32.49768 210.992 -6.75984 -25.98152 226.0962 -18.4696 -33.81222 210.5607 + + + + + + + + + + 0.01561552 0.9998533 -0.007047474 -9.83374e-4 0.9999992 -8.28155e-4 0.0179196 0.9998139 -0.007163643 -0.007168531 0.9999681 0.003523528 0.9430803 0.01013004 -0.3324108 0.9003587 0.01549392 -0.4348724 0.8726164 0.01240891 -0.4882485 -0.009253084 0.01497787 -0.9998451 0.4717823 -8.03786e-4 -0.8817148 0.2070965 0.03782767 -0.9775889 0.5514918 0.02437365 -0.8338242 0.7138675 0.03087198 -0.6996 0.2803763 0.01563024 -0.9597629 0.006108462 0.01884508 -0.9998038 4.5718e-6 0.9999929 0.00380212 -0.07373255 4.01605e-7 -0.9972781 -0.3711361 0.01462346 -0.9284633 -0.4718902 0.009450912 -0.8816067 -0.3568481 0.00298798 -0.9341576 -0.01830124 0.01230752 -0.9997568 -0.0732674 1.48331e-4 -0.9973124 -0.7139815 0.02471327 -0.6997284 -0.8684197 0.005056619 -0.4958041 -0.9588694 0.01751494 -0.283307 -0.937036 -0.02975642 -0.347963 0.002332031 0.9999969 -0.001030385 0.002692818 0.9999962 -7.23134e-4 0.00100547 0.9999967 -0.002405107 -0.00285989 0.9999933 -0.002279937 0.7823848 0.001180171 0.6227942 -5.38646e-4 0.9999998 -5.09263e-4 -4.01403e-4 0.9999997 -6.29528e-4 -1.76652e-4 0.9999998 -7.22099e-4 7.78423e-6 0.9999998 -7.33227e-4 1.83785e-4 0.9999997 -7.1537e-4 3.47216e-4 0.9999998 -6.39705e-4 4.29291e-4 0.9999998 -5.85633e-4 5.45349e-4 0.9999998 -4.78294e-4 -0.7963042 0.002041757 0.6048931 -0.7663735 -0.06200253 0.6393962 0.9556614 0.04262202 0.2913672 0.9821822 0.01345783 0.1874488 -0.8685721 0.004554927 0.4955421 -0.9838455 0.002532005 -0.179002 -0.9407939 0.01547765 0.3386259 -0.980711 0.04160088 0.1909852 0.03443318 0.9993918 -0.00551629 0.06774985 0.9957424 0.06250667 0.002877116 0.9999958 -2.34614e-4 -0.006032586 0.00586915 0.9999647 -0.05306607 -0.1125792 0.9922248 0.6086811 -0.0421673 0.7922937 0.7361648 0.06695115 0.6734828 -0.9654965 -0.02146059 0.2595301 -0.7207093 0.03904652 0.6921369 -0.9998136 0.007922708 0.01760703 -0.05492252 0.9984904 7.58672e-4 0.920313 -0.220179 -0.3233347 0.8972351 0.3114074 0.3130409 0.7861373 -0.001013457 0.6180511 0.003188788 -0.9999918 0.002502799 -0.003045499 -0.9999921 0.002569794 -0.00465238 -0.9999889 8.33297e-4 -0.02951377 -0.9994115 -0.01748067 -0.7705227 -0.5248699 0.3616716 5.11691e-6 -0.257188 -0.9663615 1.24225e-6 -0.2571765 -0.9663645 0.9985636 0.02016961 0.04963934 -4.69601e-6 0.9999005 0.01410865 -0.07368648 -3.12358e-7 -0.9972815 -0.03583323 -0.02026367 -0.9991524 0.4249283 -0.02359986 -0.9049193 -0.3710723 -0.01455062 -0.92849 -0.472149 -0.009394407 -0.8814687 -0.3568308 -0.002956986 -0.9341644 -1 -4.24115e-6 0 0.7138376 -0.03070336 -0.6996379 0.5515098 -0.02424395 -0.8338161 0.2070288 -0.03762084 -0.9776113 0.4720516 8.22893e-4 -0.8815706 0.001894712 0.9998987 0.01411074 -0.2355772 0.9105972 0.3395823 -5.38076e-4 -0.9999998 -5.08822e-4 -4.01263e-4 -0.9999997 -6.29058e-4 -1.76679e-4 -0.9999998 -7.2135e-4 8.17477e-6 -0.9999997 -7.32632e-4 1.83417e-4 -0.9999997 -7.14577e-4 3.471e-4 -0.9999998 -6.39847e-4 4.32299e-4 -0.9999998 -5.82755e-4 5.42617e-4 -0.9999998 -4.79558e-4 -0.73538 0.322638 0.5959203 -0.7120482 0.3725554 0.5951384 -0.6078385 0.6282297 0.4856539 -0.48342 0.7671771 0.4215977 -0.5388346 0.7187522 0.4393776 -0.2852668 0.9011696 0.3263683 -0.2129948 0.9589554 0.1871842 -0.02202355 0.999601 -0.01768767 0.01704108 0.9996063 -0.02229034 0.1863371 0.896737 0.4014243 0.07409763 0.9954727 0.05953019 0.2531335 0.9318023 0.260131 0.5006239 0.7538162 0.425602 0.6172995 0.6169193 0.488213 0.2999255 0.8867565 0.351721 0.7286733 0.3009279 0.6152053 0.7174101 0.3757173 0.5866509 0.7168346 0.2806226 0.6382783 0.520361 0.5283061 0.6709077 0.523715 0.5266789 0.6695759 0.5033223 0.7778653 0.3762877 0.3692883 0.7789661 0.5067921 -0.1229239 0.8053518 0.5799122 0.3813698 0.6829724 0.6229814 -0.741412 -0.007068693 0.6710129 -0.7303746 -0.002066254 0.6830437 -0.471109 0.05690366 0.8802376 -0.3518304 0.07971221 0.9326636 -0.243121 0.03165817 0.9694792 -0.1195573 0.08084994 0.9895299 0 0.05677258 0.9983872 0.7303774 0.006114065 0.6830164 0.694662 -0.004732429 0.7193207 -0.7261114 0.2812638 0.6274177 -0.4371832 0.5765635 0.6902503 -0.4955929 0.5476281 0.6741597 -0.4707143 0.799388 0.3733726 -0.2689011 0.7365325 0.6206546 -0.2763309 0.7346469 0.6196251 -0.7963036 -0.002040565 0.6048938 -0.7663729 0.06200355 0.6393969 -0.6317504 0.3098716 0.7105429 0.4704322 0.3900039 0.7915747 0.3753774 0.4616464 0.8037253 0.6691301 0.3433059 0.6590948 -0.5017848 0.06503021 0.8625445 -0.3340008 0.4501765 0.8281211 -0.3153828 0.4489123 0.8360691 -0.1954229 0.5620726 0.8036692 -0.1070548 0.4509173 0.8861225 0.1070474 0.4509207 0.8861216 0.1954077 0.5620622 0.8036803 0.3153808 0.4488867 0.8360836 0.2884777 0.4467479 0.8468748 0.2431266 0.03166055 0.9694777 0.1195609 0.08085137 0.9895293 0.5421731 0.02782279 0.8398061 0.5179169 0.04720693 0.8541274 0.351823 0.07971644 0.9326661 -0.5526021 0.3217239 0.7688463 -0.3655399 0.4986488 0.7859581 -0.6772923 0.5526573 0.4856389 -0.2271692 0.9638545 0.1392075 -0.6307378 0.7448603 0.2176074 -0.07914316 0.7638497 0.6405232 0.05340451 0.9894914 0.1343678 0.0830931 0.9832947 0.1619484 0.2885079 0.921459 0.2601472 -0.08982717 0.8150457 0.5723913 0.8337591 0.3971052 0.3836059 0.7008895 0.5337672 0.4731242 -0.07362639 0.9393897 0.3348526 -0.6092302 0.01056563 0.7929231 -0.02864557 -0.06671625 -0.9973607 -0.01899331 -0.01468348 -0.9997118 -0.07170587 -0.1221694 -0.9899156 -0.9992634 0.01644247 -0.03467571 -0.9892613 0.1411869 0.03779631 0.01059871 0.9984721 0.05423283 -0.02160245 0.9997224 0.009422302 0.02458703 0.9987548 0.04341065 0.5879015 -0.8089326 3.66184e-6 0.9503999 -0.3110228 0.002229988 0.8465853 -0.5265705 -0.07756859 0.7476761 -0.6637343 -0.02091056 0.5093628 -0.8605239 0.006959497 0.3946705 -0.9185638 -0.0218169 0.4849303 -0.8745529 2.15127e-6 -0.1596977 9.15928e-4 -0.9871655 2.62161e-5 -1.92937e-4 -1 -0.02109515 -0.02395379 -0.9994905 5.41095e-6 -0.007953941 -0.9999685 0 0 -1 -0.02604895 -0.03952682 -0.998879 -0.01878607 0.0265699 -0.9994705 0.05621528 -0.01764327 -0.9982628 -0.01576113 0.003093779 -0.9998711 0.004345476 -0.004326999 -0.9999813 3.00818e-5 -2.98508e-5 -1 -5.97265e-6 -2.32931e-4 -1 -3.49237e-6 0 -1 0.06948161 -0.02334308 -0.9973102 0.05688816 -0.06188285 -0.9964609 -0.149518 0.1477029 -0.9776647 0.02101701 0.02193903 -0.9995384 0.02149832 0.01863515 -0.9995953 -0.01842051 -0.01221692 -0.9997557 -0.07320171 -1.48202e-4 -0.9973172 0.01302427 -0.03728014 -0.9992201 0.1754911 -0.02767938 -0.9840918 -0.5018509 0.8648977 -0.009893178 0.08127123 -0.07713711 -0.9937026 0.4938455 -0.8651844 0.08702135 0.9576157 -0.2497935 0.1434417 0.9996075 0.0161854 0.02287256 0.002379298 0.9999973 7.95637e-7 1.09931e-5 9.98728e-7 -1 2.9185e-6 -1.18877e-4 -1 1.13283e-5 -2.95498e-6 -1 1.94274e-5 -1.88479e-5 -1 1.00795e-5 1.31849e-5 -1 1.018e-5 -4.62368e-6 -1 9.84221e-6 -1.6866e-7 -1 0.3747807 0.9270318 -0.01231205 0.1591798 0.9871444 0.01442277 0.3863968 0.9221749 -0.01706165 0.999954 -0.003096759 -0.00908643 0.9997152 -0.02175867 0.009814977 0.997394 0.06343418 -0.03437125 -0.936868 -0.02874648 -0.3485 -0.9829717 -0.06138265 -0.1732013 6.28868e-6 -1 1.39816e-6 6.37632e-6 -1 1.69668e-6 9.29848e-6 -1 2.32462e-7 -0.411606 -0.8475078 -0.3351284 -0.3163666 -0.3705716 -0.8732634 2.44869e-6 -1 0 -0.1916322 -0.9783129 0.0786184 2.56887e-6 -1 1.86827e-7 0.3608216 0.8531318 0.3767942 0.06977778 0.8842558 0.4617605 -0.3635968 -0.9315491 0.003710746 -0.3945259 -0.9188822 -0.002241134 -0.4696127 -0.8828235 0.009317815 -0.7191555 -0.6947782 -0.009934186 -0.7901011 -0.6107949 -0.05167198 -0.9474853 -0.3195125 0.01354765 -0.9838739 -0.1778907 -0.01863515 -0.0548895 -0.9984923 7.56458e-4 0.01396352 -0.9998953 -0.003825962 -0.4694667 0.8828023 -0.01616048 -0.2559659 0.9655795 0.04623579 0.9999764 0.006870687 6.22494e-6 0.2503749 -0.003657698 -0.9681421 0.763278 0.6458025 -0.01860147 -0.2727189 0.8640754 0.4230818 0.2152742 -0.9685378 -0.1248667 0.05919623 -0.9978007 -0.02983027 0.06005632 -0.9981946 -8.2818e-4 0.02759218 -0.9994053 0.02068221 -0.03444087 -0.9994049 0.00197637 0.01151961 -0.9996533 -0.0236774 0.004373311 -0.9999776 -0.005082786 0.9994055 0.02954089 0.0177769 0.9946824 0.08597451 -0.05670303 -0.568115 -0.795584 -0.2104555 -0.5583503 -0.8168305 -0.1450276 -0.9998291 0.01820641 0.003232419 -0.999854 0.01707386 8.59636e-4 -0.9999301 3.94797e-4 -0.01181763 0.4772557 -0.8143917 -0.3301413 0.5607668 -0.8203443 -0.1121422 -0.00246793 0.9997731 -0.02116316 -0.03393405 0.9993694 0.01046085 -0.03308695 0.9985523 -0.04241055 0.005249023 0.9995884 0.02820628 -0.006562709 0.9997723 0.02031064 -0.007406949 0.9999691 -0.002665102 -0.01351153 0.9986205 -0.05074167 0.002455651 0.9991959 -0.04001909 2.37993e-5 1 8.81335e-5 -0.02211898 0.9997543 0.001488208 -0.03124815 0.9994884 -0.006819605 -5.61348e-6 1 -8.64025e-7 3.53451e-7 0 -1 -9.37535e-6 0 -1 4.60591e-6 0 -1 1.03512e-6 0 -1 -0.4849405 -0.8745471 0 -0.4138299 -0.9074271 -0.07294458 -0.4434108 -0.8951808 0.04514765 -0.9925606 -0.1034097 0.06426614 -0.9947476 -0.01479196 0.1012839 0.07096368 0.9917967 0.1063174 0.04890638 0.9868294 0.1541952 0.1234307 0.8427708 0.5239298 0.1143648 0.841211 0.528474 0.219567 0.8041195 0.552433 0.3604821 0.8014485 0.4772137 0.5655164 0.6549519 0.5012278 -0.8274569 0.5226513 0.2053067 -0.5280175 0.8407658 0.1196261 -0.7690887 0.4900162 0.4103495 -0.8873252 0.1838574 0.4229074 -0.8899116 0.2083881 0.4057484 -0.8040372 0.5778281 0.1401391 -0.9593175 0.2694405 0.08433115 -0.9642212 0.1154479 0.2386404 -0.8688678 -0.1330495 0.4768297 -0.8676385 -0.4969342 0.01612305 -0.9044708 -0.4103116 0.116521 -0.9175149 -0.1181952 0.379732 -0.2441689 -0.8989203 -0.3637636 -0.6721805 -0.6307423 -0.3877339 -0.5974522 -0.8018327 -0.01073169 -0.9882476 -0.01705551 0.1519078 -0.9642937 -0.1811885 -0.1931539 -0.8705127 -0.348563 0.347436 -0.7695573 -0.5342514 0.3497957 -0.81971 -0.08346235 0.5666653 -0.8681145 -0.1954786 0.4562517 -0.7247098 -0.5218476 0.4499677 -0.5606065 -0.8176971 0.1307356 -0.7146515 -0.691065 0.1081783 -0.7804269 -0.589892 0.2072712 -0.9442567 -0.3232704 0.06225353 -0.9572325 -0.1493089 0.2478163 0.8360711 1.33197e-5 0.5486212 0.8841178 -0.02389752 0.4666528 0.9706866 0.01696532 0.2397498 0.9965743 -0.009937644 0.08210355 -0.6227433 0.7822567 -0.01629316 -0.9011184 0.4335024 0.007832765 -0.8454152 0.5336051 -0.02321231 -0.9927151 0.1204811 0.001057386 -0.4778087 0.8783803 0.01212602 0.9543956 -0.2649516 0.1375851 0.5125366 -0.8194128 0.2566494 0.6355918 -0.690502 0.3452972 0.6859034 -0.6520827 0.3229935 0.8263667 -0.4009248 0.3954462 0.8176549 -0.3412975 0.4636341 0.8785032 -0.1076066 0.4654601 0.8788756 -0.109982 0.4641999 0.9640756 -0.206492 0.1670908 0.7789077 0.1204649 0.6154601 0.6247628 0.5636731 0.5403186 0.1967519 0.8852924 0.4213624 0.6079871 0.655305 0.448249 0.1140219 0.9902958 0.0794565 0.05424469 0.9971574 0.05229395 7.63476e-7 0.9917173 0.1284403 -5.57107e-5 0.855217 0.5182702 0.6627902 -0.4888584 -0.5672097 0.4250437 -0.8640182 -0.2698344 0.5050352 -0.8071358 -0.3057305 0.6443608 -0.7647176 -0.002474963 0.6346895 -0.7716925 0.04074215 0.7714651 -0.5656436 0.2913568 0.6992948 -0.4688475 0.5396007 0.8350618 -0.1320554 0.5340725 0.9077774 -0.4182678 -0.03150045 0.8182771 -0.2402003 0.5222321 0.8979891 -0.3095135 -0.3127571 0.892437 -0.4486555 -0.04758882 0.92031 0.2202008 -0.3233284 0.8972198 -0.3114494 0.3130432 0.7846387 -0.1588892 0.5992466 0.2363368 -0.8919925 -0.3853499 -0.7970869 -0.02018803 0.6035272 -0.7675027 0.01902532 0.6407633 -0.7661004 0.01858872 0.6424521 -0.7700661 0.03111505 0.6372049 -0.7724037 0.01748228 0.6348912 0.02658361 0.899107 0.4369211 -0.01884251 0.9989008 0.04292184 -0.3006139 0.06971323 -0.9511948 -0.3598193 0.1449738 -0.9216901 -0.6508402 0.4357442 -0.6217188 -0.4024789 0.5504338 -0.7314598 -0.4052345 0.6278684 -0.6645046 -0.3334318 0.2679589 -0.9038923 -0.2578296 0.1117492 -0.9597063 -0.2392701 0.6298083 -0.73898 0.990478 0.1145869 -0.07631158 0.9814518 0.1645613 -0.09834754 0.5533722 0.8221759 0.1334404 0.8393178 0.5229089 0.1487008 0.9577251 0.1842736 0.2209207 0.9500852 0.2060413 0.2342758 0.7672755 0.500145 0.4014268 0.7974837 0.5680521 0.2033138 0.8042327 0.2694952 0.5297001 0.9039701 0.115408 0.4117271 0.7761536 -0.111862 0.6205422 0.7647511 -0.3449332 0.5442214 0.6236506 -0.5473755 0.5580683 0.5836703 -0.6952409 0.4194869 0.423861 -0.8426687 0.3320413 0.4037796 -0.8530196 0.3306353 0.1520934 -0.9734494 0.1710667 0.9802788 0.1901723 -0.05374163 0.9197636 0.3920379 -0.01847422 0.7828142 0.6221591 -0.01095563 0.6330473 0.7733222 -0.03498685 0.5895365 0.8073804 -0.02416431 0.3544063 0.9350436 -0.009473919 -0.5067823 -0.3723047 -0.7775353 -0.2469734 -0.8998813 -0.3594689 -0.2498766 -0.8918724 -0.376995 0.7756012 0.009838342 0.6311467 0.7748757 0.01344811 0.6319707 0.7782664 0.01343435 0.6277906 0.7822631 0.01479077 0.6227727 0.7727896 1.38788e-5 0.6346625 -0.9959989 0.004353165 0.08926069 -0.9770304 -0.01896309 0.2122547 -0.9099169 0.01688849 0.4144468 0.6010963 0.285396 0.74648 0.06548047 0.649806 0.7572744 0.2335387 0.5700045 0.7877528 0.9909892 0.1323928 -0.02031874 0.8487841 0.5287336 0.002544105 0.143653 0.9894773 -0.01728206 0.5318949 0.8468082 0.001921951 0.7066237 0.7067496 -0.03446674 -0.9991282 -0.006493687 -0.04123902 -0.3540402 0.9351833 -0.009369313 -0.5900734 0.806986 -0.02422761 -0.705804 0.7063435 -0.05403476 -0.7369824 0.6744424 -0.04454702 -0.9154844 0.4019613 -0.01776158 -0.4381065 0.001401245 -0.898922 -0.5948804 0.2809926 0.7531007 -0.3912907 0.474345 0.788599 -0.1161795 0.6381697 0.7610795 -0.7994903 -0.08438038 0.5947229 -0.7754129 -0.1842107 0.6039879 -0.6629921 -0.5435766 0.5147485 -0.6602965 -0.5461651 0.5154729 -0.4397987 -0.8264575 0.3514901 -0.4887438 -0.7963126 0.3563928 -0.2597916 -0.948232 0.182659 -0.2017438 -0.9638398 0.1741042 -0.3998326 0.8392901 0.3684103 -0.1537533 0.9595644 0.2357882 -0.0354377 0.8796215 0.4743524 -0.8192392 0.5732416 0.01553893 -0.9991894 0.02178466 -0.03385227 -0.7931811 0.4790177 0.3760396 -0.8798047 0.442303 0.1741027 0.8508662 0.5253615 0.004709303 0.6052916 0.586708 0.5379554 0.6608806 -0.05089694 -0.7487632 0.6208562 0.2645697 -0.7379299 0.6541627 0.3175907 -0.6864455 0.5396941 0.4289317 -0.7243949 0.5600119 0.4854119 -0.671388 0.4017937 0.5502665 -0.7319622 0.4044627 0.6230685 -0.6694743 0.2398301 0.6244189 -0.743359 -0.9755337 0.2197839 0.005385875 -0.9933806 0.05732041 -0.09954684 -0.7767203 0.1414058 0.6137671 -0.6457282 0.5682321 0.5100466 -0.655591 0.5434229 0.5243015 -0.3957766 0.845305 0.3589156 -0.4101067 0.8362125 0.3640896 0.9156996 -0.2218957 0.3350471 0.7881427 -0.1518562 0.5964654 0.2319261 -0.1492663 -0.9612128 0.8726297 -0.01234376 -0.4882265 0.9003875 -0.01541072 -0.4348161 0.9430808 -0.01008367 -0.332411 0.9556811 -0.0423755 0.2913385 0.9992616 0.032009 0.02125591 -0.8655185 0.03527402 0.4996334 -0.7139762 -0.02458065 -0.6997385 -0.8684329 -0.005037248 -0.4957812 -0.9588723 -0.01742041 -0.283303 -0.9838462 -0.002529859 -0.1789985 -0.9950361 -0.00968796 0.09904223 -0.9912891 -0.004385292 0.1316314 -0.006805241 -0.9999716 0.003245055 0.009081721 -0.999953 -0.00339955 0.02289599 -0.9995089 0.02139681 -0.003095984 -0.9999951 6.3684e-4 0.01654303 -0.9998555 -0.003924548 0.01694923 -0.9998489 -0.003889501 -0.3648713 -2.32697e-7 -0.9310581 -0.02970188 -0.005619406 0.999543 -0.07490563 -0.1220666 0.9896913 0.6197327 -0.01931172 0.7845754 0.5883926 -0.02188336 0.8082793 0.999951 -2.34747e-4 0.009894788 -0.9181715 -5.32592e-7 -0.3961832 -0.9810655 0.0814464 0.1757188 -0.9990285 0.01286119 0.04215216 0.9999437 3.20412e-7 0.01061564 -0.3648695 0 -0.9310587 0.002380132 -0.9999972 0 -1 5.65485e-6 0 -4.43723e-6 -0.9999005 0.01411229 0.9985735 -0.01968896 0.04963397 8.95525e-7 0.2571764 -0.9663645 5.1169e-6 0.2571879 -0.9663615 0.3648553 0 -0.9310643 -1 0 6.88764e-6 -0.9996351 -0.006514608 -0.02621853 0.9990285 0.01286178 0.04215323 0.9810658 0.08144551 0.1757175 0.9221677 4.01184e-7 -0.3867903 -0.9999833 1.49927e-4 -0.005787253 -0.9999031 0.008701324 0.01087605 -0.6240751 -0.01303207 0.7812559 0.0342608 -0.08595836 -0.9957095 -0.6197327 -0.01931256 0.7845754 0.07490497 -0.1220666 0.9896914 0.02782058 -7.8799e-4 0.9996127 0.364862 1.74527e-7 -0.9310616 -0.01694965 -0.9998488 -0.003890633 -0.01624745 -0.9998602 -0.003951251 -3.73537e-4 -1 -1.7318e-4 -0.02289587 -0.9995089 0.02139723 -0.009080529 -0.9999531 -0.003400564 0.006906628 -0.9999706 0.003343224 0.9998136 0.007922589 0.01760774 0.7207027 0.03904807 0.6921437 0.9655002 -0.02145862 0.2595167 -0.7367969 0.03170281 0.6753705 -0.6086808 -0.04216694 0.7922939 0.04616856 -0.1137907 0.9924315 0.006091892 -0.01415282 0.9998814 -0.002877116 0.9999959 -2.34832e-4 -0.06774985 0.9957424 0.06250584 -0.03443318 0.9993919 -0.005516827 -0.005532741 0.9999846 -3.11838e-4 0.9401224 -0.0288853 -0.3396108 -0.01791948 0.9998138 -0.007163763 0.003006219 0.9999954 -5.59963e-4 -0.01561576 0.9998533 -0.007047951 -0.00665456 0.05444574 -0.9984946 -0.7809695 0.004064798 0.624556 -0.7851648 0.005571246 0.6192618 -0.6859233 0.02910339 0.7270916 -0.7851656 -0.00557214 0.6192607 -0.003186404 -0.9999918 0.002517282 0.002876639 -0.9999927 0.002543389 0.004396855 -0.9999901 7.90065e-4 0.002737343 -0.9999941 0.00209999 5.21896e-6 -0.9999889 -0.004736304 0.002923846 0.9999931 -0.002302467 -9.41666e-4 0.9999967 -0.002402782 -0.002547204 0.9999966 -6.90574e-4 -0.01241379 0.9998887 0.008295118 -0.09635287 0.7400428 0.6656221 -0.09785389 0.7200407 0.6869979 0.1229031 0.630445 0.7664425 0.05083739 0.87742 0.477022 0.05550712 0.7045406 0.7074896 -0.07282197 0.6513915 0.7552391 0.1010162 0.9932321 0.05732083 -0.1165456 0.9906029 0.07157623 0.0182901 0.9161313 0.400461 0.05686694 0.7890759 0.611658 0.01517993 0.7924018 0.6098106 0.03442543 0.8215216 0.5691374 -0.1216966 0.5496575 0.8264785 0.1066867 0.5021326 0.8581846 0.004188001 0.5902419 0.8072156 -0.3277313 0.2838617 0.9011186 0.3029078 0.3115621 0.9006531 0.1694648 0.6967461 0.6970126 -0.169481 0.6967648 0.69699 -0.1157587 0.7179153 0.6864384 -0.798479 0.4406887 0.410152 -0.7984801 -0.4406876 0.4101511 -0.1157594 -0.7179127 0.686441 -0.1694784 -0.6967654 0.69699 0.1694658 -0.6967464 0.6970121 0.3029071 -0.3115618 0.9006535 -0.3277247 -0.2838609 0.9011212 0.004183411 -0.5902422 0.8072155 0.1066867 -0.5021319 0.8581851 -0.1216967 -0.5496581 0.8264781 0.03442543 -0.8215218 0.569137 0.01517879 -0.792401 0.6098119 0.05686688 -0.7890751 0.6116589 0.01828736 -0.9161332 0.4004566 -0.1165456 -0.9906029 0.07157582 0.1010162 -0.9932321 0.05732148 -0.07281565 -0.6513924 0.755239 0.0555076 -0.7045409 0.7074893 0.05084019 -0.8774212 0.4770193 0.1229027 -0.6304432 0.766444 -0.09785425 -0.7200406 0.686998 -0.09635329 -0.7400448 0.6656199 0.2317361 0.1483667 -0.9613979 0.7881434 0.15186 0.5964634 -0.3167011 -0.9075972 0.2756226 -0.4140712 -0.8482246 0.3302423 -0.5395525 -0.7096875 0.4530196 -0.6555927 -0.5434225 0.5242998 -0.6457279 -0.5682289 0.5100505 -0.776723 -0.1414021 0.6137645 -0.9933947 -0.05732291 -0.0994032 -0.9758101 -0.21856 0.005127072 0.2398105 -0.6244221 -0.7433626 0.4044717 -0.6230846 -0.6694537 0.4018092 -0.550262 -0.7319571 0.5600175 -0.4854167 -0.6713799 0.5396963 -0.4289281 -0.7243953 0.6541643 -0.3175924 -0.6864432 0.6208423 -0.2645666 -0.7379427 0.6608842 0.05089545 -0.7487602 0.605291 -0.5867071 0.5379568 0.8508697 -0.5253557 0.004708409 -0.8797973 -0.4423131 0.1741145 -0.7931867 -0.4790179 0.3760278 -0.9991895 -0.02178269 -0.03385305 -0.8192293 -0.5732556 0.01553922 -0.03543365 -0.8796225 0.4743509 -0.1537479 -0.9595668 0.235782 -0.2527154 -0.9227926 0.2908416 -0.4116985 -0.7353618 0.5382819 -0.2017378 0.9638411 0.1741042 -0.2598019 0.9482291 0.1826599 -0.4887523 0.7963092 0.3563887 -0.4397916 0.8264623 0.3514876 -0.6602929 0.5461685 0.515474 -0.6629944 0.5435734 0.514749 -0.7754171 0.1842058 0.603984 -0.7994899 0.08438801 0.5947225 -0.1161795 -0.6381701 0.7610791 -0.3912903 -0.4743452 0.7885991 -0.5947979 -0.2807018 0.7532742 -0.4381141 -0.001394927 -0.8989183 -0.9154844 -0.4019613 -0.01776087 -0.7369866 -0.6744379 -0.04454606 -0.7058036 -0.7063439 -0.05403476 -0.5900745 -0.8069853 -0.02422738 -0.354041 -0.9351831 -0.009369909 -0.9991283 0.006489396 -0.04123884 0.7066251 -0.7067482 -0.0344668 0.5318939 -0.8468089 0.001921832 0.1436579 -0.9894766 -0.01728206 0.8487824 -0.5287364 0.002543389 0.9909892 -0.1323919 -0.02031975 0.1629773 -0.6154218 0.7711644 0.6002393 -0.2721695 0.7520882 -0.9099137 -0.01689112 0.4144537 -0.9770304 0.01896232 0.2122544 -0.9959983 -0.004354298 0.08926653 0.7727872 -1.17436e-5 0.6346653 0.7822638 -0.01479077 0.6227717 0.7782727 -0.0134325 0.6277828 0.7748641 -0.0134468 0.6319847 0.7756067 -0.009769678 0.6311409 -0.2498764 0.8918737 -0.3769922 -0.2545314 0.8776582 -0.4061159 -0.5030127 0.3592442 -0.78608 0.3544009 -0.9350457 -0.009474277 0.589532 -0.8073836 -0.02416473 0.6330451 -0.7733238 -0.03498852 0.7828165 -0.6221563 -0.01095533 0.9197658 -0.3920325 -0.01847434 0.9802774 -0.1901789 -0.05374157 0.1520909 0.9734491 0.1710709 0.4037771 0.8530201 0.3306369 0.4238623 0.8426662 0.3320458 0.5836796 0.695232 0.4194886 0.6236494 0.5473738 0.5580713 0.764749 0.344937 0.5442218 0.7761544 0.1118572 0.620542 0.9039669 -0.1154219 0.4117301 0.8042307 -0.2694995 0.5297009 0.7974857 -0.5680493 0.2033143 0.7672784 -0.5001384 0.4014297 0.9500834 -0.2060435 0.2342812 0.9577237 -0.1842757 0.2209249 0.839318 -0.5229063 0.1487089 0.5533696 -0.8221775 0.1334397 0.9816411 -0.1636645 -0.09795272 0.990478 -0.1145861 -0.07631123 -0.2392714 -0.629809 -0.7389789 -0.2578273 -0.1117475 -0.959707 -0.333428 -0.267957 -0.9038943 -0.4052199 -0.6278792 -0.6645033 -0.4024835 -0.55044 -0.7314526 -0.6508463 -0.4357496 -0.6217085 -0.3598049 -0.1449792 -0.9216949 -0.3006575 -0.06971067 -0.9511811 -0.01884192 -0.9989006 0.04292756 0.02657991 -0.8991083 0.4369187 -0.7723858 -0.01748555 0.634913 -0.7701148 -0.03067618 0.6371673 -0.7661063 -0.01858836 0.6424451 -0.7675042 -0.01902604 0.6407616 -0.7970856 0.02018475 0.6035291 0.2535958 0.8756906 -0.4109198 0.7846361 0.1588929 0.5992489 0.9159475 0.2203544 0.3353866 0.8957033 0.4416928 -0.05121588 0.8988689 0.3035946 -0.3160145 0.8186227 0.2385198 0.5224609 0.9081901 0.41686 -0.03766542 0.8350587 0.132052 0.534078 0.6992965 0.468846 0.5395998 0.7714607 0.5656477 0.2913608 0.6346947 0.7716882 0.04074245 0.6443302 0.7647435 -0.002476513 0.5050375 0.8071385 -0.3057201 0.4562367 0.8433465 -0.2839275 0.6720523 0.4761483 -0.5671231 -5.57107e-5 -0.8552163 0.5182714 0 -0.9917175 0.1284381 0.05424267 -0.9971575 0.05229395 0.114026 -0.9902949 0.07946074 0.6079872 -0.655304 0.4482503 0.1967505 -0.8852941 0.4213593 0.624763 -0.5636701 0.5403214 0.7789117 -0.1204689 0.6154542 0.9640727 0.206499 0.1670988 0.8788765 0.1099736 0.4642002 0.8785071 0.1076032 0.4654534 0.8176548 0.3413038 0.4636294 0.8263599 0.4009275 0.3954572 0.6858997 0.6520839 0.3229989 0.635596 0.6904995 0.3452945 0.5125473 0.819407 0.2566469 0.954396 0.2649465 0.137593 -0.4778034 -0.8783832 0.01212602 -0.9927139 -0.1204916 0.001057803 -0.8454159 -0.533604 -0.02321141 -0.9011201 -0.433499 0.007833063 -0.6227384 -0.7822605 -0.01629376 0.9965736 0.009937465 0.08211195 0.9706856 -0.01696079 0.2397538 0.8841198 0.02389872 0.4666489 0.8360694 -8.47633e-6 0.5486238 -0.957233 0.149309 0.2478142 -0.944256 0.3232735 0.06224888 -0.7804265 0.5898939 0.2072667 -0.7146556 0.6910612 0.108175 -0.5606067 0.8176974 0.1307339 -0.7247087 0.5218446 0.4499728 -0.8681064 0.1954864 0.4562637 -0.819703 0.08345621 0.5666765 -0.7695608 0.5342481 0.3497934 -0.8705136 0.3485633 0.3474332 -0.9649506 0.1778831 -0.1929459 -0.9882927 0.01688498 0.1516331 -0.5974515 0.8018334 -0.01072555 -0.6754906 0.6236003 -0.3934912 -0.2740764 0.884638 -0.3772238 -0.9177595 0.1165055 0.3796631 -0.9046795 0.4118255 0.1093373 -0.8719916 0.4892361 0.01669174 -0.8689638 0.1312093 0.4771648 -0.9642225 -0.1154589 0.2386301 -0.9593179 -0.2694368 0.08433866 -0.8040369 -0.5778309 0.1401301 -0.8899129 -0.2083746 0.4057527 -0.8873223 -0.1838634 0.4229105 -0.7690857 -0.4900171 0.4103543 -0.5280125 -0.8407688 0.1196268 -0.827458 -0.5226476 0.2053114 0.5879882 -0.6555112 0.4738934 0.07571399 -0.7536299 0.6529237 0.1782882 -0.8329461 0.5238456 0.5785899 -0.6055189 0.5464254 0.1497783 -0.9670164 0.2060241 0.1182811 -0.9579306 0.2614931 -0.994749 0.01469337 0.101285 -0.9926303 0.1027346 0.06427264 -0.4434116 0.8951804 0.04515022 -0.4138267 0.9074281 -0.07295143 -0.4849444 0.874545 -2.31367e-6 -1.4138e-6 0 -1 -5.21713e-6 -1 -9.87456e-7 -0.0312457 -0.9994885 -0.006819605 -0.0221188 -0.9997543 0.001488804 2.37993e-5 -1 5.0362e-5 0.002456784 -0.9991959 -0.04001933 -0.01351159 -0.9986205 -0.05074238 -0.007404625 -0.9999691 -0.002663493 -0.006559848 -0.9997721 0.02031409 0.005249023 -0.9995886 0.02819651 -0.03308689 -0.9985523 -0.04241108 -0.03393387 -0.9993694 0.01045912 -0.002466559 -0.9997731 -0.02116179 0.5625076 0.8191086 -0.112456 0.4793964 0.8133304 -0.3296559 -0.9999302 -3.97464e-4 -0.01181858 -0.999854 -0.01707005 8.57435e-4 -0.9998291 -0.01820611 0.003236711 -0.5583469 0.816833 -0.1450268 -0.5681154 0.7955833 -0.2104571 0.9946826 -0.08597427 -0.05670309 0.9994055 -0.02954083 0.01777702 0.004370391 0.9999776 -0.00507766 0.01152008 0.9996532 -0.02367955 -0.03444099 0.9994048 0.001975238 0.03484785 0.999195 0.01987296 0.06619232 0.9978065 -9.11919e-4 0.06575399 0.9977093 -0.01589393 0.2324028 0.9654414 -0.1179484 -0.272727 -0.8640773 0.4230725 0.7632826 -0.645797 -0.01860153 0.2503061 0.00365889 -0.9681599 0.9999764 -0.006869375 6.22494e-6 -0.2559697 -0.9655786 0.04623591 -0.4694701 -0.8828005 -0.01615875 0.01395988 0.9998953 -0.003827512 -0.9838749 0.1778851 -0.01863652 -0.9474848 0.319514 0.01354771 -0.7900997 0.6107968 -0.0516709 -0.7191565 0.6947773 -0.009933114 -0.4696145 0.8828225 0.009318947 -0.3945242 0.9188829 -0.002240538 -0.3636043 0.9315462 0.003709852 0.06976252 -0.8842528 0.4617686 0.3608219 -0.8531297 0.376799 0.00494951 0.9999857 -0.002028107 -0.1916331 0.9783127 0.07862019 0.005896329 0.9999827 -3.56167e-6 -0.3187491 0.3573514 -0.8778947 -0.4251361 0.8424407 -0.3309882 1.16521e-5 0.9999969 -0.002523541 -0.005432426 0.9999849 -9.56914e-4 -0.005879878 0.9999827 1.81246e-6 -0.9829964 0.06097781 -0.1732048 -0.9368816 0.0285623 -0.3484786 0.997394 -0.063434 -0.03437215 0.999715 0.02176302 0.009816706 0.9999539 0.003097832 -0.009088635 0.3863917 -0.922177 -0.0170626 0.1591699 -0.9871459 0.01442086 0.3747824 -0.927031 -0.01231426 1.18106e-5 1.68675e-7 -1 1.01801e-5 4.6237e-6 -1 1.17595e-5 -1.3185e-5 -1 1.55417e-5 1.88478e-5 -1 8.49626e-6 2.95496e-6 -1 -1.5263e-6 1.18872e-4 -1 5.49652e-6 -9.98732e-7 -1 0.9996075 -0.01618295 0.02287381 0.9576163 0.2497914 0.1434407 0.4938477 0.8651834 0.08701807 0.08183103 0.07767653 -0.9936147 -0.5018499 -0.8648982 -0.009893476 0.1753887 0.02755653 -0.9841135 0.0128324 0.03711909 -0.9992285 0.02149415 -0.01863509 -0.9995953 0.02101212 -0.02193951 -0.9995386 -0.1495462 -0.1477016 -0.9776606 0.05689537 0.06188315 -0.9964604 1.17085e-5 0 -1 0.06935995 0.02323383 -0.9973211 -4.45904e-6 2.15306e-4 -1 2.74334e-5 2.76083e-5 -1 0.00436896 0.004325568 -0.9999811 -0.01578551 -0.003089249 -0.9998707 0.05621349 0.01764327 -0.998263 -0.01879006 -0.0265693 -0.9994704 -0.02604907 0.03952699 -0.9988789 7.21659e-6 0 -1 4.84819e-5 0.007918596 -0.9999687 2.09687e-5 1.7912e-4 -1 -0.1596896 -9.11323e-4 -0.987167 0.4849263 0.8745551 2.80999e-6 0.3946677 0.9185648 -0.0218203 0.5093696 0.8605198 0.006959199 0.747671 0.6637401 -0.02090996 0.8465863 0.5265686 -0.07757008 0.9503988 0.3110259 0.002228796 0.5879024 0.808932 3.66185e-6 0.02458733 -0.9987548 0.0434103 -0.02160239 -0.9997223 0.00942111 0.01059871 -0.9984721 0.05423325 -0.9892613 -0.1411867 0.03779608 -0.9992634 -0.01644313 -0.03467535 -0.07170575 0.1221691 -0.9899157 -0.01898711 0.01468348 -0.9997119 -0.02864581 0.06671714 -0.9973607 -0.6092182 -0.010531 0.7929328 -0.07362383 -0.9393891 0.3348549 0.7008909 -0.5337646 0.4731252 0.8337613 -0.3971043 0.3836021 -0.08983391 -0.815045 0.5723912 0.2885083 -0.9214586 0.2601485 0.08309364 -0.9832934 0.1619556 0.0534023 -0.9894925 0.1343609 -0.07914286 -0.7638472 0.6405263 -0.6307367 -0.7448605 0.2176102 -0.2271678 -0.9638542 0.1392116 -0.6772837 -0.5526646 0.4856425 -0.3655392 -0.49865 0.7859577 -0.5548316 -0.3192333 0.7682785 0.3518245 -0.07938301 0.9326938 0.5180169 -0.0469895 0.8540788 0.5421748 -0.02773648 0.8398078 0.1195595 -0.080513 0.9895571 0.2431306 -0.03152769 0.9694812 0.2884729 -0.4467502 0.8468753 0.3153802 -0.4488881 0.8360831 0.1954076 -0.5620622 0.8036804 0.1070545 -0.4509208 0.8861206 -0.1070554 -0.4509189 0.8861216 -0.1954215 -0.5620718 0.8036702 -0.3153825 -0.4489117 0.8360695 -0.3340011 -0.4501768 0.8281209 -0.5018664 -0.0647763 0.8625164 0.6731516 -0.3432823 0.6549994 0.375369 -0.4616496 0.8037274 0.5290802 -0.3666331 0.7652806 -0.6351261 -0.3099389 0.7074976 -0.2763308 -0.7346482 0.6196236 -0.2688961 -0.7365332 0.6206559 -0.4707093 -0.7993911 0.373372 -0.4955915 -0.5476307 0.6741585 -0.4371829 -0.5765613 0.6902524 -0.7275909 -0.2789816 0.6267223 0.6946297 0.00473541 0.719352 0.7303734 -0.006094932 0.6830209 -1.66085e-5 -0.05653405 0.9984008 -0.1195588 -0.08051151 0.9895573 -0.2431238 -0.03152507 0.9694829 -0.3518372 -0.07937836 0.9326896 -0.471107 -0.05666512 0.8802542 -0.7303768 0.002067029 0.6830414 -0.7413413 0.007032275 0.6710914 0.3813788 -0.6829662 0.6229828 -0.1229404 -0.8053502 0.579911 0.3693046 -0.7789613 0.5067873 0.5033299 -0.7778624 0.3762835 0.5237146 -0.5266814 0.6695744 0.5203624 -0.5283064 0.6709066 0.7185439 -0.2778205 0.6375818 0.718279 -0.3733571 0.5870944 0.7295628 -0.2962683 0.6164117 0.2999265 -0.8867561 0.3517212 0.6172964 -0.6169246 0.4882102 0.5006275 -0.7538118 0.4256053 0.2531336 -0.9318027 0.260129 0.07409596 -0.9954726 0.05953264 0.1863412 -0.8967377 0.4014205 0.01704108 -0.9996064 -0.02228999 -0.02202343 -0.9996011 -0.0176872 -0.2129934 -0.9589563 0.1871813 -0.2852635 -0.9011706 0.3263683 -0.5388355 -0.7187525 0.439376 -0.4834186 -0.7671775 0.4215983 -0.6078405 -0.6282277 0.4856542 -0.7127113 -0.3700712 0.5958943 -0.7367714 -0.3183754 0.596494 -0.2355777 -0.9105976 0.3395808 0.001893043 -0.9998987 0.01411026 -0.7705341 0.524855 0.361669 0.8232404 0.01104104 0.5675857 0.775734 -0.00804162 0.6310089 0.7903486 -0.04252731 0.6111796 0.6735427 0.03208643 0.7384517 0.7767007 -0.006259262 0.6298387 0.7914705 0.02728754 0.6105979 + + + + + + + + + + 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 + + + + + + + + + + + + + + + + +

2 0 0 6 0 1 7 0 2 4 1 3 0 1 4 3 1 5 7 2 6 6 2 7 3 2 8 3 3 9 0 3 10 5 3 11 10 4 12 8 4 13 0 4 14 8 5 15 5 5 16 0 5 17 8 6 18 9 6 19 5 6 20 14 7 21 2 7 22 11 7 23 11 8 24 7 8 25 3 8 26 11 9 27 3 9 28 12 9 29 3 10 30 9 10 31 12 10 32 9 11 33 3 11 34 5 11 35 14 12 36 13 12 37 2 12 38 2 13 39 7 13 40 11 13 41 29 14 42 15 14 43 22 14 44 18 15 45 26 15 46 28 15 47 19 16 48 23 16 49 17 16 50 23 17 51 26 17 52 17 17 53 26 18 54 20 18 55 17 18 56 26 19 57 16 19 58 20 19 59 16 20 60 26 20 61 18 20 62 19 21 63 27 21 64 23 21 65 19 22 66 21 22 67 27 22 68 21 23 69 25 23 70 27 23 71 29 24 72 30 24 73 15 24 74 29 25 75 22 25 76 48 25 77 50 26 78 29 26 79 48 26 80 50 27 81 48 27 82 33 27 83 50 28 84 33 28 85 49 28 86 33 29 87 39 29 88 49 29 89 40 30 90 33 30 91 48 30 92 34 31 93 40 31 94 48 31 95 36 32 96 34 32 97 48 32 98 32 33 99 36 33 100 48 33 101 35 34 102 32 34 103 48 34 104 31 35 105 35 35 106 48 35 107 37 36 108 31 36 109 48 36 110 38 37 111 37 37 112 48 37 113 43 38 114 41 38 115 38 38 116 46 39 117 43 39 118 38 39 119 44 40 120 10 40 121 0 40 122 4 41 123 44 41 124 0 41 125 24 42 126 45 42 127 46 42 128 21 43 129 47 43 130 25 43 131 47 44 132 24 44 133 25 44 134 47 45 135 45 45 136 24 45 137 3 46 138 6 46 139 4 46 140 1 47 141 51 47 142 2 47 143 2 48 144 51 48 145 6 48 146 51 49 147 49 49 148 6 49 149 51 50 150 50 50 151 49 50 152 1 51 153 2 51 154 52 51 155 49 52 156 4 52 157 6 52 158 50 53 159 1 53 160 29 53 161 1 54 162 50 54 163 51 54 164 30 55 165 29 55 166 1 55 167 54 56 168 56 56 169 55 56 170 53 57 171 8 57 172 10 57 173 53 58 174 10 58 175 44 58 176 77 59 177 283 59 178 91 59 179 283 60 180 77 60 181 281 60 182 281 61 183 77 61 184 279 61 185 281 62 186 279 62 187 30 62 188 30 63 189 279 63 190 61 63 191 197 64 192 190 64 193 181 64 194 60 65 195 59 65 196 61 65 197 60 66 198 58 66 199 59 66 200 217 67 201 282 67 202 59 67 203 58 68 204 217 68 205 59 68 206 234 69 207 280 69 208 277 69 209 282 70 210 267 70 211 284 70 212 165 71 213 282 71 214 217 71 215 237 72 216 227 72 217 274 72 218 274 73 219 227 73 220 277 73 221 277 74 222 227 74 223 254 74 224 280 75 225 234 75 226 58 75 227 270 76 228 289 76 229 288 76 230 288 77 231 241 77 232 270 77 233 267 78 234 241 78 235 288 78 236 267 79 237 288 79 238 284 79 239 222 80 240 92 80 241 242 80 242 96 81 243 106 81 244 97 81 245 95 82 246 279 82 247 77 82 248 79 83 249 279 83 250 95 83 251 69 84 252 279 84 253 79 84 254 65 85 255 279 85 256 69 85 257 80 86 258 279 86 259 65 86 260 64 87 261 279 87 262 80 87 263 85 88 264 279 88 265 64 88 266 89 89 267 279 89 268 85 89 269 82 90 270 86 90 271 245 90 272 103 91 273 86 91 274 82 91 275 103 92 276 83 92 277 86 92 278 106 93 279 83 93 280 103 93 281 104 94 282 106 94 283 103 94 284 106 95 285 107 95 286 97 95 287 106 96 288 104 96 289 107 96 290 222 97 291 252 97 292 100 97 293 107 98 294 252 98 295 97 98 296 101 99 297 105 99 298 94 99 299 100 100 300 94 100 301 222 100 302 100 101 303 101 101 304 94 101 305 102 102 306 70 102 307 101 102 308 102 103 309 67 103 310 70 103 311 102 104 312 101 104 313 100 104 314 102 105 315 178 105 316 67 105 317 91 106 318 178 106 319 102 106 320 67 107 321 178 107 322 230 107 323 73 108 324 67 108 325 230 108 326 70 109 327 67 109 328 73 109 329 70 110 330 105 110 331 101 110 332 70 111 333 93 111 334 105 111 335 70 112 336 75 112 337 93 112 338 73 113 339 75 113 340 70 113 341 85 114 342 78 114 343 82 114 344 85 115 345 82 115 346 89 115 347 80 116 348 62 116 349 64 116 350 80 117 351 76 117 352 62 117 353 65 118 354 76 118 355 80 118 356 65 119 357 81 119 358 76 119 359 69 120 360 81 120 361 65 120 362 77 121 363 71 121 364 95 121 365 91 122 366 71 122 367 77 122 368 63 123 369 245 123 370 86 123 371 57 124 372 86 124 373 83 124 374 57 125 375 63 125 376 86 125 377 96 126 378 83 126 379 106 126 380 88 127 381 83 127 382 96 127 383 88 128 384 57 128 385 83 128 386 245 129 387 89 129 388 82 129 389 272 130 390 89 130 391 245 130 392 82 131 393 78 131 394 103 131 395 141 132 396 230 132 397 178 132 398 141 133 399 73 133 400 230 133 401 102 134 402 71 134 403 91 134 404 78 135 405 64 135 406 62 135 407 62 136 408 87 136 409 78 136 410 76 137 411 87 137 412 62 137 413 76 138 414 84 138 415 87 138 416 81 139 417 84 139 418 76 139 419 68 140 420 84 140 421 81 140 422 68 141 423 72 141 424 84 141 425 74 142 426 72 142 427 68 142 428 74 143 429 71 143 430 72 143 431 68 144 432 69 144 433 79 144 434 81 145 435 69 145 436 68 145 437 71 146 438 79 146 439 95 146 440 74 147 441 79 147 442 71 147 443 68 148 444 79 148 445 74 148 446 63 149 447 119 149 448 245 149 449 57 150 450 119 150 451 63 150 452 98 151 453 247 151 454 99 151 455 92 152 456 93 152 457 99 152 458 93 153 459 98 153 460 99 153 461 98 154 462 93 154 463 75 154 464 94 155 465 92 155 466 222 155 467 94 156 468 105 156 469 92 156 470 88 157 471 97 157 472 154 157 473 88 158 474 96 158 475 97 158 476 88 159 477 207 159 478 172 159 479 154 160 480 207 160 481 88 160 482 93 161 483 92 161 484 105 161 485 85 162 486 64 162 487 78 162 488 239 163 489 226 163 490 137 163 491 239 164 492 137 164 493 171 164 494 171 165 495 185 165 496 239 165 497 247 166 498 155 166 499 99 166 500 155 167 501 242 167 502 99 167 503 97 168 504 252 168 505 260 168 506 242 169 507 252 169 508 222 169 509 260 170 510 252 170 511 242 170 512 212 171 513 236 171 514 132 171 515 225 172 516 235 172 517 130 172 518 225 173 519 213 173 520 235 173 521 192 174 522 213 174 523 225 174 524 160 175 525 213 175 526 192 175 527 160 176 528 205 176 529 213 176 530 212 177 531 201 177 532 134 177 533 267 178 534 170 178 535 221 178 536 165 179 537 217 179 538 242 179 539 165 180 540 267 180 541 282 180 542 170 181 543 267 181 544 165 181 545 242 182 546 116 182 547 117 182 548 116 182 549 242 182 550 264 182 551 264 183 552 131 183 553 116 183 554 131 184 555 264 184 556 263 184 557 242 185 558 155 185 559 264 185 560 255 186 561 234 186 562 159 186 563 234 187 564 255 187 565 260 187 566 260 188 567 217 188 568 234 188 569 242 189 570 217 189 571 260 189 572 242 190 573 117 190 574 165 190 575 159 191 576 180 191 577 189 191 578 234 182 579 180 182 580 159 182 581 159 192 582 206 192 583 156 192 584 189 193 585 206 193 586 159 193 587 159 194 588 145 194 589 228 194 590 156 195 591 145 195 592 159 195 593 277 196 594 254 196 595 180 196 596 180 197 597 234 197 598 277 197 599 180 198 600 254 198 601 236 198 602 254 199 603 132 199 604 236 199 605 242 200 606 92 200 607 99 200 608 213 182 609 205 182 610 235 182 611 205 201 612 246 201 613 235 201 614 134 202 615 236 202 616 212 202 617 212 203 618 124 203 619 201 203 620 266 204 621 124 204 622 212 204 623 58 205 624 234 205 625 217 205 626 108 206 627 224 206 628 139 206 629 108 207 630 139 207 631 201 207 632 108 208 633 201 208 634 124 208 635 138 209 636 113 209 637 167 209 638 224 210 639 113 210 640 138 210 641 224 211 642 136 211 643 113 211 644 224 212 645 108 212 646 136 212 647 159 213 648 250 213 649 172 213 650 159 214 651 123 214 652 250 214 653 172 215 654 255 215 655 159 215 656 130 216 657 235 216 658 129 216 659 129 217 660 235 217 661 233 217 662 233 218 663 166 218 664 129 218 665 221 219 666 220 219 667 241 219 668 188 220 669 220 220 670 221 220 671 180 221 672 134 221 673 201 221 674 236 222 675 134 222 676 180 222 677 201 223 678 139 223 679 180 223 680 254 224 681 251 224 682 266 224 683 254 225 684 227 225 685 251 225 686 170 226 687 165 226 688 265 226 689 265 227 690 169 227 691 193 227 692 165 228 693 169 228 694 265 228 695 172 229 696 250 229 697 150 229 698 250 230 699 123 230 700 150 230 701 191 231 702 226 231 703 146 231 704 191 232 705 137 232 706 226 232 707 109 233 708 137 233 709 191 233 710 143 234 711 137 234 712 109 234 713 143 235 714 171 235 715 137 235 716 174 236 717 171 236 718 143 236 719 174 237 720 185 237 721 171 237 722 220 238 723 240 238 724 246 238 725 124 239 726 266 239 727 239 239 728 168 240 729 264 240 730 155 240 731 152 241 732 264 241 733 168 241 734 132 242 735 266 242 736 212 242 737 132 243 738 254 243 739 266 243 740 260 244 741 154 244 742 97 244 743 152 245 744 168 245 745 163 245 746 220 246 747 200 246 748 241 246 749 220 247 750 160 247 751 200 247 752 246 248 753 160 248 754 220 248 755 160 249 756 246 249 757 205 249 758 266 250 759 226 250 760 239 250 761 266 251 762 146 251 763 226 251 764 266 252 765 258 252 766 146 252 767 260 253 768 207 253 769 154 253 770 260 254 771 255 254 772 207 254 773 185 255 774 124 255 775 239 255 776 108 256 777 124 256 778 185 256 779 108 257 780 185 257 781 136 257 782 136 258 783 185 258 784 174 258 785 174 259 786 229 259 787 136 259 788 246 260 789 233 260 790 235 260 791 240 261 792 233 261 793 246 261 794 167 262 795 157 262 796 138 262 797 175 263 798 157 263 799 243 263 800 138 264 801 157 264 802 175 264 803 228 265 804 243 265 805 159 265 806 243 266 807 228 266 808 175 266 809 159 267 810 243 267 811 123 267 812 253 268 813 244 268 814 248 268 815 248 269 816 203 269 817 253 269 818 244 270 819 253 270 820 263 270 821 152 271 822 263 271 823 264 271 824 215 272 825 263 272 826 152 272 827 244 273 828 263 273 829 215 273 830 240 182 831 193 182 832 233 182 833 193 274 834 126 274 835 166 274 836 193 275 837 169 275 838 126 275 839 193 276 840 166 276 841 233 276 842 203 277 843 166 277 844 126 277 845 203 182 846 248 182 847 166 182 848 265 278 849 221 278 850 170 278 851 265 279 852 188 279 853 221 279 854 188 280 855 265 280 856 193 280 857 220 281 858 193 281 859 240 281 860 188 282 861 193 282 862 220 282 863 215 283 864 133 283 865 151 283 866 215 284 867 142 284 868 133 284 869 120 285 870 142 285 871 118 285 872 120 286 873 133 286 874 142 286 875 141 287 876 133 287 877 120 287 878 141 288 879 151 288 880 133 288 881 114 289 882 151 289 883 141 289 884 196 290 885 231 290 886 218 290 887 157 291 888 231 291 889 196 291 890 128 292 891 115 292 892 196 292 893 256 293 894 115 293 895 128 293 896 256 294 897 176 294 898 115 294 899 128 295 900 196 295 901 218 295 902 128 296 903 229 296 904 256 296 905 218 297 906 229 297 907 128 297 908 272 298 909 190 298 910 211 298 911 158 299 912 195 299 913 232 299 914 211 300 915 197 300 916 195 300 917 211 301 918 190 301 919 197 301 920 158 302 921 258 302 922 237 302 923 158 303 924 232 303 925 258 303 926 195 304 927 219 304 928 232 304 929 195 305 930 273 305 931 211 305 932 158 306 933 273 306 934 195 306 935 197 307 936 219 307 937 195 307 938 197 308 939 181 308 940 219 308 941 259 309 942 181 309 943 190 309 944 140 310 945 199 310 946 208 310 947 140 311 948 182 311 949 199 311 950 182 312 951 109 312 952 191 312 953 182 313 954 143 313 955 109 313 956 140 314 957 143 314 958 182 314 959 140 315 960 174 315 961 143 315 962 208 316 963 174 316 964 140 316 965 121 317 966 209 317 967 111 317 968 161 318 969 209 318 970 121 318 971 161 319 972 129 319 973 209 319 974 130 320 975 129 320 976 161 320 977 113 321 978 231 321 979 167 321 980 136 322 981 231 322 982 113 322 983 136 323 984 218 323 985 231 323 986 136 324 987 229 324 988 218 324 989 231 325 990 157 325 991 167 325 992 110 326 993 225 326 994 130 326 995 192 327 996 112 327 997 160 327 998 192 328 999 149 328 1000 112 328 1001 225 329 1002 149 329 1003 192 329 1004 110 330 1005 149 330 1006 225 330 1007 110 331 1008 173 331 1009 149 331 1010 161 332 1011 173 332 1012 110 332 1013 161 333 1014 121 333 1015 173 333 1016 130 334 1017 161 334 1018 110 334 1019 153 335 1020 114 335 1021 111 335 1022 249 336 1023 114 336 1024 153 336 1025 257 337 1026 114 337 1027 249 337 1028 257 338 1029 151 338 1030 114 338 1031 244 339 1032 151 339 1033 257 339 1034 244 340 1035 215 340 1036 151 340 1037 152 341 1038 142 341 1039 215 341 1040 118 342 1041 142 342 1042 152 342 1043 270 343 1044 204 343 1045 271 343 1046 200 344 1047 204 344 1048 270 344 1049 214 345 1050 204 345 1051 200 345 1052 216 346 1053 204 346 1054 214 346 1055 216 347 1056 194 347 1057 204 347 1058 184 348 1059 194 348 1060 216 348 1061 184 349 1062 210 349 1063 194 349 1064 179 350 1065 238 350 1066 210 350 1067 210 351 1068 144 351 1069 194 351 1070 210 352 1071 238 352 1072 144 352 1073 194 353 1074 271 353 1075 204 353 1076 194 354 1077 144 354 1078 271 354 1079 144 355 1080 268 355 1081 271 355 1082 144 356 1083 269 356 1084 268 356 1085 210 357 1086 184 357 1087 179 357 1088 200 358 1089 270 358 1090 241 358 1091 208 359 1092 259 359 1093 176 359 1094 259 360 1095 127 360 1096 176 360 1097 190 361 1098 127 361 1099 259 361 1100 245 362 1101 190 362 1102 272 362 1103 127 363 1104 190 363 1105 245 363 1106 123 364 1107 162 364 1108 164 364 1109 123 365 1110 243 365 1111 162 365 1112 183 366 1113 117 366 1114 116 366 1115 177 367 1116 117 367 1117 183 367 1118 131 368 1119 187 368 1120 135 368 1121 131 369 1122 261 369 1123 187 369 1124 263 370 1125 261 370 1126 131 370 1127 135 371 1128 116 371 1129 131 371 1130 183 372 1131 116 372 1132 135 372 1133 263 373 1134 253 373 1135 261 373 1136 189 374 1137 139 374 1138 224 374 1139 180 375 1140 139 375 1141 189 375 1142 249 376 1143 262 376 1144 257 376 1145 147 377 1146 125 377 1147 262 377 1148 209 378 1149 125 378 1150 147 378 1151 209 379 1152 129 379 1153 125 379 1154 147 380 1155 249 380 1156 153 380 1157 262 381 1158 249 381 1159 147 381 1160 147 382 1161 111 382 1162 209 382 1163 153 383 1164 111 383 1165 147 383 1166 184 384 1167 173 384 1168 121 384 1169 184 385 1170 149 385 1171 173 385 1172 216 386 1173 149 386 1174 184 386 1175 216 387 1176 112 387 1177 149 387 1178 216 388 1179 160 388 1180 112 388 1181 214 389 1182 160 389 1183 216 389 1184 200 390 1185 160 390 1186 214 390 1187 224 391 1188 202 391 1189 189 391 1190 198 392 1191 202 392 1192 224 392 1193 224 393 1194 148 393 1195 198 393 1196 138 394 1197 148 394 1198 224 394 1199 138 395 1200 186 395 1201 148 395 1202 138 396 1203 175 396 1204 186 396 1205 227 397 1206 237 397 1207 251 397 1208 251 398 1209 237 398 1210 258 398 1211 251 399 1212 258 399 1213 266 399 1214 178 400 1215 269 400 1216 238 400 1217 238 401 1218 114 401 1219 178 401 1220 179 402 1221 114 402 1222 238 402 1223 179 403 1224 121 403 1225 114 403 1226 121 404 1227 111 404 1228 114 404 1229 174 405 1230 256 405 1231 229 405 1232 208 406 1233 256 406 1234 174 406 1235 208 407 1236 176 407 1237 256 407 1238 141 408 1239 178 408 1240 114 408 1241 118 409 1242 73 409 1243 120 409 1244 120 410 1245 73 410 1246 141 410 1247 166 411 1248 125 411 1249 129 411 1250 262 412 1251 125 412 1252 166 412 1253 257 413 1254 248 413 1255 244 413 1256 262 414 1257 248 414 1258 257 414 1259 262 415 1260 166 415 1261 248 415 1262 183 416 1263 126 416 1264 177 416 1265 203 417 1266 261 417 1267 253 417 1268 203 418 1269 187 418 1270 261 418 1271 126 419 1272 187 419 1273 203 419 1274 126 420 1275 135 420 1276 187 420 1277 126 421 1278 183 421 1279 135 421 1280 177 422 1281 165 422 1282 117 422 1283 245 423 1284 119 423 1285 127 423 1286 119 424 1287 57 424 1288 223 424 1289 57 425 1290 164 425 1291 223 425 1292 199 426 1293 259 426 1294 208 426 1295 199 427 1296 181 427 1297 259 427 1298 182 428 1299 181 428 1300 199 428 1301 182 429 1302 219 429 1303 181 429 1304 191 430 1305 219 430 1306 182 430 1307 191 431 1308 232 431 1309 219 431 1310 146 432 1311 232 432 1312 191 432 1313 146 433 1314 258 433 1315 232 433 1316 223 434 1317 243 434 1318 119 434 1319 223 435 1320 162 435 1321 243 435 1322 164 436 1323 162 436 1324 223 436 1325 168 437 1326 155 437 1327 122 437 1328 155 438 1329 247 438 1330 122 438 1331 247 439 1332 163 439 1333 168 439 1334 168 440 1335 122 440 1336 247 440 1337 255 441 1338 172 441 1339 207 441 1340 88 442 1341 172 442 1342 150 442 1343 202 443 1344 206 443 1345 189 443 1346 198 444 1347 206 444 1348 202 444 1349 198 445 1350 156 445 1351 206 445 1352 148 446 1353 156 446 1354 198 446 1355 148 447 1356 145 447 1357 156 447 1358 186 448 1359 145 448 1360 148 448 1361 186 449 1362 228 449 1363 145 449 1364 228 450 1365 186 450 1366 175 450 1367 126 451 1368 165 451 1369 177 451 1370 169 452 1371 165 452 1372 126 452 1373 127 453 1374 115 453 1375 176 453 1376 119 454 1377 115 454 1378 127 454 1379 119 455 1380 196 455 1381 115 455 1382 119 456 1383 157 456 1384 196 456 1385 243 457 1386 157 457 1387 119 457 1388 238 458 1389 269 458 1390 144 458 1391 121 459 1392 179 459 1393 184 459 1394 221 460 1395 241 460 1396 267 460 1397 271 461 1398 289 461 1399 270 461 1400 271 462 1401 286 462 1402 289 462 1403 268 463 1404 286 463 1405 271 463 1406 269 464 1407 286 464 1408 268 464 1409 269 465 1410 285 465 1411 286 465 1412 275 466 1413 272 466 1414 211 466 1415 237 467 1416 274 467 1417 278 467 1418 237 468 1419 278 468 1420 158 468 1421 158 469 1422 278 469 1423 276 469 1424 158 470 1425 276 470 1426 273 470 1427 273 471 1428 276 471 1429 275 471 1430 273 472 1431 275 472 1432 211 472 1433 289 473 1434 286 473 1435 288 473 1436 284 474 1437 287 474 1438 52 474 1439 284 475 1440 52 475 1441 282 475 1442 286 476 1443 285 476 1444 288 476 1445 288 477 1446 285 477 1447 287 477 1448 288 478 1449 287 478 1450 284 478 1451 15 479 1452 61 479 1453 59 479 1454 283 480 1455 281 480 1456 287 480 1457 281 481 1458 52 481 1459 287 481 1460 52 482 1461 2 482 1462 282 482 1463 287 483 1464 285 483 1465 283 483 1466 59 484 1467 282 484 1468 2 484 1469 15 485 1470 30 485 1471 61 485 1472 52 486 1473 281 486 1474 30 486 1475 30 487 1476 1 487 1477 52 487 1478 2 488 1479 290 488 1480 59 488 1481 15 489 1482 59 489 1483 290 489 1484 291 490 1485 13 490 1486 18 490 1487 28 491 1488 291 491 1489 18 491 1490 291 492 1491 290 492 1492 13 492 1493 13 493 1494 290 493 1495 2 493 1496 22 494 1497 290 494 1498 291 494 1499 22 495 1500 15 495 1501 290 495 1502 22 496 1503 291 496 1504 58 496 1505 28 497 1506 58 497 1507 291 497 1508 304 498 1509 58 498 1510 28 498 1511 301 499 1512 296 499 1513 298 499 1514 296 500 1515 301 500 1516 292 500 1517 22 501 1518 60 501 1519 301 501 1520 58 502 1521 304 502 1522 295 502 1523 58 503 1524 295 503 1525 280 503 1526 294 504 1527 293 504 1528 275 504 1529 277 505 1530 280 505 1531 295 505 1532 296 506 1533 295 506 1534 304 506 1535 292 507 1536 294 507 1537 296 507 1538 293 508 1539 294 508 1540 292 508 1541 22 509 1542 58 509 1543 60 509 1544 274 510 1545 277 510 1546 294 510 1547 274 511 1548 294 511 1549 275 511 1550 276 512 1551 274 512 1552 275 512 1553 277 513 1554 295 513 1555 296 513 1556 277 514 1557 296 514 1558 294 514 1559 278 515 1560 274 515 1561 276 515 1562 301 516 1563 298 516 1564 302 516 1565 298 517 1566 300 517 1567 299 517 1568 299 518 1569 302 518 1570 298 518 1571 297 519 1572 303 519 1573 24 519 1574 298 520 1575 296 520 1576 304 520 1577 300 521 1578 297 521 1579 299 521 1580 300 522 1581 303 522 1582 297 522 1583 304 523 1584 303 523 1585 300 523 1586 298 524 1587 304 524 1588 300 524 1589 23 525 1590 24 525 1591 303 525 1592 25 526 1593 24 526 1594 27 526 1595 302 527 1596 22 527 1597 301 527 1598 26 528 1599 23 528 1600 303 528 1601 23 529 1602 27 529 1603 24 529 1604 304 530 1605 26 530 1606 303 530 1607 28 531 1608 26 531 1609 304 531 1610 24 532 1611 46 532 1612 297 532 1613 297 533 1614 46 533 1615 38 533 1616 275 534 1617 293 534 1618 272 534 1619 293 535 1620 89 535 1621 272 535 1622 89 536 1623 293 536 1624 292 536 1625 89 537 1626 292 537 1627 279 537 1628 279 538 1629 292 538 1630 301 538 1631 61 539 1632 279 539 1633 301 539 1634 60 540 1635 61 540 1636 301 540 1637 38 541 1638 299 541 1639 297 541 1640 38 542 1641 48 542 1642 299 542 1643 48 543 1644 302 543 1645 299 543 1646 22 544 1647 302 544 1648 48 544 1649 118 545 1650 152 545 1651 163 545 1652 75 546 1653 118 546 1654 163 546 1655 75 547 1656 73 547 1657 118 547 1658 123 548 1659 164 548 1660 150 548 1661 88 549 1662 150 549 1663 164 549 1664 57 550 1665 88 550 1666 164 550 1667 90 551 1668 252 551 1669 107 551 1670 90 552 1671 100 552 1672 252 552 1673 90 553 1674 107 553 1675 104 553 1676 66 554 1677 90 554 1678 104 554 1679 66 555 1680 102 555 1681 90 555 1682 90 556 1683 102 556 1684 100 556 1685 66 557 1686 104 557 1687 87 557 1688 66 558 1689 72 558 1690 102 558 1691 87 559 1692 104 559 1693 103 559 1694 78 560 1695 87 560 1696 103 560 1697 71 561 1698 102 561 1699 72 561 1700 66 562 1701 84 562 1702 72 562 1703 66 563 1704 87 563 1705 84 563 1706 75 564 1707 163 564 1708 98 564 1709 98 565 1710 163 565 1711 247 565 1712 457 566 1713 328 566 1714 397 566 1715 472 567 1716 457 567 1717 397 567 1718 480 568 1719 467 568 1720 465 568 1721 480 569 1722 475 569 1723 467 569 1724 476 570 1725 475 570 1726 454 570 1727 470 571 1728 453 571 1729 465 571 1730 465 572 1731 453 572 1732 452 572 1733 480 573 1734 454 573 1735 475 573 1736 480 574 1737 465 574 1738 452 574 1739 463 575 1740 451 575 1741 454 575 1742 480 576 1743 463 576 1744 454 576 1745 480 577 1746 452 577 1747 463 577 1748 463 578 1749 452 578 1750 448 578 1751 463 579 1752 321 579 1753 451 579 1754 463 580 1755 448 580 1756 321 580 1757 483 581 1758 396 581 1759 464 581 1760 464 582 1761 396 582 1762 410 582 1763 436 583 1764 410 583 1765 396 583 1766 472 584 1767 377 584 1768 474 584 1769 472 585 1770 397 585 1771 377 585 1772 377 586 1773 397 586 1774 408 586 1775 348 587 1776 11 587 1777 12 587 1778 417 588 1779 362 588 1780 383 588 1781 330 589 1782 327 589 1783 402 589 1784 327 590 1785 369 590 1786 402 590 1787 327 591 1788 438 591 1789 369 591 1790 438 592 1791 441 592 1792 369 592 1793 438 593 1794 432 593 1795 441 593 1796 432 594 1797 385 594 1798 441 594 1799 392 595 1800 433 595 1801 14 595 1802 433 596 1803 384 596 1804 14 596 1805 341 597 1806 386 597 1807 378 597 1808 378 598 1809 415 598 1810 341 598 1811 378 599 1812 412 599 1813 415 599 1814 412 600 1815 403 600 1816 415 600 1817 412 601 1818 368 601 1819 403 601 1820 368 602 1821 359 602 1822 403 602 1823 368 603 1824 364 603 1825 359 603 1826 364 604 1827 374 604 1828 359 604 1829 464 605 1830 410 605 1831 389 605 1832 317 606 1833 358 606 1834 389 606 1835 393 607 1836 328 607 1837 437 607 1838 328 608 1839 393 608 1840 397 608 1841 404 609 1842 437 609 1843 328 609 1844 393 610 1845 437 610 1846 404 610 1847 396 611 1848 346 611 1849 398 611 1850 346 612 1851 330 612 1852 398 612 1853 346 613 1854 327 613 1855 330 613 1856 438 614 1857 327 614 1858 346 614 1859 414 615 1860 337 615 1861 313 615 1862 414 616 1863 373 616 1864 337 616 1865 373 617 1866 349 617 1867 337 617 1868 373 618 1869 381 618 1870 349 618 1871 381 619 1872 382 619 1873 349 619 1874 381 620 1875 367 620 1876 382 620 1877 367 621 1878 312 621 1879 382 621 1880 367 622 1881 357 622 1882 312 622 1883 483 623 1884 346 623 1885 396 623 1886 438 624 1887 346 624 1888 483 624 1889 43 625 1890 432 625 1891 438 625 1892 384 626 1893 439 626 1894 14 626 1895 433 627 1896 425 627 1897 380 627 1898 433 628 1899 376 628 1900 425 628 1901 433 629 1902 363 629 1903 376 629 1904 363 630 1905 310 630 1906 376 630 1907 363 631 1908 320 631 1909 310 631 1910 380 632 1911 384 632 1912 433 632 1913 309 633 1914 326 633 1915 395 633 1916 309 634 1917 315 634 1918 326 634 1919 315 635 1920 329 635 1921 326 635 1922 309 636 1923 395 636 1924 434 636 1925 395 637 1926 430 637 1927 434 637 1928 377 638 1929 406 638 1930 474 638 1931 406 639 1932 324 639 1933 339 639 1934 357 640 1935 316 640 1936 385 640 1937 357 641 1938 387 641 1939 316 641 1940 387 642 1941 340 642 1942 316 642 1943 417 643 1944 324 643 1945 444 643 1946 383 644 1947 324 644 1948 417 644 1949 383 645 1950 314 645 1951 324 645 1952 314 646 1953 42 646 1954 324 646 1955 42 647 1956 314 647 1957 44 647 1958 322 648 1959 305 648 1960 313 648 1961 322 649 1962 313 649 1963 19 649 1964 17 650 1965 322 650 1966 19 650 1967 422 651 1968 378 651 1969 386 651 1970 422 652 1971 412 652 1972 378 652 1973 422 653 1974 345 653 1975 412 653 1976 345 654 1977 368 654 1978 412 654 1979 368 655 1980 345 655 1981 364 655 1982 345 656 1983 374 656 1984 364 656 1985 366 657 1986 353 657 1987 400 657 1988 353 658 1989 351 658 1990 400 658 1991 351 659 1992 443 659 1993 400 659 1994 351 660 1995 411 660 1996 443 660 1997 351 661 1998 362 661 1999 411 661 2000 362 662 2001 388 662 2002 411 662 2003 362 663 2004 417 663 2005 388 663 2006 407 664 2007 413 664 2008 444 664 2009 413 665 2010 356 665 2011 444 665 2012 309 666 2013 413 666 2014 325 666 2015 413 667 2016 407 667 2017 325 667 2018 356 668 2019 434 668 2020 430 668 2021 356 669 2022 413 669 2023 434 669 2024 413 670 2025 309 670 2026 434 670 2027 325 671 2028 315 671 2029 309 671 2030 16 672 2031 374 672 2032 421 672 2033 374 673 2034 345 673 2035 421 673 2036 308 674 2037 310 674 2038 320 674 2039 380 675 2040 425 675 2041 440 675 2042 425 676 2043 428 676 2044 440 676 2045 308 677 2046 428 677 2047 310 677 2048 428 678 2049 376 678 2050 310 678 2051 428 679 2052 425 679 2053 376 679 2054 384 680 2055 380 680 2056 439 680 2057 380 681 2058 440 681 2059 439 681 2060 436 682 2061 398 682 2062 330 682 2063 436 683 2064 396 683 2065 398 683 2066 432 684 2067 43 684 2068 319 684 2069 43 685 2070 46 685 2071 319 685 2072 319 686 2073 312 686 2074 432 686 2075 312 687 2076 385 687 2077 432 687 2078 357 688 2079 385 688 2080 312 688 2081 366 689 2082 12 689 2083 9 689 2084 333 690 2085 383 690 2086 362 690 2087 314 691 2088 53 691 2089 44 691 2090 370 692 2091 8 692 2092 53 692 2093 370 693 2094 361 693 2095 8 693 2096 314 694 2097 333 694 2098 53 694 2099 333 695 2100 370 695 2101 53 695 2102 383 696 2103 333 696 2104 314 696 2105 362 697 2106 370 697 2107 333 697 2108 362 698 2109 351 698 2110 370 698 2111 351 699 2112 361 699 2113 370 699 2114 351 700 2115 353 700 2116 361 700 2117 353 701 2118 366 701 2119 361 701 2120 366 702 2121 9 702 2122 361 702 2123 9 703 2124 8 703 2125 361 703 2126 377 704 2127 408 704 2128 418 704 2129 408 705 2130 352 705 2131 418 705 2132 329 706 2133 409 706 2134 352 706 2135 329 707 2136 315 707 2137 409 707 2138 315 708 2139 324 708 2140 409 708 2141 315 709 2142 325 709 2143 324 709 2144 325 710 2145 407 710 2146 324 710 2147 407 711 2148 444 711 2149 324 711 2150 429 712 2151 445 712 2152 399 712 2153 399 713 2154 388 713 2155 417 713 2156 399 714 2157 445 714 2158 388 714 2159 445 715 2160 411 715 2161 388 715 2162 445 716 2163 344 716 2164 411 716 2165 344 717 2166 372 717 2167 411 717 2168 372 718 2169 443 718 2170 411 718 2171 372 719 2172 400 719 2173 443 719 2174 445 720 2175 429 720 2176 344 720 2177 338 721 2178 394 721 2179 402 721 2180 424 722 2181 350 722 2182 340 722 2183 424 723 2184 338 723 2185 350 723 2186 424 724 2187 442 724 2188 338 724 2189 442 725 2190 394 725 2191 338 725 2192 429 726 2193 399 726 2194 430 726 2195 399 727 2196 356 727 2197 430 727 2198 399 728 2199 417 728 2200 356 728 2201 417 729 2202 444 729 2203 356 729 2204 357 730 2205 420 730 2206 387 730 2207 420 731 2208 416 731 2209 387 731 2210 420 732 2211 381 732 2212 416 732 2213 381 733 2214 446 733 2215 416 733 2216 381 734 2217 373 734 2218 446 734 2219 420 735 2220 367 735 2221 381 735 2222 420 736 2223 357 736 2224 367 736 2225 312 737 2226 319 737 2227 382 737 2228 343 738 2229 349 738 2230 382 738 2231 343 739 2232 318 739 2233 349 739 2234 21 740 2235 318 740 2236 47 740 2237 318 741 2238 45 741 2239 47 741 2240 318 742 2241 337 742 2242 349 742 2243 21 743 2244 313 743 2245 337 743 2246 21 744 2247 19 744 2248 313 744 2249 45 745 2250 343 745 2251 319 745 2252 45 746 2253 318 746 2254 343 746 2255 318 747 2256 21 747 2257 337 747 2258 46 748 2259 45 748 2260 319 748 2261 350 749 2262 431 749 2263 340 749 2264 431 750 2265 316 750 2266 340 750 2267 431 751 2268 350 751 2269 369 751 2270 316 752 2271 441 752 2272 385 752 2273 316 753 2274 431 753 2275 441 753 2276 431 754 2277 369 754 2278 441 754 2279 402 755 2280 369 755 2281 338 755 2282 369 756 2283 350 756 2284 338 756 2285 324 757 2286 419 757 2287 409 757 2288 406 758 2289 418 758 2290 419 758 2291 406 759 2292 377 759 2293 418 759 2294 419 760 2295 324 760 2296 406 760 2297 352 761 2298 419 761 2299 418 761 2300 352 762 2301 409 762 2302 419 762 2303 375 763 2304 54 763 2305 371 763 2306 54 764 2307 55 764 2308 371 764 2309 375 765 2310 371 765 2311 306 765 2312 306 766 2313 348 766 2314 375 766 2315 306 767 2316 391 767 2317 348 767 2318 363 182 2319 395 182 2320 326 182 2321 363 182 2322 433 182 2323 395 182 2324 371 182 2325 336 182 2326 395 182 2327 371 182 2328 433 182 2329 392 182 2330 371 768 2331 395 768 2332 433 768 2333 55 182 2334 336 182 2335 371 182 2336 329 769 2337 352 769 2338 308 769 2339 352 770 2340 408 770 2341 308 770 2342 408 771 2343 307 771 2344 308 771 2345 329 772 2346 308 772 2347 320 772 2348 326 773 2349 320 773 2350 363 773 2351 320 774 2352 326 774 2353 329 774 2354 401 775 2355 436 775 2356 330 775 2357 330 776 2358 386 776 2359 341 776 2360 341 777 2361 401 777 2362 330 777 2363 422 778 2364 386 778 2365 402 778 2366 386 779 2367 330 779 2368 402 779 2369 394 780 2370 422 780 2371 402 780 2372 55 781 2373 56 781 2374 336 781 2375 56 782 2376 335 782 2377 336 782 2378 387 783 2379 424 783 2380 340 783 2381 424 784 2382 387 784 2383 379 784 2384 447 785 2385 424 785 2386 379 785 2387 447 786 2388 379 786 2389 435 786 2390 379 787 2391 332 787 2392 435 787 2393 311 788 2394 358 788 2395 317 788 2396 311 789 2397 405 789 2398 358 789 2399 305 790 2400 414 790 2401 313 790 2402 305 791 2403 342 791 2404 414 791 2405 305 792 2406 332 792 2407 342 792 2408 400 793 2409 360 793 2410 56 793 2411 56 794 2412 54 794 2413 400 794 2414 54 795 2415 366 795 2416 400 795 2417 54 796 2418 12 796 2419 366 796 2420 408 797 2421 397 797 2422 393 797 2423 311 798 2424 458 798 2425 405 798 2426 427 799 2427 305 799 2428 20 799 2429 427 800 2430 355 800 2431 305 800 2432 408 801 2433 393 801 2434 307 801 2435 393 802 2436 404 802 2437 307 802 2438 435 803 2439 332 803 2440 305 803 2441 387 804 2442 390 804 2443 379 804 2444 387 805 2445 416 805 2446 390 805 2447 416 806 2448 423 806 2449 390 806 2450 416 807 2451 446 807 2452 423 807 2453 446 808 2454 373 808 2455 423 808 2456 373 809 2457 342 809 2458 423 809 2459 373 810 2460 414 810 2461 342 810 2462 323 811 2463 410 811 2464 436 811 2465 389 812 2466 410 812 2467 323 812 2468 14 813 2469 306 813 2470 392 813 2471 306 814 2472 371 814 2473 392 814 2474 391 815 2475 306 815 2476 14 815 2477 20 816 2478 322 816 2479 17 816 2480 20 817 2481 305 817 2482 322 817 2483 365 818 2484 16 818 2485 421 818 2486 334 819 2487 16 819 2488 426 819 2489 16 820 2490 365 820 2491 426 820 2492 375 821 2493 348 821 2494 54 821 2495 348 822 2496 12 822 2497 54 822 2498 336 823 2499 430 823 2500 395 823 2501 430 824 2502 336 824 2503 335 824 2504 429 825 2505 430 825 2506 335 825 2507 389 826 2508 401 826 2509 317 826 2510 401 827 2511 323 827 2512 436 827 2513 401 828 2514 389 828 2515 323 828 2516 345 829 2517 424 829 2518 447 829 2519 345 830 2520 442 830 2521 424 830 2522 345 831 2523 422 831 2524 442 831 2525 422 832 2526 394 832 2527 442 832 2528 447 833 2529 435 833 2530 365 833 2531 447 834 2532 365 834 2533 421 834 2534 447 835 2535 421 835 2536 345 835 2537 305 836 2538 355 836 2539 435 836 2540 355 837 2541 365 837 2542 435 837 2543 426 838 2544 355 838 2545 334 838 2546 360 839 2547 335 839 2548 56 839 2549 354 182 2550 335 182 2551 360 182 2552 331 840 2553 456 840 2554 462 840 2555 20 841 2556 334 841 2557 427 841 2558 16 842 2559 334 842 2560 20 842 2561 403 843 2562 401 843 2563 415 843 2564 401 844 2565 341 844 2566 415 844 2567 374 845 2568 401 845 2569 359 845 2570 401 846 2571 403 846 2572 359 846 2573 18 847 2574 401 847 2575 16 847 2576 401 848 2577 374 848 2578 16 848 2579 331 182 2580 14 182 2581 439 182 2582 331 849 2583 311 849 2584 13 849 2585 311 850 2586 18 850 2587 13 850 2588 18 851 2589 311 851 2590 317 851 2591 317 852 2592 401 852 2593 18 852 2594 331 853 2595 307 853 2596 404 853 2597 428 854 2598 308 854 2599 307 854 2600 307 855 2601 440 855 2602 428 855 2603 440 182 2604 307 182 2605 331 182 2606 331 856 2607 439 856 2608 440 856 2609 391 857 2610 14 857 2611 11 857 2612 14 858 2613 331 858 2614 13 858 2615 11 859 2616 348 859 2617 391 859 2618 355 860 2619 426 860 2620 365 860 2621 400 861 2622 354 861 2623 360 861 2624 400 862 2625 372 862 2626 354 862 2627 372 863 2628 344 863 2629 354 863 2630 344 864 2631 335 864 2632 354 864 2633 344 865 2634 429 865 2635 335 865 2636 355 866 2637 427 866 2638 334 866 2639 311 867 2640 331 867 2641 321 867 2642 331 868 2643 347 868 2644 321 868 2645 458 869 2646 311 869 2647 321 869 2648 404 870 2649 456 870 2650 331 870 2651 328 871 2652 456 871 2653 404 871 2654 390 872 2655 332 872 2656 379 872 2657 332 873 2658 390 873 2659 423 873 2660 332 874 2661 423 874 2662 342 874 2663 37 875 2664 470 875 2665 31 875 2666 461 876 2667 450 876 2668 462 876 2669 405 877 2670 464 877 2671 358 877 2672 464 878 2673 389 878 2674 358 878 2675 464 879 2676 458 879 2677 459 879 2678 464 880 2679 405 880 2680 458 880 2681 460 881 2682 462 881 2683 450 881 2684 460 882 2685 347 882 2686 462 882 2687 457 883 2688 472 883 2689 461 883 2690 461 884 2691 456 884 2692 457 884 2693 462 885 2694 456 885 2695 461 885 2696 457 886 2697 456 886 2698 328 886 2699 483 887 2700 481 887 2701 438 887 2702 481 888 2703 43 888 2704 438 888 2705 478 889 2706 473 889 2707 34 889 2708 473 890 2709 476 890 2710 34 890 2711 476 891 2712 40 891 2713 34 891 2714 469 892 2715 478 892 2716 36 892 2717 478 893 2718 34 893 2719 36 893 2720 473 894 2721 475 894 2722 476 894 2723 473 895 2724 478 895 2725 475 895 2726 478 896 2727 467 896 2728 475 896 2729 478 897 2730 469 897 2731 467 897 2732 469 898 2733 471 898 2734 467 898 2735 471 899 2736 465 899 2737 467 899 2738 471 900 2739 482 900 2740 465 900 2741 482 901 2742 470 901 2743 465 901 2744 470 902 2745 482 902 2746 31 902 2747 454 903 2748 39 903 2749 476 903 2750 406 904 2751 339 904 2752 474 904 2753 324 905 2754 42 905 2755 339 905 2756 41 906 2757 453 906 2758 470 906 2759 464 907 2760 468 907 2761 483 907 2762 464 908 2763 459 908 2764 468 908 2765 459 909 2766 449 909 2767 468 909 2768 483 910 2769 466 910 2770 481 910 2771 483 911 2772 468 911 2773 466 911 2774 481 912 2775 466 912 2776 43 912 2777 39 913 2778 33 913 2779 476 913 2780 33 914 2781 40 914 2782 476 914 2783 36 915 2784 32 915 2785 469 915 2786 32 916 2787 471 916 2788 469 916 2789 32 917 2790 35 917 2791 471 917 2792 35 918 2793 482 918 2794 471 918 2795 35 919 2796 31 919 2797 482 919 2798 37 920 2799 38 920 2800 41 920 2801 37 921 2802 41 921 2803 470 921 2804 474 922 2805 477 922 2806 472 922 2807 477 923 2808 461 923 2809 472 923 2810 477 924 2811 450 924 2812 461 924 2813 477 925 2814 455 925 2815 450 925 2816 477 926 2817 474 926 2818 479 926 2819 474 927 2820 339 927 2821 479 927 2822 479 928 2823 339 928 2824 42 928 2825 39 929 2826 454 929 2827 42 929 2828 454 930 2829 479 930 2830 42 930 2831 454 931 2832 451 931 2833 455 931 2834 454 932 2835 477 932 2836 479 932 2837 454 933 2838 455 933 2839 477 933 2840 451 934 2841 460 934 2842 455 934 2843 451 935 2844 347 935 2845 460 935 2846 455 936 2847 460 936 2848 450 936 2849 448 937 2850 458 937 2851 321 937 2852 347 938 2853 451 938 2854 321 938 2855 449 939 2856 448 939 2857 452 939 2858 449 940 2859 458 940 2860 448 940 2861 452 941 2862 453 941 2863 449 941 2864 449 942 2865 453 942 2866 468 942 2867 453 943 2868 466 943 2869 468 943 2870 453 944 2871 41 944 2872 466 944 2873 41 945 2874 43 945 2875 466 945 2876 459 946 2877 458 946 2878 449 946 2879 347 947 2880 331 947 2881 462 947 2882 343 948 2883 382 948 2884 319 948 2885 4 949 2886 49 949 2887 44 949 2888 42 950 2889 44 950 2890 49 950 2891 39 951 2892 42 951 2893 49 951 2894 269 952 2895 283 952 2896 285 952 2897 178 953 2898 283 953 2899 269 953 2900 91 954 2901 283 954 2902 178 954 2903

+
+
+
+ + + + 3.15658 67.48139 15.1406 38.18585 55.74057 15.1406 43.16133 51.98325 15.1406 -38.10755 55.74084 15.1406 -32.80664 59.02303 15.1406 -43.08306 51.98356 15.1406 -27.22552 61.8021 15.1406 27.30387 61.80191 15.1406 21.49008 64.05413 15.1406 9.364744 66.90607 15.1406 -9.28636 66.90615 15.1406 -3.07818 67.48143 15.1406 -15.41501 65.76057 15.1406 -21.41171 64.05429 15.1406 15.49339 65.76045 15.1406 47.7831 47.69076 15.1406 67.48139 -3.15657 15.1406 55.74057 -38.18585 15.1406 51.98325 -43.16133 15.1406 55.74084 38.10755 15.1406 59.02303 32.80664 15.1406 59.02279 -32.88496 15.1406 51.98356 43.08307 15.1406 61.8021 27.22553 15.1406 61.80191 -27.30387 15.1406 64.05413 -21.49008 15.1406 66.90607 -9.364744 15.1406 66.90615 9.28636 15.1406 67.48143 3.07819 15.1406 65.76057 15.41502 15.1406 64.05429 21.41172 15.1406 65.76045 -15.49339 15.1406 47.69075 -47.78311 15.1406 -3.15659 -67.48139 15.1406 -38.18586 -55.74056 15.1406 -43.16134 -51.98324 15.1406 38.10754 -55.74085 15.1406 32.80663 -59.02303 15.1406 -32.88497 -59.02278 15.1406 43.08305 -51.98357 15.1406 27.22552 -61.80211 15.1406 -27.30388 -61.8019 15.1406 -21.49009 -64.05413 15.1406 -9.36475 -66.90607 15.1406 9.286354 -66.90615 15.1406 3.07817 -67.48143 15.1406 15.415 -65.76057 15.1406 21.41171 -64.05429 15.1406 -15.4934 -65.76045 15.1406 -47.76879 -47.78297 15.1406 -67.48139 3.15658 15.1406 -55.74057 38.18586 15.1406 -51.98325 43.16134 15.1406 -55.74085 -38.10754 15.1406 -59.02303 -32.80663 15.1406 -59.02279 32.88497 15.1406 -51.98357 -43.08306 15.1406 -61.8021 -27.22552 15.1406 -61.8019 27.30388 15.1406 -64.05413 21.49009 15.1406 -66.90607 9.36475 15.1406 -66.90615 -9.286354 15.1406 -67.48143 -3.07818 15.1406 -65.76057 -15.41501 15.1406 -64.05429 -21.41171 15.1406 -65.76045 15.49339 15.1406 -47.78297 47.76878 15.1406 29.88855 -2.94626 0.1406 -66.19735 -12.94628 0.1406 -29.81065 -2.94627 0.1406 -26.99805 -12.94628 0.1406 -62.80806 24.68092 0.1406 -59.55455 -31.64598 0.1406 -29.94435 1.05372 0.1406 25.07615 16.58062 10.1406 19.66905 -64.52888 0.1406 48.37674 47.16753 0.1406 19.94364 64.55223 0.1406 -52.20975 -42.68178 0.1406 -67.45365 -0.94628 0.1406 -24.99785 16.58122 10.1406 64.67866 -19.38757 0.1406 -64.60076 -19.38758 0.1406 27.90535 11.16503 0.1406 -29.54145 5.05372 0.1406 5.20453 42.74233 0.1406 -47.76075 -47.60588 0.1406 -10.21735 41.81262 0.1406 -29.84025 -2.63611 10.1406 -29.13205 7.05731 10.1406 15.23755 40.27813 0.1406 26.26944 62.24863 0.1406 29.88855 3.05372 0.1406 13.41974 66.21413 0.1406 28.92445 8.154973 0.1406 43.44324 51.74813 0.1406 27.94955 -10.94626 0.1406 -37.52395 -56.02908 0.1406 -29.13296 -6.94627 0.1406 60.12025 30.81873 0.1406 0.03894978 43.05372 0.1406 67.35356 -4.94628 0.1406 0.03898996 -29.94628 0.1406 -48.29885 47.16752 0.1406 65.02655 18.29823 0.1406 56.75694 36.65043 0.1406 9.953144 -28.26076 0.1406 -3.32206 -29.75738 0.1406 -27.41255 -12.04648 10.1406 67.47224 3.05372 0.1406 -23.42537 -18.63925 0.1406 56.23166 -37.34457 0.1406 -67.27565 5.05372 0.1406 26.53895 -14.00867 10.1406 -67.09716 -6.94627 0.1406 -0.30649 5.53084 10.5439 62.45715 -25.64087 0.1406 31.91315 -59.44657 0.1406 -52.75146 42.11822 0.1406 0.03893995 67.55373 0.1406 -31.83525 -59.44658 0.1406 29.21085 -6.94627 0.1406 -26.49595 14.05002 0.1406 -32.25645 59.32642 0.1406 -43.36536 51.74812 0.1406 26.57375 14.05033 0.1406 23.16535 19.09483 10.1406 -42.84965 -52.06938 0.1406 66.27526 -12.94627 0.1406 13.23215 -66.14438 0.1406 -25.94143 -14.94691 10.1406 6.76282 67.21804 0.1406 -56.67905 36.65042 0.1406 -64.94865 18.29822 0.1406 -22.95787 19.3189 0.1406 23.03557 19.3191 0.1406 0.03894978 25.24342 10.1406 62.88595 24.68093 0.1406 3.15977 43.10341 10.13999 -4.88601 -29.49477 10.1406 3.40005 -29.75737 0.1406 16.39395 39.49302 0.1406 52.28765 -42.68177 0.1406 -56.15375 -37.34458 0.1406 14.27375 30.47312 10.1406 0.03894978 -67.44628 0.1406 47.83865 -47.60587 0.1406 -26.79235 13.47312 10.1406 -26.19156 62.24862 0.1406 28.09124 10.56283 10.1406 20.13022 -22.225 10.1406 6.66763 -67.11997 0.1406 14.06305 29.80373 0.1406 -62.37925 -25.64088 0.1406 -38.00016 55.81462 0.1406 26.87055 13.47253 10.1406 32.79684 59.07212 15.1406 37.60185 -56.02907 0.1406 -6.58973 -67.11997 0.1406 28.67294 -8.89598 10.1406 -9.25984 42.20282 10.14001 -5.12663 42.74233 0.1406 1.83378 -29.89258 10.1406 15.78844 40.00233 10.14021 16.00825 -25.34277 0.1406 -19.86576 64.55223 0.1406 -6.68494 67.21804 0.1406 -13.98546 29.80534 0.1406 -66.44275 11.73412 0.1406 -60.04235 30.81872 0.1406 59.63245 -31.64597 0.1406 -28.84655 8.154784 0.1406 -25.83825 -62.28908 0.1406 -14.08326 27.71662 0.1406 21.34193 21.17674 10.1406 14.00565 28.40123 0.1406 24.72693 -16.9904 10.1406 17.06925 38.2692 0.1406 -17.09755 37.57352 0.1406 -8.48113 -28.71097 10.1406 -18.67477 -23.39396 0.1406 32.33434 59.32643 0.1406 -17.05125 37.03053 10.14291 -14.19585 30.47311 10.1406 38.07804 55.81463 0.1406 13.97235 29.10572 10.1406 29.09395 7.52404 10.1406 -29.37345 -5.85473 10.1406 21.26152 -21.1501 0.1406 -3.08271 43.10331 10.13999 -28.01435 10.56122 10.1406 29.97205 2.05655 10.1406 -28.56105 -9.00385 10.1406 4.49238 -29.52047 10.25291 52.82935 42.11823 0.1406 -6.64069 -29.19318 0.1406 16.89603 36.20391 10.14 30.02915 -0.7147 10.1406 -13.34186 66.21413 0.1406 -19.59114 -64.52888 0.1406 42.92755 -52.06937 0.1406 10.29525 41.81262 0.1406 25.44953 -15.8931 0.1406 -13.15425 -66.14438 0.1406 -17.22932 -24.47799 10.1406 -20.79073 21.64364 0.1406 -1.75515 -29.89258 10.1406 -22.10432 -20.1868 10.1406 -16.81815 36.20392 10.14292 -27.82755 11.16482 0.1406 66.52066 11.73413 0.1406 9.33692 42.20303 10.14001 17.17624 37.39723 10.14021 14.43386 27.07011 0.1406 -15.21455 40.37392 10.14 -22.84564 19.45203 10.1406 29.37685 -6.21435 10.1406 14.45012 -26.25819 10.1406 14.16115 27.71701 10.1406 -29.71885 3.85807 10.1406 -29.95585 0.61422 10.1406 7.99297 -28.87258 10.1406 -16.72595 38.92103 0.1406 -16.38056 39.54288 10.13363 -12.98475 -26.97188 0.1406 -17.01304 38.32173 10.14054 16.83693 39.01018 10.13958 25.91615 -62.28907 0.1406 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.04916781 -0.9987773 0.005146324 -0.1469879 -0.9890517 -0.01308947 -0.1837452 -0.9829677 -0.003493785 -0.2434051 -0.9698358 -0.01313441 -0.2736766 -0.9618126 -0.004205524 -0.337469 -0.9412479 -0.01293218 -0.3612312 -0.9324629 -0.005010128 -0.4282761 -0.9035615 -0.01249933 -0.4457399 -0.8951432 -0.005902945 -0.5149333 -0.8571488 -0.01181811 -0.5264254 -0.8501935 -0.006875932 -0.5966258 -0.8024457 -0.01089286 -0.6725513 -0.7399947 -0.009096682 -0.7444596 -0.6676163 -0.008280873 -0.7419795 -0.6703886 -0.006745934 -0.7980152 -0.6026235 -0.004088521 -0.8042136 -0.5942854 -0.008090734 -0.8502129 -0.5264284 -0.003372848 -0.8586741 -0.5124389 -0.009223997 -0.89516 -0.4457365 -0.002769887 -0.9048432 -0.4256244 -0.01014858 -0.9324749 -0.3612278 -0.0022825 -0.9422483 -0.3347398 -0.01084285 -0.9618215 -0.2736712 -0.001889407 -0.9705653 -0.2405717 -0.01133197 -0.9829736 -0.1837395 -0.001617193 -0.09225469 -0.9954928 -0.02198249 -0.9888861 -0.1483018 -0.01054334 -0.9981868 -0.05931073 -0.01027768 -0.9957328 -0.09226769 -0.001714885 -0.9995107 0.02965128 -0.009959101 -0.9999984 7.83158e-6 -0.001851022 -0.04985654 0.9986411 0.01517665 6.11492e-6 0.9998459 -0.01755702 -0.1490958 0.9886499 0.01848965 -0.09224909 0.9955148 -0.02098661 -0.2467961 0.968817 0.02202945 -0.1836844 0.982676 -0.02465862 -0.4340626 0.9008774 -0.003102719 -0.4457374 0.895162 0.001756191 -0.5216395 0.8531641 -0.001877188 -0.5264329 0.8502166 4.13116e-4 -0.6040424 0.7969521 -4.0426e-4 -0.6026287 0.7980208 -0.001184463 -0.6804111 0.7328296 0.001302778 -0.6676228 0.744468 -0.006880342 -0.7500339 0.6613992 -7.16275e-4 -0.7389752 0.6736725 -0.009002506 -0.8121829 0.5834022 0.001024544 -0.7979614 0.6025939 -0.01175856 -0.8662556 0.4995918 0.003058016 -0.8501212 0.5263813 -0.01472598 -0.9117024 0.4108163 0.005379021 -0.8950168 0.4456734 -0.01789695 -0.9480707 0.3179596 0.00799483 -0.9322645 0.3611528 -0.02125549 -0.975002 0.2219281 0.01091939 -0.9615253 0.2735921 -0.02483075 -0.9922178 0.1237106 0.01412945 0.04985862 0.9986827 0.01212102 0.1491193 0.9888051 -0.005301773 0.1837446 0.9829646 0.004329442 0.2468531 0.9690411 -0.004817008 0.2736773 0.9618144 0.003723263 0.3421748 0.9396275 -0.004074275 0.3612332 0.9324712 0.002859115 0.4340624 0.9008775 -0.003104209 0.4450342 0.8955124 0.001460731 0.5216401 0.8531641 -0.001619756 0.5258399 0.8505836 4.20024e-4 0.6040421 0.7969524 -4.06167e-4 0.6026355 0.7980158 -0.001183211 0.6804102 0.7328304 0.001300692 0.7500334 0.6614 -2.51438e-4 0.7980067 0.6026164 0.006234824 0.8121833 0.5834001 -0.001654863 0.8501981 0.5264235 0.006455421 0.8662552 0.4995938 -0.002845108 0.8951446 0.4457299 0.006406426 0.9117093 0.4108182 -0.003813982 0.93246 0.3612221 0.006098628 0.9480911 0.3179664 -0.004546463 0.9618085 0.2736675 0.00553739 0.9750476 0.2219385 -0.005053639 0.9829636 0.18374 0.004721641 0.9940152 0.1089667 -0.007763743 0.9957337 0.09227043 -7.60801e-4 0.09226739 0.9956305 -0.01437467 0.9957302 -0.09227788 0.002524197 0.9998672 -0.0148316 -0.006751179 0.9999998 -6.52633e-6 -6.12885e-4 0.9706053 -0.2405841 0.00668931 0.9324096 -0.3612104 -0.01180875 0.9422971 -0.3347535 0.004049062 0.8951111 -0.4457241 -0.01031482 0.9048895 -0.4256437 0.001620352 0.8501793 -0.5264177 -0.008926868 0.8587122 -0.5124578 -6.27868e-4 0.7979924 -0.6026186 -0.00767219 0.8042364 -0.5943036 -0.002679705 0.7327088 -0.6805075 -0.006887078 0.7419962 -0.6704039 -6.04868e-4 0.6736933 -0.7390082 -0.002089202 0.6725766 -0.7400225 -0.002739727 0.6026282 -0.7980204 -0.001682519 0.5966536 -0.8024851 -0.004695892 0.5264312 -0.8502168 -0.001411139 0.5149593 -0.8571903 -0.006470322 0.44574 -0.8951616 -0.001274883 0.4282964 -0.9036026 -0.008051812 0.3374416 -0.9411662 0.01841765 0.1836652 -0.982573 -0.02859234 0.2433991 -0.9698137 0.01477462 0.09223747 -0.99539 -0.02628672 0.146991 -0.9890729 0.01133942 -6.11156e-6 -0.9997097 -0.02409273 0.04916685 -0.9987574 0.008136868 0.7743389 -0.6077327 0.1762394 0.6709738 -0.741075 -0.02453613 0.7314653 -0.6818782 8.68517e-4 0.8001199 -0.5998393 -9.93936e-4 0.8300756 -0.5573999 0.01673531 0.8660164 -0.5000057 -0.00317645 0.9079599 -0.4190481 0.002737045 0.922078 -0.3869558 -0.006132245 0.9471932 -0.3206592 -0.001661241 0.9526861 -0.3038939 -0.006152391 0.9757937 -0.2186594 0.003861546 0.9835832 -0.1804087 -0.004121541 0.9949496 -0.1002161 0.005668044 0.9993665 0.03554135 0.001855731 0.9994385 0.03340721 0.002617478 0.9973396 -0.07286679 -0.002055585 0.9896446 0.143532 -0.001522302 0.9859352 0.1670385 0.005477666 0.9682901 0.2497971 -0.003979861 0.9420294 0.3351911 0.01509249 0.8918353 0.452345 -0.003735363 0.8469022 0.531482 0.01684445 0.9355447 0.3531392 0.00700283 0.8067144 0.5907474 -0.01515001 0.7073229 0.7067113 0.01592606 0.660665 0.7505477 -0.01413428 0.5322556 0.846454 0.01482343 0.4352185 0.8994544 -0.03958278 0.3304283 0.9437071 0.01530671 0.2130073 0.9770187 -0.007910132 -0.1820928 0.9832756 -0.003365457 -0.1382665 0.9903606 -0.008265078 -0.05611616 0.9984132 0.004710316 0 0.9999856 -0.00537014 0.05611348 0.9984133 0.004705786 0.126045 0.9920043 -0.006337761 0.1676048 0.9858542 3.22968e-4 -0.9227706 0.3851561 -0.01221543 -0.8924322 0.4510156 0.01223289 -0.854564 0.5193244 -0.004765331 -0.7820889 0.6230543 0.01185411 -0.7513319 0.6597744 -0.01407897 -0.6237362 0.7815194 0.01344251 -0.5788823 0.8152627 -0.01556622 -0.434078 0.9007534 0.01482164 -0.3752359 0.9267762 -0.01685065 -0.2226211 0.9747738 0.01600158 -0.9672294 0.2538921 -0.00252676 -0.9536842 0.3007206 0.007332324 -0.9859411 0.1670421 0.004140436 -0.999768 -0.020599 0.006293892 -0.9999012 0 0.01405858 -0.9929642 0.1177732 -0.01232063 -0.9825935 -0.1857029 0.004938125 -0.9496313 -0.313348 -0.003674149 -0.987319 -0.1585685 -0.007567763 -0.6730729 -0.7389896 0.02944964 -0.6692135 -0.7426623 0.02461928 -0.7522541 -0.6588541 -0.005013048 -0.7961584 -0.6050797 -0.003237605 -0.8300631 -0.5574186 0.01673275 -0.8660276 -0.4999863 -0.003185331 -0.9079648 -0.4190377 0.002736508 -0.9221218 -0.386851 -0.006154835 -0.9471845 -0.3206849 -0.001704335 0 0 -1 0 0 -1 0 0 -1 0.2935867 -0.9558883 0.009187877 0.144209 -0.9892366 0.02479338 0.1796569 -0.9837286 -0.001211345 0.06015551 -0.9979071 0.02372848 1.5888e-5 -0.9999877 0.004964172 -0.06015551 -0.9979069 0.02373379 -0.1796568 -0.9837286 -0.001214861 -0.1441912 -0.9892389 0.02480417 -0.2965059 -0.9549899 0.008868932 -0.3228356 -0.9464186 -0.008316457 0.4049757 -0.9115484 0.07123428 0.9092891 0.4160752 -0.008653283 0.9279882 0.371771 0.02498388 0.9986147 -0.04675936 0.02413225 0.5800126 -0.8140324 0.03060775 0.8879591 -0.459918 -0.002070426 0.96395 -0.2658244 0.01174277 0.9995426 -0.02959257 -0.006233096 0.9624128 0.2713963 0.01027792 -0.9070907 0.4150716 0.07001584 -0.9423431 0.3346386 -0.002545058 -0.9730734 0.2284906 0.03033548 -0.9785536 -0.2058565 -0.00748074 -0.8754459 -0.483069 0.01545721 -0.6873169 -0.726343 -0.004623889 -0.5616844 -0.8273117 0.008124887 -0.9519383 -0.3062283 -0.006150066 -0.9908655 -0.1347116 0.006190657 -0.9991444 0.04089224 -0.006207823 -0.9765405 0.2152456 0.006167232 0 0 -1 0 0 -1 -6.84483e-7 0 -1 0.1401688 -0.8464147 -0.5137462 3.92904e-7 0 -1 0.01062613 0.01094919 -0.9998837 0 0.01138436 -0.9999353 -0.001866638 0.01127153 -0.9999347 0 0 -1 -0.01297652 0.001539111 -0.9999147 -0.01230746 0.003230571 -0.9999191 -0.01152145 0.004808962 -0.9999222 0.01376777 -0.001005828 -0.9999048 0.01352137 4.80883e-4 -0.9999085 -0.01335 -2.75069e-4 -0.999911 0.01385504 -0.002541244 -0.9999008 0.0137571 -0.004388332 -0.9998958 -0.0135684 -0.002179145 -0.9999056 0.01352357 -0.005675196 -0.9998925 -0.01341599 -0.004426836 -0.9999003 0.01297825 -0.007493138 -0.9998878 -0.01269626 -0.007329881 -0.9998926 -0.01321768 -0.005545139 -0.9998974 0.0122286 -0.00916773 -0.9998833 -0.01140701 -0.009990572 -0.999885 -0.003891646 -0.02038633 -0.9997847 -0.01193726 -0.009072482 -0.9998877 0.005199432 -0.02054548 -0.9997755 -1.38558e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.01041489 0.006329298 -0.9999258 -0.008999526 0.007902801 -0.9999283 -0.006774663 0.009541034 -0.9999316 -0.004323601 0.01067882 -0.9999337 1.78641e-4 4.86499e-4 -1 -1.77168e-4 -6.16379e-5 -1 -0.001374006 -0.001794755 -0.9999974 -0.003102898 -0.004051268 -0.999987 0.003194987 0.003181397 -0.9999899 1.0507e-5 -2.89645e-5 -1 1.88823e-6 -3.38779e-5 -1 0 -3.41743e-5 -1 -1.75336e-6 -3.38779e-5 -1 1.63012e-5 -4.36613e-5 -1 -3.12347e-4 3.06079e-4 -1 2.22164e-4 -3.4425e-4 -1 -1.78375e-4 2.18321e-4 -1 4.62061e-5 -1.26026e-4 -1 0 0 -1 0 0 -1 -0.9957313 0.092278 -0.001986742 -0.9825724 0.1836702 -0.0285781 -0.6026169 -0.7979912 -0.007939815 -0.6736652 -0.7389723 -0.009754598 0.2735412 -0.961361 -0.03099054 0.3612274 -0.9324769 -0.001260221 0.9617342 -0.2736533 -0.01346099 0.9829703 -0.1837469 0.002535045 0.9909908 -0.1335728 -0.009781718 0.7389967 0.6736846 0.005747079 0.6805227 0.7327257 0.00137335 -0.2736713 0.9618161 0.003723561 -0.361222 0.9324588 -0.006274521 -0.3421755 0.9396258 0.004384338 + + + + + + + + + + 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 + + + + + + + + + + + + + + + + +

79 0 0 112 0 1 84 0 2 84 1 3 73 1 4 68 1 5 114 0 6 84 0 7 68 0 8 79 2 9 84 2 10 114 2 11 173 3 12 178 3 13 167 3 14 43 4 15 158 4 16 145 4 17 43 5 18 203 5 19 158 5 20 48 6 21 203 6 22 43 6 23 48 7 24 199 7 25 203 7 26 42 8 27 199 8 28 48 8 29 42 9 30 172 9 31 199 9 32 41 10 33 172 10 34 42 10 35 41 11 36 120 11 37 172 11 38 38 12 39 120 12 40 41 12 41 38 13 42 97 13 43 120 13 44 34 14 45 97 14 46 38 14 47 34 15 48 127 15 49 97 15 50 49 16 51 86 16 52 127 16 53 56 17 54 86 17 55 49 17 56 56 18 57 78 18 58 86 18 59 53 19 60 78 19 61 56 19 62 53 20 63 143 20 64 78 20 65 54 21 66 143 21 67 53 21 68 54 22 69 72 22 70 143 22 71 57 23 72 72 23 73 54 23 74 57 24 75 153 24 76 72 24 77 64 25 78 153 25 79 57 25 80 64 26 81 82 26 82 153 26 83 63 27 84 82 27 85 64 27 86 63 28 87 68 28 88 82 28 89 61 29 90 68 29 91 63 29 92 145 30 93 33 30 94 43 30 95 61 31 96 114 31 97 68 31 98 79 32 99 114 32 100 62 32 101 62 33 102 114 33 103 61 33 104 50 34 105 112 34 106 79 34 107 50 35 108 79 35 109 62 35 110 166 36 111 0 36 112 119 36 113 166 37 114 11 37 115 0 37 116 198 38 117 11 38 118 166 38 119 198 39 120 10 39 121 11 39 122 165 40 123 10 40 124 198 40 125 165 41 126 12 41 127 10 41 128 123 42 129 6 42 130 148 42 131 123 43 132 4 43 133 6 43 134 154 44 135 4 44 136 123 44 137 3 45 138 4 45 139 154 45 140 124 46 141 3 46 142 154 46 143 124 47 144 5 47 145 3 47 146 103 48 147 5 48 148 124 48 149 103 49 150 66 49 151 5 49 152 118 50 153 66 50 154 103 50 155 118 51 156 52 51 157 66 51 158 132 52 159 52 52 160 118 52 161 132 53 162 51 53 163 52 53 164 169 54 165 51 54 166 132 54 167 169 55 168 55 55 169 51 55 170 71 56 171 55 56 172 169 56 173 71 57 174 58 57 175 55 57 176 133 58 177 58 58 178 71 58 179 133 59 180 59 59 181 58 59 182 168 60 183 59 60 184 133 60 185 168 61 186 65 61 187 59 61 188 112 62 189 65 62 190 168 62 191 9 63 192 131 63 193 119 63 194 9 64 195 93 64 196 131 64 197 14 65 198 93 65 199 9 65 200 14 66 201 77 66 202 93 66 203 8 67 204 77 67 205 14 67 206 8 68 207 91 68 208 77 68 209 7 69 210 91 69 211 8 69 212 7 70 213 181 70 214 91 70 215 156 71 216 181 71 217 7 71 218 156 72 219 184 72 220 181 72 221 1 73 222 184 73 223 156 73 224 1 74 225 95 74 226 184 74 227 2 75 228 95 75 229 1 75 230 2 76 231 76 76 232 95 76 233 22 77 234 194 77 235 76 77 236 19 78 237 194 78 238 22 78 239 19 79 240 105 79 241 194 79 242 20 80 243 105 80 244 19 80 245 20 81 246 99 81 247 105 81 248 23 82 249 99 82 250 20 82 251 23 83 252 137 83 253 99 83 254 30 84 255 137 84 256 23 84 257 30 85 258 104 85 259 137 85 260 29 86 261 104 86 262 30 86 263 29 87 264 210 87 265 104 87 266 27 88 267 210 88 268 29 88 269 27 89 270 109 89 271 210 89 272 28 90 273 109 90 274 27 90 275 119 91 276 0 91 277 9 91 278 101 92 279 16 92 280 26 92 281 109 93 282 16 93 283 101 93 284 16 94 285 109 94 286 28 94 287 25 95 288 81 95 289 128 95 290 24 96 291 81 96 292 25 96 293 24 97 294 116 97 295 81 97 296 21 98 297 116 98 298 24 98 299 21 99 300 170 99 301 116 99 302 17 100 303 170 100 304 21 100 305 17 101 306 111 101 307 170 101 308 18 102 309 111 102 310 17 102 311 18 103 312 142 103 313 111 103 314 32 104 315 142 104 316 18 104 317 32 105 318 146 105 319 142 105 320 39 106 321 146 106 322 32 106 323 39 107 324 200 107 325 146 107 326 36 108 327 200 108 328 39 108 329 36 109 330 157 109 331 200 109 332 37 110 333 157 110 334 36 110 335 37 111 336 117 111 337 157 111 338 40 112 339 117 112 340 37 112 341 40 113 342 227 113 343 117 113 344 46 114 345 75 114 346 227 114 347 44 115 348 75 115 349 46 115 350 44 116 351 129 116 352 75 116 353 45 117 354 129 117 355 44 117 356 45 118 357 151 118 358 129 118 359 33 119 360 151 119 361 45 119 362 33 120 363 145 120 364 151 120 365 215 121 366 173 121 367 183 121 368 215 122 369 205 122 370 173 122 371 215 123 372 134 123 373 205 123 374 80 124 375 134 124 376 215 124 377 122 125 378 134 125 379 80 125 380 147 126 381 122 126 382 80 126 383 147 127 384 209 127 385 122 127 386 190 128 387 209 128 388 147 128 389 190 129 390 171 129 391 209 129 392 89 130 393 171 130 394 190 130 395 89 131 396 84 131 397 171 131 398 219 132 399 84 132 400 89 132 401 219 133 402 73 133 403 84 133 404 69 134 405 220 134 406 88 134 407 69 135 408 73 135 409 220 135 410 220 136 411 73 136 412 219 136 413 187 137 414 69 137 415 88 137 416 98 138 417 69 138 418 187 138 419 192 139 420 98 139 421 187 139 422 70 140 423 98 140 424 192 140 425 130 141 426 70 141 427 108 141 428 110 142 429 70 142 430 130 142 431 70 143 432 192 143 433 108 143 434 207 144 435 110 144 436 130 144 437 207 145 438 180 145 439 110 145 440 204 146 441 180 146 442 207 146 443 204 147 444 224 147 445 180 147 446 179 148 447 224 148 448 204 148 449 179 149 450 195 149 451 224 149 452 139 150 453 195 150 454 179 150 455 140 151 456 193 151 457 221 151 458 140 152 459 162 152 460 193 152 461 102 153 462 162 153 463 140 153 464 102 154 465 206 154 466 162 154 467 107 155 468 206 155 469 102 155 470 107 156 471 139 156 472 206 156 473 195 157 474 139 157 475 107 157 476 96 158 477 113 158 478 159 158 479 202 159 480 113 159 481 96 159 482 202 160 483 176 160 484 113 160 485 188 161 486 176 161 487 202 161 488 188 162 489 150 162 490 176 162 491 164 163 492 150 163 493 188 163 494 164 164 495 217 164 496 150 164 497 106 165 498 217 165 499 164 165 500 106 166 501 221 166 502 217 166 503 140 167 504 221 167 505 106 167 506 121 168 507 159 168 508 216 168 509 121 169 510 96 169 511 159 169 512 216 170 513 67 170 514 121 170 515 92 171 516 197 171 517 191 171 518 67 172 519 197 172 520 92 172 521 197 173 522 67 173 523 216 173 524 186 174 525 94 174 526 92 174 527 149 175 528 94 175 529 186 175 530 92 176 531 191 176 532 186 176 533 213 177 534 174 177 535 218 177 536 135 178 537 174 178 538 213 178 539 135 179 540 126 179 541 174 179 542 135 180 543 74 180 544 126 180 545 125 181 546 74 181 547 135 181 548 125 182 549 155 182 550 74 182 551 83 183 552 155 183 553 125 183 554 83 184 555 149 184 556 155 184 557 94 185 558 149 185 559 83 185 560 101 186 561 96 186 562 109 186 563 128 187 564 96 187 565 101 187 566 67 0 567 92 0 568 109 0 569 96 188 570 121 188 571 109 188 572 67 0 573 109 0 574 121 0 575 87 189 576 160 189 577 214 189 578 87 190 579 189 190 580 160 190 581 161 191 582 189 191 583 87 191 584 100 192 585 189 192 586 161 192 587 100 193 588 138 193 589 189 193 590 85 194 591 138 194 592 100 194 593 201 195 594 138 195 595 85 195 596 201 196 597 211 196 598 138 196 599 90 197 600 211 197 601 201 197 602 90 198 603 163 198 604 211 198 605 214 199 606 222 199 607 87 199 608 208 200 609 183 200 610 167 200 611 167 201 612 178 201 613 208 201 614 183 202 615 173 202 616 167 202 617 223 203 618 222 203 619 214 203 620 225 204 621 222 204 622 223 204 623 225 205 624 178 205 625 222 205 626 182 206 627 178 206 628 225 206 629 182 207 630 208 207 631 178 207 632 196 208 633 177 208 634 144 208 635 177 209 636 152 209 637 144 209 638 212 210 639 177 210 640 196 210 641 226 211 642 177 211 643 212 211 644 226 212 645 141 212 646 177 212 647 163 213 648 141 213 649 226 213 650 163 214 651 90 214 652 141 214 653 175 215 654 213 215 655 218 215 656 185 216 657 175 216 658 218 216 659 185 217 660 152 217 661 175 217 662 144 218 663 152 218 664 185 218 665 204 219 666 139 219 667 179 219 668 139 0 669 204 0 670 207 0 671 206 220 672 207 220 673 130 220 674 206 221 675 139 221 676 207 221 677 193 222 678 162 222 679 221 222 680 88 223 681 206 223 682 187 223 683 115 224 684 206 224 685 88 224 686 115 225 687 162 225 688 206 225 689 221 226 690 162 226 691 115 226 692 206 227 693 130 227 694 108 227 695 192 0 696 206 0 697 108 0 698 187 0 699 206 0 700 192 0 701 216 228 702 115 228 703 197 228 704 216 229 705 159 229 706 115 229 707 115 230 708 159 230 709 113 230 710 219 231 711 115 231 712 220 231 713 220 232 714 115 232 715 88 232 716 115 233 717 191 233 718 197 233 719 89 234 720 115 234 721 219 234 722 190 235 723 115 235 724 89 235 725 191 236 726 115 236 727 186 236 728 190 237 729 147 237 730 115 237 731 115 238 732 149 238 733 186 238 734 115 239 735 147 239 736 80 239 737 115 240 738 74 240 739 155 240 740 115 241 741 155 241 742 149 241 743 115 242 744 80 242 745 215 242 746 115 243 747 174 243 748 126 243 749 136 244 750 174 244 751 115 244 752 126 245 753 74 245 754 115 245 755 215 246 756 136 246 757 115 246 758 183 0 759 136 0 760 215 0 761 136 247 762 218 247 763 174 247 764 185 0 765 218 0 766 136 0 767 136 0 768 144 0 769 185 0 770 82 0 771 68 0 772 70 0 773 82 0 774 70 0 775 110 0 776 82 0 777 110 0 778 153 0 779 72 0 780 153 0 781 110 0 782 72 0 783 110 0 784 143 0 785 110 248 786 180 248 787 143 248 788 78 249 789 143 249 790 180 249 791 78 0 792 180 0 793 86 0 794 86 250 795 180 250 796 127 250 797 127 251 798 180 251 799 224 251 800 97 252 801 127 252 802 224 252 803 97 253 804 224 253 805 120 253 806 120 0 807 224 0 808 172 0 809 172 254 810 224 254 811 195 254 812 172 0 813 195 0 814 199 0 815 195 255 816 203 255 817 199 255 818 107 256 819 203 256 820 195 256 821 107 257 822 158 257 823 203 257 824 102 258 825 158 258 826 107 258 827 102 259 828 145 259 829 158 259 830 102 260 831 151 260 832 145 260 833 102 0 834 140 0 835 151 0 836 129 0 837 151 0 838 140 0 839 106 261 840 129 261 841 140 261 842 75 0 843 129 0 844 106 0 845 75 0 846 106 0 847 227 0 848 106 0 849 164 0 850 227 0 851 117 0 852 227 0 853 164 0 854 117 0 855 164 0 856 157 0 857 157 0 858 164 0 859 200 0 860 164 0 861 188 0 862 200 0 863 146 0 864 200 0 865 188 0 866 142 262 867 146 262 868 188 262 869 111 0 870 142 0 871 188 0 872 111 263 873 188 263 874 202 263 875 111 0 876 202 0 877 170 0 878 116 0 879 170 0 880 202 0 881 81 0 882 116 0 883 202 0 884 81 264 885 202 264 886 96 264 887 81 265 888 96 265 889 128 265 890 92 0 891 210 0 892 109 0 893 94 0 894 210 0 895 92 0 896 94 266 897 104 266 898 210 266 899 94 267 900 137 267 901 104 267 902 83 0 903 137 0 904 94 0 905 83 268 906 99 268 907 137 268 908 83 269 909 125 269 910 99 269 911 99 0 912 125 0 913 105 0 914 105 270 915 125 270 916 135 270 917 105 271 918 135 271 919 194 271 920 76 272 921 194 272 922 135 272 923 76 0 924 135 0 925 213 0 926 76 0 927 213 0 928 95 0 929 95 0 930 213 0 931 184 0 932 175 0 933 184 0 934 213 0 935 152 273 936 184 273 937 175 273 938 152 0 939 177 0 940 184 0 941 141 0 942 184 0 943 177 0 944 141 0 945 181 0 946 184 0 947 90 274 948 181 274 949 141 274 950 90 275 951 91 275 952 181 275 953 77 276 954 91 276 955 90 276 956 77 277 957 90 277 958 201 277 959 77 0 960 201 0 961 93 0 962 85 0 963 93 0 964 201 0 965 85 278 966 131 278 967 93 278 968 85 279 969 100 279 970 131 279 971 100 280 972 119 280 973 131 280 974 100 0 975 161 0 976 119 0 977 119 281 978 161 281 979 166 281 980 87 0 981 166 0 982 161 0 983 87 282 984 198 282 985 166 282 986 87 283 987 165 283 988 198 283 989 87 0 990 222 0 991 165 0 992 148 284 993 165 284 994 222 284 995 123 0 996 148 0 997 222 0 998 123 285 999 222 285 1000 178 285 1001 123 286 1002 178 286 1003 154 286 1004 154 287 1005 178 287 1006 173 287 1007 124 288 1008 154 288 1009 173 288 1010 124 0 1011 173 0 1012 205 0 1013 103 0 1014 124 0 1015 205 0 1016 103 289 1017 205 289 1018 134 289 1019 103 0 1020 134 0 1021 118 0 1022 118 290 1023 134 290 1024 122 290 1025 118 0 1026 122 0 1027 132 0 1028 122 291 1029 169 291 1030 132 291 1031 122 292 1032 209 292 1033 169 292 1034 71 0 1035 169 0 1036 209 0 1037 71 293 1038 209 293 1039 171 293 1040 71 294 1041 171 294 1042 133 294 1043 84 295 1044 133 295 1045 171 295 1046 84 296 1047 168 296 1048 133 296 1049 84 0 1050 112 0 1051 168 0 1052 113 297 1053 176 297 1054 115 297 1055 150 298 1056 115 298 1057 176 298 1058 150 299 1059 217 299 1060 115 299 1061 115 300 1062 217 300 1063 221 300 1064 136 301 1065 183 301 1066 208 301 1067 136 302 1068 208 302 1069 182 302 1070 136 303 1071 182 303 1072 225 303 1073 136 304 1074 225 304 1075 223 304 1076 136 305 1077 223 305 1078 214 305 1079 136 306 1080 214 306 1081 160 306 1082 136 307 1083 160 307 1084 189 307 1085 136 308 1086 189 308 1087 138 308 1088 136 309 1089 138 309 1090 211 309 1091 136 310 1092 211 310 1093 163 310 1094 136 311 1095 163 311 1096 226 311 1097 136 312 1098 226 312 1099 212 312 1100 136 313 1101 212 313 1102 196 313 1103 136 314 1104 196 314 1105 144 314 1106 68 315 1107 73 315 1108 69 315 1109 68 316 1110 69 316 1111 98 316 1112 68 0 1113 98 0 1114 70 0 1115 50 317 1116 60 317 1117 112 317 1118 60 318 1119 65 318 1120 112 318 1121 34 319 1122 35 319 1123 127 319 1124 35 320 1125 49 320 1126 127 320 1127 46 321 1128 227 321 1129 47 321 1130 40 322 1131 47 322 1132 227 322 1133 25 323 1134 128 323 1135 31 323 1136 26 324 1137 31 324 1138 128 324 1139 26 325 1140 128 325 1141 101 325 1142 15 326 1143 22 326 1144 76 326 1145 2 327 1146 15 327 1147 76 327 1148 12 328 1149 165 328 1150 13 328 1151 6 329 1152 13 329 1153 165 329 1154 6 330 1155 165 330 1156 148 330 1157

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + 0.001 0 0 1.6e-4 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + 0.001 0 0 1.6e-4 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_E4.dae b/URDFs/sr_description/meshes/components/forearm/forearm_E4.dae new file mode 100644 index 0000000..15447c5 --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_E4.dae @@ -0,0 +1,304 @@ + + + + + + Blender User + Blender 2.80.75 commit date:2019-07-29, commit time:14:47, hash:f6cb5f54494e + + 2022-02-23T11:14:54 + 2022-02-23T11:14:54 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.21961 0.21961 0.21961 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.80848 0.80848 0.80848 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.21961 0.21961 0.21961 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.04392 0.04392 0.04392 1 + + + 0.21961 0.21961 0.21961 1 + + + 0.45000 0.45000 0.45000 1 + + + 32 + + + 1 + + + + + + + + + + + + + + + + + + + + + + + 29.2331 -14.16401 196.7418 10.76716 -13.86542 201.6429 21.39861 -14.07537 193.4641 27.46566 -14.16783 194.2271 28.3862 -14.16117 201.1792 28.55589 -14.16393 195.3397 26.57802 -14.088 203.1484 26.0908 -14.14846 193.4914 29.12671 -29.98901 195.9577 28.15216 -30.7099 194.1976 29.69017 -29.98164 197.5565 25.48671 -30.31977 193.1829 27.11698 -30.73169 193.5123 21.12255 -28.88793 193.1422 21.49174 -35.58555 193.141 15.37017 -19.99502 188.3348 -21.50867 -35.58535 193.141 -27.01785 -30.10811 193.7396 -21.49532 -28.98937 193.141 -28.13104 -30.71404 194.175 -25.83329 -30.16364 193.2869 -29.20789 -30.24131 196.066 -15.387 -19.99488 188.3347 -27.60938 -14.16784 194.2271 -28.52991 -14.16118 201.1792 -29.57075 -14.16784 198.2878 -26.23451 -14.14847 193.4914 -28.69961 -14.16394 195.3397 -21.49527 -19.99485 193.141 10.70515 -20.04278 200.9014 10.82763 -0.05495995 198.8623 -8.135762 -19.99491 225.7452 -1.23421 -19.99494 228.0908 11.7382 -19.99501 222.4602 5.95719 -19.99498 226.9021 -5.97408 -19.99492 226.9021 1.21731 -19.99496 228.0908 -10.08011 -19.99495 224.2513 -11.75508 -19.99489 222.4602 11.60935 -27.98278 222.6372 10.0632 -19.995 224.2513 -11.76637 -27.98262 222.4723 19.13893 -28.90956 212.8358 -19.56073 -29.1617 212.2155 28.61199 -30.50734 201.1697 -29.58549 -31.27479 199.4863 -28.62001 -31.02658 201.1763 -29.68513 -29.98092 198.6928 0.30527 -20.00591 213.1484 27.08075 -19.99508 203.1861 11.08792 -20.04278 202.3254 12.11914 -14.04642 203.0609 10.88063 -6.11725 201.9681 29.74393 -30.96025 198.3759 27.56346 -30.98839 192.2909 26.96834 -31.01417 183.141 27.47483 -30.98838 185.8623 -18.46961 13.78698 210.5607 -21.49532 8.98936 185.941 21.47847 8.989562 185.941 -15.38701 -0.005129933 188.3347 15.37016 -0.004969954 188.3348 -6.75985 5.95628 226.0962 -19.3355 12.47244 210.992 -8.13577 -0.005089998 225.7452 -1.23421 -0.005059957 228.0908 -0.00830996 9.959582 224.8453 17.88496 10.4642 213.5606 3.46709 5.95633 227.3319 1.2173 -0.00503993 228.0908 15.97012 12.39993 213.5357 10.52479 8.08447 223.6853 6.17142 8.188192 225.1135 18.30959 13.6839 210.6959 6.74287 5.95635 226.0962 17.12156 15.64486 209.2734 -3.48406 5.9563 227.3319 11.7382 -0.004989922 222.4602 -10.60663 7.42227 223.7478 5.95718 -0.005019903 226.9021 -5.97409 -0.005079925 226.9021 -0.008489966 5.95632 227.7518 -11.76637 7.98262 222.4723 -16.29367 12.62307 212.9111 -0.008529961 8.18816 226.6161 -10.08011 -0.005059957 224.2513 -17.75995 10.64507 213.6346 -6.18846 8.18812 225.1134 -16.56421 15.84821 208.9666 -11.75509 -0.005109906 222.4602 0.49007 13.58403 220.1232 11.60934 7.98279 222.6372 13.68506 14.29911 211.3139 15.56888 14.94498 209.9162 12.05915 14.15369 213.031 10.06319 -0.004999995 224.2513 -14.86134 13.86502 212.0578 -13.91902 14.26721 211.633 16.32755 15.88888 208.8843 15.13303 15.10267 208.1131 5.6449 14.28627 218.7978 14.31331 13.30281 213.8854 9.693612 11.31001 222.849 -9.71062 11.3099 222.849 -8.34798 13.16498 221.4855 14.46985 14.123 211.9805 -14.33889 13.31698 213.8898 -5.66194 14.28621 218.7978 -34.98714 16.48372 183.1409 -33.10577 12.07831 191.3992 34.53139 14.69207 192.9881 33.88874 20.98234 194.5057 32.41469 12.07866 193.3363 -34.1106 23.48006 183.1409 30.25814 21.87187 198.9264 -33.77184 22.3201 194.3907 21.85608 22.07732 193.141 21.5077 20.57482 193.141 23.13377 23.71641 201.67 -28.60559 23.35913 199.7737 24.55461 23.43409 201.7894 33.88875 15.98538 194.5058 15.59797 23.35947 198.696 -18.99684 24.95138 199.2961 -26.98518 11.01389 183.141 34.79623 22.32104 191.4061 22.85788 21.89442 183.141 -30.21933 22.3222 198.8859 -34.42173 22.51174 192.9438 34.983 20.98681 191.8221 34.96197 15.42036 191.4038 23.87253 24.13467 193.007 -27.23467 14.78579 192.907 25.57107 24.78537 199.4185 -25.79275 15.58531 191.141 23.03796 22.73579 192.9002 -34.88922 21.86153 183.1409 -32.84603 11.88464 186.1409 -25.58381 24.60102 183.141 -22.51073 15.58533 183.141 -34.43144 14.03747 192.9506 26.59187 23.15303 201.3888 23.33065 24.83233 199.8286 -34.2779 13.29147 191.4056 29.74393 10.96026 198.376 -23.89275 24.13781 193.0072 -30.61917 10.96507 191.6171 34.40472 22.51211 192.944 -23.93853 23.68398 192.6409 33.33868 13.29117 194.0602 -17.29799 23.95095 200.9552 28.25447 24.81621 197.3397 18.9806 24.83241 199.828 33.76669 22.32434 194.3975 -15.50301 16.01193 207.2098 15.79879 23.79947 193.0517 -22.86767 22.95523 193.0072 -32.11723 24.78397 192.5457 -29.2079 10.24129 196.066 -18.36642 24.93965 193.141 31.64711 11.23419 192.173 34.86427 15.97845 192.6572 -23.93228 24.8351 199.8356 16.44956 23.47284 200.9732 -22.88459 24.13721 201.208 21.49174 15.58557 193.141 34.57374 22.71798 183.141 -32.72465 24.58339 183.1409 16.12519 24.09111 199.5014 22.49384 15.58557 183.141 25.77583 15.58558 193.141 -34.67782 14.25417 186.1409 -16.127 24.11815 199.4553 33.79073 14.87376 194.428 -34.99195 15.41791 191.6172 -26.32878 24.97958 192.6354 -34.17892 20.98644 194.1828 22.47717 19.97113 192.6676 19.13892 8.90957 212.8358 31.19183 15.35321 197.9084 -21.50867 15.58534 193.141 -32.14261 14.30173 196.4264 -33.12226 12.36458 193.119 22.4581 21.41522 192.9022 32.11715 14.3039 196.4186 -34.98714 15.98502 185.9497 -25.04825 24.49428 192.6409 23.91961 23.68204 192.6405 27.44081 14.78608 191.641 -22.25968 19.97178 192.986 -29.67965 13.00989 199.7989 -32.04143 11.52369 192.4942 33.26425 12.18998 191.9951 26.57535 14.78608 183.141 30.00427 11.64074 196.8428 -29.81092 11.35786 198.0291 -33.37424 23.89329 193.2573 -30.50339 12.80341 197.7443 -23.08364 22.60834 192.6409 -33.74797 14.3105 194.368 28.41702 10.99705 193.6954 -25.79273 15.5853 183.141 -22.54487 21.34432 192.641 25.56682 24.60129 183.141 29.19439 10.89103 195.2594 30.98028 11.09095 186.141 -21.95733 21.40113 193.1557 -15.57331 23.22389 199.1776 -34.60375 15.97808 193.4542 34.5805 20.99011 193.4515 31.26432 14.32288 197.5403 -29.5855 11.27478 199.4863 -27.23466 14.78579 191.375 32.83066 11.88598 186.141 29.83044 11.42817 194.892 23.945 24.97985 198.6896 30.84862 12.283 195.854 21.12254 8.88795 193.1423 -34.82428 22.32404 191.4081 -31.17939 12.40927 195.6551 27.56345 10.9884 192.2909 27.21774 14.78604 192.907 10.59446 14.2863 212.6366 -25.76259 24.35805 200.5835 -23.34137 22.76534 183.141 34.27376 13.32267 192.1381 -30.99624 11.09043 186.1409 -27.01786 10.1081 193.7396 -25.20465 24.97959 192.9981 -34.98717 20.98197 191.3992 19.45186 12.02961 211.1126 -33.85997 23.85172 191.4055 -29.93584 11.48745 195.3008 34.97022 16.48409 183.141 -21.49532 8.989352 193.141 34.91357 15.23474 186.141 -26.13454 15.58531 193.0807 -28.13105 10.71403 194.175 30.32481 14.308 199.0056 -28.03135 10.9881 186.0626 26.96833 11.01418 183.141 27.11698 10.7317 193.5123 14.4827 14.55406 193.141 -27.91828 24.87933 197.0564 30.97259 24.97988 191.3993 -19.56074 9.16169 212.2155 27.47482 10.9884 185.8623 15.54012 22.73135 199.9994 32.70765 24.58374 183.141 33.34771 23.88522 193.2536 -17.63467 24.7285 199.5171 -27.1286 10.69656 193.53 0.004659891 14.05591 212.8021 26.31544 24.97986 192.639 -25.8333 10.16362 193.2869 -15.98162 23.93966 193.1003 -34.87456 20.98974 192.6554 32.35282 24.78691 191.8237 -28.63495 10.96214 193.9001 -31.22917 15.24397 197.8865 -15.23129 15.28555 193.141 25.02793 24.49245 192.6405 33.8424 23.85223 191.4054 25.18572 24.97985 193.0048 17.70369 24.81411 193.141 25.77583 15.58558 191.141 -27.20847 10.97332 192.9282 25.4867 10.31978 193.1829 29.69016 9.981652 197.5565 28.61198 10.50735 201.1697 28.15215 10.70991 194.1976 29.1267 9.989022 195.9577 -28.62002 11.02657 201.1763 -29.68514 9.980912 198.6928 -27.60927 -5.92986 194.2273 -29.27717 -5.93045 201.2351 -29.57054 -5.92983 198.2878 -26.23457 -5.9503 193.4912 -28.69948 -5.93367 195.3398 0.30526 0.005899906 213.1484 -21.49528 -0.005159974 193.141 11.52659 -0.05495995 202.7647 21.39854 -6.05413 193.6616 26.864 -0.004909992 203.2208 26.09085 -5.95029 193.4912 29.13345 -5.93044 201.4083 29.23282 -5.93372 196.7418 26.6949 -5.97775 203.1822 27.46555 -5.92985 194.2273 28.55576 -5.93366 195.3398 21.47848 -28.98956 185.941 -21.49532 -28.98937 185.941 -11.67031 -0.05495995 202.7647 -26.95345 -0.005189955 203.1901 -26.83862 -5.97777 203.1822 -21.54226 -6.05414 193.6616 -11.02435 -6.11725 201.9681 -27.0507 -19.99482 203.0668 -10.91088 -13.86543 201.6429 -11.23163 -20.04278 202.3254 -12.26285 -14.04643 203.0609 -10.97135 -0.0549699 198.8623 -10.84887 -20.04279 200.9014 -26.72174 -14.08801 203.1484 -21.54232 -14.07538 193.4641 -27.20847 -30.99855 192.9282 25.77584 -35.61081 191.141 17.7037 -44.83934 193.141 25.18573 -45.00508 193.0048 33.84242 -43.87745 191.4054 25.02794 -44.51768 192.6405 -15.23128 -35.31078 193.141 -31.22916 -35.26921 197.8865 -28.63494 -30.98738 193.9001 30.32481 -34.33322 199.0056 32.35283 -44.81213 191.8237 -34.87455 -41.01498 192.6554 -15.98161 -43.9649 193.1003 -29.81091 -31.3831 198.0291 -29.67964 -33.03514 199.7989 26.31545 -45.00509 192.639 0.004669964 -34.08114 212.8021 -27.12859 -30.72179 193.53 -17.63465 -44.75374 199.5171 30.25815 -41.89709 198.9264 33.34773 -43.91044 193.2536 32.70767 -44.60896 183.141 -28.20184 -44.24278 198.9098 15.54013 -42.75657 199.9994 30.9726 -45.00511 191.3993 -27.91827 -44.90458 197.0564 14.48271 -34.57928 193.141 -28.03135 -31.01334 186.0626 31.26433 -34.34811 197.5403 -26.13453 -35.61054 193.0807 34.91357 -35.25996 186.141 34.97023 -36.5093 183.141 -29.93584 -31.51268 195.3008 -33.85996 -43.87696 191.4055 19.45187 -32.05484 211.1126 -34.98717 -41.00721 191.3992 -25.20464 -45.00482 192.9981 -30.99623 -31.11567 186.1409 -30.50338 -32.82864 197.7443 34.27377 -33.34789 192.1381 -23.34136 -42.79058 183.141 -25.76258 -44.38329 200.5835 10.59447 -34.31153 212.6366 27.21775 -34.81126 192.907 -31.17938 -32.4345 195.6551 -34.82426 -42.34929 191.4081 30.84863 -32.30822 195.854 23.94501 -45.00507 198.6896 29.83044 -31.45339 194.892 32.83066 -31.9112 186.141 -27.23465 -34.81103 191.375 34.58051 -41.01534 193.4515 -34.60375 -36.00331 193.4542 -15.5733 -43.24913 199.1776 -21.95732 -41.42637 193.1557 30.98029 -31.11618 186.141 29.19439 -30.91626 195.2594 32.11715 -34.32912 196.4186 25.56683 -44.62652 183.141 -22.54486 -41.36955 192.641 -25.79273 -35.61053 183.141 28.41703 -31.02227 193.6954 -33.74796 -34.33574 194.368 -23.08363 -42.63358 192.6409 -33.37422 -43.91854 193.2573 30.00428 -31.66597 196.8428 26.57535 -34.8113 183.141 33.26425 -32.2152 191.9951 -32.04143 -31.54894 192.4942 -22.25967 -39.99702 192.986 27.44082 -34.81131 191.641 23.91962 -43.70727 192.6405 23.13378 -43.74164 201.67 -25.04824 -44.51952 192.6409 -34.98713 -36.01025 185.9497 22.45811 -41.44044 192.9022 -33.12226 -32.38982 193.119 -32.1426 -34.32697 196.4264 31.19184 -35.37843 197.9084 22.47717 -39.99635 192.6676 -34.1789 -41.01167 194.1828 -26.32877 -45.00481 192.6354 -34.99195 -35.44315 191.6172 33.79074 -34.89899 194.428 -16.12698 -44.14339 199.4553 -34.67781 -34.2794 186.1409 25.77583 -35.61081 193.141 22.49384 -35.61079 183.141 16.12521 -44.11633 199.5014 -32.72463 -44.60863 183.1409 34.57375 -42.7432 183.141 -22.88458 -44.16245 201.208 16.44957 -43.49807 200.9732 -23.93227 -44.86033 199.8356 34.86427 -36.00367 192.6572 31.64712 -31.2594 192.173 -18.36641 -44.96488 193.141 -32.11722 -44.8092 192.5457 -22.86766 -42.98047 193.0072 15.7988 -43.82469 193.0517 -15.503 -36.03717 207.2098 26.59188 -43.17825 201.3888 33.76669 -42.34956 194.3975 18.98061 -44.85764 199.828 28.25448 -44.84144 197.3397 -17.29797 -43.97618 200.9552 33.33868 -33.3164 194.0602 -23.93851 -43.70922 192.6409 34.40473 -42.53733 192.944 -30.61916 -30.9903 191.6171 -23.89274 -44.16305 193.0072 -34.27789 -33.31671 191.4056 33.88875 -36.0106 194.5058 23.33066 -44.85756 199.8286 26.64597 -44.28524 200.1048 -34.43144 -34.06271 192.9506 -22.51072 -35.61057 183.141 -25.5838 -44.62625 183.141 -32.84603 -31.90988 186.1409 -34.88921 -41.88677 183.1409 23.03797 -42.76101 192.9002 -25.79275 -35.61054 191.141 -27.23466 -34.81103 192.907 23.87254 -44.15989 193.007 34.96198 -35.44559 191.4038 34.98302 -41.01204 191.8221 -34.42172 -42.53698 192.9438 -30.21932 -42.34743 198.8859 22.85789 -41.91965 183.141 34.79625 -42.34627 191.4061 -26.98517 -31.03913 183.141 -18.99683 -44.97661 199.2961 15.59798 -43.3847 198.696 -28.60558 -43.38437 199.7737 21.50771 -40.60004 193.141 21.85609 -42.10255 193.141 -33.77182 -42.34534 194.3907 -34.1106 -43.50529 183.1409 32.4147 -32.10388 193.3363 33.88876 -41.00756 194.5057 34.53139 -34.7173 192.9881 -33.10577 -32.10356 191.3992 -34.98714 -36.50895 183.1409 -5.66193 -34.31144 218.7978 -14.33888 -33.34222 213.8898 14.46985 -34.14823 211.9805 5.64491 -34.3115 218.7978 -8.34797 -33.19022 221.4855 -9.71062 -31.33514 222.849 9.69362 -31.33524 222.849 14.31332 -33.32804 213.8854 15.13304 -35.1279 208.1131 16.32756 -35.91411 208.8843 -13.91902 -34.29244 211.633 -14.86134 -33.89025 212.0578 12.05916 -34.17892 213.031 15.56889 -34.9702 209.9162 13.68507 -34.32434 211.3139 0.49008 -33.60926 220.1232 -16.5642 -35.87345 208.9666 -6.18845 -28.21336 225.1134 -17.75994 -30.6703 213.6346 -0.008519947 -28.21339 226.6161 -16.29366 -32.64831 212.9111 -0.008489966 -25.98155 227.7518 -10.60662 -27.4475 223.7478 -3.48405 -25.98153 227.3319 17.12157 -35.67009 209.2734 6.74288 -25.98158 226.0962 18.3096 -33.70912 210.6959 6.17142 -28.21342 225.1135 10.5248 -28.1097 223.6853 15.97012 -32.42515 213.5357 3.46709 -25.98156 227.3319 17.88497 -30.48943 213.5606 -0.008299946 -29.98481 224.8453 -19.33549 -32.49768 210.992 -6.75984 -25.98152 226.0962 -18.4696 -33.81222 210.5607 + + + + + + + + + + 0.01561552 0.9998533 -0.007047474 -9.83374e-4 0.9999992 -8.28155e-4 0.0179196 0.9998139 -0.007163643 -0.007168531 0.9999681 0.003523528 0.9430803 0.01013004 -0.3324108 0.9003587 0.01549392 -0.4348724 0.8726164 0.01240891 -0.4882485 -0.009253084 0.01497787 -0.9998451 0.4717823 -8.03786e-4 -0.8817148 0.2070965 0.03782767 -0.9775889 0.5514918 0.02437365 -0.8338242 0.7138675 0.03087198 -0.6996 0.2803763 0.01563024 -0.9597629 0.006108462 0.01884508 -0.9998038 4.5718e-6 0.9999929 0.00380212 -0.07373255 4.01605e-7 -0.9972781 -0.3711361 0.01462346 -0.9284633 -0.4718902 0.009450912 -0.8816067 -0.3568481 0.00298798 -0.9341576 -0.01830124 0.01230752 -0.9997568 -0.0732674 1.48331e-4 -0.9973124 -0.7139815 0.02471327 -0.6997284 -0.8684197 0.005056619 -0.4958041 -0.9588694 0.01751494 -0.283307 -0.937036 -0.02975642 -0.347963 0.002332031 0.9999969 -0.001030385 0.002692818 0.9999962 -7.23134e-4 0.00100547 0.9999967 -0.002405107 -0.00285989 0.9999933 -0.002279937 0.7823848 0.001180171 0.6227942 -5.38646e-4 0.9999998 -5.09263e-4 -4.01403e-4 0.9999997 -6.29528e-4 -1.76652e-4 0.9999998 -7.22099e-4 7.78423e-6 0.9999998 -7.33227e-4 1.83785e-4 0.9999997 -7.1537e-4 3.47216e-4 0.9999998 -6.4053e-4 4.29291e-4 0.9999998 -5.85633e-4 5.45349e-4 0.9999998 -4.78294e-4 -0.7963042 0.002041757 0.6048931 -0.7663735 -0.06200253 0.6393962 0.9556614 0.04262202 0.2913672 0.9821822 0.01345783 0.1874488 -0.8685721 0.004554927 0.4955421 -0.9838455 0.002532005 -0.179002 -0.9407939 0.01547765 0.3386259 -0.980711 0.04160088 0.1909852 0.03443318 0.9993918 -0.00551629 0.06774985 0.9957424 0.06250667 0.002877116 0.9999958 -2.34614e-4 -0.006032586 0.00586915 0.9999647 -0.05306607 -0.1125792 0.9922248 0.6086811 -0.0421673 0.7922937 0.7361648 0.06695115 0.6734828 -0.9654965 -0.02146059 0.2595301 -0.7207093 0.03904652 0.6921369 -0.9998136 0.007922708 0.01760703 -0.05492252 0.9984904 7.58672e-4 0.920313 -0.220179 -0.3233347 0.8972351 0.3114074 0.3130409 0.7861373 -0.001013457 0.6180511 0.003188788 -0.9999918 0.002502799 -0.003045499 -0.9999921 0.002569794 -0.00465238 -0.9999889 8.33297e-4 -0.02951377 -0.9994115 -0.01748067 -0.7705227 -0.5248699 0.3616716 5.11691e-6 -0.257188 -0.9663614 9.08155e-7 -0.2571765 -0.9663645 0.9985636 0.02016973 0.04963958 -4.67135e-6 0.9999005 0.01410841 -0.07369214 -3.12358e-7 -0.9972811 -0.03583323 -0.02026367 -0.9991524 0.4249283 -0.02359986 -0.9049193 -0.3710723 -0.01455062 -0.92849 -0.472149 -0.009394407 -0.8814687 -0.3568308 -0.002956986 -0.9341644 -1 -4.24115e-6 0 0.7138376 -0.03070336 -0.6996379 0.5515098 -0.02424395 -0.8338161 0.2070288 -0.03762084 -0.9776113 0.4720516 8.22893e-4 -0.8815706 0.001894712 0.9998987 0.01411074 -0.2355772 0.9105972 0.3395823 -5.38089e-4 -0.9999998 -5.08808e-4 -4.01256e-4 -0.9999997 -6.2907e-4 -1.76685e-4 -0.9999998 -7.21357e-4 8.14874e-6 -0.9999997 -7.32639e-4 1.8343e-4 -0.9999997 -7.14579e-4 3.47087e-4 -0.9999998 -6.39864e-4 4.32299e-4 -0.9999998 -5.82758e-4 5.4263e-4 -0.9999998 -4.79544e-4 -0.73538 0.322638 0.5959203 -0.7120482 0.3725554 0.5951384 -0.6078385 0.6282297 0.4856539 -0.48342 0.7671771 0.4215977 -0.5388346 0.7187522 0.4393776 -0.2852668 0.9011696 0.3263683 -0.2129948 0.9589554 0.1871842 -0.02202355 0.999601 -0.01768743 0.01704108 0.9996063 -0.02229034 0.1863371 0.896737 0.4014243 0.07409763 0.9954727 0.05953019 0.2531335 0.9318023 0.260131 0.5006234 0.7538163 0.4256023 0.6172994 0.6169198 0.4882124 0.2999256 0.8867564 0.3517211 0.7286737 0.3009265 0.6152057 0.7174099 0.3757179 0.5866508 0.7168346 0.2806226 0.6382783 0.520361 0.5283061 0.6709077 0.523715 0.5266789 0.6695759 0.5033223 0.7778653 0.3762877 0.3692883 0.7789661 0.5067921 -0.1229239 0.8053518 0.5799122 0.3813698 0.6829724 0.6229814 -0.741412 -0.007068693 0.6710129 -0.7303805 -0.002066254 0.6830375 -0.471109 0.05690366 0.8802376 -0.3518304 0.07971221 0.9326636 -0.243121 0.03165817 0.9694793 -0.1195573 0.08084994 0.9895299 -1.66786e-5 0.05677258 0.9983872 0.7303774 0.006114065 0.6830164 0.694662 -0.004732429 0.7193207 -0.7261114 0.2812638 0.6274177 -0.4371832 0.5765635 0.6902503 -0.4955929 0.5476281 0.6741597 -0.4707143 0.799388 0.3733726 -0.2689011 0.7365325 0.6206546 -0.2763309 0.7346469 0.6196251 -0.7963036 -0.002040565 0.6048938 -0.7663729 0.06200355 0.6393969 -0.6317504 0.3098716 0.7105429 0.4704322 0.3900039 0.7915747 0.3753774 0.4616464 0.8037253 0.66913 0.3433058 0.6590951 -0.5017848 0.06503021 0.8625445 -0.3340008 0.4501765 0.8281211 -0.3153828 0.4489123 0.8360691 -0.1954229 0.5620726 0.8036692 -0.1070548 0.4509173 0.8861225 0.1070474 0.4509207 0.8861216 0.1954075 0.5620626 0.80368 0.3153874 0.448886 0.8360815 0.2884733 0.4467489 0.8468759 0.2431266 0.03166055 0.9694778 0.1195609 0.08085137 0.9895293 0.5421726 0.02782279 0.8398064 0.5179243 0.04720669 0.8541231 0.351823 0.07971644 0.9326661 -0.5526021 0.3217239 0.7688463 -0.3655399 0.4986488 0.7859581 -0.6772923 0.5526573 0.4856389 -0.2271692 0.9638545 0.1392075 -0.6307378 0.7448603 0.2176074 -0.07914316 0.7638497 0.6405232 0.05340451 0.9894914 0.1343678 0.0830931 0.9832947 0.1619484 0.2885079 0.921459 0.2601472 -0.08982717 0.8150457 0.5723913 0.8337591 0.3971052 0.3836059 0.7008895 0.5337672 0.4731242 -0.07362639 0.9393897 0.3348526 -0.6092302 0.01056563 0.7929231 -0.02864557 -0.06671625 -0.9973607 -0.01899331 -0.01468348 -0.9997118 -0.07170587 -0.1221694 -0.9899156 -0.9992634 0.01644247 -0.03467571 -0.9892613 0.1411869 0.03779631 0.01059871 0.9984721 0.05423283 -0.02160245 0.9997224 0.009422302 0.02458703 0.9987548 0.04341065 0.5879015 -0.8089326 3.66184e-6 0.9503999 -0.3110228 0.002229988 0.8465853 -0.5265705 -0.07756859 0.7476761 -0.6637343 -0.02091056 0.5093628 -0.8605239 0.006959497 0.3946705 -0.9185638 -0.0218169 0.4849303 -0.8745529 2.15127e-6 -0.1596977 9.15928e-4 -0.9871655 2.62161e-5 -1.92937e-4 -1 -0.02109515 -0.02395379 -0.9994905 5.41095e-6 -0.007953941 -0.9999685 0 0 -1 -0.02604895 -0.03952682 -0.998879 -0.01878607 0.0265699 -0.9994705 0.05621528 -0.01764327 -0.9982628 -0.01577299 0.003093779 -0.9998708 0.004349648 -0.004326999 -0.9999812 3.0096e-5 -2.98508e-5 -1 -5.97265e-6 -2.32931e-4 -1 -3.49237e-6 0 -1 0.06948161 -0.02334308 -0.9973102 1.17088e-5 0 -1 0.05688816 -0.06188285 -0.9964609 -0.149518 0.1477029 -0.9776647 0.02101701 0.02193903 -0.9995384 0.02149832 0.01863515 -0.9995953 -0.01842051 -0.01221692 -0.9997557 -0.07320165 -1.48202e-4 -0.9973172 0.01302427 -0.03728014 -0.9992201 0.1754911 -0.02767938 -0.9840918 -0.5018509 0.8648977 -0.009893178 0.08127123 -0.07713711 -0.9937026 0.4938455 -0.8651844 0.08702135 0.9576157 -0.2497935 0.1434417 0.9996075 0.0161854 0.02287256 0.002379298 0.9999973 1.19346e-6 1.09931e-5 9.98728e-7 -1 2.9185e-6 -1.18877e-4 -1 1.13283e-5 -2.95498e-6 -1 1.94274e-5 -1.88479e-5 -1 1.00795e-5 1.31849e-5 -1 1.018e-5 -4.62368e-6 -1 9.84221e-6 -1.6866e-7 -1 0.3747807 0.9270318 -0.01231205 0.1591798 0.9871444 0.01442277 0.3863968 0.9221749 -0.01706165 0.999954 -0.003096759 -0.00908643 0.9997152 -0.02175867 0.009814977 0.997394 0.06343418 -0.03437125 -0.936868 -0.02874648 -0.3485 -0.9829717 -0.06138265 -0.1732013 6.28868e-6 -1 1.39816e-6 6.37632e-6 -1 1.69668e-6 9.29848e-6 -1 2.32462e-7 -0.411606 -0.8475078 -0.3351284 -0.3163666 -0.3705716 -0.8732634 2.44869e-6 -1 0 -0.1916322 -0.9783129 0.0786184 2.56887e-6 -1 1.86827e-7 0.3608216 0.8531318 0.3767942 0.06977778 0.8842558 0.4617605 -0.3635968 -0.9315491 0.003710746 -0.3945259 -0.9188822 -0.002241134 -0.4696127 -0.8828235 0.009317815 -0.7191555 -0.6947782 -0.009934186 -0.7901011 -0.6107949 -0.05167198 -0.9474853 -0.3195125 0.01354765 -0.9838739 -0.1778907 -0.01863515 -0.0548895 -0.9984923 7.56458e-4 0.01396352 -0.9998953 -0.003825962 -0.4694667 0.8828023 -0.01616048 -0.2559659 0.9655795 0.04623579 0.9999764 0.006870687 6.22494e-6 0.2503749 -0.003657698 -0.9681421 0.763278 0.6458025 -0.01860147 -0.2727189 0.8640754 0.4230818 0.2152742 -0.9685378 -0.1248667 0.05919623 -0.9978007 -0.02983027 0.06005632 -0.9981946 -8.2818e-4 0.02759218 -0.9994053 0.02068221 -0.03444087 -0.9994049 0.00197637 0.01151961 -0.9996533 -0.0236774 0.004373311 -0.9999776 -0.005082786 0.9994055 0.02954089 0.0177769 0.9946824 0.08597451 -0.05670303 -0.568115 -0.795584 -0.2104555 -0.5583503 -0.8168305 -0.1450276 -0.9998291 0.01820641 0.003232419 -0.999854 0.01707386 8.59636e-4 -0.9999301 3.94797e-4 -0.01181763 0.4772557 -0.8143917 -0.3301413 0.5607668 -0.8203443 -0.1121422 -0.00246793 0.9997731 -0.02116316 -0.03393405 0.9993694 0.01046085 -0.03308695 0.9985523 -0.04241055 0.005249023 0.9995884 0.02820628 -0.006562709 0.9997723 0.02031064 -0.007406949 0.9999691 -0.002665102 -0.01351153 0.9986205 -0.05074167 0.002455651 0.9991959 -0.04001909 2.37993e-5 1 8.81335e-5 -0.02211898 0.9997543 0.001488208 -0.03124815 0.9994884 -0.006819605 -5.61348e-6 1 -8.64025e-7 3.53451e-7 0 -1 -9.37535e-6 0 -1 4.60591e-6 0 -1 1.03512e-6 0 -1 -0.4849405 -0.8745471 0 -0.4138299 -0.9074271 -0.07294458 -0.4434108 -0.8951808 0.04514765 -0.9925606 -0.1034097 0.06426614 -0.9947476 -0.01479196 0.1012839 0.07096368 0.9917967 0.1063174 0.04890638 0.9868294 0.1541952 0.1234307 0.8427708 0.5239298 0.1143648 0.841211 0.528474 0.219567 0.8041195 0.552433 0.3604821 0.8014485 0.4772137 0.5655164 0.6549519 0.5012278 -0.8274569 0.5226513 0.2053067 -0.5280175 0.8407658 0.1196261 -0.7690887 0.4900162 0.4103495 -0.8873252 0.1838574 0.4229074 -0.8899116 0.2083881 0.4057484 -0.8040372 0.5778281 0.1401391 -0.9593175 0.2694405 0.08433115 -0.9642212 0.1154479 0.2386404 -0.8688678 -0.1330495 0.4768297 -0.8676385 -0.4969342 0.01612305 -0.9044708 -0.4103116 0.116521 -0.9175149 -0.1181952 0.379732 -0.2441689 -0.8989203 -0.3637636 -0.6721805 -0.6307423 -0.3877339 -0.5974522 -0.8018327 -0.01073169 -0.9882476 -0.01705551 0.1519078 -0.9642937 -0.1811885 -0.1931539 -0.8705127 -0.348563 0.347436 -0.7695573 -0.5342514 0.3497957 -0.81971 -0.08346235 0.5666653 -0.8681145 -0.1954786 0.4562517 -0.7247098 -0.5218476 0.4499677 -0.5606065 -0.8176971 0.1307356 -0.7146515 -0.691065 0.1081783 -0.7804269 -0.589892 0.2072712 -0.9442567 -0.3232704 0.06225353 -0.9572325 -0.1493089 0.2478163 0.8360711 1.33197e-5 0.5486212 0.8841178 -0.02389752 0.4666528 0.9706866 0.01696532 0.2397498 0.9965743 -0.009937644 0.08210355 -0.6227433 0.7822567 -0.01629316 -0.9011184 0.4335024 0.007832765 -0.8454152 0.5336051 -0.02321231 -0.9927151 0.1204811 0.001057386 -0.4778087 0.8783803 0.01212602 0.9543956 -0.2649516 0.1375851 0.5125366 -0.8194128 0.2566494 0.6355918 -0.690502 0.3452972 0.6859034 -0.6520827 0.3229935 0.8263667 -0.4009248 0.3954462 0.8176549 -0.3412975 0.4636341 0.8785032 -0.1076066 0.4654601 0.8788756 -0.109982 0.4641999 0.9640756 -0.206492 0.1670908 0.7789077 0.1204649 0.6154601 0.6247628 0.5636731 0.5403186 0.1967519 0.8852924 0.4213624 0.6079871 0.655305 0.448249 0.1140219 0.9902958 0.0794565 0.05424469 0.9971574 0.05229395 7.63476e-7 0.9917173 0.1284403 -5.57107e-5 0.855217 0.5182702 0.6628001 -0.4888519 -0.5672035 0.4250437 -0.8640182 -0.2698344 0.5050352 -0.8071358 -0.3057305 0.6443608 -0.7647176 -0.002474963 0.6346895 -0.7716925 0.04074215 0.7714651 -0.5656436 0.2913568 0.6992948 -0.4688475 0.5396007 0.8350618 -0.1320554 0.5340725 0.9077774 -0.4182678 -0.03150045 0.8182771 -0.2402003 0.5222321 0.8979862 -0.3095173 -0.3127618 0.8924387 -0.448652 -0.0475887 0.92031 0.2202008 -0.3233284 0.8972198 -0.3114494 0.3130432 0.7846387 -0.1588892 0.5992466 0.2363368 -0.8919925 -0.3853499 -0.7970869 -0.02018803 0.6035272 -0.7675027 0.01902532 0.6407633 -0.7661004 0.01858872 0.6424521 -0.7700661 0.03111505 0.6372049 -0.7724037 0.01748228 0.6348912 0.02658361 0.899107 0.4369211 -0.01884251 0.9989008 0.04292184 -0.3006139 0.06971323 -0.9511948 -0.3598193 0.1449738 -0.9216901 -0.6508402 0.4357442 -0.6217188 -0.4024789 0.5504338 -0.7314598 -0.4052345 0.6278684 -0.6645046 -0.3334318 0.2679589 -0.9038923 -0.2578296 0.1117492 -0.9597063 -0.2392701 0.6298083 -0.73898 0.990478 0.1145869 -0.07631158 0.9814518 0.1645613 -0.09834754 0.5533722 0.8221759 0.1334404 0.8393178 0.5229089 0.1487008 0.9577251 0.1842736 0.2209207 0.9500852 0.2060413 0.2342758 0.7672755 0.500145 0.4014268 0.7974837 0.5680521 0.2033138 0.8042327 0.2694952 0.5297001 0.9039701 0.115408 0.4117271 0.7761536 -0.111862 0.6205422 0.7647511 -0.3449332 0.5442214 0.6236506 -0.5473755 0.5580683 0.5836703 -0.6952409 0.4194869 0.423861 -0.8426687 0.3320413 0.4037796 -0.8530196 0.3306353 0.1520934 -0.9734494 0.1710667 0.9802788 0.1901723 -0.05374163 0.9197636 0.3920379 -0.01847422 0.7828142 0.6221591 -0.01095563 0.6330473 0.7733222 -0.03498685 0.5895365 0.8073804 -0.02416431 0.3544063 0.9350436 -0.009473919 -0.5067823 -0.3723047 -0.7775353 -0.2469734 -0.8998813 -0.3594689 -0.2498766 -0.8918724 -0.376995 0.7756012 0.009838342 0.6311467 0.7748757 0.01344811 0.6319707 0.7782664 0.01343435 0.6277906 0.7822631 0.01479077 0.6227727 0.7727896 1.38788e-5 0.6346625 -0.9959989 0.004353165 0.08926069 -0.9770304 -0.01896309 0.2122547 -0.9099169 0.01688849 0.4144468 0.6010963 0.285396 0.74648 0.06548047 0.649806 0.7572744 0.2335387 0.5700045 0.7877528 0.9909892 0.1323928 -0.02031874 0.8487841 0.5287336 0.002544105 0.143653 0.9894773 -0.01728206 0.5318949 0.8468082 0.001921951 0.7066237 0.7067496 -0.03446674 -0.9991282 -0.006493687 -0.04123902 -0.3540402 0.9351833 -0.009369313 -0.5900734 0.806986 -0.02422761 -0.705804 0.7063435 -0.05403476 -0.7369824 0.6744424 -0.04454702 -0.9154844 0.4019613 -0.01776158 -0.4381065 0.001401245 -0.898922 -0.5948804 0.2809926 0.7531007 -0.3912907 0.474345 0.788599 -0.1161795 0.6381697 0.7610795 -0.7994903 -0.08438038 0.5947229 -0.7754129 -0.1842107 0.6039879 -0.6629921 -0.5435766 0.5147485 -0.6602965 -0.5461651 0.5154729 -0.4397987 -0.8264575 0.3514901 -0.4887438 -0.7963126 0.3563928 -0.2597916 -0.948232 0.182659 -0.2017438 -0.9638398 0.1741042 -0.3998326 0.8392901 0.3684103 -0.1537533 0.9595644 0.2357882 -0.0354377 0.8796215 0.4743524 -0.8192392 0.5732416 0.01553893 -0.9991894 0.02178466 -0.03385227 -0.7931811 0.4790177 0.3760396 -0.8798047 0.442303 0.1741027 0.8508662 0.5253615 0.004709303 0.6052916 0.586708 0.5379554 0.6608806 -0.05089694 -0.7487632 0.6208562 0.2645697 -0.7379299 0.6541627 0.3175907 -0.6864455 0.5396941 0.4289317 -0.7243949 0.5600119 0.4854119 -0.671388 0.4017937 0.5502665 -0.7319622 0.4044627 0.6230685 -0.6694743 0.2398301 0.6244189 -0.743359 -0.9755337 0.2197839 0.005385875 -0.9933806 0.05732041 -0.09954684 -0.7767203 0.1414058 0.6137671 -0.6457282 0.5682321 0.5100466 -0.655591 0.5434229 0.5243015 -0.3957766 0.845305 0.3589156 -0.4101067 0.8362125 0.3640896 0.9156996 -0.2218957 0.3350471 0.7881427 -0.1518562 0.5964654 0.2319261 -0.1492663 -0.9612128 0.8726297 -0.01234376 -0.4882264 0.9003875 -0.01541072 -0.4348161 0.9430788 -0.01008385 -0.3324166 0.9556811 -0.0423755 0.2913385 0.9992616 0.032009 0.02125591 -0.8655185 0.03527402 0.4996334 -0.7139762 -0.02458065 -0.6997385 -0.8684329 -0.005037248 -0.4957812 -0.9588723 -0.01742041 -0.283303 -0.9838462 -0.002529859 -0.1789985 -0.9950361 -0.00968796 0.09904223 -0.9912885 -0.004385471 0.1316354 -0.006805241 -0.9999716 0.003245055 0.009081721 -0.999953 -0.00339955 0.02289599 -0.9995089 0.02139681 -0.003095984 -0.9999951 6.3684e-4 0.01654303 -0.9998555 -0.003924548 0.01694923 -0.9998489 -0.003889501 -0.3648681 -2.32698e-7 -0.9310593 -0.02970188 -0.005619406 0.999543 -0.07490563 -0.1220666 0.9896913 0.6197327 -0.01931172 0.7845754 0.5883926 -0.02188336 0.8082793 0.999951 -2.34747e-4 0.009894788 -0.9181715 -5.32592e-7 -0.3961832 -0.9810655 0.0814464 0.1757188 -0.9990285 0.01286119 0.04215216 0.9999437 3.20409e-7 0.01061552 -0.3648763 0 -0.931056 0.002380132 -0.9999972 0 -1 5.65485e-6 0 -4.43723e-6 -0.9999005 0.01411229 0.9985735 -0.01968896 0.04963397 8.95525e-7 0.2571764 -0.9663645 5.1169e-6 0.2571879 -0.9663615 0.3648553 0 -0.9310643 -1 0 6.88764e-6 -0.9996351 -0.006514608 -0.02621853 0.9990285 0.01286178 0.04215323 0.9810657 0.08144569 0.1757178 0.9221678 4.01184e-7 -0.3867903 -0.9999833 1.49927e-4 -0.005787253 -0.9999031 0.008701324 0.01087605 -0.6240751 -0.01303207 0.7812559 0.0342608 -0.08595836 -0.9957095 -0.6197327 -0.01931256 0.7845754 0.07490497 -0.1220666 0.9896914 0.02782058 -7.8799e-4 0.9996127 0.364862 1.74527e-7 -0.9310616 -0.01694965 -0.9998488 -0.003890633 -0.01624745 -0.9998602 -0.003951251 -3.73537e-4 -1 -1.7318e-4 -0.02289587 -0.9995089 0.02139723 -0.009080529 -0.9999531 -0.003400564 0.006906628 -0.9999706 0.003343224 0.9998136 0.007922589 0.01760774 0.7207027 0.03904807 0.6921437 0.9655002 -0.02145862 0.2595167 -0.7367969 0.03170281 0.6753705 -0.6086808 -0.04216694 0.7922939 0.04616856 -0.1137907 0.9924315 0.006091892 -0.01415282 0.9998814 -0.002877116 0.9999959 -2.34832e-4 -0.06774985 0.9957424 0.06250584 -0.03443318 0.9993919 -0.005516827 -0.005532741 0.9999846 -3.11838e-4 0.9401224 -0.0288853 -0.3396108 -0.01791948 0.9998138 -0.007163763 0.003006219 0.9999954 -5.59963e-4 -0.01561576 0.9998533 -0.007047951 -0.00665456 0.05444574 -0.9984946 -0.7809695 0.004064798 0.624556 -0.7851648 0.005571246 0.6192618 -0.6859233 0.02910339 0.7270916 -0.7851656 -0.00557214 0.6192607 -0.003186404 -0.9999918 0.002517282 0.002876639 -0.9999927 0.002543389 0.004396855 -0.9999901 7.90092e-4 0.002737402 -0.9999941 0.00209999 5.21896e-6 -0.9999889 -0.004736304 0.002923846 0.9999931 -0.002302467 -9.41666e-4 0.9999967 -0.002402782 -0.002547204 0.9999966 -6.90574e-4 -0.01241379 0.9998887 0.008295118 -0.09635287 0.7400428 0.6656221 -0.09785389 0.7200407 0.6869979 0.1229031 0.630445 0.7664425 0.05083739 0.87742 0.477022 0.05550712 0.7045406 0.7074896 -0.07282197 0.6513915 0.7552391 0.1010162 0.9932321 0.05732113 -0.1165456 0.9906029 0.07157582 0.0182901 0.9161313 0.400461 0.05686694 0.7890757 0.6116582 0.01517993 0.7924017 0.6098107 0.03442543 0.8215215 0.5691373 -0.1216966 0.5496576 0.8264784 0.1066825 0.5021325 0.8581852 0.004188001 0.5902419 0.8072156 -0.3277313 0.2838617 0.9011186 0.3029078 0.3115621 0.9006531 0.1694653 0.6967461 0.6970126 -0.169481 0.696765 0.6969898 -0.1157587 0.7179153 0.6864384 -0.798479 0.4406887 0.410152 -0.7984801 -0.4406876 0.4101511 -0.1157594 -0.7179127 0.686441 -0.1694784 -0.6967654 0.69699 0.1694658 -0.6967464 0.6970121 0.3029071 -0.3115618 0.9006535 -0.3277247 -0.2838609 0.9011212 0.004183411 -0.5902422 0.8072155 0.1066867 -0.5021319 0.8581851 -0.1216967 -0.5496581 0.8264781 0.03442543 -0.8215218 0.569137 0.01517879 -0.792401 0.6098119 0.05686688 -0.7890751 0.6116589 0.01828736 -0.9161332 0.4004566 -0.1165456 -0.9906029 0.07157582 0.1010162 -0.9932321 0.05732148 -0.07281565 -0.6513924 0.755239 0.0555076 -0.7045409 0.7074893 0.05084019 -0.8774212 0.4770193 0.1229027 -0.6304432 0.766444 -0.09785425 -0.7200406 0.686998 -0.09635329 -0.7400448 0.6656199 0.2317361 0.1483667 -0.9613979 0.7881434 0.15186 0.5964634 -0.3167011 -0.9075972 0.2756226 -0.4140712 -0.8482246 0.3302423 -0.5395525 -0.7096875 0.4530196 -0.6555927 -0.5434225 0.5242998 -0.6457279 -0.5682289 0.5100505 -0.776723 -0.1414021 0.6137645 -0.9933947 -0.05732291 -0.0994032 -0.9758101 -0.21856 0.005127072 0.2398105 -0.6244221 -0.7433626 0.4044717 -0.6230846 -0.6694537 0.4018092 -0.550262 -0.7319571 0.5600175 -0.4854167 -0.6713799 0.5396963 -0.4289281 -0.7243953 0.6541643 -0.3175924 -0.6864432 0.6208423 -0.2645666 -0.7379427 0.6608842 0.05089545 -0.7487602 0.605291 -0.5867071 0.5379568 0.8508697 -0.5253557 0.004708409 -0.8797973 -0.4423131 0.1741145 -0.7931867 -0.4790179 0.3760278 -0.9991895 -0.02178269 -0.03385305 -0.8192293 -0.5732556 0.01553922 -0.03543365 -0.8796225 0.4743509 -0.1537479 -0.9595668 0.235782 -0.2527154 -0.9227926 0.2908416 -0.4116985 -0.7353618 0.5382819 -0.2017378 0.9638411 0.1741042 -0.2598019 0.9482291 0.1826599 -0.4887523 0.7963092 0.3563887 -0.4397916 0.8264623 0.3514876 -0.6602929 0.5461685 0.515474 -0.6629944 0.5435734 0.514749 -0.7754171 0.1842058 0.603984 -0.7994899 0.08438801 0.5947225 -0.1161795 -0.6381701 0.7610791 -0.3912903 -0.4743452 0.7885991 -0.5947979 -0.2807018 0.7532742 -0.4381141 -0.001394927 -0.8989183 -0.9154844 -0.4019613 -0.01776087 -0.7369866 -0.6744379 -0.04454606 -0.7058036 -0.7063439 -0.05403476 -0.5900745 -0.8069853 -0.02422738 -0.354041 -0.9351831 -0.009369909 -0.9991283 0.006489396 -0.04123884 0.7066251 -0.7067482 -0.0344668 0.5318939 -0.8468089 0.001921832 0.1436579 -0.9894766 -0.01728206 0.8487824 -0.5287364 0.002543389 0.9909892 -0.1323919 -0.02031975 0.1629773 -0.6154218 0.7711644 0.6002393 -0.2721695 0.7520882 -0.9099137 -0.01689112 0.4144537 -0.9770304 0.01896232 0.2122544 -0.9959983 -0.004354298 0.08926653 0.7727872 -1.17436e-5 0.6346653 0.7822638 -0.01479077 0.6227717 0.7782727 -0.0134325 0.6277828 0.7748641 -0.0134468 0.6319847 0.7756067 -0.009769678 0.6311409 -0.2498764 0.8918737 -0.3769922 -0.2545314 0.8776582 -0.4061159 -0.5030127 0.3592442 -0.78608 0.3544009 -0.9350457 -0.009474277 0.589532 -0.8073836 -0.02416473 0.6330451 -0.7733238 -0.03498852 0.7828165 -0.6221563 -0.01095533 0.9197658 -0.3920325 -0.01847434 0.9802774 -0.1901789 -0.05374157 0.1520909 0.9734491 0.1710709 0.4037771 0.8530201 0.3306369 0.4238623 0.8426662 0.3320458 0.5836796 0.695232 0.4194886 0.6236494 0.5473738 0.5580713 0.764749 0.344937 0.5442218 0.7761544 0.1118572 0.620542 0.9039669 -0.1154219 0.4117301 0.8042307 -0.2694995 0.5297009 0.7974857 -0.5680493 0.2033143 0.7672784 -0.5001384 0.4014297 0.9500834 -0.2060435 0.2342812 0.9577237 -0.1842757 0.2209249 0.839318 -0.5229063 0.1487089 0.5533696 -0.8221775 0.1334397 0.9816411 -0.1636645 -0.09795272 0.990478 -0.1145861 -0.07631123 -0.2392714 -0.629809 -0.7389789 -0.2578273 -0.1117475 -0.959707 -0.333428 -0.267957 -0.9038943 -0.4052199 -0.6278792 -0.6645033 -0.4024835 -0.55044 -0.7314526 -0.6508463 -0.4357496 -0.6217085 -0.3598049 -0.1449792 -0.9216949 -0.3006575 -0.06971067 -0.9511811 -0.01884192 -0.9989006 0.04292756 0.02657991 -0.8991083 0.4369187 -0.7723858 -0.01748555 0.634913 -0.7701148 -0.03067618 0.6371673 -0.7661063 -0.01858836 0.6424451 -0.7675042 -0.01902604 0.6407616 -0.7970856 0.02018475 0.6035291 0.2535958 0.8756906 -0.4109198 0.7846361 0.1588929 0.5992489 0.9159475 0.2203544 0.3353866 0.8957033 0.4416928 -0.05121588 0.8988689 0.3035946 -0.3160145 0.8186227 0.2385198 0.5224609 0.9081901 0.41686 -0.03766542 0.8350587 0.132052 0.534078 0.6992965 0.468846 0.5395998 0.7714607 0.5656477 0.2913608 0.6346947 0.7716882 0.04074245 0.6443302 0.7647435 -0.002476513 0.5050375 0.8071385 -0.3057201 0.4562367 0.8433465 -0.2839275 0.6720523 0.4761483 -0.5671231 -5.57107e-5 -0.8552163 0.5182714 0 -0.9917175 0.1284381 0.05424267 -0.9971575 0.05229395 0.114026 -0.9902949 0.07946074 0.6079872 -0.655304 0.4482503 0.1967505 -0.8852941 0.4213593 0.624763 -0.5636701 0.5403214 0.7789117 -0.1204689 0.6154542 0.9640727 0.206499 0.1670988 0.8788765 0.1099736 0.4642002 0.8785071 0.1076032 0.4654534 0.8176548 0.3413038 0.4636294 0.8263599 0.4009275 0.3954572 0.6858997 0.6520839 0.3229989 0.635596 0.6904995 0.3452945 0.5125473 0.819407 0.2566469 0.954396 0.2649465 0.137593 -0.4778034 -0.8783832 0.01212602 -0.9927139 -0.1204916 0.001057803 -0.8454159 -0.533604 -0.02321141 -0.9011201 -0.433499 0.007833063 -0.6227384 -0.7822605 -0.01629376 0.9965736 0.009937465 0.08211195 0.9706856 -0.01696079 0.2397538 0.8841198 0.02389872 0.4666489 0.8360694 -8.47633e-6 0.5486238 -0.957233 0.149309 0.2478142 -0.944256 0.3232735 0.06224888 -0.7804265 0.5898939 0.2072667 -0.7146556 0.6910612 0.108175 -0.5606067 0.8176974 0.1307339 -0.7247087 0.5218446 0.4499728 -0.8681064 0.1954864 0.4562637 -0.819703 0.08345621 0.5666765 -0.7695608 0.5342481 0.3497934 -0.8705136 0.3485633 0.3474332 -0.9649506 0.1778831 -0.1929459 -0.9882927 0.01688498 0.1516331 -0.5974515 0.8018334 -0.01072555 -0.6754906 0.6236003 -0.3934912 -0.2740764 0.884638 -0.3772238 -0.9177595 0.1165055 0.3796631 -0.9046795 0.4118255 0.1093373 -0.8719916 0.4892361 0.01669174 -0.8689638 0.1312093 0.4771648 -0.9642225 -0.1154589 0.2386301 -0.9593179 -0.2694368 0.08433866 -0.8040369 -0.5778309 0.1401301 -0.8899129 -0.2083746 0.4057527 -0.8873223 -0.1838634 0.4229105 -0.7690857 -0.4900171 0.4103543 -0.5280125 -0.8407688 0.1196268 -0.827458 -0.5226476 0.2053114 0.5879882 -0.6555112 0.4738934 0.07571399 -0.7536299 0.6529237 0.1782882 -0.8329461 0.5238456 0.5785899 -0.6055189 0.5464254 0.1497783 -0.9670164 0.2060241 0.1182811 -0.9579306 0.2614931 -0.994749 0.01469337 0.101285 -0.9926303 0.1027346 0.06427264 -0.4434116 0.8951804 0.04515022 -0.4138267 0.9074281 -0.07295143 -0.4849444 0.874545 -2.31367e-6 -1.4138e-6 0 -1 -5.21713e-6 -1 -9.87456e-7 -0.0312457 -0.9994885 -0.006819605 -0.0221188 -0.9997543 0.001488804 2.37993e-5 -1 5.0362e-5 0.002456784 -0.9991959 -0.04001933 -0.01351159 -0.9986205 -0.05074238 -0.007404625 -0.9999691 -0.002663493 -0.006559848 -0.9997721 0.02031409 0.005249023 -0.9995886 0.02819651 -0.03308689 -0.9985523 -0.04241108 -0.03393387 -0.9993694 0.01045912 -0.002466559 -0.9997731 -0.02116179 0.5625076 0.8191086 -0.112456 0.4793964 0.8133304 -0.3296559 -0.9999302 -3.97464e-4 -0.01181858 -0.999854 -0.01707005 8.57435e-4 -0.9998291 -0.01820611 0.003236711 -0.5583469 0.816833 -0.1450268 -0.5681154 0.7955833 -0.2104571 0.9946826 -0.08597427 -0.05670309 0.9994055 -0.02954083 0.01777702 0.004370391 0.9999776 -0.00507766 0.01152008 0.9996532 -0.02367955 -0.03444099 0.9994048 0.001975238 0.03484785 0.999195 0.01987296 0.06619232 0.9978065 -9.11919e-4 0.06575399 0.9977093 -0.01589393 0.2324028 0.9654414 -0.1179484 -0.272727 -0.8640773 0.4230725 0.7632826 -0.645797 -0.01860153 0.2503061 0.00365889 -0.9681599 0.9999764 -0.006869375 6.22494e-6 -0.2559697 -0.9655786 0.04623591 -0.4694701 -0.8828005 -0.01615875 0.01395988 0.9998953 -0.003827512 -0.9838749 0.1778851 -0.01863652 -0.9474848 0.319514 0.01354771 -0.7900997 0.6107968 -0.0516709 -0.7191565 0.6947773 -0.009933114 -0.4696145 0.8828225 0.009318947 -0.3945242 0.9188829 -0.002240538 -0.3636043 0.9315462 0.003709852 0.06976252 -0.8842528 0.4617686 0.3608219 -0.8531297 0.376799 0.00494951 0.9999857 -0.002028107 -0.1916331 0.9783127 0.07862019 0.005896329 0.9999827 -3.56167e-6 -0.3187491 0.3573514 -0.8778947 -0.4251361 0.8424407 -0.3309882 1.16521e-5 0.9999969 -0.002523541 -0.005432426 0.9999849 -9.56914e-4 -0.005879878 0.9999827 1.81246e-6 -0.9829964 0.06097781 -0.1732048 -0.9368816 0.0285623 -0.3484786 0.997394 -0.063434 -0.03437215 0.999715 0.02176302 0.009816706 0.9999539 0.003097832 -0.009088635 0.3863917 -0.922177 -0.0170626 0.1591699 -0.9871459 0.01442086 0.3747824 -0.927031 -0.01231426 1.18106e-5 1.68675e-7 -1 1.01801e-5 4.6237e-6 -1 1.17595e-5 -1.3185e-5 -1 1.55417e-5 1.88478e-5 -1 8.49626e-6 2.95496e-6 -1 -1.5263e-6 1.18872e-4 -1 5.49652e-6 -9.98732e-7 -1 0.9996075 -0.01618295 0.02287381 0.9576163 0.2497914 0.1434407 0.4938477 0.8651834 0.08701807 0.08183103 0.07767653 -0.9936147 -0.5018499 -0.8648982 -0.009893476 0.1753887 0.02755653 -0.9841135 0.0128324 0.03711909 -0.9992285 0.02149415 -0.01863509 -0.9995953 0.02101212 -0.02193951 -0.9995386 -0.1495462 -0.1477016 -0.9776606 0.05689537 0.06188315 -0.9964604 1.17085e-5 0 -1 0.06935995 0.02323383 -0.9973211 -4.45904e-6 2.15306e-4 -1 2.74334e-5 2.76083e-5 -1 0.00436896 0.004325568 -0.9999811 -0.01578551 -0.003089249 -0.9998707 0.05621349 0.01764327 -0.998263 -0.01879006 -0.0265693 -0.9994704 -0.02604907 0.03952699 -0.9988789 7.21659e-6 0 -1 4.84819e-5 0.007918596 -0.9999687 2.09687e-5 1.7912e-4 -1 -0.1596896 -9.11323e-4 -0.987167 0.4849263 0.8745551 2.80999e-6 0.3946677 0.9185648 -0.0218203 0.5093696 0.8605198 0.006959199 0.747671 0.6637401 -0.02090996 0.8465863 0.5265686 -0.07757008 0.9503988 0.3110259 0.002228796 0.5879024 0.808932 3.66185e-6 0.02458733 -0.9987548 0.0434103 -0.02160239 -0.9997223 0.00942111 0.01059871 -0.9984721 0.05423325 -0.9892613 -0.1411867 0.03779608 -0.9992634 -0.01644313 -0.03467535 -0.07170575 0.1221691 -0.9899157 -0.01898711 0.01468348 -0.9997119 -0.02864581 0.06671714 -0.9973607 -0.6092178 -0.01053076 0.7929331 -0.07362383 -0.9393891 0.3348549 0.7008909 -0.5337646 0.4731252 0.8337613 -0.3971043 0.3836021 -0.08983391 -0.815045 0.5723912 0.2885083 -0.9214586 0.2601485 0.08309364 -0.9832934 0.1619556 0.0534023 -0.9894925 0.1343609 -0.07914286 -0.7638472 0.6405263 -0.6307367 -0.7448605 0.2176102 -0.2271678 -0.9638542 0.1392116 -0.6772837 -0.5526646 0.4856425 -0.3655392 -0.49865 0.7859577 -0.5548316 -0.3192333 0.7682785 0.3518245 -0.07938301 0.9326938 0.5180169 -0.0469895 0.8540788 0.5421748 -0.02773648 0.8398078 0.1195595 -0.080513 0.9895571 0.2431306 -0.03152769 0.9694812 0.2884729 -0.4467502 0.8468753 0.3153802 -0.4488881 0.8360831 0.1954076 -0.5620622 0.8036804 0.1070545 -0.4509208 0.8861206 -0.1070554 -0.4509189 0.8861216 -0.1954215 -0.5620718 0.8036702 -0.3153825 -0.4489117 0.8360695 -0.3340011 -0.4501768 0.8281209 -0.5018664 -0.0647763 0.8625163 0.6731516 -0.3432823 0.6549994 0.375369 -0.4616496 0.8037274 0.5290802 -0.3666331 0.7652806 -0.6351261 -0.3099389 0.7074976 -0.2763308 -0.7346482 0.6196236 -0.2688961 -0.7365332 0.6206559 -0.4707093 -0.7993911 0.373372 -0.4955915 -0.5476307 0.6741585 -0.4371829 -0.5765613 0.6902524 -0.7275909 -0.2789816 0.6267223 0.6946297 0.00473541 0.719352 0.7303734 -0.006094932 0.6830209 -1.66085e-5 -0.05653405 0.9984008 -0.1195588 -0.08051151 0.9895573 -0.2431238 -0.03152507 0.9694829 -0.3518372 -0.07937836 0.9326896 -0.4711073 -0.05666488 0.880254 -0.7303768 0.002067029 0.6830414 -0.7413413 0.007032275 0.6710914 0.3813788 -0.6829662 0.6229828 -0.1229404 -0.8053502 0.579911 0.3693046 -0.7789613 0.5067873 0.5033299 -0.7778624 0.3762835 0.5237146 -0.5266814 0.6695744 0.5203624 -0.5283064 0.6709066 0.7185439 -0.2778205 0.6375818 0.718279 -0.3733571 0.5870944 0.7295628 -0.2962683 0.6164117 0.2999265 -0.8867561 0.3517212 0.6172964 -0.6169246 0.4882102 0.5006275 -0.7538118 0.4256053 0.2531336 -0.9318027 0.260129 0.07409596 -0.9954726 0.05953264 0.1863412 -0.8967377 0.4014205 0.01704108 -0.9996064 -0.02228999 -0.02202343 -0.9996011 -0.0176872 -0.2129934 -0.9589563 0.1871813 -0.2852635 -0.9011706 0.3263683 -0.5388355 -0.7187525 0.439376 -0.4834186 -0.7671775 0.4215983 -0.6078405 -0.6282277 0.4856542 -0.7127113 -0.3700712 0.5958943 -0.7367714 -0.3183754 0.596494 -0.2355777 -0.9105976 0.3395808 0.001893043 -0.9998987 0.01411026 -0.7705341 0.524855 0.361669 0.8232404 0.01104104 0.5675857 0.775734 -0.00804162 0.6310089 0.7903486 -0.04252731 0.6111796 0.6735427 0.03208643 0.7384517 0.7767007 -0.006259262 0.6298387 0.7914705 0.02728754 0.6105979 + + + + + + + + + + 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 + + + + + + + + + + + + + + + + +

2 0 0 6 0 1 7 0 2 4 1 3 0 1 4 3 1 5 7 2 6 6 2 7 3 2 8 3 3 9 0 3 10 5 3 11 10 4 12 8 4 13 0 4 14 8 5 15 5 5 16 0 5 17 8 6 18 9 6 19 5 6 20 14 7 21 2 7 22 11 7 23 11 8 24 7 8 25 3 8 26 11 9 27 3 9 28 12 9 29 3 10 30 9 10 31 12 10 32 9 11 33 3 11 34 5 11 35 14 12 36 13 12 37 2 12 38 2 13 39 7 13 40 11 13 41 29 14 42 15 14 43 22 14 44 18 15 45 26 15 46 28 15 47 19 16 48 23 16 49 17 16 50 23 17 51 26 17 52 17 17 53 26 18 54 20 18 55 17 18 56 26 19 57 16 19 58 20 19 59 16 20 60 26 20 61 18 20 62 19 21 63 27 21 64 23 21 65 19 22 66 21 22 67 27 22 68 21 23 69 25 23 70 27 23 71 29 24 72 30 24 73 15 24 74 29 25 75 22 25 76 48 25 77 50 26 78 29 26 79 48 26 80 50 27 81 48 27 82 33 27 83 50 28 84 33 28 85 49 28 86 33 29 87 39 29 88 49 29 89 40 30 90 33 30 91 48 30 92 34 31 93 40 31 94 48 31 95 36 32 96 34 32 97 48 32 98 32 33 99 36 33 100 48 33 101 35 34 102 32 34 103 48 34 104 31 35 105 35 35 106 48 35 107 37 36 108 31 36 109 48 36 110 38 37 111 37 37 112 48 37 113 43 38 114 41 38 115 38 38 116 46 39 117 43 39 118 38 39 119 44 40 120 10 40 121 0 40 122 4 41 123 44 41 124 0 41 125 24 42 126 45 42 127 46 42 128 21 43 129 47 43 130 25 43 131 47 44 132 24 44 133 25 44 134 47 45 135 45 45 136 24 45 137 3 46 138 6 46 139 4 46 140 1 47 141 51 47 142 2 47 143 2 48 144 51 48 145 6 48 146 51 49 147 49 49 148 6 49 149 51 50 150 50 50 151 49 50 152 1 51 153 2 51 154 52 51 155 49 52 156 4 52 157 6 52 158 50 53 159 1 53 160 29 53 161 1 54 162 50 54 163 51 54 164 30 55 165 29 55 166 1 55 167 54 56 168 56 56 169 55 56 170 53 57 171 8 57 172 10 57 173 53 58 174 10 58 175 44 58 176 77 59 177 283 59 178 91 59 179 283 60 180 77 60 181 281 60 182 281 61 183 77 61 184 279 61 185 281 62 186 279 62 187 30 62 188 30 63 189 279 63 190 61 63 191 197 64 192 190 64 193 181 64 194 60 65 195 59 65 196 61 65 197 60 66 198 58 66 199 59 66 200 217 67 201 282 67 202 59 67 203 58 68 204 217 68 205 59 68 206 234 69 207 280 69 208 277 69 209 282 70 210 267 70 211 284 70 212 165 71 213 282 71 214 217 71 215 237 72 216 227 72 217 274 72 218 274 73 219 227 73 220 277 73 221 277 74 222 227 74 223 254 74 224 280 75 225 234 75 226 58 75 227 270 76 228 289 76 229 288 76 230 288 77 231 241 77 232 270 77 233 267 78 234 241 78 235 288 78 236 267 79 237 288 79 238 284 79 239 222 80 240 92 80 241 242 80 242 96 81 243 106 81 244 97 81 245 95 82 246 279 82 247 77 82 248 79 83 249 279 83 250 95 83 251 69 84 252 279 84 253 79 84 254 65 85 255 279 85 256 69 85 257 80 86 258 279 86 259 65 86 260 64 87 261 279 87 262 80 87 263 85 88 264 279 88 265 64 88 266 89 89 267 279 89 268 85 89 269 82 90 270 86 90 271 245 90 272 103 91 273 86 91 274 82 91 275 103 92 276 83 92 277 86 92 278 106 93 279 83 93 280 103 93 281 104 94 282 106 94 283 103 94 284 106 95 285 107 95 286 97 95 287 106 96 288 104 96 289 107 96 290 222 97 291 252 97 292 100 97 293 107 98 294 252 98 295 97 98 296 101 99 297 105 99 298 94 99 299 100 100 300 94 100 301 222 100 302 100 101 303 101 101 304 94 101 305 102 102 306 70 102 307 101 102 308 102 103 309 67 103 310 70 103 311 102 104 312 101 104 313 100 104 314 102 105 315 178 105 316 67 105 317 91 106 318 178 106 319 102 106 320 67 107 321 178 107 322 230 107 323 73 108 324 67 108 325 230 108 326 70 109 327 67 109 328 73 109 329 70 110 330 105 110 331 101 110 332 70 111 333 93 111 334 105 111 335 70 112 336 75 112 337 93 112 338 73 113 339 75 113 340 70 113 341 85 114 342 78 114 343 82 114 344 85 115 345 82 115 346 89 115 347 80 116 348 62 116 349 64 116 350 80 117 351 76 117 352 62 117 353 65 118 354 76 118 355 80 118 356 65 119 357 81 119 358 76 119 359 69 120 360 81 120 361 65 120 362 77 121 363 71 121 364 95 121 365 91 122 366 71 122 367 77 122 368 63 123 369 245 123 370 86 123 371 57 124 372 86 124 373 83 124 374 57 125 375 63 125 376 86 125 377 96 126 378 83 126 379 106 126 380 88 127 381 83 127 382 96 127 383 88 128 384 57 128 385 83 128 386 245 129 387 89 129 388 82 129 389 272 130 390 89 130 391 245 130 392 82 131 393 78 131 394 103 131 395 141 132 396 230 132 397 178 132 398 141 133 399 73 133 400 230 133 401 102 134 402 71 134 403 91 134 404 78 135 405 64 135 406 62 135 407 62 136 408 87 136 409 78 136 410 76 137 411 87 137 412 62 137 413 76 138 414 84 138 415 87 138 416 81 139 417 84 139 418 76 139 419 68 140 420 84 140 421 81 140 422 68 141 423 72 141 424 84 141 425 74 142 426 72 142 427 68 142 428 74 143 429 71 143 430 72 143 431 68 144 432 69 144 433 79 144 434 81 145 435 69 145 436 68 145 437 71 146 438 79 146 439 95 146 440 74 147 441 79 147 442 71 147 443 68 148 444 79 148 445 74 148 446 63 149 447 119 149 448 245 149 449 57 150 450 119 150 451 63 150 452 98 151 453 247 151 454 99 151 455 92 152 456 93 152 457 99 152 458 93 153 459 98 153 460 99 153 461 98 154 462 93 154 463 75 154 464 94 155 465 92 155 466 222 155 467 94 156 468 105 156 469 92 156 470 88 157 471 97 157 472 154 157 473 88 158 474 96 158 475 97 158 476 88 159 477 207 159 478 172 159 479 154 160 480 207 160 481 88 160 482 93 161 483 92 161 484 105 161 485 85 162 486 64 162 487 78 162 488 239 163 489 226 163 490 137 163 491 239 164 492 137 164 493 171 164 494 171 165 495 185 165 496 239 165 497 247 166 498 155 166 499 99 166 500 155 167 501 242 167 502 99 167 503 97 168 504 252 168 505 260 168 506 242 169 507 252 169 508 222 169 509 260 170 510 252 170 511 242 170 512 212 171 513 236 171 514 132 171 515 225 172 516 235 172 517 130 172 518 225 173 519 213 173 520 235 173 521 192 174 522 213 174 523 225 174 524 160 175 525 213 175 526 192 175 527 160 176 528 205 176 529 213 176 530 212 177 531 201 177 532 134 177 533 267 178 534 170 178 535 221 178 536 165 179 537 217 179 538 242 179 539 165 180 540 267 180 541 282 180 542 170 181 543 267 181 544 165 181 545 242 182 546 116 182 547 117 182 548 116 182 549 242 182 550 264 182 551 264 183 552 131 183 553 116 183 554 131 184 555 264 184 556 263 184 557 242 185 558 155 185 559 264 185 560 255 186 561 234 186 562 159 186 563 234 187 564 255 187 565 260 187 566 260 188 567 217 188 568 234 188 569 242 189 570 217 189 571 260 189 572 242 190 573 117 190 574 165 190 575 159 191 576 180 191 577 189 191 578 234 192 579 180 192 580 159 192 581 159 193 582 206 193 583 156 193 584 189 194 585 206 194 586 159 194 587 159 195 588 145 195 589 228 195 590 156 196 591 145 196 592 159 196 593 277 197 594 254 197 595 180 197 596 180 198 597 234 198 598 277 198 599 180 199 600 254 199 601 236 199 602 254 200 603 132 200 604 236 200 605 242 201 606 92 201 607 99 201 608 213 182 609 205 182 610 235 182 611 205 202 612 246 202 613 235 202 614 134 203 615 236 203 616 212 203 617 212 204 618 124 204 619 201 204 620 266 205 621 124 205 622 212 205 623 58 206 624 234 206 625 217 206 626 108 207 627 224 207 628 139 207 629 108 208 630 139 208 631 201 208 632 108 209 633 201 209 634 124 209 635 138 210 636 113 210 637 167 210 638 224 211 639 113 211 640 138 211 641 224 212 642 136 212 643 113 212 644 224 213 645 108 213 646 136 213 647 159 214 648 250 214 649 172 214 650 159 215 651 123 215 652 250 215 653 172 216 654 255 216 655 159 216 656 130 217 657 235 217 658 129 217 659 129 218 660 235 218 661 233 218 662 233 219 663 166 219 664 129 219 665 221 220 666 220 220 667 241 220 668 188 221 669 220 221 670 221 221 671 180 222 672 134 222 673 201 222 674 236 223 675 134 223 676 180 223 677 201 224 678 139 224 679 180 224 680 254 225 681 251 225 682 266 225 683 254 226 684 227 226 685 251 226 686 170 227 687 165 227 688 265 227 689 265 228 690 169 228 691 193 228 692 165 229 693 169 229 694 265 229 695 172 230 696 250 230 697 150 230 698 250 231 699 123 231 700 150 231 701 191 232 702 226 232 703 146 232 704 191 233 705 137 233 706 226 233 707 109 234 708 137 234 709 191 234 710 143 235 711 137 235 712 109 235 713 143 236 714 171 236 715 137 236 716 174 237 717 171 237 718 143 237 719 174 238 720 185 238 721 171 238 722 220 239 723 240 239 724 246 239 725 124 240 726 266 240 727 239 240 728 168 241 729 264 241 730 155 241 731 152 242 732 264 242 733 168 242 734 132 243 735 266 243 736 212 243 737 132 244 738 254 244 739 266 244 740 260 245 741 154 245 742 97 245 743 152 246 744 168 246 745 163 246 746 220 247 747 200 247 748 241 247 749 220 248 750 160 248 751 200 248 752 246 249 753 160 249 754 220 249 755 160 250 756 246 250 757 205 250 758 266 251 759 226 251 760 239 251 761 266 252 762 146 252 763 226 252 764 266 253 765 258 253 766 146 253 767 260 254 768 207 254 769 154 254 770 260 255 771 255 255 772 207 255 773 185 256 774 124 256 775 239 256 776 108 257 777 124 257 778 185 257 779 108 258 780 185 258 781 136 258 782 136 259 783 185 259 784 174 259 785 174 260 786 229 260 787 136 260 788 246 261 789 233 261 790 235 261 791 240 262 792 233 262 793 246 262 794 167 263 795 157 263 796 138 263 797 175 264 798 157 264 799 243 264 800 138 265 801 157 265 802 175 265 803 228 266 804 243 266 805 159 266 806 243 267 807 228 267 808 175 267 809 159 268 810 243 268 811 123 268 812 253 269 813 244 269 814 248 269 815 248 270 816 203 270 817 253 270 818 244 271 819 253 271 820 263 271 821 152 272 822 263 272 823 264 272 824 215 273 825 263 273 826 152 273 827 244 274 828 263 274 829 215 274 830 240 182 831 193 182 832 233 182 833 193 275 834 126 275 835 166 275 836 193 276 837 169 276 838 126 276 839 193 277 840 166 277 841 233 277 842 203 278 843 166 278 844 126 278 845 203 182 846 248 182 847 166 182 848 265 279 849 221 279 850 170 279 851 265 280 852 188 280 853 221 280 854 188 281 855 265 281 856 193 281 857 220 282 858 193 282 859 240 282 860 188 283 861 193 283 862 220 283 863 215 284 864 133 284 865 151 284 866 215 285 867 142 285 868 133 285 869 120 286 870 142 286 871 118 286 872 120 287 873 133 287 874 142 287 875 141 288 876 133 288 877 120 288 878 141 289 879 151 289 880 133 289 881 114 290 882 151 290 883 141 290 884 196 291 885 231 291 886 218 291 887 157 292 888 231 292 889 196 292 890 128 293 891 115 293 892 196 293 893 256 294 894 115 294 895 128 294 896 256 295 897 176 295 898 115 295 899 128 296 900 196 296 901 218 296 902 128 297 903 229 297 904 256 297 905 218 298 906 229 298 907 128 298 908 272 299 909 190 299 910 211 299 911 158 300 912 195 300 913 232 300 914 211 301 915 197 301 916 195 301 917 211 302 918 190 302 919 197 302 920 158 303 921 258 303 922 237 303 923 158 304 924 232 304 925 258 304 926 195 305 927 219 305 928 232 305 929 195 306 930 273 306 931 211 306 932 158 307 933 273 307 934 195 307 935 197 308 936 219 308 937 195 308 938 197 309 939 181 309 940 219 309 941 259 310 942 181 310 943 190 310 944 140 311 945 199 311 946 208 311 947 140 312 948 182 312 949 199 312 950 182 313 951 109 313 952 191 313 953 182 314 954 143 314 955 109 314 956 140 315 957 143 315 958 182 315 959 140 316 960 174 316 961 143 316 962 208 317 963 174 317 964 140 317 965 121 318 966 209 318 967 111 318 968 161 319 969 209 319 970 121 319 971 161 320 972 129 320 973 209 320 974 130 321 975 129 321 976 161 321 977 113 322 978 231 322 979 167 322 980 136 323 981 231 323 982 113 323 983 136 324 984 218 324 985 231 324 986 136 325 987 229 325 988 218 325 989 231 326 990 157 326 991 167 326 992 110 327 993 225 327 994 130 327 995 192 328 996 112 328 997 160 328 998 192 329 999 149 329 1000 112 329 1001 225 330 1002 149 330 1003 192 330 1004 110 331 1005 149 331 1006 225 331 1007 110 332 1008 173 332 1009 149 332 1010 161 333 1011 173 333 1012 110 333 1013 161 334 1014 121 334 1015 173 334 1016 130 335 1017 161 335 1018 110 335 1019 153 336 1020 114 336 1021 111 336 1022 249 337 1023 114 337 1024 153 337 1025 257 338 1026 114 338 1027 249 338 1028 257 339 1029 151 339 1030 114 339 1031 244 340 1032 151 340 1033 257 340 1034 244 341 1035 215 341 1036 151 341 1037 152 342 1038 142 342 1039 215 342 1040 118 343 1041 142 343 1042 152 343 1043 270 344 1044 204 344 1045 271 344 1046 200 345 1047 204 345 1048 270 345 1049 214 346 1050 204 346 1051 200 346 1052 216 347 1053 204 347 1054 214 347 1055 216 348 1056 194 348 1057 204 348 1058 184 349 1059 194 349 1060 216 349 1061 184 350 1062 210 350 1063 194 350 1064 179 351 1065 238 351 1066 210 351 1067 210 352 1068 144 352 1069 194 352 1070 210 353 1071 238 353 1072 144 353 1073 194 354 1074 271 354 1075 204 354 1076 194 355 1077 144 355 1078 271 355 1079 144 356 1080 268 356 1081 271 356 1082 144 357 1083 269 357 1084 268 357 1085 210 358 1086 184 358 1087 179 358 1088 200 359 1089 270 359 1090 241 359 1091 208 360 1092 259 360 1093 176 360 1094 259 361 1095 127 361 1096 176 361 1097 190 362 1098 127 362 1099 259 362 1100 245 363 1101 190 363 1102 272 363 1103 127 364 1104 190 364 1105 245 364 1106 123 365 1107 162 365 1108 164 365 1109 123 366 1110 243 366 1111 162 366 1112 183 367 1113 117 367 1114 116 367 1115 177 368 1116 117 368 1117 183 368 1118 131 369 1119 187 369 1120 135 369 1121 131 370 1122 261 370 1123 187 370 1124 263 371 1125 261 371 1126 131 371 1127 135 372 1128 116 372 1129 131 372 1130 183 373 1131 116 373 1132 135 373 1133 263 374 1134 253 374 1135 261 374 1136 189 375 1137 139 375 1138 224 375 1139 180 376 1140 139 376 1141 189 376 1142 249 377 1143 262 377 1144 257 377 1145 147 378 1146 125 378 1147 262 378 1148 209 379 1149 125 379 1150 147 379 1151 209 380 1152 129 380 1153 125 380 1154 147 381 1155 249 381 1156 153 381 1157 262 382 1158 249 382 1159 147 382 1160 147 383 1161 111 383 1162 209 383 1163 153 384 1164 111 384 1165 147 384 1166 184 385 1167 173 385 1168 121 385 1169 184 386 1170 149 386 1171 173 386 1172 216 387 1173 149 387 1174 184 387 1175 216 388 1176 112 388 1177 149 388 1178 216 389 1179 160 389 1180 112 389 1181 214 390 1182 160 390 1183 216 390 1184 200 391 1185 160 391 1186 214 391 1187 224 392 1188 202 392 1189 189 392 1190 198 393 1191 202 393 1192 224 393 1193 224 394 1194 148 394 1195 198 394 1196 138 395 1197 148 395 1198 224 395 1199 138 396 1200 186 396 1201 148 396 1202 138 397 1203 175 397 1204 186 397 1205 227 398 1206 237 398 1207 251 398 1208 251 399 1209 237 399 1210 258 399 1211 251 400 1212 258 400 1213 266 400 1214 178 401 1215 269 401 1216 238 401 1217 238 402 1218 114 402 1219 178 402 1220 179 403 1221 114 403 1222 238 403 1223 179 404 1224 121 404 1225 114 404 1226 121 405 1227 111 405 1228 114 405 1229 174 406 1230 256 406 1231 229 406 1232 208 407 1233 256 407 1234 174 407 1235 208 408 1236 176 408 1237 256 408 1238 141 409 1239 178 409 1240 114 409 1241 118 410 1242 73 410 1243 120 410 1244 120 411 1245 73 411 1246 141 411 1247 166 412 1248 125 412 1249 129 412 1250 262 413 1251 125 413 1252 166 413 1253 257 414 1254 248 414 1255 244 414 1256 262 415 1257 248 415 1258 257 415 1259 262 416 1260 166 416 1261 248 416 1262 183 417 1263 126 417 1264 177 417 1265 203 418 1266 261 418 1267 253 418 1268 203 419 1269 187 419 1270 261 419 1271 126 420 1272 187 420 1273 203 420 1274 126 421 1275 135 421 1276 187 421 1277 126 422 1278 183 422 1279 135 422 1280 177 423 1281 165 423 1282 117 423 1283 245 424 1284 119 424 1285 127 424 1286 119 425 1287 57 425 1288 223 425 1289 57 426 1290 164 426 1291 223 426 1292 199 427 1293 259 427 1294 208 427 1295 199 428 1296 181 428 1297 259 428 1298 182 429 1299 181 429 1300 199 429 1301 182 430 1302 219 430 1303 181 430 1304 191 431 1305 219 431 1306 182 431 1307 191 432 1308 232 432 1309 219 432 1310 146 433 1311 232 433 1312 191 433 1313 146 434 1314 258 434 1315 232 434 1316 223 435 1317 243 435 1318 119 435 1319 223 436 1320 162 436 1321 243 436 1322 164 437 1323 162 437 1324 223 437 1325 168 438 1326 155 438 1327 122 438 1328 155 439 1329 247 439 1330 122 439 1331 247 440 1332 163 440 1333 168 440 1334 168 441 1335 122 441 1336 247 441 1337 255 442 1338 172 442 1339 207 442 1340 88 443 1341 172 443 1342 150 443 1343 202 444 1344 206 444 1345 189 444 1346 198 445 1347 206 445 1348 202 445 1349 198 446 1350 156 446 1351 206 446 1352 148 447 1353 156 447 1354 198 447 1355 148 448 1356 145 448 1357 156 448 1358 186 449 1359 145 449 1360 148 449 1361 186 450 1362 228 450 1363 145 450 1364 228 451 1365 186 451 1366 175 451 1367 126 452 1368 165 452 1369 177 452 1370 169 453 1371 165 453 1372 126 453 1373 127 454 1374 115 454 1375 176 454 1376 119 455 1377 115 455 1378 127 455 1379 119 456 1380 196 456 1381 115 456 1382 119 457 1383 157 457 1384 196 457 1385 243 458 1386 157 458 1387 119 458 1388 238 459 1389 269 459 1390 144 459 1391 121 460 1392 179 460 1393 184 460 1394 221 461 1395 241 461 1396 267 461 1397 271 462 1398 289 462 1399 270 462 1400 271 463 1401 286 463 1402 289 463 1403 268 464 1404 286 464 1405 271 464 1406 269 465 1407 286 465 1408 268 465 1409 269 466 1410 285 466 1411 286 466 1412 275 467 1413 272 467 1414 211 467 1415 237 468 1416 274 468 1417 278 468 1418 237 469 1419 278 469 1420 158 469 1421 158 470 1422 278 470 1423 276 470 1424 158 471 1425 276 471 1426 273 471 1427 273 472 1428 276 472 1429 275 472 1430 273 473 1431 275 473 1432 211 473 1433 289 474 1434 286 474 1435 288 474 1436 284 475 1437 287 475 1438 52 475 1439 284 476 1440 52 476 1441 282 476 1442 286 477 1443 285 477 1444 288 477 1445 288 478 1446 285 478 1447 287 478 1448 288 479 1449 287 479 1450 284 479 1451 15 480 1452 61 480 1453 59 480 1454 283 481 1455 281 481 1456 287 481 1457 281 482 1458 52 482 1459 287 482 1460 52 483 1461 2 483 1462 282 483 1463 287 484 1464 285 484 1465 283 484 1466 59 485 1467 282 485 1468 2 485 1469 15 486 1470 30 486 1471 61 486 1472 52 487 1473 281 487 1474 30 487 1475 30 488 1476 1 488 1477 52 488 1478 2 489 1479 290 489 1480 59 489 1481 15 490 1482 59 490 1483 290 490 1484 291 491 1485 13 491 1486 18 491 1487 28 492 1488 291 492 1489 18 492 1490 291 493 1491 290 493 1492 13 493 1493 13 494 1494 290 494 1495 2 494 1496 22 495 1497 290 495 1498 291 495 1499 22 496 1500 15 496 1501 290 496 1502 22 497 1503 291 497 1504 58 497 1505 28 498 1506 58 498 1507 291 498 1508 304 499 1509 58 499 1510 28 499 1511 301 500 1512 296 500 1513 298 500 1514 296 501 1515 301 501 1516 292 501 1517 22 502 1518 60 502 1519 301 502 1520 58 503 1521 304 503 1522 295 503 1523 58 504 1524 295 504 1525 280 504 1526 294 505 1527 293 505 1528 275 505 1529 277 506 1530 280 506 1531 295 506 1532 296 507 1533 295 507 1534 304 507 1535 292 508 1536 294 508 1537 296 508 1538 293 509 1539 294 509 1540 292 509 1541 22 510 1542 58 510 1543 60 510 1544 274 511 1545 277 511 1546 294 511 1547 274 512 1548 294 512 1549 275 512 1550 276 513 1551 274 513 1552 275 513 1553 277 514 1554 295 514 1555 296 514 1556 277 515 1557 296 515 1558 294 515 1559 278 516 1560 274 516 1561 276 516 1562 301 517 1563 298 517 1564 302 517 1565 298 518 1566 300 518 1567 299 518 1568 299 519 1569 302 519 1570 298 519 1571 297 520 1572 303 520 1573 24 520 1574 298 521 1575 296 521 1576 304 521 1577 300 522 1578 297 522 1579 299 522 1580 300 523 1581 303 523 1582 297 523 1583 304 524 1584 303 524 1585 300 524 1586 298 525 1587 304 525 1588 300 525 1589 23 526 1590 24 526 1591 303 526 1592 25 527 1593 24 527 1594 27 527 1595 302 528 1596 22 528 1597 301 528 1598 26 529 1599 23 529 1600 303 529 1601 23 530 1602 27 530 1603 24 530 1604 304 531 1605 26 531 1606 303 531 1607 28 532 1608 26 532 1609 304 532 1610 24 533 1611 46 533 1612 297 533 1613 297 534 1614 46 534 1615 38 534 1616 275 535 1617 293 535 1618 272 535 1619 293 536 1620 89 536 1621 272 536 1622 89 537 1623 293 537 1624 292 537 1625 89 538 1626 292 538 1627 279 538 1628 279 539 1629 292 539 1630 301 539 1631 61 540 1632 279 540 1633 301 540 1634 60 541 1635 61 541 1636 301 541 1637 38 542 1638 299 542 1639 297 542 1640 38 543 1641 48 543 1642 299 543 1643 48 544 1644 302 544 1645 299 544 1646 22 545 1647 302 545 1648 48 545 1649 118 546 1650 152 546 1651 163 546 1652 75 547 1653 118 547 1654 163 547 1655 75 548 1656 73 548 1657 118 548 1658 123 549 1659 164 549 1660 150 549 1661 88 550 1662 150 550 1663 164 550 1664 57 551 1665 88 551 1666 164 551 1667 90 552 1668 252 552 1669 107 552 1670 90 553 1671 100 553 1672 252 553 1673 90 554 1674 107 554 1675 104 554 1676 66 555 1677 90 555 1678 104 555 1679 66 556 1680 102 556 1681 90 556 1682 90 557 1683 102 557 1684 100 557 1685 66 558 1686 104 558 1687 87 558 1688 66 559 1689 72 559 1690 102 559 1691 87 560 1692 104 560 1693 103 560 1694 78 561 1695 87 561 1696 103 561 1697 71 562 1698 102 562 1699 72 562 1700 66 563 1701 84 563 1702 72 563 1703 66 564 1704 87 564 1705 84 564 1706 75 565 1707 163 565 1708 98 565 1709 98 566 1710 163 566 1711 247 566 1712 457 567 1713 328 567 1714 397 567 1715 472 568 1716 457 568 1717 397 568 1718 480 569 1719 467 569 1720 465 569 1721 480 570 1722 475 570 1723 467 570 1724 476 571 1725 475 571 1726 454 571 1727 470 572 1728 453 572 1729 465 572 1730 465 573 1731 453 573 1732 452 573 1733 480 574 1734 454 574 1735 475 574 1736 480 575 1737 465 575 1738 452 575 1739 463 576 1740 451 576 1741 454 576 1742 480 577 1743 463 577 1744 454 577 1745 480 578 1746 452 578 1747 463 578 1748 463 579 1749 452 579 1750 448 579 1751 463 580 1752 321 580 1753 451 580 1754 463 581 1755 448 581 1756 321 581 1757 483 582 1758 396 582 1759 464 582 1760 464 583 1761 396 583 1762 410 583 1763 436 584 1764 410 584 1765 396 584 1766 472 585 1767 377 585 1768 474 585 1769 472 586 1770 397 586 1771 377 586 1772 377 587 1773 397 587 1774 408 587 1775 348 588 1776 11 588 1777 12 588 1778 417 589 1779 362 589 1780 383 589 1781 330 590 1782 327 590 1783 402 590 1784 327 591 1785 369 591 1786 402 591 1787 327 592 1788 438 592 1789 369 592 1790 438 593 1791 441 593 1792 369 593 1793 438 594 1794 432 594 1795 441 594 1796 432 595 1797 385 595 1798 441 595 1799 392 596 1800 433 596 1801 14 596 1802 433 597 1803 384 597 1804 14 597 1805 341 598 1806 386 598 1807 378 598 1808 378 599 1809 415 599 1810 341 599 1811 378 600 1812 412 600 1813 415 600 1814 412 601 1815 403 601 1816 415 601 1817 412 602 1818 368 602 1819 403 602 1820 368 603 1821 359 603 1822 403 603 1823 368 604 1824 364 604 1825 359 604 1826 364 605 1827 374 605 1828 359 605 1829 464 606 1830 410 606 1831 389 606 1832 317 607 1833 358 607 1834 389 607 1835 393 608 1836 328 608 1837 437 608 1838 328 609 1839 393 609 1840 397 609 1841 404 610 1842 437 610 1843 328 610 1844 393 611 1845 437 611 1846 404 611 1847 396 612 1848 346 612 1849 398 612 1850 346 613 1851 330 613 1852 398 613 1853 346 614 1854 327 614 1855 330 614 1856 438 615 1857 327 615 1858 346 615 1859 414 616 1860 337 616 1861 313 616 1862 414 617 1863 373 617 1864 337 617 1865 373 618 1866 349 618 1867 337 618 1868 373 619 1869 381 619 1870 349 619 1871 381 620 1872 382 620 1873 349 620 1874 381 621 1875 367 621 1876 382 621 1877 367 622 1878 312 622 1879 382 622 1880 367 623 1881 357 623 1882 312 623 1883 483 624 1884 346 624 1885 396 624 1886 438 625 1887 346 625 1888 483 625 1889 43 626 1890 432 626 1891 438 626 1892 384 627 1893 439 627 1894 14 627 1895 433 628 1896 425 628 1897 380 628 1898 433 629 1899 376 629 1900 425 629 1901 433 630 1902 363 630 1903 376 630 1904 363 631 1905 310 631 1906 376 631 1907 363 632 1908 320 632 1909 310 632 1910 380 633 1911 384 633 1912 433 633 1913 309 634 1914 326 634 1915 395 634 1916 309 635 1917 315 635 1918 326 635 1919 315 636 1920 329 636 1921 326 636 1922 309 637 1923 395 637 1924 434 637 1925 395 638 1926 430 638 1927 434 638 1928 377 639 1929 406 639 1930 474 639 1931 406 640 1932 324 640 1933 339 640 1934 357 641 1935 316 641 1936 385 641 1937 357 642 1938 387 642 1939 316 642 1940 387 643 1941 340 643 1942 316 643 1943 417 644 1944 324 644 1945 444 644 1946 383 645 1947 324 645 1948 417 645 1949 383 646 1950 314 646 1951 324 646 1952 314 647 1953 42 647 1954 324 647 1955 42 648 1956 314 648 1957 44 648 1958 322 649 1959 305 649 1960 313 649 1961 322 650 1962 313 650 1963 19 650 1964 17 651 1965 322 651 1966 19 651 1967 422 652 1968 378 652 1969 386 652 1970 422 653 1971 412 653 1972 378 653 1973 422 654 1974 345 654 1975 412 654 1976 345 655 1977 368 655 1978 412 655 1979 368 656 1980 345 656 1981 364 656 1982 345 657 1983 374 657 1984 364 657 1985 366 658 1986 353 658 1987 400 658 1988 353 659 1989 351 659 1990 400 659 1991 351 660 1992 443 660 1993 400 660 1994 351 661 1995 411 661 1996 443 661 1997 351 662 1998 362 662 1999 411 662 2000 362 663 2001 388 663 2002 411 663 2003 362 664 2004 417 664 2005 388 664 2006 407 665 2007 413 665 2008 444 665 2009 413 666 2010 356 666 2011 444 666 2012 309 667 2013 413 667 2014 325 667 2015 413 668 2016 407 668 2017 325 668 2018 356 669 2019 434 669 2020 430 669 2021 356 670 2022 413 670 2023 434 670 2024 413 671 2025 309 671 2026 434 671 2027 325 672 2028 315 672 2029 309 672 2030 16 673 2031 374 673 2032 421 673 2033 374 674 2034 345 674 2035 421 674 2036 308 675 2037 310 675 2038 320 675 2039 380 676 2040 425 676 2041 440 676 2042 425 677 2043 428 677 2044 440 677 2045 308 678 2046 428 678 2047 310 678 2048 428 679 2049 376 679 2050 310 679 2051 428 680 2052 425 680 2053 376 680 2054 384 681 2055 380 681 2056 439 681 2057 380 682 2058 440 682 2059 439 682 2060 436 683 2061 398 683 2062 330 683 2063 436 684 2064 396 684 2065 398 684 2066 432 685 2067 43 685 2068 319 685 2069 43 686 2070 46 686 2071 319 686 2072 319 687 2073 312 687 2074 432 687 2075 312 688 2076 385 688 2077 432 688 2078 357 689 2079 385 689 2080 312 689 2081 366 690 2082 12 690 2083 9 690 2084 333 691 2085 383 691 2086 362 691 2087 314 692 2088 53 692 2089 44 692 2090 370 693 2091 8 693 2092 53 693 2093 370 694 2094 361 694 2095 8 694 2096 314 695 2097 333 695 2098 53 695 2099 333 696 2100 370 696 2101 53 696 2102 383 697 2103 333 697 2104 314 697 2105 362 698 2106 370 698 2107 333 698 2108 362 699 2109 351 699 2110 370 699 2111 351 700 2112 361 700 2113 370 700 2114 351 701 2115 353 701 2116 361 701 2117 353 702 2118 366 702 2119 361 702 2120 366 703 2121 9 703 2122 361 703 2123 9 704 2124 8 704 2125 361 704 2126 377 705 2127 408 705 2128 418 705 2129 408 706 2130 352 706 2131 418 706 2132 329 707 2133 409 707 2134 352 707 2135 329 708 2136 315 708 2137 409 708 2138 315 709 2139 324 709 2140 409 709 2141 315 710 2142 325 710 2143 324 710 2144 325 711 2145 407 711 2146 324 711 2147 407 712 2148 444 712 2149 324 712 2150 429 713 2151 445 713 2152 399 713 2153 399 714 2154 388 714 2155 417 714 2156 399 715 2157 445 715 2158 388 715 2159 445 716 2160 411 716 2161 388 716 2162 445 717 2163 344 717 2164 411 717 2165 344 718 2166 372 718 2167 411 718 2168 372 719 2169 443 719 2170 411 719 2171 372 720 2172 400 720 2173 443 720 2174 445 721 2175 429 721 2176 344 721 2177 338 722 2178 394 722 2179 402 722 2180 424 723 2181 350 723 2182 340 723 2183 424 724 2184 338 724 2185 350 724 2186 424 725 2187 442 725 2188 338 725 2189 442 726 2190 394 726 2191 338 726 2192 429 727 2193 399 727 2194 430 727 2195 399 728 2196 356 728 2197 430 728 2198 399 729 2199 417 729 2200 356 729 2201 417 730 2202 444 730 2203 356 730 2204 357 731 2205 420 731 2206 387 731 2207 420 732 2208 416 732 2209 387 732 2210 420 733 2211 381 733 2212 416 733 2213 381 734 2214 446 734 2215 416 734 2216 381 735 2217 373 735 2218 446 735 2219 420 736 2220 367 736 2221 381 736 2222 420 737 2223 357 737 2224 367 737 2225 312 738 2226 319 738 2227 382 738 2228 343 739 2229 349 739 2230 382 739 2231 343 740 2232 318 740 2233 349 740 2234 21 741 2235 318 741 2236 47 741 2237 318 742 2238 45 742 2239 47 742 2240 318 743 2241 337 743 2242 349 743 2243 21 744 2244 313 744 2245 337 744 2246 21 745 2247 19 745 2248 313 745 2249 45 746 2250 343 746 2251 319 746 2252 45 747 2253 318 747 2254 343 747 2255 318 748 2256 21 748 2257 337 748 2258 46 749 2259 45 749 2260 319 749 2261 350 750 2262 431 750 2263 340 750 2264 431 751 2265 316 751 2266 340 751 2267 431 752 2268 350 752 2269 369 752 2270 316 753 2271 441 753 2272 385 753 2273 316 754 2274 431 754 2275 441 754 2276 431 755 2277 369 755 2278 441 755 2279 402 756 2280 369 756 2281 338 756 2282 369 757 2283 350 757 2284 338 757 2285 324 758 2286 419 758 2287 409 758 2288 406 759 2289 418 759 2290 419 759 2291 406 760 2292 377 760 2293 418 760 2294 419 761 2295 324 761 2296 406 761 2297 352 762 2298 419 762 2299 418 762 2300 352 763 2301 409 763 2302 419 763 2303 375 764 2304 54 764 2305 371 764 2306 54 765 2307 55 765 2308 371 765 2309 375 766 2310 371 766 2311 306 766 2312 306 767 2313 348 767 2314 375 767 2315 306 768 2316 391 768 2317 348 768 2318 363 182 2319 395 182 2320 326 182 2321 363 182 2322 433 182 2323 395 182 2324 371 182 2325 336 182 2326 395 182 2327 371 182 2328 433 182 2329 392 182 2330 371 769 2331 395 769 2332 433 769 2333 55 182 2334 336 182 2335 371 182 2336 329 770 2337 352 770 2338 308 770 2339 352 771 2340 408 771 2341 308 771 2342 408 772 2343 307 772 2344 308 772 2345 329 773 2346 308 773 2347 320 773 2348 326 774 2349 320 774 2350 363 774 2351 320 775 2352 326 775 2353 329 775 2354 401 776 2355 436 776 2356 330 776 2357 330 777 2358 386 777 2359 341 777 2360 341 778 2361 401 778 2362 330 778 2363 422 779 2364 386 779 2365 402 779 2366 386 780 2367 330 780 2368 402 780 2369 394 781 2370 422 781 2371 402 781 2372 55 782 2373 56 782 2374 336 782 2375 56 783 2376 335 783 2377 336 783 2378 387 784 2379 424 784 2380 340 784 2381 424 785 2382 387 785 2383 379 785 2384 447 786 2385 424 786 2386 379 786 2387 447 787 2388 379 787 2389 435 787 2390 379 788 2391 332 788 2392 435 788 2393 311 789 2394 358 789 2395 317 789 2396 311 790 2397 405 790 2398 358 790 2399 305 791 2400 414 791 2401 313 791 2402 305 792 2403 342 792 2404 414 792 2405 305 793 2406 332 793 2407 342 793 2408 400 794 2409 360 794 2410 56 794 2411 56 795 2412 54 795 2413 400 795 2414 54 796 2415 366 796 2416 400 796 2417 54 797 2418 12 797 2419 366 797 2420 408 798 2421 397 798 2422 393 798 2423 311 799 2424 458 799 2425 405 799 2426 427 800 2427 305 800 2428 20 800 2429 427 801 2430 355 801 2431 305 801 2432 408 802 2433 393 802 2434 307 802 2435 393 803 2436 404 803 2437 307 803 2438 435 804 2439 332 804 2440 305 804 2441 387 805 2442 390 805 2443 379 805 2444 387 806 2445 416 806 2446 390 806 2447 416 807 2448 423 807 2449 390 807 2450 416 808 2451 446 808 2452 423 808 2453 446 809 2454 373 809 2455 423 809 2456 373 810 2457 342 810 2458 423 810 2459 373 811 2460 414 811 2461 342 811 2462 323 812 2463 410 812 2464 436 812 2465 389 813 2466 410 813 2467 323 813 2468 14 814 2469 306 814 2470 392 814 2471 306 815 2472 371 815 2473 392 815 2474 391 816 2475 306 816 2476 14 816 2477 20 817 2478 322 817 2479 17 817 2480 20 818 2481 305 818 2482 322 818 2483 365 819 2484 16 819 2485 421 819 2486 334 820 2487 16 820 2488 426 820 2489 16 821 2490 365 821 2491 426 821 2492 375 822 2493 348 822 2494 54 822 2495 348 823 2496 12 823 2497 54 823 2498 336 824 2499 430 824 2500 395 824 2501 430 825 2502 336 825 2503 335 825 2504 429 826 2505 430 826 2506 335 826 2507 389 827 2508 401 827 2509 317 827 2510 401 828 2511 323 828 2512 436 828 2513 401 829 2514 389 829 2515 323 829 2516 345 830 2517 424 830 2518 447 830 2519 345 831 2520 442 831 2521 424 831 2522 345 832 2523 422 832 2524 442 832 2525 422 833 2526 394 833 2527 442 833 2528 447 834 2529 435 834 2530 365 834 2531 447 835 2532 365 835 2533 421 835 2534 447 836 2535 421 836 2536 345 836 2537 305 837 2538 355 837 2539 435 837 2540 355 838 2541 365 838 2542 435 838 2543 426 839 2544 355 839 2545 334 839 2546 360 840 2547 335 840 2548 56 840 2549 354 182 2550 335 182 2551 360 182 2552 331 841 2553 456 841 2554 462 841 2555 20 842 2556 334 842 2557 427 842 2558 16 843 2559 334 843 2560 20 843 2561 403 844 2562 401 844 2563 415 844 2564 401 845 2565 341 845 2566 415 845 2567 374 846 2568 401 846 2569 359 846 2570 401 847 2571 403 847 2572 359 847 2573 18 848 2574 401 848 2575 16 848 2576 401 849 2577 374 849 2578 16 849 2579 331 182 2580 14 182 2581 439 182 2582 331 850 2583 311 850 2584 13 850 2585 311 851 2586 18 851 2587 13 851 2588 18 852 2589 311 852 2590 317 852 2591 317 853 2592 401 853 2593 18 853 2594 331 854 2595 307 854 2596 404 854 2597 428 855 2598 308 855 2599 307 855 2600 307 856 2601 440 856 2602 428 856 2603 440 182 2604 307 182 2605 331 182 2606 331 857 2607 439 857 2608 440 857 2609 391 858 2610 14 858 2611 11 858 2612 14 859 2613 331 859 2614 13 859 2615 11 860 2616 348 860 2617 391 860 2618 355 861 2619 426 861 2620 365 861 2621 400 862 2622 354 862 2623 360 862 2624 400 863 2625 372 863 2626 354 863 2627 372 864 2628 344 864 2629 354 864 2630 344 865 2631 335 865 2632 354 865 2633 344 866 2634 429 866 2635 335 866 2636 355 867 2637 427 867 2638 334 867 2639 311 868 2640 331 868 2641 321 868 2642 331 869 2643 347 869 2644 321 869 2645 458 870 2646 311 870 2647 321 870 2648 404 871 2649 456 871 2650 331 871 2651 328 872 2652 456 872 2653 404 872 2654 390 873 2655 332 873 2656 379 873 2657 332 874 2658 390 874 2659 423 874 2660 332 875 2661 423 875 2662 342 875 2663 37 876 2664 470 876 2665 31 876 2666 461 877 2667 450 877 2668 462 877 2669 405 878 2670 464 878 2671 358 878 2672 464 879 2673 389 879 2674 358 879 2675 464 880 2676 458 880 2677 459 880 2678 464 881 2679 405 881 2680 458 881 2681 460 882 2682 462 882 2683 450 882 2684 460 883 2685 347 883 2686 462 883 2687 457 884 2688 472 884 2689 461 884 2690 461 885 2691 456 885 2692 457 885 2693 462 886 2694 456 886 2695 461 886 2696 457 887 2697 456 887 2698 328 887 2699 483 888 2700 481 888 2701 438 888 2702 481 889 2703 43 889 2704 438 889 2705 478 890 2706 473 890 2707 34 890 2708 473 891 2709 476 891 2710 34 891 2711 476 892 2712 40 892 2713 34 892 2714 469 893 2715 478 893 2716 36 893 2717 478 894 2718 34 894 2719 36 894 2720 473 895 2721 475 895 2722 476 895 2723 473 896 2724 478 896 2725 475 896 2726 478 897 2727 467 897 2728 475 897 2729 478 898 2730 469 898 2731 467 898 2732 469 899 2733 471 899 2734 467 899 2735 471 900 2736 465 900 2737 467 900 2738 471 901 2739 482 901 2740 465 901 2741 482 902 2742 470 902 2743 465 902 2744 470 903 2745 482 903 2746 31 903 2747 454 904 2748 39 904 2749 476 904 2750 406 905 2751 339 905 2752 474 905 2753 324 906 2754 42 906 2755 339 906 2756 41 907 2757 453 907 2758 470 907 2759 464 908 2760 468 908 2761 483 908 2762 464 909 2763 459 909 2764 468 909 2765 459 910 2766 449 910 2767 468 910 2768 483 911 2769 466 911 2770 481 911 2771 483 912 2772 468 912 2773 466 912 2774 481 913 2775 466 913 2776 43 913 2777 39 914 2778 33 914 2779 476 914 2780 33 915 2781 40 915 2782 476 915 2783 36 916 2784 32 916 2785 469 916 2786 32 917 2787 471 917 2788 469 917 2789 32 918 2790 35 918 2791 471 918 2792 35 919 2793 482 919 2794 471 919 2795 35 920 2796 31 920 2797 482 920 2798 37 921 2799 38 921 2800 41 921 2801 37 922 2802 41 922 2803 470 922 2804 474 923 2805 477 923 2806 472 923 2807 477 924 2808 461 924 2809 472 924 2810 477 925 2811 450 925 2812 461 925 2813 477 926 2814 455 926 2815 450 926 2816 477 927 2817 474 927 2818 479 927 2819 474 928 2820 339 928 2821 479 928 2822 479 929 2823 339 929 2824 42 929 2825 39 930 2826 454 930 2827 42 930 2828 454 931 2829 479 931 2830 42 931 2831 454 932 2832 451 932 2833 455 932 2834 454 933 2835 477 933 2836 479 933 2837 454 934 2838 455 934 2839 477 934 2840 451 935 2841 460 935 2842 455 935 2843 451 936 2844 347 936 2845 460 936 2846 455 937 2847 460 937 2848 450 937 2849 448 938 2850 458 938 2851 321 938 2852 347 939 2853 451 939 2854 321 939 2855 449 940 2856 448 940 2857 452 940 2858 449 941 2859 458 941 2860 448 941 2861 452 942 2862 453 942 2863 449 942 2864 449 943 2865 453 943 2866 468 943 2867 453 944 2868 466 944 2869 468 944 2870 453 945 2871 41 945 2872 466 945 2873 41 946 2874 43 946 2875 466 946 2876 459 947 2877 458 947 2878 449 947 2879 347 948 2880 331 948 2881 462 948 2882 343 949 2883 382 949 2884 319 949 2885 4 950 2886 49 950 2887 44 950 2888 42 951 2889 44 951 2890 49 951 2891 39 952 2892 42 952 2893 49 952 2894 269 953 2895 283 953 2896 285 953 2897 178 954 2898 283 954 2899 269 954 2900 91 955 2901 283 955 2902 178 955 2903

+
+
+
+ + + + 3.15658 67.48139 15.1406 38.18585 55.74057 15.1406 43.16133 51.98325 15.1406 -38.10755 55.74084 15.1406 -32.80664 59.02303 15.1406 -43.08306 51.98356 15.1406 -27.22552 61.8021 15.1406 27.30387 61.80191 15.1406 21.49008 64.05413 15.1406 9.364742 66.90607 15.1406 -9.28636 66.90615 15.1406 -3.07818 67.48143 15.1406 -15.41501 65.76057 15.1406 -21.41171 64.05429 15.1406 15.49339 65.76045 15.1406 47.7831 47.69076 15.1406 67.48139 -3.15657 15.1406 55.74057 -38.18585 15.1406 51.98325 -43.16133 15.1406 55.74084 38.10755 15.1406 59.02303 32.80664 15.1406 59.02279 -32.88496 15.1406 51.98356 43.08307 15.1406 61.8021 27.22553 15.1406 61.80191 -27.30387 15.1406 64.05413 -21.49008 15.1406 66.90607 -9.364742 15.1406 66.90615 9.28636 15.1406 67.48143 3.07819 15.1406 65.76057 15.41502 15.1406 64.05429 21.41172 15.1406 65.76045 -15.49339 15.1406 47.69075 -47.78311 15.1406 -3.15659 -67.48139 15.1406 -38.18586 -55.74056 15.1406 -43.16134 -51.98324 15.1406 38.10754 -55.74085 15.1406 32.80663 -59.02303 15.1406 -32.88497 -59.02278 15.1406 43.08305 -51.98357 15.1406 27.22552 -61.80211 15.1406 -27.30388 -61.8019 15.1406 -21.49009 -64.05413 15.1406 -9.36475 -66.90607 15.1406 9.286352 -66.90615 15.1406 3.07817 -67.48143 15.1406 15.415 -65.76057 15.1406 21.41171 -64.05429 15.1406 -15.4934 -65.76045 15.1406 -47.76879 -47.78297 15.1406 -67.48139 3.15658 15.1406 -55.74057 38.18586 15.1406 -51.98325 43.16134 15.1406 -55.74085 -38.10754 15.1406 -59.02303 -32.80663 15.1406 -59.02279 32.88497 15.1406 -51.98357 -43.08306 15.1406 -61.8021 -27.22552 15.1406 -61.8019 27.30388 15.1406 -64.05413 21.49009 15.1406 -66.90607 9.36475 15.1406 -66.90615 -9.286352 15.1406 -67.48143 -3.07818 15.1406 -65.76057 -15.41501 15.1406 -64.05429 -21.41171 15.1406 -65.76045 15.49339 15.1406 -47.78297 47.76878 15.1406 29.88855 -2.94626 0.1406 -66.19735 -12.94628 0.1406 -29.81065 -2.94627 0.1406 -26.99805 -12.94628 0.1406 -62.80806 24.68092 0.1406 -59.55455 -31.64598 0.1406 -29.94435 1.05372 0.1406 25.07615 16.58062 10.1406 19.66905 -64.52888 0.1406 48.37674 47.16753 0.1406 19.94364 64.55223 0.1406 -52.20975 -42.68178 0.1406 -67.45365 -0.94628 0.1406 -24.99785 16.58122 10.1406 64.67866 -19.38757 0.1406 -64.60076 -19.38758 0.1406 27.90535 11.16503 0.1406 -29.54145 5.05372 0.1406 5.20453 42.74233 0.1406 -47.76075 -47.60588 0.1406 -10.21735 41.81262 0.1406 -29.84025 -2.63611 10.1406 -29.13205 7.05731 10.1406 15.23755 40.27813 0.1406 26.26944 62.24863 0.1406 29.88855 3.05372 0.1406 13.41974 66.21413 0.1406 28.92445 8.154972 0.1406 43.44324 51.74813 0.1406 27.94955 -10.94626 0.1406 -37.52395 -56.02908 0.1406 -29.13296 -6.94627 0.1406 60.12025 30.81873 0.1406 0.0389499 43.05372 0.1406 67.35356 -4.94628 0.1406 0.03898996 -29.94628 0.1406 -48.29885 47.16752 0.1406 65.02655 18.29823 0.1406 56.75694 36.65043 0.1406 9.953142 -28.26076 0.1406 -3.32206 -29.75738 0.1406 -27.41255 -12.04648 10.1406 67.47224 3.05372 0.1406 -23.42537 -18.63925 0.1406 56.23166 -37.34457 0.1406 -67.27565 5.05372 0.1406 26.53895 -14.00867 10.1406 -67.09716 -6.94627 0.1406 -0.30649 5.53084 10.5439 62.45715 -25.64087 0.1406 31.91315 -59.44657 0.1406 -52.75146 42.11822 0.1406 0.03893995 67.55373 0.1406 -31.83525 -59.44658 0.1406 29.21085 -6.94627 0.1406 -26.49595 14.05002 0.1406 -32.25645 59.32642 0.1406 -43.36536 51.74812 0.1406 26.57375 14.05033 0.1406 23.16535 19.09483 10.1406 -42.84965 -52.06938 0.1406 66.27526 -12.94627 0.1406 13.23215 -66.14438 0.1406 -25.94143 -14.94691 10.1406 6.76282 67.21804 0.1406 -56.67905 36.65042 0.1406 -64.94865 18.29822 0.1406 -22.95787 19.3189 0.1406 23.03557 19.3191 0.1406 0.0389499 25.24342 10.1406 62.88595 24.68093 0.1406 3.15977 43.10341 10.13999 -4.88601 -29.49477 10.1406 3.40005 -29.75737 0.1406 16.39395 39.49302 0.1406 52.28765 -42.68177 0.1406 -56.15375 -37.34458 0.1406 14.27375 30.47312 10.1406 0.0389499 -67.44628 0.1406 47.83865 -47.60587 0.1406 -26.79235 13.47312 10.1406 -26.19156 62.24862 0.1406 28.09124 10.56283 10.1406 20.13022 -22.225 10.1406 6.66763 -67.11997 0.1406 14.06305 29.80373 0.1406 -62.37925 -25.64088 0.1406 -38.00016 55.81462 0.1406 26.87055 13.47253 10.1406 32.79684 59.07212 15.1406 37.60185 -56.02907 0.1406 -6.58973 -67.11997 0.1406 28.67294 -8.89598 10.1406 -9.25984 42.20282 10.14001 -5.12663 42.74233 0.1406 1.83378 -29.89258 10.1406 15.78844 40.00233 10.14021 16.00825 -25.34277 0.1406 -19.86576 64.55223 0.1406 -6.68494 67.21804 0.1406 -13.98546 29.80534 0.1406 -66.44275 11.73412 0.1406 -60.04235 30.81872 0.1406 59.63245 -31.64597 0.1406 -28.84655 8.154782 0.1406 -25.83825 -62.28908 0.1406 -14.08326 27.71662 0.1406 21.34193 21.17674 10.1406 14.00565 28.40123 0.1406 24.72693 -16.9904 10.1406 17.06925 38.2692 0.1406 -17.09755 37.57352 0.1406 -8.48113 -28.71097 10.1406 -18.67477 -23.39396 0.1406 32.33434 59.32643 0.1406 -17.05125 37.03053 10.14291 -14.19585 30.47311 10.1406 38.07804 55.81463 0.1406 13.97235 29.10572 10.1406 29.09395 7.52404 10.1406 -29.37345 -5.85473 10.1406 21.26152 -21.1501 0.1406 -3.08271 43.10331 10.13999 -28.01435 10.56122 10.1406 29.97205 2.05655 10.1406 -28.56105 -9.00385 10.1406 4.49238 -29.52047 10.25291 52.82935 42.11823 0.1406 -6.64069 -29.19318 0.1406 16.89603 36.20391 10.14 30.02915 -0.7147 10.1406 -13.34186 66.21413 0.1406 -19.59114 -64.52888 0.1406 42.92755 -52.06937 0.1406 10.29525 41.81262 0.1406 25.44953 -15.8931 0.1406 -13.15425 -66.14438 0.1406 -17.22932 -24.47799 10.1406 -20.79073 21.64364 0.1406 -1.75515 -29.89258 10.1406 -22.10432 -20.1868 10.1406 -16.81815 36.20392 10.14292 -27.82755 11.16482 0.1406 66.52066 11.73413 0.1406 9.33692 42.20303 10.14001 17.17624 37.39723 10.14021 14.43386 27.07011 0.1406 -15.21455 40.37392 10.14 -22.84564 19.45203 10.1406 29.37685 -6.21435 10.1406 14.45012 -26.25819 10.1406 14.16115 27.71701 10.1406 -29.71885 3.85807 10.1406 -29.95585 0.61422 10.1406 7.99297 -28.87258 10.1406 -16.72595 38.92103 0.1406 -16.38056 39.54288 10.13363 -12.98475 -26.97188 0.1406 -17.01304 38.32173 10.14054 16.83693 39.01018 10.13958 25.91615 -62.28907 0.1406 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.04916781 -0.9987773 0.005146324 -0.1469879 -0.9890517 -0.01308947 -0.1837452 -0.9829677 -0.003493785 -0.2434051 -0.9698358 -0.01313441 -0.2736766 -0.9618126 -0.004205524 -0.337469 -0.9412479 -0.01293218 -0.3612312 -0.9324629 -0.005010128 -0.4282761 -0.9035615 -0.01249933 -0.4457399 -0.8951432 -0.005902945 -0.5149333 -0.8571488 -0.01181811 -0.5264254 -0.8501935 -0.006875932 -0.5966258 -0.8024457 -0.01089286 -0.6725513 -0.7399947 -0.009096682 -0.7444596 -0.6676163 -0.008280873 -0.7419795 -0.6703886 -0.006745934 -0.7980152 -0.6026235 -0.004088521 -0.8042136 -0.5942854 -0.008090734 -0.8502129 -0.5264284 -0.003372848 -0.8586741 -0.5124389 -0.009223997 -0.89516 -0.4457365 -0.002769887 -0.9048432 -0.4256244 -0.01014858 -0.9324749 -0.3612278 -0.0022825 -0.9422483 -0.3347398 -0.01084285 -0.9618215 -0.2736712 -0.001889407 -0.9705653 -0.2405717 -0.01133197 -0.9829737 -0.1837394 -0.001617133 -0.09225469 -0.9954928 -0.02198249 -0.988886 -0.1483018 -0.01054334 -0.9981868 -0.05931073 -0.01027768 -0.9957328 -0.09226769 -0.001714885 -0.9995107 0.02965128 -0.009959101 -0.9999984 7.83158e-6 -0.001851022 -0.04985654 0.9986411 0.01517665 6.11492e-6 0.9998459 -0.01755702 -0.1490958 0.9886499 0.01848965 -0.09224909 0.9955148 -0.02098661 -0.2467961 0.968817 0.02202945 -0.1836844 0.982676 -0.02465862 -0.4340626 0.9008774 -0.003102719 -0.4457374 0.895162 0.001756191 -0.5216395 0.8531641 -0.001877188 -0.5264329 0.8502166 4.13116e-4 -0.6040424 0.7969521 -4.0426e-4 -0.6026287 0.7980208 -0.001184463 -0.6804111 0.7328296 0.001302778 -0.6676228 0.744468 -0.006880342 -0.7500339 0.6613992 -7.16275e-4 -0.7389752 0.6736725 -0.009002506 -0.8121829 0.5834022 0.001024544 -0.7979614 0.6025939 -0.01175856 -0.8662556 0.4995918 0.003058016 -0.8501212 0.5263813 -0.01472598 -0.9117024 0.4108163 0.005379021 -0.8950168 0.4456734 -0.01789695 -0.9480707 0.3179596 0.00799483 -0.9322645 0.3611528 -0.02125549 -0.975002 0.2219281 0.01091939 -0.9615253 0.2735921 -0.02483075 -0.9922178 0.1237106 0.01412945 0.04985862 0.9986827 0.01212102 0.1491193 0.9888051 -0.005301773 0.1837445 0.9829646 0.004329442 0.2468531 0.9690411 -0.004817008 0.2736773 0.9618144 0.003723263 0.3421748 0.9396275 -0.004074275 0.3612332 0.9324712 0.002859115 0.4340624 0.9008775 -0.003104209 0.4450342 0.8955124 0.001460731 0.5216401 0.8531641 -0.001619756 0.5258399 0.8505836 4.20024e-4 0.6040421 0.7969524 -4.06167e-4 0.6026355 0.7980158 -0.001183211 0.6804102 0.7328304 0.001300692 0.7500334 0.6614 -2.51438e-4 0.7980067 0.6026164 0.006234824 0.8121833 0.5834001 -0.001654863 0.8501981 0.5264235 0.006455421 0.8662552 0.4995938 -0.002845108 0.8951446 0.4457299 0.006406426 0.9117093 0.4108182 -0.003813982 0.93246 0.3612221 0.006098628 0.9480911 0.3179664 -0.004546463 0.9618085 0.2736675 0.00553739 0.9750476 0.2219385 -0.005053639 0.9829636 0.18374 0.004721641 0.9940152 0.1089667 -0.007763743 0.9957337 0.09227043 -7.60801e-4 0.09226745 0.9956306 -0.01437467 0.9957302 -0.09227788 0.002524197 0.9998672 -0.0148316 -0.006751179 0.9999998 -6.52633e-6 -6.12885e-4 0.9706053 -0.2405841 0.00668931 0.9324096 -0.3612104 -0.01180875 0.9422971 -0.3347535 0.004049062 0.8951111 -0.4457241 -0.01031482 0.9048895 -0.4256437 0.001620352 0.8501793 -0.5264177 -0.008926868 0.8587122 -0.5124578 -6.27868e-4 0.7979924 -0.6026186 -0.00767219 0.8042364 -0.5943036 -0.002679705 0.7327088 -0.6805075 -0.006887078 0.7419962 -0.6704039 -6.04868e-4 0.6736933 -0.7390082 -0.002089202 0.6725766 -0.7400225 -0.002739727 0.6026282 -0.7980204 -0.001682519 0.5966536 -0.8024851 -0.004695892 0.5264312 -0.8502168 -0.001411139 0.5149593 -0.8571903 -0.006470322 0.44574 -0.8951616 -0.001274883 0.4282964 -0.9036026 -0.008051812 0.3374416 -0.9411662 0.01841765 0.1836652 -0.982573 -0.02859234 0.243399 -0.9698138 0.01477462 0.09223747 -0.99539 -0.02628672 0.146991 -0.9890729 0.01133942 -6.11156e-6 -0.9997097 -0.02409273 0.04916685 -0.9987574 0.008136868 0.7743389 -0.6077327 0.1762394 0.6709738 -0.741075 -0.02453613 0.7314653 -0.6818782 8.68517e-4 0.8001199 -0.5998393 -9.93936e-4 0.8300756 -0.5573999 0.01673531 0.8660164 -0.5000057 -0.00317645 0.9079599 -0.4190481 0.002737045 0.922078 -0.3869558 -0.006132245 0.9471933 -0.320659 -0.001661241 0.9526861 -0.3038939 -0.006152331 0.9757936 -0.2186595 0.003861546 0.9835832 -0.1804087 -0.004121541 0.9949496 -0.1002161 0.005668044 0.9993665 0.03554135 0.001855731 0.9994385 0.03340721 0.002617478 0.9973396 -0.07286679 -0.002055585 0.9896446 0.143532 -0.001522302 0.9859352 0.1670385 0.005477666 0.9682901 0.2497971 -0.003979861 0.9420294 0.3351911 0.01509249 0.8918353 0.452345 -0.003735363 0.8469022 0.531482 0.01684445 0.9355447 0.3531392 0.00700283 0.8067144 0.5907474 -0.01515001 0.7073229 0.7067113 0.01592606 0.660665 0.7505477 -0.01413428 0.5322556 0.846454 0.01482343 0.4352185 0.8994544 -0.03958278 0.3304283 0.9437071 0.01530671 0.2130073 0.9770187 -0.007910132 -0.1820928 0.9832756 -0.003365457 -0.1382665 0.9903606 -0.008265078 -0.05611616 0.9984132 0.004710316 0 0.9999856 -0.00537014 0.05611348 0.9984133 0.004705786 0.126045 0.9920043 -0.006337761 0.1676048 0.9858542 3.22968e-4 -0.9227706 0.3851561 -0.01221543 -0.8924322 0.4510156 0.01223289 -0.854564 0.5193244 -0.004765331 -0.7820889 0.6230543 0.01185411 -0.7513319 0.6597744 -0.01407897 -0.6237362 0.7815194 0.01344251 -0.5788823 0.8152627 -0.01556622 -0.4340779 0.9007534 0.01482188 -0.3752359 0.9267762 -0.01685065 -0.2226211 0.9747737 0.01600182 -0.9672294 0.2538921 -0.00252676 -0.9536842 0.3007206 0.007332324 -0.9859411 0.1670421 0.004140436 -0.999768 -0.020599 0.006293892 -0.9999012 0 0.01405858 -0.9929642 0.1177732 -0.01232063 -0.9825935 -0.1857029 0.004938185 -0.9496312 -0.313348 -0.00367403 -0.987319 -0.1585685 -0.007567763 -0.6730729 -0.7389896 0.02944964 -0.6692135 -0.7426623 0.02461928 -0.7522541 -0.6588541 -0.005013048 -0.7961584 -0.6050797 -0.003237605 -0.8300631 -0.5574186 0.01673275 -0.8660276 -0.4999863 -0.003185331 -0.9079648 -0.4190377 0.002736508 -0.9221218 -0.386851 -0.006154835 -0.9471845 -0.3206846 -0.001704275 0 0 -1 0 0 -1 0 0 -1 0.2935867 -0.9558883 0.009187877 0.144209 -0.9892366 0.02479338 0.1796569 -0.9837286 -0.001211345 0.06015551 -0.9979071 0.02372848 1.5888e-5 -0.9999877 0.004964172 -0.06015551 -0.9979069 0.02373319 -0.1796568 -0.9837286 -0.001214861 -0.1441912 -0.9892389 0.02480417 -0.2965059 -0.9549899 0.008868932 -0.3228356 -0.9464186 -0.008316457 0.4049757 -0.9115484 0.07123428 0.9092891 0.4160752 -0.008653283 0.9279882 0.371771 0.02498388 0.9986147 -0.04675936 0.02413225 0.5800126 -0.8140324 0.03060775 0.8879591 -0.459918 -0.002070426 0.96395 -0.2658244 0.01174277 0.9995426 -0.02959257 -0.006233096 0.9624128 0.2713963 0.01027792 -0.9070907 0.4150716 0.07001584 -0.9423431 0.3346386 -0.002545058 -0.9730734 0.2284906 0.03033548 -0.9785536 -0.2058565 -0.00748074 -0.8754459 -0.483069 0.01545721 -0.6873169 -0.726343 -0.004623889 -0.5616844 -0.8273117 0.008124887 -0.9519383 -0.3062283 -0.006150066 -0.9908655 -0.1347116 0.006190657 -0.9991444 0.04089224 -0.006207823 -0.9765405 0.2152456 0.006167232 0 0 -1 0 0 -1 -6.84483e-7 0 -1 0.1401688 -0.8464147 -0.5137462 3.92904e-7 0 -1 0.01062613 0.01094919 -0.9998837 0 0.01138436 -0.9999353 -0.001866638 0.01127153 -0.9999347 0 0 -1 -0.01297652 0.001539111 -0.9999147 -0.01230746 0.003230571 -0.9999191 -0.01152145 0.004808962 -0.9999222 0.01376777 -0.001005828 -0.9999048 0.01352137 4.80883e-4 -0.9999085 -0.01335 -2.75069e-4 -0.999911 0.01385504 -0.002541244 -0.9999008 0.0137571 -0.004388332 -0.9998958 -0.0135684 -0.002179145 -0.9999056 0.01352357 -0.005675196 -0.9998925 -0.01341599 -0.004426836 -0.9999003 0.01297825 -0.007493138 -0.9998878 -0.01269626 -0.007329881 -0.9998926 -0.01321768 -0.005545139 -0.9998974 0.0122286 -0.00916773 -0.9998833 -0.01140701 -0.009990572 -0.999885 -0.003891646 -0.02038633 -0.9997847 -0.01193726 -0.009072482 -0.9998877 0.005199432 -0.02054548 -0.9997755 -1.38558e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.01041489 0.006329298 -0.9999258 -0.008999526 0.007902801 -0.9999283 -0.006774663 0.009541034 -0.9999316 -0.004323601 0.01067882 -0.9999337 1.78641e-4 4.86499e-4 -1 -1.77168e-4 -6.16379e-5 -1 -0.001374006 -0.001794755 -0.9999974 -0.003102898 -0.004051268 -0.999987 0.003194987 0.003181397 -0.9999899 1.0507e-5 -2.89645e-5 -1 1.88823e-6 -3.38779e-5 -1 0 -3.41743e-5 -1 -1.75336e-6 -3.38779e-5 -1 1.63012e-5 -4.36613e-5 -1 -3.12347e-4 3.06079e-4 -1 2.22164e-4 -3.4425e-4 -1 -1.78375e-4 2.18321e-4 -1 4.62061e-5 -1.26026e-4 -1 0 0 -1 0 0 -1 -0.9957313 0.092278 -0.001986742 -0.9825724 0.1836702 -0.0285781 -0.6026169 -0.7979912 -0.007939815 -0.6736652 -0.7389723 -0.009754598 0.2735412 -0.961361 -0.03099054 0.3612274 -0.9324769 -0.001260221 0.9617342 -0.2736533 -0.01346099 0.9829703 -0.1837469 0.002535104 0.9909908 -0.1335728 -0.009781718 0.7389967 0.6736846 0.005747079 0.6805227 0.7327257 0.00137335 -0.2736713 0.9618161 0.003723561 -0.361222 0.9324588 -0.006274521 -0.3421755 0.9396258 0.004384338 + + + + + + + + + + 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 + + + + + + + + + + + + + + + + +

79 0 0 112 0 1 84 0 2 84 1 3 73 1 4 68 1 5 114 0 6 84 0 7 68 0 8 79 2 9 84 2 10 114 2 11 173 3 12 178 3 13 167 3 14 43 4 15 158 4 16 145 4 17 43 5 18 203 5 19 158 5 20 48 6 21 203 6 22 43 6 23 48 7 24 199 7 25 203 7 26 42 8 27 199 8 28 48 8 29 42 9 30 172 9 31 199 9 32 41 10 33 172 10 34 42 10 35 41 11 36 120 11 37 172 11 38 38 12 39 120 12 40 41 12 41 38 13 42 97 13 43 120 13 44 34 14 45 97 14 46 38 14 47 34 15 48 127 15 49 97 15 50 49 16 51 86 16 52 127 16 53 56 17 54 86 17 55 49 17 56 56 18 57 78 18 58 86 18 59 53 19 60 78 19 61 56 19 62 53 20 63 143 20 64 78 20 65 54 21 66 143 21 67 53 21 68 54 22 69 72 22 70 143 22 71 57 23 72 72 23 73 54 23 74 57 24 75 153 24 76 72 24 77 64 25 78 153 25 79 57 25 80 64 26 81 82 26 82 153 26 83 63 27 84 82 27 85 64 27 86 63 28 87 68 28 88 82 28 89 61 29 90 68 29 91 63 29 92 145 30 93 33 30 94 43 30 95 61 31 96 114 31 97 68 31 98 79 32 99 114 32 100 62 32 101 62 33 102 114 33 103 61 33 104 50 34 105 112 34 106 79 34 107 50 35 108 79 35 109 62 35 110 166 36 111 0 36 112 119 36 113 166 37 114 11 37 115 0 37 116 198 38 117 11 38 118 166 38 119 198 39 120 10 39 121 11 39 122 165 40 123 10 40 124 198 40 125 165 41 126 12 41 127 10 41 128 123 42 129 6 42 130 148 42 131 123 43 132 4 43 133 6 43 134 154 44 135 4 44 136 123 44 137 3 45 138 4 45 139 154 45 140 124 46 141 3 46 142 154 46 143 124 47 144 5 47 145 3 47 146 103 48 147 5 48 148 124 48 149 103 49 150 66 49 151 5 49 152 118 50 153 66 50 154 103 50 155 118 51 156 52 51 157 66 51 158 132 52 159 52 52 160 118 52 161 132 53 162 51 53 163 52 53 164 169 54 165 51 54 166 132 54 167 169 55 168 55 55 169 51 55 170 71 56 171 55 56 172 169 56 173 71 57 174 58 57 175 55 57 176 133 58 177 58 58 178 71 58 179 133 59 180 59 59 181 58 59 182 168 60 183 59 60 184 133 60 185 168 61 186 65 61 187 59 61 188 112 62 189 65 62 190 168 62 191 9 63 192 131 63 193 119 63 194 9 64 195 93 64 196 131 64 197 14 65 198 93 65 199 9 65 200 14 66 201 77 66 202 93 66 203 8 67 204 77 67 205 14 67 206 8 68 207 91 68 208 77 68 209 7 69 210 91 69 211 8 69 212 7 70 213 181 70 214 91 70 215 156 71 216 181 71 217 7 71 218 156 72 219 184 72 220 181 72 221 1 73 222 184 73 223 156 73 224 1 74 225 95 74 226 184 74 227 2 75 228 95 75 229 1 75 230 2 76 231 76 76 232 95 76 233 22 77 234 194 77 235 76 77 236 19 78 237 194 78 238 22 78 239 19 79 240 105 79 241 194 79 242 20 80 243 105 80 244 19 80 245 20 81 246 99 81 247 105 81 248 23 82 249 99 82 250 20 82 251 23 83 252 137 83 253 99 83 254 30 84 255 137 84 256 23 84 257 30 85 258 104 85 259 137 85 260 29 86 261 104 86 262 30 86 263 29 87 264 210 87 265 104 87 266 27 88 267 210 88 268 29 88 269 27 89 270 109 89 271 210 89 272 28 90 273 109 90 274 27 90 275 119 91 276 0 91 277 9 91 278 101 92 279 16 92 280 26 92 281 109 93 282 16 93 283 101 93 284 16 94 285 109 94 286 28 94 287 25 95 288 81 95 289 128 95 290 24 96 291 81 96 292 25 96 293 24 97 294 116 97 295 81 97 296 21 98 297 116 98 298 24 98 299 21 99 300 170 99 301 116 99 302 17 100 303 170 100 304 21 100 305 17 101 306 111 101 307 170 101 308 18 102 309 111 102 310 17 102 311 18 103 312 142 103 313 111 103 314 32 104 315 142 104 316 18 104 317 32 105 318 146 105 319 142 105 320 39 106 321 146 106 322 32 106 323 39 107 324 200 107 325 146 107 326 36 108 327 200 108 328 39 108 329 36 109 330 157 109 331 200 109 332 37 110 333 157 110 334 36 110 335 37 111 336 117 111 337 157 111 338 40 112 339 117 112 340 37 112 341 40 113 342 227 113 343 117 113 344 46 114 345 75 114 346 227 114 347 44 115 348 75 115 349 46 115 350 44 116 351 129 116 352 75 116 353 45 117 354 129 117 355 44 117 356 45 118 357 151 118 358 129 118 359 33 119 360 151 119 361 45 119 362 33 120 363 145 120 364 151 120 365 215 121 366 173 121 367 183 121 368 215 122 369 205 122 370 173 122 371 215 123 372 134 123 373 205 123 374 80 124 375 134 124 376 215 124 377 122 125 378 134 125 379 80 125 380 147 126 381 122 126 382 80 126 383 147 127 384 209 127 385 122 127 386 190 128 387 209 128 388 147 128 389 190 129 390 171 129 391 209 129 392 89 130 393 171 130 394 190 130 395 89 131 396 84 131 397 171 131 398 219 132 399 84 132 400 89 132 401 219 133 402 73 133 403 84 133 404 69 134 405 220 134 406 88 134 407 69 135 408 73 135 409 220 135 410 220 136 411 73 136 412 219 136 413 187 137 414 69 137 415 88 137 416 98 138 417 69 138 418 187 138 419 192 139 420 98 139 421 187 139 422 70 140 423 98 140 424 192 140 425 130 141 426 70 141 427 108 141 428 110 142 429 70 142 430 130 142 431 70 143 432 192 143 433 108 143 434 207 144 435 110 144 436 130 144 437 207 145 438 180 145 439 110 145 440 204 146 441 180 146 442 207 146 443 204 147 444 224 147 445 180 147 446 179 148 447 224 148 448 204 148 449 179 149 450 195 149 451 224 149 452 139 150 453 195 150 454 179 150 455 140 151 456 193 151 457 221 151 458 140 152 459 162 152 460 193 152 461 102 153 462 162 153 463 140 153 464 102 154 465 206 154 466 162 154 467 107 155 468 206 155 469 102 155 470 107 156 471 139 156 472 206 156 473 195 157 474 139 157 475 107 157 476 96 158 477 113 158 478 159 158 479 202 159 480 113 159 481 96 159 482 202 160 483 176 160 484 113 160 485 188 161 486 176 161 487 202 161 488 188 162 489 150 162 490 176 162 491 164 163 492 150 163 493 188 163 494 164 164 495 217 164 496 150 164 497 106 165 498 217 165 499 164 165 500 106 166 501 221 166 502 217 166 503 140 167 504 221 167 505 106 167 506 121 168 507 159 168 508 216 168 509 121 169 510 96 169 511 159 169 512 216 170 513 67 170 514 121 170 515 92 171 516 197 171 517 191 171 518 67 172 519 197 172 520 92 172 521 197 173 522 67 173 523 216 173 524 186 174 525 94 174 526 92 174 527 149 175 528 94 175 529 186 175 530 92 176 531 191 176 532 186 176 533 213 177 534 174 177 535 218 177 536 135 178 537 174 178 538 213 178 539 135 179 540 126 179 541 174 179 542 135 180 543 74 180 544 126 180 545 125 181 546 74 181 547 135 181 548 125 182 549 155 182 550 74 182 551 83 183 552 155 183 553 125 183 554 83 184 555 149 184 556 155 184 557 94 185 558 149 185 559 83 185 560 101 186 561 96 186 562 109 186 563 128 187 564 96 187 565 101 187 566 67 0 567 92 0 568 109 0 569 96 188 570 121 188 571 109 188 572 67 0 573 109 0 574 121 0 575 87 189 576 160 189 577 214 189 578 87 190 579 189 190 580 160 190 581 161 191 582 189 191 583 87 191 584 100 192 585 189 192 586 161 192 587 100 193 588 138 193 589 189 193 590 85 194 591 138 194 592 100 194 593 201 195 594 138 195 595 85 195 596 201 196 597 211 196 598 138 196 599 90 197 600 211 197 601 201 197 602 90 198 603 163 198 604 211 198 605 214 199 606 222 199 607 87 199 608 208 200 609 183 200 610 167 200 611 167 201 612 178 201 613 208 201 614 183 202 615 173 202 616 167 202 617 223 203 618 222 203 619 214 203 620 225 204 621 222 204 622 223 204 623 225 205 624 178 205 625 222 205 626 182 206 627 178 206 628 225 206 629 182 207 630 208 207 631 178 207 632 196 208 633 177 208 634 144 208 635 177 209 636 152 209 637 144 209 638 212 210 639 177 210 640 196 210 641 226 211 642 177 211 643 212 211 644 226 212 645 141 212 646 177 212 647 163 213 648 141 213 649 226 213 650 163 214 651 90 214 652 141 214 653 175 215 654 213 215 655 218 215 656 185 216 657 175 216 658 218 216 659 185 217 660 152 217 661 175 217 662 144 218 663 152 218 664 185 218 665 204 219 666 139 219 667 179 219 668 139 0 669 204 0 670 207 0 671 206 220 672 207 220 673 130 220 674 206 221 675 139 221 676 207 221 677 193 222 678 162 222 679 221 222 680 88 223 681 206 223 682 187 223 683 115 224 684 206 224 685 88 224 686 115 225 687 162 225 688 206 225 689 221 226 690 162 226 691 115 226 692 206 227 693 130 227 694 108 227 695 192 0 696 206 0 697 108 0 698 187 0 699 206 0 700 192 0 701 216 228 702 115 228 703 197 228 704 216 229 705 159 229 706 115 229 707 115 230 708 159 230 709 113 230 710 219 231 711 115 231 712 220 231 713 220 232 714 115 232 715 88 232 716 115 233 717 191 233 718 197 233 719 89 234 720 115 234 721 219 234 722 190 235 723 115 235 724 89 235 725 191 236 726 115 236 727 186 236 728 190 237 729 147 237 730 115 237 731 115 238 732 149 238 733 186 238 734 115 239 735 147 239 736 80 239 737 115 240 738 74 240 739 155 240 740 115 241 741 155 241 742 149 241 743 115 242 744 80 242 745 215 242 746 115 243 747 174 243 748 126 243 749 136 244 750 174 244 751 115 244 752 126 245 753 74 245 754 115 245 755 215 246 756 136 246 757 115 246 758 183 0 759 136 0 760 215 0 761 136 247 762 218 247 763 174 247 764 185 0 765 218 0 766 136 0 767 136 0 768 144 0 769 185 0 770 82 0 771 68 0 772 70 0 773 82 0 774 70 0 775 110 0 776 82 0 777 110 0 778 153 0 779 72 0 780 153 0 781 110 0 782 72 0 783 110 0 784 143 0 785 110 248 786 180 248 787 143 248 788 78 249 789 143 249 790 180 249 791 78 0 792 180 0 793 86 0 794 86 250 795 180 250 796 127 250 797 127 251 798 180 251 799 224 251 800 97 252 801 127 252 802 224 252 803 97 253 804 224 253 805 120 253 806 120 0 807 224 0 808 172 0 809 172 254 810 224 254 811 195 254 812 172 0 813 195 0 814 199 0 815 195 255 816 203 255 817 199 255 818 107 256 819 203 256 820 195 256 821 107 257 822 158 257 823 203 257 824 102 258 825 158 258 826 107 258 827 102 259 828 145 259 829 158 259 830 102 260 831 151 260 832 145 260 833 102 0 834 140 0 835 151 0 836 129 0 837 151 0 838 140 0 839 106 261 840 129 261 841 140 261 842 75 0 843 129 0 844 106 0 845 75 0 846 106 0 847 227 0 848 106 0 849 164 0 850 227 0 851 117 0 852 227 0 853 164 0 854 117 0 855 164 0 856 157 0 857 157 0 858 164 0 859 200 0 860 164 0 861 188 0 862 200 0 863 146 0 864 200 0 865 188 0 866 142 262 867 146 262 868 188 262 869 111 0 870 142 0 871 188 0 872 111 263 873 188 263 874 202 263 875 111 0 876 202 0 877 170 0 878 116 0 879 170 0 880 202 0 881 81 0 882 116 0 883 202 0 884 81 264 885 202 264 886 96 264 887 81 265 888 96 265 889 128 265 890 92 0 891 210 0 892 109 0 893 94 0 894 210 0 895 92 0 896 94 0 897 104 0 898 210 0 899 94 266 900 137 266 901 104 266 902 83 0 903 137 0 904 94 0 905 83 267 906 99 267 907 137 267 908 83 268 909 125 268 910 99 268 911 99 0 912 125 0 913 105 0 914 105 269 915 125 269 916 135 269 917 105 270 918 135 270 919 194 270 920 76 271 921 194 271 922 135 271 923 76 0 924 135 0 925 213 0 926 76 0 927 213 0 928 95 0 929 95 0 930 213 0 931 184 0 932 175 0 933 184 0 934 213 0 935 152 272 936 184 272 937 175 272 938 152 0 939 177 0 940 184 0 941 141 0 942 184 0 943 177 0 944 141 0 945 181 0 946 184 0 947 90 273 948 181 273 949 141 273 950 90 274 951 91 274 952 181 274 953 77 275 954 91 275 955 90 275 956 77 276 957 90 276 958 201 276 959 77 0 960 201 0 961 93 0 962 85 0 963 93 0 964 201 0 965 85 277 966 131 277 967 93 277 968 85 278 969 100 278 970 131 278 971 100 279 972 119 279 973 131 279 974 100 0 975 161 0 976 119 0 977 119 280 978 161 280 979 166 280 980 87 0 981 166 0 982 161 0 983 87 281 984 198 281 985 166 281 986 87 282 987 165 282 988 198 282 989 87 0 990 222 0 991 165 0 992 148 283 993 165 283 994 222 283 995 123 0 996 148 0 997 222 0 998 123 284 999 222 284 1000 178 284 1001 123 285 1002 178 285 1003 154 285 1004 154 286 1005 178 286 1006 173 286 1007 124 287 1008 154 287 1009 173 287 1010 124 0 1011 173 0 1012 205 0 1013 103 0 1014 124 0 1015 205 0 1016 103 288 1017 205 288 1018 134 288 1019 103 0 1020 134 0 1021 118 0 1022 118 289 1023 134 289 1024 122 289 1025 118 0 1026 122 0 1027 132 0 1028 122 290 1029 169 290 1030 132 290 1031 122 291 1032 209 291 1033 169 291 1034 71 0 1035 169 0 1036 209 0 1037 71 292 1038 209 292 1039 171 292 1040 71 293 1041 171 293 1042 133 293 1043 84 0 1044 133 0 1045 171 0 1046 84 294 1047 168 294 1048 133 294 1049 84 0 1050 112 0 1051 168 0 1052 113 295 1053 176 295 1054 115 295 1055 150 296 1056 115 296 1057 176 296 1058 150 297 1059 217 297 1060 115 297 1061 115 298 1062 217 298 1063 221 298 1064 136 299 1065 183 299 1066 208 299 1067 136 300 1068 208 300 1069 182 300 1070 136 301 1071 182 301 1072 225 301 1073 136 302 1074 225 302 1075 223 302 1076 136 303 1077 223 303 1078 214 303 1079 136 304 1080 214 304 1081 160 304 1082 136 305 1083 160 305 1084 189 305 1085 136 306 1086 189 306 1087 138 306 1088 136 307 1089 138 307 1090 211 307 1091 136 308 1092 211 308 1093 163 308 1094 136 309 1095 163 309 1096 226 309 1097 136 310 1098 226 310 1099 212 310 1100 136 311 1101 212 311 1102 196 311 1103 136 312 1104 196 312 1105 144 312 1106 68 313 1107 73 313 1108 69 313 1109 68 314 1110 69 314 1111 98 314 1112 68 0 1113 98 0 1114 70 0 1115 50 315 1116 60 315 1117 112 315 1118 60 316 1119 65 316 1120 112 316 1121 34 317 1122 35 317 1123 127 317 1124 35 318 1125 49 318 1126 127 318 1127 46 319 1128 227 319 1129 47 319 1130 40 320 1131 47 320 1132 227 320 1133 25 321 1134 128 321 1135 31 321 1136 26 322 1137 31 322 1138 128 322 1139 26 323 1140 128 323 1141 101 323 1142 15 324 1143 22 324 1144 76 324 1145 2 325 1146 15 325 1147 76 325 1148 12 326 1149 165 326 1150 13 326 1151 6 327 1152 13 327 1153 165 327 1154 6 328 1155 165 328 1156 148 328 1157

+
+
+
+ + + + -12.40309 -66.35067 0.1000061 0 7.62939e-6 7.62939e-6 0 -67.5 0.1000061 12.40309 -66.35067 0.1000061 2.979828 -67.43418 97.78995 -1.14441e-4 -67.49415 97.35852 -0.2644425 -67.49948 97.32025 -3.110527 -67.42829 97.83242 -2.557541 -67.36343 99.19498 -0.2174301 -67.42195 98.68281 2.450081 -67.36827 99.15251 6.797615 -67.15684 99.7853 -5.968361 -67.23561 99.21858 -4.907318 -67.205 100.5811 5.589149 -67.14025 101.1479 -9.14013 -66.87831 101.7893 -7.515217 -66.91121 103.1518 9.056107 -66.67855 105.1877 11.01418 -66.59532 103.8251 12.66901 -65.95706 111.5007 -10.47327 -66.42523 107.4041 -12.4017 -66.34246 105.6444 12.3969 -66.31919 105.8117 -13.73271 -65.69657 113.78 -12.73776 -66.28724 106.0416 -24.38381 -62.94187 0.1000061 24.38382 -62.94187 0.1000061 15.40825 -65.71784 110.1381 -30.96359 -66.27737 139.4326 30.90659 -66.09642 138.3964 31.01489 -66.29549 139.9993 -31.01229 -66.24581 139.8871 -31.05478 -66.21829 140.2837 31.04912 -66.25001 140.2829 32.94938 -65.88991 138.4435 33.32701 -65.98114 140.4894 -16.70195 -65.40103 112.4174 -30.90658 -66.09642 138.3964 -33.3029 -65.80783 138.4631 31.06602 -66.22755 140.423 -33.37005 -65.99106 139.9054 -31.14796 -66.15792 141.1536 31.20829 -66.03852 141.602 31.32136 -65.69046 142.4 -31.17796 -66.07563 141.3685 31.31862 -65.6989 142.3807 -33.39518 -65.8217 141.3474 -19.62515 -63.83676 130.0532 -30.90429 -66.02533 138.1339 -22.25699 -63.61036 129.2173 -20.94102 -63.78581 129.8651 19.62515 -63.83676 130.0532 21.0809 -63.77378 129.8206 22.37375 -63.58717 129.1316 30.90421 -66.02266 138.124 -31.32168 -65.68132 142.398 33.16726 -65.46546 142.5096 -30.90374 -66.00828 138.0709 -22.46363 -63.56832 129.062 -33.31011 -65.77252 138.3242 -33.31517 -65.72641 138.1591 30.90374 -66.00828 138.0709 33.31052 -65.77244 138.3243 -27.66501 -61.57025 121.6847 -24.37521 -62.92065 126.6707 -30.91589 -62.28678 124.3303 -23.57149 -63.25056 127.8888 -33.46523 -61.96583 124.4092 23.5715 -63.25056 127.8888 24.38382 -62.94187 126.749 30.91589 -62.28678 124.3303 33.31518 -65.72641 138.1591 -33.30651 -65.80741 138.4632 -35.42964 -65.08216 140.7122 -35.45656 -65.13343 140.4447 -34.40615 -65.40134 138.5641 -33.33021 -65.80455 138.4639 34.41022 -65.42572 138.5588 34.44237 -65.61074 140.491 33.29281 -65.78078 138.4706 33.30112 -65.77814 138.4712 34.28799 -65.11653 142.499 16.31508 -64.97018 120.1359 19.84266 -64.51758 118.7733 -35.37985 -64.98731 141.2073 -35.28959 -64.81539 142.1045 -33.40621 -65.30775 142.7014 -34.43663 -65.44667 138.4695 -33.31769 -65.72548 138.1594 34.43583 -65.44818 138.4743 33.31873 -65.7251 138.1595 34.42033 -65.31977 138.2747 33.46523 -61.96583 124.4092 -34.42004 -65.31987 138.2746 -17.16833 -64.70021 122.4981 -31.36591 -65.55998 142.7148 31.37325 -65.53074 142.7662 35.15781 -65.28615 140.484 35.00881 -64.80581 142.457 -31.37132 -65.52558 142.7602 31.51433 -64.61631 143.9612 -31.51432 -64.61631 143.9612 -33.33919 -64.45751 143.8423 33.34203 -64.47798 143.8625 32.90968 -64.51071 143.8858 33.34714 -64.47673 143.8616 35.1595 -65.15983 138.5923 35.00426 -65.23696 138.6057 34.41669 -65.42366 138.5593 35.15636 -65.04895 138.3516 -35.14174 -65.12567 138.6327 -35.16043 -65.15752 138.5845 -20.8804 -64.18923 121.1356 -35.15588 -65.04911 138.3516 -35.21611 -64.24681 143.1409 -35.26613 -64.63381 142.4355 -33.38167 -64.45381 143.8395 35.45702 -65.13334 140.443 35.45335 -65.12583 140.4799 35.15593 -65.16429 138.6236 35.142 -65.17095 138.6219 35.4303 -65.07869 140.7113 35.57628 -64.96183 138.669 35.57615 -64.96292 138.6733 -35.57655 -64.95928 138.6592 -35.58429 -64.89148 138.3964 -40.13861 -62.32341 140.7186 -40.0722 -62.22029 138.3964 -35.57614 -64.96289 138.6732 40.06351 -62.22588 138.3964 40.12992 -62.32901 140.7186 34.05444 -64.30229 143.7367 34.243 -64.25579 143.7034 35.27989 -64.77111 142.2216 -35.8461 -61.02825 124.6557 35.84611 -61.02825 124.6557 35.58429 -64.89148 138.3964 34.81005 -64.11593 143.6033 35.2661 -64.65663 142.4226 35.21686 -64.24755 143.1408 -39.68976 -61.62648 143.1595 -31.54043 -64.10157 144.477 -33.44108 -63.95959 144.3032 31.53584 -64.19216 144.3862 33.39009 -64.25205 144.08 34.27832 -64.18763 143.8402 -33.85765 -63.92847 144.2651 -33.63952 -64.43138 143.8227 -35.19025 -64.04668 143.5056 -35.18993 -64.0325 143.5236 34.85728 -64.10583 143.6441 32.9516 -64.04322 144.3938 33.42775 -63.95714 144.3021 39.68117 -61.63202 143.1595 35.18973 -64.0223 143.5363 35.03522 -64.0604 143.5636 34.8427 -64.10788 143.5976 31.54043 -64.10157 144.477 -31.55338 -62.43313 146.1488 -31.54961 -63.26744 145.3128 34.32561 -63.79481 144.1293 34.92541 -63.68637 144.0138 31.54962 -63.26744 145.3128 35.19849 -63.637 143.9612 35.24987 -62.77935 144.7971 -35.19849 -63.637 143.9612 -39.37644 -61.13998 143.9612 39.36791 -61.14548 143.9612 -35.24987 -62.77935 144.7971 31.55338 -62.43313 146.1488 33.45972 -62.30451 146.0181 -35.53416 -57.38965 0.1000061 -30.8694 -60.02773 115.9893 -32.24962 -59.29764 113.6707 -33.01746 -58.87356 112.6467 -33.50817 -58.59256 112.1442 -34.06499 -58.27371 111.574 -35.28104 -57.54561 110.8466 35.53417 -57.38965 0.1000061 34.87167 -57.79459 111.0243 33.78187 -58.43829 111.8255 33.50871 -58.59205 112.1461 32.43307 -59.19751 113.4085 30.86941 -60.02773 115.9893 27.66501 -61.57025 121.6847 35.53314 -57.388 110.7808 35.28104 -57.54561 110.8466 -35.29613 -61.921 145.6331 -33.45971 -62.30451 146.0181 35.29613 -61.921 145.6331 -31.46146 -62.32654 146.2643 -31.53009 -62.37823 146.2061 -30.29002 -62.08549 146.6177 -30.79804 -62.15237 146.5022 31.53394 -62.38285 146.201 -31.19845 -62.23231 146.3838 33.44785 -62.12905 146.2005 31.47584 -62.33488 146.2546 33.39575 -61.96479 146.3894 -33.44462 -62.11308 146.2181 31.17963 -62.22753 146.3904 33.10779 -61.61107 146.8739 46.53628 -57.70347 140.7186 46.01589 -57.05821 143.1595 -33.38229 -61.93659 146.4238 -44.2475 -59.20483 138.3964 -46.54257 -57.6984 140.7186 35.29041 -61.61151 145.9465 -33.12643 -61.62633 146.8503 30.70572 -62.13822 146.5252 32.63325 -61.33657 147.3605 44.24757 -59.2049 138.3964 -32.72626 -61.37852 147.2772 -29.87708 -62.04957 146.6928 29.83891 -62.05187 146.694 35.24192 -61.31815 146.268 -35.28764 -61.58315 145.9764 -31.29684 -60.99013 148.2911 -32.2124 -61.18666 147.6964 29.39273 -62.00743 146.7809 -27.99698 -61.91819 147.0392 -29.39273 -62.00743 146.7809 31.29685 -60.99013 148.2911 27.99699 -61.91819 147.0392 30.07903 -61.15533 148.5057 34.95244 -60.67018 147.0829 -35.22884 -61.26738 146.3263 -43.5879 -58.09842 143.9612 -26.71896 -61.86213 147.3307 -30.07902 -61.15533 148.5057 26.71896 -61.86213 147.3307 27.26589 -61.79849 147.6909 28.90596 -61.30999 148.7363 26.71584 -61.86204 147.3315 -26.71583 -61.86204 147.3315 -28.6465 -61.44316 148.5774 26.58175 -61.83184 147.587 -26.58174 -61.83184 147.587 -26.30099 -61.7526 148.2129 -28.78052 -61.3349 148.8832 26.301 -61.7526 148.2129 28.78053 -61.3349 148.8832 28.51212 -61.31026 149.2255 25.99529 -61.61348 149.1936 -25.99529 -61.61348 149.1936 -28.51212 -61.31026 149.2255 28.22823 -61.25123 149.7677 43.58797 -58.09849 143.9612 -46.0221 -57.05319 143.1595 -34.97147 -60.69874 147.0433 25.90698 -61.54159 149.6554 -25.90697 -61.54159 149.6554 -28.22822 -61.25123 149.7677 28.15161 -61.21496 150.0251 34.46333 -60.14305 147.8916 -25.85341 -61.46508 150.1204 -28.1516 -61.21496 150.0251 25.85342 -61.46508 150.1204 28.11095 -61.17304 150.2853 -25.83957 -61.42425 150.3586 -28.11095 -61.17304 150.2853 25.83957 -61.42425 150.3586 -25.83484 -61.38188 150.5993 28.10417 -61.14948 150.4191 -28.90267 -61.31144 148.7342 -28.10417 -61.14948 150.4191 25.83485 -61.38188 150.5993 28.10693 -61.12424 150.5544 -25.85429 -61.29081 151.0966 -28.10692 -61.12424 150.5544 25.85429 -61.29081 151.0966 28.14289 -61.06758 150.8345 -34.55967 -60.22563 147.7536 33.06878 -59.40439 149.4256 -30.47001 -60.50551 149.6939 -30.83062 -60.20024 150.0109 -30.75757 -60.22705 150.0365 -30.58814 -60.28923 150.0959 29.17537 -61.22975 148.908 30.83063 -60.20024 150.0109 30.75758 -60.22705 150.0365 30.58814 -60.28923 150.0959 30.33953 -60.37015 150.2291 -25.9554 -61.14582 151.8391 -28.14289 -61.06758 150.8345 25.95541 -61.14582 151.8391 28.27147 -60.97169 151.2538 -40.80025 -54.38534 149.4256 -30.33952 -60.37015 150.2291 30.27769 -60.38404 150.2918 30.95004 -60.15473 149.9757 -30.27769 -60.38404 150.2918 30.25089 -60.38261 150.3549 -34.02585 -59.83914 148.4466 -30.25089 -60.38261 150.3549 30.25084 -60.37594 150.3873 -32.01392 -59.76418 149.6839 32.01392 -59.76418 149.6839 -30.25084 -60.37594 150.3873 30.26016 -60.36512 150.4199 -26.25296 -60.91518 152.9207 -28.27147 -60.97169 151.2538 -26.88637 -60.51012 154.6025 -26.5629 -60.71851 153.7668 -27.00935 -60.42669 154.922 -27.12557 -60.34034 155.2445 26.25297 -60.91518 152.9207 28.61501 -60.80795 151.8659 -30.26015 -60.36512 150.4199 30.30891 -60.32991 150.4875 -30.30891 -60.32991 150.4875 30.45467 -60.24526 150.5883 -36.00645 -57.15727 110.9437 36.00645 -57.15727 110.9437 40.43933 -54.11173 110.9437 -32.67179 -59.53979 149.5228 -33.06877 -59.40439 149.4256 -28.615 -60.80795 151.8659 -30.45466 -60.24526 150.5883 30.8187 -60.05378 150.7352 26.56291 -60.71851 153.7668 28.95664 -60.6298 152.6383 -28.95664 -60.6298 152.6383 -30.8187 -60.05378 150.7352 31.18254 -59.86566 151.4246 26.88638 -60.51012 154.6025 29.31336 -60.44094 153.4015 40.80025 -54.38534 149.4256 -29.31336 -60.44094 153.4015 -31.18254 -59.86566 151.4246 31.56227 -59.66634 152.1055 27.00935 -60.42669 154.922 29.44572 -60.35268 153.7883 -30.95004 -60.15473 149.9757 -29.44571 -60.35268 153.7883 -31.56226 -59.66634 152.1055 31.70602 -59.58537 152.5518 27.12557 -60.34034 155.2445 29.57008 -60.26048 154.1786 -30.69177 -60.1484 150.4113 30.69177 -60.1484 150.4113 -29.57007 -60.26048 154.1786 -31.70601 -59.58537 152.5518 31.84058 -59.49928 153.0024 -27.36855 -60.12828 156.0049 27.36856 -60.12828 156.0049 29.82693 -60.03067 155.0983 -32.5325 -59.28677 150.0363 -29.82692 -60.03067 155.0983 -31.84057 -59.49928 153.0024 32.11628 -59.2789 154.0645 36.64969 -56.83385 150.0363 -36.84606 -57.13837 149.4256 -32.47185 -59.17624 150.7352 36.84606 -57.13837 149.4256 -27.57166 -59.90026 156.7782 27.57167 -59.90026 156.7782 30.03647 -59.77888 156.033 36.58136 -56.72789 150.7352 -30.03647 -59.77888 156.033 -32.11627 -59.2789 154.0645 32.33748 -59.02958 155.1446 -27.81108 -59.50908 158.0692 27.81109 -59.50908 158.0692 30.25987 -59.27231 157.7939 -32.33747 -59.02958 155.1446 -32.41751 -58.82469 155.9458 -30.25986 -59.27231 157.7939 32.41751 -58.82469 155.9458 -35.59382 -57.35267 152.1055 -36.58135 -56.72789 150.7352 35.59382 -57.35267 152.1055 -27.78043 -59.11188 159.3801 27.78043 -59.11188 159.3801 30.10348 -58.46947 159.4925 -36.64968 -56.83385 150.0363 -30.10347 -58.46947 159.4925 -32.55856 -58.46356 157.3578 32.55857 -58.46356 157.3578 32.42652 -57.82707 159.605 46.45928 -57.60799 138.3964 -44.21722 -51.07108 110.9437 -40.43933 -54.11173 110.9437 -46.46555 -57.60293 138.3964 -27.77326 -59.09597 159.4326 -27.63355 -58.79611 160.4222 27.77326 -59.09597 159.4326 -32.41349 -57.80021 159.695 27.63355 -58.79611 160.4222 32.27743 -57.49831 160.6846 32.4135 -57.80021 159.695 -35.4304 -57.08935 155.9499 35.4304 -57.08935 155.9499 -27.49548 -58.49983 161.4 -29.92435 -58.1895 161.4 -32.27742 -57.49831 160.6846 27.49548 -58.49983 161.4 29.90737 -58.19391 161.4 32.17907 -57.28005 161.4 -28.7603 -58.417 164.9 -27.49548 -58.49983 164.9 27.49548 -58.49983 164.9 29.83041 -58.21349 164.9 -28.70774 -58.01852 166.4 -27.49548 -58.09791 166.4 27.49548 -58.09791 166.4 -32.42652 -57.82707 159.605 -34.94437 -56.30621 159.695 -29.92356 -58.18552 164.9 29.90588 -58.18925 164.9 29.7329 -57.82357 166.4 31.02435 -57.82987 164.9 -32.17906 -57.28005 161.4 -29.98766 -58.17276 164.9 30.87644 -57.45616 166.4 -29.8836 -57.78453 166.4 -32.17906 -57.28005 164.9 -31.98221 -56.92964 166.4 45.65262 -56.60777 143.9612 44.54954 -51.35917 149.4256 -45.65879 -56.60279 143.9612 -28.56417 -56.92988 167.4981 -27.49548 -56.99983 167.4981 27.49548 -56.99983 167.4981 -29.5993 -56.7239 167.4981 32.17907 -57.28005 164.9 34.94438 -56.30621 159.695 29.46651 -56.7583 167.4981 -31.44438 -55.97229 167.4981 52.32718 -52.33557 138.3964 52.4139 -52.42232 140.7186 51.82779 -51.8361 143.1595 -52.41801 -52.4182 140.7186 44.21723 -51.07108 110.9437 -52.33137 -52.33137 138.3964 -35.53236 -57.38679 110.7885 -41.96545 -50.55094 161.4 -42.31011 -50.96493 159.695 -38.92922 -53.62849 159.695 42.31011 -50.96493 159.695 38.92923 -53.62849 159.695 31.98222 -56.92964 166.4 30.47233 -56.43515 167.4981 -45.47445 -49.88309 0.1000061 -36.8296 -56.56703 110.4887 -36.84729 -56.55551 110.4859 -35.80255 -57.21605 110.7261 -36.49872 -56.77612 110.5652 -36.61693 -56.70143 110.5379 -40.40755 -54.0692 110.4859 -44.18247 -51.03094 110.4859 45.47446 -49.88309 0.1000061 40.40755 -54.0692 110.4859 36.8473 -56.55551 110.4859 36.82961 -56.56703 110.4887 36.64712 -56.68459 110.521 36.54641 -56.74947 110.5388 36.28058 -56.92073 110.5858 35.86512 -57.18046 110.6942 36.22111 -56.98075 110.7588 -39.65272 -54.62518 152.1055 -39.63599 -54.60115 150.7352 -39.47067 -54.37438 155.9499 39.65272 -54.62518 152.1055 41.96545 -50.55094 161.4 37.26118 -54.11193 164.9 -37.26117 -54.11193 164.9 -37.03322 -53.7809 166.4 -36.22111 -56.98075 110.7588 40.5828 -54.09549 150.0363 39.47067 -54.37438 155.9499 -51.42276 -51.42276 143.9612 -51.83185 -51.83204 143.1595 -28.36804 -55.44276 167.9 -27.49548 -55.49983 167.9 27.49548 -55.49983 167.9 -36.62057 -56.70462 110.5686 36.62057 -56.70462 110.5686 -29.21094 -55.27505 167.9 -36.41046 -52.87651 167.4981 37.03323 -53.7809 166.4 31.44439 -55.97229 167.4981 -40.5828 -54.09549 150.0363 39.636 -54.60115 150.7352 29.10259 -55.30311 167.9 -30.7097 -54.66453 167.9 -36.69534 -56.65509 110.5401 36.69534 -56.65509 110.5401 51.41864 -51.42689 143.9612 -44.54953 -51.35917 149.4256 29.9203 -55.04042 167.9 -35.55975 -51.64107 167.9 36.41047 -52.87651 167.4981 30.70971 -54.66453 167.9 -55.49984 -27.49547 167.9 35.55976 -51.64107 167.9 -43.82703 -51.33653 152.1055 -44.22948 -50.9902 150.7352 -40.50714 -53.99463 150.7352 -43.62582 -51.10084 155.9499 40.50714 -53.99463 150.7352 43.82704 -51.33653 152.1055 44.31211 -51.08545 150.0363 43.62582 -51.10084 155.9499 -42.02793 -50.48846 161.4 -42.03369 -50.49422 164.9 -41.77655 -50.18532 166.4 42.03369 -50.49422 164.9 -44.3121 -51.08545 150.0363 44.22949 -50.9902 150.7352 44.18248 -51.03094 110.4859 -41.07402 -49.34138 167.4981 41.77655 -50.18532 166.4 -40.11434 -48.18854 167.9 41.07402 -49.34138 167.4981 52.33115 -52.33116 138.3964 57.69601 -46.54554 140.7186 57.05082 -46.02505 143.1595 -57.69823 -46.54278 140.7186 47.76725 -47.76724 110.9437 -47.76725 -47.76724 110.9437 -51.07109 -44.21722 110.9437 -57.60276 -46.46577 138.3964 57.60054 -46.46852 138.3964 51.42255 -51.42255 143.9612 -57.05302 -46.02231 143.1595 40.11435 -48.18854 167.9 48.07508 -48.07507 149.4256 -48.07508 -48.07507 149.4256 -56.60262 -45.659 143.9612 56.60045 -45.66171 143.9612 51.35918 -44.54953 149.4256 47.81886 -47.81885 150.0363 -47.7297 -47.7297 152.1055 -47.7297 -47.7297 150.7352 -47.51057 -47.51057 155.9499 47.72971 -47.7297 152.1055 -46.85883 -46.85882 159.695 -43.02737 -50.39985 159.695 47.51058 -47.51057 155.9499 43.02737 -50.39985 159.695 -47.81886 -47.81885 150.0363 47.72971 -47.7297 150.7352 -45.44726 -49.85387 110.4859 45.44726 -49.85387 110.4859 42.02794 -50.48846 161.4 -46.45695 -46.45695 164.9 -46.17275 -46.17274 166.4 46.45696 -46.45695 164.9 -50.48846 -42.02792 161.4 -50.39986 -43.02736 159.695 50.48847 -42.02792 161.4 46.85883 -46.85882 159.695 -45.39629 -45.39628 167.4981 46.17276 -46.17274 166.4 -53.86616 -40.67782 0.1000061 -51.03095 -44.18247 110.4859 -47.7297 -47.7297 110.4859 53.86616 -40.67782 0.1000061 47.72971 -47.7297 110.4859 -44.33564 -44.33563 167.9 45.3963 -45.39628 167.4981 44.33564 -44.33563 167.9 -51.35918 -44.54953 149.4256 51.08546 -44.31209 150.0363 -51.08546 -44.31209 150.0363 50.99022 -44.22948 150.7352 51.0711 -44.21722 110.9437 51.03096 -44.18247 110.4859 -50.99021 -44.22948 150.7352 51.33655 -43.82703 152.1055 -51.33654 -43.82703 152.1055 -51.10084 -43.62582 155.9499 51.10085 -43.62582 155.9499 50.39986 -43.02736 159.695 59.20476 -44.24743 138.3964 62.32257 -40.13992 140.7186 61.62565 -39.69105 143.1595 -62.32326 -40.13885 140.7186 -62.22014 -40.07242 138.3964 -59.20484 -44.24749 138.3964 -54.11174 -40.43932 110.9437 -50.49422 -42.03368 164.9 -50.18532 -41.77654 166.4 50.49423 -42.03368 164.9 -49.34139 -41.07401 167.4981 50.18532 -41.77654 166.4 61.13916 -39.37772 143.9612 58.09834 -43.58782 143.9612 -58.09842 -43.58789 143.9612 -61.62634 -39.68999 143.1595 54.38535 -40.80024 149.4256 -48.18855 -40.11433 167.9 49.34139 -41.07401 167.4981 -54.38534 -40.80024 149.4256 54.0955 -40.58279 150.0363 48.18856 -40.11433 167.9 -54.0955 -40.58279 150.0363 53.99464 -40.50713 150.7352 -61.02825 -35.84609 124.6557 54.11175 -40.43932 110.9437 57.15729 -36.00645 110.9437 61.02826 -35.84609 124.6557 62.21945 -40.0735 138.3964 -53.99464 -40.50713 150.7352 54.62519 -39.65271 152.1055 -53.85736 -40.67075 110.4859 53.85737 -40.67075 110.4859 -54.62519 -39.65271 152.1055 -54.37439 -39.47066 155.9499 -50.96493 -42.3101 159.695 54.3744 -39.47066 155.9499 50.96494 -42.3101 159.695 -61.13984 -39.37666 143.9612 -60.67019 -34.95243 147.0829 -61.31816 -35.2419 146.268 -61.61151 -35.2904 145.9465 61.921 -35.29612 145.6331 61.58316 -35.28763 145.9764 61.26739 -35.22883 146.3263 -53.6285 -38.92921 159.695 -50.55095 -41.96545 161.4 -57.28006 -32.17906 161.4 -57.49832 -32.27741 160.6846 53.6285 -38.92921 159.695 57.49832 -32.27741 160.6846 50.55096 -41.96545 161.4 -54.11194 -37.26116 164.9 -53.78091 -37.03322 166.4 54.11194 -37.26116 164.9 57.28007 -32.17906 161.4 57.28007 -32.17906 164.9 -52.87651 -36.41045 167.4981 53.78091 -37.03322 166.4 -51.64108 -35.55974 167.9 52.87652 -36.41045 167.4981 -57.13838 -36.84605 149.4256 -60.14305 -34.46332 147.8916 60.69874 -34.97146 147.0433 60.22565 -34.55966 147.7536 57.13838 -36.84605 149.4256 56.83386 -36.64967 150.0363 -60.42352 -30.08733 0.1000061 60.42352 -30.08733 0.1000061 54.06921 -40.40754 110.4859 -54.06921 -40.40754 110.4859 -54.60116 -39.63599 150.7352 -56.83385 -36.64967 150.0363 56.7279 -36.58134 150.7352 54.60116 -39.63599 150.7352 -57.15728 -36.00645 110.9437 -56.98076 -36.2211 110.7588 -56.70462 -36.62057 110.5686 -56.6551 -36.69533 110.5401 -56.55552 -36.84728 110.4859 56.55553 -36.84728 110.4859 56.6551 -36.69533 110.5401 56.70463 -36.62057 110.5686 56.98077 -36.2211 110.7588 65.13344 -35.45656 140.4447 65.08217 -35.42964 140.7122 64.98732 -35.37984 141.2073 64.81543 -35.28958 142.1045 64.63382 -35.26612 142.4355 -65.12776 -35.44635 140.5531 -65.12153 -35.45125 140.4821 -64.96292 -35.57613 138.6733 -64.24225 -35.21745 143.139 -64.6426 -35.26792 142.4159 -64.81623 -35.2898 142.1022 -65.09529 -35.43002 140.7146 51.64109 -35.55974 167.9 64.89151 -35.58428 138.3964 64.95929 -35.57654 138.6592 64.96289 -35.57613 138.6732 -64.89149 -35.58428 138.3964 -64.96183 -35.57626 138.669 64.24681 -35.2161 143.1409 64.04673 -35.19024 143.5056 64.0325 -35.18992 143.5236 -64.0223 -35.18972 143.5363 -57.35268 -35.59381 152.1055 -56.72789 -36.58134 150.7352 -57.08936 -35.43039 155.9499 57.35268 -35.59381 152.1055 -56.30622 -34.94437 159.695 57.08937 -35.43039 155.9499 63.63701 -35.19849 143.9612 62.77936 -35.24986 144.7971 -63.63701 -35.19849 143.9612 -62.77936 -35.24986 144.7971 -61.921 -35.29612 145.6331 56.30623 -34.94437 159.695 -57.28006 -32.17906 164.9 -56.92965 -31.9822 166.4 -55.9723 -31.44437 167.4981 56.92966 -31.9822 166.4 -56.56703 -36.8296 110.4887 56.56704 -36.8296 110.4887 -59.4044 -33.06877 149.4256 59.83915 -34.02584 148.4466 59.4044 -33.06877 149.4256 -56.6846 -36.64711 110.521 56.70144 -36.61692 110.5379 -60.15474 -30.95003 149.9757 -59.76419 -32.01391 149.6839 -60.05379 -30.81869 150.7352 -60.14841 -30.69176 150.4113 -60.22706 -30.75757 150.0365 -60.20025 -30.83061 150.0109 59.28679 -32.53249 150.0363 59.17625 -32.47184 150.7352 -56.74948 -36.54639 110.5388 -56.92073 -36.28056 110.5858 56.77613 -36.49872 110.5652 -59.86567 -31.18253 151.4246 -59.66635 -31.56226 152.1055 59.66635 -31.56226 152.1055 57.21606 -35.80254 110.7261 -54.66453 -30.70969 167.9 55.9723 -31.44437 167.4981 -57.18046 -35.8651 110.6942 -57.7946 -34.87166 111.0243 -57.54561 -35.28103 110.8466 57.54562 -35.28103 110.8466 -58.4383 -33.78186 111.8255 -58.59206 -33.5087 112.1461 -65.04895 -35.15635 138.3516 -61.96584 -33.46522 124.4092 58.27372 -34.06499 111.574 61.96585 -33.46522 124.4092 65.3199 -34.42003 138.2746 65.04912 -35.15587 138.3516 -59.02959 -32.33747 155.1446 -59.27891 -32.11627 154.0645 -59.49929 -31.84056 153.0024 -59.58538 -31.70601 152.5518 -58.8247 -32.4175 155.9458 59.27891 -32.11627 154.0645 59.02959 -32.33747 155.1446 59.58539 -31.70601 152.5518 59.49929 -31.84056 153.0024 65.15753 -35.16042 138.5845 65.12569 -35.14173 138.6327 -65.15985 -35.15949 138.5923 -65.16429 -35.15592 138.6236 54.66454 -30.70969 167.9 65.99108 -33.37004 139.9054 65.40135 -34.40614 138.5641 -65.28617 -35.1578 140.484 -58.46356 -32.55855 157.3578 -57.82707 -32.42651 159.605 58.82471 -32.4175 155.9458 58.46357 -32.55855 157.3578 -64.80582 -35.0088 142.457 65.8217 -33.39517 141.3474 -62.30451 -33.4597 146.0181 62.1131 -33.44462 146.2181 62.30452 -33.4597 146.0181 -62.12906 -33.44784 146.2005 65.30776 -33.40621 142.7014 61.9366 -33.38228 146.4238 -64.04323 -32.95159 144.3938 -63.95714 -33.42774 144.3021 -63.79482 -34.32559 144.1293 -63.68637 -34.9254 144.0138 -63.26744 -31.54961 145.3128 63.92848 -33.85764 144.2651 63.95959 -33.44107 144.3032 63.26745 -31.54961 145.3128 62.43313 -31.55337 146.1488 -61.9648 -33.39574 146.3894 61.62634 -33.12642 146.8503 -64.06041 -35.03521 143.5636 64.45383 -33.38167 143.8395 64.43138 -33.63951 143.8227 65.44667 -34.43662 138.4695 -65.17097 -35.14199 138.6219 -65.23696 -35.00426 138.6057 -65.44818 -34.43581 138.4743 -65.61075 -34.44235 140.491 -65.42572 -34.4102 138.5588 -65.42367 -34.41667 138.5593 -65.31977 -34.42031 138.2747 -64.10585 -34.85726 143.6441 -64.10789 -34.84269 143.5976 -64.11594 -34.81004 143.6033 -64.25579 -34.24299 143.7034 -65.11653 -34.28797 142.499 61.37854 -32.72625 147.2772 -61.61108 -33.10778 146.8739 -57.80022 -32.41349 159.695 57.82708 -32.42651 159.605 57.80022 -32.41349 159.695 -64.18764 -34.27831 143.8402 61.18667 -32.2124 147.6964 -61.33658 -32.63324 147.3605 -65.98115 -33.327 140.4894 65.80458 -33.3302 138.4639 65.77252 -33.31011 138.3242 65.7255 -33.31769 138.1594 -65.77246 -33.3105 138.3243 -65.72512 -33.31872 138.1595 -65.77816 -33.3011 138.4712 -64.47673 -33.34713 143.8616 -65.46547 -33.16724 142.5096 -64.30229 -34.05443 143.7367 -64.25205 -33.39007 144.08 58.59257 -33.50817 112.1442 60.99014 -31.29683 148.2911 -59.19752 -32.43305 113.4085 58.87357 -33.01745 112.6467 -62.28678 -30.91588 124.3303 -60.02774 -30.86939 115.9893 -65.72642 -33.31517 138.1591 59.29766 -32.24961 113.6707 62.28679 -30.91588 124.3303 66.0083 -30.90373 138.0709 65.72644 -33.31517 138.1591 -62.43313 -31.55337 146.1488 62.37825 -31.53008 146.2061 -62.38286 -31.53393 146.201 62.32655 -31.46146 146.2643 64.1016 -31.54042 144.477 64.45752 -33.33918 143.8423 64.61632 -31.51432 143.9612 65.56 -31.3659 142.7148 65.52559 -31.37131 142.7602 65.68132 -31.32167 142.398 -62.33489 -31.47582 146.2546 66.15793 -31.14795 141.1536 66.07563 -31.17796 141.3685 -64.19216 -31.53582 144.3862 -64.61631 -31.51432 143.9612 -64.51071 -32.90967 143.8858 -64.47799 -33.34202 143.8625 62.23231 -31.19845 146.3838 65.80786 -33.30289 138.4631 66.24584 -31.01228 139.8871 65.80742 -33.3065 138.4632 66.21831 -31.05477 140.2837 -66.03852 -31.20828 141.602 -66.22756 -31.06601 140.423 -65.88993 -32.94936 138.4435 -65.78079 -33.2928 138.4706 -66.2955 -31.01487 139.9993 -66.25003 -31.0491 140.2829 -66.0083 -30.90373 138.0709 66.02536 -30.90428 138.1339 -66.02267 -30.90419 138.124 66.09645 -30.90657 138.3964 66.27738 -30.96359 139.4326 -65.53075 -31.37324 142.7662 -65.69047 -31.32134 142.4 -65.69892 -31.31861 142.3807 62.15237 -30.79803 146.5022 -62.22754 -31.17962 146.3904 -60.99014 -31.29683 148.2911 59.5398 -32.67179 149.5228 -64.1016 -31.54042 144.477 -66.09643 -30.90657 138.3964 62.08551 -30.29001 146.6177 59.76419 -32.01391 149.6839 -62.13822 -30.7057 146.5252 -62.05188 -29.83889 146.694 -59.27232 -30.25985 157.7939 59.27232 -30.25985 157.7939 58.46948 -30.10347 159.4925 60.15475 -30.95003 149.9757 60.20026 -30.83061 150.0109 60.22706 -30.75757 150.0365 60.28924 -30.58813 150.0959 60.14841 -30.69176 150.4113 60.05379 -30.81869 150.7352 59.86568 -31.18253 151.4246 -58.46948 -30.10347 159.4925 -59.77889 -30.03646 156.033 59.77889 -30.03646 156.033 -59.09598 -27.77325 159.4326 58.79613 -27.63354 160.4222 59.09598 -27.77325 159.4326 -60.03068 -29.82692 155.0983 -58.79612 -27.63354 160.4222 58.18951 -29.92434 161.4 60.02774 -30.86939 115.9893 -58.19392 -29.90736 161.4 -57.82988 -31.02433 164.9 58.17277 -29.98765 164.9 -57.45616 -30.87642 166.4 -60.26049 -29.57006 154.1786 60.03068 -29.82692 155.0983 -61.15533 -30.07901 148.5057 61.15533 -30.07901 148.5057 60.50552 -30.47001 149.6939 -56.43515 -30.47232 167.4981 57.78454 -29.88359 166.4 -60.35269 -29.44571 153.7883 60.2605 -29.57006 154.1786 -60.44094 -29.31335 153.4015 60.3527 -29.44571 153.7883 -60.62981 -28.95663 152.6383 60.44095 -29.31335 153.4015 -62.43313 31.55339 146.1488 -62.0855 30.29003 146.6177 -62.15237 30.79805 146.5022 -62.32655 31.46148 146.2643 -62.23231 31.19846 146.3838 64.19217 31.53584 144.3862 64.1016 31.54044 144.477 63.26745 31.54963 145.3128 62.43313 31.55339 146.1488 64.61632 31.51434 143.9612 -64.1016 31.54044 144.477 -63.26744 31.54963 145.3128 -65.52559 31.37133 142.7602 -64.61631 31.51434 143.9612 -55.04042 -29.92029 167.9 56.72391 -29.59929 167.4981 -65.55999 31.36592 142.7148 65.53075 31.37326 142.7662 65.69049 31.32137 142.4 -65.68132 31.32169 142.398 -66.07563 31.17797 141.3685 -66.15793 31.14797 141.1536 -62.00744 -29.39272 146.7809 62.00745 -29.39272 146.7809 61.9182 -27.99698 147.0392 62.04957 -29.87707 146.6928 -60.80796 -28.61499 151.8659 60.62981 -28.95663 152.6383 65.69892 31.31863 142.3807 66.22756 31.06603 140.423 66.03853 31.2083 141.602 -66.2183 31.05479 140.2837 66.2955 31.01489 139.9993 66.25003 31.04913 140.2829 -58.18925 -29.90586 164.9 -66.27738 30.96361 139.4326 -66.24582 31.0123 139.8871 66.09645 30.90659 138.3964 -61.22976 -29.17535 148.908 -60.40272 -30.07736 117.3739 -63.25057 -23.57148 127.8888 -61.92281 -26.86662 122.9864 60.42352 -30.08733 117.4506 61.92282 -26.86662 122.9864 -63.77378 -21.08088 129.8206 -63.58718 -22.37374 129.1316 -66.09643 30.90659 138.3964 -63.83677 19.62516 130.0532 -63.83677 -19.62514 130.0532 63.83678 -19.62514 130.0532 63.61038 -22.25699 129.2173 63.78583 -20.94101 129.8651 63.56833 -22.46362 129.062 63.25058 -23.57148 127.8888 -57.82358 -29.7329 166.4 -56.75831 -29.46649 167.4981 -61.33491 -28.78051 148.8832 61.33491 -28.78051 148.8832 -60.24527 -30.45465 150.5883 -60.97169 -28.27146 151.2538 60.24528 -30.45465 150.5883 60.80797 -28.61499 151.8659 -60.28924 -30.58813 150.0959 -61.31026 -28.51211 149.2255 55.27506 -29.21093 167.9 -62.04957 29.87709 146.6928 -60.38405 -30.27768 150.2918 -60.37016 -30.33952 150.2291 -60.32992 -30.3089 150.4875 -60.37594 -30.25083 150.3873 -60.38262 -30.25088 150.3549 60.32992 -30.3089 150.4875 60.37017 -30.33952 150.2291 60.38405 -30.27768 150.2918 60.37595 -30.25083 150.3873 60.36513 -30.26014 150.4199 61.31027 -28.51211 149.2255 61.25125 -28.22821 149.7677 -55.30312 -29.10258 167.9 61.31145 -28.90266 148.7342 -61.06759 -28.14288 150.8345 60.97169 -28.27146 151.2538 -61.25124 -28.22821 149.7677 61.21498 -28.1516 150.0251 -60.36513 -30.26014 150.4199 -61.12425 -28.10691 150.5544 61.0676 -28.14288 150.8345 62.3349 31.47585 146.2546 62.22754 31.17964 146.3904 62.13823 30.70573 146.5252 62.38286 31.53395 146.201 -61.21497 -28.1516 150.0251 60.38263 -30.25088 150.3549 61.17306 -28.11094 150.2853 -61.14949 -28.10416 150.4191 61.12425 -28.10691 150.5544 -59.50909 -27.81107 158.0692 -59.90027 -27.57166 156.7782 59.50909 -27.81107 158.0692 59.11188 -27.78042 159.3801 -61.17305 -28.11094 150.2853 61.14949 -28.10416 150.4191 -59.11188 -27.78042 159.3801 -64.92324 -18.47224 0.1000061 -64.89091 -18.46338 116.0874 64.92324 -18.47224 0.1000061 64.89038 -18.46276 116.0913 64.18924 -20.88039 121.1356 -61.30965 -28.90712 148.737 -61.91819 -27.99698 147.0392 61.86214 -26.71895 147.3307 61.44318 -28.64649 148.5774 -64.5176 -19.84264 118.7733 -60.12829 -27.36855 156.0049 59.90027 -27.57166 156.7782 58.18553 -29.92355 164.9 58.49985 -27.49547 161.4 58.41701 -28.76029 164.9 58.01854 -28.70773 166.4 -58.49984 -27.49547 161.4 -58.2135 -29.8304 164.9 62.05188 29.83891 146.694 -58.49984 -27.49547 164.9 -58.09791 -27.49547 166.4 -60.34035 -27.12556 155.2445 60.12829 -27.36855 156.0049 -56.99983 -27.49547 167.4981 56.92988 -28.56416 167.4981 -60.4267 -27.00934 154.922 60.34035 -27.12556 155.2445 -60.51013 -26.88636 154.6025 60.4267 -27.00934 154.922 -60.71852 -26.56289 153.7668 60.51013 -26.88636 154.6025 55.44276 -28.36803 167.9 -60.91518 -26.25296 152.9207 60.71852 -26.56289 153.7668 -61.7985 -27.26587 147.6909 -61.83184 -26.58173 147.587 61.83185 -26.58173 147.587 61.75261 -26.30098 148.2129 58.49985 -27.49547 164.9 58.09792 -27.49547 166.4 61.86206 -26.71582 147.3315 -61.14583 -25.9554 151.8391 60.91519 -26.25296 152.9207 56.99984 -27.49547 167.4981 -61.75261 -26.30098 148.2129 61.61349 -25.99528 149.1936 55.49984 -27.49547 167.9 -61.29082 -25.85428 151.0966 61.14583 -25.9554 151.8391 -61.61349 -25.99528 149.1936 61.54161 -25.90696 149.6554 -61.5416 -25.90696 149.6554 61.46509 -25.85341 150.1204 -61.38189 -25.83484 150.5993 61.29083 -25.85428 151.0966 -61.46509 -25.85341 150.1204 61.42427 -25.83956 150.3586 -61.42426 -25.83956 150.3586 61.3819 -25.83484 150.5993 -62.00744 29.39274 146.7809 -61.86214 -26.71895 147.3307 -61.86214 26.71897 147.3307 -61.91819 27.99699 147.0392 62.00745 29.39274 146.7809 61.9182 27.99699 147.0392 -59.50909 27.8111 158.0692 -59.11188 27.78044 159.3801 59.90027 27.57168 156.7782 59.50909 27.8111 158.0692 59.11188 27.78044 159.3801 59.09598 27.77326 159.4326 58.79613 27.63355 160.4222 -58.49984 27.49549 161.4 -58.79612 27.63355 160.4222 -59.09598 27.77326 159.4326 -59.90027 27.57168 156.7782 58.49985 27.49549 161.4 58.49985 27.49549 164.9 -58.49984 27.49549 164.9 58.09792 27.49549 166.4 -58.09791 27.49549 166.4 56.99984 27.49549 167.4981 -56.99983 27.49549 167.4981 55.49984 27.49549 167.9 -55.49984 27.49549 167.9 -60.12829 27.36857 156.0049 60.12829 27.36857 156.0049 -60.34035 27.12558 155.2445 -60.4267 27.00936 154.922 -60.51013 26.88638 154.6025 -60.71852 26.56291 153.7668 -60.91518 26.25298 152.9207 -61.14583 25.95541 151.8391 60.34035 27.12558 155.2445 -61.86205 -26.71582 147.3315 61.86206 26.71584 147.3315 61.86214 26.71897 147.3307 -61.86205 26.71584 147.3315 -61.75261 26.301 148.2129 -61.83184 26.58176 147.587 -61.61349 25.9953 149.1936 61.83185 26.58176 147.587 61.75261 26.301 148.2129 61.61349 25.9953 149.1936 61.29083 25.8543 151.0966 61.14583 25.95541 151.8391 60.91519 26.25298 152.9207 60.71852 26.56291 153.7668 60.51013 26.88638 154.6025 60.4267 27.00936 154.922 -61.46509 25.85342 150.1204 -61.5416 25.90698 149.6554 61.46509 25.85342 150.1204 61.54161 25.90698 149.6554 -61.29082 25.8543 151.0966 -61.38189 25.83485 150.5993 -61.42426 25.83958 150.3586 61.3819 25.83485 150.5993 61.42427 25.83958 150.3586 -64.97019 -16.31506 120.1359 64.70024 -17.16832 122.4981 65.69658 -13.7327 113.78 -64.70021 17.16834 122.4981 63.83678 19.62516 130.0532 -67.21206 -6.228104 0.1000061 -65.71785 -15.40824 110.1381 -66.59533 -11.01417 103.8251 -67.15686 -6.7976 99.7853 67.21207 -6.228104 0.1000061 66.28725 -12.73775 106.0416 65.40103 -16.70194 112.4174 67.20645 -6.227486 99.42861 66.87831 -9.140124 101.7893 64.97019 16.31509 120.1359 -65.69657 13.73273 113.78 -65.95707 -12.66899 111.5007 -66.67855 -9.056097 105.1877 65.95708 12.66901 111.5007 66.42525 -10.47326 107.4041 -66.91122 7.515228 103.1518 -66.42524 10.47328 107.4041 -67.14025 -5.589138 101.1479 66.91123 -7.515209 103.1518 -67.20501 4.907333 100.5811 67.20502 -4.90731 100.5811 66.67856 9.056117 105.1877 -67.19831 -6.227085 99.48712 -67.21206 6.228127 0.1000061 -67.43419 -2.979813 97.78995 67.21207 6.228127 0.1000061 67.43419 2.979835 97.78995 67.49948 -0.2644348 97.32025 67.4283 -3.110519 97.83242 67.23563 -5.968353 99.21858 -67.36828 -2.450066 99.15251 -67.36344 2.557556 99.19498 67.36344 -2.557533 99.19498 67.14025 5.589157 101.1479 -67.49948 0.2644577 97.32025 -67.42196 0.2174453 98.68281 67.42197 -0.2174224 98.68281 67.3683 2.450088 99.15251 64.92324 18.47226 0.1000061 60.42352 30.08735 0.1000061 53.86616 40.67785 0.1000061 45.47446 49.88311 0.1000061 35.53417 57.38967 0.1000061 24.38382 62.94189 0.1000061 12.40309 66.3507 0.1000061 0 67.50001 0.1000061 -12.40309 66.3507 0.1000061 -24.38381 62.94189 0.1000061 -35.53416 57.38967 0.1000061 -45.47445 49.88311 0.1000061 -53.86616 40.67785 0.1000061 -60.42352 30.08735 0.1000061 -64.92324 18.47226 0.1000061 -67.42829 3.110535 97.83242 67.19831 6.227104 99.48712 -67.23562 5.968376 99.21858 -67.20643 6.227509 99.42861 67.15686 6.797623 99.7853 66.59534 11.01419 103.8251 -66.87831 9.140147 101.7893 65.71785 15.40826 110.1381 -66.28725 12.73777 106.0416 -65.40103 16.70196 112.4174 -64.18924 20.88041 121.1356 -64.89038 18.46278 116.0913 64.89093 18.4634 116.0874 63.58719 22.37376 129.1316 63.25058 23.5715 127.8888 64.5176 19.84267 118.7733 -63.78582 20.94103 129.8651 -63.61037 22.257 129.2173 -63.56833 22.46364 129.062 -60.42352 30.08735 117.4506 60.40272 30.07738 117.3739 63.77379 21.0809 129.8206 61.92282 26.86664 122.9864 -63.25057 23.5715 127.8888 -61.92281 26.86664 122.9864 -66.02534 30.9043 138.1339 66.02268 30.90421 138.124 66.0083 30.90375 138.0709 -66.0083 30.90375 138.0709 62.28679 30.9159 124.3303 -61.14949 28.10418 150.4191 -61.12425 28.10693 150.5544 61.12425 28.10693 150.5544 61.0676 28.1429 150.8345 -61.17305 28.11096 150.2853 61.14949 28.10418 150.4191 -61.21497 28.15162 150.0251 61.17306 28.11096 150.2853 -61.06759 28.1429 150.8345 60.97169 28.27148 151.2538 -61.25124 28.22823 149.7677 61.21498 28.15162 150.0251 -60.97169 28.27148 151.2538 60.80797 28.61501 151.8659 -61.31026 28.51212 149.2255 61.25125 28.22823 149.7677 -60.80796 28.61501 151.8659 60.62981 28.95665 152.6383 -61.33491 28.78053 148.8832 61.31027 28.51212 149.2255 -60.62981 28.95665 152.6383 60.44095 29.31337 153.4015 -61.44317 28.64652 148.5774 61.79851 27.26589 147.6909 61.33491 28.78053 148.8832 -61.15533 30.07903 148.5057 -62.28678 30.9159 124.3303 -60.44094 29.31337 153.4015 60.3527 29.44573 153.7883 -60.35269 29.44573 153.7883 60.2605 29.57008 154.1786 -60.26049 29.57008 154.1786 60.03068 29.82694 155.0983 61.31001 28.90597 148.7363 -60.03068 29.82694 155.0983 59.77889 30.03648 156.033 -58.18951 29.92436 161.4 -58.41701 28.76031 164.9 58.19392 29.90738 161.4 58.21351 29.83042 164.9 -58.01853 28.70776 166.4 -56.92988 28.56418 167.4981 57.82358 29.73291 166.4 -55.44276 28.36805 167.9 56.75831 29.46652 167.4981 51.64109 35.55977 167.9 48.18856 40.11436 167.9 44.33564 44.33565 167.9 40.11435 48.18857 167.9 -30.7097 54.66455 167.9 -35.55975 51.6411 167.9 -40.11434 48.18857 167.9 -44.33564 44.33565 167.9 -48.18855 40.11436 167.9 -51.64108 35.55977 167.9 -54.66453 30.70972 167.9 -55.27506 29.21095 167.9 55.30313 29.1026 167.9 55.04043 29.92031 167.9 54.66454 30.70972 167.9 35.55976 51.6411 167.9 30.70971 54.66455 167.9 29.21095 55.27507 167.9 28.36804 55.44277 167.9 27.49548 55.49985 167.9 -27.49548 55.49985 167.9 -29.10259 55.30314 167.9 -29.9203 55.04043 167.9 -59.77889 30.03648 156.033 59.27232 30.25987 157.7939 -57.49832 32.27743 160.6846 -57.80022 32.4135 159.695 57.28007 32.17908 161.4 57.49832 32.27743 160.6846 -58.46948 30.10349 159.4925 57.80022 32.4135 159.695 58.46948 30.10349 159.4925 -59.27232 30.25987 157.7939 -60.99014 31.29685 148.2911 61.15533 30.07903 148.5057 -60.38262 30.2509 150.3549 -60.37594 30.25085 150.3873 60.37595 30.25085 150.3873 60.36513 30.26016 150.4199 -60.36513 30.26016 150.4199 60.32992 30.30892 150.4875 -60.38405 30.2777 150.2918 60.38263 30.2509 150.3549 -60.32992 30.30892 150.4875 60.24528 30.45467 150.5883 -60.37016 30.33954 150.2291 60.38405 30.2777 150.2918 -60.28924 30.58815 150.0959 60.37017 30.33954 150.2291 -60.24527 30.45467 150.5883 60.05379 30.81871 150.7352 60.22706 30.75758 150.0365 60.28924 30.58815 150.0959 -56.72391 29.59931 167.4981 -60.05379 30.81871 150.7352 59.86568 31.18255 151.4246 -61.31202 28.90157 148.7335 -58.18552 29.92357 164.9 -57.78454 29.88361 166.4 -60.50551 30.47002 149.6939 -60.20025 30.83064 150.0109 -60.22706 30.75758 150.0365 61.22977 29.17538 148.908 60.20026 30.83064 150.0109 -59.86567 31.18255 151.4246 59.66635 31.56228 152.1055 56.43516 30.47234 167.4981 60.15475 30.95005 149.9757 -59.66635 31.56228 152.1055 59.58539 31.70602 152.5518 60.99014 31.29685 148.2911 -59.58538 31.70602 152.5518 59.49929 31.84058 153.0024 57.45617 30.87644 166.4 -59.49929 31.84058 153.0024 59.27891 32.11629 154.0645 -55.9723 31.4444 167.4981 58.18926 29.90588 164.9 -59.27891 32.11629 154.0645 59.02959 32.33749 155.1446 61.33658 32.63326 147.3605 -58.17276 29.98767 164.9 -56.92965 31.98222 166.4 57.82989 31.02435 164.9 55.9723 31.4444 167.4981 -57.28006 32.17908 161.4 -57.28006 32.17908 164.9 -59.02959 32.33749 155.1446 -58.8247 32.41752 155.9458 58.82471 32.41752 155.9458 60.02774 30.86942 115.9893 -59.76419 32.01393 149.6839 59.76419 32.01393 149.6839 -60.02774 30.86942 115.9893 -59.29765 32.24963 113.6707 -58.87356 33.01747 112.6467 -58.59257 33.50819 112.1442 -58.27371 34.06501 111.574 -57.54561 35.28105 110.8466 -57.21606 35.80257 110.7261 -56.77613 36.49874 110.5652 -56.70143 36.61693 110.5379 -56.56703 36.82962 110.4887 -54.06921 40.40756 110.4859 -56.55552 36.8473 110.4859 54.06921 40.40756 110.4859 56.55553 36.8473 110.4859 56.56704 36.82962 110.4887 56.6846 36.64713 110.521 56.74948 36.54642 110.5388 56.92074 36.28059 110.5858 57.18047 35.86513 110.6942 57.54562 35.28105 110.8466 57.79461 34.87168 111.0243 58.43831 33.78187 111.8255 58.59206 33.50872 112.1461 59.19752 32.43307 113.4085 53.85737 40.67077 110.4859 -57.82707 32.42653 159.605 -58.46356 32.55858 157.3578 57.82708 32.42653 159.605 -60.14841 30.69178 150.4113 60.14841 30.69178 150.4113 58.46357 32.55858 157.3578 -61.18667 32.21242 147.6964 -61.37853 32.72627 147.2772 -60.15474 30.95005 149.9757 56.92966 31.98222 166.4 -59.28678 32.53252 150.0363 -59.17625 32.47186 150.7352 56.83386 36.6497 150.0363 52.87652 36.41048 167.4981 -61.62634 33.12644 146.8503 56.7279 36.58137 150.7352 61.96585 33.46524 124.4092 57.28007 32.17908 164.9 -61.96584 33.46524 124.4092 -65.72642 33.31518 138.1591 65.72644 33.31518 138.1591 65.77246 33.31052 138.3243 65.88993 32.94939 138.4435 -65.80784 33.30291 138.4631 -65.77252 33.31013 138.3242 -65.99108 33.37006 139.9054 65.98117 33.32702 140.4894 -65.8217 33.39519 141.3474 61.61108 33.1078 146.8739 -61.93659 33.38231 146.4238 65.46547 33.16727 142.5096 -59.5398 32.67181 149.5228 -59.4044 33.06879 149.4256 -59.83914 34.02586 148.4466 59.4044 33.06879 149.4256 -65.30776 33.40623 142.7014 -64.45751 33.3392 143.8423 -52.87651 36.41048 167.4981 53.78091 37.03324 166.4 -62.37824 31.53011 146.2061 -62.11309 33.44464 146.2181 61.9648 33.39576 146.3894 -63.95959 33.44109 144.3032 64.25206 33.3901 144.08 64.51071 32.90969 143.8858 -62.30451 33.45972 146.0181 62.12906 33.44786 146.2005 64.04323 32.95161 144.3938 -62.77936 35.24988 144.7971 62.77936 35.24988 144.7971 62.30452 33.45972 146.0181 -57.35268 35.59383 152.1055 -56.72789 36.58137 150.7352 57.35268 35.59383 152.1055 -53.78091 37.03324 166.4 54.11194 37.26118 164.9 -50.55095 41.96546 161.4 50.96494 42.31012 159.695 50.55096 41.96546 161.4 -54.11194 37.26118 164.9 -60.22564 34.55968 147.7536 -50.96493 42.31012 159.695 -53.6285 38.92924 159.695 -56.30622 34.94439 159.695 56.30623 34.94439 159.695 53.6285 38.92924 159.695 -57.08936 35.43041 155.9499 57.08937 35.43041 155.9499 -56.83385 36.6497 150.0363 60.14306 34.46334 147.8916 -60.69874 34.97148 147.0433 64.47801 33.34204 143.8625 65.78079 33.29282 138.4706 63.95715 33.42776 144.3021 -57.13838 36.84607 149.4256 57.13838 36.84607 149.4256 60.6702 34.95244 147.0829 -61.26739 35.22885 146.3263 64.47676 33.34715 143.8616 65.11653 34.28799 142.499 65.77816 33.30112 138.4712 65.42572 34.41022 138.5588 -65.80741 33.30652 138.4632 -65.80455 33.33022 138.4639 -65.44667 34.43664 138.4695 -65.72549 33.31771 138.1594 65.44818 34.43584 138.4743 65.72512 33.31874 138.1595 65.31978 34.42033 138.2747 -65.31988 34.42005 138.2746 65.61075 34.44237 140.491 -65.40135 34.40616 138.5641 -64.45381 33.38169 143.8395 64.18764 34.27833 143.8402 64.30229 34.05445 143.7367 -65.08217 35.42966 140.7122 -65.13344 35.45658 140.4447 -63.92847 33.85766 144.2651 -64.43138 33.63953 143.8227 -64.04673 35.19026 143.5056 -64.24681 35.21612 143.1409 -61.58316 35.28765 145.9764 -64.98732 35.37986 141.2073 -64.81542 35.2896 142.1045 61.31816 35.24193 146.268 -64.63382 35.26613 142.4355 63.79483 34.32561 144.1293 -61.921 35.29614 145.6331 61.61153 35.29042 145.9465 61.921 35.29614 145.6331 -61.02825 35.84611 124.6557 61.02826 35.84611 124.6557 65.04895 35.15637 138.3516 -64.0325 35.18995 143.5236 -63.63701 35.1985 143.9612 64.2558 34.24301 143.7034 64.10585 34.85728 143.6441 64.11595 34.81006 143.6033 64.80582 35.00882 142.457 63.68638 34.92542 144.0138 -65.12568 35.14175 138.6327 65.42369 34.41669 138.5593 65.28617 35.15781 140.484 65.23697 35.00427 138.6057 -65.04912 35.15589 138.3516 -65.15753 35.16044 138.5845 65.15985 35.15951 138.5923 54.38535 40.80026 149.4256 -54.38534 40.80026 149.4256 64.10791 34.84271 143.5976 64.06041 35.03523 143.5636 57.15729 36.00646 110.9437 63.63701 35.1985 143.9612 54.3744 39.47068 155.9499 58.09851 43.58798 143.9612 65.17098 35.142 138.6219 64.24756 35.21686 143.1408 65.07872 35.43031 140.7113 64.77114 35.2799 142.2216 64.65665 35.26611 142.4226 64.02231 35.18974 143.5363 -64.96289 35.57616 138.6732 -64.95928 35.57657 138.6592 65.16429 35.15594 138.6236 -64.89149 35.5843 138.3964 64.96184 35.57629 138.669 64.96292 35.57616 138.6733 65.13335 35.45703 140.443 64.89151 35.5843 138.3964 65.12584 35.45336 140.4799 61.14549 39.36792 143.9612 61.63203 39.68117 143.1595 -61.13916 39.37775 143.9612 -61.62565 39.69108 143.1595 62.32902 40.12993 140.7186 -58.09834 43.58784 143.9612 -62.32257 40.13994 140.7186 -57.15728 36.00646 110.9437 -54.37439 39.47068 155.9499 54.62519 39.65273 152.1055 -62.21945 40.07352 138.3964 62.22589 40.06352 138.3964 49.34139 41.07403 167.4981 -54.62519 39.65273 152.1055 -54.60116 39.63601 150.7352 -56.98076 36.22112 110.7588 -59.20476 44.24744 138.3964 54.11175 40.43934 110.9437 59.20492 44.24757 138.3964 56.98077 36.22112 110.7588 -54.11174 40.43934 110.9437 -56.70462 36.62058 110.5686 56.70463 36.62058 110.5686 -49.34139 41.07403 167.4981 50.18532 41.77656 166.4 -54.0955 40.58281 150.0363 54.60116 39.63601 150.7352 -56.6551 36.69535 110.5401 56.6551 36.69535 110.5401 54.0955 40.58281 150.0363 -50.18532 41.77656 166.4 50.49423 42.0337 164.9 -50.48846 42.02795 161.4 -50.49422 42.0337 164.9 -57.05082 46.02507 143.1595 -51.10084 43.62583 155.9499 51.10085 43.62583 155.9499 51.33655 43.82705 152.1055 -53.99464 40.50715 150.7352 53.99464 40.50715 150.7352 -51.33654 43.82705 152.1055 -50.99021 44.2295 150.7352 57.05822 46.0159 143.1595 -57.69601 46.54556 140.7186 57.70349 46.53629 140.7186 45.3963 45.39631 167.4981 -53.85736 40.67077 110.4859 -51.07109 44.21724 110.9437 -51.03095 44.18249 110.4859 51.0711 44.21724 110.9437 57.60801 46.45929 138.3964 -51.08546 44.31212 150.0363 50.99022 44.2295 150.7352 -51.35918 44.54954 149.4256 51.08546 44.31212 150.0363 51.03096 44.18249 110.4859 -47.7297 47.72972 110.4859 -56.60044 45.66173 143.9612 51.35918 44.54954 149.4256 -45.39629 45.39631 167.4981 46.17276 46.17277 166.4 -46.17275 46.17277 166.4 46.45696 46.45697 164.9 50.48847 42.02795 161.4 -50.39986 43.02738 159.695 -42.02793 50.48848 161.4 -43.02737 50.39987 159.695 -46.85883 46.85884 159.695 -46.45695 46.45697 164.9 50.39986 43.02738 159.695 42.02794 50.48848 161.4 42.03369 50.49424 164.9 47.51058 47.51059 155.9499 46.85883 46.85884 159.695 56.60778 45.65263 143.9612 -47.51057 47.51059 155.9499 47.72971 47.72972 152.1055 -47.7297 47.72972 152.1055 -47.7297 47.72972 150.7352 47.72971 47.72972 110.4859 47.76725 47.76726 110.9437 -47.76725 47.76726 110.9437 -57.60054 46.46854 138.3964 52.33559 52.32719 138.3964 -47.81886 47.81887 150.0363 47.72971 47.72972 150.7352 -48.07508 48.07509 149.4256 47.81886 47.81887 150.0363 41.07402 49.3414 167.4981 -51.42254 51.42257 143.9612 51.4269 51.41865 143.9612 48.07508 48.07509 149.4256 -41.07402 49.3414 167.4981 41.77655 50.18533 166.4 51.83612 51.8278 143.1595 -51.82778 51.83613 143.1595 -52.4139 52.42233 140.7186 -41.77655 50.18533 166.4 -42.03369 50.49424 164.9 -52.33114 52.33118 138.3964 52.42232 52.41391 140.7186 43.62582 51.10086 155.9499 43.02737 50.39987 159.695 -43.62582 51.10086 155.9499 43.82704 51.33655 152.1055 -45.44726 49.85389 110.4859 45.44726 49.85389 110.4859 -44.3121 51.08547 150.0363 -44.22948 50.99023 150.7352 44.22949 50.99023 150.7352 -43.82703 51.33655 152.1055 -44.21722 51.0711 110.9437 -52.32717 52.33559 138.3964 44.21723 51.0711 110.9437 46.46854 57.60055 138.3964 52.33117 52.33115 138.3964 -44.54953 51.35919 149.4256 44.31211 51.08547 150.0363 -51.41864 51.42691 143.9612 51.42256 51.42255 143.9612 44.54954 51.35919 149.4256 36.41047 52.87652 167.4981 -36.41046 52.87652 167.4981 37.03323 53.78092 166.4 -44.18247 51.03097 110.4859 44.18248 51.03097 110.4859 -40.40755 54.06922 110.4859 -37.03322 53.78092 166.4 37.26118 54.11195 164.9 -42.31011 50.96495 159.695 42.31011 50.96495 159.695 -41.96545 50.55096 161.4 41.96545 50.55096 161.4 -37.26117 54.11195 164.9 -32.17906 57.28007 161.4 32.27743 57.49833 160.6846 32.17907 57.28007 161.4 32.17907 57.28007 164.9 -39.47067 54.3744 155.9499 -38.92922 53.62851 159.695 -32.27742 57.49833 160.6846 39.47067 54.3744 155.9499 38.92923 53.62851 159.695 -40.5828 54.09551 150.0363 -40.50714 53.99465 150.7352 40.50714 53.99465 150.7352 39.65272 54.6252 152.1055 40.40755 54.06922 110.4859 40.43933 54.11175 110.9437 -40.43933 54.11175 110.9437 -46.45927 57.60802 138.3964 44.24744 59.20477 138.3964 -40.80025 54.38536 149.4256 40.5828 54.09551 150.0363 -39.65272 54.6252 152.1055 -43.58797 58.09852 143.9612 -45.65262 56.60779 143.9612 45.66172 56.60046 143.9612 40.80025 54.38536 149.4256 46.02506 57.05083 143.1595 31.44439 55.97231 167.4981 -46.01588 57.05823 143.1595 -46.53628 57.7035 140.7186 46.54555 57.69601 140.7186 -31.44438 55.97231 167.4981 31.98222 56.92966 166.4 -34.94437 56.30624 159.695 35.4304 57.08938 155.9499 34.94438 56.30624 159.695 -31.98221 56.92966 166.4 -39.63599 54.60117 150.7352 39.636 54.60117 150.7352 -36.84729 56.55553 110.4859 36.8473 56.55553 110.4859 -36.64968 56.83387 150.0363 -36.84606 57.13839 149.4256 36.64969 56.83387 150.0363 36.58136 56.7279 150.7352 -36.00645 57.15729 110.9437 -36.22111 56.98077 110.7588 -36.62057 56.70463 110.5686 -36.69534 56.65511 110.5401 -35.8461 61.02827 124.6557 -44.24756 59.20492 138.3964 36.69534 56.65511 110.5401 36.62057 56.70463 110.5686 36.22111 56.98077 110.7588 36.00645 57.15729 110.9437 -32.17906 57.28007 164.9 -35.4304 57.08938 155.9499 35.59382 57.35269 152.1055 -34.46333 60.14307 147.8916 -34.95243 60.6702 147.0829 35.22884 61.2674 146.3263 34.97147 60.69875 147.0433 34.55968 60.22565 147.7536 36.84606 57.13839 149.4256 43.58784 58.09835 143.9612 -36.58135 56.7279 150.7352 -35.59382 57.35269 152.1055 29.5993 56.72392 167.4981 -30.47233 56.43516 167.4981 28.56417 56.92989 167.4981 -29.4665 56.75832 167.4981 27.49548 56.99985 167.4981 -27.49548 56.99985 167.4981 29.88361 57.78455 166.4 -32.42652 57.82709 159.605 -32.41349 57.80023 159.695 32.42652 57.82709 159.605 32.4135 57.80023 159.695 32.55857 58.46358 157.3578 -30.87643 57.45618 166.4 -36.8296 56.56705 110.4887 36.82961 56.56705 110.4887 -36.64712 56.68461 110.521 36.61693 56.70145 110.5379 -36.5464 56.74949 110.5388 36.49873 56.77614 110.5652 -36.28057 56.92074 110.5858 28.70775 58.01855 166.4 -30.8187 60.05379 150.7352 -31.18254 59.86568 151.4246 -31.56226 59.66636 152.1055 32.47185 59.17626 150.7352 31.56227 59.66636 152.1055 -29.7329 57.82359 166.4 35.80256 57.21607 110.7261 -30.95004 60.15475 149.9757 -32.01392 59.7642 149.6839 -30.69177 60.14842 150.4113 -30.75757 60.22707 150.0365 -30.83062 60.20026 150.0109 -33.06877 59.40441 149.4256 33.06878 59.40441 149.4256 32.53251 59.2868 150.0363 -35.86511 57.18048 110.6942 29.98766 58.17277 164.9 27.49548 58.09793 166.4 -35.53314 57.38802 110.7808 -27.49548 58.09793 166.4 39.69107 61.62566 143.1595 39.37774 61.13917 143.9612 -39.68116 61.63204 143.1595 -40.12991 62.32903 140.7186 -32.55856 58.46358 157.3578 -32.41751 58.82471 155.9458 32.33748 59.0296 155.1446 32.41751 58.82471 155.9458 34.02585 59.83916 148.4466 -34.87167 57.79462 111.0243 -35.28104 57.54563 110.8466 35.84611 61.02827 124.6557 35.28104 57.54563 110.8466 35.53237 57.38681 110.7885 -29.90736 58.19393 161.4 -27.63355 58.79613 160.4222 -31.02434 57.82989 164.9 29.92436 58.18951 161.4 -32.33747 59.0296 155.1446 -32.11627 59.27892 154.0645 -31.84057 59.4993 153.0024 -31.70601 59.58539 152.5518 32.11628 59.27892 154.0645 31.70602 59.58539 152.5518 31.84058 59.4993 153.0024 -29.90587 58.18927 164.9 -27.77326 59.09599 159.4326 27.63355 58.79613 160.4222 34.065 58.27373 111.574 40.13994 62.32258 140.7186 -40.06351 62.2259 138.3964 29.92356 58.18554 164.9 -33.78186 58.43832 111.8255 -30.10347 58.46949 159.4925 27.77326 59.09599 159.4326 30.10348 58.46949 159.4925 -29.83041 58.21352 164.9 -30.25986 59.27233 157.7939 28.7603 58.41702 164.9 27.49548 58.49985 164.9 -27.49548 58.49985 164.9 35.29613 61.92101 145.6331 35.28764 61.58317 145.9764 -39.3679 61.1455 143.9612 -35.24191 61.31817 146.268 -35.2904 61.61153 145.9465 27.49548 58.49985 161.4 -27.49548 58.49985 161.4 33.50818 58.59258 112.1442 33.46523 61.96586 124.4092 -33.50871 58.59207 112.1461 30.25987 59.27233 157.7939 -27.78043 59.11189 159.3801 -27.81108 59.50909 158.0692 27.78043 59.11189 159.3801 -32.43306 59.19753 113.4085 -33.46523 61.96586 124.4092 33.01746 58.87358 112.6467 -30.03647 59.7789 156.033 30.03647 59.7789 156.033 32.24962 59.29767 113.6707 -29.82692 60.03069 155.0983 27.81109 59.50909 158.0692 30.69177 60.14842 150.4113 30.8187 60.05379 150.7352 31.18254 59.86568 151.4246 -30.8694 60.02775 115.9893 40.07352 62.21946 138.3964 -27.57166 59.90028 156.7782 -29.57007 60.2605 154.1786 29.82693 60.03069 155.0983 32.01392 59.7642 149.6839 30.95004 60.15475 149.9757 30.83063 60.20026 150.0109 30.75758 60.22707 150.0365 30.58814 60.28925 150.0959 32.6718 59.53981 149.5228 30.86941 60.02775 115.9893 30.91589 62.2868 124.3303 -31.29684 60.99015 148.2911 -32.63325 61.33658 147.3605 31.29685 60.99015 148.2911 -29.44571 60.35271 153.7883 29.57008 60.2605 154.1786 27.57167 59.90028 156.7782 -29.31336 60.44095 153.4015 29.44572 60.35271 153.7883 -28.95664 60.62981 152.6383 29.31336 60.44095 153.4015 -30.07902 61.15534 148.5057 30.07903 61.15534 148.5057 30.47002 60.50553 149.6939 -27.36855 60.1283 156.0049 32.21241 61.18668 147.6964 -28.615 60.80797 151.8659 28.95664 60.62981 152.6383 27.36856 60.1283 156.0049 -27.66501 61.57027 121.6847 -30.91589 62.2868 124.3303 27.66501 61.57027 121.6847 -27.12557 60.34036 155.2445 -30.45466 60.24528 150.5883 -28.27147 60.9717 151.2538 30.45467 60.24528 150.5883 28.61501 60.80797 151.8659 27.12557 60.34036 155.2445 -33.10779 61.61109 146.8739 -30.27769 60.38406 150.2918 -30.33952 60.37018 150.2291 -30.30891 60.32993 150.4875 -30.25084 60.37596 150.3873 -30.25089 60.38264 150.3549 -30.58814 60.28925 150.0959 30.30891 60.32993 150.4875 30.33953 60.37018 150.2291 30.27769 60.38406 150.2918 30.25084 60.37596 150.3873 30.26016 60.36514 150.4199 -29.17536 61.22977 148.908 -28.78052 61.33492 148.8832 28.78053 61.33492 148.8832 32.72626 61.37855 147.2772 -28.51212 61.31028 149.2255 -28.14289 61.0676 150.8345 28.27147 60.9717 151.2538 -27.00935 60.42671 154.922 28.51212 61.31028 149.2255 28.22823 61.25126 149.7677 -30.26015 60.36514 150.4199 -28.10692 61.12426 150.5544 28.14289 61.0676 150.8345 27.00935 60.42671 154.922 -25.9554 61.14583 151.8391 -26.25296 60.9152 152.9207 -26.5629 60.71853 153.7668 -26.88637 60.51014 154.6025 -28.10417 61.1495 150.4191 28.10693 61.12426 150.5544 -28.22822 61.25126 149.7677 28.15161 61.21499 150.0251 -28.11095 61.17307 150.2853 30.25089 60.38264 150.3549 28.10417 61.1495 150.4191 -28.1516 61.21499 150.0251 28.11095 61.17307 150.2853 26.88638 60.51014 154.6025 28.90156 61.31203 148.7335 26.56291 60.71853 153.7668 -33.39574 61.9648 146.3894 33.12643 61.62635 146.8503 26.25297 60.9152 152.9207 25.95541 61.14583 151.8391 -25.85429 61.29084 151.0966 -29.39273 62.00745 146.7809 -29.8389 62.05189 146.694 29.39273 62.00745 146.7809 27.99699 61.9182 147.0392 29.87708 62.04958 146.6928 30.29002 62.08552 146.6177 -35.58429 64.89151 138.3964 -35.15636 65.04896 138.3516 35.58429 64.89151 138.3964 35.15588 65.04914 138.3516 -25.83484 61.3819 150.5993 25.85429 61.29084 151.0966 -25.83957 61.42428 150.3586 25.83485 61.3819 150.5993 35.18994 64.03251 143.5236 35.19849 63.63702 143.9612 35.24987 62.77936 144.7971 -35.19849 63.63702 143.9612 -35.18973 64.02233 143.5363 -35.24987 62.77936 144.7971 -35.29613 61.92101 145.6331 -25.85341 61.46509 150.1204 25.83957 61.42428 150.3586 -28.90713 61.30967 148.737 -27.99698 61.9182 147.0392 26.71896 61.86214 147.3307 28.64651 61.44318 148.5774 -25.90697 61.54162 149.6554 25.85342 61.46509 150.1204 -25.99529 61.6135 149.1936 25.90698 61.54162 149.6554 -26.30099 61.75262 148.2129 25.99529 61.6135 149.1936 33.3823 61.93661 146.4238 -27.26588 61.79851 147.6909 -26.58174 61.83185 147.587 26.301 61.75262 148.2129 -33.44784 62.12907 146.2005 26.58175 61.83185 147.587 -31.17963 62.22755 146.3904 -30.70571 62.13824 146.5252 30.79804 62.15238 146.5022 26.71584 61.86207 147.3315 -24.38381 62.94189 126.749 24.37521 62.92068 126.6707 30.90374 66.0083 138.0709 33.44463 62.1131 146.2181 -31.47583 62.33491 146.2546 -33.45971 62.30453 146.0181 35.26613 64.63383 142.4355 35.21612 64.24682 143.1409 35.19025 64.04673 143.5056 31.19846 62.23232 146.3838 -35.21685 64.24757 143.1408 -26.71583 61.86207 147.3315 -26.71896 61.86214 147.3307 33.45972 62.30453 146.0181 31.46147 62.32656 146.2643 -31.53394 62.38286 146.201 -34.42032 65.3198 138.2747 -33.31517 65.72644 138.1591 -33.31873 65.72512 138.1595 33.31518 65.72644 138.1591 33.3177 65.7255 138.1594 34.42004 65.3199 138.2746 -31.55338 62.43314 146.1488 31.5301 62.37826 146.2061 35.57656 64.9593 138.6592 35.57615 64.9629 138.6732 35.45657 65.13346 140.4447 -35.45702 65.13336 140.443 -35.57614 64.96293 138.6733 -35.57627 64.96186 138.669 -30.90374 66.0083 138.0709 -31.54961 63.26746 145.3128 31.55338 62.43314 146.1488 35.42966 65.08218 140.7122 35.37985 64.98733 141.2073 35.2896 64.81544 142.1045 -35.2661 64.65666 142.4226 -35.27988 64.77114 142.2216 -35.4303 65.07872 140.7113 -35.45335 65.12585 140.4799 -31.53583 64.19218 144.3862 -31.54043 64.1016 144.477 31.54962 63.26746 145.3128 -32.95159 64.04325 144.3938 -33.42774 63.95716 144.3021 -34.3256 63.79484 144.1293 -34.92541 63.68639 144.0138 33.85765 63.92849 144.2651 33.44108 63.9596 144.3032 20.8804 64.18925 121.1356 23.5715 63.25059 127.8888 -23.57149 63.25059 127.8888 -19.84265 64.5176 118.7733 -15.40824 65.71786 110.1381 16.70195 65.40104 112.4174 12.40171 66.34249 105.6444 12.73776 66.28726 106.0416 -22.37375 63.5872 129.1316 -16.31507 64.97019 120.1359 22.46363 63.56834 129.062 31.54043 64.1016 144.477 30.90429 66.02536 138.1339 22.257 63.61039 129.2173 17.16834 64.70024 122.4981 -30.90658 66.09645 138.3964 -21.08089 63.77379 129.8206 -30.9042 66.02268 138.124 -19.62515 63.83678 130.0532 30.90659 66.09645 138.3964 20.94103 63.78583 129.8651 -35.03522 64.06042 143.5636 -34.85727 64.10585 143.6441 19.62515 63.83678 130.0532 -34.27832 64.18766 143.8402 33.38168 64.45384 143.8395 33.63953 64.43139 143.8227 -33.39008 64.25207 144.08 33.33919 64.45753 143.8423 31.51433 64.61634 143.9612 -34.8427 64.10791 143.5976 -31.51432 64.61634 143.9612 -34.81005 64.11596 143.6033 -34.243 64.25582 143.7034 -35.0088 64.80583 142.457 -33.34714 64.47676 143.8616 -34.05444 64.3023 143.7367 33.40622 65.30776 142.7014 -32.90967 64.51072 143.8858 -33.34203 64.47801 143.8625 -34.28798 65.11654 142.499 31.37132 65.5256 142.7602 -33.16725 65.46548 142.5096 -12.669 65.95709 111.5007 -31.37325 65.53076 142.7662 13.73272 65.69659 113.78 -35.15781 65.28617 140.484 -34.44236 65.61077 140.491 33.39519 65.82171 141.3474 35.16044 65.15754 138.5845 35.14174 65.1257 138.6327 -35.1595 65.15985 138.5923 -35.15592 65.1643 138.6236 -34.43582 65.44819 138.4743 33.37005 65.99108 139.9054 -33.32701 65.98117 140.4894 34.43663 65.44668 138.4695 34.40615 65.40136 138.5641 -35.14199 65.17098 138.6219 -35.00426 65.23698 138.6057 -34.41668 65.42369 138.5593 -34.41021 65.42573 138.5588 31.36591 65.56002 142.7148 31.32169 65.68133 142.398 -33.31051 65.77247 138.3243 33.33021 65.80458 138.4639 -33.30111 65.77816 138.4712 33.31012 65.77253 138.3242 -31.32135 65.69049 142.4 -31.31862 65.69892 142.3807 -31.20828 66.03855 141.602 31.17796 66.07563 141.3685 31.14797 66.15795 141.1536 10.47327 66.42527 107.4041 -12.39689 66.31922 105.8117 -33.29281 65.7808 138.4706 -32.94937 65.88993 138.4435 33.30651 65.80743 138.4632 33.3029 65.80786 138.4631 30.9636 66.27738 139.4326 31.01229 66.24584 139.8871 -31.01488 66.29551 139.9993 7.515221 66.91123 103.1518 -9.056103 66.67858 105.1877 -31.06601 66.22756 140.423 -31.04911 66.25003 140.2829 31.05478 66.21833 140.2837 -11.01418 66.59535 103.8251 9.140137 66.87832 101.7893 -6.797607 67.15687 99.7853 -2.97982 67.4342 97.78995 3.110527 67.42831 97.83242 5.968369 67.23564 99.21858 1.2207e-4 67.49418 97.35852 0.2644501 67.49949 97.32025 -5.589146 67.14025 101.1479 4.907326 67.20503 100.5811 2.557548 67.36344 99.19498 -2.450073 67.3683 99.15251 0.2174377 67.42198 98.68281 + + + + + + + + + + -1.37278e-4 -0.001481413 -0.9999989 1.37278e-4 -0.001481413 -0.9999989 0.0922693 -0.9957318 -0.002143502 0.02011072 -0.9997978 6.01363e-5 -0.09226948 -0.9957341 5.98525e-5 0.02228158 -0.9996452 -0.01459896 -0.02653306 -0.9996119 -0.008498907 -0.01530295 -0.9984378 0.05373924 -0.01244038 -0.9982826 0.05724847 0.01197665 -0.9983377 0.05637776 0.01021218 -0.9983724 0.05611002 0.01240247 -0.9985113 0.05311626 0.0744692 -0.9972158 -0.003876864 0.03925466 -0.9972104 0.06348699 -0.06939345 -0.9975797 -0.004401087 -0.04093301 -0.9976861 0.054286 -0.03166586 -0.9976747 0.06035286 1.53731e-6 -0.9935321 0.113552 1.60835e-6 -0.9935358 0.1135197 0.04141777 -0.9979447 0.04889702 -2.5058e-6 -0.9935323 0.1135506 -0.1131618 -0.9935755 -0.001524269 -0.06697618 -0.9961919 0.05582165 -0.05103939 -0.9967619 0.06213593 -2.81169e-6 -0.993532 0.1135532 -7.11976e-7 -0.993533 0.1135447 0.1325337 -0.9911783 -5.63212e-4 0.06538695 -0.9953936 0.07011699 0.07609444 -0.9959199 0.04851126 -1.09111e-6 -0.9935328 0.1135455 -5.48653e-7 -0.9935327 0.1135465 -0.08956676 -0.9946553 0.05136829 -0.07956975 -0.9943056 0.07088857 -0.1620281 -0.9867861 7.88187e-5 0.09313845 -0.9929594 0.07319033 0.09592765 -0.9936584 0.05865997 0.1954153 -0.9807206 3.03322e-4 0 -0.9935327 0.1135467 -0.09850907 -0.9931311 0.06313896 -0.09521776 -0.9937872 0.05762445 -4.07157e-4 -0.001430988 -0.9999989 -0.2736625 -0.9618259 7.83666e-5 4.07156e-4 -0.001430988 -0.9999989 0.2736618 -0.9618241 -0.001942217 0.1954082 -0.980722 3.03488e-4 -0.1756679 -0.9843791 -0.01177471 0.1152597 -0.9916634 0.05761134 8.3727e-4 -0.9923691 -0.1233 -9.24103e-4 -0.9976044 0.06917095 -9.2393e-4 -0.997607 0.06913441 -5.02344e-4 -0.9873778 0.1583821 0.1026896 -0.9862574 -0.1294271 0.149243 -0.9862103 -0.07152593 0.1029525 -0.984004 0.1453852 -0.2270321 -0.9738702 -0.005794584 -0.1258288 -0.9902716 0.0594083 0 -0.9850955 -0.1720086 -0.1225335 -0.9765057 -0.1772629 -0.2144027 -0.9757195 0.04475492 -5.02367e-4 -0.9873991 0.1582501 0.1029867 -0.9840098 0.1453219 -0.1075069 -0.9856402 -0.1302144 -0.106809 -0.9926183 0.05745327 -3.03913e-4 -0.9976033 0.06919318 7.52927e-4 -0.987405 0.1582112 0.1029722 -0.984009 0.1453384 -0.1068035 -0.9926195 0.05744177 -1.4647e-4 -0.9338845 0.3575749 -0.001150429 -0.9164563 0.4001334 -0.001120686 -0.9165488 0.3999215 -0.1374633 -0.9840192 0.1131819 -0.1101325 -0.933254 0.3419182 0 -0.9652252 -0.2614201 2.61891e-5 -0.9652112 -0.2614716 -3.33169e-6 -0.9652259 -0.2614173 0 -0.9652212 -0.2614347 -0.1225852 -0.9576722 -0.2604551 0 -0.9652251 -0.2614203 -7.97758e-6 -0.9652258 -0.2614175 0 -0.9652269 -0.2614139 -3.19882e-6 -0.9652401 -0.2613651 0.1030608 -0.9598746 -0.2608048 -1.47484e-4 -0.9338529 0.3576576 -0.110132 -0.9332026 0.3420584 0.1602584 -0.9532985 0.2560063 0.08883887 -0.917541 0.3875902 3.35495e-4 -0.9652742 -0.2612385 1.8495e-5 -0.9652382 -0.261372 -0.1201464 -0.9636176 -0.238759 -0.1214098 -0.9569776 -0.2635406 -0.1215062 -0.9578454 -0.2603241 -2.07626e-4 -0.9651865 -0.2615627 0.121244 -0.9578431 -0.2604542 0.1298475 -0.8741407 -0.4679934 2.52283e-6 -0.9652249 -0.2614212 -2.63584e-6 -0.9652249 -0.261421 3.44217e-6 -0.9652246 -0.2614222 -5.92604e-6 -0.9652248 -0.2614214 -0.1285333 -0.9572473 -0.2591468 -0.1214861 -0.9577668 -0.2606221 5.5296e-6 -0.9652245 -0.2614228 -1.06288e-5 -0.9652257 -0.2614178 1.31318e-6 -0.9652248 -0.2614213 0.1214799 -0.9581031 -0.2593862 0.121509 -0.9570296 -0.263306 -0.1188974 -0.9843268 -0.1302467 -0.3249789 -0.9222337 0.2094609 -0.3678647 -0.9242541 0.1021275 -0.3989742 -0.9122455 -0.09288704 -0.3585142 -0.9244959 -0.129518 -0.1225927 -0.9838204 -0.1306464 0.3138457 -0.9446403 -0.095685 0.3084449 -0.9460637 -0.09912312 0.307484 -0.9463698 -0.09918618 0.3084412 -0.9460659 -0.09911459 0.3048585 -0.9190958 0.2496482 0.2894071 -0.9217338 0.2581672 0 -0.9935328 0.1135457 0.146472 -0.9878964 0.05105614 0.1233367 -0.9895863 0.07420951 0.3040771 -0.9524885 -0.01740652 -0.391458 -0.8956787 0.2109984 -0.3914687 -0.8956697 0.2110168 -0.3356493 -0.8815821 0.3318927 -0.1152979 -0.9289908 0.3516855 -0.1204615 -0.9636921 -0.2382993 -0.1229177 -0.9632736 -0.2387366 -0.2669394 -0.8327567 0.4850358 -0.2988496 -0.9198999 -0.2539154 0.303882 -0.9525522 -0.0173223 0.3040047 -0.9525084 -0.01757454 -0.298597 -0.9212598 -0.2492395 -0.3590185 -0.901673 -0.2410221 0.2241788 -0.9228695 0.3131387 0.3611752 -0.9007447 -0.2412708 0.3572339 -0.9022737 -0.2414252 0.2991405 -0.7917628 -0.5325662 -0.3627952 -0.8998589 -0.242144 0.1285284 -0.9569309 -0.2603147 0.3601784 -0.9007325 -0.2428016 -0.3572212 -0.9019173 -0.2427724 -0.3406984 -0.7745394 -0.5329292 0.3572418 -0.9019094 -0.2427708 0.2660183 -0.9639645 -0.002619624 0.08874386 -0.9170748 0.3887137 0 -0.9935325 0.1135486 -0.1273996 -0.9898537 0.06292009 -1.47727e-4 -0.9338487 0.3576683 9.95501e-5 -0.916616 0.399769 0.08883374 -0.9175347 0.3876066 -0.117545 -0.9327347 0.3408653 0.4105882 -0.9069956 -0.09368199 0.4025258 -0.8819808 0.2451182 0.3956411 -0.8842696 0.2480635 -1.2329e-4 -0.797028 0.6039426 -0.1026169 -0.7986693 0.5929563 -1.23489e-4 -0.7941595 0.6077094 0.1140664 -0.7954365 0.5952056 0 -0.7972761 0.603615 -0.102354 -0.7947304 0.5982702 -0.1080586 -0.7987599 0.5918666 0.09248739 -0.8099256 0.5791949 0.09259831 -0.8099025 0.5792095 0.2903459 -0.7899116 0.5401287 0.253214 -0.7966216 0.548887 0.3954094 -0.8543065 -0.3373602 0.263477 -0.9094418 0.3217071 0.2645965 -0.9090668 0.3218483 0.3413594 -0.7781633 -0.5271961 0.3951042 -0.8324126 -0.3885642 -0.2146348 -0.7744807 0.595073 -0.2668755 -0.832745 0.4850911 -0.3863201 -0.7577778 -0.5258609 0.3060955 -0.9506966 -0.04981553 0.3060333 -0.9507114 -0.04991626 -0.3555356 -0.9323465 -0.06576174 -0.2818611 -0.9594537 -0.001729547 -0.1581228 -0.985521 0.06120127 -0.3572729 -0.9018967 -0.2427724 -0.3530154 -0.8455808 -0.4004665 0.3572207 -0.9019177 -0.2427714 -0.3594124 -0.8071643 0.468304 -0.3594278 -0.8071815 0.4682626 -0.3048799 -0.7586247 0.5757924 -0.108922 -0.7939509 0.5981454 0.4676492 -0.8558986 0.220776 0.447625 -0.8922799 -0.05889463 0.4366678 -0.8976684 -0.0592693 0.4370514 -0.8974845 -0.05922675 0.4673849 -0.8560038 0.2209273 0.4510231 -0.8587553 0.2431414 0.438272 -0.8954908 -0.07754945 0.4374439 -0.8959176 -0.07729542 0.4395974 -0.8948307 -0.07766646 0.440527 -0.8736811 -0.2064394 0.4369187 -0.897691 -0.05703532 0.4530837 -0.8074228 -0.3778672 -0.4510192 -0.8673453 -0.2104616 -0.253616 -0.7588742 0.5998242 -0.3530179 -0.8455684 -0.4004903 -0.493842 -0.843476 0.2113488 -0.5180568 -0.8540406 -0.04724514 -0.5161528 -0.8548721 -0.05272758 -0.3555105 -0.9323563 -0.06575638 0.5180061 -0.8540638 -0.04737967 0.492073 -0.8421511 0.2205578 0.5161443 -0.8548775 -0.05272126 0.4923205 -0.8420128 0.2205331 -0.3607102 -0.9057393 -0.2225417 0.2902562 -0.773396 0.563569 0.2903113 -0.773379 0.5635637 0.3570078 -0.753614 0.5519163 -0.4938876 -0.843468 0.2112749 0.4923121 -0.8420231 0.2205129 0.3088182 -0.9255107 0.2192292 -0.3572497 -0.9008992 -0.246482 -0.3771037 -0.8936299 -0.2433487 0.357322 -0.9008724 -0.2464749 0.3771006 -0.8936305 -0.2433509 0.3571223 -0.9069153 -0.2235358 -0.4938557 -0.8434796 0.2113026 1.78415e-7 -0.9935327 0.1135462 0.1150313 -0.9905408 0.07481318 0.2509751 -0.9677819 -0.02024322 0.1548329 -0.9851952 0.07360178 0.5027238 -0.8414941 -0.1978806 -0.5000367 -0.8419377 -0.2027418 0.5008078 -0.841539 -0.2024936 -0.5009279 -0.8415156 -0.2022943 -0.4982404 -0.837104 -0.2258613 0.4981819 -0.8371363 -0.2258707 -0.5067229 -0.7402004 0.4419677 0.2900985 -0.7969073 0.5298885 0.4811422 -0.7117422 0.5117862 0.4912299 -0.7419337 0.4563196 0.508938 -0.7324997 0.4521353 0 -0.9935325 0.1135483 -0.05229294 -0.9939492 0.09659415 -0.1532919 -0.9871994 0.04403376 -0.2030166 -0.9791623 0.005047261 -0.1530414 -0.9871132 0.04675567 0.5089411 -0.7325027 0.4521269 0.2892472 -0.8231236 0.4886757 -0.448897 -0.7696148 0.4540756 -0.4958145 -0.8067229 0.3215063 0 -0.7078374 0.7063755 -0.1066248 -0.6870828 0.7187131 -0.1166108 -0.7059527 0.6985934 0 -0.7078217 0.7063911 0.09292745 -0.7071142 0.7009665 0.0912587 -0.7007097 0.7075859 0.3222466 -0.9466558 -2.38385e-4 0.09122806 -0.7006067 0.7076918 0.2850317 -0.6959143 0.659136 0.2329379 -0.7003472 0.6747249 0.2833588 -0.8855817 0.3680391 -0.1072313 -0.6871318 0.718576 -0.11693 -0.6869708 0.7172157 -0.1065304 -0.6823542 0.7232179 -0.007704317 -0.6541997 -0.7562827 -0.2759342 -0.8342459 0.4773824 -0.3046963 -0.7001615 0.6457045 -0.3058346 -0.7453057 0.5924395 0.2835777 -0.8855541 0.367937 0.2538462 -0.8902853 0.3780928 0.2342059 -0.9717051 -0.03060644 0.07826811 -0.7760245 0.6258276 0.2546681 -0.6023014 0.7565562 0.2484429 -0.602775 0.7582469 0.4458287 -0.7643258 0.4658784 0.4777043 -0.817658 0.3213007 0.2892958 -0.8231303 0.4886353 0.2892792 -0.823131 0.488644 0.2882441 -0.8239061 0.4879491 -0.4488754 -0.7695879 0.4541424 0 -0.7079558 0.7062568 6.1461e-7 -0.7078019 0.706411 -4.09605e-7 -0.7078306 0.7063823 0.07071793 -0.707949 0.7027143 -0.3409547 -0.9400797 1.80803e-4 -0.3610876 -0.9324225 -0.01428699 -0.2918843 -0.9563094 0.0166127 0.2542425 -0.5929328 0.7640625 0.3331724 -0.5845665 0.7397825 0.2342137 -0.9717194 -0.03009045 0.2342648 -0.9716871 -0.03072845 0.255361 -0.6623014 0.7043775 0.4476975 -0.6310629 0.6335034 -0.1166643 -0.7036094 0.7009446 0 -0.7078021 0.7064108 0.07071918 -0.7064201 0.7042511 0.2885515 -0.7122249 0.6399015 0.2547492 -0.7123422 0.653966 -0.4247437 -0.7075889 0.5647221 0.2553048 -0.6826887 0.6846573 0.1873074 -0.5909833 0.7846368 -0.4073207 -0.681518 0.6079665 -0.4186946 -0.6945225 0.5850926 -0.2988244 -0.7109078 0.6366429 0.4068676 -0.6808638 0.6090018 0.4186956 -0.6945133 0.5851028 -0.1163755 -0.5299414 0.8400112 -0.1877552 -0.6099263 0.7698948 0.2552046 -0.6826079 0.6847753 -0.2995436 -0.6750665 0.6742099 -1.04853e-5 -0.9652199 -0.2614393 0.2552236 -0.6826563 0.6847199 0.2552515 -0.6826513 0.6847145 -0.3910509 -0.6542953 0.6472843 0.3909953 -0.6543106 0.6473023 -0.1883751 -0.6955834 0.69331 0 -0.7078324 0.7063805 0.1854769 -0.7929844 0.5803224 0.09575641 -0.7047928 0.702921 0.3552239 -0.9347813 0 -6.63172e-4 -0.001331806 -0.9999989 -0.4316138 -0.9020574 -0.001471698 -0.4628306 -0.8864395 -0.003611564 -0.4783892 -0.878134 -0.004954636 -0.4920706 -0.8705327 -0.006281495 -0.4920606 -0.8705385 -0.00627774 -0.5100352 -0.8601139 -0.008276581 -0.4457386 -0.8951631 -2.41843e-4 -0.3799684 -0.9249995 1.8096e-4 6.63172e-4 -0.001331806 -0.999999 0.5043925 -0.8634409 -0.007623255 0.4855079 -0.8742144 -0.005601108 0.4855085 -0.8742141 -0.005600392 0.4641675 -0.8857397 -0.003703832 0.431613 -0.9020577 -0.001471579 0.3856834 -0.9226312 0 0.4457386 -0.8951632 1.74429e-5 0.5280887 -0.8491234 -0.01058399 0.516727 -0.8561016 -0.009132325 1.1715e-6 -0.9652246 -0.2614219 -0.3908218 -0.6529493 0.6487802 -0.2837367 -0.6768429 0.6792476 -0.09161931 -0.8753505 0.4747287 0.3907715 -0.6529631 0.6487966 0.2837387 -0.6768445 0.6792452 -0.06335872 -0.7073532 0.7040151 0 -0.7348653 0.6782131 -0.09574717 -0.6989572 0.7087252 -0.001027226 -0.8634181 0.5044881 0.001213252 -0.7200251 0.6939471 -1.92904e-4 -0.7850188 0.6194719 -5.49853e-4 -0.8279197 0.5608465 0.09572607 -0.7142612 0.6933019 0.0929234 -0.6995603 0.708506 9.17211e-4 -0.7446138 0.667495 0.09797215 -0.7374156 0.6682962 0.08399897 -0.6955216 0.7135783 -0.09094667 -0.6889813 0.7190504 -0.09476101 -0.7155779 0.6920756 4.83985e-4 -0.7840091 0.6207492 0.1049234 -0.7724753 0.6263172 0.05650681 -0.7195837 0.6921028 0.5845674 -0.8096338 -0.05267167 0.5543712 -0.7678067 0.3211629 0.5543745 -0.7678054 0.3211604 -0.08012533 -0.6893281 0.7200047 -0.09525239 -0.7410312 0.6646802 -0.5846729 -0.8095574 -0.05267268 -0.5846723 -0.809558 -0.05266994 -0.5544671 -0.7677364 0.3211653 -0.2837509 -0.6819363 0.6741279 0.2837538 -0.6796922 0.6763892 0.2843996 -0.6816133 0.6741812 1.63691e-6 -0.9652257 -0.2614179 -0.1285483 -0.9589358 -0.2528192 -0.07057595 -0.9627195 -0.2611325 -2.18254e-6 -0.9652258 -0.2614179 0.1285312 -0.9570384 -0.2599178 -0.05992096 -0.7215721 0.6897415 -0.0938692 -0.7774521 0.6218978 1.17399e-4 -0.8334006 0.5526694 0.1163491 -0.8122125 0.5716413 0.0390107 -0.7643888 0.6435744 0.5678616 -0.7864866 -0.242842 0.5845673 -0.8096339 -0.05266994 -0.5679515 -0.7864032 -0.2429015 -0.04641807 -0.762257 0.645608 -0.09971958 -0.8171049 0.567799 -1.24751e-4 -0.9018525 0.4320442 -4.32931e-5 -0.8903989 0.4551811 0.04650682 -0.772146 0.6337412 0.2850096 -0.6862704 0.6691805 0.283648 -0.6834938 0.6725921 -0.2846465 -0.6832268 0.6724416 -0.284136 -0.6798332 0.676087 -0.02436566 -0.8431007 0.5372036 -0.1307398 -0.8637255 0.4867088 -0.1059578 -0.8486164 0.5182886 6.80035e-4 -0.8889362 0.4580307 -4.35043e-5 -0.9019612 0.4318172 -2.28286e-4 -0.9448122 0.3276125 0.1084296 -0.870639 0.479824 0.02132076 -0.8414558 0.5399053 -0.02434968 -0.8431058 0.5371962 -0.0419746 -0.8523647 0.5212606 0 -0.9451768 0.326559 0.189005 -0.9081851 0.3734663 0.02304399 -0.899931 0.4354231 -0.2711062 -0.9283306 -0.2543696 -0.2711172 -0.9283272 -0.2543702 -0.1822082 -0.9492202 -0.2564785 -0.3771114 -0.8946075 -0.2397173 0.09640139 -0.9630703 -0.2514011 0.2263904 -0.9393485 -0.2576273 0.3770974 -0.8933361 -0.2444347 0.2874151 -0.6973317 0.6565981 0.2764581 -0.6905074 0.668409 -0.2840669 -0.6862463 0.669606 -0.2844279 -0.6874609 0.6682053 -0.4242435 -0.6401347 0.6405037 -0.4037472 -0.5590443 0.7241945 0.3910638 -0.6512833 0.6503069 0 -0.9820065 0.1888472 -0.05164051 -0.9140986 0.4021903 -0.1732317 -0.9527162 0.2496449 0 -0.9820013 0.1888746 -0.002607464 -0.984058 0.1778289 0.1744095 -0.9529089 0.2480846 0.1003891 -0.9524815 0.2875781 0 -0.9947774 0.1020683 0 -0.9934345 0.1144027 -0.03923934 -0.9633937 0.2652038 -0.1980382 -0.9799215 0.02312672 7.8203e-4 -0.9931084 0.1171973 0.02821785 -0.9908242 0.1321783 0 -0.993084 0.1174069 -0.1030056 -0.9800649 0.1698907 -9.95882e-5 -0.993085 0.1173979 3.99055e-5 -0.9920842 0.1255747 -0.02210199 -0.9454483 0.3250216 -0.1169959 -0.9773721 0.1762267 0 -0.9920834 0.1255813 -0.01181465 -0.9267854 0.3754057 0.122796 -0.9783263 0.1667302 0.1152394 -0.9777157 0.1754766 0.2538974 -0.9657804 0.05295795 0 -0.9900882 0.1404477 0 -0.990087 0.1404558 -0.1155903 -0.9778083 0.1747282 -0.1203612 -0.9789428 0.1648767 0.1185468 -0.978531 0.1685934 0.1138769 -0.9780957 0.1742438 0.4748901 -0.6577115 0.5847179 0.4748815 -0.6577097 0.584727 -0.4749773 -0.6576505 0.5847157 -0.5544688 -0.7677363 0.3211628 -0.2791669 -0.6934502 0.6642234 -0.2829959 -0.6994265 0.6562895 0 -0.9881002 0.1538113 0 -0.9880976 0.153828 -0.1158409 -0.9790865 0.1672442 -0.1139254 -0.978125 0.1740474 0.1145024 -0.9784217 0.1719888 0.1136795 -0.9781588 0.1740187 0.4236533 -0.6364193 0.644584 0.411462 -0.5698676 0.7113018 0.2905577 -0.7116722 0.6396084 0.2678406 -0.7036148 0.6581701 -0.4236004 -0.6359475 0.6450842 0 -0.9867312 0.1623631 -0.1140809 -0.9784958 0.171848 -0.1136801 -0.9781588 0.174018 0 -0.9867326 0.1623545 0.1134391 -0.9779641 0.1752651 0.1138343 -0.9781382 0.1740335 0 -0.9856249 0.1689484 -0.1137042 -0.9779242 0.1753159 -0.1137918 -0.9781004 0.1742735 -2.13876e-5 -0.9856247 0.1689494 2.11348e-5 -0.9848571 0.1733682 0.1134447 -0.9774892 0.1778908 0.1140238 -0.978074 0.1742696 -0.3717005 -0.9143291 0.1607518 -0.1989868 -0.8858605 0.419113 -0.1138669 -0.9774491 0.1778417 -0.1140035 -0.9780485 0.1744259 0 -0.9848542 0.1733843 0.1137272 -0.9770637 0.1800357 0.1143375 -0.9780206 0.1743638 0 -0.9836471 0.1801065 -0.11433 -0.9770106 0.179942 -0.1143537 -0.9779738 0.1746152 0 -0.983644 0.1801239 0.1143339 -0.97647 0.1828503 0.1153746 -0.9778617 0.1745715 -0.2722615 -0.7040064 0.6559334 -0.2829716 -0.7144468 0.6399163 0.2951494 -0.7279523 0.6188476 0.250635 -0.7327197 0.6326959 -0.3717002 -0.9143222 0.1607918 -0.04744726 -0.7458675 0.6644023 -0.3952608 -0.8995134 0.1861308 -0.3953588 -0.89945 0.1862292 -0.3120937 -0.8982712 0.3093647 0.2538896 -0.9657839 0.05293005 0.1938401 -0.8451731 0.4981051 0.3952608 -0.8995134 0.1861308 0.3181639 -0.894564 0.31389 0.4230433 -0.6300091 0.6512472 -0.1989672 -0.885907 0.4190237 -0.3306767 -0.9038352 0.2715419 0.3859532 -0.9106227 0.1476699 0.3813878 -0.9107015 0.158639 0.3208853 -0.90872 0.2669467 0.1653635 -0.9672573 0.1925309 0 -0.9814632 0.1916508 -0.1161313 -0.9763091 0.1825762 -0.1154358 -0.9777424 0.1751983 0 -0.981461 0.1916623 0.1165914 -0.9753611 0.1872894 0.1176823 -0.9775335 0.1748689 -0.4185678 -0.6324084 0.6518133 -0.4234572 -0.6341571 0.646938 -0.3616049 -0.9254935 0.1127117 -0.3322103 -0.9152765 0.2278276 0.3543152 -0.9239116 0.1443896 0.329594 -0.9163633 0.2272581 0.4037492 -0.8874428 0.2223329 0.2631494 -0.8629063 0.4314453 -0.3457996 -0.9285089 0.1352553 -0.3346711 -0.9207332 0.2006133 0.3409665 -0.9253414 0.1657865 0.3336957 -0.9211056 0.2005285 -0.2829693 -0.728278 0.6241312 -0.2653572 -0.7163728 0.6452872 -0.3371887 -0.927025 0.1640992 -0.3356958 -0.9246416 0.1798511 0.3346096 -0.9229111 0.1904513 0.3358088 -0.9246107 0.179799 -0.2092465 -0.7849387 0.5831699 -0.410366 -0.8501498 0.3299171 0.4047029 -0.8495075 0.3384562 0.2092501 -0.7849372 0.5831709 -0.3351485 -0.9227589 0.1902413 -0.3364918 -0.9269211 0.1661039 0.334256 -0.9188954 0.2095336 0.3371233 -0.9267157 0.1659693 0 -0.9780124 0.2085471 -0.1203423 -0.9751313 0.186109 -0.1179431 -0.9773078 0.1759517 0.001000463 -0.9701961 0.2423189 0.001603364 -0.9674057 0.2532269 3.90382e-4 -0.9740014 0.2265418 0.001981139 -0.9657985 0.2592862 -0.001435816 -0.9779312 0.2089222 0.1217688 -0.9737833 0.1921424 0.1223555 -0.9769966 0.1746623 -0.4749776 -0.657655 0.5847104 -0.3367608 -0.9181735 0.2086858 -0.3370061 -0.9302785 0.1449448 0.3361701 -0.9125655 0.2328388 0.339663 -0.9294003 0.1443753 -0.3461945 -0.9109196 0.2244436 -0.3362399 -0.9352392 0.1107719 0.3479901 -0.9022777 0.2545545 0.3433811 -0.9329577 0.1080715 -0.5404003 -0.8113902 -0.2227409 -0.483034 -0.8441277 -0.2326516 -0.3888458 -0.8894328 -0.2402257 0.5523307 -0.8039352 -0.2204973 0.5440674 -0.8081952 -0.2254136 0.463091 -0.854374 -0.2357796 0.3570358 -0.9028146 -0.2396898 0.2573115 -0.9383575 -0.2308161 -0.3864837 -0.7818488 0.4892267 -0.3864452 -0.7818689 0.4892252 -0.2799775 -0.7455485 0.6047894 0.3864681 -0.7818598 0.4892216 -0.1283479 -0.973663 0.1884341 -0.3686086 -0.9020513 0.2245686 -0.3328092 -0.9407603 0.06487035 0.372453 -0.8953264 0.2442737 0.3483452 -0.9357635 0.05479532 -0.1250841 -0.9755094 0.1809292 -6.23183e-4 -0.9739793 0.2266364 0.1220069 -0.9756827 0.1820929 0.1211507 -0.9776342 0.1719126 -0.1179568 -0.9777742 0.1733313 -0.3507992 -0.9345018 0.0603851 -0.399976 -0.8986452 0.1801561 0.3528894 -0.9337844 0.05929452 0.3539836 -0.9327965 0.06772387 -0.1272087 -0.972844 0.1933714 -1.73208e-4 -0.9702718 0.2420175 0.124045 -0.973001 0.194633 0.1228441 -0.9752358 0.1839141 -0.4126359 -0.6294183 0.6584561 0.4119931 -0.6290563 0.659204 0.4228402 -0.6345819 0.6469249 -0.1195793 -0.9753466 0.185472 -0.3553758 -0.9324851 0.06465017 -0.3561616 -0.9320644 0.06637138 0.3575166 -0.9317467 0.06348353 0.3588643 -0.9305887 0.07225847 -0.128576 -0.9705146 0.2038866 -3.83214e-5 -0.9675599 0.2526421 0.1250296 -0.9706813 0.2052936 0.1180503 -0.9761251 0.1823297 -0.4200302 -0.8436254 0.3344709 -0.4064251 -0.8417365 0.3553847 -0.1150008 -0.9762883 0.1834017 -0.3680668 -0.9258783 0.08530163 -0.3610854 -0.9298396 0.07082164 0.3628181 -0.9277414 0.08751565 0.3536106 -0.9337444 0.05550682 -0.1285468 -0.9685532 0.2130271 0 -0.9659695 0.258656 0.1250972 -0.9687195 0.2143207 0.1190255 -0.9741078 0.192216 -0.390632 -0.901535 0.1861217 -0.4300377 -0.8728294 0.2307303 -0.4409544 -0.8753678 0.1982186 0.430075 -0.8728162 0.2307111 0.4382928 -0.8748629 0.2061902 0.4433479 -0.8778648 0.1810967 -0.4451928 -0.8801146 0.1649301 0.3914789 -0.9009392 0.1872242 0.4474389 -0.8823025 0.1460852 -0.4188773 -0.8723995 0.2519146 0.4188594 -0.8724102 0.2519075 -0.4467445 -0.8839102 0.1382834 -0.1160639 -0.9742715 0.1931948 -0.3688243 -0.9240207 0.1007703 -0.3489006 -0.9354059 0.05730801 0.3636522 -0.9258406 0.1028412 0.3556485 -0.9318552 0.07183527 0 -0.9632415 0.2686373 -0.1306677 -0.9650048 0.2273585 0 -0.9632422 0.2686346 0.1231104 -0.9653967 0.2298979 0.122507 -0.9703745 0.2082441 -0.4431835 -0.8900647 0.1066455 0.4431834 -0.8900731 0.1065772 -0.4329248 -0.8176265 0.3795564 -0.4510182 -0.8607059 0.2361527 0.4108443 -0.8750957 0.2557625 -0.1160427 -0.9707553 0.2101622 -0.3731843 -0.9192354 0.1254588 -0.3510239 -0.9334754 0.0735253 0.361711 -0.9232276 0.1296765 0.3618057 -0.927042 0.09843736 -0.4343489 -0.8960824 0.09152883 0.4343762 -0.8960689 0.09153097 -0.4338066 -0.8170879 0.3797094 0.481864 -0.8367272 0.2601825 0.4437633 -0.7696574 0.4590226 -0.4606301 -0.6615908 0.5917074 -0.3884895 -0.6444113 0.6586426 -0.4273207 -0.8078251 0.4059749 0.4330403 -0.7524847 0.4962288 -0.4142619 -0.7872111 0.4568214 0.4165536 -0.724993 0.5485147 -0.4676257 -0.8808175 0.07407212 -0.4466247 -0.8769496 0.1774427 0.4881864 -0.8704649 0.06296801 0.3860778 -0.643567 0.6608824 0.4637058 -0.6660225 0.5842866 0 -0.9591718 0.2828241 -0.1298901 -0.9597815 0.248894 0 -0.9591714 0.282826 0.123106 -0.960187 0.2507705 0.1239046 -0.9647625 0.2321225 -0.4688431 -0.8832582 -0.006421327 0.4919645 -0.852365 0.1773273 0.4996696 -0.8657804 -0.02747404 -0.1181293 -0.9651541 0.2335019 -0.3732667 -0.9134037 0.1623752 -0.3515717 -0.9306056 0.1018365 0.3626363 -0.9170727 0.1657487 0.3646598 -0.9208755 0.1378827 0 -0.9570313 0.2899848 -0.1274468 -0.9555398 0.2658967 0 -0.9570347 0.2899739 0.1224376 -0.9559065 0.2669308 0.1256173 -0.9575311 0.2595277 -0.4699923 -0.8826627 -0.003722548 0.4999073 -0.8657074 -0.02536422 -0.3854812 -0.6425672 0.6622021 -0.3552221 -0.9241527 0.1405671 -0.3709884 -0.9079065 0.1951245 -0.1218584 -0.9578635 0.2600928 -0.3701472 -0.9041892 0.2131504 0.3701479 -0.9041892 0.2131487 0.3709878 -0.9079068 0.1951242 -0.3865089 -0.7814301 0.4898754 0.3850027 -0.6836147 0.6200354 -0.4974097 -0.8667383 -0.03672349 -0.5115566 -0.8586358 0.03247249 -0.4977423 -0.86732 -0.002956748 0.4974113 -0.8667376 -0.03671401 0.4977424 -0.86732 -0.002945721 -0.4993629 -0.866238 0.01638472 0.4993671 -0.8662358 0.01637828 -0.38647 -0.7814552 0.489866 0 -0.9570302 0.2899882 -0.1243814 -0.9487873 0.2903997 0 -0.9570327 0.2899804 0.2424511 -0.9268885 0.2865229 0.1348947 -0.8909793 0.433543 -0.5044972 -0.8620827 0.04791802 0.5044949 -0.8620844 0.047912 -0.4359925 -0.7318137 0.5237932 -0.4424933 -0.7375791 0.5100753 0.4424967 -0.7375811 0.5100694 -0.5036958 -0.8454651 0.1774242 -0.5206643 -0.8490715 0.08936679 0.5206644 -0.8490709 0.08937138 -0.220677 -0.8738051 0.4333202 -0.3711045 -0.8258722 0.4245193 -0.3584861 -0.9123967 0.1975355 0.3584855 -0.9123951 0.1975435 0.2206465 -0.8738109 0.433324 0.3649912 -0.8899297 0.2735081 0.5702881 -0.789845 -0.2256467 0.5845749 -0.8096283 -0.05267214 -0.6108427 -0.7589495 -0.225537 -0.5516833 -0.8029913 -0.2255011 -0.5692098 -0.7881483 -0.2341426 -0.5846693 -0.8095598 -0.05267554 -0.5037139 -0.845457 0.177412 0 -0.9570324 0.2899811 -0.2393343 -0.9196664 0.3113404 0 -0.9570309 0.2899862 2.51586e-6 -0.9569815 0.290149 0.2393664 -0.9196971 0.3112254 -0.239065 -0.9193933 0.3123521 -0.2394355 -0.9201824 0.3097339 0 -0.9570297 0.2899905 0.2392824 -0.9193332 0.3123626 0.2389405 -0.9191218 0.3132454 0.239441 -0.9202069 0.3096569 -0.4917243 -0.854131 0.169315 -0.5145924 -0.8536624 0.08034354 0.560966 -0.8137528 0.1520646 -0.4917191 -0.8541315 0.1693275 0.4917197 -0.8541319 0.1693239 0.4974125 -0.863789 0.08030849 0 -0.9570326 0.2899806 -0.1207639 -0.9451658 0.3034431 -0.2709397 -0.9618432 -0.03807234 -0.2391577 -0.9190641 0.3132489 0 -0.9570307 0.289987 0.1198983 -0.9453056 0.3033512 0.3578209 -0.8894673 -0.2842746 0.2391357 -0.9190613 0.313274 -0.1267051 -0.9916894 -0.02231782 -0.06534326 -0.9978628 0 0 -1 0 0.1217204 -0.9925645 0 0.1258294 -0.992048 -0.002783 -0.06312215 -0.9640015 0.2582957 -0.06312865 -0.9639983 0.2583066 0 -0.9659262 0.2588177 0.1176308 -0.9592211 0.2570176 -0.2394476 -0.9202643 0.3094811 -0.2435467 -0.9293341 0.2775304 0.2394584 -0.9203016 0.3093616 -0.4917775 -0.8297618 0.2639135 -0.5119717 -0.8250916 0.2389745 0.5178518 -0.8146306 0.2611642 -0.1951694 -0.9807689 0.001161515 -0.1885471 -0.9474835 0.2583119 0.3058122 -0.9520909 0.001398921 0.2954351 -0.9197788 0.258312 0.1176129 -0.959227 0.2570034 0.3059085 -0.95206 0.001398682 0.3731185 -0.9275083 -0.02260416 -0.3547747 -0.8795319 0.3171099 -0.3740711 -0.9273972 -0.002331137 -0.1952336 -0.9807561 0.001161038 0.2955262 -0.919755 0.2582926 0.2955155 -0.9197568 0.2582985 -0.1886723 -0.9474589 0.2583107 -0.1885505 -0.9474825 0.2583129 -0.3772701 -0.9261034 0 -0.3645993 -0.8950188 0.2569221 -0.3645958 -0.8950126 0.2569481 0.4748814 -0.657714 0.5847222 0.4787461 -0.5931447 0.6472879 0.4357812 -0.6035574 0.6676926 -0.4749631 -0.6576498 0.5847281 -0.4462076 -0.6178294 0.6474455 -0.04625529 -0.7063621 0.7063378 -0.0462346 -0.7063506 0.7063506 0 -0.7071062 0.7071074 0 -0.707112 0.7071017 0.08637475 -0.704463 0.7044652 -0.1381585 -0.6942551 0.7063443 -0.1381573 -0.6942535 0.706346 0.4299025 -0.9028754 0 0.4153186 -0.8722463 0.2582578 -0.4826749 -0.8176292 0.3138592 0.4957819 -0.8349331 0.238929 0.4826609 -0.8176188 0.3139076 0.2165303 -0.6739425 0.7063401 0.08633494 -0.7045249 0.7044082 -0.4823659 -0.8171375 0.3156098 0.4823673 -0.8171359 0.315612 0.4805855 -0.8698194 -0.1115884 -0.2678028 -0.6574228 0.7043274 -0.2678 -0.6574192 0.7043318 0.6674281 -0.742809 -0.05267488 0.6674286 -0.7428087 -0.05267226 0.6329506 -0.704435 0.3211618 0.6329519 -0.7044333 0.3211631 -0.6674983 -0.7427461 -0.05267286 -0.633022 -0.7043715 0.3211604 0.6511067 -0.7246438 -0.2257245 0.6101369 -0.7580746 -0.2303389 -0.651175 -0.7245807 -0.2257301 -0.6674969 -0.742747 -0.05267661 -0.5342178 -0.845347 3.05453e-5 -0.4830194 -0.8464424 -0.2241151 0.4829908 -0.8537926 -0.1943149 -0.5381699 -0.7826562 0.3127657 -0.4188016 -0.5315616 0.7362387 -0.4982062 -0.7414181 0.4495441 -0.5411463 -0.785547 0.3001278 0.5398079 -0.7815692 0.3126614 0.4187989 -0.531557 0.7362436 0.4982014 -0.7414209 0.4495449 0.4153149 -0.8722432 0.2582739 0.304349 -0.6391595 0.706291 0.2165352 -0.6739537 0.7063278 -8.96603e-4 -0.001187264 -0.9999989 -0.5455767 -0.838061 -1.63357e-4 -0.5342078 -0.8453534 3.05494e-5 -0.5341646 -0.8453806 3.10546e-5 -0.5342383 -0.8453339 3.01379e-5 -0.5725547 -0.8198664 -6.15637e-4 -0.6269924 -0.7790139 -0.004247725 -0.6026344 -0.7980165 -0.001244843 -0.5342107 -0.8453514 3.05695e-5 8.96603e-4 -0.001187264 -0.9999989 0.6026325 -0.7980148 -0.002600729 0.5725552 -0.819866 -6.1567e-4 0.545768 -0.8379365 -1.56878e-4 0.5415521 -0.8406673 -9.02342e-5 0.5415681 -0.8406569 -9.09652e-5 0.5415499 -0.8406687 -9.09503e-5 0.5301148 -0.8479259 1.75158e-5 0.5301058 -0.8479315 1.7515e-5 0.5025022 -0.8556191 -0.124127 0.4897835 -0.8400493 -0.2333012 -0.4831253 -0.8464004 -0.2240453 -0.5576218 -0.8298205 -0.02135413 -0.5709865 -0.8200995 0.03757005 -0.5559489 -0.8273287 0.08030045 -0.555947 -0.8273302 0.08029913 0.5575948 -0.8297802 0.02351576 0.5559477 -0.8273295 0.08030033 -0.566586 -0.8240026 0 0.5404608 -0.7860279 0.3001039 0.5290127 -0.8486139 0 0.5649214 -0.8215814 -0.07660216 -0.5229766 -0.8389326 -0.1506243 -0.511025 -0.8197526 0.258571 -0.5110289 -0.8197543 0.2585588 0.5110293 -0.8197511 0.2585681 -0.4923719 -0.8490701 -0.191442 -0.4903374 -0.8399088 -0.2326427 0.5025448 -0.8555958 -0.1241147 -0.5616074 -0.817383 -0.1283833 0.5616213 -0.8173757 -0.1283688 -0.4914776 -0.7059148 0.5100334 0.4914686 -0.7059226 0.5100315 0.4914912 -0.7059087 0.510029 -0.5416097 -0.8059899 0.2388286 -0.5416069 -0.8059926 0.2388268 0.5416067 -0.8059923 0.2388278 0.5559482 -0.8273293 0.08029872 0.5421816 -0.6034313 0.5847305 -0.5422487 -0.6033772 0.5847241 -0.5422521 -0.603376 0.5847222 -0.633009 -0.7043801 0.3211672 -0.01693171 -0.2587851 0.9657865 -0.01693415 -0.2587769 0.9657887 0 -0.2588136 0.9659273 0 -0.258815 0.965927 0.03170967 -0.258685 0.9654412 -0.5627961 -0.8264073 -0.01765561 -0.5017906 -0.8469856 -0.1755608 0.5627937 -0.8264091 -0.01764482 0.5292229 -0.8413284 -0.1099539 -0.05062127 -0.2543448 0.965788 -0.05063521 -0.2543448 0.9657872 -0.37426 -0.6003748 0.7067387 -0.3742644 -0.6003763 0.7067351 0.3742619 -0.6003718 0.7067403 0.5110285 -0.8197546 0.2585586 0.3043305 -0.6391509 0.7063068 0.5331642 -0.8440502 -0.05757832 -0.562316 -0.8076645 0.1774229 -0.4914731 -0.7059142 0.5100386 0.5623052 -0.8076715 0.1774252 0.5623296 -0.8076573 0.1774126 -0.5033912 -0.8512416 -0.1482739 0.07930964 -0.2469061 0.9657885 0.03167229 -0.258728 0.9654309 0.5334849 -0.8438617 -0.05737197 -0.5623232 -0.8076584 0.1774274 0.5712595 -0.8204917 -0.0213558 -0.09836339 -0.2414471 0.965416 -0.09834659 -0.2414469 0.9654178 -0.5596635 -0.8282288 0.02852618 -0.5063105 -0.8494856 -0.1484046 0.5595957 -0.8282778 0.02844148 0.5369521 -0.8418172 -0.05501323 -0.5070758 -0.8513037 -0.1347448 0.5350346 -0.8434692 -0.04793614 -0.5582817 -0.8285446 0.04284352 -0.542775 -0.839652 -0.01949191 0.5582495 -0.828565 0.04286861 0.5434744 -0.8392326 -0.01801568 0.5422009 -0.6034288 0.5847153 0.5094017 -0.5669343 0.6473758 -0.4728566 -0.5858496 0.6581694 -0.5094465 -0.5668779 0.6473901 -0.5687557 -0.8144069 -0.1151449 0.5687557 -0.8144069 -0.1151449 0.1115075 -0.2341731 0.9657791 0.07930624 -0.2469121 0.9657872 0.5416072 -0.8059927 0.2388256 -0.1370503 -0.2198454 0.9658598 -0.137053 -0.2198463 0.9658592 0.1370475 -0.2198463 0.96586 0.3742652 -0.6003777 0.7067334 0.1115157 -0.2341708 0.9657786 -2.93151e-5 0 1 0 0 1 3.693e-5 0 1 -1.01387e-5 0 1 4.29679e-6 0 1 0.1370526 -0.2198458 0.9658595 -0.6187545 -0.7854053 -0.0167737 -0.6277275 -0.7777107 0.03353315 -0.5712548 -0.8204948 -0.0213626 -0.6168513 -0.782974 0.08028876 -0.6168497 -0.7829753 0.08028811 0.5712599 -0.8204913 -0.02135878 0.6186661 -0.7852749 0.02440422 0.616849 -0.7829755 0.08029133 -0.5623422 -0.8076459 0.1774246 0.5623307 -0.8076533 0.1774273 -0.5402498 -0.6693241 0.5100347 0.5402212 -0.6693423 0.5100412 0.5402637 -0.6693226 0.5100221 -0.6009431 -0.7627851 0.238802 -0.6009442 -0.7627846 0.238801 0.6009423 -0.7627859 0.2388014 0.6009452 -0.7627842 0.2387999 0.6168496 -0.7829756 0.08028745 -0.6889086 -0.6890048 0.2251166 -0.6040863 -0.7969156 -0.002304732 -0.5835408 -0.7698206 0.258566 -0.5835487 -0.7698155 0.258564 0.6040883 -0.7969167 0.001137077 0.5835442 -0.7698186 0.2585646 -0.6228209 -0.773846 -0.1151369 -0.6228236 -0.7738459 -0.1151238 0.6228219 -0.7738473 -0.1151235 -0.6181054 -0.7658092 0.1774315 -0.5402317 -0.6693398 0.5100334 0.6181049 -0.7658098 0.1774314 0.6181061 -0.7658082 0.177434 0.6269978 -0.7790206 -7.62112e-4 0.6228198 -0.7738477 -0.115132 -0.618109 -0.7658067 0.1774303 0.6280297 -0.7780937 -0.01220619 -0.4273644 -0.563802 0.706744 -0.4273765 -0.5638018 0.7067369 0.5835485 -0.7698144 0.2585672 0.4273741 -0.5638055 0.7067353 -0.1564932 -0.2064539 0.9658606 -0.156505 -0.2064521 0.9658591 0.4273736 -0.5637972 0.7067422 0.1565026 -0.2064523 0.9658594 0.7427014 -0.6675482 -0.05267143 0.7422692 -0.6680285 -0.05267357 0.7043279 -0.633068 0.3211654 0.7043362 -0.6330602 0.3211625 -0.7427436 -0.6675012 -0.05267 -0.7043769 -0.6330167 0.321159 0.7232721 -0.651728 -0.2283158 0.6632059 -0.7126244 -0.2287455 -0.663206 -0.7126266 -0.2287382 -0.7126253 -0.6632075 -0.2287378 -0.7245789 -0.6511767 -0.2257306 -0.7427464 -0.6674983 -0.05266815 0.724048 -0.6507802 -0.22856 0.7427033 -0.6675459 -0.05267202 0.6032464 -0.5423926 0.5847257 0.6033456 -0.5422933 0.5847154 -0.6033741 -0.5422549 0.5847218 -0.7043723 -0.633018 0.3211663 -5.9359e-6 0 1 1.15063e-6 0 1 0.1564926 -0.2064543 0.9658606 0.5152822 -0.5531619 0.6545963 0.5613175 -0.5063431 0.6546292 -0.5152906 -0.5531738 0.6545795 -0.6033828 -0.5422499 0.5847173 -0.56248 -0.5054995 0.6542833 0.6033533 -0.5422893 0.5847113 0.5531907 -0.5153046 0.6545544 0.5668406 -0.5094837 0.6473934 -0.5862919 -0.6293929 0.5100258 0.5862848 -0.6293938 0.5100331 0.5862866 -0.6293872 0.510039 -0.6787287 -0.7343891 0 -0.6815197 -0.7316409 0.01524919 -0.6765347 -0.732021 0.08028721 -0.6765339 -0.7320219 0.08028668 0.6786643 -0.7343204 0.01372778 0.6765317 -0.7320237 0.08028781 -0.6590847 -0.7131478 0.2388044 -0.6009382 -0.7627892 0.2388011 -0.6590896 -0.7131446 0.2388008 0.6590846 -0.7131485 0.2388024 0.6009379 -0.7627889 0.2388032 0.6765339 -0.7320218 0.08028715 -0.6707833 -0.7201182 0.1774247 -0.5862858 -0.6293851 0.5100427 0.6707844 -0.7201172 0.177425 0.6708045 -0.7200952 0.1774386 -0.6767391 -0.7271676 -0.1151157 -0.6767337 -0.7271703 -0.11513 0.6767328 -0.727172 -0.1151238 0.6767328 -0.7271707 -0.1151331 -0.6812666 -0.7320355 3.61547e-4 0.6812666 -0.7320355 3.61667e-4 -0.6708084 -0.7200922 0.1774353 0.6816033 -0.7317219 0 -0.6745563 -0.6744596 0.3001302 -0.5890775 -0.7477148 0.3064478 0.6745074 -0.6745074 0.3001326 0.5890745 -0.7477203 0.3064404 0.7070248 -0.7071851 -0.002323389 -0.674144 -0.7385964 -0.002324342 -0.6512203 -0.7134807 0.2585683 -0.6512245 -0.7134783 0.2585641 0.6741442 -0.7385961 -0.002322196 0.6512189 -0.7134837 0.2585635 -0.661481 -0.6614887 0.3533776 -0.6197077 -0.5727282 0.5366048 -0.6386758 -0.6910412 0.3384605 -0.7048375 -0.7048375 -0.08005183 0.6614888 -0.6614847 0.3533703 0.7048372 -0.7048379 -0.08005177 0.6590884 -0.7131448 0.2388034 0.5727207 -0.6197063 0.5366145 -0.4769503 -0.5225373 0.7067343 -0.4769405 -0.5225399 0.706739 0.6512219 -0.7134787 0.2585697 0.4769436 -0.522538 0.7067383 -0.001099467 -0.001002311 -0.999999 -0.7390069 -0.6736935 -0.002408087 -0.7320306 -0.6812698 -0.00166589 -0.681271 -0.7320313 3.61544e-4 0.001099467 -0.001002311 -0.9999989 0.6812696 -0.7320325 3.61634e-4 0.739008 -0.6736938 -0.001956045 -0.6767328 -0.7271708 -0.115132 0.6767311 -0.7271742 -0.1151211 -0.174647 -0.1913478 0.9658594 -0.1746508 -0.1913457 0.9658592 0.4769401 -0.5225411 0.7067383 0.1746548 -0.1913453 0.9658586 -8.69668e-6 0 1 0.1746392 -0.1913473 0.965861 -0.5601381 -0.5217762 0.6434244 -0.629391 -0.5862838 0.5100376 0.6293732 -0.5862944 0.5100474 0.6293885 -0.5862805 0.5100445 -0.7200998 -0.6708008 0.1774336 -0.6293677 -0.5862944 0.5100541 0.720102 -0.6708006 0.1774251 0.7201126 -0.6707945 0.1774051 -0.7271549 -0.676751 -0.1151251 -0.7271634 -0.676741 -0.1151309 0.727165 -0.6767383 -0.115136 0.7134093 -0.6639387 -0.2241267 0.7320296 -0.681267 -0.002827882 0.7271542 -0.676755 -0.1151065 -0.7201076 -0.6707956 0.1774217 -0.7317206 -0.6816048 0 0.7343904 -0.6787273 0 0.7316355 -0.6815255 0.01525014 -0.7343202 -0.6786645 0.01372373 -0.7320219 -0.6765338 0.08028763 -0.7320222 -0.6765331 0.08029085 0.732024 -0.6765314 0.08028751 -0.7131448 -0.6590882 0.2388039 -0.7131435 -0.6590906 0.238801 0.7131448 -0.6590871 0.2388068 0.7320218 -0.6765337 0.08028912 0.7131453 -0.6590887 0.238801 0.691053 -0.6386632 0.3384598 0.809536 -0.5847025 -0.05267328 0.8095329 -0.5847069 -0.05267399 0.7677133 -0.5544979 0.3211674 0.7677195 -0.5544924 0.3211622 -0.8095576 -0.5846726 -0.0526731 -0.8095554 -0.584676 -0.05267012 -0.8095558 -0.5846754 -0.05266946 -0.7677358 -0.5544685 0.3211644 0.7881302 -0.5692387 -0.2341327 -0.7580731 -0.6101388 -0.2303387 -0.7897753 -0.5703859 -0.2256438 -0.7385961 -0.6741442 -0.002325117 -0.7134749 -0.6512269 0.2585677 -0.7134776 -0.6512217 0.2585729 0.7385968 -0.6741434 -0.002325117 0.7134755 -0.6512246 0.2585716 -0.522552 -0.4769392 0.7067309 -0.5225315 -0.4769461 0.7067413 0.713485 -0.6512147 0.2585707 0.5225438 -0.4769399 0.7067365 0.6576476 -0.4749909 0.5847079 0.6576219 -0.4749944 0.5847339 0.6576434 -0.474988 0.584715 -0.6576495 -0.4749732 0.5847201 -0.6576536 -0.4749701 0.584718 -0.7677304 -0.5544761 0.3211644 0.5858518 -0.4728559 0.658168 0.6178197 -0.4462316 0.6474384 -0.6035397 -0.435891 0.6676367 -0.1913564 -0.1746466 0.9658578 -0.19134 -0.1746495 0.9658606 0.5225417 -0.4769414 0.7067369 0.1913555 -0.1746488 0.9658576 -0.593152 -0.4787477 0.6472799 -0.669347 -0.5402259 0.5100301 0.6693207 -0.5402402 0.5100495 0.6693291 -0.5402436 0.5100347 1.37496e-5 0 1 -1.00403e-6 0 1 0.1913371 -0.1746478 0.9658615 -0.7657979 -0.6181175 0.1774389 -0.6693096 -0.5402578 0.5100454 0.7657968 -0.6181188 0.1774386 0.765824 -0.6180949 0.1774052 -0.8081933 -0.5440716 -0.2254105 -0.7864019 -0.5679526 -0.2429038 0.802991 -0.5516849 -0.2254979 0.8113867 -0.5404065 -0.2227385 0.7863811 -0.5679773 -0.2429133 0.7589502 -0.6108433 -0.2255331 0.8095388 -0.5846989 -0.05267155 -0.7658256 -0.6180898 0.1774158 -0.7780952 -0.6280277 -0.01221096 0.7854019 -0.6187589 -0.01677483 0.7777157 -0.6277214 0.03353005 -0.7738376 -0.6228289 -0.1151499 -0.7738406 -0.6228296 -0.1151261 0.7738507 -0.6228157 -0.1151341 -0.7790227 -0.6269957 1.02266e-4 0.7790218 -0.6269969 1.02174e-4 0.7738347 -0.6228372 -0.1151248 -0.7852778 -0.6186625 0.02440637 -0.7829765 -0.6168482 0.08028781 -0.7829758 -0.6168488 0.08029097 0.7829749 -0.6168502 0.08028846 -0.7627902 -0.6009371 0.2388009 -0.7627841 -0.6009438 0.2388038 0.7829765 -0.6168482 0.08028858 0.7627845 -0.6009441 0.2388018 0.7627832 -0.6009455 0.2388017 -0.6576644 -0.4749627 0.5847121 -0.6300269 -0.4230481 0.6512269 -0.6363528 -0.4236927 0.6446237 -0.569679 -0.4114236 0.7114749 -0.6345837 -0.4228483 0.646918 0.6401402 -0.4242632 0.6404851 0.5589849 -0.4037414 0.7242437 0.6341622 -0.4234641 0.6469286 0.6359217 -0.423625 0.6450934 -0.7477288 -0.5890625 0.3064426 0.7477195 -0.5890719 0.306447 -0.7627853 -0.6009436 0.2387996 -0.7860236 -0.5404696 0.3000996 -0.7815704 -0.5398099 0.3126551 -0.5315578 -0.418779 0.7362545 -0.6743894 -0.6746309 0.3001204 0.7627857 -0.6009421 0.2388026 0.531564 -0.4187814 0.7362486 0.7855376 -0.5411623 0.3001239 0.6743894 -0.6746309 0.3001204 -0.7969169 -0.604088 0.001142024 -0.7070307 -0.7071791 -0.00232774 -0.7698183 -0.5835447 0.2585641 -0.7698227 -0.5835399 0.2585622 0.7969174 -0.604084 -0.002306222 0.7698208 -0.58354 0.2585675 0.6887269 -0.6891115 0.2253456 -0.8215814 -0.5649217 -0.07660102 0.7826755 -0.5381507 0.3127508 0.8240042 -0.5665837 0 0.8389304 -0.5229821 -0.1506169 -0.5638031 -0.4273763 0.7067359 -0.5637912 -0.4273826 0.7067415 0.7698172 -0.5835458 0.2585648 0.5637989 -0.4273802 0.7067369 -0.2064567 -0.156498 0.9658593 -0.2064535 -0.1564987 0.9658598 0.5638004 -0.4273794 0.7067362 0.206457 -0.1564987 0.965859 -0.666028 -0.4637055 0.5842807 -0.6290656 -0.4119759 0.6592059 -0.7059296 -0.4914731 0.5100175 0.6323968 -0.4185815 0.6518159 0.6294385 -0.4126325 0.6584388 0.6615934 -0.4606195 0.5917127 0.7059074 -0.4914822 0.5100393 0.7059247 -0.4914697 0.5100273 -0.001264929 -7.83228e-4 -0.999999 -0.8502166 -0.526433 1.01519e-4 0.001264929 -7.83228e-4 -0.999999 0.8502167 -0.526433 -2.74983e-4 0.779034 -0.6269817 1.0214e-4 -0.7789356 -0.6269526 -0.013776 -0.7738377 -0.622833 -0.1151276 0.7738614 -0.622803 -0.1151311 -0.807666 -0.5623118 0.1774296 -0.8076561 -0.5623272 0.1774257 -0.7059087 -0.4914737 0.5100457 0.8076538 -0.5623278 0.1774342 0.8076627 -0.5623193 0.1774209 0.8076619 -0.5623178 0.177429 -0.8204931 -0.5712575 -0.02135604 0.8204931 -0.5712575 -0.02135866 -0.8173986 -0.5615735 -0.1284318 -0.8263784 -0.5628389 -0.01764434 -0.8282392 -0.5596479 0.02853763 -0.8285385 -0.5582922 0.04282408 -0.8144215 -0.568736 -0.1151396 -0.8039338 -0.5523336 -0.2204952 0.8285479 -0.5582746 0.04287242 0.8144147 -0.5687431 -0.1151522 0.8282435 -0.5596508 0.02835309 0.8263764 -0.5628412 -0.01765871 0.8173985 -0.5615773 -0.1284165 -0.8198516 -0.5725411 -0.006333887 0.8198497 -0.5725437 -0.006334066 0.8434239 -0.4939149 0.211387 0.8434838 -0.4938656 0.2112627 0.8434745 -0.4938741 0.2112797 0.8548699 -0.5161566 -0.05272412 0.806717 -0.4958216 0.3215101 0.7401779 -0.5067111 0.4420188 -0.8570869 -0.5136334 -0.03978437 -0.8570815 -0.5136495 -0.03969228 -0.8539538 -0.5176701 -0.05273139 -0.7388038 -0.5066369 0.4443963 -0.7388368 -0.5066571 0.4443185 -0.8409063 -0.4948393 0.2191136 -0.8408897 -0.4948599 0.2191307 -0.8180766 -0.4769981 0.3212844 0.2064546 -0.156499 0.9658595 0.8370964 -0.4982542 -0.2258595 0.8415407 -0.5008838 -0.2022984 0.8415917 -0.5010739 -0.2016143 0.8540366 -0.5180623 -0.0472548 -0.8371013 -0.4982457 -0.2258598 -0.8415146 -0.5008772 -0.2024236 -0.8427546 -0.5005522 -0.1980206 0.7696168 -0.4489036 0.4540656 0.7696062 -0.4489165 0.4540708 0.7076326 -0.4232873 0.5657597 0.6945113 -0.4187059 0.5850977 -0.694484 -0.4187404 0.5851055 -0.768741 -0.4475648 0.4568623 -0.8297794 -0.5575965 0.02350217 -0.8204966 -0.5712524 -0.0213586 -0.8273287 -0.5559489 0.08030045 -0.8273301 -0.555947 0.08029991 0.8298193 -0.5576233 -0.02135646 0.8273296 -0.5559478 0.08029806 -0.8076636 -0.5623172 0.1774225 0.8201034 -0.5709811 0.03756415 -0.8059926 -0.5416063 0.2388275 -0.8059921 -0.5416078 0.2388259 0.8273302 -0.5559467 0.08029896 0.805993 -0.5416061 0.2388269 0.6815193 -0.4073317 0.6079576 0.6529527 -0.3908249 0.6487749 0.6542886 -0.3910602 0.6472854 -0.6808707 -0.4069135 0.6089636 -0.6542937 -0.3910531 0.6472845 -0.6512707 -0.3911194 0.6502861 -0.6529434 -0.3908231 0.6487853 -0.7414091 -0.4982117 0.4495527 0.8059902 -0.5416099 0.2388278 0.7414023 -0.49821 0.4495658 -0.8486129 -0.5290145 0 -0.8197547 -0.5110241 0.2585665 -0.8197565 -0.5110237 0.258562 0.8197529 -0.5110287 0.2585635 -0.6003673 -0.374265 0.7067424 -0.6003692 -0.3742647 0.706741 0.819758 -0.5110197 0.2585649 0.6003724 -0.3742669 0.7067371 -0.8381901 -0.5453636 -0.003997802 -0.8396152 -0.5428854 -0.01793807 0.838442 -0.5449762 -0.004019856 0.8393556 -0.5433328 -0.0164873 -0.6435717 -0.3860821 0.6608753 -0.7375746 -0.4424833 0.5100904 0.6444188 -0.388471 0.6586461 0.6425741 -0.3854829 0.6621945 0.737586 -0.4424821 0.510075 -0.8409199 -0.5411473 -0.003671228 -0.8435314 -0.5349438 -0.04785537 0.8456723 -0.533694 -0.003053426 0.8515288 -0.5068266 -0.1342593 -0.84204 -0.536625 -0.05479419 0.849547 -0.5062335 -0.1483162 -0.7249815 -0.4165925 0.5485004 -0.870441 -0.4882292 0.06296694 -0.8367099 -0.4818846 0.2601999 -0.7705936 -0.4429865 0.4582013 -0.7521046 -0.4331724 0.4966895 -0.8523808 -0.4919406 0.1773177 -0.6836344 -0.3849864 0.6200239 0.7318128 -0.4359927 0.5237944 0.845452 -0.5037132 0.1774374 0.8454632 -0.5036984 0.1774259 -0.8409734 -0.5410642 -0.003668665 -0.8438137 -0.5335305 -0.05765128 -0.8438339 -0.5335168 -0.05748438 -0.8413477 -0.5291653 -0.1100826 0.8469106 -0.50189 -0.1756384 0.8510413 -0.5037541 -0.1481918 0.8456751 -0.5336895 -0.003048181 -0.8657777 -0.4996744 -0.02746701 -0.8667406 -0.4974058 -0.03672063 -0.8657067 -0.4999085 -0.02537018 0.8667405 -0.4974064 -0.03671503 0.8586398 -0.5115507 0.03245812 -0.8409569 -0.5410897 -0.003669798 0.8456743 -0.5336908 -0.00305289 0.8491095 -0.4922348 -0.1916193 -0.2198482 -0.1370492 0.9658594 -0.21985 -0.1370491 0.9658589 0.6003677 -0.3742638 0.7067427 0.2198464 -0.1370498 0.9658598 -0.8482596 -0.5295734 -0.002792179 -0.8556248 -0.5024775 -0.1241883 -0.8360555 -0.5070362 -0.2095841 0.8399017 -0.4903475 -0.232647 -0.8698057 -0.4805896 -0.1116767 -0.8543795 -0.4630804 -0.2357802 -0.8537449 -0.4830628 -0.1943455 0.84413 -0.4830303 -0.2326511 0.846398 -0.4831038 -0.2241008 -0.8482528 -0.5295844 -0.002792835 -0.9028136 -0.3570396 -0.2396883 -0.9383609 -0.2572987 -0.2308169 -0.9008902 -0.3572735 -0.2464806 -0.8933333 -0.3771049 -0.2444332 -0.8936272 -0.3771089 -0.2433503 0.8894339 -0.3888428 -0.2402261 0.894607 -0.3771132 -0.239717 0.8939362 -0.3771089 -0.2422123 0.9008789 -0.3573052 -0.2464756 0.90091 -0.3572171 -0.2464899 0.8456634 -0.5337082 -0.003053367 -0.8490805 -0.5206494 0.08936744 -0.8620686 -0.5045217 0.04791337 -0.8662634 -0.4993185 0.01639854 -0.8673056 -0.4977673 -0.002964258 -0.8637896 -0.4974111 0.08030974 -0.8137563 -0.5609627 0.152058 0.849084 -0.5206439 0.08936649 0.8673048 -0.4977687 -0.002993643 0.8662605 -0.4993224 0.01642763 0.8620679 -0.5045229 0.04791337 0.8536623 -0.5145927 0.08034408 -0.9069313 -0.3571027 -0.2235028 0.8673701 -0.4509932 -0.2104146 0.8455973 -0.3529423 -0.4004958 0.9062383 -0.3596882 -0.2221632 0.7586142 -0.253881 0.6000409 -0.8073487 -0.4531912 -0.3778966 -0.8950194 -0.439372 -0.07676351 -0.8713148 -0.4439644 -0.2090601 0.9323381 -0.3555578 -0.06576114 -0.8984649 -0.4363407 -0.04865849 0.2198504 -0.1370498 0.9658588 0.9222662 -0.3249054 0.209432 0.9323477 -0.3555324 -0.0657618 0.9122456 -0.3989727 -0.09289145 -0.8714677 -0.4885808 -0.0428152 -0.8708316 -0.4882021 -0.0575428 -0.8763784 -0.4286443 0.2196025 -0.8541259 -0.4917251 0.1693382 -0.8146375 -0.5178439 0.261158 -0.8349326 -0.4957809 0.2389329 0.8541337 -0.4917261 0.1692959 0.8541264 -0.4917253 0.1693353 0.8250935 -0.5119684 0.2389753 -0.9479058 -0.2355626 0.2144407 -0.8790773 -0.4089533 0.2449089 0.9242486 -0.3678701 0.1021577 0.8956837 -0.3914608 0.2109718 0.8956901 -0.3914435 0.210977 -0.679708 -0.2837333 0.676382 -0.6768556 -0.2837414 0.6792329 0.6798298 -0.2841501 0.6760845 0.6819355 -0.2837511 0.6741285 0.6768537 -0.2837464 0.6792327 -0.6816402 -0.2844012 0.6741533 -0.6862796 -0.2850111 0.6691704 -0.7270837 -0.5276464 0.4392479 0.807115 -0.3594597 0.4683526 0.8815901 -0.3356341 0.3318867 0.6874686 -0.2844293 0.6681968 0.683236 -0.2846268 0.6724405 -0.854786 -0.5189763 -0.002125322 0.8584271 -0.5129329 -0.001747727 -0.7270289 -0.5276363 0.4393508 0.8071502 -0.3594252 0.4683185 -0.6827456 -0.255286 0.6846076 -0.6826132 -0.2551946 0.6847737 -0.6826298 -0.2552829 0.6847242 -0.6826739 -0.2552441 0.6846947 -0.5909789 -0.1873053 0.7846404 -0.7929731 -0.1854777 0.5803377 0.5298459 -0.1164153 0.840066 0.6750749 -0.2995464 0.6742002 0.6099498 -0.1877468 0.7698782 0.6955816 -0.1883752 0.6933117 0.8753418 -0.09160465 0.4747477 -0.6835049 -0.2836191 0.6725929 -0.6973271 -0.2874276 0.6565976 0.6994274 -0.2829861 0.6562927 0.6862238 -0.2840614 0.6696314 -0.7603733 -0.4116747 0.5023511 -0.8288576 -0.2890102 0.4790285 0.8342944 -0.2759297 0.4773005 0.7586357 -0.3048793 0.5757782 -0.7121648 -0.2887213 0.6398917 -0.7123344 -0.2547 0.6539937 0.7108989 -0.2988338 0.6366484 0.7440258 -0.3060645 0.5939278 0.6545095 -0.007661581 -0.756015 0.7001649 -0.3047024 0.6456978 0.7742195 -0.2148903 0.5953205 0.8455536 -0.3530746 -0.4004715 0.7578719 -0.3862479 -0.5257783 -0.8954163 -0.4385219 -0.07699513 -0.8954945 -0.4382967 -0.07736665 -0.8544681 -0.3954125 -0.3369471 -0.8324308 -0.3949973 -0.3886337 -0.8974471 -0.437123 -0.05926531 -0.8975008 -0.437017 -0.0592339 -0.9070053 -0.4105662 -0.09368479 -0.9512862 -0.3042673 -0.04975908 -0.9507116 -0.3060316 -0.04992252 -0.8819743 -0.4025337 0.2451285 -0.9019157 -0.357226 -0.2427711 -0.7781541 -0.3413999 -0.5271833 0.8328449 -0.2668787 0.4849177 -0.9717007 -0.2341967 -0.03081917 -0.6310518 -0.4476874 0.6335216 -0.7969109 -0.290099 0.5298826 -0.7972391 -0.2892652 0.5298448 -0.7968935 -0.2900882 0.5299147 -0.7536249 -0.3569901 0.5519128 -0.8842754 -0.3956311 0.2480584 -0.909413 -0.2636302 0.3216629 0.7144366 -0.2829904 0.6399195 0.6934863 -0.2791535 0.6641914 -0.6904804 -0.2764782 0.6684285 -0.7116891 -0.2905296 0.6396025 -0.8176016 -0.4827391 0.3138321 -0.8171393 -0.4823581 0.3156172 0.8175818 -0.482724 0.3139067 0.8297685 -0.4917674 0.2639116 0.8171412 -0.4823542 0.3156179 -0.6622895 -0.2553877 0.7043791 -0.8614951 -0.5077639 -0.001482963 -0.9716911 -0.2342366 -0.03081774 -0.5845367 -0.3331761 0.7398043 -0.890343 -0.2537803 0.3780015 -0.9716732 -0.2342997 -0.03090339 0.7282654 -0.2829621 0.6241492 0.7040225 -0.2722424 0.6559241 -0.7035946 -0.2678723 0.6581787 -0.7279551 -0.2951545 0.618842 -0.9446415 -0.3138436 -0.09568035 -0.9190919 -0.3048691 0.2496494 0.8328799 -0.266909 0.4848411 0.9198586 -0.298846 -0.2540698 0.7746306 -0.3406909 -0.5328013 0.9212726 -0.2986344 -0.2491474 -0.9228403 -0.2241808 0.3132234 -0.9097677 -0.2621496 0.3218701 -0.7917125 -0.2991501 -0.5326355 -0.9019036 -0.3572565 -0.242771 -0.9022884 -0.3572422 -0.2413583 0.9019161 -0.3572229 -0.2427738 -0.9524804 -0.3040969 -0.01749837 -0.9460619 -0.3084539 -0.09911108 0.9244849 -0.3585411 -0.1295218 -0.5929481 -0.2542428 0.7640504 -0.7966187 -0.253216 0.5488902 -0.7733823 -0.2902603 0.5635857 -0.7734003 -0.2902691 0.5635565 -0.9217298 -0.2894183 0.2581692 -0.6027334 -0.2484285 0.7582848 -0.7003472 -0.2329491 0.6747211 -0.8855768 -0.2834129 0.3680094 -0.8855605 -0.2833918 0.3680649 0.8682204 -0.4961781 -9.61024e-4 0.9283341 -0.2710918 -0.2543723 0.7455517 -0.2799811 0.6047837 0.7163609 -0.2653674 0.6452963 0.6869822 -0.1169151 0.7172074 0.682393 -0.1065022 0.7231854 -0.8717856 -0.4898871 -7.09308e-4 -0.871793 -0.4898743 -7.08645e-4 -0.9393503 -0.2263816 -0.2576283 0.8682102 -0.4961956 -9.61237e-4 0.9283254 -0.2711201 -0.2543736 -0.957039 -0.1285283 -0.2599169 -0.9630703 -0.09639835 -0.251402 -0.9569307 -0.1285257 -0.2603167 -0.9022888 -0.3563206 -0.2427152 0.9492179 -0.1822162 -0.2564812 0.9589368 -0.1285437 -0.2528176 0.9572477 -0.1285285 -0.2591474 0.9577669 -0.1214818 -0.2606241 0.8992682 -0.3641803 -0.2422591 -0.7143056 -0.09572267 0.6932567 -0.7047986 -0.09574615 0.7029165 0.7156055 -0.09476846 0.6920461 0.6989955 -0.09577775 0.7086832 -0.699724 -0.0929588 0.7083396 -0.7374407 -0.09795844 0.6682706 0.7410563 -0.09524017 0.6646541 0.6888747 -0.09090292 0.7191581 0.703595 -0.1166784 0.7009567 0.6870551 -0.1072431 0.7186475 0.687088 -0.1066064 0.7187108 0.7059522 -0.1166433 0.6985885 -0.6022654 -0.2546136 0.7566031 0.7986388 -0.1026107 0.5929985 0.79407 -0.108654 0.5980362 0.7947182 -0.1023543 0.5982864 0.9289917 -0.115303 0.3516811 0.9327606 -0.1175488 0.3407931 -0.6954818 -0.08396387 0.7136212 -0.7724832 -0.1049304 0.6263061 0.9840176 -0.13747 0.1131882 0.9332209 -0.1101346 0.3420076 0.9332101 -0.1101287 0.3420389 -0.7070901 -0.09291875 0.7009919 -0.700713 -0.09125679 0.7075829 -0.7760692 -0.07827883 0.6257708 -0.7006756 -0.09115034 0.7076337 -0.695261 -0.2879711 0.6585475 0.7774434 -0.0938819 0.6219068 0.6893086 -0.0801391 0.7200219 0.9856393 -0.1075146 -0.1302149 0.98284 -0.1298907 -0.1309732 0.9839183 -0.1218284 -0.1306247 0.9926177 -0.1068046 0.0574702 0.9926193 -0.1067976 0.05745589 -0.7907605 -0.2883247 0.5399692 -0.8099096 -0.09252929 0.5792105 0.7987604 -0.1080683 0.5918641 0.9633913 -0.1221809 -0.2386401 -0.984007 -0.1029729 0.1453512 -0.9460556 -0.3084706 -0.09912037 -0.9464361 -0.3073051 -0.09910804 -0.9862108 -0.1492426 -0.07151913 -0.9840062 -0.1029785 0.1453525 -0.9840105 -0.1029627 0.1453344 -0.9532975 -0.1602515 0.2560144 -0.9042757 -0.3523001 -0.2411853 0.9004577 -0.3624484 -0.240431 -0.9581027 -0.121482 -0.2593868 -0.9570374 -0.1214926 -0.2632851 0.957023 -0.121405 -0.2633779 0.9578132 -0.1214981 -0.2604463 -0.9525054 -0.3040239 -0.0174055 -0.9578995 -0.1213114 -0.2602157 -0.8741006 -0.1298561 -0.4680659 -0.9528955 -0.3027892 -0.01757919 0.9630655 -0.1244288 -0.2387936 0.963572 -0.1201704 -0.2389311 0.9576832 -0.1225742 -0.26042 0.9765071 -0.1225382 -0.1772525 0.9757277 -0.2143672 0.04474419 -0.8099015 -0.09259247 0.5792118 -0.7954307 -0.1140686 0.5952128 -0.9175387 -0.08882856 0.3875983 -0.9169744 -0.08873784 0.388952 -0.9175494 -0.08883947 0.38757 0.8171256 -0.09971892 0.5677691 0.7215923 -0.05990058 0.6897222 -0.7195895 -0.05651861 0.6920959 -0.8122261 -0.1163234 0.5716271 -0.7818654 -0.3864619 0.4892175 -0.7327187 -0.2506296 0.6326992 0.7814767 -0.3864466 0.4898502 0.7818751 -0.3864431 0.4892168 0.8756499 -0.4829463 -5.14305e-4 -0.7064194 -0.07074248 0.7042495 -0.7079483 -0.07072389 0.7027143 -0.959881 -0.1030324 -0.2607926 -0.9862575 -0.1026881 -0.1294271 0.8486045 -0.1059565 0.5183084 0.762308 -0.0464366 0.6455465 0.7814367 -0.386498 0.4898736 0.7818502 -0.3864793 0.489228 -0.7643797 -0.03898203 0.6435869 -0.7721617 -0.04650861 0.6337219 -0.8706422 -0.1084231 0.4798195 -0.9123954 -0.3584831 0.1975464 -0.8899314 -0.3649905 0.2735033 0.8258754 -0.3711019 0.4245156 0.9293334 -0.2435483 0.2775314 0.9123951 -0.3584851 0.1975443 0.7872059 -0.4142904 0.4568047 0.8075466 -0.4277051 0.4061242 0.8176377 -0.4328073 0.3796665 0.8173353 -0.4332512 0.3798111 0.8607288 -0.4509837 0.2361354 0.8769371 -0.4466403 0.1774654 0.8808574 -0.4675492 0.07408243 0.8826591 -0.4699991 -0.003719568 0.8832521 -0.4688544 -0.00644195 -0.8833262 -0.4687588 -1.46606e-4 -0.9203476 -0.2394905 0.3092001 -0.8738083 -0.2206555 0.4333248 0.920307 -0.2394932 0.3093187 -0.904181 -0.3701633 0.2131571 -0.9079091 -0.3709834 0.1951216 0.9079114 -0.3709825 0.1951127 0.9041824 -0.370159 0.2131587 -0.9191107 -0.2389535 0.3132681 -0.9202117 -0.2393527 0.3097109 0.919065 -0.2391398 0.3132597 0.9193918 -0.2390819 0.3123438 0.9202387 -0.2393106 0.3096633 -0.9170768 -0.3626288 0.1657425 -0.9208787 -0.3646512 0.1378839 0.9241515 -0.3552222 0.140574 -0.9190605 -0.2391461 0.3132683 -0.919344 -0.2392661 0.3123436 0.8795407 -0.3547666 0.3170946 0.9618371 -0.2709605 -0.03807848 0.8840477 -0.4673969 -1.34986e-4 0.9627187 -0.07058095 -0.2611339 0.863724 -0.1307461 0.4867098 -0.8894696 -0.3578138 -0.284277 -0.9275088 -0.3731174 -0.02260315 -0.9028747 -0.4299039 0 0.9261064 -0.3772625 0 0.9274007 -0.3740625 -0.00233066 -0.8722476 -0.4153081 0.2582699 -0.8722419 -0.4153224 0.2582665 0.895018 -0.3645948 0.2569308 -0.9232224 -0.3617277 0.1296666 -0.9270481 -0.36179 0.09843754 0.913412 -0.3732486 0.1623703 0.9306023 -0.3515816 0.1018326 -0.8495228 -0.4046769 0.3384488 -0.7849372 -0.2092354 0.5831758 0.7849398 -0.2092344 0.5831729 0.8501647 -0.410351 0.3298973 0.8417295 -0.4064627 0.3553583 -0.6391611 -0.3043356 0.7062953 -0.6391488 -0.3043431 0.7063032 0.895016 -0.3645921 0.2569418 0.6574208 -0.2678006 0.7043301 -0.9258248 -0.3636876 0.102858 -0.9318624 -0.3556289 0.07183676 0.9192379 -0.3731734 0.1254727 0.933456 -0.3510709 0.07354867 -0.9277324 -0.3628413 0.08751535 -0.9337554 -0.3535805 0.05551415 0.9240256 -0.3688099 0.1007769 0.9354097 -0.34889 0.05731123 -0.931752 -0.357502 0.06348598 -0.9305851 -0.3588709 0.072272 0.9258807 -0.3680624 0.08529382 0.9298386 -0.3610866 0.07082927 -0.7078261 0 0.7063867 -0.8633924 0.001029253 0.5045319 -0.7202419 -0.001213908 0.6937221 -0.734749 0 0.6783393 -0.7850702 1.92262e-4 0.6194069 -0.8279023 5.49493e-4 0.5608722 0.7081113 -1.12977e-5 0.706101 0.7078098 7.16609e-7 0.7064031 0.7078214 0 0.7063915 0.7078332 -2.04798e-7 0.7063797 0.7080652 -0.06350064 0.7032862 0.7347728 0 0.6783134 -0.707808 -1.12609e-6 0.7064049 0.707781 6.14621e-7 0.7064319 -0.7080058 1.35369e-5 0.7062067 0.7078661 0 0.7063466 0.707831 8.30879e-7 0.7063818 -0.7078477 -8.05682e-7 0.7063652 -0.7077762 -7.55466e-7 0.7064368 -0.7078381 4.09598e-7 0.7063748 -0.7444182 -9.17461e-4 0.6677131 -0.7941526 1.23314e-4 0.6077184 -0.7972812 0 0.6036083 -0.7078714 0 0.7063414 0.797276 0 0.603615 -0.7840862 -4.83872e-4 0.6206517 0.785095 -1.92252e-4 0.6193753 -0.234175 -0.1115061 0.9657787 -0.2341618 -0.1115033 0.9657823 0.6574082 -0.2678086 0.7043387 0.2414608 -0.09835398 0.9654136 -0.9166175 -9.95422e-5 0.3997654 -0.7967405 1.23359e-4 0.6043216 0.796676 -1.23282e-4 0.6044067 0.7941628 -1.23312e-4 0.6077051 0.9338588 -1.48106e-4 0.3576423 0.916594 9.97697e-5 0.3998194 0.9338589 -1.47876e-4 0.3576419 -0.9338589 1.4759e-4 0.3576419 -0.9338594 1.47143e-4 0.3576405 -0.9160429 0.001138091 0.4010788 -0.9338394 1.47905e-4 0.3576925 -0.9165613 0.001120686 0.3998929 -0.9081863 -0.1889958 0.3734681 -0.841431 -0.02134251 0.539943 0.852361 -0.04196465 0.5212676 0.9527119 -0.1732196 0.2496698 0.8431001 -0.02439391 0.5372031 0.8430865 -0.02431493 0.5372281 -0.9874022 -7.52973e-4 0.1582285 0.8279159 -5.49369e-4 0.5608522 -0.9337838 -0.3528932 0.05928122 -0.9328003 -0.3539738 0.06772202 0.9324941 -0.3553518 0.06465321 0.932068 -0.3561541 0.06636011 -0.8333323 -1.17813e-4 0.5527725 0.9338593 -1.48202e-4 0.3576408 0.9164368 -0.001115739 0.4001779 0.9976022 -3.04006e-4 0.06920903 0.9874033 7.53123e-4 0.1582214 0.9165577 -0.001120984 0.3999009 -0.9873665 5.02725e-4 0.1584525 -0.9976028 3.04077e-4 0.06920033 0.9976045 -9.24104e-4 0.06916993 0.9873801 -5.02202e-4 0.1583676 0.9873688 -5.0268e-4 0.1584383 -0.9873828 5.0249e-4 0.1583514 -0.9520649 -0.3058928 0.001402258 -0.9197568 -0.2955184 0.2582952 -0.9923687 -8.37149e-4 -0.1233035 -0.9976043 9.24155e-4 0.06917381 -0.9976071 9.24145e-4 0.06913173 0.9976078 -9.2345e-4 0.06912386 0.9850956 0 -0.1720077 0.9923704 8.37149e-4 -0.1232893 -0.8873734 -0.4038376 0.2224493 -0.8629129 -0.2631515 0.4314309 0.8435718 -0.4201306 0.3344802 -0.965226 1.76632e-5 -0.261417 -0.9652244 -8.7604e-7 -0.2614229 -0.9652254 -1.81984e-6 -0.2614194 -0.9652251 -4.35722e-6 -0.2614207 0.9652257 -8.93825e-6 -0.2614181 0.9652257 -5.50705e-7 -0.261418 0.9652246 -4.23409e-6 -0.2614223 -0.9652262 0 -0.2614163 -0.9652315 6.39797e-5 -0.2613967 -0.9652251 0 -0.2614204 -0.9652253 0 -0.2614197 -0.9652268 7.97748e-6 -0.2614139 -0.9850919 0 -0.1720288 0.9652246 0 -0.261422 0.9652358 -5.23731e-5 -0.2613809 0.9652236 6.66342e-6 -0.2614257 0.9652249 0 -0.2614207 0.9652499 0 -0.2613286 0.9652272 3.69932e-5 -0.2614126 -0.9653179 2.56331e-4 -0.2610774 -0.9652241 -5.5296e-6 -0.2614241 0.9652248 1.6954e-6 -0.2614213 0.965225 0 -0.2614208 -0.9197545 -0.2955255 0.2582954 -0.6739393 -0.2165455 0.7063384 -0.6739546 -0.2165232 0.7063307 -0.903694 -0.4281791 1.96697e-4 0.8922486 -0.4515448 0 -0.8452084 -0.1937603 0.4980762 -0.8994103 -0.3954514 0.1862235 0.7459406 -0.0473932 0.6643241 0.8994242 -0.3953566 0.1863579 -0.8960733 -0.4343659 0.09153741 -0.895376 -0.3723443 0.2442571 -0.9357498 -0.3483808 0.05480003 0.8960539 -0.4344081 0.0915268 0.9345005 -0.350803 0.06038457 0.8986257 -0.4000067 0.1801848 0.8634502 -0.00102967 0.5044331 -0.8751298 -0.4107772 0.2557538 -0.8945544 -0.3181788 0.3139023 -0.9106712 -0.3858502 0.1476404 0.8994293 -0.3953963 0.1862489 -1.11217e-4 0 1 0.241451 -0.09835439 0.9654159 -0.9018126 1.24002e-4 0.4321277 -0.890409 4.36286e-5 0.4551614 -0.8728128 -0.430018 0.2308302 -0.8824021 -0.4472813 0.1459659 -0.8779432 -0.4430122 0.1815384 -0.8747338 -0.4385907 0.2061043 -0.8900595 -0.4432022 0.1066117 -0.8723688 -0.418942 0.2519138 0.890071 -0.4431909 0.1065618 0.8723638 -0.418967 0.2518891 0.8727926 -0.4300081 0.2309247 0.8753045 -0.4410702 0.1982403 0.8802611 -0.4448807 0.1649897 0.8839834 -0.4466053 0.1382648 -0.9106883 -0.3814318 0.1586092 0.8982853 -0.3120642 0.3093535 0.9038283 -0.3306946 0.2715428 0.9255169 -0.3615757 0.1126123 -0.2469123 -0.079328 0.9657854 -0.2469064 -0.07932347 0.9657872 0.9143272 -0.3717014 0.160761 0.885914 -0.198967 0.4190093 -0.9022272 -0.3481423 0.2545252 -0.9329596 -0.343371 0.1080868 0.9020432 -0.3686367 0.2245556 0.9407677 -0.332791 0.06485664 -0.9087234 -0.3208867 0.2669337 -0.9240441 -0.353941 0.1444585 0.9152866 -0.332175 0.2278383 0.9284319 -0.3458861 0.1355622 -0.9010267 -0.3914002 0.1869675 -0.9125538 -0.3362742 0.2327347 -0.9294167 -0.3396185 0.144374 0.9109404 -0.3460459 0.2245886 0.9352163 -0.3362899 0.1108135 0.7839826 4.84103e-4 0.6207828 0.8333649 1.17526e-4 0.5527231 0.9018386 -1.23761e-4 0.4320731 0.7202417 0.001213073 0.6937221 0.7446945 9.17256e-4 0.6674049 -0.9163411 -0.3296611 0.2272501 -0.9253842 -0.3408731 0.1657397 0.901117 -0.3914444 0.186439 0.920724 -0.334681 0.2006393 0.9270883 -0.3370517 0.1640229 -0.918859 -0.3344067 0.2094526 -0.9267413 -0.3370398 0.1659967 0.9181386 -0.3368225 0.2087392 0.9302861 -0.3370198 0.1448639 -0.9559046 -0.1224325 0.2669398 -0.957532 -0.125615 0.2595252 -0.8909828 -0.1348845 0.4335388 0.94879 -0.1243798 0.2903914 0.8738045 -0.2206735 0.4333229 0.9578627 -0.1218549 0.260097 -0.9210983 -0.3337022 0.2005516 -0.9228036 -0.3347676 0.1906937 0.9246435 -0.3356835 0.1798642 0.922676 -0.3351598 0.1906219 -0.9246071 -0.3358103 0.1798147 0.9269565 -0.3364197 0.1660529 -0.9196904 -0.2393336 0.3112701 -0.9268869 -0.2424565 0.2865231 0.9196896 -0.2393369 0.3112699 -0.001387298 -5.37458e-4 -0.999999 -0.9324718 -0.3612425 2.87535e-4 -0.9327792 -0.3604485 1.96103e-4 0.001387298 -5.37458e-4 -0.999999 0.9324719 -0.3612427 2.93693e-4 0.9334565 -0.3586906 0 0.930328 -0.3645547 -0.03987026 0.9307749 -0.3628696 -0.04454088 -0.967276 -0.1653385 0.1924592 -0.9529132 -0.1744465 0.2480424 -0.8999254 -0.02304202 0.4354346 0.9140951 -0.05164563 0.4021975 0.9799185 -0.1980587 0.02307915 0.8858428 -0.1989794 0.4191537 -0.9289684 -0.367864 -0.04115724 -0.9289715 -0.3654883 -0.05856901 -0.9601814 -0.123106 0.2507923 -0.9647653 -0.123903 0.2321119 0.9555396 -0.1274431 0.2658993 0.9651528 -0.1181267 0.2335088 0.9807413 -0.1953078 0.001159965 0.9474829 -0.1885567 0.258307 0.945168 -0.1207602 0.3034376 0.9807682 -0.1951729 0.001160085 0.9916894 -0.1267055 -0.02231776 0.9474883 -0.1885381 0.2583011 0.9474814 -0.1885597 0.2583106 -0.9453035 -0.1198999 0.3033567 -0.9920481 -0.1258288 -0.002781867 -0.9520201 -0.3060325 0.00140208 -0.9197359 -0.2955851 0.2582931 0.6942541 -0.1381583 0.7063453 0.8903487 -4.36144e-5 0.4552792 0.9021965 -4.34845e-5 0.4313253 -0.8904047 4.35642e-5 0.4551699 -0.9925643 -0.1217224 0 -0.959218 -0.1176351 0.2570273 -0.9592304 -0.1176076 0.2569932 -0.9654017 -0.1231054 0.2298796 -0.9703707 -0.122508 0.208261 0.9597806 -0.1298933 0.2488955 0.9707568 -0.1160407 0.2101571 -0.7044688 -0.08636975 0.7044601 -0.7045252 -0.08632969 0.7044085 0.6942387 -0.138144 0.7063632 0.2543538 -0.05061233 0.965786 -0.9687291 -0.1250851 0.2142842 -0.9741083 -0.1190404 0.1922048 0.9649997 -0.1306724 0.2273771 0.9742786 -0.1160598 0.193162 -0.2586834 -0.03169888 0.965442 -0.2587087 -0.03166931 0.9654362 -0.9706709 -0.1250292 0.2053429 -0.976135 -0.1180273 0.1822914 0.9685549 -0.128536 0.2130262 0.9762938 -0.1149872 0.1833806 -0.9448568 -1.84811e-4 0.327484 0.9447852 -2.27871e-4 0.3276904 -0.9730036 -0.124049 0.1946168 -0.9752309 -0.1228571 0.1839315 0.9705044 -0.1285878 0.2039276 0.975345 -0.1195851 0.1854771 6.51666e-7 0 1 0.2543452 -0.05060094 0.9657889 -0.965782 -0.2538855 0.05298358 -0.9756839 -0.1219996 0.1820909 -0.977638 -0.12114 0.1718984 0.9728485 -0.1272038 0.1933524 0.9777704 -0.1179614 0.1733503 -0.9657794 -0.2538921 0.05299973 -0.9524843 -0.1004028 0.2875639 0.9142897 -0.3717819 0.1607874 -0.9267944 0.01183515 0.3753826 -0.9783228 -0.122799 0.1667478 0.945438 -0.02204209 0.3250558 0.9773679 -0.1170198 0.1762336 0.978953 -0.1203489 0.1648252 0.9978619 -0.06535696 0 0.9640008 -0.06314176 0.2582939 0.9639995 -0.06311255 0.2583061 0.7063581 -0.0462529 0.7063419 0.9645183 -0.04334908 0.2604334 0.9800663 -0.1029658 0.1699066 -0.9737838 -0.12177 0.1921385 -0.9769939 -0.1223537 0.1746786 0.9755091 -0.1250815 0.1809327 0.9736716 -0.1283274 0.1884028 0.7063556 -0.04624354 0.706345 0.2587862 -0.01694089 0.9657862 -0.9777187 -0.1152393 0.1754602 -0.9785302 -0.1185592 0.1685892 0.9778064 -0.1155885 0.17474 0.9790903 -0.1158332 0.1672278 0.2587647 -0.01692855 0.9657921 -0.9753552 -0.1165837 0.1873247 -0.9775355 -0.117686 0.1748556 0.975124 -0.1203476 0.1861444 0.9773073 -0.1179443 0.1759535 -0.9780961 -0.1138736 0.1742442 -0.9784239 -0.1145331 0.1719565 0.9781253 -0.1139355 0.1740397 0.9784961 -0.1140865 0.1718422 -0.9781597 -0.113678 0.1740137 -0.9779595 -0.1134393 0.1752904 0.9781554 -0.1136672 0.174045 0.977921 -0.1137056 0.175333 -0.9764662 -0.114353 0.1828587 -0.9778637 -0.1153712 0.1745626 0.97631 -0.1161521 0.1825585 0.9777389 -0.11544 0.1752147 -0.9781375 -0.1138148 0.1740496 -0.9774899 -0.1134657 0.1778736 0.9781017 -0.113812 0.1742523 0.9774456 -0.1138231 0.1778896 -0.9770649 -0.1137667 0.1800039 -0.9780147 -0.1143423 0.1743934 0.9770116 -0.114336 0.1799329 0.9779739 -0.1143485 0.1746183 -0.978075 -0.1140139 0.17427 0.9780452 -0.1140279 0.1744288 -0.9009959 5.51275e-4 0.4338274 -0.9820094 0 0.1888327 -0.9820094 0 0.1888324 -0.9451814 0 0.326546 -0.9840605 0.002610564 0.1778156 0.8888521 6.78956e-4 0.4581938 0.945177 0 0.3265584 0.9820052 0 0.1888545 -0.957028 0 0.2899957 -0.95703 0 0.2899889 -0.9570326 0 0.2899808 0.9570322 0 0.2899819 0.9570289 0 0.2899928 0.9570319 0 0.289983 -0.9570465 0 0.2899345 0.9570304 0 0.2899879 0.9571004 0 0.2897567 0.9570309 -1.32798e-7 0.2899863 0.9571062 3.61587e-6 0.2897376 -0.9570316 1.90891e-7 0.2899837 0.9570325 0 0.2899808 -0.9570298 0 0.2899898 -0.9570291 0 0.289992 -0.9570887 -2.5159e-6 0.2897955 -0.9570315 0 0.2899839 0.9570292 0 0.2899914 -0.9591715 0 0.2828252 -0.9570322 0 0.2899819 0.9591715 0 0.2828253 -1 0 0 0.9570298 0 0.2899898 1 0 0 -0.9659245 0 0.2588242 0.965925 0 0.2588219 -0.7071086 0 0.7071049 0.7071086 0 0.707105 0.7071086 0 0.7071049 -0.7071086 0 0.707105 -0.2588142 0 0.9659271 0.2588124 0 0.9659277 0.2588124 0 0.9659277 -0.963246 0 0.2686209 -0.9591709 0 0.2828272 0.9591709 0 0.2828272 0.9632456 0 0.2686222 -0.9908168 -0.02818942 0.1322401 -0.9659742 0 0.2586385 -0.9675527 -3.8323e-5 0.2526698 -0.9702733 -1.73369e-4 0.242012 -0.9739829 -6.23846e-4 0.2266204 -0.9779285 -0.001435339 0.208935 -0.9657896 0.001981794 0.2593196 -0.9632431 0 0.2686315 0.9659742 0 0.2586385 0.9632431 0 0.2686315 -0.9674087 0.001605331 0.253215 0.9675526 3.8323e-5 0.2526698 -0.9701974 0.001000285 0.2423139 0.9702733 1.73206e-4 0.242012 -0.9349716 -0.3544047 -0.01501518 0.9338399 -0.3574677 -0.01264905 -0.9938246 0 0.1109631 -0.9929539 -0.003425002 0.1184518 0.994843 0 0.1014275 0.9820045 0 0.1888575 0.9948439 0 0.101418 -0.993826 0 0.1109502 -0.9930884 9.81732e-5 0.1173695 -0.9920844 -3.94552e-5 0.125573 -0.9930828 0 0.117417 0.9930847 0 0.1174001 -0.9920837 0 0.1255786 0.9920821 3.98514e-5 0.1255908 -0.9740019 3.89713e-4 0.2265394 0.9739832 6.23172e-4 0.2266196 -0.9900869 0 0.1404559 -0.9900873 0 0.1404533 0.9920814 0 0.1255965 0.9900869 0 0.1404559 0.9900874 0 0.1404526 0.9930901 -9.93018e-5 0.1173548 -0.9780105 0 0.2085561 0.97793 0.001436352 0.2089285 -0.9881 0 0.1538133 0.9881023 0 0.1537989 -0.9814631 0 0.1916511 0.9814594 0 0.1916701 0.9814602 0 0.1916665 0.9780113 0 0.2085521 0.9740017 -3.90208e-4 0.2265405 0.9701955 -0.001000463 0.2423216 0.9657852 -0.001981258 0.259336 0.96741 -0.001605927 0.2532104 -0.9867313 0 0.1623621 -0.9867323 0 0.1623557 -0.9880986 0 0.1538223 0.9867292 0 0.1623747 0.9881011 0 0.1538063 0.9867298 0 0.1623715 -0.9814621 0 0.1916567 -0.9836442 0 0.1801229 -0.9836419 0 0.180135 0.9836431 0 0.1801288 -0.985629 2.10806e-5 0.1689251 -0.984853 -2.08358e-5 0.1733918 -0.9856281 0 0.1689305 0.9856317 0 0.1689091 -0.9848573 0 0.1733672 0.9848549 2.14384e-5 0.1733809 0.9836453 0 0.1801169 0.9848573 0 0.1733672 0.9856342 -2.16918e-5 0.1688945 -0.967782 -0.2509748 -0.02024531 -0.9851958 -0.1548288 0.07360327 0.9563126 -0.291874 0.01661264 0.9791504 -0.2030744 0.005043804 0.9871122 -0.1530472 0.04675507 -0.9652309 0 -0.2613988 -0.9905405 -0.1150339 0.07481205 0.9872001 -0.1532877 0.04403269 0.9939497 -0.05228841 0.09659254 0.9865887 -0.1548067 0.05174523 0.9884423 -0.132328 0.07396793 -0.9868709 -0.1498724 0.06020146 -0.9935327 0 0.1135475 -0.9935325 0 0.1135482 0.9935324 0 0.1135501 0.9652248 0 -0.2614213 -0.001462459 -2.73382e-4 -0.9999989 -0.9654073 -0.2607467 2.89041e-4 -0.9802022 -0.1979929 -0.001565158 -0.9904538 -0.1377122 -0.006064713 -0.982973 -0.1837493 -5.05449e-4 0.001462459 -2.73383e-4 -0.999999 0.9756729 -0.219231 -6.9496e-4 0.9605929 -0.2779593 2.94855e-4 0.9829733 -0.1837486 5.67121e-5 0.9929171 -0.1185249 -0.008213102 0.9860574 -0.1663654 -0.003690421 -0.9868699 -0.1498771 0.06020605 0.9884427 -0.1323262 0.07396525 0.9935327 1.78415e-7 0.1135475 0.993533 2.13676e-7 0.1135448 0.9902715 -0.1258294 0.05940836 -0.9935327 0 0.1135472 -0.9935327 5.13261e-7 0.1135463 -0.9909785 -0.1180778 0.06339758 -0.9929595 -0.0931372 0.07319104 -0.9925338 -0.1113929 0.04968291 0.9935326 -2.56631e-7 0.1135473 0.9935329 -5.65304e-7 0.1135452 0.9931309 -0.09851169 0.06313914 0.99379 -0.09521347 0.05758398 -0.9935328 1.24698e-6 0.113546 -0.9935327 0 0.1135467 -0.9935329 3.76869e-7 0.1135452 -0.9953942 -0.06537634 0.07011795 -0.9959195 -0.07609403 0.04851925 0.9935325 -1.09731e-6 0.1135482 0.9953422 -0.07298427 0.06298708 0.9961912 -0.06698703 0.05582046 -0.9935323 2.99913e-6 0.1135504 -0.9935328 1.26574e-6 0.1135459 0.993533 -6.32872e-7 0.1135444 0.9935329 1.24698e-6 0.1135453 0.9967741 -0.05216455 0.06099444 -0.9973768 -0.07238596 1.38709e-4 -0.9976127 -0.04517632 0.05223125 -0.001487791 0 -0.9999989 -0.9999975 0 -0.002273797 -0.9973777 -0.07237285 1.38709e-4 0.001487791 0 -0.9999989 0.9999975 0 -0.002273738 0.9997761 0.02073192 -0.004227459 0.9996801 -0.02525496 -0.001406133 0.9977331 -0.06729501 -6.0796e-5 0.9937238 -0.1118622 5.68736e-5 0.9960693 -0.05763906 0.06725972 -0.99721 -0.0392462 0.0634973 -0.9979091 -0.0404396 0.05041998 0.9976863 -0.04092854 0.05428749 -0.9935344 -2.99443e-6 0.1135323 -0.9935318 0 0.1135548 0.9935322 -4.77293e-7 0.1135509 0.9935326 -2.99913e-6 0.1135474 0.9976752 -0.03167241 0.06034153 0.9984381 -0.01529645 0.05373513 -0.999776 -0.02073818 -0.004227519 -0.9983377 -0.01193386 0.05638837 -0.998561 -0.01084649 0.05251973 0.9935349 -1.92171e-6 0.1135281 0.9935324 0 0.1135497 0.998284 -0.0124489 0.05722123 -0.9935341 -4.61211e-6 0.1135342 0.998338 0.01193135 0.05638301 0.998562 0.01084256 0.05250203 0.001462459 2.73383e-4 -0.999999 0.001387298 5.37458e-4 -0.9999989 0.001264929 7.83228e-4 -0.9999989 0.001099467 0.001002311 -0.999999 8.96602e-4 0.001187264 -0.999999 6.63172e-4 0.001331806 -0.9999989 4.07157e-4 0.001430988 -0.9999989 1.37277e-4 0.001481413 -0.9999989 -1.37277e-4 0.001481413 -0.9999989 -4.07157e-4 0.001430988 -0.9999989 -6.63172e-4 0.001331806 -0.999999 -8.96602e-4 0.001187264 -0.9999989 -0.001099467 0.001002311 -0.999999 -0.001264929 7.83228e-4 -0.9999989 -0.001387298 5.37458e-4 -0.9999989 -0.001462459 2.73382e-4 -0.9999989 -0.9982836 0.01244652 0.05722677 -0.9996801 0.02525854 -0.001406013 -0.9984383 0.01530194 0.05373084 0.9972105 0.03925621 0.06348341 0.9979088 0.04044407 0.05042266 -0.9976753 0.03167647 0.06033813 0.9973773 0.0723778 1.38787e-4 -0.9977332 0.06729483 -6.07961e-5 -0.9976862 0.04092842 0.05428731 -0.9967741 0.05216932 0.06098985 -0.9960661 0.05766373 0.06728565 0.997613 0.04516905 0.05223083 0.9953935 0.06538558 0.07011812 0.9959197 0.07609325 0.0485177 -0.9937195 0.1118996 5.70259e-5 0.9973774 0.07237702 1.38788e-4 -0.9829733 0.1837487 5.68646e-5 -0.9929182 0.1185159 -0.008213758 -0.9961916 0.06698119 0.05582159 0.9829731 0.1837494 -5.05374e-4 0.9904543 0.1377089 -0.006064891 -0.995343 0.07296907 0.06299018 0.9929598 0.09313392 0.073192 0.9925335 0.1113958 0.04968178 -0.9860573 0.1663655 -0.003690421 -0.9937897 0.09521472 0.05758601 -0.9931311 0.09850931 0.06314039 0.9802016 0.1979959 -0.001565098 0.9909781 0.1180815 0.06339704 -0.9756729 0.219231 -6.9496e-4 -0.9902712 0.1258313 0.05940926 -0.9865889 0.1548037 0.05175054 -0.9884426 0.1323248 0.073969 -0.9884429 0.1323246 0.0739662 0.9654101 0.2607364 2.88854e-4 0.9868708 0.1498705 0.06020665 0.99054 0.1150383 0.07481217 0.967782 0.2509748 -0.02024614 0.9851959 0.1548289 0.07360231 0.986871 0.1498693 0.06020778 -0.9605929 0.2779593 2.94836e-4 -0.9872006 0.1532856 0.04402846 -0.9939491 0.05230569 0.0965892 -0.9791582 0.2030357 0.005075156 -0.9871133 0.1530404 0.04675638 -0.930775 0.3628694 -0.04454088 -0.9324719 0.3612426 2.93686e-4 -0.9334565 0.3586907 0 0.9324719 0.3612426 2.87345e-4 0.9289718 0.3654885 -0.05856317 0.9327783 0.3604508 1.96113e-4 -0.9652258 4.07527e-6 -0.2614175 0.9652273 -7.97748e-6 -0.2614121 0.9652267 -7.86425e-6 -0.2614142 0.9349726 0.354402 -0.01501584 0.9289677 0.3678654 -0.04115873 -0.9338395 0.3574689 -0.01264786 -0.9303275 0.3645565 -0.03986865 -0.9563093 0.2918848 0.01661092 -0.9652226 4.58115e-6 -0.2614294 0.9652259 -6.59821e-6 -0.2614174 -0.9652364 -2.94774e-5 -0.2613784 -0.9652302 -5.23785e-5 -0.2614012 0.9652184 5.11835e-5 -0.2614453 0.9652761 -2.62446e-4 -0.2612321 0.9652242 5.5296e-6 -0.2614234 -0.9653648 -4.47135e-4 -0.2609034 -0.9652241 2.22226e-6 -0.2614239 -0.965225 -2.5431e-6 -0.261421 0.9652247 1.16805e-6 -0.2614221 0.9652253 2.42645e-6 -0.2614197 -0.9780439 0.1140274 0.1744357 -0.977011 0.1143404 0.1799328 -0.9779754 0.1143397 0.1746157 0.9780087 0.1143587 0.174417 0.9764802 0.1143393 0.1827923 0.9778646 0.115373 0.1745564 -0.9781017 0.1137992 0.1742609 -0.9774438 0.1138452 0.1778849 0.9780803 0.1140205 0.1742364 0.9770713 0.1137474 0.1799814 -0.9781575 0.1136655 0.1740353 -0.9779249 0.1136963 0.1753174 0.9781364 0.1138116 0.1740578 0.9774817 0.1134524 0.1779274 -0.9763073 0.1161409 0.1825795 -0.9777394 0.1154374 0.1752142 0.9753506 0.1165832 0.1873486 0.977531 0.1176953 0.1748748 -0.9781221 0.1139338 0.1740584 -0.9784967 0.1140887 0.1718373 0.9781652 0.1136721 0.1739873 0.9779595 0.1134393 0.1752904 -0.975131 0.1203415 0.1861114 -0.9773066 0.1179414 0.1759597 0.9737872 0.121768 0.1921225 0.9769958 0.1223472 0.1746721 -0.9778054 0.1155943 0.1747415 -0.9790902 0.1158434 0.1672214 0.9780967 0.1138705 0.1742427 0.9784193 0.1145439 0.1719757 -0.9755093 0.1250848 0.1809294 -0.973667 0.1283432 0.1884165 0.9756812 0.1220059 0.1821008 0.9776341 0.1211544 0.1719103 -0.9773712 0.1170116 0.1762213 -0.9789477 0.1203427 0.1648605 0.9777166 0.1152346 0.1754744 0.9785314 0.1185492 0.1685894 -0.9728471 0.1272069 0.1933572 -0.9777739 0.1179485 0.173339 0.9730051 0.1240385 0.1946166 0.9752332 0.1228536 0.1839217 -0.9800675 0.1029527 0.1699075 -0.9454496 0.02207124 0.32502 0.9927788 0.005454778 0.1198357 0.9908217 0.0282045 0.1322003 0.926797 -0.01185667 0.3753755 0.9783182 0.1228459 0.166741 -0.963459 0.04268342 0.264433 -0.9140996 0.0516417 0.4021878 -0.9799184 0.198057 0.02309602 0.9840629 -0.002610504 0.1778022 -0.9652261 0 -0.2614166 -0.9652243 5.55725e-6 -0.2614232 0.9652248 2.72326e-6 -0.2614216 -0.9705046 0.1285878 0.203927 -0.975342 0.1196011 0.1854819 0.9706687 0.1250421 0.2053452 0.9761326 0.1180413 0.1822947 -0.9685491 0.1285599 0.2130379 -0.9762955 0.1149737 0.1833797 0.9687274 0.125085 0.214292 0.974111 0.1190208 0.1922023 -0.9650027 0.1306621 0.2273702 -0.9742788 0.1160598 0.1931605 0.9654029 0.1231046 0.2298753 0.9703676 0.1225127 0.2082725 0.9657982 0.2538072 0.05306458 0.9524819 0.1004064 0.2875705 -0.9597805 0.1298933 0.248896 -0.9707587 0.1160439 0.2101464 0.960183 0.1231039 0.2507871 0.9647635 0.1239064 0.2321178 -0.9451689 0.1207595 0.3034352 -0.9916897 0.1267024 -0.02231884 -0.9978625 0.06535011 0 0.9453035 0.1198999 0.3033567 0.9925644 0.1217215 0 0.9920476 0.1258323 -0.002785265 -0.9639984 0.06314182 0.2583025 -0.9639992 0.06311953 0.2583055 0.9592192 0.1176269 0.257026 -0.7063609 0.04624861 0.7063394 -0.7063554 0.04622977 0.7063462 0.9592276 0.117616 0.2569997 0.7044611 0.0863797 0.7044666 -0.2587744 0.01693874 0.9657893 -0.2587875 0.01692855 0.965786 0.7045235 0.08633196 0.7044101 0.2586804 0.03169971 0.9654427 4.75575e-5 0 1 -2.74988e-5 0 1 -1.07139e-6 0 1 1.00404e-6 0 1 -4.73301e-7 0 1 2.24386e-7 0 1 -3.25835e-7 0 1 -2.33553e-4 0 1 -4.30826e-5 0 1 5.13789e-5 0 1 -2.17184e-5 0 1 0.2587329 0.03166925 0.9654297 -0.9555396 0.1274431 0.2658991 -0.9651528 0.1181267 0.2335082 0.9559056 0.1224301 0.2669371 0.957531 0.1256178 0.259528 -0.9618389 0.2709535 -0.0380854 -0.9190657 0.2391396 0.3132581 -0.91939 0.2390803 0.3123504 0.8894721 0.3578149 -0.2842671 0.9190569 0.2391576 0.3132701 0.9193446 0.2392697 0.3123393 -0.9197262 0.2392684 0.3112146 -0.9202063 0.2393486 0.3097301 0.9191113 0.2389549 0.3132653 0.9202326 0.239309 0.3096823 0.919752 0.2392342 0.3111648 -0.948789 0.1243812 0.2903941 -0.8738031 0.2206744 0.4333254 0.9268863 0.2424578 0.2865241 -0.9578619 0.1218565 0.2600995 0.8909806 0.1348862 0.4335427 -0.8523659 0.04196441 0.5212594 -0.9527123 0.1732245 0.249665 0.952912 0.1744197 0.2480654 0.8999256 0.02303099 0.4354349 -0.9246379 0.3357162 0.1798319 -0.9225096 0.3354943 0.1908396 -0.9269546 0.3364251 0.1660526 0.9245746 0.3358629 0.1798835 0.9189884 0.3340184 0.2095046 0.9267268 0.3370619 0.1660327 -0.9183257 0.3365789 0.2083094 -0.9302678 0.3370499 0.1449106 0.9125185 0.3363413 0.2327755 0.9294139 0.3396411 0.1443388 -0.9207296 0.3346712 0.2006296 -0.927065 0.3370473 0.1641634 0.9211014 0.333697 0.200546 0.9227898 0.3347499 0.1907925 -0.9108868 0.3461548 0.224638 -0.9352226 0.3362772 0.1107993 0.9022281 0.3481627 0.2544943 0.9329617 0.3433599 0.108105 -0.9152997 0.3321533 0.2278175 -0.9284428 0.3458842 0.1354925 0.9163588 0.3296259 0.22723 0.9253993 0.3409037 0.1655925 -0.9038339 0.3306909 0.2715286 -0.9255049 0.36159 0.1126652 0.9087239 0.3208896 0.2669284 0.9240252 0.3539556 0.1445432 -0.9020711 0.3685772 0.224541 -0.9407625 0.332803 0.06486999 0.8953519 0.3723697 0.2443071 0.9357558 0.3483676 0.05478405 -0.2543398 0.050601 0.9657902 -0.8982745 0.3120583 0.3093907 0.8945825 0.3181425 0.3138594 0.9106306 0.3859456 0.1476414 0.9106854 0.3814446 0.1585946 -0.6942533 0.1381475 0.7063481 -0.2543529 0.05061215 0.9657862 -0.9344999 0.3508062 0.06037437 -0.8986339 0.3999916 0.1801771 0.9337857 0.3528859 0.05929404 0.9327965 0.3539864 0.0677092 -0.9143035 0.3717528 0.1607761 -0.8858768 0.19895 0.4190958 -0.9474853 0.1885406 0.2583103 -0.9474866 0.1885432 0.2583032 -0.6942524 0.1381523 0.706348 -0.9807682 0.1951729 0.001162409 -0.9143258 0.3717112 0.1607456 -0.7459405 0.04737573 0.6643255 -0.8993933 0.395444 0.1863217 -0.8994805 0.39531 0.1861856 0.965797 0.2538141 0.05305337 0.8452029 0.1937441 0.4980917 0.8994039 0.3953469 0.1864767 -0.8859036 0.1989659 0.4190315 0.9672466 0.1654084 0.1925465 -0.9324855 0.3553721 0.06466454 -0.9320689 0.3561506 0.0663653 0.9317561 0.3574941 0.06347125 0.93058 0.358882 0.07228213 0.2469145 0.07932645 0.965785 0.2469084 0.0793212 0.965787 0.8874248 0.4037961 0.2223195 0.8629108 0.2631635 0.431428 -0.2414547 0.09835338 0.9654151 -0.9258807 0.3680624 0.08529382 -0.9298389 0.3610867 0.07082402 0.9277341 0.3628378 0.08751231 0.9337515 0.353593 0.05550086 -0.8431022 0.02438151 0.5372004 0.9081825 0.1890025 0.3734737 0.8414484 0.02135747 0.5399153 -0.9240332 0.3687913 0.1007752 -0.9353986 0.3489158 0.0573346 0.9258255 0.3636887 0.1028481 0.9318597 0.3556333 0.07185202 0.6739499 0.2165355 0.7063313 0.6739574 0.2165241 0.7063277 -0.9192407 0.3731687 0.1254658 -0.9334657 0.3510504 0.07352232 0.9232171 0.3617364 0.129681 0.9270495 0.3617868 0.09843593 -0.657418 0.2678035 0.7043315 -0.2414485 0.09835547 0.9654165 0.91974 0.2955765 0.2582885 0.9197573 0.2955129 0.2582997 -0.913411 0.3732511 0.1623694 -0.9305996 0.3515885 0.1018333 0.9170757 0.362631 0.1657439 0.9208772 0.3646544 0.1378858 0.9520527 0.3059307 0.001399099 0.7721636 0.04649484 0.6337204 0.8706398 0.1084256 0.4798234 -0.8430887 0.02434587 0.5372232 -0.947459 0.1886968 0.2582928 -0.8950176 0.3645936 0.2569344 -0.6574186 0.2678076 0.7043294 0.9520614 0.3059042 0.00139904 0.919755 0.2955262 0.2582926 0.92751 0.3731144 -0.02260452 0.2341727 0.111505 0.9657794 0.2341837 0.111503 0.9657769 -0.9807413 0.1953081 0.001162111 -0.8795458 0.3547561 0.3170919 -0.9273971 0.3740711 -0.002327978 -0.9261075 0.3772599 0 -0.895016 0.3645974 0.2569342 -0.9241535 0.3552175 0.1405737 -0.9079092 0.3709852 0.1951176 -0.9041808 0.3701633 0.2131579 0.9041836 0.3701568 0.2131574 0.9079117 0.3709826 0.1951109 0.9036952 0.4281764 1.96676e-4 0.9652256 -2.64944e-5 -0.2614184 -0.7849404 0.2092329 0.5831726 -0.8501664 0.4103356 0.3299119 0.8495185 0.4046888 0.3384456 0.7849398 0.2092344 0.5831729 -0.884043 0.4674056 -1.3509e-4 -0.8756468 0.4829519 -5.14322e-4 -0.8682268 0.4961665 -9.60635e-4 -0.8682115 0.4961935 -9.61587e-4 -0.858427 0.512933 -0.001747786 -0.8456783 0.5336843 -0.003051459 -0.8456698 0.5336977 -0.003053188 -0.8456537 0.5337234 -0.003058373 -0.8456747 0.53369 -0.003051102 -0.8502169 0.5264326 -2.74926e-4 -0.8198516 0.5725411 -0.006333947 -0.8381361 0.5454466 -0.003998398 -0.8922502 0.4515414 0 0.8198497 0.5725437 -0.006334125 0.8383259 0.5451546 -0.00402528 0.8409434 0.5411108 -0.003668785 0.840956 0.5410912 -0.003668844 0.8409408 0.5411148 -0.003671944 0.8482539 0.5295827 -0.002792418 0.8482614 0.5295705 -0.002792418 0.854786 0.5189763 -0.002126455 0.8614974 0.5077601 -0.001482605 0.8717858 0.4898867 -7.08927e-4 0.8717937 0.4898729 -7.08643e-4 0.8833249 0.4687614 -1.46671e-4 0.7789486 0.6269368 -0.01377213 0.8502172 0.5264321 1.01452e-4 -0.9652265 1.78762e-5 -0.2614148 -0.9203429 0.2394892 0.3092152 -0.8258721 0.3711059 0.4245184 -0.9293325 0.2435524 0.277531 0.9203115 0.2394727 0.3093214 0.8738084 0.2206515 0.4333265 -0.9013732 0.3908837 0.1863775 -0.8753321 0.440976 0.1983282 -0.8800961 0.4452846 0.1647806 0.9011394 0.3906505 0.1879894 0.8823826 0.4473061 0.1460086 0.8779451 0.442984 0.1815974 0.8748449 0.4384608 0.2059094 -0.9123943 0.3584869 0.1975446 0.9123952 0.3584852 0.1975433 0.8899316 0.3649892 0.2735047 -0.8840878 0.4464243 0.1381814 -0.8728205 0.4300218 0.2307932 0.8727976 0.4300105 0.2309011 -0.8637232 0.1307324 0.4867148 -0.8486131 0.1059671 0.5182923 -0.7622976 0.04642421 0.6455596 -0.8900563 0.4432006 0.1066455 0.8900694 0.44319 0.1065788 -0.8723664 0.4189502 0.2519079 0.8723618 0.4189661 0.2518975 -0.8960526 0.4344064 0.09154665 0.8960397 0.4344346 0.09154099 -0.8435699 0.4201294 0.3344862 -0.8417182 0.4064754 0.3553708 0.6391683 0.3043314 0.7062905 0.6391555 0.3043376 0.7062995 -0.8173974 0.433225 0.3797073 -0.860724 0.4509904 0.2361394 0.8751155 0.4108108 0.2557485 -0.8808457 0.4675696 0.07409197 -0.8769398 0.4466389 0.1774553 0.8704317 0.4882469 0.06295895 0.8367118 0.481884 0.2601947 0.7643943 0.03900951 0.643568 -0.2198427 0.1370493 0.9658606 0.2198367 0.13705 0.965862 0.2198497 0.1370494 0.965859 -0.8177619 0.4327076 0.3795123 0.7703467 0.4428437 0.4587545 -0.8171139 0.09971612 0.5677865 -0.7215666 0.05990558 0.6897486 -0.8832546 0.4688498 -0.006433129 0.8523805 0.4919388 0.1773241 0.8657768 0.4996758 -0.02747207 -0.8076698 0.4276208 0.4059681 0.7522078 0.4332318 0.4964814 -0.9627195 0.07057666 -0.2611327 0.9570394 0.1285253 -0.259917 0.9630696 0.09640491 -0.2514025 0.8722445 0.4153139 0.2582707 0.8722403 0.4153212 0.2582738 -0.9572474 0.1285283 -0.2591482 -0.957766 0.1214897 -0.2606232 -0.9579351 0.1214618 -0.2600141 0.9581037 0.1214751 -0.2593863 0.9570701 0.1214739 -0.263175 0.9578711 0.1213096 -0.2603212 0.8741357 0.1298392 -0.4680051 0.9598597 0.1030513 -0.2608637 -0.9636088 0.1201608 -0.2387877 -0.957682 0.122574 -0.2604241 -0.9569889 0.1213964 -0.2635056 -0.976504 0.1225344 -0.1772716 0.9862585 0.1026962 -0.1294132 -0.9589366 0.1285436 -0.2528183 0.9569305 0.1285257 -0.2603174 -0.7871797 0.4143056 0.4568359 0.7249892 0.4165967 0.548487 -0.9757172 0.2144068 0.04478651 -0.9856388 0.1075009 -0.13023 -0.9926213 0.1067921 0.05743288 0.9862112 0.1492357 -0.07152646 0.9840056 0.1029793 0.1453554 0.9028787 0.4298958 0 0.9840082 0.1029557 0.1453552 -0.9926202 0.106794 0.05744761 0.9840084 0.1029637 0.1453475 -0.9840177 0.1374688 0.1131879 -0.9332054 0.1101472 0.3420457 -0.9332099 0.1101288 0.3420397 0.7195922 0.05650782 0.6920939 0.8122118 0.1163274 0.5716469 -0.8826616 0.4699946 -0.003722548 0.865707 0.4999081 -0.02536451 -0.7774676 0.09388148 0.6218767 -0.6892138 0.0801509 0.7201113 0.9532963 0.1602489 0.2560204 0.9175462 0.08884811 0.3875761 -0.7818604 0.3864464 0.4892376 -0.7818517 0.3864743 0.4892296 -0.7455536 0.2799834 0.6047802 -0.7163569 0.2653706 0.6452994 0.781857 0.3864684 0.4892258 0.7327227 0.2506274 0.6326954 0.9172397 0.08889377 0.3882902 0.9175146 0.08882761 0.3876556 -0.9289916 0.1153043 0.3516811 -0.9327413 0.1175497 0.3408457 -0.798702 0.1026074 0.5929139 -0.7947257 0.1023511 0.598277 -0.7987575 0.1080752 0.5918668 0.7954338 0.1140664 0.5952092 -0.6003739 0.3742654 0.7067366 -0.2198489 0.1370492 0.9658592 0.6003677 0.3742669 0.7067412 0.6003829 0.3742641 0.7067297 -0.7080152 0.0638417 0.7033056 -0.741053 0.09524762 0.6646566 -0.6889973 0.09090071 0.7190409 0.6955643 0.0839858 0.7135382 0.7724723 0.1049368 0.6263185 -0.6870936 0.1066134 0.7187044 -0.7059566 0.1166386 0.6985847 0.7070996 0.09291648 0.7009828 0.7007386 0.09126663 0.7075564 0.8099033 0.09259361 0.579209 -0.7156268 0.09476536 0.6920245 -0.6989275 0.09577429 0.7087508 0.6997239 0.09296017 0.7083396 0.7374407 0.09795784 0.6682706 0.7079318 0.07071745 0.7027316 0.7760482 0.07827609 0.6257973 -0.7035756 0.1166763 0.7009766 0.7064341 0.0707485 0.704234 -0.6099411 0.1877467 0.7698851 -0.6955868 0.1883715 0.6933075 0.5909802 0.1873049 0.7846396 0.7929759 0.1854801 0.5803331 0.7047958 0.09574162 0.7029199 -0.8753337 0.09161013 0.4747617 0.7142831 0.09572166 0.6932801 -0.8667358 0.4974141 -0.03672122 -0.8586386 0.5115528 0.03245913 -0.8673202 0.4977419 -0.002949416 0.866738 0.4974105 -0.03671652 0.8673153 0.4977504 -0.002969682 -0.866249 0.4993439 0.01638478 0.8662472 0.4993465 0.0164023 -0.8620748 0.5045108 0.04791545 0.8620745 0.5045115 0.04791516 -0.8197535 0.511025 0.2585688 -0.6003788 0.3742631 0.7067337 0.8197537 0.5110251 0.2585678 0.819755 0.5110245 0.2585648 -0.781435 0.3864925 0.4898808 0.6836348 0.3849849 0.6200243 -0.8490808 0.5206496 0.08936434 0.8490824 0.5206468 0.08936542 -0.782677 0.5381477 0.3127523 -0.8240028 0.566586 0 0.7860229 0.5404691 0.3001021 0.7815738 0.5398098 0.3126464 0.8486115 0.5290166 0 0.821583 0.5649194 -0.07659983 -0.8389341 0.5229751 -0.1506216 -0.819755 0.5110244 0.258565 -0.7282705 0.2829605 0.6241437 -0.7040264 0.2722463 0.6559184 -0.9492163 0.1822267 -0.2564803 -0.531554 0.418776 0.7362589 -0.7414153 0.4982081 0.4495466 -0.8171387 0.4823614 0.3156138 -0.7855372 0.5411615 0.3001261 0.8171432 0.4823554 0.3156112 0.5315603 0.4187785 0.736253 0.7414042 0.4982113 0.4495612 -0.8541325 0.4917255 0.1693037 -0.8536611 0.5145943 0.08034598 0.8137529 0.5609687 0.1520537 -0.8176232 0.4826943 0.3138449 0.8175608 0.4827116 0.3139808 -0.8541263 0.4917254 0.1693352 0.8541259 0.4917268 0.1693335 0.8637903 0.4974104 0.08030813 -0.82977 0.4917626 0.2639155 0.814637 0.5178435 0.2611608 0.8349337 0.4957792 0.2389329 0.9393498 0.226384 -0.2576281 -0.8454475 0.5037217 0.1774346 -0.8454626 0.5036991 0.1774271 -0.7318003 0.4359985 0.523807 -0.7814638 0.3864558 0.4898636 -0.8250902 0.5119736 0.2389753 0.7036072 0.2678652 0.6581681 0.7279525 0.2951532 0.6188456 -0.714434 0.2829908 0.6399222 -0.6934697 0.2791502 0.6642101 0.7006747 0.09110903 0.7076398 0.8099254 0.09247368 0.5791974 0.9524921 0.3040654 -0.01740789 0.9460633 0.3084429 -0.099132 0.6827358 0.2552695 0.6846236 0.6022524 0.2545908 0.7566213 -0.9283351 0.2710888 -0.2543717 -0.6425759 0.385484 0.6621921 -0.7375783 0.4424855 0.5100832 0.6435655 0.3860824 0.6608811 0.7375838 0.4424888 0.5100724 0.690495 0.2764725 0.6684159 0.7116891 0.290525 0.6396046 -0.6994259 0.2829871 0.656294 -0.68623 0.284064 0.6696239 0.7898467 0.289852 0.5404887 0.7966243 0.2532212 0.5488796 0.9217272 0.289422 0.2581743 0.9527615 0.3032083 -0.01761621 0.9464733 0.3071858 -0.09912347 0.9524971 0.3040456 -0.0174843 0.9460567 0.3084665 -0.09912168 -0.963595 0.1208499 -0.2384955 -0.9841151 0.1204799 -0.1303923 -0.9633275 0.1226125 -0.2386766 -0.983807 0.122628 -0.1307142 -0.9199063 0.2988423 -0.2539013 -0.9212391 0.2986884 -0.2492066 -0.9038314 0.3533159 -0.2413641 0.92283 0.2241783 0.3132555 0.9019601 0.3584526 -0.2407898 0.902261 0.3572888 -0.2413914 0.7917211 0.2991511 -0.5326222 -0.9019837 0.3568071 -0.243134 0.8997026 0.363235 -0.2420653 -0.901912 0.3572359 -0.2427705 -0.7745934 0.3406745 -0.532866 0.9019064 0.3572487 -0.2427721 0.9446359 0.3138602 -0.09568071 0.9190853 0.3048841 0.2496554 -0.8328428 0.2668973 0.484911 -0.9244894 0.3585229 -0.1295406 -0.6871214 0.1074709 0.7185501 -0.7939849 0.1088836 0.5981073 0.6960163 0.2871354 0.6581144 0.7003434 0.2329584 0.6747218 0.8855817 0.2834438 0.3679739 0.7733955 0.2902848 0.5635551 -0.9222523 0.3249335 0.2094492 -0.9242514 0.3678636 0.1021559 -0.9122447 0.3989744 -0.09289234 -0.6869902 0.1169031 0.7172016 -0.6823506 0.1064888 0.7232274 -0.6543322 0.007659554 -0.7561686 -0.8343095 0.275903 0.4772894 -0.7586322 0.3048726 0.5757864 -0.6874371 0.2844377 0.6682256 -0.6832833 0.2846071 0.6724007 0.6027305 0.2484385 0.7582839 -0.895683 0.391462 0.2109729 -0.8956892 0.3914418 0.2109842 -0.8815897 0.3356392 0.3318825 0.6835663 0.2835941 0.6725411 0.6973163 0.2874295 0.6566082 -0.807143 0.3594341 0.4683241 -0.8071127 0.3594533 0.4683616 0.6826284 0.2551866 0.6847615 0.592966 0.2542399 0.7640377 -0.529886 0.1164283 0.8400389 -0.6798254 0.2841489 0.6760894 -0.6820052 0.2837155 0.674073 0.681619 0.2843905 0.6741792 0.6862215 0.2850124 0.6692294 -0.6768389 0.2837496 0.6792462 0.6797301 0.2837413 0.6763564 0.6768385 0.2837511 0.6792458 -0.8946071 0.3771124 -0.2397175 -0.9283253 0.2711244 -0.2543696 -0.8939357 0.3771104 -0.2422121 0.8933333 0.3771041 -0.2444342 0.893629 0.3771051 -0.2433496 0.9019157 0.357226 -0.2427711 0.9383722 0.2572581 -0.2308161 -0.7001682 0.3046986 0.645696 -0.7438079 0.3062077 0.5941268 0.9028171 0.3570297 -0.2396899 -0.6750684 0.2995424 0.6742084 -0.7108854 0.2988252 0.6366675 -0.6444118 0.3884783 0.6586487 0.8856223 0.2833002 0.3679866 0.7733998 0.2902374 0.5635734 -0.8894298 0.3888539 -0.240224 0.8903349 0.25379 0.3780139 0.971679 0.2343177 -0.03058123 0.7536215 0.3569988 0.5519119 0.7969129 0.290075 0.529893 0.5845578 0.3331565 0.7397966 0.8842747 0.3956329 0.2480584 0.682628 0.2552925 0.6847224 0.6623022 0.2553911 0.7043659 -0.8328278 0.2669087 0.4849306 -0.9323491 0.3555281 -0.0657652 0.9101732 0.2614226 0.3213146 0.9070053 0.4105665 -0.0936836 0.9528486 0.2995698 -0.0483492 0.9094648 0.2636793 0.3214764 0.9506943 0.3060854 -0.04992139 -0.9008862 0.3572858 -0.2464773 -0.8455587 0.3530437 -0.4004881 -0.7578349 0.3862498 -0.5258305 0.7781743 0.3414016 -0.5271525 0.8544681 0.3954125 -0.3369471 0.8324109 0.3950152 -0.3886582 -0.7742573 0.2148276 0.595294 0.8819722 0.4025401 0.2451258 0.666024 0.4637041 0.5842865 0.629059 0.4119802 0.6592095 -0.629431 0.4126347 0.6584446 -0.6616015 0.4606166 0.5917059 0.9717066 0.2342404 -0.0302934 0.797246 0.2890407 0.529957 0.9716851 0.2343164 -0.03039729 0.7968834 0.2902029 0.529867 0.6310569 0.447703 0.6335057 0.8698166 0.4805809 -0.111629 0.8543729 0.4630933 -0.2357786 0.6826481 0.2552687 0.6847113 0.7123257 0.2547396 0.6539877 -0.8059933 0.5416054 0.2388271 0.8059922 0.5416077 0.2388257 0.8059916 0.5416075 0.2388283 0.6345795 0.4228416 0.6469265 0.6300311 0.4230353 0.6512312 -0.6323928 0.4185846 0.6518178 0.8955069 0.4382539 -0.07746565 0.8975475 0.4369207 -0.05923533 0.7676689 0.3910006 0.5077431 0.9255245 0.3087709 0.219237 0.7418962 0.4912438 0.4563656 0.7419591 0.4912076 0.4563024 0.8587868 0.4509637 0.2431399 0.71218 0.288715 0.6398776 0.8231213 0.289305 0.4886453 -0.9061605 0.3597137 -0.2224392 -0.7585375 0.2538414 0.6001545 -0.9323429 0.3555451 -0.0657615 0.8952718 0.4388232 -0.07696002 0.8971751 0.4376899 -0.05919897 -0.9009054 0.3572308 -0.2464864 -0.8455596 0.3530184 -0.4005087 0.8951584 0.4390606 -0.07692366 0.8724497 0.442667 -0.2070688 0.8976897 0.4369213 -0.0570358 0.8922506 0.447682 -0.05890542 0.9008967 0.3572569 -0.2464807 0.9069536 0.3570634 -0.223475 0.8073521 0.4531669 -0.3779186 0.8560425 0.4673936 0.2207593 0.8560078 0.4674197 0.2208381 -0.8673747 0.4509614 -0.2104637 0.6808339 0.4068666 0.6090361 0.6945258 0.4186978 0.5850865 0.7643346 0.4458371 0.4658563 -0.6815075 0.4073246 0.6079755 -0.7074295 0.4234995 0.5658548 -0.6945126 0.4187067 0.5850958 -0.7695989 0.4489212 0.4540786 -0.6542892 0.3910605 0.6472846 0.6543121 0.3909971 0.6472998 -0.7696174 0.4489053 0.4540628 0.7324997 0.508939 0.4521341 0.8176602 0.4776988 0.3213032 -0.6341613 0.4234646 0.6469292 -0.6359086 0.4236255 0.645106 0.6363312 0.4236896 0.6446471 -0.652953 0.390825 0.6487745 0.6529592 0.3907694 0.6488016 0.732478 0.5089438 0.4521641 -0.8067188 0.4958195 0.3215085 -0.7401915 0.5067052 0.4420028 0.8420155 0.4923238 0.2205163 -0.8441387 0.4830124 -0.2326568 -0.846405 0.4831228 -0.2240332 0.8537392 0.4830858 -0.1943131 -0.6401607 0.4242584 0.6404679 -0.8434695 0.4938781 0.2112909 0.5698747 0.4114599 0.7112972 0.6513298 0.3910505 0.6502685 -0.558982 0.4037392 0.724247 -0.8434922 0.4938536 0.2112576 -0.8434249 0.4939195 0.2113714 0.8420394 0.4923101 0.2204554 -0.8273312 0.5559453 0.08030074 -0.8059906 0.5416094 0.2388272 0.8273304 0.5559468 0.08029812 0.8273294 0.5559481 0.08029824 0.842006 0.4923437 0.2205077 -0.8540407 0.5180561 -0.04724776 -0.8548676 0.5161607 -0.05272334 0.8540667 0.5180019 -0.0473743 0.8548775 0.5161436 -0.05272841 -0.2064582 0.1564996 0.9658587 0.2064574 0.1564989 0.9658589 0.2064553 0.1564996 0.9658593 -0.8408194 0.5018721 -0.2028473 0.8418473 0.5021927 -0.1977269 0.8415765 0.5007902 -0.2023813 -0.8415424 0.5008686 -0.2023288 -0.8370979 0.4982516 -0.2258594 0.8371338 0.4981856 -0.225872 -0.8298194 0.5576234 -0.02135419 -0.8201082 0.5709744 0.03756034 -0.8273274 0.5559511 0.08029866 0.8297792 0.5575964 0.02351129 -0.8398972 0.4903782 -0.2325983 -0.8491165 0.4922748 -0.1914861 -0.8113867 0.5404067 -0.2227385 -0.7863795 0.567979 -0.2429141 0.8039357 0.5523306 -0.220496 0.8081953 0.5440672 -0.2254136 0.7864877 0.56786 -0.2428421 0.8556154 0.5025032 -0.1241495 0.8360625 0.5070369 -0.2095547 -0.8174122 0.5615671 -0.1283733 -0.8029917 0.551684 -0.225498 0.8174049 0.5615816 -0.1283567 -0.8263676 0.562853 -0.0176987 -0.8469724 0.5018486 -0.1754593 0.8263574 0.5628675 -0.01771706 0.8413639 0.5291564 -0.1100014 0.8438176 0.5335329 -0.05757147 -0.5638021 0.4273785 0.7067354 -0.2064567 0.156498 0.9658593 0.563798 0.4273824 0.7067362 0.5638002 0.4273801 0.7067359 -0.851 0.5037297 -0.1485112 0.843816 0.533532 -0.05760484 -0.8076528 0.5623307 0.1774291 -0.807663 0.5623167 0.1774281 0.8076704 0.5623087 0.1774189 0.8204993 0.5712484 -0.0213586 -0.8495922 0.506081 -0.1485773 -0.8515567 0.5066199 -0.1348611 -0.828351 0.5594691 0.02879238 0.8283529 0.5594752 0.02862119 0.84195 0.5367503 -0.05495023 0.8436297 0.5347853 -0.04789179 -0.7059208 0.4914799 0.510023 -0.7059145 0.4914718 0.5100395 0.8076475 0.5623359 0.1774367 0.705916 0.491481 0.5100285 -0.8285292 0.5583121 0.04274529 -0.8391307 0.5436304 -0.01804578 0.8285479 0.5582746 0.04287242 0.8393338 0.5433188 -0.0179857 0.7059239 0.4914669 0.5100312 -0.8144173 0.568741 -0.115145 0.814414 0.5687426 -0.1151598 -0.7698196 0.5835443 0.2585616 -0.5637952 0.4273811 0.7067393 0.7698143 0.58355 0.2585639 0.769816 0.5835447 0.258571 -0.6890799 0.6888876 0.2249507 -0.7969138 0.6040887 -0.002301812 -0.769813 0.5835507 0.2585668 0.7969162 0.604089 0.001138508 -0.7627841 0.6009455 0.238799 0.7627862 0.6009425 0.2387999 0.6577149 0.4748899 0.5847142 -0.6576461 0.4749898 0.5847105 -0.6576243 0.4749961 0.58473 -0.7829762 0.6168487 0.08028864 -0.7627844 0.600944 0.2388024 0.7627846 0.6009442 0.238801 0.782974 0.616851 0.08029043 0.7829759 0.6168489 0.08028876 -0.8076667 0.5623123 0.1774247 -0.8204931 0.5712575 -0.02135866 0.807666 0.5623118 0.1774296 0.820492 0.571259 -0.02135932 -0.7854022 0.6187584 -0.01677769 -0.7777146 0.6277227 0.03352946 -0.7829726 0.6168525 0.08029276 0.7852788 0.6186612 0.02440428 0.657712 0.474886 0.5847207 0.7678042 0.5543725 0.3211666 -0.7677147 0.5544978 0.3211641 -0.7677177 0.5544935 0.3211644 0.8096308 0.5845713 -0.05267202 0.8096302 0.5845724 -0.05267244 -0.8095353 0.5847038 -0.0526694 -0.1913449 0.1746477 0.96586 0.1913579 0.1746484 0.9658572 0.1913384 0.1746485 0.9658611 0.7678066 0.5543718 0.3211621 -0.8095382 0.5846993 -0.05267632 -0.7738377 0.622833 -0.1151276 -0.7790085 0.6270135 1.0233e-4 0.7738596 0.6228016 -0.1151507 -0.7738519 0.6228167 -0.1151206 -0.7738355 0.6228322 -0.1151465 -0.758951 0.6108422 -0.2255333 0.7738389 0.6228299 -0.1151364 0.7580742 0.6101376 -0.2303385 0.7898468 0.5702857 -0.2256469 -0.7657989 0.6181182 0.1774322 -0.7658247 0.6180869 0.1774291 0.7658247 0.6180869 0.1774291 0.7780953 0.6280277 -0.01220864 -0.6693298 0.5402441 0.5100335 -0.6693426 0.5402415 0.5100193 0.7657986 0.6181203 0.1774256 0.669305 0.5402541 0.5100554 -0.7790227 0.6269958 1.02333e-4 0.7790217 0.6269969 1.02236e-4 0.7738474 0.6228219 -0.1151223 -0.7320286 0.681268 -0.002827703 -0.7390074 0.6736946 -0.001955926 0.739007 0.6736935 -0.002408027 -0.5858517 0.4728562 0.6581678 -0.6178179 0.4462303 0.6474407 0.5931456 0.478745 0.647288 0.6693553 0.5402349 0.5100097 -0.5225471 0.4769403 0.7067337 -0.1913447 0.1746482 0.9658599 0.5225426 0.4769418 0.706736 0.5225392 0.4769392 0.7067403 -0.713481 0.6512205 0.258567 -0.5225316 0.4769446 0.7067423 0.7134801 0.6512197 0.2585714 0.7134861 0.6512157 0.2585646 -0.6744849 0.6745332 0.3001253 0.67448 0.6745283 0.3001472 0.7071111 0.7070987 -0.00232619 -0.7477236 0.5890696 0.3064416 -0.6614879 0.6614844 0.3533725 -0.5727381 0.6197 0.5366032 -0.6910521 0.6386654 0.3384574 -0.7048376 0.7048376 -0.0800504 -0.7385961 0.6741442 -0.002320766 0.7477211 0.5890732 0.3064407 0.6614826 0.661491 0.3533701 0.7071045 0.7071052 -0.00232315 0.6658689 0.7295359 -0.1561921 0.738596 0.6741443 -0.002321302 -0.7134885 0.6512138 0.2585631 -0.7627905 0.6009374 0.238799 0.7627818 0.6009478 0.2388004 -0.7131451 0.6590892 0.2388002 0.7131446 0.659088 0.2388054 0.7131459 0.6590874 0.2388028 0.6197082 0.5727272 0.5366053 -0.6576275 0.4749904 0.5847309 0.657709 0.474883 0.5847265 0.6035552 0.4357829 0.6676934 -0.7131459 0.6590874 0.2388028 -0.7320231 0.6765318 0.08029294 0.7320247 0.6765307 0.08028733 0.732023 0.6765322 0.08029097 -0.7343904 0.6787273 0 -0.7316349 0.6815262 0.01524895 -0.7320226 0.6765334 0.08028495 0.7343202 0.6786645 0.01372796 -0.7271511 0.6767538 -0.1151334 0.7320315 0.6812688 -0.001665711 0.727158 0.6767451 -0.1151407 0.7271659 0.6767405 -0.1151177 -0.7271667 0.6767365 -0.1151363 -0.78813 0.5692389 -0.2341327 -0.7134102 0.6639375 -0.2241272 0.7126227 0.6632078 -0.2287455 0.7246445 0.6511058 -0.2257248 -0.7200998 0.6707998 0.1774374 -0.7201237 0.6707748 0.1774348 0.7201076 0.6707933 0.1774306 0.7317217 0.6816035 0 -0.8095362 0.5847023 -0.05267357 0.8096339 0.5845673 -0.05266946 -0.6293731 0.5863006 0.5100405 -0.6294025 0.586283 0.5100244 0.7201182 0.6707845 0.1774203 0.6293764 0.5863025 0.5100342 -0.1746485 0.1913469 0.9658594 0.1746447 0.1913454 0.9658604 0.174652 0.1913461 0.9658588 -0.5531896 0.5153035 0.654556 -0.5668414 0.509484 0.6473924 0.5669336 0.5094016 0.6473765 0.5531636 0.5152792 0.6545971 0.6294047 0.5862799 0.5100253 -0.4769479 0.5225386 0.7067349 -0.1746447 0.1913454 0.9658604 0.4769501 0.5225378 0.706734 0.4769423 0.5225435 0.706735 0.6034318 0.5421905 0.5847218 0.6034255 0.5421933 0.5847257 -0.6033516 0.5422853 0.5847167 0.7044358 0.6329491 0.3211631 -0.6033415 0.5422904 0.5847222 -0.7043295 0.6330667 0.3211644 -0.704337 0.6330602 0.321161 -0.6512197 0.7134811 0.2585685 -0.4769438 0.522543 0.7067344 0.6512201 0.7134821 0.258565 0.651215 0.713484 0.2585722 -0.6741442 0.7385961 -0.002325117 -0.6512203 0.7134807 0.2585683 0.7428078 0.6674299 -0.05266863 -0.7240471 0.6507813 -0.2285598 -0.742702 0.6675473 -0.05267196 0.7428084 0.6674293 -0.05266815 0.7044383 0.632948 0.3211596 -0.7426993 0.6675506 -0.05266839 -0.6590869 0.7131457 0.238805 0.6590872 0.7131455 0.2388046 0.6590893 0.7131444 0.2388022 0.6386775 0.691043 0.3384532 -0.6590893 0.7131448 0.238801 -0.6765304 0.732025 0.08028745 0.6765314 0.732024 0.08028757 0.6765324 0.7320231 0.08028799 -0.6767312 0.727169 -0.115153 -0.681271 0.7320312 3.61588e-4 0.6812696 0.7320325 3.61631e-4 0.6767317 0.7271727 -0.1151269 -0.6707797 0.7201175 0.1774413 -0.6708007 0.7201033 0.1774201 -0.6816089 0.7317167 0 0.6708007 0.7201033 0.1774201 0.6787277 0.7343901 0 0.6815296 0.7316316 0.01525485 -0.6786597 0.7343246 0.01373207 -0.6765339 0.7320219 0.08028668 -0.6767386 0.727167 -0.1151224 -0.7235562 0.6512736 -0.2287124 -0.663205 0.7126253 -0.2287452 0.6767328 0.727172 -0.1151238 0.6639378 0.7134099 -0.2241272 0.6507816 0.7240468 -0.2285602 0.6494537 0.7253449 -0.2282209 -0.5862821 0.6294003 0.5100281 -0.5863019 0.6293773 0.5100337 0.6707828 0.7201166 0.1774335 0.5862825 0.6293997 0.5100285 -0.5152808 0.5531634 0.654596 -0.562573 0.5061711 0.6536838 0.5053334 0.5632512 0.6537479 0.5153053 0.5531897 0.6545544 0.586287 0.6293866 0.5100394 -0.1564959 0.2064532 0.9658603 0.1564937 0.2064543 0.9658604 0.1565071 0.2064548 0.9658581 -0.4273822 0.5638005 0.7067344 -0.1564947 0.2064563 0.9658598 0.4273883 0.5637971 0.7067334 0.4273775 0.5638031 0.7067352 -0.6767336 0.7271714 -0.1151236 -0.6812701 0.7320322 3.61599e-4 0.6812701 0.7320322 3.61665e-4 0.6767343 0.7271722 -0.1151142 -0.6269973 0.7790211 -7.62228e-4 -0.6026323 0.7980149 -0.002600729 0.6026339 0.7980169 -0.001244902 -0.5835408 0.7698181 0.2585734 -0.4273771 0.5638015 0.7067368 0.5835409 0.7698183 0.2585726 0.5835489 0.769814 0.2585673 -0.6009408 0.7627871 0.2388015 -0.5890775 0.7477148 0.3064478 0.600941 0.7627872 0.2388005 0.589075 0.7477195 0.3064412 -0.6745563 0.6744596 0.3001302 -0.707145 0.7070648 -0.002326726 0.6745278 0.6744915 0.3001225 0.6888471 0.6891356 0.2249041 0.6040881 0.7969142 -0.002302408 -0.6040863 0.7969182 0.001138627 -0.5835408 0.7698206 0.258566 -0.5404603 0.7860261 0.3001095 -0.5649212 0.8215817 -0.07660216 0.5381703 0.782656 0.3127659 0.5411457 0.7855453 0.3001331 0.5665866 0.8240023 0 0.5229765 0.8389323 -0.1506257 -0.600942 0.7627866 0.2388001 -0.6009431 0.7627851 0.238802 -0.5398164 0.7815673 0.3126515 -0.4187987 0.5315579 0.7362431 0.6009453 0.7627843 0.2387992 0.6009425 0.7627862 0.2388 0.4187989 0.531557 0.7362436 -0.6181033 0.7658137 0.1774197 -0.6181191 0.7657969 0.177437 -0.6280246 0.7780979 -0.0122016 0.61812 0.7658003 0.1774193 0.6187634 0.7853986 -0.0167672 0.6277177 0.7777187 0.03352999 -0.6228401 0.7738355 -0.1151034 0.6269909 0.779015 -0.004247605 0.6228212 0.7738479 -0.1151239 0.6228384 0.7738369 -0.1151031 -0.6228229 0.7738484 -0.11511 -0.651107 0.7246435 -0.2257245 -0.6101381 0.7580736 -0.2303388 0.6108423 0.7589509 -0.2255334 0.5692372 0.7881314 -0.2341326 -0.5402169 0.6693426 0.5100454 -0.5402579 0.6693215 0.5100296 0.6181039 0.7658085 0.1774401 0.5402292 0.6693367 0.5100401 -0.6168498 0.7829754 0.0802868 0.6168476 0.7829768 0.08029055 0.6168527 0.7829731 0.08028775 -0.6186671 0.7852742 0.02440428 -0.6168496 0.7829753 0.0802896 -0.4787443 0.5931442 0.6472896 -0.4357858 0.6035563 0.6676905 -0.509401 0.5669346 0.6473762 0.5094826 0.5668416 0.6473934 0.4728587 0.5858488 0.6581686 0.5402514 0.6693284 0.5100274 0.5425205 0.6029521 0.5849105 0.5422857 0.6033427 0.5847254 0.5422976 0.6033481 0.5847089 -0.6028135 0.5433253 0.5843061 -0.5421876 0.6034362 0.5847199 -0.1370549 0.2198495 0.9658583 0.1370375 0.2198465 0.9658614 0.1370611 0.2198485 0.9658576 0.6330585 0.7043388 0.3211603 -0.5421904 0.603429 0.5847249 -0.63295 0.7044335 0.3211666 -0.6329521 0.7044343 0.3211603 0.6667074 0.7434597 -0.05262023 0.6675503 0.7426999 -0.05266523 0.6675448 0.7427044 -0.05266958 -0.741726 0.668637 -0.05260419 -0.6674323 0.7428054 -0.05267137 -0.6674281 0.742809 -0.05267554 0.6330694 0.7043296 0.3211588 -0.1370503 0.2198451 0.9658599 -0.3742668 0.6003748 0.7067351 0.3742608 0.6003762 0.7067371 0.3742654 0.6003772 0.7067338 -0.5416101 0.8059906 0.2388261 -0.4982067 0.7414102 0.4495565 0.5416072 0.8059927 0.2388256 0.5416116 0.80599 0.2388244 0.4982135 0.7414047 0.449558 -0.3742617 0.6003776 0.7067354 -0.511027 0.8197513 0.2585719 0.5110155 0.8197601 0.2585663 0.5110271 0.8197515 0.2585711 -0.5623344 0.8076492 0.1774342 -0.5712575 0.8204931 -0.02135866 0.5623297 0.8076518 0.1774371 0.57126 0.8204914 -0.02135354 -0.5687557 0.8144069 -0.1151449 -0.5725547 0.8198664 -6.15637e-4 0.5725552 0.819866 -6.15638e-4 0.5687542 0.8144089 -0.1151385 -0.5623028 0.8076714 0.1774334 -0.4914573 0.7059172 0.5100498 -0.4914898 0.705913 0.5100243 0.5623157 0.8076608 0.1774407 0.562332 0.8076545 0.1774179 0.4914785 0.7059195 0.5100262 -0.5616192 0.8173725 -0.1283988 -0.5628325 0.8263814 -0.0177018 -0.5595837 0.8282601 0.02917957 -0.5582513 0.8285736 0.0426774 -0.5523314 0.8039349 -0.2204964 -0.5702865 0.7898461 -0.225647 -0.5440676 0.8081951 -0.2254137 0.5582541 0.8285717 0.04267758 0.5595837 0.8282601 0.02917957 0.5628325 0.8263814 -0.0177018 0.5616192 0.8173725 -0.1283988 0.5516836 0.8029919 -0.2254983 -0.5290124 0.8486141 0 -0.511026 0.8197541 0.258565 -0.5416089 0.8059907 0.2388279 -0.5559478 0.8273293 0.08030122 0.5559491 0.827329 0.08029717 0.5559468 0.8273299 0.08030235 -0.463705 0.6660213 0.5842888 -0.4119981 0.6290549 0.6592022 -0.4228408 0.6345803 0.6469262 0.4185656 0.6324051 0.651818 0.4126424 0.6294264 0.6584441 0.4606257 0.6615853 0.591717 0.4462287 0.6178219 0.6474382 0.4234659 0.6341612 0.6469283 0.4914773 0.7059153 0.510033 -0.5623379 0.8076463 0.1774364 -0.5712515 0.8204972 -0.02135592 0.5576198 0.8298218 -0.02135539 0.5709778 0.8201056 0.03756731 -0.557595 0.8297805 0.02349752 -0.5559478 0.8273297 0.08029758 -0.1115182 0.2341732 0.9657777 0.09836828 0.2414482 0.9654152 0.09833508 0.2414479 0.9654186 -0.1114907 0.234174 0.9657808 -0.07932835 0.2469096 0.9657861 0.05059844 0.2543496 0.9657878 0.05061465 0.2543435 0.9657887 -0.07932811 0.246909 0.9657862 -0.03167241 0.2587291 0.9654306 0.01695239 0.2587851 0.9657862 0.01693266 0.2587754 0.9657891 0 0.258815 0.965927 0 0.2588136 0.9659273 -0.03169989 0.2586846 0.9654417 -0.3043354 0.6391564 0.7062996 0.2678008 0.6574199 0.7043308 0.2678046 0.6574184 0.7043308 -0.4957799 0.8349332 0.238933 -0.4826749 0.8176292 0.3138592 -0.4823582 0.8171415 0.3156113 0.4826576 0.8176017 0.3139575 0.4917703 0.8297658 0.2639145 0.5119722 0.8250905 0.2389772 0.4823582 0.8171415 0.3156113 -0.3043318 0.6391571 0.7063005 -0.216532 0.6739485 0.7063338 -0.5455767 0.838061 -1.56823e-4 -0.5436609 0.839143 -0.01648592 0.5457202 0.8379676 -1.59111e-4 0.5434744 0.8392326 -0.01801568 -0.5415614 0.8406614 -9.15066e-5 -0.5350546 0.8434609 -0.04785817 0.5342117 0.8453507 3.0341e-5 0.507094 0.8513812 -0.1341866 0.4749873 0.6576448 0.584714 -0.4748852 0.6577109 0.5847225 -0.5367524 0.8419532 -0.05487883 0.5062133 0.8495704 -0.1482505 -0.5415516 0.8406676 -8.9811e-5 -0.5335447 0.8438247 -0.05735838 0.5341913 0.8453637 3.08113e-5 0.5035846 0.8511879 -0.147925 -0.5331566 0.8440647 -0.0574364 -0.5292441 0.8413086 -0.1100023 0.5019263 0.8469595 -0.1752988 0.1381449 0.6942523 0.7063496 0.1381568 0.6942465 0.706353 -0.4919596 0.852366 0.1773356 -0.4996693 0.8657802 -0.02748078 -0.4974098 0.8667385 -0.03671389 -0.4999039 0.8657092 -0.02537357 0.5037243 0.8454455 0.1774362 0.4974095 0.8667386 -0.03671884 0.5115562 0.8586362 0.0324701 -0.5415455 0.8406715 -9.05174e-5 -0.2165471 0.6739398 0.7063375 -0.08632475 0.7045178 0.7044166 0.5342116 0.8453509 3.04659e-5 0.4923453 0.8490684 -0.1915175 -0.416575 0.7249849 0.5485092 -0.4881999 0.8704566 0.06297963 -0.4818678 0.8367238 0.2601859 -0.4438897 0.7698779 0.4585303 -0.4328137 0.7524736 0.4964432 -0.3850099 0.6836243 0.6200205 -0.4424885 0.7375833 0.5100734 0.4360045 0.7318051 0.5237952 0.503694 0.8454644 0.1774325 0.4424989 0.7375848 0.5100623 -0.5301179 0.8479239 1.75857e-5 -0.5025306 0.8555903 -0.1242109 -0.4153174 0.8722439 0.2582679 0.3645979 0.8950172 0.2569294 0.3645975 0.8950166 0.2569319 0.04624873 0.7063623 0.7063381 0.0462507 0.7063501 0.7063501 -0.5024542 0.8556379 -0.124193 -0.4897801 0.8400444 -0.2333258 0.4903517 0.8399143 -0.2325925 0 0.7071091 0.7071045 0 0.7071062 0.7071074 -0.08637529 0.7044674 0.7044608 0.4750002 0.6576343 0.5847153 0.4749906 0.6576415 0.584715 0.554497 0.7677153 0.3211643 -0.474883 0.6577228 0.584711 -0.5543713 0.7678069 0.3211622 -0.5543708 0.7678043 0.321169 -0.4917191 0.8541315 0.1693275 -0.5178482 0.8146331 0.2611631 -0.4974069 0.8637921 0.08030903 0.4917246 0.8541329 0.1693043 0.49172 0.8541322 0.1693217 0.5145901 0.8536639 0.08034384 -0.3860751 0.643569 0.6608819 0.3884735 0.6444131 0.6586503 0.3854856 0.6425732 0.6621938 -0.4805855 0.8698194 -0.1115884 -0.4630974 0.8543705 -0.2357795 -0.4830253 0.853774 -0.1943107 0.5404095 0.8113845 -0.2227393 0.4830423 0.8441216 -0.2326561 0.4831598 0.8463761 -0.2240629 0.4830699 0.8464519 -0.2239705 -0.5301141 0.8479264 1.74306e-5 0.5342044 0.8453555 3.05685e-5 -0.357828 0.8894681 -0.2842632 -0.2391349 0.9190593 0.3132803 -0.3731193 0.9275081 -0.02260237 -0.4299038 0.9028747 0 0.3547687 0.8795336 0.317112 0.3772625 0.9261064 0 0.3740674 0.9273986 -0.002331137 -0.4153215 0.8722442 0.25826 -0.5206643 0.8490715 0.08936679 -0.5044972 0.8620827 0.04791802 -0.4993629 0.866238 0.01638472 -0.4977423 0.86732 -0.00297147 -0.5609688 0.8137531 0.1520527 0.5206684 0.8490689 0.0893675 0.4977431 0.8673195 -0.00297147 0.4993629 0.866238 0.01638472 0.5044983 0.8620821 0.04791808 0.534204 0.8453557 3.05452e-5 -0.4457386 0.8951633 1.74196e-5 -0.5280978 0.8491176 -0.01059114 0.4457386 0.8951631 -2.41905e-4 -0.29553 0.9197539 0.2582923 -0.2955142 0.9197571 0.2582988 -0.2392829 0.9193391 0.3123451 -0.2389382 0.9191175 0.3132599 0.2709391 0.9618433 -0.03807228 0.2391564 0.9190609 0.3132592 -0.5167336 0.8560976 -0.009129941 0.5100388 0.8601117 -0.008275866 0.3888459 0.8894331 -0.2402242 0.5847014 0.8095371 -0.05267155 -0.5845717 0.8096305 -0.05267226 0.5847044 0.8095349 -0.05267149 0.5544956 0.7677164 0.3211641 -0.584567 0.809634 -0.05267167 -0.5845733 0.8096291 -0.05267739 0.1887086 0.9474523 0.2583089 0.188551 0.9474844 0.2583057 -0.5043932 0.8634405 -0.00762403 -0.3570374 0.9028146 -0.2396874 -0.2395323 0.9203014 0.3093054 -0.2394354 0.9201825 0.3097338 0.2390648 0.9193936 0.3123518 0.2394285 0.9201589 0.3098091 0.2395312 0.9203249 0.3092361 -0.2955295 0.9197558 0.2582861 -0.1176163 0.9592279 0.2569987 -0.2206452 0.8738126 0.4333211 -0.3649922 0.8899293 0.2735082 0.2435477 0.9293321 0.2775362 -0.3059102 0.9520594 0.001395285 0.1885479 0.9474874 0.258297 0.06312584 0.9639994 0.2583029 0.06311905 0.9639993 0.2583047 0 0.9659277 0.2588124 0 0.9659262 0.2588177 -0.1176257 0.9592217 0.2570177 0.4242557 0.6401497 0.6404808 0.4037404 0.5589873 0.7242423 0.423609 0.6359359 0.64509 -0.474891 0.657711 0.5847177 -0.4230455 0.6300197 0.6512356 -0.4236403 0.6364046 0.644607 -0.4114632 0.5698714 0.7112978 0.195404 0.9807222 0.001158893 0.1951641 0.9807699 0.001161515 -0.3059643 0.9520421 0.001398086 0.120764 0.9451696 0.3034312 0.1267081 0.9916889 -0.02232128 -0.1198952 0.9453026 0.3033619 -0.1258296 0.992048 -0.002786576 -0.1217158 0.992565 0 0.4920618 0.8705377 -0.006280303 0.2711082 0.9283291 -0.2543731 0.3771147 0.8946061 -0.2397173 0.0653463 0.9978626 0 -0.4854925 0.8742229 -0.005598187 -0.2572783 0.9383653 -0.230821 -0.3584856 0.9123954 0.197542 0.3711018 0.8258789 0.4245087 0.3584855 0.9123951 0.1975435 -0.2393513 0.9197319 0.3111339 -0.2424563 0.9268885 0.2865182 -0.1348887 0.8909802 0.433543 0.2393506 0.9197324 0.3111329 0.2206749 0.873804 0.4333233 0 0.9570313 0.2899849 0 1 0 0 0.9570319 0.2899826 -0.4855059 0.8742156 -0.00560081 -0.2263855 0.9393499 -0.2576268 -0.377101 0.8933347 -0.2444342 0.4920637 0.8705366 -0.006276547 0.2711056 0.9283292 -0.2543749 0 0.957028 0.2899956 -1.32797e-7 0.9570285 0.289994 2.51609e-6 0.957071 0.289854 -0.3701461 0.9041866 0.2131628 -0.370989 0.9079081 0.1951158 0.3709878 0.9079068 0.1951242 0.3701498 0.9041859 0.2131598 0.4783961 0.8781301 -0.00495702 0.182226 0.9492172 -0.2564773 -0.3626307 0.9170753 0.1657466 -0.3646616 0.9208739 0.1378886 0.3552243 0.9241513 0.1405711 0 0.9570894 0.2897927 0 0.9570358 0.2899699 0 0.9570306 0.289987 0.1243777 0.948791 0.290389 0.467624 0.8808143 0.07412201 0.4466397 0.8769361 0.1774721 0.4699875 0.8826653 -0.003728449 0.468843 0.8832581 -0.00644499 -0.4641675 0.8857397 -0.003703594 -0.09640008 0.9630702 -0.2514019 0.5679772 0.786381 -0.2429136 0.5846991 0.8095388 -0.05266922 -0.5678614 0.7864868 -0.2428413 -0.122439 0.955903 0.2669424 -0.1256141 0.9575309 0.25953 0.1218513 0.957863 0.2600979 -0.3617106 0.9232311 0.1296526 -0.3618019 0.9270421 0.09845 0.3732627 0.9134052 0.1623761 0.3515717 0.9306056 0.1018365 0.4142922 0.7872109 0.4567943 0.4273808 0.8079618 0.4056396 0.4332228 0.8174077 0.3796877 0.4331378 0.8174718 0.3796465 0.3864597 0.7814561 0.4898727 0.3865047 0.7814356 0.48987 0.4509817 0.8607241 0.2361558 0.4628275 0.8864411 -0.003611207 0.128542 0.9589367 -0.2528189 0.07057166 0.96272 -0.261132 -0.3864722 0.7818611 0.4892162 -0.2951414 0.7279559 0.6188471 -0.2506312 0.7327198 0.6326971 0.3865016 0.7818359 0.4892334 0.2799797 0.7455503 0.604786 -0.3636541 0.9258394 0.1028456 -0.355663 0.9318494 0.0718382 0.3731845 0.9192329 0.1254765 0.3510239 0.9334754 0.0735253 0 0.9570288 0.2899931 0 0.9570299 0.2899895 0.1274513 0.955536 0.265908 0.3864437 0.7818744 0.4892175 -0.3627899 0.9277533 0.08750599 -0.3536112 0.9337435 0.05551713 0.3688327 0.9240144 0.1007961 0.3489001 0.9354046 0.05733197 -0.3575177 0.9317463 0.0634821 -0.3588683 0.9305874 0.07225537 0.3680396 0.9258915 0.08527445 0.3610758 0.9298434 0.07082116 -0.4046915 0.8495135 0.338455 -0.2092491 0.7849369 0.5831715 0.2092493 0.7849341 0.5831751 0.4103667 0.8501552 0.3299022 0.4064347 0.8417215 0.3554095 -0.1231051 0.9601842 0.2507821 -0.1239075 0.9647666 0.2321045 0.1181297 0.9651516 0.2335117 0.2829684 0.7282742 0.6241359 0.2653565 0.716369 0.6452918 -0.3528849 0.9337854 0.05930602 -0.353977 0.9327996 0.06771481 0.3553758 0.9324851 0.06465017 0.3561556 0.9320675 0.06635725 0 0.9591709 0.2828273 0 0.9591723 0.2828229 0.1298909 0.9597853 0.2488787 -0.4316138 0.9020574 -0.001471698 2.18255e-6 0.9652258 -0.2614178 -0.1285259 0.9570389 -0.2599188 0.4316128 0.9020578 -0.001471579 -2.18254e-6 0.9652258 -0.2614178 -0.1231144 0.9653969 0.2298954 -0.1225071 0.9703699 0.2082647 0.1160442 0.9707565 0.2101562 -0.4343652 0.8960719 0.09155446 -0.372406 0.895339 0.2442989 -0.3483638 0.935756 0.05480319 0.4343749 0.8960661 0.09156513 0.3508011 0.9345002 0.06039911 0.3999936 0.8986337 0.1801742 0 0.9632445 0.2686263 0 0.963242 0.2686352 0.130667 0.9650025 0.2273681 -0.2905432 0.7116801 0.6396063 -0.2678478 0.703608 0.6581742 -0.4300599 0.872773 0.2309026 -0.4474087 0.8823206 0.1460685 -0.4432958 0.8777908 0.1815826 -0.4383304 0.874897 0.2059652 -0.4431835 0.8900647 0.1066455 -0.4189119 0.8723963 0.2518686 -0.4108195 0.8751059 0.2557679 0.4431817 0.8900697 0.1066109 0.4189227 0.8723917 0.2518661 0.4300552 0.8727759 0.2309001 0.4408285 0.875428 0.1982322 0.4452174 0.8801447 0.1647019 0.4468427 0.8838613 0.1382786 -0.4036108 0.8874874 0.2224065 -0.2631504 0.8629093 0.4314389 0.4200577 0.8436172 0.3344576 -0.1938379 0.8451962 0.4980667 -0.3952533 0.8994963 0.186229 0.04735386 0.7458708 0.6644052 0.3951869 0.8995206 0.1862528 0.2722579 0.7039963 0.655946 0.2829852 0.7144434 0.6399141 -0.3182025 0.8945571 0.3138707 -0.386054 0.9105802 0.1476693 0.3953912 0.8994344 0.1862354 -0.3479948 0.9023101 0.2544328 -0.3433762 0.9329577 0.1080873 0.368605 0.9020642 0.224523 0.3327987 0.9407634 0.06487923 -0.125099 0.9687191 0.2143211 -0.1190294 0.9741082 0.1922116 0.1160714 0.9742738 0.1931788 -0.3813829 0.9107039 0.158637 0.3121165 0.8982604 0.309373 0.3306613 0.9038456 0.2715257 0.3616324 0.9254865 0.1126807 -0.391351 0.9009133 0.1876156 -0.3361989 0.9126197 0.2325848 -0.3396722 0.9293891 0.1444253 0.3462463 0.9108214 0.2247623 0.3362387 0.9352379 0.1107865 0 0.9659665 0.2586673 -0.001981139 0.9657914 0.2593126 0.001436352 0.9779295 0.2089301 6.23025e-4 0.9739862 0.2266069 1.73372e-4 0.970272 0.2420175 3.82147e-5 0.9675533 0.2526676 0.1285437 0.9685553 0.2130193 -0.1250282 0.9706763 0.2053185 -0.1180428 0.9761354 0.1822788 0.1149827 0.9762948 0.1833778 -0.3341885 0.9188681 0.2097607 -0.3371051 0.9267199 0.1659833 0.3367846 0.9182505 0.2083082 0.3370095 0.9302842 0.1448996 -0.3208732 0.9087259 0.2669414 -0.3541655 0.9239673 0.1444 0.3322139 0.9152865 0.2277818 0.3457612 0.9284523 0.1357414 -0.3347887 0.9227871 0.1907366 -0.3357763 0.9246016 0.1799065 0.3910388 0.9013271 0.1862744 0.3352764 0.9225539 0.1910084 0.3364904 0.9269217 0.1661032 -0.3409531 0.9253913 0.1655353 -0.3337004 0.921101 0.2005417 0.3371891 0.9270248 0.1640994 0.3356521 0.9246568 0.179854 -0.3296048 0.9163577 0.2272652 0.3346711 0.9207332 0.2006133 -0.001605153 0.9674127 0.2531998 0.1285843 0.9705066 0.2039191 -0.1240477 0.9730026 0.1946232 -0.1228456 0.9752358 0.1839138 0.1195846 0.9753468 0.1854677 0.3717908 0.9143053 0.1606788 0.1989438 0.8859113 0.4190255 -0.001000463 0.9701936 0.2423293 0.1272105 0.9728491 0.1933448 -0.1220108 0.9756824 0.1820917 -0.1211501 0.9776356 0.1719051 0.117964 0.97777 0.1733503 -0.2874168 0.6973341 0.6565948 -0.2764816 0.6905108 0.6683957 0.2791805 0.6934534 0.6642144 0.2829837 0.6994252 0.6562961 -3.90553e-4 0.9740037 0.2265315 0.1250846 0.9755102 0.1809251 -0.1217712 0.9737847 0.1921334 -0.1223527 0.9769967 0.1746633 0.1283416 0.9736658 0.1884236 0 0.9780136 0.208541 0.1179414 0.9773115 0.1759325 -0.1165957 0.9753511 0.1873388 -0.1176899 0.9775275 0.1748976 0.1203454 0.9751257 0.1861367 -0.1889986 0.9081841 0.373472 -0.1084313 0.870641 0.4798197 -0.02132594 0.8414514 0.5399119 0.04196465 0.8523615 0.5212667 0.1732248 0.9527125 0.2496638 0.02437829 0.8431052 0.5371959 0.02433151 0.8430786 0.5372398 0.130738 0.8637227 0.4867144 -0.4981843 0.8371348 -0.2258713 -0.3572728 0.9008908 -0.246479 -0.3771076 0.8936279 -0.2433502 0.4982517 0.8370981 -0.2258587 0.3572518 0.9008995 -0.2464781 0.3771064 0.8936286 -0.2433488 -0.1143248 0.9764677 0.1828678 -0.115382 0.9778738 0.1744989 0.1161382 0.9763165 0.1825324 0.1154412 0.9777328 0.1752484 -0.1137437 0.9770807 0.1799328 -0.1143416 0.9780066 0.1744402 0.1143558 0.977025 0.1798474 0.1143442 0.9779749 0.1746158 0.4073306 0.6815181 0.6079596 0.4186998 0.6945171 0.5850953 0.39083 0.6529486 0.6487758 0.3910564 0.6542969 0.6472795 -0.406858 0.6808427 0.609032 -0.4186989 0.6945117 0.5851023 -0.3909929 0.6543139 0.6473005 -0.3910676 0.6512942 0.6502938 -0.3907667 0.6529669 0.6487956 0 0.9814563 0.1916862 0 0.9814586 0.1916749 -0.1134381 0.9774883 0.1778998 -0.1140303 0.9780866 0.1741945 0.1138629 0.9774149 0.1780321 0.1140024 0.9780392 0.174479 -0.1653923 0.9672478 0.1925547 -0.1744449 0.9529175 0.2480268 -0.02303636 0.899926 0.4354338 0.05164015 0.9140974 0.402193 0.1980454 0.979921 0.02308779 0.198991 0.8858243 0.4191873 -0.1134322 0.977961 0.1752866 -0.113815 0.9781293 0.1740958 0.1136797 0.9779269 0.1753168 0.1137954 0.9781284 0.1741132 0.1059589 0.8486187 0.5182848 -0.1145058 0.9784334 0.1719208 -0.1136856 0.9781581 0.1740182 0.1140807 0.9784958 0.1718477 0.1136717 0.9781452 0.1741001 -0.2538655 0.9657818 0.05308538 -0.11855 0.9785309 0.1685925 -0.113876 0.9780953 0.1742464 0.1158413 0.9790901 0.167223 0.1139324 0.9781242 0.1740475 0.2840564 0.6862322 0.6696248 0.2844392 0.687465 0.6681963 0 0.983648 0.1801019 0 0.9836498 0.1800923 -0.253825 0.9657934 0.05306816 -0.1004144 0.9524829 0.2875643 -0.1228107 0.9783281 0.1667085 -0.1152402 0.977718 0.1754628 0.1155874 0.9778087 0.1747282 0.1203527 0.9789441 0.164875 0.3717669 0.9143006 0.1607603 -0.2850094 0.6862688 0.6691823 -0.283632 0.683472 0.672621 0.01183605 0.9267777 0.375424 0.02207303 0.9454393 0.3250499 0.1170059 0.9773767 0.1761944 -0.1163474 0.8122019 0.5716568 -0.03899204 0.764383 0.6435824 -0.04650199 0.7721389 0.63375 0.04645746 0.7622836 0.6455739 0.0997222 0.8171249 0.5677698 0 0.9848456 0.1734337 2.19991e-5 0.9856443 0.1688354 -2.17384e-5 0.9848439 0.1734433 0 0.985637 0.168878 0.04488515 0.9657112 0.2557094 0.1029691 0.9800577 0.1699544 0 0.9867254 0.1623978 0 0.9867223 0.1624171 0 0.9881069 0.1537689 0 0.9881003 0.1538114 -0.3856823 0.9226318 0 -1.1715e-6 0.9652249 -0.2614209 0.3799715 0.9249982 1.80892e-4 0 0.9652246 -0.2614219 2.30636e-6 0.9652248 -0.2614215 0.2846617 0.6832183 0.6724438 0.2841309 0.6798507 0.6760715 -0.1049314 0.7724868 0.6263015 -0.05648869 0.7195667 0.692122 -0.2837554 0.6796965 0.6763843 -0.2843799 0.6816222 0.6741805 0 0.9900873 0.1404536 0 0.9900879 0.1404495 0.448911 0.7696081 0.4540731 0.4489074 0.7696192 0.454058 0.424151 0.7068683 0.5660682 0.4958192 0.8067189 0.3215091 0.05989331 0.7215616 0.6897549 0.09386914 0.7774523 0.6218976 -0.4458364 0.764334 0.465858 -0.4777035 0.8176578 0.3213025 0 0.9920819 0.1255933 9.86008e-5 0.993085 0.1173979 -3.95093e-5 0.992086 0.1255605 -0.02820748 0.9908208 0.1322064 0.002616584 0.9840617 0.177808 -0.009568154 0.9923582 0.1230196 0 0.9930695 0.1175283 0 0.996766 0.08035981 0 0.9968503 0.07930696 0 0.9820044 0.1888588 0 0.982004 0.1888605 0 0.9451766 0.3265598 -6.79283e-4 0.8888638 0.4581711 2.28105e-4 0.9447844 0.3276927 -0.2837452 0.6768476 0.6792393 0.2837468 0.6819192 0.6741469 0.2837464 0.6768454 0.6792411 0.08014243 0.6893072 0.7200229 0.09524875 0.7410606 0.6646479 -0.09796154 0.7373923 0.6683235 -0.08398216 0.6956395 0.7134653 -0.3572412 0.9019098 -0.2427706 -0.1285235 0.9569308 -0.2603177 -0.3597579 0.9010759 -0.2421501 -0.3572418 0.9019094 -0.2427709 0.1285316 0.9572474 -0.2591472 0.1214799 0.9577676 -0.2606222 0.3646627 0.8989728 -0.2426295 0.3572185 0.9019178 -0.2427741 0.3572728 0.9018964 -0.2427736 4.36623e-5 0.9020589 0.4316129 1.23623e-4 0.9017782 0.4321992 4.36301e-5 0.8903989 0.4551813 -4.84319e-4 0.7839642 0.620806 -1.175e-4 0.8334236 0.5526349 0.001028239 0.8634928 0.5043603 -0.001213192 0.7199705 0.6940037 -9.1728e-4 0.7446683 0.6674341 0.09088194 0.6888445 0.7191897 0.09477162 0.715577 0.6920751 -0.0957328 0.7142479 0.6933147 -0.09286123 0.6995936 0.7084813 5.49853e-4 0.8279199 0.5608463 0.5008814 0.8415286 -0.2023552 0.5001802 0.8420619 -0.2018701 0.5180632 0.8540359 -0.0472579 0.5161625 0.8548662 -0.05272644 -0.5180095 0.8540614 -0.04738599 -0.5030236 0.8419123 -0.1953229 -0.5008473 0.8415361 -0.2024084 -0.5161451 0.8548771 -0.05272132 1.92501e-4 0.7849942 0.6195031 -1.14903e-6 0.9652246 -0.2614223 -0.1214787 0.9581036 -0.2593848 -0.1854767 0.792985 0.5803216 -0.09576308 0.7047891 0.7029238 0.09574109 0.6991209 0.7085645 0.09161454 0.875358 0.4747159 0.4938236 0.8434712 0.2114111 0.4939 0.8434593 0.2112804 0.4938724 0.8434759 0.2112785 0.5067332 0.7401576 0.4420274 0.06336736 0.7077774 0.7035878 0 0.7348896 0.6781868 -0.5089434 0.7324963 0.4521348 -0.5089453 0.7325139 0.4521042 -0.4923119 0.842024 0.2205098 -0.4923176 0.8420101 0.2205507 -0.4921761 0.8420825 0.2205897 0 0.707825 0.7063878 7.53227e-6 0.7079869 0.7062256 -2.04749e-7 0.7077987 0.7064142 0 0.7078241 0.7063888 0.18838 0.6955736 0.6933184 -0.2553661 0.6827176 0.6846056 -0.2551968 0.6825904 0.6847955 -0.2552584 0.6826499 0.6847134 -0.2553755 0.6826211 0.6846984 -0.1873079 0.5909765 0.7846418 0.1163448 0.5299252 0.8400258 0.2995606 0.6750536 0.6742152 0.1877571 0.6099326 0.7698893 0.3409507 0.9400812 1.80738e-4 0.361088 0.9324223 -0.01429194 0 0.9652259 -0.2614175 -0.3222448 0.9466564 -2.38444e-4 -0.2660169 0.9639649 -0.002619922 -0.2736629 0.9618238 -0.001942157 -0.3552357 0.9347767 0 0.2818595 0.9594542 -0.001729309 0.2736631 0.9618256 7.83665e-5 0.1756936 0.9843746 -0.01177215 0.2270352 0.9738693 -0.005794405 1.32859e-6 0.9652264 -0.2614155 -6.91202e-6 0.9652227 -0.2614293 -0.2509759 0.9677817 -0.0202465 -0.1548314 0.9851954 0.07360261 -2.96301e-6 0.965226 -0.2614172 0.2918743 0.9563124 0.01661401 -0.07071954 0.7064167 0.7042544 -8.19483e-7 0.7078051 0.7064078 0.1166709 0.7036091 0.7009437 -2.2365e-4 0.9652178 -0.2614469 1.84955e-5 0.9652263 -0.2614158 0.2030497 0.9791556 0.005028605 0.1530457 0.9871126 0.04675388 1.01035e-5 0.965229 -0.2614058 -5.11803e-5 0.9652228 -0.2614291 3.93627e-4 0.9652391 -0.2613683 0 0.9652348 -0.2613846 -0.1150271 0.9905413 0.0748111 -2.61904e-5 0.9652217 -0.2614328 -3.33169e-6 0.9652277 -0.2614107 0.1532853 0.9872003 0.04403871 -0.2884756 0.7122412 0.6399174 -0.2547925 0.7123337 0.6539583 0.298825 0.7108999 0.6366515 -0.255375 0.662308 0.7043662 -0.4476879 0.6310833 0.6334899 6.98043e-6 0.9652252 -0.26142 0 0.9652239 -0.2614247 0.0522927 0.993949 0.0965963 -0.2542243 0.5929338 0.7640679 -0.3331816 0.5845636 0.7397807 0 0.9935324 0.1135495 -5.35245e-7 0.9935326 0.1135476 0 0.9652248 -0.2614216 0 0.9652248 -0.2614219 0.1169083 0.6869707 0.7172194 0.304709 0.7001761 0.6456825 0.1065678 0.6823655 0.7232018 -0.2546572 0.6022808 0.7565762 -0.2484353 0.6027651 0.7582573 0.1071127 0.6870648 0.7186577 0.106625 0.6870813 0.7187144 0.116619 0.7059517 0.6985931 -0.2892995 0.8231409 0.4886155 0.3058112 0.7443551 0.5936455 -0.07071429 0.7080168 0.7026463 -0.07826346 0.7760441 0.6258038 0.007888019 0.6545279 -0.7559968 0.2759187 0.8343173 0.4772668 -0.2344493 0.9716649 -0.03001731 -0.2893716 0.8231145 0.4886173 0 0.7078394 0.7063735 -1.51068e-7 0.7078024 0.7064105 -0.2342449 0.9717093 -0.03017145 -0.2538401 0.8903183 0.3780194 -0.2342737 0.971695 -0.03040808 -0.2881804 0.8238466 0.488087 -0.2901029 0.7969002 0.5298967 -0.2893061 0.8231021 0.4886768 -0.4810928 0.7117814 0.5117784 -0.2329345 0.7003328 0.6747412 -0.2833907 0.8856792 0.36778 -0.2833821 0.8855298 0.3681462 0.1581264 0.9855207 0.06119668 -0.09292852 0.7070962 0.7009845 0.359411 0.807155 0.4683211 0.3048933 0.7586268 0.5757825 -0.09126418 0.7007452 0.7075501 -0.0911656 0.7006075 0.7076991 -0.2852057 0.6951889 0.6598258 -0.2901789 0.7734181 0.5635786 -0.3569965 0.7536246 0.5519089 -0.2902666 0.7733934 0.5635672 0.1084201 0.794076 0.5980707 0.102353 0.794727 0.5982749 0.108075 0.7987646 0.5918571 -0.2899546 0.7905526 0.5394008 -0.2532232 0.7966216 0.5488827 -0.09244531 0.809925 0.5792024 -0.09260421 0.8099034 0.5792071 -0.1464707 0.9878965 0.05105781 -0.1233386 0.9895859 0.07421141 1.23798e-4 0.7941575 0.6077122 0 0.7972829 0.6036059 -0.1140837 0.7954346 0.595205 0.3594122 0.8071416 0.4683434 -0.4912056 0.7419874 0.4562586 -4.00643e-7 0.9935328 0.1135457 0.1274012 0.9898536 0.06292015 -0.3088217 0.9255024 0.2192593 -0.4509918 0.8587737 0.243134 -0.4025295 0.8819775 0.2451241 -0.3956373 0.8842704 0.2480669 0.3914595 0.895684 0.2109737 0.3356439 0.8815842 0.3318925 -0.3570848 0.9069218 -0.2235698 0.4509961 0.8673512 -0.2104865 0.3530249 0.845585 -0.400449 0.3611132 0.9056406 -0.2222891 0.2537152 0.7588009 0.5998747 -0.4530837 0.8074228 -0.3778672 -0.4393955 0.8949735 -0.07716333 -0.4408596 0.8743408 -0.2029061 0.3555521 0.9323398 -0.06576669 -0.4369261 0.8976868 -0.05704557 1.28315e-7 0.9935325 0.1135476 0.3914381 0.895693 0.2109748 -0.3414174 0.7782026 -0.5271005 -0.3950885 0.8323931 -0.3886218 0.3530339 0.8455821 -0.4004474 -0.4673905 0.856014 0.2208762 0.3249624 0.9222383 0.2094661 0.3678562 0.9242554 0.1021456 -0.304856 0.9190949 0.2496545 -0.2894177 0.921728 0.2581765 0.2147837 0.7744621 0.5950434 0.2668984 0.8328166 0.4849556 0.3555201 0.932352 -0.06576657 -0.4676303 0.8559349 0.2206746 -0.4476206 0.892282 -0.05889487 0.3989731 0.912246 -0.0928868 0.3863019 0.7578183 -0.5258159 -0.4381466 0.8956161 -0.07680845 -0.4382635 0.8954612 -0.07793962 -0.3953324 0.8544207 -0.3371611 -0.4375522 0.8972385 -0.05925559 -0.4370226 0.8974989 -0.05921924 -0.2635775 0.9095028 0.3214526 -0.3060499 0.9507057 -0.04992181 -0.4105926 0.9069928 -0.09369015 -0.3034642 0.9515964 -0.04872268 0.1026493 0.7984177 0.5932895 0.1152982 0.9289901 0.3516871 0.1175605 0.9327763 0.3407461 -0.3572308 0.9022554 -0.2414985 -0.2991475 0.7917883 -0.5325244 0.3407204 0.7746038 -0.5328215 0.1258315 0.9902713 0.05940717 0.2669548 0.8328059 0.4849427 0.358516 0.9244945 -0.1295238 -0.2613078 0.9103125 0.3210131 -0.2242153 0.9228236 0.3132477 -0.3040044 0.9525102 -0.01748579 -0.3138434 0.9446403 -0.09569203 -0.3084591 0.9460594 -0.09912055 0.2988557 0.9198728 -0.2540069 0.298603 0.9213026 -0.2490742 -0.08882731 0.9175193 0.3876443 -0.08890253 0.9176614 0.3872904 -0.1602606 0.9532954 0.2560167 -0.08884859 0.9175301 0.3876137 1.23472e-4 0.7969083 0.6041003 -1.00004e-4 0.9165918 0.3998243 1.48102e-4 0.9338794 0.3575882 1.47865e-4 0.9338607 0.3576371 0.1101291 0.9332087 0.3420428 1.49239e-4 0.9338235 0.3577343 0.001131355 0.9165996 0.3998049 0 0.9935325 0.1135479 0.09851557 0.9931305 0.06313896 0.001120984 0.9165502 0.3999183 -0.1954132 0.9807209 3.03559e-4 -0.1152631 0.991663 0.05761164 -0.3599262 0.9013378 -0.240922 0.3619002 0.9006381 -0.2405813 -0.121514 0.9570662 -0.2631705 0.1214072 0.9570167 -0.2633998 0.1215364 0.9578225 -0.2603939 -0.3040637 0.9524915 -0.01747739 -0.1212503 0.9579009 -0.2602391 -0.1298486 0.8741385 -0.4679972 -0.3041372 0.9524688 -0.01743221 0.1223729 0.9633736 -0.2386133 0.1226876 0.9631893 -0.239195 0.1201609 0.9635716 -0.2389378 -0.3080083 0.9462007 -0.09917283 -0.3084406 0.9460656 -0.099119 0.122051 0.9838848 -0.1306687 0.1217318 0.9839393 -0.1305556 0.1225863 0.9576764 -0.2604392 0.122537 0.9765085 -0.1772456 0.2143868 0.9757254 0.04470217 0.1075114 0.9856399 -0.1302132 0.1374728 0.9840178 0.113182 0.1101254 0.9331972 0.3420754 -0.1030576 0.9598485 -0.2609021 -0.1026931 0.9862588 -0.1294133 -0.1492394 0.9862108 -0.07152575 1.71461e-6 0.9935324 0.1135495 -6.85817e-7 0.9935332 0.1135428 -0.09592807 0.9936582 0.05866301 -0.1029673 0.9840093 0.145339 -0.1029505 0.984007 0.1453667 -0.1029828 0.9840179 0.1452699 0.1068093 0.9926201 0.05742096 0.106816 0.9926183 0.05744153 -7.5303e-4 0.987405 0.1582112 0 0.9850968 -0.1720013 -8.37156e-4 0.9923703 -0.1232909 3.03482e-4 0.997602 0.06921112 9.23855e-4 0.9976097 0.06909501 5.01912e-4 0.9873692 0.1584355 5.02006e-4 0.9873816 0.1583582 9.23905e-4 0.9976092 0.06910222 0.09523087 0.9937859 0.05762475 -0.1954111 0.9807214 3.03585e-4 -0.09313917 0.9929597 0.07318514 0.1620211 0.9867873 7.89062e-5 0.0895667 0.9946555 0.05136364 0.07957243 0.9943057 0.07088285 -0.1325352 0.9911782 -5.63211e-4 -0.07446539 0.9972162 -0.003877222 -0.09226745 0.995732 -0.002143561 0.06938815 0.9975801 -0.004401504 0.1131685 0.9935747 -0.001524031 0.09226769 0.9957343 5.95502e-5 -0.02219331 0.9996474 -0.01458036 0.02653044 0.9996119 -0.008499324 -0.06537717 0.9953938 0.07012134 -0.07609432 0.9959201 0.04850637 0 0.993533 0.1135442 1.26574e-6 0.993533 0.1135441 0.06698411 0.9961916 0.05581629 0.05103635 0.9967614 0.06214565 1.12292e-6 0.9935328 0.1135463 0 0.9935322 0.1135505 -0.04141491 0.9979441 0.04891294 -0.03925621 0.9972107 0.06348091 0.04092729 0.9976863 0.05428594 0.03166407 0.9976757 0.06033772 1.44123e-6 0.9935335 0.1135399 0.01530021 0.9984374 0.0537467 0.01245021 0.9982845 0.05721068 -0.01021218 0.9983727 0.05610531 -0.01240891 0.9985116 0.05311095 -0.01189428 0.9983391 0.05637121 -0.02011591 0.9997977 6.00069e-5 + + + + + + + + + + + + + + +

0 0 1 0 2 0 1 1 3 1 2 1 3 2 4 2 2 2 4 3 5 3 2 3 5 4 0 4 2 4 0 5 5 5 6 5 7 6 0 6 6 6 8 7 7 7 6 7 9 8 8 8 6 8 5 9 9 9 6 9 10 10 9 10 5 10 4 11 10 11 5 11 3 12 11 12 4 12 11 13 10 13 4 13 12 14 0 14 7 14 13 15 12 15 7 15 8 16 13 16 7 16 10 17 8 17 9 17 14 18 8 18 10 18 11 19 14 19 10 19 14 20 13 20 8 20 15 21 0 21 12 21 16 22 15 22 12 22 13 23 16 23 12 23 14 24 17 24 13 24 17 25 16 25 13 25 3 26 18 26 11 26 18 27 14 27 11 27 18 28 17 28 14 28 17 29 19 29 16 29 19 30 20 30 16 30 20 31 21 31 16 31 21 32 15 32 16 32 21 33 0 33 15 33 18 34 22 34 17 34 22 35 19 35 17 35 3 36 22 36 18 36 19 37 23 37 20 37 23 38 24 38 20 38 24 39 21 39 20 39 25 40 1 40 0 40 21 41 25 41 0 41 1 42 26 42 3 42 26 43 27 43 3 43 27 44 22 44 3 44 24 45 25 45 21 45 27 46 19 46 22 46 28 47 29 47 30 47 31 48 28 48 30 48 32 49 31 49 30 49 33 50 32 50 30 50 29 51 34 51 30 51 34 52 35 52 30 52 35 53 33 53 30 53 36 54 25 54 24 54 23 55 36 55 24 55 37 56 29 56 28 56 38 57 37 57 28 57 31 58 38 58 28 58 39 59 32 59 33 59 35 60 39 60 33 60 40 61 38 61 31 61 32 62 40 62 31 62 41 63 32 63 39 63 42 64 41 64 39 64 35 65 42 65 39 65 41 66 40 66 32 66 43 67 44 67 41 67 45 68 43 68 41 68 42 69 45 69 41 69 46 70 40 70 41 70 44 71 46 71 41 71 47 72 29 72 37 72 48 73 49 73 37 73 49 74 50 74 37 74 50 75 47 75 37 75 38 76 48 76 37 76 47 77 51 77 29 77 51 78 52 78 29 78 52 79 53 79 29 79 53 80 54 80 29 80 54 81 34 81 29 81 43 82 55 82 44 82 55 83 46 83 44 83 35 84 56 84 42 84 56 85 45 85 42 85 57 86 58 86 48 86 58 87 49 87 48 87 38 88 59 88 48 88 59 89 60 89 48 89 60 90 57 90 48 90 53 91 61 91 54 91 61 92 62 92 54 92 62 93 34 93 54 93 63 94 64 94 57 94 65 95 63 95 57 95 64 96 66 96 57 96 66 97 58 97 57 97 67 98 65 98 57 98 60 99 67 99 57 99 53 100 68 100 61 100 68 101 69 101 61 101 69 102 70 102 61 102 70 103 71 103 61 103 71 104 62 104 61 104 72 105 38 105 40 105 73 106 74 106 40 106 46 107 73 107 40 107 74 108 75 108 40 108 75 109 76 109 40 109 76 110 72 110 40 110 77 111 78 111 35 111 34 112 79 112 35 112 79 113 80 113 35 113 80 114 77 114 35 114 78 115 81 115 35 115 81 116 56 116 35 116 82 117 23 117 19 117 83 118 82 118 19 118 27 119 83 119 19 119 62 120 79 120 34 120 84 121 73 121 46 121 85 122 84 122 46 122 86 123 85 123 46 123 55 124 86 124 46 124 72 125 59 125 38 125 76 126 59 126 72 126 75 127 87 127 76 127 87 128 59 128 76 128 62 129 80 129 79 129 62 130 77 130 80 130 87 131 88 131 59 131 88 132 60 132 59 132 89 133 77 133 62 133 71 134 90 134 62 134 90 135 91 135 62 135 91 136 89 136 62 136 88 137 67 137 60 137 70 138 92 138 71 138 92 139 90 139 71 139 93 140 67 140 88 140 87 141 93 141 88 141 92 142 91 142 90 142 26 143 83 143 27 143 56 144 43 144 45 144 82 145 94 145 23 145 94 146 36 146 23 146 95 147 55 147 43 147 96 148 95 148 43 148 56 149 96 149 43 149 95 150 86 150 55 150 77 151 97 151 78 151 97 152 98 152 78 152 98 153 81 153 78 153 96 154 99 154 95 154 99 155 86 155 95 155 100 156 99 156 96 156 56 157 100 157 96 157 100 158 101 158 99 158 102 159 86 159 99 159 101 160 102 160 99 160 103 161 104 161 56 161 104 162 100 162 56 162 105 163 103 163 56 163 81 164 105 164 56 164 106 165 107 165 89 165 107 166 108 166 89 166 108 167 77 167 89 167 91 168 109 168 89 168 109 169 106 169 89 169 110 170 111 170 87 170 75 171 110 171 87 171 111 172 93 172 87 172 108 173 97 173 77 173 107 174 97 174 108 174 74 175 110 175 75 175 112 176 25 176 36 176 94 177 112 177 36 177 113 178 67 178 93 178 111 179 113 179 93 179 92 180 109 180 91 180 114 181 115 181 86 181 115 182 85 182 86 182 116 183 114 183 86 183 102 184 116 184 86 184 117 185 118 185 97 185 119 186 117 186 97 186 120 187 119 187 97 187 107 188 120 188 97 188 118 189 121 189 97 189 121 190 98 190 97 190 106 191 120 191 107 191 106 192 119 192 120 192 106 193 122 193 119 193 122 194 123 194 119 194 123 195 117 195 119 195 109 196 122 196 106 196 124 197 125 197 111 197 110 198 124 198 111 198 125 199 113 199 111 199 73 200 126 200 74 200 127 201 128 201 74 201 126 202 127 202 74 202 128 203 110 203 74 203 123 204 129 204 117 204 130 205 118 205 117 205 129 206 130 206 117 206 130 207 121 207 118 207 128 208 124 208 110 208 131 209 105 209 81 209 132 210 131 210 81 210 98 211 132 211 81 211 84 212 126 212 73 212 130 213 133 213 121 213 133 214 98 214 121 214 125 215 134 215 113 215 134 216 67 216 113 216 135 217 136 217 109 217 92 218 135 218 109 218 136 219 122 219 109 219 85 220 126 220 84 220 51 221 94 221 82 221 53 222 51 222 82 222 68 223 53 223 82 223 83 224 68 224 82 224 122 225 129 225 123 225 127 226 124 226 128 226 136 227 129 227 122 227 127 228 125 228 124 228 127 229 134 229 125 229 135 230 129 230 136 230 115 231 126 231 85 231 137 232 132 232 98 232 138 233 137 233 98 233 133 234 138 234 98 234 130 235 138 235 133 235 51 236 47 236 94 236 47 237 50 237 94 237 50 238 49 238 94 238 49 239 58 239 94 239 58 240 112 240 94 240 130 241 139 241 138 241 139 242 137 242 138 242 114 243 140 243 115 243 140 244 126 244 115 244 100 245 141 245 101 245 142 246 102 246 101 246 141 247 142 247 101 247 143 248 141 248 100 248 144 249 143 249 100 249 104 250 144 250 100 250 26 251 68 251 83 251 103 252 144 252 104 252 105 253 144 253 103 253 145 254 144 254 105 254 131 255 145 255 105 255 142 256 116 256 102 256 142 257 146 257 116 257 146 258 147 258 116 258 147 259 148 259 116 259 148 260 114 260 116 260 146 261 149 261 147 261 149 262 148 262 147 262 132 263 145 263 131 263 150 264 145 264 132 264 137 265 150 265 132 265 151 266 143 266 144 266 152 267 151 267 144 267 145 268 152 268 144 268 153 269 154 269 139 269 130 270 153 270 139 270 154 271 155 271 139 271 155 272 156 272 139 272 156 273 137 273 139 273 148 274 140 274 114 274 157 275 158 275 143 275 159 276 141 276 143 276 158 277 159 277 143 277 151 278 157 278 143 278 64 279 25 279 112 279 66 280 64 280 112 280 58 281 66 281 112 281 160 282 152 282 145 282 150 283 160 283 145 283 156 284 150 284 137 284 155 285 150 285 156 285 161 286 160 286 150 286 155 287 161 287 150 287 159 288 142 288 141 288 162 289 158 289 157 289 151 290 162 290 157 290 154 291 163 291 155 291 163 292 161 292 155 292 149 293 140 293 148 293 152 294 164 294 151 294 164 295 162 295 151 295 165 296 166 296 149 296 166 297 140 297 149 297 146 298 165 298 149 298 167 299 163 299 154 299 153 300 167 300 154 300 168 301 146 301 142 301 159 302 168 302 142 302 160 303 164 303 152 303 168 304 165 304 146 304 53 305 52 305 51 305 161 306 164 306 160 306 163 307 164 307 161 307 168 308 166 308 165 308 167 309 164 309 163 309 158 310 168 310 159 310 169 311 158 311 162 311 164 312 170 312 162 312 170 313 169 313 162 313 26 314 69 314 68 314 171 315 1 315 25 315 63 316 172 316 25 316 172 317 173 317 25 317 173 318 174 318 25 318 174 319 175 319 25 319 175 320 176 320 25 320 176 321 177 321 25 321 177 322 171 322 25 322 64 323 63 323 25 323 1 324 178 324 26 324 179 325 180 325 26 325 180 326 181 326 26 326 181 327 182 327 26 327 182 328 183 328 26 328 183 329 184 329 26 329 184 330 69 330 26 330 178 331 185 331 26 331 185 332 186 332 26 332 186 333 179 333 26 333 184 334 70 334 69 334 187 335 166 335 168 335 188 336 187 336 168 336 158 337 188 337 168 337 167 338 189 338 164 338 189 339 170 339 164 339 190 340 191 340 158 340 169 341 190 341 158 341 191 342 188 342 158 342 192 343 193 343 169 343 194 344 192 344 169 344 195 345 190 345 169 345 193 346 195 346 169 346 170 347 196 347 169 347 196 348 194 348 169 348 197 349 192 349 194 349 196 350 198 350 194 350 198 351 197 351 194 351 190 352 199 352 191 352 199 353 188 353 191 353 200 354 192 354 197 354 198 355 201 355 197 355 201 356 200 356 197 356 129 357 202 357 130 357 203 358 153 358 130 358 202 359 203 359 130 359 195 360 204 360 190 360 204 361 199 361 190 361 205 362 127 362 126 362 206 363 205 363 126 363 140 364 206 364 126 364 199 365 187 365 188 365 189 366 207 366 170 366 207 367 196 367 170 367 172 368 63 368 65 368 67 369 173 369 65 369 173 370 172 370 65 370 184 371 183 371 70 371 183 372 92 372 70 372 193 373 208 373 195 373 208 374 204 374 195 374 209 375 192 375 200 375 201 376 210 376 200 376 210 377 209 377 200 377 135 378 211 378 129 378 211 379 202 379 129 379 205 380 134 380 127 380 192 381 212 381 193 381 212 382 208 382 193 382 213 383 192 383 209 383 214 384 213 384 209 384 210 385 214 385 209 385 207 386 215 386 196 386 215 387 198 387 196 387 204 388 216 388 199 388 216 389 187 389 199 389 213 390 217 390 192 390 217 391 218 391 192 391 218 392 212 392 192 392 219 393 220 393 214 393 221 394 213 394 214 394 220 395 221 395 214 395 210 396 222 396 214 396 222 397 219 397 214 397 221 398 217 398 213 398 220 399 217 399 221 399 223 400 220 400 219 400 222 401 224 401 219 401 224 402 223 402 219 402 176 403 175 403 67 403 175 404 174 404 67 404 174 405 173 405 67 405 134 406 176 406 67 406 183 407 182 407 92 407 182 408 181 408 92 408 181 409 135 409 92 409 215 410 225 410 198 410 225 411 201 411 198 411 208 412 226 412 204 412 226 413 216 413 204 413 216 414 227 414 187 414 227 415 166 415 187 415 167 416 207 416 189 416 223 417 228 417 220 417 228 418 229 418 220 418 229 419 217 419 220 419 230 420 228 420 223 420 231 421 230 421 223 421 224 422 232 422 223 422 232 423 231 423 223 423 233 424 234 424 228 424 230 425 233 425 228 425 234 426 235 426 228 426 235 427 229 427 228 427 236 428 233 428 230 428 231 429 236 429 230 429 233 430 237 430 234 430 237 431 235 431 234 431 236 432 238 432 233 432 238 433 237 433 233 433 239 434 235 434 237 434 238 435 239 435 237 435 240 436 238 436 236 436 231 437 241 437 236 437 241 438 242 438 236 438 242 439 240 439 236 439 232 440 241 440 231 440 240 441 243 441 238 441 243 442 244 442 238 442 244 443 245 443 238 443 245 444 239 444 238 444 242 445 246 445 240 445 246 446 243 446 240 446 247 447 167 447 153 447 203 448 247 448 153 448 166 449 248 449 140 449 248 450 206 450 140 450 212 451 249 451 208 451 249 452 226 452 208 452 243 453 250 453 244 453 250 454 251 454 244 454 252 455 245 455 244 455 251 456 252 456 244 456 246 457 253 457 243 457 253 458 250 458 243 458 247 459 215 459 207 459 167 460 247 460 207 460 225 461 254 461 201 461 254 462 210 462 201 462 226 463 227 463 216 463 250 464 255 464 251 464 256 465 252 465 251 465 255 466 256 466 251 466 257 467 255 467 250 467 253 468 258 468 250 468 258 469 257 469 250 469 257 470 259 470 255 470 260 471 256 471 255 471 259 472 260 472 255 472 261 473 262 473 257 473 262 474 259 474 257 474 258 475 263 475 257 475 263 476 261 476 257 476 239 477 264 477 235 477 264 478 229 478 235 478 265 479 260 479 259 479 262 480 265 480 259 480 266 481 262 481 261 481 263 482 267 482 261 482 267 483 266 483 261 483 266 484 268 484 262 484 269 485 265 485 262 485 268 486 269 486 262 486 270 487 268 487 266 487 267 488 271 488 266 488 271 489 270 489 266 489 218 490 272 490 212 490 272 491 249 491 212 491 254 492 273 492 210 492 273 493 222 493 210 493 274 494 264 494 239 494 275 495 274 495 239 495 276 496 275 496 239 496 277 497 276 497 239 497 245 498 277 498 239 498 232 499 278 499 241 499 278 500 279 500 241 500 279 501 280 501 241 501 280 502 242 502 241 502 247 503 225 503 215 503 274 504 229 504 264 504 252 505 277 505 245 505 280 506 281 506 242 506 281 507 282 507 242 507 282 508 246 508 242 508 224 509 278 509 232 509 270 510 283 510 268 510 284 511 269 511 268 511 283 512 284 512 268 512 285 513 283 513 270 513 271 514 286 514 270 514 286 515 285 515 270 515 249 516 287 516 226 516 287 517 227 517 226 517 288 518 277 518 252 518 256 519 288 519 252 519 282 520 289 520 246 520 289 521 253 521 246 521 290 522 279 522 278 522 224 523 290 523 278 523 291 524 288 524 256 524 260 525 291 525 256 525 289 526 292 526 253 526 292 527 258 527 253 527 293 528 272 528 218 528 217 529 293 529 218 529 294 530 291 530 260 530 265 531 294 531 260 531 292 532 295 532 258 532 295 533 263 533 258 533 296 534 217 534 229 534 274 535 296 535 229 535 297 536 290 536 224 536 222 537 297 537 224 537 298 538 294 538 265 538 269 539 298 539 265 539 295 540 299 540 263 540 299 541 267 541 263 541 285 542 300 542 283 542 301 543 284 543 283 543 300 544 301 544 283 544 302 545 303 545 285 545 304 546 302 546 285 546 303 547 300 547 285 547 305 548 304 548 285 548 306 549 305 549 285 549 286 550 307 550 285 550 307 551 306 551 285 551 227 552 248 552 166 552 308 553 298 553 269 553 284 554 308 554 269 554 299 555 309 555 267 555 309 556 271 556 267 556 310 557 308 557 284 557 301 558 310 558 284 558 309 559 311 559 271 559 311 560 286 560 271 560 205 561 312 561 134 561 312 562 177 562 134 562 177 563 176 563 134 563 313 564 314 564 135 564 314 565 211 565 135 565 179 566 313 566 135 566 180 567 179 567 135 567 181 568 180 568 135 568 315 569 316 569 217 569 296 570 315 570 217 570 316 571 293 571 217 571 273 572 297 572 222 572 300 573 317 573 301 573 318 574 310 574 301 574 317 575 318 575 301 575 311 576 319 576 286 576 319 577 307 577 286 577 303 578 317 578 300 578 320 579 305 579 306 579 321 580 320 580 306 580 307 581 321 581 306 581 303 582 322 582 317 582 322 583 323 583 317 583 323 584 318 584 317 584 324 585 321 585 307 585 319 586 324 586 307 586 302 587 322 587 303 587 325 588 305 588 320 588 326 589 325 589 320 589 321 590 326 590 320 590 272 591 287 591 249 591 327 592 254 592 225 592 247 593 327 593 225 593 302 594 328 594 322 594 328 595 329 595 322 595 329 596 323 596 322 596 330 597 326 597 321 597 324 598 330 598 321 598 304 599 328 599 302 599 331 600 305 600 325 600 332 601 331 601 325 601 326 602 332 602 325 602 275 603 333 603 274 603 333 604 296 604 274 604 304 605 334 605 328 605 334 606 335 606 328 606 335 607 329 607 328 607 336 608 332 608 326 608 330 609 336 609 326 609 305 610 334 610 304 610 337 611 305 611 331 611 338 612 337 612 331 612 332 613 338 613 331 613 294 614 298 614 291 614 339 615 288 615 291 615 298 616 339 616 291 616 282 617 340 617 289 617 340 618 292 618 289 618 340 619 295 619 292 619 308 620 339 620 298 620 309 621 299 621 295 621 340 622 309 622 295 622 339 623 277 623 288 623 281 624 340 624 282 624 310 625 339 625 308 625 305 626 341 626 334 626 341 627 342 627 334 627 342 628 335 628 334 628 343 629 338 629 332 629 336 630 343 630 332 630 337 631 344 631 305 631 344 632 341 632 305 632 345 633 344 633 337 633 346 634 345 634 337 634 338 635 346 635 337 635 318 636 339 636 310 636 340 637 311 637 309 637 347 638 276 638 277 638 339 639 347 639 277 639 280 640 340 640 281 640 344 641 348 641 341 641 348 642 349 642 341 642 349 643 342 643 341 643 350 644 346 644 338 644 343 645 350 645 338 645 323 646 339 646 318 646 340 647 319 647 311 647 347 648 275 648 276 648 351 649 340 649 280 649 279 650 351 650 280 650 352 651 287 651 272 651 293 652 352 652 272 652 347 653 333 653 275 653 290 654 351 654 279 654 347 655 296 655 333 655 297 656 351 656 290 656 323 657 353 657 339 657 353 658 347 658 339 658 351 659 319 659 340 659 354 660 273 660 254 660 327 661 354 661 254 661 345 662 355 662 344 662 355 663 348 663 344 663 356 664 355 664 345 664 357 665 356 665 345 665 346 666 357 666 345 666 329 667 353 667 323 667 351 668 358 668 319 668 358 669 324 669 319 669 355 670 359 670 348 670 359 671 360 671 348 671 360 672 349 672 348 672 361 673 357 673 346 673 350 674 361 674 346 674 356 675 362 675 355 675 362 676 359 676 355 676 363 677 362 677 356 677 364 678 363 678 356 678 357 679 364 679 356 679 335 680 353 680 329 680 358 681 330 681 324 681 316 682 352 682 293 682 365 683 360 683 359 683 366 684 365 684 359 684 362 685 367 685 359 685 367 686 366 686 359 686 368 687 364 687 357 687 361 688 368 688 357 688 347 689 315 689 296 689 273 690 351 690 297 690 369 691 370 691 335 691 370 692 353 692 335 692 342 693 369 693 335 693 358 694 371 694 330 694 371 695 336 695 330 695 349 696 369 696 342 696 371 697 343 697 336 697 347 698 316 698 315 698 363 699 372 699 362 699 372 700 367 700 362 700 373 701 372 701 363 701 374 702 373 702 363 702 364 703 374 703 363 703 360 704 369 704 349 704 371 705 350 705 343 705 347 706 375 706 316 706 375 707 352 707 316 707 354 708 351 708 273 708 353 709 375 709 347 709 365 710 369 710 360 710 371 711 361 711 350 711 372 712 376 712 367 712 376 713 377 713 367 713 377 714 366 714 367 714 368 715 378 715 364 715 379 716 374 716 364 716 378 717 379 717 364 717 314 718 380 718 211 718 380 719 202 719 211 719 381 720 382 720 205 720 382 721 312 721 205 721 383 722 381 722 205 722 206 723 383 723 205 723 370 724 375 724 353 724 373 725 384 725 372 725 384 726 376 726 372 726 385 727 384 727 373 727 386 728 385 728 373 728 374 729 386 729 373 729 385 730 387 730 384 730 387 731 376 731 384 731 388 732 385 732 386 732 389 733 388 733 386 733 390 734 389 734 386 734 374 735 390 735 386 735 366 736 391 736 365 736 391 737 369 737 365 737 371 738 368 738 361 738 377 739 391 739 366 739 392 740 378 740 368 740 371 741 392 741 368 741 388 742 393 742 385 742 393 743 394 743 385 743 394 744 395 744 385 744 395 745 387 745 385 745 396 746 393 746 388 746 397 747 396 747 388 747 398 748 397 748 388 748 389 749 398 749 388 749 399 750 394 750 393 750 400 751 399 751 393 751 401 752 400 752 393 752 396 752 401 752 393 752 402 753 401 753 396 753 397 754 402 754 396 754 403 755 399 755 400 755 404 756 403 756 400 756 401 757 405 757 400 757 405 757 404 757 400 757 402 758 405 758 401 758 387 759 406 759 376 759 406 760 377 760 376 760 379 761 390 761 374 761 406 762 407 762 377 762 407 763 391 763 377 763 392 764 379 764 378 764 408 765 394 765 399 765 403 766 408 766 399 766 397 767 409 767 402 767 409 768 410 768 402 768 410 769 405 769 402 769 411 770 409 770 397 770 398 771 411 771 397 771 412 772 395 772 394 772 413 773 412 773 394 773 408 774 413 774 394 774 411 775 414 775 409 775 414 776 410 776 409 776 415 777 413 777 408 777 403 778 415 778 408 778 416 779 412 779 413 779 417 780 416 780 413 780 415 781 417 781 413 781 203 782 418 782 247 782 419 783 327 783 247 783 418 784 419 784 247 784 420 785 248 785 227 785 287 786 420 786 227 786 421 787 403 787 404 787 422 788 421 788 404 788 405 789 423 789 404 789 423 790 422 790 404 790 410 791 423 791 405 791 424 792 415 792 403 792 421 793 424 793 403 793 398 794 425 794 411 794 425 795 414 795 411 795 387 796 407 796 406 796 392 797 426 797 379 797 426 798 390 798 379 798 414 799 427 799 410 799 427 800 423 800 410 800 395 801 407 801 387 801 426 802 389 802 390 802 186 803 313 803 179 803 428 804 417 804 415 804 424 805 428 805 415 805 429 806 430 806 202 806 380 807 429 807 202 807 431 808 203 808 202 808 430 809 431 809 202 809 432 810 383 810 206 810 248 811 432 811 206 811 433 812 429 812 380 812 314 813 433 813 380 813 434 814 381 814 383 814 432 815 434 815 383 815 435 816 171 816 177 816 312 817 435 817 177 817 185 818 313 818 186 818 412 819 436 819 395 819 437 820 438 820 395 820 438 821 407 821 395 821 436 822 437 822 395 822 439 823 398 823 389 823 440 824 439 824 389 824 426 825 440 825 389 825 425 826 441 826 414 826 441 827 442 827 414 827 442 828 427 828 414 828 443 829 1 829 171 829 444 830 445 830 171 830 446 831 447 831 171 831 447 832 448 832 171 832 448 833 444 833 171 833 445 834 449 834 171 834 449 835 450 835 171 835 450 836 443 836 171 836 435 837 446 837 171 837 1 838 451 838 178 838 451 839 452 839 178 839 452 840 453 840 178 840 453 841 454 841 178 841 454 842 455 842 178 842 455 843 456 843 178 843 456 844 457 844 178 844 457 845 458 845 178 845 458 846 185 846 178 846 458 847 459 847 185 847 459 848 313 848 185 848 312 849 446 849 435 849 460 850 461 850 369 850 461 851 370 851 369 851 391 852 462 852 369 852 462 853 460 853 369 853 358 854 463 854 371 854 463 855 392 855 371 855 416 856 436 856 412 856 439 857 464 857 398 857 465 858 425 858 398 858 464 859 465 859 398 859 466 860 436 860 416 860 467 861 466 861 416 861 417 862 467 862 416 862 465 863 441 863 425 863 468 864 447 864 446 864 312 865 468 865 446 865 457 866 459 866 458 866 382 867 468 867 312 867 459 868 314 868 313 868 375 869 287 869 352 869 469 870 351 870 354 870 327 871 469 871 354 871 407 872 438 872 391 872 438 873 462 873 391 873 470 874 426 874 392 874 463 875 470 875 392 875 431 876 418 876 203 876 471 877 472 877 248 877 420 878 471 878 248 878 472 879 432 879 248 879 473 880 421 880 422 880 474 881 473 881 422 881 423 882 475 882 422 882 475 883 474 883 422 883 427 884 475 884 423 884 382 885 476 885 468 885 476 886 447 886 468 886 477 887 314 887 459 887 457 888 477 888 459 888 478 889 424 889 421 889 473 890 478 890 421 890 479 891 467 891 417 891 428 892 479 892 417 892 480 893 481 893 441 893 465 894 480 894 441 894 481 895 442 895 441 895 456 896 477 896 457 896 370 897 482 897 375 897 482 898 287 898 375 898 469 899 483 899 351 899 483 900 358 900 351 900 476 901 448 901 447 901 442 902 484 902 427 902 484 903 475 903 427 903 455 904 477 904 456 904 461 905 482 905 370 905 483 906 463 906 358 906 485 907 428 907 424 907 478 908 485 908 424 908 382 909 486 909 476 909 486 910 448 910 476 910 487 911 314 911 477 911 455 912 487 912 477 912 486 913 444 913 448 913 454 914 487 914 455 914 382 915 445 915 486 915 445 916 444 916 486 916 453 917 314 917 487 917 454 918 453 918 487 918 431 919 488 919 418 919 488 920 419 920 418 920 287 921 489 921 420 921 489 922 471 922 420 922 382 923 449 923 445 923 452 924 314 924 453 924 481 925 490 925 442 925 490 926 484 926 442 926 470 927 440 927 426 927 491 928 479 928 428 928 485 929 491 929 428 929 492 930 493 930 481 930 480 931 492 931 481 931 493 932 490 932 481 932 494 933 473 933 474 933 475 934 494 934 474 934 484 934 494 934 475 934 494 935 478 935 473 935 490 934 494 934 484 934 494 936 485 936 478 936 493 934 494 934 490 934 494 937 491 937 485 937 495 934 494 934 493 934 492 938 495 938 493 938 496 939 497 939 460 939 497 940 498 940 460 940 498 941 461 941 460 941 462 942 499 942 460 942 499 943 496 943 460 943 483 944 500 944 463 944 500 945 501 945 463 945 501 946 470 946 463 946 498 947 482 947 461 947 469 948 500 948 483 948 482 949 489 949 287 949 502 950 469 950 327 950 419 951 502 951 327 951 438 952 437 952 462 952 437 953 499 953 462 953 503 954 439 954 470 954 439 955 440 955 470 955 501 956 503 956 470 956 504 957 436 957 466 957 505 958 504 958 466 958 506 959 505 959 466 959 467 960 506 960 466 960 464 961 507 961 465 961 507 962 480 962 465 962 381 963 450 963 382 963 450 964 449 964 382 964 452 965 433 965 314 965 498 966 508 966 482 966 508 967 489 967 482 967 502 968 509 968 469 968 509 969 500 969 469 969 451 970 510 970 452 970 510 971 433 971 452 971 497 972 508 972 498 972 509 973 501 973 500 973 511 974 506 974 467 974 479 975 511 975 467 975 507 976 512 976 480 976 512 977 492 977 480 977 513 978 511 978 479 978 491 979 513 979 479 979 512 980 514 980 492 980 514 981 495 981 492 981 515 982 516 982 430 982 429 983 515 983 430 983 517 984 431 984 430 984 516 985 517 985 430 985 518 986 434 986 432 986 472 987 518 987 432 987 519 988 515 988 429 988 433 989 519 989 429 989 520 990 381 990 434 990 521 991 520 991 434 991 522 992 521 992 434 992 518 993 522 993 434 993 519 994 523 994 515 994 523 995 516 995 515 995 524 996 488 996 431 996 517 997 524 997 431 997 471 998 525 998 472 998 525 999 518 999 472 999 494 1000 513 1000 491 1000 526 1001 494 1001 495 1001 514 1002 526 1002 495 1002 527 1003 419 1003 488 1003 524 1004 527 1004 488 1004 489 1005 528 1005 471 1005 529 1006 525 1006 471 1006 528 1007 529 1007 471 1007 517 1008 530 1008 524 1008 531 1009 527 1009 524 1009 530 1010 531 1010 524 1010 508 1011 528 1011 489 1011 532 1012 502 1012 419 1012 527 1013 532 1013 419 1013 533 1014 534 1014 496 1014 534 1015 497 1015 496 1015 499 1016 535 1016 496 1016 535 1017 533 1017 496 1017 509 1018 536 1018 501 1018 536 1019 503 1019 501 1019 537 1020 535 1020 499 1020 437 1021 538 1021 499 1021 538 1022 537 1022 499 1022 539 1023 540 1023 503 1023 540 1024 439 1024 503 1024 536 1025 539 1025 503 1025 497 1026 541 1026 508 1026 541 1027 528 1027 508 1027 532 1028 542 1028 502 1028 542 1029 509 1029 502 1029 520 1030 543 1030 381 1030 543 1031 450 1031 381 1031 544 1032 519 1032 433 1032 510 1033 544 1033 433 1033 543 1034 443 1034 450 1034 451 1035 544 1035 510 1035 534 1036 541 1036 497 1036 542 1037 536 1037 509 1037 436 1038 504 1038 437 1038 504 1039 538 1039 437 1039 545 1040 464 1040 439 1040 540 1041 545 1041 439 1041 545 1042 507 1042 464 1042 546 1043 504 1043 505 1043 547 1044 546 1044 505 1044 506 1045 547 1045 505 1045 545 1046 548 1046 507 1046 548 1047 512 1047 507 1047 549 1048 550 1048 504 1048 550 1049 537 1049 504 1049 537 1050 538 1050 504 1050 546 1051 549 1051 504 1051 540 1052 551 1052 545 1052 551 1053 548 1053 545 1053 539 1054 552 1054 540 1054 552 1055 551 1055 540 1055 553 1056 547 1056 506 1056 511 1057 553 1057 506 1057 548 1058 554 1058 512 1058 554 1059 514 1059 512 1059 555 1060 1 1060 443 1060 556 1061 555 1061 443 1061 557 1062 556 1062 443 1062 543 1063 557 1063 443 1063 1 1064 558 1064 451 1064 559 1065 544 1065 451 1065 558 1066 559 1066 451 1066 520 1067 557 1067 543 1067 559 1068 519 1068 544 1068 560 1069 553 1069 511 1069 513 1070 560 1070 511 1070 554 1071 561 1071 514 1071 561 1072 526 1072 514 1072 494 1073 560 1073 513 1073 562 934 494 934 526 934 561 1074 562 1074 526 1074 563 1075 529 1075 528 1075 541 1076 563 1076 528 1076 564 1077 532 1077 527 1077 531 1078 564 1078 527 1078 534 1079 565 1079 541 1079 565 1080 563 1080 541 1080 564 1081 566 1081 532 1081 566 1082 542 1082 532 1082 521 1083 556 1083 520 1083 556 1084 557 1084 520 1084 559 1085 567 1085 519 1085 567 1086 523 1086 519 1086 558 1087 568 1087 559 1087 568 1088 567 1088 559 1088 569 1089 565 1089 534 1089 533 1090 569 1090 534 1090 570 1091 536 1091 542 1091 566 1092 570 1092 542 1092 571 1093 569 1093 533 1093 535 1094 572 1094 533 1094 572 1095 571 1095 533 1095 570 1096 539 1096 536 1096 537 1097 550 1097 535 1097 550 1098 572 1098 535 1098 573 1099 552 1099 539 1099 570 1100 573 1100 539 1100 573 1101 574 1101 552 1101 574 1102 551 1102 552 1102 575 1103 576 1103 516 1103 523 1104 575 1104 516 1104 577 1105 517 1105 516 1105 576 1106 577 1106 516 1106 578 1107 579 1107 518 1107 579 1108 580 1108 518 1108 580 1109 522 1109 518 1109 525 1110 578 1110 518 1110 567 1111 575 1111 523 1111 581 1112 521 1112 522 1112 580 1113 581 1113 522 1113 582 1114 549 1114 546 1114 583 1115 582 1115 546 1115 547 1116 583 1116 546 1116 551 1117 584 1117 548 1117 584 1118 554 1118 548 1118 585 1119 583 1119 547 1119 553 1120 585 1120 547 1120 584 1121 586 1121 554 1121 586 1122 561 1122 554 1122 577 1123 587 1123 517 1123 587 1124 588 1124 517 1124 588 1125 530 1125 517 1125 589 1126 590 1126 525 1126 529 1127 589 1127 525 1127 590 1128 578 1128 525 1128 591 1129 531 1129 530 1129 588 1130 591 1130 530 1130 563 1131 589 1131 529 1131 592 1132 585 1132 553 1132 560 1133 592 1133 553 1133 586 1134 593 1134 561 1134 593 1135 562 1135 561 1135 594 1136 589 1136 563 1136 565 1137 594 1137 563 1137 595 1138 564 1138 531 1138 591 1139 595 1139 531 1139 494 1140 592 1140 560 1140 596 1141 494 1141 562 1141 593 1142 596 1142 562 1142 569 1143 597 1143 565 1143 597 1144 594 1144 565 1144 595 1145 598 1145 564 1145 598 1146 566 1146 564 1146 599 1147 581 1147 580 1147 579 1148 599 1148 580 1148 600 1149 601 1149 575 1149 601 1150 602 1150 575 1150 602 1151 603 1151 575 1151 567 1152 600 1152 575 1152 603 1153 576 1153 575 1153 604 1154 597 1154 569 1154 571 1155 604 1155 569 1155 605 1156 570 1156 566 1156 598 1157 605 1157 566 1157 581 1158 606 1158 521 1158 606 1159 556 1159 521 1159 568 1160 600 1160 567 1160 606 1161 555 1161 556 1161 558 1162 607 1162 568 1162 607 1163 600 1163 568 1163 608 1164 604 1164 571 1164 572 1165 609 1165 571 1165 609 1166 608 1166 571 1166 605 1167 573 1167 570 1167 550 1168 610 1168 572 1168 610 1169 609 1169 572 1169 605 1170 611 1170 573 1170 611 1171 612 1171 573 1171 612 1172 574 1172 573 1172 613 1173 590 1173 589 1173 614 1174 615 1174 589 1174 615 1175 616 1175 589 1175 616 1176 613 1176 589 1176 594 1177 614 1177 589 1177 617 1178 618 1178 588 1178 587 1179 617 1179 588 1179 619 1180 591 1180 588 1180 618 1181 619 1181 588 1181 549 1182 610 1182 550 1182 612 1183 551 1183 574 1183 620 1184 609 1184 610 1184 621 1185 622 1185 610 1185 622 1186 623 1186 610 1186 623 1187 620 1187 610 1187 549 1188 621 1188 610 1188 611 1189 624 1189 612 1189 624 1190 625 1190 612 1190 625 1191 626 1191 612 1191 626 1192 551 1192 612 1192 627 1193 621 1193 582 1193 621 1194 549 1194 582 1194 628 1195 627 1195 582 1195 583 1196 628 1196 582 1196 551 1197 629 1197 584 1197 629 1198 586 1198 584 1198 626 1199 629 1199 551 1199 627 1200 622 1200 621 1200 625 1201 630 1201 626 1201 630 1202 631 1202 626 1202 631 1203 629 1203 626 1203 632 1204 628 1204 583 1204 585 1205 632 1205 583 1205 629 1206 633 1206 586 1206 633 1207 593 1207 586 1207 634 1208 632 1208 585 1208 592 1209 634 1209 585 1209 633 1210 635 1210 593 1210 635 1211 596 1211 593 1211 636 1212 637 1212 594 1212 637 1213 614 1213 594 1213 597 1214 636 1214 594 1214 619 1215 638 1215 591 1215 638 1216 639 1216 591 1216 639 1217 640 1217 591 1217 641 1218 595 1218 591 1218 640 1219 641 1219 591 1219 642 1220 1 1220 555 1220 606 1221 642 1221 555 1221 1 1222 643 1222 558 1222 643 1223 644 1223 558 1223 644 1224 607 1224 558 1224 645 1225 642 1225 606 1225 581 1226 645 1226 606 1226 644 1227 600 1227 607 1227 604 1228 646 1228 597 1228 646 1229 647 1229 597 1229 647 1230 636 1230 597 1230 641 1231 648 1231 595 1231 648 1232 649 1232 595 1232 649 1233 598 1233 595 1233 608 1234 646 1234 604 1234 649 1235 605 1235 598 1235 650 1236 651 1236 581 1236 651 1237 652 1237 581 1237 652 1238 653 1238 581 1238 653 1239 654 1239 581 1239 654 1240 645 1240 581 1240 599 1241 650 1241 581 1241 655 1242 656 1242 600 1242 644 1243 655 1243 600 1243 656 1244 657 1244 600 1244 657 1245 658 1245 600 1245 658 1246 601 1246 600 1246 654 1247 642 1247 645 1247 643 1248 655 1248 644 1248 659 1249 660 1249 576 1249 660 1250 661 1250 576 1250 661 1251 662 1251 576 1251 603 1252 659 1252 576 1252 663 1253 577 1253 576 1253 662 1254 663 1254 576 1254 664 1255 665 1255 578 1255 665 1256 666 1256 578 1256 666 1257 579 1257 578 1257 667 1258 668 1258 578 1258 668 1259 669 1259 578 1259 669 1260 670 1260 578 1260 670 1261 664 1261 578 1261 590 1262 667 1262 578 1262 494 934 634 934 592 934 671 934 494 934 596 934 635 1263 671 1263 596 1263 602 1264 672 1264 603 1264 672 1265 673 1265 603 1265 673 1266 674 1266 603 1266 674 1267 659 1267 603 1267 675 1268 599 1268 579 1268 676 1269 675 1269 579 1269 666 1270 676 1270 579 1270 663 1271 677 1271 577 1271 677 1272 678 1272 577 1272 678 1273 679 1273 577 1273 679 1274 587 1274 577 1274 613 1275 680 1275 590 1275 680 1276 667 1276 590 1276 681 1277 682 1277 608 1277 682 1278 646 1278 608 1278 609 1279 683 1279 608 1279 683 1280 681 1280 608 1280 649 1281 684 1281 605 1281 684 1282 611 1282 605 1282 682 1283 647 1283 646 1283 648 1284 684 1284 649 1284 685 1285 683 1285 609 1285 620 1286 685 1286 609 1286 684 1287 686 1287 611 1287 686 1288 624 1288 611 1288 679 1289 687 1289 587 1289 688 1290 617 1290 587 1290 687 1291 688 1291 587 1291 689 1292 680 1292 613 1292 690 1293 689 1293 613 1293 616 1294 691 1294 613 1294 691 1295 690 1295 613 1295 623 1296 685 1296 620 1296 686 1297 692 1297 624 1297 692 1298 625 1298 624 1298 693 1299 622 1299 627 1299 694 1300 693 1300 627 1300 628 1301 694 1301 627 1301 631 1302 633 1302 629 1302 695 1303 694 1303 628 1303 632 1304 695 1304 628 1304 631 1305 696 1305 633 1305 696 1306 635 1306 633 1306 697 1307 642 1307 654 1307 653 1308 697 1308 654 1308 643 1309 698 1309 655 1309 698 1310 656 1310 655 1310 699 1311 637 1311 636 1311 647 1312 699 1312 636 1312 639 1313 700 1313 640 1313 700 1314 701 1314 640 1314 701 1315 641 1315 640 1315 702 1316 642 1316 697 1316 653 1317 702 1317 697 1317 643 1318 703 1318 698 1318 703 1319 656 1319 698 1319 652 1320 702 1320 653 1320 703 1321 657 1321 656 1321 704 1322 705 1322 647 1322 706 1323 707 1323 647 1323 707 1324 708 1324 647 1324 708 1325 709 1325 647 1325 709 1326 704 1326 647 1326 682 1327 706 1327 647 1327 705 1328 699 1328 647 1328 701 1329 710 1329 641 1329 710 1330 711 1330 641 1330 711 1331 648 1331 641 1331 712 1332 642 1332 702 1332 652 1333 712 1333 702 1333 713 1334 712 1334 652 1334 651 1335 713 1335 652 1335 714 1336 658 1336 657 1336 703 1337 714 1337 657 1337 643 1338 714 1338 703 1338 715 1339 706 1339 682 1339 681 1340 716 1340 682 1340 716 1341 715 1341 682 1341 717 1342 684 1342 648 1342 711 1343 717 1343 648 1343 713 1344 642 1344 712 1344 643 1345 718 1345 714 1345 718 1346 658 1346 714 1346 719 1347 695 1347 632 1347 634 1348 719 1348 632 1348 696 1349 720 1349 635 1349 720 1350 671 1350 635 1350 721 1351 642 1351 713 1351 651 1352 721 1352 713 1352 650 1353 721 1353 651 1353 718 1354 601 1354 658 1354 722 1355 723 1355 650 1355 599 1356 722 1356 650 1356 723 1357 721 1357 650 1357 724 1358 602 1358 601 1358 718 1359 724 1359 601 1359 723 1360 642 1360 721 1360 725 1361 722 1361 599 1361 726 1362 725 1362 599 1362 675 1363 727 1363 599 1363 728 1364 726 1364 599 1364 727 1365 728 1365 599 1365 724 1366 729 1366 602 1366 729 1367 730 1367 602 1367 730 1368 731 1368 602 1368 731 1369 732 1369 602 1369 732 1370 672 1370 602 1370 643 1371 724 1371 718 1371 733 1372 734 1372 681 1372 734 1373 735 1373 681 1373 735 1374 736 1374 681 1374 736 1375 716 1375 681 1375 683 1376 737 1376 681 1376 737 1377 733 1377 681 1377 738 1378 739 1378 684 1378 717 1379 740 1379 684 1379 740 1380 741 1380 684 1380 741 1381 738 1381 684 1381 739 1382 686 1382 684 1382 676 1383 727 1383 675 1383 742 1384 673 1384 672 1384 732 1385 742 1385 672 1385 743 1386 674 1386 673 1386 742 1387 743 1387 673 1387 744 1388 727 1388 676 1388 745 1389 744 1389 676 1389 666 1390 745 1390 676 1390 743 1391 659 1391 674 1391 665 1392 745 1392 666 1392 494 934 719 934 634 934 746 934 494 934 671 934 720 1393 746 1393 671 1393 747 1394 660 1394 659 1394 743 1395 748 1395 659 1395 748 1396 747 1396 659 1396 664 1397 749 1397 665 1397 749 1398 745 1398 665 1398 670 1399 749 1399 664 1399 750 1400 737 1400 683 1400 751 1401 750 1401 683 1401 685 1402 751 1402 683 1402 739 1403 752 1403 686 1403 752 1404 753 1404 686 1404 753 1405 692 1405 686 1405 669 1406 754 1406 670 1406 754 1407 749 1407 670 1407 747 1408 755 1408 660 1408 755 1409 661 1409 660 1409 755 1410 662 1410 661 1410 616 1411 756 1411 691 1411 756 1412 690 1412 691 1412 757 1413 618 1413 617 1413 758 1414 757 1414 617 1414 688 1415 758 1415 617 1415 759 1416 756 1416 616 1416 615 1417 759 1417 616 1417 668 1418 754 1418 669 1418 760 1419 663 1419 662 1419 755 1420 760 1420 662 1420 761 1421 619 1421 618 1421 757 1422 761 1422 618 1422 722 1423 642 1423 723 1423 643 1424 729 1424 724 1424 667 1425 754 1425 668 1425 760 1426 677 1426 663 1426 762 1427 763 1427 690 1427 763 1428 764 1428 690 1428 764 1429 765 1429 690 1429 765 1430 689 1430 690 1430 766 1431 762 1431 690 1431 756 1432 766 1432 690 1432 767 1433 768 1433 688 1433 687 1434 767 1434 688 1434 768 1435 769 1435 688 1435 769 1436 770 1436 688 1436 770 1437 758 1437 688 1437 771 1438 759 1438 615 1438 614 1439 771 1439 615 1439 772 1440 638 1440 619 1440 761 1441 772 1441 619 1441 773 1442 754 1442 667 1442 680 1443 773 1443 667 1443 774 1444 678 1444 677 1444 760 1445 774 1445 677 1445 773 1446 680 1446 689 1446 765 1447 773 1447 689 1447 679 1448 767 1448 687 1448 775 1449 679 1449 678 1449 774 1450 775 1450 678 1450 775 1451 767 1451 679 1451 776 1452 743 1452 742 1452 732 1453 731 1453 742 1453 731 1454 776 1454 742 1454 745 1455 777 1455 744 1455 777 1456 778 1456 744 1456 778 1457 779 1457 744 1457 779 1458 727 1458 744 1458 777 1459 745 1459 749 1459 778 1460 777 1460 749 1460 780 1461 781 1461 749 1461 781 1462 782 1462 749 1462 782 1463 778 1463 749 1463 754 1464 780 1464 749 1464 783 1465 728 1465 727 1465 779 1466 783 1466 727 1466 776 1467 748 1467 743 1467 784 1468 785 1468 773 1468 765 1469 784 1469 773 1469 785 1470 754 1470 773 1470 785 1471 786 1471 754 1471 786 1472 787 1472 754 1472 787 1473 788 1473 754 1473 788 1474 780 1474 754 1474 782 1475 779 1475 778 1475 789 1476 639 1476 638 1476 772 1477 789 1477 638 1477 790 1478 771 1478 614 1478 637 1479 790 1479 614 1479 791 1480 751 1480 685 1480 623 1481 791 1481 685 1481 792 1482 793 1482 692 1482 753 1483 792 1483 692 1483 793 1484 625 1484 692 1484 764 1485 784 1485 765 1485 725 1486 642 1486 722 1486 786 1487 785 1487 784 1487 764 1488 794 1488 784 1488 794 1489 787 1489 784 1489 787 1490 786 1490 784 1490 795 1491 700 1491 639 1491 789 1492 795 1492 639 1492 796 1493 790 1493 637 1493 699 1494 796 1494 637 1494 797 1495 781 1495 780 1495 788 1496 797 1496 780 1496 798 1497 748 1497 776 1497 799 1498 798 1498 776 1498 731 1499 800 1499 776 1499 800 1500 799 1500 776 1500 781 1501 801 1501 779 1501 782 1502 781 1502 779 1502 801 1503 783 1503 779 1503 802 1504 728 1504 783 1504 801 1505 802 1505 783 1505 730 1506 800 1506 731 1506 803 1507 801 1507 781 1507 797 1508 803 1508 781 1508 798 1509 747 1509 748 1509 763 1510 794 1510 764 1510 804 1511 805 1511 788 1511 787 1512 806 1512 788 1512 806 1513 804 1513 788 1513 805 1514 797 1514 788 1514 763 1515 807 1515 794 1515 807 1516 804 1516 794 1516 804 1517 806 1517 794 1517 806 1518 787 1518 794 1518 643 1519 808 1519 729 1519 808 1520 730 1520 729 1520 809 1521 701 1521 700 1521 795 1522 809 1522 700 1522 774 1523 768 1523 767 1523 775 1524 774 1524 767 1524 726 1525 642 1525 725 1525 810 1526 642 1526 726 1526 728 1527 810 1527 726 1527 643 1528 811 1528 808 1528 811 1529 730 1529 808 1529 812 1530 813 1530 728 1530 813 1531 810 1531 728 1531 814 1532 812 1532 728 1532 802 1533 814 1533 728 1533 811 1534 815 1534 730 1534 815 1535 816 1535 730 1535 816 1536 817 1536 730 1536 817 1537 818 1537 730 1537 818 1538 800 1538 730 1538 759 1539 819 1539 756 1539 819 1540 766 1540 756 1540 820 1541 757 1541 758 1541 770 1542 820 1542 758 1542 821 1543 819 1543 759 1543 771 1544 821 1544 759 1544 822 1545 761 1545 757 1545 820 1546 822 1546 757 1546 823 1547 769 1547 768 1547 774 1548 824 1548 768 1548 824 1549 825 1549 768 1549 825 1550 823 1550 768 1550 762 1551 807 1551 763 1551 826 1552 827 1552 760 1552 824 1553 774 1553 760 1553 827 1554 824 1554 760 1554 755 1555 828 1555 760 1555 828 1556 826 1556 760 1556 829 1557 821 1557 771 1557 790 1558 829 1558 771 1558 747 1559 830 1559 755 1559 830 1560 831 1560 755 1560 831 1561 828 1561 755 1561 832 1562 833 1562 807 1562 833 1563 834 1563 807 1563 762 1564 832 1564 807 1564 834 1565 835 1565 807 1565 835 1566 804 1566 807 1566 836 1567 772 1567 761 1567 822 1568 836 1568 761 1568 837 1569 838 1569 747 1569 839 1570 837 1570 747 1570 798 1571 839 1571 747 1571 838 1572 840 1572 747 1572 840 1573 830 1573 747 1573 835 1574 805 1574 804 1574 834 1575 805 1575 835 1575 827 1576 825 1576 824 1576 799 1577 839 1577 798 1577 841 1578 842 1578 797 1578 843 1579 844 1579 797 1579 844 1580 803 1580 797 1580 845 1581 843 1581 797 1581 846 1582 845 1582 797 1582 842 1583 846 1583 797 1583 805 1584 841 1584 797 1584 801 1585 814 1585 802 1585 818 1586 799 1586 800 1586 847 1587 812 1587 814 1587 801 1588 847 1588 814 1588 848 1589 799 1589 818 1589 817 1590 848 1590 818 1590 844 1591 843 1591 801 1591 849 1592 847 1592 801 1592 843 1593 849 1593 801 1593 803 1594 844 1594 801 1594 837 1595 839 1595 799 1595 848 1596 837 1596 799 1596 848 1597 850 1597 837 1597 850 1598 851 1598 837 1598 851 1599 838 1599 837 1599 834 1600 833 1600 805 1600 833 1601 852 1601 805 1601 852 1602 853 1602 805 1602 853 1603 854 1603 805 1603 854 1604 841 1604 805 1604 855 1605 789 1605 772 1605 836 1606 855 1606 772 1606 856 1607 829 1607 790 1607 796 1608 856 1608 790 1608 705 1609 857 1609 699 1609 857 1610 796 1610 699 1610 858 1611 710 1611 701 1611 809 1612 858 1612 701 1612 643 1613 815 1613 811 1613 766 1614 859 1614 762 1614 859 1615 832 1615 762 1615 860 1616 849 1616 843 1616 845 1617 860 1617 843 1617 861 1618 795 1618 789 1618 855 1619 861 1619 789 1619 862 1620 710 1620 858 1620 809 1621 862 1621 858 1621 863 1622 856 1622 796 1622 864 1623 863 1623 796 1623 857 1624 864 1624 796 1624 865 1625 737 1625 750 1625 751 1626 865 1626 750 1626 866 1627 867 1627 753 1627 867 1628 792 1628 753 1628 752 1629 866 1629 753 1629 862 1630 868 1630 710 1630 868 1631 869 1631 710 1631 869 1632 870 1632 710 1632 870 1633 871 1633 710 1633 871 1634 872 1634 710 1634 872 1635 711 1635 710 1635 872 1636 873 1636 711 1636 874 1637 717 1637 711 1637 873 1638 874 1638 711 1638 813 1639 642 1639 810 1639 791 1640 875 1640 751 1640 875 1641 865 1641 751 1641 867 1642 793 1642 792 1642 865 1643 876 1643 737 1643 876 1644 733 1644 737 1644 739 1645 877 1645 752 1645 877 1646 866 1646 752 1646 623 1647 878 1647 791 1647 878 1648 875 1648 791 1648 879 1649 625 1649 793 1649 880 1650 879 1650 793 1650 867 1651 880 1651 793 1651 876 1652 881 1652 733 1652 881 1653 734 1653 733 1653 738 1654 877 1654 739 1654 622 1655 882 1655 623 1655 882 1656 878 1656 623 1656 883 1657 630 1657 625 1657 879 1658 883 1658 625 1658 643 1659 884 1659 815 1659 884 1660 816 1660 815 1660 861 1661 809 1661 795 1661 885 1662 882 1662 622 1662 886 1663 885 1663 622 1663 693 1664 886 1664 622 1664 887 1665 631 1665 630 1665 883 1666 887 1666 630 1666 888 1667 886 1667 693 1667 694 1668 888 1668 693 1668 887 1669 696 1669 631 1669 881 1670 889 1670 734 1670 889 1671 735 1671 734 1671 890 1672 877 1672 738 1672 741 1673 890 1673 738 1673 704 1674 891 1674 705 1674 891 1675 857 1675 705 1675 809 1676 892 1676 862 1676 892 1677 893 1677 862 1677 893 1678 868 1678 862 1678 894 1679 888 1679 694 1679 695 1680 894 1680 694 1680 887 1681 895 1681 696 1681 895 1682 720 1682 696 1682 889 1683 896 1683 735 1683 896 1684 736 1684 735 1684 897 1685 890 1685 741 1685 740 1686 897 1686 741 1686 896 1687 898 1687 736 1687 898 1688 716 1688 736 1688 899 1689 897 1689 740 1689 717 1690 899 1690 740 1690 898 1691 900 1691 716 1691 900 1692 715 1692 716 1692 901 1693 899 1693 717 1693 874 1694 901 1694 717 1694 902 1695 766 1695 819 1695 903 1696 904 1696 819 1696 821 1697 903 1697 819 1697 905 1698 902 1698 819 1698 906 1699 905 1699 819 1699 904 1700 906 1700 819 1700 907 1701 908 1701 770 1701 908 1702 909 1702 770 1702 909 1703 910 1703 770 1703 769 1704 907 1704 770 1704 822 1705 820 1705 770 1705 910 1706 822 1706 770 1706 902 1707 859 1707 766 1707 823 1708 907 1708 769 1708 902 1709 832 1709 859 1709 825 1710 911 1710 823 1710 911 1711 907 1711 823 1711 912 1712 833 1712 832 1712 913 1713 912 1713 832 1713 902 1714 913 1714 832 1714 829 1715 903 1715 821 1715 914 1716 852 1716 833 1716 915 1717 914 1717 833 1717 912 1718 915 1718 833 1718 827 1719 911 1719 825 1719 856 1720 903 1720 829 1720 910 1721 836 1721 822 1721 916 1722 894 1722 695 1722 719 1723 916 1723 695 1723 895 1724 917 1724 720 1724 917 1725 746 1725 720 1725 918 1726 853 1726 852 1726 914 1727 918 1727 852 1727 826 1728 919 1728 827 1728 919 1729 911 1729 827 1729 828 1730 920 1730 826 1730 920 1731 919 1731 826 1731 831 1732 920 1732 828 1732 921 1733 922 1733 853 1733 922 1734 923 1734 853 1734 923 1735 854 1735 853 1735 918 1736 921 1736 853 1736 923 1737 841 1737 854 1737 891 1738 924 1738 857 1738 924 1739 864 1739 857 1739 925 1740 926 1740 809 1740 926 1741 892 1741 809 1741 927 1742 925 1742 809 1742 861 1743 927 1743 809 1743 923 1744 842 1744 841 1744 910 1745 855 1745 836 1745 900 1746 928 1746 715 1746 928 1747 706 1747 715 1747 929 1748 901 1748 874 1748 873 1749 929 1749 874 1749 863 1750 903 1750 856 1750 830 1751 920 1751 831 1751 930 1752 920 1752 830 1752 840 1753 931 1753 830 1753 931 1754 932 1754 830 1754 932 1755 930 1755 830 1755 933 1756 846 1756 842 1756 923 1757 933 1757 842 1757 838 1758 934 1758 840 1758 934 1759 935 1759 840 1759 935 1760 931 1760 840 1760 933 1761 845 1761 846 1761 936 1762 885 1762 886 1762 888 1763 936 1763 886 1763 937 1764 860 1764 845 1764 938 1765 937 1765 845 1765 933 1766 938 1766 845 1766 851 1767 934 1767 838 1767 850 1768 939 1768 851 1768 939 1769 934 1769 851 1769 709 1770 940 1770 704 1770 940 1771 891 1771 704 1771 893 1772 869 1772 868 1772 941 1773 813 1773 812 1773 847 1774 942 1774 812 1774 942 1775 943 1775 812 1775 943 1776 941 1776 812 1776 884 1777 944 1777 816 1777 944 1778 945 1778 816 1778 945 1779 817 1779 816 1779 946 1780 947 1780 860 1780 947 1781 849 1781 860 1781 948 1782 949 1782 860 1782 949 1783 950 1783 860 1783 950 1784 946 1784 860 1784 937 1785 948 1785 860 1785 951 1786 939 1786 850 1786 848 1787 952 1787 850 1787 952 1788 953 1788 850 1788 953 1789 951 1789 850 1789 817 1790 954 1790 848 1790 954 1791 952 1791 848 1791 947 1792 847 1792 849 1792 947 1793 942 1793 847 1793 945 1794 955 1794 817 1794 955 1795 954 1795 817 1795 956 1796 936 1796 888 1796 957 1797 956 1797 888 1797 894 1798 957 1798 888 1798 941 1799 642 1799 813 1799 643 1800 944 1800 884 1800 958 1801 940 1801 709 1801 708 1802 958 1802 709 1802 893 1803 959 1803 869 1803 959 1804 870 1804 869 1804 960 1805 707 1805 706 1805 961 1806 960 1806 706 1806 928 1807 961 1807 706 1807 872 1808 962 1808 873 1808 963 1809 929 1809 873 1809 962 1810 963 1810 873 1810 910 1811 861 1811 855 1811 707 1812 964 1812 708 1812 965 1813 958 1813 708 1813 964 1814 965 1814 708 1814 959 1815 871 1815 870 1815 494 1816 916 1816 719 1816 966 934 494 934 746 934 917 1817 966 1817 746 1817 967 1818 903 1818 863 1818 864 1819 967 1819 863 1819 968 1820 969 1820 707 1820 970 1821 971 1821 707 1821 971 1822 972 1822 707 1822 972 1823 968 1823 707 1823 960 1824 970 1824 707 1824 969 1825 964 1825 707 1825 973 1826 962 1826 872 1826 871 1827 974 1827 872 1827 974 1828 975 1828 872 1828 975 1829 976 1829 872 1829 976 1830 977 1830 872 1830 977 1831 973 1831 872 1831 969 1832 965 1832 964 1832 959 1833 978 1833 871 1833 978 1834 979 1834 871 1834 979 1835 974 1835 871 1835 980 1836 957 1836 894 1836 916 1837 980 1837 894 1837 981 1838 959 1838 893 1838 892 1839 981 1839 893 1839 982 1840 970 1840 960 1840 961 1841 982 1841 960 1841 973 1842 983 1842 962 1842 983 1843 963 1843 962 1843 984 1844 965 1844 969 1844 968 1845 984 1845 969 1845 979 1846 985 1846 974 1846 985 1847 975 1847 974 1847 986 1848 971 1848 970 1848 987 1849 986 1849 970 1849 982 1850 987 1850 970 1850 977 1851 988 1851 973 1851 988 1852 983 1852 973 1852 989 1853 990 1853 861 1853 990 1854 991 1854 861 1854 991 1855 927 1855 861 1855 910 1856 992 1856 861 1856 992 1857 989 1857 861 1857 993 1858 984 1858 968 1858 972 1859 993 1859 968 1859 994 1860 976 1860 975 1860 985 1861 995 1861 975 1861 995 1862 994 1862 975 1862 996 1863 971 1863 986 1863 987 1864 996 1864 986 1864 976 1865 997 1865 977 1865 997 1866 988 1866 977 1866 998 1867 999 1867 865 1867 999 1868 876 1868 865 1868 875 1869 998 1869 865 1869 1000 1870 1001 1870 866 1870 1001 1871 867 1871 866 1871 877 1872 1000 1872 866 1872 1002 1873 993 1873 972 1873 971 1874 1002 1874 972 1874 995 1875 1003 1875 994 1875 1003 1876 976 1876 994 1876 996 1877 1002 1877 971 1877 1003 1878 997 1878 976 1878 878 1879 1004 1879 875 1879 1004 1880 998 1880 875 1880 1001 1881 880 1881 867 1881 1005 1882 1 1882 642 1882 1006 1883 1005 1883 642 1883 941 1884 1006 1884 642 1884 1 1885 1007 1885 643 1885 1007 1886 1008 1886 643 1886 1008 1887 944 1887 643 1887 1009 1888 945 1888 944 1888 1008 1889 1009 1889 944 1889 940 1890 1010 1890 891 1890 1010 1891 1011 1891 891 1891 1011 1892 924 1892 891 1892 926 1893 1012 1893 892 1893 1012 1894 1013 1894 892 1894 1013 1895 981 1895 892 1895 943 1896 1014 1896 941 1896 1014 1897 1006 1897 941 1897 999 1898 1015 1898 876 1898 1015 1899 881 1899 876 1899 1016 1900 1000 1900 877 1900 890 1901 1016 1901 877 1901 883 1902 1017 1902 887 1902 1017 1903 895 1903 887 1903 879 1904 1018 1904 883 1904 1019 1905 1017 1905 883 1905 1018 1906 1019 1906 883 1906 1019 1907 1020 1907 1017 1907 1020 1908 895 1908 1017 1908 494 934 980 934 916 934 1021 1909 882 1909 885 1909 1022 1910 1021 1910 885 1910 936 1911 1022 1911 885 1911 956 1912 1022 1912 936 1912 1020 1913 917 1913 895 1913 991 1914 1023 1914 927 1914 1023 1915 925 1915 927 1915 924 1916 967 1916 864 1916 1024 1917 1021 1917 1022 1917 1025 1918 1024 1918 1022 1918 956 1919 1025 1919 1022 1919 1015 1920 1026 1920 881 1920 1026 1921 889 1921 881 1921 1027 1922 1016 1922 890 1922 897 1923 1027 1923 890 1923 1028 1924 1025 1924 956 1924 957 1925 1028 1925 956 1925 1020 1926 1029 1926 917 1926 1029 1927 966 1927 917 1927 1026 1928 1030 1928 889 1928 1030 1929 896 1929 889 1929 1031 1930 1027 1930 897 1930 899 1931 1031 1931 897 1931 494 1932 1028 1932 957 1932 980 1933 494 1933 957 1933 1030 1934 1032 1934 896 1934 1032 1935 898 1935 896 1935 1033 1936 1031 1936 899 1936 901 1937 1033 1937 899 1937 1011 1938 967 1938 924 1938 1023 1939 926 1939 925 1939 1032 1940 1034 1940 898 1940 1034 1941 900 1941 898 1941 1035 1942 1033 1942 901 1942 929 1943 1035 1943 901 1943 1036 1944 494 1944 966 1944 1029 1945 1036 1945 966 1945 958 1946 1010 1946 940 1946 1034 1947 1037 1947 900 1947 1037 1948 928 1948 900 1948 1038 1949 1035 1949 929 1949 963 1950 1038 1950 929 1950 958 1951 1039 1951 1010 1951 1039 1952 1011 1952 1010 1952 1013 1953 959 1953 981 1953 1040 1954 1039 1954 958 1954 965 1955 1040 1955 958 1955 1013 1956 1041 1956 959 1956 1041 1957 1042 1957 959 1957 1042 1958 978 1958 959 1958 1018 1959 1043 1959 1019 1959 1043 1960 1020 1960 1019 1960 1043 1961 1044 1961 1020 1961 1044 1962 1029 1962 1020 1962 1012 1963 1045 1963 1013 1963 1045 1964 1041 1964 1013 1964 1046 1965 961 1965 928 1965 1037 1966 1046 1966 928 1966 1047 1967 1038 1967 963 1967 983 1968 1047 1968 963 1968 1044 1969 1048 1969 1029 1969 1048 1970 1036 1970 1029 1970 1049 1971 1040 1971 965 1971 984 1972 1049 1972 965 1972 1042 1973 1050 1973 978 1973 1050 1974 979 1974 978 1974 1051 934 494 934 1036 934 1048 1975 1051 1975 1036 1975 1052 1976 982 1976 961 1976 1046 1977 1052 1977 961 1977 988 1978 1053 1978 983 1978 1053 1979 1047 1979 983 1979 1054 1980 1049 1980 984 1980 993 1981 1054 1981 984 1981 1050 1982 1055 1982 979 1982 1055 1983 985 1983 979 1983 1056 1984 1054 1984 993 1984 1002 1985 1056 1985 993 1985 1055 1986 1057 1986 985 1986 1057 1987 995 1987 985 1987 1058 1988 987 1988 982 1988 1052 1989 1058 1989 982 1989 997 1990 1059 1990 988 1990 1059 1991 1053 1991 988 1991 1060 1992 1056 1992 1002 1992 996 1993 1060 1993 1002 1993 1057 1994 1061 1994 995 1994 1061 1995 1003 1995 995 1995 1062 1996 996 1996 987 1996 1058 1997 1062 1997 987 1997 1003 1998 1063 1998 997 1998 1063 1999 1059 1999 997 1999 1062 2000 1060 2000 996 2000 1061 2001 1063 2001 1003 2001 1064 2002 967 2002 1011 2002 1065 2003 1066 2003 1011 2003 1066 2004 1067 2004 1011 2004 1067 2005 1064 2005 1011 2005 1039 2006 1065 2006 1011 2006 1023 2007 1068 2007 926 2007 1068 2008 1069 2008 926 2008 1069 2009 1012 2009 926 2009 1070 2010 999 2010 998 2010 1071 2011 1070 2011 998 2011 1004 2012 1071 2012 998 2012 1016 2013 1072 2013 1000 2013 1072 2014 1073 2014 1000 2014 1073 2015 1001 2015 1000 2015 878 2016 1071 2016 1004 2016 1073 2017 1074 2017 1001 2017 1074 2018 1075 2018 1001 2018 1075 2019 1076 2019 1001 2019 1076 2020 880 2020 1001 2020 882 2021 1071 2021 878 2021 1076 2022 879 2022 880 2022 1021 2023 1077 2023 882 2023 1077 2024 1078 2024 882 2024 1079 2025 1071 2025 882 2025 1078 2026 1079 2026 882 2026 1076 2027 1018 2027 879 2027 1080 2028 1015 2028 999 2028 1070 2029 1080 2029 999 2029 1027 2030 1072 2030 1016 2030 1024 2031 1077 2031 1021 2031 1076 2032 1081 2032 1018 2032 1082 2033 1043 2033 1018 2033 1081 2033 1082 2033 1018 2033 1083 2031 1077 2031 1024 2031 1025 2034 1083 2034 1024 2034 1082 2035 1084 2035 1043 2035 1084 2035 1044 2035 1043 2035 1085 2034 1083 2034 1025 2034 1028 2036 1085 2036 1025 2036 1084 2037 1086 2037 1044 2037 1086 2038 1048 2038 1044 2038 1087 2039 1085 2039 1028 2039 494 2040 1087 2040 1028 2040 1086 2041 1088 2041 1048 2041 1088 2042 1051 2042 1048 2042 1051 934 1089 934 494 934 1089 2040 1087 2040 494 2040 1088 934 1089 934 1051 934 1090 2043 1026 2043 1015 2043 1080 2044 1090 2044 1015 2044 1091 2045 1072 2045 1027 2045 1031 2046 1091 2046 1027 2046 1040 2047 1065 2047 1039 2047 1092 2048 1093 2048 1026 2048 1093 2049 1094 2049 1026 2049 1094 2050 1095 2050 1026 2050 1095 2051 1096 2051 1026 2051 1096 2052 1097 2052 1026 2052 1097 2053 1030 2053 1026 2053 1090 2054 1092 2054 1026 2054 1033 2055 1098 2055 1031 2055 1098 2056 1091 2056 1031 2056 1097 2057 1032 2057 1030 2057 1035 2058 1098 2058 1033 2058 1097 2059 1034 2059 1032 2059 1038 2060 1098 2060 1035 2060 942 2061 1014 2061 943 2061 1009 2062 955 2062 945 2062 1099 2063 1066 2063 1065 2063 1040 2064 1099 2064 1065 2064 1100 2065 1045 2065 1012 2065 1069 2066 1101 2066 1012 2066 1101 2067 1100 2067 1012 2067 1102 2068 1066 2068 1099 2068 1040 2069 1103 2069 1099 2069 1103 2070 1104 2070 1099 2070 1104 2071 1102 2071 1099 2071 1100 2072 1041 2072 1045 2072 1049 2073 1103 2073 1040 2073 1100 2074 1042 2074 1041 2074 1097 2075 1037 2075 1034 2075 1047 2076 1098 2076 1038 2076 1105 2077 1103 2077 1049 2077 1054 2078 1105 2078 1049 2078 1106 2079 1107 2079 1042 2079 1107 2080 1108 2080 1042 2080 1108 2081 1050 2081 1042 2081 1100 2082 1106 2082 1042 2082 1097 2083 1046 2083 1037 2083 1053 2084 1098 2084 1047 2084 1056 2085 1105 2085 1054 2085 1108 2086 1055 2086 1050 2086 1097 2087 1052 2087 1046 2087 1109 2088 1110 2088 1053 2088 1059 2089 1109 2089 1053 2089 1110 2090 1111 2090 1053 2090 1111 2091 1112 2091 1053 2091 1112 2092 1113 2092 1053 2092 1114 2093 1098 2093 1053 2093 1113 2094 1114 2094 1053 2094 1060 2095 1115 2095 1056 2095 1115 2096 1116 2096 1056 2096 1116 2097 1105 2097 1056 2097 1117 2098 1057 2098 1055 2098 1108 2099 1118 2099 1055 2099 1118 2100 1117 2100 1055 2100 1097 2101 1119 2101 1052 2101 1119 2102 1120 2102 1052 2102 1120 2103 1058 2103 1052 2103 1063 2104 1109 2104 1059 2104 1062 2105 1120 2105 1060 2105 1120 2106 1121 2106 1060 2106 1121 2107 1115 2107 1060 2107 1117 2108 1061 2108 1057 2108 1058 2109 1120 2109 1062 2109 1117 2110 1063 2110 1061 2110 1122 2111 1109 2111 1063 2111 1123 2112 1122 2112 1063 2112 1117 2113 1123 2113 1063 2113 947 2114 1124 2114 942 2114 1124 2115 1014 2115 942 2115 1009 2116 954 2116 955 2116 1125 2117 952 2117 954 2117 1009 2118 1125 2118 954 2118 946 2119 950 2119 947 2119 950 2120 1124 2120 947 2120 1125 2121 953 2121 952 2121 1125 2122 951 2122 953 2122 1126 2123 1125 2123 1009 2123 1008 2124 1126 2124 1009 2124 1124 2125 1006 2125 1014 2125 949 2126 1127 2126 950 2126 1127 2127 1124 2127 950 2127 1125 2128 1128 2128 951 2128 1128 2129 939 2129 951 2129 1129 2130 1 2130 1005 2130 1006 2131 1130 2131 1005 2131 1130 2132 1131 2132 1005 2132 1131 2133 1132 2133 1005 2133 1132 2134 1129 2134 1005 2134 1 2135 1133 2135 1007 2135 1134 2136 1135 2136 1007 2136 1135 2137 1008 2137 1007 2137 1133 2138 1136 2138 1007 2138 1136 2139 1137 2139 1007 2139 1137 2140 1134 2140 1007 2140 1124 2141 1130 2141 1006 2141 1135 2142 1126 2142 1008 2142 1138 2143 1128 2143 1125 2143 1126 2144 1138 2144 1125 2144 1134 2145 1126 2145 1135 2145 1127 2146 1139 2146 1124 2146 1139 2147 1140 2147 1124 2147 1140 2148 1130 2148 1124 2148 1141 2149 1131 2149 1130 2149 1140 2150 1141 2150 1130 2150 1142 2151 1138 2151 1126 2151 1143 2152 1142 2152 1126 2152 1134 2153 1143 2153 1126 2153 1137 2154 1143 2154 1134 2154 1144 2155 1141 2155 1140 2155 1145 2156 1144 2156 1140 2156 1139 2157 1145 2157 1140 2157 1146 2158 1132 2158 1131 2158 1141 2159 1146 2159 1131 2159 1147 2160 1142 2160 1143 2160 1137 2161 1147 2161 1143 2161 1136 2162 1147 2162 1137 2162 1148 2163 1146 2163 1141 2163 1144 2164 1148 2164 1141 2164 1149 2165 1150 2165 1147 2165 1150 2166 1142 2166 1147 2166 1136 2167 1149 2167 1147 2167 1151 2168 1129 2168 1132 2168 1146 2169 1151 2169 1132 2169 1152 2170 1 2170 1129 2170 1153 2171 1152 2171 1129 2171 1151 2172 1153 2172 1129 2172 1 2173 1154 2173 1133 2173 1154 2174 1155 2174 1133 2174 1155 2175 1156 2175 1133 2175 1156 2176 1157 2176 1133 2176 1157 2177 1158 2177 1133 2177 1158 2178 1136 2178 1133 2178 1158 2179 1149 2179 1136 2179 1159 2180 1153 2180 1151 2180 1146 2181 1159 2181 1151 2181 1157 2182 1149 2182 1158 2182 1160 2183 1159 2183 1146 2183 1148 2184 1160 2184 1146 2184 1161 2185 1162 2185 1149 2185 1162 2186 1150 2186 1149 2186 1157 2187 1161 2187 1149 2187 1156 2188 1161 2188 1157 2188 1163 2189 1152 2189 1153 2189 1164 2190 1163 2190 1153 2190 1159 2191 1164 2191 1153 2191 1165 2192 1166 2192 1161 2192 1166 2193 1162 2193 1161 2193 1156 2194 1165 2194 1161 2194 1160 2195 1164 2195 1159 2195 1155 2196 1165 2196 1156 2196 1155 2197 1166 2197 1165 2197 1167 2198 1154 2198 1 2198 1168 2199 1167 2199 1 2199 1169 2200 1168 2200 1 2200 1170 2201 1169 2201 1 2201 1171 2202 1170 2202 1 2202 1172 2203 1171 2203 1 2203 1173 2204 1172 2204 1 2204 1174 2205 1173 2205 1 2205 1175 2206 1174 2206 1 2206 1176 2207 1175 2207 1 2207 1177 2208 1176 2208 1 2208 1178 2209 1177 2209 1 2209 1179 2210 1178 2210 1 2210 1180 2211 1179 2211 1 2211 1181 2212 1180 2212 1 2212 1152 2213 1181 2213 1 2213 1160 2214 1163 2214 1164 2214 1182 2215 1152 2215 1163 2215 1160 2216 1182 2216 1163 2216 1155 2217 1183 2217 1166 2217 1183 2218 1162 2218 1166 2218 1148 2219 1182 2219 1160 2219 1154 2220 1183 2220 1155 2220 1184 2221 1152 2221 1182 2221 1148 2222 1184 2222 1182 2222 1144 2223 1185 2223 1148 2223 1185 2224 1184 2224 1148 2224 1183 2225 1186 2225 1162 2225 1186 2226 1187 2226 1162 2226 1187 2227 1150 2227 1162 2227 1185 2228 1152 2228 1184 2228 1154 2229 1186 2229 1183 2229 1181 2230 1152 2230 1185 2230 1188 2231 1181 2231 1185 2231 1144 2232 1188 2232 1185 2232 1167 2233 1186 2233 1154 2233 1167 2234 1187 2234 1186 2234 1145 2235 1188 2235 1144 2235 1187 2236 1189 2236 1150 2236 1189 2237 1142 2237 1150 2237 1190 2238 1181 2238 1188 2238 1145 2239 1190 2239 1188 2239 1139 2240 1190 2240 1145 2240 1167 2241 1189 2241 1187 2241 1189 2242 1138 2242 1142 2242 1191 2243 1181 2243 1190 2243 1139 2244 1191 2244 1190 2244 1127 2245 1192 2245 1139 2245 1192 2246 1193 2246 1139 2246 1193 2247 1191 2247 1139 2247 1167 2248 1194 2248 1189 2248 1194 2249 1138 2249 1189 2249 1195 2250 1128 2250 1138 2250 1196 2251 1195 2251 1138 2251 1197 2252 1196 2252 1138 2252 1194 2253 1197 2253 1138 2253 1193 2254 1181 2254 1191 2254 1198 2255 1199 2255 1127 2255 949 2256 1198 2256 1127 2256 1199 2257 1200 2257 1127 2257 1200 2258 1192 2258 1127 2258 1192 2259 1201 2259 1193 2259 1180 2260 1181 2260 1193 2260 1201 2261 1180 2261 1193 2261 1167 2262 1168 2262 1194 2262 1202 2263 1197 2263 1194 2263 1168 2264 1202 2264 1194 2264 948 2265 1198 2265 949 2265 1203 2266 939 2266 1128 2266 1195 2267 1203 2267 1128 2267 1204 2268 1196 2268 1197 2268 1202 2269 1204 2269 1197 2269 1205 2270 1206 2270 1192 2270 1206 2271 1201 2271 1192 2271 1200 2272 1205 2272 1192 2272 948 2273 1199 2273 1198 2273 1195 2274 939 2274 1203 2274 1207 2275 1200 2275 1199 2275 948 2276 1207 2276 1199 2276 1208 2277 939 2277 1195 2277 1209 2278 1208 2278 1195 2278 1196 2279 1209 2279 1195 2279 1207 2280 1210 2280 1200 2280 1210 2281 1205 2281 1200 2281 1210 2282 1206 2282 1205 2282 1211 2283 1209 2283 1196 2283 1204 2284 1211 2284 1196 2284 1212 2285 1121 2285 1120 2285 1213 2286 1212 2286 1120 2286 1119 2287 1213 2287 1120 2287 1123 2288 1214 2288 1122 2288 1214 2289 1215 2289 1122 2289 1215 2290 1109 2290 1122 2290 1216 2291 1115 2291 1121 2291 1212 2292 1216 2292 1121 2292 1117 2293 1217 2293 1123 2293 1217 2294 1214 2294 1123 2294 1218 2295 1116 2295 1115 2295 1216 2296 1218 2296 1115 2296 1118 2297 1219 2297 1117 2297 1219 2298 1217 2298 1117 2298 1220 2299 1213 2299 1119 2299 1097 2300 1220 2300 1119 2300 1215 2301 1221 2301 1109 2301 1221 2302 1110 2302 1109 2302 1222 2303 1105 2303 1116 2303 1218 2304 1222 2304 1116 2304 1108 2305 1223 2305 1118 2305 1223 2306 1219 2306 1118 2306 1224 2307 1220 2307 1097 2307 1096 2308 1224 2308 1097 2308 1221 2309 1225 2309 1110 2309 1225 2310 1111 2310 1110 2310 1226 2311 1103 2311 1105 2311 1222 2312 1226 2312 1105 2312 1107 2313 1227 2313 1108 2313 1227 2314 1223 2314 1108 2314 1095 2315 1228 2315 1096 2315 1228 2316 1224 2316 1096 2316 1229 2317 1112 2317 1111 2317 1225 2318 1229 2318 1111 2318 1230 2319 1104 2319 1103 2319 1226 2320 1230 2320 1103 2320 1106 2321 1231 2321 1107 2321 1231 2322 1227 2322 1107 2322 1094 2323 1232 2323 1095 2323 1232 2324 1228 2324 1095 2324 1233 2325 1113 2325 1112 2325 1229 2326 1233 2326 1112 2326 1234 2327 1102 2327 1104 2327 1230 2328 1234 2328 1104 2328 1100 2329 1101 2329 1106 2329 1101 2330 1235 2330 1106 2330 1235 2331 1236 2331 1106 2331 1236 2332 1231 2332 1106 2332 1234 2333 1066 2333 1102 2333 1237 2334 1067 2334 1066 2334 1234 2335 1237 2335 1066 2335 1069 2336 1235 2336 1101 2336 1238 2337 1201 2337 1206 2337 1210 2338 1238 2338 1206 2338 1202 2339 1211 2339 1204 2339 1093 2340 1239 2340 1094 2340 1239 2341 1232 2341 1094 2341 1240 2342 1114 2342 1113 2342 1233 2343 1240 2343 1113 2343 1092 2344 1241 2344 1093 2344 1241 2345 1239 2345 1093 2345 1242 2346 1098 2346 1114 2346 1240 2347 1242 2347 1114 2347 1090 2348 1243 2348 1092 2348 1243 2349 1241 2349 1092 2349 1244 2350 1091 2350 1098 2350 1242 2351 1244 2351 1098 2351 1245 2352 1236 2352 1235 2352 1069 2353 1245 2353 1235 2353 1080 2354 1246 2354 1090 2354 1246 2355 1243 2355 1090 2355 1247 2356 1072 2356 1091 2356 1244 2357 1247 2357 1091 2357 1248 2358 1078 2358 1077 2358 1249 2359 1248 2359 1077 2359 1083 2360 1249 2360 1077 2360 1076 2361 1250 2361 1081 2361 1251 2362 1082 2362 1081 2362 1250 2363 1251 2363 1081 2363 1252 2364 1249 2364 1083 2364 1085 2365 1252 2365 1083 2365 1251 2366 1084 2366 1082 2366 1253 2367 1252 2367 1085 2367 1087 2368 1253 2368 1085 2368 1251 2369 1254 2369 1084 2369 1254 2370 1086 2370 1084 2370 1255 2371 1253 2371 1087 2371 1089 2372 1255 2372 1087 2372 1254 2373 1256 2373 1086 2373 1256 2374 1088 2374 1086 2374 1088 934 1255 934 1089 934 1257 2375 1258 2375 1088 2375 1258 2376 1259 2376 1088 2376 1259 934 1260 934 1088 934 1261 934 1262 934 1088 934 1262 934 1263 934 1088 934 1263 2377 1264 2377 1088 2377 1264 2378 1265 2378 1088 2378 1265 2379 1266 2379 1088 2379 1266 2380 1267 2380 1088 2380 1267 934 1268 934 1088 934 1268 2381 1255 2381 1088 2381 1269 2382 1270 2382 1088 2382 1270 934 1271 934 1088 934 1271 2383 1257 2383 1088 2383 1260 934 1272 934 1088 934 1272 934 1273 934 1088 934 1273 934 1274 934 1088 934 1274 2384 1275 2384 1088 2384 1275 934 1276 934 1088 934 1276 934 1277 934 1088 934 1277 934 1278 934 1088 934 1278 2385 1279 2385 1088 2385 1279 934 1261 934 1088 934 1256 2386 1269 2386 1088 2386 1070 2387 1280 2387 1080 2387 1280 2388 1246 2388 1080 2388 1281 2389 1073 2389 1072 2389 1247 2390 1281 2390 1072 2390 1248 2391 1282 2391 1078 2391 1282 2392 1283 2392 1078 2392 1283 2393 1079 2393 1078 2393 1284 2394 1250 2394 1076 2394 1285 2395 1284 2395 1076 2395 1075 2396 1285 2396 1076 2396 1286 2397 1071 2397 1079 2397 1283 2398 1286 2398 1079 2398 1287 2399 1285 2399 1075 2399 1288 2400 1287 2400 1075 2400 1074 2401 1288 2401 1075 2401 1289 2402 1070 2402 1071 2402 1286 2403 1289 2403 1071 2403 1073 2404 1288 2404 1074 2404 1289 2405 1280 2405 1070 2405 1281 2406 1288 2406 1073 2406 1290 2407 1064 2407 1067 2407 1237 2408 1290 2408 1067 2408 1291 2409 1245 2409 1069 2409 1068 2410 1291 2410 1069 2410 1292 2411 1216 2411 1212 2411 1293 2412 1292 2412 1212 2412 1213 2413 1293 2413 1212 2413 1219 2414 1294 2414 1217 2414 1294 2415 1295 2415 1217 2415 1295 2416 1214 2416 1217 2416 1296 2417 1293 2417 1213 2417 1220 2418 1296 2418 1213 2418 1295 2419 1297 2419 1214 2419 1297 2420 1215 2420 1214 2420 1298 2421 1218 2421 1216 2421 1292 2422 1298 2422 1216 2422 1223 2423 1299 2423 1219 2423 1299 2424 1294 2424 1219 2424 1300 2425 1296 2425 1220 2425 1224 2426 1300 2426 1220 2426 1297 2427 1301 2427 1215 2427 1301 2428 1221 2428 1215 2428 1302 2429 1222 2429 1218 2429 1298 2430 1302 2430 1218 2430 1227 2431 1303 2431 1223 2431 1303 2432 1299 2432 1223 2432 1304 2433 1226 2433 1222 2433 1302 2434 1304 2434 1222 2434 1231 2435 1305 2435 1227 2435 1305 2436 1303 2436 1227 2436 1306 2437 1300 2437 1224 2437 1228 2438 1306 2438 1224 2438 1301 2439 1307 2439 1221 2439 1307 2440 1225 2440 1221 2440 1268 2441 1253 2441 1255 2441 1304 2442 1230 2442 1226 2442 1236 2443 1308 2443 1231 2443 1308 2444 1309 2444 1231 2444 1309 2445 1305 2445 1231 2445 1310 2446 1252 2446 1253 2446 1268 2447 1310 2447 1253 2447 1232 2448 1311 2448 1228 2448 1311 2449 1306 2449 1228 2449 1312 2450 1229 2450 1225 2450 1307 2451 1312 2451 1225 2451 1230 2452 1313 2452 1234 2452 1313 2453 1237 2453 1234 2453 1314 2454 1249 2454 1252 2454 1315 2455 1314 2455 1252 2455 1310 2456 1315 2456 1252 2456 1314 2457 1248 2457 1249 2457 1316 2458 1313 2458 1230 2458 1317 2459 1316 2459 1230 2459 1318 2460 1317 2460 1230 2460 1304 2461 1318 2461 1230 2461 1245 2462 1319 2462 1236 2462 1319 2463 1320 2463 1236 2463 1320 2464 1308 2464 1236 2464 1316 2465 1237 2465 1313 2465 1291 2466 1319 2466 1245 2466 1239 2467 1321 2467 1232 2467 1321 2468 1311 2468 1232 2468 1322 2469 1233 2469 1229 2469 1312 2470 1322 2470 1229 2470 1256 2471 1323 2471 1269 2471 1323 2472 1270 2472 1269 2472 1324 2473 1320 2473 1319 2473 1291 2474 1324 2474 1319 2474 1267 2475 1310 2475 1268 2475 1241 2476 1325 2476 1239 2476 1325 2477 1321 2477 1239 2477 1326 2478 1240 2478 1233 2478 1322 2479 1326 2479 1233 2479 1290 2480 967 2480 1064 2480 1327 2481 1291 2481 1068 2481 1023 2482 1327 2482 1068 2482 1243 2483 1328 2483 1241 2483 1328 2484 1325 2484 1241 2484 1329 2485 1242 2485 1240 2485 1326 2486 1329 2486 1240 2486 1254 2487 1330 2487 1256 2487 1330 2488 1323 2488 1256 2488 1246 2489 1331 2489 1243 2489 1331 2490 1328 2490 1243 2490 1332 2491 1244 2491 1242 2491 1329 2492 1332 2492 1242 2492 1333 2493 1315 2493 1310 2493 1267 2494 1333 2494 1310 2494 1251 2495 1334 2495 1254 2495 1334 2496 1330 2496 1254 2496 1280 2497 1335 2497 1246 2497 1335 2498 1331 2498 1246 2498 1336 2499 1247 2499 1244 2499 1332 2500 1336 2500 1244 2500 1250 2501 1334 2501 1251 2501 991 2502 1337 2502 1023 2502 1337 2503 1327 2503 1023 2503 1290 2504 903 2504 967 2504 1338 2505 1314 2505 1315 2505 1339 2506 1338 2506 1315 2506 1333 2507 1339 2507 1315 2507 1250 2508 1340 2508 1334 2508 1340 2509 1330 2509 1334 2509 1284 2510 1340 2510 1250 2510 1323 2511 1341 2511 1270 2511 1341 2512 1271 2512 1270 2512 1338 2513 1248 2513 1314 2513 1342 2514 1282 2514 1248 2514 1338 2515 1342 2515 1248 2515 1343 2516 1342 2516 1338 2516 1339 2517 1343 2517 1338 2517 1344 2518 1335 2518 1280 2518 1345 2519 1344 2519 1280 2519 1289 2520 1345 2520 1280 2520 1346 2521 1281 2521 1247 2521 1336 2522 1346 2522 1247 2522 1168 2523 1347 2523 1202 2523 1347 2524 1211 2524 1202 2524 1348 2525 1290 2525 1237 2525 1316 2526 1348 2526 1237 2526 1349 2527 1324 2527 1291 2527 1327 2528 1349 2528 1291 2528 1350 2529 1351 2529 1180 2529 1351 2530 1352 2530 1180 2530 1352 2531 1353 2531 1180 2531 1353 2532 1354 2532 1180 2532 1354 2533 1355 2533 1180 2533 1355 2534 1356 2534 1180 2534 1356 2535 1357 2535 1180 2535 1357 2536 1358 2536 1180 2536 1358 2537 1359 2537 1180 2537 1360 2538 1179 2538 1180 2538 1361 2539 1360 2539 1180 2539 1359 2540 1361 2540 1180 2540 1201 2541 1350 2541 1180 2541 1362 2542 1363 2542 1168 2542 1363 2543 1364 2543 1168 2543 1364 2544 1365 2544 1168 2544 1365 2545 1366 2545 1168 2545 1366 2546 1367 2546 1168 2546 1367 2547 1368 2547 1168 2547 1368 2548 1369 2548 1168 2548 1369 2549 1370 2549 1168 2549 1370 2550 1371 2550 1168 2550 1371 2551 1372 2551 1168 2551 1372 2552 1373 2552 1168 2552 1373 2553 1347 2553 1168 2553 1374 2554 1362 2554 1168 2554 1169 2555 1374 2555 1168 2555 1238 2556 1350 2556 1201 2556 1283 2557 1375 2557 1286 2557 1376 2558 1289 2558 1286 2558 1375 2559 1376 2559 1286 2559 1377 2560 1287 2560 1288 2560 1281 2561 1377 2561 1288 2561 1298 2562 1292 2562 1293 2562 1378 2563 1298 2563 1293 2563 1296 2564 1378 2564 1293 2564 1297 2565 1295 2565 1294 2565 1379 2566 1297 2566 1294 2566 1299 2567 1379 2567 1294 2567 1303 2568 1379 2568 1299 2568 1376 2569 1345 2569 1289 2569 1346 2570 1380 2570 1281 2570 1380 2571 1377 2571 1281 2571 1300 2572 1378 2572 1296 2572 1378 2573 1302 2573 1298 2573 1305 2574 1379 2574 1303 2574 1290 2575 1381 2575 903 2575 1381 2576 1382 2576 903 2576 1382 2577 904 2577 903 2577 1306 2578 1378 2578 1300 2578 1379 2579 1301 2579 1297 2579 1378 2580 1304 2580 1302 2580 1309 2581 1379 2581 1305 2581 1311 2582 1378 2582 1306 2582 1379 2583 1307 2583 1301 2583 1317 2584 1383 2584 1316 2584 1383 2585 1348 2585 1316 2585 1330 2586 1384 2586 1323 2586 1384 2587 1341 2587 1323 2587 1385 2588 1318 2588 1304 2588 1378 2589 1385 2589 1304 2589 1308 2590 1379 2590 1309 2590 1311 2591 1386 2591 1378 2591 1386 2592 1385 2592 1378 2592 1387 2593 1307 2593 1379 2593 1308 2594 1387 2594 1379 2594 990 2595 1337 2595 991 2595 1266 2596 1333 2596 1267 2596 1341 2597 1388 2597 1271 2597 1388 2598 1257 2598 1271 2598 1385 2599 1317 2599 1318 2599 1320 2600 1387 2600 1308 2600 1382 2601 1389 2601 904 2601 1389 2602 906 2602 904 2602 1321 2603 1386 2603 1311 2603 1387 2604 1390 2604 1307 2604 1390 2605 1312 2605 1307 2605 1385 2606 1383 2606 1317 2606 1324 2607 1387 2607 1320 2607 1238 2608 1351 2608 1350 2608 1391 2609 1211 2609 1347 2609 1373 2610 1391 2610 1347 2610 1340 2611 1392 2611 1330 2611 1392 2612 1384 2612 1330 2612 1393 2613 1238 2613 1210 2613 1394 2614 1393 2614 1210 2614 1207 2615 1394 2615 1210 2615 1211 2616 1395 2616 1209 2616 1395 2617 1396 2617 1209 2617 1396 2618 1208 2618 1209 2618 1396 2619 1397 2619 1208 2619 1397 2620 939 2620 1208 2620 1398 2621 1399 2621 1207 2621 948 2622 1398 2622 1207 2622 1399 2623 1394 2623 1207 2623 937 2624 1398 2624 948 2624 1397 2625 934 2625 939 2625 1393 2626 1351 2626 1238 2626 1391 2627 1395 2627 1211 2627 1385 2628 1348 2628 1383 2628 1349 2629 1387 2629 1324 2629 938 2630 1398 2630 937 2630 1400 2631 1398 2631 938 2631 933 2632 1400 2632 938 2632 1397 2633 1401 2633 934 2633 1401 2634 935 2634 934 2634 1284 2635 1392 2635 1340 2635 1401 2636 931 2636 935 2636 923 2637 1400 2637 933 2637 1401 2638 932 2638 931 2638 1402 2639 1400 2639 923 2639 922 2640 1402 2640 923 2640 921 2641 1402 2641 922 2641 989 2642 1403 2642 990 2642 1403 2643 1337 2643 990 2643 1325 2644 1386 2644 1321 2644 1390 2645 1322 2645 1312 2645 1389 2646 1404 2646 906 2646 1404 2647 905 2647 906 2647 1401 2648 1405 2648 932 2648 1405 2649 930 2649 932 2649 1406 2650 1407 2650 1290 2650 1348 2651 1406 2651 1290 2651 1407 2652 1408 2652 1290 2652 1408 2653 1381 2653 1290 2653 1409 2654 1349 2654 1327 2654 1337 2655 1409 2655 1327 2655 1405 2656 920 2656 930 2656 1405 2657 919 2657 920 2657 1410 2658 1402 2658 921 2658 918 2659 1410 2659 921 2659 914 2660 1410 2660 918 2660 1411 2661 1410 2661 914 2661 915 2662 1411 2662 914 2662 1405 2663 911 2663 919 2663 1412 2664 1339 2664 1333 2664 1266 2665 1412 2665 1333 2665 1384 2666 1413 2666 1341 2666 1413 2667 1388 2667 1341 2667 1414 2668 902 2668 905 2668 1404 2669 1415 2669 905 2669 1415 2670 1414 2670 905 2670 992 2671 1416 2671 989 2671 1416 2672 1403 2672 989 2672 1417 2673 1411 2673 915 2673 912 2674 1417 2674 915 2674 1418 2675 907 2675 911 2675 1419 2676 1418 2676 911 2676 1405 2677 1419 2677 911 2677 1415 2678 1420 2678 1414 2678 1420 2679 902 2679 1414 2679 910 2680 1421 2680 992 2680 1421 2681 1416 2681 992 2681 1422 2682 908 2682 907 2682 1418 2683 1422 2683 907 2683 913 2684 1417 2684 912 2684 1422 2685 909 2685 908 2685 1423 2686 1417 2686 913 2686 902 2687 1423 2687 913 2687 1422 2688 1424 2688 909 2688 1424 2689 1425 2689 909 2689 1425 2690 910 2690 909 2690 1420 2691 1423 2691 902 2691 1425 2692 1421 2692 910 2692 1426 2693 1427 2693 1325 2693 1427 2694 1386 2694 1325 2694 1328 2695 1426 2695 1325 2695 1390 2696 1428 2696 1322 2696 1428 2697 1326 2697 1322 2697 1331 2698 1426 2698 1328 2698 1428 2699 1329 2699 1326 2699 1335 2700 1426 2700 1331 2700 1428 2701 1332 2701 1329 2701 1429 2702 1343 2702 1339 2702 1412 2703 1429 2703 1339 2703 1392 2704 1430 2704 1384 2704 1430 2705 1413 2705 1384 2705 1385 2706 1406 2706 1348 2706 1409 2707 1387 2707 1349 2707 1344 2708 1426 2708 1335 2708 1428 2709 1336 2709 1332 2709 1431 2710 1282 2710 1342 2710 1343 2711 1431 2711 1342 2711 1432 2712 1433 2712 1284 2712 1285 2713 1432 2713 1284 2713 1430 2714 1392 2714 1284 2714 1433 2715 1430 2715 1284 2715 1434 2716 1431 2716 1343 2716 1429 2717 1434 2717 1343 2717 1408 2718 1435 2718 1381 2718 1435 2719 1382 2719 1381 2719 1393 2720 1352 2720 1351 2720 1436 2721 1437 2721 1282 2721 1437 2722 1438 2722 1282 2722 1438 2723 1283 2723 1282 2723 1431 2724 1436 2724 1282 2724 1287 2725 1439 2725 1285 2725 1440 2726 1432 2726 1285 2726 1439 2727 1440 2727 1285 2727 1345 2728 1441 2728 1344 2728 1441 2729 1426 2729 1344 2729 1428 2730 1346 2730 1336 2730 1438 2731 1375 2731 1283 2731 1377 2732 1439 2732 1287 2732 1376 2733 1441 2733 1345 2733 1442 2734 1380 2734 1346 2734 1428 2735 1442 2735 1346 2735 1438 2736 1376 2736 1375 2736 1380 2737 1442 2737 1377 2737 1442 2738 1439 2738 1377 2738 1372 2739 1391 2739 1373 2739 1443 2740 1385 2740 1386 2740 1427 2741 1443 2741 1386 2741 1443 2742 1407 2742 1385 2742 1407 2743 1406 2743 1385 2743 1438 2744 1441 2744 1376 2744 1403 2745 1444 2745 1337 2745 1444 2746 1409 2746 1337 2746 1435 2747 1445 2747 1382 2747 1445 2748 1389 2748 1382 2748 1446 2749 1418 2749 1419 2749 1405 2750 1446 2750 1419 2750 1396 2751 1447 2751 1397 2751 1447 2752 1401 2752 1397 2752 1448 2753 1424 2753 1422 2753 1418 2754 1448 2754 1422 2754 1393 2755 1353 2755 1352 2755 1449 2756 1408 2756 1407 2756 1443 2757 1449 2757 1407 2757 1444 2758 1450 2758 1409 2758 1450 2759 1387 2759 1409 2759 1416 2760 1451 2760 1403 2760 1451 2761 1444 2761 1403 2761 1445 2762 1452 2762 1389 2762 1452 2763 1404 2763 1389 2763 1453 2764 1446 2764 1405 2764 1454 2765 1453 2765 1405 2765 1401 2766 1454 2766 1405 2766 1396 2767 1455 2767 1447 2767 1455 2768 1401 2768 1447 2768 1396 2769 1456 2769 1455 2769 1456 2770 1401 2770 1455 2770 1457 2771 1399 2771 1398 2771 1400 2772 1457 2772 1398 2772 1458 2773 1399 2773 1457 2773 1400 2774 1458 2774 1457 2774 1458 2775 1459 2775 1399 2775 1459 2776 1460 2776 1399 2776 1460 2777 1394 2777 1399 2777 1461 2778 1456 2778 1396 2778 1395 2779 1462 2779 1396 2779 1462 2780 1463 2780 1396 2780 1463 2781 1461 2781 1396 2781 1460 2782 1393 2782 1394 2782 1391 2783 1462 2783 1395 2783 1464 2784 1393 2784 1460 2784 1459 2785 1464 2785 1460 2785 1391 2786 1463 2786 1462 2786 1456 2787 1465 2787 1401 2787 1465 2788 1454 2788 1401 2788 1466 2789 1459 2789 1458 2789 1400 2790 1466 2790 1458 2790 1417 2791 1467 2791 1411 2791 1467 2792 1410 2792 1411 2792 1453 2793 1418 2793 1446 2793 1468 2794 1418 2794 1453 2794 1469 2795 1468 2795 1453 2795 1454 2796 1469 2796 1453 2796 1470 2797 1471 2797 1400 2797 1402 2798 1470 2798 1400 2798 1471 2799 1466 2799 1400 2799 1417 2800 1472 2800 1467 2800 1472 2801 1473 2801 1467 2801 1473 2802 1474 2802 1467 2802 1474 2803 1475 2803 1467 2803 1475 2804 1410 2804 1467 2804 1452 2805 1476 2805 1404 2805 1476 2806 1415 2806 1404 2806 1468 2807 1448 2807 1418 2807 1477 2808 1470 2808 1402 2808 1478 2809 1477 2809 1402 2809 1410 2810 1478 2810 1402 2810 1421 2811 1479 2811 1416 2811 1479 2812 1451 2812 1416 2812 1475 2813 1480 2813 1410 2813 1480 2814 1478 2814 1410 2814 1481 2815 1424 2815 1448 2815 1468 2816 1481 2816 1448 2816 1423 2817 1472 2817 1417 2817 1476 2818 1482 2818 1415 2818 1482 2819 1420 2819 1415 2819 1425 2820 1483 2820 1421 2820 1483 2821 1479 2821 1421 2821 1482 2822 1423 2822 1420 2822 1484 2823 1483 2823 1425 2823 1424 2824 1484 2824 1425 2824 1485 2825 1354 2825 1393 2825 1354 2826 1353 2826 1393 2826 1464 2827 1485 2827 1393 2827 1372 2828 1486 2828 1391 2828 1486 2829 1487 2829 1391 2829 1487 2830 1463 2830 1391 2830 1371 2831 1486 2831 1372 2831 1472 2832 1488 2832 1473 2832 1488 2833 1474 2833 1473 2833 1370 2834 1486 2834 1371 2834 1423 2835 1489 2835 1472 2835 1489 2836 1488 2836 1472 2836 1449 2837 1435 2837 1408 2837 1490 2838 1468 2838 1469 2838 1454 2839 1490 2839 1469 2839 1485 2840 1355 2840 1354 2840 1491 2841 1468 2841 1490 2841 1492 2842 1491 2842 1490 2842 1454 2843 1493 2843 1490 2843 1493 2844 1492 2844 1490 2844 1491 2845 1481 2845 1468 2845 1465 2846 1493 2846 1454 2846 1494 2847 1424 2847 1481 2847 1491 2848 1494 2848 1481 2848 1495 2849 1459 2849 1466 2849 1471 2850 1495 2850 1466 2850 1461 2851 1496 2851 1456 2851 1497 2852 1465 2852 1456 2852 1496 2853 1497 2853 1456 2853 1461 2854 1498 2854 1496 2854 1498 2855 1497 2855 1496 2855 1499 2856 1485 2856 1464 2856 1500 2857 1499 2857 1464 2857 1459 2858 1500 2858 1464 2858 1487 2859 1461 2859 1463 2859 1501 2860 1498 2860 1461 2860 1487 2861 1501 2861 1461 2861 1495 2862 1500 2862 1459 2862 1497 2863 1493 2863 1465 2863 1502 2864 1450 2864 1444 2864 1451 2865 1502 2865 1444 2865 1503 2866 1445 2866 1435 2866 1449 2867 1503 2867 1435 2867 1504 2868 1491 2868 1492 2868 1493 2869 1504 2869 1492 2869 1505 2870 1491 2870 1504 2870 1493 2871 1505 2871 1504 2871 1505 2872 1494 2872 1491 2872 1369 2873 1506 2873 1370 2873 1506 2874 1486 2874 1370 2874 1507 2875 1424 2875 1494 2875 1505 2876 1507 2876 1494 2876 1437 2877 1441 2877 1438 2877 1442 2878 1508 2878 1439 2878 1508 2879 1440 2879 1439 2879 1509 2880 1502 2880 1451 2880 1479 2881 1509 2881 1451 2881 1503 2882 1452 2882 1445 2882 1501 2883 1510 2883 1498 2883 1510 2884 1497 2884 1498 2884 1511 2885 1505 2885 1493 2885 1512 2886 1513 2886 1493 2886 1513 2887 1514 2887 1493 2887 1514 2888 1511 2888 1493 2888 1497 2889 1512 2889 1493 2889 1515 2890 1507 2890 1505 2890 1511 2891 1515 2891 1505 2891 1516 2892 1517 2892 1495 2892 1517 2893 1500 2893 1495 2893 1471 2894 1516 2894 1495 2894 1501 2895 1518 2895 1510 2895 1518 2896 1497 2896 1510 2896 1519 2897 1485 2897 1499 2897 1500 2898 1519 2898 1499 2898 1501 2899 1520 2899 1518 2899 1520 2900 1521 2900 1518 2900 1521 2901 1522 2901 1518 2901 1522 2902 1497 2902 1518 2902 1486 2903 1523 2903 1487 2903 1523 2904 1520 2904 1487 2904 1520 2905 1501 2905 1487 2905 1522 2906 1524 2906 1497 2906 1524 2907 1512 2907 1497 2907 1517 2908 1519 2908 1500 2908 1525 2909 1507 2909 1515 2909 1526 2910 1525 2910 1515 2910 1511 2911 1526 2911 1515 2911 1489 2912 1527 2912 1488 2912 1528 2913 1474 2913 1488 2913 1527 2914 1528 2914 1488 2914 1528 2915 1475 2915 1474 2915 1423 2916 1527 2916 1489 2916 1525 2917 1424 2917 1507 2917 1528 2918 1480 2918 1475 2918 1514 2919 1529 2919 1511 2919 1529 2920 1526 2920 1511 2920 1503 2921 1530 2921 1452 2921 1530 2922 1476 2922 1452 2922 1483 2923 1509 2923 1479 2923 1482 2924 1527 2924 1423 2924 1525 2925 1484 2925 1424 2925 1513 2926 1529 2926 1514 2926 1528 2927 1531 2927 1480 2927 1531 2928 1478 2928 1480 2928 1512 2929 1529 2929 1513 2929 1485 2930 1532 2930 1355 2930 1532 2931 1356 2931 1355 2931 1368 2932 1506 2932 1369 2932 1530 2933 1482 2933 1476 2933 1531 2934 1477 2934 1478 2934 1525 2935 1509 2935 1483 2935 1484 2936 1525 2936 1483 2936 1530 2937 1527 2937 1482 2937 1531 2938 1470 2938 1477 2938 1531 2939 1471 2939 1470 2939 1524 2940 1529 2940 1512 2940 1533 2941 1426 2941 1441 2941 1437 2942 1533 2942 1441 2942 1534 2943 1508 2943 1442 2943 1428 2944 1534 2944 1442 2944 1522 2945 1529 2945 1524 2945 1535 2946 1516 2946 1471 2946 1531 2947 1535 2947 1471 2947 1521 2948 1536 2948 1522 2948 1536 2949 1529 2949 1522 2949 1265 2950 1412 2950 1266 2950 1388 2951 1537 2951 1257 2951 1537 2952 1258 2952 1257 2952 1535 2953 1517 2953 1516 2953 1520 2954 1536 2954 1521 2954 1523 2955 1536 2955 1520 2955 1535 2956 1519 2956 1517 2956 1535 2957 1485 2957 1519 2957 1486 2958 1536 2958 1523 2958 1538 2959 1539 2959 1426 2959 1539 2960 1427 2960 1426 2960 1533 2961 1538 2961 1426 2961 1390 2962 1534 2962 1428 2962 1532 2963 1540 2963 1356 2963 1540 2964 1357 2964 1356 2964 1541 2965 1532 2965 1485 2965 1535 2966 1541 2966 1485 2966 1506 2967 1542 2967 1486 2967 1542 2968 1543 2968 1486 2968 1543 2969 1536 2969 1486 2969 1367 2970 1544 2970 1368 2970 1544 2971 1506 2971 1368 2971 1545 2972 1540 2972 1532 2972 1541 2973 1545 2973 1532 2973 1544 2974 1542 2974 1506 2974 1545 2975 1546 2975 1540 2975 1546 2976 1357 2976 1540 2976 1547 2977 1542 2977 1544 2977 1367 2978 1547 2978 1544 2978 1366 2979 1547 2979 1367 2979 1548 2980 1429 2980 1412 2980 1265 2981 1548 2981 1412 2981 1413 2982 1549 2982 1388 2982 1549 2983 1537 2983 1388 2983 1546 2984 1358 2984 1357 2984 1365 2985 1547 2985 1366 2985 1550 2986 1443 2986 1427 2986 1539 2987 1550 2987 1427 2987 1387 2988 1551 2988 1390 2988 1551 2989 1534 2989 1390 2989 1546 2990 1552 2990 1358 2990 1552 2991 1359 2991 1358 2991 1545 2992 1552 2992 1546 2992 1553 2993 1542 2993 1547 2993 1365 2994 1553 2994 1547 2994 1364 2995 1553 2995 1365 2995 1550 2996 1503 2996 1443 2996 1503 2997 1449 2997 1443 2997 1554 2998 1551 2998 1387 2998 1450 2999 1554 2999 1387 2999 1545 3000 1361 3000 1552 3000 1361 3001 1359 3001 1552 3001 1363 3002 1542 3002 1553 3002 1364 3003 1363 3003 1553 3003 1502 3004 1554 3004 1450 3004 1545 3005 1360 3005 1361 3005 1362 3006 1542 3006 1363 3006 1555 3007 1434 3007 1429 3007 1548 3008 1555 3008 1429 3008 1430 3009 1556 3009 1413 3009 1556 3010 1549 3010 1413 3010 1557 3011 1431 3011 1434 3011 1558 3012 1557 3012 1434 3012 1555 3013 1558 3013 1434 3013 1433 3014 1556 3014 1430 3014 1436 3015 1533 3015 1437 3015 1508 3016 1432 3016 1440 3016 1526 3017 1509 3017 1525 3017 1559 3018 1528 3018 1527 3018 1530 3019 1559 3019 1527 3019 1560 3020 1538 3020 1533 3020 1436 3021 1560 3021 1533 3021 1561 3022 1432 3022 1508 3022 1562 3023 1561 3023 1508 3023 1534 3024 1562 3024 1508 3024 1563 3025 1550 3025 1539 3025 1538 3026 1563 3026 1539 3026 1554 3027 1564 3027 1551 3027 1564 3028 1534 3028 1551 3028 1565 3029 1566 3029 1538 3029 1566 3030 1563 3030 1538 3030 1560 3031 1565 3031 1538 3031 1564 3032 1562 3032 1534 3032 1567 3033 1509 3033 1526 3033 1529 3034 1567 3034 1526 3034 1559 3035 1568 3035 1528 3035 1568 3036 1531 3036 1528 3036 1569 3037 1529 3037 1536 3037 1543 3038 1569 3038 1536 3038 1531 3039 1541 3039 1535 3039 1264 3040 1548 3040 1265 3040 1537 3041 1570 3041 1258 3041 1570 3042 1259 3042 1258 3042 1569 3043 1567 3043 1529 3043 1568 3044 1541 3044 1531 3044 1545 3045 1571 3045 1360 3045 1571 3046 1179 3046 1360 3046 1374 3047 1542 3047 1362 3047 1572 3048 1573 3048 1545 3048 1573 3049 1571 3049 1545 3049 1541 3050 1572 3050 1545 3050 1374 3051 1574 3051 1542 3051 1574 3052 1575 3052 1542 3052 1575 3053 1543 3053 1542 3053 1576 3054 1550 3054 1563 3054 1566 3055 1576 3055 1563 3055 1554 3056 1577 3056 1564 3056 1577 3057 1562 3057 1564 3057 1576 3058 1578 3058 1550 3058 1578 3059 1503 3059 1550 3059 1579 3060 1577 3060 1554 3060 1502 3061 1579 3061 1554 3061 1573 3062 1179 3062 1571 3062 1169 3063 1580 3063 1374 3063 1580 3064 1574 3064 1374 3064 1573 3065 1581 3065 1179 3065 1581 3066 1178 3066 1179 3066 1170 3067 1580 3067 1169 3067 1578 3068 1582 3068 1503 3068 1582 3069 1530 3069 1503 3069 1509 3070 1583 3070 1502 3070 1583 3071 1579 3071 1502 3071 1584 3072 1555 3072 1548 3072 1264 3073 1584 3073 1548 3073 1549 3074 1585 3074 1537 3074 1585 3075 1570 3075 1537 3075 1586 3076 1558 3076 1555 3076 1584 3077 1586 3077 1555 3077 1556 3078 1587 3078 1549 3078 1587 3079 1585 3079 1549 3079 1557 3080 1436 3080 1431 3080 1432 3081 1588 3081 1433 3081 1588 3082 1556 3082 1433 3082 1589 3083 1436 3083 1557 3083 1590 3084 1591 3084 1557 3084 1591 3085 1592 3085 1557 3085 1592 3086 1589 3086 1557 3086 1593 3087 1590 3087 1557 3087 1558 3088 1593 3088 1557 3088 1432 3089 1594 3089 1588 3089 1594 3090 1595 3090 1588 3090 1595 3091 1596 3091 1588 3091 1596 3092 1587 3092 1588 3092 1587 3093 1556 3093 1588 3093 1586 3094 1593 3094 1558 3094 1589 3095 1560 3095 1436 3095 1561 3096 1594 3096 1432 3096 1592 3097 1560 3097 1589 3097 1597 3098 1598 3098 1594 3098 1561 3099 1597 3099 1594 3099 1598 3100 1595 3100 1594 3100 1582 3101 1559 3101 1530 3101 1567 3102 1599 3102 1509 3102 1599 3103 1583 3103 1509 3103 1592 3104 1600 3104 1560 3104 1600 3105 1565 3105 1560 3105 1601 3106 1597 3106 1561 3106 1562 3107 1601 3107 1561 3107 1602 3108 1603 3108 1565 3108 1603 3109 1566 3109 1565 3109 1600 3110 1602 3110 1565 3110 1577 3111 1601 3111 1562 3111 1572 3112 1581 3112 1573 3112 1170 3113 1604 3113 1580 3113 1605 3114 1574 3114 1580 3114 1604 3115 1605 3115 1580 3115 1606 3116 1581 3116 1572 3116 1541 3117 1607 3117 1572 3117 1607 3118 1606 3118 1572 3118 1605 3119 1608 3119 1574 3119 1608 3120 1575 3120 1574 3120 1609 3121 1576 3121 1566 3121 1603 3122 1609 3122 1566 3122 1579 3123 1610 3123 1577 3123 1610 3124 1601 3124 1577 3124 1568 3125 1607 3125 1541 3125 1575 3126 1569 3126 1543 3126 1609 3127 1611 3127 1576 3127 1611 3128 1578 3128 1576 3128 1612 3129 1610 3129 1579 3129 1583 3130 1612 3130 1579 3130 1263 3131 1584 3131 1264 3131 1570 3132 1613 3132 1259 3132 1613 3133 1260 3133 1259 3133 1611 3134 1614 3134 1578 3134 1614 3135 1582 3135 1578 3135 1599 3136 1615 3136 1583 3136 1615 3137 1616 3137 1583 3137 1616 3138 1612 3138 1583 3138 1617 3139 1586 3139 1584 3139 1263 3140 1617 3140 1584 3140 1585 3141 1618 3141 1570 3141 1618 3142 1613 3142 1570 3142 1567 3143 1619 3143 1599 3143 1619 3144 1615 3144 1599 3144 1614 3145 1559 3145 1582 3145 1569 3146 1619 3146 1567 3146 1614 3147 1620 3147 1559 3147 1620 3148 1621 3148 1559 3148 1621 3149 1568 3149 1559 3149 1622 3150 1593 3150 1586 3150 1617 3151 1622 3151 1586 3151 1587 3152 1596 3152 1585 3152 1596 3153 1618 3153 1585 3153 1623 3154 1590 3154 1593 3154 1622 3155 1623 3155 1593 3155 1608 3156 1569 3156 1575 3156 1624 3157 1606 3157 1607 3157 1568 3158 1624 3158 1607 3158 1608 3159 1625 3159 1569 3159 1625 3160 1619 3160 1569 3160 1621 3161 1624 3161 1568 3161 1591 3162 1600 3162 1592 3162 1597 3163 1626 3163 1598 3163 1626 3164 1627 3164 1598 3164 1627 3165 1595 3165 1598 3165 1591 3166 1628 3166 1600 3166 1628 3167 1602 3167 1600 3167 1629 3168 1626 3168 1597 3168 1601 3169 1629 3169 1597 3169 1606 3170 1630 3170 1581 3170 1630 3171 1178 3171 1581 3171 1170 3172 1631 3172 1604 3172 1631 3173 1605 3173 1604 3173 1632 3174 1609 3174 1603 3174 1633 3175 1632 3175 1603 3175 1602 3176 1633 3176 1603 3176 1612 3177 1634 3177 1610 3177 1629 3178 1601 3178 1610 3178 1634 3179 1629 3179 1610 3179 1635 3180 1633 3180 1602 3180 1628 3181 1635 3181 1602 3181 1636 3182 1630 3182 1606 3182 1624 3183 1637 3183 1606 3183 1637 3184 1636 3184 1606 3184 1631 3185 1638 3185 1605 3185 1638 3186 1639 3186 1605 3186 1639 3187 1640 3187 1605 3187 1640 3188 1608 3188 1605 3188 1632 3189 1641 3189 1609 3189 1641 3190 1611 3190 1609 3190 1642 3191 1634 3191 1612 3191 1616 3192 1642 3192 1612 3192 1641 3193 1643 3193 1611 3193 1643 3194 1614 3194 1611 3194 1615 3195 1644 3195 1616 3195 1644 3196 1645 3196 1616 3196 1645 3197 1642 3197 1616 3197 1262 3198 1617 3198 1263 3198 1613 3199 1646 3199 1260 3199 1646 3200 1272 3200 1260 3200 1647 3201 1622 3201 1617 3201 1262 3202 1647 3202 1617 3202 1618 3203 1648 3203 1613 3203 1648 3204 1646 3204 1613 3204 1636 3205 1649 3205 1630 3205 1649 3206 1178 3206 1630 3206 1170 3207 1650 3207 1631 3207 1650 3208 1638 3208 1631 3208 1649 3209 1651 3209 1178 3209 1651 3210 1177 3210 1178 3210 1171 3211 1650 3211 1170 3211 1652 3212 1623 3212 1622 3212 1647 3213 1652 3213 1622 3213 1596 3214 1653 3214 1618 3214 1653 3215 1648 3215 1618 3215 1654 3216 1628 3216 1591 3216 1590 3217 1654 3217 1591 3217 1626 3218 1655 3218 1627 3218 1655 3219 1595 3219 1627 3219 1656 3220 1654 3220 1590 3220 1623 3221 1656 3221 1590 3221 1655 3222 1657 3222 1595 3222 1657 3223 1653 3223 1595 3223 1653 3224 1596 3224 1595 3224 1658 3225 1656 3225 1623 3225 1652 3226 1658 3226 1623 3226 1659 3227 1654 3227 1656 3227 1658 3228 1659 3228 1656 3228 1660 3229 1661 3229 1657 3229 1655 3230 1660 3230 1657 3230 1661 3231 1662 3231 1657 3231 1662 3232 1653 3232 1657 3232 1663 3233 1628 3233 1654 3233 1664 3234 1663 3234 1654 3234 1659 3235 1665 3235 1654 3235 1665 3236 1664 3236 1654 3236 1666 3237 1667 3237 1655 3237 1626 3238 1666 3238 1655 3238 1667 3239 1660 3239 1655 3239 1668 3240 1632 3240 1633 3240 1669 3241 1668 3241 1633 3241 1635 3242 1669 3242 1633 3242 1642 3243 1670 3243 1634 3243 1671 3244 1629 3244 1634 3244 1670 3245 1671 3245 1634 3245 1636 3246 1651 3246 1649 3246 1171 3247 1672 3247 1650 3247 1673 3248 1638 3248 1650 3248 1672 3249 1673 3249 1650 3249 1674 3250 1651 3250 1636 3250 1637 3251 1675 3251 1636 3251 1675 3252 1674 3252 1636 3252 1673 3253 1676 3253 1638 3253 1676 3254 1639 3254 1638 3254 1668 3255 1677 3255 1632 3255 1677 3256 1641 3256 1632 3256 1678 3257 1670 3257 1642 3257 1645 3258 1678 3258 1642 3258 1663 3259 1635 3259 1628 3259 1671 3260 1666 3260 1626 3260 1629 3261 1671 3261 1626 3261 1679 3262 1669 3262 1635 3262 1663 3263 1679 3263 1635 3263 1677 3264 1680 3264 1641 3264 1680 3265 1681 3265 1641 3265 1681 3266 1643 3266 1641 3266 1644 3267 1682 3267 1645 3267 1682 3268 1683 3268 1645 3268 1683 3269 1678 3269 1645 3269 1619 3270 1644 3270 1615 3270 1619 3271 1684 3271 1644 3271 1684 3272 1682 3272 1644 3272 1643 3273 1620 3273 1614 3273 1681 3274 1620 3274 1643 3274 1261 3275 1647 3275 1262 3275 1646 3276 1685 3276 1272 3276 1685 3277 1273 3277 1272 3277 1625 3278 1684 3278 1619 3278 1681 3279 1686 3279 1620 3279 1686 3280 1687 3280 1620 3280 1687 3281 1621 3281 1620 3281 1640 3282 1625 3282 1608 3282 1639 3283 1688 3283 1640 3283 1688 3284 1625 3284 1640 3284 1621 3285 1637 3285 1624 3285 1621 3286 1687 3286 1637 3286 1687 3287 1675 3287 1637 3287 1688 3288 1684 3288 1625 3288 1261 3289 1689 3289 1647 3289 1689 3290 1652 3290 1647 3290 1648 3291 1690 3291 1646 3291 1690 3292 1685 3292 1646 3292 1691 3293 1663 3293 1664 3293 1665 3294 1691 3294 1664 3294 1692 3295 1693 3295 1667 3295 1666 3296 1692 3296 1667 3296 1693 3297 1660 3297 1667 3297 1689 3298 1694 3298 1652 3298 1694 3299 1658 3299 1652 3299 1653 3300 1662 3300 1648 3300 1662 3301 1690 3301 1648 3301 1695 3302 1668 3302 1669 3302 1679 3303 1695 3303 1669 3303 1678 3304 1696 3304 1670 3304 1696 3305 1671 3305 1670 3305 1674 3306 1697 3306 1651 3306 1697 3307 1177 3307 1651 3307 1171 3308 1698 3308 1672 3308 1698 3309 1673 3309 1672 3309 1695 3310 1699 3310 1668 3310 1699 3311 1700 3311 1668 3311 1700 3312 1677 3312 1668 3312 1701 3313 1702 3313 1678 3313 1702 3314 1696 3314 1678 3314 1683 3315 1701 3315 1678 3315 1703 3316 1704 3316 1674 3316 1704 3317 1705 3317 1674 3317 1705 3318 1706 3318 1674 3318 1706 3319 1697 3319 1674 3319 1707 3320 1703 3320 1674 3320 1675 3321 1708 3321 1674 3321 1708 3322 1707 3322 1674 3322 1698 3323 1709 3323 1673 3323 1709 3324 1710 3324 1673 3324 1710 3325 1711 3325 1673 3325 1711 3326 1712 3326 1673 3326 1712 3327 1676 3327 1673 3327 1713 3328 1659 3328 1658 3328 1694 3329 1713 3329 1658 3329 1691 3330 1714 3330 1663 3330 1714 3331 1679 3331 1663 3331 1715 3332 1692 3332 1666 3332 1671 3333 1715 3333 1666 3333 1700 3334 1716 3334 1677 3334 1716 3335 1717 3335 1677 3335 1717 3336 1680 3336 1677 3336 1718 3337 1719 3337 1683 3337 1719 3338 1720 3338 1683 3338 1720 3339 1721 3339 1683 3339 1682 3340 1722 3340 1683 3340 1722 3341 1718 3341 1683 3341 1721 3342 1701 3342 1683 3342 1723 3343 1699 3343 1695 3343 1679 3344 1723 3344 1695 3344 1715 3345 1671 3345 1696 3345 1702 3346 1715 3346 1696 3346 1724 3347 1723 3347 1679 3347 1714 3348 1724 3348 1679 3348 1279 3349 1689 3349 1261 3349 1685 3350 1725 3350 1273 3350 1725 3351 1274 3351 1273 3351 1726 3352 1689 3352 1279 3352 1278 3353 1726 3353 1279 3353 1725 3354 1727 3354 1274 3354 1727 3355 1275 3355 1274 3355 1728 3356 1726 3356 1278 3356 1277 3357 1728 3357 1278 3357 1727 3358 1729 3358 1275 3358 1729 3359 1276 3359 1275 3359 1729 3360 1730 3360 1277 3360 1276 3361 1729 3361 1277 3361 1730 3362 1728 3362 1277 3362 1726 3363 1694 3363 1689 3363 1690 3364 1731 3364 1685 3364 1731 3365 1725 3365 1685 3365 1732 3366 1714 3366 1691 3366 1733 3367 1732 3367 1691 3367 1665 3368 1733 3368 1691 3368 1734 3369 1735 3369 1693 3369 1736 3370 1734 3370 1693 3370 1692 3371 1736 3371 1693 3371 1735 3372 1660 3372 1693 3372 1737 3373 1694 3373 1726 3373 1728 3374 1737 3374 1726 3374 1738 3375 1177 3375 1697 3375 1706 3376 1738 3376 1697 3376 1171 3377 1739 3377 1698 3377 1739 3378 1709 3378 1698 3378 1740 3379 1177 3379 1738 3379 1706 3380 1740 3380 1738 3380 1171 3381 1741 3381 1739 3381 1741 3382 1709 3382 1739 3382 1684 3383 1722 3383 1682 3383 1680 3384 1686 3384 1681 3384 1705 3385 1740 3385 1706 3385 1741 3386 1710 3386 1709 3386 1742 3387 1177 3387 1740 3387 1705 3388 1742 3388 1740 3388 1171 3389 1743 3389 1741 3389 1743 3390 1710 3390 1741 3390 1744 3391 1742 3391 1705 3391 1704 3392 1744 3392 1705 3392 1743 3393 1711 3393 1710 3393 1731 3394 1745 3394 1725 3394 1745 3395 1727 3395 1725 3395 1746 3396 1699 3396 1723 3396 1747 3397 1746 3397 1723 3397 1724 3398 1748 3398 1723 3398 1748 3399 1747 3399 1723 3399 1701 3400 1749 3400 1702 3400 1750 3401 1715 3401 1702 3401 1749 3402 1750 3402 1702 3402 1744 3403 1177 3403 1742 3403 1751 3404 1737 3404 1728 3404 1730 3405 1751 3405 1728 3405 1171 3406 1752 3406 1743 3406 1752 3407 1711 3407 1743 3407 1753 3408 1754 3408 1699 3408 1746 3409 1755 3409 1699 3409 1755 3410 1756 3410 1699 3410 1756 3411 1757 3411 1699 3411 1757 3412 1753 3412 1699 3412 1754 3413 1758 3413 1699 3413 1758 3414 1700 3414 1699 3414 1759 3415 1760 3415 1701 3415 1760 3416 1749 3416 1701 3416 1721 3417 1759 3417 1701 3417 1761 3418 1177 3418 1744 3418 1704 3419 1761 3419 1744 3419 1737 3420 1713 3420 1694 3420 1662 3421 1762 3421 1690 3421 1762 3422 1731 3422 1690 3422 1745 3423 1763 3423 1727 3423 1763 3424 1729 3424 1727 3424 1764 3425 1761 3425 1704 3425 1703 3426 1764 3426 1704 3426 1752 3427 1712 3427 1711 3427 1763 3428 1765 3428 1730 3428 1729 3429 1763 3429 1730 3429 1765 3430 1751 3430 1730 3430 1766 3431 1767 3431 1684 3431 1767 3432 1722 3432 1684 3432 1688 3433 1766 3433 1684 3433 1680 3434 1768 3434 1686 3434 1768 3435 1769 3435 1686 3435 1769 3436 1687 3436 1686 3436 1770 3437 1771 3437 1714 3437 1732 3438 1770 3438 1714 3438 1771 3439 1724 3439 1714 3439 1772 3440 1773 3440 1692 3440 1773 3441 1736 3441 1692 3441 1715 3442 1772 3442 1692 3442 1758 3443 1716 3443 1700 3443 1720 3444 1774 3444 1721 3444 1774 3445 1759 3445 1721 3445 1775 3446 1776 3446 1703 3446 1707 3447 1775 3447 1703 3447 1776 3448 1764 3448 1703 3448 1777 3449 1676 3449 1712 3449 1778 3450 1777 3450 1712 3450 1752 3451 1779 3451 1712 3451 1779 3452 1778 3452 1712 3452 1764 3453 1177 3453 1761 3453 1171 3454 1779 3454 1752 3454 1780 3455 1781 3455 1659 3455 1781 3456 1665 3456 1659 3456 1782 3457 1780 3457 1659 3457 1713 3458 1782 3458 1659 3458 1660 3459 1783 3459 1661 3459 1762 3460 1662 3460 1661 3460 1783 3461 1762 3461 1661 3461 1737 3462 1782 3462 1713 3462 1784 3463 1785 3463 1724 3463 1785 3464 1786 3464 1724 3464 1786 3465 1787 3465 1724 3465 1787 3466 1748 3466 1724 3466 1771 3467 1784 3467 1724 3467 1788 3468 1772 3468 1715 3468 1750 3469 1789 3469 1715 3469 1789 3470 1790 3470 1715 3470 1790 3471 1788 3471 1715 3471 1171 3472 1778 3472 1779 3472 1176 3473 1177 3473 1764 3473 1776 3474 1176 3474 1764 3474 1172 3475 1778 3475 1171 3475 1791 3476 1782 3476 1737 3476 1751 3477 1791 3477 1737 3477 1781 3478 1792 3478 1665 3478 1792 3479 1733 3479 1665 3479 1793 3480 1783 3480 1660 3480 1735 3481 1793 3481 1660 3481 1775 3482 1176 3482 1776 3482 1172 3483 1794 3483 1778 3483 1794 3484 1777 3484 1778 3484 1676 3485 1688 3485 1639 3485 1687 3486 1708 3486 1675 3486 1676 3487 1795 3487 1688 3487 1795 3488 1766 3488 1688 3488 1769 3489 1796 3489 1687 3489 1796 3490 1708 3490 1687 3490 1762 3491 1797 3491 1731 3491 1797 3492 1745 3492 1731 3492 1798 3493 1176 3493 1775 3493 1707 3494 1798 3494 1775 3494 1799 3495 1732 3495 1733 3495 1792 3496 1799 3496 1733 3496 1800 3497 1793 3497 1735 3497 1801 3498 1800 3498 1735 3498 1734 3499 1801 3499 1735 3499 1802 3500 1791 3500 1751 3500 1765 3501 1802 3501 1751 3501 1799 3502 1803 3502 1732 3502 1803 3503 1770 3503 1732 3503 1736 3504 1801 3504 1734 3504 1791 3505 1780 3505 1782 3505 1797 3506 1804 3506 1745 3506 1804 3507 1805 3507 1745 3507 1805 3508 1763 3508 1745 3508 1805 3509 1806 3509 1765 3509 1763 3510 1805 3510 1765 3510 1806 3511 1802 3511 1765 3511 1807 3512 1808 3512 1722 3512 1767 3513 1807 3513 1722 3513 1808 3514 1718 3514 1722 3514 1809 3515 1768 3515 1680 3515 1717 3516 1810 3516 1680 3516 1810 3517 1811 3517 1680 3517 1811 3518 1809 3518 1680 3518 1783 3519 1797 3519 1762 3519 1783 3520 1804 3520 1797 3520 1802 3521 1780 3521 1791 3521 1793 3522 1812 3522 1783 3522 1812 3523 1804 3523 1783 3523 1813 3524 1781 3524 1780 3524 1802 3525 1813 3525 1780 3525 1806 3526 1813 3526 1802 3526 1172 3527 1814 3527 1794 3527 1814 3528 1815 3528 1794 3528 1815 3529 1777 3529 1794 3529 1812 3530 1805 3530 1804 3530 1816 3531 1176 3531 1798 3531 1707 3532 1816 3532 1798 3532 1803 3533 1771 3533 1770 3533 1817 3534 1801 3534 1736 3534 1773 3535 1817 3535 1736 3535 1792 3536 1818 3536 1799 3536 1818 3537 1819 3537 1799 3537 1819 3538 1803 3538 1799 3538 1820 3539 1800 3539 1801 3539 1817 3540 1820 3540 1801 3540 1812 3541 1781 3541 1813 3541 1806 3542 1812 3542 1813 3542 1793 3543 1781 3543 1812 3543 1806 3542 1805 3542 1812 3542 1821 3544 1176 3544 1816 3544 1822 3545 1821 3545 1816 3545 1707 3546 1822 3546 1816 3546 1172 3547 1823 3547 1814 3547 1823 3548 1815 3548 1814 3548 1793 3549 1792 3549 1781 3549 1800 3550 1818 3550 1793 3550 1818 3551 1792 3551 1793 3551 1803 3552 1824 3552 1771 3552 1824 3553 1784 3553 1771 3553 1772 3554 1825 3554 1773 3554 1825 3555 1817 3555 1773 3555 1172 3556 1826 3556 1823 3556 1826 3557 1815 3557 1823 3557 1824 3558 1827 3558 1784 3558 1827 3559 1785 3559 1784 3559 1788 3560 1825 3560 1772 3560 1820 3561 1818 3561 1800 3561 1820 3562 1819 3562 1818 3562 1828 3563 1819 3563 1820 3563 1817 3564 1828 3564 1820 3564 1829 3565 1830 3565 1749 3565 1760 3566 1829 3566 1749 3566 1831 3567 1750 3567 1749 3567 1830 3568 1831 3568 1749 3568 1832 3569 1176 3569 1821 3569 1822 3570 1832 3570 1821 3570 1777 3571 1833 3571 1676 3571 1833 3572 1795 3572 1676 3572 1796 3573 1707 3573 1708 3573 1819 3574 1834 3574 1803 3574 1834 3575 1824 3575 1803 3575 1825 3576 1828 3576 1817 3576 1827 3577 1835 3577 1785 3577 1835 3578 1786 3578 1785 3578 1836 3579 1825 3579 1788 3579 1790 3580 1836 3580 1788 3580 1837 3581 1838 3581 1760 3581 1838 3582 1839 3582 1760 3582 1839 3583 1840 3583 1760 3583 1840 3584 1841 3584 1760 3584 1759 3585 1842 3585 1760 3585 1842 3586 1837 3586 1760 3586 1841 3587 1829 3587 1760 3587 1172 3588 1843 3588 1826 3588 1844 3589 1815 3589 1826 3589 1843 3590 1844 3590 1826 3590 1754 3591 1845 3591 1758 3591 1846 3592 1716 3592 1758 3592 1845 3593 1846 3593 1758 3593 1847 3594 1842 3594 1759 3594 1774 3595 1847 3595 1759 3595 1835 3596 1848 3596 1786 3596 1848 3597 1787 3597 1786 3597 1849 3598 1836 3598 1790 3598 1789 3599 1849 3599 1790 3599 1828 3600 1834 3600 1819 3600 1850 3601 1834 3601 1828 3601 1825 3602 1850 3602 1828 3602 1847 3603 1837 3603 1842 3603 1848 3604 1851 3604 1787 3604 1851 3605 1748 3605 1787 3605 1852 3606 1849 3606 1789 3606 1750 3607 1852 3607 1789 3607 1851 3608 1853 3608 1748 3608 1853 3609 1747 3609 1748 3609 1854 3610 1852 3610 1750 3610 1831 3611 1854 3611 1750 3611 1753 3612 1855 3612 1754 3612 1855 3613 1845 3613 1754 3613 1847 3614 1856 3614 1837 3614 1856 3615 1857 3615 1837 3615 1857 3616 1838 3616 1837 3616 1834 3617 1858 3617 1824 3617 1858 3618 1827 3618 1824 3618 1836 3619 1850 3619 1825 3619 1720 3620 1859 3620 1774 3620 1859 3621 1847 3621 1774 3621 1853 3622 1860 3622 1747 3622 1860 3623 1746 3623 1747 3623 1861 3624 1854 3624 1831 3624 1830 3625 1861 3625 1831 3625 1850 3626 1858 3626 1834 3626 1862 3627 1858 3627 1850 3627 1836 3628 1862 3628 1850 3628 1863 3629 1176 3629 1832 3629 1864 3630 1863 3630 1832 3630 1822 3631 1864 3631 1832 3631 1172 3632 1865 3632 1843 3632 1865 3633 1844 3633 1843 3633 1858 3634 1866 3634 1827 3634 1866 3635 1835 3635 1827 3635 1849 3636 1862 3636 1836 3636 1867 3637 1755 3637 1746 3637 1868 3638 1867 3638 1746 3638 1860 3639 1868 3639 1746 3639 1829 3640 1869 3640 1830 3640 1870 3641 1861 3641 1830 3641 1869 3642 1870 3642 1830 3642 1862 3643 1866 3643 1858 3643 1871 3644 1866 3644 1862 3644 1849 3645 1871 3645 1862 3645 1872 3646 1717 3646 1716 3646 1846 3647 1872 3647 1716 3647 1873 3648 1874 3648 1755 3648 1875 3649 1876 3649 1755 3649 1876 3650 1877 3650 1755 3650 1877 3651 1873 3651 1755 3651 1867 3652 1875 3652 1755 3652 1874 3653 1878 3653 1755 3653 1878 3654 1756 3654 1755 3654 1879 3655 1869 3655 1829 3655 1841 3656 1880 3656 1829 3656 1880 3657 1881 3657 1829 3657 1881 3658 1882 3658 1829 3658 1882 3659 1883 3659 1829 3659 1883 3660 1879 3660 1829 3660 1757 3661 1884 3661 1753 3661 1884 3662 1855 3662 1753 3662 1857 3663 1839 3663 1838 3663 1885 3664 1884 3664 1757 3664 1756 3665 1885 3665 1757 3665 1857 3666 1886 3666 1839 3666 1886 3667 1840 3667 1839 3667 1887 3668 1859 3668 1720 3668 1719 3669 1887 3669 1720 3669 1888 3670 1885 3670 1756 3670 1878 3671 1888 3671 1756 3671 1886 3672 1841 3672 1840 3672 1889 3673 1875 3673 1867 3673 1868 3674 1889 3674 1867 3674 1879 3675 1890 3675 1869 3675 1890 3676 1870 3676 1869 3676 1866 3677 1891 3677 1835 3677 1891 3678 1848 3678 1835 3678 1852 3679 1871 3679 1849 3679 1874 3680 1888 3680 1878 3680 1886 3681 1892 3681 1841 3681 1892 3682 1893 3682 1841 3682 1893 3683 1880 3683 1841 3683 1894 3684 1876 3684 1875 3684 1895 3685 1894 3685 1875 3685 1889 3686 1895 3686 1875 3686 1883 3687 1896 3687 1879 3687 1896 3688 1890 3688 1879 3688 1871 3689 1891 3689 1866 3689 1897 3690 1898 3690 1871 3690 1898 3691 1899 3691 1871 3691 1899 3692 1900 3692 1871 3692 1900 3693 1901 3693 1871 3693 1901 3694 1891 3694 1871 3694 1852 3695 1897 3695 1871 3695 1891 3696 1901 3696 1848 3696 1901 3697 1851 3697 1848 3697 1854 3698 1897 3698 1852 3698 1902 3699 1876 3699 1894 3699 1895 3700 1902 3700 1894 3700 1882 3701 1903 3701 1883 3701 1903 3702 1896 3702 1883 3702 1904 3703 1888 3703 1874 3703 1873 3704 1904 3704 1874 3704 1893 3705 1905 3705 1880 3705 1905 3706 1881 3706 1880 3706 1906 3707 1877 3707 1876 3707 1902 3708 1906 3708 1876 3708 1881 3709 1907 3709 1882 3709 1907 3710 1908 3710 1882 3710 1908 3711 1903 3711 1882 3711 1909 3712 1873 3712 1877 3712 1906 3713 1909 3713 1877 3713 1881 3714 1910 3714 1907 3714 1910 3715 1908 3715 1907 3715 1909 3716 1904 3716 1873 3716 1905 3717 1910 3717 1881 3717 1911 3718 1898 3718 1897 3718 1854 3719 1911 3719 1897 3719 1901 3720 1900 3720 1851 3720 1900 3721 1853 3721 1851 3721 1861 3722 1911 3722 1854 3722 1912 3723 1886 3723 1857 3723 1856 3724 1912 3724 1857 3724 1913 3725 1898 3725 1911 3725 1861 3726 1913 3726 1911 3726 1900 3727 1899 3727 1853 3727 1899 3728 1860 3728 1853 3728 1870 3729 1913 3729 1861 3729 1914 3730 1810 3730 1717 3730 1872 3731 1914 3731 1717 3731 1915 3732 1887 3732 1719 3732 1718 3733 1915 3733 1719 3733 1916 3734 1898 3734 1913 3734 1870 3735 1916 3735 1913 3735 1898 3736 1868 3736 1860 3736 1899 3737 1898 3737 1860 3737 1890 3738 1916 3738 1870 3738 1917 3739 1898 3739 1916 3739 1890 3740 1917 3740 1916 3740 1918 3741 1889 3741 1868 3741 1898 3742 1918 3742 1868 3742 1896 3743 1917 3743 1890 3743 1855 3744 1919 3744 1845 3744 1920 3745 1846 3745 1845 3745 1919 3746 1920 3746 1845 3746 1921 3747 1922 3747 1847 3747 1922 3748 1856 3748 1847 3748 1923 3749 1921 3749 1847 3749 1924 3750 1923 3750 1847 3750 1859 3751 1924 3751 1847 3751 1796 3752 1925 3752 1707 3752 1925 3753 1926 3753 1707 3753 1926 3754 1822 3754 1707 3754 1927 3755 1833 3755 1777 3755 1928 3756 1927 3756 1777 3756 1815 3757 1928 3757 1777 3757 1929 3758 1895 3758 1889 3758 1918 3759 1929 3759 1889 3759 1903 3760 1930 3760 1896 3760 1930 3761 1917 3761 1896 3761 1931 3762 1902 3762 1895 3762 1929 3763 1931 3763 1895 3763 1908 3764 1932 3764 1903 3764 1932 3765 1930 3765 1903 3765 1933 3766 1934 3766 1767 3766 1766 3767 1933 3767 1767 3767 1935 3768 1807 3768 1767 3768 1934 3769 1935 3769 1767 3769 1936 3770 1937 3770 1809 3770 1937 3771 1768 3771 1809 3771 1938 3772 1936 3772 1809 3772 1811 3773 1939 3773 1809 3773 1939 3774 1938 3774 1809 3774 1917 3775 1918 3775 1898 3775 1930 3776 1918 3776 1917 3776 1940 3777 1906 3777 1902 3777 1931 3778 1940 3778 1902 3778 1910 3779 1941 3779 1908 3779 1941 3780 1932 3780 1908 3780 1884 3781 1942 3781 1855 3781 1942 3782 1943 3782 1855 3782 1943 3783 1919 3783 1855 3783 1922 3784 1944 3784 1856 3784 1944 3785 1945 3785 1856 3785 1945 3786 1912 3786 1856 3786 1946 3787 1909 3787 1906 3787 1940 3788 1946 3788 1906 3788 1905 3789 1947 3789 1910 3789 1947 3790 1941 3790 1910 3790 1887 3791 1924 3791 1859 3791 1948 3792 1904 3792 1909 3792 1946 3793 1948 3793 1909 3793 1893 3794 1949 3794 1905 3794 1949 3795 1947 3795 1905 3795 1885 3796 1942 3796 1884 3796 1950 3797 1888 3797 1904 3797 1948 3798 1950 3798 1904 3798 1892 3799 1951 3799 1893 3799 1951 3800 1949 3800 1893 3800 1952 3801 1915 3801 1718 3801 1808 3802 1952 3802 1718 3802 1930 3803 1929 3803 1918 3803 1932 3804 1929 3804 1930 3804 1885 3805 1953 3805 1942 3805 1953 3806 1943 3806 1942 3806 1954 3807 1885 3807 1888 3807 1950 3808 1954 3808 1888 3808 1955 3809 1951 3809 1892 3809 1886 3810 1955 3810 1892 3810 1945 3811 1886 3811 1912 3811 1956 3812 1811 3812 1810 3812 1914 3813 1956 3813 1810 3813 1954 3814 1953 3814 1885 3814 1945 3815 1957 3815 1886 3815 1957 3816 1955 3816 1886 3816 1958 3817 1872 3817 1846 3817 1959 3818 1958 3818 1846 3818 1920 3819 1959 3819 1846 3819 1960 3820 1924 3820 1887 3820 1915 3821 1960 3821 1887 3821 1932 3822 1931 3822 1929 3822 1940 3823 1931 3823 1932 3823 1941 3824 1940 3824 1932 3824 1947 3825 1940 3825 1941 3825 1944 3826 1961 3826 1945 3826 1961 3827 1957 3827 1945 3827 1947 3828 1946 3828 1940 3828 1949 3829 1946 3829 1947 3829 1951 3830 1948 3830 1946 3830 1949 3831 1951 3831 1946 3831 1962 3832 1176 3832 1863 3832 1864 3833 1962 3833 1863 3833 1172 3834 1963 3834 1865 3834 1963 3835 1964 3835 1865 3835 1964 3836 1844 3836 1865 3836 1965 3837 1952 3837 1808 3837 1807 3838 1965 3838 1808 3838 1966 3839 1914 3839 1872 3839 1958 3840 1966 3840 1872 3840 1967 3841 1939 3841 1811 3841 1956 3842 1967 3842 1811 3842 1955 3843 1950 3843 1948 3843 1951 3844 1955 3844 1948 3844 1968 3845 1969 3845 1766 3845 1969 3846 1970 3846 1766 3846 1970 3847 1933 3847 1766 3847 1795 3848 1968 3848 1766 3848 1971 3849 1960 3849 1915 3849 1952 3850 1971 3850 1915 3850 1937 3851 1972 3851 1768 3851 1972 3852 1769 3852 1768 3852 1955 3853 1954 3853 1950 3853 1973 3854 1954 3854 1955 3854 1957 3855 1973 3855 1955 3855 1954 3856 1974 3856 1953 3856 1974 3857 1943 3857 1953 3857 1973 3858 1974 3858 1954 3858 1961 3859 1973 3859 1957 3859 1961 3860 1944 3860 1973 3860 1944 3861 1974 3861 1973 3861 1944 3862 1943 3862 1974 3862 1922 3863 1943 3863 1944 3863 1922 3864 1919 3864 1943 3864 1920 3865 1919 3865 1922 3865 1921 3866 1920 3866 1922 3866 1967 3867 1938 3867 1939 3867 1975 3868 1965 3868 1807 3868 1935 3869 1975 3869 1807 3869 1976 3870 1971 3870 1952 3870 1965 3871 1976 3871 1952 3871 1977 3872 1956 3872 1914 3872 1966 3873 1977 3873 1914 3873 1926 3874 1978 3874 1822 3874 1979 3875 1864 3875 1822 3875 1980 3876 1979 3876 1822 3876 1978 3877 1980 3877 1822 3877 1844 3878 1964 3878 1815 3878 1964 3879 1981 3879 1815 3879 1981 3880 1982 3880 1815 3880 1982 3881 1983 3881 1815 3881 1983 3882 1928 3882 1815 3882 1923 3883 1920 3883 1921 3883 1924 3884 1959 3884 1923 3884 1959 3885 1920 3885 1923 3885 1966 3886 1958 3886 1924 3886 1958 3887 1959 3887 1924 3887 1960 3888 1984 3888 1924 3888 1984 3889 1977 3889 1924 3889 1977 3890 1966 3890 1924 3890 1985 3891 1976 3891 1965 3891 1975 3892 1985 3892 1965 3892 1984 3893 1967 3893 1956 3893 1977 3894 1984 3894 1956 3894 1971 3895 1984 3895 1960 3895 1927 3896 1986 3896 1833 3896 1986 3897 1987 3897 1833 3897 1987 3898 1988 3898 1833 3898 1988 3899 1795 3899 1833 3899 1989 3900 1990 3900 1796 3900 1990 3901 1991 3901 1796 3901 1991 3902 1925 3902 1796 3902 1769 3903 1989 3903 1796 3903 1976 3904 1984 3904 1971 3904 1992 3905 1962 3905 1864 3905 1979 3906 1992 3906 1864 3906 1993 3907 1938 3907 1967 3907 1984 3908 1993 3908 1967 3908 1994 3909 1985 3909 1975 3909 1935 3910 1994 3910 1975 3910 1988 3911 1995 3911 1795 3911 1995 3912 1996 3912 1795 3912 1996 3913 1997 3913 1795 3913 1997 3914 1968 3914 1795 3914 1985 3915 1994 3915 1976 3915 1994 3916 1984 3916 1976 3916 1972 3917 1998 3917 1769 3917 1998 3918 1999 3918 1769 3918 1999 3919 2000 3919 1769 3919 2000 3920 2001 3920 1769 3920 2001 3921 1989 3921 1769 3921 1994 3922 1993 3922 1984 3922 2002 3923 2003 3923 1994 3923 2003 3924 1993 3924 1994 3924 2004 3925 2002 3925 1994 3925 1935 3926 2004 3926 1994 3926 2005 3927 2006 3927 1938 3927 2006 3928 2007 3928 1938 3928 2007 3929 2008 3929 1938 3929 2008 3930 1936 3930 1938 3930 1993 3931 2005 3931 1938 3931 2009 3932 2010 3932 1935 3932 1934 3933 2009 3933 1935 3933 2010 3934 2004 3934 1935 3934 1172 3935 2011 3935 1963 3935 2011 3936 2012 3936 1963 3936 2012 3937 1964 3937 1963 3937 2013 3938 2014 3938 1176 3938 2014 3939 2015 3939 1176 3939 2015 3940 1175 3940 1176 3940 1962 3941 2013 3941 1176 3941 2016 3942 2011 3942 1172 3942 1173 3943 2017 3943 1172 3943 2017 3944 2018 3944 1172 3944 2018 3945 2016 3945 1172 3945 1992 3946 2013 3946 1962 3946 1992 3947 2019 3947 2013 3947 2019 3948 2020 3948 2013 3948 2020 3949 2014 3949 2013 3949 2021 3950 1964 3950 2012 3950 2011 3951 2021 3951 2012 3951 2003 3952 2005 3952 1993 3952 2022 3953 2002 3953 2004 3953 2010 3954 2022 3954 2004 3954 2023 3955 1964 3955 2021 3955 2024 3956 2023 3956 2021 3956 2025 3957 2024 3957 2021 3957 2011 3958 2025 3958 2021 3958 2026 3959 2027 3959 2019 3959 2028 3960 2026 3960 2019 3960 1992 3961 2028 3961 2019 3961 2027 3962 2029 3962 2019 3962 2029 3963 2020 3963 2019 3963 2030 3964 2023 3964 2024 3964 2031 3965 2030 3965 2024 3965 2025 3966 2031 3966 2024 3966 2032 3967 1937 3967 1936 3967 2008 3968 2032 3968 1936 3968 1933 3969 2009 3969 1934 3969 2007 3970 2033 3970 2008 3970 2033 3971 2032 3971 2008 3971 2026 3972 2029 3972 2027 3972 2034 3973 2030 3973 2031 3973 2025 3974 2034 3974 2031 3974 2006 3975 2035 3975 2007 3975 2035 3976 2033 3976 2007 3976 2034 3977 2025 3977 2029 3977 2025 3978 2020 3978 2029 3978 2026 3979 2034 3979 2029 3979 2026 3980 2030 3980 2034 3980 2036 3981 2010 3981 2009 3981 1933 3982 2037 3982 2009 3982 2037 3983 2036 3983 2009 3983 2005 3984 2038 3984 2006 3984 2038 3985 2035 3985 2006 3985 2036 3986 2039 3986 2010 3986 2039 3987 2040 3987 2010 3987 2040 3988 2022 3988 2010 3988 2032 3989 1972 3989 1937 3989 1970 3990 2037 3990 1933 3990 2003 3991 2002 3991 2005 3991 2002 3992 2038 3992 2005 3992 2036 3993 2037 3993 1970 3993 1969 3994 2036 3994 1970 3994 2033 3995 2041 3995 2032 3995 2041 3996 1972 3996 2032 3996 2040 3997 2042 3997 2022 3997 2042 3998 2002 3998 2022 3998 2043 3999 2041 3999 2033 3999 2035 4000 2044 4000 2033 4000 2044 4001 2043 4001 2033 4001 2043 4002 1972 4002 2041 4002 2044 4003 2045 4003 2043 4003 1998 4004 1972 4004 2043 4004 2045 4005 1998 4005 2043 4005 2038 4006 2046 4006 2035 4006 2046 4007 2047 4007 2035 4007 2047 4008 2044 4008 2035 4008 2016 4009 2025 4009 2011 4009 2042 4010 2038 4010 2002 4010 1968 4011 2048 4011 1969 4011 2048 4012 2036 4012 1969 4012 2042 4013 2049 4013 2038 4013 2049 4014 2050 4014 2038 4014 2050 4015 2046 4015 2038 4015 2047 4016 2051 4016 2044 4016 2051 4017 2045 4017 2044 4017 2046 4018 2051 4018 2047 4018 2048 4019 2039 4019 2036 4019 2048 4020 2052 4020 2039 4020 2052 4021 2040 4021 2039 4021 2050 4022 2053 4022 2046 4022 2053 4023 2051 4023 2046 4023 2049 4024 2053 4024 2050 4024 2042 4025 2053 4025 2049 4025 2020 4026 2054 4026 2014 4026 2054 4027 2015 4027 2014 4027 2052 4028 2055 4028 2042 4028 2040 4029 2052 4029 2042 4029 2055 4030 2053 4030 2042 4030 1997 4031 2048 4031 1968 4031 2045 4032 1999 4032 1998 4032 2056 4033 2020 4033 2025 4033 2016 4034 2056 4034 2025 4034 2045 4035 2000 4035 1999 4035 2057 4036 2000 4036 2045 4036 2058 4037 2057 4037 2045 4037 2051 4038 2058 4038 2045 4038 1996 4039 2059 4039 1997 4039 2059 4040 2048 4040 1997 4040 1991 4041 1926 4041 1925 4041 2060 4042 1986 4042 1927 4042 1928 4043 2060 4043 1927 4043 2061 4044 1987 4044 1986 4044 2060 4045 2061 4045 1986 4045 2062 4046 1926 4046 1991 4046 2063 4047 2062 4047 1991 4047 1990 4048 2063 4048 1991 4048 2061 4049 1988 4049 1987 4049 1989 4050 2063 4050 1990 4050 2056 4051 2054 4051 2020 4051 1995 4052 2059 4052 1996 4052 2064 4053 1978 4053 1926 4053 2062 4054 2064 4054 1926 4054 1983 4055 2060 4055 1928 4055 2057 4056 2001 4056 2000 4056 1988 4057 2065 4057 1995 4057 2065 4058 2059 4058 1995 4058 2066 4059 2058 4059 2051 4059 2053 4060 2066 4060 2051 4060 2060 4061 2067 4061 2061 4061 2067 4062 2068 4062 2061 4062 2068 4063 1988 4063 2061 4063 2057 4064 1989 4064 2001 4064 2057 4065 2063 4065 1989 4065 2068 4066 2065 4066 1988 4066 1983 4067 2067 4067 2060 4067 2063 4068 2069 4068 2062 4068 2069 4069 2070 4069 2062 4069 2070 4070 2064 4070 2062 4070 2057 4071 2069 4071 2063 4071 2057 4072 2070 4072 2069 4072 2071 4073 2064 4073 2070 4073 2057 4074 2071 4074 2070 4074 2058 4075 2072 4075 2057 4075 2072 4076 2071 4076 2057 4076 2073 4077 2052 4077 2048 4077 2059 4078 2074 4078 2048 4078 2074 4079 2073 4079 2048 4079 2075 4080 1980 4080 1978 4080 2064 4081 2075 4081 1978 4081 1982 4082 2067 4082 1983 4082 2018 4083 2056 4083 2016 4083 2067 4084 2076 4084 2068 4084 2076 4085 2065 4085 2068 4085 2072 4086 2064 4086 2071 4086 2075 4087 2064 4087 2072 4087 2077 4088 2075 4088 2072 4088 2058 4089 2066 4089 2072 4089 2066 4090 2077 4090 2072 4090 2078 4091 2076 4091 2067 4091 1982 4092 2078 4092 2067 4092 2055 4093 2079 4093 2053 4093 2079 4094 2080 4094 2053 4094 2081 4095 2066 4095 2053 4095 2080 4096 2081 4096 2053 4096 2073 4097 2055 4097 2052 4097 2073 4098 2079 4098 2055 4098 2074 4099 2079 4099 2073 4099 2082 4100 2079 4100 2074 4100 2059 4101 2082 4101 2074 4101 2082 4102 2083 4102 2079 4102 2083 4103 2080 4103 2079 4103 2084 4104 2054 4104 2056 4104 2018 4105 2084 4105 2056 4105 2083 4106 2081 4106 2080 4106 2085 4107 1175 4107 2015 4107 2054 4108 2085 4108 2015 4108 2075 4109 1979 4109 1980 4109 1981 4110 2078 4110 1982 4110 2075 4111 1992 4111 1979 4111 2023 4112 2078 4112 1981 4112 1964 4113 2023 4113 1981 4113 2086 4114 2087 4114 2075 4114 2028 4115 1992 4115 2075 4115 2087 4116 2028 4116 2075 4116 2077 4117 2086 4117 2075 4117 2088 4118 2076 4118 2078 4118 2089 4119 2088 4119 2078 4119 2023 4120 2089 4120 2078 4120 2066 4121 2086 4121 2077 4121 2066 4122 2087 4122 2086 4122 2088 4123 2065 4123 2076 4123 2089 4124 2065 4124 2088 4124 2023 4125 2030 4125 2089 4125 2030 4126 2090 4126 2089 4126 2090 4127 2091 4127 2089 4127 2091 4128 2065 4128 2089 4128 2065 4129 2083 4129 2059 4129 2083 4130 2082 4130 2059 4130 2026 4131 2028 4131 2087 4131 2092 4132 2026 4132 2087 4132 2066 4133 2092 4133 2087 4133 2093 4134 2094 4134 2054 4134 2084 4135 2093 4135 2054 4135 2094 4136 2085 4136 2054 4136 2081 4137 2095 4137 2066 4137 2096 4138 2092 4138 2066 4138 2095 4139 2096 4139 2066 4139 2091 4140 2097 4140 2065 4140 2097 4141 2083 4141 2065 4141 2083 4142 2095 4142 2081 4142 2090 4143 2030 4143 2026 4143 2092 4144 2090 4144 2026 4144 2097 4145 2095 4145 2083 4145 2091 4146 2092 4146 2097 4146 2092 4147 2096 4147 2097 4147 2096 4148 2095 4148 2097 4148 2090 4149 2092 4149 2091 4149 2017 4150 2084 4150 2018 4150 2098 4151 1175 4151 2085 4151 2094 4152 2098 4152 2085 4152 1173 4153 2099 4153 2017 4153 2093 4154 2084 4154 2017 4154 2099 4155 2093 4155 2017 4155 2098 4156 2100 4156 1175 4156 2100 4157 2101 4157 1175 4157 2101 4158 1174 4158 1175 4158 2102 4159 2103 4159 1173 4159 2103 4160 2099 4160 1173 4160 1174 4161 2104 4161 1173 4161 2104 4162 2105 4162 1173 4162 2105 4163 2102 4163 1173 4163 2106 4164 2100 4164 2098 4164 2094 4165 2106 4165 2098 4165 2107 4166 2106 4166 2094 4166 2093 4167 2107 4167 2094 4167 2103 4168 2093 4168 2099 4168 2103 4169 2107 4169 2093 4169 2108 4170 2109 4170 2106 4170 2107 4171 2108 4171 2106 4171 2109 4172 2100 4172 2106 4172 2109 4173 2101 4173 2100 4173 2103 4174 2102 4174 2107 4174 2102 4175 2108 4175 2107 4175 2110 4176 2109 4176 2108 4176 2102 4177 2105 4177 2108 4177 2105 4178 2110 4178 2108 4178 2110 4179 2104 4179 2109 4179 2104 4180 2101 4180 2109 4180 2105 4181 2104 4181 2110 4181 2104 4182 1174 4182 2101 4182

+
+
+
+
+ + + + 1 0 0 1.6e-4 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 1.6e-4 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + -0.2908646 -0.7711008 0.5663933 4.076245 0.9551712 -0.1998833 0.2183912 1.005454 -0.05518904 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054209 -0.6141704 -6.50764 -4.01133e-9 0.8953956 0.4452714 5.343665 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 15.1406 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_G1M5.dae b/URDFs/sr_description/meshes/components/forearm/forearm_G1M5.dae new file mode 100644 index 0000000..dd5869f --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_G1M5.dae @@ -0,0 +1,122 @@ + + + + + + Blender User + Blender 2.82.7 + + 2022-03-18T07:36:51 + 2022-03-18T07:36:51 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.04392 0.04392 0.04392 1 + + + 0.21961 0.21961 0.21961 1 + + + 0.45000 0.45000 0.45000 1 + + + 32 + + + 1 + + + + + + + + + + + + + + + + + -0.02623391 -0.03521358 0.1496011 -0.02618992 -0.03425312 0.1500974 -0.02616453 -0.03866803 0.1500959 -0.005057454 0.0345999 0.143736 -0.005057454 0.03679984 0.143736 -0.006575882 0.0345999 0.1415436 -0.006575882 0.03679984 0.1415436 -0.00797683 0.0345999 0.1405261 -0.00797683 0.03679984 0.1405261 -0.01051414 0.0345999 0.138683 -0.01051414 0.03679984 0.138683 -0.01174145 0.0345999 0.1384443 -0.01174145 0.03679984 0.1384443 -0.01529228 0.0345999 0.1377538 -0.01529228 0.03679984 0.1377538 -0.01604086 0.0345999 0.1379402 -0.01604086 0.03679984 0.1379402 -0.02001583 0.0345999 0.13893 -0.02001583 0.03679984 0.13893 -0.02024543 0.0345999 0.1391158 -0.02024543 0.03679984 0.1391158 -0.02366226 0.03679984 0.14188 -0.02617186 0.03347349 0.1500961 -0.02624154 0.03025054 0.1494353 -0.02622157 0.03165191 0.1482014 -0.02621138 0.03385323 0.1495463 -0.02617383 0.03210926 0.1476939 -0.02624994 0.03422433 0.1490089 -0.02612435 0.03229433 0.1474367 -0.02607053 0.03537255 0.1469987 -0.02586144 0.03327924 0.1460688 -0.02590376 0.03573668 0.1462306 -0.02576041 0.03347533 0.145725 -0.0257321 0.03592181 0.1457347 -0.02572077 0.03355228 0.1455901 -0.02565842 0.03600126 0.1455218 -0.02533948 0.03396451 0.1446461 -0.02528339 0.03640592 0.1444378 -0.02508193 0.03424274 0.1440083 -0.02481943 0.03663754 0.1435099 -0.02475011 0.03442138 0.1433877 -0.02380019 0.03679984 0.1419914 -0.02380019 0.0345999 0.1419914 -0.02366226 0.0345999 0.14188 -0.02613574 -0.03832614 0.1505991 -0.02616441 -0.03369635 0.150385 -0.02492105 -0.03508919 0.154304 -0.02524435 -0.0358088 0.1535388 -0.02571946 -0.03686636 0.1524139 -0.02615278 -0.03342568 0.1504746 -0.02612221 -0.032 0.1506907 -0.02492105 0.02988922 0.154304 -0.02612221 0.02679985 0.1506907 -0.02612709 0.02735805 0.1506575 -0.02613294 0.02762436 0.1506183 -0.02525389 0.03061318 0.1535422 -0.02619034 0.02904456 0.1501569 -0.02563285 0.03143793 0.1526744 -0.02613574 0.03312611 0.1505991 -0.02619451 0.02914339 0.1500978 -0.02622139 0.02977544 0.1497197 -0.02604287 -0.03796499 0.1468521 -0.02618867 -0.03719431 0.147827 -0.02619594 -0.03904181 0.1495462 -0.02624011 -0.03588688 0.1490709 -0.02624732 -0.03570389 0.1492449 -0.02573186 -0.04112321 0.1457326 -0.02567327 -0.04121828 0.145514 -0.02562087 -0.03890794 0.1452911 -0.02559125 -0.04135179 0.1452069 -0.02509397 -0.03943473 0.1440327 -0.02528339 -0.04160583 0.1444378 -0.02424943 -0.03976428 0.1425961 -0.02442169 -0.04194486 0.1428523 -0.02380025 -0.03979986 0.1419916 -0.02380025 -0.04199987 0.1419916 -0.02368611 -0.03979986 0.1418507 -0.02624547 -0.03963023 0.1486809 -0.02607053 -0.04057252 0.1469987 -0.02573972 -0.0386424 0.1457304 -0.02569991 -0.03873169 0.1455829 -0.02368611 -0.04199987 0.1418507 -0.02028387 -0.04199987 0.1390681 -0.02028387 -0.03979986 0.1390681 -0.01607537 -0.04199987 0.1378015 -0.01607537 -0.03979986 0.1378015 -0.01170253 -0.04199987 0.138244 -0.01170253 -0.03979986 0.138244 -0.007833123 -0.04199987 0.1403282 -0.007833123 -0.03979986 0.1403282 -0.005057454 -0.04199987 0.143736 -0.005057454 -0.03979986 0.143736 -0.002073884 0.03679984 0.1472916 -0.002073884 0.0345999 0.1472916 -0.001454651 0.03674829 0.1480296 -4.30169e-4 0.03391474 0.1492507 -0.002073884 -0.03979986 0.1472917 -0.002073884 -0.04199987 0.1472917 1.11491e-4 -0.03888893 0.1498962 1.39871e-4 -0.04131484 0.14993 0.001711249 -0.03639996 0.1518028 0.002016603 -0.03936392 0.1521667 0.003270626 -0.036444 0.1536613 0.002296805 -0.03299999 0.1525008 0.003710985 -0.03299999 0.1541861 0.002296805 0.02779996 0.1525008 0.003710985 0.02779996 0.1541861 0.001856446 0.0303573 0.1519758 0.003166437 0.0312038 0.153537 0.001711249 0.03119999 0.1518028 0.003036201 0.03201854 0.1533818 9.11425e-4 0.03244435 0.1508495 0.001895368 0.03399449 0.1520223 1.11491e-4 0.03368896 0.1498962 0.001168966 0.03525274 0.1511566 8.26677e-5 0.03587204 0.1498619 -0.04468363 0.02863204 0.1352923 -0.04468363 -0.03383207 0.1352923 -0.04103291 0.02741122 0.1389318 -0.04090267 -0.03258025 0.1390618 -0.03586727 0.02679985 0.1440818 -0.03586733 -0.032 0.1440818 -0.02531814 0.02679985 0.1545989 -0.02531814 -0.032 0.1545989 -0.05350261 0.02922093 0.1140468 -0.05350261 0.02922093 0 -0.05350261 -0.02922093 0.1140468 -0.05350261 -0.02922093 0 0.05499982 0.03211307 0 0.05499982 0.03211307 0.1033861 0.05499982 0.0317341 0.1035228 0.05499982 0.03116172 0.1036442 0.05499982 0.03048259 0.1036889 0.05499982 -0.03211307 0 0.05499982 -0.03048259 0.1036889 0.05499982 -0.0308181 0.1036785 0.05499982 -0.03142088 0.1036003 0.05499982 -0.031663 0.1035431 0.05499982 -0.03211307 0.1033861 0.0320633 -0.03791302 0.1303958 0.03662502 -0.04112488 0.1265681 0.04291534 -0.03677845 0.12129 0.02181714 0.02837979 0.1389933 0.02733808 -0.03528881 0.1343607 0.0273292 0.03008478 0.1343682 0.04928439 -0.03048259 0.1159456 0.04928439 0.03048259 0.1159456 0.04408854 0.03578764 0.1203055 0.04846173 -0.03143972 0.116636 0.03218114 0.03279644 0.130297 0.03367292 0.03395056 0.1290451 0.03981745 0.03910624 0.1238894 0.01597625 0.02779996 0.1438944 0.01597625 -0.03299999 0.1438944 0.0161814 -0.03300058 0.1437222 0.02196466 -0.03360992 0.1388695 -0.02843612 0.05997622 0 -0.02843612 0.05997622 0.1022255 0.02565425 0.05997622 0 0.02372968 0.05997622 0.1022255 0.02450311 0.05997622 0.1021777 0.02510929 0.05997622 0.1020546 0.02559107 0.05997622 0.1018754 0.02565425 0.05997622 0.1018446 0.02565425 -0.05997622 0 0.02565425 -0.05997622 0.1050993 0.02559286 -0.05997622 0.1051267 -0.02843612 -0.05997622 0.1053854 -0.02843612 -0.05997622 0 0.02413386 -0.05997622 0.1053854 0.02515876 -0.05997622 0.1052713 0.02479273 -0.05997622 0.1053419 0.027888 0.04031467 0.1285147 -0.03372383 0.05364292 0.1151862 -0.03603756 0.05187666 0.1169525 0.03493005 0.0463311 0.122498 0.02958649 0.05130249 0.1175268 0.03450143 0.04589027 0.122939 0.02372968 0.0552901 0.1135392 0.0340324 0.04547023 0.1233589 -0.03132373 0.0552901 0.1135392 -0.03925633 0.04861372 0.1202154 -0.04168009 0.04463338 0.1241958 -0.04309391 0.04031467 0.1285147 -0.03861737 -0.04325091 0.1316651 -0.04214227 -0.04443883 0.1297483 -0.04213196 -0.04445332 0.1297293 0.02627813 -0.04480743 0.1292865 0.02155297 -0.04330784 0.1315522 -0.04186517 -0.04480743 0.1292865 0.01869404 -0.04279732 0.132923 -0.03630477 -0.04279834 0.1329227 0.01039648 -0.04200035 0.1369016 0.0101912 -0.04199987 0.137 -0.02880704 -0.04199987 0.137 0.01617974 -0.04234856 0.1341286 -0.03384238 -0.04231643 0.1342617 -0.04154139 -0.04551863 0.1284388 -0.0391528 -0.04933434 0.1238915 -0.03603756 -0.05246603 0.1201593 0.03083997 -0.04801923 0.1254587 0.02733016 -0.05417054 0.1181278 0.03199023 -0.04894053 0.1243607 0.03274393 -0.04973137 0.1234184 -0.03345811 -0.05442363 0.1178263 -0.03077238 -0.05623292 0.11567 0.02413386 -0.05623292 0.11567 0.05432766 0.03048259 0.1082777 0.05432766 -0.03048259 0.1082777 0.05236762 0.03048259 0.1124811 0.05236762 -0.03048259 0.1124811 -0.02880698 0.03679984 0.137 0.0101912 0.03679984 0.137 0.02639603 0.03965497 0.12923 -0.04319638 0.04002237 0.1288174 -0.04328066 0.03974169 0.1291292 -0.04313004 0.03967118 0.1292111 0.02154403 0.03810554 0.1315564 -0.03397274 0.03713327 0.1341909 0.01603209 0.03713124 0.1341993 -0.03720289 0.03778296 0.1324343 0.01971393 0.03778213 0.132434 -0.03884536 0.03811347 0.1315411 0.04341465 -0.05160474 0.1055567 0.04271638 -0.05226427 0.105969 0.03645592 -0.05680847 0 0.0413075 -0.05338466 0.1068009 0.03883767 -0.05520761 0.1052721 0.03645592 -0.05680847 0.1039295 0.04345709 -0.05164992 0 0.04973667 -0.04563421 0 0.04973667 -0.04563421 0.1018236 0.04973667 0.04563421 0.1018236 0.04973667 0.04563421 0 0.04457169 0.05069106 0.1048734 0.04345709 0.05164992 0 0.04344415 0.05163466 0.1042094 0.03645592 0.05680847 0 0.03645592 0.05680847 0.1005687 0.04204392 0.05280673 0.1033847 -0.03927677 -0.05489587 0.1113985 -0.04230493 -0.05259788 0.1137315 -0.04230493 -0.05259788 0 -0.03612416 -0.05701988 0.1092422 -0.03338152 -0.05866777 0 -0.03338152 -0.05866777 0.1053854 -0.03588855 -0.05716866 0.109086 -0.03464317 -0.05793184 0.1072357 -0.03491598 -0.05776768 0.1083202 -0.0335763 -0.05855643 0.106448 -0.0338546 -0.05839616 0.1070358 -0.03426015 -0.05815911 0.1076243 -0.03343313 -0.05863839 0.1059337 -0.04230493 0.05259788 0 -0.04230493 0.05259788 0.1098815 -0.03958874 0.05467134 0.1081151 -0.03437578 0.05809068 0.104604 -0.03388416 0.05837893 0.1039264 -0.03509145 0.05766129 0.1043468 -0.03368151 0.05849605 0.1035423 -0.03347235 0.05861604 0.1029521 -0.03339463 0.05866026 0.1025018 -0.03338152 0.05866777 0.1022255 -0.03677123 0.05660492 0.1064682 -0.03566777 0.05730646 0.105771 -0.0347445 0.0578711 0.1049975 -0.03338152 0.05866777 0 -0.02848017 -0.0599094 0.1068477 0.02413386 -0.05901134 0.1108577 -0.02860212 -0.05972331 0.1082189 -0.02883911 -0.05935913 0.1097865 -0.03057163 -0.05657058 0.1152536 -0.02974325 -0.05793172 0.1132115 -0.02918452 -0.05882066 0.1113558 -0.02907359 -0.05899351 0.1108517 -0.02928316 0.05866551 0.1085681 -0.02959716 0.05816638 0.1096175 0.02372968 0.05783265 0.1102254 -0.02982145 0.05780071 0.1102057 -0.03038376 0.05688405 0.1116802 0.02372968 0.05943101 0.1063666 -0.02844727 0.05995935 0.1029623 -0.02851355 0.05985862 0.104163 -0.02869153 0.0595861 0.105737 -0.02879738 0.05942296 0.1063645 -0.02886438 0.05931997 0.106761 -0.03150886 0.03603863 0.1397101 -0.03379935 0.03387105 0.1420076 -0.03532975 0.03062677 0.1435427 -0.02520966 0.02752017 0.1546341 -0.02531588 0.02681976 0.154601 -0.02510046 0.02823984 0.154668 -0.02509951 0.02824676 0.1546683 -0.02501457 0.02877616 0.1545956 -0.02492874 0.02931153 0.154522 -0.02490437 0.029464 0.154501 -0.02489864 0.02967876 0.1544173 -0.0248959 0.02978581 0.1543757 -0.04112529 0.03676044 0.1331371 -0.04469853 0.02866619 0.1352772 -0.04019427 0.03080153 0.1389068 -0.04489046 0.02911919 0.1350761 -0.04540443 0.03066784 0.1343369 -0.04318714 0.03468436 0.1341446 -0.04621195 0.03410387 0.1325629 -0.04483312 0.0320838 0.1344671 -0.04592108 0.03258121 0.133376 -0.04576081 0.03174155 0.1338243 -0.04630357 0.03767681 0.1303672 -0.04629766 0.03745049 0.1305063 -0.04542195 0.03840076 0.1301121 -0.04527562 0.03832608 0.1302158 -0.04540812 0.03840953 0.1301057 -0.04625988 0.03597021 0.131416 -0.03643471 0.03597825 0.1363824 -0.03859657 0.03377825 0.1380209 -0.0248959 -0.03498578 0.1543757 -0.02489864 -0.03487879 0.1544173 -0.03532975 -0.0358268 0.1435427 -0.02490437 -0.03466397 0.154501 -0.02492874 -0.03451168 0.154522 -0.02501457 -0.03397613 0.1545956 -0.02509951 -0.03344672 0.1546683 -0.02510046 -0.03343981 0.154668 -0.02531588 -0.03201973 0.154601 -0.02520966 -0.03272014 0.1546341 -0.03379935 -0.03907102 0.1420076 -0.03150886 -0.04123878 0.1397101 -0.0448423 -0.03420263 0.1351283 -0.04529047 -0.03548943 0.134522 -0.04461503 -0.03719604 0.134676 -0.04216897 -0.04442965 0.1297603 -0.04090505 -0.04190289 0.1332909 -0.04356539 -0.04385304 0.1303068 -0.04252487 -0.04430115 0.1299146 -0.04628139 -0.04118156 0.1314222 -0.046346 -0.04209578 0.1308818 -0.04297119 -0.03981733 0.1343281 -0.04543012 -0.04277169 0.1307758 -0.04467976 -0.04320687 0.1305871 -0.04563939 -0.03649091 0.1340501 -0.04593157 -0.03778374 0.1333793 -0.04609119 -0.03848952 0.1330131 -0.04007071 -0.0359829 0.1390247 -0.04469853 -0.03386622 0.1352772 -0.03630971 -0.04116928 0.1364679 -0.0384745 -0.03896796 0.1381232 -0.04701596 0.04785227 0 -0.05055886 0.04218125 0 -0.04713296 0.04770362 0.1131443 -0.04700088 0.04783767 0.1130551 -0.05264347 0.03584831 0.1193487 -0.05247467 0.03700697 0.1202756 -0.0527575 0.0358662 0 -0.05076897 0.04173302 0.1171247 -0.05051285 0.04215359 0.1168444 -0.05349195 0.03002578 0.1146906 -0.05055826 -0.04218089 0.1220077 -0.05056089 -0.04217696 0.122011 -0.0527575 -0.0358662 0 -0.05122965 -0.04067587 0.1232108 -0.05266839 -0.03624713 0.1196677 -0.05104637 -0.04110985 0.1228587 -0.05271416 -0.03586035 0.1193584 -0.05055886 -0.04218125 0 -0.04701596 -0.04785227 0 -0.04701024 -0.0478487 0.1175047 -0.04697769 -0.04790037 0.1174636 -0.04470658 -0.03385102 0.1352694 -0.04470658 0.02865099 0.1352694 -0.04492998 -0.03403913 0.1350437 -0.04500669 0.02890473 0.1349653 -0.04636526 -0.03536111 0.1334712 -0.04663187 0.03043085 0.1331529 -0.04751145 -0.03658467 0.132035 -0.04795324 0.03190523 0.1314298 -0.05030405 0.03504395 0.1275261 -0.05073887 0.03538316 0.1266244 -0.05242866 -0.03543215 0.1218109 -0.05122965 -0.03838503 0.1255018 -0.05102062 -0.03869879 0.1259953 -0.04973649 0.03438663 0.1285997 -0.05087304 -0.03884357 0.1263296 -0.05053985 -0.03903484 0.1270465 -0.05028718 -0.03909832 0.1275593 -0.04971915 -0.03908795 0.1286311 -0.0494467 0.03398323 0.1290597 -0.04946666 -0.03903341 0.1290723 -0.04936712 -0.03901177 0.1292464 -0.05006688 0.03482311 0.1279874 -0.05242002 0.03558987 0.1220336 -0.05247467 0.03544974 0.1218327 -0.05115145 0.03567963 0.1256894 -0.05163991 0.03593277 0.1244536 -0.0518791 0.0359801 0.123782 -0.05217301 0.0359041 0.1228792 -0.05234563 0.03572624 0.1222983 -0.05349195 0.02986466 0.1148515 -0.05247575 0.0354442 0.1218259 -0.05266839 -0.03484189 0.1210729 -0.04580122 -0.04484117 0.1278892 -0.04911756 -0.04302579 0.126601 -0.04919362 -0.04297816 0.1265032 -0.04615068 -0.04431951 0.1284319 -0.05078834 -0.04151672 0.1241278 -0.05046284 -0.04195296 0.1247029 -0.04905045 -0.04353255 0.1256143 -0.04970461 -0.04265916 0.1258465 -0.04641753 -0.04387044 0.1289266 -0.04695063 -0.04368901 0.1287612 -0.04778105 -0.04352843 0.1280287 -0.0425812 -0.04445755 0.1297081 -0.0437743 -0.04442471 0.1295503 -0.04590731 -0.04404413 0.129085 -0.04217278 -0.04444062 0.1297458 -0.04941093 -0.04284238 0.1262238 -0.04536169 -0.04563581 0.1270022 -0.04854518 -0.04445648 0.1247336 -0.04499459 -0.04937535 0.1200253 -0.04227113 -0.04987442 0.1222624 -0.03842329 -0.05332565 0.1183916 -0.04058116 -0.05337101 0.1161785 -0.03565222 -0.05534982 0.1160303 -0.03765106 -0.05551213 0.1138222 -0.03277295 -0.0572201 0.1138485 -0.03369045 -0.05735486 0.1127468 -0.03460764 -0.05748987 0.111645 -0.03348386 -0.05764949 0.1124641 -0.03251087 -0.05845558 0.1109372 -0.03186011 -0.05897539 0.1095913 -0.03145945 -0.05928772 0.108473 -0.03118538 -0.05949819 0.1073677 -0.03104472 -0.05960518 0.1064069 -0.03099375 -0.05964356 0.1053854 -0.03099375 -0.05964356 0 -0.04538232 0.03959095 0.1287239 -0.04743844 0.03932011 0.12822 -0.04696428 0.03876841 0.1291427 -0.04674685 0.03949308 0.1284606 -0.04661923 0.03985553 0.1280971 -0.04647237 0.04023671 0.1277431 -0.04654556 0.04021424 0.1277056 -0.04840219 0.0393638 0.1273415 -0.0484398 0.03936553 0.1273072 -0.0494132 0.03933399 0.1262367 -0.04390478 0.04935157 0.1173174 -0.04577273 0.04881066 0.1153154 -0.04943686 0.04343456 0.1194375 -0.05139601 0.03870779 0.1230231 -0.05112886 0.03893345 0.1235736 -0.04732775 0.04454797 0.1215186 -0.05056309 0.03917783 0.1245542 -0.0495398 0.03931689 0.1260515 -0.05220443 0.03774321 0.1211618 -0.05181568 0.03835302 0.1221583 -0.05236375 0.03736305 0.1206715 -0.04465287 0.04496139 0.1231595 -0.04167473 0.04928416 0.1189942 -0.03787237 0.05280292 0.1155977 -0.03844618 0.05295008 0.1150312 -0.04110389 0.05317491 0.1119517 -0.04060178 0.05319803 0.1125991 -0.03959602 0.05324465 0.1138963 -0.03597652 0.05483877 0.1132709 -0.03800016 0.05519372 0.1108312 -0.03527683 0.05699998 0.1091638 -0.03340047 0.05654716 0.1115993 -0.0309844 0.0596078 0.1022255 -0.03181684 0.0593875 0.1022255 -0.03183007 0.0593791 0.1026616 -0.03016436 0.05981642 0.1028167 -0.03015196 0.05982804 0.1022255 -0.03043591 0.05956053 0.1050497 -0.03023797 0.05974733 0.1037811 -0.03190839 0.05932885 0.1033732 -0.03211891 0.05919301 0.1043094 -0.03232347 0.05905967 0.1049225 -0.03282094 0.0587309 0.1060149 -0.03319525 0.05847883 0.1066582 -0.03062832 0.05937761 0.1058798 -0.0310958 0.05892556 0.1073578 -0.03144741 0.05857896 0.1082271 -0.03233271 0.0576806 0.1099699 -0.03413856 0.05782496 0.1079506 -0.03099375 0.05964356 0 0.04977792 -0.04558932 0.1018306 0.05259978 -0.04161262 0 0.05039364 -0.04488158 0.1019377 0.05225211 -0.04223042 0.1023051 0.05433636 -0.0369994 0.1029128 0.0540691 -0.03814357 0.1027938 0.05439054 -0.0370121 0 0.05365425 -0.03932529 0.1026605 0.05255973 -0.04159319 0.1023831 0.05476701 -0.03515672 0.1031045 0.05260568 -0.03135073 0.1120807 0.05438977 -0.03109484 0.1080462 0.05104738 -0.03491979 0.113524 0.05313694 -0.03362935 0.1107734 0.05091118 -0.03446662 0.1138513 0.05299592 -0.03296095 0.1111992 0.05061024 -0.0336076 0.1143901 0.04978406 -0.03156584 0.1154744 0.05397886 -0.03423392 0.1082678 0.05337047 -0.03491628 0.1098381 0.05141246 -0.03613615 0.1126459 0.05449086 -0.03221625 0.1075246 0.05452722 -0.03267616 0.1072683 0.0545873 -0.03355181 0.1066974 0.04976987 -0.04559803 0.1018512 0.04976207 -0.04560667 0.1018717 0.0502671 -0.0450266 0.1022748 0.05013358 -0.04516541 0.1026118 0.05177319 -0.04288029 0.1037364 0.05292654 -0.04049444 0.1051769 0.05327409 -0.03950721 0.1057276 0.05174267 -0.0414403 0.1076123 0.05138826 -0.04264259 0.106132 0.05115365 -0.04343789 0.1051524 0.05387085 -0.03695476 0.1070474 0.05183368 -0.03842884 0.1106889 0.05183845 -0.03899604 0.1101267 0.0518468 -0.03997403 0.1091575 0.05185192 -0.04060262 0.1085343 0.02877807 -0.05973076 0.1047971 0.0312826 -0.05916804 0 0.03127402 -0.05913209 0.1045342 0.03640305 -0.05684214 0.1039363 0.03587192 -0.05716919 0.1040031 0.03297716 -0.05858749 0.1043473 0.03183126 -0.05899852 0.1044754 0.04131305 -0.05338037 0.1068381 0.0506553 -0.03542572 0.1138703 0.05178219 -0.03912913 0.1102147 0.04459118 -0.04966825 0.1107321 0.04526937 -0.04601073 0.115103 0.04168045 -0.05256158 0.1110916 0.04164326 -0.05279582 0.1101733 0.04106307 -0.04945391 0.1182187 0.04128879 -0.0501123 0.1171526 0.04162508 -0.05151051 0.1142107 0.04165256 -0.05203384 0.1126577 0.04083514 -0.04878854 0.1192957 0.04469496 -0.04159277 0.1187216 0.04006677 -0.04693037 0.1216623 0.03811383 -0.04315561 0.1250773 0.03907853 -0.04484093 0.1237043 0.03945899 -0.04564517 0.1229182 0.03642153 -0.0568304 0.1039773 0.03641229 -0.05683624 0.1039568 0.03607434 -0.05703938 0.104452 0.03597426 -0.05710601 0.1042276 0.03413635 -0.05784934 0.1068979 0.03358328 -0.05827838 0.1056278 0.03378635 -0.05793154 0.1073033 0.03263109 -0.05862051 0.1061538 0.02896392 -0.05790013 0.112253 0.0273655 -0.05944854 0.1087982 0.03079015 -0.05813938 0.1105028 0.03006297 -0.05923724 0.1074962 0.03121221 -0.05819457 0.1100984 0.03335028 -0.05803376 0.1078086 0.02874165 -0.05784821 0.1124517 0.02722245 -0.059435 0.1089174 0.02759557 -0.05752938 0.1133877 0.02624917 -0.05932754 0.1096476 0.02725136 -0.05743378 0.1136689 0.02608281 -0.05703413 0.1144977 0.0254696 -0.05922293 0.110146 0.03638535 -0.052226 0.1191127 0.03576582 -0.05183285 0.1199355 0.03060162 -0.05571115 0.1155185 0.03464221 -0.05111956 0.1214277 0.036502 -0.05624294 0.1089268 0.03371036 -0.05641365 0.1123998 0.03767055 -0.05290836 0.117011 0.04023987 -0.05367559 0.1110432 0.04011482 -0.05365324 0.1113775 0.03909015 -0.05346995 0.1141183 0.0382471 -0.05313634 0.1158359 0.04130077 -0.05338984 0.1068377 0.04051625 -0.05366736 0.1101363 0.05476599 0.03516244 0.1031039 0.05439054 0.0370121 0 0.05433619 0.03699934 0.1029128 0.05259978 0.04161262 0 0.05351865 0.03966671 0.102621 0.05406671 0.03815072 0.1027929 0.04977792 0.04558932 0.1018306 0.05015254 0.04516667 0.1018951 0.05206316 0.04254585 0.1022638 0.05254817 0.04158639 0.1023828 0.04976987 0.04559803 0.1018512 0.05007261 0.04525673 0.1021063 0.05161941 0.04313659 0.1035711 0.04976207 0.04560667 0.1018717 0.0499897 0.04534441 0.1023174 0.05105912 0.04364871 0.1048669 0.05138617 0.04264044 0.1061323 0.0528137 0.0407775 0.1050144 0.053272 0.03951328 0.1057243 0.05169785 0.04167973 0.1073381 0.05185163 0.04060781 0.1085288 0.05183863 0.03899604 0.1101268 0.0538702 0.03695958 0.1070451 0.0518341 0.03843307 0.110685 0.05141246 0.03613615 0.1126459 0.05319035 0.03487581 0.1097452 0.05407643 0.03424787 0.1082996 0.05438357 0.0335378 0.1066653 0.05099606 0.03472417 0.1136794 0.05317658 0.03382909 0.1106387 0.05105513 0.03492438 0.1135327 0.05453735 0.03281283 0.1071867 0.05444914 0.03173029 0.1077674 0.05283451 0.0322597 0.1116067 0.05026715 0.03271353 0.1148977 0.0312826 0.05916804 0 0.03127276 0.05912786 0.1012278 0.03190523 0.0589742 0.101155 0.03640526 0.05684083 0.1005757 0.03341591 0.05840867 0.1009694 0.02881664 0.05972462 0.1015105 0.04047286 0.04000675 0.1232916 0.04611134 0.04828768 0.109715 0.04463601 0.0505613 0.1055815 0.04457718 0.05068629 0.1049118 0.04665035 0.0447207 0.1140674 0.04595768 0.04044008 0.1176941 0.04107308 0.0409345 0.1226401 0.04228729 0.04302418 0.1208966 0.04249078 0.04341173 0.1204745 0.04437083 0.04740911 0.1151162 0.04417079 0.04692876 0.1158788 0.04368299 0.04575634 0.1177394 0.04329431 0.04494118 0.1188081 0.04485213 0.0493707 0.1105242 0.04483997 0.04907453 0.1114783 0.04478091 0.04877257 0.1122515 0.04487985 0.05004292 0.1083587 0.02738022 0.05694639 0.111116 0.02763777 0.05705088 0.1109238 0.02685612 0.05865299 0.1081816 0.02807158 0.05888676 0.1071217 0.02920502 0.05755996 0.1095188 0.02942156 0.05762022 0.1093043 0.02696818 0.05970853 0.1044462 0.02685302 0.05970162 0.1045444 0.02760308 0.05931138 0.1057035 0.02823805 0.05891442 0.1069608 0.02600133 0.05964189 0.1051835 0.02583312 0.05631977 0.1122708 0.02543061 0.0583148 0.1092168 0.02497947 0.05955541 0.1057924 0.03641527 0.05683434 0.1005962 0.03642547 0.05682796 0.1006168 0.03401988 0.0580917 0.1021442 0.03027582 0.05916398 0.1043192 0.03280216 0.05854868 0.1028809 0.03069549 0.0578382 0.107949 0.03157401 0.0579884 0.1070145 0.03360772 0.0578944 0.1045801 0.03376436 0.05785816 0.1043745 0.03457504 0.05767083 0.1033105 0.0396527 0.05393987 0.1075214 0.03323036 0.05316454 0.1148121 0.03665459 0.05406171 0.1114087 0.04456567 0.05069649 0.1049116 0.04382508 0.05097013 0.1083412 0.04331499 0.05091673 0.1098921 0.04280513 0.05086314 0.1114417 0.0424962 0.05078077 0.1122096 0.03842502 0.04875826 0.1190509 0.03872627 0.04895508 0.1187108 0.03951311 0.04942065 0.1176527 0.04112994 0.05025744 0.1150527 0.04127866 0.05031424 0.1147435 0.03689682 0.04776018 0.1207765 0.01553589 0.03124397 0.1433696 0.01428174 0.03416395 0.1418751 0.01240491 0.03611487 0.1396384 0.01803588 0.03606539 0.1363316 0.03112334 0.03484958 0.1307808 0.02958792 0.03910446 0.1293305 0.02812772 0.03840082 0.1302283 0.03011882 0.03859508 0.1294538 0.02974051 0.03676158 0.1307573 0.03257298 0.03582072 0.1296042 0.03210997 0.03640466 0.1296365 0.0311824 0.03757476 0.1297013 0.02642232 0.03264504 0.1345906 0.0250681 0.0349707 0.1341603 0.02339071 0.03684812 0.1331171 0.02111274 0.03141117 0.1388812 0.01979982 0.03407955 0.137957 0.03628069 0.04378139 0.1243495 0.03828209 0.04157966 0.1245329 0.03886306 0.04232829 0.123932 0.03727704 0.04496121 0.1232441 0.03680127 0.04435974 0.1238103 0.03833544 0.04403138 0.1232686 0.0393939 0.04310137 0.1232931 0.04457139 0.0506913 0.1049117 0.04437041 0.05052691 0.108354 0.04388725 0.05004298 0.1114885 0.04371941 0.04986935 0.1122708 0.04290515 0.04901176 0.1151989 0.04183614 0.04786527 0.1179395 0.04128456 0.04726803 0.1190798 0.03993266 0.04579347 0.1213656 0.01240497 -0.04131484 0.1396384 0.01428174 -0.03936392 0.141875 0.01553595 -0.036444 0.1433696 0.01260197 -0.04129916 0.1395242 0.01447433 -0.03934442 0.1417396 0.01573067 -0.03643167 0.143213 0.01817888 -0.04127538 0.1362466 0.01994013 -0.03929024 0.1378566 0.02339953 -0.0420503 0.1331118 0.02507656 -0.04017305 0.1341542 0.02801257 -0.04355072 0.130299 0.02854984 -0.04300236 0.1304793 0.02962666 -0.04190361 0.1308405 0.03054881 -0.0406202 0.1308625 0.0212543 -0.03662967 0.1387669 0.02643096 -0.03784823 0.1345836 0.03100883 -0.03997993 0.1308736 0.03313148 -0.04625195 0.1267066 0.03514212 -0.04385572 0.1270922 0.03435456 -0.04751843 0.1253184 0.03732866 -0.04690492 0.1242236 0.03647017 -0.04551982 0.1255659 0.03623867 -0.0477463 0.1241744 0.03514885 -0.04858762 0.1241253 0.04098773 -0.05315458 0.1110755 0.04130691 -0.05338507 0.1068379 0.04109674 -0.05325382 0.1101587 0.04044044 -0.05259943 0.1142082 0.03963989 -0.05172401 0.1172082 0.03883928 -0.05081617 0.1194397 0.03766429 -0.04944998 0.1219743 -0.04651254 -0.04253435 0.1302981 -0.05247467 0.03622823 0.1210541 -0.05249452 0.03649216 0.1213689 -0.05238461 0.03675419 0.1217508 -0.05212724 0.03715789 0.1225523 -0.05168443 0.03750699 0.1237406 -0.0513218 0.03762555 0.1245961 -0.05057799 0.0376228 0.1261281 -0.04995334 0.03754287 0.1272078 -0.04930055 0.03741574 0.1282055 -0.04891878 0.03700721 0.1289257 -0.04838532 0.03620189 0.129876 -0.04470252 0.02865856 0.1352733 -0.04494965 0.02901202 0.1350218 -0.04623961 0.031093 0.1335315 -0.04721683 0.03304111 0.1321313 -0.05275005 -0.03555423 0.1203801 -0.05144345 -0.03957468 0.1244004 -0.04900389 -0.04026252 0.1292829 -0.04804736 -0.04232013 0.129132 -0.04853028 -0.04171729 0.1292953 -0.04915475 -0.04151839 0.1285776 -0.04861062 -0.04161679 0.1293225 -0.05002599 -0.04119521 0.1272309 -0.05040997 -0.04095149 0.1265618 -0.05091232 -0.04047042 0.1255925 -0.05113291 -0.04016751 0.1251233 -0.048074 -0.04201602 0.1296592 -0.0481621 -0.04068249 0.1303856 -0.04824596 -0.0405659 0.1303063 -0.04806643 -0.04075682 0.1304118 -0.04470252 -0.03385865 0.1352733 -0.04488664 -0.03412079 0.1350867 -0.04603385 -0.03593027 0.133792 -0.0468986 -0.03755956 0.1326211 -0.04313021 -0.03383207 0.1337343 -0.04313021 0.02863204 0.1337343 -0.03958594 0.02743703 0.1372678 -0.03431391 0.02679985 0.1425238 -0.03431391 -0.032 0.1425238 -0.0390852 -0.03252035 0.137767 -0.05130273 0.02922093 0.1140468 -0.05130273 -0.02922093 0.1140468 0.05279994 0.0317341 0.1035228 0.05279994 0.03211307 0.1033861 0.05279994 0.03119874 0.103639 0.05279994 -0.03211307 0.1033861 0.05279994 -0.03163373 0.1035509 0.05279994 -0.03142088 0.1036003 0.05279994 -0.03077971 0.1036807 0.05279994 -0.03048259 0.1036889 0.05279994 0.03048259 0.1036889 0.0322588 0.03395056 0.1273599 0.04787027 -0.03048259 0.1142603 0.03102821 0.03298527 0.1283925 0.04717886 -0.03129041 0.1148406 0.02611464 0.03017109 0.1325154 0.04157698 -0.03671652 0.1195411 0.0352109 -0.04112488 0.1248828 0.03840333 0.03910624 0.1222041 0.04258728 0.03586333 0.1186934 0.04787027 0.03048259 0.1142603 0.03064918 -0.03791302 0.1287106 0.02578747 -0.03523075 0.13279 0.0205115 0.02840197 0.1372169 0.02026391 -0.03355211 0.1374247 0.01456207 0.02779996 0.1422091 0.01456207 -0.03299999 0.1422091 -0.02843612 0.05777633 0.1022255 0.02372968 0.05777633 0.1022255 0.02565425 0.05777633 0.1018446 0.02510929 0.05777633 0.1020546 0.02454245 0.05777633 0.1021724 -0.02843612 -0.05777633 0.1053854 0.02413386 -0.05777633 0.1053854 0.02482867 -0.05777633 0.1053367 0.02515876 -0.05777633 0.1052713 0.02565425 -0.05777633 0.1050993 0.02950942 0.04980796 0.1159099 0.03493005 0.0447756 0.1209424 0.03450143 0.04433465 0.1213834 0.027888 0.03875899 0.126959 -0.04309391 0.03875899 0.126959 -0.04180788 0.04279363 0.1229244 0.02372968 0.05373442 0.1119835 0.0340324 0.04391473 0.1218033 -0.03132373 0.05373442 0.1119835 -0.03372383 0.0520873 0.1136305 -0.03935444 0.04693168 0.1187863 -0.03603756 0.05032104 0.1153969 0.02141654 -0.04130846 0.1306309 0.02627813 -0.04312217 0.1278724 -0.04186517 -0.04312217 0.1278724 0.01869189 -0.04074847 0.1321766 -0.04213196 -0.04270309 0.1283964 -0.04214227 -0.0426861 0.1284188 -0.02880704 -0.03979986 0.137 0.0101912 -0.03979986 0.137 -0.03357815 -0.04013586 0.1339297 0.01589304 -0.04017341 0.1337648 -0.03630363 -0.04074865 0.1321759 -0.03849244 -0.04124081 0.1307675 0.03083997 -0.0463339 0.1240445 0.02413386 -0.0545476 0.1142559 -0.03077238 -0.0545476 0.1142559 -0.03345811 -0.0527383 0.1164122 -0.03603756 -0.05078071 0.1187452 0.02725481 -0.05253809 0.1166508 0.03204089 -0.04730248 0.1228905 0.03274393 -0.04804611 0.1220043 -0.0392434 -0.04753428 0.122614 -0.04166162 -0.0435779 0.1273291 0.05052959 0.03048259 0.1112722 0.05052959 -0.03048259 0.1112722 0.05222016 0.03048259 0.1076468 0.05222016 -0.03048259 0.1076468 0.0101912 0.0345999 0.137 -0.002073884 0.0345999 0.1472917 -0.02880698 0.0345999 0.137 -0.02380019 0.0345999 0.1419916 -0.03450179 0.03511399 0.1333354 0.016649 0.03511554 0.1333358 0.01614058 0.03500694 0.1336243 -0.03407907 0.03501117 0.1336075 -0.03979229 0.03654927 0.1299309 0.02264606 0.03655272 0.1299331 0.02174371 0.03620332 0.1304452 -0.0390405 0.03621912 0.1304147 -0.04328066 0.03808099 0.1276863 -0.04319638 0.03841304 0.1273173 0.02665728 0.03810626 0.1276572 0.04811573 -0.04414701 0.1018236 0.03746843 -0.05348086 0.1052091 0.03996115 -0.05164474 0.1068009 0.04142814 -0.05047541 0.1059055 0.03526777 -0.05495697 0.1039295 0.04200541 -0.04992926 0.1055532 0.03526777 0.05495697 0.1005687 0.04056763 0.05116975 0.1033235 0.04202741 0.04995065 0.1042101 0.04311913 0.04903888 0.1048734 0.04811573 0.04414701 0.1018236 -0.04092597 -0.05088359 0.1137315 -0.03799664 -0.05310678 0.1113985 -0.03494679 -0.05516153 0.1092422 -0.03278195 -0.05647498 0.1070901 -0.03248196 -0.05664789 0.106448 -0.03351402 -0.05604368 0.1072357 -0.03235352 -0.05672138 0.1059862 -0.03229343 -0.05675572 0.1053854 -0.03471887 -0.05530536 0.109086 -0.03383797 -0.05584859 0.1083765 -0.03314352 -0.05626344 0.1076243 -0.03325539 0.05619746 0.104604 -0.03351771 0.0560413 0.1048998 -0.03394788 0.05578196 0.1043468 -0.03229343 0.05675572 0.1022255 -0.03444916 0.05547374 0.1057286 -0.0355727 0.05475986 0.1064682 -0.03829842 0.05288952 0.1081151 -0.04092597 0.05088359 0.1098815 -0.03236913 0.05671244 0.1028998 -0.03258377 0.0565896 0.1035423 -0.03275114 0.05649292 0.1038758 -0.03230625 0.05674839 0.1025018 -0.03057163 -0.05483901 0.1138967 -0.02979606 -0.05593919 0.1122649 -0.02860212 -0.05755811 0.1078293 -0.02886629 -0.0572077 0.109306 0.02413386 -0.05694407 0.1101053 -0.0290721 -0.05693084 0.1101007 -0.02918452 -0.05677956 0.1105349 -0.02848905 -0.05770695 0.1067672 -0.02883905 0.057244 0.1060213 -0.02869153 0.05743986 0.1052542 0.02372968 0.0567258 0.1075065 -0.02850282 0.05768889 0.1037764 -0.02844727 0.05776154 0.102861 -0.03033429 0.05517995 0.1102827 -0.02951413 0.05632954 0.1083765 -0.02928316 0.05664575 0.1076959 -0.02923184 0.05671483 0.1075025 -0.03389471 0.02978479 0.1421033 -0.03270107 0.03231537 0.1409059 -0.03091442 0.03400611 0.1391139 -0.03599596 0.03410536 0.1353074 -0.04081386 0.03516089 0.1316395 -0.04335612 0.02904057 0.1335014 -0.04408764 0.03062099 0.1325588 -0.04370433 0.03153377 0.1326403 -0.04535579 0.03494608 0.1297174 -0.0456385 0.03647041 0.1286519 -0.04495096 0.03703504 0.1284528 -0.04438406 0.0312609 0.1321769 -0.04462426 0.03198266 0.1317155 -0.04241919 0.03354823 0.1324056 -0.03892743 0.03007358 0.1372559 -0.04314661 0.02866071 0.133718 -0.04503506 0.03321582 0.1309269 -0.04494017 0.0370419 0.128448 -0.03768026 0.03238999 0.1365749 -0.03156054 -0.03875494 0.1397619 -0.03357625 -0.03589987 0.1417837 -0.04084575 -0.03970581 0.1323781 -0.04314661 -0.0338608 0.133718 -0.03809404 -0.03602653 0.1375492 -0.04330313 -0.03414273 0.1335574 -0.04373908 -0.03505337 0.1330188 -0.04482537 -0.03770828 0.1313888 -0.04422897 -0.03607672 0.1324134 -0.04279333 -0.03722721 0.1331208 -0.04486638 -0.04143518 0.1291161 -0.04555714 -0.04096508 0.1291674 -0.04493963 -0.03821718 0.1310416 -0.04245394 -0.04258865 0.1285353 -0.04311174 -0.04234558 0.1287515 -0.04481512 -0.04147005 0.1291123 -0.0421639 -0.04267954 0.1284273 -0.03611367 -0.03876507 0.1361694 -0.05129623 0.02982223 0.1145659 -0.05050379 0.03536212 0.1193485 -0.05035006 0.03643596 0.1202756 -0.04894691 0.04042047 0.117409 -0.04849421 0.04118388 0.1168597 -0.04553651 0.04617232 0.1132709 -0.04525977 0.04645526 0.1130674 -0.05049669 -0.0358662 0.1197836 -0.04919636 -0.03983587 0.1232108 -0.04902642 -0.04023814 0.1228587 -0.05055671 -0.03537136 0.1193565 -0.04874342 -0.04087167 0.1223154 -0.04853761 -0.04120874 0.1220265 -0.04527992 -0.04647475 0.1175115 -0.04538226 -0.04637116 0.1176003 -0.04570192 -0.03652417 0.1307811 -0.04747051 -0.03901177 0.1281318 -0.04756319 -0.0390349 0.1279706 -0.04315149 0.02865099 0.133713 -0.04315149 -0.03385102 0.133713 -0.04335868 -0.03403913 0.133504 -0.04342973 0.02890473 0.1334311 -0.04468864 -0.03536111 0.1320466 -0.0449357 0.03043085 0.1317518 -0.04611361 0.03184425 0.1302204 -0.04912388 0.03567963 0.1248356 -0.0487414 0.03538316 0.125702 -0.05031585 -0.03543454 0.1212441 -0.04961609 0.03594619 0.1235824 -0.05035006 0.03544974 0.1212618 -0.0502994 0.03558987 0.1214479 -0.05025196 0.03568905 0.1216177 -0.05007064 0.0359041 0.1222314 -0.04979825 0.0359801 0.1230682 -0.04833859 0.03504395 0.1265376 -0.04816627 0.03487634 0.1268746 -0.0478127 0.03438663 0.1275324 -0.0477215 -0.03907424 0.1276956 -0.0475434 0.03398364 0.1279584 -0.04832309 -0.03909832 0.1265684 -0.04850387 -0.03905421 0.1262032 -0.04886591 -0.03884357 0.1254287 -0.0489664 -0.0387417 0.1252019 -0.04919636 -0.03838503 0.1246618 -0.05049669 -0.03495776 0.120692 -0.05129623 0.02974009 0.1146481 -0.05035108 0.0354442 0.1212555 -0.04763925 -0.04155451 0.1258822 -0.04758214 -0.04158574 0.1259614 -0.04526644 -0.04259872 0.1273844 -0.04642421 -0.04192394 0.1273351 -0.04879003 -0.04057854 0.1240618 -0.04746979 -0.04212766 0.1250081 -0.04860597 -0.04081279 0.1243987 -0.04792714 -0.04139661 0.1254815 -0.04511731 -0.04227596 0.1280414 -0.04551959 -0.04212838 0.1279354 -0.0459401 -0.04197394 0.1278245 -0.04322248 -0.04264962 0.1283492 -0.04248952 -0.04268771 0.1284046 -0.04216647 -0.04268658 0.1284181 -0.04780799 -0.041462 0.1256473 -0.04493516 -0.04314833 0.1267825 -0.04467409 -0.04364609 0.1262195 -0.04717624 -0.04268997 0.1244482 -0.04169416 -0.04794603 0.1213476 -0.0438314 -0.04754108 0.1196019 -0.03948765 -0.05132859 0.1156055 -0.038773 -0.05154997 0.1165369 -0.03786486 -0.05129462 0.1172701 -0.03597724 -0.05360049 0.1141813 -0.03307247 -0.05549496 0.1120045 -0.03284323 -0.05568045 0.1117209 -0.03196179 -0.05637544 0.1104601 -0.03127139 -0.05690032 0.1091586 -0.03091353 -0.05716592 0.1082486 -0.03061705 -0.05738252 0.1071653 -0.03049033 -0.05747407 0.1063907 -0.03043121 -0.05751687 0.1053854 -0.04623359 0.03742551 0.1275444 -0.04491984 0.03796339 0.1273701 -0.04598426 0.03788697 0.1271647 -0.04652369 0.03775215 0.1269771 -0.04728537 0.03790527 0.1261345 -0.04802292 0.03799408 0.1251822 -0.04663121 0.03850895 0.1259827 -0.04586631 0.03828305 0.1267554 -0.04725664 0.03789955 0.1261662 -0.04568874 0.03857553 0.1262428 -0.04932302 0.03785049 0.1229361 -0.04984432 0.0374552 0.1217749 -0.04742574 0.04213535 0.1197935 -0.05017971 0.0369215 0.1208559 -0.05026382 0.03671288 0.1205852 -0.04489433 0.04297691 0.1217492 -0.04897135 0.03797185 0.1236145 -0.0491324 0.0379163 0.1233035 -0.04186397 0.04751372 0.1174377 -0.04402494 0.04724836 0.1155099 -0.03789216 0.05103403 0.1138041 -0.03881317 0.05138808 0.1130131 -0.0395143 0.05122071 0.111974 -0.03630328 0.05324393 0.111225 -0.03370428 0.0549736 0.1095581 -0.03043121 0.05751687 0.1022255 -0.0304436 0.05750787 0.1026875 -0.03050589 0.05746299 0.1033539 -0.03071755 0.05730938 0.1044334 -0.03088295 0.05718839 0.1049968 -0.03138256 0.05681705 0.1062381 -0.03164315 0.05661988 0.1067486 -0.03257262 0.05589663 0.1082059 0.05256801 -0.03497642 0.1030874 0.05220091 -0.03645902 0.1029123 0.0516023 -0.03853195 0.1026605 0.05187338 -0.037781 0.1027563 0.0481522 -0.04410696 0.1018306 0.04848796 -0.04372829 0.1018955 0.05027061 -0.04125875 0.1022844 0.05061882 -0.0405457 0.1023828 0.04938817 -0.034487 0.1121425 0.04924303 -0.03398633 0.1124943 0.05117887 -0.03328466 0.1098269 0.04901379 -0.03330683 0.1129065 0.05107146 -0.03274905 0.1101543 0.04825311 -0.03134948 0.1139029 0.05071204 -0.03118598 0.1109677 0.05226773 -0.03099089 0.1074704 0.05236083 -0.03210681 0.106985 0.05238842 -0.03248459 0.1067852 0.05226826 -0.03334188 0.1062144 0.04970574 -0.0355829 0.1113727 0.05123919 -0.03449594 0.1088708 0.05200344 -0.03395432 0.107624 0.04814553 -0.04411447 0.1018483 0.04841852 -0.04380643 0.1020787 0.04987257 -0.0417937 0.1034651 0.04813855 -0.04412192 0.101866 0.04834657 -0.04388236 0.1022619 0.04936403 -0.04225498 0.1046347 0.04961788 -0.04143708 0.1056239 0.05097454 -0.03954035 0.1048309 0.05120283 -0.03891021 0.1051848 0.05007237 -0.0377596 0.1095414 0.0517984 -0.03650748 0.1064391 0.05006515 -0.03815567 0.1091517 0.05003529 -0.03981816 0.1075161 0.04995352 -0.04035615 0.1069315 0.05004286 -0.03758507 0.1096881 0.03065121 -0.05700874 0.1045336 0.03145664 -0.056804 0.1044375 0.03217154 -0.05654025 0.1043473 0.03522074 -0.05498701 0.1039363 0.03488838 -0.05519372 0.1039834 0.02859157 -0.05753231 0.1047793 0.0431661 -0.04099214 0.1172528 0.04913949 -0.03481853 0.1123751 0.03753006 -0.0443511 0.1222203 0.03667867 -0.04297286 0.1234142 0.04368412 -0.04491633 0.1140317 0.03946745 -0.0483545 0.1172034 0.03929919 -0.04793673 0.1179324 0.038522 -0.0462616 0.120237 0.03789222 -0.04504859 0.1214963 0.04308849 -0.04816651 0.1101427 0.04008108 -0.05015802 0.1134037 0.03969299 -0.04891514 0.1162249 0.03996527 -0.05164164 0.1068347 0.04018265 -0.05117928 0.1098672 0.04019266 -0.05105656 0.1104144 0.04012858 -0.0505414 0.1121283 0.02713006 -0.05732113 0.1082895 0.02967697 -0.05711019 0.1070574 0.03522861 -0.05498182 0.103954 0.03523659 -0.05497682 0.1039716 0.03495275 -0.05515342 0.104125 0.03501617 -0.05511164 0.1042667 0.03269433 -0.05627351 0.1054518 0.03317147 -0.05590373 0.1065472 0.03209716 -0.05649435 0.1057834 0.0326749 -0.05602961 0.1071129 0.03196758 -0.05610126 0.1078608 0.0306468 -0.05623471 0.1092572 0.02850884 -0.05598551 0.1112694 0.02609932 -0.05721676 0.1090459 0.02544641 -0.05713582 0.1094457 0.02826017 -0.05592077 0.1114697 0.02696365 -0.05558323 0.1125143 0.02600669 -0.05527395 0.1131734 0.03601902 -0.05047082 0.1177985 0.03611814 -0.05052947 0.1176214 0.03110003 -0.0542066 0.1134456 0.03995603 -0.05164867 0.1068344 0.03933125 -0.05183786 0.1098392 0.03460729 -0.05453044 0.1095166 0.03918617 -0.05183482 0.1103808 0.03695929 -0.05102777 0.1161179 0.03820711 -0.05160665 0.1133357 0.0385347 -0.05168288 0.1123471 0.03446227 -0.04939699 0.1200618 0.0481522 0.04410696 0.1018306 0.05009996 0.04153782 0.102243 0.05220079 0.03645896 0.1029123 0.05187124 0.03778737 0.1027555 0.0514816 0.03883582 0.102621 0.05061018 0.04054003 0.1023826 0.0525673 0.03498154 0.1030868 0.04814553 0.04411447 0.1018483 0.04813855 0.04412192 0.101866 0.04973286 0.04202193 0.1033169 0.04927498 0.04244387 0.1043822 0.05087357 0.03979378 0.1046853 0.04961746 0.04143589 0.1056246 0.0499112 0.04057204 0.1066895 0.05120086 0.03891563 0.1051818 0.05003488 0.03982281 0.1075112 0.0517975 0.03651207 0.1064368 0.05244404 0.03335398 0.1062422 0.05191928 0.0339424 0.1075966 0.05139458 0.03453075 0.108951 0.05006539 0.03815573 0.1091518 0.05007261 0.03776341 0.1095378 0.04970574 0.0355829 0.1113727 0.05240094 0.03266441 0.106683 0.05122727 0.03354102 0.1096603 0.05233001 0.03171676 0.1071714 0.05095267 0.0321995 0.1104633 0.0493974 0.03449314 0.1121537 0.04934644 0.03431308 0.1122828 0.04876118 0.03261411 0.1132906 0.02862632 0.05752635 0.101491 0.03065013 0.05700558 0.1012272 0.03522253 0.05498582 0.1005757 0.03256201 0.05638116 0.1009694 0.03152292 0.05678099 0.1011136 0.04319083 0.04886972 0.1059392 0.04436475 0.04701495 0.1092699 0.04331934 0.04855602 0.1078917 0.04324764 0.04796242 0.110002 0.04251432 0.04588663 0.1148685 0.04274505 0.04637181 0.1140457 0.04485356 0.04383409 0.1131448 0.04317849 0.04756873 0.11129 0.04321831 0.04771864 0.1108688 0.04203766 0.04488444 0.1165678 0.044245 0.04001504 0.1163721 0.04175853 0.0443564 0.1173099 0.03901308 0.03988939 0.1216498 0.03957146 0.04069811 0.1210497 0.04076617 0.04261672 0.1193519 0.04090321 0.04285669 0.1190702 0.043123 0.04903537 0.1049082 0.02518481 0.05697536 0.1067606 0.0273422 0.05725848 0.1051869 0.02890366 0.05574429 0.1082786 0.02729022 0.05525302 0.1097043 0.02625328 0.05713027 0.1060672 0.02705651 0.0551638 0.1098733 0.02575284 0.05466538 0.1108162 0.03523141 0.05498015 0.1005934 0.0330832 0.05610775 0.1019827 0.03223991 0.05643302 0.1024954 0.03524005 0.05497467 0.1006111 0.03356188 0.05574464 0.1029886 0.03288626 0.05591553 0.1038589 0.03282845 0.05591976 0.1039271 0.02985846 0.057047 0.103861 0.0300523 0.05592107 0.1070802 0.030954 0.05606007 0.1061393 0.03672719 0.04616534 0.119262 0.03274279 0.05146867 0.1134922 0.03794556 0.04702025 0.1177703 0.03838002 0.04732519 0.1172384 0.03578186 0.05227226 0.1104627 0.04033374 0.04849094 0.1139987 0.03888714 0.0476529 0.1165022 0.04209882 0.04914349 0.1094316 0.04168075 0.04907006 0.1108412 0.04152822 0.04901945 0.1112599 0.040398 0.04851931 0.1138516 0.03844338 0.05217069 0.1070038 0.0425592 0.04922419 0.1078793 0.04311448 0.04904294 0.1049081 0.01186376 0.03408235 0.1389935 0.01328194 0.03260827 0.1406834 0.01422929 0.03040218 0.1418126 0.02313512 0.03525072 0.1316077 0.02796143 0.03716307 0.1283876 0.02917236 0.03784453 0.1275753 0.02917736 0.03593796 0.1287664 0.03037708 0.03668898 0.1278555 0.03022325 0.03451323 0.1287681 0.03142774 0.03536361 0.1277822 0.02440023 0.03383719 0.13238 0.02542442 0.0320912 0.132692 0.01765209 0.0341975 0.1352275 0.01898342 0.03269755 0.136447 0.01997596 0.03068584 0.1371375 0.03652161 0.0418446 0.1226999 0.03705126 0.04244881 0.1221604 0.03753519 0.04307615 0.1215919 0.03900188 0.04469126 0.1196967 0.04311883 0.04903924 0.1049081 0.04295164 0.04890424 0.1078882 0.04249835 0.04845041 0.1108766 0.04240942 0.0483585 0.1113016 0.04165297 0.04756247 0.1141048 0.04064232 0.04647779 0.116719 0.04027009 0.0460745 0.1175011 0.01397657 -0.03639996 0.1415112 0.01237654 -0.03888893 0.1396045 0.01945215 -0.03656834 0.1371629 0.01788407 -0.03894352 0.13585 0.02800965 -0.04178673 0.1288152 0.02325761 -0.03993314 0.1321349 0.02952855 -0.03997629 0.1291065 0.02479839 -0.03779077 0.132896 0.03409039 -0.04318827 0.1252788 0.03257143 -0.04499852 0.1249874 0.03382951 -0.04624062 0.1236028 0.03452885 -0.04707378 0.1224251 0.03543138 -0.04474544 0.1237837 0.03611791 -0.04584687 0.1224969 0.03541588 -0.04659038 0.1226344 0.03672295 -0.04814589 0.1204645 0.03782516 -0.04942744 0.1180307 0.03996062 -0.0516451 0.1068345 0.03976982 -0.05152541 0.1098561 0.03920412 -0.05096149 0.1134006 0.03970742 -0.05146896 0.1104024 0.03844726 -0.05013293 0.1162669 -0.04566252 -0.04124265 0.1287978 -0.05041342 0.03595125 0.1207772 -0.04876077 0.03691041 0.1251135 -0.04942876 0.03700119 0.1236533 -0.05034667 0.03616142 0.1210269 -0.05028373 0.03631681 0.121249 -0.05004143 0.03669822 0.1220244 -0.04967486 0.03694719 0.1230419 -0.04770296 0.03654605 0.126968 -0.04824393 0.03675109 0.1260715 -0.0474587 0.03628826 0.1274343 -0.04695683 0.03553617 0.1283407 -0.04314911 0.02865594 0.1337155 -0.04339361 0.02897268 0.133467 -0.04468727 0.03085023 0.1319916 -0.04565644 0.03255218 0.1306561 -0.04933184 -0.03913837 0.1239643 -0.05055058 -0.03541857 0.1202445 -0.04663461 -0.04110699 0.1280593 -0.04699128 -0.04066175 0.12818 -0.04694032 -0.04072529 0.1281628 -0.04733628 -0.04063999 0.1276822 -0.04724037 -0.03980404 0.1281549 -0.04815769 -0.04042637 0.1263604 -0.04840272 -0.0402956 0.1259202 -0.04889065 -0.03987383 0.124962 -0.04902547 -0.03970003 0.1246733 -0.04665154 -0.04091459 0.1283932 -0.04676038 -0.03999608 0.128803 -0.04664677 -0.04011696 0.1288698 -0.04670727 -0.04006981 0.1288533 -0.04314911 -0.03385597 0.1337155 -0.04447883 -0.0357216 0.1322499 -0.0433312 -0.03409087 0.1335312 -0.04532253 -0.0371297 0.1311439 -0.02489769 -0.03469491 0.1544765 + + + + + + + + + + 0.9950376 0.005755543 -0.09933358 -0.8220834 0 0.5693671 -0.8220867 0 0.5693625 -0.5876519 0 0.809114 -0.5876528 0 0.8091133 -0.5877006 0 0.8090785 -0.1908943 0 0.9816107 -0.1909356 0 0.9816026 -0.1908935 0 0.9816108 -0.1908788 0 0.9816137 0.241673 0 0.9703578 0.2416089 0 0.9703737 0.241629 0 0.9703688 0.2416282 0 0.970369 0.6290388 0 0.7773739 0.6290943 0 0.777329 0.6289438 0 0.7774507 0.9997726 -0.02022182 -0.006787359 0.9982295 0.02757477 -0.05270367 0.9975268 -0.03994768 0.05783313 0.997879 0.05626046 -0.03274643 0.9872372 -0.05694133 0.1487295 0.9962865 -0.005209445 0.08594256 0.9804967 0.01076143 0.1962407 0.9769554 0.002768933 0.2134257 0.959733 -0.001967549 0.280907 0.9463486 -0.01221185 0.3229169 0.9612178 -0.01219707 0.2755206 0.9466413 -0.01510077 0.3219354 0.9291437 -0.01333087 0.3694784 0.9442678 0.006386101 0.3291166 0.9255114 0.01103681 0.378559 0.8949343 -0.005238294 0.4461674 0.881672 0.001561045 0.4718602 0.830527 -0.004730641 0.5569586 0.8268031 0 0.5624915 0.6285328 0 0.7777832 0.6289432 0 0.7774514 0.9981195 0.005761444 -0.06102627 0.9422351 -0.07647776 -0.3261044 0.9697089 0.07555103 -0.2322862 0.9468732 -0.1003799 -0.3055407 0.9768778 -0.01328957 -0.2133852 0.9571335 0.05334639 -0.2846924 0.9547276 0.0244261 -0.2964771 0.9489455 0 -0.31544 0.9489459 0 -0.3154388 0.9513981 -0.00988394 -0.3078051 0.9538764 -0.02332812 -0.2992922 0.9355302 0.06459879 -0.3472899 0.9677565 -0.04159557 -0.2484296 0.9444304 0.106975 -0.3108177 0.9739196 0.01152175 -0.2266007 0.9969094 -0.004838407 -0.07841217 0.9971526 -0.005245685 -0.07522791 0.9968106 -0.005246043 -0.07963043 0.996827 -0.005268275 -0.07942384 0.9931725 0.07735002 0.0873236 0.9995834 0.01745909 0.0229873 0.998165 0.00488317 -0.06035679 0.9994894 0.03057903 0.00927186 0.9984411 0.01225078 -0.05445533 0.9662733 0.002929389 0.2575023 0.9664035 0.002882003 0.2570138 0.9220731 -0.002137005 0.38701 0.9270734 -0.01096642 0.3747196 0.8637771 0.0185908 0.5035311 0.8773838 -0.01295602 0.4796144 0.8028253 0.006625771 0.5961775 0.8107599 0 0.5853788 0.7770649 0 0.6294206 0.9943635 -0.1050298 0.0144959 0.9943593 -0.004568517 0.1059659 0.9660085 0.004306793 0.2584748 0.9663894 0.003311932 0.2570618 0.9658665 0.003312885 0.2590196 0.9657675 0.003332853 0.2593882 0.7770637 0 0.629422 0.6331031 0 0.7740675 0.633098 0 0.7740717 0.2881883 0 0.9575738 -0.100682 0 0.9949188 -0.1006763 0 0.9949193 -0.4742118 0 0.8804108 -0.4742131 0 0.8804102 -0.7753536 0 0.6315275 -0.7660384 0 0.6427949 -0.7660368 0 0.6427969 -0.7660835 0 0.6427412 -0.7660803 -4.803e-6 0.642745 -0.7660464 0 0.6427853 -0.7660447 0 0.6427873 -0.7660591 0 0.6427702 -0.7660469 -7.05027e-6 0.6427848 -0.7660542 -7.21229e-6 0.6427761 -0.7660405 -1.86057e-5 0.6427925 -0.7660565 -2.38484e-5 0.6427733 -0.7660632 -1.05338e-5 0.6427654 -0.7660383 -3.00092e-7 0.6427951 -0.7660412 0 0.6427915 -0.766047 0 0.6427847 -0.7660425 3.54029e-5 0.64279 -0.7660568 2.00809e-5 0.642773 -0.76604 -3.66928e-5 0.6427929 -0.7660342 2.89577e-6 0.6427999 -0.7660572 4.66972e-5 0.6427725 -0.7660565 -5.20398e-5 0.6427733 -0.766067 -4.29326e-5 0.6427608 -0.7660683 -2.69593e-5 0.6427593 -0.7660477 -6.1849e-5 0.6427837 -0.7660654 6.399e-6 0.6427626 -0.7660593 5.07097e-6 0.6427699 -0.7060216 0 0.7081903 -0.7060357 1.362e-6 0.7081763 -0.7060304 1.46356e-6 0.7081816 -0.7060278 6.96131e-7 0.7081843 -0.7060315 7.3101e-7 0.7081806 -0.7060284 0 0.7081835 -1 0 0 1 -7.73118e-6 0 1 0 0 1 1.48684e-7 0 1 -1.40001e-5 0 1 -9.48068e-6 0 1 6.41107e-6 0 0.642781 6.68336e-6 0.7660501 0.6427839 0 0.7660476 0.6427921 0 0.7660408 0.6427906 0 0.766042 0.6427813 -8.39864e-7 0.7660499 0.6427909 1.71853e-6 0.7660419 0.6427804 -2.00508e-6 0.7660506 0.6428084 1.08326e-5 0.766027 0.6428179 1.17191e-5 0.7660191 0.6427835 -6.05333e-7 0.766048 0.6427851 -1.31419e-5 0.7660466 0.6427838 0 0.7660476 0.6427849 0 0.7660468 0.6427909 0 0.7660417 0.6427854 0 0.7660464 0.6427874 -4.04328e-7 0.7660446 0.6427823 -3.68401e-7 0.766049 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -3.53641e-6 0.7071061 0.7071076 9.17293e-5 0.7071503 0.7070632 6.80344e-6 0.7071051 0.7071085 -7.37263e-5 0.7070677 0.707146 1.59623e-5 0.7071109 0.7071027 0 0.7071087 0.7071049 -1.01766e-5 0.7070869 0.7071267 -2.00941e-6 0.7071094 0.7071042 -2.86448e-7 0.7071117 0.7071019 0 0.7071182 0.7070955 -0.04731392 -0.8077765 0.5875871 0 -0.8338955 0.5519226 0.00895965 -0.9308384 0.3653215 -0.01122385 -0.7842248 0.6203753 1.37794e-5 -0.8878681 0.4600984 -0.470973 -0.04199963 0.8811474 0 -0.9999908 0.004307448 1.52196e-5 -0.937154 0.3489159 0.005375444 -0.9907463 0.1356201 -0.01499783 -0.9317055 0.362905 2.76346e-4 -0.9934419 0.1143382 0 -0.7660678 0.6427597 -7.18207e-7 -0.7660382 0.642795 1.19586e-6 -0.7660496 0.6427815 7.25874e-6 -0.7660479 0.6427835 -4.90581e-5 -0.7660273 0.6428081 1.05584e-6 -0.766047 0.6427847 0 -0.7660469 0.6427847 1.27175e-6 -0.7660481 0.6427834 0 -0.7660443 0.6427878 1.65648e-5 -0.7660512 0.6427796 0.9894416 0 0.144932 0.9063109 0 0.4226117 0.7470157 0 0.6648065 0 1 -3.55509e-6 0 1 8.25919e-6 0 1 -7.92037e-6 0 1 1.75195e-6 0 1 5.74236e-6 0 1 -2.07648e-5 0 1 2.74355e-6 0 1 -4.96954e-6 0 1 1.66653e-7 0 1 9.79065e-7 0 0.7351182 0.6779389 -0.01388692 0.7450162 0.666902 0.002143323 0.8302304 0.5574163 0 0.9930288 0.1178725 2.05267e-5 0.9930672 0.1175491 -2.03608e-5 0.9378943 0.3469215 1.65784e-5 0.9382541 0.345947 1.66442e-5 0.9378817 0.3469554 3.45041e-5 0.9382691 0.3459064 -3.26849e-5 0.8313015 0.5558217 -0.006819128 0.734613 0.6784521 -0.1064887 0.7330369 0.6718015 0 -1 2.28222e-5 0 -1 -1.64751e-6 0 -1 -3.84772e-6 0 -1 1.49258e-6 0 -1 -9.46393e-7 0.6837441 -0.7296651 -0.009104907 0.6213081 -0.7835603 -0.003104388 0.5943258 -0.8042235 -0.00121653 0.5578485 -0.8299428 0 0.5931819 -0.8050683 5.83094e-4 0.6917701 -0.7221176 5.87191e-4 0.6866042 -0.7270315 0 0.6995885 0.714546 0 0.6917694 0.7221181 -7.50195e-4 0.6417165 0.766942 1.91621e-4 0.5931823 0.8050682 0 0.5826107 0.8127508 -0.001129984 0.6417682 0.7668988 1.91563e-4 -0.6045322 -0.7965809 0 -0.5596345 -0.8287374 -0.001883804 -0.5624385 -0.8268392 0 -0.5355077 -0.8445215 -0.003886878 -0.5274299 -0.8495863 -0.004575073 -0.5266605 -0.8500671 -0.003853559 -0.5084918 -0.8610472 -0.005836427 -0.5079631 -0.8613733 -0.003100872 -0.5113438 -0.8593751 0.001415073 -0.5107244 -0.8597217 -0.006273031 -0.5052831 -0.8629528 -0.001296699 -0.5075222 -0.8616292 -0.004045188 -0.6067997 0.7948548 0 -0.5127059 0.8585371 -0.006845593 -0.5132713 0.8581784 -0.009085714 -0.5124404 0.8586938 -0.007057368 -0.5102149 0.8600398 -0.003548026 -0.5078989 0.8614165 -6.97523e-4 -0.5406818 0.8411763 -0.009245395 -0.5203518 0.8539493 0.002158701 -0.5138568 0.8578721 -0.002578437 -0.5072686 0.8617881 0 -0.5624383 0.8268383 -0.001241207 -0.5358971 0.8442743 -0.003922283 -0.5664532 0.8240925 -0.001574158 0 -0.9989562 0.04568046 0.00357455 -0.9848011 0.1736493 0.006622254 -0.9908211 0.1350178 0.001812696 -0.9739902 0.2265831 0 -0.7767144 0.629853 9.11382e-4 -0.831941 0.5548635 0.008593618 -0.9008186 0.4341108 0.001574039 -0.8660252 0.4999978 -3.52559e-4 -0.9459331 0.3243619 -3.52621e-4 -0.9458741 0.3245338 7.51509e-4 0.902967 0.4297094 -7.01715e-4 0.8493903 0.5277649 -6.97943e-4 0.7933712 0.6087378 0.006779491 0.8480839 0.5298186 0 0.759152 0.6509134 0 0.9914445 0.1305291 0.008615255 0.9996966 0.02307826 0.004618167 0.9964677 0.08385163 8.65444e-4 0.98533 0.1706578 -1.58309e-4 0.9678329 0.251594 -1.57066e-4 0.9238806 0.3826807 0.0106765 0.9673413 0.2532529 0.004094362 0.9399268 0.3413516 -0.06360059 0.9959341 0.06379902 -0.1559113 0.9804605 0.1199534 -0.1751464 0.9722471 0.1551105 -0.4266133 0.8012214 0.4195779 -0.3796803 0.8651333 0.3276998 -0.3363991 0.9144563 0.2249564 -0.392855 0.8314783 0.3928217 -0.2526634 0.93187 0.2603455 -0.2527253 0.9318348 0.2604112 -0.6483615 0.3900149 0.653847 -0.5989162 0.5440149 0.5876625 -0.5613936 0.6615862 0.4971327 -0.5911337 0.555547 0.5847466 -0.5087574 0.6908396 0.5137185 -0.5086797 0.6909514 0.5136452 -0.725552 0.07770854 0.6837658 -0.6926415 0.1950972 0.6943953 -0.706067 0.00610274 0.7081187 -0.7255189 0.07782161 0.6837881 -0.7258061 0.07667714 0.6836126 -0.6979455 0.206068 0.685863 -0.6979181 0.2061711 0.6858599 -0.6979379 0.2061142 0.685857 -0.680009 0.2819172 0.6768386 -0.6802427 0.2809128 0.6770213 -0.6747004 0.3023684 0.6733148 -0.648367 0.3899897 0.6538566 -0.122294 0.8363899 0.5343183 -0.04342037 0.7918171 0.6092131 -0.7051614 0.004644274 0.7090317 -0.6659364 0.1700938 0.7263587 -0.6446383 0.06508815 0.761712 -0.6551575 0.1371848 0.7429327 -0.4836565 0.4025048 0.7772171 -0.6141954 0.2772271 0.7388567 -0.6142191 0.2772039 0.7388457 -0.1771982 0.5119812 0.8405214 -0.2637505 0.5667873 0.780505 -0.127066 0.7103157 0.6923192 -0.08432829 0.6731783 0.7346562 -0.124075 0.7132067 0.6898851 -0.1689853 0.7485148 0.6412251 -0.2992682 0.5964178 0.7447983 -0.2829875 0.6314035 0.7219749 -0.4800443 0.4503617 0.7528161 -0.4800779 0.4503144 0.7528228 -0.0480163 0.9048722 0.4229665 -0.1532611 0.8871292 0.4353307 -0.2948703 0.7399825 0.6045474 -0.3869117 0.6842326 0.6181627 -0.5067067 0.4842425 0.7132725 -0.5549858 0.4389012 0.7066516 -0.6496239 0.1945256 0.734948 -0.6030995 0.1717051 0.7789663 -0.05572164 0.9743306 0.2181168 -0.197062 0.9411394 0.2746329 -0.3212282 0.8275046 0.4604874 -0.4167806 0.7696944 0.4835953 -0.538283 0.5543092 0.6348171 -0.586485 0.503582 0.634382 -0.6729661 0.1950265 0.7134993 -0.6847487 0.1746059 0.7075536 -0.7206225 -0.2677015 0.6395617 -0.6774943 -0.2915056 0.675297 -0.6800277 -0.2818422 0.676851 -0.6979039 -0.2062738 0.6858434 -0.697927 -0.206126 0.6858644 -0.6979414 -0.2060861 0.6858618 -0.7258644 -0.07615447 0.6836091 -0.7059747 -0.006139397 0.7082105 -0.6926362 -0.1951106 0.6943969 -0.7255523 -0.07770973 0.6837655 -0.7255163 -0.07782137 0.6837909 -0.59668 -0.552914 0.5816005 -0.6440277 -0.4025795 0.6505062 -0.6440669 -0.4024515 0.6505465 -0.359409 -0.887075 0.289695 -0.3928833 -0.8314635 0.3928248 -0.4215705 -0.8091214 0.4093911 -0.4994727 -0.7028509 0.5064855 -0.5843468 -0.5555599 0.5915167 -0.5573503 -0.671431 0.4884065 -0.5573045 -0.6715832 0.4882497 -0.1377313 -0.9807877 0.1381507 -0.09650379 -0.9953146 -0.006000638 -0.1535551 -0.9800594 0.1261129 -0.225322 -0.9484027 0.223075 -0.3050987 -0.9004736 0.3099388 -0.3050812 -0.9004862 0.3099197 -0.5941178 -0.1640812 0.7874653 -0.02952355 -0.8243489 0.5653118 -0.1083369 -0.7851912 0.6097032 -0.4975883 -0.4150392 0.7616748 -0.3489897 -0.5874434 0.7301483 -0.278786 -0.6346229 0.7207859 -0.2382723 -0.701964 0.6711728 -0.2382471 -0.7020047 0.6711392 -0.5940985 -0.1640748 0.787481 -0.622657 -0.244901 0.7431835 -0.5293283 -0.4291081 0.7319002 -0.4795771 -0.3162354 0.8185359 -0.4976261 -0.4149711 0.7616872 -0.6666886 -0.1709187 0.7254744 -0.6437684 -0.05581533 0.7631821 -0.1273173 -0.9311218 0.341764 -0.1196153 -0.9804684 0.1561222 -0.3695542 -0.7626188 0.5308881 -0.3662939 -0.8309144 0.4188202 -0.5602205 -0.4991996 0.661024 -0.5640921 -0.5552803 0.6111169 -0.6764601 -0.1732037 0.7158228 -0.6810945 -0.1950859 0.7057279 -0.3468223 -0.6699903 0.6563745 -0.3345993 -0.7540482 0.5652033 -0.5330846 -0.4309529 0.72808 -0.529796 -0.491948 0.6908715 -0.6595892 -0.1610015 0.7341803 -0.6449754 -0.06160491 0.7617163 -0.03557997 -0.806615 0.5900055 -0.05163502 -0.8032745 0.5933667 -0.1818318 -0.867352 0.4632902 -0.04914379 -0.9075878 0.4169765 -0.04912132 -0.9075886 0.4169775 -0.7096832 0.704521 0 -0.8481008 0.5298349 -1.81099e-4 -0.7121233 0.7020545 1.86004e-4 -0.7118332 0.7023486 1.85989e-4 -0.9896626 0.1434118 9.66504e-4 -0.9408232 0.3388965 -0.001002371 -0.9443995 0.3288002 -4.36006e-4 -0.8539496 0.5203556 4.59167e-4 -0.8539534 0.5203492 4.5921e-4 -0.9937715 0.1114377 0 -0.999828 0.01771342 -0.005500257 -0.9896597 0.1434325 9.66506e-4 -0.8448712 -0.5348267 -0.01237756 -0.9353485 -0.3491603 -0.05665951 -0.4484603 -0.59008 -0.6713339 -0.9310904 -0.3541482 -0.08746349 -0.9443994 -0.3288006 5.0036e-6 -0.8481007 -0.5298351 5.02995e-6 -0.8475921 -0.5306484 5.76574e-5 -0.7096832 -0.704521 0 -0.7089865 -0.7052221 -5.81315e-5 -0.8467468 -0.5319961 5.76479e-5 -0.9465579 -0.3225339 3.58906e-4 -0.9930568 -0.1176353 3.65803e-4 -0.9937715 -0.1114377 0 -0.70639 0 0.7078228 -0.706337 0 0.7078757 -0.7107393 0 0.7034556 -0.7117462 7.51579e-6 0.7024368 -0.7385806 -6.05262e-5 0.6741652 -0.7444176 2.13821e-4 0.6677144 -0.7815247 -1.48572e-4 0.6238744 -0.7934134 2.60639e-4 0.6086832 -0.9018636 -0.007840573 0.4319498 -0.920252 0.002224147 0.3913199 -0.9145559 0.001654624 0.4044562 -0.9067414 9.99958e-4 0.421686 -0.8970443 4.65436e-4 0.4419404 -0.8835666 -9.22451e-6 0.4683056 -0.8460088 2.76062e-5 0.533169 -0.8680078 3.23637e-4 0.4965505 -0.8459222 3.24057e-4 0.5333064 -0.8682215 0.002033591 0.4961727 -0.8323314 -4.7111e-4 0.5542783 -0.9496064 0.00614351 0.3133845 -0.8834015 -0.01148951 0.4684759 -0.8912643 -0.00989902 0.4533764 -0.964733 -7.07932e-4 0.2632297 -0.9155145 -0.005495369 0.4022474 -0.9302163 -0.003309071 0.3669972 -0.942059 -0.002009987 0.3354412 -0.9508472 -0.001230478 0.3096583 -0.9585296 -8.33711e-4 0.2849918 -0.9626063 -7.32414e-4 0.2709035 -0.9999113 0 0.01332229 -0.9888637 -6.87679e-4 0.1488225 -0.9894723 -6.88009e-4 0.1447205 -0.9463517 0.01897042 0.3225814 -0.9931546 -0.001410543 0.1167995 -0.1857454 -0.8189323 0.5429996 -0.2440139 -0.9330472 -0.2643484 -0.9052723 -0.4220222 0.04878127 -0.7694399 -0.6369336 -0.04772883 -0.7161278 -0.6921623 -0.08984637 -0.7758363 -0.6166113 0.1336738 -0.4125004 -0.7741426 0.4801528 -0.4779449 -0.7980849 0.3669186 -0.4568091 -0.881818 0.1171434 -0.02094888 -0.9985585 -0.04941713 -0.2515283 -0.8547366 0.4540474 -0.412625 -0.7741354 0.4800576 -0.002801895 -0.7971953 0.6037151 -0.01956504 -0.8163065 0.5772875 0.01652711 -0.9880759 -0.1530785 -0.2190686 -0.7700795 0.5991548 -0.5577467 -0.7479653 0.3598145 -0.5589547 -0.7410169 0.3721072 -0.7351045 -0.6220563 0.269569 -0.7349585 -0.6221544 0.2697404 -0.1959674 -0.7867724 0.5853085 -0.2045689 -0.7772505 0.595007 -0.5507286 -0.7385768 0.3888472 -0.5738601 -0.7073175 0.4127791 -0.7542067 -0.6322026 0.1774604 -0.744165 -0.6337064 0.2112696 -0.7437621 -0.63443 0.2105151 -0.1657634 -0.7965864 0.5813541 -0.1940647 -0.79074 0.5805768 -0.4707886 -0.7876731 0.3974031 -0.5445362 -0.7508445 0.3737821 -0.7817537 -0.6207879 0.05902183 -0.8137834 -0.566936 0.1278294 -0.8438019 -0.5118998 0.1611123 -0.1309102 -0.8105496 0.570852 -0.1558418 -0.8091655 0.5665374 -0.3739055 -0.8451934 0.3818939 -0.440611 -0.825731 0.3521794 -0.582937 -0.7968334 0.1588749 -0.6682804 -0.7381543 0.09235596 -0.1138525 -0.8194607 0.5617133 -0.120423 -0.8191076 0.5608575 -0.3288889 -0.8723073 0.3618178 -0.3472594 -0.8674157 0.3563719 -0.4989799 -0.8587642 0.1163753 -0.5147927 -0.8474218 0.1298645 -0.5410152 -0.832692 0.1180112 -0.1042214 -0.8219708 0.5599126 -0.110438 -0.8219158 0.5588006 -0.3015235 -0.8832188 0.3591771 -0.3152904 -0.8820084 0.3502187 -0.3093916 -0.878045 0.3651219 -0.4739549 -0.8710828 0.1287698 -0.4689183 -0.8743565 0.1249662 -0.4483854 -0.7623379 0.4666814 -0.4483982 -0.7623393 0.4666669 -0.1362525 -0.8005892 0.5835172 0.1391605 -0.9637869 0.2274845 -0.07567059 -0.9008815 0.4274185 -0.2285599 -0.8503277 0.4740287 -0.08639717 -0.9426856 0.3223034 -0.1950995 -0.9061283 0.3753236 -0.07903409 -0.9932314 -0.08511847 -0.4166826 -0.8931117 0.1694908 -0.4457114 -0.8770841 0.1790669 -0.4018011 -0.906304 0.1310307 -0.4212501 -0.8957202 0.142246 -0.39183 -0.9147549 0.09845215 -0.4036231 -0.9083977 0.1090967 -0.3842516 -0.9206294 0.06922757 -0.3910679 -0.9170824 0.07762801 -0.3799026 -0.924099 0.04141551 -0.3827231 -0.9226824 0.04669255 -0.3775673 -0.9258746 0.01411455 -0.3782538 -0.9255642 0.01596993 -0.1390319 -0.9457015 0.2938007 -0.110511 -0.9667955 0.2304213 -0.1692357 -0.9430513 0.2863799 -0.1070522 -0.9812515 0.1602668 -0.1509177 -0.967682 0.2020285 -0.1168305 -0.9887884 0.09299659 -0.1374419 -0.9830728 0.1211519 -0.1230252 -0.9919133 0.03119111 -0.1288615 -0.9907967 0.04143303 -0.1289726 -0.9916483 0 -0.3783003 -0.925683 0 -0.3782997 -0.9256833 0 -0.1767576 0.7497301 0.6377003 -0.3855319 0.6911093 0.6113371 -0.1831224 0.7023814 0.6878419 -0.1762186 0.7497929 0.6377757 -0.2195627 0.7437573 0.6313614 -0.3039187 0.6237877 0.7200851 -0.1759981 0.7548126 0.6318882 -0.4869804 0.6877328 0.5383992 -0.4208483 0.7573586 0.4992944 -0.4336358 0.7036164 0.5629245 -0.4435907 0.8119252 0.3794796 -0.4204757 0.7577709 0.4989826 -0.3820666 0.7179513 0.5818687 -0.1799457 0.7273772 0.662225 -0.1733879 0.7369654 0.6533136 -0.1733586 0.7371135 0.6531543 -0.1732789 0.7052966 0.6874091 -0.6058809 0.7011612 0.3758742 -0.1694204 0.7240723 0.6685927 -0.7943457 0.5902863 0.1434473 -0.7448493 0.6062608 0.2786527 -0.6684308 0.627992 0.3985303 -0.6683583 0.6280082 0.3986265 -0.8887319 0.453157 0.06931412 -0.9457412 0.323864 -0.02618813 -0.4843431 0.6981061 0.5273135 -0.4196009 0.7629474 0.4917787 -0.4525504 0.6910327 0.5636239 -0.4843766 0.698089 0.5273057 -0.9326875 0.359884 0.0240333 -0.8691435 0.4696153 0.1550841 -0.8301204 0.5530136 0.07124745 -0.8087282 0.58639 0.04588758 -0.7802223 0.5978223 0.1840152 -0.6891933 0.721767 0.06375795 -0.157092 0.7181628 0.6779118 -0.1459521 0.7425648 0.6536785 -0.1330701 0.7337121 0.6663025 -0.1150645 0.7568705 0.6433563 -0.106482 0.7477104 0.6554317 -0.2945604 0.8091087 0.5085051 -0.3349758 0.8118957 0.4781385 -0.3845476 0.7476086 0.5414837 -0.6492922 0.7072594 0.2796496 -0.7026261 0.5913825 0.3957063 -0.8409162 0.5019487 0.2022562 -0.6445122 0.7463873 0.1658617 -0.6661932 0.744627 0.04144138 -0.4909904 0.7967619 0.3522768 -0.5314264 0.7995567 0.2798128 -0.4706969 0.8159435 0.3356797 -0.3081423 0.797225 0.5191154 -0.09032613 0.7608835 0.6425712 -0.09912073 0.7875093 0.6082798 -0.2772606 0.8236284 0.4947352 -0.2772861 0.8236356 0.494709 -0.3147946 0.8666048 0.3871702 -0.4376751 0.8443528 0.309045 -0.4375874 0.8443544 0.3091651 -0.5064384 0.8520588 0.1323476 -0.5629234 0.8207011 0.09781104 -0.4978858 0.8540196 0.150865 -0.4946667 0.860206 0.1238978 -0.3196989 0.8563593 0.405514 -0.319278 0.8634916 0.3904407 -0.1110548 0.7755442 0.6214483 -0.1111407 0.778999 0.6170967 -0.2558186 0.966664 0.01084923 -0.4178792 0.9084898 0.004854321 -0.2557511 0.9666465 0.01363396 -0.0926519 0.9870586 0.1308853 -0.08154886 0.9935458 0.07884418 -0.08820205 0.9940177 0.06441444 -0.08475023 0.9961684 0.02158647 -0.08605527 0.9961316 0.01779085 -0.4178532 0.9085018 0.004829108 -0.4188433 0.9079007 0.01693385 -0.4186551 0.9079661 0.01804447 -0.422156 0.905866 0.03451204 -0.4219585 0.9058787 0.03653466 -0.427173 0.902789 0.04995328 -0.427725 0.902327 0.05345571 -0.4344573 0.8982118 0.06680333 -0.434961 0.8975611 0.07206451 -0.4430244 0.8926413 0.08319258 -0.445645 0.8906973 0.08977133 -0.2550117 0.9668565 0.01255083 -0.257202 0.9655352 0.03986221 -0.2541607 0.9658818 0.04974687 -0.2607994 0.9619957 0.08092081 -0.2548099 0.961615 0.101827 -0.2621876 0.9574444 0.1206571 -0.2629818 0.9531973 0.1491832 -0.2698633 0.9490464 0.1627417 -0.2653141 0.9422821 0.2042379 -0.2702013 0.9394099 0.2109506 -0.281773 0.9250176 0.2548462 -0.1640791 0.8645966 0.4749221 -0.0998336 0.9098008 0.4028598 -0.09055149 0.9371325 0.3370209 -0.08029049 0.9430158 0.3229163 -0.0995509 0.9599009 0.2620685 -0.08670431 0.967671 0.2368441 -0.07656896 0.9772716 0.1976804 -0.1061271 0.9665752 0.2333872 -0.07804083 0.9837877 0.1614669 -0.088229 0.8606927 0.5014218 -0.08285498 0.902319 0.4230315 -0.2859458 0.903137 0.3202789 -0.2851627 0.9228914 0.2587546 -0.4581751 0.8818158 0.1116988 -0.4557093 0.8843238 0.1014917 -0.103676 0.7803617 0.6166742 -0.1086053 0.8480036 0.5187435 -0.3087788 0.8636485 0.3984556 -0.2975044 0.8958409 0.3300912 -0.4797567 0.8663195 0.1390103 -0.4745283 0.8712209 0.1256867 -0.4178675 0.908508 0 -0.3782998 0.9256829 -7.26518e-4 -0.08606821 0.9962893 0 -0.1289725 0.9916479 -7.26759e-4 -0.2557697 0.9667378 3.62267e-4 -0.2558345 0.9667207 3.62201e-4 0.736764 -0.67615 0 0.8146414 -0.5799651 -7.38731e-5 0.754823 -0.6559117 -0.00469774 0.8188852 -0.5739571 -6.82962e-4 0.9737637 -0.2275609 5.40744e-4 0.9435763 -0.3311546 -6.93935e-4 0.9318895 -0.3627393 -0.0014894 0.9005763 -0.4346976 4.35316e-4 0.9005519 -0.4347484 4.35295e-4 0.9737543 -0.2276011 5.40743e-4 0.992354 -0.1234167 -0.00140196 0.9970859 -0.07628893 0 0.9050116 0.0535382 0.4220046 0.9884204 0.04542636 0.1447818 0.8200915 -0.152043 0.5516638 0.8198322 -0.1744512 0.5453826 0.8061807 -0.08480793 0.58556 0.8066223 -0.1212351 0.5785003 0.7694995 -0.02747207 0.6380563 0.7689045 -0.08162367 0.6341322 0.7458771 0.05526256 0.6637873 0.9401583 -0.07148945 0.3331543 0.8238608 -0.2277018 0.5190426 0.8388827 -0.1298263 0.5286029 0.9143654 -0.05879694 0.4005982 0.9145685 2.11849e-4 0.404431 0.9288312 -0.08410805 0.3608303 0.928328 -0.03961735 0.3696453 0.9337013 -0.1151326 0.3390374 0.9337939 -0.1103046 0.340385 0.9422699 -0.1351084 0.3063873 0.9904124 -0.004279673 0.1380765 0.9898829 0.02420836 0.1398072 0.9919763 -0.01626694 0.1253734 0.9915179 0.006031095 0.1298304 0.9925793 -0.02796506 0.1183398 0.9923751 -0.0118938 0.1226803 0.9934988 -0.03748697 0.107494 0.7379865 -0.6748136 -0.001624166 0.7508447 -0.6604093 0.009594321 0.7464912 -0.6650417 0.02168798 0.7949451 -0.6030339 0.06642651 0.7365278 -0.6764048 0.001828312 0.7529433 -0.6578974 0.0157305 0.7542084 -0.6566349 5.26505e-4 0.8138337 -0.5783383 0.05656415 0.8153303 -0.5789104 0.009964644 0.8915579 -0.4422873 0.09750193 0.8815373 -0.4671921 0.06799703 0.8623141 -0.4416991 0.2476219 0.8367111 -0.5056409 0.2103378 0.8361089 -0.5162196 0.1855788 0.8568511 -0.4810645 0.1854274 0.7838902 -0.6125063 0.1017462 0.8965734 -0.439453 0.05511331 0.9336212 -0.3403498 0.1118645 0.9257062 -0.3699205 0.07891249 0.9594272 -0.2396095 0.1486164 0.9536157 -0.2800555 0.110391 0.8726279 -0.3400846 0.3505184 0.8726368 -0.3400152 0.3505637 0.8754236 -0.367211 0.3143085 0.8901368 -0.3171157 0.3272525 0.8660191 -0.4168708 0.2760972 0.965099 -0.2370956 0.1112194 0.9792478 -0.09164655 0.1807615 0.9786852 -0.2025426 0.03393822 0.841693 -0.2526632 0.4771942 0.879837 -0.2946048 0.3729543 0.941608 -0.1681948 0.2916933 0.9415886 -0.1682204 0.291741 0.07833176 -0.9969274 0 0.1421411 -0.9898446 -0.001918673 0.2332758 -0.9724107 3.53069e-4 0.4149736 -0.9098336 0 0.537173 -0.843438 -0.007589101 0.5236615 -0.8518998 -0.006734907 0.4397597 -0.8981129 -0.002144753 0.3376113 -0.9412857 -2.45732e-4 0.2332317 -0.9724211 3.53098e-4 0.6214184 -0.7834753 -0.002400815 0.779019 -0.1960821 0.5955511 0.7121915 -0.1765897 0.6794111 0.6000325 -0.2061223 0.7729648 0.6463236 -0.1371077 0.7506446 0.658523 -0.02346783 0.7521947 0.9403554 -0.2354128 0.2455863 0.9403702 -0.2354215 0.2455217 0.550967 -0.4953039 0.6716468 0.6333504 -0.4317938 0.6422004 0.7790234 -0.1961051 0.595538 0.6946544 -0.7151487 0.07757425 0.7434191 -0.6528272 0.1454123 0.7747792 -0.5686955 0.2762294 0.7771512 -0.5367377 0.3285555 0.7549066 -0.5857495 0.2949808 0.7811051 -0.5054302 0.366627 0.7063486 -0.6922205 0.1479952 0.6988442 -0.7140637 0.04159289 0.7129289 -0.6943902 0.09774875 0.7131915 -0.6941421 0.09759545 0.7158386 -0.6917392 0.09524732 0.6468408 -0.7594909 0.06906992 0.7410845 -0.4896866 0.4593483 0.753547 -0.5561835 0.3504668 0.7543033 -0.5563747 0.3485311 0.6991817 -0.6736679 0.2394085 0.6991864 -0.6736522 0.2394393 0.7410843 -0.4896887 0.4593462 0.7500644 -0.3579747 0.5561095 0.7617409 -0.3659489 0.5346328 0.6651946 -0.0587818 0.7443527 0.7211269 -0.139993 0.6785116 0.6967239 -0.1197698 0.7072701 0.7223694 -0.2773907 0.6334327 0.7223666 -0.2773678 0.6334459 0.7898747 -0.4284782 0.4387532 0.7896584 -0.4548601 0.4117547 0.7681692 -0.3429549 0.5406458 0.77253 -0.3112455 0.5534651 0.6978551 -0.1188387 0.7063114 0.6977298 -0.1074524 0.7082564 0.537784 -0.8430827 8.35977e-5 0.5243033 -0.851488 0.008617162 0.5308865 -0.8473147 0.01474612 0.4514191 -0.8900913 0.06291514 0.4789574 -0.8735676 0.0864852 0.3802149 -0.9137676 0.1430569 0.4018507 -0.9051469 0.1386551 0.5380051 -0.8429416 8.35671e-5 0.5274447 -0.8495627 0.006727576 0.5243358 -0.8515114 6.01922e-4 0.4589396 -0.8875409 0.04056501 0.4407261 -0.8976054 0.008069932 0.3632974 -0.9301886 0.05257666 0.3420214 -0.9384471 0.04835891 0.1914493 -0.9256756 0.3263005 0.2127576 -0.9332855 0.289331 0.1668466 -0.9384858 0.3023352 0.3347284 -0.9164291 0.219351 0.2901867 -0.9346893 0.2052996 0.3897537 -0.908185 0.1526177 0.2421451 -0.9648711 0.1019295 0.2704657 -0.959683 0.07653141 0.2390785 -0.96893 0.06337374 0.1333317 -0.9841998 0.1165058 0.0876255 -0.9910348 0.1008561 0.109343 -0.9249749 0.3639584 0.01763045 -0.9909303 0.1332153 0.1903194 -0.9235696 0.3328632 0.06029438 -0.9200369 0.3871651 0.1793504 -0.9103022 0.3730732 0.08068847 -0.9093501 0.4081322 -0.006145477 -0.9040906 0.4272968 0.1532735 -0.8913005 0.4267207 -0.0885142 -0.8847877 0.4575107 0.128112 -0.8588901 0.4958781 0.05298 -0.991509 0.1187564 -0.002511084 -0.9898064 0.1423973 0.04513126 -0.9897521 0.1354778 -0.0335074 -0.9873906 0.1547159 0.02908909 -0.9881303 0.150839 -0.06856417 -0.9840809 0.1639629 0.01146209 -0.9847427 0.1736391 0.1731218 -0.8315703 0.5277497 0.05682069 -0.7926833 0.60698 0.5521007 -0.8336477 0.01470851 0.5459414 -0.8372626 0.03064888 0.5200108 -0.8438034 0.1326076 0.5099238 -0.8561724 0.08334743 0.4316741 -0.8808899 0.1941404 0.2633923 -0.8800516 0.3951377 0.2633866 -0.8800567 0.3951299 0.3849851 -0.8837563 0.2660099 0.3880724 -0.8710286 0.3011795 0.4316217 -0.8808878 0.1942667 0.216595 -0.857692 0.4663167 0.1145983 -0.8219403 0.5579259 0.1662063 -0.8535195 0.493842 0.1660617 -0.8534589 0.4939954 0.1730782 -0.8315545 0.5277889 0.07824254 -0.8124337 0.57778 0.09905582 -0.7975376 0.5950813 0.0415861 -0.7913486 0.6099492 0.2547174 -0.8574808 0.447041 0.2484903 -0.8619875 0.4418486 0.2512341 -0.8649588 0.434428 0.4595625 -0.8580473 0.2292535 0.4595979 -0.8580483 0.229179 0.3932247 -0.8780016 0.272924 0.3628329 -0.8651857 0.3461301 0.362942 -0.8651943 0.3459944 0.5957923 -0.8031264 -0.004431545 0.5432574 -0.8321354 0.1114547 0.5275986 -0.8477666 0.05414491 0.5027967 -0.8520561 0.1455888 0.9970731 0.0764541 0 0.9923539 0.1234174 -0.001399576 0.9736859 0.2278937 5.42608e-4 0.9318895 0.3627393 -0.00146526 0.9404419 0.3399537 -8.02992e-4 0.973679 0.2279233 5.42605e-4 0.8146418 0.5799646 0 0.7372063 0.6756415 -0.005956411 0.7487256 0.6628603 -0.005137801 0.8081394 0.5889902 -0.001134276 0.8924379 0.4511702 5.65721e-4 0.8924181 0.4512093 5.65695e-4 0.7365278 0.6764048 0.001828312 0.7446799 0.6673658 0.008655607 0.7483554 0.6632978 5.22485e-4 0.7933135 0.6074025 0.04142421 0.8075295 0.5897781 0.007614433 0.7379865 0.6748136 -0.001624166 0.7484606 0.6631332 0.007824122 0.7429417 0.669213 0.01384109 0.7976776 0.5996555 0.06421738 0.7749281 0.6259424 0.08765059 0.8521271 0.4938269 0.1732467 0.8297523 0.5289815 0.1780168 0.8839098 0.4583279 0.09294551 0.8756213 0.4793824 0.0589919 0.8887864 0.4555493 0.05033618 0.9184723 0.3846381 0.09199088 0.933126 0.3477568 0.09133094 0.8318126 0.5184903 0.1981304 0.8731679 0.4129235 0.2589826 0.8539697 0.4531738 0.255674 0.8901834 0.3171495 0.327093 0.8687133 0.3723899 0.3265932 0.8726001 0.3403421 0.3503373 0.8875294 0.1938838 0.4179722 0.8694775 0.2603137 0.4198163 0.8694589 0.2603467 0.4198344 0.9829173 0.1334044 0.1267954 0.9593486 0.2399752 0.1485337 0.9535449 0.2803581 0.1102337 0.965042 0.2373759 0.1111161 0.9780952 0.1285891 0.1636905 0.9851995 0.08909797 0.1464364 0.8238727 0.1561629 0.5448368 0.8096396 0.3748468 0.4516347 0.8671988 0.1011093 0.4875892 0.9927229 0.04086214 0.1132763 0.9643355 0.2551587 0.07036495 0.8972057 0.3669833 0.2456529 0.9091143 -0.2915104 0.2975452 0.8631891 0.3211579 0.3895666 0.9913151 0.02727961 0.1286475 0.9916191 -0.01184505 0.1286523 0.9207144 0.1234993 0.3701798 0.9321191 0.01987177 0.3616064 0.7865679 0.1907945 0.5872892 0.8185458 0.05002647 0.572259 0.9893967 0.00953561 0.1449253 0.9896658 -0.03998738 0.1377048 0.9030814 0.08434343 0.4211059 0.9183588 -0.04795807 0.3928325 0.7406979 0.1297714 0.659186 0.7836319 -0.05452811 0.6188279 0.2361511 0.9717163 4.07974e-4 0.5385514 0.8425928 0 0.4149742 0.9098332 -8.40727e-5 0.4641418 0.8857554 -0.003145515 0.3505539 0.9365426 -3.63508e-4 0.2361391 0.9717193 4.08006e-4 0.1421411 0.9898446 -0.00197494 0.07930564 0.9968504 0 0.6541956 0.02564841 0.7558905 0.7818059 0.5702077 0.2522754 0.7327237 0.6667784 0.1360978 0.7120953 0.7004076 0.04847186 0.7178289 0.6930572 0.06628268 0.7087473 0.7047808 0.03100693 0.6966542 0.717344 -0.009519219 0.7818037 0.5702134 0.252269 0.774851 0.5325896 0.3405205 0.783033 0.5091465 0.3572523 0.7524995 0.2297915 0.6172037 0.7679926 0.3284125 0.5498479 0.7665571 0.3383736 0.5457962 0.7958385 0.4230906 0.4331691 0.7958324 0.4230902 0.4331808 0.671994 0.05099886 0.7387985 0.687914 0.1249297 0.7149594 0.7161681 0.1529942 0.6809524 0.7526171 0.2300387 0.6169682 0.6822979 0.06964129 0.7277498 0.7349166 0.1285362 0.6658649 0.6981428 0.1160663 0.706488 0.7359478 0.2832483 0.6149401 0.7523156 0.4502552 0.480928 0.7523034 0.4502377 0.4809633 0.7778061 0.328239 0.5359823 0.778942 0.3287355 0.5340247 0.7359717 0.2832998 0.6148877 0.7128009 0.667209 0.2162108 0.7845721 0.5236632 0.3319992 0.8282638 0.497607 0.2576165 0.7764158 0.5186631 0.3580046 0.7338496 0.6708227 0.1070598 0.802955 0.5946626 0.04049539 0.7128074 0.667194 0.2162355 0.0218032 0.8659195 0.4997081 0.1643387 0.8938971 0.4170621 0.04005944 0.99581 0.08220595 0.0193125 0.9954503 0.09330457 0.14047 0.9622669 0.2330464 0.1129592 0.9614835 0.2505788 0.09007257 0.9618749 0.2582319 0.2216489 0.8966623 0.3832342 0.1381242 0.8717995 0.4699864 0.1838322 0.8942605 0.4080489 0.07274824 0.9531424 0.293645 0.1186389 0.9614995 0.247878 0.008292198 0.9945527 0.1039044 0.03241038 0.9956694 0.08713364 0.06307733 0.8393158 0.5399725 0.1419401 0.8664928 0.4785849 0.02216452 0.9409008 0.3379566 0.09113687 0.9531604 0.2884086 -0.014095 0.9929761 0.1174721 0.02040189 0.9947313 0.1004658 -0.02129459 0.793192 0.6085993 0.08090257 0.839302 0.5376123 -0.03491145 0.9233173 0.3824481 0.05941039 0.9410213 0.3330908 -0.03864127 0.9907042 0.1304311 0.007090508 0.9933718 0.1147268 0.5373309 0.8433707 -0.001202821 0.4825633 0.8751356 0.03564387 0.2428412 0.9677488 0.06701064 0.2778282 0.9574249 0.0784161 0.2465475 0.9629502 0.1092765 0.3703341 0.9281859 0.03638142 0.3570733 0.9316144 0.06777477 0.4647457 0.8854442 -4.12411e-5 0.4689137 0.8818785 0.04909539 0.5388367 0.8424068 0.002414703 0.1802777 0.9304468 0.3190119 0.3292224 0.9132972 0.2397932 0.3357746 0.9214087 0.1956057 0.4086616 0.8998162 0.1527305 0.4219824 0.8953962 0.1421146 0.3940514 0.9083219 0.1402677 0.4999883 0.8629114 0.07345622 0.2426891 0.8958765 0.372166 0.3613135 0.9259446 0.1099055 0.2133235 0.9253705 0.313341 0.1666848 0.9612782 0.2194548 0.1655633 0.980088 0.1096194 0.08538115 0.9945873 0.05921345 0.5926561 0.7957611 0.1245918 0.2055824 0.8240334 0.527925 0.1294026 0.7881858 0.6016796 0.08792531 0.7624773 0.6410129 0.153891 0.7672965 0.6225541 0.04443573 0.7382856 0.6730231 0.2578426 0.8305564 0.4936532 0.2670099 0.8311498 0.4877455 0.2995941 0.8569446 0.4193917 0.299602 0.8569475 0.4193803 0.4137679 0.8622463 0.2921085 0.410384 0.8576984 0.3097394 0.5716651 0.8199182 0.03054797 0.5415565 0.8332655 0.1112889 0.5431495 0.835308 0.08514314 0.4651319 0.8617388 0.2026293 0.4651948 0.8617364 0.2024953 0.6438768 0.7651063 -0.005913615 0.6139953 0.7862135 0.06984287 0.2850781 0.950117 0.1265237 0.5872533 0.8012509 0.1145889 0.5402329 0.8159274 0.2059395 0.4372221 0.8439542 0.3107708 0.4430873 0.8548443 0.270028 0.1703113 0.7800296 0.6021196 0.2405699 0.8097592 0.5351788 0.2954555 0.8404614 0.4542365 0.2851561 0.81643 0.5021235 0.4201817 0.8348836 0.3555513 0.4201639 0.8348798 0.3555812 0.1703712 0.7800549 0.6020697 0.08595925 0.7640247 0.6394352 0.05636125 0.7356145 0.6750517 0.6304333 0.1950942 0.7513268 0.6157235 0.2415307 0.7500318 0.6157591 0.2413191 0.7500707 0.5405181 0.5555408 0.6318343 0.4660313 0.6681191 0.5800274 0.4660356 0.6681156 0.5800279 0.3653512 0.8314253 0.4186294 0.2087387 0.938835 0.2738925 0.2087135 0.9388499 0.2738605 0.1319572 0.9807519 0.1439208 0.03438764 0.9985681 0.04098206 0.03937619 0.9080926 0.4169142 0.5860404 0.1128552 0.8023842 0.0857219 0.6368925 0.7661721 0.09834855 0.6993442 0.7079867 0.274892 0.4872131 0.8288895 0.2645294 0.521925 0.8109369 0.5843156 0.1030363 0.8049589 0.4595661 0.3184766 0.8290787 0.4437583 0.3311746 0.8327076 0.4443551 0.3056102 0.8421111 0.3020234 0.5101804 0.8052936 0.5895027 0.1396995 0.7955946 0.5916488 0.1168619 0.7976811 0.4508826 0.4093151 0.7931999 0.4627299 0.3446995 0.8167396 0.2745643 0.6427096 0.7152194 0.2983515 0.5461198 0.7827769 0.07783818 0.8193277 0.5680173 0.109238 0.707016 0.6987099 0.6023902 0.168842 0.7801401 0.6013363 0.1447444 0.785776 0.4772189 0.4879361 0.7308765 0.4817669 0.4225788 0.7676771 0.2990863 0.7492772 0.5908732 0.3135845 0.6596693 0.6830089 0.1406678 0.8823046 0.4491674 0.1115462 0.834177 0.5400984 0.6189957 0.1950728 0.7607832 0.6145952 0.1713042 0.7700179 0.5112653 0.5553075 0.6559279 0.5082809 0.494323 0.7051917 0.330466 0.8309782 0.4475124 0.3357993 0.7570215 0.5604974 0.1059134 0.9804716 0.1657038 0.1170294 0.9279451 0.3538674 0.09519982 0.6448944 0.7583194 0.1329327 0.6271392 0.7674798 0.2755796 0.4877961 0.8283181 0.2753867 0.4879871 0.8282698 0.3744565 0.4096761 0.831834 0.5862487 0.1046587 0.8033424 0.571561 0.1446457 0.8077101 0.4425343 0.3041584 0.8435943 0.4425659 0.3041155 0.8435931 0.579535 0.1827833 0.7941848 0.1291251 0.6357073 0.761054 0.1248853 0.6259125 0.7698295 0.381497 0.4554623 0.8043719 0.3811724 0.435718 0.815388 0.3618466 0.433577 0.8252746 0.5947223 0.2285957 0.770746 0.5600553 0.1349885 0.8173838 0.5815192 0.1846896 0.7922912 0.3602414 0.3977427 0.8438169 0.3744359 0.4292615 0.8219078 0.1205573 0.6167562 0.7778676 0.1263225 0.6272788 0.7684816 0.6674312 0.7446711 7.7249e-4 0.6646863 0.742384 0.08401238 0.6578972 0.7531077 4.62896e-4 0.6864746 0.7233031 0.0747348 0.5834261 0.7821187 0.2188705 0.6134263 0.7607661 0.2119982 0.6279991 0.7747187 0.0736761 0.685043 0.7246712 0.07461738 0.6551412 0.7509721 0.08264964 0.5833253 0.782172 0.2189486 0.5657882 0.7641965 0.3096574 0.5619037 0.7738255 0.2923324 0.5361031 0.7460677 0.3949388 0.5154945 0.7730128 0.3697521 0.6695219 0.7069289 0.2280176 0.6929408 0.6887708 0.2131382 0.6964564 0.6827802 0.2208156 0.6827472 0.6684975 0.2949026 0.6859804 0.6584826 0.3095668 0.6696766 0.6415333 0.3741236 0.6896283 0.6105992 0.3893346 0.6427232 0.5608597 0.5218652 0.6620934 0.5635417 0.4940174 0.6689667 0.5370803 0.513837 0.6413747 0.5070362 0.5758063 0.6388518 0.4817732 0.5998024 0.3098811 0.677975 0.6665761 0.3481115 0.6804485 0.644832 0.3350601 0.656005 0.6763078 0.394069 0.721965 0.5687496 0.3930423 0.6975049 0.5991701 0.4433752 0.7521109 0.4875938 0.4619995 0.7193002 0.51881 0.5083712 0.7697861 0.38599 0.1560196 0.66504 0.7303285 0.2887554 0.6549028 0.6983715 0.4022266 0.4784134 0.7805988 0.4022473 0.4783968 0.7805982 0.5915365 0.431389 0.6811667 0.6271733 0.4308548 0.6488589 0.6158304 0.4096065 0.6730346 0.5945253 0.3860332 0.7053496 0.620429 0.2575525 0.7407662 0.1254028 -0.9807851 0.1494488 0.1254061 -0.980784 0.1494529 0.3571177 -0.8314642 0.4255989 0.3571115 -0.8314718 0.4255891 0.5344505 -0.5555887 0.6369331 0.5344558 -0.5555651 0.6369493 0.6304323 -0.1950833 0.7513306 0.6304334 -0.1950937 0.7513269 0.08551114 -0.9794656 0.1825786 0.3271986 -0.830834 0.4501734 0.5151129 -0.5554302 0.6528063 0.6220291 -0.1950753 0.7583044 0.3751527 -0.8291498 0.4144529 0.2884268 -0.8257139 0.4847748 0.3799129 -0.7621948 0.5241426 0.2635925 -0.7378418 0.6213763 0.3518084 -0.674631 0.6489253 0.1544533 -0.9791581 0.1318852 0.0472005 -0.9741834 0.2207687 0.1817793 -0.9356511 0.3025116 0.04020071 -0.906093 0.4211644 0.1248248 -0.894625 0.4290282 0.1106387 -0.833606 0.5411655 0.0352528 -0.7979634 0.6016741 0.1565277 -0.741608 0.6523164 0.2978441 -0.5487055 0.7811602 0.2558796 -0.6338809 0.7298772 0.3303367 -0.5708169 0.7516953 0.462597 -0.3463773 0.8161048 0.5429126 -0.5536085 0.6314773 0.4864387 -0.5522807 0.6770255 0.5330565 -0.4974476 0.6843951 0.4565424 -0.4814748 0.7481651 0.5033751 -0.4315174 0.7486029 0.4461462 -0.4071177 0.7969998 0.4808396 -0.3593478 0.799789 0.6301681 -0.1943533 0.7517414 0.6108652 -0.194163 0.7675576 0.6224437 -0.1723723 0.7634472 0.5956717 -0.1668298 0.785712 0.6082563 -0.1476734 0.7798827 0.5842382 -0.1374177 0.7998639 0.5975185 -0.1215994 0.7925816 0.09721297 -0.7023373 0.7051752 0.1396517 -0.6855694 0.7144873 0.2778956 -0.5347032 0.7980392 0.2779244 -0.5346843 0.7980418 0.3858149 -0.4530603 0.8036686 0.4458243 -0.3345628 0.8302461 0.4457545 -0.334665 0.8302423 0.5795032 -0.1613833 0.7988314 0.5893361 -0.1158132 0.7995438 0.1385442 -0.7012608 0.6993131 0.5738371 -0.2941971 0.764303 0.6367693 -0.2955095 0.7121791 0.3667407 -0.5201871 0.7713018 0.3982811 -0.5155625 0.7586616 0.3864299 -0.5440296 0.7447844 0.1236363 -0.6966922 0.7066357 0.136812 -0.683602 0.7169176 0.1163442 -0.6805628 0.7233936 0.4066796 -0.4675417 0.7848671 0.347222 -0.468171 0.8125594 0.6251488 -0.194406 0.755907 0.5383452 -0.2053516 0.8173221 0.5448152 -0.7981544 0.25715 0.5591538 -0.8128585 0.1631199 0.6137332 -0.7895134 5.92788e-4 0.6104269 -0.788989 0.06982326 0.6087909 -0.7933307 3.96606e-4 0.6058703 -0.7916404 0.07890993 0.6396263 -0.7654257 0.07072287 0.6306037 -0.7577495 0.1677932 0.6546713 -0.7127352 0.2518216 0.6279848 -0.7400116 0.2408692 0.6401481 -0.7519293 0.1575207 0.5692173 -0.8074269 0.1550922 0.5770853 -0.8137829 0.06877428 0.6546419 -0.7127721 0.2517936 0.6218289 -0.6773948 0.3930205 0.6564154 -0.6588809 0.3674166 0.6118142 -0.6085114 0.5053685 0.6344279 -0.6093987 0.4755361 0.5448121 -0.7981939 0.2570338 0.5154265 -0.8237802 0.2360544 0.4808665 -0.7859399 0.3886721 0.4652137 -0.8086459 0.3600949 0.4491599 -0.8097639 0.377542 0.4207937 -0.7775386 0.4672968 0.384534 -0.7827891 0.4892595 0.633913 -0.3660244 0.6813079 0.5909054 -0.7779521 0.2135916 0.5575902 -0.4301105 0.7099988 0.6351484 -0.5897765 0.4987486 0.5862411 -0.5337727 0.6094326 0.6267734 -0.5265339 0.5743843 0.5559551 -0.4430336 0.7033031 0.4103158 -0.572913 0.7095152 0.3367981 -0.7254266 0.6002694 0.3399574 -0.752952 0.5634647 0.306808 -0.7479874 0.5885437 0.2871299 -0.7247505 0.6263331 0.1552795 -0.7346758 0.6604088 -0.4188213 -0.6646084 0.6187767 -0.002925992 -0.7971284 0.6038028 -0.02359396 -0.7944145 0.6069176 -0.02329319 -0.7938846 0.6076222 -0.1026037 -0.7792903 0.6182063 -0.103143 -0.779646 0.6176679 -0.2667739 -0.7320288 0.6268696 -0.2672847 -0.7321195 0.6265462 -0.2670788 -0.7322631 0.626466 -0.4185188 -0.664987 0.6185744 -0.4187934 -0.6647714 0.6186203 -0.4183113 -0.6649041 0.6188039 -0.993512 0.08041083 0.08042532 -0.9931755 0.08238667 0.0825535 -0.9935089 0.08045828 0.08041507 -0.9935113 0.08043283 0.08041155 -0.993508 0.08041572 0.08046925 -0.9999454 0.007394731 0.007404983 -0.9752195 0.156446 0.1564344 -0.9988257 -0.03425705 -0.03425979 -0.9737795 0.212128 0.08219105 -0.9646413 0.2371013 0.1151096 -0.9614292 0.2470977 0.1208164 -0.9476052 0.2721991 0.1671888 -0.9358894 0.3031093 0.1795434 -0.8949951 0.3316079 0.2983622 -0.9049729 0.3563379 0.2324809 -0.8846172 0.3767413 0.2748063 -0.8706184 0.3762243 0.3169844 -0.8289343 0.4152467 0.3747506 -0.9968245 -0.07953822 0.003835618 -0.9698414 0.08746653 0.2275025 -0.9712752 0.08211743 0.2233413 -0.9617494 0.09947425 0.2552313 -0.9609637 0.1021705 0.2571189 -0.947581 0.1126119 0.2990134 -0.9410634 0.1284607 0.3128861 -0.9313868 0.1279774 0.3407937 -0.9183104 0.1414552 0.3697251 -0.911001 0.138503 0.3884512 -0.8872247 0.1644991 0.4310132 -0.7759042 0.392541 0.4938466 -0.780906 0.4957838 0.3799793 -0.7452266 0.4777905 0.4651384 -0.8830637 0.161076 0.4407415 -0.6458714 0.5051362 0.57244 -0.7447704 0.4773975 0.4662711 -0.847041 0.1722472 0.5028444 -0.8572722 0.1816759 0.4817453 -0.8114891 0.1845123 0.5544733 -0.5896776 0.452771 0.668789 -0.6733687 0.536247 0.5089341 -0.5546271 0.5374998 0.635203 -0.5632289 0.5489345 0.6176117 -0.5673625 0.5500885 0.6127827 -0.8162283 0.1955557 0.543626 -0.8287782 0.2010487 0.5222129 -0.5113763 0.485695 0.7089391 -0.5173263 0.4873967 0.7034331 -0.7890713 0.1729028 0.5894667 -0.8056618 0.1812645 0.5639613 -0.4925224 0.4464278 0.7470769 -0.7043929 0.005955755 0.7097854 -0.7089111 0.01254707 0.7051863 -0.6974318 0.02219849 0.7163074 -0.7209776 0.04806256 0.6912896 -0.648911 0.141472 0.7475963 -0.6489032 0.141516 0.7475948 -0.6757323 0.1756063 0.7159249 -0.7050725 0.006214559 0.709108 -0.7067816 0.009402811 0.7073693 -0.7093508 0.005837976 0.7048315 -0.7332369 0.03198683 0.6792206 -0.7273446 0.03912687 0.6851562 -0.760221 0.08186614 0.6444859 -0.7536051 0.08615529 0.6516569 -0.6121969 0.2782751 0.7401202 -0.6122134 0.2782748 0.7401068 -0.6202638 0.2905722 0.7285882 -0.4926018 0.4464269 0.7470252 -0.4925848 0.4464747 0.7470079 -0.7825757 0.1316019 0.6084868 -0.7782611 0.1477645 0.6103076 -0.7750833 0.1444914 0.6151165 -0.9930679 -4.66039e-4 0.1175418 -0.9677755 -0.1095506 0.2267363 -0.9655452 -0.2530508 0.06072795 -0.9655458 -0.06074702 0.2530439 -0.9677768 -0.1095455 0.2267329 -0.993061 -0.1176002 4.10586e-4 -0.9930834 -0.1174104 3.53124e-4 -0.9677752 -0.226731 0.1095648 -0.833051 -0.2271656 0.5044027 -0.6602907 -0.6367927 0.3981348 -0.6604519 -0.6365128 0.3983151 -0.8017575 -0.2165278 0.5570466 -0.8092773 -0.2107346 0.548326 -0.8382152 -0.2057532 0.5050355 -0.8629267 -0.2104719 0.4594116 -0.8448409 -0.1839196 0.5024117 -0.7338346 -0.592356 0.3325676 -0.6594228 -0.5809612 0.4771223 -0.5859797 -0.6130153 0.5299436 -0.7807767 -0.5111752 0.3592878 -0.780906 -0.5111063 0.3591048 -0.7809773 -0.5111604 0.3588725 -0.7081704 -0.5169293 0.4809146 -0.9108831 -0.1581162 0.3811709 -0.9064818 -0.1559029 0.3924095 -0.9267464 -0.1362591 0.3501068 -0.9274417 -0.1358996 0.3484012 -0.9391734 -0.1193516 0.3220381 -0.9436876 -0.1169285 0.3094861 -0.8914722 -0.1764061 0.4173228 -0.8801818 -0.1715602 0.4425464 -0.828648 -0.4697875 0.304372 -0.8640574 -0.4507645 0.2240899 -0.8505937 -0.4350687 0.295306 -0.9064087 -0.3824254 0.1793717 -0.8968948 -0.3870062 0.2140235 -0.9341393 -0.3331293 0.1280966 -0.9317281 -0.3342531 0.1419776 -0.6886776 -0.6426455 0.3357527 -0.813939 -0.2204392 0.5375034 -0.813951 -0.2206904 0.5373821 -0.5914962 -0.5545408 0.5853348 -0.8139538 -0.2206591 0.5373908 -0.4652528 -0.5582478 0.6869492 -0.5652166 -0.4945455 0.6602689 -0.7140178 -0.3560088 0.6028569 -0.4622459 -0.4528663 0.7623915 -0.438404 -0.7880042 0.4322634 -0.5378978 -0.5931863 0.598996 -0.702628 -0.005990087 0.7115322 -0.7066828 -0.008965373 0.7074738 -0.6622908 -0.1103561 0.7410753 -0.7384482 -0.05927073 0.6717002 -0.700075 -0.01690822 0.7138692 -0.7052861 -0.006176829 0.7088959 -0.7079899 -0.009411931 0.7061598 -0.7087252 -0.004183232 0.7054722 -0.7278624 -0.02486801 0.6852722 -0.7243149 -0.03352594 0.6886538 -0.7511509 -0.06715476 0.656706 -0.7491587 -0.07535266 0.6580905 -0.6920921 -0.3303614 0.6417709 -0.6328753 -0.2389807 0.736449 -0.6328725 -0.2013959 0.7476043 -0.7121031 -0.189807 0.6759308 -0.6580721 -0.1209007 0.7431851 -0.5214099 -0.4065898 0.750211 -0.5213058 -0.4062508 0.7504669 -0.5216835 -0.3468877 0.7794327 -0.771829 -0.1327576 0.6218162 -0.7805536 -0.1221789 0.6130322 -0.7699421 -0.1292797 0.6248808 0.7060306 0 -0.7081814 0.7060323 0 -0.7081797 0.706031 0 -0.708181 0.706031 0 -0.708181 0.7060309 1.43963e-7 -0.7081811 0.706026 0 -0.708186 -0.6427834 3.78019e-6 -0.7660481 -0.6428398 -2.04065e-5 -0.7660007 -0.6427794 1.4811e-6 -0.7660514 -0.6427841 -4.3754e-7 -0.7660474 -0.6427837 -8.12412e-7 -0.7660477 -0.6427848 6.55188e-7 -0.7660467 -0.6427841 2.13999e-6 -0.7660475 -0.6427943 0 -0.7660389 -0.6427941 -1.54395e-6 -0.7660391 -0.6427812 -8.74059e-7 -0.7660499 -0.642784 -8.22638e-7 -0.7660476 -0.6427772 -1.62679e-7 -0.7660532 -0.6427905 -1.2102e-7 -0.7660421 -0.6427869 -5.14494e-7 -0.7660451 -0.6427878 -5.38144e-7 -0.7660443 -0.6427852 0 -0.7660465 -3.50735e-5 -0.707128 -0.7070856 0 -0.7071025 -0.7071111 1.36811e-5 -0.7071017 -0.707112 3.62884e-5 -0.7071018 -0.7071118 0 -0.7071109 -0.7071027 1.45038e-6 -0.7071045 -0.7071091 4.93417e-6 -0.7070981 -0.7071154 -1.10381e-6 -0.707111 -0.7071027 -1.12978e-6 -0.7071104 -0.7071031 -3.38899e-6 -0.7071209 -0.7070927 0 0.8355675 -0.549388 -0.01115894 0.9336932 -0.3579002 0.01335525 0.7841903 -0.6203768 0.011689 0.7992581 -0.6008745 0 0.9940671 -0.1087691 3.74033e-4 0.9934769 -0.1140335 -3.80951e-4 0.9442083 -0.3293486 1.09653e-6 0.9402514 -0.3404811 1.24153e-6 0.944033 -0.3298513 0.005777359 0.8476227 -0.530568 0 0.7660409 -0.6427918 -6.99458e-6 0.7660609 -0.642768 -1.25734e-6 0.7660521 -0.6427785 1.84771e-6 0.7660406 -0.6427922 4.30818e-5 0.7660276 -0.6428077 8.05022e-5 0.7660189 -0.642818 1.55038e-5 0.7660451 -0.642787 2.63894e-6 0.7660387 -0.6427946 1.10901e-6 0.7660501 -0.642781 0 0.7661129 -0.642706 -0.7470087 0 -0.6648144 -0.747007 0 -0.6648163 -0.9063065 0 -0.422621 -0.9894425 0 -0.1449261 -0.9894426 0 -0.1449255 0 -1 -3.91618e-7 0 -1 -6.85888e-7 0 -1 1.66118e-5 0 -1 -1.43559e-6 0 -1 5.94028e-6 0 -1 -2.35977e-6 0 -1 -4.71009e-7 0 -1 9.48141e-6 3.02245e-5 -0.9359107 -0.3522377 0 -0.9928086 -0.1197128 -4.33943e-5 -0.9927397 -0.1202827 3.93649e-5 -0.9353725 -0.3536644 6.63508e-5 -0.8260561 -0.563588 3.02131e-5 -0.9359416 -0.3521553 -6.61376e-5 -0.9353208 -0.3538011 6.76975e-5 -0.8259791 -0.563701 6.62106e-5 -0.8259537 -0.5637381 0.00552982 -0.7439103 -0.6682567 -8.76575e-4 -0.8252146 -0.5648186 2.19313e-4 -0.7194862 -0.6945068 0 -0.7304986 -0.6829143 0 1 2.85277e-6 0 1 -1.56647e-6 0 1 1.64751e-6 0 1 -1.49258e-6 0 1 7.449e-6 0 1 -1.92386e-6 0 1 -1.15389e-6 -0.6083944 0.792706 0.03838831 0.50845 0.8610733 0.005598783 0.5075834 0.8615931 0.004074573 0.5053883 0.8628911 0.001308143 0.5276137 0.849472 0.004597008 0.5115321 0.8592627 -0.001641154 0.5080521 0.8613218 0.002814888 0.5137552 -0.8579322 0.002819776 0.5187731 -0.8549084 -0.002494394 0.5400685 -0.8415811 0.008207023 0.5124737 -0.8586753 0.006888568 0.5132524 -0.8581924 0.008821845 0.5126971 -0.8585434 0.006705522 0.5080034 -0.8613547 7.41676e-4 0.5097658 -0.8603083 0.002940416 0 0.7766534 -0.6299281 -7.42538e-4 0.8289722 -0.5592895 -0.001353383 0.9729176 -0.2311483 2.63249e-4 0.9443562 -0.328925 2.58623e-4 0.8660202 -0.5000091 -0.01625043 0.9428824 -0.3327293 -0.006981372 0.8985102 -0.4388972 0 0.9848075 -0.1736503 -0.0112695 0.9986567 -0.05057513 -0.00551933 0.9902351 -0.1392988 -0.002547681 -0.9687951 -0.2478504 -0.006257176 -0.9859465 -0.1669443 -0.004151105 -0.9807746 -0.1951 -6.83612e-4 -0.996856 -0.07923096 0 -0.9997321 -0.02314871 0 -0.7619728 -0.6476091 -0.006549835 -0.8550485 -0.5185068 -0.01527833 -0.9048271 -0.4255053 -7.29468e-4 -0.8314746 -0.5555625 2.20417e-4 -0.9417388 -0.336345 2.20456e-4 -0.9417256 -0.3363822 0.6996957 -0.1950157 -0.6873098 0.7050734 -0.08823251 -0.703624 0.7055788 -0.03585654 -0.7077237 0.6022782 -0.5323659 -0.5948508 0.6549596 -0.367448 -0.6603105 0.6908088 -0.1950947 -0.6962193 0.6910995 -0.3491737 -0.6328184 0.6910374 -0.34942 -0.6327504 0.3944791 -0.8432331 -0.3651635 0.4552842 -0.761743 -0.4609385 0.5849903 -0.5555506 -0.590889 0.5294123 -0.7335785 -0.4261283 0.5686512 -0.6369472 -0.5205135 0.1377373 -0.980786 -0.1381573 0.1052516 -0.9929041 -0.05534976 0.1880697 -0.9659993 -0.1774123 0.2783977 -0.9164416 -0.2874538 0.3882022 -0.8314597 -0.3974595 0.3350134 -0.9056026 -0.260096 0.3944619 -0.8432692 -0.3650985 0.05225265 -0.9045724 -0.4231057 0.04776608 -0.7889931 -0.6125425 0.6029251 -0.183906 -0.7763118 0.2024369 -0.5355537 -0.819879 0.603056 -0.1839493 -0.7761998 0.6139876 -0.2698145 -0.7417678 0.530744 -0.4240813 -0.7338024 0.6664949 -0.1697365 -0.7259299 0.6525765 -0.05756455 -0.7555331 0.4947112 -0.3452411 -0.7975397 0.4837137 -0.4394322 -0.7569151 0.3224694 -0.6485478 -0.6894921 0.3508564 -0.533765 -0.769412 0.09463644 -0.7995513 -0.593095 0.1332899 -0.7046554 -0.696918 0.1302325 -0.7130107 -0.6889523 0.6543912 -0.06848412 -0.7530485 0.6598194 -0.1613162 -0.7339043 0.524935 -0.4876952 -0.6975649 0.536254 -0.4269379 -0.728118 0.3261625 -0.7476867 -0.5784312 0.3545696 -0.665149 -0.6571585 0.09874707 -0.9142911 -0.3928369 0.1356196 -0.8383619 -0.5279741 0.6805435 -0.195067 -0.7062645 0.6781537 -0.1726004 -0.7143645 0.5602521 -0.5551678 -0.6147409 0.5649817 -0.4976621 -0.6581248 0.3583773 -0.8305434 -0.4263372 0.3792479 -0.761161 -0.5261228 0.1070725 -0.979874 -0.1684708 0.14295 -0.9312925 -0.3350515 0.03372669 0.9988583 -0.03383374 0.1983164 0.9656914 -0.1676626 0.1805074 0.9764838 -0.1178842 0.275714 0.9223486 -0.2706562 0.5178345 0.7070553 -0.4815809 0.4650918 0.8078014 -0.3621417 0.4995241 0.7071001 -0.500485 0.3908149 0.8305518 -0.3967965 0.390327 0.831014 -0.3963087 0.7030523 0.09177893 -0.7051909 0.7015779 0.1968083 -0.684876 0.6932521 0.3054209 -0.6527785 0.6932459 0.3055197 -0.6527388 0.687314 0.4145214 -0.5964659 0.6856883 0.2588129 -0.680329 0.5759606 0.575219 -0.5808549 0.575934 0.5752696 -0.5808312 0.1647692 0.8230002 -0.5436193 0.7059096 4.34941e-4 -0.7083018 0.6485146 0.2284396 -0.7261159 0.6265837 0.09294545 -0.7737921 0.6343798 0.1453406 -0.7592355 0.5885152 0.2646343 -0.7639494 0.2778202 0.4979032 -0.8215282 0.5436962 0.3862125 -0.7451406 0.4334418 0.553644 -0.7110603 0.4239786 0.4721223 -0.7728795 0.08428025 0.7798252 -0.620298 0.2270174 0.7144215 -0.6618649 0.3437431 0.5853953 -0.7342705 0.08757162 0.781892 -0.6172327 0.003562569 0.7983384 -0.6021988 0.02356541 0.7949575 -0.6062074 0.6735165 0.2339619 -0.7011686 0.6567189 0.2586565 -0.7083906 0.5089981 0.6515156 -0.5625375 0.4385468 0.7046444 -0.5578109 0.2347428 0.9245656 -0.3001237 0.1011781 0.9596856 -0.2622336 0.5604751 0.2062029 -0.8020899 0.6324099 0.2405885 -0.7363254 0.4785526 0.574896 -0.6636882 0.4065688 0.6282383 -0.6633389 0.1816354 0.8772332 -0.4443767 0.08706176 0.8905434 -0.4464895 0.9606694 -0.2470144 0.126879 0.9352225 0.3503714 0.05097901 0.4736865 0.6076636 0.6374685 0.9335287 0.3498557 0.07826459 0.9007342 0.3946111 0.1815494 0.8686835 -0.1010184 -0.4849579 0.7078044 0 -0.7064085 0.7070948 0 -0.7071188 0.7103342 0 -0.7038647 0.7117387 -1.00442e-5 -0.7024443 0.7386444 5.31396e-5 -0.6740953 0.7443867 -1.96524e-4 -0.6677488 0.7805609 1.30288e-4 -0.6250799 0.7925407 -2.28788e-4 -0.609819 0.833544 4.88424e-4 -0.5524529 0.9154576 0.004976391 -0.4023839 0.9309673 0.002833127 -0.3650918 0.9647049 5.31325e-4 -0.2633332 0.9630333 5.49092e-4 -0.269382 0.9589559 6.2731e-4 -0.2835549 0.9508635 0.001015782 -0.3096087 0.9426719 0.001690983 -0.3337168 0.9018874 0.007137238 -0.4319124 0.8920935 0.008901238 -0.4517632 0.8839935 0.01040208 -0.4673838 0.8666529 -3.22965e-5 -0.4989115 0.8451701 -3.17761e-4 -0.5344973 0.8451479 -3.17848e-4 -0.5345324 0.8822227 4.92987e-5 -0.4708325 0.8961281 -4.02681e-4 -0.4437954 0.9058465 -8.58688e-4 -0.4236053 0.9139436 -0.001486182 -0.4058386 0.9196268 -0.001991808 -0.3927881 0.9488599 -0.005590021 -0.315648 0.9927248 0 -0.1204053 0.9997475 0.01049643 -0.01987099 0.9452515 -0.01875501 -0.3258035 0.9898611 5.13964e-4 -0.1420379 0.9885289 5.13727e-4 -0.1510312 0.3273717 0.9355 0.1329198 0.4987202 0.8400356 -0.2135846 0.9014052 0.4293895 -0.0556181 0.7481548 0.6622939 0.04038989 0.7414261 0.6683643 0.05980515 0.7830736 0.598773 -0.1681272 0.4107586 0.7779784 -0.475423 0.4659045 0.7671818 -0.4408687 0.3981294 0.8650273 -0.3053208 0.2437526 0.8474335 -0.4716368 0.0568068 0.9960839 -0.06774961 0.04229265 0.9987111 -0.02806466 0.02152705 0.8118373 -0.5834868 0.001320123 0.7972533 -0.6036435 0.7260891 0.6310399 -0.2730994 0.7260888 0.6310592 -0.2730555 0.5602291 0.738312 -0.3755512 0.5600707 0.7416907 -0.3690743 0.2049941 0.7762917 -0.5961113 0.2034192 0.812533 -0.5462699 0.5636976 0.7308817 -0.3847818 0.8277527 0.5487368 -0.1171051 0.5666491 0.7107896 -0.4167578 0.5391185 0.7672431 -0.3474036 0.4904302 0.7615081 -0.4237733 0.6698187 0.7372829 -0.08807301 0.745495 0.6334369 -0.2073522 0.7879514 0.6118961 -0.06867235 0.808663 0.5797117 -0.09999328 0.83661 0.520393 -0.1710991 0.1516487 0.8154554 -0.5586012 0.1725866 0.7884806 -0.5903492 0.1922687 0.7980812 -0.571051 0.20143 0.7783036 -0.5947012 0.2007532 0.7862511 -0.5843864 0.5711693 0.7808946 -0.2529217 0.6330372 0.7728469 -0.04440242 0.5267797 0.8240557 -0.2084115 0.4423432 0.8257343 -0.3499935 0.1817312 0.8367737 -0.516511 0.181662 0.836758 -0.5165609 0.1760841 0.8412299 -0.5112012 0.1731783 0.8370218 -0.5190414 0.1804094 0.8378477 -0.5152319 0.4861478 0.8573144 -0.1693294 0.4764748 0.8576061 -0.1936073 0.4987063 0.847559 -0.1814826 0.4473551 0.8720945 -0.1983051 0.4468426 0.8786252 -0.1683733 0.160367 0.8405243 -0.5174954 0.1611768 0.8456516 -0.5088177 0.2007336 0.8127009 -0.547013 0.4525294 0.8685116 -0.2022493 0.126114 0.8738311 -0.4695899 0.1612549 0.852119 -0.4978858 0.1477042 0.9061791 -0.3962611 0.1428263 0.909185 -0.3911311 0.1452098 0.9419159 -0.3028343 0.1388775 0.9457935 -0.2935777 0.1146962 0.9648402 -0.2364919 0.1667633 0.9437299 -0.2855941 0.1269673 0.9699622 -0.2074909 0.1372879 0.9778572 -0.1579477 0.1267679 0.9841057 -0.1243623 0.1326444 0.9866036 -0.09496742 0.1237871 0.9912864 -0.04503387 0.1288886 0.9910573 -0.03454333 0.4322909 0.8831771 -0.1819968 0.4337009 0.8822502 -0.1831341 0.4241565 0.8919809 -0.1564019 0.4124633 0.8995261 -0.1439686 0.4080085 0.9047492 -0.122303 0.398927 0.9105002 -0.1088422 0.3959084 0.9134949 -0.09372109 0.3877384 0.9185008 -0.07755839 0.3877127 0.9193782 -0.06650346 0.3815941 0.923147 -0.04675096 0.3818571 0.9233233 -0.04073333 0.3777058 0.9257674 -0.01712036 0.3782915 0.9255653 -0.01498717 0.3117239 -0.6302539 -0.7110615 0.2048201 -0.7610574 -0.6155 0.1767826 -0.7497648 -0.6376526 0.2205786 -0.7434188 -0.6314062 0.1854176 -0.6821517 -0.7073113 0.3842387 -0.7014552 -0.6002677 0.5331593 -0.6980205 -0.4780258 0.170726 -0.7514557 -0.6373124 0.3655555 -0.7999655 -0.4758408 0.43219 -0.7071509 -0.5595976 0.1793054 -0.732353 -0.6568932 0.1792445 -0.7324147 -0.6568412 0.2288204 -0.7322264 -0.6414716 0.1384571 -0.8800712 -0.4542075 0.1831764 -0.8798275 -0.4385772 0.4423798 -0.6424368 -0.6257597 0.4860346 -0.6686552 -0.5627349 0.833741 -0.5150724 -0.1989386 0.9070405 -0.4107469 -0.09254425 0.9363916 -0.3503439 -0.02073633 0.9476273 -0.3186945 0.02089434 0.5379154 -0.6805209 -0.4975323 0.6430047 -0.6652096 -0.3795276 0.5861201 -0.6551056 -0.4767599 0.7715628 -0.5612624 -0.2994588 0.7714375 -0.561326 -0.2996624 0.2324837 -0.715049 -0.6592848 0.2105549 -0.716729 -0.6648054 0.230666 -0.7238146 -0.6502967 0.1727563 -0.7458111 -0.6433671 0.1996996 -0.7418011 -0.6401963 0.4892789 -0.7499262 -0.4452158 0.5587725 -0.7185611 -0.4140573 0.8435028 -0.5087779 -0.1721861 0.8165012 -0.5660171 -0.1138002 0.7916243 -0.6039775 -0.09242451 0.7610553 -0.6100022 -0.2206636 0.6731914 -0.732324 -0.1025432 0.2021559 -0.7843288 -0.5864822 0.1426296 -0.78422 -0.6038675 0.1844567 -0.7989555 -0.5724037 0.4491081 -0.8024222 -0.3929638 0.5352475 -0.8127104 -0.2302438 0.6294159 -0.7741901 -0.06682276 0.5836204 -0.7656872 -0.2703898 0.5034696 -0.8394818 -0.2044226 0.4844709 -0.848185 -0.2141736 0.4901986 -0.8497717 -0.1938904 0.1837838 -0.7995124 -0.5718421 0.1778954 -0.7987275 -0.5747936 0.1792764 -0.8030977 -0.5682377 0.1615505 -0.8055192 -0.5701231 0.1702125 -0.8043501 -0.5692527 0.4453181 -0.8706206 -0.2090733 0.4680604 -0.8602353 -0.202274 0.1289336 -0.9914371 -0.02070897 0.3783233 -0.9256404 -0.007833421 0.1274269 -0.9917207 -0.01589125 0.1318008 -0.9887632 -0.07054084 0.1233853 -0.990822 -0.05520981 0.141393 -0.978992 -0.1469106 0.1115167 -0.9866743 -0.118482 0.1501567 -0.9644662 -0.2173889 0.1149678 -0.9776008 -0.1762927 0.1713927 -0.9412961 -0.2908377 0.1000035 -0.9635848 -0.2479992 0.1326645 -0.9440369 -0.3019844 0.1782649 -0.9141255 -0.3641377 0.1080168 -0.9446732 -0.3097177 0.2137316 -0.8744739 -0.4354473 0.08036899 -0.9123328 -0.4014846 0.2446822 -0.8044151 -0.5413383 0.08059608 -0.8533388 -0.5150896 0.3781315 -0.9257261 -0.006931006 0.3797027 -0.9247199 -0.02681428 0.3784892 -0.9253025 -0.02368944 0.3846653 -0.9213779 -0.05563718 0.3800247 -0.923637 -0.04976052 0.3923858 -0.9161692 -0.08165329 0.3860384 -0.919602 -0.07284647 0.4037011 -0.9083452 -0.1092461 0.3906139 -0.9150252 -0.1007451 0.4155765 -0.8994433 -0.1352701 0.4014169 -0.9075968 -0.1230144 0.4340494 -0.8860483 -0.1628485 0.4089087 -0.8991025 -0.1562326 0.4621189 -0.8633551 -0.2026435 0.4291154 -0.8811575 -0.1985487 -0.9894344 0.004014074 -0.1449261 -0.8185049 0.1519911 -0.5540294 -0.8161578 0.07241737 -0.5732733 -0.8047733 0.1836771 -0.5644491 -0.800325 -0.005804538 -0.5995383 -0.7617542 0.1525238 -0.6296564 -0.762613 -0.0717433 -0.6428642 -0.7437276 0.09361344 -0.6618956 -0.9890138 -0.0434007 -0.1413089 -0.9902663 0.01731765 -0.138104 -0.990742 -0.02458286 -0.1335142 -0.9920067 0.02854394 -0.1229145 -0.9918215 -0.005123138 -0.1275309 -0.9924761 0.03980207 -0.1157893 -0.9749447 0.2006238 -0.09608888 -0.9079573 0.3128871 -0.2787746 -0.9317294 0.03415018 -0.3615441 -0.9278816 0.1190069 -0.3533739 -0.9250908 -0.0152269 -0.3794407 -0.911314 0.09791976 -0.3998983 -0.9108379 -0.05944216 -0.4084619 -0.9045717 0.06182342 -0.4218152 -0.8664402 0.09344577 -0.4904584 -0.8221568 0.3268986 -0.4660425 -0.8678405 0.2804758 -0.4101052 -0.9315842 -0.2351601 -0.2772198 -0.7393278 0.6733301 0.00458008 -0.7477723 0.6639507 -0.002459764 -0.7482237 0.6634463 -6.44469e-4 -0.7953217 0.6046181 -0.04359418 -0.8102189 0.586078 -0.007603287 -0.7363231 0.6766242 -0.002863764 -0.745945 0.6659145 -0.01113629 -0.7430514 0.6690863 -0.01408094 -0.7997366 0.5966767 -0.06632035 -0.7762156 0.6237952 -0.09148299 -0.8558163 0.4845782 -0.1810045 -0.8342643 0.5196659 -0.1842568 -0.8890055 0.4475181 -0.09693849 -0.8802934 0.4699449 -0.06507962 -0.8944683 0.4440518 -0.05238711 -0.9196738 0.382647 -0.08821165 -0.9323526 0.3487667 -0.09529215 -0.870952 0.3525359 -0.3422883 -0.8663604 0.3824313 -0.321195 -0.8895542 0.3283963 -0.317568 -0.8556568 0.4517417 -0.2525486 -0.8707079 0.4165421 -0.2614583 -0.8346414 0.5101929 -0.2075504 -0.8713288 0.2215852 -0.4378198 -0.8713417 0.2216048 -0.437784 -0.9826381 0.1369845 -0.1251312 -0.8852564 0.2523927 -0.3906651 -0.8712025 0.2213581 -0.4381858 -0.9561212 0.2540675 -0.1458837 -0.951185 0.2903663 -0.1045684 -0.9621704 0.250828 -0.1063649 -0.9774729 0.1334959 -0.1634796 -0.9850323 0.09478449 -0.1439699 -0.7017294 0.1154468 -0.7030277 -0.5576071 0.4774364 -0.6790647 -0.6958066 0.1203482 -0.7080745 -0.7200149 0.1433884 -0.6789833 -0.6662216 0.06150776 -0.7432131 -0.7322872 0.3717057 -0.5706053 -0.8092538 0.4093762 -0.4213308 -0.7627174 0.3729867 -0.5283402 -0.7232577 0.2798916 -0.6313153 -0.7232391 0.2798254 -0.631366 -0.7512266 0.5585199 -0.3517304 -0.7520101 0.5588022 -0.3496012 -0.7427591 0.4926008 -0.4534901 -0.7161855 0.6957616 -0.05471813 -0.7058321 0.6938294 -0.1428354 -0.6982001 0.6779956 -0.2298665 -0.6981915 0.6780117 -0.2298452 -0.69192 0.7184661 -0.07108575 -0.7396259 0.6593262 -0.1350651 -0.6220782 0.7829494 0.002996921 -0.6689442 0.7307508 -0.1360772 -0.7147313 0.6925922 -0.09734183 -0.7145497 0.6927639 -0.09745198 -0.7005091 0.7123233 -0.04338866 -0.7907145 0.436488 -0.4292424 -0.7802688 0.5108243 -0.3608867 -0.7718091 0.5410712 -0.3339951 -0.7754742 0.5697872 -0.2719972 -0.7754833 0.5697529 -0.2720431 -0.6960282 0.1859008 -0.6935313 -0.7901825 0.1820908 -0.5851962 -0.7902086 0.1820645 -0.5851691 -0.6567938 0.02071112 -0.7537858 -0.6479073 0.1302682 -0.7504974 -0.5766154 0.2278457 -0.7846025 -0.694695 0.1106177 -0.710748 -0.769308 0.2977759 -0.5652388 -0.7667213 0.3438076 -0.5421577 -0.7635197 0.3352215 -0.551964 -0.7907306 0.4365499 -0.4291496 -0.1226984 0.9888546 -0.08433198 -0.5366925 0.843777 0.001410603 -0.5293151 0.8484172 -0.003720581 -0.5327007 0.8462318 -0.0110324 -0.4675688 0.88249 -0.05090004 -0.4804171 0.8728654 -0.0854724 -0.4059502 0.9047892 -0.1286895 -0.3954173 0.9069592 -0.1451557 -0.538787 0.8424354 -0.00334984 -0.5290077 0.8485652 -0.009376049 -0.5286341 0.8488493 -9.0979e-4 -0.4488752 0.892219 -0.04956394 -0.4465191 0.8947618 -0.00468856 -0.3520543 0.9341242 -0.05890518 -0.3658548 0.9298198 -0.03981906 -0.2562389 0.9615011 -0.09928357 -0.280313 0.9573732 -0.06972223 -0.2525127 0.9658143 -0.05865246 -0.09678149 0.9858912 -0.1365725 -0.3010414 0.9333795 -0.1953893 -0.3371539 0.9209691 -0.1953029 -0.3269929 0.9187144 -0.2214487 -0.212528 0.9364839 -0.2789801 -0.1968068 0.9254556 -0.3237271 -0.04232156 0.9916377 -0.1219169 -0.006297349 0.9893962 -0.1451057 -0.0277056 0.9897873 -0.1398336 0.02577537 0.9871433 -0.1577462 -0.01068204 0.9882551 -0.1524401 0.05651479 0.9832333 -0.1733737 -0.067649 0.9217543 -0.381828 -0.1624297 0.9230458 -0.3487162 -0.09021091 0.9094795 -0.4058439 -0.1296766 0.9091174 -0.3958406 -0.01683712 0.8955003 -0.4447425 -0.08743691 0.8963825 -0.4345727 0.04678702 0.8650718 -0.4994615 -0.2681415 0.8597048 -0.4347504 -0.594803 0.8038637 0.003569304 -0.5637128 0.8233799 -0.06537115 -0.486303 0.8666012 -0.1118561 -0.4837394 0.8648248 -0.1344407 -0.2680773 0.8596724 -0.434854 -0.3286611 0.8843892 -0.3314177 -0.3251674 0.8735235 -0.362247 -0.4637611 0.8582363 -0.2199004 -0.4637342 0.8582383 -0.2199492 -0.1766102 0.8366611 -0.5184661 -0.1000998 0.8283013 -0.5512688 -0.05971777 0.7939877 -0.6049938 -0.1734475 0.8535941 -0.491216 -0.1735045 0.8536095 -0.491169 -0.1362096 0.8023654 -0.5810824 -0.1405858 0.8020176 -0.58052 -0.04393678 0.7927728 -0.6079316 -0.5514057 0.8341179 -0.01411038 -0.5466824 0.8369423 -0.02580994 -0.512613 0.8481254 -0.1338335 -0.5261539 0.8397716 -0.133962 -0.4412008 0.8766109 -0.1920818 -0.3670251 0.8926404 -0.2616978 -0.3083639 0.8852451 -0.348214 -0.4517206 0.8211725 -0.3487469 -0.2701795 0.8777069 -0.3957699 -0.7363231 -0.6766242 -0.002863764 -0.7812279 -0.6227556 -0.04311197 -0.7674431 -0.6363788 -0.07780313 -0.7393278 -0.6733301 0.00458008 -0.7928968 -0.6077886 -0.04368048 -0.7967261 -0.6043406 3.82133e-5 -0.8812571 -0.4635289 -0.09234195 -0.8742766 -0.4821603 -0.05623102 -0.8510075 -0.4972825 -0.1688094 -0.8279263 -0.532324 -0.1765488 -0.8296959 -0.5229099 -0.1953708 -0.8591766 -0.4538172 -0.236359 -0.8626481 -0.4316189 -0.2637113 -0.9620777 -0.2512179 -0.1062836 -0.951117 -0.2906367 -0.1044351 -0.9560444 -0.2543799 -0.1458425 -0.9197852 -0.3851878 -0.07500505 -0.9274365 -0.3584005 -0.1068201 -0.886635 -0.4600095 -0.04764163 -0.9923815 -0.08933168 -0.08484619 -0.9721586 -0.1906093 -0.1362937 -0.9413033 -0.1748942 -0.2887216 -0.9413151 -0.1748813 -0.288691 -0.8895731 -0.3285833 -0.3173212 -0.8663138 -0.3826794 -0.3210247 -0.8709515 -0.3526793 -0.3421414 -0.8809202 -0.2927229 -0.3718779 -0.841471 -0.2579178 -0.4747684 -0.9422648 -0.1366317 -0.305727 -0.9935057 -0.03861802 -0.1070284 -0.9405699 -0.07789027 -0.3305472 -0.9925588 -0.01527446 -0.1208049 -0.9927093 -0.02556008 -0.1177927 -0.9911409 0.005800127 -0.1326884 -0.9914015 -0.009098172 -0.1305391 -0.9889286 0.03222441 -0.1448515 -0.9352664 -0.1126676 -0.3355337 -0.935339 -0.1042125 -0.3380544 -0.9238206 -0.03886568 -0.3808479 -0.923924 -0.06310588 -0.3773356 -0.9060417 0.02417272 -0.4224978 -0.8395869 -0.1388691 -0.5251755 -0.8243764 -0.2309733 -0.5167735 -0.8238576 -0.1571887 -0.5445646 -0.8238604 -0.1573094 -0.5445253 -0.7935119 -0.08416646 -0.6027064 -0.7935189 -0.08817297 -0.602124 -0.7469703 0.009778976 -0.6647856 -0.6735 -0.05388468 -0.7372207 -0.8095285 -0.5856589 -0.04083526 -0.7094533 -0.6717779 -0.2130506 -0.751336 -0.454351 -0.4786015 -0.7779167 -0.5223641 -0.3492587 -0.7927204 -0.5164114 -0.3239037 -0.7557372 -0.5911965 -0.2816882 -0.7094415 -0.6718 -0.21302 -0.7513228 -0.4542998 -0.4786711 -0.7761476 -0.3302363 -0.5371584 -0.7801995 -0.3323646 -0.5299268 -0.6541599 -0.02565383 -0.7559211 -0.6814886 -0.07006794 -0.7284668 -0.7336526 -0.1328514 -0.6664116 -0.6955775 -0.1184682 -0.7086165 -0.7386719 -0.2916985 -0.6076807 -0.738701 -0.2918238 -0.6075852 -0.6983755 -0.1716047 -0.6948551 -0.6974141 -0.1168731 -0.7070745 -0.7520874 -0.2299069 -0.6176629 -0.7958034 -0.432095 -0.4242532 -0.7958075 -0.4320929 -0.4242478 -0.7683008 -0.3372824 -0.5440168 -0.7691154 -0.3307631 -0.5468614 -0.7520848 -0.2299086 -0.6176654 -0.6974903 -0.7165658 0.006395876 -0.7097756 -0.7036303 -0.03351241 -0.7179341 -0.6931517 -0.06412082 -0.7350588 -0.6683881 -0.1137807 -0.7350387 -0.668504 -0.1132276 -0.7810629 -0.5725841 -0.2491755 -0.7853364 -0.523414 -0.3305823 -0.7475585 -0.6014725 -0.2817573 -0.7815196 -0.5150813 -0.3520208 -0.1407585 -0.8231959 -0.5500323 -0.08080548 -0.9106487 -0.405203 -0.005264163 -0.9885967 -0.1504955 -0.2169533 -0.8912847 -0.3981746 0.006447196 -0.8878439 -0.4600999 -0.1491073 -0.890973 -0.4288756 -0.02344483 -0.870109 -0.4923015 0.1044251 -0.8578302 -0.5032126 -0.05523622 -0.9881322 -0.143331 0.03372281 -0.9851721 -0.1682219 -0.03473597 -0.9853204 -0.1671442 0.0750302 -0.9804928 -0.1816709 -0.01274418 -0.9807032 -0.1950866 -0.5377243 -0.8431205 7.78505e-4 -0.4827006 -0.8750373 -0.03619617 -0.4644876 -0.8855797 -6.9964e-5 -0.3857689 -0.9212304 -0.05017137 -0.3641759 -0.9302276 -0.04530537 -0.5391298 -0.8422226 -3.9116e-4 -0.4701724 -0.8813498 -0.04648089 -0.5002943 -0.8627424 -0.0733568 -0.4028859 -0.9052314 -0.1350524 -0.4275763 -0.8936222 -0.1364474 -0.3106306 -0.9281609 -0.2050027 -0.3448702 -0.9196571 -0.1878708 -0.214101 -0.9156127 -0.3403148 -0.2395038 -0.9208605 -0.3076587 -0.1846839 -0.9311053 -0.3145393 -0.340757 -0.9113472 -0.2309355 -0.2607495 -0.9595321 -0.1063387 -0.2871776 -0.9552214 -0.07128226 -0.2562951 -0.9646182 -0.06184482 -0.1468697 -0.9815821 -0.1221719 -0.09573054 -0.989854 -0.1049992 -0.05938458 -0.7371152 -0.6731529 -0.08737373 -0.762762 -0.6407495 -0.1797429 -0.7829634 -0.5955342 -0.1797143 -0.7829475 -0.5955637 -0.2862231 -0.8152768 -0.5033887 -0.2990128 -0.8394449 -0.4537881 -0.2446473 -0.8119763 -0.5299456 -0.460117 -0.8690599 -0.181734 -0.4466931 -0.8542739 -0.2658597 -0.4251547 -0.8360593 -0.3467688 -0.4251331 -0.8360596 -0.3467941 -0.5905871 -0.7973873 -0.1240177 -0.5410749 -0.8161184 -0.2029503 -0.5690069 -0.8184738 -0.07957315 -0.6139226 -0.78654 -0.06673848 -0.642134 -0.7665849 0.003403961 -0.4130284 -0.8613028 -0.2959143 -0.469558 -0.8609863 -0.1954943 -0.541905 -0.8360906 -0.08539104 -0.5396937 -0.8345585 -0.1106476 -0.5707467 -0.8205605 -0.03047382 -0.4616553 -0.8229662 -0.3310609 -0.4137794 -0.8619125 -0.293076 -0.4132127 -0.8613553 -0.2955037 -0.1316967 -0.7896269 -0.5992874 -0.2103255 -0.8261837 -0.52267 -0.2654024 -0.8321167 -0.486974 -0.3013084 -0.8582611 -0.4154533 -0.301277 -0.8582473 -0.4155043 -0.1316533 -0.7895833 -0.5993545 -0.09707707 -0.755059 -0.6484305 -0.04671537 -0.73989 -0.671104 -0.1580486 -0.9658702 -0.2052202 -0.1580417 -0.9658737 -0.2052093 -0.1253865 -0.9807903 -0.1494281 -0.4681414 -0.7069685 -0.5301314 -0.3462063 -0.8313825 -0.4346776 -0.4433889 -0.7070247 -0.5509286 -0.54 -0.5555415 -0.6322766 -0.612534 -0.2588559 -0.7468573 -0.6221131 -0.1950731 -0.758236 -0.6208822 -0.2588328 -0.7399398 -0.1251134 -0.8355695 -0.534949 -0.1213209 -0.7071908 -0.6965361 -0.06701636 -0.6671941 -0.7418631 -0.1199771 -0.6652263 -0.7369393 -0.2608919 -0.5119718 -0.8184256 -0.2974922 -0.5064023 -0.8093548 -0.436659 -0.3215346 -0.840205 -0.4570721 -0.3163431 -0.8312715 -0.5824933 -0.1088542 -0.8055137 -0.5886266 -0.1067435 -0.8013268 -0.03677368 -0.7940856 -0.6066927 -0.08185452 -0.7982366 -0.5967566 -0.2463929 -0.6251705 -0.7405758 -0.328297 -0.5608373 -0.7600544 -0.4349048 -0.3993321 -0.8070884 -0.4791839 -0.3527045 -0.8037303 -0.5848053 -0.1366813 -0.7995755 -0.5970969 -0.1195703 -0.7932077 -0.04311096 -0.907616 -0.4175822 -0.0868107 -0.9135744 -0.3972981 -0.26634 -0.7392606 -0.6185118 -0.3499804 -0.6706146 -0.6540564 -0.4587481 -0.4824465 -0.7461874 -0.5021548 -0.4287615 -0.7510021 -0.5970124 -0.1672837 -0.784597 -0.6081919 -0.1468768 -0.7800832 -0.0521838 -0.9763724 -0.2096994 -0.1789752 -0.9358032 -0.3037111 -0.2935494 -0.8287031 -0.4765291 -0.3781494 -0.7624785 -0.5250045 -0.4906378 -0.5546821 -0.6720137 -0.5324517 -0.4976993 -0.6846828 -0.6131491 -0.1950357 -0.7655125 -0.6228345 -0.1725896 -0.7630793 -0.5862228 -0.104716 -0.803354 -0.5346675 -0.2196663 -0.8160131 -0.09521204 -0.6448631 -0.7583444 -0.2030627 -0.5844469 -0.7856127 -0.2796276 -0.4914976 -0.8247658 -0.446748 -0.3076635 -0.8400949 -0.1980156 -0.5902019 -0.782593 -0.1805785 -0.5803304 -0.7941083 -0.5613257 -0.2745106 -0.7807416 -0.5140146 -0.2532685 -0.819539 -0.1939175 -0.5768586 -0.7934924 -0.1737514 -0.5667735 -0.8053436 -0.5505301 -0.2331603 -0.801594 -0.4949229 -0.2112131 -0.8428763 -0.5863059 -0.333739 -0.7381488 -0.6526685 -0.7576432 8.55772e-4 -0.6505939 -0.75613 -0.07067525 -0.6294836 -0.7738156 -0.07042616 -0.670834 -0.7416074 5.7459e-4 -0.6673505 -0.7409508 -0.07506918 -0.6850757 -0.7249763 -0.0712794 -0.6854426 -0.7246242 -0.07133257 -0.6712043 -0.7109733 -0.2097662 -0.6972041 -0.6835727 -0.2159513 -0.6133226 -0.7581776 -0.2213645 -0.5945362 -0.7766678 -0.2081201 -0.5840869 -0.7829658 -0.2140256 -0.5708681 -0.7696322 -0.2859651 -0.5636599 -0.7702512 -0.29833 -0.6971893 -0.6835967 -0.2159231 -0.6812773 -0.6669943 -0.3016286 -0.6881342 -0.6659437 -0.2880807 -0.6645071 -0.6415565 -0.3831914 -0.6954414 -0.6197814 -0.3636376 -0.6445935 -0.565667 -0.5143153 -0.6634948 -0.5646762 -0.4908314 -0.5431333 -0.7481074 -0.3812368 -0.5185551 -0.7755039 -0.3601311 -0.5136667 -0.7725778 -0.3731891 -0.4758725 -0.7319208 -0.4876856 -0.4373243 -0.7458882 -0.5023927 -0.4099311 -0.716447 -0.5645 -0.3894725 -0.7114506 -0.5849353 -0.6717169 -0.5401546 -0.5069808 -0.6330476 -0.4981536 -0.5925316 -0.6518973 -0.5014801 -0.5688127 -0.5975623 -0.4433514 -0.668101 -0.6321487 -0.4365383 -0.6401738 -0.6226447 -0.4197832 -0.6603754 -0.5467106 -0.33761 -0.7662423 -0.3466456 -0.6632214 -0.6633055 -0.3528507 -0.6861763 -0.6361278 -0.3194596 -0.6857765 -0.6539543 -0.2637056 -0.6238516 -0.7357096 -0.2195679 -0.6234109 -0.7504324 -0.6208819 0.2588148 -0.7399464 -0.6208735 0.2588471 -0.7399421 -0.4545062 0.7071183 -0.5416715 -0.4545319 0.7070891 -0.541688 -0.1663642 0.9659267 -0.1982639 -0.1663646 0.9659265 -0.1982645 -0.6060702 0.2587665 -0.7521428 -0.6011509 0.2282645 -0.7658414 -0.4265641 0.7066568 -0.5645169 -0.4297511 0.6372883 -0.63967 -0.1403356 0.965373 -0.219911 -0.07435405 0.8884543 -0.4529026 -0.07444548 0.8884404 -0.4529144 -0.1587301 0.9092808 -0.3847249 -0.3852398 0.4526265 -0.8041888 -0.3648325 0.5334812 -0.7630826 -0.5724895 0.156477 -0.8048421 -0.569003 0.1866795 -0.800866 -0.585227 0.2251191 -0.7789935 -0.5846595 0.1932644 -0.7879227 -0.3916544 0.6294993 -0.671072 -0.403963 0.5501694 -0.7308403 -0.2022265 0.8333218 -0.51447 -0.1066438 0.7953227 -0.5967319 -0.1454011 0.6894642 -0.7095758 -0.569195 0.1540955 -0.8076335 -0.569153 0.1541317 -0.8076561 -0.3720266 0.4434234 -0.8154582 -0.3720651 0.4433911 -0.8154581 -0.1293064 0.6783432 -0.7232776 -0.1293395 0.6783261 -0.7232878 -0.1881174 0.7456799 -0.6391974 -0.1956095 0.6692897 -0.7167903 -0.607245 0.2716527 -0.7466313 -0.5898355 0.4305047 -0.6831982 -0.4375327 0.5543804 -0.7079742 -0.4562824 0.2742423 -0.8465209 -0.2387781 0.7202737 -0.6512993 -0.5854874 0.1656482 -0.7935776 -0.5799399 0.2462029 -0.7765654 -0.3800824 0.4490854 -0.8086161 -0.3738589 0.4953781 -0.784111 -0.1281461 0.6775306 -0.7242451 -0.1267129 0.6909265 -0.7117334 -0.3263683 0.7673918 -0.5519001 -0.6025846 0.7980546 -8.70368e-4 -0.5990178 0.797729 -0.06932741 -0.6150659 0.7884752 -0.001016378 -0.6119838 0.787043 -0.07771223 -0.5771101 0.8137738 -0.06867659 -0.5690293 0.8071948 -0.1569786 -0.5172016 0.8229848 -0.2349441 -0.5529205 0.8013027 -0.2284575 -0.5640069 0.8123365 -0.1483435 -0.6326939 0.7595894 -0.1507403 -0.6397024 0.765354 -0.07081121 -0.6283433 0.6872259 -0.3645617 -0.6553798 0.7162413 -0.239741 -0.6483013 0.7253034 -0.2316042 -0.6241742 0.7414832 -0.2461895 -0.6372952 0.7543195 -0.157661 -0.517255 0.8229623 -0.2349056 -0.4846393 0.7872967 -0.3811678 -0.4551238 0.8161299 -0.3560819 -0.4139478 0.7693731 -0.4865309 -0.4017142 0.7926068 -0.4586942 -0.3919875 0.7851912 -0.4793964 -0.3474168 0.731868 -0.5862345 -0.5538843 0.4437691 -0.7044723 -0.6195957 0.5206404 -0.5873967 -0.6036624 0.5594508 -0.5679848 -0.6362255 0.5968629 -0.4888476 -0.6363887 0.6121872 -0.4692935 -0.6163722 0.6135231 -0.4936342 -0.6534792 0.655445 -0.3786249 -0.5818225 0.4205244 -0.6961622 -0.5818269 0.4205702 -0.6961309 -0.5880241 0.4466213 -0.6743568 -0.2358652 0.7169541 -0.6560065 -0.2629891 0.6917202 -0.6725771 -0.2201585 0.6987273 -0.6806691 0.001229822 0.7961211 -0.6051361 0.02273499 0.7933385 -0.6083562 0.022619 0.793794 -0.6077661 0.08719187 0.7823379 -0.6167212 0.08694583 0.7830557 -0.6158443 0.2475298 0.7389034 -0.6266984 0.409597 0.6695119 -0.6196646 0.4092376 0.6695901 -0.6198175 0.4096115 0.6694945 -0.6196737 0.4090831 0.6698784 -0.6196081 0.4094719 0.6696345 -0.6196148 0.2473933 0.7393553 -0.626219 0.9899316 -0.01142829 -0.1410845 0.9906625 -0.1361847 -0.006456375 0.9956209 0.04545575 -0.08168751 0.9941585 -0.07631266 -0.07632476 0.994157 -0.07636356 -0.07629209 0.9999666 -0.005768716 -0.005799293 0.7739782 -0.5024926 -0.385304 0.9738382 -0.2119987 -0.08182901 0.9769081 -0.07122129 -0.2014402 0.9738036 -0.2120512 -0.08210319 0.9643314 -0.2378786 -0.1160984 0.9656098 -0.2363863 -0.1082553 0.9426826 -0.2800361 -0.1814648 0.9436689 -0.2951192 -0.1496457 0.8981115 -0.3298028 -0.2909052 0.8971212 -0.3765404 -0.2310649 0.8488345 -0.374377 -0.3732584 0.8624409 -0.3985312 -0.3120397 0.8379706 -0.4092862 -0.3609572 0.789911 -0.3911164 -0.4723014 0.974901 -0.07402706 -0.2099722 0.9723754 -0.08086884 -0.2189665 0.9712591 -0.08209002 -0.2234214 0.9626459 -0.09925448 -0.2519155 0.963185 -0.1003789 -0.249397 0.9431739 -0.1158167 -0.3114636 0.946357 -0.1287499 -0.2963646 0.9239053 -0.1276288 -0.3607076 0.9300385 -0.1424219 -0.3387396 0.8983635 -0.131393 -0.4191407 0.9025058 -0.1776943 -0.3923112 0.5673376 -0.5500894 -0.6128048 0.8709193 -0.1948727 -0.4511366 0.8607953 -0.1437193 -0.4882381 0.6932078 -0.5502873 -0.4654535 0.6919875 -0.4345561 -0.5764671 0.8426651 -0.2151165 -0.4935996 0.8293599 -0.1567376 -0.5362793 0.6668948 -0.5301199 -0.5236644 0.6090222 -0.4711418 -0.6380575 0.8259693 -0.2059119 -0.5247621 0.8210566 -0.19351 -0.5370477 0.5699482 -0.5553633 -0.605583 0.5693793 -0.5521611 -0.6090365 0.7977253 -0.1919248 -0.5716635 0.7962909 -0.1687437 -0.5809014 0.5164324 -0.4963772 -0.6977874 0.517987 -0.4901321 -0.7010421 0.7077773 0.00114113 -0.7064348 0.7095534 -0.003272831 -0.7046441 0.6982014 -0.02300053 -0.7155318 0.734409 -0.06311184 -0.6757665 0.6530677 -0.1355458 -0.7450704 0.6505202 -0.1437753 -0.7457561 0.6980855 -0.2059968 -0.685742 0.638997 -0.2155455 -0.7383921 0.6127262 -0.270727 -0.742478 0.7723326 -0.1391836 -0.6197826 0.774605 -0.1408318 -0.6165658 0.7800357 -0.126591 -0.612796 0.7525386 -0.08398866 -0.6531706 0.7555218 -0.07545465 -0.6507638 0.7266945 -0.03828352 -0.6858933 0.7310985 -0.02861505 -0.6816716 0.7097649 -0.004978358 -0.7044211 0.7114761 0.002053439 -0.7027073 0.709227 0.004259586 -0.7049674 0.659386 -0.34477 -0.6680897 0.525003 -0.367035 -0.7678915 0.4881916 -0.4373749 -0.7552298 0.9637161 0.2586125 -0.06611239 0.9637164 0.06611764 -0.2586103 0.9697616 0.09148734 -0.2262579 0.9684138 0.1059628 -0.2257134 0.9927726 4.72211e-4 -0.1200103 0.9706935 0.2189271 -0.09912115 0.9927735 0.1200025 -4.82422e-4 0.9927756 0.1199852 -4.81732e-4 0.5911905 0.6149296 -0.5218768 0.6482251 0.6340395 -0.4216613 0.6484817 0.6337148 -0.4217548 0.8300907 0.2262449 -0.5096693 0.83001 0.2261175 -0.5098574 0.8299057 0.2260493 -0.5100572 0.6500673 0.590933 -0.4777143 0.6794201 0.5977175 -0.4255846 0.7634856 0.5136904 -0.3914232 0.7801673 0.5113111 -0.3604164 0.7806867 0.5111633 -0.3595001 0.8159921 0.488413 -0.309208 0.7880306 0.4893289 -0.3735842 0.8391284 0.4709322 -0.272188 0.87031 0.4190716 -0.2587268 0.8929217 0.3975118 -0.2113654 0.9049781 0.3781993 -0.1948849 0.9275109 0.3463761 -0.1405243 0.9327737 0.3322386 -0.1398243 0.8088424 0.203724 -0.5516071 0.8450335 0.2121024 -0.4908472 0.866064 0.1808551 -0.4660737 0.8812603 0.1783146 -0.4377034 0.8912576 0.1685969 -0.4209929 0.9063621 0.1627379 -0.3899028 0.9106179 0.1521306 -0.3842281 0.9265606 0.1364657 -0.3505174 0.9268795 0.1358984 -0.3498942 0.9419299 0.115809 -0.3152086 0.9399645 0.1249712 -0.3175674 0.6887924 0.6426601 -0.3354893 0.8139163 0.2207048 -0.5374287 0.6887641 0.6426749 -0.3355191 0.5915 0.5546256 -0.5852506 0.8138993 0.2206482 -0.5374778 0.8142961 0.2201729 -0.5370715 0.4648696 0.5584863 -0.6870148 0.5652444 0.4945414 -0.6602482 0.7141115 0.3559179 -0.6027995 0.4621523 0.4528536 -0.7624558 0.4631381 0.6400889 -0.6130166 0.7063379 -0.001135349 -0.707874 0.7127549 0.004367351 -0.7013997 0.6598234 0.1225741 -0.741356 0.7189373 0.03936028 -0.6939596 0.6993115 0.01830911 -0.7145826 0.5176783 0.3996514 -0.7564972 0.6597068 0.1228145 -0.74142 0.7021974 0.1764891 -0.6897612 0.6228428 0.2171286 -0.7516131 0.6805623 0.3023952 -0.6673771 0.6158723 0.2858828 -0.7341474 0.5025611 0.3715758 -0.7806175 0.7688528 0.1262418 -0.6268401 0.7094913 -0.004324495 -0.704701 0.7103796 -8.74852e-4 -0.7038182 0.7084156 0.004346966 -0.7057822 0.7279298 0.02586066 -0.6851639 0.723562 0.0322324 -0.6895065 0.7507933 0.06631964 -0.6571994 0.7460098 0.0705856 -0.6621837 0.7768334 0.1158165 -0.618964 0.7672566 0.1245337 -0.6291333 0 0 -1 -0.6791808 0 0.733971 -0.6786826 0 0.7344318 -0.2973482 0 0.9547691 -0.2977405 0 0.954647 -0.2962558 0 0.9551087 0.6505188 0 0.7594901 0.6504684 0 0.7595334 -0.2599059 0 0.9656341 -0.2817229 0 0.9594959 -0.2969409 0 0.954896 0.8656446 -0.201632 -0.4582621 0.650869 0 0.7591901 0.651155 0 0.7589449 0.9610607 0 0.2763375 0.8940551 -0.1418277 0.4249122 0.9433789 0 -0.331717 0.9433889 0 -0.3316887 0.9977445 0 0.06712651 0.9977437 0 0.06713891 0.999854 0 -0.017089 0.8264161 5.30871e-4 0.5630596 0.98552 0.14577 0.08661115 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 5 2 4 2 6 2 5 3 6 3 7 3 7 4 6 4 8 4 7 5 8 5 9 5 9 5 8 5 10 5 9 6 10 6 11 6 11 7 10 7 12 7 11 8 12 8 13 8 13 9 12 9 14 9 13 10 14 10 15 10 15 11 14 11 16 11 15 12 16 12 17 12 17 13 16 13 18 13 17 14 18 14 19 14 19 15 18 15 20 15 19 16 20 16 21 16 22 17 23 17 24 17 22 18 24 18 25 18 25 19 24 19 26 19 25 20 26 20 27 20 27 21 26 21 28 21 27 22 28 22 29 22 29 23 28 23 30 23 29 24 30 24 31 24 31 25 30 25 32 25 31 26 32 26 33 26 33 27 32 27 34 27 33 28 34 28 35 28 35 29 34 29 36 29 35 30 36 30 37 30 37 31 36 31 38 31 37 32 38 32 39 32 39 33 38 33 40 33 39 34 40 34 41 34 41 35 40 35 42 35 41 36 42 36 21 36 21 36 42 36 43 36 21 37 43 37 19 37 2 38 1 38 44 38 45 39 46 39 47 39 45 40 47 40 1 40 1 41 47 41 48 41 1 42 48 42 44 42 45 43 49 43 46 43 46 44 49 44 50 44 46 45 50 45 51 45 51 46 50 46 52 46 52 47 53 47 51 47 51 48 53 48 54 48 51 49 54 49 55 49 55 50 54 50 56 50 55 51 56 51 57 51 57 52 56 52 58 52 58 53 56 53 59 53 58 54 59 54 22 54 22 55 59 55 60 55 22 56 60 56 23 56 61 57 62 57 63 57 63 58 62 58 64 58 63 59 64 59 2 59 2 60 64 60 65 60 2 61 65 61 0 61 66 62 67 62 68 62 68 63 67 63 69 63 68 64 69 64 70 64 70 65 69 65 71 65 70 66 71 66 72 66 72 67 71 67 73 67 72 68 73 68 74 68 74 69 73 69 75 69 74 70 75 70 76 70 63 71 77 71 61 71 61 72 77 72 78 72 61 73 78 73 79 73 79 74 78 74 66 74 79 75 66 75 80 75 80 76 66 76 68 76 75 77 81 77 76 77 76 78 81 78 82 78 76 79 82 79 83 79 83 80 82 80 84 80 83 80 84 80 85 80 85 81 84 81 86 81 85 82 86 82 87 82 87 83 86 83 88 83 87 84 88 84 89 84 89 85 88 85 90 85 89 85 90 85 91 85 4 86 3 86 92 86 92 87 3 87 93 87 92 88 93 88 94 88 94 89 93 89 95 89 91 90 90 90 96 90 96 91 90 91 97 91 96 92 97 92 98 92 98 93 97 93 99 93 98 94 99 94 100 94 99 95 101 95 100 95 100 96 101 96 102 96 100 97 102 97 103 97 103 98 102 98 104 98 103 99 104 99 105 99 105 100 104 100 106 100 105 101 106 101 107 101 107 102 106 102 108 102 107 103 108 103 109 103 109 104 108 104 110 104 109 105 110 105 111 105 111 106 110 106 112 106 111 107 112 107 113 107 113 108 112 108 114 108 113 109 114 109 95 109 95 110 114 110 115 110 95 111 115 111 94 111 116 112 117 112 118 112 118 113 117 113 119 113 118 114 119 114 120 114 120 115 119 115 121 115 120 116 121 116 122 116 122 117 121 117 123 117 124 118 125 118 126 118 126 118 125 118 127 118 128 119 129 119 130 119 130 120 131 120 128 120 128 121 131 121 132 121 128 120 132 120 133 120 133 120 132 120 134 120 133 122 134 122 135 122 135 120 136 120 133 120 133 123 136 123 137 123 133 124 137 124 138 124 139 125 140 125 141 125 142 126 143 126 144 126 144 127 143 127 139 127 145 128 146 128 147 128 139 129 141 129 144 129 144 130 141 130 148 130 144 131 148 131 149 131 149 132 148 132 145 132 149 133 145 133 150 133 150 134 145 134 147 134 150 135 147 135 151 135 152 136 106 136 104 136 104 137 153 137 152 137 152 138 153 138 154 138 152 139 154 139 142 139 142 140 154 140 155 140 142 141 155 141 143 141 156 142 157 142 158 142 158 143 157 143 159 143 158 142 159 142 160 142 160 144 161 144 158 144 158 142 161 142 162 142 158 142 162 142 163 142 164 145 165 145 166 145 167 145 168 145 169 145 169 146 168 146 164 146 166 145 170 145 164 145 164 147 170 147 171 147 164 148 171 148 169 148 172 149 173 149 174 149 175 150 176 150 177 150 177 151 176 151 178 151 177 152 178 152 179 152 179 153 178 153 172 153 172 154 178 154 180 154 172 155 180 155 173 155 174 156 181 156 172 156 172 157 181 157 182 157 172 158 182 158 183 158 184 159 185 159 186 159 187 160 188 160 189 160 189 161 188 161 190 161 189 162 190 162 186 162 186 163 190 163 191 163 186 164 191 164 184 164 192 165 193 165 194 165 190 166 195 166 191 166 191 167 195 167 192 167 191 168 192 168 196 168 196 169 192 169 194 169 189 170 197 170 187 170 187 171 197 171 198 171 187 172 198 172 199 172 200 173 201 173 202 173 202 174 201 174 203 174 199 175 204 175 187 175 187 176 204 176 205 176 187 177 205 177 200 177 200 178 205 178 206 178 200 179 206 179 201 179 134 180 132 180 207 180 134 180 207 180 208 180 208 181 207 181 209 181 208 181 209 181 210 181 210 182 209 182 146 182 210 182 146 182 145 182 18 183 16 183 211 183 211 184 16 184 14 184 211 185 14 185 212 185 41 142 21 142 211 142 211 142 21 142 20 142 211 186 20 186 18 186 14 187 12 187 212 187 212 188 12 188 10 188 212 189 10 189 8 189 8 190 6 190 212 190 212 191 6 191 4 191 212 192 4 192 92 192 213 193 172 193 183 193 214 194 215 194 216 194 213 195 183 195 217 195 211 196 212 196 218 196 218 197 212 197 219 197 218 198 219 198 220 198 220 199 219 199 221 199 220 200 221 200 222 200 222 201 221 201 217 201 222 202 217 202 216 202 216 203 217 203 183 203 216 204 183 204 214 204 81 205 75 205 194 205 88 206 193 206 90 206 90 145 193 145 97 145 88 145 86 145 193 145 193 207 86 207 84 207 193 145 84 145 194 145 194 208 84 208 82 208 194 209 82 209 81 209 223 210 224 210 225 210 224 211 226 211 225 211 225 212 226 212 227 212 225 213 227 213 228 213 225 214 229 214 223 214 223 215 229 215 230 215 223 216 230 216 231 216 232 217 233 217 234 217 234 218 233 218 235 218 234 219 235 219 236 219 237 220 238 220 235 220 235 221 238 221 239 221 235 222 239 222 236 222 240 223 241 223 242 223 240 224 242 224 243 224 242 225 244 225 245 225 243 226 242 226 246 226 246 227 242 227 247 227 246 228 247 228 248 228 249 229 250 229 247 229 247 230 250 230 251 230 247 231 251 231 248 231 242 232 245 232 247 232 247 233 245 233 252 233 247 234 252 234 249 234 253 235 254 235 255 235 256 236 257 236 258 236 258 237 257 237 259 237 259 238 260 238 258 238 258 239 260 239 261 239 258 240 261 240 262 240 263 241 264 241 258 241 258 242 264 242 265 242 258 243 265 243 256 243 262 244 266 244 258 244 258 245 266 245 253 245 258 246 253 246 263 246 263 247 253 247 255 247 167 248 169 248 267 248 267 249 169 249 268 249 267 250 268 250 269 250 269 251 268 251 270 251 206 252 205 252 271 252 271 253 272 253 206 253 206 254 272 254 273 254 206 255 273 255 268 255 268 256 273 256 274 256 268 257 274 257 270 257 275 258 276 258 277 258 277 259 276 259 278 259 277 260 278 260 178 260 178 261 278 261 279 261 178 262 279 262 180 262 159 263 157 263 280 263 280 264 157 264 281 264 280 265 281 265 282 265 282 266 283 266 280 266 280 267 283 267 284 267 280 268 284 268 277 268 277 269 284 269 285 269 277 270 285 270 275 270 41 271 211 271 39 271 39 272 211 272 286 272 39 273 286 273 37 273 287 274 27 274 29 274 29 275 31 275 287 275 287 276 31 276 33 276 287 277 33 277 286 277 286 278 33 278 35 278 286 279 35 279 37 279 288 280 55 280 57 280 57 281 58 281 288 281 288 282 58 282 22 282 288 283 22 283 287 283 287 284 22 284 25 284 287 285 25 285 27 285 289 286 288 286 290 286 290 287 288 287 120 287 290 288 120 288 122 288 289 289 291 289 288 289 288 290 291 290 292 290 288 291 292 291 293 291 293 292 294 292 288 292 288 293 294 293 295 293 288 294 295 294 296 294 296 295 297 295 288 295 288 296 297 296 51 296 288 297 51 297 55 297 220 298 222 298 298 298 298 299 222 299 216 299 116 300 118 300 299 300 299 301 118 301 300 301 299 302 300 302 301 302 301 303 300 303 302 303 303 304 304 304 305 304 305 305 304 305 306 305 305 306 306 306 307 306 308 307 309 307 310 307 310 308 309 308 311 308 310 309 311 309 312 309 215 310 312 310 216 310 216 311 312 311 311 311 216 312 311 312 298 312 298 313 311 313 309 313 298 314 309 314 303 314 303 315 309 315 313 315 303 316 313 316 304 316 218 317 220 317 314 317 314 318 220 318 298 318 314 319 298 319 315 319 315 320 298 320 303 320 315 321 303 321 300 321 300 322 303 322 305 322 300 323 305 323 302 323 302 324 305 324 307 324 211 325 218 325 286 325 286 326 218 326 314 326 286 327 314 327 287 327 287 328 314 328 315 328 287 329 315 329 288 329 288 330 315 330 300 330 288 331 300 331 120 331 120 332 300 332 118 332 46 333 316 333 317 333 46 334 317 334 318 334 318 335 317 335 319 335 318 336 319 336 320 336 320 337 321 337 318 337 318 338 321 338 322 338 318 339 322 339 323 339 123 340 121 340 324 340 324 341 121 341 318 341 324 342 318 342 325 342 325 343 318 343 323 343 44 344 48 344 318 344 318 345 48 345 47 345 318 346 47 346 46 346 78 347 326 347 66 347 66 348 326 348 327 348 78 349 77 349 326 349 326 350 77 350 63 350 326 351 63 351 318 351 318 352 63 352 2 352 318 353 2 353 44 353 194 354 75 354 327 354 327 355 75 355 73 355 327 356 73 356 71 356 71 357 69 357 327 357 327 358 69 358 67 358 327 359 67 359 66 359 328 360 329 360 330 360 331 361 185 361 184 361 332 362 333 362 334 362 335 363 336 363 337 363 337 364 336 364 338 364 337 365 338 365 332 365 332 366 338 366 339 366 332 367 339 367 333 367 329 368 340 368 330 368 330 369 340 369 341 369 330 370 341 370 337 370 337 371 341 371 342 371 337 372 342 372 335 372 119 373 117 373 343 373 343 374 117 374 344 374 196 375 194 375 345 375 345 376 194 376 327 376 345 377 327 377 346 377 346 378 327 378 326 378 346 379 326 379 343 379 343 380 326 380 318 380 343 381 318 381 119 381 119 382 318 382 121 382 332 383 345 383 337 383 337 384 345 384 346 384 337 385 346 385 330 385 330 386 346 386 343 386 330 387 343 387 328 387 328 388 343 388 344 388 334 389 331 389 332 389 332 390 331 390 184 390 332 391 184 391 345 391 345 392 184 392 191 392 345 393 191 393 196 393 254 394 253 394 347 394 348 395 349 395 347 395 347 396 349 396 350 396 347 397 350 397 254 397 351 398 352 398 353 398 353 399 352 399 354 399 353 400 354 400 348 400 348 401 354 401 355 401 348 402 355 402 349 402 125 403 124 403 353 403 353 404 124 404 356 404 353 405 356 405 351 405 357 406 358 406 359 406 360 407 361 407 362 407 362 408 361 408 363 408 362 409 363 409 358 409 359 410 364 410 357 410 357 411 364 411 365 411 357 412 365 412 366 412 242 413 241 413 365 413 365 414 241 414 367 414 365 415 367 415 366 415 358 416 363 416 359 416 359 417 363 417 126 417 359 418 126 418 127 418 117 419 116 419 368 419 368 420 116 420 369 420 368 421 369 421 370 421 370 422 369 422 371 422 370 423 371 423 372 423 372 424 371 424 373 424 372 425 373 425 374 425 374 426 373 426 375 426 376 427 377 427 378 427 379 428 380 428 381 428 381 429 380 429 382 429 381 430 382 430 383 430 383 431 384 431 381 431 381 432 384 432 385 432 381 433 385 433 386 433 386 434 385 434 387 434 386 435 387 435 375 435 375 436 387 436 388 436 375 437 388 437 374 437 379 438 381 438 378 438 378 439 381 439 389 439 378 440 389 440 376 440 390 441 391 441 378 441 377 442 392 442 378 442 378 443 392 443 393 443 378 444 393 444 394 444 394 445 395 445 378 445 378 446 395 446 396 446 378 447 396 447 390 447 397 448 124 448 126 448 391 449 398 449 378 449 378 450 398 450 397 450 378 451 397 451 399 451 399 452 397 452 126 452 400 453 189 453 186 453 401 454 402 454 403 454 404 455 360 455 362 455 404 456 362 456 405 456 405 457 362 457 406 457 405 458 406 458 407 458 408 459 409 459 403 459 403 460 409 460 410 460 403 461 410 461 401 461 411 462 412 462 403 462 403 463 412 463 413 463 403 464 413 464 408 464 186 465 185 465 414 465 414 466 411 466 186 466 186 467 411 467 403 467 186 468 403 468 400 468 400 469 403 469 402 469 400 470 402 470 406 470 406 471 402 471 415 471 406 472 415 472 407 472 197 473 189 473 416 473 416 474 189 474 400 474 416 475 400 475 417 475 417 476 400 476 406 476 358 477 357 477 418 477 418 478 357 478 366 478 418 479 366 479 367 479 198 480 197 480 419 480 419 481 197 481 416 481 419 482 416 482 418 482 418 483 416 483 417 483 418 484 417 484 358 484 358 485 417 485 406 485 358 486 406 486 362 486 199 487 198 487 420 487 420 488 198 488 419 488 420 489 419 489 421 489 421 490 419 490 418 490 421 491 418 491 241 491 241 492 418 492 367 492 204 493 199 493 422 493 422 494 199 494 420 494 422 495 420 495 423 495 423 496 420 496 421 496 243 497 423 497 240 497 240 498 423 498 421 498 240 499 421 499 241 499 205 500 204 500 424 500 424 501 204 501 422 501 424 502 422 502 425 502 425 503 422 503 423 503 425 504 423 504 426 504 426 505 423 505 243 505 426 506 243 506 246 506 424 507 425 507 427 507 427 508 425 508 426 508 271 509 205 509 424 509 424 510 427 510 271 510 271 511 427 511 428 511 271 512 428 512 272 512 272 513 428 513 429 513 272 514 429 514 273 514 426 515 246 515 427 515 427 516 246 516 248 516 427 517 248 517 428 517 428 518 248 518 251 518 428 519 251 519 429 519 429 520 251 520 250 520 429 521 250 521 430 521 430 522 250 522 249 522 430 523 249 523 431 523 431 524 249 524 252 524 431 525 252 525 432 525 432 526 252 526 245 526 432 527 245 527 433 527 273 528 429 528 274 528 274 529 429 529 430 529 274 530 430 530 270 530 270 531 430 531 431 531 270 532 431 532 269 532 269 533 431 533 432 533 269 534 432 534 267 534 267 535 432 535 433 535 267 536 433 536 167 536 168 537 167 537 433 537 168 537 433 537 434 537 434 538 433 538 245 538 434 539 245 539 244 539 215 540 435 540 312 540 436 541 437 541 438 541 438 542 437 542 435 542 312 543 435 543 310 543 310 544 435 544 437 544 310 545 437 545 308 545 435 546 215 546 214 546 439 547 440 547 441 547 442 548 439 548 443 548 443 549 439 549 441 549 443 550 441 550 444 550 442 551 436 551 439 551 439 552 436 552 438 552 439 553 438 553 435 553 435 554 214 554 439 554 439 555 214 555 183 555 439 556 183 556 440 556 445 557 446 557 447 557 440 558 183 558 182 558 448 559 449 559 450 559 449 560 451 560 450 560 450 561 451 561 452 561 450 562 452 562 444 562 453 563 454 563 447 563 354 564 352 564 455 564 456 565 441 565 440 565 457 566 450 566 456 566 456 567 450 567 444 567 456 568 444 568 441 568 455 569 453 569 354 569 354 570 453 570 447 570 354 571 447 571 355 571 355 572 447 572 446 572 355 573 446 573 349 573 349 574 446 574 350 574 440 575 182 575 456 575 456 576 182 576 181 576 456 577 181 577 457 577 457 578 181 578 174 578 457 579 174 579 458 579 458 580 459 580 457 580 457 581 459 581 445 581 457 582 445 582 450 582 450 583 445 583 447 583 450 584 447 584 448 584 448 585 447 585 454 585 254 586 350 586 460 586 460 587 350 587 446 587 460 588 446 588 461 588 461 589 446 589 445 589 461 590 445 590 462 590 462 591 445 591 459 591 174 592 173 592 458 592 458 593 173 593 463 593 458 594 463 594 459 594 459 595 463 595 462 595 462 596 463 596 464 596 462 597 464 597 461 597 461 598 464 598 460 598 460 599 464 599 255 599 460 600 255 600 254 600 263 601 255 601 465 601 465 602 255 602 464 602 465 603 464 603 466 603 466 604 464 604 463 604 466 605 463 605 180 605 180 606 463 606 173 606 467 607 468 607 469 607 468 608 262 608 261 608 470 609 471 609 467 609 472 610 282 610 473 610 473 611 282 611 281 611 473 612 281 612 470 612 470 613 281 613 157 613 470 614 157 614 471 614 468 615 261 615 469 615 469 616 261 616 260 616 469 617 260 617 474 617 474 618 260 618 259 618 474 619 259 619 475 619 475 620 259 620 257 620 475 621 257 621 476 621 476 622 257 622 256 622 476 623 256 623 477 623 477 624 256 624 265 624 477 625 265 625 478 625 467 626 469 626 470 626 470 627 469 627 474 627 470 628 474 628 473 628 473 629 474 629 475 629 473 630 475 630 472 630 472 631 475 631 476 631 472 632 476 632 479 632 479 633 476 633 477 633 479 634 477 634 480 634 480 635 477 635 478 635 480 636 478 636 481 636 278 637 276 637 481 637 481 638 276 638 275 638 481 639 275 639 480 639 480 640 275 640 285 640 480 641 285 641 479 641 479 642 285 642 284 642 479 643 284 643 472 643 472 644 284 644 283 644 472 645 283 645 282 645 279 646 278 646 482 646 482 647 278 647 481 647 482 648 481 648 483 648 483 649 481 649 478 649 483 650 478 650 264 650 264 651 478 651 265 651 180 652 279 652 466 652 466 653 279 653 482 653 466 654 482 654 465 654 465 655 482 655 483 655 465 656 483 656 263 656 263 657 483 657 264 657 262 658 468 658 266 658 266 659 468 659 484 659 157 660 156 660 471 660 471 661 156 661 484 661 471 662 484 662 467 662 467 663 484 663 468 663 231 664 230 664 485 664 485 665 230 665 486 665 485 666 486 666 487 666 487 667 486 667 488 667 489 668 490 668 491 668 491 669 490 669 492 669 491 670 492 670 486 670 486 671 492 671 493 671 486 672 493 672 488 672 489 673 491 673 494 673 494 674 491 674 133 674 494 675 133 675 138 675 208 676 210 676 495 676 134 677 208 677 496 677 497 678 498 678 499 678 499 679 498 679 500 679 499 680 500 680 501 680 501 681 500 681 495 681 501 682 495 682 502 682 502 683 495 683 210 683 502 684 210 684 145 684 503 685 498 685 504 685 504 686 498 686 497 686 504 687 497 687 505 687 208 688 495 688 496 688 496 689 495 689 500 689 496 690 500 690 506 690 506 691 500 691 498 691 506 692 498 692 507 692 507 693 498 693 503 693 507 694 503 694 508 694 134 695 496 695 135 695 135 696 496 696 506 696 135 697 506 697 136 697 136 698 506 698 507 698 136 699 507 699 137 699 137 700 507 700 508 700 137 701 508 701 138 701 231 702 509 702 510 702 510 703 509 703 511 703 510 704 511 704 512 704 512 705 511 705 513 705 231 706 485 706 509 706 509 707 485 707 487 707 509 708 487 708 511 708 511 709 487 709 488 709 511 710 488 710 513 710 513 711 488 711 493 711 513 712 493 712 514 712 515 713 516 713 514 713 514 714 516 714 517 714 514 715 517 715 513 715 513 716 517 716 518 716 513 717 518 717 512 717 493 718 492 718 514 718 514 719 492 719 490 719 514 720 490 720 515 720 515 721 490 721 489 721 515 722 489 722 519 722 520 723 521 723 519 723 519 724 521 724 522 724 519 725 522 725 515 725 515 726 522 726 523 726 515 727 523 727 516 727 489 728 494 728 519 728 519 729 494 729 138 729 519 730 138 730 508 730 505 731 520 731 504 731 504 732 520 732 519 732 504 733 519 733 503 733 503 734 519 734 508 734 165 735 164 735 524 735 524 736 164 736 525 736 524 737 525 737 526 737 225 738 228 738 525 738 525 739 228 739 527 739 525 740 527 740 528 740 528 741 529 741 525 741 525 742 529 742 530 742 525 743 530 743 526 743 531 744 226 744 224 744 497 745 499 745 532 745 532 746 499 746 501 746 532 747 501 747 148 747 148 748 501 748 502 748 148 749 502 749 145 749 522 750 521 750 533 750 533 751 521 751 520 751 533 752 520 752 532 752 532 753 520 753 505 753 532 754 505 754 497 754 510 755 512 755 534 755 512 756 518 756 534 756 534 757 518 757 517 757 534 758 517 758 535 758 535 759 517 759 516 759 535 760 516 760 523 760 536 761 537 761 534 761 231 762 510 762 223 762 223 763 510 763 534 763 223 764 534 764 224 764 224 765 534 765 537 765 224 766 537 766 531 766 538 767 539 767 535 767 535 768 539 768 540 768 535 769 540 769 534 769 534 770 540 770 541 770 534 771 541 771 536 771 538 772 535 772 542 772 542 773 535 773 543 773 542 774 543 774 544 774 140 775 545 775 141 775 141 776 545 776 546 776 141 777 546 777 543 777 543 778 546 778 547 778 543 779 547 779 544 779 523 780 522 780 535 780 535 781 522 781 533 781 535 782 533 782 543 782 543 783 533 783 532 783 543 784 532 784 141 784 141 785 532 785 148 785 228 786 548 786 549 786 549 787 548 787 550 787 549 788 550 788 551 788 551 789 550 789 552 789 551 790 552 790 553 790 553 791 552 791 554 791 553 792 554 792 555 792 228 793 549 793 527 793 527 794 549 794 551 794 527 795 551 795 528 795 528 796 551 796 553 796 528 797 553 797 529 797 529 798 553 798 555 798 529 799 555 799 530 799 556 800 557 800 558 800 558 801 557 801 559 801 558 802 559 802 560 802 560 803 559 803 555 803 560 804 555 804 561 804 561 805 555 805 554 805 530 806 555 806 526 806 526 807 555 807 559 807 526 808 559 808 524 808 524 809 559 809 557 809 524 810 557 810 165 810 557 811 556 811 562 811 165 812 557 812 563 812 557 813 562 813 563 813 563 814 562 814 564 814 563 815 564 815 565 815 564 816 566 816 565 816 565 817 566 817 567 817 565 818 567 818 568 818 568 819 567 819 206 819 568 820 206 820 268 820 165 821 563 821 166 821 166 822 563 822 565 822 166 823 565 823 170 823 170 824 565 824 568 824 170 825 568 825 171 825 171 826 568 826 268 826 171 827 268 827 169 827 569 828 570 828 571 828 572 829 203 829 201 829 548 830 228 830 227 830 548 831 227 831 550 831 550 832 227 832 552 832 552 833 227 833 573 833 552 834 573 834 554 834 556 835 558 835 574 835 574 836 558 836 560 836 574 837 560 837 573 837 573 838 560 838 561 838 573 839 561 839 554 839 571 840 562 840 556 840 567 841 566 841 571 841 571 842 566 842 564 842 571 843 564 843 562 843 570 844 572 844 571 844 571 845 572 845 201 845 571 846 201 846 567 846 567 847 201 847 206 847 556 848 574 848 571 848 571 849 574 849 575 849 571 850 575 850 569 850 576 851 577 851 573 851 573 852 577 852 578 852 573 853 578 853 574 853 574 854 578 854 579 854 574 855 579 855 575 855 227 856 226 856 580 856 227 857 580 857 573 857 573 858 580 858 581 858 573 859 581 859 576 859 129 860 128 860 582 860 582 861 128 861 583 861 582 862 583 862 584 862 585 863 586 863 583 863 583 864 586 864 587 864 583 865 587 865 584 865 233 866 232 866 585 866 585 867 232 867 588 867 585 868 588 868 589 868 589 869 590 869 585 869 585 870 590 870 591 870 585 871 591 871 586 871 232 872 592 872 588 872 588 873 592 873 593 873 588 874 593 874 589 874 589 875 593 875 594 875 589 876 594 876 590 876 232 877 595 877 592 877 592 878 595 878 596 878 592 879 596 879 593 879 593 880 596 880 597 880 593 881 597 881 594 881 594 882 597 882 598 882 594 883 598 883 599 883 590 884 594 884 591 884 591 885 594 885 599 885 591 886 599 886 586 886 586 887 599 887 600 887 586 888 600 888 587 888 598 889 601 889 599 889 599 890 601 890 602 890 599 891 602 891 600 891 600 892 602 892 603 892 600 893 603 893 604 893 604 894 603 894 605 894 604 895 605 895 606 895 606 896 607 896 604 896 604 897 607 897 608 897 604 898 608 898 609 898 587 899 600 899 584 899 584 900 600 900 604 900 584 901 604 901 582 901 582 902 604 902 609 902 582 903 609 903 129 903 610 904 611 904 612 904 612 905 611 905 607 905 612 906 607 906 606 906 130 907 129 907 613 907 613 908 129 908 609 908 613 909 609 909 611 909 611 910 609 910 608 910 611 911 608 911 607 911 131 912 130 912 614 912 614 913 130 913 613 913 614 914 613 914 615 914 615 915 613 915 611 915 615 916 611 916 616 916 616 917 611 917 610 917 132 918 131 918 207 918 207 919 131 919 614 919 207 920 614 920 209 920 209 921 614 921 615 921 209 922 615 922 146 922 146 923 615 923 616 923 617 924 618 924 619 924 238 925 237 925 620 925 620 926 237 926 617 926 620 927 617 927 621 927 621 928 617 928 619 928 618 929 617 929 622 929 622 930 617 930 158 930 622 931 158 931 163 931 623 932 151 932 147 932 624 933 598 933 597 933 597 934 596 934 625 934 625 935 596 935 595 935 625 936 595 936 626 936 626 937 595 937 232 937 626 938 232 938 234 938 598 939 624 939 601 939 601 940 624 940 627 940 601 941 627 941 602 941 612 942 606 942 628 942 628 943 606 943 605 943 628 944 605 944 627 944 627 945 605 945 603 945 627 946 603 946 602 946 147 947 146 947 616 947 147 948 616 948 628 948 628 949 616 949 610 949 628 950 610 950 612 950 623 951 147 951 629 951 629 952 147 952 630 952 630 953 147 953 628 953 630 954 628 954 631 954 632 955 633 955 627 955 627 956 633 956 634 956 627 957 634 957 628 957 628 958 634 958 635 958 628 959 635 959 631 959 624 960 636 960 637 960 624 961 637 961 627 961 627 962 637 962 638 962 627 963 638 963 632 963 597 964 625 964 624 964 624 965 625 965 639 965 624 966 639 966 636 966 640 967 641 967 642 967 643 968 644 968 645 968 163 969 162 969 646 969 646 970 162 970 647 970 646 971 647 971 648 971 648 972 647 972 643 972 648 973 643 973 649 973 649 974 643 974 645 974 641 975 644 975 642 975 642 976 644 976 643 976 642 977 643 977 650 977 650 978 643 978 647 978 650 979 647 979 161 979 161 980 647 980 162 980 651 981 640 981 652 981 652 982 640 982 642 982 652 983 642 983 653 983 653 984 642 984 650 984 653 985 650 985 160 985 160 986 650 986 161 986 178 987 651 987 277 987 277 988 651 988 652 988 277 989 652 989 280 989 280 990 652 990 653 990 280 991 653 991 159 991 159 992 653 992 160 992 238 993 654 993 655 993 655 994 654 994 656 994 622 995 657 995 618 995 618 996 657 996 658 996 618 997 658 997 619 997 619 998 658 998 656 998 619 999 656 999 621 999 621 1000 656 1000 654 1000 621 1001 654 1001 620 1001 620 1002 654 1002 238 1002 659 1003 660 1003 657 1003 657 1004 660 1004 661 1004 657 1005 661 1005 658 1005 658 1006 661 1006 662 1006 658 1007 662 1007 656 1007 656 1008 662 1008 663 1008 656 1009 663 1009 655 1009 649 1010 645 1010 659 1010 649 1011 659 1011 648 1011 648 1012 659 1012 657 1012 648 1013 657 1013 646 1013 646 1014 657 1014 622 1014 646 1015 622 1015 163 1015 236 1016 239 1016 664 1016 644 1017 641 1017 665 1017 665 1018 641 1018 640 1018 665 1019 640 1019 176 1019 176 1020 640 1020 651 1020 176 1021 651 1021 178 1021 644 1022 665 1022 645 1022 645 1023 665 1023 666 1023 645 1024 666 1024 659 1024 659 1025 666 1025 660 1025 660 1026 666 1026 664 1026 660 1027 664 1027 661 1027 238 1028 655 1028 239 1028 239 1029 655 1029 663 1029 239 1030 663 1030 664 1030 664 1031 663 1031 662 1031 664 1032 662 1032 661 1032 667 1033 234 1033 236 1033 667 1034 236 1034 668 1034 668 1035 236 1035 669 1035 669 1036 236 1036 664 1036 669 1037 664 1037 670 1037 670 1038 664 1038 666 1038 670 1039 666 1039 671 1039 665 1040 672 1040 673 1040 673 1041 674 1041 665 1041 665 1042 674 1042 675 1042 665 1043 675 1043 666 1043 666 1044 675 1044 676 1044 666 1045 676 1045 671 1045 672 1046 665 1046 677 1046 677 1047 665 1047 176 1047 677 1048 176 1048 175 1048 152 1049 678 1049 106 1049 106 1050 678 1050 108 1050 108 1051 678 1051 110 1051 110 1052 678 1052 679 1052 110 1053 679 1053 112 1053 112 1054 679 1054 114 1054 114 1055 679 1055 680 1055 114 1056 680 1056 115 1056 115 1057 680 1057 94 1057 94 1058 680 1058 212 1058 94 1059 212 1059 92 1059 221 1060 219 1060 681 1060 682 1061 149 1061 150 1061 172 1062 213 1062 683 1062 683 1063 213 1063 684 1063 683 1064 684 1064 685 1064 685 1065 684 1065 686 1065 150 1066 687 1066 682 1066 682 1067 687 1067 688 1067 682 1068 688 1068 686 1068 686 1069 688 1069 689 1069 686 1070 689 1070 685 1070 144 1071 149 1071 690 1071 690 1072 149 1072 682 1072 690 1073 682 1073 691 1073 691 1074 682 1074 686 1074 691 1075 686 1075 692 1075 692 1076 686 1076 684 1076 692 1077 684 1077 217 1077 217 1078 684 1078 213 1078 142 1079 144 1079 693 1079 693 1080 144 1080 690 1080 693 1081 690 1081 694 1081 694 1082 690 1082 691 1082 694 1083 691 1083 681 1083 681 1084 691 1084 692 1084 681 1085 692 1085 221 1085 221 1086 692 1086 217 1086 152 1087 142 1087 678 1087 678 1088 142 1088 693 1088 678 1089 693 1089 679 1089 679 1090 693 1090 694 1090 679 1091 694 1091 680 1091 680 1092 694 1092 681 1092 680 1093 681 1093 212 1093 212 1094 681 1094 219 1094 172 1095 683 1095 179 1095 179 1096 683 1096 695 1096 683 1097 685 1097 695 1097 695 1098 685 1098 689 1098 695 1099 689 1099 696 1099 150 1100 151 1100 687 1100 687 1101 151 1101 696 1101 687 1102 696 1102 688 1102 688 1103 696 1103 689 1103 697 1104 623 1104 629 1104 175 1105 177 1105 698 1105 698 1106 177 1106 699 1106 698 1107 699 1107 700 1107 700 1108 699 1108 697 1108 700 1109 697 1109 701 1109 701 1110 697 1110 629 1110 151 1111 623 1111 696 1111 696 1112 623 1112 697 1112 696 1113 697 1113 695 1113 695 1114 697 1114 699 1114 695 1115 699 1115 179 1115 179 1116 699 1116 177 1116 234 1117 667 1117 702 1117 702 1118 667 1118 668 1118 626 1119 234 1119 702 1119 703 1120 639 1120 625 1120 669 1121 704 1121 668 1121 668 1122 704 1122 703 1122 668 1123 703 1123 702 1123 702 1124 703 1124 625 1124 702 1125 625 1125 626 1125 669 1126 670 1126 704 1126 704 1127 670 1127 671 1127 704 1128 671 1128 705 1128 705 1129 671 1129 676 1129 705 1130 676 1130 706 1130 639 1131 703 1131 636 1131 636 1132 703 1132 704 1132 636 1133 704 1133 637 1133 637 1134 704 1134 705 1134 637 1135 705 1135 638 1135 638 1136 705 1136 706 1136 638 1137 706 1137 632 1137 632 1138 706 1138 633 1138 633 1139 706 1139 707 1139 633 1140 707 1140 634 1140 634 1141 707 1141 708 1141 634 1142 708 1142 635 1142 677 1143 709 1143 672 1143 672 1144 709 1144 708 1144 672 1145 708 1145 673 1145 673 1146 708 1146 707 1146 673 1147 707 1147 674 1147 674 1148 707 1148 706 1148 674 1149 706 1149 675 1149 675 1150 706 1150 676 1150 677 1151 175 1151 698 1151 677 1152 698 1152 709 1152 709 1153 698 1153 700 1153 709 1154 700 1154 701 1154 635 1155 708 1155 631 1155 631 1156 708 1156 709 1156 631 1157 709 1157 630 1157 630 1158 709 1158 701 1158 630 1159 701 1159 629 1159 97 1160 193 1160 710 1160 97 1161 710 1161 99 1161 99 1162 710 1162 711 1162 99 1163 711 1163 101 1163 101 1164 711 1164 712 1164 101 1165 712 1165 102 1165 102 1166 712 1166 153 1166 102 1167 153 1167 104 1167 710 1168 193 1168 192 1168 711 1169 710 1169 713 1169 712 1170 711 1170 714 1170 153 1171 712 1171 715 1171 711 1172 713 1172 714 1172 714 1173 713 1173 716 1173 714 1174 716 1174 717 1174 717 1175 716 1175 718 1175 717 1176 718 1176 719 1176 710 1177 192 1177 713 1177 713 1178 192 1178 195 1178 713 1179 195 1179 716 1179 716 1180 195 1180 190 1180 716 1181 190 1181 718 1181 718 1182 190 1182 188 1182 718 1183 188 1183 187 1183 187 1184 720 1184 718 1184 718 1185 720 1185 721 1185 718 1186 721 1186 719 1186 719 1187 721 1187 722 1187 719 1188 722 1188 723 1188 712 1189 714 1189 715 1189 715 1190 714 1190 717 1190 715 1191 717 1191 724 1191 724 1192 717 1192 719 1192 724 1193 719 1193 725 1193 725 1194 719 1194 723 1194 725 1195 723 1195 726 1195 153 1196 715 1196 154 1196 154 1197 715 1197 724 1197 154 1198 724 1198 155 1198 155 1199 724 1199 725 1199 155 1200 725 1200 143 1200 143 1201 725 1201 726 1201 143 1202 726 1202 139 1202 187 1203 200 1203 720 1203 720 1204 200 1204 727 1204 720 1205 727 1205 721 1205 721 1206 727 1206 722 1206 722 1207 727 1207 728 1207 722 1208 728 1208 723 1208 723 1209 728 1209 726 1209 726 1210 728 1210 140 1210 726 1211 140 1211 139 1211 729 1212 202 1212 203 1212 546 1213 545 1213 730 1213 730 1214 545 1214 731 1214 730 1215 731 1215 732 1215 732 1216 731 1216 729 1216 732 1217 729 1217 733 1217 733 1218 729 1218 203 1218 200 1219 202 1219 727 1219 727 1220 202 1220 729 1220 727 1221 729 1221 728 1221 728 1222 729 1222 731 1222 728 1223 731 1223 140 1223 140 1224 731 1224 545 1224 577 1225 576 1225 734 1225 734 1226 576 1226 581 1226 226 1227 735 1227 580 1227 580 1228 735 1228 736 1228 226 1229 531 1229 735 1229 735 1230 531 1230 537 1230 735 1231 537 1231 736 1231 736 1232 537 1232 536 1232 541 1233 737 1233 536 1233 536 1234 737 1234 734 1234 536 1235 734 1235 736 1235 736 1236 734 1236 581 1236 736 1237 581 1237 580 1237 541 1238 540 1238 737 1238 737 1239 540 1239 539 1239 737 1240 539 1240 738 1240 738 1241 539 1241 538 1241 738 1242 538 1242 739 1242 577 1243 734 1243 578 1243 578 1244 734 1244 737 1244 578 1245 737 1245 579 1245 579 1246 737 1246 738 1246 579 1247 738 1247 575 1247 575 1248 738 1248 739 1248 575 1249 739 1249 569 1249 546 1250 730 1250 547 1250 547 1251 730 1251 732 1251 547 1252 732 1252 544 1252 538 1253 542 1253 739 1253 739 1254 542 1254 544 1254 739 1255 544 1255 740 1255 740 1256 544 1256 732 1256 740 1257 732 1257 733 1257 569 1258 739 1258 570 1258 570 1259 739 1259 740 1259 570 1260 740 1260 572 1260 572 1261 740 1261 733 1261 572 1262 733 1262 203 1262 338 1263 336 1263 741 1263 185 1264 331 1264 414 1264 414 1265 331 1265 334 1265 414 1266 334 1266 411 1266 411 1267 334 1267 333 1267 411 1268 333 1268 412 1268 412 1269 333 1269 339 1269 412 1270 339 1270 413 1270 413 1271 339 1271 338 1271 413 1272 338 1272 408 1272 408 1273 338 1273 741 1273 408 1274 741 1274 409 1274 742 1275 352 1275 351 1275 391 1276 742 1276 398 1276 398 1277 742 1277 351 1277 398 1278 351 1278 397 1278 397 1279 351 1279 356 1279 397 1280 356 1280 124 1280 742 1281 391 1281 390 1281 352 1282 742 1282 743 1282 352 1283 743 1283 455 1283 455 1284 743 1284 744 1284 455 1285 744 1285 453 1285 453 1286 744 1286 745 1286 453 1287 745 1287 454 1287 454 1288 745 1288 448 1288 448 1289 745 1289 746 1289 448 1290 746 1290 449 1290 449 1291 746 1291 747 1291 449 1292 747 1292 451 1292 742 1293 390 1293 743 1293 743 1294 390 1294 396 1294 743 1295 396 1295 744 1295 744 1296 396 1296 395 1296 744 1297 395 1297 745 1297 745 1298 395 1298 394 1298 745 1299 394 1299 746 1299 746 1300 394 1300 393 1300 746 1301 393 1301 747 1301 747 1302 393 1302 392 1302 747 1303 392 1303 748 1303 451 1304 747 1304 452 1304 452 1305 747 1305 748 1305 452 1306 748 1306 444 1306 748 1307 392 1307 377 1307 443 1308 444 1308 749 1308 749 1309 444 1309 748 1309 748 1310 377 1310 749 1310 749 1311 377 1311 376 1311 749 1312 376 1312 750 1312 443 1313 749 1313 442 1313 442 1314 749 1314 750 1314 442 1315 750 1315 436 1315 437 1316 436 1316 751 1316 751 1317 436 1317 750 1317 751 1318 750 1318 389 1318 389 1319 750 1319 376 1319 308 1320 437 1320 752 1320 752 1321 437 1321 751 1321 752 1322 751 1322 381 1322 381 1323 751 1323 389 1323 309 1324 308 1324 752 1324 116 1325 299 1325 753 1325 753 1326 299 1326 301 1326 753 1327 301 1327 754 1327 754 1328 301 1328 755 1328 301 1329 302 1329 755 1329 755 1330 302 1330 307 1330 755 1331 307 1331 756 1331 116 1332 753 1332 369 1332 369 1333 753 1333 754 1333 369 1334 754 1334 371 1334 371 1335 754 1335 755 1335 371 1336 755 1336 373 1336 373 1337 755 1337 756 1337 373 1338 756 1338 375 1338 307 1339 306 1339 756 1339 756 1340 306 1340 304 1340 756 1341 304 1341 752 1341 752 1342 304 1342 313 1342 752 1343 313 1343 309 1343 375 1344 756 1344 386 1344 386 1345 756 1345 752 1345 386 1346 752 1346 381 1346 126 1347 757 1347 399 1347 399 1348 757 1348 378 1348 360 1349 758 1349 757 1349 757 1350 758 1350 379 1350 757 1351 379 1351 378 1351 126 1352 363 1352 757 1352 757 1353 363 1353 361 1353 757 1354 361 1354 360 1354 759 1355 388 1355 387 1355 760 1356 761 1356 762 1356 762 1357 761 1357 763 1357 762 1358 763 1358 759 1358 759 1359 387 1359 762 1359 762 1360 387 1360 385 1360 762 1361 385 1361 384 1361 384 1362 764 1362 762 1362 762 1363 764 1363 410 1363 762 1364 410 1364 760 1364 760 1365 410 1365 409 1365 407 1366 415 1366 764 1366 415 1367 402 1367 764 1367 764 1368 402 1368 401 1368 764 1369 401 1369 410 1369 765 1370 383 1370 382 1370 765 1371 382 1371 766 1371 766 1372 382 1372 380 1372 766 1373 380 1373 767 1373 767 1374 380 1374 379 1374 767 1375 379 1375 758 1375 384 1376 383 1376 764 1376 764 1377 383 1377 765 1377 764 1378 765 1378 407 1378 407 1379 765 1379 766 1379 407 1380 766 1380 405 1380 405 1381 766 1381 767 1381 405 1382 767 1382 404 1382 404 1383 767 1383 758 1383 404 1384 758 1384 360 1384 760 1385 768 1385 761 1385 769 1386 770 1386 759 1386 759 1387 770 1387 388 1387 741 1388 336 1388 771 1388 759 1389 763 1389 769 1389 769 1390 763 1390 761 1390 769 1391 761 1391 771 1391 771 1392 761 1392 768 1392 771 1393 768 1393 741 1393 741 1394 768 1394 760 1394 741 1395 760 1395 409 1395 117 1396 772 1396 344 1396 344 1397 772 1397 773 1397 774 1398 329 1398 773 1398 773 1399 329 1399 328 1399 773 1400 328 1400 344 1400 117 1401 368 1401 772 1401 772 1402 368 1402 370 1402 772 1403 370 1403 773 1403 773 1404 370 1404 372 1404 773 1405 372 1405 774 1405 774 1406 372 1406 374 1406 774 1407 374 1407 775 1407 335 1408 342 1408 775 1408 775 1409 342 1409 341 1409 775 1410 341 1410 774 1410 774 1411 341 1411 340 1411 774 1412 340 1412 329 1412 771 1413 336 1413 335 1413 771 1414 335 1414 769 1414 769 1415 335 1415 775 1415 769 1416 775 1416 770 1416 770 1417 775 1417 374 1417 770 1418 374 1418 388 1418 776 1419 777 1419 778 1419 52 1420 50 1420 779 1420 779 1421 50 1421 780 1421 779 1422 780 1422 778 1422 778 1423 780 1423 781 1423 778 1424 781 1424 776 1424 793 1425 794 1425 795 1425 795 1426 794 1426 796 1426 795 1427 796 1427 797 1427 797 1428 796 1428 798 1428 797 1429 798 1429 799 1429 793 1430 800 1430 794 1430 794 1431 800 1431 801 1431 794 1432 801 1432 802 1432 799 1433 803 1433 797 1433 797 1434 803 1434 804 1434 797 1435 804 1435 805 1435 805 1436 804 1436 806 1436 805 1437 806 1437 807 1437 807 1438 806 1438 808 1438 807 1439 808 1439 105 1439 105 1440 808 1440 103 1440 819 1441 820 1441 821 1441 822 1442 823 1442 824 1442 819 1443 821 1443 825 1443 825 1444 821 1444 826 1444 825 1445 826 1445 827 1445 827 1446 826 1446 822 1446 827 1447 822 1447 828 1447 824 1448 829 1448 822 1448 822 1449 829 1449 830 1449 822 1450 830 1450 828 1450 831 1451 832 1451 833 1451 831 1452 833 1452 834 1452 834 1453 833 1453 835 1453 834 1454 835 1454 836 1454 837 1455 838 1455 839 1455 839 1456 838 1456 840 1456 839 1457 840 1457 841 1457 841 1458 840 1458 834 1458 841 1459 834 1459 842 1459 842 1460 834 1460 836 1460 843 1461 844 1461 845 1461 843 1462 845 1462 832 1462 832 1463 845 1463 846 1463 832 1464 846 1464 847 1464 844 1465 843 1465 848 1465 848 1466 843 1466 849 1466 848 1467 849 1467 850 1467 847 1468 851 1468 832 1468 832 1469 851 1469 852 1469 832 1470 852 1470 833 1470 794 1471 802 1471 853 1471 794 1472 853 1472 854 1472 854 1473 853 1473 855 1473 854 1473 855 1473 856 1473 856 1474 855 1474 792 1474 856 1475 792 1475 791 1475 857 1476 858 1476 3 1476 3 145 5 145 857 145 857 145 5 145 7 145 857 1477 7 1477 9 1477 9 1478 11 1478 857 1478 857 1479 11 1479 13 1479 857 1480 13 1480 859 1480 859 1481 13 1481 15 1481 859 145 15 145 17 145 17 145 19 145 859 145 859 1482 19 1482 43 1482 859 1483 43 1483 860 1483 861 1484 862 1484 863 1484 857 1485 859 1485 863 1485 863 1486 859 1486 864 1486 863 1487 864 1487 861 1487 865 1488 866 1488 867 1488 862 1489 861 1489 867 1489 867 1490 861 1490 868 1490 867 1491 868 1491 865 1491 865 1492 869 1492 866 1492 866 1493 869 1493 870 1493 866 1494 870 1494 871 1494 871 1495 870 1495 823 1495 871 1496 823 1496 822 1496 837 1497 74 1497 76 1497 96 1498 838 1498 91 1498 91 1499 838 1499 89 1499 76 142 83 142 837 142 837 1500 83 1500 85 1500 837 1501 85 1501 838 1501 838 1502 85 1502 87 1502 838 1503 87 1503 89 1503 873 1504 874 1504 875 1504 886 1505 887 1505 888 1505 888 1506 887 1506 889 1506 888 1507 889 1507 890 1507 891 1508 892 1508 888 1508 888 1509 892 1509 893 1509 888 1510 893 1510 886 1510 894 1511 895 1511 896 1511 895 1512 898 1512 896 1512 896 1513 898 1513 899 1513 902 1514 903 1514 896 1514 896 1515 903 1515 904 1515 896 1516 904 1516 894 1516 896 1517 897 1517 905 1517 896 1518 905 1518 902 1518 845 1519 844 1519 906 1519 906 1520 844 1520 907 1520 908 1521 909 1521 910 1521 910 1522 909 1522 911 1522 910 1523 911 1523 844 1523 844 1524 911 1524 912 1524 844 1525 912 1525 907 1525 815 1526 814 1526 910 1526 910 1527 814 1527 913 1527 910 1528 913 1528 908 1528 914 1529 915 1529 916 1529 916 1530 915 1530 917 1530 916 1531 917 1531 810 1531 810 1532 917 1532 918 1532 810 1533 918 1533 809 1533 825 1534 827 1534 919 1534 919 1535 920 1535 825 1535 825 1536 920 1536 921 1536 825 1537 921 1537 916 1537 916 1538 921 1538 922 1538 916 1539 922 1539 914 1539 56 1540 54 1540 779 1540 779 1541 54 1541 53 1541 779 1542 53 1542 52 1542 24 1543 23 1543 923 1543 923 1544 23 1544 60 1544 923 1545 60 1545 779 1545 779 1546 60 1546 59 1546 779 1547 59 1547 56 1547 32 1548 30 1548 924 1548 924 1549 30 1549 28 1549 924 1550 28 1550 923 1550 923 1551 28 1551 26 1551 923 1552 26 1552 24 1552 859 1553 860 1553 925 1553 925 1554 860 1554 40 1554 40 1555 38 1555 925 1555 925 1556 38 1556 36 1556 925 1557 36 1557 924 1557 924 1558 36 1558 34 1558 924 1559 34 1559 32 1559 861 1560 864 1560 926 1560 865 1561 868 1561 927 1561 928 1562 929 1562 930 1562 931 1563 932 1563 933 1563 929 1564 934 1564 930 1564 930 1565 934 1565 935 1565 930 1566 935 1566 936 1566 778 1567 777 1567 937 1567 937 1568 777 1568 938 1568 935 1569 939 1569 936 1569 936 1570 939 1570 931 1570 936 1571 931 1571 927 1571 927 1572 931 1572 933 1572 927 1573 933 1573 865 1573 865 1574 933 1574 940 1574 865 1575 940 1575 869 1575 938 1576 928 1576 937 1576 937 1577 928 1577 930 1577 937 1578 930 1578 941 1578 941 1579 930 1579 936 1579 941 1580 936 1580 926 1580 926 1581 936 1581 927 1581 926 1582 927 1582 861 1582 861 1583 927 1583 868 1583 779 1584 778 1584 923 1584 923 1585 778 1585 937 1585 923 1586 937 1586 924 1586 924 1587 937 1587 941 1587 924 1588 941 1588 925 1588 925 1589 941 1589 926 1589 925 1590 926 1590 859 1590 859 1591 926 1591 864 1591 74 1592 837 1592 72 1592 72 1593 837 1593 942 1593 72 1594 942 1594 70 1594 70 1595 942 1595 68 1595 62 1596 61 1596 943 1596 943 1597 61 1597 79 1597 943 1598 79 1598 942 1598 942 1599 79 1599 80 1599 942 1600 80 1600 68 1600 50 1601 49 1601 780 1601 780 1602 49 1602 45 1602 780 1603 45 1603 1 1603 1 1604 0 1604 780 1604 780 1605 0 1605 65 1605 780 1606 65 1606 943 1606 943 1607 65 1607 64 1607 943 1608 64 1608 62 1608 841 1609 842 1609 944 1609 776 1610 781 1610 945 1610 945 1611 781 1611 946 1611 945 1612 946 1612 947 1612 947 1613 946 1613 948 1613 949 1614 950 1614 951 1614 952 1615 953 1615 954 1615 949 1616 951 1616 954 1616 954 1617 951 1617 944 1617 954 1618 944 1618 952 1618 955 1619 956 1619 944 1619 944 1620 956 1620 957 1620 944 1621 957 1621 952 1621 842 1622 836 1622 944 1622 944 1623 836 1623 958 1623 944 1624 958 1624 955 1624 781 1625 780 1625 946 1625 946 1626 780 1626 943 1626 946 1627 943 1627 959 1627 959 1628 943 1628 942 1628 959 1629 942 1629 839 1629 839 1630 942 1630 837 1630 950 1631 948 1631 951 1631 951 1632 948 1632 946 1632 951 1633 946 1633 944 1633 944 1634 946 1634 959 1634 944 1635 959 1635 841 1635 841 1636 959 1636 839 1636 962 1637 961 1637 963 1637 967 1638 968 1638 969 1638 967 1639 969 1639 970 1639 970 1640 969 1640 971 1640 970 1641 971 1641 972 1641 975 1642 976 1642 977 1642 978 1643 777 1643 776 1643 776 1644 979 1644 978 1644 978 1645 979 1645 980 1645 978 1646 980 1646 981 1646 981 1647 980 1647 982 1647 981 1648 982 1648 983 1648 983 1649 982 1649 975 1649 983 1650 975 1650 984 1650 984 1651 975 1651 977 1651 985 1652 986 1652 987 1652 985 1653 987 1653 988 1653 989 1654 990 1654 987 1654 987 1655 990 1655 991 1655 991 1656 992 1656 987 1656 987 1657 992 1657 993 1657 987 1658 993 1658 988 1658 986 1659 994 1659 987 1659 987 1660 994 1660 995 1660 987 1661 995 1661 996 1661 997 1662 996 1662 977 1662 977 1663 996 1663 998 1663 977 1664 998 1664 984 1664 997 1665 999 1665 996 1665 996 1666 999 1666 1000 1666 996 1667 1000 1667 1001 1667 1001 1668 1002 1668 996 1668 996 1669 1002 1669 1003 1669 996 1670 1003 1670 987 1670 783 1671 782 1671 1004 1671 1004 1672 782 1672 1005 1672 1004 1673 1005 1673 987 1673 987 1674 1005 1674 1006 1674 987 1675 1006 1675 989 1675 1007 1676 1008 1676 1009 1676 1009 1677 1008 1677 1010 1677 969 1678 968 1678 1011 1678 969 1679 1011 1679 1012 1679 1012 1680 1011 1680 1013 1680 1012 1681 1013 1681 1014 1681 1015 1682 1009 1682 1016 1682 1016 1683 1009 1683 1010 1683 1016 1684 1010 1684 1017 1684 1015 1685 1018 1685 1009 1685 1009 1686 1018 1686 1019 1686 1009 1687 1019 1687 835 1687 835 1688 1019 1688 1020 1688 835 1689 1020 1689 836 1689 1014 1690 1021 1690 1012 1690 1012 1691 1021 1691 1007 1691 1012 1692 1007 1692 1022 1692 1022 1693 1007 1693 1009 1693 1022 1694 1009 1694 833 1694 833 1695 1009 1695 835 1695 1012 1696 1022 1696 1023 1696 969 1697 1012 1697 1024 1697 1012 1698 1023 1698 1024 1698 1024 1699 1023 1699 1025 1699 1024 1700 1025 1700 1026 1700 973 1701 974 1701 1026 1701 1026 1702 974 1702 972 1702 1026 1703 972 1703 1024 1703 1024 1704 972 1704 971 1704 1024 1705 971 1705 969 1705 847 1706 1025 1706 851 1706 851 1707 1025 1707 1023 1707 851 1708 1023 1708 852 1708 852 1709 1023 1709 1022 1709 852 1710 1022 1710 833 1710 883 1711 973 1711 1027 1711 1027 1712 973 1712 1026 1712 1027 1713 1026 1713 1028 1713 1028 1714 1026 1714 1025 1714 1028 1715 1025 1715 1029 1715 1029 1716 1025 1716 847 1716 847 1717 846 1717 1029 1717 1029 1718 846 1718 1030 1718 1029 1719 1030 1719 1028 1719 1028 1720 1030 1720 1027 1720 1027 1721 1030 1721 884 1721 1027 1722 884 1722 883 1722 885 1723 884 1723 1031 1723 1031 1724 884 1724 1030 1724 1031 1725 1030 1725 845 1725 845 1726 1030 1726 846 1726 1031 1727 845 1727 906 1727 885 1728 1031 1728 1032 1728 1031 1729 906 1729 1032 1729 1032 1730 906 1730 907 1730 1032 1731 907 1731 1033 1731 1033 1732 907 1732 912 1732 1033 1733 912 1733 1034 1733 1034 1734 912 1734 911 1734 1034 1735 911 1735 1035 1735 911 1736 909 1736 1035 1736 1035 1737 909 1737 908 1737 1035 1738 908 1738 1036 1738 1036 1739 908 1739 913 1739 1036 1740 913 1740 1037 1740 1037 1741 913 1741 814 1741 1037 1742 814 1742 1038 1742 885 1743 1032 1743 891 1743 891 1744 1032 1744 1033 1744 891 1745 1033 1745 892 1745 892 1746 1033 1746 1034 1746 892 1747 1034 1747 893 1747 893 1748 1034 1748 1035 1748 893 1749 1035 1749 886 1749 886 1750 1035 1750 1036 1750 886 1751 1036 1751 887 1751 887 1752 1036 1752 1037 1752 887 1753 1037 1753 889 1753 889 1754 1037 1754 1038 1754 889 1755 1038 1755 890 1755 933 1756 932 1756 1039 1756 933 1757 1039 1757 940 1757 869 1758 940 1758 1040 1758 1040 1759 940 1759 1039 1759 1040 1760 1039 1760 1041 1760 1041 1761 1039 1761 1042 1761 1043 1762 1044 1762 1045 1762 1046 1763 870 1763 869 1763 1042 1764 1047 1764 1041 1764 1041 1765 1047 1765 1046 1765 1041 1766 1046 1766 1040 1766 1040 1767 1046 1767 869 1767 823 1768 870 1768 1048 1768 1048 1769 870 1769 1046 1769 1048 1770 1046 1770 1045 1770 1045 1771 1046 1771 1047 1771 1045 1772 1047 1772 1043 1772 1049 1773 1050 1773 1051 1773 1050 1774 1052 1774 963 1774 963 1775 1052 1775 1053 1775 963 1776 1053 1776 962 1776 1045 1777 1044 1777 1054 1777 1054 1778 1044 1778 1055 1778 1054 1779 1055 1779 1051 1779 1051 1780 1055 1780 1056 1780 1051 1781 1056 1781 1049 1781 1045 1782 1054 1782 1048 1782 1048 1783 1054 1783 824 1783 1048 1784 824 1784 823 1784 829 1785 824 1785 1057 1785 1057 1786 824 1786 1054 1786 1057 1787 1054 1787 1058 1787 1058 1788 1054 1788 1051 1788 1050 1789 963 1789 1051 1789 1051 1790 963 1790 964 1790 1051 1791 964 1791 1058 1791 1058 1792 964 1792 965 1792 1058 1793 965 1793 966 1793 830 1794 829 1794 1059 1794 1059 1795 829 1795 1057 1795 1059 1796 1057 1796 1060 1796 1060 1797 1057 1797 1058 1797 1060 1798 1058 1798 1061 1798 1061 1799 1058 1799 966 1799 1061 1800 966 1800 901 1800 901 1801 900 1801 1061 1801 1061 1802 900 1802 1062 1802 1061 1803 1062 1803 1060 1803 1060 1804 1062 1804 1059 1804 1059 1805 1062 1805 828 1805 1059 1806 828 1806 830 1806 827 1807 828 1807 1063 1807 1063 1808 828 1808 1062 1808 1063 1809 1062 1809 899 1809 899 1810 1062 1810 900 1810 1064 1811 809 1811 918 1811 897 1812 1064 1812 1065 1812 1064 1813 918 1813 1065 1813 1065 1814 918 1814 917 1814 1065 1815 917 1815 1066 1815 1066 1816 917 1816 915 1816 1066 1817 915 1817 1067 1817 1067 1818 915 1818 914 1818 1067 1819 914 1819 1068 1819 1068 1820 914 1820 922 1820 1068 1821 922 1821 1069 1821 922 1822 921 1822 1069 1822 1069 1823 921 1823 920 1823 1069 1824 920 1824 1070 1824 1070 1825 920 1825 919 1825 1070 1826 919 1826 1071 1826 1071 1827 919 1827 827 1827 1071 1828 827 1828 1063 1828 897 1829 1065 1829 905 1829 905 1830 1065 1830 1066 1830 905 1831 1066 1831 902 1831 902 1832 1066 1832 1067 1832 902 1833 1067 1833 903 1833 903 1834 1067 1834 1068 1834 903 1835 1068 1835 904 1835 904 1836 1068 1836 1069 1836 904 1837 1069 1837 894 1837 894 1838 1069 1838 1070 1838 894 1839 1070 1839 895 1839 895 1840 1070 1840 1071 1840 895 1841 1071 1841 898 1841 898 1842 1071 1842 1063 1842 898 1843 1063 1843 899 1843 856 1844 791 1844 790 1844 1080 1845 1081 1845 1082 1845 1082 1846 1081 1846 1083 1846 1082 1847 1083 1847 1084 1847 1084 1848 1083 1848 1085 1848 1084 1849 1085 1849 1086 1849 1086 1850 1085 1850 794 1850 1086 1851 794 1851 854 1851 856 1852 790 1852 1087 1852 1087 1853 790 1853 789 1853 1087 1854 789 1854 1088 1854 1088 1855 789 1855 788 1855 1088 1856 788 1856 1089 1856 1089 1857 788 1857 787 1857 1089 1858 787 1858 1090 1858 1090 1859 1082 1859 1089 1859 1089 1860 1082 1860 1084 1860 1089 1861 1084 1861 1088 1861 1088 1862 1084 1862 1086 1862 1088 1863 1086 1863 1087 1863 1087 1864 1086 1864 854 1864 1087 1865 854 1865 856 1865 1091 1866 1080 1866 1092 1866 1092 1867 1080 1867 1082 1867 1092 1868 1082 1868 1093 1868 1093 1869 1082 1869 1090 1869 872 1870 1094 1870 1076 1870 1076 1871 1094 1871 1095 1871 1076 1872 1095 1872 1077 1872 1077 1873 1095 1873 1096 1873 1077 1874 1096 1874 1078 1874 872 1875 1097 1875 1094 1875 1094 1876 1097 1876 1098 1876 1094 1877 1098 1877 1095 1877 1095 1878 1098 1878 1099 1878 1095 1879 1099 1879 1096 1879 1096 1880 1099 1880 1100 1880 1096 1881 1100 1881 1101 1881 1078 1882 1096 1882 1079 1882 1079 1883 1096 1883 1101 1883 1079 1884 1101 1884 1074 1884 1074 1885 1101 1885 1102 1885 1074 1886 1102 1886 1075 1886 1103 1887 1104 1887 1105 1887 1105 1888 1104 1888 1102 1888 1105 1889 1102 1889 1106 1889 1106 1890 1102 1890 1101 1890 1106 1891 1101 1891 1107 1891 1107 1892 1101 1892 1100 1892 1093 1893 1108 1893 1092 1893 1092 1894 1108 1894 1091 1894 1090 1895 1104 1895 1093 1895 1093 1896 1104 1896 1103 1896 1093 1897 1103 1897 1108 1897 1075 1898 1102 1898 1073 1898 1073 1899 1102 1899 1104 1899 1073 1900 1104 1900 1072 1900 1072 1901 1104 1901 1090 1901 1072 1902 1090 1902 787 1902 1115 1903 798 1903 796 1903 1091 1904 1108 1904 1116 1904 1115 1905 1117 1905 798 1905 798 1906 1117 1906 1118 1906 798 1907 1118 1907 799 1907 1119 1908 1120 1908 1115 1908 1115 1909 1120 1909 1121 1909 1121 1910 1122 1910 1115 1910 1115 1911 1122 1911 1123 1911 1115 1912 1123 1912 1117 1912 1124 1913 1125 1913 1119 1913 1119 1914 1125 1914 1126 1914 1119 1915 1126 1915 1120 1915 1127 1916 1128 1916 1124 1916 1128 1917 1129 1917 1124 1917 1124 1918 1129 1918 1130 1918 1124 1919 1130 1919 1125 1919 1098 1920 1097 1920 1124 1920 1098 1921 1124 1921 1099 1921 874 1922 1127 1922 875 1922 875 1923 1127 1923 1124 1923 875 1924 1124 1924 877 1924 877 1925 1124 1925 1097 1925 877 1926 1097 1926 872 1926 1105 1927 1106 1927 1119 1927 1119 1928 1106 1928 1107 1928 1119 1929 1107 1929 1124 1929 1124 1930 1107 1930 1100 1930 1124 1931 1100 1931 1099 1931 1083 1932 1081 1932 1116 1932 1116 1933 1081 1933 1080 1933 1116 1934 1080 1934 1091 1934 796 1935 794 1935 1085 1935 1085 1936 1083 1936 796 1936 796 1937 1083 1937 1116 1937 796 1938 1116 1938 1115 1938 1115 1939 1116 1939 1108 1939 1115 1940 1108 1940 1119 1940 1119 1941 1108 1941 1103 1941 1119 1942 1103 1942 1105 1942 818 1943 1131 1943 1132 1943 876 1944 1133 1944 1134 1944 1134 1945 1133 1945 1135 1945 1134 1946 1135 1946 1136 1946 1136 1947 1135 1947 1137 1947 1136 1948 1137 1948 1138 1948 1138 1949 1137 1949 1139 1949 1138 1950 1139 1950 1140 1950 876 1951 1112 1951 1133 1951 1133 1952 1112 1952 1113 1952 1133 1953 1113 1953 1135 1953 1135 1954 1113 1954 1111 1954 1135 1955 1111 1955 1137 1955 1137 1956 1111 1956 1110 1956 1137 1957 1110 1957 1139 1957 1139 1958 1110 1958 1109 1958 1139 1959 1109 1959 1132 1959 1132 1960 1109 1960 1114 1960 1132 1961 1114 1961 818 1961 1140 1962 1139 1962 1141 1962 1141 1963 1139 1963 1132 1963 1141 1964 1132 1964 1142 1964 1142 1965 1132 1965 1131 1965 1142 1966 1131 1966 1143 1966 1131 1967 818 1967 817 1967 1131 1968 817 1968 1144 1968 1144 1969 817 1969 816 1969 1144 1970 816 1970 1145 1970 1145 1971 816 1971 815 1971 1145 1972 815 1972 910 1972 1143 1973 1131 1973 1146 1973 1146 1974 1131 1974 1144 1974 1146 1975 1144 1975 1147 1975 1147 1976 1144 1976 1145 1976 1147 1977 1145 1977 1148 1977 1148 1978 1145 1978 910 1978 1148 1979 910 1979 844 1979 1149 1980 1150 1980 1151 1980 1152 1981 874 1981 873 1981 1152 1982 873 1982 1153 1982 1153 1983 873 1983 1154 1983 1153 1984 1154 1984 1155 1984 1150 1985 1156 1985 1151 1985 1151 1986 1156 1986 1157 1986 1151 1987 1157 1987 1154 1987 1154 1988 1157 1988 1158 1988 1154 1989 1158 1989 1155 1989 1149 1990 1151 1990 1159 1990 1159 1991 1151 1991 848 1991 1159 1992 848 1992 850 1992 1143 1993 1146 1993 1151 1993 1151 1994 1146 1994 1147 1994 1151 1995 1147 1995 848 1995 848 1996 1147 1996 1148 1996 848 1997 1148 1997 844 1997 876 1998 1134 1998 873 1998 873 1999 1134 1999 1136 1999 873 2000 1136 2000 1154 2000 1154 2001 1136 2001 1138 2001 1138 2002 1140 2002 1154 2002 1154 2003 1140 2003 1141 2003 1154 2004 1141 2004 1151 2004 1151 2005 1141 2005 1142 2005 1151 2006 1142 2006 1143 2006 882 2007 1167 2007 1168 2007 1168 2008 1167 2008 1169 2008 1168 2009 1169 2009 1170 2009 882 2010 1160 2010 1167 2010 1167 2011 1160 2011 1161 2011 1167 2012 1161 2012 1169 2012 1169 2013 1161 2013 1165 2013 1169 2014 1165 2014 1171 2014 1170 2015 1169 2015 1172 2015 1172 2016 1169 2016 1171 2016 1172 2017 1171 2017 1173 2017 1173 2018 1171 2018 1174 2018 1173 2019 1174 2019 1175 2019 1166 2020 1176 2020 1162 2020 1162 2021 1176 2021 1174 2021 1162 2022 1174 2022 1163 2022 1163 2023 1174 2023 1171 2023 1163 2024 1171 2024 1164 2024 1164 2025 1171 2025 1165 2025 1166 2026 785 2026 1177 2026 1166 2027 1177 2027 1176 2027 1176 2028 1177 2028 1178 2028 1176 2029 1178 2029 1179 2029 1175 2030 1174 2030 1180 2030 1180 2031 1174 2031 1176 2031 1180 2032 1176 2032 1181 2032 1181 2033 1176 2033 1179 2033 1181 2034 1179 2034 1182 2034 1178 2035 1177 2035 1183 2035 1177 2036 785 2036 784 2036 1184 2037 1179 2037 1178 2037 1177 2038 784 2038 1183 2038 1183 2039 784 2039 786 2039 1183 2040 786 2040 1185 2040 1185 2041 786 2041 792 2041 1185 2042 792 2042 855 2042 1178 2043 1183 2043 1184 2043 1184 2044 1183 2044 1185 2044 1184 2045 1185 2045 1186 2045 1186 2046 1185 2046 855 2046 1186 2047 855 2047 853 2047 1182 2048 1179 2048 1187 2048 1187 2049 1179 2049 1184 2049 1187 2050 1184 2050 1188 2050 1188 2051 1184 2051 1186 2051 1188 2052 1186 2052 1189 2052 1189 2053 1186 2053 853 2053 1189 2054 853 2054 802 2054 1189 2055 802 2055 801 2055 1195 2056 1196 2056 1197 2056 1197 2057 1196 2057 1198 2057 1199 2058 1200 2058 1201 2058 1201 2059 1200 2059 1202 2059 1201 2060 1202 2060 1196 2060 1196 2061 1202 2061 1203 2061 1196 2062 1203 2062 1198 2062 1199 2063 1201 2063 1204 2063 1204 2064 1201 2064 1205 2064 1204 2065 1205 2065 1206 2065 801 2066 800 2066 1207 2066 1207 2067 1208 2067 801 2067 801 2068 1208 2068 1209 2068 801 2069 1209 2069 1205 2069 1205 2070 1209 2070 1210 2070 1205 2071 1210 2071 1206 2071 1189 2072 801 2072 1188 2072 1188 2073 801 2073 1205 2073 1188 2074 1205 2074 1187 2074 1175 2075 1180 2075 1201 2075 1201 2076 1180 2076 1181 2076 1201 2077 1181 2077 1205 2077 1205 2078 1181 2078 1182 2078 1205 2079 1182 2079 1187 2079 881 2080 882 2080 1211 2080 1211 2081 882 2081 1168 2081 1211 2082 1168 2082 1195 2082 1195 2083 1168 2083 1170 2083 1195 2084 1170 2084 1196 2084 1196 2085 1170 2085 1172 2085 1196 2086 1172 2086 1201 2086 1201 2087 1172 2087 1173 2087 1201 2088 1173 2088 1175 2088 825 2089 916 2089 1212 2089 1213 2090 1214 2090 1215 2090 811 2091 1213 2091 1216 2091 1213 2092 1215 2092 1216 2092 1216 2093 1215 2093 1217 2093 1216 2094 1217 2094 1212 2094 1212 2095 1217 2095 1218 2095 1212 2096 1218 2096 825 2096 811 2097 1216 2097 812 2097 812 2098 1216 2098 1212 2098 812 2099 1212 2099 813 2099 813 2100 1212 2100 916 2100 813 2101 916 2101 810 2101 878 2102 1219 2102 1192 2102 1192 2103 1219 2103 1220 2103 1192 2104 1220 2104 1193 2104 1193 2105 1220 2105 1221 2105 1193 2106 1221 2106 1194 2106 878 2107 1222 2107 1219 2107 1219 2108 1222 2108 1223 2108 1219 2109 1223 2109 1220 2109 1220 2110 1223 2110 1224 2110 1220 2111 1224 2111 1221 2111 1221 2112 1224 2112 1225 2112 1221 2113 1225 2113 1226 2113 1214 2114 1213 2114 1227 2114 1227 2115 1213 2115 1226 2115 1227 2116 1226 2116 1228 2116 1228 2117 1226 2117 1225 2117 1194 2118 1221 2118 1191 2118 1191 2119 1221 2119 1226 2119 1191 2120 1226 2120 1190 2120 1190 2121 1226 2121 1213 2121 1190 2122 1213 2122 811 2122 820 2123 819 2123 1229 2123 1229 2124 819 2124 1230 2124 1229 2125 1230 2125 1231 2125 1231 2126 1230 2126 1232 2126 1233 2127 1234 2127 1230 2127 1230 2128 1234 2128 1235 2128 1230 2129 1235 2129 1232 2129 1236 2130 1237 2130 1233 2130 1237 2131 1238 2131 1233 2131 1233 2132 1238 2132 1239 2132 1233 2133 1239 2133 1234 2133 1240 2134 879 2134 880 2134 1236 2135 1240 2135 1241 2135 1241 2136 1240 2136 880 2136 1241 2137 880 2137 1242 2137 1242 2138 880 2138 881 2138 1225 2139 1224 2139 1240 2139 1240 2140 1224 2140 1223 2140 1240 2141 1223 2141 879 2141 879 2142 1223 2142 1222 2142 879 2143 1222 2143 878 2143 1236 2144 1233 2144 1240 2144 1240 2145 1233 2145 1228 2145 1240 2146 1228 2146 1225 2146 1217 2147 1215 2147 1230 2147 1230 2148 1215 2148 1214 2148 1230 2149 1214 2149 1233 2149 1233 2150 1214 2150 1227 2150 1233 2151 1227 2151 1228 2151 1217 2152 1230 2152 1218 2152 1218 2153 1230 2153 819 2153 1218 2154 819 2154 825 2154 113 2155 95 2155 1243 2155 1243 2156 95 2156 858 2156 1243 2157 858 2157 857 2157 113 2158 1243 2158 111 2158 111 2159 1243 2159 1244 2159 111 2160 1244 2160 109 2160 109 2161 1244 2161 1245 2161 109 2162 1245 2162 107 2162 107 2163 1245 2163 807 2163 107 2164 807 2164 105 2164 862 2165 867 2165 1246 2165 866 2166 871 2166 1247 2166 871 2167 822 2167 1247 2167 1247 2168 822 2168 1248 2168 1247 2169 1248 2169 1249 2169 1249 2170 1248 2170 1250 2170 1249 2171 1250 2171 1251 2171 1251 2172 1250 2172 1252 2172 1251 2173 1252 2173 795 2173 795 2174 1252 2174 793 2174 867 2175 866 2175 1246 2175 1246 2176 866 2176 1247 2176 1246 2177 1247 2177 1253 2177 1253 2178 1247 2178 1249 2178 1253 2179 1249 2179 1254 2179 1254 2180 1249 2180 1251 2180 1254 2181 1251 2181 797 2181 797 2182 1251 2182 795 2182 863 2183 862 2183 1255 2183 1255 2184 862 2184 1246 2184 1255 2185 1246 2185 1256 2185 1256 2186 1246 2186 1253 2186 1256 2187 1253 2187 1257 2187 1257 2188 1253 2188 1254 2188 1257 2189 1254 2189 805 2189 805 2190 1254 2190 797 2190 857 2191 863 2191 1243 2191 1243 2192 863 2192 1255 2192 1243 2193 1255 2193 1244 2193 1244 2194 1255 2194 1256 2194 1244 2195 1256 2195 1245 2195 1245 2196 1256 2196 1257 2196 1245 2197 1257 2197 807 2197 807 2198 1257 2198 805 2198 793 2199 1252 2199 800 2199 800 2200 1252 2200 1258 2200 822 2201 826 2201 1248 2201 1248 2202 826 2202 1258 2202 1248 2203 1258 2203 1250 2203 1250 2204 1258 2204 1252 2204 821 2205 820 2205 1259 2205 1259 2206 820 2206 1260 2206 1259 2207 1260 2207 1207 2207 1207 2208 1260 2208 1208 2208 826 2209 821 2209 1258 2209 1258 2210 821 2210 1259 2210 1258 2211 1259 2211 800 2211 800 2212 1259 2212 1207 2212 1208 2213 1260 2213 1261 2213 881 2214 1262 2214 1242 2214 1242 2215 1262 2215 1263 2215 1242 2216 1263 2216 1241 2216 881 2217 1211 2217 1262 2217 1262 2218 1211 2218 1195 2218 1262 2219 1195 2219 1263 2219 1263 2220 1195 2220 1197 2220 1263 2221 1197 2221 1264 2221 1264 2222 1197 2222 1198 2222 1241 2223 1263 2223 1236 2223 1236 2224 1263 2224 1264 2224 1236 2225 1264 2225 1237 2225 1237 2226 1264 2226 1265 2226 1237 2227 1265 2227 1238 2227 1198 2228 1203 2228 1264 2228 1264 2229 1203 2229 1202 2229 1264 2230 1202 2230 1265 2230 1265 2231 1202 2231 1200 2231 1265 2232 1200 2232 1266 2232 1266 2233 1200 2233 1199 2233 1266 2234 1199 2234 1267 2234 1238 2235 1265 2235 1239 2235 1239 2236 1265 2236 1266 2236 1239 2237 1266 2237 1234 2237 1234 2238 1266 2238 1267 2238 1234 2239 1267 2239 1235 2239 1235 2240 1267 2240 1268 2240 1235 2241 1268 2241 1232 2241 1199 2242 1204 2242 1267 2242 1267 2243 1204 2243 1206 2243 1267 2244 1206 2244 1268 2244 1268 2245 1206 2245 1210 2245 1268 2246 1210 2246 1261 2246 1261 2247 1210 2247 1209 2247 1261 2248 1209 2248 1208 2248 1232 2249 1268 2249 1231 2249 1231 2250 1268 2250 1261 2250 1231 2251 1261 2251 1229 2251 1229 2252 1261 2252 1260 2252 1229 2253 1260 2253 820 2253 103 2254 808 2254 1269 2254 103 2255 1269 2255 100 2255 100 2256 1269 2256 1270 2256 100 2257 1270 2257 98 2257 98 2258 1270 2258 838 2258 98 2259 838 2259 96 2259 808 2260 806 2260 1269 2260 1269 2261 806 2261 1271 2261 1269 2262 1271 2262 1270 2262 1270 2263 1271 2263 1272 2263 1270 2264 1272 2264 838 2264 831 2265 834 2265 1272 2265 1272 2266 834 2266 840 2266 1272 2267 840 2267 838 2267 1273 2268 1274 2268 1275 2268 1275 2269 1274 2269 1276 2269 1275 2270 1276 2270 803 2270 803 2271 1276 2271 804 2271 806 2272 804 2272 1271 2272 1271 2273 804 2273 1276 2273 1271 2274 1276 2274 1272 2274 1272 2275 1276 2275 1274 2275 1272 2276 1274 2276 831 2276 831 2277 1274 2277 1273 2277 831 2278 1273 2278 832 2278 803 2279 799 2279 1277 2279 803 2280 1277 2280 1275 2280 1275 2281 1277 2281 1278 2281 1275 2282 1278 2282 1273 2282 1273 2283 1278 2283 843 2283 1273 2284 843 2284 832 2284 1279 2285 1280 2285 849 2285 849 2286 1280 2286 850 2286 1118 2287 1117 2287 1281 2287 1281 2288 1117 2288 1282 2288 1281 2289 1282 2289 1279 2289 1279 2290 1282 2290 1283 2290 1279 2291 1283 2291 1280 2291 799 2292 1118 2292 1277 2292 1277 2293 1118 2293 1281 2293 1277 2294 1281 2294 1278 2294 1278 2295 1281 2295 1279 2295 1278 2296 1279 2296 843 2296 843 2297 1279 2297 849 2297 1159 2298 1284 2298 1285 2298 874 2299 1286 2299 1127 2299 1127 2300 1286 2300 1287 2300 874 2301 1152 2301 1286 2301 1286 2302 1152 2302 1153 2302 1286 2303 1153 2303 1287 2303 1287 2304 1153 2304 1155 2304 1158 2305 1288 2305 1155 2305 1155 2306 1288 2306 1289 2306 1155 2307 1289 2307 1287 2307 1287 2308 1289 2308 1128 2308 1287 2309 1128 2309 1127 2309 1290 2310 1125 2310 1288 2310 1288 2311 1125 2311 1130 2311 1288 2312 1130 2312 1289 2312 1289 2313 1130 2313 1129 2313 1289 2314 1129 2314 1128 2314 1158 2315 1157 2315 1288 2315 1288 2316 1157 2316 1156 2316 1288 2317 1156 2317 1290 2317 1290 2318 1156 2318 1150 2318 1290 2319 1150 2319 1285 2319 1285 2320 1150 2320 1149 2320 1285 2321 1149 2321 1159 2321 1123 2322 1122 2322 1284 2322 1284 2323 1122 2323 1121 2323 1284 2324 1121 2324 1285 2324 1285 2325 1121 2325 1120 2325 1285 2326 1120 2326 1290 2326 1290 2327 1120 2327 1126 2327 1290 2328 1126 2328 1125 2328 1282 2329 1117 2329 1123 2329 1282 2330 1123 2330 1283 2330 1283 2331 1123 2331 1284 2331 1283 2332 1284 2332 1280 2332 1280 2333 1284 2333 1159 2333 1280 2334 1159 2334 850 2334 836 2335 1020 2335 958 2335 958 2336 1020 2336 1019 2336 958 2337 1019 2337 955 2337 955 2338 1019 2338 1018 2338 955 2339 1018 2339 956 2339 956 2340 1018 2340 1015 2340 1291 2341 953 2341 952 2341 1017 2342 1291 2342 1016 2342 1016 2343 1291 2343 952 2343 1016 2344 952 2344 1015 2344 1015 2345 952 2345 957 2345 1015 2346 957 2346 956 2346 1292 2347 989 2347 1006 2347 962 2348 1292 2348 961 2348 961 2349 1292 2349 1006 2349 961 2350 1006 2350 960 2350 960 2351 1006 2351 1005 2351 960 2352 1005 2352 782 2352 1044 2353 1293 2353 1294 2353 1292 2354 962 2354 1053 2354 989 2355 1292 2355 1295 2355 1292 2356 1053 2356 1295 2356 1295 2357 1053 2357 1052 2357 1295 2358 1052 2358 1296 2358 1296 2359 1052 2359 1050 2359 1296 2360 1050 2360 1297 2360 1297 2361 1050 2361 1049 2361 1297 2362 1049 2362 1298 2362 1298 2363 1049 2363 1056 2363 1298 2364 1056 2364 1294 2364 1294 2365 1056 2365 1055 2365 1294 2366 1055 2366 1044 2366 989 2367 1295 2367 990 2367 990 2368 1295 2368 1296 2368 990 2369 1296 2369 991 2369 991 2370 1296 2370 1297 2370 991 2371 1297 2371 992 2371 992 2372 1297 2372 1298 2372 992 2373 1298 2373 993 2373 993 2374 1298 2374 1294 2374 993 2375 1294 2375 988 2375 988 2376 1294 2376 1293 2376 988 2377 1293 2377 985 2377 1047 2378 1042 2378 1299 2378 986 2379 985 2379 1300 2379 1300 2380 985 2380 1293 2380 1300 2381 1293 2381 1043 2381 1043 2382 1293 2382 1044 2382 994 2383 986 2383 1299 2383 1299 2384 986 2384 1300 2384 1299 2385 1300 2385 1047 2385 1047 2386 1300 2386 1043 2386 995 2387 994 2387 1301 2387 1301 2388 994 2388 1299 2388 1301 2389 1299 2389 1039 2389 1039 2390 1299 2390 1042 2390 996 2391 995 2391 1302 2391 1302 2392 995 2392 1301 2392 1302 2393 1301 2393 932 2393 932 2394 1301 2394 1039 2394 777 2395 1303 2395 938 2395 938 2396 1303 2396 1304 2396 938 2397 1304 2397 928 2397 928 2398 1304 2398 929 2398 929 2399 1304 2399 1305 2399 929 2400 1305 2400 934 2400 934 2401 1305 2401 935 2401 935 2402 1305 2402 1306 2402 935 2403 1306 2403 939 2403 996 2404 1302 2404 998 2404 998 2405 1302 2405 1306 2405 998 2406 1306 2406 984 2406 984 2407 1306 2407 1305 2407 984 2408 1305 2408 983 2408 983 2409 1305 2409 1304 2409 983 2410 1304 2410 981 2410 981 2411 1304 2411 1303 2411 981 2412 1303 2412 978 2412 978 2413 1303 2413 777 2413 939 2414 1306 2414 931 2414 931 2415 1306 2415 1302 2415 931 2416 1302 2416 932 2416 1307 2417 968 2417 967 2417 1003 2418 1307 2418 987 2418 987 2419 1307 2419 1308 2419 987 2420 1308 2420 1004 2420 1004 2421 1308 2421 783 2421 1307 2422 967 2422 1308 2422 1308 2423 967 2423 970 2423 1308 2424 970 2424 783 2424 1309 2425 1017 2425 1010 2425 1310 2426 1311 2426 1312 2426 1312 2427 1311 2427 1309 2427 976 2428 1313 2428 977 2428 977 2429 1313 2429 1310 2429 977 2430 1310 2430 997 2430 1309 2431 1010 2431 1312 2431 1312 2432 1010 2432 1008 2432 1312 2433 1008 2433 1314 2433 1008 2434 1007 2434 1314 2434 1314 2435 1007 2435 1021 2435 1314 2436 1021 2436 1315 2436 1021 2437 1014 2437 1315 2437 1315 2438 1014 2438 1013 2438 1315 2439 1013 2439 1316 2439 1316 2440 1013 2440 1011 2440 1316 2441 1011 2441 1317 2441 1317 2442 1011 2442 968 2442 1317 2443 968 2443 1307 2443 1310 2444 1312 2444 997 2444 997 2445 1312 2445 1314 2445 997 2446 1314 2446 999 2446 999 2447 1314 2447 1315 2447 999 2448 1315 2448 1000 2448 1000 2449 1315 2449 1316 2449 1000 2450 1316 2450 1001 2450 1001 2451 1316 2451 1317 2451 1001 2452 1317 2452 1002 2452 1002 2453 1317 2453 1307 2453 1002 2454 1307 2454 1003 2454 1311 2455 1318 2455 1309 2455 1319 2456 1313 2456 976 2456 1309 2457 1318 2457 1017 2457 1320 2458 953 2458 1291 2458 1313 2459 1319 2459 1310 2459 1310 2460 1319 2460 1321 2460 1310 2461 1321 2461 1311 2461 1311 2462 1321 2462 1320 2462 1311 2463 1320 2463 1318 2463 1318 2464 1320 2464 1291 2464 1318 2465 1291 2465 1017 2465 776 2466 945 2466 1322 2466 1322 2467 945 2467 947 2467 948 2468 1323 2468 947 2468 947 2469 1323 2469 1324 2469 947 2470 1324 2470 1322 2470 954 2471 953 2471 1320 2471 948 2472 950 2472 1323 2472 1323 2473 950 2473 949 2473 1323 2474 949 2474 1325 2474 1325 2475 949 2475 954 2475 954 2476 1320 2476 1325 2476 1325 2477 1320 2477 1321 2477 1325 2478 1321 2478 1319 2478 776 2479 1322 2479 979 2479 979 2480 1322 2480 1324 2480 979 2481 1324 2481 980 2481 980 2482 1324 2482 1323 2482 980 2483 1323 2483 982 2483 982 2484 1323 2484 1325 2484 982 2485 1325 2485 975 2485 975 2486 1325 2486 1319 2486 975 2487 1319 2487 976 2487 491 2488 486 2488 127 2488 127 2488 486 2488 230 2488 127 2488 230 2488 229 2488 348 2488 347 2488 253 2488 484 2488 156 2488 125 2488 125 2488 156 2488 158 2488 235 2488 233 2488 125 2488 125 2488 233 2488 585 2488 229 2488 225 2488 127 2488 127 2488 225 2488 525 2488 127 2488 525 2488 164 2488 164 2488 168 2488 127 2488 127 2488 168 2488 434 2488 127 2488 434 2488 244 2488 244 2488 242 2488 127 2488 127 2488 242 2488 365 2488 127 2488 365 2488 359 2488 359 2488 365 2488 364 2488 348 2488 253 2488 353 2488 585 2488 583 2488 125 2488 125 2488 583 2488 128 2488 125 2488 128 2488 127 2488 127 2488 128 2488 133 2488 127 2488 133 2488 491 2488 353 2488 253 2488 125 2488 125 2488 253 2488 266 2488 125 2488 266 2488 484 2488 158 2488 617 2488 125 2488 125 2488 617 2488 237 2488 125 2488 237 2488 235 2488 122 2489 123 2489 290 2489 290 2490 123 2490 324 2490 290 2491 324 2491 289 2491 289 2492 324 2492 325 2492 289 2493 325 2493 323 2493 322 2494 321 2494 292 2494 292 2495 321 2495 293 2495 322 2496 292 2496 323 2496 323 2497 292 2497 291 2497 323 2498 291 2498 289 2498 296 2499 295 2499 294 2499 293 2500 321 2500 294 2500 294 2501 321 2501 320 2501 294 2502 320 2502 296 2502 319 2503 317 2503 1326 2503 46 2504 51 2504 316 2504 316 2505 51 2505 297 2505 316 2506 297 2506 317 2506 317 2507 297 2507 296 2507 317 2508 296 2508 1326 2508 1326 2509 296 2509 320 2509 1326 2510 320 2510 319 2510

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_G4.dae b/URDFs/sr_description/meshes/components/forearm/forearm_G4.dae new file mode 100644 index 0000000..8085e6b --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_G4.dae @@ -0,0 +1,122 @@ + + + + + + Blender User + Blender 2.82.7 + + 2022-03-18T07:36:51 + 2022-03-18T07:36:51 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.04392 0.04392 0.04392 1 + + + 0.21961 0.21961 0.21961 1 + + + 0.45000 0.45000 0.45000 1 + + + 32 + + + 1 + + + + + + + + + + + + + + + + + -0.02623391 -0.03521358 0.1496011 -0.02618992 -0.03425312 0.1500974 -0.02616453 -0.03866803 0.1500959 -0.005057454 0.0345999 0.143736 -0.005057454 0.03679984 0.143736 -0.006575882 0.0345999 0.1415436 -0.006575882 0.03679984 0.1415436 -0.00797683 0.0345999 0.1405261 -0.00797683 0.03679984 0.1405261 -0.01051414 0.0345999 0.138683 -0.01051414 0.03679984 0.138683 -0.01174145 0.0345999 0.1384443 -0.01174145 0.03679984 0.1384443 -0.01529228 0.0345999 0.1377538 -0.01529228 0.03679984 0.1377538 -0.01604086 0.0345999 0.1379402 -0.01604086 0.03679984 0.1379402 -0.02001583 0.0345999 0.13893 -0.02001583 0.03679984 0.13893 -0.02024543 0.0345999 0.1391158 -0.02024543 0.03679984 0.1391158 -0.02366226 0.03679984 0.14188 -0.02617186 0.03347349 0.1500961 -0.02624154 0.03025054 0.1494353 -0.02622157 0.03165191 0.1482014 -0.02621138 0.03385323 0.1495463 -0.02617383 0.03210926 0.1476939 -0.02624994 0.03422433 0.1490089 -0.02612435 0.03229433 0.1474367 -0.02607053 0.03537255 0.1469987 -0.02586144 0.03327924 0.1460688 -0.02590376 0.03573668 0.1462306 -0.02576041 0.03347533 0.145725 -0.0257321 0.03592181 0.1457347 -0.02572077 0.03355228 0.1455901 -0.02565842 0.03600126 0.1455218 -0.02533948 0.03396451 0.1446461 -0.02528339 0.03640592 0.1444378 -0.02508193 0.03424274 0.1440083 -0.02481943 0.03663754 0.1435099 -0.02475011 0.03442138 0.1433877 -0.02380019 0.03679984 0.1419914 -0.02380019 0.0345999 0.1419914 -0.02366226 0.0345999 0.14188 -0.02613574 -0.03832614 0.1505991 -0.02616441 -0.03369635 0.150385 -0.02492105 -0.03508919 0.154304 -0.02524435 -0.0358088 0.1535388 -0.02571946 -0.03686636 0.1524139 -0.02615278 -0.03342568 0.1504746 -0.02612221 -0.032 0.1506907 -0.02492105 0.02988922 0.154304 -0.02612221 0.02679985 0.1506907 -0.02612709 0.02735805 0.1506575 -0.02613294 0.02762436 0.1506183 -0.02525389 0.03061318 0.1535422 -0.02619034 0.02904456 0.1501569 -0.02563285 0.03143793 0.1526744 -0.02613574 0.03312611 0.1505991 -0.02619451 0.02914339 0.1500978 -0.02622139 0.02977544 0.1497197 -0.02604287 -0.03796499 0.1468521 -0.02618867 -0.03719431 0.147827 -0.02619594 -0.03904181 0.1495462 -0.02624011 -0.03588688 0.1490709 -0.02624732 -0.03570389 0.1492449 -0.02573186 -0.04112321 0.1457326 -0.02567327 -0.04121828 0.145514 -0.02562087 -0.03890794 0.1452911 -0.02559125 -0.04135179 0.1452069 -0.02509397 -0.03943473 0.1440327 -0.02528339 -0.04160583 0.1444378 -0.02424943 -0.03976428 0.1425961 -0.02442169 -0.04194486 0.1428523 -0.02380025 -0.03979986 0.1419916 -0.02380025 -0.04199987 0.1419916 -0.02368611 -0.03979986 0.1418507 -0.02624547 -0.03963023 0.1486809 -0.02607053 -0.04057252 0.1469987 -0.02573972 -0.0386424 0.1457304 -0.02569991 -0.03873169 0.1455829 -0.02368611 -0.04199987 0.1418507 -0.02028387 -0.04199987 0.1390681 -0.02028387 -0.03979986 0.1390681 -0.01607537 -0.04199987 0.1378015 -0.01607537 -0.03979986 0.1378015 -0.01170253 -0.04199987 0.138244 -0.01170253 -0.03979986 0.138244 -0.007833123 -0.04199987 0.1403282 -0.007833123 -0.03979986 0.1403282 -0.005057454 -0.04199987 0.143736 -0.005057454 -0.03979986 0.143736 -0.002073884 0.03679984 0.1472916 -0.002073884 0.0345999 0.1472916 -0.001454651 0.03674829 0.1480296 -4.30169e-4 0.03391474 0.1492507 -0.002073884 -0.03979986 0.1472917 -0.002073884 -0.04199987 0.1472917 1.11491e-4 -0.03888893 0.1498962 1.39871e-4 -0.04131484 0.14993 0.001711249 -0.03639996 0.1518028 0.002016603 -0.03936392 0.1521667 0.003270626 -0.036444 0.1536613 0.002296805 -0.03299999 0.1525008 0.003710985 -0.03299999 0.1541861 0.002296805 0.02779996 0.1525008 0.003710985 0.02779996 0.1541861 0.001856446 0.0303573 0.1519758 0.003166437 0.0312038 0.153537 0.001711249 0.03119999 0.1518028 0.003036201 0.03201854 0.1533818 9.11425e-4 0.03244435 0.1508495 0.001895368 0.03399449 0.1520223 1.11491e-4 0.03368896 0.1498962 0.001168966 0.03525274 0.1511566 8.26677e-5 0.03587204 0.1498619 -0.04468363 0.02863204 0.1352923 -0.04468363 -0.03383207 0.1352923 -0.04103291 0.02741122 0.1389318 -0.04090267 -0.03258025 0.1390618 -0.03586727 0.02679985 0.1440818 -0.03586733 -0.032 0.1440818 -0.02531814 0.02679985 0.1545989 -0.02531814 -0.032 0.1545989 -0.05350261 0.02922093 0.1140468 -0.05350261 0.02922093 0 -0.05350261 -0.02922093 0.1140468 -0.05350261 -0.02922093 0 0.05499982 0.03211307 0 0.05499982 0.03211307 0.1033861 0.05499982 0.0317341 0.1035228 0.05499982 0.03116172 0.1036442 0.05499982 0.03048259 0.1036889 0.05499982 -0.03211307 0 0.05499982 -0.03048259 0.1036889 0.05499982 -0.0308181 0.1036785 0.05499982 -0.03142088 0.1036003 0.05499982 -0.031663 0.1035431 0.05499982 -0.03211307 0.1033861 0.0320633 -0.03791302 0.1303958 0.03662502 -0.04112488 0.1265681 0.04291534 -0.03677845 0.12129 0.02181714 0.02837979 0.1389933 0.02733808 -0.03528881 0.1343607 0.0273292 0.03008478 0.1343682 0.04928439 -0.03048259 0.1159456 0.04928439 0.03048259 0.1159456 0.04408854 0.03578764 0.1203055 0.04846173 -0.03143972 0.116636 0.03218114 0.03279644 0.130297 0.03367292 0.03395056 0.1290451 0.03981745 0.03910624 0.1238894 0.01597625 0.02779996 0.1438944 0.01597625 -0.03299999 0.1438944 0.0161814 -0.03300058 0.1437222 0.02196466 -0.03360992 0.1388695 -0.02843612 0.05997622 0 -0.02843612 0.05997622 0.1022255 0.02565425 0.05997622 0 0.02372968 0.05997622 0.1022255 0.02450311 0.05997622 0.1021777 0.02510929 0.05997622 0.1020546 0.02559107 0.05997622 0.1018754 0.02565425 0.05997622 0.1018446 0.02565425 -0.05997622 0 0.02565425 -0.05997622 0.1050993 0.02559286 -0.05997622 0.1051267 -0.02843612 -0.05997622 0.1053854 -0.02843612 -0.05997622 0 0.02413386 -0.05997622 0.1053854 0.02515876 -0.05997622 0.1052713 0.02479273 -0.05997622 0.1053419 0.027888 0.04031467 0.1285147 -0.03372383 0.05364292 0.1151862 -0.03603756 0.05187666 0.1169525 0.03493005 0.0463311 0.122498 0.02958649 0.05130249 0.1175268 0.03450143 0.04589027 0.122939 0.02372968 0.0552901 0.1135392 0.0340324 0.04547023 0.1233589 -0.03132373 0.0552901 0.1135392 -0.03925633 0.04861372 0.1202154 -0.04168009 0.04463338 0.1241958 -0.04309391 0.04031467 0.1285147 -0.03861737 -0.04325091 0.1316651 -0.04214227 -0.04443883 0.1297483 -0.04213196 -0.04445332 0.1297293 0.02627813 -0.04480743 0.1292865 0.02155297 -0.04330784 0.1315522 -0.04186517 -0.04480743 0.1292865 0.01869404 -0.04279732 0.132923 -0.03630477 -0.04279834 0.1329227 0.01039648 -0.04200035 0.1369016 0.0101912 -0.04199987 0.137 -0.02880704 -0.04199987 0.137 0.01617974 -0.04234856 0.1341286 -0.03384238 -0.04231643 0.1342617 -0.04154139 -0.04551863 0.1284388 -0.0391528 -0.04933434 0.1238915 -0.03603756 -0.05246603 0.1201593 0.03083997 -0.04801923 0.1254587 0.02733016 -0.05417054 0.1181278 0.03199023 -0.04894053 0.1243607 0.03274393 -0.04973137 0.1234184 -0.03345811 -0.05442363 0.1178263 -0.03077238 -0.05623292 0.11567 0.02413386 -0.05623292 0.11567 0.05432766 0.03048259 0.1082777 0.05432766 -0.03048259 0.1082777 0.05236762 0.03048259 0.1124811 0.05236762 -0.03048259 0.1124811 -0.02880698 0.03679984 0.137 0.0101912 0.03679984 0.137 0.02639603 0.03965497 0.12923 -0.04319638 0.04002237 0.1288174 -0.04328066 0.03974169 0.1291292 -0.04313004 0.03967118 0.1292111 0.02154403 0.03810554 0.1315564 -0.03397274 0.03713327 0.1341909 0.01603209 0.03713124 0.1341993 -0.03720289 0.03778296 0.1324343 0.01971393 0.03778213 0.132434 -0.03884536 0.03811347 0.1315411 0.04341465 -0.05160474 0.1055567 0.04271638 -0.05226427 0.105969 0.03645592 -0.05680847 0 0.0413075 -0.05338466 0.1068009 0.03883767 -0.05520761 0.1052721 0.03645592 -0.05680847 0.1039295 0.04345709 -0.05164992 0 0.04973667 -0.04563421 0 0.04973667 -0.04563421 0.1018236 0.04973667 0.04563421 0.1018236 0.04973667 0.04563421 0 0.04457169 0.05069106 0.1048734 0.04345709 0.05164992 0 0.04344415 0.05163466 0.1042094 0.03645592 0.05680847 0 0.03645592 0.05680847 0.1005687 0.04204392 0.05280673 0.1033847 -0.03927677 -0.05489587 0.1113985 -0.04230493 -0.05259788 0.1137315 -0.04230493 -0.05259788 0 -0.03612416 -0.05701988 0.1092422 -0.03338152 -0.05866777 0 -0.03338152 -0.05866777 0.1053854 -0.03588855 -0.05716866 0.109086 -0.03464317 -0.05793184 0.1072357 -0.03491598 -0.05776768 0.1083202 -0.0335763 -0.05855643 0.106448 -0.0338546 -0.05839616 0.1070358 -0.03426015 -0.05815911 0.1076243 -0.03343313 -0.05863839 0.1059337 -0.04230493 0.05259788 0 -0.04230493 0.05259788 0.1098815 -0.03958874 0.05467134 0.1081151 -0.03437578 0.05809068 0.104604 -0.03388416 0.05837893 0.1039264 -0.03509145 0.05766129 0.1043468 -0.03368151 0.05849605 0.1035423 -0.03347235 0.05861604 0.1029521 -0.03339463 0.05866026 0.1025018 -0.03338152 0.05866777 0.1022255 -0.03677123 0.05660492 0.1064682 -0.03566777 0.05730646 0.105771 -0.0347445 0.0578711 0.1049975 -0.03338152 0.05866777 0 -0.02848017 -0.0599094 0.1068477 0.02413386 -0.05901134 0.1108577 -0.02860212 -0.05972331 0.1082189 -0.02883911 -0.05935913 0.1097865 -0.03057163 -0.05657058 0.1152536 -0.02974325 -0.05793172 0.1132115 -0.02918452 -0.05882066 0.1113558 -0.02907359 -0.05899351 0.1108517 -0.02928316 0.05866551 0.1085681 -0.02959716 0.05816638 0.1096175 0.02372968 0.05783265 0.1102254 -0.02982145 0.05780071 0.1102057 -0.03038376 0.05688405 0.1116802 0.02372968 0.05943101 0.1063666 -0.02844727 0.05995935 0.1029623 -0.02851355 0.05985862 0.104163 -0.02869153 0.0595861 0.105737 -0.02879738 0.05942296 0.1063645 -0.02886438 0.05931997 0.106761 -0.03150886 0.03603863 0.1397101 -0.03379935 0.03387105 0.1420076 -0.03532975 0.03062677 0.1435427 -0.02520966 0.02752017 0.1546341 -0.02531588 0.02681976 0.154601 -0.02510046 0.02823984 0.154668 -0.02509951 0.02824676 0.1546683 -0.02501457 0.02877616 0.1545956 -0.02492874 0.02931153 0.154522 -0.02490437 0.029464 0.154501 -0.02489864 0.02967876 0.1544173 -0.0248959 0.02978581 0.1543757 -0.04112529 0.03676044 0.1331371 -0.04469853 0.02866619 0.1352772 -0.04019427 0.03080153 0.1389068 -0.04489046 0.02911919 0.1350761 -0.04540443 0.03066784 0.1343369 -0.04318714 0.03468436 0.1341446 -0.04621195 0.03410387 0.1325629 -0.04483312 0.0320838 0.1344671 -0.04592108 0.03258121 0.133376 -0.04576081 0.03174155 0.1338243 -0.04630357 0.03767681 0.1303672 -0.04629766 0.03745049 0.1305063 -0.04542195 0.03840076 0.1301121 -0.04527562 0.03832608 0.1302158 -0.04540812 0.03840953 0.1301057 -0.04625988 0.03597021 0.131416 -0.03643471 0.03597825 0.1363824 -0.03859657 0.03377825 0.1380209 -0.0248959 -0.03498578 0.1543757 -0.02489864 -0.03487879 0.1544173 -0.03532975 -0.0358268 0.1435427 -0.02490437 -0.03466397 0.154501 -0.02492874 -0.03451168 0.154522 -0.02501457 -0.03397613 0.1545956 -0.02509951 -0.03344672 0.1546683 -0.02510046 -0.03343981 0.154668 -0.02531588 -0.03201973 0.154601 -0.02520966 -0.03272014 0.1546341 -0.03379935 -0.03907102 0.1420076 -0.03150886 -0.04123878 0.1397101 -0.0448423 -0.03420263 0.1351283 -0.04529047 -0.03548943 0.134522 -0.04461503 -0.03719604 0.134676 -0.04216897 -0.04442965 0.1297603 -0.04090505 -0.04190289 0.1332909 -0.04356539 -0.04385304 0.1303068 -0.04252487 -0.04430115 0.1299146 -0.04628139 -0.04118156 0.1314222 -0.046346 -0.04209578 0.1308818 -0.04297119 -0.03981733 0.1343281 -0.04543012 -0.04277169 0.1307758 -0.04467976 -0.04320687 0.1305871 -0.04563939 -0.03649091 0.1340501 -0.04593157 -0.03778374 0.1333793 -0.04609119 -0.03848952 0.1330131 -0.04007071 -0.0359829 0.1390247 -0.04469853 -0.03386622 0.1352772 -0.03630971 -0.04116928 0.1364679 -0.0384745 -0.03896796 0.1381232 -0.04701596 0.04785227 0 -0.05055886 0.04218125 0 -0.04713296 0.04770362 0.1131443 -0.04700088 0.04783767 0.1130551 -0.05264347 0.03584831 0.1193487 -0.05247467 0.03700697 0.1202756 -0.0527575 0.0358662 0 -0.05076897 0.04173302 0.1171247 -0.05051285 0.04215359 0.1168444 -0.05349195 0.03002578 0.1146906 -0.05055826 -0.04218089 0.1220077 -0.05056089 -0.04217696 0.122011 -0.0527575 -0.0358662 0 -0.05122965 -0.04067587 0.1232108 -0.05266839 -0.03624713 0.1196677 -0.05104637 -0.04110985 0.1228587 -0.05271416 -0.03586035 0.1193584 -0.05055886 -0.04218125 0 -0.04701596 -0.04785227 0 -0.04701024 -0.0478487 0.1175047 -0.04697769 -0.04790037 0.1174636 -0.04470658 -0.03385102 0.1352694 -0.04470658 0.02865099 0.1352694 -0.04492998 -0.03403913 0.1350437 -0.04500669 0.02890473 0.1349653 -0.04636526 -0.03536111 0.1334712 -0.04663187 0.03043085 0.1331529 -0.04751145 -0.03658467 0.132035 -0.04795324 0.03190523 0.1314298 -0.05030405 0.03504395 0.1275261 -0.05073887 0.03538316 0.1266244 -0.05242866 -0.03543215 0.1218109 -0.05122965 -0.03838503 0.1255018 -0.05102062 -0.03869879 0.1259953 -0.04973649 0.03438663 0.1285997 -0.05087304 -0.03884357 0.1263296 -0.05053985 -0.03903484 0.1270465 -0.05028718 -0.03909832 0.1275593 -0.04971915 -0.03908795 0.1286311 -0.0494467 0.03398323 0.1290597 -0.04946666 -0.03903341 0.1290723 -0.04936712 -0.03901177 0.1292464 -0.05006688 0.03482311 0.1279874 -0.05242002 0.03558987 0.1220336 -0.05247467 0.03544974 0.1218327 -0.05115145 0.03567963 0.1256894 -0.05163991 0.03593277 0.1244536 -0.0518791 0.0359801 0.123782 -0.05217301 0.0359041 0.1228792 -0.05234563 0.03572624 0.1222983 -0.05349195 0.02986466 0.1148515 -0.05247575 0.0354442 0.1218259 -0.05266839 -0.03484189 0.1210729 -0.04580122 -0.04484117 0.1278892 -0.04911756 -0.04302579 0.126601 -0.04919362 -0.04297816 0.1265032 -0.04615068 -0.04431951 0.1284319 -0.05078834 -0.04151672 0.1241278 -0.05046284 -0.04195296 0.1247029 -0.04905045 -0.04353255 0.1256143 -0.04970461 -0.04265916 0.1258465 -0.04641753 -0.04387044 0.1289266 -0.04695063 -0.04368901 0.1287612 -0.04778105 -0.04352843 0.1280287 -0.0425812 -0.04445755 0.1297081 -0.0437743 -0.04442471 0.1295503 -0.04590731 -0.04404413 0.129085 -0.04217278 -0.04444062 0.1297458 -0.04941093 -0.04284238 0.1262238 -0.04536169 -0.04563581 0.1270022 -0.04854518 -0.04445648 0.1247336 -0.04499459 -0.04937535 0.1200253 -0.04227113 -0.04987442 0.1222624 -0.03842329 -0.05332565 0.1183916 -0.04058116 -0.05337101 0.1161785 -0.03565222 -0.05534982 0.1160303 -0.03765106 -0.05551213 0.1138222 -0.03277295 -0.0572201 0.1138485 -0.03369045 -0.05735486 0.1127468 -0.03460764 -0.05748987 0.111645 -0.03348386 -0.05764949 0.1124641 -0.03251087 -0.05845558 0.1109372 -0.03186011 -0.05897539 0.1095913 -0.03145945 -0.05928772 0.108473 -0.03118538 -0.05949819 0.1073677 -0.03104472 -0.05960518 0.1064069 -0.03099375 -0.05964356 0.1053854 -0.03099375 -0.05964356 0 -0.04538232 0.03959095 0.1287239 -0.04743844 0.03932011 0.12822 -0.04696428 0.03876841 0.1291427 -0.04674685 0.03949308 0.1284606 -0.04661923 0.03985553 0.1280971 -0.04647237 0.04023671 0.1277431 -0.04654556 0.04021424 0.1277056 -0.04840219 0.0393638 0.1273415 -0.0484398 0.03936553 0.1273072 -0.0494132 0.03933399 0.1262367 -0.04390478 0.04935157 0.1173174 -0.04577273 0.04881066 0.1153154 -0.04943686 0.04343456 0.1194375 -0.05139601 0.03870779 0.1230231 -0.05112886 0.03893345 0.1235736 -0.04732775 0.04454797 0.1215186 -0.05056309 0.03917783 0.1245542 -0.0495398 0.03931689 0.1260515 -0.05220443 0.03774321 0.1211618 -0.05181568 0.03835302 0.1221583 -0.05236375 0.03736305 0.1206715 -0.04465287 0.04496139 0.1231595 -0.04167473 0.04928416 0.1189942 -0.03787237 0.05280292 0.1155977 -0.03844618 0.05295008 0.1150312 -0.04110389 0.05317491 0.1119517 -0.04060178 0.05319803 0.1125991 -0.03959602 0.05324465 0.1138963 -0.03597652 0.05483877 0.1132709 -0.03800016 0.05519372 0.1108312 -0.03527683 0.05699998 0.1091638 -0.03340047 0.05654716 0.1115993 -0.0309844 0.0596078 0.1022255 -0.03181684 0.0593875 0.1022255 -0.03183007 0.0593791 0.1026616 -0.03016436 0.05981642 0.1028167 -0.03015196 0.05982804 0.1022255 -0.03043591 0.05956053 0.1050497 -0.03023797 0.05974733 0.1037811 -0.03190839 0.05932885 0.1033732 -0.03211891 0.05919301 0.1043094 -0.03232347 0.05905967 0.1049225 -0.03282094 0.0587309 0.1060149 -0.03319525 0.05847883 0.1066582 -0.03062832 0.05937761 0.1058798 -0.0310958 0.05892556 0.1073578 -0.03144741 0.05857896 0.1082271 -0.03233271 0.0576806 0.1099699 -0.03413856 0.05782496 0.1079506 -0.03099375 0.05964356 0 0.04977792 -0.04558932 0.1018306 0.05259978 -0.04161262 0 0.05039364 -0.04488158 0.1019377 0.05225211 -0.04223042 0.1023051 0.05433636 -0.0369994 0.1029128 0.0540691 -0.03814357 0.1027938 0.05439054 -0.0370121 0 0.05365425 -0.03932529 0.1026605 0.05255973 -0.04159319 0.1023831 0.05476701 -0.03515672 0.1031045 0.05260568 -0.03135073 0.1120807 0.05438977 -0.03109484 0.1080462 0.05104738 -0.03491979 0.113524 0.05313694 -0.03362935 0.1107734 0.05091118 -0.03446662 0.1138513 0.05299592 -0.03296095 0.1111992 0.05061024 -0.0336076 0.1143901 0.04978406 -0.03156584 0.1154744 0.05397886 -0.03423392 0.1082678 0.05337047 -0.03491628 0.1098381 0.05141246 -0.03613615 0.1126459 0.05449086 -0.03221625 0.1075246 0.05452722 -0.03267616 0.1072683 0.0545873 -0.03355181 0.1066974 0.04976987 -0.04559803 0.1018512 0.04976207 -0.04560667 0.1018717 0.0502671 -0.0450266 0.1022748 0.05013358 -0.04516541 0.1026118 0.05177319 -0.04288029 0.1037364 0.05292654 -0.04049444 0.1051769 0.05327409 -0.03950721 0.1057276 0.05174267 -0.0414403 0.1076123 0.05138826 -0.04264259 0.106132 0.05115365 -0.04343789 0.1051524 0.05387085 -0.03695476 0.1070474 0.05183368 -0.03842884 0.1106889 0.05183845 -0.03899604 0.1101267 0.0518468 -0.03997403 0.1091575 0.05185192 -0.04060262 0.1085343 0.02877807 -0.05973076 0.1047971 0.0312826 -0.05916804 0 0.03127402 -0.05913209 0.1045342 0.03640305 -0.05684214 0.1039363 0.03587192 -0.05716919 0.1040031 0.03297716 -0.05858749 0.1043473 0.03183126 -0.05899852 0.1044754 0.04131305 -0.05338037 0.1068381 0.0506553 -0.03542572 0.1138703 0.05178219 -0.03912913 0.1102147 0.04459118 -0.04966825 0.1107321 0.04526937 -0.04601073 0.115103 0.04168045 -0.05256158 0.1110916 0.04164326 -0.05279582 0.1101733 0.04106307 -0.04945391 0.1182187 0.04128879 -0.0501123 0.1171526 0.04162508 -0.05151051 0.1142107 0.04165256 -0.05203384 0.1126577 0.04083514 -0.04878854 0.1192957 0.04469496 -0.04159277 0.1187216 0.04006677 -0.04693037 0.1216623 0.03811383 -0.04315561 0.1250773 0.03907853 -0.04484093 0.1237043 0.03945899 -0.04564517 0.1229182 0.03642153 -0.0568304 0.1039773 0.03641229 -0.05683624 0.1039568 0.03607434 -0.05703938 0.104452 0.03597426 -0.05710601 0.1042276 0.03413635 -0.05784934 0.1068979 0.03358328 -0.05827838 0.1056278 0.03378635 -0.05793154 0.1073033 0.03263109 -0.05862051 0.1061538 0.02896392 -0.05790013 0.112253 0.0273655 -0.05944854 0.1087982 0.03079015 -0.05813938 0.1105028 0.03006297 -0.05923724 0.1074962 0.03121221 -0.05819457 0.1100984 0.03335028 -0.05803376 0.1078086 0.02874165 -0.05784821 0.1124517 0.02722245 -0.059435 0.1089174 0.02759557 -0.05752938 0.1133877 0.02624917 -0.05932754 0.1096476 0.02725136 -0.05743378 0.1136689 0.02608281 -0.05703413 0.1144977 0.0254696 -0.05922293 0.110146 0.03638535 -0.052226 0.1191127 0.03576582 -0.05183285 0.1199355 0.03060162 -0.05571115 0.1155185 0.03464221 -0.05111956 0.1214277 0.036502 -0.05624294 0.1089268 0.03371036 -0.05641365 0.1123998 0.03767055 -0.05290836 0.117011 0.04023987 -0.05367559 0.1110432 0.04011482 -0.05365324 0.1113775 0.03909015 -0.05346995 0.1141183 0.0382471 -0.05313634 0.1158359 0.04130077 -0.05338984 0.1068377 0.04051625 -0.05366736 0.1101363 0.05476599 0.03516244 0.1031039 0.05439054 0.0370121 0 0.05433619 0.03699934 0.1029128 0.05259978 0.04161262 0 0.05351865 0.03966671 0.102621 0.05406671 0.03815072 0.1027929 0.04977792 0.04558932 0.1018306 0.05015254 0.04516667 0.1018951 0.05206316 0.04254585 0.1022638 0.05254817 0.04158639 0.1023828 0.04976987 0.04559803 0.1018512 0.05007261 0.04525673 0.1021063 0.05161941 0.04313659 0.1035711 0.04976207 0.04560667 0.1018717 0.0499897 0.04534441 0.1023174 0.05105912 0.04364871 0.1048669 0.05138617 0.04264044 0.1061323 0.0528137 0.0407775 0.1050144 0.053272 0.03951328 0.1057243 0.05169785 0.04167973 0.1073381 0.05185163 0.04060781 0.1085288 0.05183863 0.03899604 0.1101268 0.0538702 0.03695958 0.1070451 0.0518341 0.03843307 0.110685 0.05141246 0.03613615 0.1126459 0.05319035 0.03487581 0.1097452 0.05407643 0.03424787 0.1082996 0.05438357 0.0335378 0.1066653 0.05099606 0.03472417 0.1136794 0.05317658 0.03382909 0.1106387 0.05105513 0.03492438 0.1135327 0.05453735 0.03281283 0.1071867 0.05444914 0.03173029 0.1077674 0.05283451 0.0322597 0.1116067 0.05026715 0.03271353 0.1148977 0.0312826 0.05916804 0 0.03127276 0.05912786 0.1012278 0.03190523 0.0589742 0.101155 0.03640526 0.05684083 0.1005757 0.03341591 0.05840867 0.1009694 0.02881664 0.05972462 0.1015105 0.04047286 0.04000675 0.1232916 0.04611134 0.04828768 0.109715 0.04463601 0.0505613 0.1055815 0.04457718 0.05068629 0.1049118 0.04665035 0.0447207 0.1140674 0.04595768 0.04044008 0.1176941 0.04107308 0.0409345 0.1226401 0.04228729 0.04302418 0.1208966 0.04249078 0.04341173 0.1204745 0.04437083 0.04740911 0.1151162 0.04417079 0.04692876 0.1158788 0.04368299 0.04575634 0.1177394 0.04329431 0.04494118 0.1188081 0.04485213 0.0493707 0.1105242 0.04483997 0.04907453 0.1114783 0.04478091 0.04877257 0.1122515 0.04487985 0.05004292 0.1083587 0.02738022 0.05694639 0.111116 0.02763777 0.05705088 0.1109238 0.02685612 0.05865299 0.1081816 0.02807158 0.05888676 0.1071217 0.02920502 0.05755996 0.1095188 0.02942156 0.05762022 0.1093043 0.02696818 0.05970853 0.1044462 0.02685302 0.05970162 0.1045444 0.02760308 0.05931138 0.1057035 0.02823805 0.05891442 0.1069608 0.02600133 0.05964189 0.1051835 0.02583312 0.05631977 0.1122708 0.02543061 0.0583148 0.1092168 0.02497947 0.05955541 0.1057924 0.03641527 0.05683434 0.1005962 0.03642547 0.05682796 0.1006168 0.03401988 0.0580917 0.1021442 0.03027582 0.05916398 0.1043192 0.03280216 0.05854868 0.1028809 0.03069549 0.0578382 0.107949 0.03157401 0.0579884 0.1070145 0.03360772 0.0578944 0.1045801 0.03376436 0.05785816 0.1043745 0.03457504 0.05767083 0.1033105 0.0396527 0.05393987 0.1075214 0.03323036 0.05316454 0.1148121 0.03665459 0.05406171 0.1114087 0.04456567 0.05069649 0.1049116 0.04382508 0.05097013 0.1083412 0.04331499 0.05091673 0.1098921 0.04280513 0.05086314 0.1114417 0.0424962 0.05078077 0.1122096 0.03842502 0.04875826 0.1190509 0.03872627 0.04895508 0.1187108 0.03951311 0.04942065 0.1176527 0.04112994 0.05025744 0.1150527 0.04127866 0.05031424 0.1147435 0.03689682 0.04776018 0.1207765 0.01553589 0.03124397 0.1433696 0.01428174 0.03416395 0.1418751 0.01240491 0.03611487 0.1396384 0.01803588 0.03606539 0.1363316 0.03112334 0.03484958 0.1307808 0.02958792 0.03910446 0.1293305 0.02812772 0.03840082 0.1302283 0.03011882 0.03859508 0.1294538 0.02974051 0.03676158 0.1307573 0.03257298 0.03582072 0.1296042 0.03210997 0.03640466 0.1296365 0.0311824 0.03757476 0.1297013 0.02642232 0.03264504 0.1345906 0.0250681 0.0349707 0.1341603 0.02339071 0.03684812 0.1331171 0.02111274 0.03141117 0.1388812 0.01979982 0.03407955 0.137957 0.03628069 0.04378139 0.1243495 0.03828209 0.04157966 0.1245329 0.03886306 0.04232829 0.123932 0.03727704 0.04496121 0.1232441 0.03680127 0.04435974 0.1238103 0.03833544 0.04403138 0.1232686 0.0393939 0.04310137 0.1232931 0.04457139 0.0506913 0.1049117 0.04437041 0.05052691 0.108354 0.04388725 0.05004298 0.1114885 0.04371941 0.04986935 0.1122708 0.04290515 0.04901176 0.1151989 0.04183614 0.04786527 0.1179395 0.04128456 0.04726803 0.1190798 0.03993266 0.04579347 0.1213656 0.01240497 -0.04131484 0.1396384 0.01428174 -0.03936392 0.141875 0.01553595 -0.036444 0.1433696 0.01260197 -0.04129916 0.1395242 0.01447433 -0.03934442 0.1417396 0.01573067 -0.03643167 0.143213 0.01817888 -0.04127538 0.1362466 0.01994013 -0.03929024 0.1378566 0.02339953 -0.0420503 0.1331118 0.02507656 -0.04017305 0.1341542 0.02801257 -0.04355072 0.130299 0.02854984 -0.04300236 0.1304793 0.02962666 -0.04190361 0.1308405 0.03054881 -0.0406202 0.1308625 0.0212543 -0.03662967 0.1387669 0.02643096 -0.03784823 0.1345836 0.03100883 -0.03997993 0.1308736 0.03313148 -0.04625195 0.1267066 0.03514212 -0.04385572 0.1270922 0.03435456 -0.04751843 0.1253184 0.03732866 -0.04690492 0.1242236 0.03647017 -0.04551982 0.1255659 0.03623867 -0.0477463 0.1241744 0.03514885 -0.04858762 0.1241253 0.04098773 -0.05315458 0.1110755 0.04130691 -0.05338507 0.1068379 0.04109674 -0.05325382 0.1101587 0.04044044 -0.05259943 0.1142082 0.03963989 -0.05172401 0.1172082 0.03883928 -0.05081617 0.1194397 0.03766429 -0.04944998 0.1219743 -0.04651254 -0.04253435 0.1302981 -0.05247467 0.03622823 0.1210541 -0.05249452 0.03649216 0.1213689 -0.05238461 0.03675419 0.1217508 -0.05212724 0.03715789 0.1225523 -0.05168443 0.03750699 0.1237406 -0.0513218 0.03762555 0.1245961 -0.05057799 0.0376228 0.1261281 -0.04995334 0.03754287 0.1272078 -0.04930055 0.03741574 0.1282055 -0.04891878 0.03700721 0.1289257 -0.04838532 0.03620189 0.129876 -0.04470252 0.02865856 0.1352733 -0.04494965 0.02901202 0.1350218 -0.04623961 0.031093 0.1335315 -0.04721683 0.03304111 0.1321313 -0.05275005 -0.03555423 0.1203801 -0.05144345 -0.03957468 0.1244004 -0.04900389 -0.04026252 0.1292829 -0.04804736 -0.04232013 0.129132 -0.04853028 -0.04171729 0.1292953 -0.04915475 -0.04151839 0.1285776 -0.04861062 -0.04161679 0.1293225 -0.05002599 -0.04119521 0.1272309 -0.05040997 -0.04095149 0.1265618 -0.05091232 -0.04047042 0.1255925 -0.05113291 -0.04016751 0.1251233 -0.048074 -0.04201602 0.1296592 -0.0481621 -0.04068249 0.1303856 -0.04824596 -0.0405659 0.1303063 -0.04806643 -0.04075682 0.1304118 -0.04470252 -0.03385865 0.1352733 -0.04488664 -0.03412079 0.1350867 -0.04603385 -0.03593027 0.133792 -0.0468986 -0.03755956 0.1326211 -0.04313021 -0.03383207 0.1337343 -0.04313021 0.02863204 0.1337343 -0.03958594 0.02743703 0.1372678 -0.03431391 0.02679985 0.1425238 -0.03431391 -0.032 0.1425238 -0.0390852 -0.03252035 0.137767 -0.05130273 0.02922093 0.1140468 -0.05130273 -0.02922093 0.1140468 0.05279994 0.0317341 0.1035228 0.05279994 0.03211307 0.1033861 0.05279994 0.03119874 0.103639 0.05279994 -0.03211307 0.1033861 0.05279994 -0.03163373 0.1035509 0.05279994 -0.03142088 0.1036003 0.05279994 -0.03077971 0.1036807 0.05279994 -0.03048259 0.1036889 0.05279994 0.03048259 0.1036889 0.0322588 0.03395056 0.1273599 0.04787027 -0.03048259 0.1142603 0.03102821 0.03298527 0.1283925 0.04717886 -0.03129041 0.1148406 0.02611464 0.03017109 0.1325154 0.04157698 -0.03671652 0.1195411 0.0352109 -0.04112488 0.1248828 0.03840333 0.03910624 0.1222041 0.04258728 0.03586333 0.1186934 0.04787027 0.03048259 0.1142603 0.03064918 -0.03791302 0.1287106 0.02578747 -0.03523075 0.13279 0.0205115 0.02840197 0.1372169 0.02026391 -0.03355211 0.1374247 0.01456207 0.02779996 0.1422091 0.01456207 -0.03299999 0.1422091 -0.02843612 0.05777633 0.1022255 0.02372968 0.05777633 0.1022255 0.02565425 0.05777633 0.1018446 0.02510929 0.05777633 0.1020546 0.02454245 0.05777633 0.1021724 -0.02843612 -0.05777633 0.1053854 0.02413386 -0.05777633 0.1053854 0.02482867 -0.05777633 0.1053367 0.02515876 -0.05777633 0.1052713 0.02565425 -0.05777633 0.1050993 0.02950942 0.04980796 0.1159099 0.03493005 0.0447756 0.1209424 0.03450143 0.04433465 0.1213834 0.027888 0.03875899 0.126959 -0.04309391 0.03875899 0.126959 -0.04180788 0.04279363 0.1229244 0.02372968 0.05373442 0.1119835 0.0340324 0.04391473 0.1218033 -0.03132373 0.05373442 0.1119835 -0.03372383 0.0520873 0.1136305 -0.03935444 0.04693168 0.1187863 -0.03603756 0.05032104 0.1153969 0.02141654 -0.04130846 0.1306309 0.02627813 -0.04312217 0.1278724 -0.04186517 -0.04312217 0.1278724 0.01869189 -0.04074847 0.1321766 -0.04213196 -0.04270309 0.1283964 -0.04214227 -0.0426861 0.1284188 -0.02880704 -0.03979986 0.137 0.0101912 -0.03979986 0.137 -0.03357815 -0.04013586 0.1339297 0.01589304 -0.04017341 0.1337648 -0.03630363 -0.04074865 0.1321759 -0.03849244 -0.04124081 0.1307675 0.03083997 -0.0463339 0.1240445 0.02413386 -0.0545476 0.1142559 -0.03077238 -0.0545476 0.1142559 -0.03345811 -0.0527383 0.1164122 -0.03603756 -0.05078071 0.1187452 0.02725481 -0.05253809 0.1166508 0.03204089 -0.04730248 0.1228905 0.03274393 -0.04804611 0.1220043 -0.0392434 -0.04753428 0.122614 -0.04166162 -0.0435779 0.1273291 0.05052959 0.03048259 0.1112722 0.05052959 -0.03048259 0.1112722 0.05222016 0.03048259 0.1076468 0.05222016 -0.03048259 0.1076468 0.0101912 0.0345999 0.137 -0.002073884 0.0345999 0.1472917 -0.02880698 0.0345999 0.137 -0.02380019 0.0345999 0.1419916 -0.03450179 0.03511399 0.1333354 0.016649 0.03511554 0.1333358 0.01614058 0.03500694 0.1336243 -0.03407907 0.03501117 0.1336075 -0.03979229 0.03654927 0.1299309 0.02264606 0.03655272 0.1299331 0.02174371 0.03620332 0.1304452 -0.0390405 0.03621912 0.1304147 -0.04328066 0.03808099 0.1276863 -0.04319638 0.03841304 0.1273173 0.02665728 0.03810626 0.1276572 0.04811573 -0.04414701 0.1018236 0.03746843 -0.05348086 0.1052091 0.03996115 -0.05164474 0.1068009 0.04142814 -0.05047541 0.1059055 0.03526777 -0.05495697 0.1039295 0.04200541 -0.04992926 0.1055532 0.03526777 0.05495697 0.1005687 0.04056763 0.05116975 0.1033235 0.04202741 0.04995065 0.1042101 0.04311913 0.04903888 0.1048734 0.04811573 0.04414701 0.1018236 -0.04092597 -0.05088359 0.1137315 -0.03799664 -0.05310678 0.1113985 -0.03494679 -0.05516153 0.1092422 -0.03278195 -0.05647498 0.1070901 -0.03248196 -0.05664789 0.106448 -0.03351402 -0.05604368 0.1072357 -0.03235352 -0.05672138 0.1059862 -0.03229343 -0.05675572 0.1053854 -0.03471887 -0.05530536 0.109086 -0.03383797 -0.05584859 0.1083765 -0.03314352 -0.05626344 0.1076243 -0.03325539 0.05619746 0.104604 -0.03351771 0.0560413 0.1048998 -0.03394788 0.05578196 0.1043468 -0.03229343 0.05675572 0.1022255 -0.03444916 0.05547374 0.1057286 -0.0355727 0.05475986 0.1064682 -0.03829842 0.05288952 0.1081151 -0.04092597 0.05088359 0.1098815 -0.03236913 0.05671244 0.1028998 -0.03258377 0.0565896 0.1035423 -0.03275114 0.05649292 0.1038758 -0.03230625 0.05674839 0.1025018 -0.03057163 -0.05483901 0.1138967 -0.02979606 -0.05593919 0.1122649 -0.02860212 -0.05755811 0.1078293 -0.02886629 -0.0572077 0.109306 0.02413386 -0.05694407 0.1101053 -0.0290721 -0.05693084 0.1101007 -0.02918452 -0.05677956 0.1105349 -0.02848905 -0.05770695 0.1067672 -0.02883905 0.057244 0.1060213 -0.02869153 0.05743986 0.1052542 0.02372968 0.0567258 0.1075065 -0.02850282 0.05768889 0.1037764 -0.02844727 0.05776154 0.102861 -0.03033429 0.05517995 0.1102827 -0.02951413 0.05632954 0.1083765 -0.02928316 0.05664575 0.1076959 -0.02923184 0.05671483 0.1075025 -0.03389471 0.02978479 0.1421033 -0.03270107 0.03231537 0.1409059 -0.03091442 0.03400611 0.1391139 -0.03599596 0.03410536 0.1353074 -0.04081386 0.03516089 0.1316395 -0.04335612 0.02904057 0.1335014 -0.04408764 0.03062099 0.1325588 -0.04370433 0.03153377 0.1326403 -0.04535579 0.03494608 0.1297174 -0.0456385 0.03647041 0.1286519 -0.04495096 0.03703504 0.1284528 -0.04438406 0.0312609 0.1321769 -0.04462426 0.03198266 0.1317155 -0.04241919 0.03354823 0.1324056 -0.03892743 0.03007358 0.1372559 -0.04314661 0.02866071 0.133718 -0.04503506 0.03321582 0.1309269 -0.04494017 0.0370419 0.128448 -0.03768026 0.03238999 0.1365749 -0.03156054 -0.03875494 0.1397619 -0.03357625 -0.03589987 0.1417837 -0.04084575 -0.03970581 0.1323781 -0.04314661 -0.0338608 0.133718 -0.03809404 -0.03602653 0.1375492 -0.04330313 -0.03414273 0.1335574 -0.04373908 -0.03505337 0.1330188 -0.04482537 -0.03770828 0.1313888 -0.04422897 -0.03607672 0.1324134 -0.04279333 -0.03722721 0.1331208 -0.04486638 -0.04143518 0.1291161 -0.04555714 -0.04096508 0.1291674 -0.04493963 -0.03821718 0.1310416 -0.04245394 -0.04258865 0.1285353 -0.04311174 -0.04234558 0.1287515 -0.04481512 -0.04147005 0.1291123 -0.0421639 -0.04267954 0.1284273 -0.03611367 -0.03876507 0.1361694 -0.05129623 0.02982223 0.1145659 -0.05050379 0.03536212 0.1193485 -0.05035006 0.03643596 0.1202756 -0.04894691 0.04042047 0.117409 -0.04849421 0.04118388 0.1168597 -0.04553651 0.04617232 0.1132709 -0.04525977 0.04645526 0.1130674 -0.05049669 -0.0358662 0.1197836 -0.04919636 -0.03983587 0.1232108 -0.04902642 -0.04023814 0.1228587 -0.05055671 -0.03537136 0.1193565 -0.04874342 -0.04087167 0.1223154 -0.04853761 -0.04120874 0.1220265 -0.04527992 -0.04647475 0.1175115 -0.04538226 -0.04637116 0.1176003 -0.04570192 -0.03652417 0.1307811 -0.04747051 -0.03901177 0.1281318 -0.04756319 -0.0390349 0.1279706 -0.04315149 0.02865099 0.133713 -0.04315149 -0.03385102 0.133713 -0.04335868 -0.03403913 0.133504 -0.04342973 0.02890473 0.1334311 -0.04468864 -0.03536111 0.1320466 -0.0449357 0.03043085 0.1317518 -0.04611361 0.03184425 0.1302204 -0.04912388 0.03567963 0.1248356 -0.0487414 0.03538316 0.125702 -0.05031585 -0.03543454 0.1212441 -0.04961609 0.03594619 0.1235824 -0.05035006 0.03544974 0.1212618 -0.0502994 0.03558987 0.1214479 -0.05025196 0.03568905 0.1216177 -0.05007064 0.0359041 0.1222314 -0.04979825 0.0359801 0.1230682 -0.04833859 0.03504395 0.1265376 -0.04816627 0.03487634 0.1268746 -0.0478127 0.03438663 0.1275324 -0.0477215 -0.03907424 0.1276956 -0.0475434 0.03398364 0.1279584 -0.04832309 -0.03909832 0.1265684 -0.04850387 -0.03905421 0.1262032 -0.04886591 -0.03884357 0.1254287 -0.0489664 -0.0387417 0.1252019 -0.04919636 -0.03838503 0.1246618 -0.05049669 -0.03495776 0.120692 -0.05129623 0.02974009 0.1146481 -0.05035108 0.0354442 0.1212555 -0.04763925 -0.04155451 0.1258822 -0.04758214 -0.04158574 0.1259614 -0.04526644 -0.04259872 0.1273844 -0.04642421 -0.04192394 0.1273351 -0.04879003 -0.04057854 0.1240618 -0.04746979 -0.04212766 0.1250081 -0.04860597 -0.04081279 0.1243987 -0.04792714 -0.04139661 0.1254815 -0.04511731 -0.04227596 0.1280414 -0.04551959 -0.04212838 0.1279354 -0.0459401 -0.04197394 0.1278245 -0.04322248 -0.04264962 0.1283492 -0.04248952 -0.04268771 0.1284046 -0.04216647 -0.04268658 0.1284181 -0.04780799 -0.041462 0.1256473 -0.04493516 -0.04314833 0.1267825 -0.04467409 -0.04364609 0.1262195 -0.04717624 -0.04268997 0.1244482 -0.04169416 -0.04794603 0.1213476 -0.0438314 -0.04754108 0.1196019 -0.03948765 -0.05132859 0.1156055 -0.038773 -0.05154997 0.1165369 -0.03786486 -0.05129462 0.1172701 -0.03597724 -0.05360049 0.1141813 -0.03307247 -0.05549496 0.1120045 -0.03284323 -0.05568045 0.1117209 -0.03196179 -0.05637544 0.1104601 -0.03127139 -0.05690032 0.1091586 -0.03091353 -0.05716592 0.1082486 -0.03061705 -0.05738252 0.1071653 -0.03049033 -0.05747407 0.1063907 -0.03043121 -0.05751687 0.1053854 -0.04623359 0.03742551 0.1275444 -0.04491984 0.03796339 0.1273701 -0.04598426 0.03788697 0.1271647 -0.04652369 0.03775215 0.1269771 -0.04728537 0.03790527 0.1261345 -0.04802292 0.03799408 0.1251822 -0.04663121 0.03850895 0.1259827 -0.04586631 0.03828305 0.1267554 -0.04725664 0.03789955 0.1261662 -0.04568874 0.03857553 0.1262428 -0.04932302 0.03785049 0.1229361 -0.04984432 0.0374552 0.1217749 -0.04742574 0.04213535 0.1197935 -0.05017971 0.0369215 0.1208559 -0.05026382 0.03671288 0.1205852 -0.04489433 0.04297691 0.1217492 -0.04897135 0.03797185 0.1236145 -0.0491324 0.0379163 0.1233035 -0.04186397 0.04751372 0.1174377 -0.04402494 0.04724836 0.1155099 -0.03789216 0.05103403 0.1138041 -0.03881317 0.05138808 0.1130131 -0.0395143 0.05122071 0.111974 -0.03630328 0.05324393 0.111225 -0.03370428 0.0549736 0.1095581 -0.03043121 0.05751687 0.1022255 -0.0304436 0.05750787 0.1026875 -0.03050589 0.05746299 0.1033539 -0.03071755 0.05730938 0.1044334 -0.03088295 0.05718839 0.1049968 -0.03138256 0.05681705 0.1062381 -0.03164315 0.05661988 0.1067486 -0.03257262 0.05589663 0.1082059 0.05256801 -0.03497642 0.1030874 0.05220091 -0.03645902 0.1029123 0.0516023 -0.03853195 0.1026605 0.05187338 -0.037781 0.1027563 0.0481522 -0.04410696 0.1018306 0.04848796 -0.04372829 0.1018955 0.05027061 -0.04125875 0.1022844 0.05061882 -0.0405457 0.1023828 0.04938817 -0.034487 0.1121425 0.04924303 -0.03398633 0.1124943 0.05117887 -0.03328466 0.1098269 0.04901379 -0.03330683 0.1129065 0.05107146 -0.03274905 0.1101543 0.04825311 -0.03134948 0.1139029 0.05071204 -0.03118598 0.1109677 0.05226773 -0.03099089 0.1074704 0.05236083 -0.03210681 0.106985 0.05238842 -0.03248459 0.1067852 0.05226826 -0.03334188 0.1062144 0.04970574 -0.0355829 0.1113727 0.05123919 -0.03449594 0.1088708 0.05200344 -0.03395432 0.107624 0.04814553 -0.04411447 0.1018483 0.04841852 -0.04380643 0.1020787 0.04987257 -0.0417937 0.1034651 0.04813855 -0.04412192 0.101866 0.04834657 -0.04388236 0.1022619 0.04936403 -0.04225498 0.1046347 0.04961788 -0.04143708 0.1056239 0.05097454 -0.03954035 0.1048309 0.05120283 -0.03891021 0.1051848 0.05007237 -0.0377596 0.1095414 0.0517984 -0.03650748 0.1064391 0.05006515 -0.03815567 0.1091517 0.05003529 -0.03981816 0.1075161 0.04995352 -0.04035615 0.1069315 0.05004286 -0.03758507 0.1096881 0.03065121 -0.05700874 0.1045336 0.03145664 -0.056804 0.1044375 0.03217154 -0.05654025 0.1043473 0.03522074 -0.05498701 0.1039363 0.03488838 -0.05519372 0.1039834 0.02859157 -0.05753231 0.1047793 0.0431661 -0.04099214 0.1172528 0.04913949 -0.03481853 0.1123751 0.03753006 -0.0443511 0.1222203 0.03667867 -0.04297286 0.1234142 0.04368412 -0.04491633 0.1140317 0.03946745 -0.0483545 0.1172034 0.03929919 -0.04793673 0.1179324 0.038522 -0.0462616 0.120237 0.03789222 -0.04504859 0.1214963 0.04308849 -0.04816651 0.1101427 0.04008108 -0.05015802 0.1134037 0.03969299 -0.04891514 0.1162249 0.03996527 -0.05164164 0.1068347 0.04018265 -0.05117928 0.1098672 0.04019266 -0.05105656 0.1104144 0.04012858 -0.0505414 0.1121283 0.02713006 -0.05732113 0.1082895 0.02967697 -0.05711019 0.1070574 0.03522861 -0.05498182 0.103954 0.03523659 -0.05497682 0.1039716 0.03495275 -0.05515342 0.104125 0.03501617 -0.05511164 0.1042667 0.03269433 -0.05627351 0.1054518 0.03317147 -0.05590373 0.1065472 0.03209716 -0.05649435 0.1057834 0.0326749 -0.05602961 0.1071129 0.03196758 -0.05610126 0.1078608 0.0306468 -0.05623471 0.1092572 0.02850884 -0.05598551 0.1112694 0.02609932 -0.05721676 0.1090459 0.02544641 -0.05713582 0.1094457 0.02826017 -0.05592077 0.1114697 0.02696365 -0.05558323 0.1125143 0.02600669 -0.05527395 0.1131734 0.03601902 -0.05047082 0.1177985 0.03611814 -0.05052947 0.1176214 0.03110003 -0.0542066 0.1134456 0.03995603 -0.05164867 0.1068344 0.03933125 -0.05183786 0.1098392 0.03460729 -0.05453044 0.1095166 0.03918617 -0.05183482 0.1103808 0.03695929 -0.05102777 0.1161179 0.03820711 -0.05160665 0.1133357 0.0385347 -0.05168288 0.1123471 0.03446227 -0.04939699 0.1200618 0.0481522 0.04410696 0.1018306 0.05009996 0.04153782 0.102243 0.05220079 0.03645896 0.1029123 0.05187124 0.03778737 0.1027555 0.0514816 0.03883582 0.102621 0.05061018 0.04054003 0.1023826 0.0525673 0.03498154 0.1030868 0.04814553 0.04411447 0.1018483 0.04813855 0.04412192 0.101866 0.04973286 0.04202193 0.1033169 0.04927498 0.04244387 0.1043822 0.05087357 0.03979378 0.1046853 0.04961746 0.04143589 0.1056246 0.0499112 0.04057204 0.1066895 0.05120086 0.03891563 0.1051818 0.05003488 0.03982281 0.1075112 0.0517975 0.03651207 0.1064368 0.05244404 0.03335398 0.1062422 0.05191928 0.0339424 0.1075966 0.05139458 0.03453075 0.108951 0.05006539 0.03815573 0.1091518 0.05007261 0.03776341 0.1095378 0.04970574 0.0355829 0.1113727 0.05240094 0.03266441 0.106683 0.05122727 0.03354102 0.1096603 0.05233001 0.03171676 0.1071714 0.05095267 0.0321995 0.1104633 0.0493974 0.03449314 0.1121537 0.04934644 0.03431308 0.1122828 0.04876118 0.03261411 0.1132906 0.02862632 0.05752635 0.101491 0.03065013 0.05700558 0.1012272 0.03522253 0.05498582 0.1005757 0.03256201 0.05638116 0.1009694 0.03152292 0.05678099 0.1011136 0.04319083 0.04886972 0.1059392 0.04436475 0.04701495 0.1092699 0.04331934 0.04855602 0.1078917 0.04324764 0.04796242 0.110002 0.04251432 0.04588663 0.1148685 0.04274505 0.04637181 0.1140457 0.04485356 0.04383409 0.1131448 0.04317849 0.04756873 0.11129 0.04321831 0.04771864 0.1108688 0.04203766 0.04488444 0.1165678 0.044245 0.04001504 0.1163721 0.04175853 0.0443564 0.1173099 0.03901308 0.03988939 0.1216498 0.03957146 0.04069811 0.1210497 0.04076617 0.04261672 0.1193519 0.04090321 0.04285669 0.1190702 0.043123 0.04903537 0.1049082 0.02518481 0.05697536 0.1067606 0.0273422 0.05725848 0.1051869 0.02890366 0.05574429 0.1082786 0.02729022 0.05525302 0.1097043 0.02625328 0.05713027 0.1060672 0.02705651 0.0551638 0.1098733 0.02575284 0.05466538 0.1108162 0.03523141 0.05498015 0.1005934 0.0330832 0.05610775 0.1019827 0.03223991 0.05643302 0.1024954 0.03524005 0.05497467 0.1006111 0.03356188 0.05574464 0.1029886 0.03288626 0.05591553 0.1038589 0.03282845 0.05591976 0.1039271 0.02985846 0.057047 0.103861 0.0300523 0.05592107 0.1070802 0.030954 0.05606007 0.1061393 0.03672719 0.04616534 0.119262 0.03274279 0.05146867 0.1134922 0.03794556 0.04702025 0.1177703 0.03838002 0.04732519 0.1172384 0.03578186 0.05227226 0.1104627 0.04033374 0.04849094 0.1139987 0.03888714 0.0476529 0.1165022 0.04209882 0.04914349 0.1094316 0.04168075 0.04907006 0.1108412 0.04152822 0.04901945 0.1112599 0.040398 0.04851931 0.1138516 0.03844338 0.05217069 0.1070038 0.0425592 0.04922419 0.1078793 0.04311448 0.04904294 0.1049081 0.01186376 0.03408235 0.1389935 0.01328194 0.03260827 0.1406834 0.01422929 0.03040218 0.1418126 0.02313512 0.03525072 0.1316077 0.02796143 0.03716307 0.1283876 0.02917236 0.03784453 0.1275753 0.02917736 0.03593796 0.1287664 0.03037708 0.03668898 0.1278555 0.03022325 0.03451323 0.1287681 0.03142774 0.03536361 0.1277822 0.02440023 0.03383719 0.13238 0.02542442 0.0320912 0.132692 0.01765209 0.0341975 0.1352275 0.01898342 0.03269755 0.136447 0.01997596 0.03068584 0.1371375 0.03652161 0.0418446 0.1226999 0.03705126 0.04244881 0.1221604 0.03753519 0.04307615 0.1215919 0.03900188 0.04469126 0.1196967 0.04311883 0.04903924 0.1049081 0.04295164 0.04890424 0.1078882 0.04249835 0.04845041 0.1108766 0.04240942 0.0483585 0.1113016 0.04165297 0.04756247 0.1141048 0.04064232 0.04647779 0.116719 0.04027009 0.0460745 0.1175011 0.01397657 -0.03639996 0.1415112 0.01237654 -0.03888893 0.1396045 0.01945215 -0.03656834 0.1371629 0.01788407 -0.03894352 0.13585 0.02800965 -0.04178673 0.1288152 0.02325761 -0.03993314 0.1321349 0.02952855 -0.03997629 0.1291065 0.02479839 -0.03779077 0.132896 0.03409039 -0.04318827 0.1252788 0.03257143 -0.04499852 0.1249874 0.03382951 -0.04624062 0.1236028 0.03452885 -0.04707378 0.1224251 0.03543138 -0.04474544 0.1237837 0.03611791 -0.04584687 0.1224969 0.03541588 -0.04659038 0.1226344 0.03672295 -0.04814589 0.1204645 0.03782516 -0.04942744 0.1180307 0.03996062 -0.0516451 0.1068345 0.03976982 -0.05152541 0.1098561 0.03920412 -0.05096149 0.1134006 0.03970742 -0.05146896 0.1104024 0.03844726 -0.05013293 0.1162669 -0.04566252 -0.04124265 0.1287978 -0.05041342 0.03595125 0.1207772 -0.04876077 0.03691041 0.1251135 -0.04942876 0.03700119 0.1236533 -0.05034667 0.03616142 0.1210269 -0.05028373 0.03631681 0.121249 -0.05004143 0.03669822 0.1220244 -0.04967486 0.03694719 0.1230419 -0.04770296 0.03654605 0.126968 -0.04824393 0.03675109 0.1260715 -0.0474587 0.03628826 0.1274343 -0.04695683 0.03553617 0.1283407 -0.04314911 0.02865594 0.1337155 -0.04339361 0.02897268 0.133467 -0.04468727 0.03085023 0.1319916 -0.04565644 0.03255218 0.1306561 -0.04933184 -0.03913837 0.1239643 -0.05055058 -0.03541857 0.1202445 -0.04663461 -0.04110699 0.1280593 -0.04699128 -0.04066175 0.12818 -0.04694032 -0.04072529 0.1281628 -0.04733628 -0.04063999 0.1276822 -0.04724037 -0.03980404 0.1281549 -0.04815769 -0.04042637 0.1263604 -0.04840272 -0.0402956 0.1259202 -0.04889065 -0.03987383 0.124962 -0.04902547 -0.03970003 0.1246733 -0.04665154 -0.04091459 0.1283932 -0.04676038 -0.03999608 0.128803 -0.04664677 -0.04011696 0.1288698 -0.04670727 -0.04006981 0.1288533 -0.04314911 -0.03385597 0.1337155 -0.04447883 -0.0357216 0.1322499 -0.0433312 -0.03409087 0.1335312 -0.04532253 -0.0371297 0.1311439 -0.02489769 -0.03469491 0.1544765 + + + + + + + + + + 0.9950376 0.005755543 -0.09933358 -0.8220834 0 0.5693671 -0.8220867 0 0.5693625 -0.5876519 0 0.809114 -0.5876528 0 0.8091133 -0.5877006 0 0.8090785 -0.1908943 0 0.9816107 -0.1909356 0 0.9816026 -0.1908935 0 0.9816108 -0.1908788 0 0.9816137 0.241673 0 0.9703578 0.2416089 0 0.9703737 0.241629 0 0.9703688 0.2416282 0 0.970369 0.6290388 0 0.7773739 0.6290943 0 0.777329 0.6289438 0 0.7774507 0.9997726 -0.02022182 -0.006787359 0.9982295 0.02757477 -0.05270367 0.9975268 -0.03994768 0.05783313 0.997879 0.05626046 -0.03274643 0.9872372 -0.05694133 0.1487295 0.9962865 -0.005209445 0.08594256 0.9804967 0.01076143 0.1962407 0.9769554 0.002768933 0.2134257 0.959733 -0.001967549 0.280907 0.9463486 -0.01221185 0.3229169 0.9612178 -0.01219707 0.2755206 0.9466413 -0.01510077 0.3219354 0.9291437 -0.01333087 0.3694784 0.9442678 0.006386101 0.3291166 0.9255114 0.01103681 0.378559 0.8949343 -0.005238294 0.4461674 0.881672 0.001561045 0.4718602 0.830527 -0.004730641 0.5569586 0.8268031 0 0.5624915 0.6285328 0 0.7777832 0.6289432 0 0.7774514 0.9981195 0.005761444 -0.06102627 0.9422351 -0.07647776 -0.3261044 0.9697089 0.07555103 -0.2322862 0.9468732 -0.1003799 -0.3055407 0.9768778 -0.01328957 -0.2133852 0.9571335 0.05334639 -0.2846924 0.9547276 0.0244261 -0.2964771 0.9489455 0 -0.31544 0.9489459 0 -0.3154388 0.9513981 -0.00988394 -0.3078051 0.9538764 -0.02332812 -0.2992922 0.9355302 0.06459879 -0.3472899 0.9677565 -0.04159557 -0.2484296 0.9444304 0.106975 -0.3108177 0.9739196 0.01152175 -0.2266007 0.9969094 -0.004838407 -0.07841217 0.9971526 -0.005245685 -0.07522791 0.9968106 -0.005246043 -0.07963043 0.996827 -0.005268275 -0.07942384 0.9931725 0.07735002 0.0873236 0.9995834 0.01745909 0.0229873 0.998165 0.00488317 -0.06035679 0.9994894 0.03057903 0.00927186 0.9984411 0.01225078 -0.05445533 0.9662733 0.002929389 0.2575023 0.9664035 0.002882003 0.2570138 0.9220731 -0.002137005 0.38701 0.9270734 -0.01096642 0.3747196 0.8637771 0.0185908 0.5035311 0.8773838 -0.01295602 0.4796144 0.8028253 0.006625771 0.5961775 0.8107599 0 0.5853788 0.7770649 0 0.6294206 0.9943635 -0.1050298 0.0144959 0.9943593 -0.004568517 0.1059659 0.9660085 0.004306793 0.2584748 0.9663894 0.003311932 0.2570618 0.9658665 0.003312885 0.2590196 0.9657675 0.003332853 0.2593882 0.7770637 0 0.629422 0.6331031 0 0.7740675 0.633098 0 0.7740717 0.2881883 0 0.9575738 -0.100682 0 0.9949188 -0.1006763 0 0.9949193 -0.4742118 0 0.8804108 -0.4742131 0 0.8804102 -0.7753536 0 0.6315275 -0.7660384 0 0.6427949 -0.7660368 0 0.6427969 -0.7660835 0 0.6427412 -0.7660803 -4.803e-6 0.642745 -0.7660464 0 0.6427853 -0.7660447 0 0.6427873 -0.7660591 0 0.6427702 -0.7660469 -7.05027e-6 0.6427848 -0.7660542 -7.21229e-6 0.6427761 -0.7660405 -1.86057e-5 0.6427925 -0.7660565 -2.38484e-5 0.6427733 -0.7660632 -1.05338e-5 0.6427654 -0.7660383 -3.00092e-7 0.6427951 -0.7660412 0 0.6427915 -0.766047 0 0.6427847 -0.7660425 3.54029e-5 0.64279 -0.7660568 2.00809e-5 0.642773 -0.76604 -3.66928e-5 0.6427929 -0.7660342 2.89577e-6 0.6427999 -0.7660572 4.66972e-5 0.6427725 -0.7660565 -5.20398e-5 0.6427733 -0.766067 -4.29326e-5 0.6427608 -0.7660683 -2.69593e-5 0.6427593 -0.7660477 -6.1849e-5 0.6427837 -0.7660654 6.399e-6 0.6427626 -0.7660593 5.07097e-6 0.6427699 -0.7060216 0 0.7081903 -0.7060357 1.362e-6 0.7081763 -0.7060304 1.46356e-6 0.7081816 -0.7060278 6.96131e-7 0.7081843 -0.7060315 7.3101e-7 0.7081806 -0.7060284 0 0.7081835 -1 0 0 1 -7.73118e-6 0 1 0 0 1 1.48684e-7 0 1 -1.40001e-5 0 1 -9.48068e-6 0 1 6.41107e-6 0 0.642781 6.68336e-6 0.7660501 0.6427839 0 0.7660476 0.6427921 0 0.7660408 0.6427906 0 0.766042 0.6427813 -8.39864e-7 0.7660499 0.6427909 1.71853e-6 0.7660419 0.6427804 -2.00508e-6 0.7660506 0.6428084 1.08326e-5 0.766027 0.6428179 1.17191e-5 0.7660191 0.6427835 -6.05333e-7 0.766048 0.6427851 -1.31419e-5 0.7660466 0.6427838 0 0.7660476 0.6427849 0 0.7660468 0.6427909 0 0.7660417 0.6427854 0 0.7660464 0.6427874 -4.04328e-7 0.7660446 0.6427823 -3.68401e-7 0.766049 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -3.53641e-6 0.7071061 0.7071076 9.17293e-5 0.7071503 0.7070632 6.80344e-6 0.7071051 0.7071085 -7.37263e-5 0.7070677 0.707146 1.59623e-5 0.7071109 0.7071027 0 0.7071087 0.7071049 -1.01766e-5 0.7070869 0.7071267 -2.00941e-6 0.7071094 0.7071042 -2.86448e-7 0.7071117 0.7071019 0 0.7071182 0.7070955 -0.04731392 -0.8077765 0.5875871 0 -0.8338955 0.5519226 0.00895965 -0.9308384 0.3653215 -0.01122385 -0.7842248 0.6203753 1.37794e-5 -0.8878681 0.4600984 -0.470973 -0.04199963 0.8811474 0 -0.9999908 0.004307448 1.52196e-5 -0.937154 0.3489159 0.005375444 -0.9907463 0.1356201 -0.01499783 -0.9317055 0.362905 2.76346e-4 -0.9934419 0.1143382 0 -0.7660678 0.6427597 -7.18207e-7 -0.7660382 0.642795 1.19586e-6 -0.7660496 0.6427815 7.25874e-6 -0.7660479 0.6427835 -4.90581e-5 -0.7660273 0.6428081 1.05584e-6 -0.766047 0.6427847 0 -0.7660469 0.6427847 1.27175e-6 -0.7660481 0.6427834 0 -0.7660443 0.6427878 1.65648e-5 -0.7660512 0.6427796 0.9894416 0 0.144932 0.9063109 0 0.4226117 0.7470157 0 0.6648065 0 1 -3.55509e-6 0 1 8.25919e-6 0 1 -7.92037e-6 0 1 1.75195e-6 0 1 5.74236e-6 0 1 -2.07648e-5 0 1 2.74355e-6 0 1 -4.96954e-6 0 1 1.66653e-7 0 1 9.79065e-7 0 0.7351182 0.6779389 -0.01388692 0.7450162 0.666902 0.002143323 0.8302304 0.5574163 0 0.9930288 0.1178725 2.05267e-5 0.9930672 0.1175491 -2.03608e-5 0.9378943 0.3469215 1.65784e-5 0.9382541 0.345947 1.66442e-5 0.9378817 0.3469554 3.45041e-5 0.9382691 0.3459064 -3.26849e-5 0.8313015 0.5558217 -0.006819128 0.734613 0.6784521 -0.1064887 0.7330369 0.6718015 0 -1 2.28222e-5 0 -1 -1.64751e-6 0 -1 -3.84772e-6 0 -1 1.49258e-6 0 -1 -9.46393e-7 0.6837441 -0.7296651 -0.009104907 0.6213081 -0.7835603 -0.003104388 0.5943258 -0.8042235 -0.00121653 0.5578485 -0.8299428 0 0.5931819 -0.8050683 5.83094e-4 0.6917701 -0.7221176 5.87191e-4 0.6866042 -0.7270315 0 0.6995885 0.714546 0 0.6917694 0.7221181 -7.50195e-4 0.6417165 0.766942 1.91621e-4 0.5931823 0.8050682 0 0.5826107 0.8127508 -0.001129984 0.6417682 0.7668988 1.91563e-4 -0.6045322 -0.7965809 0 -0.5596345 -0.8287374 -0.001883804 -0.5624385 -0.8268392 0 -0.5355077 -0.8445215 -0.003886878 -0.5274299 -0.8495863 -0.004575073 -0.5266605 -0.8500671 -0.003853559 -0.5084918 -0.8610472 -0.005836427 -0.5079631 -0.8613733 -0.003100872 -0.5113438 -0.8593751 0.001415073 -0.5107244 -0.8597217 -0.006273031 -0.5052831 -0.8629528 -0.001296699 -0.5075222 -0.8616292 -0.004045188 -0.6067997 0.7948548 0 -0.5127059 0.8585371 -0.006845593 -0.5132713 0.8581784 -0.009085714 -0.5124404 0.8586938 -0.007057368 -0.5102149 0.8600398 -0.003548026 -0.5078989 0.8614165 -6.97523e-4 -0.5406818 0.8411763 -0.009245395 -0.5203518 0.8539493 0.002158701 -0.5138568 0.8578721 -0.002578437 -0.5072686 0.8617881 0 -0.5624383 0.8268383 -0.001241207 -0.5358971 0.8442743 -0.003922283 -0.5664532 0.8240925 -0.001574158 0 -0.9989562 0.04568046 0.00357455 -0.9848011 0.1736493 0.006622254 -0.9908211 0.1350178 0.001812696 -0.9739902 0.2265831 0 -0.7767144 0.629853 9.11382e-4 -0.831941 0.5548635 0.008593618 -0.9008186 0.4341108 0.001574039 -0.8660252 0.4999978 -3.52559e-4 -0.9459331 0.3243619 -3.52621e-4 -0.9458741 0.3245338 7.51509e-4 0.902967 0.4297094 -7.01715e-4 0.8493903 0.5277649 -6.97943e-4 0.7933712 0.6087378 0.006779491 0.8480839 0.5298186 0 0.759152 0.6509134 0 0.9914445 0.1305291 0.008615255 0.9996966 0.02307826 0.004618167 0.9964677 0.08385163 8.65444e-4 0.98533 0.1706578 -1.58309e-4 0.9678329 0.251594 -1.57066e-4 0.9238806 0.3826807 0.0106765 0.9673413 0.2532529 0.004094362 0.9399268 0.3413516 -0.06360059 0.9959341 0.06379902 -0.1559113 0.9804605 0.1199534 -0.1751464 0.9722471 0.1551105 -0.4266133 0.8012214 0.4195779 -0.3796803 0.8651333 0.3276998 -0.3363991 0.9144563 0.2249564 -0.392855 0.8314783 0.3928217 -0.2526634 0.93187 0.2603455 -0.2527253 0.9318348 0.2604112 -0.6483615 0.3900149 0.653847 -0.5989162 0.5440149 0.5876625 -0.5613936 0.6615862 0.4971327 -0.5911337 0.555547 0.5847466 -0.5087574 0.6908396 0.5137185 -0.5086797 0.6909514 0.5136452 -0.725552 0.07770854 0.6837658 -0.6926415 0.1950972 0.6943953 -0.706067 0.00610274 0.7081187 -0.7255189 0.07782161 0.6837881 -0.7258061 0.07667714 0.6836126 -0.6979455 0.206068 0.685863 -0.6979181 0.2061711 0.6858599 -0.6979379 0.2061142 0.685857 -0.680009 0.2819172 0.6768386 -0.6802427 0.2809128 0.6770213 -0.6747004 0.3023684 0.6733148 -0.648367 0.3899897 0.6538566 -0.122294 0.8363899 0.5343183 -0.04342037 0.7918171 0.6092131 -0.7051614 0.004644274 0.7090317 -0.6659364 0.1700938 0.7263587 -0.6446383 0.06508815 0.761712 -0.6551575 0.1371848 0.7429327 -0.4836565 0.4025048 0.7772171 -0.6141954 0.2772271 0.7388567 -0.6142191 0.2772039 0.7388457 -0.1771982 0.5119812 0.8405214 -0.2637505 0.5667873 0.780505 -0.127066 0.7103157 0.6923192 -0.08432829 0.6731783 0.7346562 -0.124075 0.7132067 0.6898851 -0.1689853 0.7485148 0.6412251 -0.2992682 0.5964178 0.7447983 -0.2829875 0.6314035 0.7219749 -0.4800443 0.4503617 0.7528161 -0.4800779 0.4503144 0.7528228 -0.0480163 0.9048722 0.4229665 -0.1532611 0.8871292 0.4353307 -0.2948703 0.7399825 0.6045474 -0.3869117 0.6842326 0.6181627 -0.5067067 0.4842425 0.7132725 -0.5549858 0.4389012 0.7066516 -0.6496239 0.1945256 0.734948 -0.6030995 0.1717051 0.7789663 -0.05572164 0.9743306 0.2181168 -0.197062 0.9411394 0.2746329 -0.3212282 0.8275046 0.4604874 -0.4167806 0.7696944 0.4835953 -0.538283 0.5543092 0.6348171 -0.586485 0.503582 0.634382 -0.6729661 0.1950265 0.7134993 -0.6847487 0.1746059 0.7075536 -0.7206225 -0.2677015 0.6395617 -0.6774943 -0.2915056 0.675297 -0.6800277 -0.2818422 0.676851 -0.6979039 -0.2062738 0.6858434 -0.697927 -0.206126 0.6858644 -0.6979414 -0.2060861 0.6858618 -0.7258644 -0.07615447 0.6836091 -0.7059747 -0.006139397 0.7082105 -0.6926362 -0.1951106 0.6943969 -0.7255523 -0.07770973 0.6837655 -0.7255163 -0.07782137 0.6837909 -0.59668 -0.552914 0.5816005 -0.6440277 -0.4025795 0.6505062 -0.6440669 -0.4024515 0.6505465 -0.359409 -0.887075 0.289695 -0.3928833 -0.8314635 0.3928248 -0.4215705 -0.8091214 0.4093911 -0.4994727 -0.7028509 0.5064855 -0.5843468 -0.5555599 0.5915167 -0.5573503 -0.671431 0.4884065 -0.5573045 -0.6715832 0.4882497 -0.1377313 -0.9807877 0.1381507 -0.09650379 -0.9953146 -0.006000638 -0.1535551 -0.9800594 0.1261129 -0.225322 -0.9484027 0.223075 -0.3050987 -0.9004736 0.3099388 -0.3050812 -0.9004862 0.3099197 -0.5941178 -0.1640812 0.7874653 -0.02952355 -0.8243489 0.5653118 -0.1083369 -0.7851912 0.6097032 -0.4975883 -0.4150392 0.7616748 -0.3489897 -0.5874434 0.7301483 -0.278786 -0.6346229 0.7207859 -0.2382723 -0.701964 0.6711728 -0.2382471 -0.7020047 0.6711392 -0.5940985 -0.1640748 0.787481 -0.622657 -0.244901 0.7431835 -0.5293283 -0.4291081 0.7319002 -0.4795771 -0.3162354 0.8185359 -0.4976261 -0.4149711 0.7616872 -0.6666886 -0.1709187 0.7254744 -0.6437684 -0.05581533 0.7631821 -0.1273173 -0.9311218 0.341764 -0.1196153 -0.9804684 0.1561222 -0.3695542 -0.7626188 0.5308881 -0.3662939 -0.8309144 0.4188202 -0.5602205 -0.4991996 0.661024 -0.5640921 -0.5552803 0.6111169 -0.6764601 -0.1732037 0.7158228 -0.6810945 -0.1950859 0.7057279 -0.3468223 -0.6699903 0.6563745 -0.3345993 -0.7540482 0.5652033 -0.5330846 -0.4309529 0.72808 -0.529796 -0.491948 0.6908715 -0.6595892 -0.1610015 0.7341803 -0.6449754 -0.06160491 0.7617163 -0.03557997 -0.806615 0.5900055 -0.05163502 -0.8032745 0.5933667 -0.1818318 -0.867352 0.4632902 -0.04914379 -0.9075878 0.4169765 -0.04912132 -0.9075886 0.4169775 -0.7096832 0.704521 0 -0.8481008 0.5298349 -1.81099e-4 -0.7121233 0.7020545 1.86004e-4 -0.7118332 0.7023486 1.85989e-4 -0.9896626 0.1434118 9.66504e-4 -0.9408232 0.3388965 -0.001002371 -0.9443995 0.3288002 -4.36006e-4 -0.8539496 0.5203556 4.59167e-4 -0.8539534 0.5203492 4.5921e-4 -0.9937715 0.1114377 0 -0.999828 0.01771342 -0.005500257 -0.9896597 0.1434325 9.66506e-4 -0.8448712 -0.5348267 -0.01237756 -0.9353485 -0.3491603 -0.05665951 -0.4484603 -0.59008 -0.6713339 -0.9310904 -0.3541482 -0.08746349 -0.9443994 -0.3288006 5.0036e-6 -0.8481007 -0.5298351 5.02995e-6 -0.8475921 -0.5306484 5.76574e-5 -0.7096832 -0.704521 0 -0.7089865 -0.7052221 -5.81315e-5 -0.8467468 -0.5319961 5.76479e-5 -0.9465579 -0.3225339 3.58906e-4 -0.9930568 -0.1176353 3.65803e-4 -0.9937715 -0.1114377 0 -0.70639 0 0.7078228 -0.706337 0 0.7078757 -0.7107393 0 0.7034556 -0.7117462 7.51579e-6 0.7024368 -0.7385806 -6.05262e-5 0.6741652 -0.7444176 2.13821e-4 0.6677144 -0.7815247 -1.48572e-4 0.6238744 -0.7934134 2.60639e-4 0.6086832 -0.9018636 -0.007840573 0.4319498 -0.920252 0.002224147 0.3913199 -0.9145559 0.001654624 0.4044562 -0.9067414 9.99958e-4 0.421686 -0.8970443 4.65436e-4 0.4419404 -0.8835666 -9.22451e-6 0.4683056 -0.8460088 2.76062e-5 0.533169 -0.8680078 3.23637e-4 0.4965505 -0.8459222 3.24057e-4 0.5333064 -0.8682215 0.002033591 0.4961727 -0.8323314 -4.7111e-4 0.5542783 -0.9496064 0.00614351 0.3133845 -0.8834015 -0.01148951 0.4684759 -0.8912643 -0.00989902 0.4533764 -0.964733 -7.07932e-4 0.2632297 -0.9155145 -0.005495369 0.4022474 -0.9302163 -0.003309071 0.3669972 -0.942059 -0.002009987 0.3354412 -0.9508472 -0.001230478 0.3096583 -0.9585296 -8.33711e-4 0.2849918 -0.9626063 -7.32414e-4 0.2709035 -0.9999113 0 0.01332229 -0.9888637 -6.87679e-4 0.1488225 -0.9894723 -6.88009e-4 0.1447205 -0.9463517 0.01897042 0.3225814 -0.9931546 -0.001410543 0.1167995 -0.1857454 -0.8189323 0.5429996 -0.2440139 -0.9330472 -0.2643484 -0.9052723 -0.4220222 0.04878127 -0.7694399 -0.6369336 -0.04772883 -0.7161278 -0.6921623 -0.08984637 -0.7758363 -0.6166113 0.1336738 -0.4125004 -0.7741426 0.4801528 -0.4779449 -0.7980849 0.3669186 -0.4568091 -0.881818 0.1171434 -0.02094888 -0.9985585 -0.04941713 -0.2515283 -0.8547366 0.4540474 -0.412625 -0.7741354 0.4800576 -0.002801895 -0.7971953 0.6037151 -0.01956504 -0.8163065 0.5772875 0.01652711 -0.9880759 -0.1530785 -0.2190686 -0.7700795 0.5991548 -0.5577467 -0.7479653 0.3598145 -0.5589547 -0.7410169 0.3721072 -0.7351045 -0.6220563 0.269569 -0.7349585 -0.6221544 0.2697404 -0.1959674 -0.7867724 0.5853085 -0.2045689 -0.7772505 0.595007 -0.5507286 -0.7385768 0.3888472 -0.5738601 -0.7073175 0.4127791 -0.7542067 -0.6322026 0.1774604 -0.744165 -0.6337064 0.2112696 -0.7437621 -0.63443 0.2105151 -0.1657634 -0.7965864 0.5813541 -0.1940647 -0.79074 0.5805768 -0.4707886 -0.7876731 0.3974031 -0.5445362 -0.7508445 0.3737821 -0.7817537 -0.6207879 0.05902183 -0.8137834 -0.566936 0.1278294 -0.8438019 -0.5118998 0.1611123 -0.1309102 -0.8105496 0.570852 -0.1558418 -0.8091655 0.5665374 -0.3739055 -0.8451934 0.3818939 -0.440611 -0.825731 0.3521794 -0.582937 -0.7968334 0.1588749 -0.6682804 -0.7381543 0.09235596 -0.1138525 -0.8194607 0.5617133 -0.120423 -0.8191076 0.5608575 -0.3288889 -0.8723073 0.3618178 -0.3472594 -0.8674157 0.3563719 -0.4989799 -0.8587642 0.1163753 -0.5147927 -0.8474218 0.1298645 -0.5410152 -0.832692 0.1180112 -0.1042214 -0.8219708 0.5599126 -0.110438 -0.8219158 0.5588006 -0.3015235 -0.8832188 0.3591771 -0.3152904 -0.8820084 0.3502187 -0.3093916 -0.878045 0.3651219 -0.4739549 -0.8710828 0.1287698 -0.4689183 -0.8743565 0.1249662 -0.4483854 -0.7623379 0.4666814 -0.4483982 -0.7623393 0.4666669 -0.1362525 -0.8005892 0.5835172 0.1391605 -0.9637869 0.2274845 -0.07567059 -0.9008815 0.4274185 -0.2285599 -0.8503277 0.4740287 -0.08639717 -0.9426856 0.3223034 -0.1950995 -0.9061283 0.3753236 -0.07903409 -0.9932314 -0.08511847 -0.4166826 -0.8931117 0.1694908 -0.4457114 -0.8770841 0.1790669 -0.4018011 -0.906304 0.1310307 -0.4212501 -0.8957202 0.142246 -0.39183 -0.9147549 0.09845215 -0.4036231 -0.9083977 0.1090967 -0.3842516 -0.9206294 0.06922757 -0.3910679 -0.9170824 0.07762801 -0.3799026 -0.924099 0.04141551 -0.3827231 -0.9226824 0.04669255 -0.3775673 -0.9258746 0.01411455 -0.3782538 -0.9255642 0.01596993 -0.1390319 -0.9457015 0.2938007 -0.110511 -0.9667955 0.2304213 -0.1692357 -0.9430513 0.2863799 -0.1070522 -0.9812515 0.1602668 -0.1509177 -0.967682 0.2020285 -0.1168305 -0.9887884 0.09299659 -0.1374419 -0.9830728 0.1211519 -0.1230252 -0.9919133 0.03119111 -0.1288615 -0.9907967 0.04143303 -0.1289726 -0.9916483 0 -0.3783003 -0.925683 0 -0.3782997 -0.9256833 0 -0.1767576 0.7497301 0.6377003 -0.3855319 0.6911093 0.6113371 -0.1831224 0.7023814 0.6878419 -0.1762186 0.7497929 0.6377757 -0.2195627 0.7437573 0.6313614 -0.3039187 0.6237877 0.7200851 -0.1759981 0.7548126 0.6318882 -0.4869804 0.6877328 0.5383992 -0.4208483 0.7573586 0.4992944 -0.4336358 0.7036164 0.5629245 -0.4435907 0.8119252 0.3794796 -0.4204757 0.7577709 0.4989826 -0.3820666 0.7179513 0.5818687 -0.1799457 0.7273772 0.662225 -0.1733879 0.7369654 0.6533136 -0.1733586 0.7371135 0.6531543 -0.1732789 0.7052966 0.6874091 -0.6058809 0.7011612 0.3758742 -0.1694204 0.7240723 0.6685927 -0.7943457 0.5902863 0.1434473 -0.7448493 0.6062608 0.2786527 -0.6684308 0.627992 0.3985303 -0.6683583 0.6280082 0.3986265 -0.8887319 0.453157 0.06931412 -0.9457412 0.323864 -0.02618813 -0.4843431 0.6981061 0.5273135 -0.4196009 0.7629474 0.4917787 -0.4525504 0.6910327 0.5636239 -0.4843766 0.698089 0.5273057 -0.9326875 0.359884 0.0240333 -0.8691435 0.4696153 0.1550841 -0.8301204 0.5530136 0.07124745 -0.8087282 0.58639 0.04588758 -0.7802223 0.5978223 0.1840152 -0.6891933 0.721767 0.06375795 -0.157092 0.7181628 0.6779118 -0.1459521 0.7425648 0.6536785 -0.1330701 0.7337121 0.6663025 -0.1150645 0.7568705 0.6433563 -0.106482 0.7477104 0.6554317 -0.2945604 0.8091087 0.5085051 -0.3349758 0.8118957 0.4781385 -0.3845476 0.7476086 0.5414837 -0.6492922 0.7072594 0.2796496 -0.7026261 0.5913825 0.3957063 -0.8409162 0.5019487 0.2022562 -0.6445122 0.7463873 0.1658617 -0.6661932 0.744627 0.04144138 -0.4909904 0.7967619 0.3522768 -0.5314264 0.7995567 0.2798128 -0.4706969 0.8159435 0.3356797 -0.3081423 0.797225 0.5191154 -0.09032613 0.7608835 0.6425712 -0.09912073 0.7875093 0.6082798 -0.2772606 0.8236284 0.4947352 -0.2772861 0.8236356 0.494709 -0.3147946 0.8666048 0.3871702 -0.4376751 0.8443528 0.309045 -0.4375874 0.8443544 0.3091651 -0.5064384 0.8520588 0.1323476 -0.5629234 0.8207011 0.09781104 -0.4978858 0.8540196 0.150865 -0.4946667 0.860206 0.1238978 -0.3196989 0.8563593 0.405514 -0.319278 0.8634916 0.3904407 -0.1110548 0.7755442 0.6214483 -0.1111407 0.778999 0.6170967 -0.2558186 0.966664 0.01084923 -0.4178792 0.9084898 0.004854321 -0.2557511 0.9666465 0.01363396 -0.0926519 0.9870586 0.1308853 -0.08154886 0.9935458 0.07884418 -0.08820205 0.9940177 0.06441444 -0.08475023 0.9961684 0.02158647 -0.08605527 0.9961316 0.01779085 -0.4178532 0.9085018 0.004829108 -0.4188433 0.9079007 0.01693385 -0.4186551 0.9079661 0.01804447 -0.422156 0.905866 0.03451204 -0.4219585 0.9058787 0.03653466 -0.427173 0.902789 0.04995328 -0.427725 0.902327 0.05345571 -0.4344573 0.8982118 0.06680333 -0.434961 0.8975611 0.07206451 -0.4430244 0.8926413 0.08319258 -0.445645 0.8906973 0.08977133 -0.2550117 0.9668565 0.01255083 -0.257202 0.9655352 0.03986221 -0.2541607 0.9658818 0.04974687 -0.2607994 0.9619957 0.08092081 -0.2548099 0.961615 0.101827 -0.2621876 0.9574444 0.1206571 -0.2629818 0.9531973 0.1491832 -0.2698633 0.9490464 0.1627417 -0.2653141 0.9422821 0.2042379 -0.2702013 0.9394099 0.2109506 -0.281773 0.9250176 0.2548462 -0.1640791 0.8645966 0.4749221 -0.0998336 0.9098008 0.4028598 -0.09055149 0.9371325 0.3370209 -0.08029049 0.9430158 0.3229163 -0.0995509 0.9599009 0.2620685 -0.08670431 0.967671 0.2368441 -0.07656896 0.9772716 0.1976804 -0.1061271 0.9665752 0.2333872 -0.07804083 0.9837877 0.1614669 -0.088229 0.8606927 0.5014218 -0.08285498 0.902319 0.4230315 -0.2859458 0.903137 0.3202789 -0.2851627 0.9228914 0.2587546 -0.4581751 0.8818158 0.1116988 -0.4557093 0.8843238 0.1014917 -0.103676 0.7803617 0.6166742 -0.1086053 0.8480036 0.5187435 -0.3087788 0.8636485 0.3984556 -0.2975044 0.8958409 0.3300912 -0.4797567 0.8663195 0.1390103 -0.4745283 0.8712209 0.1256867 -0.4178675 0.908508 0 -0.3782998 0.9256829 -7.26518e-4 -0.08606821 0.9962893 0 -0.1289725 0.9916479 -7.26759e-4 -0.2557697 0.9667378 3.62267e-4 -0.2558345 0.9667207 3.62201e-4 0.736764 -0.67615 0 0.8146414 -0.5799651 -7.38731e-5 0.754823 -0.6559117 -0.00469774 0.8188852 -0.5739571 -6.82962e-4 0.9737637 -0.2275609 5.40744e-4 0.9435763 -0.3311546 -6.93935e-4 0.9318895 -0.3627393 -0.0014894 0.9005763 -0.4346976 4.35316e-4 0.9005519 -0.4347484 4.35295e-4 0.9737543 -0.2276011 5.40743e-4 0.992354 -0.1234167 -0.00140196 0.9970859 -0.07628893 0 0.9050116 0.0535382 0.4220046 0.9884204 0.04542636 0.1447818 0.8200915 -0.152043 0.5516638 0.8198322 -0.1744512 0.5453826 0.8061807 -0.08480793 0.58556 0.8066223 -0.1212351 0.5785003 0.7694995 -0.02747207 0.6380563 0.7689045 -0.08162367 0.6341322 0.7458771 0.05526256 0.6637873 0.9401583 -0.07148945 0.3331543 0.8238608 -0.2277018 0.5190426 0.8388827 -0.1298263 0.5286029 0.9143654 -0.05879694 0.4005982 0.9145685 2.11849e-4 0.404431 0.9288312 -0.08410805 0.3608303 0.928328 -0.03961735 0.3696453 0.9337013 -0.1151326 0.3390374 0.9337939 -0.1103046 0.340385 0.9422699 -0.1351084 0.3063873 0.9904124 -0.004279673 0.1380765 0.9898829 0.02420836 0.1398072 0.9919763 -0.01626694 0.1253734 0.9915179 0.006031095 0.1298304 0.9925793 -0.02796506 0.1183398 0.9923751 -0.0118938 0.1226803 0.9934988 -0.03748697 0.107494 0.7379865 -0.6748136 -0.001624166 0.7508447 -0.6604093 0.009594321 0.7464912 -0.6650417 0.02168798 0.7949451 -0.6030339 0.06642651 0.7365278 -0.6764048 0.001828312 0.7529433 -0.6578974 0.0157305 0.7542084 -0.6566349 5.26505e-4 0.8138337 -0.5783383 0.05656415 0.8153303 -0.5789104 0.009964644 0.8915579 -0.4422873 0.09750193 0.8815373 -0.4671921 0.06799703 0.8623141 -0.4416991 0.2476219 0.8367111 -0.5056409 0.2103378 0.8361089 -0.5162196 0.1855788 0.8568511 -0.4810645 0.1854274 0.7838902 -0.6125063 0.1017462 0.8965734 -0.439453 0.05511331 0.9336212 -0.3403498 0.1118645 0.9257062 -0.3699205 0.07891249 0.9594272 -0.2396095 0.1486164 0.9536157 -0.2800555 0.110391 0.8726279 -0.3400846 0.3505184 0.8726368 -0.3400152 0.3505637 0.8754236 -0.367211 0.3143085 0.8901368 -0.3171157 0.3272525 0.8660191 -0.4168708 0.2760972 0.965099 -0.2370956 0.1112194 0.9792478 -0.09164655 0.1807615 0.9786852 -0.2025426 0.03393822 0.841693 -0.2526632 0.4771942 0.879837 -0.2946048 0.3729543 0.941608 -0.1681948 0.2916933 0.9415886 -0.1682204 0.291741 0.07833176 -0.9969274 0 0.1421411 -0.9898446 -0.001918673 0.2332758 -0.9724107 3.53069e-4 0.4149736 -0.9098336 0 0.537173 -0.843438 -0.007589101 0.5236615 -0.8518998 -0.006734907 0.4397597 -0.8981129 -0.002144753 0.3376113 -0.9412857 -2.45732e-4 0.2332317 -0.9724211 3.53098e-4 0.6214184 -0.7834753 -0.002400815 0.779019 -0.1960821 0.5955511 0.7121915 -0.1765897 0.6794111 0.6000325 -0.2061223 0.7729648 0.6463236 -0.1371077 0.7506446 0.658523 -0.02346783 0.7521947 0.9403554 -0.2354128 0.2455863 0.9403702 -0.2354215 0.2455217 0.550967 -0.4953039 0.6716468 0.6333504 -0.4317938 0.6422004 0.7790234 -0.1961051 0.595538 0.6946544 -0.7151487 0.07757425 0.7434191 -0.6528272 0.1454123 0.7747792 -0.5686955 0.2762294 0.7771512 -0.5367377 0.3285555 0.7549066 -0.5857495 0.2949808 0.7811051 -0.5054302 0.366627 0.7063486 -0.6922205 0.1479952 0.6988442 -0.7140637 0.04159289 0.7129289 -0.6943902 0.09774875 0.7131915 -0.6941421 0.09759545 0.7158386 -0.6917392 0.09524732 0.6468408 -0.7594909 0.06906992 0.7410845 -0.4896866 0.4593483 0.753547 -0.5561835 0.3504668 0.7543033 -0.5563747 0.3485311 0.6991817 -0.6736679 0.2394085 0.6991864 -0.6736522 0.2394393 0.7410843 -0.4896887 0.4593462 0.7500644 -0.3579747 0.5561095 0.7617409 -0.3659489 0.5346328 0.6651946 -0.0587818 0.7443527 0.7211269 -0.139993 0.6785116 0.6967239 -0.1197698 0.7072701 0.7223694 -0.2773907 0.6334327 0.7223666 -0.2773678 0.6334459 0.7898747 -0.4284782 0.4387532 0.7896584 -0.4548601 0.4117547 0.7681692 -0.3429549 0.5406458 0.77253 -0.3112455 0.5534651 0.6978551 -0.1188387 0.7063114 0.6977298 -0.1074524 0.7082564 0.537784 -0.8430827 8.35977e-5 0.5243033 -0.851488 0.008617162 0.5308865 -0.8473147 0.01474612 0.4514191 -0.8900913 0.06291514 0.4789574 -0.8735676 0.0864852 0.3802149 -0.9137676 0.1430569 0.4018507 -0.9051469 0.1386551 0.5380051 -0.8429416 8.35671e-5 0.5274447 -0.8495627 0.006727576 0.5243358 -0.8515114 6.01922e-4 0.4589396 -0.8875409 0.04056501 0.4407261 -0.8976054 0.008069932 0.3632974 -0.9301886 0.05257666 0.3420214 -0.9384471 0.04835891 0.1914493 -0.9256756 0.3263005 0.2127576 -0.9332855 0.289331 0.1668466 -0.9384858 0.3023352 0.3347284 -0.9164291 0.219351 0.2901867 -0.9346893 0.2052996 0.3897537 -0.908185 0.1526177 0.2421451 -0.9648711 0.1019295 0.2704657 -0.959683 0.07653141 0.2390785 -0.96893 0.06337374 0.1333317 -0.9841998 0.1165058 0.0876255 -0.9910348 0.1008561 0.109343 -0.9249749 0.3639584 0.01763045 -0.9909303 0.1332153 0.1903194 -0.9235696 0.3328632 0.06029438 -0.9200369 0.3871651 0.1793504 -0.9103022 0.3730732 0.08068847 -0.9093501 0.4081322 -0.006145477 -0.9040906 0.4272968 0.1532735 -0.8913005 0.4267207 -0.0885142 -0.8847877 0.4575107 0.128112 -0.8588901 0.4958781 0.05298 -0.991509 0.1187564 -0.002511084 -0.9898064 0.1423973 0.04513126 -0.9897521 0.1354778 -0.0335074 -0.9873906 0.1547159 0.02908909 -0.9881303 0.150839 -0.06856417 -0.9840809 0.1639629 0.01146209 -0.9847427 0.1736391 0.1731218 -0.8315703 0.5277497 0.05682069 -0.7926833 0.60698 0.5521007 -0.8336477 0.01470851 0.5459414 -0.8372626 0.03064888 0.5200108 -0.8438034 0.1326076 0.5099238 -0.8561724 0.08334743 0.4316741 -0.8808899 0.1941404 0.2633923 -0.8800516 0.3951377 0.2633866 -0.8800567 0.3951299 0.3849851 -0.8837563 0.2660099 0.3880724 -0.8710286 0.3011795 0.4316217 -0.8808878 0.1942667 0.216595 -0.857692 0.4663167 0.1145983 -0.8219403 0.5579259 0.1662063 -0.8535195 0.493842 0.1660617 -0.8534589 0.4939954 0.1730782 -0.8315545 0.5277889 0.07824254 -0.8124337 0.57778 0.09905582 -0.7975376 0.5950813 0.0415861 -0.7913486 0.6099492 0.2547174 -0.8574808 0.447041 0.2484903 -0.8619875 0.4418486 0.2512341 -0.8649588 0.434428 0.4595625 -0.8580473 0.2292535 0.4595979 -0.8580483 0.229179 0.3932247 -0.8780016 0.272924 0.3628329 -0.8651857 0.3461301 0.362942 -0.8651943 0.3459944 0.5957923 -0.8031264 -0.004431545 0.5432574 -0.8321354 0.1114547 0.5275986 -0.8477666 0.05414491 0.5027967 -0.8520561 0.1455888 0.9970731 0.0764541 0 0.9923539 0.1234174 -0.001399576 0.9736859 0.2278937 5.42608e-4 0.9318895 0.3627393 -0.00146526 0.9404419 0.3399537 -8.02992e-4 0.973679 0.2279233 5.42605e-4 0.8146418 0.5799646 0 0.7372063 0.6756415 -0.005956411 0.7487256 0.6628603 -0.005137801 0.8081394 0.5889902 -0.001134276 0.8924379 0.4511702 5.65721e-4 0.8924181 0.4512093 5.65695e-4 0.7365278 0.6764048 0.001828312 0.7446799 0.6673658 0.008655607 0.7483554 0.6632978 5.22485e-4 0.7933135 0.6074025 0.04142421 0.8075295 0.5897781 0.007614433 0.7379865 0.6748136 -0.001624166 0.7484606 0.6631332 0.007824122 0.7429417 0.669213 0.01384109 0.7976776 0.5996555 0.06421738 0.7749281 0.6259424 0.08765059 0.8521271 0.4938269 0.1732467 0.8297523 0.5289815 0.1780168 0.8839098 0.4583279 0.09294551 0.8756213 0.4793824 0.0589919 0.8887864 0.4555493 0.05033618 0.9184723 0.3846381 0.09199088 0.933126 0.3477568 0.09133094 0.8318126 0.5184903 0.1981304 0.8731679 0.4129235 0.2589826 0.8539697 0.4531738 0.255674 0.8901834 0.3171495 0.327093 0.8687133 0.3723899 0.3265932 0.8726001 0.3403421 0.3503373 0.8875294 0.1938838 0.4179722 0.8694775 0.2603137 0.4198163 0.8694589 0.2603467 0.4198344 0.9829173 0.1334044 0.1267954 0.9593486 0.2399752 0.1485337 0.9535449 0.2803581 0.1102337 0.965042 0.2373759 0.1111161 0.9780952 0.1285891 0.1636905 0.9851995 0.08909797 0.1464364 0.8238727 0.1561629 0.5448368 0.8096396 0.3748468 0.4516347 0.8671988 0.1011093 0.4875892 0.9927229 0.04086214 0.1132763 0.9643355 0.2551587 0.07036495 0.8972057 0.3669833 0.2456529 0.9091143 -0.2915104 0.2975452 0.8631891 0.3211579 0.3895666 0.9913151 0.02727961 0.1286475 0.9916191 -0.01184505 0.1286523 0.9207144 0.1234993 0.3701798 0.9321191 0.01987177 0.3616064 0.7865679 0.1907945 0.5872892 0.8185458 0.05002647 0.572259 0.9893967 0.00953561 0.1449253 0.9896658 -0.03998738 0.1377048 0.9030814 0.08434343 0.4211059 0.9183588 -0.04795807 0.3928325 0.7406979 0.1297714 0.659186 0.7836319 -0.05452811 0.6188279 0.2361511 0.9717163 4.07974e-4 0.5385514 0.8425928 0 0.4149742 0.9098332 -8.40727e-5 0.4641418 0.8857554 -0.003145515 0.3505539 0.9365426 -3.63508e-4 0.2361391 0.9717193 4.08006e-4 0.1421411 0.9898446 -0.00197494 0.07930564 0.9968504 0 0.6541956 0.02564841 0.7558905 0.7818059 0.5702077 0.2522754 0.7327237 0.6667784 0.1360978 0.7120953 0.7004076 0.04847186 0.7178289 0.6930572 0.06628268 0.7087473 0.7047808 0.03100693 0.6966542 0.717344 -0.009519219 0.7818037 0.5702134 0.252269 0.774851 0.5325896 0.3405205 0.783033 0.5091465 0.3572523 0.7524995 0.2297915 0.6172037 0.7679926 0.3284125 0.5498479 0.7665571 0.3383736 0.5457962 0.7958385 0.4230906 0.4331691 0.7958324 0.4230902 0.4331808 0.671994 0.05099886 0.7387985 0.687914 0.1249297 0.7149594 0.7161681 0.1529942 0.6809524 0.7526171 0.2300387 0.6169682 0.6822979 0.06964129 0.7277498 0.7349166 0.1285362 0.6658649 0.6981428 0.1160663 0.706488 0.7359478 0.2832483 0.6149401 0.7523156 0.4502552 0.480928 0.7523034 0.4502377 0.4809633 0.7778061 0.328239 0.5359823 0.778942 0.3287355 0.5340247 0.7359717 0.2832998 0.6148877 0.7128009 0.667209 0.2162108 0.7845721 0.5236632 0.3319992 0.8282638 0.497607 0.2576165 0.7764158 0.5186631 0.3580046 0.7338496 0.6708227 0.1070598 0.802955 0.5946626 0.04049539 0.7128074 0.667194 0.2162355 0.0218032 0.8659195 0.4997081 0.1643387 0.8938971 0.4170621 0.04005944 0.99581 0.08220595 0.0193125 0.9954503 0.09330457 0.14047 0.9622669 0.2330464 0.1129592 0.9614835 0.2505788 0.09007257 0.9618749 0.2582319 0.2216489 0.8966623 0.3832342 0.1381242 0.8717995 0.4699864 0.1838322 0.8942605 0.4080489 0.07274824 0.9531424 0.293645 0.1186389 0.9614995 0.247878 0.008292198 0.9945527 0.1039044 0.03241038 0.9956694 0.08713364 0.06307733 0.8393158 0.5399725 0.1419401 0.8664928 0.4785849 0.02216452 0.9409008 0.3379566 0.09113687 0.9531604 0.2884086 -0.014095 0.9929761 0.1174721 0.02040189 0.9947313 0.1004658 -0.02129459 0.793192 0.6085993 0.08090257 0.839302 0.5376123 -0.03491145 0.9233173 0.3824481 0.05941039 0.9410213 0.3330908 -0.03864127 0.9907042 0.1304311 0.007090508 0.9933718 0.1147268 0.5373309 0.8433707 -0.001202821 0.4825633 0.8751356 0.03564387 0.2428412 0.9677488 0.06701064 0.2778282 0.9574249 0.0784161 0.2465475 0.9629502 0.1092765 0.3703341 0.9281859 0.03638142 0.3570733 0.9316144 0.06777477 0.4647457 0.8854442 -4.12411e-5 0.4689137 0.8818785 0.04909539 0.5388367 0.8424068 0.002414703 0.1802777 0.9304468 0.3190119 0.3292224 0.9132972 0.2397932 0.3357746 0.9214087 0.1956057 0.4086616 0.8998162 0.1527305 0.4219824 0.8953962 0.1421146 0.3940514 0.9083219 0.1402677 0.4999883 0.8629114 0.07345622 0.2426891 0.8958765 0.372166 0.3613135 0.9259446 0.1099055 0.2133235 0.9253705 0.313341 0.1666848 0.9612782 0.2194548 0.1655633 0.980088 0.1096194 0.08538115 0.9945873 0.05921345 0.5926561 0.7957611 0.1245918 0.2055824 0.8240334 0.527925 0.1294026 0.7881858 0.6016796 0.08792531 0.7624773 0.6410129 0.153891 0.7672965 0.6225541 0.04443573 0.7382856 0.6730231 0.2578426 0.8305564 0.4936532 0.2670099 0.8311498 0.4877455 0.2995941 0.8569446 0.4193917 0.299602 0.8569475 0.4193803 0.4137679 0.8622463 0.2921085 0.410384 0.8576984 0.3097394 0.5716651 0.8199182 0.03054797 0.5415565 0.8332655 0.1112889 0.5431495 0.835308 0.08514314 0.4651319 0.8617388 0.2026293 0.4651948 0.8617364 0.2024953 0.6438768 0.7651063 -0.005913615 0.6139953 0.7862135 0.06984287 0.2850781 0.950117 0.1265237 0.5872533 0.8012509 0.1145889 0.5402329 0.8159274 0.2059395 0.4372221 0.8439542 0.3107708 0.4430873 0.8548443 0.270028 0.1703113 0.7800296 0.6021196 0.2405699 0.8097592 0.5351788 0.2954555 0.8404614 0.4542365 0.2851561 0.81643 0.5021235 0.4201817 0.8348836 0.3555513 0.4201639 0.8348798 0.3555812 0.1703712 0.7800549 0.6020697 0.08595925 0.7640247 0.6394352 0.05636125 0.7356145 0.6750517 0.6304333 0.1950942 0.7513268 0.6157235 0.2415307 0.7500318 0.6157591 0.2413191 0.7500707 0.5405181 0.5555408 0.6318343 0.4660313 0.6681191 0.5800274 0.4660356 0.6681156 0.5800279 0.3653512 0.8314253 0.4186294 0.2087387 0.938835 0.2738925 0.2087135 0.9388499 0.2738605 0.1319572 0.9807519 0.1439208 0.03438764 0.9985681 0.04098206 0.03937619 0.9080926 0.4169142 0.5860404 0.1128552 0.8023842 0.0857219 0.6368925 0.7661721 0.09834855 0.6993442 0.7079867 0.274892 0.4872131 0.8288895 0.2645294 0.521925 0.8109369 0.5843156 0.1030363 0.8049589 0.4595661 0.3184766 0.8290787 0.4437583 0.3311746 0.8327076 0.4443551 0.3056102 0.8421111 0.3020234 0.5101804 0.8052936 0.5895027 0.1396995 0.7955946 0.5916488 0.1168619 0.7976811 0.4508826 0.4093151 0.7931999 0.4627299 0.3446995 0.8167396 0.2745643 0.6427096 0.7152194 0.2983515 0.5461198 0.7827769 0.07783818 0.8193277 0.5680173 0.109238 0.707016 0.6987099 0.6023902 0.168842 0.7801401 0.6013363 0.1447444 0.785776 0.4772189 0.4879361 0.7308765 0.4817669 0.4225788 0.7676771 0.2990863 0.7492772 0.5908732 0.3135845 0.6596693 0.6830089 0.1406678 0.8823046 0.4491674 0.1115462 0.834177 0.5400984 0.6189957 0.1950728 0.7607832 0.6145952 0.1713042 0.7700179 0.5112653 0.5553075 0.6559279 0.5082809 0.494323 0.7051917 0.330466 0.8309782 0.4475124 0.3357993 0.7570215 0.5604974 0.1059134 0.9804716 0.1657038 0.1170294 0.9279451 0.3538674 0.09519982 0.6448944 0.7583194 0.1329327 0.6271392 0.7674798 0.2755796 0.4877961 0.8283181 0.2753867 0.4879871 0.8282698 0.3744565 0.4096761 0.831834 0.5862487 0.1046587 0.8033424 0.571561 0.1446457 0.8077101 0.4425343 0.3041584 0.8435943 0.4425659 0.3041155 0.8435931 0.579535 0.1827833 0.7941848 0.1291251 0.6357073 0.761054 0.1248853 0.6259125 0.7698295 0.381497 0.4554623 0.8043719 0.3811724 0.435718 0.815388 0.3618466 0.433577 0.8252746 0.5947223 0.2285957 0.770746 0.5600553 0.1349885 0.8173838 0.5815192 0.1846896 0.7922912 0.3602414 0.3977427 0.8438169 0.3744359 0.4292615 0.8219078 0.1205573 0.6167562 0.7778676 0.1263225 0.6272788 0.7684816 0.6674312 0.7446711 7.7249e-4 0.6646863 0.742384 0.08401238 0.6578972 0.7531077 4.62896e-4 0.6864746 0.7233031 0.0747348 0.5834261 0.7821187 0.2188705 0.6134263 0.7607661 0.2119982 0.6279991 0.7747187 0.0736761 0.685043 0.7246712 0.07461738 0.6551412 0.7509721 0.08264964 0.5833253 0.782172 0.2189486 0.5657882 0.7641965 0.3096574 0.5619037 0.7738255 0.2923324 0.5361031 0.7460677 0.3949388 0.5154945 0.7730128 0.3697521 0.6695219 0.7069289 0.2280176 0.6929408 0.6887708 0.2131382 0.6964564 0.6827802 0.2208156 0.6827472 0.6684975 0.2949026 0.6859804 0.6584826 0.3095668 0.6696766 0.6415333 0.3741236 0.6896283 0.6105992 0.3893346 0.6427232 0.5608597 0.5218652 0.6620934 0.5635417 0.4940174 0.6689667 0.5370803 0.513837 0.6413747 0.5070362 0.5758063 0.6388518 0.4817732 0.5998024 0.3098811 0.677975 0.6665761 0.3481115 0.6804485 0.644832 0.3350601 0.656005 0.6763078 0.394069 0.721965 0.5687496 0.3930423 0.6975049 0.5991701 0.4433752 0.7521109 0.4875938 0.4619995 0.7193002 0.51881 0.5083712 0.7697861 0.38599 0.1560196 0.66504 0.7303285 0.2887554 0.6549028 0.6983715 0.4022266 0.4784134 0.7805988 0.4022473 0.4783968 0.7805982 0.5915365 0.431389 0.6811667 0.6271733 0.4308548 0.6488589 0.6158304 0.4096065 0.6730346 0.5945253 0.3860332 0.7053496 0.620429 0.2575525 0.7407662 0.1254028 -0.9807851 0.1494488 0.1254061 -0.980784 0.1494529 0.3571177 -0.8314642 0.4255989 0.3571115 -0.8314718 0.4255891 0.5344505 -0.5555887 0.6369331 0.5344558 -0.5555651 0.6369493 0.6304323 -0.1950833 0.7513306 0.6304334 -0.1950937 0.7513269 0.08551114 -0.9794656 0.1825786 0.3271986 -0.830834 0.4501734 0.5151129 -0.5554302 0.6528063 0.6220291 -0.1950753 0.7583044 0.3751527 -0.8291498 0.4144529 0.2884268 -0.8257139 0.4847748 0.3799129 -0.7621948 0.5241426 0.2635925 -0.7378418 0.6213763 0.3518084 -0.674631 0.6489253 0.1544533 -0.9791581 0.1318852 0.0472005 -0.9741834 0.2207687 0.1817793 -0.9356511 0.3025116 0.04020071 -0.906093 0.4211644 0.1248248 -0.894625 0.4290282 0.1106387 -0.833606 0.5411655 0.0352528 -0.7979634 0.6016741 0.1565277 -0.741608 0.6523164 0.2978441 -0.5487055 0.7811602 0.2558796 -0.6338809 0.7298772 0.3303367 -0.5708169 0.7516953 0.462597 -0.3463773 0.8161048 0.5429126 -0.5536085 0.6314773 0.4864387 -0.5522807 0.6770255 0.5330565 -0.4974476 0.6843951 0.4565424 -0.4814748 0.7481651 0.5033751 -0.4315174 0.7486029 0.4461462 -0.4071177 0.7969998 0.4808396 -0.3593478 0.799789 0.6301681 -0.1943533 0.7517414 0.6108652 -0.194163 0.7675576 0.6224437 -0.1723723 0.7634472 0.5956717 -0.1668298 0.785712 0.6082563 -0.1476734 0.7798827 0.5842382 -0.1374177 0.7998639 0.5975185 -0.1215994 0.7925816 0.09721297 -0.7023373 0.7051752 0.1396517 -0.6855694 0.7144873 0.2778956 -0.5347032 0.7980392 0.2779244 -0.5346843 0.7980418 0.3858149 -0.4530603 0.8036686 0.4458243 -0.3345628 0.8302461 0.4457545 -0.334665 0.8302423 0.5795032 -0.1613833 0.7988314 0.5893361 -0.1158132 0.7995438 0.1385442 -0.7012608 0.6993131 0.5738371 -0.2941971 0.764303 0.6367693 -0.2955095 0.7121791 0.3667407 -0.5201871 0.7713018 0.3982811 -0.5155625 0.7586616 0.3864299 -0.5440296 0.7447844 0.1236363 -0.6966922 0.7066357 0.136812 -0.683602 0.7169176 0.1163442 -0.6805628 0.7233936 0.4066796 -0.4675417 0.7848671 0.347222 -0.468171 0.8125594 0.6251488 -0.194406 0.755907 0.5383452 -0.2053516 0.8173221 0.5448152 -0.7981544 0.25715 0.5591538 -0.8128585 0.1631199 0.6137332 -0.7895134 5.92788e-4 0.6104269 -0.788989 0.06982326 0.6087909 -0.7933307 3.96606e-4 0.6058703 -0.7916404 0.07890993 0.6396263 -0.7654257 0.07072287 0.6306037 -0.7577495 0.1677932 0.6546713 -0.7127352 0.2518216 0.6279848 -0.7400116 0.2408692 0.6401481 -0.7519293 0.1575207 0.5692173 -0.8074269 0.1550922 0.5770853 -0.8137829 0.06877428 0.6546419 -0.7127721 0.2517936 0.6218289 -0.6773948 0.3930205 0.6564154 -0.6588809 0.3674166 0.6118142 -0.6085114 0.5053685 0.6344279 -0.6093987 0.4755361 0.5448121 -0.7981939 0.2570338 0.5154265 -0.8237802 0.2360544 0.4808665 -0.7859399 0.3886721 0.4652137 -0.8086459 0.3600949 0.4491599 -0.8097639 0.377542 0.4207937 -0.7775386 0.4672968 0.384534 -0.7827891 0.4892595 0.633913 -0.3660244 0.6813079 0.5909054 -0.7779521 0.2135916 0.5575902 -0.4301105 0.7099988 0.6351484 -0.5897765 0.4987486 0.5862411 -0.5337727 0.6094326 0.6267734 -0.5265339 0.5743843 0.5559551 -0.4430336 0.7033031 0.4103158 -0.572913 0.7095152 0.3367981 -0.7254266 0.6002694 0.3399574 -0.752952 0.5634647 0.306808 -0.7479874 0.5885437 0.2871299 -0.7247505 0.6263331 0.1552795 -0.7346758 0.6604088 -0.4188213 -0.6646084 0.6187767 -0.002925992 -0.7971284 0.6038028 -0.02359396 -0.7944145 0.6069176 -0.02329319 -0.7938846 0.6076222 -0.1026037 -0.7792903 0.6182063 -0.103143 -0.779646 0.6176679 -0.2667739 -0.7320288 0.6268696 -0.2672847 -0.7321195 0.6265462 -0.2670788 -0.7322631 0.626466 -0.4185188 -0.664987 0.6185744 -0.4187934 -0.6647714 0.6186203 -0.4183113 -0.6649041 0.6188039 -0.993512 0.08041083 0.08042532 -0.9931755 0.08238667 0.0825535 -0.9935089 0.08045828 0.08041507 -0.9935113 0.08043283 0.08041155 -0.993508 0.08041572 0.08046925 -0.9999454 0.007394731 0.007404983 -0.9752195 0.156446 0.1564344 -0.9988257 -0.03425705 -0.03425979 -0.9737795 0.212128 0.08219105 -0.9646413 0.2371013 0.1151096 -0.9614292 0.2470977 0.1208164 -0.9476052 0.2721991 0.1671888 -0.9358894 0.3031093 0.1795434 -0.8949951 0.3316079 0.2983622 -0.9049729 0.3563379 0.2324809 -0.8846172 0.3767413 0.2748063 -0.8706184 0.3762243 0.3169844 -0.8289343 0.4152467 0.3747506 -0.9968245 -0.07953822 0.003835618 -0.9698414 0.08746653 0.2275025 -0.9712752 0.08211743 0.2233413 -0.9617494 0.09947425 0.2552313 -0.9609637 0.1021705 0.2571189 -0.947581 0.1126119 0.2990134 -0.9410634 0.1284607 0.3128861 -0.9313868 0.1279774 0.3407937 -0.9183104 0.1414552 0.3697251 -0.911001 0.138503 0.3884512 -0.8872247 0.1644991 0.4310132 -0.7759042 0.392541 0.4938466 -0.780906 0.4957838 0.3799793 -0.7452266 0.4777905 0.4651384 -0.8830637 0.161076 0.4407415 -0.6458714 0.5051362 0.57244 -0.7447704 0.4773975 0.4662711 -0.847041 0.1722472 0.5028444 -0.8572722 0.1816759 0.4817453 -0.8114891 0.1845123 0.5544733 -0.5896776 0.452771 0.668789 -0.6733687 0.536247 0.5089341 -0.5546271 0.5374998 0.635203 -0.5632289 0.5489345 0.6176117 -0.5673625 0.5500885 0.6127827 -0.8162283 0.1955557 0.543626 -0.8287782 0.2010487 0.5222129 -0.5113763 0.485695 0.7089391 -0.5173263 0.4873967 0.7034331 -0.7890713 0.1729028 0.5894667 -0.8056618 0.1812645 0.5639613 -0.4925224 0.4464278 0.7470769 -0.7043929 0.005955755 0.7097854 -0.7089111 0.01254707 0.7051863 -0.6974318 0.02219849 0.7163074 -0.7209776 0.04806256 0.6912896 -0.648911 0.141472 0.7475963 -0.6489032 0.141516 0.7475948 -0.6757323 0.1756063 0.7159249 -0.7050725 0.006214559 0.709108 -0.7067816 0.009402811 0.7073693 -0.7093508 0.005837976 0.7048315 -0.7332369 0.03198683 0.6792206 -0.7273446 0.03912687 0.6851562 -0.760221 0.08186614 0.6444859 -0.7536051 0.08615529 0.6516569 -0.6121969 0.2782751 0.7401202 -0.6122134 0.2782748 0.7401068 -0.6202638 0.2905722 0.7285882 -0.4926018 0.4464269 0.7470252 -0.4925848 0.4464747 0.7470079 -0.7825757 0.1316019 0.6084868 -0.7782611 0.1477645 0.6103076 -0.7750833 0.1444914 0.6151165 -0.9930679 -4.66039e-4 0.1175418 -0.9677755 -0.1095506 0.2267363 -0.9655452 -0.2530508 0.06072795 -0.9655458 -0.06074702 0.2530439 -0.9677768 -0.1095455 0.2267329 -0.993061 -0.1176002 4.10586e-4 -0.9930834 -0.1174104 3.53124e-4 -0.9677752 -0.226731 0.1095648 -0.833051 -0.2271656 0.5044027 -0.6602907 -0.6367927 0.3981348 -0.6604519 -0.6365128 0.3983151 -0.8017575 -0.2165278 0.5570466 -0.8092773 -0.2107346 0.548326 -0.8382152 -0.2057532 0.5050355 -0.8629267 -0.2104719 0.4594116 -0.8448409 -0.1839196 0.5024117 -0.7338346 -0.592356 0.3325676 -0.6594228 -0.5809612 0.4771223 -0.5859797 -0.6130153 0.5299436 -0.7807767 -0.5111752 0.3592878 -0.780906 -0.5111063 0.3591048 -0.7809773 -0.5111604 0.3588725 -0.7081704 -0.5169293 0.4809146 -0.9108831 -0.1581162 0.3811709 -0.9064818 -0.1559029 0.3924095 -0.9267464 -0.1362591 0.3501068 -0.9274417 -0.1358996 0.3484012 -0.9391734 -0.1193516 0.3220381 -0.9436876 -0.1169285 0.3094861 -0.8914722 -0.1764061 0.4173228 -0.8801818 -0.1715602 0.4425464 -0.828648 -0.4697875 0.304372 -0.8640574 -0.4507645 0.2240899 -0.8505937 -0.4350687 0.295306 -0.9064087 -0.3824254 0.1793717 -0.8968948 -0.3870062 0.2140235 -0.9341393 -0.3331293 0.1280966 -0.9317281 -0.3342531 0.1419776 -0.6886776 -0.6426455 0.3357527 -0.813939 -0.2204392 0.5375034 -0.813951 -0.2206904 0.5373821 -0.5914962 -0.5545408 0.5853348 -0.8139538 -0.2206591 0.5373908 -0.4652528 -0.5582478 0.6869492 -0.5652166 -0.4945455 0.6602689 -0.7140178 -0.3560088 0.6028569 -0.4622459 -0.4528663 0.7623915 -0.438404 -0.7880042 0.4322634 -0.5378978 -0.5931863 0.598996 -0.702628 -0.005990087 0.7115322 -0.7066828 -0.008965373 0.7074738 -0.6622908 -0.1103561 0.7410753 -0.7384482 -0.05927073 0.6717002 -0.700075 -0.01690822 0.7138692 -0.7052861 -0.006176829 0.7088959 -0.7079899 -0.009411931 0.7061598 -0.7087252 -0.004183232 0.7054722 -0.7278624 -0.02486801 0.6852722 -0.7243149 -0.03352594 0.6886538 -0.7511509 -0.06715476 0.656706 -0.7491587 -0.07535266 0.6580905 -0.6920921 -0.3303614 0.6417709 -0.6328753 -0.2389807 0.736449 -0.6328725 -0.2013959 0.7476043 -0.7121031 -0.189807 0.6759308 -0.6580721 -0.1209007 0.7431851 -0.5214099 -0.4065898 0.750211 -0.5213058 -0.4062508 0.7504669 -0.5216835 -0.3468877 0.7794327 -0.771829 -0.1327576 0.6218162 -0.7805536 -0.1221789 0.6130322 -0.7699421 -0.1292797 0.6248808 0.7060306 0 -0.7081814 0.7060323 0 -0.7081797 0.706031 0 -0.708181 0.706031 0 -0.708181 0.7060309 1.43963e-7 -0.7081811 0.706026 0 -0.708186 -0.6427834 3.78019e-6 -0.7660481 -0.6428398 -2.04065e-5 -0.7660007 -0.6427794 1.4811e-6 -0.7660514 -0.6427841 -4.3754e-7 -0.7660474 -0.6427837 -8.12412e-7 -0.7660477 -0.6427848 6.55188e-7 -0.7660467 -0.6427841 2.13999e-6 -0.7660475 -0.6427943 0 -0.7660389 -0.6427941 -1.54395e-6 -0.7660391 -0.6427812 -8.74059e-7 -0.7660499 -0.642784 -8.22638e-7 -0.7660476 -0.6427772 -1.62679e-7 -0.7660532 -0.6427905 -1.2102e-7 -0.7660421 -0.6427869 -5.14494e-7 -0.7660451 -0.6427878 -5.38144e-7 -0.7660443 -0.6427852 0 -0.7660465 -3.50735e-5 -0.707128 -0.7070856 0 -0.7071025 -0.7071111 1.36811e-5 -0.7071017 -0.707112 3.62884e-5 -0.7071018 -0.7071118 0 -0.7071109 -0.7071027 1.45038e-6 -0.7071045 -0.7071091 4.93417e-6 -0.7070981 -0.7071154 -1.10381e-6 -0.707111 -0.7071027 -1.12978e-6 -0.7071104 -0.7071031 -3.38899e-6 -0.7071209 -0.7070927 0 0.8355675 -0.549388 -0.01115894 0.9336932 -0.3579002 0.01335525 0.7841903 -0.6203768 0.011689 0.7992581 -0.6008745 0 0.9940671 -0.1087691 3.74033e-4 0.9934769 -0.1140335 -3.80951e-4 0.9442083 -0.3293486 1.09653e-6 0.9402514 -0.3404811 1.24153e-6 0.944033 -0.3298513 0.005777359 0.8476227 -0.530568 0 0.7660409 -0.6427918 -6.99458e-6 0.7660609 -0.642768 -1.25734e-6 0.7660521 -0.6427785 1.84771e-6 0.7660406 -0.6427922 4.30818e-5 0.7660276 -0.6428077 8.05022e-5 0.7660189 -0.642818 1.55038e-5 0.7660451 -0.642787 2.63894e-6 0.7660387 -0.6427946 1.10901e-6 0.7660501 -0.642781 0 0.7661129 -0.642706 -0.7470087 0 -0.6648144 -0.747007 0 -0.6648163 -0.9063065 0 -0.422621 -0.9894425 0 -0.1449261 -0.9894426 0 -0.1449255 0 -1 -3.91618e-7 0 -1 -6.85888e-7 0 -1 1.66118e-5 0 -1 -1.43559e-6 0 -1 5.94028e-6 0 -1 -2.35977e-6 0 -1 -4.71009e-7 0 -1 9.48141e-6 3.02245e-5 -0.9359107 -0.3522377 0 -0.9928086 -0.1197128 -4.33943e-5 -0.9927397 -0.1202827 3.93649e-5 -0.9353725 -0.3536644 6.63508e-5 -0.8260561 -0.563588 3.02131e-5 -0.9359416 -0.3521553 -6.61376e-5 -0.9353208 -0.3538011 6.76975e-5 -0.8259791 -0.563701 6.62106e-5 -0.8259537 -0.5637381 0.00552982 -0.7439103 -0.6682567 -8.76575e-4 -0.8252146 -0.5648186 2.19313e-4 -0.7194862 -0.6945068 0 -0.7304986 -0.6829143 0 1 2.85277e-6 0 1 -1.56647e-6 0 1 1.64751e-6 0 1 -1.49258e-6 0 1 7.449e-6 0 1 -1.92386e-6 0 1 -1.15389e-6 -0.6083944 0.792706 0.03838831 0.50845 0.8610733 0.005598783 0.5075834 0.8615931 0.004074573 0.5053883 0.8628911 0.001308143 0.5276137 0.849472 0.004597008 0.5115321 0.8592627 -0.001641154 0.5080521 0.8613218 0.002814888 0.5137552 -0.8579322 0.002819776 0.5187731 -0.8549084 -0.002494394 0.5400685 -0.8415811 0.008207023 0.5124737 -0.8586753 0.006888568 0.5132524 -0.8581924 0.008821845 0.5126971 -0.8585434 0.006705522 0.5080034 -0.8613547 7.41676e-4 0.5097658 -0.8603083 0.002940416 0 0.7766534 -0.6299281 -7.42538e-4 0.8289722 -0.5592895 -0.001353383 0.9729176 -0.2311483 2.63249e-4 0.9443562 -0.328925 2.58623e-4 0.8660202 -0.5000091 -0.01625043 0.9428824 -0.3327293 -0.006981372 0.8985102 -0.4388972 0 0.9848075 -0.1736503 -0.0112695 0.9986567 -0.05057513 -0.00551933 0.9902351 -0.1392988 -0.002547681 -0.9687951 -0.2478504 -0.006257176 -0.9859465 -0.1669443 -0.004151105 -0.9807746 -0.1951 -6.83612e-4 -0.996856 -0.07923096 0 -0.9997321 -0.02314871 0 -0.7619728 -0.6476091 -0.006549835 -0.8550485 -0.5185068 -0.01527833 -0.9048271 -0.4255053 -7.29468e-4 -0.8314746 -0.5555625 2.20417e-4 -0.9417388 -0.336345 2.20456e-4 -0.9417256 -0.3363822 0.6996957 -0.1950157 -0.6873098 0.7050734 -0.08823251 -0.703624 0.7055788 -0.03585654 -0.7077237 0.6022782 -0.5323659 -0.5948508 0.6549596 -0.367448 -0.6603105 0.6908088 -0.1950947 -0.6962193 0.6910995 -0.3491737 -0.6328184 0.6910374 -0.34942 -0.6327504 0.3944791 -0.8432331 -0.3651635 0.4552842 -0.761743 -0.4609385 0.5849903 -0.5555506 -0.590889 0.5294123 -0.7335785 -0.4261283 0.5686512 -0.6369472 -0.5205135 0.1377373 -0.980786 -0.1381573 0.1052516 -0.9929041 -0.05534976 0.1880697 -0.9659993 -0.1774123 0.2783977 -0.9164416 -0.2874538 0.3882022 -0.8314597 -0.3974595 0.3350134 -0.9056026 -0.260096 0.3944619 -0.8432692 -0.3650985 0.05225265 -0.9045724 -0.4231057 0.04776608 -0.7889931 -0.6125425 0.6029251 -0.183906 -0.7763118 0.2024369 -0.5355537 -0.819879 0.603056 -0.1839493 -0.7761998 0.6139876 -0.2698145 -0.7417678 0.530744 -0.4240813 -0.7338024 0.6664949 -0.1697365 -0.7259299 0.6525765 -0.05756455 -0.7555331 0.4947112 -0.3452411 -0.7975397 0.4837137 -0.4394322 -0.7569151 0.3224694 -0.6485478 -0.6894921 0.3508564 -0.533765 -0.769412 0.09463644 -0.7995513 -0.593095 0.1332899 -0.7046554 -0.696918 0.1302325 -0.7130107 -0.6889523 0.6543912 -0.06848412 -0.7530485 0.6598194 -0.1613162 -0.7339043 0.524935 -0.4876952 -0.6975649 0.536254 -0.4269379 -0.728118 0.3261625 -0.7476867 -0.5784312 0.3545696 -0.665149 -0.6571585 0.09874707 -0.9142911 -0.3928369 0.1356196 -0.8383619 -0.5279741 0.6805435 -0.195067 -0.7062645 0.6781537 -0.1726004 -0.7143645 0.5602521 -0.5551678 -0.6147409 0.5649817 -0.4976621 -0.6581248 0.3583773 -0.8305434 -0.4263372 0.3792479 -0.761161 -0.5261228 0.1070725 -0.979874 -0.1684708 0.14295 -0.9312925 -0.3350515 0.03372669 0.9988583 -0.03383374 0.1983164 0.9656914 -0.1676626 0.1805074 0.9764838 -0.1178842 0.275714 0.9223486 -0.2706562 0.5178345 0.7070553 -0.4815809 0.4650918 0.8078014 -0.3621417 0.4995241 0.7071001 -0.500485 0.3908149 0.8305518 -0.3967965 0.390327 0.831014 -0.3963087 0.7030523 0.09177893 -0.7051909 0.7015779 0.1968083 -0.684876 0.6932521 0.3054209 -0.6527785 0.6932459 0.3055197 -0.6527388 0.687314 0.4145214 -0.5964659 0.6856883 0.2588129 -0.680329 0.5759606 0.575219 -0.5808549 0.575934 0.5752696 -0.5808312 0.1647692 0.8230002 -0.5436193 0.7059096 4.34941e-4 -0.7083018 0.6485146 0.2284396 -0.7261159 0.6265837 0.09294545 -0.7737921 0.6343798 0.1453406 -0.7592355 0.5885152 0.2646343 -0.7639494 0.2778202 0.4979032 -0.8215282 0.5436962 0.3862125 -0.7451406 0.4334418 0.553644 -0.7110603 0.4239786 0.4721223 -0.7728795 0.08428025 0.7798252 -0.620298 0.2270174 0.7144215 -0.6618649 0.3437431 0.5853953 -0.7342705 0.08757162 0.781892 -0.6172327 0.003562569 0.7983384 -0.6021988 0.02356541 0.7949575 -0.6062074 0.6735165 0.2339619 -0.7011686 0.6567189 0.2586565 -0.7083906 0.5089981 0.6515156 -0.5625375 0.4385468 0.7046444 -0.5578109 0.2347428 0.9245656 -0.3001237 0.1011781 0.9596856 -0.2622336 0.5604751 0.2062029 -0.8020899 0.6324099 0.2405885 -0.7363254 0.4785526 0.574896 -0.6636882 0.4065688 0.6282383 -0.6633389 0.1816354 0.8772332 -0.4443767 0.08706176 0.8905434 -0.4464895 0.9606694 -0.2470144 0.126879 0.9352225 0.3503714 0.05097901 0.4736865 0.6076636 0.6374685 0.9335287 0.3498557 0.07826459 0.9007342 0.3946111 0.1815494 0.8686835 -0.1010184 -0.4849579 0.7078044 0 -0.7064085 0.7070948 0 -0.7071188 0.7103342 0 -0.7038647 0.7117387 -1.00442e-5 -0.7024443 0.7386444 5.31396e-5 -0.6740953 0.7443867 -1.96524e-4 -0.6677488 0.7805609 1.30288e-4 -0.6250799 0.7925407 -2.28788e-4 -0.609819 0.833544 4.88424e-4 -0.5524529 0.9154576 0.004976391 -0.4023839 0.9309673 0.002833127 -0.3650918 0.9647049 5.31325e-4 -0.2633332 0.9630333 5.49092e-4 -0.269382 0.9589559 6.2731e-4 -0.2835549 0.9508635 0.001015782 -0.3096087 0.9426719 0.001690983 -0.3337168 0.9018874 0.007137238 -0.4319124 0.8920935 0.008901238 -0.4517632 0.8839935 0.01040208 -0.4673838 0.8666529 -3.22965e-5 -0.4989115 0.8451701 -3.17761e-4 -0.5344973 0.8451479 -3.17848e-4 -0.5345324 0.8822227 4.92987e-5 -0.4708325 0.8961281 -4.02681e-4 -0.4437954 0.9058465 -8.58688e-4 -0.4236053 0.9139436 -0.001486182 -0.4058386 0.9196268 -0.001991808 -0.3927881 0.9488599 -0.005590021 -0.315648 0.9927248 0 -0.1204053 0.9997475 0.01049643 -0.01987099 0.9452515 -0.01875501 -0.3258035 0.9898611 5.13964e-4 -0.1420379 0.9885289 5.13727e-4 -0.1510312 0.3273717 0.9355 0.1329198 0.4987202 0.8400356 -0.2135846 0.9014052 0.4293895 -0.0556181 0.7481548 0.6622939 0.04038989 0.7414261 0.6683643 0.05980515 0.7830736 0.598773 -0.1681272 0.4107586 0.7779784 -0.475423 0.4659045 0.7671818 -0.4408687 0.3981294 0.8650273 -0.3053208 0.2437526 0.8474335 -0.4716368 0.0568068 0.9960839 -0.06774961 0.04229265 0.9987111 -0.02806466 0.02152705 0.8118373 -0.5834868 0.001320123 0.7972533 -0.6036435 0.7260891 0.6310399 -0.2730994 0.7260888 0.6310592 -0.2730555 0.5602291 0.738312 -0.3755512 0.5600707 0.7416907 -0.3690743 0.2049941 0.7762917 -0.5961113 0.2034192 0.812533 -0.5462699 0.5636976 0.7308817 -0.3847818 0.8277527 0.5487368 -0.1171051 0.5666491 0.7107896 -0.4167578 0.5391185 0.7672431 -0.3474036 0.4904302 0.7615081 -0.4237733 0.6698187 0.7372829 -0.08807301 0.745495 0.6334369 -0.2073522 0.7879514 0.6118961 -0.06867235 0.808663 0.5797117 -0.09999328 0.83661 0.520393 -0.1710991 0.1516487 0.8154554 -0.5586012 0.1725866 0.7884806 -0.5903492 0.1922687 0.7980812 -0.571051 0.20143 0.7783036 -0.5947012 0.2007532 0.7862511 -0.5843864 0.5711693 0.7808946 -0.2529217 0.6330372 0.7728469 -0.04440242 0.5267797 0.8240557 -0.2084115 0.4423432 0.8257343 -0.3499935 0.1817312 0.8367737 -0.516511 0.181662 0.836758 -0.5165609 0.1760841 0.8412299 -0.5112012 0.1731783 0.8370218 -0.5190414 0.1804094 0.8378477 -0.5152319 0.4861478 0.8573144 -0.1693294 0.4764748 0.8576061 -0.1936073 0.4987063 0.847559 -0.1814826 0.4473551 0.8720945 -0.1983051 0.4468426 0.8786252 -0.1683733 0.160367 0.8405243 -0.5174954 0.1611768 0.8456516 -0.5088177 0.2007336 0.8127009 -0.547013 0.4525294 0.8685116 -0.2022493 0.126114 0.8738311 -0.4695899 0.1612549 0.852119 -0.4978858 0.1477042 0.9061791 -0.3962611 0.1428263 0.909185 -0.3911311 0.1452098 0.9419159 -0.3028343 0.1388775 0.9457935 -0.2935777 0.1146962 0.9648402 -0.2364919 0.1667633 0.9437299 -0.2855941 0.1269673 0.9699622 -0.2074909 0.1372879 0.9778572 -0.1579477 0.1267679 0.9841057 -0.1243623 0.1326444 0.9866036 -0.09496742 0.1237871 0.9912864 -0.04503387 0.1288886 0.9910573 -0.03454333 0.4322909 0.8831771 -0.1819968 0.4337009 0.8822502 -0.1831341 0.4241565 0.8919809 -0.1564019 0.4124633 0.8995261 -0.1439686 0.4080085 0.9047492 -0.122303 0.398927 0.9105002 -0.1088422 0.3959084 0.9134949 -0.09372109 0.3877384 0.9185008 -0.07755839 0.3877127 0.9193782 -0.06650346 0.3815941 0.923147 -0.04675096 0.3818571 0.9233233 -0.04073333 0.3777058 0.9257674 -0.01712036 0.3782915 0.9255653 -0.01498717 0.3117239 -0.6302539 -0.7110615 0.2048201 -0.7610574 -0.6155 0.1767826 -0.7497648 -0.6376526 0.2205786 -0.7434188 -0.6314062 0.1854176 -0.6821517 -0.7073113 0.3842387 -0.7014552 -0.6002677 0.5331593 -0.6980205 -0.4780258 0.170726 -0.7514557 -0.6373124 0.3655555 -0.7999655 -0.4758408 0.43219 -0.7071509 -0.5595976 0.1793054 -0.732353 -0.6568932 0.1792445 -0.7324147 -0.6568412 0.2288204 -0.7322264 -0.6414716 0.1384571 -0.8800712 -0.4542075 0.1831764 -0.8798275 -0.4385772 0.4423798 -0.6424368 -0.6257597 0.4860346 -0.6686552 -0.5627349 0.833741 -0.5150724 -0.1989386 0.9070405 -0.4107469 -0.09254425 0.9363916 -0.3503439 -0.02073633 0.9476273 -0.3186945 0.02089434 0.5379154 -0.6805209 -0.4975323 0.6430047 -0.6652096 -0.3795276 0.5861201 -0.6551056 -0.4767599 0.7715628 -0.5612624 -0.2994588 0.7714375 -0.561326 -0.2996624 0.2324837 -0.715049 -0.6592848 0.2105549 -0.716729 -0.6648054 0.230666 -0.7238146 -0.6502967 0.1727563 -0.7458111 -0.6433671 0.1996996 -0.7418011 -0.6401963 0.4892789 -0.7499262 -0.4452158 0.5587725 -0.7185611 -0.4140573 0.8435028 -0.5087779 -0.1721861 0.8165012 -0.5660171 -0.1138002 0.7916243 -0.6039775 -0.09242451 0.7610553 -0.6100022 -0.2206636 0.6731914 -0.732324 -0.1025432 0.2021559 -0.7843288 -0.5864822 0.1426296 -0.78422 -0.6038675 0.1844567 -0.7989555 -0.5724037 0.4491081 -0.8024222 -0.3929638 0.5352475 -0.8127104 -0.2302438 0.6294159 -0.7741901 -0.06682276 0.5836204 -0.7656872 -0.2703898 0.5034696 -0.8394818 -0.2044226 0.4844709 -0.848185 -0.2141736 0.4901986 -0.8497717 -0.1938904 0.1837838 -0.7995124 -0.5718421 0.1778954 -0.7987275 -0.5747936 0.1792764 -0.8030977 -0.5682377 0.1615505 -0.8055192 -0.5701231 0.1702125 -0.8043501 -0.5692527 0.4453181 -0.8706206 -0.2090733 0.4680604 -0.8602353 -0.202274 0.1289336 -0.9914371 -0.02070897 0.3783233 -0.9256404 -0.007833421 0.1274269 -0.9917207 -0.01589125 0.1318008 -0.9887632 -0.07054084 0.1233853 -0.990822 -0.05520981 0.141393 -0.978992 -0.1469106 0.1115167 -0.9866743 -0.118482 0.1501567 -0.9644662 -0.2173889 0.1149678 -0.9776008 -0.1762927 0.1713927 -0.9412961 -0.2908377 0.1000035 -0.9635848 -0.2479992 0.1326645 -0.9440369 -0.3019844 0.1782649 -0.9141255 -0.3641377 0.1080168 -0.9446732 -0.3097177 0.2137316 -0.8744739 -0.4354473 0.08036899 -0.9123328 -0.4014846 0.2446822 -0.8044151 -0.5413383 0.08059608 -0.8533388 -0.5150896 0.3781315 -0.9257261 -0.006931006 0.3797027 -0.9247199 -0.02681428 0.3784892 -0.9253025 -0.02368944 0.3846653 -0.9213779 -0.05563718 0.3800247 -0.923637 -0.04976052 0.3923858 -0.9161692 -0.08165329 0.3860384 -0.919602 -0.07284647 0.4037011 -0.9083452 -0.1092461 0.3906139 -0.9150252 -0.1007451 0.4155765 -0.8994433 -0.1352701 0.4014169 -0.9075968 -0.1230144 0.4340494 -0.8860483 -0.1628485 0.4089087 -0.8991025 -0.1562326 0.4621189 -0.8633551 -0.2026435 0.4291154 -0.8811575 -0.1985487 -0.9894344 0.004014074 -0.1449261 -0.8185049 0.1519911 -0.5540294 -0.8161578 0.07241737 -0.5732733 -0.8047733 0.1836771 -0.5644491 -0.800325 -0.005804538 -0.5995383 -0.7617542 0.1525238 -0.6296564 -0.762613 -0.0717433 -0.6428642 -0.7437276 0.09361344 -0.6618956 -0.9890138 -0.0434007 -0.1413089 -0.9902663 0.01731765 -0.138104 -0.990742 -0.02458286 -0.1335142 -0.9920067 0.02854394 -0.1229145 -0.9918215 -0.005123138 -0.1275309 -0.9924761 0.03980207 -0.1157893 -0.9749447 0.2006238 -0.09608888 -0.9079573 0.3128871 -0.2787746 -0.9317294 0.03415018 -0.3615441 -0.9278816 0.1190069 -0.3533739 -0.9250908 -0.0152269 -0.3794407 -0.911314 0.09791976 -0.3998983 -0.9108379 -0.05944216 -0.4084619 -0.9045717 0.06182342 -0.4218152 -0.8664402 0.09344577 -0.4904584 -0.8221568 0.3268986 -0.4660425 -0.8678405 0.2804758 -0.4101052 -0.9315842 -0.2351601 -0.2772198 -0.7393278 0.6733301 0.00458008 -0.7477723 0.6639507 -0.002459764 -0.7482237 0.6634463 -6.44469e-4 -0.7953217 0.6046181 -0.04359418 -0.8102189 0.586078 -0.007603287 -0.7363231 0.6766242 -0.002863764 -0.745945 0.6659145 -0.01113629 -0.7430514 0.6690863 -0.01408094 -0.7997366 0.5966767 -0.06632035 -0.7762156 0.6237952 -0.09148299 -0.8558163 0.4845782 -0.1810045 -0.8342643 0.5196659 -0.1842568 -0.8890055 0.4475181 -0.09693849 -0.8802934 0.4699449 -0.06507962 -0.8944683 0.4440518 -0.05238711 -0.9196738 0.382647 -0.08821165 -0.9323526 0.3487667 -0.09529215 -0.870952 0.3525359 -0.3422883 -0.8663604 0.3824313 -0.321195 -0.8895542 0.3283963 -0.317568 -0.8556568 0.4517417 -0.2525486 -0.8707079 0.4165421 -0.2614583 -0.8346414 0.5101929 -0.2075504 -0.8713288 0.2215852 -0.4378198 -0.8713417 0.2216048 -0.437784 -0.9826381 0.1369845 -0.1251312 -0.8852564 0.2523927 -0.3906651 -0.8712025 0.2213581 -0.4381858 -0.9561212 0.2540675 -0.1458837 -0.951185 0.2903663 -0.1045684 -0.9621704 0.250828 -0.1063649 -0.9774729 0.1334959 -0.1634796 -0.9850323 0.09478449 -0.1439699 -0.7017294 0.1154468 -0.7030277 -0.5576071 0.4774364 -0.6790647 -0.6958066 0.1203482 -0.7080745 -0.7200149 0.1433884 -0.6789833 -0.6662216 0.06150776 -0.7432131 -0.7322872 0.3717057 -0.5706053 -0.8092538 0.4093762 -0.4213308 -0.7627174 0.3729867 -0.5283402 -0.7232577 0.2798916 -0.6313153 -0.7232391 0.2798254 -0.631366 -0.7512266 0.5585199 -0.3517304 -0.7520101 0.5588022 -0.3496012 -0.7427591 0.4926008 -0.4534901 -0.7161855 0.6957616 -0.05471813 -0.7058321 0.6938294 -0.1428354 -0.6982001 0.6779956 -0.2298665 -0.6981915 0.6780117 -0.2298452 -0.69192 0.7184661 -0.07108575 -0.7396259 0.6593262 -0.1350651 -0.6220782 0.7829494 0.002996921 -0.6689442 0.7307508 -0.1360772 -0.7147313 0.6925922 -0.09734183 -0.7145497 0.6927639 -0.09745198 -0.7005091 0.7123233 -0.04338866 -0.7907145 0.436488 -0.4292424 -0.7802688 0.5108243 -0.3608867 -0.7718091 0.5410712 -0.3339951 -0.7754742 0.5697872 -0.2719972 -0.7754833 0.5697529 -0.2720431 -0.6960282 0.1859008 -0.6935313 -0.7901825 0.1820908 -0.5851962 -0.7902086 0.1820645 -0.5851691 -0.6567938 0.02071112 -0.7537858 -0.6479073 0.1302682 -0.7504974 -0.5766154 0.2278457 -0.7846025 -0.694695 0.1106177 -0.710748 -0.769308 0.2977759 -0.5652388 -0.7667213 0.3438076 -0.5421577 -0.7635197 0.3352215 -0.551964 -0.7907306 0.4365499 -0.4291496 -0.1226984 0.9888546 -0.08433198 -0.5366925 0.843777 0.001410603 -0.5293151 0.8484172 -0.003720581 -0.5327007 0.8462318 -0.0110324 -0.4675688 0.88249 -0.05090004 -0.4804171 0.8728654 -0.0854724 -0.4059502 0.9047892 -0.1286895 -0.3954173 0.9069592 -0.1451557 -0.538787 0.8424354 -0.00334984 -0.5290077 0.8485652 -0.009376049 -0.5286341 0.8488493 -9.0979e-4 -0.4488752 0.892219 -0.04956394 -0.4465191 0.8947618 -0.00468856 -0.3520543 0.9341242 -0.05890518 -0.3658548 0.9298198 -0.03981906 -0.2562389 0.9615011 -0.09928357 -0.280313 0.9573732 -0.06972223 -0.2525127 0.9658143 -0.05865246 -0.09678149 0.9858912 -0.1365725 -0.3010414 0.9333795 -0.1953893 -0.3371539 0.9209691 -0.1953029 -0.3269929 0.9187144 -0.2214487 -0.212528 0.9364839 -0.2789801 -0.1968068 0.9254556 -0.3237271 -0.04232156 0.9916377 -0.1219169 -0.006297349 0.9893962 -0.1451057 -0.0277056 0.9897873 -0.1398336 0.02577537 0.9871433 -0.1577462 -0.01068204 0.9882551 -0.1524401 0.05651479 0.9832333 -0.1733737 -0.067649 0.9217543 -0.381828 -0.1624297 0.9230458 -0.3487162 -0.09021091 0.9094795 -0.4058439 -0.1296766 0.9091174 -0.3958406 -0.01683712 0.8955003 -0.4447425 -0.08743691 0.8963825 -0.4345727 0.04678702 0.8650718 -0.4994615 -0.2681415 0.8597048 -0.4347504 -0.594803 0.8038637 0.003569304 -0.5637128 0.8233799 -0.06537115 -0.486303 0.8666012 -0.1118561 -0.4837394 0.8648248 -0.1344407 -0.2680773 0.8596724 -0.434854 -0.3286611 0.8843892 -0.3314177 -0.3251674 0.8735235 -0.362247 -0.4637611 0.8582363 -0.2199004 -0.4637342 0.8582383 -0.2199492 -0.1766102 0.8366611 -0.5184661 -0.1000998 0.8283013 -0.5512688 -0.05971777 0.7939877 -0.6049938 -0.1734475 0.8535941 -0.491216 -0.1735045 0.8536095 -0.491169 -0.1362096 0.8023654 -0.5810824 -0.1405858 0.8020176 -0.58052 -0.04393678 0.7927728 -0.6079316 -0.5514057 0.8341179 -0.01411038 -0.5466824 0.8369423 -0.02580994 -0.512613 0.8481254 -0.1338335 -0.5261539 0.8397716 -0.133962 -0.4412008 0.8766109 -0.1920818 -0.3670251 0.8926404 -0.2616978 -0.3083639 0.8852451 -0.348214 -0.4517206 0.8211725 -0.3487469 -0.2701795 0.8777069 -0.3957699 -0.7363231 -0.6766242 -0.002863764 -0.7812279 -0.6227556 -0.04311197 -0.7674431 -0.6363788 -0.07780313 -0.7393278 -0.6733301 0.00458008 -0.7928968 -0.6077886 -0.04368048 -0.7967261 -0.6043406 3.82133e-5 -0.8812571 -0.4635289 -0.09234195 -0.8742766 -0.4821603 -0.05623102 -0.8510075 -0.4972825 -0.1688094 -0.8279263 -0.532324 -0.1765488 -0.8296959 -0.5229099 -0.1953708 -0.8591766 -0.4538172 -0.236359 -0.8626481 -0.4316189 -0.2637113 -0.9620777 -0.2512179 -0.1062836 -0.951117 -0.2906367 -0.1044351 -0.9560444 -0.2543799 -0.1458425 -0.9197852 -0.3851878 -0.07500505 -0.9274365 -0.3584005 -0.1068201 -0.886635 -0.4600095 -0.04764163 -0.9923815 -0.08933168 -0.08484619 -0.9721586 -0.1906093 -0.1362937 -0.9413033 -0.1748942 -0.2887216 -0.9413151 -0.1748813 -0.288691 -0.8895731 -0.3285833 -0.3173212 -0.8663138 -0.3826794 -0.3210247 -0.8709515 -0.3526793 -0.3421414 -0.8809202 -0.2927229 -0.3718779 -0.841471 -0.2579178 -0.4747684 -0.9422648 -0.1366317 -0.305727 -0.9935057 -0.03861802 -0.1070284 -0.9405699 -0.07789027 -0.3305472 -0.9925588 -0.01527446 -0.1208049 -0.9927093 -0.02556008 -0.1177927 -0.9911409 0.005800127 -0.1326884 -0.9914015 -0.009098172 -0.1305391 -0.9889286 0.03222441 -0.1448515 -0.9352664 -0.1126676 -0.3355337 -0.935339 -0.1042125 -0.3380544 -0.9238206 -0.03886568 -0.3808479 -0.923924 -0.06310588 -0.3773356 -0.9060417 0.02417272 -0.4224978 -0.8395869 -0.1388691 -0.5251755 -0.8243764 -0.2309733 -0.5167735 -0.8238576 -0.1571887 -0.5445646 -0.8238604 -0.1573094 -0.5445253 -0.7935119 -0.08416646 -0.6027064 -0.7935189 -0.08817297 -0.602124 -0.7469703 0.009778976 -0.6647856 -0.6735 -0.05388468 -0.7372207 -0.8095285 -0.5856589 -0.04083526 -0.7094533 -0.6717779 -0.2130506 -0.751336 -0.454351 -0.4786015 -0.7779167 -0.5223641 -0.3492587 -0.7927204 -0.5164114 -0.3239037 -0.7557372 -0.5911965 -0.2816882 -0.7094415 -0.6718 -0.21302 -0.7513228 -0.4542998 -0.4786711 -0.7761476 -0.3302363 -0.5371584 -0.7801995 -0.3323646 -0.5299268 -0.6541599 -0.02565383 -0.7559211 -0.6814886 -0.07006794 -0.7284668 -0.7336526 -0.1328514 -0.6664116 -0.6955775 -0.1184682 -0.7086165 -0.7386719 -0.2916985 -0.6076807 -0.738701 -0.2918238 -0.6075852 -0.6983755 -0.1716047 -0.6948551 -0.6974141 -0.1168731 -0.7070745 -0.7520874 -0.2299069 -0.6176629 -0.7958034 -0.432095 -0.4242532 -0.7958075 -0.4320929 -0.4242478 -0.7683008 -0.3372824 -0.5440168 -0.7691154 -0.3307631 -0.5468614 -0.7520848 -0.2299086 -0.6176654 -0.6974903 -0.7165658 0.006395876 -0.7097756 -0.7036303 -0.03351241 -0.7179341 -0.6931517 -0.06412082 -0.7350588 -0.6683881 -0.1137807 -0.7350387 -0.668504 -0.1132276 -0.7810629 -0.5725841 -0.2491755 -0.7853364 -0.523414 -0.3305823 -0.7475585 -0.6014725 -0.2817573 -0.7815196 -0.5150813 -0.3520208 -0.1407585 -0.8231959 -0.5500323 -0.08080548 -0.9106487 -0.405203 -0.005264163 -0.9885967 -0.1504955 -0.2169533 -0.8912847 -0.3981746 0.006447196 -0.8878439 -0.4600999 -0.1491073 -0.890973 -0.4288756 -0.02344483 -0.870109 -0.4923015 0.1044251 -0.8578302 -0.5032126 -0.05523622 -0.9881322 -0.143331 0.03372281 -0.9851721 -0.1682219 -0.03473597 -0.9853204 -0.1671442 0.0750302 -0.9804928 -0.1816709 -0.01274418 -0.9807032 -0.1950866 -0.5377243 -0.8431205 7.78505e-4 -0.4827006 -0.8750373 -0.03619617 -0.4644876 -0.8855797 -6.9964e-5 -0.3857689 -0.9212304 -0.05017137 -0.3641759 -0.9302276 -0.04530537 -0.5391298 -0.8422226 -3.9116e-4 -0.4701724 -0.8813498 -0.04648089 -0.5002943 -0.8627424 -0.0733568 -0.4028859 -0.9052314 -0.1350524 -0.4275763 -0.8936222 -0.1364474 -0.3106306 -0.9281609 -0.2050027 -0.3448702 -0.9196571 -0.1878708 -0.214101 -0.9156127 -0.3403148 -0.2395038 -0.9208605 -0.3076587 -0.1846839 -0.9311053 -0.3145393 -0.340757 -0.9113472 -0.2309355 -0.2607495 -0.9595321 -0.1063387 -0.2871776 -0.9552214 -0.07128226 -0.2562951 -0.9646182 -0.06184482 -0.1468697 -0.9815821 -0.1221719 -0.09573054 -0.989854 -0.1049992 -0.05938458 -0.7371152 -0.6731529 -0.08737373 -0.762762 -0.6407495 -0.1797429 -0.7829634 -0.5955342 -0.1797143 -0.7829475 -0.5955637 -0.2862231 -0.8152768 -0.5033887 -0.2990128 -0.8394449 -0.4537881 -0.2446473 -0.8119763 -0.5299456 -0.460117 -0.8690599 -0.181734 -0.4466931 -0.8542739 -0.2658597 -0.4251547 -0.8360593 -0.3467688 -0.4251331 -0.8360596 -0.3467941 -0.5905871 -0.7973873 -0.1240177 -0.5410749 -0.8161184 -0.2029503 -0.5690069 -0.8184738 -0.07957315 -0.6139226 -0.78654 -0.06673848 -0.642134 -0.7665849 0.003403961 -0.4130284 -0.8613028 -0.2959143 -0.469558 -0.8609863 -0.1954943 -0.541905 -0.8360906 -0.08539104 -0.5396937 -0.8345585 -0.1106476 -0.5707467 -0.8205605 -0.03047382 -0.4616553 -0.8229662 -0.3310609 -0.4137794 -0.8619125 -0.293076 -0.4132127 -0.8613553 -0.2955037 -0.1316967 -0.7896269 -0.5992874 -0.2103255 -0.8261837 -0.52267 -0.2654024 -0.8321167 -0.486974 -0.3013084 -0.8582611 -0.4154533 -0.301277 -0.8582473 -0.4155043 -0.1316533 -0.7895833 -0.5993545 -0.09707707 -0.755059 -0.6484305 -0.04671537 -0.73989 -0.671104 -0.1580486 -0.9658702 -0.2052202 -0.1580417 -0.9658737 -0.2052093 -0.1253865 -0.9807903 -0.1494281 -0.4681414 -0.7069685 -0.5301314 -0.3462063 -0.8313825 -0.4346776 -0.4433889 -0.7070247 -0.5509286 -0.54 -0.5555415 -0.6322766 -0.612534 -0.2588559 -0.7468573 -0.6221131 -0.1950731 -0.758236 -0.6208822 -0.2588328 -0.7399398 -0.1251134 -0.8355695 -0.534949 -0.1213209 -0.7071908 -0.6965361 -0.06701636 -0.6671941 -0.7418631 -0.1199771 -0.6652263 -0.7369393 -0.2608919 -0.5119718 -0.8184256 -0.2974922 -0.5064023 -0.8093548 -0.436659 -0.3215346 -0.840205 -0.4570721 -0.3163431 -0.8312715 -0.5824933 -0.1088542 -0.8055137 -0.5886266 -0.1067435 -0.8013268 -0.03677368 -0.7940856 -0.6066927 -0.08185452 -0.7982366 -0.5967566 -0.2463929 -0.6251705 -0.7405758 -0.328297 -0.5608373 -0.7600544 -0.4349048 -0.3993321 -0.8070884 -0.4791839 -0.3527045 -0.8037303 -0.5848053 -0.1366813 -0.7995755 -0.5970969 -0.1195703 -0.7932077 -0.04311096 -0.907616 -0.4175822 -0.0868107 -0.9135744 -0.3972981 -0.26634 -0.7392606 -0.6185118 -0.3499804 -0.6706146 -0.6540564 -0.4587481 -0.4824465 -0.7461874 -0.5021548 -0.4287615 -0.7510021 -0.5970124 -0.1672837 -0.784597 -0.6081919 -0.1468768 -0.7800832 -0.0521838 -0.9763724 -0.2096994 -0.1789752 -0.9358032 -0.3037111 -0.2935494 -0.8287031 -0.4765291 -0.3781494 -0.7624785 -0.5250045 -0.4906378 -0.5546821 -0.6720137 -0.5324517 -0.4976993 -0.6846828 -0.6131491 -0.1950357 -0.7655125 -0.6228345 -0.1725896 -0.7630793 -0.5862228 -0.104716 -0.803354 -0.5346675 -0.2196663 -0.8160131 -0.09521204 -0.6448631 -0.7583444 -0.2030627 -0.5844469 -0.7856127 -0.2796276 -0.4914976 -0.8247658 -0.446748 -0.3076635 -0.8400949 -0.1980156 -0.5902019 -0.782593 -0.1805785 -0.5803304 -0.7941083 -0.5613257 -0.2745106 -0.7807416 -0.5140146 -0.2532685 -0.819539 -0.1939175 -0.5768586 -0.7934924 -0.1737514 -0.5667735 -0.8053436 -0.5505301 -0.2331603 -0.801594 -0.4949229 -0.2112131 -0.8428763 -0.5863059 -0.333739 -0.7381488 -0.6526685 -0.7576432 8.55772e-4 -0.6505939 -0.75613 -0.07067525 -0.6294836 -0.7738156 -0.07042616 -0.670834 -0.7416074 5.7459e-4 -0.6673505 -0.7409508 -0.07506918 -0.6850757 -0.7249763 -0.0712794 -0.6854426 -0.7246242 -0.07133257 -0.6712043 -0.7109733 -0.2097662 -0.6972041 -0.6835727 -0.2159513 -0.6133226 -0.7581776 -0.2213645 -0.5945362 -0.7766678 -0.2081201 -0.5840869 -0.7829658 -0.2140256 -0.5708681 -0.7696322 -0.2859651 -0.5636599 -0.7702512 -0.29833 -0.6971893 -0.6835967 -0.2159231 -0.6812773 -0.6669943 -0.3016286 -0.6881342 -0.6659437 -0.2880807 -0.6645071 -0.6415565 -0.3831914 -0.6954414 -0.6197814 -0.3636376 -0.6445935 -0.565667 -0.5143153 -0.6634948 -0.5646762 -0.4908314 -0.5431333 -0.7481074 -0.3812368 -0.5185551 -0.7755039 -0.3601311 -0.5136667 -0.7725778 -0.3731891 -0.4758725 -0.7319208 -0.4876856 -0.4373243 -0.7458882 -0.5023927 -0.4099311 -0.716447 -0.5645 -0.3894725 -0.7114506 -0.5849353 -0.6717169 -0.5401546 -0.5069808 -0.6330476 -0.4981536 -0.5925316 -0.6518973 -0.5014801 -0.5688127 -0.5975623 -0.4433514 -0.668101 -0.6321487 -0.4365383 -0.6401738 -0.6226447 -0.4197832 -0.6603754 -0.5467106 -0.33761 -0.7662423 -0.3466456 -0.6632214 -0.6633055 -0.3528507 -0.6861763 -0.6361278 -0.3194596 -0.6857765 -0.6539543 -0.2637056 -0.6238516 -0.7357096 -0.2195679 -0.6234109 -0.7504324 -0.6208819 0.2588148 -0.7399464 -0.6208735 0.2588471 -0.7399421 -0.4545062 0.7071183 -0.5416715 -0.4545319 0.7070891 -0.541688 -0.1663642 0.9659267 -0.1982639 -0.1663646 0.9659265 -0.1982645 -0.6060702 0.2587665 -0.7521428 -0.6011509 0.2282645 -0.7658414 -0.4265641 0.7066568 -0.5645169 -0.4297511 0.6372883 -0.63967 -0.1403356 0.965373 -0.219911 -0.07435405 0.8884543 -0.4529026 -0.07444548 0.8884404 -0.4529144 -0.1587301 0.9092808 -0.3847249 -0.3852398 0.4526265 -0.8041888 -0.3648325 0.5334812 -0.7630826 -0.5724895 0.156477 -0.8048421 -0.569003 0.1866795 -0.800866 -0.585227 0.2251191 -0.7789935 -0.5846595 0.1932644 -0.7879227 -0.3916544 0.6294993 -0.671072 -0.403963 0.5501694 -0.7308403 -0.2022265 0.8333218 -0.51447 -0.1066438 0.7953227 -0.5967319 -0.1454011 0.6894642 -0.7095758 -0.569195 0.1540955 -0.8076335 -0.569153 0.1541317 -0.8076561 -0.3720266 0.4434234 -0.8154582 -0.3720651 0.4433911 -0.8154581 -0.1293064 0.6783432 -0.7232776 -0.1293395 0.6783261 -0.7232878 -0.1881174 0.7456799 -0.6391974 -0.1956095 0.6692897 -0.7167903 -0.607245 0.2716527 -0.7466313 -0.5898355 0.4305047 -0.6831982 -0.4375327 0.5543804 -0.7079742 -0.4562824 0.2742423 -0.8465209 -0.2387781 0.7202737 -0.6512993 -0.5854874 0.1656482 -0.7935776 -0.5799399 0.2462029 -0.7765654 -0.3800824 0.4490854 -0.8086161 -0.3738589 0.4953781 -0.784111 -0.1281461 0.6775306 -0.7242451 -0.1267129 0.6909265 -0.7117334 -0.3263683 0.7673918 -0.5519001 -0.6025846 0.7980546 -8.70368e-4 -0.5990178 0.797729 -0.06932741 -0.6150659 0.7884752 -0.001016378 -0.6119838 0.787043 -0.07771223 -0.5771101 0.8137738 -0.06867659 -0.5690293 0.8071948 -0.1569786 -0.5172016 0.8229848 -0.2349441 -0.5529205 0.8013027 -0.2284575 -0.5640069 0.8123365 -0.1483435 -0.6326939 0.7595894 -0.1507403 -0.6397024 0.765354 -0.07081121 -0.6283433 0.6872259 -0.3645617 -0.6553798 0.7162413 -0.239741 -0.6483013 0.7253034 -0.2316042 -0.6241742 0.7414832 -0.2461895 -0.6372952 0.7543195 -0.157661 -0.517255 0.8229623 -0.2349056 -0.4846393 0.7872967 -0.3811678 -0.4551238 0.8161299 -0.3560819 -0.4139478 0.7693731 -0.4865309 -0.4017142 0.7926068 -0.4586942 -0.3919875 0.7851912 -0.4793964 -0.3474168 0.731868 -0.5862345 -0.5538843 0.4437691 -0.7044723 -0.6195957 0.5206404 -0.5873967 -0.6036624 0.5594508 -0.5679848 -0.6362255 0.5968629 -0.4888476 -0.6363887 0.6121872 -0.4692935 -0.6163722 0.6135231 -0.4936342 -0.6534792 0.655445 -0.3786249 -0.5818225 0.4205244 -0.6961622 -0.5818269 0.4205702 -0.6961309 -0.5880241 0.4466213 -0.6743568 -0.2358652 0.7169541 -0.6560065 -0.2629891 0.6917202 -0.6725771 -0.2201585 0.6987273 -0.6806691 0.001229822 0.7961211 -0.6051361 0.02273499 0.7933385 -0.6083562 0.022619 0.793794 -0.6077661 0.08719187 0.7823379 -0.6167212 0.08694583 0.7830557 -0.6158443 0.2475298 0.7389034 -0.6266984 0.409597 0.6695119 -0.6196646 0.4092376 0.6695901 -0.6198175 0.4096115 0.6694945 -0.6196737 0.4090831 0.6698784 -0.6196081 0.4094719 0.6696345 -0.6196148 0.2473933 0.7393553 -0.626219 0.9899316 -0.01142829 -0.1410845 0.9906625 -0.1361847 -0.006456375 0.9956209 0.04545575 -0.08168751 0.9941585 -0.07631266 -0.07632476 0.994157 -0.07636356 -0.07629209 0.9999666 -0.005768716 -0.005799293 0.7739782 -0.5024926 -0.385304 0.9738382 -0.2119987 -0.08182901 0.9769081 -0.07122129 -0.2014402 0.9738036 -0.2120512 -0.08210319 0.9643314 -0.2378786 -0.1160984 0.9656098 -0.2363863 -0.1082553 0.9426826 -0.2800361 -0.1814648 0.9436689 -0.2951192 -0.1496457 0.8981115 -0.3298028 -0.2909052 0.8971212 -0.3765404 -0.2310649 0.8488345 -0.374377 -0.3732584 0.8624409 -0.3985312 -0.3120397 0.8379706 -0.4092862 -0.3609572 0.789911 -0.3911164 -0.4723014 0.974901 -0.07402706 -0.2099722 0.9723754 -0.08086884 -0.2189665 0.9712591 -0.08209002 -0.2234214 0.9626459 -0.09925448 -0.2519155 0.963185 -0.1003789 -0.249397 0.9431739 -0.1158167 -0.3114636 0.946357 -0.1287499 -0.2963646 0.9239053 -0.1276288 -0.3607076 0.9300385 -0.1424219 -0.3387396 0.8983635 -0.131393 -0.4191407 0.9025058 -0.1776943 -0.3923112 0.5673376 -0.5500894 -0.6128048 0.8709193 -0.1948727 -0.4511366 0.8607953 -0.1437193 -0.4882381 0.6932078 -0.5502873 -0.4654535 0.6919875 -0.4345561 -0.5764671 0.8426651 -0.2151165 -0.4935996 0.8293599 -0.1567376 -0.5362793 0.6668948 -0.5301199 -0.5236644 0.6090222 -0.4711418 -0.6380575 0.8259693 -0.2059119 -0.5247621 0.8210566 -0.19351 -0.5370477 0.5699482 -0.5553633 -0.605583 0.5693793 -0.5521611 -0.6090365 0.7977253 -0.1919248 -0.5716635 0.7962909 -0.1687437 -0.5809014 0.5164324 -0.4963772 -0.6977874 0.517987 -0.4901321 -0.7010421 0.7077773 0.00114113 -0.7064348 0.7095534 -0.003272831 -0.7046441 0.6982014 -0.02300053 -0.7155318 0.734409 -0.06311184 -0.6757665 0.6530677 -0.1355458 -0.7450704 0.6505202 -0.1437753 -0.7457561 0.6980855 -0.2059968 -0.685742 0.638997 -0.2155455 -0.7383921 0.6127262 -0.270727 -0.742478 0.7723326 -0.1391836 -0.6197826 0.774605 -0.1408318 -0.6165658 0.7800357 -0.126591 -0.612796 0.7525386 -0.08398866 -0.6531706 0.7555218 -0.07545465 -0.6507638 0.7266945 -0.03828352 -0.6858933 0.7310985 -0.02861505 -0.6816716 0.7097649 -0.004978358 -0.7044211 0.7114761 0.002053439 -0.7027073 0.709227 0.004259586 -0.7049674 0.659386 -0.34477 -0.6680897 0.525003 -0.367035 -0.7678915 0.4881916 -0.4373749 -0.7552298 0.9637161 0.2586125 -0.06611239 0.9637164 0.06611764 -0.2586103 0.9697616 0.09148734 -0.2262579 0.9684138 0.1059628 -0.2257134 0.9927726 4.72211e-4 -0.1200103 0.9706935 0.2189271 -0.09912115 0.9927735 0.1200025 -4.82422e-4 0.9927756 0.1199852 -4.81732e-4 0.5911905 0.6149296 -0.5218768 0.6482251 0.6340395 -0.4216613 0.6484817 0.6337148 -0.4217548 0.8300907 0.2262449 -0.5096693 0.83001 0.2261175 -0.5098574 0.8299057 0.2260493 -0.5100572 0.6500673 0.590933 -0.4777143 0.6794201 0.5977175 -0.4255846 0.7634856 0.5136904 -0.3914232 0.7801673 0.5113111 -0.3604164 0.7806867 0.5111633 -0.3595001 0.8159921 0.488413 -0.309208 0.7880306 0.4893289 -0.3735842 0.8391284 0.4709322 -0.272188 0.87031 0.4190716 -0.2587268 0.8929217 0.3975118 -0.2113654 0.9049781 0.3781993 -0.1948849 0.9275109 0.3463761 -0.1405243 0.9327737 0.3322386 -0.1398243 0.8088424 0.203724 -0.5516071 0.8450335 0.2121024 -0.4908472 0.866064 0.1808551 -0.4660737 0.8812603 0.1783146 -0.4377034 0.8912576 0.1685969 -0.4209929 0.9063621 0.1627379 -0.3899028 0.9106179 0.1521306 -0.3842281 0.9265606 0.1364657 -0.3505174 0.9268795 0.1358984 -0.3498942 0.9419299 0.115809 -0.3152086 0.9399645 0.1249712 -0.3175674 0.6887924 0.6426601 -0.3354893 0.8139163 0.2207048 -0.5374287 0.6887641 0.6426749 -0.3355191 0.5915 0.5546256 -0.5852506 0.8138993 0.2206482 -0.5374778 0.8142961 0.2201729 -0.5370715 0.4648696 0.5584863 -0.6870148 0.5652444 0.4945414 -0.6602482 0.7141115 0.3559179 -0.6027995 0.4621523 0.4528536 -0.7624558 0.4631381 0.6400889 -0.6130166 0.7063379 -0.001135349 -0.707874 0.7127549 0.004367351 -0.7013997 0.6598234 0.1225741 -0.741356 0.7189373 0.03936028 -0.6939596 0.6993115 0.01830911 -0.7145826 0.5176783 0.3996514 -0.7564972 0.6597068 0.1228145 -0.74142 0.7021974 0.1764891 -0.6897612 0.6228428 0.2171286 -0.7516131 0.6805623 0.3023952 -0.6673771 0.6158723 0.2858828 -0.7341474 0.5025611 0.3715758 -0.7806175 0.7688528 0.1262418 -0.6268401 0.7094913 -0.004324495 -0.704701 0.7103796 -8.74852e-4 -0.7038182 0.7084156 0.004346966 -0.7057822 0.7279298 0.02586066 -0.6851639 0.723562 0.0322324 -0.6895065 0.7507933 0.06631964 -0.6571994 0.7460098 0.0705856 -0.6621837 0.7768334 0.1158165 -0.618964 0.7672566 0.1245337 -0.6291333 0 0 -1 -0.6791808 0 0.733971 -0.6786826 0 0.7344318 -0.2973482 0 0.9547691 -0.2977405 0 0.954647 -0.2962558 0 0.9551087 0.6505188 0 0.7594901 0.6504684 0 0.7595334 -0.2599059 0 0.9656341 -0.2817229 0 0.9594959 -0.2969409 0 0.954896 0.8656446 -0.201632 -0.4582621 0.650869 0 0.7591901 0.651155 0 0.7589449 0.9610607 0 0.2763375 0.8940551 -0.1418277 0.4249122 0.9433789 0 -0.331717 0.9433889 0 -0.3316887 0.9977445 0 0.06712651 0.9977437 0 0.06713891 0.999854 0 -0.017089 0.8264161 5.30871e-4 0.5630596 0.98552 0.14577 0.08661115 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 5 2 4 2 6 2 5 3 6 3 7 3 7 4 6 4 8 4 7 5 8 5 9 5 9 5 8 5 10 5 9 6 10 6 11 6 11 7 10 7 12 7 11 8 12 8 13 8 13 9 12 9 14 9 13 10 14 10 15 10 15 11 14 11 16 11 15 12 16 12 17 12 17 13 16 13 18 13 17 14 18 14 19 14 19 15 18 15 20 15 19 16 20 16 21 16 22 17 23 17 24 17 22 18 24 18 25 18 25 19 24 19 26 19 25 20 26 20 27 20 27 21 26 21 28 21 27 22 28 22 29 22 29 23 28 23 30 23 29 24 30 24 31 24 31 25 30 25 32 25 31 26 32 26 33 26 33 27 32 27 34 27 33 28 34 28 35 28 35 29 34 29 36 29 35 30 36 30 37 30 37 31 36 31 38 31 37 32 38 32 39 32 39 33 38 33 40 33 39 34 40 34 41 34 41 35 40 35 42 35 41 36 42 36 21 36 21 36 42 36 43 36 21 37 43 37 19 37 2 38 1 38 44 38 45 39 46 39 47 39 45 40 47 40 1 40 1 41 47 41 48 41 1 42 48 42 44 42 45 43 49 43 46 43 46 44 49 44 50 44 46 45 50 45 51 45 51 46 50 46 52 46 52 47 53 47 51 47 51 48 53 48 54 48 51 49 54 49 55 49 55 50 54 50 56 50 55 51 56 51 57 51 57 52 56 52 58 52 58 53 56 53 59 53 58 54 59 54 22 54 22 55 59 55 60 55 22 56 60 56 23 56 61 57 62 57 63 57 63 58 62 58 64 58 63 59 64 59 2 59 2 60 64 60 65 60 2 61 65 61 0 61 66 62 67 62 68 62 68 63 67 63 69 63 68 64 69 64 70 64 70 65 69 65 71 65 70 66 71 66 72 66 72 67 71 67 73 67 72 68 73 68 74 68 74 69 73 69 75 69 74 70 75 70 76 70 63 71 77 71 61 71 61 72 77 72 78 72 61 73 78 73 79 73 79 74 78 74 66 74 79 75 66 75 80 75 80 76 66 76 68 76 75 77 81 77 76 77 76 78 81 78 82 78 76 79 82 79 83 79 83 80 82 80 84 80 83 80 84 80 85 80 85 81 84 81 86 81 85 82 86 82 87 82 87 83 86 83 88 83 87 84 88 84 89 84 89 85 88 85 90 85 89 85 90 85 91 85 4 86 3 86 92 86 92 87 3 87 93 87 92 88 93 88 94 88 94 89 93 89 95 89 91 90 90 90 96 90 96 91 90 91 97 91 96 92 97 92 98 92 98 93 97 93 99 93 98 94 99 94 100 94 99 95 101 95 100 95 100 96 101 96 102 96 100 97 102 97 103 97 103 98 102 98 104 98 103 99 104 99 105 99 105 100 104 100 106 100 105 101 106 101 107 101 107 102 106 102 108 102 107 103 108 103 109 103 109 104 108 104 110 104 109 105 110 105 111 105 111 106 110 106 112 106 111 107 112 107 113 107 113 108 112 108 114 108 113 109 114 109 95 109 95 110 114 110 115 110 95 111 115 111 94 111 116 112 117 112 118 112 118 113 117 113 119 113 118 114 119 114 120 114 120 115 119 115 121 115 120 116 121 116 122 116 122 117 121 117 123 117 124 118 125 118 126 118 126 118 125 118 127 118 128 119 129 119 130 119 130 120 131 120 128 120 128 121 131 121 132 121 128 120 132 120 133 120 133 120 132 120 134 120 133 122 134 122 135 122 135 120 136 120 133 120 133 123 136 123 137 123 133 124 137 124 138 124 139 125 140 125 141 125 142 126 143 126 144 126 144 127 143 127 139 127 145 128 146 128 147 128 139 129 141 129 144 129 144 130 141 130 148 130 144 131 148 131 149 131 149 132 148 132 145 132 149 133 145 133 150 133 150 134 145 134 147 134 150 135 147 135 151 135 152 136 106 136 104 136 104 137 153 137 152 137 152 138 153 138 154 138 152 139 154 139 142 139 142 140 154 140 155 140 142 141 155 141 143 141 156 142 157 142 158 142 158 143 157 143 159 143 158 142 159 142 160 142 160 144 161 144 158 144 158 142 161 142 162 142 158 142 162 142 163 142 164 145 165 145 166 145 167 145 168 145 169 145 169 146 168 146 164 146 166 145 170 145 164 145 164 147 170 147 171 147 164 148 171 148 169 148 172 149 173 149 174 149 175 150 176 150 177 150 177 151 176 151 178 151 177 152 178 152 179 152 179 153 178 153 172 153 172 154 178 154 180 154 172 155 180 155 173 155 174 156 181 156 172 156 172 157 181 157 182 157 172 158 182 158 183 158 184 159 185 159 186 159 187 160 188 160 189 160 189 161 188 161 190 161 189 162 190 162 186 162 186 163 190 163 191 163 186 164 191 164 184 164 192 165 193 165 194 165 190 166 195 166 191 166 191 167 195 167 192 167 191 168 192 168 196 168 196 169 192 169 194 169 189 170 197 170 187 170 187 171 197 171 198 171 187 172 198 172 199 172 200 173 201 173 202 173 202 174 201 174 203 174 199 175 204 175 187 175 187 176 204 176 205 176 187 177 205 177 200 177 200 178 205 178 206 178 200 179 206 179 201 179 134 180 132 180 207 180 134 180 207 180 208 180 208 181 207 181 209 181 208 181 209 181 210 181 210 182 209 182 146 182 210 182 146 182 145 182 18 183 16 183 211 183 211 184 16 184 14 184 211 185 14 185 212 185 41 142 21 142 211 142 211 142 21 142 20 142 211 186 20 186 18 186 14 187 12 187 212 187 212 188 12 188 10 188 212 189 10 189 8 189 8 190 6 190 212 190 212 191 6 191 4 191 212 192 4 192 92 192 213 193 172 193 183 193 214 194 215 194 216 194 213 195 183 195 217 195 211 196 212 196 218 196 218 197 212 197 219 197 218 198 219 198 220 198 220 199 219 199 221 199 220 200 221 200 222 200 222 201 221 201 217 201 222 202 217 202 216 202 216 203 217 203 183 203 216 204 183 204 214 204 81 205 75 205 194 205 88 206 193 206 90 206 90 145 193 145 97 145 88 145 86 145 193 145 193 207 86 207 84 207 193 145 84 145 194 145 194 208 84 208 82 208 194 209 82 209 81 209 223 210 224 210 225 210 224 211 226 211 225 211 225 212 226 212 227 212 225 213 227 213 228 213 225 214 229 214 223 214 223 215 229 215 230 215 223 216 230 216 231 216 232 217 233 217 234 217 234 218 233 218 235 218 234 219 235 219 236 219 237 220 238 220 235 220 235 221 238 221 239 221 235 222 239 222 236 222 240 223 241 223 242 223 240 224 242 224 243 224 242 225 244 225 245 225 243 226 242 226 246 226 246 227 242 227 247 227 246 228 247 228 248 228 249 229 250 229 247 229 247 230 250 230 251 230 247 231 251 231 248 231 242 232 245 232 247 232 247 233 245 233 252 233 247 234 252 234 249 234 253 235 254 235 255 235 256 236 257 236 258 236 258 237 257 237 259 237 259 238 260 238 258 238 258 239 260 239 261 239 258 240 261 240 262 240 263 241 264 241 258 241 258 242 264 242 265 242 258 243 265 243 256 243 262 244 266 244 258 244 258 245 266 245 253 245 258 246 253 246 263 246 263 247 253 247 255 247 167 248 169 248 267 248 267 249 169 249 268 249 267 250 268 250 269 250 269 251 268 251 270 251 206 252 205 252 271 252 271 253 272 253 206 253 206 254 272 254 273 254 206 255 273 255 268 255 268 256 273 256 274 256 268 257 274 257 270 257 275 258 276 258 277 258 277 259 276 259 278 259 277 260 278 260 178 260 178 261 278 261 279 261 178 262 279 262 180 262 159 263 157 263 280 263 280 264 157 264 281 264 280 265 281 265 282 265 282 266 283 266 280 266 280 267 283 267 284 267 280 268 284 268 277 268 277 269 284 269 285 269 277 270 285 270 275 270 41 271 211 271 39 271 39 272 211 272 286 272 39 273 286 273 37 273 287 274 27 274 29 274 29 275 31 275 287 275 287 276 31 276 33 276 287 277 33 277 286 277 286 278 33 278 35 278 286 279 35 279 37 279 288 280 55 280 57 280 57 281 58 281 288 281 288 282 58 282 22 282 288 283 22 283 287 283 287 284 22 284 25 284 287 285 25 285 27 285 289 286 288 286 290 286 290 287 288 287 120 287 290 288 120 288 122 288 289 289 291 289 288 289 288 290 291 290 292 290 288 291 292 291 293 291 293 292 294 292 288 292 288 293 294 293 295 293 288 294 295 294 296 294 296 295 297 295 288 295 288 296 297 296 51 296 288 297 51 297 55 297 220 298 222 298 298 298 298 299 222 299 216 299 116 300 118 300 299 300 299 301 118 301 300 301 299 302 300 302 301 302 301 303 300 303 302 303 303 304 304 304 305 304 305 305 304 305 306 305 305 306 306 306 307 306 308 307 309 307 310 307 310 308 309 308 311 308 310 309 311 309 312 309 215 310 312 310 216 310 216 311 312 311 311 311 216 312 311 312 298 312 298 313 311 313 309 313 298 314 309 314 303 314 303 315 309 315 313 315 303 316 313 316 304 316 218 317 220 317 314 317 314 318 220 318 298 318 314 319 298 319 315 319 315 320 298 320 303 320 315 321 303 321 300 321 300 322 303 322 305 322 300 323 305 323 302 323 302 324 305 324 307 324 211 325 218 325 286 325 286 326 218 326 314 326 286 327 314 327 287 327 287 328 314 328 315 328 287 329 315 329 288 329 288 330 315 330 300 330 288 331 300 331 120 331 120 332 300 332 118 332 46 333 316 333 317 333 46 334 317 334 318 334 318 335 317 335 319 335 318 336 319 336 320 336 320 337 321 337 318 337 318 338 321 338 322 338 318 339 322 339 323 339 123 340 121 340 324 340 324 341 121 341 318 341 324 342 318 342 325 342 325 343 318 343 323 343 44 344 48 344 318 344 318 345 48 345 47 345 318 346 47 346 46 346 78 347 326 347 66 347 66 348 326 348 327 348 78 349 77 349 326 349 326 350 77 350 63 350 326 351 63 351 318 351 318 352 63 352 2 352 318 353 2 353 44 353 194 354 75 354 327 354 327 355 75 355 73 355 327 356 73 356 71 356 71 357 69 357 327 357 327 358 69 358 67 358 327 359 67 359 66 359 328 360 329 360 330 360 331 361 185 361 184 361 332 362 333 362 334 362 335 363 336 363 337 363 337 364 336 364 338 364 337 365 338 365 332 365 332 366 338 366 339 366 332 367 339 367 333 367 329 368 340 368 330 368 330 369 340 369 341 369 330 370 341 370 337 370 337 371 341 371 342 371 337 372 342 372 335 372 119 373 117 373 343 373 343 374 117 374 344 374 196 375 194 375 345 375 345 376 194 376 327 376 345 377 327 377 346 377 346 378 327 378 326 378 346 379 326 379 343 379 343 380 326 380 318 380 343 381 318 381 119 381 119 382 318 382 121 382 332 383 345 383 337 383 337 384 345 384 346 384 337 385 346 385 330 385 330 386 346 386 343 386 330 387 343 387 328 387 328 388 343 388 344 388 334 389 331 389 332 389 332 390 331 390 184 390 332 391 184 391 345 391 345 392 184 392 191 392 345 393 191 393 196 393 254 394 253 394 347 394 348 395 349 395 347 395 347 396 349 396 350 396 347 397 350 397 254 397 351 398 352 398 353 398 353 399 352 399 354 399 353 400 354 400 348 400 348 401 354 401 355 401 348 402 355 402 349 402 125 403 124 403 353 403 353 404 124 404 356 404 353 405 356 405 351 405 357 406 358 406 359 406 360 407 361 407 362 407 362 408 361 408 363 408 362 409 363 409 358 409 359 410 364 410 357 410 357 411 364 411 365 411 357 412 365 412 366 412 242 413 241 413 365 413 365 414 241 414 367 414 365 415 367 415 366 415 358 416 363 416 359 416 359 417 363 417 126 417 359 418 126 418 127 418 117 419 116 419 368 419 368 420 116 420 369 420 368 421 369 421 370 421 370 422 369 422 371 422 370 423 371 423 372 423 372 424 371 424 373 424 372 425 373 425 374 425 374 426 373 426 375 426 376 427 377 427 378 427 379 428 380 428 381 428 381 429 380 429 382 429 381 430 382 430 383 430 383 431 384 431 381 431 381 432 384 432 385 432 381 433 385 433 386 433 386 434 385 434 387 434 386 435 387 435 375 435 375 436 387 436 388 436 375 437 388 437 374 437 379 438 381 438 378 438 378 439 381 439 389 439 378 440 389 440 376 440 390 441 391 441 378 441 377 442 392 442 378 442 378 443 392 443 393 443 378 444 393 444 394 444 394 445 395 445 378 445 378 446 395 446 396 446 378 447 396 447 390 447 397 448 124 448 126 448 391 449 398 449 378 449 378 450 398 450 397 450 378 451 397 451 399 451 399 452 397 452 126 452 400 453 189 453 186 453 401 454 402 454 403 454 404 455 360 455 362 455 404 456 362 456 405 456 405 457 362 457 406 457 405 458 406 458 407 458 408 459 409 459 403 459 403 460 409 460 410 460 403 461 410 461 401 461 411 462 412 462 403 462 403 463 412 463 413 463 403 464 413 464 408 464 186 465 185 465 414 465 414 466 411 466 186 466 186 467 411 467 403 467 186 468 403 468 400 468 400 469 403 469 402 469 400 470 402 470 406 470 406 471 402 471 415 471 406 472 415 472 407 472 197 473 189 473 416 473 416 474 189 474 400 474 416 475 400 475 417 475 417 476 400 476 406 476 358 477 357 477 418 477 418 478 357 478 366 478 418 479 366 479 367 479 198 480 197 480 419 480 419 481 197 481 416 481 419 482 416 482 418 482 418 483 416 483 417 483 418 484 417 484 358 484 358 485 417 485 406 485 358 486 406 486 362 486 199 487 198 487 420 487 420 488 198 488 419 488 420 489 419 489 421 489 421 490 419 490 418 490 421 491 418 491 241 491 241 492 418 492 367 492 204 493 199 493 422 493 422 494 199 494 420 494 422 495 420 495 423 495 423 496 420 496 421 496 243 497 423 497 240 497 240 498 423 498 421 498 240 499 421 499 241 499 205 500 204 500 424 500 424 501 204 501 422 501 424 502 422 502 425 502 425 503 422 503 423 503 425 504 423 504 426 504 426 505 423 505 243 505 426 506 243 506 246 506 424 507 425 507 427 507 427 508 425 508 426 508 271 509 205 509 424 509 424 510 427 510 271 510 271 511 427 511 428 511 271 512 428 512 272 512 272 513 428 513 429 513 272 514 429 514 273 514 426 515 246 515 427 515 427 516 246 516 248 516 427 517 248 517 428 517 428 518 248 518 251 518 428 519 251 519 429 519 429 520 251 520 250 520 429 521 250 521 430 521 430 522 250 522 249 522 430 523 249 523 431 523 431 524 249 524 252 524 431 525 252 525 432 525 432 526 252 526 245 526 432 527 245 527 433 527 273 528 429 528 274 528 274 529 429 529 430 529 274 530 430 530 270 530 270 531 430 531 431 531 270 532 431 532 269 532 269 533 431 533 432 533 269 534 432 534 267 534 267 535 432 535 433 535 267 536 433 536 167 536 168 537 167 537 433 537 168 537 433 537 434 537 434 538 433 538 245 538 434 539 245 539 244 539 215 540 435 540 312 540 436 541 437 541 438 541 438 542 437 542 435 542 312 543 435 543 310 543 310 544 435 544 437 544 310 545 437 545 308 545 435 546 215 546 214 546 439 547 440 547 441 547 442 548 439 548 443 548 443 549 439 549 441 549 443 550 441 550 444 550 442 551 436 551 439 551 439 552 436 552 438 552 439 553 438 553 435 553 435 554 214 554 439 554 439 555 214 555 183 555 439 556 183 556 440 556 445 557 446 557 447 557 440 558 183 558 182 558 448 559 449 559 450 559 449 560 451 560 450 560 450 561 451 561 452 561 450 562 452 562 444 562 453 563 454 563 447 563 354 564 352 564 455 564 456 565 441 565 440 565 457 566 450 566 456 566 456 567 450 567 444 567 456 568 444 568 441 568 455 569 453 569 354 569 354 570 453 570 447 570 354 571 447 571 355 571 355 572 447 572 446 572 355 573 446 573 349 573 349 574 446 574 350 574 440 575 182 575 456 575 456 576 182 576 181 576 456 577 181 577 457 577 457 578 181 578 174 578 457 579 174 579 458 579 458 580 459 580 457 580 457 581 459 581 445 581 457 582 445 582 450 582 450 583 445 583 447 583 450 584 447 584 448 584 448 585 447 585 454 585 254 586 350 586 460 586 460 587 350 587 446 587 460 588 446 588 461 588 461 589 446 589 445 589 461 590 445 590 462 590 462 591 445 591 459 591 174 592 173 592 458 592 458 593 173 593 463 593 458 594 463 594 459 594 459 595 463 595 462 595 462 596 463 596 464 596 462 597 464 597 461 597 461 598 464 598 460 598 460 599 464 599 255 599 460 600 255 600 254 600 263 601 255 601 465 601 465 602 255 602 464 602 465 603 464 603 466 603 466 604 464 604 463 604 466 605 463 605 180 605 180 606 463 606 173 606 467 607 468 607 469 607 468 608 262 608 261 608 470 609 471 609 467 609 472 610 282 610 473 610 473 611 282 611 281 611 473 612 281 612 470 612 470 613 281 613 157 613 470 614 157 614 471 614 468 615 261 615 469 615 469 616 261 616 260 616 469 617 260 617 474 617 474 618 260 618 259 618 474 619 259 619 475 619 475 620 259 620 257 620 475 621 257 621 476 621 476 622 257 622 256 622 476 623 256 623 477 623 477 624 256 624 265 624 477 625 265 625 478 625 467 626 469 626 470 626 470 627 469 627 474 627 470 628 474 628 473 628 473 629 474 629 475 629 473 630 475 630 472 630 472 631 475 631 476 631 472 632 476 632 479 632 479 633 476 633 477 633 479 634 477 634 480 634 480 635 477 635 478 635 480 636 478 636 481 636 278 637 276 637 481 637 481 638 276 638 275 638 481 639 275 639 480 639 480 640 275 640 285 640 480 641 285 641 479 641 479 642 285 642 284 642 479 643 284 643 472 643 472 644 284 644 283 644 472 645 283 645 282 645 279 646 278 646 482 646 482 647 278 647 481 647 482 648 481 648 483 648 483 649 481 649 478 649 483 650 478 650 264 650 264 651 478 651 265 651 180 652 279 652 466 652 466 653 279 653 482 653 466 654 482 654 465 654 465 655 482 655 483 655 465 656 483 656 263 656 263 657 483 657 264 657 262 658 468 658 266 658 266 659 468 659 484 659 157 660 156 660 471 660 471 661 156 661 484 661 471 662 484 662 467 662 467 663 484 663 468 663 231 664 230 664 485 664 485 665 230 665 486 665 485 666 486 666 487 666 487 667 486 667 488 667 489 668 490 668 491 668 491 669 490 669 492 669 491 670 492 670 486 670 486 671 492 671 493 671 486 672 493 672 488 672 489 673 491 673 494 673 494 674 491 674 133 674 494 675 133 675 138 675 208 676 210 676 495 676 134 677 208 677 496 677 497 678 498 678 499 678 499 679 498 679 500 679 499 680 500 680 501 680 501 681 500 681 495 681 501 682 495 682 502 682 502 683 495 683 210 683 502 684 210 684 145 684 503 685 498 685 504 685 504 686 498 686 497 686 504 687 497 687 505 687 208 688 495 688 496 688 496 689 495 689 500 689 496 690 500 690 506 690 506 691 500 691 498 691 506 692 498 692 507 692 507 693 498 693 503 693 507 694 503 694 508 694 134 695 496 695 135 695 135 696 496 696 506 696 135 697 506 697 136 697 136 698 506 698 507 698 136 699 507 699 137 699 137 700 507 700 508 700 137 701 508 701 138 701 231 702 509 702 510 702 510 703 509 703 511 703 510 704 511 704 512 704 512 705 511 705 513 705 231 706 485 706 509 706 509 707 485 707 487 707 509 708 487 708 511 708 511 709 487 709 488 709 511 710 488 710 513 710 513 711 488 711 493 711 513 712 493 712 514 712 515 713 516 713 514 713 514 714 516 714 517 714 514 715 517 715 513 715 513 716 517 716 518 716 513 717 518 717 512 717 493 718 492 718 514 718 514 719 492 719 490 719 514 720 490 720 515 720 515 721 490 721 489 721 515 722 489 722 519 722 520 723 521 723 519 723 519 724 521 724 522 724 519 725 522 725 515 725 515 726 522 726 523 726 515 727 523 727 516 727 489 728 494 728 519 728 519 729 494 729 138 729 519 730 138 730 508 730 505 731 520 731 504 731 504 732 520 732 519 732 504 733 519 733 503 733 503 734 519 734 508 734 165 735 164 735 524 735 524 736 164 736 525 736 524 737 525 737 526 737 225 738 228 738 525 738 525 739 228 739 527 739 525 740 527 740 528 740 528 741 529 741 525 741 525 742 529 742 530 742 525 743 530 743 526 743 531 744 226 744 224 744 497 745 499 745 532 745 532 746 499 746 501 746 532 747 501 747 148 747 148 748 501 748 502 748 148 749 502 749 145 749 522 750 521 750 533 750 533 751 521 751 520 751 533 752 520 752 532 752 532 753 520 753 505 753 532 754 505 754 497 754 510 755 512 755 534 755 512 756 518 756 534 756 534 757 518 757 517 757 534 758 517 758 535 758 535 759 517 759 516 759 535 760 516 760 523 760 536 761 537 761 534 761 231 762 510 762 223 762 223 763 510 763 534 763 223 764 534 764 224 764 224 765 534 765 537 765 224 766 537 766 531 766 538 767 539 767 535 767 535 768 539 768 540 768 535 769 540 769 534 769 534 770 540 770 541 770 534 771 541 771 536 771 538 772 535 772 542 772 542 773 535 773 543 773 542 774 543 774 544 774 140 775 545 775 141 775 141 776 545 776 546 776 141 777 546 777 543 777 543 778 546 778 547 778 543 779 547 779 544 779 523 780 522 780 535 780 535 781 522 781 533 781 535 782 533 782 543 782 543 783 533 783 532 783 543 784 532 784 141 784 141 785 532 785 148 785 228 786 548 786 549 786 549 787 548 787 550 787 549 788 550 788 551 788 551 789 550 789 552 789 551 790 552 790 553 790 553 791 552 791 554 791 553 792 554 792 555 792 228 793 549 793 527 793 527 794 549 794 551 794 527 795 551 795 528 795 528 796 551 796 553 796 528 797 553 797 529 797 529 798 553 798 555 798 529 799 555 799 530 799 556 800 557 800 558 800 558 801 557 801 559 801 558 802 559 802 560 802 560 803 559 803 555 803 560 804 555 804 561 804 561 805 555 805 554 805 530 806 555 806 526 806 526 807 555 807 559 807 526 808 559 808 524 808 524 809 559 809 557 809 524 810 557 810 165 810 557 811 556 811 562 811 165 812 557 812 563 812 557 813 562 813 563 813 563 814 562 814 564 814 563 815 564 815 565 815 564 816 566 816 565 816 565 817 566 817 567 817 565 818 567 818 568 818 568 819 567 819 206 819 568 820 206 820 268 820 165 821 563 821 166 821 166 822 563 822 565 822 166 823 565 823 170 823 170 824 565 824 568 824 170 825 568 825 171 825 171 826 568 826 268 826 171 827 268 827 169 827 569 828 570 828 571 828 572 829 203 829 201 829 548 830 228 830 227 830 548 831 227 831 550 831 550 832 227 832 552 832 552 833 227 833 573 833 552 834 573 834 554 834 556 835 558 835 574 835 574 836 558 836 560 836 574 837 560 837 573 837 573 838 560 838 561 838 573 839 561 839 554 839 571 840 562 840 556 840 567 841 566 841 571 841 571 842 566 842 564 842 571 843 564 843 562 843 570 844 572 844 571 844 571 845 572 845 201 845 571 846 201 846 567 846 567 847 201 847 206 847 556 848 574 848 571 848 571 849 574 849 575 849 571 850 575 850 569 850 576 851 577 851 573 851 573 852 577 852 578 852 573 853 578 853 574 853 574 854 578 854 579 854 574 855 579 855 575 855 227 856 226 856 580 856 227 857 580 857 573 857 573 858 580 858 581 858 573 859 581 859 576 859 129 860 128 860 582 860 582 861 128 861 583 861 582 862 583 862 584 862 585 863 586 863 583 863 583 864 586 864 587 864 583 865 587 865 584 865 233 866 232 866 585 866 585 867 232 867 588 867 585 868 588 868 589 868 589 869 590 869 585 869 585 870 590 870 591 870 585 871 591 871 586 871 232 872 592 872 588 872 588 873 592 873 593 873 588 874 593 874 589 874 589 875 593 875 594 875 589 876 594 876 590 876 232 877 595 877 592 877 592 878 595 878 596 878 592 879 596 879 593 879 593 880 596 880 597 880 593 881 597 881 594 881 594 882 597 882 598 882 594 883 598 883 599 883 590 884 594 884 591 884 591 885 594 885 599 885 591 886 599 886 586 886 586 887 599 887 600 887 586 888 600 888 587 888 598 889 601 889 599 889 599 890 601 890 602 890 599 891 602 891 600 891 600 892 602 892 603 892 600 893 603 893 604 893 604 894 603 894 605 894 604 895 605 895 606 895 606 896 607 896 604 896 604 897 607 897 608 897 604 898 608 898 609 898 587 899 600 899 584 899 584 900 600 900 604 900 584 901 604 901 582 901 582 902 604 902 609 902 582 903 609 903 129 903 610 904 611 904 612 904 612 905 611 905 607 905 612 906 607 906 606 906 130 907 129 907 613 907 613 908 129 908 609 908 613 909 609 909 611 909 611 910 609 910 608 910 611 911 608 911 607 911 131 912 130 912 614 912 614 913 130 913 613 913 614 914 613 914 615 914 615 915 613 915 611 915 615 916 611 916 616 916 616 917 611 917 610 917 132 918 131 918 207 918 207 919 131 919 614 919 207 920 614 920 209 920 209 921 614 921 615 921 209 922 615 922 146 922 146 923 615 923 616 923 617 924 618 924 619 924 238 925 237 925 620 925 620 926 237 926 617 926 620 927 617 927 621 927 621 928 617 928 619 928 618 929 617 929 622 929 622 930 617 930 158 930 622 931 158 931 163 931 623 932 151 932 147 932 624 933 598 933 597 933 597 934 596 934 625 934 625 935 596 935 595 935 625 936 595 936 626 936 626 937 595 937 232 937 626 938 232 938 234 938 598 939 624 939 601 939 601 940 624 940 627 940 601 941 627 941 602 941 612 942 606 942 628 942 628 943 606 943 605 943 628 944 605 944 627 944 627 945 605 945 603 945 627 946 603 946 602 946 147 947 146 947 616 947 147 948 616 948 628 948 628 949 616 949 610 949 628 950 610 950 612 950 623 951 147 951 629 951 629 952 147 952 630 952 630 953 147 953 628 953 630 954 628 954 631 954 632 955 633 955 627 955 627 956 633 956 634 956 627 957 634 957 628 957 628 958 634 958 635 958 628 959 635 959 631 959 624 960 636 960 637 960 624 961 637 961 627 961 627 962 637 962 638 962 627 963 638 963 632 963 597 964 625 964 624 964 624 965 625 965 639 965 624 966 639 966 636 966 640 967 641 967 642 967 643 968 644 968 645 968 163 969 162 969 646 969 646 970 162 970 647 970 646 971 647 971 648 971 648 972 647 972 643 972 648 973 643 973 649 973 649 974 643 974 645 974 641 975 644 975 642 975 642 976 644 976 643 976 642 977 643 977 650 977 650 978 643 978 647 978 650 979 647 979 161 979 161 980 647 980 162 980 651 981 640 981 652 981 652 982 640 982 642 982 652 983 642 983 653 983 653 984 642 984 650 984 653 985 650 985 160 985 160 986 650 986 161 986 178 987 651 987 277 987 277 988 651 988 652 988 277 989 652 989 280 989 280 990 652 990 653 990 280 991 653 991 159 991 159 992 653 992 160 992 238 993 654 993 655 993 655 994 654 994 656 994 622 995 657 995 618 995 618 996 657 996 658 996 618 997 658 997 619 997 619 998 658 998 656 998 619 999 656 999 621 999 621 1000 656 1000 654 1000 621 1001 654 1001 620 1001 620 1002 654 1002 238 1002 659 1003 660 1003 657 1003 657 1004 660 1004 661 1004 657 1005 661 1005 658 1005 658 1006 661 1006 662 1006 658 1007 662 1007 656 1007 656 1008 662 1008 663 1008 656 1009 663 1009 655 1009 649 1010 645 1010 659 1010 649 1011 659 1011 648 1011 648 1012 659 1012 657 1012 648 1013 657 1013 646 1013 646 1014 657 1014 622 1014 646 1015 622 1015 163 1015 236 1016 239 1016 664 1016 644 1017 641 1017 665 1017 665 1018 641 1018 640 1018 665 1019 640 1019 176 1019 176 1020 640 1020 651 1020 176 1021 651 1021 178 1021 644 1022 665 1022 645 1022 645 1023 665 1023 666 1023 645 1024 666 1024 659 1024 659 1025 666 1025 660 1025 660 1026 666 1026 664 1026 660 1027 664 1027 661 1027 238 1028 655 1028 239 1028 239 1029 655 1029 663 1029 239 1030 663 1030 664 1030 664 1031 663 1031 662 1031 664 1032 662 1032 661 1032 667 1033 234 1033 236 1033 667 1034 236 1034 668 1034 668 1035 236 1035 669 1035 669 1036 236 1036 664 1036 669 1037 664 1037 670 1037 670 1038 664 1038 666 1038 670 1039 666 1039 671 1039 665 1040 672 1040 673 1040 673 1041 674 1041 665 1041 665 1042 674 1042 675 1042 665 1043 675 1043 666 1043 666 1044 675 1044 676 1044 666 1045 676 1045 671 1045 672 1046 665 1046 677 1046 677 1047 665 1047 176 1047 677 1048 176 1048 175 1048 152 1049 678 1049 106 1049 106 1050 678 1050 108 1050 108 1051 678 1051 110 1051 110 1052 678 1052 679 1052 110 1053 679 1053 112 1053 112 1054 679 1054 114 1054 114 1055 679 1055 680 1055 114 1056 680 1056 115 1056 115 1057 680 1057 94 1057 94 1058 680 1058 212 1058 94 1059 212 1059 92 1059 221 1060 219 1060 681 1060 682 1061 149 1061 150 1061 172 1062 213 1062 683 1062 683 1063 213 1063 684 1063 683 1064 684 1064 685 1064 685 1065 684 1065 686 1065 150 1066 687 1066 682 1066 682 1067 687 1067 688 1067 682 1068 688 1068 686 1068 686 1069 688 1069 689 1069 686 1070 689 1070 685 1070 144 1071 149 1071 690 1071 690 1072 149 1072 682 1072 690 1073 682 1073 691 1073 691 1074 682 1074 686 1074 691 1075 686 1075 692 1075 692 1076 686 1076 684 1076 692 1077 684 1077 217 1077 217 1078 684 1078 213 1078 142 1079 144 1079 693 1079 693 1080 144 1080 690 1080 693 1081 690 1081 694 1081 694 1082 690 1082 691 1082 694 1083 691 1083 681 1083 681 1084 691 1084 692 1084 681 1085 692 1085 221 1085 221 1086 692 1086 217 1086 152 1087 142 1087 678 1087 678 1088 142 1088 693 1088 678 1089 693 1089 679 1089 679 1090 693 1090 694 1090 679 1091 694 1091 680 1091 680 1092 694 1092 681 1092 680 1093 681 1093 212 1093 212 1094 681 1094 219 1094 172 1095 683 1095 179 1095 179 1096 683 1096 695 1096 683 1097 685 1097 695 1097 695 1098 685 1098 689 1098 695 1099 689 1099 696 1099 150 1100 151 1100 687 1100 687 1101 151 1101 696 1101 687 1102 696 1102 688 1102 688 1103 696 1103 689 1103 697 1104 623 1104 629 1104 175 1105 177 1105 698 1105 698 1106 177 1106 699 1106 698 1107 699 1107 700 1107 700 1108 699 1108 697 1108 700 1109 697 1109 701 1109 701 1110 697 1110 629 1110 151 1111 623 1111 696 1111 696 1112 623 1112 697 1112 696 1113 697 1113 695 1113 695 1114 697 1114 699 1114 695 1115 699 1115 179 1115 179 1116 699 1116 177 1116 234 1117 667 1117 702 1117 702 1118 667 1118 668 1118 626 1119 234 1119 702 1119 703 1120 639 1120 625 1120 669 1121 704 1121 668 1121 668 1122 704 1122 703 1122 668 1123 703 1123 702 1123 702 1124 703 1124 625 1124 702 1125 625 1125 626 1125 669 1126 670 1126 704 1126 704 1127 670 1127 671 1127 704 1128 671 1128 705 1128 705 1129 671 1129 676 1129 705 1130 676 1130 706 1130 639 1131 703 1131 636 1131 636 1132 703 1132 704 1132 636 1133 704 1133 637 1133 637 1134 704 1134 705 1134 637 1135 705 1135 638 1135 638 1136 705 1136 706 1136 638 1137 706 1137 632 1137 632 1138 706 1138 633 1138 633 1139 706 1139 707 1139 633 1140 707 1140 634 1140 634 1141 707 1141 708 1141 634 1142 708 1142 635 1142 677 1143 709 1143 672 1143 672 1144 709 1144 708 1144 672 1145 708 1145 673 1145 673 1146 708 1146 707 1146 673 1147 707 1147 674 1147 674 1148 707 1148 706 1148 674 1149 706 1149 675 1149 675 1150 706 1150 676 1150 677 1151 175 1151 698 1151 677 1152 698 1152 709 1152 709 1153 698 1153 700 1153 709 1154 700 1154 701 1154 635 1155 708 1155 631 1155 631 1156 708 1156 709 1156 631 1157 709 1157 630 1157 630 1158 709 1158 701 1158 630 1159 701 1159 629 1159 97 1160 193 1160 710 1160 97 1161 710 1161 99 1161 99 1162 710 1162 711 1162 99 1163 711 1163 101 1163 101 1164 711 1164 712 1164 101 1165 712 1165 102 1165 102 1166 712 1166 153 1166 102 1167 153 1167 104 1167 710 1168 193 1168 192 1168 711 1169 710 1169 713 1169 712 1170 711 1170 714 1170 153 1171 712 1171 715 1171 711 1172 713 1172 714 1172 714 1173 713 1173 716 1173 714 1174 716 1174 717 1174 717 1175 716 1175 718 1175 717 1176 718 1176 719 1176 710 1177 192 1177 713 1177 713 1178 192 1178 195 1178 713 1179 195 1179 716 1179 716 1180 195 1180 190 1180 716 1181 190 1181 718 1181 718 1182 190 1182 188 1182 718 1183 188 1183 187 1183 187 1184 720 1184 718 1184 718 1185 720 1185 721 1185 718 1186 721 1186 719 1186 719 1187 721 1187 722 1187 719 1188 722 1188 723 1188 712 1189 714 1189 715 1189 715 1190 714 1190 717 1190 715 1191 717 1191 724 1191 724 1192 717 1192 719 1192 724 1193 719 1193 725 1193 725 1194 719 1194 723 1194 725 1195 723 1195 726 1195 153 1196 715 1196 154 1196 154 1197 715 1197 724 1197 154 1198 724 1198 155 1198 155 1199 724 1199 725 1199 155 1200 725 1200 143 1200 143 1201 725 1201 726 1201 143 1202 726 1202 139 1202 187 1203 200 1203 720 1203 720 1204 200 1204 727 1204 720 1205 727 1205 721 1205 721 1206 727 1206 722 1206 722 1207 727 1207 728 1207 722 1208 728 1208 723 1208 723 1209 728 1209 726 1209 726 1210 728 1210 140 1210 726 1211 140 1211 139 1211 729 1212 202 1212 203 1212 546 1213 545 1213 730 1213 730 1214 545 1214 731 1214 730 1215 731 1215 732 1215 732 1216 731 1216 729 1216 732 1217 729 1217 733 1217 733 1218 729 1218 203 1218 200 1219 202 1219 727 1219 727 1220 202 1220 729 1220 727 1221 729 1221 728 1221 728 1222 729 1222 731 1222 728 1223 731 1223 140 1223 140 1224 731 1224 545 1224 577 1225 576 1225 734 1225 734 1226 576 1226 581 1226 226 1227 735 1227 580 1227 580 1228 735 1228 736 1228 226 1229 531 1229 735 1229 735 1230 531 1230 537 1230 735 1231 537 1231 736 1231 736 1232 537 1232 536 1232 541 1233 737 1233 536 1233 536 1234 737 1234 734 1234 536 1235 734 1235 736 1235 736 1236 734 1236 581 1236 736 1237 581 1237 580 1237 541 1238 540 1238 737 1238 737 1239 540 1239 539 1239 737 1240 539 1240 738 1240 738 1241 539 1241 538 1241 738 1242 538 1242 739 1242 577 1243 734 1243 578 1243 578 1244 734 1244 737 1244 578 1245 737 1245 579 1245 579 1246 737 1246 738 1246 579 1247 738 1247 575 1247 575 1248 738 1248 739 1248 575 1249 739 1249 569 1249 546 1250 730 1250 547 1250 547 1251 730 1251 732 1251 547 1252 732 1252 544 1252 538 1253 542 1253 739 1253 739 1254 542 1254 544 1254 739 1255 544 1255 740 1255 740 1256 544 1256 732 1256 740 1257 732 1257 733 1257 569 1258 739 1258 570 1258 570 1259 739 1259 740 1259 570 1260 740 1260 572 1260 572 1261 740 1261 733 1261 572 1262 733 1262 203 1262 338 1263 336 1263 741 1263 185 1264 331 1264 414 1264 414 1265 331 1265 334 1265 414 1266 334 1266 411 1266 411 1267 334 1267 333 1267 411 1268 333 1268 412 1268 412 1269 333 1269 339 1269 412 1270 339 1270 413 1270 413 1271 339 1271 338 1271 413 1272 338 1272 408 1272 408 1273 338 1273 741 1273 408 1274 741 1274 409 1274 742 1275 352 1275 351 1275 391 1276 742 1276 398 1276 398 1277 742 1277 351 1277 398 1278 351 1278 397 1278 397 1279 351 1279 356 1279 397 1280 356 1280 124 1280 742 1281 391 1281 390 1281 352 1282 742 1282 743 1282 352 1283 743 1283 455 1283 455 1284 743 1284 744 1284 455 1285 744 1285 453 1285 453 1286 744 1286 745 1286 453 1287 745 1287 454 1287 454 1288 745 1288 448 1288 448 1289 745 1289 746 1289 448 1290 746 1290 449 1290 449 1291 746 1291 747 1291 449 1292 747 1292 451 1292 742 1293 390 1293 743 1293 743 1294 390 1294 396 1294 743 1295 396 1295 744 1295 744 1296 396 1296 395 1296 744 1297 395 1297 745 1297 745 1298 395 1298 394 1298 745 1299 394 1299 746 1299 746 1300 394 1300 393 1300 746 1301 393 1301 747 1301 747 1302 393 1302 392 1302 747 1303 392 1303 748 1303 451 1304 747 1304 452 1304 452 1305 747 1305 748 1305 452 1306 748 1306 444 1306 748 1307 392 1307 377 1307 443 1308 444 1308 749 1308 749 1309 444 1309 748 1309 748 1310 377 1310 749 1310 749 1311 377 1311 376 1311 749 1312 376 1312 750 1312 443 1313 749 1313 442 1313 442 1314 749 1314 750 1314 442 1315 750 1315 436 1315 437 1316 436 1316 751 1316 751 1317 436 1317 750 1317 751 1318 750 1318 389 1318 389 1319 750 1319 376 1319 308 1320 437 1320 752 1320 752 1321 437 1321 751 1321 752 1322 751 1322 381 1322 381 1323 751 1323 389 1323 309 1324 308 1324 752 1324 116 1325 299 1325 753 1325 753 1326 299 1326 301 1326 753 1327 301 1327 754 1327 754 1328 301 1328 755 1328 301 1329 302 1329 755 1329 755 1330 302 1330 307 1330 755 1331 307 1331 756 1331 116 1332 753 1332 369 1332 369 1333 753 1333 754 1333 369 1334 754 1334 371 1334 371 1335 754 1335 755 1335 371 1336 755 1336 373 1336 373 1337 755 1337 756 1337 373 1338 756 1338 375 1338 307 1339 306 1339 756 1339 756 1340 306 1340 304 1340 756 1341 304 1341 752 1341 752 1342 304 1342 313 1342 752 1343 313 1343 309 1343 375 1344 756 1344 386 1344 386 1345 756 1345 752 1345 386 1346 752 1346 381 1346 126 1347 757 1347 399 1347 399 1348 757 1348 378 1348 360 1349 758 1349 757 1349 757 1350 758 1350 379 1350 757 1351 379 1351 378 1351 126 1352 363 1352 757 1352 757 1353 363 1353 361 1353 757 1354 361 1354 360 1354 759 1355 388 1355 387 1355 760 1356 761 1356 762 1356 762 1357 761 1357 763 1357 762 1358 763 1358 759 1358 759 1359 387 1359 762 1359 762 1360 387 1360 385 1360 762 1361 385 1361 384 1361 384 1362 764 1362 762 1362 762 1363 764 1363 410 1363 762 1364 410 1364 760 1364 760 1365 410 1365 409 1365 407 1366 415 1366 764 1366 415 1367 402 1367 764 1367 764 1368 402 1368 401 1368 764 1369 401 1369 410 1369 765 1370 383 1370 382 1370 765 1371 382 1371 766 1371 766 1372 382 1372 380 1372 766 1373 380 1373 767 1373 767 1374 380 1374 379 1374 767 1375 379 1375 758 1375 384 1376 383 1376 764 1376 764 1377 383 1377 765 1377 764 1378 765 1378 407 1378 407 1379 765 1379 766 1379 407 1380 766 1380 405 1380 405 1381 766 1381 767 1381 405 1382 767 1382 404 1382 404 1383 767 1383 758 1383 404 1384 758 1384 360 1384 760 1385 768 1385 761 1385 769 1386 770 1386 759 1386 759 1387 770 1387 388 1387 741 1388 336 1388 771 1388 759 1389 763 1389 769 1389 769 1390 763 1390 761 1390 769 1391 761 1391 771 1391 771 1392 761 1392 768 1392 771 1393 768 1393 741 1393 741 1394 768 1394 760 1394 741 1395 760 1395 409 1395 117 1396 772 1396 344 1396 344 1397 772 1397 773 1397 774 1398 329 1398 773 1398 773 1399 329 1399 328 1399 773 1400 328 1400 344 1400 117 1401 368 1401 772 1401 772 1402 368 1402 370 1402 772 1403 370 1403 773 1403 773 1404 370 1404 372 1404 773 1405 372 1405 774 1405 774 1406 372 1406 374 1406 774 1407 374 1407 775 1407 335 1408 342 1408 775 1408 775 1409 342 1409 341 1409 775 1410 341 1410 774 1410 774 1411 341 1411 340 1411 774 1412 340 1412 329 1412 771 1413 336 1413 335 1413 771 1414 335 1414 769 1414 769 1415 335 1415 775 1415 769 1416 775 1416 770 1416 770 1417 775 1417 374 1417 770 1418 374 1418 388 1418 776 1419 777 1419 778 1419 52 1420 50 1420 779 1420 779 1421 50 1421 780 1421 779 1422 780 1422 778 1422 778 1423 780 1423 781 1423 778 1424 781 1424 776 1424 793 1425 794 1425 795 1425 795 1426 794 1426 796 1426 795 1427 796 1427 797 1427 797 1428 796 1428 798 1428 797 1429 798 1429 799 1429 793 1430 800 1430 794 1430 794 1431 800 1431 801 1431 794 1432 801 1432 802 1432 799 1433 803 1433 797 1433 797 1434 803 1434 804 1434 797 1435 804 1435 805 1435 805 1436 804 1436 806 1436 805 1437 806 1437 807 1437 807 1438 806 1438 808 1438 807 1439 808 1439 105 1439 105 1440 808 1440 103 1440 819 1441 820 1441 821 1441 822 1442 823 1442 824 1442 819 1443 821 1443 825 1443 825 1444 821 1444 826 1444 825 1445 826 1445 827 1445 827 1446 826 1446 822 1446 827 1447 822 1447 828 1447 824 1448 829 1448 822 1448 822 1449 829 1449 830 1449 822 1450 830 1450 828 1450 831 1451 832 1451 833 1451 831 1452 833 1452 834 1452 834 1453 833 1453 835 1453 834 1454 835 1454 836 1454 837 1455 838 1455 839 1455 839 1456 838 1456 840 1456 839 1457 840 1457 841 1457 841 1458 840 1458 834 1458 841 1459 834 1459 842 1459 842 1460 834 1460 836 1460 843 1461 844 1461 845 1461 843 1462 845 1462 832 1462 832 1463 845 1463 846 1463 832 1464 846 1464 847 1464 844 1465 843 1465 848 1465 848 1466 843 1466 849 1466 848 1467 849 1467 850 1467 847 1468 851 1468 832 1468 832 1469 851 1469 852 1469 832 1470 852 1470 833 1470 794 1471 802 1471 853 1471 794 1472 853 1472 854 1472 854 1473 853 1473 855 1473 854 1473 855 1473 856 1473 856 1474 855 1474 792 1474 856 1475 792 1475 791 1475 857 1476 858 1476 3 1476 3 145 5 145 857 145 857 145 5 145 7 145 857 1477 7 1477 9 1477 9 1478 11 1478 857 1478 857 1479 11 1479 13 1479 857 1480 13 1480 859 1480 859 1481 13 1481 15 1481 859 145 15 145 17 145 17 145 19 145 859 145 859 1482 19 1482 43 1482 859 1483 43 1483 860 1483 861 1484 862 1484 863 1484 857 1485 859 1485 863 1485 863 1486 859 1486 864 1486 863 1487 864 1487 861 1487 865 1488 866 1488 867 1488 862 1489 861 1489 867 1489 867 1490 861 1490 868 1490 867 1491 868 1491 865 1491 865 1492 869 1492 866 1492 866 1493 869 1493 870 1493 866 1494 870 1494 871 1494 871 1495 870 1495 823 1495 871 1496 823 1496 822 1496 837 1497 74 1497 76 1497 96 1498 838 1498 91 1498 91 1499 838 1499 89 1499 76 142 83 142 837 142 837 1500 83 1500 85 1500 837 1501 85 1501 838 1501 838 1502 85 1502 87 1502 838 1503 87 1503 89 1503 873 1504 874 1504 875 1504 886 1505 887 1505 888 1505 888 1506 887 1506 889 1506 888 1507 889 1507 890 1507 891 1508 892 1508 888 1508 888 1509 892 1509 893 1509 888 1510 893 1510 886 1510 894 1511 895 1511 896 1511 895 1512 898 1512 896 1512 896 1513 898 1513 899 1513 902 1514 903 1514 896 1514 896 1515 903 1515 904 1515 896 1516 904 1516 894 1516 896 1517 897 1517 905 1517 896 1518 905 1518 902 1518 845 1519 844 1519 906 1519 906 1520 844 1520 907 1520 908 1521 909 1521 910 1521 910 1522 909 1522 911 1522 910 1523 911 1523 844 1523 844 1524 911 1524 912 1524 844 1525 912 1525 907 1525 815 1526 814 1526 910 1526 910 1527 814 1527 913 1527 910 1528 913 1528 908 1528 914 1529 915 1529 916 1529 916 1530 915 1530 917 1530 916 1531 917 1531 810 1531 810 1532 917 1532 918 1532 810 1533 918 1533 809 1533 825 1534 827 1534 919 1534 919 1535 920 1535 825 1535 825 1536 920 1536 921 1536 825 1537 921 1537 916 1537 916 1538 921 1538 922 1538 916 1539 922 1539 914 1539 56 1540 54 1540 779 1540 779 1541 54 1541 53 1541 779 1542 53 1542 52 1542 24 1543 23 1543 923 1543 923 1544 23 1544 60 1544 923 1545 60 1545 779 1545 779 1546 60 1546 59 1546 779 1547 59 1547 56 1547 32 1548 30 1548 924 1548 924 1549 30 1549 28 1549 924 1550 28 1550 923 1550 923 1551 28 1551 26 1551 923 1552 26 1552 24 1552 859 1553 860 1553 925 1553 925 1554 860 1554 40 1554 40 1555 38 1555 925 1555 925 1556 38 1556 36 1556 925 1557 36 1557 924 1557 924 1558 36 1558 34 1558 924 1559 34 1559 32 1559 861 1560 864 1560 926 1560 865 1561 868 1561 927 1561 928 1562 929 1562 930 1562 931 1563 932 1563 933 1563 929 1564 934 1564 930 1564 930 1565 934 1565 935 1565 930 1566 935 1566 936 1566 778 1567 777 1567 937 1567 937 1568 777 1568 938 1568 935 1569 939 1569 936 1569 936 1570 939 1570 931 1570 936 1571 931 1571 927 1571 927 1572 931 1572 933 1572 927 1573 933 1573 865 1573 865 1574 933 1574 940 1574 865 1575 940 1575 869 1575 938 1576 928 1576 937 1576 937 1577 928 1577 930 1577 937 1578 930 1578 941 1578 941 1579 930 1579 936 1579 941 1580 936 1580 926 1580 926 1581 936 1581 927 1581 926 1582 927 1582 861 1582 861 1583 927 1583 868 1583 779 1584 778 1584 923 1584 923 1585 778 1585 937 1585 923 1586 937 1586 924 1586 924 1587 937 1587 941 1587 924 1588 941 1588 925 1588 925 1589 941 1589 926 1589 925 1590 926 1590 859 1590 859 1591 926 1591 864 1591 74 1592 837 1592 72 1592 72 1593 837 1593 942 1593 72 1594 942 1594 70 1594 70 1595 942 1595 68 1595 62 1596 61 1596 943 1596 943 1597 61 1597 79 1597 943 1598 79 1598 942 1598 942 1599 79 1599 80 1599 942 1600 80 1600 68 1600 50 1601 49 1601 780 1601 780 1602 49 1602 45 1602 780 1603 45 1603 1 1603 1 1604 0 1604 780 1604 780 1605 0 1605 65 1605 780 1606 65 1606 943 1606 943 1607 65 1607 64 1607 943 1608 64 1608 62 1608 841 1609 842 1609 944 1609 776 1610 781 1610 945 1610 945 1611 781 1611 946 1611 945 1612 946 1612 947 1612 947 1613 946 1613 948 1613 949 1614 950 1614 951 1614 952 1615 953 1615 954 1615 949 1616 951 1616 954 1616 954 1617 951 1617 944 1617 954 1618 944 1618 952 1618 955 1619 956 1619 944 1619 944 1620 956 1620 957 1620 944 1621 957 1621 952 1621 842 1622 836 1622 944 1622 944 1623 836 1623 958 1623 944 1624 958 1624 955 1624 781 1625 780 1625 946 1625 946 1626 780 1626 943 1626 946 1627 943 1627 959 1627 959 1628 943 1628 942 1628 959 1629 942 1629 839 1629 839 1630 942 1630 837 1630 950 1631 948 1631 951 1631 951 1632 948 1632 946 1632 951 1633 946 1633 944 1633 944 1634 946 1634 959 1634 944 1635 959 1635 841 1635 841 1636 959 1636 839 1636 962 1637 961 1637 963 1637 967 1638 968 1638 969 1638 967 1639 969 1639 970 1639 970 1640 969 1640 971 1640 970 1641 971 1641 972 1641 975 1642 976 1642 977 1642 978 1643 777 1643 776 1643 776 1644 979 1644 978 1644 978 1645 979 1645 980 1645 978 1646 980 1646 981 1646 981 1647 980 1647 982 1647 981 1648 982 1648 983 1648 983 1649 982 1649 975 1649 983 1650 975 1650 984 1650 984 1651 975 1651 977 1651 985 1652 986 1652 987 1652 985 1653 987 1653 988 1653 989 1654 990 1654 987 1654 987 1655 990 1655 991 1655 991 1656 992 1656 987 1656 987 1657 992 1657 993 1657 987 1658 993 1658 988 1658 986 1659 994 1659 987 1659 987 1660 994 1660 995 1660 987 1661 995 1661 996 1661 997 1662 996 1662 977 1662 977 1663 996 1663 998 1663 977 1664 998 1664 984 1664 997 1665 999 1665 996 1665 996 1666 999 1666 1000 1666 996 1667 1000 1667 1001 1667 1001 1668 1002 1668 996 1668 996 1669 1002 1669 1003 1669 996 1670 1003 1670 987 1670 783 1671 782 1671 1004 1671 1004 1672 782 1672 1005 1672 1004 1673 1005 1673 987 1673 987 1674 1005 1674 1006 1674 987 1675 1006 1675 989 1675 1007 1676 1008 1676 1009 1676 1009 1677 1008 1677 1010 1677 969 1678 968 1678 1011 1678 969 1679 1011 1679 1012 1679 1012 1680 1011 1680 1013 1680 1012 1681 1013 1681 1014 1681 1015 1682 1009 1682 1016 1682 1016 1683 1009 1683 1010 1683 1016 1684 1010 1684 1017 1684 1015 1685 1018 1685 1009 1685 1009 1686 1018 1686 1019 1686 1009 1687 1019 1687 835 1687 835 1688 1019 1688 1020 1688 835 1689 1020 1689 836 1689 1014 1690 1021 1690 1012 1690 1012 1691 1021 1691 1007 1691 1012 1692 1007 1692 1022 1692 1022 1693 1007 1693 1009 1693 1022 1694 1009 1694 833 1694 833 1695 1009 1695 835 1695 1012 1696 1022 1696 1023 1696 969 1697 1012 1697 1024 1697 1012 1698 1023 1698 1024 1698 1024 1699 1023 1699 1025 1699 1024 1700 1025 1700 1026 1700 973 1701 974 1701 1026 1701 1026 1702 974 1702 972 1702 1026 1703 972 1703 1024 1703 1024 1704 972 1704 971 1704 1024 1705 971 1705 969 1705 847 1706 1025 1706 851 1706 851 1707 1025 1707 1023 1707 851 1708 1023 1708 852 1708 852 1709 1023 1709 1022 1709 852 1710 1022 1710 833 1710 883 1711 973 1711 1027 1711 1027 1712 973 1712 1026 1712 1027 1713 1026 1713 1028 1713 1028 1714 1026 1714 1025 1714 1028 1715 1025 1715 1029 1715 1029 1716 1025 1716 847 1716 847 1717 846 1717 1029 1717 1029 1718 846 1718 1030 1718 1029 1719 1030 1719 1028 1719 1028 1720 1030 1720 1027 1720 1027 1721 1030 1721 884 1721 1027 1722 884 1722 883 1722 885 1723 884 1723 1031 1723 1031 1724 884 1724 1030 1724 1031 1725 1030 1725 845 1725 845 1726 1030 1726 846 1726 1031 1727 845 1727 906 1727 885 1728 1031 1728 1032 1728 1031 1729 906 1729 1032 1729 1032 1730 906 1730 907 1730 1032 1731 907 1731 1033 1731 1033 1732 907 1732 912 1732 1033 1733 912 1733 1034 1733 1034 1734 912 1734 911 1734 1034 1735 911 1735 1035 1735 911 1736 909 1736 1035 1736 1035 1737 909 1737 908 1737 1035 1738 908 1738 1036 1738 1036 1739 908 1739 913 1739 1036 1740 913 1740 1037 1740 1037 1741 913 1741 814 1741 1037 1742 814 1742 1038 1742 885 1743 1032 1743 891 1743 891 1744 1032 1744 1033 1744 891 1745 1033 1745 892 1745 892 1746 1033 1746 1034 1746 892 1747 1034 1747 893 1747 893 1748 1034 1748 1035 1748 893 1749 1035 1749 886 1749 886 1750 1035 1750 1036 1750 886 1751 1036 1751 887 1751 887 1752 1036 1752 1037 1752 887 1753 1037 1753 889 1753 889 1754 1037 1754 1038 1754 889 1755 1038 1755 890 1755 933 1756 932 1756 1039 1756 933 1757 1039 1757 940 1757 869 1758 940 1758 1040 1758 1040 1759 940 1759 1039 1759 1040 1760 1039 1760 1041 1760 1041 1761 1039 1761 1042 1761 1043 1762 1044 1762 1045 1762 1046 1763 870 1763 869 1763 1042 1764 1047 1764 1041 1764 1041 1765 1047 1765 1046 1765 1041 1766 1046 1766 1040 1766 1040 1767 1046 1767 869 1767 823 1768 870 1768 1048 1768 1048 1769 870 1769 1046 1769 1048 1770 1046 1770 1045 1770 1045 1771 1046 1771 1047 1771 1045 1772 1047 1772 1043 1772 1049 1773 1050 1773 1051 1773 1050 1774 1052 1774 963 1774 963 1775 1052 1775 1053 1775 963 1776 1053 1776 962 1776 1045 1777 1044 1777 1054 1777 1054 1778 1044 1778 1055 1778 1054 1779 1055 1779 1051 1779 1051 1780 1055 1780 1056 1780 1051 1781 1056 1781 1049 1781 1045 1782 1054 1782 1048 1782 1048 1783 1054 1783 824 1783 1048 1784 824 1784 823 1784 829 1785 824 1785 1057 1785 1057 1786 824 1786 1054 1786 1057 1787 1054 1787 1058 1787 1058 1788 1054 1788 1051 1788 1050 1789 963 1789 1051 1789 1051 1790 963 1790 964 1790 1051 1791 964 1791 1058 1791 1058 1792 964 1792 965 1792 1058 1793 965 1793 966 1793 830 1794 829 1794 1059 1794 1059 1795 829 1795 1057 1795 1059 1796 1057 1796 1060 1796 1060 1797 1057 1797 1058 1797 1060 1798 1058 1798 1061 1798 1061 1799 1058 1799 966 1799 1061 1800 966 1800 901 1800 901 1801 900 1801 1061 1801 1061 1802 900 1802 1062 1802 1061 1803 1062 1803 1060 1803 1060 1804 1062 1804 1059 1804 1059 1805 1062 1805 828 1805 1059 1806 828 1806 830 1806 827 1807 828 1807 1063 1807 1063 1808 828 1808 1062 1808 1063 1809 1062 1809 899 1809 899 1810 1062 1810 900 1810 1064 1811 809 1811 918 1811 897 1812 1064 1812 1065 1812 1064 1813 918 1813 1065 1813 1065 1814 918 1814 917 1814 1065 1815 917 1815 1066 1815 1066 1816 917 1816 915 1816 1066 1817 915 1817 1067 1817 1067 1818 915 1818 914 1818 1067 1819 914 1819 1068 1819 1068 1820 914 1820 922 1820 1068 1821 922 1821 1069 1821 922 1822 921 1822 1069 1822 1069 1823 921 1823 920 1823 1069 1824 920 1824 1070 1824 1070 1825 920 1825 919 1825 1070 1826 919 1826 1071 1826 1071 1827 919 1827 827 1827 1071 1828 827 1828 1063 1828 897 1829 1065 1829 905 1829 905 1830 1065 1830 1066 1830 905 1831 1066 1831 902 1831 902 1832 1066 1832 1067 1832 902 1833 1067 1833 903 1833 903 1834 1067 1834 1068 1834 903 1835 1068 1835 904 1835 904 1836 1068 1836 1069 1836 904 1837 1069 1837 894 1837 894 1838 1069 1838 1070 1838 894 1839 1070 1839 895 1839 895 1840 1070 1840 1071 1840 895 1841 1071 1841 898 1841 898 1842 1071 1842 1063 1842 898 1843 1063 1843 899 1843 856 1844 791 1844 790 1844 1080 1845 1081 1845 1082 1845 1082 1846 1081 1846 1083 1846 1082 1847 1083 1847 1084 1847 1084 1848 1083 1848 1085 1848 1084 1849 1085 1849 1086 1849 1086 1850 1085 1850 794 1850 1086 1851 794 1851 854 1851 856 1852 790 1852 1087 1852 1087 1853 790 1853 789 1853 1087 1854 789 1854 1088 1854 1088 1855 789 1855 788 1855 1088 1856 788 1856 1089 1856 1089 1857 788 1857 787 1857 1089 1858 787 1858 1090 1858 1090 1859 1082 1859 1089 1859 1089 1860 1082 1860 1084 1860 1089 1861 1084 1861 1088 1861 1088 1862 1084 1862 1086 1862 1088 1863 1086 1863 1087 1863 1087 1864 1086 1864 854 1864 1087 1865 854 1865 856 1865 1091 1866 1080 1866 1092 1866 1092 1867 1080 1867 1082 1867 1092 1868 1082 1868 1093 1868 1093 1869 1082 1869 1090 1869 872 1870 1094 1870 1076 1870 1076 1871 1094 1871 1095 1871 1076 1872 1095 1872 1077 1872 1077 1873 1095 1873 1096 1873 1077 1874 1096 1874 1078 1874 872 1875 1097 1875 1094 1875 1094 1876 1097 1876 1098 1876 1094 1877 1098 1877 1095 1877 1095 1878 1098 1878 1099 1878 1095 1879 1099 1879 1096 1879 1096 1880 1099 1880 1100 1880 1096 1881 1100 1881 1101 1881 1078 1882 1096 1882 1079 1882 1079 1883 1096 1883 1101 1883 1079 1884 1101 1884 1074 1884 1074 1885 1101 1885 1102 1885 1074 1886 1102 1886 1075 1886 1103 1887 1104 1887 1105 1887 1105 1888 1104 1888 1102 1888 1105 1889 1102 1889 1106 1889 1106 1890 1102 1890 1101 1890 1106 1891 1101 1891 1107 1891 1107 1892 1101 1892 1100 1892 1093 1893 1108 1893 1092 1893 1092 1894 1108 1894 1091 1894 1090 1895 1104 1895 1093 1895 1093 1896 1104 1896 1103 1896 1093 1897 1103 1897 1108 1897 1075 1898 1102 1898 1073 1898 1073 1899 1102 1899 1104 1899 1073 1900 1104 1900 1072 1900 1072 1901 1104 1901 1090 1901 1072 1902 1090 1902 787 1902 1115 1903 798 1903 796 1903 1091 1904 1108 1904 1116 1904 1115 1905 1117 1905 798 1905 798 1906 1117 1906 1118 1906 798 1907 1118 1907 799 1907 1119 1908 1120 1908 1115 1908 1115 1909 1120 1909 1121 1909 1121 1910 1122 1910 1115 1910 1115 1911 1122 1911 1123 1911 1115 1912 1123 1912 1117 1912 1124 1913 1125 1913 1119 1913 1119 1914 1125 1914 1126 1914 1119 1915 1126 1915 1120 1915 1127 1916 1128 1916 1124 1916 1128 1917 1129 1917 1124 1917 1124 1918 1129 1918 1130 1918 1124 1919 1130 1919 1125 1919 1098 1920 1097 1920 1124 1920 1098 1921 1124 1921 1099 1921 874 1922 1127 1922 875 1922 875 1923 1127 1923 1124 1923 875 1924 1124 1924 877 1924 877 1925 1124 1925 1097 1925 877 1926 1097 1926 872 1926 1105 1927 1106 1927 1119 1927 1119 1928 1106 1928 1107 1928 1119 1929 1107 1929 1124 1929 1124 1930 1107 1930 1100 1930 1124 1931 1100 1931 1099 1931 1083 1932 1081 1932 1116 1932 1116 1933 1081 1933 1080 1933 1116 1934 1080 1934 1091 1934 796 1935 794 1935 1085 1935 1085 1936 1083 1936 796 1936 796 1937 1083 1937 1116 1937 796 1938 1116 1938 1115 1938 1115 1939 1116 1939 1108 1939 1115 1940 1108 1940 1119 1940 1119 1941 1108 1941 1103 1941 1119 1942 1103 1942 1105 1942 818 1943 1131 1943 1132 1943 876 1944 1133 1944 1134 1944 1134 1945 1133 1945 1135 1945 1134 1946 1135 1946 1136 1946 1136 1947 1135 1947 1137 1947 1136 1948 1137 1948 1138 1948 1138 1949 1137 1949 1139 1949 1138 1950 1139 1950 1140 1950 876 1951 1112 1951 1133 1951 1133 1952 1112 1952 1113 1952 1133 1953 1113 1953 1135 1953 1135 1954 1113 1954 1111 1954 1135 1955 1111 1955 1137 1955 1137 1956 1111 1956 1110 1956 1137 1957 1110 1957 1139 1957 1139 1958 1110 1958 1109 1958 1139 1959 1109 1959 1132 1959 1132 1960 1109 1960 1114 1960 1132 1961 1114 1961 818 1961 1140 1962 1139 1962 1141 1962 1141 1963 1139 1963 1132 1963 1141 1964 1132 1964 1142 1964 1142 1965 1132 1965 1131 1965 1142 1966 1131 1966 1143 1966 1131 1967 818 1967 817 1967 1131 1968 817 1968 1144 1968 1144 1969 817 1969 816 1969 1144 1970 816 1970 1145 1970 1145 1971 816 1971 815 1971 1145 1972 815 1972 910 1972 1143 1973 1131 1973 1146 1973 1146 1974 1131 1974 1144 1974 1146 1975 1144 1975 1147 1975 1147 1976 1144 1976 1145 1976 1147 1977 1145 1977 1148 1977 1148 1978 1145 1978 910 1978 1148 1979 910 1979 844 1979 1149 1980 1150 1980 1151 1980 1152 1981 874 1981 873 1981 1152 1982 873 1982 1153 1982 1153 1983 873 1983 1154 1983 1153 1984 1154 1984 1155 1984 1150 1985 1156 1985 1151 1985 1151 1986 1156 1986 1157 1986 1151 1987 1157 1987 1154 1987 1154 1988 1157 1988 1158 1988 1154 1989 1158 1989 1155 1989 1149 1990 1151 1990 1159 1990 1159 1991 1151 1991 848 1991 1159 1992 848 1992 850 1992 1143 1993 1146 1993 1151 1993 1151 1994 1146 1994 1147 1994 1151 1995 1147 1995 848 1995 848 1996 1147 1996 1148 1996 848 1997 1148 1997 844 1997 876 1998 1134 1998 873 1998 873 1999 1134 1999 1136 1999 873 2000 1136 2000 1154 2000 1154 2001 1136 2001 1138 2001 1138 2002 1140 2002 1154 2002 1154 2003 1140 2003 1141 2003 1154 2004 1141 2004 1151 2004 1151 2005 1141 2005 1142 2005 1151 2006 1142 2006 1143 2006 882 2007 1167 2007 1168 2007 1168 2008 1167 2008 1169 2008 1168 2009 1169 2009 1170 2009 882 2010 1160 2010 1167 2010 1167 2011 1160 2011 1161 2011 1167 2012 1161 2012 1169 2012 1169 2013 1161 2013 1165 2013 1169 2014 1165 2014 1171 2014 1170 2015 1169 2015 1172 2015 1172 2016 1169 2016 1171 2016 1172 2017 1171 2017 1173 2017 1173 2018 1171 2018 1174 2018 1173 2019 1174 2019 1175 2019 1166 2020 1176 2020 1162 2020 1162 2021 1176 2021 1174 2021 1162 2022 1174 2022 1163 2022 1163 2023 1174 2023 1171 2023 1163 2024 1171 2024 1164 2024 1164 2025 1171 2025 1165 2025 1166 2026 785 2026 1177 2026 1166 2027 1177 2027 1176 2027 1176 2028 1177 2028 1178 2028 1176 2029 1178 2029 1179 2029 1175 2030 1174 2030 1180 2030 1180 2031 1174 2031 1176 2031 1180 2032 1176 2032 1181 2032 1181 2033 1176 2033 1179 2033 1181 2034 1179 2034 1182 2034 1178 2035 1177 2035 1183 2035 1177 2036 785 2036 784 2036 1184 2037 1179 2037 1178 2037 1177 2038 784 2038 1183 2038 1183 2039 784 2039 786 2039 1183 2040 786 2040 1185 2040 1185 2041 786 2041 792 2041 1185 2042 792 2042 855 2042 1178 2043 1183 2043 1184 2043 1184 2044 1183 2044 1185 2044 1184 2045 1185 2045 1186 2045 1186 2046 1185 2046 855 2046 1186 2047 855 2047 853 2047 1182 2048 1179 2048 1187 2048 1187 2049 1179 2049 1184 2049 1187 2050 1184 2050 1188 2050 1188 2051 1184 2051 1186 2051 1188 2052 1186 2052 1189 2052 1189 2053 1186 2053 853 2053 1189 2054 853 2054 802 2054 1189 2055 802 2055 801 2055 1195 2056 1196 2056 1197 2056 1197 2057 1196 2057 1198 2057 1199 2058 1200 2058 1201 2058 1201 2059 1200 2059 1202 2059 1201 2060 1202 2060 1196 2060 1196 2061 1202 2061 1203 2061 1196 2062 1203 2062 1198 2062 1199 2063 1201 2063 1204 2063 1204 2064 1201 2064 1205 2064 1204 2065 1205 2065 1206 2065 801 2066 800 2066 1207 2066 1207 2067 1208 2067 801 2067 801 2068 1208 2068 1209 2068 801 2069 1209 2069 1205 2069 1205 2070 1209 2070 1210 2070 1205 2071 1210 2071 1206 2071 1189 2072 801 2072 1188 2072 1188 2073 801 2073 1205 2073 1188 2074 1205 2074 1187 2074 1175 2075 1180 2075 1201 2075 1201 2076 1180 2076 1181 2076 1201 2077 1181 2077 1205 2077 1205 2078 1181 2078 1182 2078 1205 2079 1182 2079 1187 2079 881 2080 882 2080 1211 2080 1211 2081 882 2081 1168 2081 1211 2082 1168 2082 1195 2082 1195 2083 1168 2083 1170 2083 1195 2084 1170 2084 1196 2084 1196 2085 1170 2085 1172 2085 1196 2086 1172 2086 1201 2086 1201 2087 1172 2087 1173 2087 1201 2088 1173 2088 1175 2088 825 2089 916 2089 1212 2089 1213 2090 1214 2090 1215 2090 811 2091 1213 2091 1216 2091 1213 2092 1215 2092 1216 2092 1216 2093 1215 2093 1217 2093 1216 2094 1217 2094 1212 2094 1212 2095 1217 2095 1218 2095 1212 2096 1218 2096 825 2096 811 2097 1216 2097 812 2097 812 2098 1216 2098 1212 2098 812 2099 1212 2099 813 2099 813 2100 1212 2100 916 2100 813 2101 916 2101 810 2101 878 2102 1219 2102 1192 2102 1192 2103 1219 2103 1220 2103 1192 2104 1220 2104 1193 2104 1193 2105 1220 2105 1221 2105 1193 2106 1221 2106 1194 2106 878 2107 1222 2107 1219 2107 1219 2108 1222 2108 1223 2108 1219 2109 1223 2109 1220 2109 1220 2110 1223 2110 1224 2110 1220 2111 1224 2111 1221 2111 1221 2112 1224 2112 1225 2112 1221 2113 1225 2113 1226 2113 1214 2114 1213 2114 1227 2114 1227 2115 1213 2115 1226 2115 1227 2116 1226 2116 1228 2116 1228 2117 1226 2117 1225 2117 1194 2118 1221 2118 1191 2118 1191 2119 1221 2119 1226 2119 1191 2120 1226 2120 1190 2120 1190 2121 1226 2121 1213 2121 1190 2122 1213 2122 811 2122 820 2123 819 2123 1229 2123 1229 2124 819 2124 1230 2124 1229 2125 1230 2125 1231 2125 1231 2126 1230 2126 1232 2126 1233 2127 1234 2127 1230 2127 1230 2128 1234 2128 1235 2128 1230 2129 1235 2129 1232 2129 1236 2130 1237 2130 1233 2130 1237 2131 1238 2131 1233 2131 1233 2132 1238 2132 1239 2132 1233 2133 1239 2133 1234 2133 1240 2134 879 2134 880 2134 1236 2135 1240 2135 1241 2135 1241 2136 1240 2136 880 2136 1241 2137 880 2137 1242 2137 1242 2138 880 2138 881 2138 1225 2139 1224 2139 1240 2139 1240 2140 1224 2140 1223 2140 1240 2141 1223 2141 879 2141 879 2142 1223 2142 1222 2142 879 2143 1222 2143 878 2143 1236 2144 1233 2144 1240 2144 1240 2145 1233 2145 1228 2145 1240 2146 1228 2146 1225 2146 1217 2147 1215 2147 1230 2147 1230 2148 1215 2148 1214 2148 1230 2149 1214 2149 1233 2149 1233 2150 1214 2150 1227 2150 1233 2151 1227 2151 1228 2151 1217 2152 1230 2152 1218 2152 1218 2153 1230 2153 819 2153 1218 2154 819 2154 825 2154 113 2155 95 2155 1243 2155 1243 2156 95 2156 858 2156 1243 2157 858 2157 857 2157 113 2158 1243 2158 111 2158 111 2159 1243 2159 1244 2159 111 2160 1244 2160 109 2160 109 2161 1244 2161 1245 2161 109 2162 1245 2162 107 2162 107 2163 1245 2163 807 2163 107 2164 807 2164 105 2164 862 2165 867 2165 1246 2165 866 2166 871 2166 1247 2166 871 2167 822 2167 1247 2167 1247 2168 822 2168 1248 2168 1247 2169 1248 2169 1249 2169 1249 2170 1248 2170 1250 2170 1249 2171 1250 2171 1251 2171 1251 2172 1250 2172 1252 2172 1251 2173 1252 2173 795 2173 795 2174 1252 2174 793 2174 867 2175 866 2175 1246 2175 1246 2176 866 2176 1247 2176 1246 2177 1247 2177 1253 2177 1253 2178 1247 2178 1249 2178 1253 2179 1249 2179 1254 2179 1254 2180 1249 2180 1251 2180 1254 2181 1251 2181 797 2181 797 2182 1251 2182 795 2182 863 2183 862 2183 1255 2183 1255 2184 862 2184 1246 2184 1255 2185 1246 2185 1256 2185 1256 2186 1246 2186 1253 2186 1256 2187 1253 2187 1257 2187 1257 2188 1253 2188 1254 2188 1257 2189 1254 2189 805 2189 805 2190 1254 2190 797 2190 857 2191 863 2191 1243 2191 1243 2192 863 2192 1255 2192 1243 2193 1255 2193 1244 2193 1244 2194 1255 2194 1256 2194 1244 2195 1256 2195 1245 2195 1245 2196 1256 2196 1257 2196 1245 2197 1257 2197 807 2197 807 2198 1257 2198 805 2198 793 2199 1252 2199 800 2199 800 2200 1252 2200 1258 2200 822 2201 826 2201 1248 2201 1248 2202 826 2202 1258 2202 1248 2203 1258 2203 1250 2203 1250 2204 1258 2204 1252 2204 821 2205 820 2205 1259 2205 1259 2206 820 2206 1260 2206 1259 2207 1260 2207 1207 2207 1207 2208 1260 2208 1208 2208 826 2209 821 2209 1258 2209 1258 2210 821 2210 1259 2210 1258 2211 1259 2211 800 2211 800 2212 1259 2212 1207 2212 1208 2213 1260 2213 1261 2213 881 2214 1262 2214 1242 2214 1242 2215 1262 2215 1263 2215 1242 2216 1263 2216 1241 2216 881 2217 1211 2217 1262 2217 1262 2218 1211 2218 1195 2218 1262 2219 1195 2219 1263 2219 1263 2220 1195 2220 1197 2220 1263 2221 1197 2221 1264 2221 1264 2222 1197 2222 1198 2222 1241 2223 1263 2223 1236 2223 1236 2224 1263 2224 1264 2224 1236 2225 1264 2225 1237 2225 1237 2226 1264 2226 1265 2226 1237 2227 1265 2227 1238 2227 1198 2228 1203 2228 1264 2228 1264 2229 1203 2229 1202 2229 1264 2230 1202 2230 1265 2230 1265 2231 1202 2231 1200 2231 1265 2232 1200 2232 1266 2232 1266 2233 1200 2233 1199 2233 1266 2234 1199 2234 1267 2234 1238 2235 1265 2235 1239 2235 1239 2236 1265 2236 1266 2236 1239 2237 1266 2237 1234 2237 1234 2238 1266 2238 1267 2238 1234 2239 1267 2239 1235 2239 1235 2240 1267 2240 1268 2240 1235 2241 1268 2241 1232 2241 1199 2242 1204 2242 1267 2242 1267 2243 1204 2243 1206 2243 1267 2244 1206 2244 1268 2244 1268 2245 1206 2245 1210 2245 1268 2246 1210 2246 1261 2246 1261 2247 1210 2247 1209 2247 1261 2248 1209 2248 1208 2248 1232 2249 1268 2249 1231 2249 1231 2250 1268 2250 1261 2250 1231 2251 1261 2251 1229 2251 1229 2252 1261 2252 1260 2252 1229 2253 1260 2253 820 2253 103 2254 808 2254 1269 2254 103 2255 1269 2255 100 2255 100 2256 1269 2256 1270 2256 100 2257 1270 2257 98 2257 98 2258 1270 2258 838 2258 98 2259 838 2259 96 2259 808 2260 806 2260 1269 2260 1269 2261 806 2261 1271 2261 1269 2262 1271 2262 1270 2262 1270 2263 1271 2263 1272 2263 1270 2264 1272 2264 838 2264 831 2265 834 2265 1272 2265 1272 2266 834 2266 840 2266 1272 2267 840 2267 838 2267 1273 2268 1274 2268 1275 2268 1275 2269 1274 2269 1276 2269 1275 2270 1276 2270 803 2270 803 2271 1276 2271 804 2271 806 2272 804 2272 1271 2272 1271 2273 804 2273 1276 2273 1271 2274 1276 2274 1272 2274 1272 2275 1276 2275 1274 2275 1272 2276 1274 2276 831 2276 831 2277 1274 2277 1273 2277 831 2278 1273 2278 832 2278 803 2279 799 2279 1277 2279 803 2280 1277 2280 1275 2280 1275 2281 1277 2281 1278 2281 1275 2282 1278 2282 1273 2282 1273 2283 1278 2283 843 2283 1273 2284 843 2284 832 2284 1279 2285 1280 2285 849 2285 849 2286 1280 2286 850 2286 1118 2287 1117 2287 1281 2287 1281 2288 1117 2288 1282 2288 1281 2289 1282 2289 1279 2289 1279 2290 1282 2290 1283 2290 1279 2291 1283 2291 1280 2291 799 2292 1118 2292 1277 2292 1277 2293 1118 2293 1281 2293 1277 2294 1281 2294 1278 2294 1278 2295 1281 2295 1279 2295 1278 2296 1279 2296 843 2296 843 2297 1279 2297 849 2297 1159 2298 1284 2298 1285 2298 874 2299 1286 2299 1127 2299 1127 2300 1286 2300 1287 2300 874 2301 1152 2301 1286 2301 1286 2302 1152 2302 1153 2302 1286 2303 1153 2303 1287 2303 1287 2304 1153 2304 1155 2304 1158 2305 1288 2305 1155 2305 1155 2306 1288 2306 1289 2306 1155 2307 1289 2307 1287 2307 1287 2308 1289 2308 1128 2308 1287 2309 1128 2309 1127 2309 1290 2310 1125 2310 1288 2310 1288 2311 1125 2311 1130 2311 1288 2312 1130 2312 1289 2312 1289 2313 1130 2313 1129 2313 1289 2314 1129 2314 1128 2314 1158 2315 1157 2315 1288 2315 1288 2316 1157 2316 1156 2316 1288 2317 1156 2317 1290 2317 1290 2318 1156 2318 1150 2318 1290 2319 1150 2319 1285 2319 1285 2320 1150 2320 1149 2320 1285 2321 1149 2321 1159 2321 1123 2322 1122 2322 1284 2322 1284 2323 1122 2323 1121 2323 1284 2324 1121 2324 1285 2324 1285 2325 1121 2325 1120 2325 1285 2326 1120 2326 1290 2326 1290 2327 1120 2327 1126 2327 1290 2328 1126 2328 1125 2328 1282 2329 1117 2329 1123 2329 1282 2330 1123 2330 1283 2330 1283 2331 1123 2331 1284 2331 1283 2332 1284 2332 1280 2332 1280 2333 1284 2333 1159 2333 1280 2334 1159 2334 850 2334 836 2335 1020 2335 958 2335 958 2336 1020 2336 1019 2336 958 2337 1019 2337 955 2337 955 2338 1019 2338 1018 2338 955 2339 1018 2339 956 2339 956 2340 1018 2340 1015 2340 1291 2341 953 2341 952 2341 1017 2342 1291 2342 1016 2342 1016 2343 1291 2343 952 2343 1016 2344 952 2344 1015 2344 1015 2345 952 2345 957 2345 1015 2346 957 2346 956 2346 1292 2347 989 2347 1006 2347 962 2348 1292 2348 961 2348 961 2349 1292 2349 1006 2349 961 2350 1006 2350 960 2350 960 2351 1006 2351 1005 2351 960 2352 1005 2352 782 2352 1044 2353 1293 2353 1294 2353 1292 2354 962 2354 1053 2354 989 2355 1292 2355 1295 2355 1292 2356 1053 2356 1295 2356 1295 2357 1053 2357 1052 2357 1295 2358 1052 2358 1296 2358 1296 2359 1052 2359 1050 2359 1296 2360 1050 2360 1297 2360 1297 2361 1050 2361 1049 2361 1297 2362 1049 2362 1298 2362 1298 2363 1049 2363 1056 2363 1298 2364 1056 2364 1294 2364 1294 2365 1056 2365 1055 2365 1294 2366 1055 2366 1044 2366 989 2367 1295 2367 990 2367 990 2368 1295 2368 1296 2368 990 2369 1296 2369 991 2369 991 2370 1296 2370 1297 2370 991 2371 1297 2371 992 2371 992 2372 1297 2372 1298 2372 992 2373 1298 2373 993 2373 993 2374 1298 2374 1294 2374 993 2375 1294 2375 988 2375 988 2376 1294 2376 1293 2376 988 2377 1293 2377 985 2377 1047 2378 1042 2378 1299 2378 986 2379 985 2379 1300 2379 1300 2380 985 2380 1293 2380 1300 2381 1293 2381 1043 2381 1043 2382 1293 2382 1044 2382 994 2383 986 2383 1299 2383 1299 2384 986 2384 1300 2384 1299 2385 1300 2385 1047 2385 1047 2386 1300 2386 1043 2386 995 2387 994 2387 1301 2387 1301 2388 994 2388 1299 2388 1301 2389 1299 2389 1039 2389 1039 2390 1299 2390 1042 2390 996 2391 995 2391 1302 2391 1302 2392 995 2392 1301 2392 1302 2393 1301 2393 932 2393 932 2394 1301 2394 1039 2394 777 2395 1303 2395 938 2395 938 2396 1303 2396 1304 2396 938 2397 1304 2397 928 2397 928 2398 1304 2398 929 2398 929 2399 1304 2399 1305 2399 929 2400 1305 2400 934 2400 934 2401 1305 2401 935 2401 935 2402 1305 2402 1306 2402 935 2403 1306 2403 939 2403 996 2404 1302 2404 998 2404 998 2405 1302 2405 1306 2405 998 2406 1306 2406 984 2406 984 2407 1306 2407 1305 2407 984 2408 1305 2408 983 2408 983 2409 1305 2409 1304 2409 983 2410 1304 2410 981 2410 981 2411 1304 2411 1303 2411 981 2412 1303 2412 978 2412 978 2413 1303 2413 777 2413 939 2414 1306 2414 931 2414 931 2415 1306 2415 1302 2415 931 2416 1302 2416 932 2416 1307 2417 968 2417 967 2417 1003 2418 1307 2418 987 2418 987 2419 1307 2419 1308 2419 987 2420 1308 2420 1004 2420 1004 2421 1308 2421 783 2421 1307 2422 967 2422 1308 2422 1308 2423 967 2423 970 2423 1308 2424 970 2424 783 2424 1309 2425 1017 2425 1010 2425 1310 2426 1311 2426 1312 2426 1312 2427 1311 2427 1309 2427 976 2428 1313 2428 977 2428 977 2429 1313 2429 1310 2429 977 2430 1310 2430 997 2430 1309 2431 1010 2431 1312 2431 1312 2432 1010 2432 1008 2432 1312 2433 1008 2433 1314 2433 1008 2434 1007 2434 1314 2434 1314 2435 1007 2435 1021 2435 1314 2436 1021 2436 1315 2436 1021 2437 1014 2437 1315 2437 1315 2438 1014 2438 1013 2438 1315 2439 1013 2439 1316 2439 1316 2440 1013 2440 1011 2440 1316 2441 1011 2441 1317 2441 1317 2442 1011 2442 968 2442 1317 2443 968 2443 1307 2443 1310 2444 1312 2444 997 2444 997 2445 1312 2445 1314 2445 997 2446 1314 2446 999 2446 999 2447 1314 2447 1315 2447 999 2448 1315 2448 1000 2448 1000 2449 1315 2449 1316 2449 1000 2450 1316 2450 1001 2450 1001 2451 1316 2451 1317 2451 1001 2452 1317 2452 1002 2452 1002 2453 1317 2453 1307 2453 1002 2454 1307 2454 1003 2454 1311 2455 1318 2455 1309 2455 1319 2456 1313 2456 976 2456 1309 2457 1318 2457 1017 2457 1320 2458 953 2458 1291 2458 1313 2459 1319 2459 1310 2459 1310 2460 1319 2460 1321 2460 1310 2461 1321 2461 1311 2461 1311 2462 1321 2462 1320 2462 1311 2463 1320 2463 1318 2463 1318 2464 1320 2464 1291 2464 1318 2465 1291 2465 1017 2465 776 2466 945 2466 1322 2466 1322 2467 945 2467 947 2467 948 2468 1323 2468 947 2468 947 2469 1323 2469 1324 2469 947 2470 1324 2470 1322 2470 954 2471 953 2471 1320 2471 948 2472 950 2472 1323 2472 1323 2473 950 2473 949 2473 1323 2474 949 2474 1325 2474 1325 2475 949 2475 954 2475 954 2476 1320 2476 1325 2476 1325 2477 1320 2477 1321 2477 1325 2478 1321 2478 1319 2478 776 2479 1322 2479 979 2479 979 2480 1322 2480 1324 2480 979 2481 1324 2481 980 2481 980 2482 1324 2482 1323 2482 980 2483 1323 2483 982 2483 982 2484 1323 2484 1325 2484 982 2485 1325 2485 975 2485 975 2486 1325 2486 1319 2486 975 2487 1319 2487 976 2487 491 2488 486 2488 127 2488 127 2488 486 2488 230 2488 127 2488 230 2488 229 2488 348 2488 347 2488 253 2488 484 2488 156 2488 125 2488 125 2488 156 2488 158 2488 235 2488 233 2488 125 2488 125 2488 233 2488 585 2488 229 2488 225 2488 127 2488 127 2488 225 2488 525 2488 127 2488 525 2488 164 2488 164 2488 168 2488 127 2488 127 2488 168 2488 434 2488 127 2488 434 2488 244 2488 244 2488 242 2488 127 2488 127 2488 242 2488 365 2488 127 2488 365 2488 359 2488 359 2488 365 2488 364 2488 348 2488 253 2488 353 2488 585 2488 583 2488 125 2488 125 2488 583 2488 128 2488 125 2488 128 2488 127 2488 127 2488 128 2488 133 2488 127 2488 133 2488 491 2488 353 2488 253 2488 125 2488 125 2488 253 2488 266 2488 125 2488 266 2488 484 2488 158 2488 617 2488 125 2488 125 2488 617 2488 237 2488 125 2488 237 2488 235 2488 122 2489 123 2489 290 2489 290 2490 123 2490 324 2490 290 2491 324 2491 289 2491 289 2492 324 2492 325 2492 289 2493 325 2493 323 2493 322 2494 321 2494 292 2494 292 2495 321 2495 293 2495 322 2496 292 2496 323 2496 323 2497 292 2497 291 2497 323 2498 291 2498 289 2498 296 2499 295 2499 294 2499 293 2500 321 2500 294 2500 294 2501 321 2501 320 2501 294 2502 320 2502 296 2502 319 2503 317 2503 1326 2503 46 2504 51 2504 316 2504 316 2505 51 2505 297 2505 316 2506 297 2506 317 2506 317 2507 297 2507 296 2507 317 2508 296 2508 1326 2508 1326 2509 296 2509 320 2509 1326 2510 320 2510 319 2510

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_collision_C6M2.dae b/URDFs/sr_description/meshes/components/forearm/forearm_collision_C6M2.dae new file mode 100644 index 0000000..3bfce97 --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_collision_C6M2.dae @@ -0,0 +1,134 @@ + + + + + + Blender User + Blender 2.65.10 r54602 + + 2013-02-21T11:19:02 + 2013-02-21T11:19:02 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -0.07187819 -0.004186391 0 0.04628068 0.05515515 0 -0.06897521 -0.02064979 0 -0.06235378 -0.03599995 0 0.008358657 -0.07151311 0 -0.008358657 -0.07151311 0 -0.02462542 -0.06765782 0 -0.05775284 0.04299539 0 0 0.07199996 0 -0.06611156 0.02851772 0 0.0166043 0.07005923 0 0.0395646 -0.06015509 0 0.05775284 0.04299539 0 0.06611156 0.02851772 0 0.07187819 -0.004186391 0 0.06897521 -0.02064979 0 0.06235378 -0.03599995 0 0.02462542 -0.06765782 0 -0.0395646 -0.06015509 0 -0.0523709 -0.04940938 0 -0.07090616 0.01250267 0 0.03231352 0.06434154 0 0.07090616 0.01250267 0 0.0523709 -0.04940938 0 -0.04628068 0.05515515 0 -0.03231352 0.06434154 0 -0.0166043 0.07005923 0 -0.0166043 0.07005923 0 -0.01654911 0.0698353 0.1216 -0.01154959 0.07106757 0.1216 0 0.07199996 0 -0.02280008 0.06829458 0.1216 -0.03231352 0.06434154 0 -0.03227734 0.06425672 0.1216 -0.03346002 0.06375283 0.1216 -0.04628068 0.05515515 0 -0.04325342 0.05755984 0.1216 -0.05925482 0.04090064 0.1216 -0.05762785 0.04289335 0.1216 -0.05775284 0.04299539 0 -0.05192655 0.04987615 0.1216 -0.04614305 0.05499982 0.1216 -0.06504839 0.03086584 0.1216 -0.06611156 0.02851772 0 -0.06596064 0.0284605 0.1216 -0.0691573 0.02003163 0.1216 -0.07090616 0.01250267 0 -0.07070279 0.01246112 0.1216 -0.07147502 0.008678615 0.1216 -0.07187819 -0.004186391 0 -0.07194161 -0.00289911 0.1216 -0.06897521 -0.02064979 0 -0.07054489 -0.01440185 0.1216 -0.07178664 -0.004175305 0.1216 -0.06235378 -0.03599995 0 -0.06732112 -0.02553153 0.1216 -0.06875371 -0.02058565 0.1216 -0.0523709 -0.04940938 0 -0.05577152 -0.04553604 0.1216 -0.06235378 -0.03599995 0.1216 -0.0395646 -0.06015509 0 -0.04774481 -0.05389273 0.1216 -0.05220454 -0.04924964 0.1216 -0.02455973 -0.06746101 0.1216 -0.02822154 -0.06623852 0.1216 -0.02462542 -0.06765782 0 -0.03848153 -0.06085366 0.1216 -0.03950923 -0.06008136 0.1216 -0.01723068 -0.06990778 0.1216 -0.008358657 -0.07151311 0 -0.008332788 -0.07135385 0.1216 -0.005793571 -0.07176649 0.1216 0.008358657 -0.07151311 0 0.005793571 -0.07176649 0.1216 0.02822154 -0.06623852 0.1216 0.02455973 -0.06746101 0.1216 0.02462542 -0.06765782 0 0.01723068 -0.06990778 0.1216 0.008332788 -0.07135385 0.1216 0.03848153 -0.06085366 0.1216 0.0395646 -0.06015509 0 0.03950923 -0.06008136 0.1216 0.04774481 -0.05389273 0.1216 0.0523709 -0.04940938 0 0.05220454 -0.04924964 0.1216 0.05577152 -0.04553604 0.1216 0.06235378 -0.03599995 0 0.06235378 -0.03599995 0.1216 0.06732112 -0.02553153 0.1216 0.06897521 -0.02064979 0 0.06875371 -0.02058565 0.1216 0.07054489 -0.01440185 0.1216 0.07187819 -0.004186391 0 0.07178664 -0.004175305 0.1216 0.07090616 0.01250267 0 0.07147502 0.008678615 0.1216 0.07194161 -0.00289911 0.1216 0.06611156 0.02851772 0 0.0691573 0.02003163 0.1216 0.07070279 0.01246112 0.1216 0.05762785 0.04289335 0.1216 0.05925482 0.04090064 0.1216 0.05775284 0.04299539 0 0.06504839 0.03086584 0.1216 0.06596064 0.0284605 0.1216 0.05192655 0.04987615 0.1216 0.04628068 0.05515515 0 0.04614305 0.05499982 0.1216 0.03231352 0.06434154 0 0.03346002 0.06375283 0.1216 0.04325342 0.05755984 0.1216 0.0166043 0.07005923 0 0.02280008 0.06829458 0.1216 0.03227734 0.06425672 0.1216 0 0.07199996 0.1216 0.01154959 0.07106757 0.1216 0.01654911 0.0698353 0.1216 0.03247708 0.06742197 0.12494 0.03485423 0.06640917 0.12494 0.03479444 0.06629526 0.1236902 0.05845278 0.04661101 0.12494 0.06172376 0.0426048 0.12494 0.06161791 0.04253172 0.1236902 0.0166741 -0.07302772 0.12494 0.00603497 -0.0747568 0.12494 0.006024599 -0.07462853 0.1236902 -0.05858427 -0.04672509 0.12494 -0.06495189 -0.03749996 0.12494 -0.06484049 -0.03743565 0.1236902 -0.07481777 -7.34357e-6 0.12494 -0.07445317 0.009040236 0.12494 -0.07432544 0.009024739 0.1236902 -0.04666709 0.05853056 0.12494 -0.04505562 0.05995815 0.12494 -0.04497838 0.05985534 0.1236902 0.06615871 0.03139269 0.1218616 0.06026619 0.04159873 0.1218616 0.06110221 0.04217582 0.122601 0.05672347 -0.04631328 0.1218616 0.06341809 -0.03661447 0.1218616 0.06429785 -0.03712236 0.122601 -0.0117467 0.07228064 0.1218616 -0.02318924 0.06946033 0.1218616 -0.02351093 0.07042384 0.122601 0.0117467 0.07228064 0.1218616 0.04399168 0.05854231 0.1218616 0.07269501 0.008826732 0.1218616 0.07174903 -0.01464766 0.1218616 0.04855972 -0.05481261 0.1218616 0.03913831 -0.06189233 0.1218616 0.01752483 -0.071101 0.1218616 0.005892455 -0.07299149 0.1218616 -0.02870327 -0.0673691 0.1218616 -0.05672347 -0.04631328 0.1218616 -0.07174903 -0.01464766 0.1218616 -0.07316952 -0.002948582 0.1218616 -0.07033771 0.02037352 0.1218616 -0.06615871 0.03139269 0.1218616 -0.05281287 0.05072742 0.1218616 -0.03403115 0.06484097 0.1218616 -0.04399168 0.05854231 0.1218616 -0.06026619 0.04159873 0.1218616 -0.03913831 -0.06189233 0.1218616 -0.005892455 -0.07299149 0.1218616 0.06847023 -0.02596729 0.1218616 0.07316952 -0.002948582 0.1218616 0.05281287 0.05072742 0.1218616 0.03403115 0.06484097 0.1218616 0.02318924 0.06946033 0.1218616 0 0.07322895 0.1218616 -0.03479444 0.06629526 0.1236902 -0.03450322 0.06574046 0.122601 0.07000589 -0.02654969 0.1236902 0.06942003 -0.02632755 0.122601 0.0737034 0.00894922 0.122601 0.07418453 -0.00298953 0.122601 0.05399739 0.05186516 0.1236902 0.05354547 0.05143111 0.122601 0.01190966 0.07328331 0.122601 0 0.07424473 0.122601 -0.01190966 0.07328331 0.122601 -0.0676425 0.03209674 0.1236902 -0.06161791 0.04253172 0.1236902 -0.06110221 0.04217582 0.122601 -0.07290077 0.01664435 0.12494 -0.07203882 0.02086627 0.12494 -0.07191526 0.02083051 0.1236902 -0.06707644 0.03182816 0.122601 -0.07269501 0.008826732 0.1218616 -0.0737034 0.00894922 0.122601 -0.07418453 -0.00298953 0.122601 -0.07481062 -0.003014743 0.1236902 -0.07335823 -0.01497614 0.1236902 -0.06847023 -0.02596729 0.1218616 -0.06341809 -0.03661447 0.1218616 -0.06429785 -0.03712236 0.122601 -0.05751037 -0.04695576 0.122601 -0.05799567 -0.04735201 0.1236902 -0.04964888 -0.05604195 0.1236902 -0.04855972 -0.05481261 0.1218616 -0.03968125 -0.06275093 0.122601 -0.02910143 -0.06830364 0.122601 -0.02934706 -0.06888008 0.1236902 -0.01791787 -0.07269573 0.1236902 0.005974173 -0.07400399 0.122601 0.0177679 -0.07208734 0.122601 0.01791787 -0.07269573 0.1236902 0.02934706 -0.06888008 0.1236902 0.02870327 -0.0673691 0.1218616 0.03968125 -0.06275093 0.122601 0.04923337 -0.05557298 0.122601 0.04964888 -0.05604195 0.1236902 0.05799567 -0.04735201 0.1236902 0.07481062 -0.003014743 0.1236902 0.07432544 0.009024739 0.1236902 0.07191526 0.02083051 0.1236902 0.07131344 0.02065616 0.122601 0.0676425 0.03209674 0.1236902 0.06775873 0.03215193 0.12494 0.06754362 0.03252452 0.12494 0.01201015 0.07390177 0.1236902 0 0.0748713 0.1236902 -0.01201015 0.07390177 0.1236902 -0.02370935 0.07101815 0.1236902 -0.03485423 0.06640917 0.12494 -0.03247708 0.06742197 0.12494 -0.04460197 0.05935442 0.122601 -0.05354547 0.05143111 0.122601 -0.05399739 0.05186516 0.1236902 -0.05409014 0.05195432 0.12494 -0.05845278 0.04661101 0.12494 -0.06775873 0.03215193 0.12494 -0.06754362 0.03252452 0.12494 -0.06172376 0.0426048 0.12494 -0.07131344 0.02065616 0.122601 -0.06735402 -0.0324375 0.12494 -0.07012617 -0.02659535 0.12494 -0.07000589 -0.02654969 0.1236902 -0.0727443 -0.01485085 0.122601 -0.07300519 -0.01665592 0.12494 -0.0734843 -0.01500189 0.12494 -0.07493913 -0.003019928 0.12494 -0.06942003 -0.02632755 0.122601 -0.032449 -0.06739687 0.12494 -0.04008489 -0.06338924 0.12494 -0.04001617 -0.06328052 0.1236902 -0.04923337 -0.05557298 0.122601 -0.04663425 -0.05846774 0.12494 -0.04973417 -0.05613827 0.12494 -0.05809533 -0.04743337 0.12494 0 -0.0747568 0.12494 -0.00603497 -0.0747568 0.12494 -0.006024599 -0.07462853 0.1236902 -0.0177679 -0.07208734 0.122601 -0.0166741 -0.07302772 0.12494 -0.01794862 -0.0728206 0.12494 -0.02939748 -0.06899845 0.12494 -0.01752483 -0.071101 0.1218616 -0.005974173 -0.07400399 0.122601 0.04663425 -0.05846774 0.12494 0.04008489 -0.06338924 0.12494 0.04001617 -0.06328052 0.1236902 0.02910143 -0.06830364 0.122601 0.032449 -0.06739687 0.12494 0.02939748 -0.06899845 0.12494 0.01794862 -0.0728206 0.12494 0.06735402 -0.0324375 0.12494 0.06495189 -0.03749996 0.12494 0.06484049 -0.03743565 0.1236902 0.05751037 -0.04695576 0.122601 0.05858427 -0.04672509 0.12494 0.05809533 -0.04743337 0.12494 0.04973417 -0.05613827 0.12494 0.07012617 -0.02659535 0.12494 0.07335823 -0.01497614 0.1236902 0.0734843 -0.01500189 0.12494 0.07300519 -0.01665592 0.12494 0.0727443 -0.01485085 0.122601 0.07493913 -0.003019928 0.12494 0.07203882 0.02086627 0.12494 0.07290077 0.01664435 0.12494 0.07445317 0.009040236 0.12494 0.07481777 -7.34357e-6 0.12494 0.06707644 0.03182816 0.122601 0.07033771 0.02037352 0.1218616 0.05409014 0.05195432 0.12494 0.04497838 0.05985534 0.1236902 0.04505562 0.05995815 0.12494 0.04666709 0.05853056 0.12494 0.04460197 0.05935442 0.122601 0.03450322 0.06574046 0.122601 0.02351093 0.07042384 0.122601 0.02370935 0.07101815 0.1236902 0.02375006 0.07114022 0.12494 0.01663351 0.07289427 0.12494 -0.02375006 0.07114022 0.12494 -0.01663351 0.07289427 0.12494 -0.01203083 0.07402873 0.12494 0 0.07499998 0.12494 0.01203083 0.07402873 0.12494 0 0.04996079 0.3576697 -0.009746849 0.04900079 0.3576697 -0.01108312 0.04859542 0.3576697 -0.01911914 0.04615771 0.3576697 -0.02158457 0.04483991 0.3576697 -0.02775669 0.04154086 0.3576697 -0.03100055 0.03887873 0.3576697 -0.03532761 0.03532761 0.3576697 -0.03887873 0.03100055 0.3576697 -0.04154086 0.02775669 0.3576697 -0.04483991 0.02158457 0.3576697 -0.04615771 0.01911914 0.3576697 -0.04859542 0.01108312 0.3576697 -0.04900079 0.009746849 0.3576697 -0.04996079 0 0.3576697 -0.04900079 -0.009746849 0.3576697 -0.04859542 -0.01108312 0.3576697 -0.04615771 -0.01911914 0.3576697 -0.04483991 -0.02158457 0.3576697 -0.04154086 -0.02775669 0.3576697 -0.03887873 -0.03100055 0.3576697 -0.03532761 -0.03532761 0.3576697 -0.03100055 -0.03887873 0.3576697 -0.02775669 -0.04154086 0.3576697 -0.02158457 -0.04483991 0.3576697 -0.01911914 -0.04615771 0.3576697 -0.01108312 -0.04859542 0.3576697 -0.009746849 -0.04900079 0.3576697 0 -0.04996079 0.3576697 0.009746849 -0.04900079 0.3576697 0.01108312 -0.04859542 0.3576697 0.01911914 -0.04615771 0.3576697 0.02158457 -0.04483991 0.3576697 0.02775669 -0.04154086 0.3576697 0.03100055 -0.03887873 0.3576697 0.03532761 -0.03532761 0.3576697 0.04996079 0 0.3576697 0.04900079 -0.009746849 0.3576697 0.03887873 -0.03100055 0.3576697 0.04154086 -0.02775669 0.3576697 0.04483991 -0.02158457 0.3576697 0.04615771 -0.01911914 0.3576697 0.04859542 -0.01108312 0.3576697 0.04900079 0.009746849 0.3576697 0.04859542 0.01108312 0.3576697 0.04615771 0.01911914 0.3576697 0.04483991 0.02158457 0.3576697 0.04154086 0.02775669 0.3576697 0.03887873 0.03100055 0.3576697 0.03532761 0.03532761 0.3576697 0.03100055 0.03887873 0.3576697 0.02775669 0.04154086 0.3576697 0.02158457 0.04483991 0.3576697 0.01911914 0.04615771 0.3576697 0.01108312 0.04859542 0.3576697 0.009746849 0.04900079 0.3576697 0 0.04001814 0.3666 0 -0.04001814 0.3666 0.007807135 -0.03924924 0.3666 -0.007807135 0.03924924 0.3666 -0.01531428 -0.03697192 0.3666 -0.007807135 -0.03924924 0.3666 0.01531428 -0.03697192 0.3666 0.02223289 -0.03327387 0.3666 0.02829712 -0.02829712 0.3666 0.03327387 -0.02223289 0.3666 0.03697192 -0.01531428 0.3666 0.03924924 -0.007807135 0.3666 -0.01531428 0.03697192 0.3666 -0.02223289 0.03327387 0.3666 -0.02829712 0.02829712 0.3666 -0.03327387 0.02223289 0.3666 -0.03697192 0.01531428 0.3666 -0.03924924 0.007807135 0.3666 -0.04001814 0 0.3666 -0.03924924 -0.007807135 0.3666 -0.03697192 -0.01531428 0.3666 -0.03327387 -0.02223289 0.3666 -0.02829712 -0.02829712 0.3666 -0.02223289 -0.03327387 0.3666 0.04001814 0 0.3666 0.03924924 0.007807135 0.3666 0.03697192 0.01531428 0.3666 0.02829712 0.02829712 0.3666 0.02223289 0.03327387 0.3666 0.01531428 0.03697192 0.3666 0.03327387 0.02223289 0.3666 0.007807135 0.03924924 0.3666 0.04067534 -0.0271784 0.3611563 0.0271784 0.04067534 0.3611563 -0.04067534 0.0271784 0.3611563 -0.0271784 -0.04067534 0.3611563 0.01668351 -0.04027754 0.365938 0.0242207 -0.0362488 0.365938 0.0308271 -0.0308271 0.365938 0.0362488 -0.0242207 0.365938 0.04027754 0.01668351 0.365938 0.0362488 0.0242207 0.365938 0.0308271 0.0308271 0.365938 0.0242207 0.0362488 0.365938 -0.01668351 0.04027754 0.365938 -0.0242207 0.0362488 0.365938 -0.0308271 0.0308271 0.365938 -0.0362488 0.0242207 0.365938 -0.04027754 -0.01668351 0.365938 -0.0362488 -0.0242207 0.365938 -0.0308271 -0.0308271 0.365938 -0.0242207 -0.0362488 0.365938 -0.04027754 0.01668351 0.365938 -0.0427584 0.008505165 0.365938 -0.04001814 0 0.3666 -0.04359608 0 0.365938 -0.0427584 -0.008505165 0.365938 0.01668351 0.04027754 0.365938 0.008505165 0.0427584 0.365938 0 0.04001814 0.3666 0 0.04359608 0.365938 -0.008505165 0.0427584 0.365938 0.04027754 -0.01668351 0.365938 0.0427584 -0.008505165 0.365938 0.04001814 0 0.3666 0.04359608 0 0.365938 0.0427584 0.008505165 0.365938 -0.01668351 -0.04027754 0.365938 -0.008505165 -0.0427584 0.365938 0 -0.04001814 0.3666 0 -0.04359608 0.365938 0.008505165 -0.0427584 0.365938 -0.04314547 0.01787143 0.3640397 -0.04580301 0.009110748 0.3640397 -0.04670029 0 0.3640397 -0.04580301 -0.009110748 0.3640397 0.01787143 0.04314547 0.3640397 0.009110748 0.04580301 0.3640397 0 0.04670029 0.3640397 -0.009110748 0.04580301 0.3640397 0.04314547 -0.01787143 0.3640397 0.04580301 -0.009110748 0.3640397 0.04670029 0 0.3640397 0.04580301 0.009110748 0.3640397 -0.01787143 -0.04314547 0.3640397 -0.009110748 -0.04580301 0.3640397 0 -0.04670029 0.3640397 0.009110748 -0.04580301 0.3640397 -0.04519605 0.0187208 0.3611563 -0.04797983 0.009543776 0.3611563 -0.04891985 0 0.3611563 -0.04797983 -0.009543776 0.3611563 0.0187208 0.04519605 0.3611563 0.009543776 0.04797983 0.3611563 0 0.04891985 0.3611563 -0.009543776 0.04797983 0.3611563 0.04519605 -0.0187208 0.3611563 0.04797983 -0.009543776 0.3611563 0.04891985 0 0.3611563 0.04797983 0.009543776 0.3611563 -0.0187208 -0.04519605 0.3611563 -0.009543776 -0.04797983 0.3611563 0 -0.04891985 0.3611563 0.009543776 -0.04797983 0.3611563 -0.0259453 -0.03882992 0.3640397 -0.0330221 -0.0330221 0.3640397 -0.03459155 -0.03459155 0.3611563 -0.04067534 -0.0271784 0.3611563 -0.03882992 -0.0259453 0.3640397 -0.04519605 -0.0187208 0.3611563 -0.04314547 -0.01787143 0.3640397 -0.04996079 0 0.3576697 -0.03882992 0.0259453 0.3640397 -0.0330221 0.0330221 0.3640397 -0.03459155 0.03459155 0.3611563 -0.0271784 0.04067534 0.3611563 -0.0259453 0.03882992 0.3640397 -0.0187208 0.04519605 0.3611563 -0.01787143 0.04314547 0.3640397 0 0.04996079 0.3576697 0.0259453 0.03882992 0.3640397 0.0330221 0.0330221 0.3640397 0.03459155 0.03459155 0.3611563 0.04067534 0.0271784 0.3611563 0.03882992 0.0259453 0.3640397 0.04519605 0.0187208 0.3611563 0.04314547 0.01787143 0.3640397 0.04996079 0 0.3576697 0.03882992 -0.0259453 0.3640397 0.0330221 -0.0330221 0.3640397 0.03459155 -0.03459155 0.3611563 0.0271784 -0.04067534 0.3611563 0.0259453 -0.03882992 0.3640397 0.0187208 -0.04519605 0.3611563 0.01787143 -0.04314547 0.3640397 0 -0.04996079 0.3576697 -9.97302e-4 -0.01712656 0.3815245 -0.001768171 -0.0185312 0.3841782 -0.000999987 -0.01719999 0.3816499 -9.99995e-4 -0.01856958 0.3839784 -9.81216e-4 -0.01700705 0.3813179 -9.26628e-4 -0.01687663 0.3810852 -5.38521e-4 -0.01542317 0.3785513 -8.26135e-4 -0.01663649 0.380657 -6.46162e-4 -0.01641011 0.3802427 -4.47178e-4 -0.01621794 0.379902 -4.20789e-4 -0.01619243 0.3798568 1.97014e-7 -0.01546436 0.3785936 -0.002096772 -0.01851475 0.3842637 -7.0358e-4 -0.01538938 0.3785163 -0.002576649 -0.01847296 0.3844786 -0.002581238 -0.01847255 0.3844807 -0.001285076 -0.01519346 0.3783108 -0.001499354 -0.01508712 0.3781969 -0.001527726 -0.01507306 0.3781819 -0.002046644 -0.01472252 0.3777934 -0.002366423 -0.01442307 0.3774439 -0.002728641 -0.01394772 0.3768467 -0.002915263 -0.01355922 0.3763078 -0.004947781 -0.01815599 0.3861157 -0.004107356 -0.01830083 0.3853677 -0.004035413 -0.01830989 0.3853209 -0.003457784 -0.01838254 0.3849452 -0.002581179 -0.01414126 0.3770898 -0.002585291 -0.01413589 0.3770831 -0.003103494 -0.01842713 0.3847146 -0.003332912 -0.01839828 0.3848639 -0.002999961 -0.01310867 0.3756 -0.002956926 -0.01282829 0.3750935 -0.004949212 -0.007979869 0.3688088 -0.002909421 -0.01271486 0.3748684 -0.002667188 -0.01242899 0.3742267 -0.003623545 -0.008763432 0.3687224 -0.00379002 -0.008693873 0.3687303 -0.004851818 -0.008058905 0.3688004 -0.006884336 -0.01766562 0.3886485 -0.006244003 -0.01785719 0.3876586 -0.006896734 -0.006075561 0.3690016 -0.00607419 -0.01790803 0.387396 -0.005246758 -0.01809781 0.386416 -0.00513035 -0.01812452 0.3862782 -0.005213558 -0.007765471 0.3688317 -0.005856633 -0.007243871 0.3688873 -0.006577312 -0.006457984 0.3689653 -0.006803452 -0.00621134 0.3689898 -0.008215844 -0.01704877 0.3918347 -0.008145928 -0.01709944 0.3915725 -0.007511317 -0.005180418 0.3690793 -0.007709681 -0.0173276 0.3903928 -0.007601857 -0.01738399 0.3901012 -0.00705558 -0.01759839 0.3889952 -0.006948053 -0.01764065 0.3887776 -0.006902217 -0.01765859 0.3886848 -0.008259892 -0.01701676 0.392 -0.007656872 -0.004889428 0.3690973 -0.007720649 -0.004761993 0.3691052 -0.008258938 -0.003585815 0.3691607 -0.008421659 -0.003108263 0.3691641 -0.008934259 -0.008014082 0.3816623 -0.008909881 -0.008552789 0.3820858 -0.008882641 -0.008974373 0.3824504 -0.008882522 -0.008976161 0.382452 -0.008833289 -0.009661018 0.383074 -0.008812069 -0.009927093 0.3833427 -0.008707344 -0.01123857 0.3846674 -0.008663773 -0.01180291 0.3853136 -0.008645296 -0.01204216 0.3855875 -0.008563995 -0.0133835 0.3873449 -0.008151829 -0.00390011 0.3691585 -0.008563041 -0.01341313 0.3873896 -0.008564233 -0.002689778 0.369167 -0.00868541 -0.00214982 0.3691106 -0.008765399 -0.001793384 0.3690733 -0.008785724 -0.001652956 0.3690319 -0.008859932 -0.001141428 0.3688811 -0.008865892 -0.001100063 0.3688688 -0.008893072 -0.01592659 0.394398 -0.008598029 -0.0167641 0.3933044 -0.008558511 -0.01680022 0.3931199 -0.008999943 -0.01500004 0.3955511 -0.008921146 -0.01568293 0.3947013 -0.00892508 -0.01445895 0.3926215 -0.008896172 -0.01589965 0.3944317 -0.00856769 -0.01352047 0.3876006 -0.008587002 -0.01358419 0.3878285 -0.008643984 -0.01368069 0.3883648 -0.008903145 -0.01430088 0.3917657 -0.008897125 -0.01428633 0.3916862 -0.008905112 -6.53215e-4 0.3686026 -0.008914709 -5.43413e-4 0.3685373 -0.008928835 -2.23709e-4 0.3682112 -0.008999943 0 0.3700508 -0.008999943 -0.005900204 0.3800812 -0.008940339 0 0.3680386 -0.008987128 -0.00684452 0.3807428 -0.008939445 -0.007899284 0.381572 -0.008940339 0 0.3680385 -0.00893867 0 0.367983 -0.002646863 -0.009171485 0.3686767 -0.002595782 -0.01238024 0.3741013 -0.002584993 -0.009187042 0.3686749 -0.002585768 -0.01237338 0.3740836 -0.002542853 -0.01234406 0.3740082 -0.002110242 -0.01216048 0.3734677 -0.001909792 -0.01210713 0.3732864 -0.001490652 -0.01203697 0.3730164 -0.001317203 -0.01200789 0.3729046 -0.001064419 -0.01198267 0.3727952 -0.001853168 -0.009370386 0.3686538 -3.73065e-4 -0.0119459 0.3726233 -0.001387298 -0.009487152 0.3686404 0.00178188 -0.01207947 0.3731865 0.002291142 -0.01222264 0.3736633 0.002582073 -0.00917834 0.3686758 0.001520574 -0.01203453 0.3730139 -1.39584e-4 -0.009602904 0.3686271 -1.03153e-4 -0.01194149 0.3726018 -3.79978e-7 -0.009594619 0.368628 -8.9312e-7 -0.01194328 0.3726105 -3.29839e-7 -0.009594619 0.368628 0 -0.01194334 0.3726106 0.001116991 -0.009528398 0.3686356 6.08811e-4 -0.01195394 0.3726624 0.001854062 -0.009369969 0.3686539 8.70613e-4 -0.01196813 0.3727291 0.002368032 -0.009259462 0.3686666 0.001498878 -0.01203233 0.3730044 0.003624618 -0.008767426 0.368722 0.003538727 -0.008815765 0.3687167 0.002829194 -0.01258963 0.3746023 0.00253278 -0.0123381 0.3739922 0.002585828 -0.01238316 0.3741015 0.002587616 -0.01238465 0.3741051 0.002923905 -0.01274454 0.3749287 0.00494647 -0.007974505 0.3688093 0.004701972 -0.008161127 0.3687891 0.002999961 -0.01310867 0.3756 0.002928555 -0.0135203 0.3762506 0.004944741 -0.01815456 0.3861229 0.002827823 -0.01376628 0.3766016 0.00436294 -0.01826155 0.3855696 0.003336846 -0.018399 0.3848602 0.003470301 -0.01838576 0.3849284 0.00348258 -0.01838403 0.3849373 0.004028677 -0.01830804 0.3853296 0.006523668 -0.006550014 0.3689574 0.005598127 -0.007477104 0.3688629 0.005327224 -0.01808422 0.3864867 0.005216658 -0.007768273 0.3688315 0.005250513 -0.01809835 0.3864137 0.00621128 -0.01787126 0.3875861 0.006890356 -0.006068527 0.3690017 0.00658673 -0.006467223 0.368965 0.007656931 -0.004887938 0.3690982 0.007244646 -0.005603373 0.3690446 0.007048606 -0.01760768 0.3889465 0.006252408 -0.01785826 0.387653 0.006894648 -0.01765614 0.3886964 0.006945312 -0.01764017 0.3887788 0.007068157 -0.01759946 0.3889889 0.007880866 -0.004499435 0.3691274 0.007729351 -0.004762291 0.3691077 0.007714927 -0.01732814 0.3903913 0.007768034 -0.01730585 0.3905065 0.008223652 -0.01704925 0.3918328 0.008940398 0 0.3680391 0.008938789 0 0.3679844 0.008931636 -2.09147e-4 0.3682234 0.008939981 -0.0079993 0.3816331 0.008929967 -2.5805e-4 0.3682793 0.008903801 -6.61226e-4 0.3685988 0.008892595 -8.34154e-4 0.3687357 0.008855104 -0.001150131 0.3688641 0.008813738 -0.001498281 0.3690056 0.008893489 -0.01589828 0.3944319 0.008939266 -0.01445853 0.3926193 0.008654892 -0.01664042 0.3934714 0.008872866 -0.01424252 0.3914442 0.008598029 -0.0167641 0.3933044 0.008268833 -0.01701807 0.3919938 0.008794903 -0.01398891 0.3900645 0.008709371 -0.0138061 0.3890467 0.008785426 -0.001650214 0.3690323 0.008692264 -0.002150475 0.3691205 0.008675158 -0.002242207 0.3691368 0.008587002 -0.01358419 0.3878285 0.00856781 -0.01352095 0.3876018 0.008563041 -0.01341331 0.3873898 0.008241474 -0.01703923 0.3918846 0.00826174 -0.003588199 0.3691647 0.008563995 -0.0133835 0.3873449 0.008604526 -0.01263993 0.3863336 0.008667767 -0.01177841 0.3853093 0.008707523 -0.0112366 0.3846651 0.008750975 -0.01069951 0.3840945 0.008812785 -0.009890019 0.3833231 0.008882582 -0.008975327 0.3824513 0.008427739 -0.003111124 0.3691656 0.008356273 -0.003362059 0.369174 0.008910119 -0.008549034 0.3820827 0.008884727 -0.008942604 0.382423 0.008954167 -0.007737517 0.381419 0.008999943 -0.005900859 0.3800817 0.008999943 0 0.3700508 0.008946955 -0.007870316 0.3815276 0.008940398 0 0.3680393 0.008928656 -0.01568359 0.3947017 0.008999943 -0.01499986 0.3955513 0.008999347 -0.01499974 0.3953347 0.008912444 -0.01583945 0.3945081 0.008948028 -0.01448702 0.3927742 0.002581954 -0.01847386 0.384474 0.002585768 -0.01414072 0.37709 0.002584218 -0.01414304 0.377093 9.22638e-4 -0.01681429 0.3809779 0.001565277 -0.01505219 0.3781593 0.001496851 -0.01508253 0.3781915 9.80936e-4 -0.01531136 0.3784351 8.85898e-4 -0.01534116 0.3784662 8.26145e-4 -0.01663649 0.380657 2.81697e-4 -0.01545763 0.3785867 0.000999987 -0.01719999 0.3816499 9.99999e-4 -0.0185697 0.3839785 0.0013749 -0.01855534 0.3840525 0.00176686 -0.01853126 0.384177 0.002385795 -0.01849329 0.3843737 9.34208e-4 -0.01687198 0.3810784 0.002271771 -0.01452028 0.3775593 0.001760125 -0.01493328 0.3780294 0.002509474 -0.01425874 0.3772439 0.002578198 -0.01847422 0.3844721 7.09929e-5 -0.01546972 0.3785992 1.41762e-7 -0.01578611 0.3791366 3.81218e-4 -0.01613956 0.379753 4.25931e-4 -0.01618951 0.3798438 4.50633e-4 -0.01621711 0.379894 0 -0.01578599 0.3791364 5.00215e-7 -0.01546436 0.3785936 0.00142312 -0.01569998 0.4194982 -0.006548583 -0.01569998 0.4020425 -0.004154145 -0.01569998 0.4005036 -0.004154145 -0.01569998 0.4186963 -0.006548583 -0.01569998 0.4171575 -0.00841248 -0.01569998 0.4041936 -0.00142312 -0.01569998 0.3997018 0.00142312 -0.01569998 0.3997018 0.004154145 -0.01569998 0.4186963 0.006548583 -0.01569998 0.4171575 -0.00142312 -0.01569998 0.4194982 -0.00841248 -0.01569998 0.4150064 -0.009594917 -0.01569998 0.4124173 -0.009594917 -0.01569998 0.4067827 -0.00999999 -0.01569998 0.4096 0.00841248 -0.01569998 0.4150064 0.004154145 -0.01569998 0.4005036 0.006548583 -0.01569998 0.4020425 0.00841248 -0.01569998 0.4041936 0.009594917 -0.01569998 0.4067827 0.009594917 -0.01569998 0.4124173 0.00999999 -0.01569998 0.4096 -0.006548583 0.01569998 0.4020425 -0.00841248 0.01569998 0.4041936 0.00142312 0.01569998 0.4194982 -0.004154145 0.01569998 0.4005036 0.004154145 0.01569998 0.4186963 0.00142312 0.01569998 0.3997018 -0.00142312 0.01569998 0.3997018 0.00841248 0.01569998 0.4150064 0.00841248 0.01569998 0.4041936 0.006548583 0.01569998 0.4020425 -0.00841248 0.01569998 0.4150064 -0.006548583 0.01569998 0.4171575 0.009594917 0.01569998 0.4067827 0.009594917 0.01569998 0.4124173 0.00999999 0.01569998 0.4096 0.006548583 0.01569998 0.4171575 0.004154145 0.01569998 0.4005036 -0.009594917 0.01569998 0.4124173 -0.009594917 0.01569998 0.4067827 -0.00999999 0.01569998 0.4096 -0.004154145 0.01569998 0.4186963 -0.00142312 0.01569998 0.4194982 -0.00999999 -0.01559996 0.4096 -0.009594917 -0.01559996 0.4067827 -0.00841248 -0.01559996 0.4041936 -0.006548583 -0.01559996 0.4020425 -0.004154145 -0.01559996 0.4005036 -0.00142312 -0.01559996 0.3997018 0.00142312 -0.01559996 0.3997018 0.004154145 -0.01559996 0.4005036 0.006548583 -0.01559996 0.4020425 0.00841248 -0.01559996 0.4041936 0.009594917 -0.01559996 0.4067827 0.00999999 -0.01559996 0.4096 0.009594917 -0.01559996 0.4124173 0.00841248 -0.01559996 0.4150064 0.006548583 -0.01559996 0.4171575 0.004154145 -0.01559996 0.4186963 0.00142312 -0.01559996 0.4194982 -0.00142312 -0.01559996 0.4194982 -0.004154145 -0.01559996 0.4186963 -0.006548583 -0.01559996 0.4171575 -0.00841248 -0.01559996 0.4150064 -0.009594917 -0.01559996 0.4124173 -0.009594917 0.01559996 0.4124173 -0.00999999 0.01559996 0.4096 -0.009594917 0.01559996 0.4067827 -0.00841248 0.01559996 0.4041936 -0.006548583 0.01559996 0.4020425 -0.004154145 0.01559996 0.4005036 -0.00142312 0.01559996 0.3997018 0.00142312 0.01559996 0.3997018 0.004154145 0.01559996 0.4005036 0.006548583 0.01559996 0.4020425 0.00841248 0.01559996 0.4041936 0.009594917 0.01559996 0.4067827 0.00999999 0.01559996 0.4096 0.009594917 0.01559996 0.4124173 0.00841248 0.01559996 0.4150064 0.006548583 0.01559996 0.4171575 0.004154145 0.01559996 0.4186963 0.00142312 0.01559996 0.4194982 -0.00142312 0.01559996 0.4194982 -0.004154145 0.01559996 0.4186963 -0.006548583 0.01559996 0.4171575 -0.00841248 0.01559996 0.4150064 0 -0.01559996 0.4216 -0.003105819 -0.01559996 0.4211911 -0.005999982 -0.01559996 0.4199923 -0.008485257 -0.01559996 0.4180853 -0.0103923 -0.01559996 0.4156 -0.01159107 -0.01559996 0.4127058 -0.01199996 -0.01559996 0.4096 -0.01159107 -0.01559996 0.4064942 -0.0103923 -0.01559996 0.4036 -0.008485257 -0.01559996 0.4011147 -0.005999982 -0.01559996 0.3992077 -0.003105819 -0.01559996 0.3980089 0 -0.01559996 0.3976 0.003105819 -0.01559996 0.3980089 0.005999982 -0.01559996 0.3992077 0.008485257 -0.01559996 0.4011147 0.0103923 -0.01559996 0.4036 0.01159107 -0.01559996 0.4064942 0.01199996 -0.01559996 0.4096 0.01159107 -0.01559996 0.4127058 0.0103923 -0.01559996 0.4156 0.008485257 -0.01559996 0.4180853 0.005999982 -0.01559996 0.4199923 0.003105819 -0.01559996 0.4211911 -0.003105819 0.01559996 0.3980089 -0.005999982 0.01559996 0.3992077 -0.008485257 0.01559996 0.4011147 -0.0103923 0.01559996 0.4036 -0.01159107 0.01559996 0.4064942 -0.01199996 0.01559996 0.4096 -0.01159107 0.01559996 0.4127058 -0.0103923 0.01559996 0.4156 -0.008485257 0.01559996 0.4180853 -0.005999982 0.01559996 0.4199923 -0.003105819 0.01559996 0.4211911 0 0.01559996 0.4216 0.003105819 0.01559996 0.4211911 0.005999982 0.01559996 0.4199923 0.008485257 0.01559996 0.4180853 0.0103923 0.01559996 0.4156 0.01159107 0.01559996 0.4127058 0.01199996 0.01559996 0.4096 0.01159107 0.01559996 0.4064942 0.0103923 0.01559996 0.4036 0.008485257 0.01559996 0.4011147 0.005999982 0.01559996 0.3992077 0.003105819 0.01559996 0.3980089 0 0.01559996 0.3976 0.01159107 -0.01059997 0.4127058 0.01199996 -0.01059997 0.4096 0.01159107 -0.01059997 0.4064942 0.0103923 -0.01059997 0.4036 0.008485257 -0.01059997 0.4011147 0.005999982 -0.01059997 0.3992077 0.003105819 -0.01059997 0.3980089 0 -0.01559996 0.3976 0 -0.01059997 0.3976 -0.003105819 -0.01059997 0.3980089 -0.005999982 -0.01059997 0.3992077 -0.008485257 -0.01059997 0.4011147 -0.0103923 -0.01059997 0.4036 -0.01159107 -0.01059997 0.4064942 -0.01199996 -0.01059997 0.4096 -0.01159107 -0.01059997 0.4127058 -0.0103923 -0.01059997 0.4156 -0.008485257 -0.01059997 0.4180853 -0.005999982 -0.01059997 0.4199923 -0.003105819 -0.01059997 0.4211911 0 -0.01559996 0.4216 0 -0.01059997 0.4216 0.003105819 -0.01059997 0.4211911 0.005999982 -0.01059997 0.4199923 0.008485257 -0.01059997 0.4180853 0.0103923 -0.01059997 0.4156 0.01199996 0.01059997 0.4096 0.01159107 0.01059997 0.4064942 0.0103923 0.01059997 0.4036 0.008485257 0.01059997 0.4011147 0.005999982 0.01059997 0.3992077 0.003105819 0.01059997 0.3980089 0 0.01059997 0.3976 0 0.01559996 0.3976 -0.003105819 0.01059997 0.3980089 -0.005999982 0.01059997 0.3992077 -0.008485257 0.01059997 0.4011147 -0.0103923 0.01059997 0.4036 -0.01159107 0.01059997 0.4064942 -0.01199996 0.01059997 0.4096 -0.01159107 0.01059997 0.4127058 -0.0103923 0.01059997 0.4156 -0.008485257 0.01059997 0.4180853 -0.005999982 0.01059997 0.4199923 -0.003105819 0.01059997 0.4211911 0 0.01059997 0.4216 0 0.01559996 0.4216 0.003105819 0.01059997 0.4211911 0.005999982 0.01059997 0.4199923 0.008485257 0.01059997 0.4180853 0.0103923 0.01059997 0.4156 0.01159107 0.01059997 0.4127058 0.009011745 -0.01663351 0.3982506 0.009179353 -0.01660895 0.3986154 0.009541928 -0.01589709 0.3982594 0.008832335 -0.01638221 0.3964715 0.008727312 -0.01669144 0.3965988 0.008734762 -0.0166909 0.3967368 0.009158194 -0.01603496 0.3976084 0.008757531 -0.01668709 0.3970034 0.00885421 -0.01666545 0.3976495 0.008857548 -0.01666468 0.3976719 0.008705496 -0.01669025 0.3957846 0.008711159 -0.01669287 0.3962463 0.008716523 -0.01669228 0.3963991 0.008917808 -0.01609176 0.3965018 0.008886337 -0.01617872 0.3963962 0.008854985 -0.01626551 0.3962908 0.008823573 -0.01635527 0.3961832 0.008807718 -0.01640051 0.3961279 0.008747518 -0.01657122 0.3959257 0.009177446 -0.015531 0.3972412 0.009135127 -0.01560169 0.397138 0.009083449 -0.01570004 0.3970032 0.009030342 -0.01582556 0.3968425 0.008918046 -0.01609128 0.3965024 0.009646177 -0.0150786 0.3980141 0.009431004 -0.01521527 0.397736 0.009381532 -0.01527684 0.3976394 0.009265184 -0.0154218 0.3974123 0.009900748 -0.01595747 0.398743 0.009922027 -0.01584422 0.3986963 0.009926795 -0.01581865 0.3986857 0.01000624 -0.01533937 0.3984997 0.009999513 -0.01490169 0.398419 0.009849786 -0.01495176 0.3982747 0.01000702 -0.01539146 0.3985093 0.009841501 -0.01495456 0.3982667 0.009782075 -0.01624369 0.3989334 0.009779393 -0.01624757 0.3989372 0.009319126 -0.0165885 0.3989195 0.009554386 -0.01656979 0.3992542 0.008909761 -0.01665413 0.3978833 0.008963763 -0.01664322 0.3981019 0.009008824 -0.0166341 0.3982415 0.0061962 -0.00999999 0.395772 0.00618267 -0.00999999 0.3957487 0.006340384 -0.01001757 0.3956505 0.005306661 -0.0100001 0.3942363 0.005320131 -0.0100001 0.3942286 0.005914568 -0.01002258 0.3948904 0.004551708 -0.01000487 0.3928384 0.004603385 -0.01001936 0.3926386 0.004688262 -0.0100252 0.3927267 0.005062937 -0.01002448 0.3933766 0.004846751 -0.0100001 0.3934423 0.004895806 -0.01000076 0.3934723 0.004872024 -0.0100001 0.393486 0.005304396 -0.0100001 0.3942325 0.00650835 -0.01007682 0.395546 0.005764007 -0.01000005 0.395026 0.005743086 -0.01000005 0.3949898 0.006791591 -0.01001149 0.3964024 0.007441639 -0.01004743 0.3970097 0.007288575 -0.01000565 0.3971351 0.007214426 -0.00999999 0.3971952 0.007085144 -0.00999999 0.3970513 0.006853818 -0.00999999 0.3967185 0.006685674 -0.00999999 0.3964765 0.006237089 -0.00999999 0.3958309 0.007718086 -0.01025021 0.3967834 0.009001314 -0.01046562 0.3978192 0.008244454 -0.01020985 0.3974384 0.008917331 -0.01031273 0.3979291 0.008120775 -0.01010084 0.3975627 0.008839786 -0.01017141 0.3980307 0.007986962 -0.01003116 0.3976973 0.008717834 -0.01009625 0.3981903 0.00781852 -0.00999999 0.3978675 0.008573889 -0.01000744 0.3983786 0.007903397 -0.00999999 0.3979619 0.008499562 -0.00999999 0.3984756 0.007902622 -0.01056432 0.3966324 0.009080648 -0.01082789 0.3977155 0.009051859 -0.01063978 0.3977531 0.007489025 -0.01060259 0.3960487 0.00796175 -0.01073014 0.3965836 0.00811994 -0.01077282 0.3967626 0.008262157 -0.0108112 0.3969235 0.008317887 -0.01082473 0.3969779 0.008592128 -0.01089125 0.3972452 0.009106993 -0.01099997 0.397681 0.007344663 -0.01056361 0.3958854 0.006785929 -0.01029723 0.3953732 0.006919324 -0.01044958 0.3953546 0.006884157 -0.01044017 0.3953108 0.006227254 -0.01018035 0.3947092 0.006368637 -0.01030194 0.3946676 0.004990935 -0.01006132 0.3930595 0.005205988 -0.01008695 0.3932959 0.005655407 -0.01008653 0.3940398 0.005483686 -0.01012009 0.3936012 0.005502223 -0.01012229 0.3936216 0.005787193 -0.01018136 0.3939657 0.006148815 -0.01025635 0.3944022 0.006955444 -0.01006352 0.396288 0.007588028 -0.01013028 0.3968899 0.005494952 -0.01002508 0.3941301 0.006080925 -0.0100851 0.394794 0.006659269 -0.01017302 0.395452 0.007824361 -0.01039862 0.3966965 0.009034395 -0.01052594 0.397776 0.00453478 -0.01000016 0.3929038 0.00453478 0.01000016 0.3929038 0.005062937 0.01002448 0.3933766 0.004551708 0.01000487 0.3928384 0.004993259 0.01005899 0.3930584 0.004771411 0.01003146 0.3928127 0.004698574 0.01002579 0.3927367 0.004688203 0.01002514 0.3927268 0.004687011 0.01002496 0.3927247 0.00468111 0.01002454 0.3927186 0.004603385 0.01001936 0.3926386 0.005786955 0.01018118 0.3939658 0.005501985 0.01012212 0.3936218 0.005655407 0.01008653 0.3940398 0.005482912 0.01011973 0.3936007 0.005206942 0.01008552 0.3932951 0.006148755 0.01025617 0.3944025 0.006227254 0.01018035 0.3947092 0.006345808 0.010297 0.3946405 0.006810545 0.01041644 0.3952216 0.006808757 0.01041597 0.3952193 0.006785929 0.01029723 0.3953732 0.006728351 0.01039439 0.3951184 0.006368517 0.0103017 0.3946678 0.007413804 0.01058244 0.3959677 0.007344603 0.01056325 0.3958855 0.007237315 0.01028043 0.3960912 0.006946504 0.01045328 0.3953924 0.006659269 0.01017302 0.395452 0.006941556 0.01045191 0.3953862 0.006883025 0.01043605 0.3953127 0.006825149 0.01042038 0.39524 0.007824361 0.01039862 0.3966965 0.007960557 0.01072925 0.396584 0.007725238 0.01066881 0.3963376 0.007481157 0.01060116 0.3960477 0.009057044 0.01064115 0.3977463 0.008516013 0.01087182 0.3971655 0.008430421 0.0105192 0.3972512 0.008339226 0.01082646 0.3969805 0.008111357 0.01076793 0.3967419 0.009083509 0.01072466 0.3977118 0.009096682 0.01087898 0.3976945 0.008592128 0.01089137 0.3972452 0.009106993 0.01099997 0.3976811 0.008349597 0.01035261 0.3973325 0.008971035 0.01036947 0.3978588 0.008995354 0.01044636 0.397827 0.00872159 0.0100845 0.3981851 0.008766233 0.01010149 0.3981267 0.007441639 0.01004743 0.3970097 0.008784592 0.01012551 0.3981027 0.008825242 0.01017874 0.3980495 0.006836116 0.00999999 0.3967197 0.007288575 0.01000565 0.3971351 0.007221817 0.00999999 0.3971897 0.00756514 0.00999999 0.397608 0.008606851 0.01004087 0.3983351 0.007626116 0.00999999 0.3976823 0.008499443 0.00999999 0.3984756 0.006955444 0.01006352 0.396288 0.006262421 0.00999999 0.3958386 0.006810486 0.00999999 0.3966885 0.00573045 0.00999999 0.3949899 0.005733549 0.00999999 0.3949953 0.005736947 0.00999993 0.3949934 0.005852758 0.00999999 0.3952032 0.006340384 0.01001757 0.3956505 0.006198108 0.00999999 0.3957388 0.007107019 0.01015549 0.3961822 0.007588028 0.01013028 0.3968899 0.007718086 0.01025021 0.3967834 0.008244454 0.01020985 0.3974384 0.00892347 0.01030719 0.397921 0.005283415 0.01000005 0.3942099 0.005300521 0.01000005 0.3942397 0.005320131 0.0100001 0.3942286 0.005914568 0.01002258 0.3948904 0.00650835 0.01007682 0.395546 0.006080925 0.0100851 0.394794 0.005494952 0.01002508 0.3941301 0.004895806 0.01000076 0.3934723 0.004838228 0.0100001 0.3934332 0.004869341 0.0100001 0.3934874 -0.01438385 -0.01099997 0.4055175 -0.01415354 -0.01099997 0.4046325 -0.01404082 -0.01052594 0.4046721 -0.009551644 -0.01099997 0.4211069 -0.01018869 -0.01099997 0.4206086 -0.01010751 -0.01052594 0.4205209 -0.01148349 -0.00999999 0.4016726 -0.0122627 -0.00999999 0.4028453 -0.01236957 -0.01000744 0.4027864 -0.01306772 -0.00999999 0.4046456 -0.01320999 -0.00999999 0.4049637 -0.01332509 -0.01000744 0.4049233 -0.01386457 -0.00999999 0.4112848 -0.01382052 -0.00999999 0.4118344 -0.01394098 -0.01000744 0.4118539 -0.01148629 -0.00999999 0.4175299 -0.01107603 -0.00999999 0.4181628 -0.01117253 -0.01000744 0.4182374 -0.006483793 -0.00999999 0.4219554 -0.005642712 -0.00999999 0.4224125 -0.005691885 -0.01000744 0.4225241 0 -0.00999999 0.4235518 0.001160323 -0.00999999 0.4235518 0.001170456 -0.01000744 0.4236734 0.003349065 -0.00999999 0.4231852 0.003448963 -0.00999999 0.4231685 0.003479003 -0.01000744 0.4232867 0.009270191 -0.00999999 0.4200618 0.009509563 -0.00999999 0.4198746 0.009592413 -0.01000744 0.4199641 0.01306003 -0.00999999 0.4145514 0.01326161 -0.00999999 0.4140865 0.01337718 -0.01000744 0.4141256 0.01148343 -0.00999999 0.4016726 0.0109784 -0.00999999 0.4009124 0.01107406 -0.01000744 0.4008367 -0.008571207 -0.01002717 0.3983823 -0.008499741 -0.00999999 0.3984758 -0.009474515 -0.01000744 0.3991279 -0.009280264 -0.00999999 0.3991249 -0.009392678 -0.00999999 0.3992184 -0.009768307 -0.01017141 0.3988032 -0.008832156 -0.01018744 0.3980409 -0.008825361 -0.01017862 0.3980498 -0.008766472 -0.01010149 0.3981269 -0.008721768 -0.01008445 0.3981854 -0.008607149 -0.01004081 0.3983353 -0.009057044 -0.01064068 0.3977466 -0.009023666 -0.01053524 0.3977903 -0.00998336 -0.01052594 0.3985655 -0.008971214 -0.01036953 0.3978589 -0.00892347 -0.01030701 0.3979214 -0.009083628 -0.01072472 0.3977118 -0.01006358 -0.01099997 0.3984768 -0.009107053 -0.01099997 0.3976811 0.009983241 -0.01052594 0.3985654 0.0100634 -0.01099997 0.3984767 0.009768187 -0.01017141 0.3988031 0.009474396 -0.01000744 0.3991278 0.009280264 -0.00999999 0.3991249 0.009392559 -0.00999999 0.3992183 0.01306772 -0.00999999 0.4046456 0.01226264 -0.00999999 0.4028452 0.01236951 -0.01000744 0.4027863 0.01332509 -0.01000744 0.4049231 0.01320993 -0.00999999 0.4049635 0.01379436 -0.00999999 0.4072093 0.01386457 -0.00999999 0.4112848 0.01399976 -0.00999999 0.4096 0.01412177 -0.01000744 0.40952 0.01399976 -0.00999999 0.4095207 0.01385712 -0.00999999 0.4079161 0.01394098 -0.01000744 0.4118537 0.01382052 -0.00999999 0.4118343 0.01148629 -0.00999999 0.4175299 0.01233834 -0.00999999 0.4162155 0.01244586 -0.01000744 0.4162731 0.01117265 -0.01000744 0.4182373 0.01107609 -0.00999999 0.4181627 0.007681727 -0.00999999 0.4213043 0.005692064 -0.01000744 0.422524 0.00564289 -0.00999999 0.4224124 0.006483793 -0.00999999 0.4219554 -0.003349065 -0.00999999 0.4231852 -0.001160144 -0.00999999 0.4235519 -0.001170277 -0.01000744 0.4236735 -0.003478884 -0.01000744 0.4232868 -0.003448784 -0.00999999 0.4231685 -0.009270191 -0.00999999 0.4200619 -0.007681608 -0.00999999 0.4213044 -0.007748544 -0.01000744 0.4214064 -0.009592294 -0.01000744 0.4199643 -0.009509444 -0.00999999 0.4198747 -0.01306003 -0.00999999 0.4145514 -0.01233828 -0.00999999 0.4162156 -0.0124458 -0.01000744 0.4162732 -0.01337713 -0.01000744 0.4141258 -0.01326155 -0.00999999 0.4140866 -0.01385718 -0.00999999 0.4079161 -0.01399976 -0.00999999 0.4095209 -0.01412177 -0.01000744 0.4095202 -0.01399976 -0.00999999 0.4096 -0.01391458 -0.01000744 0.4071886 -0.01379436 -0.00999999 0.4072094 -0.01107418 -0.01000744 0.4008368 -0.01097846 -0.00999999 0.4009125 0.01141744 -0.01017141 0.4005649 0.01275306 -0.01017141 0.402575 0.01166886 -0.01052594 0.400366 0.01303386 -0.01052594 0.4024204 0.01373827 -0.01017141 0.4047781 0.01404076 -0.01052594 0.4046719 0.01455962 -0.01017141 0.4095175 0.01437324 -0.01017141 0.4119237 0.01488023 -0.01052594 0.4095157 0.01468974 -0.01052594 0.4119748 0.0128318 -0.01017141 0.41648 0.01151907 -0.01017141 0.4185051 0.01311433 -0.01052594 0.4166315 0.01177269 -0.01052594 0.4187012 0.0098899 -0.01017141 0.4202855 0.01010763 -0.01052594 0.4205208 0.005868554 -0.01017141 0.4229248 0.003586888 -0.01017141 0.4237111 0.005997776 -0.01052594 0.4232182 0.003665864 -0.01052594 0.4240218 -0.001206576 -0.01017141 0.4241098 -0.003586769 -0.01017141 0.4237112 -0.0012331 -0.01052594 0.4244293 -0.003665745 -0.01052594 0.4240219 -0.005868375 -0.01017141 0.4229249 -0.005997598 -0.01052594 0.4232183 -0.01151895 -0.01017141 0.4185053 -0.01283174 -0.01017141 0.4164802 -0.01177257 -0.01052594 0.4187013 -0.01311427 -0.01052594 0.4166316 -0.01437324 -0.01017141 0.4119238 -0.01455962 -0.01017141 0.4095177 -0.01468974 -0.01052594 0.411975 -0.01488023 -0.01052594 0.4095159 -0.01275312 -0.01017141 0.4025751 -0.01141756 -0.01017141 0.4005651 -0.01303392 -0.01052594 0.4024205 -0.01166898 -0.01052594 0.4003661 0.01105767 -0.01099997 0.3995388 0.01176255 -0.01099997 0.4002919 0.01310628 -0.01099997 0.4023142 0.01313853 -0.01099997 0.4023627 0.01415348 -0.01099997 0.4046323 0.01438385 -0.01099997 0.4055176 0.01391458 -0.01000744 0.4071884 0.014346 -0.01017141 0.4071137 0.0146619 -0.01052594 0.4070589 0.01477962 -0.01099997 0.4070385 0.01494687 -0.01099997 0.4089201 0.01499974 -0.01099997 0.409515 0.0148077 -0.01099997 0.4119939 0.0147174 -0.01099997 0.4123579 0.01379197 -0.01017141 0.4142659 0.01409566 -0.01052594 0.4143687 0.01420885 -0.01099997 0.414407 0.01367217 -0.01099997 0.4156446 0.01321965 -0.01099997 0.416688 0.01195627 -0.01099997 0.4186369 0.01186728 -0.01099997 0.4187743 0.01018881 -0.01099997 0.4206085 0.009551644 -0.01099997 0.4211069 0.007748663 -0.01000744 0.4214063 0.007988929 -0.01017141 0.4217724 0.008164882 -0.01052594 0.4220404 0.008230447 -0.01099997 0.4221403 0.00666362 -0.01099997 0.4229919 0.006045937 -0.01099997 0.4233276 0.003695309 -0.01099997 0.4241377 0.003429591 -0.01099997 0.4241822 0.001206696 -0.01017141 0.4241098 0.001233279 -0.01052594 0.4244293 0.001243174 -0.01099997 0.4245484 0 -0.01099997 0.4245484 -0.001243054 -0.01099997 0.4245484 -0.003429591 -0.01099997 0.4241822 -0.00369513 -0.01099997 0.4241377 -0.006045758 -0.01099997 0.4233276 -0.00666362 -0.01099997 0.4229919 -0.00798881 -0.01017141 0.4217725 -0.008164703 -0.01052594 0.4220405 -0.008230268 -0.01099997 0.4221404 -0.009889721 -0.01017141 0.4202857 -0.01186716 -0.01099997 0.4187744 -0.01195627 -0.01099997 0.4186369 -0.01321959 -0.01099997 0.4166882 -0.01367217 -0.01099997 0.4156446 -0.01379191 -0.01017141 0.4142661 -0.0140956 -0.01052594 0.4143688 -0.01420879 -0.01099997 0.4144071 -0.0147174 -0.01099997 0.4123579 -0.0148077 -0.01099997 0.411994 -0.01499974 -0.01099997 0.4095152 -0.01494687 -0.01099997 0.4089201 -0.01434606 -0.01017141 0.4071138 -0.0146619 -0.01052594 0.4070591 -0.01477968 -0.01099997 0.4070387 -0.01373833 -0.01017141 0.4047783 -0.01313859 -0.01099997 0.4023628 -0.01310628 -0.01099997 0.4023142 -0.01176267 -0.01099997 0.400292 -0.01105761 -0.01099997 0.3995388 0 -0.01059997 0.3976 0 -0.01059997 0.3956 0.003350377 -0.01059997 0.3960068 0.01389789 -0.01059997 0.4079125 0.01309019 -0.01059997 0.4046355 0.01152175 -0.01059997 0.4016471 0.009283661 -0.01059997 0.3991208 0.006506085 -0.01059997 0.3972036 -0.003350377 -0.01059997 0.3960068 -0.006506085 -0.01059997 0.3972036 -0.009283661 -0.01059997 0.3991208 -0.01152175 -0.01059997 0.4016471 -0.01309019 -0.01059997 0.4046355 -0.01389789 -0.01059997 0.4079125 -0.01399999 -0.01059997 0.4096 0.01399999 -0.01059997 0.4096 0.01389789 -0.01059997 0.4112875 0.01309019 -0.01059997 0.4145644 0.01152175 -0.01059997 0.4175529 0.009283661 -0.01059997 0.4200791 0.006506085 -0.01059997 0.4219964 0.003350377 -0.01059997 0.4231932 0 -0.01059997 0.4216 0 -0.01059997 0.4236 -0.003350377 -0.01059997 0.4231932 -0.006506085 -0.01059997 0.4219964 -0.009283661 -0.01059997 0.4200791 -0.01152175 -0.01059997 0.4175529 -0.01309019 -0.01059997 0.4145644 -0.01389789 -0.01059997 0.4112875 0 0.01059997 0.3976 -0.001687467 0.01059997 0.3957021 -0.004964411 0.01059997 0.3965098 -0.007952868 0.01059997 0.3980782 -0.01047915 0.01059997 0.4003162 -0.01239633 0.01059997 0.4030939 -0.01359313 0.01059997 0.4062496 -0.01399999 0.01059997 0.4096 -0.01359313 0.01059997 0.4129504 -0.01239633 0.01059997 0.4161061 -0.01047915 0.01059997 0.4188837 -0.007952868 0.01059997 0.4211218 -0.004964411 0.01059997 0.4226902 0 0.01059997 0.4216 -0.001687467 0.01059997 0.4234979 0.001687467 0.01059997 0.4234979 0.004964411 0.01059997 0.4226902 0.007952868 0.01059997 0.4211218 0.01047915 0.01059997 0.4188837 0.01239633 0.01059997 0.4161061 0.01359313 0.01059997 0.4129504 0.01399999 0.01059997 0.4096 0.01359313 0.01059997 0.4062496 0.01239633 0.01059997 0.4030939 0.01047915 0.01059997 0.4003162 0.007952868 0.01059997 0.3980782 0.004964411 0.01059997 0.3965098 0.001687467 0.01059997 0.3957021 -0.008376598 -0.01035666 0.3973544 -0.008456408 -0.01052373 0.3972734 -0.00784564 -0.01040256 0.3967178 -0.006836354 -0.00999999 0.3967202 -0.007313132 -0.01000624 0.3971566 -0.007465541 -0.01004904 0.397031 -0.0072425 -0.00999999 0.3972148 -0.007565557 -0.00999999 0.3976084 -0.004687309 -0.01002508 0.3927261 -0.004603266 -0.0100193 0.392639 -0.004551529 -0.01000481 0.3928391 -0.005066335 -0.01002466 0.3933812 -0.00453478 -0.01000016 0.3929038 -0.005165696 -0.010073 0.3932397 -0.004995524 -0.0100556 0.3930563 -0.004721522 -0.01002752 0.3927611 -0.00548315 -0.01011902 0.3936001 -0.005500674 -0.01012182 0.3936206 -0.005662143 -0.01008731 0.3940483 -0.005473971 -0.01011759 0.3935893 -0.005215287 -0.01008021 0.393296 -0.006799042 -0.0102998 0.3953894 -0.00636667 -0.01030117 0.3946657 -0.006237149 -0.01018196 0.3947218 -0.006147027 -0.01025569 0.3944007 -0.005793809 -0.01018249 0.3939743 -0.007433056 -0.01058691 0.3959844 -0.0073421 -0.01056253 0.3958825 -0.00725454 -0.01028352 0.3961103 -0.006918728 -0.01044911 0.3953544 -0.006896853 -0.01044327 0.3953271 -0.007984697 -0.01073497 0.3966026 -0.007487952 -0.01060169 0.396046 -0.008536577 -0.01087808 0.397192 -0.008351922 -0.01083356 0.3970141 -0.008316814 -0.01082414 0.3969748 -0.008111774 -0.01076906 0.396745 -0.008587896 -0.01089042 0.3972413 -0.007626295 -0.00999999 0.3976824 -0.006973981 -0.01006513 0.3963071 -0.006263136 -0.00999999 0.3958396 -0.006811857 -0.00999999 0.3966903 -0.005731403 -0.00999999 0.3949915 -0.005741596 -0.00999999 0.3950092 -0.005747675 -0.00999999 0.3950057 -0.00585401 -0.00999999 0.3952053 -0.006354928 -0.01001828 0.3956665 -0.006209731 -0.00999999 0.3957569 -0.005284488 -0.01000005 0.3942117 -0.005305945 -0.01000005 0.3942492 -0.005327165 -0.01000016 0.3942371 -0.005925059 -0.01002323 0.3949028 -0.006522476 -0.01007831 0.395562 -0.004839479 -0.0100001 0.3934353 -0.004899322 -0.01000076 0.3934768 -0.005501866 -0.0100255 0.3941386 -0.006091177 -0.01008629 0.3948065 -0.006672918 -0.0101751 0.3954681 -0.00712496 -0.01015788 0.3962012 -0.007740318 -0.01025354 0.3968046 -0.007611095 -0.01013278 0.396911 -0.008272528 -0.01021319 0.3974602 -0.004872143 -0.0100001 0.3934924 0.008639752 -0.01637536 0.4179275 0.008492231 -0.01629602 0.4180736 0.008923947 -0.01621276 0.4184894 0.008725702 -0.01651108 0.4178423 0.008725643 -0.01651096 0.4178423 0.00919485 -0.01643264 0.4182825 0.01033645 -0.01351165 0.4204181 0.01036304 -0.01319992 0.4204447 0.0105946 -0.01379728 0.4202177 0.0109384 -0.01539373 0.4197331 0.01093828 -0.01539826 0.4197319 0.01071631 -0.01577717 0.4194989 0.01032578 -0.01622867 0.419106 0.01047503 -0.01645296 0.4191673 0.01036483 -0.01658254 0.4190542 0.009880781 -0.01656258 0.4186584 0.01082187 -0.01588678 0.4195429 0.01074963 -0.01607084 0.4194559 0.01072055 -0.01614499 0.4194208 0.01068276 -0.01620864 0.4193805 0.01093357 -0.01556426 0.4196853 0.01091563 -0.0156477 0.4196559 0.01068216 -0.01503533 0.4197723 0.01084136 -0.01458382 0.4199647 0.01092725 -0.0148676 0.4198759 0.0109499 -0.01498979 0.4198463 0.01094466 -0.01517486 0.4197944 0.01039117 -0.01553523 0.4194805 0.01051175 -0.01437687 0.4200753 0.01062434 -0.01387399 0.4201886 0.010634 -0.0138989 0.4201791 0.009992957 -0.01485383 0.4200749 0.01010292 -0.01463907 0.4201846 0.01031041 -0.01490867 0.4198738 0.01080286 -0.01445662 0.4200046 0.01018232 -0.01434981 0.420264 0.01018536 -0.01433873 0.420267 0.01030236 -0.01391249 0.4203839 0.01031333 -0.01378327 0.420395 0.009850203 -0.01513278 0.4199323 0.01003938 -0.01537448 0.4196028 0.009790599 -0.01524913 0.4198728 0.00973612 -0.01531267 0.4198185 0.009709179 -0.0157563 0.4192728 0.009414613 -0.01568734 0.4194982 0.008905768 -0.01604807 0.4189912 0.0090456 -0.01595503 0.4191305 0.009332478 -0.01603931 0.4188968 0.009359717 -0.01574599 0.4194435 0.009370386 -0.01573884 0.4194542 0.00879389 -0.01607877 0.4188796 0.00864917 -0.01611852 0.4187355 0.008328974 -0.01620823 0.4182354 0.008237898 -0.01619994 0.4183256 0.008375167 -0.01619374 0.4184623 0.008476734 -0.01628768 0.418089 0.009348273 -0.0171597 0.4180254 0.008948266 -0.01719999 0.4176217 0.008888244 -0.01685947 0.4176812 0.01001912 -0.01687783 0.418703 0.009945213 -0.01694095 0.4186279 0.009398698 -0.01676613 0.4181739 0.009494304 -0.01710617 0.4181728 0.008884251 -0.01683676 0.4176852 0.008865833 -0.01673239 0.4177035 0.009632766 -0.01624763 0.4187207 0.01003676 -0.01594465 0.4191253 0.009762287 -0.01658254 0.3995247 0.01002341 -0.01624596 0.3992552 0.0101549 -0.01607644 0.3991194 0.01023674 -0.01583838 0.399035 0.01038819 -0.01539736 0.3988787 0.01039093 -0.01536816 0.3988758 0.0104379 -0.0148676 0.3988273 -0.008852839 -0.01610368 0.4187809 -0.008730351 -0.01612555 0.4186613 -0.009000837 -0.01621288 0.4184113 -0.009011209 -0.01707178 0.4175494 -0.00901699 -0.01719999 0.4175436 -0.009570479 -0.0171144 0.418092 -0.01090276 -0.01443183 0.4199019 -0.01070308 -0.01387882 0.4201045 -0.01060348 -0.01437717 0.4199824 -0.01067656 -0.01380538 0.4201313 -0.01045799 -0.01319998 0.4203531 -0.01045203 -0.01342362 0.4203473 -0.01043921 -0.01351219 0.4203346 -0.01040029 -0.01378035 0.4202965 -0.01034504 -0.01416116 0.4202424 -0.01040023 -0.01490896 0.4197828 -0.01094442 -0.01459074 0.4198573 -0.01090538 -0.0144419 0.4198991 -0.01077103 -0.01503568 0.419678 -0.01103794 -0.01517784 0.4196999 -0.01101708 -0.0148676 0.4197795 -0.01104992 -0.01535648 0.419654 -0.0104773 -0.01553559 0.4193889 -0.0110436 -0.01538431 0.4196439 -0.0110411 -0.01539528 0.4196399 -0.01080244 -0.01577758 0.4194043 -0.01092904 -0.015886 0.4194626 -0.01092195 -0.01589834 0.4194551 -0.01044702 -0.01658254 0.4189633 -0.01056396 -0.01646327 0.4190801 -0.01040828 -0.01622897 0.4190151 -0.01064318 -0.01638245 0.4191592 -0.01082831 -0.016061 0.4193556 -0.0100978 -0.01687806 0.418615 -0.009959101 -0.01656281 0.4185716 -0.01002413 -0.01694041 0.4185415 -0.009472548 -0.0167663 0.4180915 -0.009635746 -0.01710432 0.4181567 -0.008954763 -0.01686179 0.4176064 -0.008313179 -0.01619994 0.4182539 -0.008547842 -0.01628273 0.4180171 -0.009497344 -0.015679 0.4194114 -0.009440481 -0.01573628 0.4193558 -0.009793341 -0.01575648 0.4191873 -0.009352803 -0.01582461 0.4192699 -0.009413182 -0.01603949 0.4188148 -0.009128212 -0.01595002 0.4190502 -0.008875846 -0.01609086 0.4188034 -0.009764552 -0.01540988 0.4196729 -0.0101267 -0.01537472 0.4195142 -0.009823739 -0.01531332 0.4197309 -0.01028233 -0.01433914 0.4201808 -0.01027864 -0.01434957 0.4201772 -0.01009511 -0.0148707 0.419997 -0.009937524 -0.01512765 0.4198426 -0.008798003 -0.01651328 0.4177646 -0.008893609 -0.01663434 0.4176682 -0.008949339 -0.01684176 0.4176118 -0.01011955 -0.01594495 0.4190369 -0.009711742 -0.01624786 0.418636 -0.009269773 -0.01643282 0.4182019 -0.008795559 -0.01651018 0.4177671 -0.008568763 -0.01629012 0.417996 -0.008642315 -0.01631605 0.4179218 -0.00913304 -0.01105493 0.397701 -0.01036888 -0.01486915 0.3987609 -0.009988665 -0.01453065 0.3984095 -0.01043796 -0.0148676 0.3988274 -0.01108914 -0.0148676 0.3995094 -0.009999334 -0.01490163 0.3984191 -0.009998261 -0.01486253 0.3984181 -0.009989678 -0.01455289 0.3984104 -0.009926497 -0.01399445 0.3983547 -0.009843647 -0.01328027 0.3982818 -0.009831666 -0.01321691 0.3982713 -0.009803414 -0.01311004 0.3982475 -0.009559392 -0.0121873 0.398042 -0.009493827 -0.01193928 0.3979867 -0.009205758 -0.01123327 0.3977586 -0.01124382 -0.0148676 0.3996714 -0.01264691 -0.0148676 0.4015343 -0.01307219 -0.0148676 0.4023318 -0.01374429 -0.0148676 0.4035922 -0.01441109 -0.0148676 0.4055122 -0.01450943 -0.0148676 0.4057953 -0.01492381 -0.0148676 0.4080904 -0.01494282 -0.0148676 0.4089177 -0.01471871 -0.0148676 0.412361 -0.01497745 -0.0148676 0.410422 -0.009698331 -0.01319998 0.421043 -0.01194351 -0.0148676 0.4186278 -0.0130043 -0.0148676 0.4170758 -0.01368331 -0.0148676 0.415648 -0.01400595 -0.0148676 0.4149696 -0.014669 -0.0148676 0.4127336 -0.01168835 -0.0148676 0.4190012 0.01161348 -0.0148676 0.4190935 0.01193892 -0.0148676 0.4186244 0.00959742 -0.01319998 0.4211277 0.009578526 -0.01319998 0.4211412 0.00769937 -0.01319998 0.4224732 0.006663501 -0.01319998 0.4229882 0.005616068 -0.01319998 0.423509 0.003432095 -0.01319998 0.4241992 0.003397703 -0.01319998 0.4242101 0.001097559 -0.01319998 0.4245598 1.96694e-7 -0.01319998 0.424555 -0.001228928 -0.01319998 0.4245496 -0.003431797 -0.01319998 0.4241949 -0.003525912 -0.01319998 0.4241797 -0.005738079 -0.01319998 0.4234591 -0.006663382 -0.01319998 0.4229888 -0.007812142 -0.01319998 0.4224051 -0.009572982 -0.01319998 0.4211335 0.01371532 -0.0148676 0.4035264 0.01441341 -0.0148676 0.4055114 0.01449805 -0.0148676 0.4057521 0.01492208 -0.0148676 0.4080731 0.01494169 -0.0148676 0.4089177 0.01497691 -0.0148676 0.4104318 0.01471644 -0.0148676 0.4123606 0.01466119 -0.0148676 0.4127699 0.01398277 -0.0148676 0.4150297 0.01368457 -0.0148676 0.4156484 0.0129584 -0.0148676 0.417155 0.01307028 -0.0148676 0.4023331 0.01259332 -0.0148676 0.4014509 0.009558081 -0.01213455 0.3980395 0.009495198 -0.01194375 0.3979879 0.009205222 -0.01123875 0.3977587 0.009571373 -0.01218789 0.3980508 0.00980246 -0.0131154 0.3982468 0.00984472 -0.01328498 0.3982827 0.009889781 -0.01355445 0.398322 0.011092 -0.0148676 0.3995067 0.01115971 -0.0148676 0.399577 0.009933829 -0.01399755 0.398361 0.009989559 -0.01455801 0.3984103 0.0099985 -0.01486778 0.3984182 -0.005960464 6.8354e-4 0.3526 -0.005997598 1.50804e-4 0.3526 0.005999505 0 0.3526 -0.00598669 -3.91727e-4 0.3526 0.005974948 -5.42086e-4 0.3526 -0.005705893 -0.001853883 0.3526 -0.005073606 -0.003201901 0.3526 0.005657494 -0.001996755 0.3526 0.004991531 -0.003328442 0.3526 0.005975723 5.33502e-4 0.3526 0.005668163 0.001966238 0.3526 0.005022406 0.003281712 0.3526 0.004077017 0.004401326 0.3526 0.002888381 0.00525844 0.3526 0.001527428 0.005801796 0.3526 7.5408e-5 0.005999028 0.3526 -0.001381158 0.005838334 0.3526 -0.002755284 0.00532937 0.3526 -0.003965079 0.004502415 0.3526 -0.004938304 0.003406882 0.3526 -0.005616903 0.002108097 0.3526 0.002797305 -0.005307435 0.3526 -0.002929866 -0.005235433 0.3526 0.001404166 -0.00583285 0.3526 -0.001550376 -0.005795717 0.3526 -7.5408e-5 -0.005999028 0.3526 -0.004128873 -0.004352748 0.3526 0.004018187 -0.004455149 0.3526 0.006506085 -0.00999999 0.3972036 0.003350377 -0.00999999 0.3960068 0.002630591 -0.00999993 0.3958494 0.002726018 -0.00999993 0.3957167 0.002965927 -0.00999993 0.3953756 0.00297594 -0.00999999 0.3953613 0.003308892 -0.00999993 0.3948603 0.003773093 -0.009999871 0.3941618 0.003905177 -0.009999871 0.3939631 0.003966271 -0.009999752 0.3938657 0.004964411 0.00999999 0.3965098 0.007952868 0.00999999 0.3980782 0.003905177 0.009999871 0.393963 0.003773272 0.009999871 0.3941615 0.003308892 0.00999993 0.3948603 0.00297594 0.00999999 0.3953613 0.002967894 0.00999993 0.3953728 0.004059433 0.00999993 0.3937035 0.002965986 0.00999993 0.3953756 0.002726018 0.00999993 0.3957167 0.002630591 0.00999993 0.3958494 -0.007912516 0.00999999 0.3979705 -0.007844746 0.00999999 0.3978953 -0.008017182 0.01003253 0.3977196 -0.006206691 0.00999999 0.3957888 -0.006193995 0.00999999 0.3957669 -0.006354928 0.01001828 0.3956665 -0.005312383 0.01000005 0.3942456 -0.005327165 0.01000016 0.3942371 -0.005925059 0.01002323 0.3949028 -0.004848241 0.0100001 0.3934447 -0.00453478 0.01000016 0.3929038 -0.004551529 0.01000481 0.3928391 -0.006897032 0.0104435 0.395327 -0.006799042 0.0102998 0.3953894 -0.006237149 0.01018196 0.3947218 -0.007688105 0.01065856 0.3962944 -0.007982373 0.01073431 0.3966041 -0.007923066 0.01056867 0.3966541 -0.008109629 0.0107671 0.3967381 -0.008336722 0.01082557 0.396977 -0.006919205 0.01044946 0.3953547 -0.007342159 0.01056283 0.3958824 -0.007478058 0.01060044 0.3960443 -0.005793988 0.01018267 0.3939742 -0.006147086 0.01025587 0.3944004 -0.006366848 0.01030141 0.3946655 -0.005483746 0.01011925 0.3936004 -0.005500853 0.01012194 0.3936204 -0.005662143 0.01008731 0.3940483 -0.004687368 0.01002508 0.3927261 -0.004990398 0.01006078 0.3930584 -0.005066335 0.01002466 0.3933812 -0.005210459 0.01008671 0.3932998 -0.005474209 0.01011776 0.3935891 -0.004603266 0.0100193 0.392639 -0.004899322 0.01000076 0.3934768 -0.004874944 0.0100001 0.3934908 -0.005306184 0.0100001 0.3942349 -0.006522476 0.01007831 0.395562 -0.005766034 0.01000005 0.3950284 -0.00575155 0.01000005 0.3950034 -0.006810665 0.0100122 0.3964216 -0.007465541 0.01004904 0.397031 -0.007313132 0.01000624 0.3971566 -0.007235467 0.00999999 0.39722 -0.007095873 0.00999999 0.3970653 -0.006854295 0.00999999 0.3967185 -0.006701052 0.00999999 0.3964985 -0.006236791 0.00999999 0.395832 -0.007740318 0.01025354 0.3968046 -0.009002983 0.01043993 0.3978174 -0.008272528 0.01021319 0.3974602 -0.008918583 0.01031434 0.3979278 -0.008149981 0.01010322 0.3975847 -0.008787751 0.01011949 0.398099 -0.008720517 0.01009154 0.398187 -0.008499741 0.00999999 0.3984758 -0.009049296 0.01064354 0.3977568 -0.009090483 0.01082462 0.3977029 -0.009102523 0.01087766 0.3976871 -0.008587896 0.01089024 0.3972414 -0.009107053 0.01099997 0.3976811 -0.005501866 0.0100255 0.3941386 -0.006091177 0.01008629 0.3948065 -0.006672918 0.0101751 0.3954681 -0.00784564 0.01040256 0.3967178 -0.0090065 0.0104556 0.3978127 -0.006974041 0.01006513 0.3963071 -0.007611095 0.01013278 0.396911 -0.003350377 -0.00999999 0.3960068 0 -0.01059997 0.4236 -3.93444e-7 -0.009799838 0.3956096 0.001342773 -0.009810864 0.3956645 0.002133131 -0.009910106 0.3957635 0.00230664 -0.009954869 0.3957913 0.002506971 -0.009982705 0.3958272 -0.001523017 -0.009818673 0.3956831 -0.001342773 -0.009810864 0.3956645 -2.00569e-4 -0.009798228 0.3956015 -0.002630591 -0.00999993 0.3958494 -0.002506971 -0.009982705 0.3958272 -0.00230664 -0.009954869 0.3957913 -0.006506085 -0.00999999 0.3972036 -0.007952868 0.00999999 0.3980782 0.007763206 0.00999999 0.4212504 0.00794208 0.00999999 0.4211082 0.01374131 0.00999999 0.4069212 0.01399576 0.00999999 0.4092556 0.01332718 0.00999999 0.4138877 0.01354652 0.00999999 0.4129396 0.01385641 0.00999999 0.4115998 0.01399976 0.00999999 0.4096 0.01242303 0.00999999 0.416055 0.0123924 0.00999999 0.4161036 0.01116931 0.00999999 0.4180407 0.01044261 0.00999999 0.418851 0.009601354 0.00999999 0.4197889 0.005706667 0.00999999 0.4223841 0.004949808 0.00999999 0.4226483 -0.001173973 0.00999999 0.4235507 0.001174271 0.00999999 0.4235507 0.001681864 0.00999999 0.4234646 0.003489613 0.00999999 0.4231581 -0.005706369 0.00999999 0.4223842 -0.004949808 0.00999999 0.4226483 -0.003489255 0.00999999 0.4231582 -0.001681864 0.00999999 0.4234646 -0.007762968 0.00999999 0.4212506 -0.00794208 0.00999999 0.4211082 -0.009601116 0.00999999 0.4197891 -0.01044261 0.00999999 0.418851 -0.01354652 0.00999999 0.4129396 -0.01332712 0.00999999 0.413888 -0.01242285 0.00999999 0.4160553 -0.0123924 0.00999999 0.4161036 -0.01116913 0.00999999 0.418041 -0.01355385 0.00999999 0.4062607 -0.01374137 0.00999999 0.4069215 -0.01399576 0.00999999 0.409256 -0.01399976 0.00999999 0.4096 -0.01385635 0.00999999 0.4116002 -0.0123614 0.00999999 0.4031105 -0.01310032 0.00999999 0.4046623 -0.01074093 0.00999999 0.4006205 -0.01209074 0.00999999 0.4025421 -0.009088933 0.00999999 0.3989515 -0.0104593 0.00999999 0.4003359 -0.00230664 0.009954869 0.3957913 -0.002133131 0.009910106 0.3957635 -0.001686811 0.009854078 0.3957076 -0.002506971 0.009982705 0.3958272 -0.002630591 0.00999993 0.3958494 -0.004964411 0.00999999 0.3965098 0.00168699 0.009847164 0.3957057 0.001522958 0.009818673 0.3956831 0.001342773 0.009810864 0.3956645 2.00569e-4 0.009798228 0.3956015 -0.001342773 0.009810864 0.3956645 0.002506971 0.009982705 0.3958272 0.00230658 0.009954869 0.3957913 0.01209056 0.00999999 0.4025418 0.01074069 0.00999999 0.4006202 0.0104593 0.00999999 0.4003359 0.009088635 0.00999999 0.3989512 0.01355385 0.00999999 0.4062607 0.0131002 0.00999999 0.404662 0.0123614 0.00999999 0.4031105 -0.004052042 -0.00999993 0.3937145 -0.003895342 -0.009999871 0.3939777 -0.003775656 -0.009999871 0.3941596 -0.00330305 -0.009999871 0.3948782 -0.003161191 -0.009999871 0.3950937 -0.002706766 -0.00999993 0.3957428 -0.002714991 -0.00999993 0.3957318 -0.002965748 -0.00999993 0.3953734 -0.002754151 -0.00999993 0.3956761 -0.002714991 0.00999993 0.3957318 -0.002947866 0.00999993 0.3954011 -0.002966344 0.00999993 0.3953734 -0.003895282 0.009999871 0.3939777 -0.003775238 0.009999871 0.394158 -0.003298163 0.00999993 0.3948749 -0.01038819 -0.01539736 0.3988787 -0.009996354 -0.01538527 0.3985202 -0.009995579 -0.01551604 0.3985477 -0.01023477 -0.01584404 0.3990371 -0.009729921 -0.01657718 0.3994799 -0.0101549 -0.0160765 0.3991195 -0.009749054 -0.01658016 0.3995063 -0.009762287 -0.01658254 0.3995248 -0.009757578 -0.01625001 0.3989623 -0.009616672 -0.01649862 0.3991702 -0.009554266 -0.01656973 0.3992543 -0.009863078 -0.01606398 0.3988066 -0.009915292 -0.01584798 0.3987045 -0.009921967 -0.01582062 0.3986916 0.009448528 -0.01435863 0.4209488 0.002974927 -0.0162 0.4212255 0.002715587 -0.0162 0.4212746 0.002896547 -0.01609474 0.4220553 -0.009237408 -0.01514136 0.4204992 -0.009687662 -0.01351416 0.4210304 -0.009547829 -0.01435863 0.4208654 -0.008782744 -0.01574778 0.4199627 -0.00774306 -0.01619994 0.4187359 -0.008267939 -0.01609474 0.4193553 -0.006659924 -0.01609474 0.4205164 -0.006238996 -0.0162 0.4198275 -0.007150411 -0.0162 0.4192371 -0.003005862 -0.01609474 0.4220293 -0.002818226 -0.0162 0.4212512 -0.003055036 -0.0162 0.4212047 -0.004891753 -0.01609474 0.421415 -0.004499316 -0.0162 0.4207246 -0.004587888 -0.0162 0.420682 -0.005871593 -0.0162 0.4200655 -0.001560091 -0.0162 0.4214982 -0.00104767 -0.01609474 0.4223447 -9.81645e-4 -0.0162 0.421537 -4.11521e-5 -0.0162 0.4215999 9.35707e-4 -0.01609474 0.4223534 8.76691e-4 -0.0162 0.4215448 0.001478016 -0.0162 0.4215087 0.004422903 -0.0162 0.4207552 0.004787802 -0.01609474 0.4214575 0.004490911 -0.0162 0.420723 0.005799293 -0.0162 0.4201057 0.006563782 -0.01609474 0.4205746 0.006149232 -0.0162 0.4198824 0.008181929 -0.01609474 0.4194275 0.007083296 -0.0162 0.4192865 0.007662951 -0.01619994 0.4188041 0.00869137 -0.01574778 0.4200394 0.009141325 -0.01514136 0.4205799 0.00958687 -0.01351416 0.4211151 0.007690906 -0.01351416 0.422459 0.005609929 -0.01351416 0.4234936 0.003393948 -0.01351416 0.424194 0.001096367 -0.01351416 0.4245433 -0.001227557 -0.01351416 0.4245331 -0.003522038 -0.01351416 0.4241636 -0.005731761 -0.01351416 0.4234439 -0.007803559 -0.01351416 0.4223909 -0.007690906 -0.01435863 0.4222064 -0.00564903 -0.01435863 0.423244 -0.003471195 -0.01435863 0.4239534 -0.001209855 -0.01435863 0.4243175 0.001080513 -0.01435863 0.4243276 0.003344953 -0.01435863 0.4239834 0.005528926 -0.01435863 0.4232931 0.007579922 -0.01435863 0.4222734 -0.007440924 -0.01514136 0.4217965 -0.005465328 -0.01514136 0.4228004 -0.003358364 -0.01514136 0.4234868 -0.001170516 -0.01514136 0.4238391 0.001045405 -0.01514136 0.4238488 0.003236234 -0.01514136 0.4235157 0.005349218 -0.01514136 0.4228479 0.007333457 -0.01514136 0.4218614 -0.007074654 -0.01574778 0.4211962 -0.005196332 -0.01574778 0.4221507 -0.00319302 -0.01574778 0.4228033 -0.001112878 -0.01574778 0.4231383 9.93971e-4 -0.01574778 0.4231475 0.00307691 -0.01574778 0.4228308 0.005085885 -0.01574778 0.4221959 0.006972491 -0.01574778 0.4212579 0.01260709 -0.01607644 0.4169502 0.01129859 -0.01607644 0.4188361 0.01155817 -0.01539736 0.4190483 0.01289671 -0.01539736 0.417119 0.01110661 -0.01539736 0.3996248 0.01085716 -0.01607644 0.3998488 0.01043736 -0.01658254 0.4002258 0.01253336 -0.01539736 0.4014897 0.01485097 -0.01539736 0.4080803 0.01442897 -0.01539736 0.4057705 0.01365 -0.01539736 0.4035553 0.01490557 -0.01539736 0.4104278 0.01459133 -0.01539736 0.4127548 0.01391619 -0.01539736 0.4150038 0.01402896 -0.01658254 0.4096 0.01457083 -0.01607644 0.4104092 0.01395612 -0.01658254 0.4081719 0.01451748 -0.01607644 0.4081145 0.01382678 -0.01658254 0.4074639 0.01355957 -0.01658254 0.4060012 0.01410496 -0.01607644 0.4058564 0.01291352 -0.01658254 0.404164 0.01334345 -0.01607644 0.4036911 0.01282751 -0.01658254 0.4039195 0.01225185 -0.01607644 0.4016718 0.01177811 -0.01658254 0.4019784 0.01119035 -0.01658254 0.4012101 0.01426368 -0.01607644 0.412684 0.01360368 -0.01607644 0.4148824 0.01400738 -0.01658254 0.4103779 0.01393961 -0.01658254 0.41088 0.0137121 -0.01658254 0.4125648 0.01321339 -0.01658254 0.414226 0.01307761 -0.01658254 0.4146782 0.01086169 -0.01658254 0.418479 0.01168966 -0.01658254 0.4172856 0.01211959 -0.01658254 0.416666 -0.01411604 -0.0160765 0.4058985 -0.01337164 -0.0160765 0.4037551 -0.01367884 -0.01539736 0.4036208 -0.01362621 -0.0160765 0.414824 -0.01427125 -0.0160765 0.4126487 -0.01459914 -0.01539736 0.4127187 -0.0149061 -0.01539736 0.410418 -0.01137143 -0.0160765 0.4187462 -0.01093894 -0.0160765 0.3999406 -0.01051592 -0.01658254 0.4003142 -0.01093173 -0.01658254 0.4183926 -0.01163268 -0.01539736 0.4189564 -0.01393926 -0.01539736 0.414944 -0.01444029 -0.01539736 0.4058134 -0.01258665 -0.01539736 0.4015728 -0.01119023 -0.01539736 0.3997187 -0.01265174 -0.0160765 0.416873 -0.01294237 -0.01539736 0.4170401 -0.01457136 -0.0160765 0.4103997 -0.01451915 -0.0160765 0.4081313 -0.0148527 -0.01539736 0.4080976 -0.012304 -0.0160765 0.401753 -0.01175063 -0.01658254 0.4171944 -0.0121625 -0.01658254 0.4165918 -0.01309931 -0.01658254 0.414622 -0.01324212 -0.01658254 0.4141403 -0.01371943 -0.01658254 0.4125308 -0.01394903 -0.01658254 0.4108097 -0.01400786 -0.01658254 0.4103688 -0.01395773 -0.01658254 0.4081881 -0.01381778 -0.01658254 0.4074131 -0.01357018 -0.01658254 0.4060416 -0.01290708 -0.01658254 0.4041323 -0.01285457 -0.01658254 0.4039811 -0.01182824 -0.01658254 0.4020565 -0.01118284 -0.01658254 0.4011996 0.008222639 0.01043993 0.4219398 0.006044387 0.01043993 0.4231406 0.006111264 0.01087766 0.4232904 -0.01106607 0.01099997 0.3995324 -0.0115081 0.01099997 0.3999791 -0.01150238 0.01087766 0.3999839 -0.0143795 0.01099997 0.4055199 -0.01472288 0.01099997 0.4067301 -0.01471549 0.01087766 0.4067316 -0.01196694 0.01099997 0.4186438 -0.01196694 0.01099997 0.4186439 -0.01196092 0.01087766 0.4186394 -0.006664514 0.01099997 0.422994 -0.006114006 0.01099997 0.4232974 -0.006110906 0.01087766 0.4232906 0 0.01099997 0.4245471 0.001258194 0.01099997 0.4245471 0.001257538 0.01087766 0.4245396 0.003429055 0.01099997 0.4241791 0.00373882 0.01099997 0.4241266 0.003736972 0.01087766 0.4241193 0.01308935 0.01099997 0.4023215 0.01295417 0.01099997 0.4020376 0.01294767 0.01087766 0.4020414 0.009396374 0.01011949 0.3985907 0.009626507 0.01043993 0.3983211 0.009732961 0.01087766 0.3981963 0.009737849 0.01099997 0.3981906 -0.009626746 0.01043993 0.3983213 -0.009733259 0.01087766 0.3981966 -0.009396672 0.01011949 0.3985909 0.01150214 0.01087766 0.3999836 0.01150792 0.01099997 0.3999788 0.01106607 0.01099997 0.3995324 0.01403594 0.01099997 0.4043093 0.01496142 0.01099997 0.4089192 0.01472282 0.01099997 0.4067298 0.01471543 0.01087766 0.4067313 0.0143795 0.01099997 0.4055199 0.01498794 0.01087766 0.4092313 0.01499545 0.01099997 0.409231 0.01484614 0.01099997 0.4117427 0.01367342 0.01099997 0.4156459 0.01427912 0.01099997 0.4141941 0.01427197 0.01087766 0.4141917 0.01470446 0.01099997 0.4123553 0.01330375 0.01087766 0.4165127 0.01331037 0.01099997 0.4165161 0.01196712 0.01099997 0.4186436 0.01028203 0.01087766 0.4205112 0.01028716 0.01099997 0.4205167 0.01196694 0.01099997 0.4186438 0.006664514 0.01099997 0.422994 0.008317768 0.01099997 0.4220826 0.008313596 0.01087766 0.4220763 0.009548723 0.01099997 0.4211038 0.006114304 0.01099997 0.4232972 -0.003429055 0.01099997 0.4241791 -0.001257836 0.01099997 0.4245471 -0.001257181 0.01087766 0.4245397 -0.003736615 0.01087766 0.4241194 -0.003738522 0.01099997 0.4241266 -0.009548723 0.01099997 0.4211038 -0.00831747 0.01099997 0.4220827 -0.008313298 0.01087766 0.4220765 -0.01028174 0.01087766 0.4205114 -0.01028692 0.01099997 0.4205169 -0.01367342 0.01099997 0.4156459 -0.01331025 0.01099997 0.4165164 -0.01330357 0.01087766 0.416513 -0.01470446 0.01099997 0.4123553 -0.01427906 0.01099997 0.4141944 -0.01427191 0.01087766 0.4141921 -0.01483869 0.01087766 0.411742 -0.01484608 0.01099997 0.4117431 -0.01496142 0.01099997 0.4089192 -0.01498794 0.01087766 0.4092316 -0.01499545 0.01099997 0.4092314 -0.01499998 0.01099997 0.4096 -0.01402902 0.01087766 0.4043123 -0.01403605 0.01099997 0.4043096 -0.01294785 0.01087766 0.4020417 -0.01295435 0.01099997 0.402038 -0.01308935 0.01099997 0.4023215 -0.009738147 0.01099997 0.3981909 0.0101695 0.01043993 0.4203918 0.01137632 0.01043993 0.4000888 0.01280605 0.01043993 0.4021241 0.0111044 0.01011949 0.4003161 0.01249992 0.01011949 0.4023028 0.01455444 0.01043993 0.4067626 0.01482397 0.01043993 0.4092352 0.01420658 0.01011949 0.4068304 0.01446962 0.01011949 0.409244 0.01411586 0.01043993 0.4141415 0.0131582 0.01043993 0.416437 0.01377844 0.01011949 0.4140329 0.01284366 0.01011949 0.4162736 0.0115475 0.01011949 0.4183265 0.01183027 0.01043993 0.4185402 0.01196116 0.01087766 0.4186391 0.005899906 0.01011949 0.4228169 0.008026123 0.01011949 0.4216449 0.009926438 0.01011949 0.4201339 0.00124377 0.01043993 0.4243762 -0.001243472 0.01043993 0.4243763 0.001214087 0.01011949 0.424023 -0.001213729 0.01011949 0.424023 -0.006044089 0.01043993 0.4231408 -0.008222341 0.01043993 0.42194 -0.005899608 0.01011949 0.4228171 -0.008025825 0.01011949 0.4216451 -0.01183009 0.01043993 0.4185405 -0.01315802 0.01043993 0.4164373 -0.01154732 0.01011949 0.4183268 -0.01284348 0.01011949 0.4162739 -0.01411575 0.01043993 0.4141418 -0.01377832 0.01011949 0.4140332 -0.01482397 0.01043993 0.4092356 -0.0145545 0.01043993 0.406763 -0.01446962 0.01011949 0.4092443 -0.01420664 0.01011949 0.4068308 -0.01280623 0.01043993 0.4021244 -0.01137655 0.01043993 0.4000891 -0.0125001 0.01011949 0.4023031 -0.01110458 0.01011949 0.4003164 0.0140289 0.01087766 0.404312 0.01387542 0.01043993 0.4043698 0.01354378 0.01011949 0.4044948 0.01483869 0.01087766 0.4117416 0.01467639 0.01043993 0.4117182 0.01432555 0.01011949 0.4116675 0.003696084 0.01043993 0.4239605 0.003607749 0.01011949 0.4236172 -0.003695726 0.01043993 0.4239605 -0.003607392 0.01011949 0.4236173 -0.01016926 0.01043993 0.4203921 -0.009926199 0.01011949 0.4201341 -0.01467633 0.01043993 0.4117185 -0.01432549 0.01011949 0.4116679 -0.01387554 0.01043993 0.4043701 -0.0135439 0.01011949 0.4044951 0.006029725 0.002091646 0.3526761 0.006356894 5.67532e-4 0.3526761 0.006680071 5.96381e-4 0.3528929 0.003072619 0.005593836 0.3526761 0.004337072 0.004682123 0.3526761 0.004557549 0.004920125 0.3528929 -0.002931058 0.005669295 0.3526761 -0.001469254 0.006210744 0.3526761 -0.001543939 0.00652647 0.3528929 -0.006340622 7.2714e-4 0.3526761 -0.005975186 0.002242565 0.3526761 -0.006278932 0.002356529 0.3528929 0.006382167 0 0.3526761 0.006706595 0 0.3528929 0.006681919 5.53752e-4 0.3528929 -0.006704509 1.68578e-4 0.3528929 -0.0063802 1.60423e-4 0.3526761 -0.006677627 5.53407e-4 0.3528929 -0.006662964 7.64103e-4 0.3528929 -0.004217982 0.00478965 0.3526761 -0.004897475 0.004509627 0.3528929 -0.005253314 0.0036242 0.3526761 -0.005520343 0.003808438 0.3528929 -0.006111025 0.002677977 0.3528929 -0.00308007 0.005957484 0.3528929 -0.003183901 0.005886495 0.3528929 -0.004432439 0.005033075 0.3528929 0.001624882 0.006171882 0.3526761 0.0010975 0.006568431 0.3528929 8.02179e-5 0.00638169 0.3526761 8.42956e-5 0.006706058 0.3528929 -0.001099467 0.006575524 0.3528929 0.003228843 0.00587821 0.3528929 0.0031901 0.005893647 0.3528929 0.001707494 0.006485581 0.3528929 0.006336212 0.00219798 0.3528929 0.006102204 0.002674579 0.3528929 0.005342781 0.003490984 0.3526761 0.00561434 0.003668487 0.3528929 0.004900574 0.004513859 0.3528929 -0.00539726 -0.003406167 0.3526761 -0.006069839 -0.001972138 0.3526761 -0.006378352 -0.002072393 0.3528929 -8.02179e-5 -0.00638169 0.3526761 -0.00164926 -0.006165385 0.3526761 -0.001733064 -0.006478786 0.3528929 0.005309939 -0.003540754 0.3526761 0.004274487 -0.004739284 0.3526761 0.004491746 -0.004980206 0.3528929 -0.006706595 0 0.3528929 0.006382167 0 0.3526761 0.006679177 -6.05976e-4 0.3528929 0.00635606 -5.76663e-4 0.3526761 0.006454348 -0.001636087 0.3528929 0.00601834 -0.00212413 0.3526761 0.005579829 -0.0037207 0.3528929 0.005607843 -0.003664791 0.3528929 0.006324291 -0.002232074 0.3528929 0.001493752 -0.006204903 0.3526761 0.00216037 -0.006297528 0.3528929 0.002975761 -0.00564599 0.3526761 0.003127038 -0.005932986 0.3528929 0.004094779 -0.005257368 0.3528929 -8.42956e-5 -0.006706058 0.3528929 -1.10871e-6 -0.00669676 0.3528929 0.001569688 -0.00652033 0.3528929 -0.004392266 -0.004630386 0.3526761 -0.004089951 -0.005252659 0.3528929 -0.003116726 -0.005569398 0.3526761 -0.003275156 -0.00585252 0.3528929 -0.00216192 -0.006304621 0.3528929 -0.00567162 -0.003579318 0.3528929 -0.005605041 -0.00366038 0.3528929 -0.004615545 -0.004865765 0.3528929 -0.006368577 -4.16714e-4 0.3526761 -0.00669229 -4.37896e-4 0.3528929 -0.006461679 -0.00163871 0.3528929 0.004417419 -0.009931623 0.3921844 0.004419684 -0.009932518 0.3921858 0.004299104 -0.00990504 0.3923919 0.004729926 -0.01005351 0.392377 0.004308223 -0.009914815 0.3924006 0.004307866 -0.009914457 0.3924003 0.004415571 -0.009930849 0.3921833 0.004083752 -0.009673655 0.3921838 0.004171252 -0.009677112 0.392018 0.004185199 -0.009915947 0.3927089 0.004186689 -0.009917199 0.3927097 0.004361391 -0.009958803 0.3928071 0.004184901 -0.009915769 0.3927087 0.003896474 -0.009682476 0.392548 0.003520429 -0.009767413 0.3933655 0.003661274 -0.009880661 0.3934598 0.00351727 -0.009768128 0.3933724 0.003404021 -0.009793698 0.3936186 0.00240755 -0.009944796 0.3955987 0.002431213 -0.009942471 0.3955534 0.00244677 -0.009940803 0.3955237 0.002448976 -0.009940564 0.3955194 0.00249803 -0.009933114 0.395422 0.00307399 -0.009955704 0.3947013 0.002913892 -0.009869456 0.3945952 0.003393352 -0.009796142 0.3936419 0.00324279 -0.009995877 0.3948155 0.003825187 -0.009959638 0.3935601 0.00324279 0.009995877 0.3948155 0.00399959 0.009996831 0.3936668 0.00307399 0.009955704 0.3947013 0.002913892 0.009869456 0.3945952 0.00254184 0.009926378 0.3953349 0.002448976 0.009940564 0.3955194 0.002407491 0.009944736 0.3955987 0.003896474 0.009682476 0.392548 0.003563582 0.009757637 0.3932717 0.004037439 0.00979644 0.3926265 0.003404021 0.009793698 0.3936185 0.003393292 0.009796142 0.3936419 0.003825187 0.009959638 0.3935601 0.004185199 0.009915947 0.3927088 0.004184901 0.009915769 0.3927087 0.004186689 0.009917199 0.3927097 0.004307746 0.009914338 0.3924006 0.004083752 0.009673655 0.3921838 0.004298985 0.00990498 0.3923922 0.004307687 0.009914338 0.3924006 0.004729926 0.01005351 0.392377 0.004419684 0.009932518 0.3921858 0.004171252 0.009677112 0.392018 0.004415571 0.009930849 0.3921833 0.004417419 0.009931623 0.3921844 0.001342773 -0.009768307 0.39546 0.001342773 -0.009176492 0.3936262 -0.001342773 -0.009768307 0.39546 -0.001342773 -0.009176492 0.3936262 -0.001342773 -0.008944332 0.3932063 -0.001342773 0.009750127 0.3953785 0.001342773 0.009750127 0.3953785 -0.001342773 0.009142994 0.3935497 0.001342773 0.008948266 0.3932045 0.001342773 0.009142994 0.3935497 0.001342773 -0.008944332 0.3932063 0.001342773 -0.008243978 0.3919399 -0.001342773 -0.008243978 0.3919399 0.001342773 -0.007386088 0.3909175 -0.001342773 -0.007386088 0.3909175 0.001342773 -0.007005333 0.3904638 -0.001342773 -0.007005333 0.3904638 0.001342773 -0.005506575 0.3892527 -0.001342773 -0.005506575 0.3892527 0.001342773 -0.005276322 0.3891309 -0.001342773 -0.005276322 0.3891309 0.001342773 -0.003803312 0.3883515 -0.001342773 -0.003803312 0.3883515 0.001342773 -0.002736032 0.3880288 -0.001342773 -0.002736032 0.3880288 0.001342773 -0.001958906 0.3877937 -0.001342773 -0.001958906 0.3877937 0.001342773 -4.1737e-5 0.3876001 -0.001342773 -4.17357e-5 0.3876001 0.001342773 -3.62733e-7 0.3876039 -0.001342773 -3.62723e-7 0.3876039 0.001342773 0.00187695 0.3877778 -0.001342773 0.00187695 0.3877778 0.001342773 0.002736151 0.3880298 -0.001342773 0.002736151 0.3880298 0.001342773 0.003726005 0.3883201 -0.001342773 0.003726005 0.3883201 0.001342773 0.005279362 0.3891254 -0.001342773 0.005279362 0.3891254 0.001342773 0.005436718 0.389207 -0.001342773 0.005436718 0.389207 0.001342773 0.00694549 0.3904056 -0.001342773 0.00694549 0.3904056 0.001342773 0.007384181 0.3909196 -0.001342773 0.007384181 0.3909196 0.001342773 0.008196413 0.3918713 -0.001342773 0.008196413 0.3918713 -0.001342773 0.008948266 0.3932045 -0.003819882 -0.009960174 0.3935722 -0.003994286 -0.00999695 0.393679 -0.003234863 -0.009996116 0.3948319 -0.003066003 -0.009956479 0.3947176 -0.002497851 -0.009932756 0.3954218 -0.002905786 -0.009870648 0.3946112 -0.003310859 -0.009809017 0.3938064 -0.002440333 -0.009941518 0.3955361 -0.002308428 -0.00995469 0.3957879 -0.003896474 -0.009682476 0.392548 -0.003520309 -0.009767293 0.3933653 -0.004037439 -0.0097965 0.3926265 -0.003385841 -0.009797632 0.3936575 -0.00418514 -0.009916007 0.3927089 -0.004184901 -0.009915828 0.3927088 -0.004186809 -0.009917378 0.3927098 -0.004307687 -0.009914338 0.3924008 -0.004083752 -0.009673655 0.3921838 -0.004298925 -0.00990498 0.3923923 -0.004307627 -0.009914338 0.3924008 -0.004185259 0.009915888 0.3927089 -0.004298925 0.00990498 0.3923923 -0.004307627 0.009914338 0.3924008 -0.004361391 0.009958803 0.3928071 -0.004186809 0.00991714 0.3927098 -0.004307687 0.009914338 0.3924008 -0.004083752 0.009673655 0.3921838 -0.004184961 0.009915649 0.3927088 -0.003896474 0.009682476 0.392548 -0.003066003 0.009956479 0.3947176 -0.003819823 0.009960174 0.3935722 -0.003234803 0.009996116 0.3948319 -0.003563523 0.009757578 0.3932715 -0.00365585 0.009881556 0.3934718 -0.003511607 0.00976926 0.3933842 -0.003385841 0.009797632 0.3936575 -0.002308428 0.00995469 0.3957879 -0.002440333 0.009941518 0.3955361 -0.00254172 0.00992608 0.3953347 -0.002905786 0.009870707 0.3946113 -0.003310859 0.009809017 0.3938065 -0.004729926 -0.01005351 0.392377 -0.004419684 -0.009932518 0.3921858 -0.004171252 -0.009677112 0.392018 -0.004415571 -0.009930849 0.3921833 -0.004419684 0.009932518 0.3921858 -0.004415571 0.009930849 0.3921833 -0.004171252 0.009677112 0.392018 -0.004729926 0.01005351 0.392377 -0.008924961 -0.0160889 0.3965126 -0.008889675 -0.01626223 0.3965696 -0.008862793 -0.01625216 0.3963106 -0.009137213 -0.01559782 0.3971436 -0.009167373 -0.01556062 0.3972021 -0.009155988 -0.01580744 0.3972787 -0.009912908 -0.01492875 0.3983384 -0.009170055 -0.01660728 0.3986423 -0.00905323 -0.01627528 0.3974543 -0.008782327 -0.0166828 0.3972263 -0.008740603 -0.01668936 0.396717 -0.008717477 -0.01669299 0.3964349 -0.008825063 -0.01635128 0.396188 -0.008714973 -0.01669353 0.3963778 -0.008706927 -0.01668655 0.3957785 -0.008975565 -0.01663947 0.3981356 -0.008881151 -0.01666063 0.3976915 -0.00887072 -0.01666301 0.3976422 -0.009337306 -0.01627153 0.3982698 -0.009120404 -0.0166155 0.3985128 -0.009012639 -0.01663333 0.3982322 -0.00948143 -0.01583355 0.3980515 -0.009518742 -0.01535016 0.397892 -0.009350836 -0.01533412 0.3975588 -0.009387612 -0.01528877 0.3976302 -0.009486675 -0.0151664 0.3978228 -0.009505927 -0.01515567 0.3978461 -0.009855329 -0.01496082 0.3982688 -0.008928179 -0.01608037 0.3965232 -0.009027957 -0.01581823 0.3968475 -0.009029924 -0.0158143 0.3968527 -0.009040832 -0.01579231 0.3968824 -0.005960047 -0.01648598 0.4149364 -0.005961835 -0.01648998 0.4149343 -0.006156146 -0.01719999 0.4147089 -0.006110846 -0.01685345 0.414763 -0.006105363 -0.01681154 0.4147695 -0.005711555 -0.0162661 0.4152004 -0.005738794 -0.01627355 0.4151737 -0.005470454 -0.0162 0.4154373 0.00542128 -0.0162 0.4154829 0.004756152 -0.0162 0.4160326 0.002487897 -0.0162 0.4172033 -0.004809916 -0.0162 0.4159925 -0.002551555 -0.0162 0.4171822 -3.35409e-5 -0.0162 0.4175999 0.005962908 -0.01656365 0.4149332 0.005911946 -0.01650583 0.4149878 0.005726158 -0.01629507 0.4151867 0.00566715 -0.01627665 0.4152441 0.00606209 -0.01686191 0.4148195 0.00609374 -0.01695704 0.4147832 0.006113111 -0.01719999 0.4147604 0.009157955 -0.01739335 0.4008327 0.008621037 -0.01798135 0.4016929 0.009750604 -0.01660066 0.3995554 0.009654104 -0.01674336 0.3997936 0.009635865 -0.01677024 0.3998386 0.009397506 -0.01708102 0.4003345 0.008473336 -0.01811867 0.4018707 0.008564352 -0.01857244 0.4031789 0.008100986 -0.01846498 0.4023191 0.008024394 -0.01853013 0.4023965 0.008018016 -0.01853555 0.4024031 0.008014261 -0.01853871 0.4024065 0.007973551 -0.0185725 0.4024459 0.00868386 -0.01857244 0.4033272 0.009661436 -0.01857244 0.4049725 0.009842038 -0.01857244 0.4054564 0.01033067 -0.01857244 0.4067655 0.01054793 -0.01857244 0.4079707 0.01067018 -0.01857244 0.4086489 0.01066917 -0.01857244 0.4105627 0.01066595 -0.01857244 0.4105802 0.01032757 -0.01857244 0.4124458 0.01007336 -0.01857244 0.4131247 0.009656369 -0.01857244 0.414238 0.008923053 -0.01857244 0.4154692 0.008677005 -0.01857244 0.4158823 0.00802797 -0.01857244 0.4166929 -0.009688436 -0.01857244 0.4141707 -0.008969128 -0.01857244 0.4153993 -0.008727133 -0.01857244 0.4158125 -0.008088588 -0.01857244 0.4166237 -0.0106737 -0.01857244 0.410511 -0.01067101 -0.01857244 0.4105263 -0.0103442 -0.01857244 0.4123848 -0.01009637 -0.01857244 0.4130598 -0.00801599 -0.01853734 0.4024055 -0.008558571 -0.01857244 0.4031713 -0.008003175 -0.01854777 0.4024173 -0.007973551 -0.01857244 0.4024459 -0.00846976 -0.01812201 0.4018755 -0.008617341 -0.01798516 0.4016988 -0.008018553 -0.01853489 0.4024022 -0.008026361 -0.01852828 0.4023945 -0.008088767 -0.01847529 0.4023318 -0.008679926 -0.01857244 0.4033218 -0.009653687 -0.01857244 0.4049562 -0.009833097 -0.01857244 0.4054337 -0.01032286 -0.01857244 0.4067372 -0.01054227 -0.01857244 0.4079318 -0.01066648 -0.01857244 0.4086084 -0.009152472 -0.01739954 0.4008424 -0.009391188 -0.01708871 0.4003466 -0.009628772 -0.01677942 0.3998531 -0.009749114 0.01658016 0.3995063 -0.009762287 0.01658254 0.3995247 -0.0100528 0.0162487 0.3992249 -0.010338 0.01561182 0.3989306 -0.0104379 0.0148676 0.3988274 -0.01000934 0.01502704 0.3984333 -0.01036888 0.01486843 0.3987609 -0.009999334 0.01490163 0.3984191 -0.009992063 0.01538282 0.3985246 -0.009980261 0.01562488 0.3985868 -0.0102356 0.01584041 0.3990362 -0.009761214 0.01625311 0.3989589 -0.009554266 0.01656973 0.3992543 -0.009708523 0.01657426 0.3994508 -0.00992316 0.01582008 0.3986902 -0.009915411 0.01584649 0.3987041 -0.009824931 0.0161556 0.3988679 -0.009729921 0.01657718 0.3994799 -0.009727299 0.01657676 0.3994762 -0.01491588 0.0148676 0.4080142 -0.01494091 0.0148676 0.4089179 0.009115993 0.01101869 0.3976879 -0.009560585 0.01218718 0.3980429 -0.009810745 0.01310664 0.3982532 -0.009117662 0.01102226 0.3976892 -0.009204387 0.01123404 0.3977578 -0.009493231 0.0119397 0.3979862 -0.009984493 0.01445412 0.3984058 -0.009989678 0.01455289 0.3984104 -0.009998261 0.01486253 0.3984181 -0.009844541 0.01327991 0.3982825 -0.009929656 0.01399397 0.3983575 -0.01109212 0.0148676 0.3995066 0.009985268 0.014463 0.3984065 0.011092 0.0148676 0.3995067 0.0104379 0.0148676 0.3988274 0.009999513 0.01490169 0.398419 0.009998619 0.01486778 0.3984182 0.009990096 0.01455795 0.3984108 0.009930312 0.01399892 0.3983581 0.009845674 0.01328462 0.3982835 0.009810745 0.01311182 0.3982533 0.009784042 0.01297956 0.3982301 0.009563744 0.01219111 0.3980454 0.009494721 0.01194411 0.3979875 0.009205877 0.01123839 0.397759 0.01115971 0.0148676 0.399577 0.01259332 0.0148676 0.4014509 0.01307028 0.0148676 0.4023331 0.01371532 0.0148676 0.4035264 0.01441341 0.0148676 0.4055114 0.01449805 0.0148676 0.4057521 0.01492208 0.0148676 0.4080731 0.01494169 0.0148676 0.4089177 0.01497691 0.0148676 0.4104318 0.01471644 0.0148676 0.4123606 0.01466119 0.0148676 0.4127699 0.01398277 0.0148676 0.4150297 0.01368457 0.0148676 0.4156484 0.0129584 0.0148676 0.417155 0.01193892 0.0148676 0.4186244 0.009578526 0.01319998 0.4211412 0.009597301 0.01319998 0.4211278 0.01036304 0.01319998 0.4204447 0.01085394 0.01459079 0.419953 0.01092725 0.0148676 0.4198759 0.01161348 0.0148676 0.4190935 0.01058357 0.01380538 0.4202249 0.01061034 0.01387882 0.4201982 0.01081192 0.01443225 0.4199972 0.01081442 0.01444178 0.4199945 0.007699251 0.01319998 0.4224733 0.006663501 0.01319998 0.4229882 0.005615949 0.01319998 0.423509 0.003432095 0.01319998 0.4241992 0.003397524 0.01319998 0.4242101 -0.01089388 0.01445674 0.4199092 -0.01072663 0.01389908 0.4200851 -0.01101708 0.0148676 0.4197795 -0.01093196 0.01458382 0.4198691 -0.0116927 0.0148676 0.4189957 -0.01194363 0.0148676 0.4186279 -0.01071703 0.01387399 0.4200948 -0.01068753 0.01379728 0.4201241 -0.01045799 0.01319992 0.4203531 -0.00969845 0.01319998 0.4210429 -0.009572982 0.01319998 0.4211335 -0.007812321 0.01319998 0.422405 -0.006663382 0.01319998 0.4229888 -0.005738198 0.01319998 0.423459 -0.003526091 0.01319998 0.4241797 -0.003431797 0.01319998 0.4241948 -0.001229107 0.01319998 0.4245495 1.97258e-7 0.01319998 0.424555 0.001097381 0.01319998 0.4245598 -0.01301473 0.0148676 0.4170576 -0.01368212 0.0148676 0.4156475 -0.01401835 0.0148676 0.4149371 -0.01467913 0.0148676 0.4126859 -0.01472115 0.0148676 0.4123614 -0.01498073 0.0148676 0.4103593 -0.01448619 0.0148676 0.4057078 -0.01441621 0.0148676 0.4055105 -0.01370209 0.0148676 0.4034966 -0.01307052 0.0148676 0.4023331 -0.01115578 0.0148676 0.3995726 -0.01258283 0.0148676 0.4014347 -3.23602e-7 -0.005994081 0.3620768 0 -0.005994081 0.3620768 0 -0.005994081 0.3591233 3.2416e-7 -0.005994081 0.3591233 2.8411e-4 -0.005993127 0.3620728 7.46865e-4 -0.005951106 0.361891 0.001277863 -0.005860805 0.3598621 7.9431e-4 -0.005946815 0.3618724 0.001164853 -0.005886018 0.361545 0.00149995 -0.005809426 0.3606 0.001415073 -0.005830764 0.3601025 0.001404583 -0.005833268 0.3611264 0.001282095 -0.005860209 0.3613403 0.001147985 -0.005889236 0.3596346 7.46113e-4 -0.005952239 0.3593057 7.19062e-4 -0.00595647 0.3592836 2.43518e-4 -0.005994915 0.3591199 -2.84626e-4 -0.005993068 0.3591272 -7.46845e-4 -0.005951106 0.359309 -0.001277804 -0.005860805 0.3613379 -7.94605e-4 -0.005946755 0.3593277 -0.001164853 -0.005886018 0.359655 -0.00149995 -0.005809426 0.3606 -0.001415491 -0.005830645 0.3610963 -0.001404583 -0.005833268 0.3600736 -0.001282095 -0.005860209 0.3598597 -0.001148521 -0.005889177 0.3615648 -7.4617e-4 -0.005952239 0.3618943 -7.19577e-4 -0.005956411 0.3619161 -2.42887e-4 -0.005994915 0.3620802 -3.55e-7 0.005994081 0.3591232 0 0.005994081 0.3591232 0 0.005994081 0.3620768 3.55058e-7 0.005994081 0.3620768 7.46927e-4 0.005951106 0.3593088 7.93584e-4 0.005946874 0.3593271 0.001284599 0.005859673 0.3613411 0.001162171 0.005886554 0.3596517 0.001282274 0.005860149 0.3598597 0.001380324 0.005839049 0.3611871 0.001498162 0.005809962 0.360674 0.00149995 0.005809426 0.3606 0.001402318 0.005833804 0.3600676 0.001137375 0.005891323 0.3615779 7.44724e-4 0.00595206 0.3618924 7.05969e-4 0.00595802 0.3619235 2.86379e-4 0.005993008 0.3591276 2.41198e-4 0.005994975 0.3620805 -7.46927e-4 0.005951106 0.3618912 -7.93586e-4 0.005946874 0.3618729 -0.001284599 0.005859673 0.3598589 -0.001162111 0.005886554 0.3615484 -0.001282274 0.005860149 0.3613403 -0.001380324 0.005839049 0.360013 -0.001498162 0.005809962 0.3605259 -0.00149995 0.005809426 0.3606 -0.001402258 0.005833804 0.3611325 -0.001137375 0.005891323 0.3596221 -7.44724e-4 0.00595206 0.3593075 -7.05971e-4 0.00595802 0.3592765 -2.86381e-4 0.005993008 0.3620724 -2.41204e-4 0.005994975 0.3591195 -1.84239e-6 -0.007708251 0.3539285 -4.19157e-4 -0.007730841 0.3539285 -0.002071261 -0.007459998 0.3539285 -0.002500414 -0.007288992 0.3539285 -0.003626525 -0.006840348 0.3539285 -0.004739224 -0.006085872 0.3539285 -0.005012214 -0.0059008 0.3539285 -0.006163537 -0.004685401 0.3539285 -0.006447196 -0.004213929 0.3539285 -0.007026672 -0.003250837 0.3539285 -0.007484018 -0.001893401 0.3539285 -0.007561206 -0.00166434 0.3539285 -0.007742226 0 0.3539285 -0.007673203 6.34718e-4 0.3539285 -0.007561206 0.00166434 0.3539285 -0.007075726 0.003105163 0.3539285 -0.007026672 0.003250837 0.3539285 -0.006163537 0.004685401 0.3539285 -0.005663752 0.005212962 0.3539285 -0.005012214 0.0059008 0.3539285 -0.003681004 0.006803393 0.3539285 -0.003626525 0.006840348 0.3539285 -0.002071261 0.007459998 0.3539285 -0.001266956 0.007591843 0.3539285 -4.19157e-4 0.007730841 0.3539285 0.001252532 0.007640242 0.3539285 0.001273691 0.007634341 0.3539285 0.002865672 0.007192313 0.3539285 0.003663718 0.006769239 0.3539285 0.00434482 0.006408154 0.3539285 0.005620837 0.005324304 0.3539285 0.005687236 0.005236923 0.3539285 0.006633996 0.003991544 0.3539285 0.007050335 0.003091573 0.3539285 0.007336914 0.002472102 0.3539285 0.007696807 8.37084e-4 0.3539285 0.007696807 6.3935e-4 0.3539285 0.007696807 -8.37084e-4 0.3539285 0.007464706 -0.001891613 0.3539285 0.007336914 -0.002472102 0.3539285 0.006633996 -0.003991544 0.3539285 0.006461024 -0.004218995 0.3539285 0.005620837 -0.005324304 0.3539285 0.004730582 -0.006080508 0.3539285 0.001252532 -0.007640242 0.3539285 0.002505421 -0.00729233 0.3539285 0.002865672 -0.007192313 0.3539285 0.00434482 -0.006408154 0.3539285 0.004424631 -0.009932398 0.3921715 0.0047369 -0.01005458 0.3923613 0.004177093 -0.009677708 0.3920074 0.004415571 -0.009930849 0.3921833 0.004422128 -0.009931445 0.3921699 0.00240767 -0.009308993 0.3935688 0.00240767 0.003779768 0.3881861 0.00240767 0.005515158 0.3890859 0.003404796 0.005747914 0.3887265 0.00240767 -0.001987159 0.3876522 0.00240767 -4.23394e-5 0.3874557 0.003404796 -4.41262e-5 0.3870276 0.00240767 -0.008362948 0.3918582 0.00240767 -0.007106423 0.3903608 0.003404796 -0.007406353 0.3900553 0.003404796 0.008665621 0.3915433 0.00240767 0.008314728 0.3917886 0.00240767 0.009275019 0.3934913 0.003404796 0.009666383 0.3933179 0.00240767 0.009890854 0.3953465 0.00240767 -0.009909331 0.3954291 0.003404796 -0.009701788 0.3933987 0.004171252 -0.008950769 0.390968 0.004171252 -0.009209871 0.3912768 0.003404796 -0.008715927 0.3916159 0.004171252 -0.002572894 0.3867611 0.004171252 -0.004248976 0.387268 0.003404796 -0.004021048 0.3878221 0.004171252 -0.005001068 0.3876659 0.003404796 -0.005821764 0.3887749 0.004171252 -0.006151735 0.3882747 0.004171252 -0.007163166 0.389092 0.004171252 -0.007826089 0.3896278 0.004171252 -4.66269e-5 0.3864285 0.004171252 -0.002188384 0.3866448 0.003404796 -0.002071022 0.3872324 0.003404796 0.001984417 0.3872154 0.004171252 0.002096891 0.3866269 0.004171252 -4.04188e-7 0.3864328 0.004171252 0.006073653 0.3882237 0.004171252 0.00500071 0.3876674 0.003404796 0.00393933 0.3877888 0.004171252 0.004162549 0.3872328 0.004171252 0.002571702 0.3867662 0.003404796 0.007343113 0.3899937 0.004171252 0.007759273 0.3895627 0.004171252 0.007164895 0.3890905 0.004171252 0.008955478 0.3909643 0.004171252 0.009156763 0.3912001 0.00240767 -0.005586028 0.3891322 0.00240767 0.00190407 0.387636 0.00240767 0.007045745 0.3903017 0.00240767 -0.003858268 0.388218 0.004177093 0.009677708 0.3920074 0.004422128 0.009931445 0.3921699 0.004415571 0.009930849 0.3921833 0.004424035 0.00993216 0.3921711 0.004424631 0.009932398 0.3921715 0.0047369 0.01005458 0.3923613 -0.00948143 0.01583349 0.3980514 -0.009167075 0.0166074 0.398635 -0.009337365 0.01627135 0.3982697 -0.009120225 0.01661533 0.3985128 -0.009012579 0.01663351 0.3982326 -0.008975148 0.01663982 0.3981351 -0.009053289 0.0162751 0.3974542 -0.008884847 0.01665997 0.3976933 -0.008739054 0.01668989 0.3967172 -0.008771002 0.01668542 0.3971362 -0.008874297 0.01666235 0.3976416 -0.008706927 0.01668655 0.3957785 -0.008717477 0.01669293 0.3964349 -0.008816123 0.01637643 0.3961549 -0.008824944 0.01635128 0.3961862 -0.009027838 0.01581889 0.3968471 -0.008928179 0.01608031 0.3965225 -0.008889734 0.01626205 0.3965695 -0.00892508 0.01608836 0.3965125 -0.008862733 0.01625204 0.3963092 -0.009041011 0.01579219 0.3968828 -0.009029805 0.0158149 0.3968525 -0.008825719 0.01634913 0.3961886 -0.009511828 0.0151605 0.3978447 -0.009388744 0.015289 0.3976298 -0.009518742 0.0153501 0.397892 -0.009345531 0.01533418 0.3975543 -0.009215414 0.01547002 0.3973272 -0.009155988 0.01580733 0.3972787 -0.009162664 0.01555579 0.3972032 -0.009136676 0.01559811 0.3971421 -0.009859859 0.01496756 0.3982637 -0.009561479 0.01510864 0.3979313 -0.003316223 0.008623242 0.391573 -0.003316223 0.009619116 0.3933388 -0.002308428 0.009251177 0.3935018 -0.003316223 0.003920018 0.3878369 -0.003316223 0.00571978 0.38877 -0.002308428 0.005501031 0.3891077 -0.002308428 0.00829339 0.3918035 -0.002308428 0.003770112 0.3882103 -0.002308428 -4.22295e-5 0.3874818 -0.002308428 -0.001982092 0.3876777 -0.002308428 -0.008341491 0.391873 -0.002308428 -0.009285092 0.3935792 -0.004171252 0.008955478 0.3909643 -0.004171252 0.009156763 0.3912001 -0.004171252 -0.009209871 0.3912768 -0.003316223 -0.00867325 0.3916452 -0.003316223 -0.009654343 0.3934193 -0.002308428 -0.00988388 0.3954347 -0.002308428 0.009865462 0.3953523 -0.002308428 -0.007088184 0.3903794 -0.002308428 -0.005571722 0.389154 -0.002308428 -0.003848314 0.3882421 -0.002308428 0.001899182 0.3876615 -0.002308428 0.007027685 0.3903205 -0.003316223 -4.39089e-5 0.3870794 -0.003316223 -0.00206089 0.3872832 -0.003316223 -0.004001379 0.38787 -0.003316223 -0.005793273 0.388818 -0.003316223 -0.007370114 0.3900923 -0.003316223 0.001974701 0.3872663 -0.003316223 0.007307171 0.390031 -0.004171252 -0.008950769 0.390968 -0.004171252 -0.007826089 0.3896277 -0.004171252 -0.007163166 0.389092 -0.004171252 -0.006151735 0.3882747 -0.004171252 -0.005001068 0.3876659 -0.004171252 -0.004248976 0.387268 -0.004171252 -0.002572894 0.3867611 -0.004171252 -0.002188384 0.3866448 -0.004171252 -4.66255e-5 0.3864285 -0.004171252 -4.05781e-7 0.3864328 -0.004171252 0.002096891 0.3866269 -0.004171252 0.002571702 0.3867662 -0.004171252 0.004162549 0.3872328 -0.004171252 0.00500071 0.3876674 -0.004171252 0.006073653 0.3882237 -0.004171252 0.007164895 0.3890905 -0.004171252 0.007759273 0.3895627 -0.004177093 -0.009677708 0.3920074 -0.004422128 -0.009931445 0.3921699 -0.004422724 -0.009931683 0.3921703 -0.0047369 -0.01005458 0.3923613 -0.004422724 0.009931683 0.3921703 -0.004424035 0.00993216 0.392171 -0.0047369 0.01005458 0.3923613 -0.004422128 0.009931445 0.3921699 -0.004177093 0.009677708 0.3920074 0.0100333 0.01626104 0.399245 0.0100823 0.01620292 0.3991944 0.0107795 0.01620292 0.3999185 0.01151996 0.01555192 0.4190171 0.01048129 0.01646387 0.4191727 0.01036483 0.01658254 0.4190542 0.01086169 0.01658254 0.418479 0.01081621 0.01595062 0.4195274 0.01067316 0.0161885 0.4193743 0.01121777 0.01620292 0.4187701 0.01054912 0.01639473 0.4192416 0.01092284 0.01554578 0.4196835 0.0108307 0.01589554 0.4195486 0.01094257 0.01517587 0.4197953 0.01095306 0.0153867 0.4197402 0.01095491 0.01542413 0.4197304 0.01285409 0.01555192 0.4170942 0.01387023 0.01555192 0.414986 0.01454317 0.01555192 0.4127444 0.01438134 0.01555192 0.4057831 0.01480197 0.01555192 0.4080854 0.01485633 0.01555192 0.4104251 0.01360493 0.01555192 0.4035753 0.01106989 0.01555192 0.3996577 0.01249194 0.01555192 0.4015165 0.01037693 0.01536446 0.3988903 0.01035392 0.01555192 0.3989141 0.01023596 0.01583456 0.3990358 0.009762287 0.01658254 0.3995247 0.01043736 0.01658254 0.4002258 0.01119035 0.01658254 0.4012101 0.01216423 0.01620292 0.4017286 0.01177811 0.01658254 0.4019784 0.01324808 0.01620292 0.4037333 0.01400411 0.01620292 0.4058833 0.01291352 0.01658254 0.404164 0.01282751 0.01658254 0.4039195 0.01441365 0.01620292 0.4081251 0.01382678 0.01658254 0.4074639 0.01355957 0.01658254 0.4060012 0.01393961 0.01658254 0.41088 0.01400738 0.01658254 0.410378 0.01446664 0.01620292 0.4104034 0.01402896 0.01658254 0.4096 0.01395612 0.01658254 0.4081719 0.0137121 0.01658254 0.4125648 0.0141617 0.01620292 0.4126619 0.01321339 0.01658254 0.414226 0.01350635 0.01620292 0.4148446 0.01307761 0.01658254 0.4146782 0.01251691 0.01620292 0.4168977 0.01211959 0.01658254 0.416666 0.01168966 0.01658254 0.4172856 -0.00307548 0.0162 0.4211993 -0.002818167 0.0162 0.4212503 -0.002894699 0.01618349 0.4215692 0.009045422 0.01595002 0.4191295 0.009053349 0.01594555 0.4191374 0.008419275 0.01596713 0.4197128 -0.009456157 0.01573884 0.4193719 -0.00913608 0.0159499 0.4190589 -0.008507966 0.01596713 0.4196383 -0.009128332 0.01595503 0.4190513 -0.008987188 0.01604807 0.4189133 -0.008728265 0.01611852 0.4186599 -0.007961988 0.01618349 0.4189941 -0.008536219 0.01617074 0.4184721 -0.00845164 0.01619374 0.4183893 -0.009880304 0.01524913 0.4197866 -0.009825229 0.01531267 0.4197328 -0.00901407 0.01548701 0.4202353 -0.009690582 0.01546818 0.4196011 -0.009500801 0.01568734 0.4194155 -0.01019549 0.01463907 0.4200955 -0.01012569 0.0147742 0.4200271 -0.009406089 0.01478379 0.4206979 -0.0100845 0.01485383 0.4199867 -0.009630441 0.01398754 0.4209626 -0.01040786 0.01378327 0.4203038 -0.01039677 0.01391249 0.4202929 -0.01037687 0.01398426 0.4202734 -0.0102787 0.01433873 0.4201771 -0.007757484 0.01398754 0.4223151 -0.005697965 0.01398754 0.4233618 -0.003501355 0.01398754 0.4240774 -0.001220464 0.01398754 0.4244447 0.001089692 0.01398754 0.4244549 0.003373682 0.01398754 0.4241077 0.00557655 0.01398754 0.4234114 0.007645249 0.01398754 0.422383 0.009530007 0.01398754 0.421047 0.01030582 0.01378035 0.4203876 0.01035714 0.01342362 0.4204388 0.01003563 0.01477855 0.4201174 0.01018899 0.01433914 0.4202708 0.0102511 0.0141611 0.4203329 0.01027655 0.01398408 0.4203583 0.00967592 0.01540988 0.419758 0.00973457 0.01531332 0.4198166 0.008920073 0.01548701 0.4203143 0.009267985 0.01582461 0.4193513 0.009411215 0.015679 0.419494 0.009609222 0.01547765 0.4196915 0.007878959 0.01618349 0.4190638 0.008458733 0.01616019 0.4185453 0.008651256 0.01612555 0.4187368 0.008772671 0.01610368 0.4188576 0.008237898 0.01619994 0.4183256 0.007662415 0.01619994 0.4188037 0.007066667 0.0162 0.4192987 0.006320714 0.01618349 0.4201683 0.006148815 0.0162 0.419882 0.002789199 0.01618349 0.4215943 0.002715647 0.0162 0.4212754 0.002954483 0.0162 0.4212307 0.004610419 0.01618349 0.4210187 0.004402816 0.0162 0.4207631 0.004490315 0.0162 0.420722 0.005780756 0.0162 0.4201159 0.001457035 0.0162 0.4215113 9.00934e-4 0.01618349 0.4218813 8.76616e-4 0.0162 0.4215451 -6.27601e-5 0.0162 0.4215998 -0.001009047 0.01618349 0.4218729 -9.81717e-4 0.0162 0.4215367 -0.001581072 0.0162 0.4214955 -0.004519343 0.0162 0.4207165 -0.004710793 0.01618349 0.4209776 -0.004588544 0.0162 0.420683 -0.005890011 0.0162 0.4200551 -0.006413519 0.01618349 0.4201123 -0.006239414 0.0162 0.4198279 -0.007166922 0.0162 0.4192248 -0.007743597 0.01619994 0.4187363 -0.008313179 0.01619994 0.418254 -0.006853342 0.01596713 0.4208332 -0.00503385 0.01596713 0.4217578 -0.003093242 0.01596713 0.42239 -0.001078188 0.01596713 0.4227145 9.62716e-4 0.01596713 0.4227235 0.00298047 0.01596713 0.4224168 0.004926562 0.01596713 0.4218017 0.006754159 0.01596713 0.4208931 -0.007260978 0.01548701 0.4215013 -0.005333244 0.01548701 0.422481 -0.003277242 0.01548701 0.4231508 -0.001142323 0.01548701 0.4234946 0.001019954 0.01548701 0.4235041 0.003157794 0.01548701 0.4231792 0.005219638 0.01548701 0.4225275 0.007155895 0.01548701 0.4215648 -0.007576823 0.01478379 0.422019 -0.005565226 0.01478379 0.4230412 -0.003419756 0.01478379 0.4237402 -0.001192033 0.01478379 0.4240989 0.0010643 0.01478379 0.4241089 0.003295123 0.01478379 0.4237697 0.005446672 0.01478379 0.4230898 0.00746715 0.01478379 0.4220852 0.00930804 0.01478379 0.4207803 0.01000344 0.0148707 0.4200853 -0.0135709 0.01561182 0.403555 -0.01246237 0.01561182 0.4015129 -0.01211857 0.0162487 0.401736 -0.01453852 0.01561182 0.4126564 -0.01483726 0.01561182 0.4103521 -0.01442801 0.0162487 0.4103313 -0.0111832 0.01658254 0.4011998 -0.01176834 0.01658254 0.4019633 -0.01290124 0.01658254 0.4041345 -0.01354849 0.01658254 0.4059597 -0.01395171 0.0162487 0.4058514 -0.01394629 0.01658254 0.4108094 -0.01372885 0.01658254 0.4124862 -0.0141375 0.0162487 0.4125721 -0.01105195 0.01511305 0.4197193 -0.0116927 0.0148676 0.4189957 -0.01104509 0.01517784 0.4196995 -0.01090788 0.01588565 0.4194468 -0.01098942 0.01570194 0.4195395 -0.01158076 0.01561182 0.4189057 -0.01099938 0.01560842 0.4195681 -0.01102131 0.0154016 0.4196312 -0.01055866 0.01645416 0.4190757 -0.01073998 0.0162456 0.4192582 -0.01126128 0.0162487 0.4186491 -0.01075643 0.0162267 0.4192748 -0.01044702 0.01658254 0.4189633 -0.01093578 0.01658254 0.4183875 -0.01174998 0.01658254 0.417194 -0.01253449 0.0162487 0.4167824 -0.01217222 0.01658254 0.4165748 -0.01350116 0.0162487 0.4147402 -0.01311093 0.01658254 0.4145916 -0.01324325 0.01658254 0.4141407 -0.01436555 0.0162487 0.4080727 -0.01381927 0.01658254 0.4074131 -0.0139504 0.01658254 0.4081168 -0.01402896 0.01658254 0.4096 -0.01401096 0.01658254 0.4103102 -0.01043361 0.01658254 0.4002217 -0.01104891 0.01561182 0.3996686 -0.01115578 0.0148676 0.3995726 -0.01074415 0.0162487 0.3999426 -0.0128901 0.01561182 0.4169862 -0.01388412 0.01561182 0.4148859 -0.01477307 0.01561182 0.4080293 -0.01434749 0.01561182 0.405745 -0.01319652 0.0162487 0.4037218 -0.01281517 0.01658254 0.4038917 -0.01301473 0.0148676 0.4170576 -0.01401835 0.0148676 0.4149371 -0.01467913 0.0148676 0.4126859 -0.01498073 0.0148676 0.4103593 -0.01491588 0.0148676 0.4080142 -0.01448619 0.0148676 0.4057078 -0.01370209 0.0148676 0.4034966 -0.01258283 0.0148676 0.4014347 0.008992314 -0.01472377 0.3961726 0.008988738 -0.01491671 0.3961674 0.009093523 -0.01490473 0.3969294 0.008827507 -0.01630181 0.3959466 0.009774208 -0.01403605 0.3982062 0.008259832 -0.01090973 0.3968915 0.005139529 -0.01014512 0.3925786 0.004786431 -0.01006221 0.3923853 0.005934834 -0.01040756 0.3930703 0.006414651 -0.0106365 0.3934186 0.006212353 -0.01040172 0.3941019 0.005495011 -0.01022863 0.3927732 0.005720734 -0.0103054 0.3929149 0.007430076 -0.01122087 0.3951327 0.007430851 -0.01080703 0.3957915 0.008512139 -0.01201885 0.3967763 0.008821904 -0.01161056 0.3973613 0.009270191 -0.01239496 0.3977519 0.009585618 -0.01321256 0.3980345 0.009848296 -0.01487237 0.3982743 0.009383022 -0.01488924 0.3976513 0.008978426 -0.01546341 0.3961527 0.008975148 -0.01549744 0.3961481 0.008921027 -0.01588493 0.3960714 0.008894622 -0.01600253 0.3960363 0.008813679 -0.01634585 0.3959283 0.008883714 -0.01392805 0.3960194 0.008974492 -0.01455897 0.3961473 0.008987843 -0.01465177 0.3961662 0.008373439 -0.01237457 0.3960983 0.008396804 -0.01266115 0.3953857 0.008490502 -0.01283353 0.3955014 0.008588969 -0.01301479 0.3956232 0.008620858 -0.01309013 0.3956647 0.008915245 -0.01365226 0.3967166 0.008857309 -0.01382088 0.395983 0.008863687 -0.01384067 0.3959916 0.00811249 -0.01215618 0.3950376 0.00816214 -0.01222932 0.3950956 0.0074445 -0.01137602 0.3943182 0.007481932 -0.01141166 0.3943555 0.007568478 -0.01151388 0.3944492 0.006566166 -0.0107088 0.3935285 0.006640911 -0.01075434 0.3935893 0.007410824 -0.01134395 0.3942847 0.008895754 -0.01272183 0.3971538 0.009162724 -0.01344352 0.3974241 0.009321093 -0.01416277 0.397587 0.008641302 -0.01685947 0.3962924 0.00871706 -0.01732993 0.3998894 0.008170068 -0.01817911 0.4016025 0.007953703 -0.01857191 0.4024215 0.007837951 -0.01855516 0.4022194 0.007841289 -0.01855605 0.4022274 0.007797539 -0.01834529 0.4012123 0.007749259 -0.01845806 0.4016593 0.007744848 -0.01846849 0.4017005 0.007799863 -0.01853859 0.4020988 0.007802665 -0.01854217 0.4021191 0.007829129 -0.01855278 0.4021982 0.008124411 -0.01782929 0.3993333 0.008022487 -0.01798528 0.3998907 0.007893621 -0.01817744 0.400583 0.007826745 -0.0182771 0.400942 0.008226633 -0.01767289 0.3987741 0.008330106 -0.01750004 0.3981462 0.008386075 -0.01740038 0.3978653 0.008438885 -0.01730126 0.3975827 0.008494496 -0.01719009 0.3972623 0.008505403 -0.01716822 0.3971994 0.008566677 -0.01703596 0.3968139 0.006390213 -0.01060831 0.3898256 0.00610888 -0.01047784 0.3901749 0.005897164 -0.01028525 0.3898857 0.005094707 -0.01003485 0.3909787 0.005219638 -0.01015102 0.3914514 0.005938947 -0.01039904 0.3903858 0.005807816 -0.01033824 0.3905487 0.00537163 -0.01019936 0.3912181 0.007245182 -0.01115447 0.3888064 0.007245182 -0.01115453 0.3888064 0.006687343 -0.01068967 0.3890796 0.006814002 -0.01087588 0.3894138 0.006937265 -0.01095372 0.3892941 0.007291495 -0.01123619 0.3890373 0.006667912 -0.01059728 0.3889678 0.006817698 -0.0106911 0.3888458 0.007243812 -0.01108485 0.3886843 0.007242679 -0.01103109 0.38859 0.006187796 -0.01029634 0.3893589 0.006161153 -0.01028215 0.3893841 0.005462229 -0.00997138 0.3901244 0.00547415 -0.009975969 0.3901103 0.005821704 -0.01013088 0.3897429 0.004756629 -0.009768843 0.3910581 0.004938304 -0.009820997 0.3908177 0.005389273 -0.009950459 0.3902209 -0.00149995 -0.008786678 0.3606 -0.001434624 -0.008797585 0.3610382 -0.001279056 -0.008820712 0.3613398 -7.47233e-4 -0.00888127 0.361892 -7.91005e-4 -0.008878588 0.3618747 -0.001188576 -0.008834183 0.3615152 2.02058e-4 -0.00891149 0.3620865 6.66068e-4 -0.008887648 0.3619354 5.89589e-7 -0.008910477 0.3620805 -2.91736e-4 -0.008908987 0.3620716 7.11404e-4 -0.008885324 0.3619207 7.45531e-4 -0.008881807 0.3618934 0.00113064 -0.008841753 0.3615858 0.001278221 -0.008820593 0.3613376 0.001405417 -0.008802294 0.3611236 0.00149995 -0.008786678 0.3606 0.001434624 -0.008797585 0.3601619 0.001279056 -0.008820712 0.3598603 0.001188576 -0.008834183 0.3596848 7.91005e-4 -0.008878588 0.3593252 7.47233e-4 -0.00888127 0.359308 6.65968e-4 -0.008886218 0.3592759 2.91736e-4 -0.008908987 0.3591284 -5.89589e-7 -0.008910477 0.3591195 -2.02058e-4 -0.00891149 0.3591135 -7.11404e-4 -0.008885324 0.3592793 -7.45531e-4 -0.008881807 0.3593066 -0.00113064 -0.008841753 0.3596141 -0.001278221 -0.008820593 0.3598623 -0.001405417 -0.008802294 0.3600763 -0.007617413 -0.003524184 0.3547835 -0.00819689 -0.001804232 0.3547835 -0.008589863 -0.001890718 0.3557913 -0.003931403 -0.007415413 0.3547835 -0.005433559 -0.006396889 0.3547835 -0.005694091 -0.006703555 0.3557913 0.001357853 -0.008282542 0.3547835 -4.54396e-4 -0.00838083 0.3547835 -4.7618e-4 -0.008782565 0.3557913 0.006093382 -0.005771934 0.3547835 0.004710078 -0.006946861 0.3547835 0.00493592 -0.007279932 0.3557913 0.008343935 9.07459e-4 0.3547835 0.008343935 -9.07459e-4 0.3547835 0.008743941 -9.50963e-4 0.3557913 0.006093382 0.005771934 0.3547835 0.007191717 0.004327118 0.3547835 0.00753647 0.004534542 0.3557913 0.001357853 0.008282542 0.3547835 0.003106594 0.007797002 0.3547835 0.003255546 0.008170783 0.3557913 -0.005433559 0.006396889 0.3547835 -0.003931403 0.007415413 0.3547835 -0.004119873 0.007770895 0.3557913 -0.004440605 -0.007695555 0.3567569 -0.004175245 -0.007875442 0.3567569 -0.004119873 -0.007770895 0.3557913 0.008496344 -0.002622663 0.3567569 0.008861541 -9.63752e-4 0.3567569 0.007332742 0.004996836 0.3567569 0.006471335 0.00612998 0.3567569 0.006385505 0.006048619 0.3557913 0.003255248 0.008292913 0.3567569 0.001442074 0.008796334 0.3567569 0.001422941 0.008679628 0.3557913 -0.004440605 0.007695555 0.3567569 -0.005770623 0.006793737 0.3567569 -0.005694091 0.006703555 0.3557913 -0.008589863 0.001890718 0.3557913 -0.008705377 0.00191617 0.3567569 -0.00876981 0.001323699 0.3567569 -0.0080899 0.003742754 0.3567569 -0.007982552 0.003693103 0.3557913 -0.008019149 0.003860414 0.3567569 -0.007001996 0.005322813 0.3557913 -0.007096171 0.005394399 0.3567569 -0.006496667 0.006027281 0.3567569 -0.004175245 0.007875442 0.3567569 -0.002384662 0.00858885 0.3567569 -0.002353012 0.008474886 0.3557913 -0.001977801 0.008655548 0.3567569 -4.7618e-4 0.008782565 0.3557913 6.63758e-4 0.008859753 0.3567569 0 0.008913755 0.3567569 -4.82584e-4 0.008900701 0.3567569 0.00493592 0.007279932 0.3557913 0.00500226 0.007377803 0.3567569 0.003299295 0.008280694 0.3567569 0.005526602 0.006932497 0.3567569 0.007637858 0.004595518 0.3567569 0.00844717 0.002846181 0.3567569 0.008335053 0.002808392 0.3557913 0.008496344 0.002622663 0.3567569 0.008743941 9.50963e-4 0.3557913 0.008861541 9.63752e-4 0.3567569 0.008861541 0 0.3567569 0.008335053 -0.002808392 0.3557913 0.00844717 -0.002846181 0.3567569 0.007637858 -0.004595518 0.3567569 0.005526602 -0.006932497 0.3567569 0.006471335 -0.00612998 0.3567569 0.006385505 -0.006048619 0.3557913 0.007332742 -0.004996836 0.3567569 0.00500226 -0.007377803 0.3567569 0.003299295 -0.008280694 0.3567569 0.003255546 -0.008170783 0.3557913 0.003255248 -0.008292913 0.3567569 0.001422941 -0.008679628 0.3557913 -4.82584e-4 -0.008900701 0.3567569 6.63403e-4 -0.008838593 0.3567569 0.001442074 -0.008796334 0.3567569 -0.002353012 -0.008474886 0.3557913 -0.001977801 -0.008655548 0.3567569 -0.002384662 -0.00858885 0.3567569 -0.005770623 -0.006793737 0.3567569 -0.006496667 -0.006027281 0.3567569 -0.007001996 -0.005322813 0.3557913 -0.008705377 -0.00191617 0.3567569 -0.0080899 -0.003742754 0.3567569 -0.007982552 -0.003693103 0.3557913 -0.008019149 -0.003860414 0.3567569 -0.007096171 -0.005394399 0.3567569 -0.008913755 0 0.3567569 -0.00876981 -0.001323699 0.3567569 -0.00819689 0.001804232 0.3547835 -0.007617413 0.003524184 0.3547835 -0.00668168 0.005079269 0.3547835 -0.002245366 0.008087217 0.3547835 0.004710078 0.006946861 0.3547835 0.007953763 0.002679944 0.3547835 0.007953763 -0.002679944 0.3547835 0.007191717 -0.004327118 0.3547835 0.00753647 -0.004534542 0.3557913 0.003106594 -0.007797002 0.3547835 -0.002245366 -0.008087217 0.3547835 -0.00668168 -0.005079269 0.3547835 -0.008795499 0 0.3557913 -0.008393108 0 0.3547835 -4.54396e-4 0.00838083 0.3547835 -7.37776e-4 0.008880198 0.3593215 -9.84303e-4 0.008859276 0.359468 -0.001293599 0.008818924 0.3598543 -0.001320064 0.008815467 0.3598874 -0.001486301 0.008789002 0.3603966 -0.00149995 0.008786678 0.3606 2.02455e-4 0.00891149 0.3591135 6.66068e-4 0.008887648 0.3592645 0 0.008913755 0.3591 -5.23806e-4 0.008898377 0.3591945 7.11698e-4 0.008885324 0.3592794 7.45596e-4 0.008881807 0.3593065 0.001131534 0.008841693 0.3596151 0.0012784 0.008820533 0.3598622 0.001405298 0.008802294 0.3600757 0.00149995 0.008786678 0.3606 -0.001405298 0.008802294 0.3611243 -0.0012784 0.008820533 0.3613378 -0.001131534 0.008841693 0.3615849 -7.45596e-4 0.008881807 0.3618935 -7.11698e-4 0.008885324 0.3619206 -2.02449e-4 0.00891149 0.3620865 0 0.008913755 0.3621 5.23873e-4 0.008898377 0.3620055 6.65916e-4 0.008886277 0.3619211 7.37776e-4 0.008880198 0.3618785 9.84351e-4 0.008859276 0.361732 0.001293599 0.008818924 0.3613457 0.001320064 0.008815467 0.3613126 0.001486301 0.008789002 0.3608033 0.01000708 0.01539218 0.3985096 0.009779572 0.01624763 0.3989372 0.009781897 0.01624423 0.398934 0.009921967 0.0158419 0.3986959 0.009930253 0.01581811 0.3986819 0.009960472 0.01573139 0.3986306 0.009554386 0.01656985 0.3992542 0.0100063 0.01533937 0.3984999 0.009427428 0.0152167 0.3977296 0.009635686 0.01509338 0.3980015 0.00953412 0.01590472 0.3982552 0.009850144 0.01496922 0.3982746 0.009829878 0.0149784 0.3982549 0.009065806 0.01573771 0.3969559 0.00913608 0.01560205 0.3971412 0.00915116 0.01605099 0.3976085 0.008885562 0.01618129 0.3963909 0.008916258 0.01609545 0.3964958 0.008823692 0.01641017 0.3964795 0.008918166 0.01609092 0.3965017 0.009029865 0.0158236 0.3968454 0.009172976 0.01553958 0.3972311 0.009259641 0.01542961 0.3974009 0.009381532 0.015275 0.3976396 0.008724093 0.01663738 0.395846 0.008808076 0.01639842 0.3961234 0.008823573 0.01635444 0.3961794 0.008705556 0.01669025 0.3957846 0.008711278 0.01669245 0.396247 0.008718013 0.01668941 0.3964028 0.00872755 0.01669096 0.3965998 0.008858621 0.01666349 0.397673 0.008854985 0.01666438 0.3976503 0.008765697 0.01668632 0.3970851 0.008734345 0.01669204 0.3967388 0.009182631 0.01660704 0.3986144 0.009009242 0.01663428 0.3982403 0.009004831 0.016635 0.3982309 0.008964538 0.01664251 0.3981026 0.008910775 0.01665312 0.3978846 0.00932306 0.01658499 0.3989174 0.009512901 0.01656991 0.3991957 0.007242679 -0.009158194 0.3867222 0.007242679 -0.009476125 0.3869666 0.007242679 -0.01091343 0.3884478 0.006161153 0.01028203 0.389384 0.006239473 0.01032441 0.3893119 0.007242679 0.009160518 0.3867193 0.006817698 0.01069182 0.3888465 0.007242679 0.01103109 0.38859 0.007242679 0.01086306 0.388388 0.006662726 0.01059335 0.3889712 0.007242679 0.009417593 0.3869147 0.005811274 0.01012605 0.3897539 0.005461752 0.009970247 0.3901236 0.00538516 0.009947538 0.3902235 0.004917502 0.009809136 0.3908336 0.004843413 0.009787201 0.3909303 0.004756212 0.009768068 0.3910577 0.007242679 0.007774472 0.3856658 0.007242679 0.006392657 0.3849022 0.007242679 0.005968034 0.3846675 0.007242679 0.004036307 0.3839408 0.007242679 0.003284513 0.3837767 0.007242679 0.002019762 0.3835008 0.007242679 -1.92588e-7 0.3833596 0.007242679 -3.9085e-5 0.3833569 0.007242679 -0.002097129 0.3835121 0.007242679 -0.003284037 0.3837779 0.007242679 -0.00411117 0.3839631 0.007242679 -0.006038904 0.3847004 0.007242679 -0.006394088 0.3848993 0.007242679 -0.007839798 0.3857087 -0.004938244 0.009820997 0.3908177 -0.004756629 0.009768843 0.3910581 -0.007242679 0.009158372 0.386722 -0.007242679 0.009469866 0.386961 -0.006817698 0.01069134 0.388846 -0.007242679 0.010912 0.388446 -0.007242679 0.01103109 0.38859 -0.006667912 0.0105974 0.3889679 -0.006187856 0.0102964 0.3893589 -0.006161153 0.01028215 0.3893841 -0.005821764 0.01013088 0.3897429 -0.005473792 0.00997579 0.3901108 -0.005462169 0.00997138 0.3901243 -0.005389213 0.009950399 0.3902209 -0.006817758 -0.01069229 0.3888471 -0.007242679 -0.01103109 0.38859 -0.007242679 -0.010912 0.388446 -0.006161093 -0.01028186 0.3893839 -0.00666815 -0.01059883 0.3889694 -0.007242679 -0.009158372 0.386722 -0.007242679 -0.009469866 0.386961 -0.004756152 -0.009767889 0.3910576 -0.005821764 -0.01013064 0.3897428 -0.005461752 -0.009970188 0.3901236 -0.005387365 -0.009948909 0.390222 -0.004937767 -0.009819984 0.3908171 -0.007242679 -0.007827699 0.3857007 -0.007242679 -0.006393611 0.3849002 -0.007242679 -0.006020188 0.3846917 -0.007242679 -0.00408554 0.3839554 -0.007242679 -0.003284156 0.3837777 -0.007242679 -0.002064526 0.3835073 -0.007242679 0 0.3833569 -0.007242679 0.002064526 0.3835073 -0.007242679 0.003284156 0.3837777 -0.007242679 0.00408554 0.3839554 -0.007242679 0.006020188 0.3846917 -0.007242679 0.006393611 0.3849002 -0.007242679 0.007827699 0.3857007 0.0100395 0.01537466 0.4196027 0.01031053 0.01490885 0.4198737 0.008474767 0.01628273 0.4180909 0.008495867 0.01629012 0.41807 0.008924007 0.01621282 0.4184893 0.008942425 0.01707178 0.4176276 0.008948266 0.01719999 0.4176217 0.009496688 0.0171144 0.4181752 0.01051187 0.01437711 0.4200752 0.01039123 0.01553541 0.4194805 0.01068222 0.01503556 0.4197722 0.01071625 0.01577734 0.4194988 0.01032578 0.01622879 0.4191059 0.009561359 0.01710432 0.4182405 0.009398698 0.01676619 0.4181738 0.009945213 0.01694095 0.4186279 0.009880721 0.01656264 0.4186584 0.01001906 0.01687788 0.418703 0.008885443 0.01686179 0.417684 0.008880019 0.01684176 0.4176894 0.009332537 0.01603943 0.4188966 0.009709239 0.01575642 0.4192727 0.00919491 0.0164327 0.4182824 0.009632766 0.01624774 0.4187206 0.01003682 0.01594477 0.4191252 0.008570075 0.01631605 0.4179965 0.008724749 0.01651018 0.4178432 0.008727252 0.01651328 0.4178407 0.008823692 0.01663434 0.4177452 0.009708583 0.01666367 0.3996611 0.009656369 0.01857244 0.414238 0.008923053 0.01857244 0.4154692 0.008677005 0.01857244 0.4158823 0.00802797 0.01857244 0.4166929 0.01066917 0.01857244 0.4105627 0.01066595 0.01857244 0.4105802 0.01032757 0.01857244 0.4124458 0.01007336 0.01857244 0.4131247 0.007976293 0.01857036 0.4024433 0.008014082 0.01853883 0.4024067 0.008018136 0.01853555 0.4024032 0.008564352 0.01857244 0.4031789 0.007973551 0.0185725 0.4024459 0.008473098 0.01811873 0.4018706 0.008621037 0.01798135 0.4016929 0.008027732 0.01852732 0.4023932 0.008090734 0.0184738 0.4023297 0.008019864 0.01853394 0.4024009 0.00868386 0.01857244 0.4033272 0.009661436 0.01857244 0.4049725 0.009842038 0.01857244 0.4054564 0.01033067 0.01857244 0.4067655 0.01054793 0.01857244 0.4079707 0.01067018 0.01857244 0.4086489 0.00965327 0.01674455 0.3997957 0.00965476 0.0167424 0.3997921 0.009660363 0.0167343 0.3997787 0.009158074 0.01739329 0.4008328 0.009397506 0.01708102 0.4003345 0.009635746 0.0167703 0.3998386 0.005915343 0.01648628 0.414986 0.005916953 0.01648992 0.4149841 0.006113111 0.01719999 0.4147604 0.006067335 0.01685345 0.4148141 0.006061851 0.01681166 0.4148205 0.005664348 0.01626628 0.4152482 0.005692422 0.01627397 0.415221 0.00542128 0.0162 0.4154829 -0.002551555 0.0162 0.4171822 -0.005470454 0.0162 0.4154373 -0.004809916 0.0162 0.4159925 0.004756152 0.0162 0.4160326 0.002487897 0.0162 0.4172033 -3.35409e-5 0.0162 0.4175999 -0.006007552 0.01656389 0.4148829 -0.005956888 0.01650583 0.414938 -0.008796453 0.01651108 0.4177662 -0.00840342 0.01620823 0.4181628 -0.005772948 0.01629513 0.4151383 -0.008711278 0.01637536 0.4178521 -0.008796393 0.01651096 0.4177662 -0.005714237 0.01627665 0.4151963 -0.008549809 0.01628768 0.4180151 -0.008565127 0.01629602 0.4179996 -0.008935332 0.01673239 0.417626 -0.008953571 0.01683676 0.4176076 -0.006105661 0.01686191 0.4147685 -0.008957505 0.01685947 0.4176036 -0.006136953 0.01695692 0.414732 -0.00901699 0.01719999 0.4175436 -0.006156146 0.01719999 0.4147089 -0.009472548 0.01676625 0.4180915 -0.009793281 0.01575636 0.4191875 -0.009959101 0.0165627 0.4185717 -0.01002413 0.01694041 0.4185415 -0.01040834 0.01622885 0.4190151 -0.01009786 0.016878 0.4186151 -0.0108025 0.0157774 0.4194045 -0.01077097 0.01503545 0.4196781 -0.01060336 0.01437693 0.4199826 -0.01040017 0.01490873 0.4197829 -0.01012659 0.0153746 0.4195144 -0.009413063 0.01603937 0.418815 -0.009000718 0.01621282 0.4184114 -0.009421706 0.01715952 0.4179446 -0.009568095 0.01710629 0.4180896 -0.01047724 0.01553541 0.419389 -0.01011949 0.01594477 0.419037 -0.009711682 0.01624774 0.4186361 -0.009269714 0.0164327 0.418202 -0.0106737 0.01857244 0.410511 -0.01067101 0.01857244 0.4105263 -0.008015871 0.01853734 0.4024055 -0.007973551 0.01857244 0.4024459 -0.008558571 0.01857244 0.4031713 -0.009151995 0.0173996 0.4008421 -0.008617162 0.01798516 0.4016987 -0.009628474 0.01677948 0.3998529 -0.009390771 0.01708877 0.4003463 -0.008468091 0.01812207 0.4018738 -0.0103442 0.01857244 0.4123848 -0.01009637 0.01857244 0.4130598 -0.009688436 0.01857244 0.4141707 -0.008969128 0.01857244 0.4153993 -0.008727133 0.01857244 0.4158125 -0.008088588 0.01857244 0.4166237 -0.009653687 0.01857244 0.4049562 -0.008679926 0.01857244 0.4033218 -0.01066648 0.01857244 0.4086084 -0.01054227 0.01857244 0.4079318 -0.01032286 0.01857244 0.4067372 -0.009833097 0.01857244 0.4054337 0.002598047 0.008499979 0.3741 0.002999961 0.008499979 0.3756 0.002598047 0.008499979 0.3771 0.00149995 0.008499979 0.3781981 -0.002598047 0.008499979 0.3741 0 0.008499979 0.3786 -0.00149995 0.008499979 0.3730019 0 0.008499979 0.3726 -0.00149995 0.008499979 0.3781981 -0.002598047 0.008499979 0.3771 -0.002999961 0.008499979 0.3756 0.00149995 0.008499979 0.3730019 -0.008714675 0.01733553 0.3999033 -0.008168458 0.01818197 0.4016085 -0.007797241 0.0183469 0.4012201 -0.007751643 0.01845729 0.4016601 -0.007744431 0.01847481 0.4017299 -0.007798135 0.01854068 0.4021006 -0.007803201 0.01854681 0.4021354 -0.007822811 0.01855379 0.4021911 -0.007825672 0.01855486 0.402199 -0.007833063 0.01855665 0.4022164 -0.00783658 0.01855719 0.4022231 -0.007904469 0.01856815 0.4023517 -0.008123219 0.0178315 0.3993487 -0.008022129 0.01798641 0.3999041 -0.007894277 0.01817649 0.4005831 -0.007825314 0.01827895 0.4009492 -0.008468568 0.01720249 0.3972807 -0.008224666 0.01767605 0.3987915 -0.008330106 0.01749998 0.398146 -0.008700668 0.01670396 0.3958306 -0.009773492 0.01403129 0.3982055 -0.009584367 0.01320821 0.3980333 -0.009161651 0.01343971 0.397423 -0.008771717 0.01649343 0.3958657 -0.004761219 0.01005828 0.392373 -0.004785537 0.01006209 0.3923848 -0.005142927 0.0101369 0.3925735 -0.006194531 0.01050734 0.3932422 -0.006416678 0.01063019 0.393415 -0.006210625 0.01040083 0.3941006 -0.005939364 0.01039862 0.393066 -0.005262494 0.01016199 0.3926367 -0.005719304 0.01030486 0.392914 -0.007428109 0.01121902 0.3951309 -0.008257389 0.01090705 0.3968895 -0.008510231 0.01201593 0.3967745 -0.007428586 0.01080513 0.3957897 -0.008819699 0.01160728 0.3973594 -0.009268403 0.01239109 0.3977503 -0.009848177 0.0148673 0.3982742 -0.009382963 0.01488488 0.3976513 -0.009093463 0.01490092 0.3969294 -0.008975505 0.01549392 0.3961487 -0.008998751 0.01510781 0.3961819 -0.008995473 0.01491427 0.3961772 -0.008896052 0.0159986 0.396037 -0.008918225 0.01590019 0.3960677 -0.008828938 0.01629656 0.3959438 -0.008814513 0.01634609 0.3959242 -0.008914351 0.01364886 0.3967156 -0.008854746 0.01381903 0.3959798 -0.008883059 0.01392501 0.3960186 -0.008953332 0.01431912 0.3961173 -0.008976459 0.01455843 0.3961502 -0.008992135 0.01472055 0.3961725 -0.008409738 0.01264321 0.3953953 -0.008497655 0.01282924 0.3955076 -0.008371829 0.01237177 0.3960967 -0.008619725 0.01308739 0.3956633 -0.008768916 0.01349759 0.3958619 -0.007480025 0.01140981 0.3943538 -0.007570743 0.01150763 0.3944487 -0.007841527 0.01179951 0.3947324 -0.008160531 0.01222687 0.3950938 -0.006639122 0.01075321 0.393588 -0.007079064 0.01106047 0.3939694 -0.00744313 0.01137763 0.3943184 -0.008894264 0.01271843 0.3971523 -0.009320497 0.01415866 0.3975864 -0.006390213 0.01060831 0.3898256 -0.00610888 0.01047784 0.3901749 -0.005898118 0.01028668 0.3898873 -0.005219638 0.01015102 0.3914514 -0.00537163 0.01019936 0.3912181 -0.005096137 0.01003617 0.39098 -0.005807816 0.01033824 0.3905487 -0.005938947 0.01039904 0.3903858 -0.007245182 0.01115447 0.3888064 -0.007245182 0.01115453 0.3888064 -0.006687819 0.0106911 0.3890814 -0.006814002 0.01087588 0.3894138 -0.006937265 0.01095372 0.3892941 -0.007291495 0.01123619 0.3890373 -0.007243812 0.01108604 0.3886863 -0.008046686 0.01198512 0.3881176 -0.008133351 0.01211756 0.3880556 -0.008149862 0.01215392 0.3881476 -0.008539795 0.01288861 0.3878604 -0.008541107 0.01290768 0.3879804 -0.00853604 0.01283085 0.387757 -0.008502244 0.01282715 0.388028 -0.008535385 0.01282 0.3877446 -0.008463621 0.01274704 0.3880754 -0.008534967 0.01281261 0.3877362 -0.008419156 0.01256889 0.3878449 -0.008382797 0.01249873 0.3878772 -0.007691025 0.01158004 0.388515 -0.007826507 0.01164871 0.3882751 -0.007683992 0.01149797 0.3883519 -0.008159875 0.01226192 0.3883722 -0.007975816 0.01196801 0.388552 -0.007711112 0.01168495 0.3887397 -0.007432639 0.01138716 0.3889371 -0.005897164 -0.01028525 0.3898857 -0.005219638 -0.01015102 0.3914514 -0.00537163 -0.01019936 0.3912181 -0.005094707 -0.01003485 0.3909787 -0.006937265 -0.01095372 0.3892941 -0.007291495 -0.01123619 0.3890373 -0.007262229 -0.01113796 0.3888114 -0.005938947 -0.01039904 0.3903858 -0.00610888 -0.01047784 0.3901749 -0.006390213 -0.01060831 0.3898256 -0.006687343 -0.01068967 0.3890796 -0.006814002 -0.01087588 0.3894138 -0.005807816 -0.01033824 0.3905487 -0.007245719 -0.01108241 0.3886838 -0.00723946 -0.01106137 0.3886355 -0.006210565 -0.01040077 0.3941007 -0.007428646 -0.01080513 0.3957898 -0.009773492 -0.01403129 0.3982056 -0.004761219 -0.01005828 0.392373 -0.004785537 -0.01006209 0.3923848 -0.005142927 -0.0101369 0.3925735 -0.005262553 -0.01016199 0.3926367 -0.005719304 -0.01030486 0.392914 -0.005939364 -0.01039862 0.393066 -0.006194531 -0.01050734 0.3932422 -0.007570743 -0.01150763 0.3944487 -0.007480084 -0.01140987 0.3943537 -0.00742805 -0.01121896 0.3951311 -0.00744313 -0.01137763 0.3943183 -0.007079064 -0.01106047 0.3939694 -0.006639122 -0.01075321 0.393588 -0.006416678 -0.01063019 0.393415 -0.008497655 -0.01282924 0.3955076 -0.008409738 -0.01264321 0.3953953 -0.008371829 -0.01237177 0.3960968 -0.008160531 -0.01222693 0.3950938 -0.007841527 -0.01179951 0.3947324 -0.008883059 -0.01392501 0.3960186 -0.008854746 -0.01381903 0.3959798 -0.008914351 -0.01364886 0.3967157 -0.008768916 -0.01349759 0.3958619 -0.008619725 -0.01308739 0.3956633 -0.009093463 -0.01490092 0.3969295 -0.008992135 -0.01472055 0.3961725 -0.008976459 -0.01455843 0.3961502 -0.008953332 -0.01431912 0.3961172 -0.008975505 -0.01549392 0.3961487 -0.008998751 -0.01510781 0.3961818 -0.008995473 -0.01491427 0.3961772 -0.008771717 -0.01649343 0.3958657 -0.008814513 -0.01634609 0.3959241 -0.008828938 -0.01629656 0.3959438 -0.008896052 -0.0159986 0.3960369 -0.009383022 -0.01488488 0.3976513 -0.008918225 -0.01590019 0.3960677 -0.009848237 -0.0148673 0.3982742 -0.009584367 -0.01320821 0.3980333 -0.009268403 -0.01239109 0.3977503 -0.008819699 -0.01160728 0.3973594 -0.008257389 -0.01090705 0.3968895 -0.008510291 -0.01201587 0.3967745 -0.008894264 -0.01271837 0.3971524 -0.009320557 -0.01415866 0.3975865 -0.009161651 -0.01343971 0.397423 -0.008022189 -0.01798635 0.3999043 -0.008123159 -0.01783162 0.3993486 -0.008714675 -0.01733553 0.3999033 -0.008224487 -0.01767641 0.398791 -0.008469998 -0.01720219 0.3972811 -0.008330106 -0.01749998 0.398146 -0.008345484 -0.01747316 0.3980707 -0.007894217 -0.01817649 0.4005831 -0.007825195 -0.01827901 0.400949 -0.008168458 -0.01818197 0.4016085 -0.0077973 -0.01834696 0.4012202 -0.007838487 -0.01855635 0.4022203 -0.00782597 -0.01855486 0.4021995 -0.007808327 -0.01853781 0.4020992 -0.007744252 -0.018476 0.4017353 -0.007752001 -0.01845717 0.4016602 -0.006156146 -0.01899999 0.4147089 -0.006989419 -0.01899999 0.4155346 -0.007526576 -0.01890367 0.4160668 -0.007555067 -0.01888763 0.416095 -0.008027493 -0.01862204 0.4165631 0.004849314 -0.01899999 0.4159627 0.004752039 -0.01899999 0.4160264 -0.005290508 -0.01899999 0.415601 -0.004795432 -0.01899999 0.4159733 0.006113111 -0.01899999 0.4147604 0.00577563 -0.01899999 0.4151356 -0.004296183 -0.01899999 0.4163486 -0.003199219 -0.01899999 0.4169325 -3.2824e-5 -0.01899999 0.4175797 -9.05239e-4 -0.01899999 0.4175488 -0.002025663 -0.01899999 0.4173393 -0.002543807 -0.01899999 0.4171597 3.37973e-4 -0.01899999 0.4175929 0.001571297 -0.01899999 0.4174442 0.003898084 -0.01899999 0.4165862 0.002767741 -0.01899999 0.4171061 0.002483189 -0.01899999 0.4171865 0.007536947 -0.01887774 0.4161974 0.00750333 -0.01888543 0.4161635 0.007006585 -0.01899844 0.4156621 0.006938755 -0.01899999 0.4155937 0.006871104 -0.018992 0.4034351 0.006824731 -0.01899993 0.4034767 0.007421076 -0.01899999 0.40424 0.007408082 -0.01899999 0.4149632 0.008986949 -0.01889109 0.4139165 0.00825268 -0.01899999 0.4135631 0.008075416 -0.01889109 0.4154468 0.007733285 -0.01899999 0.4145262 0.009090244 -0.01899999 0.4107996 0.008834898 -0.01899999 0.4120348 0.009611606 -0.01889109 0.4122485 0.008820772 -0.01899999 0.4121033 0.008365213 -0.01899999 0.4133545 0.009112358 -0.01899999 0.4104229 0.009929478 -0.01889109 0.410496 0.009168148 -0.01899999 0.4094713 0.009930431 -0.01889109 0.4087148 0.008824527 -0.01899999 0.4071781 0.009053051 -0.01899999 0.408146 0.009108781 -0.01899999 0.408788 0.007458746 -0.01886433 0.4029078 0.007419109 -0.01888555 0.4029434 0.008081853 -0.01889109 0.4037621 0.007383823 -0.01890438 0.4029751 0.00874722 -0.01899999 0.4068506 0.009614467 -0.01889109 0.406962 0.008256793 -0.01899999 0.4056128 0.008991658 -0.01889109 0.4052933 0.007592439 -0.01899999 0.4044593 0.007904648 -0.01862579 0.4025077 0.007193326 -0.01885813 0.402425 0.007290065 -0.0186215 0.4006474 0.007588326 -0.01837158 0.3994045 0.007853865 -0.01808023 0.3981461 0.007110714 -0.01880896 0.4018594 0.007166445 -0.01872724 0.4012595 0.006364703 -0.01898771 0.4020956 0.00638169 -0.01899999 0.4028403 0.006497859 -0.01899755 0.4028007 0.006393194 -0.01899999 0.4028568 0.006411314 -0.01896101 0.4013987 0.006057798 -0.01899999 0.4020127 0.006119966 -0.01899999 0.4021715 0.005830645 -0.01899999 0.4005389 0.00584656 -0.01899999 0.4008039 0.006547152 -0.0189144 0.4007278 0.005853593 -0.01899999 0.4009214 0.005958497 -0.01899999 0.4014821 0.005740463 -0.01899999 0.3990345 0.005766332 -0.01899999 0.3994661 0.00611782 -0.01897758 0.3994544 0.006894171 -0.01877379 0.3994281 0.00770992 -0.01825565 0.398146 0.005731999 -0.01899999 0.398146 0.006496429 -0.01887124 0.398146 0.006714344 -0.01883459 0.398146 0.007214844 -0.01854354 0.398146 0.007699251 -0.01824164 0.3937538 0.007841229 -0.01813334 0.3937538 0.007942557 -0.01800382 0.3937538 0.008309721 -0.01753479 0.3937538 0.008330106 -0.01749998 0.3937538 0.005731999 -0.01899999 0.3937538 0.006382584 -0.01892858 0.3937487 0.007232129 -0.01859802 0.3937538 0.007202327 -0.01861494 0.3937618 0.007024466 -0.01870721 0.3937773 0.006708085 -0.01881635 0.3937632 0.006505131 -0.01888632 0.3937541 -0.007447123 -0.01887524 0.4029182 -0.006861805 -0.01899325 0.4034435 -0.007417261 -0.0188924 0.4029451 -0.008074343 -0.0188924 0.4037598 -0.008980154 -0.0188924 0.4052802 -0.00825864 -0.01899999 0.4056277 -0.006824731 -0.01899999 0.4034767 -0.007414042 -0.01899999 0.4042382 -0.007639169 -0.01899999 0.404529 -0.009602665 -0.0188924 0.406937 -0.008772075 -0.01899999 0.406931 -0.008293032 -0.01899999 0.4056887 -0.009922325 -0.0188924 0.4086776 -0.009066045 -0.01899999 0.4082295 -0.008822262 -0.01899999 0.4071527 -0.009113132 -0.01899999 0.4103782 -0.009168922 -0.01899999 0.4095562 -0.009106636 -0.01899999 0.4087531 -0.0090788 -0.01899999 0.4108833 -0.009929001 -0.0188924 0.4104474 -0.008841395 -0.01899999 0.4119808 -0.009622514 -0.0188924 0.4121904 -0.008797407 -0.01899999 0.4121841 -0.008330464 -0.01899999 0.413431 -0.008118212 -0.0188924 0.4153791 -0.00828731 -0.01899999 0.4135093 -0.00901252 -0.0188924 0.4138518 -0.007687926 -0.01899999 0.4145967 -0.007456421 -0.01899999 0.4149075 0.008377611 0.01248884 0.3878815 0.008152067 0.01215708 0.3881456 0.008422434 0.0125752 0.3878418 0.008535385 0.01282 0.3877446 0.008534967 0.01281261 0.3877362 0.008496284 0.01283067 0.388027 0.008541107 0.01290768 0.3879804 0.008539676 0.01288855 0.3878611 0.008165478 0.01226276 0.3883708 0.00853604 0.01283091 0.3877571 0.007262229 0.01113796 0.3888114 0.007692396 0.01158154 0.388514 0.007245957 0.0110833 0.388686 0.007685303 0.01149964 0.3883512 0.00723946 0.01106137 0.3886355 0.008136212 0.0121206 0.388054 0.008047223 0.01198476 0.3881176 0.007828712 0.01165145 0.3882737 0.007291495 0.01123619 0.3890373 0.007443904 0.01137673 0.3889403 0.007484972 0.01141458 0.3889142 0.007716119 0.0116828 0.3887398 0.008060276 0.01208215 0.3884801 0.005219638 0.01015102 0.3914514 0.005358338 0.01019519 0.3912385 0.005082309 0.01003313 0.3910016 0.006683111 0.01068812 0.3890854 0.006937265 0.01095372 0.3892941 0.005938947 0.01039904 0.3903858 0.006100118 0.01047378 0.3901857 0.005888521 0.01028281 0.3898988 0.006390213 0.01060831 0.3898256 0.00680989 0.01087325 0.3894178 0.005807816 0.01033824 0.3905487 0.009321093 0.01416277 0.397587 0.009383022 0.01488924 0.3976513 0.009093523 0.01490473 0.3969294 0.007430851 0.01080703 0.3957915 0.006640911 0.01075434 0.3935893 0.006411314 0.01064074 0.3934199 0.006212353 0.01040166 0.3941019 0.004907488 0.0100829 0.3924455 0.00480163 0.01006466 0.3923926 0.004788339 0.01006251 0.3923861 0.004786431 0.01006221 0.3923853 0.005138456 0.01014608 0.3925788 0.005720734 0.0103054 0.3929149 0.005773901 0.01032525 0.3929496 0.005935728 0.01040536 0.393069 0.007430076 0.01122087 0.3951327 0.007575094 0.01150667 0.3944509 0.007564544 0.01149374 0.3944393 0.007481932 0.01141166 0.3943555 0.007441639 0.01137965 0.3943185 0.006710886 0.01079863 0.3936474 0.00816214 0.01222932 0.3950956 0.008373439 0.01237452 0.3960984 0.008222818 0.01232272 0.3951675 0.008620858 0.01309013 0.3956648 0.008488237 0.01283442 0.3954991 0.008397698 0.0126599 0.3953859 0.008970797 0.01455932 0.3961422 0.008895158 0.01398164 0.3960354 0.008915245 0.01365226 0.3967166 0.008993685 0.01474982 0.3961746 0.008992314 0.01472377 0.3961726 0.008883714 0.01392805 0.3960195 0.008852362 0.01382482 0.395977 0.008654415 0.01317352 0.3957088 0.008894681 0.01600253 0.3960363 0.008920848 0.01588588 0.3960713 0.008951783 0.01569259 0.3961148 0.008975148 0.01549744 0.3961481 0.008989572 0.01491659 0.3961687 0.008827507 0.01630181 0.3959466 0.008813679 0.01634585 0.3959283 0.009848296 0.01487237 0.3982743 0.009774208 0.01403605 0.3982062 0.009585678 0.01321256 0.3980345 0.009270191 0.01239496 0.3977519 0.008821904 0.01161056 0.3973613 0.008259832 0.01090973 0.3968915 0.008512139 0.01201885 0.3967763 0.009162724 0.01344352 0.3974241 0.008895754 0.01272183 0.3971538 0.00722754 -0.01859003 0.3935193 0.007160544 -0.01862835 0.3935298 0.006536424 -0.01888138 0.3936277 0.00652486 -0.01888597 0.3936295 0.00648868 -0.01890057 0.3936352 0.006910383 -0.01873081 0.393569 0.006638646 -0.01884019 0.3936116 0.007150053 -0.01863431 0.3935315 -0.000999987 -0.01719999 0.4016627 -0.000999987 -0.01899999 0.4016627 0.000999987 -0.01899999 0.4016627 9.26865e-4 -0.01687353 0.401654 5.8614e-4 -0.01655209 0.4016215 0.000999987 -0.01719999 0.4016627 9.04651e-4 -0.01677435 0.4016513 6.6699e-4 -0.0164678 0.4016283 6.36592e-4 -0.01642858 0.4016253 2.46943e-4 -0.01623082 0.4016038 2.44328e-4 -0.0162307 0.4016038 -1.88727e-4 -0.0162177 0.4016022 -6.62459e-4 -0.01647394 0.4016286 -8.32036e-4 -0.01664513 0.4016434 -9.27632e-4 -0.01687639 0.4016543 -2.40617e-4 -0.01623928 0.4016047 -5.6234e-4 -0.01637285 0.4016198 -9.81112e-4 -0.0170058 0.4016604 0 -0.01619911 0.3805859 0 -0.01609033 0.3798697 0 -0.01608961 0.379865 0 -0.01608502 0.3798347 0 -0.01619994 0.380657 2.37274e-4 -0.01625877 0.380657 4.67199e-4 -0.01631581 0.380657 6.55144e-4 -0.01648372 0.380657 -2.37143e-4 -0.01625913 0.380657 -4.6981e-4 -0.01631718 0.380657 -6.55332e-4 -0.01648342 0.380657 0.006404817 -0.01838409 0.3892537 0.00688976 -0.01838409 0.390641 0.007550239 -0.01764124 0.3904404 0.002610623 -0.01899999 0.3865885 0.002688646 -0.01899999 0.3866778 0.003342032 -0.01885432 0.3860189 0.005708158 -0.01899999 0.3936044 0.00549364 -0.01899999 0.3924704 0.005729079 -0.01899999 0.3937351 0.005175232 -0.01899993 0.3912273 0.006030857 -0.01885432 0.3909018 0.005154371 -0.01899993 0.3911681 0.005571186 -0.01885432 0.3895866 0.004700541 -0.01899999 0.389881 0.004988789 -0.01885432 0.3883152 0.004163503 -0.01899999 0.3887475 0.004258096 -0.01885432 0.3871117 0.003375351 -0.01899999 0.3874636 0.00349301 -0.01899999 0.3876501 0.004097819 -0.01899999 0.3886089 0.00279951 -0.01885432 0.3855378 0.001823604 -0.01899999 0.3859727 0.002193391 -0.01885432 0.3851208 0.001719892 -0.01899999 0.3859236 0.001522004 -0.01885432 0.3847905 0.001174271 -0.01899999 0.385665 0.000999987 -0.01899999 0.3855825 0.001000046 -0.01899611 0.3854225 0.001000404 -0.01886838 0.3846668 0.001000344 -0.01884949 0.3846232 0.003973662 -0.01838409 0.3853812 0.004991829 -0.01838409 0.3865945 0.005783736 -0.01838409 0.3878985 0.007045805 -0.01764124 0.3889977 0.007933855 -0.01764124 0.3918977 0.008036792 -0.01784807 0.3933924 0.008202373 -0.01763296 0.3933664 0.008280694 -0.01753121 0.3933541 0.008402109 -0.01724815 0.3933351 0.008577227 -0.01683992 0.3933076 0.007516443 -0.01836496 0.393474 0.007599771 -0.01830011 0.3934609 0.007260441 -0.01838409 0.3920493 0.007822394 -0.01812666 0.393426 0.007887721 -0.01804178 0.3934158 0.007355153 -0.01849061 0.3934993 -10e-4 -0.01884758 0.3846244 -0.000999987 -0.01899999 0.3855825 -0.000999987 -0.01899737 0.385452 -0.000999987 -0.01887404 0.3846859 -0.004833281 -0.01899999 0.3902158 -0.004706919 -0.01899999 0.3899324 -0.005571246 -0.01885437 0.3895867 -0.007045924 -0.01764124 0.3889979 -0.007933855 -0.01764124 0.3918978 -0.008360326 -0.01722884 0.3933416 -0.008379042 -0.01719218 0.3933387 -0.007550299 -0.01764124 0.3904405 -0.006404876 -0.01838415 0.3892539 -0.005783796 -0.01838415 0.3878986 -0.004991829 -0.01838415 0.3865947 -0.003973722 -0.01838415 0.3853814 -0.00219351 -0.01885437 0.3851209 -0.00279951 -0.01885437 0.3855378 -0.001522123 -0.01885437 0.3847905 -0.001180589 -0.01899999 0.3856527 -0.003342092 -0.01885437 0.3860192 -0.004258155 -0.01885437 0.3871119 -0.00350058 -0.01899999 0.3876463 -0.002839028 -0.01899999 0.3868183 -0.002685904 -0.01899999 0.3866829 -0.002068281 -0.01899999 0.3861365 -0.001714587 -0.01899999 0.3859309 -0.001347601 -0.01899999 0.3857176 -0.004988789 -0.01885437 0.3883154 -0.004219412 -0.01899999 0.388839 -0.004165172 -0.01899999 0.3887476 -0.003541827 -0.01899999 0.3876979 -0.006981492 -0.01872032 0.3935579 -0.00663197 -0.01879858 0.3936127 -0.006030857 -0.01885437 0.3909019 -0.006418049 -0.01884645 0.3936462 -0.006292521 -0.01887452 0.3936659 -0.005138218 -0.01899999 0.3911733 -0.00531727 -0.01899999 0.3917353 -0.005731999 -0.01899999 0.3937538 -0.008162736 -0.01761496 0.3933726 -0.008002579 -0.01792812 0.3933978 -0.007883548 -0.01804369 0.3934164 -0.007541239 -0.01837617 0.3934701 -0.007260382 -0.01838415 0.3920494 -0.00688976 -0.01838415 0.3906411 -0.00753057 -0.01838356 0.3934718 -0.007518827 -0.01839172 0.3934736 -0.00734353 -0.01851338 0.3935011 -0.007269918 -0.01856446 0.3935126 -0.007229447 -0.01858633 0.393519 -0.007121682 -0.01864457 0.3935359 -0.00700283 -0.01870882 0.3935545 -0.006017327 -0.01899999 0.4018589 -0.006127893 -0.01899999 0.4021692 -0.006333708 -0.01899999 0.4027469 -0.006401062 -0.01899999 0.4028515 -0.006741702 -0.01899999 0.4033803 -0.00573498 -0.01899999 0.3986881 -0.005768895 -0.01899999 0.3994662 -0.005815386 -0.01899999 0.4005333 -0.005816996 -0.01899999 0.4005704 -0.005853056 -0.01899999 0.4008023 -0.005958914 -0.01899999 0.401483 -0.005731999 -0.01899999 0.398146 -0.006486892 -0.01899802 0.4028067 -0.006706714 -0.01881563 0.398146 -0.007202029 -0.01861518 0.398146 -0.006882548 -0.01877856 0.3994285 -0.006111681 -0.01897829 0.3994547 -0.00649476 -0.0189014 0.398146 -0.006495237 -0.01890116 0.398146 -0.006399333 -0.01896297 0.401401 -0.006534993 -0.01891738 0.4007292 -0.006352841 -0.01898884 0.4020993 -0.007177889 -0.01886367 0.4024334 -0.007094264 -0.01881539 0.4018647 -0.007273972 -0.01863044 0.4006492 -0.007150053 -0.01873487 0.4012625 -0.007573723 -0.01838284 0.3994051 -0.007701516 -0.01824432 0.398146 -0.007810175 -0.01816362 0.398146 -0.007856547 -0.01810628 0.398146 -0.008283495 -0.017578 0.398146 0.007908344 -0.01804119 0.3934422 0.008561432 -0.01693242 0.3934002 0.008437931 -0.01723539 0.393589 0.008811235 -0.01627957 0.3946586 0.008714616 -0.01666492 0.3943856 0.008795797 -0.01634126 0.3946149 0.008942365 -0.01575666 0.3950292 0.008463621 -0.01274704 0.3880754 0.008502304 -0.01282715 0.388028 0.008966386 -0.0145592 0.3939676 0.008541107 -0.01290768 0.3879804 0.008772492 -0.01350921 0.3901718 0.008858919 -0.01388251 0.3915246 0.008886992 -0.01400387 0.3919646 0.008942186 -0.01424235 0.3928288 0.007975816 -0.01196801 0.388552 0.008161902 -0.0122652 0.3883702 0.007432699 -0.01138722 0.3889371 0.007712483 -0.01168644 0.3887387 0.008051276 -0.0119825 0.3881182 0.008141934 -0.01211738 0.3880548 0.008152067 -0.01215708 0.3881456 0.008534967 -0.01281261 0.3877362 0.008535385 -0.01282 0.3877446 0.008422434 -0.0125752 0.3878418 0.008318364 -0.01237976 0.3879315 0.007692396 -0.01158154 0.388514 0.007828712 -0.01165145 0.3882737 0.007685303 -0.01149964 0.3883512 0.008539676 -0.01288855 0.3878611 0.00853604 -0.01283091 0.3877571 -0.008826076 -0.001218557 0.3684176 -0.008810341 -0.001327753 0.3684439 0.006976723 -0.005548 0.3674207 0.007345259 -0.005007803 0.3676182 0.008898437 -4.88019e-4 0.3679001 2.3408e-7 -0.008891344 0.366101 -6.73011e-4 -0.008888304 0.3661022 -0.001981139 -0.008682072 0.3661859 -0.001852273 -0.008719205 0.3661708 0.003249168 -0.008280277 0.3663481 5.92609e-4 -0.008894026 0.3661 6.6545e-4 -0.008883893 0.366104 0.002917289 -0.008422851 0.3662907 0.001852512 -0.008719086 0.3661709 -0.001979291 0.008678138 0.3661875 -0.00187838 0.008713603 0.3661731 0 0.008913755 0.3660919 0 0.008913755 0.3660919 6.64551e-4 0.008866608 0.3661114 0.001258492 0.008824467 0.3661289 0.00184822 0.008701562 0.3661789 0.00237143 0.008592486 0.3662233 0.003251731 0.008283913 0.3663471 0.008829593 -0.001213908 0.3684356 0.008837044 -0.001167058 0.3684287 0.008875072 -8.14195e-4 0.3682399 0.008506417 -0.002623498 0.3683645 0.008588135 -0.002387404 0.3684247 0.008658111 -0.002085924 0.3684549 0.008759677 -0.001648783 0.3684986 0.008761167 -0.001642286 0.3684992 0.008882939 -7.4086e-4 0.3682007 0.008394777 -0.002946138 0.3682821 0.008227288 -0.003430247 0.3681585 0.007639765 -0.004575967 0.367776 0.007711291 -0.004471182 0.3678144 0.005547046 -0.006955802 0.3668762 0.006082475 -0.006516039 0.3670491 0.006550073 -0.006009876 0.3672434 0.003605365 -0.008127212 0.3664097 0.004102468 -0.007913589 0.3664957 0.005209088 -0.007233321 0.3667671 -0.003605008 -0.008127868 0.3664094 -0.003064155 -0.008370518 0.3663119 -0.005208849 -0.00723344 0.366767 -0.004449605 -0.007707655 0.3665779 -0.004214942 -0.007854223 0.3665195 -0.007635295 -0.004573464 0.3677761 -0.007042884 -0.005463778 0.3674524 -0.006551027 -0.006011426 0.3672429 -0.006518006 -0.006048142 0.3672288 -0.006186068 -0.006417751 0.3670874 -0.008779585 -0.00154078 0.368495 -0.008756458 -0.00164771 0.3684883 -0.008661091 -0.00208801 0.368461 -0.008630335 -0.002229869 0.3684521 -0.008399784 -0.002949297 0.3682847 -0.008318543 -0.003202617 0.3682258 -0.008009552 -0.003857374 0.3680147 -0.007760167 -0.004385769 0.3678444 -0.008871316 8.2978e-4 0.3682203 -0.008895218 5.74962e-4 0.3680421 -0.008897721 4.97461e-4 0.3679005 -0.008899152 -4.85067e-4 0.3679045 -0.008891522 -6.29493e-4 0.3680997 -0.008873999 -8.19903e-4 0.3682351 -0.00890845 -3.07979e-4 0.3676652 -0.008905589 2.53076e-4 0.3674539 -0.008913755 0 0.3567569 -0.008913755 0 0.3669915 -0.00891 -2.20158e-4 0.3674731 -0.008857011 -0.001004457 0.3683663 -0.008644759 0.002078175 0.3684293 -0.008756458 0.001646995 0.3684905 -0.008846879 0.00108993 0.3684023 -0.008827686 0.001215875 0.3684261 -0.008810579 0.001327931 0.3684473 -0.008769869 0.001595079 0.3684979 -0.006481826 0.006015896 0.3672378 -0.006513237 0.005980789 0.3672512 -0.007342338 0.005054235 0.3676046 -0.007605075 0.00455749 0.3677715 -0.007983326 0.003842353 0.3680118 -0.0083099 0.003225028 0.3682193 -0.008408427 0.002953946 0.3682932 -0.008441209 0.002863824 0.3683178 -0.004428923 0.007677614 0.3665892 -0.005169928 0.007182598 0.3667858 -0.005835771 0.006737887 0.3669624 -0.003599286 0.008108377 0.3664172 -0.003989279 0.007971286 0.3664726 0.00351268 0.00819242 0.3663838 0.00361222 0.008141934 0.3664041 0.004540503 0.00767064 0.3665929 0.007308721 0.005102694 0.3675864 0.006563365 0.006021499 0.36724 0.006499946 0.0060997 0.3672105 0.005638122 0.006904125 0.3668972 0.005553662 0.006963074 0.3668738 0.005193889 0.007214367 0.3667741 0.007978141 0.00397545 0.3679851 0.007626116 0.004568278 0.3677754 0.007359206 0.005017697 0.3676165 0.00890696 -3.49457e-4 0.3677353 0.008909404 -2.2503e-4 0.3674705 0.008913755 0 0.3669915 0.008911252 2.07838e-4 0.3674791 0.008827686 0.001218318 0.3684261 0.008808791 0.001363813 0.3684759 0.008753597 0.00164777 0.3684771 0.008911192 2.14609e-4 0.367495 0.008838653 0.00115472 0.367974 0.008899331 4.84224e-4 0.367906 0.008895635 5.68106e-4 0.3680338 0.008874475 8.19088e-4 0.3682378 0.008865177 9.29248e-4 0.3683273 0.008677601 0.00203818 0.3684789 0.008663058 0.00208795 0.3684689 0.008506417 0.002624034 0.3683609 0.008409857 0.002954483 0.3682944 0.008409798 0.002954721 0.3682944 -0.007826507 -0.01164871 0.3882751 -0.007683634 -0.01149755 0.3883522 -0.007690668 -0.01157969 0.3885152 -0.008149147 -0.01215285 0.3881483 -0.008535385 -0.01282 0.3877446 -0.008419156 -0.01256889 0.3878449 -0.008534967 -0.01281261 0.3877362 -0.008496284 -0.01283067 0.388027 -0.008541107 -0.01290768 0.3879804 -0.008539676 -0.01288831 0.3878605 -0.008162915 -0.01225829 0.3883735 -0.00853604 -0.01283079 0.387757 -0.008140742 -0.01211088 0.388057 -0.008059144 -0.01197671 0.3881191 -0.007992684 -0.01186734 0.3881698 -0.007443904 -0.01137673 0.3889403 -0.007484972 -0.01141458 0.3889142 -0.00771445 -0.01168084 0.3887411 -0.008060276 -0.01208215 0.3884801 0.008120357 0.0178399 0.399382 0.008128821 0.01782655 0.3993338 0.00871706 0.01732993 0.3998894 0.008438885 0.01730126 0.3975827 0.008492052 0.01719057 0.3972617 0.008330047 0.01750004 0.3981462 0.008227467 0.01767164 0.3987751 0.008641302 0.01685947 0.3962924 0.008572101 0.01702374 0.3967781 0.007826685 0.01827716 0.4009418 0.007894456 0.01817649 0.4005829 0.008024573 0.01798307 0.3998933 0.008170068 0.01817911 0.4016025 0.007796347 0.01834541 0.4012107 0.007835626 0.01855742 0.4022228 0.007823824 0.01855432 0.4021943 0.007822811 0.01855391 0.4021914 0.007799863 0.01854568 0.4021255 0.007796883 0.01854115 0.4021009 0.007744789 0.01846134 0.401667 0.007745742 0.01845926 0.4016589 0.007837653 0.01855796 0.4022276 0.008688032 -0.01081109 0.3850346 0.008800745 -0.009576559 0.3836289 0.008828699 -0.009838044 0.3833746 0.008974432 -0.007113099 0.3811386 0.008820116 -0.009364306 0.3833873 0.008837282 -0.009176909 0.3831738 0.008904099 -0.008342385 0.3823103 0.008909225 -0.008271694 0.3822396 0.008940637 -0.007713377 0.381709 0.008951544 -0.007519423 0.3815248 0.008948922 -0.007566094 0.3815691 0.008700489 -0.01159286 0.3854637 0.008650362 -0.01123708 0.3855746 0.008672058 -0.01099175 0.3852636 0.008562207 -0.01241773 0.3871831 0.008620381 -0.01157701 0.3860055 0.008642852 -0.01132255 0.385683 0.008610546 -0.0130937 0.3875452 0.008611261 -0.01309645 0.3875433 0.008611083 -0.01309758 0.3875425 0.008608818 -0.0132628 0.3878963 0.008610367 -0.01323992 0.3879011 0.008616149 -0.01315474 0.3879191 0.00888127 -0.01391983 0.3915151 0.008066296 0.004327654 0.3829547 0.008066296 0.008335649 0.3848043 0.008066296 0.01009744 0.3861434 0.008651137 0.01088988 0.3852443 0.008651137 -0.002425014 0.3813098 0.008651137 -4.51951e-5 0.3811303 0.008953928 -4.86908e-5 0.3798564 0.008999943 0.001555979 0.3791798 0.008999943 -5.1132e-5 0.3791266 0.008560538 0.01237791 0.3871031 0.008999943 0.005264818 0.3798798 0.008999943 0.005238234 0.3798734 0.008953928 0.005028307 0.3805837 0.008949875 -0.007516086 0.3815327 0.008066296 -0.01170122 0.3877871 0.008651137 -0.01095753 0.3853043 0.008066296 -0.0101602 0.386199 0.008651137 -0.009065449 0.3838497 0.008651137 -0.006982982 0.3826839 0.008999943 -0.002718567 0.3793345 0.008999943 -0.004080355 0.3795701 0.008953928 -0.005121588 0.3806116 0.008999943 -0.005330145 0.3799213 0.008999943 0.005900144 0.3800812 0.008651137 0.00898981 0.3838002 0.008823633 0.009286344 0.3833218 0.008904159 0.008342385 0.3823102 0.008942306 0.007752537 0.3817357 0.008944988 0.007711112 0.3816953 0.008651137 0.006901025 0.3826458 0.008949518 0.007561981 0.3815624 0.008953928 0.007434785 0.3814891 0.008953154 0.007442772 0.3814561 0.008687973 0.01081103 0.3850346 0.008751451 0.01013302 0.3842291 0.00879693 0.009599387 0.3836573 0.008066296 0.01164722 0.387723 0.00856316 0.01233237 0.3870369 0.00864619 0.01132065 0.3857052 0.008648753 0.01128911 0.3856638 0.008678138 0.01093143 0.385193 0.008999943 -3.32737e-4 0.3791173 0.008999943 -0.002217292 0.3792477 0.008953928 -0.002612531 0.3800498 0.008999943 0.003429055 0.3794351 0.008953928 0.00251621 0.3800356 0.008999943 0.002618253 0.3793246 0.008066296 -0.008405745 0.3848503 0.008066296 -4.19064e-5 0.3823288 0.008066296 -0.002248525 0.3824951 0.008066296 -0.004407942 0.3829787 0.008066296 0.006398856 0.3837339 0.008066296 -0.006474852 0.3837693 0.008651137 -0.004753887 0.3818312 0.008651137 0.002335548 0.3812967 0.008066296 0.002165615 0.382483 0.008651137 0.004667282 0.3818054 -0.008625686 -0.01324266 0.387899 -0.008625924 -0.01324063 0.3878994 -0.008869886 -0.01394766 0.3917623 -0.008969068 -0.0145598 0.3939681 -0.008990466 -0.01469177 0.3944435 -0.008867621 -0.01393359 0.3917117 -0.008832335 -0.01371616 0.390928 -0.008625924 -0.01324063 0.3878994 -0.008610844 -0.01309937 0.3875413 -0.008611261 -0.01309657 0.3875433 -0.008557319 -0.01242762 0.3871744 -0.008942127 -0.00775516 0.3817383 -0.008903861 -0.008345842 0.3823137 -0.008819043 -0.009340047 0.3833794 -0.008826494 -0.009867668 0.383402 -0.008945167 -0.007708191 0.3816925 -0.008949577 -0.007561862 0.3815621 -0.008951485 -0.007499814 0.3815068 -0.008699655 -0.01160728 0.3854764 -0.008796691 -0.00960201 0.3836602 -0.008751213 -0.01013541 0.3842319 -0.008687794 -0.01081293 0.3850369 -0.008674144 -0.0109806 0.385258 -0.008648693 -0.01129209 0.3856688 -0.008646309 -0.01132136 0.3857075 -0.008560597 -0.01237124 0.3870921 -0.008812069 -0.0162791 0.3946588 -0.008793711 -0.01633971 0.3946152 -0.008495569 -0.01714509 0.3935265 -0.008453667 -0.01723492 0.393584 -0.008620679 -0.01691031 0.3942054 -0.008330106 -0.01749998 0.3937538 -0.008903324 -0.01597815 0.3948749 -0.00884664 0.009075284 0.3830624 -0.008821606 0.009349524 0.383374 -0.008651137 0.009051382 0.3838405 -0.008798539 0.009601354 0.3836601 -0.008687794 0.01081287 0.385037 -0.008651137 0.006961345 0.3826737 -0.008933603 0.00774306 0.3817508 -0.008903861 0.008345782 0.3823137 -0.008651137 -0.009051382 0.3838405 -0.008651137 -0.006961345 0.3826737 -0.008953928 -0.007499754 0.3815193 -0.008066296 -0.01015347 0.386193 -0.008651137 -0.01095026 0.3852978 -0.008066296 -0.008392751 0.3848417 -0.008066296 -0.01169973 0.3877853 -0.008563578 0.01241326 0.387183 -0.008066296 0.01169973 0.3877853 -0.008672177 0.0109871 0.3852553 -0.008651137 0.01095026 0.3852978 -0.008651077 0.01122266 0.3855506 -0.008066296 0.01015347 0.386193 -0.008639872 0.0113483 0.3857081 -0.008640766 0.01133769 0.3856948 -0.008999943 0.002676486 0.3793272 -0.008999943 0.004080414 0.3795702 -0.008953928 0.00508964 0.380602 -0.008999943 0.005296707 0.3799117 -0.008999943 0.005900204 0.3800812 -0.008953928 0 0.3798564 -0.008999943 4.62621e-7 0.3791282 -0.008999943 3.32786e-4 0.3791173 -0.008999943 -0.001555979 0.3791798 -0.008953928 -0.00257194 0.3800438 -0.008999943 -0.002676367 0.3793325 -0.008953928 -0.00508964 0.380602 -0.008999943 -0.005264759 0.3798798 -0.008999943 -0.003429055 0.3794351 -0.008992314 0.006551444 0.3806377 -0.00894618 0.007487475 0.381512 -0.008941173 0.007588803 0.3816066 -0.008651137 -0.004724204 0.3818224 -0.008651137 -0.002387285 0.3813042 -0.008651137 0 0.3811302 -0.008651137 0.002387285 0.3813042 -0.008066296 0.008392751 0.3848417 -0.008066296 -0.004380464 0.3829704 -0.008066296 -0.002213597 0.38249 -0.008066296 0 0.3823287 -0.008066296 0.002213597 0.38249 -0.008066296 0.004380464 0.3829704 -0.008066296 -0.006454765 0.3837599 -0.008066296 0.006454765 0.3837599 -0.008651137 0.004724204 0.3818224 -0.008953928 0.00257194 0.3800438 -0.008999943 0.002217352 0.3792477 -0.007242679 0 0.3833569 -0.000999987 0.01899999 0.4016627 -0.000999987 0.01719999 0.4016627 2.41729e-4 0.01899999 0.4016035 3.49919e-5 0.0170449 0.4016001 0.000999987 0.01899999 0.4016627 0.000999987 0.01719999 0.4016627 -9.30514e-4 0.01688981 0.4016544 -9.04677e-4 0.01677453 0.4016513 -6.75408e-4 0.01647859 0.4016291 6.5904e-4 0.01647031 0.4016283 8.31973e-4 0.01664507 0.4016433 9.26842e-4 0.01687455 0.4016542 -6.36625e-4 0.01642853 0.4016253 -2.54071e-4 0.01623463 0.4016042 -2.45828e-4 0.01623046 0.4016038 5.63043e-4 0.01637333 0.4016199 2.3329e-4 0.01623642 0.4016043 1.88059e-4 0.01621764 0.4016022 9.81118e-4 0.01700586 0.4016604 0.009614467 0.01889109 0.406962 0.006993889 0.01899898 0.4156493 0.006938755 0.01899999 0.4155937 0.007411003 0.01899999 0.4149652 0.008081853 0.01889109 0.4037621 0.007420778 0.01889109 0.402942 0.007447421 0.01887577 0.402918 0.006861865 0.01899313 0.4034433 0.007417559 0.01899999 0.4042427 0.006824672 0.01899993 0.4034767 0.007528066 0.01888149 0.4161882 0.007503569 0.01888686 0.4161635 0.008075416 0.01889109 0.4154468 0.008986949 0.01889109 0.4139165 0.009611606 0.01889109 0.4122485 0.009930431 0.01889109 0.4087148 0.009929478 0.01889109 0.410496 0.008991658 0.01889109 0.4052933 0.007687866 0.01899999 0.4145968 0.008256494 0.01899999 0.4135651 0.008330345 0.01899999 0.4134311 0.008797407 0.01899999 0.4121842 0.008829951 0.01899999 0.4120337 0.0090788 0.01899999 0.4108833 0.009110093 0.01899999 0.4104225 0.009168922 0.01899999 0.409556 0.008827745 0.01899999 0.4071772 0.009066045 0.01899999 0.4082295 0.009109318 0.01899999 0.4087878 0.008772075 0.01899999 0.4069311 0.008292973 0.01899999 0.4056887 0.00826615 0.01899999 0.4056411 0.007639169 0.01899999 0.404529 0.006113111 0.01899999 0.4147604 -0.002830564 0.01899999 0.4170826 -0.002546727 0.01899999 0.4171654 0.005240023 0.01899999 0.4156451 -0.004805803 0.01899999 0.4159864 -0.005821883 0.01899999 0.4150869 -0.006156146 0.01899999 0.4147089 -0.004902482 0.01899999 0.4159218 0.004741787 0.01899999 0.4160133 0.004239499 0.01899999 0.4163845 0.003137648 0.01899999 0.416959 0.002480328 0.01899999 0.4171808 0.001960694 0.01899999 0.417356 8.38555e-4 0.01899999 0.4175561 -0.001637041 0.01899999 0.4174307 -4.04983e-4 0.01899999 0.4175898 -3.40884e-5 0.01899999 0.4175797 -0.003956556 0.01899999 0.4165532 -0.007593095 0.01887774 0.4161327 -0.00755912 0.01888543 0.4160991 -0.007057845 0.01899844 0.4156024 -0.006989419 0.01899999 0.4155346 -0.008984386 0.01889109 0.4052782 -0.008078157 0.01889109 0.403757 -0.007447838 0.0188775 0.4029176 -0.007430851 0.01888734 0.4029328 -0.007420539 0.01888924 0.4029421 -0.006861746 0.01899307 0.4034435 -0.008122086 0.01889109 0.4153818 -0.007450759 0.01899999 0.4149036 -0.009607195 0.01889109 0.4069356 -0.009927034 0.01889109 0.4086772 -0.00993371 0.01889109 0.4104478 -0.009627044 0.01889109 0.4121917 -0.009016752 0.01889109 0.4138538 -0.008222639 0.01899999 0.4055429 -0.00754857 0.01899999 0.4043951 -0.007420837 0.01899999 0.404233 -0.006824672 0.01899999 0.4034767 -0.008257091 0.01899999 0.4056276 -0.008723556 0.01899999 0.4067765 -0.008816182 0.01899999 0.4071545 -0.009040355 0.01899999 0.4080691 -0.009105622 0.01899999 0.4087536 -0.009166657 0.01899999 0.4093934 -0.009117305 0.01899999 0.4103788 -0.009100079 0.01899999 0.4107224 -0.008841693 0.01899999 0.4120284 -0.008396744 0.01899999 0.4132834 -0.008279502 0.01899999 0.4135053 -0.007774829 0.01899999 0.4144604 -0.006486892 0.01899802 0.4028067 -0.006352841 0.01898884 0.4020993 -0.006377995 0.01899999 0.4028334 -0.006393909 0.01899999 0.4028563 -0.006399333 0.01896297 0.401401 -0.006055712 0.01899999 0.4020053 -0.006120383 0.01899999 0.4021713 -0.005829274 0.01899999 0.4005206 -0.005846142 0.01899999 0.4008039 -0.006534993 0.01891738 0.4007292 -0.005852699 0.01899999 0.4009143 -0.005958437 0.01899999 0.4014823 -0.005740225 0.01899999 0.3990225 -0.00576663 0.01899999 0.3994662 -0.006111681 0.01897829 0.3994547 -0.006882548 0.01877856 0.3994285 -0.005731999 0.01899999 0.398146 -0.006490409 0.01887232 0.398146 -0.006714344 0.01883459 0.398146 -0.007204055 0.01854979 0.398146 -0.00770992 0.01825565 0.398146 -0.007273972 0.01863044 0.4006492 -0.007573723 0.01838284 0.3994051 -0.007842242 0.01809442 0.398146 -0.007094264 0.01881539 0.4018647 -0.007177889 0.01886367 0.4024334 -0.007150053 0.01873487 0.4012625 -0.007668197 -0.004887402 0.3690664 0.00653994 -0.006317377 0.368533 0.007668375 -0.004887163 0.3690665 0.008930623 0 0.3676608 0.005155324 -0.007488965 0.3680679 0.003561913 -0.008363962 0.3677097 0.001819789 -0.008906066 0.3674841 0 -0.009089827 0.367407 -0.00181961 -0.008906126 0.367484 -0.003561735 -0.008364081 0.3677096 -0.005155086 -0.007489144 0.3680679 -0.006539702 -0.006317555 0.368533 -0.008930623 0 0.3676609 0.006887733 0.006065845 0.3690016 0.006585597 0.006477832 0.3689644 0.006539285 0.006314933 0.3685253 -0.001303553 0.00950098 0.3686389 -0.001853227 0.00936973 0.368654 -0.00181955 0.00890392 0.3674762 -0.005154788 0.007486701 0.3680601 0 0.009087681 0.3673992 0.008930623 0 0.3676608 0.008933424 1.70426e-4 0.3681863 0.008931159 2.10368e-4 0.368221 0.008436858 0.003113508 0.369174 0.008694171 0.002149462 0.3691248 0.008700609 0.002125322 0.3691236 0.008781731 0.001652717 0.3690227 0.008839011 0.00131911 0.3689514 0.008857011 0.001148879 0.3688703 0.008901774 7.25186e-4 0.3686684 0.008905827 6.54274e-4 0.3686068 0.007739961 0.004731714 0.3691087 0.008425056 0.003157615 0.3691762 0.008258044 0.003584861 0.3691627 0.007989525 0.004271745 0.369141 0.007667303 0.004884779 0.3690588 0.005155026 0.007486581 0.3680601 0.003561794 0.008361697 0.3677019 0.001819789 0.008903861 0.3674762 -0.003561615 0.008361816 0.3677018 -0.006539106 0.006315112 0.3685252 -0.007667124 0.004885017 0.3690587 -0.007738769 0.004731833 0.3691083 -0.008060276 0.004115045 0.3691493 -0.008256316 0.003583669 0.3691608 -0.008430659 0.003111064 0.369171 -0.008488535 0.002954244 0.3691744 -0.008783817 0.001653611 0.369027 -0.008745551 0.001901268 0.3690922 -0.008685111 0.002148926 0.3691115 -0.008859634 0.001144349 0.3688795 -0.008855402 0.001190125 0.3689051 -0.008905351 6.51959e-4 0.3686037 -0.00891298 5.70375e-4 0.368558 -0.008928537 2.24945e-4 0.3682097 -0.006583631 0.006463766 0.3689653 -0.00670731 0.006331443 0.3689785 -0.006891548 0.006070375 0.3690016 -0.007463335 0.005260288 0.3690731 -0.007656812 0.00488907 0.3690978 -0.00584048 0.00725913 0.3688859 -0.004783749 0.008105874 0.3687953 -0.004946351 0.007975637 0.3688092 -0.00521171 0.007762968 0.368832 -0.0037207 0.008728504 0.3687265 -0.002548933 0.009203612 0.368673 -0.002584874 0.009189069 0.3686746 -0.003625154 0.008767247 0.3687221 -4.93604e-5 0.009603917 0.368627 0.002449691 0.009234786 0.3686695 0.001853764 0.009369611 0.368654 0.001208901 0.009515464 0.3686372 0 0.00960046 0.3686274 0.005215704 0.00776726 0.3688317 0.004947543 0.007976531 0.3688092 0.004768013 0.008116602 0.3687941 0.003630697 0.008772373 0.3687216 0.002583146 0.009182572 0.3686753 0.005683183 0.00740242 0.3688709 0.007655382 0.00488758 0.3690978 0.007381379 0.00539267 0.3690624 0.008667051 0.01178866 0.3853226 0.008707523 0.01123654 0.3846651 0.008699715 0.01160591 0.3854746 0.008782327 0.0103119 0.383701 0.008826673 0.009865045 0.383399 0.008595585 0.01309525 0.3875437 0.008595287 0.013098 0.3875418 0.008602857 0.01266443 0.3863655 0.008563995 0.0133835 0.3873449 0.008603513 0.01302289 0.3875936 0.008945286 0.007906377 0.3815575 0.008940517 0.007993876 0.381629 0.008810579 0.009921908 0.3833429 0.008877992 0.008992016 0.3824892 0.008910119 0.008549034 0.3820826 0.008953511 0.007755339 0.3814341 0.008563041 0.01341331 0.3873898 0.008625686 0.01324266 0.387899 0.008625924 0.01324057 0.3878994 0.00856781 0.01352095 0.3876018 0.008587002 0.01358419 0.3878285 0.008623301 0.0132637 0.3878946 0.00888735 0.01400536 0.3919701 0.00888133 0.01392036 0.3915153 0.008858919 0.01388251 0.3915249 0.008772432 0.01350903 0.3901718 0.008999943 0.01499992 0.3955515 0.008999288 0.01500093 0.3953346 0.008966386 0.0145592 0.3939676 0.008948028 0.01448708 0.3927742 0.008942186 0.01424235 0.3928288 0.008939266 0.01445865 0.3926196 0.008872866 0.01424264 0.3914445 0.008794903 0.01398897 0.3900645 10e-4 0.0188474 0.3846241 9.99998e-4 0.0185697 0.3839785 0.000999987 0.01719999 0.3816499 0.000999987 0.01899999 0.3855825 0.000999987 0.01899743 0.3854528 0.000999987 0.01887422 0.3846864 2.31335e-4 0.01625192 0.380657 0 0.01619994 0.380657 0 0.01619911 0.3805859 4.51262e-4 0.01621836 0.3798967 8.26146e-4 0.01663649 0.380657 7.72986e-4 0.01656556 0.380657 6.57679e-4 0.01647555 0.380657 4.63232e-4 0.0163238 0.380657 4.2773e-4 0.01629608 0.380657 0 0.01608502 0.3798347 0 0.01578599 0.3791364 1.85692e-7 0.01578617 0.3791367 3.77162e-4 0.01613569 0.3797463 4.2544e-4 0.01618957 0.3798443 0 0.01608961 0.379865 -2.54901e-4 0.01623302 0.380657 0 0.01608961 0.379865 -4.16622e-4 0.01619029 0.3798539 -4.41476e-4 0.01621443 0.3798967 -4.52397e-4 0.01634246 0.380657 -6.626e-4 0.016429 0.3802776 -6.84842e-4 0.01647126 0.380657 -8.26136e-4 0.01663649 0.380657 -9.29391e-4 0.01689302 0.3811137 -0.000999987 0.01719999 0.3816499 -9.86253e-4 0.01703423 0.3813652 9.07535e-4 0.01677978 0.3809162 9.27772e-4 0.01687175 0.3810768 -0.008616149 0.01315474 0.3879191 -0.008629977 0.01311236 0.3887287 -0.008610367 0.01323992 0.3879011 -0.008877694 0.01393377 0.3917132 -0.008901715 0.01401346 0.3920027 -0.008881688 0.01394718 0.3917618 -0.008887052 0.01428711 0.3916864 -0.008715391 0.0138154 0.3891087 -0.008587002 0.01358419 0.3878285 -0.008930146 0.01440536 0.3923326 -0.008936285 0.01445806 0.3926179 -0.008956193 0.0145604 0.3939698 -0.008999943 0.01500004 0.3955509 -0.00856769 0.01352047 0.3876006 -0.008610367 0.01323992 0.3879011 -0.008595287 0.01309627 0.387543 -0.008595407 0.0130952 0.3875437 -0.008603334 0.01302236 0.387594 -0.008563995 0.0133835 0.3873449 -0.008563041 0.01341313 0.3873896 -0.008699595 0.01160728 0.3854764 -0.008826494 0.009867668 0.383402 -0.008663654 0.01180315 0.3853133 -0.008646309 0.0120269 0.3855695 -0.008880257 0.008984386 0.3824689 -0.008839905 0.009571552 0.3829898 -0.008811831 0.00992465 0.3833451 -0.008707284 0.01123881 0.3846672 -0.00890994 0.00855267 0.3820859 -0.008933484 0.008015215 0.3816658 -0.00893861 0.007897675 0.381574 -0.008990466 0.006714403 0.3806493 0.001976966 0.01477807 0.3778563 0.001496493 0.01508373 0.3781926 0.001489102 0.01203823 0.3730216 0.001767754 0.01207637 0.3731757 0.002305269 0.01222801 0.3736799 0.002650082 0.01241564 0.3741936 0.002590656 0.01238328 0.374105 0.002585828 0.01238065 0.3740979 0 0.01194113 0.3726 1.86122e-7 0.01194113 0.3726 3.93082e-4 0.0119462 0.3726255 0.001117587 0.01198738 0.372816 -0.001095652 0.01198542 0.3728073 -3.72472e-4 0.01194566 0.3726229 -7.52765e-5 0.01194131 0.3726009 -2.35745e-5 0.01194119 0.3726001 -4.7295e-6 0.01194113 0.3726 0 0.01194113 0.3726 -0.002586364 0.01238572 0.3741078 -0.002585351 0.01238518 0.3741063 -0.002275347 0.01221638 0.3736445 -0.001726508 0.01206845 0.3731461 -0.001490592 0.01203739 0.3730194 -0.002671122 0.01243191 0.3742341 -0.002925455 0.01274693 0.3749337 -0.002590596 0.01414197 0.3770948 -0.00263518 0.01409065 0.3770321 -0.002908289 0.01357769 0.3763345 -0.002999961 0.01310867 0.3756 -0.00258547 0.01414787 0.377102 -0.002210676 0.01457947 0.3776289 -0.001104593 0.01526761 0.3783892 -0.001491308 0.01507443 0.3781818 -0.00171411 0.01496309 0.3780623 2.61577e-7 0.01545727 0.3785864 -5.62131e-4 0.01536238 0.3785468 -4.71406e-4 0.0154345 0.3785631 0.001440048 0.01511961 0.3782321 8.07754e-4 0.01536333 0.3784893 1.7481e-4 0.01546567 0.378595 6.63362e-7 0.01545727 0.3785864 0.002910256 0.01271575 0.3748705 0.002999961 0.01310867 0.3756 0.002983987 0.01329791 0.3759106 0.002802252 0.01381456 0.3766672 0.002585589 0.0141313 0.3770754 0.002578139 0.01414221 0.3770894 0.00244677 0.01433426 0.3773369 -0.008943378 0.01574999 0.395034 -0.007779002 0.01803976 0.3935987 -0.008669793 0.0162881 0.3946967 -0.008688867 0.01625049 0.3947202 -9.99994e-4 0.01856958 0.3839784 -10e-4 0.01899999 0.3855825 -0.000999987 0.01890349 0.384795 -0.000999987 0.01883983 0.3846278 -0.000999987 0.01864224 0.3841091 -0.007639169 0.01810532 0.3936093 -0.006540656 0.01862066 0.3936926 -0.005731999 0.01899999 0.3937538 -0.007452666 0.01819282 0.3936234 -0.006600797 0.01859241 0.393688 -0.008099257 0.01754093 0.3934836 -0.007933795 0.0176413 0.3918978 -0.001522064 0.01885437 0.3847905 -0.00117588 0.01899999 0.3856623 -0.002480804 0.01899999 0.3864686 -0.002682566 0.01899999 0.3866841 -0.003342032 0.01885437 0.3860192 -0.005527138 0.01899999 0.3926268 -0.005140602 0.01899993 0.3911717 -0.005571186 0.01885437 0.3895868 -0.004988729 0.01885437 0.3883154 -0.00415486 0.01899999 0.3887524 -0.004542529 0.01899999 0.3895114 -0.004705071 0.01899999 0.3899324 -0.006030797 0.01885437 0.390902 -0.005046129 0.01899993 0.3908159 -0.004258096 0.01885437 0.387112 -0.003206312 0.01899999 0.3872437 -0.003485858 0.01899999 0.3876558 -0.003926336 0.01899999 0.3883051 -0.00219345 0.01885437 0.385121 -0.001724183 0.01899999 0.3859142 -0.00279951 0.01885437 0.3855379 -0.001713812 0.01899999 0.3859065 -0.001768767 0.01853144 0.3841758 -0.002063572 0.01851683 0.3842515 -0.002575874 0.01847243 0.3844804 -0.00258094 0.01847201 0.3844826 -0.003116726 0.01842558 0.3847219 -0.003333568 0.01839834 0.3848628 -0.003459215 0.01838254 0.3849445 -0.005079448 0.01813459 0.3862261 -0.00494939 0.01815676 0.3861115 -0.004991769 0.01838415 0.3865948 -0.003973662 0.01838415 0.3853814 -0.004090726 0.01830309 0.3853548 -0.004036247 0.01830995 0.3853195 -0.005783736 0.01838415 0.3878986 -0.00596261 0.017937 0.3872476 -0.00524497 0.01809757 0.3864176 -0.006943583 0.01764017 0.3887798 -0.006898343 0.01765763 0.3886893 -0.006404817 0.01838415 0.3892539 -0.006834506 0.01768237 0.3885615 -0.006238043 0.01785659 0.3876626 -0.007052063 0.01759821 0.388997 -0.007045924 0.0176413 0.3889979 -0.007586896 0.01739138 0.3900676 -0.007550239 0.0176413 0.3904406 -0.007707238 0.01732826 0.3903936 -0.008164882 0.01708829 0.3916338 -0.008216917 0.01704937 0.3918344 -0.008258879 0.01701796 0.3919962 -0.008598029 0.0167641 0.3933044 -0.0068897 0.01838415 0.3906412 -0.007260382 0.01838415 0.3920494 -0.008896887 0.01590991 0.394419 -0.008898019 0.01589983 0.3944315 -0.008922636 0.01568263 0.3947017 0.008936107 0.01568394 0.3947025 0.002164423 0.01850962 0.3842874 0.001767873 0.01853114 0.3841769 0.001156389 0.01856422 0.3840064 0.002581834 0.01847249 0.3844795 0.002576828 0.01847296 0.3844771 0.004031717 0.01830887 0.385326 0.003459751 0.01838237 0.3849456 0.003156363 0.01842141 0.3847439 0.003333866 0.01839858 0.3848619 0.004949212 0.01815652 0.3861129 0.004187822 0.01828885 0.3854298 0.006240904 0.01785695 0.3876604 0.006020784 0.01792204 0.3873245 0.006857156 0.01767468 0.3886008 0.005245804 0.01809775 0.3864166 0.005108654 0.01812887 0.3862559 0.008213102 0.01704919 0.3918353 0.008137762 0.01710504 0.3915477 0.007705569 0.01732814 0.3903942 0.007559299 0.01740366 0.3900037 0.007054686 0.01759845 0.3889955 0.006946682 0.01764011 0.3887798 0.006900489 0.01765793 0.3886874 0.008255898 0.01701754 0.3919986 0.008598029 0.0167641 0.3933044 0.008704483 0.01652264 0.3936282 0.008887648 0.01589679 0.394432 0.008929669 0.0157532 0.3946165 0.006236016 0.01899999 0.4025318 0.006129682 0.01899999 0.4021708 0.005954861 0.01899999 0.4015772 0.006411969 0.01899999 0.4028465 0.006629943 0.01899999 0.4032365 0.00576961 0.01899999 0.3994663 0.00579214 0.01899999 0.4002599 0.005825996 0.01899999 0.4005339 0.001175105 0.01899999 0.3856636 0.005859076 0.01899999 0.400802 0.005943536 0.01899999 0.4014854 0.004531621 0.01899999 0.3894847 0.004703998 0.01899999 0.3899326 0.005486547 0.01899999 0.3924397 0.005731999 0.01899999 0.3937538 0.005731999 0.01899999 0.398146 0.00505954 0.01899999 0.3908568 0.005144178 0.01899999 0.3911706 0.001722872 0.01899999 0.3859174 0.00176829 0.01899999 0.3859385 0.002473354 0.01899999 0.3864615 0.002682447 0.01899999 0.3866841 0.003193557 0.01899999 0.3872282 0.003489315 0.01899999 0.3876535 0.003832519 0.01899999 0.3881471 0.004150152 0.01899999 0.3887549 0.001522064 0.01885432 0.3847903 0.00219351 0.01885432 0.3851206 0.007045865 0.01764118 0.3889977 0.007260501 0.01838403 0.3920493 0.007317662 0.01852864 0.3935052 0.00688982 0.01838403 0.390641 0.007285714 0.01855474 0.3935102 0.00722754 0.01859003 0.3935193 0.007129132 0.01863247 0.3935347 0.006909132 0.01872742 0.3935692 0.006031036 0.01885432 0.3909018 0.006643295 0.0188421 0.3936109 0.006639897 0.01884359 0.3936114 0.007870316 0.01807731 0.3934185 0.007582485 0.01831233 0.3934636 0.007516741 0.01836603 0.3934739 0.007933855 0.01764118 0.3918977 0.008018434 0.01787608 0.3933953 0.007894396 0.01804453 0.3934147 0.008403062 0.01724892 0.3933349 0.008310317 0.01747941 0.3933495 0.008198976 0.01763069 0.3933669 0.007550239 0.01764118 0.3904404 0.006404876 0.01838403 0.3892537 0.005783796 0.01838403 0.3878984 0.004991888 0.01838403 0.3865945 0.003973722 0.01838403 0.3853811 0.00279957 0.01885432 0.3855377 0.003342151 0.01885432 0.3860189 0.004258275 0.01885432 0.3871116 0.005571305 0.01885432 0.3895865 0.004988908 0.01885432 0.3883152 0.006542325 0.01888567 0.3936268 0.006517708 0.01888948 0.3936306 0.005809903 0.01899892 0.3937416 0.008903384 0.01597803 0.3948753 0.008495569 0.01714509 0.3935265 0.008620679 0.01691025 0.3942055 0.008330106 0.01749998 0.3937538 0.008453667 0.01723492 0.3935841 0.008793652 0.01633983 0.3946154 0.008812069 0.01627904 0.394659 0.007010638 0.01871389 0.398146 0.007214426 0.0185725 0.398146 0.006882667 0.01877856 0.3994285 0.006479918 0.01883262 0.398146 0.006111741 0.01897829 0.3994546 0.007177889 0.01886367 0.4024333 0.007094323 0.01881533 0.4018646 0.007274091 0.01863032 0.4006491 0.007149994 0.01873487 0.4012625 0.007573783 0.01838278 0.399405 0.006352901 0.01898878 0.4020993 0.006399214 0.01896297 0.4014009 0.006486952 0.01899802 0.4028066 0.00670278 0.01878273 0.398146 0.006535112 0.01891732 0.4007291 0.007857739 0.01810729 0.3981461 0.007825493 0.01814877 0.398146 0.007697403 0.01823759 0.398146 0.007232129 0.01859802 0.3937538 0.00650388 0.01886999 0.3937538 0.006714344 0.01883459 0.3937538 0 -0.008499979 0.3786 0.00149995 -0.008499979 0.3781981 0.002598047 -0.008499979 0.3771 0.002999961 -0.008499979 0.3756 -0.002598047 -0.008499979 0.3741 0.002598047 -0.008499979 0.3741 0.00149995 -0.008499979 0.3730019 0 -0.008499979 0.3726 -0.00149995 -0.008499979 0.3730019 -0.00149995 -0.008499979 0.3781981 -0.002598047 -0.008499979 0.3771 -0.002999961 -0.008499979 0.3756 -0.007232129 -0.01859796 0.3937538 -0.007688701 -0.01822936 0.3937538 -0.007928907 -0.01802933 0.3935182 -0.007955551 -0.01801395 0.3937538 -0.006707072 -0.01881706 0.3937541 -0.006523072 -0.01889377 0.3937542 -0.006362378 -0.01891642 0.3937541 -0.005770385 -0.01899975 0.3937539 0.007277429 0.01857131 0.3937538 0.007697761 0.01824021 0.3937538 0.007870018 0.01810449 0.3937539 0.007945001 0.01800596 0.3937538 0.007907807 0.01804149 0.3934405 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.2393146 0.9709402 0.001896262 -0.1160919 0.9932326 -0.003410696 -0.2393156 0.9709399 0.001896262 -0.3420177 0.9396859 -0.00379008 -0.3919665 0.9199791 7.58312e-4 -0.3919622 0.919981 7.58312e-4 -0.5495088 0.8354872 -0.001136183 -0.534463 0.845185 -0.003408193 -0.7746042 0.632445 0.001327157 -0.7746042 0.632445 0.001327157 -0.7273678 0.6862362 -0.003979802 -0.6631217 0.7485096 0.00170654 -0.6631217 0.7485096 0.00170654 -0.8660235 0.4999989 -0.002083539 -0.8660236 0.4999988 -0.002083599 -0.9350158 0.3546037 0.001327157 -0.9350154 0.3546044 0.001327157 -0.957982 0.2868009 -0.003979861 -0.9797891 0.200026 0.00170648 -0.9797896 0.2000238 0.00170648 -0.9983041 0.05814474 -0.00284183 -0.9991885 0.04026603 -9.47381e-4 -0.9848008 -0.1736468 -0.00379008 -0.9927086 -0.1205369 7.58246e-4 -0.9927091 -0.1205329 7.58246e-4 -0.9182108 -0.3960776 -0.003410696 -0.9605164 -0.278217 0.001896321 -0.9605163 -0.2782176 0.001896321 -0.8021184 -0.5971552 -0.003410756 -0.8229838 -0.5680649 0 -0.9034506 -0.4286923 0 -0.6427831 -0.7660389 -0.00379008 -0.721201 -0.6927233 0.001896262 -0.7212015 -0.6927227 0.001896262 -0.316667 -0.9485352 0.00170654 -0.4647206 -0.8854508 -0.003408253 -0.4487987 -0.8936321 -0.001136183 -0.6007428 -0.7994419 7.58287e-4 -0.6007421 -0.7994426 7.58287e-4 -0.3166679 -0.948535 0.00170654 -0.2306142 -0.9730371 -0.003979861 -0.160411 -0.9870494 0.001327157 -0.1604098 -0.9870496 0.001327157 0 -0.9999979 -0.002083539 0 -0.9999979 -0.002083539 0.316667 -0.9485352 0.00170654 0.3166679 -0.9485349 0.00170654 0.2306141 -0.9730372 -0.003979861 0.160411 -0.9870494 0.001327157 0.1604098 -0.9870496 0.001327157 0.4647206 -0.8854508 -0.003408253 0.4487987 -0.8936321 -0.001136183 0.6007428 -0.7994419 7.58287e-4 0.6007421 -0.7994425 7.58287e-4 0.6427831 -0.7660388 -0.00379014 0.721201 -0.6927233 0.001896262 0.7212015 -0.6927227 0.001896262 0.8021184 -0.5971552 -0.003410756 0.8229838 -0.5680649 0 0.9034506 -0.4286923 0 0.9182108 -0.3960775 -0.003410696 0.9605164 -0.278217 0.001896321 0.9605163 -0.2782176 0.001896321 0.9848008 -0.1736468 -0.00379008 0.9927086 -0.1205369 7.58246e-4 0.9983041 0.05814474 -0.00284183 0.9991885 0.04026603 -9.47381e-4 0.9927091 -0.1205329 7.58246e-4 0.957982 0.2868009 -0.003979861 0.9797891 0.200026 0.00170648 0.9797896 0.2000238 0.00170648 0.7746042 0.632445 0.001327157 0.8660235 0.4999989 -0.002083539 0.8660236 0.4999988 -0.002083599 0.9350158 0.3546037 0.001327157 0.9350155 0.3546044 0.001327157 0.7746042 0.632445 0.001327157 0.7273678 0.6862362 -0.003979802 0.6631217 0.7485096 0.00170654 0.5495087 0.8354872 -0.001136183 0.5344631 0.845185 -0.003408193 0.6631217 0.7485096 0.00170654 0.3420177 0.9396858 -0.00379008 0.3919665 0.9199792 7.58313e-4 0.3919622 0.919981 7.58312e-4 -0.0804665 0.9967573 0 0.0804665 0.9967573 0 0.1160919 0.9932326 -0.003410696 0.2393146 0.9709402 0.001896262 0.2393156 0.97094 0.001896262 0.3899208 0.9151753 -0.1020591 0.7705597 0.629143 -0.102063 0.1595738 -0.9818956 -0.1020655 -0.8186862 -0.5650983 -0.102063 -0.993971 0.04005521 -0.102065 -0.6596598 0.7446022 -0.1020619 0.5107645 0.2948899 -0.807564 0.48538 -0.3350336 -0.8075634 -0.1411437 0.5726425 -0.8075637 0.0499826 0.202788 -0.9779462 0.1384986 0.1563325 -0.977946 0.208688 0.008409857 -0.9779461 0.2006115 -0.05810797 -0.977946 0.1254698 -0.16697 -0.977946 0.09706109 -0.1849344 -0.977946 0.03350317 -0.2061535 -0.9779459 0 -0.2088583 -0.9779459 -0.09706115 -0.1849346 -0.977946 -0.1718864 -0.1186447 -0.9779462 -0.2073348 -0.02517503 -0.9779461 -0.2086879 0.008409857 -0.9779461 -0.1952853 0.07406193 -0.9779461 -0.1808769 0.1044294 -0.9779459 -0.1384986 0.1563326 -0.977946 -0.08186477 0.1921463 -0.9779459 -0.0499829 0.2027883 -0.9779462 -0.0499829 0.2027886 -0.9779461 -0.0499826 0.202788 -0.9779462 -0.01680594 0.2081797 -0.9779462 -0.1116276 0.1765248 -0.977946 -0.1384986 0.1563325 -0.977946 -0.1617825 0.1320914 -0.977946 -0.1254696 -0.1669698 -0.9779461 -0.03350329 -0.2061542 -0.9779458 0.1718866 -0.1186448 -0.9779461 0.1718864 -0.1186446 -0.9779461 0.1506287 -0.1446807 -0.9779461 0.2006112 -0.05810773 -0.9779462 0.2073353 -0.02517509 -0.977946 0.195286 0.07406216 -0.9779459 0.1952864 0.07406216 -0.9779458 0.1808769 0.1044293 -0.9779458 0.1808764 0.1044291 -0.9779461 0.1617825 0.1320914 -0.9779459 0.1384986 0.1563326 -0.977946 0.1116279 0.1765253 -0.9779458 0.08186477 0.1921463 -0.9779459 0.08186513 0.1921445 -0.9779462 0.0499829 0.2027883 -0.9779462 0.01680594 0.2081797 -0.9779462 -0.3400275 0.7980742 -0.4974523 -0.2311741 0.5425859 -0.8075638 -0.2311736 0.542584 -0.807565 -0.08186513 0.1921444 -0.9779461 -0.08186525 0.1921448 -0.9779461 0.7837349 -0.3718872 -0.4974529 0.5328376 -0.2528348 -0.8075634 0.5328364 -0.252834 -0.8075645 0.1886927 -0.08953577 -0.977946 0.1886923 -0.08953553 -0.9779461 0.5893025 0.02374798 -0.8075634 0.6719631 0.5486409 -0.4974523 0.4568465 0.3730036 -0.8075639 0.4568454 0.3730029 -0.807565 0.1617825 0.1320914 -0.9779459 0.1617826 0.1320915 -0.9779459 0.04745769 0.5878682 -0.8075636 0.04745745 0.5878671 -0.8075642 -0.04745763 0.5878671 -0.8075643 -0.7512697 0.433746 -0.4974518 -0.9746742 0.1989801 -0.102064 -0.9301335 0.3527527 -0.1020638 -0.8111187 0.3076164 -0.4974521 -0.7512694 0.4337458 -0.4974524 -0.5107644 0.2948901 -0.8075639 -0.2046368 0.04177701 -0.9779461 -0.2046375 0.04177707 -0.9779459 -0.5778602 0.117971 -0.8075645 -0.5893009 0.02374792 -0.8075645 -0.8667864 0.03493016 -0.4974546 -0.861165 -0.1045648 -0.4974546 -0.2006112 -0.05810773 -0.9779462 -0.1886923 -0.08953559 -0.9779461 -0.5328378 -0.2528346 -0.8075634 -0.4853801 -0.3350335 -0.8075634 -0.7139319 -0.4927914 -0.4974514 -0.6256372 -0.6009327 -0.4974514 -0.1506289 -0.144681 -0.9779459 -0.1254698 -0.16697 -0.977946 -0.3543061 -0.4714956 -0.8075637 -0.2740848 -0.5222246 -0.8075637 -0.4031437 -0.7681256 -0.4974517 -0.2747068 -0.8228476 -0.4974516 -0.03350293 -0.2061537 -0.9779459 0 -0.2088583 -0.9779459 0 -0.5897793 -0.8075646 0.09460705 -0.5821418 -0.8075645 0.1391551 -0.8562575 -0.4974524 0.2747067 -0.8228471 -0.4974525 0.06613856 -0.1981095 -0.9779459 0.09706115 -0.1849346 -0.977946 0.2740846 -0.5222246 -0.8075637 0.3543059 -0.4714958 -0.8075637 0.5211389 -0.6935101 -0.4974515 0.6256371 -0.6009326 -0.4974517 0.8667864 0.0349307 -0.4974545 0.8667892 0.03493028 -0.49745 0.8499612 0.1735208 -0.49745 0.2073345 -0.02517414 -0.9779461 0.2086879 0.008409857 -0.9779462 0.589301 0.02374809 -0.8075646 0.5778602 0.117971 -0.8075644 0.8499608 0.1735208 -0.4974507 0.8111194 0.3076167 -0.4974508 0.930134 0.3527529 -0.1020599 0.8615011 0.4973929 -0.1020596 0.06980359 0.8646775 -0.4974538 0.06980437 0.8646801 -0.4974492 -0.06980377 0.8646801 -0.4974492 -0.06980413 0.8646774 -0.4974538 -0.2076041 0.8422827 -0.4974538 -0.3899208 0.9151753 -0.1020591 -0.3899198 0.9151754 -0.102061 -0.3400275 0.7980738 -0.4974533 -0.2076041 0.842283 -0.4974532 -0.1411437 0.5726428 -0.8075634 -0.04745757 0.5878682 -0.8075634 -0.01680594 0.2081797 -0.9779462 0.01680594 0.2081797 -0.9779462 -0.1116279 0.1765254 -0.9779458 -0.3152169 0.4984757 -0.8075644 -0.3152166 0.4984749 -0.807565 -0.4636446 0.7331949 -0.4974525 -0.4636446 0.7331951 -0.4974521 -0.531675 0.8407765 -0.1020623 -0.5316748 0.8407768 -0.1020591 -0.1384986 0.1563326 -0.9779459 -0.3910955 0.4414556 -0.807565 -0.391096 0.4414563 -0.8075644 -0.5752533 0.6493268 -0.497452 -0.5752531 0.6493266 -0.4974526 -0.6596599 0.7446021 -0.1020607 -0.6596599 0.744602 -0.1020623 -0.1617826 0.1320914 -0.9779459 -0.4568464 0.3730038 -0.8075639 -0.4568456 0.3730029 -0.8075648 -0.6719633 0.548641 -0.497452 -0.6719632 0.5486409 -0.4974523 -0.77056 0.6291427 -0.1020613 -0.7705602 0.629143 -0.1020604 -0.9301338 0.3527532 -0.1020599 -0.8615012 0.4973929 -0.1020596 -0.8615032 0.4973894 -0.1020583 -0.861503 0.4973887 -0.1020633 -0.7705597 0.629143 -0.102063 -0.1617825 0.1320914 -0.9779459 -0.1808764 0.104429 -0.9779459 -0.5107626 0.2948887 -0.8075656 -0.5514516 0.2091379 -0.8075658 -0.8111193 0.3076168 -0.4974508 -0.8499608 0.1735207 -0.4974507 -0.9746744 0.1989812 -0.1020606 -0.9746738 0.1989818 -0.102065 -0.1952864 0.07406216 -0.9779458 -0.1952859 0.07406216 -0.9779459 -0.5514532 0.2091388 -0.8075645 -0.5778604 0.1179711 -0.8075644 -0.8499612 0.1735209 -0.49745 -0.8667891 0.03493082 -0.4974499 -0.9939716 0.04005616 -0.1020582 -0.8987327 -0.4264539 -0.1020609 -0.9555026 -0.2767642 -0.1020606 -0.8332417 -0.2413509 -0.4974517 -0.8611667 -0.1045646 -0.4974516 -0.5854806 -0.07109028 -0.8075635 -0.5893025 0.02374815 -0.8075635 -0.208688 0.008409857 -0.9779461 -0.2046366 0.04177653 -0.9779461 -0.9555025 -0.2767642 -0.1020615 -0.9555013 -0.2767668 -0.1020652 -0.9875246 -0.1199077 -0.1020653 -0.9875252 -0.1199072 -0.1020597 -0.9939715 0.04005682 -0.1020597 -0.8987324 -0.4264544 -0.1020628 -0.8987324 -0.4264543 -0.1020633 -0.7837349 -0.3718872 -0.497453 -0.8332407 -0.2413508 -0.4974532 -0.5664955 -0.1640872 -0.8075631 -0.5854811 -0.07109022 -0.807563 -0.2073352 -0.02517503 -0.9779459 -0.2073345 -0.02517414 -0.9779461 -0.2006115 -0.05810797 -0.977946 -0.2006111 -0.05810773 -0.9779462 -0.5664936 -0.1640869 -0.8075645 -0.5328362 -0.2528342 -0.8075645 -0.7837354 -0.3718874 -0.4974522 -0.7139317 -0.4927912 -0.4974519 -0.8186864 -0.5650982 -0.1020619 -0.4622967 -0.8808322 -0.1020599 -0.5976055 -0.7952682 -0.1020598 -0.5211391 -0.6935099 -0.4974516 -0.6256371 -0.6009327 -0.4974517 -0.4253504 -0.4085547 -0.8075644 -0.4853789 -0.3350329 -0.8075643 -0.1718866 -0.1186447 -0.9779461 -0.1886928 -0.08953571 -0.9779461 -0.5976051 -0.7952681 -0.1020628 -0.5976055 -0.795268 -0.1020615 -0.7174364 -0.6891071 -0.102061 -0.7174363 -0.689107 -0.1020615 -0.8186863 -0.5650982 -0.1020619 -0.1506287 -0.1446807 -0.977946 -0.1506289 -0.1446811 -0.9779459 -0.4253502 -0.4085545 -0.8075646 -0.3543052 -0.4714947 -0.8075646 -0.5211381 -0.6935091 -0.497454 -0.4031429 -0.7681246 -0.4974539 -0.4622964 -0.8808322 -0.1020616 0 -0.9947777 -0.1020656 -0.1595733 -0.9818956 -0.1020655 -0.1391551 -0.8562576 -0.4974524 -0.2747065 -0.8228471 -0.4974524 -0.186764 -0.559427 -0.8075647 -0.2740841 -0.5222235 -0.8075647 -0.09706109 -0.1849344 -0.9779461 -0.1254699 -0.1669698 -0.9779459 -0.1595739 -0.9818961 -0.10206 -0.1595757 -0.981896 -0.1020583 -0.3150144 -0.9435836 -0.1020583 -0.3150144 -0.9435836 -0.1020582 -0.4622955 -0.8808332 -0.1020581 -0.06613856 -0.1981095 -0.9779459 -0.06613856 -0.1981092 -0.9779461 -0.1867644 -0.5594278 -0.8075641 -0.09460717 -0.5821425 -0.807564 -0.1391551 -0.8562575 -0.4974523 0 -0.8674913 -0.4974523 0 -0.9947777 -0.1020656 0 -0.9947777 -0.1020656 -0.0661388 -0.1981096 -0.9779459 -0.03350311 -0.2061536 -0.977946 -0.09460699 -0.5821418 -0.8075646 0 -0.5897792 -0.8075645 0 -0.8674913 -0.4974523 0.1391551 -0.8562576 -0.4974524 0.1595733 -0.9818962 -0.1020606 0.5976052 -0.7952684 -0.1020598 0.4622965 -0.8808324 -0.10206 0.4031435 -0.7681258 -0.4974517 0.2747067 -0.8228476 -0.4974516 0.1867643 -0.5594278 -0.807564 0.09460711 -0.5821425 -0.807564 0.03350317 -0.2061541 -0.9779458 0.03350293 -0.2061537 -0.9779459 0.4622966 -0.880832 -0.1020622 0.4622955 -0.8808332 -0.102058 0.3150144 -0.9435837 -0.102058 0.3150144 -0.9435836 -0.1020582 0.1595757 -0.981896 -0.1020583 0.0661388 -0.1981096 -0.9779459 0.06613856 -0.1981092 -0.9779461 0.1867641 -0.5594269 -0.8075646 0.2740842 -0.5222234 -0.8075646 0.4031432 -0.7681245 -0.497454 0.5211383 -0.6935089 -0.4974539 0.5976054 -0.7952681 -0.1020618 0.8987324 -0.4264544 -0.1020628 0.8186863 -0.5650982 -0.1020631 0.7139319 -0.4927914 -0.4974514 0.6256372 -0.6009328 -0.4974514 0.4253502 -0.4085545 -0.8075645 0.3543053 -0.4714946 -0.8075646 0.1254697 -0.1669698 -0.977946 0.1254699 -0.1669698 -0.9779459 0.8186863 -0.5650984 -0.1020618 0.8186863 -0.5650982 -0.1020619 0.7174364 -0.6891071 -0.1020617 0.7174364 -0.6891071 -0.102061 0.5976055 -0.795268 -0.1020614 0.1506289 -0.144681 -0.9779459 0.1506289 -0.1446811 -0.9779459 0.4253504 -0.4085547 -0.8075643 0.485379 -0.3350328 -0.8075643 0.7139317 -0.4927912 -0.497452 0.7837353 -0.3718875 -0.4974522 0.8987324 -0.4264543 -0.1020633 0.8987327 -0.426454 -0.1020609 0.9555013 -0.2767668 -0.1020652 0.2006111 -0.05810773 -0.9779461 0.5664955 -0.1640875 -0.8075631 0.5664938 -0.1640867 -0.8075646 0.8332415 -0.2413511 -0.4974516 0.8332408 -0.2413507 -0.4974532 0.9555025 -0.2767642 -0.1020613 0.9555026 -0.2767643 -0.1020606 0.2073349 -0.02517497 -0.977946 0.5854806 -0.07109016 -0.8075634 0.5854811 -0.07109034 -0.8075631 0.8611651 -0.1045644 -0.4974546 0.8611667 -0.104565 -0.4974517 0.9875251 -0.1199077 -0.1020597 0.9875247 -0.1199071 -0.1020653 0.9301334 0.3527531 -0.1020638 0.9746742 0.1989801 -0.102064 0.9746744 0.1989812 -0.1020605 0.9746738 0.1989818 -0.102065 0.9939709 0.04005616 -0.102065 0.9939719 0.04005521 -0.102056 0.9939715 0.04005682 -0.1020597 0.861503 0.4973887 -0.1020633 0.8615032 0.4973894 -0.1020583 0.7512694 0.4337459 -0.4974524 0.8111187 0.3076165 -0.4974521 0.5514533 0.2091385 -0.8075645 0.5778603 0.1179711 -0.8075644 0.2046376 0.04177707 -0.9779459 0.2046366 0.04177653 -0.9779461 0.2046368 0.04177701 -0.9779461 0.1952853 0.07406198 -0.9779461 0.5514515 0.209138 -0.8075658 0.5107625 0.294889 -0.8075656 0.7512697 0.433746 -0.4974518 0.6719634 0.548641 -0.497452 0.77056 0.6291427 -0.1020615 0.7705601 0.6291429 -0.1020606 0.6596598 0.7446022 -0.1020619 0.1384986 0.1563326 -0.9779459 0.3910961 0.4414562 -0.8075644 0.3910954 0.4414556 -0.8075651 0.575253 0.6493265 -0.4974525 0.5752532 0.6493267 -0.4974522 0.6596598 0.744602 -0.1020622 0.6596601 0.7446021 -0.1020606 0.1116275 0.1765247 -0.977946 0.3152165 0.498475 -0.8075649 0.315217 0.4984755 -0.8075645 0.4636446 0.7331951 -0.4974522 0.4636445 0.733195 -0.4974525 0.5316751 0.8407767 -0.1020593 0.5316747 0.8407766 -0.102062 0.08186531 0.1921448 -0.977946 0.2311743 0.5425857 -0.8075637 0.2311734 0.5425842 -0.8075651 0.3400273 0.7980737 -0.4974532 0.3400276 0.7980743 -0.4974523 0.3899199 0.9151757 -0.1020579 0.3899194 0.9151756 -0.1020618 0.0499829 0.2027886 -0.9779461 0.1411438 0.5726428 -0.8075634 0.1411436 0.5726424 -0.8075637 0.2076041 0.8422828 -0.4974539 0.2076042 0.842283 -0.4974535 0.2380661 0.9658719 -0.102058 0.2380662 0.9658719 -0.1020578 -0.3899196 0.9151759 -0.1020579 -0.2380662 0.9658719 -0.1020577 -0.2380661 0.9658719 -0.102058 -0.2380661 0.9658721 -0.1020575 -0.08004593 0.9915528 -0.1020574 -0.08004671 0.9915518 -0.1020656 0.08004587 0.9915519 -0.1020656 0.08004677 0.9915527 -0.1020575 0.2380661 0.9658721 -0.1020576 -0.09745079 0.9894328 0.1073608 -0.2379633 0.965455 0.1061612 -0.288641 0.9515258 0.1062307 -0.2379554 0.9654225 0.1064729 -0.288591 0.951357 0.1078663 -0.3897598 0.914801 0.1059553 -0.4686889 0.8768568 0.1070187 -0.3897175 0.9146981 0.1069943 -0.468641 0.8767645 0.1079787 -0.5314539 0.8404274 0.1060115 -0.6307035 0.7685143 0.1076978 -0.6592997 0.7441958 0.1072221 -0.630727 0.768543 0.1073546 -0.6593635 0.7442673 0.1063296 -0.7685706 0.6307497 0.1070239 -0.7701618 0.6288177 0.106954 -0.768577 0.6307544 0.1069506 -0.7701653 0.628821 0.1069094 -0.8769565 0.4687435 0.1059576 -0.8610197 0.4971098 0.1073635 -0.8768044 0.4686616 0.1075661 -0.8609814 0.4970928 0.1077498 -0.9297444 0.3526055 0.1060408 -0.9513469 0.2885882 0.1079626 -0.9742189 0.1988872 0.1064959 -0.9515222 0.2886385 0.1062701 -0.974276 0.1989006 0.1059472 -0.9893738 0.09744495 0.1079065 -0.9935474 0.0400381 0.1061157 -0.9935473 0.04003971 0.1061157 -0.9894223 -0.09744977 0.1074571 -0.9870582 -0.1198505 0.1065461 -0.9514865 -0.2886292 0.106615 -0.9550246 -0.2766287 0.1067913 -0.9514768 -0.2886273 0.1067065 -0.9549794 -0.2766127 0.1072377 -0.8770111 -0.4687713 0.1053808 -0.8982855 -0.4262417 0.1067765 -0.8768876 -0.4687067 0.1066868 -0.8981472 -0.4261768 0.1081895 -0.7688385 -0.6309692 0.1037555 -0.8182201 -0.5647765 0.1074393 -0.8182203 -0.5647765 0.1074393 -0.7684901 -0.6306836 0.1079867 -0.7171402 -0.6888226 0.1059874 -0.6306992 -0.7685089 0.107762 -0.5972919 -0.7948507 0.1070264 -0.630747 -0.7685676 0.1070615 -0.5973404 -0.794916 0.1062681 -0.4686834 -0.8768444 0.1071442 -0.4620605 -0.8803821 0.1068997 -0.468697 -0.8768706 0.1068692 -0.4620635 -0.8803912 0.1068105 -0.314868 -0.9431452 0.1064686 -0.2886013 -0.9513902 0.1075453 -0.1594947 -0.9813981 0.1068602 -0.2886228 -0.9514654 0.10682 -0.1595065 -0.9814813 0.1060757 -0.09744465 -0.9893704 0.1079385 0 -0.9943721 0.1059446 0 -0.9943721 0.1059446 0.09744465 -0.9893704 0.1079385 0.1595065 -0.9814813 0.1060757 0.2886228 -0.9514654 0.10682 0.1594947 -0.9813981 0.1068602 0.2886013 -0.9513902 0.1075453 0.314868 -0.9431452 0.1064686 0.4687021 -0.8768814 0.1067593 0.4620591 -0.8803828 0.1068997 0.4686975 -0.8768703 0.1068692 0.4620493 -0.8803609 0.1071229 0.6308475 -0.7686898 0.105581 0.5972916 -0.794851 0.1070264 0.6307471 -0.7685674 0.1070615 0.9894223 -0.09744977 0.1074571 0.5972262 -0.7947633 0.1080376 0.7171402 -0.6888226 0.1059874 0.7684901 -0.6306836 0.1079867 0.8182203 -0.5647765 0.1074393 0.7685153 -0.6307045 0.1076852 0.8183501 -0.5648662 0.1059687 0.87678 -0.4686492 0.1078181 0.8982853 -0.4262422 0.1067765 0.8768882 -0.4687057 0.1066868 0.8983401 -0.4262676 0.106212 0.95142 -0.2886103 0.1072565 0.9550255 -0.2766261 0.1067913 0.951477 -0.2886263 0.1067065 0.9550324 -0.2766309 0.1067171 0.9870582 -0.1198505 0.1065461 0.9935473 0.04003971 0.1061157 0.9935474 0.0400381 0.1061157 0.9893738 0.09744495 0.1079065 0.974276 0.1989006 0.1059472 0.9515222 0.2886385 0.1062701 0.9742189 0.1988872 0.1064959 0.9513469 0.2885882 0.1079626 0.9297444 0.3526055 0.1060408 0.8767989 0.4686581 0.1076256 0.8610175 0.4971137 0.1073635 0.8768042 0.4686619 0.1075661 0.8611097 0.4971617 0.1063964 0.7685814 0.6307583 0.1068956 0.7701616 0.6288179 0.106954 0.7685767 0.6307548 0.1069506 0.7701568 0.6288136 0.1070135 0.6308346 0.768674 0.1057733 0.6593 0.7441956 0.1072221 0.6307269 0.7685431 0.1073547 0.6592517 0.7441416 0.107891 0.5314539 0.8404274 0.1060115 0.468641 0.8767645 0.1079787 0.3897175 0.9146981 0.1069943 0.4686889 0.8768568 0.1070187 0.3897598 0.914801 0.1059553 0.288591 0.951357 0.1078663 0.2379554 0.9654225 0.1064729 0.288641 0.9515258 0.1062307 0.2379633 0.965455 0.1061612 0.09745079 0.9894328 0.1073608 0.0800082 0.9910746 0.1066289 -0.0800082 0.9910746 0.1066289 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.7409957 -0.6081193 0.2848094 0.6081193 0.7409957 0.2848094 -0.7409957 0.6081193 0.2848094 -0.6081193 -0.7409957 0.2848094 0.08616435 -0.1612022 0.9831529 0.1159577 -0.141295 0.9831529 0.1412949 -0.1159577 0.9831529 0.1612023 -0.08616441 0.9831528 0.1612022 0.08616435 0.9831529 0.141295 0.1159577 0.9831529 0.1159577 0.1412949 0.9831529 0.08616441 0.1612023 0.9831528 -0.08616435 0.1612022 0.9831529 -0.1159577 0.141295 0.9831529 -0.1412949 0.1159577 0.9831529 -0.1612023 0.08616441 0.9831528 -0.1612022 -0.08616435 0.9831529 -0.141295 -0.1159577 0.9831529 -0.1159577 -0.1412949 0.9831529 -0.08616441 -0.1612023 0.9831528 -0.1749146 0.05305975 0.9831529 -0.1749146 0.05305975 0.9831528 -0.1819051 0.01791602 0.9831529 -0.181905 0.01791608 0.9831529 -0.181905 -0.01791602 0.9831529 -0.1819051 -0.01791608 0.9831528 -0.1749146 -0.05305975 0.9831529 0.05305975 0.1749146 0.9831529 0.05305975 0.1749146 0.9831528 0.01791602 0.1819051 0.9831529 0.01791608 0.181905 0.9831529 -0.01791602 0.181905 0.9831529 -0.01791608 0.1819051 0.9831528 -0.05305975 0.1749146 0.9831529 0.1749146 -0.05305975 0.9831529 0.1749146 -0.05305975 0.9831528 0.1819051 -0.01791602 0.9831529 0.181905 -0.01791608 0.9831529 0.181905 0.01791602 0.9831529 0.1819051 0.01791608 0.9831528 0.1749146 0.05305975 0.9831529 -0.05305975 -0.1749146 0.9831529 -0.05305975 -0.1749146 0.9831528 -0.01791602 -0.1819051 0.9831529 -0.01791608 -0.181905 0.9831529 0.01791602 -0.181905 0.9831529 0.01791608 -0.1819051 0.9831528 0.05305975 -0.1749146 0.9831529 -0.5010039 0.151978 0.8519963 -0.5010042 0.1519779 0.8519961 -0.521027 0.05131667 0.8519961 -0.5210272 0.05131661 0.8519961 -0.5210271 -0.05131667 0.8519961 -0.521027 -0.05131655 0.8519962 0.151978 0.5010039 0.8519963 0.1519779 0.5010042 0.8519961 0.05131667 0.521027 0.8519961 0.05131661 0.5210272 0.8519961 -0.05131667 0.5210271 0.8519961 -0.05131655 0.521027 0.8519962 0.5010039 -0.151978 0.8519963 0.5010042 -0.1519779 0.8519961 0.521027 -0.05131667 0.8519961 0.5210272 -0.05131661 0.8519961 0.5210271 0.05131667 0.8519961 0.521027 0.05131655 0.8519962 -0.151978 -0.5010039 0.8519963 -0.1519779 -0.5010042 0.8519961 -0.05131667 -0.521027 0.8519961 -0.05131661 -0.5210272 0.8519961 0.05131667 -0.5210271 0.8519961 0.05131655 -0.521027 0.8519962 -0.7596551 0.2304388 0.6081302 -0.7596551 0.2304387 0.60813 -0.7900149 0.07780957 0.60813 -0.7900149 0.07780957 0.60813 -0.7900149 -0.07780957 0.60813 -0.7900149 -0.07780957 0.60813 0.2304388 0.7596551 0.6081302 0.2304387 0.7596551 0.60813 0.07780957 0.7900149 0.60813 0.07780957 0.7900149 0.60813 -0.07780957 0.7900149 0.60813 -0.07780957 0.7900149 0.60813 0.7596551 -0.2304388 0.6081302 0.7596551 -0.2304387 0.60813 0.7900149 -0.07780957 0.60813 0.7900149 -0.07780957 0.60813 0.7900149 0.07780957 0.60813 0.7900149 0.07780957 0.60813 -0.2304388 -0.7596551 0.6081302 -0.2304387 -0.7596551 0.60813 -0.07780957 -0.7900149 0.60813 -0.07780957 -0.7900149 0.60813 0.07780957 -0.7900149 0.60813 0.07780957 -0.7900149 0.60813 -0.08616441 -0.1612022 0.9831529 -0.2467987 -0.4617278 0.8519964 -0.2467987 -0.4617279 0.8519963 -0.3742123 -0.7001019 0.6081304 -0.3742123 -0.700102 0.6081302 -0.4518734 -0.8453958 0.2848094 -0.4518737 -0.8453953 0.2848104 -0.1159577 -0.141295 0.9831528 -0.3321352 -0.4047082 0.8519962 -0.3321352 -0.4047079 0.8519964 -0.5036053 -0.6136449 0.6081296 -0.5036053 -0.6136443 0.6081304 -0.6081195 -0.7409951 0.2848105 -0.6081194 -0.7409955 0.2848097 -0.7409957 -0.6081193 0.2848094 -0.1412949 -0.1159577 0.9831529 -0.4047079 -0.332135 0.8519964 -0.404708 -0.3321353 0.8519961 -0.6136445 -0.503605 0.6081304 -0.6136447 -0.5036056 0.6081297 -0.7409952 -0.6081196 0.28481 -0.7409953 -0.6081192 0.2848104 -0.8453959 -0.451873 0.2848099 -0.1612023 -0.08616441 0.9831529 -0.4617279 -0.2467988 0.8519964 -0.4617278 -0.2467987 0.8519963 -0.700102 -0.3742124 0.6081302 -0.7001018 -0.3742122 0.6081304 -0.8453956 -0.4518734 0.2848102 -0.8453955 -0.4518738 0.2848094 -0.1749145 -0.05305975 0.9831528 -0.5010042 -0.151978 0.8519962 -0.5010039 -0.1519778 0.8519963 -0.7596551 -0.2304388 0.60813 -0.7596549 -0.2304387 0.6081302 -0.9173077 -0.2782621 0.2848106 -0.9173077 -0.2782624 0.2848098 -0.8453959 0.451873 0.2848099 -0.9173077 0.2782624 0.2848099 -0.9173077 0.2782621 0.2848106 -0.9173082 0.2782606 0.2848101 -0.9539682 0.09395748 0.28481 -0.9539679 0.09395784 0.2848109 -0.9539678 -0.09395748 0.2848109 -0.9539682 -0.09395784 0.28481 -0.9173082 -0.2782606 0.2848101 -0.1612022 0.08616441 0.9831529 -0.4617278 0.2467987 0.8519964 -0.4617279 0.2467987 0.8519963 -0.7001019 0.3742123 0.6081304 -0.700102 0.3742123 0.6081302 -0.8453958 0.4518734 0.2848094 -0.8453953 0.4518737 0.2848104 -0.141295 0.1159577 0.9831528 -0.4047082 0.3321352 0.8519962 -0.4047079 0.3321352 0.8519964 -0.6136449 0.5036053 0.6081296 -0.6136443 0.5036053 0.6081304 -0.7409951 0.6081195 0.2848105 -0.7409955 0.6081194 0.2848097 -0.6081193 0.7409957 0.2848094 -0.1159577 0.1412949 0.9831529 -0.332135 0.4047079 0.8519964 -0.3321353 0.404708 0.8519961 -0.503605 0.6136445 0.6081304 -0.5036056 0.6136447 0.6081297 -0.6081196 0.7409952 0.28481 -0.6081192 0.7409953 0.2848104 -0.451873 0.8453959 0.2848099 -0.08616441 0.1612023 0.9831529 -0.2467988 0.4617279 0.8519964 -0.2467987 0.4617278 0.8519963 -0.3742124 0.700102 0.6081302 -0.3742122 0.7001018 0.6081304 -0.4518734 0.8453956 0.2848102 -0.4518738 0.8453955 0.2848094 -0.05305975 0.1749145 0.9831528 -0.151978 0.5010042 0.8519962 -0.1519778 0.5010039 0.8519963 -0.2304388 0.7596551 0.60813 -0.2304387 0.7596549 0.6081302 -0.2782621 0.9173077 0.2848106 -0.2782624 0.9173077 0.2848098 0.451873 0.8453959 0.2848099 0.2782624 0.9173077 0.2848099 0.2782621 0.9173077 0.2848106 0.2782606 0.9173082 0.2848101 0.09395748 0.9539682 0.28481 0.09395784 0.9539679 0.2848109 -0.09395748 0.9539678 0.2848109 -0.09395784 0.9539682 0.28481 -0.2782606 0.9173082 0.2848101 0.08616441 0.1612022 0.9831529 0.2467987 0.4617278 0.8519964 0.2467987 0.4617279 0.8519963 0.3742123 0.7001019 0.6081304 0.3742123 0.700102 0.6081302 0.4518734 0.8453958 0.2848094 0.4518737 0.8453953 0.2848104 0.1159577 0.141295 0.9831528 0.3321352 0.4047082 0.8519962 0.3321352 0.4047079 0.8519964 0.5036053 0.6136449 0.6081296 0.5036053 0.6136443 0.6081304 0.6081195 0.7409951 0.2848105 0.6081194 0.7409955 0.2848097 0.7409957 0.6081193 0.2848094 0.1412949 0.1159577 0.9831529 0.4047079 0.332135 0.8519964 0.404708 0.3321353 0.8519961 0.6136445 0.503605 0.6081304 0.6136447 0.5036056 0.6081297 0.7409952 0.6081196 0.28481 0.7409953 0.6081192 0.2848104 0.8453959 0.451873 0.2848099 0.1612023 0.08616441 0.9831529 0.4617279 0.2467988 0.8519964 0.4617278 0.2467987 0.8519963 0.700102 0.3742124 0.6081302 0.7001018 0.3742122 0.6081304 0.8453956 0.4518734 0.2848102 0.8453955 0.4518738 0.2848094 0.1749145 0.05305975 0.9831528 0.5010042 0.151978 0.8519962 0.5010039 0.1519778 0.8519963 0.7596551 0.2304388 0.60813 0.7596549 0.2304387 0.6081302 0.9173077 0.2782621 0.2848106 0.9173077 0.2782624 0.2848098 0.8453959 -0.451873 0.2848099 0.9173077 -0.2782624 0.2848099 0.9173077 -0.2782621 0.2848106 0.9173082 -0.2782606 0.2848101 0.9539682 -0.09395748 0.28481 0.9539679 -0.09395784 0.2848109 0.9539678 0.09395748 0.2848109 0.9539682 0.09395784 0.28481 0.9173082 0.2782606 0.2848101 0.1612022 -0.08616441 0.9831529 0.4617278 -0.2467987 0.8519964 0.4617279 -0.2467987 0.8519963 0.7001019 -0.3742123 0.6081304 0.700102 -0.3742123 0.6081302 0.8453958 -0.4518734 0.2848094 0.8453953 -0.4518737 0.2848104 0.141295 -0.1159577 0.9831528 0.4047082 -0.3321352 0.8519962 0.4047079 -0.3321352 0.8519964 0.6136449 -0.5036053 0.6081296 0.6136443 -0.5036053 0.6081304 0.7409951 -0.6081195 0.2848105 0.7409955 -0.6081194 0.2848097 0.6081193 -0.7409957 0.2848094 0.1159577 -0.1412949 0.9831529 0.332135 -0.4047079 0.8519964 0.3321353 -0.404708 0.8519961 0.503605 -0.6136445 0.6081304 0.5036056 -0.6136447 0.6081297 0.6081196 -0.7409952 0.28481 0.6081192 -0.7409953 0.2848104 0.451873 -0.8453959 0.2848099 0.08616441 -0.1612023 0.9831529 0.2467988 -0.4617279 0.8519964 0.2467987 -0.4617278 0.8519963 0.3742124 -0.700102 0.6081302 0.3742122 -0.7001018 0.6081304 0.4518734 -0.8453956 0.2848102 0.4518738 -0.8453955 0.2848094 0.05305975 -0.1749145 0.9831528 0.151978 -0.5010042 0.8519962 0.1519778 -0.5010039 0.8519963 0.2304388 -0.7596551 0.60813 0.2304387 -0.7596549 0.6081302 0.2782621 -0.9173077 0.2848106 0.2782624 -0.9173077 0.2848098 -0.451873 -0.8453959 0.2848099 -0.2782624 -0.9173077 0.2848099 -0.2782621 -0.9173077 0.2848106 -0.2782606 -0.9173082 0.2848101 -0.09395748 -0.9539682 0.28481 -0.09395784 -0.9539679 0.2848109 0.09395748 -0.9539678 0.2848109 0.09395784 -0.9539682 0.28481 0.2782606 -0.9173082 0.2848101 0.1771482 0.8476391 0.5001266 0.1723535 0.8490473 0.4994126 0.1336655 0.8506807 0.5084052 0.1335421 0.8507036 0.5083993 0.08596956 0.8581314 0.5061816 0.03201937 0.862389 0.5052326 0.03193265 0.8623888 0.5052384 0.02613562 0.8623062 0.5057125 0.1936767 0.8427115 0.5023213 0.2801082 0.81309 0.5103175 0.1736528 0.8454978 0.5049536 0.07402068 0.8684598 0.4902024 0.298962 0.8060482 0.5107915 0.3003106 0.8054767 0.5109021 0.1201967 0.865948 0.485476 0.1646314 0.8562361 0.4896491 0.1649009 0.8561762 0.4896633 0.2043089 0.8467621 0.4911739 0.2487423 0.8361856 0.4887952 0.3690595 0.809833 0.4560325 0.5268986 0.7193171 0.452726 0.4030019 0.7869471 0.4672297 0.4029482 0.7869721 0.4672342 0.2861331 0.8266892 0.4844717 0.2842158 0.8271813 0.4847602 0.2887434 0.8260145 0.4840736 0.2864297 0.8266894 0.484296 0.402996 0.7869525 0.467226 0.4028993 0.7869928 0.4672414 0.4213796 0.7777473 0.4664207 0.3970286 0.7832652 0.4783973 0.3707754 0.7882409 0.4911229 0.3584042 0.8045607 0.4735278 0.4858133 0.7658756 0.4212126 0.6113061 0.7182375 0.3323249 0.7216857 0.596409 0.3513774 0.7216947 0.5964012 0.3513722 0.6279184 0.6670246 0.4009947 0.6279652 0.6669953 0.4009701 0.4066727 0.791951 0.4554462 0.4489412 0.7702929 0.4528802 0.5142704 0.7393198 0.4346631 0.5961802 0.6915768 0.4077876 0.5961797 0.6915771 0.4077878 0.7065811 0.6127887 0.3538829 0.7065939 0.6127786 0.3538751 0.8015999 0.5257254 0.2846935 0.9325879 0.3073855 0.1891927 0.8768694 0.4141029 0.2441697 0.8768753 0.4140934 0.2441644 0.8064287 0.5098909 0.299473 0.8064042 0.509919 0.2994911 0.796905 0.520575 0.3065032 0.8068162 0.5090808 0.2998071 0.8068308 0.5090636 0.299797 0.9325832 0.3073965 0.1891985 0.872835 0.4214057 0.2461223 0.8728056 0.4214527 0.2461463 0.9342831 0.3171821 0.1628206 0.9881254 0.1200471 0.09590059 0.9810773 0.1589826 0.1105081 0.9772129 0.1767523 0.1175318 0.9771233 0.1771435 0.1176863 0.9686396 0.2105546 0.1319249 0.968634 0.2105743 0.1319335 0.9586575 0.2432008 0.1477466 0.9586508 0.2432212 0.1477568 0.9503652 0.2669713 0.1597882 0.872826 0.4214205 0.2461295 0.9304946 0.3157374 0.185714 0.93028 0.316207 0.1859901 0.9432404 0.2855063 0.1696579 0.9342826 0.3171837 0.1628212 0.9649853 0.2297898 0.1264912 0.9649877 0.2297817 0.1264875 0.9804372 0.1709244 0.09761095 0.9804413 0.1709058 0.09760165 0.9804292 0.1709591 0.0976302 0.9770146 0.0948109 0.1909273 0.996978 0.06775051 0.0380091 0.9969781 0.06774967 0.03800863 0.9373451 0.3017233 0.1742046 0.9456342 0.2835944 0.1592171 0.950254 0.2729335 0.1500821 0.9969797 0.06773465 0.03799659 0.9746984 0.1806307 0.1316648 0.9845383 0.1660293 0.05584371 0.9480935 0.2423182 0.2059146 0.9640924 0.2384328 0.1169423 0.96409 0.2384343 0.1169596 0.9882116 0.1324132 0.07684028 0.9882149 0.1323948 0.07682985 0.9921532 0.1080181 0.06296056 0.9982966 0.05028748 0.02958095 0.9995049 0.02601587 0.01769506 0.9953711 0.08303064 0.04839718 0.995372 0.08302307 0.04839277 0.9957374 0.07969254 0.04643207 0.9941695 0.09313458 0.05434137 0.9968132 0.07410949 0.02951264 0.3583906 0.804564 0.4735324 0.2893133 0.825082 0.4853221 0.2246828 0.8396182 0.494529 0.2911403 0.824261 0.4856246 0.2905218 0.824423 0.48572 0.2596535 0.8319181 0.4904003 0.2267661 0.8375182 0.4971321 0.1851282 0.842284 0.5062461 0.1851177 0.8422846 0.5062491 0.1409058 0.8426297 0.5197312 0.2252787 0.8428428 0.4887388 0.08406788 0.8499485 0.5201153 0.2273669 0.8534541 0.4689567 -0.2303087 0.8365318 0.4971643 -0.1902638 0.8407111 0.5069562 0.08494424 0.85737 0.5076428 0.02646279 0.8616837 0.5067551 -0.05445486 0.8603826 0.5067313 -0.0281645 0.8610213 0.5077885 -0.06265163 0.8596729 0.5069886 -0.03303676 0.860893 0.5077125 -0.05440604 0.8600865 0.5072388 -0.02871161 0.8578488 0.5130995 -0.1950212 0.8508411 0.4878897 -0.08659917 0.8493796 0.5206294 -0.1944746 0.8477075 0.4935297 -0.3354349 0.8361937 0.4338934 -0.1417724 0.8423699 0.519917 -0.1423745 0.8423637 0.5197623 -0.4613648 0.7710985 0.4388049 -0.2709239 0.8285856 0.4899449 -0.3017019 0.8208033 0.4850341 -0.3286678 0.813083 0.4804928 -0.3057358 0.8177567 0.4876471 -0.3084647 0.8172275 0.4868149 -0.385625 0.7851634 0.4845738 -0.5837713 0.7254557 0.3645889 -0.461319 0.7711159 0.4388224 -0.410797 0.7901783 0.4548233 -0.3791372 0.8054504 0.4555267 -0.5541232 0.7023059 0.4468936 -0.3252794 0.8160233 0.4778068 -0.438923 0.7709189 0.4615525 -0.438808 0.7709721 0.4615729 -0.4387944 0.7709788 0.4615746 -0.6754168 0.6363662 0.3726261 -0.5731281 0.7059694 0.4160905 -0.4159947 0.7787639 0.469548 -0.4512458 0.7692954 0.4522851 -0.5733498 0.7062956 0.4152305 -0.5396947 0.7253973 0.4272335 -0.5397602 0.7253611 0.4272123 -0.6457945 0.654978 0.3923689 -0.7690659 0.5567942 0.3138757 -0.7690718 0.5567885 0.3138715 -0.8423787 0.4650736 0.2722218 -0.7385367 0.5810254 0.3420135 -0.7385373 0.5810248 0.342013 -0.7663472 0.5536261 0.3258988 -0.7391371 0.5799555 0.3425315 -0.7390614 0.5800261 0.3425757 -0.825617 0.4859451 0.2867299 -0.8423825 0.4650685 0.2722187 -0.8424006 0.465045 0.2722029 -0.8256018 0.4859632 0.2867429 -0.8255937 0.4859733 0.286749 -0.89072 0.3920013 0.2301147 -0.9972516 0.06795549 0.02952027 -0.9949113 0.08685058 0.05107474 -0.9927725 0.1035014 0.06074661 -0.9903202 0.1197595 0.0701698 -0.9903222 0.1197465 0.07016247 -0.9842712 0.1528733 0.08854401 -0.9842739 0.1528598 0.08853679 -0.9789913 0.1709793 0.1110944 -0.9831991 0.1614226 0.0852192 -0.9611724 0.2238245 0.1614009 -0.9505247 0.2447391 0.1913253 -0.9683612 0.229939 0.09697753 -0.9610206 0.2465641 0.1250825 -0.9729635 0.2012409 0.1133318 -0.9729655 0.2012334 0.113328 -0.972964 0.2012392 0.1133307 -0.9541179 0.2626975 0.1436977 -0.9469735 0.2796545 0.158223 -0.9402039 0.294749 0.1707028 -0.8907348 0.391976 0.2301009 -0.9382705 0.2964556 0.1782201 -0.9037373 0.3688534 0.2172697 -0.9339157 0.3080029 0.181482 -0.9432944 0.285438 0.1694724 -0.9478718 0.2736794 0.1632131 -0.9567643 0.2489806 0.1503691 -0.9567592 0.2489954 0.1503764 -0.9641637 0.2258709 0.1391789 -0.9736605 0.1918089 0.123266 -0.9736599 0.1918113 0.123267 -0.9500225 0.2754002 0.1470107 -0.9500268 0.275388 0.1470061 -0.9867642 0.1313394 0.09511268 -0.9088133 0.3721714 0.1885387 -0.9811633 0.1586768 0.1101831 -0.9811761 0.1586138 0.1101591 -0.9987224 0.04355639 0.0256232 -0.9927181 0.103833 0.06106817 -0.9927232 0.1037973 0.06104731 -0.9981485 0.05220574 0.03121262 -0.9983451 0.0493316 0.02955549 -0.9949753 0.1000776 0.002957165 -0.9789936 0.170971 0.1110877 -0.9974405 0.06373172 0.0324195 -0.9851701 0.1500304 0.08325076 -0.9968666 0.07129907 0.03425663 -0.3253397 0.8160037 0.4777994 -0.2991439 0.8230391 0.4828246 -0.3020185 0.8222585 0.482365 -0.1420326 0.8535683 0.5012463 -0.1419763 0.8535702 0.5012591 -0.1037201 0.857265 0.5043201 -0.09693253 0.8578988 0.5045925 -0.06472074 0.859764 0.5065739 -0.1319161 0.8544048 0.502584 -0.2118615 0.8366779 0.5050591 -0.2118191 0.8366919 0.5050537 -0.2106747 0.8371896 0.5047076 -0.1821758 0.8481049 0.4975238 -0.1614668 0.8477771 0.5051756 -0.2532439 0.8465811 0.4681536 -0.1941749 0.8510835 0.4878043 -0.2992746 0.8230041 0.4828033 -0.2679157 0.8311545 0.4872406 -0.3291404 0.8133094 0.4797857 -0.3263441 0.814207 0.4801734 -0.01971721 0.8627517 0.5052433 -0.01821947 0.8624432 0.5058259 -0.07367765 0.8581662 0.5080575 -0.07375937 0.8581568 0.5080615 -0.07394993 0.8581337 0.5080727 0.04173773 0.8595593 0.5093287 0.06214785 0.8586426 0.5087931 0.01596242 0.8601981 0.5097101 0.02561187 0.8600227 0.5096126 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.9898214 0 0.1423145 -0.9898213 0 -0.1423159 -0.9898213 0 -0.1423159 -0.9096335 0 -0.4154118 -0.9096335 0 -0.4154118 -0.7557472 0 -0.6548634 -0.7557472 0 -0.6548634 -0.5406454 0 -0.8412505 -0.5406454 0 -0.8412505 -0.2817315 0 -0.9594932 -0.2817315 0 -0.9594932 0 0 -1 0 0 -1 0.2817315 0 -0.9594932 0.2817315 0 -0.9594932 0.5406454 0 -0.8412505 0.5406454 0 -0.8412505 0.7557472 0 -0.6548634 0.7557472 0 -0.6548634 0.9096335 0 -0.4154118 0.9096335 0 -0.4154118 0.9898213 0 -0.1423159 0.9898213 0 -0.1423159 0.9898214 0 0.1423145 0.9898214 0 0.1423145 0.9096318 0 0.4154157 0.9096318 0 0.4154157 0.7557518 0 0.6548583 0.7557518 0 0.6548583 0.540638 0 0.8412554 0.540638 0 0.8412554 0.2817315 0 0.9594932 0.2817315 0 0.9594932 0 0 1 0 0 1 -0.2817315 0 0.9594932 -0.2817315 0 0.9594932 -0.540638 0 0.8412554 -0.540638 0 0.8412554 -0.7557518 0 0.6548583 -0.7557518 0 0.6548583 -0.9096318 0 0.4154157 -0.9096318 0 0.4154157 -0.9898214 0 0.1423145 -0.9898214 0 0.1423145 -0.9898213 0 -0.1423159 -0.9898213 0 -0.1423159 -0.9096335 0 -0.4154118 -0.9096335 0 -0.4154118 -0.7557472 0 -0.6548634 -0.7557472 0 -0.6548634 -0.5406454 0 -0.8412505 -0.5406454 0 -0.8412505 -0.2817315 0 -0.9594932 -0.2817315 0 -0.9594932 0 0 -1 0 0 -1 0.2817315 0 -0.9594932 0.2817315 0 -0.9594932 0.5406454 0 -0.8412505 0.5406454 0 -0.8412505 0.7557472 0 -0.6548634 0.7557472 0 -0.6548634 0.9096335 0 -0.4154118 0.9096335 0 -0.4154118 0.9898213 0 -0.1423159 0.9898213 0 -0.1423159 0.9898214 0 0.1423145 0.9898214 0 0.1423145 0.9096318 0 0.4154157 0.9096318 0 0.4154157 0.7557518 0 0.6548583 0.7557518 0 0.6548583 0.540638 0 0.8412554 0.540638 0 0.8412554 0.2817315 0 0.9594932 0.2817315 0 0.9594932 0 0 1 0 0 1 -0.2817315 0 0.9594932 -0.2817315 0 0.9594932 -0.540638 0 0.8412554 -0.540638 0 0.8412554 -0.7557518 0 0.6548583 -0.7557518 0 0.6548583 -0.9096318 0 0.4154157 -0.9096318 0 0.4154157 -0.9898214 0 0.1423145 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.991445 0 0.1305252 0.9914449 0 -0.1305264 0.9914449 0 -0.1305264 0.923879 0 -0.3826845 0.923879 0 -0.3826845 0.7933526 0 -0.6087624 0.7933526 0 -0.6087624 0.608767 0 -0.7933492 0.608767 0 -0.7933492 0.3826816 0 -0.9238803 0.3826816 0 -0.9238803 0.1305255 0 -0.9914449 0.1305255 0 -0.9914449 -0.1305255 0 -0.9914449 -0.1305255 0 -0.9914449 -0.3826816 0 -0.9238803 -0.3826816 0 -0.9238803 -0.608767 0 -0.7933492 -0.608767 0 -0.7933492 -0.7933526 0 -0.6087624 -0.7933526 0 -0.6087624 -0.923879 0 -0.3826845 -0.923879 0 -0.3826845 -0.9914449 0 -0.1305264 -0.9914449 0 -0.1305264 -0.991445 0 0.1305252 -0.991445 0 0.1305252 -0.923879 0 0.3826845 -0.923879 0 0.3826845 -0.7933526 0 0.6087624 -0.7933526 0 0.6087624 -0.608761 0 0.7933537 -0.608761 0 0.7933537 -0.3826816 0 0.9238803 -0.3826816 0 0.9238803 -0.1305348 0 0.9914438 -0.1305348 0 0.9914438 0.1305348 0 0.9914438 0.1305348 0 0.9914438 0.3826816 0 0.9238803 0.3826816 0 0.9238803 0.608761 0 0.7933537 0.608761 0 0.7933537 0.7933526 0 0.6087624 0.7933526 0 0.6087624 0.923879 0 0.3826845 0.923879 0 0.3826845 0.991445 0 0.1305252 0.991445 0 0.1305252 0.9914449 0 -0.1305264 0.9914449 0 -0.1305264 0.923879 0 -0.3826845 0.923879 0 -0.3826845 0.7933526 0 -0.6087624 0.7933526 0 -0.6087624 0.608767 0 -0.7933492 0.608767 0 -0.7933492 0.3826816 0 -0.9238803 0.3826816 0 -0.9238803 0.1305255 0 -0.9914449 0.1305255 0 -0.9914449 -0.1305255 0 -0.9914449 -0.1305255 0 -0.9914449 -0.3826816 0 -0.9238803 -0.3826816 0 -0.9238803 -0.608767 0 -0.7933492 -0.608767 0 -0.7933492 -0.7933526 0 -0.6087624 -0.7933526 0 -0.6087624 -0.923879 0 -0.3826845 -0.923879 0 -0.3826845 -0.9914449 0 -0.1305264 -0.9914449 0 -0.1305264 -0.991445 0 0.1305252 -0.991445 0 0.1305252 -0.923879 0 0.3826845 -0.923879 0 0.3826845 -0.7933526 0 0.6087624 -0.7933526 0 0.6087624 -0.608761 0 0.7933537 -0.608761 0 0.7933537 -0.3826816 0 0.9238803 -0.3826816 0 0.9238803 -0.1305348 0 0.9914438 -0.1305348 0 0.9914438 0.1305348 0 0.9914438 0.1305348 0 0.9914438 0.3826816 0 0.9238803 0.3826816 0 0.9238803 0.608761 0 0.7933537 0.608761 0 0.7933537 0.7933526 0 0.6087624 0.7933526 0 0.6087624 0.923879 0 0.3826845 0.923879 0 0.3826845 0.991445 0 0.1305252 -0.7713736 0.551595 0.317373 -0.9393426 0.3394125 0.04934239 -0.9049234 0.4031868 0.1362128 -0.8769772 0.4756857 0.06807553 -0.8913453 0.4374921 0.1187611 -0.8913337 0.4374921 0.1188485 -0.9347507 0.3550533 0.01335841 -0.9386913 0.3432996 0.03168785 -0.9393408 0.339416 0.04935216 -0.9593169 0.2762388 0.05833554 -0.9593167 0.2762395 0.05833739 -0.9611548 0.2705852 0.05445444 -0.9611374 0.2706455 0.05445957 -0.9600747 0.2744467 0.05418151 -0.9600725 0.2744549 0.05417835 -0.9465458 0.2128177 0.242404 -0.9548746 0.1936721 0.2251788 -0.9677428 0.1498629 0.2025217 -0.9566469 0.1978033 0.2137773 -0.956962 0.2707319 0.1045365 -0.9566904 0.2702665 0.1081646 -0.8214769 0.2570979 0.5089955 -0.9147431 0.1416732 0.3783833 -0.8583859 0.2342339 0.4564079 -0.9167163 0.2575926 0.3054136 -0.9167169 0.2575922 0.3054121 -0.7212498 0.375685 0.5819446 -0.7212435 0.3757103 0.5819361 -0.7378987 0.278182 0.6149147 -0.7093176 0.1171907 0.695079 -0.6028031 0.3986225 0.6911793 -0.7714525 0.1037355 0.6277737 -0.7966313 0.02462768 0.6039636 -0.7091083 0.1173802 0.6952607 -0.6052896 0.5993465 0.5238401 -0.62633 0.5796846 0.5212261 -0.6073679 0.7306315 0.3119003 -0.5864359 0.7803953 0.2169703 -0.5651069 0.7444419 0.3556129 -0.8773838 0.4384871 0.1947481 -0.8773899 0.4384822 0.1947315 -0.7756792 0.5282207 0.3454051 -0.7930885 0.5683902 0.218959 -0.7931048 0.5684043 0.2188643 -0.08154016 -0.9955457 0.04732745 -0.0152229 -0.9996797 -0.02022224 -0.1125777 -0.9927266 0.04266345 -0.09969985 -0.9932953 0.05851769 -0.01977074 -0.999738 0.01153856 -0.01960134 -0.9997379 0.01183247 -0.002577781 -0.9999955 0.001560449 -0.002539515 -0.9999953 0.001714348 -0.1225591 -0.9920409 0.02888345 -0.09772521 -0.9935958 0.05672019 -0.09774684 -0.9935957 0.05668288 -0.1675373 -0.9783613 0.1214097 -0.04427683 -0.9982266 0.03978961 -0.03909945 -0.9988659 0.02717006 -0.05892258 -0.9971138 0.0478788 -0.07277506 -0.9960656 0.05056905 -0.07277351 -0.9960655 0.05057126 -0.4755534 -0.7677407 0.429445 -0.5018814 -0.6693027 0.5478585 -0.3899638 -0.8488987 0.3567903 -0.4497487 -0.6707678 0.5897428 -0.2479326 -0.9387671 0.2392603 -0.2511548 -0.9353923 0.2489228 -0.126282 -0.990383 0.05651825 -0.2029606 -0.9364204 0.2862233 -0.02523303 -0.9994243 0.02267813 -0.03992074 -0.9981282 0.04633283 -0.685445 -0.2424415 0.6865765 -0.7275137 -0.419498 0.5429043 -0.72754 -0.4194973 0.54287 -0.7275049 -0.4193702 0.543015 -0.7066401 -0.2478322 0.662751 -0.7065387 -0.2472282 0.6630846 -0.6847879 -0.08837395 0.7233642 -0.6560305 -0.2434971 0.714376 -0.7275679 -0.4193657 0.5429341 -0.7077614 -0.4692398 0.5280982 -0.6657117 -0.6312375 0.3979538 -0.6657114 -0.6312374 0.3979545 -0.6445996 -0.6312713 0.4312632 -0.5720189 -0.7657665 0.2939323 -0.3075073 -0.9346985 0.1782637 -0.3074883 -0.9347054 0.1782602 -0.3041082 -0.9346566 0.1842154 -0.3294758 -0.9228387 0.1995357 -0.3291224 -0.9229921 0.1994091 -0.4715764 -0.8470777 0.2451021 -0.4567848 -0.8471363 0.2714917 -0.5573701 -0.7614718 0.3309067 -0.55742 -0.7614338 0.33091 -0.076581 -0.9956417 0.05322617 -0.1095702 -0.9933934 0.03411436 -0.1912631 -0.9673812 0.1661084 -0.220426 -0.9674416 0.1243739 -0.2999156 -0.9158955 0.2668066 -0.09624487 -0.9915931 0.08648729 -0.05641597 -0.9980992 0.02480447 -0.2362412 -0.9387505 0.2508735 -0.1716423 -0.9782631 0.1163624 -0.3719854 -0.8491649 0.3748946 -0.3168097 -0.9159724 0.2462241 -0.427715 -0.8136107 0.3938241 -0.443136 -0.8140373 0.3754648 -0.3766405 -0.8939232 0.2429882 -0.2380752 -0.9578685 0.1606488 -0.2252398 -0.9573487 0.1809712 -0.08155483 -0.9955458 0.04730385 -0.1073195 -0.9923493 0.06103718 -0.1282848 -0.9914569 0.02358412 -0.2472107 -0.9501888 0.1898111 -0.2854571 -0.9503448 0.1239317 -0.3871782 -0.8791247 0.2779079 -0.4166784 -0.8792967 0.2306869 -0.5702589 -0.6789686 0.4623922 -0.5279344 -0.6776722 0.511904 -0.5326401 -0.6668569 0.5211491 -0.08581554 -0.995067 0.04977315 -0.09548097 -0.993939 0.05448657 -0.07872617 -0.9909793 0.1084538 -0.1283549 -0.9914868 0.02188396 -0.2530274 -0.947521 0.1953999 -0.2957004 -0.9477401 0.1197907 -0.4051817 -0.8706547 0.2789051 -0.4407949 -0.8708242 0.217635 -0.5282619 -0.7681989 0.3616764 -0.5509427 -0.768413 0.325582 -0.6682277 -0.5209156 0.5311485 -0.6137524 -0.5196331 0.5943816 -0.6598056 -0.2433413 0.7109442 -0.08952122 0.994789 0.04879409 -0.1922549 0.9702301 0.1472808 -0.1203647 0.9927264 -0.002555012 -0.1157435 0.992596 0.03683197 -0.1075364 0.9930046 0.0487619 -0.1534767 0.9881172 -0.008324682 -0.1132142 0.9927493 0.04039257 -0.1106663 0.9929195 0.04317206 -0.4714648 0.8471338 0.2451229 -0.3381639 0.9190807 0.2023261 -0.314144 0.929411 0.193672 -0.3024266 0.9382596 0.1679499 -0.3024287 0.9382595 0.1679462 -0.4714689 0.8471337 0.2451153 -0.5134825 0.7931495 0.3274898 -0.55732 0.7615147 0.3308925 -0.6647171 0.6358771 0.392188 -0.6641398 0.63625 0.3925613 -0.6155939 0.6800116 0.398282 -0.5702683 0.7654718 0.2980719 -0.5571764 0.7615131 0.3311377 -0.6846411 0.5803433 0.4409856 -0.6937146 0.5767899 0.4313624 -0.5891833 0.6924095 0.4164521 -0.6648893 0.635783 0.3920487 -0.6649432 0.6357817 0.3919593 -0.6643797 0.6360918 0.3924117 -0.6926977 0.471121 0.5460906 -0.6713206 0.4910296 0.5551744 -0.6846849 0.580317 0.4409523 -0.6847346 0.5803402 0.4408445 -0.6245481 0.3240706 0.7105758 -0.7225759 0.3236309 0.6108578 -0.6658565 0.3720412 0.6466997 -0.6927024 0.4711495 0.54606 -0.6926754 0.4711213 0.5461186 -0.549826 0.4621152 0.6958023 -0.667881 0.1385314 0.731262 -0.6200338 -0.3812005 0.6857436 -0.6566904 0.138802 0.741277 -0.5805941 0.4615577 0.6707272 -0.169361 0.9734898 0.1537349 -0.4203335 0.7817549 0.4606291 -0.4203289 0.7817608 0.4606232 -0.1468762 0.9782302 0.1466048 -0.05084502 0.9978344 0.04172962 -0.05084675 0.9978343 0.04172754 -0.1544792 0.9783991 0.1373736 -0.1106465 0.9909025 0.07661294 -0.1538771 0.9740954 0.1657106 -0.09122592 0.9930108 0.07488203 -0.15192 0.9741392 0.167252 -0.1832764 0.9722879 0.1451415 -0.1109353 0.9912497 0.07153564 -0.1273105 0.9863501 0.1044296 0.01169604 0.9999102 -0.006539642 0.01166224 0.9999102 -0.006598591 -0.07247328 0.996575 0.03982245 -0.08781039 0.9945266 0.05662453 -0.4667933 0.8137636 0.3462553 -0.427715 0.8136107 0.3938241 -0.5169977 0.7219259 0.4599307 -0.4665088 0.7222709 0.5105823 -0.4150243 0.782007 0.4649946 -0.5185111 0.7859379 0.3368199 -0.4913268 0.7858303 0.3755909 -0.589055 0.6785923 0.4387789 -0.5416391 0.6783965 0.4963921 -0.6148936 0.5663391 0.5487859 -0.5512384 0.5665602 0.6124916 -0.6037444 0.4606543 0.6506077 -0.002659261 0.9999952 0.001585781 -0.002648949 0.9999952 0.001603901 -0.09434866 0.9942307 0.05102771 -0.05633103 0.9910938 0.120665 -0.1142272 0.9932276 0.02123862 -0.2251664 0.9573441 0.1810863 -0.2380752 0.9578685 0.1606488 -0.1046823 0.9940726 0.0293498 -0.1548911 0.9828696 0.09988003 -0.6189513 0.7070688 0.3419839 -0.704369 0.7097085 -0.01334589 -0.5282619 0.7681989 0.3616764 -0.4407949 0.8708243 0.217635 -0.4051817 0.8706547 0.2789051 -0.2957003 0.9477402 0.1197907 -0.2530274 0.947521 0.1953999 -0.1283549 0.9914868 0.02188396 -0.08139294 0.9912556 0.1038638 -0.09423506 0.9940793 0.05409568 -0.01809328 0.9997816 0.01045465 -0.01809245 0.9997816 0.01045608 -0.09785282 0.9938224 0.05236089 -0.06805509 0.9891818 0.1299534 -0.1282848 0.9914569 0.02358412 -0.2472106 0.9501888 0.189811 -0.2854571 0.9503448 0.1239317 -0.3871781 0.8791247 0.2779079 -0.3960582 0.8794602 0.2639843 -0.3744164 0.8952136 0.2416713 -0.3532176 0.8951392 0.2719619 -0.3232884 0.9158277 0.2382106 -0.3168097 0.9159724 0.2462241 -0.3855465 0.8272916 0.408586 -0.4323735 0.7809578 0.4507305 0.938605 -0.2436566 0.2442377 0.5975178 -0.2436553 -0.7639402 0.05108076 -0.9981176 0.03393959 0.0559954 -0.9981171 0.02504009 0.06112354 -0.9981182 -0.00490278 0.05146664 -0.9981172 -0.03336381 0.02929472 -0.9981166 -0.05389899 0 -0.9981172 -0.06133496 -0.01012271 -0.9981173 -0.06049305 -0.03779035 -0.9981167 -0.04831981 -0.05627053 -0.9981173 -0.02440333 -0.05108225 -0.9981176 0.03394156 0.1304152 -0.9742806 0.1837638 0.03911852 -0.998127 0.04703313 0.03911852 -0.998127 0.04703521 0.384499 -0.783167 0.488682 0.3847855 -0.7828044 0.4890372 0.1709173 -0.9734097 0.1525152 0.2327011 -0.9364907 0.2623649 0.1304265 -0.9742771 0.1837747 0.1304036 -0.9742848 0.18375 0.5545232 -0.4621267 0.6920569 0.5544981 -0.4622021 0.6920267 0.4914472 -0.6707014 0.5555531 0.3848211 -0.7827738 0.4890581 0.3847932 -0.7828016 0.4890357 0.5545169 -0.462142 0.6920518 0.6384496 -0.2444315 0.7298188 0.633367 -0.1388809 0.7612873 -0.474579 -0.6703739 0.5704154 -0.6202128 -0.2441877 0.7454586 -0.6201945 -0.244265 0.7454484 -0.6201927 -0.2442408 0.7454578 -0.620193 -0.2442341 0.7454599 -0.474537 -0.6704561 0.5703536 -0.4745544 -0.6704041 0.5704002 -0.4745206 -0.6704498 0.5703747 -0.224455 -0.9363922 0.2697954 -0.2244496 -0.9363963 0.2697857 -0.2244535 -0.9363945 0.2697886 -0.03907716 -0.9981312 0.04697978 -0.03911548 -0.998128 0.04701602 -0.03911578 -0.9981269 0.04703772 -0.04477679 -0.9981173 0.04191517 -0.05599212 -0.9981172 0.02503973 -0.05108761 -0.9981171 0.03394508 -0.05598998 -0.9981173 0.02503842 -0.05935704 -0.9981173 0.01544606 -0.06449776 -0.9979044 -0.005173146 -0.06112462 -0.9981302 -6.46047e-6 -0.06109333 -0.9981173 0.005429267 -0.06112438 -0.9981181 -0.004902362 -0.05952954 -0.9981172 -0.01477301 -0.05147069 -0.998117 -0.03336554 -0.05627399 -0.9981171 -0.02440416 -0.05146712 -0.9981173 -0.0333625 -0.04524922 -0.9981173 -0.04140579 -0.03778779 -0.9981173 -0.04831135 -0.02928632 -0.9981175 -0.05388796 -0.01998412 -0.9981174 -0.0579847 -0.01013046 -0.9981179 -0.06048321 0.01013123 -0.9981173 -0.06049245 -1.57555e-6 -0.9981172 -0.06133508 0.01013845 -0.9981174 -0.06048923 0.01998323 -0.9981174 -0.05798691 0.03778523 -0.9981175 -0.04831016 0.02928656 -0.9981174 -0.05388754 0.03778797 -0.9981175 -0.0483064 0.05626803 -0.9981175 -0.02440273 0.05146378 -0.9981175 -0.03336119 0.05627036 -0.9981172 -0.02440387 0.06109333 -0.9981173 0.005428493 0.06112462 -0.9981302 -8.63343e-6 0.06448847 -0.997905 -0.005172729 0.06109321 -0.9981173 0.005428612 0.05935752 -0.9981173 0.01544553 0.05108296 -0.9981175 0.03394067 0.04477393 -0.9981176 0.04191201 -0.05108481 -0.9981173 0.03394287 -0.2929669 -0.9360973 0.1946593 -0.2929615 -0.9360994 0.1946571 -0.6187149 -0.6694673 0.4111028 -0.6187136 -0.6694687 0.4111024 -0.05599087 -0.9981173 0.02503925 -0.3210921 -0.9360987 0.1435933 -0.3210984 -0.9360964 0.1435947 -0.6781209 -0.6694691 0.3032546 -0.6781247 -0.6694649 0.3032551 -0.06191325 -0.99807 -0.004795849 -0.3506925 -0.9360967 -0.02716493 -0.3506929 -0.9360966 -0.02716505 -0.74062 -0.6694706 -0.05736929 -0.7406188 -0.6694718 -0.05736881 -0.0514661 -0.9981173 -0.03336209 -0.2951554 -0.9360963 -0.1913297 -0.2951524 -0.9360978 -0.1913267 -0.6233322 -0.66947 -0.4040629 -0.6233338 -0.6694674 -0.4040648 -0.04525381 -0.9981169 -0.04141044 -0.2594919 -0.9360982 -0.2374535 -0.2594898 -0.9360994 -0.2374507 -0.5480253 -0.669467 -0.5014801 -0.5480296 -0.6694583 -0.501487 -0.01998454 -0.9981173 -0.05798631 -0.1146095 -0.9360974 -0.3325454 -0.1146109 -0.9360933 -0.3325564 -0.2420422 -0.6694567 -0.7023128 -0.2420407 -0.6694904 -0.7022812 0.01013231 -0.998117 -0.06049704 0.05810487 -0.9360905 -0.3469271 0.05809497 -0.9361005 -0.3469018 0.1226928 -0.6694737 -0.7326334 0.1226997 -0.6694566 -0.7326477 0.019988 -0.9981166 -0.05799865 0.1146025 -0.9361004 -0.3325393 0.1146073 -0.9360969 -0.3325475 0.2420412 -0.669457 -0.7023129 0.2420247 -0.6694875 -0.7022895 0.05146795 -0.9981172 -0.03336435 0.2951499 -0.9360973 -0.1913326 0.2951547 -0.9360955 -0.1913344 0.6233299 -0.6694652 -0.4040746 0.6233267 -0.6694687 -0.4040735 0.06191128 -0.9980702 -0.004796445 0.3506922 -0.9360966 -0.0271691 0.3506924 -0.9360964 -0.0271691 0.7406188 -0.6694712 -0.05737775 0.7406197 -0.6694703 -0.05737757 0.0510807 -0.9981176 0.03393954 0.2929723 -0.9360956 0.1946595 0.2929762 -0.9360935 0.1946635 0.6187149 -0.6694716 0.4110956 0.6187155 -0.6694705 0.4110963 -0.04477357 -0.9981175 0.04191249 -0.2567874 -0.9360974 0.2403786 -0.2567872 -0.9360975 0.2403784 -0.5423196 -0.6694517 0.5076652 -0.542307 -0.6694666 0.5076589 -0.7080386 -0.2436702 0.6628018 -0.7080382 -0.2436712 0.6628017 -0.7080539 -0.2436412 0.6627961 -0.8078002 -0.2436443 0.5367462 -0.8077979 -0.2436677 0.5367389 -0.8078184 -0.2436643 0.5367096 -0.8853628 -0.2436619 0.3959313 -0.885365 -0.2436549 0.3959307 -0.9386032 -0.243655 0.2442462 -0.05935788 -0.9981173 0.01544624 -0.3404068 -0.9360964 0.0885815 -0.3404068 -0.9360964 0.0885815 -0.7188999 -0.6694672 0.1870739 -0.7188963 -0.669471 0.187074 -0.9386034 -0.2436537 0.244247 -0.9386014 -0.2436596 0.2442485 -0.966054 -0.2436576 0.08585256 -0.7399221 -0.6694709 0.06575638 -0.7399226 -0.6694706 0.06575626 -0.350363 -0.9360964 0.03113645 -0.3503623 -0.9360966 0.03113651 -0.06109404 -0.9981173 0.005429387 -0.06109356 -0.9981173 0.005429387 -0.9660538 -0.2436586 0.08585268 -0.9660539 -0.2436583 0.08585256 -0.9669651 -0.2436556 -0.07490181 -0.966965 -0.2436563 -0.07490164 -0.9413099 -0.2436566 -0.2335957 -0.05952858 -0.9981173 -0.01477271 -0.3413881 -0.9360966 -0.08471947 -0.341391 -0.9360954 -0.08472084 -0.7209672 -0.6694735 -0.178918 -0.7209645 -0.6694769 -0.1789163 -0.9413091 -0.2436581 -0.2335976 -0.9413098 -0.2436551 -0.2335986 -0.05626946 -0.9981174 -0.02440255 -0.3227089 -0.9360945 -0.1399503 -0.3227047 -0.9360963 -0.1399474 -0.6815032 -0.669481 -0.2955476 -0.6815113 -0.6694701 -0.2955543 -0.8897916 -0.2436542 -0.3858802 -0.8897931 -0.2436442 -0.385883 -0.8897923 -0.2436596 -0.3858753 -0.8138281 -0.2436605 -0.527554 -0.8138342 -0.243642 -0.5275532 -0.8138263 -0.243637 -0.5275679 -0.7155098 -0.2436319 -0.6547436 -0.7155086 -0.2436577 -0.6547353 -0.5975281 -0.2436578 -0.7639314 -0.03778612 -0.9981175 -0.04830902 -0.2167022 -0.9360999 -0.2770505 -0.2167056 -0.9360972 -0.2770574 -0.4576659 -0.6694562 -0.5851243 -0.457661 -0.6694701 -0.585112 -0.5975291 -0.2436561 -0.7639311 -0.597531 -0.2436794 -0.7639221 -0.4631248 -0.243682 -0.8521352 -0.3547254 -0.6694579 -0.6526837 -0.354723 -0.6694701 -0.6526725 -0.1679647 -0.9360973 -0.3090466 -0.1679648 -0.9360972 -0.3090468 -0.02929216 -0.9981168 -0.05389612 -0.02928787 -0.9981175 -0.05388629 -0.4631252 -0.2436882 -0.8521332 -0.4631116 -0.243662 -0.8521481 -0.3160193 -0.2436623 -0.9169299 -0.3160158 -0.2436315 -0.9169393 -0.160176 -0.2436296 -0.9565502 -0.01013153 -0.9981172 -0.06049233 -0.05810385 -0.936093 -0.3469204 -0.05810445 -0.9360984 -0.3469057 -0.1227082 -0.6694919 -0.7326142 -0.1227061 -0.6694737 -0.7326309 -0.1602095 -0.2436125 -0.9565489 -0.1602149 -0.2436416 -0.9565407 -7.80816e-7 -0.9981177 -0.06132745 -4.4783e-6 -0.9360986 -0.3517378 0 -0.9360905 -0.3517591 0 -0.6694737 -0.7428358 0 -0.6694736 -0.7428358 0 -0.2436414 -0.9698654 0 -0.2436414 -0.9698654 -2.32523e-5 -0.2436984 -0.9698511 0.1601997 -0.2436981 -0.9565288 0.1601953 -0.2436738 -0.9565358 0.1601718 -0.2436857 -0.9565366 0.3159953 -0.243685 -0.9169321 0.3160018 -0.2436616 -0.9169362 0.4631142 -0.2436615 -0.8521469 0.02928662 -0.9981174 -0.05388778 0.167961 -0.9360967 -0.30905 0.1679615 -0.9360964 -0.3090507 0.3547072 -0.6694864 -0.6526643 0.3547192 -0.6694684 -0.6526764 0.463123 -0.2436785 -0.8521372 0.463122 -0.2436812 -0.852137 0.03779107 -0.9981169 -0.04831677 0.216704 -0.9360965 -0.2770609 0.216698 -0.9360993 -0.2770559 0.4576505 -0.6694687 -0.585122 0.4576618 -0.669454 -0.5851301 0.5975148 -0.2436787 -0.763935 0.5975262 -0.2436422 -0.7639377 0.7155015 -0.2436554 -0.654744 0.5480225 -0.6694643 -0.5014867 0.5480294 -0.6694561 -0.5014901 0.2594921 -0.9360976 -0.2374557 0.2594887 -0.936099 -0.2374536 0.04524904 -0.9981172 -0.04140663 0.04524618 -0.9981175 -0.0414043 0.7154965 -0.2436705 -0.6547437 0.8138164 -0.2436683 -0.5275686 0.8138203 -0.2436707 -0.5275616 0.8138241 -0.2436587 -0.5275611 0.8897869 -0.2436582 -0.3858885 0.05626946 -0.9981173 -0.02440321 0.3227043 -0.9360957 -0.1399521 0.3227009 -0.936097 -0.1399514 0.6815086 -0.6694693 -0.2955619 0.6815117 -0.669466 -0.2955623 0.8897869 -0.2436584 -0.3858884 0.8897891 -0.2436524 -0.3858869 0.941307 -0.2436535 -0.233611 0.7209662 -0.669472 -0.1789274 0.7209701 -0.6694678 -0.1789273 0.3413873 -0.9360964 -0.08472406 0.341386 -0.9360969 -0.084724 0.05952638 -0.9981175 -0.01477301 0.05952835 -0.9981172 -0.01477342 0.9413054 -0.2436589 -0.2336117 0.9413079 -0.2436547 -0.2336063 0.9669645 -0.2436548 -0.07491308 0.9669643 -0.2436554 -0.0749132 0.9660548 -0.2436586 0.08584046 0.06109374 -0.9981173 0.005428552 0.350363 -0.9360964 0.03113198 0.350363 -0.9360964 0.03113198 0.7399227 -0.6694714 0.0657469 0.7399228 -0.6694712 0.0657469 0.9660549 -0.2436583 0.08584022 0.9660559 -0.2436541 0.08584141 0.05936038 -0.998117 0.01544642 0.3404073 -0.9360965 0.08857882 0.3404065 -0.9360968 0.08857846 0.7188969 -0.6694723 0.1870669 0.7188935 -0.6694766 0.1870648 0.9386076 -0.2436472 0.2442371 0.9386041 -0.2436656 0.2442324 0.8853679 -0.2436568 0.395923 0.6781222 -0.6694716 0.3032459 0.6781159 -0.6694803 0.3032405 0.321102 -0.9360957 0.1435906 0.3210993 -0.936097 0.1435887 0.05598676 -0.9981176 0.02503603 0.05599629 -0.9981169 0.02504092 0.8853672 -0.2436617 0.3959215 0.8076772 -0.2436592 0.5369246 0.8078087 -0.2436371 0.5367364 0.8078051 -0.2436757 0.5367245 0.7080461 -0.2436804 0.6627899 0.04477691 -0.9981174 0.04191511 0.256798 -0.9360927 0.2403855 0.2567895 -0.9360981 0.2403734 0.5423148 -0.6694704 0.5076456 0.5423228 -0.6694537 0.507659 0.7080463 -0.2436803 0.6627899 0.7080457 -0.2436713 0.6627937 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.6148648 -0.5619364 0.5533253 0.1504399 -0.9771265 0.1503046 0.05277335 -0.9976664 0.04332333 0.153903 -0.9740815 0.1657678 0.1123997 -0.9927495 0.0426014 0.08952254 -0.9947944 0.04868274 0.2561604 -0.9554145 0.1468503 0.1757102 -0.9756553 0.1312348 0.1231287 -0.9921914 0.01988619 0.1132397 -0.9926971 0.04158222 0.2703541 -0.9573549 0.1018841 0.3147019 -0.9292021 0.1937681 0.2700536 -0.9575073 0.1012471 0.2818648 -0.950971 0.1273044 0.2818872 -0.9509696 0.1272643 0.5562016 -0.7610871 0.3337459 0.5574501 -0.7612671 0.3312429 0.5127931 -0.7941057 0.3262502 0.4730149 -0.845785 0.246789 0.4730171 -0.8457849 0.2467852 0.6700673 -0.5841323 0.4580385 0.6952605 -0.5726831 0.434335 0.6538395 -0.6244467 0.4272707 0.6671273 -0.6286336 0.3997013 0.6671002 -0.6286342 0.3997455 0.7095409 -0.476585 0.5190555 0.6975269 -0.3067314 0.6475895 0.7507563 -0.2563318 0.6088178 0.6681735 -0.3448355 0.6592668 0.7095534 -0.4765961 0.519028 0.7095409 -0.476585 0.5190553 0.656968 -0.1386322 0.7410628 0.6912909 0.01708233 0.7223747 0.5393356 -0.4622386 0.7038841 0.6251875 -0.3064919 0.7177768 0.6029078 -0.4606069 0.6514165 0.5630796 -0.5624857 0.6054348 0.5797048 -0.4616475 0.6714342 0.4129862 -0.7820219 0.4667806 0.05277317 -0.9976663 0.04332357 0.1099408 -0.9910911 0.07517606 0.1576718 -0.9772891 0.1415821 0.1689912 -0.9735096 0.1540166 0.4199272 -0.781705 0.4610841 0.1538853 -0.9740888 0.165742 0.0730884 -0.9955193 0.05999559 0.1519315 -0.974134 0.1672708 0.1864919 -0.9712103 0.1482275 0.1120405 -0.9910721 0.07227033 0.1292818 -0.9859163 0.1060917 -0.002588868 -0.9999958 -0.001378655 -0.002580344 -0.9999958 -0.001393437 0.07158434 -0.9967058 0.03812164 0.08962917 -0.9942958 0.0578143 0.004024505 -0.999989 0.002405762 0.004030823 -0.9999891 0.002394556 0.09559923 -0.9940887 0.05146247 0.07779639 -0.9928955 0.09003484 0.1167901 -0.9928942 0.02282649 0.2281973 -0.9562307 0.1831638 0.240979 -0.9567483 0.1629778 0.1066244 -0.9938344 0.0304026 0.1563684 -0.9825381 0.1008358 0.09447294 -0.9940491 0.05423265 0.08237183 -0.9911946 0.1036731 0.1290497 -0.9913908 0.02214318 0.2545049 -0.9469394 0.1962983 0.2972156 -0.9471595 0.1206299 0.4072079 -0.869284 0.2802268 0.4427522 -0.8694507 0.2191485 0.5304087 -0.7658383 0.3635357 0.5354769 -0.766003 0.3556742 0.52091 -0.7831565 0.3395863 0.4932119 -0.7830442 0.3789246 0.4691334 -0.8108253 0.3499659 0.4291769 -0.8106698 0.3982732 0.4321295 -0.780938 0.4509986 0.4679996 -0.7186634 0.514295 0.5179143 -0.7182562 0.464621 0.5421249 -0.6747624 0.5007958 0.5905503 -0.6749602 0.4423563 0.6405816 -0.5732002 0.5109763 0.6700595 -0.5841324 0.4580498 0.01779067 -0.9997889 0.01028233 0.01779103 -0.9997888 0.01028168 0.09863555 -0.9937301 0.05264467 0.07489848 -0.989717 0.121863 0.1299678 -0.991216 0.02447861 0.2495572 -0.9492791 0.1912859 0.2877637 -0.9494392 0.125528 0.3897863 -0.8773457 0.279877 0.3984624 -0.8776716 0.2663087 0.3774254 -0.893166 0.2445498 0.355829 -0.8930887 0.2752783 0.3264344 -0.9137261 0.2419609 0.3192616 -0.9138838 0.2507762 0.386431 -0.8257978 0.4107665 0.4318144 -0.781279 0.45071 0.1548436 0.9253682 -0.3460017 0.4709298 0.6327275 -0.6147204 -0.5253261 0.1166142 -0.8428723 0.5009528 0.2210701 -0.8367641 0.5933716 0.1801095 -0.7845193 0.6271231 0.1799325 -0.757853 0.5578011 0.2150878 -0.8016204 0.5996794 0.1373749 -0.7883608 0.5997756 0.1370714 -0.7883405 0.5981897 0.1442596 -0.7882629 0.5933307 0.1800713 -0.7845592 0.5021568 0.2200812 -0.836303 0.5355697 0.1767731 -0.8257822 0.5330857 0.1813439 -0.8263983 0.1599647 0.3387114 -0.9271925 0.2141281 0.2672033 -0.9395486 0.2163385 0.2576946 -0.9416959 0.2686986 0.3640958 -0.8917598 -0.2379112 0.2638068 -0.934775 -0.3691433 0.5657842 -0.737307 -0.4946827 0.4653505 -0.7339876 -0.1153649 0.3897991 -0.9136452 -0.1638339 0.2491444 -0.954508 -0.4441003 0.3483181 -0.8254994 -0.4441369 0.3481701 -0.8255422 -0.4588 0.2917395 -0.8392798 -0.5155214 0.3553614 -0.7797153 -0.5252825 0.1164082 -0.8429279 -0.5253422 0.1166649 -0.8428552 -0.52535 0.1165849 -0.8428614 -0.3691073 0.5658562 -0.7372697 -0.389047 0.6218129 -0.6796993 -0.4485725 0.5779688 -0.6817145 -0.2748312 0.7500721 -0.6015478 -0.2722971 0.7531385 -0.5988629 -0.2809048 0.7514212 -0.5970417 -0.1208077 0.8771836 -0.464709 -0.1207823 0.8772004 -0.4646838 -0.1970139 0.8679429 -0.4559172 -0.1772331 0.8915306 -0.4168475 -0.2809311 0.7513912 -0.5970668 -0.06508833 0.9768787 -0.2036458 -0.05786877 0.9381461 -0.3413693 0.04825663 0.9495389 -0.3099147 0.02265506 0.9974039 -0.06835353 0.3640252 0.9218506 -0.132956 0.04827672 0.9495446 -0.3098945 0.04557794 0.9693635 -0.2413652 0.3638991 0.9218937 -0.1330012 0.6773088 0.2408608 -0.695154 0.6281431 0.1682434 -0.7596911 0.6281526 0.1682488 -0.7596819 0.6614627 0.1715356 -0.7300977 0.6625613 0.1884124 -0.724923 0.6626217 0.1884292 -0.7248634 0.664055 0.1878111 -0.7237113 0.6509506 0.2403061 -0.7200807 0.6508827 0.2405839 -0.7200494 0.5173217 0.6653072 -0.5382794 0.5277379 0.5369142 -0.6581916 0.4835842 0.5239293 -0.7011736 0.484162 0.5202782 -0.7034897 0.4161339 0.4802662 -0.7721249 0.4170478 0.4770707 -0.7736114 0.3558998 0.4190477 -0.835305 0.3569996 0.4164426 -0.836138 0.314288 0.3557047 -0.8801689 0.354061 0.242901 -0.9031279 0.4512698 0.6615743 -0.598895 0.3554378 0.8344473 -0.4211433 0.2215998 0.7991215 -0.5588368 0.222598 0.7964058 -0.562306 0.1179196 0.73482 -0.667933 0.1190785 0.7323198 -0.6704685 0.02480161 0.6428373 -0.7656011 0.02601057 0.6407285 -0.7673269 -0.05424469 0.526713 -0.8483105 -0.05310136 0.5250861 -0.8493909 -0.1029717 0.4204384 -0.9014591 -0.01645141 0.294179 -0.9556088 -0.4980219 0.7594875 0.4185128 -0.5348285 0.7406451 0.4066983 -0.5222173 0.7547978 0.3969503 -0.6435817 0.5906022 0.486818 -0.4216077 0.7431584 0.5195793 -0.70682 0.3792478 0.5971403 -0.6610059 0.442018 0.6063755 -0.6793857 0.3853914 0.6244267 -0.6793712 0.3854334 0.6244163 -0.6204479 0.4426985 0.6473503 -0.6898369 0.1208389 0.7138087 -0.6876896 0.1336259 0.7136017 -0.6876873 0.1336421 0.7136007 -0.6814936 0.1224896 0.7215005 -0.07625776 0.9641279 -0.2542485 -0.697354 0.06429028 -0.7138377 0.2035287 0.2711364 -0.9407769 0.659066 0.03720349 -0.7511644 0.4905766 0.1921629 -0.8499459 0.4906497 0.1920864 -0.8499209 0.4996314 0.1329464 -0.8559752 0.4805242 0.1914189 -0.8558359 0.5397784 0.3005207 -0.7863374 0.09770143 0.3822626 -0.9188742 0.2178152 0.2105197 -0.9530152 0.21843 0.2081429 -0.9533966 -0.2136333 0.2564935 -0.9426409 -0.2136593 0.2565454 -0.9426209 -0.3076968 0.3344211 -0.8907779 -0.3412981 0.2497714 -0.9061622 -0.5327213 0.1773675 -0.8274956 -0.5398682 0.1896864 -0.8200984 -0.5972228 0.1798322 -0.7816555 -0.5971328 0.179748 -0.7817437 -0.5915991 0.1641358 -0.7893478 -0.5401375 0.190043 -0.8198385 -0.5401228 0.1900433 -0.8198482 -0.6142673 0.1797539 -0.7683517 -0.6252962 0.170304 -0.7615781 -0.6212319 0.1679885 -0.7654089 -0.6547324 0.1714263 -0.7361648 -0.6549453 0.1743906 -0.7352787 -0.676363 0.1892527 -0.7118403 -0.6539342 0.1829063 -0.7341085 -0.6643154 0.3568069 -0.6567907 -0.07969182 0.9629758 -0.2575402 0.2291532 0.7858135 -0.5744438 0.22922 0.7857016 -0.5745704 0.2172361 0.8712659 -0.4401183 0.07665425 0.897673 -0.4339441 0.02058684 0.9260381 -0.3768681 0.1784007 0.9219642 -0.3437371 0.178492 0.9219387 -0.3437582 0.229243 0.7857235 -0.5745313 0.3204584 0.7618628 -0.5629134 0.3612856 0.6330516 -0.68463 0.4379265 0.4276905 -0.7907599 0.4381063 0.4271569 -0.7909487 0.4287905 0.4565134 -0.7795732 0.4810159 0.4329982 -0.762323 0.3962336 0.6220282 -0.6753367 0.3612494 0.6330989 -0.6846055 0.3612605 0.6330915 -0.6846063 -0.4954995 0.745854 -0.4451767 -0.6030921 0.3558958 -0.7138754 -0.603169 0.3556689 -0.7139235 -0.531725 0.1782651 -0.8279432 -0.304333 0.3524265 -0.8849728 -0.3503488 0.4172354 -0.8385525 -0.3475835 0.4179414 -0.8393514 -0.4112557 0.4778021 -0.7762564 -0.4079577 0.4792818 -0.7770839 -0.4792656 0.5208336 -0.7064253 -0.475553 0.5232816 -0.707125 -0.5224095 0.5369536 -0.6623966 -0.3824029 0.7429999 -0.5492896 -0.07432466 0.9637592 -0.2562109 -0.07758897 0.9625542 -0.2597488 -0.07744604 0.9626033 -0.2596092 -0.1749296 0.3085269 -0.9349924 0.1156276 0.4096469 -0.9048866 0.05992633 0.5259298 -0.8484142 0.06223624 0.5256502 -0.8484212 -0.02018678 0.6416391 -0.766741 -0.01711755 0.6416984 -0.7667661 -0.1144226 0.7331736 -0.6703461 -0.110694 0.733767 -0.6703229 -0.2192338 0.7970101 -0.5627711 -0.2148697 0.7983234 -0.5625929 -0.3029975 0.8248749 -0.4772567 -0.452199 0.7462393 -0.4885111 0.6393782 -0.02416068 0.7685127 0.6929134 -0.03044509 0.7203777 0.719094 -0.1072893 0.6865805 0.6789929 -8.3781e-4 0.7341445 0.6789904 -5.73802e-4 0.7341469 0.6785246 4.61915e-4 0.7345775 0.7098264 -0.01036339 0.7043005 0.7045087 -0.01606827 0.7095135 0.6967058 -0.02462619 0.7169342 0.6967414 -0.02458471 0.716901 0.6967549 -0.0245524 0.7168889 0.7273519 0.08591097 0.680866 0.6399028 -0.01278173 0.7683495 0.6399117 -0.01272916 0.768343 0.7084391 -0.01006257 0.7057002 0.7088324 -0.01112985 0.7052891 0.7232361 -0.01113486 0.6905111 0.7300032 -0.01170635 0.6833435 0.7987341 0.0106312 0.6015902 0.832845 -0.01265966 0.5533615 0.8823322 0.009921789 0.4705225 0.8327358 0.009863615 0.5535829 0.8823211 0.01137995 0.4705104 0.9128017 -0.01320302 0.4081897 0.9445872 0.01171606 0.3280513 0.9677474 -0.007163703 0.251821 0.9446254 -0.007107257 0.3280736 0.9676874 -0.01333367 0.2518001 0.9840216 0.01163965 0.1776691 0.9959905 -0.01305311 0.08850133 0.9997352 0.00102216 0.02299094 0.9705583 -5.23025e-4 -0.2408655 0.9911636 0.01025474 -0.1322485 0.9997351 0.00102216 0.02299118 0.9957261 0.02648407 0.08847695 0.9969363 -0.01236027 -0.07723522 0.6159834 -0.01819193 -0.787549 0.6722668 0.003680825 -0.7402998 0.7824429 -0.05526942 -0.6202648 0.7398141 -0.02076494 -0.672491 0.8301723 0.1455532 -0.5381714 0.737681 -0.0119068 -0.6750444 0.7397224 -0.02085888 -0.6725889 0.7643553 0.004038572 -0.6447827 0.8391073 0.004048347 -0.5439509 0.8255441 -0.01060104 -0.5642381 0.91738 0.01118487 -0.3978553 0.9030729 -0.00298649 -0.429477 0.9174342 -0.003000557 -0.3978762 0.9029789 -0.0150848 -0.42942 0.9704347 0.01587814 -0.240841 0.9586178 -0.01562058 -0.2842674 0.9912157 -4.43009e-4 -0.1322546 0.7791189 -0.03011524 -0.6261525 0.7788807 -0.02841228 -0.6265282 0.7462087 -0.4278086 -0.5100513 0.7572084 -0.01528853 -0.6529945 -0.743885 -0.01611298 -0.6681134 -0.7516385 -0.02118062 -0.6592351 -0.7391437 -0.4366561 -0.5128334 -0.734086 -0.02613639 -0.6785534 -0.7336413 -0.02659255 -0.6790164 -0.8348584 0.1005603 -0.5412016 -0.7282876 -0.02208316 -0.6849157 -0.7377187 -0.008150398 -0.675059 -0.665738 0.002845823 -0.7461801 -0.6159696 -0.02028566 -0.7875087 -0.5778933 -0.0197612 -0.815873 -0.6159824 -0.01978522 -0.7875115 -0.5782297 0.01615703 -0.815714 -0.4774462 -0.01766747 -0.8784834 -0.44519 0.001515209 -0.8954348 -0.477503 0.001488924 -0.8786289 -0.4451628 0.01314711 -0.8953532 -0.3258007 -0.0142948 -0.9453305 -0.3013528 0.009375035 -0.9534665 -0.1651472 -0.007840394 -0.9862378 -0.300906 -0.007739365 -0.9536224 -0.1651844 -0.01012182 -0.9862108 -0.1503055 0.004820942 -0.9886279 0 -0.005188226 -0.9999866 0.004399418 -0.002993285 -0.9999858 -2.39751e-5 -0.002993762 -0.9999955 0.004388511 -5.00181e-4 -0.9999903 0.1651797 5.37638e-4 -0.9862633 0.158971 -0.00584042 -0.987266 0.1651476 -0.005840599 -0.9862515 0.1591112 -0.006588935 -0.9872387 0.3258139 0.007034063 -0.9454078 0.3097072 -0.01347815 -0.9507364 0.4774572 0.01429814 -0.8785386 0.4530248 0.001267194 -0.891497 0.4775161 0.001252114 -0.8786221 0.4529455 -0.02113217 -0.8912878 0.6159384 0.02233266 -0.7874777 0.5853749 -0.01548546 -0.8106149 0.5854312 -0.01548552 -0.8105743 -0.9433422 -0.007729947 0.3317315 -0.9433414 -0.007729947 0.3317338 -0.9676836 -0.01329565 0.2518165 -0.9836496 0.01185154 0.1797029 -0.9959902 -0.01299607 0.08851313 -0.999729 0.001321375 0.02324181 -0.9960736 0.001277267 0.08852034 -0.9996648 0.01141262 0.02324086 -0.9969366 -0.01241743 -0.07722324 -0.990951 0.01069432 -0.1337981 -0.9705612 6.15771e-5 -0.2408547 -0.9910072 1.43222e-4 -0.1338087 -0.9704956 -0.01155865 -0.2408415 -0.9577229 0.009696483 -0.2875291 -0.9173907 -0.0104233 -0.3978515 -0.9008203 -0.003316402 -0.4341794 -0.9174382 -0.003334879 -0.3978644 -0.9008021 0.008418262 -0.4341481 -0.8390848 -0.009007573 -0.5439263 -0.821595 0.005531191 -0.5700448 -0.771247 0.005520403 -0.6365122 -0.7771025 -0.03862375 -0.6281878 -0.9670857 0.03759866 0.251658 -0.9127964 -0.01331508 0.4081979 -0.8796217 0.0118907 0.4755253 -0.8328774 0.01047223 0.5533586 -0.8796325 0.0105257 0.4755373 -0.8328288 -0.01305645 0.5533766 -0.6937009 -0.03388112 0.7194659 -0.7273864 0.08523869 0.6809138 -0.6395068 -0.01312738 0.7686735 -0.6395061 -0.01313048 0.7686738 -0.6981844 -0.02278739 0.7155551 -0.6982131 -0.02271932 0.7155294 -0.6981603 -0.02278095 0.715579 -0.7057987 -0.01470273 0.7082599 -0.7085554 -0.01215189 0.7055507 -0.7299997 -0.01215809 0.6833392 -0.720267 -0.0159111 0.6935145 -0.7941745 0.0114904 0.6075812 -0.7062377 -0.007882475 0.707931 -0.7062467 -0.007906854 0.7079216 -0.7161293 -0.1082961 0.6895149 -0.6814928 -0.001133322 0.731824 -0.6814928 -0.001093268 0.731824 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -2.65782e-6 -1 4.89766e-6 -8.95591e-5 -1 9.00115e-5 5.07168e-6 -1 6.50456e-5 8.24408e-6 -1 7.25093e-5 0 -1 0 0 -1 0 0 -1 0 -5.51011e-5 -1 1.58569e-5 -6.30733e-5 -1 2.07126e-5 4.55058e-5 -1 -4.22614e-5 4.47904e-5 -1 -4.22355e-5 4.08537e-5 -1 -4.31375e-5 0.002484142 -0.9999967 6.20158e-4 -2.96473e-4 -1 2.39158e-4 -2.89693e-4 -0.9999999 2.5326e-4 -4.95137e-4 -0.9999998 -2.36808e-4 4.48157e-6 -1 6.47722e-5 1.07361e-4 -1 1.78071e-4 5.28559e-6 -1 6.52291e-5 6.29222e-6 -1 7.62773e-5 0 -1 0 1.48803e-4 1 8.72545e-5 4.26021e-6 1 -3.51611e-6 -1.70559e-4 1 1.60028e-4 -1.75792e-4 1 1.86418e-4 -2.27937e-5 1 -8.5552e-5 -2.22761e-5 1 -8.67749e-5 -2.68532e-5 1 -1.27904e-6 2.65372e-5 1 -5.48647e-5 -3.35377e-4 0.9999998 5.71734e-4 0 1 0 0 1 0 0 1 0 -1.75368e-4 0.9999999 1.86885e-4 -1.75573e-4 1 1.86469e-4 -1.75758e-4 1 1.86143e-4 -1.76039e-4 1 1.85334e-4 -7.00685e-6 1 -4.89754e-6 -1.91751e-5 1 1.65426e-5 -5.42125e-5 1 1.15434e-4 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 6.79069e-5 1 4.61709e-5 0.09758448 0.9913258 0.08803695 0.08326435 0.9953556 0.04831612 0.01722496 0.9996688 -0.01912015 0.08565628 0.9950842 0.04970395 0.6461945 0.6285331 0.4328725 0.7060895 0.4239397 0.5671973 0.7061414 0.4239389 0.5671332 0.7060982 0.4238464 0.5672562 0.6671606 0.6284988 0.3998574 0.6672036 0.6285119 0.399765 0.7072062 0.4693006 0.5287877 0.7644134 0.2952285 0.5731601 0.7643721 0.2953784 0.5731378 0.5575482 0.761183 0.3312712 0.5575413 0.7611883 0.3312706 0.5743532 0.7630512 0.296431 0.4020854 0.8879209 0.2234364 0.3036506 0.9363334 0.1762837 0.3036394 0.9363375 0.1762816 0.3036402 0.9363375 0.17628 0.1125165 0.9927375 0.04257029 0.0995506 0.9933254 0.05826026 0.09577357 0.9939017 0.05465215 0.07993835 0.9909467 0.1078637 0.01946818 0.9997461 0.01134335 0.01929724 0.999746 0.01163977 0.004582643 0.9999858 0.002723217 0.00458461 0.9999858 0.00274229 0.122451 0.9920787 0.02802485 0.09928297 0.9933911 0.05759423 0.09927892 0.993391 0.05760109 0.1713002 0.977257 0.125 0.04637926 0.9980472 0.04184138 0.04074054 0.9987667 0.02837866 0.0613982 0.9968583 0.0500372 0.07453852 0.9958654 0.05192583 0.07453942 0.9958653 0.05192458 0.4479876 0.7931968 0.4124876 0.4667785 0.7395364 0.484978 0.3931576 0.845964 0.3602387 0.4326362 0.7413746 0.5130199 0.23385 0.936761 0.2603708 0.1892269 0.9683946 0.1624962 0.1317324 0.9885616 0.07343345 0.1596122 0.9695918 0.1855149 0.6676166 0.3478686 0.6582367 0.678562 0.2064653 0.7049295 0.6498149 0.3489351 0.6752665 0.5928577 -0.4438182 0.6719711 0.6525934 0.06106638 0.7552434 0.473082 0.8457527 0.2467707 0.4585573 0.8458002 0.2726668 0.2972183 0.9471583 0.120634 0.4072056 0.8692861 0.2802238 0.4427498 0.8694527 0.2191452 0.530385 0.7658747 0.3634939 0.5525824 0.7660881 0.328271 0.6692507 0.5166541 0.5340151 0.6167262 0.5155318 0.5948746 0.6514515 0.3487505 0.6737833 0.2704908 0.9573197 0.1018515 0.3109758 0.9311807 0.1902537 0.12905 0.9913909 0.02214217 0.254508 0.9469379 0.1963015 0.1089233 0.9921103 0.06207138 0.1299682 0.991216 0.02447783 0.2495602 0.9492778 0.1912889 0.2877689 0.9494378 0.1255274 0.3898158 0.8773234 0.2799062 0.418923 0.8775041 0.233431 0.572035 0.6753956 0.4654212 0.5230971 0.6737408 0.5219606 0.6168692 0.3511192 0.7044061 0.07820481 0.9954484 0.05446529 0.1087292 0.9935414 0.0324586 0.1944839 0.9661854 0.1692975 0.2236822 0.9662614 0.1276927 0.3030465 0.9138081 0.2704026 0.08326226 0.9953556 0.04831939 0.2281845 0.9562299 0.183184 0.2409789 0.9567483 0.1629779 0.3786458 0.8924497 0.2452772 0.4454983 0.811081 0.3790498 0.4292076 0.8106332 0.3983148 0.319262 0.9138837 0.2507757 0.373938 0.8462838 0.3794392 0.1749143 0.9771715 0.1205852 0.2391116 0.9368458 0.2552366 0.05869066 0.9979178 0.0267474 0.09758549 0.9913257 0.08803594 -0.354605 0 -0.9350162 0.6156422 0.03655117 0.7871777 0.1650277 0.0134449 0.9861974 -0.9981467 -0.007588863 -0.06037729 -0.9160609 0.0547344 0.3972866 -0.96731 -0.08640992 0.2384213 -0.9662638 -0.09396207 0.2398023 -0.9952566 0.0556004 0.07983046 -0.9966322 0.05558937 0.06028461 -0.9967984 3.91454e-4 0.07995486 -0.9999999 3.92708e-4 1.41243e-4 -0.9160618 0.0547344 0.3972844 -0.8730487 -0.1668265 0.4582083 -0.8370398 0.07029277 0.542608 -0.6157252 0.0365054 0.7871147 -0.7473498 -0.05560761 0.6620997 -0.7307946 -0.1368346 0.6687418 -0.8370342 0.07029271 0.5426166 -0.615668 0.0365054 0.7871596 -0.5606003 -0.1615977 0.8121658 -0.4760714 0.07760387 0.8759759 -0.1652874 0.0133953 0.9861544 -0.3545358 -0.01975667 0.9348337 -0.3202705 -0.18365 0.9293543 -0.4760958 0.07760387 0.8759626 -0.1651647 0.0133953 0.9861751 -0.1191387 -0.1516595 0.9812265 2.56044e-5 0.08001023 0.996794 0.120522 0.01343137 0.9926198 0.1606193 -0.2336503 0.9589625 0 0.08001023 0.996794 0.3258012 -0.01465171 0.9453248 0.3512703 -0.1368211 0.9262232 0.4760669 0.07755988 0.8759822 0.5676884 0.0364862 0.8224346 0.5903398 -0.2861121 0.7547442 0.4760984 0.07755982 0.8759651 0.736909 -0.04756546 0.6743164 0.7433541 -0.1171481 0.6585597 0.8370463 0.07028758 0.5425985 0.8841367 0.05459374 0.4640278 0.862721 -0.3402003 0.374134 0.8370408 0.07028764 0.5426069 0.9667789 -0.09250026 0.2382904 0.9670386 -0.08511483 0.2399829 0.916064 0.0547443 0.3972781 0.9937674 0.06801956 -0.08831691 0.9937674 0.06801956 -0.08831483 0.9981466 -0.007605314 -0.06037729 1 3.89603e-4 1.05693e-4 0.9981755 3.88892e-4 0.06037801 0.9952579 0.05558347 0.07982635 0.9952581 0.05558341 0.07982355 0.9599239 -0.1270779 -0.2497946 0.969025 -0.06281065 -0.2388418 0.9121111 0.04096215 -0.4078916 0.9121089 0.04096215 -0.4078962 0.8735905 -0.1631556 -0.4584973 0.8304673 0.07640492 -0.5518029 0.7482169 -0.0280711 -0.6628601 0.71904 -0.1730139 -0.6730881 0.8304667 0.07640492 -0.5518038 0.5270744 -0.1995521 -0.8260578 0.6394456 0.008891463 -0.7687849 0.6393644 0.008891463 -0.7688525 0.2136872 0 -0.9769021 0.354605 0 -0.9350162 0.354605 0 -0.9350162 0.5680607 0 -0.8229867 0.04095309 0.01204025 -0.9990886 0.1102595 -0.106795 -0.9881486 0.1211917 -0.1419551 -0.9824262 0.1194328 -0.1353245 -0.9835767 0.1686237 -0.05590844 -0.9840936 0.1684226 -0.05618864 -0.9841122 -0.09826421 -0.08611404 -0.9914276 -0.05501496 -0.01194429 -0.9984141 0.04085505 0.01204025 -0.9990925 -0.2136864 0 -0.9769023 -0.1684681 -0.05613231 -0.9841075 -0.1196237 -0.1231766 -0.9851486 -0.1420472 -0.2217829 -0.9646942 -0.1153496 -0.1199907 -0.9860511 -0.639411 0.00889939 -0.7688136 -0.639428 0.00889939 -0.7687995 -0.5623713 -0.1411756 -0.8147441 -0.5379137 0 -0.8429999 -0.354605 0 -0.9350162 -0.7298858 -0.02144938 -0.6832324 -0.7418695 -0.1329257 -0.6572368 -0.8304776 0.07640236 -0.5517877 -0.8847147 0.04089409 -0.4643357 -0.8714337 -0.2978931 -0.3896961 -0.8304745 0.07640236 -0.5517923 -0.9937693 0.06801033 -0.08830225 -0.9937691 0.06801033 -0.08830428 -0.964815 -0.1121665 -0.2378042 -0.9662862 -0.05540221 -0.2514389 -0.912115 0.04097491 -0.4078813 -0.4647263 0 -0.8854545 0.6221397 -0.02891576 0.7823721 0.9865386 0.1232041 -0.1075282 0.990796 0.06204771 -0.1203049 0.9711898 -0.07955056 0.2246376 0.97119 -0.07955056 0.2246367 0.9795883 0.1620474 0.118943 0.9974412 -3.91693e-4 0.07148939 0.9999325 -3.92681e-4 -0.01161581 0.9062792 0.188955 0.3780927 0.9349558 0.01137465 0.3545818 0.8454917 -0.00787121 0.5339307 0.8455405 -0.00787121 0.5338532 0.8140462 0.1469642 0.5618988 0.7419551 -0.08149194 0.6654785 0.6628476 -0.02887421 0.7481976 0.6007804 0.261018 0.7556008 0.74196 -0.081492 0.6654731 0.4824747 0.03512936 0.8752052 0.4612339 0.1222462 0.878817 0.3286974 -0.07371979 0.9415537 0 0.08762812 0.9961532 1.26421e-5 0.08756828 0.9961585 0.1668749 -0.05618596 0.9843759 0.2389412 -0.05603432 0.9694159 0.1573923 0.3369969 0.9282568 0.3286987 -0.07371979 0.9415532 -0.3286835 -0.07371777 0.9415587 -0.3286852 -0.07371777 0.9415581 -0.2359742 0.1665623 0.9573783 -0.1668717 -0.05623525 0.9843737 -0.1668821 -0.05623519 0.9843719 -0.4773827 0.1486818 0.8660252 -0.4642905 0.04295045 0.8846409 -0.622062 -0.02893018 0.7824333 -0.6220862 -0.02893018 0.7824141 -0.6548864 0.1571322 0.7392113 -0.7419382 -0.08148854 0.6654978 -0.9711829 -0.07955658 0.2246655 -0.926044 0.138202 0.351202 -0.9228659 0.008202433 0.385034 -0.8455298 -0.007813155 0.5338711 -0.8229572 -0.007806658 0.5680497 -0.8253666 0.2172017 0.5211462 -0.7419378 -0.08148849 0.6654983 -0.9598028 -0.06790971 -0.2723363 -0.9867348 0.1095425 -0.1198118 -0.9926091 0.05502176 -0.108166 -0.9999325 -3.89577e-4 -0.01161068 -0.9927089 -3.86763e-4 0.1205361 -0.9613363 0.2666146 0.06891405 -0.9711844 -0.07955652 0.2246586 -0.9330873 -0.06420356 -0.3538731 -0.8395045 0.3679976 -0.3997623 -0.9598024 -0.06790977 -0.2723373 -0.8209136 0.07090789 -0.5666329 -0.8132421 0.111039 -0.5712335 -0.9009858 -0.0644198 -0.4290391 -0.587979 0 -0.8088762 -0.6271969 0.0570172 -0.776771 -0.6541506 0.1639099 -0.7383905 -0.7099475 -0.0465191 -0.7027165 -0.7099293 -0.04651898 -0.7027348 -0.155439 0.01251268 -0.9877663 -0.1250768 -0.007488965 -0.9921188 -0.1724071 0.02923667 -0.9845917 -0.1723173 0.02911347 -0.9846112 -0.2370777 0.1364865 -0.9618552 -0.2722727 0 -0.9622203 -0.4647263 0 -0.8854545 0.1376489 -0.004915356 -0.9904689 0.1022137 0.002649605 -0.994759 0.05487608 0.02349311 -0.9982168 0 0.124515 -0.9922177 -0.04058289 0.02976149 -0.9987328 -0.1251345 -0.007488965 -0.9921115 0.2673997 0.1882801 -0.9450122 0.1722862 0.0290637 -0.9846181 0.1724146 0.02923971 -0.9845903 0.1376722 -0.004915356 -0.9904656 0.5880321 0 -0.8088377 0.4647263 0 -0.8854545 0.4647263 0 -0.8854545 0.2393172 0 -0.9709414 0.8186363 0.1026682 -0.565061 0.8165324 0.06541228 -0.5735818 0.7099558 -0.04646766 -0.7027117 0.6624057 -0.04636889 -0.7477089 0.6765489 0.3062381 -0.6697013 0.6271353 0.05681389 -0.7768356 0.9597973 -0.06789046 -0.2723603 0.9597967 -0.06789046 -0.2723621 0.9217794 0.1676704 -0.3495846 0.9009767 -0.06443649 -0.429056 0.9009765 -0.06443655 -0.4290562 1.72796e-4 -1 1.83141e-4 0.001034438 -0.9999994 -3.32883e-4 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -2.31287e-5 -1 7.22426e-5 -2.96504e-5 -1 8.78749e-5 0 -1 0 0 -1 0 0 -1 0 7.57406e-5 -1 -7.54159e-5 6.89236e-5 -1 -7.38465e-5 6.6461e-5 -1 -7.39499e-5 2.06879e-5 -1 -2.07097e-4 0.00111109 -0.9999964 0.00245136 4.16706e-5 -1 -7.90865e-5 3.98807e-5 -1 -8.01734e-5 -7.29445e-5 -1 -2.83607e-4 -2.25188e-5 -1 7.11513e-5 -3.16944e-5 -1 8.13598e-5 8.22769e-5 -1 -4.14347e-5 1.72927e-4 -1 1.83271e-4 1.73499e-4 -1 1.81158e-4 4.85754e-5 1 9.97437e-5 2.15043e-5 1 2.14747e-5 -1.99191e-5 1 -5.38743e-5 -3.57016e-5 1 5.38984e-5 1.85695e-4 1 1.7475e-4 1.88436e-4 1 1.69849e-4 -2.87858e-5 1 5.0156e-5 -3.70362e-5 1 6.38127e-5 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 3.98937e-5 1 -8.85055e-5 7.58705e-5 1 -4.40437e-6 -1.89466e-5 1 -5.23504e-5 -1.91982e-5 1 -5.26069e-5 1.85758e-4 1 1.75237e-4 1.89713e-4 0.9999999 1.96923e-4 1.85594e-4 1 1.75143e-4 0 1 0 0 1 0 0 1 0 0.6889428 0.1336625 0.7123849 0.6781631 0.1544554 0.7184973 0.6660729 0.1390548 0.7328101 0.6639404 0.1571267 0.7310913 0.6525024 0.4423038 0.6153113 0.4977497 0.7437242 0.4462282 0.4946786 0.7437847 0.4495302 0.5051088 0.7039529 0.4993149 0.5459307 0.7426304 0.3878914 0.4382876 0.8199899 0.3681313 0.5051058 0.7039873 0.4992695 0.6445772 0.4485229 0.6191505 0.6493526 0.4424232 0.6185491 0.6474519 0.4478147 0.6166589 0.647387 0.4479743 0.616611 -0.6384863 0.3614676 -0.6794678 -0.02421963 0.9914728 -0.1280441 0.5258244 0.6513062 -0.5470914 0.6660652 0.1988638 -0.7188953 0.6660541 0.1988965 -0.7188965 0.6660447 0.1989659 -0.718886 0.6177052 0.442382 -0.6501834 0.6178393 0.4419773 -0.6503312 0.525852 0.6512727 -0.5471047 0.2311248 0.9277181 -0.2931219 0.2311499 0.9277095 -0.2931295 0.403974 0.8113872 -0.4224405 0.403903 0.8114632 -0.4223621 0.08301311 0.9917004 -0.09817916 0.08113718 0.9918618 -0.09811753 0.0811398 0.9918614 -0.09811925 0.07589745 0.9915611 -0.1051006 0.08008009 0.989093 -0.123622 0.08301621 0.9917004 -0.09817647 0.02515256 0.9914504 -0.1280361 0.04200577 0.9907605 -0.1289534 0.04223692 0.9909963 -0.1270527 0.05700469 0.9912921 -0.1187037 0.05974429 0.9912665 -0.1175645 0.06033623 0.9902414 -0.1256253 0.07029986 0.9916046 -0.1085273 0.02514022 0.9914504 -0.1280391 0.02197349 0.9904029 -0.1364519 0.008606851 0.99167 -0.128517 0.008601009 0.9916699 -0.1285175 6.10395e-4 0.9902753 -0.1391198 -0.00771594 0.9916768 -0.1285204 -0.01962751 0.9914368 -0.1291037 -0.02656489 0.9897407 -0.1403837 -0.007713198 0.9916769 -0.1285207 -0.04210549 0.9906679 -0.1296311 -0.04031699 0.9910112 -0.1275591 -0.05631601 0.9912617 -0.1192846 -0.05628794 0.9912619 -0.119296 -0.06105661 0.9905503 -0.1228088 -0.06960815 0.9915909 -0.1090972 -0.1409291 0.9815961 -0.1288733 -0.1409511 0.9815896 -0.1288981 -0.1409395 0.9815922 -0.1288903 -0.06960755 0.9915909 -0.1090975 -0.08032554 0.9903067 -0.1133153 -0.08230841 0.9916876 -0.09889882 -0.06361168 0.9913944 -0.1144148 -0.02072304 0.9994752 -0.02489751 -0.4219375 0.7705044 -0.4777989 -0.4219551 0.7704784 -0.4778253 -0.2852742 0.9044317 -0.3172098 -0.285497 0.9042734 -0.3174602 -0.550487 0.5857936 -0.5948194 -0.5504778 0.585851 -0.5947713 -0.5505231 0.585757 -0.5948221 -0.6762478 0.1195499 -0.7269091 -0.6384544 0.3615954 -0.6794297 -0.6609771 0.1194635 -0.7408359 -0.6800739 0.05239838 -0.7312687 -0.5772144 0.05232208 -0.8149146 -0.5775167 0.0522964 -0.8147022 -0.5775147 0.05227148 -0.8147053 -0.4445819 0.05227053 -0.8942118 -0.4445791 0.05228072 -0.8942126 -0.4445912 0.05233573 -0.8942034 -0.300953 0.05233931 -0.9522016 -0.3009566 0.05231469 -0.9522018 -0.3005037 0.05226218 -0.9523477 -0.1500882 0.05225944 -0.9872904 -0.1501011 0.0523616 -0.9872831 0.004393398 0.0523625 -0.9986185 0.004379689 0.05231469 -0.9986211 0.004382491 0.05230367 -0.9986217 0.1587561 0.05230343 -0.9859315 0.1587575 0.05231362 -0.9859307 0.1588972 0.05227148 -0.9859104 0.3093072 0.05227142 -0.9495245 0.3093125 0.052235 -0.9495248 0.4524067 0.05223792 -0.8902806 0.4524259 0.05231577 -0.8902662 0.4524263 0.05231434 -0.8902661 0.5846435 0.05231148 -0.8096021 0.5846416 0.05229032 -0.8096048 0.5847014 0.05225479 -0.8095639 0.668896 0.05238914 -0.7415077 0.6718049 0.03724628 -0.7397912 0.6177002 0.4424091 -0.6501696 0.6339219 0.2481162 -0.7325171 0.5672472 0.2474284 -0.7854998 0.5672428 0.2474021 -0.7855111 0.4389522 0.2474011 -0.8637788 0.4389591 0.2474311 -0.8637666 0.300107 0.2474327 -0.9212561 0.3001012 0.2474128 -0.9212633 0.154032 0.2474129 -0.9565882 0.1540325 0.2474145 -0.9565877 0.004261136 0.2474147 -0.9689003 0.004249334 0.2473844 -0.9689081 -0.1456242 0.2473846 -0.9579116 -0.1456218 0.2473902 -0.9579105 -0.2920041 0.2473909 -0.9238677 -0.2920009 0.247398 -0.9238666 -0.4313499 0.2473987 -0.8676007 -0.4313484 0.247402 -0.8676006 -0.5603297 0.2474027 -0.7904572 -0.5603301 0.2474017 -0.7904572 -0.6213522 0.248103 -0.7432135 -0.6762289 0.1196182 -0.7269154 0.525821 0.651312 -0.5470876 0.5474938 0.5228316 -0.6533741 0.4994666 0.5216922 -0.6916434 0.4994667 0.5216963 -0.6916402 0.3865072 0.5216972 -0.7605553 0.3865042 0.5216772 -0.7605705 0.2642501 0.5216763 -0.8111879 0.2642508 0.5216786 -0.8111862 0.135619 0.521678 -0.8422943 0.135626 0.5216968 -0.8422815 0.003751814 0.521697 -0.8531225 0.003751933 0.5216973 -0.8531224 -0.1282278 0.5216972 -0.8434392 -0.1282209 0.5217096 -0.8434326 -0.2570971 0.5217093 -0.8134621 -0.2571117 0.5216863 -0.8134722 -0.3798106 0.5216864 -0.7639289 -0.3798056 0.5216935 -0.7639265 -0.493373 0.5216932 -0.6960024 -0.4933739 0.521692 -0.6960027 -0.5431514 0.5228351 -0.6569857 -0.638453 0.3615962 -0.6794305 0.4039558 0.8113971 -0.4224389 0.4105625 0.757225 -0.5079851 0.3829882 0.7563372 -0.5303527 0.3829876 0.7563412 -0.5303475 0.2963657 0.7563406 -0.5831947 0.2963664 0.7563521 -0.5831796 0.2026236 0.7563531 -0.6219918 0.2026215 0.7563451 -0.6220022 0.1039971 0.7563452 -0.6458534 0.103992 0.7563341 -0.645867 0.002868533 0.7563335 -0.6541798 0.002876818 0.7563463 -0.654165 -0.09831541 0.7563467 -0.6467409 -0.09832584 0.756334 -0.6467542 -0.197153 0.7563342 -0.6237702 -0.1971408 0.7563467 -0.6237589 -0.2912347 0.7563467 -0.5857661 -0.2912299 0.7563511 -0.5857629 -0.3783063 0.7563506 -0.5336836 -0.3783127 0.7563452 -0.5336866 -0.4209811 0.757314 -0.4992499 -0.4074219 0.7697289 -0.4914517 0.2526153 0.9286167 -0.2717658 0.2719109 0.9165984 -0.2931071 0.2344627 0.9163033 -0.3246774 0.234463 0.9163028 -0.3246786 0.1814364 0.9163027 -0.3570297 0.1814366 0.9163007 -0.3570349 0.1240426 0.9163002 -0.3807982 0.1240448 0.9163078 -0.3807793 0.06366997 0.9163083 -0.39538 0.06366688 0.9163037 -0.3953909 0.001757085 0.9163037 -0.4004803 0.001756072 0.9163028 -0.4004826 -0.06019395 0.9163025 -0.3959372 -0.06018757 0.9163072 -0.3959277 -0.1206917 0.916307 -0.3818571 -0.1206926 0.9163066 -0.3818581 -0.1782861 0.9163064 -0.3586035 -0.1782969 0.916301 -0.3586122 -0.2316064 0.9163011 -0.3267272 -0.2316013 0.9163034 -0.3267243 -0.2479408 0.9167004 -0.3133458 -0.2855247 0.904262 -0.3174684 -0.7371677 0.4415783 -0.511461 -0.81428 0.1332573 -0.5649695 -0.7139177 0.1335434 0.6873774 -0.6460239 0.4424192 0.6220276 -0.4811196 0.7442603 0.4632499 -0.7139119 0.1335596 0.6873803 -0.7139146 0.1335694 0.6873755 -0.7139031 0.1335723 0.687387 -0.7871472 0.1332443 0.6022003 -0.7871432 0.1332607 0.6022019 -0.9908159 0.1332414 0.02303457 -0.9749475 0.133241 0.1781131 -0.9749475 0.1332408 0.1781131 -0.9349582 0.1332411 0.3287857 -0.9349586 0.1332406 0.3287848 -0.9349583 0.133246 0.3287832 -0.8718374 0.1332483 0.4713218 -0.8718373 0.1332664 0.471317 -0.871836 0.1332566 0.4713223 -0.990816 0.1332405 0.0230351 -0.9908159 0.1332405 0.0230351 -0.9821714 0.1332411 -0.1326127 -0.9821717 0.1332396 -0.1326123 -0.9821716 0.133237 -0.1326158 -0.9492284 0.1332316 -0.2849819 -0.9492276 0.1332444 -0.2849786 -0.8927972 0.1332535 -0.4302985 -0.8928045 0.1332205 -0.4302936 -0.8927926 0.133246 -0.4303101 -0.7455953 0.1335625 -0.6528773 -0.7510542 0.1978736 -0.6298918 -0.7516522 0.02030324 -0.6592472 -0.7107927 0.3650465 -0.601261 -0.6868326 0.5128395 -0.5150308 -0.6838328 0.442624 -0.5800489 -0.6374409 0.5191931 -0.5693046 -0.7252008 0.2048695 -0.6573525 -0.7250788 0.2056582 -0.6572408 -0.725217 0.2047842 -0.6573612 -0.507613 0.7695689 -0.387418 -0.5751285 0.6536224 -0.49194 -0.6374982 0.5190681 -0.5693542 -0.710531 0.7027312 0.036255 -0.6686484 0.7434163 0.01554518 -0.6579406 0.7434152 0.1201987 -0.6579409 0.7434152 0.120199 -0.6579396 0.7434163 0.1201981 -0.6309522 0.7434165 0.2218807 -0.6309528 0.743416 0.2218813 -0.6309567 0.7434142 0.221876 -0.5883604 0.7434136 0.3180696 -0.5883579 0.7434157 0.3180694 -0.4811319 0.7442458 0.4632605 -0.4811271 0.7442547 0.4632512 -0.5311985 0.743423 0.406387 -0.5311977 0.7434244 0.4063856 -0.5311996 0.7434149 0.4064003 -0.6460093 0.4424883 0.6219937 -0.6460088 0.4424464 0.6220241 -0.712608 0.4415591 0.5451747 -0.7126071 0.4415645 0.5451716 -0.7892759 0.441566 0.4266884 -0.7892739 0.441574 0.426684 -0.8464152 0.4415733 0.2976479 -0.846418 0.4415652 0.297652 -0.8826193 0.4415686 0.1612457 -0.8826182 0.4415714 0.1612444 -0.8969835 0.4415719 0.02085363 -0.8969836 0.4415718 0.02085363 -0.8891572 0.4415729 -0.1200535 -0.889156 0.4415752 -0.1200543 -0.8593301 0.4415786 -0.2579922 -0.8593337 0.4415724 -0.2579909 -0.8082483 0.4415726 -0.3895487 -0.6675591 0.7443263 -0.01852911 -0.6628068 0.7434234 -0.0894919 -0.662807 0.7434231 -0.08949249 -0.6628085 0.7434218 -0.08949184 -0.6405782 0.7434207 -0.1923156 -0.6405735 0.7434245 -0.1923163 -0.6405746 0.7434238 -0.1923151 -0.6024939 0.7434239 -0.2903825 -0.8082472 0.4415746 -0.389549 -0.7371698 0.4415751 -0.511461 -0.8142862 0.1332356 -0.5649657 -0.814285 0.1332328 -0.5649681 -0.4812174 0.7718051 -0.4156283 -0.5124545 0.7444378 -0.4280219 -0.5495049 0.7434257 -0.3812643 -0.5495157 0.7434178 -0.3812645 -0.5495161 0.7434145 -0.3812704 -0.602503 0.7434166 -0.2903828 0.8475548 0.4415967 0.2943521 0.8601836 0.4416104 -0.2550771 0.8745069 0.1332726 0.4663434 0.9908202 0.1332519 0.0227862 0.9823769 0.1332474 -0.1310752 0.564142 0.642098 -0.5190895 0.4831075 0.7442064 0.4612635 0.4470595 0.8099332 -0.3796654 0.5264235 0.7444185 -0.4107549 0.5115063 0.8023671 -0.3075197 0.5641372 0.6421055 -0.5190854 0.7591853 0.1136397 -0.6408775 0.6991758 0.3788648 -0.6063124 0.6991471 0.3789541 -0.6062896 0.6774088 0.4424454 -0.5876729 0.7428371 0.3709123 -0.5573303 0.5643486 0.6418591 -0.5191605 0.7521775 0.1160759 -0.6486566 0.7542695 0.1335763 -0.6428333 0.818211 0.1332352 -0.5592666 0.8182268 0.1332628 -0.5592369 0.8950285 0.1332487 -0.4256392 0.9823769 0.1332468 -0.1310761 0.9362251 0.1332518 0.3251562 0.9753121 0.1332527 0.1760966 0.874507 0.1332502 0.4663496 0.7168013 0.1335563 0.6843674 0.7916553 0.1332578 0.5962585 0.7167882 0.1335663 0.6843791 0.7167876 0.133564 0.6843802 0.6486408 0.4423965 0.6193146 0.6486404 0.4424111 0.6193044 0.6486254 0.4424396 0.6192999 0.4831076 0.7442052 0.4612655 0.8102482 0.4416091 -0.3853302 0.8950231 0.1332613 -0.4256467 0.8950231 0.1332556 -0.4256488 0.9823758 0.1332572 -0.1310735 0.889328 0.4416061 -0.1186586 0.8893305 0.4416004 -0.1186611 0.8829323 0.4416068 0.1594175 0.9753123 0.1332504 0.1760972 0.9908201 0.1332527 0.0227859 0.8745092 0.1332644 0.4663411 0.7916842 0.4415941 0.4221738 0.7916781 0.4416041 0.4221747 0.8182266 0.1332567 -0.5592386 0.740724 0.4416123 -0.5062673 0.7407242 0.4416114 -0.5062678 0.5521491 0.743448 -0.3773811 0.5521534 0.743441 -0.3773884 0.5521533 0.7434434 -0.377384 0.6039747 0.7434454 -0.2872344 0.81025 0.441603 -0.3853335 0.8601864 0.4416029 -0.2550809 0.9501845 0.1332504 -0.281769 0.9501864 0.1332403 -0.2817672 0.6039712 0.7434497 -0.2872303 0.641194 0.7434501 -0.1901375 0.6411933 0.7434504 -0.1901382 0.6411956 0.7434479 -0.1901406 0.6629169 0.7434498 -0.08845132 0.6629153 0.7434513 -0.08845031 0.6629146 0.7434523 -0.08844792 0.9908201 0.1332522 0.02278625 0.8969737 0.4416025 0.02062803 0.8969736 0.4416027 0.02062809 0.6686136 0.743451 0.01537638 0.6686131 0.7434515 0.01537662 0.65815 0.7434498 0.1188324 0.6581495 0.7434502 0.1188315 0.8829331 0.4416054 0.1594171 0.847548 0.4416084 0.2943543 0.9362266 0.1332497 0.3251524 0.936226 0.1332665 0.3251474 0.6581515 0.7434487 0.1188306 0.6317782 0.7434468 0.2194157 0.6317753 0.7434501 0.2194128 0.6317671 0.743453 0.2194266 0.5901239 0.743453 0.3146928 0.5901309 0.7434473 0.3146932 0.5342167 0.7434461 0.4023685 0.791655 0.1332491 0.5962609 0.7166715 0.4416046 0.5397846 0.7166728 0.4416024 0.5397846 0.5342153 0.7434512 0.402361 0.5342158 0.7434509 0.4023609 -0.452265 0.3498383 -0.8204082 0.7093656 0.06112837 0.702185 0.9602282 0.06105023 0.2724605 0.8044967 0.06113684 -0.5908023 0.4818435 0.06103849 -0.8741288 -2.36421e-5 0.06103754 -0.9981355 -0.1668044 0.06105333 -0.9840979 -0.9011654 0.06105852 0.4291535 -0.1414961 0.9742994 0.1752701 -0.141475 0.9743053 0.175254 -0.1608781 0.969664 0.1840379 -0.1513099 0.9741515 0.1677323 -0.5437014 0.4622943 0.7004803 -0.5437276 0.4622142 0.7005128 -0.4131227 0.7820953 0.4665367 -0.4131326 0.7820758 0.4665607 -0.4192968 0.7415757 0.5236943 -0.3832062 0.7828941 0.4901323 -0.3832122 0.7828867 0.4901398 -0.5437837 0.4621505 0.7005114 -0.6116811 0.3508872 0.7090306 -0.6130324 0.139024 0.7777298 -0.6179819 0.06129455 0.7837994 -0.6222607 0.1391055 0.7703513 0.5882545 0.3517214 0.7281819 0.588467 0.3508163 0.7284467 0.5884726 0.3507848 0.7284573 0.5884811 0.3507719 0.7284567 0.5885113 0.3507063 0.7284638 0.421574 0.7415822 0.5218534 0.4215574 0.7416217 0.5218108 0.4215373 0.7416397 0.5218017 0.1536015 0.9696674 0.1901363 0.1536474 0.9696447 0.1902147 0.1535525 0.9696681 0.1901718 -0.709369 0.06112843 0.7021815 -0.816757 0.06111735 0.5737358 -0.9011684 0.06108456 0.4291436 -0.992256 0.0610851 0.1081508 -0.9602175 0.06111621 0.2724833 -0.9922552 0.06108891 0.108156 -0.9963759 0.06105637 -0.05922245 -0.9211761 0.06113767 -0.3843132 -0.9724572 0.06110578 -0.2249293 -0.9211851 0.06104201 -0.3843072 -0.8439885 0.06103557 -0.5328773 -0.7430471 0.06099766 -0.6664535 -0.4818661 0.06112802 -0.8741101 -0.6211922 0.06112182 -0.7812711 -0.3289903 0.06103837 -0.9423586 0.1668208 0.06103777 -0.9840961 0 0.06103742 -0.9981355 0.1668032 0.06105303 -0.9840981 0.6211755 0.06092762 -0.7812995 0.4818649 0.06091213 -0.8741258 0.6211917 0.06098681 -0.781282 0.743034 0.06099778 -0.6664682 0.9211717 0.06114238 -0.3843234 0.8439667 0.06117111 -0.532896 0.9724547 0.0610513 -0.2249542 0.9211739 0.06104433 -0.3843335 0.972454 0.06106239 -0.2249546 0.9922591 0.0610758 0.1081279 0.9922585 0.06108152 0.1081301 0.9980457 0.06127321 0.01226419 0.960227 0.06107407 0.2724593 0.9011694 0.06105846 0.4291453 0.8167768 0.06105709 0.5737139 0.627229 0.06116795 0.7764291 0.6272056 0.06131786 0.7764362 0.7093904 0.06111896 0.7021608 -0.5830278 0.3498414 -0.7332731 -0.6211919 0.06111192 -0.7812719 -0.6212094 0.06098699 -0.781268 -0.8167583 0.06105691 0.5737403 -0.766587 0.3498076 0.538497 -0.7665843 0.3498215 0.5384918 -0.5498809 0.7405598 0.3862671 -0.5498761 0.7405663 0.3862615 -0.9922565 0.06107693 0.1081514 -0.9313069 0.3498048 0.1015082 -0.9313076 0.3498033 0.1015085 -0.6680282 0.7405651 0.07281219 -0.6680244 0.7405687 0.0728107 -0.921185 0.06103491 -0.3843082 -0.864602 0.3497958 -0.3607024 -0.8645927 0.349818 -0.3607033 -0.6201701 0.740572 -0.2587315 -0.6201837 0.7405601 -0.2587335 -0.5002533 0.7405576 -0.4486883 -0.6973924 0.3498362 -0.6255067 -0.6974049 0.3498055 -0.6255097 -0.7430458 0.06110054 -0.6664456 -0.7511692 0.06113046 -0.6572731 -0.3244187 0.7405592 -0.5884936 -0.3244167 0.7405617 -0.5884916 -0.4182155 0.7405623 -0.5259878 -1.18286e-5 0.06115853 -0.9981281 -1.1102e-5 0.3498114 -0.9368202 -1.12248e-5 0.3498107 -0.9368203 -8.05169e-6 0.7405576 -0.6719928 -8.24887e-6 0.740557 -0.6719936 0.48185 0.06108456 -0.874122 0.4522469 0.3498359 -0.8204191 0.452247 0.3498175 -0.820427 0.324404 0.7405563 -0.5885052 0.3244035 0.740558 -0.5885035 0.8439814 0.0609827 -0.5328944 0.7921264 0.3498326 -0.5001529 0.7921358 0.3497877 -0.5001695 0.568205 0.7405561 -0.3587753 0.5681952 0.7405687 -0.3587648 0.9211721 0.06106531 -0.3843345 0.8645927 0.3497921 -0.3607283 0.864587 0.3498135 -0.3607213 0.6201687 0.7405684 -0.2587456 0.620168 0.7405692 -0.258745 0.9922603 0.06105875 0.1081272 0.9313098 0.3498039 0.1014854 0.931309 0.349806 0.1014857 0.6680277 0.7405672 0.07279568 0.6680253 0.7405692 0.07279598 0.8167721 0.06111741 0.5737141 0.7666074 0.3497928 0.5384777 0.7665995 0.3498113 0.5384767 0.54988 0.7405704 0.386248 0.5498883 0.7405626 0.3862511 -0.1742904 0.9694629 0.1725245 -0.4775838 0.7405579 0.4727449 -0.4775817 0.7405617 0.4727412 -0.6657982 0.3498087 0.65905 -0.6657984 0.3498066 0.6590508 -0.7093702 0.06112229 0.7021811 -0.7093701 0.06111925 0.7021812 -0.174294 0.9694612 0.1725299 -0.1742948 0.9694635 0.1725164 -0.2006753 0.9694629 0.1409648 -0.20068 0.9694612 0.1409698 -0.2214197 0.9694612 0.1054428 -0.9011685 0.06107902 0.4291439 -0.84581 0.3498175 0.4027817 -0.8458136 0.3498032 0.4027866 -0.606702 0.7405664 0.2889189 -0.6067007 0.7405679 0.2889177 -0.2214201 0.9694611 0.1054427 -0.2214206 0.9694611 0.1054431 -0.2359295 0.9694612 0.06695026 -0.6464635 0.7405616 0.1834485 -0.6464579 0.7405675 0.1834452 -0.9012389 0.3498045 0.2557443 -0.9012392 0.3498039 0.2557446 -0.9602196 0.06109178 0.2724815 -0.9602201 0.06107425 0.2724834 -0.2359277 0.9694616 0.06694936 -0.2359272 0.9694619 0.06694871 -0.2437996 0.9694616 0.0265727 -0.2438009 0.9694611 0.02657318 -0.2444351 0.9696615 0.002839505 -0.996375 0.0610699 -0.05922311 -0.9351714 0.3498067 -0.05558526 -0.9351722 0.3498045 -0.05558484 -0.6707993 0.7405665 -0.03987103 -0.6707984 0.7405673 -0.03987121 -0.2572953 0.9662118 -0.01529318 -0.2443983 0.9695167 -0.01751667 -0.2389361 0.9694613 -0.05526643 -0.654694 0.7405701 -0.1514321 -0.6546968 0.7405677 -0.151432 -0.9127269 0.3498002 -0.2111147 -0.9127256 0.3498035 -0.211115 -0.9724583 0.06108045 -0.2249313 -0.9724594 0.06106984 -0.2249294 -0.238938 0.9694609 -0.05526643 -0.2389375 0.9694609 -0.05526655 -0.2263398 0.9694606 -0.09442633 -0.2263359 0.9694616 -0.09442561 -0.2073584 0.9694613 -0.1309475 -0.8439858 0.0610693 -0.5328776 -0.7921379 0.3498225 -0.5001417 -0.7921451 0.3498052 -0.5001422 -0.5682146 0.7405574 -0.3587576 -0.568212 0.7405598 -0.3587568 -0.2073665 0.9694623 -0.1309268 -0.2073692 0.9694617 -0.1309278 -0.1825661 0.9694617 -0.1637482 -0.1825654 0.9694622 -0.1637467 -0.5002554 0.7405555 -0.4486894 -0.4182237 0.7405532 -0.5259941 -0.5830367 0.3498188 -0.733277 -0.4522712 0.3498207 -0.8204122 -0.4818746 0.06102955 -0.8741122 -0.4818761 0.06104016 -0.8741107 -0.1825683 0.9694615 -0.1637478 -0.1526287 0.9694614 -0.1919609 -0.1526282 0.9694618 -0.1919599 -0.1526436 0.9694598 -0.1919571 -0.1183997 0.96946 -0.2147763 -0.1184001 0.9694599 -0.2147768 -0.08083325 0.9694596 -0.2315469 -0.3289893 0.0610544 -0.9423578 -0.3087762 0.3498409 -0.8844594 -0.3087806 0.3498272 -0.8844635 -0.2214931 0.7405588 -0.6344397 -0.2214855 0.7405707 -0.6344283 -0.08083403 0.9694606 -0.231543 -0.08083069 0.9694619 -0.2315385 -0.04099559 0.9694619 -0.2417913 -0.1123329 0.7405576 -0.6625373 -0.1123267 0.7405709 -0.6625236 -0.1565972 0.3498113 -0.9236392 -0.1565929 0.349828 -0.9236336 -0.166843 0.06103801 -0.9840924 -0.1668486 0.06094229 -0.9840973 -0.04099863 0.9694598 -0.2417991 -0.04098939 0.9694619 -0.2417918 -3.00925e-6 0.969462 -0.2452419 -3.11234e-6 0.9694619 -0.2452424 0.04099142 0.9694617 -0.2417925 0.1668196 0.06101149 -0.9840979 0.1565717 0.3498108 -0.9236437 0.1565738 0.3498263 -0.9236375 0.1123131 0.7405572 -0.6625413 0.1123143 0.7405691 -0.6625276 0.04098933 0.9694623 -0.2417908 0.04098904 0.9694615 -0.2417938 0.08082675 0.9694615 -0.2315413 0.2214747 0.7405554 -0.63445 0.2214735 0.7405689 -0.6344347 0.3087569 0.3498383 -0.8844673 0.3087561 0.3498256 -0.8844726 0.3289662 0.061037 -0.9423671 0.3289666 0.06105333 -0.9423659 0.0808261 0.9694629 -0.2315362 0.08082592 0.9694626 -0.2315369 0.118389 0.9694625 -0.2147706 0.1183891 0.9694625 -0.2147709 0.1526182 0.9694626 -0.191964 0.6211789 0.06107717 -0.781285 0.5830203 0.3498161 -0.7332912 0.5830221 0.3497938 -0.7333006 0.418205 0.7405592 -0.5260006 0.4181997 0.7405709 -0.5259885 0.1526246 0.9694617 -0.1919628 0.1526213 0.9694636 -0.1919558 0.743035 0.06091052 -0.6664749 0.6973896 0.3497955 -0.6255326 0.6973831 0.3498398 -0.6255149 0.5002371 0.7405701 -0.4486857 0.5002479 0.7405531 -0.4487019 0.1825588 0.9694633 -0.1637477 0.1825638 0.9694612 -0.1637546 0.1825639 0.969461 -0.1637549 0.2073676 0.9694611 -0.1309344 0.2073681 0.969461 -0.1309345 0.2073685 0.9694612 -0.1309334 0.2263358 0.9694612 -0.09443128 0.226334 0.9694616 -0.09443008 0.2389335 0.9694616 -0.05527293 0.9724545 0.06105774 -0.2249537 0.9127185 0.34981 -0.2111352 0.9127172 0.3498138 -0.2111341 0.6546929 0.7405681 -0.1514467 0.6546949 0.7405662 -0.1514478 0.2389366 0.9694609 -0.05527216 0.2389358 0.969461 -0.05527168 0.2448118 0.9694613 -0.01455694 0.6707962 0.7405683 -0.03988677 0.6707977 0.740567 -0.03988724 0.9351704 0.3498061 -0.05560749 0.9351701 0.3498068 -0.05560737 0.9620203 0.2669169 -0.05720394 0.9955675 0.06112074 -0.07148283 0.2596192 0.9655317 -0.01861095 0.2444347 0.9696616 0.002838194 0.2438007 0.9694615 0.02656739 0.2438012 0.9694613 0.02656733 0.2359313 0.9694612 0.06694364 0.9602274 0.06105834 0.2724611 0.9012437 0.3498067 0.2557247 0.9012444 0.3498049 0.2557245 0.6464574 0.7405717 0.1834297 0.6464679 0.7405624 0.1834299 0.2359313 0.9694612 0.06694352 0.2359301 0.9694614 0.06694352 0.2214208 0.9694616 0.1054378 0.6067044 0.7405697 0.288905 0.6067157 0.7405596 0.2889072 0.8458259 0.349796 0.4027671 0.8458219 0.3498053 0.4027673 0.9011752 0.06111007 0.4291257 0.9011777 0.06107854 0.429125 0.2214199 0.9694618 0.1054376 0.2214199 0.9694617 0.1054376 0.2006818 0.969462 0.1409624 0.2006836 0.9694614 0.1409631 0.1742947 0.9694614 0.1725283 0.7093901 0.06099313 0.7021721 0.6658102 0.3498129 0.6590355 0.6658104 0.3498122 0.6590356 0.4775912 0.7405616 0.4727315 0.4775879 0.740565 0.4727296 0.1742951 0.9694625 0.1725221 0.1743006 0.9694609 0.1725253 -0.546031 -0.1172238 0.8295233 -0.326638 -0.4529882 0.8295235 0.1939767 -0.5237026 0.8295232 0.5429118 -0.1309118 0.8295233 -0.555415 -0.02474373 0.8312052 -0.5554151 -0.02474391 0.831205 -0.5554152 -0.02474755 0.8312049 0.554618 -0.038697 0.8312048 0.5546181 -0.03869694 0.8312048 0.5546178 -0.03869628 0.831205 0.5429117 -0.1309118 0.8295235 0.4175192 -0.370903 0.8295232 0.417519 -0.3709029 0.8295233 0.4949808 -0.2586219 0.8295233 0.4949808 -0.2586219 0.8295233 0.4949805 -0.2586221 0.8295233 0.1939764 -0.5237021 0.8295236 0.315149 -0.4610552 0.8295236 0.3151485 -0.4610556 0.8295234 0.3151485 -0.4610555 0.8295235 0.4175191 -0.3709025 0.8295235 -0.0751658 -0.5533908 0.8295232 -0.07516586 -0.5533909 0.8295233 0.06123197 -0.5551053 0.8295233 0.06123214 -0.5551058 0.8295229 0.06123179 -0.5551055 0.8295231 -0.326638 -0.4529883 0.8295235 -0.2070776 -0.5186615 0.8295235 -0.207079 -0.518661 0.8295235 -0.2070789 -0.518661 0.8295234 -0.07516556 -0.5533905 0.8295233 -0.546031 -0.1172239 0.8295231 -0.5013251 -0.2460985 0.8295231 -0.5013253 -0.2460985 0.8295231 -0.5013253 -0.2460985 0.829523 -0.4267104 -0.3602911 0.8295231 -0.42671 -0.3602904 0.8295236 -0.4267099 -0.3602906 0.8295235 -0.1950687 -0.008690237 0.980751 -0.1950688 -0.008690297 0.980751 -0.1921135 -0.04124361 0.9805057 -0.1921134 -0.04124355 0.9805057 -0.1763843 -0.08658629 0.9805057 -0.1763842 -0.08658629 0.9805058 -0.1501321 -0.1267633 0.9805057 -0.1501322 -0.1267635 0.9805057 -0.1149232 -0.1593779 0.9805056 -0.1149232 -0.1593779 0.9805057 -0.07285797 -0.1824839 0.9805057 -0.07285797 -0.1824839 0.9805056 -0.02644604 -0.194703 0.9805057 -0.02644604 -0.1947029 0.9805057 0.02154362 -0.1953061 0.9805057 0.02154362 -0.1953061 0.9805058 0.06824797 -0.1842574 0.9805057 0.06824803 -0.1842576 0.9805057 0.1108808 -0.1622162 0.9805057 0.1108807 -0.1622161 0.9805057 0.1468983 -0.130497 0.9805057 0.1468983 -0.1304971 0.9805057 0.1741521 -0.09099251 0.9805057 0.1741521 -0.09099251 0.9805057 0.191016 -0.04605948 0.9805057 0.191016 -0.04605948 0.9805057 0.1947886 -0.01359093 0.980751 0.1947887 -0.01359081 0.980751 0.5057054 0.2371879 0.82946 0.07627153 0.5533343 0.82946 -0.4226789 0.3651565 0.8294597 0.5555719 -0.006984174 0.8314391 -0.5554094 0.02514338 0.8311969 -0.5554096 0.02514326 0.8311968 -0.5457195 0.1191061 0.82946 -0.5457196 0.1191061 0.82946 -0.4226784 0.3651563 0.82946 -0.4995829 0.2498257 0.82946 -0.4995836 0.2498244 0.8294602 -0.4995836 0.2498244 0.82946 -0.5457196 0.119106 0.82946 -0.1971094 0.5226317 0.82946 -0.1971098 0.522632 0.8294599 -0.3197404 0.4579983 0.8294597 -0.3197407 0.4579985 0.8294596 -0.3197405 0.4579985 0.8294597 0.07627153 0.5533345 0.8294599 -0.0623396 0.5550768 0.8294597 -0.06233894 0.555077 0.8294597 -0.0623387 0.5550765 0.8294601 -0.1971094 0.5226317 0.8294601 0.3311518 0.449817 0.8294596 0.3311516 0.4498161 0.8294601 0.210184 0.5175119 0.8294602 0.210184 0.5175123 0.82946 0.2101842 0.5175121 0.82946 0.5057057 0.2371882 0.8294598 0.4317243 0.3544157 0.8294599 0.4317235 0.3544164 0.82946 0.4317235 0.3544166 0.8294598 0.3311514 0.4498168 0.8294599 0.5493998 0.0110448 0.8354866 0.5554937 0.01815444 0.8313226 0.548541 0.1053512 0.82946 0.5485413 0.1053514 0.8294599 0.5485411 0.105351 0.82946 0.1952289 0.003924727 0.9807499 0.1952289 0.003924727 0.9807499 0.1930097 0.0370689 0.9804964 0.1930096 0.0370689 0.9804964 0.1779375 0.08345693 0.9804964 0.1779374 0.08345687 0.9804964 0.1519061 0.1247048 0.9804964 0.151906 0.1247048 0.9804965 0.1165189 0.1582722 0.9804965 0.116519 0.1582725 0.9804964 0.07395541 0.1820918 0.9804964 0.07395541 0.1820919 0.9804964 0.02683687 0.1946963 0.9804964 0.02683687 0.1946962 0.9804964 -0.02193456 0.1953092 0.9804964 -0.02193456 0.1953092 0.9804964 -0.06935495 0.1838932 0.9804964 -0.06935489 0.1838931 0.9804964 -0.1125038 0.1611511 0.9804964 -0.1125037 0.1611511 0.9804964 -0.1487234 0.1284837 0.9804964 -0.1487237 0.1284839 0.9804964 -0.1757835 0.08790326 0.9804964 -0.1757836 0.08790332 0.9804964 -0.192017 0.04190868 0.9804964 -0.192017 0.04190868 0.9804964 -0.1950686 0.008830606 0.9807499 -0.1950685 0.008830666 0.9807499 -0.3272666 -0.9426205 -0.06605517 -0.3136991 -0.9491179 -0.02771574 -0.3156049 -0.9449755 -0.08610975 -0.5956048 -0.7645877 -0.246294 -0.5910075 -0.7690292 -0.2435243 -0.3273624 -0.942583 -0.06611466 -0.5953592 -0.7675864 -0.2373996 -0.5859054 -0.7552863 -0.293696 -0.5936778 -0.7681484 -0.2397803 -0.5987225 -0.7635976 -0.2417643 -0.5383294 -0.8140903 -0.2178498 -0.2366302 -0.9715577 0.009045541 -0.1879624 -0.978799 -0.08137947 -0.285165 -0.9561887 -0.06621265 -0.236628 -0.9715584 0.009031713 -0.5936713 -0.7681542 -0.2397781 -0.4826594 -0.8269749 -0.2883617 -0.5048984 -0.8167259 -0.2793501 -0.1218673 -0.9886822 -0.08749783 -0.4878928 -0.8162926 -0.3092362 -0.4734263 -0.8313019 -0.2912123 -0.4669755 -0.831454 -0.3010286 -0.4668954 -0.831452 -0.3011582 -0.1170526 -0.9867113 -0.112693 -0.117067 -0.9867102 -0.1126865 -0.1131711 -0.9870356 -0.1138117 -0.1141981 -0.9869422 -0.1135952 -0.08577549 -0.9891521 -0.1192505 -0.1829001 -0.9763193 -0.1155356 -0.3335467 -0.9122132 -0.2379366 -0.3461856 -0.9122676 -0.218914 -0.4654811 -0.8333008 -0.2982236 -0.4669141 -0.8314251 -0.3012033 -0.03482824 -0.9990943 -0.02444738 -0.04179465 -0.9987379 -0.02785027 -0.04179483 -0.9987379 -0.02785009 -0.09978491 -0.9921827 -0.074943 -0.0459302 -0.9964488 -0.070571 -0.1757071 -0.9789927 -0.1034424 -0.5462296 -0.8129492 -0.2018586 -0.1745815 -0.9789782 -0.1054653 -0.1296097 -0.9878107 -0.086205 -0.1465926 -0.9848343 -0.09280121 -0.1204604 -0.989103 -0.0846439 -0.1199921 -0.9892008 -0.08416438 -0.1714897 -0.9808927 -0.09187358 -0.1465989 -0.9807961 -0.1286386 -0.3344721 -0.9246905 -0.1818677 -0.3310286 -0.9247896 -0.1875748 -0.5031098 -0.8256911 -0.2551761 -0.04180574 0.9987373 -0.0278567 -0.03838777 0.999009 -0.02252686 -0.3573482 0.9119005 -0.2018407 -0.08581507 0.989147 -0.1192645 -0.08580565 0.9891479 -0.1192639 -0.116957 0.9866808 -0.113058 -0.1169943 0.9866783 -0.1130414 -0.487907 0.8162838 -0.3092368 -0.4879545 0.8162413 -0.3092742 -0.4873657 0.8167358 -0.3088969 -0.1632772 0.9810753 -0.104076 -0.5324764 0.8034167 -0.2664408 -0.5154941 0.8165151 -0.2599404 -0.3710405 0.8967645 -0.2411273 -0.3995105 0.8810843 -0.2531442 -0.3335721 0.9121989 -0.2379556 -0.148487 0.9838638 -0.09981679 -0.1665861 0.9787341 -0.1197019 -0.5137844 0.8178036 -0.259274 -0.0312913 0.9985697 -0.04335111 -0.1144126 0.9905138 -0.07610654 -0.1607971 0.9837678 -0.0796566 -0.02956593 0.9993683 -0.01971888 -0.03838753 0.999009 -0.02252733 -0.1218673 0.9886823 -0.08749634 -0.1203007 0.9891502 -0.08431845 -0.1195741 0.9892591 -0.08407425 -0.1715071 0.9808924 -0.09184384 -0.03523588 0.9990756 -0.02462857 -0.03956139 0.9988587 -0.02676039 -0.5359977 0.8157499 -0.2173905 -0.3236007 0.9460697 -0.01531779 -0.2031168 0.97515 -0.08846455 -0.2366311 0.9715574 0.009045243 -0.5479469 0.7806357 -0.3006029 -0.5359783 0.8148301 -0.2208601 -0.2806444 0.9527094 -0.1165475 -0.5932323 0.7684774 -0.2398291 -0.5507782 0.803533 -0.2257832 -0.5359567 0.8148538 -0.2208251 -0.3405676 0.9392817 -0.04199689 -0.2849226 0.9561491 -0.06780874 -0.5859057 0.7552868 -0.2936945 -0.595396 0.7676343 -0.2371522 -0.3274495 0.9425636 -0.06596046 -0.3273535 0.9426012 -0.06590038 -0.5908673 0.7692603 -0.2431348 -0.3016023 0.95032 -0.07699328 3.02009e-4 -0.9790127 -0.203799 -0.01184725 -0.9516049 -0.3070958 -4.04806e-4 -0.9790127 -0.203799 0.01310396 -0.9515898 -0.3070914 0.3391761 -0.8232307 -0.4552479 0.006085276 -0.94099 -0.3383794 -4.72867e-4 0.9781572 -0.207866 6.38932e-4 0.9781571 -0.207866 0.02829784 0.948693 -0.3149298 0.01771587 0.9449849 -0.326634 -0.3574993 0.8134506 -0.4587945 -0.02149969 0.9488552 -0.3149785 -0.2947738 -0.83622 -0.462433 0 -0.9420862 -0.3353706 0 -0.8750931 -0.4839547 5.38224e-6 -0.8750979 -0.483946 7.13319e-6 -0.7660325 -0.642802 0 -0.7660232 -0.642813 0 -0.7660374 -0.6427961 -1.34002e-7 -0.766037 -0.6427966 0 -0.6285255 -0.777789 0 -0.6285255 -0.777789 0 -0.4676074 -0.8839362 0 -0.4676082 -0.8839358 0 -0.4676761 -0.8838999 -1.52414e-7 -0.4676759 -0.8839001 0 -0.2894607 -0.9571899 0 -0.2894609 -0.9571899 0 -0.2894681 -0.9571877 -1.23829e-7 -0.2894678 -0.9571878 0 -0.1004989 -0.9949372 0 -0.1004989 -0.9949372 0 0.0918104 -0.9957765 0 0.09181314 -0.9957762 0 0.092202 -0.9957404 0 0.09220194 -0.9957404 1.34206e-7 0.2814566 -0.9595739 0 0.281457 -0.9595739 0 0.2814504 -0.9595757 1.43628e-7 0.2814501 -0.959576 2.39425e-7 0.4602795 -0.8877741 0 0.4602798 -0.8877739 0 0.4603477 -0.8877388 2.40683e-7 0.4603444 -0.8877404 3.23549e-7 0.6220037 -0.7830144 3.29527e-7 0.6220036 -0.7830144 3.95665e-7 0.7606414 -0.6491723 0 0.7606425 -0.6491711 0 0.7606384 -0.6491758 5.41328e-7 0.7606377 -0.6491767 6.04114e-7 0.8710295 -0.4912307 0 0.8710299 -0.4912297 0 0.8710309 -0.4912282 0.1593497 -0.9840987 -0.07846993 0.02977329 -0.9993643 -0.01960879 0.03791511 -0.9989689 -0.02496898 0.03412753 -0.9991315 -0.02390617 0.1218955 -0.9886934 -0.08733129 0.1218463 -0.9887101 -0.08721154 0.1211074 -0.9889451 -0.08555942 0.1201203 -0.9892064 -0.08391511 0.08769571 -0.9889062 -0.1198916 0.355661 -0.9127972 -0.200765 0.3318152 -0.913102 -0.236946 0.08774727 -0.9889019 -0.1198899 0.1170329 -0.986693 -0.1128732 0.1170522 -0.9867012 -0.1127814 0.4880021 -0.8161975 -0.3093149 0.4880079 -0.8161923 -0.3093191 0.1198701 -0.9892435 -0.08383536 0.169048 -0.9814131 -0.09083515 0.1609968 -0.9815879 -0.1027874 0.02699899 -0.9987924 -0.04104632 0.114825 -0.9905084 -0.07555305 0.5210455 -0.8123216 -0.2620025 0.5156702 -0.8164041 -0.2599398 0.3696374 -0.8975417 -0.2403892 0.397402 -0.8823294 -0.252124 0.3317797 -0.9131168 -0.2369388 0.03794527 -0.9990307 -0.02231407 0.03794759 -0.9990307 -0.02231031 0.1471182 -0.9842041 -0.09848093 0.1663684 -0.9788091 -0.1193916 0.5156044 -0.8164545 -0.2599119 0.5374256 -0.8146079 -0.2181459 0.3234848 -0.9461088 -0.01535677 0.2024737 -0.9752638 -0.08868479 0.2362496 -0.9716503 0.009048998 0.5479057 -0.7806733 -0.3005805 0.5360015 -0.8147478 -0.2211076 0.338396 -0.9305889 -0.1396162 0.5933027 -0.7683424 -0.2400875 0.5405181 -0.8113477 -0.2226098 0.535994 -0.814756 -0.2210953 0.5936084 0.7682612 -0.2395913 0.2367783 0.9715229 0.008903026 0.5361196 0.8157767 -0.216989 0.3383437 0.9304451 -0.1406956 0.1877163 0.978776 -0.08222109 0.2855444 0.9560345 -0.06680148 0.2367782 0.9715229 0.008902072 0.5936335 0.7682391 -0.2395995 0.5193438 0.8097516 -0.2731015 0.5046636 0.8169112 -0.2792324 0.1218967 0.9886938 -0.08732622 0.1209174 0.9890049 -0.08513677 0.1194024 0.9893236 -0.08355629 0.1274123 0.9882122 -0.08486968 0.1001735 0.9921512 -0.07484143 0.04101556 0.9987837 -0.02736371 0.04101568 0.9987837 -0.02736353 0.1755015 0.9789462 -0.1042291 0.1293812 0.9878432 -0.08617562 0.1747319 0.9789387 -0.1055832 0.487626 0.8164777 -0.3091685 0.4764052 0.8288645 -0.2932947 0.4653916 0.8324902 -0.3006174 0.4654012 0.8324903 -0.3006017 0.1169225 0.9866444 -0.1134107 0.117038 0.9866935 -0.1128624 0.087704 0.9889057 -0.1198899 0.2046044 0.9706965 -0.1260377 0.331801 0.9131092 -0.2369384 0.3443964 0.9131628 -0.2180019 0.4638463 0.8345118 -0.2973831 0.4637812 0.8345767 -0.297302 0.1691048 0.9814109 -0.09075361 0.1443004 0.9813048 -0.1273511 0.3329455 0.9254034 -0.1810409 0.3293478 0.9255064 -0.1869972 0.04650998 0.9963884 -0.071042 0.5528199 0.8081319 -0.2032556 0.5441104 0.8145411 -0.201163 0.3405088 -0.9393041 -0.04197293 0.2848199 -0.9561828 -0.06776583 0.5859221 -0.7552726 -0.2936983 0.5954201 -0.7676368 -0.2370839 0.3269359 -0.9427657 -0.06561762 0.5910614 -0.7690833 -0.2432227 0.3400866 -0.9352382 -0.09834015 0.5910274 0.7691159 -0.2432022 0.3269324 0.9427665 -0.06562459 0.5954196 0.7676361 -0.2370873 0.5859218 0.7552722 -0.2936998 0.3400862 0.9352369 -0.09835332 0.316145 0.9448912 -0.08504641 0.3142693 0.94892 -0.02802872 0.9664217 0.232519 0.1093795 0.9152194 0.1572415 0.3710103 0.699109 0.1505034 0.6989959 0.5294335 0.7996339 0.2833472 0.8615331 0.4796815 0.1663327 0.9336742 0.3508099 0.07200574 0.9259274 0.3612775 0.1101685 0.9408942 0.3307731 0.0728529 0.946537 0.3210314 0.03172856 0.944848 0.3252603 0.03831589 0.9491268 0.314468 0.01638156 0.8609588 0.4828696 0.1599591 0.8609533 0.4828749 0.1599719 0.8609599 0.4828693 0.1599538 0.7345983 0.633987 0.2417143 0.7346202 0.6339753 0.2416782 0.6190496 0.7010333 0.3540193 0.6238495 0.678332 0.3881717 0.7317921 0.1439441 0.6661534 0.7509081 0.4217568 0.508191 0.7509564 0.4216281 0.5082267 0.7241321 0.4835237 0.49177 0.7223949 0.4304658 0.5411514 0.6418496 0.6723497 0.368748 0.7628679 0.254889 0.594192 0.868015 0.2146968 0.4477223 0.8926783 0.01391148 0.4504796 0.8926784 0.01390981 0.4504793 0.7880373 0.09173613 0.6087542 0.7903215 0.09091508 0.6059096 0.7887195 0.09747171 0.6069769 0.7887248 0.09746628 0.6069707 0.9664334 0.2325003 0.1093157 0.9664223 0.2325152 0.1093832 0.9654527 0.1872303 0.1812344 0.9576843 0.2093208 0.1975488 0.9157369 0.3009794 0.2661532 0.9548896 0.0958755 0.2810583 0.9549072 0.0957033 0.2810569 0.9152144 0.1572447 0.3710212 0.9101015 0.1449767 0.3881971 0.8655623 0.3310937 0.3757378 0.8539394 0.4283595 0.2954584 0.7344567 0.6297664 0.2529183 0.7345965 0.633984 0.2417278 -0.5862615 0.5630686 -0.5824528 -0.4721089 0.7477136 -0.4669451 -0.70239 0.06429153 -0.7088827 -0.6867277 0.198774 -0.6992096 -0.6610363 0.356819 -0.6600843 -0.6932634 0.1986004 -0.6927798 -0.6623119 0.3566496 -0.658896 -0.5880942 0.5611425 -0.582464 -0.6464262 0.35683 -0.6743927 -0.4731511 0.7463936 -0.4680007 -0.1385082 0.9813714 -0.1331385 -0.3908082 0.8363943 -0.3843351 -0.4631789 0.7464103 -0.4778461 -0.1729607 0.9705386 -0.1677479 -0.172708 0.9705079 -0.1681855 -0.1726244 0.9705374 -0.1681011 -0.1351823 0.9813824 -0.1364346 -2.37318e-6 1 1.04095e-6 -2.9752e-7 1 -3.60032e-7 -2.01447e-6 1 1.44075e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.95203e-6 1 1.40811e-6 3.00577e-7 1 -3.57581e-7 3.01694e-7 1 -3.56812e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.4370794 0.7903138 -0.4293782 0.0456289 0.9979347 -0.0452125 0.5480126 0.6396552 -0.5390022 0.4370161 0.7903769 -0.4293265 0.5211275 0.6653938 -0.5344881 0.1515654 0.975868 -0.157193 0.2557303 0.9341494 -0.2489316 0.1571622 0.9758947 -0.1514248 0.2577695 0.9341896 -0.2466673 0.2578752 0.9341336 -0.2467686 0.5352397 0.6654013 -0.5203456 0.6773409 0.240891 -0.6951121 0.6341298 0.450491 -0.6284405 0.6905065 0.2406615 -0.6821164 0.6350299 0.4505212 -0.627509 0.6945853 0.2408891 -0.6778817 0.7050563 0.1218974 -0.6985962 -0.4020562 0.8531898 0.3322921 -0.3748583 0.853935 0.3609383 -0.3742471 0.8544732 0.3602977 -0.373965 0.8548752 0.3596369 -0.3365274 0.9057957 0.2574557 -0.4022201 0.8502635 0.3395158 -0.402229 0.8502486 0.3395427 -0.4041934 0.8550873 0.324736 -0.4041686 0.8550982 0.3247381 -0.4019224 0.8565461 0.3237085 -0.3955122 0.8610869 0.31953 -0.4135759 0.8479267 0.3316252 -0.4005029 0.857577 0.322737 -0.4044609 0.8549808 0.3246834 -0.4039024 0.8549668 0.3254143 -0.4122195 0.8547602 0.3153732 -0.4391325 0.8596996 0.2609198 -0.4556835 0.8553751 0.2463449 -0.4832617 0.858824 0.1699392 -0.4806352 0.8583744 0.1793972 -0.4843153 0.8581559 0.1703144 -0.4846146 0.8558211 0.1808837 -0.5064393 0.8572975 0.09252125 -0.506309 0.857509 0.09126651 -0.5061157 0.8574951 0.09246188 -0.5061188 0.8576251 0.09122937 -0.5150291 0.8567696 0.02628177 -0.509649 0.8603824 -2.78521e-4 -0.5125524 0.8585381 -0.01422321 -0.5136201 0.8552106 -0.06934899 -0.5109816 0.854586 -0.09263169 -0.5135283 0.8552668 -0.06933617 -0.5023369 0.8598577 -0.09111791 -0.4972435 0.8546712 -0.149285 -0.4807134 0.8581991 -0.1800248 -0.4919361 0.858013 -0.1476905 -0.4773856 0.8603147 -0.1787776 -0.4679737 0.8544766 -0.2255449 -0.4379184 0.8603419 -0.2608435 -0.4234618 0.8569456 -0.2938103 -0.443004 0.8568027 -0.2638877 -0.4095538 0.8513146 -0.3279161 -0.4146067 0.8554092 -0.3104451 -0.4147629 0.8552438 -0.3106923 -0.3807615 0.8861305 -0.2641847 -0.3898787 0.8570891 -0.3367388 0.4171206 0.8552851 -0.3074047 0.3837086 0.885431 -0.262259 0.3926582 0.8571 -0.3334656 0.4398927 0.8603194 -0.2575749 0.4254308 0.8570065 -0.2907721 0.4448681 0.8568719 -0.2605051 0.4193081 0.8529775 -0.3108216 0.4057067 0.8564038 -0.3193348 0.4715903 0.8776972 0.08514803 0.5120742 0.8588605 0.01177656 0.5132249 0.8534951 -0.09025603 0.5133562 0.8554379 -0.06849342 0.5111191 0.8547981 -0.08987486 0.5045516 0.8607529 -0.0673204 0.4936239 0.8505799 -0.181244 0.4925342 0.8579496 -0.1460565 0.4820104 0.8581047 -0.1769806 0.4844383 0.8629503 -0.1436537 0.4690313 0.8545497 -0.223057 0.4016231 0.856616 0.3238949 0.4013863 0.8567907 0.3237262 0.404372 0.8551204 0.3244265 0.4008566 0.8571704 0.3233772 0.4019653 0.8563717 0.3241167 0.4018368 0.8564633 0.3240339 0.4037961 0.8551814 0.3249821 0.4041803 0.8550123 0.3249496 0.4037094 0.8550007 0.325565 0.4146786 0.8546868 0.3123332 0.4385182 0.8599158 0.2612403 0.4573438 0.8551945 0.2438831 0.4791808 0.8590475 0.1800647 0.4844724 0.8584709 0.168268 0.4796102 0.8587754 0.180219 0.4882575 0.8560667 0.1695712 0.5056915 0.8577019 0.09286296 0.5064076 0.857433 0.09143292 0.5061582 0.8574175 0.09294748 0.5333663 0.8458821 0.002013802 0.4018038 0.8532636 0.3324079 0.4019072 0.8503939 0.3395598 0.3856976 0.8756981 0.2904999 0.3749299 0.8559675 0.3560158 0.3761476 0.8541236 0.3591458 0.4562187 -0.7806723 0.427101 0.701897 -0.1894289 0.6866276 0.6915073 -0.08578908 0.7172572 0.6801437 -0.02847522 0.7325255 0.6810714 -0.2129769 0.7005588 0.6810759 -0.2129672 0.7005573 0.5928804 -0.5411415 0.5963713 0.5217173 -0.7388558 0.426501 0.6279717 -0.4998389 0.5965003 0.6281287 -0.4994964 0.5966219 0.6103984 -0.5407798 0.5787668 0.6706134 -0.490909 0.5561349 0.4532345 -0.748229 0.4844912 0.4599402 -0.780674 0.4230875 0.431567 -0.7758153 0.4602829 0.4640045 -0.7809076 0.4181902 0.4621478 -0.7807958 0.420449 0.9996042 -0.005297422 0.02763229 -0.6282907 0.01588869 0.7778165 0.6935153 0.02398163 0.7200427 0.6283047 0.01629054 0.7777968 0.6286125 0.005516648 0.7776992 0.677096 -0.3039391 0.6701956 0.6862439 0.04583597 0.7259259 0.6935201 0.02397006 0.7200384 0.6794487 0.001542925 0.7337214 0.6789978 5.36186e-4 0.7341402 0.6790005 8.70529e-4 0.7341373 0.7067056 0.009911835 0.7074383 0.7067148 0.009936749 0.7074287 0.7177773 0.0822575 0.6913968 0.6931082 0.02565294 0.720377 -0.7178102 0.08400988 0.6911519 -0.6815654 0.001389861 0.7317559 -0.6815657 0.001195073 0.731756 -0.6816028 0.001295268 0.7317214 -0.7062081 0.009768962 0.707937 -0.6999042 0.01647633 0.7140467 -0.6999149 0.01646375 0.7140365 -0.6932193 0.02491772 0.7202959 -0.6932348 0.02488112 0.7202822 -0.710343 -0.03163772 0.7031443 -0.6285547 0.005475103 0.7777462 -0.6285499 0.005492627 0.77775 -0.7068136 0.009935915 0.70733 -0.7066321 0.009444296 0.7075181 -0.7203165 0.009443402 0.6935813 -0.7106687 0.009095728 0.703468 -0.794199 -0.008381605 0.6075999 -0.8182384 0.01085829 0.5747765 -0.8796387 -0.009925305 0.4755387 -0.9028352 -0.005745351 0.4299486 -0.8796687 -0.005768597 0.475552 -0.9027873 0.01219069 0.4299144 -0.9433131 -0.01104563 0.3317204 -0.9619768 0.009032905 0.2729819 -0.9433303 0.008997976 0.3317335 -0.9619333 0.01309698 0.2729702 -0.9836509 -0.01174074 0.1797028 -0.9940208 0.01357823 0.1083432 -0.9997169 -0.005097448 0.02324151 -0.9997168 -0.005097448 0.02324205 -0.9933794 -0.03837966 0.1082785 -0.9981454 0.01363354 -0.05932766 -0.990938 -0.01185035 -0.1337963 -0.9742725 0.00333625 -0.2253488 -0.9910016 0.003261923 -0.1338103 -0.9741921 0.01326167 -0.2253307 -0.9577071 -0.01126712 -0.2875243 -0.9228309 0.01246649 -0.3850036 -0.9008221 0.002870738 -0.4341788 -0.9008302 0.002870738 -0.4341622 -0.7525475 -0.008756995 -0.6584798 -0.8215758 -0.008820414 -0.5700309 -0.8455114 0.01124393 -0.5338389 -0.9227144 -0.02037924 -0.3849453 -0.5780128 0.02166736 -0.81574 -0.6222133 0.02228188 -0.7825305 -0.6657351 -0.001461207 -0.7461867 -0.7444279 0.00382173 -0.667692 -0.7517176 0.01548099 -0.6593036 -0.7338544 0.02077758 -0.6789889 -0.7339672 0.02065545 -0.6788708 -0.7613557 -0.008769452 -0.6482752 -0.7805787 0.05836272 -0.6223267 -0.7803537 0.3128972 -0.5414273 -0.751624 0.01506149 -0.6594198 -0.7517184 0.01548689 -0.6593024 -0.5781649 0.02166759 -0.8156322 -0.6219537 -0.03593689 -0.7822288 -0.444922 0.03384894 -0.8949294 -0.4827674 -0.002505302 -0.8757451 -0.4451887 -0.002539992 -0.8954332 -0.4826248 -0.02505671 -0.8754687 -0.3012659 0.02351444 -0.9532502 -0.3295689 -0.01477849 -0.9440159 -0.167109 0.009258389 -0.985895 -0.3019055 0.009145498 -0.953294 -0.1671482 0.01153552 -0.9858644 0.7449414 0.01290625 -0.6670051 0.7572776 0.02109217 -0.6527524 0.7446891 0.4328842 -0.5079857 0.7349145 0.02255517 -0.6777846 0.7347412 0.0227226 -0.677967 0.8040096 -0.05546784 -0.5920235 0.7348799 0.02257919 -0.6778213 0.7443952 0.008180677 -0.6676892 0.6722756 -0.002833902 -0.7402957 0.6222172 0.02066224 -0.7825719 0.5853813 0.01737892 -0.8105719 0.6222374 0.01740866 -0.782635 0.5853875 -0.0156883 -0.810602 0.4826881 0.01741558 -0.8756192 0.453056 -0.002290487 -0.891479 0.4827424 -0.00226885 -0.8757595 0.4530073 -0.0118919 -0.8914274 0.3295533 0.01306092 -0.9440466 0.3097403 -0.006996273 -0.9507955 0.1671101 0.007622838 -0.9859089 0.158842 0.007258594 -0.9872774 0.167128 0.00725907 -0.9859085 0.1589854 -0.001006841 -0.9872804 0 0.001083672 -0.9999995 0.004412114 0.003548681 -0.999984 -2.36862e-5 0.003549158 -0.9999937 0.004400014 0.00607866 -0.9999719 -0.1502799 -0.005291283 -0.9886294 0.7786501 0.03589552 -0.626431 0.7723709 -0.007276475 -0.6351301 0.8260906 -0.007305979 -0.56349 0.845507 0.01010245 -0.5338686 0.9038346 -0.009198069 -0.427783 0.922896 0.002237319 -0.3850429 0.9038726 0.002211928 -0.427796 0.9228314 0.01174181 -0.385025 0.9594696 -0.0105856 -0.2816135 0.9741915 0.01287823 -0.2253559 0.9916909 0.004488527 -0.1285653 0.9742619 0.004565358 -0.2253727 0.9916349 -0.01147329 -0.1285627 0.9973909 0.009101271 -0.07161378 0.9995641 -0.01039612 0.02763259 0.9998387 -0.01310658 0.01228624 0.9941011 -0.005241453 0.1083309 0.982602 0.03127598 0.1830714 0.9936 -0.03218257 0.1082741 0.9420406 0.03066611 0.3340943 0.9619764 0.0098055 0.2729566 0.9424542 0.009769141 0.3341926 0.9617056 -0.02567774 0.272879 0.8785974 0.02439373 0.4769399 0.9028488 -0.005689024 0.4299206 0.9028393 -0.005689024 0.4299405 0.700308 0.01605832 0.7136601 0.7064461 0.009503901 0.7077031 0.7106626 0.00950396 0.7034688 0.7201723 0.007294714 0.6937569 0.8182216 -0.01414662 0.5747288 0.793584 0.0186308 0.6081753 0.8788158 -0.01000642 0.4770562 -0.004662632 0.9999892 8.59578e-6 0.003101468 0.9999952 8.72167e-6 -0.08134251 0.9964193 0.02305948 -0.08135002 0.9964188 0.02305746 -0.1583558 0.9873734 0.004147827 -0.2427918 0.9700784 -9.65796e-5 -0.214393 0.9767474 2.11681e-4 -0.214475 0.9767295 2.20285e-4 -0.2144759 0.9767293 2.20288e-4 -0.002663254 0.9982817 0.05853801 -0.1592451 0.9867038 -0.03250616 -0.1371631 0.9903047 -0.02197098 -0.1371805 0.9903023 -0.02197569 -0.0782718 0.9969094 -0.006721258 0.003450512 0.999994 8.76283e-6 0.08142822 0.9964132 -0.02302885 0.08143335 0.9964128 -0.02302747 0.1583784 0.9873698 -0.004143774 0.2428125 0.9700732 1.00151e-4 0.2144931 0.9767255 -2.19699e-4 0.2144873 0.9767268 -2.19089e-4 0.2144873 0.9767267 -2.19089e-4 0.002628922 0.9982814 -0.05854338 0.1592348 0.9867051 0.0325154 0.1372051 0.9902983 0.02199727 0.1371994 0.9902991 0.02199578 0.07827574 0.996909 0.006724357 -0.003484189 0.9999939 8.73446e-6 -0.004245281 -0.999991 0 0.004244625 -0.999991 0 -0.08143991 -0.9964057 -0.02330923 -0.157908 -0.9874445 -0.004276335 -0.2144572 -0.9767334 -7.34923e-6 -0.1925677 -0.9812167 0.01146739 -0.2266606 -0.9739738 1.29548e-5 -0.229642 -0.9732747 8.46456e-4 -0.2014446 -0.9794683 -0.007870256 -0.1976665 -0.9802353 0.008170127 -0.152685 -0.9882749 2.17855e-4 -0.152687 -0.9882746 2.17853e-4 -0.003778517 -0.9999929 9.60373e-7 -0.08738428 -0.9961417 -0.008108794 0.003526687 -0.9998582 0.01646882 -0.07881444 -0.9968883 0.001397728 0.08142858 -0.9964065 0.02331221 0.1579062 -0.9874448 0.004276812 0.2144531 -0.9767343 7.168e-6 0.192563 -0.9812176 -0.01147186 0.2266659 -0.9739726 -1.31454e-5 0.2295866 -0.9732879 -8.29578e-4 0.20144 -0.9794692 0.00787127 0.1976674 -0.980235 -0.008170425 0.1526847 -0.988275 -2.17881e-4 0.1526843 -0.988275 -2.17881e-4 0.003780126 -0.9999928 -9.6053e-7 0.08738428 -0.9961417 0.008108675 -0.003526687 -0.9998582 -0.01646864 0.0788151 -0.9968883 -0.001397609 -0.08008843 0.7131136 0.6964589 -0.03884869 0.716526 0.6964777 0.09538209 0.691978 0.7155897 0.1150959 0.702055 0.7027601 0.2615911 0.6565438 0.7074747 0.2655918 0.6539359 0.7083989 0.2612034 0.6555712 0.7085189 0.2645626 0.6514022 0.711113 0.4008265 0.591175 0.6998931 0.4151202 0.5638738 0.7139477 0.3933061 0.580082 0.7133129 0.4125654 0.5604047 0.7181479 0.5223039 0.4947527 0.6945634 0.5344222 0.4387254 0.7224355 0.6143211 0.3696247 0.6971279 0.5554352 0.4559738 0.6953988 0.6188519 0.3723509 0.6916482 0.6244032 0.2928602 0.7241225 0.6848009 0.2307363 0.691237 0.6889261 0.132313 0.7126529 0.6653996 0.2241976 0.7120245 0.678175 0.1302485 0.7232662 0.7163841 0.07791149 0.6933425 0.7069166 0.02310317 0.7069195 0.7070774 -0.008888781 0.7070802 0.7105316 -0.07727485 0.6994094 0.7180378 -0.05009925 0.6941986 0.7180379 -0.05009829 0.6941986 0.7184889 -0.07814049 0.6911351 0.6714475 -0.1619055 0.7231492 0.6836478 -0.2303476 0.6925067 0.6215134 -0.3247341 0.7129298 0.6652503 -0.2241479 0.7121797 0.6143674 -0.3210002 0.7207715 0.615437 -0.3702962 0.6957858 0.5048999 -0.4782667 0.7185659 0.5275141 -0.4686169 0.7086094 0.5122607 -0.4852393 0.7086126 0.5352846 -0.4755194 0.6981058 0.3952975 -0.5830201 0.7098081 0.3986663 -0.5832403 0.7077401 0.3963901 -0.5846266 0.7078748 0.3987148 -0.5833098 0.7076555 0.2634006 -0.6610856 0.7025568 0.2428935 -0.6557698 0.7148208 0.1160127 -0.7076464 0.6969774 0.07779067 -0.7052226 0.7047055 0.1147027 -0.6996562 0.7052124 0.07611221 -0.6900023 0.7197943 -0.03902041 -0.7196888 0.6931995 -0.09302365 -0.6848646 0.7227081 -0.1856814 -0.6687637 0.719915 -0.09315681 -0.6858471 0.7217587 -0.1933042 -0.6962187 0.6913125 -0.2559155 -0.6409795 0.7236385 -0.3376994 -0.636969 0.6929861 -0.2681831 -0.6717107 0.6905669 -0.3384295 -0.6383455 0.6913613 -0.4043009 -0.5606927 0.7226095 -0.4665106 -0.5492187 0.6933446 -0.5480501 -0.4166182 0.7253071 -0.532005 -0.4491961 0.7177699 -0.5552949 -0.4221242 0.7165604 -0.5529731 -0.4669001 0.6900905 -0.6339214 -0.293283 0.7156318 -0.6349868 -0.3117124 0.706843 -0.6417667 -0.2969133 0.7070912 -0.6398207 -0.3140855 0.7014128 -0.6903543 -0.1519584 0.7073328 -0.6883366 -0.1477745 0.7101799 -0.713558 0 0.7005962 -0.7125395 -0.03174853 0.7009134 -0.7125397 -0.03174382 0.7009133 -0.7227656 0 0.6910933 -0.7093012 0.03211009 0.7041738 -0.6879326 0.1514253 0.7098023 -0.6888425 0.1503435 0.7091494 -0.6885548 0.1515622 0.7091694 -0.6891937 0.15042 0.7087918 -0.6466522 0.2991731 0.7016668 -0.6238499 0.3119657 0.7165814 -0.5686481 0.4322762 0.6998405 -0.6399937 0.3200408 0.6985569 -0.5718367 0.4346989 0.6957296 -0.5239093 0.4526107 0.7215695 -0.4672402 0.5500778 0.6921712 -0.4041312 0.5788803 0.7082199 -0.08008736 0.7131136 0.6964589 -0.03709137 0.6841089 0.7284361 -0.2618075 0.6941773 0.6705033 -0.1877824 0.6763313 0.7122596 -0.2474908 0.6562163 0.7128314 -0.1795811 0.6467928 0.7412218 -0.4355862 0.6239362 0.6488206 -0.315891 0.5958338 0.7383732 -0.4570307 0.5380579 0.708249 -0.3219484 -0.9435635 -0.0776996 -0.5928764 -0.7543314 -0.281925 -0.6036073 -0.7521983 -0.2643027 -0.302942 -0.946833 -0.1083208 -0.3040103 -0.9464516 -0.1086607 -0.3032262 -0.9467547 -0.1082101 -0.3028213 -0.9469 -0.1080725 -0.1337148 -0.9431256 -0.3043594 -0.3929713 0.4232606 -0.816348 -0.3929422 -0.09241789 -0.9149074 -0.3929421 -0.7044168 -0.5910951 -0.6433543 0.6725198 -0.3658038 -0.6562374 0.6666145 -0.3535215 -0.3929547 0.8009625 -0.4517142 -0.3944247 0.8481983 -0.3535372 -0.540844 0.7740864 -0.3290562 -0.2884835 0.9363083 -0.2002595 -0.267125 0.9412167 -0.2067732 -0.2683244 0.9142697 -0.3035013 -0.4159787 0.8665158 -0.2758843 -0.4159758 0.8665166 -0.275886 -0.02082949 0.9779451 -0.207821 -0.1522454 0.9796952 -0.1304554 -0.1522417 0.9796953 -0.1304594 -0.2182401 -0.9588819 -0.1814305 -0.2641042 -0.9423843 -0.2053315 -0.2641046 -0.9423797 -0.2053515 -0.279469 -0.9396488 -0.197376 -0.2787411 -0.9397917 -0.1977245 -0.2823847 -0.9388986 -0.196795 -0.2823341 -0.9389132 -0.196798 -0.5354956 -0.7785732 -0.3272128 -0.5354897 -0.7786488 -0.3270426 -0.5354879 -0.7785773 -0.3272154 -0.6140938 -0.6045778 -0.5073208 -0.6155835 -0.6666828 -0.4202272 -0.6628069 -0.6691321 -0.3360792 -0.6141031 -0.2284493 -0.7554393 -0.614102 -0.3691138 -0.6975914 -0.6140951 -0.3691069 -0.6976011 -0.6140992 -0.3691018 -0.6976002 -0.614099 -0.4960478 -0.6138558 -0.6141133 -0.4960343 -0.6138525 -0.6140984 -0.4960595 -0.613847 -0.6140962 -0.07932424 -0.7852347 -0.6141111 0.07275211 -0.7858593 -0.6140779 0.3632597 -0.7006788 -0.614099 0.3632782 -0.7006506 -0.6140993 0.2221279 -0.7573251 -0.6140968 0.4909027 -0.6179802 -0.6140916 0.4909123 -0.6179776 -0.6140975 0.6003181 -0.51235 -0.6140966 0.6003182 -0.5123509 -0.6140944 0.6003267 -0.5123437 -0.6150771 0.674114 -0.4089625 -0.7240663 0.5819472 -0.3702234 -0.6525575 -0.6711531 -0.3517417 -0.626055 -0.682384 -0.3773689 -0.3929524 -0.8047052 -0.4450144 -0.3944825 -0.8473591 -0.3554798 -0.4088966 -0.8690707 -0.2784238 -0.3929395 -0.5779665 -0.7152295 -0.3929441 -0.5779631 -0.7152298 -0.3929426 -0.4300599 -0.8128005 -0.392947 0.2588166 -0.8823869 -0.6140915 0.2221354 -0.7573291 -0.6141088 0.2221782 -0.7573027 -0.392969 0.5719709 -0.7200171 -0.3929452 0.5719662 -0.7200338 -0.3929473 0.6994521 -0.5969583 -0.4098918 -0.8702871 -0.2731102 -0.3958433 -0.8739368 -0.2820324 -0.133717 -0.9431248 -0.3043604 -0.1336374 -0.9846774 -0.112033 -0.09693092 -0.9744027 -0.2028393 -0.1337162 -0.8672448 -0.4795897 -0.1337099 -0.8672388 -0.4796024 -0.3929607 -0.8046998 -0.4450169 -0.392962 -0.7044028 -0.5910987 -0.6140959 -0.6045717 -0.5073255 -0.614098 -0.6045714 -0.5073235 -0.1337116 -0.6228815 -0.7708047 -0.1337247 -0.6228747 -0.7708079 -0.1337226 -0.7591574 -0.637023 -0.1337254 -0.7591539 -0.6370266 -0.1337221 -0.7591525 -0.6370288 -0.13372 -0.867234 -0.4796084 -0.1337106 -0.4634085 -0.8759989 -0.1337292 -0.4634724 -0.8759623 -0.3929523 -0.4300529 -0.8127995 -0.3929518 -0.2661741 -0.8801932 -0.6141047 -0.2284477 -0.7554383 -0.6140974 -0.2284244 -0.7554513 -0.1337238 -0.4634757 -0.8759613 -0.1337248 -0.2868617 -0.9485926 -0.3929468 -0.2661776 -0.8801945 -0.3929464 -0.09241515 -0.9149057 -0.6141085 -0.07931613 -0.7852259 -0.6140989 0.07296198 -0.7858492 -0.1337264 -0.2868608 -0.9485927 -0.1337204 -0.2868685 -0.9485912 -0.1337209 -0.09959936 -0.9860014 -0.1337263 -0.09959626 -0.986001 -0.1337311 0.09098571 -0.9868322 -0.6141008 0.07275897 -0.7858666 -0.3929423 0.08477461 -0.9156472 -0.3929466 0.08477699 -0.9156451 -0.1337117 0.09136497 -0.9867997 -0.1337276 0.09137386 -0.9867967 -0.133727 0.2789286 -0.9509553 -0.1337261 0.2789297 -0.950955 -0.3929486 0.2588173 -0.8823859 -0.3929493 0.4232534 -0.8163623 -0.6141021 0.3632637 -0.7006555 -0.6141012 0.4909146 -0.6179666 -0.1337205 0.6164174 -0.7759822 -0.1337091 0.6164134 -0.7759873 -0.1337095 0.456214 -0.8797673 -0.1336983 0.4561582 -0.879798 -0.1337186 0.4561458 -0.8798013 -0.1337189 0.2789228 -0.9509581 -0.1337192 0.7538104 -0.6433422 -0.1337206 0.7538087 -0.6433439 -0.3929544 0.6994525 -0.5969531 -0.3929547 0.8009625 -0.4517142 -0.5410382 0.7325345 -0.4131233 -0.5405841 0.7742406 -0.3291208 -0.1520005 0.9796598 -0.1310049 -0.1343142 0.9690439 -0.2071554 -0.1337125 0.9405521 -0.3122222 -0.1337061 0.9405518 -0.3122259 -0.133702 0.8631924 -0.4868497 -0.1337152 0.863208 -0.4868184 -0.1337167 0.8632073 -0.4868193 -0.1337178 0.7538074 -0.6433459 -0.5933439 0.7538173 -0.2823163 -0.6031818 0.7526232 -0.2640647 -0.3033336 0.94669 -0.1084745 -0.3029971 0.9468261 -0.108227 -0.3050419 0.9460501 -0.1092646 -0.3032215 0.9467553 -0.1082183 -0.3042796 0.9463745 -0.108578 -0.3207777 0.9440109 -0.07710486 0.7284998 -0.4748286 0.4937871 0.6112378 -0.7153536 0.3386114 0.6146957 -0.7020986 0.3594536 0.7346507 -0.6341809 0.2410455 0.7346444 -0.6341842 0.2410556 0.7346405 -0.6341776 0.2410855 0.7345 -0.6297054 0.2529445 0.8659319 -0.4754626 0.1552326 0.8430508 -0.5346322 0.05859738 0.8659282 -0.475469 0.1552339 0.8659107 -0.4754848 0.1552834 0.9498618 -0.3121334 0.01831209 0.9500017 -0.3117359 0.01781326 0.9664012 -0.2326468 0.1092885 0.9663961 -0.2326538 0.1093199 0.9664031 -0.2326427 0.1092818 0.9578995 -0.2087569 0.197102 0.957859 -0.2088658 0.1971838 0.9654433 -0.1872535 0.1812608 0.9085703 -0.3799571 0.1735875 0.9249603 -0.3637888 0.1100274 0.9416279 -0.3296477 0.06833297 0.9465557 -0.3209391 0.03210258 0.9489839 -0.3145481 0.02211666 0.8851612 -0.08206868 0.4579896 0.8851866 -0.08191865 0.4579673 0.8645011 -0.2163231 0.4536982 0.8953307 -0.1672289 0.4128165 0.9151909 -0.1052849 0.3890252 0.9407643 -0.1201431 0.3170621 0.9407474 -0.1201562 0.3171072 0.7473078 -0.0153858 0.6642999 0.7473013 -0.01542025 0.6643064 0.624931 0.4581556 0.6321034 0.7704848 -0.1934107 0.607409 0.7918575 -0.1205738 0.598685 0.7812721 -0.1905838 0.5943834 0.7549583 -0.2571796 0.6032385 0.728499 -0.4748458 0.4937717 0.7286248 -0.4745562 0.4938648 0.9549351 -0.09531921 0.2810928 0.9117013 -0.3038831 0.2765066 0.8655807 -0.3310078 0.3757711 0.8539572 -0.4283143 0.2954726 0.7217745 -0.4841324 0.4946286 0.6003276 -0.7190195 0.3501683 0.3693259 0.8094465 -0.4565026 0.3693194 0.4277378 -0.8250112 0.1210476 0.8646251 -0.4876176 0.1210538 0.4568948 -0.8812451 0.121064 0.09113782 -0.988452 0.1210595 -0.0997616 -0.9876195 0.1210324 -0.7603918 -0.6380873 0.1210435 -0.8686699 -0.4803759 0.09631556 0.9736098 -0.2068997 0.6039363 0.6062551 -0.5174127 0.6053639 0.6715683 -0.4272361 0.721893 -0.585413 -0.3690016 0.6049466 -0.6837819 -0.4080221 0.6441331 -0.6813452 -0.3476512 0.6310033 -0.6863235 -0.3616558 0.5212169 -0.7899982 -0.3228557 0.3979966 -0.8775102 -0.2675344 0.2575173 -0.9195739 -0.2967637 0.2575983 -0.9449039 -0.2019896 0.2672523 -0.9448319 -0.189391 0.02128863 -0.9787909 -0.2037528 0.2743154 0.9420876 -0.1929299 0.2727341 0.9425281 -0.1930202 0.2154017 0.9567201 -0.1956755 0.6582311 0.6748944 -0.3335403 0.6479936 0.6767092 -0.349527 0.607403 0.6919396 -0.3902324 0.5278607 0.7849327 -0.3244131 0.5278613 0.7849235 -0.3244341 0.5278677 0.7849265 -0.3244165 0.5264654 0.785588 -0.3250935 0.370698 0.8589985 -0.3531353 0.4041215 0.8738445 -0.2703358 0.3706533 0.881472 -0.2926149 0.2606129 0.9437617 -0.2034573 0.2606128 0.9437621 -0.2034554 0.121046 -0.9446724 -0.3048635 0.1210544 -0.9446728 -0.3048592 0.1215911 -0.9732215 -0.1950784 0.1575979 -0.9829642 -0.09457516 0.1521887 -0.9796561 -0.130815 0.1210532 -0.6239033 -0.7720692 0.1210549 -0.4642425 -0.8773966 0.1210558 -0.09975981 -0.9876201 0.1210555 -0.2873389 -0.9501484 0.1210641 -0.2873288 -0.9501503 0.1210678 -0.2873317 -0.950149 0.1210663 -0.4642359 -0.8773984 0.1210454 0.2793874 -0.9525181 0.1210453 0.09152394 -0.9884187 0.1210504 0.6174315 -0.7772548 0.1210553 0.6174293 -0.7772559 0.1210471 0.7550472 -0.6444001 0.1210553 0.7550436 -0.6444025 0.1210502 0.7550491 -0.6443973 0.1044669 0.9829611 -0.1512421 0.1215109 0.9758954 -0.1812828 0.1210514 0.9420938 -0.312739 0.1210516 0.9420938 -0.3127391 0.1210368 -0.8686642 -0.480388 0.1210368 -0.8686642 -0.480388 0.3693279 -0.8132277 -0.4497306 0.3694004 -0.8836545 -0.2875724 0.5212398 -0.7899851 -0.3228507 0.5222181 -0.7895633 -0.3223015 0.522179 -0.7463158 -0.412725 0.3693313 -0.8132274 -0.4497282 0.3693345 -0.7118726 -0.5973519 0.1210553 -0.7604004 -0.6380727 0.1210525 -0.7604036 -0.6380695 0.3693267 -0.09340238 -0.9245938 0.3693146 -0.09339582 -0.9245993 0.369315 -0.2689933 -0.8895218 0.3693169 -0.2689942 -0.8895207 0.3693174 -0.4346098 -0.8214128 0.3693338 -0.4346153 -0.8214026 0.3693318 -0.5840867 -0.7227978 0.369324 0.2615509 -0.8917348 0.1210539 0.2793793 -0.9525194 0.121052 0.2793803 -0.9525192 0.3693198 0.5780313 -0.7276557 0.3693252 0.5780276 -0.727656 0.3693246 0.7068634 -0.6032773 0.6039348 -0.6105544 -0.5123341 0.6039364 -0.610549 -0.5123384 0.3693191 -0.7118717 -0.5973628 0.3693182 -0.5840839 -0.7228072 0.1210348 -0.6238975 -0.7720767 0.1210319 -0.4641706 -0.8774377 0.603946 -0.6105483 -0.512328 0.6039475 -0.5009424 -0.6199228 0.603942 -0.5009521 -0.6199201 0.6039309 -0.500948 -0.6199343 0.6039294 -0.3727529 -0.7045031 0.6039321 -0.3727535 -0.7045004 0.6039398 -0.3727624 -0.7044892 0.6039405 -0.2307083 -0.7629086 0.6039443 -0.2307046 -0.7629066 0.6039377 -0.2306807 -0.7629192 0.6039364 -0.08010846 -0.7929965 0.6039363 -0.08010834 -0.7929966 0.6039268 0.07368868 -0.7936261 0.1210431 0.09152287 -0.988419 0.3693267 0.08568215 -0.9253412 0.369324 0.08568388 -0.9253422 0.6039293 0.07348889 -0.7936427 0.603954 0.073471 -0.7936256 0.6039537 0.2243307 -0.7647978 0.6039531 0.2243286 -0.764799 0.3693072 0.2615622 -0.8917384 0.3693082 0.4277458 -0.8250122 0.1210439 0.4569002 -0.8812437 0.1210568 0.4569589 -0.8812116 0.6039469 0.2243349 -0.764802 0.6039454 0.3668681 -0.7075717 0.6039347 0.3668574 -0.7075864 0.6039331 0.3668596 -0.7075865 0.6039339 0.4957578 -0.6240897 0.6039276 0.495764 -0.624091 0.6039313 0.4957565 -0.6240934 0.6039329 0.6062555 -0.517416 0.6039362 0.6062552 -0.5174125 0.3693245 0.7068635 -0.6032773 0.3693236 0.809448 -0.4565019 0.1210508 0.8646237 -0.4876192 0.1210524 0.8646255 -0.4876157 0.5933067 -0.7538251 -0.2823734 0.6028723 -0.7526701 -0.2646371 0.304256 -0.9462995 -0.109296 0.3022759 -0.9470646 -0.1081564 0.3042496 -0.9463924 -0.1085056 0.3207495 -0.9440268 -0.0770266 0.3048671 0.9460659 -0.1096147 0.3024604 0.9470414 -0.1078438 0.304321 0.9463846 -0.1083741 0.3207669 0.9440234 -0.0769968 0.3042702 0.9462977 -0.1092712 0.6029006 0.7526646 -0.2645882 0.5933304 0.7538211 -0.2823346 -0.4587296 -0.7710226 0.4416915 -0.8091901 -0.1732118 -0.5614348 -0.4409939 -0.8126819 -0.3808839 -0.5501499 -0.6599795 -0.5116271 -0.5501523 -0.6599758 -0.5116292 -0.6762496 -0.4133609 -0.6097697 -0.7450516 -0.1337598 -0.6534575 -0.7450546 -0.1337873 -0.6534482 -0.7553363 -0.1737232 -0.6318919 -0.7663404 -0.1268023 -0.6297965 -0.6762453 -0.4133737 -0.6097658 -0.8091892 -0.1732101 -0.5614367 -0.8091896 -0.1732248 -0.5614316 -0.8872158 -0.1732214 -0.4276006 -0.8872155 -0.1732083 -0.4276067 -0.8872082 -0.1732205 -0.4276172 -0.9432892 -0.173217 -0.2831985 -0.9432914 -0.1732083 -0.2831964 -0.9688501 -0.1732075 0.176999 -0.9846189 -0.17321 0.0228905 -0.9846189 -0.17321 0.0228905 -0.9846187 -0.1732111 0.02289104 -0.9760287 -0.1732068 -0.1317849 -0.976028 -0.173212 -0.1317832 -0.9760279 -0.173209 -0.1317884 -0.9291122 -0.1732047 0.3267269 -0.9291098 -0.1732069 0.3267328 -0.96885 -0.1732082 0.1769988 -0.7094067 -0.1736333 0.6830765 -0.7822217 -0.1732126 0.5984368 -0.7822218 -0.173214 0.5984364 -0.8663852 -0.1732131 0.4683737 -0.8663849 -0.1732113 0.4683751 -0.8663877 -0.173204 0.4683723 -0.9291122 -0.1732058 0.3267266 -0.7094171 -0.1736135 0.6830708 -0.7094214 -0.1736305 0.6830621 -0.7094233 -0.1736232 0.6830619 -0.6179094 -0.5140274 0.5949486 -0.4587467 -0.7710021 0.4417092 -0.4587438 -0.7710043 0.4417088 -0.5065428 -0.7702211 0.3875227 -0.5065444 -0.77022 0.3875229 -0.5065497 -0.7702065 0.3875427 -0.5610538 -0.770209 0.3033096 -0.6016663 -0.7702151 0.2115807 -0.6016709 -0.770213 0.2115753 -0.5610514 -0.7702117 0.3033071 -0.6273985 -0.7702164 0.11462 -0.6274011 -0.7702144 0.1146193 -0.6016691 -0.7702123 0.211583 -0.6320431 -0.7702195 -0.0853433 -0.6365032 -0.7710719 -0.01766121 -0.6714205 -0.7409122 0.01560938 -0.6362725 -0.770781 0.03246551 -0.6273977 -0.7702172 0.1146188 -0.6320404 -0.7702224 -0.08533793 -0.6320416 -0.7702213 -0.08533859 -0.6108433 -0.7702198 -0.1833902 -0.610843 -0.7702201 -0.18339 -0.6108427 -0.7702202 -0.1833902 -0.5745329 -0.7702191 -0.2769017 -0.574531 -0.7702205 -0.2769014 -0.4751489 -0.8097237 -0.3443561 -0.4932493 -0.7711985 -0.40244 -0.5239967 -0.7702274 -0.3635616 -0.5240031 -0.770219 -0.3635703 -0.5240027 -0.7702201 -0.3635684 -0.6762466 -0.413594 -0.609615 -0.6749381 -0.5141779 -0.5292255 -0.7052202 -0.5130832 -0.4892956 -0.7052221 -0.5130761 -0.4893003 -0.7732211 -0.5130786 -0.3726654 -0.7732176 -0.5130882 -0.3726596 -0.8220863 -0.5130876 -0.2468104 -0.8220863 -0.5130876 -0.2468104 -0.8506181 -0.5130867 -0.1148517 -0.8506169 -0.513089 -0.1148507 -0.8581055 -0.5130858 0.01994931 -0.8581051 -0.5130862 0.01994949 -0.8443627 -0.5130853 0.1542564 -0.844361 -0.513088 0.1542571 -0.8097282 -0.5130892 0.2847449 -0.8097242 -0.5130951 0.2847459 -0.7550567 -0.5130987 0.4081901 -0.7550586 -0.513096 0.40819 -0.6817088 -0.5130985 0.5215392 -0.6817231 -0.5130783 0.5215403 -0.6179102 -0.5140227 0.5949518 -0.6179013 -0.5140342 0.5949512 0.009780406 -0.9987335 -0.04935306 -0.2660544 -0.9287039 -0.2583099 0.302291 -0.9045158 -0.3007844 0.3026015 -0.9042978 -0.3011276 0.1398519 -0.9816151 -0.1298967 0.1398515 -0.9816154 -0.1298958 0.1398425 -0.9816179 -0.1298858 0.446803 -0.7710796 -0.4536553 0.4468008 -0.771084 -0.4536502 0.446792 -0.7710949 -0.4536404 0.5568228 -0.5858197 -0.5888664 0.5568014 -0.5858638 -0.5888428 0.6663696 -0.1323409 -0.7337829 0.6599165 -0.1193582 -0.7417978 0.6599146 -0.1193318 -0.7418037 0.6333788 -0.3613005 -0.6843195 0.6333564 -0.3613868 -0.6842948 0.5803447 -0.1320243 -0.8035979 0.5803319 -0.1320271 -0.8036067 0.5803338 -0.1320356 -0.803604 0.4490907 -0.1320357 -0.8836764 0.4490832 -0.132048 -0.8836785 0.4490732 -0.1320323 -0.8836859 0.3070318 -0.132032 -0.9424961 0.3070356 -0.1320453 -0.942493 0.1574553 -0.1320443 -0.9786583 0.1575887 -0.1320297 -0.9786388 0.1575934 -0.1320435 -0.9786363 0.00437349 -0.1320436 -0.9912342 0.004373133 -0.1320441 -0.9912342 0.004361569 -0.1320284 -0.9912364 -0.1489701 -0.1320285 -0.979988 -0.1489662 -0.1320393 -0.9799871 -0.2992748 -0.1320333 -0.9449877 -0.298721 -0.132013 -0.9451658 -0.2987107 -0.1320402 -0.9451652 -0.4412922 -0.13204 -0.887596 -0.4412844 -0.132026 -0.8876019 -0.4412798 -0.1320328 -0.8876032 -0.6649703 -0.1989025 -0.7198975 -0.5732378 -0.1320329 -0.8086814 -0.573235 -0.1320188 -0.8086858 -0.5730879 -0.1320222 -0.8087894 -0.6442004 -0.1324054 -0.7533093 -0.6652735 -0.03726243 -0.7456693 -0.5755862 -0.4411966 -0.68851 -0.5755577 -0.4412406 -0.6885057 -0.6649921 -0.1988397 -0.7198946 -0.6649719 -0.1989896 -0.7198718 -0.4923106 -0.6501493 -0.5787367 -0.3979902 -0.8113365 -0.4281786 -0.397959 -0.8113589 -0.4281651 -0.3979576 -0.8113604 -0.4281637 -0.1054733 -0.9917045 -0.07346826 -0.2659416 -0.9287705 -0.2581869 -0.08127307 -0.9918795 -0.09782481 -0.05543351 -0.9983139 -0.01722055 -0.03113752 -0.9988122 -0.03747773 -0.03426659 -0.9982429 -0.04834067 -0.02649199 -0.9987796 -0.0416826 -0.009293496 -0.9987269 -0.04957973 -0.01673501 -0.998457 -0.05294978 -0.01650011 -0.9985569 -0.05110728 -0.02193158 -0.9986681 -0.04670161 -0.0230025 -0.9986642 -0.04626774 -0.02529287 -0.9982284 -0.05385297 -0.02649199 -0.9987795 -0.0416826 -0.009289801 -0.9987269 -0.04958063 -0.008776366 -0.9982931 -0.05773866 -0.002846658 -0.9988021 -0.04884868 -0.002845346 -0.9988022 -0.0488488 2.61606e-4 -0.9982311 -0.05945354 0.003351986 -0.998804 -0.04877781 0.008015453 -0.9987282 -0.04977637 0.01237154 -0.9979736 -0.06241434 0.003351688 -0.998804 -0.04877787 0.01781171 -0.9984216 -0.05326342 0.01660019 -0.9985628 -0.05095815 0.02250385 -0.9986584 -0.04663562 0.02250099 -0.9986584 -0.04663676 0.02591854 -0.9983623 -0.05100017 0.02697139 -0.9987753 -0.04147702 0.02697181 -0.9987754 -0.04147678 0.03465598 -0.9982464 -0.04798984 0.03154993 -0.9988079 -0.03724646 0.02838641 -0.9987993 -0.03992694 0.02093786 -0.9994752 -0.02471733 0.3022848 -0.9045167 -0.3007882 0.1438996 -0.9684973 -0.2032384 0.1456865 -0.9685436 -0.2017394 0.1456866 -0.9685435 -0.2017394 0.1127398 -0.9685436 -0.2218403 0.1127407 -0.9685433 -0.221841 0.07707661 -0.9685432 -0.2366074 0.07707828 -0.9685428 -0.2366093 0.03956329 -0.9685427 -0.2456824 0.03956192 -0.9685432 -0.2456803 0.001097321 -0.9685432 -0.2488428 0.001094877 -0.9685446 -0.2488375 -0.03739649 -0.9685447 -0.2460139 -0.03739517 -0.9685435 -0.2460185 -0.0749939 -0.9685435 -0.237275 -0.07499337 -0.9685424 -0.2372794 -0.1107833 -0.9685425 -0.2228285 -0.1107834 -0.9685416 -0.2228322 -0.1439095 -0.9685418 -0.2030194 -0.1439087 -0.9685428 -0.2030151 -0.134965 -0.9682613 -0.2103674 -0.1054682 -0.991706 -0.07345592 0.4467675 -0.7711148 -0.4536308 0.3212174 -0.8522075 -0.4129912 0.3067867 -0.8517092 -0.4248216 0.3067852 -0.8517101 -0.4248209 0.2374089 -0.85171 -0.467148 0.2374039 -0.8517134 -0.4671443 0.1623065 -0.8517135 -0.4982377 0.1623037 -0.8517156 -0.4982349 0.08330488 -0.8517155 -0.5173404 0.08331084 -0.85171 -0.5173485 0.002310991 -0.8517101 -0.5240083 0.002310752 -0.8517104 -0.5240077 -0.078749 -0.8517107 -0.5180615 -0.07874995 -0.8517123 -0.5180585 -0.1579158 -0.8517122 -0.4996487 -0.1579175 -0.8517177 -0.4996389 -0.2332803 -0.8517169 -0.4692105 -0.2332801 -0.8517131 -0.4692176 -0.3030283 -0.851713 -0.4275028 -0.3030269 -0.8517184 -0.4274932 -0.31954 -0.8522615 -0.4141795 -0.2659505 -0.9287661 -0.2581931 0.5568155 -0.5858393 -0.5888538 0.4819979 -0.6529794 -0.5842055 0.4439647 -0.6518818 -0.6147727 0.4439589 -0.6518879 -0.6147704 0.3435553 -0.6518878 -0.6760266 0.3435662 -0.6518755 -0.676033 0.2348892 -0.6518751 -0.7210311 0.2348821 -0.6518841 -0.7210254 0.1205585 -0.6518837 -0.7486743 0.1205548 -0.6518892 -0.7486703 0.003345191 -0.6518892 -0.758307 0.003344357 -0.6518906 -0.7583057 -0.1139671 -0.6518906 -0.7497 -0.1139616 -0.6518773 -0.7497125 -0.2285286 -0.6518777 -0.7230699 -0.2285288 -0.6518784 -0.7230693 -0.33759 -0.651879 -0.6790338 -0.3375917 -0.651894 -0.6790184 -0.4385299 -0.6518931 -0.6186493 -0.4385306 -0.6518775 -0.6186652 -0.4930503 -0.6529686 -0.5749202 -0.4922851 -0.6502311 -0.5786665 0.6333289 -0.3614361 -0.6842941 0.6013427 -0.3994202 -0.6919902 0.5369792 -0.3984345 -0.7435746 0.5369807 -0.3984321 -0.7435749 0.4155367 -0.3984325 -0.8176679 0.4155371 -0.3984317 -0.817668 0.284096 -0.398432 -0.8720902 0.2841002 -0.3984242 -0.8720925 0.1458172 -0.398424 -0.9055361 0.1458179 -0.3984223 -0.9055368 0.004046499 -0.3984223 -0.9171931 0.004046082 -0.3984233 -0.9171927 -0.1378423 -0.3984236 -0.9067845 -0.1378459 -0.3984339 -0.9067794 -0.2764052 -0.3984336 -0.8745576 -0.2764061 -0.3984374 -0.8745554 -0.4083185 -0.3984367 -0.8212941 -0.4083178 -0.3984325 -0.8212965 -0.5304124 -0.3984321 -0.7482744 -0.5304128 -0.3984367 -0.7482717 -0.619111 -0.3990769 -0.6763424 -0.6057882 -0.4422668 -0.6613779 0.7397283 -0.5399567 0.4015581 0.8347029 -0.539963 -0.1082168 0.4965996 -0.7800942 0.3805813 0.5896862 -0.7800929 0.209106 0.6204644 -0.7800981 -0.08044081 0.7563999 -0.0525434 -0.6519957 0.7649444 -0.2610942 -0.5888035 0.6471944 -0.5524634 -0.5252843 0.7227503 -0.2708638 -0.6358183 0.7227628 -0.2708051 -0.635829 0.4773303 -0.7758899 -0.4124932 0.4773025 -0.7759194 -0.4124696 0.4811292 -0.7757018 -0.4084134 0.4747992 -0.7808968 -0.4059137 0.5168599 -0.780102 -0.3525573 0.5168573 -0.780104 -0.3525568 0.5168569 -0.7801048 -0.3525555 0.5655098 -0.7801033 -0.267652 0.5655135 -0.7800996 -0.2676553 0.6003339 -0.7800972 -0.1762039 0.600329 -0.7801008 -0.1762039 0.600332 -0.780099 -0.1762017 0.6150785 -0.7800936 0.1145976 0.6150784 -0.7800935 0.1145976 0.6150779 -0.780094 0.114597 0.625423 -0.7800943 0.01728928 0.6792856 -0.7329902 0.03600674 0.6244102 -0.7809365 -0.01581752 0.4965982 -0.780097 0.380577 0.7071627 -0.1893901 0.6812139 0.449929 -0.780853 0.4333965 0.4499388 -0.7808464 0.4333981 0.6057708 -0.5408955 0.5835013 0.6057523 -0.5409169 0.5835006 0.6057456 -0.5409445 0.583482 0.7071843 -0.1893867 0.6811924 0.7071837 -0.1893854 0.6811934 0.6385633 -0.5534209 -0.5347545 0.6496174 -0.5411031 -0.5340455 0.6953341 -0.5399547 -0.4742988 0.6953368 -0.5399512 -0.474299 0.7607862 -0.5399541 -0.3600749 0.7607771 -0.5399662 -0.3600759 0.8076185 -0.5399653 -0.2370439 0.8413669 -0.5399637 0.02325886 0.841367 -0.5399636 0.02325886 0.8274488 -0.5399645 0.1541652 0.7932917 -0.5399608 0.2813017 0.7397273 -0.5399596 0.4015561 0.5498601 -0.7801018 0.298488 0.5498701 -0.780094 0.29849 0.8875914 -0.1889469 -0.4200958 0.8875903 -0.1889505 -0.4200965 0.8112312 -0.1889543 -0.5533537 0.8112323 -0.1889514 -0.553353 0.8112216 -0.1889387 -0.553373 0.7502448 -0.1894441 -0.6334379 0.7649445 -0.2609844 -0.5888523 0.8875952 -0.1889407 -0.4200908 0.9422412 -0.1889401 -0.2765559 0.8076202 -0.5399631 -0.2370434 0.8347029 -0.5399632 -0.1082168 0.6204628 -0.7800994 -0.08044123 0.6204643 -0.780098 -0.08044368 0.9422405 -0.1889427 -0.2765566 0.9738387 -0.1889402 -0.1262537 0.9738385 -0.1889396 -0.1262553 0.9738387 -0.1889388 -0.126255 0.9816139 -0.1889388 0.02713584 0.9816138 -0.1889391 0.02713578 0.9816139 -0.1889389 0.0271359 0.9653768 -0.1889356 0.1798639 0.8274499 -0.5399626 0.1541661 0.7932912 -0.5399617 0.2813011 0.5896787 -0.7801001 0.2091001 0.5896797 -0.7800997 0.209099 0.9653761 -0.1889412 0.1798619 0.9255093 -0.1889428 0.3282272 0.9255241 -0.1889328 0.3281913 0.9255238 -0.1889372 0.3281896 0.863029 -0.1889365 0.4684912 0.8630289 -0.1889454 0.4684878 0.863029 -0.1889458 0.4684875 0.4966015 -0.7800927 0.3805817 0.6680686 -0.5399547 0.5119894 0.6680644 -0.5399703 0.5119785 0.7794263 -0.1889476 0.5973219 0.7794259 -0.1889392 0.5973251 -0.9905951 0.01495033 0.1360073 -0.9591513 0.278944 0.04710793 -0.6954081 -0.005890488 0.718591 -0.7083938 -0.2030532 0.675979 -0.1210195 -0.9730425 -0.1963226 -0.1520338 -0.9883751 5.41561e-4 -0.5080644 -0.8496155 0.1415064 -0.134577 -0.9888271 0.06411123 -0.2412584 -0.9691817 0.04981333 -0.2249801 -0.9692748 0.09945064 -0.2708919 -0.9589836 0.08347475 -0.2492777 -0.9606538 0.1224946 -0.3537054 -0.9335924 0.05742555 -0.2852182 -0.9455469 0.1568173 -0.4726179 -0.8781635 0.07389885 -0.4287884 -0.8953405 0.1204407 -0.5725823 -0.6874779 0.4466807 -0.511317 -0.8110375 0.2842063 -0.6913031 -0.5812773 0.4292048 -0.6913101 -0.581279 0.4291911 -0.6962472 -0.6489604 0.3067415 -0.5113505 -0.8110045 0.2842399 -0.5113218 -0.8110182 0.2842526 -0.7178943 -0.4565795 0.5255123 -0.7178652 -0.4566074 0.5255278 -0.7915541 -0.254999 0.5553536 -0.763351 -0.2360832 0.6012986 -0.70854 -0.2028574 0.6758846 -0.7577993 -0.1853627 0.6256045 -0.7578732 -0.1855844 0.6254492 -0.6542743 -0.08783763 0.7511389 -0.68987 -0.03419744 0.7231251 -0.6939958 -0.05198657 0.7180997 -0.6939946 -0.05198884 0.7181007 -0.6947057 -0.02120172 0.7189816 -0.6947247 -0.02112418 0.7189655 -0.6969195 -0.02112078 0.7168383 -0.6965792 -0.02205252 0.7171409 -0.6915262 -0.03258228 0.7216162 -0.6949782 -0.009206593 0.7189719 -0.6898153 -0.004837989 0.7239692 -0.6933113 -0.01081764 0.720557 -0.6937484 -0.001743674 0.7202152 -0.691675 -0.008725702 0.7221562 -0.6922603 -0.008740544 0.7215949 -0.7994315 0.03798621 0.5995551 -0.9354212 0.04892343 0.350134 -0.9074385 0.0833891 0.4118275 -0.9277305 0.03874057 0.3712348 -0.8870831 -0.01076352 0.4614844 -0.8870804 -0.0107637 0.4614894 -0.9892859 0.05509907 0.1351944 -0.9574586 0.03870183 0.2859635 -0.9427643 0.04267323 0.3307184 -0.996361 0.01646482 0.08362793 -0.9900164 0.07962429 0.1163079 -0.9666096 0.1933464 0.1681758 -0.9903336 0.127656 0.05425208 -0.9773373 0.1934912 0.08586674 -0.9550862 0.2786007 0.1009555 -0.9671472 0.2364098 0.09346932 -0.97724 0.2098305 0.03119355 -0.9686413 0.2320719 0.08875113 -0.9671453 0.2364166 0.09347271 -0.9585172 0.2809205 0.04825282 -0.9585161 0.2809162 0.048303 -0.9585179 0.2809172 0.04825967 -0.9877876 -0.1226115 0.09613496 -0.987789 -0.1225947 0.09614259 -0.991414 -0.05132079 0.1202684 -0.9055056 -0.4031341 0.1324478 -0.9055059 -0.4031335 0.1324473 -0.9310791 -0.3595007 0.06205517 -0.9298081 -0.3619327 0.06679385 -0.9584729 -0.2519651 0.1335788 -0.9584695 -0.2519773 0.1335813 -0.801878 -0.5927307 0.07524704 -0.8607196 -0.4971869 0.1093934 -0.9055031 -0.4031392 0.13245 -0.7416207 -0.6612607 0.112841 -0.7999034 -0.5930039 0.09220051 -0.7998976 -0.5930111 0.0922048 -0.5080634 -0.849616 0.1415069 -0.5691326 -0.8176617 0.08670288 -0.5911741 -0.8043736 0.05912977 -0.6703596 -0.7320236 0.1214895 -0.7416509 -0.661228 0.1128343 -0.7204931 -0.1199792 0.683004 -0.7800562 -0.237553 0.5788618 -0.8092771 -0.1848886 0.5575723 -0.8066387 -0.1306896 0.5764151 -0.8122231 -0.1157526 0.5717473 -0.8054519 -0.07793581 0.5875145 -0.8089637 -0.06336247 0.5844339 -0.9755048 -0.1858935 0.1176175 -0.9877441 -0.1246472 0.09394001 -0.9183683 -0.06439614 0.3904519 -0.9268144 -0.0460565 0.3726846 -0.8009121 -0.01533043 0.5985857 -0.8012163 0.03164023 0.5975378 -0.7933683 0.00992459 0.6086611 -0.7405183 -0.4532756 0.4961591 -0.7229563 -0.5846613 0.3681104 -0.820198 -0.4840023 0.304987 -0.8464751 -0.3802823 0.3726464 -0.8900503 -0.3026972 0.3408589 -0.9028403 -0.1981794 0.3815813 -0.906427 -0.194999 0.3746537 -0.9250438 -0.1221674 0.3596791 -0.8022077 -0.041664 0.5955895 -0.8045317 -0.02297902 0.5934652 -0.6909846 -0.00239408 0.7228655 -0.6918128 -0.001679658 0.722075 -0.9209354 0.3894854 0.01338368 -0.6873158 0.7047405 0.1758913 -0.484995 0.8230293 0.2956393 -0.4874394 0.8259227 0.2832922 -0.4003975 0.8478406 0.347632 -0.3990488 0.8487959 0.3468509 -0.5949103 0.7727022 0.2213891 -0.4716597 0.8102572 0.34788 -0.5013101 0.8089069 0.3071776 -0.5949157 0.7726991 0.2213854 -0.4324408 0.8551527 0.2858474 -0.4724783 0.8366681 0.2770394 -0.4874488 0.8259098 0.2833136 -0.3867724 0.8582129 0.3374578 -0.4213889 0.8475608 0.3226019 -0.3439878 0.9065909 0.2444695 -0.3995496 0.8654951 0.3021231 -0.4072255 0.8600459 0.3073899 -0.4120047 0.8557245 0.3130301 -0.4099123 0.8601433 0.3035219 -0.4329195 0.8508867 0.2976115 -0.4329279 0.8508784 0.2976229 -0.5316071 0.8330994 0.1527725 -0.5315935 0.8330942 0.1528482 -0.5144016 0.8296073 0.2171238 -0.5144338 0.8295958 0.2170913 -0.4603327 0.8465016 0.2674487 -0.4446156 0.8510621 0.2793034 -0.6841195 0.7252038 0.07784622 -0.684327 0.7254157 0.07394999 -0.6320637 0.7554327 0.1726762 -0.5114618 0.8478049 0.1401204 -0.5316082 0.8330983 0.1527741 -0.6841182 0.7252053 0.07784354 -0.7566365 0.6395185 0.1360785 -0.7885184 0.6137708 0.03903943 -0.7801604 0.5880157 0.2135117 -0.7888593 0.5919524 0.1652068 -0.8183625 0.573299 0.04014039 -0.8083796 0.563131 0.1714814 -0.8372249 0.5457375 0.03500401 -0.8374962 0.5446874 0.0437687 -0.8560084 0.5048373 0.1113051 -0.8385038 0.5431911 0.04306584 -0.8606514 0.4966828 0.1121848 -0.8819627 0.4708367 0.02132296 -0.8906405 0.4493464 0.06962138 -0.893938 0.4457757 0.04646348 -0.9021763 0.4310433 0.01672077 -0.9221588 0.3837912 0.04824519 -0.9188387 0.39343 0.03079247 -0.5545253 -0.8202567 -0.1402884 -0.401868 -0.9081937 -0.1169887 -0.5545175 -0.8202604 -0.1402966 -0.55453 -0.8202525 -0.1402937 -0.4542703 -0.8810838 -0.1316435 -0.4411611 -0.8915528 -0.1025202 -0.4411645 -0.8915517 -0.1025155 -0.679872 -0.7114354 -0.1778588 -0.5498738 -0.8349201 -0.02339076 -0.6018071 -0.7725968 -0.2022927 -0.640859 -0.7477566 -0.173666 -0.6697893 -0.7325792 -0.1212847 -0.6720213 -0.7301265 -0.1237042 -0.6941516 -0.6093598 -0.3831897 -0.6948502 -0.6281287 -0.3501964 -0.7006115 -0.5995749 -0.3868506 -0.7041242 -0.6202923 -0.3456103 -0.6941555 -0.6093571 -0.3831869 -0.6936111 -0.6182359 -0.3697135 -0.6807503 -0.636686 -0.3622292 -0.6674262 -0.6536122 -0.3568379 -0.6673088 -0.6545723 -0.3552943 -0.6673266 -0.654564 -0.3552759 -0.3124607 -0.9452306 -0.0943796 -0.3123294 -0.9452818 -0.09430146 -0.5988321 -0.7529978 -0.2727532 -0.6313003 -0.707577 -0.317482 -0.6308522 -0.7051426 -0.3237273 -0.6410922 -0.7021545 -0.3098062 -0.668031 -0.6490395 -0.3639813 -0.6680471 -0.6489707 -0.3640742 -0.9890337 0.003476202 0.1476488 -0.8690648 -0.004097342 0.4946812 -0.8887759 6.64563e-4 0.4583415 -0.8687974 6.78571e-4 0.4951673 -0.3667829 -6.14596e-4 0.9303064 -0.6331808 0.004514336 0.7739907 -0.6708683 -0.003354728 0.7415689 -0.8886343 0.004369318 0.4585957 0.3094102 0.005856454 0.9509106 0.3661076 -0.005922019 0.9305537 0.01393359 0.004305183 0.9998936 -0.03015667 0.001249969 0.9995445 -5.86069e-6 0.001256883 0.9999992 -0.03025865 0.001246869 0.9995414 0.01401609 -0.003180027 0.9998968 -0.3667145 0.00340712 0.9303273 -0.3258244 -0.004721939 0.9454185 -0.6337586 -3.91632e-4 0.7735308 0.3091525 0.005864858 0.9509944 0.6242097 3.43646e-4 0.7812568 0.3653895 5.81576e-4 0.9308546 0.6243273 -0.004792034 0.7811481 0.661876 0.002693355 0.7496086 0.8596747 -0.002889752 0.5108337 0.8678518 -0.001583456 0.4968206 0.8596333 -0.001585483 0.5109093 0.8677975 -2.12901e-4 0.496918 0.9840876 1.18741e-4 0.1776838 0.9839709 0 0.1783289 0.9857495 0 -0.1682196 0.9890317 0.003553986 -0.1476605 0.8687298 -0.004185974 -0.4952688 0.8887763 6.5362e-4 -0.4583409 0.8684722 6.68087e-4 -0.4957374 0.8886638 0.004434466 -0.4585379 0.6708703 -0.003386795 -0.7415671 0.6328591 0.004535555 -0.7742536 0.3667815 -5.88616e-4 -0.9303069 0.6329348 -3.64554e-4 -0.774205 0.3669806 -0.004228115 -0.930219 0.3257459 -0.003441214 -0.9454511 0.3667461 0.003366351 -0.9303151 -0.01397955 -0.003135442 -0.9998974 0.03015667 0.001277506 -0.9995443 4.05679e-6 0.001287519 -0.9999992 0.03015649 0.001280605 -0.9995444 -0.01390838 0.004334032 -0.9998939 -0.3098598 -0.004271268 -0.9507727 -0.3655148 0.00499165 -0.9307922 -0.6237917 3.64274e-4 -0.7815906 -0.3658175 6.02679e-4 -0.9306864 -0.6243277 -0.004799127 -0.7811478 -0.6619443 0.002693891 -0.7495482 -0.8596748 -0.0028916 -0.5108336 -0.8678886 -0.001579582 -0.4967563 -0.8596331 -0.00158149 -0.5109094 -0.8677856 -2.11019e-4 -0.4969387 -0.9840876 1.20902e-4 -0.177684 -0.9839689 0 -0.1783407 -0.9858199 0 0.1678068 0.8808079 0.2967786 0.3689173 0.5216022 0.7693058 0.3689172 -0.05032032 0.9280992 0.3689171 -0.6017212 0.7084009 0.3689171 -0.9294623 0 0.3689171 -0.7399384 -0.5624867 0.3689171 -0.2486573 -0.8955835 0.3689168 0.5216021 -0.7693057 0.3689174 0.5570707 0.8216184 0.1208947 -0.9694573 0.213394 0.1208948 -0.7902541 -0.6007353 0.120895 -0.2655662 -0.9564827 0.1208945 0.5570711 -0.8216181 0.1208947 0.9868463 -0.1073259 0.1208947 0.9407024 -0.3169596 0.1208947 0.9407026 -0.3169594 0.1208942 0.8505743 -0.5117696 0.1208943 0.8505725 -0.5117725 0.1208947 0.8505724 -0.5117725 0.1208946 0.7206705 -0.6826555 0.1208948 0.7206706 -0.6826555 0.1208947 0.7206706 -0.6826554 0.1208946 0.3674232 -0.9221631 0.1208949 0.3674231 -0.9221631 0.1208949 0.1605969 -0.9795882 0.1208948 0.1605955 -0.9795883 0.1208954 -0.07993823 -0.9817072 0.1728026 0.02687877 -0.9922209 0.121553 0.1605951 -0.9795885 0.1208946 -0.4649727 -0.8770317 0.1208949 -0.4649728 -0.8770318 0.120895 -0.6426379 -0.7565718 0.120895 -0.6426379 -0.7565719 0.1208949 -0.6426378 -0.7565719 0.1208949 -0.9009186 -0.4168095 0.1208946 -0.9009186 -0.4168093 0.1208948 -0.9694577 -0.213392 0.1208948 -0.9694574 -0.2133938 0.1208944 -0.9694573 -0.213394 0.1208948 -0.9926654 0 0.1208948 -0.9694577 0.2133919 0.1208948 -0.9009186 0.4168095 0.1208948 -0.6426379 0.7565719 0.120895 -0.7902541 0.6007353 0.120895 -0.4649728 0.8770319 0.120895 -0.4649727 0.8770317 0.1208949 -0.2655649 0.956483 0.1208949 -0.2655664 0.9564826 0.1208949 -0.05374139 0.9912095 0.120895 -0.05374217 0.9912096 0.1208944 -0.2655662 0.9564827 0.1208945 0.1605955 0.9795883 0.1208954 0.3674231 0.922163 0.1208948 0.3674231 0.922163 0.1208949 0.1605969 0.9795882 0.1208948 0.7206706 0.6826555 0.1208948 0.7206705 0.6826555 0.1208947 0.9407024 0.3169597 0.1208942 0.8505743 0.5117695 0.1208943 0.8505724 0.5117724 0.1208947 0.8505724 0.5117725 0.1208946 0.7206706 0.6826554 0.1208946 0.9868463 0.1073263 0.1208944 0.8808079 -0.2967786 0.3689173 0.8808079 -0.2967786 0.3689174 0.7964164 -0.4791878 0.3689173 0.7964164 -0.4791878 0.3689173 0.6747853 -0.6391907 0.3689173 0.3440293 -0.8634489 0.3689174 0.3440294 -0.8634489 0.3689172 0.1503704 -0.917218 0.3689173 -0.435368 -0.8211912 0.3689169 -0.4353681 -0.8211912 0.3689171 -0.6017212 -0.708401 0.3689171 -0.8435572 -0.3902711 0.3689171 -0.8435572 -0.390271 0.3689173 -0.9077319 -0.1998069 0.3689173 -0.9694574 0.2133938 0.1208944 -0.907732 0.199807 0.3689171 -0.9077319 0.1998071 0.3689173 -0.7399385 0.5624867 0.3689171 -0.7902539 0.6007356 0.1208947 -0.790254 0.6007353 0.1208946 -0.435368 0.8211912 0.3689171 -0.4353681 0.8211912 0.3689169 -0.2486578 0.8955833 0.3689169 0.1503705 0.9172181 0.3689172 0.1503705 0.917218 0.3689172 0.3440293 0.8634489 0.3689172 0.6747853 0.6391907 0.3689172 0.6747853 0.6391906 0.3689174 0.7964164 0.4791878 0.3689173 0.9868463 0.1073259 0.1208952 0.9240138 0.1004924 0.3689173 0.9240139 0.1004928 0.3689166 0.792724 -0.08621418 0.6034532 0.9240137 -0.1004928 0.3689173 0.924014 -0.1004924 0.3689166 0.9868463 -0.1073259 0.1208947 0.9868462 -0.1073262 0.1208952 0.6832566 -0.4111019 0.6034532 0.6832566 -0.4111018 0.6034532 0.7556576 -0.2546098 0.603453 0.7556571 -0.2546104 0.6034532 0.7556572 -0.2546105 0.6034532 0.792724 -0.08621406 0.6034532 0.5789076 -0.5483706 0.6034532 0.5789076 -0.5483705 0.6034532 0.6747854 -0.6391907 0.3689172 0.5216023 -0.7693057 0.3689172 0.557071 -0.8216181 0.1208949 0.5570707 -0.8216184 0.1208948 0.2951476 -0.7407647 0.6034529 0.2951475 -0.7407647 0.603453 0.4474926 -0.6599962 0.603453 0.4474896 -0.659998 0.6034532 0.4474896 -0.6599979 0.6034533 0.5789075 -0.5483705 0.6034533 0.1290047 -0.7868941 0.6034529 0.129005 -0.7868939 0.6034531 0.1503705 -0.917218 0.3689171 -0.05031991 -0.9280992 0.3689172 -0.05358839 -0.9883823 0.1422275 -0.08055996 -0.9893534 0.1212016 0.1290044 -0.7868937 0.6034534 -0.04317045 -0.7962287 0.6034534 -0.05032032 -0.9280989 0.3689177 -0.2486577 -0.895583 0.3689177 -0.2655664 -0.9564826 0.1208949 -0.2655649 -0.956483 0.1208949 -0.04317027 -0.796229 0.6034532 -0.2133262 -0.7683334 0.6034532 -0.2133265 -0.7683334 0.6034532 -0.2133266 -0.7683331 0.6034535 -0.3735081 -0.7045109 0.6034535 -0.373508 -0.7045114 0.6034531 -0.3735082 -0.704511 0.6034533 -0.5162249 -0.6077467 0.6034533 -0.6017212 -0.7084008 0.3689172 -0.7399385 -0.5624867 0.3689172 -0.7902539 -0.6007356 0.1208947 -0.7902541 -0.6007354 0.1208946 -0.5162249 -0.6077467 0.6034533 -0.6348026 -0.4825658 0.6034533 -0.6348033 -0.4825651 0.6034532 -0.6348033 -0.482565 0.6034532 -0.7236992 -0.3348188 0.6034532 -0.7236991 -0.3348186 0.6034535 -0.7236991 -0.3348193 0.6034531 -0.7787557 -0.1714172 0.6034531 -0.907732 -0.1998071 0.3689171 -0.9294623 0 0.3689171 -0.9926654 0 0.1208948 -0.9926654 0 0.1208948 -0.7787556 -0.1714169 0.6034535 -0.7973983 0 0.6034535 -0.7973982 0 0.6034535 -0.7973983 0 0.6034535 -0.7787555 0.1714172 0.6034534 -0.7787557 0.1714171 0.6034532 -0.7787558 0.1714169 0.6034532 -0.9009187 0.4168094 0.1208945 -0.8435571 0.3902711 0.3689174 -0.8435572 0.390271 0.3689171 -0.7236993 0.3348188 0.6034531 -0.7236992 0.3348189 0.6034532 -0.6348029 0.4825657 0.6034532 -0.6348031 0.4825649 0.6034533 -0.7399384 0.5624867 0.3689172 -0.6017212 0.7084009 0.3689172 -0.6426379 0.7565718 0.1208949 -0.6426379 0.7565719 0.1208949 -0.373508 0.704511 0.6034534 -0.3735081 0.704511 0.6034533 -0.516225 0.6077466 0.6034532 -0.5162248 0.6077467 0.6034533 -0.5162248 0.6077468 0.6034532 -0.6348033 0.4825649 0.6034532 -0.2133266 0.7683331 0.6034535 -0.2133265 0.7683333 0.6034533 -0.2486572 0.8955832 0.3689177 -0.05031991 0.9280989 0.3689177 -0.05374169 0.9912095 0.1208946 0.1605951 0.9795885 0.1208946 0.1290046 0.7868942 0.6034529 0.1290049 0.7868937 0.6034534 -0.04317009 0.7962287 0.6034535 -0.04317045 0.7962288 0.6034533 -0.04317039 0.796229 0.6034533 -0.2133266 0.7683333 0.6034531 0.2951477 0.7407646 0.6034529 0.2951475 0.7407647 0.603453 0.3440294 0.8634488 0.3689174 0.5216022 0.7693056 0.3689174 0.557071 0.8216181 0.1208949 0.5570711 0.8216181 0.1208948 0.5789076 0.5483705 0.6034532 0.5789076 0.5483704 0.6034532 0.4474903 0.6599974 0.6034533 0.4474897 0.6599981 0.6034531 0.4474897 0.659998 0.603453 0.2951476 0.7407647 0.603453 0.6832566 0.4111018 0.6034532 0.6832566 0.4111018 0.6034532 0.7964164 0.4791878 0.3689174 0.8808079 0.2967786 0.3689174 0.9407026 0.3169594 0.1208947 0.9868463 0.1073259 0.1208947 0.6832566 0.4111019 0.6034531 0.7556571 0.2546106 0.6034532 0.7556574 0.2546105 0.603453 0.7556576 0.2546091 0.6034533 0.792724 0.08621418 0.6034532 0.7927239 0.08621394 0.6034535 0.7927238 -0.0862137 0.6034535 -0.511054 0.005315542 -0.8595322 -0.6243627 -0.008350551 -0.7810899 -0.7809999 0.007860958 -0.6244817 -0.8490943 -0.003407061 -0.5282303 -0.7806403 -0.003351271 -0.6249716 -0.8489729 -0.005099594 -0.5284118 -0.9507001 0.006171584 -0.3100501 -0.9745336 -0.005855023 -0.2241651 -0.9977487 0.0010553 -0.0670557 0.309431 -0.005810678 -0.9509043 0.3665926 0.00605756 -0.9303618 0.0152778 -0.004379928 -0.9998736 0.06644421 -0.007924079 -0.9977587 -3.37128e-5 -0.007941067 -0.9999684 -0.177214 -0.007793843 -0.9841415 0.01531547 0.0272836 -0.9995104 -0.5087288 -0.02731204 -0.8604936 -0.3207524 0.01110398 -0.947098 -0.6258125 0.005208015 -0.7799561 0.3095926 -0.005805432 -0.9508516 0.6242763 -3.28257e-4 -0.7812036 0.365592 -5.62827e-4 -0.930775 0.6248373 0.004730224 -0.7807407 0.6606323 -0.002436935 -0.7507057 0.8596652 0.002595484 -0.5108512 0.8660918 0.001553714 -0.4998826 0.8596138 0.001554906 -0.5109421 0.8660293 4.8266e-4 -0.4999927 0.9840926 -5.17902e-4 -0.1776561 -0.9996948 0 -0.02470266 -0.9835846 0 0.1804477 -0.9840942 -5.22013e-4 0.1776464 -0.8660008 4.82684e-4 0.5000425 -0.8596135 0.001549959 0.5109424 -0.8661029 0.001548886 0.4998632 -0.8596383 0.002597033 0.5108966 -0.6605951 -0.00242871 0.7507386 -0.6248373 0.00473082 0.7807406 -0.3660871 -5.53001e-4 0.9305804 -0.6246963 -3.19887e-4 0.7808678 -0.3656792 -0.004930496 0.930728 -0.3099151 0.004320561 0.9507544 -0.01527762 -0.00439012 0.9998737 -0.06644594 -0.007934272 0.9977585 3.37506e-5 -0.007951259 0.9999684 0.1772459 -0.007803797 0.9841357 -0.01543962 0.02730631 0.9995079 0.5089103 -0.02733647 0.8603855 0.3203951 0.005144 0.94727 0.5110938 0.007681846 0.8594907 0.6257897 0.005208075 0.7799744 0.5110573 0.005315542 0.8595303 0.6243275 -0.008348405 0.7811181 0.7810311 0.007864296 0.6244426 0.8490931 -0.00339955 0.5282323 0.7804863 -0.003342807 0.6251639 0.8490203 -0.00509876 0.5283357 0.9507172 0.006167531 0.309998 0.9745355 -0.005854547 0.2241571 0.9977501 0.001054704 0.0670343 0.9996952 0 0.02468746 0.9835868 0 -0.1804356 -0.7126593 -0.1735936 0.6796925 -0.4810691 -0.7617973 0.4338633 -0.587755 -0.5536193 0.5899574 -0.6357704 -0.5134677 0.5763218 -0.6203044 -0.547877 0.5612959 -0.6374649 -0.513389 0.5745173 -0.63953 -0.5439713 0.543228 -0.6465262 -0.333478 0.686146 -0.4750086 -0.7704204 0.4252285 -0.4750274 -0.7704008 0.4252431 -0.498076 -0.7595314 0.4183686 -0.7166172 -0.1162408 0.6877119 -0.7166438 -0.1160144 0.6877226 -0.6784685 -0.1737068 0.7137973 -0.819817 -0.2618805 0.5092337 -0.7170094 -0.1159406 0.6873539 -0.6959368 -0.3241103 0.6407999 -0.6804696 -0.2949448 0.6707971 -0.7728548 -0.1039543 0.6260103 -0.7978002 -0.01899212 0.6026228 -0.7173068 -0.1156554 0.6870915 -0.9558244 -0.1959427 0.219103 -0.9587582 -0.2793881 0.05219948 -0.9562548 -0.2763864 0.09585064 -0.9450334 -0.2665814 0.1893305 -0.9686177 -0.1495739 0.1985131 -0.9686157 -0.1495833 0.1985156 -0.9467133 -0.2164439 0.2385079 -0.9178116 -0.2603743 0.2997116 -0.8500641 -0.2943273 0.4367637 -0.9160782 -0.1438722 0.3743014 -0.9160825 -0.143864 0.3742941 -0.9593461 -0.2775475 0.0512095 -0.9604598 -0.2736834 0.05113077 -0.9587599 -0.2793847 0.0521894 -0.9481347 -0.3175898 0.01331883 -0.9342266 -0.3561702 0.01906275 -0.9377605 -0.3456596 0.03353345 -0.9384998 -0.3418858 0.04829436 -0.8902744 -0.4383069 0.1236876 -0.8902735 -0.4383069 0.1236937 -0.8888472 -0.443042 0.1168945 -0.9275009 -0.3656163 0.07789015 -0.9384981 -0.341889 0.04830324 -0.7726585 -0.5493744 0.3180983 -0.7725678 -0.5493021 0.3184437 -0.7939556 -0.5682046 0.2162821 -0.7770495 -0.5294966 0.3403343 -0.8769092 -0.4394143 0.1947956 -0.8769064 -0.4394167 0.194803 -0.669887 -0.5366876 0.5130476 -0.6699087 -0.5366303 0.5130793 -0.6518883 -0.5775682 0.4913825 -0.6269096 -0.5466448 0.5551251 -0.5871933 -0.7802767 0.2153422 -0.5654086 -0.7441228 0.3558012 -0.5672259 -0.7471299 0.3464846 -0.53863 -0.7513513 0.3812466 -0.7156581 -0.5583188 -0.4196588 -0.6968451 -0.5494148 -0.4610317 -0.7095427 -0.595988 -0.3759621 -0.727273 -0.580628 -0.3659852 -0.8698229 -0.3006946 -0.3911406 -0.7166492 -0.5005151 -0.4856938 -0.707072 -0.5449424 -0.4506519 -0.7141188 -0.4919372 -0.4980283 -0.7141243 -0.4919316 -0.4980261 -0.7235671 -0.4795576 -0.4964627 -0.7148605 -0.5344582 -0.4509199 -0.7205574 -0.5355558 -0.4404282 -0.7160205 -0.5347477 -0.4487311 -0.7156606 -0.5582543 -0.4197405 -0.7156607 -0.5583227 -0.4196492 -0.7198653 0.4851828 -0.4963784 -0.7070291 0.5436787 -0.4522427 -0.7136558 0.4931082 -0.4975336 -0.7136656 0.4930981 -0.4975296 -0.8746914 0.2932922 -0.3858685 -0.7219175 0.4939504 -0.4846112 -0.7230311 0.5058507 -0.4704691 -0.5871457 0.5034986 -0.6338367 -0.7253053 0.5336702 -0.4348888 -0.7133191 0.5330846 -0.4549687 -0.7140606 0.5598961 -0.4202783 -0.7013028 0.5422369 -0.4627673 -0.7060778 0.5772605 -0.4101521 -0.7291535 0.5774078 -0.3673356 -0.7114084 0.5928347 -0.3774189 -0.7076751 0.5848285 -0.3964486 -0.7230144 0.505848 -0.4704976 -0.7089418 0.4994484 -0.4979488 -0.7101456 0.4379356 -0.5512763 -0.7064306 0.4282833 -0.5634973 -0.7050471 0.3263997 -0.6295807 -0.7096341 0.3407995 -0.6166647 -0.7098704 0.3242006 -0.6252823 -0.7124705 0.3394119 -0.6141542 -0.7030837 0.2503983 -0.665563 -0.7130214 0.1973361 -0.6727994 -0.7072576 0.1507035 -0.6907063 -0.7068576 0.199132 -0.678748 -0.7032091 0.1515452 -0.6946445 -0.7110188 0.06482011 -0.7001789 -0.7064424 0.04934394 -0.7060484 -0.7057859 0.06549263 -0.7053914 -0.7063232 0.04924231 -0.7061748 -0.7060521 -0.05324447 -0.7061554 -0.7112447 -0.07065171 -0.6993849 -0.7031199 -0.1553799 -0.6938872 -0.7059442 -0.2049919 -0.6779536 -0.7065404 -0.1546366 -0.690571 -0.7130234 -0.2029519 -0.6711245 -0.7031726 -0.2540125 -0.6640979 -0.7111142 -0.3288221 -0.6214439 -0.7097526 -0.3441268 -0.6146772 -0.7100204 -0.3293272 -0.6224265 -0.7062121 -0.3458608 -0.617774 -0.7054232 -0.4454821 -0.5512928 -0.7097774 -0.4293251 -0.5584768 -0.7100527 -0.4425832 -0.5476727 -0.6963961 -0.5146 -0.5002193 -0.7148772 -0.5344683 -0.4508817 0.713968 0.562028 -0.4175813 0.689817 0.5506912 -0.4699913 0.7114171 0.5928284 -0.3774126 0.7291253 0.577434 -0.3673505 0.8705126 0.2996281 -0.390424 0.7168366 0.5001986 -0.4857434 0.707076 0.5448846 -0.4507156 0.7140846 0.4920317 -0.497984 0.7141001 0.4920156 -0.4979777 0.7237441 0.4793755 -0.4963805 0.7155108 0.5323343 -0.4523987 0.7212486 0.5331786 -0.4421774 0.7143994 0.5322477 -0.454253 0.7139703 0.5620414 -0.4175596 0.7139703 0.5620315 -0.4175729 0.7070799 -0.5448815 -0.450713 0.7143429 -0.4918141 -0.4978284 0.7143371 -0.4918201 -0.4978307 0.8706167 -0.299517 -0.3902768 0.7169352 -0.5001259 -0.4856728 0.7270819 -0.5807991 -0.3660935 0.7095279 -0.5960017 -0.3759682 0.6969009 -0.5493741 -0.4609958 0.7231493 -0.5054402 -0.4707283 0.5976428 -0.5039204 -0.6236081 0.7252056 -0.5363321 -0.4317693 0.7151134 -0.5354642 -0.4493228 0.7156661 -0.5582712 -0.4197087 0.7156715 -0.5582794 -0.4196885 0.7231401 -0.5054386 -0.4707444 0.708851 -0.4989278 -0.4985994 0.7100846 -0.4425464 -0.547661 0.7060607 -0.4311472 -0.5617744 0.7056713 -0.3313659 -0.6262784 0.7096576 -0.3434067 -0.6151893 0.7099062 -0.3293918 -0.6225224 0.7118247 -0.3423554 -0.6132687 0.7032018 -0.2529017 -0.6644908 0.7130188 -0.2029535 -0.6711289 0.7065525 -0.1531838 -0.6908823 0.705968 -0.2049831 -0.6779314 0.7030343 -0.153948 -0.6942931 0.7114175 -0.07063424 -0.6992109 0.7057992 -0.05147385 -0.7065395 0.706107 0.06546723 -0.7050723 0.706116 0.06527388 -0.7050813 0.7113983 0.0510652 -0.7009314 0.6968764 0.2018621 -0.6881969 0.7071564 0.1530609 -0.6902914 0.7071563 0.1530528 -0.6902933 0.7129989 0.1973537 -0.672818 0.7029581 0.2529874 -0.664716 0.7116167 0.3233895 -0.6237155 0.7098259 0.3433409 -0.6150318 0.7101237 0.3240727 -0.6250609 0.7055506 0.3454111 -0.6187806 0.706546 0.440174 -0.5541118 0.7095422 0.4290237 -0.5590068 0.7097581 0.438165 -0.5515931 0.6967773 0.5141823 -0.500118 0.7155067 0.5323323 -0.4524073 -0.3646501 -0.6176369 -0.6968178 0.07970857 -0.9626433 -0.2587749 0.7038997 -0.06425309 -0.7073873 -0.1951432 -0.2711699 -0.9425423 -0.6015162 -0.1974852 -0.7740658 -0.4877954 -0.2988188 -0.8202213 -0.4730384 -0.1915248 -0.8599725 -0.492038 -0.1334048 -0.8602916 -0.4831839 -0.1920456 -0.8541966 -0.6523784 -0.03722006 -0.756979 -0.08961093 -0.3823571 -0.9196591 -0.209513 -0.2105276 -0.954873 -0.2093583 -0.2111287 -0.9547742 0.3228607 -0.329869 -0.8871005 0.2218754 -0.2568634 -0.9406341 0.2218546 -0.256822 -0.9406503 0.5396308 -0.1754063 -0.8234266 0.5396044 -0.1754382 -0.8234369 0.6050511 -0.1800533 -0.7755604 0.5932219 -0.1518413 -0.7905897 0.5888071 -0.1770057 -0.7886539 0.5556743 -0.1869766 -0.8101024 0.5398226 -0.1756684 -0.8232449 0.6827437 -0.1891962 -0.7057378 0.6616955 -0.1744399 -0.729198 0.6614901 -0.1715065 -0.7300797 0.6281642 -0.1682109 -0.7596808 0.6321792 -0.1705181 -0.7558261 0.6211905 -0.1799846 -0.7627109 0.605078 -0.1800788 -0.7755335 0.6703251 -0.3568499 -0.6506325 0.6606541 -0.1828855 -0.7280721 0.6097774 -0.3554068 -0.708419 0.08207464 -0.9629769 -0.2567865 0.07804286 -0.9632542 -0.2570035 0.07856917 -0.9641477 -0.2534684 -0.2133696 -0.8712759 -0.4419861 -0.07274651 -0.897723 -0.4345129 -0.07291197 -0.8976335 -0.4346698 -0.01724976 -0.9260708 -0.3769553 -0.175293 -0.9219764 -0.3452997 0.07859426 -0.9641525 -0.2534425 -0.3552255 -0.6330434 -0.6878015 -0.2988535 -0.8016835 -0.5176777 -0.3009511 -0.7591901 -0.5771125 -0.2240813 -0.7857974 -0.5764635 -0.2241119 -0.7857663 -0.5764938 -0.4309712 -0.4277837 -0.7945218 -0.4309883 -0.4277326 -0.7945401 -0.4561445 -0.4610916 -0.7611352 -0.474227 -0.4330493 -0.7665358 -0.3815776 -0.637817 -0.6690202 0.4819938 -0.5234079 -0.7026565 0.4856249 -0.5210103 -0.7019377 0.4149526 -0.4794517 -0.773266 0.4181849 -0.4779989 -0.7724236 0.355078 -0.4181231 -0.8361176 0.357821 -0.4174215 -0.8352983 0.313519 -0.3544269 -0.8809583 0.4627346 -0.2459124 -0.8517063 0.2199657 -0.7983972 -0.560515 0.2242699 -0.7971031 -0.560651 0.1167173 -0.7338542 -0.669205 0.120391 -0.7332702 -0.6691942 0.02399575 -0.6418067 -0.766491 0.0269621 -0.6417499 -0.7664398 -0.05470407 -0.5257613 -0.8488713 -0.05246925 -0.5260323 -0.8488445 -0.1076561 -0.409736 -0.9058292 0.1832667 -0.3086218 -0.9333627 0.07983767 -0.9625993 -0.2588986 0.456753 -0.7462264 -0.4842756 0.3072803 -0.8249385 -0.4743999 0.3880525 -0.7422839 -0.5462873 0.5284374 -0.5370766 -0.6574973 0.4995102 -0.745894 -0.4406039 0.6096341 -0.3558279 -0.7083309 -0.3745796 -0.8541704 0.3606705 -0.4147655 -0.8552413 -0.3106958 -0.3807689 -0.8861258 -0.2641898 -0.3898783 -0.8570907 -0.3367349 -0.4379185 -0.8603419 -0.2608436 -0.4234619 -0.8569455 -0.2938103 -0.4430041 -0.8568025 -0.2638878 -0.4169778 -0.8528817 -0.3142009 -0.403057 -0.8563881 -0.3227144 -0.4695702 -0.8787176 0.0857855 -0.5039559 -0.8633465 0.02571707 -0.5125523 -0.8585382 -0.0142219 -0.5135963 -0.8529661 -0.09310024 -0.5135279 -0.8552666 -0.06934046 -0.5109755 -0.8545839 -0.09268486 -0.5038748 -0.8610933 -0.06803303 -0.493272 -0.8500344 -0.184728 -0.491936 -0.858013 -0.1476913 -0.4807137 -0.858199 -0.1800239 -0.4834305 -0.863267 -0.1451379 -0.4679738 -0.8544765 -0.2255449 -0.5514147 -0.8225287 0.1392419 -0.3860946 -0.8684086 0.3111226 -0.4045825 -0.85507 0.3242967 -0.4019058 -0.8565587 0.3236956 -0.4024663 -0.8561135 0.3241766 -0.3830508 -0.8697446 0.3111532 -0.4018505 -0.8565982 0.3236601 -0.4041053 -0.8551216 0.3247553 -0.4044266 -0.8549799 0.3247286 -0.4039028 -0.8549668 0.3254141 -0.4122191 -0.85476 0.3153738 -0.4391324 -0.8596997 0.2609198 -0.4556836 -0.8553752 0.2463447 -0.4801095 -0.8587095 0.1792009 -0.4843178 -0.8581557 0.1703085 -0.4806349 -0.8583742 0.1793982 -0.4871886 -0.8563264 0.1713249 -0.5067022 -0.8572691 0.09133738 -0.5061159 -0.8574948 0.09246182 -0.5063096 -0.8575089 0.09126377 -0.533356 -0.8458909 -2.91439e-4 -0.3740432 -0.8547648 0.3598179 -0.3740735 -0.8547217 0.3598885 -0.3741428 -0.8546271 0.3600412 -0.4020552 -0.8531888 0.3322962 -0.4022274 -0.8502539 0.3395314 -0.3874829 -0.8729156 0.2964378 -0.3731294 -0.8562358 0.3572601 -0.3739269 -0.8549311 0.3595433 0.5924507 -0.5613349 -0.5778455 0.4768993 -0.7470943 -0.4630519 0.7088856 -0.06425458 -0.7023906 0.6931265 -0.1988122 -0.692856 0.6670693 -0.3568623 -0.6539633 0.6996047 -0.1986199 -0.6863698 0.6684043 -0.3564149 -0.6528432 0.5935932 -0.5607807 -0.5772107 0.6526396 -0.3567665 -0.6684155 0.4774253 -0.7464337 -0.463575 0.1400352 -0.9812774 -0.1322299 0.3946568 -0.8360826 -0.3810667 0.4676201 -0.7463967 -0.4735223 0.1744778 -0.9705364 -0.1661827 0.17405 -0.970567 -0.1664521 0.1741361 -0.9705369 -0.1665374 0.1367748 -0.9812878 -0.1355243 0 -1 0 2.36706e-6 -1 1.06635e-6 3.00529e-7 -1 -3.57524e-7 1.99673e-6 -1 1.45604e-6 -1.96918e-6 -1 1.3931e-6 -2.97565e-7 -1 -3.60087e-7 -2.98588e-7 -1 -3.59397e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.4332432 -0.790158 -0.4335329 -0.04520392 -0.9979354 -0.04562306 -0.4272323 -0.790292 -0.4392166 -0.5273817 -0.6654205 -0.5282842 -0.5485741 -0.6300626 -0.5496251 -0.1501691 -0.9758493 -0.1586419 -0.2534326 -0.9341449 -0.2512872 -0.1558237 -0.9758738 -0.1529361 -0.2556326 -0.9341134 -0.2491671 -0.2555824 -0.9341402 -0.2491181 -0.5304259 -0.6654021 -0.525251 -0.6709278 -0.2409546 -0.7012821 -0.6283405 -0.4504534 -0.6342554 -0.684245 -0.2404547 -0.6884695 -0.6292906 -0.4503697 -0.6333723 -0.6883137 -0.2409228 -0.6842371 -0.6985931 -0.121948 -0.7050507 -0.6443306 -0.2400881 -0.7260824 0.2861784 -0.7513946 -0.5945654 -0.4975742 -0.2044503 -0.8429827 -0.654728 -0.1714557 -0.7361618 -0.5873555 -0.1798639 -0.7890897 -0.5874143 -0.1799182 -0.7890335 -0.6202212 -0.1797757 -0.7635485 -0.6212303 -0.1680322 -0.7654006 -0.6212163 -0.1680243 -0.7654137 -0.5204167 -0.1981683 -0.8305996 -0.5271507 -0.1884075 -0.8286222 -0.5484265 -0.2174123 -0.8074406 -0.5915391 -0.1381913 -0.7943454 -0.5873508 -0.1799257 -0.789079 -0.1517251 -0.338564 -0.9286301 -0.2101152 -0.2611398 -0.9421558 0.2449811 -0.263545 -0.933021 0.1722792 -0.2490867 -0.9530351 0.123455 -0.3896805 -0.9126379 0.5176689 -0.2960742 -0.8027198 0.5223902 -0.3552331 -0.7751889 0.5326895 -0.1163091 -0.8382806 0.5327432 -0.1165425 -0.8382139 0.5327404 -0.1165704 -0.8382118 0.3755288 -0.565765 -0.73409 0.3755718 -0.5657117 -0.7341091 0.5010822 -0.4653133 -0.7296575 0.4513545 -0.348334 -0.8215489 0.4513711 -0.3482747 -0.8215649 0.3755447 -0.5657334 -0.7341061 0.4136428 -0.6246882 -0.6623173 0.280106 -0.7499769 -0.5992288 0.2834591 -0.7544438 -0.5920013 0.2800999 -0.7499999 -0.5992029 0.2801005 -0.7499836 -0.5992231 0.1810882 -0.8912557 -0.4157767 0.1560851 -0.8567315 -0.4915775 0.1254724 -0.8768097 -0.4641782 -0.02200186 -0.9974043 -0.06856 -0.3627644 -0.9218544 -0.1363327 -0.3628558 -0.921823 -0.1363008 -0.04341602 -0.9693556 -0.241795 -0.1516367 -0.9253774 -0.3473947 -0.04548525 -0.9495247 -0.3103772 -0.04548108 -0.9495165 -0.3104031 0.02199161 -0.9265022 -0.3756463 0.06684875 -0.9768543 -0.2031915 0.1249481 -0.8771536 -0.4636697 -0.6708707 -0.2408952 -0.7013573 -0.657373 -0.1876548 -0.7298264 -0.6558155 -0.1883155 -0.7310562 -0.6558581 -0.1883272 -0.731015 0.02486014 -0.2939521 -0.9554969 0.1109771 -0.4203395 -0.9005547 0.06063556 -0.5249734 -0.8489561 0.06180667 -0.5266549 -0.8478292 -0.0191695 -0.6406294 -0.767611 -0.01796257 -0.6427634 -0.7658541 -0.1130593 -0.7321927 -0.6716483 -0.1118896 -0.7347695 -0.6690251 -0.2174935 -0.7963229 -0.564417 -0.216513 -0.7990806 -0.5608853 -0.3516038 -0.8344016 -0.4244393 -0.4457406 -0.6615386 -0.6030605 -0.4722338 -0.6218894 -0.6246989 -0.4457458 -0.6615452 -0.6030496 -0.210983 -0.2649496 -0.9408974 -0.2108978 -0.2647753 -0.9409655 -0.3151749 -0.3295466 -0.8899796 -0.3060216 -0.3548705 -0.8834124 -0.3495618 -0.4162092 -0.8393906 -0.348464 -0.4188292 -0.8385434 -0.410126 -0.4768126 -0.7774615 -0.4091933 -0.4801254 -0.7759125 -0.4777569 -0.5200867 -0.707996 -0.4771825 -0.5238605 -0.7055971 -0.5670524 -0.5483666 -0.6146101 -0.6441941 -0.2406494 -0.7260177 0.5114376 -0.8546004 -0.08994394 0.4014979 -0.8567042 0.3238167 0.4017668 -0.8532611 0.3324589 0.3740041 -0.8545942 0.3602636 0.340408 -0.9033632 0.2608779 0.4018732 -0.8504054 0.3395712 0.4018707 -0.8504096 0.3395634 0.4033524 -0.8553577 0.3250691 0.5138665 -0.8552795 -0.06662082 0.5028575 -0.8598347 -0.08842211 0.4981076 -0.8547012 -0.1462007 0.4818839 -0.8581854 -0.1769341 0.4928552 -0.8580024 -0.1446567 0.4785766 -0.8602831 -0.1757194 0.4695026 -0.8545106 -0.2222138 0.4399097 -0.8603078 -0.2575851 0.425773 -0.8569539 -0.2904258 0.444952 -0.8568138 -0.2605531 0.4121825 -0.851381 -0.3244319 0.4170993 -0.8554361 -0.3070135 0.4172568 -0.8552711 -0.3072591 0.383347 -0.8858161 -0.2614863 0.3927402 -0.8570948 -0.3333824 0.438887 -0.8596609 0.2614598 0.411907 -0.8547993 0.3156751 0.4036998 -0.8550092 0.3255545 0.4041982 -0.8550217 0.3249028 0.4033629 -0.8553531 0.3250682 0.5139465 -0.8552304 -0.06663358 0.5126634 -0.8584916 -0.01298451 0.509713 -0.8603424 0.001924455 0.5150545 -0.8567224 0.02730286 0.5057933 -0.8576401 0.09287995 0.5057838 -0.8574979 0.09423404 0.5060009 -0.8575131 0.09292018 0.5061365 -0.8572825 0.09430021 0.4841436 -0.8558676 0.1819222 0.4838967 -0.8581374 0.1715925 0.4802733 -0.8583507 0.1804762 0.4828788 -0.8587836 0.1712276 0.4552067 -0.8554104 0.2471032 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.4322669 -0.8052504 0.4058538 0.3597936 -0.8574835 0.3677916 0.4829617 -0.8211635 0.3040371 0.487119 -0.8261139 0.283286 0.4339903 -0.8058546 0.4028037 0.4356998 -0.806436 0.3997833 0.4512688 -0.8107591 0.3728622 0.5217354 -0.8068521 0.2770954 0.6402179 -0.7422978 0.1977752 0.6402062 -0.7423059 0.1977828 0.4328839 -0.8512182 0.2967138 0.4328876 -0.8512146 0.2967188 0.432436 -0.8551276 0.2859301 0.4723114 -0.8367391 0.2771095 0.4871163 -0.8261173 0.2832803 0.5312982 -0.8330813 0.1539406 0.531301 -0.8330825 0.1539248 0.5104176 -0.8308913 0.2215706 0.5105293 -0.8308526 0.2214584 0.4593789 -0.8468492 0.2679882 0.4501441 -0.8495036 0.2751615 0.4467093 -0.8504691 0.2777646 0.4213671 -0.85725 0.2959259 0.4067343 -0.8607798 0.3059825 0.3772346 -0.884536 0.2743908 0.3962219 -0.8569695 0.3295626 0.6826761 -0.726508 0.07835566 0.682864 -0.7267037 0.0748232 0.6314965 -0.7558589 0.1728854 0.5109094 -0.8479696 0.1411353 0.5312932 -0.8330857 0.153934 0.8354908 -0.5296037 0.1465435 0.6826766 -0.7265074 0.07835668 0.7541362 -0.6425748 0.1355592 0.7868841 -0.6158351 0.03950446 0.7712599 -0.5816422 0.2585548 0.7971162 -0.5987323 0.07826602 0.8354881 -0.529609 0.1465403 0.8355002 -0.5295731 0.1465998 0.8543108 -0.5163279 0.05965429 0.8543102 -0.5163286 0.05965524 0.8874657 -0.460585 0.01631659 0.9215508 -0.3878127 0.01859247 0.8089771 0.06360858 0.5843886 0.9506242 -0.3096619 0.02056956 0.1505448 0.9886023 0.00138247 0.1514927 0.9884387 -0.006241261 0.1315997 0.9813542 -0.1400904 0.5468333 0.8295549 0.1131904 0.4570265 0.8815958 0.1179648 0.1345335 0.9888339 0.06409698 0.2215782 0.9737415 0.05225503 0.2100033 0.9738326 0.0868836 0.2425182 0.9671955 0.07561594 0.2167952 0.9717481 0.09330344 0.3412941 0.9365854 0.07953751 0.2851723 0.9452831 0.1584824 0.4409603 0.893252 0.08749306 0.3540067 0.9181144 0.1781718 0.4234539 0.899321 0.1091266 0.5418225 0.7596314 0.3597061 0.5109437 0.8113269 0.2840513 0.6910374 0.5817002 0.4290596 0.6910876 0.5817105 0.4289647 0.6959321 0.6493206 0.306694 0.5109398 0.8113299 0.2840503 0.5109435 0.8113281 0.2840486 0.7279476 0.02721858 0.6850923 0.7280578 0.02747225 0.6849651 0.7672587 0.2367773 0.5960291 0.7336305 0.2165323 0.6441274 0.8059937 0.3097803 0.504391 0.7311674 0.4551663 0.5081513 0.7311926 0.4551422 0.5081368 0.6500617 0.03344535 0.7591451 0.6558152 0.08856225 0.7497087 0.699374 0.022991 0.7143861 0.6981569 0.02627867 0.7154623 0.6899175 0.03435921 0.7230722 0.6938694 0.05143916 0.7182614 0.6938566 0.0514636 0.7182719 0.6964402 0.007647573 0.717574 0.6964431 0.007625043 0.7175715 0.6928309 0.008323371 0.721052 0.6935499 0.01361924 0.7202798 0.6912834 0.02287584 0.7222216 0.6922628 0.001213133 0.7216445 0.6814751 0.1539448 0.7154669 0.7432581 0.004235088 0.6689913 0.856641 0.0395596 0.514394 0.9466411 -0.03903746 0.3199166 0.9465622 -0.03902053 0.3201521 0.931424 -0.05216771 0.3601775 0.9314435 -0.05214595 0.3601304 0.8903205 -0.1168513 0.4400852 0.9281134 0.002931654 0.372286 0.8566974 0.03953981 0.5143015 0.8566325 0.03954458 0.5144096 0.9717837 -0.1774836 0.1553575 0.9560922 -0.2317245 0.1794194 0.9936634 -0.05126571 0.1000236 0.9922214 -0.05994158 0.109104 0.9914946 0.01378822 0.1294151 0.9654783 -0.2387982 0.1040539 0.9895536 -0.1253145 0.07127392 0.9770355 -0.1899263 0.09659004 0.9654687 -0.2388362 0.1040555 0.9654805 -0.238792 0.1040479 0.9667203 -0.2363746 0.09787207 0.9771272 -0.2103293 0.03136658 0.9592511 -0.278608 0.04706341 0.9637169 -0.2637324 0.0411691 0.9637193 -0.263724 0.04116797 0.9689221 0.2119906 0.127476 0.9903085 0.08011209 0.1134506 0.9903086 0.08011054 0.1134513 0.9914945 0.01379191 0.1294152 0.92105 0.3773517 0.09629595 0.9210512 0.377349 0.09629362 0.9295915 0.3624786 0.06684958 0.9499931 0.2922391 0.1100429 0.9689136 0.2120245 0.1274832 0.7763487 0.6221841 0.1008449 0.7763587 0.6221728 0.100838 0.7948658 0.6042404 0.05551558 0.8354673 0.5407433 0.09793347 0.8882791 0.4424551 0.1232631 0.54683 0.8295569 0.113192 0.5995757 0.7988763 0.04801702 0.5966498 0.7994287 0.07016366 0.7154981 0.6880415 0.1210839 0.7154949 0.6880447 0.1210846 0.805464 0.078148 0.5874697 0.8122196 0.1160439 0.5716932 0.8066334 0.1309587 0.5763614 0.8092373 0.1852378 0.557514 0.7799805 0.2378945 0.5788235 0.7206832 0.1205628 0.6827008 0.7279617 0.02719002 0.6850785 0.9833329 0.1495586 0.1033856 0.9886361 0.1279788 0.07886761 0.9183499 0.06472605 0.3904409 0.9267795 0.04646241 0.3727209 0.8009043 0.01546072 0.5985927 0.7981538 -0.1056333 0.5931207 0.7018158 0.1542136 0.6954659 0.6906285 0.002624928 0.723205 0.6909723 0.002407193 0.7228773 0.804551 0.02318614 0.593431 0.802219 0.04183918 0.595562 0.9249939 0.1226015 0.3596596 0.9063363 0.1953997 0.3746646 0.9027681 0.198557 0.381556 0.8899053 0.3031292 0.3408535 0.846298 0.3806654 0.3726575 0.8199454 0.4844213 0.3050007 0.7227537 0.5849366 0.3680709 0.7403615 0.453755 0.4959549 0.5539308 0.8207726 -0.1396176 0.3248551 0.9429875 -0.07241392 0.4403876 0.8920038 -0.101922 0.4534108 0.8816758 -0.1306387 0.5539361 0.8207681 -0.1396226 0.5539234 0.8207762 -0.1396254 0.6795248 0.7117475 -0.1779369 0.5488641 0.8356249 -0.02189236 0.6014544 0.7731031 -0.2014054 0.6404141 0.7483273 -0.1728471 0.6691393 0.7332887 -0.1205828 0.6720244 0.730123 -0.1237083 0.6949257 0.6280736 -0.3501456 0.7005659 0.6002288 -0.3859182 0.7040836 0.62032 -0.3456435 0.6668781 0.6554401 -0.3545024 0.6806902 0.6371329 -0.3615559 0.6934316 0.6189376 -0.3688752 0.6939451 0.6101913 -0.3822395 0.6939331 0.6101993 -0.3822482 0.6676127 0.6497315 -0.3635138 0.6670189 0.6542932 -0.3563513 0.6668822 0.6554382 -0.3544982 0.5901135 0.754255 -0.2878638 0.6676151 0.649721 -0.363528 0.6406015 0.7029526 -0.3090106 0.6302431 0.7059767 -0.3230954 0.4403898 0.8920031 -0.101919 0.3687268 0.9207258 -0.1276889 0.6321455 0.7168487 -0.2941427 0.2438096 0.9464179 -0.2117785 0.2427635 0.9467462 -0.2115125 0.8473154 0.528082 -0.05644416 0.998042 0.06253582 0.001196205 0.9190613 0.378652 -0.1093114 0.9737934 0.1940338 -0.1186481 0.9198141 0.3745419 -0.1168773 0.8848095 0.4569587 -0.09111022 0.9140784 0.3275699 -0.2390785 0.8530288 0.2027664 -0.4808613 0.8692469 0.2551894 -0.4234246 0.8473134 0.528085 -0.05644571 0.7351731 0.6576397 -0.1644099 0.7550975 0.5732271 -0.31818 0.8473146 0.5280826 -0.05645072 0.8285396 0.4443268 -0.3407285 0.7644904 0.5883909 -0.263345 0.7587068 0.5943772 -0.2666081 0.76471 0.5635014 -0.3125455 0.8790137 0.4437573 -0.1743975 0.8790093 0.4437643 -0.174401 0.8008299 0.5946218 -0.07138949 0.7792503 0.5916657 -0.2066414 0.7458243 0.6266465 -0.2259656 0.7538952 0.652143 -0.0796982 0.7539005 0.6521385 -0.0796827 0.6675352 -0.6542428 -0.3554759 0.4411659 -0.8915506 -0.1025184 0.6976344 -0.6855919 -0.2080145 0.5545154 -0.8202617 -0.1402981 0.5545242 -0.8202573 -0.1402887 0.5544378 -0.8218234 -0.1311679 0.6408582 -0.7477568 -0.1736679 0.6408551 -0.7477589 -0.1736703 0.4333437 -0.8940784 -0.1133006 0.4815595 -0.86609 -0.1341219 0.5545359 -0.8202486 -0.1402935 0.3248582 -0.9429864 -0.07241469 0.3250424 -0.9429056 -0.07263988 0.3692582 -0.9203854 -0.1286045 0.63302 -0.7156001 -0.2953006 0.5899939 -0.7542712 -0.2880662 0.6675437 -0.6542389 -0.3554673 0.6683003 -0.6484845 -0.3644758 0.6623095 -0.6714492 -0.3324186 0.6311359 -0.7046998 -0.3241383 0.6311438 -0.7046977 -0.3241277 0.6514275 -0.7426863 -0.1551108 0.6622622 -0.7146028 -0.2252812 0.6622372 -0.7146525 -0.2251968 0.6899868 -0.6238365 -0.3670778 0.6979464 -0.6073924 -0.3794013 0.6939172 -0.6101416 -0.3823689 0.7093797 -0.5862216 -0.3913113 0.7073884 -0.5641598 -0.4258233 0.5109409 -0.811299 0.2841361 0.7403265 -0.4538818 0.495891 0.6971141 -0.007600128 0.7169199 0.1505318 -0.9886043 0.001370489 0.1514859 -0.9884397 -0.006245851 0.1344653 -0.988841 0.06413084 0.2215817 -0.9737405 0.05226039 0.1315909 -0.9813524 -0.1401119 0.1968929 -0.9724256 0.1249865 0.2079602 -0.9729668 0.1004401 0.2479664 -0.9648668 0.08686059 0.2162656 -0.9702973 0.1084085 0.343066 -0.9356423 0.08294212 0.3057551 -0.9402738 0.1496624 0.3992035 -0.9167768 0.01252484 0.345087 -0.9197456 0.1870372 0.3541263 -0.9180816 0.1781035 0.4420706 -0.8924961 0.08957904 0.7763628 -0.622166 0.1008477 0.7155016 -0.6880365 0.1210918 0.6105655 -0.787988 -0.07927685 0.5995857 -0.7988678 0.04803371 0.5468378 -0.8295499 0.1132054 0.5468384 -0.8295495 0.1132051 0.9210512 -0.3773446 0.09631043 0.8882847 -0.4424407 0.1232739 0.8045708 -0.5877936 0.08464455 0.8085159 -0.5881983 0.0180279 0.776359 -0.6221703 0.1008503 0.9689136 -0.2120169 0.1274961 0.9689136 -0.212017 0.1274961 0.9321087 -0.3489578 0.09696322 0.9419794 -0.3353359 0.01498204 0.9210527 -0.3773418 0.09630787 0.9903061 -0.08010673 0.1134741 0.98772 -0.12541 0.09317404 0.9951522 -0.09106874 0.03712797 0.983332 -0.1495559 0.1033974 0.9924569 0.05018568 0.1118515 0.9914917 -0.01380759 0.1294354 0.991492 -0.01379144 0.1294351 0.9506599 0.3095326 0.02086603 0.9638659 0.2627822 0.04368102 0.9638716 0.2627614 0.04368084 0.9529795 0.2985625 0.05187022 0.9776483 0.1995763 0.06613069 0.904801 0.07217419 0.4196738 0.9274818 -0.02999442 0.372663 0.9047901 0.07219421 0.4196938 0.9047949 0.07217991 0.4196859 0.94655 0.03898614 0.3201926 0.9465006 0.03897541 0.3203396 0.9927265 0.06034791 0.1041741 0.9558687 0.2324646 0.1796526 0.985401 0.113673 0.1267411 0.9668501 0.2294908 0.1119592 0.9770426 0.1899216 0.09652811 0.9654972 0.2387547 0.1039772 0.9654777 0.2388283 0.1039899 0.8003601 0.0653367 0.5959486 0.7867091 0.08288669 0.6117341 0.8794996 -0.0347855 0.4746267 0.6875103 0.03531885 0.7253153 0.7455661 -0.09435784 0.6597181 0.7455595 -0.09435772 0.6597253 0.6928281 -8.10616e-4 0.7211023 0.692318 -0.001252114 0.7215914 0.6923135 -0.001511335 0.7215953 0.693506 -0.01218962 0.7203477 0.6987113 -0.02554064 0.7149476 0.6987236 -0.02550774 0.7149369 0.6898199 -0.03425681 0.7231701 0.693646 -0.05080741 0.718522 0.7030377 -0.1116206 0.702338 0.7370867 -0.1496275 0.6590256 0.7549415 -0.1742577 0.6322163 0.703121 -0.111674 0.7022461 0.6545761 -0.08795475 0.7508621 0.6846005 -0.06078016 0.7263801 0.6936668 -0.05076742 0.7185047 0.8136983 -0.3485494 0.4651972 0.7530639 -0.2260525 0.6178957 0.7530642 -0.2260526 0.6178954 0.7403316 -0.4537447 0.496009 0.715156 -0.4572459 0.5286571 0.715143 -0.4572548 0.5286668 0.6300495 -0.7642745 0.1375572 0.6609761 -0.7208298 0.2086027 0.6856979 -0.5530412 0.4732482 0.4288156 -0.8954959 0.1191825 0.5421043 -0.7590119 0.3605883 0.5109402 -0.8113024 0.2841278 0.7940454 -0.1624627 0.5857455 0.8234593 -0.156891 0.5452522 0.7799755 -0.237887 0.5788334 0.7885143 -0.2385922 0.5668501 0.7548884 -0.1218532 0.6444342 0.6929837 -0.008390069 0.7209045 0.79984 -0.05880254 0.597326 0.8126387 -0.04749357 0.5808293 0.934319 -0.07415974 0.3486378 0.899087 -0.1018515 0.4257568 0.9267702 -0.04646134 0.3727445 0.805323 -0.01637703 0.5926101 0.8006834 -0.02243262 0.5986675 0.6976299 -0.003556251 0.7164496 0.6870288 -0.00544399 0.7266098 0.6910724 -0.5816664 0.4290492 0.7206229 -0.5867963 0.3692867 0.8448063 -0.4527487 0.2851684 0.821357 -0.4185752 0.3875147 0.9192291 -0.2387431 0.313081 0.8629967 -0.2297589 0.4499418 0.9063246 -0.1953855 0.3747004 0.8205415 -0.09253102 0.5640476 0.7988307 -0.1036417 0.5925605 0.6944786 -0.01941543 0.7192513 0.6935713 -0.02311104 0.7200172 0.6826687 0.7265278 0.07823652 0.7906261 0.6117185 0.02666008 0.7125087 0.662395 0.2314395 0.8885218 0.4585106 0.01723265 0.8755881 0.4818681 0.03389441 0.8523124 0.5192045 0.06316936 0.8523105 0.5192071 0.06317251 0.7993245 0.5999819 0.03319793 0.7986401 0.5996794 0.0505833 0.7950635 0.5899441 0.1408539 0.8183885 0.5707684 0.06681108 0.8395739 0.5210761 0.1536077 0.8395708 0.5210869 0.1535876 0.6828501 0.7267157 0.07483422 0.6828503 0.7267155 0.07483375 0.5960678 0.7787461 0.1955958 0.5314166 0.8330013 0.1539654 0.4083392 0.8600074 0.3060172 0.5068966 0.8306502 0.2303824 0.5069616 0.8306282 0.2303187 0.53142 0.8329989 0.1539666 0.5314196 0.8329986 0.1539692 0.4150389 0.8553678 0.3099818 0.41504 0.8553668 0.3099831 0.4130013 0.8589084 0.3028304 0.4328967 0.8509661 0.2974174 0.4154249 0.8550271 0.3104041 0.4144201 0.8558956 0.3093518 0.4144641 0.8558605 0.3093901 0.4870685 0.8261212 0.2833515 0.4601364 0.8451274 0.2720923 0.4332886 0.8468638 0.3083547 0.4328882 0.8509745 0.297406 0.7170786 0.6789745 0.1574547 0.6393266 0.7429521 0.1982008 0.6393622 0.7429277 0.1981778 0.5212699 0.8069188 0.2777764 0.4487825 0.8106909 0.375998 0.4322729 0.8052524 0.4058431 0.4296154 0.8041889 0.4107442 0.4844662 0.8230448 0.2964621 0.4870635 0.826128 0.28334 -0.7038423 7.90742e-6 -0.7103563 -0.7040271 -3.78314e-4 -0.710173 -0.7038517 0 -0.7103469 -0.7038424 -8.61883e-6 -0.7103562 -0.7038421 -9.05062e-6 -0.7103565 -0.7038437 -6.32218e-6 -0.7103549 -0.7039099 1.66368e-4 -0.7102892 -0.7038462 -1.13945e-5 -0.7103524 -0.7038429 -6.76712e-6 -0.7103557 -0.5431853 -0.1349709 -0.8286933 0.7489133 0.005418241 -0.6626459 0.7176416 0 -0.6964126 0.7290197 0.01142603 -0.6843975 0.5989908 -0.08204609 -0.7965417 0.6958746 0.03035336 -0.7175216 0.7108524 0.03968685 -0.7022206 0.7141175 0.04265099 -0.6987253 0.7121881 0.04090315 -0.700796 -0.6801347 0.08733367 -0.7278665 -0.6926168 0.0256285 -0.7208503 -0.6370095 0.002632439 -0.7708514 -0.7069892 0.03461587 -0.7063768 -0.7100521 0.03738147 -0.7031562 -0.7068597 0.03428435 -0.7065224 -0.74351 0 -0.6687249 -0.6658877 -0.0210222 -0.7457557 -0.7501156 0.002747297 -0.661301 -0.7495865 0.00256139 -0.6619014 0.6961898 0.03054773 -0.7172076 0.6434301 0.008592009 -0.7654567 0.6009903 0.008604526 -0.7992101 0.4659019 -0.02701729 -0.8844238 0.4695922 -0.02992624 -0.8823761 0.03546971 0.007210135 -0.9993448 0.1836058 -0.03922051 -0.9822173 0.1636101 -0.02462136 -0.9862179 0.327544 0.008493363 -0.9447977 0.3275592 0.008493363 -0.9447924 0.03550177 0.007210135 -0.9993435 -0.1553559 -0.0181427 -0.987692 -0.1196054 -0.04615807 -0.991748 -0.5481801 0.002648353 -0.8363562 -0.4173311 -0.05147242 -0.9072956 -0.4585837 -0.01498132 -0.888525 -0.2718999 0.006237328 -0.9623054 -0.2719203 0.006237328 -0.9622996 0.7103428 1.21927e-5 -0.7038558 0.7104337 -1.59323e-4 -0.7037641 0.7103378 3.4482e-5 -0.703861 0.7103536 -2.30315e-6 -0.703845 0.7103489 -1.53232e-5 -0.7038497 0.7105073 2.56057e-4 -0.7036898 0.7103469 -1.10052e-5 -0.7038516 0.710336 -2.19809e-5 -0.7038627 0.7103598 0 -0.7038388 -0.09967386 0.9919663 0.07789772 -0.01300346 0.9998685 -0.009678423 -0.1141989 0.9911264 -0.0680229 -0.1284258 0.9892979 -0.06925594 -0.1050498 0.9913882 -0.07819163 -0.1314157 0.9909551 -0.02716398 -0.1314134 0.9909552 -0.02717226 -0.127591 0.9906754 -0.04778182 -0.130448 0.9903166 -0.04749846 -0.1166675 0.9911766 -0.06290918 -0.1313686 0.9913038 -0.007702112 -0.1414367 0.9899473 -7.72826e-5 -0.1448582 0.9888612 0.03420144 -0.1303375 0.9914051 0.01131749 -0.1303375 0.9914051 0.01131737 -0.2844807 0.9290152 0.2366466 -0.2845593 0.928975 0.23671 -0.130923 0.9900346 0.05186933 -0.1262875 0.9908732 0.04713708 -0.1173766 0.9907836 0.06760507 -0.1192929 0.9903259 0.07087987 -0.1043182 0.9911968 0.08152621 -0.106844 0.9912086 0.0780372 -0.09965187 0.9919697 0.0778827 -0.2845593 0.9289768 0.2367027 -0.3172694 0.9177391 0.2389457 -0.3886691 0.8665122 0.3131979 -0.1130532 0.9913185 -0.06713086 -0.1200148 0.9873456 -0.1036583 -0.1199666 0.9873555 -0.1036199 -0.3705163 0.9184032 -0.1387557 -0.3705168 0.9184031 -0.1387557 -0.3399159 0.9184027 -0.2024689 -0.3399111 0.9184045 -0.2024691 -0.3399103 0.918403 -0.2024771 -0.3125928 0.9189153 -0.2405838 -0.3147302 0.9151196 -0.251994 -0.3705155 0.9184035 -0.1387562 -0.3892922 0.9184037 -0.07061296 -0.1374572 0.9901938 -0.02493309 -0.1313685 0.9913037 -0.007702827 -0.3956439 0.918404 -2.16218e-4 -0.395644 0.9184041 -2.16184e-4 -0.3892974 0.9184047 -0.07057267 -0.3892922 0.9184036 -0.07061296 -0.3893699 0.9184035 0.070185 -0.3893681 0.9184042 0.07018679 -0.130169 0.9912141 0.02346402 -0.1283085 0.9912714 0.03029495 -0.3893682 0.9184041 0.07018691 -0.3706651 0.9184041 0.1383517 -0.3706656 0.918404 0.1383516 -0.3706656 0.9184041 0.138351 -0.3401337 0.9184041 0.2020961 -0.3401355 0.9184029 0.2020987 -0.3074254 0.9187791 0.2476583 -0.3648687 0.9070542 0.2100558 -0.5806152 0.8059284 0.1156086 -0.6600636 0.7511739 -0.00733596 -0.7049258 0.7059505 0.06865584 -0.7102085 0.7038699 0.01308017 -0.7665495 0.640987 0.03921061 -0.7721205 0.6337184 0.04723227 -0.402746 0.90492 0.1375336 -0.420097 0.882051 0.213318 -0.4307993 0.884953 0.176834 -0.461325 0.8838406 0.07749247 -0.5022736 0.8497503 0.1601421 -0.5148344 0.8561626 0.04394441 -0.5873695 0.7975063 0.1377708 -0.5806139 0.8059279 0.115619 -0.3381869 0.9016536 0.2695373 -0.3470933 0.9051007 0.2455993 -0.3473641 0.9051908 0.2448831 -0.3499591 0.9058844 0.2385415 -0.01526427 0.999742 0.01682138 -0.01697105 0.9997862 0.0118131 -0.01698368 0.9997863 0.0117895 -0.04935085 0.9981697 0.03495168 -0.04465538 0.9988496 0.01747465 -0.0446549 0.9988496 0.0174762 -0.1204696 0.9926908 0.007221698 -0.1204695 0.9926908 0.00722301 -0.1094425 0.9928906 0.04680323 -0.08291363 0.9964359 0.01551449 -0.08291351 0.9964359 0.01551496 -0.06348663 0.9979754 0.003805935 -0.06348663 0.9979754 0.003806114 -0.2550836 0.9657469 -0.04759472 -0.1365836 0.9881227 0.07041591 -0.07220095 0.9914836 0.1083847 -0.3247606 0.9264355 0.1903883 -0.3246793 0.926471 0.1903547 -0.3443089 0.9170818 0.2010278 0.04432654 0.8355765 0.5475828 -0.3752959 0.8668002 0.328345 -0.1159767 0.991461 0.05961984 -0.1532945 0.9848031 0.08163213 -0.1722432 0.9839682 0.046247 -0.197393 0.9737283 0.1135302 -0.2263261 0.9737989 0.02218645 -0.2764668 0.9553362 0.1043975 -0.2945598 0.9556093 0.006731092 -0.3570422 0.9298806 0.08855992 -0.3665316 0.9304015 0.002777874 -0.4992769 0.8647528 0.05408537 -0.5003413 0.8652598 0.03136724 -0.7728757 0.6343499 -0.01623535 -0.1660285 0.9861198 0.001578986 -0.1124449 0.9924934 0.04809409 -0.1659463 0.9856137 0.03205353 -0.254171 0.9671056 -0.01019436 -0.5024994 0.8640736 0.02951502 -0.5024988 0.8640739 0.0295152 -0.6065081 0.7950672 0.004001379 -0.7729669 0.6344229 -0.005446434 -0.7874761 0.6163234 -0.005185782 -0.7874764 0.616323 -0.005185782 -0.7729775 0.6344318 -0.001432061 -0.8626531 0.5057959 1.79878e-6 -0.1090858 0.9940323 0 -0.1660226 0.9860848 -0.008552551 -0.6065051 0.7950695 0.004001379 -0.4974616 0.867381 -0.01349681 -0.5026775 0.8643815 -0.01264709 -0.4612292 0.8871837 -0.01313698 -0.5026908 0.8644028 -0.01047688 -0.3262317 0.9452795 0.004406869 -0.16603 0.9861111 0.004346787 -0.3259003 0.9453963 -0.00388354 -0.3259094 0.945393 -0.00388354 0.3066866 0.9191105 0.2473443 0.1043537 0.9909722 0.08416885 0.3066829 0.9191069 0.2473621 0.1147958 0.9910324 0.06838726 0.1061666 0.9909473 0.08217167 0.1033609 0.9914032 0.08022576 0.103467 0.9914039 0.08007943 0.1225492 0.9900543 0.06909573 0.1286022 0.9905182 0.04832404 0.1261683 0.9908152 0.0486502 0.1161878 0.9910647 0.06550639 0.1375971 0.9901659 0.02526724 0.1285635 0.9912739 0.02910989 0.1285629 0.991274 0.0291121 0.1531953 0.9881412 -0.01040256 0.1298063 0.9914883 0.01006507 0.1298063 0.9914883 0.01006489 0.1408 0.9895694 -0.03045719 0.130331 0.9912058 -0.02291709 0.1289989 0.9912521 -0.02790409 0.1287453 0.9905048 -0.04821884 0.289761 0.928023 -0.2341195 0.2897494 0.9280289 -0.2341104 0.1166228 0.9910941 -0.06427681 0.1198901 0.9903021 -0.07020097 0.1052574 0.9913502 -0.07839328 0.1070454 0.9913539 -0.07588475 0.1023194 0.991828 -0.07620996 0.3066899 0.9191033 0.2473672 0.3067189 0.9191004 0.2473418 0.3392465 0.9187316 0.2020992 0.3392435 0.9187327 0.2020989 0.3696424 0.9187331 0.1389029 0.3696419 0.918734 0.1388981 0.3696433 0.9187335 0.1388978 0.3883844 0.9187334 0.07131987 0.3883816 0.9187344 0.07132065 0.3883823 0.9187342 0.07131999 0.3948753 0.9187336 0.00149089 0.1307325 0.9914176 4.93613e-4 0.1299502 0.9914813 -0.008824586 0.3889122 0.9187331 -0.06838601 0.388911 0.9187338 -0.06838518 0.3889097 0.9187334 -0.06839573 0.3948754 0.9187335 0.00149089 0.3706827 0.918733 -0.1361036 0.3706824 0.918733 -0.1361038 0.1273722 0.9907518 -0.04676735 0.1166228 0.9910941 -0.06427681 0.3942759 0.8650071 -0.3103374 0.3163968 0.9192719 -0.234163 0.340758 0.9187316 -0.1995404 0.340759 0.9187335 -0.1995295 0.3407613 0.9187327 -0.1995294 0.3706826 0.9187328 -0.1361042 -0.8709256 0.2602496 -0.416844 -0.8536086 0.2035027 -0.4795197 -0.9143302 0.3270833 -0.2387817 -0.8789258 0.4724829 -0.06518667 -0.8922389 0.4269273 -0.1471155 -0.890088 0.4338593 -0.1396762 -0.9650966 0.2200722 -0.1419744 -0.9408662 0.3092515 -0.1383272 -0.7624386 0.6235976 -0.1726654 -0.7618232 0.59146 -0.264198 -0.7459263 0.6406205 -0.1822069 -0.7596044 0.5151806 -0.3969763 -0.847969 0.5262811 -0.06306141 -0.847966 0.5262859 -0.06306385 -0.8234584 0.5328021 -0.1950339 -0.8470525 0.3822661 -0.3692895 -0.7646924 0.5884743 -0.2625712 -0.7284439 0.6576865 -0.1918805 -0.7284196 0.6576973 -0.1919348 -0.7514243 0.6490396 -0.1187818 -0.7990707 0.5754544 -0.1741786 -0.8188894 0.5508832 -0.1610839 -0.7786958 0.6230213 -0.07401055 -0.8909666 0.4291856 -0.1482508 -0.4383005 0.8932139 -0.1003081 -0.6698178 0.7332054 -0.1172771 -0.5531655 0.8214344 -0.1387563 -0.5531637 0.8214353 -0.1387582 -0.5529217 0.823026 -0.1300223 -0.6403107 0.7484624 -0.172645 -0.6403059 0.7484656 -0.1726486 -0.43014 0.8958365 -0.1116088 -0.480944 0.8665076 -0.1336321 -0.553163 0.8214361 -0.1387569 -0.3248991 0.9429682 -0.07246714 -0.6295608 0.7057916 -0.3248252 -0.6303322 0.7059841 -0.3229053 -0.3253386 0.942773 -0.07303327 -0.3693436 0.9203693 -0.128475 -0.3118251 0.9454851 -0.09393119 -0.6326985 0.7159157 -0.2952244 -0.5900154 0.7542659 -0.2880363 -0.6303072 0.7059909 -0.3229389 -0.6617352 0.6724763 -0.3314848 -0.6675328 0.6493394 -0.3643602 -0.678416 0.6402772 -0.3602733 -0.6667953 0.6557186 -0.3541431 -0.6668103 0.6557115 -0.3541274 -0.6618958 0.714905 -0.2253994 -0.661899 0.7148944 -0.2254236 -0.6618973 0.7148979 -0.2254176 -0.6916473 0.6205083 -0.3695855 -0.6981388 0.6071177 -0.379487 -0.6946814 0.6094688 -0.3820543 -0.7094585 0.5865114 -0.3907338 -0.7074092 0.5641418 -0.4258128 -0.926814 0.04605633 0.3726856 -0.7402657 0.45331 0.4965046 -0.5215708 0.8411952 0.1426692 -0.1553592 0.9844838 0.08157736 -0.1494761 0.9886193 -0.0169906 -0.1500625 0.9885882 -0.01321721 -0.1520398 0.9883742 5.92815e-4 -0.1397648 0.988288 -0.06125837 -0.1787154 0.9830039 0.04200136 -0.1523023 0.9847437 0.0841673 -0.2189736 0.975287 0.02942419 -0.1452431 0.9853873 0.08897376 -0.263818 0.9645725 -2.02232e-4 -0.216033 0.9670358 0.1348015 -0.2353121 0.9663177 0.1042033 -0.3056451 0.9488015 0.07973015 -0.2892871 0.9445483 0.1553753 -0.3703142 0.928193 0.03640347 -0.2979457 0.940449 0.1636582 -0.4791691 0.8755178 0.06217372 -0.8056475 0.5876309 0.07497966 -0.7538731 0.6479555 0.1087616 -0.6872838 0.7147352 0.129594 -0.6314193 0.7627449 0.1397493 -0.6226173 0.7825263 5.22401e-4 -0.5777438 0.8126657 0.07606941 -0.8056688 0.5876039 0.0749638 -0.8048783 0.5873836 0.08456552 -0.870952 0.4778783 0.1143462 -0.9116077 0.3913567 0.125743 -0.9116125 0.3913481 0.1257355 -0.9116054 0.3913625 0.1257416 -0.9898954 0.1140336 0.08428317 -0.9915633 0.04300588 0.1222816 -0.9882969 0.1098268 0.1058651 -0.9779773 0.1751582 0.1134898 -0.9620642 0.2360184 0.1368496 -0.9342597 0.3214265 0.1544144 -0.9496106 0.3093438 -0.05045926 -0.9349445 0.3516751 0.04694145 -0.9773181 -0.1934947 0.08607596 -0.9604315 -0.2537243 0.1148708 -0.9834108 -0.1283326 0.1281948 -0.9875915 -0.09750193 0.1231116 -0.9926577 -0.05908983 0.1055422 -0.9906412 -0.01979207 0.1350485 -0.9906413 -0.01979094 0.1350485 -0.9585109 -0.2809839 0.04801082 -0.9585144 -0.2809722 0.0480076 -0.9585138 -0.2809776 0.04798805 -0.9572136 -0.2715947 0.09989148 -0.967986 -0.2332779 0.09265279 -0.9775687 -0.1971213 0.07417982 -0.9575895 -0.2841137 0.04797548 -0.9592046 -0.2788204 0.04675263 -0.9280581 0.007538437 0.372359 -0.9081366 -0.08145952 0.4106729 -0.9081422 -0.08144861 0.4106627 -0.9354494 -0.04921203 0.3500182 -0.943943 -0.04183727 0.3274464 -0.9591331 -0.04082983 0.279994 -0.8008307 -0.03453129 0.5978945 -0.8008513 -0.03446501 0.5978708 -0.8879549 0.01034092 0.4598141 -0.6946386 0.002042651 0.719356 -0.6914751 0.0108655 0.7223185 -0.6916612 0.001700878 0.72222 -0.6911019 0.002185165 0.722754 -0.6861115 0.00538069 0.7274765 -0.6968903 0.003379821 0.7171698 -0.6963592 0.007587671 0.7176533 -0.6928177 0.00827533 0.7210652 -0.6936169 0.01412981 0.7202055 -0.6936207 0.01411437 0.7202022 -0.6916621 0.01730364 0.722014 -0.6973371 0.02702015 0.7162339 -0.6973509 0.02698296 0.7162218 -0.6899263 0.0342577 0.7230687 -0.6939394 0.05151695 0.7181881 -0.7010852 0.08790296 0.7076389 -0.7325984 0.1261274 0.6688733 -0.732615 0.1261397 0.6688528 -0.654284 0.0878356 0.7511307 -0.6840499 0.06122457 0.7268614 -0.6939322 0.05153059 0.718194 -0.8160044 0.3616852 0.4509108 -0.7680167 0.2570735 0.5865694 -0.7319487 0.2167519 0.6459642 -0.7319222 0.2167351 0.646 -0.7402654 0.4533386 0.4964788 -0.7307221 0.4548279 0.5090941 -0.7308593 0.4547431 0.5089728 -0.6928734 0.5808188 0.4272891 -0.6909264 0.5790702 0.4327799 -0.6932113 0.5809948 0.4265012 -0.6930139 0.5808935 0.4269595 -0.6933003 0.5810238 0.4263169 -0.568809 0.6978149 0.4353281 -0.4561716 0.8729381 0.1728776 -0.4791684 0.8755181 0.06217443 -0.5113223 0.8109843 0.2843484 -0.5113207 0.8109906 0.2843333 -0.6613701 0.7204231 0.2087584 -0.6858968 0.5528232 0.4732147 -0.6858261 0.5524596 0.4737414 -0.987313 0.1236141 0.09966248 -0.9343472 0.07377415 0.348644 -0.8991543 0.1015258 0.4256926 -0.6932469 0.5810106 0.4264214 -0.7259355 0.5820079 0.3664487 -0.8450343 0.4523463 0.2851312 -0.8215687 0.4182056 0.3874648 -0.9193344 0.2383205 0.3130934 -0.8631068 0.2294467 0.4498898 -0.9064342 0.1949918 0.3746404 -0.6928974 0.01089662 0.7209538 -0.8012322 -0.03039562 0.597581 -0.8007199 0.02222055 0.5986267 -0.8053003 0.01623034 0.5926449 -0.799853 0.05858713 0.5973296 -0.8125974 0.04730367 0.5809026 -0.7988414 0.1033858 0.5925908 -0.8205316 0.09225714 0.5641068 -0.7940911 0.1621693 0.5857649 -0.8234732 0.1565725 0.5453228 -0.780056 0.2375538 0.5788615 -0.7928037 0.2385819 0.5608395 -0.7273491 0.03884065 0.6851677 -0.4911043 0.870222 0.03911852 -0.3240453 0.9450638 -0.04299908 -0.324045 0.9450641 -0.04299962 -0.3806939 0.922889 -0.05786293 -0.3237369 0.9448882 -0.04879206 -0.3883584 0.9111187 -0.137987 -0.1068515 0.9839392 0.1429914 -0.3751568 0.9268715 -0.01291406 -0.3751543 0.9268722 -0.01292586 -0.3751564 0.9268716 -0.01291489 -0.407746 0.8445721 0.3470466 -0.4063087 0.8593216 0.310612 -0.491097 0.8702263 0.0391156 0 0 1 -0.08843481 0.00692135 0.9960579 -0.09917128 0 0.9950703 -0.08854031 0.006808698 0.9960494 -0.08958989 0.005293071 0.9959647 -0.08970195 0.005401372 0.995954 -0.05888646 -0.007258951 0.9982383 -0.01005774 0.04432642 0.9989665 -0.04270052 0.009614408 0.9990417 -0.002963006 0.02047377 0.999786 0.06830948 0.01881128 0.9974867 0.03180599 0.03530901 0.9988703 0.03225541 0.03551048 0.9988486 0.04428642 0.04265326 0.9981079 0.03824782 0.0386846 0.9985192 0.03252977 0.03349572 0.9989093 0.01003193 0.01114666 0.9998876 0.2606445 0.95449 0.1449599 0.2316135 0.8961049 0.3786175 0.2327209 0.9614902 0.1462112 0.2730731 0.8843142 0.3787075 0.2327178 0.9615265 0.1459764 0.211633 0.896688 0.3887955 0.2110411 0.8985531 0.3847909 0.2406234 0.9705494 0.01159077 0.2406173 0.9705506 0.01161229 0.2232615 0.9673092 0.1202792 0.6640368 0.7432204 0.08172291 0.6640343 0.7432224 0.08172428 -0.2092199 0.8989093 0.3849534 -0.2420759 0.9701882 0.01158094 -0.2420728 0.9701889 0.01159203 -0.6653521 0.7424786 0.07766616 -0.5625022 0.8161995 0.1319463 -0.6628488 0.7396834 0.1161887 -0.2247843 0.9669437 0.1203821 -0.2617756 0.9541862 0.1449214 -0.2295065 0.8989335 0.3731556 -0.2374762 0.960352 0.1460442 -0.2374801 0.9603867 0.1458101 -0.6918018 0.6803849 0.24184 -0.8279047 0.480789 0.2888181 -0.1170513 0.9878459 0.1022716 -0.1056953 0.5794231 0.8081445 -0.1054295 0.577256 0.8097285 -0.1694002 0.9850262 0.03204292 -0.1053628 0.5765848 0.8102152 -0.12711 0.9916795 0.02036547 -0.1271581 0.9916808 0.02000111 -0.1481871 0.9875774 0.05226308 -0.1483168 0.9875804 0.05183804 -0.1476058 0.9876765 0.05203431 -0.1430247 0.9875479 0.06552076 -0.1396827 0.9879824 0.06617641 -0.1193094 0.987806 0.1000232 -0.1207623 0.9870561 0.1055299 -0.1302437 0.9880716 0.08216494 -0.1317677 0.9880477 0.079993 -0.1336218 0.9874408 0.08429592 -0.1396816 0.9879825 0.06617844 -0.09396243 0.9883058 0.1200942 -0.0894373 0.9874759 0.1299701 -0.06636154 0.9879163 0.1400622 -0.06561547 0.9881911 0.1384657 -0.0114293 0.9996436 0.02412295 -0.1329164 0.9848746 0.1111541 -0.06596356 0.9838787 0.1662274 -0.182308 0.8981075 0.4002084 -0.1183416 0.9108901 0.3953157 -0.1175691 0.9120174 0.3929401 -0.1130121 0.911431 0.3956283 -0.06832778 0.9879453 0.1389077 -0.1903675 0.9022104 0.3870097 -0.182279 0.8981081 0.4002202 -0.2787564 0.8847517 0.3735092 -0.2787939 0.8847523 0.3734799 -0.2556641 0.892525 0.3715305 -0.2747436 0.8917397 0.3596056 -0.2729474 0.8918378 0.3607286 -0.104692 0.9874734 0.1180499 -0.3066204 0.8868178 0.345743 -0.3430592 0.88827 0.3054292 -0.4768363 0.7029587 0.5277085 -0.4360007 0.8222318 0.3658391 -0.5293561 0.7408705 0.4133921 -0.5293721 0.7408608 0.413389 -0.5294109 0.7408626 0.4133363 -0.5628542 0.7525504 0.3418526 -0.6050927 0.7161759 0.3477858 -0.6654842 0.6812743 0.3049524 -0.6546699 0.7076182 0.2658644 -0.6546711 0.7076181 0.2658616 -0.7379415 0.5820907 0.3414863 -0.8201667 0.4978528 0.2819026 -0.86847 0.4483252 0.211576 -0.776691 0.6144605 0.1385258 -0.7766911 0.6144604 0.1385258 -0.9035294 0.3983007 0.1580861 -0.9035312 0.3982968 0.1580856 -0.9455716 0.2672076 0.1857267 -0.8781545 0.4450253 0.1754907 -0.8813457 0.4532062 0.1335439 -0.8684746 0.4483254 0.2115565 -0.8279081 0.4807892 0.2888078 -0.81862 0.4979371 0.2862165 -0.6918233 0.6803475 0.2418842 -0.6650022 0.6801525 0.3084875 -0.678678 0.6761703 0.2866879 -0.6020216 0.7924989 0.09754741 -0.6020131 0.7925057 0.09754496 -0.713942 0.6806938 0.1641427 -0.7766927 0.6144579 0.1385276 -0.776701 0.6144481 0.1385247 -0.362028 0.9290356 0.07634544 -0.1566069 0.9872062 0.02996677 -0.1839975 0.9817957 0.04714095 -0.4785595 0.8700347 0.118408 -0.4785519 0.8700389 0.1184077 -0.5971195 0.7920759 0.126744 -0.8372954 0.5003579 0.2204053 -0.7086594 0.6804435 0.1865438 -0.7086477 0.6804611 0.1865238 -0.34656 0.9335821 0.09121835 -0.6020098 0.7925081 0.0975452 -0.3620312 0.9290342 0.07634657 -0.4493213 0.8856588 0.1171274 -0.438358 0.8856461 0.1532101 -0.4383829 0.8856269 0.1532498 -0.4222972 0.8855728 0.1934577 -0.4223346 0.885539 0.1935312 -0.3972887 0.8854331 0.2411844 -0.3973434 0.8853693 0.2413287 -0.356586 0.8851433 0.2989444 -0.3566585 0.8850058 0.2992647 -0.3113285 0.8856178 0.3446093 -0.4768469 0.7029593 0.527698 1 -8.49903e-7 0 0.9999993 0.001194298 -9.25754e-5 1 0 0 0.9999989 -0.001522839 1.70465e-4 1 -9.60359e-5 3.94274e-4 0.9999909 0.004086971 0.001161515 -1 1.3284e-5 -1.31188e-6 -1 -3.65496e-6 0 -1 0 0 -1 1.79338e-6 -2.00748e-7 -1 3.48839e-6 0 -1 2.81072e-5 4.52579e-6 0.141253 0.9879691 0.0629667 0.8902228 0.2248186 0.3961818 0.8861503 0.4379092 0.15157 0.8691474 0.4743229 0.1400023 0.87721 0.4597553 0.1383033 0.8685438 0.4755455 0.1396009 0.8826204 0.4594839 0.09927594 0.8542657 0.4684779 0.2252966 0.9194185 0.2266367 0.3214116 0.7926186 0.5378206 0.2872362 0.8542679 0.4684778 0.2252886 0.7132921 0.664273 0.2235078 0.6565715 0.6916384 0.3009154 0.5814266 0.7351923 0.3484758 0.581401 0.735194 0.348515 0.5837762 0.7304001 0.3545718 0.6530029 0.7009906 0.2867043 0.6529994 0.7009909 0.2867118 0.4205766 0.756954 0.5001359 0.4206166 0.7569566 0.5000984 0.4593527 0.8002717 0.3854354 0.4967215 0.7649756 0.4099758 0.4967192 0.7649769 0.4099761 0.2488657 0.8906995 0.3804209 0.2481443 0.8907111 0.3808647 0.2544059 0.8935792 0.3698566 0.2481368 0.8907136 0.3808641 0.1870253 0.9058892 0.3799818 0.1522962 0.8980058 0.4127851 0.1232377 0.8972167 0.4240458 0.1471213 0.9085676 0.3909735 0.007675945 0.9997757 0.01974368 0.1186779 0.9857193 0.1194689 0.0688945 0.9849374 0.1585935 0.1130853 0.9126588 0.3927669 0.1193152 0.9878048 0.1000282 0.1258858 0.9869318 0.1005901 0.1022875 0.9880101 0.1156429 0.1024608 0.9880121 0.115472 0.1021844 0.9880372 0.1155026 0.08976894 0.9873751 0.1305066 0.07685965 0.9882358 0.1322214 0.06772965 0.9881685 0.1376072 0.08121347 0.9868556 0.1397157 0.05619144 0.987895 0.144589 0.1406598 0.9879583 0.06444543 0.1434186 0.9875949 0.06393182 0.1331769 0.9879326 0.07907718 0.13247 0.9879193 0.08041995 0.1351211 0.9875748 0.08023858 0.121424 0.9878449 0.09704947 0.2142108 0.9764029 0.0274074 0.2142191 0.976401 0.02740931 0.214213 0.9764024 0.02740842 0.1531531 0.9869977 0.04878294 0.145691 0.9880192 0.05091333 0.1469426 0.9880371 0.04680454 0.1733391 0.9845795 0.02359855 0.2116827 0.9763699 0.04350149 0.8886085 0.4375786 0.1374768 0.8787152 0.4598077 0.1282045 0.8787183 0.4598017 0.1282051 0.6729781 0.7201945 0.1685835 0.6729683 0.720203 0.1685861 0.7195357 0.6805222 0.138412 0.6917964 0.6803909 0.2418391 0.6918402 0.6803537 0.2418181 0.6689779 0.6803978 0.2992113 0.7132866 0.6642763 0.2235158 0.55592 0.8245447 0.1052576 0.5558621 0.824585 0.1052466 0.555867 0.8245816 0.1052474 0.8539761 0.4692576 0.2247712 0.708645 0.6804651 0.1865192 0.7086634 0.680449 0.1865084 0.3947093 0.9129148 0.1038809 0.5524703 0.8241217 0.1248999 0.4580638 0.8813189 0.1159937 0.4580445 0.8813291 0.1159922 0.4580802 0.8813105 0.1159934 0.3296959 0.8822124 0.3361577 0.3296426 0.8822154 0.336202 0.3135635 0.8813621 0.3533819 0.2988403 0.8851582 0.3566361 0.3567967 0.8849986 0.2991213 0.3564659 0.8851376 0.2991046 0.3973944 0.8853677 0.2412504 0.397232 0.8854355 0.2412692 0.422339 0.8855435 0.193501 0.4222499 0.8855811 0.1935227 0.4383823 0.8856362 0.1531976 0.43834 0.8856546 0.1532124 0.4495698 0.8856514 0.1162267 0.4581339 0.8812826 0.1159924 0 1 0 0 1 0 0 1 0 -4.59273e-5 1 -1.08061e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 2.64808e-7 1 1.83252e-6 2.98359e-6 1 1.60896e-6 2.98381e-6 1 1.60892e-6 0 1 0 0 1 0 0 1 0 0 1 0 3.98841e-6 1 1.45225e-6 5.42072e-6 1 1.12084e-6 5.42154e-6 1 1.12065e-6 7.60284e-6 1 4.45796e-7 7.60295e-6 1 4.45761e-7 1.12398e-5 1 -9.75968e-7 1.12398e-5 1 -9.7598e-7 1.81979e-5 1 -4.29657e-6 6.81532e-5 1 -3.12871e-5 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -6.85944e-6 1 -1.68021e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 5.01159e-6 1 0 5.19809e-6 1 0 2.00089e-7 1 2.26167e-7 2.00051e-7 1 2.26171e-7 -4.60322e-6 1 8.21233e-7 0 1 0 5.17663e-5 1 -2.34595e-5 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 4.55338e-6 1 7.61729e-7 -2.52023e-7 1 2.20201e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 9.77751e-6 1 -2.45467e-6 9.46033e-6 1 -2.35444e-6 4.22264e-6 1 -6.00459e-7 1.49422e-6 1 4.75943e-7 -6.88827e-6 1 4.12138e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 4.2477e-6 1 2.48176e-6 -2.36259e-6 1 0 0 1 0 -3.39638e-6 1 0 1.3535e-5 1 7.02188e-6 -2.13398e-6 1 7.52618e-7 -1.37352e-5 1 -3.83982e-6 0.7903282 0.6126831 -9.10838e-4 -0.9225073 0.3859796 -4.90572e-5 -0.9906593 0.1363496 0.001734256 -0.9241735 0.38197 -0.001548111 -0.9992884 0.0377162 5.77217e-4 -0.9953033 0.0968067 0 -0.6457359 0.7205868 0.2525468 0.6516579 0.7293702 0.2082328 0.7778294 0.6284748 -9.15748e-4 0.9774515 0.2109869 0.008560478 0.7903565 0.6126448 -0.001771986 0.9758117 0.2186124 3.64425e-4 0.9758118 0.2186118 3.64425e-4 0.9804687 0.196675 0 0.4527705 0.8916249 -0.001942515 0.6662601 0.7457088 0.003979682 0.02994149 0.9995447 -0.003741204 0.2406333 0.9706152 -0.001381933 0.03001773 0.9995484 -0.001349806 0.2406385 0.9706102 0.002990663 -0.3836349 0.9234811 -0.002674281 -0.9241507 0.3820281 -4.90962e-5 -0.7106673 0.703513 -0.00465095 -0.8233567 0.567524 -5.36386e-4 -0.7105014 0.7036955 -5.59593e-4 -0.6673676 0.7447277 -9.67348e-4 -0.3835212 0.9235318 7.60567e-4 -0.2420889 0.9702536 -9.60693e-4 -0.242092 0.9702528 -9.60692e-4 0.1219917 0.9904395 0.06440299 0.3750455 0.9266784 0.02466064 0.06295323 0.9980127 0.002742648 0.3746024 0.9255379 -0.05525064 0.0616303 0.9972739 0.04057741 0.1248452 0.9921613 0.005438983 0.1281713 0.9917519 7.03012e-4 0.08134824 0.9966055 0.01264828 0.08134824 0.9966055 0.01264846 0.1154779 0.9923328 0.04405158 0.06768125 0.9974155 0.0241149 0.03881645 0.9986549 0.03437423 0.04457092 0.99888 0.01587998 0.01930928 0.999675 0.01664024 0.01711672 0.9997928 0.0110228 0.01711571 0.9997926 0.01102471 0.07521879 0.996487 0.03682231 0.1015077 0.9909904 0.08737337 0.3055102 0.9191429 0.2486762 0.3531081 0.9098879 0.2177584 0.3350705 0.9040718 0.2652961 0.4363223 0.8888876 0.1396486 0.3550379 0.9093309 0.2169455 0.3550039 0.9093293 0.2170081 0.5493249 0.8350278 0.03115916 0.4995013 0.8510735 0.1617791 0.5096609 0.8577269 0.06745529 0.427363 0.886373 0.178056 0.4273643 0.8863731 0.1780518 0.7029547 0.7078455 0.06935018 0.7029547 0.7078455 0.06935 0.6571236 0.7537372 -0.008284032 0.578394 0.807308 0.1171073 0.5783942 0.8073081 0.1171067 0.5958892 0.8025847 0.02781826 0.7772274 0.6281541 -0.03660684 0.7441495 0.6676988 -0.02048933 0.7775062 0.6283885 0.02473956 0.8583941 0.5129908 -2.75252e-4 0.3745829 0.9255461 -0.05524444 0.2506272 0.9680625 0.00640279 0.2521075 0.9664142 -0.04985409 0.1325672 0.9886932 0.07008367 0.1153867 0.993308 0.005023837 0.1182852 0.9928093 0.0183922 0.3389575 0.9170487 0.21007 0.1289827 0.9848803 0.1156474 0.1355711 0.9853345 0.1036164 0.2116001 0.9759302 0.05277919 0.192426 0.9748368 0.1125418 0.2879644 0.9575031 0.01626163 0.2707303 0.9565626 0.1081353 0.3628628 0.9317889 -0.01001125 0.3505923 0.9310817 0.1008555 0.4975287 0.8665024 -0.04048198 0.4952419 0.8675792 0.04518556 0.5954839 0.802042 -0.04612833 -0.6102602 0.7912517 0.03877198 -0.6102541 0.7912562 0.03877687 -0.6032238 0.790768 0.1039565 -0.603227 0.790766 0.1039531 -0.7874236 0.6162823 0.01265901 -0.6102615 0.791251 0.03876495 -0.6567676 0.5656538 0.4986906 -0.6745426 0.7138134 -0.1883153 -0.6102579 0.7912534 0.03877234 -0.8850587 0.3961733 0.2443718 -0.9581664 0.2670797 0.1028857 -0.6567881 0.5656151 0.4987074 -0.8294523 0.5580506 0.02425915 -0.7876562 0.613288 0.05895578 -0.7859787 0.6151507 0.06186383 -0.7872567 0.6134342 0.06265276 -0.8607138 0.5046589 0.06701493 -0.9138824 0.397621 0.0819537 -0.8963928 0.4306825 0.1048453 -0.8963969 0.4306737 0.1048463 -0.9689344 0.2412917 0.0542643 -0.9724073 0.2226961 0.06950181 -0.9738562 0.2256513 0.0261811 -0.9738566 0.2256498 0.0261771 -0.9536191 0.2759636 0.1202272 -0.9411343 0.3244273 -0.09493798 -0.9411342 0.324427 -0.09493923 -0.9252482 0.3727653 0.07044059 -0.9771171 0.1981051 -0.07743835 -0.978897 0.186886 0.0826705 -0.9978696 0.04082369 0.05088818 -0.9010943 -0.4336195 -0.001791715 -0.8716689 0.490095 1.56838e-6 -0.881893 0.4714492 5.92341e-4 -0.8922759 0.4514865 0.001923561 -0.8922743 0.4514896 0.001923203 -0.9023434 0.4309953 0.004408538 -0.9119299 0.4102621 0.008293807 -0.9201558 0.391299 0.0140866 -0.9988921 -0.04632091 0.008310377 -0.9584423 0.2813555 0.04719328 -0.9761645 0.2169289 0.006688475 -0.9761652 0.2169262 0.00668776 -0.9902861 0.1390082 -0.003192007 -0.9954461 0.09505856 0.007140636 -0.9977318 0.06564849 0.01489001 -0.9995952 0.01932865 -0.02087575 -0.9995951 0.01933473 -0.02087658 -0.9721797 0.2338129 0.0140683 -0.9721806 0.23381 0.01406812 -0.955618 0.2942733 0.0140556 -0.9696516 0.2444831 -0.001884102 -0.908796 0.4172377 0.001644551 -0.9010976 -0.4336127 -0.001791715 -0.9300736 -0.3673639 -0.00263977 -0.9603158 -0.2784838 -0.01550769 -0.9980598 -0.06185227 0.007141649 -0.9899086 -0.1416588 0.003702938 -0.9899094 -0.1416531 0.003702938 -0.9603161 -0.2784824 -0.01550805 -0.9603153 -0.2784854 -0.01550704 -0.8969655 -0.4352001 0.07780516 -0.9762626 -0.2149266 0.0267927 -0.9566334 -0.2864022 0.05316394 -0.9931782 -0.1160656 -0.01121747 -0.9531828 -0.3020368 0.01470762 -0.9286785 -0.3682216 0.04437345 -0.8803346 -0.4743137 0.006125867 -0.8803359 -0.4743112 0.006126165 -0.8483857 -0.5293696 -0.003097355 -0.8483858 -0.5293695 -0.003097355 -0.5345694 -0.8447855 0.02394288 -0.6102534 -0.7921966 0.003907859 -0.8279713 -0.5607692 0.00118196 -0.7618421 -0.647757 -0.002735316 -0.7296504 -0.6838167 0.002264916 -0.7632103 -0.6461501 2.8021e-4 -0.7292267 -0.6842631 0.003540098 -0.6909211 -0.7229239 0.003017604 -0.6909356 -0.7229101 0.003017663 -0.4285276 -0.9035218 -0.003517031 -0.4249646 -0.9052001 -0.004207313 -0.4283534 -0.9036032 -0.00380975 -0.4251182 -0.9051274 -0.004355847 -0.5322518 -0.846583 0.002324342 -0.5322574 -0.8465794 0.002323865 -0.6279339 -0.7782022 -0.01001489 -0.7434027 -0.6675456 -0.04165685 -0.4285299 -0.9035208 -0.003517031 -0.325967 -0.9453561 0.006881117 -0.2411885 -0.970171 0.02441895 -0.1608286 -0.986795 0.01922839 -0.5074437 -0.8476669 -0.1547961 -0.2285292 -0.9735371 -1.55071e-4 -0.3288716 -0.9441945 -0.01844453 -0.5028449 -0.8603146 -0.08370018 -0.8499507 -0.5109149 -0.1286461 -0.9143232 -0.3270503 -0.2388541 -0.853605 -0.2034957 -0.479529 -0.8787289 -0.2962363 -0.3742724 -0.8499395 -0.5109314 -0.1286545 -0.7552261 -0.5730919 -0.318118 -0.8499422 -0.5109174 -0.1286927 -0.8287921 -0.4435729 -0.3410964 -0.7646903 -0.5884764 -0.2625723 -0.7589678 -0.5944043 -0.2658033 -0.7649133 -0.5632992 -0.3124127 -0.7538972 -0.6521428 -0.07967966 -0.7353484 -0.6575375 -0.1640338 -0.7459446 -0.62655 -0.2258359 -0.7538944 -0.6521449 -0.07968735 -0.9983024 -0.05817896 0.002745151 -0.9190467 -0.3787078 -0.1092409 -0.9738183 -0.1939232 -0.1186248 -0.9198201 -0.3745254 -0.1168836 -0.8850098 -0.4565422 -0.09125113 -0.8790615 -0.443437 -0.1749694 -0.8255812 -0.5217199 -0.2149975 -0.8061049 -0.5791513 0.1215679 -0.7792438 -0.5916945 -0.2065834 0.9896205 0.1436631 0.003481507 -0.8263633 0.5631353 0.001517415 -0.9766032 0.214967 -0.00594139 0.005177438 0.9999753 -0.004756152 0.004481554 0.9999787 -0.004756212 0.1215026 0.9925221 -0.01169782 0.2799274 0.9594348 0.03354752 0.06862688 0.9974406 -0.0200631 0.1419298 0.9898763 -8.44714e-4 0.06051868 0.9981669 6.04344e-4 0.0051741 0.9999758 -0.004640221 0.1574569 0.9875109 -0.00543344 0.1574581 0.9875108 -0.005433261 0.1822414 0.98325 -0.002706229 0.1666662 0.9859018 0.01483511 0.1666648 0.9859021 0.01483547 0.1250624 0.9917663 0.02755224 0.1250553 0.991767 0.0275557 0.1617756 0.9867896 0.008666336 -0.005899488 0.9995689 0.0287621 -0.05413228 0.9984184 0.01517158 -0.00519061 0.9999731 0.005193471 0.05078029 0.9987088 -0.001475095 -0.2092843 0.9772999 0.03294044 -0.0681867 0.9974928 0.01893836 -0.06817901 0.9974933 0.01893836 -0.05413001 0.9983627 0.0184912 -0.06666553 0.9976618 0.01505351 -0.2673459 0.9628925 -0.03693383 -0.1674956 0.9838164 0.06364244 -0.2092862 0.9772995 0.03293913 -0.2363005 0.9715837 -0.01368695 -0.1919311 0.9809412 -0.03027999 0.004481375 0.9999785 -0.00479114 -0.1379901 0.9903917 0.009114682 -0.0515567 0.9986696 -9.11709e-4 -0.0515446 0.9986702 -9.11707e-4 -0.1919319 0.980941 -0.03027963 -0.1444196 0.9881353 -0.05226355 -0.408087 0.9066597 0.1069254 -0.1330163 0.9903979 -0.03766697 -0.2715586 0.9617745 0.03529489 -0.1373926 0.9905149 -0.001851856 -0.08115768 -0.9966831 0.005999743 -0.011357 -0.9999356 0 0.02707958 -0.9996333 0 0.02931231 -0.9995703 -4.60211e-4 0.1617814 -0.986825 0.001792192 0.105725 -0.9937464 0.03591978 0.1057327 -0.9937457 0.03591603 0.1520013 -0.9882063 0.01854389 0.1520001 -0.9882066 0.01854419 0.1887313 -0.9819725 0.01050823 0.181836 -0.9833227 -0.003504097 0.153559 -0.9881159 -0.006827056 0.1535549 -0.9881165 -0.006827652 0.1146262 -0.9933075 -0.01418238 0.1146154 -0.9933087 -0.01418554 0.3381814 -0.9394814 0.05484551 0.05910617 -0.9979611 -0.02408391 0.1057569 -0.9943805 -0.004778385 -0.07124423 -0.9974501 0.004169523 0.01135772 -0.9999356 -6.39926e-6 -0.07075965 -0.9974934 -3.97074e-6 -0.2044638 -0.9788613 0.005008101 -0.2044651 -0.978861 0.005008399 -0.03060162 -0.9995094 -0.006680428 -0.08740639 -0.9961617 -0.00470823 -0.07062149 -0.9974921 -0.004709064 -0.08610361 -0.9962831 -0.002510786 -0.08610951 -0.9962825 -0.002510011 -0.3364363 -0.9404799 0.04804474 -0.1744555 -0.9839712 -0.03695821 -0.1744619 -0.9839702 -0.03695559 -0.287773 -0.9576618 -0.008401274 -0.2410463 -0.9704042 0.01457768 -0.2029824 -0.9784818 0.0370348 -0.2029822 -0.9784818 0.03703498 -0.1590629 -0.9847217 0.07086664 -0.2673061 -0.9627493 -0.04075866 -0.1067019 -0.9942823 0.004172503 -0.08115273 -0.9966335 0.0116533 -0.05493289 -0.9984276 0.01117318 -0.05492454 -0.9984279 0.01117318 -0.9757682 0.1752094 0.1310656 -0.9451048 0.3267663 8.42824e-4 -0.9741328 0.225955 0.003103673 -0.9741326 0.2259557 0.003103613 -0.9741206 0.2260077 0.003099024 -0.9871438 0.1437105 0.06995922 -0.9957004 0.09075856 0.01854193 -0.9927079 0.1197437 0.01387828 -0.9872476 0.1589382 0.008994638 -0.9451053 0.3267649 8.42825e-4 -0.9766178 0.214968 -0.002572774 -0.9449226 0.3272906 -0.001454353 -0.7960923 0.6051735 0.001524865 -0.8259606 0.5637272 -8.52862e-4 -0.9075752 0.4198892 -5.83518e-4 -0.8303059 0.5566752 0.0265513 -0.8966423 0.4427227 0.005390167 -0.6473832 0.7621586 0.003061413 -0.6355988 0.7720037 0.004941284 -0.7960715 0.6051577 -0.007380604 -0.7364807 0.676379 0.01037114 -0.7364805 0.6763793 0.01037114 -0.2453628 0.9693511 0.01247084 -0.2737065 0.9618123 -0.001443326 -0.2675267 0.9635494 -0.001441717 -0.3944908 0.9188975 -0.002103805 -0.4684082 0.8835118 8.02692e-4 -0.3967781 0.9178104 0.01383119 -0.6472827 0.7620403 -0.017883 -0.5252698 0.8508891 0.008909404 -0.6352412 0.7723078 0.003060221 0.5611496 0.8276344 -0.01150524 0.4092758 0.9124107 -3.15748e-4 0.3701332 0.9289647 0.005093693 0.2762339 0.9610877 -0.002318024 0.1617829 0.9868223 0.002834141 0.2434452 0.9699106 0.002815842 0.2052333 0.9786814 0.007865965 0.7259552 0.6876614 -0.01053446 0.5310664 0.8472977 0.007415175 0.5611865 0.827688 0.001538813 0.5300263 0.8479798 0.001535296 0.4101222 0.9120149 0.005347669 0.8336495 0.5522533 0.006695568 0.7494446 0.6613532 0.0307371 0.8567707 0.5155017 -0.01420885 0.7440933 0.6680754 6.27406e-4 0.7259926 0.6876966 0.002851724 0.7445166 0.6675979 0.002849459 0.6426413 0.7661066 0.009635984 0.9896212 0.1436586 0.003481507 0.9773894 0.2113948 0.004724323 0.9773901 0.211391 0.004724204 0.9773896 0.2113933 0.004724323 0.953024 0.3026536 0.01208621 0.9939999 0.1081038 -0.01666426 0.9524173 0.3047901 0.00206536 0.9476462 0.3192992 0.003853738 0.9040786 0.4273611 -0.002104222 0.8568587 0.5155507 -8.69249e-4 0.9042317 0.4270412 -8.8626e-4 0.8336498 0.5522528 0.006695568 0.9899346 -0.1307791 0.05409544 0.9890701 0.1343113 0.06083375 0.9980576 0.06191319 0.006919801 0.9964326 -0.0842337 0.00519222 0.9988709 -0.04682922 0.007993578 0.9941364 -0.1081191 0.001799166 0.9994801 -0.03224223 0 0.994138 0.1081193 0 0.999257 0.03742641 0.009215176 0.9992568 0.0374301 0.009214758 0.9967569 0.0802825 0.005522787 0.9954554 0.09510523 0.004860341 0.989621 0.1436597 0.003481566 0.9682232 -0.2500209 0.005785822 0.9789522 -0.1704391 0.1122631 0.9934386 -0.1143023 0.003870189 0.9884807 -0.1513066 0.003503799 0.9858124 -0.167814 0.003500521 0.9327824 -0.1990365 0.3005021 0.7259944 -0.6876984 -0.001775741 0.7444301 -0.6676881 -0.004043042 0.856706 -0.5154629 -0.0187866 0.7498593 -0.6610873 0.02597028 0.8834555 -0.4685015 -0.003560602 0.8834557 -0.4685013 -0.003560662 0.8568536 -0.5155476 -0.003551304 0.8833618 -0.4686727 -0.004217088 0.9476464 -0.3192993 0.003764152 0.9403755 -0.3400784 0.006387591 0.994013 -0.1081053 -0.01586109 0.941263 -0.3371855 0.01816463 0.9682234 -0.2500196 0.005785763 0.5611858 -0.827687 -0.002177357 0.5552544 -0.8316799 -0.001008987 0.7258928 -0.6876023 -0.01681673 0.5592469 -0.8287227 0.02148598 0.7448704 -0.6672068 -0.001780211 0.2312526 -0.9728837 0.004433155 0.246909 -0.9690358 0.002355337 0.161783 -0.9868234 0.002384543 0.3701286 -0.9289534 -0.007119536 0.3321271 -0.9432301 0.002944707 0.5611357 -0.8276137 -0.01349776 0.333159 -0.9428032 0.01127916 0.555039 -0.8318215 -0.002177596 -0.453509 -0.8912363 0.005241453 -0.6470357 -0.7617495 -0.03290021 -0.455971 -0.8897454 0.02106094 -0.2166554 -0.9760447 -0.01992994 -0.2721413 -0.9622569 -0.001004278 -0.3306843 -0.943741 -0.001008391 -0.2675259 -0.9635463 -0.002904176 -0.4684072 -0.8835098 0.002282381 -0.7773917 -0.6290013 0.00442487 -0.7773928 -0.629 0.004424691 -0.6864482 -0.726846 0.02199262 -0.7959463 -0.6050625 -0.01921218 -0.5753245 -0.8177849 0.01515561 -0.647381 -0.7621559 0.004038393 -0.5733114 -0.8193277 0.004013121 -0.5733114 -0.8193278 0.004013121 -0.9075669 -0.4198853 0.0043208 -0.8594738 -0.5111752 -0.002178072 -0.796091 -0.6051725 -0.002343297 -0.8602879 -0.5097994 0.003075718 -0.8602875 -0.5097999 0.003075718 -0.9980764 0.06199288 6.60671e-4 -0.9996755 0.02533119 0.002718627 -0.9999901 0 0.004466712 -0.9995247 0.0304048 0.00510323 -0.9996988 -0.02400761 0.005104124 -0.9644297 -0.1884554 0.1853644 -0.994881 -0.09471029 0.03524076 -0.995101 -0.09335291 0.03254306 -0.9951009 -0.09335362 0.03255051 -0.9953532 -0.09528058 0.01390928 -0.9953534 -0.09527862 0.01391172 -0.991943 -0.1265285 -0.006290495 -0.9854341 -0.1700578 -1.47048e-5 -0.9813602 -0.1910048 0.02119988 -0.9579545 -0.2524992 0.136262 -0.9968026 -0.07966512 0.006169557 -0.980822 -0.1940751 0.01798045 -0.9998564 0 -0.01694142 -0.9603745 -0.2785164 0.01046246 -0.9766201 -0.2149707 8.73085e-4 -0.959909 -0.2803105 8.66471e-4 -0.9766203 -0.2149685 -0.001138091 -0.9598061 -0.2806636 -4.66981e-4 -0.9211043 -0.3893151 6.80673e-4 0.7644961 -0.5884177 -0.2632688 0.8528004 -0.2024366 -0.4814051 0.9140667 -0.3275099 -0.2392056 0.8789948 -0.4723049 -0.06554651 0.8918977 -0.4280428 -0.145938 0.8900883 -0.4338608 -0.1396701 0.9650806 -0.2201285 -0.1419959 0.9410465 -0.3086681 -0.1384041 0.7623844 -0.623649 -0.1727193 0.7614734 -0.5915599 -0.2649813 0.7456499 -0.6409118 -0.1823131 0.7594032 -0.5153839 -0.3970971 0.8731695 -0.4684074 -0.1347946 0.8731554 -0.4684302 -0.1348064 0.8293666 -0.4729911 -0.2973726 0.8253875 -0.2728505 -0.4942548 0.821297 -0.4646972 -0.3309499 0.72843 -0.6576995 -0.191888 0.7284184 -0.6577048 -0.1919144 0.7513868 -0.6490609 -0.1189035 0.799027 -0.5756111 -0.1738615 0.818448 -0.551552 -0.1610382 0.7792099 -0.6221293 -0.0760734 0.8908273 -0.4299413 -0.1468923 -0.6858182 -0.72342 0.07947874 -0.8385345 -0.5426982 0.04835808 -0.8373303 -0.5351968 0.1115455 -0.8332368 -0.5228099 0.1799618 -0.8174238 -0.574299 0.04471009 -0.788749 -0.5919874 0.1656073 -0.802725 -0.5955153 0.03153133 -0.7338886 -0.6514153 0.1925247 -0.6948704 -0.6649069 0.27396 -0.9209647 -0.3894184 0.01332014 -0.9187698 -0.3935132 0.03177297 -0.913437 -0.4069124 0.007427513 -0.8951317 -0.4433193 0.04698175 -0.895129 -0.4433235 0.04699188 -0.8981916 -0.4395945 0.002917826 -0.866242 -0.494666 0.07021671 -0.855497 -0.5047354 0.1156163 -0.6840354 -0.7256449 0.07439696 -0.6840302 -0.7256488 0.07440787 -0.683991 -0.7256116 0.07512706 -0.5303429 -0.8340559 0.1519446 -0.4456354 -0.8507711 0.2785632 -0.4527837 -0.8487632 0.2731082 -0.4611701 -0.8463125 0.2666029 -0.5171912 -0.8285524 0.2145091 -0.5172086 -0.8285462 0.2144915 -0.5303082 -0.8340318 0.152197 -0.5303514 -0.8340486 0.1519558 -0.4329215 -0.8509266 0.2974946 -0.4329283 -0.8509199 0.2975038 -0.4094621 -0.8602445 0.3038423 -0.4118769 -0.855753 0.31312 -0.4117634 -0.8558615 0.3129727 -0.3985821 -0.8674327 0.2978134 -0.4191393 -0.8493577 0.320802 -0.3453758 -0.9063335 0.2434653 -0.4108807 -0.8561431 0.3133624 -0.3936286 -0.8679156 0.3029505 -0.5972008 -0.7780253 0.1950073 -0.4603343 -0.8450679 0.2719421 -0.4333147 -0.8468251 0.3084243 -0.5961555 -0.772116 0.2200807 -0.7197355 -0.6761048 0.157681 -0.7907723 -0.6113792 0.02991348 -0.5961477 -0.7721205 0.2200862 -0.507221 -0.8070565 0.302302 -0.4785822 -0.8101503 0.3385492 -0.4852261 -0.823241 0.2946691 -0.4852691 -0.82328 0.2944893 -0.4461992 -0.8098424 0.3808695 -0.4838945 -0.8225257 0.2988268 -0.4849994 -0.823053 0.2955659 -0.4851141 -0.8231377 0.2951418 -0.4874511 -0.8259018 0.283333 -0.4874505 -0.8259026 0.2833316 -0.9955044 -0.01547366 -0.09344381 -0.9986612 0.04432094 0.02667522 -0.9760511 0.1844443 0.1153458 -0.9972616 0.07324719 0.01021373 -0.9955037 -0.01546716 -0.09345042 -0.995506 -0.01546782 -0.09342682 -0.9978486 -0.006865024 -0.06520104 -0.9981776 0.02170932 -0.05630451 -0.9985935 0.02335798 -0.0475986 -0.9985685 0.02373069 -0.04793632 -0.9989295 0.02016109 -0.04163306 -0.998916 0.0140472 -0.04437768 -0.9987381 0.01499104 -0.0479303 -0.9988059 0.01097345 -0.04760724 -0.9987378 0.01499772 -0.04793602 -0.9988059 0.0109722 -0.04760456 -0.998806 0.01097214 -0.0476045 -0.9852434 -0.09417301 -0.142923 -0.981384 -0.1300709 -0.141304 -0.9852423 -0.09417951 -0.142926 -0.9852413 -0.09416711 -0.1429411 -0.9751842 -0.1545793 -0.1584959 -0.9770281 -0.1505867 -0.1507962 -0.9754961 -0.1562989 -0.1548481 -0.9904027 0.1286423 0.05053412 -0.9852438 -0.09417229 -0.1429209 -0.9864121 -0.09087038 -0.1368719 -0.9904419 0.1293556 0.04787367 -0.9760512 0.1844436 0.1153464 -0.9895663 0.1346203 0.05134111 -0.9898851 0.1326028 0.05043828 -0.9899927 0.1310666 0.05230647 -0.9878666 0.1433954 0.0596432 -0.9905453 0.1264346 0.05323666 -0.9977527 0.0629431 0.02297377 -0.9941424 0.04701912 0.09731471 -0.9932049 0.1077674 0.043935 -0.9904918 0.1124396 0.07926666 -0.9907404 0.1217943 0.05999666 -0.9585923 -0.282771 -0.03378194 -0.9760708 -0.1862682 -0.1122052 -0.9762452 -0.176242 -0.1260318 -0.9760662 -0.1864376 -0.111963 -0.210018 0.576332 -0.7897683 -0.9745698 -0.2087448 -0.08148109 -0.9750387 -0.2057021 -0.08358305 -0.7671804 -0.08189475 0.636182 -0.9981858 0.01300716 0.05878609 -0.9981394 -0.03491878 0.04998266 -0.9995446 -0.0268687 0.01373666 -0.9993527 -0.03341066 0.01333785 -0.9978349 -0.06570547 0.002894222 -0.9931544 0.04471862 0.1079105 -0.9965881 -0.01128977 0.08176016 -0.9956891 -0.0685175 0.06251859 -0.9967274 -0.04557824 0.06676167 -0.9981402 -0.0349105 0.04997408 -0.997506 -0.04987323 0.04994446 -0.9996092 0.02224522 0.01692873 -0.8642693 -0.4963413 -0.08175569 -0.8642691 -0.496342 -0.08175253 -0.9552683 -0.2950725 0.01986455 -0.9956923 0.05137324 0.07718539 -0.995692 0.05137699 0.07718586 -0.7796699 0.1334866 -0.6117975 -0.8982368 0.2659522 -0.3499143 -0.9727642 -0.0174281 -0.2311406 -0.9980116 0.002086341 -0.0629965 -0.9126804 0.3187478 -0.2557621 -0.9980668 0.01458781 -0.06041449 -0.9809626 -0.1018959 -0.1653162 -0.9809634 -0.1018762 -0.1653246 -0.75733 -0.5032558 -0.416155 -0.9112624 -0.3125712 -0.2681418 -0.8419824 -0.3917099 -0.3709838 -0.8420148 -0.3916854 -0.3709364 -0.8419806 -0.3917267 -0.37097 -0.9304494 -0.2533859 -0.2646872 -0.9304496 -0.2533838 -0.264689 -0.8985778 -0.3037565 -0.3166863 -0.8953459 -0.3511288 -0.2739787 -0.8830334 -0.3850949 -0.2682421 -0.883853 -0.3589649 -0.2999134 -0.9011133 -0.3111633 -0.3019475 -0.8997789 -0.3099312 -0.3071494 -0.8997721 -0.3099097 -0.3071906 -0.9557321 -0.1788098 -0.2336735 -0.955733 -0.1787718 -0.2336983 -0.9557362 -0.1787813 -0.2336786 -0.9722203 -0.1268547 -0.1967121 -0.9728286 -0.1283652 -0.1926832 -0.9985299 -0.009244263 -0.05340921 -0.9979651 -0.01724708 -0.06138521 -0.9979651 -0.01724714 -0.06138521 -0.9980809 0.01870632 -0.0590316 -0.9558776 0.1729542 -0.2374548 -0.9729824 0.1256291 -0.1937074 -0.973281 0.1356048 -0.1852977 -0.972868 0.08931624 -0.2134256 -0.9990201 -0.04220724 0.01331746 -0.9990202 -0.04220658 0.01331758 -0.9626182 0.1650416 -0.2147735 -0.9558779 0.1729595 -0.2374499 -0.9558775 0.172959 -0.2374517 -0.8886175 0.3605446 -0.2834901 -0.8899461 0.3255512 -0.3193935 -0.8993219 0.3193656 -0.2987066 -0.8993006 0.3193119 -0.2988281 -0.8981474 0.315945 -0.3057942 -0.9248071 0.2729413 -0.2650184 -0.8471977 0.3827738 -0.3684293 -0.8887087 0.3435595 -0.3035848 -0.8587029 0.4390249 -0.2643605 -0.9006356 0.3473552 -0.261151 -0.7642629 0.5517129 -0.3339385 -0.7642745 0.5516895 -0.3339511 -0.8472018 0.3827688 -0.3684253 -0.9982284 -0.004108369 -0.05935567 -0.9983406 0.01355898 -0.05596715 -0.9979502 0.008643984 -0.06340843 -0.9979503 0.008642435 -0.06340861 -0.9983813 -0.02392888 -0.0515958 -0.9943883 -0.03650933 -0.09929311 -0.9732488 -0.08104801 -0.2149836 -0.9729404 -0.1237212 -0.1951411 -0.9728288 -0.1283707 -0.1926792 -0.8982365 -0.2146961 -0.383506 -0.9688736 -0.1209277 -0.21601 -0.9572248 -0.1674683 -0.2359557 -0.8982376 -0.03304618 -0.4382659 -0.8982383 -0.03304535 -0.4382649 -0.8982382 -0.09604251 -0.4288869 -0.8982383 0.2125908 -0.3846728 -0.9689208 0.1196538 -0.2165077 -0.9729855 0.1256874 -0.193654 -0.7648473 -0.5614115 -0.3159518 -0.7776401 -0.531947 -0.3351243 -0.7796621 -0.4493955 -0.4360857 -0.7796639 -0.4493928 -0.4360854 -0.7796635 -0.3816543 -0.4964522 -0.9589331 -0.1728666 -0.2248649 -0.8982383 -0.2678697 -0.348445 -0.8982365 -0.2678737 -0.3484464 -0.7796637 -0.3816549 -0.4964514 -0.7796712 -0.3816421 -0.4964495 -0.7796719 -0.3058954 -0.5463881 -0.7796646 -0.3058922 -0.5464003 -0.8982347 -0.2146999 -0.383508 -0.8982347 -0.1570238 -0.4105095 -0.9727645 -0.08281242 -0.2164977 -0.9727646 -0.05065023 -0.226194 -0.9979664 -0.01392865 -0.06220269 -0.9979761 -0.01084399 -0.06266057 -0.7796626 -0.3059008 -0.5463982 -0.7796626 -0.2237108 -0.584876 -0.8982396 -0.1570143 -0.4105025 -0.8982396 -0.09604007 -0.4288845 -0.972764 -0.05065208 -0.2261961 -0.972764 -0.01742899 -0.2311419 -0.9981607 -0.004558324 -0.06045228 -0.9980115 0.002086699 -0.0629965 -0.7796626 -0.2237107 -0.5848759 -0.7796622 -0.1368337 -0.6110674 -0.7796645 -0.1368381 -0.6110635 -0.7796672 -0.1368329 -0.6110611 -0.7796671 -0.04708272 -0.6244215 -0.7796682 -0.04708158 -0.6244204 -0.7796716 0.04355907 -0.6246718 -0.9982907 0.004073977 -0.05830156 -0.9727643 0.01615804 -0.2312327 -0.9727652 0.01615995 -0.2312285 -0.8982377 0.03064155 -0.4384407 -0.8982343 0.03063762 -0.4384478 -0.7796667 0.04365044 -0.6246716 -0.7796728 0.04365611 -0.6246633 -0.9980615 0.0132659 -0.06080496 -0.9727652 0.04940825 -0.2264654 -0.9727656 0.04940873 -0.2264637 -0.8982344 0.09368777 -0.4294153 -0.8982349 0.09368818 -0.4294142 -0.7796726 0.1334796 -0.6117956 -0.7796639 0.1334735 -0.6118081 -0.9982489 0.02082943 -0.05536371 -0.9727656 0.08162099 -0.2169451 -0.9727645 0.08162033 -0.2169501 -0.898235 0.1547631 -0.4113664 -0.8982386 0.1547649 -0.4113579 -0.7796692 0.2205021 -0.5860841 -0.7796642 0.2204996 -0.5860919 -0.7796643 0.3028905 -0.5480701 -0.7796645 0.3028897 -0.5480704 -0.8982367 0.2125905 -0.3846766 -0.8982369 0.2659522 -0.3499144 -0.955469 0.1785623 -0.2349351 -0.9248071 0.2729419 -0.2650179 -0.7796654 0.3028901 -0.548069 -0.7796657 0.3789151 -0.4985429 -0.779664 0.3789176 -0.4985433 -0.7796665 0.3789263 -0.4985327 -0.7796661 0.4469943 -0.4385394 -0.7796638 0.4469948 -0.4385433 -0.7804538 0.4806719 -0.3998081 0.9888454 0.08719265 0.1207571 0.9887542 0.08764261 0.1211766 0.9952017 0.04887229 0.08476471 0.9977744 -0.06047117 0.02809745 0.9977743 -0.06047433 0.02809721 0.9822553 0.1783355 0.05805855 0.9955604 -0.0937727 0.008138716 0.9939178 -0.09313946 0.05875802 0.9961646 -0.0848816 0.02123993 0.9951117 -0.08667778 0.04732567 0.9774604 0.1879632 0.09613037 0.9929483 0.08634328 0.08123105 0.9671759 -0.25275 0.0262326 0.9907349 0.12181 0.06005656 0.9702528 -0.2405802 -0.02703005 0.3155524 0.02743929 0.9485114 0.656844 -0.07804566 0.7499765 0.964064 -0.2451724 -0.1023287 0.9904896 0.1125349 0.07915884 0.9900015 0.08979213 0.1087859 0.9897508 0.113514 0.08664852 0.971975 -0.229372 -0.05150681 0.1948406 0.5805821 -0.7905451 0.9760758 -0.186402 -0.1119385 0.97608 -0.1862713 -0.1121197 0.9756188 -0.1609521 -0.1492052 0.9987659 0.02067899 -0.04515552 0.9952092 -0.01808828 -0.09607958 0.999314 0.03442376 -0.01365983 0.9993141 0.03442174 -0.01365292 0.9988148 0.0436061 -0.02162241 0.9995464 0.03011816 -1.99187e-4 0.9995464 0.0301181 -2.01993e-4 0.9993657 0.02620774 -0.02411198 0.9950648 -0.04748797 -0.08712607 0.9840095 0.1592051 0.0798676 0.9907975 0.1228475 0.05682295 0.9990671 0.02635037 -0.03421497 0.9982064 0.02157622 -0.05584412 0.9985926 0.02338081 -0.04760479 0.9840093 0.1592083 0.07986426 0.9897429 0.1333345 0.05129289 0.9891446 0.1370568 0.0529949 0.9904536 0.1283894 0.05017912 0.9891443 0.1370589 0.05299234 0.9887603 0.1381049 0.05727219 0.9904799 0.1276313 0.05157446 0.9952087 -0.01808851 -0.09608519 0.995209 -0.01809167 -0.09608197 0.9924919 -0.05679798 -0.1083228 0.9800404 -0.1071999 -0.167419 0.9886756 -0.08363723 -0.1246015 0.988675 -0.08363837 -0.1246048 0.9886787 -0.08366966 -0.1245546 0.9893037 -0.09497344 -0.1107171 0.9581347 -0.1964718 -0.2082706 0.975632 -0.160923 -0.1491504 0.9650025 0.2576819 0.04868727 0.9583525 0.2824503 0.04221659 0.9616267 0.2661977 0.06643092 0.9159936 0.3987592 -0.04412102 0.970229 0.1711994 0.1713077 0.9019991 0.4314019 0.01702708 0.9965231 0.07775717 0.02992546 0.9697418 0.1645792 0.1803178 0.9813728 0.183604 -0.05654263 0.9813711 0.1836231 -0.05651003 0.8749971 -0.4819625 -0.04574233 0.8676682 0.4971439 1.44498e-6 0.9618912 0.2729253 0.01664555 0.9602133 0.2787259 0.0173881 0.9490185 0.3151378 0.007228195 0.8922376 0.4513088 -0.01524972 0.9079576 0.4190617 6.30777e-4 0.9079555 0.4190661 6.3032e-4 0.975396 0.2204489 -0.002242386 0.9959276 0.0891633 0.01333957 0.9977604 0.05711704 0.03481596 0.9902909 0.1389721 0.003272593 0.9600849 0.2792131 0.01664733 0.9600828 0.2792201 0.01664769 0.9617106 0.2736792 0.01456689 0.9753955 0.220451 -0.002242326 0.9953182 -0.09221082 0.02896231 0.9998404 -0.0171982 -0.004835546 0.9998405 -0.01719617 -0.004835844 0.968694 -0.245717 0.03542345 0.9686942 -0.2457172 0.03542351 0.9988853 -0.04698741 -0.004515111 0.9890009 -0.1478695 0.003448963 0.9954015 -0.09572887 0.003437161 0.9849039 -0.1726758 0.01213252 0.9481205 -0.3093479 0.07328838 0.9767189 -0.2139663 -0.01544809 0.9109684 -0.411212 0.03226786 0.9697472 -0.2429462 -0.02382296 0.9697396 -0.2429772 -0.02381318 0.9351882 -0.354151 2.4271e-4 0.8640464 -0.5034123 2.5759e-4 0.8640448 -0.5034149 2.57307e-4 0.73311 -0.6801102 -6.5507e-5 0.8054565 -0.5925678 0.0101605 0.7640228 -0.6448473 -0.02100408 0.7640235 -0.6448464 -0.0210039 0.9150725 -0.3995453 0.05482739 0.8668741 -0.4976626 0.02935034 0.5379495 -0.8429565 -0.005896985 0.6376963 -0.7695825 -0.03295713 0.69629 -0.7154434 -0.05762708 0.501107 -0.8648905 0.02926158 0.5011067 -0.8648906 0.0292617 0.578014 -0.815973 0.009382069 0.6567798 -0.7540824 -2.23911e-4 0.677931 -0.7351256 -2.23708e-4 0.6569482 -0.7539358 6.73176e-5 0.7331078 -0.6801124 -6.55783e-5 0.2228728 -0.9741961 0.03563094 0.4966439 -0.8645206 -0.0771296 0.3168875 -0.9484128 -0.009762942 0.2098838 -0.9776788 0.009641587 0.5090308 -0.8464792 -0.1560784 0.1630617 -0.9864486 0.01816177 0.1593027 -0.9870253 0.02008974 0.5379527 -0.8429543 -0.0058977 0.4176754 -0.9085916 0.002931058 0.3931758 -0.9194608 0.002142727 0.4204593 -0.9073114 2.10214e-4 0.3920462 -0.9199454 2.07777e-4 0.3035925 -0.9527584 0.009114444 0.7571212 0.5033916 -0.4163707 0.9125055 -0.3195532 -0.2553809 0.9554426 0.1791971 -0.234559 0.9554426 0.1791954 -0.2345601 0.955443 0.1791962 -0.2345578 0.9735252 0.1285558 -0.1890024 0.9553003 -0.1743934 -0.2387221 0.9725926 -0.1268416 -0.1948713 0.9727265 -0.137207 -0.187022 0.9727586 -0.08213055 -0.216784 0.9630851 0.1947893 0.1858066 0.9794371 -0.1269065 -0.156836 0.961973 -0.1668856 -0.2162343 0.955302 -0.1743898 -0.2387185 0.9553005 -0.1743868 -0.2387263 0.8982872 -0.3216843 -0.2993316 0.8980024 -0.3206251 -0.3013158 0.8982329 -0.2675948 -0.3486697 0.8982675 -0.3216222 -0.2994574 0.8899518 -0.3271718 -0.3177175 0.8882884 -0.3616077 -0.2831668 0.8883898 -0.3540065 -0.292306 0.8734617 -0.4078506 -0.2659369 0.7646448 -0.5617771 -0.3157924 0.764639 -0.5617898 -0.315784 0.818918 -0.4518792 -0.3538056 0.8668181 -0.3744735 -0.3292352 0.866776 -0.3745303 -0.3292814 0.9105978 0.3112941 -0.2718598 0.8463211 0.3784086 -0.3748968 0.8463497 0.378386 -0.3748548 0.8463292 0.3784114 -0.3748754 0.9365596 0.2382993 -0.2570399 0.9365593 0.2383217 -0.2570203 0.8986554 0.2982891 -0.3216242 0.899449 0.3389085 -0.2759211 0.8821076 0.381269 -0.2766229 0.8826325 0.3582527 -0.3043267 0.9015337 0.3104237 -0.3014535 0.9002482 0.3067661 -0.308946 0.9002383 0.3067361 -0.309005 0.9985159 0.00928837 -0.05366307 0.9979627 0.01724821 -0.06142365 0.9979627 0.01724648 -0.06142419 0.9980023 -0.00208944 -0.06314235 0.9980024 -0.002090394 -0.06314241 0.9982951 -0.004241585 -0.05821502 0.9979529 -0.008638083 -0.063367 0.9981845 -0.02028721 -0.05671125 0.9980751 -0.01873224 -0.05912172 0.9980834 -0.01339644 -0.06041616 0.9983185 -0.01364874 -0.05633687 0.9979529 -0.008636474 -0.06336724 0.9985789 0.02736294 -0.04573369 0.9961697 0.02820265 -0.08276742 0.9741298 0.07743555 -0.2123087 0.9735252 0.128558 -0.1890013 0.9735252 0.1285545 -0.1890034 0.9727635 -0.0501765 -0.2263039 0.9727649 -0.05017834 -0.2262973 0.972765 -0.01684522 -0.2311806 0.9727644 -0.01684415 -0.231183 0.9727644 0.0168454 -0.231183 0.8982355 0.2142251 -0.3837713 0.9688795 0.1206507 -0.2161384 0.9575068 0.1665424 -0.2354662 0.8982335 -0.09514087 -0.4290974 0.8982331 -0.09514051 -0.4290986 0.898233 -0.03193986 -0.4383574 0.8982342 -0.03194129 -0.4383549 0.8982343 0.03193968 -0.4383549 0.8982331 0.03194141 -0.4383572 0.8982331 0.09514111 -0.4290984 0.8982332 -0.2142276 -0.3837757 0.9688814 -0.1206473 -0.2161324 0.9725933 -0.1268585 -0.1948571 0.764636 0.5617922 -0.3157866 0.7776446 0.5318863 -0.3352101 0.7796627 0.4492332 -0.4362518 0.7796621 0.4492342 -0.4362518 0.7796617 0.3812432 -0.4967709 0.9585734 0.1734255 -0.225966 0.898233 0.2675971 -0.3486676 0.8982354 0.2675917 -0.3486657 0.7796643 0.3812507 -0.4967609 0.7796639 0.3812516 -0.496761 0.779664 0.3052182 -0.5467777 0.779667 0.3052196 -0.5467725 0.8982331 0.2142305 -0.3837742 0.8982331 0.1563366 -0.4107753 0.9727636 0.0824508 -0.21664 0.9727636 0.0501796 -0.226303 0.997972 0.01377993 -0.06214559 0.9979814 0.01083278 -0.06257605 0.7796638 0.3052335 -0.5467695 0.7796645 0.2227365 -0.585245 0.8982337 0.1563353 -0.4107743 0.8982335 0.09514027 -0.4290976 0.972765 0.05017513 -0.2262978 0.972765 0.01684397 -0.2311807 0.9982069 0.004349827 -0.05970108 0.9981697 0.004175961 -0.0603317 0.7796601 0.2227424 -0.5852485 0.7796601 0.1355507 -0.611356 0.7796605 0.1355516 -0.6113553 0.7796566 0.1355589 -0.6113587 0.7796567 0.04550647 -0.6245516 0.7796624 0.04550039 -0.624545 0.7796621 -0.045506 -0.6245447 0.7796564 -0.04550093 -0.6245523 0.7796568 -0.1355527 -0.6113598 0.779663 -0.1355569 -0.6113508 0.7796601 -0.135551 -0.611356 0.979251 0.07208144 0.189399 0.9727636 -0.08244901 -0.2166405 0.9727645 -0.08244955 -0.2166367 0.8982337 -0.1563361 -0.4107741 0.8982331 -0.1563358 -0.4107756 0.7796603 -0.2227384 -0.5852499 0.7796647 -0.2227405 -0.5852433 0.7796638 -0.3052326 -0.5467699 0.7796669 -0.3052197 -0.5467727 0.8982356 -0.214228 -0.3837695 0.8982353 -0.2675943 -0.3486639 0.9087621 -0.254078 -0.3310527 0.9065916 -0.3073714 -0.2891618 0.7796641 -0.3052185 -0.5467776 0.7796639 -0.3812513 -0.4967612 0.779664 -0.381251 -0.4967612 0.7796617 -0.3812446 -0.4967697 0.7796621 -0.4492338 -0.4362523 0.7796627 -0.4492337 -0.4362513 0.7804637 -0.4817652 -0.3984705 0.04765903 0 0.9988637 0.05924618 -0.008014798 0.9982113 -0.07789528 0.006489336 0.9969404 -0.06481033 0 0.9978976 0.05839693 -0.01367819 0.9981997 0.05840712 -0.01374197 0.9981982 0.06211811 -0.02673089 0.9977107 -0.06784933 -0.01910579 0.9975126 0.06211054 -0.02672135 0.9977115 0.04892373 -0.01231092 0.9987267 0.04808151 -0.01201021 0.9987712 -0.01883077 -0.06778383 0.9975224 -0.05201488 -0.007493793 0.9986182 -0.04440009 -0.005624115 0.998998 0.00373739 0.003285288 0.9999876 -0.06463491 -0.02124625 0.9976827 -0.06444472 -0.02024 0.997716 -0.06386655 -0.005890846 0.997941 -0.3706651 -0.9184041 0.1383517 -0.01047176 -0.9999142 -0.007868766 -0.3072392 -0.9188424 0.2476542 -0.1049898 -0.9908659 0.0846284 -0.1040115 -0.9912928 0.08074676 -0.1067553 -0.9908443 0.08265042 -0.1171323 -0.9881384 -0.09931147 -0.117125 -0.9881398 -0.09930568 -0.3131448 -0.9160118 -0.2507246 -0.3115864 -0.9188958 -0.2419595 -0.3399103 -0.918403 -0.2024771 -0.3399111 -0.9184045 -0.2024691 -0.3892922 -0.9184037 -0.07061296 -0.3705155 -0.9184035 -0.1387562 -0.3705165 -0.9184032 -0.1387556 -0.3705167 -0.9184031 -0.1387559 -0.3399159 -0.9184026 -0.2024689 -0.3956439 -0.9184041 -2.16185e-4 -0.395644 -0.9184039 -2.16218e-4 -0.3893683 -0.9184041 0.07018685 -0.389368 -0.9184043 0.07018691 -0.3893699 -0.9184035 0.070185 -0.3401331 -0.9184041 0.2020972 -0.3401362 -0.9184029 0.2020975 -0.3074254 -0.9187791 0.2476583 -0.3073428 -0.9187872 0.247731 -0.3073281 -0.918819 0.2476307 -0.1118916 -0.9912734 -0.06969481 -0.1051453 -0.9913129 -0.07901287 -0.1205756 -0.9901027 -0.07182127 -0.1167418 -0.9910757 -0.06434458 -0.1167463 -0.9910758 -0.06433522 -0.1286115 -0.9905248 -0.04816406 -0.1286224 -0.9905228 -0.04817593 -0.1302764 -0.9910771 -0.02818346 -0.1314625 -0.9910342 -0.02384573 -0.3892923 -0.9184037 -0.07061302 -0.3892974 -0.9184047 -0.07057267 -0.1404695 -0.9896187 -0.03038632 -0.130903 -0.9913553 -0.008886814 -0.1316848 -0.9912916 -7.19547e-5 -0.1527087 -0.9882169 -0.01036775 -0.1291511 -0.9911937 0.02924215 -0.1387125 -0.9900169 0.02500408 -0.1305296 -0.9913927 0.01012194 -0.1305296 -0.9913927 0.01012188 -0.1291516 -0.9911937 0.0292406 -0.129749 -0.9903634 0.04842901 -0.3706656 -0.9184039 0.1383516 -0.3706656 -0.9184041 0.138351 -0.1267139 -0.9907351 0.04886066 -0.1170476 -0.9909312 0.06599485 -0.115719 -0.9908994 0.0687564 -0.1231448 -0.9899569 0.06943023 -0.104116 -0.9912936 0.08060258 0.710356 8.94713e-6 -0.7038425 0.7103523 0 -0.7038462 0.7104101 -5.35266e-5 -0.7037878 0.7103533 3.08358e-6 -0.7038453 0.7103516 -3.56192e-7 -0.703847 0.7105979 3.32973e-4 -0.7035983 0.7103536 -8.35872e-5 -0.703845 0.7103406 -5.9051e-5 -0.7038581 0.710227 1.27494e-4 -0.7039728 0.279962 -0.006230771 -0.9599909 -0.7117838 0 -0.7023986 -0.7232931 -0.01145744 -0.6904461 -0.7232434 -0.01141786 -0.6904988 -0.7311049 -0.01755797 -0.6820392 -0.7316924 -0.01788467 -0.6814002 -0.7203406 -0.0116561 -0.6935226 0.6862647 -0.08716797 -0.7221099 0.7128631 -0.03459948 -0.7004492 0.7555605 -0.002724111 -0.6550732 0.7555083 -0.002708196 -0.6551335 0.7551122 -0.002567708 -0.6555906 0.749078 0 -0.6624818 0.7367419 4.77399e-4 -0.6761739 0.6722504 0.007796227 -0.7402828 0.5527388 0.09297949 -0.8281512 -0.6942242 -0.003241419 -0.7197516 -0.6943404 -0.003275752 -0.7196393 -0.5942668 0.008101642 -0.8042272 -0.6369877 -0.008591532 -0.7708261 -0.5942648 -0.008604049 -0.8042234 -0.4584677 0.02701735 -0.8883003 -0.4621642 0.02991777 -0.8862896 -0.3196518 -0.008491694 -0.947497 -0.3196096 -0.008491694 -0.9475113 -0.1553344 0.02462303 -0.987555 -0.1753508 0.03921324 -0.9837248 0.2799723 -0.006230771 -0.9599878 0.1278972 0.0461688 -0.9907124 0.1636327 0.01813769 -0.9863546 -0.02706813 -0.007208228 -0.9996076 -0.0271058 -0.007208228 -0.9996066 0.4254775 0.0102272 -0.9049113 0.4657847 0.03510409 -0.8842015 0.5551815 -0.002649784 -0.8317251 0.6434515 -0.00263375 -0.7654823 0.698651 -0.02563607 -0.7150033 -0.7038629 3.36822e-5 -0.710336 -0.7038 -8.38211e-5 -0.7103982 -0.703867 5.00825e-5 -0.7103319 -0.7038462 1.13945e-5 -0.7103524 -0.7038534 -8.64732e-6 -0.7103453 -0.7039157 -1.14255e-4 -0.7102836 -0.7038343 2.008e-5 -0.7103644 -0.703827 2.72932e-5 -0.7103716 -0.7038567 0 -0.710342 0.3703418 -0.9184114 0.1391664 0.3072801 -0.9187833 0.2478233 0.3101505 -0.9178196 0.2478181 0.3101096 -0.9178416 0.2477878 0.1056045 -0.9905505 0.08750575 0.105586 -0.9905539 0.08749079 0.1208308 -0.9873491 -0.1026718 0.120841 -0.9873471 -0.1026797 0.11366 -0.9913182 -0.06610393 0.01308351 -0.9998686 -0.009566485 0.3398851 -0.9184117 0.2024801 0.3398862 -0.9184109 0.2024818 0.3072983 -0.9187813 0.2478072 0.3891231 -0.9184101 0.07145708 0.3891211 -0.9184111 0.07145482 0.3891208 -0.9184111 0.07145506 0.3956252 -0.9184108 0.001493692 0.3896487 -0.9184114 -0.06851559 0.3896508 -0.9184105 -0.06851494 0.3713861 -0.9184105 -0.1363624 0.3713864 -0.9184103 -0.1363623 0.3713843 -0.9184111 -0.1363624 0.3414056 -0.9184113 -0.1999069 0.3414022 -0.9184126 -0.1999071 0.3414014 -0.9184109 -0.1999164 0.3145933 -0.9189181 -0.2379511 0.3167928 -0.9151322 -0.2493499 0.1175742 -0.9906604 0.06905311 0.1185082 -0.99044 0.07059907 0.1044827 -0.991111 0.08235484 0.1043543 -0.9911099 0.0825318 0.1078541 -0.9905259 0.08500474 0.1241059 -0.9909886 0.05039209 0.1256302 -0.9909533 0.0472083 0.3703416 -0.918412 0.139164 0.3703484 -0.9184094 0.1391624 0.1315551 -0.9898688 0.05341428 0.1277518 -0.9913118 0.03130859 0.1298099 -0.9912524 0.02383714 0.1458967 -0.9886533 0.03575843 0.1302333 -0.9914055 0.01242518 0.1302333 -0.9914056 0.01242548 0.1412304 -0.9899766 5.33297e-4 0.3956256 -0.9184107 0.001493871 0.3896476 -0.9184111 -0.06852585 0.1316158 -0.9912789 -0.006594955 0.1316158 -0.9912788 -0.006594896 0.1372575 -0.9902414 -0.02413493 0.1319128 -0.9909176 -0.02610188 0.1275739 -0.9907224 -0.04684174 0.1310928 -0.99028 -0.04647779 0.1170914 -0.9911922 -0.06186962 0.1146073 -0.9911415 -0.06710797 0.1291154 -0.9892804 -0.06821697 0.1057029 -0.9913895 -0.07728987 0.1249108 -0.9899789 0.06587243 0.01418489 -0.9997766 0.01567023 0.01540124 -0.9998242 0.01070052 0.01540404 -0.9998241 0.01069527 0.04814022 -0.9982705 0.0337392 0.04274928 -0.9989475 0.01663506 0.04274898 -0.9989473 0.01663583 0.1183044 -0.9929525 0.007033824 0.1183044 -0.9929524 0.00703448 0.1078515 -0.9931186 0.04564487 0.08083826 -0.9966138 0.01504319 0.0808382 -0.9966137 0.01504361 0.06250476 -0.9980377 0.003716051 0.06250476 -0.9980378 0.003716289 0.2520543 -0.9665644 -0.0471366 0.1360968 -0.988283 0.06909668 0.1660289 -0.9861197 0.001553773 0.1132686 -0.9924219 0.0476318 0.1659447 -0.985621 0.03183639 0.2511215 -0.9679106 -0.009337365 0.502521 -0.864106 0.0281676 0.5025213 -0.8641059 0.02816748 0.5783942 -0.8073152 0.1170567 0.6571162 -0.7537439 -0.008280932 0.7029885 -0.7078033 0.06943964 0.7076593 -0.7064697 0.01090925 0.7667923 -0.6407029 0.03910613 0.7721387 -0.6337286 0.04679495 0.3993762 -0.9066845 0.1357274 0.4172403 -0.8824529 0.2172269 0.4274017 -0.8863545 0.1780551 0.4586564 -0.8853678 0.07588291 0.4995598 -0.851047 0.1617373 0.5116218 -0.8581485 0.0427125 0.5852532 -0.7987219 0.1397213 0.5783951 -0.8073155 0.1170505 0.2986221 -0.9180427 0.2608112 0.3391683 -0.905065 0.2565581 0.3453935 -0.9070855 0.2406226 0.3438992 -0.9066889 0.2442307 0.3473827 -0.9075307 0.2360367 0.3588088 -0.9087107 0.2133101 0.3167752 -0.9162613 0.2451915 0.3520759 -0.9092172 0.2221859 0.3386109 -0.9160634 0.2148735 0.09766334 -0.9905453 0.09634304 0.124888 -0.9899827 0.06585896 0.1310003 -0.9850389 0.11197 0.1674116 -0.9848813 0.04451984 0.1928803 -0.9749057 0.1111575 0.2213253 -0.9749665 0.02134507 0.2718063 -0.9568485 0.1027735 0.2896476 -0.9571114 0.006491601 0.3523184 -0.9317871 0.08743369 0.3616709 -0.9323015 0.002844095 0.4948293 -0.8673465 0.05342394 0.4957459 -0.8678001 0.0340448 0.7728397 -0.634301 -0.01952344 0.8510399 0.4431463 -0.2816958 -0.7759655 0.5651445 0.2801595 -0.8412246 0.5210784 0.1442864 -0.995701 0.08782815 0.0294218 -0.9964313 0.07604861 0.03662443 -0.9956334 0.09009689 0.02442806 -0.9971414 0.06911319 0.03053623 -0.9970184 0.07296156 0.02511954 -0.9970183 0.07296299 0.02511888 -0.9970183 0.07296276 0.02511912 -0.9945282 0.09935861 0.03227126 -0.9921871 0.1216476 0.02768987 -0.9946714 0.09540468 0.03907483 -0.9909233 0.1282562 0.04026442 -0.9905693 0.1322274 0.03589385 -0.9860967 0.1625452 0.03453165 -0.9902783 0.133492 0.03910219 -0.9846861 0.1653776 0.0551685 -0.9804409 0.1910117 0.04743713 -0.9739586 0.221674 0.04759567 -0.9740028 0.2214789 0.04759728 -0.9784849 0.1944429 0.06898647 -0.9784842 0.1944466 0.06898683 -0.972984 0.2185642 0.07437717 -0.9477785 0.314712 0.05169361 -0.9585255 0.2753769 0.0734604 -0.9480521 0.3044626 0.09219354 -0.9573477 0.2754884 0.08712893 -0.947911 0.3024022 0.1000882 -0.9067142 0.4085548 0.1046539 -0.8638582 0.4887136 0.1220986 -0.9047515 0.4069939 0.1256207 -0.9201162 0.3808583 0.09128582 -0.9201123 0.3808674 0.09128707 -0.7759609 0.5651501 0.280161 -0.7759581 0.5651566 0.2801554 -0.7757289 0.4452493 0.447211 -0.8216518 0.4947823 -0.2829818 -0.8216348 0.494814 -0.2829756 -0.6766488 0.6381362 0.3673263 -0.5915979 0.7406851 0.31843 -0.5916171 0.7406749 0.3184179 -0.5915961 0.7406899 0.3184217 -0.4628068 0.7746253 0.4310052 -0.5101805 0.7876088 0.3455262 -0.4758048 0.8065096 0.3509301 -0.3193252 0.8673213 0.3818182 -0.3384857 0.8469364 0.4100322 -0.2042701 0.9079093 0.3660255 -0.2042614 0.907911 0.3660259 -0.338486 0.8469359 0.4100323 0.08903437 0.9144613 0.3947576 -0.05728411 0.9226192 0.3814345 -0.1088492 0.9186533 0.3797737 -0.06673657 0.8982081 0.4344748 -0.05591028 0.8922318 0.4481033 0.236222 0.9008116 0.364332 0.3740453 0.8547523 0.3598451 0.3740354 0.8547564 0.3598461 0.3189289 0.8539014 0.4112624 0.236253 0.9007968 0.3643479 0.2362228 0.9008113 0.3643319 0.4953958 0.7880595 0.3654385 0.5091423 0.7687135 0.3871095 0.6150146 0.7252494 0.309468 0.6909412 0.5924549 0.4142434 0.6149971 0.7252593 0.3094794 0.6149974 0.7252591 0.3094793 0.7237516 0.6536188 -0.2212829 0.7222948 0.3234645 0.6112781 0.7896525 0.5129834 0.3365961 0.7896413 0.5130181 0.3365696 0.9866638 0.1563634 0.04522216 0.9870404 0.1536052 0.04644036 0.9865981 0.156576 0.04591387 0.9911782 0.1201835 0.05587244 0.989985 0.1409416 -0.008067607 0.9929282 0.1142777 0.03216075 0.9935335 0.1079896 0.03506344 0.9944447 0.09340256 0.04853242 0.9957982 0.0915752 -1.53199e-4 0.9960946 0.08495604 0.02404367 0.9965936 0.07619065 0.03156238 0.9967536 0.07822883 0.01904398 0.9970859 0.07205361 0.02506035 0.9970859 0.07205361 0.02505999 0.9970859 0.07205265 0.02506113 0.7986488 0.5938717 0.09734702 0.8472806 0.5107189 0.1458826 0.9286004 0.3544244 0.1099303 0.8465155 0.5168234 0.1276916 0.8920868 0.4398961 0.1033083 0.912197 0.3892394 0.1280211 0.938964 0.319023 0.1287282 0.9119712 0.3967379 0.1044396 0.9443001 0.3212395 0.07143235 0.954532 0.2882922 0.07587027 0.9435907 0.3209286 0.08149629 0.9542039 0.283882 0.09437131 0.9730765 0.2240369 0.0541262 0.9765054 0.207991 0.05636394 0.9727935 0.2243525 0.05778193 0.9760208 0.2072521 0.06655901 0.9857559 0.1590374 0.05470222 0.9765751 0.2081134 0.0546804 0.9872993 0.1528672 0.043262 0.7629027 0.6305125 0.142945 0.7628704 0.6305502 0.1429522 0.7629046 0.6305108 0.1429426 0.6589365 0.7427676 0.1187396 0.6633968 0.7399873 0.1110112 0.6731556 0.684159 0.2806924 0.7229644 0.6361773 0.269446 0.5492985 0.8239459 0.1392271 0.4971901 0.8607482 0.1091548 0.539963 0.8393153 0.06316465 0.2879239 0.9490711 0.1279219 0.2879324 0.9490686 0.1279205 0.3078329 0.9456056 0.1052084 0.4269052 0.8921297 0.1478394 0.4269123 0.8921265 0.1478386 0.1087595 0.9039567 0.4135621 0.104094 0.9896172 0.09910708 0.1483967 0.9795679 0.1357392 -0.1416077 0.9863896 0.08356392 0.00471121 0.9886403 0.150227 0.004711925 0.9886403 0.1502271 -0.1416289 0.9863874 0.08355271 -0.1052792 0.9848806 0.1375733 -0.2792157 0.9515913 0.1285012 -0.3074415 0.9462571 0.1003845 -0.4121087 0.8987176 0.1499102 -0.6529257 0.7478567 0.1199935 -0.5432569 0.8277718 0.1402349 -0.4960022 0.8626393 0.09917277 -0.4121105 0.8987163 0.1499127 -0.4121171 0.8987135 0.1499119 -0.6716032 0.6602092 0.3362633 -0.6626969 0.7414875 0.1050202 -0.6529276 0.7478553 0.1199922 -0.8412216 0.521083 0.1442874 -0.8412244 0.521078 0.1442884 -0.7986484 0.593904 0.09715354 -0.7540263 0.6402454 0.1467323 -0.7540289 0.6402424 0.1467316 -0.784727 -0.5495648 0.2866741 0.2257247 -0.9036877 0.3638637 0.5791472 -0.794485 0.1827073 -0.07062447 -0.9887909 0.1315478 -0.9971632 -0.07096022 0.02510464 -0.9971639 -0.07094442 0.02512276 -0.9961869 -0.08222895 0.02915447 -0.9970008 -0.07469606 0.0202496 -0.9967041 -0.07713872 0.0251109 -0.9964802 -0.07518428 0.03707695 -0.9621318 -0.2615499 0.07677406 -0.9610697 -0.2652413 0.07740885 -0.9625338 -0.2607107 0.07455593 -0.9612045 -0.2666679 0.07052791 -0.9629073 -0.2605845 0.07003831 -0.9612066 -0.2667227 0.07029145 -0.9816339 -0.1812694 0.05946624 -0.9802085 -0.190921 0.05235129 -0.9822963 -0.1798678 0.05235964 -0.980594 -0.1909636 0.04436421 -0.9903656 -0.1288111 0.05082994 -0.9887996 -0.1429388 0.04293996 -0.9909268 -0.1264073 0.04566442 -0.9903011 -0.1367872 0.02434962 -0.9940098 -0.0982964 0.04777318 -0.9931404 -0.1117506 0.03440988 -0.9946808 -0.09380227 0.04255694 -0.9956023 -0.09302109 0.01110267 -0.996035 -0.08479493 0.02690833 -0.8720951 -0.4711304 0.1322351 -0.9623512 -0.2607801 0.07664185 -0.9278708 -0.3595817 0.09877598 -0.9269254 -0.3615694 0.1003837 -0.9276648 -0.3594187 0.101273 -0.875457 -0.4660156 0.1280798 -0.8006837 -0.5871423 0.1190364 -0.7911407 -0.602823 0.1034442 -0.8723658 -0.467388 0.1432704 -0.8723704 -0.4673789 0.1432722 -0.5936548 -0.7907261 0.1494197 -0.5936574 -0.7907244 0.1494181 -0.6618402 -0.7432988 0.097337 -0.701933 -0.6992402 0.135474 -0.7927422 -0.5973234 0.1215095 -0.344403 -0.92947 0.1321824 -0.3074592 -0.9463123 0.09980845 -0.3444049 -0.9294691 0.1321827 -0.4697144 -0.8732491 0.1296315 -0.4991919 -0.8573125 0.1257885 -0.4646003 -0.8815293 0.08397996 -0.5936547 -0.7907261 0.1494197 -0.07398325 -0.9885495 0.1315156 -0.07398545 -0.9885495 0.1315145 -0.1042345 -0.989338 0.1017124 -0.2137341 -0.9659283 0.1459466 -0.2137392 -0.9659273 0.1459463 0.3445268 -0.9310196 0.1204325 0.3096865 -0.9423546 0.1267362 0.5660136 -0.8218928 0.06419295 0.5660125 -0.8218936 0.06419444 0.3484151 -0.9215092 0.1715451 0.3484061 -0.9215124 0.171546 0.7660454 -0.6177511 0.1776461 0.7660573 -0.6177371 0.1776433 0.7660592 -0.6177351 0.1776421 0.7999185 -0.5899353 0.1100307 0.8939 -0.4222339 0.150537 0.9135624 -0.3814361 0.1411039 0.8939284 -0.4242038 0.1447183 0.8788844 -0.4470073 0.1665735 0.8937664 -0.4187186 0.1607989 0.9358949 -0.343622 0.07761913 0.943501 -0.3239576 0.06969439 0.9353752 -0.3432586 0.08512818 0.9436362 -0.3208379 0.08132475 0.9351631 -0.3431401 0.08789116 0.9676911 -0.2395245 0.0787518 0.9847645 -0.1658543 0.05226176 0.9674782 -0.2388086 0.08340483 0.9666811 -0.2423831 0.08232951 0.9666801 -0.2423874 0.08232986 0.9917859 -0.121368 0.04038232 0.9863177 -0.1587365 0.04449915 0.9914017 -0.1205561 0.05088055 0.9860174 -0.1594364 0.04847568 0.98526 -0.1645167 0.04687213 0.9863933 -0.1585517 0.04346871 0.9684901 -0.2434793 0.0523892 0.9930026 -0.1124396 0.03609967 0.9930032 -0.1124333 0.03610265 0.99266 -0.1163302 0.0330668 0.996329 -0.07876974 0.03352683 0.9962778 -0.08180367 0.02718192 0.9965435 -0.07683092 0.03159034 0.9966445 -0.07792383 0.02504986 0.9966444 -0.07792514 0.02504926 0.9966445 -0.07792448 0.02505004 0.7138909 -0.6383247 0.2879258 0.7890112 -0.5293346 0.3118751 0.7890089 -0.5293409 0.3118701 0.7722244 -0.437146 0.4610563 0.8671371 -0.4640153 -0.1810054 0.8671396 -0.4640101 -0.1810068 0.6617304 -0.7434828 0.09667569 0.6687289 -0.6396787 0.3789629 0.7138962 -0.6383196 0.2879246 0.6111295 -0.72987 0.306285 0.6111313 -0.729869 0.3062838 0.6111321 -0.7298684 0.3062837 0.505469 -0.8406157 0.1945924 0.5100468 -0.7816573 0.3589763 0.4805188 -0.7750921 0.4102851 0.2257193 -0.903689 0.3638641 0.3566235 -0.8316699 0.4256113 0.3190711 -0.8557204 0.4073525 0.3642416 -0.8574484 0.3634699 0.3643134 -0.8574206 0.3634633 0.07903599 -0.9178013 0.3890938 0.1087744 -0.903084 0.4154605 0.1050868 -0.9857795 0.1311314 0.1108643 -0.9841041 0.1387376 -0.2144249 -0.9061681 0.3645292 -0.2144306 -0.9061667 0.3645288 -0.1087999 -0.9019579 0.4178931 -0.06786161 -0.9206748 0.3843863 -0.06776475 -0.9206808 0.3843888 -0.6002697 -0.7352769 0.314713 -0.6002652 -0.7352793 0.3147158 -0.5091306 -0.7671811 0.3901526 -0.4838525 -0.7999672 0.3548792 -0.3194392 -0.8713181 0.3725097 -0.3473781 -0.8401898 0.4164248 -0.3473237 -0.8402254 0.4163984 -0.6724779 -0.6679535 0.3187658 -0.6811817 -0.6265482 0.37872 -0.6002567 -0.7352865 0.3147155 -0.9114565 -0.3916735 0.1258529 -0.8497521 -0.4768273 -0.224849 -0.7390261 -0.6495553 -0.1786568 -0.7527159 -0.3702714 0.5443509 -0.7847266 -0.5495659 0.2866731 -0.9896277 -0.1340543 0.05163866 -0.9896712 -0.133781 0.05151349 -0.9899302 -0.1322782 0.05040496 -0.9951916 -0.09607452 0.01905739 -0.9896277 -0.1340545 0.05163848 -0.9915288 -0.1238108 0.03926193 -0.9955323 -0.0904926 0.02695512 -0.9925128 0.05664461 -0.1082113 -0.9800574 0.1071093 -0.1673775 -0.9885332 0.08403289 -0.1254611 -0.9885328 0.08403408 -0.1254639 -0.9885293 0.08400529 -0.1255111 -0.9890033 0.09186333 -0.1159037 -0.9689301 0.1640874 -0.185067 -0.9932517 -0.03191816 0.1115008 -0.964926 0.1965913 -0.1739811 -0.9649251 0.1965937 -0.1739844 -0.9990091 -0.02402645 -0.03746455 -0.9988642 -0.02530968 -0.04036915 -0.9952198 0.0180006 -0.09598755 -0.9952201 0.01800006 -0.09598368 -0.9952201 0.01800036 -0.09598338 -0.9794788 -0.1701647 0.1080047 -0.9794788 -0.1701656 0.1080039 -0.9991447 -0.03346443 -0.02429085 -0.9983926 -0.02629315 -0.05020803 -0.9988685 -0.01899898 -0.04359775 -0.9994575 -0.001009047 -0.03291785 -0.9994577 -0.001008629 -0.03291225 -0.9986178 -0.0129863 -0.05093067 -0.9997219 -0.01256036 -0.01996582 -0.9988779 -0.02627551 -0.03940403 -0.9957763 -0.08474361 0.03532963 -0.9654564 0.2189325 -0.141289 -0.9654522 0.2190803 -0.1410886 -0.2729525 -0.5663353 -0.7776641 -0.2790307 -0.5643758 -0.776931 -0.6628996 0.0813862 0.7442716 -0.9702413 0.2406437 -0.02687972 -0.9955523 -0.07311969 0.05940592 -0.9899955 -0.08975076 0.1088756 -0.9898748 -0.08087474 0.1166499 -0.9889732 -0.08732622 0.1196084 -0.9768561 0.2138698 -0.003420889 -0.9641344 0.2450525 -0.1019524 -0.8660926 0.4933073 -0.08081799 -0.9666343 0.2541152 0.03230339 -0.9924362 -0.0968514 0.07543414 -0.8660925 0.4933081 -0.08081477 -0.99533 0.07806682 0.05677956 -0.9924361 -0.09685343 0.07543379 -0.9979552 0.06382638 0.003417909 -0.9993606 0.03316444 0.0133599 -0.9995455 0.02683019 0.0137456 -0.9981402 0.0348792 0.04999518 -0.9978564 0.03803437 0.05325394 -0.997808 0.04555326 0.04800236 -0.9995974 -0.02245026 0.01735079 -0.9981788 -0.01329368 0.05884218 -0.9967868 0.0509572 0.0617997 -0.9900441 -0.08986765 0.1083351 1 -4.42392e-6 -4.41404e-7 1 1.27485e-6 0 1 0 0 1 -8.96035e-7 0 1 -1.74078e-6 0 1 -1.38599e-5 2.2282e-6 0.219216 -0.9756053 0.01177227 0.7985667 -0.5984261 -0.06463295 0.6122589 -0.7844202 0.09911626 0.6122662 -0.784415 0.09911251 0.6122441 -0.7844319 0.09911519 0.2128031 -0.8981969 0.3846519 0.2109199 -0.8985724 0.3848123 0.2116102 -0.8966702 0.3888493 0.2329776 -0.9614687 0.1459432 0.2290789 -0.8962651 0.3797783 0.262041 -0.954115 0.14491 0.203081 -0.9734326 0.105769 0.2192264 -0.9756034 0.01173669 -0.1285542 -0.9916315 0.01187419 -0.08918386 -0.9847229 0.1495561 -0.2093744 -0.8988721 0.3849561 -0.236028 -0.9607192 0.1459777 -0.2362132 -0.9666488 0.09896206 -0.5401116 -0.8276124 0.152765 -0.4800351 -0.8661727 0.1389651 -0.5674461 -0.8132743 0.1288017 -0.4835919 -0.8725838 0.06882208 -0.7596882 -0.6496921 0.02781975 0.6152954 -0.7882959 -0.001066625 -0.4521125 -0.8919609 8.78733e-5 -0.4847383 -0.8746592 8.78094e-5 -0.4520913 -0.8919716 -3.10391e-4 -0.484741 -0.8746575 -6.68329e-4 -0.7461796 -0.6381394 0.1897209 -0.9758084 -0.2186276 0 -0.7904855 -0.6124805 5.69179e-4 -0.7904827 -0.6124841 5.69179e-4 -0.8659374 -0.500149 -0.001843392 -0.9758089 -0.2186254 -8.70516e-5 -0.9277279 -0.373257 -1.08245e-4 -0.9962676 -0.08629292 0.0021227 -0.02953565 -0.9995637 -1.08179e-4 -0.1285631 -0.9916994 0.001991868 0.38349 -0.9235411 -0.002662837 0.2192311 -0.9756727 -7.42885e-4 0.3834367 -0.9235668 -7.19626e-4 0.219241 -0.9756682 0.002180218 0.6152734 -0.7883132 -0.001066505 0.6152881 -0.7883013 0.001258015 0.7108136 -0.7033804 -2.21301e-4 0.7108182 -0.7033758 -2.213e-4 0.800253 -0.5996626 2.3274e-5 0.8695636 -0.4938209 -3.92952e-5 0.9241206 -0.3821 8.85673e-4 0.9766061 -0.215036 7.33983e-5 0.9241341 -0.3820683 9.37836e-5 0.9770496 -0.2130089 -0.001144647 0.9953038 -0.09680151 0 0.9541246 0.2977078 0.03187984 0.9977985 -0.06489711 0.01365035 0.9896193 0.1366446 0.04451799 0.9967491 0.03214639 0.07387727 0.9967501 0.03214383 0.07386559 0.997667 0.0311737 0.06073689 0.9965966 0.05706018 0.05949348 0.9931731 -0.04476147 0.1077191 0.9978312 0.01940137 0.06290245 0.997895 0.06410294 0.009817481 0.9978947 0.06410866 0.009813308 0.9978947 0.06410819 0.009813368 0.9941525 -0.04704511 0.09719896 0.9834021 0.1712304 -0.06000441 0.2177133 -0.5825464 -0.7830969 0.2726372 -0.5660713 -0.7779666 0.9654072 0.2192192 -0.1411803 0.9654082 0.2191872 -0.1412238 0.995816 -0.08436179 0.03512436 0.9956004 -0.07275581 0.05904698 0.9946455 -0.07441377 0.07171422 0.9787404 0.2012551 -0.03954476 0.7694124 0.08119314 0.633571 0.9586083 0.2826599 -0.03425532 0.9845083 0.09590488 -0.1467838 0.9845057 0.09587234 -0.1468233 0.9845063 0.09587353 -0.1468178 0.9845012 0.09588336 -0.1468461 0.9867095 0.08965295 -0.135523 0.9952403 -0.09564596 0.01867288 0.985248 0.1104536 -0.1307148 0.9727008 0.1700847 -0.1578745 0.964305 0.188493 -0.1859738 0.9890792 -0.13744 0.05322223 0.9952871 -0.0952174 0.01836115 0.9894738 -0.1364037 0.04832905 0.9954732 -0.09194076 0.0240814 0.9930088 -0.1088132 0.04575359 0.9823738 -0.165528 0.08684605 0.9820146 -0.1698711 0.08240771 0.9905631 -0.128028 0.04892355 0.9890792 -0.1374394 0.05322289 0.9955831 0.0144068 -0.09277349 0.995583 0.0144062 -0.09277415 0.9974603 0.01319223 -0.0699926 0.9981362 -0.0326997 -0.05152451 0.9983521 -0.02132344 -0.05327874 0.9983719 -0.0264399 -0.05054175 0.9991571 -0.01346379 -0.03877842 0.9991516 -0.0126385 -0.03919929 0.9991322 -0.01277774 -0.03964555 0.9991465 -0.012474 -0.03938031 0.9991468 -0.01247298 -0.03937059 0.9991151 -0.01234614 -0.04020601 0.9990068 -0.008368909 -0.04376435 0.9999341 -0.01147878 -2.98342e-4 0.5738314 9.83075e-4 0.8189729 0.7070906 0.006087005 -0.7070968 0.4926369 -0.1087688 -0.8634108 0.6879762 -0.02770072 -0.7252044 0.8436213 -0.1131398 -0.5248833 0.965924 0.002180933 -0.2588168 0.8301452 0.002309024 -0.5575424 0.8299448 0.002308189 -0.5578408 0.1579942 0 -0.9874401 0.06464296 5.14606e-6 -0.9979085 0.2587663 -0.02237528 -0.9656808 0.2554569 -0.02353149 -0.9665341 0.4834849 0.006333708 -0.8753297 -0.2587571 -0.02391809 -0.9656463 -0.2480872 -0.02039277 -0.968523 -0.07362401 -0.001342713 -0.9972851 -0.01613801 -8.45783e-5 -0.9998697 -0.004744291 -6.52049e-6 -0.9999887 0 0 -1 0 0 -1 -0.8305882 0.003623723 -0.5568754 -0.8296445 0.003622889 -0.5582804 -0.6765857 -0.03140896 -0.7356936 -0.7070096 -0.01631253 -0.7070157 -0.4726398 0.005604028 -0.8812379 -0.472624 0.005604028 -0.8812463 -0.8296176 0.003623723 -0.5583203 -0.9658861 -0.009124755 -0.2588067 -0.9441996 -0.03481173 -0.3275291 -0.8155167 0.001615166 0.5787312 -0.9307281 -0.001737833 0.3657075 -0.9657319 -0.01999741 0.2587705 -0.992302 0 0.1238418 -0.9938005 0 -0.1111773 -0.8158308 0.001615166 0.5782883 -0.7071127 0.001328229 0.7070996 -0.7996261 -0.03736716 0.5993345 -0.4737663 0.002812027 0.8806461 -0.4737978 0.002812027 0.8806293 -0.6549236 -0.005814731 0.7556727 -0.0704227 0.001955389 0.9975153 -0.04051619 -0.1699337 0.9846222 -0.30229 0.1697746 0.9379752 -0.2766298 -0.01521986 0.960856 -0.2587941 -0.01215291 0.9658561 0.2588131 9.40261e-4 0.965927 0.5412272 -0.07117992 0.8378584 0.3672577 -0.02822971 0.9296908 0.1641913 -0.003415703 0.9864226 -0.04949122 0.001955628 0.9987726 -0.07406616 0.001954972 0.9972515 0.9384221 -0.03942698 -0.3432341 0.9925268 0 -0.1220276 0.9659249 0 0.2588222 0.9945067 -0.05847448 0.08681696 0.9694556 -0.01733171 0.2446537 0.8845365 0.003993749 0.466454 0.8845288 0.003993749 0.4664683 0.7071081 0.003821134 0.707095 0.8597127 -0.06472665 0.5066602 0.7335247 -0.01874876 0.6794042 0.5796137 0.8148005 0.01217257 0.5026719 0.8638851 0.0319916 0.5026756 0.8638831 0.03199046 0.5379511 0.8429554 -0.005897283 0.4176764 0.908591 0.002931416 0.5379496 0.8429564 -0.005896925 0.6376965 0.7695823 -0.03295725 0.7550788 0.6501953 -0.08427387 0.417679 0.9085898 0.002931475 0.3920426 0.919947 2.07457e-4 0.3920458 0.9199457 2.07457e-4 0.3035926 0.9527583 0.009114146 0.2228734 0.974196 0.03563058 0.4966324 0.8645276 -0.07712501 0.3168916 0.9484115 -0.009763896 0.2098813 0.9776793 0.009641885 0.50904 0.8464726 -0.156085 0.1630413 0.9864519 0.01817107 0.1593262 0.9870219 0.02007633 0.8038572 0.5947909 0.006123363 0.8636007 0.5038513 0.01810497 0.7345973 0.6784967 0.003015756 0.7345969 0.6784971 0.003015756 0.7292317 0.6842579 0.003518879 0.6583222 0.7527317 0.002612113 0.6583218 0.752732 0.002612113 0.8480794 0.5298656 -0.00197649 0.9118489 0.4088695 0.03684413 0.739264 0.6728401 -0.02784371 0.8480796 0.5298652 -0.00197643 0.9008396 0.4341517 -6.76617e-4 0.9008429 0.4341448 -6.76617e-4 0.9157967 0.4016407 -0.001101553 0.9850643 0.1712486 0.01794803 0.9514729 0.3076792 -0.005722343 0.9514776 0.307665 -0.005726993 0.9514731 0.3076789 -0.005722343 0.9689746 0.2437357 0.04100054 0.9689714 0.2437474 0.04100501 0.9887142 0.1491503 -0.01408505 0.9416413 0.3363832 0.01256424 0.9112387 0.4105012 0.03365707 0.998397 0.05524784 0.01229071 0.9954411 0.09491866 0.009357929 0.995441 0.09491872 0.009357929 0.9900968 -0.1403375 -0.003713071 0.9981522 -0.05881923 0.01524382 0.9976035 -0.06849038 0.00980705 0.9998404 0.01719689 -0.004835784 0.9998404 0.01719808 -0.004835605 0.8536826 -0.5191101 0.04184222 0.8536827 -0.5191099 0.04184228 0.8664351 -0.4955216 0.06122565 0.9170972 -0.3628468 0.1651515 0.9562371 -0.2623803 0.1294888 0.9649407 -0.2309403 0.1247243 0.9139427 -0.3857789 0.126029 0.9650973 -0.2331662 0.1192513 0.9132066 -0.3896716 0.1192044 0.9760413 -0.2174448 0.007831275 0.976042 -0.2174416 0.0078305 -1 4.67497e-6 0 -1 -5.72229e-7 2.17958e-7 -1 0 0 -1 4.61848e-7 0 -1 0 0 -1 -7.67368e-5 -6.3051e-6 0.7728551 -0.6343166 0.01837152 0.4235833 -0.9057016 0.01677966 0.7725647 -0.6340753 0.03304874 0.1657887 -0.9846944 0.05376881 0.4213494 -0.9057095 0.046422 0.1660291 -0.9861209 0 0.5023865 -0.8638744 0.03645116 0.421195 -0.9056812 0.04833507 0.5023067 -0.8637375 0.04056531 0.4202082 -0.9054495 0.05988621 0.4202061 -0.9054504 0.05988621 0.8347857 -0.548075 0.0524078 0.08453351 -0.931169 0.3546527 0.05513083 -0.9910679 0.1214289 0.112228 -0.9881144 0.1050468 0.4187259 -0.9049158 0.07613211 0.4574579 -0.8808889 0.1215192 0.1391358 -0.9882193 0.06374686 0.1450801 -0.9866403 0.0741133 0.1439159 -0.9880301 0.05554002 0.1457507 -0.9880094 0.05093395 0.1509819 -0.9868179 0.05826568 0.1495308 -0.9879585 0.03972846 0.1182088 -0.9880316 0.09909695 0.1221508 -0.9859036 0.1143385 0.1260933 -0.9883234 0.08554059 0.130522 -0.9882739 0.07923877 0.1360759 -0.9863887 0.09230768 0.1361087 -0.9882507 0.06953412 0.08863204 -0.9876938 0.1288611 0.09055209 -0.9881958 0.1235689 0.08453983 -0.9311608 0.3546721 0.0917856 -0.9874578 0.1284623 0.06794732 -0.9880939 0.1380349 0.0650655 -0.9875378 0.1433026 0.09286516 -0.98763 0.1263449 0.1657912 -0.8619902 0.4790471 0.1647779 -0.898858 0.4060823 0.1503495 -0.898773 0.4118277 0.1868916 -0.9060475 0.3796702 0.2479745 -0.890026 0.3825735 0.2490654 -0.8900064 0.3819094 0.2479686 -0.8900223 0.3825859 0.2547507 -0.8932644 0.3703792 0.3292327 -0.882529 0.3357802 0.1051055 -0.9873806 0.1184585 0.3131664 -0.8816754 0.3529522 0.329196 -0.8825312 0.3358107 0.4893957 -0.7717283 0.4061124 0.4848953 -0.7741685 0.4068658 0.4682121 -0.799272 0.3767514 0.4167628 -0.7633278 0.4935985 0.5755565 -0.739273 0.3495858 0.5785055 -0.7326779 0.3584889 0.5785121 -0.7326776 0.3584789 0.7135567 -0.6622782 0.2285264 0.713543 -0.6622856 0.2285479 0.6533309 -0.6953451 0.2994229 0.6531362 -0.6959241 0.2985011 0.6531396 -0.6959239 0.2984941 0.8965121 -0.1359837 0.4216331 0.7983472 -0.5336249 0.2790813 0.856642 -0.4635729 0.226417 0.8566367 -0.4635731 0.2264363 0.8559987 -0.4652984 0.2253081 0.8865303 -0.4395042 0.144568 0.886532 -0.439504 0.1445578 0.8889645 -0.4534753 0.06404817 0.8253657 -0.5544851 0.1063849 0.1759823 -0.9831129 -0.0501908 0.4245856 -0.9053862 0.001742124 0.4245846 -0.9053866 0.001741886 0.4167602 -0.7633276 0.493601 0.299499 -0.8851964 0.3559883 0.356647 -0.8850136 0.2992553 0.3565713 -0.8851569 0.2989214 0.3973162 -0.8853825 0.2413249 0.3972582 -0.8854501 0.241172 0.4222945 -0.8855563 0.1935384 0.4222555 -0.8855919 0.1934617 0.4383547 -0.8856465 0.1532173 0.4383305 -0.8856649 0.1531789 0.4489796 -0.8856945 0.1181637 0.2895534 -0.953765 -0.08056783 0.4275546 -0.9021631 -0.05743509 0.8965202 -0.1359845 0.4216156 0.6623643 -0.6799793 0.3144865 0.6918186 -0.6803672 0.2418417 0.6918001 -0.6803996 0.2418037 0.7086508 -0.6804577 0.1865245 0.7086372 -0.6804783 0.1865011 0.728181 -0.6790735 0.0927996 0.4275555 -0.9021627 -0.05743479 0.8469735 -0.5066244 -0.1611448 0.8743304 -0.4817103 -0.05917376 0.8991669 -0.377345 -0.2216072 0.8762512 -0.4789136 -0.05315625 0.9061368 -0.3661369 -0.2118017 0.9147752 -0.3809568 0.1343806 0.9972808 -0.02832925 0.06803232 -0.9959694 -0.08965331 0.002684712 0.9997357 -0.01981872 0.01165807 0.9957063 -0.08000922 0.04655718 0.9957073 -0.07999908 0.04655128 0.9956861 -0.08019232 0.04667276 0.9984038 -0.04811227 0.0295841 0.996766 -0.07474505 0.02951127 0.9876172 -0.1357461 0.07864654 0.9876104 -0.1357835 0.07866656 0.9940995 -0.09371668 0.05462032 0.9920969 -0.1084313 0.06313848 0.9876143 -0.1357618 0.07865434 0.9969496 -0.06996589 0.0345875 0.9969531 -0.06993079 0.03455954 0.996953 -0.06993228 0.03456038 0.9758583 -0.1799764 0.1237292 0.9858402 -0.1597684 0.05092287 0.9540298 -0.2187259 0.2049046 0.9661996 -0.2344287 0.1072451 0.9661998 -0.2344286 0.1072443 0.9534019 -0.2653543 0.1435685 0.9456323 -0.2836021 0.1592148 0.937359 -0.3016896 0.1741881 0.9788641 -0.1777869 0.1010785 0.9788661 -0.1777788 0.1010745 0.9603464 -0.2448254 0.133399 0.9427632 -0.2866256 0.170421 0.9502828 -0.2671173 0.1600347 0.9583901 -0.243922 0.1482921 0.9583914 -0.243918 0.1482901 0.9689183 -0.2094764 0.1315932 0.9689193 -0.2094734 0.1315919 0.9790033 -0.168732 0.1143767 0.979003 -0.1687337 0.1143774 0.9246988 -0.3373386 0.1764509 0.9908056 -0.1075484 0.08208304 0.9257258 -0.337897 0.1698742 0.9603447 -0.2448308 0.1334014 0.9300174 -0.3167182 0.1864332 0.9210763 -0.3355656 0.1975204 0.8648052 -0.4339461 0.2525923 0.7890198 -0.5293526 0.311823 0.8028922 -0.5140943 0.3017802 0.8028846 -0.5141027 0.3017858 0.8028737 -0.5141152 0.3017937 0.877434 -0.4130897 0.2438576 0.8774194 -0.4131129 0.2438706 0.8648045 -0.4339471 0.2525929 0.8648084 -0.4339411 0.2525898 0.9366065 -0.2975013 0.1850983 0.9365989 -0.2975193 0.1851075 0.6999908 -0.6184322 0.3571476 0.5917611 -0.6947134 0.4088913 0.5113818 -0.7398065 0.4372357 0.5916059 -0.6944422 0.4095761 0.6999985 -0.6184263 0.3571429 0.7936005 -0.5344316 0.2908284 0.6194613 -0.6721316 0.4055945 0.6194486 -0.6721394 0.4056012 0.7132433 -0.6036221 0.3562645 0.7132356 -0.6036286 0.3562688 0.8033612 -0.5130831 0.3022525 0.6060993 -0.7202552 0.3374555 0.4776599 -0.7685054 0.4257235 0.3490775 -0.8070949 0.4761751 0.3733901 -0.7875156 0.4903049 0.4160957 -0.7787897 0.4694156 0.4495151 -0.7698437 0.4530749 0.4045723 -0.7928336 0.4557808 0.3615788 -0.8130621 0.4562793 0.4032546 -0.7861185 0.4684051 0.4032577 -0.786117 0.4684048 0.5242232 -0.7193512 0.4557673 0.2716142 -0.8304599 0.4863765 0.2877436 -0.8264153 0.4839848 0.2739288 -0.8303603 0.4852473 0.4032937 -0.7861021 0.4683989 0.4032205 -0.7861334 0.4684096 0.515609 -0.8374252 -0.181291 0.5156405 -0.8373891 -0.1813678 0.07892841 -0.8481816 0.5237923 0.07887345 -0.848168 0.5238227 0.07894974 -0.8481859 0.523782 0.1081576 -0.8519164 0.5123869 0.1248466 -0.8527354 0.5072038 0.2723602 -0.8302782 0.4862696 0.2228687 -0.8424538 0.490511 0.1926078 -0.8498942 0.4904917 0.1247921 -0.8527351 0.5072178 0.1704377 -0.8493356 0.49958 0.1704378 -0.8493355 0.49958 0.178116 -0.8466941 0.5013818 0.302389 -0.7972885 0.5223906 0.3044213 -0.7961723 0.5229125 -0.08702826 -0.8542737 0.5124866 -0.08597397 -0.8544471 0.5123755 0.0169807 -0.8654602 0.50069 -0.03357702 -0.8579177 0.5126888 0.003751337 -0.8583815 0.5129984 -0.03134423 -0.8579678 0.5127462 0.01602172 -0.8582696 0.5129491 0.1088403 -0.8848709 0.4529429 -0.1855779 -0.8450046 0.5015258 -0.1855777 -0.8450046 0.5015257 -0.1197279 -0.8557372 0.5033677 -0.3104764 -0.7937916 0.5229717 -0.3113203 -0.7933413 0.5231531 -0.2024152 -0.8385878 0.5057654 -0.2022967 -0.8386303 0.5057424 -0.08635139 -0.8543887 0.5124094 -0.05467331 -0.8607801 0.5060321 -0.09660845 -0.857881 0.5046851 -0.2489771 -0.8359687 0.4890468 -0.1960195 -0.848654 0.4912868 -0.2128072 -0.840038 0.4990484 -0.1341816 -0.8627285 0.4875395 -0.1959733 -0.8486657 0.491285 -0.41027 -0.7843047 0.4653437 -0.294977 -0.8243356 0.4831764 -0.29492 -0.8243507 0.4831853 -0.2956406 -0.8241587 0.4830724 -0.2949922 -0.8243551 0.4831339 -0.4102366 -0.7843185 0.46535 -0.4103046 -0.7842898 0.4653382 -0.3833377 -0.8030382 0.4562693 -0.5292518 -0.7188422 0.4507312 -0.4102827 -0.7842987 0.4653425 -0.4131008 -0.7796037 0.4707077 -0.3702512 -0.7880964 0.49175 -0.5954136 -0.7258704 0.344376 -0.7176699 -0.5996567 0.3540649 -0.7176908 -0.5996387 0.3540528 -0.6242385 -0.6690374 0.4033799 -0.6242212 -0.6690481 0.4033889 -0.781738 -0.5460633 0.3011652 -0.684098 -0.6306321 0.3664875 -0.4263736 -0.7820375 0.454558 -0.4493618 -0.7699638 0.453023 -0.5174556 -0.7375189 0.4339417 -0.5815981 -0.7007554 0.4131413 -0.5815805 -0.700766 0.4131478 -0.9357379 -0.2989259 0.1871843 -0.8745144 -0.4174672 0.2468717 -0.8745129 -0.4174696 0.246873 -0.8022906 -0.5148407 0.3021073 -0.8022785 -0.5148546 0.3021159 -0.7777386 -0.5415046 0.3192106 -0.8030303 -0.5132924 0.302776 -0.8030056 -0.5133212 0.302793 -0.9357447 -0.2989097 0.187176 -0.8564602 -0.4465476 0.2589812 -0.8564761 -0.4465239 0.2589691 -0.9364275 -0.30394 0.175283 -0.9655609 -0.2211058 0.1371284 -0.9766687 -0.179304 0.1181871 -0.9766664 -0.1793141 0.1181912 -0.9766671 -0.1793113 0.1181899 -0.9563132 -0.250196 0.1512187 -0.9563124 -0.2501983 0.1512198 -0.9476779 -0.2740868 0.1636549 -0.8564673 -0.4465368 0.2589758 -0.9135614 -0.3505888 0.2061389 -0.9290084 -0.319006 0.1875596 -0.9426127 -0.2870417 0.170553 -0.9851364 -0.1377346 0.1026424 -0.9188048 -0.3536177 0.1753638 -0.9546574 -0.2620456 0.1412842 -0.9546692 -0.2620104 0.1412708 -0.9546733 -0.2619982 0.1412652 -0.9756789 -0.190648 0.1081851 -0.9451747 -0.2849362 0.1595497 -0.9569132 -0.2568318 0.1354788 -0.9671699 -0.2345727 0.09776544 -0.9660485 -0.1167308 0.2304868 -0.950558 -0.2485383 0.1861941 -0.9817569 -0.1642509 0.09578615 -0.9871603 -0.1376287 0.08107256 -0.9821104 -0.160135 0.0990749 -0.9756781 -0.1906511 0.1081867 -0.9860261 -0.1440253 0.0837208 -0.9860262 -0.1440253 0.0837208 -0.9910023 -0.1154538 0.06771183 -0.9910023 -0.1154538 0.06771183 -0.9910036 -0.1154451 0.06770682 -0.9980148 -0.05493509 0.03079915 -0.9865446 -0.1415691 0.08177882 -0.9975334 -0.06223261 0.03246891 -0.9982997 -0.05024236 0.02955418 -0.9986516 -0.0444957 0.02674025 -0.9926173 -0.1045407 0.06149917 -0.9926235 -0.1044971 0.06147378 -0.9980975 -0.05313891 0.03126335 -0.9953873 -0.08269 0.04864603 -0.9973654 -0.06626206 0.02952367 -0.4716407 -0.7706385 0.4285691 -0.2897732 -0.8198134 0.4939002 -0.3384489 -0.8104203 0.4781959 -0.2777355 -0.8274042 0.4881242 -0.2771292 -0.8275551 0.4882128 -0.2296745 -0.8370324 0.4966149 -0.1676488 -0.8427515 0.5115308 -0.167654 -0.8427513 0.5115294 -0.06446593 -0.8579354 0.5096969 -0.2055467 -0.8537955 0.4783134 -0.08814692 -0.8501426 0.5191221 -0.2038861 -0.8445537 0.495136 -0.344133 -0.8294218 0.4400362 0.2250742 -0.8382854 0.4966076 0.2751041 -0.8285973 0.4875903 0.3491341 -0.8076154 0.4752503 0.2923927 -0.8189345 0.4938145 0.2903216 -0.8192873 0.494451 -0.02186292 -0.8613632 0.5075191 -0.06814211 -0.8595653 0.5064623 -0.06444442 -0.859777 0.506587 0 -0.8619188 0.5070464 0.07537871 -0.8598753 0.5049084 0 -0.8514108 0.5244995 0.001728832 -0.8516626 0.5240877 0.005848526 -0.8522427 0.5231139 0.02584362 -0.854722 0.5184422 0.216821 -0.8538239 0.4732583 0.08578848 -0.8500373 0.5196893 0.2148907 -0.8436052 0.4920898 0.3556692 -0.8285369 0.4324653 0.1637879 -0.84342 0.5116798 0.163798 -0.8434198 0.511677 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 3.64303e-5 -1 -1.30327e-4 -6.11332e-6 -1 9.35431e-7 2.37239e-7 -1 2.22058e-7 4.76296e-6 -1 -2.19025e-7 0 -1 0 0 -1 0 0 -1 0 -9.09025e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -9.74926e-6 -1 5.09068e-6 -1.39767e-5 -1 6.75917e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 2.30003e-7 -1 0 -4.279e-5 -1 -1.13458e-6 -1.21538e-5 -1 0 -1.54556e-5 -1 3.62795e-5 -1.2653e-5 -1 2.93081e-5 0 -1 0 1.87009e-5 -1 -5.4304e-6 1.32861e-5 -1 -3.72012e-6 3.24968e-6 -1 -7.94118e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.06783217 -0.9881218 0.1378921 -0.8905193 -0.204984 0.4061489 -0.4030454 -0.9090104 0.1060864 -0.614673 -0.7778151 0.1310747 -0.5014328 -0.8568133 0.1201501 -0.3838491 -0.9196926 0.0826174 -0.3838456 -0.9196941 0.08261615 -0.3840905 -0.9195868 0.08267199 -0.619649 -0.7782743 0.1016077 -0.6196385 -0.7782832 0.1016048 -0.6196388 -0.7782828 0.1016049 -0.7899492 -0.5973765 0.1382805 -0.8882994 -0.4346262 0.1484054 -0.9112979 -0.3769648 0.165631 -0.911295 -0.3769713 0.1656318 -0.885415 -0.4277129 0.181939 -0.7899568 -0.5973671 0.1382778 -0.7899615 -0.5973607 0.1382787 -0.8882977 -0.4346265 0.1484152 -0.8530978 -0.4709507 0.2245656 -0.8572158 -0.4596151 0.2322394 -0.9234509 -0.2073601 0.3228628 -0.7826623 -0.5534577 0.2848233 -0.8572153 -0.4596151 0.2322412 -0.7120812 -0.6639859 0.228174 -0.6548308 -0.6936522 0.3000721 -0.580129 -0.7339683 0.3531869 -0.5801392 -0.7339676 0.3531715 -0.5797522 -0.7347828 0.3521103 -0.6530963 -0.6984658 0.2925932 -0.6531052 -0.6984653 0.2925746 -0.4427766 -0.7265876 0.5253755 -0.442786 -0.7265884 0.5253666 -0.446685 -0.8123988 0.3748075 -0.497545 -0.7664713 0.4061658 -0.4975613 -0.7664623 0.406163 -0.2524425 -0.8908944 0.3775974 -0.2529078 -0.8908845 0.3773097 -0.2557843 -0.8924137 0.3717154 -0.2528949 -0.8908832 0.3773213 -0.1874364 -0.9053646 0.3810284 -0.1624347 -0.8983459 0.4081539 -0.162434 -0.898346 0.4081542 -0.1122711 -0.9137496 0.3904571 -0.1021209 -0.9138238 0.3930616 -0.009096622 -0.9997659 0.01963168 -0.1241925 -0.9855629 0.1150735 -0.06911802 -0.9849612 0.1583483 -0.1129863 -0.9127167 0.3926606 -0.1120554 -0.9881101 0.1052711 -0.1051555 -0.9873621 0.1185681 -0.09159904 -0.9881113 0.1234735 -0.08915424 -0.9875552 0.1295623 -0.06565046 -0.9877144 0.1418102 -0.06570076 -0.9877154 0.1417807 -0.1120622 -0.98811 0.1052643 -0.1236805 -0.9868898 0.1036897 -0.1256494 -0.9882199 0.08737152 -0.1448287 -0.9872298 0.06634795 -0.1347512 -0.9883733 0.07043051 -0.1302224 -0.9883282 0.07905405 -0.1485344 -0.9858554 0.07763051 -0.1256494 -0.9882198 0.08737152 -0.1500099 -0.9878557 0.04047203 -0.1500089 -0.9878558 0.0404753 -0.1504735 -0.9872142 0.05259114 -0.1438655 -0.9880482 0.05534929 -0.143866 -0.9880481 0.05534803 -0.3838563 -0.9196894 0.08261895 -0.1467115 -0.9884136 0.03891128 -0.151812 -0.9876073 0.03981053 -0.1472483 -0.9884521 0.03578102 -0.01291841 -0.9999137 0.002412736 -0.789949 -0.5973768 0.1382806 -0.7136862 -0.6806688 0.1653541 -0.7086633 -0.6804388 0.1865453 -0.7086827 -0.6804218 0.1865339 -0.6918115 -0.6803624 0.2418755 -0.6918488 -0.6803309 0.2418578 -0.6659198 -0.6801978 0.3064012 -0.7120946 -0.6639785 0.2281535 -0.3791174 -0.9187593 0.1102329 -0.4504873 -0.8855663 0.1132852 -0.4383836 -0.8856263 0.1532509 -0.4384322 -0.8856052 0.153234 -0.4223141 -0.8855505 0.1935228 -0.4223926 -0.8855172 0.1935036 -0.3972784 -0.8854101 0.2412855 -0.3974305 -0.8853467 0.2412679 -0.3564956 -0.8851166 0.2991309 -0.3568212 -0.88498 0.2991473 -0.2991201 -0.8851517 0.3564178 -0.3132992 -0.8815048 0.3532603 -0.3337587 -0.8825345 0.3312674 -0.3337199 -0.8825371 0.3312997 -0.9944299 -0.1049468 -0.00975281 -0.9486987 -0.3046261 0.08469718 -0.9020021 -0.431396 0.01702076 -0.9020029 -0.4313943 0.01702183 -0.9491068 -0.3073958 0.06858652 -0.9635241 -0.2649139 0.0379728 -0.9731504 -0.2254975 0.04614204 -0.9682228 -0.2376245 0.07796901 -0.9682255 -0.2376174 0.07795608 -0.9781493 -0.195549 0.07060098 -0.9944302 -0.1049451 -0.00975579 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.5697836 -0.8216499 -0.01543343 -0.2181239 -0.974781 0.04715877 -0.3445591 -0.9068721 0.2426147 -0.3478806 -0.9076653 0.2347823 -0.304488 -0.918893 0.2508435 -0.3531411 -0.9095648 0.219051 -0.344367 -0.9068145 0.2431024 -0.3444693 -0.9068484 0.2428311 -0.4401198 -0.8869467 0.1400721 -0.3604757 -0.9087237 0.2104246 -0.3604679 -0.9087235 0.2104388 -0.5499003 -0.8346579 0.03091996 -0.5000185 -0.85116 0.1597123 -0.5109359 -0.8569807 0.06729584 -0.4285371 -0.8860835 0.1766691 -0.4284425 -0.8860731 0.1769506 -0.701288 -0.7091495 0.07281368 -0.7012909 -0.7091493 0.07279032 -0.7016826 -0.7093089 0.0672487 -0.6580872 -0.7528918 -0.008674383 -0.5782262 -0.8073994 0.1173054 -0.5782277 -0.8073999 0.1172947 -0.05162829 -0.9986461 0.006376564 -0.06312692 -0.9980039 0.001795828 -0.06312692 -0.9980039 0.001795828 -0.04568213 -0.9988654 0.01345431 -0.07024437 -0.9970094 0.03221714 -0.1227388 -0.9903255 0.06473577 -0.1227329 -0.9903265 0.06473237 -0.009765803 -0.9999217 0.007816195 -0.02017766 -0.9997328 0.01127946 -0.01749205 -0.9997137 0.01632839 -0.03112673 -0.999364 0.01740092 -0.04568243 -0.9988654 0.01345348 -0.2182819 -0.9755008 0.02740824 -0.2181335 -0.974779 0.04715585 -0.2497245 -0.9677932 0.03184366 -0.252086 -0.9665463 -0.04733854 -0.1343599 -0.9884866 0.06958329 -0.1197717 -0.9926913 0.01479226 -0.1165834 -0.9922133 0.0438295 -0.07912927 -0.9968164 0.009773552 -0.07912957 -0.9968164 0.009771943 -0.7887772 -0.6134596 0.03870356 -0.7459284 -0.6656417 -0.02262431 -0.7885911 -0.6133643 -0.04368525 -0.5694246 -0.8211296 0.03875207 -0.3387728 -0.9168475 0.211243 -0.1293936 -0.9849086 0.1149448 -0.1355692 -0.9853297 0.1036654 -0.2116185 -0.9759247 0.05280774 -0.1924623 -0.9748331 0.1125099 -0.287927 -0.9575134 0.01631814 -0.2707019 -0.9565657 0.1081784 -0.3629233 -0.9317642 -0.01010936 -0.3506425 -0.9310645 0.1008402 -0.4975602 -0.8664844 -0.04048329 -0.4949625 -0.8673929 0.05139756 -0.5697846 -0.8216491 -0.01543378 -0.3908503 -0.919604 0.03955471 -0.3907201 -0.9196896 0.03884261 -0.3907152 -0.9196918 0.03883987 -0.3907124 -0.9196932 0.03883415 -0.1636382 -0.9718987 -0.16922 -0.3741024 -0.9171036 0.1377258 -0.4103977 -0.8981286 0.1579197 -0.1188995 -0.7062043 -0.6979529 -0.1769472 -0.9689156 -0.1728936 -0.177006 -0.968904 -0.1728984 -0.9921268 -0.1208057 -0.03302204 -0.9985995 -0.02308541 0.04760402 -0.9930485 -0.1171145 0.01178723 -0.9875346 -0.1573852 0.002298235 -0.9755641 -0.2196989 -0.002676665 -0.9599646 -0.279668 0.01593232 -0.9599631 -0.2796729 0.01593261 -0.9562727 -0.2917596 0.02046948 -0.9755638 -0.2196998 -0.002676665 -0.9988925 0.04631203 0.008311033 -0.9985998 0.05179506 0.01075255 -0.9994689 -0.02550476 -0.02028417 -0.9032726 0.4233746 0.06965929 -0.933836 0.3556059 0.03866368 -0.9825936 0.1833052 -0.03015089 -0.9608556 0.2733088 0.04537278 -0.9608557 0.2733085 0.04537266 -0.9790439 0.2023671 0.02281761 -0.9915826 0.1294597 0.002020776 -0.9915828 0.1294583 0.002020776 -0.9600028 0.2795431 -0.01582014 -0.960003 0.2795423 -0.01582038 -0.9600025 0.2795444 -0.01581978 -0.8644245 0.5027613 -0.00118488 -0.9248697 0.3802822 -0.001188576 -0.8739063 0.4843896 -0.04067689 -0.8644243 0.5027616 -0.00118494 -0.7644602 0.64428 -0.02244788 -0.7644599 0.6442806 -0.02244806 -0.7771168 0.6293526 0.002183258 -0.7771235 0.6293445 0.002183496 -0.8461701 0.5324369 0.0225203 -0.8978373 0.438292 0.04228854 -0.8978406 0.4382849 0.04229032 -0.684818 0.7284182 -0.02076274 -0.6266484 0.7792702 -0.007065892 -0.5320667 0.8466985 0.002589523 -0.5320693 0.8466968 0.002589344 -0.4274048 0.9040363 -0.006606578 -0.5455376 0.837894 0.01795107 -0.6219403 0.7830644 -6.80637e-4 -0.6780891 0.7349795 -6.78306e-4 -0.622371 0.7827224 7.72648e-5 -0.7046697 0.7095355 -8.74763e-6 -0.1608138 0.9867973 0.01923567 -0.1645852 0.9862089 0.01743012 -0.5040952 0.8501486 -0.1521037 -0.1712386 0.9848092 0.02878129 -0.1812981 0.9831416 0.02374041 -0.3798658 0.9233455 -0.05599099 -0.5772153 0.799472 -0.1663342 -0.2705082 0.962639 0.01230669 -0.2705109 0.9626383 0.01230561 -0.3522289 0.9359042 0.004265069 -0.4419841 0.897019 -0.002633631 -0.4233621 0.9059568 -0.002631902 -0.441259 0.8973715 -0.00385642 -0.4412565 0.8973727 -0.003856718 -0.9599639 -0.2796702 0.01593232 -0.955217 -0.2957324 0.01013875 -0.8923606 -0.4510778 -0.01487737 -0.920133 -0.3913531 0.01407009 -0.9122332 -0.409583 0.008502244 -0.8984004 -0.4391691 0.002736508 -0.8984017 -0.439166 0.002736866 -0.8771386 -0.4802374 1.05298e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.09491479 -0.00305742 -0.9954807 -0.5409931 -0.004862487 -0.841013 -0.7813409 0.003680646 -0.6240935 -0.7070958 -0.004752933 -0.7071019 -0.54948 0.0826776 -0.8314061 -0.6757109 0.0371266 -0.7362312 -0.8689906 -6.63241e-4 -0.4948284 -0.8691402 -6.64828e-4 -0.4945656 -0.9659261 -6.42815e-4 -0.2588173 -0.8800741 0.08852058 -0.4665123 -0.9404243 0.03842931 -0.3378244 0.08474004 -0.003057599 -0.9963984 -0.07949721 0.00186479 -0.9968334 -0.2587714 0.02148419 -0.9656997 -0.2425616 0.02723085 -0.9697538 -0.3977141 0.004725217 -0.9174973 0.4012866 -7.65825e-4 -0.9159522 0.2587223 0.0290054 -0.9655162 0.2480214 0.02621179 -0.9684 0.08482122 -0.00306034 -0.9963915 0.8989402 -0.002989768 -0.4380611 0.898325 -0.002988338 -0.4393214 0.8063488 0.002891302 -0.5914333 0.6874367 0.02844339 -0.7256871 0.7069731 0.01921457 -0.7069793 0.5512045 3.78297e-4 -0.8343701 0.4022562 -7.65827e-4 -0.9155268 0.8989521 -0.002988338 -0.4380368 0.9656751 0.02280431 -0.2587502 0.9632233 0.02504909 -0.2675321 0.8968107 -0.002736508 0.4424058 0.9582821 0.01479822 0.2854405 0.9657356 0.01980096 0.2587714 0.9940322 0 0.1090869 0.9936402 0 -0.1126014 0.5544232 5.95633e-4 0.8322347 0.6730956 0.007826268 0.7395141 0.7840743 0.03476637 0.6196925 0.7070971 0.00679177 0.707084 0.8967837 -0.002737343 0.4424607 0.89622 -0.002737343 0.4436015 0.05885124 4.79931e-4 0.9982666 -0.07846319 -9.18571e-4 0.9969165 0.1945 0.006005108 0.9808841 0.305142 0.02089601 0.9520775 0.2587882 0.01388734 0.9658342 0.4272588 -0.001098155 0.9041286 0.4271793 -0.001098155 0.9041663 -0.3265648 0.02187252 0.9449217 -0.258805 0.007956624 0.9658969 -0.2054049 0.009089529 0.9786348 -0.07838404 -9.19428e-4 0.9969229 -0.09789055 -9.18391e-4 0.9951968 -0.5990115 5.52722e-4 0.8007402 -0.4689778 -1.99412e-4 0.88321 -0.4693831 -1.99412e-4 0.8829946 -0.8562236 -0.003491282 0.5165936 -0.8568177 -0.003489673 0.5156077 -0.7071092 -0.003387153 0.7070962 -0.8348124 0.05233567 0.5480414 -0.7292709 0.01959174 0.6839444 -0.979725 0.01364195 -0.1998821 -0.9964048 0 -0.08472019 -0.9659249 0 0.2588222 -0.9888616 0.03953701 0.14349 -0.9433013 0.007185339 0.3318602 0.4688849 0.8818953 0.04906684 0.4688662 0.881906 0.04905503 0.468917 0.8818756 0.04911464 0.5673341 0.8230941 0.02546066 0.5673396 0.8230904 0.02545696 0.6280626 0.7779004 0.02021044 0.8070184 0.4440832 0.3892449 0.757739 0.5637625 0.3286389 0.8292468 0.4505569 0.3306785 0.7697783 0.557722 0.3104634 0.8214016 0.5022804 0.2702109 0.8070228 0.5881546 0.05280542 0.6280604 0.777902 0.0202139 0.6672881 0.7186818 0.1955071 0.8825233 0.4376595 -0.1720664 0.882523 0.4376531 -0.1720838 0.5673713 0.8230699 0.02541017 0.6672785 0.7186923 0.1955013 0.6525968 0.7469986 -0.1269268 0.5673835 0.8230621 0.02539116 0.4688819 0.8818976 0.0490548 0.2497694 0.9320418 -0.2625133 0.2497547 0.9320321 -0.2625621 0.3034673 0.7282294 0.6144832 0.3034861 0.7281638 0.6145516 0.1212551 0.8602593 0.4952285 0.1141309 0.8594243 0.4983614 0.1207444 0.8563225 0.5021278 0.004999101 0.5887003 0.808336 0.8583942 0.5129908 1.42056e-6 0.8081489 0.5889752 0.001883983 0.777737 0.6285751 -0.004317343 0.6281873 0.7780591 0.002195119 0.7776917 0.6285294 0.01209878 0.5961139 0.8028874 0.004468441 0.6281846 0.7780515 0.004477441 0.5961181 0.8028962 -9.49849e-4 0.3850328 0.9229024 9.67345e-4 0.3751596 0.9269602 -3.31847e-4 0.3850293 0.9229042 -3.31335e-4 0.3751556 0.9269615 -8.16339e-4 0.139365 0.9902407 7.84791e-4 0.375163 0.9269231 0.00813657 0.1393646 0.9902408 8.15185e-4 0.1281712 0.9917515 -0.001064598 0.006358742 0.9999797 0 -0.2183669 -0.9758667 1.85209e-7 -0.1660203 -0.9860785 -0.009302556 -0.2183666 -0.9758206 -0.009500324 -0.1660206 -0.9860484 -0.01207411 -0.218348 -0.975796 -0.01209127 -0.415611 -0.9095374 0.003035783 -0.5698373 -0.8217273 -0.007057368 -0.5075855 -0.8615726 -0.007037997 -0.5698345 -0.8217211 -0.007941246 -0.6188017 -0.7855471 -5.10419e-4 -0.5698527 -0.8217468 -5.27969e-4 -0.6188039 -0.7855438 0.001649618 -0.789358 -0.6139307 -0.001806437 -0.7957454 -0.6056286 -0.001829504 -0.7893649 -0.6139225 -0.001511394 -0.7957453 -0.6056315 2.97149e-6 -0.6326785 -0.7744129 -0.001580655 -0.6326668 -0.7744225 -0.001568913 -0.7457234 -0.585567 0.3178175 -0.6166776 -0.7828266 0.08301436 -0.6166651 -0.7828348 0.08302789 -0.465675 -0.7899813 0.3988437 -0.7954781 -0.6054334 0.02578777 -0.8264132 -0.5620133 0.03438782 -0.7944784 -0.6046704 0.05637335 -0.7996023 -0.5965079 0.0693888 -0.7995998 -0.5965112 0.06938683 -0.8873435 -0.456282 0.06654554 -0.9115859 -0.3769848 0.1639928 -0.8573388 -0.4934886 0.1464217 -0.897819 -0.375596 0.2298885 -0.6404872 -0.767768 -0.01755976 -0.6393734 -0.7559177 -0.1406772 -0.7457239 -0.5855661 0.3178178 -0.6326714 -0.7744189 -0.001576542 -0.514137 -0.8568152 0.03912305 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 1 0 2 0 2 1 1 1 3 1 4 2 5 2 1 2 1 3 5 3 6 3 7 4 8 4 9 4 9 5 8 5 10 5 11 6 12 6 13 6 14 7 15 7 16 7 12 8 11 8 1 8 1 9 11 9 17 9 1 10 17 10 4 10 6 11 18 11 1 11 1 12 18 12 19 12 1 13 19 13 3 13 0 14 20 14 1 14 1 15 20 15 9 15 1 16 9 16 21 16 21 17 9 17 10 17 13 18 22 18 11 18 11 19 22 19 14 19 11 20 14 20 23 20 23 21 14 21 16 21 7 22 24 22 8 22 8 23 24 23 25 23 8 24 25 24 26 24 27 25 28 25 29 25 27 26 29 26 30 26 28 27 27 27 31 27 31 28 27 28 32 28 31 29 32 29 33 29 33 30 32 30 34 30 34 31 32 31 35 31 34 32 35 32 36 32 37 33 38 33 39 33 39 34 38 34 40 34 39 35 40 35 35 35 35 36 40 36 41 36 35 37 41 37 36 37 37 38 39 38 42 38 42 39 39 39 43 39 42 40 43 40 44 40 44 41 43 41 45 41 45 42 43 42 46 42 45 43 46 43 47 43 47 44 46 44 48 44 48 45 46 45 49 45 48 46 49 46 50 46 51 47 52 47 49 47 49 48 52 48 53 48 49 49 53 49 50 49 54 50 55 50 51 50 51 51 55 51 56 51 51 52 56 52 52 52 57 53 58 53 54 53 54 54 58 54 59 54 54 55 59 55 55 55 60 56 61 56 57 56 57 57 61 57 62 57 57 58 62 58 58 58 63 59 64 59 65 59 65 60 64 60 66 60 65 61 66 61 60 61 60 62 66 62 67 62 60 63 67 63 61 63 63 64 65 64 68 64 68 65 65 65 69 65 68 66 69 66 70 66 70 67 69 67 71 67 71 68 69 68 72 68 71 69 72 69 73 69 74 70 75 70 76 70 76 71 75 71 77 71 76 72 77 72 72 72 72 73 77 73 78 73 72 74 78 74 73 74 74 75 76 75 79 75 79 76 76 76 80 76 79 77 80 77 81 77 81 78 80 78 82 78 82 79 80 79 83 79 82 80 83 80 84 80 84 81 83 81 85 81 85 82 83 82 86 82 85 83 86 83 87 83 87 84 86 84 88 84 88 85 86 85 89 85 88 86 89 86 90 86 90 87 89 87 91 87 91 88 89 88 92 88 91 89 92 89 93 89 94 90 95 90 92 90 92 91 95 91 96 91 92 92 96 92 93 92 97 93 98 93 94 93 94 94 98 94 99 94 94 95 99 95 95 95 100 96 101 96 102 96 102 97 101 97 103 97 102 98 103 98 97 98 97 99 103 99 104 99 97 100 104 100 98 100 100 101 102 101 105 101 105 102 102 102 106 102 105 103 106 103 107 103 108 104 109 104 106 104 106 105 109 105 110 105 106 106 110 106 107 106 111 107 112 107 108 107 108 108 112 108 113 108 108 109 113 109 109 109 29 110 114 110 30 110 30 111 114 111 115 111 30 112 115 112 111 112 111 113 115 113 116 113 111 114 116 114 112 114 117 115 118 115 119 115 120 116 121 116 122 116 123 117 124 117 125 117 126 118 127 118 128 118 129 119 130 119 131 119 132 120 133 120 134 120 135 121 136 121 137 121 138 122 139 122 140 122 141 123 142 123 143 123 116 124 115 124 144 124 107 125 110 125 145 125 96 126 95 126 146 126 90 127 91 127 147 127 81 128 82 128 148 128 74 129 79 129 149 129 78 130 77 130 150 130 71 131 73 131 151 131 66 132 64 132 152 132 59 133 58 133 153 133 53 134 52 134 154 134 48 135 50 135 155 135 44 136 45 136 156 136 37 137 42 137 157 137 41 138 40 138 158 138 33 139 34 139 159 139 31 140 142 140 28 140 28 141 142 141 141 141 28 142 141 142 29 142 29 143 141 143 114 143 34 144 36 144 160 144 160 145 36 145 41 145 40 146 38 146 161 146 61 147 67 147 162 147 68 148 70 148 163 148 87 149 139 149 85 149 85 150 139 150 138 150 85 151 138 151 84 151 164 152 88 152 90 152 91 153 93 153 165 153 98 154 104 154 135 154 135 155 104 155 103 155 135 156 103 156 136 156 136 157 103 157 101 157 136 158 101 158 100 158 166 159 105 159 107 159 110 160 109 160 167 160 167 161 109 161 113 161 113 162 112 162 168 162 168 163 112 163 116 163 144 164 115 164 169 164 170 165 143 165 171 165 171 166 143 166 142 166 171 167 142 167 159 167 159 168 142 168 31 168 159 169 31 169 33 169 172 170 140 170 173 170 173 171 140 171 139 171 173 172 139 172 164 172 164 173 139 173 87 173 164 174 87 174 88 174 174 175 175 175 165 175 176 176 137 176 177 176 177 177 137 177 136 177 177 178 136 178 166 178 166 179 136 179 100 179 166 180 100 180 105 180 178 181 144 181 179 181 179 182 144 182 169 182 179 183 169 183 180 183 181 184 182 184 183 184 184 185 185 185 186 185 186 186 185 186 181 186 186 187 181 187 187 187 187 188 181 188 183 188 187 189 183 189 161 189 45 190 47 190 156 190 156 191 47 191 188 191 156 192 188 192 189 192 189 193 188 193 190 193 189 194 190 194 191 194 191 195 190 195 192 195 56 196 55 196 193 196 193 197 55 197 194 197 193 198 194 198 195 198 195 199 194 199 196 199 195 200 196 200 197 200 197 201 196 201 198 201 62 202 61 202 199 202 199 203 61 203 162 203 199 204 162 204 200 204 200 205 162 205 201 205 200 206 201 206 202 206 202 207 201 207 203 207 70 208 71 208 163 208 163 209 71 209 151 209 163 210 151 210 204 210 204 211 151 211 205 211 204 212 205 212 206 212 206 213 205 213 207 213 75 214 74 214 208 214 208 215 74 215 149 215 208 216 149 216 209 216 209 217 149 217 210 217 209 218 210 218 211 218 211 219 210 219 212 219 213 220 175 220 214 220 214 221 175 221 174 221 214 222 174 222 215 222 93 223 96 223 165 223 165 224 96 224 146 224 165 225 146 225 174 225 174 226 146 226 216 226 174 227 216 227 215 227 215 228 216 228 217 228 215 229 217 229 218 229 218 230 217 230 219 230 220 231 178 231 221 231 221 232 178 232 179 232 221 233 179 233 222 233 222 234 179 234 180 234 222 235 180 235 223 235 224 236 225 236 170 236 170 237 225 237 223 237 170 238 223 238 143 238 143 239 223 239 180 239 143 240 180 240 141 240 141 241 180 241 169 241 141 242 169 242 114 242 114 243 169 243 115 243 34 244 160 244 159 244 159 245 160 245 226 245 159 246 226 246 171 246 171 247 226 247 134 247 171 248 134 248 170 248 170 249 134 249 133 249 170 250 133 250 224 250 41 251 158 251 160 251 160 252 158 252 227 252 160 253 227 253 226 253 226 254 227 254 228 254 226 255 228 255 134 255 134 256 228 256 229 256 134 257 229 257 132 257 40 258 161 258 158 258 158 259 161 259 183 259 158 260 183 260 227 260 227 261 183 261 182 261 227 262 182 262 228 262 228 263 182 263 230 263 228 264 230 264 229 264 185 265 231 265 181 265 181 266 231 266 232 266 181 267 232 267 182 267 182 268 232 268 233 268 182 269 233 269 230 269 38 270 37 270 161 270 161 271 37 271 157 271 161 272 157 272 187 272 187 273 157 273 234 273 187 274 234 274 186 274 186 275 234 275 131 275 186 276 131 276 184 276 184 277 131 277 130 277 42 278 44 278 157 278 157 279 44 279 156 279 157 280 156 280 234 280 234 281 156 281 189 281 234 282 189 282 131 282 131 283 189 283 191 283 131 284 191 284 129 284 235 285 236 285 237 285 237 286 236 286 192 286 237 287 192 287 238 287 238 288 192 288 190 288 238 289 190 289 155 289 155 290 190 290 188 290 155 291 188 291 48 291 48 292 188 292 47 292 236 293 239 293 192 293 192 294 239 294 240 294 192 295 240 295 191 295 191 296 240 296 241 296 191 297 241 297 129 297 127 298 235 298 128 298 128 299 235 299 237 299 128 300 237 300 242 300 242 301 237 301 238 301 242 302 238 302 154 302 154 303 238 303 155 303 154 304 155 304 53 304 53 305 155 305 50 305 52 306 56 306 154 306 154 307 56 307 193 307 154 308 193 308 242 308 242 309 193 309 195 309 242 310 195 310 128 310 128 311 195 311 197 311 128 312 197 312 126 312 243 313 244 313 245 313 245 314 244 314 198 314 245 315 198 315 246 315 246 316 198 316 196 316 246 317 196 317 153 317 153 318 196 318 194 318 153 319 194 319 59 319 59 320 194 320 55 320 244 321 247 321 198 321 198 322 247 322 248 322 198 323 248 323 197 323 197 324 248 324 249 324 197 325 249 325 126 325 58 326 62 326 153 326 153 327 62 327 199 327 153 328 199 328 246 328 246 329 199 329 200 329 246 330 200 330 245 330 245 331 200 331 202 331 245 332 202 332 243 332 250 333 251 333 252 333 252 334 251 334 203 334 252 335 203 335 253 335 253 336 203 336 201 336 253 337 201 337 152 337 152 338 201 338 162 338 152 339 162 339 66 339 66 340 162 340 67 340 251 341 254 341 203 341 203 342 254 342 255 342 203 343 255 343 202 343 202 344 255 344 256 344 202 345 256 345 243 345 64 346 63 346 152 346 152 347 63 347 257 347 152 348 257 348 253 348 253 349 257 349 258 349 253 350 258 350 252 350 252 351 258 351 125 351 252 352 125 352 250 352 250 353 125 353 124 353 63 354 68 354 257 354 257 355 68 355 163 355 257 356 163 356 258 356 258 357 163 357 204 357 258 358 204 358 125 358 125 359 204 359 206 359 125 360 206 360 123 360 259 361 260 361 261 361 261 362 260 362 207 362 261 363 207 363 262 363 262 364 207 364 205 364 262 365 205 365 150 365 150 366 205 366 151 366 150 367 151 367 78 367 78 368 151 368 73 368 260 369 263 369 207 369 207 370 263 370 264 370 207 371 264 371 206 371 206 372 264 372 265 372 206 373 265 373 123 373 77 374 75 374 150 374 150 375 75 375 208 375 150 376 208 376 262 376 262 377 208 377 209 377 262 378 209 378 261 378 261 379 209 379 211 379 261 380 211 380 259 380 266 381 267 381 268 381 268 382 267 382 212 382 268 383 212 383 269 383 269 384 212 384 210 384 269 385 210 385 148 385 148 386 210 386 149 386 148 387 149 387 81 387 81 388 149 388 79 388 267 389 270 389 212 389 212 390 270 390 271 390 212 391 271 391 211 391 211 392 271 392 272 392 211 393 272 393 259 393 82 394 84 394 148 394 148 395 84 395 138 395 148 396 138 396 269 396 269 397 138 397 140 397 269 398 140 398 268 398 268 399 140 399 172 399 268 400 172 400 266 400 266 401 172 401 273 401 274 402 275 402 276 402 90 403 147 403 164 403 164 404 147 404 277 404 164 405 277 405 173 405 173 406 277 406 274 406 173 407 274 407 172 407 172 408 274 408 276 408 172 409 276 409 273 409 91 410 165 410 147 410 147 411 165 411 175 411 147 412 175 412 277 412 277 413 175 413 213 413 277 414 213 414 274 414 274 415 213 415 278 415 274 416 278 416 275 416 218 417 279 417 215 417 215 418 279 418 280 418 215 419 280 419 214 419 214 420 280 420 281 420 214 421 281 421 213 421 213 422 281 422 282 422 213 423 282 423 278 423 121 424 219 424 122 424 122 425 219 425 217 425 122 426 217 426 283 426 283 427 217 427 216 427 283 428 216 428 284 428 284 429 216 429 146 429 284 430 146 430 99 430 99 431 146 431 95 431 99 432 98 432 284 432 284 433 98 433 135 433 284 434 135 434 283 434 283 435 135 435 137 435 283 436 137 436 122 436 122 437 137 437 176 437 122 438 176 438 120 438 120 439 176 439 285 439 286 440 287 440 288 440 107 441 145 441 166 441 166 442 145 442 289 442 166 443 289 443 177 443 177 444 289 444 286 444 177 445 286 445 176 445 176 446 286 446 288 446 176 447 288 447 285 447 110 448 167 448 145 448 145 449 167 449 290 449 145 450 290 450 289 450 289 451 290 451 119 451 289 452 119 452 286 452 286 453 119 453 118 453 286 454 118 454 287 454 113 455 168 455 167 455 167 456 168 456 291 456 167 457 291 457 290 457 290 458 291 458 292 458 290 459 292 459 119 459 119 460 292 460 293 460 119 461 293 461 117 461 116 462 144 462 168 462 168 463 144 463 178 463 168 464 178 464 291 464 291 465 178 465 220 465 291 466 220 466 292 466 292 467 220 467 294 467 292 468 294 468 293 468 225 469 295 469 223 469 223 470 295 470 296 470 223 471 296 471 222 471 222 472 296 472 297 472 222 473 297 473 221 473 221 474 297 474 298 474 221 475 298 475 220 475 220 476 298 476 299 476 220 477 299 477 294 477 300 478 297 478 301 478 301 479 297 479 296 479 301 480 296 480 302 480 302 481 296 481 295 481 302 482 295 482 303 482 303 483 295 483 225 483 303 484 225 484 304 484 304 485 225 485 224 485 304 486 224 486 305 486 305 487 224 487 133 487 305 488 133 488 306 488 306 489 133 489 132 489 306 490 132 490 307 490 307 491 132 491 229 491 307 492 229 492 308 492 308 493 229 493 230 493 308 494 230 494 309 494 309 495 230 495 233 495 309 496 233 496 310 496 310 497 233 497 232 497 310 498 232 498 311 498 232 499 231 499 311 499 311 500 231 500 185 500 311 501 185 501 312 501 312 502 185 502 184 502 312 503 184 503 313 503 313 504 184 504 130 504 313 505 130 505 314 505 130 506 129 506 314 506 314 507 129 507 241 507 314 508 241 508 315 508 315 509 241 509 240 509 315 510 240 510 316 510 316 511 240 511 239 511 316 512 239 512 317 512 317 513 239 513 236 513 317 514 236 514 318 514 318 515 236 515 235 515 318 516 235 516 319 516 319 517 235 517 127 517 319 518 127 518 320 518 127 519 126 519 320 519 320 520 126 520 249 520 320 521 249 521 321 521 321 522 249 522 248 522 321 523 248 523 322 523 322 524 248 524 247 524 322 525 247 525 323 525 323 526 247 526 244 526 323 527 244 527 324 527 324 528 244 528 243 528 324 529 243 529 325 529 243 530 256 530 325 530 325 531 256 531 255 531 325 532 255 532 326 532 326 533 255 533 254 533 326 534 254 534 327 534 327 535 254 535 251 535 327 536 251 536 328 536 251 537 250 537 328 537 328 538 250 538 124 538 328 539 124 539 329 539 329 540 124 540 123 540 329 541 123 541 330 541 330 542 123 542 265 542 330 543 265 543 331 543 331 544 265 544 264 544 331 545 264 545 332 545 332 546 264 546 263 546 332 547 263 547 333 547 333 548 263 548 260 548 333 549 260 549 334 549 334 550 260 550 259 550 334 551 259 551 335 551 278 552 336 552 337 552 259 553 272 553 335 553 335 554 272 554 271 554 335 555 271 555 338 555 338 556 271 556 270 556 338 557 270 557 339 557 339 558 270 558 267 558 339 559 267 559 340 559 340 560 267 560 266 560 340 561 266 561 341 561 341 562 266 562 273 562 341 563 273 563 342 563 342 564 273 564 276 564 342 565 276 565 337 565 337 566 276 566 275 566 337 567 275 567 278 567 278 568 282 568 336 568 336 569 282 569 281 569 336 570 281 570 343 570 343 571 281 571 280 571 343 572 280 572 344 572 344 573 280 573 279 573 344 574 279 574 345 574 345 575 279 575 218 575 345 576 218 576 346 576 346 577 218 577 219 577 346 578 219 578 347 578 347 579 219 579 121 579 347 580 121 580 348 580 348 581 121 581 120 581 348 582 120 582 349 582 349 583 120 583 285 583 349 584 285 584 350 584 350 585 285 585 288 585 350 586 288 586 351 586 288 587 287 587 351 587 351 588 287 588 118 588 351 589 118 589 352 589 352 590 118 590 117 590 352 591 117 591 353 591 353 592 117 592 293 592 353 593 293 593 354 593 354 594 293 594 294 594 354 595 294 595 355 595 355 596 294 596 299 596 355 597 299 597 300 597 300 598 299 598 298 598 300 599 298 599 297 599 356 600 357 600 358 600 359 601 360 601 356 601 356 602 360 602 361 602 356 603 361 603 357 603 358 604 362 604 356 604 356 605 362 605 363 605 356 606 363 606 364 606 364 607 365 607 356 607 356 608 365 608 366 608 356 609 366 609 367 609 359 610 368 610 360 610 360 611 368 611 369 611 360 612 369 612 370 612 370 613 371 613 360 613 360 614 371 614 372 614 360 615 372 615 373 615 373 616 374 616 360 616 360 617 374 617 375 617 360 618 375 618 376 618 376 619 377 619 360 619 360 620 377 620 378 620 360 621 378 621 379 621 367 622 380 622 356 622 356 623 380 623 381 623 356 624 381 624 382 624 383 625 384 625 385 625 382 626 386 626 356 626 356 627 386 627 383 627 356 628 383 628 387 628 387 629 383 629 385 629 338 630 339 630 388 630 350 631 351 631 389 631 308 632 309 632 390 632 322 633 323 633 391 633 363 634 362 634 392 634 364 635 363 635 393 635 365 636 364 636 394 636 366 637 365 637 395 637 386 638 382 638 396 638 383 639 386 639 397 639 384 640 383 640 398 640 385 641 384 641 399 641 369 642 368 642 400 642 370 643 369 643 401 643 371 644 370 644 402 644 372 645 371 645 403 645 377 646 376 646 404 646 378 647 377 647 405 647 379 648 378 648 406 648 360 649 379 649 407 649 372 650 408 650 373 650 373 651 408 651 409 651 373 652 409 652 410 652 410 653 409 653 411 653 410 654 411 654 375 654 375 655 411 655 412 655 375 656 412 656 376 656 385 657 413 657 387 657 387 658 413 658 414 658 387 659 414 659 415 659 415 660 414 660 416 660 415 661 416 661 359 661 359 662 416 662 417 662 359 663 417 663 368 663 366 664 418 664 367 664 367 665 418 665 419 665 367 666 419 666 420 666 420 667 419 667 421 667 420 668 421 668 381 668 381 669 421 669 422 669 381 670 422 670 382 670 360 671 423 671 361 671 361 672 423 672 424 672 361 673 424 673 425 673 425 674 424 674 426 674 425 675 426 675 358 675 358 676 426 676 427 676 358 677 427 677 362 677 408 678 428 678 409 678 409 679 428 679 429 679 409 680 429 680 411 680 411 681 429 681 430 681 411 682 430 682 412 682 412 683 430 683 431 683 413 684 432 684 414 684 414 685 432 685 433 685 414 686 433 686 416 686 416 687 433 687 434 687 416 688 434 688 417 688 417 689 434 689 435 689 418 690 436 690 419 690 419 691 436 691 437 691 419 692 437 692 421 692 421 693 437 693 438 693 421 694 438 694 422 694 422 695 438 695 439 695 423 696 440 696 424 696 424 697 440 697 441 697 424 698 441 698 426 698 426 699 441 699 442 699 426 700 442 700 427 700 427 701 442 701 443 701 428 702 444 702 429 702 429 703 444 703 445 703 429 704 445 704 430 704 430 705 445 705 446 705 430 706 446 706 431 706 431 707 446 707 447 707 432 708 448 708 433 708 433 709 448 709 449 709 433 710 449 710 434 710 434 711 449 711 450 711 434 712 450 712 435 712 435 713 450 713 451 713 436 714 452 714 437 714 437 715 452 715 453 715 437 716 453 716 438 716 438 717 453 717 454 717 438 718 454 718 439 718 439 719 454 719 455 719 440 720 456 720 441 720 441 721 456 721 457 721 441 722 457 722 442 722 442 723 457 723 458 723 442 724 458 724 443 724 443 725 458 725 459 725 360 726 407 726 423 726 423 727 407 727 460 727 423 728 460 728 440 728 440 729 460 729 391 729 440 730 391 730 456 730 456 731 391 731 323 731 456 732 323 732 324 732 379 733 406 733 407 733 407 734 406 734 461 734 407 735 461 735 460 735 460 736 461 736 462 736 460 737 462 737 391 737 391 738 462 738 321 738 391 739 321 739 322 739 463 740 319 740 320 740 378 741 405 741 406 741 406 742 405 742 464 742 406 743 464 743 461 743 461 744 464 744 463 744 461 745 463 745 462 745 462 746 463 746 320 746 462 747 320 747 321 747 465 748 317 748 318 748 377 749 404 749 405 749 405 750 404 750 466 750 405 751 466 751 464 751 464 752 466 752 465 752 464 753 465 753 463 753 463 754 465 754 318 754 463 755 318 755 319 755 376 756 412 756 404 756 404 757 412 757 431 757 404 758 431 758 466 758 466 759 431 759 447 759 466 760 447 760 465 760 465 761 447 761 316 761 465 762 316 762 317 762 310 763 311 763 444 763 444 764 311 764 312 764 444 765 312 765 445 765 445 766 312 766 313 766 445 767 313 767 446 767 446 768 313 768 467 768 446 769 467 769 447 769 447 770 467 770 315 770 447 771 315 771 316 771 372 772 403 772 408 772 408 773 403 773 468 773 408 774 468 774 428 774 428 775 468 775 390 775 428 776 390 776 444 776 444 777 390 777 309 777 444 778 309 778 310 778 371 779 402 779 403 779 403 780 402 780 469 780 403 781 469 781 468 781 468 782 469 782 470 782 468 783 470 783 390 783 390 784 470 784 307 784 390 785 307 785 308 785 471 786 305 786 306 786 370 787 401 787 402 787 402 788 401 788 472 788 402 789 472 789 469 789 469 790 472 790 471 790 469 791 471 791 470 791 470 792 471 792 306 792 470 793 306 793 307 793 473 794 303 794 304 794 369 795 400 795 401 795 401 796 400 796 474 796 401 797 474 797 472 797 472 798 474 798 473 798 472 799 473 799 471 799 471 800 473 800 304 800 471 801 304 801 305 801 368 802 417 802 400 802 400 803 417 803 435 803 400 804 435 804 474 804 474 805 435 805 451 805 474 806 451 806 473 806 473 807 451 807 302 807 473 808 302 808 303 808 352 809 353 809 448 809 448 810 353 810 354 810 448 811 354 811 449 811 449 812 354 812 355 812 449 813 355 813 450 813 450 814 355 814 475 814 450 815 475 815 451 815 451 816 475 816 301 816 451 817 301 817 302 817 385 818 399 818 413 818 413 819 399 819 476 819 413 820 476 820 432 820 432 821 476 821 389 821 432 822 389 822 448 822 448 823 389 823 351 823 448 824 351 824 352 824 384 825 398 825 399 825 399 826 398 826 477 826 399 827 477 827 476 827 476 828 477 828 478 828 476 829 478 829 389 829 389 830 478 830 349 830 389 831 349 831 350 831 479 832 347 832 348 832 383 833 397 833 398 833 398 834 397 834 480 834 398 835 480 835 477 835 477 836 480 836 479 836 477 837 479 837 478 837 478 838 479 838 348 838 478 839 348 839 349 839 481 840 345 840 346 840 386 841 396 841 397 841 397 842 396 842 482 842 397 843 482 843 480 843 480 844 482 844 481 844 480 845 481 845 479 845 479 846 481 846 346 846 479 847 346 847 347 847 382 848 422 848 396 848 396 849 422 849 439 849 396 850 439 850 482 850 482 851 439 851 455 851 482 852 455 852 481 852 481 853 455 853 344 853 481 854 344 854 345 854 340 855 341 855 452 855 452 856 341 856 342 856 452 857 342 857 453 857 453 858 342 858 337 858 453 859 337 859 454 859 454 860 337 860 483 860 454 861 483 861 455 861 455 862 483 862 343 862 455 863 343 863 344 863 366 864 395 864 418 864 418 865 395 865 484 865 418 866 484 866 436 866 436 867 484 867 388 867 436 868 388 868 452 868 452 869 388 869 339 869 452 870 339 870 340 870 365 871 394 871 395 871 395 872 394 872 485 872 395 873 485 873 484 873 484 874 485 874 486 874 484 875 486 875 388 875 388 876 486 876 335 876 388 877 335 877 338 877 487 878 333 878 334 878 364 879 393 879 394 879 394 880 393 880 488 880 394 881 488 881 485 881 485 882 488 882 487 882 485 883 487 883 486 883 486 884 487 884 334 884 486 885 334 885 335 885 489 886 331 886 332 886 363 887 392 887 393 887 393 888 392 888 490 888 393 889 490 889 488 889 488 890 490 890 489 890 488 891 489 891 487 891 487 892 489 892 332 892 487 893 332 893 333 893 362 894 427 894 392 894 392 895 427 895 443 895 392 896 443 896 490 896 490 897 443 897 459 897 490 898 459 898 489 898 489 899 459 899 330 899 489 900 330 900 331 900 324 901 325 901 456 901 456 902 325 902 326 902 456 903 326 903 457 903 457 904 326 904 327 904 457 905 327 905 458 905 458 906 327 906 491 906 458 907 491 907 459 907 459 908 491 908 329 908 459 909 329 909 330 909 492 910 493 910 494 910 494 911 493 911 495 911 496 912 497 912 498 912 498 913 497 913 499 913 498 914 499 914 500 914 500 915 501 915 498 915 498 916 501 916 502 916 498 917 502 917 503 917 492 918 496 918 493 918 493 919 496 919 498 919 493 920 498 920 504 920 504 921 498 921 505 921 504 922 505 922 506 922 506 923 505 923 507 923 507 924 505 924 508 924 507 925 508 925 509 925 509 926 510 926 507 926 507 927 510 927 511 927 507 928 511 928 512 928 513 929 514 929 515 929 515 930 516 930 513 930 513 931 516 931 517 931 513 932 517 932 518 932 512 933 519 933 507 933 507 934 519 934 520 934 507 935 520 935 521 935 521 936 520 936 513 936 521 937 513 937 522 937 522 938 513 938 518 938 523 939 524 939 525 939 525 940 524 940 526 940 525 941 526 941 527 941 528 942 529 942 527 942 527 943 529 943 530 943 527 944 530 944 525 944 531 945 532 945 533 945 532 946 534 946 533 946 533 947 534 947 535 947 533 948 535 948 536 948 514 949 523 949 515 949 515 950 523 950 525 950 515 951 525 951 536 951 536 952 525 952 537 952 536 953 537 953 538 953 538 954 539 954 536 954 536 955 539 955 540 955 536 956 540 956 533 956 541 957 542 957 543 957 543 958 542 958 544 958 543 959 544 959 545 959 545 960 546 960 543 960 543 961 546 961 547 961 543 962 547 962 533 962 533 963 547 963 548 963 533 964 548 964 531 964 541 965 543 965 549 965 549 966 543 966 550 966 549 967 550 967 551 967 552 968 553 968 554 968 554 969 555 969 552 969 552 970 555 970 556 970 552 971 556 971 557 971 557 972 558 972 552 972 552 973 558 973 559 973 552 974 559 974 560 974 560 975 561 975 552 975 552 976 561 976 562 976 552 977 562 977 563 977 551 978 564 978 549 978 549 979 564 979 552 979 549 980 552 980 565 980 565 981 552 981 563 981 553 982 566 982 554 982 554 983 566 983 567 983 554 984 567 984 568 984 568 985 569 985 554 985 554 986 569 986 570 986 554 987 570 987 571 987 572 988 573 988 574 988 575 989 576 989 577 989 577 990 576 990 578 990 565 991 579 991 549 991 549 992 579 992 580 992 549 993 580 993 581 993 578 994 572 994 577 994 577 995 572 995 574 995 577 996 574 996 582 996 582 997 574 997 549 997 582 998 549 998 583 998 583 999 549 999 581 999 571 1000 584 1000 554 1000 554 1001 584 1001 585 1001 554 1002 585 1002 586 1002 587 1003 588 1003 589 1003 589 1004 588 1004 590 1004 590 1005 591 1005 589 1005 589 1006 591 1006 554 1006 589 1007 554 1007 592 1007 592 1008 554 1008 586 1008 592 1009 586 1009 593 1009 528 1010 527 1010 594 1010 594 1011 527 1011 595 1011 594 1012 595 1012 596 1012 596 1013 595 1013 597 1013 596 1014 597 1014 598 1014 598 1015 599 1015 596 1015 596 1016 599 1016 600 1016 596 1017 600 1017 601 1017 601 1018 602 1018 596 1018 596 1019 602 1019 603 1019 596 1020 603 1020 604 1020 604 1021 603 1021 605 1021 604 1022 605 1022 606 1022 607 1023 608 1023 609 1023 607 1024 609 1024 610 1024 606 1025 605 1025 611 1025 611 1026 605 1026 612 1026 611 1027 612 1027 613 1027 613 1028 612 1028 614 1028 613 1029 614 1029 615 1029 615 1030 614 1030 616 1030 615 1031 616 1031 617 1031 617 1032 616 1032 618 1032 617 1033 618 1033 619 1033 619 1034 618 1034 620 1034 619 1035 620 1035 621 1035 621 1036 620 1036 609 1036 609 1037 620 1037 622 1037 609 1038 622 1038 610 1038 623 1039 624 1039 625 1039 608 1040 626 1040 609 1040 609 1041 626 1041 627 1041 609 1042 627 1042 624 1042 624 1043 627 1043 628 1043 624 1044 628 1044 625 1044 629 1045 630 1045 625 1045 625 1046 630 1046 631 1046 625 1047 631 1047 623 1047 632 1048 633 1048 634 1048 634 1049 633 1049 635 1049 634 1050 635 1050 636 1050 637 1051 638 1051 635 1051 638 1052 639 1052 635 1052 635 1053 639 1053 640 1053 635 1054 640 1054 636 1054 641 1055 642 1055 643 1055 643 1056 642 1056 644 1056 629 1057 632 1057 630 1057 630 1058 632 1058 634 1058 630 1059 634 1059 644 1059 644 1060 634 1060 645 1060 644 1061 645 1061 643 1061 646 1062 647 1062 643 1062 643 1063 647 1063 648 1063 643 1064 648 1064 641 1064 649 1065 650 1065 651 1065 646 1066 652 1066 647 1066 647 1067 652 1067 653 1067 647 1068 653 1068 650 1068 650 1069 653 1069 654 1069 650 1070 654 1070 651 1070 655 1071 656 1071 651 1071 651 1072 656 1072 657 1072 651 1073 657 1073 649 1073 655 1074 658 1074 656 1074 656 1075 658 1075 659 1075 656 1076 659 1076 660 1076 661 1077 662 1077 663 1077 661 1078 663 1078 664 1078 664 1079 663 1079 665 1079 664 1080 665 1080 666 1080 666 1081 667 1081 664 1081 664 1082 667 1082 668 1082 664 1083 668 1083 669 1083 670 1084 671 1084 672 1084 672 1085 671 1085 673 1085 672 1086 673 1086 674 1086 674 1087 673 1087 675 1087 675 1088 673 1088 676 1088 675 1089 676 1089 677 1089 669 1090 678 1090 664 1090 664 1091 678 1091 679 1091 664 1092 679 1092 680 1092 677 1093 681 1093 675 1093 675 1094 681 1094 682 1094 675 1095 682 1095 683 1095 660 1096 684 1096 656 1096 656 1097 684 1097 675 1097 656 1098 675 1098 685 1098 685 1099 675 1099 683 1099 685 1100 683 1100 686 1100 686 1101 687 1101 685 1101 685 1102 687 1102 688 1102 685 1103 688 1103 689 1103 689 1104 690 1104 685 1104 685 1105 690 1105 691 1105 685 1106 691 1106 692 1106 680 1107 693 1107 664 1107 664 1108 693 1108 694 1108 664 1109 694 1109 695 1109 695 1110 694 1110 685 1110 695 1111 685 1111 696 1111 696 1112 685 1112 692 1112 697 1113 698 1113 699 1113 664 1114 700 1114 661 1114 661 1115 700 1115 697 1115 661 1116 697 1116 701 1116 701 1117 697 1117 699 1117 702 1118 703 1118 704 1118 670 1119 705 1119 671 1119 671 1120 705 1120 702 1120 671 1121 702 1121 706 1121 706 1122 702 1122 704 1122 637 1123 635 1123 707 1123 707 1124 635 1124 708 1124 707 1125 708 1125 709 1125 710 1126 711 1126 712 1126 712 1127 713 1127 710 1127 710 1128 713 1128 714 1128 710 1129 714 1129 715 1129 715 1130 714 1130 716 1130 717 1131 718 1131 719 1131 719 1132 720 1132 717 1132 717 1133 720 1133 721 1133 717 1134 721 1134 722 1134 722 1135 721 1135 723 1135 722 1136 723 1136 710 1136 710 1137 723 1137 724 1137 710 1138 724 1138 711 1138 709 1139 725 1139 707 1139 707 1140 725 1140 723 1140 707 1141 723 1141 726 1141 726 1142 723 1142 721 1142 727 1143 728 1143 716 1143 716 1144 728 1144 729 1144 729 1145 730 1145 716 1145 716 1146 730 1146 731 1146 716 1147 731 1147 715 1147 502 1148 732 1148 503 1148 503 1149 732 1149 728 1149 503 1150 728 1150 733 1150 733 1151 728 1151 727 1151 734 1152 735 1152 736 1152 737 1153 738 1153 739 1153 736 1154 740 1154 734 1154 734 1155 740 1155 741 1155 734 1156 741 1156 742 1156 742 1157 741 1157 743 1157 735 1158 734 1158 739 1158 739 1159 734 1159 744 1159 739 1160 744 1160 737 1160 738 1161 745 1161 739 1161 739 1162 745 1162 746 1162 739 1163 746 1163 747 1163 747 1164 746 1164 748 1164 743 1165 741 1165 749 1165 749 1166 741 1166 750 1166 749 1167 750 1167 751 1167 751 1168 752 1168 749 1168 749 1169 752 1169 753 1169 749 1170 753 1170 754 1170 754 1171 753 1171 755 1171 756 1172 757 1172 758 1172 756 1173 758 1173 759 1173 760 1174 761 1174 758 1174 758 1175 761 1175 762 1175 758 1176 762 1176 759 1176 763 1177 764 1177 765 1177 757 1178 766 1178 767 1178 764 1179 763 1179 768 1179 768 1180 763 1180 769 1180 768 1181 769 1181 770 1181 760 1182 771 1182 761 1182 761 1183 771 1183 763 1183 761 1184 763 1184 772 1184 772 1185 763 1185 765 1185 766 1186 757 1186 773 1186 773 1187 757 1187 774 1187 773 1188 774 1188 775 1188 767 1189 776 1189 757 1189 757 1190 776 1190 777 1190 757 1191 777 1191 758 1191 746 1192 778 1192 748 1192 748 1193 778 1193 779 1193 748 1194 779 1194 747 1194 747 1195 779 1195 780 1195 747 1196 780 1196 739 1196 739 1197 780 1197 781 1197 739 1198 781 1198 735 1198 735 1199 781 1199 782 1199 735 1200 782 1200 736 1200 736 1201 782 1201 783 1201 736 1202 783 1202 740 1202 740 1203 783 1203 784 1203 740 1204 784 1204 741 1204 741 1205 784 1205 785 1205 741 1206 785 1206 750 1206 750 1207 785 1207 786 1207 750 1208 786 1208 751 1208 751 1209 786 1209 787 1209 751 1210 787 1210 752 1210 752 1211 787 1211 788 1211 752 1212 788 1212 753 1212 753 1213 788 1213 789 1213 753 1214 789 1214 755 1214 755 1215 789 1215 790 1215 755 1216 790 1216 754 1216 754 1217 790 1217 791 1217 754 1218 791 1218 749 1218 749 1219 791 1219 792 1219 749 1220 792 1220 743 1220 743 1221 792 1221 793 1221 743 1222 793 1222 742 1222 742 1223 793 1223 794 1223 742 1224 794 1224 734 1224 734 1225 794 1225 795 1225 734 1226 795 1226 744 1226 744 1227 795 1227 796 1227 744 1228 796 1228 737 1228 737 1229 796 1229 797 1229 737 1230 797 1230 738 1230 738 1231 797 1231 798 1231 738 1232 798 1232 745 1232 745 1233 798 1233 799 1233 745 1234 799 1234 746 1234 746 1235 799 1235 778 1235 800 1236 775 1236 801 1236 801 1237 775 1237 774 1237 801 1238 774 1238 802 1238 802 1239 774 1239 757 1239 802 1240 757 1240 803 1240 803 1241 757 1241 756 1241 803 1242 756 1242 804 1242 804 1243 756 1243 759 1243 804 1244 759 1244 805 1244 805 1245 759 1245 762 1245 805 1246 762 1246 806 1246 806 1247 762 1247 761 1247 806 1248 761 1248 807 1248 807 1249 761 1249 772 1249 807 1250 772 1250 808 1250 808 1251 772 1251 765 1251 808 1252 765 1252 809 1252 809 1253 765 1253 764 1253 809 1254 764 1254 810 1254 810 1255 764 1255 768 1255 810 1256 768 1256 811 1256 811 1257 768 1257 770 1257 811 1258 770 1258 812 1258 812 1259 770 1259 769 1259 812 1260 769 1260 813 1260 813 1261 769 1261 763 1261 813 1262 763 1262 814 1262 814 1263 763 1263 771 1263 814 1264 771 1264 815 1264 815 1265 771 1265 760 1265 815 1266 760 1266 816 1266 816 1267 760 1267 758 1267 816 1268 758 1268 817 1268 817 1269 758 1269 777 1269 817 1270 777 1270 818 1270 818 1271 777 1271 776 1271 818 1272 776 1272 819 1272 819 1273 776 1273 767 1273 819 1274 767 1274 820 1274 820 1275 767 1275 766 1275 820 1276 766 1276 821 1276 821 1277 766 1277 773 1277 821 1278 773 1278 800 1278 800 1279 773 1279 775 1279 794 1280 822 1280 795 1280 795 1281 822 1281 823 1281 795 1282 823 1282 796 1282 796 1283 823 1283 824 1283 796 1284 824 1284 797 1284 797 1285 824 1285 825 1285 797 1286 825 1286 798 1286 798 1287 825 1287 826 1287 798 1288 826 1288 799 1288 799 1289 826 1289 827 1289 799 1290 827 1290 778 1290 778 1291 827 1291 828 1291 778 1292 828 1292 779 1292 779 1293 828 1293 829 1293 779 1294 829 1294 780 1294 780 1295 829 1295 830 1295 780 1296 830 1296 781 1296 781 1297 830 1297 831 1297 781 1298 831 1298 782 1298 782 1299 831 1299 832 1299 782 1300 832 1300 783 1300 832 1301 833 1301 783 1301 783 1302 833 1302 834 1302 783 1303 834 1303 784 1303 784 1304 834 1304 835 1304 784 1305 835 1305 785 1305 785 1306 835 1306 836 1306 785 1307 836 1307 786 1307 786 1308 836 1308 837 1308 786 1309 837 1309 787 1309 787 1310 837 1310 838 1310 787 1311 838 1311 788 1311 788 1312 838 1312 839 1312 788 1313 839 1313 789 1313 789 1314 839 1314 840 1314 789 1315 840 1315 790 1315 790 1316 840 1316 841 1316 790 1317 841 1317 791 1317 791 1318 841 1318 842 1318 791 1319 842 1319 792 1319 792 1320 842 1320 843 1320 792 1321 843 1321 793 1321 793 1322 843 1322 844 1322 793 1323 844 1323 794 1323 794 1324 844 1324 845 1324 794 1325 845 1325 822 1325 806 1326 846 1326 805 1326 805 1327 846 1327 847 1327 805 1328 847 1328 804 1328 804 1329 847 1329 848 1329 804 1330 848 1330 803 1330 803 1331 848 1331 849 1331 803 1332 849 1332 802 1332 802 1333 849 1333 850 1333 802 1334 850 1334 801 1334 801 1335 850 1335 851 1335 801 1336 851 1336 800 1336 800 1337 851 1337 852 1337 800 1338 852 1338 821 1338 821 1339 852 1339 853 1339 821 1340 853 1340 820 1340 820 1341 853 1341 854 1341 820 1342 854 1342 819 1342 819 1343 854 1343 855 1343 819 1344 855 1344 818 1344 818 1345 855 1345 856 1345 818 1346 856 1346 817 1346 856 1347 857 1347 817 1347 817 1348 857 1348 858 1348 817 1349 858 1349 816 1349 816 1350 858 1350 859 1350 816 1351 859 1351 815 1351 815 1352 859 1352 860 1352 815 1353 860 1353 814 1353 814 1354 860 1354 861 1354 814 1355 861 1355 813 1355 813 1356 861 1356 862 1356 813 1357 862 1357 812 1357 812 1358 862 1358 863 1358 812 1359 863 1359 811 1359 811 1360 863 1360 864 1360 811 1361 864 1361 810 1361 810 1362 864 1362 865 1362 810 1363 865 1363 809 1363 809 1364 865 1364 866 1364 809 1365 866 1365 808 1365 808 1366 866 1366 867 1366 808 1367 867 1367 807 1367 807 1368 867 1368 868 1368 807 1369 868 1369 806 1369 806 1370 868 1370 869 1370 806 1371 869 1371 846 1371 870 1372 840 1372 871 1372 871 1373 840 1373 839 1373 871 1374 839 1374 872 1374 872 1375 839 1375 838 1375 872 1376 838 1376 873 1376 873 1377 838 1377 837 1377 873 1378 837 1378 874 1378 874 1379 837 1379 836 1379 874 1380 836 1380 875 1380 875 1381 836 1381 835 1381 875 1382 835 1382 876 1382 876 1383 835 1383 877 1383 876 1384 877 1384 878 1384 878 1385 877 1385 833 1385 878 1386 833 1386 879 1386 879 1387 833 1387 832 1387 879 1388 832 1388 880 1388 880 1389 832 1389 831 1389 880 1390 831 1390 881 1390 881 1391 831 1391 830 1391 881 1392 830 1392 882 1392 882 1393 830 1393 829 1393 882 1394 829 1394 883 1394 883 1395 829 1395 828 1395 883 1396 828 1396 884 1396 884 1397 828 1397 827 1397 884 1398 827 1398 885 1398 885 1399 827 1399 826 1399 885 1400 826 1400 886 1400 886 1401 826 1401 825 1401 886 1402 825 1402 887 1402 887 1403 825 1403 824 1403 887 1404 824 1404 888 1404 888 1405 824 1405 823 1405 888 1406 823 1406 889 1406 889 1407 823 1407 890 1407 889 1408 890 1408 891 1408 891 1409 890 1409 845 1409 891 1410 845 1410 892 1410 892 1411 845 1411 844 1411 892 1412 844 1412 893 1412 893 1413 844 1413 843 1413 893 1414 843 1414 894 1414 894 1415 843 1415 842 1415 894 1416 842 1416 895 1416 895 1417 842 1417 841 1417 895 1418 841 1418 870 1418 870 1419 841 1419 840 1419 862 1420 896 1420 863 1420 863 1421 896 1421 897 1421 863 1422 897 1422 864 1422 864 1423 897 1423 898 1423 864 1424 898 1424 865 1424 865 1425 898 1425 899 1425 865 1426 899 1426 866 1426 866 1427 899 1427 900 1427 866 1428 900 1428 867 1428 867 1429 900 1429 901 1429 867 1430 901 1430 868 1430 868 1431 901 1431 902 1431 868 1432 902 1432 903 1432 903 1433 902 1433 904 1433 903 1434 904 1434 846 1434 846 1435 904 1435 905 1435 846 1436 905 1436 847 1436 847 1437 905 1437 906 1437 847 1438 906 1438 848 1438 848 1439 906 1439 907 1439 848 1440 907 1440 849 1440 849 1441 907 1441 908 1441 849 1442 908 1442 850 1442 850 1443 908 1443 909 1443 850 1444 909 1444 851 1444 851 1445 909 1445 910 1445 851 1446 910 1446 852 1446 852 1447 910 1447 911 1447 852 1448 911 1448 853 1448 853 1449 911 1449 912 1449 853 1450 912 1450 854 1450 854 1451 912 1451 913 1451 854 1452 913 1452 855 1452 855 1453 913 1453 914 1453 855 1454 914 1454 856 1454 856 1455 914 1455 915 1455 856 1456 915 1456 916 1456 916 1457 915 1457 917 1457 916 1458 917 1458 858 1458 858 1459 917 1459 918 1459 858 1460 918 1460 859 1460 859 1461 918 1461 919 1461 859 1462 919 1462 860 1462 860 1463 919 1463 920 1463 860 1464 920 1464 861 1464 861 1465 920 1465 921 1465 861 1466 921 1466 862 1466 862 1467 921 1467 896 1467 922 1468 923 1468 924 1468 925 1469 926 1469 927 1469 925 1470 927 1470 928 1470 927 1471 929 1471 928 1471 928 1472 929 1472 930 1472 928 1473 930 1473 931 1473 932 1474 933 1474 925 1474 925 1475 933 1475 934 1475 925 1476 934 1476 926 1476 935 1477 936 1477 925 1477 925 1478 936 1478 937 1478 925 1479 937 1479 938 1479 938 1480 939 1480 925 1480 925 1481 939 1481 940 1481 925 1482 940 1482 932 1482 941 1483 942 1483 928 1483 942 1484 943 1484 928 1484 928 1485 943 1485 944 1485 928 1486 944 1486 925 1486 925 1487 944 1487 945 1487 925 1488 945 1488 935 1488 946 1489 947 1489 924 1489 924 1490 947 1490 948 1490 924 1491 948 1491 928 1491 928 1492 948 1492 949 1492 928 1493 949 1493 941 1493 950 1494 951 1494 924 1494 924 1495 951 1495 952 1495 924 1496 952 1496 946 1496 953 1497 954 1497 955 1497 952 1498 956 1498 946 1498 946 1499 956 1499 953 1499 946 1500 953 1500 957 1500 957 1501 953 1501 955 1501 950 1502 924 1502 958 1502 958 1503 924 1503 923 1503 958 1504 923 1504 959 1504 959 1505 923 1505 960 1505 959 1506 960 1506 961 1506 931 1507 962 1507 928 1507 928 1508 962 1508 963 1508 928 1509 963 1509 924 1509 924 1510 963 1510 964 1510 924 1511 964 1511 922 1511 965 1512 966 1512 967 1512 968 1513 969 1513 970 1513 971 1514 972 1514 973 1514 971 1515 973 1515 974 1515 975 1516 976 1516 977 1516 977 1517 976 1517 969 1517 977 1518 969 1518 978 1518 978 1519 969 1519 968 1519 979 1520 980 1520 970 1520 970 1521 980 1521 981 1521 970 1522 981 1522 968 1522 982 1523 983 1523 984 1523 985 1524 986 1524 984 1524 984 1525 986 1525 987 1525 984 1526 987 1526 982 1526 982 1527 987 1527 988 1527 982 1528 988 1528 989 1528 990 1529 991 1529 992 1529 992 1530 991 1530 993 1530 992 1531 993 1531 994 1531 994 1532 993 1532 995 1532 994 1533 995 1533 996 1533 996 1534 995 1534 997 1534 996 1535 997 1535 998 1535 998 1536 997 1536 999 1536 998 1537 999 1537 1000 1537 1000 1538 999 1538 1001 1538 1002 1539 1003 1539 1004 1539 1005 1540 1006 1540 1002 1540 1002 1541 1006 1541 1007 1541 1002 1542 1007 1542 1008 1542 1008 1543 1009 1543 1002 1543 1002 1544 1009 1544 1010 1544 1002 1545 1010 1545 1003 1545 1003 1546 1010 1546 1011 1546 1005 1547 1002 1547 1012 1547 1012 1548 1002 1548 1013 1548 1012 1549 1013 1549 1014 1549 1014 1550 1013 1550 1015 1550 1015 1551 1013 1551 1016 1551 1015 1552 1016 1552 1017 1552 973 1553 1018 1553 974 1553 974 1554 1018 1554 1019 1554 974 1555 1019 1555 1020 1555 1020 1556 1019 1556 1021 1556 1021 1557 1022 1557 1020 1557 1020 1558 1022 1558 1023 1558 1020 1559 1023 1559 1016 1559 1016 1560 1023 1560 1024 1560 1016 1561 1024 1561 1017 1561 965 1562 967 1562 989 1562 989 1563 967 1563 1025 1563 989 1564 1025 1564 982 1564 982 1565 1025 1565 1026 1565 982 1566 1026 1566 983 1566 998 1567 985 1567 996 1567 996 1568 985 1568 984 1568 996 1569 984 1569 994 1569 994 1570 984 1570 983 1570 994 1571 983 1571 992 1571 992 1572 983 1572 1026 1572 992 1573 1026 1573 990 1573 990 1574 1026 1574 1025 1574 990 1575 1025 1575 979 1575 979 1576 1025 1576 967 1576 979 1577 967 1577 980 1577 980 1578 967 1578 966 1578 976 1579 1027 1579 969 1579 969 1580 1027 1580 1028 1580 969 1581 1028 1581 970 1581 970 1582 1028 1582 1029 1582 970 1583 1029 1583 979 1583 979 1584 1029 1584 1030 1584 979 1585 1030 1585 990 1585 990 1586 1030 1586 1031 1586 990 1587 1031 1587 991 1587 1032 1588 971 1588 975 1588 975 1589 971 1589 974 1589 975 1590 974 1590 976 1590 976 1591 974 1591 1020 1591 976 1592 1020 1592 1027 1592 1027 1593 1020 1593 1016 1593 1027 1594 1016 1594 1028 1594 1028 1595 1016 1595 1013 1595 1028 1596 1013 1596 1029 1596 1029 1597 1013 1597 1002 1597 1029 1598 1002 1598 1030 1598 1030 1599 1002 1599 1004 1599 1030 1600 1004 1600 1031 1600 1033 1601 1034 1601 1035 1601 1035 1602 1034 1602 1036 1602 1036 1603 1037 1603 1035 1603 1035 1604 1037 1604 1038 1604 1035 1605 1038 1605 1039 1605 1039 1606 1040 1606 1035 1606 1035 1607 1040 1607 1041 1607 1035 1608 1041 1608 1042 1608 1043 1609 1044 1609 1045 1609 1045 1610 1044 1610 1046 1610 1045 1611 1046 1611 1034 1611 1034 1612 1046 1612 1047 1612 1034 1613 1047 1613 1036 1613 1043 1614 1045 1614 1048 1614 1048 1615 1045 1615 1049 1615 1048 1616 1049 1616 1050 1616 1051 1617 1052 1617 1053 1617 1053 1618 1052 1618 1054 1618 1053 1619 1054 1619 1049 1619 1049 1620 1054 1620 1055 1620 1049 1621 1055 1621 1050 1621 1056 1622 1057 1622 1058 1622 1058 1623 1057 1623 1059 1623 1058 1624 1059 1624 1060 1624 1061 1625 1062 1625 1053 1625 1053 1626 1062 1626 1063 1626 1053 1627 1063 1627 1051 1627 1064 1628 1065 1628 1066 1628 1064 1629 1066 1629 1058 1629 1058 1630 1066 1630 1067 1630 1058 1631 1067 1631 1056 1631 1068 1632 1069 1632 1070 1632 1070 1633 1069 1633 1071 1633 1070 1634 1071 1634 1064 1634 1064 1635 1071 1635 1072 1635 1064 1636 1072 1636 1065 1636 1068 1637 1073 1637 1069 1637 1069 1638 1073 1638 1074 1638 1069 1639 1074 1639 1075 1639 1075 1640 1074 1640 1076 1640 1077 1641 1078 1641 1079 1641 1080 1642 1081 1642 1082 1642 1082 1643 1081 1643 1083 1643 1082 1644 1083 1644 1084 1644 1082 1645 1085 1645 1086 1645 1086 1646 1085 1646 1087 1646 1086 1647 1087 1647 1088 1647 1082 1648 1086 1648 1080 1648 1080 1649 1086 1649 1088 1649 1080 1650 1088 1650 1089 1650 1089 1651 1088 1651 1090 1651 1089 1652 1090 1652 1091 1652 1092 1653 1093 1653 1082 1653 1082 1654 1093 1654 1094 1654 1082 1655 1094 1655 1085 1655 1095 1656 1096 1656 1097 1656 1097 1657 1096 1657 1098 1657 1097 1658 1098 1658 1099 1658 1099 1659 1098 1659 1100 1659 1101 1660 1102 1660 1103 1660 1103 1661 1102 1661 1104 1661 1103 1662 1104 1662 1077 1662 1077 1663 1104 1663 1105 1663 1077 1664 1105 1664 1078 1664 1060 1665 1101 1665 1058 1665 1058 1666 1101 1666 1103 1666 1058 1667 1103 1667 1064 1667 1064 1668 1103 1668 1077 1668 1064 1669 1077 1669 1070 1669 1070 1670 1077 1670 1079 1670 1070 1671 1079 1671 1068 1671 1106 1672 1107 1672 1108 1672 1108 1673 1107 1673 1095 1673 1108 1674 1095 1674 1109 1674 1109 1675 1095 1675 1097 1675 1109 1676 1097 1676 1110 1676 1110 1677 1097 1677 1099 1677 1110 1678 1099 1678 1092 1678 1092 1679 1099 1679 1100 1679 1092 1680 1100 1680 1093 1680 1059 1681 1061 1681 1060 1681 1060 1682 1061 1682 1053 1682 1060 1683 1053 1683 1111 1683 1111 1684 1053 1684 1049 1684 1111 1685 1049 1685 1112 1685 1112 1686 1049 1686 1045 1686 1112 1687 1045 1687 1113 1687 1113 1688 1045 1688 1034 1688 1113 1689 1034 1689 1114 1689 1114 1690 1034 1690 1033 1690 1114 1691 1115 1691 1113 1691 1113 1692 1115 1692 1106 1692 1113 1693 1106 1693 1112 1693 1112 1694 1106 1694 1108 1694 1112 1695 1108 1695 1111 1695 1111 1696 1108 1696 1109 1696 1111 1697 1109 1697 1060 1697 1060 1698 1109 1698 1110 1698 1060 1699 1110 1699 1101 1699 1101 1700 1110 1700 1092 1700 1101 1701 1092 1701 1102 1701 1102 1702 1092 1702 1082 1702 1102 1703 1082 1703 1104 1703 1104 1704 1082 1704 1084 1704 1104 1705 1084 1705 1105 1705 1116 1706 1117 1706 1118 1706 1119 1707 1120 1707 1121 1707 1122 1708 1123 1708 1124 1708 1125 1709 1126 1709 1127 1709 1128 1710 1129 1710 1130 1710 1131 1711 1132 1711 1133 1711 1134 1712 1135 1712 1136 1712 1137 1713 1138 1713 1139 1713 1140 1714 1141 1714 1142 1714 1143 1715 1144 1715 1145 1715 1146 1716 1147 1716 1148 1716 1149 1717 1150 1717 1151 1717 1152 1718 1153 1718 1154 1718 1154 1719 1153 1719 1155 1719 1154 1720 1155 1720 1156 1720 1157 1721 1158 1721 1159 1721 1159 1722 1160 1722 1157 1722 1157 1723 1160 1723 1161 1723 1157 1724 1161 1724 1154 1724 1154 1725 1161 1725 1162 1725 1154 1726 1162 1726 1152 1726 1163 1727 1164 1727 1165 1727 1165 1728 1164 1728 1166 1728 1165 1729 1166 1729 1157 1729 1157 1730 1166 1730 1167 1730 1157 1731 1167 1731 1158 1731 1163 1732 1165 1732 1168 1732 1168 1733 1165 1733 1169 1733 1168 1734 1169 1734 1170 1734 991 1735 1031 1735 1171 1735 1171 1736 1031 1736 1004 1736 1171 1737 1004 1737 1172 1737 1172 1738 1004 1738 1003 1738 1172 1739 1003 1739 1011 1739 991 1740 1171 1740 993 1740 993 1741 1171 1741 1173 1741 993 1742 1173 1742 995 1742 995 1743 1173 1743 997 1743 997 1744 1173 1744 1174 1744 997 1745 1174 1745 999 1745 1001 1746 999 1746 1175 1746 1175 1747 999 1747 1174 1747 1175 1748 1174 1748 1176 1748 1176 1749 1174 1749 1150 1749 1177 1750 1178 1750 1179 1750 1179 1751 1178 1751 1149 1751 1180 1752 1181 1752 1177 1752 1181 1753 1180 1753 1182 1753 1183 1754 1184 1754 1185 1754 1185 1755 1184 1755 1186 1755 1185 1756 1186 1756 1187 1756 1188 1757 1189 1757 1183 1757 1189 1758 1188 1758 1147 1758 1190 1759 1191 1759 1192 1759 1192 1760 1191 1760 1146 1760 1193 1761 1194 1761 1190 1761 1194 1762 1193 1762 1144 1762 1143 1763 1145 1763 1195 1763 1196 1764 1197 1764 1198 1764 1197 1765 1196 1765 1141 1765 1140 1766 1142 1766 1138 1766 1199 1767 1200 1767 1201 1767 1201 1768 1200 1768 1137 1768 1202 1769 1203 1769 1199 1769 1203 1770 1202 1770 1135 1770 1204 1771 1205 1771 1206 1771 1206 1772 1205 1772 1134 1772 1207 1773 1208 1773 1204 1773 1209 1774 1210 1774 1211 1774 1211 1775 1210 1775 1131 1775 1212 1776 1213 1776 1209 1776 1214 1777 1215 1777 1216 1777 1216 1778 1215 1778 1217 1778 1216 1779 1217 1779 1128 1779 1218 1780 1219 1780 1214 1780 1219 1781 1218 1781 1126 1781 1220 1782 1221 1782 1122 1782 1221 1783 1220 1783 1156 1783 1149 1784 1151 1784 1179 1784 1179 1785 1151 1785 1222 1785 1179 1786 1222 1786 1223 1786 1223 1787 1222 1787 1224 1787 1223 1788 1224 1788 1225 1788 1177 1789 1179 1789 1180 1789 1180 1790 1179 1790 1223 1790 1180 1791 1223 1791 1226 1791 1226 1792 1223 1792 1225 1792 1226 1793 1225 1793 1227 1793 1183 1794 1185 1794 1188 1794 1188 1795 1185 1795 1228 1795 1188 1796 1228 1796 1229 1796 1229 1797 1228 1797 1230 1797 1229 1798 1230 1798 1231 1798 1190 1799 1192 1799 1193 1799 1193 1800 1192 1800 1232 1800 1193 1801 1232 1801 1233 1801 1233 1802 1232 1802 1234 1802 1233 1803 1234 1803 1235 1803 1144 1804 1193 1804 1145 1804 1145 1805 1193 1805 1233 1805 1145 1806 1233 1806 1236 1806 1236 1807 1233 1807 1235 1807 1236 1808 1235 1808 1237 1808 1141 1809 1196 1809 1142 1809 1142 1810 1196 1810 1238 1810 1142 1811 1238 1811 1239 1811 1239 1812 1238 1812 1240 1812 1239 1813 1240 1813 1241 1813 1199 1814 1201 1814 1202 1814 1202 1815 1201 1815 1242 1815 1202 1816 1242 1816 1243 1816 1243 1817 1242 1817 1244 1817 1243 1818 1244 1818 1245 1818 1135 1819 1202 1819 1136 1819 1136 1820 1202 1820 1243 1820 1136 1821 1243 1821 1246 1821 1246 1822 1243 1822 1245 1822 1246 1823 1245 1823 1247 1823 1131 1824 1133 1824 1211 1824 1211 1825 1133 1825 1248 1825 1211 1826 1248 1826 1249 1826 1249 1827 1248 1827 1250 1827 1249 1828 1250 1828 1251 1828 1128 1829 1130 1829 1216 1829 1216 1830 1130 1830 1252 1830 1216 1831 1252 1831 1253 1831 1253 1832 1252 1832 1254 1832 1253 1833 1254 1833 1255 1833 1122 1834 1124 1834 1220 1834 1220 1835 1124 1835 1256 1835 1220 1836 1256 1836 1257 1836 1257 1837 1256 1837 1258 1837 1257 1838 1258 1838 1259 1838 1150 1839 1174 1839 1151 1839 1151 1840 1174 1840 1173 1840 1151 1841 1173 1841 1222 1841 1222 1842 1173 1842 1171 1842 1222 1843 1171 1843 1224 1843 1224 1844 1171 1844 1172 1844 1224 1845 1172 1845 1260 1845 1260 1846 1261 1846 1224 1846 1224 1847 1261 1847 1262 1847 1224 1848 1262 1848 1225 1848 1225 1849 1262 1849 1263 1849 1225 1850 1263 1850 1227 1850 1227 1851 1263 1851 1264 1851 1227 1852 1264 1852 1265 1852 1182 1853 1180 1853 1266 1853 1266 1854 1180 1854 1226 1854 1266 1855 1226 1855 1267 1855 1267 1856 1226 1856 1227 1856 1267 1857 1227 1857 1268 1857 1268 1858 1227 1858 1265 1858 1268 1859 1265 1859 1269 1859 1269 1860 1230 1860 1268 1860 1268 1861 1230 1861 1228 1861 1268 1862 1228 1862 1267 1862 1267 1863 1228 1863 1185 1863 1267 1864 1185 1864 1266 1864 1266 1865 1185 1865 1187 1865 1266 1866 1187 1866 1182 1866 1269 1867 1270 1867 1230 1867 1230 1868 1270 1868 1271 1868 1230 1869 1271 1869 1231 1869 1231 1870 1271 1870 1272 1870 1231 1871 1272 1871 1273 1871 1147 1872 1188 1872 1148 1872 1148 1873 1188 1873 1229 1873 1148 1874 1229 1874 1274 1874 1274 1875 1229 1875 1231 1875 1274 1876 1231 1876 1275 1876 1275 1877 1231 1877 1273 1877 1275 1878 1273 1878 1276 1878 1146 1879 1148 1879 1192 1879 1192 1880 1148 1880 1274 1880 1192 1881 1274 1881 1232 1881 1232 1882 1274 1882 1275 1882 1232 1883 1275 1883 1234 1883 1234 1884 1275 1884 1276 1884 1234 1885 1276 1885 1277 1885 1277 1886 1278 1886 1234 1886 1234 1887 1278 1887 1279 1887 1234 1888 1279 1888 1235 1888 1235 1889 1279 1889 1280 1889 1235 1890 1280 1890 1237 1890 1237 1891 1280 1891 1281 1891 1237 1892 1281 1892 1282 1892 1195 1893 1145 1893 1283 1893 1283 1894 1145 1894 1236 1894 1283 1895 1236 1895 1284 1895 1284 1896 1236 1896 1237 1896 1284 1897 1237 1897 1285 1897 1285 1898 1237 1898 1282 1898 1285 1899 1282 1899 1286 1899 1286 1900 1240 1900 1285 1900 1285 1901 1240 1901 1238 1901 1285 1902 1238 1902 1284 1902 1284 1903 1238 1903 1196 1903 1284 1904 1196 1904 1283 1904 1283 1905 1196 1905 1198 1905 1283 1906 1198 1906 1195 1906 1286 1907 1287 1907 1240 1907 1240 1908 1287 1908 1288 1908 1240 1909 1288 1909 1241 1909 1241 1910 1288 1910 1289 1910 1241 1911 1289 1911 1290 1911 1138 1912 1142 1912 1139 1912 1139 1913 1142 1913 1239 1913 1139 1914 1239 1914 1291 1914 1291 1915 1239 1915 1241 1915 1291 1916 1241 1916 1292 1916 1292 1917 1241 1917 1290 1917 1292 1918 1290 1918 1293 1918 1137 1919 1139 1919 1201 1919 1201 1920 1139 1920 1291 1920 1201 1921 1291 1921 1242 1921 1242 1922 1291 1922 1292 1922 1242 1923 1292 1923 1244 1923 1244 1924 1292 1924 1293 1924 1244 1925 1293 1925 1294 1925 1294 1926 1295 1926 1244 1926 1244 1927 1295 1927 1296 1927 1244 1928 1296 1928 1245 1928 1245 1929 1296 1929 1297 1929 1245 1930 1297 1930 1247 1930 1247 1931 1297 1931 1298 1931 1247 1932 1298 1932 1299 1932 1134 1933 1136 1933 1206 1933 1206 1934 1136 1934 1246 1934 1206 1935 1246 1935 1300 1935 1300 1936 1246 1936 1247 1936 1300 1937 1247 1937 1301 1937 1301 1938 1247 1938 1299 1938 1301 1939 1299 1939 1302 1939 1204 1940 1206 1940 1207 1940 1207 1941 1206 1941 1300 1941 1207 1942 1300 1942 1303 1942 1303 1943 1300 1943 1301 1943 1303 1944 1301 1944 1121 1944 1121 1945 1301 1945 1302 1945 1121 1946 1302 1946 1119 1946 1120 1947 1250 1947 1121 1947 1121 1948 1250 1948 1248 1948 1121 1949 1248 1949 1303 1949 1303 1950 1248 1950 1133 1950 1303 1951 1133 1951 1207 1951 1207 1952 1133 1952 1132 1952 1207 1953 1132 1953 1208 1953 1120 1954 1304 1954 1250 1954 1250 1955 1304 1955 1305 1955 1250 1956 1305 1956 1251 1956 1251 1957 1305 1957 1306 1957 1251 1958 1306 1958 1307 1958 1209 1959 1211 1959 1212 1959 1212 1960 1211 1960 1249 1960 1212 1961 1249 1961 1308 1961 1308 1962 1249 1962 1251 1962 1308 1963 1251 1963 1309 1963 1309 1964 1251 1964 1307 1964 1309 1965 1307 1965 1310 1965 1310 1966 1254 1966 1309 1966 1309 1967 1254 1967 1252 1967 1309 1968 1252 1968 1308 1968 1308 1969 1252 1969 1130 1969 1308 1970 1130 1970 1212 1970 1212 1971 1130 1971 1129 1971 1212 1972 1129 1972 1213 1972 1310 1973 1311 1973 1254 1973 1254 1974 1311 1974 1312 1974 1254 1975 1312 1975 1255 1975 1255 1976 1312 1976 1313 1976 1255 1977 1313 1977 1314 1977 1214 1978 1216 1978 1218 1978 1218 1979 1216 1979 1253 1979 1218 1980 1253 1980 1315 1980 1315 1981 1253 1981 1255 1981 1315 1982 1255 1982 1316 1982 1316 1983 1255 1983 1314 1983 1316 1984 1314 1984 1317 1984 1126 1985 1218 1985 1127 1985 1127 1986 1218 1986 1315 1986 1127 1987 1315 1987 1318 1987 1318 1988 1315 1988 1316 1988 1318 1989 1316 1989 1118 1989 1118 1990 1316 1990 1317 1990 1118 1991 1317 1991 1116 1991 1117 1992 1258 1992 1118 1992 1118 1993 1258 1993 1256 1993 1118 1994 1256 1994 1318 1994 1318 1995 1256 1995 1124 1995 1318 1996 1124 1996 1127 1996 1127 1997 1124 1997 1123 1997 1127 1998 1123 1998 1125 1998 1117 1999 1319 1999 1258 1999 1258 2000 1319 2000 1320 2000 1258 2001 1320 2001 1259 2001 1259 2002 1320 2002 1321 2002 1259 2003 1321 2003 1322 2003 1156 2004 1220 2004 1154 2004 1154 2005 1220 2005 1257 2005 1154 2006 1257 2006 1157 2006 1157 2007 1257 2007 1259 2007 1157 2008 1259 2008 1165 2008 1165 2009 1259 2009 1322 2009 1165 2010 1322 2010 1169 2010 1323 2011 1324 2011 1325 2011 1326 2012 871 2012 1327 2012 1327 2013 871 2013 872 2013 1327 2014 872 2014 1328 2014 1328 2015 872 2015 873 2015 1328 2016 873 2016 1329 2016 1329 2017 873 2017 874 2017 1329 2018 874 2018 1330 2018 1330 2019 874 2019 875 2019 1330 2020 875 2020 1325 2020 1325 2021 875 2021 876 2021 1325 2022 876 2022 1323 2022 1324 2023 1323 2023 1331 2023 1331 2024 1323 2024 879 2024 1331 2025 879 2025 1332 2025 1332 2026 879 2026 880 2026 1332 2027 880 2027 1333 2027 1333 2028 880 2028 881 2028 1333 2029 881 2029 1334 2029 1334 2030 881 2030 882 2030 1334 2031 882 2031 1335 2031 1335 2032 882 2032 883 2032 1335 2033 883 2033 1336 2033 1336 2034 883 2034 884 2034 1336 2035 884 2035 1337 2035 1326 2036 1338 2036 871 2036 871 2037 1338 2037 1339 2037 871 2038 1339 2038 870 2038 870 2039 1339 2039 1340 2039 870 2040 1340 2040 895 2040 895 2041 1340 2041 1341 2041 895 2042 1341 2042 894 2042 894 2043 1341 2043 1342 2043 894 2044 1342 2044 893 2044 893 2045 1342 2045 1343 2045 893 2046 1343 2046 892 2046 892 2047 1343 2047 1344 2047 892 2048 1344 2048 1345 2048 1345 2049 1344 2049 1346 2049 1345 2050 1346 2050 889 2050 889 2051 1346 2051 1347 2051 889 2052 1347 2052 888 2052 888 2053 1347 2053 1348 2053 888 2054 1348 2054 887 2054 887 2055 1348 2055 1349 2055 887 2056 1349 2056 886 2056 886 2057 1349 2057 1350 2057 886 2058 1350 2058 885 2058 885 2059 1350 2059 1351 2059 885 2060 1351 2060 884 2060 884 2061 1351 2061 1352 2061 884 2062 1352 2062 1337 2062 1353 2063 1354 2063 904 2063 904 2064 1354 2064 1355 2064 904 2065 1355 2065 905 2065 905 2066 1355 2066 1356 2066 905 2067 1356 2067 906 2067 906 2068 1356 2068 1357 2068 906 2069 1357 2069 907 2069 907 2070 1357 2070 1358 2070 907 2071 1358 2071 908 2071 908 2072 1358 2072 1359 2072 908 2073 1359 2073 909 2073 909 2074 1359 2074 1360 2074 909 2075 1360 2075 910 2075 910 2076 1360 2076 1361 2076 910 2077 1361 2077 911 2077 911 2078 1361 2078 1362 2078 911 2079 1362 2079 912 2079 912 2080 1362 2080 1363 2080 912 2081 1363 2081 913 2081 913 2082 1363 2082 1364 2082 913 2083 1364 2083 914 2083 914 2084 1364 2084 1365 2084 914 2085 1365 2085 1366 2085 1365 2086 1367 2086 1366 2086 1366 2087 1367 2087 1368 2087 1366 2088 1368 2088 917 2088 917 2089 1368 2089 1369 2089 917 2090 1369 2090 918 2090 918 2091 1369 2091 1370 2091 918 2092 1370 2092 919 2092 919 2093 1370 2093 1371 2093 919 2094 1371 2094 920 2094 920 2095 1371 2095 1372 2095 920 2096 1372 2096 921 2096 921 2097 1372 2097 1373 2097 921 2098 1373 2098 896 2098 896 2099 1373 2099 1374 2099 896 2100 1374 2100 897 2100 897 2101 1374 2101 1375 2101 897 2102 1375 2102 898 2102 898 2103 1375 2103 1376 2103 898 2104 1376 2104 899 2104 899 2105 1376 2105 1377 2105 899 2106 1377 2106 900 2106 900 2107 1377 2107 1378 2107 900 2108 1378 2108 901 2108 901 2109 1378 2109 1379 2109 901 2110 1379 2110 1353 2110 1353 2111 1379 2111 1380 2111 1353 2112 1380 2112 1354 2112 1381 2113 1382 2113 1383 2113 1384 2114 1385 2114 1386 2114 1385 2115 1384 2115 1387 2115 1388 2116 1162 2116 1161 2116 1389 2117 1390 2117 1391 2117 1392 2118 1391 2118 1393 2118 1394 2119 1395 2119 1392 2119 1392 2120 1395 2120 1391 2120 1391 2121 1395 2121 1396 2121 1391 2122 1396 2122 1389 2122 1397 2123 1392 2123 1398 2123 1398 2124 1392 2124 1399 2124 1397 2125 1400 2125 1392 2125 1392 2126 1400 2126 1401 2126 1392 2127 1401 2127 1394 2127 1402 2128 1403 2128 1404 2128 1404 2129 1403 2129 1405 2129 1404 2130 1405 2130 1399 2130 1399 2131 1405 2131 1406 2131 1399 2132 1406 2132 1398 2132 1407 2133 1408 2133 1409 2133 1409 2134 1408 2134 1410 2134 1409 2135 1410 2135 1402 2135 1402 2136 1410 2136 1411 2136 1402 2137 1411 2137 1403 2137 1383 2138 1412 2138 1413 2138 1414 2139 1415 2139 1382 2139 1382 2140 1415 2140 1416 2140 1382 2141 1416 2141 1383 2141 1383 2142 1416 2142 1417 2142 1383 2143 1417 2143 1412 2143 1170 2144 1418 2144 1168 2144 1168 2145 1418 2145 1414 2145 1168 2146 1414 2146 1163 2146 1163 2147 1414 2147 1382 2147 1163 2148 1382 2148 1164 2148 1164 2149 1382 2149 1381 2149 1164 2150 1381 2150 1166 2150 1166 2151 1381 2151 1167 2151 1387 2152 1388 2152 1385 2152 1385 2153 1388 2153 1161 2153 1385 2154 1161 2154 1386 2154 1386 2155 1161 2155 1160 2155 1386 2156 1160 2156 1159 2156 1162 2157 1388 2157 1152 2157 1152 2158 1388 2158 1419 2158 1152 2159 1419 2159 1153 2159 1420 2160 1421 2160 1386 2160 1386 2161 1421 2161 1422 2161 1386 2162 1422 2162 1384 2162 1423 2163 1424 2163 1425 2163 1425 2164 1424 2164 1426 2164 1425 2165 1426 2165 1427 2165 1427 2166 1426 2166 1428 2166 1429 2167 1430 2167 1431 2167 1431 2168 1430 2168 1423 2168 1431 2169 1423 2169 1432 2169 1432 2170 1423 2170 1425 2170 1432 2171 1425 2171 1433 2171 1433 2172 1425 2172 1427 2172 1433 2173 1427 2173 1420 2173 1420 2174 1427 2174 1428 2174 1420 2175 1428 2175 1421 2175 1393 2176 1434 2176 1392 2176 1392 2177 1434 2177 1435 2177 1392 2178 1435 2178 1399 2178 1399 2179 1435 2179 1436 2179 1399 2180 1436 2180 1404 2180 1404 2181 1436 2181 1437 2181 1404 2182 1437 2182 1402 2182 1402 2183 1437 2183 1438 2183 1402 2184 1438 2184 1409 2184 1409 2185 1438 2185 1439 2185 1409 2186 1439 2186 1440 2186 1440 2187 1439 2187 1441 2187 1440 2188 1441 2188 1442 2188 1158 2189 1167 2189 1442 2189 1442 2190 1167 2190 1381 2190 1442 2191 1381 2191 1440 2191 1440 2192 1381 2192 1383 2192 1440 2193 1383 2193 1409 2193 1409 2194 1383 2194 1413 2194 1409 2195 1413 2195 1407 2195 1434 2196 1443 2196 1435 2196 1435 2197 1443 2197 1429 2197 1435 2198 1429 2198 1436 2198 1436 2199 1429 2199 1431 2199 1436 2200 1431 2200 1437 2200 1437 2201 1431 2201 1432 2201 1437 2202 1432 2202 1438 2202 1438 2203 1432 2203 1433 2203 1438 2204 1433 2204 1439 2204 1439 2205 1433 2205 1420 2205 1439 2206 1420 2206 1441 2206 1441 2207 1420 2207 1386 2207 1441 2208 1386 2208 1442 2208 1442 2209 1386 2209 1159 2209 1442 2210 1159 2210 1158 2210 1444 2211 1445 2211 1446 2211 1447 2212 1448 2212 1449 2212 1450 2213 1451 2213 1452 2213 1453 2214 1454 2214 1455 2214 1456 2215 1457 2215 1458 2215 1456 2216 1458 2216 1459 2216 1455 2217 1460 2217 1456 2217 1456 2218 1460 2218 1461 2218 1461 2219 1462 2219 1456 2219 1456 2220 1462 2220 1463 2220 1456 2221 1463 2221 1457 2221 1454 2222 1464 2222 1455 2222 1455 2223 1464 2223 1465 2223 1455 2224 1465 2224 1460 2224 1466 2225 1467 2225 1468 2225 1468 2226 1469 2226 1466 2226 1466 2227 1469 2227 1470 2227 1466 2228 1470 2228 1471 2228 1472 2229 1473 2229 1474 2229 1475 2230 1476 2230 1477 2230 1477 2231 1476 2231 1472 2231 1477 2232 1472 2232 1478 2232 1478 2233 1472 2233 1474 2233 1476 2234 1479 2234 1472 2234 1472 2235 1479 2235 1480 2235 1472 2236 1480 2236 1473 2236 1473 2237 1480 2237 1481 2237 1473 2238 1481 2238 1452 2238 1452 2239 1481 2239 1482 2239 1452 2240 1482 2240 1450 2240 1475 2241 1477 2241 1483 2241 1483 2242 1477 2242 1484 2242 1483 2243 1484 2243 1485 2243 1485 2244 1484 2244 1486 2244 1486 2245 1484 2245 1487 2245 1486 2246 1487 2246 1488 2246 1489 2247 1490 2247 1491 2247 1491 2248 1490 2248 1492 2248 1491 2249 1492 2249 1487 2249 1487 2250 1492 2250 1493 2250 1487 2251 1493 2251 1488 2251 1489 2252 1491 2252 1494 2252 1494 2253 1491 2253 1446 2253 1494 2254 1446 2254 1495 2254 1496 2255 1497 2255 1498 2255 1496 2256 1498 2256 1499 2256 1495 2257 1446 2257 1498 2257 1498 2258 1446 2258 1445 2258 1498 2259 1445 2259 1499 2259 1500 2260 1501 2260 1502 2260 1458 2261 1503 2261 1459 2261 1459 2262 1503 2262 1504 2262 1459 2263 1504 2263 1505 2263 1505 2264 1504 2264 1506 2264 1505 2265 1506 2265 1500 2265 1500 2266 1502 2266 1505 2266 1505 2267 1502 2267 1507 2267 1505 2268 1507 2268 1508 2268 1508 2269 1447 2269 1505 2269 1505 2270 1447 2270 1449 2270 1505 2271 1449 2271 1459 2271 1459 2272 1449 2272 1509 2272 1459 2273 1509 2273 1456 2273 1456 2274 1509 2274 1510 2274 1456 2275 1510 2275 1455 2275 1455 2276 1510 2276 1471 2276 1455 2277 1471 2277 1453 2277 1453 2278 1471 2278 1470 2278 1448 2279 1444 2279 1449 2279 1449 2280 1444 2280 1446 2280 1449 2281 1446 2281 1509 2281 1509 2282 1446 2282 1491 2282 1509 2283 1491 2283 1510 2283 1510 2284 1491 2284 1487 2284 1510 2285 1487 2285 1471 2285 1471 2286 1487 2286 1484 2286 1471 2287 1484 2287 1466 2287 1466 2288 1484 2288 1477 2288 1466 2289 1477 2289 1467 2289 1467 2290 1477 2290 1478 2290 961 2291 1511 2291 959 2291 959 2292 1511 2292 1512 2292 959 2293 1512 2293 958 2293 958 2294 1512 2294 950 2294 950 2295 1512 2295 1513 2295 950 2296 1513 2296 951 2296 951 2297 1513 2297 1514 2297 951 2298 1514 2298 952 2298 952 2299 1514 2299 956 2299 956 2300 1514 2300 1515 2300 956 2301 1515 2301 953 2301 1515 2302 1516 2302 953 2302 953 2303 1516 2303 1517 2303 953 2304 1517 2304 954 2304 1518 2305 1519 2305 1520 2305 1521 2306 1522 2306 1523 2306 1524 2307 1525 2307 1526 2307 1527 2308 1528 2308 1529 2308 1529 2309 1530 2309 1527 2309 1527 2310 1530 2310 1531 2310 1527 2311 1531 2311 1525 2311 1525 2312 1531 2312 1532 2312 1525 2313 1532 2313 1526 2313 1533 2314 1534 2314 1526 2314 1526 2315 1534 2315 1535 2315 1526 2316 1535 2316 1524 2316 1536 2317 1537 2317 1538 2317 1537 2318 1536 2318 1539 2318 1539 2319 1536 2319 1540 2319 1539 2320 1540 2320 1541 2320 1542 2321 1543 2321 1544 2321 1544 2322 1543 2322 1545 2322 1546 2323 1547 2323 1548 2323 1548 2324 1547 2324 1549 2324 1548 2325 1549 2325 1543 2325 1543 2326 1549 2326 1550 2326 1543 2327 1550 2327 1545 2327 1546 2328 1548 2328 1551 2328 1551 2329 1548 2329 1552 2329 1551 2330 1552 2330 1553 2330 1553 2331 1552 2331 1554 2331 1553 2332 1554 2332 1555 2332 1555 2333 1554 2333 1523 2333 1523 2334 1554 2334 1556 2334 1523 2335 1556 2335 1521 2335 1519 2336 1557 2336 1558 2336 1559 2337 1560 2337 1561 2337 1561 2338 1560 2338 1562 2338 1561 2339 1562 2339 1563 2339 1563 2340 1562 2340 1564 2340 1563 2341 1564 2341 1520 2341 1520 2342 1564 2342 1565 2342 1520 2343 1565 2343 1518 2343 1559 2344 1561 2344 1566 2344 1566 2345 1561 2345 1567 2345 1566 2346 1567 2346 1568 2346 1532 2347 1569 2347 1526 2347 1526 2348 1569 2348 1570 2348 1526 2349 1570 2349 1533 2349 1533 2350 1570 2350 1571 2350 1533 2351 1571 2351 1567 2351 1567 2352 1571 2352 1572 2352 1567 2353 1572 2353 1568 2353 1573 2354 1574 2354 1554 2354 1554 2355 1574 2355 1575 2355 1554 2356 1575 2356 1556 2356 1542 2357 1541 2357 1543 2357 1543 2358 1541 2358 1540 2358 1543 2359 1540 2359 1548 2359 1548 2360 1540 2360 1576 2360 1548 2361 1576 2361 1552 2361 1552 2362 1576 2362 1577 2362 1552 2363 1577 2363 1554 2363 1554 2364 1577 2364 1578 2364 1554 2365 1578 2365 1573 2365 1573 2366 1578 2366 1579 2366 1519 2367 1558 2367 1520 2367 1520 2368 1558 2368 1580 2368 1520 2369 1580 2369 1581 2369 1538 2370 1534 2370 1536 2370 1536 2371 1534 2371 1533 2371 1536 2372 1533 2372 1540 2372 1540 2373 1533 2373 1567 2373 1540 2374 1567 2374 1576 2374 1576 2375 1567 2375 1561 2375 1576 2376 1561 2376 1577 2376 1577 2377 1561 2377 1563 2377 1577 2378 1563 2378 1578 2378 1578 2379 1563 2379 1520 2379 1578 2380 1520 2380 1579 2380 1579 2381 1520 2381 1581 2381 1582 2382 1170 2382 1169 2382 1583 2383 1584 2383 1585 2383 1585 2384 1584 2384 1586 2384 1587 2385 1588 2385 1583 2385 1583 2386 1588 2386 1589 2386 1583 2387 1589 2387 1584 2387 1590 2388 1591 2388 1322 2388 1322 2389 1591 2389 1592 2389 1322 2390 1592 2390 1593 2390 1593 2391 1594 2391 1322 2391 1322 2392 1594 2392 1595 2392 1322 2393 1595 2393 1169 2393 1169 2394 1595 2394 1596 2394 1169 2395 1596 2395 1582 2395 1584 2396 1590 2396 1586 2396 1586 2397 1590 2397 1322 2397 1586 2398 1322 2398 1597 2398 1597 2399 1322 2399 1321 2399 1597 2400 1321 2400 1598 2400 1598 2401 1321 2401 1320 2401 1598 2402 1320 2402 1599 2402 1599 2403 1320 2403 1319 2403 1599 2404 1319 2404 1600 2404 1600 2405 1319 2405 1117 2405 1600 2406 1117 2406 1601 2406 1601 2407 1117 2407 1116 2407 1601 2408 1116 2408 1602 2408 1602 2409 1116 2409 1317 2409 1602 2410 1317 2410 1603 2410 1603 2411 1317 2411 1314 2411 1603 2412 1314 2412 1604 2412 1311 2413 1605 2413 1312 2413 1312 2414 1605 2414 1606 2414 1604 2415 1314 2415 1606 2415 1606 2416 1314 2416 1313 2416 1606 2417 1313 2417 1312 2417 1119 2418 1607 2418 1120 2418 1120 2419 1607 2419 1528 2419 1525 2420 1524 2420 1608 2420 1527 2421 1305 2421 1528 2421 1528 2422 1305 2422 1304 2422 1528 2423 1304 2423 1120 2423 1527 2424 1525 2424 1305 2424 1305 2425 1525 2425 1608 2425 1305 2426 1608 2426 1306 2426 1306 2427 1608 2427 1609 2427 1306 2428 1609 2428 1307 2428 1307 2429 1609 2429 1610 2429 1307 2430 1610 2430 1310 2430 1310 2431 1610 2431 1611 2431 1310 2432 1611 2432 1311 2432 1311 2433 1611 2433 1612 2433 1311 2434 1612 2434 1605 2434 1524 2435 1535 2435 1608 2435 1608 2436 1535 2436 1534 2436 1608 2437 1534 2437 1613 2437 1613 2438 1534 2438 1538 2438 1478 2439 1474 2439 1279 2439 1468 2440 1467 2440 1614 2440 1614 2441 1467 2441 1615 2441 1474 2442 1473 2442 1279 2442 1279 2443 1473 2443 1452 2443 1279 2444 1452 2444 1280 2444 1280 2445 1452 2445 1451 2445 1280 2446 1451 2446 1281 2446 1281 2447 1451 2447 1616 2447 1281 2448 1616 2448 1282 2448 1282 2449 1616 2449 1617 2449 1282 2450 1617 2450 1286 2450 1286 2451 1617 2451 1618 2451 1286 2452 1618 2452 1287 2452 1287 2453 1618 2453 1619 2453 1287 2454 1619 2454 1288 2454 1288 2455 1619 2455 1620 2455 1288 2456 1620 2456 1289 2456 1289 2457 1620 2457 1621 2457 1289 2458 1621 2458 1290 2458 1290 2459 1621 2459 1622 2459 1290 2460 1622 2460 1293 2460 1293 2461 1622 2461 1623 2461 1293 2462 1623 2462 1294 2462 1294 2463 1623 2463 1624 2463 1294 2464 1624 2464 1295 2464 1295 2465 1624 2465 1625 2465 1295 2466 1625 2466 1296 2466 1296 2467 1625 2467 1626 2467 1296 2468 1626 2468 1297 2468 1297 2469 1626 2469 1627 2469 1297 2470 1627 2470 1298 2470 1298 2471 1627 2471 1628 2471 1298 2472 1628 2472 1299 2472 1299 2473 1628 2473 1629 2473 1299 2474 1629 2474 1302 2474 1302 2475 1629 2475 1630 2475 1302 2476 1630 2476 1119 2476 1119 2477 1630 2477 1631 2477 1119 2478 1631 2478 1607 2478 1632 2479 1633 2479 1265 2479 1265 2480 1633 2480 1634 2480 1265 2481 1634 2481 1269 2481 1269 2482 1634 2482 1635 2482 1269 2483 1635 2483 1270 2483 1270 2484 1635 2484 1636 2484 1270 2485 1636 2485 1271 2485 1271 2486 1636 2486 1637 2486 1271 2487 1637 2487 1272 2487 1272 2488 1637 2488 1638 2488 1272 2489 1638 2489 1273 2489 1273 2490 1638 2490 1639 2490 1273 2491 1639 2491 1276 2491 1276 2492 1639 2492 1640 2492 1276 2493 1640 2493 1277 2493 1277 2494 1640 2494 1641 2494 1277 2495 1641 2495 1278 2495 1278 2496 1641 2496 1642 2496 1278 2497 1642 2497 1279 2497 1279 2498 1642 2498 1615 2498 1279 2499 1615 2499 1478 2499 1478 2500 1615 2500 1467 2500 1265 2501 1264 2501 1632 2501 1632 2502 1264 2502 1263 2502 1632 2503 1263 2503 1643 2503 1643 2504 1263 2504 1262 2504 1643 2505 1262 2505 1644 2505 1644 2506 1262 2506 1261 2506 1645 2507 1260 2507 1646 2507 1646 2508 1260 2508 1172 2508 1646 2509 1172 2509 1647 2509 1647 2510 1172 2510 1011 2510 1645 2511 1648 2511 1260 2511 1260 2512 1648 2512 1649 2512 1260 2513 1649 2513 1650 2513 1650 2514 1651 2514 1260 2514 1260 2515 1651 2515 1652 2515 1260 2516 1652 2516 1261 2516 1261 2517 1652 2517 1653 2517 1261 2518 1653 2518 1644 2518 1651 2519 1654 2519 1652 2519 1652 2520 1654 2520 1655 2520 1652 2521 1655 2521 1517 2521 1517 2522 1655 2522 1656 2522 1517 2523 1656 2523 954 2523 1657 2524 1658 2524 1659 2524 1659 2525 1658 2525 1660 2525 1659 2526 1660 2526 1661 2526 1660 2527 1662 2527 1661 2527 1661 2528 1662 2528 1663 2528 1661 2529 1663 2529 1664 2529 1664 2530 1663 2530 1665 2530 1659 2531 1666 2531 1657 2531 1657 2532 1666 2532 1667 2532 1657 2533 1667 2533 1668 2533 1668 2534 1669 2534 1657 2534 1657 2535 1669 2535 1670 2535 1657 2536 1670 2536 1671 2536 1671 2537 1672 2537 1657 2537 1657 2538 1672 2538 1673 2538 1657 2539 1673 2539 1674 2539 1674 2540 1675 2540 1657 2540 1657 2541 1675 2541 1676 2541 1657 2542 1676 2542 1677 2542 1678 2543 1679 2543 1680 2543 1680 2544 1679 2544 1681 2544 1680 2545 1681 2545 1682 2545 1663 2546 1683 2546 1665 2546 1665 2547 1683 2547 1679 2547 1665 2548 1679 2548 1684 2548 1684 2549 1679 2549 1678 2549 987 2550 986 2550 1685 2550 1685 2551 986 2551 985 2551 985 2552 998 2552 1685 2552 1685 2553 998 2553 1000 2553 1685 2554 1000 2554 1001 2554 1686 2555 1687 2555 1688 2555 968 2556 981 2556 1686 2556 1686 2557 981 2557 980 2557 1686 2558 989 2558 1685 2558 1685 2559 989 2559 988 2559 1685 2560 988 2560 987 2560 1688 2561 1689 2561 1686 2561 1686 2562 1689 2562 1690 2562 1686 2563 1690 2563 1691 2563 1691 2564 1692 2564 1686 2564 1686 2565 1692 2565 1693 2565 1686 2566 1693 2566 1694 2566 1032 2567 975 2567 1694 2567 1694 2568 975 2568 977 2568 1694 2569 977 2569 1686 2569 1686 2570 977 2570 978 2570 1686 2571 978 2571 968 2571 980 2572 966 2572 1686 2572 1686 2573 966 2573 965 2573 1686 2574 965 2574 989 2574 1096 2575 1095 2575 1695 2575 1696 2576 1091 2576 1090 2576 1106 2577 1697 2577 1107 2577 1107 2578 1697 2578 1095 2578 1697 2579 1698 2579 1095 2579 1095 2580 1698 2580 1699 2580 1095 2581 1699 2581 1695 2581 1695 2582 1699 2582 1700 2582 1695 2583 1700 2583 1701 2583 1087 2584 1085 2584 1695 2584 1695 2585 1085 2585 1094 2585 1695 2586 1094 2586 1093 2586 1106 2587 1115 2587 1697 2587 1697 2588 1115 2588 1114 2588 1697 2589 1114 2589 1702 2589 1702 2590 1114 2590 1033 2590 1701 2591 1703 2591 1695 2591 1695 2592 1703 2592 1704 2592 1695 2593 1704 2593 1705 2593 1696 2594 1090 2594 1695 2594 1695 2595 1090 2595 1088 2595 1695 2596 1088 2596 1087 2596 1093 2597 1100 2597 1695 2597 1695 2598 1100 2598 1098 2598 1695 2599 1098 2599 1096 2599 1706 2600 1707 2600 1708 2600 1709 2601 1710 2601 1711 2601 1712 2602 1713 2602 1714 2602 1715 2603 1716 2603 1717 2603 1718 2604 1719 2604 1720 2604 1721 2605 1722 2605 1723 2605 1723 2606 1722 2606 1724 2606 1723 2607 1724 2607 1725 2607 1718 2608 1726 2608 1719 2608 1719 2609 1726 2609 1727 2609 1719 2610 1727 2610 1723 2610 1723 2611 1727 2611 1728 2611 1723 2612 1728 2612 1721 2612 1729 2613 1730 2613 1720 2613 1720 2614 1730 2614 1731 2614 1720 2615 1731 2615 1718 2615 1732 2616 1733 2616 1734 2616 1735 2617 1736 2617 1737 2617 1737 2618 1736 2618 1738 2618 1737 2619 1738 2619 1739 2619 1740 2620 1735 2620 1717 2620 1717 2621 1735 2621 1737 2621 1717 2622 1737 2622 1715 2622 1715 2623 1737 2623 1741 2623 1715 2624 1741 2624 1742 2624 1742 2625 1741 2625 1713 2625 1742 2626 1713 2626 1743 2626 1743 2627 1713 2627 1712 2627 1744 2628 1745 2628 1714 2628 1714 2629 1745 2629 1746 2629 1714 2630 1746 2630 1712 2630 1747 2631 1748 2631 1749 2631 1750 2632 1751 2632 1749 2632 1749 2633 1751 2633 1752 2633 1749 2634 1752 2634 1747 2634 1747 2635 1752 2635 1753 2635 1747 2636 1753 2636 1754 2636 1755 2637 1756 2637 1757 2637 1757 2638 1756 2638 1758 2638 1757 2639 1758 2639 1759 2639 1759 2640 1758 2640 1760 2640 1759 2641 1760 2641 1708 2641 1708 2642 1760 2642 1761 2642 1708 2643 1761 2643 1706 2643 1706 2644 1761 2644 1762 2644 1763 2645 1723 2645 1764 2645 1764 2646 1723 2646 1725 2646 1764 2647 1725 2647 1765 2647 1765 2648 1725 2648 1766 2648 1765 2649 1766 2649 1767 2649 1733 2650 1729 2650 1734 2650 1734 2651 1729 2651 1720 2651 1734 2652 1720 2652 1768 2652 1768 2653 1720 2653 1769 2653 1769 2654 1720 2654 1719 2654 1769 2655 1719 2655 1770 2655 1770 2656 1719 2656 1723 2656 1770 2657 1723 2657 1771 2657 1771 2658 1723 2658 1763 2658 1771 2659 1763 2659 1772 2659 1739 2660 1732 2660 1737 2660 1737 2661 1732 2661 1734 2661 1737 2662 1734 2662 1741 2662 1741 2663 1734 2663 1768 2663 1741 2664 1768 2664 1713 2664 1713 2665 1768 2665 1769 2665 1713 2666 1769 2666 1714 2666 1714 2667 1769 2667 1770 2667 1714 2668 1770 2668 1744 2668 1744 2669 1770 2669 1771 2669 1744 2670 1771 2670 1755 2670 1755 2671 1771 2671 1772 2671 1755 2672 1772 2672 1756 2672 1709 2673 1711 2673 1754 2673 1754 2674 1711 2674 1773 2674 1754 2675 1773 2675 1747 2675 1747 2676 1773 2676 1774 2676 1747 2677 1774 2677 1748 2677 1710 2678 1745 2678 1711 2678 1711 2679 1745 2679 1744 2679 1711 2680 1744 2680 1773 2680 1773 2681 1744 2681 1755 2681 1773 2682 1755 2682 1774 2682 1774 2683 1755 2683 1757 2683 1774 2684 1757 2684 1748 2684 1748 2685 1757 2685 1759 2685 1748 2686 1759 2686 1749 2686 1749 2687 1759 2687 1708 2687 1749 2688 1708 2688 1750 2688 1750 2689 1708 2689 1707 2689 1775 2690 1331 2690 1332 2690 1144 2691 1143 2691 1342 2691 1141 2692 1140 2692 1344 2692 1336 2693 1337 2693 1215 2693 1351 2694 1209 2694 1213 2694 1351 2695 1213 2695 1352 2695 1213 2696 1129 2696 1352 2696 1352 2697 1129 2697 1128 2697 1352 2698 1128 2698 1337 2698 1337 2699 1128 2699 1217 2699 1337 2700 1217 2700 1215 2700 1209 2701 1351 2701 1210 2701 1210 2702 1351 2702 1350 2702 1210 2703 1350 2703 1131 2703 1349 2704 1204 2704 1208 2704 1349 2705 1208 2705 1350 2705 1350 2706 1208 2706 1132 2706 1350 2707 1132 2707 1131 2707 1204 2708 1349 2708 1205 2708 1205 2709 1349 2709 1348 2709 1205 2710 1348 2710 1134 2710 1347 2711 1199 2711 1203 2711 1347 2712 1203 2712 1348 2712 1348 2713 1203 2713 1135 2713 1348 2714 1135 2714 1134 2714 1199 2715 1347 2715 1200 2715 1200 2716 1347 2716 1776 2716 1200 2717 1776 2717 1137 2717 1344 2718 1140 2718 1776 2718 1776 2719 1140 2719 1138 2719 1776 2720 1138 2720 1137 2720 1141 2721 1344 2721 1197 2721 1197 2722 1344 2722 1343 2722 1197 2723 1343 2723 1198 2723 1342 2724 1143 2724 1343 2724 1343 2725 1143 2725 1195 2725 1343 2726 1195 2726 1198 2726 1144 2727 1342 2727 1194 2727 1194 2728 1342 2728 1341 2728 1194 2729 1341 2729 1190 2729 1340 2730 1146 2730 1341 2730 1341 2731 1146 2731 1191 2731 1341 2732 1191 2732 1190 2732 1339 2733 1189 2733 1340 2733 1340 2734 1189 2734 1147 2734 1340 2735 1147 2735 1146 2735 1182 2736 1187 2736 1326 2736 1326 2737 1187 2737 1186 2737 1326 2738 1186 2738 1338 2738 1338 2739 1186 2739 1184 2739 1338 2740 1184 2740 1339 2740 1339 2741 1184 2741 1183 2741 1339 2742 1183 2742 1189 2742 1182 2743 1326 2743 1181 2743 1181 2744 1326 2744 1327 2744 1181 2745 1327 2745 1177 2745 1177 2746 1327 2746 1178 2746 1178 2747 1327 2747 1328 2747 1178 2748 1328 2748 1149 2748 1329 2749 1176 2749 1328 2749 1328 2750 1176 2750 1150 2750 1328 2751 1150 2751 1149 2751 1685 2752 1001 2752 1329 2752 1329 2753 1001 2753 1175 2753 1329 2754 1175 2754 1176 2754 1687 2755 1686 2755 1325 2755 1325 2756 1686 2756 1685 2756 1325 2757 1685 2757 1330 2757 1330 2758 1685 2758 1329 2758 1324 2759 1777 2759 1778 2759 1778 2760 1779 2760 1324 2760 1324 2761 1779 2761 1780 2761 1324 2762 1780 2762 1325 2762 1325 2763 1780 2763 1781 2763 1325 2764 1781 2764 1687 2764 1782 2765 1783 2765 1324 2765 1324 2766 1783 2766 1784 2766 1324 2767 1784 2767 1777 2767 1775 2768 1785 2768 1331 2768 1331 2769 1785 2769 1786 2769 1331 2770 1786 2770 1324 2770 1324 2771 1786 2771 1787 2771 1324 2772 1787 2772 1782 2772 1156 2773 1155 2773 1333 2773 1333 2774 1155 2774 1153 2774 1333 2775 1153 2775 1332 2775 1332 2776 1153 2776 1788 2776 1332 2777 1788 2777 1775 2777 1156 2778 1333 2778 1221 2778 1221 2779 1333 2779 1334 2779 1221 2780 1334 2780 1122 2780 1335 2781 1125 2781 1334 2781 1334 2782 1125 2782 1123 2782 1334 2783 1123 2783 1122 2783 1215 2784 1214 2784 1336 2784 1336 2785 1214 2785 1219 2785 1336 2786 1219 2786 1335 2786 1335 2787 1219 2787 1126 2787 1335 2788 1126 2788 1125 2788 1789 2789 1356 2789 1355 2789 1790 2790 1791 2790 1370 2790 1792 2791 1375 2791 1793 2791 1793 2792 1375 2792 1374 2792 1794 2793 1795 2793 1373 2793 1373 2794 1795 2794 1796 2794 1373 2795 1796 2795 1374 2795 1374 2796 1796 2796 1797 2796 1374 2797 1797 2797 1793 2797 1794 2798 1373 2798 1798 2798 1798 2799 1373 2799 1372 2799 1798 2800 1372 2800 1799 2800 1799 2801 1372 2801 1800 2801 1800 2802 1372 2802 1371 2802 1800 2803 1371 2803 1801 2803 1370 2804 1791 2804 1371 2804 1371 2805 1791 2805 1802 2805 1371 2806 1802 2806 1801 2806 1790 2807 1370 2807 1803 2807 1803 2808 1370 2808 1369 2808 1803 2809 1369 2809 1804 2809 1368 2810 1367 2810 1805 2810 1805 2811 1806 2811 1368 2811 1368 2812 1806 2812 1807 2812 1368 2813 1807 2813 1369 2813 1369 2814 1807 2814 1808 2814 1369 2815 1808 2815 1804 2815 1809 2816 1810 2816 1365 2816 1365 2817 1810 2817 1811 2817 1365 2818 1811 2818 1367 2818 1367 2819 1811 2819 1812 2819 1367 2820 1812 2820 1805 2820 1809 2821 1365 2821 1813 2821 1813 2822 1365 2822 1364 2822 1813 2823 1364 2823 1814 2823 1814 2824 1364 2824 1815 2824 1815 2825 1364 2825 1363 2825 1815 2826 1363 2826 1816 2826 1361 2827 1817 2827 1818 2827 1361 2828 1818 2828 1362 2828 1818 2829 1819 2829 1362 2829 1362 2830 1819 2830 1820 2830 1362 2831 1820 2831 1363 2831 1363 2832 1820 2832 1821 2832 1363 2833 1821 2833 1816 2833 1359 2834 1822 2834 1823 2834 1359 2835 1823 2835 1360 2835 1823 2836 1824 2836 1360 2836 1360 2837 1824 2837 1825 2837 1360 2838 1825 2838 1361 2838 1361 2839 1825 2839 1826 2839 1361 2840 1826 2840 1817 2840 1358 2841 1827 2841 1359 2841 1359 2842 1827 2842 1828 2842 1359 2843 1828 2843 1822 2843 1357 2844 1829 2844 1358 2844 1358 2845 1829 2845 1830 2845 1358 2846 1830 2846 1827 2846 1789 2847 1762 2847 1356 2847 1356 2848 1762 2848 1831 2848 1356 2849 1831 2849 1357 2849 1357 2850 1831 2850 1832 2850 1357 2851 1832 2851 1829 2851 1833 2852 1354 2852 1834 2852 1834 2853 1354 2853 1835 2853 1833 2854 1836 2854 1354 2854 1354 2855 1836 2855 1837 2855 1354 2856 1837 2856 1355 2856 1355 2857 1837 2857 1838 2857 1355 2858 1838 2858 1789 2858 1380 2859 1839 2859 1840 2859 1840 2860 1841 2860 1380 2860 1380 2861 1841 2861 1842 2861 1380 2862 1842 2862 1354 2862 1354 2863 1842 2863 1843 2863 1354 2864 1843 2864 1835 2864 1695 2865 1705 2865 1380 2865 1705 2866 1844 2866 1380 2866 1380 2867 1844 2867 1845 2867 1380 2868 1845 2868 1839 2868 1091 2869 1696 2869 1378 2869 1378 2870 1696 2870 1695 2870 1378 2871 1695 2871 1379 2871 1379 2872 1695 2872 1380 2872 1377 2873 1376 2873 1846 2873 1846 2874 1847 2874 1377 2874 1377 2875 1847 2875 1848 2875 1377 2876 1848 2876 1378 2876 1378 2877 1848 2877 1849 2877 1378 2878 1849 2878 1091 2878 1792 2879 1850 2879 1375 2879 1375 2880 1850 2880 1851 2880 1375 2881 1851 2881 1376 2881 1376 2882 1851 2882 1852 2882 1376 2883 1852 2883 1846 2883 1434 2884 1393 2884 1853 2884 1775 2885 1853 2885 1854 2885 1153 2886 1419 2886 1788 2886 1788 2887 1419 2887 1388 2887 1788 2888 1388 2888 1387 2888 1428 2889 1775 2889 1421 2889 1421 2890 1775 2890 1788 2890 1428 2891 1426 2891 1775 2891 1775 2892 1426 2892 1424 2892 1775 2893 1424 2893 1423 2893 1387 2894 1384 2894 1788 2894 1788 2895 1384 2895 1422 2895 1788 2896 1422 2896 1421 2896 1854 2897 1855 2897 1775 2897 1775 2898 1855 2898 1856 2898 1775 2899 1856 2899 1857 2899 1785 2900 1775 2900 1858 2900 1858 2901 1775 2901 1859 2901 1857 2902 1860 2902 1775 2902 1775 2903 1860 2903 1861 2903 1775 2904 1861 2904 1859 2904 1423 2905 1430 2905 1775 2905 1775 2906 1430 2906 1429 2906 1775 2907 1429 2907 1853 2907 1853 2908 1429 2908 1443 2908 1853 2909 1443 2909 1434 2909 1837 2910 1862 2910 1838 2910 1838 2911 1862 2911 1863 2911 1838 2912 1863 2912 1864 2912 1838 2913 1746 2913 1745 2913 1716 2914 1715 2914 1865 2914 1865 2915 1715 2915 1742 2915 1745 2916 1710 2916 1838 2916 1838 2917 1710 2917 1709 2917 1838 2918 1709 2918 1754 2918 1751 2919 1750 2919 1838 2919 1838 2920 1750 2920 1707 2920 1838 2921 1707 2921 1789 2921 1789 2922 1707 2922 1706 2922 1789 2923 1706 2923 1762 2923 1865 2924 1746 2924 1866 2924 1866 2925 1746 2925 1838 2925 1866 2926 1838 2926 1867 2926 1867 2927 1838 2927 1864 2927 1742 2928 1743 2928 1865 2928 1865 2929 1743 2929 1712 2929 1865 2930 1712 2930 1746 2930 1754 2931 1753 2931 1838 2931 1838 2932 1753 2932 1752 2932 1838 2933 1752 2933 1751 2933 1583 2934 1585 2934 1868 2934 1587 2935 1583 2935 1869 2935 1869 2936 1583 2936 1868 2936 1869 2937 1868 2937 1870 2937 1870 2938 1868 2938 1871 2938 1872 2939 1873 2939 1874 2939 1874 2940 1873 2940 1875 2940 1876 2941 1873 2941 1877 2941 1877 2942 1873 2942 1872 2942 1877 2943 1872 2943 1878 2943 1876 2944 1879 2944 1873 2944 1873 2945 1879 2945 1880 2945 1873 2946 1880 2946 1871 2946 1871 2947 1880 2947 1881 2947 1871 2948 1881 2948 1870 2948 1480 2949 1479 2949 1882 2949 1883 2950 1884 2950 1885 2950 1568 2951 1572 2951 1886 2951 1532 2952 1531 2952 1887 2952 1887 2953 1531 2953 1530 2953 1887 2954 1530 2954 1529 2954 1571 2955 1570 2955 1888 2955 1888 2956 1570 2956 1569 2956 1568 2957 1886 2957 1566 2957 1565 2958 1564 2958 1889 2958 1564 2959 1562 2959 1889 2959 1889 2960 1562 2960 1560 2960 1889 2961 1560 2961 1559 2961 1890 2962 1557 2962 1891 2962 1891 2963 1557 2963 1519 2963 1891 2964 1519 2964 1518 2964 1892 2965 1893 2965 1891 2965 1891 2966 1893 2966 1894 2966 1891 2967 1894 2967 1890 2967 1895 2968 1896 2968 1897 2968 1895 2969 1897 2969 1898 2969 1897 2970 1899 2970 1898 2970 1898 2971 1899 2971 1900 2971 1898 2972 1900 2972 1892 2972 1892 2973 1900 2973 1901 2973 1892 2974 1901 2974 1893 2974 1896 2975 1895 2975 1902 2975 1902 2976 1895 2976 1903 2976 1902 2977 1903 2977 1904 2977 1904 2978 1903 2978 1905 2978 1905 2979 1903 2979 1906 2979 1905 2980 1906 2980 1907 2980 1885 2981 1884 2981 1906 2981 1906 2982 1884 2982 1908 2982 1906 2983 1908 2983 1907 2983 1883 2984 1885 2984 1909 2984 1909 2985 1885 2985 1910 2985 1909 2986 1910 2986 1911 2986 1911 2987 1910 2987 1912 2987 1912 2988 1910 2988 1913 2988 1912 2989 1913 2989 1914 2989 1489 2990 1494 2990 1915 2990 1915 2991 1494 2991 1495 2991 1915 2992 1495 2992 1498 2992 1914 2993 1913 2993 1916 2993 1916 2994 1913 2994 1915 2994 1916 2995 1915 2995 1917 2995 1917 2996 1915 2996 1498 2996 1917 2997 1498 2997 1497 2997 1486 2998 1488 2998 1918 2998 1488 2999 1493 2999 1918 2999 1918 3000 1493 3000 1492 3000 1918 3001 1492 3001 1490 3001 1476 3002 1475 3002 1919 3002 1919 3003 1475 3003 1483 3003 1919 3004 1483 3004 1485 3004 1920 3005 1450 3005 1482 3005 1480 3006 1882 3006 1481 3006 1451 3007 1450 3007 1616 3007 1616 3008 1450 3008 1920 3008 1616 3009 1920 3009 1617 3009 1617 3010 1920 3010 1921 3010 1617 3011 1921 3011 1618 3011 1618 3012 1921 3012 1619 3012 1619 3013 1921 3013 1922 3013 1619 3014 1922 3014 1620 3014 1620 3015 1922 3015 1621 3015 1621 3016 1922 3016 1923 3016 1621 3017 1923 3017 1622 3017 1622 3018 1923 3018 1924 3018 1622 3019 1924 3019 1623 3019 1623 3020 1924 3020 1624 3020 1624 3021 1924 3021 1925 3021 1624 3022 1925 3022 1625 3022 1625 3023 1925 3023 1626 3023 1626 3024 1925 3024 1926 3024 1626 3025 1926 3025 1627 3025 1627 3026 1926 3026 1927 3026 1627 3027 1927 3027 1628 3027 1628 3028 1927 3028 1629 3028 1629 3029 1927 3029 1928 3029 1629 3030 1928 3030 1630 3030 1630 3031 1928 3031 1631 3031 1631 3032 1928 3032 1887 3032 1631 3033 1887 3033 1607 3033 1607 3034 1887 3034 1529 3034 1607 3035 1529 3035 1528 3035 1569 3036 1532 3036 1888 3036 1888 3037 1532 3037 1887 3037 1888 3038 1887 3038 1929 3038 1929 3039 1887 3039 1928 3039 1929 3040 1928 3040 1930 3040 1930 3041 1928 3041 1927 3041 1930 3042 1927 3042 1931 3042 1931 3043 1927 3043 1926 3043 1931 3044 1926 3044 1932 3044 1932 3045 1926 3045 1925 3045 1932 3046 1925 3046 1933 3046 1933 3047 1925 3047 1924 3047 1933 3048 1924 3048 1934 3048 1934 3049 1924 3049 1923 3049 1934 3050 1923 3050 1935 3050 1935 3051 1923 3051 1922 3051 1935 3052 1922 3052 1936 3052 1936 3053 1922 3053 1921 3053 1936 3054 1921 3054 1882 3054 1882 3055 1921 3055 1920 3055 1882 3056 1920 3056 1481 3056 1481 3057 1920 3057 1482 3057 1572 3058 1571 3058 1886 3058 1886 3059 1571 3059 1888 3059 1886 3060 1888 3060 1937 3060 1937 3061 1888 3061 1929 3061 1937 3062 1929 3062 1938 3062 1938 3063 1929 3063 1930 3063 1938 3064 1930 3064 1939 3064 1939 3065 1930 3065 1931 3065 1939 3066 1931 3066 1940 3066 1940 3067 1931 3067 1932 3067 1940 3068 1932 3068 1941 3068 1941 3069 1932 3069 1933 3069 1941 3070 1933 3070 1942 3070 1942 3071 1933 3071 1934 3071 1942 3072 1934 3072 1943 3072 1943 3073 1934 3073 1935 3073 1943 3074 1935 3074 1944 3074 1944 3075 1935 3075 1936 3075 1944 3076 1936 3076 1919 3076 1919 3077 1936 3077 1882 3077 1919 3078 1882 3078 1476 3078 1476 3079 1882 3079 1479 3079 1559 3080 1566 3080 1889 3080 1889 3081 1566 3081 1886 3081 1889 3082 1886 3082 1945 3082 1945 3083 1886 3083 1937 3083 1945 3084 1937 3084 1946 3084 1946 3085 1937 3085 1938 3085 1946 3086 1938 3086 1947 3086 1947 3087 1938 3087 1939 3087 1947 3088 1939 3088 1948 3088 1948 3089 1939 3089 1940 3089 1948 3090 1940 3090 1949 3090 1949 3091 1940 3091 1941 3091 1949 3092 1941 3092 1950 3092 1950 3093 1941 3093 1942 3093 1950 3094 1942 3094 1951 3094 1951 3095 1942 3095 1943 3095 1951 3096 1943 3096 1952 3096 1952 3097 1943 3097 1944 3097 1952 3098 1944 3098 1918 3098 1918 3099 1944 3099 1919 3099 1918 3100 1919 3100 1486 3100 1486 3101 1919 3101 1485 3101 1518 3102 1565 3102 1891 3102 1891 3103 1565 3103 1889 3103 1891 3104 1889 3104 1892 3104 1892 3105 1889 3105 1945 3105 1892 3106 1945 3106 1898 3106 1898 3107 1945 3107 1946 3107 1898 3108 1946 3108 1895 3108 1895 3109 1946 3109 1947 3109 1895 3110 1947 3110 1903 3110 1903 3111 1947 3111 1948 3111 1903 3112 1948 3112 1906 3112 1906 3113 1948 3113 1949 3113 1906 3114 1949 3114 1885 3114 1885 3115 1949 3115 1950 3115 1885 3116 1950 3116 1910 3116 1910 3117 1950 3117 1951 3117 1910 3118 1951 3118 1913 3118 1913 3119 1951 3119 1952 3119 1913 3120 1952 3120 1915 3120 1915 3121 1952 3121 1918 3121 1915 3122 1918 3122 1489 3122 1489 3123 1918 3123 1490 3123 1953 3124 1954 3124 1955 3124 1615 3125 1642 3125 1956 3125 1516 3126 1515 3126 1957 3126 1514 3127 1513 3127 1958 3127 1512 3128 1511 3128 1959 3128 1517 3129 1516 3129 1652 3129 1652 3130 1516 3130 1957 3130 1652 3131 1957 3131 1653 3131 1653 3132 1957 3132 1960 3132 1653 3133 1960 3133 1644 3133 1636 3134 1635 3134 1961 3134 1961 3135 1635 3135 1634 3135 1961 3136 1634 3136 1962 3136 1962 3137 1634 3137 1633 3137 1962 3138 1633 3138 1963 3138 1963 3139 1633 3139 1632 3139 1963 3140 1632 3140 1960 3140 1960 3141 1632 3141 1643 3141 1960 3142 1643 3142 1644 3142 1636 3143 1961 3143 1637 3143 1637 3144 1961 3144 1964 3144 1637 3145 1964 3145 1638 3145 1638 3146 1964 3146 1965 3146 1638 3147 1965 3147 1639 3147 1639 3148 1965 3148 1966 3148 1639 3149 1966 3149 1640 3149 1956 3150 1642 3150 1966 3150 1966 3151 1642 3151 1641 3151 1966 3152 1641 3152 1640 3152 1955 3153 1470 3153 1614 3153 1614 3154 1470 3154 1469 3154 1614 3155 1469 3155 1468 3155 1465 3156 1464 3156 1955 3156 1465 3157 1955 3157 1460 3157 1460 3158 1955 3158 1954 3158 1460 3159 1954 3159 1461 3159 1464 3160 1454 3160 1955 3160 1955 3161 1454 3161 1453 3161 1955 3162 1453 3162 1470 3162 1457 3163 1463 3163 1954 3163 1954 3164 1463 3164 1462 3164 1954 3165 1462 3165 1461 3165 1967 3166 1968 3166 1969 3166 1969 3167 1968 3167 1970 3167 1969 3168 1970 3168 1971 3168 1971 3169 1970 3169 1972 3169 1972 3170 1970 3170 1973 3170 1972 3171 1973 3171 1974 3171 1974 3172 1973 3172 1975 3172 1974 3173 1975 3173 1976 3173 1976 3174 1975 3174 1977 3174 1976 3175 1977 3175 1978 3175 1513 3176 1512 3176 1958 3176 1958 3177 1512 3177 1959 3177 1958 3178 1959 3178 1977 3178 1977 3179 1959 3179 1979 3179 1977 3180 1979 3180 1978 3180 1515 3181 1514 3181 1957 3181 1957 3182 1514 3182 1958 3182 1957 3183 1958 3183 1960 3183 1960 3184 1958 3184 1977 3184 1960 3185 1977 3185 1963 3185 1963 3186 1977 3186 1975 3186 1963 3187 1975 3187 1962 3187 1962 3188 1975 3188 1973 3188 1962 3189 1973 3189 1961 3189 1961 3190 1973 3190 1970 3190 1961 3191 1970 3191 1964 3191 1964 3192 1970 3192 1968 3192 1964 3193 1968 3193 1965 3193 1965 3194 1968 3194 1980 3194 1965 3195 1980 3195 1966 3195 1966 3196 1980 3196 1981 3196 1966 3197 1981 3197 1956 3197 1967 3198 1982 3198 1968 3198 1968 3199 1982 3199 1983 3199 1968 3200 1983 3200 1980 3200 1980 3201 1983 3201 1984 3201 1980 3202 1984 3202 1981 3202 1981 3203 1984 3203 1985 3203 1985 3204 1986 3204 1981 3204 1981 3205 1986 3205 1953 3205 1981 3206 1953 3206 1956 3206 1956 3207 1953 3207 1955 3207 1956 3208 1955 3208 1615 3208 1615 3209 1955 3209 1614 3209 1458 3210 1457 3210 1987 3210 1987 3211 1457 3211 1954 3211 1987 3212 1954 3212 1988 3212 1988 3213 1954 3213 1953 3213 1988 3214 1953 3214 1989 3214 1989 3215 1953 3215 1986 3215 1990 3216 1991 3216 1992 3216 1993 3217 1994 3217 1995 3217 1599 3218 1600 3218 1992 3218 1604 3219 1606 3219 1996 3219 1605 3220 1612 3220 1995 3220 1545 3221 1550 3221 1997 3221 1998 3222 1999 3222 1875 3222 1546 3223 2000 3223 1547 3223 1547 3224 2000 3224 1997 3224 1547 3225 1997 3225 1549 3225 1549 3226 1997 3226 1550 3226 1537 3227 1539 3227 2001 3227 1539 3228 1541 3228 2001 3228 2001 3229 1541 3229 1542 3229 2001 3230 1542 3230 1997 3230 1997 3231 1542 3231 1544 3231 1997 3232 1544 3232 1545 3232 1538 3233 1537 3233 1613 3233 1613 3234 1537 3234 2001 3234 1613 3235 2001 3235 1608 3235 1608 3236 2001 3236 1609 3236 2002 3237 1611 3237 1610 3237 1605 3238 1995 3238 1606 3238 1601 3239 1602 3239 2003 3239 2003 3240 1602 3240 1603 3240 2004 3241 1598 3241 1599 3241 1586 3242 1597 3242 2005 3242 2005 3243 1597 3243 1598 3243 1585 3244 1586 3244 1868 3244 1868 3245 1586 3245 2005 3245 1868 3246 2005 3246 1871 3246 1871 3247 2005 3247 1998 3247 1871 3248 1998 3248 1873 3248 1873 3249 1998 3249 1875 3249 2006 3250 2002 3250 2007 3250 2007 3251 2002 3251 1610 3251 2007 3252 1610 3252 1609 3252 1606 3253 1995 3253 1996 3253 1996 3254 1995 3254 1994 3254 1996 3255 1994 3255 2008 3255 2009 3256 2003 3256 2010 3256 2010 3257 2003 3257 1603 3257 2010 3258 1603 3258 1604 3258 1599 3259 1992 3259 2004 3259 2004 3260 1992 3260 1991 3260 2004 3261 1991 3261 2011 3261 1609 3262 2001 3262 2007 3262 2007 3263 2001 3263 1997 3263 2007 3264 1997 3264 2006 3264 2006 3265 1997 3265 2000 3265 2006 3266 2000 3266 2012 3266 2012 3267 2013 3267 2006 3267 2006 3268 2013 3268 1993 3268 2006 3269 1993 3269 2002 3269 2002 3270 1993 3270 1995 3270 2002 3271 1995 3271 1611 3271 1611 3272 1995 3272 1612 3272 2013 3273 2014 3273 1993 3273 1993 3274 2014 3274 2015 3274 1993 3275 2015 3275 1994 3275 1994 3276 2015 3276 2016 3276 1994 3277 2016 3277 2008 3277 2008 3278 2016 3278 2017 3278 2008 3279 2017 3279 2018 3279 1604 3280 1996 3280 2010 3280 2010 3281 1996 3281 2008 3281 2010 3282 2008 3282 2009 3282 2009 3283 2008 3283 2018 3283 2009 3284 2018 3284 2019 3284 2019 3285 2020 3285 2009 3285 2009 3286 2020 3286 1990 3286 2009 3287 1990 3287 2003 3287 2003 3288 1990 3288 1992 3288 2003 3289 1992 3289 1601 3289 1601 3290 1992 3290 1600 3290 2020 3291 2021 3291 1990 3291 1990 3292 2021 3292 2022 3292 1990 3293 2022 3293 1991 3293 1991 3294 2022 3294 2023 3294 1991 3295 2023 3295 2011 3295 2011 3296 2023 3296 2024 3296 2011 3297 2024 3297 2025 3297 1598 3298 2004 3298 2005 3298 2005 3299 2004 3299 2011 3299 2005 3300 2011 3300 1998 3300 1998 3301 2011 3301 2025 3301 1998 3302 2025 3302 1999 3302 2026 3303 2027 3303 2028 3303 2029 3304 2030 3304 2031 3304 2032 3305 2033 3305 2034 3305 2035 3306 2036 3306 2037 3306 2038 3307 2039 3307 2040 3307 2041 3308 2042 3308 2043 3308 2044 3309 2045 3309 2046 3309 2047 3310 2048 3310 2049 3310 1089 3311 1091 3311 1849 3311 1089 3312 1849 3312 1080 3312 1080 3313 1849 3313 2050 3313 1080 3314 2050 3314 1081 3314 1068 3315 1079 3315 2051 3315 2051 3316 1079 3316 1078 3316 1078 3317 1105 3317 2051 3317 2051 3318 1105 3318 1084 3318 2051 3319 1084 3319 2050 3319 2050 3320 1084 3320 1083 3320 2050 3321 1083 3321 1081 3321 1068 3322 2051 3322 1073 3322 1073 3323 2051 3323 2052 3323 1073 3324 2052 3324 1074 3324 1074 3325 2052 3325 2053 3325 1074 3326 2053 3326 1076 3326 2054 3327 1756 3327 1772 3327 1765 3328 2055 3328 1764 3328 1764 3329 2055 3329 2054 3329 1764 3330 2054 3330 1763 3330 1763 3331 2054 3331 1772 3331 1756 3332 2054 3332 1758 3332 1758 3333 2054 3333 2056 3333 1758 3334 2056 3334 1760 3334 1760 3335 2056 3335 1761 3335 1761 3336 2056 3336 1831 3336 1761 3337 1831 3337 1762 3337 2057 3338 2058 3338 2059 3338 2058 3339 2057 3339 2048 3339 2047 3340 2049 3340 2060 3340 2061 3341 2062 3341 2063 3341 2063 3342 2062 3342 2064 3342 2065 3343 2066 3343 2061 3343 2066 3344 2065 3344 2067 3344 2068 3345 2069 3345 2070 3345 2070 3346 2069 3346 2071 3346 2072 3347 2073 3347 2068 3347 2073 3348 2072 3348 2074 3348 2075 3349 2076 3349 2077 3349 2078 3350 2079 3350 2080 3350 2080 3351 2079 3351 2081 3351 2045 3352 2082 3352 2028 3352 2083 3353 2084 3353 2085 3353 2085 3354 2084 3354 2041 3354 2086 3355 2087 3355 2083 3355 2088 3356 2089 3356 2090 3356 2090 3357 2089 3357 2038 3357 2091 3358 2092 3358 2088 3358 2092 3359 2091 3359 2036 3359 2093 3360 2094 3360 2095 3360 2095 3361 2094 3361 2035 3361 2096 3362 2097 3362 2098 3362 2098 3363 2097 3363 2093 3363 2099 3364 2100 3364 2096 3364 2033 3365 2101 3365 2102 3365 2102 3366 2101 3366 2103 3366 2102 3367 2103 3367 2104 3367 2105 3368 2106 3368 2032 3368 2107 3369 2108 3369 2109 3369 2108 3370 2107 3370 2030 3370 1765 3371 1767 3371 2055 3371 2055 3372 1767 3372 2110 3372 2055 3373 2110 3373 2029 3373 2111 3374 2080 3374 2075 3374 2075 3375 2080 3375 2081 3375 2075 3376 2081 3376 2076 3376 2048 3377 2057 3377 2049 3377 2049 3378 2057 3378 2112 3378 2049 3379 2112 3379 2113 3379 2113 3380 2112 3380 2114 3380 2113 3381 2114 3381 2115 3381 2061 3382 2063 3382 2065 3382 2065 3383 2063 3383 2116 3383 2065 3384 2116 3384 2117 3384 2117 3385 2116 3385 2118 3385 2117 3386 2118 3386 2119 3386 2068 3387 2070 3387 2072 3387 2072 3388 2070 3388 2120 3388 2072 3389 2120 3389 2121 3389 2121 3390 2120 3390 2122 3390 2121 3391 2122 3391 2123 3391 2124 3392 2111 3392 2125 3392 2125 3393 2111 3393 2075 3393 2125 3394 2075 3394 2126 3394 2126 3395 2075 3395 2077 3395 2126 3396 2077 3396 2074 3396 2127 3397 2027 3397 2128 3397 2128 3398 2027 3398 2026 3398 2128 3399 2026 3399 2129 3399 2041 3400 2043 3400 2085 3400 2085 3401 2043 3401 2130 3401 2085 3402 2130 3402 2131 3402 2131 3403 2130 3403 2132 3403 2131 3404 2132 3404 2133 3404 2038 3405 2040 3405 2090 3405 2090 3406 2040 3406 2134 3406 2090 3407 2134 3407 2135 3407 2135 3408 2134 3408 2136 3408 2135 3409 2136 3409 2137 3409 2035 3410 2037 3410 2095 3410 2095 3411 2037 3411 2138 3411 2095 3412 2138 3412 2139 3412 2139 3413 2138 3413 2140 3413 2139 3414 2140 3414 2141 3414 2093 3415 2095 3415 2098 3415 2098 3416 2095 3416 2139 3416 2098 3417 2139 3417 2142 3417 2142 3418 2139 3418 2141 3418 2142 3419 2141 3419 2143 3419 2033 3420 2102 3420 2034 3420 2034 3421 2102 3421 2144 3421 2034 3422 2144 3422 2145 3422 2145 3423 2144 3423 2146 3423 2145 3424 2146 3424 2147 3424 2030 3425 2107 3425 2031 3425 2031 3426 2107 3426 2148 3426 2031 3427 2148 3427 2149 3427 2149 3428 2148 3428 2150 3428 2149 3429 2150 3429 2151 3429 1849 3430 2114 3430 2050 3430 2050 3431 2114 3431 2112 3431 2050 3432 2112 3432 2051 3432 2051 3433 2112 3433 2057 3433 2051 3434 2057 3434 2052 3434 2052 3435 2057 3435 2059 3435 2052 3436 2059 3436 2053 3436 1849 3437 1848 3437 2114 3437 2114 3438 1848 3438 1847 3438 2114 3439 1847 3439 2115 3439 2115 3440 1847 3440 1846 3440 2115 3441 1846 3441 1852 3441 2060 3442 2049 3442 2152 3442 2152 3443 2049 3443 2113 3443 2152 3444 2113 3444 2153 3444 2153 3445 2113 3445 2115 3445 2153 3446 2115 3446 2154 3446 2154 3447 2115 3447 1852 3447 2154 3448 1852 3448 1851 3448 1851 3449 2118 3449 2154 3449 2154 3450 2118 3450 2116 3450 2154 3451 2116 3451 2153 3451 2153 3452 2116 3452 2063 3452 2153 3453 2063 3453 2152 3453 2152 3454 2063 3454 2064 3454 2152 3455 2064 3455 2060 3455 1851 3456 1850 3456 2118 3456 2118 3457 1850 3457 1792 3457 2118 3458 1792 3458 2119 3458 2119 3459 1792 3459 1793 3459 2119 3460 1793 3460 1797 3460 2067 3461 2065 3461 2155 3461 2155 3462 2065 3462 2117 3462 2155 3463 2117 3463 2156 3463 2156 3464 2117 3464 2119 3464 2156 3465 2119 3465 2157 3465 2157 3466 2119 3466 1797 3466 2157 3467 1797 3467 1796 3467 1796 3468 2122 3468 2157 3468 2157 3469 2122 3469 2120 3469 2157 3470 2120 3470 2156 3470 2156 3471 2120 3471 2070 3471 2156 3472 2070 3472 2155 3472 2155 3473 2070 3473 2071 3473 2155 3474 2071 3474 2067 3474 1796 3475 1795 3475 2122 3475 2122 3476 1795 3476 1794 3476 2122 3477 1794 3477 2123 3477 2123 3478 1794 3478 1798 3478 2123 3479 1798 3479 1799 3479 2074 3480 2072 3480 2126 3480 2126 3481 2072 3481 2121 3481 2126 3482 2121 3482 2125 3482 2125 3483 2121 3483 2123 3483 2125 3484 2123 3484 2124 3484 2124 3485 2123 3485 1799 3485 2124 3486 1799 3486 1800 3486 1800 3487 1801 3487 2124 3487 2124 3488 1801 3488 2129 3488 2124 3489 2129 3489 2111 3489 2111 3490 2129 3490 2026 3490 2111 3491 2026 3491 2080 3491 2080 3492 2026 3492 2028 3492 2080 3493 2028 3493 2078 3493 2078 3494 2028 3494 2082 3494 1801 3495 1802 3495 2129 3495 2129 3496 1802 3496 1791 3496 2129 3497 1791 3497 2128 3497 2128 3498 1791 3498 1790 3498 2128 3499 1790 3499 2127 3499 2127 3500 1790 3500 1803 3500 2127 3501 1803 3501 1804 3501 2045 3502 2028 3502 2046 3502 2046 3503 2028 3503 2027 3503 2046 3504 2027 3504 2158 3504 2158 3505 2027 3505 2127 3505 2158 3506 2127 3506 2159 3506 2159 3507 2127 3507 1804 3507 2159 3508 1804 3508 1808 3508 1808 3509 2132 3509 2159 3509 2159 3510 2132 3510 2130 3510 2159 3511 2130 3511 2158 3511 2158 3512 2130 3512 2043 3512 2158 3513 2043 3513 2046 3513 2046 3514 2043 3514 2042 3514 2046 3515 2042 3515 2044 3515 1808 3516 1807 3516 2132 3516 2132 3517 1807 3517 1806 3517 2132 3518 1806 3518 2133 3518 2133 3519 1806 3519 1805 3519 2133 3520 1805 3520 1812 3520 2083 3521 2085 3521 2086 3521 2086 3522 2085 3522 2131 3522 2086 3523 2131 3523 2160 3523 2160 3524 2131 3524 2133 3524 2160 3525 2133 3525 2161 3525 2161 3526 2133 3526 1812 3526 2161 3527 1812 3527 1811 3527 1811 3528 2136 3528 2161 3528 2161 3529 2136 3529 2134 3529 2161 3530 2134 3530 2160 3530 2160 3531 2134 3531 2040 3531 2160 3532 2040 3532 2086 3532 2086 3533 2040 3533 2039 3533 2086 3534 2039 3534 2087 3534 1811 3535 1810 3535 2136 3535 2136 3536 1810 3536 1809 3536 2136 3537 1809 3537 2137 3537 2137 3538 1809 3538 1813 3538 2137 3539 1813 3539 1814 3539 2088 3540 2090 3540 2091 3540 2091 3541 2090 3541 2135 3541 2091 3542 2135 3542 2162 3542 2162 3543 2135 3543 2137 3543 2162 3544 2137 3544 2163 3544 2163 3545 2137 3545 1814 3545 2163 3546 1814 3546 1815 3546 2036 3547 2091 3547 2037 3547 2037 3548 2091 3548 2162 3548 2037 3549 2162 3549 2138 3549 2138 3550 2162 3550 2163 3550 2138 3551 2163 3551 2140 3551 2140 3552 2163 3552 1815 3552 2140 3553 1815 3553 1816 3553 1816 3554 1821 3554 2140 3554 2140 3555 1821 3555 1820 3555 2140 3556 1820 3556 2141 3556 2141 3557 1820 3557 1819 3557 2141 3558 1819 3558 2143 3558 2143 3559 1819 3559 1818 3559 2143 3560 1818 3560 1817 3560 2096 3561 2098 3561 2099 3561 2099 3562 2098 3562 2142 3562 2099 3563 2142 3563 2164 3563 2164 3564 2142 3564 2143 3564 2164 3565 2143 3565 2165 3565 2165 3566 2143 3566 1817 3566 2165 3567 1817 3567 1826 3567 1826 3568 2146 3568 2165 3568 2165 3569 2146 3569 2144 3569 2165 3570 2144 3570 2164 3570 2164 3571 2144 3571 2102 3571 2164 3572 2102 3572 2099 3572 2099 3573 2102 3573 2104 3573 2099 3574 2104 3574 2100 3574 1826 3575 1825 3575 2146 3575 2146 3576 1825 3576 1824 3576 2146 3577 1824 3577 2147 3577 2147 3578 1824 3578 1823 3578 2147 3579 1823 3579 1822 3579 2032 3580 2034 3580 2105 3580 2105 3581 2034 3581 2145 3581 2105 3582 2145 3582 2166 3582 2166 3583 2145 3583 2147 3583 2166 3584 2147 3584 2167 3584 2167 3585 2147 3585 1822 3585 2167 3586 1822 3586 1828 3586 1828 3587 2150 3587 2167 3587 2167 3588 2150 3588 2148 3588 2167 3589 2148 3589 2166 3589 2166 3590 2148 3590 2107 3590 2166 3591 2107 3591 2105 3591 2105 3592 2107 3592 2109 3592 2105 3593 2109 3593 2106 3593 1828 3594 1827 3594 2150 3594 2150 3595 1827 3595 1830 3595 2150 3596 1830 3596 2151 3596 2151 3597 1830 3597 1829 3597 2151 3598 1829 3598 1832 3598 2029 3599 2031 3599 2055 3599 2055 3600 2031 3600 2149 3600 2055 3601 2149 3601 2054 3601 2054 3602 2149 3602 2151 3602 2054 3603 2151 3603 2056 3603 2056 3604 2151 3604 1832 3604 2056 3605 1832 3605 1831 3605 2168 3606 2169 3606 2170 3606 2171 3607 2172 3607 2173 3607 2174 3608 2175 3608 2176 3608 2177 3609 2178 3609 2179 3609 2180 3610 2181 3610 2169 3610 2169 3611 2181 3611 2182 3611 2169 3612 2182 3612 2170 3612 2183 3613 2184 3613 2185 3613 2185 3614 2184 3614 2177 3614 2185 3615 2177 3615 2186 3615 2186 3616 2177 3616 2179 3616 2187 3617 2188 3617 2189 3617 2189 3618 2188 3618 2190 3618 2189 3619 2190 3619 2178 3619 2178 3620 2190 3620 2191 3620 2178 3621 2191 3621 2179 3621 2176 3622 2192 3622 2174 3622 2174 3623 2192 3623 2193 3623 2174 3624 2193 3624 2187 3624 2187 3625 2193 3625 2194 3625 2187 3626 2194 3626 2188 3626 2195 3627 2196 3627 2197 3627 2197 3628 2196 3628 2198 3628 2197 3629 2198 3629 2175 3629 2175 3630 2198 3630 2199 3630 2175 3631 2199 3631 2176 3631 2173 3632 2200 3632 2171 3632 2171 3633 2200 3633 2201 3633 2171 3634 2201 3634 2195 3634 2195 3635 2201 3635 2202 3635 2195 3636 2202 3636 2196 3636 2170 3637 2203 3637 2168 3637 2168 3638 2203 3638 2204 3638 2168 3639 2204 3639 2205 3639 2205 3640 2204 3640 2206 3640 2205 3641 2206 3641 2172 3641 2172 3642 2206 3642 2207 3642 2172 3643 2207 3643 2173 3643 1659 3644 2180 3644 1666 3644 1666 3645 2180 3645 2169 3645 1666 3646 2169 3646 1667 3646 1667 3647 2169 3647 2168 3647 1667 3648 2168 3648 1668 3648 1668 3649 2168 3649 2205 3649 1668 3650 2205 3650 1669 3650 1669 3651 2205 3651 2172 3651 1669 3652 2172 3652 1670 3652 1670 3653 2172 3653 2171 3653 1670 3654 2171 3654 1671 3654 1671 3655 2171 3655 2195 3655 1671 3656 2195 3656 1672 3656 1672 3657 2195 3657 2197 3657 1672 3658 2197 3658 1673 3658 1673 3659 2197 3659 2175 3659 1673 3660 2175 3660 1674 3660 1674 3661 2175 3661 2174 3661 1674 3662 2174 3662 1675 3662 1675 3663 2174 3663 2187 3663 1675 3664 2187 3664 1676 3664 1676 3665 2187 3665 2189 3665 1676 3666 2189 3666 1677 3666 1677 3667 2189 3667 2178 3667 1677 3668 2178 3668 1657 3668 1657 3669 2178 3669 2177 3669 1657 3670 2177 3670 1658 3670 1658 3671 2177 3671 2184 3671 2208 3672 2209 3672 2210 3672 2211 3673 2212 3673 2213 3673 2214 3674 2215 3674 2216 3674 2184 3675 2183 3675 2217 3675 2181 3676 2218 3676 2219 3676 2219 3677 2218 3677 2220 3677 2219 3678 2220 3678 2221 3678 2221 3679 2220 3679 2222 3679 2216 3680 2223 3680 2214 3680 2214 3681 2223 3681 2224 3681 2214 3682 2224 3682 2222 3682 2222 3683 2224 3683 2225 3683 2222 3684 2225 3684 2221 3684 2226 3685 2227 3685 2228 3685 2228 3686 2227 3686 2229 3686 2228 3687 2229 3687 2215 3687 2215 3688 2229 3688 2230 3688 2215 3689 2230 3689 2216 3689 2213 3690 2231 3690 2211 3690 2211 3691 2231 3691 2232 3691 2211 3692 2232 3692 2226 3692 2226 3693 2232 3693 2233 3693 2226 3694 2233 3694 2227 3694 2234 3695 2235 3695 2236 3695 2236 3696 2235 3696 2237 3696 2236 3697 2237 3697 2212 3697 2212 3698 2237 3698 2238 3698 2212 3699 2238 3699 2213 3699 2210 3700 2239 3700 2208 3700 2208 3701 2239 3701 2240 3701 2208 3702 2240 3702 2234 3702 2234 3703 2240 3703 2241 3703 2234 3704 2241 3704 2235 3704 2184 3705 2217 3705 2242 3705 2242 3706 2217 3706 2243 3706 2242 3707 2243 3707 2209 3707 2209 3708 2243 3708 2244 3708 2209 3709 2244 3709 2210 3709 1658 3710 2184 3710 1660 3710 1660 3711 2184 3711 2242 3711 1660 3712 2242 3712 1662 3712 1662 3713 2242 3713 2209 3713 1662 3714 2209 3714 1663 3714 1663 3715 2209 3715 2208 3715 1663 3716 2208 3716 1683 3716 1683 3717 2208 3717 2234 3717 1683 3718 2234 3718 1679 3718 1679 3719 2234 3719 2236 3719 1679 3720 2236 3720 1681 3720 1681 3721 2236 3721 2212 3721 1681 3722 2212 3722 1682 3722 1682 3723 2212 3723 2211 3723 1682 3724 2211 3724 1680 3724 1680 3725 2211 3725 2226 3725 1680 3726 2226 3726 1678 3726 1678 3727 2226 3727 2228 3727 1678 3728 2228 3728 1684 3728 1684 3729 2228 3729 2215 3729 1684 3730 2215 3730 1665 3730 1665 3731 2215 3731 2214 3731 1665 3732 2214 3732 1664 3732 1664 3733 2214 3733 2222 3733 1664 3734 2222 3734 1661 3734 1661 3735 2222 3735 2220 3735 1661 3736 2220 3736 1659 3736 1659 3737 2220 3737 2218 3737 2245 3738 2246 3738 2247 3738 2248 3739 972 3739 2249 3739 2248 3740 2249 3740 2246 3740 2246 3741 2249 3741 2250 3741 2246 3742 2250 3742 2247 3742 2245 3743 2247 3743 2251 3743 2251 3744 2247 3744 2252 3744 2251 3745 2252 3745 2253 3745 2247 3746 2250 3746 2254 3746 2254 3747 2250 3747 2249 3747 2254 3748 2249 3748 2255 3748 971 3749 1032 3749 2256 3749 2255 3750 2249 3750 2256 3750 2256 3751 2249 3751 972 3751 2256 3752 972 3752 971 3752 2247 3753 2254 3753 2252 3753 2252 3754 2254 3754 2257 3754 2252 3755 2257 3755 2258 3755 1688 3756 1687 3756 1781 3756 2258 3757 2257 3757 2259 3757 2259 3758 2257 3758 2260 3758 2259 3759 2260 3759 2261 3759 2261 3760 2260 3760 2262 3760 1780 3761 2263 3761 1781 3761 1781 3762 2263 3762 2264 3762 1781 3763 2264 3763 2265 3763 2265 3764 2266 3764 1781 3764 1781 3765 2266 3765 2267 3765 1781 3766 2267 3766 2268 3766 2268 3767 2267 3767 2269 3767 2268 3768 2269 3768 2260 3768 2260 3769 2269 3769 2270 3769 2260 3770 2270 3770 2262 3770 1689 3771 2271 3771 1690 3771 1690 3772 2271 3772 1691 3772 1691 3773 2271 3773 1692 3773 1692 3774 2271 3774 2272 3774 1692 3775 2272 3775 2254 3775 2256 3776 1032 3776 1694 3776 2254 3777 2255 3777 1692 3777 1692 3778 2255 3778 2256 3778 1692 3779 2256 3779 1693 3779 1693 3780 2256 3780 1694 3780 1688 3781 1781 3781 1689 3781 1689 3782 1781 3782 2268 3782 1689 3783 2268 3783 2271 3783 2271 3784 2268 3784 2260 3784 2271 3785 2260 3785 2272 3785 2272 3786 2260 3786 2257 3786 2272 3787 2257 3787 2254 3787 1700 3788 1699 3788 2273 3788 2274 3789 1702 3789 1033 3789 2275 3790 2276 3790 1844 3790 1844 3791 2276 3791 2277 3791 2277 3792 2278 3792 1844 3792 1844 3793 2278 3793 2279 3793 1844 3794 2279 3794 1845 3794 2280 3795 2281 3795 2282 3795 2282 3796 2281 3796 2283 3796 2282 3797 2283 3797 2284 3797 2275 3798 2273 3798 2285 3798 2286 3799 2287 3799 2285 3799 2285 3800 2287 3800 2282 3800 2285 3801 2282 3801 2275 3801 2275 3802 2282 3802 2284 3802 2275 3803 2284 3803 2276 3803 2274 3804 1033 3804 2285 3804 2285 3805 1033 3805 2288 3805 2285 3806 2288 3806 2286 3806 2273 3807 1699 3807 2285 3807 2285 3808 1699 3808 1698 3808 2285 3809 1698 3809 2274 3809 2274 3810 1698 3810 1697 3810 2274 3811 1697 3811 1702 3811 1844 3812 1705 3812 1704 3812 1844 3813 1704 3813 2275 3813 2275 3814 1704 3814 1703 3814 2275 3815 1703 3815 2273 3815 2273 3816 1703 3816 1701 3816 2273 3817 1701 3817 1700 3817 2286 3818 2288 3818 2289 3818 1042 3819 2289 3819 1035 3819 1035 3820 2289 3820 2288 3820 1035 3821 2288 3821 1033 3821 2290 3822 2280 3822 2291 3822 2291 3823 2280 3823 2282 3823 2289 3824 2292 3824 2286 3824 2286 3825 2292 3825 2291 3825 2286 3826 2291 3826 2287 3826 2287 3827 2291 3827 2282 3827 2293 3828 2294 3828 1042 3828 1042 3829 2294 3829 2289 3829 2295 3830 2290 3830 2296 3830 2296 3831 2290 3831 2291 3831 2296 3832 2291 3832 2297 3832 2297 3833 2291 3833 2294 3833 2294 3834 2291 3834 2292 3834 2294 3835 2292 3835 2289 3835 1778 3836 1777 3836 2298 3836 2298 3837 1777 3837 2299 3837 1784 3838 1783 3838 2300 3838 2300 3839 2301 3839 1784 3839 1784 3840 2301 3840 2302 3840 1784 3841 2302 3841 1777 3841 2303 3842 1843 3842 1842 3842 1842 3843 1841 3843 2304 3843 2305 3844 2303 3844 2306 3844 2306 3845 2303 3845 1842 3845 2306 3846 1842 3846 2307 3846 2307 3847 1842 3847 2304 3847 2299 3848 1777 3848 2308 3848 2308 3849 1777 3849 2302 3849 2308 3850 2302 3850 2309 3850 2309 3851 2302 3851 2310 3851 2309 3852 2310 3852 2311 3852 2311 3853 2310 3853 2312 3853 2311 3854 2312 3854 2313 3854 2313 3855 2312 3855 2314 3855 2313 3856 2314 3856 2315 3856 2315 3857 2314 3857 2316 3857 2315 3858 2316 3858 2317 3858 2317 3859 2316 3859 2318 3859 2317 3860 2318 3860 2319 3860 2319 3861 2318 3861 2320 3861 2319 3862 2320 3862 2321 3862 2321 3863 2320 3863 2322 3863 2321 3864 2322 3864 2323 3864 2323 3865 2322 3865 2324 3865 2323 3866 2324 3866 2325 3866 2325 3867 2324 3867 2326 3867 2325 3868 2326 3868 2327 3868 2327 3869 2326 3869 2328 3869 2327 3870 2328 3870 2329 3870 2329 3871 2328 3871 2330 3871 2329 3872 2330 3872 2331 3872 2331 3873 2330 3873 2332 3873 2331 3874 2332 3874 2333 3874 2333 3875 2332 3875 2334 3875 2333 3876 2334 3876 2335 3876 2335 3877 2334 3877 2336 3877 2335 3878 2336 3878 2337 3878 2337 3879 2336 3879 2338 3879 2337 3880 2338 3880 2339 3880 2339 3881 2338 3881 2340 3881 2339 3882 2340 3882 2341 3882 2341 3883 2340 3883 2342 3883 2341 3884 2342 3884 2343 3884 2343 3885 2342 3885 2344 3885 2343 3886 2344 3886 2306 3886 2306 3887 2344 3887 2345 3887 2306 3888 2345 3888 2305 3888 2346 3889 1855 3889 2347 3889 2347 3890 1855 3890 1854 3890 1856 3891 2348 3891 1857 3891 1857 3892 2348 3892 1860 3892 1786 3893 1785 3893 1858 3893 1858 3894 1859 3894 1786 3894 1786 3895 1859 3895 1861 3895 1786 3896 1861 3896 2349 3896 2350 3897 1786 3897 2351 3897 2351 3898 1786 3898 2349 3898 2351 3899 2349 3899 2352 3899 2350 3900 2353 3900 1786 3900 1786 3901 2353 3901 2354 3901 1786 3902 2354 3902 1787 3902 2355 3903 2356 3903 2357 3903 2357 3904 2356 3904 2358 3904 1861 3905 1860 3905 2349 3905 2349 3906 1860 3906 2348 3906 2349 3907 2348 3907 2346 3907 2346 3908 2348 3908 1856 3908 2346 3909 1856 3909 1855 3909 2359 3910 2360 3910 2346 3910 2346 3911 2360 3911 2357 3911 2346 3912 2357 3912 2349 3912 2349 3913 2357 3913 2358 3913 2349 3914 2358 3914 2352 3914 1854 3915 1853 3915 2347 3915 2347 3916 1853 3916 1393 3916 2347 3917 1393 3917 2346 3917 2346 3918 1393 3918 2361 3918 2346 3919 2361 3919 2359 3919 2359 3920 2361 3920 2362 3920 1390 3921 2362 3921 1391 3921 1391 3922 2362 3922 2361 3922 1391 3923 2361 3923 1393 3923 2363 3924 2355 3924 2364 3924 2364 3925 2355 3925 2357 3925 2362 3926 2365 3926 2359 3926 2359 3927 2365 3927 2364 3927 2359 3928 2364 3928 2360 3928 2360 3929 2364 3929 2357 3929 2366 3930 2367 3930 2368 3930 1717 3931 1716 3931 2369 3931 2366 3932 2368 3932 2370 3932 2370 3933 2368 3933 2371 3933 2370 3934 2371 3934 2369 3934 2369 3935 2371 3935 1740 3935 2369 3936 1740 3936 1717 3936 2367 3937 2366 3937 2372 3937 2372 3938 2366 3938 2373 3938 2372 3939 2373 3939 2374 3939 1862 3940 1837 3940 1836 3940 1862 3941 1836 3941 1863 3941 1863 3942 1836 3942 2375 3942 1863 3943 2375 3943 1864 3943 2376 3944 1866 3944 2377 3944 2377 3945 1866 3945 1867 3945 2377 3946 1867 3946 1864 3946 1716 3947 1865 3947 2369 3947 2369 3948 1865 3948 1866 3948 2369 3949 1866 3949 2370 3949 2374 3950 2373 3950 2378 3950 2378 3951 2373 3951 2379 3951 2378 3952 2379 3952 2380 3952 2380 3953 2379 3953 2381 3953 1836 3954 1833 3954 2382 3954 2382 3955 2383 3955 1836 3955 1836 3956 2383 3956 2384 3956 1836 3957 2384 3957 2375 3957 2375 3958 2384 3958 2385 3958 2375 3959 2385 3959 2379 3959 2379 3960 2385 3960 2386 3960 2379 3961 2386 3961 2381 3961 1864 3962 2375 3962 2377 3962 2377 3963 2375 3963 2379 3963 2377 3964 2379 3964 2376 3964 2376 3965 2379 3965 2373 3965 2376 3966 2373 3966 1866 3966 1866 3967 2373 3967 2366 3967 1866 3968 2366 3968 2370 3968 2387 3969 2388 3969 1390 3969 1390 3970 2388 3970 2362 3970 2389 3971 2363 3971 2390 3971 2390 3972 2363 3972 2364 3972 2390 3973 2364 3973 2388 3973 2388 3974 2364 3974 2365 3974 2388 3975 2365 3975 2362 3975 2368 3976 2367 3976 2391 3976 2391 3977 2367 3977 2392 3977 2392 3978 2367 3978 2372 3978 2392 3979 2372 3979 2393 3979 2368 3980 2391 3980 2371 3980 2371 3981 2391 3981 2394 3981 2371 3982 2394 3982 1740 3982 2395 3983 2396 3983 2397 3983 2398 3984 2399 3984 2400 3984 2401 3985 1587 3985 1869 3985 1877 3986 1878 3986 2402 3986 2403 3987 2404 3987 2396 3987 2396 3988 2404 3988 2405 3988 2396 3989 2405 3989 2397 3989 2397 3990 2405 3990 2406 3990 2397 3991 2406 3991 2407 3991 2407 3992 2406 3992 2408 3992 2407 3993 2408 3993 2409 3993 2410 3994 2411 3994 2403 3994 2403 3995 2411 3995 2412 3995 2403 3996 2412 3996 2404 3996 2413 3997 2414 3997 2415 3997 2414 3998 2413 3998 2402 3998 2402 3999 2413 3999 1876 3999 2402 4000 1876 4000 1877 4000 1869 4001 1870 4001 2416 4001 1870 4002 1881 4002 2416 4002 2416 4003 1881 4003 1880 4003 2416 4004 1880 4004 2413 4004 2413 4005 1880 4005 1879 4005 2413 4006 1879 4006 1876 4006 1869 4007 2416 4007 2417 4007 2417 4008 2416 4008 2418 4008 2417 4009 2418 4009 2419 4009 2419 4010 2420 4010 2417 4010 2417 4011 2420 4011 2421 4011 2417 4012 2421 4012 1869 4012 1869 4013 2421 4013 2422 4013 1869 4014 2422 4014 2401 4014 2395 4015 2423 4015 2396 4015 2396 4016 2423 4016 2424 4016 2396 4017 2424 4017 2403 4017 2403 4018 2424 4018 2425 4018 2403 4019 2425 4019 2400 4019 2400 4020 2425 4020 2426 4020 2400 4021 2426 4021 2398 4021 2399 4022 2418 4022 2400 4022 2400 4023 2418 4023 2416 4023 2400 4024 2416 4024 2403 4024 2403 4025 2416 4025 2413 4025 2403 4026 2413 4026 2410 4026 2410 4027 2413 4027 2415 4027 2427 4028 2428 4028 1579 4028 1579 4029 2428 4029 1573 4029 2429 4030 1522 4030 1521 4030 2429 4031 1521 4031 2430 4031 2430 4032 1521 4032 1556 4032 2430 4033 1556 4033 2431 4033 2431 4034 1556 4034 1575 4034 2431 4035 1575 4035 2428 4035 2428 4036 1575 4036 1574 4036 2428 4037 1574 4037 1573 4037 2432 4038 2433 4038 1580 4038 2427 4039 1579 4039 2433 4039 2433 4040 1579 4040 1581 4040 2433 4041 1581 4041 1580 4041 1580 4042 1558 4042 2432 4042 2432 4043 1558 4043 1557 4043 2432 4044 1557 4044 2434 4044 1497 4045 2435 4045 1917 4045 1917 4046 2435 4046 2436 4046 1917 4047 2436 4047 1916 4047 1883 4048 1909 4048 2437 4048 1909 4049 1911 4049 2437 4049 2437 4050 1911 4050 1912 4050 2437 4051 1912 4051 2436 4051 2436 4052 1912 4052 1914 4052 2436 4053 1914 4053 1916 4053 1894 4054 2438 4054 1890 4054 1890 4055 2438 4055 2434 4055 1890 4056 2434 4056 1557 4056 2439 4057 1899 4057 1897 4057 1897 4058 1896 4058 2439 4058 2439 4059 1896 4059 1902 4059 2439 4060 1902 4060 2440 4060 2440 4061 1902 4061 1904 4061 2440 4062 1904 4062 1905 4062 1905 4063 1907 4063 2440 4063 2440 4064 1907 4064 1908 4064 2440 4065 1908 4065 2437 4065 2437 4066 1908 4066 1884 4066 2437 4067 1884 4067 1883 4067 1894 4068 1893 4068 2438 4068 2438 4069 1893 4069 1901 4069 2438 4070 1901 4070 2439 4070 2439 4071 1901 4071 1900 4071 2439 4072 1900 4072 1899 4072 2441 4073 2442 4073 1447 4073 2435 4074 1497 4074 1496 4074 1447 4075 2442 4075 1448 4075 1448 4076 2442 4076 2443 4076 1448 4077 2443 4077 1444 4077 2435 4078 1496 4078 2444 4078 2444 4079 1496 4079 1499 4079 2444 4080 1499 4080 2443 4080 2443 4081 1499 4081 1445 4081 2443 4082 1445 4082 1444 4082 1447 4083 1508 4083 2441 4083 2441 4084 1508 4084 1507 4084 2441 4085 1507 4085 2445 4085 2445 4086 1507 4086 1502 4086 2445 4087 1502 4087 2446 4087 2446 4088 1502 4088 1501 4088 2446 4089 1501 4089 2447 4089 2448 4090 2449 4090 1979 4090 1959 4091 1511 4091 2450 4091 2450 4092 2451 4092 1959 4092 1959 4093 2451 4093 2452 4093 1959 4094 2452 4094 1979 4094 1979 4095 2452 4095 2453 4095 1979 4096 2453 4096 2448 4096 2449 4097 2454 4097 2455 4097 2455 4098 2454 4098 2456 4098 2455 4099 2456 4099 2457 4099 2457 4100 2458 4100 2455 4100 2455 4101 2458 4101 2459 4101 2455 4102 2459 4102 2460 4102 2449 4103 2455 4103 1979 4103 1979 4104 2455 4104 2461 4104 1979 4105 2461 4105 1978 4105 1978 4106 2461 4106 2462 4106 1978 4107 2462 4107 1976 4107 1976 4108 2462 4108 1974 4108 1974 4109 2462 4109 2463 4109 1974 4110 2463 4110 1972 4110 1972 4111 2463 4111 2464 4111 1972 4112 2464 4112 1971 4112 1971 4113 2464 4113 2465 4113 1971 4114 2465 4114 1969 4114 1969 4115 2465 4115 2466 4115 1969 4116 2466 4116 1967 4116 1967 4117 2466 4117 2467 4117 1967 4118 2467 4118 1982 4118 1982 4119 2467 4119 1983 4119 1983 4120 2467 4120 2468 4120 1983 4121 2468 4121 1984 4121 1984 4122 2468 4122 2469 4122 1984 4123 2469 4123 1985 4123 1985 4124 2469 4124 2470 4124 1985 4125 2470 4125 1986 4125 1986 4126 2470 4126 2471 4126 1986 4127 2471 4127 1989 4127 1989 4128 2471 4128 2472 4128 1989 4129 2472 4129 1988 4129 1988 4130 2472 4130 2473 4130 1988 4131 2473 4131 2474 4131 2474 4132 1504 4132 1988 4132 1988 4133 1504 4133 1503 4133 1988 4134 1503 4134 1987 4134 1987 4135 1503 4135 1458 4135 1553 4136 2012 4136 1551 4136 1551 4137 2012 4137 2000 4137 1551 4138 2000 4138 1546 4138 2475 4139 2013 4139 2476 4139 2476 4140 2013 4140 2012 4140 2476 4141 2012 4141 2477 4141 2477 4142 2012 4142 1553 4142 2477 4143 1553 4143 2478 4143 2020 4144 2019 4144 2479 4144 2479 4145 2019 4145 2018 4145 2479 4146 2018 4146 2480 4146 2480 4147 2018 4147 2017 4147 2480 4148 2017 4148 2481 4148 2481 4149 2017 4149 2016 4149 2481 4150 2016 4150 2482 4150 2482 4151 2016 4151 2015 4151 2482 4152 2015 4152 2475 4152 2475 4153 2015 4153 2014 4153 2475 4154 2014 4154 2013 4154 2483 4155 2484 4155 2485 4155 2485 4156 2484 4156 2486 4156 2487 4157 2488 4157 2025 4157 2483 4158 2489 4158 2484 4158 2484 4159 2489 4159 2490 4159 2484 4160 2490 4160 2491 4160 2491 4161 2487 4161 2484 4161 2484 4162 2487 4162 2025 4162 2484 4163 2025 4163 2492 4163 2492 4164 2025 4164 2024 4164 2492 4165 2024 4165 2493 4165 2493 4166 2024 4166 2023 4166 2493 4167 2023 4167 2494 4167 2494 4168 2023 4168 2022 4168 2494 4169 2022 4169 2495 4169 2495 4170 2022 4170 2021 4170 2495 4171 2021 4171 2496 4171 2496 4172 2021 4172 2020 4172 2496 4173 2020 4173 2497 4173 2497 4174 2020 4174 2479 4174 2488 4175 2498 4175 2025 4175 2025 4176 2498 4176 2499 4176 2025 4177 2499 4177 1999 4177 1999 4178 2499 4178 2500 4178 1999 4179 2500 4179 1875 4179 2501 4180 2502 4180 2503 4180 2504 4181 2505 4181 2506 4181 2506 4182 2505 4182 2507 4182 2506 4183 2507 4183 2508 4183 2506 4184 2509 4184 2504 4184 2504 4185 2509 4185 2510 4185 2504 4186 2510 4186 2511 4186 2512 4187 2513 4187 2514 4187 2510 4188 2515 4188 2511 4188 2511 4189 2515 4189 2516 4189 2511 4190 2516 4190 2503 4190 2503 4191 2516 4191 2517 4191 2503 4192 2517 4192 2512 4192 2501 4193 2503 4193 2518 4193 2512 4194 2514 4194 2503 4194 2503 4195 2514 4195 2519 4195 2503 4196 2519 4196 2518 4196 2520 4197 2521 4197 2101 4197 2522 4198 1076 4198 2053 4198 2523 4199 2524 4199 2029 4199 1767 4200 2525 4200 2110 4200 2110 4201 2525 4201 2526 4201 2110 4202 2526 4202 2029 4202 2029 4203 2526 4203 2527 4203 2029 4204 2527 4204 2523 4204 2528 4205 2529 4205 2507 4205 2507 4206 2529 4206 2530 4206 2507 4207 2530 4207 2508 4207 2531 4208 2532 4208 2533 4208 2533 4209 2532 4209 2528 4209 2533 4210 2528 4210 2505 4210 2505 4211 2528 4211 2507 4211 2534 4212 2535 4212 2536 4212 2537 4213 2538 4213 2536 4213 2536 4214 2538 4214 2539 4214 2536 4215 2539 4215 2534 4215 2540 4216 2541 4216 2059 4216 2059 4217 2541 4217 2542 4217 2059 4218 2542 4218 2543 4218 2543 4219 2544 4219 2059 4219 2059 4220 2544 4220 2545 4220 2059 4221 2545 4221 2053 4221 2053 4222 2545 4222 2546 4222 2053 4223 2546 4223 2522 4223 2534 4224 2540 4224 2535 4224 2535 4225 2540 4225 2059 4225 2535 4226 2059 4226 2547 4226 2547 4227 2059 4227 2058 4227 2547 4228 2058 4228 2548 4228 2548 4229 2058 4229 2048 4229 2548 4230 2048 4230 2549 4230 2549 4231 2048 4231 2047 4231 2549 4232 2047 4232 2550 4232 2550 4233 2047 4233 2060 4233 2550 4234 2060 4234 2551 4234 2551 4235 2060 4235 2064 4235 2551 4236 2064 4236 2552 4236 2552 4237 2064 4237 2062 4237 2552 4238 2062 4238 2553 4238 2553 4239 2062 4239 2061 4239 2553 4240 2061 4240 2554 4240 2554 4241 2061 4241 2555 4241 2061 4242 2066 4242 2555 4242 2555 4243 2066 4243 2067 4243 2555 4244 2067 4244 2556 4244 2556 4245 2067 4245 2071 4245 2556 4246 2071 4246 2557 4246 2557 4247 2071 4247 2069 4247 2557 4248 2069 4248 2558 4248 2558 4249 2069 4249 2068 4249 2558 4250 2068 4250 2559 4250 2559 4251 2068 4251 2560 4251 2077 4252 2561 4252 2074 4252 2074 4253 2561 4253 2560 4253 2074 4254 2560 4254 2073 4254 2073 4255 2560 4255 2068 4255 2081 4256 2562 4256 2563 4256 2081 4257 2563 4257 2076 4257 2076 4258 2563 4258 2564 4258 2076 4259 2564 4259 2077 4259 2565 4260 2566 4260 2567 4260 2564 4261 2568 4261 2077 4261 2077 4262 2568 4262 2569 4262 2077 4263 2569 4263 2561 4263 2561 4264 2569 4264 2570 4264 2561 4265 2570 4265 2567 4265 2567 4266 2570 4266 2571 4266 2567 4267 2571 4267 2565 4267 2562 4268 2081 4268 2572 4268 2572 4269 2081 4269 2079 4269 2572 4270 2079 4270 2573 4270 2573 4271 2079 4271 2078 4271 2573 4272 2078 4272 2574 4272 2574 4273 2078 4273 2082 4273 2574 4274 2082 4274 2575 4274 2082 4275 2045 4275 2575 4275 2575 4276 2045 4276 2044 4276 2575 4277 2044 4277 2576 4277 2576 4278 2044 4278 2042 4278 2577 4279 2578 4279 2035 4279 2579 4280 2580 4280 2581 4280 2581 4281 2580 4281 2582 4281 2578 4282 2583 4282 2035 4282 2035 4283 2583 4283 2584 4283 2035 4284 2584 4284 2036 4284 2036 4285 2584 4285 2585 4285 2036 4286 2585 4286 2092 4286 2092 4287 2585 4287 2586 4287 2092 4288 2586 4288 2088 4288 2088 4289 2586 4289 2587 4289 2088 4290 2587 4290 2089 4290 2089 4291 2587 4291 2588 4291 2089 4292 2588 4292 2038 4292 2038 4293 2588 4293 2589 4293 2038 4294 2589 4294 2039 4294 2039 4295 2589 4295 2590 4295 2039 4296 2590 4296 2087 4296 2087 4297 2590 4297 2591 4297 2087 4298 2591 4298 2083 4298 2083 4299 2591 4299 2592 4299 2083 4300 2592 4300 2084 4300 2084 4301 2592 4301 2593 4301 2084 4302 2593 4302 2041 4302 2041 4303 2593 4303 2594 4303 2041 4304 2594 4304 2042 4304 2042 4305 2594 4305 2595 4305 2042 4306 2595 4306 2576 4306 2580 4307 2577 4307 2582 4307 2582 4308 2577 4308 2035 4308 2582 4309 2035 4309 2596 4309 2596 4310 2035 4310 2094 4310 2596 4311 2094 4311 2597 4311 2597 4312 2094 4312 2093 4312 2597 4313 2093 4313 2598 4313 2598 4314 2093 4314 2097 4314 2598 4315 2097 4315 2599 4315 2599 4316 2097 4316 2096 4316 2599 4317 2096 4317 2600 4317 2600 4318 2096 4318 2100 4318 2600 4319 2100 4319 2601 4319 2601 4320 2100 4320 2104 4320 2601 4321 2104 4321 2521 4321 2521 4322 2104 4322 2103 4322 2521 4323 2103 4323 2101 4323 2520 4324 2101 4324 2602 4324 2602 4325 2101 4325 2033 4325 2602 4326 2033 4326 2603 4326 2603 4327 2033 4327 2032 4327 2603 4328 2032 4328 2604 4328 2604 4329 2032 4329 2106 4329 2604 4330 2106 4330 2605 4330 2605 4331 2106 4331 2109 4331 2605 4332 2109 4332 2108 4332 2524 4333 2531 4333 2029 4333 2029 4334 2531 4334 2533 4334 2029 4335 2533 4335 2030 4335 2030 4336 2533 4336 2606 4336 2030 4337 2606 4337 2108 4337 2108 4338 2606 4338 2607 4338 2108 4339 2607 4339 2605 4339 2608 4340 2609 4340 2610 4340 2610 4341 2609 4341 2611 4341 2612 4342 2613 4342 2614 4342 2614 4343 2613 4343 2615 4343 2614 4344 2615 4344 2616 4344 2617 4345 2618 4345 2619 4345 2619 4346 2618 4346 2614 4346 2619 4347 2614 4347 2620 4347 2620 4348 2614 4348 2616 4348 2612 4349 2614 4349 2609 4349 2609 4350 2614 4350 2621 4350 2609 4351 2621 4351 2622 4351 2622 4352 2623 4352 2609 4352 2609 4353 2623 4353 2624 4353 2609 4354 2624 4354 2611 4354 2625 4355 2626 4355 2627 4355 2627 4356 2626 4356 2628 4356 2627 4357 2628 4357 2629 4357 2630 4358 2631 4358 2632 4358 2632 4359 2631 4359 2627 4359 2632 4360 2627 4360 2633 4360 2633 4361 2627 4361 2629 4361 2625 4362 2627 4362 2610 4362 2610 4363 2627 4363 2634 4363 2610 4364 2634 4364 2635 4364 2635 4365 2636 4365 2610 4365 2610 4366 2636 4366 2637 4366 2610 4367 2637 4367 2608 4367 2638 4368 2639 4368 2640 4368 2640 4369 2639 4369 2641 4369 2642 4370 2643 4370 2644 4370 2644 4371 2643 4371 2645 4371 2644 4372 2645 4372 2646 4372 2647 4373 2644 4373 2648 4373 2648 4374 2644 4374 2646 4374 2648 4375 2646 4375 2649 4375 2649 4376 2646 4376 2650 4376 2644 4377 2651 4377 2642 4377 2642 4378 2651 4378 2652 4378 2642 4379 2652 4379 2653 4379 2639 4380 2654 4380 2641 4380 2641 4381 2654 4381 2642 4381 2641 4382 2642 4382 2655 4382 2655 4383 2642 4383 2653 4383 2656 4384 2657 4384 2658 4384 2658 4385 2657 4385 2659 4385 2658 4386 2659 4386 2660 4386 2661 4387 2658 4387 2662 4387 2662 4388 2658 4388 2660 4388 2662 4389 2660 4389 2663 4389 2663 4390 2660 4390 2664 4390 2658 4391 2665 4391 2656 4391 2656 4392 2665 4392 2666 4392 2656 4393 2666 4393 2667 4393 2640 4394 2668 4394 2638 4394 2638 4395 2668 4395 2656 4395 2638 4396 2656 4396 2669 4396 2669 4397 2656 4397 2667 4397 2670 4398 2232 4398 2231 4398 2670 4399 2231 4399 2671 4399 2671 4400 2231 4400 2213 4400 2671 4401 2213 4401 2672 4401 2672 4402 2213 4402 2673 4402 2673 4403 2213 4403 2238 4403 2673 4404 2238 4404 2674 4404 2674 4405 2238 4405 2237 4405 2674 4406 2237 4406 2675 4406 2675 4407 2237 4407 2235 4407 2675 4408 2235 4408 2676 4408 2676 4409 2235 4409 2241 4409 2676 4410 2241 4410 2677 4410 2677 4411 2241 4411 2240 4411 2677 4412 2240 4412 2678 4412 2678 4413 2240 4413 2239 4413 2678 4414 2239 4414 2679 4414 2679 4415 2239 4415 2210 4415 2679 4416 2210 4416 2680 4416 2680 4417 2210 4417 2244 4417 2680 4418 2244 4418 2681 4418 2681 4419 2244 4419 2243 4419 2681 4420 2243 4420 2682 4420 2243 4421 2217 4421 2682 4421 2682 4422 2217 4422 2183 4422 2682 4423 2183 4423 2683 4423 2183 4424 2185 4424 2683 4424 2683 4425 2185 4425 2186 4425 2683 4426 2186 4426 2684 4426 2684 4427 2186 4427 2179 4427 2684 4428 2179 4428 2685 4428 2685 4429 2179 4429 2191 4429 2685 4430 2191 4430 2686 4430 2686 4431 2191 4431 2190 4431 2686 4432 2190 4432 2687 4432 2687 4433 2190 4433 2688 4433 2688 4434 2190 4434 2188 4434 2688 4435 2188 4435 2689 4435 2689 4436 2188 4436 2194 4436 2689 4437 2194 4437 2690 4437 2690 4438 2194 4438 2193 4438 2690 4439 2193 4439 2691 4439 2691 4440 2193 4440 2192 4440 2691 4441 2192 4441 2692 4441 2692 4442 2192 4442 2176 4442 2692 4443 2176 4443 2693 4443 2693 4444 2176 4444 2199 4444 2693 4445 2199 4445 2694 4445 2694 4446 2199 4446 2198 4446 2694 4447 2198 4447 2695 4447 2695 4448 2198 4448 2196 4448 2695 4449 2196 4449 2696 4449 2696 4450 2196 4450 2202 4450 2696 4451 2202 4451 2697 4451 2697 4452 2202 4452 2201 4452 2697 4453 2201 4453 2698 4453 2698 4454 2201 4454 2200 4454 2698 4455 2200 4455 2699 4455 2699 4456 2200 4456 2173 4456 2699 4457 2173 4457 2700 4457 2700 4458 2173 4458 2701 4458 2701 4459 2173 4459 2207 4459 2701 4460 2207 4460 2702 4460 2702 4461 2207 4461 2206 4461 2702 4462 2206 4462 2703 4462 2703 4463 2206 4463 2204 4463 2703 4464 2204 4464 2704 4464 2704 4465 2204 4465 2203 4465 2704 4466 2203 4466 2705 4466 2705 4467 2203 4467 2170 4467 2705 4468 2170 4468 2706 4468 2170 4469 2182 4469 2706 4469 2706 4470 2182 4470 2181 4470 2706 4471 2181 4471 2707 4471 2707 4472 2181 4472 2219 4472 2707 4473 2219 4473 2708 4473 2708 4474 2219 4474 2221 4474 2708 4475 2221 4475 2709 4475 2709 4476 2221 4476 2225 4476 2709 4477 2225 4477 2710 4477 2710 4478 2225 4478 2224 4478 2710 4479 2224 4479 2711 4479 2711 4480 2224 4480 2223 4480 2711 4481 2223 4481 2712 4481 2712 4482 2223 4482 2216 4482 2712 4483 2216 4483 2713 4483 2713 4484 2216 4484 2230 4484 2232 4485 2670 4485 2233 4485 2233 4486 2670 4486 2714 4486 2233 4487 2714 4487 2227 4487 2227 4488 2714 4488 2715 4488 2227 4489 2715 4489 2229 4489 2229 4490 2715 4490 2716 4490 2229 4491 2716 4491 2230 4491 2230 4492 2716 4492 2717 4492 2230 4493 2717 4493 2713 4493 2718 4494 2719 4494 2248 4494 2253 4495 2720 4495 2721 4495 2721 4496 2720 4496 2722 4496 2721 4497 2722 4497 2245 4497 2245 4498 2722 4498 2718 4498 2245 4499 2718 4499 2246 4499 2246 4500 2718 4500 2248 4500 2298 4501 2299 4501 2723 4501 2724 4502 2725 4502 2726 4502 2727 4503 2728 4503 2729 4503 2730 4504 2731 4504 2732 4504 2281 4505 2280 4505 2733 4505 2733 4506 2280 4506 2290 4506 2734 4507 2735 4507 2736 4507 2736 4508 2735 4508 2284 4508 2736 4509 2284 4509 2283 4509 2279 4510 2278 4510 2737 4510 2737 4511 2278 4511 2277 4511 2737 4512 2277 4512 2735 4512 2735 4513 2277 4513 2276 4513 2735 4514 2276 4514 2284 4514 1841 4515 1840 4515 2304 4515 2304 4516 1840 4516 1839 4516 2304 4517 1839 4517 1845 4517 1780 4518 1779 4518 2738 4518 2269 4519 2267 4519 2738 4519 2738 4520 2267 4520 2266 4520 2738 4521 2266 4521 2265 4521 2265 4522 2264 4522 2738 4522 2738 4523 2264 4523 2263 4523 2738 4524 2263 4524 1780 4524 2258 4525 2259 4525 2739 4525 2739 4526 2259 4526 2261 4526 2739 4527 2261 4527 2262 4527 2740 4528 2741 4528 2742 4528 2742 4529 2741 4529 2253 4529 2742 4530 2253 4530 2252 4530 2743 4531 2744 4531 2745 4531 2745 4532 2744 4532 2746 4532 2745 4533 2746 4533 2747 4533 2747 4534 2746 4534 2748 4534 2747 4535 2748 4535 2732 4535 2732 4536 2748 4536 2749 4536 2732 4537 2749 4537 2750 4537 2751 4538 2752 4538 2753 4538 2754 4539 2755 4539 2756 4539 2757 4540 2758 4540 2759 4540 2759 4541 2758 4541 2760 4541 2759 4542 2760 4542 2761 4542 2762 4543 2763 4543 2764 4543 2762 4544 2764 4544 2726 4544 2763 4545 2762 4545 2765 4545 2765 4546 2762 4546 2733 4546 2765 4547 2733 4547 2766 4547 2766 4548 2733 4548 2290 4548 2766 4549 2290 4549 2295 4549 2252 4550 2258 4550 2742 4550 2742 4551 2258 4551 2739 4551 2742 4552 2739 4552 2723 4552 2723 4553 2739 4553 2262 4553 2723 4554 2262 4554 2270 4554 2732 4555 2731 4555 2747 4555 2747 4556 2731 4556 2767 4556 2747 4557 2767 4557 2745 4557 2768 4558 2759 4558 2754 4558 2754 4559 2759 4559 2761 4559 2754 4560 2761 4560 2755 4560 2726 4561 2725 4561 2762 4561 2762 4562 2725 4562 2769 4562 2762 4563 2769 4563 2733 4563 2270 4564 2269 4564 2723 4564 2723 4565 2269 4565 2738 4565 2723 4566 2738 4566 2298 4566 2298 4567 2738 4567 1779 4567 2298 4568 1779 4568 1778 4568 2299 4569 2308 4569 2723 4569 2723 4570 2308 4570 2730 4570 2723 4571 2730 4571 2742 4571 2742 4572 2730 4572 2732 4572 2742 4573 2732 4573 2740 4573 2740 4574 2732 4574 2750 4574 2315 4575 2767 4575 2313 4575 2313 4576 2767 4576 2731 4576 2313 4577 2731 4577 2311 4577 2311 4578 2731 4578 2730 4578 2311 4579 2730 4579 2309 4579 2309 4580 2730 4580 2308 4580 2315 4581 2317 4581 2767 4581 2767 4582 2317 4582 2770 4582 2767 4583 2770 4583 2745 4583 2745 4584 2770 4584 2753 4584 2745 4585 2753 4585 2743 4585 2743 4586 2753 4586 2752 4586 2317 4587 2319 4587 2770 4587 2770 4588 2319 4588 2727 4588 2770 4589 2727 4589 2753 4589 2753 4590 2727 4590 2729 4590 2753 4591 2729 4591 2751 4591 2751 4592 2729 4592 2756 4592 2319 4593 2321 4593 2727 4593 2727 4594 2321 4594 2323 4594 2727 4595 2323 4595 2728 4595 2728 4596 2323 4596 2325 4596 2728 4597 2325 4597 2327 4597 2756 4598 2729 4598 2754 4598 2754 4599 2729 4599 2728 4599 2754 4600 2728 4600 2768 4600 2768 4601 2728 4601 2327 4601 2768 4602 2327 4602 2329 4602 2329 4603 2331 4603 2768 4603 2768 4604 2331 4604 2724 4604 2768 4605 2724 4605 2759 4605 2759 4606 2724 4606 2726 4606 2759 4607 2726 4607 2757 4607 2757 4608 2726 4608 2764 4608 2339 4609 2769 4609 2337 4609 2337 4610 2769 4610 2725 4610 2337 4611 2725 4611 2335 4611 2335 4612 2725 4612 2724 4612 2335 4613 2724 4613 2333 4613 2333 4614 2724 4614 2331 4614 2339 4615 2341 4615 2769 4615 2769 4616 2341 4616 2734 4616 2769 4617 2734 4617 2733 4617 2733 4618 2734 4618 2736 4618 2733 4619 2736 4619 2281 4619 2281 4620 2736 4620 2283 4620 1845 4621 2279 4621 2304 4621 2304 4622 2279 4622 2737 4622 2304 4623 2737 4623 2307 4623 2307 4624 2737 4624 2735 4624 2307 4625 2735 4625 2306 4625 2306 4626 2735 4626 2734 4626 2306 4627 2734 4627 2343 4627 2343 4628 2734 4628 2341 4628 2771 4629 2295 4629 2772 4629 2772 4630 2295 4630 2773 4630 2772 4631 2773 4631 2774 4631 2774 4632 2773 4632 2297 4632 2774 4633 2297 4633 2775 4633 2775 4634 2297 4634 2294 4634 2775 4635 2294 4635 2776 4635 2776 4636 2294 4636 2293 4636 2517 4637 2516 4637 2777 4637 2513 4638 2512 4638 2778 4638 2778 4639 2512 4639 2779 4639 2778 4640 2779 4640 2780 4640 2780 4641 2779 4641 2781 4641 2781 4642 2779 4642 2782 4642 2782 4643 2779 4643 2783 4643 2782 4644 2783 4644 2784 4644 2785 4645 2786 4645 2783 4645 2783 4646 2786 4646 2787 4646 2783 4647 2787 4647 2784 4647 2788 4648 2789 4648 2790 4648 2790 4649 2789 4649 2791 4649 2792 4650 2793 4650 2794 4650 2794 4651 2793 4651 2795 4651 2794 4652 2795 4652 2796 4652 2797 4653 2798 4653 2783 4653 2798 4654 2792 4654 2783 4654 2783 4655 2792 4655 2794 4655 2783 4656 2794 4656 2785 4656 2785 4657 2794 4657 2796 4657 2785 4658 2796 4658 2789 4658 2789 4659 2796 4659 2799 4659 2789 4660 2799 4660 2791 4660 2800 4661 2801 4661 2802 4661 2802 4662 2801 4662 2803 4662 2802 4663 2803 4663 2777 4663 2777 4664 2803 4664 2804 4664 2777 4665 2804 4665 2805 4665 2805 4666 2804 4666 2806 4666 2805 4667 2806 4667 2807 4667 2506 4668 2508 4668 2808 4668 2808 4669 2809 4669 2506 4669 2506 4670 2809 4670 2800 4670 2506 4671 2800 4671 2509 4671 2509 4672 2800 4672 2802 4672 2509 4673 2802 4673 2510 4673 2510 4674 2802 4674 2777 4674 2510 4675 2777 4675 2515 4675 2515 4676 2777 4676 2516 4676 2807 4677 2797 4677 2805 4677 2805 4678 2797 4678 2783 4678 2805 4679 2783 4679 2777 4679 2777 4680 2783 4680 2779 4680 2777 4681 2779 4681 2517 4681 2517 4682 2779 4682 2512 4682 2810 4683 2811 4683 2812 4683 2813 4684 2814 4684 2815 4684 2345 4685 2344 4685 2816 4685 2336 4686 2334 4686 2817 4686 2328 4687 2326 4687 2818 4687 2818 4688 2326 4688 2819 4688 2312 4689 2310 4689 2820 4689 2302 4690 2301 4690 2821 4690 1835 4691 1843 4691 2303 4691 2822 4692 2823 4692 2810 4692 2810 4693 2823 4693 2393 4693 2389 4694 2824 4694 2363 4694 2363 4695 2824 4695 2825 4695 2363 4696 2825 4696 2355 4696 2355 4697 2825 4697 2356 4697 2826 4698 2352 4698 2358 4698 2351 4699 2821 4699 2350 4699 2350 4700 2821 4700 2827 4700 2350 4701 2827 4701 2353 4701 2353 4702 2827 4702 2354 4702 2300 4703 1783 4703 1782 4703 2383 4704 2382 4704 2828 4704 2828 4705 2382 4705 1833 4705 2828 4706 1833 4706 1834 4706 2393 4707 2372 4707 2810 4707 2810 4708 2372 4708 2374 4708 2810 4709 2374 4709 2811 4709 2811 4710 2374 4710 2378 4710 2811 4711 2378 4711 2380 4711 2380 4712 2381 4712 2811 4712 2811 4713 2381 4713 2386 4713 2811 4714 2386 4714 2812 4714 2812 4715 2386 4715 2385 4715 2812 4716 2385 4716 2828 4716 2828 4717 2385 4717 2384 4717 2828 4718 2384 4718 2383 4718 2821 4719 2301 4719 2827 4719 2827 4720 2301 4720 2300 4720 2827 4721 2300 4721 2354 4721 2354 4722 2300 4722 1782 4722 2354 4723 1782 4723 1787 4723 2316 4724 2314 4724 2829 4724 2318 4725 2830 4725 2831 4725 2326 4726 2324 4726 2819 4726 2819 4727 2324 4727 2322 4727 2819 4728 2322 4728 2831 4728 2831 4729 2322 4729 2320 4729 2831 4730 2320 4730 2318 4730 2332 4731 2330 4731 2832 4731 2832 4732 2330 4732 2328 4732 2833 4733 2340 4733 2815 4733 2815 4734 2340 4734 2338 4734 2816 4735 2344 4735 2833 4735 2833 4736 2344 4736 2342 4736 2833 4737 2342 4737 2340 4737 1834 4738 1835 4738 2828 4738 2828 4739 1835 4739 2303 4739 2828 4740 2303 4740 2812 4740 2812 4741 2303 4741 2305 4741 2310 4742 2302 4742 2820 4742 2820 4743 2302 4743 2821 4743 2820 4744 2821 4744 2826 4744 2826 4745 2821 4745 2351 4745 2826 4746 2351 4746 2352 4746 2358 4747 2356 4747 2826 4747 2826 4748 2356 4748 2825 4748 2826 4749 2825 4749 2820 4749 2820 4750 2825 4750 2829 4750 2820 4751 2829 4751 2312 4751 2312 4752 2829 4752 2314 4752 2834 4753 2818 4753 2835 4753 2835 4754 2818 4754 2819 4754 2835 4755 2819 4755 2836 4755 2836 4756 2819 4756 2831 4756 2836 4757 2831 4757 2837 4757 2837 4758 2831 4758 2830 4758 2837 4759 2830 4759 2838 4759 2839 4760 2817 4760 2832 4760 2832 4761 2817 4761 2334 4761 2832 4762 2334 4762 2332 4762 2815 4763 2814 4763 2833 4763 2833 4764 2814 4764 2840 4764 2833 4765 2840 4765 2816 4765 2824 4766 2841 4766 2825 4766 2825 4767 2841 4767 2838 4767 2825 4768 2838 4768 2829 4768 2829 4769 2838 4769 2830 4769 2829 4770 2830 4770 2316 4770 2316 4771 2830 4771 2318 4771 2841 4772 2842 4772 2838 4772 2838 4773 2842 4773 2843 4773 2838 4774 2843 4774 2837 4774 2837 4775 2843 4775 2844 4775 2837 4776 2844 4776 2836 4776 2836 4777 2844 4777 2845 4777 2845 4778 2846 4778 2836 4778 2836 4779 2846 4779 2847 4779 2836 4780 2847 4780 2835 4780 2835 4781 2847 4781 2848 4781 2835 4782 2848 4782 2834 4782 2834 4783 2848 4783 2849 4783 2834 4784 2849 4784 2850 4784 2328 4785 2818 4785 2832 4785 2832 4786 2818 4786 2834 4786 2832 4787 2834 4787 2839 4787 2839 4788 2834 4788 2850 4788 2839 4789 2850 4789 2851 4789 2851 4790 2852 4790 2839 4790 2839 4791 2852 4791 2813 4791 2839 4792 2813 4792 2817 4792 2817 4793 2813 4793 2815 4793 2817 4794 2815 4794 2336 4794 2336 4795 2815 4795 2338 4795 2852 4796 2853 4796 2813 4796 2813 4797 2853 4797 2854 4797 2813 4798 2854 4798 2814 4798 2814 4799 2854 4799 2855 4799 2814 4800 2855 4800 2840 4800 2840 4801 2855 4801 2856 4801 2840 4802 2856 4802 2857 4802 2857 4803 2822 4803 2840 4803 2840 4804 2822 4804 2810 4804 2840 4805 2810 4805 2816 4805 2816 4806 2810 4806 2812 4806 2816 4807 2812 4807 2345 4807 2345 4808 2812 4808 2305 4808 2858 4809 2389 4809 2859 4809 2859 4810 2389 4810 2390 4810 2859 4811 2390 4811 2860 4811 2860 4812 2390 4812 2388 4812 2860 4813 2388 4813 2861 4813 2861 4814 2388 4814 2387 4814 2392 4815 2862 4815 2863 4815 2392 4816 2863 4816 2391 4816 2391 4817 2863 4817 2864 4817 2391 4818 2864 4818 2394 4818 2862 4819 2392 4819 2865 4819 2865 4820 2392 4820 2393 4820 2865 4821 2393 4821 2866 4821 2867 4822 2868 4822 2869 4822 2561 4823 2567 4823 2870 4823 2871 4824 2872 4824 2873 4824 2874 4825 2875 4825 2876 4825 2876 4826 2875 4826 2877 4826 2870 4827 2878 4827 2879 4827 2566 4828 2880 4828 2567 4828 2567 4829 2880 4829 2881 4829 2567 4830 2881 4830 2870 4830 2870 4831 2881 4831 2882 4831 2870 4832 2882 4832 2878 4832 2561 4833 2870 4833 2560 4833 2560 4834 2870 4834 2883 4834 2560 4835 2883 4835 2559 4835 2559 4836 2883 4836 2884 4836 2559 4837 2884 4837 2558 4837 2558 4838 2884 4838 2885 4838 2558 4839 2885 4839 2557 4839 2886 4840 2553 4840 2887 4840 2887 4841 2553 4841 2554 4841 2887 4842 2554 4842 2888 4842 2888 4843 2554 4843 2555 4843 2888 4844 2555 4844 2885 4844 2885 4845 2555 4845 2556 4845 2885 4846 2556 4846 2557 4846 2889 4847 2551 4847 2886 4847 2886 4848 2551 4848 2552 4848 2886 4849 2552 4849 2553 4849 2535 4850 2547 4850 2890 4850 2890 4851 2547 4851 2548 4851 2890 4852 2548 4852 2891 4852 2891 4853 2548 4853 2549 4853 2891 4854 2549 4854 2889 4854 2889 4855 2549 4855 2550 4855 2889 4856 2550 4856 2551 4856 2536 4857 2535 4857 2892 4857 2892 4858 2535 4858 2890 4858 2892 4859 2890 4859 2893 4859 2893 4860 2890 4860 2894 4860 2895 4861 2867 4861 2896 4861 2896 4862 2867 4862 2869 4862 2896 4863 2869 4863 2897 4863 2897 4864 2869 4864 2898 4864 2897 4865 2898 4865 2899 4865 2899 4866 2898 4866 2900 4866 2901 4867 2902 4867 2900 4867 2900 4868 2902 4868 2903 4868 2900 4869 2903 4869 2899 4869 2904 4870 2905 4870 2901 4870 2901 4871 2905 4871 2906 4871 2901 4872 2906 4872 2902 4872 2907 4873 2908 4873 2909 4873 2909 4874 2908 4874 2910 4874 2909 4875 2910 4875 2904 4875 2904 4876 2910 4876 2911 4876 2904 4877 2911 4877 2905 4877 2907 4878 2909 4878 2912 4878 2912 4879 2909 4879 2913 4879 2912 4880 2913 4880 2914 4880 2914 4881 2913 4881 2915 4881 2914 4882 2915 4882 2916 4882 2916 4883 2915 4883 2917 4883 2916 4884 2917 4884 2918 4884 2877 4885 2871 4885 2876 4885 2876 4886 2871 4886 2873 4886 2876 4887 2873 4887 2917 4887 2917 4888 2873 4888 2919 4888 2917 4889 2919 4889 2918 4889 2879 4890 2874 4890 2870 4890 2870 4891 2874 4891 2876 4891 2870 4892 2876 4892 2883 4892 2883 4893 2876 4893 2917 4893 2883 4894 2917 4894 2884 4894 2884 4895 2917 4895 2915 4895 2884 4896 2915 4896 2885 4896 2885 4897 2915 4897 2913 4897 2885 4898 2913 4898 2888 4898 2888 4899 2913 4899 2909 4899 2888 4900 2909 4900 2887 4900 2887 4901 2909 4901 2904 4901 2887 4902 2904 4902 2886 4902 2886 4903 2904 4903 2901 4903 2886 4904 2901 4904 2889 4904 2889 4905 2901 4905 2900 4905 2889 4906 2900 4906 2891 4906 2891 4907 2900 4907 2898 4907 2891 4908 2898 4908 2890 4908 2890 4909 2898 4909 2869 4909 2890 4910 2869 4910 2894 4910 2894 4911 2869 4911 2868 4911 2920 4912 2921 4912 2922 4912 2923 4913 2924 4913 2925 4913 2926 4914 2927 4914 2928 4914 2928 4915 2927 4915 2929 4915 2930 4916 2931 4916 2932 4916 2932 4917 2931 4917 2933 4917 2932 4918 2933 4918 2934 4918 2935 4919 2936 4919 2937 4919 2937 4920 2936 4920 2938 4920 2937 4921 2938 4921 2939 4921 2940 4922 2941 4922 2942 4922 2942 4923 2941 4923 2943 4923 2586 4924 2585 4924 2944 4924 2944 4925 2585 4925 2945 4925 2945 4926 2946 4926 2944 4926 2944 4927 2946 4927 2947 4927 2944 4928 2947 4928 2948 4928 2586 4929 2944 4929 2587 4929 2587 4930 2944 4930 2949 4930 2587 4931 2949 4931 2588 4931 2588 4932 2949 4932 2589 4932 2589 4933 2949 4933 2950 4933 2589 4934 2950 4934 2590 4934 2590 4935 2950 4935 2951 4935 2590 4936 2951 4936 2591 4936 2591 4937 2951 4937 2592 4937 2592 4938 2951 4938 2952 4938 2592 4939 2952 4939 2593 4939 2593 4940 2952 4940 2594 4940 2594 4941 2952 4941 2953 4941 2594 4942 2953 4942 2595 4942 2595 4943 2953 4943 2954 4943 2595 4944 2954 4944 2576 4944 2576 4945 2954 4945 2575 4945 2575 4946 2954 4946 2955 4946 2575 4947 2955 4947 2574 4947 2574 4948 2955 4948 2573 4948 2573 4949 2955 4949 2956 4949 2573 4950 2956 4950 2572 4950 2957 4951 2958 4951 2959 4951 2572 4952 2956 4952 2562 4952 2562 4953 2956 4953 2957 4953 2562 4954 2957 4954 2563 4954 2563 4955 2957 4955 2959 4955 2563 4956 2959 4956 2564 4956 2960 4957 2961 4957 2957 4957 2961 4958 2962 4958 2957 4958 2957 4959 2962 4959 2963 4959 2957 4960 2963 4960 2958 4960 2964 4961 2965 4961 2966 4961 2967 4962 2968 4962 2966 4962 2966 4963 2968 4963 2969 4963 2966 4964 2969 4964 2964 4964 2970 4965 2971 4965 2972 4965 2923 4966 2925 4966 2973 4966 2974 4967 2971 4967 2975 4967 2975 4968 2971 4968 2970 4968 2975 4969 2970 4969 2976 4969 2976 4970 2970 4970 2977 4970 2976 4971 2977 4971 2978 4971 2979 4972 2980 4972 2981 4972 2979 4973 2981 4973 2982 4973 2981 4974 2983 4974 2982 4974 2982 4975 2983 4975 2984 4975 2982 4976 2984 4976 2977 4976 2977 4977 2984 4977 2985 4977 2977 4978 2985 4978 2978 4978 2980 4979 2979 4979 2986 4979 2986 4980 2979 4980 2987 4980 2986 4981 2987 4981 2988 4981 2988 4982 2987 4982 2989 4982 2989 4983 2987 4983 2990 4983 2989 4984 2990 4984 2991 4984 2922 4985 2921 4985 2990 4985 2990 4986 2921 4986 2992 4986 2990 4987 2992 4987 2991 4987 2920 4988 2922 4988 2993 4988 2993 4989 2922 4989 2994 4989 2993 4990 2994 4990 2995 4990 2995 4991 2994 4991 2996 4991 2996 4992 2994 4992 2997 4992 2996 4993 2997 4993 2998 4993 2998 4994 2997 4994 2999 4994 2999 4995 2997 4995 2932 4995 2999 4996 2932 4996 3000 4996 3000 4997 2932 4997 2934 4997 3000 4998 2934 4998 3001 4998 2929 4999 2930 4999 2928 4999 2928 5000 2930 5000 2932 5000 2928 5001 2932 5001 3002 5001 3002 5002 2932 5002 2997 5002 3002 5003 2997 5003 3003 5003 3003 5004 2997 5004 2994 5004 3003 5005 2994 5005 3004 5005 3004 5006 2994 5006 2922 5006 3004 5007 2922 5007 3005 5007 3005 5008 2922 5008 2990 5008 3005 5009 2990 5009 3006 5009 3006 5010 2990 5010 2987 5010 3006 5011 2987 5011 3007 5011 3007 5012 2987 5012 2979 5012 3007 5013 2979 5013 3008 5013 3008 5014 2979 5014 2982 5014 3008 5015 2982 5015 3009 5015 3009 5016 2982 5016 2977 5016 3009 5017 2977 5017 2925 5017 2925 5018 2977 5018 2970 5018 2925 5019 2970 5019 2973 5019 2973 5020 2970 5020 2972 5020 2939 5021 2926 5021 2937 5021 2937 5022 2926 5022 2928 5022 2937 5023 2928 5023 3010 5023 3010 5024 2928 5024 3002 5024 3010 5025 3002 5025 3011 5025 3011 5026 3002 5026 3003 5026 3011 5027 3003 5027 3012 5027 3012 5028 3003 5028 3004 5028 3012 5029 3004 5029 3013 5029 3013 5030 3004 5030 3005 5030 3013 5031 3005 5031 3014 5031 3014 5032 3005 5032 3006 5032 3014 5033 3006 5033 3015 5033 3015 5034 3006 5034 3007 5034 3015 5035 3007 5035 3016 5035 3016 5036 3007 5036 3008 5036 3016 5037 3008 5037 3017 5037 3017 5038 3008 5038 3009 5038 3017 5039 3009 5039 2966 5039 2966 5040 3009 5040 2925 5040 2966 5041 2925 5041 2967 5041 2967 5042 2925 5042 2924 5042 2943 5043 2935 5043 2942 5043 2942 5044 2935 5044 2937 5044 2942 5045 2937 5045 3018 5045 3018 5046 2937 5046 3010 5046 3018 5047 3010 5047 3019 5047 3019 5048 3010 5048 3011 5048 3019 5049 3011 5049 3020 5049 3020 5050 3011 5050 3012 5050 3020 5051 3012 5051 3021 5051 3021 5052 3012 5052 3013 5052 3021 5053 3013 5053 3022 5053 3022 5054 3013 5054 3014 5054 3022 5055 3014 5055 3023 5055 3023 5056 3014 5056 3015 5056 3023 5057 3015 5057 3024 5057 3024 5058 3015 5058 3016 5058 3024 5059 3016 5059 3025 5059 3025 5060 3016 5060 3017 5060 3025 5061 3017 5061 3026 5061 3026 5062 3017 5062 2966 5062 3026 5063 2966 5063 3027 5063 3027 5064 2966 5064 2965 5064 2948 5065 2940 5065 2944 5065 2944 5066 2940 5066 2942 5066 2944 5067 2942 5067 2949 5067 2949 5068 2942 5068 3018 5068 2949 5069 3018 5069 2950 5069 2950 5070 3018 5070 3019 5070 2950 5071 3019 5071 2951 5071 2951 5072 3019 5072 3020 5072 2951 5073 3020 5073 2952 5073 2952 5074 3020 5074 3021 5074 2952 5075 3021 5075 2953 5075 2953 5076 3021 5076 3022 5076 2953 5077 3022 5077 2954 5077 2954 5078 3022 5078 3023 5078 2954 5079 3023 5079 2955 5079 2955 5080 3023 5080 3024 5080 2955 5081 3024 5081 2956 5081 2956 5082 3024 5082 3025 5082 2956 5083 3025 5083 2957 5083 2957 5084 3025 5084 3026 5084 2957 5085 3026 5085 2960 5085 2960 5086 3026 5086 3027 5086 3028 5087 3029 5087 3030 5087 3031 5088 3032 5088 3033 5088 3034 5089 3035 5089 3030 5089 3036 5090 3037 5090 3038 5090 3039 5091 3040 5091 3041 5091 3042 5092 2579 5092 3043 5092 3042 5093 3043 5093 3044 5093 3045 5094 3046 5094 3047 5094 3047 5095 3046 5095 3048 5095 3047 5096 3048 5096 3049 5096 3050 5097 3051 5097 3052 5097 3052 5098 3051 5098 3053 5098 3054 5099 3050 5099 3055 5099 3055 5100 3050 5100 3052 5100 3055 5101 3052 5101 3056 5101 3056 5102 3052 5102 3057 5102 3056 5103 3057 5103 3058 5103 3058 5104 3057 5104 3059 5104 3058 5105 3059 5105 3060 5105 3041 5106 3040 5106 3059 5106 3059 5107 3040 5107 3061 5107 3059 5108 3061 5108 3060 5108 3038 5109 3037 5109 3062 5109 3037 5110 3063 5110 3062 5110 3062 5111 3063 5111 3064 5111 3062 5112 3064 5112 3033 5112 3033 5113 3064 5113 3065 5113 3033 5114 3065 5114 3066 5114 3034 5115 3030 5115 3067 5115 3068 5116 3069 5116 2533 5116 2502 5117 3067 5117 2503 5117 2503 5118 3067 5118 3070 5118 2503 5119 3070 5119 2511 5119 2511 5120 3070 5120 3068 5120 2511 5121 3068 5121 2504 5121 2504 5122 3068 5122 2533 5122 2504 5123 2533 5123 2505 5123 3053 5124 3045 5124 3052 5124 3052 5125 3045 5125 3047 5125 3052 5126 3047 5126 3057 5126 3057 5127 3047 5127 3071 5127 3057 5128 3071 5128 3059 5128 3059 5129 3071 5129 3072 5129 3059 5130 3072 5130 3041 5130 3033 5131 3032 5131 3062 5131 3062 5132 3032 5132 3073 5132 3062 5133 3073 5133 3038 5133 3074 5134 3028 5134 3075 5134 3075 5135 3028 5135 3030 5135 3075 5136 3030 5136 3076 5136 3076 5137 3030 5137 3035 5137 2597 5138 3072 5138 3077 5138 3077 5139 3072 5139 3071 5139 3077 5140 3071 5140 2582 5140 2582 5141 3071 5141 3047 5141 2582 5142 3047 5142 3043 5142 3043 5143 3047 5143 3049 5143 3043 5144 3049 5144 3044 5144 2597 5145 3078 5145 3072 5145 3072 5146 3078 5146 3031 5146 3072 5147 3031 5147 3041 5147 3041 5148 3031 5148 3033 5148 3041 5149 3033 5149 3039 5149 3039 5150 3033 5150 3066 5150 3078 5151 3079 5151 3031 5151 3031 5152 3079 5152 2600 5152 3031 5153 2600 5153 3032 5153 3032 5154 2600 5154 3080 5154 3032 5155 3080 5155 3073 5155 3073 5156 3080 5156 2521 5156 2521 5157 3081 5157 3073 5157 3073 5158 3081 5158 3074 5158 3073 5159 3074 5159 3038 5159 3038 5160 3074 5160 3075 5160 3038 5161 3075 5161 3036 5161 3036 5162 3075 5162 3076 5162 3081 5163 3082 5163 3074 5163 3074 5164 3082 5164 2603 5164 3074 5165 2603 5165 3028 5165 3028 5166 2603 5166 3083 5166 3028 5167 3083 5167 3029 5167 3029 5168 3083 5168 2605 5168 3029 5169 2605 5169 3084 5169 3067 5170 3030 5170 3070 5170 3070 5171 3030 5171 3029 5171 3070 5172 3029 5172 3068 5172 3068 5173 3029 5173 3084 5173 3068 5174 3084 5174 3069 5174 3085 5175 3086 5175 3087 5175 939 5176 938 5176 3088 5176 1655 5177 1654 5177 3089 5177 1010 5178 1009 5178 3090 5178 3091 5179 2248 5179 3092 5179 3092 5180 2248 5180 2719 5180 3093 5181 3094 5181 3095 5181 972 5182 2248 5182 973 5182 973 5183 2248 5183 3091 5183 973 5184 3091 5184 1018 5184 1018 5185 3091 5185 3096 5185 1018 5186 3096 5186 1019 5186 1019 5187 3096 5187 3097 5187 1019 5188 3097 5188 1021 5188 3097 5189 3093 5189 1021 5189 1021 5190 3093 5190 3095 5190 1021 5191 3095 5191 1022 5191 1022 5192 3095 5192 1023 5192 1014 5193 1015 5193 3098 5193 3098 5194 1015 5194 1017 5194 3098 5195 1017 5195 3095 5195 3095 5196 1017 5196 1024 5196 3095 5197 1024 5197 1023 5197 3099 5198 1005 5198 1012 5198 1005 5199 3099 5199 1006 5199 1006 5200 3099 5200 3100 5200 1006 5201 3100 5201 3090 5201 1009 5202 1008 5202 3090 5202 3090 5203 1008 5203 1007 5203 3090 5204 1007 5204 1006 5204 1011 5205 1010 5205 3101 5205 3102 5206 1646 5206 3101 5206 3101 5207 1646 5207 1647 5207 3101 5208 1647 5208 1011 5208 1650 5209 1649 5209 3103 5209 3103 5210 1649 5210 1648 5210 3103 5211 1648 5211 3102 5211 3102 5212 1648 5212 1645 5212 3102 5213 1645 5213 1646 5213 3089 5214 1654 5214 3103 5214 3103 5215 1654 5215 1651 5215 3103 5216 1651 5216 1650 5216 954 5217 1656 5217 955 5217 955 5218 1656 5218 3104 5218 955 5219 3104 5219 957 5219 3105 5220 947 5220 946 5220 942 5221 941 5221 3087 5221 3087 5222 941 5222 949 5222 3087 5223 949 5223 3105 5223 3105 5224 949 5224 948 5224 3105 5225 948 5225 947 5225 3086 5226 944 5226 3087 5226 3087 5227 944 5227 943 5227 3087 5228 943 5228 942 5228 3086 5229 3106 5229 944 5229 944 5230 3106 5230 3107 5230 944 5231 3107 5231 945 5231 3107 5232 3108 5232 945 5232 945 5233 3108 5233 3109 5233 945 5234 3109 5234 935 5234 935 5235 3109 5235 936 5235 3088 5236 938 5236 3109 5236 3109 5237 938 5237 937 5237 3109 5238 937 5238 936 5238 939 5239 3088 5239 940 5239 940 5240 3088 5240 3110 5240 940 5241 3110 5241 932 5241 3111 5242 3112 5242 3087 5242 3087 5243 3112 5243 3113 5243 3087 5244 3113 5244 3085 5244 3114 5245 3115 5245 3116 5245 3116 5246 3117 5246 3114 5246 3114 5247 3117 5247 3118 5247 3114 5248 3118 5248 3119 5248 3119 5249 3118 5249 3120 5249 3119 5250 3120 5250 3121 5250 3098 5251 3122 5251 3114 5251 3114 5252 3122 5252 3123 5252 3114 5253 3123 5253 3115 5253 3124 5254 3125 5254 3098 5254 3098 5255 3125 5255 3126 5255 3098 5256 3126 5256 3122 5256 3094 5257 3127 5257 3095 5257 3095 5258 3127 5258 3128 5258 3095 5259 3128 5259 3098 5259 3098 5260 3128 5260 3129 5260 3098 5261 3129 5261 3124 5261 1010 5262 3090 5262 3101 5262 3101 5263 3090 5263 3100 5263 3101 5264 3100 5264 3102 5264 3102 5265 3100 5265 3130 5265 3102 5266 3130 5266 3103 5266 3103 5267 3130 5267 3131 5267 3103 5268 3131 5268 3089 5268 3121 5269 3111 5269 3119 5269 3119 5270 3111 5270 3087 5270 3119 5271 3087 5271 3132 5271 3132 5272 3087 5272 3105 5272 3132 5273 3105 5273 3104 5273 3104 5274 3105 5274 946 5274 3104 5275 946 5275 957 5275 1012 5276 1014 5276 3099 5276 3099 5277 1014 5277 3098 5277 3099 5278 3098 5278 3100 5278 3100 5279 3098 5279 3114 5279 3100 5280 3114 5280 3130 5280 3130 5281 3114 5281 3119 5281 3130 5282 3119 5282 3131 5282 3131 5283 3119 5283 3132 5283 3131 5284 3132 5284 3089 5284 3089 5285 3132 5285 3104 5285 3089 5286 3104 5286 1655 5286 1655 5287 3104 5287 1656 5287 933 5288 932 5288 3133 5288 922 5289 964 5289 3134 5289 2451 5290 3134 5290 2452 5290 2452 5291 3134 5291 2453 5291 2450 5292 1511 5292 961 5292 2450 5293 961 5293 2451 5293 922 5294 3134 5294 923 5294 2451 5295 961 5295 3134 5295 3134 5296 961 5296 960 5296 3134 5297 960 5297 923 5297 3135 5298 2449 5298 3134 5298 3134 5299 2449 5299 2448 5299 3134 5300 2448 5300 2453 5300 3136 5301 2460 5301 2459 5301 2458 5302 3137 5302 2459 5302 2459 5303 3137 5303 3138 5303 2459 5304 3138 5304 3136 5304 2458 5305 2457 5305 3137 5305 3137 5306 2457 5306 2456 5306 3137 5307 2456 5307 3135 5307 3135 5308 2456 5308 2454 5308 3135 5309 2454 5309 2449 5309 3139 5310 3140 5310 3135 5310 3135 5311 3140 5311 3141 5311 3135 5312 3141 5312 3142 5312 3142 5313 3143 5313 3135 5313 3135 5314 3143 5314 3144 5314 3135 5315 3144 5315 3137 5315 3145 5316 3146 5316 3134 5316 3134 5317 3146 5317 3147 5317 3134 5318 3147 5318 3135 5318 3135 5319 3147 5319 3148 5319 3135 5320 3148 5320 3139 5320 3145 5321 3134 5321 3149 5321 3149 5322 3134 5322 964 5322 3149 5323 964 5323 3150 5323 964 5324 963 5324 3150 5324 3150 5325 963 5325 962 5325 3150 5326 962 5326 3151 5326 3151 5327 962 5327 931 5327 3151 5328 931 5328 3152 5328 3152 5329 931 5329 3153 5329 3153 5330 931 5330 930 5330 3153 5331 930 5331 3154 5331 3154 5332 930 5332 929 5332 3154 5333 929 5333 3155 5333 929 5334 927 5334 3155 5334 3155 5335 927 5335 926 5335 3155 5336 926 5336 3133 5336 3133 5337 926 5337 934 5337 3133 5338 934 5338 933 5338 3156 5339 3157 5339 3158 5339 3159 5340 3160 5340 2719 5340 3157 5341 3161 5341 3158 5341 3158 5342 3161 5342 3162 5342 3158 5343 3162 5343 3159 5343 3159 5344 3162 5344 3163 5344 3159 5345 3163 5345 3160 5345 3164 5346 3165 5346 3166 5346 3156 5347 3158 5347 3167 5347 3167 5348 3158 5348 3166 5348 3167 5349 3166 5349 3168 5349 3168 5350 3166 5350 3165 5350 3168 5351 3165 5351 3169 5351 3166 5352 3170 5352 3171 5352 3164 5353 3166 5353 3172 5353 3172 5354 3166 5354 3171 5354 3172 5355 3171 5355 3173 5355 3170 5356 3166 5356 3174 5356 3174 5357 3166 5357 3158 5357 3174 5358 3158 5358 3175 5358 3176 5359 3177 5359 3158 5359 3158 5360 3177 5360 3178 5360 3158 5361 3178 5361 3175 5361 2719 5362 2718 5362 3159 5362 3159 5363 2718 5363 2722 5363 3159 5364 2722 5364 2720 5364 2720 5365 3179 5365 3159 5365 3159 5366 3179 5366 3180 5366 3159 5367 3180 5367 3158 5367 3158 5368 3180 5368 3181 5368 3158 5369 3181 5369 3176 5369 3182 5370 3183 5370 2631 5370 2631 5371 3183 5371 2627 5371 2627 5372 3183 5372 3184 5372 2627 5373 3184 5373 2634 5373 3185 5374 2635 5374 3186 5374 3186 5375 2635 5375 2634 5375 3186 5376 2634 5376 3187 5376 3187 5377 2634 5377 3184 5377 3188 5378 3189 5378 2613 5378 2613 5379 2612 5379 3188 5379 3188 5380 2612 5380 2609 5380 3188 5381 2609 5381 3190 5381 3190 5382 2609 5382 2608 5382 3190 5383 2608 5383 3191 5383 3191 5384 2608 5384 2637 5384 3191 5385 2637 5385 3185 5385 3185 5386 2637 5386 2636 5386 3185 5387 2636 5387 2635 5387 3189 5388 3192 5388 2613 5388 2613 5389 3192 5389 3193 5389 2613 5390 3193 5390 2615 5390 2615 5391 3193 5391 3194 5391 2615 5392 3194 5392 2616 5392 2616 5393 3194 5393 3195 5393 2616 5394 3195 5394 2620 5394 2620 5395 3195 5395 3196 5395 2620 5396 3196 5396 2619 5396 2619 5397 3196 5397 3197 5397 2619 5398 3197 5398 2617 5398 2617 5399 3197 5399 2618 5399 2618 5400 3197 5400 3198 5400 2618 5401 3198 5401 2614 5401 2614 5402 3198 5402 3199 5402 2614 5403 3199 5403 2621 5403 3199 5404 3200 5404 2621 5404 2621 5405 3200 5405 3201 5405 2621 5406 3201 5406 2622 5406 2622 5407 3201 5407 3202 5407 2622 5408 3202 5408 2623 5408 2623 5409 3202 5409 3203 5409 2623 5410 3203 5410 2624 5410 2624 5411 3203 5411 3204 5411 2624 5412 3204 5412 2611 5412 2611 5413 3204 5413 3205 5413 2611 5414 3205 5414 2610 5414 2610 5415 3205 5415 3206 5415 2610 5416 3206 5416 2625 5416 2625 5417 3206 5417 3207 5417 2625 5418 3207 5418 2626 5418 2626 5419 3207 5419 3208 5419 2626 5420 3208 5420 2628 5420 2628 5421 3208 5421 3209 5421 2628 5422 3209 5422 2629 5422 2629 5423 3209 5423 3210 5423 2629 5424 3210 5424 2633 5424 2633 5425 3210 5425 3211 5425 2633 5426 3211 5426 2632 5426 2632 5427 3211 5427 3182 5427 2632 5428 3182 5428 2630 5428 2630 5429 3182 5429 2631 5429 3212 5430 3213 5430 3214 5430 3215 5431 3216 5431 3217 5431 3218 5432 3219 5432 3220 5432 3221 5433 3222 5433 3223 5433 3224 5434 3225 5434 3226 5434 3227 5435 3228 5435 3229 5435 3230 5436 3231 5436 3232 5436 3233 5437 3234 5437 3235 5437 3236 5438 3237 5438 3238 5438 3239 5439 3240 5439 3226 5439 3241 5440 3242 5440 3243 5440 3244 5441 3245 5441 3246 5441 3247 5442 3248 5442 3249 5442 3250 5443 3251 5443 3252 5443 3251 5444 3250 5444 3253 5444 3253 5445 3250 5445 3254 5445 3253 5446 3254 5446 3255 5446 3255 5447 3254 5447 3256 5447 3255 5448 3256 5448 3257 5448 3249 5449 3248 5449 3256 5449 3256 5450 3248 5450 3258 5450 3256 5451 3258 5451 3257 5451 3259 5452 3235 5452 3260 5452 3260 5453 3235 5453 3261 5453 3260 5454 3261 5454 3262 5454 3262 5455 3261 5455 3263 5455 3264 5456 3265 5456 3263 5456 3263 5457 3265 5457 3266 5457 3263 5458 3266 5458 3262 5458 3267 5459 3268 5459 3232 5459 3232 5460 3268 5460 3269 5460 3243 5461 3242 5461 3267 5461 3267 5462 3242 5462 3270 5462 3267 5463 3270 5463 3268 5463 3271 5464 3229 5464 3272 5464 3272 5465 3229 5465 3273 5465 3272 5466 3273 5466 3274 5466 3274 5467 3273 5467 3275 5467 3274 5468 3275 5468 3276 5468 3276 5469 3275 5469 3277 5469 3278 5470 3279 5470 3239 5470 3279 5471 3278 5471 3280 5471 3281 5472 3282 5472 3283 5472 3283 5473 3282 5473 3284 5473 3285 5474 3223 5474 3286 5474 3286 5475 3223 5475 3287 5475 3286 5476 3287 5476 3288 5476 3288 5477 3287 5477 3289 5477 3290 5478 3291 5478 3289 5478 3289 5479 3291 5479 3292 5479 3289 5480 3292 5480 3288 5480 3220 5481 3293 5481 3294 5481 3238 5482 3237 5482 3293 5482 3293 5483 3237 5483 3295 5483 3293 5484 3295 5484 3294 5484 3296 5485 3217 5485 3297 5485 3297 5486 3217 5486 3298 5486 3299 5487 3300 5487 3301 5487 3301 5488 3300 5488 3302 5488 3301 5489 3302 5489 3298 5489 3298 5490 3302 5490 3303 5490 3298 5491 3303 5491 3297 5491 3304 5492 3305 5492 3214 5492 3250 5493 3306 5493 3254 5493 3254 5494 3306 5494 3307 5494 3254 5495 3307 5495 3256 5495 3256 5496 3307 5496 3308 5496 3256 5497 3308 5497 3249 5497 3235 5498 3234 5498 3261 5498 3261 5499 3234 5499 3309 5499 3261 5500 3309 5500 3263 5500 3232 5501 3231 5501 3267 5501 3267 5502 3231 5502 3310 5502 3267 5503 3310 5503 3243 5503 3229 5504 3228 5504 3273 5504 3273 5505 3228 5505 3311 5505 3273 5506 3311 5506 3275 5506 3239 5507 3226 5507 3278 5507 3278 5508 3226 5508 3225 5508 3278 5509 3225 5509 3312 5509 3313 5510 3283 5510 3314 5510 3314 5511 3283 5511 3284 5511 3314 5512 3284 5512 3280 5512 3223 5513 3222 5513 3287 5513 3287 5514 3222 5514 3315 5514 3287 5515 3315 5515 3289 5515 3220 5516 3219 5516 3293 5516 3293 5517 3219 5517 3316 5517 3293 5518 3316 5518 3238 5518 3217 5519 3216 5519 3298 5519 3298 5520 3216 5520 3317 5520 3298 5521 3317 5521 3301 5521 3304 5522 3214 5522 3318 5522 3318 5523 3214 5523 3213 5523 3318 5524 3213 5524 3319 5524 2683 5525 3306 5525 3319 5525 3319 5526 3306 5526 3250 5526 3319 5527 3250 5527 3318 5527 3318 5528 3250 5528 3252 5528 3318 5529 3252 5529 3304 5529 2687 5530 3308 5530 2686 5530 2686 5531 3308 5531 3307 5531 2686 5532 3307 5532 2685 5532 2685 5533 3307 5533 3306 5533 2685 5534 3306 5534 2684 5534 2684 5535 3306 5535 2683 5535 2687 5536 2688 5536 3308 5536 3308 5537 2688 5537 3233 5537 3308 5538 3233 5538 3249 5538 3249 5539 3233 5539 3235 5539 3249 5540 3235 5540 3247 5540 3247 5541 3235 5541 3259 5541 2692 5542 3309 5542 2691 5542 2691 5543 3309 5543 3234 5543 2691 5544 3234 5544 2690 5544 2690 5545 3234 5545 3233 5545 2690 5546 3233 5546 2689 5546 2689 5547 3233 5547 2688 5547 2692 5548 2693 5548 3309 5548 3309 5549 2693 5549 3320 5549 3309 5550 3320 5550 3263 5550 3263 5551 3320 5551 3246 5551 3263 5552 3246 5552 3264 5552 3264 5553 3246 5553 3245 5553 2693 5554 2694 5554 3320 5554 3320 5555 2694 5555 3230 5555 3320 5556 3230 5556 3246 5556 3246 5557 3230 5557 3232 5557 3246 5558 3232 5558 3244 5558 3244 5559 3232 5559 3269 5559 2694 5560 2695 5560 3230 5560 3230 5561 2695 5561 2696 5561 3230 5562 2696 5562 3231 5562 3231 5563 2696 5563 2697 5563 3231 5564 2697 5564 3310 5564 3310 5565 2697 5565 2698 5565 2698 5566 2699 5566 3310 5566 3310 5567 2699 5567 3227 5567 3310 5568 3227 5568 3243 5568 3243 5569 3227 5569 3229 5569 3243 5570 3229 5570 3241 5570 3241 5571 3229 5571 3271 5571 2699 5572 2700 5572 3227 5572 3227 5573 2700 5573 2701 5573 3227 5574 2701 5574 3228 5574 3228 5575 2701 5575 2702 5575 3228 5576 2702 5576 3311 5576 3311 5577 2702 5577 2703 5577 2703 5578 2704 5578 3311 5578 3311 5579 2704 5579 3224 5579 3311 5580 3224 5580 3275 5580 3275 5581 3224 5581 3226 5581 3275 5582 3226 5582 3277 5582 3277 5583 3226 5583 3240 5583 2704 5584 2705 5584 3224 5584 3224 5585 2705 5585 2706 5585 3224 5586 2706 5586 3225 5586 3225 5587 2706 5587 2707 5587 3225 5588 2707 5588 3312 5588 3312 5589 2707 5589 2708 5589 3312 5590 2708 5590 2709 5590 3280 5591 3278 5591 3314 5591 3314 5592 3278 5592 3312 5592 3314 5593 3312 5593 3313 5593 3313 5594 3312 5594 2709 5594 3313 5595 2709 5595 2710 5595 2710 5596 2711 5596 3313 5596 3313 5597 2711 5597 3221 5597 3313 5598 3221 5598 3283 5598 3283 5599 3221 5599 3223 5599 3283 5600 3223 5600 3281 5600 3281 5601 3223 5601 3285 5601 2716 5602 3315 5602 2717 5602 2717 5603 3315 5603 3222 5603 2717 5604 3222 5604 2713 5604 2713 5605 3222 5605 3221 5605 2713 5606 3221 5606 2712 5606 2712 5607 3221 5607 2711 5607 2716 5608 2715 5608 3315 5608 3315 5609 2715 5609 3218 5609 3315 5610 3218 5610 3289 5610 3289 5611 3218 5611 3220 5611 3289 5612 3220 5612 3290 5612 3290 5613 3220 5613 3294 5613 2672 5614 3316 5614 2671 5614 2671 5615 3316 5615 3219 5615 2671 5616 3219 5616 2670 5616 2670 5617 3219 5617 3218 5617 2670 5618 3218 5618 2714 5618 2714 5619 3218 5619 2715 5619 2672 5620 2673 5620 3316 5620 3316 5621 2673 5621 3215 5621 3316 5622 3215 5622 3238 5622 3238 5623 3215 5623 3217 5623 3238 5624 3217 5624 3236 5624 3236 5625 3217 5625 3296 5625 2677 5626 3317 5626 2676 5626 2676 5627 3317 5627 3216 5627 2676 5628 3216 5628 2675 5628 2675 5629 3216 5629 3215 5629 2675 5630 3215 5630 2674 5630 2674 5631 3215 5631 2673 5631 2677 5632 2678 5632 3317 5632 3317 5633 2678 5633 3212 5633 3317 5634 3212 5634 3301 5634 3301 5635 3212 5635 3214 5635 3301 5636 3214 5636 3299 5636 3299 5637 3214 5637 3305 5637 2678 5638 2679 5638 3212 5638 3212 5639 2679 5639 2680 5639 3212 5640 2680 5640 3213 5640 3213 5641 2680 5641 2681 5641 3213 5642 2681 5642 3319 5642 3319 5643 2681 5643 2682 5643 3319 5644 2682 5644 2683 5644 3321 5645 2666 5645 3322 5645 3322 5646 2666 5646 2665 5646 3322 5647 2665 5647 3323 5647 3323 5648 2665 5648 2658 5648 3323 5649 2658 5649 3324 5649 3324 5650 2658 5650 2661 5650 3324 5651 2661 5651 3325 5651 3325 5652 2661 5652 2662 5652 3325 5653 2662 5653 3326 5653 3327 5654 3328 5654 2642 5654 2642 5655 2654 5655 3327 5655 3327 5656 2654 5656 2639 5656 3327 5657 2639 5657 3329 5657 3329 5658 2639 5658 2638 5658 3329 5659 2638 5659 3330 5659 3330 5660 2638 5660 2669 5660 3330 5661 2669 5661 3321 5661 3321 5662 2669 5662 2667 5662 3321 5663 2667 5663 2666 5663 3328 5664 3331 5664 2642 5664 2642 5665 3331 5665 3332 5665 2642 5666 3332 5666 2643 5666 2643 5667 3332 5667 3333 5667 2643 5668 3333 5668 2645 5668 2645 5669 3333 5669 3334 5669 2645 5670 3334 5670 2646 5670 2646 5671 3334 5671 3335 5671 2646 5672 3335 5672 2650 5672 2650 5673 3335 5673 3336 5673 2662 5674 2663 5674 3326 5674 3326 5675 2663 5675 2664 5675 3326 5676 2664 5676 3337 5676 3337 5677 2664 5677 2660 5677 3337 5678 2660 5678 3338 5678 3338 5679 2660 5679 2659 5679 3338 5680 2659 5680 3339 5680 3339 5681 2659 5681 2657 5681 3339 5682 2657 5682 3340 5682 3340 5683 2657 5683 2656 5683 3340 5684 2656 5684 3341 5684 3341 5685 2656 5685 2668 5685 3341 5686 2668 5686 3342 5686 3342 5687 2668 5687 2640 5687 3342 5688 2640 5688 3343 5688 3343 5689 2640 5689 2641 5689 3343 5690 2641 5690 3344 5690 3344 5691 2641 5691 2655 5691 3344 5692 2655 5692 3345 5692 3345 5693 2655 5693 2653 5693 3345 5694 2653 5694 3346 5694 3346 5695 2653 5695 2652 5695 3346 5696 2652 5696 3347 5696 3347 5697 2652 5697 2651 5697 3347 5698 2651 5698 3348 5698 3348 5699 2651 5699 2644 5699 3348 5700 2644 5700 3349 5700 3349 5701 2644 5701 2647 5701 3349 5702 2647 5702 3350 5702 3350 5703 2647 5703 2648 5703 3350 5704 2648 5704 3336 5704 3336 5705 2648 5705 2649 5705 3336 5706 2649 5706 2650 5706 2892 5707 2893 5707 3351 5707 3352 5708 3353 5708 2868 5708 2868 5709 3353 5709 3354 5709 2868 5710 3354 5710 2894 5710 2894 5711 3354 5711 3355 5711 2894 5712 3355 5712 2893 5712 2893 5713 3355 5713 3356 5713 2893 5714 3356 5714 3351 5714 2868 5715 2867 5715 3352 5715 3352 5716 2867 5716 2895 5716 3352 5717 2895 5717 3357 5717 3351 5718 3358 5718 2892 5718 2892 5719 3358 5719 2537 5719 2892 5720 2537 5720 2536 5720 3359 5721 3360 5721 3361 5721 3362 5722 2537 5722 3358 5722 3356 5723 3361 5723 3351 5723 3351 5724 3361 5724 3360 5724 3351 5725 3360 5725 3358 5725 3358 5726 3360 5726 3363 5726 3358 5727 3363 5727 3362 5727 3364 5728 3365 5728 3366 5728 3367 5729 3368 5729 3369 5729 3369 5730 3368 5730 3370 5730 3369 5731 3370 5731 3366 5731 3366 5732 3370 5732 3371 5732 3366 5733 3371 5733 3364 5733 3365 5734 3372 5734 3366 5734 3366 5735 3372 5735 3373 5735 3366 5736 3373 5736 3361 5736 3361 5737 3373 5737 3374 5737 3361 5738 3374 5738 3359 5738 3375 5739 3376 5739 3369 5739 3369 5740 3376 5740 3377 5740 3369 5741 3377 5741 3367 5741 3378 5742 3375 5742 3379 5742 3379 5743 3375 5743 3369 5743 3379 5744 3369 5744 3380 5744 3380 5745 3369 5745 3381 5745 3382 5746 3383 5746 3366 5746 3366 5747 3383 5747 3384 5747 3366 5748 3384 5748 3369 5748 3369 5749 3384 5749 3385 5749 3369 5750 3385 5750 3381 5750 3361 5751 3386 5751 3387 5751 3387 5752 3388 5752 3361 5752 3361 5753 3388 5753 3389 5753 3361 5754 3389 5754 3366 5754 3366 5755 3389 5755 3390 5755 3366 5756 3390 5756 3382 5756 3356 5757 3355 5757 3361 5757 3361 5758 3355 5758 3354 5758 3361 5759 3354 5759 3386 5759 3386 5760 3354 5760 3353 5760 3386 5761 3353 5761 3391 5761 3391 5762 3353 5762 3352 5762 3391 5763 3352 5763 3392 5763 3392 5764 3352 5764 3357 5764 3180 5765 3179 5765 2740 5765 2740 5766 3179 5766 2741 5766 2741 5767 3179 5767 2720 5767 2741 5768 2720 5768 2253 5768 3393 5769 3394 5769 3171 5769 3171 5770 3394 5770 3395 5770 3171 5771 3395 5771 3173 5771 3171 5772 3170 5772 3393 5772 3393 5773 3170 5773 3174 5773 3393 5774 3174 5774 3175 5774 3178 5775 3177 5775 2750 5775 2750 5776 3177 5776 3176 5776 2750 5777 3176 5777 2740 5777 2740 5778 3176 5778 3181 5778 2740 5779 3181 5779 3180 5779 3396 5780 3397 5780 3398 5780 3399 5781 3400 5781 3401 5781 3397 5782 3402 5782 3398 5782 3398 5783 3402 5783 3399 5783 3398 5784 3399 5784 3403 5784 3403 5785 3399 5785 3401 5785 3404 5786 2764 5786 3405 5786 3405 5787 2764 5787 2763 5787 3405 5788 2763 5788 3406 5788 3406 5789 2763 5789 2765 5789 3406 5790 2765 5790 3407 5790 3407 5791 2765 5791 2766 5791 3407 5792 2766 5792 3408 5792 2295 5793 2771 5793 2766 5793 2766 5794 2771 5794 3409 5794 2766 5795 3409 5795 3408 5795 3404 5796 3396 5796 2764 5796 2764 5797 3396 5797 3398 5797 2764 5798 3398 5798 2757 5798 2757 5799 3398 5799 3410 5799 2757 5800 3410 5800 2758 5800 2758 5801 3410 5801 3411 5801 2758 5802 3411 5802 2760 5802 3411 5803 3412 5803 2760 5803 2760 5804 3412 5804 3413 5804 2760 5805 3413 5805 2761 5805 2761 5806 3413 5806 3414 5806 2761 5807 3414 5807 2755 5807 2755 5808 3414 5808 3415 5808 2755 5809 3415 5809 2756 5809 2756 5810 3415 5810 3416 5810 2756 5811 3416 5811 2751 5811 3416 5812 3417 5812 2751 5812 2751 5813 3417 5813 3418 5813 2751 5814 3418 5814 2752 5814 2752 5815 3418 5815 3419 5815 2752 5816 3419 5816 2743 5816 2743 5817 3419 5817 3420 5817 2743 5818 3420 5818 2744 5818 2744 5819 3420 5819 3421 5819 2744 5820 3421 5820 2746 5820 2746 5821 3421 5821 3422 5821 2746 5822 3422 5822 2748 5822 2748 5823 3422 5823 3423 5823 2748 5824 3423 5824 2749 5824 2749 5825 3423 5825 3393 5825 2749 5826 3393 5826 2750 5826 2750 5827 3393 5827 3175 5827 2750 5828 3175 5828 3178 5828 3424 5829 3425 5829 2822 5829 2822 5830 3425 5830 2823 5830 2823 5831 3425 5831 2866 5831 2823 5832 2866 5832 2393 5832 3426 5833 3427 5833 3428 5833 3428 5834 3427 5834 3429 5834 3428 5835 3429 5835 3430 5835 3428 5836 3431 5836 3426 5836 3426 5837 3431 5837 3432 5837 3426 5838 3432 5838 3433 5838 3434 5839 3435 5839 2857 5839 2857 5840 3435 5840 3436 5840 2857 5841 3436 5841 2822 5841 2822 5842 3436 5842 3437 5842 2822 5843 3437 5843 3424 5843 3438 5844 3439 5844 3440 5844 3441 5845 3442 5845 3443 5845 3443 5846 3442 5846 3438 5846 3443 5847 3438 5847 3444 5847 3444 5848 3438 5848 3440 5848 2389 5849 2858 5849 2824 5849 2824 5850 2858 5850 3445 5850 2824 5851 3445 5851 2841 5851 3446 5852 2843 5852 3447 5852 3447 5853 2843 5853 2842 5853 3447 5854 2842 5854 3448 5854 3448 5855 2842 5855 2841 5855 3448 5856 2841 5856 3449 5856 3449 5857 2841 5857 3445 5857 3446 5858 3441 5858 2843 5858 2843 5859 3441 5859 3443 5859 2843 5860 3443 5860 2844 5860 2844 5861 3443 5861 3450 5861 2844 5862 3450 5862 2845 5862 2845 5863 3450 5863 3451 5863 2845 5864 3451 5864 2846 5864 3451 5865 3452 5865 2846 5865 2846 5866 3452 5866 3453 5866 2846 5867 3453 5867 2847 5867 2847 5868 3453 5868 3454 5868 2847 5869 3454 5869 2848 5869 2848 5870 3454 5870 3455 5870 2848 5871 3455 5871 2849 5871 2849 5872 3455 5872 3456 5872 2849 5873 3456 5873 2850 5873 2850 5874 3456 5874 2851 5874 2851 5875 3456 5875 3457 5875 2851 5876 3457 5876 2852 5876 3457 5877 3458 5877 2852 5877 2852 5878 3458 5878 3459 5878 2852 5879 3459 5879 2853 5879 2853 5880 3459 5880 3460 5880 2853 5881 3460 5881 2854 5881 2854 5882 3460 5882 3461 5882 2854 5883 3461 5883 2855 5883 2855 5884 3461 5884 3462 5884 2855 5885 3462 5885 2856 5885 2856 5886 3462 5886 3426 5886 2856 5887 3426 5887 2857 5887 2857 5888 3426 5888 3433 5888 2857 5889 3433 5889 3434 5889 2965 5890 3463 5890 3464 5890 3465 5891 3466 5891 3467 5891 3468 5892 3469 5892 3470 5892 2570 5893 2569 5893 3471 5893 2962 5894 3471 5894 2963 5894 2963 5895 3471 5895 2569 5895 2963 5896 2569 5896 2958 5896 2958 5897 2569 5897 2568 5897 2958 5898 2568 5898 2959 5898 2959 5899 2568 5899 2564 5899 3464 5900 2565 5900 3471 5900 3471 5901 2565 5901 2571 5901 3471 5902 2571 5902 2570 5902 3472 5903 2881 5903 3473 5903 3473 5904 2881 5904 2880 5904 3473 5905 2880 5905 2566 5905 2879 5906 2878 5906 3474 5906 3474 5907 2878 5907 2882 5907 2871 5908 2877 5908 3475 5908 3475 5909 2877 5909 2875 5909 3475 5910 2875 5910 3474 5910 3474 5911 2875 5911 2874 5911 3474 5912 2874 5912 2879 5912 3470 5913 3476 5913 3477 5913 3477 5914 3476 5914 3478 5914 3477 5915 3478 5915 3479 5915 3479 5916 3478 5916 3480 5916 3479 5917 3480 5917 3475 5917 3475 5918 3480 5918 2872 5918 3475 5919 2872 5919 2871 5919 3468 5920 3470 5920 3481 5920 3481 5921 3470 5921 3477 5921 3481 5922 3477 5922 3482 5922 2974 5923 3465 5923 2971 5923 2971 5924 3465 5924 3467 5924 2971 5925 3467 5925 2972 5925 3483 5926 3484 5926 2967 5926 2967 5927 2924 5927 3483 5927 3483 5928 2924 5928 2923 5928 3483 5929 2923 5929 3467 5929 3467 5930 2923 5930 2973 5930 3467 5931 2973 5931 2972 5931 2965 5932 2964 5932 3463 5932 3463 5933 2964 5933 2969 5933 3463 5934 2969 5934 3484 5934 3484 5935 2969 5935 2968 5935 3484 5936 2968 5936 2967 5936 2962 5937 2961 5937 3471 5937 3471 5938 2961 5938 2960 5938 3471 5939 2960 5939 3464 5939 3464 5940 2960 5940 3027 5940 3464 5941 3027 5941 2965 5941 3485 5942 3477 5942 3486 5942 3486 5943 3477 5943 3479 5943 3486 5944 3479 5944 3487 5944 3487 5945 3479 5945 3475 5945 3487 5946 3475 5946 3472 5946 3472 5947 3475 5947 3474 5947 3472 5948 3474 5948 2881 5948 2881 5949 3474 5949 2882 5949 3467 5950 3485 5950 3483 5950 3483 5951 3485 5951 3486 5951 3483 5952 3486 5952 3484 5952 3484 5953 3486 5953 3487 5953 3484 5954 3487 5954 3463 5954 3463 5955 3487 5955 3472 5955 3463 5956 3472 5956 3464 5956 3464 5957 3472 5957 3473 5957 3464 5958 3473 5958 2565 5958 2565 5959 3473 5959 2566 5959 3466 5960 3488 5960 3467 5960 3467 5961 3488 5961 3489 5961 3467 5962 3489 5962 3485 5962 3485 5963 3489 5963 3490 5963 3485 5964 3490 5964 3477 5964 3477 5965 3490 5965 3491 5965 3477 5966 3491 5966 3482 5966 3492 5967 2895 5967 2896 5967 3478 5968 2919 5968 3480 5968 3480 5969 2919 5969 2873 5969 3480 5970 2873 5970 2872 5970 3493 5971 2918 5971 3494 5971 3494 5972 2918 5972 2919 5972 3494 5973 2919 5973 3495 5973 3495 5974 2919 5974 3478 5974 3495 5975 3478 5975 3496 5975 3497 5976 2905 5976 2911 5976 2911 5977 2910 5977 3497 5977 3497 5978 2910 5978 2908 5978 3497 5979 2908 5979 3498 5979 3498 5980 2908 5980 2907 5980 3498 5981 2907 5981 3499 5981 3499 5982 2907 5982 2912 5982 3499 5983 2912 5983 3500 5983 3500 5984 2912 5984 2914 5984 3500 5985 2914 5985 3493 5985 3493 5986 2914 5986 2916 5986 3493 5987 2916 5987 2918 5987 3501 5988 3502 5988 3503 5988 3504 5989 3505 5989 3501 5989 3506 5990 3507 5990 2897 5990 3508 5991 3509 5991 3504 5991 3501 5992 3503 5992 3504 5992 3504 5993 3503 5993 3510 5993 3504 5994 3510 5994 3508 5994 3509 5995 3506 5995 3504 5995 3504 5996 3506 5996 2897 5996 3504 5997 2897 5997 3511 5997 3511 5998 2897 5998 2899 5998 3511 5999 2899 5999 3512 5999 3512 6000 2899 6000 2903 6000 3512 6001 2903 6001 3513 6001 3513 6002 2903 6002 2902 6002 3513 6003 2902 6003 3514 6003 3514 6004 2902 6004 2906 6004 3514 6005 2906 6005 3515 6005 3515 6006 2906 6006 2905 6006 3515 6007 2905 6007 3516 6007 3516 6008 2905 6008 3497 6008 3517 6009 3518 6009 2896 6009 2896 6010 3518 6010 3519 6010 2896 6011 3519 6011 3492 6011 3507 6012 3520 6012 2897 6012 2897 6013 3520 6013 3521 6013 2897 6014 3521 6014 2896 6014 2896 6015 3521 6015 3522 6015 2896 6016 3522 6016 3517 6016 3523 6017 3524 6017 3489 6017 3489 6018 3524 6018 3490 6018 3525 6019 3469 6019 3468 6019 3525 6020 3468 6020 3526 6020 3526 6021 3468 6021 3481 6021 3526 6022 3481 6022 3527 6022 3527 6023 3481 6023 3482 6023 3527 6024 3482 6024 3524 6024 3524 6025 3482 6025 3491 6025 3524 6026 3491 6026 3490 6026 3528 6027 3529 6027 3466 6027 3523 6028 3489 6028 3529 6028 3529 6029 3489 6029 3488 6029 3529 6030 3488 6030 3466 6030 3466 6031 3465 6031 3528 6031 3528 6032 3465 6032 2974 6032 3528 6033 2974 6033 3530 6033 2920 6034 2993 6034 3531 6034 3001 6035 3532 6035 3000 6035 3000 6036 3532 6036 3533 6036 3000 6037 3533 6037 2999 6037 2976 6038 3534 6038 2975 6038 2975 6039 3534 6039 3530 6039 2975 6040 3530 6040 2974 6040 3535 6041 2983 6041 2981 6041 2993 6042 2995 6042 3531 6042 3531 6043 2995 6043 2996 6043 3531 6044 2996 6044 3533 6044 3533 6045 2996 6045 2998 6045 3533 6046 2998 6046 2999 6046 2981 6047 2980 6047 3535 6047 3535 6048 2980 6048 2986 6048 3535 6049 2986 6049 3536 6049 3536 6050 2986 6050 2988 6050 3536 6051 2988 6051 2989 6051 2976 6052 2978 6052 3534 6052 3534 6053 2978 6053 2985 6053 3534 6054 2985 6054 3535 6054 3535 6055 2985 6055 2984 6055 3535 6056 2984 6056 2983 6056 2989 6057 2991 6057 3536 6057 3536 6058 2991 6058 2992 6058 3536 6059 2992 6059 3531 6059 3531 6060 2992 6060 2921 6060 3531 6061 2921 6061 2920 6061 3537 6062 3538 6062 3539 6062 3532 6063 3001 6063 3540 6063 3541 6064 3542 6064 3538 6064 3538 6065 3542 6065 3543 6065 3538 6066 3543 6066 3539 6066 3532 6067 3540 6067 3544 6067 3544 6068 3540 6068 3545 6068 3544 6069 3545 6069 3541 6069 3541 6070 3545 6070 3546 6070 3541 6071 3546 6071 3542 6071 3539 6072 3547 6072 3537 6072 3537 6073 3547 6073 3548 6073 3537 6074 3548 6074 3549 6074 3549 6075 3548 6075 3550 6075 3549 6076 3550 6076 3551 6076 3551 6077 3550 6077 3552 6077 3551 6078 3552 6078 3553 6078 3550 6079 3548 6079 3554 6079 2926 6080 2939 6080 3555 6080 3048 6081 3046 6081 3045 6081 3554 6082 3556 6082 3557 6082 3051 6083 3050 6083 3558 6083 3558 6084 3050 6084 3054 6084 3558 6085 3054 6085 3556 6085 3556 6086 3054 6086 3559 6086 3556 6087 3559 6087 3557 6087 3049 6088 3048 6088 3560 6088 3560 6089 3048 6089 3045 6089 3560 6090 3045 6090 3558 6090 3558 6091 3045 6091 3053 6091 3558 6092 3053 6092 3051 6092 2580 6093 2579 6093 3561 6093 3561 6094 2579 6094 3042 6094 2583 6095 2578 6095 3562 6095 3562 6096 2578 6096 2577 6096 3562 6097 2577 6097 3563 6097 3562 6098 2947 6098 2583 6098 2583 6099 2947 6099 2946 6099 2583 6100 2946 6100 2584 6100 2584 6101 2946 6101 2945 6101 2584 6102 2945 6102 2585 6102 2943 6103 2941 6103 3563 6103 3563 6104 2941 6104 2940 6104 3563 6105 2940 6105 3562 6105 3562 6106 2940 6106 2948 6106 3562 6107 2948 6107 2947 6107 2943 6108 3563 6108 2935 6108 2935 6109 3563 6109 3564 6109 2935 6110 3564 6110 2936 6110 3555 6111 2939 6111 3564 6111 3564 6112 2939 6112 2938 6112 3564 6113 2938 6113 2936 6113 2926 6114 3555 6114 2927 6114 2927 6115 3555 6115 3565 6115 2927 6116 3565 6116 2929 6116 3540 6117 3001 6117 2934 6117 3540 6118 2934 6118 3545 6118 3545 6119 2934 6119 3546 6119 3546 6120 2934 6120 3566 6120 3546 6121 3566 6121 3542 6121 2934 6122 2933 6122 3566 6122 3566 6123 2933 6123 2931 6123 3566 6124 2931 6124 3565 6124 3565 6125 2931 6125 2930 6125 3565 6126 2930 6126 2929 6126 3552 6127 3550 6127 3567 6127 3567 6128 3550 6128 3554 6128 3567 6129 3554 6129 3568 6129 3568 6130 3554 6130 3557 6130 2577 6131 2580 6131 3563 6131 3563 6132 2580 6132 3561 6132 3563 6133 3561 6133 3564 6133 3564 6134 3561 6134 3569 6134 3564 6135 3569 6135 3555 6135 3555 6136 3569 6136 3570 6136 3555 6137 3570 6137 3565 6137 3565 6138 3570 6138 3571 6138 3565 6139 3571 6139 3566 6139 3566 6140 3571 6140 3572 6140 3566 6141 3572 6141 3542 6141 3547 6142 3539 6142 3572 6142 3572 6143 3539 6143 3543 6143 3572 6144 3543 6144 3542 6144 3042 6145 3044 6145 3561 6145 3561 6146 3044 6146 3049 6146 3561 6147 3049 6147 3569 6147 3569 6148 3049 6148 3560 6148 3569 6149 3560 6149 3570 6149 3570 6150 3560 6150 3558 6150 3570 6151 3558 6151 3571 6151 3571 6152 3558 6152 3556 6152 3571 6153 3556 6153 3572 6153 3572 6154 3556 6154 3554 6154 3572 6155 3554 6155 3547 6155 3547 6156 3554 6156 3548 6156 3573 6157 3574 6157 3039 6157 3575 6158 3576 6158 3577 6158 3578 6159 3579 6159 3034 6159 3067 6160 2502 6160 3580 6160 3067 6161 3580 6161 3034 6161 3034 6162 3580 6162 3581 6162 3034 6163 3581 6163 3578 6163 3575 6164 3577 6164 3582 6164 3039 6165 3574 6165 3040 6165 3040 6166 3574 6166 3583 6166 3040 6167 3583 6167 3061 6167 3061 6168 3583 6168 3584 6168 3061 6169 3584 6169 3060 6169 3060 6170 3584 6170 3585 6170 3060 6171 3585 6171 3058 6171 3058 6172 3585 6172 3586 6172 3058 6173 3586 6173 3056 6173 3056 6174 3586 6174 3587 6174 3056 6175 3587 6175 3588 6175 3588 6176 3557 6176 3056 6176 3056 6177 3557 6177 3559 6177 3056 6178 3559 6178 3055 6178 3055 6179 3559 6179 3054 6179 3589 6180 3035 6180 3590 6180 3590 6181 3035 6181 3034 6181 3590 6182 3034 6182 3577 6182 3577 6183 3034 6183 3579 6183 3577 6184 3579 6184 3582 6184 3039 6185 3066 6185 3573 6185 3573 6186 3066 6186 3065 6186 3573 6187 3065 6187 3591 6187 3591 6188 3065 6188 3064 6188 3591 6189 3064 6189 3592 6189 3592 6190 3064 6190 3063 6190 3592 6191 3063 6191 3593 6191 3593 6192 3063 6192 3037 6192 3593 6193 3037 6193 3594 6193 3594 6194 3037 6194 3036 6194 3594 6195 3036 6195 3589 6195 3589 6196 3036 6196 3076 6196 3589 6197 3076 6197 3035 6197 3595 6198 3596 6198 3597 6198 3597 6199 3598 6199 3599 6199 3599 6200 3598 6200 3600 6200 3599 6201 3601 6201 3602 6201 3600 6202 3603 6202 3599 6202 3599 6203 3603 6203 3604 6203 3599 6204 3604 6204 3605 6204 3597 6205 3599 6205 3595 6205 3595 6206 3599 6206 3602 6206 3595 6207 3602 6207 3606 6207 2501 6208 2518 6208 3607 6208 2502 6209 2501 6209 3580 6209 3580 6210 2501 6210 3607 6210 3580 6211 3607 6211 3581 6211 2518 6212 2519 6212 3607 6212 3607 6213 2519 6213 2514 6213 3607 6214 2514 6214 2513 6214 2513 6215 2778 6215 3607 6215 3607 6216 2778 6216 2780 6216 3607 6217 2780 6217 2781 6217 3575 6218 3582 6218 3608 6218 3608 6219 3582 6219 3579 6219 3608 6220 3579 6220 3607 6220 3607 6221 3579 6221 3578 6221 3607 6222 3578 6222 3581 6222 3609 6223 3610 6223 3608 6223 3608 6224 3610 6224 3611 6224 3608 6225 3611 6225 3612 6225 3612 6226 3613 6226 3608 6226 3608 6227 3613 6227 3614 6227 3608 6228 3614 6228 3615 6228 3615 6229 3616 6229 3608 6229 3608 6230 3616 6230 3617 6230 3608 6231 3617 6231 3575 6231 3575 6232 3617 6232 3618 6232 3575 6233 3618 6233 3576 6233 3619 6234 3620 6234 3607 6234 3607 6235 3620 6235 3621 6235 3607 6236 3621 6236 3608 6236 3608 6237 3621 6237 3622 6237 3608 6238 3622 6238 3609 6238 2787 6239 2786 6239 3623 6239 3619 6240 3607 6240 3624 6240 3624 6241 3607 6241 2781 6241 3624 6242 2781 6242 3625 6242 3625 6243 2781 6243 2782 6243 3625 6244 2782 6244 3623 6244 3623 6245 2782 6245 2784 6245 3623 6246 2784 6246 2787 6246 2786 6247 2785 6247 3623 6247 3623 6248 2785 6248 2789 6248 3623 6249 2789 6249 3626 6249 3626 6250 2789 6250 2788 6250 3627 6251 3628 6251 3629 6251 3630 6252 2788 6252 2790 6252 2864 6253 3631 6253 2394 6253 2394 6254 3631 6254 3632 6254 2394 6255 3632 6255 3633 6255 3634 6256 3635 6256 3636 6256 3634 6257 3636 6257 3637 6257 1740 6258 2394 6258 1735 6258 1735 6259 2394 6259 3633 6259 1735 6260 3633 6260 1736 6260 1736 6261 3633 6261 3638 6261 1736 6262 3638 6262 1738 6262 1738 6263 3638 6263 3639 6263 1738 6264 3639 6264 1739 6264 1739 6265 3639 6265 3637 6265 1739 6266 3637 6266 1732 6266 1732 6267 3637 6267 3636 6267 1732 6268 3636 6268 1733 6268 1733 6269 3636 6269 1729 6269 1726 6270 1718 6270 3640 6270 3640 6271 1718 6271 1731 6271 3640 6272 1731 6272 3636 6272 3636 6273 1731 6273 1730 6273 3636 6274 1730 6274 1729 6274 1725 6275 1724 6275 3641 6275 3641 6276 1724 6276 1722 6276 3641 6277 1722 6277 3642 6277 3642 6278 1722 6278 1721 6278 3642 6279 1721 6279 3643 6279 3643 6280 1721 6280 1728 6280 3643 6281 1728 6281 1727 6281 1767 6282 1766 6282 2525 6282 2525 6283 1766 6283 3644 6283 3628 6284 2523 6284 3645 6284 3645 6285 2523 6285 2527 6285 3645 6286 2527 6286 3644 6286 3644 6287 2527 6287 2526 6287 3644 6288 2526 6288 2525 6288 2528 6289 2532 6289 3627 6289 3627 6290 2532 6290 2531 6290 3627 6291 2531 6291 3628 6291 3628 6292 2531 6292 2524 6292 3628 6293 2524 6293 2523 6293 2529 6294 3646 6294 2530 6294 2530 6295 3646 6295 2808 6295 2530 6296 2808 6296 2508 6296 2800 6297 2809 6297 3647 6297 2798 6298 2797 6298 3648 6298 3648 6299 2797 6299 2807 6299 3648 6300 2807 6300 2806 6300 2806 6301 2804 6301 3648 6301 3648 6302 2804 6302 2803 6302 3648 6303 2803 6303 3647 6303 3647 6304 2803 6304 2801 6304 3647 6305 2801 6305 2800 6305 2793 6306 2792 6306 3649 6306 3649 6307 2792 6307 2798 6307 3649 6308 2798 6308 3650 6308 3650 6309 2798 6309 3648 6309 3650 6310 3648 6310 3651 6310 3652 6311 2799 6311 2796 6311 3649 6312 3653 6312 2793 6312 2793 6313 3653 6313 3652 6313 2793 6314 3652 6314 2795 6314 2795 6315 3652 6315 2796 6315 2799 6316 3652 6316 2791 6316 2791 6317 3652 6317 3654 6317 2791 6318 3654 6318 2790 6318 2790 6319 3654 6319 3655 6319 2790 6320 3655 6320 3630 6320 3656 6321 3657 6321 3658 6321 3659 6322 3660 6322 3648 6322 3648 6323 3660 6323 3661 6323 3648 6324 3661 6324 3651 6324 3662 6325 3663 6325 3664 6325 3664 6326 3663 6326 3665 6326 3664 6327 3665 6327 3656 6327 3656 6328 3665 6328 3666 6328 3656 6329 3666 6329 3657 6329 3667 6330 3668 6330 3640 6330 3640 6331 3668 6331 3669 6331 3640 6332 3669 6332 3664 6332 3664 6333 3669 6333 3670 6333 3664 6334 3670 6334 3662 6334 3635 6335 3671 6335 3636 6335 3636 6336 3671 6336 3672 6336 3636 6337 3672 6337 3640 6337 3640 6338 3672 6338 3673 6338 3640 6339 3673 6339 3667 6339 3629 6340 3628 6340 3674 6340 3674 6341 3628 6341 3645 6341 3674 6342 3645 6342 3642 6342 3642 6343 3645 6343 3644 6343 3642 6344 3644 6344 3641 6344 3641 6345 3644 6345 1766 6345 3641 6346 1766 6346 1725 6346 3658 6347 3659 6347 3656 6347 3656 6348 3659 6348 3648 6348 3656 6349 3648 6349 3675 6349 3675 6350 3648 6350 3647 6350 3675 6351 3647 6351 3646 6351 3646 6352 3647 6352 2809 6352 3646 6353 2809 6353 2808 6353 2529 6354 2528 6354 3646 6354 3646 6355 2528 6355 3627 6355 3646 6356 3627 6356 3675 6356 3675 6357 3627 6357 3629 6357 3675 6358 3629 6358 3656 6358 3656 6359 3629 6359 3674 6359 3656 6360 3674 6360 3664 6360 3664 6361 3674 6361 3642 6361 3664 6362 3642 6362 3640 6362 3640 6363 3642 6363 3643 6363 3640 6364 3643 6364 1726 6364 1726 6365 3643 6365 1727 6365 3676 6366 3677 6366 3678 6366 3679 6367 2864 6367 2863 6367 3680 6368 3681 6368 3682 6368 3682 6369 3681 6369 3678 6369 3682 6370 3678 6370 3683 6370 3683 6371 3678 6371 3677 6371 3684 6372 3685 6372 3686 6372 3676 6373 3678 6373 3687 6373 3687 6374 3678 6374 3686 6374 3687 6375 3686 6375 3688 6375 3688 6376 3686 6376 3685 6376 3688 6377 3685 6377 3689 6377 3684 6378 3686 6378 3690 6378 3690 6379 3686 6379 3428 6379 3690 6380 3428 6380 3430 6380 3434 6381 3433 6381 3678 6381 3678 6382 3433 6382 3432 6382 3678 6383 3432 6383 3686 6383 3686 6384 3432 6384 3431 6384 3686 6385 3431 6385 3428 6385 3437 6386 3436 6386 3678 6386 3678 6387 3436 6387 3435 6387 3678 6388 3435 6388 3434 6388 2865 6389 2866 6389 3425 6389 3437 6390 3678 6390 3424 6390 3424 6391 3678 6391 3681 6391 3424 6392 3681 6392 3425 6392 3680 6393 3679 6393 3681 6393 3681 6394 3679 6394 2863 6394 3681 6395 2863 6395 3425 6395 3425 6396 2863 6396 2862 6396 3425 6397 2862 6397 2865 6397 3691 6398 3692 6398 3693 6398 3694 6399 3695 6399 3696 6399 3696 6400 3695 6400 3697 6400 3696 6401 3697 6401 3698 6401 3698 6402 3697 6402 3699 6402 3698 6403 3699 6403 3693 6403 3700 6404 3698 6404 3701 6404 3701 6405 3698 6405 3693 6405 3701 6406 3693 6406 3702 6406 3702 6407 3693 6407 3692 6407 3685 6408 3684 6408 3703 6408 3703 6409 3684 6409 3690 6409 3691 6410 3693 6410 3704 6410 3704 6411 3693 6411 3703 6411 3704 6412 3703 6412 3705 6412 3705 6413 3703 6413 3690 6413 3705 6414 3690 6414 3430 6414 3699 6415 3706 6415 3693 6415 3693 6416 3706 6416 3707 6416 3693 6417 3707 6417 3703 6417 3703 6418 3707 6418 3708 6418 3703 6419 3708 6419 3685 6419 3685 6420 3708 6420 3709 6420 3685 6421 3709 6421 3689 6421 3441 6422 3446 6422 3710 6422 3711 6423 3712 6423 3713 6423 3714 6424 3715 6424 3716 6424 3717 6425 3718 6425 3710 6425 3710 6426 3718 6426 3719 6426 3710 6427 3719 6427 3720 6427 3720 6428 3719 6428 3721 6428 3720 6429 3721 6429 3714 6429 3713 6430 3712 6430 3710 6430 3710 6431 3712 6431 3722 6431 3710 6432 3722 6432 3717 6432 2860 6433 2861 6433 3711 6433 2860 6434 3711 6434 2859 6434 3711 6435 3713 6435 2859 6435 2859 6436 3713 6436 3445 6436 2859 6437 3445 6437 2858 6437 3446 6438 3447 6438 3710 6438 3710 6439 3447 6439 3448 6439 3710 6440 3448 6440 3713 6440 3713 6441 3448 6441 3449 6441 3713 6442 3449 6442 3445 6442 3714 6443 3716 6443 3720 6443 3720 6444 3716 6444 3723 6444 3720 6445 3723 6445 3724 6445 3441 6446 3710 6446 3442 6446 3442 6447 3710 6447 3720 6447 3442 6448 3720 6448 3438 6448 3438 6449 3720 6449 3724 6449 3438 6450 3724 6450 3439 6450 1406 6451 1405 6451 3725 6451 1411 6452 1410 6452 3726 6452 1591 6453 1590 6453 3727 6453 3728 6454 2861 6454 2387 6454 3728 6455 2387 6455 3729 6455 1390 6456 1389 6456 2387 6456 2387 6457 1389 6457 3730 6457 2387 6458 3730 6458 3729 6458 1389 6459 1396 6459 3730 6459 3730 6460 1396 6460 1395 6460 3730 6461 1395 6461 3731 6461 3731 6462 1395 6462 1394 6462 3731 6463 1394 6463 3732 6463 3732 6464 1394 6464 1401 6464 3732 6465 1401 6465 3733 6465 1401 6466 1400 6466 3733 6466 3733 6467 1400 6467 1397 6467 3733 6468 1397 6468 3734 6468 3735 6469 3736 6469 3737 6469 3737 6470 3736 6470 3738 6470 3738 6471 3739 6471 3725 6471 3739 6472 3740 6472 3725 6472 3725 6473 3740 6473 3741 6473 3725 6474 3741 6474 3734 6474 3742 6475 3743 6475 3744 6475 3744 6476 3743 6476 3745 6476 3744 6477 3745 6477 3737 6477 3737 6478 3745 6478 3746 6478 3737 6479 3746 6479 3735 6479 3747 6480 3748 6480 3749 6480 3749 6481 3748 6481 3750 6481 3749 6482 3750 6482 3744 6482 3744 6483 3750 6483 3751 6483 3744 6484 3751 6484 3742 6484 3752 6485 3753 6485 3754 6485 3752 6486 3754 6486 3749 6486 3749 6487 3754 6487 3755 6487 3749 6488 3755 6488 3747 6488 3756 6489 3757 6489 3752 6489 3752 6490 3757 6490 3758 6490 3752 6491 3758 6491 3753 6491 2407 6492 2409 6492 3759 6492 3759 6493 3760 6493 2407 6493 2407 6494 3760 6494 3761 6494 2407 6495 3761 6495 2397 6495 2397 6496 3761 6496 3762 6496 2399 6497 2398 6497 3752 6497 3763 6498 2419 6498 3752 6498 3752 6499 2419 6499 2418 6499 3752 6500 2418 6500 2399 6500 2398 6501 2426 6501 3752 6501 3752 6502 2426 6502 2425 6502 3752 6503 2425 6503 3756 6503 3756 6504 2425 6504 2424 6504 3756 6505 2424 6505 3764 6505 3764 6506 2424 6506 2423 6506 3764 6507 2423 6507 3762 6507 3762 6508 2423 6508 2395 6508 3762 6509 2395 6509 2397 6509 3765 6510 2421 6510 3763 6510 3763 6511 2421 6511 2420 6511 3763 6512 2420 6512 2419 6512 1587 6513 2401 6513 3765 6513 3765 6514 2401 6514 2422 6514 3765 6515 2422 6515 2421 6515 1584 6516 1589 6516 3765 6516 3765 6517 1589 6517 1588 6517 3765 6518 1588 6518 1587 6518 3766 6519 1592 6519 1591 6519 3767 6520 1594 6520 1593 6520 1594 6521 3767 6521 1595 6521 1595 6522 3767 6522 3768 6522 1595 6523 3768 6523 1596 6523 1414 6524 1418 6524 3768 6524 3769 6525 1416 6525 3768 6525 3768 6526 1416 6526 1415 6526 3768 6527 1415 6527 1414 6527 1418 6528 1170 6528 3768 6528 3768 6529 1170 6529 1582 6529 3768 6530 1582 6530 1596 6530 3726 6531 1413 6531 3770 6531 3770 6532 1413 6532 1412 6532 3770 6533 1412 6533 1417 6533 1410 6534 1408 6534 3726 6534 3726 6535 1408 6535 1407 6535 3726 6536 1407 6536 1413 6536 3738 6537 3725 6537 3737 6537 3737 6538 3725 6538 1405 6538 3737 6539 1405 6539 1403 6539 3734 6540 1397 6540 3725 6540 3725 6541 1397 6541 1398 6541 3725 6542 1398 6542 1406 6542 3767 6543 3771 6543 3768 6543 3768 6544 3771 6544 3770 6544 3768 6545 3770 6545 3769 6545 3769 6546 3770 6546 1417 6546 3769 6547 1417 6547 1416 6547 1591 6548 3727 6548 3766 6548 3766 6549 3727 6549 3772 6549 3766 6550 3772 6550 3773 6550 3749 6551 3773 6551 3752 6551 3752 6552 3773 6552 3772 6552 3752 6553 3772 6553 3763 6553 3763 6554 3772 6554 3727 6554 3763 6555 3727 6555 3765 6555 3765 6556 3727 6556 1590 6556 3765 6557 1590 6557 1584 6557 1403 6558 1411 6558 3737 6558 3737 6559 1411 6559 3726 6559 3737 6560 3726 6560 3744 6560 3744 6561 3726 6561 3770 6561 3744 6562 3770 6562 3749 6562 3749 6563 3770 6563 3771 6563 3749 6564 3771 6564 3773 6564 3773 6565 3771 6565 3767 6565 3773 6566 3767 6566 3766 6566 3766 6567 3767 6567 1593 6567 3766 6568 1593 6568 1592 6568 3774 6569 3775 6569 3776 6569 3775 6570 3777 6570 2415 6570 2415 6571 3777 6571 2410 6571 3778 6572 2409 6572 2408 6572 2408 6573 2406 6573 3778 6573 3778 6574 2406 6574 2405 6574 3778 6575 2405 6575 2404 6575 3777 6576 3779 6576 2410 6576 2410 6577 3779 6577 3780 6577 2410 6578 3780 6578 2411 6578 2411 6579 3780 6579 3778 6579 2411 6580 3778 6580 2412 6580 2412 6581 3778 6581 2404 6581 3774 6582 3776 6582 3781 6582 3781 6583 3776 6583 3782 6583 3782 6584 3776 6584 3783 6584 3782 6585 3783 6585 3784 6585 3785 6586 3786 6586 3783 6586 3783 6587 3786 6587 3787 6587 3787 6588 3788 6588 3783 6588 3783 6589 3788 6589 3789 6589 3783 6590 3789 6590 3784 6590 2490 6591 2489 6591 3785 6591 2490 6592 3785 6592 2491 6592 2491 6593 3785 6593 3783 6593 2491 6594 3783 6594 2487 6594 2489 6595 2483 6595 3785 6595 3785 6596 2483 6596 2485 6596 3785 6597 2485 6597 2486 6597 3776 6598 2499 6598 2498 6598 3776 6599 2498 6599 3783 6599 3783 6600 2498 6600 2488 6600 3783 6601 2488 6601 2487 6601 3775 6602 2415 6602 3776 6602 3776 6603 2415 6603 2414 6603 3776 6604 2414 6604 2402 6604 2402 6605 1878 6605 3776 6605 3776 6606 1878 6606 1872 6606 3776 6607 1872 6607 1874 6607 1874 6608 1875 6608 3776 6608 3776 6609 1875 6609 2500 6609 3776 6610 2500 6610 2499 6610 1553 6611 1555 6611 2478 6611 2478 6612 1555 6612 1523 6612 3790 6613 3791 6613 2429 6613 2429 6614 3791 6614 3792 6614 2429 6615 3792 6615 3793 6615 3793 6616 3794 6616 2429 6616 2429 6617 3794 6617 2478 6617 2429 6618 2478 6618 1522 6618 1522 6619 2478 6619 1523 6619 3795 6620 3796 6620 2445 6620 2430 6621 2431 6621 2428 6621 3790 6622 2429 6622 3797 6622 3797 6623 2429 6623 2430 6623 3797 6624 2430 6624 3798 6624 2433 6625 2432 6625 3798 6625 2430 6626 2428 6626 3798 6626 3798 6627 2428 6627 2427 6627 3798 6628 2427 6628 2433 6628 2444 6629 2443 6629 2442 6629 2444 6630 3796 6630 2435 6630 2435 6631 3796 6631 2436 6631 2444 6632 2442 6632 3796 6632 3796 6633 2442 6633 2441 6633 3796 6634 2441 6634 2445 6634 2447 6635 3799 6635 3800 6635 3795 6636 2445 6636 3800 6636 3800 6637 2445 6637 2446 6637 3800 6638 2446 6638 2447 6638 2432 6639 2434 6639 3798 6639 3798 6640 2434 6640 2438 6640 3798 6641 2438 6641 3801 6641 3801 6642 2438 6642 2439 6642 3801 6643 2439 6643 3802 6643 3803 6644 3804 6644 2440 6644 2440 6645 3804 6645 3805 6645 2440 6646 3805 6646 2439 6646 2439 6647 3805 6647 3806 6647 2439 6648 3806 6648 3802 6648 3803 6649 2440 6649 3807 6649 3807 6650 2440 6650 2437 6650 3807 6651 2437 6651 3808 6651 3796 6652 3809 6652 2436 6652 2436 6653 3809 6653 3810 6653 2436 6654 3810 6654 2437 6654 2437 6655 3810 6655 3811 6655 2437 6656 3811 6656 3808 6656 1501 6657 1500 6657 2474 6657 2474 6658 1500 6658 1506 6658 2474 6659 1506 6659 1504 6659 1501 6660 2474 6660 2447 6660 2447 6661 2474 6661 3812 6661 2447 6662 3812 6662 3813 6662 3813 6663 3814 6663 2447 6663 2447 6664 3814 6664 3815 6664 2447 6665 3815 6665 3799 6665 3816 6666 3817 6666 3818 6666 3819 6667 3815 6667 3814 6667 3820 6668 3821 6668 3822 6668 3822 6669 3821 6669 3823 6669 3822 6670 3823 6670 3819 6670 3824 6671 3825 6671 3826 6671 3826 6672 3825 6672 3827 6672 3826 6673 3827 6673 3820 6673 3820 6674 3827 6674 3828 6674 3820 6675 3828 6675 3821 6675 3829 6676 3830 6676 3831 6676 3831 6677 3830 6677 3832 6677 3833 6678 3834 6678 3832 6678 3832 6679 3834 6679 3835 6679 3832 6680 3835 6680 3831 6680 3836 6681 3837 6681 3838 6681 3838 6682 3837 6682 3839 6682 3840 6683 3841 6683 3842 6683 3842 6684 3841 6684 3843 6684 3842 6685 3843 6685 3844 6685 3844 6686 3843 6686 3838 6686 3844 6687 3838 6687 3818 6687 3818 6688 3838 6688 3839 6688 3818 6689 3839 6689 3816 6689 3836 6690 3838 6690 3845 6690 3845 6691 3838 6691 2455 6691 3845 6692 2455 6692 2460 6692 3819 6693 3814 6693 3822 6693 3822 6694 3814 6694 3813 6694 3822 6695 3813 6695 3812 6695 2470 6696 3826 6696 2471 6696 2471 6697 3826 6697 3820 6697 2471 6698 3820 6698 2472 6698 2472 6699 3820 6699 3822 6699 2472 6700 3822 6700 2473 6700 2473 6701 3822 6701 3812 6701 2473 6702 3812 6702 2474 6702 2470 6703 2469 6703 3826 6703 3826 6704 2469 6704 3830 6704 3826 6705 3830 6705 3824 6705 3824 6706 3830 6706 3829 6706 2466 6707 3832 6707 2467 6707 2467 6708 3832 6708 3830 6708 2467 6709 3830 6709 2468 6709 2468 6710 3830 6710 2469 6710 2466 6711 2465 6711 3832 6711 3832 6712 2465 6712 3841 6712 3832 6713 3841 6713 3833 6713 3833 6714 3841 6714 3840 6714 2465 6715 2464 6715 3841 6715 3841 6716 2464 6716 2463 6716 3841 6717 2463 6717 3843 6717 3843 6718 2463 6718 2462 6718 3843 6719 2462 6719 3838 6719 3838 6720 2462 6720 2461 6720 3838 6721 2461 6721 2455 6721 3143 6722 3142 6722 3846 6722 3847 6723 3147 6723 3146 6723 3847 6724 3146 6724 3848 6724 3848 6725 3146 6725 3145 6725 3848 6726 3145 6726 3849 6726 3849 6727 3145 6727 3149 6727 3849 6728 3149 6728 3150 6728 3846 6729 3142 6729 3850 6729 3142 6730 3141 6730 3850 6730 3850 6731 3141 6731 3140 6731 3850 6732 3140 6732 3851 6732 3851 6733 3140 6733 3139 6733 3851 6734 3139 6734 3847 6734 3847 6735 3139 6735 3148 6735 3847 6736 3148 6736 3147 6736 3136 6737 3138 6737 3846 6737 3138 6738 3137 6738 3846 6738 3846 6739 3137 6739 3144 6739 3846 6740 3144 6740 3143 6740 3852 6741 3853 6741 3854 6741 3854 6742 3853 6742 3855 6742 3854 6743 3855 6743 3817 6743 3856 6744 3857 6744 3852 6744 3852 6745 3857 6745 3858 6745 3852 6746 3858 6746 3853 6746 3859 6747 3860 6747 3861 6747 3861 6748 3860 6748 3862 6748 3861 6749 3862 6749 3856 6749 3856 6750 3862 6750 3863 6750 3856 6751 3863 6751 3857 6751 3864 6752 3865 6752 3866 6752 3866 6753 3865 6753 3859 6753 3866 6754 3859 6754 3867 6754 3867 6755 3859 6755 3861 6755 3816 6756 3839 6756 3846 6756 3839 6757 3837 6757 3846 6757 3846 6758 3837 6758 3836 6758 3846 6759 3836 6759 3136 6759 3136 6760 3836 6760 3845 6760 3136 6761 3845 6761 2460 6761 3817 6762 3816 6762 3854 6762 3854 6763 3816 6763 3846 6763 3854 6764 3846 6764 3852 6764 3852 6765 3846 6765 3850 6765 3852 6766 3850 6766 3856 6766 3856 6767 3850 6767 3851 6767 3856 6768 3851 6768 3861 6768 3861 6769 3851 6769 3847 6769 3861 6770 3847 6770 3867 6770 3867 6771 3847 6771 3848 6771 3867 6772 3848 6772 3868 6772 3868 6773 3848 6773 3849 6773 3869 6774 3864 6774 3870 6774 3870 6775 3864 6775 3866 6775 3870 6776 3866 6776 3871 6776 3871 6777 3866 6777 3867 6777 3871 6778 3867 6778 3872 6778 3872 6779 3867 6779 3868 6779 3873 6780 3868 6780 3874 6780 3874 6781 3868 6781 3849 6781 3874 6782 3849 6782 3875 6782 3875 6783 3849 6783 3876 6783 3876 6784 3849 6784 3150 6784 3876 6785 3150 6785 3877 6785 3878 6786 3869 6786 3879 6786 3879 6787 3869 6787 3870 6787 3873 6788 3880 6788 3868 6788 3868 6789 3880 6789 3881 6789 3868 6790 3881 6790 3872 6790 3872 6791 3881 6791 3882 6791 3872 6792 3882 6792 3871 6792 3871 6793 3882 6793 3883 6793 3871 6794 3883 6794 3870 6794 3870 6795 3883 6795 3884 6795 3870 6796 3884 6796 3879 6796 3885 6797 2486 6797 2484 6797 3886 6798 3887 6798 3888 6798 3888 6799 3887 6799 3885 6799 3888 6800 3889 6800 3890 6800 3891 6801 3886 6801 3892 6801 3892 6802 3886 6802 3888 6802 3892 6803 3888 6803 3893 6803 3893 6804 3888 6804 3890 6804 3894 6805 3895 6805 3889 6805 3889 6806 3895 6806 3896 6806 3889 6807 3896 6807 3890 6807 3897 6808 3898 6808 3894 6808 3894 6809 3898 6809 3899 6809 3894 6810 3899 6810 3895 6810 3900 6811 3901 6811 3897 6811 3897 6812 3901 6812 3902 6812 3897 6813 3902 6813 3898 6813 3903 6814 3904 6814 3905 6814 3905 6815 3904 6815 3906 6815 3905 6816 3906 6816 3907 6816 3907 6817 3906 6817 3908 6817 3794 6818 3793 6818 3909 6818 3909 6819 3793 6819 3792 6819 3910 6820 3911 6820 3912 6820 3912 6821 3911 6821 3909 6821 3912 6822 3909 6822 3913 6822 3913 6823 3909 6823 3792 6823 3913 6824 3792 6824 3791 6824 3885 6825 2484 6825 3888 6825 3888 6826 2484 6826 2492 6826 3888 6827 2492 6827 3889 6827 2492 6828 2493 6828 3889 6828 3889 6829 2493 6829 2494 6829 3889 6830 2494 6830 3894 6830 3894 6831 2494 6831 2495 6831 3894 6832 2495 6832 3897 6832 3897 6833 2495 6833 2496 6833 2496 6834 2497 6834 3897 6834 3897 6835 2497 6835 3904 6835 3897 6836 3904 6836 3900 6836 3900 6837 3904 6837 3903 6837 2481 6838 3906 6838 2480 6838 2480 6839 3906 6839 3904 6839 2480 6840 3904 6840 2479 6840 2479 6841 3904 6841 2497 6841 2481 6842 2482 6842 3906 6842 3906 6843 2482 6843 3911 6843 3906 6844 3911 6844 3908 6844 3908 6845 3911 6845 3910 6845 2478 6846 3794 6846 2477 6846 2477 6847 3794 6847 3909 6847 2477 6848 3909 6848 2476 6848 2476 6849 3909 6849 3911 6849 2476 6850 3911 6850 2475 6850 2475 6851 3911 6851 2482 6851 3914 6852 3915 6852 3916 6852 3916 6853 3915 6853 3917 6853 3916 6854 3917 6854 3918 6854 3919 6855 3920 6855 3921 6855 3915 6856 3922 6856 3917 6856 3917 6857 3922 6857 3919 6857 3917 6858 3919 6858 3923 6858 3923 6859 3919 6859 3921 6859 3924 6860 3925 6860 3926 6860 3926 6861 3925 6861 3927 6861 3926 6862 3927 6862 3928 6862 3928 6863 3927 6863 3400 6863 3914 6864 3929 6864 3915 6864 3915 6865 3929 6865 3930 6865 3915 6866 3930 6866 3925 6866 3925 6867 3930 6867 3931 6867 3925 6868 3931 6868 3927 6868 3932 6869 3933 6869 3924 6869 3924 6870 3933 6870 3934 6870 3924 6871 3934 6871 3925 6871 3925 6872 3934 6872 3935 6872 3925 6873 3935 6873 3915 6873 3915 6874 3935 6874 3936 6874 3915 6875 3936 6875 3922 6875 3937 6876 3938 6876 3939 6876 3940 6877 3941 6877 3932 6877 3942 6878 3943 6878 3944 6878 3944 6879 3943 6879 3945 6879 3944 6880 3945 6880 3940 6880 3940 6881 3945 6881 3946 6881 3940 6882 3946 6882 3941 6882 3939 6883 3938 6883 3944 6883 3944 6884 3938 6884 3947 6884 3944 6885 3947 6885 3942 6885 2775 6886 2776 6886 3937 6886 3409 6887 3939 6887 3408 6887 3408 6888 3939 6888 3407 6888 2775 6889 3937 6889 2774 6889 2774 6890 3937 6890 3939 6890 2774 6891 3939 6891 2772 6891 2772 6892 3939 6892 3409 6892 2772 6893 3409 6893 2771 6893 3407 6894 3939 6894 3406 6894 3406 6895 3939 6895 3944 6895 3406 6896 3944 6896 3405 6896 3397 6897 3396 6897 3944 6897 3944 6898 3396 6898 3404 6898 3944 6899 3404 6899 3405 6899 3932 6900 3924 6900 3940 6900 3940 6901 3924 6901 3926 6901 3940 6902 3926 6902 3928 6902 3397 6903 3944 6903 3402 6903 3402 6904 3944 6904 3940 6904 3402 6905 3940 6905 3399 6905 3399 6906 3940 6906 3928 6906 3399 6907 3928 6907 3400 6907 3948 6908 3949 6908 3950 6908 1061 6909 1059 6909 3951 6909 3952 6910 3953 6910 3954 6910 1041 6911 1040 6911 3955 6911 3956 6912 3957 6912 2293 6912 2293 6913 3957 6913 3958 6913 2293 6914 3958 6914 2776 6914 3956 6915 2293 6915 3955 6915 3955 6916 2293 6916 1042 6916 3955 6917 1042 6917 1041 6917 1040 6918 1039 6918 3955 6918 3955 6919 1039 6919 1038 6919 3955 6920 1038 6920 3959 6920 1038 6921 1037 6921 3959 6921 3959 6922 1037 6922 1036 6922 3959 6923 1036 6923 3960 6923 3960 6924 1036 6924 1047 6924 3960 6925 1047 6925 3961 6925 3961 6926 1047 6926 1046 6926 3961 6927 1046 6927 3962 6927 3963 6928 3964 6928 3965 6928 3965 6929 3966 6929 3963 6929 3963 6930 3966 6930 3967 6930 3963 6931 3967 6931 3954 6931 3954 6932 3967 6932 3968 6932 3954 6933 3968 6933 3952 6933 3964 6934 3963 6934 3969 6934 3969 6935 3963 6935 3970 6935 3969 6936 3970 6936 3971 6936 3972 6937 3973 6937 3970 6937 3970 6938 3973 6938 3974 6938 3970 6939 3974 6939 3971 6939 3975 6940 3976 6940 3977 6940 3978 6941 3979 6941 3950 6941 3950 6942 3979 6942 3975 6942 3976 6943 3980 6943 3977 6943 3977 6944 3980 6944 3981 6944 3977 6945 3981 6945 3970 6945 3970 6946 3981 6946 3982 6946 3970 6947 3982 6947 3972 6947 3370 6948 3983 6948 3984 6948 3370 6949 3984 6949 3371 6949 3984 6950 3985 6950 3371 6950 3371 6951 3985 6951 3986 6951 3371 6952 3986 6952 3950 6952 3950 6953 3986 6953 3987 6953 3950 6954 3987 6954 3978 6954 3988 6955 3376 6955 3989 6955 3989 6956 3376 6956 3375 6956 3989 6957 3375 6957 3378 6957 3370 6958 3368 6958 3983 6958 3983 6959 3368 6959 3367 6959 3983 6960 3367 6960 3988 6960 3988 6961 3367 6961 3377 6961 3988 6962 3377 6962 3376 6962 3949 6963 3374 6963 3950 6963 3950 6964 3374 6964 3373 6964 3950 6965 3373 6965 3372 6965 3372 6966 3365 6966 3950 6966 3950 6967 3365 6967 3364 6967 3950 6968 3364 6968 3371 6968 3363 6969 3360 6969 3949 6969 3949 6970 3360 6970 3359 6970 3949 6971 3359 6971 3374 6971 2537 6972 3362 6972 2538 6972 2538 6973 3362 6973 3990 6973 2538 6974 3990 6974 2539 6974 2539 6975 3990 6975 2534 6975 2534 6976 3990 6976 2540 6976 2540 6977 3990 6977 3991 6977 2540 6978 3991 6978 2541 6978 2541 6979 3991 6979 3992 6979 2541 6980 3992 6980 2542 6980 2542 6981 3992 6981 2543 6981 2543 6982 3992 6982 3993 6982 2543 6983 3993 6983 2544 6983 2544 6984 3993 6984 2545 6984 2545 6985 3993 6985 3994 6985 2545 6986 3994 6986 2546 6986 3995 6987 1071 6987 3994 6987 3994 6988 1071 6988 1069 6988 3994 6989 1069 6989 1075 6989 1075 6990 1076 6990 3994 6990 3994 6991 1076 6991 2522 6991 3994 6992 2522 6992 2546 6992 3996 6993 3951 6993 1067 6993 1067 6994 1066 6994 3996 6994 3996 6995 1066 6995 1065 6995 3996 6996 1065 6996 1072 6996 1059 6997 1057 6997 3951 6997 3951 6998 1057 6998 1056 6998 3951 6999 1056 6999 1067 6999 1054 7000 1052 7000 3963 7000 1054 7001 3963 7001 1055 7001 1052 7002 1051 7002 3963 7002 3963 7003 1051 7003 1063 7003 3963 7004 1063 7004 1062 7004 1044 7005 3954 7005 1046 7005 1046 7006 3954 7006 3953 7006 1046 7007 3953 7007 3962 7007 1044 7008 1043 7008 3954 7008 3954 7009 1043 7009 1048 7009 3954 7010 1048 7010 3963 7010 3963 7011 1048 7011 1050 7011 3963 7012 1050 7012 1055 7012 3975 7013 3977 7013 3950 7013 3950 7014 3977 7014 3997 7014 3950 7015 3997 7015 3948 7015 1062 7016 1061 7016 3963 7016 3963 7017 1061 7017 3951 7017 3963 7018 3951 7018 3970 7018 3970 7019 3951 7019 3996 7019 3970 7020 3996 7020 3977 7020 3977 7021 3996 7021 3998 7021 3977 7022 3998 7022 3997 7022 3362 7023 3363 7023 3990 7023 3990 7024 3363 7024 3949 7024 3990 7025 3949 7025 3991 7025 3991 7026 3949 7026 3948 7026 3991 7027 3948 7027 3992 7027 3992 7028 3948 7028 3997 7028 3992 7029 3997 7029 3993 7029 3993 7030 3997 7030 3998 7030 3993 7031 3998 7031 3994 7031 3994 7032 3998 7032 3996 7032 3994 7033 3996 7033 3995 7033 3995 7034 3996 7034 1072 7034 3995 7035 1072 7035 1071 7035 3999 7036 4000 7036 3880 7036 4001 7037 3883 7037 3882 7037 3883 7038 4001 7038 3884 7038 3884 7039 4001 7039 4002 7039 3884 7040 4002 7040 3879 7040 3879 7041 4002 7041 4003 7041 3879 7042 4003 7042 3878 7042 3880 7043 4004 7043 4005 7043 4001 7044 3880 7044 4005 7044 4006 7045 4004 7045 3880 7045 3882 7046 3881 7046 4001 7046 4001 7047 3881 7047 3880 7047 4000 7048 4006 7048 3880 7048 4007 7049 4008 7049 4009 7049 4010 7050 4011 7050 4012 7050 4012 7051 4011 7051 4009 7051 4010 7052 4013 7052 4011 7052 4011 7053 4013 7053 4014 7053 4011 7054 4014 7054 4015 7054 4015 7055 4016 7055 4011 7055 4011 7056 4016 7056 4017 7056 4011 7057 4017 7057 4009 7057 4009 7058 4017 7058 4018 7058 4019 7059 4020 7059 4021 7059 4018 7060 4022 7060 4009 7060 4009 7061 4022 7061 4023 7061 4009 7062 4023 7062 4019 7062 4019 7063 4021 7063 4009 7063 4009 7064 4021 7064 4024 7064 4009 7065 4024 7065 4007 7065 4025 7066 731 7066 4026 7066 4026 7067 731 7067 730 7067 4026 7068 730 7068 4027 7068 728 7069 732 7069 4028 7069 4027 7070 730 7070 4028 7070 4028 7071 730 7071 729 7071 4028 7072 729 7072 728 7072 4029 7073 4030 7073 4025 7073 4025 7074 4030 7074 4031 7074 4025 7075 4031 7075 731 7075 731 7076 4031 7076 4032 7076 731 7077 4032 7077 715 7077 4028 7078 732 7078 502 7078 4029 7079 4025 7079 4033 7079 4033 7080 4025 7080 4034 7080 4034 7081 501 7081 4035 7081 4035 7082 501 7082 500 7082 4035 7083 500 7083 499 7083 4034 7084 4025 7084 501 7084 501 7085 4025 7085 4026 7085 501 7086 4026 7086 502 7086 502 7087 4026 7087 4027 7087 502 7088 4027 7088 4028 7088 4036 7089 4037 7089 4038 7089 659 7090 658 7090 4038 7090 4039 7091 4040 7091 4041 7091 4002 7092 4001 7092 4042 7092 4042 7093 4001 7093 4005 7093 4042 7094 4005 7094 4043 7094 4002 7095 4042 7095 4003 7095 4003 7096 4042 7096 4044 7096 4003 7097 4044 7097 3878 7097 4045 7098 4046 7098 4047 7098 4047 7099 4046 7099 4048 7099 4047 7100 4048 7100 4049 7100 4049 7101 4048 7101 4050 7101 4049 7102 4050 7102 4051 7102 4041 7103 4040 7103 4052 7103 4040 7104 4053 7104 4052 7104 4052 7105 4053 7105 4054 7105 4052 7106 4054 7106 4050 7106 4050 7107 4054 7107 4055 7107 4050 7108 4055 7108 4051 7108 4039 7109 4056 7109 4057 7109 4057 7110 4056 7110 4058 7110 4057 7111 4058 7111 4059 7111 4060 7112 4061 7112 4059 7112 4062 7113 4061 7113 4063 7113 4063 7114 4061 7114 4060 7114 4063 7115 4060 7115 4064 7115 4060 7116 720 7116 719 7116 4064 7117 4060 7117 4065 7117 4065 7118 4060 7118 719 7118 4065 7119 719 7119 718 7119 4059 7120 4058 7120 4060 7120 4060 7121 4058 7121 721 7121 4060 7122 721 7122 720 7122 638 7123 637 7123 4056 7123 4056 7124 637 7124 707 7124 4056 7125 707 7125 4058 7125 4058 7126 707 7126 726 7126 4058 7127 726 7127 721 7127 4039 7128 4041 7128 4056 7128 4056 7129 4041 7129 639 7129 4056 7130 639 7130 638 7130 640 7131 4066 7131 636 7131 636 7132 4066 7132 4067 7132 636 7133 4067 7133 634 7133 634 7134 4067 7134 645 7134 645 7135 4067 7135 643 7135 643 7136 4067 7136 4068 7136 643 7137 4068 7137 646 7137 4036 7138 653 7138 4068 7138 4068 7139 653 7139 652 7139 4068 7140 652 7140 646 7140 654 7141 4069 7141 651 7141 651 7142 4069 7142 655 7142 4070 7143 660 7143 659 7143 4071 7144 4072 7144 4070 7144 4070 7145 4072 7145 4073 7145 4073 7146 4074 7146 675 7146 675 7147 4074 7147 4075 7147 675 7148 4075 7148 674 7148 4073 7149 675 7149 4070 7149 4070 7150 675 7150 684 7150 4070 7151 684 7151 660 7151 658 7152 655 7152 4038 7152 4038 7153 655 7153 4069 7153 4038 7154 4069 7154 4036 7154 4036 7155 4069 7155 654 7155 4036 7156 654 7156 653 7156 4076 7157 4077 7157 4078 7157 4078 7158 4077 7158 4079 7158 4078 7159 4079 7159 4070 7159 4070 7160 4079 7160 4080 7160 4070 7161 4080 7161 4071 7161 4004 7162 4046 7162 4005 7162 4005 7163 4046 7163 4045 7163 4005 7164 4045 7164 4043 7164 4006 7165 4000 7165 4037 7165 4037 7166 4000 7166 3999 7166 4037 7167 3999 7167 4081 7167 659 7168 4038 7168 4070 7168 4070 7169 4038 7169 4037 7169 4070 7170 4037 7170 4078 7170 4078 7171 4037 7171 4081 7171 4078 7172 4081 7172 4076 7172 4004 7173 4006 7173 4046 7173 4046 7174 4006 7174 4037 7174 4046 7175 4037 7175 4048 7175 4048 7176 4037 7176 4036 7176 4048 7177 4036 7177 4050 7177 4050 7178 4036 7178 4068 7178 4050 7179 4068 7179 4052 7179 4052 7180 4068 7180 4067 7180 4052 7181 4067 7181 4041 7181 4041 7182 4067 7182 4066 7182 4041 7183 4066 7183 639 7183 639 7184 4066 7184 640 7184 717 7185 4012 7185 718 7185 718 7186 4012 7186 4065 7186 4012 7187 4009 7187 4062 7187 4012 7188 4062 7188 4065 7188 4065 7189 4062 7189 4063 7189 4065 7190 4063 7190 4064 7190 4082 7191 4007 7191 495 7191 495 7192 4007 7192 494 7192 4008 7193 4007 7193 4083 7193 4083 7194 4007 7194 4082 7194 4083 7195 4082 7195 4084 7195 4084 7196 4082 7196 4085 7196 4086 7197 4087 7197 4088 7197 546 7198 4089 7198 547 7198 542 7199 541 7199 4090 7199 4091 7200 541 7200 549 7200 4091 7201 549 7201 4092 7201 4092 7202 549 7202 574 7202 4092 7203 574 7203 573 7203 4093 7204 544 7204 542 7204 4089 7205 546 7205 4093 7205 4093 7206 546 7206 545 7206 4093 7207 545 7207 544 7207 548 7208 4094 7208 531 7208 531 7209 4094 7209 4095 7209 536 7210 535 7210 4096 7210 4096 7211 535 7211 534 7211 4096 7212 534 7212 4095 7212 4095 7213 534 7213 532 7213 4095 7214 532 7214 531 7214 518 7215 517 7215 4097 7215 4097 7216 517 7216 516 7216 4097 7217 516 7217 4096 7217 4096 7218 516 7218 515 7218 4096 7219 515 7219 536 7219 506 7220 507 7220 4098 7220 4098 7221 507 7221 521 7221 4098 7222 521 7222 4099 7222 506 7223 4098 7223 504 7223 504 7224 4098 7224 4100 7224 504 7225 4100 7225 493 7225 493 7226 4100 7226 4082 7226 493 7227 4082 7227 495 7227 4101 7228 4083 7228 4084 7228 4101 7229 4084 7229 4100 7229 4100 7230 4084 7230 4085 7230 4100 7231 4085 7231 4082 7231 4102 7232 4103 7232 4104 7232 4104 7233 4105 7233 4102 7233 4102 7234 4105 7234 4106 7234 4102 7235 4106 7235 4099 7235 4099 7236 4106 7236 4107 7236 4099 7237 4107 7237 4098 7237 4098 7238 4107 7238 4108 7238 4098 7239 4108 7239 4100 7239 4100 7240 4108 7240 4109 7240 4100 7241 4109 7241 4101 7241 4088 7242 4087 7242 4110 7242 4087 7243 4111 7243 4110 7243 4110 7244 4111 7244 4112 7244 4110 7245 4112 7245 4103 7245 4103 7246 4112 7246 4113 7246 4103 7247 4113 7247 4104 7247 4114 7248 4115 7248 4116 7248 4116 7249 4115 7249 4117 7249 4116 7250 4117 7250 4118 7250 4086 7251 4088 7251 4119 7251 4119 7252 4088 7252 4116 7252 4119 7253 4116 7253 4120 7253 4120 7254 4116 7254 4118 7254 4120 7255 4118 7255 4121 7255 541 7256 4091 7256 4090 7256 4090 7257 4091 7257 4122 7257 4090 7258 4122 7258 4123 7258 4123 7259 4124 7259 4090 7259 4090 7260 4124 7260 4125 7260 4090 7261 4125 7261 4126 7261 4093 7262 4127 7262 4089 7262 4089 7263 4127 7263 4094 7263 4089 7264 4094 7264 547 7264 547 7265 4094 7265 548 7265 4125 7266 4128 7266 4126 7266 4126 7267 4128 7267 4129 7267 4126 7268 4129 7268 4130 7268 542 7269 4090 7269 4093 7269 4093 7270 4090 7270 4126 7270 4093 7271 4126 7271 4127 7271 4127 7272 4126 7272 4130 7272 4127 7273 4130 7273 4131 7273 4131 7274 4132 7274 4127 7274 4127 7275 4132 7275 4133 7275 4127 7276 4133 7276 4134 7276 521 7277 522 7277 4099 7277 4099 7278 522 7278 518 7278 4099 7279 518 7279 4102 7279 4102 7280 518 7280 4097 7280 4102 7281 4097 7281 4103 7281 4103 7282 4097 7282 4096 7282 4103 7283 4096 7283 4110 7283 4110 7284 4096 7284 4095 7284 4110 7285 4095 7285 4088 7285 4088 7286 4095 7286 4094 7286 4088 7287 4094 7287 4116 7287 4116 7288 4094 7288 4127 7288 4116 7289 4127 7289 4114 7289 4114 7290 4127 7290 4134 7290 3913 7291 3791 7291 3790 7291 4061 7292 4062 7292 4009 7292 3853 7293 3799 7293 3855 7293 3855 7294 3799 7294 3817 7294 4135 7295 4136 7295 3790 7295 3790 7296 4136 7296 4137 7296 3790 7297 4137 7297 4138 7297 3853 7298 3858 7298 3799 7298 3799 7299 3858 7299 3857 7299 3799 7300 3857 7300 3863 7300 3863 7301 3862 7301 3799 7301 3799 7302 3862 7302 3860 7302 3799 7303 3860 7303 3859 7303 4138 7304 4139 7304 3790 7304 3790 7305 4139 7305 3891 7305 3790 7306 3891 7306 3892 7306 3913 7307 3790 7307 3912 7307 3802 7308 3806 7308 4009 7308 4140 7309 4141 7309 4008 7309 4008 7310 4141 7310 4142 7310 4008 7311 4142 7311 4143 7311 4143 7312 4144 7312 4008 7312 4008 7313 4144 7313 4145 7313 4008 7314 4145 7314 4135 7314 3815 7315 3819 7315 3799 7315 3799 7316 3819 7316 3823 7316 3799 7317 3823 7317 3817 7317 3817 7318 3823 7318 3821 7318 3817 7319 3821 7319 3828 7319 3802 7320 4009 7320 3801 7320 3796 7321 3795 7321 4009 7321 4009 7322 3795 7322 3800 7322 4009 7323 3800 7323 3799 7323 3828 7324 3827 7324 3817 7324 3817 7325 3827 7325 3825 7325 3817 7326 3825 7326 3824 7326 3824 7327 3829 7327 3817 7327 3817 7328 3829 7328 3831 7328 3817 7329 3831 7329 3835 7329 3835 7330 3834 7330 3817 7330 3817 7331 3834 7331 3833 7331 3817 7332 3833 7332 3818 7332 3892 7333 3893 7333 3790 7333 3790 7334 3893 7334 3890 7334 3790 7335 3890 7335 3896 7335 3896 7336 3895 7336 3790 7336 3790 7337 3895 7337 3899 7337 3790 7338 3899 7338 3898 7338 4049 7339 4051 7339 4009 7339 4009 7340 4051 7340 4055 7340 4009 7341 4055 7341 4054 7341 4135 7342 3790 7342 4008 7342 4008 7343 3790 7343 3797 7343 4008 7344 3797 7344 4009 7344 4009 7345 3797 7345 3798 7345 4009 7346 3798 7346 3801 7346 3898 7347 3902 7347 3790 7347 3790 7348 3902 7348 3901 7348 3790 7349 3901 7349 3900 7349 3806 7350 3805 7350 4009 7350 4009 7351 3805 7351 3804 7351 4009 7352 3804 7352 3803 7352 4083 7353 4101 7353 4008 7353 4008 7354 4101 7354 4109 7354 4109 7355 4108 7355 4008 7355 4008 7356 4108 7356 4107 7356 4008 7357 4107 7357 4106 7357 4106 7358 4105 7358 4008 7358 4008 7359 4105 7359 4104 7359 4008 7360 4104 7360 4113 7360 3818 7361 3833 7361 3844 7361 3844 7362 3833 7362 3840 7362 3844 7363 3840 7363 3842 7363 3900 7364 3903 7364 3790 7364 3790 7365 3903 7365 3905 7365 3790 7366 3905 7366 3907 7366 3859 7367 3865 7367 3799 7367 3799 7368 3865 7368 3864 7368 3799 7369 3864 7369 4009 7369 4009 7370 3864 7370 3869 7370 4009 7371 3869 7371 3878 7371 4054 7372 4053 7372 4009 7372 4009 7373 4053 7373 4040 7373 4009 7374 4040 7374 4039 7374 3803 7375 3807 7375 4009 7375 4009 7376 3807 7376 3808 7376 4009 7377 3808 7377 3811 7377 3811 7378 3810 7378 4009 7378 4009 7379 3810 7379 3809 7379 4009 7380 3809 7380 3796 7380 4113 7381 4112 7381 4008 7381 4008 7382 4112 7382 4111 7382 4008 7383 4111 7383 4087 7383 4087 7384 4086 7384 4008 7384 4008 7385 4086 7385 4119 7385 4008 7386 4119 7386 4120 7386 4120 7387 4121 7387 4008 7387 4008 7388 4121 7388 4146 7388 4008 7389 4146 7389 4140 7389 3907 7390 3908 7390 3790 7390 3790 7391 3908 7391 3910 7391 3790 7392 3910 7392 3912 7392 3878 7393 4044 7393 4009 7393 4009 7394 4044 7394 4042 7394 4009 7395 4042 7395 4043 7395 4039 7396 4057 7396 4009 7396 4009 7397 4057 7397 4059 7397 4009 7398 4059 7398 4061 7398 4043 7399 4045 7399 4009 7399 4009 7400 4045 7400 4047 7400 4009 7401 4047 7401 4049 7401 4015 7402 4014 7402 4032 7402 497 7403 496 7403 4021 7403 4021 7404 496 7404 492 7404 4021 7405 492 7405 4024 7405 4024 7406 492 7406 494 7406 4024 7407 494 7407 4007 7407 4035 7408 499 7408 497 7408 715 7409 4032 7409 710 7409 710 7410 4032 7410 4014 7410 710 7411 4014 7411 722 7411 722 7412 4014 7412 4013 7412 4013 7413 4010 7413 722 7413 722 7414 4010 7414 4012 7414 722 7415 4012 7415 717 7415 4015 7416 4032 7416 4016 7416 4016 7417 4032 7417 4031 7417 4016 7418 4031 7418 4017 7418 4017 7419 4031 7419 4030 7419 4017 7420 4030 7420 4018 7420 4018 7421 4030 7421 4029 7421 4018 7422 4029 7422 4022 7422 4021 7423 4020 7423 497 7423 497 7424 4020 7424 4019 7424 497 7425 4019 7425 4035 7425 4035 7426 4019 7426 4023 7426 4035 7427 4023 7427 4034 7427 4034 7428 4023 7428 4022 7428 4034 7429 4022 7429 4033 7429 4033 7430 4022 7430 4029 7430 3887 7431 3886 7431 4147 7431 4148 7432 4149 7432 4150 7432 4141 7433 4151 7433 4142 7433 4152 7434 4153 7434 4151 7434 4151 7435 4141 7435 4152 7435 4152 7436 4141 7436 4140 7436 4152 7437 4140 7437 4146 7437 4135 7438 4145 7438 4154 7438 4154 7439 4145 7439 4144 7439 4154 7440 4144 7440 4155 7440 4135 7441 4154 7441 4136 7441 4136 7442 4154 7442 4156 7442 4136 7443 4156 7443 4137 7443 4137 7444 4156 7444 4147 7444 4137 7445 4147 7445 4138 7445 4138 7446 4147 7446 4139 7446 4139 7447 4147 7447 3886 7447 4139 7448 3886 7448 3891 7448 2486 7449 3885 7449 3785 7449 3785 7450 3885 7450 4157 7450 3785 7451 4157 7451 3786 7451 4158 7452 3788 7452 4157 7452 4157 7453 3788 7453 3787 7453 4157 7454 3787 7454 3786 7454 4159 7455 3782 7455 4160 7455 4160 7456 3782 7456 3784 7456 4160 7457 3784 7457 4158 7457 4158 7458 3784 7458 3789 7458 4158 7459 3789 7459 3788 7459 3777 7460 3775 7460 4161 7460 4161 7461 3775 7461 3774 7461 4161 7462 3774 7462 4159 7462 4159 7463 3774 7463 3781 7463 4159 7464 3781 7464 3782 7464 4162 7465 4163 7465 4161 7465 4161 7466 4163 7466 4164 7466 4161 7467 4164 7467 3777 7467 3777 7468 4164 7468 4165 7468 3777 7469 4165 7469 3779 7469 4153 7470 4148 7470 4151 7470 4151 7471 4148 7471 4150 7471 4151 7472 4150 7472 4142 7472 4142 7473 4150 7473 4155 7473 4142 7474 4155 7474 4143 7474 4143 7475 4155 7475 4144 7475 3885 7476 3887 7476 4157 7476 4157 7477 3887 7477 4147 7477 4157 7478 4147 7478 4158 7478 4158 7479 4147 7479 4156 7479 4158 7480 4156 7480 4160 7480 4160 7481 4156 7481 4154 7481 4160 7482 4154 7482 4159 7482 4159 7483 4154 7483 4155 7483 4159 7484 4155 7484 4161 7484 4161 7485 4155 7485 4150 7485 4161 7486 4150 7486 4162 7486 4162 7487 4150 7487 4149 7487 3880 7488 4081 7488 3999 7488 4076 7489 4081 7489 3880 7489 3880 7490 3873 7490 4166 7490 4166 7491 3873 7491 3874 7491 4166 7492 3874 7492 3875 7492 4077 7493 4076 7493 3880 7493 4080 7494 4079 7494 4166 7494 4166 7495 4079 7495 3880 7495 4077 7496 3880 7496 4079 7496 4074 7497 4167 7497 4075 7497 4075 7498 4167 7498 674 7498 4080 7499 4166 7499 4071 7499 4071 7500 4166 7500 3875 7500 4071 7501 3875 7501 4072 7501 4072 7502 3875 7502 3876 7502 4072 7503 3876 7503 4073 7503 4073 7504 3876 7504 3877 7504 4073 7505 3877 7505 4074 7505 4074 7506 3877 7506 4168 7506 4074 7507 4168 7507 4167 7507 705 7508 670 7508 4169 7508 672 7509 4170 7509 670 7509 670 7510 4170 7510 4171 7510 670 7511 4171 7511 4169 7511 672 7512 674 7512 4167 7512 4167 7513 4168 7513 672 7513 672 7514 4168 7514 3877 7514 672 7515 3877 7515 4170 7515 705 7516 4169 7516 702 7516 702 7517 4169 7517 4172 7517 702 7518 4172 7518 703 7518 4173 7519 4174 7519 3116 7519 3877 7520 3150 7520 3151 7520 3151 7521 3152 7521 3877 7521 3877 7522 3152 7522 3153 7522 3877 7523 3153 7523 3154 7523 3154 7524 3155 7524 3877 7524 3877 7525 3155 7525 3133 7525 3877 7526 3133 7526 932 7526 4175 7527 703 7527 3085 7527 3110 7528 3088 7528 4172 7528 4172 7529 3088 7529 3109 7529 4172 7530 3109 7530 3108 7530 3108 7531 3107 7531 4172 7531 4172 7532 3107 7532 3106 7532 4172 7533 3106 7533 703 7533 703 7534 3106 7534 3086 7534 703 7535 3086 7535 3085 7535 4172 7536 4169 7536 3110 7536 3110 7537 4169 7537 4171 7537 3110 7538 4171 7538 932 7538 932 7539 4171 7539 4170 7539 932 7540 4170 7540 3877 7540 4174 7541 4176 7541 3116 7541 3116 7542 4176 7542 4177 7542 3116 7543 4177 7543 4178 7543 3085 7544 3113 7544 4175 7544 4175 7545 3113 7545 3112 7545 4175 7546 3112 7546 3111 7546 4178 7547 4179 7547 3116 7547 3116 7548 4179 7548 4180 7548 3116 7549 4180 7549 3117 7549 3111 7550 3121 7550 4175 7550 4175 7551 3121 7551 3120 7551 4175 7552 3120 7552 4180 7552 4180 7553 3120 7553 3118 7553 4180 7554 3118 7554 3117 7554 4181 7555 3115 7555 3123 7555 3115 7556 4181 7556 3116 7556 3116 7557 4181 7557 4182 7557 3116 7558 4182 7558 4173 7558 3128 7559 3127 7559 4183 7559 3128 7560 4183 7560 3129 7560 3123 7561 3122 7561 4181 7561 4181 7562 3122 7562 3126 7562 4181 7563 3126 7563 4184 7563 4184 7564 3126 7564 3125 7564 4184 7565 3125 7565 4183 7565 4183 7566 3125 7566 3124 7566 4183 7567 3124 7567 3129 7567 3093 7568 3161 7568 3094 7568 3094 7569 3161 7569 3157 7569 3094 7570 3157 7570 3127 7570 3127 7571 3157 7571 3156 7571 3127 7572 3156 7572 3167 7572 3167 7573 3168 7573 3127 7573 3127 7574 3168 7574 3169 7574 3127 7575 3169 7575 4183 7575 3093 7576 3097 7576 3161 7576 3161 7577 3097 7577 3096 7577 3161 7578 3096 7578 3091 7578 2719 7579 3160 7579 3092 7579 3092 7580 3160 7580 3163 7580 3092 7581 3163 7581 3091 7581 3091 7582 3163 7582 3162 7582 3091 7583 3162 7583 3161 7583 4185 7584 4186 7584 4187 7584 4188 7585 4189 7585 4190 7585 4190 7586 4189 7586 4187 7586 4190 7587 4187 7587 4191 7587 4191 7588 4187 7588 4186 7588 4192 7589 3164 7589 3172 7589 4185 7590 4187 7590 4193 7590 4193 7591 4187 7591 4192 7591 4193 7592 4192 7592 4194 7592 4194 7593 4192 7593 3172 7593 4194 7594 3172 7594 3173 7594 4183 7595 3169 7595 3165 7595 3164 7596 4192 7596 3165 7596 3165 7597 4192 7597 4184 7597 3165 7598 4184 7598 4183 7598 4195 7599 4176 7599 4196 7599 4196 7600 4176 7600 4174 7600 4196 7601 4174 7601 4189 7601 4189 7602 4174 7602 4173 7602 4189 7603 4173 7603 4187 7603 4187 7604 4173 7604 4182 7604 4187 7605 4182 7605 4192 7605 4192 7606 4182 7606 4181 7606 4192 7607 4181 7607 4184 7607 4197 7608 4198 7608 3305 7608 4199 7609 4200 7609 3284 7609 3240 7610 3239 7610 4201 7610 3188 7611 3190 7611 4202 7611 4202 7612 3190 7612 4203 7612 3187 7613 4204 7613 3186 7613 3186 7614 4204 7614 4205 7614 3186 7615 4205 7615 3185 7615 3185 7616 4205 7616 4203 7616 3185 7617 4203 7617 3191 7617 3191 7618 4203 7618 3190 7618 3187 7619 3184 7619 4204 7619 4204 7620 3184 7620 3183 7620 4204 7621 3183 7621 3182 7621 3209 7622 3294 7622 3210 7622 3210 7623 3294 7623 3211 7623 3209 7624 3208 7624 3294 7624 3294 7625 3208 7625 3207 7625 3294 7626 3207 7626 3290 7626 3204 7627 3291 7627 3205 7627 3205 7628 3291 7628 3290 7628 3205 7629 3290 7629 3206 7629 3206 7630 3290 7630 3207 7630 3199 7631 3198 7631 3288 7631 3204 7632 3203 7632 3291 7632 3291 7633 3203 7633 3202 7633 3291 7634 3202 7634 3292 7634 3292 7635 3202 7635 3201 7635 3292 7636 3201 7636 3288 7636 3288 7637 3201 7637 3200 7637 3288 7638 3200 7638 3199 7638 3197 7639 3196 7639 4206 7639 4206 7640 3196 7640 3195 7640 4202 7641 4207 7641 3188 7641 3188 7642 4207 7642 4208 7642 3188 7643 4208 7643 3189 7643 3189 7644 4208 7644 3192 7644 3195 7645 3194 7645 4206 7645 4206 7646 3194 7646 3193 7646 4206 7647 3193 7647 4209 7647 4209 7648 3193 7648 3192 7648 4209 7649 3192 7649 4210 7649 4210 7650 3192 7650 4208 7650 3264 7651 3327 7651 3265 7651 3265 7652 3327 7652 3329 7652 3265 7653 3329 7653 3266 7653 3266 7654 3329 7654 3330 7654 3266 7655 3330 7655 3262 7655 3262 7656 3330 7656 3321 7656 3262 7657 3321 7657 3322 7657 3322 7658 3323 7658 3262 7658 3262 7659 3323 7659 3324 7659 3262 7660 3324 7660 3325 7660 3326 7661 3337 7661 4211 7661 4211 7662 3337 7662 3338 7662 4211 7663 3338 7663 3339 7663 3339 7664 3340 7664 4211 7664 4211 7665 3340 7665 3341 7665 4211 7666 3341 7666 4212 7666 4212 7667 3341 7667 3342 7667 4212 7668 3342 7668 4213 7668 4213 7669 3342 7669 4214 7669 4214 7670 3342 7670 3343 7670 4214 7671 3343 7671 4215 7671 4216 7672 3347 7672 4217 7672 4217 7673 3347 7673 4218 7673 3343 7674 3344 7674 4215 7674 4215 7675 3344 7675 3345 7675 4215 7676 3345 7676 4216 7676 4216 7677 3345 7677 3346 7677 4216 7678 3346 7678 3347 7678 4218 7679 3347 7679 4219 7679 4219 7680 3347 7680 3348 7680 4219 7681 3348 7681 3349 7681 3350 7682 3336 7682 3244 7682 3244 7683 3336 7683 3335 7683 3244 7684 3335 7684 3334 7684 3334 7685 3333 7685 3244 7685 3244 7686 3333 7686 3332 7686 3244 7687 3332 7687 3245 7687 3245 7688 3332 7688 3331 7688 3245 7689 3331 7689 3264 7689 3264 7690 3331 7690 3328 7690 3264 7691 3328 7691 3327 7691 4220 7692 4221 7692 4222 7692 3239 7693 4223 7693 4224 7693 4224 7694 4225 7694 3239 7694 3239 7695 4225 7695 4226 7695 3239 7696 4226 7696 4227 7696 4228 7697 4201 7697 4222 7697 4222 7698 4201 7698 3239 7698 4222 7699 3239 7699 4220 7699 4220 7700 3239 7700 4227 7700 4223 7701 3239 7701 4229 7701 4229 7702 3239 7702 3279 7702 4229 7703 3279 7703 4230 7703 3284 7704 4200 7704 3280 7704 3280 7705 4200 7705 4231 7705 3280 7706 4231 7706 3279 7706 3279 7707 4231 7707 4232 7707 3279 7708 4232 7708 4230 7708 3281 7709 4233 7709 3282 7709 3282 7710 4233 7710 4234 7710 3282 7711 4234 7711 3284 7711 3284 7712 4234 7712 4235 7712 3284 7713 4235 7713 4199 7713 3198 7714 3197 7714 3288 7714 3288 7715 3197 7715 4206 7715 3288 7716 4206 7716 3286 7716 3286 7717 4206 7717 4236 7717 3286 7718 4236 7718 3285 7718 3285 7719 4236 7719 4237 7719 3285 7720 4237 7720 3281 7720 3281 7721 4237 7721 4238 7721 3281 7722 4238 7722 4233 7722 3236 7723 4239 7723 3237 7723 3237 7724 4239 7724 4240 7724 3237 7725 4240 7725 3295 7725 3295 7726 4240 7726 4204 7726 3295 7727 4204 7727 3294 7727 3294 7728 4204 7728 3182 7728 3294 7729 3182 7729 3211 7729 3297 7730 4241 7730 3296 7730 3296 7731 4241 7731 4242 7731 3296 7732 4242 7732 3236 7732 3236 7733 4242 7733 4243 7733 3236 7734 4243 7734 4239 7734 4244 7735 4245 7735 3302 7735 3302 7736 4245 7736 4246 7736 3302 7737 4246 7737 3303 7737 3303 7738 4246 7738 4247 7738 3303 7739 4247 7739 3297 7739 3297 7740 4247 7740 4248 7740 3297 7741 4248 7741 4241 7741 4198 7742 4249 7742 3305 7742 3305 7743 4249 7743 4250 7743 3305 7744 4250 7744 4251 7744 4251 7745 4252 7745 3305 7745 3305 7746 4252 7746 4253 7746 3305 7747 4253 7747 3299 7747 3299 7748 4253 7748 4254 7748 3299 7749 4254 7749 3300 7749 3300 7750 4254 7750 4255 7750 3300 7751 4255 7751 3302 7751 3302 7752 4255 7752 4256 7752 3302 7753 4256 7753 4244 7753 4257 7754 4258 7754 4259 7754 4260 7755 4261 7755 4262 7755 4263 7756 4260 7756 3305 7756 4257 7757 4259 7757 3252 7757 3252 7758 4259 7758 4264 7758 3252 7759 4264 7759 4265 7759 4265 7760 4264 7760 4266 7760 4265 7761 4266 7761 3305 7761 3305 7762 4266 7762 4267 7762 3305 7763 4267 7763 4263 7763 4260 7764 4262 7764 3305 7764 3305 7765 4262 7765 4268 7765 3305 7766 4268 7766 4197 7766 4269 7767 4270 7767 3252 7767 4271 7768 4257 7768 4272 7768 4272 7769 4257 7769 3252 7769 4272 7770 3252 7770 4273 7770 4273 7771 3252 7771 4270 7771 4273 7772 4270 7772 4274 7772 3258 7773 4275 7773 3257 7773 3257 7774 4275 7774 4276 7774 3257 7775 4276 7775 3255 7775 3255 7776 4276 7776 4277 7776 4277 7777 4278 7777 3255 7777 3255 7778 4278 7778 4279 7778 3255 7779 4279 7779 3253 7779 3253 7780 4279 7780 4280 7780 3253 7781 4280 7781 3251 7781 3251 7782 4280 7782 4281 7782 3251 7783 4281 7783 3252 7783 3252 7784 4281 7784 4282 7784 3252 7785 4282 7785 4269 7785 3247 7786 4283 7786 3248 7786 3248 7787 4283 7787 4284 7787 3248 7788 4284 7788 3258 7788 3258 7789 4284 7789 4285 7789 3258 7790 4285 7790 4275 7790 3325 7791 3326 7791 3262 7791 3262 7792 3326 7792 4211 7792 3262 7793 4211 7793 3260 7793 3260 7794 4211 7794 3259 7794 3259 7795 4211 7795 4286 7795 3259 7796 4286 7796 3247 7796 3247 7797 4286 7797 4287 7797 3247 7798 4287 7798 4283 7798 4288 7799 3268 7799 4289 7799 4289 7800 3268 7800 3270 7800 4289 7801 3270 7801 4290 7801 3349 7802 3350 7802 4219 7802 4219 7803 3350 7803 3244 7803 4219 7804 3244 7804 4288 7804 4288 7805 3244 7805 3269 7805 4288 7806 3269 7806 3268 7806 3241 7807 4291 7807 4292 7807 4292 7808 4293 7808 3241 7808 3241 7809 4293 7809 4294 7809 3241 7810 4294 7810 3242 7810 3242 7811 4294 7811 4295 7811 3242 7812 4295 7812 3270 7812 3270 7813 4295 7813 4296 7813 3270 7814 4296 7814 4290 7814 3272 7815 4297 7815 3271 7815 3271 7816 4297 7816 4298 7816 3271 7817 4298 7817 3241 7817 3241 7818 4298 7818 4299 7818 3241 7819 4299 7819 4291 7819 4201 7820 4300 7820 3240 7820 3240 7821 4300 7821 4301 7821 3240 7822 4301 7822 3277 7822 3277 7823 4301 7823 4302 7823 3277 7824 4302 7824 4303 7824 4304 7825 4305 7825 4306 7825 4303 7826 4307 7826 4308 7826 4308 7827 4307 7827 4309 7827 4308 7828 4309 7828 4310 7828 4310 7829 4311 7829 4308 7829 4308 7830 4311 7830 4312 7830 4308 7831 4312 7831 4304 7831 4304 7832 4306 7832 4308 7832 4308 7833 4306 7833 4313 7833 4308 7834 4313 7834 4314 7834 4303 7835 4308 7835 3277 7835 3277 7836 4308 7836 4314 7836 3277 7837 4314 7837 3276 7837 3276 7838 4314 7838 4315 7838 3276 7839 4315 7839 3274 7839 3274 7840 4315 7840 4316 7840 3274 7841 4316 7841 3272 7841 3272 7842 4316 7842 4317 7842 3272 7843 4317 7843 4297 7843 4318 7844 4319 7844 4320 7844 4321 7845 4322 7845 4323 7845 4323 7846 4322 7846 4324 7846 4325 7847 4326 7847 4327 7847 4321 7848 4328 7848 4322 7848 4322 7849 4328 7849 4325 7849 4322 7850 4325 7850 4329 7850 4329 7851 4325 7851 4327 7851 3716 7852 4320 7852 3723 7852 3723 7853 4320 7853 4319 7853 3723 7854 4319 7854 3724 7854 3724 7855 4319 7855 3439 7855 4323 7856 4330 7856 4321 7856 4321 7857 4330 7857 4331 7857 4321 7858 4331 7858 4320 7858 4320 7859 4331 7859 4332 7859 4320 7860 4332 7860 4318 7860 3715 7861 4333 7861 3716 7861 3716 7862 4333 7862 4334 7862 3716 7863 4334 7863 4320 7863 4320 7864 4334 7864 4335 7864 4320 7865 4335 7865 4321 7865 4321 7866 4335 7866 4336 7866 4321 7867 4336 7867 4328 7867 4337 7868 4338 7868 4339 7868 4340 7869 4341 7869 3383 7869 3383 7870 3382 7870 4340 7870 4340 7871 3382 7871 3390 7871 4340 7872 3390 7872 4342 7872 4342 7873 3390 7873 3389 7873 4342 7874 3389 7874 4343 7874 4343 7875 3389 7875 3388 7875 4343 7876 3388 7876 3387 7876 3378 7877 3379 7877 4344 7877 4344 7878 3379 7878 3380 7878 4344 7879 3380 7879 4345 7879 3380 7880 3381 7880 4345 7880 4345 7881 3381 7881 3385 7881 4345 7882 3385 7882 4341 7882 4341 7883 3385 7883 3384 7883 4341 7884 3384 7884 3383 7884 4346 7885 4347 7885 4339 7885 4339 7886 4347 7886 4348 7886 4339 7887 4348 7887 4337 7887 4349 7888 4350 7888 4346 7888 4349 7889 4351 7889 4352 7889 4352 7890 4353 7890 4349 7890 4349 7891 4353 7891 4354 7891 4349 7892 4354 7892 4355 7892 4355 7893 4356 7893 4349 7893 4349 7894 4356 7894 4357 7894 4349 7895 4357 7895 4350 7895 3507 7896 3506 7896 4349 7896 4349 7897 3506 7897 3509 7897 4349 7898 3509 7898 4351 7898 4351 7899 3509 7899 3508 7899 4351 7900 3508 7900 3510 7900 3510 7901 3503 7901 4351 7901 4351 7902 3503 7902 3502 7902 4351 7903 3502 7903 4358 7903 4358 7904 3502 7904 3501 7904 4358 7905 3501 7905 3505 7905 4346 7906 4339 7906 4349 7906 4349 7907 4339 7907 3520 7907 4349 7908 3520 7908 3507 7908 3386 7909 4339 7909 3387 7909 3387 7910 4339 7910 4338 7910 3387 7911 4338 7911 4343 7911 3386 7912 3391 7912 4339 7912 4339 7913 3391 7913 3392 7913 4339 7914 3392 7914 3357 7914 3518 7915 3517 7915 4339 7915 3518 7916 4339 7916 3519 7916 3357 7917 2895 7917 4339 7917 4339 7918 2895 7918 3492 7918 4339 7919 3492 7919 3519 7919 3517 7920 3522 7920 4339 7920 4339 7921 3522 7921 3521 7921 4339 7922 3521 7922 3520 7922 4359 7923 4360 7923 4361 7923 4362 7924 698 7924 697 7924 691 7925 4361 7925 692 7925 692 7926 4361 7926 696 7926 4360 7927 4363 7927 4361 7927 4361 7928 4363 7928 4364 7928 4361 7929 4364 7929 696 7929 696 7930 4364 7930 4365 7930 696 7931 4365 7931 695 7931 695 7932 4365 7932 4366 7932 695 7933 4366 7933 664 7933 664 7934 4366 7934 4367 7934 664 7935 4367 7935 700 7935 4362 7936 697 7936 4368 7936 700 7937 4367 7937 697 7937 697 7938 4367 7938 4369 7938 697 7939 4369 7939 4368 7939 4370 7940 4371 7940 4372 7940 4373 7941 4374 7941 4370 7941 4370 7942 4374 7942 4375 7942 4370 7943 4375 7943 4371 7943 4188 7944 4373 7944 4376 7944 4376 7945 4373 7945 4370 7945 4376 7946 4370 7946 4377 7946 4377 7947 4370 7947 4378 7947 4372 7948 4359 7948 4370 7948 4370 7949 4359 7949 4361 7949 4370 7950 4361 7950 690 7950 690 7951 4361 7951 691 7951 690 7952 689 7952 4370 7952 4370 7953 689 7953 688 7953 4370 7954 688 7954 4378 7954 4378 7955 688 7955 687 7955 4378 7956 687 7956 686 7956 4379 7957 4380 7957 4378 7957 681 7958 4379 7958 682 7958 682 7959 4379 7959 4378 7959 682 7960 4378 7960 683 7960 683 7961 4378 7961 686 7961 4381 7962 4176 7962 4195 7962 4188 7963 4376 7963 4189 7963 4189 7964 4376 7964 4377 7964 4189 7965 4377 7965 4196 7965 4196 7966 4377 7966 4378 7966 4196 7967 4378 7967 4195 7967 4195 7968 4378 7968 4380 7968 4195 7969 4380 7969 4381 7969 676 7970 673 7970 4382 7970 671 7971 706 7971 4180 7971 4180 7972 706 7972 4175 7972 4175 7973 706 7973 704 7973 4175 7974 704 7974 703 7974 4379 7975 681 7975 677 7975 677 7976 676 7976 4379 7976 4379 7977 676 7977 4382 7977 4379 7978 4382 7978 4177 7978 671 7979 4180 7979 673 7979 673 7980 4180 7980 4179 7980 673 7981 4179 7981 4382 7981 4382 7982 4179 7982 4178 7982 4382 7983 4178 7983 4177 7983 4176 7984 4381 7984 4177 7984 4177 7985 4381 7985 4380 7985 4177 7986 4380 7986 4379 7986 3414 7987 3413 7987 4383 7987 4384 7988 4385 7988 4386 7988 4387 7989 4388 7989 4389 7989 4390 7990 4391 7990 4389 7990 3916 7991 3918 7991 4392 7991 4393 7992 4394 7992 4395 7992 4362 7993 4368 7993 4396 7993 4396 7994 4368 7994 4369 7994 4194 7995 3173 7995 3395 7995 4373 7996 4188 7996 4190 7996 4191 7997 4186 7997 4397 7997 4397 7998 4186 7998 4185 7998 4397 7999 4185 7999 4193 7999 4359 8000 4372 8000 4398 8000 4398 8001 4372 8001 4371 8001 4398 8002 4371 8002 4399 8002 4190 8003 4191 8003 4373 8003 4373 8004 4191 8004 4397 8004 4373 8005 4397 8005 4374 8005 4374 8006 4397 8006 4399 8006 4374 8007 4399 8007 4375 8007 4375 8008 4399 8008 4371 8008 4364 8009 4363 8009 4400 8009 4400 8010 4363 8010 4360 8010 4400 8011 4360 8011 4359 8011 4365 8012 4401 8012 4366 8012 4366 8013 4401 8013 4367 8013 4402 8014 4403 8014 4404 8014 4404 8015 4403 8015 4405 8015 4404 8016 4405 8016 698 8016 4393 8017 4395 8017 4406 8017 4407 8018 4408 8018 4409 8018 4410 8019 4411 8019 4412 8019 4412 8020 4411 8020 4413 8020 4412 8021 4413 8021 4414 8021 4414 8022 4413 8022 4415 8022 4414 8023 4415 8023 4406 8023 4416 8024 4417 8024 4407 8024 4407 8025 4417 8025 4418 8025 4407 8026 4418 8026 4408 8026 4419 8027 4392 8027 4420 8027 4419 8028 4420 8028 4385 8028 4420 8029 4421 8029 4385 8029 4385 8030 4421 8030 4422 8030 4385 8031 4422 8031 4386 8031 4386 8032 4422 8032 4423 8032 4419 8033 3930 8033 3929 8033 4419 8034 3929 8034 4392 8034 4392 8035 3929 8035 3914 8035 4392 8036 3914 8036 3916 8036 3400 8037 3927 8037 4419 8037 4419 8038 3927 8038 3931 8038 4419 8039 3931 8039 3930 8039 4424 8040 4425 8040 4426 8040 4394 8041 4427 8041 4428 8041 4428 8042 4427 8042 4429 8042 4428 8043 4429 8043 4390 8043 698 8044 4362 8044 4404 8044 4404 8045 4362 8045 4396 8045 4404 8046 4396 8046 4401 8046 4401 8047 4396 8047 4369 8047 4401 8048 4369 8048 4367 8048 4430 8049 4401 8049 4400 8049 4400 8050 4401 8050 4365 8050 4400 8051 4365 8051 4364 8051 4431 8052 4388 8052 4432 8052 4432 8053 4388 8053 4387 8053 4432 8054 4387 8054 4433 8054 4434 8055 4407 8055 4412 8055 4412 8056 4407 8056 4409 8056 4412 8057 4409 8057 4410 8057 4193 8058 4194 8058 4397 8058 4397 8059 4194 8059 3395 8059 4397 8060 3395 8060 4399 8060 4399 8061 3395 8061 3394 8061 4399 8062 3394 8062 3393 8062 4359 8063 4398 8063 4400 8063 4400 8064 4398 8064 4399 8064 4400 8065 4399 8065 4430 8065 4430 8066 4399 8066 3393 8066 4430 8067 3393 8067 3423 8067 3423 8068 3422 8068 4430 8068 4430 8069 3422 8069 4435 8069 4430 8070 4435 8070 4401 8070 4401 8071 4435 8071 4436 8071 4401 8072 4436 8072 4404 8072 4404 8073 4436 8073 4426 8073 4404 8074 4426 8074 4402 8074 4402 8075 4426 8075 4425 8075 3422 8076 3421 8076 4435 8076 4435 8077 3421 8077 4433 8077 4435 8078 4433 8078 4436 8078 4436 8079 4433 8079 4387 8079 4436 8080 4387 8080 4426 8080 4426 8081 4387 8081 4389 8081 4426 8082 4389 8082 4424 8082 4424 8083 4389 8083 4391 8083 3421 8084 3420 8084 4433 8084 4433 8085 3420 8085 3419 8085 4433 8086 3419 8086 4432 8086 4432 8087 3419 8087 3418 8087 4432 8088 3418 8088 4431 8088 4431 8089 3418 8089 3417 8089 4431 8090 3417 8090 3416 8090 4390 8091 4389 8091 4428 8091 4428 8092 4389 8092 4388 8092 4428 8093 4388 8093 4437 8093 4437 8094 4388 8094 4431 8094 4437 8095 4431 8095 4438 8095 4438 8096 4431 8096 3416 8096 4438 8097 3416 8097 3415 8097 4394 8098 4428 8098 4395 8098 4395 8099 4428 8099 4437 8099 4395 8100 4437 8100 4439 8100 4439 8101 4437 8101 4438 8101 4439 8102 4438 8102 4383 8102 4383 8103 4438 8103 3415 8103 4383 8104 3415 8104 3414 8104 4406 8105 4395 8105 4414 8105 4414 8106 4395 8106 4439 8106 4414 8107 4439 8107 4412 8107 4412 8108 4439 8108 4383 8108 4412 8109 4383 8109 4434 8109 4434 8110 4383 8110 3413 8110 4434 8111 3413 8111 3412 8111 3412 8112 3411 8112 4434 8112 4434 8113 3411 8113 4384 8113 4434 8114 4384 8114 4407 8114 4407 8115 4384 8115 4386 8115 4407 8116 4386 8116 4416 8116 4416 8117 4386 8117 4423 8117 3411 8118 3410 8118 4384 8118 4384 8119 3410 8119 3398 8119 4384 8120 3398 8120 4385 8120 4385 8121 3398 8121 3403 8121 4385 8122 3403 8122 4419 8122 4419 8123 3403 8123 3401 8123 4419 8124 3401 8124 3400 8124 580 8125 4440 8125 581 8125 581 8126 4440 8126 4441 8126 581 8127 4441 8127 583 8127 4442 8128 4443 8128 577 8128 577 8129 4443 8129 4444 8129 577 8130 4444 8130 575 8130 577 8131 582 8131 4442 8131 4442 8132 582 8132 583 8132 4442 8133 583 8133 4445 8133 4445 8134 583 8134 4441 8134 4445 8135 4441 8135 4446 8135 4446 8136 4441 8136 4447 8136 4446 8137 4447 8137 4326 8137 565 8138 563 8138 4448 8138 4327 8139 4326 8139 4447 8139 4447 8140 4441 8140 4327 8140 4327 8141 4441 8141 4440 8141 4327 8142 4440 8142 4329 8142 565 8143 4448 8143 579 8143 580 8144 579 8144 4440 8144 4440 8145 579 8145 4448 8145 4440 8146 4448 8146 4329 8146 4329 8147 4448 8147 4449 8147 4329 8148 4449 8148 4322 8148 4322 8149 4449 8149 4324 8149 4450 8150 4324 8150 4449 8150 4451 8151 4452 8151 555 8151 4452 8152 4453 8152 4454 8152 555 8153 554 8153 4451 8153 4451 8154 554 8154 591 8154 4451 8155 591 8155 4455 8155 4455 8156 591 8156 4456 8156 4456 8157 591 8157 4457 8157 4457 8158 591 8158 590 8158 4457 8159 590 8159 588 8159 559 8160 558 8160 4454 8160 4454 8161 558 8161 557 8161 4454 8162 557 8162 4452 8162 4452 8163 557 8163 556 8163 4452 8164 556 8164 555 8164 559 8165 4454 8165 560 8165 560 8166 4454 8166 4458 8166 560 8167 4458 8167 561 8167 4458 8168 4449 8168 4448 8168 561 8169 4458 8169 562 8169 562 8170 4458 8170 4448 8170 562 8171 4448 8171 563 8171 4453 8172 4459 8172 4454 8172 4454 8173 4459 8173 4460 8173 4454 8174 4460 8174 4458 8174 4458 8175 4460 8175 4461 8175 4458 8176 4461 8176 4462 8176 4462 8177 4463 8177 4458 8177 4458 8178 4463 8178 4464 8178 4458 8179 4464 8179 4449 8179 4449 8180 4464 8180 4465 8180 4449 8181 4465 8181 4450 8181 4466 8182 4467 8182 572 8182 573 8183 572 8183 4468 8183 4468 8184 572 8184 4467 8184 4468 8185 4467 8185 4469 8185 4469 8186 4467 8186 4470 8186 4469 8187 4470 8187 4471 8187 575 8188 4472 8188 576 8188 576 8189 4472 8189 4466 8189 576 8190 4466 8190 578 8190 578 8191 4466 8191 572 8191 4446 8192 4326 8192 4325 8192 3780 8193 3779 8193 4471 8193 4467 8194 3760 8194 3759 8194 4467 8195 3759 8195 4470 8195 4470 8196 3759 8196 2409 8196 4470 8197 2409 8197 4471 8197 4471 8198 2409 8198 3778 8198 4471 8199 3778 8199 3780 8199 3764 8200 3762 8200 4472 8200 575 8201 3757 8201 4472 8201 4472 8202 3757 8202 3756 8202 4472 8203 3756 8203 3764 8203 4467 8204 4466 8204 3760 8204 3760 8205 4466 8205 4472 8205 3760 8206 4472 8206 3761 8206 3761 8207 4472 8207 3762 8207 3754 8208 3753 8208 575 8208 575 8209 3753 8209 3758 8209 575 8210 3758 8210 3757 8210 3750 8211 3748 8211 4443 8211 4443 8212 3748 8212 3747 8212 575 8213 4444 8213 3754 8213 3754 8214 4444 8214 4443 8214 3754 8215 4443 8215 3755 8215 3755 8216 4443 8216 3747 8216 3750 8217 4443 8217 3751 8217 3751 8218 4443 8218 4442 8218 3751 8219 4442 8219 3742 8219 3742 8220 4442 8220 4445 8220 3742 8221 4445 8221 4446 8221 4446 8222 4325 8222 3742 8222 3742 8223 4325 8223 4328 8223 3742 8224 4328 8224 4336 8224 3735 8225 3746 8225 4334 8225 4334 8226 3746 8226 3745 8226 4336 8227 4335 8227 3742 8227 3742 8228 4335 8228 4334 8228 3742 8229 4334 8229 3743 8229 3743 8230 4334 8230 3745 8230 3721 8231 3734 8231 3714 8231 3714 8232 3734 8232 3715 8232 3715 8233 3734 8233 4333 8233 4333 8234 3734 8234 3741 8234 4333 8235 3741 8235 3740 8235 3740 8236 3739 8236 4333 8236 4333 8237 3739 8237 3738 8237 4333 8238 3738 8238 4334 8238 4334 8239 3738 8239 3736 8239 4334 8240 3736 8240 3735 8240 3730 8241 3731 8241 3717 8241 3717 8242 3722 8242 3730 8242 3730 8243 3722 8243 3712 8243 3730 8244 3712 8244 3729 8244 3729 8245 3712 8245 3711 8245 3729 8246 3711 8246 3728 8246 3728 8247 3711 8247 2861 8247 3721 8248 3719 8248 3734 8248 3734 8249 3719 8249 3718 8249 3734 8250 3718 8250 3733 8250 3733 8251 3718 8251 3717 8251 3733 8252 3717 8252 3732 8252 3732 8253 3717 8253 3731 8253 3705 8254 3430 8254 3429 8254 4323 8255 4324 8255 4450 8255 4473 8256 4474 8256 4475 8256 4475 8257 4474 8257 4476 8257 4475 8258 4476 8258 4477 8258 4478 8259 4479 8259 4480 8259 4481 8260 4453 8260 4452 8260 4451 8261 4455 8261 4482 8261 4482 8262 4455 8262 4456 8262 4482 8263 4456 8263 4483 8263 4483 8264 4456 8264 4457 8264 4462 8265 4461 8265 4481 8265 4461 8266 4460 8266 4481 8266 4481 8267 4460 8267 4459 8267 4481 8268 4459 8268 4453 8268 4464 8269 4463 8269 4484 8269 4484 8270 4463 8270 4485 8270 4484 8271 4485 8271 4486 8271 4464 8272 4484 8272 4465 8272 4465 8273 4484 8273 4487 8273 4465 8274 4487 8274 4450 8274 4450 8275 4487 8275 4330 8275 4450 8276 4330 8276 4323 8276 4319 8277 4318 8277 4487 8277 4319 8278 4487 8278 3439 8278 4318 8279 4332 8279 4487 8279 4487 8280 4332 8280 4331 8280 4487 8281 4331 8281 4330 8281 4488 8282 3700 8282 3701 8282 3702 8283 3692 8283 4489 8283 4489 8284 3692 8284 3691 8284 4489 8285 3691 8285 3704 8285 4477 8286 4490 8286 4491 8286 4491 8287 4490 8287 4492 8287 4491 8288 4492 8288 4493 8288 3701 8289 3702 8289 4488 8289 4488 8290 3702 8290 4489 8290 4488 8291 4489 8291 4494 8291 4494 8292 4489 8292 4493 8292 4494 8293 4493 8293 4495 8293 4495 8294 4493 8294 4492 8294 4496 8295 4497 8295 4498 8295 4498 8296 4497 8296 4499 8296 4498 8297 4499 8297 4500 8297 4501 8298 4502 8298 4503 8298 4502 8299 4501 8299 4504 8299 4504 8300 4501 8300 4505 8300 4504 8301 4505 8301 4506 8301 4457 8302 588 8302 4507 8302 4507 8303 588 8303 4508 8303 4507 8304 4508 8304 4505 8304 4505 8305 4508 8305 4509 8305 4505 8306 4509 8306 4506 8306 4500 8307 4510 8307 4498 8307 4498 8308 4510 8308 4511 8308 4498 8309 4511 8309 4478 8309 4478 8310 4511 8310 4512 8310 4478 8311 4512 8311 4479 8311 4513 8312 4507 8312 4514 8312 4514 8313 4507 8313 4505 8313 4514 8314 4505 8314 4515 8314 4515 8315 4505 8315 4501 8315 4515 8316 4501 8316 4516 8316 4517 8317 4478 8317 4475 8317 4475 8318 4478 8318 4480 8318 4475 8319 4480 8319 4473 8319 4518 8320 4513 8320 4519 8320 4519 8321 4513 8321 4514 8321 4519 8322 4514 8322 4520 8322 4520 8323 4514 8323 4515 8323 4520 8324 4515 8324 4521 8324 4521 8325 4515 8325 4516 8325 4521 8326 4516 8326 4522 8326 4523 8327 4481 8327 4482 8327 4482 8328 4481 8328 4452 8328 4482 8329 4452 8329 4451 8329 3704 8330 3705 8330 4489 8330 4489 8331 3705 8331 3429 8331 4489 8332 3429 8332 4493 8332 4493 8333 3429 8333 3427 8333 4493 8334 3427 8334 3426 8334 4477 8335 4491 8335 4475 8335 4475 8336 4491 8336 4493 8336 4475 8337 4493 8337 4517 8337 4517 8338 4493 8338 3426 8338 4517 8339 3426 8339 3462 8339 3462 8340 3461 8340 4517 8340 4517 8341 3461 8341 4524 8341 4517 8342 4524 8342 4478 8342 4478 8343 4524 8343 4525 8343 4478 8344 4525 8344 4498 8344 4498 8345 4525 8345 4526 8345 4498 8346 4526 8346 4496 8346 4496 8347 4526 8347 4527 8347 3461 8348 3460 8348 4524 8348 4524 8349 3460 8349 4522 8349 4524 8350 4522 8350 4525 8350 4525 8351 4522 8351 4516 8351 4525 8352 4516 8352 4526 8352 4526 8353 4516 8353 4501 8353 4526 8354 4501 8354 4527 8354 4527 8355 4501 8355 4503 8355 3460 8356 3459 8356 4522 8356 4522 8357 3459 8357 3458 8357 4522 8358 3458 8358 4521 8358 4521 8359 3458 8359 3457 8359 4521 8360 3457 8360 4520 8360 4520 8361 3457 8361 4528 8361 4520 8362 4528 8362 4519 8362 4519 8363 4528 8363 3455 8363 4519 8364 3455 8364 4518 8364 4518 8365 3455 8365 3454 8365 4518 8366 3454 8366 3453 8366 4457 8367 4507 8367 4483 8367 4483 8368 4507 8368 4513 8368 4483 8369 4513 8369 4482 8369 4482 8370 4513 8370 4518 8370 4482 8371 4518 8371 4523 8371 4523 8372 4518 8372 3453 8372 4523 8373 3453 8373 3452 8373 3452 8374 3451 8374 4523 8374 4523 8375 3451 8375 4486 8375 4523 8376 4486 8376 4481 8376 4481 8377 4486 8377 4485 8377 4481 8378 4485 8378 4462 8378 4462 8379 4485 8379 4463 8379 3451 8380 3450 8380 4486 8380 4486 8381 3450 8381 3443 8381 4486 8382 3443 8382 4484 8382 4484 8383 3443 8383 3444 8383 4484 8384 3444 8384 4487 8384 4487 8385 3444 8385 3440 8385 4487 8386 3440 8386 3439 8386 4529 8387 4530 8387 4531 8387 4531 8388 4530 8388 4532 8388 4531 8389 4532 8389 4533 8389 4533 8390 4532 8390 4534 8390 4530 8391 4535 8391 4532 8391 4532 8392 4535 8392 4536 8392 4532 8393 4536 8393 4537 8393 4538 8394 4539 8394 4540 8394 4537 8395 4541 8395 4532 8395 4532 8396 4541 8396 4542 8396 4532 8397 4542 8397 4543 8397 4544 8398 4538 8398 4545 8398 4545 8399 4538 8399 4532 8399 4545 8400 4532 8400 4546 8400 4546 8401 4532 8401 4543 8401 4538 8402 4540 8402 4532 8402 4532 8403 4540 8403 4547 8403 4532 8404 4547 8404 4534 8404 3513 8405 3514 8405 4548 8405 4549 8406 4550 8406 4551 8406 4552 8407 4553 8407 4554 8407 4553 8408 4552 8408 4555 8408 4555 8409 4552 8409 4556 8409 4555 8410 4556 8410 4557 8410 4558 8411 4559 8411 4560 8411 4560 8412 4559 8412 4549 8412 3496 8413 4558 8413 3495 8413 3495 8414 4558 8414 4560 8414 3495 8415 4560 8415 3494 8415 3494 8416 4560 8416 4561 8416 3498 8417 3499 8417 4562 8417 4562 8418 3499 8418 3500 8418 4562 8419 3500 8419 4561 8419 4561 8420 3500 8420 3493 8420 4561 8421 3493 8421 3494 8421 4563 8422 3516 8422 4564 8422 4564 8423 3516 8423 3497 8423 4548 8424 3514 8424 4563 8424 4563 8425 3514 8425 3515 8425 4563 8426 3515 8426 3516 8426 3512 8427 4565 8427 3511 8427 3511 8428 4565 8428 4552 8428 3511 8429 4552 8429 3504 8429 3504 8430 4552 8430 4554 8430 3504 8431 4554 8431 3505 8431 4549 8432 4551 8432 4560 8432 4560 8433 4551 8433 4566 8433 4560 8434 4566 8434 4561 8434 4566 8435 4567 8435 4561 8435 4561 8436 4567 8436 4568 8436 4561 8437 4568 8437 4562 8437 4562 8438 4568 8438 4569 8438 4569 8439 4570 8439 4562 8439 4562 8440 4570 8440 4564 8440 4562 8441 4564 8441 3498 8441 3498 8442 4564 8442 3497 8442 4570 8443 4571 8443 4564 8443 4564 8444 4571 8444 4572 8444 4564 8445 4572 8445 4563 8445 4563 8446 4572 8446 4573 8446 4574 8447 4548 8447 4575 8447 4575 8448 4548 8448 4563 8448 4575 8449 4563 8449 4576 8449 4576 8450 4563 8450 4573 8450 4574 8451 4577 8451 4548 8451 4548 8452 4577 8452 4565 8452 4548 8453 4565 8453 3513 8453 3513 8454 4565 8454 3512 8454 4577 8455 4578 8455 4565 8455 4565 8456 4578 8456 4579 8456 4565 8457 4579 8457 4552 8457 4552 8458 4579 8458 4580 8458 4552 8459 4580 8459 4556 8459 3496 8460 3478 8460 3476 8460 4581 8461 4550 8461 3525 8461 3525 8462 4550 8462 4549 8462 3476 8463 3470 8463 3496 8463 3496 8464 3470 8464 3469 8464 3496 8465 3469 8465 4558 8465 4558 8466 3469 8466 3525 8466 4558 8467 3525 8467 4559 8467 4559 8468 3525 8468 4549 8468 4582 8469 4583 8469 3531 8469 4581 8470 3525 8470 4584 8470 4584 8471 3525 8471 3526 8471 4584 8472 3526 8472 3527 8472 3527 8473 3524 8473 4584 8473 4584 8474 3524 8474 3523 8474 4584 8475 3523 8475 3529 8475 3541 8476 3538 8476 3544 8476 3544 8477 3538 8477 4585 8477 3537 8478 3549 8478 4586 8478 3549 8479 3551 8479 4586 8479 4586 8480 3551 8480 3553 8480 4586 8481 3553 8481 4587 8481 3537 8482 4586 8482 3538 8482 3538 8483 4586 8483 4588 8483 3538 8484 4588 8484 4585 8484 3529 8485 3528 8485 4584 8485 4584 8486 3528 8486 3530 8486 4584 8487 3530 8487 4589 8487 4589 8488 3530 8488 3534 8488 4589 8489 3534 8489 4590 8489 4590 8490 3534 8490 3535 8490 4590 8491 3535 8491 4591 8491 4591 8492 3535 8492 4592 8492 4592 8493 3535 8493 4593 8493 4593 8494 3535 8494 3536 8494 4593 8495 3536 8495 4594 8495 4583 8496 4595 8496 3531 8496 3531 8497 4595 8497 4596 8497 3531 8498 4596 8498 3536 8498 3536 8499 4596 8499 4597 8499 3536 8500 4597 8500 4594 8500 4582 8501 3531 8501 4598 8501 4598 8502 3531 8502 3533 8502 4598 8503 3533 8503 4585 8503 4585 8504 3533 8504 3532 8504 4585 8505 3532 8505 3544 8505 3552 8506 3567 8506 3588 8506 3588 8507 3567 8507 3568 8507 3588 8508 3568 8508 3557 8508 3552 8509 3588 8509 3553 8509 3553 8510 3588 8510 4599 8510 3553 8511 4599 8511 4600 8511 4600 8512 4601 8512 3553 8512 3553 8513 4601 8513 4602 8513 3553 8514 4602 8514 4587 8514 3594 8515 3589 8515 4603 8515 3577 8516 3576 8516 4604 8516 4604 8517 3576 8517 4605 8517 4605 8518 4606 8518 4604 8518 4604 8519 4606 8519 4607 8519 4604 8520 4607 8520 4608 8520 4609 8521 4600 8521 4599 8521 4600 8522 4609 8522 4601 8522 4601 8523 4609 8523 4610 8523 4601 8524 4610 8524 4602 8524 4603 8525 3589 8525 4604 8525 4604 8526 3589 8526 3590 8526 4604 8527 3590 8527 3577 8527 3593 8528 4611 8528 3592 8528 3592 8529 4611 8529 4612 8529 3592 8530 4612 8530 3591 8530 3591 8531 4612 8531 3573 8531 3574 8532 4613 8532 3583 8532 3583 8533 4613 8533 4614 8533 3583 8534 4614 8534 3584 8534 3584 8535 4614 8535 3585 8535 3585 8536 4614 8536 4615 8536 3585 8537 4615 8537 3586 8537 3586 8538 4615 8538 4609 8538 3586 8539 4609 8539 3587 8539 3587 8540 4609 8540 4599 8540 3587 8541 4599 8541 3588 8541 4616 8542 4603 8542 4617 8542 4617 8543 4603 8543 4604 8543 4617 8544 4604 8544 4618 8544 4618 8545 4604 8545 4608 8545 4618 8546 4608 8546 4619 8546 4616 8547 4620 8547 4603 8547 4603 8548 4620 8548 4611 8548 4603 8549 4611 8549 3594 8549 3594 8550 4611 8550 3593 8550 4620 8551 4621 8551 4611 8551 4611 8552 4621 8552 4622 8552 4611 8553 4622 8553 4612 8553 4612 8554 4622 8554 4623 8554 4612 8555 4623 8555 4624 8555 4624 8556 4625 8556 4612 8556 4612 8557 4625 8557 4613 8557 4612 8558 4613 8558 3573 8558 3573 8559 4613 8559 3574 8559 4625 8560 4626 8560 4613 8560 4613 8561 4626 8561 4627 8561 4613 8562 4627 8562 4614 8562 4614 8563 4627 8563 4628 8563 4614 8564 4628 8564 4615 8564 4628 8565 4629 8565 4615 8565 4615 8566 4629 8566 4630 8566 4615 8567 4630 8567 4609 8567 4609 8568 4630 8568 4631 8568 4609 8569 4631 8569 4610 8569 4619 8570 4608 8570 4632 8570 4633 8571 4634 8571 4632 8571 4632 8572 4634 8572 4635 8572 4632 8573 4635 8573 4619 8573 4636 8574 4637 8574 4633 8574 4633 8575 4637 8575 4638 8575 4633 8576 4638 8576 4634 8576 4639 8577 4640 8577 4641 8577 4641 8578 4640 8578 4642 8578 4641 8579 4642 8579 4636 8579 4636 8580 4642 8580 4643 8580 4636 8581 4643 8581 4637 8581 4644 8582 4645 8582 4646 8582 4646 8583 4645 8583 4639 8583 4646 8584 4639 8584 4647 8584 4647 8585 4639 8585 4641 8585 4648 8586 4644 8586 4649 8586 4649 8587 4644 8587 4646 8587 4649 8588 4646 8588 4650 8588 4650 8589 4646 8589 4647 8589 4650 8590 4647 8590 4651 8590 4651 8591 4647 8591 4652 8591 4653 8592 3621 8592 3620 8592 4653 8593 3620 8593 4654 8593 4654 8594 3620 8594 3619 8594 4654 8595 3619 8595 4655 8595 4655 8596 3619 8596 3624 8596 4655 8597 3624 8597 3625 8597 4656 8598 4657 8598 3612 8598 3612 8599 3611 8599 4656 8599 4656 8600 3611 8600 3610 8600 4656 8601 3610 8601 4658 8601 4658 8602 3610 8602 3609 8602 4658 8603 3609 8603 4653 8603 4653 8604 3609 8604 3622 8604 4653 8605 3622 8605 3621 8605 4605 8606 3576 8606 3618 8606 3617 8607 3616 8607 4657 8607 4657 8608 3616 8608 3615 8608 3615 8609 3614 8609 4657 8609 4657 8610 3614 8610 3613 8610 4657 8611 3613 8611 3612 8611 3618 8612 3617 8612 4605 8612 4605 8613 3617 8613 4657 8613 4605 8614 4657 8614 4606 8614 4606 8615 4657 8615 4607 8615 4608 8616 4607 8616 4632 8616 4632 8617 4607 8617 4657 8617 4632 8618 4657 8618 4633 8618 4633 8619 4657 8619 4656 8619 4633 8620 4656 8620 4636 8620 4636 8621 4656 8621 4658 8621 4636 8622 4658 8622 4641 8622 4641 8623 4658 8623 4653 8623 4641 8624 4653 8624 4647 8624 4647 8625 4653 8625 4654 8625 4647 8626 4654 8626 4652 8626 4652 8627 4654 8627 4655 8627 550 8628 4659 8628 551 8628 641 8629 648 8629 4660 8629 4232 8630 4231 8630 4661 8630 666 8631 665 8631 4201 8631 4201 8632 665 8632 663 8632 4201 8633 663 8633 4300 8633 4300 8634 663 8634 662 8634 4300 8635 662 8635 4301 8635 4301 8636 662 8636 4662 8636 4301 8637 4662 8637 4302 8637 4201 8638 4228 8638 666 8638 666 8639 4228 8639 4222 8639 666 8640 4222 8640 667 8640 667 8641 4222 8641 4221 8641 667 8642 4221 8642 668 8642 668 8643 4221 8643 4220 8643 668 8644 4220 8644 669 8644 669 8645 4220 8645 4227 8645 669 8646 4227 8646 678 8646 4227 8647 4226 8647 678 8647 678 8648 4226 8648 4225 8648 678 8649 4225 8649 679 8649 679 8650 4225 8650 680 8650 4225 8651 4224 8651 680 8651 680 8652 4224 8652 4223 8652 680 8653 4223 8653 693 8653 693 8654 4223 8654 4229 8654 693 8655 4229 8655 694 8655 694 8656 4229 8656 4230 8656 4661 8657 657 8657 4232 8657 4232 8658 657 8658 656 8658 4232 8659 656 8659 4230 8659 4230 8660 656 8660 685 8660 4230 8661 685 8661 694 8661 648 8662 647 8662 4660 8662 4660 8663 647 8663 650 8663 4660 8664 650 8664 4661 8664 4661 8665 650 8665 649 8665 4661 8666 649 8666 657 8666 4663 8667 642 8667 641 8667 631 8668 630 8668 4663 8668 4663 8669 630 8669 644 8669 4663 8670 644 8670 642 8670 631 8671 4663 8671 623 8671 623 8672 4663 8672 4664 8672 623 8673 4664 8673 624 8673 624 8674 4664 8674 4665 8674 624 8675 4665 8675 609 8675 617 8676 619 8676 4665 8676 4665 8677 619 8677 621 8677 4665 8678 621 8678 609 8678 606 8679 611 8679 4666 8679 4666 8680 611 8680 613 8680 4666 8681 613 8681 4665 8681 4665 8682 613 8682 615 8682 4665 8683 615 8683 617 8683 4667 8684 604 8684 606 8684 529 8685 528 8685 4668 8685 4668 8686 528 8686 594 8686 4668 8687 594 8687 4667 8687 4667 8688 594 8688 596 8688 4667 8689 596 8689 604 8689 529 8690 4668 8690 530 8690 530 8691 4668 8691 4669 8691 530 8692 4669 8692 525 8692 539 8693 538 8693 4669 8693 4669 8694 538 8694 537 8694 4669 8695 537 8695 525 8695 4659 8696 550 8696 4670 8696 550 8697 543 8697 4670 8697 4670 8698 543 8698 533 8698 4670 8699 533 8699 540 8699 569 8700 4198 8700 570 8700 570 8701 4198 8701 4197 8701 570 8702 4197 8702 571 8702 571 8703 4197 8703 584 8703 4197 8704 4268 8704 584 8704 584 8705 4268 8705 4262 8705 584 8706 4262 8706 585 8706 585 8707 4262 8707 586 8707 4262 8708 4261 8708 586 8708 586 8709 4261 8709 4260 8709 586 8710 4260 8710 593 8710 593 8711 4260 8711 4263 8711 593 8712 4263 8712 4671 8712 4671 8713 4263 8713 4267 8713 4671 8714 4267 8714 4266 8714 4670 8715 4245 8715 4659 8715 4659 8716 4245 8716 4244 8716 4659 8717 4244 8717 551 8717 551 8718 4244 8718 4256 8718 551 8719 4256 8719 564 8719 564 8720 4256 8720 4255 8720 564 8721 4255 8721 552 8721 552 8722 4255 8722 4254 8722 552 8723 4254 8723 553 8723 553 8724 4254 8724 4253 8724 553 8725 4253 8725 566 8725 566 8726 4253 8726 4252 8726 566 8727 4252 8727 567 8727 567 8728 4252 8728 4251 8728 567 8729 4251 8729 568 8729 568 8730 4251 8730 4250 8730 568 8731 4250 8731 569 8731 569 8732 4250 8732 4249 8732 569 8733 4249 8733 4198 8733 4248 8734 4247 8734 4670 8734 4670 8735 4247 8735 4246 8735 4670 8736 4246 8736 4245 8736 4241 8737 4248 8737 4669 8737 4669 8738 4248 8738 4670 8738 4669 8739 4670 8739 539 8739 539 8740 4670 8740 540 8740 4241 8741 4669 8741 4242 8741 4242 8742 4669 8742 4668 8742 4242 8743 4668 8743 4243 8743 4205 8744 4204 8744 4667 8744 4667 8745 4204 8745 4240 8745 4667 8746 4240 8746 4668 8746 4668 8747 4240 8747 4239 8747 4668 8748 4239 8748 4243 8748 606 8749 4666 8749 4667 8749 4667 8750 4666 8750 4203 8750 4667 8751 4203 8751 4205 8751 4208 8752 4207 8752 4666 8752 4666 8753 4207 8753 4202 8753 4666 8754 4202 8754 4203 8754 4208 8755 4666 8755 4210 8755 4210 8756 4666 8756 4665 8756 4210 8757 4665 8757 4209 8757 4209 8758 4665 8758 4664 8758 4209 8759 4664 8759 4206 8759 4233 8760 4238 8760 4663 8760 4663 8761 4238 8761 4237 8761 4663 8762 4237 8762 4664 8762 4664 8763 4237 8763 4236 8763 4664 8764 4236 8764 4206 8764 641 8765 4660 8765 4663 8765 4663 8766 4660 8766 4234 8766 4663 8767 4234 8767 4233 8767 4231 8768 4200 8768 4661 8768 4661 8769 4200 8769 4199 8769 4661 8770 4199 8770 4660 8770 4660 8771 4199 8771 4235 8771 4660 8772 4235 8772 4234 8772 4672 8773 4673 8773 4674 8773 4675 8774 4676 8774 4677 8774 4285 8775 4284 8775 4678 8775 4213 8776 4214 8776 4679 8776 4307 8777 4303 8777 4680 8777 4680 8778 4303 8778 4302 8778 4681 8779 4682 8779 4309 8779 4307 8780 4680 8780 4309 8780 4309 8781 4680 8781 662 8781 4309 8782 662 8782 4681 8782 4317 8783 4316 8783 4683 8783 4683 8784 4316 8784 4315 8784 4683 8785 4315 8785 4684 8785 4684 8786 4315 8786 4314 8786 4684 8787 4314 8787 4685 8787 4685 8788 4314 8788 4313 8788 4685 8789 4313 8789 4686 8789 4686 8790 4313 8790 4306 8790 4686 8791 4306 8791 4687 8791 4687 8792 4306 8792 4305 8792 4687 8793 4305 8793 4688 8793 4688 8794 4305 8794 4304 8794 4688 8795 4304 8795 4689 8795 4689 8796 4304 8796 4312 8796 4689 8797 4312 8797 4690 8797 4690 8798 4312 8798 4311 8798 4690 8799 4311 8799 4682 8799 4682 8800 4311 8800 4310 8800 4682 8801 4310 8801 4309 8801 4691 8802 4298 8802 4297 8802 4683 8803 4692 8803 4317 8803 4317 8804 4692 8804 4693 8804 4317 8805 4693 8805 4297 8805 4297 8806 4693 8806 4694 8806 4297 8807 4694 8807 4691 8807 4695 8808 4674 8808 4292 8808 4292 8809 4291 8809 4695 8809 4695 8810 4291 8810 4299 8810 4695 8811 4299 8811 4298 8811 4296 8812 4295 8812 4696 8812 4696 8813 4295 8813 4294 8813 4696 8814 4294 8814 4674 8814 4674 8815 4294 8815 4293 8815 4674 8816 4293 8816 4292 8816 4219 8817 4697 8817 4218 8817 4218 8818 4697 8818 4698 8818 4219 8819 4288 8819 4697 8819 4697 8820 4288 8820 4289 8820 4697 8821 4289 8821 4696 8821 4696 8822 4289 8822 4290 8822 4696 8823 4290 8823 4296 8823 4214 8824 4215 8824 4679 8824 4679 8825 4215 8825 4216 8825 4679 8826 4216 8826 4698 8826 4698 8827 4216 8827 4217 8827 4698 8828 4217 8828 4218 8828 4212 8829 4677 8829 4211 8829 4211 8830 4677 8830 4699 8830 4284 8831 4283 8831 4699 8831 4283 8832 4287 8832 4699 8832 4699 8833 4287 8833 4286 8833 4699 8834 4286 8834 4211 8834 4276 8835 4275 8835 4700 8835 4700 8836 4275 8836 4285 8836 4276 8837 4700 8837 4277 8837 4277 8838 4700 8838 4701 8838 4277 8839 4701 8839 4278 8839 4278 8840 4701 8840 4702 8840 4278 8841 4702 8841 4279 8841 4279 8842 4702 8842 4703 8842 4279 8843 4703 8843 4280 8843 4280 8844 4703 8844 4704 8844 4280 8845 4704 8845 4281 8845 4281 8846 4704 8846 4705 8846 4281 8847 4705 8847 4282 8847 4282 8848 4705 8848 4706 8848 4282 8849 4706 8849 4269 8849 4707 8850 4270 8850 4708 8850 4708 8851 4270 8851 4269 8851 4708 8852 4269 8852 4709 8852 4709 8853 4269 8853 4706 8853 4257 8854 4271 8854 4710 8854 4710 8855 4271 8855 4272 8855 4710 8856 4272 8856 4711 8856 4711 8857 4272 8857 4273 8857 4711 8858 4273 8858 4707 8858 4707 8859 4273 8859 4274 8859 4707 8860 4274 8860 4270 8860 4710 8861 4712 8861 4257 8861 4257 8862 4712 8862 4713 8862 4257 8863 4713 8863 4258 8863 4258 8864 4713 8864 4714 8864 4258 8865 4714 8865 4259 8865 4259 8866 4714 8866 593 8866 4259 8867 593 8867 4264 8867 4264 8868 593 8868 4671 8868 4264 8869 4671 8869 4266 8869 4700 8870 4715 8870 4716 8870 4716 8871 4717 8871 4700 8871 4700 8872 4717 8872 4718 8872 4700 8873 4718 8873 4701 8873 4701 8874 4718 8874 4719 8874 4701 8875 4719 8875 4702 8875 4285 8876 4678 8876 4700 8876 4700 8877 4678 8877 4720 8877 4700 8878 4720 8878 4715 8878 4721 8879 4722 8879 4678 8879 4678 8880 4722 8880 4723 8880 4678 8881 4723 8881 4720 8881 4284 8882 4699 8882 4678 8882 4678 8883 4699 8883 4724 8883 4678 8884 4724 8884 4721 8884 4676 8885 4725 8885 4677 8885 4677 8886 4725 8886 4726 8886 4677 8887 4726 8887 4699 8887 4699 8888 4726 8888 4727 8888 4699 8889 4727 8889 4724 8889 4728 8890 4675 8890 4679 8890 4679 8891 4675 8891 4677 8891 4679 8892 4677 8892 4213 8892 4213 8893 4677 8893 4212 8893 4729 8894 4730 8894 4698 8894 4698 8895 4730 8895 4731 8895 4698 8896 4731 8896 4679 8896 4679 8897 4731 8897 4732 8897 4679 8898 4732 8898 4728 8898 4733 8899 4734 8899 4696 8899 4696 8900 4734 8900 4735 8900 4696 8901 4735 8901 4697 8901 4697 8902 4735 8902 4736 8902 4697 8903 4736 8903 4698 8903 4698 8904 4736 8904 4737 8904 4698 8905 4737 8905 4729 8905 4674 8906 4673 8906 4696 8906 4696 8907 4673 8907 4738 8907 4696 8908 4738 8908 4733 8908 4298 8909 4691 8909 4695 8909 4695 8910 4691 8910 4739 8910 4695 8911 4739 8911 4674 8911 4674 8912 4739 8912 4740 8912 4674 8913 4740 8913 4672 8913 4741 8914 4742 8914 4743 8914 4743 8915 4742 8915 4744 8915 4743 8916 4744 8916 4745 8916 4743 8917 4746 8917 4747 8917 4741 8918 4743 8918 4748 8918 4748 8919 4743 8919 4747 8919 4748 8920 4747 8920 4749 8920 4745 8921 4417 8921 4743 8921 4743 8922 4417 8922 4416 8922 4743 8923 4416 8923 4423 8923 4423 8924 4422 8924 4743 8924 4743 8925 4422 8925 4421 8925 4743 8926 4421 8926 4746 8926 4746 8927 4421 8927 4420 8927 4746 8928 4420 8928 4750 8928 4750 8929 4420 8929 4392 8929 4750 8930 4392 8930 3918 8930 4751 8931 4410 8931 4752 8931 4752 8932 4410 8932 4409 8932 4409 8933 4408 8933 4745 8933 4745 8934 4408 8934 4418 8934 4745 8935 4418 8935 4417 8935 4744 8936 4753 8936 4745 8936 4745 8937 4753 8937 4754 8937 4745 8938 4754 8938 4409 8938 4409 8939 4754 8939 4755 8939 4409 8940 4755 8940 4752 8940 4406 8941 4415 8941 4756 8941 4756 8942 4415 8942 4413 8942 4756 8943 4413 8943 4751 8943 4751 8944 4413 8944 4411 8944 4751 8945 4411 8945 4410 8945 4757 8946 4749 8946 4747 8946 3918 8947 3917 8947 4750 8947 4750 8948 3917 8948 3923 8948 4750 8949 3923 8949 4746 8949 4746 8950 3923 8950 4747 8950 4758 8951 3921 8951 4759 8951 4759 8952 3921 8952 3920 8952 4757 8953 4747 8953 4760 8953 4761 8954 4760 8954 4762 8954 4762 8955 4760 8955 4747 8955 4762 8956 4747 8956 4758 8956 4758 8957 4747 8957 3923 8957 4758 8958 3923 8958 3921 8958 4763 8959 4764 8959 4765 8959 3920 8960 4766 8960 4759 8960 4759 8961 4766 8961 4758 8961 4765 8962 4764 8962 4766 8962 4766 8963 4764 8963 4762 8963 4766 8964 4762 8964 4758 8964 4767 8965 4768 8965 4769 8965 4769 8966 4768 8966 4770 8966 4769 8967 4770 8967 4771 8967 4771 8968 4770 8968 4772 8968 4771 8969 4772 8969 4763 8969 4763 8970 4772 8970 4773 8970 4763 8971 4773 8971 4764 8971 4764 8972 4773 8972 4774 8972 4764 8973 4774 8973 4762 8973 4762 8974 4774 8974 4761 8974 4775 8975 4534 8975 4776 8975 4776 8976 4534 8976 4777 8976 4533 8977 4534 8977 4778 8977 4778 8978 4534 8978 4775 8978 4778 8979 4775 8979 4779 8979 4779 8980 4775 8980 4780 8980 4781 8981 4782 8981 4783 8981 4784 8982 4785 8982 4786 8982 4786 8983 4787 8983 4784 8983 4784 8984 4787 8984 4788 8984 4784 8985 4788 8985 4789 8985 4790 8986 4791 8986 4792 8986 4792 8987 4793 8987 4790 8987 4790 8988 4793 8988 4794 8988 4790 8989 4794 8989 4795 8989 4795 8990 4794 8990 4784 8990 4795 8991 4784 8991 4783 8991 4783 8992 4784 8992 4789 8992 4783 8993 4789 8993 4781 8993 4783 8994 4782 8994 4796 8994 4783 8995 4796 8995 4797 8995 4798 8996 4791 8996 4790 8996 4790 8997 4797 8997 4798 8997 4798 8998 4797 8998 4796 8998 4798 8999 4796 8999 4799 8999 4799 9000 4796 9000 4800 9000 4799 9001 4800 9001 4801 9001 4801 9002 4800 9002 4802 9002 4801 9003 4802 9003 4803 9003 4788 9004 4787 9004 4544 9004 4543 9005 4542 9005 4796 9005 4796 9006 4542 9006 4800 9006 4800 9007 4542 9007 4541 9007 4800 9008 4541 9008 4802 9008 4804 9009 4803 9009 4802 9009 4535 9010 4530 9010 4805 9010 4541 9011 4537 9011 4802 9011 4802 9012 4537 9012 4536 9012 4802 9013 4536 9013 4804 9013 4804 9014 4536 9014 4535 9014 4804 9015 4535 9015 4806 9015 4806 9016 4535 9016 4805 9016 4543 9017 4796 9017 4546 9017 4546 9018 4796 9018 4782 9018 4546 9019 4782 9019 4545 9019 4545 9020 4782 9020 4781 9020 4545 9021 4781 9021 4544 9021 4544 9022 4781 9022 4789 9022 4544 9023 4789 9023 4788 9023 4786 9024 4539 9024 4787 9024 4787 9025 4539 9025 4538 9025 4787 9026 4538 9026 4544 9026 4786 9027 4785 9027 4539 9027 4539 9028 4785 9028 4807 9028 4539 9029 4807 9029 4540 9029 4540 9030 4807 9030 4808 9030 4540 9031 4808 9031 4547 9031 4547 9032 4808 9032 4777 9032 4547 9033 4777 9033 4534 9033 3695 9034 4809 9034 4810 9034 4810 9035 4809 9035 4811 9035 4810 9036 4811 9036 4812 9036 4813 9037 4814 9037 4815 9037 4815 9038 4814 9038 4812 9038 4815 9039 4812 9039 4816 9039 4816 9040 4812 9040 4811 9040 4816 9041 4811 9041 4817 9041 4815 9042 4818 9042 4813 9042 4813 9043 4818 9043 4819 9043 4813 9044 4819 9044 4820 9044 4820 9045 4819 9045 4821 9045 4822 9046 4817 9046 4823 9046 3694 9047 3696 9047 4824 9047 4824 9048 3696 9048 4825 9048 4825 9049 3696 9049 4826 9049 4826 9050 3696 9050 3698 9050 4826 9051 3698 9051 3700 9051 4824 9052 4827 9052 4828 9052 4828 9053 4822 9053 4824 9053 4824 9054 4822 9054 4823 9054 4824 9055 4823 9055 3694 9055 3694 9056 4823 9056 4809 9056 3694 9057 4809 9057 3695 9057 4494 9058 4495 9058 4829 9058 4829 9059 4495 9059 4492 9059 4492 9060 4490 9060 4829 9060 4829 9061 4490 9061 4477 9061 4829 9062 4477 9062 4830 9062 4829 9063 4825 9063 4826 9063 4494 9064 4829 9064 4488 9064 4488 9065 4829 9065 4826 9065 4488 9066 4826 9066 3700 9066 4829 9067 4831 9067 4832 9067 4825 9068 4829 9068 4824 9068 4824 9069 4829 9069 4832 9069 4824 9070 4832 9070 4827 9070 4833 9071 4834 9071 4830 9071 4830 9072 4834 9072 4835 9072 4830 9073 4835 9073 4829 9073 4829 9074 4835 9074 4836 9074 4829 9075 4836 9075 4831 9075 4477 9076 4476 9076 4830 9076 4830 9077 4476 9077 4474 9077 4830 9078 4474 9078 4833 9078 4833 9079 4474 9079 4473 9079 4833 9080 4473 9080 4837 9080 4837 9081 4473 9081 4480 9081 4837 9082 4480 9082 4838 9082 4838 9083 4480 9083 4479 9083 4838 9084 4479 9084 4839 9084 4479 9085 4512 9085 4839 9085 4839 9086 4512 9086 4511 9086 4839 9087 4511 9087 4840 9087 4840 9088 4511 9088 4510 9088 4840 9089 4510 9089 4500 9089 4841 9090 4842 9090 3598 9090 3606 9091 4843 9091 3595 9091 3595 9092 4843 9092 4844 9092 3595 9093 4844 9093 4845 9093 4846 9094 3596 9094 4847 9094 4847 9095 3596 9095 3595 9095 4847 9096 3595 9096 4848 9096 4848 9097 3595 9097 4845 9097 4849 9098 4850 9098 3602 9098 3602 9099 4850 9099 4851 9099 3602 9100 4851 9100 3606 9100 3606 9101 4851 9101 4852 9101 3606 9102 4852 9102 4843 9102 3602 9103 3601 9103 4853 9103 4853 9104 4854 9104 3602 9104 3602 9105 4854 9105 4855 9105 3602 9106 4855 9106 4856 9106 4856 9107 4857 9107 3602 9107 3602 9108 4857 9108 4858 9108 3602 9109 4858 9109 4849 9109 3599 9110 4859 9110 4860 9110 4860 9111 4861 9111 3599 9111 3599 9112 4861 9112 4862 9112 3599 9113 4862 9113 3601 9113 3601 9114 4862 9114 4863 9114 3601 9115 4863 9115 4853 9115 4859 9116 3599 9116 4864 9116 4864 9117 3599 9117 3605 9117 4864 9118 3605 9118 4865 9118 4866 9119 4867 9119 3604 9119 3604 9120 4867 9120 4868 9120 3604 9121 4868 9121 3605 9121 3605 9122 4868 9122 4869 9122 3605 9123 4869 9123 4865 9123 4866 9124 3604 9124 4870 9124 4870 9125 3604 9125 3603 9125 4870 9126 3603 9126 4871 9126 4872 9127 4873 9127 3603 9127 3603 9128 4873 9128 4874 9128 3603 9129 4874 9129 4871 9129 4875 9130 4876 9130 3600 9130 4875 9131 4877 9131 4876 9131 4876 9132 4877 9132 4872 9132 4876 9133 4872 9133 3600 9133 3600 9134 4872 9134 3603 9134 3598 9135 4842 9135 3600 9135 3600 9136 4842 9136 4878 9136 3600 9137 4878 9137 4879 9137 4879 9138 4880 9138 3600 9138 3600 9139 4880 9139 4881 9139 3600 9140 4881 9140 4875 9140 4846 9141 4882 9141 3596 9141 3596 9142 4882 9142 4883 9142 3596 9143 4883 9143 3597 9143 3597 9144 4883 9144 4884 9144 3597 9145 4884 9145 4885 9145 4885 9146 4886 9146 3597 9146 3597 9147 4886 9147 4887 9147 3597 9148 4887 9148 3598 9148 3598 9149 4887 9149 4888 9149 3598 9150 4888 9150 4841 9150 3672 9151 3671 9151 3709 9151 3709 9152 3671 9152 3635 9152 3709 9153 3635 9153 3634 9153 3687 9154 3634 9154 3676 9154 3676 9155 3634 9155 3677 9155 3687 9156 3688 9156 3634 9156 3634 9157 3688 9157 3689 9157 3634 9158 3689 9158 3709 9158 3677 9159 3634 9159 3683 9159 3683 9160 3634 9160 3637 9160 3683 9161 3637 9161 3639 9161 3639 9162 3638 9162 3683 9162 3683 9163 3638 9163 3633 9163 3683 9164 3633 9164 3682 9164 3682 9165 3633 9165 3680 9165 3680 9166 3633 9166 3632 9166 3680 9167 3632 9167 3679 9167 3679 9168 3632 9168 3631 9168 3679 9169 3631 9169 2864 9169 3670 9170 3669 9170 3708 9170 3670 9171 3708 9171 3662 9171 3669 9172 3668 9172 3708 9172 3708 9173 3668 9173 3667 9173 3708 9174 3667 9174 3709 9174 3709 9175 3667 9175 3673 9175 3709 9176 3673 9176 3672 9176 3706 9177 3699 9177 3663 9177 3662 9178 3708 9178 3663 9178 3663 9179 3708 9179 3707 9179 3663 9180 3707 9180 3706 9180 3699 9181 3697 9181 3663 9181 3663 9182 3697 9182 3695 9182 3663 9183 3695 9183 4810 9183 3659 9184 3658 9184 4820 9184 4810 9185 4812 9185 3663 9185 3663 9186 4812 9186 4814 9186 3663 9187 4814 9187 4813 9187 3658 9188 3657 9188 4820 9188 4820 9189 3657 9189 3666 9189 4820 9190 3666 9190 4813 9190 4813 9191 3666 9191 3665 9191 4813 9192 3665 9192 3663 9192 4821 9193 3661 9193 4820 9193 4820 9194 3661 9194 3660 9194 4820 9195 3660 9195 3659 9195 3653 9196 3649 9196 4889 9196 4889 9197 3649 9197 3650 9197 4889 9198 3650 9198 4821 9198 4821 9199 3650 9199 3651 9199 4821 9200 3651 9200 3661 9200 4890 9201 3625 9201 3623 9201 3623 9202 3626 9202 4890 9202 4890 9203 3626 9203 2788 9203 4890 9204 2788 9204 4891 9204 2788 9205 3630 9205 4891 9205 4891 9206 3630 9206 3655 9206 4891 9207 3655 9207 4892 9207 4892 9208 3655 9208 3654 9208 4892 9209 3654 9209 4889 9209 4889 9210 3654 9210 3652 9210 4889 9211 3652 9211 3653 9211 4893 9212 4805 9212 4530 9212 4894 9213 4895 9213 4896 9213 4530 9214 4529 9214 4894 9214 4894 9215 4896 9215 4530 9215 4530 9216 4896 9216 4897 9216 4530 9217 4897 9217 4893 9217 3625 9218 4890 9218 4655 9218 4655 9219 4890 9219 4898 9219 4655 9220 4898 9220 4652 9220 4650 9221 4899 9221 4649 9221 4649 9222 4899 9222 4900 9222 4649 9223 4900 9223 4648 9223 4652 9224 4898 9224 4651 9224 4651 9225 4898 9225 4901 9225 4651 9226 4901 9226 4650 9226 4650 9227 4901 9227 4902 9227 4650 9228 4902 9228 4899 9228 4890 9229 4903 9229 4904 9229 4897 9230 4896 9230 4905 9230 4895 9231 4894 9231 4906 9231 4907 9232 4908 9232 4909 9232 4910 9233 4900 9233 4899 9233 4910 9234 4899 9234 4911 9234 4912 9235 4913 9235 4914 9235 4914 9236 4915 9236 4912 9236 4912 9237 4915 9237 4916 9237 4912 9238 4916 9238 4917 9238 4917 9239 4916 9239 4918 9239 4917 9240 4918 9240 4911 9240 4909 9241 4908 9241 4919 9241 4908 9242 4920 9242 4919 9242 4919 9243 4920 9243 4921 9243 4919 9244 4921 9244 4913 9244 4913 9245 4921 9245 4922 9245 4913 9246 4922 9246 4914 9246 4923 9247 4924 9247 4925 9247 4925 9248 4924 9248 4907 9248 4896 9249 4895 9249 4905 9249 4905 9250 4895 9250 4906 9250 4905 9251 4906 9251 4923 9251 4923 9252 4906 9252 4926 9252 4923 9253 4926 9253 4924 9253 4893 9254 4897 9254 4927 9254 4927 9255 4897 9255 4905 9255 4927 9256 4905 9256 4928 9256 4928 9257 4905 9257 4923 9257 4928 9258 4923 9258 4929 9258 4929 9259 4923 9259 4930 9259 4930 9260 4923 9260 4931 9260 4931 9261 4923 9261 4925 9261 4931 9262 4925 9262 4932 9262 4907 9263 4909 9263 4925 9263 4925 9264 4909 9264 4933 9264 4925 9265 4933 9265 4932 9265 4934 9266 4935 9266 4936 9266 4936 9267 4935 9267 4937 9267 4937 9268 4935 9268 4938 9268 4937 9269 4938 9269 4939 9269 4940 9270 4941 9270 4936 9270 4936 9271 4941 9271 4942 9271 4936 9272 4942 9272 4934 9272 4943 9273 4944 9273 4945 9273 4945 9274 4944 9274 4946 9274 4945 9275 4946 9275 4940 9275 4940 9276 4946 9276 4947 9276 4940 9277 4947 9277 4941 9277 4948 9278 4949 9278 4950 9278 4950 9279 4949 9279 4951 9279 4950 9280 4951 9280 4952 9280 4952 9281 4951 9281 4953 9281 4953 9282 4951 9282 4904 9282 4953 9283 4904 9283 4954 9283 4954 9284 4904 9284 4955 9284 4955 9285 4904 9285 4903 9285 4955 9286 4903 9286 4956 9286 4911 9287 4899 9287 4917 9287 4917 9288 4899 9288 4902 9288 4917 9289 4902 9289 4901 9289 4939 9290 4933 9290 4937 9290 4937 9291 4933 9291 4909 9291 4937 9292 4909 9292 4936 9292 4936 9293 4909 9293 4919 9293 4936 9294 4919 9294 4940 9294 4940 9295 4919 9295 4913 9295 4940 9296 4913 9296 4945 9296 4945 9297 4913 9297 4912 9297 4945 9298 4912 9298 4957 9298 4957 9299 4912 9299 4917 9299 4957 9300 4917 9300 4958 9300 4958 9301 4917 9301 4901 9301 4958 9302 4901 9302 4898 9302 4948 9303 4943 9303 4949 9303 4949 9304 4943 9304 4945 9304 4949 9305 4945 9305 4951 9305 4951 9306 4945 9306 4957 9306 4951 9307 4957 9307 4904 9307 4904 9308 4957 9308 4958 9308 4904 9309 4958 9309 4890 9309 4890 9310 4958 9310 4898 9310 4956 9311 4890 9311 4959 9311 4959 9312 4890 9312 4891 9312 4959 9313 4891 9313 4960 9313 4960 9314 4891 9314 4892 9314 4960 9315 4892 9315 4961 9315 4961 9316 4892 9316 4889 9316 4961 9317 4889 9317 4821 9317 4768 9318 4767 9318 4962 9318 4840 9319 4500 9319 587 9319 4838 9320 4839 9320 592 9320 592 9321 4839 9321 4840 9321 592 9322 4840 9322 589 9322 589 9323 4840 9323 587 9323 592 9324 593 9324 4714 9324 4710 9325 4711 9325 4838 9325 4710 9326 4838 9326 4712 9326 592 9327 4714 9327 4838 9327 4838 9328 4714 9328 4713 9328 4838 9329 4713 9329 4712 9329 4959 9330 4960 9330 4819 9330 4819 9331 4960 9331 4961 9331 4819 9332 4961 9332 4821 9332 4959 9333 4819 9333 4956 9333 4956 9334 4819 9334 4818 9334 4956 9335 4818 9335 4955 9335 4955 9336 4818 9336 4815 9336 4955 9337 4815 9337 4816 9337 4816 9338 4817 9338 4955 9338 4955 9339 4817 9339 4822 9339 4955 9340 4822 9340 4828 9340 4711 9341 4707 9341 4838 9341 4838 9342 4707 9342 4708 9342 4838 9343 4708 9343 4709 9343 4828 9344 4827 9344 4704 9344 4704 9345 4827 9345 4832 9345 4704 9346 4832 9346 4831 9346 4831 9347 4836 9347 4704 9347 4704 9348 4836 9348 4835 9348 4704 9349 4835 9349 4834 9349 4834 9350 4833 9350 4704 9350 4704 9351 4833 9351 4837 9351 4704 9352 4837 9352 4705 9352 4705 9353 4837 9353 4838 9353 4705 9354 4838 9354 4706 9354 4706 9355 4838 9355 4709 9355 4828 9356 4704 9356 4955 9356 4955 9357 4704 9357 4703 9357 4955 9358 4703 9358 4702 9358 4717 9359 4944 9359 4718 9359 4718 9360 4944 9360 4943 9360 4718 9361 4943 9361 4948 9361 4948 9362 4950 9362 4718 9362 4718 9363 4950 9363 4952 9363 4718 9364 4952 9364 4953 9364 4702 9365 4719 9365 4955 9365 4955 9366 4719 9366 4718 9366 4955 9367 4718 9367 4954 9367 4954 9368 4718 9368 4953 9368 4934 9369 4716 9369 4715 9369 4722 9370 4935 9370 4723 9370 4723 9371 4935 9371 4934 9371 4723 9372 4934 9372 4720 9372 4720 9373 4934 9373 4715 9373 4716 9374 4934 9374 4717 9374 4717 9375 4934 9375 4942 9375 4717 9376 4942 9376 4941 9376 4941 9377 4947 9377 4717 9377 4717 9378 4947 9378 4946 9378 4717 9379 4946 9379 4944 9379 4722 9380 4721 9380 4864 9380 4864 9381 4721 9381 4724 9381 4864 9382 4724 9382 4727 9382 4864 9383 4865 9383 4722 9383 4722 9384 4865 9384 4869 9384 4722 9385 4869 9385 4935 9385 4935 9386 4869 9386 4868 9386 4935 9387 4868 9387 4867 9387 4933 9388 4939 9388 4867 9388 4867 9389 4939 9389 4938 9389 4867 9390 4938 9390 4935 9390 4870 9391 4930 9391 4866 9391 4866 9392 4930 9392 4931 9392 4866 9393 4931 9393 4867 9393 4867 9394 4931 9394 4932 9394 4867 9395 4932 9395 4933 9395 4791 9396 4873 9396 4872 9396 4873 9397 4791 9397 4874 9397 4874 9398 4791 9398 4798 9398 4874 9399 4798 9399 4799 9399 4799 9400 4801 9400 4874 9400 4874 9401 4801 9401 4803 9401 4874 9402 4803 9402 4804 9402 4870 9403 4871 9403 4930 9403 4930 9404 4871 9404 4874 9404 4930 9405 4874 9405 4806 9405 4806 9406 4874 9406 4804 9406 4893 9407 4927 9407 4805 9407 4805 9408 4927 9408 4928 9408 4805 9409 4928 9409 4806 9409 4806 9410 4928 9410 4929 9410 4806 9411 4929 9411 4930 9411 4784 9412 4794 9412 4880 9412 4880 9413 4794 9413 4793 9413 4880 9414 4793 9414 4881 9414 4881 9415 4793 9415 4792 9415 4881 9416 4792 9416 4875 9416 4875 9417 4792 9417 4791 9417 4875 9418 4791 9418 4877 9418 4877 9419 4791 9419 4872 9419 4963 9420 4964 9420 4777 9420 4777 9421 4964 9421 4965 9421 4777 9422 4965 9422 4776 9422 4966 9423 4967 9423 4807 9423 4807 9424 4967 9424 4963 9424 4807 9425 4963 9425 4808 9425 4808 9426 4963 9426 4777 9426 4784 9427 4880 9427 4785 9427 4785 9428 4880 9428 4879 9428 4785 9429 4879 9429 4807 9429 4841 9430 4888 9430 4966 9430 4841 9431 4966 9431 4842 9431 4807 9432 4879 9432 4966 9432 4966 9433 4879 9433 4878 9433 4966 9434 4878 9434 4842 9434 4885 9435 4968 9435 4969 9435 4888 9436 4887 9436 4966 9436 4966 9437 4887 9437 4886 9437 4966 9438 4886 9438 4970 9438 4970 9439 4886 9439 4885 9439 4970 9440 4885 9440 4971 9440 4971 9441 4885 9441 4969 9441 4884 9442 4972 9442 4885 9442 4885 9443 4972 9443 4973 9443 4885 9444 4973 9444 4968 9444 4883 9445 4882 9445 4734 9445 4734 9446 4882 9446 4846 9446 4734 9447 4846 9447 4735 9447 4974 9448 4975 9448 4672 9448 4974 9449 4672 9449 4976 9449 4975 9450 4977 9450 4672 9450 4672 9451 4977 9451 4978 9451 4672 9452 4978 9452 4673 9452 4673 9453 4978 9453 4738 9453 4884 9454 4883 9454 4972 9454 4972 9455 4883 9455 4734 9455 4972 9456 4734 9456 4978 9456 4978 9457 4734 9457 4733 9457 4978 9458 4733 9458 4738 9458 4979 9459 4980 9459 4740 9459 4740 9460 4980 9460 4981 9460 4740 9461 4981 9461 4982 9461 4982 9462 4983 9462 4740 9462 4740 9463 4983 9463 4984 9463 4740 9464 4984 9464 4672 9464 4672 9465 4984 9465 4985 9465 4672 9466 4985 9466 4976 9466 4979 9467 4740 9467 4986 9467 4986 9468 4740 9468 4739 9468 4986 9469 4739 9469 4691 9469 4757 9470 4760 9470 4986 9470 4744 9471 4742 9471 4693 9471 4755 9472 4754 9472 4693 9472 4693 9473 4754 9473 4753 9473 4693 9474 4753 9474 4744 9474 4742 9475 4741 9475 4693 9475 4693 9476 4741 9476 4748 9476 4693 9477 4748 9477 4749 9477 4691 9478 4694 9478 4986 9478 4986 9479 4694 9479 4693 9479 4986 9480 4693 9480 4757 9480 4757 9481 4693 9481 4749 9481 4755 9482 4693 9482 4752 9482 4752 9483 4693 9483 4692 9483 4752 9484 4692 9484 4683 9484 4683 9485 4684 9485 4752 9485 4752 9486 4684 9486 4685 9486 4752 9487 4685 9487 4686 9487 4760 9488 4761 9488 4986 9488 4986 9489 4761 9489 4774 9489 4986 9490 4774 9490 4773 9490 4987 9491 4986 9491 4988 9491 4988 9492 4986 9492 4773 9492 4988 9493 4773 9493 4989 9493 4989 9494 4773 9494 4772 9494 4989 9495 4772 9495 4990 9495 4686 9496 4687 9496 4752 9496 4752 9497 4687 9497 4688 9497 4752 9498 4688 9498 4689 9498 4689 9499 4690 9499 4752 9499 4752 9500 4690 9500 4682 9500 4752 9501 4682 9501 4681 9501 4990 9502 4772 9502 4962 9502 4962 9503 4772 9503 4770 9503 4962 9504 4770 9504 4768 9504 699 9505 4406 9505 701 9505 701 9506 4406 9506 4756 9506 4756 9507 4751 9507 701 9507 701 9508 4751 9508 4752 9508 701 9509 4752 9509 661 9509 661 9510 4752 9510 4681 9510 661 9511 4681 9511 662 9511 4735 9512 4846 9512 4736 9512 4736 9513 4846 9513 4847 9513 4736 9514 4847 9514 4737 9514 4737 9515 4847 9515 4848 9515 4737 9516 4848 9516 4845 9516 4845 9517 4844 9517 4737 9517 4737 9518 4844 9518 4843 9518 4737 9519 4843 9519 4852 9519 4732 9520 4731 9520 4851 9520 4851 9521 4731 9521 4730 9521 4851 9522 4730 9522 4852 9522 4852 9523 4730 9523 4729 9523 4852 9524 4729 9524 4737 9524 4862 9525 4861 9525 4726 9525 4726 9526 4861 9526 4860 9526 4726 9527 4860 9527 4727 9527 4727 9528 4860 9528 4859 9528 4727 9529 4859 9529 4864 9529 4851 9530 4850 9530 4732 9530 4732 9531 4850 9531 4849 9531 4732 9532 4849 9532 4728 9532 4728 9533 4849 9533 4858 9533 4728 9534 4858 9534 4675 9534 4675 9535 4858 9535 4857 9535 4675 9536 4857 9536 4856 9536 4856 9537 4855 9537 4675 9537 4675 9538 4855 9538 4854 9538 4675 9539 4854 9539 4676 9539 4676 9540 4854 9540 4853 9540 4676 9541 4853 9541 4725 9541 4725 9542 4853 9542 4726 9542 4726 9543 4853 9543 4863 9543 4726 9544 4863 9544 4862 9544 4573 9545 4572 9545 4533 9545 4551 9546 4550 9546 4581 9546 4991 9547 4533 9547 4992 9547 4992 9548 4533 9548 4993 9548 4566 9549 4551 9549 4533 9549 4598 9550 4585 9550 4533 9550 4587 9551 4619 9551 4635 9551 4635 9552 4634 9552 4587 9552 4587 9553 4634 9553 4638 9553 4587 9554 4638 9554 4637 9554 4991 9555 4994 9555 4533 9555 4533 9556 4994 9556 4995 9556 4533 9557 4995 9557 4557 9557 4920 9558 4908 9558 4529 9558 4529 9559 4908 9559 4907 9559 4529 9560 4907 9560 4924 9560 4924 9561 4926 9561 4529 9561 4529 9562 4926 9562 4906 9562 4529 9563 4906 9563 4894 9563 4648 9564 4900 9564 4910 9564 4996 9565 4997 9565 4533 9565 4533 9566 4997 9566 4998 9566 4598 9567 4533 9567 4582 9567 4585 9568 4588 9568 4533 9568 4533 9569 4588 9569 4586 9569 4533 9570 4586 9570 4531 9570 4531 9571 4586 9571 4587 9571 4531 9572 4587 9572 4529 9572 4533 9573 4778 9573 4999 9573 4998 9574 5000 9574 4533 9574 4533 9575 5000 9575 5001 9575 4533 9576 5001 9576 4993 9576 4574 9577 4575 9577 4533 9577 4533 9578 4575 9578 4576 9578 4533 9579 4576 9579 4573 9579 4910 9580 4911 9580 4529 9580 4529 9581 4911 9581 4918 9581 4572 9582 4571 9582 4533 9582 4533 9583 4571 9583 4570 9583 4533 9584 4570 9584 4569 9584 4551 9585 4581 9585 4533 9585 4533 9586 4581 9586 4584 9586 4533 9587 4584 9587 4589 9587 4624 9588 4619 9588 4625 9588 4625 9589 4619 9589 4626 9589 4624 9590 4623 9590 4619 9590 4619 9591 4623 9591 4622 9591 4619 9592 4622 9592 4618 9592 4637 9593 4643 9593 4587 9593 4587 9594 4643 9594 4642 9594 4587 9595 4642 9595 4640 9595 4529 9596 4587 9596 4910 9596 4910 9597 4587 9597 4644 9597 4910 9598 4644 9598 4648 9598 4557 9599 4556 9599 4533 9599 4533 9600 4556 9600 4580 9600 4533 9601 4580 9601 4579 9601 4918 9602 4916 9602 4529 9602 4529 9603 4916 9603 4915 9603 4529 9604 4915 9604 4914 9604 4914 9605 4922 9605 4529 9605 4529 9606 4922 9606 4921 9606 4529 9607 4921 9607 4920 9607 4569 9608 4568 9608 4533 9608 4533 9609 4568 9609 4567 9609 4533 9610 4567 9610 4566 9610 4596 9611 4595 9611 4533 9611 4533 9612 4595 9612 4583 9612 4533 9613 4583 9613 4582 9613 4629 9614 4628 9614 4619 9614 4619 9615 4628 9615 4627 9615 4619 9616 4627 9616 4626 9616 5002 9617 5003 9617 4533 9617 5004 9618 5005 9618 4533 9618 4533 9619 5005 9619 5006 9619 4533 9620 5006 9620 4996 9620 4579 9621 4578 9621 4533 9621 4533 9622 4578 9622 4577 9622 4533 9623 4577 9623 4574 9623 4533 9624 4592 9624 4593 9624 4602 9625 4610 9625 4587 9625 4587 9626 4610 9626 4631 9626 4587 9627 4631 9627 4619 9627 4619 9628 4631 9628 4630 9628 4619 9629 4630 9629 4629 9629 4622 9630 4621 9630 4618 9630 4618 9631 4621 9631 4620 9631 4618 9632 4620 9632 4617 9632 4617 9633 4620 9633 4616 9633 4640 9634 4639 9634 4587 9634 4587 9635 4639 9635 4645 9635 4587 9636 4645 9636 4644 9636 5003 9637 5007 9637 4533 9637 4533 9638 5007 9638 5008 9638 4533 9639 5008 9639 5004 9639 4589 9640 4590 9640 4533 9640 4533 9641 4590 9641 4591 9641 4533 9642 4591 9642 4592 9642 4593 9643 4594 9643 4533 9643 4533 9644 4594 9644 4597 9644 4533 9645 4597 9645 4596 9645 4999 9646 5009 9646 4533 9646 4533 9647 5009 9647 5010 9647 4533 9648 5010 9648 5011 9648 5011 9649 5012 9649 4533 9649 4533 9650 5012 9650 5013 9650 4533 9651 5013 9651 5014 9651 5014 9652 5015 9652 4533 9652 4533 9653 5015 9653 5016 9653 4533 9654 5016 9654 5002 9654 4497 9655 587 9655 4499 9655 4499 9656 587 9656 4500 9656 4506 9657 4509 9657 587 9657 587 9658 4509 9658 4508 9658 587 9659 4508 9659 588 9659 4497 9660 4496 9660 587 9660 587 9661 4496 9661 4527 9661 587 9662 4527 9662 4503 9662 4503 9663 4502 9663 587 9663 587 9664 4502 9664 4504 9664 587 9665 4504 9665 4506 9665 4999 9666 5017 9666 5018 9666 4983 9667 5019 9667 4984 9667 5020 9668 5021 9668 5022 9668 5022 9669 5021 9669 5023 9669 5022 9670 5023 9670 5024 9670 5025 9671 5026 9671 5027 9671 5027 9672 5026 9672 5028 9672 5027 9673 5028 9673 5029 9673 5030 9674 5031 9674 5020 9674 5020 9675 5031 9675 5032 9675 5020 9676 5032 9676 5021 9676 5033 9677 5034 9677 5035 9677 5033 9678 4979 9678 4986 9678 4987 9679 5036 9679 4986 9679 4986 9680 5036 9680 5037 9680 4986 9681 5037 9681 5033 9681 5033 9682 5037 9682 5038 9682 5033 9683 5038 9683 5034 9683 4979 9684 5033 9684 4980 9684 4980 9685 5033 9685 5039 9685 4980 9686 5039 9686 4981 9686 5019 9687 4983 9687 5039 9687 5039 9688 4983 9688 4982 9688 5039 9689 4982 9689 4981 9689 4985 9690 5040 9690 4976 9690 4976 9691 5040 9691 5041 9691 4978 9692 4977 9692 5042 9692 5042 9693 4977 9693 4975 9693 5042 9694 4975 9694 5041 9694 5041 9695 4975 9695 4974 9695 5041 9696 4974 9696 4976 9696 4969 9697 4968 9697 5043 9697 5043 9698 4968 9698 4973 9698 5043 9699 4973 9699 5042 9699 5042 9700 4973 9700 4972 9700 5042 9701 4972 9701 4978 9701 4967 9702 4966 9702 5018 9702 5018 9703 4966 9703 4970 9703 5018 9704 4970 9704 5044 9704 4967 9705 5018 9705 4963 9705 4963 9706 5018 9706 5017 9706 4963 9707 5017 9707 4964 9707 4964 9708 5017 9708 4965 9708 4965 9709 5017 9709 4775 9709 4965 9710 4775 9710 4776 9710 4999 9711 4778 9711 4779 9711 4999 9712 4779 9712 5017 9712 5017 9713 4779 9713 4780 9713 5017 9714 4780 9714 4775 9714 5045 9715 5012 9715 5011 9715 5045 9716 5011 9716 5044 9716 5044 9717 5011 9717 5010 9717 5044 9718 5010 9718 5018 9718 5018 9719 5010 9719 5009 9719 5018 9720 5009 9720 4999 9720 5012 9721 5045 9721 5013 9721 5013 9722 5045 9722 5046 9722 5013 9723 5046 9723 5014 9723 5047 9724 5002 9724 5048 9724 5048 9725 5002 9725 5016 9725 5048 9726 5016 9726 5046 9726 5046 9727 5016 9727 5015 9727 5046 9728 5015 9728 5014 9728 5004 9729 5008 9729 5027 9729 5027 9730 5008 9730 5007 9730 5027 9731 5007 9731 5047 9731 5047 9732 5007 9732 5003 9732 5047 9733 5003 9733 5002 9733 5029 9734 5049 9734 5027 9734 5027 9735 5049 9735 5050 9735 5027 9736 5050 9736 5004 9736 5004 9737 5050 9737 5051 9737 5004 9738 5051 9738 5005 9738 5035 9739 5030 9739 5033 9739 5033 9740 5030 9740 5020 9740 5033 9741 5020 9741 5039 9741 5039 9742 5020 9742 5022 9742 5039 9743 5022 9743 5019 9743 5019 9744 5022 9744 5040 9744 5019 9745 5040 9745 4984 9745 4984 9746 5040 9746 4985 9746 5024 9747 5025 9747 5022 9747 5022 9748 5025 9748 5027 9748 5022 9749 5027 9749 5040 9749 5040 9750 5027 9750 5047 9750 5040 9751 5047 9751 5041 9751 5041 9752 5047 9752 5048 9752 5041 9753 5048 9753 5042 9753 5042 9754 5048 9754 5046 9754 5042 9755 5046 9755 5043 9755 5043 9756 5046 9756 5045 9756 5043 9757 5045 9757 4969 9757 4969 9758 5045 9758 5044 9758 4969 9759 5044 9759 4971 9759 4971 9760 5044 9760 4970 9760 4962 9761 4767 9761 5052 9761 5053 9762 4987 9762 4988 9762 5054 9763 5055 9763 5056 9763 5056 9764 5053 9764 5054 9764 5054 9765 5053 9765 4988 9765 5054 9766 4988 9766 5057 9766 5057 9767 4988 9767 4989 9767 5057 9768 4989 9768 5058 9768 5058 9769 4989 9769 5052 9769 5052 9770 4989 9770 4990 9770 5052 9771 4990 9771 4962 9771 4403 9772 699 9772 4405 9772 4405 9773 699 9773 698 9773 4429 9774 4427 9774 699 9774 4403 9775 4402 9775 699 9775 699 9776 4402 9776 4425 9776 699 9777 4425 9777 4424 9777 4424 9778 4391 9778 699 9778 699 9779 4391 9779 4390 9779 699 9780 4390 9780 4429 9780 4427 9781 4394 9781 699 9781 699 9782 4394 9782 4393 9782 699 9783 4393 9783 4406 9783 5059 9784 5060 9784 5061 9784 5006 9785 5062 9785 5063 9785 4352 9786 5064 9786 4353 9786 4353 9787 5064 9787 4354 9787 3505 9788 4554 9788 4358 9788 4358 9789 4554 9789 5064 9789 4358 9790 5064 9790 4351 9790 4351 9791 5064 9791 4352 9791 5065 9792 4356 9792 5064 9792 5064 9793 4356 9793 4355 9793 5064 9794 4355 9794 4354 9794 5066 9795 4346 9795 5067 9795 5067 9796 4346 9796 4350 9796 5067 9797 4350 9797 5065 9797 5065 9798 4350 9798 4357 9798 5065 9799 4357 9799 4356 9799 4343 9800 4338 9800 5068 9800 4338 9801 4337 9801 5068 9801 5068 9802 4337 9802 4348 9802 5068 9803 4348 9803 5066 9803 5066 9804 4348 9804 4347 9804 5066 9805 4347 9805 4346 9805 4998 9806 4997 9806 5063 9806 5063 9807 4997 9807 4996 9807 5063 9808 4996 9808 5006 9808 4992 9809 4993 9809 5069 9809 5069 9810 4993 9810 5070 9810 4553 9811 4555 9811 5071 9811 5071 9812 4555 9812 4557 9812 4557 9813 4995 9813 5071 9813 5071 9814 4995 9814 4994 9814 5071 9815 4994 9815 5069 9815 5069 9816 4994 9816 4991 9816 5069 9817 4991 9817 4992 9817 5059 9818 5061 9818 5072 9818 5062 9819 5072 9819 5063 9819 5063 9820 5072 9820 5061 9820 5063 9821 5061 9821 4998 9821 4998 9822 5061 9822 5073 9822 4998 9823 5073 9823 5000 9823 5000 9824 5073 9824 5070 9824 5000 9825 5070 9825 5001 9825 5001 9826 5070 9826 4993 9826 4342 9827 4343 9827 5074 9827 5074 9828 4343 9828 5068 9828 5074 9829 5068 9829 5075 9829 5075 9830 5068 9830 5076 9830 4554 9831 4553 9831 5064 9831 5064 9832 4553 9832 5071 9832 5064 9833 5071 9833 5065 9833 5065 9834 5071 9834 5069 9834 5065 9835 5069 9835 5067 9835 5067 9836 5069 9836 5070 9836 5067 9837 5070 9837 5066 9837 5066 9838 5070 9838 5073 9838 5066 9839 5073 9839 5068 9839 5068 9840 5073 9840 5061 9840 5068 9841 5061 9841 5076 9841 5076 9842 5061 9842 5060 9842 5029 9843 5028 9843 5077 9843 5077 9844 5025 9844 5024 9844 5026 9845 5025 9845 5077 9845 5028 9846 5026 9846 5077 9846 5078 9847 5049 9847 5079 9847 5079 9848 5049 9848 5029 9848 5079 9849 5029 9849 5077 9849 5005 9850 5051 9850 5078 9850 5078 9851 5051 9851 5050 9851 5078 9852 5050 9852 5049 9852 4767 9853 3987 9853 5052 9853 5052 9854 3987 9854 3986 9854 3986 9855 3985 9855 5052 9855 5052 9856 3985 9856 3984 9856 5052 9857 3984 9857 3983 9857 5057 9858 5058 9858 3989 9858 3989 9859 5058 9859 5052 9859 3989 9860 5052 9860 3988 9860 3988 9861 5052 9861 3983 9861 4769 9862 3979 9862 4767 9862 4767 9863 3979 9863 3978 9863 4767 9864 3978 9864 3987 9864 3973 9865 3972 9865 4771 9865 4771 9866 3972 9866 3982 9866 4771 9867 3982 9867 4769 9867 4769 9868 3982 9868 3981 9868 4769 9869 3981 9869 3980 9869 3980 9870 3976 9870 4769 9870 4769 9871 3976 9871 3975 9871 4769 9872 3975 9872 3979 9872 4771 9873 4763 9873 3973 9873 3973 9874 4763 9874 4765 9874 3973 9875 4765 9875 4766 9875 3922 9876 3973 9876 3919 9876 3919 9877 3973 9877 4766 9877 3919 9878 4766 9878 3920 9878 3922 9879 3936 9879 3973 9879 3973 9880 3936 9880 3935 9880 3973 9881 3935 9881 3934 9881 3965 9882 3964 9882 3934 9882 3934 9883 3964 9883 3969 9883 3969 9884 3971 9884 3934 9884 3934 9885 3971 9885 3974 9885 3934 9886 3974 9886 3973 9886 3933 9887 3932 9887 3952 9887 3952 9888 3932 9888 3941 9888 3941 9889 3946 9889 3952 9889 3952 9890 3946 9890 3945 9890 3952 9891 3945 9891 3943 9891 3952 9892 3968 9892 3933 9892 3933 9893 3968 9893 3967 9893 3933 9894 3967 9894 3934 9894 3934 9895 3967 9895 3966 9895 3934 9896 3966 9896 3965 9896 2776 9897 3958 9897 3937 9897 3937 9898 3958 9898 3957 9898 3937 9899 3957 9899 3938 9899 3957 9900 3956 9900 3938 9900 3938 9901 3956 9901 3955 9901 3938 9902 3955 9902 3947 9902 3947 9903 3955 9903 3942 9903 3942 9904 3955 9904 3959 9904 3942 9905 3959 9905 3960 9905 3960 9906 3961 9906 3942 9906 3942 9907 3961 9907 3962 9907 3942 9908 3962 9908 3943 9908 3943 9909 3962 9909 3953 9909 3943 9910 3953 9910 3952 9910 5057 9911 3989 9911 5054 9911 5054 9912 3989 9912 3378 9912 5054 9913 3378 9913 5055 9913 5055 9914 3378 9914 4344 9914 5055 9915 4344 9915 4345 9915 4345 9916 4341 9916 5055 9916 5055 9917 4341 9917 4340 9917 5055 9918 4340 9918 4342 9918 5080 9919 5081 9919 5082 9919 5082 9920 5083 9920 5084 9920 5084 9921 5083 9921 5085 9921 5085 9922 5086 9922 5084 9922 5084 9923 5086 9923 5087 9923 5084 9924 5087 9924 5088 9924 5089 9925 5080 9925 5090 9925 5090 9926 5080 9926 5082 9926 5090 9927 5082 9927 5091 9927 5091 9928 5082 9928 5084 9928 616 9929 614 9929 5087 9929 602 9930 601 9930 5088 9930 599 9931 598 9931 5084 9931 5088 9932 601 9932 5084 9932 5084 9933 601 9933 600 9933 5084 9934 600 9934 599 9934 598 9935 597 9935 5084 9935 5084 9936 597 9936 595 9936 5084 9937 595 9937 5091 9937 5091 9938 595 9938 527 9938 5091 9939 527 9939 526 9939 614 9940 612 9940 5087 9940 5087 9941 612 9941 605 9941 5087 9942 605 9942 5088 9942 5088 9943 605 9943 603 9943 5088 9944 603 9944 602 9944 5086 9945 622 9945 620 9945 5086 9946 620 9946 5087 9946 5087 9947 620 9947 618 9947 5087 9948 618 9948 616 9948 626 9949 5085 9949 627 9949 627 9950 5085 9950 628 9950 626 9951 608 9951 5085 9951 5085 9952 608 9952 607 9952 5085 9953 607 9953 5086 9953 5086 9954 607 9954 610 9954 5086 9955 610 9955 622 9955 628 9956 5085 9956 625 9956 625 9957 5085 9957 5083 9957 625 9958 5083 9958 629 9958 708 9959 635 9959 5082 9959 5082 9960 635 9960 633 9960 5082 9961 633 9961 5083 9961 5083 9962 633 9962 632 9962 5083 9963 632 9963 629 9963 711 9964 724 9964 5081 9964 724 9965 723 9965 5081 9965 5081 9966 723 9966 725 9966 5081 9967 725 9967 5082 9967 5082 9968 725 9968 709 9968 5082 9969 709 9969 708 9969 716 9970 5080 9970 727 9970 727 9971 5080 9971 733 9971 716 9972 714 9972 5080 9972 5080 9973 714 9973 713 9973 5080 9974 713 9974 5081 9974 5081 9975 713 9975 712 9975 5081 9976 712 9976 711 9976 505 9977 5080 9977 508 9977 508 9978 5080 9978 5089 9978 505 9979 498 9979 5080 9979 5080 9980 498 9980 503 9980 5080 9981 503 9981 733 9981 511 9982 510 9982 5089 9982 5089 9983 510 9983 509 9983 5089 9984 509 9984 508 9984 513 9985 520 9985 5090 9985 5090 9986 520 9986 519 9986 5090 9987 519 9987 5089 9987 5089 9988 519 9988 512 9988 5089 9989 512 9989 511 9989 526 9990 524 9990 5091 9990 5091 9991 524 9991 523 9991 5091 9992 523 9992 5090 9992 5090 9993 523 9993 514 9993 5090 9994 514 9994 513 9994 4133 9995 5092 9995 4134 9995 5092 9996 4133 9996 4132 9996 4114 9997 4134 9997 5092 9997 4131 9998 4130 9998 5092 9998 5092 9999 4130 9999 4129 9999 5093 10000 5092 10000 5094 10000 573 10001 4468 10001 4092 10001 4092 10002 4468 10002 4469 10002 4092 10003 4469 10003 4091 10003 4091 10004 4469 10004 4471 10004 4091 10005 4471 10005 5094 10005 5094 10006 4471 10006 5095 10006 5094 10007 5095 10007 5093 10007 4124 10008 4123 10008 5094 10008 5094 10009 4123 10009 4122 10009 5094 10010 4122 10010 4091 10010 5092 10011 4128 10011 4125 10011 4124 10012 5094 10012 4125 10012 4125 10013 5094 10013 5092 10013 4129 10014 4128 10014 5092 10014 4132 10015 4131 10015 5092 10015 5092 10016 4117 10016 4115 10016 4115 10017 4114 10017 5092 10017 5096 10018 4117 10018 5092 10018 5096 10019 5097 10019 4117 10019 4117 10020 5097 10020 5098 10020 4117 10021 5098 10021 4118 10021 4118 10022 5098 10022 5099 10022 4118 10023 5099 10023 4121 10023 4471 10024 3779 10024 4165 10024 4471 10025 4165 10025 5095 10025 5095 10026 4165 10026 4164 10026 5095 10027 4164 10027 5093 10027 4164 10028 4163 10028 5093 10028 5093 10029 4163 10029 4162 10029 5093 10030 4162 10030 5092 10030 5092 10031 4162 10031 4149 10031 5092 10032 4149 10032 5096 10032 5096 10033 4149 10033 4148 10033 5096 10034 4148 10034 5097 10034 5097 10035 4148 10035 4153 10035 5097 10036 4153 10036 5098 10036 5098 10037 4153 10037 4152 10037 5098 10038 4152 10038 5099 10038 5099 10039 4152 10039 4146 10039 5099 10040 4146 10040 4121 10040 5006 10041 5005 10041 5062 10041 5062 10042 5005 10042 5078 10042 5062 10043 5078 10043 5072 10043 5072 10044 5078 10044 5079 10044 5072 10045 5079 10045 5059 10045 5059 10046 5079 10046 5077 10046 5059 10047 5077 10047 5060 10047 5060 10048 5077 10048 5100 10048 5060 10049 5100 10049 5076 10049 5076 10050 5100 10050 5101 10050 5076 10051 5101 10051 5075 10051 5075 10052 5101 10052 5102 10052 5075 10053 5102 10053 5074 10053 5074 10054 5102 10054 5103 10054 5074 10055 5103 10055 4342 10055 4342 10056 5103 10056 5055 10056 5023 10057 5021 10057 5077 10057 5032 10058 5031 10058 5077 10058 5034 10059 5104 10059 5035 10059 5102 10060 5101 10060 5104 10060 5104 10061 5101 10061 5100 10061 5104 10062 5100 10062 5077 10062 5102 10063 5104 10063 5103 10063 5103 10064 5104 10064 5034 10064 5103 10065 5034 10065 5055 10065 5034 10066 5038 10066 5055 10066 5055 10067 5038 10067 5037 10067 5055 10068 5037 10068 5056 10068 5056 10069 5037 10069 5036 10069 5056 10070 5036 10070 5053 10070 5053 10071 5036 10071 4987 10071 5077 10072 5031 10072 5104 10072 5104 10073 5031 10073 5030 10073 5104 10074 5030 10074 5035 10074 5021 10075 5032 10075 5077 10075 5024 10076 5023 10076 5077 10076

+
+
+ 1 +
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_collision_E2M3.dae b/URDFs/sr_description/meshes/components/forearm/forearm_collision_E2M3.dae new file mode 100644 index 0000000..21a916f --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_collision_E2M3.dae @@ -0,0 +1,93 @@ + + + + + + Blender User + Blender 2.82.7 + + 2022-03-18T07:49:55 + 2022-03-18T07:49:55 + + Z_UP + + + + + + + 0 1 0 0 1 2 0.1950903 0.9807853 0 0.1950903 0.9807853 2 0.3826835 0.9238795 0 0.3826835 0.9238795 2 0.5555703 0.8314696 0 0.5555703 0.8314696 2 0.7071068 0.7071068 0 0.7071068 0.7071068 2 0.8314697 0.5555702 0 0.8314697 0.5555702 2 0.9238795 0.3826834 0 0.9238795 0.3826834 2 0.9807853 0.1950903 0 0.9807853 0.1950903 2 1 0 0 1 0 2 0.9807853 -0.1950902 0 0.9807853 -0.1950902 2 0.9238796 -0.3826833 0 0.9238796 -0.3826833 2 0.8314697 -0.5555702 0 0.8314697 -0.5555702 2 0.7071068 -0.7071068 0 0.7071068 -0.7071068 2 0.5555702 -0.8314697 0 0.5555702 -0.8314697 2 0.3826833 -0.9238796 0 0.3826833 -0.9238796 2 0.1950901 -0.9807853 0 0.1950901 -0.9807853 2 -3.25841e-7 -1 0 -3.25841e-7 -1 2 -0.1950907 -0.9807852 0 -0.1950907 -0.9807852 2 -0.3826839 -0.9238793 0 -0.3826839 -0.9238793 2 -0.5555707 -0.8314693 0 -0.5555707 -0.8314693 2 -0.7071073 -0.7071063 0 -0.7071073 -0.7071063 2 -0.83147 -0.5555697 0 -0.83147 -0.5555697 2 -0.9238799 -0.3826827 0 -0.9238799 -0.3826827 2 -0.9807854 -0.1950894 0 -0.9807854 -0.1950894 2 -1 9.65599e-7 0 -1 9.65599e-7 2 -0.9807851 0.1950913 0 -0.9807851 0.1950913 2 -0.9238791 0.3826845 0 -0.9238791 0.3826845 2 -0.8314689 0.5555713 0 -0.8314689 0.5555713 2 -0.7071059 0.7071077 0 -0.7071059 0.7071077 2 -0.5555691 0.8314704 0 -0.5555691 0.8314704 2 -0.3826821 0.9238801 0 -0.3826821 0.9238801 2 -0.1950888 0.9807856 0 -0.1950888 0.9807856 2 + + + + + + + + + + 0.09801727 0.9951847 0 0.2902846 0.9569405 0 0.4713967 0.8819213 0 0.6343935 0.7730103 0 0.7730106 0.6343932 0 0.8819215 0.4713966 0 0.9569404 0.2902848 0 0.9951847 0.09801727 0 0.9951848 -0.09801667 0 0.9569404 -0.2902848 0 0.8819214 -0.4713968 0 0.7730103 -0.6343936 0 0.6343934 -0.7730104 0 0.4713968 -0.8819214 0 0.2902842 -0.9569405 0 0.09801691 -0.9951848 0 -0.09801757 -0.9951848 0 -0.2902852 -0.9569402 0 -0.4713971 -0.8819211 0 -0.6343941 -0.77301 0 -0.7730107 -0.634393 0 -0.8819217 -0.4713961 0 -0.9569407 -0.2902834 0 -0.9951849 -0.09801602 0 -0.9951847 0.09801787 0 -0.95694 0.2902858 0 -0.8819208 0.4713979 0 -0.7730096 0.6343944 0 -0.6343926 0.7730111 0 -0.4713955 0.881922 0 0 0 1 -0.2902831 0.9569408 0 -0.0980165 0.9951848 0 0 0 -1 0.2902847 0.9569404 0 0.6343932 0.7730106 0 0.7730103 0.6343936 0 0.9951847 -0.09801727 0 0.8819216 -0.4713962 0 0.7730106 -0.6343932 0 0.2902843 -0.9569405 0 -0.2902852 -0.9569402 0 -0.6343938 -0.7730101 0 -0.773011 -0.6343927 0 -0.9569405 -0.2902839 0 -0.9951848 -0.09801661 0 -0.9951846 0.09801846 0 -0.881921 0.4713975 0 -0.6343923 0.7730113 0 0 0 1 -7.95023e-6 0 1 7.95024e-6 0 1 2.87406e-6 0 1 -1.55543e-6 0 1 -5.75593e-7 0 1 -0.290283 0.9569408 0 + + + + + + + + + + 1 1 0.96875 0.5 1 0.5 0.96875 1 0.9375 0.5 0.96875 0.5 0.9375 1 0.90625 0.5 0.9375 0.5 0.90625 1 0.875 0.5 0.90625 0.5 0.875 1 0.84375 0.5 0.875 0.5 0.84375 1 0.8125 0.5 0.84375 0.5 0.8125 1 0.78125 0.5 0.8125 0.5 0.78125 1 0.75 0.5 0.78125 0.5 0.75 1 0.71875 0.5 0.75 0.5 0.71875 1 0.6875 0.5 0.71875 0.5 0.6875 1 0.65625 0.5 0.6875 0.5 0.65625 1 0.625 0.5 0.65625 0.5 0.625 1 0.59375 0.5 0.625 0.5 0.59375 1 0.5625 0.5 0.59375 0.5 0.5625 1 0.53125 0.5 0.5625 0.5 0.53125 1 0.5 0.5 0.53125 0.5 0.5 1 0.46875 0.5 0.5 0.5 0.46875 1 0.4375 0.5 0.46875 0.5 0.4375 1 0.40625 0.5 0.4375 0.5 0.40625 1 0.375 0.5 0.40625 0.5 0.375 1 0.34375 0.5 0.375 0.5 0.34375 1 0.3125 0.5 0.34375 0.5 0.3125 1 0.28125 0.5 0.3125 0.5 0.28125 1 0.25 0.5 0.28125 0.5 0.25 1 0.21875 0.5 0.25 0.5 0.21875 1 0.1875 0.5 0.21875 0.5 0.1875 1 0.15625 0.5 0.1875 0.5 0.15625 1 0.125 0.5 0.15625 0.5 0.125 1 0.09375 0.5 0.125 0.5 0.09375 1 0.0625 0.5 0.09375 0.5 0.02826899 0.3418443 0.1581559 0.02826893 0.4717311 0.158156 0.0625 1 0.03125 0.5 0.0625 0.5 0.03125 1 0 0.5 0.03125 0.5 0.9853885 0.2968217 0.7968216 0.01461148 0.5146115 0.2031785 1 1 0.96875 1 0.96875 0.5 0.96875 1 0.9375 1 0.9375 0.5 0.9375 1 0.90625 1 0.90625 0.5 0.90625 1 0.875 1 0.875 0.5 0.875 1 0.84375 1 0.84375 0.5 0.84375 1 0.8125 1 0.8125 0.5 0.8125 1 0.78125 1 0.78125 0.5 0.78125 1 0.75 1 0.75 0.5 0.75 1 0.71875 1 0.71875 0.5 0.71875 1 0.6875 1 0.6875 0.5 0.6875 1 0.65625 1 0.65625 0.5 0.65625 1 0.625 1 0.625 0.5 0.625 1 0.59375 1 0.59375 0.5 0.59375 1 0.5625 1 0.5625 0.5 0.5625 1 0.53125 1 0.53125 0.5 0.53125 1 0.5 1 0.5 0.5 0.5 1 0.46875 1 0.46875 0.5 0.46875 1 0.4375 1 0.4375 0.5 0.4375 1 0.40625 1 0.40625 0.5 0.40625 1 0.375 1 0.375 0.5 0.375 1 0.34375 1 0.34375 0.5 0.34375 1 0.3125 1 0.3125 0.5 0.3125 1 0.28125 1 0.28125 0.5 0.28125 1 0.25 1 0.25 0.5 0.25 1 0.21875 1 0.21875 0.5 0.21875 1 0.1875 1 0.1875 0.5 0.1875 1 0.15625 1 0.15625 0.5 0.15625 1 0.125 1 0.125 0.5 0.125 1 0.09375 1 0.09375 0.5 0.09375 1 0.0625 1 0.0625 0.5 0.341844 0.4717311 0.2968217 0.4853885 0.25 0.49 0.25 0.49 0.2031787 0.4853885 0.341844 0.4717311 0.2031787 0.4853885 0.1581563 0.4717312 0.341844 0.4717311 0.1581563 0.4717312 0.1166634 0.4495529 0.08029454 0.4197058 0.08029454 0.4197058 0.05044746 0.3833371 0.02826899 0.3418443 0.02826899 0.3418443 0.01461154 0.2968219 0.00999999 0.2500002 0.00999999 0.2500002 0.01461148 0.2031785 0.02826899 0.3418443 0.01461148 0.2031785 0.02826881 0.1581561 0.02826899 0.3418443 0.02826881 0.1581561 0.05044716 0.1166633 0.08029425 0.08029448 0.08029425 0.08029448 0.116663 0.05044734 0.1581559 0.02826893 0.1581559 0.02826893 0.2031782 0.01461154 0.2499999 0.00999999 0.2499999 0.00999999 0.2968216 0.01461148 0.341844 0.02826887 0.341844 0.02826887 0.3833369 0.05044728 0.4197056 0.08029437 0.4197056 0.08029437 0.4495527 0.1166631 0.4717311 0.158156 0.4717311 0.158156 0.4853885 0.2031783 0.49 0.25 0.49 0.25 0.4853885 0.2968217 0.4717311 0.158156 0.4853885 0.2968217 0.4717311 0.341844 0.4717311 0.158156 0.4717311 0.341844 0.4495527 0.3833369 0.4197056 0.4197056 0.4197056 0.4197056 0.3833369 0.4495527 0.341844 0.4717311 0.1581563 0.4717312 0.08029454 0.4197058 0.341844 0.4717311 0.08029454 0.4197058 0.02826899 0.3418443 0.341844 0.4717311 0.02826881 0.1581561 0.08029425 0.08029448 0.1581559 0.02826893 0.1581559 0.02826893 0.2499999 0.00999999 0.4717311 0.158156 0.2499999 0.00999999 0.341844 0.02826887 0.4717311 0.158156 0.341844 0.02826887 0.4197056 0.08029437 0.4717311 0.158156 0.4717311 0.341844 0.4197056 0.4197056 0.4717311 0.158156 0.4197056 0.4197056 0.341844 0.4717311 0.4717311 0.158156 0.02826899 0.3418443 0.02826881 0.1581561 0.1581559 0.02826893 0.341844 0.4717311 0.02826899 0.3418443 0.4717311 0.158156 0.0625 1 0.03125 1 0.03125 0.5 0.03125 1 0 1 0 0.5 0.7031787 0.4853885 0.75 0.49 0.7968217 0.4853885 0.7968217 0.4853885 0.841844 0.4717311 0.8833369 0.4495527 0.8833369 0.4495527 0.9197056 0.4197056 0.9495527 0.3833369 0.9495527 0.3833369 0.9717311 0.341844 0.8833369 0.4495527 0.9717311 0.341844 0.9853885 0.2968217 0.8833369 0.4495527 0.9853885 0.2968217 0.99 0.25 0.9853885 0.2031783 0.9853885 0.2031783 0.9717311 0.158156 0.9853885 0.2968217 0.9717311 0.158156 0.9495527 0.1166631 0.9853885 0.2968217 0.9495527 0.1166631 0.9197056 0.08029437 0.7968216 0.01461148 0.9197056 0.08029437 0.8833369 0.05044728 0.7968216 0.01461148 0.8833369 0.05044728 0.841844 0.02826887 0.7968216 0.01461148 0.7968216 0.01461148 0.75 0.00999999 0.7031782 0.01461154 0.7031782 0.01461154 0.6581559 0.02826893 0.616663 0.05044734 0.616663 0.05044734 0.5802943 0.08029448 0.5146115 0.2031785 0.5802943 0.08029448 0.5504472 0.1166633 0.5146115 0.2031785 0.5504472 0.1166633 0.5282688 0.1581561 0.5146115 0.2031785 0.5146115 0.2031785 0.51 0.2500002 0.5146116 0.2968219 0.5146116 0.2968219 0.5282691 0.3418443 0.5504475 0.3833371 0.5504475 0.3833371 0.5802946 0.4197058 0.6166634 0.4495529 0.6166634 0.4495529 0.6581563 0.4717312 0.7031787 0.4853885 0.7031787 0.4853885 0.7968217 0.4853885 0.8833369 0.4495527 0.7968216 0.01461148 0.7031782 0.01461154 0.5146115 0.2031785 0.7031782 0.01461154 0.616663 0.05044734 0.5146115 0.2031785 0.5146115 0.2031785 0.5146116 0.2968219 0.7031787 0.4853885 0.5146116 0.2968219 0.5504475 0.3833371 0.7031787 0.4853885 0.5504475 0.3833371 0.6166634 0.4495529 0.7031787 0.4853885 0.7031787 0.4853885 0.8833369 0.4495527 0.9853885 0.2968217 0.9853885 0.2968217 0.9495527 0.1166631 0.7968216 0.01461148 0.7031787 0.4853885 0.9853885 0.2968217 0.5146115 0.2031785 + + + + + + + + + + + + + + +

1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 29 14 42 30 14 43 28 14 44 31 15 45 32 15 46 30 15 47 33 16 48 34 16 49 32 16 50 35 17 51 36 17 52 34 17 53 37 18 54 38 18 55 36 18 56 39 19 57 40 19 58 38 19 59 41 20 60 42 20 61 40 20 62 43 21 63 44 21 64 42 21 65 45 22 66 46 22 67 44 22 68 47 23 69 48 23 70 46 23 71 49 24 72 50 24 73 48 24 74 51 25 75 52 25 76 50 25 77 53 26 78 54 26 79 52 26 80 55 27 81 56 27 82 54 27 83 57 28 84 58 28 85 56 28 86 59 29 87 60 29 88 58 29 89 53 30 90 37 30 91 21 30 92 61 31 93 62 31 94 60 31 95 63 32 96 0 32 97 62 32 98 14 33 99 30 33 100 46 33 101 1 0 102 3 0 103 2 0 104 3 34 105 5 34 106 4 34 107 5 2 108 7 2 109 6 2 110 7 35 111 9 35 112 8 35 113 9 36 114 11 36 115 10 36 116 11 5 117 13 5 118 12 5 119 13 6 120 15 6 121 14 6 122 15 7 123 17 7 124 16 7 125 17 37 126 19 37 127 18 37 128 19 9 129 21 9 130 20 9 131 21 38 132 23 38 133 22 38 134 23 39 135 25 39 136 24 39 137 25 12 138 27 12 139 26 12 140 27 13 141 29 13 142 28 13 143 29 40 144 31 40 145 30 40 146 31 15 147 33 15 148 32 15 149 33 16 150 35 16 151 34 16 152 35 41 153 37 41 154 36 41 155 37 18 156 39 18 157 38 18 158 39 42 159 41 42 160 40 42 161 41 43 162 43 43 163 42 43 164 43 21 165 45 21 166 44 21 167 45 44 168 47 44 169 46 44 170 47 45 171 49 45 172 48 45 173 49 46 174 51 46 175 50 46 176 51 25 177 53 25 178 52 25 179 53 47 180 55 47 181 54 47 182 55 27 183 57 27 184 56 27 185 57 48 186 59 48 187 58 48 188 59 29 189 61 29 190 60 29 191 5 49 192 3 49 193 1 49 194 1 49 195 63 49 196 5 49 197 63 49 198 61 49 199 5 49 200 61 49 201 59 49 202 57 49 203 57 49 204 55 49 205 53 49 206 53 50 207 51 50 208 49 50 209 49 49 210 47 49 211 53 49 212 47 49 213 45 49 214 53 49 215 45 49 216 43 49 217 41 49 218 41 49 219 39 49 220 37 49 221 37 49 222 35 49 223 33 49 224 33 49 225 31 49 226 29 49 227 29 49 228 27 49 229 25 49 230 25 49 231 23 49 232 21 49 233 21 51 234 19 51 235 17 51 236 17 49 237 15 49 238 21 49 239 15 49 240 13 49 241 21 49 242 13 49 243 11 49 244 9 49 245 9 49 246 7 49 247 5 49 248 61 49 249 57 49 250 5 49 251 57 49 252 53 49 253 5 49 254 45 49 255 41 49 256 37 49 257 37 49 258 33 49 259 21 49 260 33 49 261 29 49 262 21 49 263 29 49 264 25 49 265 21 49 266 13 52 267 9 52 268 21 52 269 9 53 270 5 53 271 21 53 272 53 54 273 45 54 274 37 54 275 5 49 276 53 49 277 21 49 278 61 55 279 63 55 280 62 55 281 63 32 282 1 32 283 0 32 284 62 33 285 0 33 286 2 33 287 2 33 288 4 33 289 6 33 290 6 33 291 8 33 292 10 33 293 10 33 294 12 33 295 6 33 296 12 33 297 14 33 298 6 33 299 14 33 300 16 33 301 18 33 302 18 33 303 20 33 304 14 33 305 20 33 306 22 33 307 14 33 308 22 33 309 24 33 310 30 33 311 24 33 312 26 33 313 30 33 314 26 33 315 28 33 316 30 33 317 30 33 318 32 33 319 34 33 320 34 33 321 36 33 322 38 33 323 38 33 324 40 33 325 46 33 326 40 33 327 42 33 328 46 33 329 42 33 330 44 33 331 46 33 332 46 33 333 48 33 334 50 33 335 50 33 336 52 33 337 54 33 338 54 33 339 56 33 340 58 33 341 58 33 342 60 33 343 62 33 344 62 33 345 2 33 346 6 33 347 30 33 348 34 33 349 46 33 350 34 33 351 38 33 352 46 33 353 46 33 354 50 33 355 62 33 356 50 33 357 54 33 358 62 33 359 54 33 360 58 33 361 62 33 362 62 33 363 6 33 364 14 33 365 14 33 366 22 33 367 30 33 368 62 33 369 14 33 370 46 33 371

+
+
+
+
+ + + + 67.5 0 0 0 0 67.5 0 0 0 0 91.5 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_collision_E3M5.dae b/URDFs/sr_description/meshes/components/forearm/forearm_collision_E3M5.dae new file mode 100644 index 0000000..cb1906c --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_collision_E3M5.dae @@ -0,0 +1,83 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:40:38 + 2022-02-10T09:40:38 + + Z_UP + + + + + + + -13.11653 -65.92442 164.8893 -20.45978 -71.90862 156.5069 -6.898247 -74.44371 156.5069 6.898201 -74.44371 156.5069 -2.28882e-5 -67.21208 164.8893 -6.228134 -67.21208 164.8893 -2.28882e-5 -67.21208 125.6178 -13.11653 -65.92442 125.6178 -6.228134 -67.21208 125.6178 20.45974 -71.90862 156.5069 13.11649 -65.92442 164.8893 6.228096 -67.21208 164.8893 13.11649 -65.92442 125.6178 6.228096 -67.21208 125.6178 -25.73364 -62.11018 164.8893 -33.32458 -66.92477 156.5069 -18.47228 -64.92326 164.8893 -25.73364 -62.11018 125.6178 -18.47228 -64.92326 125.6178 33.32454 -66.92477 156.5069 25.7336 -62.11018 164.8893 18.47223 -64.92326 164.8893 25.7336 -62.11018 125.6178 18.47223 -64.92326 125.6178 -13.16862 -66.20303 -4.05312e-6 -2.28882e-5 -67.50003 -4.05312e-6 13.16857 -66.20303 -4.05312e-6 -2.28882e-5 -2.28882e-5 -4.05312e-6 -13.16862 -66.20303 182.8 -2.28882e-5 -67.50003 182.8 13.16857 -66.20303 182.8 -2.28882e-5 -2.28882e-5 182.8 -37.37076 -55.91385 164.8893 -45.05456 -59.66187 156.5069 -30.08736 -60.42354 164.8893 -37.37076 -55.91385 125.6178 -30.08736 -60.42354 125.6178 45.05451 -59.66187 156.5069 37.37072 -55.91385 164.8893 30.08732 -60.42354 164.8893 37.37072 -55.91385 125.6178 30.08732 -60.42354 125.6178 -25.83115 -62.36189 -4.05312e-6 25.83111 -62.36189 -4.05312e-6 -25.83115 -62.36189 182.8 25.83111 -62.36189 182.8 -37.50101 -56.12422 -4.05312e-6 37.50097 -56.12422 -4.05312e-6 -37.50101 -56.12422 182.8 37.50097 -56.12422 182.8 -47.58427 -47.57016 164.8893 -55.25025 -50.36726 156.5069 -40.67786 -53.86618 164.8893 -47.58427 -47.57016 125.6178 -40.67786 -53.86618 125.6178 55.2502 -50.36726 156.5069 47.58422 -47.57016 164.8893 40.67782 -53.86618 164.8893 47.58422 -47.57016 125.6178 40.67782 -53.86618 125.6178 -47.72973 -47.72973 -4.05312e-6 47.72968 -47.72973 -4.05312e-6 -47.72973 -47.72973 182.8 47.72968 -47.72973 182.8 -55.98424 -37.3953 164.8893 -63.56447 -39.35746 156.5069 -49.88312 -45.47447 164.8893 -55.98424 -37.3953 125.6178 -49.88312 -45.47447 125.6178 63.56443 -39.35746 156.5069 55.9842 -37.3953 164.8893 49.88308 -45.47447 164.8893 55.9842 -37.3953 125.6178 49.88308 -45.47447 125.6178 -56.12422 -37.50101 -4.05312e-6 56.12418 -37.50101 -4.05312e-6 -56.12422 -37.50101 182.8 56.12418 -37.50101 182.8 -62.24917 -25.77503 164.8893 -69.71408 -27.00739 156.5069 -57.38968 -35.53419 164.8893 -62.24917 -25.77503 125.6178 -57.38968 -35.53419 125.6178 69.71403 -27.00739 156.5069 62.24912 -25.77503 164.8893 57.38964 -35.53419 164.8893 62.24912 -25.77503 125.6178 57.38964 -35.53419 125.6178 -62.36189 -25.83115 -4.05312e-6 62.36185 -25.83115 -4.05312e-6 -62.36189 -25.83115 182.8 62.36185 -25.83115 182.8 -66.13816 -13.15016 164.8893 -73.48966 -13.73761 156.5069 -62.9419 -24.38384 164.8893 -66.13816 -13.15016 125.6178 -62.9419 -24.38384 125.6178 73.48962 -13.73761 156.5069 66.13812 -13.15016 164.8893 62.94186 -24.38384 164.8893 66.13812 -13.15016 125.6178 62.94186 -24.38384 125.6178 -66.20303 -13.16862 -4.05312e-6 66.20298 -13.16862 -4.05312e-6 -66.20303 -13.16862 182.8 66.20298 -13.16862 182.8 -66.35071 -12.40311 164.8893 -67.50003 -2.28882e-5 164.8893 -74.76263 -2.28882e-5 156.5069 -66.35071 -12.40311 125.6178 74.76258 -2.28882e-5 156.5069 66.35066 -12.40311 164.8893 66.35066 -12.40311 125.6178 67.49998 -2.28882e-5 125.6178 -67.50003 -2.28882e-5 -4.05312e-6 67.49998 -2.28882e-5 -4.05312e-6 -67.50003 -2.28882e-5 182.8 67.49998 -2.28882e-5 182.8 -67.50003 -2.28882e-5 125.6178 67.49998 -2.28882e-5 164.8893 -73.48966 13.73757 156.5069 73.48962 13.73757 156.5069 -66.35071 12.40307 125.6178 66.35066 12.40307 164.8893 -66.20303 13.16857 -4.05312e-6 56.12418 37.50097 -4.05312e-6 62.36185 25.83111 -4.05312e-6 66.20298 13.16857 -4.05312e-6 25.83111 62.36185 -4.05312e-6 37.50097 56.12418 -4.05312e-6 47.72968 47.72968 -4.05312e-6 -13.16862 66.20298 -4.05312e-6 -2.28882e-5 67.49998 -4.05312e-6 13.16857 66.20298 -4.05312e-6 -47.72973 47.72968 -4.05312e-6 -37.50101 56.12418 -4.05312e-6 -25.83115 62.36185 -4.05312e-6 -62.36189 25.83111 -4.05312e-6 -56.12422 37.50097 -4.05312e-6 66.35066 12.40307 125.6178 -66.35071 12.40307 164.8893 -66.20303 13.16857 182.8 -47.72973 47.72968 182.8 -56.12422 37.50097 182.8 -62.36189 25.83111 182.8 -13.16862 66.20298 182.8 -25.83115 62.36185 182.8 -37.50101 56.12418 182.8 25.83111 62.36185 182.8 13.16857 66.20298 182.8 -2.28882e-5 67.49998 182.8 56.12418 37.50097 182.8 47.72968 47.72968 182.8 37.50097 56.12418 182.8 66.20298 13.16857 182.8 62.36185 25.83111 182.8 -66.13816 13.15012 125.6178 66.13812 13.15012 125.6178 -66.13816 13.15012 164.8893 66.13812 13.15012 164.8893 -62.9419 24.38379 125.6178 -69.71408 27.00735 156.5069 62.94186 24.38379 125.6178 69.71403 27.00735 156.5069 -62.9419 24.38379 164.8893 62.94186 24.38379 164.8893 -62.24917 25.77498 125.6178 62.24912 25.77498 125.6178 -62.24917 25.77498 164.8893 62.24912 25.77498 164.8893 -57.38968 35.53415 125.6178 -63.56447 39.35742 156.5069 57.38964 35.53415 125.6178 63.56443 39.35742 156.5069 -57.38968 35.53415 164.8893 57.38964 35.53415 164.8893 -55.98424 37.39525 125.6178 55.9842 37.39525 125.6178 -55.98424 37.39525 164.8893 55.9842 37.39525 164.8893 -49.88312 45.47443 125.6178 -55.25025 50.36722 156.5069 49.88308 45.47443 125.6178 55.2502 50.36722 156.5069 -49.88312 45.47443 164.8893 49.88308 45.47443 164.8893 -47.58427 47.57012 125.6178 47.58422 47.57012 125.6178 -47.58427 47.57012 164.8893 47.58422 47.57012 164.8893 -40.67786 53.86614 125.6178 -45.05456 59.66183 156.5069 40.67782 53.86614 125.6178 45.05451 59.66183 156.5069 -40.67786 53.86614 164.8893 40.67782 53.86614 164.8893 -37.37076 55.91381 125.6178 37.37072 55.91381 125.6178 -37.37076 55.91381 164.8893 37.37072 55.91381 164.8893 -30.08736 60.4235 125.6178 -33.32458 66.92472 156.5069 30.08732 60.4235 125.6178 33.32454 66.92472 156.5069 -30.08736 60.4235 164.8893 30.08732 60.4235 164.8893 -25.73364 62.11014 125.6178 25.7336 62.11014 125.6178 -25.73364 62.11014 164.8893 25.7336 62.11014 164.8893 -18.47228 64.92321 125.6178 -20.45978 71.90858 156.5069 18.47223 64.92321 125.6178 20.45974 71.90858 156.5069 -18.47228 64.92321 164.8893 18.47223 64.92321 164.8893 -13.11653 65.92437 125.6178 13.11649 65.92437 125.6178 -13.11653 65.92437 164.8893 13.11649 65.92437 164.8893 -6.228134 67.21205 125.6178 -6.898247 74.44366 156.5069 6.228096 67.21205 125.6178 6.898201 74.44366 156.5069 -6.228134 67.21205 164.8893 6.228096 67.21205 164.8893 -2.28882e-5 67.21205 125.6178 -2.28882e-5 67.21205 164.8893 + + + + + + + + + + -0.1391299 -0.7442759 0.6532199 0 -0.7571679 0.6532204 0 -0.7571682 0.6532201 -0.1391289 -0.7442752 0.653221 0 -0.9736725 -0.2279521 -0.1789118 -0.9570939 -0.2279517 -0.1789123 -0.9570936 -0.2279523 0 -0.9736725 -0.2279518 0.1391299 -0.744276 0.6532198 0.139129 -0.7442755 0.6532206 0 -0.7571678 0.6532204 0.178912 -0.9570938 -0.2279517 0 -0.9736725 -0.2279521 0.1789124 -0.9570937 -0.2279521 -0.2735207 -0.7060382 0.6532202 -0.1391282 -0.7442755 0.6532208 -0.2735238 -0.7060368 0.6532204 -0.351731 -0.9079226 -0.227952 -0.3517323 -0.9079219 -0.2279523 -0.1789112 -0.9570938 -0.227952 0.2735206 -0.7060382 0.6532201 0.2735235 -0.7060368 0.6532205 0.1391265 -0.7442758 0.6532208 0.351731 -0.9079226 -0.227952 0.1789116 -0.9570938 -0.2279522 0.3517324 -0.9079219 -0.2279524 -0.09801763 -0.9951814 -0.002578377 0.09801763 -0.9951814 -0.002578377 0 -0.9999974 0.002292275 0 -0.9999974 0.002292156 0 0 -1 0 0 -1 -0.09800189 -0.9950219 0.01808094 0 -0.9998708 -0.01607441 0 -0.9998709 -0.01607495 0.09800201 -0.9950219 0.01808094 -6.86652e-7 0 1 0 0 1 -0.1837494 -0.9829707 0.002256214 0.1837494 -0.9829707 0.002256214 -0.1837271 -0.9828499 -0.01582217 0.1837271 -0.9828499 -0.01582217 -0.3985967 -0.6437571 0.653221 -0.2735221 -0.7060377 0.6532201 -0.3985971 -0.6437568 0.6532209 -0.5125729 -0.8278326 -0.2279522 -0.5125723 -0.827833 -0.2279522 -0.3517317 -0.9079222 -0.2279521 0.398597 -0.6437575 0.6532204 0.3985971 -0.6437568 0.6532209 0.2735199 -0.7060381 0.6532205 0.5125725 -0.827833 -0.2279521 0.3517314 -0.9079223 -0.227952 0.5125723 -0.827833 -0.2279522 -0.2902838 -0.9569373 -0.002506852 -0.1837483 -0.9829708 0.002256393 0 0 -1 0.2902836 -0.9569374 -0.002506852 0.1837487 -0.9829707 0.002256274 0 0 -1 -6.86652e-7 0 1 -0.2902398 -0.9567925 0.01757949 -0.1837258 -0.9828502 -0.01582336 0.1837263 -0.9828501 -0.015823 0.2902398 -0.9567925 0.01757949 -0.3612419 -0.9324697 0.002148807 0.3612416 -0.9324699 0.002148807 -0.361202 -0.9323658 -0.01506948 0.3612016 -0.932366 -0.01506948 -0.4713954 -0.8819188 -0.002363443 -0.3612411 -0.9324701 0.002148926 0 0 -1 0.4713955 -0.8819187 -0.002363443 0.3612411 -0.9324701 0.002148866 0 0 -1 2.74661e-7 0 1 -0.4713318 -0.8818003 0.01657378 -0.3612009 -0.9323663 -0.01506978 0.3612009 -0.9323663 -0.01507002 0.4713314 -0.8818004 0.01657402 -0.5264315 -0.8502154 0.001969695 0.5264311 -0.8502157 0.001969695 -0.5263824 -0.8501359 -0.01381343 0.526382 -0.8501361 -0.01381337 -0.5100999 -0.5595545 0.6532205 -0.3985978 -0.6437575 0.6532199 -0.5101016 -0.5595531 0.6532203 -0.6559591 -0.7195525 -0.2279518 -0.6559588 -0.7195526 -0.2279523 -0.5125713 -0.8278338 -0.227952 0.5101001 -0.5595539 0.6532207 0.510102 -0.5595536 0.6532196 0.398599 -0.6437564 0.6532202 0.6559593 -0.7195522 -0.227952 0.5125738 -0.8278321 -0.2279524 0.6559588 -0.7195526 -0.2279519 -0.6343917 -0.7730089 -0.002148389 -0.52643 -0.8502162 0.001969695 0.6343917 -0.7730089 -0.002148449 0.5264309 -0.8502156 0.001969695 0 0 -1 -0.6343212 -0.7729229 0.01506662 -0.5263808 -0.8501367 -0.01381349 0.5263827 -0.8501356 -0.01381331 0.6343215 -0.7729225 0.01506698 -0.6736947 -0.7390078 0.001718819 0.6736955 -0.7390071 0.001718819 -0.6736477 -0.7389544 -0.0120545 0.6736472 -0.7389547 -0.0120545 -0.6042332 -0.4562962 0.6532198 -0.5101044 -0.5595502 0.6532207 -0.6042314 -0.4562966 0.6532211 -0.7770069 -0.5867695 -0.2279517 -0.7770068 -0.5867695 -0.2279521 -0.6559615 -0.71955 -0.2279527 0.6042332 -0.4562966 0.6532196 0.6042325 -0.4562966 0.6532202 0.5101023 -0.5595532 0.6532197 0.7770071 -0.5867692 -0.2279517 0.6559591 -0.7195522 -0.2279524 0.7770067 -0.5867698 -0.2279517 -0.7730091 -0.6343924 -0.001861691 -0.6736971 -0.7390057 0.001718759 0.773009 -0.6343924 -0.001861751 0.6736934 -0.7390091 0.001718819 0 0 -1 -0.7729445 -0.6343393 0.01305621 -0.6736487 -0.7389534 -0.01205402 0.6736466 -0.7389553 -0.01205426 0.7729443 -0.6343395 0.01305651 -0.798016 -0.6026349 0.001396358 0.798016 -0.6026349 0.001396358 -0.7979782 -0.6026068 -0.009793162 0.7979785 -0.6026064 -0.009793162 -0.6777884 -0.3374995 0.6532205 -0.6042307 -0.4562947 0.6532232 -0.677789 -0.3374987 0.6532202 -0.8715952 -0.4340043 -0.2279521 -0.8715957 -0.4340035 -0.2279519 -0.7770096 -0.5867656 -0.2279525 0.6777881 -0.3374986 0.6532213 0.6777882 -0.3374994 0.6532208 0.6042317 -0.4562937 0.6532229 0.871596 -0.4340027 -0.227952 0.7770079 -0.5867677 -0.2279524 0.8715959 -0.4340029 -0.227952 -0.8819203 -0.4713962 -0.001503586 -0.7980167 -0.6026337 0.001396358 0.8819206 -0.4713958 -0.001503586 0.7980183 -0.6026316 0.001396358 0 0 -1 -0.8818718 -0.4713714 0.01054525 -0.7979809 -0.6026033 -0.009793162 0.7979809 -0.6026034 -0.009793341 0.8818722 -0.4713706 0.01054507 -0.8951629 -0.4457381 0.001002311 0.8951629 -0.4457381 0.00100243 -0.8951416 -0.4457266 -0.00702995 0.8951411 -0.4457276 -0.007030427 -0.7282632 -0.2072093 0.6532205 -0.67779 -0.3374937 0.6532219 -0.7282627 -0.2072093 0.6532211 -0.9365033 -0.2664576 -0.2279517 -0.936503 -0.266458 -0.2279522 -0.8715986 -0.4339971 -0.2279526 0.7282629 -0.2072092 0.6532208 0.7282638 -0.2072094 0.6532198 0.6777893 -0.3374996 0.6532195 0.9365029 -0.2664588 -0.227952 0.8715969 -0.4340009 -0.227952 0.9365032 -0.266458 -0.2279517 -0.9569398 -0.2902848 -0.001073896 -0.8951625 -0.4457389 0.001002371 0.9569401 -0.2902837 -0.001073896 0.8951585 -0.4457469 0.00100243 -0.9569134 -0.2902761 0.007531642 -0.8951388 -0.4457324 -0.007030189 0.8951387 -0.4457324 -0.007030546 0.9569134 -0.290276 0.00753194 -0.9618253 -0.2736635 5.36881e-4 0.9618253 -0.2736636 5.36881e-4 -0.9618187 -0.2736614 -0.003765404 0.961819 -0.2736604 -0.003765404 -0.7282683 -0.2071974 0.6532186 -0.7539383 -0.06986355 0.6532199 -0.753938 -0.06986314 0.6532203 -0.9695188 -0.08983969 -0.227952 -0.9365 -0.26647 -0.2279508 0.7539368 -0.0698623 0.6532217 0.7282666 -0.2071975 0.6532205 0.9365047 -0.2664517 -0.2279527 0.9695188 -0.08983945 -0.2279524 0.969519 -0.08983862 -0.227952 -0.9951846 -0.09801727 -5.72668e-4 -0.9618293 -0.27365 5.36875e-4 0.9951846 -0.09801727 -5.72611e-4 0.9618293 -0.27365 5.36876e-4 -0.9951768 -0.09801578 0.004016399 -0.9618163 -0.2736701 -0.003765344 0.9618209 -0.2736539 -0.003765344 0.9951767 -0.09801673 0.004015982 -0.995734 -0.09226989 0 -0.969519 -0.08983951 -0.2279518 0.9957342 -0.0922687 0 -0.9957342 -0.09226906 0 0.9957343 -0.09226799 0 0.7539386 -0.06986266 0.6532198 -0.9695189 0.08983963 -0.2279516 0.7539376 0.06986153 0.6532209 -0.9695188 0.08983945 -0.2279521 0.7539374 0.06986343 0.6532208 -0.995734 0.09226989 0 -0.9951846 0.09801733 -5.72676e-4 0 0 -1 0.9695188 0.08983945 -0.227952 -0.7539394 0.06986349 0.6532186 -0.753936 0.06986325 0.6532226 0.9695188 0.08983856 -0.2279525 -0.9957342 0.09226906 0 -0.9951768 0.09801596 0.004016458 1.09864e-6 0 1 -1.09864e-6 0 1 2.19729e-6 0 1 -2.19729e-6 0 1 -2.19729e-6 0 1 0.9951846 0.09801733 -5.72618e-4 0.9957342 0.09226864 0 0.9957343 0.09226799 0 0.9951767 0.09801697 0.004016041 -0.9618293 0.27365 5.36858e-4 -0.9365 0.26647 -0.2279507 0.9618293 0.27365 5.36848e-4 0.9365049 0.2664518 -0.2279521 -0.9618164 0.2736699 -0.003765225 -0.7282683 0.2071974 0.6532186 0.961821 0.2736537 -0.003765165 0.7282677 0.2071978 0.6532191 -0.9618253 0.2736638 5.36853e-4 -0.9365033 0.2664576 -0.2279517 -0.936503 0.2664583 -0.2279523 0.9618253 0.2736638 5.36855e-4 0.9365029 0.2664587 -0.227952 0.9365031 0.2664584 -0.2279518 -0.9618186 0.2736617 -0.003765225 -0.7282631 0.2072093 0.6532206 -0.7282648 0.2072088 0.653219 0.9618189 0.2736607 -0.003765165 0.7282629 0.2072092 0.653221 0.7282646 0.2072093 0.6532191 -0.9569399 0.2902846 -0.001073837 0.9569402 0.2902835 -0.001073896 -0.9569134 0.2902756 0.007531523 0.9569134 0.290276 0.007531821 -0.8951622 0.4457395 0.00100243 -0.8715983 0.4339976 -0.227953 0.8951583 0.4457474 0.00100243 0.8715962 0.4340018 -0.2279531 -0.8951387 0.4457324 -0.007030427 -0.67779 0.3374937 0.6532219 0.8951387 0.4457324 -0.007030725 0.6777889 0.3374994 0.6532201 -0.8951632 0.4457377 0.001002371 -0.871595 0.4340044 -0.2279523 -0.8715959 0.4340029 -0.2279519 0.8951632 0.4457377 0.00100243 0.8715959 0.4340029 -0.2279523 0.8715961 0.4340026 -0.2279521 -0.8951418 0.4457261 -0.007030248 -0.6777881 0.3374995 0.6532207 -0.6777887 0.3374986 0.6532207 0.8951412 0.4457273 -0.007030665 0.6777879 0.3374985 0.6532216 0.6777896 0.3374986 0.6532197 -0.8819203 0.4713963 -0.001503646 0.8819205 0.4713959 -0.001503586 -0.8818721 0.4713711 0.01054531 0.8818727 0.4713698 0.01054519 -0.7980149 0.6026361 0.001396417 -0.7770075 0.5867681 -0.227953 0.7980166 0.602634 0.001396417 0.7770062 0.5867701 -0.2279521 -0.7979792 0.6026055 -0.0097934 -0.6042317 0.4562954 0.6532219 0.7979792 0.6026055 -0.0097934 0.6042321 0.4562957 0.6532211 -0.7980163 0.6026343 0.001396417 -0.7770071 0.5867692 -0.2279518 -0.7770069 0.5867693 -0.2279523 0.7980163 0.6026343 0.001396417 0.777007 0.5867694 -0.227952 0.7770069 0.5867695 -0.2279518 -0.7979788 0.6026061 -0.009793519 -0.6042327 0.4562962 0.6532202 -0.6042312 0.4562965 0.6532213 0.7979792 0.6026055 -0.009793579 0.6042328 0.4562963 0.65322 0.6042329 0.456296 0.6532202 -0.7730088 0.6343926 -0.001861751 0.7730088 0.6343926 -0.00186181 -0.7729442 0.6343398 0.01305675 0.7729439 0.6343401 0.01305705 -0.6736964 0.7390062 0.001718759 -0.6559613 0.7195504 -0.2279522 0.6736928 0.7390096 0.001718759 0.6559592 0.7195523 -0.2279518 -0.6736482 0.7389539 -0.01205378 -0.510105 0.5595509 0.6532196 0.673646 0.7389559 -0.01205402 0.5101017 0.5595545 0.6532191 -0.6736947 0.7390078 0.001718759 -0.6559591 0.7195525 -0.2279518 -0.6559588 0.7195526 -0.2279524 0.6736956 0.7390071 0.001718759 0.6559595 0.719552 -0.2279519 0.6559588 0.7195526 -0.227952 -0.6736477 0.7389544 -0.01205408 -0.5100999 0.5595545 0.6532205 -0.5101014 0.559553 0.6532205 0.6736474 0.7389547 -0.01205402 0.5101001 0.5595539 0.6532207 0.5101019 0.5595535 0.6532198 -0.6343923 0.7730085 -0.002148389 0.6343922 0.7730084 -0.002148449 -0.6343213 0.7729228 0.01506644 0.6343215 0.7729225 0.01506698 -0.52643 0.8502162 0.001969695 -0.5125717 0.8278335 -0.2279519 0.5264309 0.8502157 0.001969695 0.5125738 0.8278321 -0.2279521 -0.5263805 0.850137 -0.01381331 -0.3985977 0.6437572 0.6532203 0.526382 0.850136 -0.01381331 0.3985987 0.6437561 0.6532207 -0.5264318 0.8502151 0.001969695 -0.5125725 0.8278329 -0.2279523 -0.5125723 0.827833 -0.2279519 0.5264314 0.8502154 0.001969695 0.5125727 0.8278329 -0.2279521 0.5125723 0.827833 -0.2279519 -0.5263824 0.8501359 -0.01381343 -0.3985967 0.6437571 0.653221 -0.3985995 0.6437566 0.6532197 0.526382 0.8501359 -0.01381337 0.398597 0.6437575 0.6532204 0.3985985 0.6437569 0.6532201 -0.4713952 0.8819189 -0.002363443 0.4713953 0.8819189 -0.002363443 -0.4713324 0.8818 0.01657402 0.4713323 0.8818001 0.01657402 -0.3612405 0.9324703 0.002148926 -0.3517306 0.9079226 -0.2279518 0.3612404 0.9324703 0.002148926 0.3517307 0.9079227 -0.2279515 -0.3612 0.9323666 -0.01506996 -0.2735181 0.7060394 0.65322 0.3612003 0.9323665 -0.01507002 0.2735202 0.7060387 0.6532199 -0.3612415 0.9324699 0.002148866 -0.3517318 0.9079221 -0.2279524 -0.3517314 0.9079222 -0.2279523 0.3612412 0.93247 0.002148807 0.3517316 0.9079222 -0.2279524 0.3517315 0.9079223 -0.2279523 -0.3612017 0.932366 -0.01506948 -0.2735204 0.7060374 0.6532211 -0.2735214 0.706038 0.6532201 0.3612011 0.9323663 -0.01506966 0.2735203 0.7060375 0.653221 0.2735217 0.7060375 0.6532205 -0.2902836 0.9569374 -0.002506852 0.2902833 0.9569375 -0.002506852 -0.2902394 0.9567927 0.01757949 0.2902393 0.9567927 0.01757949 -0.1837483 0.9829708 0.002256393 -0.1789113 0.9570938 -0.227952 0.1837487 0.9829707 0.002256333 0.1789116 0.9570938 -0.2279522 -0.183726 0.9828502 -0.0158236 -0.1391282 0.7442755 0.6532208 0.1837263 0.9828501 -0.015823 0.139127 0.7442757 0.6532208 -0.1837515 0.9829702 0.002256453 -0.1789113 0.9570939 -0.227952 -0.178914 0.9570934 -0.2279517 0.1837515 0.9829702 0.002256393 0.1789112 0.9570939 -0.2279521 0.1789145 0.9570934 -0.2279515 -0.1837292 0.9828495 -0.01582413 -0.1391291 0.7442756 0.6532205 -0.1391322 0.7442757 0.6532198 0.1837291 0.9828495 -0.01582378 0.1391283 0.7442758 0.6532204 0.1391311 0.7442761 0.6532195 -0.09801703 0.9951815 -0.002578675 0.09801709 0.9951814 -0.002578616 -0.09800124 0.9950221 0.01808273 0.0980013 0.9950221 0.01808249 0 0.9999974 0.002292096 0 0.9736726 -0.2279512 0 0.9999974 0.002292096 0 0.9736725 -0.2279515 0 0.9998708 -0.01607388 0 0.757169 0.6532191 0 0.9998709 -0.01607388 0 0.7571688 0.6532195 0 0.7571691 0.6532189 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 2 1 4 2 5 2 2 2 5 3 0 3 2 3 6 4 3 4 2 4 1 5 7 5 2 5 7 6 8 6 2 6 8 7 6 7 2 7 9 8 10 8 3 8 10 9 11 9 3 9 11 10 4 10 3 10 12 11 9 11 3 11 6 12 13 12 3 12 13 13 12 13 3 13 14 14 15 14 1 14 0 15 16 15 1 15 16 16 14 16 1 16 15 17 17 17 1 17 17 18 18 18 1 18 18 19 7 19 1 19 19 20 20 20 9 20 20 21 21 21 9 21 21 22 10 22 9 22 22 23 19 23 9 23 12 24 23 24 9 24 23 25 22 25 9 25 8 26 24 26 25 26 26 27 13 27 25 27 13 28 6 28 25 28 6 29 8 29 25 29 27 30 26 30 25 30 24 31 27 31 25 31 28 32 5 32 29 32 5 33 4 33 29 33 4 34 11 34 29 34 11 35 30 35 29 35 31 36 28 36 29 36 30 37 31 37 29 37 7 38 24 38 8 38 26 39 12 39 13 39 28 40 0 40 5 40 10 41 30 41 11 41 32 42 33 42 15 42 14 43 34 43 15 43 34 44 32 44 15 44 33 45 35 45 15 45 35 46 36 46 15 46 36 47 17 47 15 47 37 48 38 48 19 48 38 49 39 49 19 49 39 50 20 50 19 50 40 51 37 51 19 51 22 52 41 52 19 52 41 53 40 53 19 53 18 54 42 54 24 54 7 55 18 55 24 55 42 56 27 56 24 56 43 57 23 57 26 57 23 58 12 58 26 58 27 59 43 59 26 59 31 60 44 60 28 60 44 61 16 61 28 61 16 62 0 62 28 62 45 37 31 37 30 37 10 63 21 63 30 63 21 64 45 64 30 64 17 65 42 65 18 65 43 66 22 66 23 66 44 67 14 67 16 67 20 68 45 68 21 68 36 69 46 69 42 69 17 70 36 70 42 70 46 71 27 71 42 71 47 72 41 72 43 72 41 73 22 73 43 73 27 74 47 74 43 74 31 75 48 75 44 75 48 76 34 76 44 76 34 77 14 77 44 77 49 37 31 37 45 37 20 78 39 78 45 78 39 79 49 79 45 79 35 80 46 80 36 80 47 81 40 81 41 81 48 82 32 82 34 82 38 83 49 83 39 83 50 84 51 84 33 84 32 85 52 85 33 85 52 86 50 86 33 86 51 87 53 87 33 87 53 88 54 88 33 88 54 89 35 89 33 89 55 90 56 90 37 90 56 91 57 91 37 91 57 92 38 92 37 92 58 93 55 93 37 93 40 94 59 94 37 94 59 95 58 95 37 95 54 96 60 96 46 96 35 97 54 97 46 97 60 71 27 71 46 71 61 98 59 98 47 98 59 99 40 99 47 99 27 100 61 100 47 100 31 37 62 37 48 37 62 101 52 101 48 101 52 102 32 102 48 102 63 37 31 37 49 37 38 103 57 103 49 103 57 104 63 104 49 104 53 105 60 105 54 105 61 106 58 106 59 106 62 107 50 107 52 107 56 108 63 108 57 108 64 109 65 109 51 109 50 110 66 110 51 110 66 111 64 111 51 111 65 112 67 112 51 112 67 113 68 113 51 113 68 114 53 114 51 114 69 115 70 115 55 115 70 116 71 116 55 116 71 117 56 117 55 117 72 118 69 118 55 118 58 119 73 119 55 119 73 120 72 120 55 120 68 121 74 121 60 121 53 122 68 122 60 122 74 71 27 71 60 71 75 123 73 123 61 123 73 124 58 124 61 124 27 125 75 125 61 125 31 75 76 75 62 75 76 126 66 126 62 126 66 127 50 127 62 127 77 37 31 37 63 37 56 128 71 128 63 128 71 129 77 129 63 129 67 130 74 130 68 130 75 131 72 131 73 131 76 132 64 132 66 132 70 133 77 133 71 133 78 134 79 134 65 134 64 135 80 135 65 135 80 136 78 136 65 136 79 137 81 137 65 137 81 138 82 138 65 138 82 139 67 139 65 139 83 140 84 140 69 140 84 141 85 141 69 141 85 142 70 142 69 142 86 143 83 143 69 143 72 144 87 144 69 144 87 145 86 145 69 145 82 146 88 146 74 146 67 147 82 147 74 147 88 71 27 71 74 71 89 148 87 148 75 148 87 149 72 149 75 149 27 150 89 150 75 150 31 37 90 37 76 37 90 151 80 151 76 151 80 152 64 152 76 152 91 37 31 37 77 37 70 153 85 153 77 153 85 154 91 154 77 154 81 155 88 155 82 155 89 156 86 156 87 156 90 157 78 157 80 157 84 158 91 158 85 158 92 159 93 159 79 159 78 160 94 160 79 160 94 161 92 161 79 161 93 162 95 162 79 162 95 163 96 163 79 163 96 164 81 164 79 164 97 165 98 165 83 165 98 166 99 166 83 166 99 167 84 167 83 167 100 168 97 168 83 168 86 169 101 169 83 169 101 170 100 170 83 170 96 171 102 171 88 171 81 172 96 172 88 172 102 71 27 71 88 71 103 173 101 173 89 173 101 174 86 174 89 174 27 71 103 71 89 71 31 37 104 37 90 37 104 175 94 175 90 175 94 176 78 176 90 176 105 37 31 37 91 37 84 177 99 177 91 177 99 178 105 178 91 178 95 179 102 179 96 179 103 180 100 180 101 180 104 181 92 181 94 181 98 182 105 182 99 182 92 183 106 183 93 183 106 184 107 184 93 184 107 185 108 185 93 185 108 186 109 186 93 186 109 187 95 187 93 187 110 188 111 188 97 188 111 189 98 189 97 189 100 190 112 190 97 190 112 191 113 191 97 191 113 192 110 192 97 192 109 193 114 193 102 193 95 194 109 194 102 194 114 71 27 71 102 71 115 195 112 195 103 195 112 196 100 196 103 196 27 71 115 71 103 71 31 37 116 37 104 37 116 197 106 197 104 197 106 198 92 198 104 198 117 37 31 37 105 37 98 199 111 199 105 199 111 200 117 200 105 200 118 201 114 201 109 201 108 202 118 202 109 202 115 203 113 203 112 203 116 204 107 204 106 204 119 205 117 205 111 205 110 206 119 206 111 206 120 207 118 207 108 207 121 208 119 208 110 208 120 209 122 209 118 209 121 210 123 210 119 210 124 71 27 71 114 71 118 211 122 211 114 211 122 212 124 212 114 212 125 71 126 71 27 71 126 71 127 71 27 71 127 71 115 71 27 71 128 213 129 213 27 213 129 71 130 71 27 71 130 71 125 71 27 71 131 71 132 71 27 71 132 71 133 71 27 71 133 71 128 71 27 71 134 71 135 71 27 71 135 71 136 71 27 71 136 71 131 71 27 71 124 71 137 71 27 71 137 71 138 71 27 71 138 71 134 71 27 71 139 214 110 214 113 214 107 215 140 215 108 215 140 216 120 216 108 216 139 217 121 217 110 217 116 218 140 218 107 218 31 37 141 37 116 37 141 219 140 219 116 219 142 220 143 220 31 220 143 221 144 221 31 221 144 37 141 37 31 37 145 37 146 37 31 37 146 222 147 222 31 222 147 223 142 223 31 223 148 37 149 37 31 37 149 37 150 37 31 37 150 37 145 37 31 37 151 224 152 224 31 224 152 222 153 222 31 222 153 37 148 37 31 37 117 37 154 37 31 37 154 37 155 37 31 37 155 37 151 37 31 37 127 225 139 225 115 225 139 226 113 226 115 226 123 227 117 227 119 227 123 228 154 228 117 228 156 229 124 229 122 229 120 230 156 230 122 230 127 231 157 231 139 231 157 232 121 232 139 232 141 233 158 233 140 233 158 234 120 234 140 234 159 235 154 235 123 235 121 236 159 236 123 236 160 237 124 237 156 237 120 238 161 238 156 238 161 239 160 239 156 239 127 240 162 240 157 240 163 241 121 241 157 241 162 242 163 242 157 242 141 243 164 243 158 243 161 244 120 244 158 244 164 245 161 245 158 245 165 246 154 246 159 246 121 247 163 247 159 247 163 248 165 248 159 248 160 249 137 249 124 249 126 250 162 250 127 250 144 251 164 251 141 251 165 252 155 252 154 252 166 253 137 253 160 253 161 254 166 254 160 254 126 255 167 255 162 255 167 256 163 256 162 256 144 257 168 257 164 257 168 258 161 258 164 258 169 259 155 259 165 259 163 260 169 260 165 260 170 261 137 261 166 261 161 262 171 262 166 262 171 263 170 263 166 263 126 264 172 264 167 264 173 265 163 265 167 265 172 266 173 266 167 266 144 267 174 267 168 267 171 268 161 268 168 268 174 269 171 269 168 269 175 270 155 270 169 270 163 271 173 271 169 271 173 272 175 272 169 272 170 273 138 273 137 273 125 274 172 274 126 274 143 275 174 275 144 275 175 276 151 276 155 276 176 277 138 277 170 277 171 278 176 278 170 278 125 279 177 279 172 279 177 280 173 280 172 280 143 281 178 281 174 281 178 282 171 282 174 282 179 283 151 283 175 283 173 284 179 284 175 284 180 285 138 285 176 285 171 286 181 286 176 286 181 287 180 287 176 287 125 288 182 288 177 288 183 289 173 289 177 289 182 290 183 290 177 290 143 291 184 291 178 291 181 292 171 292 178 292 184 293 181 293 178 293 185 294 151 294 179 294 173 295 183 295 179 295 183 296 185 296 179 296 180 297 134 297 138 297 130 298 182 298 125 298 142 299 184 299 143 299 185 300 152 300 151 300 186 301 134 301 180 301 181 302 186 302 180 302 130 303 187 303 182 303 187 304 183 304 182 304 142 305 188 305 184 305 188 306 181 306 184 306 189 307 152 307 185 307 183 308 189 308 185 308 190 309 134 309 186 309 181 310 191 310 186 310 191 311 190 311 186 311 130 312 192 312 187 312 193 313 183 313 187 313 192 314 193 314 187 314 142 315 194 315 188 315 191 316 181 316 188 316 194 317 191 317 188 317 195 318 152 318 189 318 183 319 193 319 189 319 193 320 195 320 189 320 190 321 135 321 134 321 129 322 192 322 130 322 147 323 194 323 142 323 195 324 153 324 152 324 196 325 135 325 190 325 191 326 196 326 190 326 129 327 197 327 192 327 197 328 193 328 192 328 147 329 198 329 194 329 198 330 191 330 194 330 199 331 153 331 195 331 193 332 199 332 195 332 200 333 135 333 196 333 191 334 201 334 196 334 201 335 200 335 196 335 129 336 202 336 197 336 203 337 193 337 197 337 202 338 203 338 197 338 147 339 204 339 198 339 201 340 191 340 198 340 204 341 201 341 198 341 205 342 153 342 199 342 193 343 203 343 199 343 203 344 205 344 199 344 200 345 136 345 135 345 128 346 202 346 129 346 146 347 204 347 147 347 205 348 148 348 153 348 206 349 136 349 200 349 201 350 206 350 200 350 128 351 207 351 202 351 207 352 203 352 202 352 146 353 208 353 204 353 208 354 201 354 204 354 209 355 148 355 205 355 203 356 209 356 205 356 210 357 136 357 206 357 201 358 211 358 206 358 211 359 210 359 206 359 128 360 212 360 207 360 213 361 203 361 207 361 212 362 213 362 207 362 146 363 214 363 208 363 211 364 201 364 208 364 214 365 211 365 208 365 215 366 148 366 209 366 203 367 213 367 209 367 213 368 215 368 209 368 210 369 131 369 136 369 133 370 212 370 128 370 145 371 214 371 146 371 215 372 149 372 148 372 216 373 131 373 210 373 211 374 216 374 210 374 133 375 217 375 212 375 217 376 213 376 212 376 145 377 218 377 214 377 218 378 211 378 214 378 219 379 149 379 215 379 213 380 219 380 215 380 220 381 131 381 216 381 211 382 221 382 216 382 221 383 220 383 216 383 133 384 222 384 217 384 223 385 213 385 217 385 222 386 223 386 217 386 145 387 224 387 218 387 221 388 211 388 218 388 224 389 221 389 218 389 225 390 149 390 219 390 213 391 223 391 219 391 223 392 225 392 219 392 220 393 132 393 131 393 132 394 222 394 133 394 150 395 224 395 145 395 225 396 150 396 149 396 226 397 132 397 220 397 221 398 226 398 220 398 222 399 132 399 226 399 221 400 223 400 226 400 223 398 222 398 226 398 150 401 227 401 224 401 227 402 221 402 224 402 150 403 225 403 227 403 223 404 221 404 227 404 225 405 223 405 227 405

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_collision_E3M5_scaled.dae b/URDFs/sr_description/meshes/components/forearm/forearm_collision_E3M5_scaled.dae new file mode 100644 index 0000000..6b3f42c --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_collision_E3M5_scaled.dae @@ -0,0 +1,120 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:27:23 + 2025-02-20T09:27:23 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + -13.11653 -65.92442 164.8893 -20.45978 -71.90862 156.5069 -6.898247 -74.44371 156.5069 6.898201 -74.44371 156.5069 -2.28882e-5 -67.21208 164.8893 -6.228134 -67.21208 164.8893 -2.28882e-5 -67.21208 125.6178 -13.11653 -65.92442 125.6178 -6.228134 -67.21208 125.6178 20.45974 -71.90862 156.5069 13.11649 -65.92442 164.8893 6.228096 -67.21208 164.8893 13.11649 -65.92442 125.6178 6.228096 -67.21208 125.6178 -25.73364 -62.11018 164.8893 -33.32458 -66.92477 156.5069 -18.47228 -64.92326 164.8893 -25.73364 -62.11018 125.6178 -18.47228 -64.92326 125.6178 33.32454 -66.92477 156.5069 25.7336 -62.11018 164.8893 18.47223 -64.92326 164.8893 25.7336 -62.11018 125.6178 18.47223 -64.92326 125.6178 -13.16862 -66.20303 -4.05312e-6 -2.28882e-5 -67.50003 -4.05312e-6 13.16857 -66.20303 -4.05312e-6 -2.28882e-5 -2.28882e-5 -4.05312e-6 -13.16862 -66.20303 182.8 -2.28882e-5 -67.50003 182.8 13.16857 -66.20303 182.8 -2.28882e-5 -2.28882e-5 182.8 -37.37076 -55.91385 164.8893 -45.05456 -59.66187 156.5069 -30.08736 -60.42354 164.8893 -37.37076 -55.91385 125.6178 -30.08736 -60.42354 125.6178 45.05451 -59.66187 156.5069 37.37072 -55.91385 164.8893 30.08732 -60.42354 164.8893 37.37072 -55.91385 125.6178 30.08732 -60.42354 125.6178 -25.83115 -62.36189 -4.05312e-6 25.83111 -62.36189 -4.05312e-6 -25.83115 -62.36189 182.8 25.83111 -62.36189 182.8 -37.50101 -56.12422 -4.05312e-6 37.50097 -56.12422 -4.05312e-6 -37.50101 -56.12422 182.8 37.50097 -56.12422 182.8 -47.58427 -47.57016 164.8893 -55.25025 -50.36726 156.5069 -40.67786 -53.86618 164.8893 -47.58427 -47.57016 125.6178 -40.67786 -53.86618 125.6178 55.2502 -50.36726 156.5069 47.58422 -47.57016 164.8893 40.67782 -53.86618 164.8893 47.58422 -47.57016 125.6178 40.67782 -53.86618 125.6178 -47.72973 -47.72973 -4.05312e-6 47.72968 -47.72973 -4.05312e-6 -47.72973 -47.72973 182.8 47.72968 -47.72973 182.8 -55.98424 -37.3953 164.8893 -63.56447 -39.35746 156.5069 -49.88312 -45.47447 164.8893 -55.98424 -37.3953 125.6178 -49.88312 -45.47447 125.6178 63.56443 -39.35746 156.5069 55.9842 -37.3953 164.8893 49.88308 -45.47447 164.8893 55.9842 -37.3953 125.6178 49.88308 -45.47447 125.6178 -56.12422 -37.50101 -4.05312e-6 56.12418 -37.50101 -4.05312e-6 -56.12422 -37.50101 182.8 56.12418 -37.50101 182.8 -62.24917 -25.77503 164.8893 -69.71408 -27.00739 156.5069 -57.38968 -35.53419 164.8893 -62.24917 -25.77503 125.6178 -57.38968 -35.53419 125.6178 69.71403 -27.00739 156.5069 62.24912 -25.77503 164.8893 57.38964 -35.53419 164.8893 62.24912 -25.77503 125.6178 57.38964 -35.53419 125.6178 -62.36189 -25.83115 -4.05312e-6 62.36185 -25.83115 -4.05312e-6 -62.36189 -25.83115 182.8 62.36185 -25.83115 182.8 -66.13816 -13.15016 164.8893 -73.48966 -13.73761 156.5069 -62.9419 -24.38384 164.8893 -66.13816 -13.15016 125.6178 -62.9419 -24.38384 125.6178 73.48962 -13.73761 156.5069 66.13812 -13.15016 164.8893 62.94186 -24.38384 164.8893 66.13812 -13.15016 125.6178 62.94186 -24.38384 125.6178 -66.20303 -13.16862 -4.05312e-6 66.20298 -13.16862 -4.05312e-6 -66.20303 -13.16862 182.8 66.20298 -13.16862 182.8 -66.35071 -12.40311 164.8893 -67.50003 -2.28882e-5 164.8893 -74.76263 -2.28882e-5 156.5069 -66.35071 -12.40311 125.6178 74.76258 -2.28882e-5 156.5069 66.35066 -12.40311 164.8893 66.35066 -12.40311 125.6178 67.49998 -2.28882e-5 125.6178 -67.50003 -2.28882e-5 -4.05312e-6 67.49998 -2.28882e-5 -4.05312e-6 -67.50003 -2.28882e-5 182.8 67.49998 -2.28882e-5 182.8 -67.50003 -2.28882e-5 125.6178 67.49998 -2.28882e-5 164.8893 -73.48966 13.73757 156.5069 73.48962 13.73757 156.5069 -66.35071 12.40307 125.6178 66.35066 12.40307 164.8893 -66.20303 13.16857 -4.05312e-6 56.12418 37.50097 -4.05312e-6 62.36185 25.83111 -4.05312e-6 66.20298 13.16857 -4.05312e-6 25.83111 62.36185 -4.05312e-6 37.50097 56.12418 -4.05312e-6 47.72968 47.72968 -4.05312e-6 -13.16862 66.20298 -4.05312e-6 -2.28882e-5 67.49998 -4.05312e-6 13.16857 66.20298 -4.05312e-6 -47.72973 47.72968 -4.05312e-6 -37.50101 56.12418 -4.05312e-6 -25.83115 62.36185 -4.05312e-6 -62.36189 25.83111 -4.05312e-6 -56.12422 37.50097 -4.05312e-6 66.35066 12.40307 125.6178 -66.35071 12.40307 164.8893 -66.20303 13.16857 182.8 -47.72973 47.72968 182.8 -56.12422 37.50097 182.8 -62.36189 25.83111 182.8 -13.16862 66.20298 182.8 -25.83115 62.36185 182.8 -37.50101 56.12418 182.8 25.83111 62.36185 182.8 13.16857 66.20298 182.8 -2.28882e-5 67.49998 182.8 56.12418 37.50097 182.8 47.72968 47.72968 182.8 37.50097 56.12418 182.8 66.20298 13.16857 182.8 62.36185 25.83111 182.8 -66.13816 13.15012 125.6178 66.13812 13.15012 125.6178 -66.13816 13.15012 164.8893 66.13812 13.15012 164.8893 -62.9419 24.38379 125.6178 -69.71408 27.00735 156.5069 62.94186 24.38379 125.6178 69.71403 27.00735 156.5069 -62.9419 24.38379 164.8893 62.94186 24.38379 164.8893 -62.24917 25.77498 125.6178 62.24912 25.77498 125.6178 -62.24917 25.77498 164.8893 62.24912 25.77498 164.8893 -57.38968 35.53415 125.6178 -63.56447 39.35742 156.5069 57.38964 35.53415 125.6178 63.56443 39.35742 156.5069 -57.38968 35.53415 164.8893 57.38964 35.53415 164.8893 -55.98424 37.39525 125.6178 55.9842 37.39525 125.6178 -55.98424 37.39525 164.8893 55.9842 37.39525 164.8893 -49.88312 45.47443 125.6178 -55.25025 50.36722 156.5069 49.88308 45.47443 125.6178 55.2502 50.36722 156.5069 -49.88312 45.47443 164.8893 49.88308 45.47443 164.8893 -47.58427 47.57012 125.6178 47.58422 47.57012 125.6178 -47.58427 47.57012 164.8893 47.58422 47.57012 164.8893 -40.67786 53.86614 125.6178 -45.05456 59.66183 156.5069 40.67782 53.86614 125.6178 45.05451 59.66183 156.5069 -40.67786 53.86614 164.8893 40.67782 53.86614 164.8893 -37.37076 55.91381 125.6178 37.37072 55.91381 125.6178 -37.37076 55.91381 164.8893 37.37072 55.91381 164.8893 -30.08736 60.4235 125.6178 -33.32458 66.92472 156.5069 30.08732 60.4235 125.6178 33.32454 66.92472 156.5069 -30.08736 60.4235 164.8893 30.08732 60.4235 164.8893 -25.73364 62.11014 125.6178 25.7336 62.11014 125.6178 -25.73364 62.11014 164.8893 25.7336 62.11014 164.8893 -18.47228 64.92321 125.6178 -20.45978 71.90858 156.5069 18.47223 64.92321 125.6178 20.45974 71.90858 156.5069 -18.47228 64.92321 164.8893 18.47223 64.92321 164.8893 -13.11653 65.92437 125.6178 13.11649 65.92437 125.6178 -13.11653 65.92437 164.8893 13.11649 65.92437 164.8893 -6.228134 67.21205 125.6178 -6.898247 74.44366 156.5069 6.228096 67.21205 125.6178 6.898201 74.44366 156.5069 -6.228134 67.21205 164.8893 6.228096 67.21205 164.8893 -2.28882e-5 67.21205 125.6178 -2.28882e-5 67.21205 164.8893 + + + + + + + + + + -0.1391299 -0.7442759 0.6532199 0 -0.7571679 0.6532204 0 -0.7571682 0.6532201 -0.1391289 -0.7442752 0.653221 0 -0.9736725 -0.2279521 -0.1789118 -0.9570939 -0.2279517 -0.1789123 -0.9570936 -0.2279523 0 -0.9736725 -0.2279518 0.1391299 -0.744276 0.6532198 0.139129 -0.7442755 0.6532206 0 -0.7571678 0.6532204 0.178912 -0.9570938 -0.2279517 0 -0.9736725 -0.2279521 0.1789124 -0.9570937 -0.2279521 -0.2735207 -0.7060382 0.6532202 -0.1391282 -0.7442755 0.6532208 -0.2735238 -0.7060368 0.6532204 -0.351731 -0.9079226 -0.227952 -0.3517323 -0.9079219 -0.2279523 -0.1789112 -0.9570938 -0.227952 0.2735206 -0.7060382 0.6532201 0.2735235 -0.7060368 0.6532205 0.1391265 -0.7442758 0.6532208 0.351731 -0.9079226 -0.227952 0.1789116 -0.9570938 -0.2279522 0.3517324 -0.9079219 -0.2279524 -0.09801763 -0.9951814 -0.002578377 0.09801763 -0.9951814 -0.002578377 0 -0.9999974 0.002292275 0 -0.9999974 0.002292156 0 0 -1 0 0 -1 -0.09800189 -0.9950219 0.01808094 0 -0.9998708 -0.01607441 0 -0.9998709 -0.01607495 0.09800201 -0.9950219 0.01808094 -6.86652e-7 0 1 0 0 1 -0.1837494 -0.9829707 0.002256214 0.1837494 -0.9829707 0.002256214 -0.1837271 -0.9828499 -0.01582217 0.1837271 -0.9828499 -0.01582217 -0.3985967 -0.6437571 0.653221 -0.2735221 -0.7060377 0.6532201 -0.3985971 -0.6437568 0.6532209 -0.5125729 -0.8278326 -0.2279522 -0.5125723 -0.827833 -0.2279522 -0.3517317 -0.9079222 -0.2279521 0.398597 -0.6437575 0.6532204 0.3985971 -0.6437568 0.6532209 0.2735199 -0.7060381 0.6532205 0.5125725 -0.827833 -0.2279521 0.3517314 -0.9079223 -0.227952 0.5125723 -0.827833 -0.2279522 -0.2902838 -0.9569373 -0.002506852 -0.1837483 -0.9829708 0.002256393 0 0 -1 0.2902836 -0.9569374 -0.002506852 0.1837487 -0.9829707 0.002256274 0 0 -1 -6.86652e-7 0 1 -0.2902398 -0.9567925 0.01757949 -0.1837258 -0.9828502 -0.01582336 0.1837263 -0.9828501 -0.015823 0.2902398 -0.9567925 0.01757949 -0.3612419 -0.9324697 0.002148807 0.3612416 -0.9324699 0.002148807 -0.361202 -0.9323658 -0.01506948 0.3612016 -0.932366 -0.01506948 -0.4713954 -0.8819188 -0.002363443 -0.3612411 -0.9324701 0.002148926 0 0 -1 0.4713955 -0.8819187 -0.002363443 0.3612411 -0.9324701 0.002148866 0 0 -1 2.74661e-7 0 1 -0.4713318 -0.8818003 0.01657378 -0.3612009 -0.9323663 -0.01506978 0.3612009 -0.9323663 -0.01507002 0.4713314 -0.8818004 0.01657402 -0.5264315 -0.8502154 0.001969695 0.5264311 -0.8502157 0.001969695 -0.5263824 -0.8501359 -0.01381343 0.526382 -0.8501361 -0.01381337 -0.5100999 -0.5595545 0.6532205 -0.3985978 -0.6437575 0.6532199 -0.5101016 -0.5595531 0.6532203 -0.6559591 -0.7195525 -0.2279518 -0.6559588 -0.7195526 -0.2279523 -0.5125713 -0.8278338 -0.227952 0.5101001 -0.5595539 0.6532207 0.510102 -0.5595536 0.6532196 0.398599 -0.6437564 0.6532202 0.6559593 -0.7195522 -0.227952 0.5125738 -0.8278321 -0.2279524 0.6559588 -0.7195526 -0.2279519 -0.6343917 -0.7730089 -0.002148389 -0.52643 -0.8502162 0.001969695 0.6343917 -0.7730089 -0.002148449 0.5264309 -0.8502156 0.001969695 0 0 -1 -0.6343212 -0.7729229 0.01506662 -0.5263808 -0.8501367 -0.01381349 0.5263827 -0.8501356 -0.01381331 0.6343215 -0.7729225 0.01506698 -0.6736947 -0.7390078 0.001718819 0.6736955 -0.7390071 0.001718819 -0.6736477 -0.7389544 -0.0120545 0.6736472 -0.7389547 -0.0120545 -0.6042332 -0.4562962 0.6532198 -0.5101044 -0.5595502 0.6532207 -0.6042314 -0.4562966 0.6532211 -0.7770069 -0.5867695 -0.2279517 -0.7770068 -0.5867695 -0.2279521 -0.6559615 -0.71955 -0.2279527 0.6042332 -0.4562966 0.6532196 0.6042325 -0.4562966 0.6532202 0.5101023 -0.5595532 0.6532197 0.7770071 -0.5867692 -0.2279517 0.6559591 -0.7195522 -0.2279524 0.7770067 -0.5867698 -0.2279517 -0.7730091 -0.6343924 -0.001861691 -0.6736971 -0.7390057 0.001718759 0.773009 -0.6343924 -0.001861751 0.6736934 -0.7390091 0.001718819 0 0 -1 -0.7729445 -0.6343393 0.01305621 -0.6736487 -0.7389534 -0.01205402 0.6736466 -0.7389553 -0.01205426 0.7729443 -0.6343395 0.01305651 -0.798016 -0.6026349 0.001396358 0.798016 -0.6026349 0.001396358 -0.7979782 -0.6026068 -0.009793162 0.7979785 -0.6026064 -0.009793162 -0.6777884 -0.3374995 0.6532205 -0.6042307 -0.4562947 0.6532232 -0.677789 -0.3374987 0.6532202 -0.8715952 -0.4340043 -0.2279521 -0.8715957 -0.4340035 -0.2279519 -0.7770096 -0.5867656 -0.2279525 0.6777881 -0.3374986 0.6532213 0.6777882 -0.3374994 0.6532208 0.6042317 -0.4562937 0.6532229 0.871596 -0.4340027 -0.227952 0.7770079 -0.5867677 -0.2279524 0.8715959 -0.4340029 -0.227952 -0.8819203 -0.4713962 -0.001503586 -0.7980167 -0.6026337 0.001396358 0.8819206 -0.4713958 -0.001503586 0.7980183 -0.6026316 0.001396358 0 0 -1 -0.8818718 -0.4713714 0.01054525 -0.7979809 -0.6026033 -0.009793162 0.7979809 -0.6026034 -0.009793341 0.8818722 -0.4713706 0.01054507 -0.8951629 -0.4457381 0.001002311 0.8951629 -0.4457381 0.00100243 -0.8951416 -0.4457266 -0.00702995 0.8951411 -0.4457276 -0.007030427 -0.7282632 -0.2072093 0.6532205 -0.67779 -0.3374937 0.6532219 -0.7282627 -0.2072093 0.6532211 -0.9365033 -0.2664576 -0.2279517 -0.936503 -0.266458 -0.2279522 -0.8715986 -0.4339971 -0.2279526 0.7282629 -0.2072092 0.6532208 0.7282638 -0.2072094 0.6532198 0.6777893 -0.3374996 0.6532195 0.9365029 -0.2664588 -0.227952 0.8715969 -0.4340009 -0.227952 0.9365032 -0.266458 -0.2279517 -0.9569398 -0.2902848 -0.001073896 -0.8951625 -0.4457389 0.001002371 0.9569401 -0.2902837 -0.001073896 0.8951585 -0.4457469 0.00100243 -0.9569134 -0.2902761 0.007531642 -0.8951388 -0.4457324 -0.007030189 0.8951387 -0.4457324 -0.007030546 0.9569134 -0.290276 0.00753194 -0.9618253 -0.2736635 5.36881e-4 0.9618253 -0.2736636 5.36881e-4 -0.9618187 -0.2736614 -0.003765404 0.961819 -0.2736604 -0.003765404 -0.7282683 -0.2071974 0.6532186 -0.7539383 -0.06986355 0.6532199 -0.753938 -0.06986314 0.6532203 -0.9695188 -0.08983969 -0.227952 -0.9365 -0.26647 -0.2279508 0.7539368 -0.0698623 0.6532217 0.7282666 -0.2071975 0.6532205 0.9365047 -0.2664517 -0.2279527 0.9695188 -0.08983945 -0.2279524 0.969519 -0.08983862 -0.227952 -0.9951846 -0.09801727 -5.72668e-4 -0.9618293 -0.27365 5.36875e-4 0.9951846 -0.09801727 -5.72611e-4 0.9618293 -0.27365 5.36876e-4 -0.9951768 -0.09801578 0.004016399 -0.9618163 -0.2736701 -0.003765344 0.9618209 -0.2736539 -0.003765344 0.9951767 -0.09801673 0.004015982 -0.995734 -0.09226989 0 -0.969519 -0.08983951 -0.2279518 0.9957342 -0.0922687 0 -0.9957342 -0.09226906 0 0.9957343 -0.09226799 0 0.7539386 -0.06986266 0.6532198 -0.9695189 0.08983963 -0.2279516 0.7539376 0.06986153 0.6532209 -0.9695188 0.08983945 -0.2279521 0.7539374 0.06986343 0.6532208 -0.995734 0.09226989 0 -0.9951846 0.09801733 -5.72676e-4 0 0 -1 0.9695188 0.08983945 -0.227952 -0.7539394 0.06986349 0.6532186 -0.753936 0.06986325 0.6532226 0.9695188 0.08983856 -0.2279525 -0.9957342 0.09226906 0 -0.9951768 0.09801596 0.004016458 1.09864e-6 0 1 -1.09864e-6 0 1 2.19729e-6 0 1 -2.19729e-6 0 1 -2.19729e-6 0 1 0.9951846 0.09801733 -5.72618e-4 0.9957342 0.09226864 0 0.9957343 0.09226799 0 0.9951767 0.09801697 0.004016041 -0.9618293 0.27365 5.36858e-4 -0.9365 0.26647 -0.2279507 0.9618293 0.27365 5.36848e-4 0.9365049 0.2664518 -0.2279521 -0.9618164 0.2736699 -0.003765225 -0.7282683 0.2071974 0.6532186 0.961821 0.2736537 -0.003765165 0.7282677 0.2071978 0.6532191 -0.9618253 0.2736638 5.36853e-4 -0.9365033 0.2664576 -0.2279517 -0.936503 0.2664583 -0.2279523 0.9618253 0.2736638 5.36855e-4 0.9365029 0.2664587 -0.227952 0.9365031 0.2664584 -0.2279518 -0.9618186 0.2736617 -0.003765225 -0.7282631 0.2072093 0.6532206 -0.7282648 0.2072088 0.653219 0.9618189 0.2736607 -0.003765165 0.7282629 0.2072092 0.653221 0.7282646 0.2072093 0.6532191 -0.9569399 0.2902846 -0.001073837 0.9569402 0.2902835 -0.001073896 -0.9569134 0.2902756 0.007531523 0.9569134 0.290276 0.007531821 -0.8951622 0.4457395 0.00100243 -0.8715983 0.4339976 -0.227953 0.8951583 0.4457474 0.00100243 0.8715962 0.4340018 -0.2279531 -0.8951387 0.4457324 -0.007030427 -0.67779 0.3374937 0.6532219 0.8951387 0.4457324 -0.007030725 0.6777889 0.3374994 0.6532201 -0.8951632 0.4457377 0.001002371 -0.871595 0.4340044 -0.2279523 -0.8715959 0.4340029 -0.2279519 0.8951632 0.4457377 0.00100243 0.8715959 0.4340029 -0.2279523 0.8715961 0.4340026 -0.2279521 -0.8951418 0.4457261 -0.007030248 -0.6777881 0.3374995 0.6532207 -0.6777887 0.3374986 0.6532207 0.8951412 0.4457273 -0.007030665 0.6777879 0.3374985 0.6532216 0.6777896 0.3374986 0.6532197 -0.8819203 0.4713963 -0.001503646 0.8819205 0.4713959 -0.001503586 -0.8818721 0.4713711 0.01054531 0.8818727 0.4713698 0.01054519 -0.7980149 0.6026361 0.001396417 -0.7770075 0.5867681 -0.227953 0.7980166 0.602634 0.001396417 0.7770062 0.5867701 -0.2279521 -0.7979792 0.6026055 -0.0097934 -0.6042317 0.4562954 0.6532219 0.7979792 0.6026055 -0.0097934 0.6042321 0.4562957 0.6532211 -0.7980163 0.6026343 0.001396417 -0.7770071 0.5867692 -0.2279518 -0.7770069 0.5867693 -0.2279523 0.7980163 0.6026343 0.001396417 0.777007 0.5867694 -0.227952 0.7770069 0.5867695 -0.2279518 -0.7979788 0.6026061 -0.009793519 -0.6042327 0.4562962 0.6532202 -0.6042312 0.4562965 0.6532213 0.7979792 0.6026055 -0.009793579 0.6042328 0.4562963 0.65322 0.6042329 0.456296 0.6532202 -0.7730088 0.6343926 -0.001861751 0.7730088 0.6343926 -0.00186181 -0.7729442 0.6343398 0.01305675 0.7729439 0.6343401 0.01305705 -0.6736964 0.7390062 0.001718759 -0.6559613 0.7195504 -0.2279522 0.6736928 0.7390096 0.001718759 0.6559592 0.7195523 -0.2279518 -0.6736482 0.7389539 -0.01205378 -0.510105 0.5595509 0.6532196 0.673646 0.7389559 -0.01205402 0.5101017 0.5595545 0.6532191 -0.6736947 0.7390078 0.001718759 -0.6559591 0.7195525 -0.2279518 -0.6559588 0.7195526 -0.2279524 0.6736956 0.7390071 0.001718759 0.6559595 0.719552 -0.2279519 0.6559588 0.7195526 -0.227952 -0.6736477 0.7389544 -0.01205408 -0.5100999 0.5595545 0.6532205 -0.5101014 0.559553 0.6532205 0.6736474 0.7389547 -0.01205402 0.5101001 0.5595539 0.6532207 0.5101019 0.5595535 0.6532198 -0.6343923 0.7730085 -0.002148389 0.6343922 0.7730084 -0.002148449 -0.6343213 0.7729228 0.01506644 0.6343215 0.7729225 0.01506698 -0.52643 0.8502162 0.001969695 -0.5125717 0.8278335 -0.2279519 0.5264309 0.8502157 0.001969695 0.5125738 0.8278321 -0.2279521 -0.5263805 0.850137 -0.01381331 -0.3985977 0.6437572 0.6532203 0.526382 0.850136 -0.01381331 0.3985987 0.6437561 0.6532207 -0.5264318 0.8502151 0.001969695 -0.5125725 0.8278329 -0.2279523 -0.5125723 0.827833 -0.2279519 0.5264314 0.8502154 0.001969695 0.5125727 0.8278329 -0.2279521 0.5125723 0.827833 -0.2279519 -0.5263824 0.8501359 -0.01381343 -0.3985967 0.6437571 0.653221 -0.3985995 0.6437566 0.6532197 0.526382 0.8501359 -0.01381337 0.398597 0.6437575 0.6532204 0.3985985 0.6437569 0.6532201 -0.4713952 0.8819189 -0.002363443 0.4713953 0.8819189 -0.002363443 -0.4713324 0.8818 0.01657402 0.4713323 0.8818001 0.01657402 -0.3612405 0.9324703 0.002148926 -0.3517306 0.9079226 -0.2279518 0.3612404 0.9324703 0.002148926 0.3517307 0.9079227 -0.2279515 -0.3612 0.9323666 -0.01506996 -0.2735181 0.7060394 0.65322 0.3612003 0.9323665 -0.01507002 0.2735202 0.7060387 0.6532199 -0.3612415 0.9324699 0.002148866 -0.3517318 0.9079221 -0.2279524 -0.3517314 0.9079222 -0.2279523 0.3612412 0.93247 0.002148807 0.3517316 0.9079222 -0.2279524 0.3517315 0.9079223 -0.2279523 -0.3612017 0.932366 -0.01506948 -0.2735204 0.7060374 0.6532211 -0.2735214 0.706038 0.6532201 0.3612011 0.9323663 -0.01506966 0.2735203 0.7060375 0.653221 0.2735217 0.7060375 0.6532205 -0.2902836 0.9569374 -0.002506852 0.2902833 0.9569375 -0.002506852 -0.2902394 0.9567927 0.01757949 0.2902393 0.9567927 0.01757949 -0.1837483 0.9829708 0.002256393 -0.1789113 0.9570938 -0.227952 0.1837487 0.9829707 0.002256333 0.1789116 0.9570938 -0.2279522 -0.183726 0.9828502 -0.0158236 -0.1391282 0.7442755 0.6532208 0.1837263 0.9828501 -0.015823 0.139127 0.7442757 0.6532208 -0.1837515 0.9829702 0.002256453 -0.1789113 0.9570939 -0.227952 -0.178914 0.9570934 -0.2279517 0.1837515 0.9829702 0.002256393 0.1789112 0.9570939 -0.2279521 0.1789145 0.9570934 -0.2279515 -0.1837292 0.9828495 -0.01582413 -0.1391291 0.7442756 0.6532205 -0.1391322 0.7442757 0.6532198 0.1837291 0.9828495 -0.01582378 0.1391283 0.7442758 0.6532204 0.1391311 0.7442761 0.6532195 -0.09801703 0.9951815 -0.002578675 0.09801709 0.9951814 -0.002578616 -0.09800124 0.9950221 0.01808273 0.0980013 0.9950221 0.01808249 0 0.9999974 0.002292096 0 0.9736726 -0.2279512 0 0.9999974 0.002292096 0 0.9736725 -0.2279515 0 0.9998708 -0.01607388 0 0.757169 0.6532191 0 0.9998709 -0.01607388 0 0.7571688 0.6532195 0 0.7571691 0.6532189 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 2 1 4 2 5 2 2 2 5 3 0 3 2 3 6 4 3 4 2 4 1 5 7 5 2 5 7 6 8 6 2 6 8 7 6 7 2 7 9 8 10 8 3 8 10 9 11 9 3 9 11 10 4 10 3 10 12 11 9 11 3 11 6 12 13 12 3 12 13 13 12 13 3 13 14 14 15 14 1 14 0 15 16 15 1 15 16 16 14 16 1 16 15 17 17 17 1 17 17 18 18 18 1 18 18 19 7 19 1 19 19 20 20 20 9 20 20 21 21 21 9 21 21 22 10 22 9 22 22 23 19 23 9 23 12 24 23 24 9 24 23 25 22 25 9 25 8 26 24 26 25 26 26 27 13 27 25 27 13 28 6 28 25 28 6 29 8 29 25 29 27 30 26 30 25 30 24 31 27 31 25 31 28 32 5 32 29 32 5 33 4 33 29 33 4 34 11 34 29 34 11 35 30 35 29 35 31 36 28 36 29 36 30 37 31 37 29 37 7 38 24 38 8 38 26 39 12 39 13 39 28 40 0 40 5 40 10 41 30 41 11 41 32 42 33 42 15 42 14 43 34 43 15 43 34 44 32 44 15 44 33 45 35 45 15 45 35 46 36 46 15 46 36 47 17 47 15 47 37 48 38 48 19 48 38 49 39 49 19 49 39 50 20 50 19 50 40 51 37 51 19 51 22 52 41 52 19 52 41 53 40 53 19 53 18 54 42 54 24 54 7 55 18 55 24 55 42 56 27 56 24 56 43 57 23 57 26 57 23 58 12 58 26 58 27 59 43 59 26 59 31 60 44 60 28 60 44 61 16 61 28 61 16 62 0 62 28 62 45 37 31 37 30 37 10 63 21 63 30 63 21 64 45 64 30 64 17 65 42 65 18 65 43 66 22 66 23 66 44 67 14 67 16 67 20 68 45 68 21 68 36 69 46 69 42 69 17 70 36 70 42 70 46 71 27 71 42 71 47 72 41 72 43 72 41 73 22 73 43 73 27 74 47 74 43 74 31 75 48 75 44 75 48 76 34 76 44 76 34 77 14 77 44 77 49 37 31 37 45 37 20 78 39 78 45 78 39 79 49 79 45 79 35 80 46 80 36 80 47 81 40 81 41 81 48 82 32 82 34 82 38 83 49 83 39 83 50 84 51 84 33 84 32 85 52 85 33 85 52 86 50 86 33 86 51 87 53 87 33 87 53 88 54 88 33 88 54 89 35 89 33 89 55 90 56 90 37 90 56 91 57 91 37 91 57 92 38 92 37 92 58 93 55 93 37 93 40 94 59 94 37 94 59 95 58 95 37 95 54 96 60 96 46 96 35 97 54 97 46 97 60 71 27 71 46 71 61 98 59 98 47 98 59 99 40 99 47 99 27 100 61 100 47 100 31 37 62 37 48 37 62 101 52 101 48 101 52 102 32 102 48 102 63 37 31 37 49 37 38 103 57 103 49 103 57 104 63 104 49 104 53 105 60 105 54 105 61 106 58 106 59 106 62 107 50 107 52 107 56 108 63 108 57 108 64 109 65 109 51 109 50 110 66 110 51 110 66 111 64 111 51 111 65 112 67 112 51 112 67 113 68 113 51 113 68 114 53 114 51 114 69 115 70 115 55 115 70 116 71 116 55 116 71 117 56 117 55 117 72 118 69 118 55 118 58 119 73 119 55 119 73 120 72 120 55 120 68 121 74 121 60 121 53 122 68 122 60 122 74 71 27 71 60 71 75 123 73 123 61 123 73 124 58 124 61 124 27 125 75 125 61 125 31 75 76 75 62 75 76 126 66 126 62 126 66 127 50 127 62 127 77 37 31 37 63 37 56 128 71 128 63 128 71 129 77 129 63 129 67 130 74 130 68 130 75 131 72 131 73 131 76 132 64 132 66 132 70 133 77 133 71 133 78 134 79 134 65 134 64 135 80 135 65 135 80 136 78 136 65 136 79 137 81 137 65 137 81 138 82 138 65 138 82 139 67 139 65 139 83 140 84 140 69 140 84 141 85 141 69 141 85 142 70 142 69 142 86 143 83 143 69 143 72 144 87 144 69 144 87 145 86 145 69 145 82 146 88 146 74 146 67 147 82 147 74 147 88 71 27 71 74 71 89 148 87 148 75 148 87 149 72 149 75 149 27 150 89 150 75 150 31 37 90 37 76 37 90 151 80 151 76 151 80 152 64 152 76 152 91 37 31 37 77 37 70 153 85 153 77 153 85 154 91 154 77 154 81 155 88 155 82 155 89 156 86 156 87 156 90 157 78 157 80 157 84 158 91 158 85 158 92 159 93 159 79 159 78 160 94 160 79 160 94 161 92 161 79 161 93 162 95 162 79 162 95 163 96 163 79 163 96 164 81 164 79 164 97 165 98 165 83 165 98 166 99 166 83 166 99 167 84 167 83 167 100 168 97 168 83 168 86 169 101 169 83 169 101 170 100 170 83 170 96 171 102 171 88 171 81 172 96 172 88 172 102 71 27 71 88 71 103 173 101 173 89 173 101 174 86 174 89 174 27 71 103 71 89 71 31 37 104 37 90 37 104 175 94 175 90 175 94 176 78 176 90 176 105 37 31 37 91 37 84 177 99 177 91 177 99 178 105 178 91 178 95 179 102 179 96 179 103 180 100 180 101 180 104 181 92 181 94 181 98 182 105 182 99 182 92 183 106 183 93 183 106 184 107 184 93 184 107 185 108 185 93 185 108 186 109 186 93 186 109 187 95 187 93 187 110 188 111 188 97 188 111 189 98 189 97 189 100 190 112 190 97 190 112 191 113 191 97 191 113 192 110 192 97 192 109 193 114 193 102 193 95 194 109 194 102 194 114 71 27 71 102 71 115 195 112 195 103 195 112 196 100 196 103 196 27 71 115 71 103 71 31 37 116 37 104 37 116 197 106 197 104 197 106 198 92 198 104 198 117 37 31 37 105 37 98 199 111 199 105 199 111 200 117 200 105 200 118 201 114 201 109 201 108 202 118 202 109 202 115 203 113 203 112 203 116 204 107 204 106 204 119 205 117 205 111 205 110 206 119 206 111 206 120 207 118 207 108 207 121 208 119 208 110 208 120 209 122 209 118 209 121 210 123 210 119 210 124 71 27 71 114 71 118 211 122 211 114 211 122 212 124 212 114 212 125 71 126 71 27 71 126 71 127 71 27 71 127 71 115 71 27 71 128 213 129 213 27 213 129 71 130 71 27 71 130 71 125 71 27 71 131 71 132 71 27 71 132 71 133 71 27 71 133 71 128 71 27 71 134 71 135 71 27 71 135 71 136 71 27 71 136 71 131 71 27 71 124 71 137 71 27 71 137 71 138 71 27 71 138 71 134 71 27 71 139 214 110 214 113 214 107 215 140 215 108 215 140 216 120 216 108 216 139 217 121 217 110 217 116 218 140 218 107 218 31 37 141 37 116 37 141 219 140 219 116 219 142 220 143 220 31 220 143 221 144 221 31 221 144 37 141 37 31 37 145 37 146 37 31 37 146 222 147 222 31 222 147 223 142 223 31 223 148 37 149 37 31 37 149 37 150 37 31 37 150 37 145 37 31 37 151 224 152 224 31 224 152 222 153 222 31 222 153 37 148 37 31 37 117 37 154 37 31 37 154 37 155 37 31 37 155 37 151 37 31 37 127 225 139 225 115 225 139 226 113 226 115 226 123 227 117 227 119 227 123 228 154 228 117 228 156 229 124 229 122 229 120 230 156 230 122 230 127 231 157 231 139 231 157 232 121 232 139 232 141 233 158 233 140 233 158 234 120 234 140 234 159 235 154 235 123 235 121 236 159 236 123 236 160 237 124 237 156 237 120 238 161 238 156 238 161 239 160 239 156 239 127 240 162 240 157 240 163 241 121 241 157 241 162 242 163 242 157 242 141 243 164 243 158 243 161 244 120 244 158 244 164 245 161 245 158 245 165 246 154 246 159 246 121 247 163 247 159 247 163 248 165 248 159 248 160 249 137 249 124 249 126 250 162 250 127 250 144 251 164 251 141 251 165 252 155 252 154 252 166 253 137 253 160 253 161 254 166 254 160 254 126 255 167 255 162 255 167 256 163 256 162 256 144 257 168 257 164 257 168 258 161 258 164 258 169 259 155 259 165 259 163 260 169 260 165 260 170 261 137 261 166 261 161 262 171 262 166 262 171 263 170 263 166 263 126 264 172 264 167 264 173 265 163 265 167 265 172 266 173 266 167 266 144 267 174 267 168 267 171 268 161 268 168 268 174 269 171 269 168 269 175 270 155 270 169 270 163 271 173 271 169 271 173 272 175 272 169 272 170 273 138 273 137 273 125 274 172 274 126 274 143 275 174 275 144 275 175 276 151 276 155 276 176 277 138 277 170 277 171 278 176 278 170 278 125 279 177 279 172 279 177 280 173 280 172 280 143 281 178 281 174 281 178 282 171 282 174 282 179 283 151 283 175 283 173 284 179 284 175 284 180 285 138 285 176 285 171 286 181 286 176 286 181 287 180 287 176 287 125 288 182 288 177 288 183 289 173 289 177 289 182 290 183 290 177 290 143 291 184 291 178 291 181 292 171 292 178 292 184 293 181 293 178 293 185 294 151 294 179 294 173 295 183 295 179 295 183 296 185 296 179 296 180 297 134 297 138 297 130 298 182 298 125 298 142 299 184 299 143 299 185 300 152 300 151 300 186 301 134 301 180 301 181 302 186 302 180 302 130 303 187 303 182 303 187 304 183 304 182 304 142 305 188 305 184 305 188 306 181 306 184 306 189 307 152 307 185 307 183 308 189 308 185 308 190 309 134 309 186 309 181 310 191 310 186 310 191 311 190 311 186 311 130 312 192 312 187 312 193 313 183 313 187 313 192 314 193 314 187 314 142 315 194 315 188 315 191 316 181 316 188 316 194 317 191 317 188 317 195 318 152 318 189 318 183 319 193 319 189 319 193 320 195 320 189 320 190 321 135 321 134 321 129 322 192 322 130 322 147 323 194 323 142 323 195 324 153 324 152 324 196 325 135 325 190 325 191 326 196 326 190 326 129 327 197 327 192 327 197 328 193 328 192 328 147 329 198 329 194 329 198 330 191 330 194 330 199 331 153 331 195 331 193 332 199 332 195 332 200 333 135 333 196 333 191 334 201 334 196 334 201 335 200 335 196 335 129 336 202 336 197 336 203 337 193 337 197 337 202 338 203 338 197 338 147 339 204 339 198 339 201 340 191 340 198 340 204 341 201 341 198 341 205 342 153 342 199 342 193 343 203 343 199 343 203 344 205 344 199 344 200 345 136 345 135 345 128 346 202 346 129 346 146 347 204 347 147 347 205 348 148 348 153 348 206 349 136 349 200 349 201 350 206 350 200 350 128 351 207 351 202 351 207 352 203 352 202 352 146 353 208 353 204 353 208 354 201 354 204 354 209 355 148 355 205 355 203 356 209 356 205 356 210 357 136 357 206 357 201 358 211 358 206 358 211 359 210 359 206 359 128 360 212 360 207 360 213 361 203 361 207 361 212 362 213 362 207 362 146 363 214 363 208 363 211 364 201 364 208 364 214 365 211 365 208 365 215 366 148 366 209 366 203 367 213 367 209 367 213 368 215 368 209 368 210 369 131 369 136 369 133 370 212 370 128 370 145 371 214 371 146 371 215 372 149 372 148 372 216 373 131 373 210 373 211 374 216 374 210 374 133 375 217 375 212 375 217 376 213 376 212 376 145 377 218 377 214 377 218 378 211 378 214 378 219 379 149 379 215 379 213 380 219 380 215 380 220 381 131 381 216 381 211 382 221 382 216 382 221 383 220 383 216 383 133 384 222 384 217 384 223 385 213 385 217 385 222 386 223 386 217 386 145 387 224 387 218 387 221 388 211 388 218 388 224 389 221 389 218 389 225 390 149 390 219 390 213 391 223 391 219 391 223 392 225 392 219 392 220 393 132 393 131 393 132 394 222 394 133 394 150 395 224 395 145 395 225 396 150 396 149 396 226 397 132 397 220 397 221 398 226 398 220 398 222 399 132 399 226 399 221 400 223 400 226 400 223 398 222 398 226 398 150 401 227 401 224 401 227 402 221 402 224 402 150 403 225 403 227 403 223 404 221 404 227 404 225 405 223 405 227 405

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/forearm/forearm_collision_E4.dae b/URDFs/sr_description/meshes/components/forearm/forearm_collision_E4.dae new file mode 100644 index 0000000..749854f --- /dev/null +++ b/URDFs/sr_description/meshes/components/forearm/forearm_collision_E4.dae @@ -0,0 +1,83 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:40:38 + 2022-02-10T09:40:38 + + Z_UP + + + + + + + -13.11653 -65.92442 164.8893 -20.45978 -71.90862 156.5069 -6.898247 -74.44371 156.5069 6.898201 -74.44371 156.5069 -2.28882e-5 -67.21208 164.8893 -6.228134 -67.21208 164.8893 -2.28882e-5 -67.21208 125.6178 -13.11653 -65.92442 125.6178 -6.228134 -67.21208 125.6178 20.45974 -71.90862 156.5069 13.11649 -65.92442 164.8893 6.228096 -67.21208 164.8893 13.11649 -65.92442 125.6178 6.228096 -67.21208 125.6178 -25.73364 -62.11018 164.8893 -33.32458 -66.92477 156.5069 -18.47228 -64.92326 164.8893 -25.73364 -62.11018 125.6178 -18.47228 -64.92326 125.6178 33.32454 -66.92477 156.5069 25.7336 -62.11018 164.8893 18.47223 -64.92326 164.8893 25.7336 -62.11018 125.6178 18.47223 -64.92326 125.6178 -13.16862 -66.20303 -4.05312e-6 -2.28882e-5 -67.50003 -4.05312e-6 13.16857 -66.20303 -4.05312e-6 -2.28882e-5 -2.28882e-5 -4.05312e-6 -13.16862 -66.20303 182.8 -2.28882e-5 -67.50003 182.8 13.16857 -66.20303 182.8 -2.28882e-5 -2.28882e-5 182.8 -37.37076 -55.91385 164.8893 -45.05456 -59.66187 156.5069 -30.08736 -60.42354 164.8893 -37.37076 -55.91385 125.6178 -30.08736 -60.42354 125.6178 45.05451 -59.66187 156.5069 37.37072 -55.91385 164.8893 30.08732 -60.42354 164.8893 37.37072 -55.91385 125.6178 30.08732 -60.42354 125.6178 -25.83115 -62.36189 -4.05312e-6 25.83111 -62.36189 -4.05312e-6 -25.83115 -62.36189 182.8 25.83111 -62.36189 182.8 -37.50101 -56.12422 -4.05312e-6 37.50097 -56.12422 -4.05312e-6 -37.50101 -56.12422 182.8 37.50097 -56.12422 182.8 -47.58427 -47.57016 164.8893 -55.25025 -50.36726 156.5069 -40.67786 -53.86618 164.8893 -47.58427 -47.57016 125.6178 -40.67786 -53.86618 125.6178 55.2502 -50.36726 156.5069 47.58422 -47.57016 164.8893 40.67782 -53.86618 164.8893 47.58422 -47.57016 125.6178 40.67782 -53.86618 125.6178 -47.72973 -47.72973 -4.05312e-6 47.72968 -47.72973 -4.05312e-6 -47.72973 -47.72973 182.8 47.72968 -47.72973 182.8 -55.98424 -37.3953 164.8893 -63.56447 -39.35746 156.5069 -49.88312 -45.47447 164.8893 -55.98424 -37.3953 125.6178 -49.88312 -45.47447 125.6178 63.56443 -39.35746 156.5069 55.9842 -37.3953 164.8893 49.88308 -45.47447 164.8893 55.9842 -37.3953 125.6178 49.88308 -45.47447 125.6178 -56.12422 -37.50101 -4.05312e-6 56.12418 -37.50101 -4.05312e-6 -56.12422 -37.50101 182.8 56.12418 -37.50101 182.8 -62.24917 -25.77503 164.8893 -69.71408 -27.00739 156.5069 -57.38968 -35.53419 164.8893 -62.24917 -25.77503 125.6178 -57.38968 -35.53419 125.6178 69.71403 -27.00739 156.5069 62.24912 -25.77503 164.8893 57.38964 -35.53419 164.8893 62.24912 -25.77503 125.6178 57.38964 -35.53419 125.6178 -62.36189 -25.83115 -4.05312e-6 62.36185 -25.83115 -4.05312e-6 -62.36189 -25.83115 182.8 62.36185 -25.83115 182.8 -66.13816 -13.15016 164.8893 -73.48966 -13.73761 156.5069 -62.9419 -24.38384 164.8893 -66.13816 -13.15016 125.6178 -62.9419 -24.38384 125.6178 73.48962 -13.73761 156.5069 66.13812 -13.15016 164.8893 62.94186 -24.38384 164.8893 66.13812 -13.15016 125.6178 62.94186 -24.38384 125.6178 -66.20303 -13.16862 -4.05312e-6 66.20298 -13.16862 -4.05312e-6 -66.20303 -13.16862 182.8 66.20298 -13.16862 182.8 -66.35071 -12.40311 164.8893 -67.50003 -2.28882e-5 164.8893 -74.76263 -2.28882e-5 156.5069 -66.35071 -12.40311 125.6178 74.76258 -2.28882e-5 156.5069 66.35066 -12.40311 164.8893 66.35066 -12.40311 125.6178 67.49998 -2.28882e-5 125.6178 -67.50003 -2.28882e-5 -4.05312e-6 67.49998 -2.28882e-5 -4.05312e-6 -67.50003 -2.28882e-5 182.8 67.49998 -2.28882e-5 182.8 -67.50003 -2.28882e-5 125.6178 67.49998 -2.28882e-5 164.8893 -73.48966 13.73757 156.5069 73.48962 13.73757 156.5069 -66.35071 12.40307 125.6178 66.35066 12.40307 164.8893 -66.20303 13.16857 -4.05312e-6 56.12418 37.50097 -4.05312e-6 62.36185 25.83111 -4.05312e-6 66.20298 13.16857 -4.05312e-6 25.83111 62.36185 -4.05312e-6 37.50097 56.12418 -4.05312e-6 47.72968 47.72968 -4.05312e-6 -13.16862 66.20298 -4.05312e-6 -2.28882e-5 67.49998 -4.05312e-6 13.16857 66.20298 -4.05312e-6 -47.72973 47.72968 -4.05312e-6 -37.50101 56.12418 -4.05312e-6 -25.83115 62.36185 -4.05312e-6 -62.36189 25.83111 -4.05312e-6 -56.12422 37.50097 -4.05312e-6 66.35066 12.40307 125.6178 -66.35071 12.40307 164.8893 -66.20303 13.16857 182.8 -47.72973 47.72968 182.8 -56.12422 37.50097 182.8 -62.36189 25.83111 182.8 -13.16862 66.20298 182.8 -25.83115 62.36185 182.8 -37.50101 56.12418 182.8 25.83111 62.36185 182.8 13.16857 66.20298 182.8 -2.28882e-5 67.49998 182.8 56.12418 37.50097 182.8 47.72968 47.72968 182.8 37.50097 56.12418 182.8 66.20298 13.16857 182.8 62.36185 25.83111 182.8 -66.13816 13.15012 125.6178 66.13812 13.15012 125.6178 -66.13816 13.15012 164.8893 66.13812 13.15012 164.8893 -62.9419 24.38379 125.6178 -69.71408 27.00735 156.5069 62.94186 24.38379 125.6178 69.71403 27.00735 156.5069 -62.9419 24.38379 164.8893 62.94186 24.38379 164.8893 -62.24917 25.77498 125.6178 62.24912 25.77498 125.6178 -62.24917 25.77498 164.8893 62.24912 25.77498 164.8893 -57.38968 35.53415 125.6178 -63.56447 39.35742 156.5069 57.38964 35.53415 125.6178 63.56443 39.35742 156.5069 -57.38968 35.53415 164.8893 57.38964 35.53415 164.8893 -55.98424 37.39525 125.6178 55.9842 37.39525 125.6178 -55.98424 37.39525 164.8893 55.9842 37.39525 164.8893 -49.88312 45.47443 125.6178 -55.25025 50.36722 156.5069 49.88308 45.47443 125.6178 55.2502 50.36722 156.5069 -49.88312 45.47443 164.8893 49.88308 45.47443 164.8893 -47.58427 47.57012 125.6178 47.58422 47.57012 125.6178 -47.58427 47.57012 164.8893 47.58422 47.57012 164.8893 -40.67786 53.86614 125.6178 -45.05456 59.66183 156.5069 40.67782 53.86614 125.6178 45.05451 59.66183 156.5069 -40.67786 53.86614 164.8893 40.67782 53.86614 164.8893 -37.37076 55.91381 125.6178 37.37072 55.91381 125.6178 -37.37076 55.91381 164.8893 37.37072 55.91381 164.8893 -30.08736 60.4235 125.6178 -33.32458 66.92472 156.5069 30.08732 60.4235 125.6178 33.32454 66.92472 156.5069 -30.08736 60.4235 164.8893 30.08732 60.4235 164.8893 -25.73364 62.11014 125.6178 25.7336 62.11014 125.6178 -25.73364 62.11014 164.8893 25.7336 62.11014 164.8893 -18.47228 64.92321 125.6178 -20.45978 71.90858 156.5069 18.47223 64.92321 125.6178 20.45974 71.90858 156.5069 -18.47228 64.92321 164.8893 18.47223 64.92321 164.8893 -13.11653 65.92437 125.6178 13.11649 65.92437 125.6178 -13.11653 65.92437 164.8893 13.11649 65.92437 164.8893 -6.228134 67.21205 125.6178 -6.898247 74.44366 156.5069 6.228096 67.21205 125.6178 6.898201 74.44366 156.5069 -6.228134 67.21205 164.8893 6.228096 67.21205 164.8893 -2.28882e-5 67.21205 125.6178 -2.28882e-5 67.21205 164.8893 + + + + + + + + + + -0.1391299 -0.7442759 0.6532199 0 -0.7571679 0.6532204 0 -0.7571682 0.6532201 -0.1391289 -0.7442752 0.653221 0 -0.9736725 -0.2279521 -0.1789118 -0.9570939 -0.2279517 -0.1789123 -0.9570936 -0.2279523 0 -0.9736725 -0.2279518 0.1391299 -0.744276 0.6532198 0.139129 -0.7442755 0.6532206 0 -0.7571678 0.6532204 0.178912 -0.9570938 -0.2279517 0 -0.9736725 -0.2279521 0.1789124 -0.9570937 -0.2279521 -0.2735207 -0.7060382 0.6532202 -0.1391282 -0.7442755 0.6532208 -0.2735238 -0.7060368 0.6532204 -0.351731 -0.9079226 -0.227952 -0.3517323 -0.9079219 -0.2279523 -0.1789112 -0.9570938 -0.227952 0.2735206 -0.7060382 0.6532201 0.2735235 -0.7060368 0.6532205 0.1391265 -0.7442758 0.6532208 0.351731 -0.9079226 -0.227952 0.1789116 -0.9570938 -0.2279522 0.3517324 -0.9079219 -0.2279524 -0.09801763 -0.9951814 -0.002578377 0.09801763 -0.9951814 -0.002578377 0 -0.9999974 0.002292275 0 -0.9999974 0.002292156 0 0 -1 0 0 -1 -0.09800189 -0.9950219 0.01808094 0 -0.9998708 -0.01607441 0 -0.9998709 -0.01607495 0.09800201 -0.9950219 0.01808094 -6.86652e-7 0 1 0 0 1 -0.1837494 -0.9829707 0.002256214 0.1837494 -0.9829707 0.002256214 -0.1837271 -0.9828499 -0.01582217 0.1837271 -0.9828499 -0.01582217 -0.3985967 -0.6437571 0.653221 -0.2735221 -0.7060377 0.6532201 -0.3985971 -0.6437568 0.6532209 -0.5125729 -0.8278326 -0.2279522 -0.5125723 -0.827833 -0.2279522 -0.3517317 -0.9079222 -0.2279521 0.398597 -0.6437575 0.6532204 0.3985971 -0.6437568 0.6532209 0.2735199 -0.7060381 0.6532205 0.5125725 -0.827833 -0.2279521 0.3517314 -0.9079223 -0.227952 0.5125723 -0.827833 -0.2279522 -0.2902838 -0.9569373 -0.002506852 -0.1837483 -0.9829708 0.002256393 0 0 -1 0.2902836 -0.9569374 -0.002506852 0.1837487 -0.9829707 0.002256274 0 0 -1 -6.86652e-7 0 1 -0.2902398 -0.9567925 0.01757949 -0.1837258 -0.9828502 -0.01582336 0.1837263 -0.9828501 -0.015823 0.2902398 -0.9567925 0.01757949 -0.3612419 -0.9324697 0.002148807 0.3612416 -0.9324699 0.002148807 -0.361202 -0.9323658 -0.01506948 0.3612016 -0.932366 -0.01506948 -0.4713954 -0.8819188 -0.002363443 -0.3612411 -0.9324701 0.002148926 0 0 -1 0.4713955 -0.8819187 -0.002363443 0.3612411 -0.9324701 0.002148866 0 0 -1 2.74661e-7 0 1 -0.4713318 -0.8818003 0.01657378 -0.3612009 -0.9323663 -0.01506978 0.3612009 -0.9323663 -0.01507002 0.4713314 -0.8818004 0.01657402 -0.5264315 -0.8502154 0.001969695 0.5264311 -0.8502157 0.001969695 -0.5263824 -0.8501359 -0.01381343 0.526382 -0.8501361 -0.01381337 -0.5100999 -0.5595545 0.6532205 -0.3985978 -0.6437575 0.6532199 -0.5101016 -0.5595531 0.6532203 -0.6559591 -0.7195525 -0.2279518 -0.6559588 -0.7195526 -0.2279523 -0.5125713 -0.8278338 -0.227952 0.5101001 -0.5595539 0.6532207 0.510102 -0.5595536 0.6532196 0.398599 -0.6437564 0.6532202 0.6559593 -0.7195522 -0.227952 0.5125738 -0.8278321 -0.2279524 0.6559588 -0.7195526 -0.2279519 -0.6343917 -0.7730089 -0.002148389 -0.52643 -0.8502162 0.001969695 0.6343917 -0.7730089 -0.002148449 0.5264309 -0.8502156 0.001969695 0 0 -1 -0.6343212 -0.7729229 0.01506662 -0.5263808 -0.8501367 -0.01381349 0.5263827 -0.8501356 -0.01381331 0.6343215 -0.7729225 0.01506698 -0.6736947 -0.7390078 0.001718819 0.6736955 -0.7390071 0.001718819 -0.6736477 -0.7389544 -0.0120545 0.6736472 -0.7389547 -0.0120545 -0.6042332 -0.4562962 0.6532198 -0.5101044 -0.5595502 0.6532207 -0.6042314 -0.4562966 0.6532211 -0.7770069 -0.5867695 -0.2279517 -0.7770068 -0.5867695 -0.2279521 -0.6559615 -0.71955 -0.2279527 0.6042332 -0.4562966 0.6532196 0.6042325 -0.4562966 0.6532202 0.5101023 -0.5595532 0.6532197 0.7770071 -0.5867692 -0.2279517 0.6559591 -0.7195522 -0.2279524 0.7770067 -0.5867698 -0.2279517 -0.7730091 -0.6343924 -0.001861691 -0.6736971 -0.7390057 0.001718759 0.773009 -0.6343924 -0.001861751 0.6736934 -0.7390091 0.001718819 0 0 -1 -0.7729445 -0.6343393 0.01305621 -0.6736487 -0.7389534 -0.01205402 0.6736466 -0.7389553 -0.01205426 0.7729443 -0.6343395 0.01305651 -0.798016 -0.6026349 0.001396358 0.798016 -0.6026349 0.001396358 -0.7979782 -0.6026068 -0.009793162 0.7979785 -0.6026064 -0.009793162 -0.6777884 -0.3374995 0.6532205 -0.6042307 -0.4562947 0.6532232 -0.677789 -0.3374987 0.6532202 -0.8715952 -0.4340043 -0.2279521 -0.8715957 -0.4340035 -0.2279519 -0.7770096 -0.5867656 -0.2279525 0.6777881 -0.3374986 0.6532213 0.6777882 -0.3374994 0.6532208 0.6042317 -0.4562937 0.6532229 0.871596 -0.4340027 -0.227952 0.7770079 -0.5867677 -0.2279524 0.8715959 -0.4340029 -0.227952 -0.8819203 -0.4713962 -0.001503586 -0.7980167 -0.6026337 0.001396358 0.8819206 -0.4713958 -0.001503586 0.7980183 -0.6026316 0.001396358 0 0 -1 -0.8818718 -0.4713714 0.01054525 -0.7979809 -0.6026033 -0.009793162 0.7979809 -0.6026034 -0.009793341 0.8818722 -0.4713706 0.01054507 -0.8951629 -0.4457381 0.001002311 0.8951629 -0.4457381 0.00100243 -0.8951416 -0.4457266 -0.00702995 0.8951411 -0.4457276 -0.007030427 -0.7282632 -0.2072093 0.6532205 -0.67779 -0.3374937 0.6532219 -0.7282627 -0.2072093 0.6532211 -0.9365033 -0.2664576 -0.2279517 -0.936503 -0.266458 -0.2279522 -0.8715986 -0.4339971 -0.2279526 0.7282629 -0.2072092 0.6532208 0.7282638 -0.2072094 0.6532198 0.6777893 -0.3374996 0.6532195 0.9365029 -0.2664588 -0.227952 0.8715969 -0.4340009 -0.227952 0.9365032 -0.266458 -0.2279517 -0.9569398 -0.2902848 -0.001073896 -0.8951625 -0.4457389 0.001002371 0.9569401 -0.2902837 -0.001073896 0.8951585 -0.4457469 0.00100243 -0.9569134 -0.2902761 0.007531642 -0.8951388 -0.4457324 -0.007030189 0.8951387 -0.4457324 -0.007030546 0.9569134 -0.290276 0.00753194 -0.9618253 -0.2736635 5.36881e-4 0.9618253 -0.2736636 5.36881e-4 -0.9618187 -0.2736614 -0.003765404 0.961819 -0.2736604 -0.003765404 -0.7282683 -0.2071974 0.6532186 -0.7539383 -0.06986355 0.6532199 -0.753938 -0.06986314 0.6532203 -0.9695188 -0.08983969 -0.227952 -0.9365 -0.26647 -0.2279508 0.7539368 -0.0698623 0.6532217 0.7282666 -0.2071975 0.6532205 0.9365047 -0.2664517 -0.2279527 0.9695188 -0.08983945 -0.2279524 0.969519 -0.08983862 -0.227952 -0.9951846 -0.09801727 -5.72668e-4 -0.9618293 -0.27365 5.36875e-4 0.9951846 -0.09801727 -5.72611e-4 0.9618293 -0.27365 5.36876e-4 -0.9951768 -0.09801578 0.004016399 -0.9618163 -0.2736701 -0.003765344 0.9618209 -0.2736539 -0.003765344 0.9951767 -0.09801673 0.004015982 -0.995734 -0.09226989 0 -0.969519 -0.08983951 -0.2279518 0.9957342 -0.0922687 0 -0.9957342 -0.09226906 0 0.9957343 -0.09226799 0 0.7539386 -0.06986266 0.6532198 -0.9695189 0.08983963 -0.2279516 0.7539376 0.06986153 0.6532209 -0.9695188 0.08983945 -0.2279521 0.7539374 0.06986343 0.6532208 -0.995734 0.09226989 0 -0.9951846 0.09801733 -5.72676e-4 0 0 -1 0.9695188 0.08983945 -0.227952 -0.7539394 0.06986349 0.6532186 -0.753936 0.06986325 0.6532226 0.9695188 0.08983856 -0.2279525 -0.9957342 0.09226906 0 -0.9951768 0.09801596 0.004016458 1.09864e-6 0 1 -1.09864e-6 0 1 2.19729e-6 0 1 -2.19729e-6 0 1 -2.19729e-6 0 1 0.9951846 0.09801733 -5.72618e-4 0.9957342 0.09226864 0 0.9957343 0.09226799 0 0.9951767 0.09801697 0.004016041 -0.9618293 0.27365 5.36858e-4 -0.9365 0.26647 -0.2279507 0.9618293 0.27365 5.36848e-4 0.9365049 0.2664518 -0.2279521 -0.9618164 0.2736699 -0.003765225 -0.7282683 0.2071974 0.6532186 0.961821 0.2736537 -0.003765165 0.7282677 0.2071978 0.6532191 -0.9618253 0.2736638 5.36853e-4 -0.9365033 0.2664576 -0.2279517 -0.936503 0.2664583 -0.2279523 0.9618253 0.2736638 5.36855e-4 0.9365029 0.2664587 -0.227952 0.9365031 0.2664584 -0.2279518 -0.9618186 0.2736617 -0.003765225 -0.7282631 0.2072093 0.6532206 -0.7282648 0.2072088 0.653219 0.9618189 0.2736607 -0.003765165 0.7282629 0.2072092 0.653221 0.7282646 0.2072093 0.6532191 -0.9569399 0.2902846 -0.001073837 0.9569402 0.2902835 -0.001073896 -0.9569134 0.2902756 0.007531523 0.9569134 0.290276 0.007531821 -0.8951622 0.4457395 0.00100243 -0.8715983 0.4339976 -0.227953 0.8951583 0.4457474 0.00100243 0.8715962 0.4340018 -0.2279531 -0.8951387 0.4457324 -0.007030427 -0.67779 0.3374937 0.6532219 0.8951387 0.4457324 -0.007030725 0.6777889 0.3374994 0.6532201 -0.8951632 0.4457377 0.001002371 -0.871595 0.4340044 -0.2279523 -0.8715959 0.4340029 -0.2279519 0.8951632 0.4457377 0.00100243 0.8715959 0.4340029 -0.2279523 0.8715961 0.4340026 -0.2279521 -0.8951418 0.4457261 -0.007030248 -0.6777881 0.3374995 0.6532207 -0.6777887 0.3374986 0.6532207 0.8951412 0.4457273 -0.007030665 0.6777879 0.3374985 0.6532216 0.6777896 0.3374986 0.6532197 -0.8819203 0.4713963 -0.001503646 0.8819205 0.4713959 -0.001503586 -0.8818721 0.4713711 0.01054531 0.8818727 0.4713698 0.01054519 -0.7980149 0.6026361 0.001396417 -0.7770075 0.5867681 -0.227953 0.7980166 0.602634 0.001396417 0.7770062 0.5867701 -0.2279521 -0.7979792 0.6026055 -0.0097934 -0.6042317 0.4562954 0.6532219 0.7979792 0.6026055 -0.0097934 0.6042321 0.4562957 0.6532211 -0.7980163 0.6026343 0.001396417 -0.7770071 0.5867692 -0.2279518 -0.7770069 0.5867693 -0.2279523 0.7980163 0.6026343 0.001396417 0.777007 0.5867694 -0.227952 0.7770069 0.5867695 -0.2279518 -0.7979788 0.6026061 -0.009793519 -0.6042327 0.4562962 0.6532202 -0.6042312 0.4562965 0.6532213 0.7979792 0.6026055 -0.009793579 0.6042328 0.4562963 0.65322 0.6042329 0.456296 0.6532202 -0.7730088 0.6343926 -0.001861751 0.7730088 0.6343926 -0.00186181 -0.7729442 0.6343398 0.01305675 0.7729439 0.6343401 0.01305705 -0.6736964 0.7390062 0.001718759 -0.6559613 0.7195504 -0.2279522 0.6736928 0.7390096 0.001718759 0.6559592 0.7195523 -0.2279518 -0.6736482 0.7389539 -0.01205378 -0.510105 0.5595509 0.6532196 0.673646 0.7389559 -0.01205402 0.5101017 0.5595545 0.6532191 -0.6736947 0.7390078 0.001718759 -0.6559591 0.7195525 -0.2279518 -0.6559588 0.7195526 -0.2279524 0.6736956 0.7390071 0.001718759 0.6559595 0.719552 -0.2279519 0.6559588 0.7195526 -0.227952 -0.6736477 0.7389544 -0.01205408 -0.5100999 0.5595545 0.6532205 -0.5101014 0.559553 0.6532205 0.6736474 0.7389547 -0.01205402 0.5101001 0.5595539 0.6532207 0.5101019 0.5595535 0.6532198 -0.6343923 0.7730085 -0.002148389 0.6343922 0.7730084 -0.002148449 -0.6343213 0.7729228 0.01506644 0.6343215 0.7729225 0.01506698 -0.52643 0.8502162 0.001969695 -0.5125717 0.8278335 -0.2279519 0.5264309 0.8502157 0.001969695 0.5125738 0.8278321 -0.2279521 -0.5263805 0.850137 -0.01381331 -0.3985977 0.6437572 0.6532203 0.526382 0.850136 -0.01381331 0.3985987 0.6437561 0.6532207 -0.5264318 0.8502151 0.001969695 -0.5125725 0.8278329 -0.2279523 -0.5125723 0.827833 -0.2279519 0.5264314 0.8502154 0.001969695 0.5125727 0.8278329 -0.2279521 0.5125723 0.827833 -0.2279519 -0.5263824 0.8501359 -0.01381343 -0.3985967 0.6437571 0.653221 -0.3985995 0.6437566 0.6532197 0.526382 0.8501359 -0.01381337 0.398597 0.6437575 0.6532204 0.3985985 0.6437569 0.6532201 -0.4713952 0.8819189 -0.002363443 0.4713953 0.8819189 -0.002363443 -0.4713324 0.8818 0.01657402 0.4713323 0.8818001 0.01657402 -0.3612405 0.9324703 0.002148926 -0.3517306 0.9079226 -0.2279518 0.3612404 0.9324703 0.002148926 0.3517307 0.9079227 -0.2279515 -0.3612 0.9323666 -0.01506996 -0.2735181 0.7060394 0.65322 0.3612003 0.9323665 -0.01507002 0.2735202 0.7060387 0.6532199 -0.3612415 0.9324699 0.002148866 -0.3517318 0.9079221 -0.2279524 -0.3517314 0.9079222 -0.2279523 0.3612412 0.93247 0.002148807 0.3517316 0.9079222 -0.2279524 0.3517315 0.9079223 -0.2279523 -0.3612017 0.932366 -0.01506948 -0.2735204 0.7060374 0.6532211 -0.2735214 0.706038 0.6532201 0.3612011 0.9323663 -0.01506966 0.2735203 0.7060375 0.653221 0.2735217 0.7060375 0.6532205 -0.2902836 0.9569374 -0.002506852 0.2902833 0.9569375 -0.002506852 -0.2902394 0.9567927 0.01757949 0.2902393 0.9567927 0.01757949 -0.1837483 0.9829708 0.002256393 -0.1789113 0.9570938 -0.227952 0.1837487 0.9829707 0.002256333 0.1789116 0.9570938 -0.2279522 -0.183726 0.9828502 -0.0158236 -0.1391282 0.7442755 0.6532208 0.1837263 0.9828501 -0.015823 0.139127 0.7442757 0.6532208 -0.1837515 0.9829702 0.002256453 -0.1789113 0.9570939 -0.227952 -0.178914 0.9570934 -0.2279517 0.1837515 0.9829702 0.002256393 0.1789112 0.9570939 -0.2279521 0.1789145 0.9570934 -0.2279515 -0.1837292 0.9828495 -0.01582413 -0.1391291 0.7442756 0.6532205 -0.1391322 0.7442757 0.6532198 0.1837291 0.9828495 -0.01582378 0.1391283 0.7442758 0.6532204 0.1391311 0.7442761 0.6532195 -0.09801703 0.9951815 -0.002578675 0.09801709 0.9951814 -0.002578616 -0.09800124 0.9950221 0.01808273 0.0980013 0.9950221 0.01808249 0 0.9999974 0.002292096 0 0.9736726 -0.2279512 0 0.9999974 0.002292096 0 0.9736725 -0.2279515 0 0.9998708 -0.01607388 0 0.757169 0.6532191 0 0.9998709 -0.01607388 0 0.7571688 0.6532195 0 0.7571691 0.6532189 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 2 1 4 2 5 2 2 2 5 3 0 3 2 3 6 4 3 4 2 4 1 5 7 5 2 5 7 6 8 6 2 6 8 7 6 7 2 7 9 8 10 8 3 8 10 9 11 9 3 9 11 10 4 10 3 10 12 11 9 11 3 11 6 12 13 12 3 12 13 13 12 13 3 13 14 14 15 14 1 14 0 15 16 15 1 15 16 16 14 16 1 16 15 17 17 17 1 17 17 18 18 18 1 18 18 19 7 19 1 19 19 20 20 20 9 20 20 21 21 21 9 21 21 22 10 22 9 22 22 23 19 23 9 23 12 24 23 24 9 24 23 25 22 25 9 25 8 26 24 26 25 26 26 27 13 27 25 27 13 28 6 28 25 28 6 29 8 29 25 29 27 30 26 30 25 30 24 31 27 31 25 31 28 32 5 32 29 32 5 33 4 33 29 33 4 34 11 34 29 34 11 35 30 35 29 35 31 36 28 36 29 36 30 37 31 37 29 37 7 38 24 38 8 38 26 39 12 39 13 39 28 40 0 40 5 40 10 41 30 41 11 41 32 42 33 42 15 42 14 43 34 43 15 43 34 44 32 44 15 44 33 45 35 45 15 45 35 46 36 46 15 46 36 47 17 47 15 47 37 48 38 48 19 48 38 49 39 49 19 49 39 50 20 50 19 50 40 51 37 51 19 51 22 52 41 52 19 52 41 53 40 53 19 53 18 54 42 54 24 54 7 55 18 55 24 55 42 56 27 56 24 56 43 57 23 57 26 57 23 58 12 58 26 58 27 59 43 59 26 59 31 60 44 60 28 60 44 61 16 61 28 61 16 62 0 62 28 62 45 37 31 37 30 37 10 63 21 63 30 63 21 64 45 64 30 64 17 65 42 65 18 65 43 66 22 66 23 66 44 67 14 67 16 67 20 68 45 68 21 68 36 69 46 69 42 69 17 70 36 70 42 70 46 71 27 71 42 71 47 72 41 72 43 72 41 73 22 73 43 73 27 74 47 74 43 74 31 75 48 75 44 75 48 76 34 76 44 76 34 77 14 77 44 77 49 37 31 37 45 37 20 78 39 78 45 78 39 79 49 79 45 79 35 80 46 80 36 80 47 81 40 81 41 81 48 82 32 82 34 82 38 83 49 83 39 83 50 84 51 84 33 84 32 85 52 85 33 85 52 86 50 86 33 86 51 87 53 87 33 87 53 88 54 88 33 88 54 89 35 89 33 89 55 90 56 90 37 90 56 91 57 91 37 91 57 92 38 92 37 92 58 93 55 93 37 93 40 94 59 94 37 94 59 95 58 95 37 95 54 96 60 96 46 96 35 97 54 97 46 97 60 71 27 71 46 71 61 98 59 98 47 98 59 99 40 99 47 99 27 100 61 100 47 100 31 37 62 37 48 37 62 101 52 101 48 101 52 102 32 102 48 102 63 37 31 37 49 37 38 103 57 103 49 103 57 104 63 104 49 104 53 105 60 105 54 105 61 106 58 106 59 106 62 107 50 107 52 107 56 108 63 108 57 108 64 109 65 109 51 109 50 110 66 110 51 110 66 111 64 111 51 111 65 112 67 112 51 112 67 113 68 113 51 113 68 114 53 114 51 114 69 115 70 115 55 115 70 116 71 116 55 116 71 117 56 117 55 117 72 118 69 118 55 118 58 119 73 119 55 119 73 120 72 120 55 120 68 121 74 121 60 121 53 122 68 122 60 122 74 71 27 71 60 71 75 123 73 123 61 123 73 124 58 124 61 124 27 125 75 125 61 125 31 75 76 75 62 75 76 126 66 126 62 126 66 127 50 127 62 127 77 37 31 37 63 37 56 128 71 128 63 128 71 129 77 129 63 129 67 130 74 130 68 130 75 131 72 131 73 131 76 132 64 132 66 132 70 133 77 133 71 133 78 134 79 134 65 134 64 135 80 135 65 135 80 136 78 136 65 136 79 137 81 137 65 137 81 138 82 138 65 138 82 139 67 139 65 139 83 140 84 140 69 140 84 141 85 141 69 141 85 142 70 142 69 142 86 143 83 143 69 143 72 144 87 144 69 144 87 145 86 145 69 145 82 146 88 146 74 146 67 147 82 147 74 147 88 71 27 71 74 71 89 148 87 148 75 148 87 149 72 149 75 149 27 150 89 150 75 150 31 37 90 37 76 37 90 151 80 151 76 151 80 152 64 152 76 152 91 37 31 37 77 37 70 153 85 153 77 153 85 154 91 154 77 154 81 155 88 155 82 155 89 156 86 156 87 156 90 157 78 157 80 157 84 158 91 158 85 158 92 159 93 159 79 159 78 160 94 160 79 160 94 161 92 161 79 161 93 162 95 162 79 162 95 163 96 163 79 163 96 164 81 164 79 164 97 165 98 165 83 165 98 166 99 166 83 166 99 167 84 167 83 167 100 168 97 168 83 168 86 169 101 169 83 169 101 170 100 170 83 170 96 171 102 171 88 171 81 172 96 172 88 172 102 71 27 71 88 71 103 173 101 173 89 173 101 174 86 174 89 174 27 71 103 71 89 71 31 37 104 37 90 37 104 175 94 175 90 175 94 176 78 176 90 176 105 37 31 37 91 37 84 177 99 177 91 177 99 178 105 178 91 178 95 179 102 179 96 179 103 180 100 180 101 180 104 181 92 181 94 181 98 182 105 182 99 182 92 183 106 183 93 183 106 184 107 184 93 184 107 185 108 185 93 185 108 186 109 186 93 186 109 187 95 187 93 187 110 188 111 188 97 188 111 189 98 189 97 189 100 190 112 190 97 190 112 191 113 191 97 191 113 192 110 192 97 192 109 193 114 193 102 193 95 194 109 194 102 194 114 71 27 71 102 71 115 195 112 195 103 195 112 196 100 196 103 196 27 71 115 71 103 71 31 37 116 37 104 37 116 197 106 197 104 197 106 198 92 198 104 198 117 37 31 37 105 37 98 199 111 199 105 199 111 200 117 200 105 200 118 201 114 201 109 201 108 202 118 202 109 202 115 203 113 203 112 203 116 204 107 204 106 204 119 205 117 205 111 205 110 206 119 206 111 206 120 207 118 207 108 207 121 208 119 208 110 208 120 209 122 209 118 209 121 210 123 210 119 210 124 71 27 71 114 71 118 211 122 211 114 211 122 212 124 212 114 212 125 71 126 71 27 71 126 71 127 71 27 71 127 71 115 71 27 71 128 213 129 213 27 213 129 71 130 71 27 71 130 71 125 71 27 71 131 71 132 71 27 71 132 71 133 71 27 71 133 71 128 71 27 71 134 71 135 71 27 71 135 71 136 71 27 71 136 71 131 71 27 71 124 71 137 71 27 71 137 71 138 71 27 71 138 71 134 71 27 71 139 214 110 214 113 214 107 215 140 215 108 215 140 216 120 216 108 216 139 217 121 217 110 217 116 218 140 218 107 218 31 37 141 37 116 37 141 219 140 219 116 219 142 220 143 220 31 220 143 221 144 221 31 221 144 37 141 37 31 37 145 37 146 37 31 37 146 222 147 222 31 222 147 223 142 223 31 223 148 37 149 37 31 37 149 37 150 37 31 37 150 37 145 37 31 37 151 224 152 224 31 224 152 222 153 222 31 222 153 37 148 37 31 37 117 37 154 37 31 37 154 37 155 37 31 37 155 37 151 37 31 37 127 225 139 225 115 225 139 226 113 226 115 226 123 227 117 227 119 227 123 228 154 228 117 228 156 229 124 229 122 229 120 230 156 230 122 230 127 231 157 231 139 231 157 232 121 232 139 232 141 233 158 233 140 233 158 234 120 234 140 234 159 235 154 235 123 235 121 236 159 236 123 236 160 237 124 237 156 237 120 238 161 238 156 238 161 239 160 239 156 239 127 240 162 240 157 240 163 241 121 241 157 241 162 242 163 242 157 242 141 243 164 243 158 243 161 244 120 244 158 244 164 245 161 245 158 245 165 246 154 246 159 246 121 247 163 247 159 247 163 248 165 248 159 248 160 249 137 249 124 249 126 250 162 250 127 250 144 251 164 251 141 251 165 252 155 252 154 252 166 253 137 253 160 253 161 254 166 254 160 254 126 255 167 255 162 255 167 256 163 256 162 256 144 257 168 257 164 257 168 258 161 258 164 258 169 259 155 259 165 259 163 260 169 260 165 260 170 261 137 261 166 261 161 262 171 262 166 262 171 263 170 263 166 263 126 264 172 264 167 264 173 265 163 265 167 265 172 266 173 266 167 266 144 267 174 267 168 267 171 268 161 268 168 268 174 269 171 269 168 269 175 270 155 270 169 270 163 271 173 271 169 271 173 272 175 272 169 272 170 273 138 273 137 273 125 274 172 274 126 274 143 275 174 275 144 275 175 276 151 276 155 276 176 277 138 277 170 277 171 278 176 278 170 278 125 279 177 279 172 279 177 280 173 280 172 280 143 281 178 281 174 281 178 282 171 282 174 282 179 283 151 283 175 283 173 284 179 284 175 284 180 285 138 285 176 285 171 286 181 286 176 286 181 287 180 287 176 287 125 288 182 288 177 288 183 289 173 289 177 289 182 290 183 290 177 290 143 291 184 291 178 291 181 292 171 292 178 292 184 293 181 293 178 293 185 294 151 294 179 294 173 295 183 295 179 295 183 296 185 296 179 296 180 297 134 297 138 297 130 298 182 298 125 298 142 299 184 299 143 299 185 300 152 300 151 300 186 301 134 301 180 301 181 302 186 302 180 302 130 303 187 303 182 303 187 304 183 304 182 304 142 305 188 305 184 305 188 306 181 306 184 306 189 307 152 307 185 307 183 308 189 308 185 308 190 309 134 309 186 309 181 310 191 310 186 310 191 311 190 311 186 311 130 312 192 312 187 312 193 313 183 313 187 313 192 314 193 314 187 314 142 315 194 315 188 315 191 316 181 316 188 316 194 317 191 317 188 317 195 318 152 318 189 318 183 319 193 319 189 319 193 320 195 320 189 320 190 321 135 321 134 321 129 322 192 322 130 322 147 323 194 323 142 323 195 324 153 324 152 324 196 325 135 325 190 325 191 326 196 326 190 326 129 327 197 327 192 327 197 328 193 328 192 328 147 329 198 329 194 329 198 330 191 330 194 330 199 331 153 331 195 331 193 332 199 332 195 332 200 333 135 333 196 333 191 334 201 334 196 334 201 335 200 335 196 335 129 336 202 336 197 336 203 337 193 337 197 337 202 338 203 338 197 338 147 339 204 339 198 339 201 340 191 340 198 340 204 341 201 341 198 341 205 342 153 342 199 342 193 343 203 343 199 343 203 344 205 344 199 344 200 345 136 345 135 345 128 346 202 346 129 346 146 347 204 347 147 347 205 348 148 348 153 348 206 349 136 349 200 349 201 350 206 350 200 350 128 351 207 351 202 351 207 352 203 352 202 352 146 353 208 353 204 353 208 354 201 354 204 354 209 355 148 355 205 355 203 356 209 356 205 356 210 357 136 357 206 357 201 358 211 358 206 358 211 359 210 359 206 359 128 360 212 360 207 360 213 361 203 361 207 361 212 362 213 362 207 362 146 363 214 363 208 363 211 364 201 364 208 364 214 365 211 365 208 365 215 366 148 366 209 366 203 367 213 367 209 367 213 368 215 368 209 368 210 369 131 369 136 369 133 370 212 370 128 370 145 371 214 371 146 371 215 372 149 372 148 372 216 373 131 373 210 373 211 374 216 374 210 374 133 375 217 375 212 375 217 376 213 376 212 376 145 377 218 377 214 377 218 378 211 378 214 378 219 379 149 379 215 379 213 380 219 380 215 380 220 381 131 381 216 381 211 382 221 382 216 382 221 383 220 383 216 383 133 384 222 384 217 384 223 385 213 385 217 385 222 386 223 386 217 386 145 387 224 387 218 387 221 388 211 388 218 388 224 389 221 389 218 389 225 390 149 390 219 390 213 391 223 391 219 391 223 392 225 392 219 392 220 393 132 393 131 393 132 394 222 394 133 394 150 395 224 395 145 395 225 396 150 396 149 396 226 397 132 397 220 397 221 398 226 398 220 398 222 399 132 399 226 399 221 400 223 400 226 400 223 398 222 398 226 398 150 401 227 401 224 401 227 402 221 402 224 402 150 403 225 403 227 403 223 404 221 404 227 404 225 405 223 405 227 405

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_C6M2.dae b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_C6M2.dae new file mode 100644 index 0000000..71e98f5 --- /dev/null +++ b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_C6M2.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:16:22.697136 + 2012-07-23T02:16:22.697149 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -4.16853 10.99697 56.91780 -2.13558 10.99697 56.22232 0.00030 10.99697 55.98668 2.13616 10.99697 56.22231 -7.41158 1.43357 57.78464 -7.54952 -0.00303 57.78464 -7.00374 2.81535 57.78464 -6.34754 4.08412 57.78464 -5.49969 5.16901 57.78464 -1.03468 8.49697 57.78464 2.42357 7.14735 57.78464 1.05031 7.94142 58.24917 1.05031 7.47344 57.78464 2.60851 7.94142 58.63739 0.00031 8.55728 68.91865 2.28125 8.49697 59.99264 1.05031 8.49697 59.64888 1.03530 8.49697 57.78464 -4.99969 8.49697 57.78464 -2.90817 11.39697 59.72056 -1.50644 11.39697 59.23010 -0.00019 11.39697 59.05914 1.50620 11.39697 59.22990 2.90832 11.39697 59.72033 0.00031 11.49528 59.76977 0.00032 11.49697 65.90822 1.69915 11.49697 60.07462 2.73893 11.49697 60.49405 3.64845 11.49697 61.07492 -1.69865 11.49697 60.07465 -2.73841 11.49697 60.49409 -3.64783 11.49697 61.07491 -7.54952 -4.00303 57.78464 7.55014 -4.00303 57.78465 1.13878 11.48797 71.16059 -3.33824 9.49194 70.55422 2.78628 11.49697 70.25549 2.27099 11.48797 70.79404 0.00032 11.48797 71.28465 -1.16122 11.48797 71.16059 -2.27036 11.48797 70.79404 5.28198 10.27446 71.13149 -1.06765 10.38028 73.07560 1.06828 10.38028 73.07560 3.10938 10.38170 72.45206 -5.28136 10.27446 71.13149 -3.10875 10.38170 72.45206 -2.54465 9.65113 71.40520 -3.28925 9.10508 69.40430 -5.96849 9.74083 70.08224 -4.84852 9.88731 71.04855 -3.17535 8.69990 68.29736 2.54802 9.65113 71.40519 3.44225 9.96396 71.93696 3.33827 9.49238 70.55584 3.28988 9.10508 69.40430 4.96737 9.87593 70.95893 5.56944 9.80370 70.45921 -2.78565 11.49697 70.25549 -3.73788 11.49697 69.49624 3.73850 11.49697 69.49624 4.49082 11.49697 68.53881 -3.86623 9.95133 71.70066 -2.59559 9.96856 72.33196 -1.30422 9.65113 71.81620 0.00028 9.65113 71.95565 -1.06018 9.96856 72.74751 0.81113 9.96856 72.78098 1.30478 9.65113 71.81622 2.01662 9.96856 72.53303 -5.53304 10.70933 70.64544 -4.96728 10.77157 71.09794 -4.80699 11.04699 70.66184 -3.94573 10.83814 71.77613 -3.60196 11.04698 71.60882 -2.63388 10.85606 72.42852 -1.65129 10.85606 72.73823 -2.23214 11.04697 72.25872 -0.46035 10.85606 72.91682 -0.75524 11.04697 72.59101 0.82309 10.85606 72.88416 0.76285 11.04697 72.59023 2.04635 10.85606 72.63255 2.57708 10.85606 72.45101 2.23939 11.04697 72.25643 3.99747 10.83605 71.74595 3.60862 11.04698 71.60508 5.09086 10.75973 71.00474 4.81271 11.04698 70.65682 5.71692 10.68463 70.48512 7.49423 7.94157 64.50987 8.92281 8.79775 63.71438 8.99367 8.08742 64.55763 8.69039 8.16196 65.11563 8.37644 7.53031 64.74487 8.95635 8.26939 64.86778 8.74722 9.00930 65.88835 8.77245 8.65637 65.41832 8.59545 8.83116 65.91737 7.72686 7.83903 65.04834 3.52352 -10.85658 55.20966 8.68893 -9.29155 57.92509 6.99644 -10.79866 56.75002 7.84651 -10.23448 57.50816 5.86119 -10.91940 56.20141 8.38834 -9.29184 58.21590 7.69150 -10.17120 57.61452 6.76178 -10.62444 56.96974 8.13379 -9.19327 58.25332 7.47072 -9.98157 57.66316 5.77439 -10.75303 56.34334 8.94369 -8.00302 58.26979 8.78663 -8.00302 58.44858 8.56473 -8.00302 58.53452 8.32824 -8.00302 58.50813 8.13074 -8.00303 58.37546 7.90869 -9.03650 58.13997 7.35169 -9.84937 57.60191 6.68573 -10.50130 57.00586 5.91680 -4.00303 56.51129 4.88920 -6.00303 55.93077 5.73944 -10.50303 56.40048 4.88920 -9.00303 55.93077 4.61923 -10.50303 55.80138 6.73955 -10.91053 56.37839 7.08858 -10.77342 56.59704 8.02298 -10.21861 57.23000 8.72172 -9.24322 57.79251 6.00031 -11.00303 55.97394 8.68089 5.63812 61.18336 8.56476 -0.00303 58.53451 8.32827 -0.00303 58.50815 8.68089 3.11933 59.20854 8.94369 -0.00303 58.26979 8.78664 -0.00303 58.44856 8.13074 7.10166 63.68239 8.67571 7.07942 64.04446 8.80273 7.58718 64.67844 8.80114 9.23126 65.82974 8.21285 9.19201 67.21714 7.07571 9.96326 69.35165 8.37914 9.46742 67.22308 8.75185 9.44767 65.75461 8.94514 8.88449 64.98747 8.80831 9.32990 65.52029 8.33006 8.34255 65.38938 7.94636 8.50667 65.71574 8.55656 8.56278 65.49903 8.37959 8.73646 65.91035 3.67569 8.71842 68.35970 6.20627 9.69696 69.83866 6.80137 9.56087 69.14859 7.29869 9.41038 68.46049 6.91519 8.54095 65.99626 7.57014 8.64119 66.07724 7.70401 9.25230 67.79227 8.22660 8.93963 66.59763 5.00357 11.49697 67.43311 5.24853 11.49697 66.23880 4.11090 11.49697 61.54639 4.49544 11.49697 62.19938 4.79629 11.49697 63.01113 5.02916 11.49697 63.95683 5.21279 11.49697 65.02298 6.34688 11.17864 63.68803 5.87602 11.27726 62.68842 5.34956 11.34554 61.80425 4.11882 11.39697 60.46767 4.73815 11.17530 59.66812 9.00031 7.42460 63.58684 9.00031 5.53833 60.37230 9.00031 4.97167 59.84727 9.00031 4.28707 59.33522 9.00031 3.46270 58.85725 9.00031 2.48084 58.44772 9.00031 1.33136 58.15448 9.00031 -0.00303 58.03868 9.00031 -8.00303 58.03868 6.58902 8.49697 65.82475 6.37200 8.49544 65.34729 6.13723 8.49697 64.74155 6.02274 8.49697 64.20972 5.84711 8.49697 63.64807 5.59360 8.49697 63.05240 5.24033 8.49697 62.42426 4.76095 8.49697 61.77386 4.12606 8.49697 61.12329 3.30603 8.49697 60.50996 7.35819 7.94142 63.84882 8.13074 5.63518 60.98634 7.13793 7.94142 63.15024 6.81856 7.94142 62.40866 6.37180 7.94142 61.62654 8.13074 3.31200 59.15843 8.13074 2.37288 58.76674 8.13074 1.27351 58.48625 8.13074 -0.00303 58.37546 7.84601 -0.00303 58.07458 7.55014 -0.00303 57.78465 5.76359 7.94142 60.81770 5.95262 4.64133 57.78465 6.76130 5.63631 59.19019 6.93098 2.91600 57.78465 4.95613 7.94142 60.01181 4.87115 5.76542 57.78465 3.91203 7.94142 59.25899 3.69320 6.58200 57.78465 6.37924 10.57362 69.83974 5.76106 11.04699 69.48746 6.99832 10.43204 69.12189 7.51555 10.27552 68.40620 6.39743 11.04699 68.22884 7.93707 10.11112 67.71126 6.74219 11.04698 66.98638 8.27304 9.94482 67.05045 6.77652 11.04697 64.79448 6.84833 11.04698 65.82776 8.27304 10.02494 65.82712 8.27304 9.95522 64.60337 7.68907 10.47650 65.22638 7.51440 10.58686 64.38346 7.28972 10.70574 63.34866 7.03156 10.81415 62.21390 6.56192 10.93564 60.26743 6.00031 10.99697 58.03868 4.16911 10.99697 56.91779 8.97320 -7.99930 35.69485 8.57261 9.49998 35.85024 7.47453 10.59806 35.85024 6.75099 10.89776 35.85024 8.97405 7.99896 35.64078 5.97453 10.99998 35.85024 -7.73288 7.83902 65.04834 -8.63502 -9.30826 58.01877 -7.93006 -10.24095 57.42631 -6.99314 -10.79692 56.75710 -5.98520 -10.99559 55.99763 -8.46533 -9.30571 58.17711 -7.75845 -10.20360 57.57774 -6.83918 -10.70810 56.91447 -8.28166 -9.25626 58.24971 -7.57564 -10.08604 57.65858 -6.71150 -10.54603 56.99843 -5.78438 -10.77336 56.32600 -8.08450 -9.16383 58.24420 -3.52289 -10.85658 55.20966 -5.86925 -10.93604 56.18721 -8.94307 -8.00303 58.26979 -8.78603 -8.00303 58.44856 -8.56413 -8.00303 58.53451 -8.32765 -8.00303 58.50815 -2.07017 -4.00303 54.98126 -4.06603 -4.00303 55.56384 -4.07348 -5.46536 55.56680 -4.41319 -5.67444 55.70889 -4.88858 -6.00303 55.93077 -4.88858 -9.00303 55.93077 -4.61835 -10.50303 55.80126 -5.73882 -10.50303 56.40048 -5.91618 -4.00303 56.51129 -6.61429 -10.30840 57.00250 -7.36932 -9.82743 57.61906 -7.90885 -9.03460 58.14079 -8.13012 -8.00303 58.37546 -4.42719 -11.00303 55.17110 -5.49969 7.94142 60.52766 -5.49969 8.49697 62.86916 -7.07509 9.96326 69.35165 -8.40868 9.57200 67.21003 -8.38164 9.77928 67.14390 -8.77847 8.65637 65.41832 -8.75324 9.00930 65.88834 -8.80716 9.23126 65.82973 -8.85598 8.20532 65.01575 -8.80875 7.58718 64.67843 -8.32765 -0.00303 58.50815 -8.56413 -0.00303 58.53451 -8.78603 -0.00303 58.44856 -8.94307 -0.00303 58.26979 -8.67508 -0.00303 58.49153 -8.68027 3.11935 59.20855 -8.56413 7.03771 64.05474 -8.68027 5.63813 61.18338 -8.78601 7.12115 64.03425 -8.82568 9.29202 65.44601 -8.75123 9.44767 65.75460 -8.62564 9.63634 66.23487 -8.38246 7.53031 64.74487 -8.47667 8.65770 65.68396 -7.56946 8.64121 66.07729 -8.55801 8.55985 65.49423 -7.94615 8.50652 65.71537 -8.69641 8.16196 65.11563 -8.32985 8.34236 65.38905 -6.92121 8.54095 65.99626 -7.21787 9.43370 68.56859 -8.38561 8.73646 65.91035 -8.02650 9.09237 67.15675 -7.22853 8.73646 66.44991 -4.49019 11.49697 68.53880 -5.00295 11.49697 67.43310 -5.24790 11.49697 66.23879 -5.21216 11.49697 65.02297 -5.02849 11.49697 63.95660 -4.79562 11.49697 63.01096 -4.49486 11.49697 62.19946 -4.11076 11.49697 61.54702 -5.87529 11.27728 62.68823 -6.34615 11.17867 63.68780 -5.34900 11.34554 61.80436 -6.50196 11.01932 62.49067 -4.11820 11.39697 60.46766 -4.73752 11.26217 59.66812 -8.95116 8.88449 64.98747 -8.99969 8.08742 64.55762 -8.99969 7.42452 63.58657 -8.99969 8.32860 64.17715 -8.99969 7.14456 62.79934 -8.99969 6.69775 61.89881 -8.99969 6.00432 60.89467 -8.99969 4.97055 59.84633 -8.99969 4.28585 59.33441 -8.99969 3.46150 58.85666 -8.99969 2.47985 58.44739 -8.99969 1.33074 58.15437 -8.99969 -0.00303 58.03868 -8.99969 -8.00303 58.03868 -6.36582 8.49697 65.28314 -4.99969 8.49697 59.78465 -8.13012 6.30681 61.90997 -8.13014 7.19214 64.01679 -6.93326 7.94142 62.65234 -6.58044 7.94142 61.96633 -6.11115 7.94142 61.25299 -4.99969 7.74294 59.78465 -4.99969 6.96932 58.90087 -8.13012 5.29650 60.60670 -8.13012 5.74314 61.10729 -6.84235 6.16047 59.76889 -8.13012 4.75429 60.10451 -8.13012 2.37195 58.76642 -8.13012 3.31086 59.15787 -8.13012 4.09936 59.61484 -7.66390 4.10292 59.04662 -8.13012 1.85875 58.63554 -7.84539 -0.00303 58.07458 -8.13012 -0.00303 58.37546 -8.13012 1.27291 58.48615 -6.77590 11.08882 64.79447 -8.27241 10.00166 66.46892 -8.27242 10.02460 65.87690 -6.84770 11.04698 65.82941 -8.27241 9.94482 67.05044 -6.74099 11.04698 66.98962 -7.64224 10.22999 68.20881 -7.22061 10.36962 68.82871 -6.39505 11.04699 68.23342 -6.71649 10.50161 69.46391 -5.75694 11.04699 69.49290 -8.99969 7.99697 62.95621 -8.92784 8.64962 63.24892 -8.74119 9.21523 63.62119 -8.49871 9.65676 64.07870 -8.27242 9.95522 64.60336 -7.68264 10.48045 65.19770 -8.04445 10.19218 65.20199 -7.28360 10.70835 63.32394 -6.95376 10.83841 61.88823 -6.49814 10.94335 60.01643 -5.99969 10.99697 58.03868 -7.09799 -10.76947 56.60332 -8.02191 -10.21902 57.22966 -8.72210 -9.24094 57.79337 -8.87864 8.92703 50.79252 -8.45252 9.76334 50.79252 -7.78882 10.42703 50.79252 -6.95252 10.85315 50.79252 -9.02547 7.99998 24.47807 -5.98549 10.99998 23.80068 -1.04969 -10.85241 54.68365 4.42840 -11.00303 55.17134 2.76805 -11.00303 54.62267 0.00032 -11.00303 54.33267 -2.76710 -11.00303 54.62259 -6.66595 -10.93085 11.30388 -7.24205 -10.74227 10.48113 -7.83129 -10.39779 9.62842 -8.54841 -9.69898 9.75196 -8.93990 -8.71143 9.75318 -6.02547 -11.00002 12.21858 8.87231 -8.77648 35.85024 -6.06415 -10.98435 42.34554 7.47453 -10.59810 35.85024 5.97453 -11.00002 35.85024 -8.92325 8.77644 9.75318 -8.62354 9.49998 9.75318 -8.14679 10.12130 9.75318 -7.52547 10.59806 9.75318 -7.40258 10.61573 24.42709 -6.80193 10.89776 9.75318 -6.85997 10.85877 24.18378 -9.02547 -8.00002 50.79252 -9.02547 7.99998 9.75318 -9.02547 -8.00002 9.75318 -6.02547 10.99998 9.75318 -8.82456 -8.97048 8.23386 -8.35722 -9.83346 8.87693 3.09373 -11.00002 25.24129 3.84738 -11.00002 25.66956 6.02902 7.60540 24.02987 7.59724 9.39440 22.93180 3.09373 4.51538 25.24086 4.80132 6.77597 24.02629 5.53123 7.92272 23.51520 6.36547 8.94930 22.93106 7.25502 9.81190 22.30820 8.13969 10.48946 21.68875 -7.81194 10.19832 8.06339 -8.70497 9.17054 8.32644 -7.84819 9.52832 6.46801 -8.06851 7.48123 4.76029 -8.47200 8.99747 6.76388 -8.91057 8.17181 7.25133 -8.48715 6.71069 5.17098 -8.78339 5.53871 5.93756 -8.82707 6.93589 6.13376 -8.91444 4.52108 6.55495 -9.00809 3.44139 7.10285 -2.52488 10.79660 5.44341 -6.37604 10.87409 8.50607 -3.42532 10.53381 5.09353 -6.61970 10.62987 7.63714 -5.58596 9.52464 4.65381 -4.28238 10.18335 4.86431 -6.39769 9.05089 4.57325 -7.05581 9.89042 6.26470 -7.27770 8.32427 4.56418 14.71637 -1.00002 18.30448 9.11121 9.61540 22.22925 8.30002 8.99410 22.79724 7.48444 8.20316 23.36832 6.71983 7.26218 23.90371 6.05099 6.21134 24.37204 4.46876 -10.99931 25.47945 3.97006 4.32180 25.65569 13.48764 -11.00002 19.16484 -9.00962 -7.94523 7.95428 -9.02291 7.83078 8.60572 -9.13174 7.34492 7.32504 -9.01689 1.01905 7.80848 6.11848 10.99998 28.10642 13.48764 10.99998 19.16484 9.61673 10.99998 21.56325 10.27987 10.99998 21.33061 -1.38547 10.99361 6.36442 8.95372 10.99149 21.12506 7.67080 -10.77166 33.60986 8.53410 -10.12134 34.05927 9.11094 -9.14807 34.35955 8.38867 -9.86395 35.85762 8.97843 -10.89780 31.57137 15.04788 -10.47307 28.44679 9.39344 -10.59810 32.16406 14.55192 -10.22275 29.17261 9.74981 -10.12134 32.67301 13.96278 -9.72338 30.12993 10.02327 -9.50002 33.06355 10.19517 -8.77648 33.30905 6.44810 -10.99915 33.53150 6.95150 -11.00002 32.56861 7.68086 -11.00002 31.65925 8.53307 -11.00002 30.93533 6.07891 -11.00002 34.73596 7.24306 -10.99855 29.51986 15.24554 10.78862 17.93394 16.93588 10.16265 16.75036 18.49370 9.14615 15.65955 19.85915 7.77816 14.70346 20.97974 6.11126 13.91881 21.81242 4.20950 13.33576 22.32518 2.14598 12.97673 22.49832 -0.00002 12.85549 22.32518 -2.14601 12.97673 21.81242 -4.20954 13.33576 20.97974 -6.11129 13.91881 19.85915 -7.77819 14.70346 18.49370 -9.14618 15.65955 16.93588 -10.16269 16.75036 15.24554 -10.78866 17.93394 17.24874 10.99998 22.51061 18.17611 10.65630 21.81541 19.22166 10.40002 21.06122 20.96988 9.32311 19.90791 22.40247 8.07652 18.90565 23.59134 6.43999 18.07167 24.49215 4.54886 17.44142 25.06778 2.47712 17.03791 25.29603 0.30725 16.87835 25.16816 -1.87593 16.96807 24.68785 -3.98494 17.30406 23.87474 -5.93575 17.87369 22.76056 -7.65164 18.65359 21.39038 -9.06324 19.61331 19.81750 -10.11579 20.71426 16.31776 -10.99078 23.16249 18.10548 -10.76687 21.91349 17.38796 -11.00002 24.73507 16.96749 -10.97764 25.55215 16.34939 -10.84743 26.69325 15.72066 -10.57274 27.87064 15.38818 -10.15375 29.25569 9.11094 9.14803 34.35955 8.53410 10.12130 34.05927 7.67080 10.77162 33.60986 16.43848 10.92617 26.28057 8.97843 10.89776 31.57137 15.95405 10.80158 27.06688 15.43530 10.63526 27.85690 9.39344 10.59806 32.16406 14.92284 10.39920 28.68267 14.42861 10.14589 29.35819 9.74981 10.12130 32.67301 13.86560 9.76151 30.19668 10.02327 9.49998 33.06355 13.36479 9.18490 30.88310 10.19517 8.77644 33.30905 9.29688 -7.99607 34.43215 9.27742 7.99604 34.46957 18.48210 10.97335 27.63127 20.32549 10.89922 26.34051 16.66504 10.58775 28.90359 22.11796 10.36841 25.08541 14.91703 9.74032 30.12738 23.78436 9.40314 23.91859 12.34762 8.52781 31.90911 25.25485 8.04386 22.88894 10.02733 7.99865 33.54759 11.78197 7.99998 32.32275 26.46777 6.34756 22.03964 19.10870 -1.00002 27.19253 27.37233 4.38535 21.40626 27.93064 2.23951 21.01533 28.11937 -0.00001 20.88318 27.93064 -2.23954 21.01533 27.37233 -4.38538 21.40626 10.17767 -7.99948 33.44432 26.46778 -6.34759 22.03964 11.78197 -8.00002 32.32275 12.79827 -8.62660 31.61546 25.25485 -8.04389 22.88894 13.84475 -9.17023 30.85625 23.78437 -9.40318 23.91858 14.95047 -9.75869 30.10414 22.11796 -10.36845 25.08541 20.32550 -10.89926 26.34051 18.48211 -10.97339 27.63127 16.66505 -10.58779 28.90358 17.38796 10.99998 24.73507 7.68086 10.99998 31.65925 6.88393 10.99870 32.69260 6.40583 10.99998 33.61652 6.07891 10.99998 34.73596 8.53307 10.99998 30.93533 14.42391 10.99998 24.49159 16.29335 10.99998 23.17457 -4.52128 -9.48780 55.75693 -3.74877 -5.29607 55.44330 -4.04355 -10.02226 55.55492 -3.44120 -10.49866 55.33802 -3.27828 -5.11393 55.28461 -2.56465 -5.00303 55.08788 -0.86205 -5.00303 54.81850 0.00031 -4.00303 54.78465 0.86268 -5.00303 54.81850 2.07080 -4.00303 54.98126 2.56528 -5.00303 55.08788 3.24817 -5.10488 55.27505 3.85739 -5.34857 55.48305 4.06665 -4.00303 55.56384 4.39886 -5.66467 55.70235 -2.03629 -5.00303 55.45412 2.03692 -5.00303 55.45412 -1.59865 -5.00303 55.92377 1.59927 -5.00303 55.92377 -1.27058 -5.00303 56.47660 1.27121 -5.00303 56.47660 -1.06794 -5.00303 57.08608 1.06857 -5.00303 57.08608 -0.99969 -5.00303 57.72238 1.00031 -5.00303 57.72238 -0.99969 -5.00303 64.05260 1.00031 -5.00303 64.05260 1.23270 -5.00303 64.87756 -0.22221 -5.00303 64.80972 0.22284 -5.00303 64.80972 -0.62317 -5.00303 65.00281 0.62381 -5.00303 65.00281 -1.36571 -5.07242 64.78465 -0.90065 -5.00303 65.35076 0.90128 -5.00303 65.35076 -1.16938 -5.00303 65.70529 1.17001 -5.00303 65.70531 -0.99969 -5.00303 65.78465 1.00031 -5.00303 65.78465 1.08593 -5.00303 66.22726 -1.07869 -5.00303 66.24315 0.86804 -5.00303 66.28169 -0.86541 -5.00303 66.28516 0.50304 -5.00303 66.64909 0.76600 -5.00303 66.67245 -0.75402 -5.00303 66.68211 -0.49850 -5.00303 66.65135 0.00254 -5.00303 66.78464 0.28178 -5.00303 66.92274 -0.26495 -5.00303 66.92662 2.00031 -6.00303 57.72238 2.00069 -6.00303 64.78463 2.00031 -9.00303 57.72238 2.00032 -9.00303 64.78465 0.00032 -10.00303 55.78465 -1.66580 -10.00303 55.83743 0.00032 -10.00303 56.18634 -1.38036 -10.00303 56.25980 0.00032 -10.00303 56.52710 -1.17070 -10.00303 56.72397 0.00032 -10.00303 56.79470 1.04338 -10.00303 57.21588 -1.04276 -10.00303 57.21584 1.00031 -10.00303 57.72238 -0.99969 -10.00303 57.72238 1.00032 -10.00303 64.78465 -0.99968 -10.00303 64.78465 -1.99969 -9.00303 64.78465 -1.99969 -6.00303 64.74483 -1.99969 -6.00303 57.72238 -1.99969 -9.00303 57.72238 4.41109 -6.00303 55.76503 4.41097 -9.00303 55.76500 3.90525 -6.00303 55.72464 3.90519 -9.00303 55.72466 3.40663 -6.00303 55.81253 3.40656 -9.00303 55.81256 2.94624 -6.00303 56.02271 2.94618 -9.00303 56.02274 2.55335 -6.00303 56.34171 2.55329 -9.00303 56.34176 2.25301 -6.00303 56.74930 2.25292 -9.00303 56.74944 2.06435 -6.00303 57.22037 2.06428 -9.00303 57.22060 -4.41046 -9.00303 55.76503 -4.41046 -6.00303 55.76503 -3.90463 -9.00303 55.72464 -3.90463 -6.00303 55.72464 -3.40600 -9.00303 55.81253 -3.40600 -6.00303 55.81253 -2.94561 -9.00303 56.02271 -2.94561 -6.00303 56.02271 -2.55272 -9.00303 56.34171 -2.55272 -6.00303 56.34171 -2.25238 -9.00303 56.74930 -2.25238 -6.00303 56.74930 -2.06372 -9.00303 57.22037 -2.06372 -6.00303 57.22037 -2.71138 -5.29592 55.82565 -1.97344 -5.29592 56.64922 -1.92357 -5.62035 57.72238 -1.38239 -5.07915 57.72238 -1.69827 -5.28750 64.78465 -1.70681 -5.29593 57.72238 -1.92125 -5.61481 64.78465 -1.99475 -6.00303 64.92503 1.43195 -5.11040 65.01970 1.38300 -5.07915 57.72238 1.69889 -5.28749 64.78465 1.70742 -5.29592 57.72238 1.92189 -5.61481 64.78465 1.92419 -5.62034 57.72238 3.74839 -5.30497 55.44583 2.71693 -5.29592 55.82231 1.97546 -5.29592 56.64659 1.86633 -9.50305 64.78465 1.92419 -9.38571 57.72238 1.70742 -9.71014 57.72238 1.50029 -9.86907 64.78465 1.38300 -9.92691 57.72238 -1.49969 -9.86905 64.78465 -1.38237 -9.92691 57.72238 -1.70679 -9.71014 57.72238 -1.86571 -9.50303 64.78465 -1.92357 -9.38571 57.72238 -4.20886 -9.24626 55.70316 -3.45966 -9.51198 55.65247 -2.92259 -9.70494 55.70795 -2.03552 -9.71014 56.53943 -1.97107 -9.98200 55.79823 -2.25367 -9.92569 55.77649 -2.52205 -9.84500 55.75502 0.00032 -10.66970 54.80614 -2.47480 -10.61703 55.07125 0.00032 -10.97928 54.48560 1.05032 -10.85241 54.68365 0.00031 -5.00303 65.78465 -1.73699 -5.33823 64.96863 -1.92773 -5.64578 64.93640 1.73761 -5.33822 64.96864 1.92836 -5.64578 64.93640 1.27380 -5.02203 65.28942 -1.81236 -5.27567 66.19547 -2.10209 -5.94570 66.32501 -1.15964 -5.27567 67.23690 -1.32993 -5.94570 67.50003 0.00031 -5.94570 67.95538 0.00031 -5.27567 67.64330 1.33056 -5.94570 67.50003 1.16027 -5.27567 67.23691 2.10272 -5.94570 66.32501 1.81299 -5.27567 66.19547 0.00032 -10.04902 55.45229 0.00032 -10.18686 55.17287 0.00032 -10.40319 54.94949 -1.78668 -10.32127 55.11591 -1.73172 -10.17210 55.44402 -0.99968 -10.00303 66.28465 1.00032 -10.00303 66.28465 2.10272 -8.94570 66.32501 -2.10209 -8.94570 66.32501 -1.32993 -8.94570 67.50003 0.00032 -8.94570 67.95538 1.33056 -8.94570 67.50003 1.73346 -10.17210 55.44402 1.78841 -10.32127 55.11591 2.47653 -10.61703 55.07125 2.52378 -9.84500 55.75502 2.25541 -9.92569 55.77649 1.97281 -9.98200 55.79823 2.03725 -9.71014 56.53943 2.92432 -9.70494 55.70795 3.46140 -9.51198 55.65247 4.21060 -9.24626 55.70316 1.17244 -10.00303 56.72397 1.38210 -10.00303 56.25980 1.66754 -10.00303 55.83743 3.44294 -10.49866 55.33802 4.04529 -10.02226 55.55492 4.52302 -9.48780 55.75693 + + + + + + + + + + -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.00176 -0.99998 0.00631 -0.05355 -0.99857 0.00043 0.00000 -0.99999 0.00542 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 -0.00095 1.00000 -0.00028 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.04752 0.99190 -0.11780 -0.04460 0.99084 -0.12747 -0.02095 0.99228 -0.12226 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.99978 -0.01466 0.01477 -0.99976 -0.02028 0.00805 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 0.00000 -0.10705 -0.93718 0.33202 0.09366 0.95264 0.28931 0.07028 0.94785 0.31086 0.03296 0.95258 0.30251 0.17105 0.96162 0.21453 0.17056 0.96125 0.21658 0.13733 0.94752 0.28870 0.19414 0.95999 0.20179 0.00016 0.94744 0.31993 -0.03234 0.95249 0.30284 -0.07021 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.13704 0.94751 0.28886 -0.19432 0.95992 0.20196 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 0.29459 -0.64015 0.70952 0.46219 0.52024 0.71814 0.44473 0.03813 0.89485 0.53245 0.40400 0.74383 0.39039 -0.60766 0.69162 0.43016 -0.54482 0.71982 0.60973 0.41632 0.67446 0.45012 -0.62955 0.63329 -0.34004 -0.62630 0.70151 -0.23218 -0.60875 0.75863 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 0.00000 -0.58193 0.81324 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 0.02349 0.38357 0.92321 0.18035 0.44574 0.87681 0.25235 -0.50582 0.82490 0.15528 -0.63718 0.75491 0.28039 0.27890 0.91848 0.30399 0.34310 0.88874 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41725 -0.54080 0.73037 -0.41201 -0.60635 0.68014 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 0.13338 -0.93583 0.32624 0.14454 -0.93969 0.30997 0.14440 -0.93971 0.30999 0.14454 -0.93969 0.30998 -0.14310 -0.93869 0.31366 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 0.04525 -0.90484 0.42333 -0.00555 -0.95073 0.30998 0.07081 -0.93620 0.34427 0.10399 -0.94352 0.31456 -0.39689 0.83488 0.38139 -0.32068 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.00028 0.83866 0.54466 0.01264 0.86767 0.49698 0.11187 0.86176 0.49483 0.10816 0.84369 0.52582 0.17651 0.83818 0.51604 0.25027 0.81275 0.52612 0.23285 0.86496 0.44455 0.33532 0.84040 0.42578 0.32528 0.86091 0.39119 0.18153 0.97480 -0.12965 0.17001 0.97728 -0.12654 0.30431 0.95247 -0.01398 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.69992 0.00000 0.71422 -0.71753 0.00258 0.69653 0.85361 0.22299 0.47076 0.78945 0.37028 0.48956 0.96140 0.25494 0.10351 -0.71327 -0.68531 0.14694 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.99709 0.07281 -0.02245 0.94096 0.33621 -0.03941 0.91811 -0.28358 0.27686 0.71137 -0.33210 0.61940 -0.43505 -0.65824 0.61437 0.17552 -0.92639 0.33316 0.20020 -0.56806 0.79827 -0.36475 -0.92779 0.07852 0.99241 -0.00582 0.12283 -0.36661 -0.92729 0.07565 0.69862 -0.45435 0.55272 0.48679 -0.51345 0.70669 0.93601 -0.05072 0.34830 0.94067 -0.09921 0.32450 0.99852 -0.05405 0.00588 0.96437 -0.18410 0.19000 0.49646 -0.68115 0.53810 0.74849 -0.58760 0.30738 0.33786 -0.80615 0.48576 0.24914 -0.62470 0.74005 -0.38048 -0.92472 -0.01172 -0.40310 -0.90211 0.15396 -0.39572 -0.90000 0.18275 -0.14946 -0.85152 0.50256 0.04364 -0.78466 0.61839 0.33000 -0.71943 0.61116 0.23960 -0.72465 0.64612 0.18329 -0.69229 0.69795 0.12591 -0.54798 0.82696 -0.22862 -0.88332 0.40924 -0.69814 -0.69570 0.16913 0.09772 -0.92104 0.37701 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.45559 -0.25841 0.85186 -0.29317 -0.70441 0.64642 -0.13850 -0.95397 0.26602 0.95828 -0.24461 0.14786 0.81543 -0.57879 -0.00930 0.94100 -0.24772 0.23054 0.44467 -0.88743 0.12142 0.33852 -0.93969 0.04887 0.40618 -0.89006 0.20691 0.61604 -0.70539 0.35059 0.71448 -0.30916 0.62764 -0.06005 -0.94361 0.32556 -0.19340 -0.85881 0.47439 -0.01764 -0.79254 0.60956 0.00853 -0.93684 0.34965 0.65752 -0.32585 0.67933 0.50716 -0.68460 0.52355 0.34776 -0.26959 0.89799 0.21992 -0.66340 0.71522 0.03122 -0.83832 0.54428 -0.31182 -0.70556 0.63636 -0.07666 -0.52074 0.85027 0.04715 -0.24580 0.96817 -0.10883 -0.19107 0.97553 -0.21087 -0.46595 0.85932 -0.28739 -0.53790 0.79251 -0.42242 -0.48538 0.76549 -0.36795 -0.46363 0.80602 -0.53494 -0.16968 0.82768 -0.50295 -0.10159 0.85832 -0.57290 -0.14179 0.80727 -0.57632 -0.14637 0.80401 -0.55630 -0.06916 0.82810 -0.52021 -0.25876 0.81390 0.97128 0.00000 0.23795 0.97128 0.00000 0.23795 0.75129 0.00000 0.65997 0.75129 0.00000 0.65997 0.36119 0.00000 0.93249 0.36113 -0.00000 0.93251 -0.11078 0.00000 0.99385 -0.11087 -0.00000 0.99383 -0.55763 0.00000 0.83009 -0.55763 0.00000 0.83009 -0.72632 0.00000 0.68736 -0.72738 -0.00008 0.68624 -0.69507 0.00038 0.71895 -0.61483 -0.00378 0.78865 -0.65575 -0.02015 0.75471 -0.53890 0.00034 0.84237 -0.48965 -0.00150 0.87192 -0.47159 0.00881 0.88178 -0.48356 -0.00000 0.87531 -0.35592 -0.92787 0.11130 -0.35599 -0.92772 0.11224 -0.34305 -0.92790 0.14600 -0.34306 -0.92762 0.14774 -0.32485 -0.92795 0.18269 -0.32465 -0.92748 0.18544 -0.29985 -0.92803 0.22101 -0.29922 -0.92728 0.22500 -0.26638 -0.92815 0.25995 -0.26496 -0.92700 0.26547 -0.22267 -0.92832 0.29771 -0.21990 -0.92662 0.30498 -0.16727 -0.92857 0.33134 -0.16235 -0.92614 0.34045 0.06866 -0.98340 0.16795 0.05806 -0.98803 0.14291 0.27545 0.96128 -0.00810 0.26631 0.96371 -0.01852 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24571 0.96262 0.11395 0.24710 0.96090 0.12493 0.21475 0.96198 0.16875 0.21458 0.96108 0.17403 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05537 0.18875 0.98134 -0.03660 0.20009 0.97977 0.00241 0.22383 0.97307 -0.05512 0.27743 0.96072 0.00660 0.22710 0.97309 -0.03911 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 0.04752 0.99190 -0.11780 0.85908 -0.41995 0.29260 0.84589 -0.47572 0.24118 0.71256 -0.60512 0.35508 -0.15441 -0.88248 0.44428 -0.33313 -0.82828 0.45053 -0.26799 -0.59574 0.75715 -0.27654 -0.59294 0.75627 0.87478 -0.29895 0.38130 0.92715 -0.25465 0.27484 0.88204 -0.28220 0.37731 0.83044 -0.27944 0.48196 0.81928 -0.22073 0.52920 -0.21381 -0.37604 0.90160 -0.10840 -0.20592 0.97255 -0.55344 -0.12230 0.82386 -0.71334 -0.06060 0.69819 -0.40482 -0.22605 0.88602 0.86783 -0.13547 0.47804 0.84841 -0.13085 0.51291 0.97107 -0.02065 0.23790 0.75105 0.02515 0.65977 0.35731 0.14609 0.92249 0.93755 -0.33787 0.08276 0.36885 -0.86583 0.33807 0.40262 -0.84457 0.35299 0.30818 -0.87862 0.36477 0.79236 -0.48636 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14655 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23107 0.52767 -0.56848 0.63119 0.51463 -0.58326 0.62846 0.69906 0.28926 0.65394 0.69603 0.25858 0.66983 0.73326 0.39301 0.55486 0.51543 -0.63934 0.57059 0.71478 -0.44325 0.54095 0.50370 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04157 0.78420 0.61951 -0.03530 0.75315 0.64246 -0.14144 0.82860 0.54907 -0.10926 0.30521 -0.65708 0.68927 0.27452 -0.77218 0.57305 0.19557 -0.87047 0.45170 0.25684 -0.87163 0.41749 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14388 -0.94000 0.30935 0.14372 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.04527 0.99623 -0.07396 0.21031 0.97181 -0.10652 0.06838 0.99149 -0.11075 0.04277 0.99157 -0.12228 0.04210 0.99151 -0.12305 0.54248 0.83922 -0.03771 0.56738 0.81415 -0.12343 0.43933 0.89793 0.02653 0.44975 0.89314 0.00495 0.41496 0.90361 -0.10632 0.37331 0.92770 0.00370 0.32582 0.93758 -0.12160 0.13224 0.99120 -0.00605 0.99766 0.05944 -0.03376 0.99761 0.05955 -0.03494 0.99974 0.02256 0.00118 1.00000 0.00090 -0.00097 1.00000 0.00074 -0.00099 1.00000 0.00095 -0.00164 -0.00630 -0.99996 0.00607 -0.00914 -0.99996 0.00102 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00745 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 -0.64851 -0.66869 0.36372 -0.78399 -0.56943 0.24719 -0.72894 -0.60836 0.31393 -0.67806 -0.62467 0.38732 -0.62961 -0.61117 0.47965 -0.63130 -0.61327 0.47472 -0.71791 -0.43046 0.54709 -0.63745 -0.38469 0.66759 -0.68092 -0.28192 0.67592 -0.67104 -0.18329 0.71841 -0.57400 -0.07080 0.81579 -0.71726 -0.15742 0.67879 -0.69233 -0.14685 0.70648 -0.55015 -0.62730 0.55121 -0.49917 -0.61019 0.61522 -0.53420 -0.51395 0.67118 -0.66290 -0.37590 0.64750 -0.45505 -0.62819 0.63112 -0.43573 -0.62856 0.64424 -0.31840 -0.67290 0.66770 -0.29656 -0.66599 0.68448 0.40524 0.83720 0.36725 0.40441 0.85374 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24717 0.49012 0.83244 0.25851 0.53337 0.82040 0.20605 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09072 0.58199 0.81145 0.05331 0.58209 0.81139 0.05314 0.58234 0.81175 0.04408 0.63891 0.76804 -0.04376 0.87243 0.48873 0.00135 0.66299 0.74861 -0.00494 0.53559 0.84448 -0.00042 0.46878 0.88331 -0.00031 0.39186 0.92002 -0.00125 0.24879 0.96856 0.00042 0.10852 0.99409 0.00001 -0.56299 0.82624 -0.01940 -0.41875 0.90371 -0.08924 -0.90044 -0.25936 0.34920 -0.93842 -0.11798 0.32473 -0.34308 0.92963 -0.13449 -0.12092 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29116 0.13334 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.24074 -0.72348 0.64701 -0.33159 -0.71777 0.61225 -0.04401 -0.78448 0.61859 0.36127 -0.87020 0.33502 -0.10318 -0.93694 0.33390 -0.30659 -0.65544 0.69022 -0.24901 -0.62075 0.74341 -0.54604 -0.69844 0.46262 -0.46583 -0.68911 0.55510 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71481 -0.55303 -0.49987 0.66655 -0.08363 -0.97549 0.20352 -0.95619 0.27849 0.09024 -0.00001 1.00000 0.00003 0.00000 0.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.77550 -0.62094 0.11414 -0.92389 -0.26237 0.27855 -0.93651 -0.26515 0.22944 -0.45140 -0.88525 0.11212 -0.69107 -0.67926 0.24705 -0.71876 -0.29107 0.63139 -0.43222 -0.89152 0.13554 -0.21391 -0.97644 -0.02847 -0.48193 -0.69947 0.52771 -0.64730 -0.30492 0.69858 -0.20138 -0.87331 0.44359 -0.37961 -0.70148 0.60317 0.11954 -0.91012 0.39673 -0.06955 -0.83809 0.54107 0.00035 -0.95410 0.29950 -0.34751 -0.27251 0.89720 -0.13707 -0.62234 0.77065 -0.28897 -0.27361 0.91741 0.13169 -0.69253 0.70927 0.00840 -0.57544 0.81780 0.26070 -0.59799 0.75792 0.36092 -0.63712 0.68104 0.29526 -0.70457 0.64529 0.10861 -0.19695 0.97438 0.11924 -0.19633 0.97326 0.22611 -0.43020 0.87395 0.48669 -0.26087 0.83372 0.49192 -0.26576 0.82909 0.52427 -0.22855 0.82031 0.53316 -0.23207 0.81356 0.49186 -0.30734 0.81463 0.57602 -0.13819 0.80567 0.54643 -0.07521 0.83412 0.55630 -0.06906 0.82811 0.29316 -0.70443 0.64641 0.41234 -0.30593 0.85813 0.11803 -0.96573 0.23118 -0.97128 0.00000 0.23795 -0.97128 0.00000 0.23795 -0.75129 0.00000 0.65997 -0.75129 0.00000 0.65997 -0.36118 0.00000 0.93249 -0.36118 0.00000 0.93249 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.41672 -0.06071 0.90701 0.44156 -0.03337 0.89661 0.49187 0.00000 0.87067 0.48578 -0.00165 0.87408 0.47157 0.00882 0.88178 0.56683 0.00142 0.82383 0.61482 -0.00663 0.78864 0.63155 -0.00250 0.77533 0.69992 0.00000 0.71422 0.71543 0.00227 0.69868 0.69543 0.00038 0.71859 0.72632 -0.00007 0.68736 0.72758 -0.00000 0.68603 1.00000 0.00000 -0.00000 0.96907 -0.14560 -0.19926 1.00000 -0.00000 0.00000 0.82964 0.00000 0.55829 0.81840 -0.55913 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34240 -0.93149 0.12285 0.41737 -0.90314 0.10069 -0.01779 -0.99870 0.04773 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.21448 0.96105 0.17429 -0.21468 0.96201 0.16869 -0.24706 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05397 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06967 0.99117 -0.11285 -0.06977 0.99156 -0.10925 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50577 -0.84008 0.26127 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08801 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67439 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.70424 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95385 0.19680 0.22679 -0.79602 0.59318 0.12039 0.33004 -0.80724 0.48932 -0.20020 -0.56806 0.79826 -0.19713 -0.77268 0.60342 -0.33899 -0.76788 0.54355 -0.56010 -0.42940 0.70845 -0.93154 -0.30944 0.19098 -0.92038 -0.32295 0.22046 0.55619 -0.07182 0.82795 0.11078 -0.00001 0.99385 -0.35677 0.15627 0.92103 -0.35311 -0.20995 0.91172 -0.74452 -0.13397 0.65402 -0.97123 0.01021 0.23794 -0.94190 -0.02903 0.33465 -0.87579 -0.11927 0.46772 0.43301 -0.20106 0.87868 0.50696 -0.21300 0.83524 -0.81932 -0.22063 0.52919 0.21392 -0.37591 0.90163 -0.83672 -0.33789 0.43096 -0.94486 -0.16420 0.28332 -0.90294 -0.25735 0.34420 -0.82338 -0.40407 0.39846 0.40408 -0.56439 0.71985 0.63619 -0.52427 0.56604 0.42922 -0.54084 0.72337 0.24642 -0.48596 0.83852 0.22831 -0.72646 0.64817 -0.35307 -0.83531 0.42143 0.33802 -0.85130 0.40128 0.52007 -0.78743 0.33089 0.22940 -0.79654 0.55937 -0.81758 -0.52269 0.24158 -0.97082 -0.19733 0.13627 -0.93633 -0.31452 0.15605 -0.89789 -0.41477 0.14750 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02856 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01958 -0.75159 0.65915 0.02529 -0.75611 0.64757 -0.09461 -0.76607 0.62897 -0.13240 -0.76278 0.64443 -0.05370 -0.72711 0.68600 0.02658 -0.73804 0.67155 0.06564 -0.18054 -0.90416 0.38717 -0.19130 -0.89466 0.40372 -0.24234 -0.81604 0.52474 -0.27442 -0.77224 0.57302 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.14037 -0.94027 0.31014 -0.14455 -0.93969 0.30997 -0.14454 -0.93969 0.30997 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.42741 0.90176 -0.06440 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.17579 0.98435 0.01240 -0.18182 0.98314 -0.01917 -0.04278 0.99157 -0.12227 -0.06792 0.99150 -0.11096 -0.06980 0.99114 -0.11304 -0.07001 0.99177 -0.10718 -0.99856 0.04531 0.02872 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00012 0.00067 -1.00000 -0.00130 0.00064 -1.00000 -0.00095 0.00066 0.00674 -0.99997 0.00479 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42688 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.53895 -0.63976 0.54794 0.56237 -0.62219 0.54463 0.54102 -0.54657 0.63919 0.60574 -0.46780 0.64362 0.66422 -0.46943 0.58177 0.68227 -0.49680 0.53638 0.68248 -0.54538 0.48661 0.65312 -0.61971 0.43519 0.60598 -0.47358 0.63915 0.70018 -0.42752 0.57181 0.31773 -0.23430 0.91878 0.65808 -0.28974 0.69497 0.72685 -0.34438 0.59421 0.66513 -0.26599 0.69775 0.74155 -0.38353 0.55046 0.69487 -0.20510 0.68927 0.70755 -0.17462 0.68474 0.69835 -0.06705 0.71261 0.72397 -0.08033 0.68514 0.70425 -0.06136 0.70730 -0.55875 0.82932 -0.00524 -0.62317 0.78191 -0.01634 -0.58167 0.81243 0.04018 -0.58191 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03149 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51068 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40436 0.85353 0.32861 -0.99403 0.10913 0.00067 -0.95025 0.31148 0.00318 -0.87588 0.48253 -0.00146 -0.78707 0.61676 -0.01137 -0.72035 0.69361 -0.00024 -0.54105 0.84089 -0.01294 -0.62317 0.78207 -0.00563 -0.38610 0.92244 -0.00514 -0.21949 0.97561 0.00127 -0.92962 -0.36852 0.00015 -0.81240 -0.58309 0.00262 -0.69791 -0.71618 -0.00011 -0.51123 -0.85944 0.00118 -0.25237 -0.96762 -0.00372 -0.51824 -0.85514 0.01266 0.07105 -0.94250 0.32658 0.13045 -0.90945 0.39482 0.25882 -0.96593 -0.00048 0.12978 -0.99149 -0.01044 0.36620 -0.93054 -0.00105 0.81475 -0.57977 -0.00674 0.99177 -0.12793 0.00409 0.97574 -0.21894 -0.00122 -0.19895 -0.98001 0.00034 -0.97562 -0.21944 0.00338 0.00008 -1.00000 -0.00015 -0.00145 -1.00000 -0.00027 0.00066 -1.00000 -0.00200 0.00017 -1.00000 -0.00165 -0.00015 -1.00000 -0.00148 -0.00046 -1.00000 -0.00140 -0.00520 -0.99999 -0.00079 1.00000 -0.00006 -0.00112 1.00000 0.00062 -0.00147 1.00000 0.00034 -0.00135 1.00000 0.00011 -0.00125 1.00000 0.00000 -0.00121 -1.00000 -0.00068 0.00067 -1.00000 -0.00051 0.00069 -1.00000 -0.00040 0.00070 -1.00000 -0.00030 0.00071 -1.00000 -0.00019 0.00073 -1.00000 -0.00007 0.00075 -1.00000 0.00000 0.00077 -0.99998 0.00586 0.00356 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 0.96584 0.25909 -0.00561 0.70711 0.70710 -0.00224 0.38268 0.92388 -0.00105 0.13052 0.99145 -0.00053 -0.98654 0.16350 -0.00026 -0.89099 0.45398 0.00531 -0.70705 0.70705 0.01263 -0.45399 0.89100 0.00113 -0.14944 0.98877 0.00002 -0.12153 0.99258 -0.00372 0.00005 1.00000 0.00009 -0.00008 1.00000 0.00014 0.00001 1.00000 0.00009 0.00003 1.00000 0.00009 -0.10791 -0.99416 0.00038 -0.31691 -0.94845 0.00451 -0.97382 -0.22730 0.00191 -0.99284 -0.11942 -0.00000 -0.98769 0.15643 0.00000 -0.99144 0.13053 0.00060 -0.92388 0.38269 -0.00040 -0.89101 0.45399 0.00080 -0.79335 0.60876 -0.00060 -0.70711 0.70711 0.00090 -0.60876 0.79334 0.00414 -0.52998 0.84801 -0.00169 -0.45399 0.89101 -0.00027 -0.38268 0.92388 0.00096 -0.40791 0.91302 0.00232 -0.40924 0.91243 -0.00123 -0.13052 0.99144 0.00215 -0.15956 0.98719 -0.00035 -0.15922 0.98724 0.00045 0.37033 -0.89191 -0.25953 0.00098 1.00000 -0.00054 -0.98113 -0.18864 -0.04232 -0.99277 -0.11941 -0.01238 -0.68242 0.51015 -0.52350 -0.44507 0.60140 -0.66350 0.81915 -0.00004 -0.57358 0.00000 1.00000 0.00000 -0.89260 0.25436 -0.37225 -0.88341 0.27950 -0.37611 0.49406 -0.00002 -0.86943 0.42708 -0.00424 -0.90420 -0.29256 0.00148 -0.95625 0.81913 -0.00002 -0.57360 0.82204 -0.00859 -0.56936 0.82157 -0.00716 -0.57007 0.81518 0.00991 -0.57913 0.81931 0.00004 -0.57336 0.82167 -0.00528 -0.56993 0.81915 -0.00004 -0.57358 -0.92960 -0.36850 -0.00774 -0.84092 -0.53145 -0.10206 -0.70109 -0.71172 -0.04381 -0.00074 -1.00000 0.00052 0.23448 -0.59158 -0.77140 -0.35251 -0.22831 -0.90753 0.40533 -0.59696 -0.69235 0.38686 -0.56948 -0.72528 -0.28541 -0.23270 -0.92973 -0.30811 -0.28670 -0.90712 -0.25807 -0.31078 -0.91478 0.23525 -0.64984 -0.72275 0.30826 -0.64722 -0.69719 -0.33916 -0.29520 -0.89321 0.26361 -0.72845 -0.63235 -0.34827 -0.31462 -0.88302 -0.40242 -0.27333 -0.87370 0.32573 -0.81630 -0.47702 0.00721 -0.75190 -0.65924 0.16630 -0.77478 -0.60997 -0.31407 -0.31597 -0.89528 0.82540 -0.16065 -0.54120 0.79464 -0.32812 -0.51076 0.77099 -0.39996 -0.49559 0.60058 -0.67981 -0.42091 0.72838 -0.49440 -0.47437 0.64605 -0.61357 -0.45403 0.65462 -0.60045 -0.45927 0.58106 -0.70428 -0.40787 0.58346 -0.70151 -0.40922 0.60853 -0.66981 -0.42550 0.51098 -0.78302 -0.35464 0.46760 -0.81941 -0.33155 0.49779 -0.79333 -0.35047 0.43495 -0.84709 -0.30538 0.42888 -0.85146 -0.30179 0.36001 -0.89790 -0.25331 0.36052 -0.89760 -0.25364 -0.13026 0.98946 -0.06326 -0.38403 0.91131 -0.14844 -0.42556 0.83775 -0.34216 -0.45938 0.83469 -0.30375 -0.38307 0.91172 -0.14841 -0.37824 0.91316 -0.15189 -0.60660 0.79054 -0.08417 -0.69472 0.66867 -0.26503 -0.76483 0.61785 -0.18246 -0.76449 0.63286 -0.12264 -0.78977 0.60602 -0.09486 -0.92329 0.38244 -0.03562 -0.90867 0.37797 -0.17734 -0.97318 0.23000 -0.00456 -0.96591 0.25380 -0.05104 -0.97307 0.21210 -0.09028 -0.99122 0.13050 -0.02145 -0.70695 0.56381 -0.42702 -0.88221 0.28161 -0.37735 -0.92446 0.21947 -0.31178 -0.94149 0.01783 -0.33658 -0.96942 -0.00771 -0.24528 -0.97782 -0.00116 -0.20946 -0.97851 -0.01931 -0.20530 -0.99457 -0.02576 -0.10085 -0.05971 0.99471 -0.08363 -0.07485 0.99005 -0.11918 -0.15231 0.96177 -0.22760 -0.18020 0.95116 -0.25065 -0.28594 0.87859 -0.38251 -0.26602 0.89107 -0.36773 -0.38894 0.75596 -0.52654 -0.33059 0.80936 -0.48543 -0.53530 0.65496 -0.53336 -0.57355 -0.00001 -0.81917 -0.57355 0.00000 -0.81917 -0.55955 -0.00849 -0.82876 -0.62174 0.01656 -0.78305 -0.57358 0.00002 -0.81915 -0.57360 0.00003 -0.81914 -0.57360 0.00003 -0.81914 -0.57361 0.00003 -0.81913 -0.52031 -0.00711 -0.85395 -1.00000 -0.00000 -0.00223 -0.99996 -0.00095 -0.00884 -0.99998 -0.00024 -0.00552 -0.99598 -0.01129 0.08891 0.00057 1.00000 -0.00000 -0.00228 0.99987 -0.01593 -0.07763 0.87274 0.48198 0.05892 0.74278 0.66694 0.04719 0.89564 0.44227 0.10086 0.90505 0.41316 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.25760 -0.96137 0.09704 0.13120 -0.93972 0.31577 0.04226 -0.93526 0.35142 0.03103 -0.89988 0.43502 -0.02004 -0.89145 0.45267 -0.01268 -0.79648 0.60453 0.08486 -0.99137 0.09990 0.08283 -0.99435 0.06644 0.06829 -0.99699 0.03660 0.17929 -0.98230 0.05425 0.15184 -0.98830 0.01422 0.16981 -0.97088 0.16900 0.30391 -0.91882 0.25181 0.55978 -0.82095 0.11264 0.42611 -0.82389 0.37368 0.44032 -0.78817 0.43001 0.61730 -0.77025 0.16016 0.60282 -0.59761 0.52865 0.83115 -0.53706 0.14408 0.61171 -0.54071 0.57745 0.70854 -0.37183 0.59976 0.88759 -0.39311 0.24008 0.96594 -0.16830 0.19658 0.73646 -0.16028 0.65721 0.71034 -0.10516 0.69595 0.96593 -0.07592 0.24741 0.62613 -0.77970 0.00506 0.51327 -0.85821 -0.00546 0.91370 -0.40629 0.00889 0.02994 -0.99864 0.04276 0.07669 -0.99144 0.10564 0.11288 -0.97847 0.17280 0.21741 -0.92388 0.31494 0.22797 -0.91421 0.33503 0.40596 -0.69438 0.59416 0.34757 -0.79335 0.49980 0.35373 -0.78295 0.51173 0.43178 -0.66299 0.61156 0.45135 -0.60876 0.65245 0.40363 -0.69507 0.59495 0.48671 -0.38216 0.78553 0.54652 -0.10777 0.83048 0.56817 -0.12870 0.81278 0.54675 -0.05619 0.83540 0.00103 -1.00000 0.00158 0.00067 -1.00000 -0.00027 0.00098 -1.00000 -0.00049 -0.00221 -0.99999 -0.00437 -0.00044 -1.00000 -0.00063 -0.00040 -1.00000 0.00070 -0.00216 -1.00000 -0.00138 -0.00087 -1.00000 0.00045 -0.00303 -0.99999 -0.00243 -0.00144 -1.00000 -0.00039 -0.00050 -1.00000 -0.00058 -0.00038 -1.00000 0.00071 -0.00137 -1.00000 -0.00013 -0.57359 -0.00000 -0.81914 -0.57357 -0.00000 -0.81916 -0.57357 -0.00000 -0.81916 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.00000 1.00000 -0.00000 0.06694 0.99492 -0.07524 0.24246 0.95843 -0.15039 0.23151 0.95688 -0.17544 0.17121 0.98056 -0.09584 0.39040 0.88190 -0.26428 0.38192 0.88932 -0.25148 0.48635 0.81409 -0.31738 0.51694 0.77300 -0.36775 0.61812 0.66370 -0.42123 0.63075 0.63439 -0.44688 0.71337 0.50257 -0.48840 0.72019 0.47140 -0.50903 0.78063 0.32131 -0.53607 0.78190 0.29028 -0.55170 0.81714 0.12730 -0.56221 0.81350 0.09802 -0.57324 0.82144 -0.07136 -0.56582 0.81370 -0.09802 -0.57296 0.79323 -0.26778 -0.54689 0.78263 -0.29028 -0.55066 0.73369 -0.45354 -0.50596 0.72148 -0.47140 -0.50720 0.64526 -0.62114 -0.44477 0.63257 -0.63439 -0.44430 0.53121 -0.76425 -0.36570 0.51937 -0.77301 -0.36429 0.39639 -0.87686 -0.27201 0.38619 -0.88192 -0.27031 0.24582 -0.95475 -0.16741 0.23819 -0.95694 -0.16594 0.08548 -0.99477 -0.05598 0.08108 -0.99518 -0.05510 -0.14935 0.89987 0.40979 -0.13015 0.97172 0.19701 -0.09726 0.98250 0.15886 -0.09873 0.98486 0.14250 -0.08999 0.99075 0.10155 -0.03883 0.99896 0.02385 0.03687 0.99931 -0.00474 0.05550 0.99770 -0.03893 0.01173 0.99979 0.01688 0.23355 0.95869 -0.16240 0.18854 0.97179 -0.14172 0.16191 0.98079 -0.10882 0.35127 0.90345 -0.24572 0.36632 0.88898 -0.27481 0.46754 0.81415 -0.34434 0.49388 0.79724 -0.34713 0.61070 0.66373 -0.43187 0.61715 0.65761 -0.43206 0.70548 0.50258 -0.49971 0.71457 0.49044 -0.49886 0.77241 0.32132 -0.54785 0.78202 0.30272 -0.54480 0.80861 0.12730 -0.57441 0.81670 0.10234 -0.56791 0.81264 -0.07137 -0.57838 0.81730 -0.10234 -0.56705 0.78441 -0.26777 -0.55946 0.78369 -0.30272 -0.54240 0.72482 -0.45354 -0.51859 0.71729 -0.49043 -0.49495 0.63633 -0.62112 -0.45748 0.62095 -0.65760 -0.42660 0.52230 -0.76422 -0.37837 0.49869 -0.79721 -0.34025 0.38748 -0.87682 -0.28469 0.35568 -0.90343 -0.23941 0.23703 -0.95469 -0.17993 0.19793 -0.97178 -0.12832 0.08168 -0.99476 -0.06143 0.06945 -0.99549 -0.06460 0.03687 -0.99931 -0.00474 -0.02038 -0.99965 0.01689 -0.13752 -0.98521 0.10219 0.00487 -0.99324 0.11598 -0.16707 -0.97616 0.13853 -0.22747 -0.92240 0.31215 -0.25824 -0.94013 0.22241 0.77548 0.02612 0.63083 0.71506 0.16814 0.67854 0.95542 0.16167 0.24707 0.93441 0.20972 0.28792 0.70854 0.37183 0.59976 0.82388 0.54071 0.16987 0.63066 0.54442 0.55307 0.56626 0.60266 0.56228 0.46606 0.78469 0.40872 0.41334 0.82095 0.39394 0.48143 0.83122 0.27801 0.70234 0.70234 0.11594 0.30391 0.91882 0.25181 0.38059 0.91882 0.10452 0.23278 0.97167 0.04086 0.14850 0.98212 0.11574 0.09872 0.98831 0.11621 0.07303 0.99144 0.10820 0.13051 0.99137 0.01223 0.10190 0.99435 0.02976 0.06995 0.99694 0.03481 0.07486 0.99145 0.10692 0.05303 0.99537 0.08011 0.18269 0.94743 0.26268 0.21651 0.92387 0.31556 0.24459 0.90391 0.35090 0.30156 0.85080 0.43035 0.34454 0.79333 0.50191 0.39368 0.72816 0.56107 0.41816 0.68612 0.59531 0.44741 0.60874 0.65518 0.52226 0.42592 0.73881 0.52992 0.38268 0.75680 0.53767 0.35896 0.76293 0.55113 0.13367 0.82364 0.57213 0.02920 0.81964 0.96868 0.00079 0.24831 0.96805 0.00059 0.25074 0.74639 -0.00065 0.66551 0.77578 0.00322 0.63100 0.57358 -0.00001 0.81915 0.57358 0.00000 0.81915 0.57357 -0.00016 0.81915 0.57356 -0.00002 0.81916 0.57325 -0.01084 0.81931 0.57280 -0.00126 0.81970 0.57330 0.02735 0.81889 0.57358 -0.00000 0.81915 0.57239 0.00009 0.81998 0.57351 -0.00008 0.81920 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57352 -0.00011 0.81919 0.57358 0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57295 0.00805 0.81955 0.57358 0.00569 0.81913 0.57238 0.00193 0.81999 0.57452 -0.03601 0.81769 0.57257 0.02864 0.81936 0.57358 -0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 0.00001 0.81915 0.57358 0.00002 0.81915 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00049 1.00000 0.00086 0.00078 1.00000 -0.00098 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.42643 -0.00127 0.90452 0.45581 -0.00052 0.89008 0.35546 0.00008 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37466 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00251 0.92737 -0.42805 -0.01025 0.90370 -0.45567 -0.02415 0.88982 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 0.00000 -0.00005 1.00000 -0.00013 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -0.32753 -0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90969 0.63033 -0.00000 0.77633 0.63036 0.00000 0.77631 0.80504 -0.00000 0.59322 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37169 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07959 0.00000 0.99683 0.07959 0.00000 0.99683 -0.17359 0.00000 0.98482 -0.17359 0.00000 0.98482 -0.41529 0.00000 0.90969 -0.41529 0.00000 0.90969 -0.63033 0.00000 0.77633 -0.63033 0.00000 0.77633 -0.80504 0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 -0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32894 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39517 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35199 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39126 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85625 0.38631 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12334 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81900 -0.17246 -0.19506 0.98057 0.02092 -0.54306 0.83970 0.00048 -0.55558 0.83146 -0.00032 -0.82644 0.56302 0.00033 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 -0.98020 0.19803 0.00000 -0.98037 0.19531 0.02684 -0.00000 1.00000 0.00000 0.48300 0.87548 -0.01569 0.19509 0.98078 0.00289 0.55273 0.83336 -0.00014 0.55557 0.83147 -0.00032 0.82644 0.56303 0.00033 0.83147 0.55557 -0.00016 0.98001 0.19894 0.00016 0.98079 0.19509 -0.00005 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15934 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30814 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26659 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37311 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18797 0.97320 0.19358 0.12413 0.98077 -0.19509 0.00479 0.96592 -0.25883 -0.00000 0.83147 -0.55557 -0.00242 0.70708 -0.70712 0.00482 0.55557 -0.83147 -0.00242 0.25880 -0.96592 0.00361 0.19509 -0.98079 0.00000 -0.19508 -0.98077 0.00479 -0.25882 -0.96593 0.00000 -0.55557 -0.83147 -0.00242 -0.70710 -0.70710 0.00483 -0.83147 -0.55557 -0.00242 -0.96592 -0.25882 0.00361 -0.98078 -0.19509 0.00000 0.32738 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23701 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86547 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54635 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29876 -0.95399 0.02541 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18796 -0.97320 -0.19358 0.12413 0.47154 -0.01436 0.88173 0.14306 -0.95333 0.26588 0.33917 -0.38521 0.85824 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03997 -0.73162 0.68054 0.01607 -0.98803 0.15344 -0.03998 -0.73156 0.68061 -0.01608 -0.98803 0.15344 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.53936 0.83398 0.11644 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06987 -0.98282 0.18451 -0.00431 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85101 0.52047 0.06988 0.98001 0.19894 -0.00123 -0.38262 0.92383 0.01196 -0.60550 0.79206 -0.07758 -0.98242 0.18315 0.03618 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86396 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92864 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48079 0.35273 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78086 0.11745 0.43570 0.89717 -0.07251 0.98234 0.18358 0.03605 0.84345 0.53138 -0.07891 0.60508 0.79038 0.09581 0.08395 -0.47203 0.87758 0.07372 -0.31442 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39305 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.46536 -0.69804 0.54423 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.47838 0.87812 -0.00723 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18887 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18766 0.98224 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 0.00000 1.00000 0.00000 -0.19510 0.98078 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02737 -0.96449 -0.25844 -0.05450 -0.69955 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66579 0.40977 0.96449 -0.25844 -0.05450 0.69954 -0.69957 0.14577 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18765 0.98223 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18887 -0.67100 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92407 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19358 0.12407 0.81662 -0.54565 -0.18814 0.90235 -0.34994 0.25160 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02538 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54655 0.32005 -0.92238 0.21629 0.34529 -0.86547 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68809 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.18723 0.98232 -0.00049 -0.25882 -0.96593 -0.00000 -0.67986 -0.71506 0.16275 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 -0.99707 0.00000 -0.07645 -0.99777 0.00475 -0.06651 0.83570 0.00000 0.54918 0.83570 0.00000 0.54918 0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 -0.32386 -0.00000 0.94611 -0.32386 -0.00000 0.94611 -0.83570 0.00000 0.54918 -0.83570 -0.00000 0.54918 0.99781 0.00000 -0.06609 0.99780 -0.00013 -0.06633 -0.00012 1.00000 0.00012 -0.00002 1.00000 0.00014 -0.00005 1.00000 0.00014 0.03620 -0.94022 0.33864 0.10266 -0.94500 0.31053 0.12277 -0.94865 0.29153 0.11094 -0.94337 0.31263 -0.03620 -0.94022 0.33864 -0.10286 -0.94501 0.31044 -0.12261 -0.94859 0.29179 -0.11094 -0.94337 0.31265 0.00000 1.00000 0.00000 0.01046 0.99992 0.00670 -0.00053 1.00000 0.00160 -0.00018 1.00000 0.00167 0.00018 1.00000 0.00167 0.00052 1.00000 0.00160 -0.01046 0.99992 0.00670 0.00000 1.00000 0.00000 + + + + + + + + + + + + + + +

10 0 11 0 12 0 13 1 11 1 10 1 16 2 15 2 14 2 14 3 17 3 16 3 9 4 17 4 14 4 1 5 0 5 20 5 20 6 21 6 1 6 2 7 1 7 21 7 22 8 3 8 2 8 21 9 22 9 2 9 24 10 25 10 26 10 27 11 26 11 25 11 28 12 27 12 25 12 25 13 24 13 29 13 29 14 30 14 25 14 30 15 31 15 25 15 30 16 29 16 19 16 20 17 19 17 29 17 29 18 24 18 20 18 21 19 20 19 24 19 22 20 21 20 24 20 24 21 26 21 22 21 23 22 22 22 26 22 13 23 16 23 11 23 15 24 16 24 13 24 12 25 11 25 17 25 16 26 17 26 11 26 12 27 17 27 9 27 33 28 9 28 18 28 33 29 18 29 8 29 33 30 8 30 7 30 33 31 7 31 6 31 33 32 6 32 4 32 33 33 4 33 5 33 32 34 33 34 5 34 25 35 60 35 61 35 51 36 14 36 48 36 84 37 37 37 34 37 84 38 34 38 81 38 81 39 34 39 38 39 60 40 36 40 88 40 86 41 88 41 36 41 84 42 86 42 37 42 86 43 36 43 37 43 79 44 81 44 38 44 38 45 39 45 79 45 77 46 79 46 39 46 39 47 40 47 77 47 74 48 77 48 40 48 40 49 58 49 74 49 72 50 74 50 58 50 58 51 59 51 72 51 53 52 44 52 69 52 41 53 83 53 44 53 41 54 85 54 83 54 41 55 87 55 85 55 41 56 44 56 56 56 44 57 53 57 56 57 89 58 87 58 41 58 56 59 57 59 41 59 63 60 46 60 62 60 42 61 46 61 66 61 46 62 63 62 66 62 42 63 75 63 46 63 42 64 76 64 75 64 42 65 78 65 76 65 43 66 42 66 67 66 42 67 66 67 67 67 42 68 43 68 78 68 43 69 80 69 78 69 82 70 80 70 43 70 43 71 69 71 44 71 43 72 67 72 69 72 43 73 44 73 82 73 44 74 83 74 82 74 49 75 50 75 45 75 71 76 70 76 45 76 45 77 46 77 71 77 46 78 73 78 71 78 46 79 75 79 73 79 45 80 62 80 46 80 45 81 50 81 62 81 35 82 47 82 62 82 62 83 50 83 35 83 50 84 48 84 35 84 50 85 51 85 48 85 53 86 69 86 52 86 56 87 53 87 54 87 53 88 52 88 54 88 54 89 55 89 56 89 63 90 62 90 47 90 47 91 64 91 63 91 66 92 63 92 64 92 64 93 65 93 66 93 65 94 68 94 66 94 68 95 67 95 66 95 69 96 67 96 68 96 68 97 52 97 69 97 70 98 71 98 72 98 74 99 72 99 73 99 72 100 71 100 73 100 73 101 75 101 74 101 77 102 74 102 75 102 75 103 76 103 77 103 79 104 77 104 78 104 77 105 76 105 78 105 81 106 79 106 80 106 79 107 78 107 80 107 84 108 81 108 82 108 81 109 80 109 82 109 82 110 83 110 84 110 86 111 84 111 85 111 84 112 83 112 85 112 88 113 86 113 87 113 86 114 85 114 87 114 168 115 167 115 166 115 223 116 168 116 166 116 223 117 166 117 222 117 25 118 157 118 158 118 25 119 61 119 157 119 198 120 33 120 197 120 197 121 33 121 117 121 210 122 140 122 141 122 210 123 209 123 140 123 144 124 142 124 138 124 90 125 188 125 135 125 154 126 156 126 155 126 148 127 156 127 154 127 91 128 143 128 92 128 91 129 144 129 143 129 137 130 92 130 95 130 93 131 137 131 95 131 137 132 135 132 136 132 94 133 135 133 137 133 137 134 93 134 94 134 188 135 180 135 181 135 143 136 95 136 92 136 188 137 90 137 180 137 93 138 95 138 97 138 93 139 97 139 147 139 143 140 97 140 95 140 143 141 144 141 97 141 144 142 138 142 97 142 138 143 96 143 97 143 147 144 97 144 96 144 147 145 96 145 98 145 147 146 98 146 148 146 145 147 93 147 147 147 90 148 99 148 180 148 180 149 99 149 179 149 179 150 99 150 178 150 178 151 99 151 153 151 153 152 99 152 154 152 146 153 154 153 99 153 145 154 146 154 99 154 145 155 99 155 93 155 93 156 99 156 94 156 135 157 94 157 99 157 99 158 90 158 135 158 55 159 14 159 149 159 33 160 12 160 9 160 33 161 10 161 12 161 33 162 206 162 10 162 33 163 204 163 206 163 33 164 200 164 204 164 33 165 202 165 200 165 33 166 198 166 202 166 121 167 123 167 110 167 110 168 100 168 104 168 100 169 128 169 104 169 101 170 127 170 177 170 126 171 127 171 101 171 177 172 111 172 101 172 102 173 125 173 126 173 125 174 102 174 124 174 126 175 103 175 102 175 103 176 126 176 101 176 111 177 112 177 101 177 128 178 124 178 102 178 102 179 107 179 128 179 107 180 102 180 103 180 104 181 128 181 107 181 105 182 101 182 112 182 101 183 105 183 103 183 112 184 113 184 105 184 106 185 103 185 105 185 103 186 106 186 107 186 110 187 104 187 107 187 105 188 108 188 106 188 108 189 105 189 113 189 113 190 114 190 108 190 109 191 106 191 108 191 106 192 109 192 107 192 107 193 118 193 110 193 118 194 107 194 109 194 108 195 116 195 109 195 116 196 108 196 114 196 117 197 109 197 116 197 109 198 117 198 118 198 114 199 115 199 116 199 121 200 110 200 118 200 176 201 133 201 177 201 111 202 177 202 133 202 133 203 134 203 111 203 112 204 111 204 134 204 134 205 130 205 112 205 113 206 112 206 130 206 130 207 131 207 113 207 114 208 113 208 131 208 131 209 196 209 114 209 115 210 114 210 196 210 196 211 197 211 115 211 197 212 116 212 115 212 117 213 116 213 197 213 33 214 119 214 117 214 119 215 118 215 117 215 121 216 118 216 119 216 120 217 121 217 119 217 123 218 121 218 122 218 121 219 120 219 122 219 181 220 182 220 188 220 190 221 188 221 182 221 182 222 183 222 190 222 191 223 190 223 183 223 183 224 184 224 191 224 192 225 191 225 184 225 184 226 185 226 192 226 199 227 192 227 185 227 185 228 186 228 199 228 203 229 199 229 186 229 186 230 187 230 203 230 205 231 203 231 187 231 187 232 15 232 205 232 13 233 205 233 15 233 14 234 153 234 149 234 178 235 153 235 14 235 158 236 215 236 163 236 158 237 216 237 215 237 213 238 216 238 158 238 158 239 157 239 213 239 211 240 213 240 157 240 157 241 61 241 211 241 208 242 211 242 61 242 61 243 60 243 208 243 88 244 208 244 60 244 159 245 167 245 28 245 166 246 167 246 159 246 159 247 160 247 166 247 160 248 161 248 166 248 161 249 165 249 166 249 164 250 165 250 161 250 161 251 162 251 164 251 164 252 163 252 215 252 164 253 162 253 163 253 23 254 28 254 167 254 23 255 27 255 28 255 26 256 27 256 23 256 169 257 92 257 136 257 129 258 169 258 136 258 129 259 170 259 169 259 129 260 136 260 189 260 136 261 135 261 189 261 189 262 193 262 129 262 132 263 129 263 193 263 129 264 132 264 170 264 132 265 171 265 170 265 132 266 172 266 171 266 132 267 173 267 172 267 174 268 173 268 132 268 193 269 194 269 132 269 132 270 131 270 130 270 132 271 196 271 131 271 132 272 195 272 196 272 132 273 194 273 195 273 132 274 130 274 174 274 130 275 175 275 174 275 176 276 175 276 133 276 175 277 134 277 133 277 175 278 130 278 134 278 137 279 136 279 92 279 98 280 156 280 148 280 98 281 139 281 156 281 139 282 155 282 156 282 141 283 139 283 98 283 98 284 96 284 141 284 96 285 138 285 141 285 214 286 141 286 138 286 138 287 142 287 214 287 140 288 41 288 150 288 41 289 57 289 150 289 41 290 140 290 89 290 140 291 207 291 89 291 209 292 207 292 140 292 150 293 151 293 140 293 140 294 139 294 141 294 140 295 155 295 139 295 140 296 152 296 155 296 140 297 151 297 152 297 141 298 212 298 210 298 212 299 141 299 214 299 214 300 142 300 217 300 218 301 217 301 144 301 217 302 142 302 144 302 144 303 91 303 218 303 146 304 145 304 147 304 154 305 146 305 147 305 147 306 148 306 154 306 149 307 153 307 55 307 153 308 56 308 55 308 153 309 57 309 56 309 153 310 150 310 57 310 153 311 151 311 150 311 153 312 152 312 151 312 153 313 155 313 152 313 155 314 153 314 154 314 158 315 163 315 25 315 25 316 159 316 28 316 25 317 160 317 159 317 25 318 161 318 160 318 25 319 162 319 161 319 25 320 163 320 162 320 224 321 225 321 168 321 225 322 167 322 168 322 225 323 23 323 167 323 22 324 23 324 225 324 225 325 3 325 22 325 219 326 215 326 216 326 164 327 215 327 219 327 219 328 220 328 164 328 220 329 221 329 164 329 165 330 164 330 221 330 221 331 222 331 165 331 165 332 222 332 166 332 223 333 224 333 168 333 92 334 169 334 91 334 91 335 169 335 170 335 91 336 170 336 230 336 170 337 171 337 230 337 171 338 172 338 230 338 172 339 173 339 226 339 14 340 179 340 178 340 14 341 180 341 179 341 14 342 181 342 180 342 14 343 182 343 181 343 14 344 183 344 182 344 14 345 184 345 183 345 14 346 185 346 184 346 14 347 186 347 185 347 14 348 187 348 186 348 14 349 15 349 187 349 189 350 135 350 188 350 188 351 190 351 189 351 190 352 191 352 189 352 191 353 192 353 189 353 201 354 189 354 199 354 189 355 192 355 199 355 189 356 201 356 193 356 202 357 193 357 201 357 193 358 202 358 194 358 202 359 195 359 194 359 202 360 196 360 195 360 202 361 197 361 196 361 202 362 198 362 197 362 199 363 203 363 201 363 204 364 201 364 203 364 201 365 204 365 200 365 200 366 202 366 201 366 203 367 205 367 204 367 206 368 204 368 205 368 205 369 13 369 206 369 10 370 206 370 13 370 87 371 89 371 88 371 208 372 88 372 89 372 89 373 207 373 208 373 211 374 208 374 209 374 208 375 207 375 209 375 209 376 210 376 211 376 213 377 211 377 212 377 211 378 210 378 212 378 212 379 214 379 213 379 216 380 213 380 214 380 214 381 217 381 216 381 216 382 217 382 219 382 217 383 218 383 219 383 227 384 218 384 91 384 219 385 218 385 227 385 228 386 220 386 219 386 221 387 220 387 228 387 229 388 222 388 221 388 223 389 222 389 229 389 223 390 231 390 224 390 366 391 364 391 348 391 366 392 348 392 308 392 314 393 274 393 273 393 314 394 273 394 313 394 312 395 310 395 309 395 311 396 312 396 309 396 286 397 272 397 269 397 286 398 285 398 272 398 330 399 232 399 287 399 287 400 232 400 292 400 292 401 232 401 293 401 293 402 232 402 291 402 291 403 232 403 289 403 289 404 232 404 294 404 294 405 232 405 327 405 298 406 289 406 294 406 293 407 291 407 290 407 293 408 290 408 292 408 296 409 271 409 288 409 290 410 288 410 271 410 290 411 271 411 270 411 272 412 270 412 271 412 313 413 270 413 272 413 284 414 313 414 272 414 313 415 273 415 270 415 292 416 290 416 270 416 292 417 270 417 273 417 294 418 14 418 51 418 272 419 285 419 284 419 279 420 277 420 276 420 347 421 344 421 340 421 32 422 252 422 251 422 32 423 259 423 252 423 233 424 372 424 371 424 372 425 233 425 326 425 247 426 326 426 233 426 234 427 371 427 370 427 371 428 234 428 233 428 248 429 247 429 233 429 370 430 235 430 234 430 370 431 236 431 235 431 237 432 233 432 234 432 233 433 237 433 248 433 238 434 234 434 235 434 234 435 238 435 237 435 239 436 235 436 236 436 235 437 239 437 238 437 236 438 246 438 239 438 249 439 248 439 237 439 240 440 237 440 238 440 237 441 240 441 249 441 241 442 238 442 239 442 238 443 241 443 240 443 239 444 242 444 241 444 242 445 239 445 246 445 246 446 243 446 242 446 250 447 249 447 240 447 240 448 244 448 250 448 244 449 240 449 241 449 241 450 261 450 244 450 261 451 241 451 242 451 242 452 260 452 261 452 260 453 242 453 243 453 243 454 258 454 260 454 262 455 244 455 261 455 244 456 262 456 250 456 263 457 250 457 262 457 246 458 245 458 243 458 245 459 258 459 243 459 236 460 264 460 246 460 326 461 247 461 325 461 278 462 325 462 247 462 247 463 248 463 278 463 277 464 278 464 248 464 248 465 249 465 277 465 276 466 277 466 249 466 249 467 250 467 276 467 275 468 276 468 250 468 250 469 263 469 275 469 346 470 275 470 263 470 259 471 254 471 253 471 259 472 255 472 254 472 259 473 256 473 255 473 259 474 258 474 256 474 258 475 257 475 256 475 260 476 258 476 259 476 259 477 32 477 260 477 32 478 261 478 260 478 5 479 345 479 32 479 345 480 261 480 32 480 262 481 261 481 345 481 345 482 346 482 262 482 346 483 263 483 262 483 328 484 334 484 18 484 18 485 335 485 8 485 18 486 334 486 335 486 265 487 334 487 328 487 266 488 265 488 328 488 333 489 265 489 266 489 332 490 333 490 266 490 331 491 332 491 266 491 266 492 327 492 331 492 232 493 331 493 327 493 14 494 294 494 327 494 303 495 348 495 302 495 308 496 348 496 303 496 303 497 304 497 308 497 307 498 308 498 304 498 304 499 305 499 307 499 305 500 309 500 307 500 305 501 306 501 309 501 311 502 309 502 306 502 31 503 311 503 306 503 358 504 72 504 59 504 59 505 299 505 358 505 356 506 358 506 299 506 299 507 300 507 356 507 353 508 356 508 300 508 300 509 301 509 353 509 351 510 353 510 301 510 301 511 302 511 351 511 351 512 302 512 348 512 19 513 311 513 30 513 30 514 311 514 31 514 297 515 295 515 268 515 267 516 268 516 295 516 267 517 269 517 268 517 267 518 352 518 269 518 267 519 354 519 352 519 267 520 355 520 354 520 357 521 355 521 267 521 45 522 267 522 49 522 267 523 295 523 49 523 267 524 45 524 357 524 45 525 70 525 357 525 268 526 296 526 297 526 271 527 296 527 268 527 272 528 271 528 268 528 268 529 269 529 272 529 352 530 286 530 269 530 281 531 330 531 287 531 274 532 287 532 292 532 287 533 274 533 281 533 274 534 283 534 281 534 292 535 273 535 274 535 274 536 314 536 283 536 283 537 314 537 315 537 346 538 347 538 275 538 347 539 276 539 275 539 347 540 279 540 276 540 279 541 280 541 277 541 280 542 278 542 277 542 280 543 325 543 278 543 280 544 324 544 325 544 280 545 323 545 324 545 280 546 279 546 340 546 279 547 347 547 340 547 322 548 323 548 280 548 340 549 341 549 280 549 280 550 282 550 322 550 282 551 321 551 322 551 282 552 320 552 321 552 282 553 319 553 320 553 282 554 280 554 336 554 280 555 339 555 336 555 280 556 342 556 339 556 280 557 341 557 342 557 336 558 337 558 282 558 283 559 282 559 281 559 282 560 330 560 281 560 282 561 329 561 330 561 282 562 337 562 329 562 282 563 283 563 319 563 283 564 318 564 319 564 283 565 317 565 318 565 283 566 315 566 317 566 359 567 316 567 360 567 361 568 360 568 316 568 361 569 313 569 284 569 361 570 316 570 313 570 284 571 362 571 361 571 284 572 363 572 362 572 284 573 365 573 363 573 350 574 365 574 285 574 365 575 284 575 285 575 285 576 286 576 350 576 349 577 350 577 286 577 286 578 352 578 349 578 296 579 288 579 298 579 289 580 298 580 288 580 288 581 290 581 289 581 291 582 289 582 290 582 294 583 51 583 295 583 51 584 49 584 295 584 51 585 50 585 49 585 294 586 295 586 298 586 295 587 297 587 298 587 296 588 298 588 297 588 59 589 25 589 299 589 25 590 300 590 299 590 25 591 301 591 300 591 302 592 301 592 25 592 25 593 303 593 302 593 25 594 304 594 303 594 25 595 305 595 304 595 25 596 306 596 305 596 25 597 31 597 306 597 310 598 308 598 307 598 307 599 309 599 310 599 308 600 310 600 366 600 367 601 366 601 310 601 367 602 310 602 312 602 368 603 367 603 312 603 369 604 368 604 312 604 20 605 0 605 19 605 0 606 369 606 19 606 311 607 19 607 312 607 19 608 369 608 312 608 316 609 314 609 313 609 316 610 315 610 314 610 316 611 359 611 315 611 359 612 317 612 315 612 359 613 377 613 317 613 377 614 318 614 317 614 377 615 319 615 318 615 14 616 327 616 9 616 327 617 266 617 9 617 266 618 328 618 9 618 18 619 9 619 328 619 330 620 331 620 232 620 331 621 330 621 329 621 331 622 329 622 332 622 329 623 333 623 332 623 338 624 333 624 329 624 333 625 338 625 265 625 338 626 335 626 265 626 335 627 334 627 265 627 335 628 338 628 8 628 338 629 343 629 8 629 343 630 338 630 339 630 338 631 336 631 339 631 338 632 337 632 336 632 338 633 329 633 337 633 7 634 8 634 343 634 339 635 342 635 343 635 344 636 343 636 340 636 343 637 341 637 340 637 343 638 342 638 341 638 343 639 344 639 7 639 344 640 6 640 7 640 4 641 6 641 344 641 344 642 347 642 4 642 5 643 4 643 345 643 4 644 346 644 345 644 4 645 347 645 346 645 348 646 364 646 351 646 365 647 350 647 364 647 350 648 351 648 364 648 353 649 351 649 352 649 351 650 349 650 352 650 351 651 350 651 349 651 352 652 354 652 353 652 356 653 353 653 354 653 354 654 355 654 356 654 358 655 356 655 357 655 356 656 355 656 357 656 357 657 70 657 358 657 72 658 358 658 70 658 359 659 360 659 377 659 360 660 361 660 373 660 361 661 362 661 373 661 373 662 362 662 363 662 363 663 365 663 374 663 374 664 364 664 366 664 374 665 365 665 364 665 375 666 366 666 367 666 367 667 368 667 376 667 372 668 388 668 387 668 372 669 387 669 371 669 371 670 387 670 386 670 371 671 386 671 370 671 370 672 386 672 391 672 391 673 386 673 385 673 379 674 245 674 383 674 264 675 383 675 245 675 393 676 392 676 128 676 124 677 128 677 392 677 124 678 392 678 125 678 390 679 127 679 126 679 390 680 226 680 127 680 177 681 127 681 226 681 236 682 370 682 391 682 401 683 372 683 326 683 128 684 380 684 393 684 393 685 380 685 391 685 380 686 381 686 391 686 381 687 382 687 391 687 382 688 383 688 391 688 383 689 264 689 391 689 264 690 236 690 391 690 172 691 226 691 230 691 173 692 174 692 226 692 174 693 175 693 226 693 175 694 176 694 226 694 177 695 226 695 176 695 377 696 320 696 319 696 377 697 321 697 320 697 377 698 322 698 321 698 377 699 323 699 322 699 377 700 324 700 323 700 377 701 325 701 324 701 377 702 326 702 325 702 326 703 377 703 401 703 377 704 402 704 401 704 403 705 401 705 402 705 230 706 227 706 91 706 227 707 228 707 219 707 228 708 229 708 221 708 229 709 231 709 223 709 373 710 377 710 360 710 374 711 373 711 363 711 375 712 374 712 366 712 376 713 375 713 367 713 378 714 376 714 369 714 376 715 368 715 369 715 0 716 378 716 369 716 225 717 224 717 231 717 378 718 1 718 2 718 378 719 0 719 1 719 384 720 389 720 391 720 385 721 384 721 391 721 372 722 401 722 388 722 403 723 388 723 401 723 377 724 373 724 402 724 373 725 394 725 402 725 395 726 394 726 373 726 373 727 374 727 395 727 396 728 395 728 374 728 374 729 375 729 396 729 397 730 396 730 398 730 396 731 375 731 398 731 376 732 398 732 375 732 399 733 397 733 400 733 397 734 398 734 400 734 376 735 400 735 398 735 400 736 404 736 399 736 378 737 400 737 376 737 404 738 400 738 378 738 455 739 416 739 454 739 455 740 454 740 404 740 446 741 405 741 388 741 403 742 446 742 388 742 421 743 419 743 420 743 435 744 420 744 419 744 411 745 389 745 384 745 452 746 378 746 450 746 422 747 421 747 420 747 423 748 422 748 420 748 408 749 407 749 411 749 408 750 411 750 444 750 443 751 408 751 444 751 407 752 389 752 411 752 449 753 411 753 446 753 411 754 405 754 446 754 406 755 405 755 411 755 411 756 386 756 406 756 411 757 385 757 386 757 411 758 384 758 385 758 388 759 405 759 387 759 387 760 405 760 406 760 387 761 406 761 386 761 389 762 407 762 391 762 412 763 444 763 411 763 409 764 442 764 444 764 409 765 444 765 412 765 412 766 413 766 409 766 441 767 442 767 409 767 409 768 410 768 441 768 410 769 440 769 441 769 410 770 409 770 414 770 409 771 413 771 414 771 439 772 440 772 410 772 414 773 415 773 410 773 410 774 452 774 439 774 452 775 438 775 439 775 410 776 455 776 452 776 416 777 455 777 410 777 410 778 415 778 416 778 453 779 438 779 452 779 449 780 427 780 411 780 426 781 411 781 427 781 424 782 411 782 426 782 412 783 411 783 423 783 411 784 424 784 423 784 413 785 412 785 420 785 412 786 423 786 420 786 414 787 413 787 434 787 413 788 436 788 434 788 413 789 420 789 436 789 415 790 414 790 433 790 414 791 432 791 433 791 414 792 434 792 432 792 416 793 415 793 430 793 415 794 433 794 430 794 416 795 428 795 454 795 416 796 430 796 428 796 399 797 404 797 429 797 429 798 431 798 399 798 417 799 431 799 419 799 431 800 435 800 419 800 431 801 417 801 399 801 417 802 397 802 399 802 396 803 397 803 417 803 419 804 421 804 417 804 418 805 417 805 421 805 417 806 418 806 396 806 418 807 395 807 396 807 394 808 395 808 418 808 421 809 422 809 418 809 418 810 448 810 447 810 418 811 422 811 448 811 418 812 447 812 394 812 447 813 402 813 394 813 436 814 420 814 435 814 423 815 425 815 422 815 425 816 448 816 422 816 425 817 423 817 424 817 448 818 425 818 426 818 425 819 424 819 426 819 426 820 427 820 448 820 448 821 427 821 449 821 429 822 404 822 454 822 454 823 428 823 429 823 431 824 429 824 430 824 429 825 428 825 430 825 435 826 431 826 433 826 431 827 430 827 433 827 435 828 432 828 434 828 435 829 433 829 432 829 436 830 435 830 434 830 445 831 443 831 437 831 443 832 451 832 437 832 443 833 453 833 451 833 443 834 438 834 453 834 443 835 439 835 438 835 443 836 440 836 439 836 443 837 441 837 440 837 443 838 442 838 441 838 443 839 444 839 442 839 402 840 447 840 403 840 446 841 403 841 449 841 403 842 447 842 449 842 447 843 448 843 449 843 378 844 455 844 404 844 452 845 455 845 378 845 534 846 532 846 524 846 532 847 522 847 524 847 532 848 520 848 522 848 532 849 519 849 520 849 452 850 450 850 563 850 452 851 563 851 564 851 563 852 450 852 562 852 393 853 456 853 392 853 509 854 510 854 461 854 463 855 461 855 510 855 510 856 552 856 463 856 465 857 463 857 552 857 552 858 550 858 465 858 471 859 460 859 470 859 460 860 469 860 470 860 460 861 468 861 469 861 456 862 472 862 468 862 456 863 393 863 472 863 456 864 468 864 460 864 460 865 462 865 456 865 456 866 457 866 392 866 457 867 456 867 464 867 456 868 462 868 464 868 459 869 392 869 457 869 464 870 466 870 457 870 457 871 458 871 459 871 458 872 457 872 466 872 466 873 467 873 458 873 390 874 459 874 458 874 458 875 526 875 390 875 458 876 545 876 526 876 458 877 467 877 545 877 390 878 526 878 226 878 392 879 459 879 125 879 126 880 125 880 459 880 459 881 390 881 126 881 506 882 507 882 471 882 460 883 471 883 508 883 471 884 507 884 508 884 462 885 460 885 509 885 460 886 508 886 509 886 509 887 461 887 462 887 464 888 462 888 463 888 462 889 461 889 463 889 463 890 465 890 464 890 466 891 464 891 465 891 465 892 550 892 466 892 467 893 466 893 550 893 550 894 548 894 467 894 545 895 467 895 547 895 467 896 548 896 547 896 443 897 445 897 504 897 504 898 473 898 443 898 473 899 408 899 443 899 473 900 504 900 506 900 506 901 471 901 473 901 407 902 408 902 391 902 391 903 468 903 472 903 391 904 469 904 468 904 391 905 470 905 469 905 391 906 473 906 470 906 473 907 471 907 470 907 391 908 408 908 473 908 472 909 393 909 391 909 480 910 481 910 482 910 482 911 483 911 480 911 479 912 480 912 483 912 483 913 484 913 479 913 478 914 479 914 484 914 484 915 485 915 478 915 477 916 478 916 485 916 485 917 486 917 477 917 476 918 477 918 486 918 486 919 487 919 476 919 475 920 476 920 487 920 487 921 488 921 437 921 437 922 475 922 487 922 474 923 475 923 437 923 437 924 488 924 445 924 451 925 474 925 437 925 564 926 489 926 451 926 474 927 451 927 489 927 489 928 490 928 474 928 475 929 474 929 491 929 474 930 490 930 491 930 476 931 475 931 492 931 475 932 491 932 492 932 492 933 493 933 476 933 477 934 476 934 493 934 493 935 494 935 477 935 478 936 477 936 494 936 494 937 495 937 478 937 479 938 478 938 495 938 495 939 496 939 479 939 480 940 479 940 496 940 496 941 497 941 480 941 481 942 480 942 497 942 497 943 498 943 481 943 482 944 481 944 498 944 498 945 499 945 482 945 483 946 482 946 499 946 499 947 500 947 483 947 484 948 483 948 500 948 500 949 501 949 484 949 485 950 484 950 501 950 501 951 502 951 485 951 486 952 485 952 502 952 502 953 503 953 486 953 487 954 486 954 503 954 503 955 505 955 487 955 488 956 487 956 505 956 505 957 504 957 488 957 445 958 488 958 504 958 532 959 530 959 519 959 530 960 517 960 519 960 530 961 528 961 517 961 528 962 516 962 517 962 528 963 514 963 516 963 557 964 514 964 528 964 528 965 529 965 557 965 529 966 564 966 557 966 529 967 489 967 564 967 490 968 489 968 529 968 529 969 531 969 490 969 531 970 491 970 490 970 531 971 533 971 491 971 533 972 492 972 491 972 493 973 492 973 533 973 533 974 535 974 493 974 494 975 493 975 535 975 535 976 538 976 494 976 495 977 494 977 538 977 538 978 540 978 495 978 496 979 495 979 540 979 540 980 541 980 496 980 497 981 496 981 541 981 541 982 542 982 497 982 498 983 497 983 542 983 542 984 543 984 498 984 499 985 498 985 543 985 543 986 544 986 499 986 500 987 499 987 544 987 544 988 546 988 500 988 501 989 500 989 546 989 546 990 549 990 501 990 502 991 501 991 549 991 549 992 551 992 502 992 503 993 502 993 551 993 551 994 553 994 503 994 505 995 503 995 553 995 553 996 554 996 505 996 504 997 505 997 506 997 505 998 554 998 506 998 554 999 555 999 506 999 555 1000 507 1000 506 1000 555 1001 556 1001 507 1001 556 1002 508 1002 507 1002 556 1003 509 1003 508 1003 556 1004 552 1004 510 1004 510 1005 509 1005 556 1005 525 1006 527 1006 536 1006 511 1007 527 1007 525 1007 511 1008 230 1008 527 1008 511 1009 227 1009 230 1009 525 1010 523 1010 511 1010 511 1011 512 1011 227 1011 512 1012 511 1012 521 1012 511 1013 523 1013 521 1013 521 1014 518 1014 512 1014 513 1015 512 1015 518 1015 512 1016 513 1016 227 1016 513 1017 228 1017 227 1017 518 1018 515 1018 513 1018 229 1019 228 1019 513 1019 513 1020 559 1020 229 1020 513 1021 558 1021 559 1021 513 1022 562 1022 558 1022 513 1023 515 1023 562 1023 231 1024 229 1024 561 1024 229 1025 560 1025 561 1025 229 1026 559 1026 560 1026 515 1027 557 1027 562 1027 515 1028 514 1028 557 1028 516 1029 514 1029 515 1029 515 1030 518 1030 516 1030 518 1031 517 1031 516 1031 519 1032 517 1032 518 1032 518 1033 521 1033 519 1033 521 1034 520 1034 519 1034 522 1035 520 1035 521 1035 521 1036 523 1036 522 1036 524 1037 522 1037 523 1037 523 1038 525 1038 524 1038 534 1039 524 1039 525 1039 525 1040 536 1040 534 1040 537 1041 534 1041 536 1041 226 1042 526 1042 230 1042 527 1043 230 1043 526 1043 526 1044 545 1044 527 1044 536 1045 527 1045 545 1045 528 1046 530 1046 529 1046 531 1047 529 1047 530 1047 530 1048 532 1048 531 1048 533 1049 531 1049 532 1049 532 1050 534 1050 533 1050 535 1051 533 1051 534 1051 534 1052 537 1052 535 1052 538 1053 535 1053 537 1053 536 1054 545 1054 537 1054 545 1055 539 1055 537 1055 539 1056 538 1056 537 1056 539 1057 540 1057 538 1057 545 1058 546 1058 539 1058 541 1059 540 1059 539 1059 539 1060 542 1060 541 1060 539 1061 543 1061 542 1061 539 1062 544 1062 543 1062 546 1063 544 1063 539 1063 549 1064 546 1064 547 1064 546 1065 545 1065 547 1065 547 1066 548 1066 549 1066 551 1067 549 1067 550 1067 549 1068 548 1068 550 1068 550 1069 552 1069 551 1069 553 1070 551 1070 552 1070 552 1071 556 1071 553 1071 554 1072 553 1072 556 1072 556 1073 555 1073 554 1073 562 1074 557 1074 563 1074 557 1075 564 1075 563 1075 378 1076 562 1076 450 1076 378 1077 558 1077 562 1077 378 1078 559 1078 558 1078 378 1079 560 1079 559 1079 378 1080 561 1080 560 1080 378 1081 231 1081 561 1081 564 1082 451 1082 453 1082 453 1083 452 1083 564 1083 565 1084 256 1084 257 1084 252 1085 259 1085 253 1085 253 1086 566 1086 252 1086 567 1087 565 1087 257 1087 257 1088 568 1088 567 1088 252 1089 566 1089 569 1089 252 1090 569 1090 570 1090 251 1091 252 1091 570 1091 570 1092 571 1092 251 1092 572 1093 251 1093 571 1093 571 1094 573 1094 572 1094 574 1095 572 1095 573 1095 573 1096 575 1096 574 1096 574 1097 575 1097 576 1097 574 1098 576 1098 577 1098 578 1099 574 1099 577 1099 577 1100 579 1100 578 1100 578 1101 579 1101 120 1101 119 1102 578 1102 120 1102 571 1103 570 1103 573 1103 575 1104 573 1104 570 1104 570 1105 580 1105 575 1105 581 1106 575 1106 580 1106 580 1107 582 1107 581 1107 583 1108 581 1108 582 1108 582 1109 584 1109 583 1109 585 1110 583 1110 584 1110 584 1111 586 1111 585 1111 587 1112 585 1112 586 1112 586 1113 588 1113 587 1113 589 1114 587 1114 588 1114 591 1115 589 1115 590 1115 592 1116 591 1116 590 1116 595 1117 593 1117 590 1117 594 1118 596 1118 592 1118 590 1119 597 1119 595 1119 707 1120 592 1120 596 1120 598 1121 595 1121 597 1121 596 1122 599 1122 707 1122 597 1123 600 1123 598 1123 601 1124 707 1124 599 1124 602 1125 598 1125 600 1125 599 1126 603 1126 601 1126 604 1127 601 1127 603 1127 600 1128 605 1128 602 1128 603 1129 606 1129 604 1129 607 1130 602 1130 605 1130 604 1131 606 1131 608 1131 609 1132 604 1132 608 1132 610 1133 611 1133 607 1133 605 1134 610 1134 607 1134 612 1135 611 1135 610 1135 608 1136 612 1136 609 1136 613 1137 609 1137 612 1137 614 1138 613 1138 612 1138 610 1139 614 1139 612 1139 615 1140 616 1140 617 1140 618 1141 617 1141 616 1141 619 1142 621 1142 620 1142 622 1143 620 1143 621 1143 621 1144 623 1144 622 1144 624 1145 622 1145 623 1145 623 1146 625 1146 624 1146 624 1147 625 1147 626 1147 627 1148 624 1148 626 1148 626 1149 628 1149 627 1149 629 1150 627 1150 628 1150 628 1151 630 1151 629 1151 632 1152 633 1152 634 1152 635 1153 632 1153 634 1153 120 1154 636 1154 122 1154 637 1155 122 1155 636 1155 636 1156 638 1156 637 1156 639 1157 637 1157 638 1157 638 1158 640 1158 639 1158 641 1159 639 1159 640 1159 640 1160 642 1160 641 1160 643 1161 641 1161 642 1161 642 1162 644 1162 643 1162 645 1163 643 1163 644 1163 644 1164 646 1164 645 1164 647 1165 645 1165 646 1165 646 1166 648 1166 647 1166 649 1167 647 1167 648 1167 648 1168 615 1168 649 1168 617 1169 649 1169 615 1169 256 1170 650 1170 255 1170 651 1171 255 1171 650 1171 650 1172 652 1172 651 1172 653 1173 651 1173 652 1173 652 1174 654 1174 653 1174 655 1175 653 1175 654 1175 654 1176 656 1176 655 1176 657 1177 655 1177 656 1177 656 1178 658 1178 657 1178 659 1179 657 1179 658 1179 658 1180 660 1180 659 1180 661 1181 659 1181 660 1181 660 1182 662 1182 661 1182 663 1183 661 1183 662 1183 662 1184 635 1184 663 1184 634 1185 663 1185 635 1185 651 1186 254 1186 255 1186 653 1187 566 1187 253 1187 653 1188 253 1188 254 1188 651 1189 653 1189 254 1189 653 1190 655 1190 566 1190 664 1191 570 1191 569 1191 664 1192 569 1192 566 1192 566 1193 655 1193 657 1193 664 1194 566 1194 657 1194 580 1195 570 1195 664 1195 657 1196 659 1196 664 1196 664 1197 659 1197 661 1197 665 1198 664 1198 661 1198 665 1199 582 1199 580 1199 664 1200 665 1200 580 1200 584 1201 582 1201 665 1201 661 1202 663 1202 665 1202 669 1203 586 1203 584 1203 665 1204 669 1204 584 1204 665 1205 663 1205 634 1205 665 1206 634 1206 666 1206 669 1207 665 1207 666 1207 586 1208 669 1208 667 1208 588 1209 586 1209 667 1209 668 1210 597 1210 667 1210 667 1211 669 1211 668 1211 670 1212 668 1212 669 1212 669 1213 666 1213 670 1213 670 1214 666 1214 634 1214 670 1215 634 1215 633 1215 671 1216 670 1216 633 1216 591 1217 592 1217 589 1217 589 1218 592 1218 672 1218 673 1219 589 1219 672 1219 672 1220 674 1220 673 1220 675 1221 673 1221 674 1221 674 1222 676 1222 675 1222 677 1223 675 1223 676 1223 676 1224 616 1224 677 1224 615 1225 677 1225 616 1225 120 1226 579 1226 636 1226 638 1227 636 1227 579 1227 579 1228 577 1228 638 1228 638 1229 577 1229 678 1229 640 1230 638 1230 678 1230 679 1231 642 1231 640 1231 678 1232 679 1232 640 1232 576 1233 575 1233 679 1233 679 1234 678 1234 576 1234 575 1235 581 1235 679 1235 644 1236 642 1236 679 1236 679 1237 581 1237 583 1237 680 1238 679 1238 583 1238 680 1239 646 1239 644 1239 679 1240 680 1240 644 1240 583 1241 585 1241 680 1241 648 1242 646 1242 680 1242 680 1243 585 1243 587 1243 680 1244 587 1244 589 1244 680 1245 589 1245 673 1245 675 1246 680 1246 673 1246 680 1247 675 1247 648 1247 648 1248 675 1248 677 1248 615 1249 648 1249 677 1249 681 1250 682 1250 617 1250 618 1251 681 1251 617 1251 683 1252 682 1252 681 1252 681 1253 684 1253 683 1253 685 1254 683 1254 684 1254 684 1255 630 1255 685 1255 628 1256 685 1256 630 1256 686 1257 687 1257 629 1257 631 1258 686 1258 629 1258 688 1259 687 1259 686 1259 686 1260 689 1260 688 1260 690 1261 688 1261 689 1261 689 1262 632 1262 690 1262 635 1263 690 1263 632 1263 256 1264 691 1264 650 1264 652 1265 650 1265 691 1265 691 1266 692 1266 652 1266 654 1267 652 1267 692 1267 692 1268 693 1268 654 1268 656 1269 654 1269 693 1269 694 1270 658 1270 656 1270 693 1271 694 1271 656 1271 695 1272 620 1272 694 1272 696 1273 695 1273 694 1273 697 1274 696 1274 694 1274 694 1275 693 1275 697 1275 620 1276 622 1276 694 1276 660 1277 658 1277 694 1277 694 1278 622 1278 624 1278 694 1279 624 1279 627 1279 694 1280 627 1280 629 1280 694 1281 629 1281 687 1281 688 1282 694 1282 687 1282 688 1283 662 1283 660 1283 694 1284 688 1284 660 1284 662 1285 688 1285 690 1285 635 1286 662 1286 690 1286 245 1287 257 1287 258 1287 246 1288 264 1288 245 1288 568 1289 257 1289 245 1289 379 1290 698 1290 699 1290 699 1291 568 1291 245 1291 700 1292 379 1292 383 1292 383 1293 382 1293 700 1293 381 1294 701 1294 700 1294 382 1295 381 1295 700 1295 100 1296 701 1296 381 1296 381 1297 380 1297 100 1297 100 1298 110 1298 123 1298 100 1299 380 1299 128 1299 702 1300 606 1300 603 1300 608 1301 606 1301 702 1301 612 1302 608 1302 702 1302 611 1303 612 1303 702 1303 607 1304 611 1304 702 1304 602 1305 607 1305 702 1305 702 1306 598 1306 602 1306 595 1307 598 1307 702 1307 593 1308 595 1308 702 1308 594 1309 593 1309 702 1309 596 1310 594 1310 702 1310 599 1311 596 1311 702 1311 603 1312 599 1312 702 1312 703 1313 597 1313 668 1313 668 1314 670 1314 703 1314 704 1315 703 1315 670 1315 670 1316 671 1316 704 1316 672 1317 705 1317 674 1317 676 1318 674 1318 705 1318 705 1319 706 1319 676 1319 676 1320 706 1320 616 1320 708 1321 600 1321 597 1321 703 1322 708 1322 597 1322 704 1323 671 1323 708 1323 703 1324 704 1324 708 1324 671 1325 709 1325 708 1325 605 1326 600 1326 708 1326 710 1327 708 1327 709 1327 710 1328 610 1328 605 1328 708 1329 710 1329 605 1329 709 1330 711 1330 710 1330 614 1331 610 1331 710 1331 710 1332 711 1332 712 1332 713 1333 710 1333 712 1333 710 1334 713 1334 614 1334 613 1335 614 1335 713 1335 712 1336 714 1336 713 1336 715 1337 713 1337 714 1337 713 1338 715 1338 613 1338 609 1339 613 1339 715 1339 714 1340 716 1340 715 1340 717 1341 604 1341 609 1341 715 1342 717 1342 609 1342 717 1343 715 1343 716 1343 601 1344 604 1344 717 1344 716 1345 616 1345 717 1345 705 1346 707 1346 601 1346 717 1347 705 1347 601 1347 717 1348 616 1348 706 1348 717 1349 706 1349 705 1349 672 1350 707 1350 705 1350 720 1351 699 1351 698 1351 721 1352 699 1352 720 1352 720 1353 719 1353 721 1353 722 1354 721 1354 719 1354 719 1355 718 1355 722 1355 722 1356 718 1356 619 1356 722 1357 619 1357 620 1357 32 1358 251 1358 572 1358 32 1359 572 1359 574 1359 32 1360 574 1360 578 1360 32 1361 578 1361 119 1361 33 1362 32 1362 119 1362 577 1363 576 1363 678 1363 698 1364 379 1364 700 1364 700 1365 701 1365 698 1365 707 1366 672 1366 592 1366 245 1367 379 1367 699 1367 620 1368 695 1368 722 1368 699 1369 721 1369 722 1369 695 1370 699 1370 722 1370 695 1371 696 1371 699 1371 696 1372 697 1372 699 1372 568 1373 699 1373 697 1373 568 1374 697 1374 693 1374 568 1375 693 1375 692 1375 567 1376 568 1376 692 1376 567 1377 692 1377 691 1377 565 1378 567 1378 691 1378 256 1379 565 1379 691 1379 588 1380 590 1380 589 1380 588 1381 667 1381 590 1381 629 1382 630 1382 631 1382 631 1383 724 1383 723 1383 630 1384 724 1384 631 1384 671 1385 633 1385 632 1385 689 1386 726 1386 632 1386 686 1387 726 1387 689 1387 723 1388 727 1388 726 1388 723 1389 728 1389 727 1389 723 1390 724 1390 728 1390 724 1391 729 1391 728 1391 724 1392 725 1392 729 1392 681 1393 618 1393 725 1393 681 1394 725 1394 684 1394 122 1395 739 1395 745 1395 745 1396 739 1396 744 1396 744 1397 739 1397 738 1397 744 1398 738 1398 743 1398 743 1399 738 1399 737 1399 743 1400 737 1400 733 1400 743 1401 733 1401 732 1401 734 1402 732 1402 733 1402 735 1403 732 1403 734 1403 735 1404 730 1404 732 1404 732 1405 730 1405 731 1405 742 1406 730 1406 735 1406 100 1407 732 1407 701 1407 730 1408 742 1408 619 1408 730 1409 619 1409 718 1409 719 1410 730 1410 718 1410 730 1411 719 1411 731 1411 720 1412 731 1412 719 1412 731 1413 720 1413 732 1413 720 1414 698 1414 732 1414 732 1415 100 1415 743 1415 701 1416 732 1416 698 1416 743 1417 100 1417 123 1417 617 1418 682 1418 649 1418 649 1419 682 1419 683 1419 736 1420 647 1420 683 1420 683 1421 647 1421 649 1421 683 1422 685 1422 736 1422 736 1423 685 1423 628 1423 736 1424 628 1424 626 1424 736 1425 626 1425 740 1425 736 1426 740 1426 741 1426 647 1427 736 1427 645 1427 742 1428 736 1428 741 1428 736 1429 733 1429 737 1429 733 1430 736 1430 734 1430 734 1431 736 1431 735 1431 735 1432 736 1432 742 1432 737 1433 643 1433 736 1433 736 1434 643 1434 645 1434 643 1435 737 1435 641 1435 738 1436 641 1436 737 1436 641 1437 738 1437 639 1437 739 1438 639 1438 738 1438 639 1439 739 1439 637 1439 122 1440 637 1440 739 1440 623 1441 740 1441 625 1441 740 1442 623 1442 741 1442 621 1443 741 1443 623 1443 741 1444 621 1444 742 1444 619 1445 742 1445 621 1445 123 1446 744 1446 743 1446 744 1447 123 1447 745 1447 745 1448 123 1448 122 1448 625 1449 740 1449 626 1449 590 1450 594 1450 592 1450 590 1451 593 1451 594 1451 590 1452 667 1452 597 1452 631 1453 723 1453 686 1453 686 1454 723 1454 726 1454 630 1455 684 1455 724 1455 684 1456 725 1456 724 1456 709 1457 671 1457 726 1457 671 1458 632 1458 726 1458 716 1459 714 1459 729 1459 716 1460 729 1460 725 1460 714 1461 712 1461 728 1461 714 1462 728 1462 729 1462 712 1463 711 1463 727 1463 712 1464 727 1464 728 1464 711 1465 709 1465 726 1465 711 1466 726 1466 727 1466 616 1467 716 1467 725 1467 616 1468 725 1468 618 1468 2 1469 231 1469 378 1469 2 1470 3 1470 231 1470 3 1471 225 1471 231 1471 14 1472 68 1472 65 1472 14 1473 52 1473 68 1473 14 1474 54 1474 52 1474 14 1475 55 1475 54 1475 14 1476 65 1476 64 1476 14 1477 64 1477 47 1477 14 1478 47 1478 35 1478 14 1479 35 1479 48 1479 25 1480 59 1480 58 1480 25 1481 58 1481 40 1481 25 1482 40 1482 39 1482 25 1483 39 1483 38 1483 25 1484 38 1484 34 1484 25 1485 34 1485 37 1485 25 1486 37 1486 36 1486 25 1487 36 1487 60 1487

+
+
+
+
+ + + + 0.00000 0.00002 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E2M3.dae b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E2M3.dae new file mode 100644 index 0000000..71e98f5 --- /dev/null +++ b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E2M3.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:16:22.697136 + 2012-07-23T02:16:22.697149 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -4.16853 10.99697 56.91780 -2.13558 10.99697 56.22232 0.00030 10.99697 55.98668 2.13616 10.99697 56.22231 -7.41158 1.43357 57.78464 -7.54952 -0.00303 57.78464 -7.00374 2.81535 57.78464 -6.34754 4.08412 57.78464 -5.49969 5.16901 57.78464 -1.03468 8.49697 57.78464 2.42357 7.14735 57.78464 1.05031 7.94142 58.24917 1.05031 7.47344 57.78464 2.60851 7.94142 58.63739 0.00031 8.55728 68.91865 2.28125 8.49697 59.99264 1.05031 8.49697 59.64888 1.03530 8.49697 57.78464 -4.99969 8.49697 57.78464 -2.90817 11.39697 59.72056 -1.50644 11.39697 59.23010 -0.00019 11.39697 59.05914 1.50620 11.39697 59.22990 2.90832 11.39697 59.72033 0.00031 11.49528 59.76977 0.00032 11.49697 65.90822 1.69915 11.49697 60.07462 2.73893 11.49697 60.49405 3.64845 11.49697 61.07492 -1.69865 11.49697 60.07465 -2.73841 11.49697 60.49409 -3.64783 11.49697 61.07491 -7.54952 -4.00303 57.78464 7.55014 -4.00303 57.78465 1.13878 11.48797 71.16059 -3.33824 9.49194 70.55422 2.78628 11.49697 70.25549 2.27099 11.48797 70.79404 0.00032 11.48797 71.28465 -1.16122 11.48797 71.16059 -2.27036 11.48797 70.79404 5.28198 10.27446 71.13149 -1.06765 10.38028 73.07560 1.06828 10.38028 73.07560 3.10938 10.38170 72.45206 -5.28136 10.27446 71.13149 -3.10875 10.38170 72.45206 -2.54465 9.65113 71.40520 -3.28925 9.10508 69.40430 -5.96849 9.74083 70.08224 -4.84852 9.88731 71.04855 -3.17535 8.69990 68.29736 2.54802 9.65113 71.40519 3.44225 9.96396 71.93696 3.33827 9.49238 70.55584 3.28988 9.10508 69.40430 4.96737 9.87593 70.95893 5.56944 9.80370 70.45921 -2.78565 11.49697 70.25549 -3.73788 11.49697 69.49624 3.73850 11.49697 69.49624 4.49082 11.49697 68.53881 -3.86623 9.95133 71.70066 -2.59559 9.96856 72.33196 -1.30422 9.65113 71.81620 0.00028 9.65113 71.95565 -1.06018 9.96856 72.74751 0.81113 9.96856 72.78098 1.30478 9.65113 71.81622 2.01662 9.96856 72.53303 -5.53304 10.70933 70.64544 -4.96728 10.77157 71.09794 -4.80699 11.04699 70.66184 -3.94573 10.83814 71.77613 -3.60196 11.04698 71.60882 -2.63388 10.85606 72.42852 -1.65129 10.85606 72.73823 -2.23214 11.04697 72.25872 -0.46035 10.85606 72.91682 -0.75524 11.04697 72.59101 0.82309 10.85606 72.88416 0.76285 11.04697 72.59023 2.04635 10.85606 72.63255 2.57708 10.85606 72.45101 2.23939 11.04697 72.25643 3.99747 10.83605 71.74595 3.60862 11.04698 71.60508 5.09086 10.75973 71.00474 4.81271 11.04698 70.65682 5.71692 10.68463 70.48512 7.49423 7.94157 64.50987 8.92281 8.79775 63.71438 8.99367 8.08742 64.55763 8.69039 8.16196 65.11563 8.37644 7.53031 64.74487 8.95635 8.26939 64.86778 8.74722 9.00930 65.88835 8.77245 8.65637 65.41832 8.59545 8.83116 65.91737 7.72686 7.83903 65.04834 3.52352 -10.85658 55.20966 8.68893 -9.29155 57.92509 6.99644 -10.79866 56.75002 7.84651 -10.23448 57.50816 5.86119 -10.91940 56.20141 8.38834 -9.29184 58.21590 7.69150 -10.17120 57.61452 6.76178 -10.62444 56.96974 8.13379 -9.19327 58.25332 7.47072 -9.98157 57.66316 5.77439 -10.75303 56.34334 8.94369 -8.00302 58.26979 8.78663 -8.00302 58.44858 8.56473 -8.00302 58.53452 8.32824 -8.00302 58.50813 8.13074 -8.00303 58.37546 7.90869 -9.03650 58.13997 7.35169 -9.84937 57.60191 6.68573 -10.50130 57.00586 5.91680 -4.00303 56.51129 4.88920 -6.00303 55.93077 5.73944 -10.50303 56.40048 4.88920 -9.00303 55.93077 4.61923 -10.50303 55.80138 6.73955 -10.91053 56.37839 7.08858 -10.77342 56.59704 8.02298 -10.21861 57.23000 8.72172 -9.24322 57.79251 6.00031 -11.00303 55.97394 8.68089 5.63812 61.18336 8.56476 -0.00303 58.53451 8.32827 -0.00303 58.50815 8.68089 3.11933 59.20854 8.94369 -0.00303 58.26979 8.78664 -0.00303 58.44856 8.13074 7.10166 63.68239 8.67571 7.07942 64.04446 8.80273 7.58718 64.67844 8.80114 9.23126 65.82974 8.21285 9.19201 67.21714 7.07571 9.96326 69.35165 8.37914 9.46742 67.22308 8.75185 9.44767 65.75461 8.94514 8.88449 64.98747 8.80831 9.32990 65.52029 8.33006 8.34255 65.38938 7.94636 8.50667 65.71574 8.55656 8.56278 65.49903 8.37959 8.73646 65.91035 3.67569 8.71842 68.35970 6.20627 9.69696 69.83866 6.80137 9.56087 69.14859 7.29869 9.41038 68.46049 6.91519 8.54095 65.99626 7.57014 8.64119 66.07724 7.70401 9.25230 67.79227 8.22660 8.93963 66.59763 5.00357 11.49697 67.43311 5.24853 11.49697 66.23880 4.11090 11.49697 61.54639 4.49544 11.49697 62.19938 4.79629 11.49697 63.01113 5.02916 11.49697 63.95683 5.21279 11.49697 65.02298 6.34688 11.17864 63.68803 5.87602 11.27726 62.68842 5.34956 11.34554 61.80425 4.11882 11.39697 60.46767 4.73815 11.17530 59.66812 9.00031 7.42460 63.58684 9.00031 5.53833 60.37230 9.00031 4.97167 59.84727 9.00031 4.28707 59.33522 9.00031 3.46270 58.85725 9.00031 2.48084 58.44772 9.00031 1.33136 58.15448 9.00031 -0.00303 58.03868 9.00031 -8.00303 58.03868 6.58902 8.49697 65.82475 6.37200 8.49544 65.34729 6.13723 8.49697 64.74155 6.02274 8.49697 64.20972 5.84711 8.49697 63.64807 5.59360 8.49697 63.05240 5.24033 8.49697 62.42426 4.76095 8.49697 61.77386 4.12606 8.49697 61.12329 3.30603 8.49697 60.50996 7.35819 7.94142 63.84882 8.13074 5.63518 60.98634 7.13793 7.94142 63.15024 6.81856 7.94142 62.40866 6.37180 7.94142 61.62654 8.13074 3.31200 59.15843 8.13074 2.37288 58.76674 8.13074 1.27351 58.48625 8.13074 -0.00303 58.37546 7.84601 -0.00303 58.07458 7.55014 -0.00303 57.78465 5.76359 7.94142 60.81770 5.95262 4.64133 57.78465 6.76130 5.63631 59.19019 6.93098 2.91600 57.78465 4.95613 7.94142 60.01181 4.87115 5.76542 57.78465 3.91203 7.94142 59.25899 3.69320 6.58200 57.78465 6.37924 10.57362 69.83974 5.76106 11.04699 69.48746 6.99832 10.43204 69.12189 7.51555 10.27552 68.40620 6.39743 11.04699 68.22884 7.93707 10.11112 67.71126 6.74219 11.04698 66.98638 8.27304 9.94482 67.05045 6.77652 11.04697 64.79448 6.84833 11.04698 65.82776 8.27304 10.02494 65.82712 8.27304 9.95522 64.60337 7.68907 10.47650 65.22638 7.51440 10.58686 64.38346 7.28972 10.70574 63.34866 7.03156 10.81415 62.21390 6.56192 10.93564 60.26743 6.00031 10.99697 58.03868 4.16911 10.99697 56.91779 8.97320 -7.99930 35.69485 8.57261 9.49998 35.85024 7.47453 10.59806 35.85024 6.75099 10.89776 35.85024 8.97405 7.99896 35.64078 5.97453 10.99998 35.85024 -7.73288 7.83902 65.04834 -8.63502 -9.30826 58.01877 -7.93006 -10.24095 57.42631 -6.99314 -10.79692 56.75710 -5.98520 -10.99559 55.99763 -8.46533 -9.30571 58.17711 -7.75845 -10.20360 57.57774 -6.83918 -10.70810 56.91447 -8.28166 -9.25626 58.24971 -7.57564 -10.08604 57.65858 -6.71150 -10.54603 56.99843 -5.78438 -10.77336 56.32600 -8.08450 -9.16383 58.24420 -3.52289 -10.85658 55.20966 -5.86925 -10.93604 56.18721 -8.94307 -8.00303 58.26979 -8.78603 -8.00303 58.44856 -8.56413 -8.00303 58.53451 -8.32765 -8.00303 58.50815 -2.07017 -4.00303 54.98126 -4.06603 -4.00303 55.56384 -4.07348 -5.46536 55.56680 -4.41319 -5.67444 55.70889 -4.88858 -6.00303 55.93077 -4.88858 -9.00303 55.93077 -4.61835 -10.50303 55.80126 -5.73882 -10.50303 56.40048 -5.91618 -4.00303 56.51129 -6.61429 -10.30840 57.00250 -7.36932 -9.82743 57.61906 -7.90885 -9.03460 58.14079 -8.13012 -8.00303 58.37546 -4.42719 -11.00303 55.17110 -5.49969 7.94142 60.52766 -5.49969 8.49697 62.86916 -7.07509 9.96326 69.35165 -8.40868 9.57200 67.21003 -8.38164 9.77928 67.14390 -8.77847 8.65637 65.41832 -8.75324 9.00930 65.88834 -8.80716 9.23126 65.82973 -8.85598 8.20532 65.01575 -8.80875 7.58718 64.67843 -8.32765 -0.00303 58.50815 -8.56413 -0.00303 58.53451 -8.78603 -0.00303 58.44856 -8.94307 -0.00303 58.26979 -8.67508 -0.00303 58.49153 -8.68027 3.11935 59.20855 -8.56413 7.03771 64.05474 -8.68027 5.63813 61.18338 -8.78601 7.12115 64.03425 -8.82568 9.29202 65.44601 -8.75123 9.44767 65.75460 -8.62564 9.63634 66.23487 -8.38246 7.53031 64.74487 -8.47667 8.65770 65.68396 -7.56946 8.64121 66.07729 -8.55801 8.55985 65.49423 -7.94615 8.50652 65.71537 -8.69641 8.16196 65.11563 -8.32985 8.34236 65.38905 -6.92121 8.54095 65.99626 -7.21787 9.43370 68.56859 -8.38561 8.73646 65.91035 -8.02650 9.09237 67.15675 -7.22853 8.73646 66.44991 -4.49019 11.49697 68.53880 -5.00295 11.49697 67.43310 -5.24790 11.49697 66.23879 -5.21216 11.49697 65.02297 -5.02849 11.49697 63.95660 -4.79562 11.49697 63.01096 -4.49486 11.49697 62.19946 -4.11076 11.49697 61.54702 -5.87529 11.27728 62.68823 -6.34615 11.17867 63.68780 -5.34900 11.34554 61.80436 -6.50196 11.01932 62.49067 -4.11820 11.39697 60.46766 -4.73752 11.26217 59.66812 -8.95116 8.88449 64.98747 -8.99969 8.08742 64.55762 -8.99969 7.42452 63.58657 -8.99969 8.32860 64.17715 -8.99969 7.14456 62.79934 -8.99969 6.69775 61.89881 -8.99969 6.00432 60.89467 -8.99969 4.97055 59.84633 -8.99969 4.28585 59.33441 -8.99969 3.46150 58.85666 -8.99969 2.47985 58.44739 -8.99969 1.33074 58.15437 -8.99969 -0.00303 58.03868 -8.99969 -8.00303 58.03868 -6.36582 8.49697 65.28314 -4.99969 8.49697 59.78465 -8.13012 6.30681 61.90997 -8.13014 7.19214 64.01679 -6.93326 7.94142 62.65234 -6.58044 7.94142 61.96633 -6.11115 7.94142 61.25299 -4.99969 7.74294 59.78465 -4.99969 6.96932 58.90087 -8.13012 5.29650 60.60670 -8.13012 5.74314 61.10729 -6.84235 6.16047 59.76889 -8.13012 4.75429 60.10451 -8.13012 2.37195 58.76642 -8.13012 3.31086 59.15787 -8.13012 4.09936 59.61484 -7.66390 4.10292 59.04662 -8.13012 1.85875 58.63554 -7.84539 -0.00303 58.07458 -8.13012 -0.00303 58.37546 -8.13012 1.27291 58.48615 -6.77590 11.08882 64.79447 -8.27241 10.00166 66.46892 -8.27242 10.02460 65.87690 -6.84770 11.04698 65.82941 -8.27241 9.94482 67.05044 -6.74099 11.04698 66.98962 -7.64224 10.22999 68.20881 -7.22061 10.36962 68.82871 -6.39505 11.04699 68.23342 -6.71649 10.50161 69.46391 -5.75694 11.04699 69.49290 -8.99969 7.99697 62.95621 -8.92784 8.64962 63.24892 -8.74119 9.21523 63.62119 -8.49871 9.65676 64.07870 -8.27242 9.95522 64.60336 -7.68264 10.48045 65.19770 -8.04445 10.19218 65.20199 -7.28360 10.70835 63.32394 -6.95376 10.83841 61.88823 -6.49814 10.94335 60.01643 -5.99969 10.99697 58.03868 -7.09799 -10.76947 56.60332 -8.02191 -10.21902 57.22966 -8.72210 -9.24094 57.79337 -8.87864 8.92703 50.79252 -8.45252 9.76334 50.79252 -7.78882 10.42703 50.79252 -6.95252 10.85315 50.79252 -9.02547 7.99998 24.47807 -5.98549 10.99998 23.80068 -1.04969 -10.85241 54.68365 4.42840 -11.00303 55.17134 2.76805 -11.00303 54.62267 0.00032 -11.00303 54.33267 -2.76710 -11.00303 54.62259 -6.66595 -10.93085 11.30388 -7.24205 -10.74227 10.48113 -7.83129 -10.39779 9.62842 -8.54841 -9.69898 9.75196 -8.93990 -8.71143 9.75318 -6.02547 -11.00002 12.21858 8.87231 -8.77648 35.85024 -6.06415 -10.98435 42.34554 7.47453 -10.59810 35.85024 5.97453 -11.00002 35.85024 -8.92325 8.77644 9.75318 -8.62354 9.49998 9.75318 -8.14679 10.12130 9.75318 -7.52547 10.59806 9.75318 -7.40258 10.61573 24.42709 -6.80193 10.89776 9.75318 -6.85997 10.85877 24.18378 -9.02547 -8.00002 50.79252 -9.02547 7.99998 9.75318 -9.02547 -8.00002 9.75318 -6.02547 10.99998 9.75318 -8.82456 -8.97048 8.23386 -8.35722 -9.83346 8.87693 3.09373 -11.00002 25.24129 3.84738 -11.00002 25.66956 6.02902 7.60540 24.02987 7.59724 9.39440 22.93180 3.09373 4.51538 25.24086 4.80132 6.77597 24.02629 5.53123 7.92272 23.51520 6.36547 8.94930 22.93106 7.25502 9.81190 22.30820 8.13969 10.48946 21.68875 -7.81194 10.19832 8.06339 -8.70497 9.17054 8.32644 -7.84819 9.52832 6.46801 -8.06851 7.48123 4.76029 -8.47200 8.99747 6.76388 -8.91057 8.17181 7.25133 -8.48715 6.71069 5.17098 -8.78339 5.53871 5.93756 -8.82707 6.93589 6.13376 -8.91444 4.52108 6.55495 -9.00809 3.44139 7.10285 -2.52488 10.79660 5.44341 -6.37604 10.87409 8.50607 -3.42532 10.53381 5.09353 -6.61970 10.62987 7.63714 -5.58596 9.52464 4.65381 -4.28238 10.18335 4.86431 -6.39769 9.05089 4.57325 -7.05581 9.89042 6.26470 -7.27770 8.32427 4.56418 14.71637 -1.00002 18.30448 9.11121 9.61540 22.22925 8.30002 8.99410 22.79724 7.48444 8.20316 23.36832 6.71983 7.26218 23.90371 6.05099 6.21134 24.37204 4.46876 -10.99931 25.47945 3.97006 4.32180 25.65569 13.48764 -11.00002 19.16484 -9.00962 -7.94523 7.95428 -9.02291 7.83078 8.60572 -9.13174 7.34492 7.32504 -9.01689 1.01905 7.80848 6.11848 10.99998 28.10642 13.48764 10.99998 19.16484 9.61673 10.99998 21.56325 10.27987 10.99998 21.33061 -1.38547 10.99361 6.36442 8.95372 10.99149 21.12506 7.67080 -10.77166 33.60986 8.53410 -10.12134 34.05927 9.11094 -9.14807 34.35955 8.38867 -9.86395 35.85762 8.97843 -10.89780 31.57137 15.04788 -10.47307 28.44679 9.39344 -10.59810 32.16406 14.55192 -10.22275 29.17261 9.74981 -10.12134 32.67301 13.96278 -9.72338 30.12993 10.02327 -9.50002 33.06355 10.19517 -8.77648 33.30905 6.44810 -10.99915 33.53150 6.95150 -11.00002 32.56861 7.68086 -11.00002 31.65925 8.53307 -11.00002 30.93533 6.07891 -11.00002 34.73596 7.24306 -10.99855 29.51986 15.24554 10.78862 17.93394 16.93588 10.16265 16.75036 18.49370 9.14615 15.65955 19.85915 7.77816 14.70346 20.97974 6.11126 13.91881 21.81242 4.20950 13.33576 22.32518 2.14598 12.97673 22.49832 -0.00002 12.85549 22.32518 -2.14601 12.97673 21.81242 -4.20954 13.33576 20.97974 -6.11129 13.91881 19.85915 -7.77819 14.70346 18.49370 -9.14618 15.65955 16.93588 -10.16269 16.75036 15.24554 -10.78866 17.93394 17.24874 10.99998 22.51061 18.17611 10.65630 21.81541 19.22166 10.40002 21.06122 20.96988 9.32311 19.90791 22.40247 8.07652 18.90565 23.59134 6.43999 18.07167 24.49215 4.54886 17.44142 25.06778 2.47712 17.03791 25.29603 0.30725 16.87835 25.16816 -1.87593 16.96807 24.68785 -3.98494 17.30406 23.87474 -5.93575 17.87369 22.76056 -7.65164 18.65359 21.39038 -9.06324 19.61331 19.81750 -10.11579 20.71426 16.31776 -10.99078 23.16249 18.10548 -10.76687 21.91349 17.38796 -11.00002 24.73507 16.96749 -10.97764 25.55215 16.34939 -10.84743 26.69325 15.72066 -10.57274 27.87064 15.38818 -10.15375 29.25569 9.11094 9.14803 34.35955 8.53410 10.12130 34.05927 7.67080 10.77162 33.60986 16.43848 10.92617 26.28057 8.97843 10.89776 31.57137 15.95405 10.80158 27.06688 15.43530 10.63526 27.85690 9.39344 10.59806 32.16406 14.92284 10.39920 28.68267 14.42861 10.14589 29.35819 9.74981 10.12130 32.67301 13.86560 9.76151 30.19668 10.02327 9.49998 33.06355 13.36479 9.18490 30.88310 10.19517 8.77644 33.30905 9.29688 -7.99607 34.43215 9.27742 7.99604 34.46957 18.48210 10.97335 27.63127 20.32549 10.89922 26.34051 16.66504 10.58775 28.90359 22.11796 10.36841 25.08541 14.91703 9.74032 30.12738 23.78436 9.40314 23.91859 12.34762 8.52781 31.90911 25.25485 8.04386 22.88894 10.02733 7.99865 33.54759 11.78197 7.99998 32.32275 26.46777 6.34756 22.03964 19.10870 -1.00002 27.19253 27.37233 4.38535 21.40626 27.93064 2.23951 21.01533 28.11937 -0.00001 20.88318 27.93064 -2.23954 21.01533 27.37233 -4.38538 21.40626 10.17767 -7.99948 33.44432 26.46778 -6.34759 22.03964 11.78197 -8.00002 32.32275 12.79827 -8.62660 31.61546 25.25485 -8.04389 22.88894 13.84475 -9.17023 30.85625 23.78437 -9.40318 23.91858 14.95047 -9.75869 30.10414 22.11796 -10.36845 25.08541 20.32550 -10.89926 26.34051 18.48211 -10.97339 27.63127 16.66505 -10.58779 28.90358 17.38796 10.99998 24.73507 7.68086 10.99998 31.65925 6.88393 10.99870 32.69260 6.40583 10.99998 33.61652 6.07891 10.99998 34.73596 8.53307 10.99998 30.93533 14.42391 10.99998 24.49159 16.29335 10.99998 23.17457 -4.52128 -9.48780 55.75693 -3.74877 -5.29607 55.44330 -4.04355 -10.02226 55.55492 -3.44120 -10.49866 55.33802 -3.27828 -5.11393 55.28461 -2.56465 -5.00303 55.08788 -0.86205 -5.00303 54.81850 0.00031 -4.00303 54.78465 0.86268 -5.00303 54.81850 2.07080 -4.00303 54.98126 2.56528 -5.00303 55.08788 3.24817 -5.10488 55.27505 3.85739 -5.34857 55.48305 4.06665 -4.00303 55.56384 4.39886 -5.66467 55.70235 -2.03629 -5.00303 55.45412 2.03692 -5.00303 55.45412 -1.59865 -5.00303 55.92377 1.59927 -5.00303 55.92377 -1.27058 -5.00303 56.47660 1.27121 -5.00303 56.47660 -1.06794 -5.00303 57.08608 1.06857 -5.00303 57.08608 -0.99969 -5.00303 57.72238 1.00031 -5.00303 57.72238 -0.99969 -5.00303 64.05260 1.00031 -5.00303 64.05260 1.23270 -5.00303 64.87756 -0.22221 -5.00303 64.80972 0.22284 -5.00303 64.80972 -0.62317 -5.00303 65.00281 0.62381 -5.00303 65.00281 -1.36571 -5.07242 64.78465 -0.90065 -5.00303 65.35076 0.90128 -5.00303 65.35076 -1.16938 -5.00303 65.70529 1.17001 -5.00303 65.70531 -0.99969 -5.00303 65.78465 1.00031 -5.00303 65.78465 1.08593 -5.00303 66.22726 -1.07869 -5.00303 66.24315 0.86804 -5.00303 66.28169 -0.86541 -5.00303 66.28516 0.50304 -5.00303 66.64909 0.76600 -5.00303 66.67245 -0.75402 -5.00303 66.68211 -0.49850 -5.00303 66.65135 0.00254 -5.00303 66.78464 0.28178 -5.00303 66.92274 -0.26495 -5.00303 66.92662 2.00031 -6.00303 57.72238 2.00069 -6.00303 64.78463 2.00031 -9.00303 57.72238 2.00032 -9.00303 64.78465 0.00032 -10.00303 55.78465 -1.66580 -10.00303 55.83743 0.00032 -10.00303 56.18634 -1.38036 -10.00303 56.25980 0.00032 -10.00303 56.52710 -1.17070 -10.00303 56.72397 0.00032 -10.00303 56.79470 1.04338 -10.00303 57.21588 -1.04276 -10.00303 57.21584 1.00031 -10.00303 57.72238 -0.99969 -10.00303 57.72238 1.00032 -10.00303 64.78465 -0.99968 -10.00303 64.78465 -1.99969 -9.00303 64.78465 -1.99969 -6.00303 64.74483 -1.99969 -6.00303 57.72238 -1.99969 -9.00303 57.72238 4.41109 -6.00303 55.76503 4.41097 -9.00303 55.76500 3.90525 -6.00303 55.72464 3.90519 -9.00303 55.72466 3.40663 -6.00303 55.81253 3.40656 -9.00303 55.81256 2.94624 -6.00303 56.02271 2.94618 -9.00303 56.02274 2.55335 -6.00303 56.34171 2.55329 -9.00303 56.34176 2.25301 -6.00303 56.74930 2.25292 -9.00303 56.74944 2.06435 -6.00303 57.22037 2.06428 -9.00303 57.22060 -4.41046 -9.00303 55.76503 -4.41046 -6.00303 55.76503 -3.90463 -9.00303 55.72464 -3.90463 -6.00303 55.72464 -3.40600 -9.00303 55.81253 -3.40600 -6.00303 55.81253 -2.94561 -9.00303 56.02271 -2.94561 -6.00303 56.02271 -2.55272 -9.00303 56.34171 -2.55272 -6.00303 56.34171 -2.25238 -9.00303 56.74930 -2.25238 -6.00303 56.74930 -2.06372 -9.00303 57.22037 -2.06372 -6.00303 57.22037 -2.71138 -5.29592 55.82565 -1.97344 -5.29592 56.64922 -1.92357 -5.62035 57.72238 -1.38239 -5.07915 57.72238 -1.69827 -5.28750 64.78465 -1.70681 -5.29593 57.72238 -1.92125 -5.61481 64.78465 -1.99475 -6.00303 64.92503 1.43195 -5.11040 65.01970 1.38300 -5.07915 57.72238 1.69889 -5.28749 64.78465 1.70742 -5.29592 57.72238 1.92189 -5.61481 64.78465 1.92419 -5.62034 57.72238 3.74839 -5.30497 55.44583 2.71693 -5.29592 55.82231 1.97546 -5.29592 56.64659 1.86633 -9.50305 64.78465 1.92419 -9.38571 57.72238 1.70742 -9.71014 57.72238 1.50029 -9.86907 64.78465 1.38300 -9.92691 57.72238 -1.49969 -9.86905 64.78465 -1.38237 -9.92691 57.72238 -1.70679 -9.71014 57.72238 -1.86571 -9.50303 64.78465 -1.92357 -9.38571 57.72238 -4.20886 -9.24626 55.70316 -3.45966 -9.51198 55.65247 -2.92259 -9.70494 55.70795 -2.03552 -9.71014 56.53943 -1.97107 -9.98200 55.79823 -2.25367 -9.92569 55.77649 -2.52205 -9.84500 55.75502 0.00032 -10.66970 54.80614 -2.47480 -10.61703 55.07125 0.00032 -10.97928 54.48560 1.05032 -10.85241 54.68365 0.00031 -5.00303 65.78465 -1.73699 -5.33823 64.96863 -1.92773 -5.64578 64.93640 1.73761 -5.33822 64.96864 1.92836 -5.64578 64.93640 1.27380 -5.02203 65.28942 -1.81236 -5.27567 66.19547 -2.10209 -5.94570 66.32501 -1.15964 -5.27567 67.23690 -1.32993 -5.94570 67.50003 0.00031 -5.94570 67.95538 0.00031 -5.27567 67.64330 1.33056 -5.94570 67.50003 1.16027 -5.27567 67.23691 2.10272 -5.94570 66.32501 1.81299 -5.27567 66.19547 0.00032 -10.04902 55.45229 0.00032 -10.18686 55.17287 0.00032 -10.40319 54.94949 -1.78668 -10.32127 55.11591 -1.73172 -10.17210 55.44402 -0.99968 -10.00303 66.28465 1.00032 -10.00303 66.28465 2.10272 -8.94570 66.32501 -2.10209 -8.94570 66.32501 -1.32993 -8.94570 67.50003 0.00032 -8.94570 67.95538 1.33056 -8.94570 67.50003 1.73346 -10.17210 55.44402 1.78841 -10.32127 55.11591 2.47653 -10.61703 55.07125 2.52378 -9.84500 55.75502 2.25541 -9.92569 55.77649 1.97281 -9.98200 55.79823 2.03725 -9.71014 56.53943 2.92432 -9.70494 55.70795 3.46140 -9.51198 55.65247 4.21060 -9.24626 55.70316 1.17244 -10.00303 56.72397 1.38210 -10.00303 56.25980 1.66754 -10.00303 55.83743 3.44294 -10.49866 55.33802 4.04529 -10.02226 55.55492 4.52302 -9.48780 55.75693 + + + + + + + + + + -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.00176 -0.99998 0.00631 -0.05355 -0.99857 0.00043 0.00000 -0.99999 0.00542 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 -0.00095 1.00000 -0.00028 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.04752 0.99190 -0.11780 -0.04460 0.99084 -0.12747 -0.02095 0.99228 -0.12226 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.99978 -0.01466 0.01477 -0.99976 -0.02028 0.00805 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 0.00000 -0.10705 -0.93718 0.33202 0.09366 0.95264 0.28931 0.07028 0.94785 0.31086 0.03296 0.95258 0.30251 0.17105 0.96162 0.21453 0.17056 0.96125 0.21658 0.13733 0.94752 0.28870 0.19414 0.95999 0.20179 0.00016 0.94744 0.31993 -0.03234 0.95249 0.30284 -0.07021 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.13704 0.94751 0.28886 -0.19432 0.95992 0.20196 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 0.29459 -0.64015 0.70952 0.46219 0.52024 0.71814 0.44473 0.03813 0.89485 0.53245 0.40400 0.74383 0.39039 -0.60766 0.69162 0.43016 -0.54482 0.71982 0.60973 0.41632 0.67446 0.45012 -0.62955 0.63329 -0.34004 -0.62630 0.70151 -0.23218 -0.60875 0.75863 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 0.00000 -0.58193 0.81324 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 0.02349 0.38357 0.92321 0.18035 0.44574 0.87681 0.25235 -0.50582 0.82490 0.15528 -0.63718 0.75491 0.28039 0.27890 0.91848 0.30399 0.34310 0.88874 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41725 -0.54080 0.73037 -0.41201 -0.60635 0.68014 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 0.13338 -0.93583 0.32624 0.14454 -0.93969 0.30997 0.14440 -0.93971 0.30999 0.14454 -0.93969 0.30998 -0.14310 -0.93869 0.31366 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 0.04525 -0.90484 0.42333 -0.00555 -0.95073 0.30998 0.07081 -0.93620 0.34427 0.10399 -0.94352 0.31456 -0.39689 0.83488 0.38139 -0.32068 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.00028 0.83866 0.54466 0.01264 0.86767 0.49698 0.11187 0.86176 0.49483 0.10816 0.84369 0.52582 0.17651 0.83818 0.51604 0.25027 0.81275 0.52612 0.23285 0.86496 0.44455 0.33532 0.84040 0.42578 0.32528 0.86091 0.39119 0.18153 0.97480 -0.12965 0.17001 0.97728 -0.12654 0.30431 0.95247 -0.01398 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.69992 0.00000 0.71422 -0.71753 0.00258 0.69653 0.85361 0.22299 0.47076 0.78945 0.37028 0.48956 0.96140 0.25494 0.10351 -0.71327 -0.68531 0.14694 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.99709 0.07281 -0.02245 0.94096 0.33621 -0.03941 0.91811 -0.28358 0.27686 0.71137 -0.33210 0.61940 -0.43505 -0.65824 0.61437 0.17552 -0.92639 0.33316 0.20020 -0.56806 0.79827 -0.36475 -0.92779 0.07852 0.99241 -0.00582 0.12283 -0.36661 -0.92729 0.07565 0.69862 -0.45435 0.55272 0.48679 -0.51345 0.70669 0.93601 -0.05072 0.34830 0.94067 -0.09921 0.32450 0.99852 -0.05405 0.00588 0.96437 -0.18410 0.19000 0.49646 -0.68115 0.53810 0.74849 -0.58760 0.30738 0.33786 -0.80615 0.48576 0.24914 -0.62470 0.74005 -0.38048 -0.92472 -0.01172 -0.40310 -0.90211 0.15396 -0.39572 -0.90000 0.18275 -0.14946 -0.85152 0.50256 0.04364 -0.78466 0.61839 0.33000 -0.71943 0.61116 0.23960 -0.72465 0.64612 0.18329 -0.69229 0.69795 0.12591 -0.54798 0.82696 -0.22862 -0.88332 0.40924 -0.69814 -0.69570 0.16913 0.09772 -0.92104 0.37701 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.45559 -0.25841 0.85186 -0.29317 -0.70441 0.64642 -0.13850 -0.95397 0.26602 0.95828 -0.24461 0.14786 0.81543 -0.57879 -0.00930 0.94100 -0.24772 0.23054 0.44467 -0.88743 0.12142 0.33852 -0.93969 0.04887 0.40618 -0.89006 0.20691 0.61604 -0.70539 0.35059 0.71448 -0.30916 0.62764 -0.06005 -0.94361 0.32556 -0.19340 -0.85881 0.47439 -0.01764 -0.79254 0.60956 0.00853 -0.93684 0.34965 0.65752 -0.32585 0.67933 0.50716 -0.68460 0.52355 0.34776 -0.26959 0.89799 0.21992 -0.66340 0.71522 0.03122 -0.83832 0.54428 -0.31182 -0.70556 0.63636 -0.07666 -0.52074 0.85027 0.04715 -0.24580 0.96817 -0.10883 -0.19107 0.97553 -0.21087 -0.46595 0.85932 -0.28739 -0.53790 0.79251 -0.42242 -0.48538 0.76549 -0.36795 -0.46363 0.80602 -0.53494 -0.16968 0.82768 -0.50295 -0.10159 0.85832 -0.57290 -0.14179 0.80727 -0.57632 -0.14637 0.80401 -0.55630 -0.06916 0.82810 -0.52021 -0.25876 0.81390 0.97128 0.00000 0.23795 0.97128 0.00000 0.23795 0.75129 0.00000 0.65997 0.75129 0.00000 0.65997 0.36119 0.00000 0.93249 0.36113 -0.00000 0.93251 -0.11078 0.00000 0.99385 -0.11087 -0.00000 0.99383 -0.55763 0.00000 0.83009 -0.55763 0.00000 0.83009 -0.72632 0.00000 0.68736 -0.72738 -0.00008 0.68624 -0.69507 0.00038 0.71895 -0.61483 -0.00378 0.78865 -0.65575 -0.02015 0.75471 -0.53890 0.00034 0.84237 -0.48965 -0.00150 0.87192 -0.47159 0.00881 0.88178 -0.48356 -0.00000 0.87531 -0.35592 -0.92787 0.11130 -0.35599 -0.92772 0.11224 -0.34305 -0.92790 0.14600 -0.34306 -0.92762 0.14774 -0.32485 -0.92795 0.18269 -0.32465 -0.92748 0.18544 -0.29985 -0.92803 0.22101 -0.29922 -0.92728 0.22500 -0.26638 -0.92815 0.25995 -0.26496 -0.92700 0.26547 -0.22267 -0.92832 0.29771 -0.21990 -0.92662 0.30498 -0.16727 -0.92857 0.33134 -0.16235 -0.92614 0.34045 0.06866 -0.98340 0.16795 0.05806 -0.98803 0.14291 0.27545 0.96128 -0.00810 0.26631 0.96371 -0.01852 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24571 0.96262 0.11395 0.24710 0.96090 0.12493 0.21475 0.96198 0.16875 0.21458 0.96108 0.17403 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05537 0.18875 0.98134 -0.03660 0.20009 0.97977 0.00241 0.22383 0.97307 -0.05512 0.27743 0.96072 0.00660 0.22710 0.97309 -0.03911 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 0.04752 0.99190 -0.11780 0.85908 -0.41995 0.29260 0.84589 -0.47572 0.24118 0.71256 -0.60512 0.35508 -0.15441 -0.88248 0.44428 -0.33313 -0.82828 0.45053 -0.26799 -0.59574 0.75715 -0.27654 -0.59294 0.75627 0.87478 -0.29895 0.38130 0.92715 -0.25465 0.27484 0.88204 -0.28220 0.37731 0.83044 -0.27944 0.48196 0.81928 -0.22073 0.52920 -0.21381 -0.37604 0.90160 -0.10840 -0.20592 0.97255 -0.55344 -0.12230 0.82386 -0.71334 -0.06060 0.69819 -0.40482 -0.22605 0.88602 0.86783 -0.13547 0.47804 0.84841 -0.13085 0.51291 0.97107 -0.02065 0.23790 0.75105 0.02515 0.65977 0.35731 0.14609 0.92249 0.93755 -0.33787 0.08276 0.36885 -0.86583 0.33807 0.40262 -0.84457 0.35299 0.30818 -0.87862 0.36477 0.79236 -0.48636 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14655 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23107 0.52767 -0.56848 0.63119 0.51463 -0.58326 0.62846 0.69906 0.28926 0.65394 0.69603 0.25858 0.66983 0.73326 0.39301 0.55486 0.51543 -0.63934 0.57059 0.71478 -0.44325 0.54095 0.50370 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04157 0.78420 0.61951 -0.03530 0.75315 0.64246 -0.14144 0.82860 0.54907 -0.10926 0.30521 -0.65708 0.68927 0.27452 -0.77218 0.57305 0.19557 -0.87047 0.45170 0.25684 -0.87163 0.41749 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14388 -0.94000 0.30935 0.14372 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.04527 0.99623 -0.07396 0.21031 0.97181 -0.10652 0.06838 0.99149 -0.11075 0.04277 0.99157 -0.12228 0.04210 0.99151 -0.12305 0.54248 0.83922 -0.03771 0.56738 0.81415 -0.12343 0.43933 0.89793 0.02653 0.44975 0.89314 0.00495 0.41496 0.90361 -0.10632 0.37331 0.92770 0.00370 0.32582 0.93758 -0.12160 0.13224 0.99120 -0.00605 0.99766 0.05944 -0.03376 0.99761 0.05955 -0.03494 0.99974 0.02256 0.00118 1.00000 0.00090 -0.00097 1.00000 0.00074 -0.00099 1.00000 0.00095 -0.00164 -0.00630 -0.99996 0.00607 -0.00914 -0.99996 0.00102 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00745 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 -0.64851 -0.66869 0.36372 -0.78399 -0.56943 0.24719 -0.72894 -0.60836 0.31393 -0.67806 -0.62467 0.38732 -0.62961 -0.61117 0.47965 -0.63130 -0.61327 0.47472 -0.71791 -0.43046 0.54709 -0.63745 -0.38469 0.66759 -0.68092 -0.28192 0.67592 -0.67104 -0.18329 0.71841 -0.57400 -0.07080 0.81579 -0.71726 -0.15742 0.67879 -0.69233 -0.14685 0.70648 -0.55015 -0.62730 0.55121 -0.49917 -0.61019 0.61522 -0.53420 -0.51395 0.67118 -0.66290 -0.37590 0.64750 -0.45505 -0.62819 0.63112 -0.43573 -0.62856 0.64424 -0.31840 -0.67290 0.66770 -0.29656 -0.66599 0.68448 0.40524 0.83720 0.36725 0.40441 0.85374 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24717 0.49012 0.83244 0.25851 0.53337 0.82040 0.20605 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09072 0.58199 0.81145 0.05331 0.58209 0.81139 0.05314 0.58234 0.81175 0.04408 0.63891 0.76804 -0.04376 0.87243 0.48873 0.00135 0.66299 0.74861 -0.00494 0.53559 0.84448 -0.00042 0.46878 0.88331 -0.00031 0.39186 0.92002 -0.00125 0.24879 0.96856 0.00042 0.10852 0.99409 0.00001 -0.56299 0.82624 -0.01940 -0.41875 0.90371 -0.08924 -0.90044 -0.25936 0.34920 -0.93842 -0.11798 0.32473 -0.34308 0.92963 -0.13449 -0.12092 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29116 0.13334 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.24074 -0.72348 0.64701 -0.33159 -0.71777 0.61225 -0.04401 -0.78448 0.61859 0.36127 -0.87020 0.33502 -0.10318 -0.93694 0.33390 -0.30659 -0.65544 0.69022 -0.24901 -0.62075 0.74341 -0.54604 -0.69844 0.46262 -0.46583 -0.68911 0.55510 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71481 -0.55303 -0.49987 0.66655 -0.08363 -0.97549 0.20352 -0.95619 0.27849 0.09024 -0.00001 1.00000 0.00003 0.00000 0.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.77550 -0.62094 0.11414 -0.92389 -0.26237 0.27855 -0.93651 -0.26515 0.22944 -0.45140 -0.88525 0.11212 -0.69107 -0.67926 0.24705 -0.71876 -0.29107 0.63139 -0.43222 -0.89152 0.13554 -0.21391 -0.97644 -0.02847 -0.48193 -0.69947 0.52771 -0.64730 -0.30492 0.69858 -0.20138 -0.87331 0.44359 -0.37961 -0.70148 0.60317 0.11954 -0.91012 0.39673 -0.06955 -0.83809 0.54107 0.00035 -0.95410 0.29950 -0.34751 -0.27251 0.89720 -0.13707 -0.62234 0.77065 -0.28897 -0.27361 0.91741 0.13169 -0.69253 0.70927 0.00840 -0.57544 0.81780 0.26070 -0.59799 0.75792 0.36092 -0.63712 0.68104 0.29526 -0.70457 0.64529 0.10861 -0.19695 0.97438 0.11924 -0.19633 0.97326 0.22611 -0.43020 0.87395 0.48669 -0.26087 0.83372 0.49192 -0.26576 0.82909 0.52427 -0.22855 0.82031 0.53316 -0.23207 0.81356 0.49186 -0.30734 0.81463 0.57602 -0.13819 0.80567 0.54643 -0.07521 0.83412 0.55630 -0.06906 0.82811 0.29316 -0.70443 0.64641 0.41234 -0.30593 0.85813 0.11803 -0.96573 0.23118 -0.97128 0.00000 0.23795 -0.97128 0.00000 0.23795 -0.75129 0.00000 0.65997 -0.75129 0.00000 0.65997 -0.36118 0.00000 0.93249 -0.36118 0.00000 0.93249 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.41672 -0.06071 0.90701 0.44156 -0.03337 0.89661 0.49187 0.00000 0.87067 0.48578 -0.00165 0.87408 0.47157 0.00882 0.88178 0.56683 0.00142 0.82383 0.61482 -0.00663 0.78864 0.63155 -0.00250 0.77533 0.69992 0.00000 0.71422 0.71543 0.00227 0.69868 0.69543 0.00038 0.71859 0.72632 -0.00007 0.68736 0.72758 -0.00000 0.68603 1.00000 0.00000 -0.00000 0.96907 -0.14560 -0.19926 1.00000 -0.00000 0.00000 0.82964 0.00000 0.55829 0.81840 -0.55913 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34240 -0.93149 0.12285 0.41737 -0.90314 0.10069 -0.01779 -0.99870 0.04773 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.21448 0.96105 0.17429 -0.21468 0.96201 0.16869 -0.24706 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05397 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06967 0.99117 -0.11285 -0.06977 0.99156 -0.10925 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50577 -0.84008 0.26127 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08801 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67439 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.70424 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95385 0.19680 0.22679 -0.79602 0.59318 0.12039 0.33004 -0.80724 0.48932 -0.20020 -0.56806 0.79826 -0.19713 -0.77268 0.60342 -0.33899 -0.76788 0.54355 -0.56010 -0.42940 0.70845 -0.93154 -0.30944 0.19098 -0.92038 -0.32295 0.22046 0.55619 -0.07182 0.82795 0.11078 -0.00001 0.99385 -0.35677 0.15627 0.92103 -0.35311 -0.20995 0.91172 -0.74452 -0.13397 0.65402 -0.97123 0.01021 0.23794 -0.94190 -0.02903 0.33465 -0.87579 -0.11927 0.46772 0.43301 -0.20106 0.87868 0.50696 -0.21300 0.83524 -0.81932 -0.22063 0.52919 0.21392 -0.37591 0.90163 -0.83672 -0.33789 0.43096 -0.94486 -0.16420 0.28332 -0.90294 -0.25735 0.34420 -0.82338 -0.40407 0.39846 0.40408 -0.56439 0.71985 0.63619 -0.52427 0.56604 0.42922 -0.54084 0.72337 0.24642 -0.48596 0.83852 0.22831 -0.72646 0.64817 -0.35307 -0.83531 0.42143 0.33802 -0.85130 0.40128 0.52007 -0.78743 0.33089 0.22940 -0.79654 0.55937 -0.81758 -0.52269 0.24158 -0.97082 -0.19733 0.13627 -0.93633 -0.31452 0.15605 -0.89789 -0.41477 0.14750 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02856 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01958 -0.75159 0.65915 0.02529 -0.75611 0.64757 -0.09461 -0.76607 0.62897 -0.13240 -0.76278 0.64443 -0.05370 -0.72711 0.68600 0.02658 -0.73804 0.67155 0.06564 -0.18054 -0.90416 0.38717 -0.19130 -0.89466 0.40372 -0.24234 -0.81604 0.52474 -0.27442 -0.77224 0.57302 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.14037 -0.94027 0.31014 -0.14455 -0.93969 0.30997 -0.14454 -0.93969 0.30997 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.42741 0.90176 -0.06440 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.17579 0.98435 0.01240 -0.18182 0.98314 -0.01917 -0.04278 0.99157 -0.12227 -0.06792 0.99150 -0.11096 -0.06980 0.99114 -0.11304 -0.07001 0.99177 -0.10718 -0.99856 0.04531 0.02872 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00012 0.00067 -1.00000 -0.00130 0.00064 -1.00000 -0.00095 0.00066 0.00674 -0.99997 0.00479 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42688 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.53895 -0.63976 0.54794 0.56237 -0.62219 0.54463 0.54102 -0.54657 0.63919 0.60574 -0.46780 0.64362 0.66422 -0.46943 0.58177 0.68227 -0.49680 0.53638 0.68248 -0.54538 0.48661 0.65312 -0.61971 0.43519 0.60598 -0.47358 0.63915 0.70018 -0.42752 0.57181 0.31773 -0.23430 0.91878 0.65808 -0.28974 0.69497 0.72685 -0.34438 0.59421 0.66513 -0.26599 0.69775 0.74155 -0.38353 0.55046 0.69487 -0.20510 0.68927 0.70755 -0.17462 0.68474 0.69835 -0.06705 0.71261 0.72397 -0.08033 0.68514 0.70425 -0.06136 0.70730 -0.55875 0.82932 -0.00524 -0.62317 0.78191 -0.01634 -0.58167 0.81243 0.04018 -0.58191 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03149 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51068 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40436 0.85353 0.32861 -0.99403 0.10913 0.00067 -0.95025 0.31148 0.00318 -0.87588 0.48253 -0.00146 -0.78707 0.61676 -0.01137 -0.72035 0.69361 -0.00024 -0.54105 0.84089 -0.01294 -0.62317 0.78207 -0.00563 -0.38610 0.92244 -0.00514 -0.21949 0.97561 0.00127 -0.92962 -0.36852 0.00015 -0.81240 -0.58309 0.00262 -0.69791 -0.71618 -0.00011 -0.51123 -0.85944 0.00118 -0.25237 -0.96762 -0.00372 -0.51824 -0.85514 0.01266 0.07105 -0.94250 0.32658 0.13045 -0.90945 0.39482 0.25882 -0.96593 -0.00048 0.12978 -0.99149 -0.01044 0.36620 -0.93054 -0.00105 0.81475 -0.57977 -0.00674 0.99177 -0.12793 0.00409 0.97574 -0.21894 -0.00122 -0.19895 -0.98001 0.00034 -0.97562 -0.21944 0.00338 0.00008 -1.00000 -0.00015 -0.00145 -1.00000 -0.00027 0.00066 -1.00000 -0.00200 0.00017 -1.00000 -0.00165 -0.00015 -1.00000 -0.00148 -0.00046 -1.00000 -0.00140 -0.00520 -0.99999 -0.00079 1.00000 -0.00006 -0.00112 1.00000 0.00062 -0.00147 1.00000 0.00034 -0.00135 1.00000 0.00011 -0.00125 1.00000 0.00000 -0.00121 -1.00000 -0.00068 0.00067 -1.00000 -0.00051 0.00069 -1.00000 -0.00040 0.00070 -1.00000 -0.00030 0.00071 -1.00000 -0.00019 0.00073 -1.00000 -0.00007 0.00075 -1.00000 0.00000 0.00077 -0.99998 0.00586 0.00356 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 0.96584 0.25909 -0.00561 0.70711 0.70710 -0.00224 0.38268 0.92388 -0.00105 0.13052 0.99145 -0.00053 -0.98654 0.16350 -0.00026 -0.89099 0.45398 0.00531 -0.70705 0.70705 0.01263 -0.45399 0.89100 0.00113 -0.14944 0.98877 0.00002 -0.12153 0.99258 -0.00372 0.00005 1.00000 0.00009 -0.00008 1.00000 0.00014 0.00001 1.00000 0.00009 0.00003 1.00000 0.00009 -0.10791 -0.99416 0.00038 -0.31691 -0.94845 0.00451 -0.97382 -0.22730 0.00191 -0.99284 -0.11942 -0.00000 -0.98769 0.15643 0.00000 -0.99144 0.13053 0.00060 -0.92388 0.38269 -0.00040 -0.89101 0.45399 0.00080 -0.79335 0.60876 -0.00060 -0.70711 0.70711 0.00090 -0.60876 0.79334 0.00414 -0.52998 0.84801 -0.00169 -0.45399 0.89101 -0.00027 -0.38268 0.92388 0.00096 -0.40791 0.91302 0.00232 -0.40924 0.91243 -0.00123 -0.13052 0.99144 0.00215 -0.15956 0.98719 -0.00035 -0.15922 0.98724 0.00045 0.37033 -0.89191 -0.25953 0.00098 1.00000 -0.00054 -0.98113 -0.18864 -0.04232 -0.99277 -0.11941 -0.01238 -0.68242 0.51015 -0.52350 -0.44507 0.60140 -0.66350 0.81915 -0.00004 -0.57358 0.00000 1.00000 0.00000 -0.89260 0.25436 -0.37225 -0.88341 0.27950 -0.37611 0.49406 -0.00002 -0.86943 0.42708 -0.00424 -0.90420 -0.29256 0.00148 -0.95625 0.81913 -0.00002 -0.57360 0.82204 -0.00859 -0.56936 0.82157 -0.00716 -0.57007 0.81518 0.00991 -0.57913 0.81931 0.00004 -0.57336 0.82167 -0.00528 -0.56993 0.81915 -0.00004 -0.57358 -0.92960 -0.36850 -0.00774 -0.84092 -0.53145 -0.10206 -0.70109 -0.71172 -0.04381 -0.00074 -1.00000 0.00052 0.23448 -0.59158 -0.77140 -0.35251 -0.22831 -0.90753 0.40533 -0.59696 -0.69235 0.38686 -0.56948 -0.72528 -0.28541 -0.23270 -0.92973 -0.30811 -0.28670 -0.90712 -0.25807 -0.31078 -0.91478 0.23525 -0.64984 -0.72275 0.30826 -0.64722 -0.69719 -0.33916 -0.29520 -0.89321 0.26361 -0.72845 -0.63235 -0.34827 -0.31462 -0.88302 -0.40242 -0.27333 -0.87370 0.32573 -0.81630 -0.47702 0.00721 -0.75190 -0.65924 0.16630 -0.77478 -0.60997 -0.31407 -0.31597 -0.89528 0.82540 -0.16065 -0.54120 0.79464 -0.32812 -0.51076 0.77099 -0.39996 -0.49559 0.60058 -0.67981 -0.42091 0.72838 -0.49440 -0.47437 0.64605 -0.61357 -0.45403 0.65462 -0.60045 -0.45927 0.58106 -0.70428 -0.40787 0.58346 -0.70151 -0.40922 0.60853 -0.66981 -0.42550 0.51098 -0.78302 -0.35464 0.46760 -0.81941 -0.33155 0.49779 -0.79333 -0.35047 0.43495 -0.84709 -0.30538 0.42888 -0.85146 -0.30179 0.36001 -0.89790 -0.25331 0.36052 -0.89760 -0.25364 -0.13026 0.98946 -0.06326 -0.38403 0.91131 -0.14844 -0.42556 0.83775 -0.34216 -0.45938 0.83469 -0.30375 -0.38307 0.91172 -0.14841 -0.37824 0.91316 -0.15189 -0.60660 0.79054 -0.08417 -0.69472 0.66867 -0.26503 -0.76483 0.61785 -0.18246 -0.76449 0.63286 -0.12264 -0.78977 0.60602 -0.09486 -0.92329 0.38244 -0.03562 -0.90867 0.37797 -0.17734 -0.97318 0.23000 -0.00456 -0.96591 0.25380 -0.05104 -0.97307 0.21210 -0.09028 -0.99122 0.13050 -0.02145 -0.70695 0.56381 -0.42702 -0.88221 0.28161 -0.37735 -0.92446 0.21947 -0.31178 -0.94149 0.01783 -0.33658 -0.96942 -0.00771 -0.24528 -0.97782 -0.00116 -0.20946 -0.97851 -0.01931 -0.20530 -0.99457 -0.02576 -0.10085 -0.05971 0.99471 -0.08363 -0.07485 0.99005 -0.11918 -0.15231 0.96177 -0.22760 -0.18020 0.95116 -0.25065 -0.28594 0.87859 -0.38251 -0.26602 0.89107 -0.36773 -0.38894 0.75596 -0.52654 -0.33059 0.80936 -0.48543 -0.53530 0.65496 -0.53336 -0.57355 -0.00001 -0.81917 -0.57355 0.00000 -0.81917 -0.55955 -0.00849 -0.82876 -0.62174 0.01656 -0.78305 -0.57358 0.00002 -0.81915 -0.57360 0.00003 -0.81914 -0.57360 0.00003 -0.81914 -0.57361 0.00003 -0.81913 -0.52031 -0.00711 -0.85395 -1.00000 -0.00000 -0.00223 -0.99996 -0.00095 -0.00884 -0.99998 -0.00024 -0.00552 -0.99598 -0.01129 0.08891 0.00057 1.00000 -0.00000 -0.00228 0.99987 -0.01593 -0.07763 0.87274 0.48198 0.05892 0.74278 0.66694 0.04719 0.89564 0.44227 0.10086 0.90505 0.41316 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.25760 -0.96137 0.09704 0.13120 -0.93972 0.31577 0.04226 -0.93526 0.35142 0.03103 -0.89988 0.43502 -0.02004 -0.89145 0.45267 -0.01268 -0.79648 0.60453 0.08486 -0.99137 0.09990 0.08283 -0.99435 0.06644 0.06829 -0.99699 0.03660 0.17929 -0.98230 0.05425 0.15184 -0.98830 0.01422 0.16981 -0.97088 0.16900 0.30391 -0.91882 0.25181 0.55978 -0.82095 0.11264 0.42611 -0.82389 0.37368 0.44032 -0.78817 0.43001 0.61730 -0.77025 0.16016 0.60282 -0.59761 0.52865 0.83115 -0.53706 0.14408 0.61171 -0.54071 0.57745 0.70854 -0.37183 0.59976 0.88759 -0.39311 0.24008 0.96594 -0.16830 0.19658 0.73646 -0.16028 0.65721 0.71034 -0.10516 0.69595 0.96593 -0.07592 0.24741 0.62613 -0.77970 0.00506 0.51327 -0.85821 -0.00546 0.91370 -0.40629 0.00889 0.02994 -0.99864 0.04276 0.07669 -0.99144 0.10564 0.11288 -0.97847 0.17280 0.21741 -0.92388 0.31494 0.22797 -0.91421 0.33503 0.40596 -0.69438 0.59416 0.34757 -0.79335 0.49980 0.35373 -0.78295 0.51173 0.43178 -0.66299 0.61156 0.45135 -0.60876 0.65245 0.40363 -0.69507 0.59495 0.48671 -0.38216 0.78553 0.54652 -0.10777 0.83048 0.56817 -0.12870 0.81278 0.54675 -0.05619 0.83540 0.00103 -1.00000 0.00158 0.00067 -1.00000 -0.00027 0.00098 -1.00000 -0.00049 -0.00221 -0.99999 -0.00437 -0.00044 -1.00000 -0.00063 -0.00040 -1.00000 0.00070 -0.00216 -1.00000 -0.00138 -0.00087 -1.00000 0.00045 -0.00303 -0.99999 -0.00243 -0.00144 -1.00000 -0.00039 -0.00050 -1.00000 -0.00058 -0.00038 -1.00000 0.00071 -0.00137 -1.00000 -0.00013 -0.57359 -0.00000 -0.81914 -0.57357 -0.00000 -0.81916 -0.57357 -0.00000 -0.81916 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.00000 1.00000 -0.00000 0.06694 0.99492 -0.07524 0.24246 0.95843 -0.15039 0.23151 0.95688 -0.17544 0.17121 0.98056 -0.09584 0.39040 0.88190 -0.26428 0.38192 0.88932 -0.25148 0.48635 0.81409 -0.31738 0.51694 0.77300 -0.36775 0.61812 0.66370 -0.42123 0.63075 0.63439 -0.44688 0.71337 0.50257 -0.48840 0.72019 0.47140 -0.50903 0.78063 0.32131 -0.53607 0.78190 0.29028 -0.55170 0.81714 0.12730 -0.56221 0.81350 0.09802 -0.57324 0.82144 -0.07136 -0.56582 0.81370 -0.09802 -0.57296 0.79323 -0.26778 -0.54689 0.78263 -0.29028 -0.55066 0.73369 -0.45354 -0.50596 0.72148 -0.47140 -0.50720 0.64526 -0.62114 -0.44477 0.63257 -0.63439 -0.44430 0.53121 -0.76425 -0.36570 0.51937 -0.77301 -0.36429 0.39639 -0.87686 -0.27201 0.38619 -0.88192 -0.27031 0.24582 -0.95475 -0.16741 0.23819 -0.95694 -0.16594 0.08548 -0.99477 -0.05598 0.08108 -0.99518 -0.05510 -0.14935 0.89987 0.40979 -0.13015 0.97172 0.19701 -0.09726 0.98250 0.15886 -0.09873 0.98486 0.14250 -0.08999 0.99075 0.10155 -0.03883 0.99896 0.02385 0.03687 0.99931 -0.00474 0.05550 0.99770 -0.03893 0.01173 0.99979 0.01688 0.23355 0.95869 -0.16240 0.18854 0.97179 -0.14172 0.16191 0.98079 -0.10882 0.35127 0.90345 -0.24572 0.36632 0.88898 -0.27481 0.46754 0.81415 -0.34434 0.49388 0.79724 -0.34713 0.61070 0.66373 -0.43187 0.61715 0.65761 -0.43206 0.70548 0.50258 -0.49971 0.71457 0.49044 -0.49886 0.77241 0.32132 -0.54785 0.78202 0.30272 -0.54480 0.80861 0.12730 -0.57441 0.81670 0.10234 -0.56791 0.81264 -0.07137 -0.57838 0.81730 -0.10234 -0.56705 0.78441 -0.26777 -0.55946 0.78369 -0.30272 -0.54240 0.72482 -0.45354 -0.51859 0.71729 -0.49043 -0.49495 0.63633 -0.62112 -0.45748 0.62095 -0.65760 -0.42660 0.52230 -0.76422 -0.37837 0.49869 -0.79721 -0.34025 0.38748 -0.87682 -0.28469 0.35568 -0.90343 -0.23941 0.23703 -0.95469 -0.17993 0.19793 -0.97178 -0.12832 0.08168 -0.99476 -0.06143 0.06945 -0.99549 -0.06460 0.03687 -0.99931 -0.00474 -0.02038 -0.99965 0.01689 -0.13752 -0.98521 0.10219 0.00487 -0.99324 0.11598 -0.16707 -0.97616 0.13853 -0.22747 -0.92240 0.31215 -0.25824 -0.94013 0.22241 0.77548 0.02612 0.63083 0.71506 0.16814 0.67854 0.95542 0.16167 0.24707 0.93441 0.20972 0.28792 0.70854 0.37183 0.59976 0.82388 0.54071 0.16987 0.63066 0.54442 0.55307 0.56626 0.60266 0.56228 0.46606 0.78469 0.40872 0.41334 0.82095 0.39394 0.48143 0.83122 0.27801 0.70234 0.70234 0.11594 0.30391 0.91882 0.25181 0.38059 0.91882 0.10452 0.23278 0.97167 0.04086 0.14850 0.98212 0.11574 0.09872 0.98831 0.11621 0.07303 0.99144 0.10820 0.13051 0.99137 0.01223 0.10190 0.99435 0.02976 0.06995 0.99694 0.03481 0.07486 0.99145 0.10692 0.05303 0.99537 0.08011 0.18269 0.94743 0.26268 0.21651 0.92387 0.31556 0.24459 0.90391 0.35090 0.30156 0.85080 0.43035 0.34454 0.79333 0.50191 0.39368 0.72816 0.56107 0.41816 0.68612 0.59531 0.44741 0.60874 0.65518 0.52226 0.42592 0.73881 0.52992 0.38268 0.75680 0.53767 0.35896 0.76293 0.55113 0.13367 0.82364 0.57213 0.02920 0.81964 0.96868 0.00079 0.24831 0.96805 0.00059 0.25074 0.74639 -0.00065 0.66551 0.77578 0.00322 0.63100 0.57358 -0.00001 0.81915 0.57358 0.00000 0.81915 0.57357 -0.00016 0.81915 0.57356 -0.00002 0.81916 0.57325 -0.01084 0.81931 0.57280 -0.00126 0.81970 0.57330 0.02735 0.81889 0.57358 -0.00000 0.81915 0.57239 0.00009 0.81998 0.57351 -0.00008 0.81920 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57352 -0.00011 0.81919 0.57358 0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57295 0.00805 0.81955 0.57358 0.00569 0.81913 0.57238 0.00193 0.81999 0.57452 -0.03601 0.81769 0.57257 0.02864 0.81936 0.57358 -0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 0.00001 0.81915 0.57358 0.00002 0.81915 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00049 1.00000 0.00086 0.00078 1.00000 -0.00098 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.42643 -0.00127 0.90452 0.45581 -0.00052 0.89008 0.35546 0.00008 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37466 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00251 0.92737 -0.42805 -0.01025 0.90370 -0.45567 -0.02415 0.88982 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 0.00000 -0.00005 1.00000 -0.00013 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -0.32753 -0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90969 0.63033 -0.00000 0.77633 0.63036 0.00000 0.77631 0.80504 -0.00000 0.59322 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37169 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07959 0.00000 0.99683 0.07959 0.00000 0.99683 -0.17359 0.00000 0.98482 -0.17359 0.00000 0.98482 -0.41529 0.00000 0.90969 -0.41529 0.00000 0.90969 -0.63033 0.00000 0.77633 -0.63033 0.00000 0.77633 -0.80504 0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 -0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32894 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39517 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35199 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39126 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85625 0.38631 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12334 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81900 -0.17246 -0.19506 0.98057 0.02092 -0.54306 0.83970 0.00048 -0.55558 0.83146 -0.00032 -0.82644 0.56302 0.00033 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 -0.98020 0.19803 0.00000 -0.98037 0.19531 0.02684 -0.00000 1.00000 0.00000 0.48300 0.87548 -0.01569 0.19509 0.98078 0.00289 0.55273 0.83336 -0.00014 0.55557 0.83147 -0.00032 0.82644 0.56303 0.00033 0.83147 0.55557 -0.00016 0.98001 0.19894 0.00016 0.98079 0.19509 -0.00005 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15934 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30814 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26659 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37311 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18797 0.97320 0.19358 0.12413 0.98077 -0.19509 0.00479 0.96592 -0.25883 -0.00000 0.83147 -0.55557 -0.00242 0.70708 -0.70712 0.00482 0.55557 -0.83147 -0.00242 0.25880 -0.96592 0.00361 0.19509 -0.98079 0.00000 -0.19508 -0.98077 0.00479 -0.25882 -0.96593 0.00000 -0.55557 -0.83147 -0.00242 -0.70710 -0.70710 0.00483 -0.83147 -0.55557 -0.00242 -0.96592 -0.25882 0.00361 -0.98078 -0.19509 0.00000 0.32738 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23701 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86547 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54635 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29876 -0.95399 0.02541 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18796 -0.97320 -0.19358 0.12413 0.47154 -0.01436 0.88173 0.14306 -0.95333 0.26588 0.33917 -0.38521 0.85824 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03997 -0.73162 0.68054 0.01607 -0.98803 0.15344 -0.03998 -0.73156 0.68061 -0.01608 -0.98803 0.15344 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.53936 0.83398 0.11644 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06987 -0.98282 0.18451 -0.00431 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85101 0.52047 0.06988 0.98001 0.19894 -0.00123 -0.38262 0.92383 0.01196 -0.60550 0.79206 -0.07758 -0.98242 0.18315 0.03618 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86396 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92864 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48079 0.35273 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78086 0.11745 0.43570 0.89717 -0.07251 0.98234 0.18358 0.03605 0.84345 0.53138 -0.07891 0.60508 0.79038 0.09581 0.08395 -0.47203 0.87758 0.07372 -0.31442 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39305 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.46536 -0.69804 0.54423 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.47838 0.87812 -0.00723 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18887 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18766 0.98224 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 0.00000 1.00000 0.00000 -0.19510 0.98078 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02737 -0.96449 -0.25844 -0.05450 -0.69955 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66579 0.40977 0.96449 -0.25844 -0.05450 0.69954 -0.69957 0.14577 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18765 0.98223 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18887 -0.67100 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92407 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19358 0.12407 0.81662 -0.54565 -0.18814 0.90235 -0.34994 0.25160 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02538 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54655 0.32005 -0.92238 0.21629 0.34529 -0.86547 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68809 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.18723 0.98232 -0.00049 -0.25882 -0.96593 -0.00000 -0.67986 -0.71506 0.16275 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 -0.99707 0.00000 -0.07645 -0.99777 0.00475 -0.06651 0.83570 0.00000 0.54918 0.83570 0.00000 0.54918 0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 -0.32386 -0.00000 0.94611 -0.32386 -0.00000 0.94611 -0.83570 0.00000 0.54918 -0.83570 -0.00000 0.54918 0.99781 0.00000 -0.06609 0.99780 -0.00013 -0.06633 -0.00012 1.00000 0.00012 -0.00002 1.00000 0.00014 -0.00005 1.00000 0.00014 0.03620 -0.94022 0.33864 0.10266 -0.94500 0.31053 0.12277 -0.94865 0.29153 0.11094 -0.94337 0.31263 -0.03620 -0.94022 0.33864 -0.10286 -0.94501 0.31044 -0.12261 -0.94859 0.29179 -0.11094 -0.94337 0.31265 0.00000 1.00000 0.00000 0.01046 0.99992 0.00670 -0.00053 1.00000 0.00160 -0.00018 1.00000 0.00167 0.00018 1.00000 0.00167 0.00052 1.00000 0.00160 -0.01046 0.99992 0.00670 0.00000 1.00000 0.00000 + + + + + + + + + + + + + + +

10 0 11 0 12 0 13 1 11 1 10 1 16 2 15 2 14 2 14 3 17 3 16 3 9 4 17 4 14 4 1 5 0 5 20 5 20 6 21 6 1 6 2 7 1 7 21 7 22 8 3 8 2 8 21 9 22 9 2 9 24 10 25 10 26 10 27 11 26 11 25 11 28 12 27 12 25 12 25 13 24 13 29 13 29 14 30 14 25 14 30 15 31 15 25 15 30 16 29 16 19 16 20 17 19 17 29 17 29 18 24 18 20 18 21 19 20 19 24 19 22 20 21 20 24 20 24 21 26 21 22 21 23 22 22 22 26 22 13 23 16 23 11 23 15 24 16 24 13 24 12 25 11 25 17 25 16 26 17 26 11 26 12 27 17 27 9 27 33 28 9 28 18 28 33 29 18 29 8 29 33 30 8 30 7 30 33 31 7 31 6 31 33 32 6 32 4 32 33 33 4 33 5 33 32 34 33 34 5 34 25 35 60 35 61 35 51 36 14 36 48 36 84 37 37 37 34 37 84 38 34 38 81 38 81 39 34 39 38 39 60 40 36 40 88 40 86 41 88 41 36 41 84 42 86 42 37 42 86 43 36 43 37 43 79 44 81 44 38 44 38 45 39 45 79 45 77 46 79 46 39 46 39 47 40 47 77 47 74 48 77 48 40 48 40 49 58 49 74 49 72 50 74 50 58 50 58 51 59 51 72 51 53 52 44 52 69 52 41 53 83 53 44 53 41 54 85 54 83 54 41 55 87 55 85 55 41 56 44 56 56 56 44 57 53 57 56 57 89 58 87 58 41 58 56 59 57 59 41 59 63 60 46 60 62 60 42 61 46 61 66 61 46 62 63 62 66 62 42 63 75 63 46 63 42 64 76 64 75 64 42 65 78 65 76 65 43 66 42 66 67 66 42 67 66 67 67 67 42 68 43 68 78 68 43 69 80 69 78 69 82 70 80 70 43 70 43 71 69 71 44 71 43 72 67 72 69 72 43 73 44 73 82 73 44 74 83 74 82 74 49 75 50 75 45 75 71 76 70 76 45 76 45 77 46 77 71 77 46 78 73 78 71 78 46 79 75 79 73 79 45 80 62 80 46 80 45 81 50 81 62 81 35 82 47 82 62 82 62 83 50 83 35 83 50 84 48 84 35 84 50 85 51 85 48 85 53 86 69 86 52 86 56 87 53 87 54 87 53 88 52 88 54 88 54 89 55 89 56 89 63 90 62 90 47 90 47 91 64 91 63 91 66 92 63 92 64 92 64 93 65 93 66 93 65 94 68 94 66 94 68 95 67 95 66 95 69 96 67 96 68 96 68 97 52 97 69 97 70 98 71 98 72 98 74 99 72 99 73 99 72 100 71 100 73 100 73 101 75 101 74 101 77 102 74 102 75 102 75 103 76 103 77 103 79 104 77 104 78 104 77 105 76 105 78 105 81 106 79 106 80 106 79 107 78 107 80 107 84 108 81 108 82 108 81 109 80 109 82 109 82 110 83 110 84 110 86 111 84 111 85 111 84 112 83 112 85 112 88 113 86 113 87 113 86 114 85 114 87 114 168 115 167 115 166 115 223 116 168 116 166 116 223 117 166 117 222 117 25 118 157 118 158 118 25 119 61 119 157 119 198 120 33 120 197 120 197 121 33 121 117 121 210 122 140 122 141 122 210 123 209 123 140 123 144 124 142 124 138 124 90 125 188 125 135 125 154 126 156 126 155 126 148 127 156 127 154 127 91 128 143 128 92 128 91 129 144 129 143 129 137 130 92 130 95 130 93 131 137 131 95 131 137 132 135 132 136 132 94 133 135 133 137 133 137 134 93 134 94 134 188 135 180 135 181 135 143 136 95 136 92 136 188 137 90 137 180 137 93 138 95 138 97 138 93 139 97 139 147 139 143 140 97 140 95 140 143 141 144 141 97 141 144 142 138 142 97 142 138 143 96 143 97 143 147 144 97 144 96 144 147 145 96 145 98 145 147 146 98 146 148 146 145 147 93 147 147 147 90 148 99 148 180 148 180 149 99 149 179 149 179 150 99 150 178 150 178 151 99 151 153 151 153 152 99 152 154 152 146 153 154 153 99 153 145 154 146 154 99 154 145 155 99 155 93 155 93 156 99 156 94 156 135 157 94 157 99 157 99 158 90 158 135 158 55 159 14 159 149 159 33 160 12 160 9 160 33 161 10 161 12 161 33 162 206 162 10 162 33 163 204 163 206 163 33 164 200 164 204 164 33 165 202 165 200 165 33 166 198 166 202 166 121 167 123 167 110 167 110 168 100 168 104 168 100 169 128 169 104 169 101 170 127 170 177 170 126 171 127 171 101 171 177 172 111 172 101 172 102 173 125 173 126 173 125 174 102 174 124 174 126 175 103 175 102 175 103 176 126 176 101 176 111 177 112 177 101 177 128 178 124 178 102 178 102 179 107 179 128 179 107 180 102 180 103 180 104 181 128 181 107 181 105 182 101 182 112 182 101 183 105 183 103 183 112 184 113 184 105 184 106 185 103 185 105 185 103 186 106 186 107 186 110 187 104 187 107 187 105 188 108 188 106 188 108 189 105 189 113 189 113 190 114 190 108 190 109 191 106 191 108 191 106 192 109 192 107 192 107 193 118 193 110 193 118 194 107 194 109 194 108 195 116 195 109 195 116 196 108 196 114 196 117 197 109 197 116 197 109 198 117 198 118 198 114 199 115 199 116 199 121 200 110 200 118 200 176 201 133 201 177 201 111 202 177 202 133 202 133 203 134 203 111 203 112 204 111 204 134 204 134 205 130 205 112 205 113 206 112 206 130 206 130 207 131 207 113 207 114 208 113 208 131 208 131 209 196 209 114 209 115 210 114 210 196 210 196 211 197 211 115 211 197 212 116 212 115 212 117 213 116 213 197 213 33 214 119 214 117 214 119 215 118 215 117 215 121 216 118 216 119 216 120 217 121 217 119 217 123 218 121 218 122 218 121 219 120 219 122 219 181 220 182 220 188 220 190 221 188 221 182 221 182 222 183 222 190 222 191 223 190 223 183 223 183 224 184 224 191 224 192 225 191 225 184 225 184 226 185 226 192 226 199 227 192 227 185 227 185 228 186 228 199 228 203 229 199 229 186 229 186 230 187 230 203 230 205 231 203 231 187 231 187 232 15 232 205 232 13 233 205 233 15 233 14 234 153 234 149 234 178 235 153 235 14 235 158 236 215 236 163 236 158 237 216 237 215 237 213 238 216 238 158 238 158 239 157 239 213 239 211 240 213 240 157 240 157 241 61 241 211 241 208 242 211 242 61 242 61 243 60 243 208 243 88 244 208 244 60 244 159 245 167 245 28 245 166 246 167 246 159 246 159 247 160 247 166 247 160 248 161 248 166 248 161 249 165 249 166 249 164 250 165 250 161 250 161 251 162 251 164 251 164 252 163 252 215 252 164 253 162 253 163 253 23 254 28 254 167 254 23 255 27 255 28 255 26 256 27 256 23 256 169 257 92 257 136 257 129 258 169 258 136 258 129 259 170 259 169 259 129 260 136 260 189 260 136 261 135 261 189 261 189 262 193 262 129 262 132 263 129 263 193 263 129 264 132 264 170 264 132 265 171 265 170 265 132 266 172 266 171 266 132 267 173 267 172 267 174 268 173 268 132 268 193 269 194 269 132 269 132 270 131 270 130 270 132 271 196 271 131 271 132 272 195 272 196 272 132 273 194 273 195 273 132 274 130 274 174 274 130 275 175 275 174 275 176 276 175 276 133 276 175 277 134 277 133 277 175 278 130 278 134 278 137 279 136 279 92 279 98 280 156 280 148 280 98 281 139 281 156 281 139 282 155 282 156 282 141 283 139 283 98 283 98 284 96 284 141 284 96 285 138 285 141 285 214 286 141 286 138 286 138 287 142 287 214 287 140 288 41 288 150 288 41 289 57 289 150 289 41 290 140 290 89 290 140 291 207 291 89 291 209 292 207 292 140 292 150 293 151 293 140 293 140 294 139 294 141 294 140 295 155 295 139 295 140 296 152 296 155 296 140 297 151 297 152 297 141 298 212 298 210 298 212 299 141 299 214 299 214 300 142 300 217 300 218 301 217 301 144 301 217 302 142 302 144 302 144 303 91 303 218 303 146 304 145 304 147 304 154 305 146 305 147 305 147 306 148 306 154 306 149 307 153 307 55 307 153 308 56 308 55 308 153 309 57 309 56 309 153 310 150 310 57 310 153 311 151 311 150 311 153 312 152 312 151 312 153 313 155 313 152 313 155 314 153 314 154 314 158 315 163 315 25 315 25 316 159 316 28 316 25 317 160 317 159 317 25 318 161 318 160 318 25 319 162 319 161 319 25 320 163 320 162 320 224 321 225 321 168 321 225 322 167 322 168 322 225 323 23 323 167 323 22 324 23 324 225 324 225 325 3 325 22 325 219 326 215 326 216 326 164 327 215 327 219 327 219 328 220 328 164 328 220 329 221 329 164 329 165 330 164 330 221 330 221 331 222 331 165 331 165 332 222 332 166 332 223 333 224 333 168 333 92 334 169 334 91 334 91 335 169 335 170 335 91 336 170 336 230 336 170 337 171 337 230 337 171 338 172 338 230 338 172 339 173 339 226 339 14 340 179 340 178 340 14 341 180 341 179 341 14 342 181 342 180 342 14 343 182 343 181 343 14 344 183 344 182 344 14 345 184 345 183 345 14 346 185 346 184 346 14 347 186 347 185 347 14 348 187 348 186 348 14 349 15 349 187 349 189 350 135 350 188 350 188 351 190 351 189 351 190 352 191 352 189 352 191 353 192 353 189 353 201 354 189 354 199 354 189 355 192 355 199 355 189 356 201 356 193 356 202 357 193 357 201 357 193 358 202 358 194 358 202 359 195 359 194 359 202 360 196 360 195 360 202 361 197 361 196 361 202 362 198 362 197 362 199 363 203 363 201 363 204 364 201 364 203 364 201 365 204 365 200 365 200 366 202 366 201 366 203 367 205 367 204 367 206 368 204 368 205 368 205 369 13 369 206 369 10 370 206 370 13 370 87 371 89 371 88 371 208 372 88 372 89 372 89 373 207 373 208 373 211 374 208 374 209 374 208 375 207 375 209 375 209 376 210 376 211 376 213 377 211 377 212 377 211 378 210 378 212 378 212 379 214 379 213 379 216 380 213 380 214 380 214 381 217 381 216 381 216 382 217 382 219 382 217 383 218 383 219 383 227 384 218 384 91 384 219 385 218 385 227 385 228 386 220 386 219 386 221 387 220 387 228 387 229 388 222 388 221 388 223 389 222 389 229 389 223 390 231 390 224 390 366 391 364 391 348 391 366 392 348 392 308 392 314 393 274 393 273 393 314 394 273 394 313 394 312 395 310 395 309 395 311 396 312 396 309 396 286 397 272 397 269 397 286 398 285 398 272 398 330 399 232 399 287 399 287 400 232 400 292 400 292 401 232 401 293 401 293 402 232 402 291 402 291 403 232 403 289 403 289 404 232 404 294 404 294 405 232 405 327 405 298 406 289 406 294 406 293 407 291 407 290 407 293 408 290 408 292 408 296 409 271 409 288 409 290 410 288 410 271 410 290 411 271 411 270 411 272 412 270 412 271 412 313 413 270 413 272 413 284 414 313 414 272 414 313 415 273 415 270 415 292 416 290 416 270 416 292 417 270 417 273 417 294 418 14 418 51 418 272 419 285 419 284 419 279 420 277 420 276 420 347 421 344 421 340 421 32 422 252 422 251 422 32 423 259 423 252 423 233 424 372 424 371 424 372 425 233 425 326 425 247 426 326 426 233 426 234 427 371 427 370 427 371 428 234 428 233 428 248 429 247 429 233 429 370 430 235 430 234 430 370 431 236 431 235 431 237 432 233 432 234 432 233 433 237 433 248 433 238 434 234 434 235 434 234 435 238 435 237 435 239 436 235 436 236 436 235 437 239 437 238 437 236 438 246 438 239 438 249 439 248 439 237 439 240 440 237 440 238 440 237 441 240 441 249 441 241 442 238 442 239 442 238 443 241 443 240 443 239 444 242 444 241 444 242 445 239 445 246 445 246 446 243 446 242 446 250 447 249 447 240 447 240 448 244 448 250 448 244 449 240 449 241 449 241 450 261 450 244 450 261 451 241 451 242 451 242 452 260 452 261 452 260 453 242 453 243 453 243 454 258 454 260 454 262 455 244 455 261 455 244 456 262 456 250 456 263 457 250 457 262 457 246 458 245 458 243 458 245 459 258 459 243 459 236 460 264 460 246 460 326 461 247 461 325 461 278 462 325 462 247 462 247 463 248 463 278 463 277 464 278 464 248 464 248 465 249 465 277 465 276 466 277 466 249 466 249 467 250 467 276 467 275 468 276 468 250 468 250 469 263 469 275 469 346 470 275 470 263 470 259 471 254 471 253 471 259 472 255 472 254 472 259 473 256 473 255 473 259 474 258 474 256 474 258 475 257 475 256 475 260 476 258 476 259 476 259 477 32 477 260 477 32 478 261 478 260 478 5 479 345 479 32 479 345 480 261 480 32 480 262 481 261 481 345 481 345 482 346 482 262 482 346 483 263 483 262 483 328 484 334 484 18 484 18 485 335 485 8 485 18 486 334 486 335 486 265 487 334 487 328 487 266 488 265 488 328 488 333 489 265 489 266 489 332 490 333 490 266 490 331 491 332 491 266 491 266 492 327 492 331 492 232 493 331 493 327 493 14 494 294 494 327 494 303 495 348 495 302 495 308 496 348 496 303 496 303 497 304 497 308 497 307 498 308 498 304 498 304 499 305 499 307 499 305 500 309 500 307 500 305 501 306 501 309 501 311 502 309 502 306 502 31 503 311 503 306 503 358 504 72 504 59 504 59 505 299 505 358 505 356 506 358 506 299 506 299 507 300 507 356 507 353 508 356 508 300 508 300 509 301 509 353 509 351 510 353 510 301 510 301 511 302 511 351 511 351 512 302 512 348 512 19 513 311 513 30 513 30 514 311 514 31 514 297 515 295 515 268 515 267 516 268 516 295 516 267 517 269 517 268 517 267 518 352 518 269 518 267 519 354 519 352 519 267 520 355 520 354 520 357 521 355 521 267 521 45 522 267 522 49 522 267 523 295 523 49 523 267 524 45 524 357 524 45 525 70 525 357 525 268 526 296 526 297 526 271 527 296 527 268 527 272 528 271 528 268 528 268 529 269 529 272 529 352 530 286 530 269 530 281 531 330 531 287 531 274 532 287 532 292 532 287 533 274 533 281 533 274 534 283 534 281 534 292 535 273 535 274 535 274 536 314 536 283 536 283 537 314 537 315 537 346 538 347 538 275 538 347 539 276 539 275 539 347 540 279 540 276 540 279 541 280 541 277 541 280 542 278 542 277 542 280 543 325 543 278 543 280 544 324 544 325 544 280 545 323 545 324 545 280 546 279 546 340 546 279 547 347 547 340 547 322 548 323 548 280 548 340 549 341 549 280 549 280 550 282 550 322 550 282 551 321 551 322 551 282 552 320 552 321 552 282 553 319 553 320 553 282 554 280 554 336 554 280 555 339 555 336 555 280 556 342 556 339 556 280 557 341 557 342 557 336 558 337 558 282 558 283 559 282 559 281 559 282 560 330 560 281 560 282 561 329 561 330 561 282 562 337 562 329 562 282 563 283 563 319 563 283 564 318 564 319 564 283 565 317 565 318 565 283 566 315 566 317 566 359 567 316 567 360 567 361 568 360 568 316 568 361 569 313 569 284 569 361 570 316 570 313 570 284 571 362 571 361 571 284 572 363 572 362 572 284 573 365 573 363 573 350 574 365 574 285 574 365 575 284 575 285 575 285 576 286 576 350 576 349 577 350 577 286 577 286 578 352 578 349 578 296 579 288 579 298 579 289 580 298 580 288 580 288 581 290 581 289 581 291 582 289 582 290 582 294 583 51 583 295 583 51 584 49 584 295 584 51 585 50 585 49 585 294 586 295 586 298 586 295 587 297 587 298 587 296 588 298 588 297 588 59 589 25 589 299 589 25 590 300 590 299 590 25 591 301 591 300 591 302 592 301 592 25 592 25 593 303 593 302 593 25 594 304 594 303 594 25 595 305 595 304 595 25 596 306 596 305 596 25 597 31 597 306 597 310 598 308 598 307 598 307 599 309 599 310 599 308 600 310 600 366 600 367 601 366 601 310 601 367 602 310 602 312 602 368 603 367 603 312 603 369 604 368 604 312 604 20 605 0 605 19 605 0 606 369 606 19 606 311 607 19 607 312 607 19 608 369 608 312 608 316 609 314 609 313 609 316 610 315 610 314 610 316 611 359 611 315 611 359 612 317 612 315 612 359 613 377 613 317 613 377 614 318 614 317 614 377 615 319 615 318 615 14 616 327 616 9 616 327 617 266 617 9 617 266 618 328 618 9 618 18 619 9 619 328 619 330 620 331 620 232 620 331 621 330 621 329 621 331 622 329 622 332 622 329 623 333 623 332 623 338 624 333 624 329 624 333 625 338 625 265 625 338 626 335 626 265 626 335 627 334 627 265 627 335 628 338 628 8 628 338 629 343 629 8 629 343 630 338 630 339 630 338 631 336 631 339 631 338 632 337 632 336 632 338 633 329 633 337 633 7 634 8 634 343 634 339 635 342 635 343 635 344 636 343 636 340 636 343 637 341 637 340 637 343 638 342 638 341 638 343 639 344 639 7 639 344 640 6 640 7 640 4 641 6 641 344 641 344 642 347 642 4 642 5 643 4 643 345 643 4 644 346 644 345 644 4 645 347 645 346 645 348 646 364 646 351 646 365 647 350 647 364 647 350 648 351 648 364 648 353 649 351 649 352 649 351 650 349 650 352 650 351 651 350 651 349 651 352 652 354 652 353 652 356 653 353 653 354 653 354 654 355 654 356 654 358 655 356 655 357 655 356 656 355 656 357 656 357 657 70 657 358 657 72 658 358 658 70 658 359 659 360 659 377 659 360 660 361 660 373 660 361 661 362 661 373 661 373 662 362 662 363 662 363 663 365 663 374 663 374 664 364 664 366 664 374 665 365 665 364 665 375 666 366 666 367 666 367 667 368 667 376 667 372 668 388 668 387 668 372 669 387 669 371 669 371 670 387 670 386 670 371 671 386 671 370 671 370 672 386 672 391 672 391 673 386 673 385 673 379 674 245 674 383 674 264 675 383 675 245 675 393 676 392 676 128 676 124 677 128 677 392 677 124 678 392 678 125 678 390 679 127 679 126 679 390 680 226 680 127 680 177 681 127 681 226 681 236 682 370 682 391 682 401 683 372 683 326 683 128 684 380 684 393 684 393 685 380 685 391 685 380 686 381 686 391 686 381 687 382 687 391 687 382 688 383 688 391 688 383 689 264 689 391 689 264 690 236 690 391 690 172 691 226 691 230 691 173 692 174 692 226 692 174 693 175 693 226 693 175 694 176 694 226 694 177 695 226 695 176 695 377 696 320 696 319 696 377 697 321 697 320 697 377 698 322 698 321 698 377 699 323 699 322 699 377 700 324 700 323 700 377 701 325 701 324 701 377 702 326 702 325 702 326 703 377 703 401 703 377 704 402 704 401 704 403 705 401 705 402 705 230 706 227 706 91 706 227 707 228 707 219 707 228 708 229 708 221 708 229 709 231 709 223 709 373 710 377 710 360 710 374 711 373 711 363 711 375 712 374 712 366 712 376 713 375 713 367 713 378 714 376 714 369 714 376 715 368 715 369 715 0 716 378 716 369 716 225 717 224 717 231 717 378 718 1 718 2 718 378 719 0 719 1 719 384 720 389 720 391 720 385 721 384 721 391 721 372 722 401 722 388 722 403 723 388 723 401 723 377 724 373 724 402 724 373 725 394 725 402 725 395 726 394 726 373 726 373 727 374 727 395 727 396 728 395 728 374 728 374 729 375 729 396 729 397 730 396 730 398 730 396 731 375 731 398 731 376 732 398 732 375 732 399 733 397 733 400 733 397 734 398 734 400 734 376 735 400 735 398 735 400 736 404 736 399 736 378 737 400 737 376 737 404 738 400 738 378 738 455 739 416 739 454 739 455 740 454 740 404 740 446 741 405 741 388 741 403 742 446 742 388 742 421 743 419 743 420 743 435 744 420 744 419 744 411 745 389 745 384 745 452 746 378 746 450 746 422 747 421 747 420 747 423 748 422 748 420 748 408 749 407 749 411 749 408 750 411 750 444 750 443 751 408 751 444 751 407 752 389 752 411 752 449 753 411 753 446 753 411 754 405 754 446 754 406 755 405 755 411 755 411 756 386 756 406 756 411 757 385 757 386 757 411 758 384 758 385 758 388 759 405 759 387 759 387 760 405 760 406 760 387 761 406 761 386 761 389 762 407 762 391 762 412 763 444 763 411 763 409 764 442 764 444 764 409 765 444 765 412 765 412 766 413 766 409 766 441 767 442 767 409 767 409 768 410 768 441 768 410 769 440 769 441 769 410 770 409 770 414 770 409 771 413 771 414 771 439 772 440 772 410 772 414 773 415 773 410 773 410 774 452 774 439 774 452 775 438 775 439 775 410 776 455 776 452 776 416 777 455 777 410 777 410 778 415 778 416 778 453 779 438 779 452 779 449 780 427 780 411 780 426 781 411 781 427 781 424 782 411 782 426 782 412 783 411 783 423 783 411 784 424 784 423 784 413 785 412 785 420 785 412 786 423 786 420 786 414 787 413 787 434 787 413 788 436 788 434 788 413 789 420 789 436 789 415 790 414 790 433 790 414 791 432 791 433 791 414 792 434 792 432 792 416 793 415 793 430 793 415 794 433 794 430 794 416 795 428 795 454 795 416 796 430 796 428 796 399 797 404 797 429 797 429 798 431 798 399 798 417 799 431 799 419 799 431 800 435 800 419 800 431 801 417 801 399 801 417 802 397 802 399 802 396 803 397 803 417 803 419 804 421 804 417 804 418 805 417 805 421 805 417 806 418 806 396 806 418 807 395 807 396 807 394 808 395 808 418 808 421 809 422 809 418 809 418 810 448 810 447 810 418 811 422 811 448 811 418 812 447 812 394 812 447 813 402 813 394 813 436 814 420 814 435 814 423 815 425 815 422 815 425 816 448 816 422 816 425 817 423 817 424 817 448 818 425 818 426 818 425 819 424 819 426 819 426 820 427 820 448 820 448 821 427 821 449 821 429 822 404 822 454 822 454 823 428 823 429 823 431 824 429 824 430 824 429 825 428 825 430 825 435 826 431 826 433 826 431 827 430 827 433 827 435 828 432 828 434 828 435 829 433 829 432 829 436 830 435 830 434 830 445 831 443 831 437 831 443 832 451 832 437 832 443 833 453 833 451 833 443 834 438 834 453 834 443 835 439 835 438 835 443 836 440 836 439 836 443 837 441 837 440 837 443 838 442 838 441 838 443 839 444 839 442 839 402 840 447 840 403 840 446 841 403 841 449 841 403 842 447 842 449 842 447 843 448 843 449 843 378 844 455 844 404 844 452 845 455 845 378 845 534 846 532 846 524 846 532 847 522 847 524 847 532 848 520 848 522 848 532 849 519 849 520 849 452 850 450 850 563 850 452 851 563 851 564 851 563 852 450 852 562 852 393 853 456 853 392 853 509 854 510 854 461 854 463 855 461 855 510 855 510 856 552 856 463 856 465 857 463 857 552 857 552 858 550 858 465 858 471 859 460 859 470 859 460 860 469 860 470 860 460 861 468 861 469 861 456 862 472 862 468 862 456 863 393 863 472 863 456 864 468 864 460 864 460 865 462 865 456 865 456 866 457 866 392 866 457 867 456 867 464 867 456 868 462 868 464 868 459 869 392 869 457 869 464 870 466 870 457 870 457 871 458 871 459 871 458 872 457 872 466 872 466 873 467 873 458 873 390 874 459 874 458 874 458 875 526 875 390 875 458 876 545 876 526 876 458 877 467 877 545 877 390 878 526 878 226 878 392 879 459 879 125 879 126 880 125 880 459 880 459 881 390 881 126 881 506 882 507 882 471 882 460 883 471 883 508 883 471 884 507 884 508 884 462 885 460 885 509 885 460 886 508 886 509 886 509 887 461 887 462 887 464 888 462 888 463 888 462 889 461 889 463 889 463 890 465 890 464 890 466 891 464 891 465 891 465 892 550 892 466 892 467 893 466 893 550 893 550 894 548 894 467 894 545 895 467 895 547 895 467 896 548 896 547 896 443 897 445 897 504 897 504 898 473 898 443 898 473 899 408 899 443 899 473 900 504 900 506 900 506 901 471 901 473 901 407 902 408 902 391 902 391 903 468 903 472 903 391 904 469 904 468 904 391 905 470 905 469 905 391 906 473 906 470 906 473 907 471 907 470 907 391 908 408 908 473 908 472 909 393 909 391 909 480 910 481 910 482 910 482 911 483 911 480 911 479 912 480 912 483 912 483 913 484 913 479 913 478 914 479 914 484 914 484 915 485 915 478 915 477 916 478 916 485 916 485 917 486 917 477 917 476 918 477 918 486 918 486 919 487 919 476 919 475 920 476 920 487 920 487 921 488 921 437 921 437 922 475 922 487 922 474 923 475 923 437 923 437 924 488 924 445 924 451 925 474 925 437 925 564 926 489 926 451 926 474 927 451 927 489 927 489 928 490 928 474 928 475 929 474 929 491 929 474 930 490 930 491 930 476 931 475 931 492 931 475 932 491 932 492 932 492 933 493 933 476 933 477 934 476 934 493 934 493 935 494 935 477 935 478 936 477 936 494 936 494 937 495 937 478 937 479 938 478 938 495 938 495 939 496 939 479 939 480 940 479 940 496 940 496 941 497 941 480 941 481 942 480 942 497 942 497 943 498 943 481 943 482 944 481 944 498 944 498 945 499 945 482 945 483 946 482 946 499 946 499 947 500 947 483 947 484 948 483 948 500 948 500 949 501 949 484 949 485 950 484 950 501 950 501 951 502 951 485 951 486 952 485 952 502 952 502 953 503 953 486 953 487 954 486 954 503 954 503 955 505 955 487 955 488 956 487 956 505 956 505 957 504 957 488 957 445 958 488 958 504 958 532 959 530 959 519 959 530 960 517 960 519 960 530 961 528 961 517 961 528 962 516 962 517 962 528 963 514 963 516 963 557 964 514 964 528 964 528 965 529 965 557 965 529 966 564 966 557 966 529 967 489 967 564 967 490 968 489 968 529 968 529 969 531 969 490 969 531 970 491 970 490 970 531 971 533 971 491 971 533 972 492 972 491 972 493 973 492 973 533 973 533 974 535 974 493 974 494 975 493 975 535 975 535 976 538 976 494 976 495 977 494 977 538 977 538 978 540 978 495 978 496 979 495 979 540 979 540 980 541 980 496 980 497 981 496 981 541 981 541 982 542 982 497 982 498 983 497 983 542 983 542 984 543 984 498 984 499 985 498 985 543 985 543 986 544 986 499 986 500 987 499 987 544 987 544 988 546 988 500 988 501 989 500 989 546 989 546 990 549 990 501 990 502 991 501 991 549 991 549 992 551 992 502 992 503 993 502 993 551 993 551 994 553 994 503 994 505 995 503 995 553 995 553 996 554 996 505 996 504 997 505 997 506 997 505 998 554 998 506 998 554 999 555 999 506 999 555 1000 507 1000 506 1000 555 1001 556 1001 507 1001 556 1002 508 1002 507 1002 556 1003 509 1003 508 1003 556 1004 552 1004 510 1004 510 1005 509 1005 556 1005 525 1006 527 1006 536 1006 511 1007 527 1007 525 1007 511 1008 230 1008 527 1008 511 1009 227 1009 230 1009 525 1010 523 1010 511 1010 511 1011 512 1011 227 1011 512 1012 511 1012 521 1012 511 1013 523 1013 521 1013 521 1014 518 1014 512 1014 513 1015 512 1015 518 1015 512 1016 513 1016 227 1016 513 1017 228 1017 227 1017 518 1018 515 1018 513 1018 229 1019 228 1019 513 1019 513 1020 559 1020 229 1020 513 1021 558 1021 559 1021 513 1022 562 1022 558 1022 513 1023 515 1023 562 1023 231 1024 229 1024 561 1024 229 1025 560 1025 561 1025 229 1026 559 1026 560 1026 515 1027 557 1027 562 1027 515 1028 514 1028 557 1028 516 1029 514 1029 515 1029 515 1030 518 1030 516 1030 518 1031 517 1031 516 1031 519 1032 517 1032 518 1032 518 1033 521 1033 519 1033 521 1034 520 1034 519 1034 522 1035 520 1035 521 1035 521 1036 523 1036 522 1036 524 1037 522 1037 523 1037 523 1038 525 1038 524 1038 534 1039 524 1039 525 1039 525 1040 536 1040 534 1040 537 1041 534 1041 536 1041 226 1042 526 1042 230 1042 527 1043 230 1043 526 1043 526 1044 545 1044 527 1044 536 1045 527 1045 545 1045 528 1046 530 1046 529 1046 531 1047 529 1047 530 1047 530 1048 532 1048 531 1048 533 1049 531 1049 532 1049 532 1050 534 1050 533 1050 535 1051 533 1051 534 1051 534 1052 537 1052 535 1052 538 1053 535 1053 537 1053 536 1054 545 1054 537 1054 545 1055 539 1055 537 1055 539 1056 538 1056 537 1056 539 1057 540 1057 538 1057 545 1058 546 1058 539 1058 541 1059 540 1059 539 1059 539 1060 542 1060 541 1060 539 1061 543 1061 542 1061 539 1062 544 1062 543 1062 546 1063 544 1063 539 1063 549 1064 546 1064 547 1064 546 1065 545 1065 547 1065 547 1066 548 1066 549 1066 551 1067 549 1067 550 1067 549 1068 548 1068 550 1068 550 1069 552 1069 551 1069 553 1070 551 1070 552 1070 552 1071 556 1071 553 1071 554 1072 553 1072 556 1072 556 1073 555 1073 554 1073 562 1074 557 1074 563 1074 557 1075 564 1075 563 1075 378 1076 562 1076 450 1076 378 1077 558 1077 562 1077 378 1078 559 1078 558 1078 378 1079 560 1079 559 1079 378 1080 561 1080 560 1080 378 1081 231 1081 561 1081 564 1082 451 1082 453 1082 453 1083 452 1083 564 1083 565 1084 256 1084 257 1084 252 1085 259 1085 253 1085 253 1086 566 1086 252 1086 567 1087 565 1087 257 1087 257 1088 568 1088 567 1088 252 1089 566 1089 569 1089 252 1090 569 1090 570 1090 251 1091 252 1091 570 1091 570 1092 571 1092 251 1092 572 1093 251 1093 571 1093 571 1094 573 1094 572 1094 574 1095 572 1095 573 1095 573 1096 575 1096 574 1096 574 1097 575 1097 576 1097 574 1098 576 1098 577 1098 578 1099 574 1099 577 1099 577 1100 579 1100 578 1100 578 1101 579 1101 120 1101 119 1102 578 1102 120 1102 571 1103 570 1103 573 1103 575 1104 573 1104 570 1104 570 1105 580 1105 575 1105 581 1106 575 1106 580 1106 580 1107 582 1107 581 1107 583 1108 581 1108 582 1108 582 1109 584 1109 583 1109 585 1110 583 1110 584 1110 584 1111 586 1111 585 1111 587 1112 585 1112 586 1112 586 1113 588 1113 587 1113 589 1114 587 1114 588 1114 591 1115 589 1115 590 1115 592 1116 591 1116 590 1116 595 1117 593 1117 590 1117 594 1118 596 1118 592 1118 590 1119 597 1119 595 1119 707 1120 592 1120 596 1120 598 1121 595 1121 597 1121 596 1122 599 1122 707 1122 597 1123 600 1123 598 1123 601 1124 707 1124 599 1124 602 1125 598 1125 600 1125 599 1126 603 1126 601 1126 604 1127 601 1127 603 1127 600 1128 605 1128 602 1128 603 1129 606 1129 604 1129 607 1130 602 1130 605 1130 604 1131 606 1131 608 1131 609 1132 604 1132 608 1132 610 1133 611 1133 607 1133 605 1134 610 1134 607 1134 612 1135 611 1135 610 1135 608 1136 612 1136 609 1136 613 1137 609 1137 612 1137 614 1138 613 1138 612 1138 610 1139 614 1139 612 1139 615 1140 616 1140 617 1140 618 1141 617 1141 616 1141 619 1142 621 1142 620 1142 622 1143 620 1143 621 1143 621 1144 623 1144 622 1144 624 1145 622 1145 623 1145 623 1146 625 1146 624 1146 624 1147 625 1147 626 1147 627 1148 624 1148 626 1148 626 1149 628 1149 627 1149 629 1150 627 1150 628 1150 628 1151 630 1151 629 1151 632 1152 633 1152 634 1152 635 1153 632 1153 634 1153 120 1154 636 1154 122 1154 637 1155 122 1155 636 1155 636 1156 638 1156 637 1156 639 1157 637 1157 638 1157 638 1158 640 1158 639 1158 641 1159 639 1159 640 1159 640 1160 642 1160 641 1160 643 1161 641 1161 642 1161 642 1162 644 1162 643 1162 645 1163 643 1163 644 1163 644 1164 646 1164 645 1164 647 1165 645 1165 646 1165 646 1166 648 1166 647 1166 649 1167 647 1167 648 1167 648 1168 615 1168 649 1168 617 1169 649 1169 615 1169 256 1170 650 1170 255 1170 651 1171 255 1171 650 1171 650 1172 652 1172 651 1172 653 1173 651 1173 652 1173 652 1174 654 1174 653 1174 655 1175 653 1175 654 1175 654 1176 656 1176 655 1176 657 1177 655 1177 656 1177 656 1178 658 1178 657 1178 659 1179 657 1179 658 1179 658 1180 660 1180 659 1180 661 1181 659 1181 660 1181 660 1182 662 1182 661 1182 663 1183 661 1183 662 1183 662 1184 635 1184 663 1184 634 1185 663 1185 635 1185 651 1186 254 1186 255 1186 653 1187 566 1187 253 1187 653 1188 253 1188 254 1188 651 1189 653 1189 254 1189 653 1190 655 1190 566 1190 664 1191 570 1191 569 1191 664 1192 569 1192 566 1192 566 1193 655 1193 657 1193 664 1194 566 1194 657 1194 580 1195 570 1195 664 1195 657 1196 659 1196 664 1196 664 1197 659 1197 661 1197 665 1198 664 1198 661 1198 665 1199 582 1199 580 1199 664 1200 665 1200 580 1200 584 1201 582 1201 665 1201 661 1202 663 1202 665 1202 669 1203 586 1203 584 1203 665 1204 669 1204 584 1204 665 1205 663 1205 634 1205 665 1206 634 1206 666 1206 669 1207 665 1207 666 1207 586 1208 669 1208 667 1208 588 1209 586 1209 667 1209 668 1210 597 1210 667 1210 667 1211 669 1211 668 1211 670 1212 668 1212 669 1212 669 1213 666 1213 670 1213 670 1214 666 1214 634 1214 670 1215 634 1215 633 1215 671 1216 670 1216 633 1216 591 1217 592 1217 589 1217 589 1218 592 1218 672 1218 673 1219 589 1219 672 1219 672 1220 674 1220 673 1220 675 1221 673 1221 674 1221 674 1222 676 1222 675 1222 677 1223 675 1223 676 1223 676 1224 616 1224 677 1224 615 1225 677 1225 616 1225 120 1226 579 1226 636 1226 638 1227 636 1227 579 1227 579 1228 577 1228 638 1228 638 1229 577 1229 678 1229 640 1230 638 1230 678 1230 679 1231 642 1231 640 1231 678 1232 679 1232 640 1232 576 1233 575 1233 679 1233 679 1234 678 1234 576 1234 575 1235 581 1235 679 1235 644 1236 642 1236 679 1236 679 1237 581 1237 583 1237 680 1238 679 1238 583 1238 680 1239 646 1239 644 1239 679 1240 680 1240 644 1240 583 1241 585 1241 680 1241 648 1242 646 1242 680 1242 680 1243 585 1243 587 1243 680 1244 587 1244 589 1244 680 1245 589 1245 673 1245 675 1246 680 1246 673 1246 680 1247 675 1247 648 1247 648 1248 675 1248 677 1248 615 1249 648 1249 677 1249 681 1250 682 1250 617 1250 618 1251 681 1251 617 1251 683 1252 682 1252 681 1252 681 1253 684 1253 683 1253 685 1254 683 1254 684 1254 684 1255 630 1255 685 1255 628 1256 685 1256 630 1256 686 1257 687 1257 629 1257 631 1258 686 1258 629 1258 688 1259 687 1259 686 1259 686 1260 689 1260 688 1260 690 1261 688 1261 689 1261 689 1262 632 1262 690 1262 635 1263 690 1263 632 1263 256 1264 691 1264 650 1264 652 1265 650 1265 691 1265 691 1266 692 1266 652 1266 654 1267 652 1267 692 1267 692 1268 693 1268 654 1268 656 1269 654 1269 693 1269 694 1270 658 1270 656 1270 693 1271 694 1271 656 1271 695 1272 620 1272 694 1272 696 1273 695 1273 694 1273 697 1274 696 1274 694 1274 694 1275 693 1275 697 1275 620 1276 622 1276 694 1276 660 1277 658 1277 694 1277 694 1278 622 1278 624 1278 694 1279 624 1279 627 1279 694 1280 627 1280 629 1280 694 1281 629 1281 687 1281 688 1282 694 1282 687 1282 688 1283 662 1283 660 1283 694 1284 688 1284 660 1284 662 1285 688 1285 690 1285 635 1286 662 1286 690 1286 245 1287 257 1287 258 1287 246 1288 264 1288 245 1288 568 1289 257 1289 245 1289 379 1290 698 1290 699 1290 699 1291 568 1291 245 1291 700 1292 379 1292 383 1292 383 1293 382 1293 700 1293 381 1294 701 1294 700 1294 382 1295 381 1295 700 1295 100 1296 701 1296 381 1296 381 1297 380 1297 100 1297 100 1298 110 1298 123 1298 100 1299 380 1299 128 1299 702 1300 606 1300 603 1300 608 1301 606 1301 702 1301 612 1302 608 1302 702 1302 611 1303 612 1303 702 1303 607 1304 611 1304 702 1304 602 1305 607 1305 702 1305 702 1306 598 1306 602 1306 595 1307 598 1307 702 1307 593 1308 595 1308 702 1308 594 1309 593 1309 702 1309 596 1310 594 1310 702 1310 599 1311 596 1311 702 1311 603 1312 599 1312 702 1312 703 1313 597 1313 668 1313 668 1314 670 1314 703 1314 704 1315 703 1315 670 1315 670 1316 671 1316 704 1316 672 1317 705 1317 674 1317 676 1318 674 1318 705 1318 705 1319 706 1319 676 1319 676 1320 706 1320 616 1320 708 1321 600 1321 597 1321 703 1322 708 1322 597 1322 704 1323 671 1323 708 1323 703 1324 704 1324 708 1324 671 1325 709 1325 708 1325 605 1326 600 1326 708 1326 710 1327 708 1327 709 1327 710 1328 610 1328 605 1328 708 1329 710 1329 605 1329 709 1330 711 1330 710 1330 614 1331 610 1331 710 1331 710 1332 711 1332 712 1332 713 1333 710 1333 712 1333 710 1334 713 1334 614 1334 613 1335 614 1335 713 1335 712 1336 714 1336 713 1336 715 1337 713 1337 714 1337 713 1338 715 1338 613 1338 609 1339 613 1339 715 1339 714 1340 716 1340 715 1340 717 1341 604 1341 609 1341 715 1342 717 1342 609 1342 717 1343 715 1343 716 1343 601 1344 604 1344 717 1344 716 1345 616 1345 717 1345 705 1346 707 1346 601 1346 717 1347 705 1347 601 1347 717 1348 616 1348 706 1348 717 1349 706 1349 705 1349 672 1350 707 1350 705 1350 720 1351 699 1351 698 1351 721 1352 699 1352 720 1352 720 1353 719 1353 721 1353 722 1354 721 1354 719 1354 719 1355 718 1355 722 1355 722 1356 718 1356 619 1356 722 1357 619 1357 620 1357 32 1358 251 1358 572 1358 32 1359 572 1359 574 1359 32 1360 574 1360 578 1360 32 1361 578 1361 119 1361 33 1362 32 1362 119 1362 577 1363 576 1363 678 1363 698 1364 379 1364 700 1364 700 1365 701 1365 698 1365 707 1366 672 1366 592 1366 245 1367 379 1367 699 1367 620 1368 695 1368 722 1368 699 1369 721 1369 722 1369 695 1370 699 1370 722 1370 695 1371 696 1371 699 1371 696 1372 697 1372 699 1372 568 1373 699 1373 697 1373 568 1374 697 1374 693 1374 568 1375 693 1375 692 1375 567 1376 568 1376 692 1376 567 1377 692 1377 691 1377 565 1378 567 1378 691 1378 256 1379 565 1379 691 1379 588 1380 590 1380 589 1380 588 1381 667 1381 590 1381 629 1382 630 1382 631 1382 631 1383 724 1383 723 1383 630 1384 724 1384 631 1384 671 1385 633 1385 632 1385 689 1386 726 1386 632 1386 686 1387 726 1387 689 1387 723 1388 727 1388 726 1388 723 1389 728 1389 727 1389 723 1390 724 1390 728 1390 724 1391 729 1391 728 1391 724 1392 725 1392 729 1392 681 1393 618 1393 725 1393 681 1394 725 1394 684 1394 122 1395 739 1395 745 1395 745 1396 739 1396 744 1396 744 1397 739 1397 738 1397 744 1398 738 1398 743 1398 743 1399 738 1399 737 1399 743 1400 737 1400 733 1400 743 1401 733 1401 732 1401 734 1402 732 1402 733 1402 735 1403 732 1403 734 1403 735 1404 730 1404 732 1404 732 1405 730 1405 731 1405 742 1406 730 1406 735 1406 100 1407 732 1407 701 1407 730 1408 742 1408 619 1408 730 1409 619 1409 718 1409 719 1410 730 1410 718 1410 730 1411 719 1411 731 1411 720 1412 731 1412 719 1412 731 1413 720 1413 732 1413 720 1414 698 1414 732 1414 732 1415 100 1415 743 1415 701 1416 732 1416 698 1416 743 1417 100 1417 123 1417 617 1418 682 1418 649 1418 649 1419 682 1419 683 1419 736 1420 647 1420 683 1420 683 1421 647 1421 649 1421 683 1422 685 1422 736 1422 736 1423 685 1423 628 1423 736 1424 628 1424 626 1424 736 1425 626 1425 740 1425 736 1426 740 1426 741 1426 647 1427 736 1427 645 1427 742 1428 736 1428 741 1428 736 1429 733 1429 737 1429 733 1430 736 1430 734 1430 734 1431 736 1431 735 1431 735 1432 736 1432 742 1432 737 1433 643 1433 736 1433 736 1434 643 1434 645 1434 643 1435 737 1435 641 1435 738 1436 641 1436 737 1436 641 1437 738 1437 639 1437 739 1438 639 1438 738 1438 639 1439 739 1439 637 1439 122 1440 637 1440 739 1440 623 1441 740 1441 625 1441 740 1442 623 1442 741 1442 621 1443 741 1443 623 1443 741 1444 621 1444 742 1444 619 1445 742 1445 621 1445 123 1446 744 1446 743 1446 744 1447 123 1447 745 1447 745 1448 123 1448 122 1448 625 1449 740 1449 626 1449 590 1450 594 1450 592 1450 590 1451 593 1451 594 1451 590 1452 667 1452 597 1452 631 1453 723 1453 686 1453 686 1454 723 1454 726 1454 630 1455 684 1455 724 1455 684 1456 725 1456 724 1456 709 1457 671 1457 726 1457 671 1458 632 1458 726 1458 716 1459 714 1459 729 1459 716 1460 729 1460 725 1460 714 1461 712 1461 728 1461 714 1462 728 1462 729 1462 712 1463 711 1463 727 1463 712 1464 727 1464 728 1464 711 1465 709 1465 726 1465 711 1466 726 1466 727 1466 616 1467 716 1467 725 1467 616 1468 725 1468 618 1468 2 1469 231 1469 378 1469 2 1470 3 1470 231 1470 3 1471 225 1471 231 1471 14 1472 68 1472 65 1472 14 1473 52 1473 68 1473 14 1474 54 1474 52 1474 14 1475 55 1475 54 1475 14 1476 65 1476 64 1476 14 1477 64 1477 47 1477 14 1478 47 1478 35 1478 14 1479 35 1479 48 1479 25 1480 59 1480 58 1480 25 1481 58 1481 40 1481 25 1482 40 1482 39 1482 25 1483 39 1483 38 1483 25 1484 38 1484 34 1484 25 1485 34 1485 37 1485 25 1486 37 1486 36 1486 25 1487 36 1487 60 1487

+
+
+
+
+ + + + 0.00000 0.00002 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E3M5.dae b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E3M5.dae new file mode 100644 index 0000000..71e98f5 --- /dev/null +++ b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E3M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:16:22.697136 + 2012-07-23T02:16:22.697149 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -4.16853 10.99697 56.91780 -2.13558 10.99697 56.22232 0.00030 10.99697 55.98668 2.13616 10.99697 56.22231 -7.41158 1.43357 57.78464 -7.54952 -0.00303 57.78464 -7.00374 2.81535 57.78464 -6.34754 4.08412 57.78464 -5.49969 5.16901 57.78464 -1.03468 8.49697 57.78464 2.42357 7.14735 57.78464 1.05031 7.94142 58.24917 1.05031 7.47344 57.78464 2.60851 7.94142 58.63739 0.00031 8.55728 68.91865 2.28125 8.49697 59.99264 1.05031 8.49697 59.64888 1.03530 8.49697 57.78464 -4.99969 8.49697 57.78464 -2.90817 11.39697 59.72056 -1.50644 11.39697 59.23010 -0.00019 11.39697 59.05914 1.50620 11.39697 59.22990 2.90832 11.39697 59.72033 0.00031 11.49528 59.76977 0.00032 11.49697 65.90822 1.69915 11.49697 60.07462 2.73893 11.49697 60.49405 3.64845 11.49697 61.07492 -1.69865 11.49697 60.07465 -2.73841 11.49697 60.49409 -3.64783 11.49697 61.07491 -7.54952 -4.00303 57.78464 7.55014 -4.00303 57.78465 1.13878 11.48797 71.16059 -3.33824 9.49194 70.55422 2.78628 11.49697 70.25549 2.27099 11.48797 70.79404 0.00032 11.48797 71.28465 -1.16122 11.48797 71.16059 -2.27036 11.48797 70.79404 5.28198 10.27446 71.13149 -1.06765 10.38028 73.07560 1.06828 10.38028 73.07560 3.10938 10.38170 72.45206 -5.28136 10.27446 71.13149 -3.10875 10.38170 72.45206 -2.54465 9.65113 71.40520 -3.28925 9.10508 69.40430 -5.96849 9.74083 70.08224 -4.84852 9.88731 71.04855 -3.17535 8.69990 68.29736 2.54802 9.65113 71.40519 3.44225 9.96396 71.93696 3.33827 9.49238 70.55584 3.28988 9.10508 69.40430 4.96737 9.87593 70.95893 5.56944 9.80370 70.45921 -2.78565 11.49697 70.25549 -3.73788 11.49697 69.49624 3.73850 11.49697 69.49624 4.49082 11.49697 68.53881 -3.86623 9.95133 71.70066 -2.59559 9.96856 72.33196 -1.30422 9.65113 71.81620 0.00028 9.65113 71.95565 -1.06018 9.96856 72.74751 0.81113 9.96856 72.78098 1.30478 9.65113 71.81622 2.01662 9.96856 72.53303 -5.53304 10.70933 70.64544 -4.96728 10.77157 71.09794 -4.80699 11.04699 70.66184 -3.94573 10.83814 71.77613 -3.60196 11.04698 71.60882 -2.63388 10.85606 72.42852 -1.65129 10.85606 72.73823 -2.23214 11.04697 72.25872 -0.46035 10.85606 72.91682 -0.75524 11.04697 72.59101 0.82309 10.85606 72.88416 0.76285 11.04697 72.59023 2.04635 10.85606 72.63255 2.57708 10.85606 72.45101 2.23939 11.04697 72.25643 3.99747 10.83605 71.74595 3.60862 11.04698 71.60508 5.09086 10.75973 71.00474 4.81271 11.04698 70.65682 5.71692 10.68463 70.48512 7.49423 7.94157 64.50987 8.92281 8.79775 63.71438 8.99367 8.08742 64.55763 8.69039 8.16196 65.11563 8.37644 7.53031 64.74487 8.95635 8.26939 64.86778 8.74722 9.00930 65.88835 8.77245 8.65637 65.41832 8.59545 8.83116 65.91737 7.72686 7.83903 65.04834 3.52352 -10.85658 55.20966 8.68893 -9.29155 57.92509 6.99644 -10.79866 56.75002 7.84651 -10.23448 57.50816 5.86119 -10.91940 56.20141 8.38834 -9.29184 58.21590 7.69150 -10.17120 57.61452 6.76178 -10.62444 56.96974 8.13379 -9.19327 58.25332 7.47072 -9.98157 57.66316 5.77439 -10.75303 56.34334 8.94369 -8.00302 58.26979 8.78663 -8.00302 58.44858 8.56473 -8.00302 58.53452 8.32824 -8.00302 58.50813 8.13074 -8.00303 58.37546 7.90869 -9.03650 58.13997 7.35169 -9.84937 57.60191 6.68573 -10.50130 57.00586 5.91680 -4.00303 56.51129 4.88920 -6.00303 55.93077 5.73944 -10.50303 56.40048 4.88920 -9.00303 55.93077 4.61923 -10.50303 55.80138 6.73955 -10.91053 56.37839 7.08858 -10.77342 56.59704 8.02298 -10.21861 57.23000 8.72172 -9.24322 57.79251 6.00031 -11.00303 55.97394 8.68089 5.63812 61.18336 8.56476 -0.00303 58.53451 8.32827 -0.00303 58.50815 8.68089 3.11933 59.20854 8.94369 -0.00303 58.26979 8.78664 -0.00303 58.44856 8.13074 7.10166 63.68239 8.67571 7.07942 64.04446 8.80273 7.58718 64.67844 8.80114 9.23126 65.82974 8.21285 9.19201 67.21714 7.07571 9.96326 69.35165 8.37914 9.46742 67.22308 8.75185 9.44767 65.75461 8.94514 8.88449 64.98747 8.80831 9.32990 65.52029 8.33006 8.34255 65.38938 7.94636 8.50667 65.71574 8.55656 8.56278 65.49903 8.37959 8.73646 65.91035 3.67569 8.71842 68.35970 6.20627 9.69696 69.83866 6.80137 9.56087 69.14859 7.29869 9.41038 68.46049 6.91519 8.54095 65.99626 7.57014 8.64119 66.07724 7.70401 9.25230 67.79227 8.22660 8.93963 66.59763 5.00357 11.49697 67.43311 5.24853 11.49697 66.23880 4.11090 11.49697 61.54639 4.49544 11.49697 62.19938 4.79629 11.49697 63.01113 5.02916 11.49697 63.95683 5.21279 11.49697 65.02298 6.34688 11.17864 63.68803 5.87602 11.27726 62.68842 5.34956 11.34554 61.80425 4.11882 11.39697 60.46767 4.73815 11.17530 59.66812 9.00031 7.42460 63.58684 9.00031 5.53833 60.37230 9.00031 4.97167 59.84727 9.00031 4.28707 59.33522 9.00031 3.46270 58.85725 9.00031 2.48084 58.44772 9.00031 1.33136 58.15448 9.00031 -0.00303 58.03868 9.00031 -8.00303 58.03868 6.58902 8.49697 65.82475 6.37200 8.49544 65.34729 6.13723 8.49697 64.74155 6.02274 8.49697 64.20972 5.84711 8.49697 63.64807 5.59360 8.49697 63.05240 5.24033 8.49697 62.42426 4.76095 8.49697 61.77386 4.12606 8.49697 61.12329 3.30603 8.49697 60.50996 7.35819 7.94142 63.84882 8.13074 5.63518 60.98634 7.13793 7.94142 63.15024 6.81856 7.94142 62.40866 6.37180 7.94142 61.62654 8.13074 3.31200 59.15843 8.13074 2.37288 58.76674 8.13074 1.27351 58.48625 8.13074 -0.00303 58.37546 7.84601 -0.00303 58.07458 7.55014 -0.00303 57.78465 5.76359 7.94142 60.81770 5.95262 4.64133 57.78465 6.76130 5.63631 59.19019 6.93098 2.91600 57.78465 4.95613 7.94142 60.01181 4.87115 5.76542 57.78465 3.91203 7.94142 59.25899 3.69320 6.58200 57.78465 6.37924 10.57362 69.83974 5.76106 11.04699 69.48746 6.99832 10.43204 69.12189 7.51555 10.27552 68.40620 6.39743 11.04699 68.22884 7.93707 10.11112 67.71126 6.74219 11.04698 66.98638 8.27304 9.94482 67.05045 6.77652 11.04697 64.79448 6.84833 11.04698 65.82776 8.27304 10.02494 65.82712 8.27304 9.95522 64.60337 7.68907 10.47650 65.22638 7.51440 10.58686 64.38346 7.28972 10.70574 63.34866 7.03156 10.81415 62.21390 6.56192 10.93564 60.26743 6.00031 10.99697 58.03868 4.16911 10.99697 56.91779 8.97320 -7.99930 35.69485 8.57261 9.49998 35.85024 7.47453 10.59806 35.85024 6.75099 10.89776 35.85024 8.97405 7.99896 35.64078 5.97453 10.99998 35.85024 -7.73288 7.83902 65.04834 -8.63502 -9.30826 58.01877 -7.93006 -10.24095 57.42631 -6.99314 -10.79692 56.75710 -5.98520 -10.99559 55.99763 -8.46533 -9.30571 58.17711 -7.75845 -10.20360 57.57774 -6.83918 -10.70810 56.91447 -8.28166 -9.25626 58.24971 -7.57564 -10.08604 57.65858 -6.71150 -10.54603 56.99843 -5.78438 -10.77336 56.32600 -8.08450 -9.16383 58.24420 -3.52289 -10.85658 55.20966 -5.86925 -10.93604 56.18721 -8.94307 -8.00303 58.26979 -8.78603 -8.00303 58.44856 -8.56413 -8.00303 58.53451 -8.32765 -8.00303 58.50815 -2.07017 -4.00303 54.98126 -4.06603 -4.00303 55.56384 -4.07348 -5.46536 55.56680 -4.41319 -5.67444 55.70889 -4.88858 -6.00303 55.93077 -4.88858 -9.00303 55.93077 -4.61835 -10.50303 55.80126 -5.73882 -10.50303 56.40048 -5.91618 -4.00303 56.51129 -6.61429 -10.30840 57.00250 -7.36932 -9.82743 57.61906 -7.90885 -9.03460 58.14079 -8.13012 -8.00303 58.37546 -4.42719 -11.00303 55.17110 -5.49969 7.94142 60.52766 -5.49969 8.49697 62.86916 -7.07509 9.96326 69.35165 -8.40868 9.57200 67.21003 -8.38164 9.77928 67.14390 -8.77847 8.65637 65.41832 -8.75324 9.00930 65.88834 -8.80716 9.23126 65.82973 -8.85598 8.20532 65.01575 -8.80875 7.58718 64.67843 -8.32765 -0.00303 58.50815 -8.56413 -0.00303 58.53451 -8.78603 -0.00303 58.44856 -8.94307 -0.00303 58.26979 -8.67508 -0.00303 58.49153 -8.68027 3.11935 59.20855 -8.56413 7.03771 64.05474 -8.68027 5.63813 61.18338 -8.78601 7.12115 64.03425 -8.82568 9.29202 65.44601 -8.75123 9.44767 65.75460 -8.62564 9.63634 66.23487 -8.38246 7.53031 64.74487 -8.47667 8.65770 65.68396 -7.56946 8.64121 66.07729 -8.55801 8.55985 65.49423 -7.94615 8.50652 65.71537 -8.69641 8.16196 65.11563 -8.32985 8.34236 65.38905 -6.92121 8.54095 65.99626 -7.21787 9.43370 68.56859 -8.38561 8.73646 65.91035 -8.02650 9.09237 67.15675 -7.22853 8.73646 66.44991 -4.49019 11.49697 68.53880 -5.00295 11.49697 67.43310 -5.24790 11.49697 66.23879 -5.21216 11.49697 65.02297 -5.02849 11.49697 63.95660 -4.79562 11.49697 63.01096 -4.49486 11.49697 62.19946 -4.11076 11.49697 61.54702 -5.87529 11.27728 62.68823 -6.34615 11.17867 63.68780 -5.34900 11.34554 61.80436 -6.50196 11.01932 62.49067 -4.11820 11.39697 60.46766 -4.73752 11.26217 59.66812 -8.95116 8.88449 64.98747 -8.99969 8.08742 64.55762 -8.99969 7.42452 63.58657 -8.99969 8.32860 64.17715 -8.99969 7.14456 62.79934 -8.99969 6.69775 61.89881 -8.99969 6.00432 60.89467 -8.99969 4.97055 59.84633 -8.99969 4.28585 59.33441 -8.99969 3.46150 58.85666 -8.99969 2.47985 58.44739 -8.99969 1.33074 58.15437 -8.99969 -0.00303 58.03868 -8.99969 -8.00303 58.03868 -6.36582 8.49697 65.28314 -4.99969 8.49697 59.78465 -8.13012 6.30681 61.90997 -8.13014 7.19214 64.01679 -6.93326 7.94142 62.65234 -6.58044 7.94142 61.96633 -6.11115 7.94142 61.25299 -4.99969 7.74294 59.78465 -4.99969 6.96932 58.90087 -8.13012 5.29650 60.60670 -8.13012 5.74314 61.10729 -6.84235 6.16047 59.76889 -8.13012 4.75429 60.10451 -8.13012 2.37195 58.76642 -8.13012 3.31086 59.15787 -8.13012 4.09936 59.61484 -7.66390 4.10292 59.04662 -8.13012 1.85875 58.63554 -7.84539 -0.00303 58.07458 -8.13012 -0.00303 58.37546 -8.13012 1.27291 58.48615 -6.77590 11.08882 64.79447 -8.27241 10.00166 66.46892 -8.27242 10.02460 65.87690 -6.84770 11.04698 65.82941 -8.27241 9.94482 67.05044 -6.74099 11.04698 66.98962 -7.64224 10.22999 68.20881 -7.22061 10.36962 68.82871 -6.39505 11.04699 68.23342 -6.71649 10.50161 69.46391 -5.75694 11.04699 69.49290 -8.99969 7.99697 62.95621 -8.92784 8.64962 63.24892 -8.74119 9.21523 63.62119 -8.49871 9.65676 64.07870 -8.27242 9.95522 64.60336 -7.68264 10.48045 65.19770 -8.04445 10.19218 65.20199 -7.28360 10.70835 63.32394 -6.95376 10.83841 61.88823 -6.49814 10.94335 60.01643 -5.99969 10.99697 58.03868 -7.09799 -10.76947 56.60332 -8.02191 -10.21902 57.22966 -8.72210 -9.24094 57.79337 -8.87864 8.92703 50.79252 -8.45252 9.76334 50.79252 -7.78882 10.42703 50.79252 -6.95252 10.85315 50.79252 -9.02547 7.99998 24.47807 -5.98549 10.99998 23.80068 -1.04969 -10.85241 54.68365 4.42840 -11.00303 55.17134 2.76805 -11.00303 54.62267 0.00032 -11.00303 54.33267 -2.76710 -11.00303 54.62259 -6.66595 -10.93085 11.30388 -7.24205 -10.74227 10.48113 -7.83129 -10.39779 9.62842 -8.54841 -9.69898 9.75196 -8.93990 -8.71143 9.75318 -6.02547 -11.00002 12.21858 8.87231 -8.77648 35.85024 -6.06415 -10.98435 42.34554 7.47453 -10.59810 35.85024 5.97453 -11.00002 35.85024 -8.92325 8.77644 9.75318 -8.62354 9.49998 9.75318 -8.14679 10.12130 9.75318 -7.52547 10.59806 9.75318 -7.40258 10.61573 24.42709 -6.80193 10.89776 9.75318 -6.85997 10.85877 24.18378 -9.02547 -8.00002 50.79252 -9.02547 7.99998 9.75318 -9.02547 -8.00002 9.75318 -6.02547 10.99998 9.75318 -8.82456 -8.97048 8.23386 -8.35722 -9.83346 8.87693 3.09373 -11.00002 25.24129 3.84738 -11.00002 25.66956 6.02902 7.60540 24.02987 7.59724 9.39440 22.93180 3.09373 4.51538 25.24086 4.80132 6.77597 24.02629 5.53123 7.92272 23.51520 6.36547 8.94930 22.93106 7.25502 9.81190 22.30820 8.13969 10.48946 21.68875 -7.81194 10.19832 8.06339 -8.70497 9.17054 8.32644 -7.84819 9.52832 6.46801 -8.06851 7.48123 4.76029 -8.47200 8.99747 6.76388 -8.91057 8.17181 7.25133 -8.48715 6.71069 5.17098 -8.78339 5.53871 5.93756 -8.82707 6.93589 6.13376 -8.91444 4.52108 6.55495 -9.00809 3.44139 7.10285 -2.52488 10.79660 5.44341 -6.37604 10.87409 8.50607 -3.42532 10.53381 5.09353 -6.61970 10.62987 7.63714 -5.58596 9.52464 4.65381 -4.28238 10.18335 4.86431 -6.39769 9.05089 4.57325 -7.05581 9.89042 6.26470 -7.27770 8.32427 4.56418 14.71637 -1.00002 18.30448 9.11121 9.61540 22.22925 8.30002 8.99410 22.79724 7.48444 8.20316 23.36832 6.71983 7.26218 23.90371 6.05099 6.21134 24.37204 4.46876 -10.99931 25.47945 3.97006 4.32180 25.65569 13.48764 -11.00002 19.16484 -9.00962 -7.94523 7.95428 -9.02291 7.83078 8.60572 -9.13174 7.34492 7.32504 -9.01689 1.01905 7.80848 6.11848 10.99998 28.10642 13.48764 10.99998 19.16484 9.61673 10.99998 21.56325 10.27987 10.99998 21.33061 -1.38547 10.99361 6.36442 8.95372 10.99149 21.12506 7.67080 -10.77166 33.60986 8.53410 -10.12134 34.05927 9.11094 -9.14807 34.35955 8.38867 -9.86395 35.85762 8.97843 -10.89780 31.57137 15.04788 -10.47307 28.44679 9.39344 -10.59810 32.16406 14.55192 -10.22275 29.17261 9.74981 -10.12134 32.67301 13.96278 -9.72338 30.12993 10.02327 -9.50002 33.06355 10.19517 -8.77648 33.30905 6.44810 -10.99915 33.53150 6.95150 -11.00002 32.56861 7.68086 -11.00002 31.65925 8.53307 -11.00002 30.93533 6.07891 -11.00002 34.73596 7.24306 -10.99855 29.51986 15.24554 10.78862 17.93394 16.93588 10.16265 16.75036 18.49370 9.14615 15.65955 19.85915 7.77816 14.70346 20.97974 6.11126 13.91881 21.81242 4.20950 13.33576 22.32518 2.14598 12.97673 22.49832 -0.00002 12.85549 22.32518 -2.14601 12.97673 21.81242 -4.20954 13.33576 20.97974 -6.11129 13.91881 19.85915 -7.77819 14.70346 18.49370 -9.14618 15.65955 16.93588 -10.16269 16.75036 15.24554 -10.78866 17.93394 17.24874 10.99998 22.51061 18.17611 10.65630 21.81541 19.22166 10.40002 21.06122 20.96988 9.32311 19.90791 22.40247 8.07652 18.90565 23.59134 6.43999 18.07167 24.49215 4.54886 17.44142 25.06778 2.47712 17.03791 25.29603 0.30725 16.87835 25.16816 -1.87593 16.96807 24.68785 -3.98494 17.30406 23.87474 -5.93575 17.87369 22.76056 -7.65164 18.65359 21.39038 -9.06324 19.61331 19.81750 -10.11579 20.71426 16.31776 -10.99078 23.16249 18.10548 -10.76687 21.91349 17.38796 -11.00002 24.73507 16.96749 -10.97764 25.55215 16.34939 -10.84743 26.69325 15.72066 -10.57274 27.87064 15.38818 -10.15375 29.25569 9.11094 9.14803 34.35955 8.53410 10.12130 34.05927 7.67080 10.77162 33.60986 16.43848 10.92617 26.28057 8.97843 10.89776 31.57137 15.95405 10.80158 27.06688 15.43530 10.63526 27.85690 9.39344 10.59806 32.16406 14.92284 10.39920 28.68267 14.42861 10.14589 29.35819 9.74981 10.12130 32.67301 13.86560 9.76151 30.19668 10.02327 9.49998 33.06355 13.36479 9.18490 30.88310 10.19517 8.77644 33.30905 9.29688 -7.99607 34.43215 9.27742 7.99604 34.46957 18.48210 10.97335 27.63127 20.32549 10.89922 26.34051 16.66504 10.58775 28.90359 22.11796 10.36841 25.08541 14.91703 9.74032 30.12738 23.78436 9.40314 23.91859 12.34762 8.52781 31.90911 25.25485 8.04386 22.88894 10.02733 7.99865 33.54759 11.78197 7.99998 32.32275 26.46777 6.34756 22.03964 19.10870 -1.00002 27.19253 27.37233 4.38535 21.40626 27.93064 2.23951 21.01533 28.11937 -0.00001 20.88318 27.93064 -2.23954 21.01533 27.37233 -4.38538 21.40626 10.17767 -7.99948 33.44432 26.46778 -6.34759 22.03964 11.78197 -8.00002 32.32275 12.79827 -8.62660 31.61546 25.25485 -8.04389 22.88894 13.84475 -9.17023 30.85625 23.78437 -9.40318 23.91858 14.95047 -9.75869 30.10414 22.11796 -10.36845 25.08541 20.32550 -10.89926 26.34051 18.48211 -10.97339 27.63127 16.66505 -10.58779 28.90358 17.38796 10.99998 24.73507 7.68086 10.99998 31.65925 6.88393 10.99870 32.69260 6.40583 10.99998 33.61652 6.07891 10.99998 34.73596 8.53307 10.99998 30.93533 14.42391 10.99998 24.49159 16.29335 10.99998 23.17457 -4.52128 -9.48780 55.75693 -3.74877 -5.29607 55.44330 -4.04355 -10.02226 55.55492 -3.44120 -10.49866 55.33802 -3.27828 -5.11393 55.28461 -2.56465 -5.00303 55.08788 -0.86205 -5.00303 54.81850 0.00031 -4.00303 54.78465 0.86268 -5.00303 54.81850 2.07080 -4.00303 54.98126 2.56528 -5.00303 55.08788 3.24817 -5.10488 55.27505 3.85739 -5.34857 55.48305 4.06665 -4.00303 55.56384 4.39886 -5.66467 55.70235 -2.03629 -5.00303 55.45412 2.03692 -5.00303 55.45412 -1.59865 -5.00303 55.92377 1.59927 -5.00303 55.92377 -1.27058 -5.00303 56.47660 1.27121 -5.00303 56.47660 -1.06794 -5.00303 57.08608 1.06857 -5.00303 57.08608 -0.99969 -5.00303 57.72238 1.00031 -5.00303 57.72238 -0.99969 -5.00303 64.05260 1.00031 -5.00303 64.05260 1.23270 -5.00303 64.87756 -0.22221 -5.00303 64.80972 0.22284 -5.00303 64.80972 -0.62317 -5.00303 65.00281 0.62381 -5.00303 65.00281 -1.36571 -5.07242 64.78465 -0.90065 -5.00303 65.35076 0.90128 -5.00303 65.35076 -1.16938 -5.00303 65.70529 1.17001 -5.00303 65.70531 -0.99969 -5.00303 65.78465 1.00031 -5.00303 65.78465 1.08593 -5.00303 66.22726 -1.07869 -5.00303 66.24315 0.86804 -5.00303 66.28169 -0.86541 -5.00303 66.28516 0.50304 -5.00303 66.64909 0.76600 -5.00303 66.67245 -0.75402 -5.00303 66.68211 -0.49850 -5.00303 66.65135 0.00254 -5.00303 66.78464 0.28178 -5.00303 66.92274 -0.26495 -5.00303 66.92662 2.00031 -6.00303 57.72238 2.00069 -6.00303 64.78463 2.00031 -9.00303 57.72238 2.00032 -9.00303 64.78465 0.00032 -10.00303 55.78465 -1.66580 -10.00303 55.83743 0.00032 -10.00303 56.18634 -1.38036 -10.00303 56.25980 0.00032 -10.00303 56.52710 -1.17070 -10.00303 56.72397 0.00032 -10.00303 56.79470 1.04338 -10.00303 57.21588 -1.04276 -10.00303 57.21584 1.00031 -10.00303 57.72238 -0.99969 -10.00303 57.72238 1.00032 -10.00303 64.78465 -0.99968 -10.00303 64.78465 -1.99969 -9.00303 64.78465 -1.99969 -6.00303 64.74483 -1.99969 -6.00303 57.72238 -1.99969 -9.00303 57.72238 4.41109 -6.00303 55.76503 4.41097 -9.00303 55.76500 3.90525 -6.00303 55.72464 3.90519 -9.00303 55.72466 3.40663 -6.00303 55.81253 3.40656 -9.00303 55.81256 2.94624 -6.00303 56.02271 2.94618 -9.00303 56.02274 2.55335 -6.00303 56.34171 2.55329 -9.00303 56.34176 2.25301 -6.00303 56.74930 2.25292 -9.00303 56.74944 2.06435 -6.00303 57.22037 2.06428 -9.00303 57.22060 -4.41046 -9.00303 55.76503 -4.41046 -6.00303 55.76503 -3.90463 -9.00303 55.72464 -3.90463 -6.00303 55.72464 -3.40600 -9.00303 55.81253 -3.40600 -6.00303 55.81253 -2.94561 -9.00303 56.02271 -2.94561 -6.00303 56.02271 -2.55272 -9.00303 56.34171 -2.55272 -6.00303 56.34171 -2.25238 -9.00303 56.74930 -2.25238 -6.00303 56.74930 -2.06372 -9.00303 57.22037 -2.06372 -6.00303 57.22037 -2.71138 -5.29592 55.82565 -1.97344 -5.29592 56.64922 -1.92357 -5.62035 57.72238 -1.38239 -5.07915 57.72238 -1.69827 -5.28750 64.78465 -1.70681 -5.29593 57.72238 -1.92125 -5.61481 64.78465 -1.99475 -6.00303 64.92503 1.43195 -5.11040 65.01970 1.38300 -5.07915 57.72238 1.69889 -5.28749 64.78465 1.70742 -5.29592 57.72238 1.92189 -5.61481 64.78465 1.92419 -5.62034 57.72238 3.74839 -5.30497 55.44583 2.71693 -5.29592 55.82231 1.97546 -5.29592 56.64659 1.86633 -9.50305 64.78465 1.92419 -9.38571 57.72238 1.70742 -9.71014 57.72238 1.50029 -9.86907 64.78465 1.38300 -9.92691 57.72238 -1.49969 -9.86905 64.78465 -1.38237 -9.92691 57.72238 -1.70679 -9.71014 57.72238 -1.86571 -9.50303 64.78465 -1.92357 -9.38571 57.72238 -4.20886 -9.24626 55.70316 -3.45966 -9.51198 55.65247 -2.92259 -9.70494 55.70795 -2.03552 -9.71014 56.53943 -1.97107 -9.98200 55.79823 -2.25367 -9.92569 55.77649 -2.52205 -9.84500 55.75502 0.00032 -10.66970 54.80614 -2.47480 -10.61703 55.07125 0.00032 -10.97928 54.48560 1.05032 -10.85241 54.68365 0.00031 -5.00303 65.78465 -1.73699 -5.33823 64.96863 -1.92773 -5.64578 64.93640 1.73761 -5.33822 64.96864 1.92836 -5.64578 64.93640 1.27380 -5.02203 65.28942 -1.81236 -5.27567 66.19547 -2.10209 -5.94570 66.32501 -1.15964 -5.27567 67.23690 -1.32993 -5.94570 67.50003 0.00031 -5.94570 67.95538 0.00031 -5.27567 67.64330 1.33056 -5.94570 67.50003 1.16027 -5.27567 67.23691 2.10272 -5.94570 66.32501 1.81299 -5.27567 66.19547 0.00032 -10.04902 55.45229 0.00032 -10.18686 55.17287 0.00032 -10.40319 54.94949 -1.78668 -10.32127 55.11591 -1.73172 -10.17210 55.44402 -0.99968 -10.00303 66.28465 1.00032 -10.00303 66.28465 2.10272 -8.94570 66.32501 -2.10209 -8.94570 66.32501 -1.32993 -8.94570 67.50003 0.00032 -8.94570 67.95538 1.33056 -8.94570 67.50003 1.73346 -10.17210 55.44402 1.78841 -10.32127 55.11591 2.47653 -10.61703 55.07125 2.52378 -9.84500 55.75502 2.25541 -9.92569 55.77649 1.97281 -9.98200 55.79823 2.03725 -9.71014 56.53943 2.92432 -9.70494 55.70795 3.46140 -9.51198 55.65247 4.21060 -9.24626 55.70316 1.17244 -10.00303 56.72397 1.38210 -10.00303 56.25980 1.66754 -10.00303 55.83743 3.44294 -10.49866 55.33802 4.04529 -10.02226 55.55492 4.52302 -9.48780 55.75693 + + + + + + + + + + -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.00176 -0.99998 0.00631 -0.05355 -0.99857 0.00043 0.00000 -0.99999 0.00542 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 -0.00095 1.00000 -0.00028 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.04752 0.99190 -0.11780 -0.04460 0.99084 -0.12747 -0.02095 0.99228 -0.12226 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.99978 -0.01466 0.01477 -0.99976 -0.02028 0.00805 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 0.00000 -0.10705 -0.93718 0.33202 0.09366 0.95264 0.28931 0.07028 0.94785 0.31086 0.03296 0.95258 0.30251 0.17105 0.96162 0.21453 0.17056 0.96125 0.21658 0.13733 0.94752 0.28870 0.19414 0.95999 0.20179 0.00016 0.94744 0.31993 -0.03234 0.95249 0.30284 -0.07021 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.13704 0.94751 0.28886 -0.19432 0.95992 0.20196 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 0.29459 -0.64015 0.70952 0.46219 0.52024 0.71814 0.44473 0.03813 0.89485 0.53245 0.40400 0.74383 0.39039 -0.60766 0.69162 0.43016 -0.54482 0.71982 0.60973 0.41632 0.67446 0.45012 -0.62955 0.63329 -0.34004 -0.62630 0.70151 -0.23218 -0.60875 0.75863 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 0.00000 -0.58193 0.81324 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 0.02349 0.38357 0.92321 0.18035 0.44574 0.87681 0.25235 -0.50582 0.82490 0.15528 -0.63718 0.75491 0.28039 0.27890 0.91848 0.30399 0.34310 0.88874 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41725 -0.54080 0.73037 -0.41201 -0.60635 0.68014 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 0.13338 -0.93583 0.32624 0.14454 -0.93969 0.30997 0.14440 -0.93971 0.30999 0.14454 -0.93969 0.30998 -0.14310 -0.93869 0.31366 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 0.04525 -0.90484 0.42333 -0.00555 -0.95073 0.30998 0.07081 -0.93620 0.34427 0.10399 -0.94352 0.31456 -0.39689 0.83488 0.38139 -0.32068 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.00028 0.83866 0.54466 0.01264 0.86767 0.49698 0.11187 0.86176 0.49483 0.10816 0.84369 0.52582 0.17651 0.83818 0.51604 0.25027 0.81275 0.52612 0.23285 0.86496 0.44455 0.33532 0.84040 0.42578 0.32528 0.86091 0.39119 0.18153 0.97480 -0.12965 0.17001 0.97728 -0.12654 0.30431 0.95247 -0.01398 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.69992 0.00000 0.71422 -0.71753 0.00258 0.69653 0.85361 0.22299 0.47076 0.78945 0.37028 0.48956 0.96140 0.25494 0.10351 -0.71327 -0.68531 0.14694 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.99709 0.07281 -0.02245 0.94096 0.33621 -0.03941 0.91811 -0.28358 0.27686 0.71137 -0.33210 0.61940 -0.43505 -0.65824 0.61437 0.17552 -0.92639 0.33316 0.20020 -0.56806 0.79827 -0.36475 -0.92779 0.07852 0.99241 -0.00582 0.12283 -0.36661 -0.92729 0.07565 0.69862 -0.45435 0.55272 0.48679 -0.51345 0.70669 0.93601 -0.05072 0.34830 0.94067 -0.09921 0.32450 0.99852 -0.05405 0.00588 0.96437 -0.18410 0.19000 0.49646 -0.68115 0.53810 0.74849 -0.58760 0.30738 0.33786 -0.80615 0.48576 0.24914 -0.62470 0.74005 -0.38048 -0.92472 -0.01172 -0.40310 -0.90211 0.15396 -0.39572 -0.90000 0.18275 -0.14946 -0.85152 0.50256 0.04364 -0.78466 0.61839 0.33000 -0.71943 0.61116 0.23960 -0.72465 0.64612 0.18329 -0.69229 0.69795 0.12591 -0.54798 0.82696 -0.22862 -0.88332 0.40924 -0.69814 -0.69570 0.16913 0.09772 -0.92104 0.37701 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.45559 -0.25841 0.85186 -0.29317 -0.70441 0.64642 -0.13850 -0.95397 0.26602 0.95828 -0.24461 0.14786 0.81543 -0.57879 -0.00930 0.94100 -0.24772 0.23054 0.44467 -0.88743 0.12142 0.33852 -0.93969 0.04887 0.40618 -0.89006 0.20691 0.61604 -0.70539 0.35059 0.71448 -0.30916 0.62764 -0.06005 -0.94361 0.32556 -0.19340 -0.85881 0.47439 -0.01764 -0.79254 0.60956 0.00853 -0.93684 0.34965 0.65752 -0.32585 0.67933 0.50716 -0.68460 0.52355 0.34776 -0.26959 0.89799 0.21992 -0.66340 0.71522 0.03122 -0.83832 0.54428 -0.31182 -0.70556 0.63636 -0.07666 -0.52074 0.85027 0.04715 -0.24580 0.96817 -0.10883 -0.19107 0.97553 -0.21087 -0.46595 0.85932 -0.28739 -0.53790 0.79251 -0.42242 -0.48538 0.76549 -0.36795 -0.46363 0.80602 -0.53494 -0.16968 0.82768 -0.50295 -0.10159 0.85832 -0.57290 -0.14179 0.80727 -0.57632 -0.14637 0.80401 -0.55630 -0.06916 0.82810 -0.52021 -0.25876 0.81390 0.97128 0.00000 0.23795 0.97128 0.00000 0.23795 0.75129 0.00000 0.65997 0.75129 0.00000 0.65997 0.36119 0.00000 0.93249 0.36113 -0.00000 0.93251 -0.11078 0.00000 0.99385 -0.11087 -0.00000 0.99383 -0.55763 0.00000 0.83009 -0.55763 0.00000 0.83009 -0.72632 0.00000 0.68736 -0.72738 -0.00008 0.68624 -0.69507 0.00038 0.71895 -0.61483 -0.00378 0.78865 -0.65575 -0.02015 0.75471 -0.53890 0.00034 0.84237 -0.48965 -0.00150 0.87192 -0.47159 0.00881 0.88178 -0.48356 -0.00000 0.87531 -0.35592 -0.92787 0.11130 -0.35599 -0.92772 0.11224 -0.34305 -0.92790 0.14600 -0.34306 -0.92762 0.14774 -0.32485 -0.92795 0.18269 -0.32465 -0.92748 0.18544 -0.29985 -0.92803 0.22101 -0.29922 -0.92728 0.22500 -0.26638 -0.92815 0.25995 -0.26496 -0.92700 0.26547 -0.22267 -0.92832 0.29771 -0.21990 -0.92662 0.30498 -0.16727 -0.92857 0.33134 -0.16235 -0.92614 0.34045 0.06866 -0.98340 0.16795 0.05806 -0.98803 0.14291 0.27545 0.96128 -0.00810 0.26631 0.96371 -0.01852 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24571 0.96262 0.11395 0.24710 0.96090 0.12493 0.21475 0.96198 0.16875 0.21458 0.96108 0.17403 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05537 0.18875 0.98134 -0.03660 0.20009 0.97977 0.00241 0.22383 0.97307 -0.05512 0.27743 0.96072 0.00660 0.22710 0.97309 -0.03911 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 0.04752 0.99190 -0.11780 0.85908 -0.41995 0.29260 0.84589 -0.47572 0.24118 0.71256 -0.60512 0.35508 -0.15441 -0.88248 0.44428 -0.33313 -0.82828 0.45053 -0.26799 -0.59574 0.75715 -0.27654 -0.59294 0.75627 0.87478 -0.29895 0.38130 0.92715 -0.25465 0.27484 0.88204 -0.28220 0.37731 0.83044 -0.27944 0.48196 0.81928 -0.22073 0.52920 -0.21381 -0.37604 0.90160 -0.10840 -0.20592 0.97255 -0.55344 -0.12230 0.82386 -0.71334 -0.06060 0.69819 -0.40482 -0.22605 0.88602 0.86783 -0.13547 0.47804 0.84841 -0.13085 0.51291 0.97107 -0.02065 0.23790 0.75105 0.02515 0.65977 0.35731 0.14609 0.92249 0.93755 -0.33787 0.08276 0.36885 -0.86583 0.33807 0.40262 -0.84457 0.35299 0.30818 -0.87862 0.36477 0.79236 -0.48636 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14655 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23107 0.52767 -0.56848 0.63119 0.51463 -0.58326 0.62846 0.69906 0.28926 0.65394 0.69603 0.25858 0.66983 0.73326 0.39301 0.55486 0.51543 -0.63934 0.57059 0.71478 -0.44325 0.54095 0.50370 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04157 0.78420 0.61951 -0.03530 0.75315 0.64246 -0.14144 0.82860 0.54907 -0.10926 0.30521 -0.65708 0.68927 0.27452 -0.77218 0.57305 0.19557 -0.87047 0.45170 0.25684 -0.87163 0.41749 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14388 -0.94000 0.30935 0.14372 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.04527 0.99623 -0.07396 0.21031 0.97181 -0.10652 0.06838 0.99149 -0.11075 0.04277 0.99157 -0.12228 0.04210 0.99151 -0.12305 0.54248 0.83922 -0.03771 0.56738 0.81415 -0.12343 0.43933 0.89793 0.02653 0.44975 0.89314 0.00495 0.41496 0.90361 -0.10632 0.37331 0.92770 0.00370 0.32582 0.93758 -0.12160 0.13224 0.99120 -0.00605 0.99766 0.05944 -0.03376 0.99761 0.05955 -0.03494 0.99974 0.02256 0.00118 1.00000 0.00090 -0.00097 1.00000 0.00074 -0.00099 1.00000 0.00095 -0.00164 -0.00630 -0.99996 0.00607 -0.00914 -0.99996 0.00102 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00745 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 -0.64851 -0.66869 0.36372 -0.78399 -0.56943 0.24719 -0.72894 -0.60836 0.31393 -0.67806 -0.62467 0.38732 -0.62961 -0.61117 0.47965 -0.63130 -0.61327 0.47472 -0.71791 -0.43046 0.54709 -0.63745 -0.38469 0.66759 -0.68092 -0.28192 0.67592 -0.67104 -0.18329 0.71841 -0.57400 -0.07080 0.81579 -0.71726 -0.15742 0.67879 -0.69233 -0.14685 0.70648 -0.55015 -0.62730 0.55121 -0.49917 -0.61019 0.61522 -0.53420 -0.51395 0.67118 -0.66290 -0.37590 0.64750 -0.45505 -0.62819 0.63112 -0.43573 -0.62856 0.64424 -0.31840 -0.67290 0.66770 -0.29656 -0.66599 0.68448 0.40524 0.83720 0.36725 0.40441 0.85374 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24717 0.49012 0.83244 0.25851 0.53337 0.82040 0.20605 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09072 0.58199 0.81145 0.05331 0.58209 0.81139 0.05314 0.58234 0.81175 0.04408 0.63891 0.76804 -0.04376 0.87243 0.48873 0.00135 0.66299 0.74861 -0.00494 0.53559 0.84448 -0.00042 0.46878 0.88331 -0.00031 0.39186 0.92002 -0.00125 0.24879 0.96856 0.00042 0.10852 0.99409 0.00001 -0.56299 0.82624 -0.01940 -0.41875 0.90371 -0.08924 -0.90044 -0.25936 0.34920 -0.93842 -0.11798 0.32473 -0.34308 0.92963 -0.13449 -0.12092 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29116 0.13334 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.24074 -0.72348 0.64701 -0.33159 -0.71777 0.61225 -0.04401 -0.78448 0.61859 0.36127 -0.87020 0.33502 -0.10318 -0.93694 0.33390 -0.30659 -0.65544 0.69022 -0.24901 -0.62075 0.74341 -0.54604 -0.69844 0.46262 -0.46583 -0.68911 0.55510 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71481 -0.55303 -0.49987 0.66655 -0.08363 -0.97549 0.20352 -0.95619 0.27849 0.09024 -0.00001 1.00000 0.00003 0.00000 0.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.77550 -0.62094 0.11414 -0.92389 -0.26237 0.27855 -0.93651 -0.26515 0.22944 -0.45140 -0.88525 0.11212 -0.69107 -0.67926 0.24705 -0.71876 -0.29107 0.63139 -0.43222 -0.89152 0.13554 -0.21391 -0.97644 -0.02847 -0.48193 -0.69947 0.52771 -0.64730 -0.30492 0.69858 -0.20138 -0.87331 0.44359 -0.37961 -0.70148 0.60317 0.11954 -0.91012 0.39673 -0.06955 -0.83809 0.54107 0.00035 -0.95410 0.29950 -0.34751 -0.27251 0.89720 -0.13707 -0.62234 0.77065 -0.28897 -0.27361 0.91741 0.13169 -0.69253 0.70927 0.00840 -0.57544 0.81780 0.26070 -0.59799 0.75792 0.36092 -0.63712 0.68104 0.29526 -0.70457 0.64529 0.10861 -0.19695 0.97438 0.11924 -0.19633 0.97326 0.22611 -0.43020 0.87395 0.48669 -0.26087 0.83372 0.49192 -0.26576 0.82909 0.52427 -0.22855 0.82031 0.53316 -0.23207 0.81356 0.49186 -0.30734 0.81463 0.57602 -0.13819 0.80567 0.54643 -0.07521 0.83412 0.55630 -0.06906 0.82811 0.29316 -0.70443 0.64641 0.41234 -0.30593 0.85813 0.11803 -0.96573 0.23118 -0.97128 0.00000 0.23795 -0.97128 0.00000 0.23795 -0.75129 0.00000 0.65997 -0.75129 0.00000 0.65997 -0.36118 0.00000 0.93249 -0.36118 0.00000 0.93249 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.41672 -0.06071 0.90701 0.44156 -0.03337 0.89661 0.49187 0.00000 0.87067 0.48578 -0.00165 0.87408 0.47157 0.00882 0.88178 0.56683 0.00142 0.82383 0.61482 -0.00663 0.78864 0.63155 -0.00250 0.77533 0.69992 0.00000 0.71422 0.71543 0.00227 0.69868 0.69543 0.00038 0.71859 0.72632 -0.00007 0.68736 0.72758 -0.00000 0.68603 1.00000 0.00000 -0.00000 0.96907 -0.14560 -0.19926 1.00000 -0.00000 0.00000 0.82964 0.00000 0.55829 0.81840 -0.55913 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34240 -0.93149 0.12285 0.41737 -0.90314 0.10069 -0.01779 -0.99870 0.04773 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.21448 0.96105 0.17429 -0.21468 0.96201 0.16869 -0.24706 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05397 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06967 0.99117 -0.11285 -0.06977 0.99156 -0.10925 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50577 -0.84008 0.26127 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08801 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67439 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.70424 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95385 0.19680 0.22679 -0.79602 0.59318 0.12039 0.33004 -0.80724 0.48932 -0.20020 -0.56806 0.79826 -0.19713 -0.77268 0.60342 -0.33899 -0.76788 0.54355 -0.56010 -0.42940 0.70845 -0.93154 -0.30944 0.19098 -0.92038 -0.32295 0.22046 0.55619 -0.07182 0.82795 0.11078 -0.00001 0.99385 -0.35677 0.15627 0.92103 -0.35311 -0.20995 0.91172 -0.74452 -0.13397 0.65402 -0.97123 0.01021 0.23794 -0.94190 -0.02903 0.33465 -0.87579 -0.11927 0.46772 0.43301 -0.20106 0.87868 0.50696 -0.21300 0.83524 -0.81932 -0.22063 0.52919 0.21392 -0.37591 0.90163 -0.83672 -0.33789 0.43096 -0.94486 -0.16420 0.28332 -0.90294 -0.25735 0.34420 -0.82338 -0.40407 0.39846 0.40408 -0.56439 0.71985 0.63619 -0.52427 0.56604 0.42922 -0.54084 0.72337 0.24642 -0.48596 0.83852 0.22831 -0.72646 0.64817 -0.35307 -0.83531 0.42143 0.33802 -0.85130 0.40128 0.52007 -0.78743 0.33089 0.22940 -0.79654 0.55937 -0.81758 -0.52269 0.24158 -0.97082 -0.19733 0.13627 -0.93633 -0.31452 0.15605 -0.89789 -0.41477 0.14750 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02856 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01958 -0.75159 0.65915 0.02529 -0.75611 0.64757 -0.09461 -0.76607 0.62897 -0.13240 -0.76278 0.64443 -0.05370 -0.72711 0.68600 0.02658 -0.73804 0.67155 0.06564 -0.18054 -0.90416 0.38717 -0.19130 -0.89466 0.40372 -0.24234 -0.81604 0.52474 -0.27442 -0.77224 0.57302 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.14037 -0.94027 0.31014 -0.14455 -0.93969 0.30997 -0.14454 -0.93969 0.30997 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.42741 0.90176 -0.06440 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.17579 0.98435 0.01240 -0.18182 0.98314 -0.01917 -0.04278 0.99157 -0.12227 -0.06792 0.99150 -0.11096 -0.06980 0.99114 -0.11304 -0.07001 0.99177 -0.10718 -0.99856 0.04531 0.02872 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00012 0.00067 -1.00000 -0.00130 0.00064 -1.00000 -0.00095 0.00066 0.00674 -0.99997 0.00479 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42688 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.53895 -0.63976 0.54794 0.56237 -0.62219 0.54463 0.54102 -0.54657 0.63919 0.60574 -0.46780 0.64362 0.66422 -0.46943 0.58177 0.68227 -0.49680 0.53638 0.68248 -0.54538 0.48661 0.65312 -0.61971 0.43519 0.60598 -0.47358 0.63915 0.70018 -0.42752 0.57181 0.31773 -0.23430 0.91878 0.65808 -0.28974 0.69497 0.72685 -0.34438 0.59421 0.66513 -0.26599 0.69775 0.74155 -0.38353 0.55046 0.69487 -0.20510 0.68927 0.70755 -0.17462 0.68474 0.69835 -0.06705 0.71261 0.72397 -0.08033 0.68514 0.70425 -0.06136 0.70730 -0.55875 0.82932 -0.00524 -0.62317 0.78191 -0.01634 -0.58167 0.81243 0.04018 -0.58191 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03149 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51068 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40436 0.85353 0.32861 -0.99403 0.10913 0.00067 -0.95025 0.31148 0.00318 -0.87588 0.48253 -0.00146 -0.78707 0.61676 -0.01137 -0.72035 0.69361 -0.00024 -0.54105 0.84089 -0.01294 -0.62317 0.78207 -0.00563 -0.38610 0.92244 -0.00514 -0.21949 0.97561 0.00127 -0.92962 -0.36852 0.00015 -0.81240 -0.58309 0.00262 -0.69791 -0.71618 -0.00011 -0.51123 -0.85944 0.00118 -0.25237 -0.96762 -0.00372 -0.51824 -0.85514 0.01266 0.07105 -0.94250 0.32658 0.13045 -0.90945 0.39482 0.25882 -0.96593 -0.00048 0.12978 -0.99149 -0.01044 0.36620 -0.93054 -0.00105 0.81475 -0.57977 -0.00674 0.99177 -0.12793 0.00409 0.97574 -0.21894 -0.00122 -0.19895 -0.98001 0.00034 -0.97562 -0.21944 0.00338 0.00008 -1.00000 -0.00015 -0.00145 -1.00000 -0.00027 0.00066 -1.00000 -0.00200 0.00017 -1.00000 -0.00165 -0.00015 -1.00000 -0.00148 -0.00046 -1.00000 -0.00140 -0.00520 -0.99999 -0.00079 1.00000 -0.00006 -0.00112 1.00000 0.00062 -0.00147 1.00000 0.00034 -0.00135 1.00000 0.00011 -0.00125 1.00000 0.00000 -0.00121 -1.00000 -0.00068 0.00067 -1.00000 -0.00051 0.00069 -1.00000 -0.00040 0.00070 -1.00000 -0.00030 0.00071 -1.00000 -0.00019 0.00073 -1.00000 -0.00007 0.00075 -1.00000 0.00000 0.00077 -0.99998 0.00586 0.00356 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 0.96584 0.25909 -0.00561 0.70711 0.70710 -0.00224 0.38268 0.92388 -0.00105 0.13052 0.99145 -0.00053 -0.98654 0.16350 -0.00026 -0.89099 0.45398 0.00531 -0.70705 0.70705 0.01263 -0.45399 0.89100 0.00113 -0.14944 0.98877 0.00002 -0.12153 0.99258 -0.00372 0.00005 1.00000 0.00009 -0.00008 1.00000 0.00014 0.00001 1.00000 0.00009 0.00003 1.00000 0.00009 -0.10791 -0.99416 0.00038 -0.31691 -0.94845 0.00451 -0.97382 -0.22730 0.00191 -0.99284 -0.11942 -0.00000 -0.98769 0.15643 0.00000 -0.99144 0.13053 0.00060 -0.92388 0.38269 -0.00040 -0.89101 0.45399 0.00080 -0.79335 0.60876 -0.00060 -0.70711 0.70711 0.00090 -0.60876 0.79334 0.00414 -0.52998 0.84801 -0.00169 -0.45399 0.89101 -0.00027 -0.38268 0.92388 0.00096 -0.40791 0.91302 0.00232 -0.40924 0.91243 -0.00123 -0.13052 0.99144 0.00215 -0.15956 0.98719 -0.00035 -0.15922 0.98724 0.00045 0.37033 -0.89191 -0.25953 0.00098 1.00000 -0.00054 -0.98113 -0.18864 -0.04232 -0.99277 -0.11941 -0.01238 -0.68242 0.51015 -0.52350 -0.44507 0.60140 -0.66350 0.81915 -0.00004 -0.57358 0.00000 1.00000 0.00000 -0.89260 0.25436 -0.37225 -0.88341 0.27950 -0.37611 0.49406 -0.00002 -0.86943 0.42708 -0.00424 -0.90420 -0.29256 0.00148 -0.95625 0.81913 -0.00002 -0.57360 0.82204 -0.00859 -0.56936 0.82157 -0.00716 -0.57007 0.81518 0.00991 -0.57913 0.81931 0.00004 -0.57336 0.82167 -0.00528 -0.56993 0.81915 -0.00004 -0.57358 -0.92960 -0.36850 -0.00774 -0.84092 -0.53145 -0.10206 -0.70109 -0.71172 -0.04381 -0.00074 -1.00000 0.00052 0.23448 -0.59158 -0.77140 -0.35251 -0.22831 -0.90753 0.40533 -0.59696 -0.69235 0.38686 -0.56948 -0.72528 -0.28541 -0.23270 -0.92973 -0.30811 -0.28670 -0.90712 -0.25807 -0.31078 -0.91478 0.23525 -0.64984 -0.72275 0.30826 -0.64722 -0.69719 -0.33916 -0.29520 -0.89321 0.26361 -0.72845 -0.63235 -0.34827 -0.31462 -0.88302 -0.40242 -0.27333 -0.87370 0.32573 -0.81630 -0.47702 0.00721 -0.75190 -0.65924 0.16630 -0.77478 -0.60997 -0.31407 -0.31597 -0.89528 0.82540 -0.16065 -0.54120 0.79464 -0.32812 -0.51076 0.77099 -0.39996 -0.49559 0.60058 -0.67981 -0.42091 0.72838 -0.49440 -0.47437 0.64605 -0.61357 -0.45403 0.65462 -0.60045 -0.45927 0.58106 -0.70428 -0.40787 0.58346 -0.70151 -0.40922 0.60853 -0.66981 -0.42550 0.51098 -0.78302 -0.35464 0.46760 -0.81941 -0.33155 0.49779 -0.79333 -0.35047 0.43495 -0.84709 -0.30538 0.42888 -0.85146 -0.30179 0.36001 -0.89790 -0.25331 0.36052 -0.89760 -0.25364 -0.13026 0.98946 -0.06326 -0.38403 0.91131 -0.14844 -0.42556 0.83775 -0.34216 -0.45938 0.83469 -0.30375 -0.38307 0.91172 -0.14841 -0.37824 0.91316 -0.15189 -0.60660 0.79054 -0.08417 -0.69472 0.66867 -0.26503 -0.76483 0.61785 -0.18246 -0.76449 0.63286 -0.12264 -0.78977 0.60602 -0.09486 -0.92329 0.38244 -0.03562 -0.90867 0.37797 -0.17734 -0.97318 0.23000 -0.00456 -0.96591 0.25380 -0.05104 -0.97307 0.21210 -0.09028 -0.99122 0.13050 -0.02145 -0.70695 0.56381 -0.42702 -0.88221 0.28161 -0.37735 -0.92446 0.21947 -0.31178 -0.94149 0.01783 -0.33658 -0.96942 -0.00771 -0.24528 -0.97782 -0.00116 -0.20946 -0.97851 -0.01931 -0.20530 -0.99457 -0.02576 -0.10085 -0.05971 0.99471 -0.08363 -0.07485 0.99005 -0.11918 -0.15231 0.96177 -0.22760 -0.18020 0.95116 -0.25065 -0.28594 0.87859 -0.38251 -0.26602 0.89107 -0.36773 -0.38894 0.75596 -0.52654 -0.33059 0.80936 -0.48543 -0.53530 0.65496 -0.53336 -0.57355 -0.00001 -0.81917 -0.57355 0.00000 -0.81917 -0.55955 -0.00849 -0.82876 -0.62174 0.01656 -0.78305 -0.57358 0.00002 -0.81915 -0.57360 0.00003 -0.81914 -0.57360 0.00003 -0.81914 -0.57361 0.00003 -0.81913 -0.52031 -0.00711 -0.85395 -1.00000 -0.00000 -0.00223 -0.99996 -0.00095 -0.00884 -0.99998 -0.00024 -0.00552 -0.99598 -0.01129 0.08891 0.00057 1.00000 -0.00000 -0.00228 0.99987 -0.01593 -0.07763 0.87274 0.48198 0.05892 0.74278 0.66694 0.04719 0.89564 0.44227 0.10086 0.90505 0.41316 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.25760 -0.96137 0.09704 0.13120 -0.93972 0.31577 0.04226 -0.93526 0.35142 0.03103 -0.89988 0.43502 -0.02004 -0.89145 0.45267 -0.01268 -0.79648 0.60453 0.08486 -0.99137 0.09990 0.08283 -0.99435 0.06644 0.06829 -0.99699 0.03660 0.17929 -0.98230 0.05425 0.15184 -0.98830 0.01422 0.16981 -0.97088 0.16900 0.30391 -0.91882 0.25181 0.55978 -0.82095 0.11264 0.42611 -0.82389 0.37368 0.44032 -0.78817 0.43001 0.61730 -0.77025 0.16016 0.60282 -0.59761 0.52865 0.83115 -0.53706 0.14408 0.61171 -0.54071 0.57745 0.70854 -0.37183 0.59976 0.88759 -0.39311 0.24008 0.96594 -0.16830 0.19658 0.73646 -0.16028 0.65721 0.71034 -0.10516 0.69595 0.96593 -0.07592 0.24741 0.62613 -0.77970 0.00506 0.51327 -0.85821 -0.00546 0.91370 -0.40629 0.00889 0.02994 -0.99864 0.04276 0.07669 -0.99144 0.10564 0.11288 -0.97847 0.17280 0.21741 -0.92388 0.31494 0.22797 -0.91421 0.33503 0.40596 -0.69438 0.59416 0.34757 -0.79335 0.49980 0.35373 -0.78295 0.51173 0.43178 -0.66299 0.61156 0.45135 -0.60876 0.65245 0.40363 -0.69507 0.59495 0.48671 -0.38216 0.78553 0.54652 -0.10777 0.83048 0.56817 -0.12870 0.81278 0.54675 -0.05619 0.83540 0.00103 -1.00000 0.00158 0.00067 -1.00000 -0.00027 0.00098 -1.00000 -0.00049 -0.00221 -0.99999 -0.00437 -0.00044 -1.00000 -0.00063 -0.00040 -1.00000 0.00070 -0.00216 -1.00000 -0.00138 -0.00087 -1.00000 0.00045 -0.00303 -0.99999 -0.00243 -0.00144 -1.00000 -0.00039 -0.00050 -1.00000 -0.00058 -0.00038 -1.00000 0.00071 -0.00137 -1.00000 -0.00013 -0.57359 -0.00000 -0.81914 -0.57357 -0.00000 -0.81916 -0.57357 -0.00000 -0.81916 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.00000 1.00000 -0.00000 0.06694 0.99492 -0.07524 0.24246 0.95843 -0.15039 0.23151 0.95688 -0.17544 0.17121 0.98056 -0.09584 0.39040 0.88190 -0.26428 0.38192 0.88932 -0.25148 0.48635 0.81409 -0.31738 0.51694 0.77300 -0.36775 0.61812 0.66370 -0.42123 0.63075 0.63439 -0.44688 0.71337 0.50257 -0.48840 0.72019 0.47140 -0.50903 0.78063 0.32131 -0.53607 0.78190 0.29028 -0.55170 0.81714 0.12730 -0.56221 0.81350 0.09802 -0.57324 0.82144 -0.07136 -0.56582 0.81370 -0.09802 -0.57296 0.79323 -0.26778 -0.54689 0.78263 -0.29028 -0.55066 0.73369 -0.45354 -0.50596 0.72148 -0.47140 -0.50720 0.64526 -0.62114 -0.44477 0.63257 -0.63439 -0.44430 0.53121 -0.76425 -0.36570 0.51937 -0.77301 -0.36429 0.39639 -0.87686 -0.27201 0.38619 -0.88192 -0.27031 0.24582 -0.95475 -0.16741 0.23819 -0.95694 -0.16594 0.08548 -0.99477 -0.05598 0.08108 -0.99518 -0.05510 -0.14935 0.89987 0.40979 -0.13015 0.97172 0.19701 -0.09726 0.98250 0.15886 -0.09873 0.98486 0.14250 -0.08999 0.99075 0.10155 -0.03883 0.99896 0.02385 0.03687 0.99931 -0.00474 0.05550 0.99770 -0.03893 0.01173 0.99979 0.01688 0.23355 0.95869 -0.16240 0.18854 0.97179 -0.14172 0.16191 0.98079 -0.10882 0.35127 0.90345 -0.24572 0.36632 0.88898 -0.27481 0.46754 0.81415 -0.34434 0.49388 0.79724 -0.34713 0.61070 0.66373 -0.43187 0.61715 0.65761 -0.43206 0.70548 0.50258 -0.49971 0.71457 0.49044 -0.49886 0.77241 0.32132 -0.54785 0.78202 0.30272 -0.54480 0.80861 0.12730 -0.57441 0.81670 0.10234 -0.56791 0.81264 -0.07137 -0.57838 0.81730 -0.10234 -0.56705 0.78441 -0.26777 -0.55946 0.78369 -0.30272 -0.54240 0.72482 -0.45354 -0.51859 0.71729 -0.49043 -0.49495 0.63633 -0.62112 -0.45748 0.62095 -0.65760 -0.42660 0.52230 -0.76422 -0.37837 0.49869 -0.79721 -0.34025 0.38748 -0.87682 -0.28469 0.35568 -0.90343 -0.23941 0.23703 -0.95469 -0.17993 0.19793 -0.97178 -0.12832 0.08168 -0.99476 -0.06143 0.06945 -0.99549 -0.06460 0.03687 -0.99931 -0.00474 -0.02038 -0.99965 0.01689 -0.13752 -0.98521 0.10219 0.00487 -0.99324 0.11598 -0.16707 -0.97616 0.13853 -0.22747 -0.92240 0.31215 -0.25824 -0.94013 0.22241 0.77548 0.02612 0.63083 0.71506 0.16814 0.67854 0.95542 0.16167 0.24707 0.93441 0.20972 0.28792 0.70854 0.37183 0.59976 0.82388 0.54071 0.16987 0.63066 0.54442 0.55307 0.56626 0.60266 0.56228 0.46606 0.78469 0.40872 0.41334 0.82095 0.39394 0.48143 0.83122 0.27801 0.70234 0.70234 0.11594 0.30391 0.91882 0.25181 0.38059 0.91882 0.10452 0.23278 0.97167 0.04086 0.14850 0.98212 0.11574 0.09872 0.98831 0.11621 0.07303 0.99144 0.10820 0.13051 0.99137 0.01223 0.10190 0.99435 0.02976 0.06995 0.99694 0.03481 0.07486 0.99145 0.10692 0.05303 0.99537 0.08011 0.18269 0.94743 0.26268 0.21651 0.92387 0.31556 0.24459 0.90391 0.35090 0.30156 0.85080 0.43035 0.34454 0.79333 0.50191 0.39368 0.72816 0.56107 0.41816 0.68612 0.59531 0.44741 0.60874 0.65518 0.52226 0.42592 0.73881 0.52992 0.38268 0.75680 0.53767 0.35896 0.76293 0.55113 0.13367 0.82364 0.57213 0.02920 0.81964 0.96868 0.00079 0.24831 0.96805 0.00059 0.25074 0.74639 -0.00065 0.66551 0.77578 0.00322 0.63100 0.57358 -0.00001 0.81915 0.57358 0.00000 0.81915 0.57357 -0.00016 0.81915 0.57356 -0.00002 0.81916 0.57325 -0.01084 0.81931 0.57280 -0.00126 0.81970 0.57330 0.02735 0.81889 0.57358 -0.00000 0.81915 0.57239 0.00009 0.81998 0.57351 -0.00008 0.81920 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57352 -0.00011 0.81919 0.57358 0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57295 0.00805 0.81955 0.57358 0.00569 0.81913 0.57238 0.00193 0.81999 0.57452 -0.03601 0.81769 0.57257 0.02864 0.81936 0.57358 -0.00000 0.81915 0.57358 0.00000 0.81915 0.57358 0.00001 0.81915 0.57358 0.00002 0.81915 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00049 1.00000 0.00086 0.00078 1.00000 -0.00098 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.42643 -0.00127 0.90452 0.45581 -0.00052 0.89008 0.35546 0.00008 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37466 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00251 0.92737 -0.42805 -0.01025 0.90370 -0.45567 -0.02415 0.88982 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 0.00000 -0.00005 1.00000 -0.00013 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -0.32753 -0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90969 0.63033 -0.00000 0.77633 0.63036 0.00000 0.77631 0.80504 -0.00000 0.59322 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37169 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07959 0.00000 0.99683 0.07959 0.00000 0.99683 -0.17359 0.00000 0.98482 -0.17359 0.00000 0.98482 -0.41529 0.00000 0.90969 -0.41529 0.00000 0.90969 -0.63033 0.00000 0.77633 -0.63033 0.00000 0.77633 -0.80504 0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 -0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32894 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39517 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35199 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39126 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85625 0.38631 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12334 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81900 -0.17246 -0.19506 0.98057 0.02092 -0.54306 0.83970 0.00048 -0.55558 0.83146 -0.00032 -0.82644 0.56302 0.00033 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 -0.98020 0.19803 0.00000 -0.98037 0.19531 0.02684 -0.00000 1.00000 0.00000 0.48300 0.87548 -0.01569 0.19509 0.98078 0.00289 0.55273 0.83336 -0.00014 0.55557 0.83147 -0.00032 0.82644 0.56303 0.00033 0.83147 0.55557 -0.00016 0.98001 0.19894 0.00016 0.98079 0.19509 -0.00005 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15934 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30814 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26659 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37311 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18797 0.97320 0.19358 0.12413 0.98077 -0.19509 0.00479 0.96592 -0.25883 -0.00000 0.83147 -0.55557 -0.00242 0.70708 -0.70712 0.00482 0.55557 -0.83147 -0.00242 0.25880 -0.96592 0.00361 0.19509 -0.98079 0.00000 -0.19508 -0.98077 0.00479 -0.25882 -0.96593 0.00000 -0.55557 -0.83147 -0.00242 -0.70710 -0.70710 0.00483 -0.83147 -0.55557 -0.00242 -0.96592 -0.25882 0.00361 -0.98078 -0.19509 0.00000 0.32738 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23701 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86547 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54635 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29876 -0.95399 0.02541 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18796 -0.97320 -0.19358 0.12413 0.47154 -0.01436 0.88173 0.14306 -0.95333 0.26588 0.33917 -0.38521 0.85824 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03997 -0.73162 0.68054 0.01607 -0.98803 0.15344 -0.03998 -0.73156 0.68061 -0.01608 -0.98803 0.15344 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.53936 0.83398 0.11644 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06987 -0.98282 0.18451 -0.00431 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85101 0.52047 0.06988 0.98001 0.19894 -0.00123 -0.38262 0.92383 0.01196 -0.60550 0.79206 -0.07758 -0.98242 0.18315 0.03618 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86396 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92864 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48079 0.35273 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78086 0.11745 0.43570 0.89717 -0.07251 0.98234 0.18358 0.03605 0.84345 0.53138 -0.07891 0.60508 0.79038 0.09581 0.08395 -0.47203 0.87758 0.07372 -0.31442 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39305 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.46536 -0.69804 0.54423 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.47838 0.87812 -0.00723 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18887 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18766 0.98224 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 0.00000 1.00000 0.00000 -0.19510 0.98078 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02737 -0.96449 -0.25844 -0.05450 -0.69955 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66579 0.40977 0.96449 -0.25844 -0.05450 0.69954 -0.69957 0.14577 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18765 0.98223 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18887 -0.67100 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92407 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19358 0.12407 0.81662 -0.54565 -0.18814 0.90235 -0.34994 0.25160 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02538 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54655 0.32005 -0.92238 0.21629 0.34529 -0.86547 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68809 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.18723 0.98232 -0.00049 -0.25882 -0.96593 -0.00000 -0.67986 -0.71506 0.16275 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 -0.99707 0.00000 -0.07645 -0.99777 0.00475 -0.06651 0.83570 0.00000 0.54918 0.83570 0.00000 0.54918 0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 -0.32386 -0.00000 0.94611 -0.32386 -0.00000 0.94611 -0.83570 0.00000 0.54918 -0.83570 -0.00000 0.54918 0.99781 0.00000 -0.06609 0.99780 -0.00013 -0.06633 -0.00012 1.00000 0.00012 -0.00002 1.00000 0.00014 -0.00005 1.00000 0.00014 0.03620 -0.94022 0.33864 0.10266 -0.94500 0.31053 0.12277 -0.94865 0.29153 0.11094 -0.94337 0.31263 -0.03620 -0.94022 0.33864 -0.10286 -0.94501 0.31044 -0.12261 -0.94859 0.29179 -0.11094 -0.94337 0.31265 0.00000 1.00000 0.00000 0.01046 0.99992 0.00670 -0.00053 1.00000 0.00160 -0.00018 1.00000 0.00167 0.00018 1.00000 0.00167 0.00052 1.00000 0.00160 -0.01046 0.99992 0.00670 0.00000 1.00000 0.00000 + + + + + + + + + + + + + + +

10 0 11 0 12 0 13 1 11 1 10 1 16 2 15 2 14 2 14 3 17 3 16 3 9 4 17 4 14 4 1 5 0 5 20 5 20 6 21 6 1 6 2 7 1 7 21 7 22 8 3 8 2 8 21 9 22 9 2 9 24 10 25 10 26 10 27 11 26 11 25 11 28 12 27 12 25 12 25 13 24 13 29 13 29 14 30 14 25 14 30 15 31 15 25 15 30 16 29 16 19 16 20 17 19 17 29 17 29 18 24 18 20 18 21 19 20 19 24 19 22 20 21 20 24 20 24 21 26 21 22 21 23 22 22 22 26 22 13 23 16 23 11 23 15 24 16 24 13 24 12 25 11 25 17 25 16 26 17 26 11 26 12 27 17 27 9 27 33 28 9 28 18 28 33 29 18 29 8 29 33 30 8 30 7 30 33 31 7 31 6 31 33 32 6 32 4 32 33 33 4 33 5 33 32 34 33 34 5 34 25 35 60 35 61 35 51 36 14 36 48 36 84 37 37 37 34 37 84 38 34 38 81 38 81 39 34 39 38 39 60 40 36 40 88 40 86 41 88 41 36 41 84 42 86 42 37 42 86 43 36 43 37 43 79 44 81 44 38 44 38 45 39 45 79 45 77 46 79 46 39 46 39 47 40 47 77 47 74 48 77 48 40 48 40 49 58 49 74 49 72 50 74 50 58 50 58 51 59 51 72 51 53 52 44 52 69 52 41 53 83 53 44 53 41 54 85 54 83 54 41 55 87 55 85 55 41 56 44 56 56 56 44 57 53 57 56 57 89 58 87 58 41 58 56 59 57 59 41 59 63 60 46 60 62 60 42 61 46 61 66 61 46 62 63 62 66 62 42 63 75 63 46 63 42 64 76 64 75 64 42 65 78 65 76 65 43 66 42 66 67 66 42 67 66 67 67 67 42 68 43 68 78 68 43 69 80 69 78 69 82 70 80 70 43 70 43 71 69 71 44 71 43 72 67 72 69 72 43 73 44 73 82 73 44 74 83 74 82 74 49 75 50 75 45 75 71 76 70 76 45 76 45 77 46 77 71 77 46 78 73 78 71 78 46 79 75 79 73 79 45 80 62 80 46 80 45 81 50 81 62 81 35 82 47 82 62 82 62 83 50 83 35 83 50 84 48 84 35 84 50 85 51 85 48 85 53 86 69 86 52 86 56 87 53 87 54 87 53 88 52 88 54 88 54 89 55 89 56 89 63 90 62 90 47 90 47 91 64 91 63 91 66 92 63 92 64 92 64 93 65 93 66 93 65 94 68 94 66 94 68 95 67 95 66 95 69 96 67 96 68 96 68 97 52 97 69 97 70 98 71 98 72 98 74 99 72 99 73 99 72 100 71 100 73 100 73 101 75 101 74 101 77 102 74 102 75 102 75 103 76 103 77 103 79 104 77 104 78 104 77 105 76 105 78 105 81 106 79 106 80 106 79 107 78 107 80 107 84 108 81 108 82 108 81 109 80 109 82 109 82 110 83 110 84 110 86 111 84 111 85 111 84 112 83 112 85 112 88 113 86 113 87 113 86 114 85 114 87 114 168 115 167 115 166 115 223 116 168 116 166 116 223 117 166 117 222 117 25 118 157 118 158 118 25 119 61 119 157 119 198 120 33 120 197 120 197 121 33 121 117 121 210 122 140 122 141 122 210 123 209 123 140 123 144 124 142 124 138 124 90 125 188 125 135 125 154 126 156 126 155 126 148 127 156 127 154 127 91 128 143 128 92 128 91 129 144 129 143 129 137 130 92 130 95 130 93 131 137 131 95 131 137 132 135 132 136 132 94 133 135 133 137 133 137 134 93 134 94 134 188 135 180 135 181 135 143 136 95 136 92 136 188 137 90 137 180 137 93 138 95 138 97 138 93 139 97 139 147 139 143 140 97 140 95 140 143 141 144 141 97 141 144 142 138 142 97 142 138 143 96 143 97 143 147 144 97 144 96 144 147 145 96 145 98 145 147 146 98 146 148 146 145 147 93 147 147 147 90 148 99 148 180 148 180 149 99 149 179 149 179 150 99 150 178 150 178 151 99 151 153 151 153 152 99 152 154 152 146 153 154 153 99 153 145 154 146 154 99 154 145 155 99 155 93 155 93 156 99 156 94 156 135 157 94 157 99 157 99 158 90 158 135 158 55 159 14 159 149 159 33 160 12 160 9 160 33 161 10 161 12 161 33 162 206 162 10 162 33 163 204 163 206 163 33 164 200 164 204 164 33 165 202 165 200 165 33 166 198 166 202 166 121 167 123 167 110 167 110 168 100 168 104 168 100 169 128 169 104 169 101 170 127 170 177 170 126 171 127 171 101 171 177 172 111 172 101 172 102 173 125 173 126 173 125 174 102 174 124 174 126 175 103 175 102 175 103 176 126 176 101 176 111 177 112 177 101 177 128 178 124 178 102 178 102 179 107 179 128 179 107 180 102 180 103 180 104 181 128 181 107 181 105 182 101 182 112 182 101 183 105 183 103 183 112 184 113 184 105 184 106 185 103 185 105 185 103 186 106 186 107 186 110 187 104 187 107 187 105 188 108 188 106 188 108 189 105 189 113 189 113 190 114 190 108 190 109 191 106 191 108 191 106 192 109 192 107 192 107 193 118 193 110 193 118 194 107 194 109 194 108 195 116 195 109 195 116 196 108 196 114 196 117 197 109 197 116 197 109 198 117 198 118 198 114 199 115 199 116 199 121 200 110 200 118 200 176 201 133 201 177 201 111 202 177 202 133 202 133 203 134 203 111 203 112 204 111 204 134 204 134 205 130 205 112 205 113 206 112 206 130 206 130 207 131 207 113 207 114 208 113 208 131 208 131 209 196 209 114 209 115 210 114 210 196 210 196 211 197 211 115 211 197 212 116 212 115 212 117 213 116 213 197 213 33 214 119 214 117 214 119 215 118 215 117 215 121 216 118 216 119 216 120 217 121 217 119 217 123 218 121 218 122 218 121 219 120 219 122 219 181 220 182 220 188 220 190 221 188 221 182 221 182 222 183 222 190 222 191 223 190 223 183 223 183 224 184 224 191 224 192 225 191 225 184 225 184 226 185 226 192 226 199 227 192 227 185 227 185 228 186 228 199 228 203 229 199 229 186 229 186 230 187 230 203 230 205 231 203 231 187 231 187 232 15 232 205 232 13 233 205 233 15 233 14 234 153 234 149 234 178 235 153 235 14 235 158 236 215 236 163 236 158 237 216 237 215 237 213 238 216 238 158 238 158 239 157 239 213 239 211 240 213 240 157 240 157 241 61 241 211 241 208 242 211 242 61 242 61 243 60 243 208 243 88 244 208 244 60 244 159 245 167 245 28 245 166 246 167 246 159 246 159 247 160 247 166 247 160 248 161 248 166 248 161 249 165 249 166 249 164 250 165 250 161 250 161 251 162 251 164 251 164 252 163 252 215 252 164 253 162 253 163 253 23 254 28 254 167 254 23 255 27 255 28 255 26 256 27 256 23 256 169 257 92 257 136 257 129 258 169 258 136 258 129 259 170 259 169 259 129 260 136 260 189 260 136 261 135 261 189 261 189 262 193 262 129 262 132 263 129 263 193 263 129 264 132 264 170 264 132 265 171 265 170 265 132 266 172 266 171 266 132 267 173 267 172 267 174 268 173 268 132 268 193 269 194 269 132 269 132 270 131 270 130 270 132 271 196 271 131 271 132 272 195 272 196 272 132 273 194 273 195 273 132 274 130 274 174 274 130 275 175 275 174 275 176 276 175 276 133 276 175 277 134 277 133 277 175 278 130 278 134 278 137 279 136 279 92 279 98 280 156 280 148 280 98 281 139 281 156 281 139 282 155 282 156 282 141 283 139 283 98 283 98 284 96 284 141 284 96 285 138 285 141 285 214 286 141 286 138 286 138 287 142 287 214 287 140 288 41 288 150 288 41 289 57 289 150 289 41 290 140 290 89 290 140 291 207 291 89 291 209 292 207 292 140 292 150 293 151 293 140 293 140 294 139 294 141 294 140 295 155 295 139 295 140 296 152 296 155 296 140 297 151 297 152 297 141 298 212 298 210 298 212 299 141 299 214 299 214 300 142 300 217 300 218 301 217 301 144 301 217 302 142 302 144 302 144 303 91 303 218 303 146 304 145 304 147 304 154 305 146 305 147 305 147 306 148 306 154 306 149 307 153 307 55 307 153 308 56 308 55 308 153 309 57 309 56 309 153 310 150 310 57 310 153 311 151 311 150 311 153 312 152 312 151 312 153 313 155 313 152 313 155 314 153 314 154 314 158 315 163 315 25 315 25 316 159 316 28 316 25 317 160 317 159 317 25 318 161 318 160 318 25 319 162 319 161 319 25 320 163 320 162 320 224 321 225 321 168 321 225 322 167 322 168 322 225 323 23 323 167 323 22 324 23 324 225 324 225 325 3 325 22 325 219 326 215 326 216 326 164 327 215 327 219 327 219 328 220 328 164 328 220 329 221 329 164 329 165 330 164 330 221 330 221 331 222 331 165 331 165 332 222 332 166 332 223 333 224 333 168 333 92 334 169 334 91 334 91 335 169 335 170 335 91 336 170 336 230 336 170 337 171 337 230 337 171 338 172 338 230 338 172 339 173 339 226 339 14 340 179 340 178 340 14 341 180 341 179 341 14 342 181 342 180 342 14 343 182 343 181 343 14 344 183 344 182 344 14 345 184 345 183 345 14 346 185 346 184 346 14 347 186 347 185 347 14 348 187 348 186 348 14 349 15 349 187 349 189 350 135 350 188 350 188 351 190 351 189 351 190 352 191 352 189 352 191 353 192 353 189 353 201 354 189 354 199 354 189 355 192 355 199 355 189 356 201 356 193 356 202 357 193 357 201 357 193 358 202 358 194 358 202 359 195 359 194 359 202 360 196 360 195 360 202 361 197 361 196 361 202 362 198 362 197 362 199 363 203 363 201 363 204 364 201 364 203 364 201 365 204 365 200 365 200 366 202 366 201 366 203 367 205 367 204 367 206 368 204 368 205 368 205 369 13 369 206 369 10 370 206 370 13 370 87 371 89 371 88 371 208 372 88 372 89 372 89 373 207 373 208 373 211 374 208 374 209 374 208 375 207 375 209 375 209 376 210 376 211 376 213 377 211 377 212 377 211 378 210 378 212 378 212 379 214 379 213 379 216 380 213 380 214 380 214 381 217 381 216 381 216 382 217 382 219 382 217 383 218 383 219 383 227 384 218 384 91 384 219 385 218 385 227 385 228 386 220 386 219 386 221 387 220 387 228 387 229 388 222 388 221 388 223 389 222 389 229 389 223 390 231 390 224 390 366 391 364 391 348 391 366 392 348 392 308 392 314 393 274 393 273 393 314 394 273 394 313 394 312 395 310 395 309 395 311 396 312 396 309 396 286 397 272 397 269 397 286 398 285 398 272 398 330 399 232 399 287 399 287 400 232 400 292 400 292 401 232 401 293 401 293 402 232 402 291 402 291 403 232 403 289 403 289 404 232 404 294 404 294 405 232 405 327 405 298 406 289 406 294 406 293 407 291 407 290 407 293 408 290 408 292 408 296 409 271 409 288 409 290 410 288 410 271 410 290 411 271 411 270 411 272 412 270 412 271 412 313 413 270 413 272 413 284 414 313 414 272 414 313 415 273 415 270 415 292 416 290 416 270 416 292 417 270 417 273 417 294 418 14 418 51 418 272 419 285 419 284 419 279 420 277 420 276 420 347 421 344 421 340 421 32 422 252 422 251 422 32 423 259 423 252 423 233 424 372 424 371 424 372 425 233 425 326 425 247 426 326 426 233 426 234 427 371 427 370 427 371 428 234 428 233 428 248 429 247 429 233 429 370 430 235 430 234 430 370 431 236 431 235 431 237 432 233 432 234 432 233 433 237 433 248 433 238 434 234 434 235 434 234 435 238 435 237 435 239 436 235 436 236 436 235 437 239 437 238 437 236 438 246 438 239 438 249 439 248 439 237 439 240 440 237 440 238 440 237 441 240 441 249 441 241 442 238 442 239 442 238 443 241 443 240 443 239 444 242 444 241 444 242 445 239 445 246 445 246 446 243 446 242 446 250 447 249 447 240 447 240 448 244 448 250 448 244 449 240 449 241 449 241 450 261 450 244 450 261 451 241 451 242 451 242 452 260 452 261 452 260 453 242 453 243 453 243 454 258 454 260 454 262 455 244 455 261 455 244 456 262 456 250 456 263 457 250 457 262 457 246 458 245 458 243 458 245 459 258 459 243 459 236 460 264 460 246 460 326 461 247 461 325 461 278 462 325 462 247 462 247 463 248 463 278 463 277 464 278 464 248 464 248 465 249 465 277 465 276 466 277 466 249 466 249 467 250 467 276 467 275 468 276 468 250 468 250 469 263 469 275 469 346 470 275 470 263 470 259 471 254 471 253 471 259 472 255 472 254 472 259 473 256 473 255 473 259 474 258 474 256 474 258 475 257 475 256 475 260 476 258 476 259 476 259 477 32 477 260 477 32 478 261 478 260 478 5 479 345 479 32 479 345 480 261 480 32 480 262 481 261 481 345 481 345 482 346 482 262 482 346 483 263 483 262 483 328 484 334 484 18 484 18 485 335 485 8 485 18 486 334 486 335 486 265 487 334 487 328 487 266 488 265 488 328 488 333 489 265 489 266 489 332 490 333 490 266 490 331 491 332 491 266 491 266 492 327 492 331 492 232 493 331 493 327 493 14 494 294 494 327 494 303 495 348 495 302 495 308 496 348 496 303 496 303 497 304 497 308 497 307 498 308 498 304 498 304 499 305 499 307 499 305 500 309 500 307 500 305 501 306 501 309 501 311 502 309 502 306 502 31 503 311 503 306 503 358 504 72 504 59 504 59 505 299 505 358 505 356 506 358 506 299 506 299 507 300 507 356 507 353 508 356 508 300 508 300 509 301 509 353 509 351 510 353 510 301 510 301 511 302 511 351 511 351 512 302 512 348 512 19 513 311 513 30 513 30 514 311 514 31 514 297 515 295 515 268 515 267 516 268 516 295 516 267 517 269 517 268 517 267 518 352 518 269 518 267 519 354 519 352 519 267 520 355 520 354 520 357 521 355 521 267 521 45 522 267 522 49 522 267 523 295 523 49 523 267 524 45 524 357 524 45 525 70 525 357 525 268 526 296 526 297 526 271 527 296 527 268 527 272 528 271 528 268 528 268 529 269 529 272 529 352 530 286 530 269 530 281 531 330 531 287 531 274 532 287 532 292 532 287 533 274 533 281 533 274 534 283 534 281 534 292 535 273 535 274 535 274 536 314 536 283 536 283 537 314 537 315 537 346 538 347 538 275 538 347 539 276 539 275 539 347 540 279 540 276 540 279 541 280 541 277 541 280 542 278 542 277 542 280 543 325 543 278 543 280 544 324 544 325 544 280 545 323 545 324 545 280 546 279 546 340 546 279 547 347 547 340 547 322 548 323 548 280 548 340 549 341 549 280 549 280 550 282 550 322 550 282 551 321 551 322 551 282 552 320 552 321 552 282 553 319 553 320 553 282 554 280 554 336 554 280 555 339 555 336 555 280 556 342 556 339 556 280 557 341 557 342 557 336 558 337 558 282 558 283 559 282 559 281 559 282 560 330 560 281 560 282 561 329 561 330 561 282 562 337 562 329 562 282 563 283 563 319 563 283 564 318 564 319 564 283 565 317 565 318 565 283 566 315 566 317 566 359 567 316 567 360 567 361 568 360 568 316 568 361 569 313 569 284 569 361 570 316 570 313 570 284 571 362 571 361 571 284 572 363 572 362 572 284 573 365 573 363 573 350 574 365 574 285 574 365 575 284 575 285 575 285 576 286 576 350 576 349 577 350 577 286 577 286 578 352 578 349 578 296 579 288 579 298 579 289 580 298 580 288 580 288 581 290 581 289 581 291 582 289 582 290 582 294 583 51 583 295 583 51 584 49 584 295 584 51 585 50 585 49 585 294 586 295 586 298 586 295 587 297 587 298 587 296 588 298 588 297 588 59 589 25 589 299 589 25 590 300 590 299 590 25 591 301 591 300 591 302 592 301 592 25 592 25 593 303 593 302 593 25 594 304 594 303 594 25 595 305 595 304 595 25 596 306 596 305 596 25 597 31 597 306 597 310 598 308 598 307 598 307 599 309 599 310 599 308 600 310 600 366 600 367 601 366 601 310 601 367 602 310 602 312 602 368 603 367 603 312 603 369 604 368 604 312 604 20 605 0 605 19 605 0 606 369 606 19 606 311 607 19 607 312 607 19 608 369 608 312 608 316 609 314 609 313 609 316 610 315 610 314 610 316 611 359 611 315 611 359 612 317 612 315 612 359 613 377 613 317 613 377 614 318 614 317 614 377 615 319 615 318 615 14 616 327 616 9 616 327 617 266 617 9 617 266 618 328 618 9 618 18 619 9 619 328 619 330 620 331 620 232 620 331 621 330 621 329 621 331 622 329 622 332 622 329 623 333 623 332 623 338 624 333 624 329 624 333 625 338 625 265 625 338 626 335 626 265 626 335 627 334 627 265 627 335 628 338 628 8 628 338 629 343 629 8 629 343 630 338 630 339 630 338 631 336 631 339 631 338 632 337 632 336 632 338 633 329 633 337 633 7 634 8 634 343 634 339 635 342 635 343 635 344 636 343 636 340 636 343 637 341 637 340 637 343 638 342 638 341 638 343 639 344 639 7 639 344 640 6 640 7 640 4 641 6 641 344 641 344 642 347 642 4 642 5 643 4 643 345 643 4 644 346 644 345 644 4 645 347 645 346 645 348 646 364 646 351 646 365 647 350 647 364 647 350 648 351 648 364 648 353 649 351 649 352 649 351 650 349 650 352 650 351 651 350 651 349 651 352 652 354 652 353 652 356 653 353 653 354 653 354 654 355 654 356 654 358 655 356 655 357 655 356 656 355 656 357 656 357 657 70 657 358 657 72 658 358 658 70 658 359 659 360 659 377 659 360 660 361 660 373 660 361 661 362 661 373 661 373 662 362 662 363 662 363 663 365 663 374 663 374 664 364 664 366 664 374 665 365 665 364 665 375 666 366 666 367 666 367 667 368 667 376 667 372 668 388 668 387 668 372 669 387 669 371 669 371 670 387 670 386 670 371 671 386 671 370 671 370 672 386 672 391 672 391 673 386 673 385 673 379 674 245 674 383 674 264 675 383 675 245 675 393 676 392 676 128 676 124 677 128 677 392 677 124 678 392 678 125 678 390 679 127 679 126 679 390 680 226 680 127 680 177 681 127 681 226 681 236 682 370 682 391 682 401 683 372 683 326 683 128 684 380 684 393 684 393 685 380 685 391 685 380 686 381 686 391 686 381 687 382 687 391 687 382 688 383 688 391 688 383 689 264 689 391 689 264 690 236 690 391 690 172 691 226 691 230 691 173 692 174 692 226 692 174 693 175 693 226 693 175 694 176 694 226 694 177 695 226 695 176 695 377 696 320 696 319 696 377 697 321 697 320 697 377 698 322 698 321 698 377 699 323 699 322 699 377 700 324 700 323 700 377 701 325 701 324 701 377 702 326 702 325 702 326 703 377 703 401 703 377 704 402 704 401 704 403 705 401 705 402 705 230 706 227 706 91 706 227 707 228 707 219 707 228 708 229 708 221 708 229 709 231 709 223 709 373 710 377 710 360 710 374 711 373 711 363 711 375 712 374 712 366 712 376 713 375 713 367 713 378 714 376 714 369 714 376 715 368 715 369 715 0 716 378 716 369 716 225 717 224 717 231 717 378 718 1 718 2 718 378 719 0 719 1 719 384 720 389 720 391 720 385 721 384 721 391 721 372 722 401 722 388 722 403 723 388 723 401 723 377 724 373 724 402 724 373 725 394 725 402 725 395 726 394 726 373 726 373 727 374 727 395 727 396 728 395 728 374 728 374 729 375 729 396 729 397 730 396 730 398 730 396 731 375 731 398 731 376 732 398 732 375 732 399 733 397 733 400 733 397 734 398 734 400 734 376 735 400 735 398 735 400 736 404 736 399 736 378 737 400 737 376 737 404 738 400 738 378 738 455 739 416 739 454 739 455 740 454 740 404 740 446 741 405 741 388 741 403 742 446 742 388 742 421 743 419 743 420 743 435 744 420 744 419 744 411 745 389 745 384 745 452 746 378 746 450 746 422 747 421 747 420 747 423 748 422 748 420 748 408 749 407 749 411 749 408 750 411 750 444 750 443 751 408 751 444 751 407 752 389 752 411 752 449 753 411 753 446 753 411 754 405 754 446 754 406 755 405 755 411 755 411 756 386 756 406 756 411 757 385 757 386 757 411 758 384 758 385 758 388 759 405 759 387 759 387 760 405 760 406 760 387 761 406 761 386 761 389 762 407 762 391 762 412 763 444 763 411 763 409 764 442 764 444 764 409 765 444 765 412 765 412 766 413 766 409 766 441 767 442 767 409 767 409 768 410 768 441 768 410 769 440 769 441 769 410 770 409 770 414 770 409 771 413 771 414 771 439 772 440 772 410 772 414 773 415 773 410 773 410 774 452 774 439 774 452 775 438 775 439 775 410 776 455 776 452 776 416 777 455 777 410 777 410 778 415 778 416 778 453 779 438 779 452 779 449 780 427 780 411 780 426 781 411 781 427 781 424 782 411 782 426 782 412 783 411 783 423 783 411 784 424 784 423 784 413 785 412 785 420 785 412 786 423 786 420 786 414 787 413 787 434 787 413 788 436 788 434 788 413 789 420 789 436 789 415 790 414 790 433 790 414 791 432 791 433 791 414 792 434 792 432 792 416 793 415 793 430 793 415 794 433 794 430 794 416 795 428 795 454 795 416 796 430 796 428 796 399 797 404 797 429 797 429 798 431 798 399 798 417 799 431 799 419 799 431 800 435 800 419 800 431 801 417 801 399 801 417 802 397 802 399 802 396 803 397 803 417 803 419 804 421 804 417 804 418 805 417 805 421 805 417 806 418 806 396 806 418 807 395 807 396 807 394 808 395 808 418 808 421 809 422 809 418 809 418 810 448 810 447 810 418 811 422 811 448 811 418 812 447 812 394 812 447 813 402 813 394 813 436 814 420 814 435 814 423 815 425 815 422 815 425 816 448 816 422 816 425 817 423 817 424 817 448 818 425 818 426 818 425 819 424 819 426 819 426 820 427 820 448 820 448 821 427 821 449 821 429 822 404 822 454 822 454 823 428 823 429 823 431 824 429 824 430 824 429 825 428 825 430 825 435 826 431 826 433 826 431 827 430 827 433 827 435 828 432 828 434 828 435 829 433 829 432 829 436 830 435 830 434 830 445 831 443 831 437 831 443 832 451 832 437 832 443 833 453 833 451 833 443 834 438 834 453 834 443 835 439 835 438 835 443 836 440 836 439 836 443 837 441 837 440 837 443 838 442 838 441 838 443 839 444 839 442 839 402 840 447 840 403 840 446 841 403 841 449 841 403 842 447 842 449 842 447 843 448 843 449 843 378 844 455 844 404 844 452 845 455 845 378 845 534 846 532 846 524 846 532 847 522 847 524 847 532 848 520 848 522 848 532 849 519 849 520 849 452 850 450 850 563 850 452 851 563 851 564 851 563 852 450 852 562 852 393 853 456 853 392 853 509 854 510 854 461 854 463 855 461 855 510 855 510 856 552 856 463 856 465 857 463 857 552 857 552 858 550 858 465 858 471 859 460 859 470 859 460 860 469 860 470 860 460 861 468 861 469 861 456 862 472 862 468 862 456 863 393 863 472 863 456 864 468 864 460 864 460 865 462 865 456 865 456 866 457 866 392 866 457 867 456 867 464 867 456 868 462 868 464 868 459 869 392 869 457 869 464 870 466 870 457 870 457 871 458 871 459 871 458 872 457 872 466 872 466 873 467 873 458 873 390 874 459 874 458 874 458 875 526 875 390 875 458 876 545 876 526 876 458 877 467 877 545 877 390 878 526 878 226 878 392 879 459 879 125 879 126 880 125 880 459 880 459 881 390 881 126 881 506 882 507 882 471 882 460 883 471 883 508 883 471 884 507 884 508 884 462 885 460 885 509 885 460 886 508 886 509 886 509 887 461 887 462 887 464 888 462 888 463 888 462 889 461 889 463 889 463 890 465 890 464 890 466 891 464 891 465 891 465 892 550 892 466 892 467 893 466 893 550 893 550 894 548 894 467 894 545 895 467 895 547 895 467 896 548 896 547 896 443 897 445 897 504 897 504 898 473 898 443 898 473 899 408 899 443 899 473 900 504 900 506 900 506 901 471 901 473 901 407 902 408 902 391 902 391 903 468 903 472 903 391 904 469 904 468 904 391 905 470 905 469 905 391 906 473 906 470 906 473 907 471 907 470 907 391 908 408 908 473 908 472 909 393 909 391 909 480 910 481 910 482 910 482 911 483 911 480 911 479 912 480 912 483 912 483 913 484 913 479 913 478 914 479 914 484 914 484 915 485 915 478 915 477 916 478 916 485 916 485 917 486 917 477 917 476 918 477 918 486 918 486 919 487 919 476 919 475 920 476 920 487 920 487 921 488 921 437 921 437 922 475 922 487 922 474 923 475 923 437 923 437 924 488 924 445 924 451 925 474 925 437 925 564 926 489 926 451 926 474 927 451 927 489 927 489 928 490 928 474 928 475 929 474 929 491 929 474 930 490 930 491 930 476 931 475 931 492 931 475 932 491 932 492 932 492 933 493 933 476 933 477 934 476 934 493 934 493 935 494 935 477 935 478 936 477 936 494 936 494 937 495 937 478 937 479 938 478 938 495 938 495 939 496 939 479 939 480 940 479 940 496 940 496 941 497 941 480 941 481 942 480 942 497 942 497 943 498 943 481 943 482 944 481 944 498 944 498 945 499 945 482 945 483 946 482 946 499 946 499 947 500 947 483 947 484 948 483 948 500 948 500 949 501 949 484 949 485 950 484 950 501 950 501 951 502 951 485 951 486 952 485 952 502 952 502 953 503 953 486 953 487 954 486 954 503 954 503 955 505 955 487 955 488 956 487 956 505 956 505 957 504 957 488 957 445 958 488 958 504 958 532 959 530 959 519 959 530 960 517 960 519 960 530 961 528 961 517 961 528 962 516 962 517 962 528 963 514 963 516 963 557 964 514 964 528 964 528 965 529 965 557 965 529 966 564 966 557 966 529 967 489 967 564 967 490 968 489 968 529 968 529 969 531 969 490 969 531 970 491 970 490 970 531 971 533 971 491 971 533 972 492 972 491 972 493 973 492 973 533 973 533 974 535 974 493 974 494 975 493 975 535 975 535 976 538 976 494 976 495 977 494 977 538 977 538 978 540 978 495 978 496 979 495 979 540 979 540 980 541 980 496 980 497 981 496 981 541 981 541 982 542 982 497 982 498 983 497 983 542 983 542 984 543 984 498 984 499 985 498 985 543 985 543 986 544 986 499 986 500 987 499 987 544 987 544 988 546 988 500 988 501 989 500 989 546 989 546 990 549 990 501 990 502 991 501 991 549 991 549 992 551 992 502 992 503 993 502 993 551 993 551 994 553 994 503 994 505 995 503 995 553 995 553 996 554 996 505 996 504 997 505 997 506 997 505 998 554 998 506 998 554 999 555 999 506 999 555 1000 507 1000 506 1000 555 1001 556 1001 507 1001 556 1002 508 1002 507 1002 556 1003 509 1003 508 1003 556 1004 552 1004 510 1004 510 1005 509 1005 556 1005 525 1006 527 1006 536 1006 511 1007 527 1007 525 1007 511 1008 230 1008 527 1008 511 1009 227 1009 230 1009 525 1010 523 1010 511 1010 511 1011 512 1011 227 1011 512 1012 511 1012 521 1012 511 1013 523 1013 521 1013 521 1014 518 1014 512 1014 513 1015 512 1015 518 1015 512 1016 513 1016 227 1016 513 1017 228 1017 227 1017 518 1018 515 1018 513 1018 229 1019 228 1019 513 1019 513 1020 559 1020 229 1020 513 1021 558 1021 559 1021 513 1022 562 1022 558 1022 513 1023 515 1023 562 1023 231 1024 229 1024 561 1024 229 1025 560 1025 561 1025 229 1026 559 1026 560 1026 515 1027 557 1027 562 1027 515 1028 514 1028 557 1028 516 1029 514 1029 515 1029 515 1030 518 1030 516 1030 518 1031 517 1031 516 1031 519 1032 517 1032 518 1032 518 1033 521 1033 519 1033 521 1034 520 1034 519 1034 522 1035 520 1035 521 1035 521 1036 523 1036 522 1036 524 1037 522 1037 523 1037 523 1038 525 1038 524 1038 534 1039 524 1039 525 1039 525 1040 536 1040 534 1040 537 1041 534 1041 536 1041 226 1042 526 1042 230 1042 527 1043 230 1043 526 1043 526 1044 545 1044 527 1044 536 1045 527 1045 545 1045 528 1046 530 1046 529 1046 531 1047 529 1047 530 1047 530 1048 532 1048 531 1048 533 1049 531 1049 532 1049 532 1050 534 1050 533 1050 535 1051 533 1051 534 1051 534 1052 537 1052 535 1052 538 1053 535 1053 537 1053 536 1054 545 1054 537 1054 545 1055 539 1055 537 1055 539 1056 538 1056 537 1056 539 1057 540 1057 538 1057 545 1058 546 1058 539 1058 541 1059 540 1059 539 1059 539 1060 542 1060 541 1060 539 1061 543 1061 542 1061 539 1062 544 1062 543 1062 546 1063 544 1063 539 1063 549 1064 546 1064 547 1064 546 1065 545 1065 547 1065 547 1066 548 1066 549 1066 551 1067 549 1067 550 1067 549 1068 548 1068 550 1068 550 1069 552 1069 551 1069 553 1070 551 1070 552 1070 552 1071 556 1071 553 1071 554 1072 553 1072 556 1072 556 1073 555 1073 554 1073 562 1074 557 1074 563 1074 557 1075 564 1075 563 1075 378 1076 562 1076 450 1076 378 1077 558 1077 562 1077 378 1078 559 1078 558 1078 378 1079 560 1079 559 1079 378 1080 561 1080 560 1080 378 1081 231 1081 561 1081 564 1082 451 1082 453 1082 453 1083 452 1083 564 1083 565 1084 256 1084 257 1084 252 1085 259 1085 253 1085 253 1086 566 1086 252 1086 567 1087 565 1087 257 1087 257 1088 568 1088 567 1088 252 1089 566 1089 569 1089 252 1090 569 1090 570 1090 251 1091 252 1091 570 1091 570 1092 571 1092 251 1092 572 1093 251 1093 571 1093 571 1094 573 1094 572 1094 574 1095 572 1095 573 1095 573 1096 575 1096 574 1096 574 1097 575 1097 576 1097 574 1098 576 1098 577 1098 578 1099 574 1099 577 1099 577 1100 579 1100 578 1100 578 1101 579 1101 120 1101 119 1102 578 1102 120 1102 571 1103 570 1103 573 1103 575 1104 573 1104 570 1104 570 1105 580 1105 575 1105 581 1106 575 1106 580 1106 580 1107 582 1107 581 1107 583 1108 581 1108 582 1108 582 1109 584 1109 583 1109 585 1110 583 1110 584 1110 584 1111 586 1111 585 1111 587 1112 585 1112 586 1112 586 1113 588 1113 587 1113 589 1114 587 1114 588 1114 591 1115 589 1115 590 1115 592 1116 591 1116 590 1116 595 1117 593 1117 590 1117 594 1118 596 1118 592 1118 590 1119 597 1119 595 1119 707 1120 592 1120 596 1120 598 1121 595 1121 597 1121 596 1122 599 1122 707 1122 597 1123 600 1123 598 1123 601 1124 707 1124 599 1124 602 1125 598 1125 600 1125 599 1126 603 1126 601 1126 604 1127 601 1127 603 1127 600 1128 605 1128 602 1128 603 1129 606 1129 604 1129 607 1130 602 1130 605 1130 604 1131 606 1131 608 1131 609 1132 604 1132 608 1132 610 1133 611 1133 607 1133 605 1134 610 1134 607 1134 612 1135 611 1135 610 1135 608 1136 612 1136 609 1136 613 1137 609 1137 612 1137 614 1138 613 1138 612 1138 610 1139 614 1139 612 1139 615 1140 616 1140 617 1140 618 1141 617 1141 616 1141 619 1142 621 1142 620 1142 622 1143 620 1143 621 1143 621 1144 623 1144 622 1144 624 1145 622 1145 623 1145 623 1146 625 1146 624 1146 624 1147 625 1147 626 1147 627 1148 624 1148 626 1148 626 1149 628 1149 627 1149 629 1150 627 1150 628 1150 628 1151 630 1151 629 1151 632 1152 633 1152 634 1152 635 1153 632 1153 634 1153 120 1154 636 1154 122 1154 637 1155 122 1155 636 1155 636 1156 638 1156 637 1156 639 1157 637 1157 638 1157 638 1158 640 1158 639 1158 641 1159 639 1159 640 1159 640 1160 642 1160 641 1160 643 1161 641 1161 642 1161 642 1162 644 1162 643 1162 645 1163 643 1163 644 1163 644 1164 646 1164 645 1164 647 1165 645 1165 646 1165 646 1166 648 1166 647 1166 649 1167 647 1167 648 1167 648 1168 615 1168 649 1168 617 1169 649 1169 615 1169 256 1170 650 1170 255 1170 651 1171 255 1171 650 1171 650 1172 652 1172 651 1172 653 1173 651 1173 652 1173 652 1174 654 1174 653 1174 655 1175 653 1175 654 1175 654 1176 656 1176 655 1176 657 1177 655 1177 656 1177 656 1178 658 1178 657 1178 659 1179 657 1179 658 1179 658 1180 660 1180 659 1180 661 1181 659 1181 660 1181 660 1182 662 1182 661 1182 663 1183 661 1183 662 1183 662 1184 635 1184 663 1184 634 1185 663 1185 635 1185 651 1186 254 1186 255 1186 653 1187 566 1187 253 1187 653 1188 253 1188 254 1188 651 1189 653 1189 254 1189 653 1190 655 1190 566 1190 664 1191 570 1191 569 1191 664 1192 569 1192 566 1192 566 1193 655 1193 657 1193 664 1194 566 1194 657 1194 580 1195 570 1195 664 1195 657 1196 659 1196 664 1196 664 1197 659 1197 661 1197 665 1198 664 1198 661 1198 665 1199 582 1199 580 1199 664 1200 665 1200 580 1200 584 1201 582 1201 665 1201 661 1202 663 1202 665 1202 669 1203 586 1203 584 1203 665 1204 669 1204 584 1204 665 1205 663 1205 634 1205 665 1206 634 1206 666 1206 669 1207 665 1207 666 1207 586 1208 669 1208 667 1208 588 1209 586 1209 667 1209 668 1210 597 1210 667 1210 667 1211 669 1211 668 1211 670 1212 668 1212 669 1212 669 1213 666 1213 670 1213 670 1214 666 1214 634 1214 670 1215 634 1215 633 1215 671 1216 670 1216 633 1216 591 1217 592 1217 589 1217 589 1218 592 1218 672 1218 673 1219 589 1219 672 1219 672 1220 674 1220 673 1220 675 1221 673 1221 674 1221 674 1222 676 1222 675 1222 677 1223 675 1223 676 1223 676 1224 616 1224 677 1224 615 1225 677 1225 616 1225 120 1226 579 1226 636 1226 638 1227 636 1227 579 1227 579 1228 577 1228 638 1228 638 1229 577 1229 678 1229 640 1230 638 1230 678 1230 679 1231 642 1231 640 1231 678 1232 679 1232 640 1232 576 1233 575 1233 679 1233 679 1234 678 1234 576 1234 575 1235 581 1235 679 1235 644 1236 642 1236 679 1236 679 1237 581 1237 583 1237 680 1238 679 1238 583 1238 680 1239 646 1239 644 1239 679 1240 680 1240 644 1240 583 1241 585 1241 680 1241 648 1242 646 1242 680 1242 680 1243 585 1243 587 1243 680 1244 587 1244 589 1244 680 1245 589 1245 673 1245 675 1246 680 1246 673 1246 680 1247 675 1247 648 1247 648 1248 675 1248 677 1248 615 1249 648 1249 677 1249 681 1250 682 1250 617 1250 618 1251 681 1251 617 1251 683 1252 682 1252 681 1252 681 1253 684 1253 683 1253 685 1254 683 1254 684 1254 684 1255 630 1255 685 1255 628 1256 685 1256 630 1256 686 1257 687 1257 629 1257 631 1258 686 1258 629 1258 688 1259 687 1259 686 1259 686 1260 689 1260 688 1260 690 1261 688 1261 689 1261 689 1262 632 1262 690 1262 635 1263 690 1263 632 1263 256 1264 691 1264 650 1264 652 1265 650 1265 691 1265 691 1266 692 1266 652 1266 654 1267 652 1267 692 1267 692 1268 693 1268 654 1268 656 1269 654 1269 693 1269 694 1270 658 1270 656 1270 693 1271 694 1271 656 1271 695 1272 620 1272 694 1272 696 1273 695 1273 694 1273 697 1274 696 1274 694 1274 694 1275 693 1275 697 1275 620 1276 622 1276 694 1276 660 1277 658 1277 694 1277 694 1278 622 1278 624 1278 694 1279 624 1279 627 1279 694 1280 627 1280 629 1280 694 1281 629 1281 687 1281 688 1282 694 1282 687 1282 688 1283 662 1283 660 1283 694 1284 688 1284 660 1284 662 1285 688 1285 690 1285 635 1286 662 1286 690 1286 245 1287 257 1287 258 1287 246 1288 264 1288 245 1288 568 1289 257 1289 245 1289 379 1290 698 1290 699 1290 699 1291 568 1291 245 1291 700 1292 379 1292 383 1292 383 1293 382 1293 700 1293 381 1294 701 1294 700 1294 382 1295 381 1295 700 1295 100 1296 701 1296 381 1296 381 1297 380 1297 100 1297 100 1298 110 1298 123 1298 100 1299 380 1299 128 1299 702 1300 606 1300 603 1300 608 1301 606 1301 702 1301 612 1302 608 1302 702 1302 611 1303 612 1303 702 1303 607 1304 611 1304 702 1304 602 1305 607 1305 702 1305 702 1306 598 1306 602 1306 595 1307 598 1307 702 1307 593 1308 595 1308 702 1308 594 1309 593 1309 702 1309 596 1310 594 1310 702 1310 599 1311 596 1311 702 1311 603 1312 599 1312 702 1312 703 1313 597 1313 668 1313 668 1314 670 1314 703 1314 704 1315 703 1315 670 1315 670 1316 671 1316 704 1316 672 1317 705 1317 674 1317 676 1318 674 1318 705 1318 705 1319 706 1319 676 1319 676 1320 706 1320 616 1320 708 1321 600 1321 597 1321 703 1322 708 1322 597 1322 704 1323 671 1323 708 1323 703 1324 704 1324 708 1324 671 1325 709 1325 708 1325 605 1326 600 1326 708 1326 710 1327 708 1327 709 1327 710 1328 610 1328 605 1328 708 1329 710 1329 605 1329 709 1330 711 1330 710 1330 614 1331 610 1331 710 1331 710 1332 711 1332 712 1332 713 1333 710 1333 712 1333 710 1334 713 1334 614 1334 613 1335 614 1335 713 1335 712 1336 714 1336 713 1336 715 1337 713 1337 714 1337 713 1338 715 1338 613 1338 609 1339 613 1339 715 1339 714 1340 716 1340 715 1340 717 1341 604 1341 609 1341 715 1342 717 1342 609 1342 717 1343 715 1343 716 1343 601 1344 604 1344 717 1344 716 1345 616 1345 717 1345 705 1346 707 1346 601 1346 717 1347 705 1347 601 1347 717 1348 616 1348 706 1348 717 1349 706 1349 705 1349 672 1350 707 1350 705 1350 720 1351 699 1351 698 1351 721 1352 699 1352 720 1352 720 1353 719 1353 721 1353 722 1354 721 1354 719 1354 719 1355 718 1355 722 1355 722 1356 718 1356 619 1356 722 1357 619 1357 620 1357 32 1358 251 1358 572 1358 32 1359 572 1359 574 1359 32 1360 574 1360 578 1360 32 1361 578 1361 119 1361 33 1362 32 1362 119 1362 577 1363 576 1363 678 1363 698 1364 379 1364 700 1364 700 1365 701 1365 698 1365 707 1366 672 1366 592 1366 245 1367 379 1367 699 1367 620 1368 695 1368 722 1368 699 1369 721 1369 722 1369 695 1370 699 1370 722 1370 695 1371 696 1371 699 1371 696 1372 697 1372 699 1372 568 1373 699 1373 697 1373 568 1374 697 1374 693 1374 568 1375 693 1375 692 1375 567 1376 568 1376 692 1376 567 1377 692 1377 691 1377 565 1378 567 1378 691 1378 256 1379 565 1379 691 1379 588 1380 590 1380 589 1380 588 1381 667 1381 590 1381 629 1382 630 1382 631 1382 631 1383 724 1383 723 1383 630 1384 724 1384 631 1384 671 1385 633 1385 632 1385 689 1386 726 1386 632 1386 686 1387 726 1387 689 1387 723 1388 727 1388 726 1388 723 1389 728 1389 727 1389 723 1390 724 1390 728 1390 724 1391 729 1391 728 1391 724 1392 725 1392 729 1392 681 1393 618 1393 725 1393 681 1394 725 1394 684 1394 122 1395 739 1395 745 1395 745 1396 739 1396 744 1396 744 1397 739 1397 738 1397 744 1398 738 1398 743 1398 743 1399 738 1399 737 1399 743 1400 737 1400 733 1400 743 1401 733 1401 732 1401 734 1402 732 1402 733 1402 735 1403 732 1403 734 1403 735 1404 730 1404 732 1404 732 1405 730 1405 731 1405 742 1406 730 1406 735 1406 100 1407 732 1407 701 1407 730 1408 742 1408 619 1408 730 1409 619 1409 718 1409 719 1410 730 1410 718 1410 730 1411 719 1411 731 1411 720 1412 731 1412 719 1412 731 1413 720 1413 732 1413 720 1414 698 1414 732 1414 732 1415 100 1415 743 1415 701 1416 732 1416 698 1416 743 1417 100 1417 123 1417 617 1418 682 1418 649 1418 649 1419 682 1419 683 1419 736 1420 647 1420 683 1420 683 1421 647 1421 649 1421 683 1422 685 1422 736 1422 736 1423 685 1423 628 1423 736 1424 628 1424 626 1424 736 1425 626 1425 740 1425 736 1426 740 1426 741 1426 647 1427 736 1427 645 1427 742 1428 736 1428 741 1428 736 1429 733 1429 737 1429 733 1430 736 1430 734 1430 734 1431 736 1431 735 1431 735 1432 736 1432 742 1432 737 1433 643 1433 736 1433 736 1434 643 1434 645 1434 643 1435 737 1435 641 1435 738 1436 641 1436 737 1436 641 1437 738 1437 639 1437 739 1438 639 1438 738 1438 639 1439 739 1439 637 1439 122 1440 637 1440 739 1440 623 1441 740 1441 625 1441 740 1442 623 1442 741 1442 621 1443 741 1443 623 1443 741 1444 621 1444 742 1444 619 1445 742 1445 621 1445 123 1446 744 1446 743 1446 744 1447 123 1447 745 1447 745 1448 123 1448 122 1448 625 1449 740 1449 626 1449 590 1450 594 1450 592 1450 590 1451 593 1451 594 1451 590 1452 667 1452 597 1452 631 1453 723 1453 686 1453 686 1454 723 1454 726 1454 630 1455 684 1455 724 1455 684 1456 725 1456 724 1456 709 1457 671 1457 726 1457 671 1458 632 1458 726 1458 716 1459 714 1459 729 1459 716 1460 729 1460 725 1460 714 1461 712 1461 728 1461 714 1462 728 1462 729 1462 712 1463 711 1463 727 1463 712 1464 727 1464 728 1464 711 1465 709 1465 726 1465 711 1466 726 1466 727 1466 616 1467 716 1467 725 1467 616 1468 725 1468 618 1468 2 1469 231 1469 378 1469 2 1470 3 1470 231 1470 3 1471 225 1471 231 1471 14 1472 68 1472 65 1472 14 1473 52 1473 68 1473 14 1474 54 1474 52 1474 14 1475 55 1475 54 1475 14 1476 65 1476 64 1476 14 1477 64 1477 47 1477 14 1478 47 1478 35 1478 14 1479 35 1479 48 1479 25 1480 59 1480 58 1480 25 1481 58 1481 40 1481 25 1482 40 1482 39 1482 25 1483 39 1483 38 1483 25 1484 38 1484 34 1484 25 1485 34 1485 37 1485 25 1486 37 1486 36 1486 25 1487 36 1487 60 1487

+
+
+
+
+ + + + 0.00000 0.00002 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E3M5_no_rot_scaled.dae b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E3M5_no_rot_scaled.dae new file mode 100644 index 0000000..cc99570 --- /dev/null +++ b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E3M5_no_rot_scaled.dae @@ -0,0 +1,210 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T10:55:16 + 2025-02-20T10:55:16 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -4.16853 10.99697 56.9178 -2.13558 10.99697 56.22232 3e-4 10.99697 55.98668 2.13616 10.99697 56.22231 -7.41158 1.43357 57.78464 -7.54952 -0.003029942 57.78464 -7.00374 2.81535 57.78464 -6.34754 4.08412 57.78464 -5.49969 5.16901 57.78464 -1.03468 8.496971 57.78464 2.42357 7.14735 57.78464 1.05031 7.94142 58.24917 1.05031 7.47344 57.78464 2.60851 7.94142 58.63739 3.1e-4 8.55728 68.91865 2.28125 8.496971 59.99264 1.05031 8.496971 59.64888 1.0353 8.496971 57.78464 -4.99969 8.496971 57.78464 -2.90817 11.39697 59.72056 -1.50644 11.39697 59.2301 -1.9e-4 11.39697 59.05914 1.5062 11.39697 59.2299 2.90832 11.39697 59.72033 3.1e-4 11.49528 59.76977 3.2e-4 11.49697 65.90822 1.69915 11.49697 60.07462 2.73893 11.49697 60.49405 3.64845 11.49697 61.07492 -1.69865 11.49697 60.07465 -2.73841 11.49697 60.49409 -3.64783 11.49697 61.07491 -7.54952 -4.00303 57.78464 7.55014 -4.00303 57.78465 1.13878 11.48797 71.16059 -3.33824 9.49194 70.55422 2.78628 11.49697 70.25549 2.27099 11.48797 70.79404 3.2e-4 11.48797 71.28465 -1.16122 11.48797 71.16059 -2.27036 11.48797 70.79404 5.28198 10.27446 71.13149 -1.06765 10.38028 73.0756 1.06828 10.38028 73.0756 3.10938 10.3817 72.45206 -5.28136 10.27446 71.13149 -3.10875 10.3817 72.45206 -2.54465 9.65113 71.4052 -3.28925 9.10508 69.4043 -5.96849 9.74083 70.08224 -4.84852 9.88731 71.04855 -3.17535 8.6999 68.29736 2.54802 9.65113 71.40519 3.44225 9.96396 71.93696 3.33827 9.492381 70.55584 3.28988 9.10508 69.4043 4.96737 9.87593 70.95893 5.56944 9.8037 70.45921 -2.78565 11.49697 70.25549 -3.73788 11.49697 69.49624 3.7385 11.49697 69.49624 4.49082 11.49697 68.53881 -3.86623 9.951331 71.70066 -2.59559 9.968561 72.33196 -1.30422 9.65113 71.8162 2.8e-4 9.65113 71.95565 -1.06018 9.968561 72.74751 0.81113 9.968561 72.78098 1.30478 9.65113 71.81622 2.01662 9.968561 72.53303 -5.53304 10.70933 70.64544 -4.96728 10.77157 71.09794 -4.80699 11.04699 70.66184 -3.94573 10.83814 71.77613 -3.60196 11.04698 71.60882 -2.63388 10.85606 72.42852 -1.65129 10.85606 72.73823 -2.23214 11.04697 72.25872 -0.46035 10.85606 72.91682 -0.75524 11.04697 72.59101 0.82309 10.85606 72.88416 0.76285 11.04697 72.59023 2.04635 10.85606 72.63255 2.57708 10.85606 72.45101 2.23939 11.04697 72.25643 3.99747 10.83605 71.74595 3.60862 11.04698 71.60508 5.09086 10.75973 71.00474 4.81271 11.04698 70.65682 5.71692 10.68463 70.48512 7.49423 7.94157 64.50987 8.92281 8.79775 63.71438 8.99367 8.08742 64.55763 8.69039 8.16196 65.11563 8.376441 7.53031 64.74487 8.95635 8.269391 64.86778 8.74722 9.009301 65.88835 8.77245 8.656371 65.41832 8.59545 8.83116 65.91737 7.72686 7.83903 65.04834 3.52352 -10.85658 55.20966 8.68893 -9.29155 57.92509 6.99644 -10.79866 56.75002 7.84651 -10.23448 57.50816 5.86119 -10.9194 56.20141 8.38834 -9.29184 58.2159 7.6915 -10.1712 57.61452 6.76178 -10.62444 56.96974 8.13379 -9.19327 58.25332 7.47072 -9.98157 57.66316 5.77439 -10.75303 56.34334 8.94369 -8.00302 58.26979 8.78663 -8.00302 58.44858 8.56473 -8.00302 58.53452 8.32824 -8.00302 58.50813 8.130741 -8.00303 58.37546 7.90869 -9.0365 58.13997 7.35169 -9.84937 57.60191 6.68573 -10.5013 57.00586 5.9168 -4.00303 56.51129 4.8892 -6.00303 55.93077 5.73944 -10.50303 56.40048 4.8892 -9.00303 55.93077 4.61923 -10.50303 55.80138 6.73955 -10.91053 56.37839 7.08858 -10.77342 56.59704 8.02298 -10.21861 57.23 8.72172 -9.24322 57.79251 6.00031 -11.00303 55.97394 8.680891 5.63812 61.18336 8.564761 -0.003029942 58.53451 8.32827 -0.003029942 58.50815 8.680891 3.11933 59.20854 8.94369 -0.003029942 58.26979 8.786641 -0.003029942 58.44856 8.130741 7.10166 63.68239 8.67571 7.07942 64.04446 8.80273 7.58718 64.67844 8.80114 9.23126 65.82974 8.21285 9.19201 67.21714 7.07571 9.96326 69.35165 8.37914 9.46742 67.22308 8.751851 9.44767 65.75461 8.94514 8.88449 64.98747 8.80831 9.3299 65.52029 8.33006 8.34255 65.38938 7.94636 8.50667 65.71574 8.55656 8.56278 65.49903 8.37959 8.73646 65.91035 3.67569 8.71842 68.3597 6.20627 9.69696 69.83866 6.80137 9.560871 69.14859 7.29869 9.41038 68.46049 6.91519 8.54095 65.99626 7.57014 8.64119 66.07724 7.70401 9.2523 67.79227 8.2266 8.93963 66.59763 5.00357 11.49697 67.43311 5.24853 11.49697 66.2388 4.1109 11.49697 61.54639 4.49544 11.49697 62.19938 4.79629 11.49697 63.01113 5.02916 11.49697 63.95683 5.21279 11.49697 65.02298 6.34688 11.17864 63.68803 5.87602 11.27726 62.68842 5.34956 11.34554 61.80425 4.11882 11.39697 60.46767 4.73815 11.1753 59.66812 9.00031 7.4246 63.58684 9.00031 5.53833 60.3723 9.00031 4.97167 59.84727 9.00031 4.28707 59.33522 9.00031 3.4627 58.85725 9.00031 2.48084 58.44772 9.00031 1.33136 58.15448 9.00031 -0.003029942 58.03868 9.00031 -8.00303 58.03868 6.58902 8.496971 65.82475 6.372 8.49544 65.34729 6.13723 8.496971 64.74155 6.02274 8.496971 64.20972 5.84711 8.496971 63.64807 5.5936 8.496971 63.0524 5.24033 8.496971 62.42426 4.76095 8.496971 61.77386 4.12606 8.496971 61.12329 3.30603 8.496971 60.50996 7.35819 7.94142 63.84882 8.130741 5.63518 60.98634 7.13793 7.94142 63.15024 6.81856 7.94142 62.40866 6.3718 7.94142 61.62654 8.130741 3.312 59.15843 8.130741 2.37288 58.76674 8.130741 1.27351 58.48625 8.130741 -0.003029942 58.37546 7.84601 -0.003029942 58.07458 7.55014 -0.003029942 57.78465 5.76359 7.94142 60.8177 5.95262 4.64133 57.78465 6.7613 5.63631 59.19019 6.93098 2.916 57.78465 4.95613 7.94142 60.01181 4.87115 5.76542 57.78465 3.91203 7.94142 59.25899 3.6932 6.582 57.78465 6.37924 10.57362 69.83974 5.76106 11.04699 69.48746 6.99832 10.43204 69.12189 7.51555 10.27552 68.4062 6.39743 11.04699 68.22884 7.93707 10.11112 67.71126 6.74219 11.04698 66.98638 8.27304 9.94482 67.05045 6.77652 11.04697 64.79448 6.84833 11.04698 65.82776 8.27304 10.02494 65.82712 8.27304 9.955221 64.60337 7.68907 10.4765 65.22638 7.5144 10.58686 64.38346 7.28972 10.70574 63.34866 7.03156 10.81415 62.2139 6.56192 10.93564 60.26743 6.00031 10.99697 58.03868 4.16911 10.99697 56.91779 8.9732 -7.9993 35.69485 8.57261 9.49998 35.85024 7.47453 10.59806 35.85024 6.75099 10.89776 35.85024 8.97405 7.99896 35.64078 5.97453 10.99998 35.85024 -7.73288 7.83902 65.04834 -8.635021 -9.30826 58.01877 -7.93006 -10.24095 57.42631 -6.99314 -10.79692 56.7571 -5.9852 -10.99559 55.99763 -8.465331 -9.30571 58.17711 -7.75845 -10.2036 57.57774 -6.83918 -10.7081 56.91447 -8.281661 -9.25626 58.24971 -7.57564 -10.08604 57.65858 -6.7115 -10.54603 56.99843 -5.78438 -10.77336 56.326 -8.0845 -9.16383 58.2442 -3.52289 -10.85658 55.20966 -5.86925 -10.93604 56.18721 -8.94307 -8.00303 58.26979 -8.78603 -8.00303 58.44856 -8.56413 -8.00303 58.53451 -8.327651 -8.00303 58.50815 -2.07017 -4.00303 54.98126 -4.06603 -4.00303 55.56384 -4.07348 -5.46536 55.5668 -4.41319 -5.67444 55.70889 -4.88858 -6.00303 55.93077 -4.88858 -9.00303 55.93077 -4.61835 -10.50303 55.80126 -5.73882 -10.50303 56.40048 -5.91618 -4.00303 56.51129 -6.61429 -10.3084 57.0025 -7.36932 -9.82743 57.61906 -7.90885 -9.0346 58.14079 -8.13012 -8.00303 58.37546 -4.42719 -11.00303 55.1711 -5.49969 7.94142 60.52766 -5.49969 8.496971 62.86916 -7.07509 9.96326 69.35165 -8.40868 9.572 67.21003 -8.38164 9.77928 67.1439 -8.77847 8.656371 65.41832 -8.75324 9.009301 65.88834 -8.80716 9.23126 65.82973 -8.85598 8.20532 65.01575 -8.808751 7.58718 64.67843 -8.327651 -0.003029942 58.50815 -8.56413 -0.003029942 58.53451 -8.78603 -0.003029942 58.44856 -8.94307 -0.003029942 58.26979 -8.67508 -0.003029942 58.49153 -8.680271 3.11935 59.20855 -8.56413 7.03771 64.05474 -8.680271 5.63813 61.18338 -8.78601 7.12115 64.03425 -8.82568 9.29202 65.44601 -8.751231 9.44767 65.7546 -8.62564 9.636341 66.23487 -8.38246 7.53031 64.74487 -8.47667 8.6577 65.68396 -7.56946 8.64121 66.07729 -8.558011 8.55985 65.49423 -7.94615 8.50652 65.71537 -8.696411 8.16196 65.11563 -8.329851 8.34236 65.38905 -6.92121 8.54095 65.99626 -7.21787 9.4337 68.56859 -8.38561 8.73646 65.91035 -8.0265 9.09237 67.15675 -7.22853 8.73646 66.44991 -4.49019 11.49697 68.5388 -5.00295 11.49697 67.4331 -5.2479 11.49697 66.23879 -5.21216 11.49697 65.02297 -5.02849 11.49697 63.9566 -4.79562 11.49697 63.01096 -4.49486 11.49697 62.19946 -4.11076 11.49697 61.54702 -5.87529 11.27728 62.68823 -6.34615 11.17867 63.6878 -5.349 11.34554 61.80436 -6.50196 11.01932 62.49067 -4.1182 11.39697 60.46766 -4.73752 11.26217 59.66812 -8.95116 8.88449 64.98747 -8.999691 8.08742 64.55762 -8.999691 7.42452 63.58657 -8.999691 8.3286 64.17715 -8.999691 7.14456 62.79934 -8.999691 6.69775 61.89881 -8.999691 6.00432 60.89467 -8.999691 4.97055 59.84633 -8.999691 4.28585 59.33441 -8.999691 3.4615 58.85666 -8.999691 2.47985 58.44739 -8.999691 1.33074 58.15437 -8.999691 -0.003029942 58.03868 -8.999691 -8.00303 58.03868 -6.36582 8.496971 65.28314 -4.99969 8.496971 59.78465 -8.13012 6.30681 61.90997 -8.13014 7.19214 64.01679 -6.93326 7.94142 62.65234 -6.58044 7.94142 61.96633 -6.11115 7.94142 61.25299 -4.99969 7.74294 59.78465 -4.99969 6.96932 58.90087 -8.13012 5.2965 60.6067 -8.13012 5.74314 61.10729 -6.84235 6.16047 59.76889 -8.13012 4.75429 60.10451 -8.13012 2.37195 58.76642 -8.13012 3.31086 59.15787 -8.13012 4.09936 59.61484 -7.6639 4.10292 59.04662 -8.13012 1.85875 58.63554 -7.84539 -0.003029942 58.07458 -8.13012 -0.003029942 58.37546 -8.13012 1.27291 58.48615 -6.7759 11.08882 64.79447 -8.27241 10.00166 66.46892 -8.27242 10.0246 65.8769 -6.8477 11.04698 65.82941 -8.27241 9.94482 67.05044 -6.74099 11.04698 66.98962 -7.64224 10.22999 68.20881 -7.22061 10.36962 68.82871 -6.39505 11.04699 68.23342 -6.71649 10.50161 69.46391 -5.75694 11.04699 69.4929 -8.999691 7.99697 62.95621 -8.927841 8.649621 63.24892 -8.74119 9.21523 63.62119 -8.49871 9.656761 64.0787 -8.27242 9.955221 64.60336 -7.68264 10.48045 65.1977 -8.04445 10.19218 65.20199 -7.2836 10.70835 63.32394 -6.95376 10.83841 61.88823 -6.49814 10.94335 60.01643 -5.99969 10.99697 58.03868 -7.09799 -10.76947 56.60332 -8.02191 -10.21902 57.22966 -8.7221 -9.240941 57.79337 -8.878641 8.92703 50.79252 -8.45252 9.76334 50.79252 -7.78882 10.42703 50.79252 -6.95252 10.85315 50.79252 -9.02547 7.99998 24.47807 -5.98549 10.99998 23.80068 -1.04969 -10.85241 54.68365 4.4284 -11.00303 55.17134 2.76805 -11.00303 54.62267 3.2e-4 -11.00303 54.33267 -2.7671 -11.00303 54.62259 -6.66595 -10.93085 11.30388 -7.24205 -10.74227 10.48113 -7.83129 -10.39779 9.62842 -8.54841 -9.69898 9.75196 -8.9399 -8.71143 9.75318 -6.02547 -11.00002 12.21858 8.87231 -8.77648 35.85024 -6.06415 -10.98435 42.34554 7.47453 -10.5981 35.85024 5.97453 -11.00002 35.85024 -8.923251 8.77644 9.75318 -8.62354 9.49998 9.75318 -8.14679 10.1213 9.75318 -7.52547 10.59806 9.75318 -7.40258 10.61573 24.42709 -6.80193 10.89776 9.75318 -6.85997 10.85877 24.18378 -9.02547 -8.00002 50.79252 -9.02547 7.99998 9.75318 -9.02547 -8.00002 9.75318 -6.02547 10.99998 9.75318 -8.824561 -8.97048 8.23386 -8.35722 -9.83346 8.876931 3.09373 -11.00002 25.24129 3.84738 -11.00002 25.66956 6.02902 7.6054 24.02987 7.59724 9.3944 22.9318 3.09373 4.51538 25.24086 4.80132 6.77597 24.02629 5.53123 7.92272 23.5152 6.36547 8.9493 22.93106 7.25502 9.811901 22.3082 8.13969 10.48946 21.68875 -7.81194 10.19832 8.06339 -8.70497 9.17054 8.32644 -7.84819 9.52832 6.46801 -8.068511 7.48123 4.76029 -8.472001 8.99747 6.76388 -8.910571 8.171811 7.25133 -8.487151 6.71069 5.17098 -8.78339 5.53871 5.93756 -8.827071 6.93589 6.13376 -8.914441 4.52108 6.55495 -9.00809 3.44139 7.10285 -2.52488 10.7966 5.44341 -6.37604 10.87409 8.506071 -3.42532 10.53381 5.09353 -6.6197 10.62987 7.63714 -5.58596 9.524641 4.65381 -4.28238 10.18335 4.86431 -6.39769 9.05089 4.57325 -7.05581 9.89042 6.2647 -7.2777 8.324271 4.56418 14.71637 -1.00002 18.30448 9.11121 9.6154 22.22925 8.300021 8.9941 22.79724 7.48444 8.20316 23.36832 6.71983 7.26218 23.90371 6.05099 6.21134 24.37204 4.46876 -10.99931 25.47945 3.97006 4.3218 25.65569 13.48764 -11.00002 19.16484 -9.00962 -7.94523 7.95428 -9.022911 7.83078 8.60572 -9.13174 7.34492 7.32504 -9.01689 1.01905 7.80848 6.11848 10.99998 28.10642 13.48764 10.99998 19.16484 9.61673 10.99998 21.56325 10.27987 10.99998 21.33061 -1.38547 10.99361 6.36442 8.953721 10.99149 21.12506 7.6708 -10.77166 33.60986 8.5341 -10.12134 34.05927 9.11094 -9.14807 34.35955 8.38867 -9.86395 35.85762 8.97843 -10.8978 31.57137 15.04788 -10.47307 28.44679 9.39344 -10.5981 32.16406 14.55192 -10.22275 29.17261 9.749811 -10.12134 32.67301 13.96278 -9.723381 30.12993 10.02327 -9.50002 33.06355 10.19517 -8.77648 33.30905 6.4481 -10.99915 33.5315 6.9515 -11.00002 32.56861 7.68086 -11.00002 31.65925 8.53307 -11.00002 30.93533 6.07891 -11.00002 34.73596 7.24306 -10.99855 29.51986 15.24554 10.78862 17.93394 16.93588 10.16265 16.75036 18.4937 9.14615 15.65955 19.85915 7.77816 14.70346 20.97974 6.11126 13.91881 21.81242 4.2095 13.33576 22.32518 2.14598 12.97673 22.49832 -2e-5 12.85549 22.32518 -2.14601 12.97673 21.81242 -4.20954 13.33576 20.97974 -6.11129 13.91881 19.85915 -7.77819 14.70346 18.4937 -9.146181 15.65955 16.93588 -10.16269 16.75036 15.24554 -10.78866 17.93394 17.24874 10.99998 22.51061 18.17611 10.6563 21.81541 19.22166 10.40002 21.06122 20.96988 9.32311 19.90791 22.40247 8.07652 18.90565 23.59134 6.43999 18.07167 24.49215 4.54886 17.44142 25.06778 2.47712 17.03791 25.29603 0.30725 16.87835 25.16816 -1.87593 16.96807 24.68785 -3.98494 17.30406 23.87474 -5.93575 17.87369 22.76056 -7.65164 18.65359 21.39038 -9.063241 19.61331 19.8175 -10.11579 20.71426 16.31776 -10.99078 23.16249 18.10548 -10.76687 21.91349 17.38796 -11.00002 24.73507 16.96749 -10.97764 25.55215 16.34939 -10.84743 26.69325 15.72066 -10.57274 27.87064 15.38818 -10.15375 29.25569 9.11094 9.14803 34.35955 8.5341 10.1213 34.05927 7.6708 10.77162 33.60986 16.43848 10.92617 26.28057 8.97843 10.89776 31.57137 15.95405 10.80158 27.06688 15.4353 10.63526 27.8569 9.39344 10.59806 32.16406 14.92284 10.3992 28.68267 14.42861 10.14589 29.35819 9.749811 10.1213 32.67301 13.8656 9.76151 30.19668 10.02327 9.49998 33.06355 13.36479 9.1849 30.8831 10.19517 8.77644 33.30905 9.29688 -7.99607 34.43215 9.27742 7.99604 34.46957 18.4821 10.97335 27.63127 20.32549 10.89922 26.34051 16.66504 10.58775 28.90359 22.11796 10.36841 25.08541 14.91703 9.740321 30.12738 23.78436 9.403141 23.91859 12.34762 8.527811 31.90911 25.25485 8.04386 22.88894 10.02733 7.99865 33.54759 11.78197 7.99998 32.32275 26.46777 6.34756 22.03964 19.1087 -1.00002 27.19253 27.37233 4.38535 21.40626 27.93064 2.23951 21.01533 28.11937 -10e-6 20.88318 27.93064 -2.23954 21.01533 27.37233 -4.38538 21.40626 10.17767 -7.99948 33.44432 26.46778 -6.34759 22.03964 11.78197 -8.00002 32.32275 12.79827 -8.6266 31.61546 25.25485 -8.04389 22.88894 13.84475 -9.17023 30.85625 23.78437 -9.403181 23.91858 14.95047 -9.75869 30.10414 22.11796 -10.36845 25.08541 20.3255 -10.89926 26.34051 18.48211 -10.97339 27.63127 16.66505 -10.58779 28.90358 17.38796 10.99998 24.73507 7.68086 10.99998 31.65925 6.88393 10.9987 32.6926 6.40583 10.99998 33.61652 6.07891 10.99998 34.73596 8.53307 10.99998 30.93533 14.42391 10.99998 24.49159 16.29335 10.99998 23.17457 -4.52128 -9.4878 55.75693 -3.74877 -5.29607 55.4433 -4.04355 -10.02226 55.55492 -3.4412 -10.49866 55.33802 -3.27828 -5.11393 55.28461 -2.56465 -5.00303 55.08788 -0.86205 -5.00303 54.8185 3.1e-4 -4.00303 54.78465 0.86268 -5.00303 54.8185 2.0708 -4.00303 54.98126 2.56528 -5.00303 55.08788 3.24817 -5.10488 55.27505 3.85739 -5.34857 55.48305 4.06665 -4.00303 55.56384 4.39886 -5.66467 55.70235 -2.03629 -5.00303 55.45412 2.03692 -5.00303 55.45412 -1.59865 -5.00303 55.92377 1.59927 -5.00303 55.92377 -1.27058 -5.00303 56.4766 1.27121 -5.00303 56.4766 -1.06794 -5.00303 57.08608 1.06857 -5.00303 57.08608 -0.99969 -5.00303 57.72238 1.00031 -5.00303 57.72238 -0.99969 -5.00303 64.0526 1.00031 -5.00303 64.0526 1.2327 -5.00303 64.87756 -0.2222099 -5.00303 64.80972 0.22284 -5.00303 64.80972 -0.62317 -5.00303 65.00281 0.62381 -5.00303 65.00281 -1.36571 -5.07242 64.78465 -0.90065 -5.00303 65.35076 0.90128 -5.00303 65.35076 -1.16938 -5.00303 65.70529 1.17001 -5.00303 65.70531 -0.99969 -5.00303 65.78465 1.00031 -5.00303 65.78465 1.08593 -5.00303 66.22726 -1.07869 -5.00303 66.24315 0.86804 -5.00303 66.28169 -0.86541 -5.00303 66.28516 0.50304 -5.00303 66.64909 0.766 -5.00303 66.67245 -0.75402 -5.00303 66.68211 -0.4985 -5.00303 66.65135 0.002539992 -5.00303 66.78464 0.28178 -5.00303 66.92274 -0.26495 -5.00303 66.92662 2.00031 -6.00303 57.72238 2.00069 -6.00303 64.78463 2.00031 -9.00303 57.72238 2.00032 -9.00303 64.78465 3.2e-4 -10.00303 55.78465 -1.6658 -10.00303 55.83743 3.2e-4 -10.00303 56.18634 -1.38036 -10.00303 56.2598 3.2e-4 -10.00303 56.5271 -1.1707 -10.00303 56.72397 3.2e-4 -10.00303 56.7947 1.04338 -10.00303 57.21588 -1.04276 -10.00303 57.21584 1.00031 -10.00303 57.72238 -0.99969 -10.00303 57.72238 1.00032 -10.00303 64.78465 -0.99968 -10.00303 64.78465 -1.99969 -9.00303 64.78465 -1.99969 -6.00303 64.74483 -1.99969 -6.00303 57.72238 -1.99969 -9.00303 57.72238 4.41109 -6.00303 55.76503 4.41097 -9.00303 55.765 3.90525 -6.00303 55.72464 3.90519 -9.00303 55.72466 3.40663 -6.00303 55.81253 3.40656 -9.00303 55.81256 2.94624 -6.00303 56.02271 2.94618 -9.00303 56.02274 2.55335 -6.00303 56.34171 2.55329 -9.00303 56.34176 2.25301 -6.00303 56.7493 2.25292 -9.00303 56.74944 2.06435 -6.00303 57.22037 2.06428 -9.00303 57.2206 -4.41046 -9.00303 55.76503 -4.41046 -6.00303 55.76503 -3.90463 -9.00303 55.72464 -3.90463 -6.00303 55.72464 -3.406 -9.00303 55.81253 -3.406 -6.00303 55.81253 -2.94561 -9.00303 56.02271 -2.94561 -6.00303 56.02271 -2.55272 -9.00303 56.34171 -2.55272 -6.00303 56.34171 -2.25238 -9.00303 56.7493 -2.25238 -6.00303 56.7493 -2.06372 -9.00303 57.22037 -2.06372 -6.00303 57.22037 -2.71138 -5.29592 55.82565 -1.97344 -5.29592 56.64922 -1.92357 -5.62035 57.72238 -1.38239 -5.07915 57.72238 -1.69827 -5.2875 64.78465 -1.70681 -5.29593 57.72238 -1.92125 -5.61481 64.78465 -1.99475 -6.00303 64.92503 1.43195 -5.1104 65.0197 1.383 -5.07915 57.72238 1.69889 -5.28749 64.78465 1.70742 -5.29592 57.72238 1.92189 -5.61481 64.78465 1.92419 -5.62034 57.72238 3.74839 -5.30497 55.44583 2.71693 -5.29592 55.82231 1.97546 -5.29592 56.64659 1.86633 -9.50305 64.78465 1.92419 -9.38571 57.72238 1.70742 -9.710141 57.72238 1.50029 -9.869071 64.78465 1.383 -9.92691 57.72238 -1.49969 -9.86905 64.78465 -1.38237 -9.92691 57.72238 -1.70679 -9.710141 57.72238 -1.86571 -9.50303 64.78465 -1.92357 -9.38571 57.72238 -4.20886 -9.24626 55.70316 -3.45966 -9.511981 55.65247 -2.92259 -9.70494 55.70795 -2.03552 -9.710141 56.53943 -1.97107 -9.982 55.79823 -2.25367 -9.92569 55.77649 -2.52205 -9.845 55.75502 3.2e-4 -10.6697 54.80614 -2.4748 -10.61703 55.07125 3.2e-4 -10.97928 54.4856 1.05032 -10.85241 54.68365 3.1e-4 -5.00303 65.78465 -1.73699 -5.33823 64.96863 -1.92773 -5.64578 64.9364 1.73761 -5.33822 64.96864 1.92836 -5.64578 64.9364 1.2738 -5.02203 65.28942 -1.81236 -5.27567 66.19547 -2.10209 -5.9457 66.32501 -1.15964 -5.27567 67.2369 -1.32993 -5.9457 67.50003 3.1e-4 -5.9457 67.95538 3.1e-4 -5.27567 67.6433 1.33056 -5.9457 67.50003 1.16027 -5.27567 67.23691 2.10272 -5.9457 66.32501 1.81299 -5.27567 66.19547 3.2e-4 -10.04902 55.45229 3.2e-4 -10.18686 55.17287 3.2e-4 -10.40319 54.94949 -1.78668 -10.32127 55.11591 -1.73172 -10.1721 55.44402 -0.99968 -10.00303 66.28465 1.00032 -10.00303 66.28465 2.10272 -8.9457 66.32501 -2.10209 -8.9457 66.32501 -1.32993 -8.9457 67.50003 3.2e-4 -8.9457 67.95538 1.33056 -8.9457 67.50003 1.73346 -10.1721 55.44402 1.78841 -10.32127 55.11591 2.47653 -10.61703 55.07125 2.52378 -9.845 55.75502 2.25541 -9.92569 55.77649 1.97281 -9.982 55.79823 2.03725 -9.710141 56.53943 2.92432 -9.70494 55.70795 3.4614 -9.511981 55.65247 4.2106 -9.24626 55.70316 1.17244 -10.00303 56.72397 1.3821 -10.00303 56.2598 1.66754 -10.00303 55.83743 3.44294 -10.49866 55.33802 4.04529 -10.02226 55.55492 4.52302 -9.4878 55.75693 + + + + + + + + + + -0.1649913 -0.6948316 0.6999907 -0.1721701 -0.7020109 0.6910413 -0.001761078 -0.9999787 0.006306111 -0.05354905 -0.9985651 4.31618e-4 0 -0.9999853 0.005416333 -0.04209679 0.9915068 -0.1230532 -0.01462018 0.9915619 -0.1288076 -0.01424121 0.9915308 -0.1290889 0.01421946 0.9915563 -0.1288953 0.01463288 0.9915258 -0.1290829 -9.45874e-4 0.9999995 -2.75816e-4 0 1 0 9.45802e-4 0.9999995 -2.75797e-4 0 1 -5.62796e-7 -0.04752063 0.9918997 -0.1178006 -0.04460251 0.9908388 -0.1274722 -0.0209524 0.9922773 -0.1222574 -0.01555109 0.9904482 -0.1370059 0.01553356 0.9904451 -0.1370306 0.02095091 0.992278 -0.1222517 0.04459136 0.9908379 -0.1274833 -0.09152621 -0.9255648 0.3673595 -0.09962093 -0.9288853 0.3567183 -0.9997834 -0.01466178 0.0147705 -0.9997619 -0.02028119 0.008049607 0 0 1 0 9.15527e-7 1 -2.54232e-6 0 1 5.21748e-6 4.42364e-7 1 -3.99101e-6 3.27362e-7 1 6.66583e-7 2.03894e-7 1 -6.85975e-7 0 1 -1.01054e-6 0 1 0 1 3.03796e-7 -0.1070449 -0.9371769 0.3320255 0.09366083 0.9526445 0.2893031 0.07027649 0.9478526 0.3108645 0.03296262 0.9525761 0.3025102 0.1710513 0.9616234 0.2145274 0.170564 0.9612507 0.2165763 0.1373319 0.9475182 0.2887031 0.1941366 0.9599949 0.2017938 1.64067e-4 0.947441 0.3199306 -0.03234237 0.9524948 0.3028332 -0.0702055 0.947474 0.3120327 -0.09559798 0.9524619 0.2892705 -0.1370388 0.9475119 0.2888625 -0.1943265 0.9599201 0.2019675 -0.1703899 0.9612233 0.216834 -0.1709738 0.9616587 0.2144308 0.2945978 -0.6401463 0.7095244 0.4621928 0.520227 0.7181515 0.4447255 0.03811693 0.8948556 0.5324525 0.4039812 0.7438371 0.3903992 -0.607651 0.6916277 0.4301537 -0.5448167 0.7198211 0.6097354 0.4163067 0.6744713 0.4501203 -0.6295406 0.6333012 -0.3400422 -0.6262998 0.7015125 -0.2321826 -0.6087532 0.7586243 -0.2235071 -0.5177029 0.82585 -0.2764285 0.3216638 0.9056047 -0.2873381 0.2939417 0.9116113 -0.1316081 0.4608884 0.8776453 0 -0.5819404 0.8132315 -0.01398259 -0.6233065 0.7818527 0 0.3165683 0.9485698 0.02349615 0.3835867 0.9232059 0.1803507 0.4457492 0.8768018 0.2523601 -0.5058119 0.8249053 0.1552654 -0.637186 0.7549085 0.280397 0.2788872 0.9184768 0.30397 0.3430842 0.8887608 -0.4526972 -0.6392863 0.6215934 -0.5942116 0.4216408 0.6849319 -0.4963668 0.3667149 0.7868546 -0.5515088 0.1911107 0.811982 -0.4038592 0.4439662 0.79987 -0.4172447 -0.5407997 0.7303715 -0.4120207 -0.6063383 0.6801418 -0.1441041 -0.9396946 0.3101745 -0.1445457 -0.9396927 0.3099747 -0.1445367 -0.939693 0.3099778 -0.1214696 -0.9360834 0.330141 0.1333814 -0.9358308 0.3262363 0.1445405 -0.9396934 0.3099747 0.1443963 -0.9397105 0.3099902 0.1445427 -0.9396937 0.3099728 -0.1431046 -0.9386916 0.3136546 -0.105059 -0.9425655 0.3170695 -0.09280955 -0.9347646 0.3429309 -0.03535211 -0.9430717 0.3307057 0.04524517 -0.9048495 0.4233204 -0.005543947 -0.9507276 0.3099778 0.07081139 -0.9361991 0.3442631 0.1039929 -0.943526 0.3145541 -0.3968706 0.8348858 0.3813916 -0.3206754 0.8547815 0.4080635 -0.3302763 0.8481298 0.4142384 -0.2594506 0.8268504 0.4990028 -0.2167999 0.8626601 0.4569631 -0.1682317 0.8287419 0.5337461 -0.1321747 0.7983877 0.5874581 -0.06546187 0.8972992 0.4365421 2.79591e-4 0.8386591 0.5446568 0.01265048 0.8676701 0.4969797 0.1118673 0.8617613 0.4948264 0.1081499 0.8436916 0.5258216 0.176509 0.8381801 0.5160413 0.2502694 0.8127468 0.5261253 0.2328509 0.8649675 0.4445356 0.3353143 0.8404036 0.4257771 0.3252812 0.8609095 0.391187 0.181529 0.9748023 -0.1296447 0.1700085 0.9772837 -0.1265456 0.304315 0.9524689 -0.01397544 0 1 0 -0.6998944 0 0.7142464 -0.7174819 0.002581715 0.6965724 0.853614 0.2229917 0.4707632 0.7894543 0.3702695 0.4895535 0.9614089 0.2549018 0.103528 -0.7132805 -0.6853018 0.1469433 0.1710772 -0.9322444 0.3188307 0.1746981 -0.9329795 0.31469 0.9970929 0.07281225 -0.02245032 0.9409615 0.3362115 -0.03941202 0.9181088 -0.2835884 0.2768644 0.7114064 -0.3320831 0.6193721 -0.4350414 -0.6582537 0.6143622 0.1755031 -0.9263921 0.3331615 0.2001904 -0.5680593 0.7982684 -0.3647494 -0.927789 0.07852184 0.9924112 -0.005810379 0.1228263 -0.3666052 -0.9272953 0.07565891 0.6986212 -0.4543409 0.5527231 0.4867461 -0.5134593 0.7067092 0.9360098 -0.05072003 0.3483005 0.9406656 -0.09920972 0.3245086 0.9985204 -0.05405843 0.005904078 0.9643741 -0.18409 0.1899833 0.4964783 -0.6811487 0.5380947 0.7484675 -0.5876221 0.3074032 0.3378761 -0.8061444 0.4857684 0.2491627 -0.6246939 0.740051 -0.3804789 -0.9247153 -0.01171851 -0.4030982 -0.9021154 0.1539478 -0.3957089 -0.900009 0.1827517 -0.1494771 -0.8515211 0.5025619 0.04363191 -0.784659 0.6183902 0.3300208 -0.719429 0.6111533 0.2395932 -0.7246546 0.6461198 0.1832863 -0.6922984 0.6979464 0.1259024 -0.5479865 0.8269579 -0.2286155 -0.8833224 0.4092389 -0.6981346 -0.6957037 0.169129 0.09771686 -0.921039 0.3770129 1.32489e-6 1.38119e-6 1 4.75416e-6 1.15212e-6 1 -1.69413e-5 -3.9205e-6 1 2.45604e-6 0 1 -4.04053e-6 0 1 8.02947e-6 0 1 -1.23222e-5 0 1 -0.4555901 -0.2583937 0.851863 -0.2931705 -0.7044121 0.6464167 -0.1384958 -0.9539642 0.2660291 0.9582874 -0.2446018 0.1478354 0.8154289 -0.5787826 -0.009301602 0.9409943 -0.2477343 0.2305592 0.4446534 -0.8874356 0.1214151 0.3385215 -0.9396896 0.04885286 0.4061926 -0.8900536 0.2069111 0.6160272 -0.7054057 0.3505901 0.7145048 -0.3091562 0.6276188 -0.06004381 -0.9436119 0.3255631 -0.1934021 -0.8588019 0.4743997 -0.0176416 -0.7925394 0.6095654 0.008517444 -0.9368408 0.3496527 0.6575267 -0.325846 0.6793255 0.5071847 -0.6845967 0.5235371 0.3477866 -0.2695927 0.897978 0.2198952 -0.6634022 0.7152228 0.03121852 -0.8383212 0.5442821 -0.3118229 -0.7055625 0.6363554 -0.07666134 -0.5207408 0.850266 0.04716885 -0.2458003 0.9681722 -0.1088833 -0.1910598 0.9755207 -0.210868 -0.4659456 0.8593192 -0.2874101 -0.5378904 0.7925083 -0.4224039 -0.48541 0.7654752 -0.3679085 -0.4636559 0.806019 -0.5349411 -0.1696726 0.8276771 -0.5029341 -0.1015844 0.8583344 -0.5728848 -0.1418024 0.8072764 -0.5762851 -0.1463951 0.80403 -0.5563005 -0.06916993 0.8280975 -0.5202074 -0.258749 0.8138999 0.9712756 0 0.2379572 0.9712758 0 0.237957 0.7512769 0 0.6599873 0.7512967 6.26147e-7 0.6599646 0.3611996 1.81612e-6 0.9324885 0.3611713 0 0.9324996 -0.1108073 1.84734e-6 0.993842 -0.1108706 -1.95691e-6 0.9938349 -0.557618 1.25241e-7 0.8300977 -0.5576326 0 0.8300879 -0.7263312 0 0.6873449 -0.7273804 -7.9725e-5 0.6862346 -0.6950691 3.81596e-4 0.7189429 -0.6148318 -0.003780603 0.7886493 -0.6557519 -0.02015453 0.7547074 -0.5389025 3.441e-4 0.8423681 -0.4896452 -0.001503527 0.8719205 -0.4715842 0.00881505 0.8817771 -0.4835572 0 0.8753128 -0.3559123 -0.9278683 0.111296 -0.3559927 -0.9277235 0.1122428 -0.3430498 -0.9279015 0.1459988 -0.3430542 -0.9276238 0.1477431 -0.3248466 -0.9279538 0.1826925 -0.3246483 -0.9274771 0.1854448 -0.2998468 -0.9280352 0.221004 -0.2992256 -0.927275 0.2250009 -0.2663717 -0.9281536 0.2599559 -0.2649515 -0.9269988 0.2654696 -0.2226701 -0.9283236 0.2977137 -0.2198991 -0.9266228 0.3049829 -0.1672711 -0.9285647 0.3313429 -0.1623424 -0.9261431 0.3404467 0.06865757 -0.9834015 0.1679518 0.05806756 -0.9880294 0.1429201 0.2754485 0.9612818 -0.008096873 0.2663117 0.9637091 -0.01851654 0.2767171 0.960617 0.02535045 0.2631749 0.963237 0.05397695 0.2677152 0.9606307 0.07427871 0.2457131 0.9626223 0.1139457 0.2470974 0.9609031 0.1249334 0.2147547 0.9619797 0.1687472 0.2145751 0.9610776 0.1740327 0.09300851 0.9914769 -0.09123063 0.1393717 0.9861059 -0.09039109 0.1375482 0.9871772 -0.08100384 0.1494109 0.9872235 -0.05537384 0.1887493 0.981343 -0.03660351 0.2000921 0.9797741 0.002411723 0.2238271 0.9730693 -0.05511367 0.2774343 0.960722 0.006598651 0.2270973 0.9730862 -0.03911453 0.06819635 0.9915381 -0.1104605 0.0717718 0.99107 -0.1123787 0.04751652 0.9919003 -0.1177967 0.8590837 -0.4199503 0.2926041 0.8458898 -0.4757149 0.241176 0.7125622 -0.6051212 0.3550825 -0.1544006 -0.8824839 0.4442777 -0.3331201 -0.828282 0.450533 -0.2679651 -0.5957421 0.7571566 -0.2765297 -0.592945 0.7562722 0.8747743 -0.2989572 0.3813062 0.9271588 -0.2546443 0.2748327 0.8820412 -0.2822083 0.3773084 0.8304428 -0.2794366 0.4819543 0.8192807 -0.2207296 0.5292048 -0.2138186 -0.3760391 0.9015965 -0.1083643 -0.2059155 0.9725514 -0.5534307 -0.1223037 0.8238667 -0.713365 -0.06059384 0.6981682 -0.4047765 -0.2260598 0.8860322 0.8678297 -0.1354717 0.4780366 0.848407 -0.1308484 0.5129174 0.9710696 -0.02064651 0.2379029 0.7510238 0.02514642 0.6597962 0.3573265 0.1460809 0.9224848 0.9375442 -0.3378773 0.08276367 0.368851 -0.8658302 0.3380637 0.4026481 -0.8445541 0.3529915 0.3081966 -0.8786112 0.3647702 0.7923576 -0.4863625 0.3682674 0.7305451 -0.5583623 0.3931099 0.9395713 -0.1465376 0.3094068 0.9284114 0.2902234 0.2319975 0.9282012 0.2916213 0.2310837 0.5276768 -0.5684689 0.6311897 0.5146474 -0.5832424 0.6284636 0.6990635 0.2892489 0.6539459 0.6960343 0.2585837 0.669829 0.7332642 0.3930043 0.5548616 0.5154269 -0.6393487 0.570586 0.7147815 -0.4432377 0.5409508 0.5037174 -0.6912536 0.5181095 0.6268813 -0.58202 0.5179505 0.5468428 -0.6432499 0.5359036 0.8545976 0.2361449 0.4624918 0.873515 0.3251417 0.3622907 0.7715889 0.6347616 0.0415728 0.7841985 0.6195056 -0.03529417 0.7531374 0.6424796 -0.1414353 0.8286025 0.5490723 -0.10926 0.3052155 -0.6570729 0.6892741 0.2745088 -0.7721978 0.5730232 0.1955801 -0.8704637 0.4517095 0.25684 -0.8716261 0.4174938 0.1448611 -0.9397497 0.3096547 0.1440238 -0.939967 0.3093852 0.143891 -0.9399989 0.3093502 0.1437281 -0.9400298 0.309332 0.1435382 -0.9400581 0.309334 0.1433849 -0.9400723 0.3093621 0.1033923 -0.9394617 0.3266829 0 1 -9.6449e-7 0 1 1.09329e-6 0 1 0 0 1 -1.00672e-6 0 1 5.00193e-7 0.04527223 0.996233 -0.07396173 0.21031 0.9718139 -0.1065244 0.06837558 0.9914932 -0.1107527 0.04277241 0.9915733 -0.1222826 0.04209566 0.9915073 -0.1230503 0.5424768 0.839224 -0.03770893 0.5673756 0.8141562 -0.123429 0.4393406 0.8979291 0.02652215 0.4497515 0.8931401 0.004952311 0.414958 0.9036079 -0.1063147 0.3733166 0.9276967 0.003698647 0.3258244 0.9375778 -0.1215997 0.1322396 0.9911994 -0.006046712 0.9976606 0.05944401 -0.03376162 0.9976135 0.05955141 -0.03494405 0.9997448 0.02255862 0.001182854 0.9999992 9.01195e-4 -9.72198e-4 0.9999993 7.40967e-4 -9.9205e-4 0.9999982 9.52554e-4 -0.001641333 -0.006302535 -0.9999618 0.006067037 -0.009136378 -0.9999578 0.001016259 -0.008571147 -0.9999616 0.001846075 -0.008046209 -0.9999645 0.00251609 -0.007454752 -0.9999673 0.003171563 -0.006781637 -0.9999698 0.003814399 -0.006014704 -0.9999722 0.004433214 -0.005139946 -0.9999743 0.005016267 -0.004145324 -0.9999762 0.005542099 -0.003020942 -0.9999776 0.005984246 -0.6485068 -0.668688 0.3637242 -0.7839902 -0.569435 0.2471906 -0.7289426 -0.6083524 0.3139266 -0.6780672 -0.6246666 0.3873195 -0.6296132 -0.6111657 0.4796497 -0.6313034 -0.6132703 0.4747163 -0.7179128 -0.4304578 0.5470898 -0.6374452 -0.384693 0.6675889 -0.6809163 -0.2819164 0.6759263 -0.671043 -0.1832921 0.7184048 -0.5739864 -0.0708028 0.8157983 -0.7172813 -0.1574243 0.6787675 -0.6923002 -0.1468495 0.7065096 -0.5501441 -0.627298 0.5512157 -0.499164 -0.6101937 0.6152226 -0.534205 -0.5139493 0.671179 -0.6629009 -0.3759032 0.6475023 -0.4550549 -0.6281846 0.6311175 -0.4357333 -0.6285614 0.6442415 -0.3184041 -0.6728956 0.6677054 -0.2965649 -0.6659894 0.684476 0.405238 0.837207 0.367242 0.4044098 0.8537454 0.3279813 0.453079 0.8312928 0.3219808 0.4888501 0.8366203 0.2471681 0.4901221 0.8324396 0.2585049 0.5333657 0.8204053 0.2060497 0.5503077 0.8208811 0.1526951 0.5477446 0.8253557 0.1369814 0.5793628 0.8100057 0.09071832 0.5819913 0.8114454 0.05331557 0.5820857 0.8113893 0.05314046 0.5823394 0.8117495 0.04408514 0.6389082 0.7680376 -0.04375475 0.8724383 0.4887226 0.001351833 0.6629804 0.7486205 -0.004945397 0.535577 0.8444864 -4.16936e-4 0.468789 0.8833102 -3.08288e-4 0.3918539 0.9200267 -0.001252353 0.2487961 0.9685559 4.23942e-4 0.1085256 0.9940937 8.74665e-6 -0.5629857 0.8262389 -0.01940155 -0.4187536 0.9037044 -0.08923989 -0.9004355 -0.2593656 0.3492071 -0.9384176 -0.1179853 0.3247339 -0.3430843 0.9296273 -0.1344853 -0.1209133 0.9899573 -0.07324415 -0.9531967 0.2031885 0.2238987 -0.9473427 0.291131 0.1333594 0.1918201 -0.8630257 0.4673241 -0.1259092 -0.5479874 0.8269564 -0.1824743 -0.6903214 0.700114 -0.2407373 -0.7234773 0.6470134 -0.331602 -0.7177672 0.6122503 -0.04400926 -0.784482 0.6185882 0.3612753 -0.8701928 0.3350293 -0.1031784 -0.9369419 0.3339074 -0.306599 -0.6554296 0.6902241 -0.2490028 -0.6207476 0.7434177 -0.5460386 -0.6984413 0.4626247 -0.465833 -0.6891033 0.5551002 -0.4866088 -0.6858597 0.5411177 -0.9643701 -0.1840913 0.1900019 -0.9393252 -0.2293954 0.2550414 -0.974457 0.2097489 0.0802434 -0.9417774 -0.1188834 0.3145188 -0.4720004 -0.5159746 0.7148329 -0.5530725 -0.4998519 0.6665275 -0.08362573 -0.975494 0.2035146 -0.9562017 0.2784496 0.09024453 0 1 8.87784e-5 0 -1 0 -0.7755035 -0.6209397 0.1141412 -0.9238817 -0.2623789 0.2785675 -0.9365104 -0.2651529 0.2294391 -0.4514099 -0.8852446 0.1121219 -0.6910754 -0.6792568 0.2470327 -0.718788 -0.2910559 0.6313718 -0.4322356 -0.8915157 0.1355438 -0.2139084 -0.9764392 -0.02845603 -0.4819161 -0.699472 0.527727 -0.6472725 -0.3049315 0.6986094 -0.2013591 -0.8733079 0.4436078 -0.3795996 -0.7014803 0.6031829 0.1195468 -0.9101178 0.3967297 -0.0695433 -0.8380956 0.5410726 3.32468e-4 -0.9541008 0.2994855 -0.3474875 -0.2725121 0.8972122 -0.1370828 -0.6223405 0.7706496 -0.2889722 -0.2736134 0.9174044 0.1317057 -0.6925151 0.7092789 0.0084275 -0.5754355 0.8178038 0.2606684 -0.5980051 0.7579194 0.3609135 -0.63714 0.6810244 0.2952538 -0.7045676 0.6452983 0.1086129 -0.1969487 0.9743791 0.119237 -0.1963267 0.9732618 0.2261431 -0.4302094 0.8739446 0.4866968 -0.2608748 0.833709 0.4919068 -0.2657517 0.8290982 0.5243039 -0.2285252 0.8202937 0.5331749 -0.2320426 0.8135606 0.491859 -0.3073351 0.8146287 0.5759968 -0.1382085 0.8056837 0.5464025 -0.07521688 0.8341383 0.5562836 -0.06906449 0.8281176 0.2931663 -0.7044203 0.6464098 0.412343 -0.3059164 0.8581309 0.1180198 -0.9657306 0.2311617 -0.9712756 0 0.2379572 -0.9712756 0 0.2379572 -0.7512963 0 0.6599652 -0.7512962 0 0.6599652 -0.3611708 0 0.9324998 -0.3611987 0 0.9324889 0.1107804 0 0.993845 0.1107804 0 0.9938449 0.5576156 0 0.8300992 0.5576156 0 0.8300993 0.4167314 -0.06069314 0.9070013 0.4415508 -0.03338313 0.896615 0.49187 0 0.8706688 0.485781 -0.001645684 0.8740791 0.4715737 0.00882256 0.8817825 0.5668327 0.001422226 0.8238318 0.6148238 -0.006633281 0.7886368 0.6315412 -0.002502679 0.7753384 0.6999132 0 0.714228 0.7153864 0.002269804 0.6987254 0.6954473 3.81612e-4 0.718577 0.7263305 -6.44912e-5 0.6873456 0.7275732 0 0.6860302 1 0 0 0.9690704 -0.1455959 -0.1992596 0.8296401 0 0.5582987 0.8183952 -0.5591333 0.1326618 0.2641188 -0.9384379 0.2226558 0.3083119 -0.9294099 0.2028329 0.3333473 -0.9270858 0.1714398 0.3423981 -0.9314887 0.1228517 0.4173743 -0.9031388 0.1006937 -0.01779687 -0.9987017 0.04773116 -0.2465085 0.9682102 -0.04245668 -0.2326043 0.9725051 -0.01136702 -0.2238143 0.9730722 -0.05511677 -0.2000851 0.9797757 0.002404332 -0.1797854 0.9814465 -0.0666331 -0.1646926 0.9861017 -0.02190858 -0.1375564 0.9871781 -0.08097928 -0.139383 0.9861036 -0.0903995 -0.09302467 0.9914766 -0.0912171 -0.2144753 0.9610524 0.1742947 -0.2146789 0.9620077 0.1686838 -0.2470529 0.9608838 0.1251693 -0.2456656 0.9626367 0.1139255 -0.2677079 0.9606196 0.07444846 -0.2631635 0.9632403 0.05397385 -0.2767119 0.9606159 0.02544915 -0.2688867 0.9631395 -0.007902383 -0.2554129 0.9665963 0.02135527 -0.06967389 0.9911667 -0.1128461 -0.06977134 0.9915632 -0.1092451 -0.6454412 -0.570699 0.5076498 -0.6437108 -0.5743157 0.5057647 -0.8400875 0.2612572 0.4753922 -0.6797798 0.6453154 0.348522 -0.8839559 0.08801579 0.4592117 -0.8141444 0.3264353 0.4802176 -0.757463 0.3963721 0.5187862 -0.5314285 -0.5619884 0.6338399 -0.4964218 -0.6743922 0.5465901 -0.6934289 0.328139 0.6414679 -0.6976376 0.3152927 0.6433447 -0.7042404 -0.6028192 0.3750396 -0.5509056 -0.706427 0.4443691 -0.9400386 -0.1471221 0.3077054 -0.953854 0.196794 0.226792 -0.7960029 0.5932005 0.1203864 0.3300366 -0.8072449 0.4893175 -0.2001889 -0.5680668 0.7982636 -0.1971267 -0.7726762 0.6034173 -0.3389641 -0.7678869 0.543556 -0.5601394 -0.4293831 0.7084307 -0.9315479 -0.309431 0.1909739 -0.9203815 -0.3229451 0.220464 0.5561901 -0.07182657 0.8279455 0.1108207 -1.47243e-5 0.9938405 -0.3564284 0.1562899 0.9211581 -0.3564284 0.1562899 0.9211582 -0.3564284 0.1562899 0.9211581 -0.3531406 -0.2099508 0.9117085 -0.7445072 -0.1339738 0.6540337 -0.9712256 0.01020544 0.2379428 -0.9418966 -0.02902692 0.3346466 -0.8757879 -0.1192691 0.4677291 0.4329975 -0.2010612 0.8786851 0.5069862 -0.212993 0.835224 -0.8193172 -0.2206298 0.52919 0.2139233 -0.3759058 0.9016274 -0.8367201 -0.337892 0.4309625 -0.9448633 -0.1642001 0.2833224 -0.9029375 -0.2573451 0.3442056 -0.8233859 -0.4040679 0.3984529 0.4040837 -0.56439 0.7198475 0.6361946 -0.5242626 0.5660435 0.4292011 -0.5408458 0.7233756 0.2464176 -0.4859619 0.8385221 0.228307 -0.7264661 0.6481689 -0.3530641 -0.8353092 0.4214311 0.338024 -0.8513029 0.401277 0.5200547 -0.7874316 0.3308998 0.2294226 -0.796544 0.5593596 -0.8175809 -0.5226868 0.2415778 -0.9708203 -0.1973292 0.1362694 -0.9363337 -0.3145253 0.1560553 -0.8978934 -0.4147658 0.1475022 -0.9916682 0.1243146 -0.03376692 -0.9546853 0.296244 0.02855658 -0.9338579 0.3528957 -0.0580886 -0.9701176 0.2232444 -0.09504646 -0.8466308 0.5286219 -0.06144422 -0.7798321 0.6256825 -0.01957976 -0.7515898 0.6591453 0.02530544 -0.7561105 0.6475699 -0.09460526 -0.7660733 0.6289641 -0.1324239 -0.7627729 0.6444337 -0.05369168 -0.7271167 0.6859987 0.02659392 -0.7380317 0.6715655 0.06564307 -0.1805445 -0.9041571 0.3871741 -0.1912987 -0.8946574 0.4037241 -0.2423312 -0.8160437 0.5247364 -0.2744257 -0.7722349 0.5730131 -0.1497854 -0.9392872 0.3087134 -0.1492035 -0.9378125 0.3134424 -0.1485668 -0.9376189 0.3143225 -0.1403786 -0.9402695 0.3101405 -0.1445444 -0.9396938 0.3099722 -0.1445459 -0.9396917 0.3099774 0 1 3.02082e-7 0 1 -3.75522e-7 0 1 1.19789e-6 0 1 -4.1674e-7 0 1 4.57624e-7 0 1 -2.00213e-7 0 1 2.18865e-7 0 1 4.81676e-7 -0.3586186 0.9302901 -0.07715642 -0.3415971 0.9305971 -0.1315308 -0.4274174 0.9017574 -0.06440621 -0.3705775 0.9288011 -9.95153e-4 -0.2694818 0.9591634 -0.08593654 -0.1757986 0.9843481 0.01239681 -0.181824 0.9831443 -0.01916992 -0.04278308 0.9915738 -0.1222747 -0.06792074 0.9915012 -0.11096 -0.06979429 0.9911363 -0.1130382 -0.07000792 0.9917711 -0.107187 -0.9985601 0.04530972 0.0287224 -1 0 0 -0.9999998 -1.22816e-4 6.69975e-4 -0.9999991 -0.00129801 6.43763e-4 -0.9999994 -9.48486e-4 6.55864e-4 0.006737589 -0.9999659 0.004790067 0 -1 -6.79369e-7 0.6689662 -0.7179136 0.1925731 0.713659 -0.6457888 0.2713813 0.6746267 -0.6515336 0.3469625 0.64887 -0.6298758 0.4268773 0.6481493 -0.626659 0.4326674 0.5822661 -0.6480954 0.490855 0.5389491 -0.6397618 0.5479405 0.5623564 -0.6221929 0.5446388 0.5410237 -0.5465663 0.639186 0.6057397 -0.4677963 0.6436195 0.6642187 -0.4694294 0.5817643 0.6822637 -0.4967961 0.536386 0.6824778 -0.5453812 0.4866039 0.6531258 -0.6197125 0.4351818 0.6059808 -0.4735791 0.6391481 0.7001823 -0.4275252 0.5718103 0.3176993 -0.234312 0.9187845 0.6580807 -0.2897439 0.6949664 0.7268456 -0.344377 0.5942221 0.6651231 -0.265991 0.6977536 0.7415592 -0.3835223 0.550455 0.6948758 -0.2050951 0.6892632 0.7075576 -0.1746121 0.6847429 0.6983307 -0.06705379 0.7126276 0.723989 -0.08034831 0.6851162 0.7042465 -0.06135988 0.7072989 -0.5587503 0.8293195 -0.005236923 -0.6231718 0.7819142 -0.01634794 -0.581666 0.8124344 0.04018706 -0.5818991 0.8114981 0.05352056 -0.5660099 0.8204883 0.08019936 -0.5820464 0.8125454 0.03149521 -0.5772551 0.8084235 0.1150137 -0.5437529 0.8255077 0.1512278 -0.5412178 0.8206696 0.1832619 -0.4846032 0.83957 0.2455241 -0.5106843 0.8274944 0.2333555 -0.473802 0.8160134 0.3311101 -0.404367 0.8535234 0.3286108 -0.9940275 0.1091284 6.7453e-4 -0.9502459 0.3114846 0.003183603 -0.8758803 0.4825264 -0.001455664 -0.7870848 0.6167401 -0.01136648 -0.7203364 0.6936249 -2.4322e-4 -0.5410431 0.8408954 -0.01294517 -0.6231708 0.7820657 -0.005627155 -0.386107 0.9224398 -0.005141913 -0.2194848 0.9756151 0.001271545 -0.9296176 -0.3685257 1.52643e-4 -0.8124017 -0.5830925 0.002622127 -0.6979137 -0.7161819 -1.05137e-4 -0.5112339 -0.8594409 0.001180469 -0.2523711 -0.9676234 -0.003716409 -0.5182508 -0.8551351 0.01266098 0.07104653 -0.9424952 0.3265812 0.1304501 -0.9094547 0.3948101 0.2588169 -0.9659263 -4.76069e-4 0.1297771 -0.9914882 -0.01044368 0.3662033 -0.9305344 -0.001050949 0.8147502 -0.5797731 -0.006740868 0.9917746 -0.1279317 0.004085242 0.9757367 -0.218944 -0.001220405 -0.1989517 -0.9800093 3.43677e-4 -0.9756191 -0.2194445 0.003379762 7.64159e-5 -1 -1.49634e-4 -0.001448273 -0.999999 -2.71638e-4 6.59623e-4 -0.9999979 -0.001996397 1.72426e-4 -0.9999987 -0.001645386 -1.5504e-4 -0.999999 -0.001479923 -4.61768e-4 -0.9999989 -0.001397788 -0.005196452 -0.9999862 -7.93189e-4 0.9999995 -5.68447e-5 -0.001117169 0.9999988 6.15486e-4 -0.001474797 0.9999991 3.43773e-4 -0.001350104 0.9999993 1.09861e-4 -0.001252174 0.9999994 0 -0.001213312 -0.9999995 -6.79884e-4 6.70642e-4 -0.9999997 -5.13006e-4 6.85025e-4 -0.9999998 -4.04092e-4 6.96582e-4 -0.9999998 -2.96828e-4 7.10758e-4 -0.9999997 -1.85201e-4 7.28715e-4 -0.9999998 -6.56944e-5 7.52586e-4 -0.9999997 0 7.68154e-4 -0.9999766 0.005854964 0.003560006 0.9658368 0.2590905 -0.005609154 0.7071046 0.7071055 -0.002238035 0.3826829 0.9238793 -0.001045882 0.1305231 0.9914451 -5.27442e-4 -0.9865429 0.1635021 -2.55382e-4 -0.8909943 0.4539836 0.005311489 -0.7070443 0.7070566 0.01263242 -0.4539932 0.8910045 0.001132726 -0.1494356 0.9887716 2.4953e-5 -0.1215342 0.9925803 -0.003719329 5.38233e-5 1 8.79221e-5 -8.30889e-5 1 1.35774e-4 1.01092e-5 1 9.15667e-5 3.05188e-5 1 8.92091e-5 -0.1079072 -0.994161 3.7858e-4 -0.3169037 -0.948447 0.004509031 -0.9738232 -0.2272989 0.001909673 -0.9928438 -0.119421 0 -0.9876886 0.1564338 0 -0.9914454 0.1305215 5.9877e-4 -0.9238749 0.3826948 -3.99985e-4 -0.8910064 0.4539902 7.99673e-4 -0.7933559 0.6087579 -6.00428e-4 -0.707102 0.7071111 9.00005e-4 -0.6087593 0.7933442 0.00414282 -0.5299776 0.84801 -0.0016945 -0.4539936 0.8910049 -2.73693e-4 -0.3826833 0.9238791 9.57103e-4 -0.4079104 0.9130191 0.002316653 -0.4092361 0.9124277 -0.001230716 -0.1305229 0.991443 0.002153635 -0.1595622 0.9871879 -3.46511e-4 -0.1592211 0.9872429 4.53165e-4 0.3703373 -0.8919042 -0.2595327 9.77697e-4 0.9999995 -5.41143e-4 -0.9811344 -0.1886386 -0.04231953 -0.9927677 -0.1194115 -0.01238405 -0.6824204 0.5101541 -0.5234934 -0.4450687 0.6014035 -0.6634967 0.8191503 -4.44622e-5 -0.5735791 -0.8925995 0.2543604 -0.372246 -0.8834135 0.2795027 -0.3761101 0.4940613 -2.40483e-5 -0.8694272 0.4270853 -0.004238128 -0.9042015 -0.2925593 0.001476824 -0.9562463 0.8191344 -1.58517e-5 -0.5736018 0.8220404 -0.008593678 -0.5693643 0.8215675 -0.007159709 -0.5700664 0.8151795 0.009906828 -0.5791237 0.8193041 4.15311e-5 -0.5733592 0.821676 -0.005285561 -0.5699303 0.8191466 -3.65216e-5 -0.5735841 -0.9295937 -0.3685048 -0.007738053 -0.84092 -0.531448 -0.1020618 -0.7010957 -0.7117207 -0.04380255 -7.41454e-4 -0.9999997 5.19183e-4 0.2344753 -0.5915774 -0.7713998 -0.3525118 -0.2283077 -0.9075301 0.4053244 -0.5969624 -0.6923497 0.3868564 -0.5694809 -0.7252817 -0.2854041 -0.2326986 -0.929729 -0.3081062 -0.2866998 -0.907124 -0.2580854 -0.3107728 -0.9147744 0.2352523 -0.6498371 -0.7227504 0.3082614 -0.6472194 -0.6971958 -0.3391637 -0.2951932 -0.8932127 0.2636036 -0.7284495 -0.6323564 -0.3482715 -0.3146098 -0.883022 -0.4024048 -0.2733401 -0.8737023 0.3257275 -0.8163 -0.4770284 0.007206141 -0.751901 -0.6592366 0.1662907 -0.7747772 -0.6099736 -0.3140775 -0.315967 -0.8952766 0.8254032 -0.1606515 -0.5412031 0.794644 -0.3281183 -0.5107636 0.7709919 -0.3999573 -0.4955863 0.6005789 -0.6798083 -0.4209104 0.7283819 -0.494396 -0.4743758 0.6460554 -0.6135708 -0.4540304 0.6546218 -0.600449 -0.4592726 0.5810586 -0.7042791 -0.4078749 0.5834539 -0.7015136 -0.4092193 0.6085304 -0.669809 -0.4254958 0.5109844 -0.7830237 -0.3546392 0.4675925 -0.8194093 -0.3315506 0.4977929 -0.7933271 -0.3504773 0.434952 -0.8470907 -0.3053758 0.4288837 -0.8514567 -0.3017955 0.3600082 -0.8979021 -0.2533102 0.3605179 -0.8976039 -0.2536419 -0.1302617 0.9894593 -0.06326347 -0.3840328 0.9113085 -0.1484437 -0.4255636 0.8377502 -0.3421553 -0.4593738 0.8346937 -0.3037471 -0.3830718 0.9117181 -0.1484122 -0.3782426 0.9131595 -0.1518955 -0.6066052 0.7905346 -0.08417385 -0.694724 0.6686683 -0.2650308 -0.764829 0.6178537 -0.1824648 -0.7644858 0.6328662 -0.1226459 -0.7897777 0.6060146 -0.09485536 -0.9232894 0.3824504 -0.03561431 -0.9086756 0.3779662 -0.1773421 -0.9731803 0.2299985 -0.004556834 -0.9659085 0.2538 -0.05105328 -0.9730687 0.2120987 -0.09028524 -0.9912171 0.1304935 -0.02145296 -0.7069451 0.5638127 -0.4270174 -0.8822172 0.2816067 -0.3773469 -0.9244574 0.2194724 -0.3117859 -0.9414883 0.01782989 -0.3365736 -0.9694211 -0.007707178 -0.2452823 -0.9778164 -0.001156091 -0.2094615 -0.978508 -0.01930975 -0.2053031 -0.9945684 -0.02576398 -0.1008474 -0.05970954 0.9947067 -0.08362662 -0.07485312 0.9900477 -0.1191751 -0.1523129 0.9617681 -0.2276026 -0.1801959 0.9511585 -0.2506533 -0.2859388 0.8785919 -0.3825119 -0.2660186 0.8910718 -0.3677299 -0.3889433 0.7559601 -0.5265432 -0.3305922 0.8093636 -0.485427 -0.535303 0.6549625 -0.533362 -0.5735474 -4.71213e-6 -0.8191725 -0.5735527 3.18824e-6 -0.8191688 -0.5595464 -0.008490681 -0.8287556 -0.6217409 0.01655763 -0.7830481 -0.5735746 1.98716e-5 -0.8191534 -0.5736004 2.42431e-5 -0.8191354 -0.5736002 2.60183e-5 -0.8191356 -0.5736058 2.70482e-5 -0.8191315 -0.520311 -0.007112979 -0.8539472 -0.9999976 0 -0.002230703 -0.9999605 -9.54712e-4 -0.008839666 -0.9999848 -2.38122e-4 -0.005516588 -0.995975 -0.01128739 0.08891797 5.68051e-4 0.9999999 -1.5988e-6 -0.002282917 0.9998708 -0.01591658 -0.07764339 0.8727437 0.4819648 0.05893206 0.742774 0.6669436 0.04720228 0.8956393 0.4422696 0.1008481 0.9050542 0.4131665 0 1 -9.69386e-7 0.2575954 -0.9613674 0.09704273 0.1312013 -0.9397212 0.3157696 0.04225617 -0.9352617 0.3514256 0.03103083 -0.8998861 0.4350196 -0.02004897 -0.891452 0.4526714 -0.01269209 -0.7964855 0.6045244 0.08486491 -0.9913715 0.09990334 0.08283251 -0.9943466 0.06643563 0.06828784 -0.996994 0.03660112 0.1792856 -0.9823005 0.05424475 0.1518359 -0.9883034 0.01422393 0.1698051 -0.9708784 0.1690016 0.3039133 -0.9188196 0.2518081 0.5597814 -0.8209493 0.1126378 0.4261049 -0.8238913 0.3736816 0.4403162 -0.7881703 0.4300109 0.6172985 -0.7702536 0.1601622 0.6028177 -0.5976101 0.5286522 0.8311477 -0.537061 0.1440807 0.6117074 -0.5407065 0.5774518 0.7085366 -0.371837 0.599761 0.8875923 -0.3931177 0.2400805 0.9659365 -0.1682951 0.1965796 0.7364623 -0.1602863 0.657215 0.7103452 -0.1051629 0.695953 0.9659311 -0.07592827 0.2474108 0.6261373 -0.7796966 0.005059063 0.513269 -0.8582105 -0.005459129 0.9136981 -0.4062963 0.008891582 0.02994132 -0.9986367 0.04275947 0.07668846 -0.9914423 0.1056455 0.1128827 -0.9784675 0.1727978 0.2174077 -0.9238769 0.3149372 0.227968 -0.9142159 0.3350223 0.4059697 -0.6943662 0.5941752 0.3475646 -0.7933462 0.4998007 0.3537265 -0.7829507 0.5117284 0.4317837 -0.6629896 0.6115618 0.4513458 -0.6087617 0.6524541 0.4036271 -0.6950742 0.5949429 0.4867072 -0.3821648 0.7855356 0.5465233 -0.1077722 0.8304803 0.5681761 -0.1287083 0.8127793 0.5467531 -0.05619096 0.8354063 0.001029312 -0.9999983 0.001582384 6.67082e-4 -0.9999997 -2.70317e-4 9.92466e-4 -0.9999994 -4.92211e-4 -0.002207577 -0.9999881 -0.004372894 -4.44076e-4 -0.9999997 -6.3401e-4 -3.99185e-4 -0.9999998 7.03372e-4 -0.002157986 -0.9999967 -0.001387715 -8.64077e-4 -0.9999996 4.5485e-4 -0.00302869 -0.9999926 -0.00242418 -0.001444637 -0.9999989 -3.92136e-4 -4.97433e-4 -0.9999998 -5.85536e-4 -3.77831e-4 -0.9999997 7.1514e-4 -0.001370966 -0.9999991 -1.26992e-4 -0.573601 0 -0.8191349 -0.5735639 0 -0.8191608 -0.5735695 0 -0.8191569 -0.5735751 0 -0.8191531 -0.5735766 0 -0.819152 -0.5735797 0 -0.8191497 -0.5735779 0 -0.8191511 -0.5735737 0 -0.819154 -0.5735723 0 -0.819155 -0.5735813 0 -0.8191487 -0.5735806 0 -0.8191491 -0.5735735 1.06461e-6 -0.8191542 -0.5735764 0 -0.8191521 -0.5735734 -9.25506e-7 -0.8191543 -0.5735781 9.02119e-7 -0.8191509 -0.573579 -7.87386e-7 -0.8191503 0.06693577 0.994916 -0.07524549 0.2424564 0.9584358 -0.1503855 0.2315085 0.9568821 -0.175444 0.1712161 0.9805607 -0.0958423 0.3903989 0.8818983 -0.2642804 0.3819234 0.8893216 -0.2514792 0.486346 0.8140874 -0.3173788 0.5169379 0.7730019 -0.3677544 0.6181187 0.6636969 -0.4212312 0.6307556 0.6343873 -0.4468783 0.7133687 0.5025672 -0.4883967 0.7201935 0.4713937 -0.5090278 0.7806341 0.3213067 -0.5360714 0.7818971 0.2902824 -0.5517003 0.8171386 0.1272961 -0.5622103 0.8135035 0.09802013 -0.5732402 0.8214355 -0.07136452 -0.5658187 0.8137028 -0.09801924 -0.5729573 0.7932282 -0.267776 -0.5468867 0.7826279 -0.2902833 -0.5506625 0.7336894 -0.4535452 -0.5059611 0.7214767 -0.4713993 -0.5072024 0.645263 -0.6211422 -0.4447674 0.6325663 -0.6343939 -0.4443021 0.5312107 -0.7642527 -0.3656954 0.5193697 -0.7730103 -0.3642944 0.3963859 -0.8768619 -0.2720138 0.3861932 -0.8819212 -0.2703147 0.2458239 -0.9547487 -0.1674088 0.2381871 -0.9569391 -0.1659361 0.08548009 -0.9947659 -0.05598342 0.08107566 -0.9951841 -0.0550965 -0.1493527 0.8998671 0.4097962 -0.1301479 0.9717236 0.1970152 -0.0972591 0.9824987 0.158862 -0.0987311 0.9848567 0.1425114 -0.08998769 0.9907528 0.1015437 -0.03882867 0.9989612 0.02385437 0.03686761 0.999309 -0.004739701 0.055498 0.9976996 -0.03892999 0.01173061 0.9997888 0.0168792 0.2335456 0.9586886 -0.1623966 0.1885421 0.9717851 -0.141724 0.1619065 0.9807873 -0.1088244 0.3512733 0.9034531 -0.2457226 0.3663249 0.8889813 -0.2748062 0.4675387 0.8141487 -0.3443394 0.4938822 0.7972357 -0.347125 0.6106984 0.6637285 -0.4318705 0.6171486 0.6576103 -0.4320607 0.705483 0.5025808 -0.4997063 0.7145703 0.490437 -0.4988597 0.7724085 0.3213178 -0.5478503 0.7820212 0.3027197 -0.544797 0.8086068 0.1272966 -0.5744133 0.8167033 0.1023371 -0.5679111 0.8126432 -0.07136619 -0.5783754 0.8173024 -0.1023353 -0.5670487 0.7844115 -0.2677729 -0.5594608 0.7836894 -0.3027158 -0.5423967 0.7248197 -0.4535374 -0.5185947 0.7172904 -0.4904265 -0.4949508 0.6363337 -0.6211212 -0.4574802 0.6209529 -0.6575973 -0.4265951 0.5223002 -0.7642238 -0.3783711 0.4986866 -0.7972099 -0.3402471 0.3874799 -0.876817 -0.2846954 0.3556771 -0.9034261 -0.2394061 0.2370333 -0.9546941 -0.179929 0.1979289 -0.9717813 -0.1283172 0.081676 -0.9947641 -0.06142896 0.06945049 -0.9954918 -0.06459712 0.03686761 -0.999309 -0.004739165 -0.02038204 -0.9996496 0.01689058 -0.1375164 -0.9852135 0.102194 0.004871129 -0.9932399 0.1159772 -0.1670706 -0.9761651 0.1385254 -0.2274716 -0.9224012 0.3121423 -0.2582432 -0.9401305 0.2224075 0.7754843 0.02612709 0.6308262 0.7150592 0.1681404 0.678542 0.9554156 0.1616672 0.2470726 0.934406 0.2097238 0.2879264 0.7085373 0.3718373 0.5997599 0.8238803 0.5407095 0.1698662 0.6306577 0.5444159 0.5530661 0.5662579 0.6026544 0.5622808 0.4660601 0.7846876 0.4087221 0.4133448 0.8209499 0.3939384 0.4814304 0.8312235 0.2780147 0.7023378 0.7023389 0.1159384 0.3039129 0.9188195 0.2518089 0.3805869 0.9188193 0.1045225 0.2327789 0.971671 0.04086172 0.1485034 0.9821153 0.1157433 0.09871667 0.9883065 0.1162124 0.07303458 0.9914431 0.1081975 0.1305137 0.9913712 0.01222568 0.1018981 0.9943497 0.02975851 0.06994646 0.9969431 0.03481394 0.07486492 0.9914452 0.10692 0.053029 0.9953742 0.0801143 0.1826775 0.9474362 0.2626668 0.2165121 0.923874 0.3155622 0.2445843 0.903907 0.3508999 0.3015574 0.8507992 0.4303532 0.3445414 0.7933354 0.5019067 0.3936817 0.7281528 0.5610778 0.4181507 0.6861221 0.5953037 0.447412 0.6087421 0.6551761 0.5222609 0.4259079 0.7388139 0.5299182 0.3826805 0.7567974 0.5376667 0.3589664 0.762927 0.5511312 0.1336752 0.8236416 0.5721322 0.02919226 0.8196418 0.9686799 7.87851e-4 0.2483117 0.9680526 5.91287e-4 0.2507469 0.7463847 -6.4912e-4 0.6655145 0.7757762 0.003217101 0.6310001 0.5735772 -7.39153e-6 0.8191516 0.5735753 4.99709e-6 0.8191528 0.5735731 -1.62349e-4 0.8191545 0.5735642 -2.65695e-5 0.8191606 0.5732553 -0.01083791 0.8193053 0.5727959 -0.001258671 0.8196972 0.5733017 0.02735114 0.8188878 0.5735765 -2.18259e-6 0.8191521 0.5723915 8.60799e-5 0.8199806 0.5735095 -8.07936e-5 0.819199 0.5735767 1.24925e-6 0.819152 0.5735776 2.96382e-7 0.8191513 0.5735239 -1.0892e-4 0.8191888 0.5735765 1.20538e-6 0.819152 0.5735774 0 0.8191514 0.5735771 0 0.8191516 0.5735772 -1.19435e-6 0.8191516 0.5735778 2.59358e-6 0.8191511 0.5735762 0 0.8191523 0.5729499 0.008018791 0.8195513 0.5735796 0.005685865 0.8191302 0.5723796 0.001925528 0.8199866 0.5745268 -0.03600335 0.8176936 0.5725684 0.02864056 0.8193566 0.5735754 -4.72581e-6 0.8191528 0.5735771 5.10478e-6 0.8191516 0.5735764 4.99712e-6 0.8191522 0.5735786 2.95662e-5 0.8191505 0 1 -3.71551e-7 0 1 8.75153e-7 0 1 -6.89799e-7 -4.93388e-4 0.9999996 8.58662e-4 7.78278e-4 0.9999992 -9.82297e-4 0 1 -1.64712e-6 0 1 -1.63473e-7 0 1 5.82003e-6 0.4264293 -0.001274764 0.90452 0.4558038 -5.20503e-4 0.8900801 0.3554629 8.11729e-5 0.9346904 0.3920079 0.002689003 0.9199579 0.3657835 0.03912615 0.9298772 0.3227221 -0.009045839 0.9464505 0.2724286 -0.04836392 0.9609598 0.2800181 -0.03618061 0.9593127 0.1562109 0.02802634 0.987326 0.0944252 -0.04776698 0.9943853 0 0.03383225 0.9994276 -0.09442478 -0.04776757 0.9943854 -0.1562107 0.02802634 0.9873261 -0.2683724 -0.03004956 0.9628465 -0.3747038 -0.1567031 0.9138059 -0.2801765 -0.01405972 0.9598456 -0.3741198 0.002502262 0.9273771 -0.4280449 -0.0102514 0.9036994 -0.4556709 -0.02415579 0.8898205 0 1 -5.52097e-6 0 1 4.06084e-6 0 1 -2.55717e-6 0 1 1.35737e-6 0 1 -2.8418e-6 -0.1050816 0.9935916 0.04163837 0.009289145 0.9989368 0.04515421 -0.07535994 0.9953441 -0.06009328 0.04500758 0.9983417 -0.03589177 -0.0772348 0.9952927 -0.05854439 0.0452708 0.9983854 -0.03431278 0 1 -1.46292e-6 0 1 -7.08969e-7 0 1 5.89513e-7 0 1 4.81983e-6 0 1 6.22603e-6 1 0 -5.38128e-5 1 -1.23335e-4 -1.4179e-6 0 -1 6.31439e-6 0 -1 4.5474e-6 0 -1 -3.71764e-6 0 -1 3.61024e-6 0 -1 -3.76546e-6 -0.3275186 0 0.9448447 -0.3275169 3.45434e-6 0.9448454 -0.07958406 -6.94967e-6 0.9968281 -0.07951384 7.90991e-6 0.9968339 0.1735916 2.82538e-6 0.9848178 0.1735882 5.96458e-6 0.9848183 0.4153035 -4.71091e-7 0.909683 0.4153108 9.42198e-7 0.9096797 0.6303274 -4.78954e-6 0.7763295 0.6303516 2.35545e-7 0.7763098 0.8050408 -6.35735e-6 0.5932194 0.8050831 3.60964e-6 0.5931621 0.9283187 -1.03365e-5 0.3717855 0.9283547 7.20329e-6 0.3716956 0.9919615 -1.3191e-5 0.1265405 0.9919714 0 0.1264628 0.3275125 0 0.9448469 0.3275305 0 0.9448407 0.07960557 0 0.9968265 0.07958567 0 0.996828 -0.1735882 0 0.9848183 -0.1735687 0 0.9848219 -0.4153034 0 0.909683 -0.4153032 0 0.9096831 -0.6303274 0 0.7763295 -0.8050408 0 0.5932195 -0.805048 0 0.5932099 -0.9283189 0 0.3717851 -0.9919639 0 0.1265213 -0.9919636 0 0.1265238 0.3231931 0.1619828 0.9323669 0.1810336 0.328935 0.926838 0.1843532 0.3297075 0.9259087 0.07845449 0.1685275 0.9825699 -0.159456 0.3951727 0.9046614 -0.04529678 0.9315403 0.3608061 -0.1745858 0.8633983 0.4733533 -0.4005437 0.2640368 0.8774105 -0.323741 0.3519882 0.8782347 -0.2226155 0.9204896 0.3211563 -0.5800837 0.3912526 0.7144399 -0.78059 0.2446327 0.575182 -0.6942688 0.3619252 0.6220941 -0.2604647 0.9344771 0.2427153 -0.2706943 0.9316085 0.2425493 -0.3349773 0.9210178 0.1987877 -0.8562542 0.3863072 0.3429221 -0.3237493 0.9400001 0.1076401 -0.3640664 0.9269695 0.09046095 -0.9669678 0.2230753 0.1233327 -0.9754679 0.1940327 0.1039895 -0.8142856 0.5440649 0.2023178 -0.5472632 0.8189977 -0.1724703 -0.1950388 0.9805724 0.02092069 -0.5430639 0.8396914 4.82381e-4 -0.5555866 0.8314586 -3.20725e-4 -0.8264462 0.5630156 3.27229e-4 -0.8314818 0.5555521 -1.62604e-4 -0.9807853 0.1950905 1.69154e-4 -0.9801923 0.1980485 0 -0.9803683 0.1953347 0.02687668 0.4829684 0.8754973 -0.01568627 0.1950852 0.9807822 0.00289148 0.5527347 0.8333573 -1.38918e-4 0.5555692 0.8314704 -3.21349e-4 0.8264307 0.5630386 3.26118e-4 0.8314703 0.5555692 -1.64222e-4 0.9800155 0.1989213 1.63434e-4 0.9807863 0.1950854 -5.27998e-5 -0.3232587 0.1610673 0.9325027 -0.07832032 0.1788595 0.9807525 -0.1834015 0.3285996 0.9264914 -0.1848933 0.3284058 0.9262636 0.1593244 0.3968499 0.9039502 0.386586 0.3653581 0.8467968 0.3285776 0.3081333 0.8927993 0.03931283 0.9309097 0.3631278 0.1814504 0.8602754 0.4764474 0.2226 0.9205013 0.3211334 0.5802202 0.3906986 0.7146322 0.2665869 0.9312441 0.2484267 0.2664101 0.9335933 0.239644 0.7469063 0.3731176 0.5503765 0.708252 0.3041278 0.6370914 0.3350324 0.9209909 0.1988192 0.8563885 0.3859612 0.3429765 0.3567517 0.9266388 0.1186125 0.3222819 0.9460123 0.03457248 0.1942952 0.9768219 -0.08982527 0.5503206 0.823618 0.1371165 0.9246638 0.3031827 0.2303852 0.8166416 0.5456773 -0.1879703 0.9731976 0.19358 0.1241503 0.9807738 -0.1950889 0.004793822 0.965921 -0.2588372 -1.36952e-6 0.8314763 -0.5555549 -0.002418398 0.7070793 -0.7071179 0.004824936 0.555566 -0.831469 -0.002417087 0.2588055 -0.9659228 0.003612518 0.1950869 -0.980786 -3.46085e-7 -0.1950895 -0.9807738 0.004794359 -0.2588236 -0.9659246 5.21736e-7 -0.5555659 -0.831469 -0.002417027 -0.7070991 -0.707098 0.004824757 -0.8314638 -0.5555736 -0.002417147 -0.9659171 -0.2588267 0.003613889 -0.9807851 -0.1950911 0 0.3273605 0.03111159 0.9443872 0.07823663 -0.1843753 0.9797372 0.02497243 -0.1189087 0.9925912 -0.1666529 -0.2797718 0.9454917 -0.1961517 -0.2752956 0.941136 -0.3826697 -0.3884537 0.8382527 -0.6123702 -0.2370116 0.7542071 -0.6466725 -0.3296648 0.6878488 -0.1074149 -0.9363919 0.3341142 -0.2087637 -0.9238837 0.3207128 -0.2956994 -0.8938332 0.3370822 -0.3452906 -0.8654693 0.3629564 -0.3200378 -0.9223867 0.2162838 -0.7414495 -0.3895508 0.5463543 -0.3466314 -0.924842 0.1565696 -0.336233 -0.9377092 0.08745706 -0.2987623 -0.9539894 0.02540659 -0.1945887 -0.9782516 -0.07182723 -0.5490611 -0.8217365 0.1525814 -0.909471 -0.2004873 0.3642356 -0.9021581 -0.3510844 0.2507 -0.8166401 -0.545677 -0.1879779 -0.9731997 -0.1935831 0.1241295 0.471539 -0.0143482 0.8817285 0.1430537 -0.9533354 0.2658711 0.3391696 -0.3852026 0.8582442 0.05431777 -0.7523102 0.6565662 0.2044992 -0.3714663 0.905645 0.03996634 -0.731595 0.6805671 0.01607435 -0.988027 0.1534415 -0.03998446 -0.7315404 0.6806247 -0.01607704 -0.9880283 0.1534335 -0.07104992 -0.942491 0.3265923 -0.1304692 -0.9094501 0.3948144 -0.4424508 -0.1168928 0.8891419 -0.1419774 -0.9500115 0.278066 0 1 1.43903e-6 0 1 9.52154e-7 0 1 -7.88596e-7 0 1 -9.52407e-7 0 1 -6.86874e-7 0 1 -5.49488e-7 0 1 -2.198e-6 -0.5393391 0.8339989 0.1164441 -0.8262989 0.5629221 -0.01868343 -0.8510226 0.5204593 0.0698772 -0.9828194 0.1845195 -0.004311501 0.604853 0.7911382 0.09084659 0.8262812 0.5629481 -0.01867735 0.8510008 0.520487 0.06993675 0.9800164 0.1989131 -0.001187741 -0.3826122 0.9238317 0.01196295 -0.6055043 0.792051 -0.07758784 -0.982419 0.1831501 0.03618317 -0.8434541 0.5313736 -0.07891356 -0.920412 0.3813316 -0.08618533 -0.3511033 0.9344633 0.05920141 -0.7671257 0.4246745 0.4808014 -0.3085485 0.9234268 0.2282125 -0.3523148 0.9094587 0.2208147 -0.7682769 0.3935257 0.5048646 -0.1669139 0.9277244 0.3338673 -0.2949006 0.4132846 0.8615274 -0.3026924 0.4024117 0.8639689 -0.138964 0.9073995 0.3966298 0.002514719 0.9349591 0.3547468 0.2963518 0.4032521 0.8657733 0.3009946 0.4138812 0.8591302 0.1392924 0.9069368 0.3975716 0.1703324 0.9286429 0.3295591 0.7682726 0.3935255 0.5048713 0.3494688 0.902663 0.2511395 0.3348116 0.9186226 0.2098426 0.7671315 0.4246712 0.480795 0.3527314 0.933998 0.05681943 0.9204784 0.3834818 -0.07524251 0.6135768 0.780852 0.1174461 0.4356967 0.897168 -0.07251232 0.9823454 0.1835697 0.03605079 0.84345 0.5313799 -0.07891613 0.6050899 0.7903663 0.09585148 0.0839501 -0.4720355 0.8775733 0.07372206 -0.3144437 0.9464091 0.03183829 -0.71798 0.6953352 0.05570387 -0.9124059 0.4054784 0.06149995 -0.8951175 0.441568 0.06956648 -0.9881622 0.1367331 0.01245242 -0.9194357 0.3930431 0 -1 -2.47842e-7 0 -1 3.40606e-7 0 -1 -2.52386e-7 -0.4653393 -0.6980465 0.5442338 -0.4653718 -0.6980113 0.5442513 -0.4653586 -0.6979972 0.5442807 0.04408097 -0.7185977 0.6940277 -0.04407942 -0.7185984 0.6940269 0.4783545 0.8781372 -0.007226705 0.1970303 -0.3282916 0.9237985 -0.1148359 -0.9055491 0.4084038 0.3531275 -0.8725625 0.3375438 0.1973733 -0.8019863 0.5637925 -0.1888567 -0.6710071 0.7169957 -0.2527757 -0.6501134 0.7165591 0.1260272 -0.6534007 0.7464481 -0.2126824 -0.2951642 0.9314743 -0.2042712 -0.3007111 0.9315826 0.1039767 -0.3002351 0.9481813 -9.7603e-5 -0.1876575 0.9822345 0.2626359 -0.1267769 0.9565303 0.2700648 -0.1371474 0.9530245 -0.1950807 0.9807873 0 -0.9996244 3.638e-4 0.02740442 -0.9644876 -0.258445 -0.05449807 -0.6995568 -0.6995532 0.1457593 -0.6235559 -0.665785 0.4097664 -0.2084872 -0.7652275 0.6090649 0 -0.8450017 0.5347636 0.2084891 -0.7652276 0.6090641 0.6235581 -0.6657817 0.4097684 0.9644857 -0.2584522 -0.05449759 0.6995357 -0.6995713 0.1457732 -0.2703323 -0.1375218 0.9528947 -0.2626359 -0.1267769 0.9565303 9.7603e-5 -0.1876575 0.9822345 -0.1039768 -0.3002347 0.9481814 0.2042676 -0.3007115 0.9315833 0.2126815 -0.2951624 0.9314751 -0.126026 -0.6534007 0.7464483 0.2527847 -0.6501119 0.7165575 0.1888568 -0.6710079 0.7169948 -0.1973749 -0.8019856 0.5637928 -0.3531258 -0.8725596 0.3375529 0.1148358 -0.9055492 0.4084035 -0.1970885 -0.3274795 0.9240743 -0.01244419 -0.9194349 0.3930454 -0.06952261 -0.9881656 0.1367319 -0.06146103 -0.895119 0.4415706 -0.0556696 -0.9124048 0.4054855 -0.03181892 -0.7179799 0.6953363 -0.07368361 -0.3143586 0.9464404 -0.08391344 -0.4720372 0.8775759 -0.2046165 -0.3709282 0.9058391 -0.05430173 -0.7522569 0.6566285 -0.3395893 -0.3843267 0.8584708 0.9732069 -0.1935836 0.1240712 0.8166311 -0.5456359 -0.1881361 0.9023535 -0.3499414 0.2515938 0.909486 -0.2005993 0.3641365 0.5490183 -0.8216724 0.1530799 0.1945863 -0.9782654 -0.07164603 0.2984415 -0.9540905 0.02537602 0.3363656 -0.9375873 0.08825165 0.346635 -0.9248403 0.1565712 0.7418065 -0.3885838 0.5465581 0.3200408 -0.9223852 0.2162859 0.3452902 -0.8654684 0.3629589 0.2957088 -0.8938276 0.3370887 0.2087637 -0.9238834 0.3207138 0.1074151 -0.9363915 0.3341151 0.6468894 -0.3287389 0.6880879 0.6125325 -0.2361333 0.7543508 0.3827819 -0.3879434 0.8384378 0.1960178 -0.2749503 0.9412648 0.1666819 -0.2794644 0.9455776 -0.02492803 -0.1190448 0.9925759 -0.07813352 -0.1847099 0.9796823 -0.3273653 0.02956092 0.9444354 -0.3660895 0.03957867 0.9297376 -0.3923804 0.003088414 0.9197978 -0.4278317 -9.66497e-4 0.903858 0 -1 2.52096e-6 0 1 1.39908e-6 0 1 1.41513e-6 -0.1872155 0.9823188 -4.94087e-4 -0.2588236 -0.9659247 0 -0.6798568 -0.7150565 0.1627545 0.2588062 -0.9659293 0 0.6798611 -0.715054 0.1627474 -0.9970736 0 -0.07644844 -0.9977747 0.004755139 -0.06650704 0.8357039 0 0.5491804 0.8357081 0 0.5491739 0.3238449 1.07394e-6 0.9461103 0.3238599 0 0.9461051 -0.3238601 0 0.9461051 -0.3238449 -1.08807e-6 0.9461103 -0.8357083 0 0.5491738 -0.8357039 0 0.5491804 0.9978136 0 -0.06609272 0.997798 -1.23449e-4 -0.06632697 -1.15935e-4 1 1.15117e-4 -1.59672e-5 1 1.44974e-4 -4.74823e-5 1 1.38709e-4 0.0361945 -0.9402186 0.3386429 0.1026628 -0.9450044 0.310527 0.1227682 -0.94865 0.2915325 0.1109429 -0.9433757 0.3126248 -0.03620165 -0.9402186 0.3386422 -0.102856 -0.945012 0.3104403 -0.1226163 -0.9485889 0.2917951 -0.1109423 -0.9433689 0.3126454 0 1 6.0988e-7 0.01046007 0.9999229 0.00670284 -5.27779e-4 0.9999986 0.00159657 -1.78806e-4 0.9999986 0.001674294 1.82431e-4 0.9999986 0.001673936 5.18432e-4 0.9999986 0.001601278 -0.01046007 0.9999228 0.00670284 0 1 -3.04942e-7 + + + + + + + + + + + + + + +

10 0 11 0 12 0 13 1 11 1 10 1 16 2 15 2 14 2 14 3 17 3 16 3 9 4 17 4 14 4 1 5 0 5 20 5 20 6 21 6 1 6 2 7 1 7 21 7 22 8 3 8 2 8 21 9 22 9 2 9 24 10 25 10 26 10 27 11 26 11 25 11 28 11 27 11 25 11 25 12 24 12 29 12 29 13 30 13 25 13 30 11 31 11 25 11 30 14 29 14 19 14 20 15 19 15 29 15 29 16 24 16 20 16 21 17 20 17 24 17 22 18 21 18 24 18 24 19 26 19 22 19 23 20 22 20 26 20 13 21 16 21 11 21 15 22 16 22 13 22 12 23 11 23 17 23 16 24 17 24 11 24 12 25 17 25 9 25 33 26 9 26 18 26 33 27 18 27 8 27 33 28 8 28 7 28 33 29 7 29 6 29 33 30 6 30 4 30 33 31 4 31 5 31 32 32 33 32 5 32 25 33 60 33 61 33 51 34 14 34 48 34 84 35 37 35 34 35 84 36 34 36 81 36 81 37 34 37 38 37 60 38 36 38 88 38 86 39 88 39 36 39 84 40 86 40 37 40 86 41 36 41 37 41 79 42 81 42 38 42 38 43 39 43 79 43 77 44 79 44 39 44 39 45 40 45 77 45 74 46 77 46 40 46 40 47 58 47 74 47 72 48 74 48 58 48 58 49 59 49 72 49 53 50 44 50 69 50 41 51 83 51 44 51 41 52 85 52 83 52 41 53 87 53 85 53 41 54 44 54 56 54 44 55 53 55 56 55 89 56 87 56 41 56 56 57 57 57 41 57 63 58 46 58 62 58 42 59 46 59 66 59 46 60 63 60 66 60 42 61 75 61 46 61 42 62 76 62 75 62 42 63 78 63 76 63 43 64 42 64 67 64 42 65 66 65 67 65 42 66 43 66 78 66 43 67 80 67 78 67 82 68 80 68 43 68 43 69 69 69 44 69 43 70 67 70 69 70 43 71 44 71 82 71 44 72 83 72 82 72 49 73 50 73 45 73 71 74 70 74 45 74 45 75 46 75 71 75 46 76 73 76 71 76 46 77 75 77 73 77 45 78 62 78 46 78 45 79 50 79 62 79 35 80 47 80 62 80 62 81 50 81 35 81 50 82 48 82 35 82 50 83 51 83 48 83 53 84 69 84 52 84 56 85 53 85 54 85 53 86 52 86 54 86 54 87 55 87 56 87 63 88 62 88 47 88 47 89 64 89 63 89 66 90 63 90 64 90 64 91 65 91 66 91 65 92 68 92 66 92 68 93 67 93 66 93 69 94 67 94 68 94 68 95 52 95 69 95 70 96 71 96 72 96 74 97 72 97 73 97 72 98 71 98 73 98 73 99 75 99 74 99 77 100 74 100 75 100 75 101 76 101 77 101 79 102 77 102 78 102 77 103 76 103 78 103 81 104 79 104 80 104 79 105 78 105 80 105 84 106 81 106 82 106 81 107 80 107 82 107 82 108 83 108 84 108 86 109 84 109 85 109 84 110 83 110 85 110 88 111 86 111 87 111 86 112 85 112 87 112 168 113 167 113 166 113 223 114 168 114 166 114 223 115 166 115 222 115 25 116 157 116 158 116 25 11 61 11 157 11 198 117 33 117 197 117 197 118 33 118 117 118 210 119 140 119 141 119 210 120 209 120 140 120 144 121 142 121 138 121 90 122 188 122 135 122 154 123 156 123 155 123 148 124 156 124 154 124 91 125 143 125 92 125 91 126 144 126 143 126 137 127 92 127 95 127 93 128 137 128 95 128 137 129 135 129 136 129 94 130 135 130 137 130 137 131 93 131 94 131 188 132 180 132 181 132 143 133 95 133 92 133 188 134 90 134 180 134 93 135 95 135 97 135 93 136 97 136 147 136 143 137 97 137 95 137 143 138 144 138 97 138 144 139 138 139 97 139 138 140 96 140 97 140 147 141 97 141 96 141 147 142 96 142 98 142 147 143 98 143 148 143 145 144 93 144 147 144 90 145 99 145 180 145 180 146 99 146 179 146 179 147 99 147 178 147 178 148 99 148 153 148 153 149 99 149 154 149 146 150 154 150 99 150 145 151 146 151 99 151 145 152 99 152 93 152 93 153 99 153 94 153 135 154 94 154 99 154 99 155 90 155 135 155 55 156 14 156 149 156 33 157 12 157 9 157 33 158 10 158 12 158 33 159 206 159 10 159 33 160 204 160 206 160 33 161 200 161 204 161 33 162 202 162 200 162 33 163 198 163 202 163 121 164 123 164 110 164 110 165 100 165 104 165 100 166 128 166 104 166 101 167 127 167 177 167 126 168 127 168 101 168 177 169 111 169 101 169 102 170 125 170 126 170 125 171 102 171 124 171 126 172 103 172 102 172 103 173 126 173 101 173 111 174 112 174 101 174 128 175 124 175 102 175 102 176 107 176 128 176 107 177 102 177 103 177 104 178 128 178 107 178 105 179 101 179 112 179 101 180 105 180 103 180 112 181 113 181 105 181 106 182 103 182 105 182 103 183 106 183 107 183 110 184 104 184 107 184 105 185 108 185 106 185 108 186 105 186 113 186 113 187 114 187 108 187 109 188 106 188 108 188 106 189 109 189 107 189 107 190 118 190 110 190 118 191 107 191 109 191 108 192 116 192 109 192 116 193 108 193 114 193 117 194 109 194 116 194 109 195 117 195 118 195 114 196 115 196 116 196 121 197 110 197 118 197 176 198 133 198 177 198 111 199 177 199 133 199 133 200 134 200 111 200 112 201 111 201 134 201 134 202 130 202 112 202 113 203 112 203 130 203 130 204 131 204 113 204 114 205 113 205 131 205 131 206 196 206 114 206 115 207 114 207 196 207 196 208 197 208 115 208 197 209 116 209 115 209 117 210 116 210 197 210 33 211 119 211 117 211 119 212 118 212 117 212 121 213 118 213 119 213 120 214 121 214 119 214 123 215 121 215 122 215 121 216 120 216 122 216 181 217 182 217 188 217 190 218 188 218 182 218 182 219 183 219 190 219 191 220 190 220 183 220 183 221 184 221 191 221 192 222 191 222 184 222 184 223 185 223 192 223 199 224 192 224 185 224 185 225 186 225 199 225 203 226 199 226 186 226 186 227 187 227 203 227 205 228 203 228 187 228 187 229 15 229 205 229 13 230 205 230 15 230 14 231 153 231 149 231 178 232 153 232 14 232 158 233 215 233 163 233 158 234 216 234 215 234 213 235 216 235 158 235 158 236 157 236 213 236 211 237 213 237 157 237 157 238 61 238 211 238 208 239 211 239 61 239 61 240 60 240 208 240 88 241 208 241 60 241 159 242 167 242 28 242 166 243 167 243 159 243 159 244 160 244 166 244 160 245 161 245 166 245 161 246 165 246 166 246 164 247 165 247 161 247 161 248 162 248 164 248 164 249 163 249 215 249 164 250 162 250 163 250 23 251 28 251 167 251 23 252 27 252 28 252 26 253 27 253 23 253 169 254 92 254 136 254 129 255 169 255 136 255 129 256 170 256 169 256 129 257 136 257 189 257 136 258 135 258 189 258 189 259 193 259 129 259 132 260 129 260 193 260 129 261 132 261 170 261 132 262 171 262 170 262 132 263 172 263 171 263 132 264 173 264 172 264 174 265 173 265 132 265 193 266 194 266 132 266 132 267 131 267 130 267 132 268 196 268 131 268 132 269 195 269 196 269 132 270 194 270 195 270 132 271 130 271 174 271 130 272 175 272 174 272 176 273 175 273 133 273 175 274 134 274 133 274 175 275 130 275 134 275 137 276 136 276 92 276 98 277 156 277 148 277 98 278 139 278 156 278 139 279 155 279 156 279 141 280 139 280 98 280 98 281 96 281 141 281 96 282 138 282 141 282 214 283 141 283 138 283 138 284 142 284 214 284 140 285 41 285 150 285 41 286 57 286 150 286 41 287 140 287 89 287 140 288 207 288 89 288 209 289 207 289 140 289 150 290 151 290 140 290 140 291 139 291 141 291 140 292 155 292 139 292 140 293 152 293 155 293 140 294 151 294 152 294 141 295 212 295 210 295 212 296 141 296 214 296 214 297 142 297 217 297 218 298 217 298 144 298 217 299 142 299 144 299 144 300 91 300 218 300 146 301 145 301 147 301 154 302 146 302 147 302 147 303 148 303 154 303 149 304 153 304 55 304 153 305 56 305 55 305 153 306 57 306 56 306 153 307 150 307 57 307 153 308 151 308 150 308 153 309 152 309 151 309 153 310 155 310 152 310 155 311 153 311 154 311 158 11 163 11 25 11 25 312 159 312 28 312 25 313 160 313 159 313 25 314 161 314 160 314 25 315 162 315 161 315 25 316 163 316 162 316 224 317 225 317 168 317 225 318 167 318 168 318 225 319 23 319 167 319 22 320 23 320 225 320 225 321 3 321 22 321 219 322 215 322 216 322 164 323 215 323 219 323 219 324 220 324 164 324 220 325 221 325 164 325 165 326 164 326 221 326 221 327 222 327 165 327 165 328 222 328 166 328 223 329 224 329 168 329 92 330 169 330 91 330 91 331 169 331 170 331 91 332 170 332 230 332 170 333 171 333 230 333 171 334 172 334 230 334 172 335 173 335 226 335 14 336 179 336 178 336 14 337 180 337 179 337 14 338 181 338 180 338 14 339 182 339 181 339 14 340 183 340 182 340 14 341 184 341 183 341 14 342 185 342 184 342 14 343 186 343 185 343 14 344 187 344 186 344 14 345 15 345 187 345 189 346 135 346 188 346 188 347 190 347 189 347 190 348 191 348 189 348 191 349 192 349 189 349 201 350 189 350 199 350 189 351 192 351 199 351 189 352 201 352 193 352 202 353 193 353 201 353 193 354 202 354 194 354 202 355 195 355 194 355 202 356 196 356 195 356 202 357 197 357 196 357 202 358 198 358 197 358 199 359 203 359 201 359 204 360 201 360 203 360 201 361 204 361 200 361 200 362 202 362 201 362 203 363 205 363 204 363 206 364 204 364 205 364 205 365 13 365 206 365 10 366 206 366 13 366 87 367 89 367 88 367 208 368 88 368 89 368 89 369 207 369 208 369 211 370 208 370 209 370 208 371 207 371 209 371 209 372 210 372 211 372 213 373 211 373 212 373 211 374 210 374 212 374 212 375 214 375 213 375 216 376 213 376 214 376 214 377 217 377 216 377 216 378 217 378 219 378 217 379 218 379 219 379 227 380 218 380 91 380 219 381 218 381 227 381 228 382 220 382 219 382 221 383 220 383 228 383 229 384 222 384 221 384 223 385 222 385 229 385 223 386 231 386 224 386 366 387 364 387 348 387 366 388 348 388 308 388 314 389 274 389 273 389 314 390 273 390 313 390 312 391 310 391 309 391 311 392 312 392 309 392 286 393 272 393 269 393 286 394 285 394 272 394 330 395 232 395 287 395 287 396 232 396 292 396 292 397 232 397 293 397 293 398 232 398 291 398 291 399 232 399 289 399 289 400 232 400 294 400 294 401 232 401 327 401 298 402 289 402 294 402 293 403 291 403 290 403 293 404 290 404 292 404 296 405 271 405 288 405 290 406 288 406 271 406 290 407 271 407 270 407 272 408 270 408 271 408 313 409 270 409 272 409 284 410 313 410 272 410 313 411 273 411 270 411 292 412 290 412 270 412 292 413 270 413 273 413 294 414 14 414 51 414 272 415 285 415 284 415 279 416 277 416 276 416 347 417 344 417 340 417 32 417 252 417 251 417 32 417 259 417 252 417 233 418 372 418 371 418 372 419 233 419 326 419 247 420 326 420 233 420 234 421 371 421 370 421 371 422 234 422 233 422 248 423 247 423 233 423 370 424 235 424 234 424 370 425 236 425 235 425 237 426 233 426 234 426 233 427 237 427 248 427 238 428 234 428 235 428 234 429 238 429 237 429 239 430 235 430 236 430 235 431 239 431 238 431 236 432 246 432 239 432 249 433 248 433 237 433 240 434 237 434 238 434 237 435 240 435 249 435 241 436 238 436 239 436 238 437 241 437 240 437 239 438 242 438 241 438 242 439 239 439 246 439 246 440 243 440 242 440 250 441 249 441 240 441 240 442 244 442 250 442 244 443 240 443 241 443 241 444 261 444 244 444 261 445 241 445 242 445 242 446 260 446 261 446 260 447 242 447 243 447 243 448 258 448 260 448 262 449 244 449 261 449 244 450 262 450 250 450 263 451 250 451 262 451 246 452 245 452 243 452 245 453 258 453 243 453 236 454 264 454 246 454 326 455 247 455 325 455 278 456 325 456 247 456 247 457 248 457 278 457 277 458 278 458 248 458 248 459 249 459 277 459 276 460 277 460 249 460 249 461 250 461 276 461 275 462 276 462 250 462 250 463 263 463 275 463 346 464 275 464 263 464 259 465 254 465 253 465 259 466 255 466 254 466 259 467 256 467 255 467 259 468 258 468 256 468 258 469 257 469 256 469 260 470 258 470 259 470 259 471 32 471 260 471 32 472 261 472 260 472 5 473 345 473 32 473 345 474 261 474 32 474 262 475 261 475 345 475 345 476 346 476 262 476 346 477 263 477 262 477 328 478 334 478 18 478 18 479 335 479 8 479 18 478 334 478 335 478 265 480 334 480 328 480 266 481 265 481 328 481 333 482 265 482 266 482 332 483 333 483 266 483 331 484 332 484 266 484 266 485 327 485 331 485 232 486 331 486 327 486 14 487 294 487 327 487 303 488 348 488 302 488 308 489 348 489 303 489 303 490 304 490 308 490 307 491 308 491 304 491 304 492 305 492 307 492 305 493 309 493 307 493 305 494 306 494 309 494 311 495 309 495 306 495 31 496 311 496 306 496 358 497 72 497 59 497 59 498 299 498 358 498 356 499 358 499 299 499 299 500 300 500 356 500 353 501 356 501 300 501 300 502 301 502 353 502 351 503 353 503 301 503 301 504 302 504 351 504 351 505 302 505 348 505 19 506 311 506 30 506 30 507 311 507 31 507 297 508 295 508 268 508 267 509 268 509 295 509 267 510 269 510 268 510 267 511 352 511 269 511 267 512 354 512 352 512 267 513 355 513 354 513 357 514 355 514 267 514 45 515 267 515 49 515 267 516 295 516 49 516 267 517 45 517 357 517 45 518 70 518 357 518 268 519 296 519 297 519 271 520 296 520 268 520 272 521 271 521 268 521 268 522 269 522 272 522 352 523 286 523 269 523 281 524 330 524 287 524 274 525 287 525 292 525 287 526 274 526 281 526 274 527 283 527 281 527 292 528 273 528 274 528 274 529 314 529 283 529 283 530 314 530 315 530 346 531 347 531 275 531 347 532 276 532 275 532 347 533 279 534 276 535 279 536 280 536 277 536 280 537 278 537 277 537 280 538 325 538 278 538 280 539 324 539 325 539 280 540 323 540 324 540 280 541 279 541 340 541 279 542 347 542 340 542 322 543 323 543 280 543 340 544 341 544 280 544 280 545 282 545 322 545 282 546 321 546 322 546 282 547 320 547 321 547 282 548 319 548 320 548 282 549 280 549 336 549 280 550 339 550 336 550 280 551 342 551 339 551 280 552 341 552 342 552 336 553 337 553 282 553 283 554 282 554 281 554 282 555 330 555 281 555 282 556 329 556 330 556 282 557 337 557 329 557 282 558 283 558 319 558 283 559 318 559 319 559 283 560 317 560 318 560 283 561 315 561 317 561 359 562 316 562 360 562 361 563 360 563 316 563 361 564 313 564 284 564 361 565 316 565 313 565 284 566 362 566 361 566 284 567 363 567 362 567 284 568 365 568 363 568 350 569 365 569 285 569 365 570 284 570 285 570 285 571 286 571 350 571 349 572 350 572 286 572 286 573 352 573 349 573 296 574 288 574 298 574 289 575 298 575 288 575 288 576 290 576 289 576 291 577 289 577 290 577 294 578 51 578 295 578 51 579 49 579 295 579 51 580 50 580 49 580 294 581 295 581 298 581 295 582 297 582 298 582 296 583 298 583 297 583 59 11 25 11 299 11 25 584 300 584 299 584 25 585 301 585 300 585 302 586 301 586 25 586 25 587 303 587 302 587 25 588 304 588 303 588 25 589 305 589 304 589 25 590 306 590 305 590 25 591 31 591 306 591 310 592 308 592 307 592 307 593 309 593 310 593 308 594 310 594 366 594 367 595 366 595 310 595 367 596 310 596 312 596 368 597 367 597 312 597 369 598 368 598 312 598 20 599 0 599 19 599 0 600 369 600 19 600 311 601 19 601 312 601 19 602 369 602 312 602 316 603 314 603 313 603 316 604 315 604 314 604 316 604 359 604 315 604 359 604 317 604 315 604 359 605 377 605 317 605 377 606 318 606 317 606 377 607 319 607 318 607 14 608 327 608 9 608 327 417 266 417 9 417 266 609 328 609 9 609 18 417 9 417 328 417 330 610 331 610 232 610 331 611 330 611 329 611 331 612 329 612 332 612 329 613 333 613 332 613 338 614 333 614 329 614 333 615 338 615 265 615 338 616 335 616 265 616 335 617 334 617 265 617 335 618 338 618 8 618 338 619 343 619 8 619 343 620 338 620 339 620 338 621 336 621 339 621 338 622 337 622 336 622 338 623 329 623 337 623 7 624 8 624 343 624 339 625 342 625 343 625 344 626 343 626 340 626 343 627 341 627 340 627 343 628 342 628 341 628 343 629 344 629 7 629 344 630 6 630 7 630 4 631 6 631 344 631 344 632 347 632 4 632 5 633 4 633 345 633 4 634 346 634 345 634 4 635 347 635 346 635 348 636 364 636 351 636 365 637 350 637 364 637 350 638 351 638 364 638 353 639 351 639 352 639 351 640 349 640 352 640 351 641 350 641 349 641 352 642 354 642 353 642 356 643 353 643 354 643 354 644 355 644 356 644 358 645 356 645 357 645 356 646 355 646 357 646 357 647 70 647 358 647 72 648 358 648 70 648 359 649 360 649 377 649 360 650 361 650 373 650 361 651 362 651 373 651 373 652 362 652 363 652 363 653 365 653 374 653 374 654 364 654 366 654 374 655 365 655 364 655 375 656 366 656 367 656 367 657 368 657 376 657 372 658 388 658 387 658 372 659 387 659 371 659 371 660 387 660 386 660 371 661 386 661 370 661 370 662 386 662 391 662 391 663 386 663 385 663 379 664 245 664 383 664 264 665 383 665 245 665 393 666 392 666 128 666 124 667 128 667 392 667 124 668 392 668 125 668 390 669 127 669 126 669 390 670 226 670 127 670 177 671 127 671 226 671 236 672 370 672 391 672 401 673 372 673 326 673 128 674 380 674 393 674 393 675 380 675 391 675 380 676 381 676 391 676 381 677 382 677 391 677 382 678 383 678 391 678 383 679 264 679 391 679 264 680 236 680 391 680 172 681 226 681 230 681 173 682 174 682 226 682 174 683 175 683 226 683 175 684 176 684 226 684 177 685 226 685 176 685 377 686 320 686 319 686 377 687 321 687 320 687 377 688 322 688 321 688 377 689 323 689 322 689 377 690 324 690 323 690 377 691 325 691 324 691 377 692 326 692 325 692 326 693 377 693 401 693 377 604 402 604 401 604 403 604 401 604 402 604 230 694 227 694 91 694 227 695 228 695 219 695 228 696 229 696 221 696 229 697 231 697 223 697 373 698 377 698 360 698 374 699 373 699 363 699 375 700 374 700 366 700 376 701 375 701 367 701 378 702 376 702 369 702 376 703 368 703 369 703 0 704 378 704 369 704 225 705 224 705 231 705 378 706 1 706 2 706 378 707 0 707 1 707 384 708 389 708 391 708 385 709 384 709 391 709 372 710 401 710 388 710 403 711 388 711 401 711 377 712 373 712 402 712 373 713 394 713 402 713 395 714 394 714 373 714 373 715 374 715 395 715 396 716 395 716 374 716 374 717 375 717 396 717 397 718 396 718 398 718 396 719 375 719 398 719 376 720 398 720 375 720 399 721 397 721 400 721 397 722 398 722 400 722 376 723 400 723 398 723 400 724 404 724 399 724 378 725 400 725 376 725 404 726 400 726 378 726 455 727 416 727 454 727 455 728 454 728 404 728 446 729 405 729 388 729 403 730 446 730 388 730 421 731 419 731 420 731 435 732 420 732 419 732 411 733 389 733 384 733 452 11 378 11 450 11 422 734 421 734 420 734 423 735 422 735 420 735 408 736 407 736 411 736 408 737 411 737 444 737 443 738 408 738 444 738 407 739 389 739 411 739 449 740 411 740 446 740 411 741 405 741 446 741 406 742 405 742 411 742 411 743 386 743 406 743 411 744 385 744 386 744 411 745 384 745 385 745 388 746 405 746 387 746 387 747 405 747 406 747 387 748 406 748 386 748 389 749 407 749 391 749 412 750 444 750 411 750 409 751 442 751 444 751 409 752 444 752 412 752 412 753 413 753 409 753 441 754 442 754 409 754 409 755 410 755 441 755 410 756 440 756 441 756 410 757 409 757 414 757 409 758 413 758 414 758 439 759 440 759 410 759 414 760 415 760 410 760 410 761 452 761 439 761 452 762 438 762 439 762 410 763 455 763 452 763 416 764 455 764 410 764 410 765 415 765 416 765 453 766 438 766 452 766 449 767 427 767 411 767 426 768 411 768 427 768 424 769 411 769 426 769 412 770 411 770 423 770 411 771 424 771 423 771 413 772 412 772 420 772 412 773 423 773 420 773 414 774 413 774 434 774 413 775 436 775 434 775 413 776 420 776 436 776 415 777 414 777 433 777 414 778 432 778 433 778 414 779 434 779 432 779 416 780 415 780 430 780 415 781 433 781 430 781 416 782 428 782 454 782 416 783 430 783 428 783 399 784 404 784 429 784 429 785 431 785 399 785 417 786 431 786 419 786 431 787 435 787 419 787 431 788 417 788 399 788 417 789 397 789 399 789 396 790 397 790 417 790 419 791 421 791 417 791 418 792 417 792 421 792 417 793 418 793 396 793 418 794 395 794 396 794 394 795 395 795 418 795 421 796 422 796 418 796 418 797 448 797 447 797 418 798 422 798 448 798 418 799 447 799 394 799 447 800 402 800 394 800 436 801 420 801 435 801 423 802 425 802 422 802 425 803 448 803 422 803 425 804 423 804 424 804 448 805 425 805 426 805 425 806 424 806 426 806 426 807 427 807 448 807 448 808 427 808 449 808 429 809 404 809 454 809 454 810 428 810 429 810 431 811 429 811 430 811 429 812 428 812 430 812 435 813 431 813 433 813 431 814 430 814 433 814 435 815 432 815 434 815 435 816 433 816 432 816 436 817 435 817 434 817 445 818 443 818 437 818 443 819 451 819 437 819 443 820 453 820 451 820 443 821 438 821 453 821 443 822 439 822 438 822 443 823 440 823 439 823 443 824 441 824 440 824 443 825 442 825 441 825 443 826 444 826 442 826 402 827 447 827 403 827 446 828 403 828 449 828 403 829 447 829 449 829 447 830 448 830 449 830 378 831 455 831 404 831 452 832 455 832 378 832 534 833 532 833 524 833 532 834 522 834 524 834 532 835 520 835 522 835 532 836 519 836 520 836 452 11 450 11 563 11 452 837 563 837 564 837 563 11 450 11 562 11 393 838 456 838 392 838 509 839 510 839 461 839 463 840 461 840 510 840 510 841 552 841 463 841 465 842 463 842 552 842 552 843 550 843 465 843 471 844 460 844 470 844 460 845 469 845 470 845 460 846 468 846 469 846 456 847 472 847 468 847 456 848 393 848 472 848 456 849 468 849 460 849 460 850 462 850 456 850 456 851 457 851 392 851 457 852 456 852 464 852 456 853 462 853 464 853 459 854 392 854 457 854 464 855 466 855 457 855 457 856 458 856 459 856 458 857 457 857 466 857 466 858 467 858 458 858 390 859 459 859 458 859 458 860 526 860 390 860 458 861 545 861 526 861 458 862 467 862 545 862 390 863 526 863 226 863 392 864 459 864 125 864 126 865 125 865 459 865 459 866 390 866 126 866 506 867 507 867 471 867 460 868 471 868 508 868 471 869 507 869 508 869 462 870 460 870 509 870 460 871 508 871 509 871 509 872 461 872 462 872 464 873 462 873 463 873 462 874 461 874 463 874 463 875 465 875 464 875 466 876 464 876 465 876 465 877 550 877 466 877 467 878 466 878 550 878 550 879 548 879 467 879 545 880 467 880 547 880 467 881 548 881 547 881 443 882 445 882 504 882 504 883 473 883 443 883 473 884 408 884 443 884 473 885 504 885 506 885 506 886 471 886 473 886 407 887 408 887 391 887 391 888 468 888 472 888 391 889 469 889 468 889 391 890 470 890 469 890 391 891 473 891 470 891 473 892 471 892 470 892 391 893 408 893 473 893 472 894 393 894 391 894 480 895 481 895 482 895 482 896 483 896 480 896 479 897 480 897 483 897 483 898 484 898 479 898 478 899 479 899 484 899 484 900 485 900 478 900 477 901 478 901 485 901 485 902 486 902 477 902 476 903 477 903 486 903 486 904 487 904 476 904 475 905 476 905 487 905 487 906 488 906 437 906 437 907 475 907 487 907 474 908 475 908 437 908 437 909 488 909 445 909 451 910 474 910 437 910 564 11 489 11 451 11 474 911 451 911 489 911 489 912 490 912 474 912 475 913 474 913 491 913 474 914 490 914 491 914 476 915 475 915 492 915 475 916 491 916 492 916 492 917 493 917 476 917 477 918 476 918 493 918 493 919 494 919 477 919 478 920 477 920 494 920 494 921 495 921 478 921 479 922 478 922 495 922 495 923 496 923 479 923 480 924 479 924 496 924 496 925 497 925 480 925 481 926 480 926 497 926 497 927 498 927 481 927 482 928 481 928 498 928 498 929 499 929 482 929 483 930 482 930 499 930 499 931 500 931 483 931 484 932 483 932 500 932 500 933 501 933 484 933 485 934 484 934 501 934 501 935 502 935 485 935 486 936 485 936 502 936 502 937 503 937 486 937 487 938 486 938 503 938 503 939 505 939 487 939 488 940 487 940 505 940 505 941 504 941 488 941 445 942 488 942 504 942 532 943 530 943 519 943 530 944 517 944 519 944 530 945 528 945 517 945 528 946 516 946 517 946 528 947 514 947 516 947 557 948 514 948 528 948 528 949 529 949 557 949 529 950 564 950 557 950 529 951 489 951 564 951 490 952 489 952 529 952 529 953 531 953 490 953 531 954 491 954 490 954 531 955 533 955 491 955 533 956 492 956 491 956 493 957 492 957 533 957 533 958 535 958 493 958 494 959 493 959 535 959 535 960 538 960 494 960 495 961 494 961 538 961 538 962 540 962 495 962 496 963 495 963 540 963 540 964 541 964 496 964 497 965 496 965 541 965 541 966 542 966 497 966 498 967 497 967 542 967 542 968 543 968 498 968 499 969 498 969 543 969 543 970 544 970 499 970 500 971 499 971 544 971 544 972 546 972 500 972 501 973 500 973 546 973 546 974 549 974 501 974 502 975 501 975 549 975 549 976 551 976 502 976 503 977 502 977 551 977 551 978 553 978 503 978 505 979 503 979 553 979 553 980 554 980 505 980 504 981 505 981 506 981 505 982 554 982 506 982 554 983 555 983 506 983 555 984 507 984 506 984 555 985 556 985 507 985 556 986 508 986 507 986 556 987 509 987 508 987 556 988 552 988 510 988 510 989 509 989 556 989 525 990 527 990 536 990 511 991 527 991 525 991 511 992 230 992 527 992 511 993 227 993 230 993 525 994 523 994 511 994 511 995 512 995 227 995 512 996 511 996 521 996 511 997 523 997 521 997 521 998 518 998 512 998 513 999 512 999 518 999 512 1000 513 1000 227 1000 513 1001 228 1001 227 1001 518 1002 515 1002 513 1002 229 1003 228 1003 513 1003 513 1004 559 1004 229 1004 513 1005 558 1005 559 1005 513 1006 562 1006 558 1006 513 1007 515 1007 562 1007 231 1008 229 1008 561 1008 229 1009 560 1009 561 1009 229 1010 559 1010 560 1010 515 1011 557 1011 562 1011 515 1012 514 1012 557 1012 516 1013 514 1013 515 1013 515 1014 518 1014 516 1014 518 1015 517 1015 516 1015 519 1016 517 1016 518 1016 518 1017 521 1017 519 1017 521 1018 520 1018 519 1018 522 1019 520 1019 521 1019 521 1020 523 1020 522 1020 524 1021 522 1021 523 1021 523 1022 525 1022 524 1022 534 1023 524 1023 525 1023 525 1024 536 1024 534 1024 537 1025 534 1025 536 1025 226 1026 526 1026 230 1026 527 1027 230 1027 526 1027 526 1028 545 1028 527 1028 536 1029 527 1029 545 1029 528 1030 530 1030 529 1030 531 1031 529 1031 530 1031 530 1032 532 1032 531 1032 533 1033 531 1033 532 1033 532 1034 534 1034 533 1034 535 1035 533 1035 534 1035 534 1036 537 1036 535 1036 538 1037 535 1037 537 1037 536 1038 545 1038 537 1038 545 1039 539 1039 537 1039 539 1040 538 1040 537 1040 539 1041 540 1041 538 1041 545 1042 546 1042 539 1042 541 1043 540 1043 539 1043 539 1044 542 1044 541 1044 539 1045 543 1045 542 1045 539 1046 544 1046 543 1046 546 1047 544 1047 539 1047 549 1048 546 1048 547 1048 546 1049 545 1049 547 1049 547 1050 548 1050 549 1050 551 1051 549 1051 550 1051 549 1052 548 1052 550 1052 550 1053 552 1053 551 1053 553 1054 551 1054 552 1054 552 1055 556 1055 553 1055 554 1056 553 1056 556 1056 556 1057 555 1057 554 1057 562 1058 557 1058 563 1058 557 1059 564 1059 563 1059 378 11 562 11 450 11 378 1060 558 1060 562 1060 378 1061 559 1061 558 1061 378 1062 560 1062 559 1062 378 1063 561 1063 560 1063 378 1064 231 1064 561 1064 564 11 451 11 453 11 453 1065 452 1065 564 1065 565 1066 256 1066 257 1066 252 1067 259 1067 253 1067 253 1068 566 1068 252 1068 567 1069 565 1069 257 1069 257 1070 568 1070 567 1070 252 1071 566 1071 569 1071 252 1072 569 1072 570 1072 251 1073 252 1073 570 1073 570 1074 571 1074 251 1074 572 1075 251 1075 571 1075 571 1076 573 1076 572 1076 574 1077 572 1077 573 1077 573 1078 575 1078 574 1078 574 1079 575 1079 576 1079 574 1080 576 1080 577 1080 578 1081 574 1081 577 1081 577 1082 579 1082 578 1082 578 1083 579 1083 120 1083 119 1084 578 1084 120 1084 571 11 570 11 573 11 575 1085 573 1085 570 1085 570 1086 580 1086 575 1086 581 1087 575 1087 580 1087 580 11 582 11 581 11 583 11 581 11 582 11 582 11 584 11 583 11 585 1088 583 1088 584 1088 584 11 586 11 585 11 587 11 585 11 586 11 586 11 588 11 587 11 589 11 587 11 588 11 591 11 589 11 590 11 592 11 591 11 590 11 595 11 593 11 590 11 594 1089 596 1089 592 1089 590 1090 597 1090 595 1090 707 1091 592 1091 596 1091 598 1092 595 1092 597 1092 596 1093 599 1093 707 1093 597 1094 600 1094 598 1094 601 1095 707 1095 599 1095 602 11 598 11 600 11 599 1096 603 1096 601 1096 604 11 601 11 603 11 600 1097 605 1097 602 1097 603 11 606 11 604 11 607 1098 602 1098 605 1098 604 11 606 11 608 11 609 11 604 11 608 11 610 11 611 11 607 11 605 11 610 11 607 11 612 1099 611 1099 610 1099 608 11 612 11 609 11 613 11 609 11 612 11 614 1100 613 1100 612 1100 610 11 614 11 612 11 615 1101 616 1101 617 1101 618 1102 617 1102 616 1102 619 417 621 417 620 417 622 1103 620 1103 621 1103 621 417 623 417 622 417 624 417 622 417 623 417 623 417 625 417 624 417 624 1104 625 1104 626 1104 627 1105 624 1105 626 1105 626 1106 628 1106 627 1106 629 1107 627 1107 628 1107 628 417 630 417 629 417 632 604 633 604 634 604 635 604 632 604 634 604 120 1108 636 1108 122 1108 637 1109 122 1109 636 1109 636 1110 638 1110 637 1110 639 1111 637 1111 638 1111 638 1112 640 1112 639 1112 641 1113 639 1113 640 1113 640 1114 642 1114 641 1114 643 1115 641 1115 642 1115 642 1116 644 1116 643 1116 645 1117 643 1117 644 1117 644 1118 646 1118 645 1118 647 1119 645 1119 646 1119 646 1120 648 1120 647 1120 649 1121 647 1121 648 1121 648 1122 615 1122 649 1122 617 1123 649 1123 615 1123 256 1124 650 1124 255 1124 651 1125 255 1125 650 1125 650 1126 652 1126 651 1126 653 1127 651 1127 652 1127 652 1128 654 1128 653 1128 655 1129 653 1129 654 1129 654 1130 656 1130 655 1130 657 1131 655 1131 656 1131 656 1132 658 1132 657 1132 659 1132 657 1132 658 1132 658 1133 660 1133 659 1133 661 1134 659 1134 660 1134 660 1135 662 1135 661 1135 663 1135 661 1135 662 1135 662 1136 635 1136 663 1136 634 1137 663 1137 635 1137 651 1138 254 1138 255 1138 653 1139 566 1139 253 1139 653 1140 253 1140 254 1140 651 1141 653 1141 254 1141 653 1142 655 1142 566 1142 664 1143 570 1143 569 1143 664 1144 569 1144 566 1144 566 1145 655 1145 657 1145 664 1146 566 1146 657 1146 580 1147 570 1147 664 1147 657 1148 659 1148 664 1148 664 1149 659 1149 661 1149 665 1150 664 1150 661 1150 665 1151 582 1151 580 1151 664 1152 665 1152 580 1152 584 1153 582 1153 665 1153 661 1154 663 1154 665 1154 669 1155 586 1155 584 1155 665 1156 669 1156 584 1156 665 1157 663 1157 634 1157 665 1158 634 1158 666 1158 669 1159 665 1159 666 1159 586 1160 669 1160 667 1160 588 1161 586 1161 667 1161 668 1162 597 1162 667 1162 667 1163 669 1163 668 1163 670 1164 668 1164 669 1164 669 1165 666 1165 670 1165 670 1166 666 1166 634 1166 670 1167 634 1167 633 1167 671 1168 670 1168 633 1168 591 11 592 11 589 11 589 1169 592 1169 672 1169 673 1170 589 1170 672 1170 672 1171 674 1171 673 1171 675 1172 673 1172 674 1172 674 1173 676 1173 675 1173 677 1174 675 1174 676 1174 676 1175 616 1175 677 1175 615 1176 677 1176 616 1176 120 1177 579 1177 636 1177 638 1178 636 1178 579 1178 579 1179 577 1179 638 1179 638 1180 577 1180 678 1180 640 1181 638 1181 678 1181 679 1182 642 1182 640 1182 678 1183 679 1183 640 1183 576 1184 575 1184 679 1184 679 1185 678 1185 576 1185 575 1186 581 1186 679 1186 644 1187 642 1187 679 1187 679 1188 581 1188 583 1188 680 1189 679 1189 583 1189 680 1190 646 1190 644 1190 679 1191 680 1191 644 1191 583 1192 585 1192 680 1192 648 1193 646 1193 680 1193 680 1194 585 1194 587 1194 680 1195 587 1195 589 1195 680 1196 589 1196 673 1196 675 1197 680 1197 673 1197 680 1198 675 1198 648 1198 648 1199 675 1199 677 1199 615 1200 648 1200 677 1200 681 1201 682 1201 617 1201 618 1202 681 1202 617 1202 683 1203 682 1203 681 1203 681 1204 684 1204 683 1204 685 1205 683 1205 684 1205 684 1206 630 1206 685 1206 628 1207 685 1207 630 1207 686 1208 687 1208 629 1208 631 1209 686 1209 629 1209 688 1210 687 1210 686 1210 686 1211 689 1211 688 1211 690 1212 688 1212 689 1212 689 1213 632 1213 690 1213 635 1214 690 1214 632 1214 256 1215 691 1215 650 1215 652 1216 650 1216 691 1216 691 1217 692 1217 652 1217 654 1218 652 1218 692 1218 692 1219 693 1219 654 1219 656 1220 654 1220 693 1220 694 1221 658 1221 656 1221 693 1222 694 1222 656 1222 695 1223 620 1223 694 1223 696 1224 695 1224 694 1224 697 1225 696 1225 694 1225 694 1226 693 1226 697 1226 620 1227 622 1227 694 1227 660 1228 658 1228 694 1228 694 1229 622 1229 624 1229 694 1230 624 1230 627 1230 694 1231 627 1231 629 1231 694 1232 629 1232 687 1232 688 1233 694 1233 687 1233 688 1234 662 1234 660 1234 694 1235 688 1235 660 1235 662 1236 688 1236 690 1236 635 1237 662 1237 690 1237 245 1238 257 1238 258 1238 246 1239 264 1239 245 1239 568 1240 257 1240 245 1240 379 1241 698 1241 699 1241 699 1242 568 1242 245 1242 700 1243 379 1243 383 1243 383 1244 382 1244 700 1244 381 1245 701 1245 700 1245 382 1246 381 1246 700 1246 100 1247 701 1247 381 1247 381 1248 380 1248 100 1248 100 1249 110 1249 123 1249 100 1250 380 1250 128 1250 702 1251 606 1251 603 1251 608 11 606 11 702 11 612 1252 608 1252 702 1252 611 1253 612 1253 702 1253 607 1254 611 1254 702 1254 602 11 607 11 702 11 702 1255 598 1255 602 1255 595 11 598 11 702 11 593 11 595 11 702 11 594 1256 593 1256 702 1256 596 11 594 11 702 11 599 11 596 11 702 11 603 1257 599 1257 702 1257 703 1258 597 1258 668 1258 668 1259 670 1259 703 1259 704 1260 703 1260 670 1260 670 1261 671 1261 704 1261 672 1262 705 1262 674 1262 676 1263 674 1263 705 1263 705 1264 706 1264 676 1264 676 1265 706 1265 616 1265 708 1266 600 1266 597 1266 703 1267 708 1267 597 1267 704 1268 671 1268 708 1268 703 1269 704 1269 708 1269 671 1270 709 1270 708 1270 605 1271 600 1271 708 1271 710 1272 708 1272 709 1272 710 1273 610 1273 605 1273 708 1274 710 1274 605 1274 709 1275 711 1275 710 1275 614 1276 610 1276 710 1276 710 1277 711 1277 712 1277 713 1278 710 1278 712 1278 710 1279 713 1279 614 1279 613 1280 614 1280 713 1280 712 1281 714 1281 713 1281 715 1282 713 1282 714 1282 713 1283 715 1283 613 1283 609 1284 613 1284 715 1284 714 1285 716 1285 715 1285 717 1286 604 1286 609 1286 715 1287 717 1287 609 1287 717 1288 715 1288 716 1288 601 1289 604 1289 717 1289 716 1290 616 1290 717 1290 705 1291 707 1291 601 1291 717 1292 705 1292 601 1292 717 1293 616 1293 706 1293 717 1294 706 1294 705 1294 672 1295 707 1295 705 1295 720 1296 699 1296 698 1296 721 1297 699 1297 720 1297 720 1298 719 1298 721 1298 722 1299 721 1299 719 1299 719 1300 718 1300 722 1300 722 1301 718 1301 619 1301 722 1302 619 1302 620 1302 32 417 251 417 572 417 32 1303 572 1303 574 1303 32 1304 574 1304 578 1304 32 1305 578 1305 119 1305 33 417 32 417 119 417 577 1306 576 1307 678 1308 698 1309 379 1309 700 1309 700 1310 701 1310 698 1310 707 1311 672 1311 592 1311 245 1312 379 1312 699 1312 620 1313 695 1313 722 1313 699 1314 721 1314 722 1314 695 1315 699 1315 722 1315 695 1316 696 1316 699 1316 696 1317 697 1317 699 1317 568 1318 699 1318 697 1318 568 1319 697 1319 693 1319 568 1320 693 1320 692 1320 567 1321 568 1321 692 1321 567 1322 692 1322 691 1322 565 1323 567 1323 691 1323 256 1324 565 1324 691 1324 588 11 590 11 589 11 588 1325 667 1325 590 1325 629 417 630 417 631 417 631 417 724 417 723 417 630 417 724 417 631 417 671 1326 633 1326 632 1326 689 1327 726 1327 632 1327 686 1328 726 1328 689 1328 723 1329 727 1329 726 1329 723 1330 728 1330 727 1330 723 1331 724 1331 728 1331 724 1332 729 1332 728 1332 724 1333 725 1333 729 1333 681 1334 618 1334 725 1334 681 1335 725 1335 684 1335 122 1336 739 1336 745 1336 745 1337 739 1337 744 1337 744 1338 739 1338 738 1338 744 1339 738 1339 743 1339 743 1340 738 1340 737 1340 743 1341 737 1341 733 1341 743 1342 733 1342 732 1342 734 1343 732 1343 733 1343 735 1344 732 1344 734 1344 735 1345 730 1345 732 1345 732 1346 730 1346 731 1346 742 1347 730 1347 735 1347 100 1348 732 1348 701 1348 730 1349 742 1349 619 1349 730 1350 619 1350 718 1350 719 1351 730 1351 718 1351 730 1352 719 1352 731 1352 720 1353 731 1353 719 1353 731 1354 720 1354 732 1354 720 1355 698 1355 732 1355 732 1356 100 1356 743 1356 701 1357 732 1357 698 1357 743 1358 100 1358 123 1358 617 1359 682 1359 649 1359 649 1360 682 1360 683 1360 736 1361 647 1361 683 1361 683 1362 647 1362 649 1362 683 1363 685 1363 736 1363 736 1364 685 1364 628 1364 736 1365 628 1365 626 1365 736 1366 626 1366 740 1366 736 1367 740 1367 741 1367 647 1368 736 1368 645 1368 742 1369 736 1369 741 1369 736 1370 733 1370 737 1370 733 1371 736 1371 734 1371 734 1372 736 1372 735 1372 735 1373 736 1373 742 1373 737 1374 643 1374 736 1374 736 1375 643 1375 645 1375 643 1376 737 1376 641 1376 738 1377 641 1377 737 1377 641 1378 738 1378 639 1378 739 1379 639 1379 738 1379 639 1380 739 1380 637 1380 122 1381 637 1381 739 1381 623 417 740 417 625 417 740 417 623 417 741 417 621 417 741 417 623 417 741 417 621 417 742 417 619 417 742 417 621 417 123 1382 744 1382 743 1382 744 1383 123 1383 745 1383 745 1384 123 1384 122 1384 625 1385 740 1385 626 1385 590 1386 594 1386 592 1386 590 1387 593 1387 594 1387 590 1388 667 1388 597 1388 631 1389 723 1389 686 1389 686 1390 723 1390 726 1390 630 1391 684 1391 724 1391 684 1392 725 1392 724 1392 709 1393 671 1393 726 1393 671 1394 632 1394 726 1394 716 1395 714 1395 729 1395 716 1396 729 1396 725 1396 714 1397 712 1397 728 1397 714 1398 728 1398 729 1398 712 1399 711 1399 727 1399 712 1400 727 1400 728 1400 711 1401 709 1401 726 1401 711 1402 726 1402 727 1402 616 1403 716 1403 725 1403 616 1404 725 1404 618 1404 2 1405 231 1405 378 1405 2 1406 3 1406 231 1406 3 1407 225 1407 231 1407 14 1408 68 1408 65 1408 14 1409 52 1409 68 1409 14 1410 54 1410 52 1410 14 1411 55 1411 54 1411 14 1412 65 1412 64 1412 14 1413 64 1413 47 1413 14 1414 47 1414 35 1414 14 1415 35 1415 48 1415 25 1416 59 1416 58 1416 25 1417 58 1417 40 1417 25 1418 40 1418 39 1418 25 1419 39 1419 38 1419 25 1420 38 1420 34 1420 25 1421 34 1421 37 1421 25 1422 37 1422 36 1422 25 1423 36 1423 60 1423

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 -8.74228e-13 0 0 0.001 2e-5 0 0 0 1 + + + + + + + + + + -0.2908648 -0.7711008 0.5663932 4.076245 0.9551711 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054209 -0.6141704 -6.925791 -4.01133e-9 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E4.dae b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E4.dae new file mode 100644 index 0000000..c0006dd --- /dev/null +++ b/URDFs/sr_description/meshes/components/lf_metacarpal/lf_metacarpal_E4.dae @@ -0,0 +1,122 @@ + + + + + + Blender User + Blender 3.4.1 commit date:2022-12-19, commit time:17:00, hash:55485cb379f7 + + 2023-01-24T13:24:42 + 2023-01-24T13:24:42 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.04392 0.04392 0.04392 1 + + + 0.21961 0.21961 0.21961 1 + + + 0.45000 0.45000 0.45000 1 + + + 32 + + + 1 + + + + + + + + + + + + + + + + + 15.24394 28.83184 -10.19179 15.15641 29.00881 -10.11973 16.28063 28.22163 -10.60002 14.57222 29.1015 9.876283 14.62054 29.38403 9.815271 14.14129 29.71961 9.496663 17.19709 24.4059 11 13.58356 19.24524 11 13.95005 18.98862 10.9909 16.66886 27.94979 10.72016 15.90375 26.85547 10.72037 17.96525 27.04204 10.96452 16.50399 25.73502 10.91928 19.05489 26.27907 10.9909 17.18743 24.42452 10.99998 16.24709 28.24511 10.58858 15.20964 28.0795 10.34644 15.82677 26.99567 10.68638 20.18497 25.48778 -10.84722 17.19709 24.4059 -11 19.74515 25.79575 -10.92409 16.70725 25.56796 -10.94805 17.99997 27.01774 -10.96785 16.21324 26.71866 -10.79132 15.73475 27.7926 -10.54219 19.71056 25.81997 10.92899 16.31016 17.33606 10.4843 21.4175 24.62475 10.48333 23.02203 23.50125 9.644258 18.47743 15.81852 9.236211 23.58226 23.10898 9.236211 24.46393 22.49162 8.443261 20.29858 14.54334 7.334888 25.40341 21.83379 7.334888 21.64481 13.60069 4.914807 26.65152 20.95985 5.147668 25.68908 21.63376 6.92541 22.42091 13.05726 2.147126 27.31513 20.49519 3.176747 26.74964 20.89115 4.914807 27.65837 20.25485 -1.044302 27.67682 20.24193 -0.772409 22.57199 12.95148 -0.772409 27.65499 20.25721 1.086611 27.52574 20.34772 2.147126 27.32512 20.48819 -3.136025 22.08736 13.29081 -3.637316 27.1922 20.58127 -3.637316 26.66776 20.94848 -5.110062 21.00131 14.05128 -6.244975 26.10614 21.34173 -6.244975 25.71095 21.61844 -6.892333 19.39064 15.17908 -8.410959 24.49061 22.47294 -8.415952 23.05253 23.4799 -9.623743 17.36926 16.59447 -9.98208 22.47409 23.88492 -9.98208 21.45067 24.60153 -10.47038 15.08014 18.19733 -10.84722 13.58356 19.24524 -11 10.03184 32.99863 0.7997995 10.01044 33.01557 -9.68028e-7 9.750011 33.22169 -9.68028e-7 11.52991 31.81297 6.367964 11.65032 31.71766 6.682518 11.77484 31.61911 6.800168 12.37316 31.14557 7.738904 12.37316 31.14557 7.695065 10.17147 32.88812 2.181476 9.750011 33.22169 6.513397 10.43861 32.67669 3.520436 10.16236 32.89533 6.501855 10.55752 32.58257 3.96143 10.41336 32.69667 6.552432 10.9868 32.24282 5.207934 10.41889 32.69229 6.554837 10.61476 32.53728 6.682518 12.37686 31.06437 7.774355 12.37686 31.06437 7.788693 12.32551 30.99103 7.788693 11.66147 31.82223 7.929289 11.2012 32.14452 7.367402 11.67901 31.85667 7.934671 10.74642 32.50373 6.796953 11.68239 31.86863 7.938762 10.7515 32.52043 6.802366 11.68506 31.89204 7.949999 10.7513 32.56526 6.828248 11.68218 31.91346 7.964643 11.6787 31.92295 7.972939 10.73002 32.59652 6.863603 11.6609 31.94471 7.999999 10.48931 32.70402 6.588497 10.63411 32.59055 6.682518 10.62966 32.56142 6.682518 10.46483 32.66012 6.576119 10.62315 32.54927 6.682518 10.20872 32.96154 6.599999 10.49084 32.76399 6.668508 10.20103 32.95057 6.549999 10.49883 32.74204 6.622313 10.18592 32.92898 6.520193 10.18004 32.92058 6.513397 12.0658 31.5996 8.547881 12.0879 31.57989 8.517829 12.09603 31.54936 8.489876 12.08874 31.51343 8.468997 12.06733 31.47851 8.458907 12.3925 31.19813 8.937557 12.37469 31.21312 8.902323 12.28423 31.28689 8.756451 12.14002 31.40173 8.562484 12.3992 31.18345 9.077331 12.42509 31.16744 9.047613 12.42517 31.16775 9.042554 12.41995 31.17379 9.009221 10.23481 32.94327 -9.68028e-7 10.10722 33.00242 -9.68028e-7 10.18408 32.94861 1.416438 19.82218 25.91082 -10.89954 18.08093 27.13006 -10.9432 16.36545 28.33125 -10.57619 21.52387 24.71928 -10.44685 25.77458 21.74291 -6.876841 24.55698 22.59548 -8.397036 23.12213 23.60017 -9.602112 26.72923 21.07445 -5.098577 27.71761 20.38238 -1.041955 27.38512 20.6152 -3.128977 27.71425 20.38474 1.084169 27.37515 20.62218 3.169607 26.71303 21.08579 5.136098 25.75276 21.75819 6.909845 24.53035 22.61412 8.424283 23.0917 23.62148 9.622582 21.49078 24.74246 10.45977 19.78767 25.93499 10.90443 18.04629 27.15431 10.93987 16.33199 28.35468 10.56478 14.70909 29.49104 9.79321 13.23851 30.52076 8.65413 13.14664 30.41607 8.673625 12.11545 31.4834 7.129727 13.3679 30.60643 8.581246 11.11576 32.18339 5.410649 10.5714 32.6774 3.442238 11.27141 32.18725 5.33886 10.31068 32.89014 1.398177 10.69301 32.62243 3.397859 11.38399 32.1386 5.270028 12.25784 31.49655 7.035128 12.3577 31.45681 6.944427 13.49366 30.63121 8.467388 13.57759 30.60263 8.358221 14.93251 29.62372 9.581888 14.99789 29.60812 9.458353 16.52039 28.51188 10.3368 16.56529 28.51061 10.20354 18.1977 27.33741 10.70381 18.22098 27.35129 10.56581 19.9015 26.14439 10.66913 19.90282 26.17365 10.53157 21.56786 24.9776 10.23406 21.54769 25.0219 10.10212 23.13424 23.88081 9.41494 23.09387 23.93926 9.293558 24.54185 22.89519 8.242501 24.48333 22.96634 8.136233 25.73787 22.05772 6.760741 25.66394 22.13967 6.673577 26.67743 21.39984 5.025269 26.59139 21.49027 4.96048 27.32525 20.94623 3.101212 27.23085 21.04251 3.061229 27.65704 20.71391 1.060774 27.55837 20.81318 1.047098 27.66033 20.71161 -1.019471 27.56161 20.81091 -1.006327 27.33501 20.9394 -3.061459 27.24049 21.03576 -3.021988 26.69328 21.38874 -4.988558 26.60703 21.47931 -4.924242 25.75922 22.04277 -6.728449 25.68502 22.12492 -6.641702 24.5679 22.87695 -8.215841 24.50905 22.94833 -8.109917 23.16401 23.85996 -9.394913 23.12326 23.91868 -9.273789 21.60024 24.95493 -10.22142 21.57966 24.99952 -10.08964 19.93527 26.12075 -10.66434 19.93615 26.15032 -10.52685 18.23159 27.31368 -10.70706 18.25443 27.32787 -10.56902 16.55313 28.48895 -10.34797 16.59762 28.48798 -10.21456 16.4685 28.43536 -10.48712 15.3562 29.21421 -10.01191 15.41926 29.24765 -9.935694 15.28828 29.16065 -10.07039 18.16953 27.24429 -10.85104 19.89612 26.03532 -10.80774 21.58348 24.85382 -10.35886 23.16828 23.74413 -9.521243 24.59105 22.7479 -8.326315 25.79839 21.90251 -6.818924 26.745 21.23968 -5.055637 27.39536 20.78429 -3.102625 27.72506 20.55344 -1.033179 27.72172 20.55578 1.075038 27.38548 20.79122 3.142913 26.72894 21.25093 5.092842 25.77675 21.91766 6.85165 24.56464 22.76639 8.353334 23.1381 23.76526 9.54154 21.55067 24.8768 10.37168 19.8619 26.05928 10.81259 18.13519 27.26834 10.84774 16.43532 28.4586 10.4758 14.8261 29.58539 9.710731 15.51427 29.24655 -9.751733 4.572886 25.55459 4.795831 7.444703 23.54371 -9.372173 9.655044 21.99602 -11 5.072045 25.20507 11 5.02114 25.24071 10.93541 3.874928 26.0433 1.87855 3.809091 26.0894 -1.271741 4.572886 25.55459 10.5 4.577116 25.55163 10.50365 4.820909 25.38092 10.72168 4.417338 25.6635 -4.334328 5.657721 24.79497 -7.098003 9.353471 33.56039 -8.000001 9.353471 33.56039 -5.400001 10.20631 32.96322 -8.000001 9.411291 33.5199 -5.400001 11.5911 31.99357 -8.000001 9.411285 33.51991 -9.68028e-7 14.44469 29.99548 -9.244922 13.36179 30.75373 -8.783811 12.37516 31.44458 -8.363509 11.62714 31.96835 -8.01675 10.20632 32.96321 -9.68028e-7 11.60685 31.98255 -8.007061 11.60607 31.98309 -8.009023 -9.072088 50.58312 5.299999 -9.065318 50.71726 5.458006 -9.073472 50.5557 5.206056 -9.07295 50.56603 4.969829 -9.077876 50.46842 5.026518 -9.080988 50.40674 4.940987 -9.070929 50.60607 5.499999 -9.070929 50.60607 7.000012 -9.065318 50.71726 7.483882 -9.068898 50.64631 7.296033 -9.115318 50.71814 7.999999 -9.115318 50.71814 7.660391 -9.177773 49.63633 7.999999 -9.120382 50.58982 7.396995 -9.123229 50.52246 7.000012 -9.125215 50.47725 5.234472 -9.135172 50.27039 4.916296 -9.123229 50.52246 5.499999 -9.245945 49.07587 4.699999 -9.270434 48.9533 4.699999 -9.270434 48.9533 7.999999 -9.26948 48.95748 4.699999 -9.286496 48.52361 4.585476 -9.126911 48.52361 4.581648 -9.316352 48.44679 4.563062 -9.126911 48.34368 4.488988 -9.385329 48.28816 4.48523 -9.59939 47.82141 4.099999 -9.598393 47.8243 4.103815 -9.494178 47.99711 4.099999 -9.512303 48.0291 4.284126 -9.327357 48.11589 4.099999 -9.50121 48.052 4.304152 -9.34694 48.16064 4.315553 -9.42161 48.21234 4.434054 -9.390833 48.27641 4.47784 -9.126911 48.20668 4.315553 -9.126911 48.15782 4.099999 -9.07295 48.52361 4.581648 -9.07295 48.33389 4.480877 -9.07295 48.20397 4.309802 -9.07295 48.15782 4.099999 -9.100523 50.38531 4.937105 -9.118142 50.35281 4.93122 -9.109964 50.52341 5.217989 -9.124011 50.33638 4.928244 -9.10794 50.57142 5.499999 -9.298532 48.75817 4.642472 -9.306759 48.66827 4.626194 -9.325268 48.6731 4.649999 -9.294928 48.81262 4.659444 -9.303274 48.81466 4.699999 -9.26798 48.95273 4.677702 -9.338232 48.67648 4.699999 -9.303328 48.52361 4.58762 -9.334377 48.52361 4.599999 -9.389518 48.44911 4.61372 -9.315117 48.59157 4.612306 -9.449671 48.20673 4.451641 -9.470626 48.19434 4.474781 -9.358234 48.45236 4.580537 -9.482111 48.17656 4.500865 -9.403667 48.43769 4.655674 -9.267193 48.95697 4.67847 -9.072949 64.57735 -8.347739 -9.072938 64.61064 -8.419133 -9.07295 64.03921 -8.327464 -9.07295 57.92221 -0.8922639 -9.07295 48.52361 4.599999 -9.07295 63.81996 -7.522195 -9.07295 62.66981 -7.142082 -9.07295 62.83972 -8.000001 -9.07295 61.59223 -6.586834 -9.0737 50.5187 -8.000001 -9.07295 60.61447 -5.870262 -9.07295 59.76049 -5.009916 -9.07295 48.15782 -6.000001 -9.076738 48.54871 -6.049186 -9.07295 63.94106 -7.569444 -9.07295 64.26374 -7.846342 -9.072959 50.51814 -6.050001 -9.07303 57.97973 -0.9425123 -9.07295 58.13217 -1.791386 -9.07295 58.50395 -2.945194 -9.07295 59.05119 -4.026868 -9.07295 50.71814 6.849999 -9.07295 50.87221 7.424999 -9.07295 51.29314 7.845928 -9.07295 50.6789 5.222608 -9.07295 57.92218 7.992073 -9.07295 50.71814 5.499999 -9.07295 57.73088 7.999999 -9.07295 51.86814 7.999999 2.926561 54.26222 7.999999 4.01974 54.60732 7.999999 3.812652 54.60806 7.999999 2.927051 54.77745 7.999999 2.927051 54.64222 7.999999 2.926758 54.33885 7.999999 -3.931151 54.60924 7.999999 -4.165639 54.60732 7.999999 -3.072459 54.26222 7.999999 -3.072657 54.33885 7.999999 -3.072949 54.64222 7.999999 -3.072949 54.77745 7.999999 8.927051 34.4501 -9.68028e-7 8.927051 38.16814 -9.68028e-7 8.877052 34.9001 -9.68028e-7 8.877052 38.16814 -9.68028e-7 8.927051 34.4501 -5.400001 8.927051 50.71814 5.499999 8.927051 50.58416 4.999999 8.927051 57.92212 -0.8921974 8.927051 34.37954 -5.400001 8.927051 34.37954 -8.000001 8.927051 62.83972 -8.000001 8.927051 61.89363 -6.764053 8.927038 64.61063 -8.419127 8.927051 64.57735 -8.34774 8.927051 64.03921 -8.327463 8.927051 64.41 -8.04201 8.927051 60.88453 -6.092334 8.927051 59.99259 -5.271403 8.927051 59.23965 -4.321365 8.927051 38.16814 4.499999 8.927051 49.71814 4.499999 8.927051 50.21814 4.633974 8.927051 64.09359 -7.674409 8.927051 63.81996 -7.522195 8.927051 62.99517 -7.270109 8.927051 51.29314 7.845928 8.927051 50.87221 7.424999 8.927051 51.86814 7.999999 8.927051 50.71814 6.849999 8.927051 57.73088 7.999999 8.927051 57.92218 7.992073 8.927131 57.97974 -0.9425168 8.927051 58.2207 -2.129637 8.927051 58.64416 -3.265489 -9.065318 50.71814 5.499999 8.877052 50.71814 5.499999 8.877052 50.58416 4.999999 8.877052 50.21814 4.633974 8.877052 49.71814 4.499999 8.877052 38.16814 4.499999 3.180158 25.30901 -9.67973e-7 -10.2538 6.123332 -9.68028e-7 -10.25848 5.996963 -1.281698 -10.30694 4.69012 -4.251878 -10.30922 4.628711 -4.338896 -6.44733 1.506574 -10.25373 -7.336585 2.008887 -9.561986 -7.545816 2.110517 -9.3834 -5.591895 0.9116564 -10.8187 -5.304727 1.003253 -10.90449 -4.716377 1.471503 -11 -4.95545 1.211991 -10.9794 -8.500487 2.498076 -8.486153 -9.394827 2.776427 -7.488534 -10.36654 3.082757 -6.075489 -10.16453 3.01809 -6.408053 -9.694005 2.869464 -7.098761 3.458939 25.57686 1.337149 3.183659 25.31398 0.02104842 -10.26717 5.762755 -2.159265 4.093495 25.73098 3.448311 4.447854 25.62919 4.447943 3.814965 25.71829 2.60088 3.574216 25.64058 1.779068 8.059919 58.2616 7.005201 8.25942 58.39324 -1.019655 8.057485 58.25895 6.999999 8.121526 58.31797 -1.035131 8.057485 58.25895 -1.035627 8.177854 58.35565 7.221736 8.381305 58.42008 7.503364 8.42403 58.42216 -0.9967375 8.797147 58.25836 -0.9122905 8.669658 58.35937 -0.945557 8.586151 58.39618 7.721493 8.652584 58.36842 -0.9497112 8.574512 58.39994 -0.967776 8.534082 58.41059 -0.9763461 8.737241 58.31432 7.851703 8.788137 58.26803 7.890346 8.873935 58.14643 -0.8914166 8.834367 58.21216 7.92334 8.911649 58.04532 -0.884481 8.902505 58.07691 7.969581 8.91613 58.02652 -0.8859235 8.927022 57.92752 -0.8917697 -9.03657 58.10941 -0.8873816 -9.062026 58.02651 -0.8859419 -9.072921 57.92755 -0.8919841 -9.048403 58.07691 7.969581 -8.980267 58.21216 7.92334 -8.945252 58.25592 -0.9116792 -8.735476 58.39501 -0.9644284 -8.810908 58.36192 -0.9466953 -8.73205 58.39618 7.721493 -8.906804 58.29438 -0.9221838 -8.883139 58.31432 7.851703 -8.934036 58.26803 7.890346 -8.654773 58.41543 -0.9813905 -8.527204 58.42008 7.503364 -8.490635 58.41535 -1.00882 -8.323752 58.35565 7.221736 -8.32833 58.35825 -1.028334 -8.205817 58.2616 7.005201 -8.267421 58.31797 -1.035131 -8.203385 58.25895 6.999999 -8.203385 58.25895 -1.035627 4.815939 55.81427 5.999999 4.815927 55.81427 6.999999 6.056115 56.53388 6.999999 5.45205 56.15634 -4.500001 4.130725 55.50305 -4.500001 5.45205 56.15634 -1.107088 3.902235 55.41146 5.407328 6.198037 56.63072 -1.035342 4.324727 55.58515 5.660209 4.331454 55.58808 5.664586 -4.276623 55.50305 -4.500001 -3.314348 55.15656 5.099999 -1.506647 54.76197 -4.500001 -1.506647 54.76197 5.099999 1.360748 54.76197 -4.500001 1.360748 54.76197 5.099999 3.168448 55.15656 5.099999 -5.597949 56.15634 -4.500001 -5.597949 56.15634 -1.107088 -4.961838 55.81427 5.999999 -4.806595 55.73875 5.8898 -6.758718 56.93312 -0.9940367 -4.478309 55.58879 5.666035 -6.105163 56.46964 -1.061353 -4.467202 55.58395 5.658793 -4.281552 55.50507 5.541826 -4.058514 55.41532 5.412735 -7.505631 57.55918 -0.9716399 -7.536332 57.58743 6.999999 -6.217548 56.54433 6.999999 -4.961838 55.81427 6.999999 6.974292 57.22205 -0.9718747 7.384059 57.58154 6.999999 0.6645508 64.39076 -6.500001 1.204437 64.93064 -6.500001 -0.0729494 65.66814 -6.500001 1.40205 65.66814 -6.500001 1.204437 66.40563 -6.500001 -1.350337 64.93064 -6.500001 -0.8104496 64.39076 -6.500001 -0.0729494 64.19314 -6.500001 -0.8104496 66.94553 -6.500001 -1.350337 66.40563 -6.500001 -1.547949 65.66814 -6.500001 0.6645508 66.94553 -6.500001 -0.0729494 67.14314 -6.500001 -1.350337 64.93064 -8.400001 -0.8104496 64.39076 -8.400001 -0.0729494 64.19314 -8.400001 0.6645508 64.39076 -8.400001 1.204437 64.93064 -8.400001 1.40205 65.66814 -8.400001 1.204437 66.40563 -8.400001 0.6645508 66.94553 -8.400001 -0.0729494 67.14314 -8.400001 -0.8104496 66.94553 -8.400001 -1.350337 66.40563 -8.400001 -1.547949 65.66814 -8.400001 -1.547949 64.66814 -8.400001 -1.792459 65.3233 -8.400001 -1.611069 65.01779 -8.400001 -1.547949 64.31745 -8.400001 -0.7021113 63.76968 -8.400001 0.3034535 63.70388 -8.400001 1.213461 64.13675 -8.400001 1.796883 64.9584 -8.400001 1.905605 65.96023 -8.400001 1.512027 66.88791 -8.400001 0.7160654 67.50592 -8.400001 -0.2802048 67.65737 -8.400001 -1.223859 67.30381 -8.400001 -1.875329 66.53498 -8.400001 -2.069222 65.5461 -8.400001 -2.069222 65.5461 -8.500001 -1.792459 65.3233 -8.500001 -1.611069 65.01779 -8.500001 -1.547949 64.66814 -8.500001 -1.547949 64.31745 -8.500001 -1.875329 66.53498 -8.500001 -1.223859 67.30381 -8.500001 -0.2802048 67.65737 -8.500001 0.7160654 67.50592 -8.500001 1.512027 66.88791 -8.500001 1.905605 65.96023 -8.500001 1.796883 64.9584 -8.500001 1.213461 64.13675 -8.500001 0.3034535 63.70388 -8.500001 -0.7021113 63.76968 -8.500001 2.249925 70.65354 -8.500001 2.249925 70.65354 -9.409927 0.7241755 71.11006 -9.409926 0.7236204 71.11015 -8.500001 -0.8700752 71.11006 -9.409927 -0.8695192 71.11015 -8.500001 -2.397349 70.65283 -9.409926 -2.395823 70.65354 -8.500001 -2.682737 70.24406 -9.318983 -2.682737 70.24406 -8.500001 -2.637743 70.41177 -8.500001 -2.637743 70.41177 -9.367386 -2.538099 70.55399 -8.500001 -2.538099 70.55399 -9.398971 -5.226839 66.75782 -8.560319 -5.296744 66.34782 -8.500001 -4.85375 67.88037 -8.500001 -4.85375 67.88037 -8.873221 -3.952634 69.23157 -8.500001 -3.952634 69.23157 -9.180331 -7.032312 65.91593 -8.560324 -7.025035 65.90672 -8.556244 -6.960782 65.85787 -8.534179 -6.958089 65.85627 -8.533492 -6.668304 65.70825 -8.500001 -6.75644 65.75368 -8.503081 -6.954875 65.8544 -8.532684 5.150844 66.34782 -8.500001 6.522405 65.70825 -8.500001 5.080937 66.75784 -8.560321 6.730838 65.81299 -8.51689 6.816741 65.85898 -8.534663 6.876536 65.90385 -8.554958 6.886424 65.91594 -8.560329 4.707851 67.88037 -8.500001 3.806735 69.23157 -9.180331 3.806735 69.23157 -8.500001 2.536838 70.24406 -9.318983 2.536838 70.24406 -8.500001 4.707851 67.88037 -8.873221 2.39294 70.55325 -8.500001 2.39294 70.55325 -9.398839 2.492725 70.40987 -8.500001 2.492725 70.40987 -9.366895 2.903618 72.05141 -9.97159 1.451469 72.54435 -9.97159 -3.049517 72.05141 -9.97159 -2.539139 70.9569 -9.532045 -1.597368 72.54435 -9.97159 -1.093727 72.63693 -9.97159 0.9478283 72.63693 -9.97159 -0.0729494 72.71129 -9.97159 0.1178464 59.53433 -11.49463 -0.3395004 59.5502 -11.49538 -0.7472334 59.74903 -11.5 5.139523 64.90647 -11.5 -3.555764 69.62036 -11.5 5.177875 65.24525 -11.5 -2.682737 70.24406 -11.5 5.130097 66.49172 -11.5 1.369476 59.88801 -11.5 0.6013346 59.74903 -11.5 0.5372763 59.70278 -11.49975 2.46051 70.46892 -11.49571 2.536838 70.24406 -11.5 2.286613 70.63463 -11.49112 2.249925 70.65354 -11.4955 3.327752 69.69123 -11.5 -2.67737 70.28581 -11.49981 5.080932 64.5265 -11.5 4.762152 63.0296 -11.5 4.652161 62.66963 -11.5 -4.632687 62.22871 -11.5 -4.892795 62.976 -11.5 -4.988454 63.33458 -11.5 -5.285422 64.90647 -11.5 -1.421125 71.00035 -11.491 -0.1295738 71.16785 -11.491 1.165153 71.02697 -11.491 4.178353 68.77883 -11.5 4.790579 67.69202 -11.5 4.407834 62.05217 -11.5 4.16375 61.60985 -11.5 4.048079 61.44372 -11.5 -5.313954 65.13722 -11.5 -5.291851 66.38442 -11.5 -4.977118 67.59145 -11.5 -4.3874 68.69064 -11.5 -2.580957 70.50522 -11.49455 -2.395823 70.65354 -11.4955 -2.871967 60.40924 -11.5 -3.721092 60.95841 -11.5 -4.454413 61.85507 -11.5 -3.823195 61.04236 -11.5 -4.263532 61.54074 -11.5 3.575191 60.95841 -11.5 2.726066 60.40924 -11.5 -1.515379 59.88801 -11.5 -4.180558 60.36524 -11.40465 -3.232857 59.7312 -11.4 -4.19146 60.35116 -11.4 -1.701357 59.14276 -11.4 -0.07295131 58.94264 -11.4 1.555454 59.14276 -11.4 3.590569 60.93856 -11.4999 3.086955 59.73119 -11.4 4.045561 60.35116 -11.4 -5.597949 62.80033 -8.500001 -6.012185 63.80391 -8.500001 -6.209865 64.62505 -8.500001 -6.404719 65.27549 -8.5 -2.072949 59.77323 -8.500001 -1.449825 59.59737 -8.500001 5.791963 63.5809 -8.500001 6.063968 64.62505 -8.500001 6.271283 65.30249 -8.500001 3.788471 60.78502 -8.500001 3.987662 60.94956 -8.500001 4.747403 61.72882 -8.500001 5.358136 62.62599 -8.500001 2.076272 59.82559 -8.500001 3.074546 60.29739 -8.500001 -1.17295 59.54115 -8.500001 -0.07295703 59.44319 -8.500001 1.027051 59.54115 -8.500001 -4.918482 61.76035 -8.500001 -3.93412 60.78537 -8.500001 -2.758489 60.05228 -8.500001 -6.247779 63.18154 -11.22249 -6.849146 64.67797 -11.05001 -6.098371 64.78768 -11.38531 -4.485519 60.5975 -11.39752 -4.932413 61.05155 -11.38342 -5.682283 62.7487 -11.38531 -5.177691 61.46505 -11.38531 -5.994417 62.65978 -11.27243 -5.57697 61.92427 -11.33237 -4.145315 71.46026 -9.945144 -7.520896 68.1108 -9.359498 -8.099767 67.04025 -9.095396 -7.301792 66.33341 -8.739487 -8.320357 66.43018 -8.928084 -8.458874 65.79386 -8.739488 -5.44484 70.51482 -9.833168 -6.579795 69.38865 -9.636259 -7.15658 65.95294 -8.591716 -7.241684 66.03698 -8.632415 -7.280013 66.15098 -8.675965 -7.462232 65.65814 -8.473331 -7.469335 65.6265 -8.458097 -7.40405 65.54854 -8.43083 -7.488981 65.51473 -8.403651 -7.497527 65.44336 -8.368857 -7.400498 65.54574 -8.430075 -7.503437 65.23511 -8.27259 -7.48319 65.04778 -8.202864 -7.141819 65.32446 -8.404862 -7.408339 65.83882 -8.556616 -7.317228 66.06656 -8.64731 -7.349184 65.99114 -8.619361 -6.884102 65.4236 -8.470141 -6.842358 64.99455 -8.433097 -7.573463 64.39341 -7.944629 -7.073121 64.47839 -8.298125 -6.922511 64.50396 -8.364793 -6.496241 64.57639 -8.478793 -7.49678 64.7114 -8.080444 -7.524546 64.57365 -8.023541 -7.440721 64.75251 -8.130349 -7.428176 65.03401 -8.224197 -7.475433 64.9335 -8.164704 -7.48422 64.79853 -8.114807 7.161157 66.08776 -8.654748 7.134053 66.14961 -8.675529 7.086156 66.02246 -8.626201 7.338891 65.05726 -8.2058 7.240138 65.5347 -8.427241 7.337298 65.04777 -8.202856 6.994132 65.32592 -8.405595 6.891955 65.91653 -8.561373 7.312625 65.66727 -8.477833 7.301597 65.71211 -8.49903 7.015033 65.95471 -8.592897 7.268083 65.82647 -8.551151 7.267356 65.82859 -8.552083 7.206849 65.97948 -8.614837 7.260661 65.55048 -8.431357 7.322677 65.6231 -8.456614 7.357953 65.238 -8.27373 7.359233 65.29447 -8.298586 7.3338 65.56795 -8.42978 6.618846 64.53076 -8.419168 6.73784 64.66875 -8.390835 6.697482 65.17483 -8.451251 7.166059 64.43782 -8.158402 7.427571 64.3934 -7.944619 7.342191 64.52237 -8.042103 7.365205 64.63484 -8.049194 7.281293 64.87448 -8.173338 7.338643 64.79579 -8.113756 3.999416 71.46026 -9.945144 8.312973 65.79386 -8.739489 8.173408 66.43394 -8.929164 7.155892 66.33341 -8.739487 7.953868 67.04025 -9.095396 7.374997 68.1108 -9.359498 6.433896 69.38865 -9.636258 5.298942 70.51482 -9.833167 7.688777 68.1345 -10.09209 7.729943 68.21289 -9.866684 8.295425 67.01258 -9.815318 8.337015 67.09019 -9.589717 8.316459 67.11209 -9.468084 7.670886 68.23098 -9.632518 8.271764 67.11972 -9.358376 7.525462 68.18451 -9.444525 8.114986 67.09426 -9.175563 4.087766 71.59561 -10.04095 2.980434 72.21614 -10.08711 4.166975 71.70777 -10.24043 3.030544 72.3236 -10.27459 4.18992 71.72551 -10.48086 3.041443 72.34697 -10.49493 4.15122 71.64468 -10.70584 3.010984 72.28166 -10.70473 5.513103 70.65386 -10.58849 5.438653 70.5475 -10.71513 4.087149 71.53076 -10.83159 8.199779 66.93394 -9.947852 7.597751 68.04732 -10.22252 6.619008 69.37628 -10.51035 6.567044 69.48588 -9.72638 6.694007 69.55741 -9.9198 6.742997 69.553 -10.15693 6.702517 69.47366 -10.38213 5.552751 70.73402 -10.36343 5.515904 70.72639 -10.12419 5.411202 70.63277 -9.926912 2.947517 72.14555 -10.85909 -3.093417 72.14555 -10.85909 -3.149018 72.26479 -10.73264 -1.619851 72.64576 -10.85909 -1.652355 72.79238 -10.70473 -1.013719 72.75299 -10.85909 -0.0729494 72.96535 -10.70473 -0.0729494 72.81517 -10.85909 1.473952 72.64576 -10.85909 1.49081 72.7218 -10.08711 -0.0729494 72.89306 -10.08711 -3.115956 72.19389 -10.06425 1.516473 72.83756 -10.27459 1.522054 72.86273 -10.49493 1.506456 72.79238 -10.70473 -0.0729494 73.03742 -10.49493 -0.0729494 73.01163 -10.27459 -1.667953 72.86273 -10.49493 -1.662372 72.83756 -10.27459 -1.636709 72.7218 -10.08711 -3.156884 72.28166 -10.70473 -3.186783 72.34577 -10.50603 -3.174816 72.32011 -10.26409 -8.462357 67.11209 -9.468083 -8.41574 67.11975 -9.354818 -7.815013 68.23073 -9.62889 -4.29743 71.64525 -10.70492 -8.441755 67.01302 -9.814374 -7.835089 68.13497 -10.09116 -8.345677 66.93394 -9.947852 -7.74365 68.04732 -10.22252 -7.183615 68.85984 -10.4044 -6.848801 69.47418 -10.38121 -6.764906 69.37628 -10.51035 -5.659351 70.65442 -10.58757 -5.584553 70.5475 -10.71513 -4.233047 71.53076 -10.83159 -4.231359 71.59216 -10.03733 -5.554131 70.62981 -9.923347 -6.709391 69.48349 -9.722915 -7.667329 68.18279 -9.441203 -8.256556 67.09308 -9.172377 -4.311986 71.70664 -10.23665 -5.660575 70.7255 -10.12044 -6.838381 69.55682 -9.9161 -4.335903 71.72586 -10.4783 -5.698662 70.73442 -10.36087 -6.888843 69.55345 -10.15438 -7.875738 68.21342 -9.864154 -8.482777 67.09078 -9.587202 5.549098 68.00767 -11.38531 5.941569 66.62017 -11.38531 1.297832 71.60124 -11.38531 -0.135641 71.75722 -11.38531 -1.5656 71.57176 -11.38531 -2.911864 71.05529 -11.38531 2.654445 71.11259 -11.38531 3.858128 70.31867 -11.38531 5.996798 65.17929 -11.38531 6.753104 65.11839 -11.05001 6.703248 64.67798 -11.05001 5.952464 64.78768 -11.38531 5.983874 68.86379 -11.05001 6.249621 68.29918 -11.05001 6.690995 66.7388 -11.05001 4.841391 69.26398 -11.38531 4.347951 70.89813 -11.05001 5.0244 70.24135 -11.05001 5.453731 69.71203 -11.05001 -0.1434535 72.51593 -11.05001 1.468636 72.34053 -11.05001 2.994286 71.79099 -11.05001 -5.171768 70.23971 -11.05001 -4.600597 70.806 -11.05001 -4.098946 70.23674 -11.38531 -3.265602 71.72654 -11.05001 -2.996872 71.86071 -11.05001 -1.75159 72.30738 -11.05001 -5.68172 69.59738 -11.05001 -5.060284 69.16203 -11.38531 -6.129696 68.86392 -11.05001 -5.741975 67.89141 -11.38531 -6.448352 68.16844 -11.05001 -6.105795 66.49613 -11.38531 -6.857504 66.5993 -11.05001 -6.131344 65.05442 -11.38531 -6.886238 64.97795 -11.05001 5.419311 61.90563 -11.3337 4.792423 61.05832 -11.38314 4.853142 61.16245 -11.38531 5.187827 61.78162 -11.38531 5.431785 62.41014 -11.38531 6.035146 63.03811 -11.23677 5.888564 64.37439 -11.38531 6.636764 64.49365 -11.07346 -0.8484326 57.45591 -11.10042 -2.371984 57.74623 -11.10042 -3.814259 58.31663 -11.10042 -5.124265 59.14691 -11.10042 4.978366 59.14691 -11.10042 3.66836 58.31663 -11.10042 2.226086 57.74623 -11.10042 0.7025337 57.45591 -11.10042 5.927051 57.92218 -11 4.371013 56.93594 -11 2.657866 56.25843 -11 0.848177 55.91357 -11 -0.9940758 55.91357 -11 -2.803765 56.25843 -11 -4.516911 56.93594 -11 -6.072949 57.92218 -11 4.342634 59.47238 -7.944514 4.247888 60.20407 -8.357629 2.932294 59.38369 -8.357629 -4.3938 60.20407 -8.357629 -5.495352 61.29512 -8.357629 -5.572949 60.41116 -7.944445 -6.164355 61.10964 -7.944484 -6.328297 62.60279 -8.357629 -6.805943 62.12538 -7.944535 -7.279636 63.22945 -7.944587 -6.851375 64.0623 -8.357629 -3.078207 59.3837 -8.357629 -1.613746 58.87464 -8.357629 -0.07295703 58.7021 -8.357629 1.467831 58.87464 -8.357629 6.705472 64.06229 -8.357629 6.182393 62.60277 -8.357629 7.150559 63.2798 -7.944606 5.262872 60.24473 -7.944537 6.050055 61.1523 -7.944561 5.349442 61.29511 -8.357629 6.68456 62.17247 -7.944583 -4.792158 59.70031 -7.944445 -3.355275 58.80431 -7.944445 -1.755798 58.24831 -7.944445 -0.07295799 58.05987 -7.944445 1.027051 58.1398 -7.944445 2.197532 58.40657 -7.944468 3.31229 58.85453 -7.944492 -7.302142 62.96318 -10.73662 -7.872949 65.66813 -10.4 -6.596186 59.98657 -10.95402 -6.600894 60.00556 -10.95318 -5.754703 61.10629 -11.18842 -6.943348 61.41389 -10.87096 -6.629515 61.82598 -10.97829 -7.142601 62.26308 -10.80283 -7.27192 62.82906 -10.75 -8.711905 66.35598 -9.566287 -8.525303 66.58299 -9.817767 -8.824494 65.63809 -9.4507 -8.861252 65.67082 -9.363242 -8.880146 65.70904 -9.24794 -8.731072 66.40071 -9.429048 -8.56103 65.80155 -8.769892 -8.54316 66.4603 -9.03923 -8.686983 65.80004 -8.843556 -8.640822 66.4565 -9.147165 -8.787171 65.78485 -8.948119 -8.70727 66.43608 -9.282759 -8.855549 65.75572 -9.081138 -8.880375 65.71574 -9.226062 -8.517216 65.64628 -8.692275 -9.052785 64.81289 -8.704732 -9.029636 64.85073 -8.861642 -9.035517 64.90837 -8.621472 -8.871111 65.20138 -8.583099 -8.912842 65.06562 -8.471243 -8.728026 65.14543 -8.37792 -8.629318 65.38227 -8.565663 -8.72683 65.37344 -8.608451 -8.683229 65.25646 -8.478687 -8.697777 65.22156 -8.450037 -9.052437 64.7374 -8.355716 -8.989019 64.85862 -8.295082 -8.986864 64.99519 -8.541185 -8.888335 64.95763 -8.24556 -8.820843 65.34914 -8.672704 -8.901255 65.30796 -8.757374 -8.891911 65.51109 -8.957189 -8.828232 65.54798 -8.852627 -8.74228 65.57161 -8.766696 -8.644411 65.58164 -8.704425 -8.544693 65.57997 -8.666064 -8.765408 65.02336 -8.21268 -8.958014 65.25149 -8.857072 -8.984391 65.18453 -8.962756 -8.97934 65.1138 -9.064261 -8.913132 65.27474 -9.260337 -8.928637 65.4113 -9.183093 -8.894253 65.3461 -9.306061 -7.517097 66.09214 -8.682685 -7.982596 65.63231 -8.52392 -8.767608 65.01083 -8.188877 -8.769659 64.99916 -8.165041 -8.426494 65.25393 -8.334522 -8.28091 65.22637 -8.228812 -7.806004 65.60141 -8.451249 -7.353081 66.02957 -8.634443 -7.635773 65.52638 -8.394485 -7.821492 65.00396 -8.049262 -7.677113 64.89066 -8.042198 -7.546564 64.76441 -8.062866 -7.823622 64.24887 -7.679823 -7.802027 64.17433 -7.683123 -8.234307 64.05805 -7.217257 -8.203303 63.90032 -7.195087 -8.167277 64.65592 -7.670592 -8.360208 64.44437 -7.380736 -8.034605 64.532 -7.649431 -8.35322 64.42819 -7.370438 -7.918088 64.39322 -7.653131 -8.348664 64.41743 -7.363775 -8.257016 64.14932 -7.241595 -8.311476 64.76007 -7.716324 -8.454668 64.6318 -7.529199 -8.424515 64.57749 -7.480073 -8.548922 64.77789 -7.695358 -8.5158 64.73075 -7.635401 -8.492865 64.69528 -7.594545 -8.661162 64.90949 -7.914846 -8.628798 64.8758 -7.848676 -8.600916 64.89057 -7.86656 -8.457648 64.83845 -7.782908 -8.117683 65.16992 -8.139359 -7.970057 65.09754 -8.082698 -8.703443 64.9488 -8.006389 8.036174 64.65052 -7.659471 7.903481 64.52684 -7.63707 8.143001 64.45861 -7.438647 7.592336 65.44377 -8.341886 7.361926 65.87435 -8.575428 7.52278 65.93444 -8.63592 7.761117 65.51581 -8.406342 7.913981 65.5625 -8.493474 7.85768 65.6132 -8.515771 8.02666 65.1343 -8.109148 8.498247 64.89296 -7.881026 8.189071 65.18798 -8.20174 8.556627 64.94857 -8.005392 8.623764 64.99918 -8.165071 8.346509 64.69459 -7.593796 8.482671 64.87626 -7.849393 8.469551 64.88338 -7.858132 8.326417 64.832 -7.773793 8.180337 64.75422 -7.706307 8.331953 64.67121 -7.568716 8.274847 64.57038 -7.474058 8.153326 64.28726 -7.294454 8.057403 63.90032 -7.195084 8.111091 64.14921 -7.241559 7.901923 63.98928 -7.388017 7.929576 64.17613 -7.422726 7.65548 64.17481 -7.683869 7.692302 64.24358 -7.664802 7.879502 65.06376 -8.049047 7.731141 64.97141 -8.011568 7.586673 64.85859 -7.999947 7.455737 64.73206 -8.015827 8.38459 65.61405 -8.67995 8.621711 65.01084 -8.188891 8.61951 65.02336 -8.21268 8.612602 65.05399 -8.2636 8.577201 65.15832 -8.391242 8.521877 65.29292 -8.506271 8.456319 65.44499 -8.601576 8.670164 65.58787 -8.864302 8.583244 65.60895 -8.778683 8.649736 65.42086 -8.707627 8.865345 64.92038 -8.947059 8.85423 64.96116 -8.992307 8.81701 65.2108 -9.109757 8.808387 65.12525 -9.147842 8.771406 65.25934 -9.249789 8.900026 64.78457 -8.768559 8.819625 65.27562 -9.004301 8.734477 65.71574 -9.226063 8.715354 65.67082 -9.363244 8.678596 65.6381 -9.450701 8.905757 64.75939 -8.729187 8.903602 64.83454 -8.725133 8.885833 64.92829 -8.640011 8.906538 64.7374 -8.355716 8.836738 65.01319 -8.55796 8.843122 64.85862 -8.295082 8.762371 65.08169 -8.486508 8.742439 64.95763 -8.245559 8.790824 65.33601 -8.895336 8.735052 65.55395 -8.969129 8.731887 65.38581 -8.793375 8.711029 65.24407 -8.611787 8.709651 65.75572 -9.081139 8.641275 65.78485 -8.94812 8.541084 65.80004 -8.843556 8.517255 65.80149 -8.82583 8.529146 66.1935 -9.668223 8.564857 66.3601 -9.56747 8.584024 66.40483 -9.430232 8.560232 66.44017 -9.283931 8.493801 66.46053 -9.148319 8.396162 66.46424 -9.040361 -5.015402 70.94404 -10.80449 4.869503 70.94404 -10.80449 7.253077 66.65433 -10.69377 7.72705 65.66814 -10.4 8.199779 65.46655 -10.02603 8.199779 64.48686 -9.958244 -7.398977 66.65433 -10.69377 -8.345677 65.46655 -10.02603 -8.345677 64.48686 -9.958244 6.918902 62.19618 -10.83204 6.055408 61.47006 -11.09473 5.171145 60.75599 -11.25362 6.160512 58.83308 -10.9909 6.282275 59.3143 -10.9789 6.630143 60.71877 -10.91645 7.299222 63.60813 -10.6678 7.287177 63.55311 -10.67396 6.996619 62.26273 -10.80286 6.966693 62.13349 -10.8141 6.702596 61.01798 -10.89802 -6.073211 50.51814 -11 -5.55093 2.448499 -11 6.995961 31.65764 -11 7.632733 31.10294 -11 8.485593 30.50576 -11 5.927051 34.37954 -11 -8.997402 8.73693 -11 -9.07295 9.190549 -11 -7.740763 44.45439 -11 -7.07585 46.00629 -11 -9.07295 40.11814 -11 6.384339 32.52234 -11 6.0211 33.51724 -11 -6.562747 47.46443 -11 -6.456067 47.84092 -11 -6.203246 49.01635 -11 -6.08332 50.17005 -11 -6.726995 3.955941 -11 -7.594649 5.207126 -11 -8.10232 6.109084 -11 -9.020679 40.82879 -11 -8.831702 41.70021 -11 -8.445613 42.81898 -11 -8.565022 7.178742 -11 -8.900551 8.287378 -11 6.526065 59.14499 -5.907755 5.579343 57.70285 -5.060204 6.420791 57.70285 -3.922423 -3.488589 57.70285 -6.774028 -2.812203 56.50389 -5.432595 -1.755605 56.50389 -5.846817 -4.060688 59.14499 -7.908635 -4.751179 56.78759 -4.500001 -3.773492 56.50389 -4.829346 -4.687242 57.70285 -6.021824 -4.084333 56.46711 -4.500001 5.490712 56.26158 -1.249898 6.296344 56.77519 -1.160894 5.628474 56.50389 -2.123758 7.404426 57.70285 -1.28176 7.176869 57.469 -1.101894 8.057491 58.35418 -1.184358 8.057485 59.9503 -4.711941 7.50845 59.14499 -4.579403 8.057479 59.27194 -3.739613 5.922435 60.7863 -7.824521 2.025046 57.70285 -7.290574 3.342556 57.70285 -6.774096 3.914631 59.14499 -7.908714 5.314069 59.14499 -7.030548 7.271304 60.7863 -6.574929 7.792304 62.57668 -7.041354 8.057495 61.72512 -6.272842 8.057498 62.77614 -6.821448 7.03629 57.70285 -2.648163 5.45205 56.23923 -1.253014 5.45205 56.30644 -1.683171 5.45205 56.61574 -2.920344 5.45205 56.76313 -3.342922 5.45205 57.28813 -4.500001 5.427051 57.27171 -4.500001 4.282842 56.62507 -4.500001 -1.17295 55.69116 -4.500001 -0.2802515 55.63285 -4.500001 -1.572949 55.74343 -4.500001 -2.856671 56.02445 -4.500001 -5.597949 56.50189 -2.540536 -5.597949 56.90863 -3.707491 -6.566767 57.70285 -3.922293 -5.597949 57.1856 -4.303596 -7.182241 57.70285 -2.648021 -6.606744 56.89292 -1.142432 -5.774417 56.50389 -2.123644 -6.081224 56.53302 -1.20426 -5.597949 56.23927 -1.253274 -8.203367 58.63645 -2.334903 -8.203384 58.35417 -1.184358 -7.55035 57.70285 -1.281611 -7.42008 57.55634 -1.103771 -8.203372 59.0989 -3.426572 -5.597949 56.49269 -2.5071 -7.65444 59.14499 -4.579253 -8.203377 59.72955 -4.430504 -8.203383 60.51226 -5.320995 -7.417333 60.7863 -6.574782 -7.938344 62.57668 -7.041197 -8.203394 62.4503 -6.673931 -8.2034 63.55599 -7.101736 -6.068489 60.7863 -7.824401 -5.460107 59.14499 -7.03044 0.6345377 57.70285 -7.553378 -0.7805872 57.70285 -7.553364 -2.171091 57.70285 -7.290533 -0.6404562 56.50389 -6.057601 0.4944372 56.50389 -6.057612 1.609589 56.50389 -5.846851 2.666197 56.50389 -5.432649 8.057472 58.4197 -1.535046 8.057476 58.75734 -2.671532 8.057489 60.77507 -5.56362 3.627497 56.50389 -4.82942 4.541223 57.70285 -6.021915 -5.597949 57.28813 -4.500001 -5.725341 57.70285 -5.060091 -6.672081 59.14499 -5.907624 -8.203389 61.42698 -6.075241 3.072806 56.13639 -4.500001 2.337745 55.92449 -4.500001 1.027051 55.69116 -4.500001 -8.887524 50.51814 -9.038352 -7.1113 50.51814 -10.81457 -8.19427 50.51814 -10.12132 -8.9961 63.14444 -8.674682 -8.813227 63.50702 -9.221019 -8.57195 63.9623 -9.65982 -8.721323 65.4748 -9.615975 -8.995617 63.93348 -8.867989 -8.721323 63.82178 -9.439032 -9.060686 64.67833 -8.304001 -9.053107 64.71978 -8.32451 -8.958474 64.86951 -8.221201 -8.990338 64.84291 -8.267131 -8.856724 64.9551 -8.184126 -8.890183 64.94368 -8.220168 -8.352986 64.27286 -7.246483 -8.514811 64.64085 -7.523131 -8.690049 64.63284 -7.529941 -8.856724 64.57612 -7.578144 -8.982529 64.48097 -7.659029 -9.043925 64.39037 -7.73604 -8.514811 64.29991 -7.207314 -8.217685 63.90399 -7.180185 -8.352986 63.92717 -7.085734 -8.407889 63.93265 -7.063426 -8.514811 63.93852 -7.039478 -8.612887 63.93895 -7.037734 -8.690049 64.29394 -7.215967 -8.690049 63.93601 -7.049695 -8.753654 63.93126 -7.069025 -8.856724 64.25164 -7.277219 -8.84112 63.9207 -7.111985 -8.93709 63.90176 -7.189113 -8.982529 64.18064 -7.38 -9.008707 63.8785 -7.283826 -9.043925 64.11305 -7.477861 -9.049149 61.25128 -6.176835 -9.049149 62.73444 -7.003943 -8.936894 62.808 -6.82831 -8.75351 62.85568 -6.714479 -8.534836 62.86815 -6.684701 -8.323613 62.84298 -6.744793 -8.323613 60.19918 -4.854292 -8.323613 58.63575 -2.004826 -8.232897 58.38428 -1.1837 -8.419695 58.49325 -1.172363 -8.534836 58.69841 -1.986964 -8.754496 58.47609 -1.128805 -8.740744 58.4817 -1.131455 -8.75351 58.66736 -1.995816 -8.641808 58.50881 -1.14768 -8.535202 58.51436 -1.161123 -8.841435 58.42839 -1.108824 -8.936894 58.54868 -2.02965 -8.856865 58.4174 -1.104572 -8.937941 58.34264 -1.076949 -9.049149 58.36556 -2.081856 -9.019748 58.21772 -1.031827 -9.049149 59.01082 -3.65267 -9.049149 59.98905 -5.040805 -8.936894 61.36205 -6.021942 -8.75351 61.43383 -5.921554 -8.534836 61.45261 -5.895292 -8.323613 61.41471 -5.948288 -8.936894 60.13146 -4.9144 -8.75351 60.22376 -4.832476 -8.534836 60.2479 -4.811043 -8.936894 59.17777 -3.561075 -8.75351 59.28597 -3.50171 -8.534836 59.31427 -3.486181 -8.323613 59.25714 -3.517519 8.925151 58.02581 -0.9602191 8.926633 63.82485 -7.502241 8.867029 63.87667 -7.291265 8.903249 62.73444 -7.003942 8.710826 63.91824 -7.122016 8.607801 63.93125 -7.069034 8.607614 62.85568 -6.714481 8.368913 63.93852 -7.039469 8.269714 63.93328 -7.06086 8.177722 62.84298 -6.74479 8.207088 63.92717 -7.085726 8.790996 62.808 -6.82831 8.791204 63.90175 -7.189121 8.732795 63.91441 -7.137608 8.903249 61.25129 -6.176834 8.903249 59.98905 -5.040806 8.903249 59.01083 -3.652673 8.903249 58.36556 -2.081859 8.85506 58.2539 -1.044819 8.608524 58.47612 -1.128821 8.63573 58.46357 -1.123206 8.790996 58.54868 -2.029654 8.6916 58.43106 -1.109874 8.791934 58.34277 -1.076993 8.389228 58.51435 -1.161125 8.468961 58.51245 -1.151404 8.607614 58.66736 -1.99582 8.177722 60.19918 -4.854291 8.177722 59.25715 -3.51752 8.177722 58.63576 -2.004828 8.177722 61.41472 -5.948285 8.388944 58.69841 -1.986968 8.388944 59.31427 -3.486183 8.388944 60.2479 -4.811045 8.388944 61.45262 -5.895292 8.388944 62.86815 -6.684701 8.512464 63.93757 -7.043314 8.607614 61.43383 -5.921556 8.607614 60.22376 -4.832478 8.607614 59.28597 -3.501714 8.24267 58.48235 -1.174876 8.790996 59.17777 -3.561078 8.790996 60.13146 -4.914402 8.790996 61.36205 -6.021943 8.368913 64.64758 -7.53109 8.207088 64.22012 -7.212052 8.86268 64.80255 -8.250218 8.898027 64.39615 -7.742872 8.710826 64.20045 -7.2438 8.836631 64.13467 -7.349965 8.898027 64.07203 -7.451047 8.544151 64.23965 -7.180532 8.368913 64.24518 -7.171595 8.544151 64.63953 -7.537863 8.6951 64.96466 -8.180014 8.836631 64.48709 -7.666267 8.710826 64.58261 -7.585811 8.907211 64.71979 -8.324531 8.844442 64.84291 -8.267149 8.744287 64.94369 -8.220184 8.575426 65.4748 -9.615975 8.453609 63.90657 -9.617564 8.84972 63.93348 -8.867988 8.575426 63.82178 -9.439032 8.714155 63.42022 -9.10998 8.890586 63.03817 -8.466332 8.820724 34.37954 -8.791621 8.3815 34.37954 -9.725017 8.048372 34.37954 -10.12132 6.965402 34.37954 -10.81457 7.652066 34.37954 -10.45445 6.718671 34.37954 -10.89367 6.143598 56.64064 -1.096532 6.153846 56.61839 -1.057443 6.840339 57.14601 -1.015772 7.304904 57.54598 -1.011162 7.25542 57.52603 -1.054449 8.103425 58.33054 -1.059931 5.45205 56.16409 -1.113825 6.13795 56.65668 -1.139046 5.45205 56.20597 -1.16305 5.45205 56.18312 -1.132977 5.45205 56.22526 -1.200339 6.8814 57.19621 -1.040832 8.068346 58.35113 -1.136179 -5.597949 56.1677 -1.117149 -5.597949 56.18565 -1.13586 -6.083267 56.5198 -1.150346 -8.249175 58.33064 -1.060211 -6.986141 57.14614 -1.016061 -7.613988 57.73606 -1.10407 -7.29845 57.4469 -1.097381 -8.213919 58.35124 -1.137374 -6.081079 56.53195 -1.197701 -5.597949 56.2265 -1.203481 -6.53536 56.83612 -1.124326 -6.971266 57.17108 -1.102877 -6.101085 56.47745 -1.071173 -6.549682 56.80305 -1.040176 -8.253341 58.32781 -1.053926 -8.307953 58.37744 -1.057306 -8.280047 58.41059 -1.137207 -8.709467 58.47352 -1.071583 -8.572257 58.503 -1.110568 -8.978302 58.26318 -0.9763262 -8.887757 58.3897 -1.078885 -8.41904 58.48287 -1.132359 -8.423386 58.4383 -1.05325 -8.662766 58.4366 -1.002948 -8.549539 58.45764 -1.035171 -8.83316 58.39528 -1.005458 8.702077 58.3805 -0.9935475 8.468498 58.49909 -1.101068 8.318222 58.49449 -1.127756 8.190029 58.44704 -1.137081 8.597654 58.45802 -1.057499 8.845294 58.232 -0.949974 8.881416 58.18693 -0.9761642 8.75843 58.37282 -1.065437 8.208652 58.40786 -1.057198 8.314659 58.44856 -1.049421 8.438331 58.45537 -1.027314 8.545143 58.42464 -0.9912884 0.8363772 64.16814 9.024999 0.8387156 65.14744 9.020929 0.9770508 64.16814 8.5 0.8927107 65.25609 8.91231 0.9767523 65.64314 8.524999 0.1974458 64.65393 9.514587 0.4520512 64.16814 9.409327 -0.03789997 64.61844 9.549414 -0.0729494 64.16814 9.549999 0.3215571 64.69557 9.473069 0.457571 64.76211 9.406116 0.6525145 64.90919 9.259079 -0.6035891 64.7621 9.406047 -0.4080076 64.67359 9.495105 -0.597949 64.16814 9.409327 -0.3230314 64.64889 9.519783 -0.07379722 64.61789 9.549999 -0.7520943 64.86747 9.300788 -0.982276 64.16814 9.024999 -0.9842444 65.14678 9.021576 -1.02162 65.21839 8.950026 -1.12295 64.16814 8.5 -1.122651 65.64314 8.524999 -0.982276 65.66814 7.974999 -0.982276 64.16814 7.974999 -0.597949 65.66814 7.590672 -0.597949 64.16814 7.590672 -0.0729494 65.66814 7.449999 -0.0729494 64.16814 7.449999 0.4520512 65.66814 7.590672 0.4520512 64.16814 7.590672 0.8363772 65.66814 7.974999 0.8363772 64.16814 7.974999 0.9412727 65.66814 8.22824 0.9770508 65.66814 8.5 0.9767523 65.66814 8.524999 -1.122651 65.66814 8.524999 -1.12295 65.66814 8.5 -1.113967 65.66814 8.362948 -1.087172 65.66814 8.22824 8.519477 53.60826 7.999872 8.61329 53.4197 7.999998 8.593353 54.03378 7.999944 5.190738 55.05838 7.987787 5.356223 55.09474 7.981801 5.481818 55.3078 7.969802 5.644692 55.13694 7.977376 5.962745 55.55459 7.975288 6.157998 55.14144 7.986793 6.55853 55.66696 7.999891 6.344647 55.12078 7.99135 7.024163 55.62833 7.999948 6.624475 55.06687 7.995599 7.600589 55.4152 7.999836 7.287705 54.81796 7.998445 8.085718 55.03646 8.000164 7.532987 54.67505 7.999084 8.389442 54.61367 8.000104 8.077398 54.22003 7.999705 8.242727 54.0281 7.999738 -7.050106 55.6509 7.999999 -6.704429 55.66696 7.999891 -8.214822 56.85282 7.999999 -9.065318 52.21945 7.999999 -8.773718 53.49055 7.999995 -8.724711 54.10482 7.999999 -8.499147 54.68491 7.999999 -8.115019 55.15176 7.999999 -7.588703 55.49744 7.999999 -9.065318 51.86814 7.999999 8.877052 52.2005 7.999999 8.061969 56.8464 7.999999 8.877052 51.86814 7.999999 -2.072949 57.53514 9.05 -2.072949 57.60588 9 -2.072949 55.66814 9.05 -2.072949 54.64222 9 1.927051 54.64222 9 1.927051 57.60588 9 1.927051 55.66814 9.05 1.927051 57.53514 9.05 1.927051 64.66814 9 1.927057 64.67835 6.301751 1.927051 57.60588 5.999999 1.927051 64.66814 6.227204 1.927052 64.62833 5.999999 -9.065318 50.71814 6.849999 1.867012 57.60588 9.341279 0.9270506 57.60588 10 0.9771967 57.05885 10 1.338194 57.14756 9.928678 1.26819 57.60588 9.940011 1.675874 57.24713 9.693541 1.634105 57.60588 9.707159 1.865607 57.3477 9.386111 1.923629 57.46229 9.130565 -2.067943 57.4517 9.147415 -2.015415 57.35138 9.375589 -2.012913 57.60588 9.341275 -1.938974 57.60588 9.5 -1.962796 57.31179 9.494017 -1.780012 57.60588 9.707151 -1.123071 57.05912 10 -1.072949 57.60588 10 -1.312459 57.10489 9.980918 -1.414108 57.60588 9.940006 -1.451752 57.13935 9.941286 -1.572949 57.60588 9.866024 -1.69587 57.20561 9.8078 -1.794991 57.23755 9.72146 -2.072959 57.59928 8.994226 -2.072949 57.60588 5.999999 -3.029235 55.89982 5.999999 -2.986415 55.92676 7.101749 -2.477303 56.4001 5.999999 -2.717362 56.13538 7.287653 -2.325353 56.6333 5.999999 -2.579441 56.27568 7.431003 -2.351624 56.58753 7.776352 -2.146732 57.06765 5.999999 -2.220895 56.85097 8.084344 -2.103554 57.25733 8.573949 -4.470818 55.64586 5.999999 -4.483285 55.64843 6.999999 -3.978417 55.60811 5.999999 -3.978417 55.60811 6.999999 -3.725957 55.63621 5.999999 -3.406283 55.72026 6.999999 -3.127257 55.84359 7.044283 0.1293754 64.38372 10 0.5956659 64.5531 10 0.9270506 64.66814 10 0.9149637 64.82314 9.999926 -1.06084 64.82315 9.999982 -1.072949 64.66814 10 -0.819273 64.60336 10 -0.3670387 64.40151 10 -1.12295 55.66814 10 0.9770508 55.66814 10 8.877052 50.71814 6.849999 -0.6854496 64.60726 3.149999 0.5395508 66.72902 3.149999 0.9879313 66.28063 3.149999 -1.13383 65.05564 3.149999 -1.29795 65.66814 3.149999 0.5395508 64.60726 3.149999 -0.0729494 64.44314 3.149999 0.9879313 65.05564 3.149999 1.152051 65.66814 3.149999 -0.0729494 66.89314 3.149999 -0.6854496 66.72902 3.149999 -1.13383 66.28063 3.149999 -1.263735 64.98064 4.999999 -1.330104 65.11119 4.999999 -1.447949 65.66814 3.299999 -1.349784 65.15792 5.020741 -1.380587 65.24304 5.020741 -1.263735 64.98064 3.299999 -0.7604494 64.47735 3.299999 -0.7604494 64.47735 4.999999 -0.0729494 64.29314 3.299999 -0.0729494 64.29314 4.999999 0.6145506 64.47735 3.299999 0.6145506 64.47735 4.999999 1.117836 64.98064 3.299999 1.117836 64.98064 4.999999 1.234839 65.2435 5.020741 1.203886 65.15792 5.020741 1.184207 65.11119 5 1.302051 65.66814 3.299999 1.117836 66.35564 3.299999 1.29449 65.81214 5.020741 1.302051 65.66814 5.020741 0.6145506 66.85892 3.299999 0.7350483 66.78068 5.020741 1.117703 66.35587 5.020741 -0.0729494 67.04314 3.299999 0.2126865 67.01314 5.020741 0.6145506 66.85892 5.020741 -0.7604494 66.85892 3.299999 -0.3590632 67.01304 5.020741 -0.0729494 67.04314 5.020741 -1.263735 66.35564 3.299999 -0.8813419 66.7804 5.020741 -0.7604494 66.85892 5.020741 -1.447949 65.66814 5.020741 -1.440439 65.81165 5.020741 -1.263846 66.35544 5.020741 -1.829672 64.84893 5.357112 -1.891118 64.83857 5.436473 -1.995361 65.04319 5.471707 -2.13368 65.0234 6.161619 -2.138124 65.11718 6.262163 -2.1706 65.88828 6.349894 1.836292 64.8232 5.597615 1.768099 64.8347 5.470848 1.849684 65.04387 5.471707 1.254779 64.99311 5.051605 1.578225 64.86665 5.251414 1.358673 64.9032 5.10737 1.545076 65.14277 5.151253 1.302886 64.92856 5.07903 1.917088 64.80942 5.900402 1.985456 64.99325 6.110831 1.983221 64.96714 5.999999 1.988533 64.99879 5.900599 2.082561 65.89512 5.900599 1.991456 65.24723 6.355971 1.990858 65.07749 6.225335 2.024623 65.88902 6.349894 1.933098 65.66814 6.552259 1.987052 65.3263 6.401654 1.845702 65.9439 6.642856 1.753443 66.72308 6.349894 1.667413 66.5216 6.642854 1.319402 67.0167 6.642852 1.166471 67.37473 6.349894 1.066105 67.23653 6.64285 -0.5118313 67.73114 6.349894 -0.250535 67.59836 6.642846 0.3651991 67.7313 6.349894 0.3533545 67.55905 6.642848 0.9161587 67.33515 6.64285 -1.277862 67.18653 6.642841 -0.7504025 67.48428 6.642844 -0.4762926 67.56408 6.642845 -1.912183 66.28014 6.642837 -1.687376 66.74096 6.642839 -1.899716 66.72243 6.349894 -1.312978 67.37428 6.349894 -1.991627 65.94384 6.642836 -2.018586 65.87157 6.620934 -2.13621 65.27378 6.372002 -2.078998 65.66813 6.552257 -2.068017 64.80852 5.999999 -2.12912 64.96714 5.999999 -2.134193 64.99805 5.900599 -2.001082 64.82002 5.64283 -2.022964 64.81631 5.705233 -2.029743 64.81515 5.727811 -1.584378 64.88995 5.150516 -1.465834 64.91686 5.088002 -1.504598 64.90319 5.107383 -1.40864 64.97804 5.056386 -1.690788 65.1422 5.151253 -1.073112 67.04425 5.151253 -1.546354 66.51849 5.151253 -1.764838 65.8457 5.151253 -0.4269362 67.33208 5.151253 0.2804451 67.33221 5.151253 0.9267225 67.0446 5.151253 1.400153 66.51902 5.151253 1.618877 65.84629 5.151253 -2.083353 65.87912 5.471707 -1.823736 66.67858 5.471707 -1.261401 67.30332 5.471707 -0.493578 67.64533 5.471707 0.3469753 67.64549 5.471707 1.114921 67.30374 5.471707 1.677478 66.6792 5.471707 1.937378 65.87983 5.471707 -2.22854 65.89436 5.900599 -1.950174 66.75154 5.900599 -1.347229 67.42141 5.900599 -0.5239534 67.78812 5.900599 0.3773012 67.78829 5.900599 1.200706 67.42185 5.900599 1.80389 66.75222 5.900599 1.922117 64.80852 5.999999 -2.131356 64.99325 6.11083 1.70485 66.18273 6.741574 0.7173576 66.70625 7.175736 0.7602491 66.71105 7.157929 0.8314047 66.78353 7.093803 0.8795042 66.71387 7.108028 0.9923086 66.70223 7.060302 0.6046915 66.6837 7.222174 0.2503395 67.06722 7.093803 0.2411212 66.49156 7.369272 0.1107835 66.46327 7.390681 -0.00457096 66.15213 7.468298 -0.3962822 67.0672 7.093803 -0.9773388 66.7835 7.093803 -0.5591288 66.60897 7.300061 -0.2567082 66.46327 7.390681 -0.2530871 66.34809 7.422904 -0.09753704 66.01658 7.487015 -1.337953 66.6453 6.974726 -1.629437 66.45483 6.848502 -1.07981 66.71012 7.085016 -0.9304209 66.71293 7.147798 -0.9035406 66.71086 7.158997 -1.856317 66.17465 6.738238 -1.786182 66.27262 6.777134 -1.676724 66.40558 6.828269 1.366344 66.55085 6.899144 1.530849 66.4056 6.828298 -0.0729494 65.8179 7.499479 -1.393187 66.50378 7.017951 -1.618306 66.43569 6.866382 -1.547857 66.28578 7.034149 -0.4611893 65.98226 7.552311 -0.4594488 65.81943 7.57319 -1.117106 65.98716 8.126142 -1.163048 65.97547 8.455588 -1.098653 65.9374 8.200583 -1.129819 65.89788 8.529397 -1.089398 65.88833 8.252072 -1.12295 65.83968 8.549262 -1.049227 65.83166 8.162841 -1.240858 66.05193 8.289466 -1.198533 66.01878 8.379773 -1.195247 66.01552 8.386796 -1.394173 66.08877 7.956154 -1.343172 66.0879 8.067859 -1.235476 66.11101 7.817888 -1.297078 66.07788 8.168752 -1.18715 66.07816 7.926649 -1.146361 66.03509 8.033416 -1.39541 66.08866 7.953421 -1.29274 66.13372 7.704012 -1.47393 66.06837 7.776929 -1.35173 66.14305 7.598409 -1.415337 66.13883 7.494765 -1.121182 66.46531 7.233214 -1.002427 66.40039 7.345678 -0.7406063 66.59048 7.269939 -0.6172524 66.4465 7.367143 -0.5327597 66.29055 7.448187 -0.4831562 66.13313 7.510664 -1.547667 66.15686 7.171007 -1.378513 66.33488 7.18173 -1.511583 66.10227 7.354805 -1.558668 66.00704 7.584463 -0.8154116 65.82428 7.806955 -0.7691727 65.91605 7.74441 -0.7735729 66.00693 7.700062 -0.793746 66.10784 7.6343 -0.8372259 66.21348 7.550049 -0.9087496 66.31594 7.450221 -0.9295712 65.82708 7.942183 -0.9260416 65.89254 7.918784 -0.9272413 65.95799 7.871984 -0.9396019 66.03199 7.803241 -0.9692545 66.11067 7.716079 -1.020134 66.18796 7.613867 -1.088233 66.25241 7.507875 -1.175706 66.30269 7.394927 -1.27112 66.33046 7.288304 1.359816 66.05151 7.705811 1.412762 66.00704 7.584429 1.283883 66.18559 7.343589 1.389638 66.06529 7.379712 1.396117 66.13549 7.213154 1.344064 66.0606 7.741686 1.212865 66.19405 7.436799 1.320506 66.07155 7.79485 1.146639 66.18737 7.532747 1.278702 66.08428 7.888383 1.085671 66.16777 7.631141 1.222467 66.08963 8.012876 1.033051 66.1381 7.72716 1.190137 66.08694 8.083508 1.143845 66.07543 8.1848 0.9787436 66.08917 7.844141 1.134665 66.07198 8.204629 0.9402723 66.03328 7.949216 1.082744 66.04382 8.315498 0.9164744 65.97462 8.03923 1.048659 66.01483 8.388231 0.9053307 65.91841 8.107705 1.002468 65.9495 8.487581 0.9028368 65.88298 8.139611 0.9923201 65.92571 8.510077 0.9027939 65.84965 8.158496 0.9774618 65.85401 8.546936 0.9033318 65.83166 8.162851 0.9770508 65.83968 8.54927 0.3125124 65.87444 7.569512 0.3135529 65.81943 7.573191 0.6695175 65.82428 7.80696 0.3281365 66.08058 7.52762 0.3695955 66.24286 7.469217 0.722745 66.68837 7.182314 0.564167 66.55897 7.293357 0.4471293 66.40697 7.389651 1.50403 66.36497 6.870891 0.6680994 65.8524 7.803019 0.6660194 65.90516 7.786228 0.6667481 65.96266 7.757599 0.6791763 66.05701 7.695203 0.7131615 66.15905 7.611495 0.7737084 66.2592 7.51172 0.8636694 66.34935 7.398322 0.9533701 66.40571 7.303524 1.059198 66.44471 7.20476 1.175762 66.46083 7.106784 1.302135 66.44969 7.009867 1.401481 66.15589 7.172864 -1.12295 65.76814 8.55 -1.064027 65.76814 8.203207 -0.0729494 65.76814 7.499999 -0.3295069 65.76814 7.531825 -0.781353 65.76814 7.774974 0.918128 65.76814 8.203207 0.9770508 65.76814 8.55 0.6354542 65.76814 7.774974 0.183608 65.76814 7.531825 -1.12295 65.66814 8.55 -1.117491 65.66814 8.443076 0.9770508 65.66814 8.55 0.918128 65.66814 8.203207 0.8033524 65.66814 7.971557 0.6354542 65.66814 7.774974 0.183608 65.66814 7.531825 -1.105947 65.66814 8.361806 -1.064027 65.66814 8.203207 -0.781353 65.66814 7.774974 -0.3295069 65.66814 7.531825 0.9770508 65.83968 9 0.9770508 65.8385 9.034405 0.9770508 65.79378 9.211327 0.9770155 65.66814 9.390824 0.9921751 65.72865 9.45142 1.013385 65.75986 9.482667 1.013385 65.9122 9.264456 1.367454 65.9825 9.295997 1.367454 66.04486 9.048568 1.302402 66.0763 9.050727 1.367454 65.8143 9.53719 1.302402 66.01127 9.3089 1.22293 66.02185 9.313644 1.279518 65.84086 9.563783 1.302402 65.83657 9.559495 1.22293 66.08788 9.051521 1.139338 66.07205 9.050435 1.139338 66.00737 9.307153 1.106376 65.82286 9.545749 1.139338 65.83357 9.556477 1.191772 65.84303 9.565953 1.22293 65.84477 9.567698 1.065812 65.80315 9.526014 1.065812 65.9681 9.289531 1.065812 66.0291 9.047488 1.013385 65.96799 9.043292 1.046285 66.01237 9 1.137408 66.07305 9 1.245721 66.08898 9 1.350454 66.05709 9 1.412765 66.00704 9 1.405686 65.91889 9.350179 1.396278 65.79831 9.521178 0.9850721 65.71253 9.435276 0.9850721 65.85109 9.237041 0.9850721 65.90116 9.038706 0.9898272 65.91857 9 -1.211711 65.80315 9.526014 -1.211711 65.85546 9.468821 -1.285235 65.88853 9.496387 -1.513351 65.99944 9.255043 -1.557037 65.98594 9.174109 -1.542074 65.79824 9.5211 -1.499069 66.05554 9 -1.558663 66.00704 9 -1.513351 65.8143 9.53719 -1.513351 65.86759 9.478935 -1.4483 65.83657 9.559495 -1.4483 65.8918 9.499119 -1.426832 65.84065 9.563565 -1.368828 65.90071 9.506541 -1.368828 65.84477 9.567698 -1.350411 65.84407 9.567002 -1.285235 65.83357 9.556476 -1.4483 66.02891 9.266219 -1.368828 66.03975 9.270329 -1.285235 66.02493 9.264706 -1.211711 65.98468 9.249444 -1.448301 66.07805 9 -1.394084 66.08878 9 -1.284998 66.07369 9 -1.192978 66.0132 9 -1.159285 65.75986 9.482667 -1.130971 65.71253 9.435276 -1.159285 65.80841 9.429597 -1.130971 65.75696 9.386713 -1.159285 65.92739 9.227726 -1.130971 65.86476 9.203981 -1.12295 65.80603 9.181711 -1.12295 65.7087 9.346489 -1.12295 65.66814 9.390824 -1.135879 65.91903 9 -1.12295 65.83968 9 -1.117857 65.56486 9.49866 -1.333367 65.15116 9.936824 -1.324491 65.13669 9.941727 -1.320552 65.13882 9.942732 -1.306519 65.10852 9.950795 -1.252133 65.17288 9.947437 -1.384984 65.32265 9.882284 -1.484808 65.49298 9.77239 -1.481129 65.48089 9.779907 -1.421799 65.5043 9.800281 -1.41605 65.30856 9.872859 -1.536816 65.74481 9.576387 -1.493389 65.52272 9.753285 -1.49789 65.65897 9.675285 -1.434283 65.67945 9.695047 -1.347456 65.52214 9.804565 -0.9208374 64.99315 9.874741 -0.899107 65.00798 9.81022 -1.033514 65.22551 9.765297 -1.114058 65.48027 9.638702 -1.14595 65.5047 9.695635 -1.064117 65.22871 9.827818 -1.198791 65.52236 9.748167 -1.113933 65.22133 9.885505 -1.269158 65.52881 9.786846 -1.179602 65.20203 9.927978 -1.074365 64.87498 9.998188 -1.097263 64.85667 9.999136 -1.013118 64.9233 9.978108 -0.9595471 64.9645 9.934276 -0.9964104 64.87827 9.985173 -0.9271593 64.9375 9.927608 -0.882762 64.97547 9.837026 -0.8708725 64.98564 9.75 -1.033719 65.24457 9.695349 0.7755165 65.04977 9.746066 0.7249394 64.98567 9.75 0.7368631 64.97547 9.837026 1.274942 65.46479 9.818355 1.325731 65.45043 9.798051 1.363551 65.58425 9.710434 0.9728184 65.46291 9.677483 0.9308481 65.3601 9.641619 1.097575 65.49516 9.796784 1.025494 65.48657 9.747362 1.36767 65.63323 9.678922 1.292922 65.66043 9.706166 1.286924 65.66188 9.707312 1.199676 65.6731 9.709861 1.269127 65.4668 9.819606 1.183809 65.48818 9.822385 0.8847857 65.20186 9.797533 0.9337082 65.19677 9.873706 1.000178 65.17694 9.927579 1.079353 65.14386 9.955487 1.157037 65.10321 9.952458 1.177828 65.1357 9.942107 1.323791 65.44467 9.80143 0.7812605 64.9375 9.927608 0.8505116 64.87827 9.985173 1.146472 65.0874 9.957182 -0.7774839 64.88959 9.75 -0.5529375 64.73427 9.75 -0.3214102 64.64795 9.75 -0.0729494 64.61814 9.75 0.1946964 64.65282 9.75 0.4070377 64.73427 9.75 0.6461344 64.90301 9.75 1.843071 65.53829 6.740077 1.709644 65.73833 6.95566 1.813297 65.45983 6.869783 1.707108 65.57994 7.3173 1.816504 65.3238 7.138578 1.804546 65.39877 6.983203 1.554857 65.86923 7.257875 1.574223 65.80252 7.460914 1.573276 65.96504 7.053874 1.794057 65.38527 9 1.738022 65.36376 9.341249 1.52064 65.28025 9.707107 1.634157 64.66814 9.707107 1.853612 64.66814 9.376143 1.867023 64.66814 9.341249 1.268299 64.66814 9.939972 -1.305322 64.76107 5.000011 -1.438972 64.66814 5.069401 1.159428 64.76106 5.000013 1.293075 64.66814 5.069399 1.927429 64.66811 5.999999 -1.844433 65.70727 7.018666 -1.851656 65.58258 7.321882 -1.72108 65.80113 7.459645 -1.863954 65.76052 6.917224 -1.719563 65.96601 7.052023 -1.953955 65.43562 6.913714 -1.961598 65.32612 7.128066 -1.931099 65.38188 9.137424 -1.434024 65.19094 9.888937 -1.770691 65.32026 9.574254 -1.572949 64.66814 9.866024 -2.072949 64.66814 9 -2.063461 64.66814 9.137424 -1.939956 65.38527 9 -1.938974 64.66814 9.5 -1.891627 64.66814 9.574254 -2.087906 64.80513 5.999999 -2.073332 64.66812 5.999999 -2.018719 65.13072 6.96212 -2.052874 65.0548 6.627498 -2.038607 65.03718 6.86968 -2.023187 65.11151 6.947752 -2.072693 64.72086 6.319461 -2.069019 64.79345 6.537381 -2.068683 64.85736 6.480893 -2.053747 64.94462 6.763537 -2.072949 64.66815 6.227222 -2.072849 64.68812 6.294806 -2.072705 64.69943 6.330637 0.4825487 64.58735 9.985173 -0.0729494 64.45295 9.985173 -0.6284485 64.58735 9.985173 -0.5600844 64.72036 9.837026 -0.0729494 64.6025 9.837026 0.4141855 64.72036 9.837026 0.4408922 64.6684 9.927608 -0.0729494 64.54408 9.927608 -0.586791 64.6684 9.927608 1.907688 64.94577 6.763213 1.898258 65.00743 6.808408 1.899899 64.99657 6.823271 1.898922 65.11363 6.666501 1.924927 64.79856 6.427786 -1.979202 64.66813 5.577262 -1.714773 64.66814 5.233148 -1.691563 64.79933 5.218512 -1.893425 64.81569 5.436983 -1.2424 64.47833 4.999999 -1.204817 64.32307 4.999999 -1.219859 64.33386 5.003752 -1.072958 63.93588 5 -1.175943 64.07237 5.005317 -0.8614054 63.83011 4.999991 1.062381 64.33709 4.999999 0.9268866 63.93582 5 0.7155075 63.83011 4.999991 -0.0729494 63.66814 4.999999 1.194593 64.3861 5.036453 1.875611 64.66813 5.683403 1.545663 64.79933 5.218512 1.747526 64.8157 5.436983 1.652163 64.66813 5.311369 1.753496 64.66813 5.436983 -2.07295 64.62833 5.999999 -1.50884 64.27594 5.099999 -1.50884 57.60588 5.099999 -1.794209 57.60588 5.307335 -2.010737 57.60588 5.65279 -0.8614054 63.83011 5.099999 -0.0729494 63.66814 5.099999 0.7155075 63.83011 5.099999 1.362941 64.27594 5.099999 1.864839 57.60588 5.65279 1.648312 57.60588 5.307335 1.362941 57.60588 5.099999 4.346322 55.65032 6.999999 4.324919 55.64586 5.999999 3.850784 55.60734 6.999999 2.840516 55.92676 7.101749 2.981359 55.84359 7.044283 2.883336 55.89982 5.999999 3.260384 55.72026 6.999999 3.580059 55.63621 5.999999 3.850784 55.60734 5.999999 2.571464 56.13538 7.287653 2.182426 56.62798 5.999999 2.433542 56.27568 7.431003 2.205725 56.58753 7.776352 2.331404 56.4001 5.999999 1.92706 57.59928 8.994226 1.957655 57.25733 8.573949 2.074996 56.85097 8.084344 2.000833 57.06765 5.999999 2.28177 56.36259 5.65279 2.85087 55.84675 5.65279 3.569265 55.57495 5.65279 1.940916 57.05091 5.65279 1.457534 56.91585 5.099999 3.531698 55.3617 5.307335 2.58895 55.4186 5.099999 2.737873 55.66204 5.307335 1.881345 56.06 5.099999 2.109019 56.23205 5.307335 1.732376 56.99264 5.307335 -2.734849 55.4186 5.099999 -2.027244 56.06 5.099999 -1.603433 56.91585 5.099999 -3.677597 55.3617 5.307335 -2.883772 55.66204 5.307335 -2.086814 57.05091 5.65279 -3.715164 55.57495 5.65279 -2.996769 55.84675 5.65279 -2.42767 56.36259 5.65279 -2.254918 56.23205 5.307335 -1.878276 56.99264 5.307335 1.854736 55.66814 9.413549 1.648803 55.66814 9.721751 1.3406 55.66814 9.927685 1.926336 54.04511 8.961685 1.926908 54.34103 8.982798 1.82396 54.02796 9.35721 1.636078 53.9989 9.609535 1.377184 53.96391 9.783647 1.073287 53.93024 9.862981 0.9770508 53.92125 9.866545 -2.000635 55.66814 9.413549 -1.794701 55.66814 9.721751 -1.486499 55.66814 9.927685 -1.12295 53.92125 9.866545 -2.047632 54.0409 9.144193 -2.072806 54.34103 8.982798 -2.072235 54.04511 8.961685 -1.436119 53.95346 9.817743 -1.715034 53.98929 9.667434 -2.000714 54.03303 9.290171 -1.926419 54.02097 9.433508 2.03801 56.47351 8.542172 2.060447 56.36911 8.501002 2.061026 54.64222 8.5 2.136056 56.07836 8.388176 1.950005 57.08307 8.786974 1.927056 57.5974 8.996536 2.427051 54.64222 8.133975 2.717781 54.96244 8.022141 2.61215 55.0872 8.050875 2.41036 55.40013 8.143827 2.30692 55.61058 8.215501 2.722608 54.21053 8.020983 2.431733 54.33993 8.131122 2.414111 54.13964 8.141009 2.162744 54.08825 8.353723 2.066524 54.34072 8.490101 2.07212 54.07112 8.479125 1.993789 54.05691 8.637243 -2.86368 54.96244 8.022141 -2.572949 54.64222 8.133975 -2.758049 55.0872 8.050875 -2.55626 55.40013 8.143827 -2.452819 55.61058 8.215501 -2.206924 54.64222 8.5 -2.281956 56.07836 8.388176 -2.072955 57.5974 8.996536 -2.095903 57.08307 8.786974 -2.183908 56.47351 8.542172 -2.206346 56.36911 8.501002 -2.09204 54.04853 8.798466 -2.212423 54.34072 8.490101 -2.21379 54.07035 8.486113 -2.436298 54.11363 8.227963 -2.577632 54.33993 8.131122 -2.581262 54.14424 8.128704 -2.736544 54.17913 8.058005 8.877052 51.29314 7.845928 8.877052 50.87221 7.424999 -9.065318 51.29314 7.845928 -9.065318 50.87221 7.424999 1.960931 57.14183 8.716976 2.225558 56.26644 8.211497 2.088412 56.60641 8.400228 2.450657 55.87711 8.018766 2.577373 55.70893 7.948855 2.801845 55.47029 7.875456 2.907165 55.37962 7.86101 3.093718 55.24886 7.866024 1.963488 57.20007 8.645767 2.10091 56.73394 8.245538 2.249373 56.44049 8.002355 2.494783 56.10889 7.745382 2.634126 55.96794 7.64725 2.8838 55.77159 7.534839 3.00252 55.6984 7.507244 3.215726 55.59395 7.499999 4.72654 54.89517 7.984771 4.45114 55.16143 7.866024 3.831717 55.1077 7.866024 3.845675 55.47346 7.499999 4.374409 55.51933 7.499999 4.875473 55.69425 7.499999 4.946103 55.55188 7.707106 5.038148 55.36636 7.866024 7.425961 57.5361 7.346116 7.582616 57.36623 7.707106 6.420451 55.99091 7.93819 6.219314 56.29067 7.707106 6.090556 56.48256 7.346116 7.827332 57.10085 7.93819 -2.10683 57.14183 8.716976 -2.234312 56.60641 8.400228 -2.109386 57.20007 8.645767 -2.246809 56.73394 8.245538 -2.395272 56.44049 8.002355 -2.640682 56.10889 7.745382 -2.780025 55.96794 7.64725 -3.029698 55.77159 7.534839 -3.148419 55.6984 7.507244 -3.361625 55.59395 7.499999 -2.371457 56.26644 8.211497 -2.596556 55.87711 8.018766 -2.723272 55.70893 7.948855 -2.947743 55.47029 7.875456 -3.053063 55.37962 7.86101 -3.239616 55.24886 7.866024 -3.972085 55.47429 7.499999 -5.18406 55.36637 7.866024 -5.335388 55.06189 7.987429 -4.906329 54.91033 7.983928 -5.092013 55.55189 7.707106 -4.585869 55.15907 7.866024 -3.954784 55.10867 7.866024 -4.510772 55.51731 7.499999 -5.021382 55.69425 7.499999 -6.324672 55.61726 7.986923 -6.582807 56.00197 7.93819 -5.825348 55.4294 7.966689 -7.979985 57.10707 7.93819 -7.578269 57.54203 7.346116 -7.735057 57.37226 7.707106 -6.252075 56.49307 7.346116 -6.381158 56.30139 7.707106 -8.706636 53.62926 7.999906 -8.46889 53.99798 7.999784 -8.28714 54.21587 7.99976 -7.747625 54.67669 7.999251 -7.505965 54.8211 7.998677 -6.844622 55.07788 7.996301 -6.569242 55.13432 7.992934 -6.339309 55.16093 7.987591 -5.861194 55.15849 7.97711 -0.0729494 64.16814 8.5 -0.09151363 53.87443 9.859251 -9.149499 49.15396 -7.000001 -9.126911 48.15782 -6.266905 -9.59939 47.82141 -8.000001 -9.582083 47.86475 -7.991008 -9.547583 47.974 -8.000001 -9.563637 47.90128 -7.967583 -9.437149 48.32339 -8.000001 -9.530617 47.95281 -7.90346 -9.446956 48.04197 -7.663342 -9.354118 48.61636 -8.000001 -9.16531 49.49193 -8.000001 -9.080131 50.30835 -8.000001 -9.323163 48.1177 -7.184896 -9.29874 48.12738 -7.078673 -9.171741 48.15581 -6.486344 -9.862888 47.11643 -8.000001 -9.658215 47.03491 -9.128424 -10.27941 45.58661 -9.128424 -9.226059 48.26031 -9.128424 -9.141292 48.55941 -9.128424 -8.947784 49.457 -9.128424 -8.860053 50.2982 -9.128424 -11.23519 43.92272 -8.000001 -10.86301 44.8134 -8.000001 -10.48062 45.67635 -8.000001 -11.03034 43.84166 -9.128424 -11.50658 42.45632 -9.128424 -11.71858 42.51625 -8.000001 -11.77218 41.22364 -9.128424 -11.99026 41.25493 -8.000001 -11.85264 40.11814 -9.128424 -12.07295 40.11814 -8.000001 -7.236672 50.22328 -10.76893 -8.212351 50.26831 -10.1113 -7.343226 49.19938 -10.76893 -8.307593 49.35422 -10.1113 -7.571411 48.13935 -10.76893 -8.514936 48.39182 -10.1113 -7.668989 47.795 -10.76893 -8.604815 48.07466 -10.1113 -8.148469 46.43354 -10.76893 -9.055852 46.79497 -10.1113 -8.795225 44.92468 -10.76893 -9.687246 45.32251 -10.1113 -9.519212 43.24376 -10.76893 -10.42742 43.60311 -10.1113 -9.942747 42.01427 -10.76893 -10.88263 42.27995 -10.1113 -10.16355 40.9928 -10.76893 -11.13036 41.13153 -10.1113 -10.22753 40.11814 -10.76893 -10.57295 40.11814 -10.59808 -11.20425 40.11814 -10.1113 -11.67103 40.11814 -9.500001 -8.705956 2.279628 -9.51756 -9.136272 2.43863 -9.087509 -10.16862 3.468661 -8.666199 -9.463803 2.54387 -8.7389 -10.07791 2.737588 -8.022057 -10.32397 4.996589 -9.681258 -9.712481 3.878125 -9.657875 -9.433192 3.439858 -9.648264 -8.803554 2.428658 -9.534704 -11.12109 5.455813 -8.852693 -11.49785 5.739015 -8.442862 -11.49767 6.71584 -9.010354 -11.49481 4.849116 -7.759082 -11.03195 4.073176 -7.859193 -11.49139 4.379905 -7.317353 -11.47591 3.326295 -6.034826 -11.48188 3.631497 -6.457458 -11.31588 3.190022 -6.211172 -11.11034 3.072972 -6.505656 -10.89578 3.002284 -6.862391 -11.48976 8.846767 -9.743795 -11.40043 8.278045 -9.736335 -11.49482 7.757544 -9.446337 -11.28489 7.714944 -9.72837 -10.88168 6.328999 -9.706174 11.62569 31.96933 -8.020931 11.62495 31.96981 -8.02302 12.3437 31.45371 -8.449425 12.32392 31.45159 -8.490958 13.28346 30.74966 -8.963978 13.22902 30.71751 -9.040176 14.20522 29.87039 -9.589686 13.80235 30.22552 -9.366182 14.30194 29.95683 -9.507522 13.75589 30.26601 -9.340188 13.28681 30.66873 -9.07364 11.62642 31.96884 -8.018839 12.36085 31.45136 -8.406753 13.32864 30.76198 -8.876742 14.38589 30.00068 -9.386665 14.24574 29.45652 -9.843174 16.41661 25.67194 -10.94153 14.57668 28.53466 -10.33861 14.70076 28.57296 -10.2701 14.65117 28.42481 -10.3758 12.28969 31.40822 -8.683094 12.54676 31.24711 -8.692053 13.05124 30.58424 -9.342129 13.58226 30.2162 -9.4288 14.30723 28.92577 -10.19507 14.18672 29.09728 -10.12635 14.05425 29.40121 -9.947243 13.97933 29.38702 -10.00157 13.75703 29.68939 -9.85869 15.22342 27.55994 -10.62543 15.50226 27.67535 -10.54087 15.01628 28.70582 -10.182 15.56053 27.03611 -10.74258 15.97814 26.60709 -10.80047 9.194278 33.69906 -8.000001 9.040039 33.91779 -5.400001 8.950563 34.16397 -8.000001 9.041374 33.91524 -8.000001 -10.06076 46.63562 3.999999 -9.59939 47.82141 3.999999 -10.86301 44.8134 3.999999 -11.29211 43.77723 3.999999 -11.70865 42.55116 3.999999 -11.89661 41.78994 3.999999 -12.0598 40.56817 3.999999 -12.07295 40.11814 3.999999 9.702331 32.24344 -10.12132 9.081167 31.35633 -10.81457 10.09996 32.81132 -9.038352 9.247114 33.4085 -9.038352 8.228315 31.9535 -10.81457 8.849479 32.84061 -10.12132 6.794106 33.6879 -10.89367 9.116365 33.62671 -8.791621 8.9472 33.86587 -8.791621 8.846735 34.14104 -8.791621 8.41784 34.04636 -9.725017 7.705558 33.88911 -10.45445 7.576037 32.19632 -10.89367 7.08546 32.88988 -10.89367 8.260005 32.83147 -10.45445 7.912148 33.32326 -10.45445 8.794513 33.32783 -9.725017 8.558191 33.66194 -9.725017 -12.07295 6.022943 -6.433677 -12.07295 5.65338 -6.080667 -12.07295 5.226485 -4.606201 -12.07295 5.066167 -5.390315 -12.07295 4.870179 -5.113136 -12.07295 35.30072 9.997247 -12.07295 35.38073 9.998412 -12.07295 6.32697 -2.339204 -12.07295 9.190549 -8.000001 -12.07295 8.325448 -7.769423 -12.07295 35.85398 10.05332 -12.07295 36.31687 10.19028 -12.07295 36.39333 10.22148 -12.07295 36.83393 10.45501 -12.07295 37.23624 10.76453 -12.07295 37.28231 10.80733 -12.07295 37.63443 11.20204 -12.07295 40.11814 11.70929 -12.07295 37.92065 11.65517 -12.07295 37.94832 11.70929 -12.07295 7.499185 -7.426971 -12.07295 6.725766 -6.977871 -12.07295 6.696908 -9.68028e-7 -12.07295 6.696908 6.7847 -12.07295 6.761401 6.966492 -12.07295 29.0321 9.997247 -12.07295 8.271106 9.263915 -12.07295 9.066705 9.997247 -12.07295 7.144572 7.781971 -12.07295 7.600411 8.480544 -11.54464 9.190549 -9.700225 -11.64056 9.190549 -9.551569 -11.67103 9.190549 -9.500001 -11.87639 9.190549 -9.068047 -11.9046 9.190549 -8.990848 -11.19427 9.190549 -10.12132 -11.31799 9.190549 -9.989919 -11.45301 9.190549 -9.826285 -11.45437 9.190549 -9.824507 -10.0186 9.190549 -10.84706 -10.57295 9.190549 -10.59808 -11.01639 9.190549 -10.2854 -10.63458 5.798114 -9.67976e-7 -10.76664 3.104465 -5.708994 -10.7571 3.102202 -5.715754 -10.69839 4.452849 -4.095136 -11.59771 3.601878 -5.323347 -11.17751 4.39668 -4.058031 -11.6508 3.663804 -5.306199 -11.63216 4.534764 -4.149249 -11.9559 4.834777 -4.347438 -11.55194 3.552886 -5.338474 -11.22091 3.289252 -5.462372 -11.07789 3.213866 -5.526421 -12.07292 4.857749 -5.116415 -12.03355 4.478206 -5.167979 -11.95884 4.210744 -5.204718 -11.94978 5.868907 -2.193119 -11.61063 5.523681 -2.08302 -11.13902 5.376328 -2.036026 -10.65114 5.463149 -2.063715 -11.94757 6.212098 -9.67973e-7 -11.60287 5.848861 -9.67975e-7 -11.12528 5.698277 -9.67977e-7 -10.75629 2.836995 -6.254221 -10.84437 2.84633 -6.307195 -10.63549 2.776872 -6.652747 -7.681761 1.670258 -10.09591 -7.334115 1.48879 -10.24649 -7.761856 1.719773 -9.89273 -6.60466 1.151895 -10.51247 -6.736394 1.236962 -10.41837 -6.771504 1.222812 -10.45664 -6.587303 1.144774 -10.51813 -5.980268 0.9398279 -10.70295 -6.584589 1.341521 -10.29929 -5.603518 0.9091787 -10.8149 -5.815734 0.9090395 -10.75067 -9.05428 2.292794 -8.956738 -8.696029 2.273087 -9.524471 -8.546927 2.176635 -9.624477 -8.091607 1.89985 -9.89253 -10.96542 2.898606 -6.38765 -10.78926 2.85518 -6.76522 -10.29416 2.86588 -6.457605 -10.53762 2.904237 -6.140239 -9.981804 2.591674 -7.908216 -9.839258 2.516881 -7.775649 -8.924633 2.220557 -8.804865 -7.9708 1.823014 -9.712706 -8.041459 1.87082 -9.919135 -7.846749 1.760617 -10.01774 -7.61674 1.738692 -9.731786 -7.82396 1.840955 -9.554195 -8.770716 2.234948 -8.659283 -9.675074 2.526216 -7.647414 -10.46056 2.780654 -6.54406 -10.66666 2.848668 -6.204418 -7.465436 1.841556 -9.614113 -7.672826 1.943196 -9.437087 -8.62029 2.333373 -8.54625 -9.517811 2.618056 -7.545818 -6.387752 1.758172 -10.797 -8.263828 2.825622 -10.31528 -7.543406 3.355483 -10.82364 -9.146327 4.233405 -10.37575 -9.727005 5.29552 -10.38716 -10.25582 6.558564 -10.39929 -10.63767 7.87033 -10.41008 -10.24349 7.964963 -10.66318 -8.414299 4.692775 -10.83965 -8.959624 5.679788 -10.84266 -9.456208 6.851859 -10.84586 -9.815239 8.067779 -10.84871 -10.34974 8.478689 -10.66543 -10.43197 8.997236 -10.66753 -11.92343 9.009643 -8.917634 -11.92476 8.026742 -8.651451 -11.92551 7.087268 -8.259584 -12.07292 4.859084 -5.11905 -12.04931 4.5353 -5.288457 -11.92135 4.310655 -5.952284 -12.00448 4.301963 -5.409521 -11.76035 3.694079 -5.751867 -11.7878 3.742169 -5.721562 -11.92385 4.983342 -6.731347 -11.92475 5.40553 -7.130816 -11.92555 6.206895 -7.748216 -12.04276 4.496558 -5.207877 -11.98527 4.237779 -5.271649 -12.04803 4.515637 -5.248144 -12.0006 4.268426 -5.340459 -11.76621 3.66797 -5.581713 -11.70061 3.619557 -5.444297 -11.73574 3.615409 -5.605923 -11.66357 3.56651 -5.462762 -11.43154 3.22642 -5.894672 -11.4063 3.202485 -5.846371 -11.34218 3.170783 -5.751476 -11.26299 3.162002 -5.663309 -11.21911 3.166413 -5.623328 -10.93636 3.012038 -5.791431 -11.10315 2.995921 -5.91817 -11.23757 3.058961 -6.066833 9.108339 33.95417 -5.400001 8.877052 34.9001 4.613397 8.877052 40.01064 4.613397 8.877052 52.2005 8.113331 8.877052 51.71813 8.113331 8.877052 51.16144 7.964164 8.877052 50.75391 7.556632 8.877052 50.60475 6.999934 8.877052 50.60475 5.499999 8.877052 50.48596 5.056698 8.877052 50.16144 4.732179 8.877052 49.71814 4.613397 9.256179 33.71238 6.513397 9.148275 33.88106 6.492976 8.877155 34.87954 4.613456 8.87902 34.81026 4.623098 8.883449 34.73825 4.65528 8.884471 34.72585 4.663981 8.887731 34.69113 4.699745 8.889791 34.67191 4.736056 8.890638 34.66448 4.776776 8.890638 34.66448 5.499999 8.994382 34.21652 6.180954 8.896127 34.6211 5.749835 8.903133 34.57414 5.868934 9.026069 34.13279 6.387776 8.908756 34.54096 5.936771 8.95029 34.35704 6.20231 -9.065318 51.37271 8.058469 -9.065318 51.71813 8.113409 -9.065318 52.21945 8.113409 -9.065317 50.78728 7.610853 -9.065318 51.01741 7.865256 8.870264 52.4005 8.113331 8.737594 53.09679 8.113332 8.705736 53.19116 8.113332 8.519477 53.60826 8.113333 8.481826 53.67549 8.113333 8.388811 53.82598 8.113333 8.221181 54.05507 8.113334 7.711989 54.54921 8.113336 7.477981 54.7099 8.113337 7.402051 54.75527 8.113338 6.83393 55.00764 8.11334 6.559926 55.0818 8.113342 6.157983 55.14144 8.113344 4.72654 54.89517 8.113349 4.882106 54.95922 8.113348 5.570521 55.12887 8.113346 5.853627 55.14958 8.113345 5.927051 55.15049 8.113345 -3.760547 33.94326 14 5.927051 33.94326 14 -3.760547 35.00392 14.19375 5.927051 35.00392 14.19375 -3.760547 35.92757 14.75 5.927051 35.92757 14.75 6.309205 35.96472 14.75 6.48709 35.05836 14.19375 6.677051 36.07477 14.75 7.02616 35.21963 14.19375 6.691358 34.01755 14 7.427051 34.23765 14 -10.20635 35.94315 13.63145 -10.26795 35.95375 13.60499 -10.1026 35.01366 13.04116 -10.18114 35.02892 13.00818 -10.16699 33.93797 12.79233 -10.26795 33.95919 12.74897 -9.857906 35.9146 13.77031 -9.658718 34.97259 13.21607 -9.594492 33.88087 13.02048 -8.746594 35.91441 14.14054 -8.584833 34.97024 13.57017 -8.529467 33.87478 13.37054 -7.386453 35.91452 14.46292 -7.26876 34.97151 13.88402 -7.223339 33.87808 13.68261 -5.177145 35.33979 14.31233 -5.221902 35.92425 14.72358 -5.404209 35.92332 14.71231 -5.125193 34.3153 13.98101 -5.157198 35.00786 14.15915 -5.34182 34.98848 14.13931 -5.306259 33.90897 13.94046 -5.113986 33.98571 13.9555 -5.111851 33.91318 13.95476 -5.916544 35.92043 14.67055 -5.839442 34.98289 14.09452 -5.799913 33.89878 13.89479 -4.488033 33.93462 13.98713 -4.556415 35.92691 14.7426 -4.517127 35.0003 14.18196 -4.915084 16.4484 13.9669 -4.931238 16.46542 13.96623 -5.693456 15.76287 13.9058 -5.604423 15.6742 13.9068 -4.882713 16.41438 13.96659 -4.898906 16.43138 13.96702 -5.649049 15.71845 13.90827 -7.1472 14.23741 13.6879 -7.143769 14.42178 13.69782 -7.053235 14.13829 13.67772 -8.626751 12.88848 13.31824 -8.479336 12.7304 13.28981 -7.239305 14.33843 13.67951 -8.76698 13.05444 13.30036 -10.26795 11.84762 12.74897 -10.08245 11.61688 12.78118 -9.088656 12.14823 13.06858 -9.878078 11.40661 12.72919 -11.57077 36.49507 12.51486 -11.34351 36.32841 12.81403 -11.24763 36.4337 13.11523 -10.61827 36.03272 13.42465 -10.98879 36.63041 13.60473 -10.86138 37.79519 14.11305 -11.16609 37.94832 13.85842 -11.41211 37.6201 13.55878 -11.83695 37.94832 12.87561 -11.76483 37.35205 12.89176 -10.58463 36.75889 14.01148 -11.07185 36.18845 13.09032 -10.93766 36.1343 13.20335 -11.91285 37.08335 12.14151 -11.64275 36.56363 12.40121 -10.08009 36.85036 14.31316 -10.16592 37.94832 14.50311 -11.69661 35.31235 11.45208 -11.69837 35.30072 11.44886 -11.64804 35.18985 11.53638 -11.63183 35.82849 11.68401 -11.63609 35.78315 11.65606 -11.54828 35.90618 11.92135 -11.63947 35.74956 11.63637 -11.66366 35.54505 11.53416 -11.693 35.3365 11.45902 -11.62269 36.39343 12.18253 -11.62095 36.36996 12.15537 -11.61466 36.18612 11.96408 -11.6147 36.16339 11.94287 -11.62089 35.97551 11.78584 -11.6254 35.90719 11.73634 -11.64167 36.55675 12.39155 -11.57077 35.04182 11.65883 -11.46582 35.79898 12.03501 -11.34351 34.70849 11.958 -11.22962 35.55907 12.30913 -11.07185 34.42857 12.2343 -10.95621 35.35942 12.55765 -10.93766 34.32028 12.34732 -10.82382 35.28266 12.65799 -10.61827 34.11711 12.56862 -10.51413 35.13946 12.85219 -10.48907 11.07852 12.51805 -10.6884 11.24138 12.49245 -10.85932 11.41591 12.40741 -11.22671 11.04268 12.08562 -11.03267 10.85072 12.21938 -11.67064 10.42139 11.49791 -11.46548 10.19891 11.71458 -11.97021 9.731517 10.77561 -11.78672 9.470418 11.08175 -11.94399 8.752449 10.37479 -10.79022 10.67649 12.27646 -11.16878 10.00725 11.83194 -11.45025 9.260379 11.27727 -11.59036 8.519247 10.65495 -10.27467 10.93824 12.48249 -10.52178 10.53609 12.25159 -10.82164 9.872972 11.83372 -11.02659 9.142477 11.32396 -11.10329 8.427248 10.76547 5.927051 37.91189 15.5 -3.760547 37.91189 15.5 5.927051 37.50823 15.47272 -3.760547 36.83511 15.3001 5.927051 36.65481 15.22392 -4.478436 37.91845 15.5 -5.187473 37.93822 15.5 -4.49835 36.83981 15.29931 -5.187509 37.93531 15.5 -5.197071 37.53292 15.47248 -5.210806 36.83991 15.29168 -5.215061 36.57099 15.17029 -5.221615 35.9774 14.77056 -5.258667 36.85189 15.29416 -7.047734 36.85028 15.11649 -7.4848 36.85062 15.0427 -7.514344 37.95095 15.24984 -7.071918 37.9485 15.32346 -5.25383 37.93601 15.49731 -7.656514 37.95173 15.22335 -9.055124 37.95388 14.88379 -8.992901 36.85212 14.68358 8.927051 37.91189 12.5 8.927021 37.90518 12.51162 8.927022 37.90182 12.50968 8.915884 37.78246 12.72389 8.916818 37.71776 12.6865 8.898086 37.70344 12.85987 8.900526 37.59931 12.79955 8.813531 37.49924 13.20566 8.823366 37.29357 13.08544 8.674531 37.29644 13.53565 8.697441 36.99089 13.35447 8.618019 37.23104 13.63804 8.64657 36.89358 13.43682 8.415647 37.03604 13.92821 8.465993 36.60447 13.66599 8.168836 36.84543 14.18436 8.249193 36.32381 13.86089 8.090826 36.79191 14.25035 8.181468 36.24541 13.90947 7.801988 36.61281 14.44859 7.934155 35.98458 14.04927 7.484233 36.44075 14.60023 7.66853 35.73657 14.14566 7.360732 36.37908 14.64361 7.567174 35.64838 14.16987 7.024186 36.22242 14.72306 7.296515 35.42622 14.20353 8.927032 37.89847 12.50774 8.919605 37.65303 12.64926 8.907741 37.495 12.73991 8.851371 37.08659 12.97044 8.758705 36.68099 13.19043 8.721029 36.5502 13.25869 8.586114 36.16019 13.45214 8.421575 35.77898 13.62291 8.369569 35.67194 13.6669 8.177009 35.31374 13.79906 7.965171 34.96962 13.90015 7.882838 34.84629 13.92907 7.658473 34.53295 13.98204 7.95505 37.053 14.53704 8.134153 37.91189 14.53192 8.262025 37.87296 14.38318 8.277832 37.91189 14.36382 7.427051 37.91189 15.09807 6.779576 37.91189 15.37632 6.702994 37.45414 15.36153 7.580379 37.91189 15.0033 7.402076 37.29721 15.03899 8.525127 37.91189 14 8.667407 37.51913 13.65593 8.758686 37.91189 13.49088 7.049291 36.49425 14.89393 6.517409 36.61365 15.13933 -8.809711 49.90721 13.81816 -8.800136 50.05364 13.81987 -8.985483 50.02749 13.3957 -9.05975 50.00915 13.14969 -9.154327 49.94333 12.44026 -9.154556 49.94104 12.4189 -7.994226 50.08129 14.78192 -8.209156 50.08045 14.59671 -7.85336 49.83506 14.89435 -8.501181 50.07327 14.2774 -8.671588 50.06425 14.03908 -6.484889 50.03106 15.40145 -6.831388 50.04904 15.34098 -6.506313 49.74124 15.39899 -7.112084 50.06114 15.26016 -7.755774 50.07907 14.95064 -6.566046 49.15483 15.39196 -7.904202 49.29972 14.8848 -8.852929 49.41131 13.80946 -9.194134 49.46394 12.41315 -6.732277 48.2846 15.37124 -8.031211 48.59683 14.85839 -8.946696 48.83802 13.78533 -9.270434 48.9533 12.39622 -3.760547 18.01183 14 7.427051 34.14702 14 7.403909 33.99666 14 7.336627 33.86023 14 8.177051 34.14702 13.79904 8.119197 33.77114 13.79904 8.48771 34.14702 13.56066 8.642824 33.60604 13.25 8.726089 34.14702 13.25 8.81287 34.14702 13.07402 8.834486 33.54561 12.5 8.927051 34.14702 12.5 7.95099 33.43005 13.79904 8.400735 33.11513 13.25 8.565355 32.99987 12.5 9.043382 33.75072 9.456018 9.020935 33.85371 9.419981 8.969148 33.94796 9.517933 8.961612 32.74082 10.28964 9.315605 32.46755 10.15888 9.286888 32.65795 10.02693 8.90183 33.8304 10.21906 8.784933 33.40656 10.87851 8.910356 33.61948 10.02143 8.770923 33.07824 10.54823 9.00073 33.41296 9.840327 9.058662 33.68262 9.482142 9.165399 33.2281 9.690893 9.159658 33.25236 9.678429 8.927051 34.14702 9.724807 8.937631 34.04642 9.620265 -11.29315 5.721454 6.7847 -11.27035 5.766997 7.095023 -11.483 5.784846 6.7847 -11.12888 5.698474 6.7847 -11.63374 5.870786 6.839753 -11.12528 5.698277 6.7847 -10.91343 5.710237 6.816844 -10.63458 5.798114 6.7847 -10.8836 5.744338 7.022929 -10.45697 5.909148 6.7847 -10.52625 5.869599 6.913842 -10.2538 6.123332 6.7847 -11.94757 6.212098 6.7847 -11.60287 5.848861 6.7847 -11.57934 5.834607 6.7847 -11.95881 6.232963 6.7847 -11.97017 6.278031 6.924485 -11.68295 5.94526 7.035535 -10.82292 5.754674 7.007583 -4.855338 16.39143 13.96569 -7.164243 11.89761 12.97794 -7.69533 11.07687 12.58576 -8.536818 9.801841 11.83314 -7.123669 11.96078 13.00508 -6.860802 12.38914 13.1776 -6.190743 13.6277 13.56849 -5.520639 14.97542 13.83117 -4.85964 16.43652 13.96794 -4.812689 16.46219 13.96967 -4.811347 16.46982 13.97005 -4.815573 16.46877 13.96996 -4.807898 16.46975 13.97008 -4.803877 16.46732 13.97001 -4.805683 16.46891 13.97007 -4.82394 16.46475 13.96969 -4.832162 16.45937 13.96934 -4.843565 16.45057 13.9688 -4.803027 16.44288 13.96882 -4.802172 16.44767 13.96907 -4.801436 16.45963 13.96966 -4.80245 16.46473 13.9699 -4.959095 16.08672 13.94647 -4.82803 16.36851 13.96477 -4.824744 16.37672 13.96523 -9.366253 8.563167 10.94038 -9.563576 8.265878 10.69553 -10.15546 7.371791 9.844758 -11.12248 7.554723 9.959862 -10.63247 6.653056 8.952143 -11.15573 6.801038 9.075651 -10.68763 6.571103 8.830226 -11.19665 6.280654 8.270177 -11.01532 6.100127 7.987588 -11.25616 5.841161 7.312314 -6.460944 11.71448 12.49487 -6.29649 11.77495 12.08335 -6.062375 12.15746 12.43069 -6.75637 11.78084 12.82407 -6.249942 12.14753 12.77558 -6.530508 12.22894 13.03805 -5.570674 13.37247 13.21451 -5.753483 13.4301 13.38796 -5.159235 14.79535 13.72306 -5.275906 14.85071 13.77778 -4.984285 15.38829 13.84272 -4.863502 16.03808 13.93855 -4.815999 16.01423 13.93028 -4.761028 16.34064 13.96134 -4.783346 16.34989 13.96307 -4.760707 16.35067 13.96213 -4.782039 16.35932 13.96369 -4.769368 16.43608 13.96823 -4.780586 16.43834 13.96856 -4.771696 16.44296 13.96866 -4.781853 16.44452 13.9689 -4.780778 16.4614 13.96973 -4.787664 16.4608 13.96976 -4.787776 16.47051 13.97019 -4.792667 16.46858 13.97012 -4.793488 16.47601 13.97044 -4.796951 16.47311 13.97031 -4.799177 16.48026 13.97059 -4.801346 16.47648 13.97043 -4.805149 16.48368 13.97068 -4.806066 16.47904 13.97051 -4.813329 16.48703 13.97071 -4.812668 16.48129 13.97053 -4.822334 16.48933 13.97065 -4.820081 16.48248 13.97047 -4.838397 16.49077 13.97036 -4.83358 16.48209 13.97023 -4.85289 16.48989 13.96995 -4.845983 16.47971 13.9699 -4.871772 16.48652 13.96925 -4.862375 16.47453 13.96933 -4.896925 16.47916 13.9681 -4.884508 16.46494 13.9684 -5.964882 13.51711 13.50864 -5.397169 14.91113 13.81406 -4.911246 16.06227 13.94395 -4.805685 16.35918 13.96421 -4.803389 16.368 13.96473 -4.791806 16.4406 13.96876 -4.792013 16.4461 13.96904 -4.79455 16.46022 13.96973 -4.797559 16.46665 13.97002 -4.800414 16.47022 13.97017 -4.803514 16.47269 13.97026 -4.806982 16.47439 13.97031 -4.812008 16.47555 13.97031 -4.817828 16.47562 13.97025 -4.828761 16.47342 13.97001 -4.839074 16.46954 13.9697 -4.852972 16.46254 13.96918 -4.872078 16.45073 13.96835 -10.26795 29.0321 12.74897 -11.83695 40.11814 12.87561 -11.16609 40.11814 13.85842 -10.16592 40.11814 14.50311 -11.91434 37.06767 12.10114 -11.92713 36.89646 11.758 -11.93865 36.67171 11.45147 -11.93992 36.64153 11.41781 -11.94927 36.37249 11.17184 -11.96354 35.35739 10.80088 -11.96179 35.69197 10.84601 -11.95747 36.0165 10.95795 -11.95649 36.06966 10.98332 -11.96358 35.30072 10.79992 -11.21817 29.0321 12.09439 -11.85105 29.0321 11.12957 -11.67529 6.014182 7.247293 -11.96803 6.343997 7.12335 -11.64276 6.429131 8.186272 -11.62001 6.928958 8.980418 -11.60128 7.662124 9.855526 -11.9589 6.7408 8.010146 -11.95246 7.21869 8.764723 -11.94712 7.922784 9.602301 5.927051 48.96964 15.5 4.869008 48.62652 15.5 2.409014 48.09886 15.5 -0.1008787 47.92443 15.5 -2.61021 48.10676 15.5 -5.06853 48.64215 15.5 -5.187473 48.67751 15.5 -6.416888 50.0233 15.4091 -6.185444 49.93264 15.433 -5.234992 48.8497 15.4981 -5.555928 49.2826 15.48194 -6.04254 49.813 15.44615 -7.289984 46.74294 15.28882 -6.793759 48.07399 15.36313 -9.539724 42.45703 14.7306 -9.81953 41.79969 14.6332 -10.07184 40.96316 14.53951 -10.1648 40.20779 14.50355 -7.642617 45.99179 15.226 -7.990668 45.32215 15.15544 -8.715025 44.02108 14.98003 -8.59978 51.53233 13.4976 -8.810476 51.35449 13.18009 -8.840827 50.85169 13.40073 -9.114801 50.73189 12.08228 -9.12881 50.39897 12.25619 -9.016306 51.08253 12.69823 -8.927304 51.22085 12.94282 -8.422806 51.64694 13.70355 -8.071949 51.19891 14.34206 -7.903177 51.88413 14.13461 -6.958678 51.37899 14.91307 -7.005013 52.09828 14.53745 -7.658167 51.96212 14.27872 -5.529878 52.11647 14.61606 -5.619978 52.1259 14.62968 -5.698667 51.35997 15.01238 -6.005897 52.15065 14.66068 -6.71958 52.13088 14.60346 -5.913835 50.38838 15.33781 -7.122679 50.43215 15.17539 -8.172391 50.36157 14.55674 -8.889232 50.1883 13.58426 8.929651 34.60025 9.155848 8.927051 34.75278 9.091912 8.927051 34.74413 9.101888 8.927072 34.73935 9.09774 8.927051 34.65383 9.204038 8.927051 40.05409 12.5 8.927051 48.96964 12.5 8.69869 48.96964 13.64805 7.427051 48.96964 15.09807 7.075101 48.96964 15.27164 8.525127 48.96964 14 8.048372 48.96964 14.62132 8.689176 49.37939 13.65233 6.161897 55.19129 9.5 4.706192 54.94084 9.5 4.706659 54.93896 9.651251 7.56067 54.71669 9.5 6.16228 55.18908 9.658157 8.563417 53.63212 9.5 7.560883 54.71456 9.645057 8.927051 52.2005 9.5 8.56348 53.63043 9.615128 4.730861 54.84118 10.59672 6.182044 55.07434 10.64415 4.78693 54.61195 11.47231 6.227504 54.80825 11.54694 4.879265 54.22599 12.35747 6.301408 54.36849 12.44157 4.946328 53.93888 12.83817 6.354373 54.04739 12.9172 5.08532 53.32487 13.6156 6.462378 53.37548 13.66731 5.105561 53.23326 13.71141 6.477916 53.27677 13.75787 5.270982 52.4626 14.37491 6.603227 52.46006 14.3711 5.449706 51.58369 14.90005 6.735492 51.55378 14.83372 5.643887 50.5698 15.28292 6.875882 50.53459 15.1468 5.828595 49.54336 15.47258 7.006528 49.52548 15.27406 7.571958 54.60369 10.54842 7.597327 54.34753 11.37177 7.638284 53.92714 12.18111 7.667428 53.62233 12.60764 7.726329 52.98985 13.27332 7.734746 52.89749 13.35299 7.802123 52.13831 13.88734 7.872298 51.30505 14.28205 7.945777 50.37763 14.53994 8.013273 49.46778 14.63345 8.566627 53.54228 10.33253 8.573823 53.33829 10.98806 8.585407 53.00247 11.6354 8.593614 52.7582 11.9783 8.610132 52.24944 12.51688 8.612483 52.17494 12.58169 8.631235 51.56078 13.01905 8.650629 50.88332 13.34669 8.670787 50.12574 13.56603 8.927051 52.19945 9.575625 8.927051 52.14518 10.04836 8.927051 52.01818 10.48615 8.927051 51.80506 10.92873 8.927051 51.64708 11.16909 8.927051 51.31069 11.5578 8.927051 51.26065 11.60571 8.927051 50.84137 11.93745 8.927051 50.36632 12.20003 8.927051 49.82196 12.39146 8.927051 49.27436 12.48629 -8.989071 48.66959 13.77578 -8.082441 48.40983 14.84792 -9.627299 47.7416 12.32937 -9.308258 48.79441 12.38961 -8.502869 47.20241 14.75499 -10.06081 46.6355 12.23563 -9.876015 46.27857 13.54627 -9.343199 47.56147 13.69099 -10.11688 46.50389 12.2226 -10.67555 45.23904 12.0835 -10.46718 44.99316 13.3632 -11.4003 43.49021 11.88697 -11.20153 43.26667 13.10848 -11.67982 42.65026 11.8107 -11.47232 42.46128 13.0093 -11.89656 41.79019 11.75341 -11.73303 41.3465 12.9133 -11.95835 41.45985 11.73762 -12.07153 40.26535 11.70963 -11.83569 40.25207 12.87606 -9.114816 45.8555 14.59625 -9.76861 44.55918 14.39528 -10.54275 42.90084 14.11534 -10.81535 42.16089 14.00608 -11.06861 41.17158 13.9001 -11.16492 40.23182 13.85893 -6.782782 52.51112 14.35086 -8.818209 51.60404 13.00485 -9.115318 50.87659 11.92541 -9.115318 50.71814 12.02575 -5.447623 52.51109 14.35082 -7.985734 52.1874 13.87049 -5.301436 53.18797 13.77248 -6.67201 53.22862 13.81717 -5.155922 53.83227 13.01504 -6.559364 53.93012 13.09202 -5.047199 54.2955 12.25359 -6.4735 54.44806 12.3396 -4.958302 54.66326 11.36373 -6.40212 54.86885 11.43724 -4.904284 54.88202 10.44564 -6.358199 55.1238 10.48792 -4.885838 54.95594 9.5 -6.343101 55.21079 9.5 -7.926167 52.85449 13.40577 -7.864862 53.51363 12.76436 -7.817616 54.00529 12.08997 -7.777988 54.40826 11.27256 -7.753441 54.65406 10.40577 -7.744974 54.73822 9.5 -8.80163 52.14384 12.62432 -8.78446 52.67466 12.10433 -8.771151 53.0688 11.56199 -8.759936 53.39057 10.9087 -8.752965 53.58626 10.21903 -8.750556 53.65316 9.5 -9.115318 51.24528 11.63624 -9.115318 51.59828 11.25752 -9.115318 51.85346 10.87679 -9.115318 52.05692 10.43186 -9.115318 52.17835 9.972819 -9.115318 52.21945 9.5 9.266916 32.33274 10.2843 8.903551 32.62323 10.41197 8.711278 32.96969 10.68713 8.734838 33.29151 11.04574 9.084983 31.99853 10.55847 8.715538 32.34262 10.67272 8.525339 32.70914 10.98488 8.565355 32.99987 11.41129 9.017414 34.08737 9.149069 9.41991 32.53948 10.03764 9.628505 32.71912 9.704668 9.712404 32.81832 9.500121 9.254585 33.368 9.409152 9.266304 33.38527 9.365226 9.032119 34.13568 8.923326 9.328308 33.51766 8.990759 9.336282 33.58342 8.772454 9.16085 33.84758 8.844621 9.759693 32.89179 9.337557 9.770622 32.91249 9.289888 9.815876 33.07294 8.886816 9.807584 33.15402 8.655146 9.153028 33.97661 7.999999 8.927051 34.9001 7.999999 8.927051 34.86316 8.54928 9.78684 33.23478 8.329568 9.779895 33.2618 7.999999 9.154987 33.94424 8.425293 10.79325 28.88992 11 5.009643 25.5078 11 4.940347 25.73425 11 8.18642 30.71525 11 4.859673 25.96416 11 4.861811 25.95821 11 -2.531819 17.15146 12.5 -2.625351 17.21695 13.07402 -2.696438 17.26673 13.25 -2.891705 17.40346 13.56066 -3.146183 17.58165 13.79904 -3.290334 17.68258 13.88582 9.046785 31.94397 10.59808 8.653207 31.38189 10.88751 8.264476 31.69844 11.01646 7.776843 31.00203 11.13397 7.60719 31.12082 11.29289 8.021596 31.98972 11.36876 7.477012 31.21198 11.5 7.429622 31.24516 11.61732 7.989648 32.17767 11.85001 7.367267 31.28882 12 4.040522 26.53774 12 4.121318 26.48116 11.56694 4.675198 26.09333 11.02569 4.546198 26.18366 11.07612 4.347767 26.3226 11.21931 3.576692 25.64174 10.5 3.935185 25.73337 10.5 3.966592 25.77823 10.77527 4.189878 26.09712 11.16456 4.761205 25.44182 10.70063 4.559811 25.92854 10.98567 4.923946 25.67424 10.98435 4.82639 25.53491 10.87071 4.086466 25.73163 10.5 4.373675 25.66271 10.5 4.396627 25.69549 10.70117 4.461988 25.78884 10.87172 4.056027 25.90595 11.00863 3.887125 26.1467 11.48573 3.688587 25.86316 11.25444 3.555928 25.6737 10.9083 3.509345 25.60717 10.5 3.711275 26.06752 11.88582 3.432153 25.6689 11.56066 3.245649 25.40254 11.07402 3.180158 25.30901 10.5 -7.334177 10.91971 12.40272 -7.03928 10.87857 12.08653 -8.180955 9.671844 11.65167 -9.012404 8.456245 10.76434 -9.209973 8.166074 10.52195 -9.800689 7.297326 9.683868 -10.27255 6.604278 8.812834 -10.32662 6.525426 8.694513 -10.64397 6.070682 7.879915 -7.884964 9.660211 11.3538 -8.71306 8.469863 10.48534 -8.909251 8.187488 10.2495 -9.492983 7.347001 9.438635 -9.953522 6.684091 8.605019 -10.00571 6.60912 8.492422 -10.30743 6.17781 7.719847 -6.866266 10.96123 11.69683 -7.701078 9.768993 10.99211 -8.518401 8.601736 10.15015 -8.711066 8.326581 9.923151 -9.280737 7.513007 9.14763 -9.723681 6.880418 8.360144 -9.773294 6.809562 8.254434 -10.05629 6.4054 7.531453 -5.419498 13.26091 12.90398 -4.289021 14.86007 13.02628 -4.59442 15.04198 13.52531 -4.168515 14.81402 12.42733 -5.276692 13.23138 12.28714 4.706192 54.94084 8.199952 3.821063 54.5888 8.199955 2.899187 54.30673 8.19996 2.631522 54.24006 8.246699 2.392646 54.18615 8.383502 2.21593 54.14962 8.591314 2.120078 54.13099 8.841939 2.106015 54.12833 8.949295 3.197895 54.3891 9.5 2.016655 54.11181 9.336589 1.933735 54.09712 9.5 -2.079666 54.09713 9.5 -3.379286 54.39945 9.5 -1.809576 54.0454 9.810502 -3.436845 54.20328 11.05291 -1.06457 53.93952 10.06577 -1.459256 53.98524 10.00316 -1.781477 53.84275 11.05291 -0.4869738 53.90549 10.06019 1.598342 53.83743 11.05291 1.678501 54.04824 9.798355 1.343018 53.98969 9.992557 3.254837 54.19275 11.05291 3.421782 53.61707 12.5 3.687353 52.70127 13.74264 4.033451 51.50781 14.69615 4.436491 50.11798 15.29555 -4.631321 50.13226 15.29555 -4.223908 51.52081 14.69615 -3.874054 52.71318 13.74264 -3.605602 53.62812 12.5 1.682185 53.24392 12.5 1.81556 52.29978 13.74264 1.98938 51.06936 14.69615 2.191795 49.6365 15.29555 0.9186545 53.93952 10.06576 -0.09175682 53.71998 11.05291 -0.0927 53.12058 12.5 -0.09420013 52.16707 13.74264 -0.09615707 50.92443 14.69615 -0.09843444 49.47734 15.29555 -1.867188 53.24951 12.5 -2.003534 52.3058 13.74264 -2.181227 51.07592 14.69615 -2.388152 49.64372 15.29555 -2.226601 54.12358 9.131632 -2.25194 54.12833 8.949315 -2.653831 54.21152 8.303662 -2.901602 54.27016 8.213139 -2.311724 54.13978 8.691708 -2.450745 54.16766 8.468898 -4.885838 54.95594 8.199995 -3.984517 54.59498 8.19999 -3.045118 54.30674 8.199987 5.927051 55.2005 8.199947 6.161897 55.19129 8.199946 7.427051 54.79857 8.199941 7.56067 54.71669 8.19994 8.525127 53.7005 8.199936 8.927051 52.2005 8.199934 8.927051 34.77954 5.499999 8.927051 34.77954 4.726794 8.927051 34.9001 5.499999 8.927051 34.87954 4.699999 8.927051 40.01064 4.699999 8.927051 51.11814 8.039165 8.927051 50.6789 7.599934 8.927051 50.51814 6.999934 8.927051 51.71813 8.199934 8.927051 49.71814 4.699999 8.927051 50.11814 4.807179 8.927051 50.41096 5.099999 8.927051 50.51814 5.499999 -7.615317 54.81752 8.200006 -7.744974 54.73822 8.200007 -8.713394 53.71945 8.200011 -9.115318 52.21945 8.200013 -6.343101 55.21079 8.2 -6.115317 55.21945 8.199999 -9.115318 50.96292 7.932556 -9.115318 51.34584 8.140798 -9.115318 51.71813 8.200013 8.9302 34.77954 5.579297 8.927064 34.89268 5.504884 8.930328 34.78098 5.581275 8.930395 34.78241 5.583257 8.930402 34.78385 5.585241 8.930349 34.78528 5.587227 8.970916 34.48353 6.196848 8.937129 34.69958 5.803058 8.932798 34.74859 5.667422 8.931478 34.76712 5.618225 8.930822 34.77733 5.597109 9.779895 33.2618 6.599999 9.296934 33.74135 6.599999 9.148115 33.98611 6.558994 9.035007 34.2519 6.421504 11.65362 30.11865 10.59808 12.03041 30.65675 10.08512 11.46518 29.84952 10.76182 12.28345 31.01813 9.5 9.77639 33.25679 6.565569 9.757101 33.22925 6.520193 9.766298 33.24238 6.535349 9.773881 33.25321 6.555422 9.273059 33.72438 6.529288 9.290729 33.73694 6.56173 8.946975 34.43314 6.132528 8.924198 34.64445 5.781312 8.958208 34.43038 6.155443 9.020309 34.20644 6.362809 9.130044 33.95513 6.490003 8.930953 34.77381 5.594892 8.93091 34.77027 5.592679 8.912195 34.62887 5.775507 8.925979 34.70726 5.652202 8.929534 34.71728 5.655836 8.92951 34.74264 5.607477 8.930673 34.74871 5.610121 8.930301 34.76322 5.588281 8.930692 34.76675 5.590474 8.931392 34.75482 5.612802 8.931873 34.72759 5.659616 8.932559 34.66193 5.788032 8.931661 34.76097 5.615508 8.932964 34.73807 5.663495 8.936931 34.68056 5.795384 8.97046 34.45659 6.174811 9.034667 34.22995 6.389799 9.145902 33.9732 6.521553 8.91773 34.71919 5.499999 8.903438 34.87954 4.635461 8.903438 34.74727 4.670903 8.920961 34.87954 4.665638 8.915346 34.75606 4.686136 8.892562 34.6786 4.728337 8.910243 34.69929 4.757294 8.921022 40.01064 4.665797 8.903656 40.01064 4.63572 8.920949 52.2005 8.165535 8.51868 53.69676 8.162071 4.715824 54.91922 8.135353 5.926999 55.17503 8.133273 7.414205 54.77632 8.13302 6.697381 55.07541 8.135344 8.502878 53.68765 8.133015 8.031639 54.30508 8.135338 8.903387 52.2005 8.135335 8.801969 52.97083 8.135335 4.708674 54.93527 8.165554 5.307891 55.11172 8.135351 5.92681 55.19322 8.162515 7.423331 54.79212 8.16208 8.913654 52.2005 8.149934 -9.109215 52.21945 8.165614 -9.109804 51.71813 8.167265 -9.091652 52.21945 8.135414 -9.091922 51.71813 8.135734 -9.090503 51.71813 8.134079 -7.611591 54.81108 8.162141 -6.11508 55.21215 8.162511 -8.835457 53.36109 8.113409 -8.932591 53.09436 8.113409 -8.990236 52.98978 8.135414 -9.059978 52.39685 8.113409 -7.602471 54.79528 8.133086 -7.590318 54.77423 8.113404 -7.717813 54.69625 8.113404 -7.768692 54.66258 8.113404 -8.30423 54.19712 8.113407 -8.219904 54.32404 8.13541 -8.484177 53.97758 8.113407 -5.880187 55.16007 8.113396 -6.115318 55.16944 8.113397 -6.115268 55.19397 8.133317 -6.339305 55.16093 8.113398 -6.589141 55.13115 8.1134 -6.866802 55.07212 8.113401 -6.88565 55.09436 8.135404 -7.52622 54.81017 8.113404 -5.091544 54.98611 8.113393 -5.781052 55.15045 8.113396 -5.491577 55.12969 8.135397 -4.888339 54.95037 8.165596 -4.895536 54.93435 8.135396 -4.906329 54.91033 8.113392 -8.706961 53.71573 8.162191 -8.691143 53.70661 8.13309 -8.670093 53.69445 8.113408 -3.98655 54.58923 8.165592 -3.9924 54.57267 8.135392 -4.001171 54.54784 8.113389 -3.057774 54.25837 8.113384 -3.052791 54.27742 8.128267 -3.047115 54.29911 8.161055 -2.896597 54.23936 8.144112 -2.812061 54.19691 8.148467 -2.627795 54.17868 8.244437 -2.548532 54.13716 8.275838 -2.408014 54.13355 8.424622 -2.341337 54.09461 8.481825 -2.257738 54.10501 8.666295 -2.211802 54.06998 8.745637 -2.192148 54.09207 8.945077 -2.176417 54.06351 8.943735 -2.896958 54.26133 8.175847 -2.638255 54.20103 8.271884 -2.426538 54.15612 8.445249 -2.281713 54.12769 8.678168 -2.218766 54.11562 8.947053 -2.152786 54.05925 9.112833 -2.168666 54.08839 9.117521 -2.194515 54.1113 9.124112 -2.015873 54.03556 9.454252 -2.029737 54.0645 9.465852 -2.051975 54.08615 9.481819 -1.067471 53.91642 9.991693 -1.266881 53.935 9.975066 -1.418054 53.96727 9.957367 -1.603422 53.97414 9.852583 -1.772638 54.01688 9.75641 -1.78876 54.0371 9.78191 -1.448121 53.97967 9.967261 -1.065461 53.93519 10.02561 -0.09151363 53.87443 9.9843 -0.4881897 53.88172 9.985596 -0.4873495 53.9011 10.02014 0.9194937 53.9356 10.0269 0.9215546 53.91641 9.991683 1.125194 53.93805 9.977323 1.086968 53.93159 9.980677 1.347965 53.97817 9.930362 1.450956 53.97328 9.856229 1.626456 54.0254 9.771233 1.883828 54.06452 9.465869 1.869941 54.03555 9.454251 1.331022 53.98393 9.957097 1.6573 54.03982 9.770198 1.906059 54.08615 9.481829 1.947179 54.04872 9.302861 1.962364 54.07798 9.311377 1.986591 54.10018 9.323165 2.030491 54.0635 8.943716 2.047214 54.0933 8.945137 2.073521 54.11602 8.947082 2.062409 54.09603 8.828955 2.075124 54.07169 8.716486 2.165993 54.11508 8.557497 2.216511 54.09877 8.453615 2.357092 54.15255 8.331692 2.440559 54.14537 8.250352 2.615867 54.20816 8.181698 2.717922 54.20938 8.135048 2.905175 54.28384 8.135361 2.91184 54.25836 8.113358 2.088168 54.11874 8.835026 2.188005 54.13772 8.573282 2.372146 54.17504 8.355778 2.621331 54.23033 8.211709 2.900731 54.30083 8.165561 3.837642 54.54163 8.113353 3.82891 54.56647 8.135356 3.823087 54.58304 8.165557 8.903656 51.71813 8.135656 8.913654 51.71813 8.149934 8.921022 51.71813 8.165733 8.921022 51.13524 8.009545 8.903656 51.15027 7.983497 8.921022 50.70853 7.582832 8.903656 50.73458 7.567794 8.921022 50.55234 6.999934 8.903656 50.58242 6.999934 8.921022 50.55234 5.499999 8.903656 50.58242 5.499999 8.903656 49.71814 4.63572 8.903656 50.15028 4.751512 8.921022 49.71814 4.665797 8.921022 50.13524 4.777559 8.903656 50.46662 5.06786 8.921022 50.44058 5.082898 -9.090503 51.3663 8.078119 -9.109804 51.356 8.109668 -9.109804 50.98352 7.907107 -9.089545 50.77131 7.622144 -9.090503 51.0044 7.881318 -9.10811 50.74671 7.638723 -9.112986 50.62192 7.385639 -9.094363 50.64961 7.375661 -9.097066 50.58568 7.000012 -9.115722 50.55638 7.000012 -9.108104 50.57116 7.000012 12.87394 30.90991 8.253486 13.7136 30.2631 9.077331 11.72612 31.82592 6.682518 -0.8280048 22.63768 -9.700002 -4.572949 17.28935 -9.700002 -0.8280048 22.63768 -9.600002 -4.572949 17.28935 -9.600002 -3.572949 22.66814 -9.700002 -1.072949 22.66814 -9.700002 -3.572949 22.66814 -9.600002 -1.072949 22.66814 -9.600002 -3.955633 22.59202 -9.700002 -3.955633 22.59202 -9.600002 -4.280056 22.37525 -9.700002 -4.280056 22.37525 -9.600002 -4.496829 22.05082 -9.700002 -4.496829 22.05082 -9.600002 -4.572949 21.66814 -9.700002 -4.572949 21.66814 -9.600002 -1.072949 24.66814 -9.600002 -3.572949 24.66814 -9.600002 -4.572949 25.66814 -9.600002 -4.280056 34.32525 -9.600002 -3.955633 34.54202 -9.600002 -3.572949 34.61814 -9.600002 -0.0729494 25.66814 -9.600002 -0.1490697 25.28545 -9.600002 -0.3658428 24.96103 -9.600002 -3.955633 24.74426 -9.600002 -4.280056 24.96103 -9.600002 -4.496829 25.28545 -9.600002 -1.072949 34.61814 -9.600002 -0.6902666 34.54202 -9.600002 -0.3658428 34.32525 -9.600002 -4.572949 33.61814 -9.600002 -0.0729494 33.61814 -9.600002 -0.6902666 24.74426 -9.600002 -4.496829 34.00082 -9.600002 -0.1490697 34.00082 -9.600002 -0.0729494 33.61814 -9.700002 -4.572949 33.61814 -9.700002 -0.0729494 25.66814 -9.700002 -4.572949 25.66814 -9.700002 -4.280056 24.96103 -9.700002 -3.955633 24.74426 -9.700002 -3.572949 24.66814 -9.700002 -0.3658428 34.32525 -9.700002 -0.6902666 34.54202 -9.700002 -0.1490697 34.00082 -9.700002 -1.072949 34.61814 -9.700002 -3.572949 34.61814 -9.700002 -4.496829 25.28545 -9.700002 -1.072949 24.66814 -9.700002 -3.955633 34.54202 -9.700002 -4.280056 34.32525 -9.700002 -4.496829 34.00082 -9.700002 -0.6902666 24.74426 -9.700002 -0.3658428 24.96103 -9.700002 -0.1490697 25.28545 -9.700002 -6.37295 41.36096 -9.600002 -6.080129 41.06814 -9.600002 -6.772949 40.66814 -9.600002 -5.972949 40.66814 -9.600002 -6.080129 40.26814 -9.600002 -7.46577 41.06814 -9.600002 -7.17295 41.36096 -9.600002 -6.772949 41.46814 -9.600002 -7.17295 39.97532 -9.600002 -7.46577 40.26814 -9.600002 -7.572949 40.66814 -9.600002 -6.37295 39.97532 -9.600002 -6.772949 39.86814 -9.600002 -6.772949 40.66814 -10.13069 -6.080129 41.06814 -9.650002 -6.37295 41.36096 -9.650002 -5.972949 40.66814 -9.650002 -7.17295 41.36096 -9.650002 -7.46577 41.06814 -9.650002 -6.772949 41.46814 -9.650002 -7.46577 40.26814 -9.650002 -7.17295 39.97532 -9.650002 -7.572949 40.66814 -9.650002 -6.37295 39.97532 -9.650002 -6.080129 40.26814 -9.650002 -6.772949 39.86814 -9.650002 7.401648 38.36814 -6.000001 7.427051 38.16814 -6.000001 6.177051 38.36814 -6.000001 7.319871 37.76814 -6.000001 7.027051 37.47532 -6.000001 5.927051 37.78084 -6.000001 5.927051 38.34716 -6.000001 5.93423 37.76814 -6.000001 6.227052 37.47532 -6.000001 6.627049 37.36814 -6.000001 6.707322 37.74131 -10.21973 6.927051 37.42652 -10 7.027051 37.47532 -9.900001 7.319871 37.76814 -9.607181 7.399791 37.96108 -9.527261 7.427051 38.16814 -9.500001 6.540759 38.29943 -10.38629 7.319871 38.56814 -9.607181 6.707322 38.59497 -10.21973 7.027051 38.86096 -9.900001 6.927051 38.90976 -10 6.520646 38.23109 -10.4064 6.514182 38.16814 -10.41287 6.520646 38.10519 -10.4064 6.540759 38.03685 -10.38629 7.399791 38.37519 -9.527261 6.627049 37.36814 -10 6.627049 38.96814 -10 6.557694 38.96512 -10 6.227052 38.86096 -10 6.187648 38.83666 -10 5.93423 38.56814 -10 5.922948 38.54793 -10 5.82705 38.16814 -10 5.922948 37.78835 -10 5.93423 37.76814 -10 6.187648 37.49961 -10 6.227052 37.47532 -10 6.557694 37.37115 -10 5.927051 37.78084 -9.600002 7.401648 38.36814 -6.050001 7.319871 38.56814 -6.050001 7.027051 38.86096 -6.050001 6.627049 38.96814 -6.050001 5.93423 38.56814 -6.050001 5.927051 38.55544 -6.050001 5.927051 38.55544 -9.600002 5.82705 38.16814 -9.600002 6.227052 38.86096 -6.050001 5.927051 38.34716 -6.050001 6.177051 38.36814 -6.050001 -9.07295 15.34557 -5.400001 -9.07295 15.34557 -6.000001 -10.57295 15.34557 -5.400001 -10.57295 15.34557 -6.000001 -9.238061 43.8613 -6.000001 -9.07295 43.8613 -6.000001 -9.238061 43.8613 -5.400001 -9.07295 43.8613 -5.400001 -9.786525 43.50662 -5.400001 -9.786205 43.50658 -6.000001 -9.654285 43.69346 -5.400001 -9.654285 43.69346 -6.000001 -9.462457 43.81776 -5.400001 -9.462457 43.81776 -6.000001 -10.00935 42.92792 -5.400001 -10.57295 34.26814 -5.400001 -10.57295 34.26814 -6.000001 -10.57295 36.74966 -6.000001 -10.57295 36.74966 -5.400001 -10.57295 38.99037 -6.000001 -10.57295 38.99037 -5.400001 -10.48421 41.1803 -6.000001 -10.48421 41.1803 -5.400001 -10.42197 41.51394 -6.000001 -10.00935 42.92792 -6.000001 + + + + + + + + + + -0.2038788 0.2810021 -0.9378014 -0.4027461 0.2584896 0.878054 0.01666653 -0.01166731 0.9997931 -0.1249691 0.0875675 0.9882888 -0.1264991 0.1072998 0.9861465 -0.02715975 -0.004229664 0.9996222 -0.03702384 0.04217284 0.9984242 -0.2694984 0.2470806 0.9307641 -0.2591285 0.2655823 0.9286112 -0.2397516 0.08836251 0.9668047 -0.2303572 0.1693821 0.9582512 -0.1888772 0.1322491 0.9730548 0.09225928 -0.1151213 -0.9890578 0.004391431 0.04650688 -0.9989084 0.009546875 -0.02216559 -0.9997088 -0.1123002 0.08661615 -0.9898921 -0.1191078 0.1306206 -0.9842519 -0.2069407 0.1326588 -0.969318 -0.2559511 0.1981433 -0.946165 0.002678811 0.002241551 0.9999939 0.01665997 -0.01166737 0.9997932 0.06316173 -0.044227 0.9970229 0.1368457 -0.1064701 0.9848541 0.1713386 -0.1199297 0.9778856 0.3225314 -0.2258812 0.9192123 0.3444972 -0.2518154 0.9043841 0.4197072 -0.2938829 0.8587659 0.4858719 -0.3402096 0.8051 0.5261266 -0.3816915 0.7599359 0.5692504 -0.3985932 0.719081 0.6756169 -0.4774234 0.5617907 0.6791694 -0.484498 0.5513534 0.6236287 -0.4366697 0.6483879 0.769147 -0.5509358 0.3238559 0.7613005 -0.5330685 0.3691335 0.7284274 -0.5100495 0.4574311 0.8163535 -0.5716176 -0.08258616 0.8190674 -0.5735182 0.01433491 0.8116408 -0.5807453 0.06304228 0.8102333 -0.5673312 0.1471646 0.7947478 -0.5564879 0.2422751 0.8021606 -0.5657653 -0.1909134 0.798501 -0.5670081 -0.2022327 0.7793396 -0.5456994 -0.3079643 0.7512393 -0.5260232 -0.3986719 0.723911 -0.5201629 -0.4531927 0.7011433 -0.4909456 -0.5170788 0.65682 -0.4599106 -0.5975531 0.6014705 -0.4318411 -0.672121 0.5857466 -0.4100415 -0.6991187 0.4642413 -0.3251687 -0.8238601 0.434965 -0.3151235 -0.8435062 0.3706876 -0.2595584 -0.8917512 0.2981891 -0.2087954 -0.9313902 0.2359909 -0.1785433 -0.9552124 0.1940929 -0.1359047 -0.9715235 0.06826382 -0.04779875 -0.9965217 0.06826359 -0.04779911 -0.9965217 0.6206097 0.7841197 0 0.6206047 0.7841235 1.49541e-5 0.6206214 0.7841104 -6.43214e-5 0.6206099 0.7841195 0 0.6206117 0.7841181 0 0.6206113 0.7841184 0 0.6206004 0.784127 0 0.6206098 0.7841196 2.4394e-6 0.6206132 0.7841169 0 0.6206042 0.784124 -2.2742e-6 0.6206063 0.7841225 0 0.6204769 0.7842248 2.0399e-4 0.6206058 0.7841229 -4.30293e-6 0.6206039 0.7841243 1.67614e-5 0.6206067 0.7841221 0 0.9989588 0.04562109 0 0.9989643 0.04550021 0 0.8191534 -0.5735746 0 0.6800177 -0.2379654 -0.6935045 0.6749171 -0.2487842 -0.6946894 0.7729814 -0.001361012 -0.6344273 0.766177 -0.02526473 -0.6421329 0.8086476 0.176886 -0.5610709 0.8139284 0.2932978 -0.5014947 0.807707 0.4029897 -0.4303588 0.7705643 0.5552962 -0.3128532 0.7030282 0.6869164 -0.1841121 0.6755605 0.7242907 -0.1379166 0.4253045 0.04099142 -0.9041216 0.5001972 -0.07640069 -0.8625345 0.4291787 0.01533943 -0.9030894 0.520415 -0.04985159 -0.8524572 0.4275978 -0.2290086 -0.87448 0.5954336 0.760696 -0.258458 0.5954228 0.7607256 -0.2583959 0.5330575 0.5335804 -0.6566138 0.5210658 0.4906929 -0.6983631 0.4464657 0.3524396 -0.8224688 0.3941465 0.2568845 -0.8824166 0.3347405 0.1878151 -0.9234036 0.6732247 0.7062675 -0.2189856 0.6732442 0.7062223 -0.2190715 0.7264804 0.3460291 -0.5937088 0.7265384 0.3460943 -0.5935999 0.7041169 0.6347107 -0.3183735 0.7165843 0.007735848 -0.6974576 0.6571956 0.7536396 -0.01101368 0.7101126 0.6977939 -0.09393626 0.8038985 0.5300692 -0.2697665 0.8161455 0.4931133 -0.3012406 0.8360157 0.3818145 -0.3940753 0.8317841 0.1601509 -0.5314952 0.8298193 0.1448389 -0.538908 0.7894188 -0.01294678 -0.6137186 0.695501 -0.2296936 -0.6808224 0.6872741 -0.2431315 -0.6845008 0.8796115 0.383747 -0.2811084 0.8728455 0.1564854 -0.4622262 0.8609026 0.1135693 -0.4959322 0.7108195 -0.2299854 -0.6647123 0.7034141 -0.2377302 -0.6698455 0.5725222 0.8178204 0.05820876 0.8383014 0.5262873 -0.1423821 0.8700548 0.4382652 -0.225673 0.7791225 0.6268131 -0.00857681 0.7205826 0.6889696 0.07798457 0.6597537 0.7339465 0.1613931 0.5793703 -0.4053136 -0.7071429 0.5792048 -0.4055994 -0.7071146 0.3949625 -0.2765955 -0.8760705 -0.3939906 -0.8273803 -0.4002666 0.4205973 0.9071728 0.01164484 0.1169396 0.1317541 -0.9843607 -0.03884196 0.2408306 -0.9697896 -0.03884059 0.240836 -0.9697884 0.3985066 0.2320036 -0.8873369 0.2150713 0.06393194 -0.9745035 0.1169251 0.1317464 -0.9843634 0.6770352 -0.2604314 -0.6883305 0.5575029 -0.1767444 -0.8111425 0.5574968 -0.1767454 -0.8111464 0.4656903 -0.1116043 -0.8778822 0.5551963 0.1799547 -0.8120181 0.3942096 -0.06181812 -0.9169391 0.2916545 0.009836912 -0.9564732 0.8738461 -0.04086959 -0.4844821 0.7473716 -0.3088589 -0.5882532 0.6770299 -0.2604429 -0.6883315 0.9044795 -0.4186979 -0.0812965 0.8920649 -0.410959 -0.1879711 0.8920299 -0.4110386 -0.1879625 0.8680121 -0.3932491 -0.303167 0.9283444 -0.1439505 -0.3427169 0.8401711 -0.3742535 -0.3924881 0.7909244 -0.3395609 -0.509055 0.9668575 -0.2549621 0.01345103 0.9068974 -0.4213474 0.001902341 0.8983528 -0.4146956 0.1448791 0.9805482 -0.09721523 0.1705125 0.8831083 -0.4040216 0.2385085 0.8500097 -0.3813194 0.3634269 0.9015597 -0.2398322 0.3600982 0.8179111 -0.3581116 0.4503085 0.7732086 -0.3277965 0.5428611 0.7732087 -0.3277867 0.5428668 0.7147137 -0.2859353 0.6382988 0.7696437 -0.02932274 0.6378 0.6610133 -0.2487813 0.7079331 0.5789664 -0.1911948 0.7926175 0.6759222 0.09611237 0.730679 0.5139539 -0.1454088 0.8454039 0.4179428 -0.07903212 0.9050292 0.4179538 -0.07901686 0.9050254 0.2690436 0.02523738 0.9627974 0.2690407 0.02524065 0.9627981 0.162955 0.100375 0.9815144 0.2800451 0.3742514 0.8840309 0.08466625 0.1549438 0.9842887 -0.02248805 0.2298103 0.9729756 0.1070448 0.4326049 0.8952065 -0.09885448 0.2837789 0.9537806 -0.1922969 0.348287 0.917452 -0.1923139 0.3482806 0.9174509 -0.2848882 0.4139775 0.8645585 -0.1368307 0.6405053 0.7556656 -0.351868 0.4605254 0.8149265 -0.4307038 0.5158387 0.7405436 -0.469868 0.4745365 0.744338 -0.2498452 0.7767806 0.5780911 0.01394611 0.86111 0.5082275 -0.07044988 0.8946193 0.4412405 0.1281195 0.9423302 0.3091913 -0.3693741 0.8016735 0.4699813 0.1015811 0.9781535 0.1813753 0.1849409 0.9658697 0.1813629 0.07741606 0.9870638 0.1403986 0.2543703 0.9637598 0.08039134 0.007813096 0.9968487 0.0789414 0.2184499 0.9755225 0.02520972 0.1346432 0.9907416 0.0173875 0.4206144 0.9071649 0.01164394 0.4236849 0.9049196 0.0401473 0.4236944 0.9049158 0.04013031 0.4326794 0.8986259 0.07252663 0.4326547 0.8986355 0.07255375 0.4465822 0.8888812 0.1022488 0.446598 0.8888759 0.1022262 0.4649598 0.8760183 0.1280795 0.4649466 0.8760257 0.1280765 0.4870514 0.8605495 0.1491163 0.4870622 0.8605437 0.1491144 0.5120676 0.8430367 0.164548 0.512069 0.8430381 0.1645364 0.539047 0.824145 0.1738206 0.5390426 0.8241536 0.1737934 0.5669762 0.8045874 0.1765701 0.5669704 0.8045915 0.1765705 0.5948159 0.7850933 0.1726924 0.5948172 0.7850879 0.1727121 0.6215265 0.7663865 0.1623469 0.6215215 0.7663964 0.1623198 0.6460844 0.749198 0.145868 0.6460883 0.7491958 0.1458617 0.6675933 0.7341361 0.1239496 0.667622 0.7341083 0.1239593 0.6852584 0.7217593 0.09738808 0.6852639 0.721755 0.09738165 0.6983758 0.7125749 0.06714445 0.6983505 0.7126007 0.06713366 0.7064503 0.7069272 0.03438031 0.7064766 0.7069004 0.03438967 0.7092424 0.7049647 3.40985e-4 0.7092391 0.7049679 3.41702e-4 0.7065599 0.7068497 -0.0337156 0.7065718 0.7068378 -0.03371548 0.6985759 0.7124384 -0.06650865 0.6985837 0.7124304 -0.06651222 0.6855533 0.7215585 -0.09679985 0.6855528 0.7215587 -0.09680122 0.6679915 0.7338574 -0.1234535 0.6679888 0.7338578 -0.1234652 0.6465557 0.7488682 -0.1454721 0.6465529 0.7488656 -0.1454985 0.6220375 0.766033 -0.1620588 0.6220378 0.7660296 -0.1620733 0.5953555 0.7847124 -0.1725642 0.5953629 0.7847119 -0.1725412 0.5675318 0.8041958 -0.1765698 0.5675359 0.8041948 -0.1765611 0.5395922 0.8237608 -0.17395 0.539586 0.8237695 -0.1739284 0.2897577 0.7648698 -0.5753389 -0.1657609 0.33023 -0.9292317 -0.1194903 0.3991901 -0.9090487 0.1413375 0.6427481 -0.7529268 0.08072745 0.6006113 -0.7954554 0.1889538 0.5236681 -0.8307035 0.1889466 0.5236543 -0.8307139 0.3223894 0.4302272 -0.8431902 0.322396 0.4302308 -0.8431858 0.4553042 0.3371754 -0.8240212 0.4552977 0.3371657 -0.8240288 0.582691 0.247965 -0.773941 0.5826765 0.2479712 -0.7739499 0.699772 0.1659838 -0.6948155 0.6997689 0.1659848 -0.6948184 0.8021656 0.09427046 -0.5896131 0.8021607 0.09426128 -0.589621 0.8860178 0.0355305 -0.462288 0.8860181 0.03557509 -0.462284 0.9481904 -0.007947444 -0.3176034 0.9481896 -0.007975161 -0.3176051 0.9863438 -0.03466445 -0.1610102 0.9863443 -0.03465819 -0.1610081 0.9990485 -0.04358321 0.001629948 0.9990495 -0.04356199 0.001629292 0.9858291 -0.03432613 0.1642038 0.9858291 -0.03431552 0.1642057 0.9471796 -0.007249832 0.320622 0.9471785 -0.00725764 0.320625 0.8845479 0.03660899 0.4650106 0.884554 0.03658926 0.4650005 0.8002908 0.09560096 0.5919418 0.8002926 0.09559231 0.591941 0.6975705 0.1675272 0.6966564 0.6975609 0.1675231 0.6966669 0.5802401 0.2496964 0.7752246 0.5802252 0.2496775 0.7752419 0.4526796 0.3389866 0.8247237 0.4526954 0.339002 0.8247089 0.3197256 0.4321038 0.8432449 0.3197204 0.4320957 0.8432511 0.186319 0.5255032 0.8301396 0.1863159 0.5255042 0.8301396 0.05749028 0.6156958 0.785884 0.05750519 0.6157149 0.7858679 -0.06191408 0.6993328 0.7121098 -0.06191414 0.6993198 0.7121226 -0.1490462 0.7616115 0.630661 -0.2883552 0.6622237 0.6916005 0.4837743 0.8402624 -0.2447892 0.5070819 0.84636 -0.1629197 0.3416316 0.7884843 -0.5114493 0.4059224 0.7425134 -0.5328235 0.4059227 0.7425082 -0.5328305 0.4915112 0.6825847 -0.5408281 0.4915102 0.6825785 -0.5408367 0.5767648 0.6228897 -0.5285366 0.5767557 0.6228935 -0.528542 0.6584634 0.565685 -0.4964137 0.6584635 0.5656825 -0.4964163 0.7335629 0.5130841 -0.4456795 0.7335625 0.5131058 -0.4456554 0.7992409 0.4671081 -0.3781852 0.7992393 0.4671222 -0.3781712 0.8530245 0.4294533 -0.2965115 0.8530225 0.4294639 -0.2965019 0.8928931 0.4015516 -0.2037109 0.8929023 0.4015306 -0.2037127 0.9173704 0.3844047 -0.1032698 0.9173735 0.3843969 -0.1032718 0.9255058 0.3787322 0.001045286 0.9255373 0.3786551 0.001046299 0.9170312 0.3846569 0.1053235 0.9170433 0.384629 0.1053194 0.8922464 0.402002 0.2056477 0.8922589 0.4019705 0.205655 0.8520795 0.4301129 0.2982674 0.8520823 0.4301272 0.2982394 0.7980414 0.4679712 0.3796485 0.7980362 0.4679547 0.3796796 0.732154 0.5140805 0.4468464 0.7321561 0.5140748 0.4468497 0.6568911 0.5667886 0.4972372 0.6568892 0.5667853 0.4972435 0.575093 0.6240723 0.528963 0.5750866 0.6240658 0.5289778 0.4897996 0.6837798 0.5408712 0.4897969 0.6837806 0.5408726 0.4042285 0.7436969 0.5324608 0.4042457 0.7436935 0.5324524 0.3216097 0.8015534 0.5040629 0.3215997 0.8015508 0.5040734 0.2450005 0.8551784 0.4567762 0.2450165 0.8551835 0.4567583 0.1773236 0.9025816 0.3923045 0.1773239 0.902575 0.3923196 0.1210848 0.9419571 0.3131379 0.121093 0.9419557 0.3131392 0.0841034 0.9684974 0.2343915 0.06828367 0.9682821 0.2403485 -0.5735765 -0.8191521 0 -0.5735768 -0.8191518 -3.90911e-6 -0.5735887 -0.8191434 4.54724e-5 -0.5735765 -0.8191521 6.54645e-7 -0.5735766 -0.819152 7.90069e-6 -0.5735757 -0.8191526 6.69996e-7 -0.5735765 -0.819152 -1.80185e-7 -0.5735767 -0.819152 -1.69119e-6 -0.5734307 -0.8192541 0 -0.5735764 -0.8191522 4.90723e-7 -0.5735794 -0.81915 0 -0.5735756 -0.8191528 -9.12596e-6 -0.5735781 -0.8191511 0 -0.573576 -0.8191524 0 -0.5735764 -0.8191521 0 -0.5735757 -0.8191527 9.99288e-7 -0.5735774 -0.8191515 -1.25274e-6 -0.5735762 -0.8191522 7.5031e-7 -0.5735773 -0.8191515 -1.04083e-6 -0.5735758 -0.8191525 2.38054e-6 -0.5735762 -0.8191523 0 -0.5735765 -0.819152 -9.36857e-7 -0.5735767 -0.819152 5.41408e-7 -0.5735765 -0.8191521 5.47059e-7 0.5735788 0.8191505 0 0.5736131 0.8191265 -2.07858e-5 0.5735813 0.8191486 3.47159e-6 0.5735793 0.8191502 -9.13286e-7 0.5735759 0.8191525 0 0.5735752 0.8191529 -2.82075e-6 0.5735768 0.8191518 1.54885e-6 0.5735763 0.8191522 -8.13201e-7 0.573575 0.8191531 0 0.5735772 0.8191516 -1.03515e-6 0.5735768 0.8191519 4.26063e-7 0.5735762 0.8191522 -3.48597e-6 0.5735764 0.8191522 0 0.5735769 0.8191518 2.03284e-6 0.5735756 0.8191527 -1.36593e-6 0.5735774 0.8191515 -9.38425e-6 0.5735765 0.819152 -1.41172e-6 0.5735763 0.8191522 -9.92748e-7 0.5735765 0.8191521 0 0.5735765 0.8191522 1.60277e-6 0.573577 0.8191518 0 0.5735762 0.8191523 0 0.5735985 0.8191366 2.73666e-5 0.5735418 0.8191764 -2.49228e-5 0.5735788 0.8191505 -1.96347e-6 0.5731868 0.8194248 -7.3283e-5 0.5725713 0.8198522 -0.00209701 0.5735768 0.8191519 0 0.5735777 0.8191514 1.1605e-6 0.5735759 0.8191525 5.25021e-7 0.5735763 0.8191522 1.94053e-6 0.5735766 0.8191521 -9.70282e-7 0.5735769 0.8191518 1.63238e-6 0.5735768 0.8191518 3.1867e-6 0.5735766 0.819152 -1.01513e-6 0.5735757 0.8191527 0 0.5735767 0.8191519 0 0.5735747 0.8191533 3.16774e-6 -0.9987295 0.05039429 -7.19919e-6 -0.9987295 0.05039435 -1.4602e-6 -0.9987288 0.05040824 -1.32458e-6 -0.9987293 0.05039829 0 -0.9987291 0.05040317 0 -0.9987294 0.05039405 0 -0.9987283 0.05041742 0 -0.9987304 0.05037665 4.42833e-6 -0.9983377 0.05763715 0 -0.9984445 0.05522024 -0.007707357 -0.9982924 0.0583505 -0.002743482 -0.9987702 0.04956936 -9.66133e-4 -0.9951459 0.09611225 -0.02114343 -0.9750456 0.2220049 0 -0.9909232 0.1344293 -1.15715e-4 -0.9807263 0.1949633 -0.01285374 -0.9974373 0.07103544 0.008541107 -0.9964212 0.08452731 0 -0.02296566 0.2882554 -0.9572782 -0.09795522 0.455631 -0.8847628 -0.08805429 0.4693784 -0.8785957 -0.8466731 0.5070497 -0.1613857 -0.8453701 0.5060275 -0.1711304 -0.5688933 0.7989993 -0.1948349 -0.6691775 0.6457297 -0.3677426 -0.5512145 0.8055633 -0.2173257 -0.4410222 0.6869115 -0.5776264 -0.4928361 0.6398108 -0.5897073 -0.1095231 0.5651351 -0.8176962 -0.1712524 0.7731184 -0.6107051 -0.1635452 0.7816706 -0.6018672 -0.1999318 0.9555808 -0.2165475 -0.1999319 0.955576 -0.2165685 0 0.4691021 -0.883144 -0.0505352 0.4572438 -0.8879044 0.05348539 0.7952569 -0.6039088 -0.02678823 0.7844217 -0.6196493 0.02597308 0.976318 -0.2147755 0 0.9752698 -0.221018 -0.8246432 0.4961358 -0.2716856 -0.9795011 0.1815156 -0.08734762 -0.9182103 0.3584672 -0.1684971 -0.6209319 0.6463395 -0.4434962 -0.8017171 0.5252721 -0.2852002 -0.685067 0.6616525 -0.304794 -0.6786491 0.724835 -0.118532 -0.8008045 0.5955277 -0.06371015 -0.684911 0.7020828 -0.1948762 -0.9542756 0.2680726 -0.1322695 -0.9531591 0.2992784 -0.04382133 -0.9536342 0.2977575 -0.0438469 -0.7578589 0.1827798 -0.6262918 -0.9553214 0.2107469 -0.2072365 -0.9669256 0.2290342 -0.1122424 -0.7996868 0.2262604 -0.5561541 -0.8299292 0.2153151 -0.5146425 -0.9529479 0.2212492 -0.2072178 -0.9364345 0.236895 -0.2587879 -0.1196809 0.3206651 -0.9396012 -0.3484962 0.3385142 -0.8740473 -0.5951082 0.3034021 -0.7441729 -0.5648339 0.287315 -0.7735716 -0.7545807 0.1956545 -0.6263603 -0.4809377 0.6836018 -0.5489878 -0.3273206 0.7067448 -0.6271946 -0.4967031 0.6816679 -0.5372291 -0.7283778 0.5939638 -0.341574 -0.7627431 0.4794958 -0.4339432 -0.6424231 0.5297474 -0.5537692 -0.6870779 0.396384 -0.6089365 -0.3212283 0.3481372 -0.8806889 -0.27039 0.5162993 -0.8126035 -0.2222486 0.5166165 -0.8268694 -0.4387655 0.6163547 -0.653905 -0.4960364 0.6396474 -0.5871961 -0.9004814 0.42084 -0.1096674 -0.9174464 0.366855 -0.1539789 -0.8984073 0.392955 -0.1960892 -0.9263962 0.2968587 -0.2316567 -0.9167281 0.3047971 -0.2582794 -0.9750465 0.193836 -0.1082226 -0.9737127 0.2004051 -0.1082656 -0.9689342 0.2204613 -0.1120859 -1 0 -1.48728e-4 -1 -1.95256e-5 0 -1 -2.26301e-6 0 -1 9.79706e-7 0 -1 0 0 -1 6.09067e-5 5.37734e-5 -1 5.73224e-5 7.87672e-5 -1 6.17345e-5 6.10168e-5 -1 -8.74638e-6 0 -1 4.13023e-6 0 -0.9999534 -0.00964874 3.33527e-4 -1 1.09417e-5 0 -1 -2.1932e-6 0 -1 3.61977e-6 -8.12757e-7 -0.9999981 0.001918911 3.60851e-4 -1 6.00033e-7 1.00705e-6 -0.9999995 -6.09104e-4 8.87744e-4 -1 4.93429e-5 -8.55529e-5 -1 5.51872e-7 3.41967e-7 -1 -1.45983e-4 3.7996e-4 -1 7.02486e-5 3.60168e-5 -1 6.58706e-5 4.7506e-5 -1 -5.38244e-6 0 -1 1.70222e-6 0 -1 2.37115e-7 0 -1 -7.14623e-6 0 -1 3.94027e-6 0 0 0 1 -4.97707e-7 0 1 0 0 1 -1.7577e-6 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 -7.10676e-6 -1.90368e-4 1 -2.16504e-7 0 1 0 0 1 0 0 1 2.01026e-6 0 1 -2.55029e-6 0 1 7.43674e-7 0 1 -1.97013e-6 0 1 7.14623e-6 0 0.9999985 -0.001728594 -4.25034e-4 1 0 0 0 -0.9997755 0.02119266 0.5484674 -0.8279281 0.1171267 -0.9922535 -0.1134308 0.0506618 0 -0.9659261 0.2588183 0 -0.9659215 0.2588356 0 -0.707116 0.7070976 0 -0.7070976 0.707116 0 -0.2588183 0.9659261 0 -1 0 0.8179798 -0.5727556 0.05348092 0.7648822 -0.5355758 0.3579301 0.4604478 -0.3233328 0.8267066 0.502801 -0.3520805 0.7894495 0.3621494 -0.3130431 0.8779817 0.4231379 -0.296284 0.8562536 0.3762471 -0.2726072 0.8855076 0.3758106 -0.2759698 0.884651 0.3684473 -0.3008635 0.8796181 0.5457679 -0.3821042 0.7457438 0.5889409 -0.4170665 0.6922458 0.609931 -0.4287876 0.6664274 0.7374417 -0.5163807 0.4353513 0.6961072 -0.49579 0.5192564 0.7166643 -0.5054771 0.4805052 0.6769248 -0.4739867 0.5631248 0.6503995 -0.4554153 0.6079289 0.7605302 -0.6488061 -0.02538871 0.755406 -0.6546911 -0.02723282 0.7892378 -0.6139394 0.01350259 0.8180097 -0.57275 0.05308169 0.7960574 -0.5574706 0.2356253 0.803586 -0.5769947 0.1460369 0.7889182 -0.552802 0.2683621 0.4000581 -0.8866134 -0.2320995 -0.362991 -0.9292466 -0.06883519 0.7286239 -0.6452062 -0.2298179 0.8088282 -0.5584724 -0.1841346 0.8095794 -0.572752 -0.1285938 -0.729613 0.6838259 -0.006853461 -0.4793529 0.8776184 0.002624809 -0.6776472 0.7353872 0 -0.6205888 0.7841321 -0.002566158 -0.303596 0.9528 0.001341819 -0.172971 0.9849268 -6.28916e-4 0.6205677 0.7841485 0.002648353 0.4680751 0.8836885 7.58411e-4 0.374368 0.9272803 -1.00408e-4 0.1155763 0.9932986 2.73938e-4 0.2540459 0.9671859 0.003493607 0.1044498 0.99453 7.69855e-4 0.4779477 0.8783853 -0.002340853 0.6728667 0.7397639 -1.23516e-4 0.824585 0.5657383 2.22632e-4 0.7708265 0.6370439 -0.001289963 0.9369082 0.3495719 0.001598119 0.893164 0.4497306 -6.81639e-4 0.9727556 0.2318332 1.77705e-4 0.9876362 0.156762 6.27413e-4 0.9940015 0.109367 6.26376e-5 0.9999855 0.005405247 0 -0.9559341 0.2935729 0.002273559 -0.9939955 0.1094214 6.30739e-5 -0.9999864 0.005212128 0 -0.9876653 0.1565787 -7.45e-4 -0.8930196 0.4500176 4.58414e-4 -0.8487066 0.5288636 -7.44371e-4 -0.4017693 0.9157409 3.59844e-5 -0.5754573 0.8178293 0.002003252 -0.4768665 0.8789755 -7.11793e-4 -0.7071604 0.7070532 2.99599e-4 -0.6728703 0.7397605 -1.60074e-4 -0.7704135 0.6375447 1.05244e-4 -0.2452616 0.969457 -3.29708e-5 -0.1146261 0.993408 0.001179218 3.72364e-4 0.9999998 -5.52937e-4 0.3028807 0.9530282 7.71867e-4 0.3319095 0.9433113 1.13826e-4 0.6233693 0.7819277 -9.87677e-5 0.5517647 0.8339983 0.001619458 0.7356908 0.677317 -8.91067e-4 0.6776778 0.735359 0 -0.5018804 0.8649371 0 -0.4432079 0.8964189 0 -0.4394255 0.8982772 -0.001830041 -0.5342679 0.8447645 -0.03051072 -0.3965126 0.9174599 0.03232729 -0.4135794 0.9100831 0.02647811 0.258438 0.9659864 0.008960187 0.2132585 0.9769958 0 0 1 0 -0.2584483 0.9660251 0 -0.213238 0.9769017 0.01388335 -0.3285785 0.944476 0.001153469 0.4432076 0.8964191 0 0.4523908 0.8914296 0.02638226 0.433882 0.9003586 0.03318077 0.5759544 0.8168424 -0.03232836 0.4107076 0.9115487 0.0199629 0.5244355 0.8513069 -0.01562649 0.3970407 0.9177316 0.01128792 0.4432842 0.8963811 3.70643e-5 0.3732838 0.9277172 -3.16107e-6 0.3288569 0.9443792 0.001120686 0.7081291 0.706083 0 0.7094648 0.704741 2.34585e-4 0.6423731 0.7663922 -2.41607e-4 0.6203551 0.7843117 -0.003850519 0.5071108 0.8618475 0.007586359 0.5026169 0.8645093 0 -0.4339003 0.9007544 0.01929211 -0.5028063 0.8643979 0.001537263 -0.6059148 0.7955289 -0.001114428 -0.619377 0.7850857 -0.003565669 -0.6914099 0.7224566 0.002960443 -0.7091917 0.7050157 0 -4.38341e-7 0 1 4.38341e-7 0 1 4.38347e-7 0 1 -4.38347e-7 0 1 -0.9659264 -0.2588173 0 -0.7071014 -0.7071123 0 -0.7071011 -0.7071125 0 -0.2588239 -0.9659246 0 -0.2588239 -0.9659246 0 0.2588239 -0.9659246 0 0.2588239 -0.9659246 0 0.707102 -0.7071117 0 0.7071018 -0.7071118 0 0.965926 -0.2588185 0 0.9659261 -0.2588182 0 0.9659254 0.2588207 0 0.9659253 0.258821 0 0.707112 0.7071017 0 0.7071118 0.7071018 0 0.2588147 0.9659271 0 0.2588145 0.9659271 0 -0.2588147 0.9659271 0 -0.2588145 0.9659271 0 -0.7071114 0.7071023 0 -0.7071112 0.7071024 0 -0.9659258 0.2588198 0 1.9197e-6 0 1 -1.91915e-6 0 1 -9.21802e-7 0 1 -2.55152e-7 0 1 -2.20007e-6 0 1 2.21045e-6 0 1 -2.79547e-7 0 1 -2.25205e-6 0 1 9.91466e-7 0 1 2.28907e-6 0 1 -0.6270792 -0.7789555 0 -0.8598642 -0.510523 0 -0.8598606 -0.5105288 0 -0.9840934 -0.177652 0 -0.984093 -0.1776543 0 -0.9813147 0.1924101 0 -0.7629312 0.6464798 0 -0.7629352 0.6464749 0 -0.350861 0.9364275 0 -0.350861 0.9364277 0 0.1502927 0.9886416 0 0.1502904 0.9886419 0 0.6132823 0.7898638 0 0.6132764 0.7898685 0 0.9205762 0.3905632 0 0.9205761 0.3905635 0 0.9941628 -0.1078907 0 0.9941628 -0.1078904 0 0.8153577 -0.5789577 0 0.8153609 -0.5789531 0 0.4295568 -0.9030399 0 0.4295607 -0.9030381 0 -0.06529945 -0.9978657 0 -0.06529945 -0.9978657 0 -0.5435749 -0.8393607 0 -0.5435683 -0.839365 0 0.2866529 0.9580345 0 0.286607 0.9580484 9.74729e-5 0 1 -9.46674e-5 0 1 -8.5775e-5 -0.2867986 0.9579909 9.46675e-5 -0.2866069 0.9580483 -2.69851e-4 -0.9658442 0.2591239 0 -0.9658436 0.2591258 0 -0.8189891 0.5738092 0 -0.8189886 0.5738099 0 -0.5747162 0.8183528 0 -0.5733188 0.8193323 3.25925e-4 -0.7596141 0.2195779 0.6121864 -0.9489602 0.3153961 0 -0.8319622 0.5548325 0 -0.831961 0.5548343 0 -0.6234078 0.781897 0 -0.6234074 0.7818973 0 -0.1420967 0.3045293 0.9418442 -0.124556 0.2677533 0.9554026 -0.1071155 0.2347374 0.9661391 -0.01658636 0.0355553 0.9992302 -0.06565171 0.1561806 0.9855443 -0.06681036 0.1579383 0.9851862 -0.1067247 0.233348 0.9665188 0.07339018 0.1573888 0.9848059 0.03068435 0.09930533 0.9945838 0.09179967 0.2050754 0.9744316 0.1241037 0.266944 0.9556878 0.1413599 0.3031334 0.9424052 0.8319618 0.554833 0 0.6234078 0.781897 0 0.6234072 0.7818975 0 0.7596262 0.2195782 0.6121711 0.9489595 0.3153983 0 0.8319599 0.5548359 0 0.5741743 0.8187331 0 0.5741754 0.8187325 0 0.8207883 0.5712325 0 0.9663848 0.2571001 0 0.966386 0.2570955 0 0.1105306 0.325611 0.9390211 0.09587651 0.3204299 0.9424079 -0.1105168 0.3255715 0.9390364 -0.05446898 0.2963276 0.9535319 0.06186771 0.3365818 0.9396197 0.02490806 0.3419166 0.9394001 0 0.3309977 0.9436317 -0.02490806 0.3419161 0.9394003 -0.09901314 0.3307315 0.9385165 -0.09904444 0.3307603 0.938503 9.0874e-4 -0.02135658 -0.9997716 0 0 -1 0 0 -1 -0.003048181 -0.001288414 -0.9999946 -0.01211017 0.01497274 -0.9998146 0.1901944 0.143921 -0.97114 0 0.004522144 -0.9999899 5.24284e-7 0 -1 -2.56424e-7 0 -1 8.09679e-7 0 -1 -9.18906e-4 0.007087051 -0.9999745 0.001543402 0.01419758 -0.999898 -4.75323e-4 0.01065111 -0.9999433 -2.90766e-7 0 -1 2.35369e-7 0 -1 -1.77601e-7 0 -1 -3.56151e-6 0 -1 -9.84063e-7 0 -1 2.51833e-7 0 -1 -0.01044934 -0.004337191 -0.9999361 0.006677925 0.0018996 -0.9999759 1.64529e-6 0 -1 1.55715e-4 0.0239191 -0.9997139 -0.001310229 -0.004793703 -0.9999877 1.33339e-4 0.01259535 -0.9999207 -5.31802e-6 0 -1 3.97456e-6 0 -1 -2.20303e-5 0 -1 5.92287e-7 0 -1 -5.44263e-7 0 -1 2.16248e-7 0 -1 8.39084e-7 0 -1 0.001343071 -0.007373034 -0.9999719 -0.0687043 -0.1062303 -0.9919652 -0.1378126 -0.2131392 -0.9672536 -0.06855899 -0.1097496 -0.991592 -0.04664391 -0.1213989 -0.9915073 -0.04664528 -0.1214002 -0.9915071 -0.02303051 -0.1273045 -0.9915964 -0.0168212 -0.1368884 -0.9904437 -0.0812146 -0.1892567 -0.9785633 -0.003816604 -0.1567246 -0.987635 0.02018225 -0.1642367 -0.9862146 0.03404843 -0.1149157 -0.9927915 0.002266347 -0.003518939 -0.9999912 0.02776741 -0.1261265 -0.9916255 0.0466454 -0.1214006 -0.991507 0.04664438 -0.1213998 -0.9915071 0.0676226 -0.110249 -0.9916009 0.07262384 -0.1122856 -0.9910185 2.03215e-7 0 1 -3.04581e-7 0 1 2.95162e-7 0 1 -1.21894e-6 0 1 3.50451e-7 0 1 6.63933e-7 -1.37455e-6 1 0 0 1 -4.16158e-7 0 1 8.85388e-7 0 1 -4.12892e-7 0 1 3.58483e-7 0 1 -2.90434e-7 0 1 1.85353e-7 0 1 -1.41711e-6 0 1 1.30693e-6 0 1 0 0 1 0 0 1 0 0 1 -5.06401e-6 0 1 3.30019e-7 0 1 0 0 1 -1.68856e-7 0 1 -4.01884e-7 0 1 3.28668e-7 0 1 -8.88251e-7 0 1 4.8675e-7 0 1 -1.52722e-7 0 1 0 1.71627e-6 1 4.38547e-7 7.0771e-7 1 -7.19557e-7 0 1 5.68707e-7 0 1 -7.32062e-7 0 1 4.34752e-6 0 1 -0.4003866 -0.05548024 -0.9146653 -0.1674014 -0.1900959 -0.9673884 -0.08008199 -0.09741264 -0.992017 -0.09239476 -0.0908631 -0.991568 -0.09629648 -0.08508217 -0.9917097 -0.1134352 -0.08089035 -0.9902471 -0.1356738 -0.02768653 -0.9903666 -0.1410812 -0.02665346 -0.9896392 -0.1336125 -0.03564399 -0.9903925 -0.1292331 -0.05080211 -0.9903121 -0.1398945 -0.04869168 -0.9889685 -0.124909 -0.05959618 -0.9903767 -0.321758 -0.0658223 -0.9445312 -0.3226935 -0.06585156 -0.9442101 -0.3128829 -0.1006155 -0.9444475 -0.2342105 -0.09206598 -0.9678168 -0.3869652 -0.2336294 -0.8920063 -0.1171309 -0.07401162 -0.9903549 -0.1195076 -0.0725702 -0.9901775 -0.1445473 0.3099572 0.9396982 -0.1445413 0.3099761 0.9396929 -0.1445435 0.3099732 0.9396935 -0.1445418 0.3099712 0.9396944 -0.144544 0.3099569 0.9396988 -0.1445343 0.3100251 0.9396778 -0.1445406 0.3099715 0.9396945 -0.1445475 0.3099771 0.9396916 -0.1445409 0.3099761 0.9396929 -0.1445447 0.3099757 0.9396924 -0.1445343 0.3099641 0.9396979 -0.1445415 0.309976 0.9396929 -0.1445451 0.3099758 0.9396923 -0.1445448 0.3099749 0.9396927 -0.1445399 0.3099675 0.9396959 -0.1458988 0.3075152 0.9402915 -0.1444672 0.3098146 0.9397576 -0.1446319 0.3102974 0.9395729 -0.1445453 0.3099643 0.9396962 0.1121312 0.4104648 0.904956 0.1220768 0.4172306 0.9005643 0.1197624 0.4235398 0.897926 0.1329932 0.4127679 0.9010747 0.2733991 0.3613201 0.8914599 0.2305591 0.3719736 0.8991542 0.1278337 0.405791 0.9049819 0.02300655 0.2868515 0.9576989 -0.02559173 0.349582 0.9365562 -0.03565257 0.372089 0.9275122 -0.0395013 0.3781054 0.9249194 -0.08077937 0.4370026 0.8958256 -0.08583658 0.4610639 0.8832057 -0.05039572 0.3935324 0.9179285 -0.05142378 0.3413105 0.938543 -0.04157721 0.362552 0.9310357 -0.05946981 0.3998532 0.9146479 0.0557872 0.1748846 0.9830073 -0.02202022 0.2417529 0.970088 0.08154243 0.2064205 0.9750597 -0.02918469 0.3531389 0.9351156 -0.02944326 0.3536553 0.9349123 0.02161788 0.08808296 0.9958785 0.109002 0.06639343 0.9918219 0.5817655 -0.04777121 0.8119525 0.3949972 0.06307077 0.9165148 0.07018929 0.126303 0.9895055 0.2590852 -0.004618465 0.9658435 0.07028162 0.02105337 0.997305 0.5534958 0.2202111 0.8032121 0.3935381 0.1735931 0.9027698 0.4104869 0.3137653 0.8561845 0.5022551 0.2532597 0.8268008 0.554355 0.256596 0.7917381 0.5415468 0.2397223 0.805767 0.285887 -0.1169664 0.951098 0.01932477 0.5142852 0.8574015 0.3404954 0.1137138 0.9333447 0.3389581 0.2838997 0.8969439 0.3093274 0.3441467 0.8864985 0.6195174 0.1676524 0.766871 0.05974733 0.3413924 0.9380201 -0.3580588 0.3309592 0.873075 -0.2332987 0.3681991 0.9000007 0.08517777 0.4428895 0.8925211 0.08858412 0.4487202 0.8892711 0.06971943 0.4304822 0.8999024 0.06423997 0.4223811 0.9041391 0.05048519 0.3974287 0.9162433 0.05746775 0.4029826 0.9134017 0.04066693 0.3605865 0.9318389 -0.1109601 0.4097029 0.9054454 -0.2525615 0.3636203 0.8966566 -0.165888 0.400478 0.9011652 -0.1375744 0.4137473 0.8999369 -0.1197693 0.4203254 0.8994343 -0.1185763 0.4149917 0.9020652 -0.02597343 0.2093123 0.9775038 -0.07117199 0.1854666 0.9800698 0.0163905 0.3336342 0.9425601 -0.02586948 0.2837389 0.9585527 0.0393694 0.3678106 0.929067 0.02934759 0.3582893 0.9331493 0.04107958 0.3772774 0.9251887 0.1124953 0.4810954 0.8694205 -0.1552041 -0.06850308 0.9855045 -0.1656092 0.1038691 0.9807063 -0.1041532 0.03187423 0.9940504 -0.1278041 -0.04839587 0.9906179 -0.131671 0.08148902 0.9879384 -0.6024081 0.1876569 0.7758154 -0.6148893 0.1743124 0.7691076 -0.6243146 0.1757348 0.7611496 -0.5179288 0.243467 0.8200448 -0.465851 0.2927737 0.8350248 -0.4020238 0.1616301 0.9012506 -0.5151402 -0.09815496 0.8514671 -0.4868391 0.06516039 0.8710579 -0.2849813 0.2911035 0.9132604 -0.2870637 0.2875171 0.9137441 -0.3260336 0.2601609 0.9088556 0.1445429 0.309975 0.9396929 0.1445439 0.3099929 0.9396869 0.1445451 0.3099458 0.9397023 0.1445484 0.309986 0.9396885 0.1445422 0.3099659 0.9396961 0.1445413 0.3099764 0.9396928 0.1445443 0.3099743 0.939693 0.1445415 0.3099743 0.9396935 0.1445457 0.3099778 0.9396917 0.1445381 0.3100015 0.939685 0.1445428 0.3099749 0.939693 0.1445443 0.3099746 0.9396929 0.1445472 0.3099801 0.9396906 0.1444543 0.3098289 0.9397549 0.144546 0.3099755 0.9396924 0.1444227 0.3096644 0.9398139 0.1445214 0.3099522 0.9397038 0.1446489 0.3101012 0.9396351 0.1446186 0.3100627 0.9396524 0.8687644 0.3965891 -0.2965903 0.8687655 0.3965942 -0.2965798 0.871823 0.4861587 0.05978715 0.8419237 0.511175 0.1728142 0.8085598 0.5097276 0.2939539 0.6274043 0.4887815 0.6061819 0.6274145 0.4887931 0.6061621 0.2499647 0.445399 0.859731 0.2388043 0.4804192 0.8439016 0.2230917 0.461945 0.8583922 0.3857316 0.7302685 0.5638431 0.3903254 0.7499194 0.534104 0.4710268 0.8752986 0.1094821 0.4715952 0.8741452 0.1160525 0.445708 0.8153107 -0.3696117 0.461132 0.8260283 -0.3240903 0.4508463 0.5350687 -0.7144502 0.7203724 0.2279099 -0.6550731 0.7203595 0.2279084 -0.6550878 0.6533915 0.3340755 -0.6793181 0.3064082 0.3808951 0.8723721 0.3063843 0.3808795 0.8723872 0.2924957 0.4032112 0.8671027 0.5840263 0.5578308 0.5896933 0.5840427 0.5578442 0.5896643 0.7803233 0.6071527 0.1498713 0.7803205 0.6071473 0.1499075 0.7939327 0.5145446 -0.3239056 0.7939091 0.5145323 -0.3239828 0.6534029 0.3340876 -0.6793012 0.5601685 0.4420376 -0.7005813 0.5601621 0.4420406 -0.7005844 0.6901255 0.6347255 -0.3476357 0.6901061 0.6347133 -0.3476963 0.6871621 0.7150216 0.1286564 0.6871588 0.7150203 0.1286808 0.5233554 0.6281204 0.5758159 0.5233529 0.6281217 0.5758167 0.2729018 0.4258637 0.8626499 0.2924738 0.4032079 0.8671116 0.3537663 0.6246178 -0.6962055 0.337606 0.6055955 -0.7206083 0.4508226 0.5350554 -0.7144751 0.5684336 0.7383105 -0.3630163 0.5684091 0.7382875 -0.3631016 0.5779314 0.8079726 0.1147853 0.577935 0.8079671 0.1148056 0.4521946 0.6886835 0.566776 0.4521723 0.6886553 0.5668283 0.2499591 0.4453973 0.8597337 0.2729178 0.425881 0.8626363 -0.2234271 0.6581908 -0.7189335 -0.2273578 0.6817498 -0.6953602 -0.1249175 0.7061582 -0.6969479 -0.04732561 0.7159652 -0.6965302 0.2310703 0.6807044 -0.6951604 0.1731692 0.5101239 0.8424881 0.03904473 0.5359503 0.8433462 -0.163951 0.482978 0.8601468 0.173145 0.5100769 0.8425215 0.2721217 0.8016555 0.5322578 0.272122 0.8016543 0.5322594 0.3192828 0.9405924 0.1155179 0.3192868 0.9405832 0.115582 0.30419 0.896116 -0.3231788 0.3042022 0.896147 -0.3230817 0.2310557 0.6806597 -0.6952091 0.07826024 0.7146047 -0.695137 0.07826048 0.7145795 -0.695163 0.1030256 0.94072 -0.3231592 0.1030275 0.9407286 -0.3231334 0.1081391 0.987394 0.1155822 0.1081381 0.9873968 0.1155582 0.09216964 0.8415883 0.5321972 0.09216874 0.8415607 0.5322412 0.06827342 0.6233898 0.7789248 0.09701728 0.5278069 0.8438054 -0.08901816 0.8128055 -0.5756934 -0.1030275 0.9407308 -0.3231271 -0.1030247 0.9407157 -0.3231719 -0.1081393 0.9873933 0.1155873 -0.1081381 0.9873968 0.1155582 -0.09216868 0.8415796 0.5322113 -0.09216874 0.8415606 0.5322412 -0.06827342 0.6233898 0.7789248 -0.03904473 0.5359503 0.8433462 -0.2678978 0.7892121 -0.5526076 -0.3030182 0.8926634 -0.333665 -0.3028134 0.896604 -0.3231182 -0.3208115 0.9400647 0.1155793 -0.3208184 0.9400653 0.115555 -0.2625753 0.7790316 0.5693541 -0.2773133 0.8000829 0.5319443 -0.1693609 0.5110527 0.8426992 -0.09701728 0.5278069 0.8438054 -0.807096 0.5098512 0.2977381 -0.4055616 0.7270146 -0.5540484 -0.7209551 0.2284269 -0.6542514 -0.7209595 0.22843 -0.6542455 -0.6701079 0.3110023 -0.6739681 -0.7263108 0.4164901 -0.546817 -0.6273553 0.3678171 -0.6863934 -0.5606425 0.4426621 -0.6998074 -0.5606347 0.4426503 -0.699821 -0.4512771 0.5357626 -0.7136578 -0.4512598 0.5357459 -0.7136813 -0.3429499 0.6035158 -0.7198292 -0.3429358 0.6034864 -0.7198606 -0.2248527 0.4553409 0.8614557 -0.2248759 0.4553743 0.861432 -0.2469929 0.4416452 0.8625219 -0.2470065 0.4416719 0.8625043 -0.26928 0.4226826 0.8653483 -0.2692908 0.422703 0.8653351 -0.2883064 0.4007049 0.8696639 -0.2882856 0.4006595 0.8696916 -0.3018118 0.3790016 0.8747957 -0.3018094 0.3790012 0.8747967 -0.378928 0.7279632 0.5713871 -0.3789131 0.7279528 0.5714103 -0.4485204 0.6845605 0.5746359 -0.4485357 0.6845727 0.5746094 -0.5187592 0.6248345 0.5834988 -0.5187376 0.624813 0.583541 -0.5786301 0.555486 0.5971789 -0.5786291 0.5554863 0.5971795 -0.6214133 0.4873532 0.6134595 -0.6214231 0.4873504 0.6134517 -0.4694021 0.875321 0.1160815 -0.4694142 0.8753219 0.1160257 -0.577103 0.8076081 0.1213316 -0.5770989 0.8076055 0.1213685 -0.6859789 0.7149634 0.1351307 -0.6859737 0.7149676 0.1351354 -0.7788178 0.6074465 0.15637 -0.7788338 0.607448 0.1562852 -0.840134 0.5119333 0.1791624 -0.8714122 0.48657 0.06237465 -0.4536399 0.8259208 -0.3347622 -0.4534068 0.8126911 -0.3659996 -0.5690117 0.7395308 -0.359611 -0.5690065 0.7395197 -0.359642 -0.690737 0.6359412 -0.3441819 -0.6907478 0.6359521 -0.3441402 -0.7945436 0.5157407 -0.3204872 -0.7945393 0.5157405 -0.3204983 -0.8693774 0.3977734 -0.293188 -0.8693881 0.3977771 -0.2931516 0.1339594 0.03789252 -0.9902621 0.01922369 0.1766749 -0.9840816 -0.02285557 0.1762326 -0.9840832 -0.02285838 0.1762441 -0.984081 -0.06365615 0.1659275 -0.9840814 0.06443315 0.1788826 -0.9817583 0.0539782 0.1686644 -0.9841945 0.01922398 0.176676 -0.9840814 0.0795378 0.1137906 -0.9903159 0.0837168 0.04741752 -0.9953609 0.09301519 0.141023 -0.9856271 0.1048738 0.1373316 -0.9849577 0.164272 0.09104776 -0.9822043 0.1339625 0.03789234 -0.9902617 0.1391142 0.005332231 -0.9902621 0.139115 0.005332231 -0.990262 0.401814 -0.04548043 -0.9145913 0.3660337 0.1722838 -0.914515 0.3912376 0.1106669 -0.9136115 0.39124 0.1106661 -0.9136106 0.4062927 0.01557278 -0.9136103 0.4062902 0.01557332 -0.9136115 0.4018229 -0.04549086 -0.9145867 0.1374515 -0.01556122 -0.9903863 0.1374508 -0.01555997 -0.9903864 0.1212956 0.06832808 -0.990262 0.1212955 0.06832897 -0.9902619 0.3371453 0.1899212 -0.9220972 0.2612746 0.2690961 -0.9269968 0.3142495 0.2548885 -0.914483 0.3435258 0.2147013 -0.914272 -0.05229425 0.4032149 -0.91361 0.04397839 0.4042069 -0.9136098 0.04398018 0.4042016 -0.913612 0.1377886 0.3825293 -0.9136113 0.1377883 0.3825298 -0.9136112 0.2238636 0.3394039 -0.9136137 0.2238681 0.3394097 -0.9136106 0.2973948 0.2772567 -0.913611 0.1018292 0.0949338 -0.9902618 0.1018316 0.09493356 -0.9902616 -0.2849861 0.2874427 -0.9144176 -0.2308124 0.3347332 -0.9136078 -0.2308076 0.3347235 -0.9136127 -0.1805841 0.3617134 -0.9146327 -0.1410875 0.3677599 -0.9191556 -0.1370016 0.3819537 -0.9139705 -0.05229198 0.4032114 -0.9136116 -0.2897377 0.2300267 -0.9290532 -0.3030418 0.2710707 -0.9136117 -0.3455131 0.21103 -0.9143779 -0.3401093 0.1824685 -0.9225134 -0.3679494 0.1685855 -0.9144355 -0.3934353 0.1025886 -0.9136106 -0.3934331 0.1025881 -0.9136115 -0.4065265 0.007204353 -0.9136107 -0.4065265 0.007204174 -0.9136106 -0.1372503 -0.01697033 -0.990391 -0.06253874 0.1884824 -0.9800834 -0.1092221 0.129992 -0.985481 -0.09541118 0.138368 -0.9857744 -0.0822004 0.05998814 -0.9948088 -0.4012193 -0.04960387 -0.914638 -0.4012289 -0.04959839 -0.914634 -0.1372313 -0.01696473 -0.9903938 -0.1391946 0.002466738 -0.990262 -0.1391956 0.002466917 -0.9902619 -0.1347114 0.03512674 -0.9902621 -0.134715 0.03512644 -0.9902616 -0.1226764 0.06581628 -0.990262 -0.1226765 0.06581652 -0.990262 -0.1037587 0.09281581 -0.9902623 -0.1037656 0.09281682 -0.9902614 -0.08358484 0.1106109 -0.9903429 -0.003538548 0.004980564 -0.9999814 0.003055632 -0.002943456 -0.9999911 0.4342553 -0.2711859 -0.8589997 0.09381556 -0.07543659 -0.9927276 0.1053146 -0.08689802 -0.990635 0.2956058 -0.1597852 -0.9418524 0.2694871 -0.1045984 -0.9573066 0.3385223 -0.1040421 -0.9351887 0.308129 -0.07165408 -0.9486423 0.3920581 -0.05904716 -0.9180436 0.3922262 -0.0606445 -0.9178676 0.4040108 -0.02943158 -0.9142807 0.1070288 -0.09713762 -0.9894995 0.1134853 -0.07901597 -0.9903926 0.12197 -0.06592994 -0.9903417 0.12221 -0.06743776 -0.9902106 0.1283588 -0.04982209 -0.9904756 0.1366488 -0.02107053 -0.9903955 0.1366615 -0.02113199 -0.9903925 0.1352216 -0.02879679 -0.9903969 0.1394997 -0.03244024 -0.9896907 0.1322441 -0.04040819 -0.9903932 0.1287388 -0.05094063 -0.9903694 -0.02285921 -0.18601 -0.9822819 -0.03672254 -0.1927154 -0.9805673 -0.06831216 -0.1777888 -0.9816948 -0.07070165 -0.1787738 -0.9813467 -0.1061215 -0.1640825 -0.9807218 -0.1037477 -0.1636896 -0.9810414 0.105163 -0.1625998 -0.9810719 0.1044414 -0.1647866 -0.9807841 0.06896293 -0.1794884 -0.98134 0.06999498 -0.176985 -0.9817215 0.02439028 -0.1984747 -0.9798025 0.03433316 -0.180176 -0.983035 0 -0.1975318 -0.9802965 0.03478199 -0.05487841 -0.9978871 0.03478175 -0.05487799 -0.9978871 0.02389514 -0.06041818 -0.9978871 0.02389377 -0.06041949 -0.9978871 0.01216262 -0.06382417 -0.9978871 0.01216238 -0.06382334 -0.9978871 0 -0.0649718 -0.9978871 0 -0.06497144 -0.9978871 -0.01216077 -0.06382298 -0.9978871 -0.01216316 -0.06382405 -0.9978871 -0.02389383 -0.06041896 -0.9978871 -0.02389419 -0.06041878 -0.9978871 -0.03478151 -0.05487746 -0.9978872 -0.03478175 -0.05487746 -0.9978871 -0.2774102 0.4448682 0.8515492 0.3643846 0.3678924 0.8554993 0.4183038 0.3542265 0.8363885 0.4456228 0.283849 0.8490289 0.4491291 0.2837327 0.8472183 0.5553289 0.1402153 0.8197253 0.514685 0.1536644 0.8434967 0.3924082 0.07807135 0.9164718 0.2490879 0.05580234 0.9668719 0.1901971 0.07850569 0.9786021 0.1800669 0.04334896 0.9826988 0.03768926 0.2044991 0.9781409 0.1004278 0.1610509 0.9818233 0.1335623 0.1348484 0.9818233 0.1335622 0.1348488 0.9818233 0.1587037 0.1036891 0.9818664 0.1631472 0.1039197 0.9811135 0.1746267 0.06258463 0.9826437 0.5274296 0.1890268 0.8283038 0.4563266 0.1958233 0.8679974 0.06562113 0.1887776 0.9798249 0.07124912 0.1750382 0.9819803 0.1004276 0.1610515 0.9818232 0.01760697 0.1977123 0.980102 0.03755182 0.184934 0.9820333 0.05130904 0.1818069 0.9819948 0.02112185 0.1886201 0.981823 -0.02112227 0.18862 0.981823 -0.01760655 0.1977103 0.9801024 -0.05937784 0.1708194 0.9835116 -0.05594438 0.2063585 0.9768759 -0.1413987 0.1378583 0.9803069 -0.1202455 0.1455655 0.9820142 -0.1004864 0.1611425 0.9818023 -0.1165248 0.1706014 0.9784259 -0.07815033 0.1653594 0.9831322 -0.1256192 0.1063395 0.9863629 -0.1775832 0.04626142 0.9830179 -0.1882594 0.06747007 0.9797991 -0.610006 0.151749 0.7777307 -0.4175211 0.3621589 0.8333769 -0.4454629 0.2770785 0.8513462 -0.4500252 0.2866556 0.8457576 -0.5054917 0.212746 0.8361922 -0.4871273 0.174583 0.8557031 -0.5009969 0.1636067 0.8498442 -0.42423 0.04038864 0.9046534 -0.3559139 0.4240906 0.83275 -0.3632654 0.3667655 0.8564587 -0.1343852 0.1356801 0.9815965 -0.1591858 0.1013978 0.9820277 -0.1660224 0.1130176 0.9796243 -0.167631 0.07615596 0.9829039 0.3648683 0.4007698 0.8403896 0.2875484 0.4611285 0.8394501 0.2875522 0.4611325 0.8394466 0.1784327 0.5133086 0.8394499 0.1784335 0.5133113 0.8394481 0.06047457 0.5400673 0.8394464 0.06047743 0.5400642 0.8394482 -0.03928577 0.540646 0.8403325 -0.05771249 0.51538 0.8550162 -0.1234195 0.5415875 0.8315351 -0.1701785 0.489574 0.855194 -0.2038503 0.5073295 0.8372944 -0.2760815 0.4604311 0.8436719 -0.4077174 -0.05882561 -0.9112114 -0.5428811 -0.01005816 -0.8397494 -0.1009034 -0.003414452 -0.9948904 -0.08620578 0.02254897 -0.9960222 -0.1523046 -0.09319645 -0.9839298 -0.2596632 -0.006762266 -0.9656756 -0.2688229 -0.04585838 -0.9620974 -0.3235813 -1.19716e-5 -0.9462004 -0.3098002 0.01795506 -0.9506322 -0.1290087 -0.1441384 -0.9811121 -0.1619868 -0.1290451 -0.9783188 -0.2378356 -0.1192703 -0.9639548 -0.2345878 -0.1188136 -0.9648067 -0.3101714 -0.09899479 -0.9455125 -0.3085042 -0.0987671 -0.9460816 -0.3374423 -0.07402431 -0.9384313 -0.4039139 -0.05079525 -0.9133857 -0.417907 -0.003566563 -0.9084828 -0.8177217 0.03574842 -0.5745027 -0.7572224 0.1521276 -0.6351941 -0.9086644 0.0764141 -0.4104754 -0.966727 0.1491236 -0.2078485 -0.9691908 0.159807 -0.1874325 -0.2472894 0.3244389 0.91301 -0.3772494 0.359236 0.8535997 -0.4771704 0.3436445 0.8088368 -0.7036502 0.3384433 0.6247661 -0.7035213 0.338478 0.6248923 -0.8728991 0.3034296 0.3820701 -0.8728074 0.3034956 0.3822273 -0.9657325 0.2398598 0.09913671 -0.9657107 0.2399032 0.09924429 -0.9787782 0.1927974 -0.06944358 -0.8587536 0.1706491 -0.4831368 -0.9279725 0.2961682 -0.2261668 -0.9258847 0.273381 -0.260769 -0.9338374 0.3513702 0.06698346 -0.9274665 0.3618378 0.0942313 -0.8444396 0.4027457 0.3531542 -0.8590591 0.3938818 0.3269168 -0.6805329 0.4191088 0.6010182 -0.6496647 0.4266494 0.6292107 -0.3793239 0.3518717 0.8557451 -0.3129973 0.3547929 0.8809964 -0.2374457 0.3799014 0.8940327 -0.9702721 -0.159875 -0.1816927 -0.9883485 0.1480963 0.03514093 -0.549707 0.6252973 0.5539184 -0.3592216 0.6299656 0.6885516 -0.524551 0.5371928 0.6605075 -0.5024839 0.6640603 0.553655 -0.4870823 0.6947357 0.5292384 -0.9889931 0.1448438 0.03021943 -0.905757 0.3802961 0.1870279 -0.9201581 0.3457353 0.1837834 -0.739586 0.59124 0.321633 -0.561208 0.5603768 0.6091169 -0.7318117 0.5177206 0.4431897 -0.6521536 0.5913088 0.474394 -0.8692455 0.3200835 0.3767743 -0.8560891 0.313923 0.4105655 -0.6973446 0.3686622 0.6146535 -0.7052186 0.3734977 0.6026328 -0.470077 0.381589 0.7958753 -0.5176603 0.4184151 0.7462953 -0.2718711 0.3677983 0.8892753 -0.3124616 0.4584183 0.8319978 -0.5123999 0.7420275 0.4322519 -0.5286629 0.7419466 0.4123479 -0.7954108 0.5085856 0.3296397 -0.7995344 0.4739044 0.3689979 -0.9172546 0.3635497 0.1627139 -0.8776603 0.3897576 0.2789293 -0.9790332 0.2017281 -0.02828603 -0.9666904 0.2398774 0.08926653 -0.9877493 0.09682357 -0.1223785 -0.9881755 0.0983048 -0.1176669 -0.8850826 -0.1657285 -0.4349288 -0.958105 0.0506826 -0.2818977 -0.9524772 0.06070804 -0.298499 -0.9554879 0.04578268 -0.2914563 -0.9184216 0.02380329 -0.3948866 -0.3782549 0.5427861 0.749871 -0.3046322 0.4955118 0.8134294 -0.569617 0.5191844 0.6371688 -0.5051619 0.4810983 0.7164887 -0.7436942 0.4653886 0.4799296 -0.6929397 0.4380618 0.5726575 -0.8796148 0.3807582 0.2851335 -0.8468255 0.3648706 0.3869833 -0.9602324 0.2707687 0.06810516 -0.9350458 0.2607101 0.2402488 -0.9676094 0.1819965 -0.1749554 -0.9749116 0.191009 0.1142944 -0.9876161 0.1501373 -0.04553484 -0.9873167 0.1486258 -0.05582308 -0.9734234 0.1154563 -0.1977801 -0.1717908 0.3684136 0.9136517 -0.2095752 0.5019022 0.8391498 -0.2676032 0.387958 0.8819736 -0.2582177 0.4457592 0.8571012 -0.2544758 0.5222985 0.8139081 -0.4311328 0.824443 0.366631 -0.4164335 0.8200079 0.3926452 -0.2884495 0.6250051 0.7253727 -0.3205579 0.6772673 0.6622324 -0.3454379 0.7115186 0.6118938 -0.344657 0.7140821 0.6093426 -0.3559019 0.7883216 0.5018794 -0.01480376 0.3272235 0.944831 -0.2787651 0.7632408 0.5828839 -0.2237985 0.5738058 0.7878205 -0.1057083 0.4184797 0.9020535 0.02849847 0.3676034 0.929546 -0.0387299 0.3615161 0.9315612 -0.1063934 0.4171559 0.9025861 -0.1233556 0.3303712 0.9357554 0.09009069 0.4276216 0.8994574 0.08990496 0.4233824 0.9014791 0.09695541 0.4140505 0.9050756 -0.03684252 0.5483871 0.8354127 -0.01128649 0.4213545 0.9068259 0.02296668 0.3731641 0.9274811 0.3225671 0.3896207 0.8626392 0.2920911 0.4255906 0.8564785 0.4073022 0.3569271 0.8406593 0.5321038 0.2294291 0.8150017 0.5404547 0.2401306 0.8063784 0.4739189 0.3584187 0.804324 0.4533177 0.2829529 0.8452461 0.4443683 0.3107485 0.8402217 0.6851129 0.1280103 0.7171009 0.6714801 0.1625133 0.7229827 0.7003216 0.1721975 0.6927465 0.6835786 0.2316491 0.692141 0.4239762 0.5736113 0.7008668 0.4009413 0.6090574 0.684321 0.5187622 0.4156304 0.7470858 0.4691284 0.5996529 0.6483325 0.5037015 0.494877 0.708083 0.2765771 0.6807691 0.6782763 0.2553253 0.722618 0.6423646 0.30673 0.6599721 0.6858233 0.1116275 0.8102833 0.5753089 0.1283927 0.7833983 0.6081139 0.1595345 0.7530648 0.6383121 -0.132318 0.8556348 0.5003811 -0.07408124 0.8225103 0.5639049 -0.02076107 0.8322686 0.5539836 0.1136158 0.7577392 0.6425907 -0.2038826 0.6189084 0.758541 -0.2994722 0.7379197 0.6048066 -0.0386967 0.5455345 0.8371946 -0.1437948 0.6971122 0.7023943 0.1181897 0.4673261 0.8761494 0.0101822 0.6291529 0.7772149 0.1346386 0.5160421 0.8459155 -0.3398416 0.846216 0.4103978 -0.2860849 0.8254613 0.4865892 -0.09409379 0.7553868 0.6484884 -0.1726953 0.8246997 0.5385598 0.03841143 0.6633419 0.74733 -0.05778336 0.7998799 0.597372 0.1835996 0.5761134 0.7964827 0.08928143 0.7362644 0.6707784 0.3261536 0.4668644 0.8219863 0.2383604 0.6477493 0.7236056 0.4590758 0.3403888 0.8206004 0.381612 0.5370596 0.7522894 0.5635427 0.2286796 0.7938043 0.5162801 0.4134725 0.749997 0.5995447 0.2518824 0.7596721 0.6459165 0.2922975 0.7052334 0.6278697 0.342593 0.6988633 -0.4180705 0.5757997 0.7026179 -0.08885818 0.402957 0.9108951 -0.1131681 0.4093212 0.9053449 -0.1061542 0.4177131 0.9023565 -0.1032567 0.4223843 0.9005163 0.02642369 0.4086402 0.9123131 0.02066725 0.4196189 0.9074652 0.0803855 0.3190593 0.9443196 0.1030449 0.3570373 0.9283891 0.1528643 0.4674403 0.8707078 -0.005629658 0.3437035 0.9390614 0.03503298 0.3957491 0.9176902 0.2460944 0.6060125 0.7564301 -0.1223873 0.3993386 0.9085979 0.07426828 0.5626532 0.8233503 -4.34343e-4 0.4261103 0.9046712 0.2333321 0.6150178 0.7531994 0.1473529 0.4775754 0.866146 0.09728783 0.7774531 0.6213709 0.2719339 0.8244578 0.4963077 0.3341444 0.8488601 0.4096145 0.04099905 0.8039227 0.5933191 0.06788432 0.796702 0.6005479 -0.1334132 0.780521 0.6107275 -0.1495951 0.7649081 0.6265278 -0.2595226 0.6734097 0.6922192 -0.2456702 0.7337944 0.6333972 -0.3387079 0.6229254 0.7051532 -0.3115904 0.6007396 0.7362224 -0.6832789 0.2737882 0.6768826 -0.6701112 0.2302599 0.7056425 -0.671827 0.2302201 0.7040222 -0.6805508 0.1665794 0.7135138 -0.6728667 0.1600314 0.7222468 -0.6010316 0.439628 0.6674491 -0.603862 0.4916075 0.6274335 -0.5641782 0.4647254 0.6824465 -0.544488 0.3304619 0.7709266 -0.5755483 0.3570687 0.7356943 0.2487703 0.702315 0.6669834 0.190339 0.6864845 0.7017906 0.1807056 0.6796053 0.7109727 0.02962476 0.6270213 0.7784388 0.02244055 0.620822 0.7836304 -0.1954078 0.5017024 0.8426806 -0.1544533 0.5743925 0.8038766 -0.348895 0.3617057 0.8645468 -0.3047251 0.4752412 0.8254021 -0.4302768 0.3323683 0.8392813 -0.4272301 0.3367925 0.8390741 -0.5204206 0.2822053 0.8059297 -0.5463366 0.232604 0.8046191 -0.5335958 0.2162845 0.8176165 -0.5718234 0.2140784 0.7919523 -0.4793472 0.3978498 0.7822671 -0.3510858 0.5179614 0.7800351 -0.3466504 0.5240377 0.7779577 -0.2071331 0.6270784 0.750912 -0.203646 0.6309437 0.7486245 -0.05857479 0.7147372 0.696936 -0.05824768 0.7150681 0.696624 0.0877009 0.777626 0.6225805 0.1586585 0.8240421 0.5438586 0.1223946 0.8516284 0.5096555 0.2467396 0.5544958 0.7947667 0.1857334 0.3747713 0.9083224 0.1894285 0.4062306 0.8939204 0.4759002 0.8054625 0.3531987 0.4616191 0.8016606 0.3798001 0.4407052 0.7944546 0.4178767 0.3857668 0.7638432 0.517424 0.3188961 0.6881485 0.6517338 0.2999325 0.6429331 0.7047535 0.2750883 0.5929276 0.7568113 0.2578606 0.4942281 0.8302087 0.6779683 0.4571627 0.5756399 0.9802698 0.05708181 -0.1892429 0.9645296 0.01996892 -0.2632182 0.9538672 0.03652209 -0.2979992 0.9880265 0.109672 -0.1085162 0.9892675 0.1122444 -0.0935465 0.9847869 0.1360738 -0.1080681 0.955761 0.09185689 -0.2794339 0.9822226 0.08809101 -0.1657674 0.9194597 0.01694726 -0.3928188 0.9980781 0.03149759 -0.05336874 0.9874301 0.1537024 0.03684538 0.9888332 0.1466588 0.02646225 0.9161736 0.3604243 0.1752724 0.9057238 0.3746262 0.1982923 0.785898 0.5411889 0.2991305 0.7383661 0.5727858 0.3559945 0.9919115 0.03503906 -0.1219994 0.9820806 0.07856529 -0.1713046 0.9824188 0.1866894 -5.44048e-4 0.9544976 0.2824114 0.09580206 0.9194043 0.3390648 0.1993259 0.8337476 0.3913772 0.3894727 0.7360627 0.4130925 0.5362523 0.7162683 0.5077705 0.4786741 0.5121228 0.539759 0.6681246 0.4846959 0.6747894 0.5565333 0.8455367 0.336539 0.4144989 0.8750243 0.2924571 0.3857477 0.6967621 0.3649421 0.6175273 0.6984973 0.3633936 0.6164792 0.56792 0.3741304 0.7331394 0.3560535 0.3355849 0.8721289 0.4106952 0.4298444 0.8040917 0.4076507 0.4452818 0.7972109 0.4583187 0.5264209 0.716118 0.4394036 0.605364 0.6636708 0.9662596 0.2373443 0.1000506 0.9359356 0.2535119 0.2444512 0.9555416 0.2779064 0.09853076 0.8766038 0.3397218 0.3408154 0.8582781 0.4240887 0.2889766 0.721081 0.5035696 0.4758782 0.7921438 0.5096069 0.3358705 0.5470109 0.6129177 0.5701851 0.5238277 0.7389206 0.4237934 0.4830192 0.7388257 0.4699246 0.513172 0.7645068 0.3901074 0.9073062 0.08267694 -0.4122622 0.7820164 0.08858138 -0.6169309 0.9224066 0.2797477 -0.2662845 0.9324898 0.2842127 -0.2229039 0.9296065 0.3566576 0.09288299 0.9321258 0.3561415 0.06561231 0.8583112 0.399614 0.3218858 0.8460534 0.3979955 0.3546735 0.6588796 0.4206572 0.6236388 0.6768137 0.4302517 0.5973331 0.5734995 0.3452701 0.742891 0.7034753 0.3386425 0.624855 0.7035945 0.3386641 0.6247091 0.872776 0.3037148 0.3821248 0.8728379 0.3037207 0.3819788 0.965651 0.2401883 0.09913539 0.9656622 0.2401815 0.09904271 0.9699134 0.1565214 -0.1864646 0.9699093 0.1565176 -0.1864898 0.899342 0.06840574 -0.4318619 0.8201014 0.1569877 -0.5502623 0.356003 0.3360128 0.8719847 0.3806755 0.347007 0.8571304 0.374491 0.3688353 0.8507156 0.3270847 0.3355588 0.8834116 -0.3750544 0.3782849 -0.8463066 -0.2852746 0.4920119 -0.8225222 0.5743264 0.7507447 -0.3263919 0.4840316 0.1705896 -0.8582614 0.5914587 0.1232334 -0.7968628 0.6076571 0.05605131 -0.7922192 0.6306583 0.0412895 -0.7749616 0.6049643 -0.05496758 -0.7943531 0.5090898 0.2396178 -0.8266867 0.4700978 0.2938057 -0.8322778 0.4737212 0.3350093 -0.8144673 0.4236147 0.3435932 -0.8381494 0.3956796 0.3794401 -0.8363391 0.3669018 0.3778864 -0.85005 0.3527141 0.4319898 -0.8300468 0.238969 0.403456 -0.8832423 0.3177159 0.4816974 -0.8167156 0.1745443 0.4845752 -0.8571588 0.1764394 0.5197667 -0.8358897 0.05789929 0.528675 -0.8468474 0.05737501 0.5273337 -0.8477189 -0.03592908 0.5435281 -0.8386217 -0.07738006 0.4374268 -0.8959187 -0.06610453 0.5097205 -0.8577969 -0.1819354 0.5359573 -0.8244084 -0.1809664 0.5045169 -0.8442239 -0.2409712 0.482667 -0.842001 -0.2784655 0.4038377 -0.8714196 -0.3502919 0.4286319 -0.8328087 -0.5743262 0.7507449 -0.3263919 -0.3956453 0.3793838 -0.8363808 -0.4505887 0.3075624 -0.8380783 -0.4735727 0.375977 -0.7964738 -0.4696317 0.2045744 -0.8588337 -0.4984273 0.3044255 -0.8117237 -0.5086382 0.2330456 -0.8288407 -0.5411326 0.1895807 -0.8192892 -0.5423066 0.1414062 -0.8281956 -0.6106402 0.04213374 -0.7907865 -0.6390136 0.07921135 -0.7651062 -0.6049664 -0.05496644 -0.7943515 -0.5914587 0.1232334 -0.7968628 -0.5327321 0.1499589 -0.832892 -0.5485274 0.01459634 -0.8360052 -0.5453779 0.009664952 -0.8381347 -0.5833776 -0.07212835 -0.808992 0.6154461 0.1740868 -0.7687131 0.5457515 0.1822463 -0.8178886 0.5374134 0.0205987 -0.8430674 0.5491784 0.0150336 -0.8355699 0.5792723 -0.06557077 -0.8124926 0.351057 -0.07996869 -0.932933 0.6133633 -0.121992 -0.7803227 0.3006824 -0.08218145 -0.9501771 0.2725838 -0.1252872 -0.9539399 0.235647 -0.1180591 -0.9646412 0.2342076 -0.1199131 -0.9647631 0.1460196 -0.1308344 -0.980592 0.08886337 -0.01282787 -0.9959613 0.06481003 -0.1022724 -0.9926429 0.2059182 -0.02769678 -0.9781772 0.2012887 -0.03142279 -0.9790279 0.2679798 -0.02355051 -0.9631367 0.5240549 0.001882076 -0.8516825 0.5077611 -0.01471126 -0.8613724 0.4357228 -0.0795058 -0.8965627 0.4104496 -0.00133115 -0.9118823 0.3825964 -0.04206007 -0.9229577 0.3515548 1.73241e-6 -0.9361674 0.3150174 -0.03142225 -0.9485656 0.2925255 0.002687156 -0.956254 0.2844889 -0.00985372 -0.9586288 -1.65551e-7 0 -1 1.16266e-6 0 -1 2.18092e-6 0 -1 5.0391e-7 0 -1 0 0 -1 -2.6791e-5 0 -1 0 0 -1 8.81032e-7 0 -1 1.91549e-6 0 -1 9.99971e-7 0 -1 -6.64708e-7 0 -1 -8.96966e-7 0 -1 3.96016e-7 0 -1 5.59472e-6 0 -1 -4.05086e-6 0 -1 9.72797e-7 0 -1 -3.26032e-6 0 -1 3.93716e-6 0 -1 -5.30429e-7 0 -1 2.07118e-6 0 -1 -0.6044043 0.6594683 0.4469867 0.2282789 0.7802717 0.5822929 0.3528543 0.661 0.6622484 0.3906393 0.7815225 0.4864397 0.3859545 0.8031043 0.4539413 -0.5432376 0.8271847 0.1437306 -0.7076873 0.706159 0.0227651 -0.7289476 0.5614352 0.3916963 -0.4848607 0.4205687 0.7668326 -0.2663846 0.6835731 0.6795345 -0.357888 0.6609255 0.6596164 -0.2613072 0.4357866 0.8612831 -0.5464924 0.5200895 0.656394 -0.6647822 0.363478 0.6526473 -0.6690608 0.1664404 0.7243309 -0.6932422 0.1884371 0.6956341 -0.6659646 0.2802755 0.6913298 -0.7064156 0.219627 0.6728604 -0.7068442 0.2215551 0.6717773 -0.6792619 0.3637248 0.6374226 -0.7347464 0.3138919 0.6013482 -0.7154741 0.2202959 0.6629981 -0.6134981 0.7605295 0.212638 -0.6220282 0.7648499 0.1675875 -0.5939412 0.7813054 0.1918225 -0.5039868 0.8533593 0.1333243 -0.5702432 0.8103411 0.1347964 -0.4327455 0.8745987 0.2186515 -0.5770217 0.7814264 0.2375265 -0.5759299 0.7718988 0.2692155 -0.5774574 0.767297 0.2789238 -0.5367725 0.7683345 0.3486223 -0.5544912 0.7241373 0.410079 -0.4923599 0.7493321 0.4428127 -0.4335966 0.7672395 0.4725861 0.0565319 0.8654538 0.4977892 0.113884 0.8716493 0.4767157 0.1821403 0.8665858 0.4646008 0.1903173 0.869381 0.4560222 0.574082 0.7731783 0.2694908 0.5450006 0.7603679 0.3532917 0.5933419 0.7813429 0.193517 0.5704401 0.8046237 0.1648609 0.5246109 0.8382916 0.1484953 0.7085684 0.6853153 0.1681486 0.7093437 0.7023862 0.05903595 0.6280062 0.7602368 0.1662775 0.6274622 0.7600771 0.1690387 0.6934815 0.6958304 0.186825 0.6930881 0.6637561 0.2811705 0.4419404 0.8792636 0.1777192 0.53767 0.8129565 0.2236351 0.576022 0.7813752 0.2401072 0.5689271 0.7751206 0.274791 0.6689172 0.6694508 0.3230875 0.6674886 0.6602534 0.344274 0.7227804 0.585197 0.3676045 0.6994661 0.5367859 0.4718137 0.691416 0.3638118 0.6241674 0.6678287 0.1686107 0.7249657 0.7000862 0.1971409 0.6863052 0.7059148 0.2195956 0.673396 0.5977439 0.209614 0.7737986 0.7460082 0.2403029 0.6210688 0.643323 0.3628363 0.6741554 0.6624311 0.4184542 0.6213544 0.664596 0.2851713 0.6906443 0.5516244 0.5199569 0.6521928 0.4902134 0.53845 0.6853923 -0.2771012 0.6896053 0.6690737 -0.1578506 0.6926482 0.703791 -0.1283175 0.7228956 0.6789379 -0.0501914 0.6907131 0.721385 6.99963e-6 0.7385263 0.6742247 0.0745359 0.6656394 0.742542 0.1289526 0.7196814 0.6822243 0.1161634 0.7802709 0.6145595 6.137e-6 0.7802719 0.6254406 6.3279e-6 0.7802705 0.6254423 -0.116151 0.7802695 0.6145639 -0.1161517 0.7802721 0.6145601 -0.228267 0.7802709 0.5822985 -0.2282674 0.7802719 0.5822972 -0.7098428 0.6923769 0.1293735 -0.685601 0.6978306 0.2073252 -0.7032493 0.6852323 0.1894659 -0.6771957 0.6628803 0.3193676 -0.6731153 0.6642332 0.3251312 -0.6705894 0.6600247 0.3386406 -0.6044038 0.6594669 0.4469894 -0.6753506 0.5426304 0.4994534 -0.6786493 0.5192756 0.5194112 -0.6625664 0.538062 0.5210521 -0.714845 0.4183192 0.5603621 -0.3324406 0.7802706 0.5297746 -0.3324404 0.7802703 0.5297752 -0.3995686 0.6594673 0.636748 -0.3995675 0.6594677 0.6367483 -0.4175881 0.618685 0.6654691 -0.464293 0.5532174 0.6916521 0.3121567 0.8657165 0.3912713 0.2819311 0.8477475 0.449265 0.3324517 0.7802719 0.5297659 0.3324519 0.7802724 0.5297649 0.39958 0.6594667 0.6367414 0.3995813 0.6594677 0.6367396 0.4242634 0.6024388 0.6760683 0.2071359 0.3321793 0.9201911 0.5481765 0.7414256 0.3870279 0.5544953 0.7241417 0.4100657 0.6044116 0.6594663 0.4469797 0.6044133 0.6594675 0.4469757 0.6755546 0.5422549 0.4995856 0.6680752 0.5197762 0.532455 0.710211 0.4478653 0.5431547 0.6925721 0.364265 0.6226195 -0.6317054 0.3929092 0.6682595 -0.6132499 0.4309504 0.6619716 -0.5810063 0.5187414 0.6271675 -0.5810071 0.518743 0.6271655 -0.5108733 0.6594665 0.551464 -0.5108742 0.6594684 0.5514609 -0.4353179 0.767909 0.4699088 -0.3894892 0.7815399 0.4873334 -0.3472203 0.8597683 0.3744818 -0.2866455 0.8421288 0.456786 -0.2478123 0.859645 0.4467656 -0.1845985 0.862659 0.4708961 -0.1556072 0.8740989 0.4601495 -0.09168392 0.8696374 0.4851028 -0.03926622 0.8803179 0.4727566 5.17958e-6 0.8727979 0.4880819 0.08891475 0.8779584 0.4704075 0.1161628 0.7802703 0.6145604 0.2282789 0.7802695 0.5822959 0.2797191 0.6423996 0.7134985 0.2408784 0.6929492 0.6795579 0.4511701 0.7632365 0.4625104 0.4410656 0.7607906 0.4760872 0.5108854 0.6594684 0.5514504 0.5108848 0.6594668 0.5514529 0.5810204 0.518744 0.6271524 0.5810191 0.5187422 0.627155 0.6141285 0.4282774 0.6628911 0.5055689 0.4281092 0.7490812 -0.9843033 6.00194e-5 -0.1764856 -0.3232229 8.49869e-5 -0.9463229 -0.3785233 -8.3133e-5 -0.9255919 -0.2386887 -0.00134617 -0.9710952 -0.1908115 -0.004064798 -0.9816183 -0.1758383 -0.004931449 -0.9844068 -0.0875318 3.09552e-6 -0.9961618 -0.6315442 -0.03689134 -0.7744618 -0.4066181 -5.12362e-4 -0.9135982 -0.5391359 -0.002991914 -0.8422135 -0.5951397 0.002931058 -0.8036171 -0.9932942 -0.005215167 -0.1154972 -0.9484797 9.69507e-4 -0.3168365 -0.8422139 -0.002764523 -0.5391366 -0.8728179 -0.00776863 -0.4879842 -0.7955296 -0.001548945 -0.6059129 -0.865208 -0.04083818 -0.4997474 -0.9902344 -0.03671681 -0.1344906 -0.9914774 -0.03042465 -0.1266766 -0.7370296 -0.04665529 -0.6742482 -0.7471259 -0.05458348 -0.6624376 -0.8076285 -0.06276321 -0.5863421 -0.731305 -0.2309781 -0.6417494 -0.7177206 0.2164018 -0.6618515 -0.7693017 -0.004595398 -0.6388694 -0.6373551 0.04099822 -0.7694789 -0.8485612 -0.1074815 -0.5180653 -0.8660919 -0.05320489 -0.4970454 -0.9310557 -0.07910704 -0.3561986 -0.9620552 0.1070859 -0.2509632 -0.9043614 -0.1010299 -0.4146364 -0.9033027 -0.03053838 -0.4279154 -0.9902434 -0.03579545 -0.134673 -0.9941608 -0.01707255 -0.1065498 -0.9896952 0.1298361 0.06038379 -0.9868101 0.1481086 -0.06534314 -0.883495 0.3272607 0.3351672 -0.8565612 0.2188041 0.4673625 -0.6446759 0.7644436 0.0043841 -0.7158097 0.471326 0.5152363 -0.4739715 0.8646964 0.166287 -0.5171132 0.7855437 0.3398754 -0.9902202 0.1294959 0.05191111 -0.9076941 0.3735347 0.1912155 -0.9056082 0.3864924 0.1746353 -0.7428473 0.5979197 0.3011146 -0.7396571 0.6111459 0.2817946 -0.5171109 0.7655768 0.3827381 -0.513001 0.7780491 0.3625874 0.3736565 0.3246381 0.8689022 0.1756845 0.7121008 0.6797408 -0.9937093 0.09494543 0.05939006 -0.4041641 0.775516 0.4850013 -0.6715914 0.6281797 0.3928809 -0.7012715 0.6001482 0.3847604 -0.8964092 0.3816322 0.225405 -0.8852912 0.4037178 0.2308061 -0.985261 0.1390776 0.09959018 -0.9850862 0.1120467 0.1305783 -0.4803407 0.7581081 0.4410727 -0.5275006 0.701107 0.4797835 -0.4072423 0.7558445 0.5126917 -0.2923073 0.7868236 0.5435671 0.1773009 0.7557449 0.6304079 0.09483724 0.7774207 0.6217902 -0.05986809 0.7789558 0.6242147 -0.04973316 0.7715819 0.6341831 -0.1387714 0.8002724 0.5833581 0.601714 0.492311 0.6289438 0.3149201 0.5923064 0.7416189 0.2815834 0.598748 0.7498078 0.2813593 0.5988747 0.7497907 0.2136907 0.6484672 0.7306344 0.7276629 0.2336865 0.644901 0.5827016 0.2490022 0.7736 0.4750797 0.3710446 0.7978881 0.3797336 0.390071 0.8388367 0.2792052 0.4196602 0.8636724 0.2206965 0.4108272 0.8845983 0.01797074 0.4211544 0.9068109 -0.05922347 0.4376189 0.8972081 -0.1547681 0.4162109 0.8959997 -0.2935345 0.4027496 0.8669662 -0.4040889 0.4034756 0.8209261 -0.4440547 0.3834107 0.8098221 -0.6308022 0.322605 0.7057015 -0.7012476 0.3213334 0.6363936 -0.8014814 0.2433174 0.5462822 -0.8868062 0.2081706 0.4126013 -0.9674115 0.05853283 0.2463514 0.1260183 0.6741682 0.7277477 -0.05946695 0.6783438 0.7323343 -0.05928426 0.6784267 0.7322723 -0.4053486 0.6212802 0.6705994 -0.4042948 0.6219274 0.6706357 -0.7019917 0.4842677 0.5221997 -0.7008858 0.4854919 0.5225483 -0.887256 0.3139741 0.3379307 -0.8865929 0.3151829 0.3385452 -0.987815 0.1060518 0.1139065 -0.981269 0.07002103 0.1794672 -0.9834404 0.1071359 0.1461745 -0.8603621 0.1496119 0.4872304 -0.8051781 0.1856436 0.5632271 -0.145496 0.3001993 0.9427149 -0.1572901 0.3010783 0.9405381 -0.2978342 0.2988188 0.9066433 -0.5571359 0.2599061 0.7887005 -0.4508658 0.2567513 0.8548677 -0.6364135 0.2415359 0.732556 0.7295354 0.1787927 0.6601602 0.583649 0.2012963 0.7866598 0.6691837 0.2393537 0.7034935 0.3850455 0.2863301 0.8773568 0.2936683 0.2891397 0.9111297 0.2241032 0.3028363 0.9263196 0.01824921 0.31426 0.9491616 0.8010645 0.3808073 0.4618241 0.7291138 0.6301818 0.2669534 0.7056858 0.688115 0.1688351 0.5290951 0.8259704 0.194503 0.5026246 0.8405962 0.2019073 0.2940464 0.9358673 0.194137 -0.3360466 0.9198081 0.2025488 -0.2267156 0.9515489 0.2077377 -0.1456838 0.9688442 0.200293 -0.02334815 0.9757896 0.2174615 0.1956999 0.9571605 0.2134138 -0.4374334 0.8782414 0.1932469 -0.5571178 0.8140575 0.1641039 -0.5420939 0.8241935 0.1638275 -0.6385441 0.7523388 0.1620115 -0.8609571 0.4973784 0.1066195 -0.814624 0.5707405 0.1031661 -0.9843397 0.1572979 0.07957828 -0.9715318 0.2331957 0.0417838 -0.9852549 0.1634391 0.05060112 -0.984374 0.1676048 0.05400431 -0.9900277 0.1142435 0.08242332 -0.9859442 0.1185783 0.1177002 -0.9668865 0.09237784 0.2379012 -0.9878742 0.04872196 0.1474138 -0.9880231 0.07068127 0.1371662 -0.9924059 0.05990803 0.1074317 -0.8600504 0.2484971 0.4456035 -0.8600457 0.2485041 0.4456087 -0.5558991 0.4048646 0.7259897 -0.5558995 0.4048641 0.7259896 -0.1451562 0.4818963 0.8641213 -0.1451691 0.4818953 0.8641198 0.2930567 0.4656713 0.8350259 0.2930539 0.4656712 0.8350269 0.7325426 0.3315498 0.5945218 0.5323932 0.3054546 0.789465 -0.9928622 0.07978689 0.0886501 -0.8600493 0.3413153 0.379235 -0.8600511 0.3413155 0.3792306 -0.5559035 0.5560787 0.6178575 -0.5559 0.5560805 0.617859 -0.1451696 0.6618815 0.7354174 -0.1451538 0.6618848 0.7354175 0.2930668 0.6395971 0.7106528 0.2930489 0.6395987 0.7106588 0.5824974 0.5437599 0.6041706 0.6520007 0.3828846 0.6544421 -0.9916085 0.1056725 0.07447135 -0.8600546 0.417049 0.2938987 -0.8600478 0.4170589 0.2939043 -0.5559089 0.6794787 0.4788258 -0.555904 0.6794781 0.4788323 -0.1451652 0.8087669 0.5699328 -0.1451663 0.8087643 0.5699362 0.2930891 0.7815267 0.5507403 0.2930671 0.7815265 0.5507524 -0.9929962 0.1092844 0.04489511 -0.8600452 0.4719505 0.1938689 -0.8600544 0.4719348 0.193866 -0.5558972 0.7689048 0.3158538 -0.5559114 0.7688931 0.3158577 -0.1451753 0.9151958 0.3759531 -0.1451622 0.9151964 0.3759567 0.2930746 0.8843786 0.3632931 0.2930935 0.884375 0.3632864 0.680981 0.677377 0.2782543 0.5390779 0.6884773 0.4851742 0.819998 0.4846744 0.304457 0.5187658 0.6421306 0.5644028 0.998874 0.04650628 0.00937587 0.9638952 0.09329986 0.249402 0.4668915 0.2767782 0.8398846 -0.216372 0.2886281 0.932672 -0.3775583 0.2870665 0.8803651 -0.5998393 0.2547608 0.7584786 0.6711934 0.2321152 0.7040042 0.9997928 0.00595498 0.01946866 0.991812 0.03487646 0.1228525 0.9843652 0.07353252 0.1600564 0.9929935 0.05755507 0.1032056 0.9843362 0.09769093 0.1467614 0.9916064 0.08649134 0.09610468 0.990027 0.09540355 0.1036571 0.9859429 0.1309425 0.103782 0.992863 0.09748566 0.06869989 0.9834459 0.1578307 0.08901482 0.9924079 0.1137647 0.04673618 0.9880251 0.144574 0.05389612 0.9879521 0.1421396 0.06121242 0.9487834 0.3113757 0.05343431 0.3880231 0.9090555 0.1518431 0.4672058 0.8692507 0.1616234 0.6205264 0.7666126 0.1650823 0.001406729 0.9835431 0.1806686 -0.693821 0.588666 0.4148311 -0.5684351 0.7411892 0.3570998 -0.7605795 0.6005497 0.2466959 -0.5206193 0.818434 0.2431492 -0.6152349 0.2485954 0.7481219 -0.6352422 0.3573764 0.6846528 -0.7400001 0.3275968 0.5874353 -0.526194 0.5086936 0.6814329 -0.7631509 0.4323 0.4803305 -0.552756 0.5986453 0.5797281 -0.714116 0.574114 0.4005392 -0.2930467 0.8843886 0.3632911 -0.2930653 0.8843809 0.3632948 -0.2930604 0.7815313 0.550749 -0.2930613 0.7815341 0.5507446 -0.2930561 0.6395972 0.7106571 -0.2930466 0.6395962 0.7106619 -0.2930489 0.4656746 0.8350268 -0.293042 0.4656726 0.8350301 -0.2938206 0.2957678 0.9089505 0.02750784 0.3149595 0.9487065 0.2669052 0.3016654 0.9152922 0.1454989 0.2994027 0.9429677 0.1451804 0.4818966 0.8641172 0.1451767 0.4818974 0.8641173 0.145188 0.6618794 0.7354156 0.1451711 0.6618799 0.7354186 0.145172 0.808766 0.5699323 0.1451647 0.8087617 0.5699403 0.1451671 0.9151985 0.3759499 0.1451786 0.9151957 0.3759523 0.1458312 0.9656277 0.215166 -0.2942785 0.932809 0.2080086 -0.2266443 0.9544312 0.1941481 -0.62403 0.7582027 0.1889854 -0.5677869 0.8091691 0.151207 0.214308 0.9538829 0.2101893 0.5575945 0.8107508 0.1782457 0.5559013 0.7689004 0.3158575 0.5559119 0.7688947 0.3158527 0.5559099 0.6794773 0.4788263 0.5559107 0.6794765 0.4788269 0.5559034 0.5560787 0.6178575 0.555904 0.5560789 0.6178568 0.555898 0.4048668 0.7259892 0.5559006 0.404861 0.7259905 0.5567166 0.2497868 0.7922583 0.5891363 0.2461413 0.7696318 0.7855035 0.6050491 0.1299989 0.8605016 0.5007201 0.0938965 0.8600513 0.4719391 0.1938695 0.8600468 0.471948 0.1938678 0.8600482 0.417059 0.2939028 0.8600503 0.4170572 0.2938993 0.8600504 0.341313 0.3792343 0.8600474 0.3413174 0.3792375 0.8600471 0.2485023 0.445607 0.8600473 0.248502 0.4456067 0.8607679 0.1593102 0.4834244 0.810858 0.1668209 0.5609637 -0.2008777 0.7286029 0.6548175 -0.5445556 0.4401446 0.7139552 0.9997775 0.01029425 0.01841413 0.9671737 0.2269155 0.1143868 0.9605648 0.1489336 0.2348064 0.5846988 0.3214383 0.7448522 0.6663435 0.3039513 0.6808817 0.7024102 0.3066081 0.6423484 0.808399 0.2195101 0.5461744 0.8874682 0.1991232 0.4156323 0.9907689 -0.05635201 0.1232951 0.9757462 0.1659104 0.1428053 0.4629195 0.3512174 0.81385 0.4052111 0.3836457 0.8298314 0.264509 0.3757252 0.8881812 0.05934005 0.4076723 0.9111982 0.0272181 0.3955579 0.9180377 -0.2138771 0.3865334 0.8971335 -0.2800686 0.3990503 0.8731096 -0.3739901 0.3672496 0.8516215 -0.4983025 0.3433282 0.7961284 -0.5991097 0.2699838 0.7537747 0.05981719 0.8004378 0.5964237 0.0352658 0.8056071 0.5913997 -0.1490096 0.7650232 0.6265268 0.4641783 0.7692869 0.4390174 0.8869608 0.3886399 0.2495189 0.7226903 0.5941196 0.3531866 0.7004774 0.6085807 0.3727748 0.4951539 0.7366845 0.4605634 0.4058173 0.7574359 0.5114717 0.3719166 0.7697879 0.5187529 0.2663356 0.7920023 0.5493612 -0.3460627 0.6040063 0.7179256 -0.279862 0.6091919 0.741999 -0.0941717 0.6632704 0.7424312 0.05896103 0.6650779 0.7444428 0.05932259 0.6651508 0.744349 0.4025591 0.6099564 0.6825683 0.4043443 0.6099144 0.6815499 0.6990212 0.4768813 0.532873 0.7010582 0.4763239 0.530691 0.8855968 0.3102308 0.3456522 0.886746 0.3092988 0.3435345 0.9908471 0.09031969 0.1003218 0.9764919 0.1890862 0.1034894 0.8780768 0.04468184 0.4764293 0.9899591 0.1281875 0.05957478 0.9001802 0.4315073 0.05896741 0.7300301 0.5173543 0.4465429 0.6731706 0.4379391 0.5958615 0.5077306 0.8420261 0.1822136 0.4663902 0.8097777 0.3560059 0.9896394 0.1331162 0.05379593 0.9057661 0.377113 0.1933227 0.9077756 0.3825076 0.1721381 0.7397699 0.6007629 0.3030257 0.7429676 0.6079478 0.2799977 0.5131361 0.7674459 0.3843414 0.5173479 0.776206 0.3603545 0.8414955 0.01492637 -0.5400581 0.7632023 -0.04460465 -0.6446182 0.9971776 -0.01187145 -0.07413512 0.9901168 -0.04484719 -0.1328817 0.9850211 -0.0385884 -0.168061 0.9761778 -0.03264158 -0.2145029 0.8696187 -0.05254942 -0.4909195 0.8653441 -0.05235505 -0.4984361 0.9056571 -0.06838023 -0.418461 0.9044375 -0.06754529 -0.4212252 0.9449616 -0.04337787 -0.3242928 0.9622804 -0.03682941 -0.2695555 0.6952887 0.03823989 -0.7177127 0.7373936 -0.001621365 -0.6754614 0.7367547 -0.0565474 -0.6737914 0.8103897 -0.06235873 -0.5825634 0.7367734 -0.257689 -0.625109 0.9036134 -0.03748053 -0.426706 0.9430372 -0.09938764 -0.3174949 0.9902371 -0.01687604 -0.1383684 0.9958209 -0.02405285 -0.08810389 0.9969567 0 -0.07795733 0.9910995 -9.05075e-4 -0.1331201 0.9645214 6.45287e-4 -0.2640039 0.8889554 -0.001758575 -0.4579907 0.9048262 -6.60261e-4 -0.4257809 0.7654846 4.7223e-4 -0.6434541 0.4057841 -7.03345e-5 -0.913969 0.4581099 -7.68844e-4 -0.8888953 0.4644533 -8.57417e-4 -0.8855972 0.5298674 2.06024e-4 -0.8480805 0.6434541 -2.09914e-4 -0.7654848 0.6834566 5.17005e-4 -0.729991 0.8012503 -7.88594e-4 -0.5983289 0.2486953 -5.80408e-4 -0.9685817 0.3028446 2.24795e-6 -0.9530401 0.3515572 -3.02381e-7 -0.9361664 0.1331211 0 -0.9910998 0.0499615 -0.002830564 -0.9987472 0.3052845 0.003181934 -0.9522559 0.1117631 -0.003486633 -0.9937288 0.1824834 -0.001480162 -0.9832079 -0.5405414 0.6623423 0.5187656 -0.6078442 0.7017266 0.3716253 -0.5144174 0.5527299 0.6556405 -0.4366188 0.5901935 0.6789962 -0.4754071 0.6595025 0.5822753 -0.4876974 0.5832468 0.6495956 -0.5441987 0.6586093 0.5196938 -0.5386849 0.6190953 0.5714365 -0.6587604 0.704427 0.2642298 -0.4781446 0.6993535 0.5313026 -0.5142857 0.7616543 0.3941994 -0.501276 0.8363596 0.2218673 -0.5429033 0.8207395 0.1778845 -0.5135642 0.759864 0.398571 -0.5918114 0.8032976 0.0668767 -0.592779 0.7219616 0.3569099 -0.4967381 0.5474531 0.6734586 -0.6095629 0.648728 0.4556152 -0.627671 0.6593992 0.4137898 -0.4583873 0.6303521 0.626528 -0.4887342 0.6969383 0.5248009 -0.5278439 0.7691488 0.3602651 -0.5755575 0.736846 0.3546711 -0.5603663 0.6883062 0.460678 -0.5946589 0.6912847 0.4104951 -0.6468835 0.7409994 0.1801717 -0.6693539 0.687397 0.28187 -0.6854622 0.7004474 0.1987838 0.429908 0.6514914 0.6250906 0.6837831 0.729581 0.01234143 0.6670627 0.7312036 0.1427193 0.6333723 0.6827127 -0.364339 0.5657764 0.6113386 0.5533193 0.6961857 0.6897087 0.1990665 0.6251023 0.6342362 0.4549632 0.5705369 0.8123704 0.1205906 0.5311855 0.8378269 0.1260488 0.523234 0.8254993 0.2116063 0.4977537 0.7423753 0.4484643 0.5214703 0.8203895 0.2345845 0.5668508 0.7913053 0.229164 0.5666034 0.788423 0.2394781 0.6099638 0.7892489 0.07092529 0.4352896 0.6077324 0.6642172 0.4704068 0.5851838 0.660513 0.534084 0.6801608 0.5021311 0.5129138 0.6100552 0.6039472 0.5626276 0.6531046 0.5068576 0.5005117 0.5583533 0.6616114 0.482148 0.5435763 0.6870648 0.549741 0.5628197 0.6172674 0.5080329 0.5456565 0.6664544 0.4302731 0.5985835 0.6756944 0.4879785 0.7192209 0.4945689 0.5342466 0.6895031 0.4890461 0.5437515 0.7454291 0.3855773 0.5842907 0.7165246 0.3810471 0.5880141 0.7450801 0.3147936 0.6151735 0.7234774 0.3132764 0.5429683 0.633071 0.5517306 0.548003 0.6404809 0.5380306 1 7.13882e-7 0 1 -1.91405e-5 0 1 8.35654e-7 0 1 1.34908e-5 0 1 -1.08204e-4 0 -1.05329e-6 0 1 3.35181e-7 0 1 -3.71555e-7 0 1 9.20526e-7 0 1 -3.68002e-7 0 1 2.2977e-7 0 1 -3.44379e-7 0 1 4.97548e-7 0 1 -1 -4.56099e-5 0 -1 -1.80459e-6 0 -1 7.84177e-6 0 -1 5.19041e-6 0 -1 1.23108e-5 0 -1 -5.65185e-5 0 0.4813192 0.5748205 0.6617501 0.5970726 0.6639902 0.4501349 -0.148162 0.9665651 0.2092841 -0.9752525 0.2209835 0.007012188 -0.9496729 0.2934969 0.1094579 -0.848079 0.4666132 0.2510659 -0.8070242 0.5758005 0.131018 -0.6475653 0.7025767 0.2950344 -0.6843677 0.7281469 -0.03798902 -0.5079637 0.8177437 0.270681 0.201346 0.9137774 0.3528041 -0.02556312 0.9791732 0.2014116 -0.1666913 0.8773813 0.4499067 0.1605423 0.9559994 0.2455434 0.4563241 0.8630509 0.2165911 0.5048174 0.8629041 0.02357685 0.6473107 0.7205392 0.2486206 0.7018419 0.6836765 0.2000111 0.3190703 0.553865 0.7690435 0.3171198 0.6728188 0.6683935 0.4507185 0.5648676 0.6912145 -0.03056341 0.70758 0.705972 0.1130548 0.7294498 0.6746271 0.1036451 0.6260309 0.7728797 0.2053393 0.707485 0.6762402 -0.3136156 0.9049476 0.2876024 -0.3893629 0.8540983 0.3448371 -0.3846953 0.8696651 0.3093417 -0.4889342 0.8186078 0.3013715 -0.575657 0.7277852 0.372757 -0.5907906 0.7192039 0.3656667 -0.5981227 0.703022 0.3847199 -0.7310276 0.5274112 0.432939 0.5117434 0.6048359 0.6101576 0.5618147 0.6760477 0.4767849 0.4246388 0.7740297 0.4696381 0.4216765 0.779928 0.4624949 0.2001998 0.8488889 0.4891909 0.1801616 0.8658937 0.4666584 -0.01145654 0.8553213 0.5179712 -0.04504513 0.8666516 0.4968764 -0.1717439 0.814068 0.554795 -0.2245339 0.8112407 0.5398825 -0.2264453 0.8077878 0.5442439 -0.3759353 0.7374622 0.5610903 -0.988898 0.1023036 0.1077716 -0.9999619 0.004819333 0.007291197 0.2270509 0.8424919 0.4885238 -0.5661383 0.8047693 0.1784206 -0.09193766 0.929378 0.3574969 -0.2215954 0.9694405 0.1052656 -0.3485397 0.8760969 0.3331286 -0.6144772 0.7783959 -0.1285213 0.4199583 0.8510366 0.3152329 0.3537395 0.892294 0.2804991 0.2078003 0.9400848 0.2702957 0.2052279 0.945517 0.2527434 -0.008238196 0.966572 0.2562632 0.6793838 0.5555055 0.4794281 0.9340471 0.352378 0.05818754 0.8157235 0.4268851 0.3903389 0.9727926 0.2292554 0.03341579 0.2869183 0.7901507 0.5416088 0.4052168 0.7036791 0.5836397 0.5871459 0.7125584 0.3840838 0.6444144 0.6816599 0.346511 0.7372274 0.637737 0.2231308 0.8186764 0.5352747 0.2079666 0.9604046 0.2481777 -0.1266135 0.9559426 0.2707303 0.1134851 0.9889323 0.08828902 0.1192399 0.687531 0.6232406 0.3726557 0.6639844 0.7475151 -0.01860064 0.5013478 0.8091329 0.3065198 0.4250637 0.8435013 0.3283694 0.2350968 0.7871305 0.5702239 -0.4629597 0.6071862 0.6457502 -0.3855087 0.5546339 0.7374039 -0.3068425 0.6701045 0.6758756 -0.2140154 0.619874 0.7549529 -0.1622182 0.705266 0.6901342 -0.06102591 0.6901681 0.7210714 -0.01734948 0.7347754 0.6780887 0.03949373 0.7131532 0.6998949 0.2125968 0.7943601 0.5690298 0.08013486 0.8631061 0.4986246 0.08722609 0.8408259 0.5342317 -0.1313875 0.8754088 0.4651845 -0.1148519 0.8591629 0.4986463 -0.3470995 0.8157614 0.4626612 -0.335464 0.812535 0.4767084 -0.5306612 0.7055484 0.469681 -0.5524325 0.7050748 0.444621 0.9999638 0.004825234 0.00701797 0.9889053 0.1024644 0.1075522 -0.9659241 0.001230776 -0.258823 -0.9205417 0.0740056 -0.3835707 -0.9779393 0.003341972 -0.2088627 -0.1638092 0.1261483 -0.9783932 -0.2587715 0.01888799 -0.965754 -0.3270462 0.03321117 -0.9444246 -0.4413641 -7.49538e-4 -0.8973278 -0.7071101 0.002748548 -0.7070983 -0.6392033 0.08290523 -0.7645561 -0.7874608 -6.81462e-4 -0.6163645 0.4140017 -0.001095056 -0.9102755 0.2924611 0.05214208 -0.9548549 0.2581171 0.07372456 -0.9632967 0.1203632 2.26914e-4 -0.99273 -0.01631611 -3.06947e-5 -0.9998669 0.578737 9.92423e-4 -0.8155137 0.7063512 0.04606473 -0.7063612 0.7685934 -6.91561e-4 -0.6397373 0.8864185 1.64127e-4 -0.4628848 0.9657737 0.01770597 -0.2587813 0.973703 0.003663718 -0.2277918 0.707108 0 0.7071056 0.7071045 0 0.7071092 0.2588217 0 0.9659252 0.2588195 0 0.9659258 -0.2588172 0 0.9659264 -0.2588217 0 0.9659252 -0.7071068 0 0.7071068 -0.707108 0 0.7071056 -0.9238791 0 0.3826846 -0.9656507 0.02384507 0.2587475 -0.9914448 0 0.1305266 -0.9999288 0 -0.01193898 -0.9999288 0 -0.01193767 0.9999288 0 -0.01193767 0.9999288 0 -0.01193898 0.997859 0 0.06540167 0.9657711 0.01786053 0.2587804 0.9801632 0.03562706 0.194964 0.9238791 0 0.3826846 -0.001239657 4.72631e-5 0.9999992 0.02730447 0.04014927 0.9988206 0.007757306 0.05166488 0.9986344 -0.02292513 0.02245515 0.9994851 -0.01850324 0.01909083 0.9996466 -0.04270011 0.007640838 0.9990587 -0.02505576 -0.005821585 0.9996691 -0.001376271 -0.01509749 0.9998851 -0.01466101 0.002692461 0.9998889 -0.002115666 -0.006241083 0.9999784 -0.004317283 -6.81179e-5 0.9999908 -0.00176835 -0.001403093 0.9999976 -0.002296864 5.27902e-4 0.9999973 -0.001267015 -0.001049339 0.9999988 -0.001196444 -6.49534e-5 0.9999994 -6.42551e-4 -5.02571e-4 0.9999998 -5.8003e-4 -3.325e-4 0.9999999 -5.86523e-4 -6.7403e-5 0.9999998 2.98728e-4 2.89091e-4 1 6.53053e-5 -1.25119e-5 1 -1.9897e-6 0 1 1.3901e-6 0 1 -1.53854e-6 0 1 2.88608e-7 0 1 4.03326e-6 0 1 4.71077e-4 1.03031e-4 0.9999999 -1.1621e-4 5.78508e-5 1 1.34017e-4 -1.57269e-4 1 1.74645e-4 -1.69471e-4 1 -5.04469e-4 2.17977e-4 0.9999999 1.96978e-4 0 1 -1.86069e-4 1.66541e-6 1 5.87873e-4 -6.83383e-5 0.9999999 1 0 2.4741e-6 1 -9.43902e-7 0 1 2.95665e-6 -8.99474e-5 1 -1.49429e-7 4.22121e-6 0.9775734 0.1215432 0.1719812 0.1896762 0.0173875 0.9816927 0.1731886 0.002098083 0.9848865 0.5573314 0.06465631 0.8277689 0.5366209 0.03046864 0.8432733 0.8370261 0.07688945 0.5417337 0.8402851 0.08830922 0.5349043 0.9709726 0.03578549 0.236499 0.9760146 0.1392437 0.167352 -0.8576634 0.3679271 0.3592256 -0.9775729 0.1215444 0.1719828 -0.9804677 0.03571885 0.1934096 -0.9045219 0.06570345 0.4213351 -0.9037514 0.06459796 0.4231557 -0.7922829 0.05180662 0.6079506 -0.09808987 0.008991479 0.995137 -0.1730161 0.04524213 0.9838794 -0.268036 0.02426803 0.9631032 -0.4219343 0.03652936 0.9058902 -0.4758633 0.01822823 0.8793303 -0.6071879 0.07134908 0.7913484 -0.6454953 0.05584239 0.7617202 -0.7946515 0.05580049 0.6044959 -0.9999991 0.001445055 0 -0.671562 0.7409054 0.007984995 -0.6301482 0.7753427 0.04191792 -0.8370341 0.5453848 -0.0439254 -0.7325617 0.6795392 0.03975021 -0.8091505 0.587593 0.003174602 -0.9248428 0.3803299 -0.00387752 -0.901608 0.4323626 0.01286739 -0.9905132 0.1357839 -0.02112621 -0.9674401 0.2520867 0.0226323 -0.9960423 0.08888059 1.92682e-4 0.3244303 0.9459097 0 0.3274402 0.9448704 0.001649439 0.07644122 0.9970729 -0.001606643 0.07961171 0.9968261 0 -0.1106179 0.9938631 0 -0.1923207 0.9811077 -0.02099168 -0.3536655 0.9347359 0.03448927 -0.4057214 0.9139291 0.01112318 -0.5080733 0.8613129 -0.001317799 -1.5817e-4 4.61252e-4 0.9999999 3.26883e-5 1.08553e-4 1 -3.17757e-7 0 -1 1.18587e-6 0 -1 -2.17041e-7 0 -1 -0.888096 -0.451476 -0.08634322 -0.9287757 -0.366438 -0.05566734 -0.9392673 -0.3399245 -0.04720723 -0.9659261 -0.2588183 0 -0.7071089 -0.7071048 0 -0.7071088 -0.7071049 0 -0.2588146 -0.965927 0 0.2588146 -0.965927 0 0.7071089 -0.7071048 0 0.7071088 -0.7071049 0 0.9330232 -0.3374731 -0.1248187 0.8914197 -0.4531788 0 0.9657724 -0.2587773 -0.01783192 0.9353713 -0.3501332 -0.04987215 0.9657796 0.2587793 -0.01741123 0.9986245 0.05243366 0 0.9877045 -0.1563329 0 0.7069969 0.7070035 -0.01736181 0.7430122 0.6692779 -2.7142e-5 0.9509963 0.3092026 3.10191e-5 0.2587365 0.965595 -0.02611398 0.3582857 0.9336121 0 0.544577 0.8387109 0 -0.2587363 0.9655945 -0.02612954 -0.1046185 0.9945125 0 0.10445 0.9945302 0 -0.7069964 0.707003 -0.01740545 -0.5447034 0.8386289 0 -0.3584564 0.9335465 0 -0.9876765 -0.1565095 0 -0.9986335 0.05226159 0 -0.9657804 0.2587791 -0.01736801 -0.9511058 0.3088653 -2.71417e-5 -0.7432571 0.669006 3.1019e-5 -0.7429518 -0.2733067 -0.6110042 -0.9991253 -0.04145371 -0.00549966 0.8223339 -0.3188108 -0.4713031 0.2677257 -0.09684133 -0.9586161 0.5041709 -0.2403515 -0.8294835 0.3962319 -0.1421263 -0.9070835 0.9430626 -0.2061642 -0.2610158 0.9912298 -0.1316862 0.01105326 0.9932752 -0.1041975 0.05047249 0.999967 0.002445816 -0.007751464 0.9966497 -0.0808354 0.01245737 0.9211015 -0.02576678 0.3884692 0.8573181 0.1062269 0.5037079 0.8427491 0.2740043 0.4633526 0.8602825 0.2654998 0.4352288 0.6904075 0.4852974 0.5364924 0.6825741 0.614825 0.3950732 0.566778 0.6530793 0.5022453 -1.58465e-4 0.9107563 0.4129445 0.05595481 0.8596932 0.5077368 0.3556959 0.7993139 0.4843326 0.3381717 0.8500476 0.4038059 0.4748677 0.7219794 0.503236 -0.4663419 0.8261083 0.3163391 -0.2416478 0.8300069 0.5026877 -0.1297459 0.8544937 0.5029976 -0.7625814 0.3720146 0.5292211 -0.6609353 0.6074548 0.4406396 -0.6599971 0.5940741 0.4598695 -0.3436225 0.7714182 0.5355722 -0.9306958 0.2198591 0.2923482 -0.8429751 0.2737494 0.4630922 -0.8549224 0.1704127 0.4899666 -0.9943872 -0.05234175 0.0919485 -0.9253092 -0.03820943 0.3772838 -0.8661274 0.0913102 0.4914122 -0.9312391 -0.3587391 -0.06403177 -0.9202005 -0.2033252 -0.3344994 -0.9229149 -0.2530013 -0.2902043 -0.9104708 -0.3900284 -0.137553 -0.6332676 -0.08646708 -0.7690875 -0.4273038 -0.06641972 -0.9016652 -0.3836162 -0.1310406 -0.9141482 -0.3538254 -0.06907278 -0.9327575 -0.2025926 0.3119133 -0.9282599 -0.2814005 0.2532904 -0.9255582 -0.2813931 0.2532827 -0.9255625 -0.3600934 0.1169379 -0.9255584 -0.3600973 0.1169393 -0.9255568 -0.3713841 0.01943492 -0.9282759 -0.4005955 -0.04216629 -0.9152843 -0.3708341 -0.05876338 -0.9268382 -0.349492 -0.1264814 -0.9283631 -0.149201 0.3885733 -0.909258 -0.1540508 0.3458474 -0.9255583 -0.03905171 0.371223 -0.9277222 -7.49991e-5 0.4115672 -0.9113794 0.038984 0.3711997 -0.9277344 0.1345238 0.3505345 -0.9268382 0.1637723 0.3680132 -0.9152841 0.2025376 0.3119355 -0.9282644 0.2813013 0.2533833 -0.9255628 0.2813161 0.2533994 -0.925554 0.3600547 0.1170659 -0.9255572 0.360055 0.117066 -0.9255572 0.3739867 -0.112438 -0.9205931 0.3626376 -0.08550667 -0.9279992 0.3765453 -0.03950053 -0.9255558 0.4111163 -0.06507158 -0.9092575 0.3714557 0.01950359 -0.9282459 -0.443529 -0.1845363 -0.8770567 -0.6535567 -0.2736379 -0.7056813 -0.7111528 -0.0748558 -0.699041 -0.7111491 -0.07485663 -0.6990448 -0.6801211 0.2208644 -0.6990381 -0.6801269 0.2208666 -0.6990318 -0.5314912 0.4783976 -0.6990371 -0.5314891 0.4783984 -0.6990382 -0.2909617 0.6532142 -0.699037 -0.2909662 0.6532129 -0.6990363 -1.30864e-4 0.7150741 -0.6990487 -1.29618e-4 0.7150865 -0.6990361 0.2907314 0.653305 -0.6990479 0.2907373 0.6533259 -0.6990259 0.5313094 0.4785859 -0.6990464 0.5313212 0.4785866 -0.699037 0.6800365 0.2211033 -0.6990449 0.6800477 0.2211048 -0.6990335 0.7111788 -0.07460427 -0.6990415 0.7111889 -0.07460516 -0.6990311 0.686438 -0.1737284 -0.7061313 0.7073866 -0.2732349 -0.6518796 -0.8181554 -0.3365356 -0.4662247 -0.9203594 -0.2228304 -0.3213801 -0.943583 -0.09932243 -0.3158897 -0.9435835 -0.09932345 -0.3158879 -0.9024029 0.2930487 -0.3158981 -0.9024055 0.2930513 -0.3158881 -0.7051968 0.6347528 -0.31589 -0.7052016 0.6347494 -0.315886 -0.3860601 0.8666952 -0.3159069 -0.3860509 0.8667062 -0.3158878 -1.71931e-4 0.9488023 -0.3158707 -1.76759e-4 0.9487857 -0.3159207 0.3857491 0.8668335 -0.3159071 0.3857583 0.8668312 -0.3159025 0.704976 0.6350072 -0.3158717 0.7049634 0.6350039 -0.3159061 0.9023005 0.2933662 -0.3158957 0.902303 0.2933693 -0.3158858 0.9436179 -0.09898775 -0.3158904 0.9436178 -0.09898781 -0.3158907 0.8859269 -0.3339034 -0.3219349 0.9338352 -0.352248 -0.06223624 0.9319709 -0.3590272 -0.05029773 -0.9915657 -0.1291838 0.01044225 -0.9953498 -0.09566795 0.01124364 -0.9944325 -0.1046758 0.0121203 -0.9894868 -0.06981074 0.1266589 -0.9435456 0.3064115 0.1258322 -0.9435482 0.3064084 0.1258205 -0.7373529 0.6636881 0.1258127 -0.7373458 0.6636961 0.1258128 -0.4036493 0.9062144 0.1258687 -0.4036676 0.9062141 0.1258111 -1.84872e-4 0.992054 0.1258132 -1.72638e-4 0.9920493 0.1258494 0.4033446 0.9063501 0.1258679 0.4033342 0.9063651 0.1257931 0.7371088 0.663959 0.1258141 0.7371144 0.6639531 0.1258116 0.9434388 0.3067444 0.125822 0.9434375 0.3067415 0.1258387 0.9906339 -0.04999196 0.1270644 0.9825063 -0.04907274 0.1796479 0.8011916 0.2472603 0.5449352 0.2985905 0.4508635 0.8411694 0.3438332 0.4099625 0.8448134 0.3886644 0.4343509 0.8125757 0.2322703 0.5250676 0.8187518 0.2463623 0.5046094 0.8274509 0.1368411 0.4257986 0.8944104 0.05460095 0.4302926 0.9010366 0.1165109 0.1995122 0.9729441 -0.227411 0.4657586 0.8551919 -0.06370997 0.4283552 0.9013617 -0.1593634 0.261347 0.9519985 0.1863844 0.2701212 0.944614 -0.5906425 0.4684704 0.6570213 -0.4833903 0.4442793 0.7542876 -0.3608988 0.4033082 0.8408892 -0.3176668 0.4337924 0.843156 -0.167304 0.5589579 0.8121425 -0.7510454 0.1774187 0.6359666 -0.702047 0.2358245 0.6719501 -0.6788253 0.331153 0.6553884 -0.6975669 0.3295983 0.6362118 -0.6525903 0.3506498 0.6716924 -0.4432524 0.5038407 0.7413986 -0.4301303 0.5115785 0.7438249 -0.3297117 0.5840663 0.7417255 -0.2842766 0.5822242 0.7617099 -0.1873375 0.6434552 0.7422063 -0.1001834 0.6597892 0.7447426 0.2489246 0.6257163 0.7392671 0.2834095 0.5804867 0.7633572 0.3650264 0.5549775 0.7474997 0.4186395 0.5225204 0.7427742 0.4447556 0.5124793 0.7345457 0.5012975 0.4553119 0.7357934 0.6094812 0.428411 0.6670807 0.6229692 0.3691413 0.6896696 0.6854633 0.2724302 0.6752199 0.04361939 0.6701893 0.7409073 -1.48169e-5 0.6472098 0.762312 -8.76625e-6 0.4411453 0.8974357 0 0.4411562 0.8974305 0 0.2420423 0.9702658 -0.07294034 0.1853439 0.979963 0.0924068 0.07373279 0.9929876 -0.5868427 0.4655966 0.6624466 0.1685814 0.08248329 0.9822306 0.1863077 0.1269192 0.9742592 0.8450116 0.5171194 0.1361731 0.8543889 0.5001097 0.1411022 0.9420932 0.3105217 0.1266362 0.9772455 0.1620427 0.1368703 0.9085474 0.3836414 0.1654114 0.5274966 0.847163 0.06373727 0.595422 0.7981952 0.09141719 0.6641616 0.7380872 0.1188139 -0.09484988 0.9941881 0.050929 0.007670104 0.9954091 0.09540456 0.3143163 0.9383708 0.1437551 0.2252758 0.9687941 0.1033868 0.5246616 0.839976 0.1384578 0.6368578 0.7482566 0.1858073 -0.1239387 0.9920482 0.02190315 0.0201835 0.9823909 0.1857436 -0.3260579 0.9446483 0.03641378 -0.2501371 0.942187 0.2229692 -0.3287883 0.9300634 0.1639525 -0.3373386 0.5285958 0.7789667 -0.3916753 0.5549062 0.7339412 -0.1911755 0.5126791 0.8370258 -0.1903535 0.4320636 0.8815251 -0.03483343 0.3920137 0.9192997 -0.01323115 0.4554612 0.8901574 0.0450747 0.2100262 0.9766563 0.1790786 0.4111377 0.8938102 0.1436129 0.2827137 0.9483925 -0.3868939 0.6709579 0.6325572 -0.6378273 0.4216439 0.6445097 -0.6258072 0.3061627 0.717377 -0.5937964 0.3370578 0.7306148 -0.5822984 0.436694 0.685731 -0.4427613 0.5179304 0.7319226 -0.5224832 0.4289727 0.736881 -0.439582 0.6053131 0.663599 -0.646507 0.501429 0.5749763 -0.587723 0.6717488 0.4509273 -0.9232373 0.2790089 0.264172 -0.2663934 0.9084622 0.3220732 0.5297837 0.2789402 0.8009505 0.5078414 0.1149079 0.8537525 0.4155695 0.4150544 0.8093404 0.4272869 0.2978581 0.8536432 0.2656388 0.5630699 0.7825525 0.3028652 0.4325025 0.8492434 0.09130394 0.6435316 0.7599544 0.1502534 0.5187987 0.841589 -0.08565521 0.6639389 0.742865 -0.0104494 0.5533369 0.8328921 -0.247612 0.6332235 0.7332915 -0.1577261 0.5452547 0.8232981 -0.2818263 0.5587651 0.7799715 0.8704696 -0.1304464 0.4746223 0.8920706 0.1086837 0.4386318 0.7545078 0.5374382 0.3766673 0.8255238 0.3382346 0.451783 0.5797578 0.7364667 0.3485654 0.7004988 0.5449758 0.4607633 0.3782182 0.8656232 0.3280969 0.5269098 0.712273 0.4637167 0.1642872 0.934962 0.3144136 0.3239935 0.8252085 0.4626655 -0.04758042 0.9501605 0.3081091 0.1197564 0.8805683 0.4585389 -0.2417654 0.9210401 0.3053438 -0.07809245 0.8869343 0.4552463 -0.4178591 0.8543838 0.3089048 -0.2547682 0.855495 0.4508011 -0.563721 0.7635671 0.3149353 -0.7453942 0.6558864 0.1191663 -0.4924629 0.8629346 0.1132442 -0.7024747 0.6374249 0.3165738 -0.4122155 0.7931776 0.4482719 -0.468761 0.7264827 0.5024799 -0.4267604 0.7056033 0.5656851 -0.2225633 0.7239212 0.652996 -0.2789587 0.7783508 0.5624519 -0.05517965 0.7520052 0.6568436 -0.1074667 0.8173231 0.5660689 0.1288209 0.7366628 0.6638774 0.08629584 0.8149055 0.5731336 0.3232065 0.6677215 0.6705861 0.2856798 0.7577162 0.5867311 0.5013921 0.5404803 0.6756383 0.4726747 0.6408626 0.6048751 0.6418018 0.3611854 0.6764878 0.628398 0.460145 0.6272021 0.7345745 0.08838242 0.6727473 0.7527926 0.1852002 0.6316677 0.7490932 0.6568368 0.08616781 0.7299745 0.6746444 0.1095087 0.6652114 0.6784406 0.3117888 0.6879966 0.7156245 0.1205914 0.3952775 0.8917634 0.2202588 0.5904493 0.8012712 0.09661465 0.2572095 0.9353783 0.2427159 0.4600745 0.8837699 0.08533746 0.08835119 0.9650054 0.2468981 0.2911665 0.9523775 0.09055066 -0.1110633 0.9650457 0.2373856 0.1160697 0.9890862 0.09075582 0.03302788 0.9912544 0.1277652 -0.3615817 0.9079461 0.211879 -0.1387428 0.9844915 0.1073641 -0.5011529 0.8265691 0.256182 -0.3118454 0.9454596 0.09412038 -0.6980237 0.6701986 0.2521841 -0.5160185 0.8510193 0.09742319 -0.8356544 0.4833719 0.260832 -0.7105006 0.6925087 0.1249827 -0.9396407 0.263113 0.2187396 -0.8516781 0.5028438 0.1476231 -0.9675682 0.1254897 0.2192358 -0.9414439 0.2864956 0.1777745 -0.9819315 0.01628506 0.1885354 -0.9807905 0.05839359 0.186119 -0.5487471 0.04543209 0.834753 -0.1872088 0.06201207 0.9803608 -0.2044932 0.2098116 0.9561181 -0.148734 0.1219784 0.9813254 -0.08892571 0.357289 0.929751 -0.08336049 0.3342361 0.9387956 0.3103193 0.4091982 0.8580553 0.2782869 0.4045776 0.8711335 0.2777868 0.406502 0.8703968 0.1091805 0.465719 0.8781717 0.1071891 0.4718998 0.8751121 0.07640564 0.4055242 0.9108855 0.610898 0.3441498 0.7129969 -0.5427314 0.08965206 0.8351081 -0.5224386 0.239784 0.8182675 -0.5243332 0.2075763 0.825825 -0.4100616 0.4106832 0.8143641 -0.4154824 0.4001321 0.8168652 -0.2448494 0.5569872 0.7936083 -0.2760087 0.5217682 0.8072034 -0.04057955 0.6417675 0.7658249 -0.1130959 0.5923904 0.7976735 0.1530588 0.6495141 0.7447848 0.0531789 0.6119578 0.7891007 0.321547 0.6002647 0.7323182 0.1688811 0.5786262 0.7979167 0.3865494 0.5846017 0.7133166 0.3081767 0.5611943 0.7681721 0.4505519 0.552743 0.7010552 0.3768663 0.5256828 0.7626464 0.5072444 0.5180703 0.688699 0.5065954 0.5177267 0.6894347 0.578217 0.4070499 0.7070896 0.6267543 0.3591322 0.6915224 0.6203254 0.5303314 0.5778797 0.7132519 0.5825861 0.3896989 0.7534387 0.4949124 0.4328879 0.6871975 0.5509193 0.473548 0.4649705 0.7133181 0.5243852 0.6011393 0.6531674 0.460439 0.3333743 0.7828472 0.5253684 0.4915174 0.7439539 0.4527065 0.1862394 0.8292028 0.5270082 0.3586626 0.8181766 0.4493868 0.0277884 0.8474823 0.5300958 0.1986581 0.8679056 0.4552745 -0.1673374 0.8320791 0.5288125 -0.01844835 0.8855332 0.4642097 -0.374131 0.7581911 0.5340152 -0.2504392 0.8400749 0.4812012 -0.5617769 0.6284254 0.5380413 -0.4860557 0.7126388 0.5058615 -0.7099323 0.451156 0.5407907 -0.673772 0.520094 0.5249128 -0.7887046 0.2819926 0.5462834 -0.7810993 0.3086291 0.5428003 -0.825658 0.1412746 0.5461965 -0.8292496 0.1079204 0.5483599 -0.8357036 0.03470033 0.5480835 0.9858673 0.001726627 0.1675197 0.1873404 0.01026624 0.9822414 0.1106222 -0.4389024 0.8916991 0.4473016 0.5938249 0.6687999 0.4634243 -0.2094144 0.8610363 0.7615055 0.09690892 0.640873 0.7356219 0.4722914 0.4855937 0.8758088 0.0964635 0.4729204 0.9761657 -0.1076717 0.1884342 -0.9858674 0.001708149 0.1675189 -0.976173 -0.1076503 0.1884087 -0.8275678 0.1506617 0.5407706 -0.8195858 0.1890413 0.540872 -0.5418358 -0.1429892 0.8282319 -0.4255191 0.4403045 0.7906109 -0.1772157 -0.3055208 0.9355489 -0.1231383 0.01037651 0.9923353 0.9999288 0 0.01193708 0.9999288 0 0.01193857 0.9979408 -0.01273727 0.06286412 0.9782267 -0.124319 0.1661847 -0.9999288 0 0.01193708 -0.9999288 0 0.01193857 -0.9829438 -0.04183429 0.1790845 -0.9858728 0 0.1674966 -0.8960289 0 0.4439958 -0.6428474 -0.534039 0.5491353 -0.8346071 0 0.5508457 -0.4738284 0 0.8806172 0.9722985 -0.1885331 0.1381704 0.9667928 0 0.2555615 0.8346079 0 0.5508447 0.8345388 0 0.5509492 0.4738904 0 0.8805838 0.4738284 0 0.8806172 0.1231129 0 0.9923927 0 0.303251 0.9529108 -0.1231129 0 0.9923927 -0.4738904 0 0.8805838 0 -1 3.05344e-4 0 -1 1.94863e-4 0 -0.9999995 -0.001110851 0 -1 -4.93087e-5 0 -0.9999391 0.01104521 0 -1 1.86662e-4 0 -1 -3.89522e-4 -1 -3.75469e-7 0 -1 1.6662e-6 0 -1 2.65083e-4 -1.03123e-5 -1 0 -4.19743e-5 -0.8987658 0.3594915 0.25097 0.4304552 0.87525 0.2205578 0.4299468 0.7405421 0.5164718 0.1420627 0.8169475 0.558941 0.2524207 0.7937577 0.5533828 0.4304969 0.7404559 0.5161371 0.4307683 0.8751248 0.2204436 0.1422039 0.9598577 0.2417673 0.1421464 0.9598439 0.2418559 -0.1835598 0.9532369 0.2400945 -0.1836865 0.9531807 0.2402206 -0.4124083 0.7473248 0.5209847 -0.2437701 0.7955882 0.5546311 -0.1836569 0.8125701 0.5531727 -0.07776087 0.8179373 0.5700281 0.09584856 0.8166256 0.5691536 -0.560504 0.6792404 0.4737805 -0.4995871 0.7173137 0.4856685 -0.4994877 0.8400423 0.211757 -0.499309 0.8401745 0.211654 -0.7547004 0.5379606 0.3755339 -0.7540776 0.5386868 0.3757439 -0.7548441 0.6359753 0.1604551 -0.7545582 0.6363295 0.1603959 -0.7591122 0.6454283 0.08468222 -0.4990437 0.8609867 -0.09827244 -0.5538523 0.8317524 0.03789019 -0.1862667 0.9821431 0.02645075 -0.1453722 0.9884297 -0.04328566 0.1444212 0.9858695 0.08487606 0.2901409 0.9530839 -0.08630985 0.4360505 0.8969297 0.07333022 0.6261145 0.7793965 -0.02284145 0.731013 0.6616771 0.1667437 0.7745293 0.60952 0.1690856 0.4847155 0.7174506 0.5003156 0.6138901 0.6288284 0.4771938 -0.9534385 0.2471856 0.1727845 -0.9191629 0.3281464 0.2178521 -0.9189103 0.382463 0.09657078 -0.9188307 0.3826652 0.09652727 -0.9205535 0.3858773 0.0606637 -0.8504218 0.5118724 -0.1215298 -0.991622 0.1059175 0.07394188 -0.9916567 0.1056573 0.07384824 -0.9916992 0.1246615 0.03149849 -0.9916848 0.124774 0.03150725 -0.9919362 0.1266626 0.004376947 -0.9859365 0.1596649 -0.04936081 0.504902 0.6369337 0.5825715 -0.7735458 0.542847 0.3270231 -0.6280949 0.7717695 0.09934234 -0.6202695 0.5787196 0.5294803 -0.4356816 0.6641368 0.6075391 -0.4356583 0.6641744 0.6075147 -0.2588375 0.7126505 0.6520218 -0.1443827 0.7510896 0.644219 -0.1000985 0.7342112 0.6715016 0.05358541 0.7368204 0.6739616 0.186369 0.7446523 0.6409053 0.2222361 0.7193652 0.6581223 0.5048578 0.6369001 0.5826465 -0.8005555 0.5163809 0.3040755 -0.4313606 0.7774078 0.4577831 -0.4309546 0.7776139 0.4578151 -0.1425257 0.8529355 0.5021826 -0.1423352 0.8530254 0.5020843 0.1840282 0.8470743 0.4985969 0.1837694 0.8471023 0.4986448 0.5003446 0.7461548 0.4392134 0.4998158 0.7462765 0.4396085 -0.5381177 0.8290148 0.1521969 -0.430817 0.886133 0.1707779 -0.3997441 0.901403 0.1663651 -0.142087 0.9734102 0.1796775 -0.1904653 0.9626657 0.1923483 0.1827413 0.9702292 0.1589373 0.1348075 0.9744598 0.1795969 0.4991704 0.8520888 0.1573967 0.5442073 0.8279258 0.1355633 0.9209376 0.2875303 0.2630599 0.9209243 0.2875364 0.2630999 0.9192126 0.3392233 0.1999396 0.9190216 0.3395343 0.2002893 0.9917088 0.1106508 0.06534612 0.9917352 0.1105081 0.06518638 0.9919284 0.09354275 0.08560293 0.9919297 0.09354084 0.08559012 0.7594301 0.4800823 0.4390753 0.7594153 0.4800725 0.4391115 0.7554491 0.5645519 0.3325328 0.7550551 0.5648344 0.3329475 0.7554882 0.6421048 0.1301505 0.9135943 0.4062326 0.01790636 0.8492676 0.5149385 0.1165466 0.9912966 0.1311829 0.0110554 0.9865465 0.1607494 0.02976173 1 1.05894e-6 0 1 -7.07899e-7 0 1 -4.36876e-7 0 0.9912784 0.1153667 0.06370097 -0.3095219 0.1289568 0.9421074 -0.3020761 0.1120025 0.9466814 -0.1586543 0.1846231 0.9699192 -0.1881683 0.2466487 0.9506614 -0.2069907 0.2395504 0.9485623 -0.4303632 0.378235 0.8195889 -0.4148886 0.3056005 0.8570156 -0.7733182 0.295537 0.560925 -0.231971 0.4774463 0.8474872 -0.3927382 0.4411318 0.8069446 -0.4282653 0.4427807 0.7877399 -0.168704 0.4987486 0.85017 0.2201887 0.5805155 0.7839126 0.7509063 0.5418785 0.3775019 0.8611286 0.4034474 0.3093343 0.6969867 0.4671918 0.544005 0.6417858 0.4606543 0.6131139 0.457364 0.4725859 0.7533133 0.3865186 0.4529283 0.8034049 0.07743382 0.4131052 0.9073853 0.1538693 0.2544816 0.9547584 -0.08110481 0.1201539 0.9894368 -0.06660604 0.1344624 0.9886777 0.01145863 0.03754198 0.9992294 0.2407304 0.09624117 0.9658088 0.1215847 0.2455766 0.9617221 0.3899875 0.3834856 0.837167 0.4108929 0.4023625 0.8180901 0.6079934 0.4848649 0.6286892 0.6232717 0.499024 0.602086 0.7683295 0.536791 0.3486049 0.8135951 0.4438666 0.3755602 -0.6204479 0.5336748 0.5746612 -0.4992259 0.5474095 0.6716519 -0.4344868 0.5738881 0.6941714 -0.4058604 0.5759256 0.7096387 -0.2579874 0.6178057 0.7428047 0.1535177 0.6202822 0.7692089 -0.0989626 0.5846319 0.8052403 0.05293017 0.5932512 0.8032755 0.6977069 0.4639651 0.5458402 0.503572 0.5501809 0.6661204 0.4388051 0.5564833 0.7055328 0.1270446 0.6023723 0.7880402 0.1675796 0.4121125 0.8955894 -0.1359162 0.3431198 0.9294061 0.02180254 0.4150031 0.9095588 -0.4013965 0.3080393 0.8625501 -0.3603391 0.1825248 0.91479 0.07118988 0.1803522 0.9810225 0.446388 0.2979985 0.8437622 0.4399677 0.3205277 0.8388626 0.6013744 0.5877282 0.541225 0.7381154 0.2792285 0.61418 0.5489073 0.8182945 0.170572 0.9134594 0.2008498 0.3539088 0.8155654 0.5505453 0.1781938 0.8280411 0.5415904 0.1450098 0.9513256 0.2980628 0.07834702 0.8973573 0.388081 0.2101029 0.9939893 0.1035411 0.03555923 0.8718635 0.3570768 0.3351871 0.9210886 0.2767358 0.273885 0.7594825 0.4397906 0.4793441 -0.7672725 0.6163301 0.1772858 0.4357147 0.4035908 0.8045291 -0.9033796 0.4112397 -0.121603 -0.9236093 0.2893304 0.2514635 -0.9866641 0.1618621 0.01716929 -0.5208228 0.5327132 0.6670534 -0.759321 0.4350445 0.4839091 -0.790093 0.4080354 0.4574496 -0.9013257 0.3168643 0.2953118 -0.9543622 0.2307822 0.1895587 0.61473 0.4866163 0.6207349 0.4334933 0.555743 0.7093893 0.4555553 0.5550141 0.6960092 0.2549064 0.6105971 0.7497959 0.2890951 0.6061604 0.7409412 0.09680742 0.6250991 0.7745189 0.1030518 0.6260879 0.7729129 -0.07865446 0.6421087 0.7625679 -0.2464549 0.6196052 0.7452177 0.9571368 0.09546566 0.2734515 0.4466795 0.4572588 0.7690202 0.4097447 0.4251624 0.8070603 0.2729446 0.4595569 0.8451679 0.3329863 0.4474345 0.8300136 0.08842402 0.4908642 0.8667374 0.1539696 0.5039469 0.8499007 -0.529413 0.4737043 0.7037942 -0.1872093 0.584002 0.78987 -0.4152825 0.5602046 0.7167366 -0.5639739 0.5116755 0.648168 -0.8063213 0.4489907 0.385037 -0.7261695 0.4739227 0.4980715 -0.7823826 0.4399818 0.4407875 -0.4650207 0.4734391 0.7480717 -0.5395939 0.4560357 0.7077217 -0.1441024 0.4136002 0.8989824 -0.2287884 0.410609 0.8826417 0.1943621 0.3018358 0.9333374 0.1087498 0.3114054 0.944034 -0.1294611 0.3752033 0.9178575 0.2884243 0.2614236 0.9211239 0.3982678 0.2174857 0.8911132 0.4307385 0.3437896 0.8344298 -0.8241243 0.5567017 0.1044147 -0.6572057 0.5239514 0.5418078 -0.7048215 0.5156886 0.4871263 -0.3669388 0.3912215 0.8439797 -0.5022571 0.3995776 0.7668609 -0.04373842 0.2102316 0.9766728 -0.2284564 0.2475603 0.9415528 0.06332588 0.1050529 0.9924484 0.140463 0.1960984 0.9704719 -0.9883907 0.1131719 -0.1013709 0.9861155 0.1231344 -0.1114202 0.9755461 0.219795 0 0.9866778 0.1382238 0.08579677 0.9661561 0.2578731 0.006630837 0.8872675 0.4612517 -0.001791834 0.8478021 0.5301093 -0.01469546 0.7551338 0.6549991 0.02737236 0.7169718 0.6970745 0.006211817 0.5820173 0.8131453 -0.007130742 0.4484671 0.8879138 -0.1024027 0.564295 0.8158034 0.1266336 0.2945132 0.9537906 -0.05954331 0.3493341 0.9369973 0.001341164 0.1230424 0.9923962 0.003235697 0.1191464 0.9928753 -0.001676797 -0.01531946 0.999882 -0.001195251 -0.152685 0.9879546 -0.02515977 -0.1285113 0.991703 0.003182172 -0.3178651 0.9481358 7.45661e-4 -0.3580721 0.9334821 -0.01989275 -0.4359526 0.8999269 0.008772313 -0.5765052 0.8168826 -0.01857078 -0.601201 0.7990948 0.002239108 -0.723801 0.6900085 -6.97387e-4 -0.784311 0.6200739 0.01909607 -0.7798295 0.6257793 0.01632124 -0.8965661 0.4425222 -0.01853084 -0.9011789 0.4331997 -0.01465171 -0.9850906 0.1698587 0.02728933 -0.9796953 0.2004928 -3.89459e-5 0.8635993 0.1122128 0.491533 0.8856769 0.1027809 0.4527831 0.9085755 0.2308011 0.3481687 0.9421083 0.3046612 0.1400484 0.9602549 0.2730687 0.05782896 0.9341586 0.2791198 0.2223507 0.7752346 0.6183075 0.1292563 0.8918585 0.4119935 0.1866817 0.6808759 0.2660292 0.6823757 0.7213156 0.3875293 0.5740426 0.8104959 0.2612961 0.5242336 0.8110006 0.2609924 0.523604 0.8722543 0.4076303 0.2702035 0.8045818 0.5888689 0.07669234 0.794615 0.5951767 0.1197997 0.8115742 0.5264294 0.2534153 0.790037 0.5243672 0.3176171 0.7941187 0.4932128 0.3551291 0.7707056 0.3705923 0.5183379 -0.9995893 0.02865833 0 -0.9871316 0.1598559 0.004164457 -0.9793987 0.2019262 -0.002037048 -0.9194884 0.3931158 0.001048624 -0.8567225 0.5156808 0.009987115 -0.8171048 0.5764887 -8.57735e-4 -0.6472291 0.7622955 5.44911e-4 -0.554221 0.8323241 0.008704483 -0.4759974 0.8794467 4.58032e-4 -0.1455074 0.9893351 0.006619989 -0.2393977 0.9709212 9.48774e-4 -0.3517426 0.9360968 -4.5511e-5 0.4221642 0.9065194 3.89262e-4 0.2995584 0.9540697 0.003986299 0.2912243 0.9566437 0.004611611 0.09140598 0.9958126 -0.001479625 -0.07760792 0.9969809 0.002507507 0.4997864 0.8661488 -1.18445e-4 0.6262823 0.7795956 0.001170873 0.6431655 0.7657273 -4.46043e-6 0.9688522 0.1796758 0.1704175 0.6090801 0.3067373 0.7313916 0.5834418 0.2557558 0.7708337 0.4911513 0.09108436 0.866299 0.823643 0.1527447 0.5461512 0.830989 0.1647385 0.5313366 0.9197441 0.1705656 0.3535225 0.968851 0.1796725 0.1704276 0.5477719 0.1183322 0.828217 0.453029 -0.005894899 0.8914763 0.5335556 0.112394 0.8382638 0.333465 0.05828982 0.9409587 0.1712636 0.009322583 0.9851812 0.1732182 0.01397454 0.9847844 0.741601 0.3771341 0.5547953 0.7573458 0.3739364 0.5353496 0.797586 0.47143 0.3763115 0.8466001 0.5040797 0.1707983 0.8431851 0.5170762 0.1472119 -0.4674764 0.01231229 -0.8839199 -0.6498758 0.06253397 -0.7574635 -0.5392591 -0.03819841 -0.8412732 -0.4821327 -0.001972258 -0.8760961 -0.4560612 0.03241163 -0.8893581 0.7837564 -0.0554918 -0.6185843 0.4584718 0.01558858 -0.8885723 0.4689266 0.0149942 -0.8831099 0.4884355 -0.00670582 -0.8725743 0.4945763 -0.01001441 -0.8690766 1.26518e-5 0 -1 -0.8881842 0.4320062 0.1565229 -0.8580683 0.367933 0.3582518 -0.8966025 0.4116774 0.1631745 -0.7898354 0.5695767 0.2274699 -0.8218138 0.5423302 0.1746429 -0.8041951 0.2482363 0.5400453 -0.8221148 0.238572 0.5169244 -0.7658896 0.3289195 0.552472 -0.7588766 0.3355191 0.5581517 -0.7329995 0.3887826 0.5581754 -0.9066435 0.1342037 0.3999837 -0.8480905 0.1636401 0.5039489 -0.8272057 0.2235783 0.5155032 -0.9176232 0.2508645 0.308277 -0.9359764 0.3259281 0.1331134 -0.9408587 0.3206346 0.109447 -0.8191198 0.4890197 0.2998378 -0.8221369 0.3682355 0.4341583 -0.3634877 0.1804673 0.913952 -0.5927492 0.1973082 0.7808444 -0.8649929 0.04729676 0.4995502 -0.9052727 0.01172852 0.4246692 -0.628623 0.195315 0.7527851 -0.2587693 0.02032196 0.9657254 -0.1950027 -0.1876289 0.9626886 -0.2585217 -0.02945953 0.9655562 -0.3818759 0.05340361 0.9226695 -0.9809761 0.1819258 0.06774121 -0.9809799 0.1819212 0.06770044 -0.8505179 0.5215754 0.06766474 -0.8499607 0.522011 0.07121449 -0.9315839 0.1727623 0.3198511 -0.9117017 0.194032 0.3621489 -0.8168612 0.4481626 0.3631641 -0.6795511 0.3711694 0.6328062 -0.833045 0.1544881 0.5311964 -0.6700481 0.1242614 0.7318433 -0.6471609 0.1391221 0.7495517 -0.4056828 0.06785684 0.9114917 -0.410511 0.05647134 0.9101054 -0.5863294 0.8100727 0 -0.6312119 0.7755954 -0.004825353 -0.4053984 0.9141393 0.001263558 0.1370344 0.9905618 0.003009438 0.1922928 0.9812911 0.009562075 0.01707041 0.9998544 0 -0.1940876 0.9809842 0 -0.09736788 0.9952303 0.00601834 -0.2448698 0.9695527 -0.002556264 0.9114234 0.4109008 0.02163535 0.7797661 0.6260707 -5.20078e-4 0.7039127 0.7102866 7.41139e-5 0.5492748 0.8356378 0.0026111 0.5995653 0.8002249 0.01271563 0.4219064 0.9066381 -0.001556456 0.8550292 0.5184345 -0.01228076 0.9869686 0.1608195 0.005485177 0.9931079 0.1172049 0 -2.216e-6 0 -1 -0.9727066 0.218854 0.07710313 -0.9772109 0.1996521 0.07209676 -0.9780371 0.2083665 -0.005194008 -0.9772369 0.2110289 0.02179419 -0.9998106 0.01557654 0.0116626 -0.9983612 0.04076373 0.0401659 -0.9979374 0.05286693 0.03641706 -0.9939916 0.08809238 0.06496667 -0.999989 0.00470823 9.31258e-5 -0.999992 0.002299487 0.003293037 -0.9998673 0.007991194 0.01419931 -0.9450793 -1.58899e-4 0.3268412 -0.9513945 -0.002742171 0.307963 -0.967628 -0.09586864 0.233464 -0.9777772 -0.1122556 0.1770607 -0.9795522 -0.140969 0.1435455 -0.9842819 -0.1487343 0.09522271 -0.9843593 -0.1517573 0.0894801 -0.9859714 -0.1594063 0.04949808 0.7057116 0.686121 0.1766612 -0.108283 0.13696 0.9846405 -0.09539151 0.1130654 0.9889978 -0.05650442 0.2335444 0.970703 -0.03751295 0.1032695 0.9939458 0.008338212 0.2326349 0.9725285 0.02903747 0.120018 0.992347 0.09314614 0.2087082 0.9735321 0.08608579 0.1088816 0.9903202 0.1166454 0.1282842 0.9848539 0.5645868 0.8162283 -0.1225293 0.6107676 0.7725272 0.1736804 0.3439095 0.9224535 0.1755158 0.2320851 0.9591967 -0.161488 0.1172921 0.9774287 0.1757152 -0.1265199 0.9763322 0.175409 -0.232175 0.9595685 -0.1591329 -0.352554 0.919111 0.1758998 -0.5676828 0.8043903 0.1751934 -0.6201797 0.784432 -0.006606698 -0.7123486 0.6790927 0.1771797 -0.335709 0.4246305 0.840826 -0.3357208 0.4246106 0.8408315 -0.128162 0.5297165 0.8384361 -0.1281419 0.5296266 0.8384959 0.1281609 0.5297173 0.8384358 0.1281419 0.5296266 0.838496 0.3357177 0.4246283 0.8408237 0.3357116 0.424612 0.8408343 -0.5240948 0.6628997 0.5346856 -0.5240498 0.6628442 0.5347985 -0.1992314 0.8234781 0.5312163 -0.1992698 0.8235658 0.5310658 0.1992405 0.8235073 0.5311676 0.1992623 0.8235347 0.531117 0.5240489 0.6628416 0.5348027 0.5240983 0.6629054 0.534675 0.9886023 0.1505486 8.37355e-4 0.9859376 -0.1533771 0.066352 0.9978376 0.0503 0.04231196 0.9856113 0.1674792 -0.02282983 0.9945375 -0.06661653 0.08035814 0.9752373 0.2190316 0.03061854 0.9760106 0.2124751 0.04751628 0.9736269 0.1609035 0.1617427 0.9776469 0.1661169 0.1288867 0.9599514 0.07972043 0.2685851 0.9315723 0.06040859 0.3585026 0.9109288 -0.03724962 0.4108787 0.9997792 0.02080476 -0.002939343 0.98219 -0.1525965 0.1096232 0.9746622 -0.07830476 0.209528 0.9621558 -0.1683167 0.2143029 0.9644044 -0.08995914 0.2486593 0.7848865 0.6196396 0 0.852303 0.5226676 0.01995372 0.8624745 0.505908 0.01396572 0.9974213 0.07176995 2.73731e-4 0.9899407 0.1411994 0.008958399 0.9831207 0.182322 0.01524621 0.9698563 0.2436505 0.003649592 0.9191457 0.3939133 -0.00192517 0.9848791 0 0.1732437 0.9848759 -8.72587e-7 0.1732612 0.9334281 0 0.3587647 0.8334285 -0.001146733 0.5526263 0.8435825 -2.33081e-6 0.5369996 0.5369496 2.16018e-6 0.8436143 0.5368739 -3.57928e-6 0.8436625 0.1732477 2.78903e-6 0.9848784 0.1731865 0 0.9848892 -0.9754291 0.03692311 -0.2171974 -0.9716913 -0.1894004 -0.1412221 -0.9567414 -0.03302311 -0.2890595 -0.9437702 0.006732761 -0.3305338 -0.5105068 -0.005608677 -0.8598555 -0.7908875 0.07212549 -0.6076965 -0.726845 -0.2015787 -0.6565535 -0.8831362 0.07282668 -0.4634296 -0.8827759 0.07868373 -0.4631584 -0.792963 0.06646311 -0.605634 -0.7285847 -0.1865943 -0.6590501 -0.6495496 0.2227917 -0.7269452 -0.5187508 -0.02758085 -0.8544805 -0.4767141 0.008940041 -0.879013 -0.2883676 -0.06980007 -0.9549724 -0.3117397 -0.1061506 -0.9442195 -0.4083921 -0.09084469 -0.9082748 -0.4051788 -0.08686214 -0.9101017 -0.3824748 -0.06974911 -0.9213295 -0.07637298 -0.01879513 -0.9969022 -2.90754e-5 1.74892e-5 -1 3.34302e-6 1.2022e-5 -1 8.2021e-6 3.04346e-5 -1 5.07865e-5 -5.29459e-5 -1 9.53516e-5 -4.48905e-5 -1 0 -1.10129e-6 -1 -2.42384e-4 -1.03424e-5 -1 -7.15171e-5 -4.11365e-5 -1 0 -1.07465e-6 -1 2.90991e-5 1.74939e-5 -1 -3.08586e-6 1.2022e-5 -1 -9.91833e-6 0 -1 9.91833e-6 0 -1 0.2990708 -0.1009806 -0.9488729 0.2878483 -0.06585556 -0.9554091 0.4345196 -0.04665881 -0.8994531 0.9861812 0.03730714 -0.1614149 0.735105 -0.02449369 -0.6775107 0.7468062 0.2723965 -0.6066966 0.8731737 -0.09313613 -0.4784281 0.5465061 -0.01724946 -0.8372775 0.3978782 0.2403293 -0.885401 0.5539061 -0.1321504 -0.8220246 0.7260502 0.1087948 -0.6789808 0.7779346 0.03147214 -0.6275568 0.8740368 0.03536039 -0.4845712 0.8958517 -0.01845192 -0.4439699 0.9620695 0.104551 -0.2519749 0.9767675 -0.208109 -0.05114686 0.9827669 -0.1833638 0.02338743 0.9843457 -0.1762409 0.00165838 0.9999535 -0.009496033 0.001667618 -0.1731951 0 0.9848875 -0.2588138 0.004297316 0.9659177 -0.9976251 0 0.06887829 -0.9848745 -0.002048254 0.1732575 -0.9458026 0.00260365 0.3247318 -0.9064725 0 0.4222652 -0.8431811 0 0.5376297 -0.7933319 -0.001082122 0.6087886 -0.67528 0.003206789 0.7375544 -0.608736 0 0.7933729 -0.4222189 0 0.9064939 -0.9185883 0.3952115 -0.001866638 -0.9832196 0.18234 0.005606055 -0.9663673 0.2551425 0.03219765 -0.9772565 0.2109317 0.02185314 -0.9823181 0.1864937 0.01647621 -0.9886108 0.1501581 0.01007419 -0.9954088 0.09565877 0.003278613 -0.999263 0.03838467 3.58584e-4 -0.9999212 0.01256239 5.58102e-5 -0.9999876 0.005004346 0 -0.852473 0.5227714 0 -0.7983463 0.6002333 0.04861348 -0.8622692 0.5062527 0.01414453 -0.9852727 -0.169802 0.02012604 -0.9656654 -0.2456582 -0.08451336 -0.9943887 -0.1057753 0.001686811 -0.9999526 -0.009592354 0.00168401 -0.9760416 -0.009359657 -0.2173829 -0.5877926 0 -0.8090118 -0.5103694 0.02385354 -0.8596245 -0.286825 -0.02361929 -0.9576918 -0.4179769 -0.2817282 -0.8636693 -0.5465069 -0.002650141 -0.8374505 -0.8473079 0.003951549 -0.5310873 -0.7929266 -0.002975583 -0.6093099 -0.9843211 0.002509117 -0.1763682 -0.9762818 0 -0.2165039 -0.5388021 -0.7824462 0.3122023 -0.4471771 -0.8944455 0 -0.2012265 -0.9795448 0 -0.2012265 -0.9795448 0 0.2012277 -0.9795445 0 0.2012248 -0.9795451 0 0.4472648 -0.8944017 0 0.5388801 -0.7825584 0.3117865 0.9843243 0 -0.1763681 0.9868189 -0.009368717 -0.161557 0.9870396 -8.10046e-4 -0.1604753 0.8960134 5.5798e-4 -0.444027 0.8473135 -0.002870142 -0.5310856 0.7783186 -6.59043e-5 -0.6278696 0.5877887 1.41479e-4 -0.8090145 0.5900444 0 -0.8073709 0.2945683 -0.0981785 -0.9505739 0.3465654 -0.01144593 -0.937956 0.5584703 0.0348218 -0.8287935 -1 0 4.2209e-6 -0.3295954 0.9441223 0 -0.324429 0.9459061 0.002726316 -0.08641731 0.9962557 -0.002592206 0.5080735 0.8613129 -0.001317799 0.4057221 0.9139288 0.01112318 0.3536652 0.9347361 0.03448927 0.1878116 0.9819474 -0.02249777 0.1060369 0.9943622 0 -0.08097767 0.996716 0 0.7321752 0.6800034 0.03892177 0.8089416 0.5878826 0.002778232 0.6147388 0.7887173 0.004610002 0.6713362 0.7406571 0.02710497 0.8362157 0.5466719 -0.04351097 0.9999991 0.001445055 0 0.9960423 0.08888071 1.92682e-4 0.9674399 0.2520871 0.0226323 0.895034 0.445995 -0.00158298 0.924248 0.3817324 0.006798028 0.9905135 0.1357815 -0.0211271 0.6614125 0.7297065 -0.1733838 0.3485172 0.921128 -0.1733753 0.348509 0.9211291 -0.1733861 0.1043823 0.9788479 -0.1759581 -0.0126425 0.9964932 -0.0827127 -0.07972389 0.9812806 -0.1753075 -0.2998957 0.9391279 -0.1676349 -0.3198795 0.9326428 -0.1668976 0.9239248 0.3815977 -0.027318 0.823945 0.5386522 -0.1759788 0.6614127 0.7297081 -0.1733767 0.8825724 0.4370455 -0.1733703 0.9754835 0.1337237 -0.1747851 0.9754845 0.1337211 -0.1747819 0.5858854 0.08031564 -0.8064042 0.1427348 0.5671169 -0.8111752 0.2160937 0.4778757 -0.8514332 0.2104007 0.5560963 -0.8040452 0.399309 0.440528 -0.8040446 0.3993083 0.4405317 -0.8040427 0.5328287 0.2638534 -0.8040367 0.5328251 0.263855 -0.8040387 0.5858935 0.0803157 -0.8063984 -0.005693137 0.8287001 -0.559664 0.02823776 0.8492108 -0.5272985 0.3013144 0.7963921 -0.5243753 0.3013167 0.79639 -0.5243769 0.5718485 0.6308943 -0.5243681 0.5718557 0.6308933 -0.5243613 0.7630577 0.3778613 -0.5243701 0.7630549 0.3778643 -0.5243718 0.8416561 0.1153773 -0.5275446 0.8416573 0.1153761 -0.5275428 3.80738e-7 0 -1 2.1201e-7 0 -1 8.83355e-7 0 -1 0 0 -1 0 0 -1 2.05657e-6 0 -1 -9.93776e-7 0 -1 -0.1922507 0.5081253 -0.8395527 0.3186534 0.929071 -0.1878491 -0.9754839 0.1337213 -0.1747852 -0.348508 0.9211265 -0.1734019 -0.6614133 0.7297074 -0.1733769 -0.6614143 0.7297059 -0.1733797 -0.8247699 0.5373945 -0.1759594 -0.8931495 0.442285 -0.08165889 -0.9105484 0.3744505 -0.1751816 -0.9754829 0.1337233 -0.1747891 0.07638865 0.9963821 -0.03724944 -0.1088911 0.9783471 -0.1760108 -0.348519 0.9211326 -0.1733471 0.007929384 0.8274129 -0.5615382 0.005558192 0.8331254 -0.5530562 0.0103538 0.9839023 -0.1784068 0.3005676 0.9389877 -0.167216 0.3133567 0.9348788 -0.166761 -0.2434095 0.5382831 -0.8068476 -0.3993028 0.4405276 -0.8040478 -0.3993102 0.4405275 -0.8040441 -0.5328282 0.2638558 -0.8040363 -0.5328295 0.2638532 -0.8040363 -0.5858892 0.08031708 -0.8064013 -0.5858927 0.08031666 -0.8063988 -0.1455477 0.563912 -0.8129079 -0.02629327 0.8493649 -0.5271507 -0.3013164 0.7963901 -0.5243772 -0.3013151 0.7963919 -0.5243752 -0.571849 0.630886 -0.5243774 -0.5718525 0.6308978 -0.5243594 -0.7630558 0.3778631 -0.5243715 -0.7630594 0.3778645 -0.5243652 -0.8416605 0.1153789 -0.5275372 -0.8416525 0.1153753 -0.5275507 0.1861534 0.6947159 -0.6947783 0.186166 0.6947953 -0.6946954 0.5085832 0.5085872 -0.6947534 0.5085695 0.5085614 -0.6947823 0.694742 0.1861548 -0.6947517 0.6947498 0.1861602 -0.6947426 0.694742 -0.1861548 -0.6947517 0.6947392 -0.1861556 -0.6947544 0.508588 -0.5085855 -0.6947511 0.5085927 -0.5085946 -0.694741 0.1861464 -0.6947169 -0.6947792 0.1861549 -0.6947536 -0.6947402 -0.1861456 -0.6947169 -0.6947793 -0.1861549 -0.6947536 -0.6947402 -0.508588 -0.5085856 -0.6947511 -0.5085877 -0.5085895 -0.6947483 -0.6947483 -0.1861563 -0.6947451 -0.6947326 -0.1861537 -0.6947615 -0.6947545 0.186158 -0.6947384 -0.6947351 0.1861566 -0.6947581 -0.5085832 0.5085872 -0.6947534 -0.5085898 0.5085819 -0.6947524 -0.1861659 0.6947656 -0.6947252 -0.1861549 0.6947536 -0.6947402 0.9990993 0 0.0424332 0.9807621 -0.006889462 0.1950854 0.1938272 -2.03251e-5 0.9810357 0.9754385 -0.002715408 0.2202554 0.8505287 0.003086745 0.5259195 0.8314605 -0.004329502 0.5555672 0.5704621 0.004892945 0.8213094 0.5555676 3.45535e-4 0.8314713 0.1950946 -3.40889e-4 0.9807844 0.980741 -0.009507715 0.1950809 0.968115 -0.01968705 0.2497314 0.96723 -0.0149343 0.2534623 0.9716002 -0.02630859 0.2351617 0.8309714 -0.03466427 0.5552341 0.803754 -0.04600429 0.5931805 0.5545718 -0.06002265 0.8299684 0.5624828 -0.05763572 0.8247978 0.2597146 -0.07579022 0.9627067 0.1946597 -0.06637644 0.9786224 0.04398608 -0.07609963 0.9961296 -0.1002511 -8.72362e-6 0.9949622 -0.8314686 -5.11989e-5 0.5555718 -0.8062648 -0.01039499 0.5914635 -0.9137166 0.001140832 0.4063504 -0.9807767 -0.00421226 0.1950883 -0.9753552 -0.009302198 0.2204447 -0.9986819 0 0.05132794 -0.1950692 -0.01270598 0.9807072 -0.2742335 -0.002413392 0.9616602 -0.5555578 0.005434989 0.8314603 -0.4834353 -0.01790797 0.875197 -0.6568055 1.79143e-5 0.7540602 -0.1945431 -0.07471823 0.9780441 -0.9894961 -0.007037162 0.144389 -0.9902792 -0.008399248 0.1388405 -0.9910063 -0.01142561 0.1333274 -0.1604247 -0.06785142 0.9847132 -0.5542276 -0.06946748 0.8294613 -0.4788669 -0.05107814 0.8764004 -0.9807779 -0.00396651 0.1950874 -0.9521452 -0.02295106 0.3047835 -0.8307377 -0.04184401 0.5550891 -0.8881118 -0.009396433 0.4595316 -0.7445617 -0.05685144 0.6651284 0.9186499 0.04253411 0.3927765 0.9659256 1.73632e-4 0.2588201 0.8306607 -4.46646e-5 0.556779 0.9537786 0.01721453 0.3000169 0.9940909 1.25264e-4 0.108551 0.9999986 0 0.001651525 0.2588178 0 0.9659262 0.2220424 0.1356177 0.9655596 0.3132939 0.04680681 0.948502 0.4149421 -0.002690017 0.9098439 0.7070912 0.006379604 0.7070936 0.6469513 0.05907076 0.7602399 0.7307226 0.01496684 0.6825104 0.1023991 -2.62433e-4 0.9947434 0.247996 -0.2411231 0.9382739 0.3596783 0.01440739 0.9329652 0.6481659 -0.01945006 0.7612509 0.6960202 -0.1173747 0.7083637 0.810945 -0.006990134 0.5850808 0.9618957 -0.02130496 0.2725855 0.9695181 -0.1467333 0.1962243 0.8960437 5.21801e-4 0.4439657 0.9658142 -0.0152384 0.2587867 0.9620811 0.00859642 0.2726279 0.7070722 -0.01031732 0.7070661 0.7009937 0.004129111 0.7131556 0.2588143 -0.005105316 0.9659136 0.2560514 -2.4708e-4 0.9666632 -0.1052125 0 0.9944499 -0.2574741 0.1018227 0.9609055 -0.3132939 0.04680681 0.948502 -0.4149401 -0.002690613 0.9098448 -0.5722073 0.001938641 0.8201068 -0.7068223 0.02817773 0.7068299 -0.7307255 0.01496601 0.6825074 -0.9999986 0 0.001651525 -0.9940909 1.2536e-4 0.1085511 -0.9537788 0.01721435 0.3000163 -0.9659072 0.006179451 0.2588148 -0.878096 1.65873e-5 0.4784845 -0.8306545 -4.47916e-5 0.5567883 -0.9926904 -0.01049512 0.1202319 -0.9564778 -0.1079568 0.2711008 -0.9317371 -6.46918e-4 0.3631329 -0.7579262 -0.005791366 0.6523147 -0.6947869 -0.1313208 0.7071252 -0.564935 2.80168e-4 0.8251354 -0.2560273 -6.60733e-4 0.9666694 -0.2180191 -0.2171847 0.9514718 -0.4150354 -0.003545403 0.9097985 -0.2588166 -2.49747e-4 0.9659265 -0.2560391 -0.005155384 0.9666527 -0.7071049 0.004280686 0.7070958 -0.7009422 -0.0106278 0.713139 -0.9658846 0.009119749 0.2588125 -0.961991 -0.01602655 0.2726106 0 -0.2588162 0.9659267 0 -0.2588236 0.9659247 0 -0.7071068 0.7071068 0 -0.9659267 0.2588162 0 -0.2587632 0.9659409 0 -0.2588644 0.9659137 0 -0.7070347 0.707179 0 -0.7071396 0.707074 0 -0.9659171 0.2588515 0 -0.9659312 0.258799 0.9774202 0.05971395 0.2026922 0.989663 -0.01399677 0.1427276 0.8670616 -0.01007091 0.4980992 0.8940984 0.1213593 0.4311149 0.9371242 0.01690447 0.3485865 0.8739133 0.03925198 0.4844945 0.8363571 0.107038 0.5376336 0.7376249 0.09558671 0.6684106 0.7178236 0.1192049 0.6859442 0.6219121 0.1490244 0.7687763 0.6084125 0.1615286 0.7770089 0.4637066 0.1686587 0.8697876 0.4490343 0.1785488 0.8754932 0.3124423 0.2155007 0.92517 0.2963107 0.2240808 0.928433 0.1332353 0.2270724 0.9647209 0.9999986 -3.5643e-5 0.001652896 0.9979521 0.04873752 0.04143065 0.99732 0.03486108 0.06432342 0.9779887 0.1429283 0.1520183 0.9743327 0.128615 0.1847543 0.9362083 0.2302829 0.2654882 0.9286588 0.2261945 0.2939882 0.8723164 0.3223647 0.3676209 0.8561117 0.317739 0.407572 0.7886852 0.4002674 0.4666495 0.7648734 0.4105039 0.4964426 0.6886987 0.4809287 0.5425881 0.6471018 0.4870598 0.5865426 0.5586317 0.5499429 0.6208812 0.5026913 0.5704534 0.6495264 0.4148666 0.6175081 0.6682586 0.3318636 0.6286495 0.7033253 0.9954494 0.09516304 -0.004963815 0.9735071 0.210662 0.0889129 0.9681366 0.2491477 0.02523994 0.9221848 0.3680065 0.1189391 0.9230777 0.3785544 0.06800287 0.8492177 0.5023252 0.1627841 0.8543462 0.5092445 0.1037442 0.7598611 0.6238199 0.1829208 0.7771008 0.6114153 0.149285 0.6620991 0.7168806 0.2184196 0.6792262 0.7098504 0.1864514 0.5490296 0.80275 0.2327212 0.5617121 0.796403 0.2241022 0.4326517 0.8657065 0.2517237 0.424528 0.8681094 0.25722 -0.1063734 0.3111513 0.9443886 0.04914486 0.256932 0.9651792 0.04914283 0.2569319 0.9651793 0.1335979 0.6984759 0.7030527 0.1335968 0.6984701 0.7030587 0.1816011 0.9494444 0.256079 0.1815945 0.949442 0.2560927 9.25726e-4 0.2589585 0.9658881 -0.0217635 0.2509379 0.9677585 -0.06134027 0.7072043 0.7043433 -0.06134772 0.7071875 0.7043595 -0.08352464 0.9628088 0.2569496 -0.08351629 0.9628111 0.2569435 -0.3185288 0.9124228 0.2569519 -0.3185248 0.9124297 0.2569319 -0.2622283 0.7511665 0.605793 -0.2905583 0.6529921 0.6994121 -0.2016418 0.5775809 0.791038 -0.108069 0.3095498 0.9447222 -0.1167267 0.3145913 0.9420229 -0.6185211 0.5727661 0.5379319 -0.07040148 0.1576014 0.9849901 -0.1831414 0.2816463 0.9418783 -0.1753269 0.3209733 0.9307184 -0.1642379 0.2533449 0.9533322 -0.2585231 0.4749876 0.8411614 -0.3059467 0.5272651 0.7927095 -0.4229488 0.7289025 0.5383451 -0.3762096 0.6986753 0.6085386 -0.5200447 0.8358741 0.1756927 -0.4848463 0.8355829 0.2583126 -0.708954 0.7047719 -0.02609407 -0.6989436 0.6932825 0.1756057 -0.7256407 0.6808403 0.09950953 -0.6695501 0.6646151 0.3316468 -0.3026798 0.2864167 0.9090382 -0.359952 0.3320542 0.8718799 -0.4022141 0.3615459 0.8411352 -0.4476171 0.4251437 0.7866967 -0.5762336 0.5530509 0.6017389 -0.4942327 0.0477758 0.8680159 -0.1767858 0.1731455 0.9689002 -0.07962185 0.0412653 0.9959707 -0.1258378 0.1230792 0.9843863 -0.1102296 0.1404223 0.9839366 -0.1091969 0.1384118 0.9843365 -0.3346452 0.424171 0.8414818 -0.3346344 0.4241592 0.8414921 -0.5221014 0.6617782 0.5380147 -0.5221086 0.6617906 0.5379927 -0.6097906 0.772933 0.1753003 -0.6097932 0.7729375 0.1752712 -0.9896626 -0.01399868 0.1427307 -0.9685218 0.0943281 0.2303644 -0.9419928 0.001209139 0.335631 -0.9954491 0.09516543 -0.004963815 -0.9783943 0.1929141 0.07435607 -0.9657558 0.2575096 0.03169864 -0.9330744 0.3453046 0.1006833 -0.9147663 0.3958116 0.08084464 -0.867693 0.4763015 0.1422873 -0.8396664 0.530192 0.1177155 -0.7826546 0.5999608 0.1658281 -0.7560987 0.6337444 0.1633485 -0.6846016 0.6991297 0.2062483 -0.658957 0.726607 0.1944689 -0.5624579 0.7946292 0.2284861 -0.5488079 0.804476 0.2272191 -0.424433 0.8693227 0.2532485 -0.4321869 0.8643969 0.2569681 -0.9999986 0 0.001652896 -0.9976326 0.0523523 0.04459363 -0.9973304 0.03474372 0.0642265 -0.9756521 0.1513024 0.1587786 -0.975412 0.1247726 0.1816686 -0.9302823 0.2426128 0.2751619 -0.933028 0.2171 0.2869259 -0.8594348 0.3405612 0.3813005 -0.8658655 0.3038892 0.3974021 -0.767274 0.4227517 0.4822568 -0.7841138 0.3901882 0.4826168 -0.6529657 0.5094898 0.5604071 -0.678038 0.4619269 0.5717413 -0.506563 0.5816888 0.6364215 -0.5520344 0.539961 0.6353741 -0.3417276 0.6505157 0.6782711 -0.3995888 0.5967665 0.6958438 -0.9252632 0.05060422 0.375935 -0.8788507 0.09497672 0.4675477 -0.873918 0.03925651 0.4844856 -0.7940562 0.170255 0.5835136 -0.7734985 0.04927939 0.6318796 -0.6539849 0.1881706 0.7327317 -0.6827855 0.08860951 0.7252258 -0.5200999 0.2368241 0.820616 -0.5489194 0.1077484 0.8289016 -0.3382097 0.2482039 0.9077495 -0.4233193 0.1527445 0.8930116 -0.1743628 0.2849044 0.9425642 -0.2582643 0.1785236 0.9494362 -0.136745 0.6976263 0.7032911 -0.1859411 0.9485628 0.2562319 0.1193076 0.3159995 0.941228 0.2003471 0.5781371 0.7909606 0.1072917 0.309607 0.9447921 0.03151893 0.3946651 0.9182843 0.07257121 0.2288855 0.9707446 -0.002122819 0.2590029 0.9658742 -0.05028527 0.2565474 0.9652228 -0.05028736 0.2565411 0.9652243 -0.1859322 0.9485606 0.256246 0.07694071 0.9633795 0.2568662 0.07692623 0.9633778 0.2568768 0.3164528 0.9131649 0.2568805 0.3164383 0.9131678 0.2568878 -0.1367468 0.6976053 0.7033116 0.05651015 0.7077055 0.704244 0.05651986 0.7077059 0.7042428 0.2324566 0.6708201 0.7042474 0.35826 0.7078794 0.6087335 0.05479496 0.1615834 0.9853367 0.1147736 0.2002597 0.972997 0.04232436 0.04136103 0.9982475 0.1343863 0.1151378 0.9842174 0.1386187 0.1208887 0.98294 0.2217932 0.2135425 0.951424 0.6074911 0.5839514 0.5384751 0.447764 0.4249329 0.7867271 0.4024094 0.3613059 0.841145 0.360136 0.3318915 0.8718658 0.3027751 0.2862766 0.9090506 0.6984385 0.6937888 0.1756155 0.7501446 0.6611107 0.01469403 0.7259719 0.680437 0.09985142 0.6697182 0.6643608 0.3318168 0.5896016 0.5276868 0.6114872 0.4855594 0.8351718 0.2583026 0.5204303 0.8356375 0.1756769 0.4106703 0.7362959 0.5377901 0.3990719 0.686411 0.6079322 0.2714005 0.4668148 0.8416803 0.2853553 0.5379019 0.7932427 0.1756387 0.2793388 0.9439921 0.1760669 0.2878557 0.9413499 0.610754 0.7721729 0.1752958 0.6107537 0.7721745 0.1752898 0.5229133 0.6611162 0.5380401 0.5229218 0.6611255 0.5380204 0.3351538 0.4237338 0.8414998 0.3351555 0.4237362 0.8414977 0.1113407 0.1407675 0.983762 0.1089406 0.1386657 0.9843292 0.001607477 -1.3469e-4 0.9999987 7.68667e-4 -1.66289e-4 0.9999997 7.24253e-4 -2.80587e-4 0.9999997 4.80678e-4 -2.91112e-4 0.9999999 3.99716e-4 -3.28736e-4 0.9999999 0.001377999 -5.08587e-4 0.9999989 6.85461e-4 -0.001043677 0.9999992 0.003304541 -0.001550793 0.9999934 5.38852e-4 -0.001889169 0.9999981 0.005352139 -0.004533708 0.9999755 6.01414e-4 -0.006237387 0.9999805 0.01416379 -0.009464442 0.999855 0.0335347 -0.00454235 0.9994273 0.02314686 7.22085e-4 0.9997318 0.04055249 1.63089e-4 0.9991774 0.02208048 0.03551334 0.9991253 -0.01224899 0.04005545 0.9991225 0 1 1.38402e-5 0 1 -1.03801e-5 0 1 1.03801e-5 0 1 -1.38402e-5 0 1 -1.03801e-5 -0.00346601 -0.07617306 0.9970886 0 -0.07822692 0.9969357 0.003590762 -0.0761733 0.9970882 -0.9969879 0.001945197 0.07753294 -0.9800516 0.0154336 0.1981428 -0.9134052 0.3101491 0.2636257 -0.9197438 0.3102261 0.2404812 -0.9342882 0.2953158 0.1997354 -0.9250032 0.2955223 0.2388214 -0.9317864 0.291415 0.2164521 -0.9434423 0.2673805 0.196021 -0.9735895 0.2099425 0.0897085 -0.9740743 0.2092013 0.08610546 -0.9933209 0.1036345 0.05073177 -0.9983258 0.05778491 -0.002544939 -0.999533 0.03055477 3.88675e-4 -0.965512 0.1206426 0.2307204 -0.9693803 0.1247162 0.2115368 -0.97885 0.1302102 0.1577911 -0.9778057 0.003344058 0.2094873 -0.9796887 0.01434242 0.2000113 -0.9020115 0.3868857 -0.191559 -0.9358388 0.2957987 -0.1915957 -0.9442828 0.2676174 -0.1916012 -0.9442822 0.2676207 -0.1915998 -0.9594584 0.2068946 -0.1914008 -0.959476 0.2068501 -0.1913602 -0.976225 0.1018546 -0.1913389 -0.9762336 0.1018162 -0.1913153 -0.9256229 0.3264358 -0.191473 -0.9228851 0.3449436 -0.171164 -0.9305664 0.3159481 -0.1849945 -0.9024399 0.3770973 -0.2083265 -0.8973182 0.3976192 -0.1916228 -0.9019905 0.3869128 -0.1916031 -0.9015478 0.3879733 -0.1915422 -0.9281911 0.3190879 -0.1914274 -0.928233 0.3190207 -0.1913356 -0.9595196 0.206748 -0.1912529 -0.9595506 0.2066792 -0.1911715 -0.9789675 0.07124674 -0.1911717 -0.978977 0.07121181 -0.191136 -0.1753085 -0.07740134 -0.9814663 -0.5391294 0.005227684 -0.8422068 -0.9810157 0.02998691 -0.1915963 -0.9830465 -0.05061918 -0.176231 -0.8366355 0.1148303 -0.5355888 -0.55232 0.1068469 -0.8267565 -0.5561417 0.05787634 -0.8290699 -0.5560845 0.05794018 -0.8291038 -0.5465237 0.117646 -0.8291389 -0.5464351 0.1177256 -0.829186 -0.5373935 0.1522785 -0.8294695 -0.5373795 0.1522919 -0.8294761 -0.5272154 0.1856746 -0.8291978 -0.5270391 0.1857584 -0.8292911 -0.5134538 0.2200858 -0.8294139 -0.5133409 0.2201221 -0.8294742 -0.5129821 0.2209454 -0.8294774 -0.5131466 0.2209028 -0.8293868 -0.5284224 0.1820302 -0.8292375 -0.5286921 0.1818886 -0.8290966 -0.5466355 0.1181621 -0.8289918 -0.546867 0.1179672 -0.8288668 -0.196191 0.00569725 -0.9805492 -0.1955048 0.02032274 -0.9804922 -0.1954802 0.02034306 -0.9804967 -0.1921147 0.04132163 -0.9805023 -0.1920771 0.04134678 -0.9805085 -0.1888321 0.05350536 -0.9805507 -0.1888288 0.05350774 -0.9805512 -0.1853245 0.06521391 -0.9805112 -0.1852495 0.06524074 -0.9805235 -0.1804453 0.07731145 -0.980542 -0.1803926 0.07732325 -0.9805508 -0.1802357 0.07767939 -0.9805514 -0.1803157 0.07766419 -0.980538 -0.1856858 0.06408053 -0.9805175 -0.1858288 0.06401401 -0.9804947 -0.1921406 0.04166829 -0.9804824 -0.192274 0.04156231 -0.9804608 -0.1961658 0.01442837 -0.9804646 -0.1962259 0.01435375 -0.9804537 -0.4431082 0.03241258 -0.8958821 -0.5504322 0.09563261 -0.8293847 -0.6100254 0.0444737 -0.7911329 -0.7934553 0.05784606 -0.6058735 -0.8338578 0.03825837 -0.5506519 -0.8306525 0.08654874 -0.5500236 -0.8306107 0.08662611 -0.5500743 -0.8163537 0.1758785 -0.5501212 -0.8162805 0.1759794 -0.5501977 -0.8031302 0.227598 -0.5506187 -0.8031279 0.2276142 -0.5506156 -0.7875408 0.277574 -0.550211 -0.7873997 0.2776879 -0.5503556 -0.7672511 0.3289997 -0.5505315 -0.7671673 0.3290487 -0.5506191 -0.7667247 0.3300634 -0.5506284 -0.7668471 0.3300071 -0.5504914 -0.7895699 0.271638 -0.5502657 -0.7897572 0.2714965 -0.5500667 -0.8164503 0.1761206 -0.5499005 -0.8166033 0.1759528 -0.5497271 -0.8275477 0.1093555 -0.5506415 -0.896517 0.06524646 -0.4381784 -0.7002941 -0.4892396 -0.5198393 -0.7027053 -0.4954087 -0.5106619 -0.7168607 -0.5088747 -0.4766103 -0.7467379 -0.4190565 -0.516502 -0.7144291 -0.4667108 -0.5213177 -0.7024682 -0.4948477 -0.5115313 -0.7038329 -0.5169731 -0.4871943 -0.7966834 -0.3035035 -0.5226675 -0.7971575 -0.3695743 -0.4774463 -0.7761926 -0.4001492 -0.4872429 -0.7957724 -0.4181812 -0.4380307 -0.7991275 -0.4926618 -0.3444994 -0.7920486 -0.4961964 -0.3555957 -0.786379 -0.4702551 -0.4005848 -0.7846476 -0.4729034 -0.4008625 -0.786245 -0.4905973 -0.3756769 -0.8408932 -0.1389437 -0.5230616 -0.802433 -0.1727376 -0.5711945 -0.7968145 -0.2314187 -0.5581505 -0.7891525 -0.2386474 -0.5659381 -0.7908831 -0.3029047 -0.5317451 -0.7649871 -0.3305403 -0.5527548 -0.7600626 -0.4108111 -0.5035269 -0.7593137 -0.4118847 -0.5037797 -0.7521907 -0.4976647 -0.4319016 -0.7663252 -0.475616 -0.4318973 0.5691891 0.8221244 -0.01163554 0.5768004 0.8167048 -0.01716667 0.4562879 0.8508156 -0.2606038 0.4780853 0.8356735 -0.2703411 0.302501 0.7813697 -0.5458521 0.111104 0.6165771 -0.7794156 0.1243996 0.6331555 -0.7639626 0.2004766 0.7160003 -0.6686949 0.3403733 0.7615153 -0.5515801 0.3247854 0.7657085 -0.5551621 0.5725894 0.8198404 -0.001793682 0.5723899 0.8199798 -0.001725316 0.5559931 0.8294392 -0.0538733 0.5570813 0.8286817 -0.05428761 0.5376132 0.8349413 -0.1176646 0.5357652 0.8362361 -0.1168972 0.5148876 0.8375272 -0.1828632 0.5060064 0.843761 -0.1789552 0.4829199 0.8408778 -0.2443622 0.3138315 0.8016423 -0.5088021 0.3355816 0.7865123 -0.5184435 0.4345098 0.8329293 -0.3426808 0.4355752 0.832189 -0.3431265 0.5189206 0.8392461 -0.1624423 0.511431 0.8444569 -0.159157 0.5730577 0.8194835 -0.007202386 0.5709314 0.8209601 -0.007874906 0.5728468 0.819655 -0.003531277 -0.1328535 0.4087951 -0.9029046 0.07906252 0.6389138 -0.7652047 0.1135073 0.6634486 -0.7395622 0.2748482 0.7758792 -0.5678645 -0.01390349 0.521251 -0.8532902 -0.007587909 0.04146623 -0.9991112 0.3037772 0.483909 -0.8207018 0.4702225 0.773901 -0.4242266 0.40982 0.8561473 -0.3147373 0.2428285 0.8455636 -0.4754542 0.4488951 0.8511537 -0.2720858 0.5037329 0.8190507 -0.274607 0.4867959 0.8217761 -0.2961654 0.329217 0.7768956 -0.5367023 0.3383269 0.7710314 -0.5394864 0.4002734 0.7130714 -0.5755957 0.4656701 0.5910984 -0.6586002 0.3986803 0.5883453 -0.7034941 0.367156 0.6412522 -0.6737895 0.4972552 0.6415675 -0.5840619 0.3481888 0.6593067 -0.6663928 0.1334917 0.35536 -0.9251483 0.2763304 0.4952073 -0.8236574 0.1021388 0.3697749 -0.9234902 0.1560429 0.3101422 -0.9377967 0.1905974 0.3111584 -0.9310495 0.03108942 0.1633265 -0.9860822 -0.3151183 0.2200427 -0.9231911 0.1722566 0.6752974 -0.7171479 0.177408 0.6676943 -0.7229874 0.1942844 0.6041411 -0.7728306 0.2368852 0.6070761 -0.7585145 0.2684464 0.5537262 -0.7882411 0.03070712 0.1478255 -0.9885367 -0.02647161 0.1369557 -0.9902235 -0.05746656 0.2012337 -0.9778561 -0.10223 0.1916666 -0.9761214 -0.13576 0.2583757 -0.9564576 -0.1780439 0.2476909 -0.952339 -0.2161493 0.3188284 -0.922837 0.04413586 0.4771553 -0.8777101 0.2523344 0.5232459 -0.8139664 0.2784445 0.5303135 -0.8007723 0.3861778 0.5403937 -0.747557 0.6568443 0.7540264 0 0.7517961 0.6593061 -0.01086431 0.9941049 0.1084236 0 0.9712849 0.2376685 -0.01092296 0.9393504 0.342959 1.46501e-4 0.8164126 0.577469 -1.48225e-4 -0.9319434 0.3626041 0 -0.936707 0.3501116 -0.001417279 -0.919017 0.3942177 6.40862e-4 -0.9152286 0.402935 -1.88244e-4 -0.9142611 0.4051258 0 -0.9239102 0.3826096 0 -0.9226831 0.3855594 2.98028e-4 -0.9468481 0.3216807 -5.90661e-4 -0.9457039 0.3250295 -1.63091e-4 -0.9708425 0.2397185 1.0592e-4 -0.9775786 0.2105637 -0.001758992 -0.9911963 0.1323885 0.001832485 -0.9973635 0.07254993 -0.001627922 -0.9995735 0.02920299 0 0.4161567 0.5942682 -0.6882289 0.1050065 0.1410797 -0.9844136 0.1497439 0.2340705 -0.9606184 0.0566228 0.08086502 -0.9951155 0.3229419 0.4926431 -0.8080913 0.2992756 0.4420781 -0.8455775 0.2518043 0.3626935 -0.8972447 0.3090107 0.4417964 -0.8422164 0.3451364 0.5478687 -0.7620505 0.3346782 0.5191656 -0.7864208 0.5646491 0.8063919 -0.1757943 0.5502848 0.8227686 -0.1422625 0.5466348 0.7694487 -0.3303622 0.4712776 0.6980586 -0.5390842 0.4697828 0.6890633 -0.5518116 0.4362551 0.6261273 -0.6462556 0.1008337 0.1440041 -0.9844265 0.5646469 0.8063936 -0.1757939 0.1008322 0.1440041 -0.9844266 0.3092356 0.4416363 -0.8422178 0.3092395 0.4416369 -0.8422161 0.4830771 0.6899032 -0.5391383 0.4830764 0.6899021 -0.5391404 0.5646451 0.8063936 -0.1757994 0.133107 0.0145176 -0.9909954 0.3160809 0.7875468 -0.5290209 0.6467254 0.7424104 -0.1748515 0.7768571 0.6155316 -0.1327175 0.8092675 0.5724229 -0.1319777 0.8092704 0.5724217 -0.1319656 0.9311345 0.3399589 -0.1319718 0.9311352 0.3399571 -0.1319712 0.9853599 0.1074727 -0.132346 0.9853606 0.1074614 -0.1323508 0.9004514 0.0982064 -0.4237251 0.7628322 0.08320355 -0.641221 0.7183757 -0.03006237 -0.6950055 0.133107 0.0145176 -0.9909954 0.3051175 0.03327828 -0.9517331 0.4349682 -0.004746615 -0.9004334 0.4638596 0.05059385 -0.8844629 0.6418716 0.07000935 -0.7636096 0.1096286 0.07754278 -0.9909434 0.1096289 0.07754349 -0.9909433 0.350131 0.2476575 -0.9033682 0.3501306 0.2476562 -0.9033688 0.5798375 0.4101346 -0.7039731 0.5798342 0.4101277 -0.7039798 0.1261388 0.04605329 -0.9909431 0.1261352 0.04605209 -0.9909436 0.4028558 0.1470817 -0.9033683 0.4028567 0.1470834 -0.9033675 0.6671511 0.2435771 -0.7039742 0.6671525 0.2435757 -0.7039734 0.9004554 0.0982148 -0.4237143 0.8513032 0.3108062 -0.4227088 0.8513079 0.3108144 -0.422693 0.7398846 0.5233387 -0.4227144 0.7398925 0.5233402 -0.4226987 0.8036961 0.4274148 -0.4139916 0.3832684 0.608471 -0.6948873 0.4619604 0.3222482 -0.8262862 0.2434111 0.3605467 -0.9004206 0.157683 0.1036753 -0.9820324 0.08792078 0.1009303 -0.9910011 -1 -9.67684e-6 0 -1 2.40689e-6 0 -1 -2.11102e-5 0 -1 0 0 -1 1.41498e-6 0 -1 7.78669e-6 0 -1 -1.00353e-6 0 -1 1.84871e-6 0 -1 -2.1114e-6 0 -1 2.71212e-6 0 -1 -2.98838e-7 0 -1 -4.91455e-6 0 -1 1.6429e-6 0 -1 2.24139e-6 0 -1 -1.88058e-7 0 -1 -1.69591e-6 0 -1 0 0 -1 -1.26196e-7 0 -1 -7.31048e-7 0 -0.8402453 7.65148e-5 -0.5422067 -0.8610028 0 -0.5086004 -0.8984295 0 -0.4391179 -0.9031277 -1.44672e-4 -0.4293721 -0.981469 3.79664e-4 -0.1916208 -0.9392504 0.005882263 -0.3431823 -0.9858708 0 -0.1675078 -0.7280642 -1.26429e-5 -0.685509 -0.771332 3.39071e-4 -0.6364329 -0.7947854 8.00027e-4 -0.60689 -0.7934935 8.30637e-4 -0.6085784 -0.809119 4.97762e-4 -0.5876448 -0.1962463 0 -0.9805547 -0.159656 0.001415371 -0.9871717 -0.4433452 -7.30479e-4 -0.8963506 -0.4097142 0 -0.9122139 -0.61063 0 -0.7919161 -0.5762714 0.001100301 -0.8172577 -0.6780064 1.94958e-5 -0.7350561 0.6477419 -0.7584114 0.07240724 0.2574974 -0.7468279 0.6131421 0.4753258 -0.6842555 0.553046 0.6003993 -0.607048 0.5205896 0.5876939 -0.6682164 0.4561829 -0.5398032 -0.6204038 0.5689567 -0.3413871 -0.748272 0.5688091 -0.7421995 -0.5296218 0.4106589 -0.5029349 -0.6468191 0.5733076 -0.3602705 -0.7270513 0.5844671 0.1386947 -0.7797162 0.6105789 -0.09230619 -0.7406033 0.6655722 0.1035199 -0.7654292 0.6351394 -0.9702732 -0.1979981 0.1391648 -0.9879319 -0.04201674 0.1490813 -0.981814 -0.1216276 0.1457669 -0.9327356 -0.2899779 0.2142829 -0.7777032 -0.5069701 0.3716979 -0.9681006 -0.2254071 0.1094217 -0.9698409 -0.2186486 0.1077105 -0.7266564 -0.6185339 0.2989757 -0.7404587 -0.6032059 0.2964179 -0.3088369 -0.8566604 0.4132225 -0.3396334 -0.8438917 0.4153265 0.1818903 -0.8862822 0.4259343 0.1380683 -0.8880796 0.4384653 0.6300968 -0.7010209 0.3339875 0.5848556 -0.7262926 0.3611689 -0.9673898 -0.2501832 0.03956592 -0.9680428 -0.2476186 0.03972685 -0.7211444 -0.6843436 0.1078178 -0.7262312 -0.6788067 0.1086731 -0.2973818 -0.9431638 0.1483448 -0.30847 -0.939237 0.1505997 0.1970584 -0.9685645 0.1518252 0.1816353 -0.9708926 0.1561288 0.7211046 -0.6847683 0.1053591 0.6330243 -0.7494911 0.1937614 -0.1633297 -0.9816334 0.09858685 -0.4483954 -0.892902 0.04083538 -0.1954857 -0.8478728 0.4928458 -0.04726809 -0.7425307 0.6681421 0.3555732 -0.3219516 0.8774479 0.2604566 -0.4395931 0.8596048 -0.08613473 -0.7403607 0.6666685 -0.6255055 -0.6856088 -0.3724024 -0.6834749 -0.6037166 -0.4103514 -0.6720458 -0.6215689 -0.4025004 -0.6299429 -0.6887844 -0.3588147 -0.6536792 -0.7136734 -0.251742 -0.3610515 -0.930521 -0.06142097 0.5835814 -0.6538081 0.4816302 0.5326023 -0.6887971 0.4918267 -0.698893 -0.6705034 -0.2489454 -0.6609011 -0.6834003 -0.3101189 -0.663374 -0.6802255 -0.3118145 -0.6271391 -0.6920125 -0.3575127 -0.615449 -0.7137352 -0.3343722 -0.6214861 -0.687023 -0.3765029 -0.4132631 -0.9081235 -0.06727135 -0.4068067 -0.910217 -0.07754629 -0.4060688 -0.9105839 -0.07710516 -0.3959821 -0.9138575 -0.0897932 -0.3996657 -0.9119721 -0.09259831 -0.428767 -0.9012403 -0.06264859 -0.4474141 -0.8907394 -0.08002495 -0.5104852 -0.8595425 -0.02432483 -0.4717565 -0.880705 -0.0424785 -0.4777202 -0.8777055 0.03763753 -0.4690975 -0.8826307 0.03017711 -0.2091414 -0.8391191 0.5021345 -0.3049803 -0.911729 0.2752039 -0.2330884 -0.9189287 0.3181823 -0.2066193 -0.9325964 0.2959265 -0.2057185 -0.9327281 0.296139 -0.1573142 -0.9543911 0.2537518 -0.1534878 -0.9542518 0.256603 -0.09454363 -0.9759491 0.1964305 -0.09680074 -0.976018 0.1949836 -0.07780146 -0.982176 0.1711062 -0.08334237 -0.9822034 0.1683174 -0.0735709 -0.9855292 0.1527076 0.03916674 -0.9862323 0.1606613 -0.007265508 -0.7468172 0.6649897 0.04507231 -0.7784688 0.6260631 0.0435099 -0.7792337 0.6252214 0.09871542 -0.8086532 0.5799443 0.09782934 -0.808807 0.5798798 0.1541771 -0.8342612 0.5293748 0.1506789 -0.8360845 0.5275021 0.227271 -0.8637857 0.4496914 0.2190347 -0.8680135 0.4456191 0.2639124 -0.8825129 0.3892574 0.2540723 -0.8870655 0.3854374 0.2887584 -0.8986826 0.3301335 0.233071 -0.916554 0.3249719 0.5593181 -0.6456183 0.5199428 0.6001138 -0.5726238 0.5585387 0.5408137 -0.6239901 0.564054 0.4962943 -0.6091377 0.6185817 0.507894 -0.5962816 0.6216848 0.4276167 -0.5677143 0.7034518 0.4367277 -0.5579366 0.7056739 0.3829808 -0.5328292 0.7545986 0.3854166 -0.531718 0.7541421 0.3331035 -0.5046237 0.7964904 0.3373652 -0.5006227 0.7972213 0.2652019 -0.4551731 0.8499914 0.1388089 -0.5423799 0.8285868 -0.2810626 -0.2400321 -0.9291869 -0.6917952 -0.5117155 -0.5094769 -0.5341175 -0.4095177 -0.7396039 -0.5660793 -0.4198834 -0.7094026 -0.5883654 -0.4229605 -0.6891521 -0.6032075 -0.4214339 -0.6771516 -0.6356076 -0.4153952 -0.6507303 -0.4575536 -0.3090776 -0.8337361 -0.3781198 -0.2882451 -0.8797388 -0.4055082 -0.2654253 -0.8747072 -0.3136228 -0.2610775 -0.9129509 -0.3657295 -0.283968 -0.8863432 -0.3969147 -0.2697126 -0.8773334 -0.04464489 -0.03813481 -0.9982748 -0.1561718 -0.09159833 -0.9834736 -0.2532314 -0.1066798 -0.9615058 -0.2889802 -0.1045667 -0.9516072 -0.6723375 -0.3817819 -0.6341962 -0.6035594 -0.4599878 -0.6512506 -0.6302869 -0.4230687 -0.6509618 -0.5703229 -0.4334753 -0.6977327 -0.6104274 -0.4039411 -0.6813297 -0.6363585 -0.3621495 -0.6810988 -0.6346493 -0.3543536 -0.6867706 -0.6659432 -0.2915866 -0.6866564 -0.6628839 -0.2841923 -0.6926902 -0.689477 -0.2116788 -0.6926858 -0.685944 -0.2054198 -0.6980571 -0.5072548 -0.154636 -0.8478091 -0.3839796 -0.3117669 -0.8691151 -0.4010671 -0.2887561 -0.8693476 -0.3916239 -0.2655888 -0.8809616 -0.411229 -0.2342905 -0.8809078 -0.4095392 -0.2289651 -0.8830927 -0.4298012 -0.1884346 -0.8830422 -0.4271931 -0.1834098 -0.8853626 -0.4350628 -0.1623675 -0.8856394 -0.372229 -0.1120633 -0.9213508 -0.1450275 -0.1132434 -0.9829257 -0.1408585 -0.1183041 -0.982936 -0.1352275 -0.1055011 -0.9851818 -0.1380336 -0.10169 -0.9851934 -0.1344743 -0.09325426 -0.9865193 -0.1419063 -0.08141452 -0.9865264 -0.1412782 -0.07951897 -0.9867712 -0.1482883 -0.06552129 -0.9867713 -0.1473357 -0.06373333 -0.9870311 -0.1532692 -0.04756361 -0.9870392 -0.1522377 -0.04607504 -0.9872695 -0.6989591 -0.1533063 -0.6985366 -0.6623197 -9.9786e-4 -0.7492207 -0.5180003 -0.1108318 -0.8481699 -0.2309045 -0.04974585 -0.9717039 -0.2003564 0.1697599 -0.9649035 -0.3794133 -0.08248937 -0.9215428 -0.2322627 -0.03868287 -0.9718835 -0.2326105 -0.04082041 -0.971713 -0.6455453 -0.105438 -0.7564087 -0.646277 -0.1114136 -0.754926 -0.8384564 -0.06525367 -0.5410479 -0.8079122 -0.05458629 -0.5867694 -0.8572732 -0.09290063 -0.5064112 -0.7694357 -0.07007318 -0.6348689 -0.1383822 -0.4987356 -0.8556362 -0.516658 -0.4429358 -0.7327159 -0.4095416 0.02890938 -0.9118334 -0.6304467 -0.1893237 -0.7527906 -0.6615562 -0.2189714 -0.7172134 -0.7222625 -0.1259768 -0.6800491 -0.7920138 -0.06100726 -0.6074474 -0.8901059 -0.1692066 -0.4231793 -0.9852741 0.03479236 -0.1674057 -0.9384726 -0.041103 -0.3428992 -0.8880447 -0.1346089 -0.4396103 -0.889615 -0.1742515 -0.422163 -0.8901589 -0.1748028 -0.4207865 -0.9875231 -0.05995053 -0.1456158 -0.9875829 -0.06014859 -0.145128 -0.888656 -0.1169682 -0.4434062 -0.8896192 -0.1182587 -0.4411266 -0.9874145 -0.04009431 -0.1529873 -0.98752 -0.04056131 -0.1521812 -0.9999979 -0.001689076 -0.001191735 -0.9978586 -0.05203831 -0.03962862 -0.9822384 -0.1097389 -0.1522015 -0.8482286 -0.3505476 -0.3970199 -0.8981792 -0.3292369 -0.2913373 -0.9472984 -0.2832621 -0.1496278 -0.9835637 -0.07528764 -0.1641169 -0.9872327 -0.1213296 -0.1032034 -0.9874306 -0.1211853 -0.1014649 -0.9874799 -0.1089594 -0.1140674 -0.9875508 -0.1092184 -0.1132022 -0.98752 -0.09642136 -0.1245276 -0.9875832 -0.0964936 -0.1239696 -0.9875865 -0.07887548 -0.1358367 -0.9875829 -0.07886761 -0.1358675 -0.8873824 -0.3796176 -0.2616165 -0.8870684 -0.3508162 -0.3000631 -0.8888774 -0.3504112 -0.2951427 -0.8892002 -0.3154487 -0.3313841 -0.889851 -0.3161678 -0.3289426 -0.889591 -0.2793189 -0.3613986 -0.8901678 -0.2795145 -0.3598236 -0.8901808 -0.2288044 -0.3939883 -0.8901467 -0.2287824 -0.3940781 -0.9778252 -0.1243148 0.1685343 -0.9639656 -0.2415912 0.1113737 -0.9999946 -0.003009259 0.001352965 -0.9976856 -0.06180351 -0.02834957 -0.9913741 -0.1032162 0.08077061 -0.9791803 -0.2002597 0.03319972 -0.9645708 -0.2408404 0.1076996 -0.92552 -0.3767402 0.038464 -0.8529401 -0.4610847 0.2447332 -0.8088777 -0.5563877 0.1901313 -0.7747611 -0.6049005 0.1839581 -0.4957502 -0.7909945 0.3585518 -0.580698 -0.6804509 0.4469637 -0.6451303 -0.6103618 0.4596362 -0.6214186 -0.6527823 0.4332602 -0.7689265 -0.4739026 0.4291487 -0.8528603 -0.5049667 0.1328079 -0.9239872 -0.2920317 0.2469113 -0.8292082 -0.5446422 -0.1256135 -0.9974606 -0.07115787 -0.002980768 -0.9852507 -0.1640523 -0.04866313 -0.9836915 -0.1772062 -0.03080761 -0.9452648 -0.3112255 -0.09804701 -0.9361959 -0.3491194 -0.04065752 -0.8897535 -0.4455711 -0.09902071 -0.8802765 -0.4634914 -0.1014346 -0.8297581 -0.537611 -0.14992 -0.7578139 -0.6481688 0.07480275 -0.6881066 -0.6862542 0.2357213 -0.7207222 -0.6807711 0.1308062 -0.5382099 -0.7363111 0.410093 -0.4458563 -0.7110763 0.5436754 -0.4250746 -0.7218319 0.5461413 -0.1466071 -0.7871398 0.5990971 0.1553117 -0.8797143 0.4494232 -0.2288076 -0.9498715 0.2130522 -0.4223088 -0.8574772 0.2939186 -0.664762 -0.7467116 -0.02265846 -0.7554163 -0.6225243 -0.2044745 0.1058211 -0.7630337 0.6376374 -0.1117508 -0.8184364 0.5636255 -0.7338015 -0.6512922 -0.1932715 -0.706139 -0.6709842 -0.2261593 -0.6730968 -0.70678 -0.2177218 -0.4377206 -0.8958545 0.07645469 -0.4576877 -0.8883371 0.03713887 -0.5366675 -0.8334316 0.1318328 -0.5460098 -0.832852 0.09072589 -0.07834029 -0.9300534 0.358976 -0.1292347 -0.948065 0.2906394 -0.2362238 -0.8751957 0.4221743 -0.258077 -0.8877556 0.3811643 0.4076162 -0.6302812 0.6607531 0.2912814 -0.8846552 0.3640612 0.1863613 -0.8220794 0.5380103 -0.8579297 0.5137671 0 -0.9201774 0.3210794 0.2240126 -0.9127117 0.4086044 0 -0.842608 0.5385265 0.00107634 -0.8581148 0.5134574 7.10452e-4 -0.05902981 0.9982521 0.002896726 -0.2047944 0.9788051 0 -0.2204341 0.9754019 4.3868e-4 -0.3682767 0.9297162 1.28458e-5 -0.580011 0.8146088 -8.50098e-5 -0.5250364 0.8510791 0.001138269 -0.7288008 0.6847257 -3.1421e-4 1 2.78959e-6 0 1 -4.74284e-6 0 0.7048456 0.7093608 0 0.6607836 0.750549 -0.006444513 0.8421443 0.5392367 0.004119873 0.939214 0.3433324 0 0.9938843 0.1104264 0 0.9999337 0.00508809 0.01034283 0.9995731 0.02804309 0.008200168 0.9979481 0.06380188 0.005397856 0.9963686 0.08504861 0.004071831 0.9952923 0.09686094 0.003356099 0.9937674 0.1114439 0.002599954 0.9546311 0.2977215 -0.00643301 0.9357476 0.3526694 -9.73917e-4 0.8153292 0.578997 8.21592e-4 0.8201526 0.5721447 0 0.9742148 0.2256228 0 0.9653301 0.2599335 0.02392435 0.9531984 0.2961919 0.06068885 0.9026631 0.4262588 0.05918508 0.8709904 0.4830342 0.08974242 0.890868 0.4518823 0.04644078 0.9504278 0.3030864 0.06946676 0.9550652 0.2916831 0.05264627 0.9528414 0.3025572 -0.02350527 -1 -1.25705e-6 0 -1 -7.28589e-6 0 -1 0 6.20961e-6 -1 -4.18349e-6 3.5219e-6 -1 0 -3.52516e-6 -1 -3.96432e-6 0 0.9994245 0.0339235 0 0.9480148 0.1806328 -0.2619919 0.8847183 0.1913994 -0.4250175 0.9398162 0.3172841 -0.1267921 0.9103733 0.4065243 0.07719135 0.8953189 0.4454256 0 0.8724961 0.4886212 0 0.8502635 0.5255438 -0.0292539 0.831236 0.5479034 -0.09406703 0.8069522 0.5904775 0.01283448 0.7576054 0.6526156 -0.01126694 0.6876156 0.708562 0.158508 0.6333716 0.7575714 -0.1578803 0.5659485 0.8241723 0.0210343 0.5128307 0.8583588 -0.01500344 0.5032456 0.8636347 -0.02965396 0.4041679 0.9098247 0.09416776 0.3477907 0.9249461 -0.1533506 0.2612151 0.9650579 0.02073955 0.1466013 0.9881678 -0.0450828 0.1860868 0.9752136 0.119709 0.1099787 0.993934 0 -0.3316875 0.9433894 0 -0.3729365 0.9057007 -0.2015556 -0.1983457 0.9453272 0.2588734 -0.2370287 0.9618592 0.1365447 -0.1450459 0.9892153 -0.02037417 -0.07295709 0.9971461 0.01941752 -0.007229208 0.996647 -0.08150261 -0.01230984 0.9955058 -0.09389781 0.03918606 0.9992319 0 0 -0.1797009 0.9837214 0 -0.179702 0.9837212 0 -0.5158937 0.8566527 0.05007857 -0.5152498 0.8555758 0.05008667 -0.5152483 0.8555761 0.1483815 -0.495956 0.8555762 0.1483759 -0.4959588 0.8555755 0.01746469 -0.1796725 0.9835715 0.01746529 -0.1796746 0.9835711 0.0517441 -0.1729468 0.9835711 0.05173766 -0.1729459 0.9835716 -0.4109867 -0.5209812 0.7481101 -0.4146398 -0.5205656 0.7463815 -0.4106205 -0.1820964 0.8934382 -0.4200153 -0.1813779 0.8892071 -0.3512483 -0.5288531 0.7726184 -0.3529762 -0.5293471 0.7714917 -0.3750442 -0.184813 0.9083976 -0.3797038 -0.1868594 0.9060401 -0.2678272 -0.5313864 0.8036774 -0.2665933 -0.5300046 0.8049989 -0.308075 -0.1856087 0.9330806 -0.307801 -0.1853067 0.9332309 -0.1954381 -0.5306887 0.8247265 -0.1960188 -0.5314269 0.8241131 -0.2277755 -0.1855331 0.9558744 -0.2279033 -0.1856995 0.9558116 -0.04744404 -0.5772387 0.8151962 -0.0772832 -0.2517217 0.9647091 -0.05311393 -0.4210575 0.9054776 -0.04645603 -0.07865589 0.9958188 -0.0730893 -0.01223224 0.9972504 0.189533 -0.5038866 0.8427191 -0.0662198 -0.5246476 0.8487403 -0.07034355 -0.5263913 0.8473275 -0.1167992 -0.5268675 0.841884 -0.1194065 -0.5302159 0.8394125 0.1711096 -0.1730254 0.9699401 -0.08607751 -0.1832183 0.9792966 -0.08680135 -0.1835611 0.9791685 -0.141769 -0.1843511 0.9725822 -0.1422582 -0.1850212 0.9723836 -0.05140513 -0.01160913 0.9986105 -0.02236825 -0.5182394 0.8549431 -0.1377683 -0.5769973 0.8050428 -0.03726702 -0.4205734 0.9064929 -0.03715193 -0.1807002 0.9828364 -0.1602228 -0.2528399 0.9541492 -0.05673664 -0.07896113 0.9952619 -0.007528126 -0.515879 0.8566284 -0.01086062 -0.5179798 0.8553239 -0.01447612 -0.1796805 0.9836186 -0.01526564 -0.1802254 0.9835069 -0.06157296 -0.01905328 0.9979207 -0.02874571 -0.05259138 0.9982023 -0.04459363 -0.03532123 0.9983807 -0.06762695 -0.01211947 0.997637 -0.1010477 -0.04569458 0.9938317 -0.09471273 -0.05174434 0.9941591 -0.02381545 -0.0572021 0.9980786 -0.0568422 -0.09042036 0.9942803 -0.02437388 -0.124955 0.991863 -0.08214986 -0.1785768 0.9804906 -0.04790908 -0.2199279 0.974339 -0.1453625 -0.05047649 0.9880901 -0.176617 -0.0795542 0.9810594 -0.1926043 -0.05719155 0.9796085 -0.2592143 -0.1157069 0.9588639 -0.2760009 -0.0882737 0.9570952 -0.09706801 -0.2631677 0.9598545 -0.1570497 -0.226233 0.9613293 -0.09711658 -0.3268343 0.9400786 -0.8232406 -0.4007341 0.4021034 -0.6238536 -0.5530946 0.5521714 -0.6772693 -0.1499372 0.7202952 -0.8214641 0.1038311 0.5607279 -0.8647137 -0.09121316 0.4939134 -0.9739189 -0.1124569 0.1970673 -0.5157024 -0.5239299 0.6779001 -0.4784603 -0.538412 0.6936774 -0.4095613 -0.5343709 0.7393965 -0.7159219 -0.5560339 0.4222348 -0.661495 -0.5281988 0.5323819 -0.6029418 -0.4256538 0.6747445 -0.9734157 -0.07143092 0.2176223 -0.9004461 -0.321629 0.2928341 -0.8725716 -0.3482474 0.3425532 -0.3519504 -0.5244131 0.7753207 -0.3620771 -0.530577 0.7664127 -0.479209 -0.1858593 0.8577968 -0.8334984 -0.3694358 0.4108501 -0.7833069 -0.3100318 0.538805 -0.7833084 -0.3100304 0.5388035 -0.648353 -0.2438364 0.7212367 -0.6483585 -0.2438378 0.7212312 -0.4442892 -0.20415 0.8723129 -0.5160685 0.3044046 0.8006318 -0.869805 -0.005280673 0.4933673 -0.918267 -0.1417149 0.3697333 -0.924961 -0.1185564 0.3610978 -0.9514836 -0.03994023 0.3050965 -0.8924561 -0.03643661 0.4496605 -0.8725053 -0.009869337 0.488505 -0.9691985 -0.2136636 0.122484 -0.942302 -0.2562959 0.215359 -0.922816 -0.2619287 0.282496 -0.9000725 -0.261597 0.3484773 -0.9024133 -0.2122303 0.3749783 -0.9088171 -0.1769191 0.3778243 -0.8432422 -0.4779718 0.2459384 -0.9442769 -0.04381692 0.3262229 -0.8946335 -0.1083679 0.4334599 -0.8566432 -0.1293878 0.4994209 -0.8544111 -0.1313388 0.5027243 -0.8048703 -0.1311531 0.5787771 -0.7763435 -0.1488856 0.6124737 -0.7215407 -0.1455028 0.6769107 -0.7058085 -0.1526173 0.6917676 -0.6538417 -0.161301 0.7392382 -0.6318432 -0.1694228 0.7563533 -0.5771928 -0.1631413 0.8001459 -0.5132791 -0.1804386 0.839039 -0.4642729 -0.1728087 0.8686701 -0.9832082 -0.1759943 0.04824399 -0.8835949 -0.3509092 0.3100367 -0.8758887 -0.35633 0.3253429 -0.8383102 -0.3894146 0.3815656 -0.8247617 -0.3905065 0.40899 -0.758683 -0.43221 0.4874367 -0.7427671 -0.4321827 0.5113856 -0.6902059 -0.4568383 0.5611725 -0.6731667 -0.4604977 0.5786092 -0.614513 -0.4820443 0.6245054 -0.5975376 -0.4808728 0.6416464 -0.4978917 -0.5083412 0.702633 -0.4821529 -0.5065391 0.7148054 -0.1294713 -0.3547839 0.9259405 -0.5598387 -0.151304 0.8146703 -0.5931808 -0.03932595 0.8041083 -0.6771357 -0.1889201 0.7111938 -0.7403161 -0.02858352 0.6716511 -0.810414 -0.2176001 0.543948 -0.8716871 -0.03991007 0.4884352 -0.9095344 -0.2490369 0.3327578 -0.9591224 -0.06183069 0.2761542 -0.3868355 -0.184872 0.9034272 -0.4359579 0.01155 0.8998929 -0.30234 -0.2244302 0.9264025 -0.3592798 -0.3008822 0.8833957 -0.3857741 -0.2454565 0.8893422 -0.4433343 -0.3460065 0.8268822 -0.4983145 -0.2661924 0.8251208 -0.5479623 -0.3976608 0.735937 -0.6143721 -0.3079537 0.7264375 -0.6431171 -0.4611243 0.6113631 -0.7141254 -0.3660312 0.596696 -0.1051289 -0.3922962 0.9138116 -0.1359197 -0.4335157 0.8908367 -0.1404001 -0.4267138 0.8934221 -0.1695408 -0.4769389 0.8624299 -0.1836619 -0.4632755 0.8669741 -0.2095653 -0.5308439 0.82115 -0.2334812 -0.5115523 0.8269225 -0.2496797 -0.5945701 0.7642949 -0.2827485 -0.5713136 0.7704895 0 -0.06742805 0.9977242 -0.004836618 -0.1825281 0.9831887 0.002339959 -0.2798748 0.9600337 -0.002922892 -0.5183519 0.8551626 0 -0.5459774 0.8377999 -0.00509727 -0.1828267 0.983132 0.2724432 -0.003752827 0.9621646 0.1727764 -0.07127803 0.9823787 -0.01040041 -0.2522407 0.9676086 -0.009818315 -0.4112857 0.9114537 0.04250687 -0.5221446 0.8517971 -0.007530331 -0.5584899 0.8294772 -0.01876688 -0.6620909 0.7491886 -0.007501542 -0.5202829 0.8539611 -0.004216611 -0.518351 0.8551576 -0.002219319 -0.1828783 0.9831331 -0.001669049 -0.1825298 0.9831989 -0.05548405 -0.4100549 0.9103717 -0.01301115 -0.2521889 0.9675906 -0.04290354 -0.6615921 0.7486356 -0.09907978 -0.5550621 0.8258871 -0.4648467 -0.4166564 0.7812267 -0.08396923 -0.5196155 0.8502641 -0.06769865 -0.4971892 0.864997 -0.1163511 -0.5317726 0.8388566 -0.1383287 -0.5600196 0.8168497 -0.1636732 -0.1867488 0.9686775 -0.1622642 -0.1861894 0.9690222 -0.09692466 -0.186384 0.9776843 -0.09483039 -0.1829476 0.9785385 -0.648378 -0.137426 0.7488125 -0.04110014 -0.06718957 0.9968934 -0.2320561 -0.1865816 0.9546399 -0.1809839 -0.186636 0.9656147 -0.2275207 -0.1920946 0.9546382 -0.1967836 -0.5311076 0.8241366 -0.1956198 -0.5294339 0.8254894 -0.2680482 -0.5302566 0.8043496 -0.2717432 -0.5347427 0.8001287 -0.3166269 -0.1856766 0.9301998 -0.3176475 -0.1868677 0.9296132 0.9999972 -9.31897e-4 0.002213239 0.9989702 -0.02207666 0.03963768 0.9989008 -0.01180231 0.04536473 0.9935768 -0.04553729 0.1035929 0.9938512 -0.037144 0.1043082 0.9783161 -0.08617264 0.1883404 0.9788887 -0.06622624 0.1933678 0.9402205 -0.1372367 0.3116912 0.9429922 -0.1145789 0.3124697 0.9043424 -0.1654776 0.3934234 0.910974 -0.1516456 0.3835753 0.8619726 -0.2038502 0.4641642 0.8696476 -0.1782644 0.4603639 0.7838854 -0.2530601 0.566996 0.7963562 -0.2253788 0.5612677 0.7245607 -0.2791509 0.6301481 0.7435609 -0.2607355 0.6157388 0.6619756 -0.314553 0.680327 0.681558 -0.2850146 0.6739774 0.5535278 -0.3606917 0.7506722 0.57872 -0.3299681 0.7457911 0.4717945 -0.3877179 0.7918869 0.5044456 -0.3648425 0.7825757 0.3893973 -0.4210835 0.8191815 0.4217979 -0.3898651 0.8185915 0.2625225 -0.4627156 0.8467445 0.2989812 -0.4315581 0.8510981 0.999993 6.4562e-4 0.003694355 0.9991064 -0.01882737 0.03784298 0.9979599 0.006419539 0.0635215 0.9927983 -0.02468067 0.1172283 0.9921593 -0.002812802 0.1249486 0.9766796 -0.05159848 0.20841 0.9714905 -2.73986e-4 0.2370785 0.9318646 -0.07153832 0.3556835 0.929166 -0.01188933 0.3694714 0.8836625 -0.07029676 0.4628164 0.899257 -0.03132724 0.4362975 0.8376648 -0.09716904 0.5374718 0.8455327 -0.0280314 0.5331873 0.7430541 -0.1163188 0.6590452 0.7630313 -0.04036277 0.6451 0.662647 -0.1136912 0.7402523 0.7143864 -0.06055688 0.6971263 0.5948305 -0.1397384 0.7916123 0.6352176 -0.05730962 0.7702041 0.4634588 -0.1574592 0.8720164 0.5209614 -0.07080703 0.8506384 0.3565644 -0.1569051 0.9210009 0.4481768 -0.09061825 0.8893402 0.2654511 -0.1798935 0.9471928 0.3471318 -0.09078943 0.9334114 0.1140255 -0.1953347 0.9740855 0.2104718 -0.1058325 0.9718545 0.7275656 -0.2994129 0.6172522 0.7601115 0.01450246 0.6496309 0.3930234 -0.09528988 0.9145778 0.6415861 -0.1423454 0.7537274 0.6350422 -0.1278852 0.7618182 0.7303852 -0.1483297 0.6667352 0.8257231 -0.05610561 0.5612787 0.8193547 -0.1800042 0.5442944 0.9083328 -0.0359829 0.4166975 0.9580878 -0.1118178 0.263751 0.9378497 -0.1041579 0.3310427 0.9743813 -0.02498197 0.2235108 0.9781337 0.09660947 0.1841771 0.9663969 0.1973123 0.1647573 0.9479734 0.2744938 0.1612443 0.7883272 -0.1850331 0.5867735 0.7733135 -0.187337 0.6057155 0.8358184 -0.1357645 0.5319545 0.8591191 -0.1771028 0.4801553 0.9052686 -0.1791191 0.3852341 0.2868539 -0.5286476 0.7989035 0.4155671 -0.51124 0.7522884 0.499179 -0.3615777 0.7874528 0.4662094 -0.3675289 0.8047181 0.5452212 -0.3402014 0.7661573 0.5496013 -0.3440724 0.7612836 0.6697263 -0.3630403 0.6478182 0.5230029 -0.1025859 0.8461349 0.3973762 -0.1037907 0.9117674 0.3401055 -0.3098313 0.8878811 0.3401045 -0.3098316 0.8878814 0.2620086 -0.5129687 0.817444 0.1632184 -0.545549 0.8220318 0.1433497 -0.05589342 0.9880926 0.1369633 -0.06679469 0.9883216 0.1172382 -0.2779461 0.9534156 0.117243 -0.2779496 0.953414 0.08360862 -0.5322483 0.8424496 0.05299091 -0.5452084 0.8366242 -0.9161731 0.05529236 0.3969508 -0.9102148 -0.2892722 0.2963628 -0.7046999 -0.6916651 0.158106 -0.4843693 -0.8693107 0.09841376 -0.6525102 -0.02751159 0.7572804 -0.7142841 -0.236819 0.6585705 -0.7095174 -0.3588918 0.6064503 -0.8068034 -0.1076749 0.5809257 -0.86258 0.05055427 0.5033888 -0.1717014 0.004306733 0.9851397 -0.2794106 -0.1154481 0.953206 -0.3536948 -0.2828672 0.8915639 -0.4338898 -0.03414791 0.9003186 -0.5767869 0.04250448 0.8157881 -0.3519623 0.02463948 0.9356898 -0.3497628 0.01649749 0.9366931 -0.7455242 0.05895233 0.6638662 -0.7446633 0.05322062 0.6653152 -0.967593 0.08012157 0.2394671 -0.9676012 0.07737475 0.2403353 -0.3572516 0.04602688 0.9328734 -0.3515751 0.02837145 0.9357296 -0.7438659 0.1096408 0.6592742 -0.7417672 0.09337699 0.6641251 -0.9605279 0.1471691 0.2360667 -0.961245 0.1356683 0.240005 1.66159e-6 0 1 -2.41762e-6 0 1 0.2586072 -0.03980422 0.9651622 0.2586176 -0.03980463 0.9651594 0.6061085 -0.09328699 0.7898926 0.6743649 -0.2127063 0.7070984 0.7875043 -0.1212093 0.6042726 0.8884468 -0.1367466 0.4381356 0.9425274 -0.2123501 0.2579724 0.9697976 -0.1492655 0.1929058 0.2346706 -0.1157273 0.9651616 0.2346751 -0.1157303 0.9651603 0.6378771 -0.3145678 0.7029651 0.6378901 -0.3145709 0.702952 0.8669832 -0.4275462 0.2560166 0.8669852 -0.4275488 0.2560057 0.9333887 0.281403 0.2227061 0.6154573 0.509541 0.6013156 0.9890607 -0.07757371 0.1254647 0.9830064 -0.1493384 0.1067547 0.9313407 0.1006848 0.3499531 0.8970721 0.2083054 0.3897058 0.9356421 0.2881293 0.2038518 0.6349074 0.403484 0.6588576 0.8208969 0.4095079 0.3980346 0.8204541 0.4027599 0.4057583 0.9969977 0.0312044 0.07086724 0.9983913 -0.01163607 0.05549365 0.975124 0.1154733 0.1892064 0.948758 0.2022997 0.2427618 0.9036991 0.2588654 0.3410522 0.8201751 0.3854035 0.4228205 -0.312618 -0.9362424 0.160376 -0.1368926 -0.9785927 0.1536774 -0.4155405 -0.8789061 0.2342013 0.02078372 -0.9740419 0.2254117 0.1445876 -0.7106573 -0.6885207 -0.02662515 -0.9856061 0.166948 0.529926 -0.8476842 0.0246998 0.714234 -0.6774988 0.1756849 -0.7190693 -0.6823828 -0.1315034 -0.5175827 -0.8541752 0.04993104 -0.4550294 -0.8810297 0.1293634 -0.971045 -0.2388892 -0.001868128 -0.8774143 -0.4728173 0.0811668 -0.7731819 -0.6126248 0.1639537 -0.7398828 -0.6692296 0.06859499 -0.413756 -0.8805992 0.2309786 0.3168892 -0.9171115 0.2418428 0.3718128 -0.9274616 0.03962641 0.1987708 -0.9711291 0.1319037 -0.05361998 -0.9799405 0.1919417 -0.01902318 -0.06206446 0.9978909 -0.001968085 -0.3534287 0.9354595 -0.0126326 -0.424444 0.9053662 -0.06244975 -0.4764426 0.8769848 0.04709309 -0.4566801 0.8883838 0.01653075 -0.4768816 0.8788121 -0.02296257 -0.3822304 0.9237818 -0.01283973 -0.3667593 0.9302273 0.008904099 -0.2739878 0.961692 -0.04372972 -0.2790853 0.9592701 0.008531153 -0.1953891 0.9806887 -0.03821772 -0.1120489 0.9929675 -0.009539604 -0.0508725 0.9986596 -0.01002156 -0.04835915 0.9987798 -0.009028553 -0.04844033 0.9987853 -0.00991702 -0.04816859 0.99879 -0.01294642 -0.04880917 0.9987242 -0.009831368 -0.0483362 0.9987828 -0.009680807 -0.04856699 0.998773 -0.009655892 -0.0504865 0.9986782 -0.008241355 -0.05092269 0.9986687 -0.009020864 -0.05080419 0.998668 -0.01208138 -0.04893684 0.9987288 -0.01196908 -0.04864871 0.9987443 -0.01003557 -0.05014395 0.9986916 -0.009787201 -0.04849022 0.9987758 -0.01010859 -0.04833561 0.99878 0.00711286 -0.1067532 0.9942601 -0.02838909 -0.05160075 0.9982642 -0.01870226 -0.06237185 0.9978777 -0.01043301 -0.05254077 0.9985644 -0.009702801 -0.0509873 0.9986523 -0.001121461 -0.4974189 0.8675098 -0.01621645 -0.5277999 0.849214 -0.01774978 -0.5767609 0.8167202 -0.009317755 -0.5704861 0.8212545 -0.03581136 -0.6210566 0.7829472 -0.02842092 -0.6133014 0.7893375 -0.03738325 -0.6757619 0.7361714 -0.04069536 -0.6773276 0.7345551 -0.06663799 -0.7594601 0.647132 -0.06136077 -0.7584708 0.6488119 -0.09052848 -0.8070715 0.5834727 -0.1233736 -0.8306661 0.54293 -0.0666536 -0.8596988 0.5064341 -0.2251147 -0.8801903 0.4178378 0.1361585 -0.9402678 0.3120219 0.7423698 -0.6385505 0.2028312 0.5113868 -0.6288345 0.5857053 0.1766123 -0.49522 0.8506265 0.7160928 -0.5903392 0.372439 0.7406043 -0.5493415 0.3869487 0.4941567 -0.5228945 0.6945434 0.5526639 -0.417589 0.7212365 0.2641153 -0.3367822 0.9037815 0.2993414 -0.2728392 0.914305 0.07365947 -0.1588853 0.9845455 0.08989608 -0.1616377 0.9827471 0.1149021 -0.1132791 0.9868969 0.04020035 -0.08862537 0.9952535 0.04432797 -0.07920241 0.9958725 0.04400968 -0.07197415 0.9964352 0.04611301 -0.06652128 0.9967189 0.01678127 -0.06173837 0.9979513 0.01778894 -0.05637913 0.998251 0.01576983 -0.05219936 0.9985122 0.01615929 -0.05017006 0.99861 0.007644712 -0.04964137 0.9987379 0.007121086 -0.04507714 0.9989582 0.003121793 -0.04512339 0.9989766 0.001569688 -0.04197734 0.9991174 2.64665e-4 -0.04216027 0.9991108 -0.001909613 -0.03949439 0.9992181 -0.004049122 -0.03981471 0.9991989 -0.006201982 -0.03783214 0.999265 -0.004912436 -0.03702092 0.9993025 -0.01087766 -0.03583765 0.9992985 -0.008177995 -0.03347241 0.9994062 -0.01573443 -0.03432518 0.9992869 -0.01144033 -0.03003084 0.9994835 -0.02113056 -0.03305351 0.9992302 -0.01714527 -0.02420932 0.9995599 -0.02682775 -0.02960646 0.9992016 -0.02316689 -0.0207194 0.9995169 -0.03229302 -0.02689433 0.9991165 -0.02950936 -0.01622259 0.9994329 -0.03879266 -0.02347737 0.9989715 -0.03706526 -0.01095223 0.9992529 -0.04662889 -0.01929593 0.9987259 -0.04651081 -0.004737615 0.9989066 0.4720758 -0.5622045 0.6790217 0.49642 -0.5229712 0.6928696 0.3010873 -0.4410669 0.8454623 0.3488429 -0.3552515 0.8672399 0.1502426 -0.2695791 0.9511858 0.1899783 -0.1962369 0.9619768 0.04573047 -0.1310356 0.9903224 0.06446909 -0.09470224 0.993416 0.01971119 -0.07503247 0.9969863 0.02227073 -0.06901687 0.997367 0.02206438 -0.06436342 0.9976826 0.02323645 -0.06184875 0.997815 0.006024956 -0.0563603 0.9983924 0.006483495 -0.05404788 0.9985173 0.005494654 -0.05090099 0.9986886 0.005524039 -0.05046051 0.9987109 3.58061e-4 -0.04896062 0.9988007 5.27124e-4 -0.04688107 0.9989004 -0.002096891 -0.04638755 0.9989213 -0.002444922 -0.04470014 0.9989975 -0.005050837 -0.04454481 0.9989947 -0.004885375 -0.0429905 0.9990636 -0.006094455 -0.0429266 0.9990597 -0.007621884 -0.04153847 0.9991079 -0.007583379 -0.04145187 0.9991118 -0.01023215 -0.04076707 0.9991164 -0.009011268 -0.03917586 0.9991917 -0.01309943 -0.03972584 0.9991248 -0.01161253 -0.03719055 0.9992408 -0.01661247 -0.03899252 0.9991014 -0.01454621 -0.03407949 0.9993134 -0.02001219 -0.0370891 0.9991116 -0.01831316 -0.03218853 0.9993141 -0.02337485 -0.03564113 0.9990913 -0.02217268 -0.02975451 0.9993113 -0.027314 -0.03376287 0.9990566 -0.02668637 -0.02697473 0.9992799 -0.03194499 -0.03158462 0.9989905 -0.03238558 -0.02370548 0.9991943 0.1540814 -0.449016 0.8801383 0.1811094 -0.4066441 0.8954552 0.08181399 -0.3399389 0.9368821 0.1258423 -0.2609456 0.9571161 0.02884608 -0.2050332 0.9783299 0.06468647 -0.1388164 0.9882032 -1.8255e-4 -0.1030937 0.9946717 0.01506787 -0.07340919 0.9971882 -0.001886725 -0.06390762 0.9979541 3.40407e-4 -0.05868822 0.9982764 3.64693e-4 -0.05684643 0.9983829 8.64964e-4 -0.05551987 0.9984572 -0.004727065 -0.05259382 0.9986048 -0.004618823 -0.0512821 0.9986736 -0.00482726 -0.05014234 0.9987304 -0.004696428 -0.04991644 0.9987424 -0.006451308 -0.0490055 0.9987778 -0.006139516 -0.0484448 0.9988071 -0.007755637 -0.0479924 0.9988177 -0.0074566 -0.04714071 0.9988605 -0.00737375 -0.04713177 0.9988615 -0.007641196 -0.04667991 0.9988807 -0.007967829 -0.04663008 0.9988805 -0.009536445 -0.04606765 0.9988929 -0.008085548 -0.04598689 0.9989094 -0.01067841 -0.04580515 0.9988934 -0.009057164 -0.04530948 0.998932 -0.01155221 -0.04550749 0.9988973 -0.01045012 -0.04480654 0.998941 -0.01256996 -0.04533618 0.9988928 -0.01182109 -0.04397231 0.9989629 -0.0134949 -0.04488271 0.9989011 -0.01306802 -0.04358059 0.9989645 -0.01452112 -0.04461818 0.9988986 -0.01438534 -0.0430448 0.9989696 -0.01602917 -0.04430741 0.9988894 -0.0158835 -0.04269844 0.9989618 -0.01771885 -0.04416704 0.998867 -0.017919 -0.04225784 0.9989461 -0.3122623 -0.00216186 0.9499935 -0.3739092 0 0.9274653 -0.3702494 -5.90527e-4 0.9289322 -0.3946294 0 0.9188404 -0.3453767 7.76917e-4 0.9384639 -0.2404572 -5.28454e-4 0.9706597 -0.2323884 3.5472e-5 0.9726231 -0.1883061 -2.10252e-6 0.9821104 -0.1474379 1.70285e-4 0.9890713 -0.1417383 -2.31304e-4 0.9899042 -0.0921244 6.34911e-5 0.9957476 -0.07333242 -3.40216e-4 0.9973075 -0.07888764 -1.61476e-4 0.9968835 -0.05181366 1.19915e-4 0.9986568 -0.02820134 -4.80324e-4 0.9996021 -0.01769179 0 0.9998435 -0.9801364 0 0.1983245 -0.9801365 0 0.1983242 -0.8259303 0 0.5637723 -0.8259298 0 0.563773 -0.5417807 0 0.84052 -0.541782 0 0.8405191 -0.9067499 -0.380574 0.1815709 -0.9064291 -0.3853882 0.1728075 -0.9071091 -0.3676562 0.2048955 -0.9053582 -0.3655471 0.2161062 -0.9069297 -0.3458057 0.2406177 -0.906835 -0.3229201 0.2708745 -0.9081192 -0.3164054 0.2742393 -0.9088622 -0.2929161 0.2969338 -0.9091497 -0.2831642 0.3053932 -0.9089621 -0.2636455 0.3229227 -0.9118904 -0.245114 0.3292037 -0.9055968 -0.1577501 0.3937124 -0.9094617 -0.1760926 0.3766577 -0.9118804 -0.1997016 0.3585996 -0.9242029 0.0289039 0.3808066 -0.9249608 -0.006775617 0.3800022 -0.9202138 -0.0475924 0.3885121 -0.9207692 -0.0817281 0.3814508 -0.9162173 -0.1197024 0.3823839 -0.91645 -0.1296518 0.3785631 -0.9159326 -0.1590473 0.3684718 -0.9150553 -0.1972028 0.351831 -0.9908427 -0.001603245 0.1350123 -0.9256637 -0.005784928 0.3783032 -0.9238984 0.03367918 0.3811528 -0.9908388 -0.001971185 0.1350359 -0.9907996 -0.01299715 0.1347123 -0.9906249 -0.01574397 0.1356998 -0.9906799 -0.03244572 0.1322906 -0.9902601 -0.0395016 0.1335086 -0.9903121 -0.04455447 0.1315177 -0.9902442 -0.05264532 0.1290157 -0.9902471 -0.05584043 0.1276423 -0.9895666 -0.0674743 0.1273003 -0.9896394 -0.0766285 0.1214163 -0.9887774 -0.09109771 0.1184083 -0.9887676 -0.09072071 0.1187794 -0.9887455 -0.1018226 0.1096109 -0.98874 -0.1005088 0.1108663 -0.9876907 -0.1167224 0.1041304 -0.9877628 -0.1217132 0.09752243 -0.986607 -0.1379076 0.08711093 -0.9865708 -0.1365519 0.08961957 -0.9865635 -0.1454679 0.07437485 -0.918913 -0.1207014 0.3755401 -0.8361501 -0.005283594 0.5484754 -0.8041012 -0.01483869 0.5943074 -0.8494274 -0.006855189 0.527661 -0.5672932 0 0.8235159 -0.4672404 -0.02729344 0.8837089 -0.5732795 -0.008777439 0.8193129 -0.6452999 -0.002308189 0.763926 -0.7124912 0.001127898 0.7016802 -0.9189447 0.004243075 0.3943637 -0.9907871 -0.01068556 0.1350069 -0.9813342 0 0.1923105 -0.5001514 0 0.865938 -0.5672906 0.003076672 0.8235119 -0.6588439 -5.39526e-5 0.7522797 -0.7979867 8.48362e-5 0.6026751 -0.8361584 0.00274986 0.5484812 -0.9232488 -0.001345634 0.3842003 -0.9813312 0.002531886 0.1923092 -0.9914019 0 0.1308532 -0.4142858 -0.8527461 0.3181062 -0.7735727 -0.59382 0.2212762 -0.9739217 -0.2120106 0.08079683 -0.4033494 -0.865722 0.2963695 -0.401962 -0.8225142 0.4023642 -0.3559302 -0.8501479 0.3880236 -0.3562021 -0.776508 0.5197647 -0.3241515 -0.796414 0.5105394 -0.3240284 -0.7139343 0.6207282 -0.2978412 -0.7285994 0.6167929 -0.2979987 -0.6440047 0.7045955 -0.2827801 -0.6522958 0.7032394 -0.7690418 -0.6041757 0.2086781 -0.7677444 -0.5758243 0.28106 -0.7484311 -0.602465 0.2772848 -0.748647 -0.5512076 0.3683719 -0.7350232 -0.5699709 0.3672523 -0.7348371 -0.5120729 0.4447425 -0.7236407 -0.5260282 0.4468092 -0.7238095 -0.4656693 0.5091679 -0.7172684 -0.4733746 0.5113146 -0.9734082 -0.2158943 0.07659119 -0.9731545 -0.2061792 0.1022769 -0.9709132 -0.2167016 0.101824 -0.9708932 -0.1985132 0.1340116 -0.9692969 -0.2059294 0.134375 -0.9692286 -0.1853526 0.1619895 -0.9679104 -0.1908898 0.1634342 -0.9679181 -0.1692574 0.1857057 -0.967143 -0.1723054 0.1869369 4.96037e-7 0 1 -1.24602e-6 0 1 6.10096e-7 0 1 -2.19687e-7 0 1 -1.18522e-5 0 1 -0.1117241 -2.03031e-4 0.9937393 -0.1037996 -0.002735614 0.9945946 -0.0821473 -0.01168608 0.9965517 -0.08541411 -0.02614367 0.9960025 -0.0883575 -0.002935051 0.9960846 -0.09770846 -0.02250963 0.9949606 -0.09968835 -0.00969702 0.9949715 -0.1294012 -0.007117927 0.9915668 -0.08489924 0 0.9963896 -0.07920539 -0.01523202 0.996742 -0.08097201 -0.008268475 0.9966822 -0.1831795 3.16666e-4 0.9830795 -0.1641392 -1.84708e-4 0.9864373 -0.09518057 0.001560568 0.9954589 -0.04090863 0.01419085 0.9990621 -0.04041492 1.82655e-4 0.9991831 -0.3241953 0 0.9459902 -0.3232886 -0.002599895 0.9462969 -0.3337475 -0.004914879 0.9426498 -0.3316035 -0.004106223 0.9434099 -0.3251981 -5.59631e-4 0.9456458 -0.1753392 -2.16699e-5 0.9845081 -0.1987127 2.01489e-5 0.9800578 -0.2359319 -0.001743555 0.971768 -0.2311679 -0.002474129 0.9729108 -0.2915193 0.001168131 0.9565643 -0.8654276 0.2442174 0.437485 -0.9899759 0.09584563 0.1037378 -0.9699984 0.002440392 0.2430989 -0.9528613 0.1215875 0.2779785 -0.918932 0.203685 0.3377521 -0.7953898 0.2002667 0.5720562 -0.7936671 0.198168 0.5751712 -0.6875002 0.3602286 0.6305387 -0.4697706 0.384668 0.7945729 -0.4041723 0.2910882 0.8671289 -0.5555459 0.363269 0.7479335 0.1786593 0.4250227 0.8873763 0.09981173 0.4365079 0.8941468 -0.06679904 0.383722 0.9210295 -0.08422899 0.4021903 0.9116736 -0.249746 0.4355387 0.8648313 -0.07425373 0.2887252 0.9545283 -0.01700073 0.214135 0.9766561 0.05434179 0.1730262 0.983417 -0.1392705 0.3850758 0.9123159 -0.1148256 0.3192713 0.9406812 -0.2623367 0.2078279 0.9423306 -0.7267422 0.1889141 0.660422 -0.6413955 0.1895516 0.7434259 -0.495618 0.3303079 0.8032805 -0.5119505 0.453572 0.7295062 -0.4211055 0.1906002 0.8867591 -0.9149267 0.0849722 0.3945745 -0.7775307 0.372263 0.5068199 -0.7411167 0.5325579 0.4088132 -0.7664441 0.356146 0.5345311 -0.4337107 0.8963935 -0.09150749 -0.7759261 0.6292124 0.04506283 -0.9319865 0.249746 0.2627319 -0.11329 0.3380265 0.934293 -0.07131177 0.2777626 0.9579994 -0.498037 0.3105701 0.8096328 -0.473649 0.2716161 0.8377836 -0.8017167 0.2368664 0.5487667 -0.7937292 0.2153112 0.5688894 -0.9728184 0.1249283 0.1949803 -0.9727787 0.1242058 0.195639 0.9336082 0.2154442 0.2862855 0.976239 0.1473218 0.1589143 0.9999945 0.002498149 0.002171933 0.9999945 0.002487838 0.002196609 0.9993482 0.02802783 0.02275019 0.9993491 0.0258466 0.02516502 0.9973331 0.05479794 0.04820817 0.07742792 0 0.996998 0.2572609 -0.1095833 0.9601085 0.2976732 -0.05202198 0.9532493 0.6490955 -0.002710044 0.7607022 0.5805807 -0.01173937 0.8141182 0.6087639 5.43041e-6 0.7933514 0.4306783 -3.04692e-6 0.9025056 0.3603174 -0.02182722 0.9325744 0.8780915 -0.003210306 0.4784821 0.8304952 -0.01105731 0.5569161 0.717324 0.002493917 0.6967354 0.7933386 -0.005963981 0.6087514 0.89673 0.017946 0.4422142 0.980785 -4.32807e-7 0.1950922 0.996866 -0.04055476 -0.06792366 0.9995355 -0.03047746 -3.99948e-4 0.9950017 -0.01840245 0.0981484 0.9732403 -0.004650652 0.2297425 0.9204416 0.001718401 0.3908767 0.9807854 0 0.19509 0.3948239 0 0.9187569 0.4422827 -0.003330171 0.8968695 0.1435718 0.005531132 0.9896245 0.1950914 0 0.9807851 0.9858695 8.85874e-7 0.1675152 0.9848201 0.0028764 0.1735547 0.9089212 -9.95114e-4 0.4169668 0.8968729 0 0.4422886 0.8270372 0 0.5621474 0.7933514 0.00228703 0.6087597 0.7601628 6.44003e-4 0.6497324 0.6087607 -0.001691401 0.7933521 0.6481828 0.002461016 0.7614809 0.5257746 0 0.850624 0.8967505 0.01620614 0.44224 -0.1695473 0.9854394 0.01276606 0.3212823 0.9469016 0.01245439 0.7342314 0.6788406 0.008934438 0.9692191 0.2461806 0.00307691 -0.1693972 0.9854459 0.01417356 -0.1688886 0.9799541 0.1056727 -0.1612758 0.9799183 0.1172625 -0.1614616 0.952118 0.2596182 -0.1439113 0.9472275 0.2864431 -0.1439855 0.9015076 0.4081081 -0.1153156 0.8876507 0.445846 -0.1155572 0.8455986 0.5211619 -0.09487301 0.8201277 0.5642604 -0.09477859 0.7729187 0.6273865 -0.05237805 0.7400911 0.6704638 -0.0524528 0.7161763 0.6959456 -0.04632949 0.6713315 0.7397078 -0.04627948 0.646032 0.7619062 0.003433823 0.6007631 0.7994199 0.00343436 0.5134224 0.8581292 0.05641156 0.4604476 0.8858926 0.05642265 0.3621508 0.9304103 0.113193 0.3059642 0.9452902 0.1132512 0.2002018 0.9731873 0.1665788 0.1445791 0.9753709 0.1668283 0.07560557 0.9830831 0.1950529 0.01978629 0.9805932 0.4417227 0.05058783 0.8957242 0.3213817 0.9468541 0.01345932 0.320448 0.9416328 0.1031544 0.325608 0.9389371 0.1112506 0.3259059 0.911156 0.2521509 0.3377876 0.901634 0.2701031 0.3379006 0.8554089 0.3925543 0.3571491 0.8361693 0.4162518 0.3578435 0.7919178 0.4947871 0.3716019 0.7671548 0.522863 0.3712235 0.7175742 0.589305 0.3991122 0.6820912 0.6127489 0.3997334 0.653016 0.6432599 0.4038074 0.618373 0.6742066 0.403319 0.5882003 0.7009667 0.4354259 0.5436697 0.7175149 0.4356152 0.4588732 0.7743868 0.4692551 0.4099949 0.782115 0.4693337 0.3177276 0.8238782 0.5047624 0.2681691 0.8205489 0.5049864 0.1720511 0.8458057 0.5377194 0.1255706 0.8337206 0.5371486 0.143197 0.8312437 0.6085903 0.02357232 0.7931345 0.7342773 0.6787818 0.009600996 0.7331806 0.6759986 0.07397508 0.7353784 0.6729818 0.07946187 0.7357423 0.652787 0.1804229 0.7407753 0.6436789 0.1921705 0.7409395 0.6105755 0.2796539 0.7490618 0.5934625 0.2944635 0.7498275 0.5614703 0.3500142 0.7556177 0.5419043 0.3679423 0.755277 0.5072092 0.415085 0.7669215 0.4780836 0.4280976 0.7675602 0.4573443 0.4490965 0.7692646 0.4329742 0.4698568 0.768866 0.4122565 0.4887636 0.7821446 0.3771129 0.4960199 0.7823873 0.3192037 0.5347703 0.796166 0.2817612 0.5354723 0.796319 0.2197989 0.5635287 0.8106856 0.1826303 0.5562688 0.8109368 0.119034 0.5728983 0.824078 0.08505588 0.5600545 0.8245536 0.04436606 0.5640417 0.7781124 0.1950804 0.5970637 0.9692233 0.2461597 0.003415167 0.9690518 0.2454941 0.02590894 0.9692813 0.2443499 0.02805346 0.9693959 0.2372336 0.0631805 0.9699299 0.2337474 0.06781011 0.9700415 0.2223092 0.09797 0.9709143 0.2157206 0.1038765 0.9711114 0.2047265 0.1225966 0.9717535 0.1972114 0.1296266 0.9717819 0.1856254 0.1455451 0.9730553 0.1743507 0.1508819 0.9731878 0.1676834 0.1574422 0.9734293 0.1583631 0.1653984 0.973413 0.1518463 0.1714934 0.9748733 0.1382195 0.1746931 0.9750242 0.1187004 0.1877183 0.9765437 0.1041595 0.1884495 0.9766791 0.08328485 0.1978929 0.9782596 0.06880104 0.1956394 0.9784017 0.04737049 0.2012119 0.9798468 0.03408229 0.1968219 0.9799729 0.02068942 0.1980532 0.9807476 0.008774757 0.1950827 -0.7357859 0.1476495 0.6609227 -0.3573445 0.04567974 0.932855 -0.9329866 0.2690467 0.2390608 -0.9450595 0.2242943 0.2378121 -0.9469183 0.2154924 0.2385553 -0.3550891 0.0677827 0.9323719 -0.3587226 0.05318421 0.9319279 -0.3732991 0.08760499 0.9235655 -0.9141747 0.3395344 0.2213617 -0.906671 0.3499982 0.2354764 -0.9316756 0.28003 0.231439 -0.9040179 0.3627218 0.2262399 -0.8998217 0.3724619 0.2271413 -0.8978546 0.3816596 0.2195294 -0.9103438 0.3529812 0.2160521 -0.910001 0.3556154 0.2131573 -0.9340323 0.2921811 0.2054604 -0.9346871 0.2887399 0.2073388 -0.9530298 0.2267907 0.2007491 -0.9552665 0.2050489 0.2131215 -0.9645274 0.1707659 0.201311 -0.9767171 0.08796703 0.1956675 -0.9764425 0.08484208 0.198399 -0.9801048 0.008964955 0.1982785 -0.9800994 0.008592426 0.1983212 -0.7333177 0.1639571 0.6598206 -0.7285673 0.1823081 0.6602678 -0.7331382 0.2053856 0.648325 -0.7252316 0.2279145 0.6496878 -0.730205 0.2571516 0.632988 -0.7342482 0.2476596 0.6320952 -0.7378045 0.2766561 0.6157158 -0.757422 0.2321275 0.6102694 -0.7635205 0.2563681 0.5927157 -0.7875642 0.1927218 0.5853214 -0.7878723 0.2044814 0.5808999 -0.8070076 0.139308 0.5738746 -0.8084553 0.1458842 0.5701911 -0.8233109 0.05801814 0.5646177 -0.8239318 0.05974566 0.5635308 -0.8259264 0.005888223 0.5637473 -0.8259189 0.00600636 0.5637569 -0.37011 0.09647881 0.9239646 -0.3979482 0.07301759 0.9144976 -0.399559 0.1118087 0.9098634 -0.4174318 0.07007628 0.9060023 -0.4337128 0.1210809 0.8928788 -0.458836 0.06459772 0.8861696 -0.4817484 0.1154893 0.8686661 -0.5031964 0.05807 0.8622188 -0.5074611 0.08901309 0.8570647 -0.5214107 0.04218703 0.8522625 -0.5291603 0.06484586 0.8460404 -0.5371618 0.01809811 0.843285 -0.5411159 0.02657485 0.8405281 -0.541733 0.001839041 0.8405486 -0.5417642 0.00266391 0.8405264 -0.2487555 0.5069302 0.8253136 -0.9160208 0.3935614 -0.0775603 -0.999956 0.005028426 0.007923603 -0.07554322 0.7147359 0.6953027 0.1018817 0.553048 0.8268967 0.1806792 0.5224629 0.8332992 -0.404289 0.5484586 0.731945 -0.9484538 0.2357363 0.211811 -0.9188809 0.2072601 0.3357101 -0.865058 0.2700695 0.4227734 -0.7727414 0.5069584 0.3819213 -0.6874859 0.3614185 0.6298729 -0.5545946 0.4555174 0.6963683 3.99722e-5 0.5533586 0.8329432 3.85097e-5 0.6495916 0.7602835 0.04379934 0.5918903 0.8048276 0.0437113 0.7568114 0.6521702 0.08781355 0.709105 0.6996133 0.08783876 0.8454109 0.5268442 0.121264 0.8111093 0.572186 0.1211482 0.9130458 0.3894491 0.1487407 0.8916618 0.4275693 0.1487836 0.9599282 0.2374897 0.1657092 0.9504801 0.2629225 0.1657842 0.982906 0.08007138 0.1715805 0.9811404 0.08901524 -0.4308047 0.5981318 0.6757557 -0.4318841 0.5802726 0.690478 -0.4037268 0.5469447 0.7333867 -0.4031605 0.6882326 0.6031565 -0.3743171 0.664351 0.6469348 -0.3744449 0.7831859 0.4963981 -0.3523089 0.7678222 0.5350958 -0.3520399 0.8586399 0.3725661 -0.3335147 0.851891 0.4037943 -0.3335866 0.9142095 0.2300893 -0.3221372 0.9131358 0.2498212 -0.3222297 0.9434306 0.07814592 -0.3182853 0.9441995 0.08474594 -0.7699542 0.4871002 0.412194 -0.7800778 0.4030476 0.4785724 -0.7685402 0.3842373 0.5115739 -0.7678836 0.4820041 0.4219325 -0.755934 0.4704251 0.4552628 -0.7559473 0.5530552 0.3502481 -0.7467059 0.5466493 0.3789525 -0.7463352 0.6106111 0.2648357 -0.7385451 0.6097633 0.2876455 -0.7385603 0.6538127 0.164492 -0.7337136 0.6555655 0.1786012 -0.7337869 0.6770641 0.05604553 -0.7321099 0.6784791 0.06067353 -0.9736939 0.1658825 0.1562156 -0.9745126 0.1484765 0.1681665 -0.9733726 0.1414669 0.180369 -0.9730409 0.1766852 0.1482353 -0.971849 0.1723457 0.1606438 -0.9716495 0.2019563 0.1229269 -0.9707303 0.1995067 0.1337159 -0.9705068 0.2224529 0.09290504 -0.9697226 0.2220916 0.101556 -0.9696114 0.2377579 0.05766242 -0.9691188 0.2383939 0.06306451 -0.969077 0.2459762 0.01963806 -0.9689042 0.2465075 0.02142238 -0.9983377 0.05763727 0 -0.9991366 0.04153615 -9.71573e-4 -0.9957288 0.07788586 0.04957914 -0.9940376 0.0815916 0.07233351 -0.9980551 0.06232756 -0.001265347 -0.990922 0.134429 0.001577556 -0.9890209 0.1477766 0 0.5849086 0.42913 0.6882801 0.584896 0.4280029 0.6889923 0.8648539 0.08731359 0.4943725 0.8708444 0.1285774 0.4744449 0.9421591 -0.277853 0.1874406 0.9681718 -0.1968315 0.154599 0.5471432 0.3323587 0.7682266 0.5445994 0.3453203 0.7643072 0.8309802 -0.0412631 0.5547696 0.8361999 0.02910929 0.5476517 0.8903034 -0.4107828 0.1965127 0.9351429 -0.292001 0.200607 0.9775818 0.1655625 0.1300882 0.4381037 0.5557252 0.7065654 0.487079 0.6038857 0.6309328 0.540313 0.5097329 0.669503 0.5122513 0.4852193 0.7086333 0.6221565 0.573266 0.5331862 0.6318181 0.6061762 0.4830697 0.8006783 0.3938813 0.4514112 0.8209132 0.4219108 0.3848283 0.7949334 0.3643997 0.4850711 0.931275 0.154997 0.3297014 0.9850147 0.1439653 0.09497386 0.9676781 0.1016889 0.2307782 0.8412421 0.5084308 0.1838749 0.7834537 0.3503835 0.5132561 0.8612557 0.4172185 0.2901163 0.8662511 0.3838436 0.3198016 0.8822431 0.4684735 0.04668682 0.9177117 0.3719826 0.1394065 0.6418923 0.6112434 0.4629858 0.6527266 0.6288074 0.4225509 0.6528821 0.6292595 0.4216365 0.6700097 0.6608036 0.3382686 0.6718363 0.6563423 0.343294 0.6825895 0.6970591 0.2195001 0.6860034 0.6893711 0.2327378 0.9712184 0.2376541 0.01598429 0.7487865 0.6616933 0.03848385 0.7510211 0.6586271 0.04666757 0.9709268 0.238984 0.0137124 0.9709677 0.2344104 0.04768347 0.9739411 0.1119385 0.1972526 0.6854192 0.7157366 0.1338719 0.7380922 0.6221138 0.2611404 0.8415672 0.5288054 0.1101348 0.9179545 0.3891666 0.07687067 0 0 1 4.13345e-7 0 1 -3.58553e-7 0 1 -3.05934e-7 0 1 0.803412 -0.5625553 0.1950916 0.7923734 -0.5524103 0.2588191 0.7346727 -0.5144309 0.442286 0.6498752 -0.4550484 0.6087636 0.5807408 -0.4034131 0.7071054 0.4986701 -0.3491707 0.7933524 0.3623034 -0.2536899 0.8968711 0.2131476 -0.1468316 0.9659237 0.1598087 -0.1118999 0.9807852 0.8968725 -0.4422893 0 0.8770086 -0.4798871 0.02375471 0.9197726 -0.3924128 0.005538344 0.9882163 -0.1520999 -0.01715689 0.971943 -0.2342077 0.02176338 0.9968423 -0.07940644 0 0.4952011 0.2560112 0.8302013 0.2860532 -0.03873825 0.9574305 0.2860572 -0.03873831 0.9574292 0.4105286 0.1734946 0.8951904 0.5582148 -0.2577971 0.7886298 0.6086377 -0.3523486 0.7109224 0.6956802 -0.3847599 0.606621 0.7683135 -0.4634833 0.4414495 0.7958877 -0.5441921 0.2653635 0.8185814 -0.5402685 0.1950249 0.4321843 0.1699537 0.8856255 0.7396824 -0.1705719 0.6509802 0.7396828 -0.1705731 0.6509794 0.8507179 -0.4680132 0.2392545 0.8507205 -0.4680145 0.2392427 0.798698 -0.5592536 0.2220743 0.09283405 -0.06500273 0.9935575 0.2086966 -0.1531774 0.9659102 0.2479237 -0.1776622 0.9523497 0.501186 -0.3455653 0.7933458 0.4147087 -0.2949103 0.8608395 0.6518908 -0.452163 0.6087587 0.6425238 -0.4469537 0.6224111 0.7344751 -0.514722 0.4422756 0.8046221 -0.5608237 0.1950904 0.2455888 -0.9608155 0.1285296 0.3140504 -0.4259375 0.8484985 -0.726657 -0.5915234 0.3493849 0.1823804 0.06552964 0.981042 -0.02470564 -0.219529 0.9752932 -0.04580754 -0.01606458 0.9988212 -0.583638 -0.2272261 0.7795736 -0.5841318 -0.1204102 0.8026776 -0.689001 -0.4912006 0.5329163 -0.7835431 -0.4174665 0.4601978 -0.8055903 -0.4479956 0.3877168 -0.2294207 -0.9561658 0.1819705 -0.467986 -0.8622079 0.1938729 -0.4072098 -0.1245986 0.9047958 -0.144819 -0.2123438 0.9664044 -0.3160716 -0.4569017 0.8314685 -0.3160805 -0.4568976 0.8314672 -0.4743357 -0.6829125 0.5555505 -0.4743262 -0.682904 0.5555689 -0.569415 -0.8185409 0.07587713 -0.5958817 -0.8020795 0.03992164 0.1387115 -0.3243415 0.9357147 0.2985067 -0.3047342 0.9044506 0.06368929 -0.6571967 0.7510234 0.06369876 -0.657198 0.7510215 -0.07925051 -0.8613388 0.5018116 -0.0792424 -0.8613402 0.5018104 -0.1730572 -0.9807296 0.09066933 -0.01139599 -0.9867127 0.1620747 0.5658081 -0.5461783 0.6176978 0.5658058 -0.5461797 0.6176987 0.4355887 -0.7321438 0.5236679 0.4355916 -0.7321493 0.5236577 0.3359199 -0.874485 0.3499054 0.3359246 -0.8744881 0.3498933 0.2726191 -0.9580094 0.08886408 0.4546557 -0.8858543 0.09246879 0.7726074 -0.5948582 0.2218595 0.7726091 -0.5948573 0.2218558 0.7258377 -0.6616525 0.1880844 0.7258368 -0.6616542 0.188082 0.6900403 -0.7127763 0.1256754 0.6900357 -0.7127809 0.125675 0.670667 -0.7404449 0.04412639 0.6706655 -0.7404458 0.04413539 0.1993696 -0.9799244 0 0.5300903 -0.8479412 0 0.6494426 -0.760397 -0.004557073 0.7255143 -0.6882072 0 -0.05460649 -0.9983402 -0.0183047 -0.3007087 -0.953716 0 0.1993705 -0.9799243 0 -0.1385293 -0.9902823 -0.01227205 -0.3167151 -0.9485148 -0.003353774 -0.4588935 -0.8884912 -2.75456e-4 -0.518204 -0.8552571 0 -0.7253742 -0.6883549 0 -0.7253742 -0.6883548 0 -0.968147 -0.2503826 0 -0.8801932 -0.4742882 -0.01762843 -0.9710466 -0.2388904 0 0.1835765 -0.4852746 0.8548733 0.1665248 -0.5212696 0.8369872 0.5110158 -0.6293503 0.5854752 0.7532826 -0.6234695 0.2094073 0.1936894 -0.5221953 0.83054 0.1557781 -0.5763408 0.8022247 0.1820198 -0.5947843 0.7830075 0.1490656 -0.64192 0.7521424 0.1692185 -0.6539736 0.737349 0.1476839 -0.6853278 0.7131026 0.1510111 -0.6922675 0.7056638 0.1265217 -0.7264781 0.675442 0.1451779 -0.7362938 0.6609046 0.1000366 -0.8004171 0.5910374 0.1149991 -0.8067461 0.5795997 0.08962208 -0.844882 0.527392 0.08964949 -0.847216 0.5236298 0.0642898 -0.8815377 0.4677159 0.06542992 -0.8819209 0.4668344 0.02508026 -0.9389051 0.3432615 0.01102179 -0.9354986 0.3531587 0.2313439 -0.928939 0.2890544 0.5202872 -0.6375413 0.5681923 0.4977319 -0.6695661 0.5513114 0.5101376 -0.6748115 0.5332815 0.4874995 -0.7072135 0.5120482 0.4972341 -0.7098676 0.498845 0.4825729 -0.7312508 0.4820744 0.4838956 -0.7340946 0.476393 0.4671023 -0.7575373 0.4560184 0.4762924 -0.7590243 0.4438779 0.4458224 -0.8023304 0.3968732 0.4533664 -0.802564 0.38775 0.4365471 -0.8278802 0.3521946 0.4364228 -0.8290016 0.3497022 0.4191491 -0.852417 0.3125689 0.4196957 -0.8523745 0.3119509 0.3961796 -0.8863061 0.2397984 0.4130244 -0.8824127 0.2252973 0.7543916 -0.624413 0.202489 0.7462203 -0.636071 0.1963898 0.7482974 -0.6358065 0.1892119 0.7401863 -0.6474156 0.1815965 0.7419725 -0.6467988 0.1764317 0.7367833 -0.6542862 0.1704702 0.736804 -0.6548092 0.1683592 0.7309042 -0.6631647 0.1612198 0.7326972 -0.6622967 0.1565818 0.7219586 -0.6776235 0.140008 0.7235181 -0.6766558 0.136596 0.7174813 -0.6854771 0.1238619 0.71736 -0.6857619 0.122985 0.711256 -0.6942984 0.1098393 0.711368 -0.694217 0.1096287 0.701718 -0.7079265 0.08019924 0.6999244 -0.7093968 0.08283811 0.625903 -0.5855917 0.5150999 0.6795071 -0.5199462 0.5176157 0.6529589 -0.4894249 0.5780209 0.4564179 -0.4135524 0.7878181 -0.0653392 0.02774018 0.9974775 -0.05049496 0.01664841 0.9985855 -0.03852415 0.007950484 0.999226 -0.02854943 8.34292e-4 0.9995921 -0.01866775 -0.006216168 0.9998064 0.1511083 -0.1242849 0.980673 0.008425056 0.05985611 0.9981715 0.02175807 0.04328823 0.9988257 0.03220838 0.02991598 0.9990334 0.04127854 0.018682 0.998973 0.04973554 0.007947802 0.9987309 0.05999147 -0.004609465 0.9981883 0.07384967 -0.02159029 0.9970357 0.08367109 -0.03384155 0.9959186 0.1060361 -0.06016099 0.9925407 0.124697 -0.08123713 0.9888636 0.7988921 -0.5657401 0.2042297 0.792056 -0.575492 0.2036083 0.7918819 -0.5731496 0.210767 0.8019679 -0.5583333 0.2123948 0.8094571 -0.5797843 0.09289431 0.1599944 -0.1201955 0.9797729 0.244794 -0.1985669 0.9490243 0.3480442 -0.2738157 0.8965992 0.3622625 -0.2859168 0.88714 0.4832706 -0.3707813 0.7930768 0.4363331 -0.327161 0.8381999 0.6392307 -0.4700197 0.6086589 0.6546651 -0.486963 0.5781701 0.7284856 -0.5231787 0.4422587 0.7994064 -0.5682336 0.1950902 -0.3695651 0.9292048 0 -0.2920606 0.9545392 -0.05962848 -0.2581896 0.9598876 -0.1093344 -0.2687091 0.9588813 -0.09133517 -0.2791278 0.9577705 -0.06901657 -0.2894183 0.9563849 -0.03955978 -0.2953352 0.9552758 -0.01501381 -0.3343201 0.9139454 0.2300736 -0.2270948 0.9738121 -0.01087081 -0.2249606 0.9740051 -0.02658814 0.2264378 0.9734045 -0.03478276 0.1936168 0.9724238 0.130018 0.08839297 0.9830589 0.1605677 0.05959147 0.9883339 0.1401609 -0.07894337 0.9839075 0.1602939 -0.2231216 0.96604 0.1303213 -0.3396202 0.8598336 0.3812406 -0.3202388 0.9112231 0.2590748 -0.3648574 0.9219504 0.1299482 -0.3498064 0.9308939 0.1052237 -0.3435058 0.939064 0.01275467 -0.2383354 0.6763088 0.6969955 -0.2695041 0.7317047 0.6260797 -0.2907677 0.7394936 0.6071273 -0.2853307 0.8047858 0.5204867 -0.3180505 0.8564511 0.4066146 -0.2123939 0.6109838 0.7626189 -0.2308564 0.5655913 0.7917144 -0.1500391 0.4844422 0.8618608 -0.1518279 0.3539765 0.9228483 -0.1143349 0.3317192 0.9364241 -0.04028421 0.1242214 0.9914365 -0.1148251 0.0277456 0.9929982 -0.05407679 0.1720155 0.9836089 0.06639748 0.1702833 0.9831556 0.003575801 0.01200538 0.9999216 0.1155062 0.1016764 0.9880893 0.09840995 0.1098775 0.9890615 0.07482153 0.1353071 0.9879745 0.09084475 0.2981418 0.9501888 0.1594879 0.3514375 0.9225266 0.1433903 0.4339714 0.8894426 0.1865411 0.5209788 0.8329367 0.2334682 0.5645791 0.791671 0.2176979 0.6064169 0.7647655 0.2508571 0.7130248 0.6547262 0.2986001 0.7365919 0.6068528 0.2808885 0.8016104 0.5277524 0.3338272 0.861971 0.3815304 0.3384444 0.8572285 0.3880912 0.3252165 0.9153937 0.2372526 0.371458 0.9193171 0.129904 0.3453902 0.9350578 0.07982921 -0.1308119 0.9901292 0.05032145 -0.2073845 0.9668124 0.1492168 -0.1938389 0.9036639 0.3818615 -0.1938374 0.9036653 0.3818591 -0.1665446 0.7764273 0.6078022 -0.1665406 0.7764328 0.6077963 -0.1278737 0.5961679 0.7926111 -0.1278761 0.5961681 0.7926106 -0.08043187 0.3749768 0.9235384 -0.08043146 0.3749767 0.9235385 -0.02744334 0.1279401 0.9914022 -0.02744221 0.1279397 0.9914022 -0.08816784 0.9827855 0.1623548 -0.0685479 0.9864261 0.1492143 -0.06407034 0.921996 0.3818616 -0.06407368 0.9219962 0.3818607 -0.05505216 0.7921831 0.6077955 -0.05505132 0.7921861 0.6077916 -0.04226905 0.6082606 0.7926111 -0.04226934 0.60826 0.7926115 -0.026587 0.3825834 0.9235383 -0.02658677 0.3825823 0.9235388 -0.009071528 0.1305349 0.9914022 -0.009071409 0.1305351 0.9914023 -0.02451509 0.9808819 0.1930537 0.07158458 0.9852216 0.1556094 0.06697547 0.9217875 0.3818665 0.06697857 0.9217911 0.3818573 0.05754852 0.7920057 0.6077953 0.05754697 0.7920063 0.6077948 0.04418611 0.6081247 0.7926109 0.04418265 0.6081202 0.7926146 0.0277906 0.3824961 0.9235392 0.02779269 0.3825007 0.9235371 0.009482026 0.1305063 0.9914022 0.0094828 0.1305055 0.9914023 0.08172392 0.9839482 0.1586418 0.2103067 0.9656299 0.1527417 0.1966775 0.9030501 0.3818619 0.1966756 0.9030513 0.3818601 0.1689841 0.7759051 0.6077959 0.1689843 0.775905 0.6077958 0.129749 0.5957576 0.7926149 0.1297544 0.5957612 0.7926111 0.08161348 0.374725 0.9235369 0.0816105 0.374722 0.9235385 0.02784413 0.1278526 0.9914023 0.02784579 0.1278522 0.9914023 0.226527 0.9737902 -0.02045375 0.2307299 0.972995 -0.006674349 0.2340291 0.9721697 -0.01079511 0.2292317 0.9733211 -0.009944498 0.2236847 0.974502 -0.01763808 0.2243068 0.9743695 -0.01705151 0.3717759 0.9283226 0 0.3464249 0.9378597 -0.02022522 0.2933279 0.9559846 0.007223486 0.2474743 0.9688789 -0.005496442 -0.2080322 0.9781221 0 -0.1694415 0.9848238 0.03757411 0.0391491 0.9992334 0 0.2964603 0.9550452 0 0.3211935 0.9466395 0.02661758 0.5224819 0.8526504 0 0.734262 0.6788663 0 0.7252512 0.6883245 0.0148372 0.9691053 0.246154 -0.01559615 0.9659259 0.2588191 0 1 -3.69986e-6 0 1 2.62805e-6 0 1 7.56356e-7 0 1 -2.89504e-6 0 1 0 0 1 2.23298e-7 0 1 -3.59691e-6 0 1 7.38335e-7 0 1 -2.03934e-6 0 1 -1.56103e-6 0 1 6.32271e-5 0 1 -5.48993e-6 0 1 -9.27301e-7 0 1 2.14403e-6 0 1 1.58954e-6 0 1 0 0 1 8.3784e-6 0 1 -1.20234e-5 0 -0.9319438 0.3626029 0 -0.930491 0.3648543 -0.03267818 -0.9730696 0.2305114 0 -0.9728133 0.2315909 0 -0.9729512 0.2310106 -2.23194e-5 -0.9570256 0.2900037 1.4338e-4 -0.9694366 0.2452511 -0.006679475 -0.9312725 0.3642039 0.009344518 -0.963307 0.2676656 -0.01987218 -0.9555256 0.2946308 -0.01279187 -0.9472042 0.3205547 -0.007001161 -0.9319763 0.3625196 -3.63164e-7 -0.9199986 0.3919218 0 -0.9152283 0.4029355 2.09711e-4 -0.9708416 0.2397218 -1.56873e-6 -0.9696913 0.2443333 4.78911e-4 -0.9468485 0.3216797 -5.86872e-4 -0.9487946 0.3158901 -0.001518726 -0.923909 0.3826106 0.001250207 -0.9238624 0.3827229 0.001272439 -0.9147419 0.4040387 -6.21328e-5 -0.9995735 0.02920371 0 -0.9999533 0.009607195 -0.001144468 -0.9911909 0.1323899 0.003691375 -0.9955242 0.09442621 -0.003913938 -0.9829568 0.1838374 5.49004e-7 -0.5217589 0.8530931 0 -0.7247904 0.6889695 0 -0.7333919 0.6796682 0.01369696 -0.9658258 0.2587912 -0.01441049 -0.9691269 0.2465629 0 -0.295207 0.9549986 0.02882045 -0.3194345 0.9476084 0 -0.03798836 0.9992782 0 0.1721486 0.9843868 0.03671008 0.2095622 0.9777954 0 -1 1.43407e-6 0 -1 7.74244e-6 0 -1 1.57677e-6 0 -1 3.02836e-6 0 -1 -4.61192e-7 0 -1 -1.94743e-6 0 0.9992112 0.001598119 -0.03968095 0.9999964 0 -0.002733349 0.9983119 -0.010073 -0.05720055 0.999318 0.004319787 -0.03667342 0.9996888 0.01834619 -0.01690727 0.9994482 0.03307521 0.00305581 0.9901381 0.1398534 -0.008223474 0.9967564 0.08043116 -0.002768933 0.9978057 0.06618493 -0.001841783 0.9981468 0.06083428 -0.001544237 0.9983294 0.05776268 -0.001383066 0.9995349 0.03049957 -8.54001e-5 0.9999985 0.001731872 0 0.7518405 0.6593452 0 0.7038246 0.7088329 -0.04676449 0.8544191 0.5195842 5.13445e-4 0.9713408 0.2376846 -0.001744389 0.9316022 0.354173 -0.08172386 0.9707227 0.2381413 -0.031403 0.5735769 0.8191517 0 0.5735713 0.8191556 -1.36705e-5 0.5735831 0.8191474 7.36362e-6 0.5735739 0.8191539 0 0.3597046 0.4994372 0.7881468 0.3962954 0.567685 0.7215843 0.4975579 0.4876933 0.7173503 0.07853674 0.1121621 0.9905815 0.1276222 0.1538302 0.9798209 0.2169415 0.322529 0.921364 0.2558617 0.3654041 0.8949942 0.2931944 0.418743 0.8594717 0.3385949 0.4797047 0.8094671 0.5727076 0.8179132 0.054991 0.5786882 0.7994121 0.1614327 0.5674767 0.817804 0.09574383 0.5562459 0.7903797 0.2566916 0.5556978 0.786826 0.2685238 0.5322133 0.7643476 0.3640357 0.5185384 0.7345042 0.437746 0.5198794 0.7376147 0.4308714 0.5053104 0.7216556 0.473154 0.4579933 0.6540691 0.6020264 0.4998745 0.6809086 0.5352467 0.4488739 0.6381624 0.6255086 -0.2756021 -0.9612718 -1.8731e-4 -0.5124149 -0.858738 0 -0.4770391 -0.8788816 -9.78852e-4 -0.2333152 -0.972398 0.002526164 0.3070667 -0.951688 3.93757e-5 0.04510653 -0.9989822 1.35405e-4 -0.0115481 -0.9999312 0.002085149 0.247643 -0.9688494 -0.00191915 0.6713203 -0.7411674 -1.27244e-4 0.8173091 -0.5761996 0 0.4565834 -0.8896164 0.01070171 0.7004355 -0.7137048 -0.003947734 0.4838346 -0.8751596 -2.07775e-5 0.8191525 -0.5735757 0 0.819152 -0.5735765 9.6465e-7 0.8191536 -0.5735744 -5.52869e-6 0.8191511 -0.573578 9.25578e-7 0.8191521 -0.5735763 0 0.8191522 -0.5735765 1.71137e-6 0.8191519 -0.5735767 -2.5979e-7 0.8191516 -0.5735772 -2.37283e-6 0.8191528 -0.5735754 -4.01053e-7 0.8191513 -0.5735776 -7.10983e-7 0.8191539 -0.573574 0 0.8191482 -0.5735819 0 0.8191527 -0.5735754 -3.1547e-6 0.8191512 -0.5735778 1.05233e-5 0.819153 -0.5735751 -4.45724e-6 0.8191521 -0.5735765 0 0.8191521 -0.5735763 -1.65482e-6 0.819152 -0.5735765 7.10157e-7 0.819154 -0.5735737 0 0.8191521 -0.5735764 -1.73005e-7 0.8191514 -0.5735774 0 0.8191543 -0.5735733 0 0.5647606 0.8065442 -0.1747342 0.5587266 0.7879517 -0.2587602 0.2011684 0.2872718 -0.9364861 0.3169373 0.4525576 -0.8335123 0.3167076 0.452376 -0.8336981 0.393985 0.5626599 -0.7267667 0.432838 0.6115853 -0.6622799 0.4781547 0.6847127 -0.5500335 0.5275504 0.7516302 -0.3959074 0.589289 0.5916642 -0.5501565 0.6907174 0.6971184 -0.1921858 0.6940495 0.6989853 -0.1723799 0.3868694 0.3893361 -0.8359124 0.4852879 0.4930056 -0.7221089 0.4342799 0.4345076 -0.7890527 0.5895026 0.5963848 -0.5448045 0.6414018 0.6600691 -0.3910405 0.3137965 -0.8044477 -0.5043765 0.6444047 -0.6645017 -0.3783916 0.3287442 -0.5335008 -0.7792973 0.9464279 -0.03479236 -0.3210358 0.4075342 -0.2644543 -0.8740594 0.8304079 0.1832559 -0.5261559 0.3285326 0.04297262 -0.9435145 0.5570309 0.2608655 -0.788458 0.9987526 0.04919224 -0.008571326 0.9992207 0.02997881 -0.02568036 0.999093 0.01070028 -0.04121601 0.8103333 -0.5364816 -0.2356852 0.8098887 -0.5318126 -0.2474992 0.9483804 -0.290111 -0.1281031 0.9476799 -0.2825107 -0.1486292 0.9848111 -0.1535573 -0.0810393 0.9838913 -0.1407275 -0.1102437 0.9954551 -0.07061219 -0.06389856 0.9938825 -0.04850882 -0.0992195 0.998336 -0.01114505 -0.05657911 0.9974784 -0.01880055 -0.06843584 0.9983488 -0.03143733 -0.04807651 0.993618 -0.0835517 -0.07577842 0.9940368 -0.08950531 -0.06228697 0.9775587 -0.1841836 -0.1022515 0.9776346 -0.1850941 -0.09985482 0.9125993 -0.3692802 -0.175484 0.9047677 -0.328972 -0.2705052 0.6841182 -0.6045233 -0.4080857 0.8151014 -0.3718215 -0.4442506 0.914946 -0.2503913 -0.3165095 0.9989576 0.04427766 -0.01110243 0.9990031 0.04351484 -0.00995934 0.9993007 0.03529411 -0.01235061 0.9992752 0.03565216 -0.0133484 0.9996204 0.02196288 -0.01663815 0.9994381 0.024293 -0.02309679 0.9995658 0.001414 -0.02942943 0.9970109 0.01975202 -0.07469391 0.9971163 0.03722256 -0.06613224 0.9802343 0.1150875 -0.1609215 0.9792741 0.1614493 -0.1222962 0.9340522 0.2888765 -0.2099929 0.9330832 0.3194346 -0.1652795 0.8499329 0.480588 -0.2159847 0.8507047 0.4884675 -0.1941675 0.9991637 0.01213133 -0.03904771 0.9995219 0.006474137 -0.03023725 0.9987695 -0.02474337 -0.04298061 0.9988709 -0.02617853 -0.03964298 0.9949388 -0.08207356 -0.05797231 0.9947412 -0.07946407 -0.06461995 0.9766896 -0.188947 -0.1018649 0.9712334 -0.1573652 -0.1787226 0.9356213 -0.2655171 -0.2326231 0.9064099 -0.1257357 -0.4032513 0.9137988 -0.1089144 -0.391292 0.842999 0.09335029 -0.5297533 0.8573154 0.121165 -0.5003293 0.7379982 0.354744 -0.5740345 0.7482166 0.3699662 -0.550724 0.7442308 -0.6052849 -0.2824018 0.6126788 -0.7763043 -0.1482449 0.8889676 -0.440169 -0.1264435 0.9875186 -0.1525409 -0.03922373 0.9919793 -0.05617344 -0.1132332 0.9897887 -0.1157287 -0.08321738 0.9807527 -0.1832035 -0.06753391 0.9557649 -0.2846419 -0.07411229 0.6394134 -0.08907335 -0.7636861 0.8183466 -0.1917579 -0.5417912 0.6571594 -0.1950829 -0.7280688 0.8570494 -0.1333532 -0.4976779 0.816281 -0.1305238 -0.5627156 0.9819892 -0.0735436 -0.1740368 0.9682588 -0.06469726 -0.2414316 0.6699842 -0.3888846 -0.6323685 0.5751613 -0.709021 -0.4080181 0.8434106 -0.5172159 -0.1454181 0.8365532 -0.5356558 -0.1151164 0.9591063 -0.2507526 -0.1312952 0.8815886 -0.3977492 -0.2541602 0.8119288 -0.4448164 -0.3780347 0.8558255 -0.4047964 -0.3220289 0.7163757 -0.4667929 -0.5185657 0.9882819 -0.1526404 0 0.9784247 -0.2065586 -0.004326522 0.8961517 -0.4437388 0.002854943 0.871303 -0.4907456 0 0.6419262 9.89667e-4 -0.7667658 0.9846538 0 -0.1745191 0.9848153 -6.61526e-6 -0.1736056 0.8647823 5.32619e-6 -0.502147 0.8660064 -1.13746e-5 -0.500033 0.6414837 1.14823e-5 -0.7671366 0.6427975 0 -0.7660363 0.9519279 0.2555454 -0.1689086 -0.2441996 0.593044 -0.7672454 -0.007791876 0.6302332 -0.7763668 -0.05148804 0.7036581 -0.7086708 0.2562999 0.5769592 -0.7755182 0.02472102 0.6303458 -0.7759208 0.1266779 0.9760497 -0.1768611 0.1242045 0.8371835 -0.5326324 0.5354028 0.3309045 -0.7770753 0.7140548 0.5224479 -0.4660195 0.6066696 0.7949268 0.006610751 0.4108634 0.5983651 -0.6878594 0.3227249 0.5401279 -0.7772455 0.6410247 0.0217576 -0.7672119 0.9480561 0.1248144 -0.2925938 0.4765788 0.09080183 -0.87443 0.6900054 0.2329565 -0.685291 0.9074513 0.3780244 -0.1833842 0.687307 0.3069599 -0.6583198 0.549133 0.3075268 -0.7770974 -0.2049697 0.9637357 -0.1708828 -0.2642337 0.8127323 -0.5192753 -0.2676396 0.8231903 -0.5007263 -0.1034204 0.4985016 0.8606977 -0.2040036 0.9611979 -0.1856911 0.03842407 0.9808174 -0.1911046 0.1386198 0.518117 -0.8440021 0.07793188 0.2897333 0.9539294 0.1106051 0.8444006 -0.5241702 -0.08822673 0.8455025 -0.5266325 -0.09390074 0.9045764 -0.4158416 -0.1029083 0.4175403 -0.9028123 0.2104811 0.2104747 0.9546718 0.5163258 0.6739078 -0.5284468 0.3254548 0.7841079 -0.5284449 0.3483484 0.838141 -0.4197298 0.1553956 0.5741143 -0.8038936 0.2911406 0.9379042 -0.1886076 0.5126467 0.8366173 -0.1930409 0.4625698 0.4625651 -0.7563483 0.7124149 0.676144 -0.1878679 0.94897 0.2542739 -0.1865499 0.8588943 0.1130788 -0.4995135 0.3058099 0.08440977 0.9483435 0.7840464 0.3254238 -0.5285553 0.673892 0.5162943 -0.5284978 0.7939173 0.6061396 -0.0478568 0.2931634 0.3020911 -0.9070812 -0.9846253 0 -0.1746795 -0.9861171 6.06535e-4 -0.1660506 -0.8644593 -6.43199e-4 -0.5027025 -0.8698509 1.53835e-4 -0.4933147 -0.641164 0 -0.7674039 -0.634457 6.02083e-4 -0.772958 -0.7587835 -1.02324e-5 -0.6513429 -0.5119702 0.8370836 -0.1928147 -0.03728646 0.9808421 -0.1912034 -0.7212498 0.2626642 -0.6409417 -0.4937571 0.09018224 -0.864911 -0.3283615 0.5368552 -0.7771521 -0.3132827 0.3604516 -0.8785947 -0.6357802 0.5211452 -0.5693779 0.0251289 0.6301881 -0.7760359 -0.02396517 0.6303014 -0.7759807 -0.1353295 0.6365244 -0.7592909 -0.2299727 0.578891 -0.7823029 0.09844028 0.4129982 -0.9053961 0.08887815 0.8452091 -0.5269938 0.09551978 0.9139277 -0.3944771 0.08449113 0.8707581 -0.4843984 0.2059355 0.9608327 -0.1854483 0.2060263 0.9634938 -0.1709769 0.1025239 0.4906137 0.8653249 0.2695941 0.8226697 -0.5005333 0.274115 0.8364517 -0.4745624 0.2429221 0.5936965 -0.7671462 -0.325425 0.7840745 -0.528513 -0.3013005 0.7268248 -0.6172064 -0.3078992 0.549064 -0.7769986 -0.1128053 0.9466606 -0.3018421 -0.1280962 0.9891223 -0.07230877 -0.1105508 0.8440141 -0.5248035 -0.07780653 0.289434 0.9540305 -0.1409767 0.5268023 -0.8382153 -0.2900462 0.9383 -0.1883254 -0.6740105 0.5164094 -0.528234 -0.7949063 0.6067032 -0.005930781 -0.5265175 0.3457367 -0.7766888 -0.3979761 0.6012767 -0.6928791 -0.5919503 0.7745965 -0.2226994 -0.5163254 0.6738653 -0.5285014 -0.2106163 0.2106632 0.9546003 -0.4685608 0.4685251 -0.748956 -0.7118938 0.6767313 -0.1877288 -0.8589001 0.1130843 -0.4995022 -0.9283816 0.1222173 -0.3509569 -0.6410728 0.01929324 -0.7672376 -0.9520464 0.2550951 -0.1689211 -0.948881 0.2546741 -0.1864568 -0.3060523 0.0844447 0.9482622 -0.784191 0.3254845 -0.5283035 -0.9228606 0.3850798 0.006492555 -0.5643962 0.2799488 -0.776586 0.366068 0.9140962 -0.1744207 0.3660558 0.9140524 -0.1746749 0.3214449 0.8026809 -0.502371 0.3214468 0.8026241 -0.5024607 0.2384628 0.59549 -0.7671552 0.2384798 0.5954896 -0.7671503 0.1770046 0.5768641 -0.7974317 0.187011 0.6136785 -0.7670892 0.2435906 0.7887731 -0.5643587 0.2529239 0.826893 -0.5022724 0.2883445 0.9367695 -0.1982941 0.2888366 0.9413627 -0.174384 0.2183247 0.5647956 -0.7958268 0.2143726 0.3326531 -0.9183607 0.3828706 0.7007039 -0.6020169 0.4666523 0.2490508 -0.8486515 0.5489513 0.6682791 -0.5020513 0.708804 0.2388661 -0.6637318 0.6754115 0.6529462 -0.3427546 0.8831039 0.2231131 -0.4127326 0.7464245 0.6493703 -0.1454948 0.8646607 0.4828287 -0.1387023 0.259129 0.9452109 -0.1985663 0.2533007 0.7859227 -0.5640607 0.2572175 0.9470904 -0.1919869 0.2901469 0.9387161 -0.1860832 0.283828 0.9432902 -0.1721788 0.3236519 0.93427 -0.1496302 0.3126392 0.9397215 -0.138493 0.3469391 0.9325644 -0.09978497 0.3352813 0.9374089 -0.09408026 0.3572794 0.9330789 -0.04141628 0.3550336 0.9339462 -0.04118126 0.2500065 0.7974204 -0.5491971 0.3732368 0.764718 -0.5252626 0.3641853 0.7852717 -0.5007171 0.5047808 0.7534751 -0.4212741 0.490231 0.7719614 -0.4046594 0.5996577 0.7491502 -0.2813976 0.5857669 0.7626597 -0.274276 0.650762 0.7499525 -0.1186601 0.6529862 0.7479751 -0.1189218 0.8654223 0.4891301 -0.1086099 0.8686208 0.4835653 -0.1079933 0.6511198 0.7554986 -0.07256031 0.657943 0.7496321 -0.07185238 0.3520233 0.9356472 -0.02537667 0.3561813 0.9340779 -0.02516824 0.8123207 0.5055786 -0.2907325 0.8189979 0.4934692 -0.2927979 0.6108223 0.7684052 -0.1909177 0.6223441 0.758154 -0.1946547 0.3305344 0.9415164 -0.06552803 0.3422731 0.937044 -0.06926512 0.05509299 -0.2694422 -0.9614394 0.2347539 0.9044108 -0.3562748 0.4916572 -0.01240348 -0.8707005 0.3616053 0.9021347 -0.2353603 0.6766012 0.5292515 -0.5119606 0.3048654 0.9463174 -0.1074271 0.524598 0.7838898 -0.3321354 0.2709805 0.9591752 -0.08094823 0.2286792 0.9667905 -0.1141136 0.2108109 0.9737662 -0.08566492 0.1318402 0.9849554 -0.1117184 0.1311885 0.9853175 -0.1092662 0.5061583 0.8023408 -0.316312 0.3695434 0.8275371 -0.4226347 0.2862455 0.9166575 -0.2789312 0.176092 0.838539 -0.5156007 0.1718482 0.8575259 -0.4848892 0.01443195 0.8719677 -0.4893507 0.04700434 0.8707268 -0.4895156 0.0468707 0.8727776 -0.4858626 0.05747926 0.9923554 -0.1092109 0.05743426 0.9924575 -0.1083028 -0.02363085 0.9937795 -0.1088303 -0.02389997 0.9945926 -0.1010661 -0.01431977 0.7199838 -0.6938432 -0.03284388 0.8768758 -0.4795937 -0.04006278 -0.2650812 -0.9633935 -0.1585857 0.9834416 0.08771163 -0.2333474 0.8937983 -0.3829801 -0.4935358 0.4909747 -0.7178902 -0.362328 0.9128108 -0.1884016 -0.6268708 0.5295338 -0.5715129 -0.1341935 0.9856377 -0.1025205 -0.1349698 0.9842289 -0.114354 -0.2183527 0.9722524 -0.08394855 -0.2312806 0.9660587 -0.115065 -0.2757452 0.9579811 -0.07897388 -0.3033115 0.9465716 -0.1095647 -0.1260843 0.8679765 -0.480333 -0.2020553 0.5488973 -0.8111015 -0.2363581 0.9081537 -0.3455312 -0.3813419 0.824166 -0.4187228 -0.3912594 0.8049505 -0.4460616 -0.4191642 0.8808054 -0.2201892 -0.5203214 0.7842541 -0.3379519 -0.7833651 0.5099918 -0.3553133 -0.7811226 0.5155794 -0.3521724 -0.592605 0.7707231 -0.2341058 -0.5886309 0.774915 -0.230262 -0.3271045 0.941349 -0.08285373 -0.3222711 0.9433662 -0.07875031 -0.8544709 0.4880099 -0.1781178 -0.8516537 0.4934278 -0.176678 -0.6441086 0.7558375 -0.117618 -0.6399484 0.7596232 -0.1159254 -0.3513645 0.9353044 -0.04182094 -0.344997 0.9377672 -0.03962218 -0.8654601 0.4905446 -0.1017106 -0.9352959 0.3089222 -0.1725937 -0.7110689 0.6663064 -0.2245371 -0.8746709 0.1734194 -0.4526329 -0.6109183 0.68093 -0.4038729 -0.6813007 0.1632806 -0.7135607 -0.4629477 0.7051371 -0.5370858 -0.4113352 0.1694226 -0.8956 -0.2902289 0.7325207 -0.6157765 -0.236804 0.5987619 -0.7651197 -0.3527022 0.9354513 -0.02306544 -0.649374 0.7575604 -0.06645131 -0.3539106 0.934982 -0.02358341 -0.3458968 0.9361764 -0.06268239 -0.3540495 0.9327943 -0.06740689 -0.3268957 0.9382714 -0.1130753 -0.3368665 0.9332124 -0.1250432 -0.300983 0.941015 -0.1545968 -0.3066509 0.9363266 -0.171049 -0.2678309 0.9455918 -0.1847236 -0.2679071 0.947453 -0.1748107 -0.6508774 0.7561763 -0.06749916 -0.6254315 0.7583806 -0.1835605 -0.6346793 0.7491542 -0.1896055 -0.5491505 0.7662749 -0.3335517 -0.5607096 0.7503534 -0.3501064 -0.4349894 0.7775301 -0.4541268 -0.4411647 0.758252 -0.4800288 -0.2887132 0.7944217 -0.5343584 -0.293263 0.8141487 -0.5011577 -0.237096 0.5961247 -0.767086 -0.2370668 0.5960634 -0.7671427 -0.3195422 0.8034002 -0.502435 -0.3195562 0.8034324 -0.5023747 -0.3638994 0.9149187 -0.1746456 -0.3638953 0.9149529 -0.1744748 -0.2880679 0.941549 -0.1746501 -0.2880945 0.9415633 -0.1745286 -0.2529821 0.8268508 -0.5023124 -0.2529592 0.8267576 -0.5024775 -0.1876903 0.6133751 -0.7671658 -0.1876853 0.6134017 -0.7671459 0.6428068 0 -0.7660284 0.6412109 -1.51229e-4 -0.7673647 0.8191214 7.44372e-5 -0.5736203 0.817964 0 -0.5752694 0.9062867 0 -0.4226635 0.9058591 -3.58716e-5 -0.4235793 0.9848145 7.82796e-5 -0.1736099 0.9846302 0 -0.1746525 0.9837508 0.04646259 -0.1734234 0.9837509 0.04647278 -0.1734199 0.6296943 0.2010678 -0.7503712 0.6296774 0.201067 -0.7503857 0.8583225 0.1328008 -0.4956275 0.8102472 0.1469019 -0.5673795 0.9005422 0.1125124 -0.4199581 0.983747 0.126983 -0.1269544 0.9837557 0.1269333 -0.1269363 0.8582935 0.3628467 -0.36287 0.8583256 0.3628361 -0.3628047 0.6297932 0.5492485 -0.5492603 0.6296675 0.5493237 -0.549329 0.9837665 0.1733356 -0.04645937 0.983753 0.1734097 -0.04646706 0.858323 0.4956263 -0.1328012 0.8583165 0.4956378 -0.1328004 0.6296474 0.7504137 -0.2010561 0.629812 0.7502805 -0.2010378 0.9848181 0.1735901 0 0.9848119 0.1736255 0 0.8660081 0.5000302 0 0.865992 0.5000581 0 0.6429259 0.7659285 0 0.6429077 0.7659437 0 0.6296597 0.2010675 -0.7504003 0.6296773 0.2010691 -0.7503852 0.8583402 0.132799 -0.4955971 0.8583363 0.1327956 -0.4956048 0.983751 0.04646396 -0.173422 0.9837524 0.04646903 -0.1734124 0.6296819 0.5493105 -0.5493257 0.6296645 0.5493392 -0.5493169 0.8583334 0.3628073 -0.3628152 0.8583223 0.3628396 -0.3628091 0.983754 0.1269477 -0.1269353 0.9837533 0.1269332 -0.1269547 0.6296689 0.7503904 -0.2010759 0.6298093 0.7502788 -0.2010526 0.8583253 0.4956225 -0.1328015 0.8583199 0.4956305 -0.1328065 0.9837487 0.173433 -0.04646992 0.983756 0.1733934 -0.04646426 -0.6296245 0.1220414 -0.7672542 -0.9857761 0.0264061 -0.1659771 -0.8671791 0.07822084 -0.491815 -0.9857721 0.02640241 -0.1660009 -0.9856551 0.0806204 -0.1482716 -0.9856532 0.08063125 -0.1482784 -0.625376 0.5786776 -0.5234857 -0.6296369 0.1220288 -0.767246 -0.6279986 0.3717789 -0.6836652 -0.6280251 0.3717752 -0.683643 -0.6297948 0.5763623 -0.5207351 -0.845204 0.3958258 -0.3590992 -0.9802516 0.1470359 -0.1322394 -0.985853 0.1225357 -0.1143625 -0.8616186 0.377873 -0.3388592 -0.8607197 0.2432268 -0.4472162 -0.8607457 0.2431802 -0.4471916 -0.8616263 0.07863426 -0.5014149 -0.7553374 0.102909 -0.6472058 -0.9771751 0.1977785 -0.07754004 -0.6826289 0.687838 -0.2467727 -0.6257585 0.6830403 -0.3766728 -0.4291973 0.8131675 -0.3931266 -0.8445534 0.4865026 -0.223707 -0.9788963 0.1901308 -0.07491743 -0.8441437 0.487127 -0.2238945 -0.8406829 0.5348195 -0.08497387 -0.3620601 0.9193738 -0.1538321 -0.6119174 0.7842636 -0.1024101 -0.9759442 0.2159952 -0.02965182 -0.9762685 0.2145414 -0.0295301 -0.8866761 0.4568523 -0.07135301 -0.7929282 0.6027241 -0.08937871 -0.9763731 0.2160916 0 -0.9545618 0.2980065 -0.0019629 -0.6151192 0.7884342 0 -0.6834775 0.729969 -0.001984417 -0.7960867 0.6051828 1.39579e-5 -0.8889195 0.4580635 -1.67225e-5 0.9848157 0 -0.1736033 0.9848151 0 -0.1736071 0.8660107 0 -0.5000256 0.866005 0 -0.5000354 0.6427932 0 -0.7660397 0.6427929 0 -0.7660401 -0.3695703 0.9292029 0 -0.3775343 0.923232 -0.07148844 -0.2915523 0.9528751 0.08382266 -0.3010287 0.9535924 -0.006575405 -0.2447168 0.9695938 0.001280486 -0.2457429 0.9693351 -3.19241e-4 -0.224654 0.9744385 5.37906e-4 -0.2229359 0.9748293 0.002720475 -0.2051666 0.9787256 -0.001749634 -0.1976606 0.9802652 0.003223061 -0.1883575 0.9820986 -0.00195676 -0.1880124 0.9821667 3.06773e-5 -0.1786941 0.9839048 -9.84206e-5 -0.1790312 0.9838434 2.87635e-4 -0.1739741 0.9847502 -3.45904e-4 -0.1738803 0.9847668 2.22301e-4 -0.1661953 0.9860928 -3.04961e-4 -0.1655002 0.9862089 0.001333713 -0.1567296 0.9876372 -0.002967596 -0.1722815 0.984678 -0.0269913 -0.1307449 0.9914043 0.004841566 -0.1169728 0.9930905 -0.009417653 -0.1097666 0.9939565 0.001337468 -0.09140557 0.9958134 -8.71307e-4 -0.0930863 0.9956544 -0.002725481 -0.04154556 0.9989326 0.02019411 -0.04377561 0.9990414 0 0.01838368 0.9998311 0 0.04578715 0.9952129 0.08634275 0.1088622 0.9938857 0.018449 0.09299278 0.995663 -0.002765655 0.05991303 0.9981318 0.01197147 0.1108625 0.9922199 -0.05664885 0.1240113 0.9922599 0.006459772 0.1649114 0.9861325 -0.01862823 0.1587353 0.9872723 -0.00982064 0.1608728 0.9869751 -3.27662e-4 0.1693821 0.9855504 4.76064e-4 0.1725721 0.9849941 -0.002335071 0.1716622 0.9851556 7.71887e-4 0.1740715 0.9847328 -7.58471e-4 0.1737534 0.9847885 0.001126825 0.1766 0.9842824 -7.73732e-4 0.173333 0.9848396 0.006830155 0.1870599 0.9823392 -0.004288852 0.1863983 0.9823543 0.01535284 0.3786372 0.9255453 0 0.3712524 0.9270654 -0.05216723 0.3004318 0.9516913 0.06343835 0.2933295 0.9559955 -0.005523085 0.2398083 0.9708185 0.001889646 0.2412189 0.9704124 0.0106396 0.2219837 0.9750305 -0.00623548 0.2222927 0.9749766 -0.002579391 0.2057046 0.9786134 0.001238822 0.201368 0.9794721 -0.009240508 0.003477036 0.9972733 -0.07371538 0.3786848 0.9255258 0 0.3315592 0.9403585 -0.07612192 0.2297169 0.9638259 0.1351667 0.1813958 0.9822028 -0.04871779 0.09659248 0.9953222 0.001932024 0.03984504 0.9991879 -0.006006777 -0.3617478 0.9319424 0.02494287 -0.3690711 0.9290828 -0.02432626 -0.2006587 0.9796092 0.01010531 -0.2079341 0.9781051 -0.008589327 -0.1148005 0.9933629 0.007141351 -0.1183504 0.9929719 0 -0.03798562 0.9992783 0 -0.6492711 0.760118 -0.02584367 -0.5518446 0.8339461 0.001232385 -0.5129423 0.858324 -0.01304805 -0.5214532 0.8525588 -0.03507483 -0.4890875 0.8722288 -0.003223717 -0.999547 0.03009724 0 -0.9576997 0.1749035 -0.2285169 -0.8415648 0.193058 -0.5044773 -0.9328377 0.3397193 -0.1200199 -0.900226 0.4353677 0.006935715 -0.8953443 0.4441374 0.03317385 -0.8397529 0.5414489 -0.0405991 -0.8358255 0.5488198 -0.01387524 -0.7678679 0.6405012 0.01171356 -0.7733395 0.6338841 -0.01170593 -0.6557838 0.7545055 0.02586811 0 0.1781747 -0.9839989 -1.22563e-5 0.1781792 -0.9839981 -1.45252e-5 0.1781775 -0.9839984 3.50388e-6 0.1781767 -0.9839985 4.31583e-4 0.1781178 -0.9840091 -1.14315e-4 0.1781881 -0.9839965 3.63967e-5 0.1781755 -0.9839988 7.80712e-5 0.1781193 -0.984009 0 0.1781759 -0.9839987 1.05634e-5 0.1781724 -0.9839993 -2.29751e-6 0.1781772 -0.9839985 -3.14672e-6 0.1781806 -0.9839979 0.5871493 -0.3114327 -0.7471716 0.4467755 -0.4236584 -0.7879755 0.525636 -0.2203392 -0.8216796 0.6176503 -0.4324871 -0.6568586 0.3487918 -0.6760649 -0.6490613 0.5471085 -0.4192813 -0.724483 0.560268 -0.3923012 -0.7295201 -1.23482e-5 0 -1 -1.64545e-6 0 -1 0.5725948 0.8177518 0.05845737 0.5724743 0.8177734 0.05932867 0.5725944 0.817754 0.05842959 0.5726097 0.8177418 0.0584532 0.5725956 0.8177519 0.0584498 0.5725933 0.8177505 0.05849081 0.572593 0.8177583 0.05838561 0.5725942 0.8177535 0.05843889 0.5725968 0.8177511 0.05844849 0.5725955 0.8177518 0.05845165 0.5725976 0.8177501 0.05845278 0.5725957 0.8177518 0.05844849 0.4604038 0.6750443 0.5764925 0.5177595 0.7394385 0.4302977 0.5174958 0.7392902 0.4308691 0.4581561 0.6539553 0.6020261 0.3006364 0.437058 0.8477017 0.4127914 0.5803861 0.7019653 0.3471959 0.5082055 0.7881512 0.2679637 0.3568674 0.8948974 0.1142778 0.1632057 0.9799513 -0.07990467 -0.04065716 0.9959731 0.0330277 0.07857763 0.9963608 0.1907846 0.2697642 0.9438372 0.2476089 0.3545929 0.9016395 -0.8191522 0.5735763 0 -0.8191522 0.5735763 0 0.1950942 -0.9807845 0 0.555572 -0.8314684 0 0.5555636 -0.8314741 0 0.8314741 -0.5555636 0 0.831471 -0.5555682 0 0.9807851 -0.1950916 0 0.9807853 -0.1950908 0 -5.35722e-6 0 -1 4.97814e-7 0 -1 -8.18505e-6 0 -1 4.97814e-7 0 1 -0.1234194 -0.9923546 0 -0.1234218 -0.9923544 0 -2.04636e-6 0 -1 -8.18451e-6 0 -1 2.87409e-6 0 -1 8.18451e-6 0 -1 -2.30237e-6 0 -1 2.87396e-6 0 -1 -2.04609e-6 0 1 3.59249e-6 0 1 -2.87406e-6 0 1 -0.980785 -0.195092 0 -0.9807855 -0.1950897 0 -0.831474 -0.5555638 0 -0.8314702 -0.5555694 0 -0.5555721 -0.8314684 0 -0.5555637 -0.8314741 0 -0.1950855 -0.9807862 0 -0.1950856 -0.9807862 0 -0.1950856 0.9807862 0 -0.1950855 0.9807862 0 -0.5555721 0.8314684 0 -0.8314664 0.5555751 0 -0.8314664 0.5555751 0 -0.9807859 0.1950874 0 -0.9807855 0.1950897 0 0.9807857 0.1950884 0 0.9807856 0.1950893 0 0.8314672 0.5555738 0 0.8314666 0.5555749 0 0.555572 0.8314684 0 0.1950855 0.9807863 0 0.1950855 -0.9807863 0 -0.3734973 -0.3734973 0.849117 -0.510196 -0.1367083 0.8491237 0.3734957 -0.3734957 0.8491184 0.1367117 -0.510203 0.8491189 -0.1367106 -0.5101976 0.8491224 0.373493 0.3734943 0.8491201 0.5102041 0.1367079 0.8491188 0.5102004 -0.1367082 0.849121 -0.373493 0.3734943 0.8491201 -0.1367087 0.5102 0.8491212 0.1367086 0.5102009 0.8491206 -0.5102041 0.1367092 0.8491187 -0.9659242 -0.2588255 0 -0.9659265 -0.2588167 0 -0.7070996 -0.707114 0 -0.7071126 -0.7071011 0 -0.2588163 -0.9659266 0 -0.2588264 -0.9659239 0 0.2588156 -0.9659268 0 0.2588264 -0.9659239 0 0.7071011 -0.7071126 0 0.7071126 -0.7071011 0 0.9659242 -0.2588255 0 0.9659272 -0.258814 0 0.9659257 0.2588198 0 0.9659272 0.258814 0 0.7071011 0.7071126 0 0.7071126 0.7071011 0 0.2588049 0.9659297 0 0.2588264 0.9659239 0 -0.2588049 0.9659297 0 -0.258827 0.9659237 0 -0.7071011 0.7071126 0 -0.7071111 0.7071025 0 -0.9659249 0.2588224 0 -0.9659272 0.258814 0 -9.14463e-7 0 -1 9.34377e-7 0 -1 2.05665e-7 0 -1 -0.7071038 -1.99735e-6 0.7071098 -0.7071089 -3.93185e-6 0.7071048 -0.7071061 -7.26401e-7 0.7071076 -0.7070915 -2.14733e-6 0.7071222 -0.7071188 0 0.7070947 -0.7071039 3.9318e-6 0.7071098 -0.7071128 1.99744e-6 0.7071008 -0.7070575 0 0.7071561 -0.7071611 -3.91886e-5 0.7070525 -0.7070981 3.53799e-5 0.7071155 -0.7071121 0 0.7071015 -0.7071047 1.05779e-6 0.7071089 -0.7071013 0 0.7071123 -0.7071173 0 0.7070963 -0.1013575 0.5208817 0.8475902 -0.1013637 -0.5208746 0.8475937 0.02189457 -0.5037699 0.8635605 0.0268203 -0.5022214 0.8643231 0.1570921 -0.4986498 0.8524497 0.2703937 -0.438551 0.8570649 0.3798487 -0.3623072 0.8511455 0.3822479 -0.3607374 0.850738 0.4498695 -0.2511173 0.8570634 0.5100052 -0.1287791 0.8504766 0.5099988 -0.1395665 0.848777 0.5107446 0.1289648 0.8500047 0.5051673 0.1393564 0.8516958 0.4497143 0.2509878 0.8571828 0.3810852 0.3625165 0.8505033 0.3821212 0.3606239 0.8508431 0.2704 0.4385613 0.8570576 0.09349775 0.5282979 0.8438956 0.145219 0.4609639 0.8754563 0.02189457 0.5037699 0.8635605 0.8705886 0.4920118 0 -0.4234609 0.9057247 -0.01854062 -0.2588138 0.9659273 0 -0.7071067 0.707107 0 -0.9910684 0.1324852 -0.01520895 -0.9238796 0.3826836 0 -0.7071076 0.707106 0 -0.99203 -0.1260023 0 -0.9659266 0.2588162 0 -0.9920302 -0.1260002 0 -0.9914492 -0.1304937 2.64712e-4 -0.9256129 -0.3784717 -2.72897e-4 -0.9238809 -0.3826802 0 -0.707111 -0.7071025 0 -0.2588102 -0.9659133 -0.005380332 -0.4385465 -0.8987086 0 -0.707111 -0.7071026 0 0.8705223 -0.4921292 0 0.9682319 -0.2499992 -0.005234122 0.8731639 -0.4874269 1.99575e-4 0.8705161 -0.4921399 0 0.7272716 -0.6863499 0 0.7071077 -0.7071008 -0.002703309 0.524833 -0.8512053 0 0.3004773 -0.953789 0 0.2588143 -0.9659196 -0.003807723 0.04341095 -0.9990574 0 -0.1910163 -0.9815869 0 0.707102 0.7071066 -0.002670228 0.7272676 0.6863541 0 0.8705893 0.4920104 0 0.8732029 0.487357 1.86673e-4 0.9682319 0.2499994 -0.005236148 0.9695693 0.2448171 0 0.9695693 -0.2448171 0 -0.1910044 0.9815892 0 0.04341095 0.9990574 0 0.2588142 0.9659199 -0.003759503 0.3004772 0.953789 0 0.5248375 0.8512026 0 0.08361488 -0.9964982 0 -4.57892e-6 0 -1 2.63696e-5 0 -1 -4.13584e-7 0 -1 0.8162303 -0.5777266 4.79136e-4 0.8169498 -0.5767089 0 0.5438132 -0.8392064 0 0.5438112 -0.8392076 0 0.1904842 -0.9816902 0 0.1904832 -0.9816905 0 0.9332108 -0.3593289 5.22884e-4 0.9991801 -0.04048675 0 0.9991802 -0.04048538 0 0.9830372 -0.1834067 0 0.9640046 -0.2619394 -0.04564052 0.9599629 -0.2801277 0 0.9330288 -0.3598017 0 5.30945e-7 0 -1 5.19022e-6 0 -1 7.13467e-7 0 1 1.13497e-6 0 1 2.00325e-6 0 1 -1.56876e-6 0 1 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 11 3 11 4 10 4 12 4 11 5 12 5 13 5 13 6 12 6 14 6 4 7 3 7 15 7 15 8 3 8 16 8 15 9 16 9 9 9 9 10 16 10 17 10 9 11 17 11 10 11 18 12 19 12 20 12 20 13 19 13 21 13 20 14 21 14 22 14 22 15 21 15 23 15 22 16 23 16 2 16 2 17 23 17 24 17 2 18 24 18 0 18 14 19 6 19 13 19 13 20 6 20 8 20 13 21 8 21 25 21 25 22 8 22 26 22 25 23 26 23 27 23 27 24 26 24 28 24 28 25 26 25 29 25 28 26 29 26 30 26 30 27 29 27 31 27 31 28 29 28 32 28 31 29 32 29 33 29 34 30 35 30 32 30 32 31 35 31 36 31 32 32 36 32 33 32 37 33 38 33 34 33 34 34 38 34 39 34 34 35 39 35 35 35 40 36 41 36 42 36 42 37 41 37 43 37 42 38 43 38 37 38 37 39 43 39 44 39 37 40 44 40 38 40 40 41 42 41 45 41 45 42 42 42 46 42 45 43 46 43 47 43 47 44 46 44 48 44 48 45 46 45 49 45 48 46 49 46 50 46 50 47 49 47 51 47 51 48 49 48 52 48 51 49 52 49 53 49 53 50 52 50 54 50 54 51 52 51 55 51 54 52 55 52 56 52 56 53 55 53 57 53 57 54 55 54 58 54 57 55 58 55 18 55 18 56 58 56 59 56 18 57 59 57 19 57 60 58 61 58 62 58 63 59 64 59 65 59 65 60 64 60 66 60 65 61 66 61 67 61 60 62 62 62 68 62 68 63 62 63 69 63 68 64 69 64 70 64 70 65 69 65 71 65 70 66 71 66 72 66 72 67 71 67 73 67 72 68 73 68 74 68 74 69 73 69 75 69 74 70 75 70 63 70 63 71 75 71 76 71 63 72 76 72 64 72 77 73 67 73 78 73 78 74 67 74 66 74 79 75 77 75 78 75 80 76 81 76 82 76 82 77 81 77 83 77 82 78 83 78 84 78 84 79 83 79 85 79 84 80 85 80 86 80 86 81 85 81 87 81 86 82 87 82 88 82 88 83 87 83 89 83 89 84 87 84 90 84 89 85 90 85 91 85 75 86 73 86 92 86 92 87 93 87 94 87 75 88 92 88 95 88 95 89 92 89 94 89 95 90 94 90 96 90 97 91 98 91 99 91 99 92 98 92 100 92 99 93 100 93 101 93 101 94 100 94 92 94 101 95 92 95 102 95 102 96 92 96 73 96 102 97 73 97 71 97 98 98 90 98 100 98 100 99 90 99 87 99 100 100 87 100 92 100 92 101 87 101 85 101 92 102 85 102 93 102 93 103 85 103 83 103 103 104 104 104 91 104 91 105 104 105 89 105 89 106 104 106 88 106 88 107 104 107 105 107 88 108 105 108 86 108 86 109 105 109 84 109 84 110 105 110 106 110 84 111 106 111 82 111 82 112 106 112 107 112 82 113 107 113 80 113 108 114 109 114 105 114 105 115 109 115 110 115 105 116 110 116 106 116 106 117 110 117 111 117 106 118 111 118 107 118 112 119 113 119 114 119 108 120 105 120 115 120 115 121 105 121 104 121 115 122 104 122 114 122 114 123 104 123 103 123 114 124 103 124 112 124 107 125 111 125 80 125 80 126 111 126 81 126 96 127 76 127 95 127 95 128 76 128 75 128 116 129 117 129 118 129 119 130 22 130 120 130 120 131 22 131 2 131 120 132 2 132 121 132 122 133 18 133 119 133 119 134 18 134 20 134 119 135 20 135 22 135 123 136 53 136 124 136 124 137 53 137 54 137 124 138 54 138 125 138 125 139 54 139 56 139 125 140 56 140 122 140 122 141 56 141 57 141 122 142 57 142 18 142 126 143 50 143 123 143 123 144 50 144 51 144 123 145 51 145 53 145 41 146 40 146 127 146 127 147 40 147 45 147 127 148 45 148 128 148 128 149 45 149 47 149 128 150 47 150 126 150 126 151 47 151 48 151 126 152 48 152 50 152 41 153 127 153 43 153 43 154 127 154 129 154 43 155 129 155 44 155 44 156 129 156 130 156 44 157 130 157 38 157 38 158 130 158 39 158 39 159 130 159 131 159 39 160 131 160 35 160 35 161 131 161 132 161 35 162 132 162 36 162 36 163 132 163 33 163 33 164 132 164 133 164 33 165 133 165 31 165 31 166 133 166 30 166 30 167 133 167 134 167 30 168 134 168 28 168 28 169 134 169 135 169 28 170 135 170 27 170 27 171 135 171 136 171 27 172 136 172 25 172 25 173 136 173 13 173 13 174 136 174 137 174 13 175 137 175 11 175 11 176 137 176 9 176 9 177 137 177 138 177 9 178 138 178 15 178 15 179 138 179 139 179 15 180 139 180 4 180 4 181 139 181 5 181 5 182 139 182 140 182 5 183 140 183 141 183 141 184 140 184 77 184 141 185 77 185 79 185 142 186 65 186 67 186 142 187 67 187 143 187 65 188 142 188 63 188 63 189 142 189 144 189 63 190 144 190 74 190 145 191 70 191 72 191 145 192 72 192 146 192 70 193 145 193 68 193 68 194 145 194 118 194 68 195 118 195 60 195 60 196 118 196 117 196 60 197 117 197 61 197 116 198 118 198 147 198 147 199 118 199 145 199 147 200 145 200 148 200 148 201 145 201 146 201 148 202 146 202 149 202 149 203 146 203 150 203 149 204 150 204 151 204 151 205 150 205 152 205 151 206 152 206 153 206 153 207 152 207 154 207 153 208 154 208 155 208 155 209 154 209 156 209 155 210 156 210 157 210 157 211 156 211 158 211 157 212 158 212 159 212 159 213 158 213 160 213 159 214 160 214 161 214 161 215 160 215 162 215 161 216 162 216 163 216 163 217 162 217 164 217 163 218 164 218 165 218 165 219 164 219 166 219 165 220 166 220 167 220 167 221 166 221 168 221 167 222 168 222 169 222 169 223 168 223 170 223 169 224 170 224 171 224 171 225 170 225 172 225 171 226 172 226 173 226 173 227 172 227 174 227 173 228 174 228 175 228 175 229 174 229 176 229 175 230 176 230 177 230 177 231 176 231 178 231 177 232 178 232 179 232 179 233 178 233 180 233 179 234 180 234 181 234 181 235 180 235 182 235 181 236 182 236 183 236 183 237 182 237 184 237 183 238 184 238 185 238 185 239 184 239 186 239 185 240 186 240 187 240 187 241 186 241 188 241 187 242 188 242 189 242 189 243 188 243 190 243 189 244 190 244 191 244 191 245 190 245 192 245 191 246 192 246 193 246 193 247 192 247 194 247 193 248 194 248 195 248 196 249 197 249 198 249 2 250 1 250 121 250 121 251 1 251 199 251 121 252 199 252 197 252 197 253 196 253 121 253 121 254 196 254 200 254 121 255 200 255 120 255 120 256 200 256 201 256 120 257 201 257 119 257 119 258 201 258 202 258 119 259 202 259 122 259 122 260 202 260 203 260 122 261 203 261 125 261 125 262 203 262 204 262 125 263 204 263 124 263 124 264 204 264 205 264 124 265 205 265 123 265 123 266 205 266 206 266 123 267 206 267 126 267 126 268 206 268 207 268 126 269 207 269 128 269 128 270 207 270 208 270 128 271 208 271 127 271 127 272 208 272 209 272 127 273 209 273 129 273 129 274 209 274 210 274 129 275 210 275 130 275 130 276 210 276 211 276 130 277 211 277 131 277 131 278 211 278 212 278 131 279 212 279 132 279 132 280 212 280 213 280 132 281 213 281 133 281 133 282 213 282 214 282 133 283 214 283 134 283 134 284 214 284 215 284 134 285 215 285 135 285 135 286 215 286 216 286 135 287 216 287 136 287 136 288 216 288 217 288 136 289 217 289 137 289 137 290 217 290 218 290 137 291 218 291 138 291 138 292 218 292 219 292 138 293 219 293 139 293 139 294 219 294 143 294 139 295 143 295 140 295 140 296 143 296 67 296 140 297 67 297 77 297 220 298 195 298 198 298 198 299 195 299 194 299 198 300 194 300 196 300 196 301 194 301 192 301 196 302 192 302 200 302 200 303 192 303 190 303 200 304 190 304 201 304 201 305 190 305 188 305 201 306 188 306 202 306 202 307 188 307 186 307 202 308 186 308 203 308 203 309 186 309 184 309 203 310 184 310 204 310 204 311 184 311 182 311 204 312 182 312 205 312 205 313 182 313 180 313 205 314 180 314 206 314 206 315 180 315 178 315 206 316 178 316 207 316 207 317 178 317 176 317 207 318 176 318 208 318 208 319 176 319 174 319 208 320 174 320 209 320 209 321 174 321 172 321 209 322 172 322 210 322 210 323 172 323 170 323 210 324 170 324 211 324 211 325 170 325 168 325 211 326 168 326 212 326 212 327 168 327 166 327 212 328 166 328 213 328 213 329 166 329 164 329 213 330 164 330 214 330 214 331 164 331 162 331 214 332 162 332 215 332 215 333 162 333 160 333 215 334 160 334 216 334 216 335 160 335 158 335 216 336 158 336 217 336 217 337 158 337 156 337 217 338 156 338 218 338 218 339 156 339 154 339 218 340 154 340 219 340 219 341 154 341 152 341 219 342 152 342 143 342 143 343 152 343 150 343 143 344 150 344 142 344 142 345 150 345 146 345 142 346 146 346 144 346 144 347 146 347 72 347 144 348 72 348 74 348 42 349 37 349 221 349 222 350 223 350 59 350 224 351 225 351 7 351 7 352 225 352 37 352 7 353 37 353 8 353 221 354 226 354 59 354 59 355 226 355 227 355 34 356 32 356 29 356 228 357 221 357 229 357 229 358 221 358 37 358 229 359 37 359 230 359 230 360 37 360 225 360 34 361 29 361 37 361 37 362 29 362 26 362 37 363 26 363 8 363 59 364 58 364 221 364 221 365 58 365 55 365 221 366 55 366 52 366 227 367 231 367 59 367 59 368 231 368 232 368 59 369 232 369 222 369 52 370 49 370 221 370 221 371 49 371 46 371 221 372 46 372 42 372 233 373 234 373 235 373 235 374 234 374 236 374 235 375 236 375 237 375 237 376 236 376 238 376 195 377 220 377 116 377 116 378 220 378 239 378 116 379 239 379 240 379 147 380 177 380 179 380 147 381 191 381 116 381 116 382 191 382 193 382 116 383 193 383 195 383 171 384 173 384 149 384 179 385 181 385 147 385 147 386 181 386 183 386 147 387 183 387 185 387 161 388 163 388 165 388 147 389 148 389 177 389 177 390 148 390 149 390 177 391 149 391 175 391 175 392 149 392 173 392 240 393 241 393 116 393 116 394 241 394 242 394 116 395 242 395 243 395 243 396 242 396 244 396 243 397 244 397 238 397 238 398 244 398 237 398 237 399 244 399 245 399 185 400 187 400 147 400 147 401 187 401 189 401 147 402 189 402 191 402 171 403 149 403 169 403 169 404 149 404 151 404 169 405 151 405 153 405 153 406 155 406 169 406 169 407 155 407 157 407 169 408 157 408 167 408 167 409 157 409 165 409 165 391 157 391 159 391 165 410 159 410 161 410 246 411 247 411 248 411 248 412 247 412 249 412 248 413 249 413 250 413 250 414 249 414 251 414 246 415 252 415 247 415 247 416 252 416 253 416 247 417 253 417 254 417 254 418 253 418 255 418 256 419 257 419 258 419 258 420 257 420 259 420 258 421 259 421 260 421 261 422 262 422 263 422 263 423 262 423 264 423 265 424 266 424 267 424 267 425 266 425 258 425 267 426 258 426 264 426 264 427 258 427 260 427 264 428 260 428 263 428 268 429 269 429 270 429 270 430 269 430 271 430 270 431 271 431 272 431 273 432 274 432 275 432 275 433 274 433 276 433 275 434 276 434 277 434 277 435 276 435 278 435 277 436 278 436 279 436 279 437 278 437 280 437 279 438 280 438 281 438 272 439 271 439 281 439 281 440 271 440 282 440 281 441 282 441 279 441 279 442 282 442 283 442 279 443 283 443 277 443 269 444 284 444 285 444 269 445 285 445 271 445 271 446 285 446 286 446 271 447 286 447 282 447 282 448 286 448 287 448 282 449 287 449 283 449 288 450 289 450 290 450 291 451 262 451 261 451 291 452 261 452 289 452 251 453 288 453 250 453 250 454 288 454 290 454 250 455 290 455 248 455 292 456 252 456 290 456 290 457 252 457 246 457 290 458 246 458 248 458 289 459 261 459 290 459 290 460 261 460 263 460 290 461 263 461 292 461 293 462 294 462 295 462 296 463 297 463 298 463 298 464 297 464 265 464 298 465 293 465 296 465 296 466 293 466 295 466 296 467 295 467 297 467 297 468 295 468 299 468 300 469 268 469 270 469 300 470 270 470 301 470 301 471 302 471 303 471 303 472 302 472 295 472 303 473 295 473 294 473 280 474 278 474 304 474 304 475 278 475 276 475 304 476 276 476 274 476 274 477 305 477 304 477 304 478 305 478 302 478 304 479 302 479 306 479 306 480 302 480 301 480 301 481 270 481 306 481 306 482 270 482 272 482 306 483 272 483 304 483 304 484 272 484 281 484 304 485 281 485 280 485 274 486 307 486 305 486 305 487 307 487 308 487 305 488 308 488 302 488 302 489 308 489 299 489 302 490 299 490 295 490 264 491 309 491 267 491 267 492 309 492 298 492 267 493 298 493 265 493 310 494 311 494 312 494 313 495 284 495 314 495 315 496 312 496 316 496 316 497 312 497 317 497 316 498 317 498 318 498 318 499 317 499 319 499 318 500 319 500 320 500 320 501 319 501 321 501 286 498 285 498 287 498 287 502 285 502 284 502 287 503 284 503 322 503 322 504 284 504 323 504 315 505 324 505 312 505 312 506 324 506 325 506 312 507 325 507 310 507 323 508 284 508 326 508 326 509 284 509 313 509 326 510 313 510 327 510 327 511 328 511 326 511 326 512 328 512 329 512 326 513 329 513 319 513 319 514 329 514 330 514 319 515 330 515 321 515 331 516 332 516 333 516 314 498 249 498 313 498 313 517 249 517 334 517 313 518 334 518 335 518 335 498 334 498 336 498 335 519 336 519 337 519 337 498 336 498 331 498 337 498 331 498 338 498 338 520 331 520 333 520 339 521 340 521 341 521 342 522 343 522 341 522 341 523 343 523 344 523 341 524 344 524 339 524 345 523 346 523 347 523 347 523 348 523 345 523 345 523 348 523 349 523 345 523 349 523 350 523 351 525 352 525 353 525 353 523 352 523 354 523 62 526 61 526 117 526 116 523 243 523 117 523 117 523 243 523 238 523 117 527 238 527 62 527 352 528 351 528 355 528 356 528 357 528 358 528 359 528 360 528 355 528 355 528 360 528 361 528 355 528 361 528 352 528 352 528 361 528 362 528 363 529 364 529 365 529 365 528 364 528 366 528 362 528 367 528 352 528 352 530 367 530 368 530 352 531 368 531 369 531 370 528 352 528 371 528 371 532 352 532 358 532 371 533 358 533 372 533 372 528 358 528 357 528 366 528 373 528 365 528 365 534 373 534 374 534 365 528 374 528 361 528 361 535 374 535 375 535 361 528 375 528 362 528 376 528 377 528 378 528 378 536 377 536 379 536 378 528 379 528 380 528 380 528 379 528 356 528 380 537 356 537 381 537 381 528 356 528 358 528 382 538 358 538 383 538 383 539 358 539 352 539 383 528 352 528 384 528 384 528 352 528 369 528 385 540 336 540 247 540 247 541 336 541 334 541 247 542 334 542 249 542 356 543 386 543 357 543 357 544 386 544 387 544 357 545 387 545 372 545 372 546 387 546 388 546 372 547 388 547 371 547 371 547 388 547 389 547 390 523 370 523 389 523 389 523 370 523 371 523 354 548 352 548 390 548 390 548 352 548 370 548 391 549 392 549 393 549 394 550 395 550 231 550 396 551 222 551 397 551 397 552 222 552 398 552 396 553 399 553 400 553 223 554 222 554 401 554 401 555 222 555 396 555 401 556 396 556 402 556 402 557 396 557 400 557 398 558 222 558 403 558 403 559 222 559 232 559 403 560 232 560 404 560 395 561 405 561 231 561 231 562 405 562 406 562 231 563 406 563 232 563 232 564 406 564 407 564 232 565 407 565 404 565 226 566 408 566 227 566 227 567 408 567 409 567 409 568 391 568 227 568 227 569 391 569 393 569 227 570 393 570 231 570 231 571 393 571 410 571 231 572 410 572 394 572 411 573 226 573 412 573 412 574 226 574 221 574 411 575 413 575 226 575 226 576 413 576 414 576 226 577 414 577 408 577 415 578 416 578 417 578 417 579 416 579 418 579 417 580 418 580 419 580 415 581 420 581 416 581 416 582 420 582 421 582 416 583 421 583 422 583 423 584 424 584 425 584 424 585 426 585 425 585 425 586 426 586 427 586 425 587 427 587 421 587 421 588 427 588 428 588 421 589 428 589 422 589 425 590 429 590 423 590 423 591 429 591 430 591 423 592 430 592 431 592 431 593 430 593 432 593 431 594 432 594 433 594 433 595 432 595 434 595 433 596 434 596 435 596 435 597 434 597 381 597 435 598 381 598 436 598 436 599 381 599 358 599 437 600 438 600 335 600 335 601 438 601 439 601 335 602 439 602 313 602 335 603 440 603 437 603 437 604 440 604 441 604 437 605 441 605 442 605 443 606 444 606 445 606 445 607 444 607 446 607 445 608 446 608 447 608 447 609 446 609 442 609 447 610 442 610 448 610 448 611 442 611 441 611 443 612 445 612 449 612 449 613 445 613 450 613 449 614 450 614 451 614 451 615 450 615 452 615 451 616 452 616 453 616 453 617 452 617 454 617 453 618 454 618 455 618 455 619 454 619 456 619 455 620 456 620 457 620 458 621 459 621 460 621 461 622 462 622 463 622 463 623 462 623 464 623 463 624 464 624 465 624 465 625 464 625 466 625 465 626 466 626 467 626 468 627 469 627 470 627 470 628 469 628 471 628 470 629 471 629 472 629 472 629 471 629 473 629 472 630 473 630 462 630 462 631 473 631 474 631 462 632 474 632 464 632 468 633 475 633 476 633 477 634 478 634 479 634 479 635 478 635 480 635 479 636 480 636 481 636 481 637 480 637 482 637 481 638 482 638 476 638 476 639 482 639 483 639 476 640 483 640 468 640 468 641 483 641 484 641 468 642 484 642 469 642 457 643 456 643 485 643 485 644 456 644 486 644 485 645 486 645 479 645 479 646 486 646 487 646 479 647 487 647 477 647 477 648 487 648 488 648 467 649 458 649 465 649 465 650 458 650 460 650 465 651 460 651 489 651 489 652 460 652 490 652 489 653 490 653 419 653 419 654 490 654 417 654 491 523 492 523 493 523 493 523 492 523 494 523 493 523 494 523 495 523 496 523 497 523 493 523 493 655 497 655 498 655 493 656 498 656 491 656 499 523 500 523 493 523 493 523 500 523 501 523 493 523 501 523 496 523 495 523 502 523 493 523 493 657 502 657 503 657 493 658 503 658 499 658 501 659 504 659 496 659 496 660 504 660 505 660 496 661 505 661 497 661 497 662 505 662 506 662 497 663 506 663 498 663 498 664 506 664 507 664 498 665 507 665 491 665 491 666 507 666 508 666 491 667 508 667 492 667 492 668 508 668 509 668 492 669 509 669 494 669 494 670 509 670 510 670 494 671 510 671 495 671 495 672 510 672 511 672 495 673 511 673 502 673 502 674 511 674 512 674 502 675 512 675 503 675 503 676 512 676 513 676 503 677 513 677 499 677 499 678 513 678 514 678 499 679 514 679 500 679 500 680 514 680 515 680 500 680 515 680 501 680 501 659 515 659 504 659 505 681 504 681 516 681 515 682 517 682 504 682 504 523 517 523 518 523 504 523 518 523 516 523 516 683 519 683 505 683 505 523 519 523 520 523 505 523 520 523 506 523 506 684 520 684 521 684 506 523 521 523 507 523 507 523 521 523 522 523 507 685 522 685 508 685 508 523 522 523 523 523 508 686 523 686 509 686 509 523 523 523 524 523 509 523 524 523 510 523 510 523 524 523 525 523 510 687 525 687 511 687 511 523 525 523 526 523 511 688 526 688 512 688 512 689 526 689 527 689 512 523 527 523 513 523 513 523 527 523 528 523 513 690 528 690 514 690 514 523 528 523 529 523 514 523 529 523 515 523 515 523 529 523 530 523 515 523 530 523 517 523 530 691 531 691 517 691 517 691 531 691 532 691 517 692 532 692 518 692 518 693 532 693 533 693 518 694 533 694 516 694 516 695 533 695 534 695 535 498 519 498 534 498 534 498 519 498 516 498 531 696 530 696 529 696 531 696 529 696 536 696 536 697 529 697 528 697 536 698 528 698 537 698 537 699 528 699 527 699 537 700 527 700 538 700 538 701 527 701 526 701 538 702 526 702 539 702 539 703 526 703 525 703 539 704 525 704 540 704 540 705 525 705 524 705 540 706 524 706 541 706 541 707 524 707 523 707 541 708 523 708 542 708 542 709 523 709 522 709 542 710 522 710 543 710 543 711 522 711 521 711 543 712 521 712 544 712 544 713 521 713 520 713 544 714 520 714 545 714 545 715 520 715 519 715 545 716 519 716 535 716 546 717 547 717 548 717 546 718 548 718 549 718 549 719 548 719 550 719 549 720 550 720 551 720 551 721 550 721 552 721 551 722 552 722 553 722 554 723 555 723 556 723 554 724 556 724 557 724 557 725 556 725 558 725 557 726 558 726 559 726 559 727 558 727 552 727 552 728 558 728 553 728 560 729 561 729 562 729 560 730 562 730 563 730 563 731 562 731 564 731 563 732 564 732 565 732 565 733 564 733 555 733 565 734 555 734 554 734 566 735 567 735 560 735 560 736 567 736 568 736 560 737 568 737 569 737 570 738 561 738 571 738 571 739 561 739 560 739 571 740 560 740 572 740 572 741 560 741 569 741 573 742 574 742 575 742 575 743 574 743 576 743 576 744 577 744 575 744 575 745 577 745 578 745 575 746 578 746 579 746 580 747 581 747 582 747 582 748 581 748 583 748 582 749 583 749 584 749 573 750 575 750 580 750 580 751 575 751 585 751 580 752 585 752 581 752 547 753 546 753 586 753 547 754 586 754 587 754 587 755 586 755 588 755 587 755 588 755 589 755 589 756 588 756 584 756 589 757 584 757 583 757 547 758 590 758 591 758 547 759 591 759 548 759 592 760 593 760 594 760 594 761 593 761 595 761 591 762 596 762 548 762 548 763 596 763 597 763 548 764 597 764 550 764 550 765 597 765 595 765 550 766 595 766 552 766 552 767 595 767 593 767 598 768 599 768 600 768 601 769 602 769 603 769 603 770 602 770 604 770 603 769 604 769 605 769 606 769 607 769 602 769 602 771 607 771 608 771 609 772 610 772 611 772 611 773 610 773 612 773 613 769 604 769 610 769 610 774 604 774 614 774 601 769 615 769 602 769 602 775 615 775 616 775 602 776 616 776 617 776 618 769 619 769 600 769 600 777 619 777 620 777 600 769 620 769 621 769 622 778 623 778 610 778 610 779 623 779 624 779 610 780 624 780 612 780 613 769 625 769 604 769 604 781 625 781 626 781 604 782 626 782 605 782 617 769 627 769 602 769 602 783 627 783 628 783 602 784 628 784 629 784 621 769 630 769 600 769 600 785 630 785 631 785 600 786 631 786 632 786 608 787 598 787 602 787 602 788 598 788 600 788 602 769 600 769 633 769 633 789 600 789 632 789 614 790 634 790 610 790 610 791 634 791 635 791 610 792 635 792 622 792 636 793 637 793 638 793 638 794 637 794 639 794 638 795 639 795 640 795 629 769 641 769 602 769 602 796 641 796 642 796 602 797 642 797 606 797 618 769 600 769 638 769 638 798 600 798 643 798 638 799 643 799 636 799 608 800 607 800 606 800 644 801 637 801 636 801 645 802 646 802 644 802 644 803 636 803 645 803 645 804 636 804 643 804 645 805 643 805 647 805 647 806 643 806 600 806 647 807 600 807 648 807 600 808 599 808 648 808 648 809 599 809 598 809 648 810 598 810 649 810 649 811 598 811 608 811 642 812 641 812 650 812 608 813 606 813 649 813 649 814 606 814 642 814 649 815 642 815 651 815 651 816 642 816 650 816 651 817 650 817 652 817 653 818 535 818 654 818 654 819 535 819 534 819 654 820 534 820 533 820 546 523 549 523 537 523 533 821 532 821 654 821 654 822 532 822 531 822 654 523 531 523 655 523 655 823 531 823 656 823 545 824 657 824 658 824 542 523 659 523 541 523 541 523 659 523 660 523 541 523 660 523 661 523 662 523 663 523 543 523 543 825 663 825 664 825 543 826 664 826 542 826 542 827 664 827 665 827 542 523 665 523 659 523 584 828 539 828 582 828 582 829 539 829 540 829 582 523 540 523 580 523 580 523 540 523 541 523 580 830 541 830 573 830 573 523 541 523 661 523 573 523 661 523 574 523 544 523 666 523 543 523 543 831 666 831 667 831 543 832 667 832 662 832 658 523 668 523 545 523 545 833 668 833 669 833 545 523 669 523 544 523 544 834 669 834 670 834 544 835 670 835 666 835 586 523 546 523 588 523 588 523 546 523 537 523 588 836 537 836 584 836 584 837 537 837 538 837 584 838 538 838 539 838 549 523 551 523 537 523 537 839 551 839 553 839 537 840 553 840 558 840 653 523 671 523 535 523 535 841 671 841 672 841 535 842 672 842 545 842 545 843 672 843 673 843 545 844 673 844 657 844 570 845 656 845 561 845 561 846 656 846 531 846 561 847 531 847 562 847 562 523 531 523 536 523 562 523 536 523 564 523 564 848 536 848 537 848 564 849 537 849 555 849 555 850 537 850 558 850 555 523 558 523 556 523 674 851 675 851 676 851 644 852 646 852 677 852 637 853 644 853 639 853 639 854 644 854 677 854 639 855 677 855 640 855 640 856 677 856 678 856 679 857 676 857 621 857 621 858 620 858 679 858 679 859 620 859 619 859 679 860 619 860 680 860 680 861 619 861 618 861 680 862 618 862 638 862 674 863 676 863 681 863 681 864 676 864 679 864 681 865 679 865 682 865 682 866 679 866 680 866 682 867 680 867 678 867 678 868 680 868 638 868 678 869 638 869 640 869 557 870 559 870 683 870 684 871 685 871 686 871 686 872 685 872 687 872 686 873 687 873 688 873 559 874 552 874 683 874 683 875 552 875 593 875 683 876 593 876 592 876 683 877 689 877 686 877 686 878 689 878 690 878 686 879 690 879 684 879 554 880 557 880 565 880 565 881 557 881 683 881 565 882 683 882 563 882 563 883 683 883 686 883 563 884 686 884 560 884 691 885 566 885 692 885 692 886 566 886 560 886 692 887 560 887 693 887 693 888 560 888 686 888 694 889 695 889 696 889 696 890 695 890 697 890 697 891 698 891 699 891 698 892 700 892 699 892 699 893 700 893 701 893 699 894 701 894 702 894 697 895 699 895 696 895 696 896 699 896 568 896 696 897 568 897 694 897 568 898 567 898 694 898 694 899 567 899 566 899 694 900 566 900 703 900 703 901 566 901 691 901 703 902 691 902 692 902 693 903 704 903 692 903 692 904 704 904 705 904 692 905 705 905 703 905 570 906 571 906 702 906 702 907 571 907 572 907 702 908 572 908 699 908 699 909 572 909 569 909 699 910 569 910 568 910 706 911 707 911 570 911 570 912 707 912 656 912 708 913 709 913 707 913 707 914 709 914 710 914 707 915 710 915 656 915 656 916 710 916 711 916 656 917 711 917 655 917 712 918 713 918 714 918 702 919 701 919 715 919 715 920 701 920 716 920 715 921 716 921 714 921 714 922 716 922 717 922 714 923 717 923 712 923 570 924 702 924 706 924 706 925 702 925 715 925 706 926 715 926 707 926 707 927 715 927 714 927 707 928 714 928 708 928 708 929 714 929 713 929 718 930 719 930 720 930 721 931 722 931 723 931 723 932 722 932 724 932 725 933 726 933 727 933 725 934 727 934 728 934 727 935 729 935 728 935 728 936 729 936 730 936 728 937 730 937 720 937 720 938 730 938 731 938 720 939 731 939 718 939 732 940 733 940 726 940 721 941 734 941 722 941 722 942 734 942 735 942 722 943 735 943 732 943 732 944 735 944 736 944 732 945 736 945 733 945 574 946 724 946 576 946 576 947 724 947 722 947 576 948 722 948 577 948 577 949 722 949 732 949 577 950 732 950 578 950 578 951 732 951 726 951 578 952 726 952 579 952 579 953 726 953 725 953 737 954 738 954 660 954 660 955 738 955 739 955 660 956 739 956 661 956 661 957 739 957 724 957 661 958 724 958 574 958 740 959 741 959 742 959 742 960 741 960 743 960 742 961 743 961 744 961 744 962 743 962 745 962 744 963 745 963 723 963 737 964 740 964 738 964 738 965 740 965 742 965 738 966 742 966 739 966 739 967 742 967 744 967 739 968 744 968 724 968 724 969 744 969 723 969 590 970 547 970 746 970 746 971 547 971 587 971 746 972 587 972 589 972 747 973 748 973 749 973 749 974 748 974 750 974 749 975 750 975 751 975 751 976 752 976 749 976 749 977 752 977 753 977 749 978 753 978 746 978 589 979 583 979 746 979 746 980 583 980 581 980 746 981 581 981 749 981 749 982 581 982 585 982 749 983 585 983 719 983 575 984 579 984 585 984 585 985 579 985 725 985 725 986 728 986 585 986 585 987 728 987 720 987 585 988 720 988 719 988 754 989 755 989 756 989 756 990 755 990 757 990 757 991 755 991 758 991 758 992 755 992 759 992 758 993 759 993 760 993 760 994 759 994 761 994 760 995 761 995 762 995 763 996 746 996 753 996 764 997 590 997 746 997 746 998 763 998 764 998 764 999 763 999 765 999 764 1000 765 1000 766 1000 766 1001 765 1001 767 1001 766 1002 767 1002 768 1002 768 1003 767 1003 769 1003 768 1004 769 1004 770 1004 771 1005 772 1005 773 1005 756 1006 774 1006 754 1006 754 1007 774 1007 775 1007 754 1008 775 1008 776 1008 750 1009 762 1009 751 1009 751 1010 762 1010 761 1010 751 1011 761 1011 777 1011 777 1012 761 1012 759 1012 777 1013 759 1013 778 1013 778 1014 759 1014 755 1014 778 1015 755 1015 779 1015 779 1016 755 1016 754 1016 779 1017 754 1017 780 1017 780 1018 754 1018 776 1018 780 1019 776 1019 772 1019 772 1020 771 1020 780 1020 780 1021 771 1021 781 1021 780 1022 781 1022 779 1022 779 1023 781 1023 782 1023 779 1024 782 1024 778 1024 778 1025 782 1025 783 1025 778 1026 783 1026 777 1026 777 1027 783 1027 752 1027 777 1028 752 1028 751 1028 784 1029 770 1029 773 1029 773 1030 770 1030 769 1030 773 1031 769 1031 771 1031 771 1032 769 1032 767 1032 771 1033 767 1033 781 1033 781 1034 767 1034 765 1034 781 1035 765 1035 782 1035 782 1036 765 1036 763 1036 782 1037 763 1037 783 1037 783 1038 763 1038 753 1038 783 1039 753 1039 752 1039 785 1040 786 1040 787 1040 787 1041 786 1041 788 1041 787 1042 788 1042 789 1042 790 1043 791 1043 789 1043 770 1044 784 1044 792 1044 793 1045 591 1045 590 1045 794 1046 597 1046 596 1046 795 1047 592 1047 594 1047 590 1048 764 1048 793 1048 793 1049 764 1049 766 1049 793 1050 766 1050 796 1050 796 1051 766 1051 768 1051 796 1052 768 1052 797 1052 797 1053 768 1053 770 1053 797 1054 770 1054 798 1054 798 1055 770 1055 792 1055 798 1056 792 1056 791 1056 791 1057 790 1057 798 1057 798 1058 790 1058 799 1058 798 1059 799 1059 797 1059 797 1060 799 1060 800 1060 797 1061 800 1061 796 1061 796 1062 800 1062 794 1062 796 1063 794 1063 793 1063 793 1064 794 1064 596 1064 793 1065 596 1065 591 1065 789 1066 788 1066 790 1066 790 1067 788 1067 801 1067 790 1068 801 1068 799 1068 799 1069 801 1069 802 1069 799 1070 802 1070 800 1070 800 1071 802 1071 803 1071 800 1072 803 1072 794 1072 794 1073 803 1073 595 1073 794 1074 595 1074 597 1074 786 1075 804 1075 788 1075 788 1076 804 1076 805 1076 788 1077 805 1077 801 1077 801 1078 805 1078 806 1078 801 1079 806 1079 802 1079 802 1080 806 1080 795 1080 802 1081 795 1081 803 1081 803 1082 795 1082 594 1082 803 1083 594 1083 595 1083 807 1084 808 1084 809 1084 804 1085 786 1085 810 1085 811 1086 812 1086 813 1086 813 1087 812 1087 814 1087 814 1088 812 1088 815 1088 815 1089 812 1089 816 1089 815 1090 816 1090 817 1090 817 1091 816 1091 818 1091 817 1092 818 1092 819 1092 819 1093 818 1093 810 1093 819 1094 810 1094 820 1094 820 1095 810 1095 786 1095 820 1096 786 1096 785 1096 683 1097 592 1097 795 1097 795 1098 821 1098 683 1098 683 1099 821 1099 822 1099 683 1100 822 1100 689 1100 689 1101 822 1101 823 1101 689 1102 823 1102 690 1102 690 1103 823 1103 824 1103 690 1104 824 1104 684 1104 684 1105 824 1105 825 1105 684 1106 825 1106 685 1106 795 1107 806 1107 821 1107 821 1108 806 1108 826 1108 821 1109 826 1109 822 1109 822 1110 826 1110 827 1110 822 1111 827 1111 823 1111 823 1112 827 1112 828 1112 823 1113 828 1113 824 1113 824 1114 828 1114 809 1114 824 1115 809 1115 825 1115 825 1116 809 1116 808 1116 806 1117 805 1117 826 1117 826 1118 805 1118 829 1118 826 1119 829 1119 827 1119 827 1120 829 1120 830 1120 827 1121 830 1121 828 1121 828 1122 830 1122 831 1122 828 1123 831 1123 809 1123 809 1124 831 1124 832 1124 809 1125 832 1125 807 1125 807 1126 832 1126 833 1126 805 1127 804 1127 829 1127 829 1128 804 1128 810 1128 829 1129 810 1129 830 1129 830 1130 810 1130 818 1130 830 1131 818 1131 831 1131 831 1132 818 1132 816 1132 831 1133 816 1133 832 1133 832 1134 816 1134 812 1134 832 1135 812 1135 833 1135 833 1136 812 1136 811 1136 626 1137 834 1137 835 1137 836 1138 623 1138 837 1138 837 1139 623 1139 622 1139 837 1140 622 1140 838 1140 838 1141 622 1141 839 1141 840 1142 612 1142 836 1142 836 1143 612 1143 624 1143 836 1144 624 1144 623 1144 613 1145 610 1145 841 1145 841 1146 610 1146 609 1146 841 1147 609 1147 840 1147 840 1148 609 1148 611 1148 840 1149 611 1149 612 1149 626 1150 835 1150 605 1150 605 1151 835 1151 842 1151 605 1152 842 1152 603 1152 843 1153 844 1153 845 1153 846 1154 847 1154 834 1154 834 1155 847 1155 848 1155 834 1156 848 1156 835 1156 835 1157 848 1157 843 1157 835 1158 843 1158 842 1158 842 1159 843 1159 845 1159 842 1160 845 1160 603 1160 603 1161 845 1161 601 1161 626 1162 625 1162 834 1162 834 1163 625 1163 849 1163 834 1164 849 1164 846 1164 850 1165 851 1165 849 1165 849 1166 851 1166 852 1166 849 1167 852 1167 846 1167 838 1168 853 1168 837 1168 837 1169 853 1169 854 1169 837 1170 854 1170 836 1170 836 1171 854 1171 855 1171 836 1172 855 1172 840 1172 840 1173 855 1173 850 1173 840 1174 850 1174 841 1174 841 1175 850 1175 849 1175 841 1176 849 1176 613 1176 613 1177 849 1177 625 1177 856 1178 857 1178 858 1178 858 1179 857 1179 859 1179 858 1180 859 1180 839 1180 839 1181 859 1181 860 1181 839 1182 860 1182 838 1182 838 1183 860 1183 861 1183 838 1184 861 1184 853 1184 856 1185 858 1185 862 1185 862 1186 858 1186 863 1186 862 1187 863 1187 864 1187 864 1188 863 1188 865 1188 864 1189 865 1189 866 1189 866 1190 865 1190 867 1190 866 1191 867 1191 868 1191 868 1192 867 1192 869 1192 868 1193 869 1193 870 1193 630 1194 621 1194 676 1194 622 1195 635 1195 839 1195 839 1196 635 1196 634 1196 839 1197 634 1197 858 1197 858 1198 634 1198 614 1198 675 1199 870 1199 676 1199 676 1200 870 1200 869 1200 676 1201 869 1201 630 1201 630 1202 869 1202 867 1202 630 1203 867 1203 631 1203 631 1204 867 1204 865 1204 631 1205 865 1205 632 1205 632 1206 865 1206 863 1206 632 1207 863 1207 633 1207 633 1208 863 1208 858 1208 633 1209 858 1209 602 1209 602 1210 858 1210 614 1210 602 1211 614 1211 604 1211 650 1212 641 1212 629 1212 871 1213 872 1213 873 1213 873 1214 872 1214 652 1214 873 1215 652 1215 650 1215 873 1216 874 1216 871 1216 871 1217 874 1217 875 1217 871 1218 875 1218 876 1218 876 1219 875 1219 877 1219 876 1220 877 1220 878 1220 878 1221 877 1221 845 1221 878 1222 845 1222 844 1222 650 1223 629 1223 873 1223 873 1224 629 1224 628 1224 873 1225 628 1225 874 1225 874 1226 628 1226 627 1226 874 1227 627 1227 875 1227 601 1228 845 1228 615 1228 615 1229 845 1229 877 1229 615 1230 877 1230 616 1230 616 1231 877 1231 875 1231 616 1232 875 1232 617 1232 617 1233 875 1233 627 1233 648 1234 879 1234 647 1234 647 1235 879 1235 880 1235 647 1236 880 1236 645 1236 645 1237 880 1237 881 1237 645 1238 881 1238 646 1238 646 1239 881 1239 882 1239 652 1240 883 1240 651 1240 651 1241 883 1241 884 1241 651 1242 884 1242 649 1242 649 1243 884 1243 885 1243 649 1244 885 1244 648 1244 648 1245 885 1245 886 1245 648 1246 886 1246 879 1246 883 1247 887 1247 884 1247 884 1248 887 1248 888 1248 884 1249 888 1249 885 1249 885 1250 888 1250 889 1250 885 1251 889 1251 886 1251 886 1252 889 1252 890 1252 886 1253 890 1253 879 1253 879 1254 890 1254 891 1254 879 1255 891 1255 880 1255 880 1256 891 1256 892 1256 880 1257 892 1257 881 1257 881 1258 892 1258 893 1258 881 1259 893 1259 882 1259 882 1260 893 1260 894 1260 895 1261 896 1261 897 1261 898 1262 899 1262 900 1262 900 1263 899 1263 901 1263 901 1264 899 1264 902 1264 901 1265 902 1265 903 1265 708 1266 904 1266 709 1266 709 1267 904 1267 905 1267 709 1268 905 1268 710 1268 710 1269 905 1269 711 1269 653 1270 654 1270 905 1270 905 1271 654 1271 655 1271 905 1272 655 1272 711 1272 906 1273 672 1273 898 1273 898 1274 672 1274 671 1274 898 1275 671 1275 899 1275 899 1276 671 1276 653 1276 899 1277 653 1277 902 1277 902 1278 653 1278 905 1278 902 1279 905 1279 903 1279 903 1280 905 1280 904 1280 907 1281 657 1281 906 1281 906 1282 657 1282 673 1282 906 1283 673 1283 672 1283 669 1284 668 1284 907 1284 907 1285 668 1285 658 1285 907 1286 658 1286 657 1286 907 1287 908 1287 669 1287 669 1288 908 1288 909 1288 669 1289 909 1289 670 1289 670 1290 909 1290 897 1290 670 1291 897 1291 666 1291 664 1292 663 1292 896 1292 896 1293 663 1293 662 1293 896 1294 662 1294 897 1294 897 1295 662 1295 667 1295 897 1296 667 1296 666 1296 737 1297 660 1297 910 1297 910 1298 660 1298 659 1298 910 1299 659 1299 911 1299 912 1300 741 1300 740 1300 913 1301 914 1301 915 1301 915 1302 914 1302 916 1302 915 1303 916 1303 911 1303 911 1304 916 1304 912 1304 911 1305 912 1305 910 1305 910 1306 912 1306 740 1306 910 1307 740 1307 737 1307 895 1308 913 1308 896 1308 896 1309 913 1309 915 1309 896 1310 915 1310 664 1310 664 1311 915 1311 911 1311 664 1312 911 1312 665 1312 665 1313 911 1313 659 1313 900 1314 917 1314 898 1314 898 1315 917 1315 918 1315 898 1316 918 1316 906 1316 906 1317 918 1317 919 1317 906 1318 919 1318 907 1318 907 1319 919 1319 920 1319 907 1320 920 1320 908 1320 908 1321 920 1321 921 1321 908 1322 921 1322 909 1322 909 1323 921 1323 922 1323 909 1324 922 1324 897 1324 897 1325 922 1325 923 1325 897 1326 923 1326 895 1326 924 1327 675 1327 674 1327 675 1328 924 1328 925 1328 894 1329 926 1329 882 1329 882 1330 926 1330 927 1330 882 1331 927 1331 928 1331 928 1332 927 1332 929 1332 928 1333 929 1333 930 1333 930 1334 929 1334 931 1334 930 1335 931 1335 932 1335 646 1336 882 1336 677 1336 677 1337 882 1337 678 1337 678 1338 882 1338 682 1338 682 1339 882 1339 928 1339 682 1340 928 1340 681 1340 681 1341 928 1341 930 1341 681 1342 930 1342 674 1342 674 1343 930 1343 932 1343 674 1344 932 1344 924 1344 933 1345 934 1345 935 1345 811 1346 813 1346 934 1346 935 1347 936 1347 933 1347 933 1348 936 1348 937 1348 933 1349 937 1349 938 1349 688 1350 687 1350 939 1350 939 1351 687 1351 940 1351 939 1352 940 1352 941 1352 941 1353 940 1353 942 1353 941 1354 942 1354 943 1354 943 1355 942 1355 944 1355 943 1356 944 1356 945 1356 945 1357 944 1357 938 1357 945 1358 938 1358 946 1358 946 1359 938 1359 937 1359 934 1360 933 1360 811 1360 811 1361 933 1361 938 1361 811 1362 938 1362 833 1362 833 1363 938 1363 944 1363 833 1364 944 1364 807 1364 807 1365 944 1365 942 1365 807 1366 942 1366 808 1366 808 1367 942 1367 940 1367 808 1368 940 1368 825 1368 825 1369 940 1369 687 1369 825 1370 687 1370 685 1370 947 1371 688 1371 939 1371 311 1372 948 1372 949 1372 948 1373 311 1373 950 1373 951 1374 952 1374 953 1374 954 1375 955 1375 956 1375 956 1376 955 1376 951 1376 956 1377 951 1377 957 1377 957 1378 951 1378 953 1378 311 1379 958 1379 950 1379 950 1380 958 1380 959 1380 950 1381 959 1381 960 1381 960 1382 959 1382 961 1382 955 1383 962 1383 951 1383 951 1384 962 1384 963 1384 951 1385 963 1385 952 1385 945 1386 964 1386 943 1386 943 1387 964 1387 965 1387 943 1388 965 1388 941 1388 941 1389 965 1389 966 1389 941 1390 966 1390 939 1390 939 1391 966 1391 967 1391 939 1392 967 1392 947 1392 947 1393 967 1393 968 1393 969 1394 953 1394 961 1394 961 1395 953 1395 952 1395 961 1396 952 1396 960 1396 960 1397 952 1397 963 1397 960 1398 963 1398 950 1398 950 1399 963 1399 970 1399 950 1400 970 1400 948 1400 948 1401 970 1401 971 1401 948 1402 971 1402 949 1402 949 1403 971 1403 972 1403 949 1404 972 1404 973 1404 973 1405 972 1405 974 1405 973 1406 974 1406 975 1406 975 1407 974 1407 936 1407 975 1408 936 1408 935 1408 954 1409 968 1409 955 1409 955 1410 968 1410 967 1410 955 1411 967 1411 962 1411 962 1412 967 1412 966 1412 962 1413 966 1413 963 1413 963 1414 966 1414 965 1414 963 1415 965 1415 970 1415 970 1416 965 1416 964 1416 970 1417 964 1417 971 1417 971 1418 964 1418 945 1418 971 1419 945 1419 972 1419 972 1420 945 1420 946 1420 972 1421 946 1421 974 1421 974 1422 946 1422 937 1422 974 1423 937 1423 936 1423 976 1424 686 1424 688 1424 976 1425 688 1425 977 1425 688 1426 947 1426 977 1426 977 1427 947 1427 968 1427 977 1428 968 1428 954 1428 978 1429 979 1429 980 1429 978 1430 980 1430 969 1430 954 1431 956 1431 977 1431 977 1432 956 1432 957 1432 977 1433 957 1433 980 1433 980 1434 957 1434 953 1434 980 1435 953 1435 969 1435 704 1436 693 1436 686 1436 981 1437 980 1437 979 1437 982 1438 983 1438 977 1438 977 1439 983 1439 976 1439 982 1440 705 1440 983 1440 983 1441 705 1441 704 1441 983 1442 704 1442 976 1442 976 1443 704 1443 686 1443 984 1444 698 1444 697 1444 697 1445 695 1445 984 1445 984 1446 695 1446 694 1446 984 1447 694 1447 982 1447 982 1448 694 1448 703 1448 982 1449 703 1449 705 1449 698 1450 985 1450 700 1450 700 1451 985 1451 986 1451 700 1452 986 1452 701 1452 713 1453 712 1453 987 1453 987 1454 712 1454 717 1454 987 1455 717 1455 986 1455 986 1456 717 1456 716 1456 986 1457 716 1457 701 1457 988 1458 708 1458 713 1458 708 1459 988 1459 989 1459 989 1460 988 1460 990 1460 989 1461 990 1461 991 1461 992 1462 993 1462 994 1462 994 1463 993 1463 995 1463 994 1464 995 1464 996 1464 996 1465 995 1465 997 1465 996 1466 997 1466 998 1466 999 1467 1000 1467 992 1467 992 1468 1000 1468 1001 1468 992 1469 1001 1469 993 1469 1002 1470 1003 1470 999 1470 999 1471 1003 1471 1004 1471 999 1472 1004 1472 1000 1472 1005 1473 1006 1473 1007 1473 1007 1474 1006 1474 1002 1474 1007 1475 1002 1475 1008 1475 1008 1476 1002 1476 999 1476 977 1477 980 1477 982 1477 982 1478 980 1478 981 1478 982 1479 981 1479 984 1479 984 1480 981 1480 1009 1480 984 1481 1009 1481 698 1481 698 1482 1009 1482 1010 1482 698 1483 1010 1483 985 1483 979 1484 1011 1484 981 1484 981 1485 1011 1485 1005 1485 981 1486 1005 1486 1009 1486 1009 1487 1005 1487 1007 1487 1009 1488 1007 1488 1010 1488 1010 1489 1007 1489 1008 1489 1010 1490 1008 1490 985 1490 985 1491 1008 1491 999 1491 985 1492 999 1492 986 1492 986 1493 999 1493 992 1493 986 1494 992 1494 987 1494 987 1495 992 1495 994 1495 987 1496 994 1496 713 1496 713 1497 994 1497 996 1497 713 1498 996 1498 988 1498 988 1499 996 1499 998 1499 988 1500 998 1500 990 1500 1012 1501 1013 1501 1014 1501 1015 1502 735 1502 734 1502 726 1503 733 1503 1015 1503 1015 1504 733 1504 736 1504 1015 1505 736 1505 735 1505 730 1506 729 1506 1016 1506 1016 1507 729 1507 727 1507 749 1508 719 1508 1017 1508 1017 1509 719 1509 718 1509 1017 1510 718 1510 1016 1510 1016 1511 718 1511 731 1511 1016 1512 731 1512 730 1512 1018 1513 1019 1513 1020 1513 726 1514 1015 1514 727 1514 727 1515 1015 1515 1018 1515 727 1516 1018 1516 1016 1516 1016 1517 1018 1517 1020 1517 1016 1518 1020 1518 1017 1518 1021 1519 1022 1519 1023 1519 1023 1520 1022 1520 1024 1520 1023 1521 1024 1521 1025 1521 1026 1522 1027 1522 1028 1522 1028 1523 1029 1523 1026 1523 1026 1524 1029 1524 1030 1524 1026 1525 1030 1525 1031 1525 1031 1526 1030 1526 1012 1526 1031 1527 1012 1527 1032 1527 1032 1528 1012 1528 1014 1528 1032 1529 1014 1529 1033 1529 1034 1530 1035 1530 1036 1530 1036 1531 1035 1531 1037 1531 1036 1532 1037 1532 1038 1532 1038 1533 1037 1533 1039 1533 1038 1534 1039 1534 741 1534 1035 1535 1033 1535 1037 1535 1037 1536 1033 1536 1014 1536 1037 1537 1014 1537 1039 1537 1039 1538 1014 1538 1013 1538 1039 1539 1013 1539 741 1539 1025 1540 1019 1540 1023 1540 1023 1541 1019 1541 1018 1541 1023 1542 1018 1542 1021 1542 1021 1543 1018 1543 1015 1543 1021 1544 1015 1544 1040 1544 1040 1545 1015 1545 734 1545 1040 1546 734 1546 1041 1546 1041 1547 734 1547 721 1547 1041 1548 721 1548 1042 1548 1042 1549 721 1549 723 1549 1042 1550 723 1550 1043 1550 1043 1551 723 1551 745 1551 1043 1552 745 1552 743 1552 743 1553 741 1553 1043 1553 1043 1554 741 1554 1013 1554 1043 1555 1013 1555 1042 1555 1042 1556 1013 1556 1012 1556 1042 1557 1012 1557 1041 1557 1041 1558 1012 1558 1030 1558 1041 1559 1030 1559 1040 1559 1040 1560 1030 1560 1029 1560 1040 1561 1029 1561 1021 1561 1021 1562 1029 1562 1028 1562 1021 1563 1028 1563 1022 1563 1022 1564 1028 1564 1027 1564 1020 1565 1044 1565 1017 1565 1017 1566 1044 1566 747 1566 1017 1567 747 1567 749 1567 1025 1568 1045 1568 1019 1568 1019 1569 1045 1569 1046 1569 1019 1570 1046 1570 1047 1570 1047 1571 1048 1571 1019 1571 1019 1572 1048 1572 1049 1572 1019 1573 1049 1573 1020 1573 1020 1574 1049 1574 1050 1574 1020 1575 1050 1575 1044 1575 1051 1576 1052 1576 1053 1576 1054 1577 1055 1577 1056 1577 1056 1578 1055 1578 1057 1578 1056 1579 1057 1579 1058 1579 1059 1580 1054 1580 1060 1580 1060 1581 1054 1581 1056 1581 1060 1582 1056 1582 1061 1582 1061 1583 1056 1583 1058 1583 1061 1584 1058 1584 1062 1584 1062 1585 1058 1585 1063 1585 1064 1586 1065 1586 363 1586 363 1587 1065 1587 1066 1587 363 1588 1066 1588 1067 1588 1067 1589 1066 1589 1068 1589 1067 1590 1068 1590 1069 1590 1069 1591 1068 1591 1070 1591 1069 1592 1070 1592 1071 1592 1064 1593 1059 1593 1065 1593 1065 1594 1059 1594 1060 1594 1065 1595 1060 1595 1066 1595 1066 1596 1060 1596 1072 1596 1066 1597 1072 1597 1068 1597 1073 1598 1051 1598 1074 1598 1074 1599 1051 1599 1053 1599 1074 1600 1053 1600 1075 1600 1075 1601 1053 1601 1049 1601 1075 1602 1049 1602 1048 1602 1073 1603 1076 1603 1051 1603 1051 1604 1076 1604 1077 1604 1051 1605 1077 1605 1052 1605 1052 1606 1077 1606 1078 1606 1052 1607 1078 1607 1079 1607 1079 1608 747 1608 1052 1608 1052 1609 747 1609 1044 1609 1052 1610 1044 1610 1053 1610 1053 1611 1044 1611 1050 1611 1053 1612 1050 1612 1049 1612 1061 1613 1076 1613 1060 1613 1060 1614 1076 1614 1073 1614 1060 1615 1073 1615 1072 1615 1072 1616 1073 1616 1074 1616 1072 1617 1074 1617 1068 1617 1068 1618 1074 1618 1075 1618 1068 1619 1075 1619 1070 1619 1070 1620 1075 1620 1048 1620 1070 1621 1048 1621 1071 1621 1071 1622 1048 1622 1047 1622 1071 1623 1047 1623 1046 1623 1062 1624 1063 1624 1080 1624 774 1625 756 1625 1081 1625 1081 1626 756 1626 757 1626 1081 1627 757 1627 1082 1627 1082 1628 757 1628 758 1628 1082 1629 758 1629 1083 1629 1083 1630 758 1630 760 1630 1083 1631 760 1631 1084 1631 1084 1632 760 1632 762 1632 1084 1633 762 1633 1085 1633 1079 1634 1078 1634 1085 1634 1085 1635 1078 1635 1077 1635 1085 1636 1077 1636 1084 1636 1084 1637 1077 1637 1076 1637 1084 1638 1076 1638 1083 1638 1083 1639 1076 1639 1061 1639 1083 1640 1061 1640 1082 1640 1082 1641 1061 1641 1062 1641 1082 1642 1062 1642 1081 1642 1081 1643 1062 1643 1080 1643 1081 1644 1080 1644 774 1644 747 1645 1079 1645 748 1645 748 1646 1079 1646 1085 1646 748 1647 1085 1647 750 1647 750 1648 1085 1648 762 1648 856 1649 1086 1649 857 1649 820 1650 785 1650 859 1650 772 1651 1087 1651 773 1651 776 1652 775 1652 1088 1652 1088 1653 775 1653 774 1653 1088 1654 774 1654 1089 1654 1089 1655 774 1655 1090 1655 1089 1656 1090 1656 1091 1656 847 1657 846 1657 776 1657 776 1658 846 1658 852 1658 776 1659 852 1659 772 1659 772 1660 852 1660 851 1660 772 1661 851 1661 1087 1661 1087 1662 851 1662 850 1662 1087 1663 850 1663 773 1663 773 1664 850 1664 784 1664 850 1665 855 1665 784 1665 784 1666 855 1666 854 1666 784 1667 854 1667 792 1667 792 1668 854 1668 791 1668 791 1669 854 1669 853 1669 791 1670 853 1670 789 1670 789 1671 853 1671 787 1671 787 1672 853 1672 861 1672 787 1673 861 1673 785 1673 785 1674 861 1674 860 1674 785 1675 860 1675 859 1675 859 1676 857 1676 820 1676 820 1677 857 1677 1086 1677 820 1678 1086 1678 819 1678 819 1679 1086 1679 856 1679 819 1680 856 1680 817 1680 817 1681 856 1681 862 1681 817 1682 862 1682 815 1682 862 1683 864 1683 815 1683 815 1684 864 1684 866 1684 815 1685 866 1685 814 1685 814 1686 866 1686 868 1686 813 1687 1092 1687 1093 1687 1093 1688 1092 1688 925 1688 1093 1689 925 1689 1094 1689 813 1690 814 1690 1092 1690 1092 1691 814 1691 868 1691 1092 1692 868 1692 925 1692 925 1693 868 1693 870 1693 925 1694 870 1694 675 1694 847 1695 776 1695 848 1695 848 1696 776 1696 1088 1696 848 1697 1088 1697 843 1697 843 1698 1088 1698 1089 1698 843 1699 1089 1699 844 1699 876 1700 1095 1700 1096 1700 878 1701 844 1701 1089 1701 876 1702 1096 1702 871 1702 871 1703 1096 1703 1097 1703 871 1704 1097 1704 872 1704 872 1705 1097 1705 883 1705 872 1706 883 1706 652 1706 887 1707 883 1707 1098 1707 1098 1708 883 1708 1097 1708 1098 1709 1097 1709 1099 1709 1099 1710 1097 1710 1096 1710 1099 1711 1096 1711 1100 1711 1089 1712 1101 1712 878 1712 878 1713 1101 1713 1102 1713 878 1714 1102 1714 876 1714 876 1715 1102 1715 1103 1715 876 1716 1103 1716 1095 1716 1095 1717 1103 1717 1104 1717 1095 1718 1104 1718 1096 1718 1096 1719 1104 1719 1105 1719 1096 1720 1105 1720 1100 1720 1106 1721 894 1721 893 1721 223 1722 401 1722 1107 1722 1108 769 1109 769 59 769 59 1723 1109 1723 1110 1723 59 769 1110 769 19 769 887 769 1111 769 888 769 888 769 1111 769 889 769 223 1724 1112 1724 1113 1724 1114 769 1115 769 1116 769 1108 769 59 769 1117 769 1117 1725 59 1725 223 1725 1117 1726 223 1726 1118 1726 1118 1727 223 1727 1113 1727 1118 769 1113 769 1116 769 1119 769 1120 769 892 769 892 1728 1120 1728 1121 1728 892 769 1121 769 893 769 893 1729 1121 1729 1122 1729 893 1730 1122 1730 1106 1730 1107 1731 1123 1731 223 1731 223 1732 1123 1732 1124 1732 223 1733 1124 1733 1125 1733 1126 769 1127 769 1116 769 1116 1734 1127 1734 1128 1734 1116 769 1128 769 1114 769 889 769 1111 769 890 769 890 1735 1111 1735 1118 1735 890 769 1118 769 891 769 891 769 1118 769 1116 769 891 1736 1116 1736 892 1736 892 1737 1116 1737 1115 1737 892 1738 1115 1738 1119 1738 1125 769 1129 769 223 769 223 1739 1129 1739 1130 1739 223 1740 1130 1740 1112 1740 1131 1741 1132 1741 1133 1741 1134 1742 1135 1742 1136 1742 918 1743 1137 1743 1134 1743 1138 1744 1139 1744 1140 1744 1139 1745 1138 1745 1141 1745 1142 1746 1143 1746 1144 1746 1145 1747 1146 1747 1147 1747 1148 1748 1149 1748 1150 1748 913 1749 1151 1749 914 1749 1152 1750 1153 1750 923 1750 923 1751 1153 1751 1154 1751 923 1752 1154 1752 895 1752 1151 1753 913 1753 1155 1753 1156 1754 1157 1754 916 1754 1038 1755 741 1755 912 1755 1038 1756 912 1756 1036 1756 916 1757 1157 1757 912 1757 912 1758 1157 1758 1034 1758 912 1759 1034 1759 1036 1759 1156 1760 1158 1760 1157 1760 1157 1761 1158 1761 1159 1761 1157 1762 1159 1762 1034 1762 1146 1763 1145 1763 1143 1763 1143 1764 1145 1764 1160 1764 1143 1765 1160 1765 1144 1765 1161 1766 1142 1766 1162 1766 1162 1767 1142 1767 1144 1767 1162 1768 1144 1768 1163 1768 1163 1769 1144 1769 1160 1769 1163 1770 1160 1770 1164 1770 1164 1771 1160 1771 1133 1771 1164 1772 1133 1772 1165 1772 1165 1773 1133 1773 1132 1773 1165 1774 1132 1774 1166 1774 1166 1775 1132 1775 1167 1775 1136 1776 1168 1776 1169 1776 1168 1777 1136 1777 1170 1777 1170 1778 1136 1778 1135 1778 1170 1779 1135 1779 1171 1779 1172 1780 1173 1780 1174 1780 1174 1781 1173 1781 1175 1781 1176 1782 1177 1782 1178 1782 1178 1783 1177 1783 1179 1783 1178 1784 1179 1784 1180 1784 1181 1785 1182 1785 1183 1785 1183 1786 1182 1786 1184 1786 1184 1787 1177 1787 1183 1787 1183 1788 1177 1788 1176 1788 1183 1789 1176 1789 1181 1789 1181 1790 1176 1790 1185 1790 1180 1791 1186 1791 1178 1791 1178 1792 1186 1792 1172 1792 1178 1793 1172 1793 1176 1793 1176 1794 1172 1794 1174 1794 1176 1795 1174 1795 1185 1795 1185 1796 1174 1796 1187 1796 1185 1797 1187 1797 1188 1797 1188 1798 1187 1798 1189 1798 1190 1799 1191 1799 1192 1799 708 1800 989 1800 904 1800 904 1801 989 1801 991 1801 904 1802 991 1802 1191 1802 1191 1803 991 1803 1193 1803 1191 1804 1193 1804 1192 1804 1190 1805 901 1805 1191 1805 1191 1806 901 1806 903 1806 1191 1807 903 1807 904 1807 1194 1808 1195 1808 900 1808 900 1809 1195 1809 917 1809 923 1810 922 1810 1152 1810 1152 1811 922 1811 921 1811 1152 1812 921 1812 1196 1812 1196 1813 921 1813 920 1813 1196 1814 920 1814 1197 1814 1197 1815 920 1815 919 1815 1197 1816 919 1816 1198 1816 1198 1817 1199 1817 1197 1817 1197 1818 1199 1818 1200 1818 1197 1819 1200 1819 1196 1819 1196 1820 1200 1820 1201 1820 1196 1821 1201 1821 1152 1821 1152 1822 1201 1822 1202 1822 1152 1823 1202 1823 1153 1823 1147 1824 1203 1824 1145 1824 1145 1825 1203 1825 1204 1825 1145 1826 1204 1826 1160 1826 1160 1827 1204 1827 1150 1827 1160 1828 1150 1828 1133 1828 1133 1829 1150 1829 1149 1829 1133 1830 1149 1830 1131 1830 1131 1831 1149 1831 1148 1831 1131 1832 1148 1832 1156 1832 1156 1833 1148 1833 1205 1833 1156 1834 1205 1834 1158 1834 1202 1835 1206 1835 1153 1835 1153 1836 1206 1836 1207 1836 1153 1837 1207 1837 1154 1837 1154 1838 1207 1838 1155 1838 1154 1839 1155 1839 895 1839 895 1840 1155 1840 913 1840 1141 1841 1171 1841 1139 1841 1139 1842 1171 1842 1135 1842 1139 1843 1135 1843 1140 1843 1140 1844 1135 1844 1134 1844 1140 1845 1134 1845 1195 1845 1195 1846 1134 1846 1137 1846 1195 1847 1137 1847 917 1847 917 1848 1137 1848 918 1848 1175 1849 1208 1849 1174 1849 1174 1850 1208 1850 1209 1850 1174 1851 1209 1851 1187 1851 1187 1852 1209 1852 1210 1852 1187 1853 1210 1853 1189 1853 1189 1854 1210 1854 1190 1854 1189 1855 1190 1855 1211 1855 1211 1856 1190 1856 1192 1856 916 1857 914 1857 1156 1857 1156 1858 914 1858 1151 1858 1156 1859 1151 1859 1131 1859 1131 1860 1151 1860 1155 1860 1131 1861 1155 1861 1132 1861 1132 1862 1155 1862 1207 1862 1132 1863 1207 1863 1167 1863 1167 1864 1207 1864 1206 1864 1167 1865 1206 1865 1212 1865 1212 1866 1206 1866 1202 1866 1212 1867 1202 1867 1213 1867 1213 1868 1202 1868 1201 1868 1213 1869 1201 1869 1214 1869 1214 1870 1201 1870 1200 1870 1214 1871 1200 1871 1169 1871 1169 1872 1200 1872 1199 1872 1169 1873 1199 1873 1136 1873 1136 1874 1199 1874 1198 1874 1136 1875 1198 1875 1134 1875 1134 1876 1198 1876 919 1876 1134 1877 919 1877 918 1877 1208 1878 1138 1878 1209 1878 1209 1879 1138 1879 1140 1879 1209 1880 1140 1880 1210 1880 1210 1881 1140 1881 1195 1881 1210 1882 1195 1882 1190 1882 1190 1883 1195 1883 1194 1883 1190 1884 1194 1884 901 1884 901 1885 1194 1885 900 1885 1215 1886 319 1886 317 1886 931 1887 929 1887 1216 1887 931 1888 1216 1888 932 1888 929 1889 927 1889 1216 1889 1216 1890 927 1890 926 1890 1216 1891 926 1891 1106 1891 1106 1892 926 1892 894 1892 1094 1893 925 1893 924 1893 932 1894 1216 1894 924 1894 924 1895 1216 1895 1217 1895 924 1896 1217 1896 1094 1896 317 1897 1218 1897 1215 1897 1215 1898 1218 1898 1219 1898 1215 1899 1219 1899 1217 1899 1217 1900 1219 1900 1220 1900 1217 1901 1220 1901 1094 1901 935 1902 1221 1902 975 1902 312 1903 1222 1903 317 1903 317 1904 1222 1904 1218 1904 1093 1905 1094 1905 1221 1905 1221 1906 1094 1906 1220 1906 1221 1907 1220 1907 1223 1907 1223 1908 1220 1908 1219 1908 1221 1909 935 1909 1093 1909 1093 1910 935 1910 934 1910 1093 1911 934 1911 813 1911 975 1912 1221 1912 973 1912 973 1913 1221 1913 1223 1913 973 1914 1223 1914 949 1914 1219 1915 1218 1915 1223 1915 1223 1916 1218 1916 1222 1916 1223 1917 1222 1917 949 1917 949 1918 1222 1918 312 1918 949 1919 312 1919 311 1919 958 1920 311 1920 310 1920 310 1921 1224 1921 1225 1921 1225 1922 1224 1922 1226 1922 1225 1923 1226 1923 1227 1923 1227 1924 1226 1924 1228 1924 1227 1925 1228 1925 1229 1925 1229 1926 1228 1926 979 1926 1229 1927 979 1927 978 1927 310 1928 1225 1928 958 1928 958 1929 1225 1929 1227 1929 958 1930 1227 1930 959 1930 959 1931 1227 1931 1229 1931 959 1932 1229 1932 961 1932 961 1933 1229 1933 978 1933 961 1934 978 1934 969 1934 990 1935 998 1935 1230 1935 1001 1936 1000 1936 1231 1936 1224 1937 310 1937 325 1937 1232 1938 1228 1938 1233 1938 1233 1939 1228 1939 1226 1939 1233 1940 1226 1940 1234 1940 1234 1941 1226 1941 1224 1941 1234 1942 1224 1942 1235 1942 1235 1943 1224 1943 325 1943 1235 1944 325 1944 324 1944 979 1945 1228 1945 1011 1945 1011 1946 1228 1946 1232 1946 1011 1947 1232 1947 1005 1947 1005 1948 1232 1948 1006 1948 1000 1949 1004 1949 1231 1949 1231 1950 1004 1950 1003 1950 1231 1951 1003 1951 1232 1951 1232 1952 1003 1952 1002 1952 1232 1953 1002 1953 1006 1953 998 1954 997 1954 1230 1954 1230 1955 997 1955 995 1955 1230 1956 995 1956 1236 1956 1236 1957 995 1957 993 1957 1236 1958 993 1958 1001 1958 1237 1959 991 1959 990 1959 1237 1960 990 1960 1238 1960 1238 1961 990 1961 1230 1961 1238 1962 1230 1962 1239 1962 1239 1963 1230 1963 1236 1963 1239 1964 1236 1964 1240 1964 1240 1965 1236 1965 1241 1965 1241 1966 1236 1966 1242 1966 1241 1967 1242 1967 1243 1967 1243 1968 1242 1968 1244 1968 1244 1969 1242 1969 1245 1969 1244 1970 1245 1970 1246 1970 1246 1971 1245 1971 1247 1971 1247 1972 1245 1972 1248 1972 1247 1973 1248 1973 1249 1973 1249 1974 1248 1974 1250 1974 1249 1975 1250 1975 315 1975 1001 1976 1231 1976 1236 1976 1236 1977 1231 1977 1232 1977 1236 1978 1232 1978 1242 1978 1242 1979 1232 1979 1233 1979 1242 1980 1233 1980 1245 1980 1245 1981 1233 1981 1234 1981 1245 1982 1234 1982 1248 1982 1248 1983 1234 1983 1235 1983 1248 1984 1235 1984 1250 1984 1250 1985 1235 1985 324 1985 1250 1986 324 1986 315 1986 1251 1987 318 1987 320 1987 1252 1988 1253 1988 1249 1988 1249 1989 1253 1989 1247 1989 1254 1990 1255 1990 1241 1990 1241 1991 1243 1991 1254 1991 1254 1992 1243 1992 1244 1992 1254 1993 1244 1993 1253 1993 1253 1994 1244 1994 1246 1994 1253 1995 1246 1995 1247 1995 991 1996 1237 1996 1193 1996 1193 1997 1237 1997 1238 1997 1193 1998 1238 1998 1256 1998 1256 1999 1238 1999 1239 1999 1256 2000 1239 2000 1255 2000 1255 2001 1239 2001 1240 2001 1255 2002 1240 2002 1241 2002 1257 2003 1189 2003 1211 2003 1258 2004 1181 2004 1185 2004 1182 2005 1181 2005 1259 2005 1259 2006 1181 2006 1258 2006 1259 2007 1258 2007 1260 2007 1260 2008 1258 2008 1261 2008 1262 2009 1263 2009 1264 2009 1264 2010 1263 2010 1265 2010 1264 2011 1265 2011 1261 2011 1261 2012 1265 2012 1266 2012 1261 2013 1266 2013 1260 2013 1262 2014 1264 2014 1267 2014 1267 2015 1264 2015 1268 2015 1267 2016 1268 2016 1269 2016 1269 2017 1268 2017 1270 2017 1270 2018 1268 2018 1271 2018 1270 2019 1271 2019 1272 2019 1273 2020 330 2020 329 2020 327 2021 1272 2021 328 2021 328 2022 1272 2022 1271 2022 328 2023 1271 2023 329 2023 1274 2024 321 2024 330 2024 321 2025 1274 2025 320 2025 1249 2026 315 2026 1252 2026 1252 2027 315 2027 316 2027 1252 2028 316 2028 318 2028 318 2029 1251 2029 1252 2029 1252 2030 1251 2030 1275 2030 1252 2031 1275 2031 1253 2031 1253 2032 1275 2032 1276 2032 1253 2033 1276 2033 1254 2033 1254 2034 1276 2034 1277 2034 1254 2035 1277 2035 1255 2035 1255 2036 1277 2036 1278 2036 1255 2037 1278 2037 1256 2037 1256 2038 1278 2038 1192 2038 1256 2039 1192 2039 1193 2039 320 2040 1274 2040 1251 2040 1251 2041 1274 2041 1279 2041 1251 2042 1279 2042 1275 2042 1275 2043 1279 2043 1280 2043 1275 2044 1280 2044 1276 2044 1276 2045 1280 2045 1281 2045 1276 2046 1281 2046 1277 2046 1277 2047 1281 2047 1257 2047 1277 2048 1257 2048 1278 2048 1278 2049 1257 2049 1211 2049 1278 2050 1211 2050 1192 2050 330 2051 1273 2051 1274 2051 1274 2052 1273 2052 1282 2052 1274 2053 1282 2053 1279 2053 1279 2054 1282 2054 1283 2054 1279 2055 1283 2055 1280 2055 1280 2056 1283 2056 1284 2056 1280 2057 1284 2057 1281 2057 1281 2058 1284 2058 1285 2058 1281 2059 1285 2059 1257 2059 329 2060 1271 2060 1273 2060 1273 2061 1271 2061 1268 2061 1273 2062 1268 2062 1282 2062 1282 2063 1268 2063 1264 2063 1282 2064 1264 2064 1283 2064 1283 2065 1264 2065 1261 2065 1283 2066 1261 2066 1284 2066 1284 2067 1261 2067 1258 2067 1284 2068 1258 2068 1285 2068 1285 2069 1258 2069 1185 2069 1285 2070 1185 2070 1257 2070 1257 2071 1185 2071 1188 2071 1257 2072 1188 2072 1189 2072 1286 2073 382 2073 383 2073 1287 2074 1288 2074 1289 2074 1290 2075 1291 2075 1292 2075 1293 2076 1294 2076 1295 2076 1295 2077 1294 2077 1296 2077 1295 2078 1296 2078 1034 2078 1297 2079 1298 2079 1299 2079 374 2080 1287 2080 375 2080 375 2081 1287 2081 1289 2081 375 2082 1289 2082 362 2082 362 2083 1289 2083 1300 2083 362 2084 1300 2084 367 2084 367 2085 1300 2085 1301 2085 367 2086 1301 2086 368 2086 368 2087 1301 2087 369 2087 369 2088 1301 2088 1302 2088 369 2089 1302 2089 384 2089 384 2090 1302 2090 1303 2090 384 2091 1303 2091 383 2091 383 2092 1303 2092 1304 2092 383 2093 1304 2093 1286 2093 1305 2094 1306 2094 1307 2094 1307 2095 1306 2095 1308 2095 1307 2096 1308 2096 1309 2096 1310 2097 1311 2097 1312 2097 1313 2098 1150 2098 1314 2098 1314 2099 1150 2099 1204 2099 1314 2100 1204 2100 1315 2100 1315 2101 1204 2101 1203 2101 1034 2102 1159 2102 1295 2102 1295 2103 1159 2103 1158 2103 1295 2104 1158 2104 1316 2104 1316 2105 1158 2105 1205 2105 1316 2106 1205 2106 1313 2106 1313 2107 1205 2107 1148 2107 1313 2108 1148 2108 1150 2108 1315 2109 1317 2109 1314 2109 1314 2110 1317 2110 1318 2110 1314 2111 1318 2111 1313 2111 1313 2112 1318 2112 1319 2112 1313 2113 1319 2113 1316 2113 1316 2114 1319 2114 1320 2114 1316 2115 1320 2115 1295 2115 1295 2116 1320 2116 1321 2116 1295 2117 1321 2117 1293 2117 1293 2118 1321 2118 1322 2118 1291 2119 1322 2119 1292 2119 1292 2120 1322 2120 1321 2120 1292 2121 1321 2121 1323 2121 1323 2122 1321 2122 1320 2122 1323 2123 1320 2123 1324 2123 1324 2124 1320 2124 1319 2124 1324 2125 1319 2125 1325 2125 1325 2126 1319 2126 1318 2126 1325 2127 1318 2127 1312 2127 1312 2128 1318 2128 1317 2128 1312 2129 1317 2129 1310 2129 1310 2130 1317 2130 1315 2130 1310 2131 1315 2131 1326 2131 1326 2132 1315 2132 1203 2132 1326 2133 1203 2133 1147 2133 1311 2134 1305 2134 1312 2134 1312 2135 1305 2135 1307 2135 1312 2136 1307 2136 1325 2136 1325 2137 1307 2137 1327 2137 1325 2138 1327 2138 1324 2138 1324 2139 1327 2139 1328 2139 1324 2140 1328 2140 1323 2140 1323 2141 1328 2141 1329 2141 1323 2142 1329 2142 1292 2142 1292 2143 1329 2143 1297 2143 1292 2144 1297 2144 1290 2144 1290 2145 1297 2145 1299 2145 1309 2146 1304 2146 1307 2146 1307 2147 1304 2147 1303 2147 1307 2148 1303 2148 1327 2148 1327 2149 1303 2149 1302 2149 1327 2150 1302 2150 1328 2150 1328 2151 1302 2151 1301 2151 1328 2152 1301 2152 1329 2152 1329 2153 1301 2153 1300 2153 1329 2154 1300 2154 1297 2154 1297 2155 1300 2155 1289 2155 1297 2156 1289 2156 1298 2156 1298 2157 1289 2157 1288 2157 1031 2158 1032 2158 1330 2158 1035 2159 1331 2159 1033 2159 1287 2160 374 2160 373 2160 364 2161 1332 2161 1333 2161 1287 2162 373 2162 1288 2162 1290 2163 1299 2163 1334 2163 1334 2164 1299 2164 1298 2164 1334 2165 1298 2165 1335 2165 1335 2166 1298 2166 1288 2166 1335 2167 1288 2167 1336 2167 1336 2168 1288 2168 373 2168 1336 2169 373 2169 366 2169 1290 2170 1334 2170 1291 2170 1291 2171 1334 2171 1337 2171 1291 2172 1337 2172 1322 2172 1322 2173 1337 2173 1338 2173 1322 2174 1338 2174 1293 2174 1293 2175 1338 2175 1294 2175 1294 2176 1338 2176 1331 2176 1294 2177 1331 2177 1296 2177 1296 2178 1331 2178 1035 2178 1296 2179 1035 2179 1034 2179 1339 2180 1027 2180 1330 2180 1330 2181 1027 2181 1026 2181 1330 2182 1026 2182 1031 2182 1340 2183 1025 2183 1024 2183 1333 2184 1332 2184 1341 2184 1341 2185 1332 2185 1340 2185 1341 2186 1340 2186 1342 2186 1342 2187 1340 2187 1024 2187 1342 2188 1024 2188 1339 2188 1339 2189 1024 2189 1022 2189 1339 2190 1022 2190 1027 2190 1033 2191 1331 2191 1032 2191 1032 2192 1331 2192 1338 2192 1032 2193 1338 2193 1330 2193 1330 2194 1338 2194 1337 2194 1330 2195 1337 2195 1339 2195 1339 2196 1337 2196 1334 2196 1339 2197 1334 2197 1342 2197 1342 2198 1334 2198 1335 2198 1342 2199 1335 2199 1341 2199 1341 2200 1335 2200 1336 2200 1341 2201 1336 2201 1333 2201 1333 2202 1336 2202 366 2202 1333 2203 366 2203 364 2203 1332 2204 364 2204 1343 2204 1343 2205 364 2205 363 2205 1343 2206 1344 2206 1332 2206 1332 2207 1344 2207 1345 2207 1332 2208 1345 2208 1340 2208 1340 2209 1345 2209 1045 2209 1340 2210 1045 2210 1025 2210 363 2211 1067 2211 1343 2211 1343 2212 1067 2212 1069 2212 1343 2213 1069 2213 1344 2213 1344 2214 1069 2214 1071 2214 1344 2215 1071 2215 1345 2215 1345 2216 1071 2216 1046 2216 1345 2217 1046 2217 1045 2217 1063 2218 1346 2218 1080 2218 1347 2219 1091 2219 1090 2219 363 2220 365 2220 1064 2220 1064 2221 365 2221 1348 2221 1064 2222 1348 2222 1059 2222 1059 2223 1348 2223 1054 2223 1346 2224 1063 2224 1349 2224 1063 2225 1058 2225 1349 2225 1349 2226 1058 2226 1057 2226 1349 2227 1057 2227 1348 2227 1348 2228 1057 2228 1055 2228 1348 2229 1055 2229 1054 2229 774 2230 1080 2230 1090 2230 1090 2231 1080 2231 1346 2231 1090 2232 1346 2232 1347 2232 1347 2233 1346 2233 1349 2233 1347 2234 1349 2234 1350 2234 1350 2235 1349 2235 1348 2235 1350 2236 1348 2236 1351 2236 1351 2237 1348 2237 365 2237 1351 2238 365 2238 361 2238 361 2239 360 2239 1351 2239 1351 2240 360 2240 1352 2240 1351 2241 1352 2241 1350 2241 1350 2242 1352 2242 1347 2242 1347 2243 1352 2243 1353 2243 1347 2244 1353 2244 1354 2244 1103 2245 1102 2245 1355 2245 1355 2246 1102 2246 1101 2246 1355 2247 1101 2247 1356 2247 1356 2248 1101 2248 1089 2248 1356 2249 1089 2249 1354 2249 1354 2250 1089 2250 1091 2250 1354 2251 1091 2251 1347 2251 1100 2252 1105 2252 1355 2252 1355 2253 1105 2253 1104 2253 1355 2254 1104 2254 1103 2254 1111 2255 887 2255 1357 2255 1357 2256 887 2256 1098 2256 1357 2257 1098 2257 1355 2257 1355 2258 1098 2258 1099 2258 1355 2259 1099 2259 1100 2259 1358 2260 1359 2260 1360 2260 1360 2261 1361 2261 1362 2261 419 2262 418 2262 1363 2262 1364 2263 463 2263 1359 2263 1359 2264 463 2264 465 2264 1359 2265 465 2265 1360 2265 1360 2266 465 2266 489 2266 1360 2267 489 2267 1361 2267 1361 2268 489 2268 419 2268 1365 2269 1366 2269 1367 2269 1366 2270 1365 2270 1368 2270 1161 2271 1368 2271 1142 2271 1142 2272 1368 2272 1143 2272 1368 2273 1365 2273 1143 2273 1143 2274 1365 2274 1369 2274 1143 2275 1369 2275 1146 2275 419 2276 1363 2276 1361 2276 1361 2277 1363 2277 1370 2277 1361 2278 1370 2278 1362 2278 1364 2279 1359 2279 1367 2279 1367 2280 1359 2280 1358 2280 1367 2281 1358 2281 1365 2281 1365 2282 1358 2282 1360 2282 1365 2283 1360 2283 1369 2283 1369 2284 1360 2284 1362 2284 1369 2285 1362 2285 1146 2285 1146 2286 1362 2286 1370 2286 1146 2287 1370 2287 1147 2287 1371 2288 1372 2288 1373 2288 1374 2289 1375 2289 1376 2289 1376 2290 1375 2290 1377 2290 1376 2291 1377 2291 1184 2291 1184 2292 1182 2292 1376 2292 1376 2293 1182 2293 1378 2293 1376 2294 1378 2294 1374 2294 1177 2295 1379 2295 1179 2295 1179 2296 1379 2296 1380 2296 1179 2297 1380 2297 1180 2297 1372 2298 1380 2298 1373 2298 1373 2299 1380 2299 1379 2299 1373 2300 1379 2300 1381 2300 1381 2301 1379 2301 1177 2301 1381 2302 1177 2302 1382 2302 476 2303 1383 2303 481 2303 481 2304 1383 2304 1384 2304 481 2305 1384 2305 479 2305 479 2306 1384 2306 1375 2306 479 2307 1375 2307 485 2307 485 2308 1375 2308 1374 2308 485 2309 1374 2309 457 2309 457 2310 1374 2310 1385 2310 457 2311 1385 2311 455 2311 476 2312 1371 2312 1383 2312 1383 2313 1371 2313 1373 2313 1383 2314 1373 2314 1384 2314 1384 2315 1373 2315 1381 2315 1384 2316 1381 2316 1375 2316 1375 2317 1381 2317 1382 2317 1375 2318 1382 2318 1377 2318 1377 2319 1382 2319 1177 2319 1377 2320 1177 2320 1184 2320 1173 2321 475 2321 1175 2321 1175 528 475 528 1208 528 1173 528 1172 528 475 528 475 2322 1172 2322 1186 2322 475 2323 1186 2323 476 2323 476 528 1186 528 1180 528 1380 528 1372 528 1180 528 1180 2324 1372 2324 1371 2324 1180 2325 1371 2325 476 2325 461 2326 1165 2326 1166 2326 461 523 1166 523 462 523 472 523 1214 523 470 523 470 2327 1214 2327 1169 2327 1166 523 1167 523 462 523 462 2328 1167 2328 1212 2328 462 523 1212 523 472 523 472 2329 1212 2329 1213 2329 472 2330 1213 2330 1214 2330 1169 523 1168 523 470 523 470 2331 1168 2331 1170 2331 470 523 1170 523 468 523 1170 523 1171 523 468 523 468 523 1171 523 1141 523 468 523 1141 523 475 523 475 2332 1141 2332 1138 2332 475 2333 1138 2333 1208 2333 1165 498 461 498 1164 498 1164 498 461 498 1163 498 461 2334 463 2334 1364 2334 1366 498 1368 498 1161 498 1163 2335 461 2335 1162 2335 1162 2336 461 2336 1364 2336 1162 2337 1364 2337 1161 2337 1161 2338 1364 2338 1367 2338 1161 2339 1367 2339 1366 2339 1385 2340 1386 2340 455 2340 1374 2341 1378 2341 1387 2341 1263 2342 1388 2342 1389 2342 438 2343 1272 2343 327 2343 438 2344 437 2344 1272 2344 1272 2345 437 2345 1390 2345 1272 2346 1390 2346 1270 2346 1270 2347 1390 2347 1391 2347 1270 2348 1391 2348 1269 2348 1269 2349 1391 2349 1267 2349 1260 2350 1266 2350 1389 2350 1389 2351 1266 2351 1265 2351 1389 2352 1265 2352 1263 2352 1389 2353 1392 2353 1260 2353 1260 2354 1392 2354 1387 2354 1260 2355 1387 2355 1259 2355 1259 2356 1387 2356 1378 2356 1259 2357 1378 2357 1182 2357 1393 2358 451 2358 1386 2358 1386 2359 451 2359 453 2359 1386 2360 453 2360 455 2360 443 2361 449 2361 1394 2361 1394 2362 449 2362 451 2362 1394 2363 451 2363 1395 2363 1395 2364 451 2364 1393 2364 1263 2365 1262 2365 1388 2365 1388 2366 1262 2366 1267 2366 1388 2367 1267 2367 1396 2367 1396 2368 1267 2368 1391 2368 1396 2369 1391 2369 446 2369 446 2370 1391 2370 1390 2370 446 2371 1390 2371 442 2371 442 2372 1390 2372 437 2372 1385 2373 1374 2373 1386 2373 1386 2374 1374 2374 1387 2374 1386 2375 1387 2375 1393 2375 1393 2376 1387 2376 1392 2376 1393 2377 1392 2377 1395 2377 1395 2378 1392 2378 1389 2378 1395 2379 1389 2379 1394 2379 1394 2380 1389 2380 1388 2380 1394 2381 1388 2381 443 2381 443 2382 1388 2382 1396 2382 443 2383 1396 2383 444 2383 444 2384 1396 2384 446 2384 438 2385 327 2385 439 2385 439 2386 327 2386 313 2386 427 2387 426 2387 1397 2387 1326 2388 1147 2388 1370 2388 1398 2389 1310 2389 1399 2389 1399 2390 1310 2390 1326 2390 1399 2391 1326 2391 1400 2391 1400 2392 1326 2392 1370 2392 1308 2393 1306 2393 1401 2393 1401 2394 1306 2394 1305 2394 1401 2395 1305 2395 1398 2395 1398 2396 1305 2396 1311 2396 1398 2397 1311 2397 1310 2397 423 2398 431 2398 1402 2398 1402 2399 431 2399 433 2399 1402 2400 433 2400 1403 2400 1403 2401 433 2401 435 2401 426 2402 424 2402 1397 2402 1397 2403 424 2403 423 2403 1397 2404 423 2404 1404 2404 1404 2405 423 2405 1402 2405 1404 2406 1402 2406 1304 2406 1304 2407 1402 2407 1403 2407 1304 2408 1403 2408 1286 2408 1286 2409 1403 2409 435 2409 1286 2410 435 2410 382 2410 1304 2411 1309 2411 1404 2411 1404 2412 1309 2412 1308 2412 1404 2413 1308 2413 1397 2413 1397 2414 1308 2414 1401 2414 1397 2415 1401 2415 427 2415 1363 2416 418 2416 1405 2416 1405 2417 418 2417 416 2417 1405 2418 416 2418 1406 2418 1406 2419 416 2419 422 2419 1406 2420 422 2420 1407 2420 1407 2421 422 2421 428 2421 1407 2422 428 2422 1408 2422 428 2423 427 2423 1408 2423 1408 2424 427 2424 1401 2424 1408 2425 1401 2425 1407 2425 1407 2426 1401 2426 1398 2426 1407 2427 1398 2427 1406 2427 1406 2428 1398 2428 1399 2428 1406 2429 1399 2429 1405 2429 1405 2430 1399 2430 1400 2430 1405 2431 1400 2431 1363 2431 1363 2432 1400 2432 1370 2432 358 2433 382 2433 436 2433 436 2434 382 2434 435 2434 1409 2435 1410 2435 1411 2435 1411 2436 1410 2436 1412 2436 1411 2437 1412 2437 1413 2437 1414 2438 1415 2438 1416 2438 1416 2439 1415 2439 1417 2439 1414 2440 1418 2440 1415 2440 1415 2441 1418 2441 1419 2441 1415 2442 1419 2442 1409 2442 1409 2443 1419 2443 1420 2443 1409 2444 1420 2444 1410 2444 1421 2445 1422 2445 1423 2445 1423 2446 1422 2446 1424 2446 1423 2447 1424 2447 1417 2447 1417 2448 1424 2448 1425 2448 1417 2449 1425 2449 1416 2449 1421 2450 1423 2450 1426 2450 1426 2451 1423 2451 1427 2451 1426 2452 1427 2452 1428 2452 1428 2453 1427 2453 1429 2453 1429 2454 1427 2454 1430 2454 1429 2455 1430 2455 1431 2455 1432 2456 1433 2456 1434 2456 1434 2457 1433 2457 1435 2457 1434 2458 1435 2458 1436 2458 1436 2459 1435 2459 1437 2459 1436 2460 1437 2460 1438 2460 1438 2461 1437 2461 1439 2461 1438 2462 1439 2462 1440 2462 1440 2463 1439 2463 1441 2463 1440 2464 1441 2464 1442 2464 1442 2465 1441 2465 1411 2465 1442 2466 1411 2466 1443 2466 1443 2467 1411 2467 1413 2467 1443 2468 1413 2468 1444 2468 1445 2469 1431 2469 1446 2469 1446 2470 1431 2470 1430 2470 1446 2471 1430 2471 1447 2471 1447 2472 1430 2472 1433 2472 1447 2473 1433 2473 1448 2473 1448 2474 1433 2474 1432 2474 1449 2475 1450 2475 1451 2475 1452 2476 1453 2476 1454 2476 1454 2477 1453 2477 1455 2477 1454 2478 1455 2478 1456 2478 1456 2479 1455 2479 1457 2479 1456 2480 1457 2480 1458 2480 1458 2481 1457 2481 1459 2481 1458 2482 1459 2482 1460 2482 1460 2483 1459 2483 1461 2483 1460 2484 1461 2484 1462 2484 1462 2485 1461 2485 1463 2485 1462 2486 1463 2486 1464 2486 1464 2487 1463 2487 1465 2487 1464 2488 1465 2488 1466 2488 1466 2489 1465 2489 1467 2489 1466 2490 1467 2490 1451 2490 1451 2491 1467 2491 1468 2491 1451 2492 1468 2492 1449 2492 1469 2493 1470 2493 1471 2493 1472 2494 1473 2494 1474 2494 1474 523 1475 523 337 523 337 2495 1475 2495 1476 2495 337 2496 1476 2496 1471 2496 1471 2497 1476 2497 1477 2497 1471 2498 1477 2498 1469 2498 1474 2499 337 2499 1472 2499 1472 523 337 523 338 523 1472 523 338 523 1478 523 1451 2500 1450 2500 1479 2500 1458 2501 1460 2501 1480 2501 1480 2502 1460 2502 1462 2502 1480 2503 1462 2503 380 2503 380 2504 1462 2504 1464 2504 380 2505 1464 2505 1466 2505 1481 523 378 523 1479 523 1479 523 378 523 380 523 1479 2506 380 2506 1451 2506 1451 2507 380 2507 1466 2507 1482 498 1483 498 1484 498 1484 498 1483 498 1485 498 1486 528 1487 528 1488 528 1488 528 1487 528 1489 528 1490 2508 1487 2508 1491 2508 1491 2509 1487 2509 1492 2509 1491 2510 1492 2510 1493 2510 1493 2511 1492 2511 1494 2511 1495 548 331 548 385 548 385 548 331 548 336 548 1489 2512 1487 2512 1496 2512 1497 2513 1498 2513 1499 2513 1497 2514 1499 2514 1500 2514 1500 2515 1499 2515 1501 2515 1500 2516 1501 2516 1502 2516 1502 2517 1501 2517 1503 2517 1502 2518 1503 2518 1496 2518 1496 2519 1503 2519 1504 2519 1496 2520 1504 2520 1489 2520 1482 2521 1505 2521 1506 2521 1483 2522 1482 2522 1507 2522 1507 2523 1482 2523 1506 2523 1507 2524 1506 2524 1508 2524 1508 2525 1506 2525 1509 2525 1508 2526 1509 2526 1510 2526 1511 2527 1512 2527 1513 2527 1513 2528 1512 2528 1514 2528 1513 2529 1514 2529 1515 2529 1515 2530 1514 2530 1516 2530 1515 2531 1516 2531 1517 2531 1517 2532 1516 2532 1510 2532 1517 2533 1510 2533 1518 2533 1518 2534 1510 2534 1509 2534 1519 2535 1483 2535 1520 2535 1521 2536 1522 2536 1523 2536 1523 2537 1522 2537 1524 2537 1523 2538 1524 2538 1525 2538 1524 2539 1526 2539 1525 2539 1525 2540 1526 2540 1527 2540 1525 2541 1527 2541 1528 2541 1528 2542 1527 2542 1529 2542 1528 2543 1529 2543 1520 2543 1520 2544 1529 2544 1530 2544 1520 2545 1530 2545 1519 2545 477 2546 488 2546 1531 2546 1531 2547 488 2547 1532 2547 1531 2548 1532 2548 1533 2548 1533 2549 1532 2549 1534 2549 1533 2550 1534 2550 1535 2550 1535 2551 1534 2551 1536 2551 1535 2552 1536 2552 1521 2552 1521 2553 1536 2553 1537 2553 1521 2554 1537 2554 1522 2554 1538 523 1497 523 1539 523 1539 523 1497 523 1540 523 1539 2555 1540 2555 1541 2555 1542 2556 1543 2556 1544 2556 1544 523 1543 523 1512 523 1544 523 1512 523 1545 523 1546 523 1547 523 1511 523 1511 523 1547 523 1498 523 1511 523 1498 523 1512 523 1512 523 1498 523 1497 523 1512 523 1497 523 1545 523 1545 523 1497 523 1538 523 386 548 356 548 1548 548 1548 548 356 548 379 548 1549 2557 1550 2557 1551 2557 1549 769 1552 769 1553 769 1554 2558 1555 2558 1556 2558 1556 2559 1555 2559 1549 2559 1556 769 1549 769 1557 769 1557 769 1549 769 1551 769 1558 769 1550 769 1559 769 1559 769 1550 769 1549 769 1559 769 1549 769 1560 769 1560 769 1549 769 1553 769 1561 2560 1562 2560 1563 2560 1563 2561 1562 2561 1564 2561 1563 2562 1564 2562 1565 2562 1563 2563 1566 2563 1561 2563 1561 2564 1566 2564 1567 2564 1561 2565 1567 2565 1568 2565 1568 2566 1567 2566 1569 2566 1568 2566 1569 2566 1570 2566 1570 2567 1569 2567 1571 2567 1570 2567 1571 2567 1572 2567 1572 2568 1571 2568 1573 2568 1572 2569 1573 2569 1574 2569 1575 2570 1576 2570 1577 2570 1574 2571 1573 2571 1577 2571 1577 2572 1573 2572 1578 2572 1577 2573 1578 2573 1575 2573 1579 2574 1580 2574 1578 2574 1578 2575 1580 2575 1581 2575 1578 2576 1581 2576 1575 2576 1582 2577 1583 2577 1579 2577 1579 2578 1583 2578 1584 2578 1579 2579 1584 2579 1580 2579 1585 2580 1586 2580 1582 2580 1582 2581 1586 2581 1587 2581 1582 2582 1587 2582 1583 2582 1588 2583 1589 2583 1585 2583 1585 2584 1589 2584 1590 2584 1585 2585 1590 2585 1586 2585 1591 2586 1592 2586 1588 2586 1588 2587 1592 2587 1593 2587 1588 2588 1593 2588 1589 2588 1565 2589 1594 2589 1563 2589 1563 2590 1594 2590 1595 2590 1563 2591 1595 2591 1591 2591 1591 2592 1595 2592 1596 2592 1591 2593 1596 2593 1592 2593 1597 2594 1598 2594 1599 2594 1600 2595 1601 2595 1602 2595 1603 2596 1604 2596 1605 2596 1606 2597 1576 2597 1575 2597 1607 2598 1608 2598 1609 2598 1609 2599 1608 2599 1610 2599 1603 2600 1605 2600 1611 2600 1612 2601 1613 2601 1614 2601 1615 2602 1616 2602 1614 2602 1614 2603 1616 2603 1617 2603 1614 2604 1617 2604 1612 2604 1618 2605 1619 2605 1620 2605 1619 2606 1618 2606 1621 2606 1621 2607 1618 2607 1622 2607 1621 2608 1622 2608 1623 2608 1623 2609 1622 2609 1624 2609 1624 2610 1622 2610 1625 2610 1624 2611 1625 2611 1626 2611 1627 2612 1628 2612 1629 2612 1629 2613 1628 2613 1630 2613 1629 2614 1630 2614 1625 2614 1625 2615 1630 2615 1631 2615 1625 2616 1631 2616 1626 2616 1632 2617 1633 2617 1627 2617 1627 2618 1633 2618 1634 2618 1627 2619 1634 2619 1628 2619 1635 2620 1636 2620 1637 2620 1637 2621 1636 2621 1632 2621 1637 2622 1632 2622 1638 2622 1638 2623 1632 2623 1627 2623 1635 2624 1637 2624 1639 2624 1639 2625 1637 2625 1602 2625 1639 2626 1602 2626 1640 2626 1601 2627 1641 2627 1602 2627 1602 2628 1641 2628 1642 2628 1602 2629 1642 2629 1640 2629 1643 2630 1644 2630 1645 2630 1646 2631 1647 2631 1645 2631 1645 2632 1647 2632 1648 2632 1645 2633 1648 2633 1643 2633 1597 2634 1599 2634 1649 2634 1650 2635 1651 2635 1652 2635 1652 2636 1651 2636 1653 2636 1652 2637 1653 2637 1564 2637 1593 2638 1592 2638 1654 2638 1654 2639 1592 2639 1596 2639 1654 2640 1596 2640 1655 2640 1655 2641 1596 2641 1595 2641 1655 2642 1595 2642 1656 2642 1656 2643 1595 2643 1594 2643 1656 2644 1594 2644 1653 2644 1653 2645 1594 2645 1565 2645 1653 2646 1565 2646 1564 2646 1593 2647 1654 2647 1589 2647 1589 2648 1654 2648 1657 2648 1589 2649 1657 2649 1590 2649 1590 2650 1657 2650 1658 2650 1590 2651 1658 2651 1586 2651 1586 2652 1658 2652 1587 2652 1587 2653 1658 2653 1659 2653 1587 2654 1659 2654 1583 2654 1583 2655 1659 2655 1660 2655 1583 2656 1660 2656 1584 2656 1584 2657 1660 2657 1661 2657 1584 2658 1661 2658 1580 2658 1610 2659 1606 2659 1609 2659 1609 2660 1606 2660 1575 2660 1609 2661 1575 2661 1661 2661 1661 2662 1575 2662 1581 2662 1661 2663 1581 2663 1580 2663 1651 2664 1649 2664 1653 2664 1653 2665 1649 2665 1599 2665 1653 2666 1599 2666 1656 2666 1656 2667 1599 2667 1662 2667 1656 2668 1662 2668 1655 2668 1655 2669 1662 2669 1663 2669 1655 2670 1663 2670 1654 2670 1654 2671 1663 2671 1664 2671 1654 2672 1664 2672 1657 2672 1657 2673 1664 2673 1665 2673 1657 2674 1665 2674 1658 2674 1658 2675 1665 2675 1666 2675 1658 2676 1666 2676 1659 2676 1659 2677 1666 2677 1667 2677 1659 2678 1667 2678 1660 2678 1660 2679 1667 2679 1668 2679 1660 2680 1668 2680 1661 2680 1661 2681 1668 2681 1669 2681 1661 2682 1669 2682 1609 2682 1609 2683 1669 2683 1605 2683 1609 2684 1605 2684 1607 2684 1607 2685 1605 2685 1604 2685 1598 2686 1646 2686 1599 2686 1599 2687 1646 2687 1645 2687 1599 2688 1645 2688 1662 2688 1662 2689 1645 2689 1670 2689 1662 2690 1670 2690 1663 2690 1663 2691 1670 2691 1671 2691 1663 2692 1671 2692 1664 2692 1664 2693 1671 2693 1672 2693 1664 2694 1672 2694 1665 2694 1665 2695 1672 2695 1673 2695 1665 2696 1673 2696 1666 2696 1666 2697 1673 2697 1674 2697 1666 2698 1674 2698 1667 2698 1667 2699 1674 2699 1675 2699 1667 2700 1675 2700 1668 2700 1668 2701 1675 2701 1676 2701 1668 2702 1676 2702 1669 2702 1669 2703 1676 2703 1615 2703 1669 2704 1615 2704 1605 2704 1605 2705 1615 2705 1614 2705 1605 2706 1614 2706 1611 2706 1611 2707 1614 2707 1613 2707 1611 2708 1613 2708 1677 2708 1644 2709 1678 2709 1645 2709 1645 2710 1678 2710 1600 2710 1645 2711 1600 2711 1670 2711 1670 2712 1600 2712 1602 2712 1670 2713 1602 2713 1671 2713 1671 2714 1602 2714 1637 2714 1671 2715 1637 2715 1672 2715 1672 2716 1637 2716 1638 2716 1672 2717 1638 2717 1673 2717 1673 2718 1638 2718 1627 2718 1673 2719 1627 2719 1674 2719 1674 2720 1627 2720 1629 2720 1674 2721 1629 2721 1675 2721 1675 2722 1629 2722 1625 2722 1675 2723 1625 2723 1676 2723 1676 2724 1625 2724 1622 2724 1676 2725 1622 2725 1615 2725 1615 2726 1622 2726 1618 2726 1615 2727 1618 2727 1616 2727 1616 2728 1618 2728 1620 2728 1679 2729 1621 2729 1623 2729 1680 2730 1681 2730 1682 2730 1682 2731 1681 2731 1683 2731 1682 2732 1683 2732 1684 2732 1680 2733 1682 2733 1685 2733 1685 2734 1682 2734 1686 2734 1685 2735 1686 2735 1687 2735 1687 2736 1686 2736 1688 2736 1687 2737 1688 2737 1689 2737 1690 2738 1691 2738 1692 2738 1690 2739 1692 2739 1693 2739 1693 2740 1692 2740 1694 2740 1693 2741 1694 2741 1695 2741 1696 2742 1632 2742 1697 2742 1697 2743 1632 2743 1636 2743 1698 2744 1699 2744 1691 2744 1691 2745 1699 2745 1700 2745 1691 2746 1700 2746 1692 2746 1639 2747 1701 2747 1635 2747 1635 2748 1701 2748 1702 2748 1635 2749 1702 2749 1636 2749 1636 2750 1702 2750 1703 2750 1636 2751 1703 2751 1697 2751 1696 2752 1698 2752 1632 2752 1632 2753 1698 2753 1691 2753 1632 2754 1691 2754 1633 2754 1633 2755 1691 2755 1690 2755 1633 2756 1690 2756 1634 2756 1634 2757 1690 2757 1628 2757 1630 2758 1686 2758 1631 2758 1631 2759 1686 2759 1682 2759 1631 2760 1682 2760 1626 2760 1626 2761 1682 2761 1684 2761 1626 2762 1684 2762 1624 2762 1624 2763 1684 2763 1704 2763 1624 2764 1704 2764 1623 2764 1623 2765 1704 2765 1705 2765 1623 2766 1705 2766 1679 2766 1630 2767 1628 2767 1686 2767 1686 2768 1628 2768 1690 2768 1686 2769 1690 2769 1688 2769 1688 2770 1690 2770 1693 2770 1688 2771 1693 2771 1689 2771 1689 2772 1693 2772 1695 2772 1689 2773 1695 2773 1706 2773 1707 2774 1708 2774 1709 2774 1695 2775 1710 2775 1706 2775 1706 2776 1710 2776 1711 2776 1712 2777 1713 2777 1714 2777 1714 2778 1713 2778 1715 2778 1714 2779 1715 2779 1716 2779 1716 2780 1715 2780 1717 2780 1716 2781 1717 2781 1718 2781 1719 2782 1720 2782 1712 2782 1712 2783 1720 2783 1721 2783 1712 2784 1721 2784 1713 2784 1722 2785 1723 2785 1724 2785 1724 2786 1723 2786 1725 2786 1724 2787 1725 2787 1726 2787 1726 2788 1725 2788 1719 2788 1726 2789 1719 2789 1727 2789 1727 2790 1719 2790 1712 2790 1722 2791 1724 2791 1728 2791 1728 2792 1724 2792 1729 2792 1728 2793 1729 2793 1730 2793 1730 2794 1729 2794 1731 2794 1730 2795 1731 2795 1732 2795 1698 2796 1733 2796 1699 2796 1699 2797 1733 2797 1734 2797 1700 2798 1735 2798 1692 2798 1692 2799 1735 2799 1736 2799 1692 2800 1736 2800 1694 2800 1694 2801 1736 2801 1737 2801 1694 2802 1737 2802 1695 2802 1695 2803 1737 2803 1738 2803 1695 2804 1738 2804 1710 2804 1739 2805 1709 2805 1703 2805 1703 2806 1709 2806 1708 2806 1703 2807 1708 2807 1697 2807 1697 2808 1708 2808 1707 2808 1697 2809 1707 2809 1696 2809 1698 2810 1696 2810 1733 2810 1733 2811 1696 2811 1707 2811 1733 2812 1707 2812 1740 2812 1740 2813 1707 2813 1709 2813 1740 2814 1709 2814 1741 2814 1741 2815 1709 2815 1739 2815 1741 2816 1739 2816 1742 2816 1743 2817 1711 2817 1744 2817 1744 2818 1711 2818 1710 2818 1744 2819 1710 2819 1745 2819 1745 2820 1710 2820 1738 2820 1745 2821 1738 2821 1746 2821 1746 2822 1738 2822 1737 2822 1746 2823 1737 2823 1747 2823 1747 2824 1737 2824 1736 2824 1747 2825 1736 2825 1748 2825 1748 2826 1736 2826 1735 2826 1748 2827 1735 2827 1734 2827 1734 2828 1735 2828 1700 2828 1734 2829 1700 2829 1699 2829 1718 2830 1749 2830 1716 2830 1716 2831 1749 2831 1750 2831 1716 2832 1750 2832 1714 2832 1714 2833 1750 2833 1751 2833 1714 2834 1751 2834 1712 2834 1712 2835 1751 2835 1752 2835 1712 2836 1752 2836 1727 2836 1727 2837 1752 2837 1753 2837 1727 2838 1753 2838 1726 2838 1726 2839 1753 2839 1754 2839 1726 2840 1754 2840 1724 2840 1724 2841 1754 2841 1755 2841 1724 2842 1755 2842 1729 2842 1729 2843 1755 2843 1756 2843 1729 2844 1756 2844 1731 2844 1731 2845 1756 2845 1757 2845 1731 2846 1757 2846 1732 2846 1742 2847 1730 2847 1741 2847 1741 2848 1730 2848 1732 2848 1741 2849 1732 2849 1740 2849 1740 2850 1732 2850 1757 2850 1740 2851 1757 2851 1733 2851 1733 2852 1757 2852 1756 2852 1733 2853 1756 2853 1734 2853 1734 2854 1756 2854 1755 2854 1734 2855 1755 2855 1748 2855 1748 2856 1755 2856 1754 2856 1748 2857 1754 2857 1747 2857 1747 2858 1754 2858 1753 2858 1747 2859 1753 2859 1746 2859 1746 2860 1753 2860 1752 2860 1746 2861 1752 2861 1745 2861 1745 2862 1752 2862 1751 2862 1745 2863 1751 2863 1744 2863 1744 2864 1751 2864 1750 2864 1744 2865 1750 2865 1743 2865 1743 2866 1750 2866 1749 2866 1758 2867 1759 2867 1760 2867 1760 2868 1759 2868 1761 2868 1760 2869 1761 2869 1762 2869 1758 2870 1760 2870 1763 2870 1763 2871 1760 2871 1764 2871 1763 2872 1764 2872 1765 2872 1765 2873 1764 2873 1766 2873 1765 2874 1766 2874 1767 2874 1767 2875 1766 2875 1768 2875 1767 2876 1768 2876 1769 2876 1769 2877 1768 2877 1770 2877 1769 2878 1770 2878 1771 2878 1771 2879 1770 2879 1772 2879 1772 2880 1770 2880 1773 2880 1772 2881 1773 2881 1774 2881 1774 2882 1773 2882 1775 2882 1774 2883 1775 2883 1776 2883 1776 2884 1775 2884 1777 2884 1776 2885 1777 2885 1778 2885 1778 2886 1777 2886 1779 2886 1778 2887 1779 2887 1780 2887 1780 2888 1779 2888 1781 2888 1780 2889 1781 2889 1782 2889 1782 2890 1781 2890 1783 2890 1782 2891 1783 2891 1784 2891 1784 2892 1783 2892 1785 2892 1784 2893 1785 2893 1786 2893 1787 2894 1788 2894 1789 2894 1788 2895 1787 2895 1706 2895 1706 2896 1787 2896 1790 2896 1706 2897 1790 2897 1689 2897 1689 2898 1790 2898 1791 2898 1689 2899 1791 2899 1687 2899 1681 2900 1680 2900 1792 2900 1792 2901 1680 2901 1685 2901 1792 2902 1685 2902 1793 2902 1793 2903 1685 2903 1687 2903 1793 2904 1687 2904 1794 2904 1794 2905 1687 2905 1791 2905 1795 2906 1705 2906 1704 2906 1789 2907 1796 2907 1787 2907 1787 2908 1796 2908 1797 2908 1787 2909 1797 2909 1790 2909 1790 2910 1797 2910 1798 2910 1790 2911 1798 2911 1791 2911 1791 2912 1798 2912 1799 2912 1791 2913 1799 2913 1794 2913 1794 2914 1799 2914 1800 2914 1794 2915 1800 2915 1793 2915 1793 2916 1800 2916 1801 2916 1793 2917 1801 2917 1792 2917 1792 2918 1801 2918 1802 2918 1792 2919 1802 2919 1681 2919 1681 2920 1802 2920 1803 2920 1681 2921 1803 2921 1683 2921 1683 2922 1803 2922 1804 2922 1683 2923 1804 2923 1684 2923 1684 2924 1804 2924 1805 2924 1684 2925 1805 2925 1704 2925 1704 2926 1805 2926 1806 2926 1704 2927 1806 2927 1795 2927 1795 2928 1806 2928 1807 2928 1762 2929 1807 2929 1760 2929 1760 2930 1807 2930 1806 2930 1760 2931 1806 2931 1764 2931 1764 2932 1806 2932 1805 2932 1764 2933 1805 2933 1766 2933 1766 2934 1805 2934 1804 2934 1766 2935 1804 2935 1768 2935 1768 2936 1804 2936 1803 2936 1768 2937 1803 2937 1770 2937 1770 2938 1803 2938 1802 2938 1770 2939 1802 2939 1773 2939 1773 2940 1802 2940 1801 2940 1773 2941 1801 2941 1775 2941 1775 2942 1801 2942 1800 2942 1775 2943 1800 2943 1777 2943 1777 2944 1800 2944 1799 2944 1777 2945 1799 2945 1779 2945 1779 2946 1799 2946 1798 2946 1779 2947 1798 2947 1781 2947 1781 2948 1798 2948 1797 2948 1781 2949 1797 2949 1783 2949 1783 2950 1797 2950 1796 2950 1783 2951 1796 2951 1785 2951 1785 2952 1796 2952 1789 2952 1717 2953 1808 2953 1809 2953 1810 2954 1706 2954 1711 2954 1810 2955 1711 2955 1811 2955 1811 2956 1711 2956 1743 2956 1811 2957 1743 2957 1812 2957 1812 2958 1743 2958 1749 2958 1812 2959 1749 2959 1809 2959 1809 2960 1749 2960 1718 2960 1809 2961 1718 2961 1717 2961 1813 2962 1814 2962 1786 2962 1786 2963 1785 2963 1813 2963 1813 2964 1785 2964 1789 2964 1813 2965 1789 2965 1815 2965 1815 2966 1789 2966 1788 2966 1815 2967 1788 2967 1816 2967 1816 2968 1788 2968 1706 2968 1816 2969 1706 2969 1810 2969 1817 2970 1431 2970 1445 2970 1817 2971 1445 2971 1808 2971 1808 2972 1445 2972 1818 2972 1808 2973 1818 2973 1809 2973 1413 2974 1819 2974 1444 2974 1444 2975 1819 2975 1814 2975 1444 2976 1814 2976 1820 2976 1820 2977 1814 2977 1813 2977 1820 2978 1813 2978 1821 2978 1821 2979 1813 2979 1822 2979 1822 2980 1813 2980 1815 2980 1822 2981 1815 2981 1823 2981 1818 2982 1824 2982 1809 2982 1809 2983 1824 2983 1825 2983 1809 2984 1825 2984 1812 2984 1812 2985 1825 2985 1826 2985 1812 2986 1826 2986 1811 2986 1811 2987 1826 2987 1827 2987 1811 2988 1827 2988 1810 2988 1810 2989 1827 2989 1823 2989 1810 2990 1823 2990 1816 2990 1816 2991 1823 2991 1815 2991 1443 2992 1444 2992 1820 2992 1826 548 1825 548 1448 548 1448 2993 1825 2993 1447 2993 1448 548 1432 548 1826 548 1826 548 1432 548 1434 548 1826 548 1434 548 1827 548 1827 548 1434 548 1436 548 1827 548 1436 548 1823 548 1823 2994 1436 2994 1438 2994 1823 2995 1438 2995 1822 2995 1822 2996 1438 2996 1440 2996 1822 548 1440 548 1821 548 1821 548 1440 548 1820 548 1820 548 1440 548 1442 548 1820 548 1442 548 1443 548 1445 548 1446 548 1818 548 1818 548 1446 548 1447 548 1818 2997 1447 2997 1824 2997 1824 2998 1447 2998 1825 2998 1828 2999 1786 2999 1814 2999 1829 498 1828 498 1830 498 1830 3000 1828 3000 1814 3000 1830 3001 1814 3001 1831 3001 1831 3002 1814 3002 1819 3002 1832 3003 1833 3003 1834 3003 1835 3004 1836 3004 1837 3004 1838 3005 1835 3005 1839 3005 1840 3006 1841 3006 1839 3006 1839 3007 1841 3007 1842 3007 1839 3008 1842 3008 1838 3008 1835 3009 1837 3009 1839 3009 1839 3010 1837 3010 1843 3010 1839 3011 1843 3011 1840 3011 1840 3012 1843 3012 1844 3012 1840 3013 1844 3013 1845 3013 1846 3014 1847 3014 1845 3014 1845 3015 1847 3015 1848 3015 1845 3016 1848 3016 1840 3016 1840 3017 1848 3017 1849 3017 1840 3018 1849 3018 1841 3018 1850 3019 1846 3019 1851 3019 1851 3020 1846 3020 1845 3020 1851 3021 1845 3021 1852 3021 1852 3022 1845 3022 1844 3022 1833 3023 1850 3023 1834 3023 1834 3024 1850 3024 1851 3024 1834 3025 1851 3025 1853 3025 1853 3026 1851 3026 1852 3026 1853 3027 1852 3027 1854 3027 1854 3028 1852 3028 1844 3028 1854 3029 1844 3029 1855 3029 1855 3030 1844 3030 1843 3030 1855 3031 1843 3031 1856 3031 1856 3032 1843 3032 1837 3032 1856 3033 1837 3033 1857 3033 1857 3034 1837 3034 1836 3034 1857 3035 1836 3035 1858 3035 1858 3036 1836 3036 1835 3036 1858 3037 1835 3037 1859 3037 1859 3038 1835 3038 1838 3038 1859 3039 1838 3039 1860 3039 1861 3040 1832 3040 1862 3040 1862 3041 1832 3041 1834 3041 1862 3042 1834 3042 1863 3042 1863 3043 1834 3043 1853 3043 1863 3044 1853 3044 1864 3044 1864 3045 1853 3045 1854 3045 1831 3046 1861 3046 1830 3046 1830 3047 1861 3047 1862 3047 1830 3048 1862 3048 1829 3048 1829 3049 1862 3049 1863 3049 1829 3050 1863 3050 1828 3050 1828 3051 1863 3051 1864 3051 1865 3052 1866 3052 1867 3052 1868 3053 1869 3053 1870 3053 1871 3054 1872 3054 1869 3054 1870 3055 1873 3055 1874 3055 1874 3056 1873 3056 1875 3056 1874 3057 1875 3057 1876 3057 1876 3058 1875 3058 1877 3058 1876 3059 1877 3059 1878 3059 1877 3060 1879 3060 1878 3060 1878 3061 1879 3061 1880 3061 1878 3062 1880 3062 1867 3062 1867 3063 1880 3063 1881 3063 1867 3064 1881 3064 1865 3064 1870 3065 1874 3065 1868 3065 1868 3066 1874 3066 1876 3066 1868 3067 1876 3067 1882 3067 1882 3068 1876 3068 1878 3068 1882 3069 1878 3069 1883 3069 1883 3070 1878 3070 1867 3070 1883 3071 1867 3071 1884 3071 1884 3072 1867 3072 1866 3072 1884 3073 1866 3073 1885 3073 1869 3074 1868 3074 1871 3074 1871 3075 1868 3075 1882 3075 1871 3076 1882 3076 1886 3076 1886 3077 1882 3077 1883 3077 1886 3078 1883 3078 1887 3078 1887 3079 1883 3079 1884 3079 1887 3080 1884 3080 1888 3080 1888 3081 1884 3081 1885 3081 1888 3082 1885 3082 1889 3082 1890 3083 1891 3083 1892 3083 1892 3084 1891 3084 1893 3084 1892 3085 1893 3085 1894 3085 1894 3086 1893 3086 1895 3086 1896 3087 1895 3087 1897 3087 1897 3088 1895 3088 1893 3088 1897 3089 1893 3089 1898 3089 1898 3090 1893 3090 1891 3090 1865 3091 1890 3091 1866 3091 1866 3092 1890 3092 1892 3092 1866 3093 1892 3093 1885 3093 1885 3094 1892 3094 1894 3094 1885 3095 1894 3095 1889 3095 1889 3096 1894 3096 1895 3096 1889 3097 1895 3097 1899 3097 1899 3098 1895 3098 1896 3098 1899 3099 1896 3099 1900 3099 1717 528 1900 528 1808 528 1808 3100 1900 3100 1896 3100 1808 528 1896 528 1817 528 1817 3101 1896 3101 1897 3101 1817 3102 1897 3102 1898 3102 1901 3103 1898 3103 1891 3103 1902 3104 1903 3104 1904 3104 1904 3105 1903 3105 1905 3105 1905 3106 1906 3106 1904 3106 1904 3107 1906 3107 1907 3107 1904 3108 1907 3108 1902 3108 1908 3109 1909 3109 1910 3109 1910 3110 1909 3110 1911 3110 1912 3111 1913 3111 1914 3111 1914 3112 1913 3112 1908 3112 1914 3113 1908 3113 1915 3113 1915 3114 1908 3114 1910 3114 1915 3115 1910 3115 1916 3115 1881 3116 1880 3116 1916 3116 1917 3117 1918 3117 1919 3117 1920 3118 1921 3118 1922 3118 1922 3119 1921 3119 1923 3119 1922 3120 1923 3120 1924 3120 1924 3121 1923 3121 1925 3121 1924 3122 1925 3122 1926 3122 1926 3123 1925 3123 1906 3123 1926 3124 1906 3124 1927 3124 1927 3125 1906 3125 1905 3125 1927 3126 1905 3126 1928 3126 1928 3127 1542 3127 1927 3127 1927 3128 1542 3128 1929 3128 1927 3129 1929 3129 1926 3129 1926 3130 1929 3130 1930 3130 1926 3131 1930 3131 1924 3131 1924 3132 1930 3132 1917 3132 1924 3133 1917 3133 1922 3133 1922 3134 1917 3134 1919 3134 1922 3135 1919 3135 1920 3135 1870 3136 1912 3136 1873 3136 1873 3137 1912 3137 1914 3137 1873 3138 1914 3138 1875 3138 1875 3139 1914 3139 1915 3139 1875 3140 1915 3140 1877 3140 1877 3141 1915 3141 1916 3141 1877 3142 1916 3142 1879 3142 1879 3143 1916 3143 1880 3143 1921 3144 1865 3144 1923 3144 1923 3145 1865 3145 1881 3145 1923 3146 1881 3146 1925 3146 1925 3147 1881 3147 1916 3147 1925 3148 1916 3148 1906 3148 1906 3149 1916 3149 1910 3149 1906 3150 1910 3150 1907 3150 1907 3151 1910 3151 1911 3151 1907 3152 1911 3152 1902 3152 1542 3153 1931 3153 1929 3153 1929 3154 1931 3154 1932 3154 1929 3155 1932 3155 1930 3155 1930 3156 1932 3156 1933 3156 1930 3157 1933 3157 1917 3157 1917 3158 1933 3158 1934 3158 1917 3159 1934 3159 1918 3159 1918 3160 1934 3160 1935 3160 1918 3161 1935 3161 1919 3161 1919 3162 1935 3162 1901 3162 1919 3163 1901 3163 1920 3163 1920 3164 1901 3164 1891 3164 1920 3165 1891 3165 1921 3165 1921 3166 1891 3166 1890 3166 1921 3167 1890 3167 1865 3167 1936 3168 1937 3168 1938 3168 1939 3169 1940 3169 1941 3169 1936 3170 1942 3170 1943 3170 1943 3171 1942 3171 1861 3171 1943 3172 1861 3172 1831 3172 1944 3173 1850 3173 1945 3173 1945 3174 1850 3174 1833 3174 1945 3175 1833 3175 1942 3175 1942 3176 1833 3176 1832 3176 1942 3177 1832 3177 1861 3177 1860 3178 1838 3178 1946 3178 1946 3179 1838 3179 1842 3179 1946 3180 1842 3180 1947 3180 1947 3181 1842 3181 1841 3181 1947 3182 1841 3182 1948 3182 1948 3183 1841 3183 1849 3183 1948 3184 1849 3184 1949 3184 1949 3185 1849 3185 1848 3185 1949 3186 1848 3186 1847 3186 1860 3187 1946 3187 1941 3187 1941 3188 1946 3188 1947 3188 1941 3189 1947 3189 1939 3189 1939 3190 1947 3190 1948 3190 1939 3191 1948 3191 1950 3191 1950 3192 1948 3192 1949 3192 1950 3193 1949 3193 1951 3193 1951 3194 1949 3194 1847 3194 1951 3195 1847 3195 1944 3195 1944 3196 1847 3196 1846 3196 1944 3197 1846 3197 1850 3197 1936 3198 1952 3198 1942 3198 1942 3199 1952 3199 1953 3199 1942 3200 1953 3200 1945 3200 1945 3201 1953 3201 1954 3201 1945 3202 1954 3202 1944 3202 1944 3203 1954 3203 1955 3203 1944 3204 1955 3204 1951 3204 1951 3205 1955 3205 1956 3205 1951 3206 1956 3206 1950 3206 1950 3207 1956 3207 1957 3207 1950 3208 1957 3208 1939 3208 1939 3209 1957 3209 1958 3209 1939 3210 1958 3210 1940 3210 1936 3211 1938 3211 1952 3211 1952 3212 1938 3212 1959 3212 1952 3213 1959 3213 1953 3213 1953 3214 1959 3214 1960 3214 1953 3215 1960 3215 1954 3215 1954 3216 1960 3216 1541 3216 1954 3217 1541 3217 1955 3217 1955 3218 1541 3218 1961 3218 1955 3219 1961 3219 1956 3219 1819 3220 1413 3220 1412 3220 1431 3221 1817 3221 1429 3221 1429 3222 1817 3222 1898 3222 1898 3223 1901 3223 1429 3223 1429 3224 1901 3224 1935 3224 1429 3225 1935 3225 1428 3225 1428 3226 1935 3226 1934 3226 1428 3227 1934 3227 1426 3227 1426 3228 1934 3228 1962 3228 1426 3229 1962 3229 1421 3229 1421 3230 1962 3230 1422 3230 1422 3231 1962 3231 1963 3231 1422 3232 1963 3232 1424 3232 1424 3233 1963 3233 1964 3233 1424 3234 1964 3234 1425 3234 1425 3235 1964 3235 1965 3235 1425 3236 1965 3236 1416 3236 1416 3237 1965 3237 1414 3237 1414 3238 1965 3238 1966 3238 1414 3239 1966 3239 1418 3239 1418 3240 1966 3240 1967 3240 1418 3241 1967 3241 1419 3241 1419 3242 1967 3242 1968 3242 1419 3243 1968 3243 1420 3243 1968 3244 1937 3244 1420 3244 1420 3245 1937 3245 1936 3245 1420 3246 1936 3246 1410 3246 1410 3247 1936 3247 1943 3247 1410 3248 1943 3248 1412 3248 1412 3249 1943 3249 1831 3249 1412 3250 1831 3250 1819 3250 1619 3251 1621 3251 1969 3251 1969 3252 1621 3252 1970 3252 1969 3253 1970 3253 1971 3253 1972 3254 1973 3254 1970 3254 1970 3255 1973 3255 1974 3255 1970 3256 1974 3256 1971 3256 1975 3257 1976 3257 1970 3257 1970 3258 1976 3258 1972 3258 1679 3259 1705 3259 1795 3259 1679 3260 1795 3260 1977 3260 1621 3261 1679 3261 1970 3261 1970 3262 1679 3262 1977 3262 1970 3263 1977 3263 1975 3263 1759 3264 1976 3264 1761 3264 1761 3265 1976 3265 1975 3265 1761 3266 1975 3266 1762 3266 1762 3267 1975 3267 1977 3267 1762 3268 1977 3268 1807 3268 1807 3269 1977 3269 1795 3269 1786 3270 1828 3270 1784 3270 1784 3271 1828 3271 1864 3271 1784 3272 1864 3272 1782 3272 1782 3273 1864 3273 1780 3273 1780 3274 1864 3274 1854 3274 1780 3275 1854 3275 1778 3275 1778 3276 1854 3276 1776 3276 1776 3277 1854 3277 1855 3277 1776 3278 1855 3278 1774 3278 1856 3279 1771 3279 1855 3279 1855 3280 1771 3280 1772 3280 1855 3281 1772 3281 1774 3281 1763 3282 1765 3282 1857 3282 1857 3283 1765 3283 1767 3283 1857 3284 1767 3284 1856 3284 1856 3285 1767 3285 1769 3285 1856 3286 1769 3286 1771 3286 1763 3287 1857 3287 1758 3287 1758 3288 1857 3288 1858 3288 1758 3289 1858 3289 1759 3289 1490 3290 1978 3290 1979 3290 1941 3291 1940 3291 1980 3291 1980 3292 1940 3292 1958 3292 1958 3293 1981 3293 1980 3293 1980 3294 1981 3294 1982 3294 1980 3295 1982 3295 1979 3295 1979 3296 1982 3296 1983 3296 1979 3297 1983 3297 1490 3297 1958 3298 1957 3298 1981 3298 1981 3299 1957 3299 1956 3299 1981 3300 1956 3300 1984 3300 1956 3301 1961 3301 1984 3301 1984 3302 1961 3302 1541 3302 1984 3303 1541 3303 1540 3303 1941 3304 1980 3304 1860 3304 1860 3305 1980 3305 1979 3305 1860 3306 1979 3306 1859 3306 1859 3307 1979 3307 1978 3307 1859 3308 1978 3308 1858 3308 1985 3309 1986 3309 1651 3309 1564 3310 1562 3310 1652 3310 1652 3311 1562 3311 1985 3311 1652 3312 1985 3312 1650 3312 1650 3313 1985 3313 1651 3313 1987 3314 1577 3314 1576 3314 1608 3315 1988 3315 1610 3315 1610 3316 1988 3316 1987 3316 1610 3317 1987 3317 1606 3317 1606 3318 1987 3318 1576 3318 1989 3319 1677 3319 1613 3319 1990 3320 1991 3320 1992 3320 1993 3321 1990 3321 1994 3321 1994 3322 1990 3322 1992 3322 1994 3323 1992 3323 1739 3323 1739 3324 1992 3324 1742 3324 1639 3325 1993 3325 1701 3325 1701 3326 1993 3326 1994 3326 1701 3327 1994 3327 1702 3327 1702 3328 1994 3328 1739 3328 1702 3329 1739 3329 1703 3329 1640 3330 1642 3330 1995 3330 1639 3331 1640 3331 1993 3331 1993 3332 1640 3332 1995 3332 1993 3333 1995 3333 1990 3333 1990 3334 1995 3334 1996 3334 1990 3335 1996 3335 1991 3335 1870 3336 1869 3336 1997 3336 1870 3337 1997 3337 1912 3337 1902 3338 1911 3338 1998 3338 1998 3339 1911 3339 1909 3339 1909 3340 1908 3340 1998 3340 1998 3341 1908 3341 1913 3341 1998 3342 1913 3342 1999 3342 2000 3343 1543 3343 1542 3343 1542 3344 1928 3344 2000 3344 2000 3345 1928 3345 1905 3345 2000 3346 1905 3346 1903 3346 2001 3347 2002 3347 2003 3347 2003 3348 2002 3348 1997 3348 2003 3349 1997 3349 1872 3349 1872 3350 1997 3350 1869 3350 2002 3351 2004 3351 1997 3351 1997 3352 2004 3352 1999 3352 1997 3353 1999 3353 1912 3353 1912 3354 1999 3354 1913 3354 2004 3355 2005 3355 1999 3355 1999 3356 2005 3356 2000 3356 1999 3357 2000 3357 1998 3357 1998 3358 2000 3358 1903 3358 1998 3359 1903 3359 1902 3359 1742 3360 1872 3360 1730 3360 1730 3361 1872 3361 1871 3361 1730 3362 1871 3362 1886 3362 1887 3363 1888 3363 1725 3363 1725 3364 1723 3364 1887 3364 1887 3365 1723 3365 1722 3365 1887 3366 1722 3366 1886 3366 1886 3367 1722 3367 1728 3367 1886 3368 1728 3368 1730 3368 1715 3369 1713 3369 1889 3369 1713 3370 1721 3370 1889 3370 1889 3371 1721 3371 1720 3371 1889 3372 1720 3372 1888 3372 1888 3373 1720 3373 1719 3373 1888 3374 1719 3374 1725 3374 1889 3375 1899 3375 1715 3375 1715 3376 1899 3376 1900 3376 1715 3377 1900 3377 1717 3377 1644 3378 1643 3378 2006 3378 2006 769 1643 769 2007 769 2008 3379 1996 3379 1995 3379 2009 3380 2010 3380 1995 3380 1995 3381 2010 3381 2011 3381 1995 3382 2011 3382 2008 3382 2012 3383 2013 3383 2014 3383 2014 3384 2013 3384 2015 3384 2014 3385 2015 3385 2009 3385 2009 3386 2015 3386 2010 3386 2016 3387 2017 3387 2012 3387 2012 3388 2017 3388 2018 3388 2012 3389 2018 3389 2013 3389 1995 3390 1642 3390 2009 3390 2009 3391 1642 3391 1641 3391 2009 3392 1641 3392 2014 3392 2014 3393 1641 3393 1601 3393 2014 3394 1601 3394 2012 3394 2012 3395 1601 3395 1600 3395 2012 3396 1600 3396 2016 3396 2016 3397 1600 3397 1678 3397 1962 3398 1934 3398 1933 3398 1541 3399 1960 3399 2019 3399 1541 3400 2019 3400 1539 3400 1539 3401 2019 3401 2020 3401 1539 3402 2020 3402 1538 3402 1538 3403 2020 3403 1545 3403 1545 3404 2020 3404 2021 3404 1545 3405 2021 3405 1544 3405 1544 3406 2021 3406 1931 3406 1544 3407 1931 3407 1542 3407 1962 3408 1933 3408 1963 3408 1963 3409 1933 3409 2022 3409 1963 3410 2022 3410 1964 3410 1964 3411 2022 3411 2023 3411 1964 3412 2023 3412 1965 3412 1965 3413 2023 3413 1966 3413 1966 3414 2023 3414 2024 3414 1966 3415 2024 3415 1967 3415 1967 3416 2024 3416 1968 3416 1968 3417 2024 3417 1938 3417 1968 3418 1938 3418 1937 3418 1960 3419 1959 3419 2019 3419 2019 3420 1959 3420 2025 3420 2019 3421 2025 3421 2020 3421 2020 3422 2025 3422 2026 3422 2020 3423 2026 3423 2021 3423 2021 3424 2026 3424 2027 3424 2021 3425 2027 3425 1931 3425 1931 3426 2027 3426 1932 3426 1959 3427 1938 3427 2025 3427 2025 3428 1938 3428 2024 3428 2025 3429 2024 3429 2026 3429 2026 3430 2024 3430 2023 3430 2026 3431 2023 3431 2027 3431 2027 3432 2023 3432 2022 3432 2027 3433 2022 3433 1932 3433 1932 3434 2022 3434 1933 3434 2028 3435 2029 3435 2030 3435 1493 3436 1612 3436 1617 3436 2031 3437 2029 3437 2032 3437 2032 3438 2029 3438 2028 3438 2032 3439 2028 3439 1491 3439 1973 3440 2030 3440 1974 3440 1974 3441 2030 3441 2029 3441 1974 3442 2029 3442 1971 3442 1971 3443 2029 3443 2031 3443 1971 3444 2031 3444 1969 3444 1969 3445 2031 3445 1620 3445 1969 3446 1620 3446 1619 3446 1491 3447 1493 3447 2032 3447 2032 3448 1493 3448 1617 3448 2032 3449 1617 3449 2031 3449 2031 3450 1617 3450 1616 3450 2031 3451 1616 3451 1620 3451 1759 3452 1858 3452 1976 3452 1976 3453 1858 3453 1978 3453 1976 3454 1978 3454 1972 3454 1491 3455 2028 3455 1490 3455 1490 3456 2028 3456 2030 3456 1490 3457 2030 3457 1978 3457 1978 3458 2030 3458 1973 3458 1978 3459 1973 3459 1972 3459 1490 3460 1983 3460 1487 3460 1487 3461 1983 3461 1496 3461 1983 3462 1982 3462 1496 3462 1496 3463 1982 3463 1981 3463 1496 3464 1981 3464 1502 3464 1502 3465 1981 3465 1984 3465 1502 3466 1984 3466 1500 3466 1500 3467 1984 3467 1540 3467 1500 3468 1540 3468 1497 3468 2033 3469 2007 3469 1643 3469 1643 3470 1648 3470 2033 3470 2033 3471 1648 3471 1647 3471 2033 3472 1647 3472 1646 3472 1986 3473 2034 3473 2035 3473 2035 3474 2034 3474 2033 3474 2035 3475 2033 3475 2036 3475 2036 3476 2033 3476 1646 3476 1646 3477 1598 3477 2036 3477 2036 3478 1598 3478 1597 3478 2036 3479 1597 3479 2035 3479 2035 3480 1597 3480 1649 3480 2035 3481 1649 3481 1986 3481 1986 3482 1649 3482 1651 3482 2037 3483 2038 3483 2039 3483 2039 3484 2038 3484 2040 3484 1985 3485 2037 3485 1986 3485 1986 3486 2037 3486 2039 3486 1986 3487 2039 3487 2041 3487 2041 3488 2039 3488 2040 3488 2040 3489 1568 3489 2042 3489 2042 3490 1568 3490 1570 3490 2043 3491 1572 3491 1987 3491 1987 3492 1572 3492 1574 3492 1987 3493 1574 3493 1577 3493 2040 3494 2038 3494 1568 3494 1568 769 2038 769 2037 769 1568 769 2037 769 1561 769 1561 3495 2037 3495 1985 3495 1561 3496 1985 3496 1562 3496 2043 3497 2044 3497 1572 3497 1572 3498 2044 3498 2045 3498 1572 3499 2045 3499 1570 3499 1570 3500 2045 3500 2046 3500 1570 3501 2046 3501 2042 3501 2044 3502 2043 3502 2047 3502 2047 3503 2043 3503 1987 3503 2047 3504 1987 3504 1988 3504 1677 3505 1989 3505 2048 3505 2049 3506 1607 3506 2050 3506 2050 3507 1607 3507 1604 3507 2050 3508 1604 3508 1603 3508 1608 3509 1607 3509 1988 3509 1988 3510 1607 3510 2049 3510 1988 3511 2049 3511 2051 3511 2051 3512 2049 3512 2050 3512 2051 3513 2050 3513 2052 3513 2052 3514 2050 3514 1603 3514 2052 3515 1603 3515 2048 3515 2048 3516 1603 3516 1611 3516 2048 3517 1611 3517 1677 3517 1613 3518 1612 3518 1989 3518 1989 3519 1612 3519 1493 3519 1989 3520 1493 3520 1494 3520 1512 3521 1543 3521 1514 3521 1514 3522 1543 3522 2000 3522 2001 3523 1483 3523 2002 3523 2002 3524 1483 3524 1507 3524 2002 3525 1507 3525 2004 3525 2004 3526 1507 3526 1508 3526 2004 3527 1508 3527 2005 3527 2005 3528 1508 3528 1510 3528 2005 3529 1510 3529 2000 3529 2000 3530 1510 3530 1516 3530 2000 3531 1516 3531 1514 3531 1991 3532 1996 3532 2003 3532 2003 3533 1996 3533 2001 3533 1996 3534 2008 3534 2001 3534 2001 3535 2008 3535 2011 3535 2001 3536 2011 3536 2010 3536 2010 3537 2015 3537 2001 3537 2001 3538 2015 3538 2013 3538 2013 3539 2018 3539 2001 3539 2001 3540 2018 3540 2017 3540 2001 3541 2017 3541 2016 3541 1872 3542 1742 3542 2003 3542 2003 3543 1742 3543 1992 3543 2003 3544 1992 3544 1991 3544 2016 3545 1678 3545 1644 3545 1644 3546 2006 3546 2016 3546 2016 3547 2006 3547 2007 3547 2016 3548 2007 3548 2053 3548 2053 3549 2007 3549 2033 3549 2054 3550 2055 3550 2056 3550 2034 3551 1986 3551 2054 3551 2054 3552 1986 3552 2041 3552 2054 3553 2041 3553 2040 3553 2054 3554 2056 3554 2034 3554 2034 3555 2056 3555 2057 3555 2034 3556 2057 3556 2033 3556 2033 3557 2057 3557 1520 3557 2033 3558 1520 3558 2053 3558 2058 3559 2054 3559 2040 3559 2040 3560 2042 3560 2058 3560 2058 3561 2042 3561 2046 3561 2058 3562 2046 3562 2059 3562 2059 3563 2046 3563 2045 3563 2059 3564 2045 3564 2060 3564 2060 3565 2045 3565 2044 3565 2060 3566 2044 3566 2061 3566 1494 3567 1492 3567 2062 3567 1989 3568 1494 3568 2048 3568 2048 3569 1494 3569 2062 3569 2048 3570 2062 3570 2052 3570 2052 3571 2062 3571 2063 3571 2052 3572 2063 3572 2051 3572 2051 3573 2063 3573 2064 3573 2051 3574 2064 3574 2061 3574 2044 3575 2047 3575 2061 3575 2061 3576 2047 3576 1988 3576 2061 3577 1988 3577 2051 3577 2053 3578 1520 3578 2016 3578 2016 498 1520 498 1483 498 2016 498 1483 498 2001 498 459 3579 458 3579 2065 3579 2065 3580 458 3580 2066 3580 2065 3581 2066 3581 2067 3581 2068 3582 2069 3582 2070 3582 2070 3583 2069 3583 2071 3583 2070 3584 2071 3584 2072 3584 2072 3585 2071 3585 2067 3585 2072 3586 2067 3586 2073 3586 2073 3587 2067 3587 2066 3587 2074 3588 2075 3588 2076 3588 2076 3589 2075 3589 2077 3589 2068 3590 2070 3590 2074 3590 2074 3591 2070 3591 2078 3591 2074 3592 2078 3592 2075 3592 1487 3593 2079 3593 1492 3593 1492 3594 2079 3594 2080 3594 1492 3595 2080 3595 2081 3595 2077 3596 2075 3596 2081 3596 2081 3597 2075 3597 2082 3597 2081 3598 2082 3598 1492 3598 2083 3599 2070 3599 2084 3599 2084 3600 2070 3600 2072 3600 2084 3601 2072 3601 2085 3601 2085 3602 2072 3602 2073 3602 2085 3603 2073 3603 466 3603 466 3604 2073 3604 2066 3604 466 3605 2066 3605 467 3605 467 3606 2066 3606 458 3606 2082 3607 2075 3607 2083 3607 2083 3608 2075 3608 2078 3608 2083 3609 2078 3609 2070 3609 2083 3610 2086 3610 2082 3610 2082 3611 2086 3611 2062 3611 2082 3612 2062 3612 1492 3612 2087 3613 2064 3613 2063 3613 464 3614 474 3614 2088 3614 2088 3615 474 3615 2089 3615 2088 3616 2089 3616 2090 3616 2090 3617 2089 3617 2091 3617 2090 3618 2091 3618 2092 3618 2092 3619 2091 3619 2087 3619 2092 3620 2087 3620 2093 3620 2093 3621 2087 3621 2063 3621 466 3622 464 3622 2085 3622 2085 3623 464 3623 2088 3623 2085 3624 2088 3624 2084 3624 2084 3625 2088 3625 2090 3625 2084 3626 2090 3626 2083 3626 2083 3627 2090 3627 2092 3627 2083 3628 2092 3628 2086 3628 2086 3629 2092 3629 2093 3629 2086 3630 2093 3630 2062 3630 2062 3631 2093 3631 2063 3631 471 769 469 769 2094 769 2064 769 2087 769 473 769 2087 769 2091 769 473 769 473 3632 2091 3632 2089 3632 473 769 2089 769 474 769 471 769 2094 769 473 769 2094 769 2095 769 473 769 473 769 2095 769 2096 769 473 3633 2096 3633 2055 3633 2054 3634 2058 3634 2055 3634 2055 3635 2058 3635 2059 3635 2055 769 2059 769 473 769 473 3636 2059 3636 2060 3636 473 3637 2060 3637 2064 3637 2064 3638 2060 3638 2061 3638 469 3639 2097 3639 2098 3639 478 3640 477 3640 1531 3640 1520 3641 2057 3641 2099 3641 2100 3642 1521 3642 2101 3642 2101 3643 1521 3643 1523 3643 2101 3644 1523 3644 2102 3644 2102 3645 1523 3645 1525 3645 2102 3646 1525 3646 2099 3646 2099 3647 1525 3647 1528 3647 2099 3648 1528 3648 1520 3648 1531 3649 1533 3649 2100 3649 2100 3650 1533 3650 1535 3650 2100 3651 1535 3651 1521 3651 484 3652 483 3652 2100 3652 2100 3653 483 3653 482 3653 2100 3654 482 3654 1531 3654 1531 3655 482 3655 480 3655 1531 3656 480 3656 478 3656 469 3657 2098 3657 2094 3657 2094 3658 2098 3658 2103 3658 2094 3659 2103 3659 2095 3659 2095 3660 2103 3660 2104 3660 2095 3661 2104 3661 2096 3661 2096 3662 2104 3662 2056 3662 2096 3663 2056 3663 2055 3663 469 3664 484 3664 2097 3664 2097 3665 484 3665 2100 3665 2097 3666 2100 3666 2098 3666 2098 3667 2100 3667 2101 3667 2098 3668 2101 3668 2103 3668 2103 3669 2101 3669 2102 3669 2103 3670 2102 3670 2104 3670 2104 3671 2102 3671 2099 3671 2104 3672 2099 3672 2056 3672 2056 3673 2099 3673 2057 3673 1558 3674 1585 3674 1582 3674 1558 3675 1582 3675 1550 3675 1550 3676 1582 3676 1579 3676 1550 3677 1579 3677 1551 3677 1551 3678 1579 3678 1578 3678 1551 3679 1578 3679 1557 3679 1557 3680 1578 3680 1573 3680 1557 3681 1573 3681 1556 3681 1556 3682 1573 3682 1571 3682 1556 3683 1571 3683 1554 3683 1554 3684 1571 3684 1569 3684 1554 3685 1569 3685 1555 3685 1555 3686 1569 3686 1567 3686 1555 3687 1567 3687 1549 3687 1549 3688 1567 3688 1566 3688 1549 3689 1566 3689 1552 3689 1552 3690 1566 3690 1563 3690 1552 3691 1563 3691 1553 3691 1553 3692 1563 3692 1591 3692 1553 3693 1591 3693 1560 3693 1560 3694 1591 3694 1588 3694 1560 3695 1588 3695 1559 3695 1559 3696 1588 3696 1585 3696 1559 3697 1585 3697 1558 3697 1488 3698 1489 3698 1504 3698 1488 3699 1504 3699 2105 3699 1499 3700 1498 3700 1547 3700 1504 3701 1503 3701 2105 3701 2105 3702 1503 3702 1501 3702 2105 3703 1501 3703 2106 3703 2106 3704 1501 3704 1499 3704 2106 3705 1499 3705 2107 3705 2107 3706 1499 3706 1547 3706 1486 3707 1488 3707 2105 3707 2108 3708 2109 3708 2110 3708 2110 3709 2109 3709 1486 3709 1486 3710 2105 3710 2110 3710 2110 3711 2105 3711 2106 3711 2110 3712 2106 3712 2111 3712 2111 3713 2106 3713 2107 3713 2111 3714 2107 3714 2112 3714 2112 3715 2107 3715 2113 3715 2113 3716 2107 3716 1547 3716 2113 3717 1547 3717 2114 3717 1546 3718 1511 3718 1513 3718 2115 3719 2116 3719 1518 3719 1518 3720 1509 3720 2115 3720 2115 3721 1509 3721 1506 3721 2115 3722 1506 3722 1484 3722 1484 3723 1506 3723 1505 3723 1484 3724 1505 3724 1482 3724 1546 3725 1513 3725 2117 3725 2117 3726 1513 3726 1515 3726 2117 3727 1515 3727 2116 3727 2116 3728 1515 3728 1517 3728 2116 3729 1517 3729 1518 3729 2118 3730 1546 3730 2117 3730 1484 3731 1485 3731 2119 3731 2119 3732 1485 3732 2120 3732 2119 3733 2120 3733 2121 3733 2118 3734 2117 3734 2122 3734 2122 3735 2117 3735 2116 3735 2122 3736 2116 3736 2123 3736 1484 3737 2119 3737 2115 3737 2115 3738 2119 3738 2124 3738 2115 3739 2124 3739 2116 3739 2116 3740 2124 3740 2125 3740 2116 3741 2125 3741 2123 3741 2126 3742 1486 3742 2127 3742 2127 3743 1486 3743 2128 3743 2127 3744 2128 3744 2129 3744 2126 3745 2130 3745 1486 3745 1486 3746 2130 3746 2131 3746 1486 3747 2131 3747 1487 3747 343 3748 342 3748 2132 3748 2132 3749 342 3749 2133 3749 2133 3750 2134 3750 2132 3750 2132 3751 2134 3751 2135 3751 2132 3752 2135 3752 2128 3752 2128 3753 2135 3753 2136 3753 2128 3754 2136 3754 2129 3754 339 3755 344 3755 2137 3755 2137 3756 344 3756 2138 3756 2137 3757 2138 3757 2139 3757 2139 3758 2138 3758 2140 3758 2140 3759 2138 3759 2141 3759 2140 3760 2141 3760 2142 3760 2109 3761 2108 3761 2141 3761 2141 3762 2108 3762 2143 3762 2141 3763 2143 3763 2142 3763 1486 3764 2109 3764 2128 3764 2128 3765 2109 3765 2141 3765 2128 3766 2141 3766 2132 3766 2132 3767 2141 3767 2138 3767 2132 3768 2138 3768 343 3768 343 3769 2138 3769 344 3769 350 3770 349 3770 2144 3770 2144 3771 349 3771 2145 3771 2144 3772 2145 3772 2146 3772 2146 3773 2145 3773 2147 3773 2147 3774 2145 3774 2148 3774 2148 3775 2145 3775 2149 3775 2148 3776 2149 3776 2150 3776 1485 3777 1483 3777 2151 3777 2151 3778 2152 3778 1485 3778 1485 3779 2152 3779 2153 3779 1485 3780 2153 3780 2149 3780 2149 3781 2153 3781 2154 3781 2149 3782 2154 3782 2150 3782 2121 3783 2120 3783 2155 3783 2155 3784 2120 3784 2156 3784 2155 3785 2156 3785 2157 3785 2157 3786 2156 3786 2158 3786 2158 3787 2156 3787 2159 3787 2158 3788 2159 3788 2160 3788 348 3789 347 3789 2159 3789 2159 3790 347 3790 2161 3790 2159 3791 2161 3791 2160 3791 349 3792 348 3792 2145 3792 2145 3793 348 3793 2159 3793 2145 3794 2159 3794 2149 3794 2149 3795 2159 3795 2156 3795 2149 3796 2156 3796 1485 3796 1485 3797 2156 3797 2120 3797 378 3798 1481 3798 2162 3798 378 3799 2162 3799 376 3799 376 3800 2162 3800 2163 3800 376 3800 2163 3800 377 3800 377 3801 2163 3801 1548 3801 377 3801 1548 3801 379 3801 1478 3802 338 3802 333 3802 1478 3803 333 3803 2164 3803 2164 3804 333 3804 332 3804 2164 3805 332 3805 2165 3805 2165 3806 332 3806 331 3806 2165 3807 331 3807 1495 3807 2126 3808 2166 3808 2130 3808 2130 3809 2166 3809 2131 3809 2127 3810 2167 3810 2126 3810 2126 3811 2167 3811 2168 3811 2126 3812 2168 3812 2166 3812 2127 3813 2129 3813 2167 3813 2167 3814 2129 3814 2136 3814 2167 3815 2136 3815 2169 3815 2169 3816 2136 3816 2135 3816 2169 3817 2135 3817 2170 3817 2170 3818 2135 3818 2134 3818 2170 3819 2134 3819 2171 3819 2171 3820 2134 3820 2133 3820 2171 3821 2133 3821 2172 3821 2172 3822 2133 3822 342 3822 2172 3823 342 3823 2173 3823 1487 3824 2131 3824 2079 3824 2079 3825 2131 3825 2166 3825 2079 3826 2166 3826 2174 3826 2174 3827 2166 3827 2168 3827 2174 3828 2168 3828 2175 3828 2175 3829 2168 3829 2167 3829 2175 3830 2167 3830 2176 3830 2176 3831 2167 3831 2169 3831 2176 3832 2169 3832 2177 3832 2177 3833 2169 3833 2170 3833 2177 3834 2170 3834 2178 3834 2178 3835 2170 3835 2171 3835 2178 3836 2171 3836 2179 3836 2179 3837 2171 3837 2172 3837 2179 3838 2172 3838 2180 3838 2180 3839 2172 3839 2173 3839 2180 3840 2173 3840 2181 3840 2079 3841 2174 3841 2080 3841 2080 3842 2174 3842 2175 3842 2080 3843 2175 3843 2081 3843 2081 3844 2175 3844 2176 3844 2081 3845 2176 3845 2077 3845 2077 3846 2176 3846 2177 3846 2077 3847 2177 3847 2076 3847 2076 3848 2177 3848 2178 3848 2076 3849 2178 3849 2074 3849 2074 3850 2178 3850 2179 3850 2074 3851 2179 3851 2068 3851 2068 3852 2179 3852 2180 3852 2068 3853 2180 3853 2069 3853 2069 3854 2180 3854 2181 3854 2069 3855 2181 3855 2071 3855 340 3856 2182 3856 2183 3856 342 3857 341 3857 2173 3857 2173 3858 341 3858 2184 3858 2173 3859 2184 3859 2181 3859 2181 3860 2184 3860 2185 3860 2181 3861 2185 3861 2071 3861 2071 3862 2185 3862 2067 3862 341 3863 340 3863 2184 3863 2184 3864 340 3864 2183 3864 2184 3865 2183 3865 2185 3865 2185 3866 2183 3866 2186 3866 2185 3867 2186 3867 2067 3867 2067 3868 2186 3868 2065 3868 459 3869 2065 3869 2187 3869 2187 3870 2065 3870 2186 3870 2187 3871 2186 3871 2188 3871 2188 3872 2186 3872 2183 3872 2188 3873 2183 3873 2189 3873 2189 3874 2183 3874 2182 3874 2189 3875 2182 3875 1452 3875 421 3876 2190 3876 2191 3876 1456 3877 1458 3877 2192 3877 1452 3878 1454 3878 2189 3878 2189 3879 1454 3879 1456 3879 1456 3880 2192 3880 2189 3880 2189 3881 2192 3881 2193 3881 2189 3882 2193 3882 2188 3882 2188 3883 2193 3883 2194 3883 2188 3884 2194 3884 2187 3884 2187 3885 2194 3885 460 3885 2187 3886 460 3886 459 3886 417 3887 490 3887 415 3887 415 3888 490 3888 2190 3888 415 3889 2190 3889 420 3889 420 3890 2190 3890 421 3890 432 3891 430 3891 2195 3891 2195 3892 430 3892 429 3892 2195 3893 429 3893 2191 3893 2191 3894 429 3894 425 3894 2191 3895 425 3895 421 3895 434 3896 432 3896 381 3896 381 3897 432 3897 2195 3897 381 3898 2195 3898 380 3898 380 3899 2195 3899 1480 3899 1458 3900 1480 3900 2192 3900 2192 3901 1480 3901 2195 3901 2192 3902 2195 3902 2193 3902 2193 3903 2195 3903 2191 3903 2193 3904 2191 3904 2194 3904 2194 3905 2191 3905 2190 3905 2194 3906 2190 3906 460 3906 460 3907 2190 3907 490 3907 2151 3908 2196 3908 2152 3908 2152 3909 2196 3909 2197 3909 2152 3910 2197 3910 2153 3910 1519 3911 1530 3911 2198 3911 2198 3912 1530 3912 1529 3912 2198 3913 1529 3913 2199 3913 2199 3914 1529 3914 1527 3914 2199 3915 1527 3915 2200 3915 2200 3916 1527 3916 1526 3916 2200 3917 1526 3917 2201 3917 2201 3918 1526 3918 1524 3918 2201 3919 1524 3919 2202 3919 2202 3920 1524 3920 1522 3920 2202 3921 1522 3921 2203 3921 2203 3922 1522 3922 1537 3922 2203 3923 1537 3923 2204 3923 2204 3924 1537 3924 1536 3924 2204 3925 1536 3925 2205 3925 1483 3926 1519 3926 2151 3926 2151 3927 1519 3927 2198 3927 2151 3928 2198 3928 2196 3928 2196 3929 2198 3929 2199 3929 2196 3930 2199 3930 2197 3930 2197 3931 2199 3931 2200 3931 2197 3932 2200 3932 2206 3932 2206 3933 2200 3933 2201 3933 2206 3934 2201 3934 2207 3934 2207 3935 2201 3935 2202 3935 2207 3936 2202 3936 2208 3936 2208 3937 2202 3937 2203 3937 2208 3938 2203 3938 2209 3938 2209 3939 2203 3939 2204 3939 2209 3940 2204 3940 2210 3940 2210 3941 2204 3941 2205 3941 2210 3942 2205 3942 2211 3942 2153 3943 2197 3943 2154 3943 2154 3944 2197 3944 2206 3944 2154 3945 2206 3945 2150 3945 2150 3946 2206 3946 2207 3946 2150 3947 2207 3947 2148 3947 2148 3948 2207 3948 2208 3948 2148 3949 2208 3949 2147 3949 2147 3950 2208 3950 2209 3950 2147 3951 2209 3951 2146 3951 2146 3952 2209 3952 2210 3952 2146 3953 2210 3953 2144 3953 2144 3954 2210 3954 2211 3954 2144 3955 2211 3955 350 3955 2211 3956 2205 3956 2212 3956 2205 3957 1536 3957 1534 3957 2213 3958 2214 3958 2215 3958 2216 3959 2213 3959 2217 3959 2217 3960 2213 3960 2215 3960 2217 3961 2215 3961 2218 3961 2218 3962 2215 3962 346 3962 346 3963 345 3963 2218 3963 2218 3964 345 3964 350 3964 2218 3965 350 3965 2211 3965 2205 3966 1534 3966 2212 3966 2212 3967 1534 3967 1532 3967 2212 3968 1532 3968 2219 3968 2219 3969 1532 3969 488 3969 2219 3970 488 3970 2220 3970 2211 3971 2212 3971 2218 3971 2218 3972 2212 3972 2219 3972 2218 3973 2219 3973 2217 3973 2217 3974 2219 3974 2220 3974 2217 3975 2220 3975 2216 3975 1470 3976 2221 3976 2222 3976 2222 3977 2221 3977 2223 3977 337 3978 1471 3978 335 3978 335 3979 1471 3979 2224 3979 335 3980 2224 3980 440 3980 440 3981 2224 3981 441 3981 2225 3982 445 3982 2226 3982 2226 3983 445 3983 447 3983 2226 3984 447 3984 2224 3984 2224 3985 447 3985 448 3985 2224 3986 448 3986 441 3986 486 3987 456 3987 2225 3987 2225 3988 456 3988 454 3988 454 3989 452 3989 2225 3989 2225 3990 452 3990 450 3990 2225 3991 450 3991 445 3991 2220 3992 488 3992 487 3992 487 3993 2227 3993 2220 3993 2220 3994 2227 3994 2228 3994 2220 3995 2228 3995 2216 3995 2216 3996 2228 3996 2222 3996 2216 3997 2222 3997 2213 3997 2213 3998 2222 3998 2223 3998 2213 3999 2223 3999 2214 3999 487 4000 486 4000 2227 4000 2227 4001 486 4001 2225 4001 2227 4002 2225 4002 2228 4002 2228 4003 2225 4003 2226 4003 2228 4004 2226 4004 2222 4004 2222 4005 2226 4005 2224 4005 2222 4006 2224 4006 1470 4006 1470 4007 2224 4007 1471 4007 1473 4008 2229 4008 1474 4008 1474 4009 2229 4009 2230 4009 1474 4010 2230 4010 1475 4010 1475 4011 2230 4011 2231 4011 1475 4012 2231 4012 1476 4012 1476 4013 2231 4013 2232 4013 1476 4014 2232 4014 1477 4014 1477 4015 2232 4015 2233 4015 1477 4016 2233 4016 1469 4016 1469 4017 2233 4017 2234 4017 1469 4018 2234 4018 1470 4018 1470 4019 2234 4019 2235 4019 1470 4020 2235 4020 2221 4020 2221 4021 2235 4021 2236 4021 2221 4022 2236 4022 2223 4022 2223 4023 2236 4023 2237 4023 2223 4024 2237 4024 2214 4024 1435 4025 1433 4025 2238 4025 2238 4026 1433 4026 1430 4026 2238 4027 1430 4027 1427 4027 1441 629 1439 629 2238 629 2238 629 1439 629 1437 629 2238 629 1437 629 1435 629 1415 4028 1409 4028 2238 4028 2238 4027 1409 4027 1411 4027 2238 4029 1411 4029 1441 4029 1427 629 1423 629 2238 629 2238 629 1423 629 1417 629 2238 629 1417 629 1415 629 2114 4030 1547 4030 2239 4030 2239 4031 1547 4031 1546 4031 2239 4032 1546 4032 2118 4032 323 4033 326 4033 2240 4033 2241 4034 322 4034 323 4034 2242 4035 2243 4035 2244 4035 2244 4036 2243 4036 2245 4036 2244 4037 2245 4037 2246 4037 2245 4038 2247 4038 2246 4038 2246 4039 2247 4039 2248 4039 2246 4040 2248 4040 2249 4040 2249 4041 2248 4041 2250 4041 2250 4042 2248 4042 2240 4042 2250 4043 2240 4043 2251 4043 2251 4044 2240 4044 326 4044 2251 4045 326 4045 319 4045 2248 4046 2252 4046 2240 4046 2240 4047 2252 4047 2253 4047 2240 4048 2253 4048 323 4048 323 4049 2253 4049 2254 4049 323 4050 2254 4050 2241 4050 2255 4051 2256 4051 2257 4051 2244 4052 2246 4052 2258 4052 2258 4053 2246 4053 2249 4053 2258 4054 2249 4054 2259 4054 2259 4055 2249 4055 2250 4055 2259 4056 2250 4056 2260 4056 2260 4057 2250 4057 2251 4057 2260 4058 2251 4058 2261 4058 2256 4059 2255 4059 2258 4059 2258 4060 2255 4060 2242 4060 2258 4061 2242 4061 2244 4061 2262 4062 2263 4062 2257 4062 2257 4063 2263 4063 2264 4063 2257 4064 2264 4064 2255 4064 2257 4065 2265 4065 2262 4065 2262 4066 2265 4066 2266 4066 2262 4067 2266 4067 2267 4067 2267 4068 2266 4068 2268 4068 2267 4069 2268 4069 2269 4069 2269 4070 2268 4070 2270 4070 2269 4071 2270 4071 2271 4071 2272 4072 1216 4072 1106 4072 2273 4073 1217 4073 1216 4073 2251 4074 319 4074 2261 4074 2261 4075 319 4075 1215 4075 2261 4076 1215 4076 1217 4076 1216 4077 2272 4077 2273 4077 2273 4078 2272 4078 2274 4078 2273 4079 2274 4079 2275 4079 2275 4080 2274 4080 2276 4080 2275 4081 2276 4081 2277 4081 2277 4082 2276 4082 2278 4082 2277 4083 2278 4083 2279 4083 2279 4084 2278 4084 2280 4084 2279 4085 2280 4085 2281 4085 2281 4086 2280 4086 2282 4086 2281 4087 2282 4087 2283 4087 2283 4088 2282 4088 2284 4088 2283 4089 2284 4089 2285 4089 2285 4090 2284 4090 2286 4090 2285 4091 2286 4091 2287 4091 2287 4092 2286 4092 2288 4092 2287 4093 2288 4093 2289 4093 1106 4094 1122 4094 2272 4094 2272 4095 1122 4095 1121 4095 2272 4096 1121 4096 2274 4096 2274 4097 1121 4097 1120 4097 2274 4098 1120 4098 2276 4098 2276 4099 1120 4099 1119 4099 2276 4100 1119 4100 2278 4100 2278 4101 1119 4101 1115 4101 2278 4102 1115 4102 2280 4102 2280 4103 1115 4103 1114 4103 2280 4104 1114 4104 2282 4104 2282 4105 1114 4105 1128 4105 2282 4106 1128 4106 2284 4106 2284 4107 1128 4107 1127 4107 2284 4108 1127 4108 2286 4108 2286 4109 1127 4109 1126 4109 2286 4110 1126 4110 2288 4110 2288 4111 1126 4111 1116 4111 1116 4112 2290 4112 2288 4112 2288 4113 2290 4113 2291 4113 2288 4114 2291 4114 2289 4114 2289 4115 2291 4115 2292 4115 2289 4116 2292 4116 2293 4116 1217 4117 2273 4117 2261 4117 2261 4118 2273 4118 2275 4118 2261 4119 2275 4119 2260 4119 2260 4120 2275 4120 2277 4120 2260 4121 2277 4121 2259 4121 2259 4122 2277 4122 2279 4122 2259 4123 2279 4123 2258 4123 2258 4124 2279 4124 2281 4124 2258 4125 2281 4125 2256 4125 2256 4126 2281 4126 2283 4126 2256 4127 2283 4127 2257 4127 2257 4128 2283 4128 2285 4128 2257 4129 2285 4129 2265 4129 2265 4130 2285 4130 2287 4130 2265 4131 2287 4131 2266 4131 2266 4132 2287 4132 2289 4132 2266 4133 2289 4133 2268 4133 2268 4134 2289 4134 2293 4134 2268 4135 2293 4135 2270 4135 2294 4136 2295 4136 2296 4136 2296 4137 2295 4137 2297 4137 2296 4138 2297 4138 2298 4138 2296 4139 2299 4139 2300 4139 2300 4140 2301 4140 2296 4140 2296 4141 2301 4141 2302 4141 2296 4142 2302 4142 2294 4142 2303 4143 2304 4143 2305 4143 2304 4144 2303 4144 2306 4144 2306 4145 2303 4145 2307 4145 2306 4146 2307 4146 2308 4146 2309 4147 2310 4147 2311 4147 2311 4148 2310 4148 2312 4148 2308 4149 2307 4149 2310 4149 2310 4150 2307 4150 2313 4150 2310 4151 2313 4151 2312 4151 2314 4152 2315 4152 2316 4152 2316 4153 2315 4153 2317 4153 2316 4154 2317 4154 2305 4154 2305 4155 2317 4155 2318 4155 2305 4156 2318 4156 2303 4156 2303 4157 2318 4157 2299 4157 2303 4158 2299 4158 2307 4158 2307 4159 2299 4159 2296 4159 2307 4160 2296 4160 2313 4160 2313 4161 2296 4161 2298 4161 245 4162 2319 4162 2320 4162 2320 4163 2319 4163 2321 4163 2320 4164 2321 4164 2322 4164 2322 4165 2321 4165 2323 4165 2322 4166 2323 4166 2324 4166 2325 4167 2326 4167 2327 4167 2327 4168 2326 4168 2328 4168 2327 4169 2328 4169 2323 4169 2323 4170 2328 4170 2329 4170 2323 4171 2329 4171 2324 4171 244 4172 242 4172 2330 4172 2330 4173 242 4173 241 4173 2330 4174 241 4174 2331 4174 2331 4175 241 4175 240 4175 2331 4176 240 4176 2332 4176 2332 4177 240 4177 239 4177 2332 4178 239 4178 2333 4178 2333 4179 239 4179 220 4179 2333 4180 220 4180 198 4180 198 4181 2327 4181 2333 4181 2333 4182 2327 4182 2323 4182 2333 4183 2323 4183 2332 4183 2332 4184 2323 4184 2321 4184 2332 4185 2321 4185 2331 4185 2331 4186 2321 4186 2319 4186 2331 4187 2319 4187 2330 4187 2330 4188 2319 4188 245 4188 2330 4189 245 4189 244 4189 1 4190 2325 4190 199 4190 199 4191 2325 4191 2327 4191 199 4192 2327 4192 197 4192 197 4193 2327 4193 198 4193 2325 4194 2334 4194 2326 4194 2335 4195 21 4195 19 4195 2336 4196 2337 4196 2338 4196 2339 4197 2340 4197 2341 4197 2339 4198 237 4198 245 4198 245 4199 2320 4199 2339 4199 2339 4200 2320 4200 2322 4200 2339 4201 2322 4201 2340 4201 2340 4202 2322 4202 2324 4202 2340 4203 2324 4203 2341 4203 2341 4204 2324 4204 2329 4204 2341 4205 2329 4205 2342 4205 2343 4206 2344 4206 2345 4206 2345 4207 2344 4207 2346 4207 2345 4208 2346 4208 2342 4208 2342 4209 2346 4209 2347 4209 2342 4210 2347 4210 2341 4210 2348 4211 2338 4211 2349 4211 2349 4212 2338 4212 2337 4212 2349 4213 2337 4213 2350 4213 2348 4214 2349 4214 2351 4214 2351 4215 2349 4215 2352 4215 2351 4216 2352 4216 2335 4216 2325 4217 1 4217 0 4217 2329 4218 2328 4218 2342 4218 2342 4219 2328 4219 2326 4219 2342 4220 2326 4220 2345 4220 2345 4221 2326 4221 2334 4221 2345 4222 2334 4222 2343 4222 21 4223 2335 4223 23 4223 23 4224 2335 4224 2352 4224 23 4225 2352 4225 24 4225 24 4226 2352 4226 2349 4226 24 4227 2349 4227 0 4227 0 4228 2349 4228 2350 4228 0 4229 2350 4229 2325 4229 2325 4230 2350 4230 2337 4230 2325 4231 2337 4231 2334 4231 2334 4232 2337 4232 2336 4232 2334 4233 2336 4233 2343 4233 234 4234 233 4234 2353 4234 234 4235 2353 4235 2354 4235 360 4236 359 4236 2355 4236 2355 4237 359 4237 2354 4237 2355 4238 2354 4238 2356 4238 2356 4239 2354 4239 2353 4239 2357 4240 2358 4240 2242 4240 2242 4241 2255 4241 2357 4241 2357 4242 2255 4242 2264 4242 2357 4243 2264 4243 2359 4243 2359 4244 2264 4244 2263 4244 2359 4245 2263 4245 2360 4245 2360 4246 2263 4246 2262 4246 2360 4247 2262 4247 2361 4247 2361 4248 2262 4248 2267 4248 2361 4249 2267 4249 2362 4249 2362 4250 2267 4250 2269 4250 2362 4251 2269 4251 2363 4251 2363 4252 2269 4252 2271 4252 2363 4253 2271 4253 2364 4253 2346 4254 2344 4254 2365 4254 2366 4255 2351 4255 1110 4255 1110 4256 2351 4256 2335 4256 1110 4257 2335 4257 19 4257 2336 4258 2338 4258 2366 4258 2366 4259 2338 4259 2348 4259 2366 4260 2348 4260 2351 4260 2365 4261 2344 4261 2366 4261 2366 4262 2344 4262 2343 4262 2366 4263 2343 4263 2336 4263 2367 4264 235 4264 237 4264 237 4265 2339 4265 2367 4265 2367 4266 2339 4266 2341 4266 2367 4267 2341 4267 2365 4267 2365 4268 2341 4268 2347 4268 2365 4269 2347 4269 2346 4269 2366 4270 1110 4270 1109 4270 2368 4271 233 4271 235 4271 1109 4272 2369 4272 2366 4272 2366 4273 2369 4273 2370 4273 2366 4274 2370 4274 2365 4274 2365 4275 2370 4275 2368 4275 2365 4276 2368 4276 2367 4276 2367 4277 2368 4277 235 4277 2371 4278 1118 4278 1111 4278 2372 4279 2368 4279 2370 4279 2353 4280 233 4280 2368 4280 2368 4281 2372 4281 2353 4281 2353 4282 2372 4282 2373 4282 2353 4283 2373 4283 2356 4283 2356 4284 2373 4284 2374 4284 2356 4285 2374 4285 2355 4285 360 4286 2355 4286 1352 4286 1352 4287 2355 4287 2374 4287 1352 4288 2374 4288 1353 4288 1353 4289 2375 4289 1354 4289 1354 4290 2375 4290 2376 4290 1111 4291 1357 4291 2371 4291 2371 4292 1357 4292 1355 4292 2371 4293 1355 4293 2376 4293 2376 4294 1355 4294 1356 4294 2376 4295 1356 4295 1354 4295 1108 4296 1117 4296 2377 4296 2377 4297 1117 4297 2378 4297 2377 4298 2378 4298 2379 4298 2379 4299 2378 4299 2380 4299 2379 4300 2380 4300 2381 4300 2381 4301 2380 4301 2382 4301 1117 4302 1118 4302 2378 4302 2378 4303 1118 4303 2371 4303 2378 4304 2371 4304 2380 4304 2380 4305 2371 4305 2376 4305 2380 4306 2376 4306 2382 4306 2382 4307 2376 4307 2375 4307 1353 4308 2374 4308 2375 4308 2375 4309 2374 4309 2373 4309 2375 4310 2373 4310 2382 4310 2382 4311 2373 4311 2372 4311 2382 4312 2372 4312 2381 4312 2381 4313 2372 4313 2370 4313 2381 4314 2370 4314 2379 4314 2379 4315 2370 4315 2369 4315 2379 4316 2369 4316 2377 4316 2377 4317 2369 4317 1109 4317 2377 4318 1109 4318 1108 4318 2383 4319 2384 4319 2385 4319 2385 498 2384 498 2386 498 2385 4320 2386 4320 2387 4320 2388 4321 2389 4321 2271 4321 2390 4322 2271 4322 2385 4322 2385 498 2271 498 2391 498 2385 4323 2391 4323 2392 4323 2389 498 2393 498 2271 498 2271 4324 2393 4324 2394 4324 2271 4325 2394 4325 2364 4325 2394 498 2395 498 2364 498 2364 4326 2395 4326 2396 4326 2364 4327 2396 4327 2397 4327 2397 498 2398 498 2364 498 2364 4328 2398 4328 2399 4328 2364 4329 2399 4329 2400 4329 2400 498 2399 498 2401 498 2400 498 2401 498 2402 498 2392 4330 2403 4330 2385 4330 2385 4331 2403 4331 2404 4331 2385 4332 2404 4332 2383 4332 2390 4333 2405 4333 2271 4333 2271 498 2405 498 2406 498 2271 4334 2406 4334 2407 4334 2388 498 2271 498 2408 498 2408 4335 2271 4335 2409 4335 2408 498 2409 498 2410 498 2407 498 2411 498 2271 498 2271 4336 2411 4336 2412 4336 2271 4337 2412 4337 2409 4337 2413 4338 2414 4338 2293 4338 2293 4339 2414 4339 2415 4339 2293 4340 2415 4340 2270 4340 2270 4341 2415 4341 2416 4341 2270 4342 2416 4342 2271 4342 2271 4343 2416 4343 2417 4343 2271 4344 2417 4344 2391 4344 2418 4345 2419 4345 2292 4345 2292 4346 2419 4346 2420 4346 2292 4347 2420 4347 2293 4347 2293 4348 2420 4348 2421 4348 2293 4349 2421 4349 2413 4349 1116 4350 1113 4350 2290 4350 2290 4351 1113 4351 2422 4351 2290 4352 2422 4352 2291 4352 2291 4353 2422 4353 2423 4353 2291 4354 2423 4354 2292 4354 2292 4355 2423 4355 2424 4355 2292 4356 2424 4356 2418 4356 393 4357 392 4357 2425 4357 2426 4358 2427 4358 2428 4358 2427 4359 405 4359 2428 4359 2428 4360 405 4360 395 4360 2428 4361 395 4361 394 4361 2429 4362 2430 4362 2431 4362 2431 4363 2430 4363 2432 4363 2431 4364 2432 4364 2433 4364 2429 4365 2434 4365 2430 4365 2430 4366 2434 4366 2435 4366 2430 4367 2435 4367 2428 4367 2428 4368 2435 4368 2436 4368 2428 4369 2436 4369 2426 4369 2385 4370 2387 4370 2433 4370 2433 4371 2387 4371 2437 4371 2437 4372 2438 4372 2433 4372 2433 4373 2438 4373 2439 4373 2433 4374 2439 4374 2431 4374 2390 4375 2385 4375 2440 4375 2440 4376 2385 4376 2433 4376 2440 4377 2433 4377 2441 4377 2441 4378 2433 4378 2432 4378 2441 4379 2432 4379 2442 4379 2442 4380 2432 4380 2430 4380 2442 4381 2430 4381 2443 4381 2443 4382 2430 4382 2428 4382 2443 4383 2428 4383 410 4383 410 4384 2428 4384 394 4384 2405 4385 2390 4385 2444 4385 2444 4386 2390 4386 2440 4386 2444 4387 2440 4387 2445 4387 2445 4388 2440 4388 2441 4388 2445 4389 2441 4389 2446 4389 2446 4390 2441 4390 2442 4390 2446 4391 2442 4391 2425 4391 2425 4392 2442 4392 2443 4392 2425 4393 2443 4393 393 4393 393 4394 2443 4394 410 4394 2447 4395 2448 4395 2449 4395 2450 4396 2451 4396 2452 4396 2453 4397 2454 4397 2455 4397 2456 4398 2457 4398 2458 4398 399 4399 396 4399 2459 4399 2459 4400 396 4400 2460 4400 2456 4401 2458 4401 2453 4401 2461 4402 2295 4402 2294 4402 2294 4403 2462 4403 2461 4403 2461 4404 2462 4404 2463 4404 2461 4405 2463 4405 2464 4405 2465 4406 2312 4406 2313 4406 2448 4407 2465 4407 2466 4407 406 4408 405 4408 2467 4408 2467 4409 405 4409 2468 4409 2465 4410 2313 4410 2466 4410 2466 4411 2313 4411 2298 4411 2466 4412 2298 4412 2469 4412 2469 4413 2298 4413 2461 4413 2461 4414 2298 4414 2297 4414 2461 4415 2297 4415 2295 4415 2448 4416 2466 4416 2449 4416 2449 4417 2466 4417 2469 4417 2449 4418 2469 4418 2470 4418 2470 4419 2469 4419 2461 4419 2470 4420 2461 4420 2471 4420 2471 4421 2461 4421 2464 4421 2471 4422 2464 4422 2472 4422 2472 4423 2464 4423 2473 4423 2472 4424 2473 4424 2452 4424 2452 4425 2473 4425 2474 4425 2452 4426 2474 4426 2450 4426 2455 4427 2454 4427 2451 4427 2451 4428 2454 4428 2475 4428 2451 4429 2475 4429 2452 4429 2452 4430 2475 4430 2476 4430 2452 4431 2476 4431 2472 4431 2472 4432 2476 4432 2477 4432 2472 4433 2477 4433 2471 4433 2471 4434 2477 4434 2478 4434 2471 4435 2478 4435 2470 4435 2470 4436 2478 4436 2479 4436 2470 4437 2479 4437 2449 4437 2449 4438 2479 4438 2480 4438 2449 4439 2480 4439 2447 4439 2453 4440 2458 4440 2454 4440 2454 4441 2458 4441 2481 4441 2454 4442 2481 4442 2475 4442 2475 4443 2481 4443 2482 4443 2475 4444 2482 4444 2476 4444 2476 4445 2482 4445 2483 4445 2476 4446 2483 4446 2477 4446 2477 4447 2483 4447 2484 4447 2477 4448 2484 4448 2478 4448 2478 4449 2484 4449 2467 4449 2478 4450 2467 4450 2479 4450 2479 4451 2467 4451 2468 4451 2479 4452 2468 4452 2480 4452 406 4453 2467 4453 407 4453 407 4454 2467 4454 2484 4454 407 4455 2484 4455 404 4455 404 4456 2484 4456 2483 4456 404 4457 2483 4457 403 4457 403 4458 2483 4458 2482 4458 403 4459 2482 4459 398 4459 398 4460 2482 4460 2481 4460 398 4461 2481 4461 397 4461 397 4462 2481 4462 2458 4462 397 4463 2458 4463 396 4463 396 4464 2458 4464 2457 4464 396 4465 2457 4465 2460 4465 2459 4466 2460 4466 2485 4466 2462 4467 2294 4467 2302 4467 2451 4468 2450 4468 2486 4468 2486 4469 2450 4469 2474 4469 2474 4470 2473 4470 2486 4470 2486 4471 2473 4471 2464 4471 2486 4472 2464 4472 2463 4472 2451 4473 2487 4473 2455 4473 2455 4474 2487 4474 2485 4474 2455 4475 2485 4475 2453 4475 2460 4476 2457 4476 2485 4476 2485 4477 2457 4477 2456 4477 2485 4478 2456 4478 2453 4478 1107 4479 401 4479 402 4479 402 4480 400 4480 1107 4480 1107 4481 400 4481 399 4481 1107 4482 399 4482 2459 4482 2463 4483 2462 4483 2486 4483 2486 4484 2462 4484 2302 4484 2486 4485 2302 4485 2488 4485 2488 4486 2302 4486 2301 4486 2301 4487 2300 4487 2488 4487 2488 4488 2300 4488 2299 4488 2488 4489 2299 4489 2489 4489 2489 4490 2299 4490 2318 4490 2489 4491 2318 4491 2490 4491 2318 4492 2317 4492 2490 4492 2490 4493 2317 4493 2491 4493 2490 4494 2491 4494 2492 4494 2451 4495 2486 4495 2487 4495 2487 4496 2486 4496 2488 4496 2487 4497 2488 4497 2493 4497 2493 4498 2488 4498 2489 4498 2493 4499 2489 4499 2494 4499 2494 4500 2489 4500 2490 4500 2494 4501 2490 4501 2495 4501 2495 4502 2490 4502 2492 4502 2495 4503 2492 4503 2496 4503 2459 4504 2485 4504 1107 4504 1107 4505 2485 4505 2487 4505 1107 4506 2487 4506 1123 4506 1123 4507 2487 4507 2493 4507 1123 4508 2493 4508 1124 4508 1124 4509 2493 4509 2494 4509 1124 4510 2494 4510 1125 4510 1125 4511 2494 4511 2495 4511 1125 4512 2495 4512 1129 4512 1129 4513 2495 4513 2496 4513 1129 4514 2496 4514 1130 4514 2317 4515 2315 4515 2491 4515 2491 4516 2315 4516 2497 4516 2491 4517 2497 4517 2492 4517 1112 4518 1130 4518 2497 4518 2497 4519 1130 4519 2496 4519 2497 4520 2496 4520 2492 4520 1113 4521 1112 4521 2498 4521 2498 4522 1112 4522 2497 4522 2498 4523 2497 4523 2314 4523 2314 4524 2497 4524 2315 4524 2413 4525 2314 4525 2414 4525 2314 4526 2413 4526 2421 4526 2415 4527 2414 4527 2314 4527 2420 4528 2419 4528 2314 4528 1113 4529 2498 4529 2422 4529 2314 4530 2424 4530 2423 4530 2422 4531 2498 4531 2423 4531 2423 4532 2498 4532 2314 4532 2418 4533 2424 4533 2314 4533 2419 4534 2418 4534 2314 4534 2421 4535 2420 4535 2314 4535 2416 4536 2415 4536 2314 4536 2391 4537 2417 4537 2499 4537 2499 4538 2417 4538 2416 4538 2499 4539 2416 4539 2314 4539 2316 4540 2305 4540 2500 4540 2500 4541 2305 4541 2501 4541 2500 4542 2501 4542 2392 4542 2392 4543 2501 4543 2403 4543 2314 4544 2316 4544 2499 4544 2499 4545 2316 4545 2500 4545 2499 4546 2500 4546 2391 4546 2391 4547 2500 4547 2392 4547 2502 4548 2387 4548 2386 4548 2502 4549 2386 4549 2503 4549 2504 4550 2505 4550 2503 4550 2309 4551 2506 4551 2504 4551 2504 4552 2506 4552 2507 4552 2504 4553 2507 4553 2505 4553 2503 4554 2386 4554 2504 4554 2504 4555 2386 4555 2384 4555 2504 4556 2384 4556 2508 4556 2508 4557 2384 4557 2383 4557 2508 4558 2383 4558 2509 4558 2509 4559 2383 4559 2404 4559 2509 4560 2404 4560 2510 4560 2510 4561 2404 4561 2403 4561 2510 4562 2403 4562 2501 4562 2309 4563 2504 4563 2310 4563 2310 4564 2504 4564 2508 4564 2310 4565 2508 4565 2308 4565 2308 4566 2508 4566 2509 4566 2308 4567 2509 4567 2306 4567 2306 4568 2509 4568 2510 4568 2306 4569 2510 4569 2304 4569 2304 4570 2510 4570 2501 4570 2304 4571 2501 4571 2305 4571 2437 4572 2511 4572 2438 4572 2438 4573 2511 4573 2512 4573 2387 4574 2502 4574 2437 4574 2437 4575 2502 4575 2513 4575 2437 4576 2513 4576 2511 4576 2511 4577 2513 4577 2514 4577 2511 4578 2514 4578 2512 4578 2512 4579 2514 4579 2515 4579 2512 4580 2515 4580 2516 4580 2516 4581 2515 4581 2517 4581 2516 4582 2517 4582 2518 4582 2435 4583 2434 4583 2518 4583 2518 4584 2434 4584 2429 4584 2518 4585 2429 4585 2516 4585 2516 4586 2429 4586 2431 4586 2516 4587 2431 4587 2512 4587 2512 4588 2431 4588 2439 4588 2512 4589 2439 4589 2438 4589 2506 4590 2309 4590 2519 4590 2502 4591 2503 4591 2513 4591 2513 4592 2503 4592 2505 4592 2513 4593 2505 4593 2514 4593 2514 4594 2505 4594 2507 4594 2514 4595 2507 4595 2515 4595 2515 4596 2507 4596 2506 4596 2515 4597 2506 4597 2517 4597 2517 4598 2506 4598 2519 4598 2519 4599 2520 4599 2517 4599 2517 4600 2520 4600 2521 4600 2517 4601 2521 4601 2518 4601 2518 4602 2521 4602 2522 4602 2518 4603 2522 4603 2435 4603 2435 4604 2522 4604 2523 4604 2435 4605 2523 4605 2436 4605 2480 4606 2468 4606 2524 4606 2448 4607 2447 4607 2525 4607 2522 4608 2521 4608 2525 4608 2520 4609 2519 4609 2526 4609 2519 4610 2309 4610 2311 4610 2426 4611 2436 4611 2524 4611 2524 4612 2436 4612 2523 4612 2519 4613 2311 4613 2526 4613 2526 4614 2311 4614 2312 4614 2526 4615 2312 4615 2465 4615 2465 4616 2448 4616 2526 4616 2526 4617 2448 4617 2525 4617 2526 4618 2525 4618 2520 4618 2520 4619 2525 4619 2521 4619 2447 4620 2480 4620 2525 4620 2525 4621 2480 4621 2524 4621 2525 4622 2524 4622 2522 4622 2522 4623 2524 4623 2523 4623 2468 4624 405 4624 2524 4624 2524 4625 405 4625 2427 4625 2524 4626 2427 4626 2426 4626 2358 4627 273 4627 275 4627 2243 4628 2242 4628 2245 4628 2245 4629 2242 4629 2358 4629 2245 4630 2358 4630 2247 4630 2247 4631 2358 4631 275 4631 2254 4632 277 4632 2241 4632 2241 4633 277 4633 283 4633 2254 4634 2253 4634 277 4634 277 4635 2253 4635 2252 4635 277 4636 2252 4636 275 4636 275 4637 2252 4637 2248 4637 275 4638 2248 4638 2247 4638 359 769 355 769 2527 769 236 769 234 769 2527 769 2527 769 234 769 2354 769 2527 769 2354 769 359 769 353 528 354 528 2528 528 2528 528 354 528 390 528 2528 528 390 528 2529 528 2529 528 390 528 389 528 1479 528 2530 528 1481 528 1481 528 2530 528 2531 528 1481 528 2531 528 2162 528 2162 4639 2531 4639 2532 4639 2162 528 2532 528 2163 528 2163 528 2532 528 2533 528 2163 528 2533 528 1548 528 1548 528 2533 528 2534 528 1548 528 2534 528 386 528 386 528 2534 528 2535 528 386 528 2535 528 387 528 387 528 2535 528 2536 528 387 528 2536 528 388 528 388 528 2536 528 2537 528 388 528 2537 528 389 528 389 4640 2537 4640 2538 4640 389 528 2538 528 2529 528 69 4641 62 4641 2539 4641 2539 4642 62 4642 238 4642 2539 4643 238 4643 2540 4643 2527 4644 355 4644 351 4644 353 4645 2528 4645 351 4645 351 4646 2528 4646 2541 4646 351 4647 2541 4647 2542 4647 2542 4648 2543 4648 351 4648 351 4649 2543 4649 2544 4649 351 4650 2544 4650 2545 4650 2545 4651 2546 4651 351 4651 351 4652 2546 4652 2540 4652 351 4653 2540 4653 2527 4653 2527 4654 2540 4654 238 4654 2527 4655 238 4655 236 4655 2547 4656 2548 4656 2549 4656 2549 4657 2548 4657 2550 4657 2549 4658 2550 4658 2551 4658 2546 4659 2547 4659 2540 4659 2540 4660 2547 4660 2549 4660 2540 4661 2549 4661 2552 4661 2551 4662 2553 4662 2549 4662 2549 4663 2553 4663 2554 4663 2549 4664 2554 4664 2552 4664 2164 498 2555 498 1478 498 1478 4665 2555 4665 2556 4665 1478 498 2556 498 1472 498 1472 498 2556 498 2557 498 385 498 247 498 1495 498 1495 498 247 498 254 498 1495 4666 254 4666 2165 4666 2165 4667 254 4667 2558 4667 2165 4668 2558 4668 2164 4668 2164 4669 2558 4669 2559 4669 2164 4670 2559 4670 2555 4670 2560 4671 2530 4671 1479 4671 2560 4672 1479 4672 2561 4672 2561 4673 1479 4673 1450 4673 2561 4674 1450 4674 2562 4674 2562 4675 1450 4675 2563 4675 2563 4676 1450 4676 1449 4676 2563 4677 1449 4677 2564 4677 2564 4678 1449 4678 2565 4678 2565 4679 1449 4679 1468 4679 2565 4680 1468 4680 2566 4680 2566 4681 1468 4681 1467 4681 2566 4682 1467 4682 2567 4682 2567 4683 1467 4683 1465 4683 2567 4684 1465 4684 2568 4684 2568 4685 1465 4685 2569 4685 2569 4686 1465 4686 1463 4686 2569 4687 1463 4687 2570 4687 2570 4688 1463 4688 1461 4688 2570 4689 1461 4689 2571 4689 2571 4690 1461 4690 2572 4690 2572 4691 1461 4691 1459 4691 2572 4692 1459 4692 1457 4692 2182 4693 2573 4693 1452 4693 1452 4694 2573 4694 2574 4694 1452 4695 2574 4695 1453 4695 1453 4696 2574 4696 2575 4696 1453 4697 2575 4697 1455 4697 1455 4698 2575 4698 2576 4698 1455 4699 2576 4699 1457 4699 1457 4700 2576 4700 2577 4700 1457 4701 2577 4701 2572 4701 2578 4702 2579 4702 2580 4702 2580 4703 2579 4703 2581 4703 2580 4704 2581 4704 2582 4704 2582 4704 2581 4704 2583 4704 2583 4705 2581 4705 2584 4705 2584 4706 2581 4706 2585 4706 2584 4707 2585 4707 2586 4707 2586 4708 2585 4708 2587 4708 2581 4709 2579 4709 2585 4709 2585 4710 2579 4710 2588 4710 2585 4711 2588 4711 2587 4711 2587 4712 2588 4712 2589 4712 2590 4713 2591 4713 2592 4713 2592 4714 2591 4714 2593 4714 2592 4715 2593 4715 2594 4715 2594 4716 2593 4716 2595 4716 2596 4717 2590 4717 2597 4717 2597 4718 2590 4718 2592 4718 2597 4719 2592 4719 2598 4719 2598 4720 2592 4720 2594 4720 2599 4721 2596 4721 2600 4721 2600 4722 2596 4722 2597 4722 2600 4723 2597 4723 2601 4723 2601 4724 2597 4724 2598 4724 2602 4725 2599 4725 2603 4725 2603 4726 2599 4726 2600 4726 2603 4727 2600 4727 2604 4727 2604 4728 2600 4728 2601 4728 2605 4729 2606 4729 2607 4729 2608 4730 2609 4730 2610 4730 2610 4731 2609 4731 2605 4731 2608 4732 2611 4732 2612 4732 2612 4733 2611 4733 2613 4733 2605 4734 2607 4734 2610 4734 2610 4735 2607 4735 2614 4735 2610 4736 2614 4736 2615 4736 2615 4737 2614 4737 2602 4737 2615 4738 2602 4738 2603 4738 2608 4739 2610 4739 2611 4739 2611 4740 2610 4740 2615 4740 2611 4741 2615 4741 2616 4741 2616 4742 2615 4742 2603 4742 2616 4743 2603 4743 2604 4743 2612 4744 2613 4744 2617 4744 2618 4745 2606 4745 2619 4745 2606 4746 2605 4746 2619 4746 2619 4747 2605 4747 2609 4747 2619 4748 2609 4748 2617 4748 2617 4749 2609 4749 2608 4749 2617 4750 2608 4750 2612 4750 2582 4751 2618 4751 2580 4751 2580 4752 2618 4752 2619 4752 2580 4753 2619 4753 2578 4753 2578 4754 2619 4754 2617 4754 2620 4755 2621 4755 2622 4755 2623 4756 2624 4756 2625 4756 2625 4757 2620 4757 2626 4757 2626 4758 2620 4758 2622 4758 2626 4759 2622 4759 2627 4759 2627 4760 2622 4760 2628 4760 2625 4761 2626 4761 2623 4761 2623 4762 2626 4762 2627 4762 2623 4763 2627 4763 2629 4763 2629 4764 2627 4764 2630 4764 2629 4765 2630 4765 2631 4765 2628 4766 2632 4766 2627 4766 2627 4767 2632 4767 2633 4767 2627 4768 2633 4768 2630 4768 2630 4769 2633 4769 2634 4769 2630 4770 2634 4770 2635 4770 2631 4771 2630 4771 2636 4771 2636 4772 2630 4772 2635 4772 2636 4773 2635 4773 2637 4773 2638 4774 2639 4774 2640 4774 2641 4775 2642 4775 2640 4775 2643 4776 2644 4776 2645 4776 2645 4777 2644 4777 2646 4777 2645 4778 2646 4778 2647 4778 2647 4779 2646 4779 2402 4779 2642 4780 2641 4780 2648 4780 2648 4781 2641 4781 2591 4781 2648 4782 2591 4782 2590 4782 2639 4783 2649 4783 2640 4783 2640 4784 2649 4784 2650 4784 2640 4785 2650 4785 2641 4785 2402 4786 2651 4786 2647 4786 2647 4787 2651 4787 2652 4787 2647 4788 2652 4788 2638 4788 2590 4789 2596 4789 2648 4789 2648 4790 2596 4790 2653 4790 2648 4791 2653 4791 2654 4791 2638 4792 2640 4792 2647 4792 2647 4793 2640 4793 2642 4793 2647 4794 2642 4794 2645 4794 2645 4795 2642 4795 2648 4795 2645 4796 2648 4796 2643 4796 2643 4797 2648 4797 2654 4797 2643 4798 2654 4798 2644 4798 2655 4799 2656 4799 2657 4799 2658 4800 2659 4800 2660 4800 2660 4801 2659 4801 2661 4801 2661 4802 2662 4802 2657 4802 2657 4803 2662 4803 2663 4803 2657 4804 2663 4804 2655 4804 2664 4805 2665 4805 2660 4805 2660 4806 2665 4806 2666 4806 2660 4807 2666 4807 2667 4807 2667 4808 2668 4808 2660 4808 2660 4809 2668 4809 2669 4809 2660 4810 2669 4810 2658 4810 2638 4811 2652 4811 2670 4811 2661 4812 2657 4812 2660 4812 2660 4813 2657 4813 2671 4813 2660 4814 2671 4814 2672 4814 2672 4815 2671 4815 2673 4815 2672 4816 2673 4816 2674 4816 2674 4817 2673 4817 2675 4817 2674 4818 2675 4818 2676 4818 2676 4819 2675 4819 2677 4819 2676 4820 2677 4820 2678 4820 2678 4821 2677 4821 2679 4821 2678 4822 2679 4822 2680 4822 2680 4823 2679 4823 2595 4823 2680 4824 2595 4824 2593 4824 2664 4825 2660 4825 2670 4825 2670 4826 2660 4826 2672 4826 2670 4827 2672 4827 2638 4827 2638 4828 2672 4828 2674 4828 2638 4829 2674 4829 2639 4829 2639 4830 2674 4830 2676 4830 2639 4831 2676 4831 2649 4831 2649 4832 2676 4832 2678 4832 2649 4833 2678 4833 2650 4833 2650 4834 2678 4834 2680 4834 2650 4835 2680 4835 2641 4835 2641 4836 2680 4836 2593 4836 2641 4837 2593 4837 2591 4837 2637 4838 2635 4838 2681 4838 2682 4839 2683 4839 2684 4839 2682 4840 2684 4840 2685 4840 2685 4841 2684 4841 2686 4841 2685 4842 2686 4842 2687 4842 2687 4843 2686 4843 2688 4843 2687 4844 2688 4844 2689 4844 2689 4845 2688 4845 2410 4845 2689 4846 2410 4846 2690 4846 2634 4847 2683 4847 2635 4847 2635 4848 2683 4848 2682 4848 2635 4849 2682 4849 2681 4849 2681 4850 2682 4850 2685 4850 2681 4851 2685 4851 2691 4851 2691 4852 2685 4852 2687 4852 2691 4853 2687 4853 2692 4853 2692 4854 2687 4854 2689 4854 2692 4855 2689 4855 2693 4855 2693 4856 2689 4856 2690 4856 2693 4857 2690 4857 2694 4857 2637 4858 2681 4858 2695 4858 2695 4859 2681 4859 2691 4859 2695 4860 2691 4860 2696 4860 2696 4861 2691 4861 2692 4861 2696 4862 2692 4862 2697 4862 2697 4863 2692 4863 2693 4863 2697 4864 2693 4864 2698 4864 2698 4865 2693 4865 2694 4865 2698 4866 2694 4866 2699 4866 2700 4867 2701 4867 2702 4867 2702 4868 2701 4868 2703 4868 2702 4869 2703 4869 2704 4869 2704 4870 2703 4870 2582 4870 2704 4871 2582 4871 2583 4871 2705 4872 2706 4872 2707 4872 2707 4873 2706 4873 2708 4873 2707 4874 2708 4874 2709 4874 2709 4875 2710 4875 2707 4875 2707 4876 2710 4876 2711 4876 2707 4877 2711 4877 2618 4877 2618 4878 2711 4878 2712 4878 2618 4879 2712 4879 2606 4879 2618 4880 2582 4880 2707 4880 2707 4881 2582 4881 2703 4881 2707 4882 2703 4882 2705 4882 2705 4883 2703 4883 2701 4883 2711 4884 2710 4884 2713 4884 2713 4885 2710 4885 2709 4885 2607 4886 2606 4886 2712 4886 2607 4887 2712 4887 2711 4887 2711 4888 2713 4888 2607 4888 2607 4889 2713 4889 2714 4889 2607 4890 2714 4890 2614 4890 2602 4891 2614 4891 2715 4891 2715 4892 2614 4892 2714 4892 2715 4893 2714 4893 2716 4893 2716 4894 2714 4894 2717 4894 2717 4895 2714 4895 2713 4895 2717 4896 2713 4896 2718 4896 2718 4897 2713 4897 2709 4897 2718 4898 2709 4898 2708 4898 2719 4899 2720 4899 2721 4899 2716 4900 2719 4900 2715 4900 2715 4901 2719 4901 2721 4901 2715 4902 2721 4902 2602 4902 2602 4903 2721 4903 2599 4903 2596 4904 2599 4904 2653 4904 2653 4905 2599 4905 2721 4905 2653 4906 2721 4906 2654 4906 2654 4907 2721 4907 2720 4907 2722 4908 2723 4908 2724 4908 2724 4909 2723 4909 2725 4909 2724 4910 2725 4910 2726 4910 2726 4911 2725 4911 2727 4911 2726 4912 2727 4912 2728 4912 2728 4913 2727 4913 2729 4913 2728 4914 2729 4914 2730 4914 2730 4915 2729 4915 2731 4915 2730 4916 2731 4916 2732 4916 2732 4917 2731 4917 2733 4917 2732 4918 2733 4918 2734 4918 2734 4919 2733 4919 2735 4919 2734 4920 2735 4920 2736 4920 2736 4921 2735 4921 2737 4921 2736 4922 2737 4922 2738 4922 2738 4923 2737 4923 2739 4923 2738 4924 2739 4924 2740 4924 2740 4925 2739 4925 2741 4925 2740 4926 2741 4926 2742 4926 2742 4927 2741 4927 2743 4927 2742 4928 2743 4928 2744 4928 2744 4929 2743 4929 2745 4929 2744 4930 2745 4930 2746 4930 2746 4931 2745 4931 2747 4931 2746 4932 2747 4932 2748 4932 2748 4933 2747 4933 2586 4933 2748 4934 2586 4934 2587 4934 2722 4935 2724 4935 2749 4935 2749 4936 2724 4936 2726 4936 2749 4937 2726 4937 2750 4937 2750 4938 2726 4938 2728 4938 2750 4939 2728 4939 2751 4939 2751 4940 2728 4940 2730 4940 2751 4941 2730 4941 2752 4941 2752 4942 2730 4942 2732 4942 2752 4943 2732 4943 2753 4943 2753 4944 2732 4944 2734 4944 2753 4945 2734 4945 2754 4945 2754 4946 2734 4946 2736 4946 2754 4947 2736 4947 2755 4947 2755 4948 2736 4948 2738 4948 2755 4949 2738 4949 2756 4949 2756 4950 2738 4950 2740 4950 2756 4951 2740 4951 2757 4951 2757 4952 2740 4952 2742 4952 2757 4953 2742 4953 2758 4953 2758 4954 2742 4954 2744 4954 2758 4955 2744 4955 2759 4955 2759 4956 2744 4956 2746 4956 2759 4957 2746 4957 2760 4957 2760 4958 2746 4958 2748 4958 2760 4959 2748 4959 2761 4959 2761 4960 2748 4960 2587 4960 2761 4961 2587 4961 2589 4961 2739 4962 2737 4962 2762 4962 2763 4963 2764 4963 2765 4963 2766 4964 2767 4964 2768 4964 2769 4965 2770 4965 2763 4965 2763 4966 2770 4966 2762 4966 2763 4967 2762 4967 2764 4967 2765 4968 2764 4968 2771 4968 2771 4969 2764 4969 2772 4969 2771 4970 2772 4970 2773 4970 2772 4971 2731 4971 2773 4971 2773 4972 2731 4972 2729 4972 2773 4973 2729 4973 2727 4973 2727 4974 2725 4974 2773 4974 2773 4975 2725 4975 2723 4975 2773 4976 2723 4976 2722 4976 2762 4977 2737 4977 2764 4977 2764 4978 2737 4978 2735 4978 2764 4979 2735 4979 2772 4979 2772 4980 2735 4980 2733 4980 2772 4981 2733 4981 2731 4981 2586 4982 2747 4982 2774 4982 2774 4983 2747 4983 2745 4983 2774 4984 2745 4984 2770 4984 2770 4985 2745 4985 2743 4985 2770 4986 2743 4986 2762 4986 2762 4987 2743 4987 2741 4987 2762 4988 2741 4988 2739 4988 2769 4989 2766 4989 2770 4989 2770 4990 2766 4990 2768 4990 2770 4991 2768 4991 2774 4991 2774 4992 2768 4992 2775 4992 2774 4993 2775 4993 2586 4993 2586 4994 2775 4994 2584 4994 2767 4995 2700 4995 2768 4995 2768 4996 2700 4996 2702 4996 2768 4997 2702 4997 2775 4997 2775 4998 2702 4998 2704 4998 2775 4999 2704 4999 2584 4999 2584 5000 2704 5000 2583 5000 2776 5001 2777 5001 2778 5001 2778 5002 2779 5002 2776 5002 2776 5003 2779 5003 2780 5003 2776 5004 2780 5004 2781 5004 2782 5005 2783 5005 2784 5005 2784 5006 2783 5006 2785 5006 2784 5007 2785 5007 2776 5007 2776 5008 2785 5008 2786 5008 2776 5009 2786 5009 2777 5009 2787 5010 2788 5010 2789 5010 2789 5011 2788 5011 2790 5011 2789 5012 2790 5012 2784 5012 2784 5013 2790 5013 2791 5013 2784 5014 2791 5014 2782 5014 2792 5015 2789 5015 2793 5015 2793 5016 2789 5016 2784 5016 2793 5017 2784 5017 2794 5017 2794 5018 2784 5018 2776 5018 2794 5019 2776 5019 2795 5019 2795 5020 2776 5020 2781 5020 2796 5021 2792 5021 2797 5021 2797 5022 2792 5022 2793 5022 2797 5023 2793 5023 2798 5023 2798 5024 2793 5024 2794 5024 2798 5025 2794 5025 2799 5025 2799 5026 2794 5026 2795 5026 2579 523 2578 523 2800 523 2801 523 2589 523 2588 523 2801 5027 2588 5027 2802 5027 2579 523 2800 523 2588 523 2588 523 2800 523 2803 523 2588 5028 2803 5028 2802 5028 2801 5029 2802 5029 2804 5029 2804 5030 2802 5030 2805 5030 2804 5031 2805 5031 2806 5031 2806 5032 2805 5032 2807 5032 2806 5033 2807 5033 2808 5033 2808 5034 2807 5034 2809 5034 2809 5035 2807 5035 2810 5035 2809 5036 2810 5036 2811 5036 2802 5037 2803 5037 2805 5037 2805 5038 2803 5038 2812 5038 2805 5039 2812 5039 2807 5039 2807 5040 2812 5040 2813 5040 2807 5041 2813 5041 2810 5041 2810 5042 2813 5042 2814 5042 2815 5043 2816 5043 2817 5043 2818 5044 2819 5044 2820 5044 2821 5045 2822 5045 2823 5045 2823 5046 2822 5046 2824 5046 2823 5047 2824 5047 2825 5047 2825 5048 2824 5048 2818 5048 2815 5049 2817 5049 2826 5049 2818 5050 2820 5050 2825 5050 2825 5051 2820 5051 2827 5051 2825 5052 2827 5052 2828 5052 2829 5053 2821 5053 2830 5053 2830 5054 2821 5054 2823 5054 2830 5055 2823 5055 2817 5055 2817 5056 2823 5056 2825 5056 2817 5057 2825 5057 2826 5057 2826 5058 2825 5058 2828 5058 2831 5059 2832 5059 2833 5059 2832 5060 2831 5060 2834 5060 2835 5061 2833 5061 2832 5061 2836 5062 2837 5062 2832 5062 2837 5063 2836 5063 2838 5063 2839 5064 2832 5064 2837 5064 2838 5065 2840 5065 2841 5065 2841 5066 2840 5066 2842 5066 2843 5067 2844 5067 2835 5067 2835 5068 2844 5068 2845 5068 2835 5069 2845 5069 2833 5069 2406 5070 2846 5070 2847 5070 2847 5071 2846 5071 2843 5071 2847 5072 2843 5072 2848 5072 2848 5073 2843 5073 2835 5073 2848 5074 2835 5074 2832 5074 2838 5075 2841 5075 2837 5075 2837 5076 2841 5076 2849 5076 2837 5077 2849 5077 2839 5077 2834 5078 2836 5078 2832 5078 2850 5079 2624 5079 2623 5079 2631 5080 2636 5080 2851 5080 2851 5081 2636 5081 2852 5081 2852 5082 2636 5082 2853 5082 2853 5083 2636 5083 2637 5083 2853 5084 2637 5084 2695 5084 2851 5085 2854 5085 2631 5085 2631 5086 2854 5086 2855 5086 2631 5087 2855 5087 2629 5087 2855 5088 2856 5088 2629 5088 2629 5089 2856 5089 2857 5089 2629 5090 2857 5090 2623 5090 2624 5091 2850 5091 2858 5091 2859 5092 2860 5092 2861 5092 2860 5093 2859 5093 2862 5093 2862 5094 2859 5094 2863 5094 2862 5095 2863 5095 2864 5095 2861 5096 2865 5096 2859 5096 2859 5097 2865 5097 2866 5097 2859 5098 2866 5098 2850 5098 2850 5099 2866 5099 2867 5099 2850 5100 2867 5100 2858 5100 2868 5101 2869 5101 2850 5101 2850 5102 2869 5102 2870 5102 2850 5103 2870 5103 2859 5103 2859 5104 2870 5104 2871 5104 2859 5105 2871 5105 2863 5105 2857 5106 2872 5106 2623 5106 2623 5107 2872 5107 2873 5107 2623 5108 2873 5108 2850 5108 2850 5109 2873 5109 2874 5109 2850 5110 2874 5110 2868 5110 2695 5111 2696 5111 2853 5111 2853 5112 2696 5112 2697 5112 2853 5113 2697 5113 2875 5113 2875 5114 2697 5114 2698 5114 2875 5115 2698 5115 2876 5115 2876 5116 2698 5116 2699 5116 2876 5117 2699 5117 2877 5117 2877 5118 2699 5118 2878 5118 2877 5119 2878 5119 2879 5119 2879 5120 2878 5120 2880 5120 2879 5121 2880 5121 2881 5121 2881 5122 2880 5122 2882 5122 2881 5123 2882 5123 2883 5123 2883 5124 2882 5124 2884 5124 2883 5125 2884 5125 2832 5125 2885 5126 2886 5126 2887 5126 2888 5127 2885 5127 2889 5127 2854 5128 2888 5128 2890 5128 2885 5129 2887 5129 2889 5129 2889 5130 2887 5130 2891 5130 2889 5131 2891 5131 2892 5131 2892 5132 2891 5132 2893 5132 2892 5133 2893 5133 2894 5133 2894 5134 2893 5134 2895 5134 2894 5135 2895 5135 2896 5135 2895 5136 2897 5136 2896 5136 2896 5137 2897 5137 2898 5137 2896 5138 2898 5138 2899 5138 2899 5139 2898 5139 2900 5139 2899 5140 2900 5140 2901 5140 2901 5141 2900 5141 2902 5141 2901 5142 2902 5142 2903 5142 2903 5143 2902 5143 2904 5143 2903 5144 2904 5144 2905 5144 2905 5145 2904 5145 2906 5145 2905 5146 2906 5146 2907 5146 2907 5147 2906 5147 2908 5147 2907 5148 2908 5148 2909 5148 2909 5149 2908 5149 2910 5149 2909 5150 2910 5150 2911 5150 2911 5151 2910 5151 2912 5151 2911 5152 2912 5152 2913 5152 2913 5153 2912 5153 2914 5153 2913 5154 2914 5154 2915 5154 2915 5155 2914 5155 2916 5155 2915 5156 2916 5156 2917 5156 2917 5157 2916 5157 2918 5157 2917 5158 2918 5158 2919 5158 2919 5159 2918 5159 2920 5159 2919 5160 2920 5160 2921 5160 2921 5161 2920 5161 2922 5161 2921 5162 2922 5162 2923 5162 2923 5163 2922 5163 2924 5163 2923 5164 2924 5164 2925 5164 2925 5165 2924 5165 2926 5165 2925 5166 2926 5166 2927 5166 2927 5167 2926 5167 2621 5167 2927 5168 2621 5168 2620 5168 2888 5169 2889 5169 2890 5169 2890 5170 2889 5170 2892 5170 2890 5171 2892 5171 2928 5171 2928 5172 2892 5172 2894 5172 2928 5173 2894 5173 2929 5173 2929 5174 2894 5174 2896 5174 2929 5175 2896 5175 2930 5175 2930 5176 2896 5176 2899 5176 2930 5177 2899 5177 2931 5177 2931 5178 2899 5178 2901 5178 2931 5179 2901 5179 2932 5179 2932 5180 2901 5180 2903 5180 2932 5181 2903 5181 2933 5181 2933 5182 2903 5182 2905 5182 2933 5183 2905 5183 2934 5183 2934 5184 2905 5184 2907 5184 2934 5185 2907 5185 2935 5185 2935 5186 2907 5186 2909 5186 2935 5187 2909 5187 2936 5187 2936 5188 2909 5188 2911 5188 2936 5189 2911 5189 2937 5189 2937 5190 2911 5190 2913 5190 2937 5191 2913 5191 2938 5191 2938 5192 2913 5192 2915 5192 2938 5193 2915 5193 2939 5193 2939 5194 2915 5194 2917 5194 2939 5195 2917 5195 2940 5195 2940 5196 2917 5196 2919 5196 2940 5197 2919 5197 2941 5197 2941 5198 2919 5198 2921 5198 2941 5199 2921 5199 2942 5199 2942 5200 2921 5200 2923 5200 2942 5201 2923 5201 2943 5201 2943 5202 2923 5202 2925 5202 2943 5203 2925 5203 2944 5203 2944 5204 2925 5204 2927 5204 2944 5205 2927 5205 2945 5205 2945 5206 2927 5206 2620 5206 2945 5207 2620 5207 2625 5207 2854 5208 2890 5208 2855 5208 2855 5209 2890 5209 2928 5209 2855 5210 2928 5210 2856 5210 2856 5211 2928 5211 2929 5211 2856 5212 2929 5212 2857 5212 2857 5213 2929 5213 2930 5213 2857 5214 2930 5214 2872 5214 2872 5215 2930 5215 2931 5215 2872 5216 2931 5216 2873 5216 2873 5217 2931 5217 2932 5217 2873 5218 2932 5218 2874 5218 2874 5219 2932 5219 2933 5219 2874 5220 2933 5220 2868 5220 2868 5221 2933 5221 2934 5221 2868 5222 2934 5222 2869 5222 2869 5223 2934 5223 2935 5223 2869 5224 2935 5224 2870 5224 2870 5225 2935 5225 2936 5225 2870 5226 2936 5226 2871 5226 2871 5227 2936 5227 2937 5227 2871 5228 2937 5228 2863 5228 2863 5229 2937 5229 2938 5229 2863 5230 2938 5230 2864 5230 2864 5231 2938 5231 2939 5231 2864 5232 2939 5232 2862 5232 2862 5233 2939 5233 2940 5233 2862 5234 2940 5234 2860 5234 2860 5235 2940 5235 2941 5235 2860 5236 2941 5236 2861 5236 2861 5237 2941 5237 2942 5237 2861 5238 2942 5238 2865 5238 2865 5239 2942 5239 2943 5239 2865 5240 2943 5240 2866 5240 2866 5241 2943 5241 2944 5241 2866 5242 2944 5242 2867 5242 2867 5243 2944 5243 2945 5243 2867 5244 2945 5244 2858 5244 2858 5245 2945 5245 2625 5245 2858 5246 2625 5246 2624 5246 2601 5247 2598 5247 2634 5247 2634 5248 2598 5248 2946 5248 2946 5249 2598 5249 2594 5249 2946 5250 2594 5250 2595 5250 2634 5251 2633 5251 2601 5251 2601 5252 2633 5252 2632 5252 2601 5253 2632 5253 2604 5253 2604 5254 2632 5254 2628 5254 2604 5255 2628 5255 2616 5255 2616 5256 2628 5256 2622 5256 2616 5257 2622 5257 2611 5257 2611 5258 2622 5258 2613 5258 2613 5259 2622 5259 2621 5259 2613 5260 2621 5260 2617 5260 2617 5261 2621 5261 2800 5261 2617 5262 2800 5262 2578 5262 2400 5263 2402 5263 2646 5263 2400 5264 2646 5264 2947 5264 2947 5265 2646 5265 2644 5265 2947 5266 2644 5266 2948 5266 2948 5267 2644 5267 2654 5267 2948 5268 2654 5268 2949 5268 2651 5269 2950 5269 2652 5269 2652 5270 2950 5270 2670 5270 2670 5271 2950 5271 2664 5271 2664 5272 2950 5272 2951 5272 2664 5273 2951 5273 2665 5273 2665 5274 2951 5274 2952 5274 2665 5275 2952 5275 2666 5275 2666 5276 2952 5276 2953 5276 2666 5277 2953 5277 2667 5277 2667 5278 2953 5278 2954 5278 2667 5279 2954 5279 2668 5279 2659 5280 2658 5280 2954 5280 2954 5281 2658 5281 2669 5281 2954 5282 2669 5282 2668 5282 2655 5283 2663 5283 2955 5283 2955 5284 2663 5284 2662 5284 2955 5285 2662 5285 2956 5285 2956 5286 2662 5286 2661 5286 2956 5287 2661 5287 2957 5287 2957 5288 2661 5288 2659 5288 2957 5289 2659 5289 2958 5289 2958 5290 2659 5290 2954 5290 2388 5291 2959 5291 2955 5291 2955 5292 2959 5292 2656 5292 2955 5293 2656 5293 2655 5293 2388 5294 2955 5294 2389 5294 2389 5295 2955 5295 2956 5295 2389 5296 2956 5296 2393 5296 2393 5297 2956 5297 2957 5297 2393 5298 2957 5298 2394 5298 2394 5299 2957 5299 2958 5299 2394 5300 2958 5300 2395 5300 2395 5301 2958 5301 2954 5301 2395 5302 2954 5302 2396 5302 2396 5303 2954 5303 2953 5303 2396 5304 2953 5304 2397 5304 2397 5305 2953 5305 2952 5305 2397 5306 2952 5306 2398 5306 2398 5307 2952 5307 2951 5307 2398 5308 2951 5308 2399 5308 2399 5309 2951 5309 2950 5309 2399 5310 2950 5310 2401 5310 2401 5311 2950 5311 2651 5311 2401 5312 2651 5312 2402 5312 2657 5313 2656 5313 2959 5313 2960 5314 2673 5314 2961 5314 2961 5315 2673 5315 2671 5315 2961 5316 2671 5316 2657 5316 2946 5317 2595 5317 2960 5317 2960 5318 2595 5318 2679 5318 2679 5319 2677 5319 2960 5319 2960 5320 2677 5320 2675 5320 2960 5321 2675 5321 2673 5321 2657 5322 2959 5322 2961 5322 2961 5323 2959 5323 2388 5323 2961 5324 2388 5324 2408 5324 2634 5325 2946 5325 2683 5325 2683 5326 2946 5326 2960 5326 2683 5327 2960 5327 2684 5327 2684 5328 2960 5328 2686 5328 2686 5329 2960 5329 2961 5329 2686 5330 2961 5330 2688 5330 2688 5331 2961 5331 2408 5331 2688 5332 2408 5332 2410 5332 2848 5333 2832 5333 2884 5333 2847 5334 2848 5334 2962 5334 2406 5335 2847 5335 2963 5335 2848 5336 2884 5336 2962 5336 2962 5337 2884 5337 2882 5337 2962 5338 2882 5338 2964 5338 2964 5339 2882 5339 2880 5339 2964 5340 2880 5340 2965 5340 2965 5341 2880 5341 2878 5341 2965 5342 2878 5342 2966 5342 2966 5343 2878 5343 2699 5343 2966 5344 2699 5344 2694 5344 2847 5345 2962 5345 2963 5345 2963 5346 2962 5346 2964 5346 2963 5347 2964 5347 2967 5347 2967 5348 2964 5348 2965 5348 2967 5349 2965 5349 2968 5349 2968 5350 2965 5350 2966 5350 2968 5351 2966 5351 2969 5351 2969 5352 2966 5352 2694 5352 2969 5353 2694 5353 2690 5353 2406 5354 2963 5354 2407 5354 2407 5355 2963 5355 2967 5355 2407 5356 2967 5356 2411 5356 2411 5357 2967 5357 2968 5357 2411 5358 2968 5358 2412 5358 2412 5359 2968 5359 2969 5359 2412 5360 2969 5360 2409 5360 2409 5361 2969 5361 2690 5361 2409 5362 2690 5362 2410 5362 2970 523 2971 523 2700 523 2700 5363 2971 5363 2972 5363 2700 523 2972 523 2701 523 2972 5364 2973 5364 2701 5364 2701 5365 2973 5365 2974 5365 2701 523 2974 523 2705 523 2705 5366 2974 5366 2975 5366 2705 523 2975 523 2706 523 2706 5367 2975 5367 2976 5367 2977 5368 2787 5368 2789 5368 2977 5369 2789 5369 2978 5369 2976 5370 2979 5370 2792 5370 2792 5371 2979 5371 2980 5371 2792 5372 2980 5372 2789 5372 2789 5373 2980 5373 2981 5373 2789 5374 2981 5374 2978 5374 2982 5375 2706 5375 2983 5375 2983 5376 2706 5376 2976 5376 2983 5377 2976 5377 2796 5377 2796 5378 2976 5378 2792 5378 2719 5379 2716 5379 2982 5379 2716 5380 2717 5380 2982 5380 2982 5381 2717 5381 2718 5381 2982 5382 2718 5382 2706 5382 2706 5383 2718 5383 2708 5383 2949 5384 2654 5384 2720 5384 2720 5385 2984 5385 2985 5385 2985 5386 2986 5386 2720 5386 2720 5387 2986 5387 2987 5387 2720 5388 2987 5388 2949 5388 2982 5389 2988 5389 2719 5389 2719 5390 2988 5390 2989 5390 2719 5391 2989 5391 2720 5391 2720 5392 2989 5392 2990 5392 2720 5393 2990 5393 2984 5393 2991 5394 2992 5394 2993 5394 2994 5395 2995 5395 2996 5395 2996 5396 2995 5396 2993 5396 2996 5397 2993 5397 2997 5397 2997 5398 2993 5398 2992 5398 2991 5399 2993 5399 2998 5399 2998 5400 2993 5400 2999 5400 2998 5401 2999 5401 3000 5401 3001 5402 3002 5402 2999 5402 2999 5403 3002 5403 3003 5403 2999 5404 3003 5404 3000 5404 3004 5405 3005 5405 3006 5405 3006 5406 3005 5406 3007 5406 3006 5407 3007 5407 3001 5407 3001 5408 3007 5408 3008 5408 3001 5409 3008 5409 3002 5409 2787 5410 2977 5410 3009 5410 3009 5411 2977 5411 2978 5411 3009 5412 2978 5412 2981 5412 2787 5413 3009 5413 2788 5413 2788 5414 3009 5414 3010 5414 2788 5415 3010 5415 2790 5415 2785 5416 2783 5416 3011 5416 3011 5417 2783 5417 2782 5417 3011 5418 2782 5418 3010 5418 3010 5419 2782 5419 2791 5419 3010 5420 2791 5420 2790 5420 3012 5421 2778 5421 2777 5421 3012 5422 2777 5422 3011 5422 3011 5423 2777 5423 2786 5423 3011 5424 2786 5424 2785 5424 2781 5425 2780 5425 3012 5425 3012 5426 2780 5426 2779 5426 3012 5427 2779 5427 2778 5427 3009 5428 3006 5428 3010 5428 3010 5429 3006 5429 3001 5429 3010 5430 3001 5430 3011 5430 3011 5431 3001 5431 2999 5431 3011 5432 2999 5432 3012 5432 3012 5433 2999 5433 2993 5433 3012 5434 2993 5434 2781 5434 2781 5435 2993 5435 2995 5435 2817 5436 2816 5436 3013 5436 2817 5437 3013 5437 2830 5437 3014 5438 3015 5438 3016 5438 3016 5439 3015 5439 3017 5439 3016 5440 3017 5440 3013 5440 3013 5441 3017 5441 2829 5441 3013 5442 2829 5442 2830 5442 2589 5443 2801 5443 2761 5443 2761 5444 2801 5444 2804 5444 2761 5445 2804 5445 2760 5445 2756 5446 2757 5446 2806 5446 2806 5447 2757 5447 2758 5447 2806 5448 2758 5448 2804 5448 2804 5449 2758 5449 2759 5449 2804 5450 2759 5450 2760 5450 2753 5451 2754 5451 2809 5451 2809 5452 2754 5452 2755 5452 2756 5453 2806 5453 2755 5453 2755 5454 2806 5454 2808 5454 2755 5455 2808 5455 2809 5455 2811 5456 2722 5456 2809 5456 2809 5457 2722 5457 2749 5457 2809 5458 2749 5458 2750 5458 2750 5459 2751 5459 2809 5459 2809 5460 2751 5460 2752 5460 2809 5461 2752 5461 2753 5461 3018 5462 3019 5462 3020 5462 2766 5463 3021 5463 2767 5463 2767 5464 3021 5464 3022 5464 2767 5465 3022 5465 2700 5465 2700 5466 3022 5466 2970 5466 2722 5467 3018 5467 2773 5467 2773 5468 3018 5468 3020 5468 2773 5469 3020 5469 2771 5469 2771 5470 3020 5470 3023 5470 2771 5471 3023 5471 2765 5471 2765 5472 3023 5472 3024 5472 2765 5473 3024 5473 2763 5473 2763 5474 3024 5474 3021 5474 2763 5475 3021 5475 2769 5475 2769 5476 3021 5476 2766 5476 3023 5477 3020 5477 3025 5477 3026 5478 3027 5478 3028 5478 3029 5479 3026 5479 3030 5479 3031 5480 3029 5480 3032 5480 3033 5481 3031 5481 3034 5481 3026 5482 3028 5482 3030 5482 3030 5483 3028 5483 3035 5483 3030 5484 3035 5484 3036 5484 3036 5485 3035 5485 3037 5485 3036 5486 3037 5486 3038 5486 3038 5487 3037 5487 3039 5487 3038 5488 3039 5488 3040 5488 3040 5489 3039 5489 3041 5489 3040 5490 3041 5490 3042 5490 3042 5491 3041 5491 3043 5491 3042 5492 3043 5492 3044 5492 3044 5493 3043 5493 3045 5493 3044 5494 3045 5494 3046 5494 3046 5495 3045 5495 3047 5495 3046 5496 3047 5496 3048 5496 3048 5497 3047 5497 3049 5497 3048 5498 3049 5498 3050 5498 3050 5499 3049 5499 3051 5499 3050 5500 3051 5500 3052 5500 3052 5501 3051 5501 3053 5501 3052 5502 3053 5502 3054 5502 3053 5503 2970 5503 3054 5503 3054 5504 2970 5504 3022 5504 3054 5505 3022 5505 3021 5505 3029 5506 3030 5506 3032 5506 3032 5507 3030 5507 3036 5507 3032 5508 3036 5508 3055 5508 3055 5509 3036 5509 3038 5509 3055 5510 3038 5510 3056 5510 3056 5511 3038 5511 3040 5511 3056 5512 3040 5512 3057 5512 3057 5513 3040 5513 3042 5513 3057 5514 3042 5514 3058 5514 3058 5515 3042 5515 3044 5515 3058 5516 3044 5516 3059 5516 3059 5517 3044 5517 3046 5517 3059 5518 3046 5518 3060 5518 3060 5519 3046 5519 3048 5519 3060 5520 3048 5520 3061 5520 3061 5521 3048 5521 3050 5521 3061 5522 3050 5522 3062 5522 3062 5523 3050 5523 3052 5523 3062 5524 3052 5524 3063 5524 3063 5525 3052 5525 3054 5525 3063 5526 3054 5526 3064 5526 3064 5527 3054 5527 3021 5527 3064 5528 3021 5528 3024 5528 3031 5529 3032 5529 3034 5529 3034 5530 3032 5530 3055 5530 3034 5531 3055 5531 3065 5531 3065 5532 3055 5532 3056 5532 3065 5533 3056 5533 3066 5533 3066 5534 3056 5534 3057 5534 3066 5535 3057 5535 3067 5535 3067 5536 3057 5536 3058 5536 3067 5537 3058 5537 3068 5537 3068 5538 3058 5538 3059 5538 3068 5539 3059 5539 3069 5539 3069 5540 3059 5540 3060 5540 3069 5541 3060 5541 3070 5541 3070 5542 3060 5542 3061 5542 3070 5543 3061 5543 3071 5543 3071 5544 3061 5544 3062 5544 3071 5545 3062 5545 3072 5545 3072 5546 3062 5546 3063 5546 3072 5547 3063 5547 3073 5547 3073 5548 3063 5548 3064 5548 3073 5549 3064 5549 3025 5549 3025 5550 3064 5550 3024 5550 3025 5551 3024 5551 3023 5551 3033 5552 3034 5552 3074 5552 3074 5553 3034 5553 3065 5553 3074 5554 3065 5554 3075 5554 3075 5555 3065 5555 3066 5555 3075 5556 3066 5556 3076 5556 3076 5557 3066 5557 3067 5557 3076 5558 3067 5558 3077 5558 3077 5559 3067 5559 3068 5559 3077 5560 3068 5560 3078 5560 3078 5561 3068 5561 3069 5561 3078 5562 3069 5562 3079 5562 3079 5563 3069 5563 3070 5563 3079 5564 3070 5564 3080 5564 3080 5565 3070 5565 3071 5565 3080 5566 3071 5566 3081 5566 3081 5567 3071 5567 3072 5567 3081 5568 3072 5568 3082 5568 3082 5569 3072 5569 3073 5569 3082 5570 3073 5570 3083 5570 3083 5571 3073 5571 3025 5571 3083 5572 3025 5572 3084 5572 3084 5573 3025 5573 3020 5573 3084 5574 3020 5574 3019 5574 2797 5575 2798 5575 3085 5575 2796 5576 2797 5576 3086 5576 3087 5577 3085 5577 3088 5577 3088 5578 3085 5578 2798 5578 3088 5579 2798 5579 2799 5579 2796 5580 3086 5580 2983 5580 2983 5581 3086 5581 3089 5581 2983 5582 3089 5582 2982 5582 3090 5583 3091 5583 3087 5583 3087 5584 3091 5584 3092 5584 3087 5585 3092 5585 3085 5585 3090 5586 3093 5586 3091 5586 3091 5587 3093 5587 3094 5587 3091 5588 3094 5588 3095 5588 3095 5589 3094 5589 3096 5589 3095 5590 3096 5590 3097 5590 3097 5591 3096 5591 3098 5591 3097 5592 3098 5592 3099 5592 3099 5593 3098 5593 3100 5593 3099 5594 3100 5594 3101 5594 3100 5595 3102 5595 3101 5595 3101 5596 3102 5596 3103 5596 3101 5597 3103 5597 3104 5597 3104 5598 3103 5598 2400 5598 3104 5599 2400 5599 2947 5599 2797 5600 3085 5600 3086 5600 3086 5601 3085 5601 3092 5601 3086 5602 3092 5602 3089 5602 3089 5603 3092 5603 3091 5603 3089 5604 3091 5604 3105 5604 3105 5605 3091 5605 3095 5605 3105 5606 3095 5606 3106 5606 3106 5607 3095 5607 3097 5607 3106 5608 3097 5608 3107 5608 3107 5609 3097 5609 3099 5609 3107 5610 3099 5610 3108 5610 3108 5611 3099 5611 3101 5611 3108 5612 3101 5612 3109 5612 3109 5613 3101 5613 3104 5613 3109 5614 3104 5614 3110 5614 3110 5615 3104 5615 2947 5615 3110 5616 2947 5616 2948 5616 2982 5617 3089 5617 2988 5617 2988 5618 3089 5618 3105 5618 2988 5619 3105 5619 2989 5619 2989 5620 3105 5620 3106 5620 2989 5621 3106 5621 2990 5621 2990 5622 3106 5622 3107 5622 2990 5623 3107 5623 2984 5623 2984 5624 3107 5624 3108 5624 2984 5625 3108 5625 2985 5625 2985 5626 3108 5626 3109 5626 2985 5627 3109 5627 2986 5627 2986 5628 3109 5628 3110 5628 2986 5629 3110 5629 2987 5629 2987 5630 3110 5630 2948 5630 2987 5631 2948 5631 2949 5631 3002 5632 3008 5632 3111 5632 2994 5633 2996 5633 3112 5633 3113 5634 3114 5634 2994 5634 3008 5635 3007 5635 3115 5635 3115 5636 3007 5636 3005 5636 3115 5637 3005 5637 3004 5637 3002 5638 3111 5638 3003 5638 2996 5639 2997 5639 3112 5639 3112 5640 2997 5640 2992 5640 3112 5641 2992 5641 2991 5641 2991 5642 2998 5642 3116 5642 3116 5643 2998 5643 3000 5643 3116 5644 3000 5644 3003 5644 3008 5645 3115 5645 3111 5645 3111 5646 3115 5646 3117 5646 3111 5647 3117 5647 3118 5647 3118 5648 3117 5648 3119 5648 3118 5649 3119 5649 3120 5649 3120 5650 3119 5650 3121 5650 3120 5651 3121 5651 3122 5651 3122 5652 3121 5652 3123 5652 3122 5653 3123 5653 3124 5653 3124 5654 3123 5654 3125 5654 3124 5655 3125 5655 3126 5655 3126 5656 3125 5656 3127 5656 3126 5657 3127 5657 3128 5657 3003 5658 3111 5658 3116 5658 3116 5659 3111 5659 3118 5659 3116 5660 3118 5660 3129 5660 3129 5661 3118 5661 3120 5661 3129 5662 3120 5662 3130 5662 3130 5663 3120 5663 3122 5663 3130 5664 3122 5664 3131 5664 3131 5665 3122 5665 3124 5665 3131 5666 3124 5666 3132 5666 3132 5667 3124 5667 3126 5667 3132 5668 3126 5668 3133 5668 3133 5669 3126 5669 3128 5669 3133 5670 3128 5670 3134 5670 2991 5671 3116 5671 3112 5671 3112 5672 3116 5672 3129 5672 3112 5673 3129 5673 3135 5673 3135 5674 3129 5674 3130 5674 3135 5675 3130 5675 3136 5675 3136 5676 3130 5676 3131 5676 3136 5677 3131 5677 3137 5677 3137 5678 3131 5678 3132 5678 3137 5679 3132 5679 3138 5679 3138 5680 3132 5680 3133 5680 3138 5681 3133 5681 3139 5681 3139 5682 3133 5682 3134 5682 3139 5683 3134 5683 3140 5683 2994 5684 3112 5684 3113 5684 3113 5685 3112 5685 3135 5685 3113 5686 3135 5686 3141 5686 3141 5687 3135 5687 3136 5687 3141 5688 3136 5688 3142 5688 3142 5689 3136 5689 3137 5689 3142 5690 3137 5690 3143 5690 3143 5691 3137 5691 3138 5691 3143 5692 3138 5692 3144 5692 3144 5693 3138 5693 3139 5693 3144 5694 3139 5694 3145 5694 3145 5695 3139 5695 3140 5695 3145 5696 3140 5696 3146 5696 3114 5697 256 5697 258 5697 2994 5698 3114 5698 2995 5698 2995 5699 3114 5699 2795 5699 2995 5700 2795 5700 2781 5700 3114 5701 258 5701 2795 5701 2795 5702 258 5702 266 5702 2795 5703 266 5703 2799 5703 3147 5704 2819 5704 3148 5704 3148 5705 2819 5705 2818 5705 3148 5706 2818 5706 3149 5706 3149 5707 2818 5707 2824 5707 3149 5708 2824 5708 3150 5708 3150 5709 2824 5709 2822 5709 3151 5710 3147 5710 3152 5710 3152 5711 3147 5711 3148 5711 3152 5712 3148 5712 3153 5712 3153 5713 3148 5713 3149 5713 3153 5714 3149 5714 3154 5714 3154 5715 3149 5715 3150 5715 2816 5716 3155 5716 3013 5716 2819 5717 3156 5717 2820 5717 2820 5718 3156 5718 3157 5718 2820 5719 3157 5719 2827 5719 2827 5720 3157 5720 2828 5720 3157 5721 3158 5721 2828 5721 2828 5722 3158 5722 3159 5722 2828 5723 3159 5723 2826 5723 2826 5724 3159 5724 3160 5724 2826 5725 3160 5725 2815 5725 3013 5726 3155 5726 3016 5726 3016 5727 3155 5727 3161 5727 3016 5728 3161 5728 3014 5728 3162 5729 3163 5729 3164 5729 2815 5730 3160 5730 2816 5730 2816 5731 3160 5731 3162 5731 2816 5732 3162 5732 3155 5732 3155 5733 3162 5733 3164 5733 3155 5734 3164 5734 3161 5734 3158 5735 3165 5735 3159 5735 3159 5736 3165 5736 3166 5736 3159 5737 3166 5737 3160 5737 3160 5738 3166 5738 3167 5738 3160 5739 3167 5739 3162 5739 3162 5740 3167 5740 3168 5740 3162 5741 3168 5741 3163 5741 3169 5742 3170 5742 3171 5742 3172 5743 3173 5743 3174 5743 3174 5744 3173 5744 3169 5744 3169 5745 3171 5745 3174 5745 3174 5746 3171 5746 3014 5746 3174 5747 3014 5747 3161 5747 3168 5748 3172 5748 3163 5748 3163 5749 3172 5749 3174 5749 3163 5750 3174 5750 3164 5750 3164 5751 3174 5751 3161 5751 7 5752 6 5752 224 5752 224 523 6 523 3175 523 224 523 3175 523 3176 523 3176 523 3175 523 3177 523 3178 5753 3179 5753 3175 5753 3175 5754 3179 5754 3180 5754 3175 5755 3180 5755 3177 5755 3181 5756 2814 5756 3182 5756 3182 5757 2814 5757 2813 5757 3182 5758 2813 5758 3183 5758 3183 5759 2813 5759 3184 5759 3184 5760 2813 5760 2812 5760 3184 5761 2812 5761 3185 5761 3185 5762 2812 5762 3186 5762 3186 5763 2812 5763 2803 5763 3186 5764 2803 5764 2800 5764 2810 5765 2814 5765 3154 5765 3154 5766 3150 5766 2810 5766 2810 5767 3150 5767 2822 5767 2810 5768 2822 5768 2811 5768 2811 5769 2822 5769 2821 5769 2811 5770 2821 5770 2829 5770 3187 5771 3151 5771 3152 5771 3188 5772 3189 5772 3178 5772 3178 5773 3189 5773 3190 5773 3187 5774 3152 5774 3188 5774 3190 5775 3189 5775 3191 5775 3191 5776 3189 5776 3192 5776 3191 5777 3192 5777 3193 5777 3193 5778 3192 5778 3194 5778 3194 5779 3192 5779 3195 5779 3194 5780 3195 5780 3196 5780 3188 5781 3152 5781 3189 5781 3189 5782 3152 5782 3153 5782 3189 5783 3153 5783 3192 5783 3192 5784 3153 5784 3154 5784 3192 5785 3154 5785 3195 5785 3196 5786 3197 5786 3198 5786 3179 5787 3178 5787 3199 5787 3199 5788 3178 5788 3190 5788 3199 5789 3190 5789 3200 5789 3200 5790 3190 5790 3191 5790 3200 5791 3191 5791 3201 5791 3201 5792 3191 5792 3193 5792 3201 5793 3193 5793 3198 5793 3198 5794 3193 5794 3194 5794 3198 5795 3194 5795 3196 5795 3202 5796 3203 5796 3204 5796 3200 5797 3201 5797 3205 5797 230 5798 3206 5798 229 5798 3179 5799 3199 5799 3180 5799 3180 5800 3199 5800 3207 5800 3180 5801 3207 5801 3177 5801 3208 5802 3209 5802 3176 5802 3176 5803 3209 5803 224 5803 3206 5804 230 5804 3209 5804 3209 5805 230 5805 225 5805 3209 5806 225 5806 224 5806 3210 5807 3211 5807 3212 5807 3212 5808 3211 5808 228 5808 3176 5809 3177 5809 3208 5809 3208 5810 3177 5810 3207 5810 3208 5811 3207 5811 3209 5811 3209 5812 3207 5812 3213 5812 3209 5813 3213 5813 3206 5813 3206 5814 3213 5814 3212 5814 3206 5815 3212 5815 229 5815 229 5816 3212 5816 228 5816 3199 5817 3200 5817 3207 5817 3207 5818 3200 5818 3205 5818 3207 5819 3205 5819 3213 5819 3213 5820 3205 5820 3214 5820 3213 5821 3214 5821 3212 5821 3212 5822 3214 5822 3204 5822 3212 5823 3204 5823 3210 5823 3210 5824 3204 5824 3203 5824 3201 5825 3198 5825 3205 5825 3205 5826 3198 5826 3215 5826 3205 5827 3215 5827 3214 5827 3214 5828 3215 5828 3216 5828 3214 5829 3216 5829 3204 5829 3204 5830 3216 5830 3217 5830 3204 5831 3217 5831 3202 5831 3202 5832 3217 5832 3218 5832 3198 5833 3197 5833 3215 5833 3215 5834 3197 5834 3219 5834 3215 5835 3219 5835 3216 5835 3216 5836 3219 5836 3220 5836 3216 5837 3220 5837 3217 5837 3217 5838 3220 5838 3221 5838 3217 5839 3221 5839 3218 5839 3218 5840 3221 5840 3222 5840 2425 5841 2838 5841 2836 5841 2838 5842 2425 5842 2840 5842 2840 5843 2425 5843 392 5843 2840 5844 392 5844 2842 5844 2834 5845 2445 5845 2836 5845 2836 5846 2445 5846 2446 5846 2836 5847 2446 5847 2425 5847 2834 5848 2831 5848 2445 5848 2445 5849 2831 5849 2833 5849 2445 5850 2833 5850 2845 5850 2845 5851 2844 5851 2445 5851 2445 5852 2844 5852 2843 5852 2445 5853 2843 5853 2444 5853 2444 5854 2843 5854 2405 5854 2405 5855 2843 5855 2846 5855 2405 5856 2846 5856 2406 5856 2854 5857 2851 5857 2888 5857 2888 5858 2851 5858 3223 5858 2888 5859 3223 5859 2885 5859 2886 5860 2885 5860 3224 5860 2851 5861 2852 5861 3223 5861 3223 5862 2852 5862 2853 5862 3223 5863 2853 5863 3225 5863 3225 5864 2853 5864 2875 5864 3225 5865 2875 5865 3226 5865 3226 5866 2875 5866 2876 5866 3226 5867 2876 5867 3227 5867 3227 5868 2876 5868 2877 5868 3227 5869 2877 5869 3228 5869 3228 5870 2877 5870 2879 5870 3228 5871 2879 5871 3229 5871 3229 5872 2879 5872 2881 5872 3229 5873 2881 5873 3230 5873 3230 5874 2881 5874 2883 5874 3230 5875 2883 5875 3231 5875 2883 5876 2832 5876 3231 5876 3231 5877 2832 5877 2839 5877 3231 5878 2839 5878 2849 5878 2885 5879 3223 5879 3224 5879 3224 5880 3223 5880 3225 5880 3224 5881 3225 5881 3232 5881 3232 5882 3225 5882 3226 5882 3232 5883 3226 5883 3233 5883 3233 5884 3226 5884 3227 5884 3233 5885 3227 5885 3234 5885 3234 5886 3227 5886 3228 5886 3234 5887 3228 5887 3235 5887 3235 5888 3228 5888 3229 5888 3235 5889 3229 5889 3236 5889 3236 5890 3229 5890 3230 5890 3236 5891 3230 5891 3237 5891 3237 5892 3230 5892 3231 5892 3237 5893 3231 5893 3238 5893 3238 5894 3231 5894 2849 5894 3238 5895 2849 5895 2841 5895 2886 5896 3224 5896 3239 5896 3239 5897 3224 5897 3232 5897 3239 5898 3232 5898 3240 5898 3240 5899 3232 5899 3233 5899 3240 5900 3233 5900 3241 5900 3241 5901 3233 5901 3234 5901 3241 5902 3234 5902 3242 5902 3242 5903 3234 5903 3235 5903 3242 5904 3235 5904 3243 5904 3243 5905 3235 5905 3236 5905 3243 5906 3236 5906 3244 5906 3244 5907 3236 5907 3237 5907 3244 5908 3237 5908 3245 5908 3245 5909 3237 5909 3238 5909 3245 5910 3238 5910 3246 5910 3246 5911 3238 5911 2841 5911 3246 5912 2841 5912 2842 5912 2887 5913 3247 5913 2891 5913 3247 5914 3248 5914 2891 5914 2891 5915 3248 5915 3249 5915 2891 5916 3249 5916 2893 5916 2621 5917 2926 5917 2800 5917 2800 5918 2926 5918 2924 5918 2800 5919 2924 5919 2922 5919 2922 5920 2920 5920 2800 5920 2800 5921 2920 5921 2918 5921 2800 5922 2918 5922 3186 5922 3186 5923 2918 5923 2916 5923 2916 5924 2914 5924 3186 5924 3186 5925 2914 5925 2912 5925 3186 5926 2912 5926 2910 5926 2910 5927 2908 5927 3186 5927 3186 5928 2908 5928 2906 5928 3186 5929 2906 5929 2904 5929 2904 5930 2902 5930 3186 5930 3186 5931 2902 5931 2900 5931 3186 5932 2900 5932 2898 5932 3181 5933 3248 5933 3250 5933 3250 5934 3248 5934 3247 5934 3250 5935 3247 5935 3251 5935 3251 5936 3247 5936 2887 5936 3251 5937 2887 5937 2886 5937 2898 5938 2897 5938 3186 5938 3186 5939 2897 5939 2895 5939 3186 5940 2895 5940 3185 5940 3185 5941 2895 5941 2893 5941 3185 5942 2893 5942 3184 5942 3184 5943 2893 5943 3249 5943 3184 5944 3249 5944 3183 5944 3183 5945 3249 5945 3248 5945 3183 5946 3248 5946 3182 5946 3182 5947 3248 5947 3181 5947 2241 629 283 629 322 629 322 629 283 629 287 629 3252 5948 3253 5948 3027 5948 3027 5949 3253 5949 3254 5949 3254 5950 3255 5950 3027 5950 3027 5951 3255 5951 3256 5951 3027 5952 3256 5952 3257 5952 3257 5953 3258 5953 3027 5953 3027 5954 3258 5954 3259 5954 3027 5955 3259 5955 3260 5955 3260 5956 3259 5956 3261 5956 3260 5957 3261 5957 3262 5957 3263 5958 3264 5958 3265 5958 3265 5959 3264 5959 3266 5959 3267 5960 3268 5960 3269 5960 3267 5961 3269 5961 3270 5961 3271 5962 3272 5962 3273 5962 3274 5963 3260 5963 3262 5963 3275 5964 3037 5964 3274 5964 3274 5965 3037 5965 3035 5965 3274 5966 3035 5966 3260 5966 3260 5967 3035 5967 3028 5967 3260 5968 3028 5968 3027 5968 3045 5969 3043 5969 3276 5969 3276 5970 3043 5970 3041 5970 3276 5971 3041 5971 3275 5971 3275 5972 3041 5972 3039 5972 3275 5973 3039 5973 3037 5973 3045 5974 3276 5974 3047 5974 3047 5975 3276 5975 3277 5975 3047 5976 3277 5976 3049 5976 3049 5977 3277 5977 3278 5977 3049 5978 3278 5978 3051 5978 2971 5979 2970 5979 3278 5979 3278 5980 2970 5980 3053 5980 3278 5981 3053 5981 3051 5981 3279 5982 3009 5982 2981 5982 2976 5983 2975 5983 2979 5983 2979 5984 2975 5984 3279 5984 2979 5985 3279 5985 2980 5985 2980 5986 3279 5986 2981 5986 3009 5987 3279 5987 3006 5987 3006 5988 3279 5988 3280 5988 3006 5989 3280 5989 3004 5989 3004 5990 3280 5990 3115 5990 3115 5991 3280 5991 3281 5991 3115 5992 3281 5992 3117 5992 3117 5993 3281 5993 3119 5993 3119 5994 3281 5994 3282 5994 3119 5995 3282 5995 3121 5995 3121 5996 3282 5996 3266 5996 3121 5997 3266 5997 3123 5997 3123 5998 3266 5998 3125 5998 3125 5999 3266 5999 3264 5999 3125 6000 3264 6000 3127 6000 3262 6001 3272 6001 3274 6001 3274 6002 3272 6002 3271 6002 3274 6003 3271 6003 3275 6003 3275 6004 3271 6004 3283 6004 3275 6005 3283 6005 3276 6005 3276 6006 3283 6006 3284 6006 3276 6007 3284 6007 3277 6007 3277 6008 3284 6008 3285 6008 3277 6009 3285 6009 3278 6009 3278 6010 3285 6010 3286 6010 3278 6011 3286 6011 2971 6011 2971 6012 3286 6012 2972 6012 3273 6013 3287 6013 3271 6013 3271 6014 3287 6014 3288 6014 3271 6015 3288 6015 3283 6015 3283 6016 3288 6016 3289 6016 3283 6017 3289 6017 3284 6017 3284 6018 3289 6018 3290 6018 3284 6019 3290 6019 3285 6019 3285 6020 3290 6020 3291 6020 3285 6021 3291 6021 3286 6021 3286 6022 3291 6022 3292 6022 3286 6023 3292 6023 2972 6023 2972 6024 3292 6024 2973 6024 3287 6025 3270 6025 3288 6025 3288 6026 3270 6026 3269 6026 3288 6027 3269 6027 3289 6027 3289 6028 3269 6028 3293 6028 3289 6029 3293 6029 3290 6029 3290 6030 3293 6030 3294 6030 3290 6031 3294 6031 3291 6031 3291 6032 3294 6032 3295 6032 3291 6033 3295 6033 3292 6033 3292 6034 3295 6034 3296 6034 3292 6035 3296 6035 2973 6035 2973 6036 3296 6036 2974 6036 3268 6037 3265 6037 3269 6037 3269 6038 3265 6038 3266 6038 3269 6039 3266 6039 3293 6039 3293 6040 3266 6040 3282 6040 3293 6041 3282 6041 3294 6041 3294 6042 3282 6042 3281 6042 3294 6043 3281 6043 3295 6043 3295 6044 3281 6044 3280 6044 3295 6045 3280 6045 3296 6045 3296 6046 3280 6046 3279 6046 3296 6047 3279 6047 2974 6047 2974 6048 3279 6048 2975 6048 3263 6049 3297 6049 3264 6049 3264 6050 3297 6050 3298 6050 3299 6051 3300 6051 3264 6051 3298 6052 3301 6052 3264 6052 3264 6053 3301 6053 3302 6053 3264 6054 3302 6054 3299 6054 3303 6055 3127 6055 3304 6055 3304 6056 3127 6056 3264 6056 3304 6057 3264 6057 3305 6057 3305 6058 3264 6058 3300 6058 3252 6059 3027 6059 3306 6059 3306 6060 3027 6060 3026 6060 3306 6061 3026 6061 3307 6061 3307 6062 3026 6062 3308 6062 3308 6063 3026 6063 3029 6063 3308 6064 3029 6064 3309 6064 3309 6065 3029 6065 3031 6065 3309 6066 3031 6066 3310 6066 3310 6067 3031 6067 3033 6067 3310 6068 3033 6068 3311 6068 3312 528 3313 528 3314 528 3314 6069 3313 6069 3315 6069 3314 528 3315 528 3316 528 2722 528 2811 528 2829 528 3317 6070 3019 6070 3318 6070 3318 528 3019 528 3018 528 3318 528 3018 528 3319 528 2829 528 3017 528 2722 528 2722 6071 3017 6071 3015 6071 2722 528 3015 528 3018 528 3018 6072 3015 6072 3014 6072 3018 528 3014 528 3319 528 3319 6073 3014 6073 3171 6073 3319 6074 3171 6074 3170 6074 3082 6075 3083 6075 3317 6075 3317 6076 3083 6076 3084 6076 3317 6077 3084 6077 3019 6077 3320 528 3311 528 3080 528 3080 6078 3311 6078 3033 6078 3080 6079 3033 6079 3079 6079 3079 6080 3033 6080 3074 6080 3079 528 3074 528 3078 528 3320 528 3080 528 3317 528 3317 6081 3080 6081 3081 6081 3317 6082 3081 6082 3082 6082 3321 528 3322 528 3323 528 3323 528 3324 528 3321 528 3321 6083 3324 6083 3319 6083 3321 528 3319 528 3316 528 3316 6084 3319 6084 3170 6084 3316 528 3170 528 3314 528 3075 528 3076 528 3074 528 3074 6085 3076 6085 3077 6085 3074 6086 3077 6086 3078 6086 273 6087 2358 6087 2357 6087 273 6088 2357 6088 274 6088 266 6089 265 6089 297 6089 2799 6090 266 6090 3088 6090 3088 6091 266 6091 297 6091 3088 6092 297 6092 3087 6092 3087 6093 297 6093 299 6093 3087 6094 299 6094 3090 6094 3090 6095 299 6095 308 6095 3090 6096 308 6096 307 6096 307 6097 274 6097 3090 6097 3090 6098 274 6098 2357 6098 3090 6099 2357 6099 3093 6099 3093 6100 2357 6100 2359 6100 2362 6101 3100 6101 2361 6101 2361 6102 3100 6102 3098 6102 2361 6103 3098 6103 2360 6103 2360 6104 3098 6104 3096 6104 2360 6105 3096 6105 2359 6105 2359 6106 3096 6106 3094 6106 2359 6107 3094 6107 3093 6107 2364 6108 2400 6108 2363 6108 2363 6109 2400 6109 3103 6109 2363 6110 3103 6110 2362 6110 2362 6111 3103 6111 3102 6111 2362 6112 3102 6112 3100 6112 3325 6113 3326 6113 3134 6113 3134 6114 3326 6114 3327 6114 3134 6115 3327 6115 3140 6115 3140 6116 3327 6116 3328 6116 3140 6117 3328 6117 3146 6117 3325 6118 3134 6118 3329 6118 3329 6119 3134 6119 3128 6119 3329 6120 3128 6120 3330 6120 3330 6121 3128 6121 3127 6121 3330 6122 3127 6122 3303 6122 257 6123 256 6123 3331 6123 3331 6124 256 6124 3114 6124 3331 498 3114 498 3332 498 3333 6125 3143 6125 3144 6125 3114 498 3113 498 3332 498 3332 6126 3113 6126 3141 6126 3332 498 3141 498 3333 498 3333 6127 3141 6127 3142 6127 3333 6128 3142 6128 3143 6128 3144 498 3145 498 3333 498 3333 498 3145 498 3146 498 3333 498 3146 498 3328 498 3334 6129 3312 6129 3335 6129 3335 6130 3312 6130 3314 6130 3336 6131 3334 6131 3335 6131 3336 6132 3335 6132 3337 6132 3337 6133 3335 6133 3338 6133 3338 6134 3335 6134 3339 6134 3170 6135 3340 6135 3341 6135 3341 6136 3342 6136 3170 6136 3170 6137 3342 6137 3343 6137 3170 6138 3343 6138 3344 6138 3344 6139 3339 6139 3170 6139 3170 6140 3339 6140 3335 6140 3170 6141 3335 6141 3314 6141 3169 6142 3173 6142 3345 6142 3345 6143 3346 6143 3169 6143 3169 6144 3346 6144 3347 6144 3169 6145 3347 6145 3170 6145 3170 6146 3347 6146 3348 6146 3170 6147 3348 6147 3340 6147 3173 6148 91 6148 90 6148 90 6149 98 6149 3173 6149 3173 6150 98 6150 97 6150 3173 6151 97 6151 3345 6151 3349 6152 3350 6152 3147 6152 3147 6153 3350 6153 3156 6153 3147 6154 3156 6154 2819 6154 3178 6155 3175 6155 3188 6155 3188 6156 3175 6156 3351 6156 3188 6157 3351 6157 3187 6157 3187 6158 3351 6158 3349 6158 3187 6159 3349 6159 3151 6159 3151 6160 3349 6160 3147 6160 3173 6161 3172 6161 91 6161 91 6162 3172 6162 3168 6162 91 6163 3168 6163 103 6163 103 6164 3168 6164 3167 6164 103 6165 3167 6165 112 6165 3167 6166 3166 6166 112 6166 112 6167 3166 6167 3165 6167 112 6168 3165 6168 3352 6168 3352 6169 3165 6169 3158 6169 3352 6170 3158 6170 3350 6170 3350 6171 3158 6171 3157 6171 3350 6172 3157 6172 3156 6172 3210 6173 411 6173 412 6173 221 6174 228 6174 412 6174 412 6175 228 6175 3211 6175 412 6176 3211 6176 3210 6176 3202 6177 414 6177 413 6177 411 6178 3210 6178 413 6178 413 6179 3210 6179 3203 6179 413 6180 3203 6180 3202 6180 3218 6181 3222 6181 409 6181 409 6182 3222 6182 391 6182 3218 6183 409 6183 3202 6183 3202 6184 409 6184 408 6184 3202 6185 408 6185 414 6185 3195 6186 3154 6186 2814 6186 3240 6187 3241 6187 391 6187 3250 6188 3251 6188 3222 6188 3222 6189 3251 6189 2886 6189 3222 6190 2886 6190 391 6190 391 6191 2886 6191 3239 6191 391 6192 3239 6192 3240 6192 3250 6193 3222 6193 3181 6193 3181 6194 3222 6194 3221 6194 3181 6195 3221 6195 3220 6195 3220 6196 3219 6196 3181 6196 3181 6197 3219 6197 3197 6197 3181 6198 3197 6198 2814 6198 2814 6199 3197 6199 3196 6199 2814 6200 3196 6200 3195 6200 3241 6201 3242 6201 391 6201 391 6202 3242 6202 3243 6202 391 6203 3243 6203 3244 6203 2842 6204 392 6204 3246 6204 3246 6205 392 6205 391 6205 3246 6206 391 6206 3245 6206 3245 6207 391 6207 3244 6207 3345 6208 97 6208 3353 6208 3353 6209 97 6209 99 6209 71 6210 69 6210 102 6210 102 6211 69 6211 3354 6211 102 6212 3354 6212 101 6212 101 6213 3354 6213 3355 6213 101 6214 3355 6214 99 6214 99 6215 3355 6215 3356 6215 99 6216 3356 6216 3353 6216 3357 6217 3358 6217 3353 6217 3353 6218 3358 6218 3346 6218 3353 6219 3346 6219 3345 6219 3354 6220 69 6220 2539 6220 3354 6221 2539 6221 3355 6221 3355 6222 2539 6222 3357 6222 3355 6223 3357 6223 3356 6223 3356 6224 3357 6224 3353 6224 3359 6225 2553 6225 3360 6225 3360 6226 2553 6226 2551 6226 2552 6227 2554 6227 3361 6227 3361 6228 3362 6228 2552 6228 2552 6229 3362 6229 3363 6229 2552 6230 3363 6230 2540 6230 2540 6231 3363 6231 3357 6231 2540 6232 3357 6232 2539 6232 3338 6233 3339 6233 3344 6233 3337 6234 3338 6234 3364 6234 3336 6235 3337 6235 3365 6235 2551 6236 3366 6236 3360 6236 3360 6237 3366 6237 3367 6237 3360 6238 3367 6238 3368 6238 3368 6239 3367 6239 3369 6239 3368 6240 3369 6240 3370 6240 3370 6241 3369 6241 3371 6241 3370 6242 3371 6242 3372 6242 3372 6243 3371 6243 3334 6243 3372 6244 3334 6244 3336 6244 3336 6245 3365 6245 3372 6245 3372 6246 3365 6246 3373 6246 3372 6247 3373 6247 3370 6247 3370 6248 3373 6248 3374 6248 3370 6249 3374 6249 3368 6249 3368 6250 3374 6250 3375 6250 3368 6251 3375 6251 3360 6251 3360 6252 3375 6252 3361 6252 3360 6253 3361 6253 3359 6253 3359 6254 3361 6254 2554 6254 3359 6255 2554 6255 2553 6255 3338 6256 3344 6256 3364 6256 3364 6257 3344 6257 3343 6257 3364 6258 3343 6258 3376 6258 3376 6259 3343 6259 3342 6259 3376 6260 3342 6260 3377 6260 3377 6261 3342 6261 3341 6261 3377 6262 3341 6262 3378 6262 3378 6263 3341 6263 3340 6263 3378 6264 3340 6264 3379 6264 3379 6265 3340 6265 3348 6265 3379 6266 3348 6266 3380 6266 3380 6267 3348 6267 3347 6267 3380 6268 3347 6268 3381 6268 3381 6269 3347 6269 3346 6269 3381 6270 3346 6270 3358 6270 3337 6271 3364 6271 3365 6271 3365 6272 3364 6272 3376 6272 3365 6273 3376 6273 3373 6273 3373 6274 3376 6274 3377 6274 3373 6275 3377 6275 3374 6275 3374 6276 3377 6276 3378 6276 3374 6277 3378 6277 3375 6277 3375 6278 3378 6278 3379 6278 3375 6279 3379 6279 3361 6279 3361 6280 3379 6280 3380 6280 3361 6281 3380 6281 3362 6281 3362 6282 3380 6282 3381 6282 3362 6283 3381 6283 3363 6283 3363 6284 3381 6284 3358 6284 3363 6285 3358 6285 3357 6285 2551 6286 2550 6286 3366 6286 3366 6287 2550 6287 2548 6287 3366 6288 2548 6288 3382 6288 3312 6289 3334 6289 3382 6289 3382 6290 3334 6290 3371 6290 3371 6291 3369 6291 3382 6291 3382 6292 3369 6292 3367 6292 3382 6293 3367 6293 3366 6293 2542 6294 2541 6294 3383 6294 2542 6295 3383 6295 2543 6295 2543 6296 3383 6296 3384 6296 3384 6297 3383 6297 3385 6297 3384 6298 3385 6298 3386 6298 3386 6299 3385 6299 3315 6299 3386 6300 3315 6300 3313 6300 2544 6301 2543 6301 3384 6301 2545 6302 3387 6302 2546 6302 2546 6303 3387 6303 3388 6303 2546 6304 3388 6304 2547 6304 3313 6305 3388 6305 3386 6305 3386 6306 3388 6306 3387 6306 3386 6307 3387 6307 3384 6307 3384 6308 3387 6308 2545 6308 3384 6309 2545 6309 2544 6309 3313 6310 3312 6310 3382 6310 3313 6311 3382 6311 3388 6311 3388 6312 3382 6312 2548 6312 3388 6313 2548 6313 2547 6313 3383 6314 2541 6314 2528 6314 3316 6315 3315 6315 3385 6315 3316 6316 3385 6316 3389 6316 3389 6317 3385 6317 3383 6317 3389 6318 3383 6318 3390 6318 3390 6319 3383 6319 2528 6319 3390 6320 2528 6320 2529 6320 3311 6321 3391 6321 3392 6321 2574 6322 2573 6322 3393 6322 2577 6323 2576 6323 3394 6323 3394 6324 2576 6324 2575 6324 3395 6325 2569 6325 2570 6325 2577 6326 3394 6326 2572 6326 2572 6327 3394 6327 3396 6327 2572 6328 3396 6328 2571 6328 2564 6329 2565 6329 3397 6329 3397 6330 2565 6330 2566 6330 3398 6331 2567 6331 3395 6331 3395 6332 2567 6332 2568 6332 3395 6333 2568 6333 2569 6333 3399 6334 2530 6334 2560 6334 3399 6335 2560 6335 3400 6335 2560 6336 2561 6336 3400 6336 3400 6337 2561 6337 2562 6337 3400 6338 2562 6338 3397 6338 3397 6339 2562 6339 2563 6339 3397 6340 2563 6340 2564 6340 3401 6341 3252 6341 3306 6341 2574 6342 3393 6342 3402 6342 3402 6343 3393 6343 3401 6343 3402 6344 3401 6344 3403 6344 3401 6345 3306 6345 3403 6345 3403 6346 3306 6346 3307 6346 3403 6347 3307 6347 3404 6347 3404 6348 3396 6348 3403 6348 3403 6349 3396 6349 3394 6349 3403 6350 3394 6350 3402 6350 3402 6351 3394 6351 2575 6351 3402 6352 2575 6352 2574 6352 3392 6353 3398 6353 3404 6353 3404 6354 3398 6354 3395 6354 3404 6355 3395 6355 3396 6355 3396 6356 3395 6356 2570 6356 3396 6357 2570 6357 2571 6357 3307 6358 3308 6358 3404 6358 3404 6359 3308 6359 3309 6359 3404 6360 3309 6360 3392 6360 3392 6361 3309 6361 3310 6361 3392 6362 3310 6362 3311 6362 3405 629 3399 629 3391 629 3391 6363 3399 6363 3400 6363 3391 6364 3400 6364 3392 6364 3392 6365 3400 6365 3397 6365 3392 6366 3397 6366 3398 6366 3398 6367 3397 6367 2566 6367 3398 6368 2566 6368 2567 6368 3333 6369 3328 6369 3406 6369 3333 6370 3406 6370 3407 6370 3407 6371 3406 6371 3408 6371 3407 6372 3408 6372 3409 6372 2557 6373 2556 6373 3408 6373 3408 6374 2556 6374 3410 6374 3408 6375 3410 6375 3409 6375 3326 6376 3325 6376 3411 6376 3329 6377 3330 6377 3412 6377 3413 6378 3414 6378 3415 6378 3415 6379 3414 6379 3416 6379 3417 6380 3418 6380 3419 6380 3420 6381 3421 6381 3422 6381 3422 6382 3421 6382 3423 6382 3424 6383 3425 6383 3426 6383 3426 6384 3425 6384 3427 6384 3428 6385 3429 6385 3430 6385 3430 6386 3429 6386 3431 6386 3432 6387 3433 6387 3434 6387 3412 6388 3434 6388 3426 6388 3426 6389 3434 6389 3433 6389 3426 6390 3433 6390 3424 6390 3330 6391 3303 6391 3412 6391 3412 6392 3303 6392 3435 6392 3412 6393 3435 6393 3434 6393 3434 6394 3435 6394 3436 6394 3434 6395 3436 6395 3432 6395 3432 6396 3436 6396 3437 6396 3411 6397 3430 6397 3417 6397 3417 6398 3430 6398 3431 6398 3417 6399 3431 6399 3418 6399 3427 6400 3428 6400 3426 6400 3426 6401 3428 6401 3430 6401 3426 6402 3430 6402 3412 6402 3412 6403 3430 6403 3411 6403 3412 6404 3411 6404 3329 6404 3329 6405 3411 6405 3325 6405 3438 6406 3422 6406 3439 6406 3439 6407 3422 6407 3423 6407 3439 6408 3423 6408 3440 6408 3419 6409 3420 6409 3417 6409 3417 6410 3420 6410 3422 6410 3417 6411 3422 6411 3411 6411 3411 6412 3422 6412 3438 6412 3411 6413 3438 6413 3326 6413 3326 6414 3438 6414 3327 6414 3406 6415 3415 6415 3408 6415 3408 6416 3415 6416 3416 6416 3408 6417 3416 6417 2557 6417 3328 6418 3327 6418 3406 6418 3406 6419 3327 6419 3438 6419 3406 6420 3438 6420 3415 6420 3415 6421 3438 6421 3439 6421 3415 6422 3439 6422 3413 6422 3413 6423 3439 6423 3440 6423 3303 6424 3304 6424 3441 6424 3303 6425 3441 6425 3435 6425 3435 6426 3441 6426 3442 6426 3435 6427 3442 6427 3436 6427 3436 6428 3442 6428 3443 6428 3436 6429 3443 6429 3437 6429 3444 6430 3443 6430 3445 6430 3445 6431 3443 6431 3442 6431 3445 6432 3442 6432 3446 6432 3446 6433 3442 6433 3441 6433 3446 6434 3441 6434 3305 6434 3305 6435 3441 6435 3304 6435 3444 6436 3445 6436 3447 6436 3444 6437 3447 6437 3448 6437 3448 6438 3447 6438 3449 6438 3448 6439 3449 6439 3450 6439 3450 6440 3449 6440 3451 6440 3450 6441 3451 6441 3452 6441 3452 6442 3451 6442 3453 6442 3452 6443 3453 6443 3454 6443 3454 6444 3453 6444 3455 6444 3454 6445 3455 6445 3456 6445 3446 6446 3305 6446 3300 6446 3445 6447 3446 6447 3457 6447 3446 6448 3300 6448 3457 6448 3457 6449 3300 6449 3299 6449 3457 6450 3299 6450 3458 6450 3458 6451 3299 6451 3302 6451 3458 6452 3302 6452 3459 6452 3459 6453 3302 6453 3301 6453 3459 6454 3301 6454 3460 6454 3460 6455 3301 6455 3298 6455 3460 6456 3298 6456 3461 6456 3445 6457 3457 6457 3447 6457 3447 6458 3457 6458 3458 6458 3447 6459 3458 6459 3449 6459 3449 6460 3458 6460 3459 6460 3449 6461 3459 6461 3451 6461 3451 6462 3459 6462 3460 6462 3451 6463 3460 6463 3453 6463 3453 6464 3460 6464 3461 6464 3453 6465 3461 6465 3455 6465 3462 6466 3456 6466 3463 6466 3463 6467 3456 6467 3455 6467 3463 6468 3455 6468 3464 6468 3464 6469 3455 6469 3461 6469 3464 6470 3461 6470 3297 6470 3297 6471 3461 6471 3298 6471 3465 6472 3462 6472 3466 6472 3466 6473 3462 6473 3463 6473 3466 6474 3463 6474 3467 6474 3467 6475 3463 6475 3464 6475 3467 6476 3464 6476 3263 6476 3263 6477 3464 6477 3297 6477 3468 6478 3469 6478 3470 6478 3470 6479 3469 6479 3471 6479 3470 6480 3471 6480 3472 6480 3472 6481 3471 6481 3465 6481 3472 6482 3465 6482 3466 6482 3467 6483 3263 6483 3265 6483 3466 6484 3467 6484 3473 6484 3467 6485 3265 6485 3473 6485 3473 6486 3265 6486 3268 6486 3473 6487 3268 6487 3474 6487 3474 6488 3268 6488 3267 6488 3474 6489 3267 6489 3475 6489 3466 6490 3473 6490 3472 6490 3472 6491 3473 6491 3474 6491 3472 6492 3474 6492 3470 6492 3470 6493 3474 6493 3475 6493 3470 6494 3475 6494 3468 6494 3476 6495 3477 6495 3478 6495 3477 6496 3468 6496 3478 6496 3478 6497 3468 6497 3475 6497 3478 6498 3475 6498 3270 6498 3270 6499 3475 6499 3267 6499 3270 6500 3287 6500 3478 6500 3478 6501 3287 6501 3479 6501 3478 6502 3479 6502 3476 6502 3476 6503 3479 6503 3480 6503 3480 6504 3481 6504 3482 6504 3482 6505 3481 6505 3483 6505 3482 6506 3483 6506 3484 6506 3483 6507 3485 6507 3484 6507 3484 6508 3485 6508 3486 6508 3484 6509 3486 6509 3487 6509 3479 6510 3287 6510 3273 6510 3479 6511 3273 6511 3488 6511 3488 6512 3273 6512 3272 6512 3488 6513 3272 6513 3489 6513 3489 6514 3272 6514 3262 6514 3489 6515 3262 6515 3490 6515 3480 6516 3479 6516 3481 6516 3481 6517 3479 6517 3488 6517 3481 6518 3488 6518 3483 6518 3483 6519 3488 6519 3489 6519 3483 6520 3489 6520 3485 6520 3485 6521 3489 6521 3490 6521 3485 6522 3490 6522 3486 6522 3491 6523 3487 6523 3492 6523 3492 6524 3487 6524 3486 6524 3492 6525 3486 6525 3493 6525 3493 6526 3486 6526 3490 6526 3493 6527 3490 6527 3261 6527 3261 6528 3490 6528 3262 6528 3494 6529 3491 6529 3495 6529 3495 6530 3491 6530 3492 6530 3495 6531 3492 6531 3496 6531 3496 6532 3492 6532 3493 6532 3496 6533 3493 6533 3259 6533 3259 6534 3493 6534 3261 6534 3494 6535 3495 6535 3497 6535 3494 6536 3497 6536 3498 6536 3498 6537 3497 6537 3499 6537 3498 6538 3499 6538 3500 6538 3500 6539 3499 6539 3501 6539 3500 6540 3501 6540 3502 6540 3502 6541 3501 6541 3503 6541 3502 6542 3503 6542 3504 6542 3504 6543 3503 6543 3505 6543 3504 6544 3505 6544 3506 6544 3496 6545 3259 6545 3258 6545 3495 6546 3496 6546 3507 6546 3496 6547 3258 6547 3507 6547 3507 6548 3258 6548 3257 6548 3507 6549 3257 6549 3508 6549 3508 6550 3257 6550 3256 6550 3508 6551 3256 6551 3509 6551 3509 6552 3256 6552 3255 6552 3509 6553 3255 6553 3510 6553 3510 6554 3255 6554 3254 6554 3510 6555 3254 6555 3511 6555 3495 6556 3507 6556 3497 6556 3497 6557 3507 6557 3508 6557 3497 6558 3508 6558 3499 6558 3499 6559 3508 6559 3509 6559 3499 6560 3509 6560 3501 6560 3501 6561 3509 6561 3510 6561 3501 6562 3510 6562 3503 6562 3503 6563 3510 6563 3511 6563 3503 6564 3511 6564 3505 6564 2573 6565 3512 6565 3513 6565 2573 6566 3513 6566 3393 6566 3393 6567 3513 6567 3514 6567 3393 6568 3514 6568 3401 6568 3401 6569 3514 6569 3253 6569 3401 6570 3253 6570 3252 6570 3254 6571 3253 6571 3511 6571 3511 6572 3253 6572 3514 6572 3511 6573 3514 6573 3505 6573 3505 6574 3514 6574 3513 6574 3505 6575 3513 6575 3506 6575 3506 6576 3513 6576 3512 6576 2531 6577 2530 6577 3515 6577 3515 6578 2530 6578 3399 6578 3515 6579 3399 6579 3516 6579 3516 6580 3399 6580 3405 6580 3516 6581 3405 6581 3517 6581 3517 6582 3405 6582 3391 6582 3517 6583 3391 6583 3320 6583 3320 6584 3391 6584 3311 6584 3320 6585 3317 6585 3517 6585 3517 6586 3317 6586 3518 6586 2532 6587 2531 6587 3519 6587 3519 6588 2531 6588 3515 6588 3519 6589 3515 6589 3518 6589 3518 6590 3515 6590 3516 6590 3518 6591 3516 6591 3517 6591 3317 6592 3318 6592 3518 6592 3518 6593 3318 6593 3520 6593 3518 6594 3520 6594 3519 6594 3519 6595 3520 6595 3521 6595 3519 6596 3521 6596 2532 6596 2532 6597 3521 6597 2533 6597 3318 6598 3319 6598 3520 6598 3520 6599 3319 6599 3522 6599 3520 6600 3522 6600 3521 6600 3521 6601 3522 6601 3523 6601 3521 6602 3523 6602 2533 6602 2533 6603 3523 6603 2534 6603 3319 6604 3324 6604 3524 6604 3319 6605 3524 6605 3522 6605 3522 6606 3524 6606 3525 6606 3522 6607 3525 6607 3523 6607 3523 6608 3525 6608 2535 6608 3523 6609 2535 6609 2534 6609 2538 6610 2537 6610 3526 6610 3526 6611 2537 6611 3527 6611 3526 6612 3527 6612 3528 6612 3528 6613 3527 6613 3529 6613 3528 6614 3529 6614 3321 6614 3321 6615 3529 6615 3322 6615 2537 6616 2536 6616 3527 6616 3527 6617 2536 6617 3530 6617 3527 6618 3530 6618 3529 6618 3529 6619 3530 6619 3531 6619 3529 6620 3531 6620 3322 6620 3322 6621 3531 6621 3323 6621 2536 6622 2535 6622 3530 6622 3530 6623 2535 6623 3525 6623 3530 6624 3525 6624 3531 6624 3531 6625 3525 6625 3524 6625 3531 6626 3524 6626 3323 6626 3323 6627 3524 6627 3324 6627 3532 6628 3410 6628 2556 6628 3333 6629 3407 6629 3533 6629 3533 6630 3407 6630 3409 6630 3333 6631 3533 6631 3332 6631 3332 6632 3533 6632 3534 6632 3332 6633 3534 6633 3331 6633 2559 6634 2558 6634 3535 6634 2556 6635 2555 6635 3532 6635 3532 6636 2555 6636 2559 6636 3532 6637 2559 6637 3536 6637 3536 6638 2559 6638 3535 6638 3536 6639 3535 6639 3537 6639 257 6640 3331 6640 3537 6640 3537 6641 3331 6641 3534 6641 3537 6642 3534 6642 3536 6642 3536 6643 3534 6643 3533 6643 3536 6644 3533 6644 3532 6644 3532 6645 3533 6645 3409 6645 3532 6646 3409 6646 3410 6646 3538 6647 259 6647 257 6647 254 6648 255 6648 3539 6648 2558 6649 254 6649 3535 6649 3535 6650 254 6650 3539 6650 3535 6651 3539 6651 3537 6651 257 6652 3537 6652 3538 6652 3538 6653 3537 6653 3539 6653 3538 6654 3539 6654 3540 6654 3540 6655 3539 6655 255 6655 3540 6656 255 6656 253 6656 260 6657 259 6657 3541 6657 3541 6658 259 6658 3538 6658 3541 6659 3538 6659 3542 6659 3542 6660 3538 6660 3540 6660 260 6661 3541 6661 263 6661 263 6662 3541 6662 292 6662 253 6663 252 6663 3540 6663 3540 6664 252 6664 292 6664 3540 6665 292 6665 3542 6665 3542 6666 292 6666 3541 6666 3321 6667 3316 6667 3389 6667 3321 6668 3389 6668 3528 6668 3528 6669 3389 6669 3390 6669 3528 6670 3390 6670 3526 6670 3526 6671 3390 6671 2529 6671 3526 6672 2529 6672 2538 6672 2573 6673 2182 6673 3512 6673 3512 6674 2182 6674 340 6674 3512 6675 340 6675 3506 6675 3506 6676 340 6676 339 6676 3506 6677 339 6677 3504 6677 3504 6678 339 6678 2137 6678 3504 6679 2137 6679 3502 6679 3502 6680 2137 6680 2139 6680 3502 6681 2139 6681 3500 6681 2139 6682 2140 6682 3500 6682 3500 6683 2140 6683 2142 6683 3500 6684 2142 6684 3498 6684 3498 6685 2142 6685 2143 6685 3498 6686 2143 6686 3494 6686 3494 6687 2143 6687 2108 6687 3494 6688 2108 6688 3491 6688 3491 6689 2108 6689 2110 6689 3491 6690 2110 6690 3487 6690 3487 6691 2110 6691 2111 6691 3487 6692 2111 6692 3484 6692 3484 6693 2111 6693 2112 6693 3484 6694 2112 6694 3482 6694 3482 6695 2112 6695 2113 6695 3482 6696 2113 6696 3480 6696 3480 6697 2113 6697 2114 6697 3480 6698 2114 6698 3476 6698 3476 6699 2114 6699 2239 6699 3476 6700 2239 6700 3477 6700 3477 6701 2239 6701 2118 6701 3471 6702 3469 6702 2118 6702 2118 6703 3469 6703 3468 6703 2118 6704 3468 6704 3477 6704 2118 6705 2122 6705 3471 6705 3471 6706 2122 6706 2123 6706 3471 6707 2123 6707 3465 6707 2123 6708 2125 6708 3465 6708 3465 6709 2125 6709 2124 6709 3465 6710 2124 6710 3462 6710 3462 6711 2124 6711 2119 6711 3462 6712 2119 6712 3456 6712 3456 6713 2119 6713 2121 6713 3456 6714 2121 6714 3454 6714 3454 6715 2121 6715 2155 6715 3454 6716 2155 6716 3452 6716 3452 6717 2155 6717 2157 6717 3452 6718 2157 6718 3450 6718 2215 6719 3437 6719 346 6719 346 6720 3437 6720 3443 6720 346 6721 3443 6721 347 6721 347 6722 3443 6722 3444 6722 347 6723 3444 6723 2161 6723 2161 6724 3444 6724 3448 6724 2161 6725 3448 6725 2160 6725 2160 6726 3448 6726 3450 6726 2160 6727 3450 6727 2158 6727 2158 6728 3450 6728 2157 6728 2237 6729 2236 6729 3425 6729 3437 6730 2215 6730 3432 6730 3432 6731 2215 6731 2214 6731 3432 6732 2214 6732 3433 6732 3433 6733 2214 6733 2237 6733 3433 6734 2237 6734 3424 6734 3424 6735 2237 6735 3425 6735 2233 6736 3431 6736 2234 6736 2234 6737 3431 6737 3429 6737 2234 6738 3429 6738 2235 6738 2235 6739 3429 6739 3428 6739 2235 6740 3428 6740 2236 6740 2236 6741 3428 6741 3427 6741 2236 6742 3427 6742 3425 6742 2231 6743 3420 6743 2232 6743 2232 6744 3420 6744 3419 6744 2232 6745 3419 6745 2233 6745 2233 6746 3419 6746 3418 6746 2233 6747 3418 6747 3431 6747 2557 6748 3416 6748 1472 6748 1472 6749 3416 6749 3414 6749 1472 6750 3414 6750 1473 6750 1473 6751 3414 6751 3413 6751 1473 6752 3413 6752 2229 6752 2229 6753 3413 6753 3440 6753 2229 6754 3440 6754 2230 6754 2230 6755 3440 6755 3423 6755 2230 6756 3423 6756 2231 6756 2231 6757 3423 6757 3421 6757 2231 6758 3421 6758 3420 6758 301 6759 303 6759 314 6759 314 6760 303 6760 294 6760 309 6761 264 6761 314 6761 314 6762 264 6762 262 6762 262 6763 291 6763 289 6763 249 6764 314 6764 251 6764 251 6765 314 6765 262 6765 251 6766 262 6766 288 6766 288 6767 262 6767 289 6767 294 6768 293 6768 314 6768 314 6769 293 6769 298 6769 314 6770 298 6770 309 6770 284 629 269 629 314 629 314 629 269 629 268 629 300 629 301 629 268 629 268 629 301 629 314 629 79 6771 3543 6771 141 6771 141 6772 3543 6772 3544 6772 141 6773 3544 6773 5 6773 64 6774 3545 6774 66 6774 66 6775 3545 6775 3543 6775 66 6776 3543 6776 78 6776 78 6777 3543 6777 79 6777 94 769 93 769 3545 769 64 769 76 769 3545 769 3545 6778 76 6778 96 6778 3545 6779 96 6779 94 6779 113 6780 112 6780 3544 6780 113 6781 3544 6781 114 6781 110 6782 109 6782 3543 6782 3543 6783 109 6783 108 6783 3543 6784 108 6784 3544 6784 3544 6785 108 6785 115 6785 3544 6786 115 6786 114 6786 93 6787 83 6787 3545 6787 3545 6788 83 6788 81 6788 3545 6789 81 6789 3543 6789 3543 6790 81 6790 111 6790 3543 6791 111 6791 110 6791 3350 6792 3 6792 5 6792 3544 6793 112 6793 5 6793 5 6794 112 6794 3352 6794 5 6795 3352 6795 3350 6795 17 6796 16 6796 3351 6796 3 6797 3350 6797 16 6797 16 6798 3350 6798 3349 6798 16 6799 3349 6799 3351 6799 3175 6800 6 6800 3351 6800 3351 6801 6 6801 14 6801 14 6802 12 6802 3351 6802 3351 6803 12 6803 10 6803 3351 6804 10 6804 17 6804 3546 6805 3547 6805 3548 6805 3548 6806 3547 6806 3549 6806 3550 548 3551 548 3552 548 3552 548 3551 548 3553 548 3550 6807 3552 6807 3554 6807 3554 6807 3552 6807 3555 6807 3554 6808 3555 6808 3556 6808 3556 6809 3555 6809 3557 6809 3556 6810 3557 6810 3558 6810 3558 6811 3557 6811 3559 6811 3558 6812 3559 6812 3560 6812 3560 6813 3559 6813 3561 6813 3561 769 3559 769 3557 769 3548 6814 3549 6814 3553 6814 3553 6815 3549 6815 3561 6815 3553 769 3561 769 3552 769 3552 769 3561 769 3557 769 3552 6816 3557 6816 3555 6816 3560 528 3561 528 3547 528 3547 528 3561 528 3549 528 3550 523 3560 523 3551 523 3551 6817 3560 6817 3547 6817 3551 523 3547 523 3546 523 3550 523 3554 523 3560 523 3560 523 3554 523 3556 523 3560 523 3556 523 3558 523 3546 6818 3548 6818 3551 6818 3551 6819 3548 6819 3553 6819 3562 769 3563 769 3564 769 3565 6820 3566 6820 3567 6820 3568 6821 3569 6821 3570 6821 3563 769 3571 769 3564 769 3564 6822 3571 6822 3572 6822 3564 6823 3572 6823 3573 6823 3574 769 3575 769 3576 769 3577 769 3578 769 3564 769 3564 769 3578 769 3568 769 3564 769 3568 769 3562 769 3562 769 3568 769 3570 769 3562 769 3570 769 3579 769 3580 769 3565 769 3577 769 3577 6824 3565 6824 3567 6824 3577 769 3567 769 3578 769 3578 769 3567 769 3574 769 3578 769 3574 769 3581 769 3581 6825 3574 6825 3576 6825 3582 523 3583 523 3584 523 3584 523 3583 523 3585 523 3586 6826 3587 6826 3588 6826 3589 523 3590 523 3591 523 3591 6827 3590 6827 3592 6827 3593 523 3583 523 3592 523 3592 523 3583 523 3582 523 3592 523 3582 523 3591 523 3594 523 3586 523 3585 523 3585 523 3586 523 3588 523 3585 523 3588 523 3584 523 3584 523 3588 523 3595 523 3593 523 3596 523 3583 523 3583 523 3596 523 3597 523 3583 523 3597 523 3598 523 3595 523 3599 523 3584 523 3584 6828 3599 6828 3600 6828 3584 523 3600 523 3601 523 3582 498 3584 498 3578 498 3578 498 3584 498 3568 498 3582 6829 3578 6829 3591 6829 3591 6830 3578 6830 3581 6830 3591 6831 3581 6831 3589 6831 3589 6832 3581 6832 3576 6832 3589 6833 3576 6833 3590 6833 3590 6834 3576 6834 3575 6834 3590 6835 3575 6835 3592 6835 3592 6836 3575 6836 3574 6836 3595 6837 3562 6837 3599 6837 3599 6838 3562 6838 3579 6838 3599 6839 3579 6839 3600 6839 3600 6839 3579 6839 3570 6839 3600 6840 3570 6840 3601 6840 3601 6841 3570 6841 3569 6841 3601 6842 3569 6842 3584 6842 3584 6843 3569 6843 3568 6843 3585 528 3583 528 3564 528 3564 528 3583 528 3577 528 3585 6844 3564 6844 3594 6844 3594 6845 3564 6845 3573 6845 3594 6846 3573 6846 3586 6846 3586 6847 3573 6847 3572 6847 3586 6848 3572 6848 3587 6848 3587 6848 3572 6848 3571 6848 3587 6849 3571 6849 3588 6849 3588 6849 3571 6849 3563 6849 3593 6850 3567 6850 3596 6850 3596 6850 3567 6850 3566 6850 3596 6808 3566 6808 3597 6808 3597 6809 3566 6809 3565 6809 3597 6810 3565 6810 3598 6810 3598 6811 3565 6811 3580 6811 3598 6812 3580 6812 3583 6812 3583 6813 3580 6813 3577 6813 3593 548 3592 548 3567 548 3567 548 3592 548 3574 548 3562 629 3595 629 3563 629 3563 629 3595 629 3588 629 3602 769 3603 769 3604 769 3604 769 3603 769 3605 769 3604 769 3605 769 3606 769 3607 769 3608 769 3604 769 3604 769 3608 769 3609 769 3604 769 3609 769 3602 769 3610 769 3611 769 3604 769 3604 769 3611 769 3612 769 3604 769 3612 769 3607 769 3606 769 3613 769 3604 769 3604 769 3613 769 3614 769 3604 769 3614 769 3610 769 3615 6851 3616 6851 3617 6851 3618 6852 3616 6852 3615 6852 3615 6853 3619 6853 3620 6853 3621 6854 3619 6854 3615 6854 3617 6855 3621 6855 3615 6855 3615 6856 3622 6856 3623 6856 3624 6857 3622 6857 3615 6857 3620 6858 3624 6858 3615 6858 3615 6859 3625 6859 3626 6859 3627 6860 3625 6860 3615 6860 3623 6861 3627 6861 3615 6861 3626 6862 3618 6862 3615 6862 3618 6863 3605 6863 3616 6863 3616 6864 3605 6864 3603 6864 3616 6865 3603 6865 3617 6865 3617 6866 3603 6866 3602 6866 3617 6867 3602 6867 3621 6867 3621 6868 3602 6868 3609 6868 3621 6869 3609 6869 3619 6869 3619 6870 3609 6870 3608 6870 3619 6871 3608 6871 3620 6871 3620 6872 3608 6872 3607 6872 3620 6873 3607 6873 3624 6873 3624 6874 3607 6874 3612 6874 3624 6875 3612 6875 3622 6875 3622 6876 3612 6876 3611 6876 3622 6877 3611 6877 3623 6877 3623 6878 3611 6878 3610 6878 3623 6879 3610 6879 3627 6879 3627 6880 3610 6880 3614 6880 3627 6881 3614 6881 3625 6881 3625 6882 3614 6882 3613 6882 3625 6883 3613 6883 3626 6883 3626 6884 3613 6884 3606 6884 3626 6885 3606 6885 3618 6885 3618 6886 3606 6886 3605 6886 3628 769 3629 769 3630 769 3630 6887 3629 6887 3631 6887 3630 6888 3631 6888 3632 6888 3633 769 3634 769 3635 769 3635 6889 3634 6889 3630 6889 3635 769 3630 769 3636 769 3636 769 3630 769 3632 769 3636 769 3632 769 3637 769 3638 6890 3639 6890 3640 6890 3640 6891 3641 6891 3638 6891 3638 6892 3641 6892 3642 6892 3638 6893 3642 6893 3643 6893 3644 6894 3645 6894 3646 6894 3646 6895 3645 6895 3647 6895 3646 6896 3647 6896 3648 6896 3644 6897 3649 6897 3645 6897 3645 6898 3649 6898 3650 6898 3645 6899 3650 6899 3651 6899 3651 6900 3652 6900 3645 6900 3645 6901 3652 6901 3638 6901 3645 6902 3638 6902 3653 6902 3653 6903 3638 6903 3643 6903 3654 6904 3639 6904 3638 6904 3648 6905 3655 6905 3646 6905 3646 6906 3655 6906 3656 6906 3646 6907 3656 6907 3644 6907 3656 6908 3657 6908 3644 6908 3644 6909 3657 6909 3658 6909 3644 6910 3658 6910 3649 6910 3649 6911 3658 6911 3659 6911 3659 6912 3660 6912 3649 6912 3649 6913 3660 6913 3661 6913 3649 6914 3661 6914 3650 6914 3650 6915 3661 6915 3662 6915 3650 6916 3662 6916 3651 6916 3651 6917 3662 6917 3663 6917 3651 6918 3663 6918 3652 6918 3663 6919 3664 6919 3652 6919 3652 6920 3664 6920 3665 6920 3652 6921 3665 6921 3638 6921 3638 6922 3665 6922 3666 6922 3638 6923 3666 6923 3654 6923 3667 6924 3633 6924 3635 6924 3639 6925 3637 6925 3640 6925 3640 6926 3637 6926 3632 6926 3640 6927 3632 6927 3631 6927 3643 6928 3642 6928 3631 6928 3631 6929 3642 6929 3641 6929 3631 6930 3641 6930 3640 6930 3629 6931 3628 6931 3668 6931 3631 6932 3629 6932 3643 6932 3643 6933 3629 6933 3668 6933 3643 6934 3668 6934 3653 6934 3653 6935 3668 6935 3669 6935 3653 6936 3669 6936 3645 6936 3645 6937 3669 6937 3670 6937 3671 6938 3648 6938 3670 6938 3670 6939 3648 6939 3647 6939 3670 6940 3647 6940 3645 6940 3672 6941 3673 6941 3674 6941 3675 6942 3660 6942 3674 6942 3674 6943 3660 6943 3659 6943 3674 6944 3659 6944 3672 6944 3672 6945 3659 6945 3658 6945 3672 6946 3658 6946 3676 6946 3658 6947 3657 6947 3676 6947 3676 6948 3657 6948 3656 6948 3676 6949 3656 6949 3671 6949 3671 6950 3656 6950 3655 6950 3671 6951 3655 6951 3648 6951 3636 6952 3664 6952 3635 6952 3635 6953 3664 6953 3663 6953 3635 6954 3663 6954 3667 6954 3667 6955 3663 6955 3662 6955 3667 6956 3662 6956 3675 6956 3675 6957 3662 6957 3661 6957 3675 6958 3661 6958 3660 6958 3639 6959 3654 6959 3637 6959 3637 6960 3654 6960 3666 6960 3637 6961 3666 6961 3636 6961 3636 6962 3666 6962 3665 6962 3636 6963 3665 6963 3664 6963 3667 769 3675 769 3674 769 3634 528 3633 528 3677 528 3677 528 3633 528 3667 528 3677 528 3667 528 3673 528 3673 528 3667 528 3674 528 3630 548 3678 548 3628 548 3628 548 3678 548 3668 548 3634 6964 3677 6964 3630 6964 3630 6964 3677 6964 3678 6964 3669 769 3668 769 3678 769 3677 6965 3673 6965 3678 6965 3678 6966 3673 6966 3672 6966 3678 769 3672 769 3676 769 3676 769 3671 769 3678 769 3678 6967 3671 6967 3670 6967 3678 769 3670 769 3669 769 3679 629 3680 629 3681 629 3681 629 3680 629 3682 629 3683 548 3684 548 3685 548 3685 548 3684 548 3686 548 3687 6968 3688 6968 3689 6968 3689 6969 3688 6969 3690 6969 3689 6970 3690 6970 3691 6970 3691 6971 3690 6971 3692 6971 3691 6972 3692 6972 3685 6972 3685 6973 3692 6973 3683 6973 3688 6974 3687 6974 3693 6974 3694 528 3695 528 3696 528 3694 528 3696 528 3697 528 3697 528 3696 528 3698 528 3697 528 3698 528 3699 528 3699 6975 3698 6975 3700 6975 3699 6976 3700 6976 3701 6976 3701 6977 3700 6977 3702 6977 3701 6978 3702 6978 3693 6978 3693 6979 3702 6979 3703 6979 3693 6980 3703 6980 3688 6980 3685 769 3686 769 3679 769 3679 769 3681 769 3694 769 3691 769 3685 769 3689 769 3689 769 3685 769 3679 769 3689 769 3679 769 3687 769 3687 6981 3679 6981 3694 6981 3701 769 3693 769 3699 769 3699 6982 3693 6982 3687 6982 3699 769 3687 769 3697 769 3697 769 3687 769 3694 769 3700 523 3698 523 3684 523 3682 523 3680 523 3695 523 3695 6983 3680 6983 3684 6983 3695 523 3684 523 3696 523 3696 6984 3684 6984 3698 6984 3683 523 3692 523 3690 523 3690 523 3688 523 3683 523 3683 6985 3688 6985 3703 6985 3683 523 3703 523 3684 523 3684 523 3703 523 3702 523 3684 6986 3702 6986 3700 6986 3679 498 3686 498 3680 498 3680 498 3686 498 3684 498 3682 528 3695 528 3681 528 3681 528 3695 528 3694 528

+
+
+
+
+ + + + 1 -8.74228e-8 8.74228e-8 0 8.74228e-8 4.37114e-8 -1 0 8.74228e-8 1 4.37114e-8 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_E3M5.dae b/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_E3M5.dae new file mode 100644 index 0000000..b9039a1 --- /dev/null +++ b/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_E3M5.dae @@ -0,0 +1,107 @@ + + + + + + Blender User + Blender 2.82.7 + + 2022-03-18T13:40:55 + 2022-03-18T13:40:55 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.80848 0.80848 0.80848 1 + + + 1 + + + + + + + + + + + + + + + + + -67.48848 0 -1.247326 -67.3963 5 -3.740275 -67.3963 0 -3.740275 -67.21206 5 -6.228115 -67.21206 0 -6.228115 -66.93602 5 -8.707448 -66.93602 0 -8.707448 -66.56855 5 -11.17489 -66.56855 0 -11.17489 -66.11016 5 -13.62706 -66.11016 0 -13.62706 -65.56147 5 -16.06063 -65.56147 0 -16.06063 -64.92324 5 -18.47225 -64.92324 0 -18.47225 -64.19632 5 -20.85865 -64.19632 0 -20.85865 -63.38172 5 -23.21655 -63.38172 0 -23.21655 -62.48054 5 -25.54275 -62.48054 0 -25.54275 -61.49403 5 -27.83405 -61.49403 0 -27.83405 -60.42352 5 -30.08734 -60.42352 0 -30.08734 -59.27048 5 -32.29953 -59.27048 0 -32.29953 -58.03649 5 -34.4676 -58.03649 0 -34.4676 -56.72322 5 -36.5886 -56.72322 0 -36.5886 -55.33248 5 -38.65962 -55.33248 0 -38.65962 -53.86616 5 -40.67784 -53.86616 0 -40.67784 -52.32627 5 -42.64049 -52.32627 0 -42.64049 -50.7149 5 -44.54491 -50.7149 0 -44.54491 -49.03427 5 -46.38848 -49.03427 0 -46.38848 -47.28665 5 -48.16868 -47.28665 0 -48.16868 -45.47445 5 -49.8831 -45.47445 0 -49.8831 -43.60015 5 -51.52938 -43.60015 0 -51.52938 -41.66628 5 -53.10528 -41.66628 0 -53.10528 -39.6755 5 -54.60865 -39.6755 0 -54.60865 -37.63053 5 -56.03742 -37.63053 0 -56.03742 -35.53417 5 -57.38965 -35.53417 0 -57.38965 -33.38927 5 -58.6635 -33.38927 0 -58.6635 -31.19876 5 -59.85722 -31.19876 0 -59.85722 -28.96564 5 -60.96918 -28.96564 0 -60.96918 -26.69296 5 -61.99787 -26.69296 0 -61.99787 -24.38381 5 -62.94188 -24.38381 0 -62.94188 -22.04136 5 -63.79991 -22.04136 0 -63.79991 -19.66881 5 -64.5708 -19.66881 0 -64.5708 -17.26939 5 -65.25349 -17.26939 0 -65.25349 -14.84638 5 -65.84706 -14.84638 0 -65.84706 -12.40309 5 -66.35069 -12.40309 0 -66.35069 -9.942866 5 -66.76369 -9.942866 0 -66.76369 -7.469056 5 -67.08549 -7.469056 0 -67.08549 -4.985045 5 -67.31567 -4.985045 0 -67.31567 -2.494226 5 -67.4539 -2.494226 0 -67.4539 0 5 -67.5 0 0 -67.5 2.494226 5 -67.4539 -67.48848 5 -1.247326 -67.48848 0 1.247326 -67.48848 5 1.247326 -67.3963 0 3.740275 -67.3963 5 3.740275 -67.21206 0 6.228115 -67.21206 5 6.228115 -66.93602 0 8.707448 -66.93602 5 8.707448 -66.56855 0 11.17489 -66.56855 5 11.17489 -66.11016 0 13.62706 -66.11016 5 13.62706 -65.56147 0 16.06063 -65.56147 5 16.06063 -64.92324 0 18.47225 -64.92324 5 18.47225 -64.19632 0 20.85865 -64.19632 5 20.85865 -63.38172 0 23.21655 -63.38172 5 23.21655 -62.48054 0 25.54275 -62.48054 5 25.54275 -61.49403 0 27.83405 -61.49403 5 27.83405 -60.42352 0 30.08734 -60.42352 5 30.08734 -59.27048 0 32.29953 -59.27048 5 32.29953 -58.03649 0 34.4676 -58.03649 5 34.4676 -56.72322 0 36.5886 -56.72322 5 36.5886 -55.33248 0 38.65962 -55.33248 5 38.65962 -53.86616 0 40.67784 -53.86616 5 40.67784 -52.32627 0 42.64049 -52.32627 5 42.64049 -50.7149 0 44.54491 -50.7149 5 44.54491 -49.03427 0 46.38848 -49.03427 5 46.38848 -47.28665 0 48.16868 -47.28665 5 48.16868 -45.47445 0 49.8831 -45.47445 5 49.8831 -43.60015 0 51.52938 -43.60015 5 51.52938 -41.66628 0 53.10528 -41.66628 5 53.10528 -39.6755 0 54.60865 -39.6755 5 54.60865 -37.63053 0 56.03742 -37.63053 5 56.03742 -35.53417 0 57.38965 -35.53417 5 57.38965 -33.38927 0 58.6635 -33.38927 5 58.6635 -31.19876 0 59.85722 -31.19876 5 59.85722 -28.96564 0 60.96918 -28.96564 5 60.96918 -26.69296 0 61.99787 -26.69296 5 61.99787 -24.38381 0 62.94188 -24.38381 5 62.94188 -22.04136 0 63.79991 -22.04136 5 63.79991 -19.66881 0 64.5708 -19.66881 5 64.5708 -17.26939 0 65.25349 -17.26939 5 65.25349 -14.84638 0 65.84706 -14.84638 5 65.84706 -12.40309 0 66.35069 -12.40309 5 66.35069 -9.942866 0 66.76369 -9.942866 5 66.76369 -7.469056 0 67.08549 -7.469056 5 67.08549 -4.985045 0 67.31567 -4.985045 5 67.31567 -2.494226 0 67.4539 -2.494226 5 67.4539 0 0 67.5 0 5 67.5 2.494226 0 67.4539 2.494226 5 67.4539 4.985045 0 67.31567 4.985045 5 67.31567 7.469056 0 67.08549 7.469056 5 67.08549 9.942866 0 66.76369 9.942866 5 66.76369 12.40309 0 66.35069 12.40309 5 66.35069 14.84638 0 65.84706 14.84638 5 65.84706 17.26939 0 65.25349 17.26939 5 65.25349 19.66881 0 64.5708 19.66881 5 64.5708 22.04136 0 63.79991 22.04136 5 63.79991 24.38381 0 62.94188 24.38381 5 62.94188 26.69296 0 61.99787 26.69296 5 61.99787 28.96564 0 60.96918 28.96564 5 60.96918 31.19876 0 59.85722 31.19876 5 59.85722 33.38927 0 58.6635 33.38927 5 58.6635 35.53417 0 57.38965 35.53417 5 57.38965 37.63053 0 56.03742 37.63053 5 56.03742 39.6755 0 54.60865 39.6755 5 54.60865 41.66628 0 53.10528 41.66628 5 53.10528 43.60015 0 51.52938 43.60015 5 51.52938 45.47445 0 49.8831 45.47445 5 49.8831 47.28665 0 48.16868 47.28665 5 48.16868 49.03427 0 46.38848 49.03427 5 46.38848 50.7149 0 44.54491 50.7149 5 44.54491 52.32627 0 42.64049 52.32627 5 42.64049 53.86616 0 40.67784 53.86616 5 40.67784 55.33248 0 38.65962 55.33248 5 38.65962 56.72322 0 36.5886 56.72322 5 36.5886 58.03649 0 34.4676 58.03649 5 34.4676 59.27048 0 32.29953 59.27048 5 32.29953 60.42352 0 30.08734 60.42352 5 30.08734 61.49403 0 27.83405 61.49403 5 27.83405 62.48054 0 25.54275 62.48054 5 25.54275 63.38172 0 23.21655 63.38172 5 23.21655 64.19632 0 20.85865 64.19632 5 20.85865 64.92324 0 18.47225 64.92324 5 18.47225 65.56147 0 16.06063 65.56147 5 16.06063 66.11016 0 13.62706 66.11016 5 13.62706 66.56855 0 11.17489 66.56855 5 11.17489 66.93602 0 8.707448 66.93602 5 8.707448 67.21206 0 6.228115 67.21206 5 6.228115 67.3963 0 3.740275 67.3963 5 3.740275 67.48848 0 1.247326 67.48848 5 1.247326 67.48848 0 -1.247326 67.48848 5 -1.247326 67.3963 0 -3.740275 67.3963 5 -3.740275 67.21206 0 -6.228115 67.21206 5 -6.228115 66.93602 0 -8.707448 66.93602 5 -8.707448 66.56855 0 -11.17489 66.56855 5 -11.17489 66.11016 0 -13.62706 66.11016 5 -13.62706 65.56147 0 -16.06063 65.56147 5 -16.06063 64.92324 0 -18.47225 64.92324 5 -18.47225 64.19632 0 -20.85865 64.19632 5 -20.85865 63.38172 0 -23.21655 63.38172 5 -23.21655 62.48054 0 -25.54275 62.48054 5 -25.54275 61.49403 0 -27.83405 61.49403 5 -27.83405 60.42352 0 -30.08734 60.42352 5 -30.08734 59.27048 0 -32.29953 59.27048 5 -32.29953 58.03649 0 -34.4676 58.03649 5 -34.4676 56.72322 0 -36.5886 56.72322 5 -36.5886 55.33248 0 -38.65962 55.33248 5 -38.65962 53.86616 0 -40.67784 53.86616 5 -40.67784 52.32627 0 -42.64049 52.32627 5 -42.64049 50.7149 0 -44.54491 50.7149 5 -44.54491 49.03427 0 -46.38848 49.03427 5 -46.38848 47.28665 0 -48.16868 47.28665 5 -48.16868 45.47445 0 -49.8831 45.47445 5 -49.8831 43.60015 0 -51.52938 43.60015 5 -51.52938 41.66628 0 -53.10528 41.66628 5 -53.10528 39.6755 0 -54.60865 39.6755 5 -54.60865 37.63053 0 -56.03742 37.63053 5 -56.03742 35.53417 0 -57.38965 35.53417 5 -57.38965 33.38927 0 -58.6635 33.38927 5 -58.6635 31.19876 0 -59.85722 31.19876 5 -59.85722 28.96564 0 -60.96918 28.96564 5 -60.96918 26.69296 0 -61.99787 26.69296 5 -61.99787 24.38381 0 -62.94188 24.38381 5 -62.94188 22.04136 0 -63.79991 22.04136 5 -63.79991 19.66881 0 -64.5708 19.66881 5 -64.5708 17.26939 0 -65.25349 17.26939 5 -65.25349 14.84638 0 -65.84706 14.84638 5 -65.84706 12.40309 0 -66.35069 12.40309 5 -66.35069 9.942866 0 -66.76369 9.942866 5 -66.76369 7.469056 0 -67.08549 7.469056 5 -67.08549 4.985045 0 -67.31567 4.985045 5 -67.31567 2.494226 0 -67.4539 32.0355 8 6.040412 63.60995 8 10.67823 32.31158 8 4.326852 63.96108 8 8.32045 32.49607 8 2.601027 32.58845 8 -0.867829 64.4009 8 -3.57404 32.49607 8 -2.601027 64.22486 8 -5.951309 32.31158 8 -4.326852 -3.465168 8 32.41531 -4.763488 8 64.32387 -1.735043 8 32.55379 -2.383372 8 64.45595 0 8 32.6 0 8 64.5 1.735043 8 32.55379 63.96108 8 -8.32045 63.60995 8 -10.67823 32.0355 8 -6.040412 63.17193 8 -13.02141 31.66862 8 -7.736851 62.64762 8 -15.34682 31.21196 8 -9.411357 64.22486 8 5.951309 64.4009 8 3.57404 32.58845 8 0.867829 64.48899 8 1.191889 64.48899 8 -1.191889 2.383372 8 64.45595 4.763488 8 64.32387 3.465168 8 32.41531 7.137098 8 64.10392 5.18547 8 32.18495 -6.891074 8 31.86335 -11.85184 8 63.40177 -5.18547 8 32.18495 -9.500961 8 63.79641 -7.137098 8 64.10392 -5.18547 8 -32.18495 -11.85184 8 -63.40177 -6.891074 8 -31.86335 -14.18654 8 -62.92052 -8.577144 8 -31.45143 29.31758 8 14.25622 58.76096 8 26.59698 30.03477 8 12.67567 59.70363 8 24.40751 30.66683 8 11.05919 -10.2389 8 30.95036 -18.79464 8 61.70098 -8.577144 8 31.45143 -16.50186 8 62.35334 -14.18654 8 62.92052 -18.02128 8 27.16603 -33.95487 8 54.839 -16.54991 8 28.08666 -31.9053 8 56.05624 -15.03162 8 28.92768 -29.81215 8 57.1969 -13.47072 8 29.68669 -20.80676 8 25.09659 -39.81444 8 50.74505 -19.44158 8 26.1684 -37.91215 8 52.1816 -35.95807 8 53.54687 -23.35649 8 22.74279 -45.18502 8 46.02785 -22.11297 8 23.95364 -43.45337 8 47.66608 -41.66236 8 49.23919 -11.87164 8 -30.36156 -25.5066 8 -59.24241 -13.47072 8 -29.68669 -27.67828 8 -58.25944 -15.03162 8 -28.92768 -29.81215 8 -57.1969 -16.54991 8 -28.08666 -16.50186 8 -62.35334 -18.79464 8 -61.70098 -10.2389 8 -30.95036 -21.06175 8 -60.96435 -23.30009 8 -60.14446 60.56475 8 22.18471 61.34314 8 19.9316 31.21196 8 9.411357 62.03775 8 17.65126 31.66862 8 7.736851 62.64762 8 15.34682 63.17193 8 13.02141 27.63614 8 17.29172 55.45709 8 32.93571 28.51728 8 15.79636 56.63624 8 30.864 57.73803 8 28.75012 25.64158 8 20.1313 51.47211 8 38.86993 26.67667 8 18.73807 52.87326 8 36.94142 54.20219 8 34.96244 22.11297 8 23.95364 45.18502 8 46.02785 23.35649 8 22.74279 46.85496 8 44.32677 24.53381 8 21.46747 48.46091 8 42.56513 50.00065 8 40.74536 9.500961 8 63.79641 11.85184 8 63.40177 6.891074 8 31.86335 14.18654 8 62.92052 8.577144 8 31.45143 -25.64158 8 -20.1313 -51.47211 8 -38.86993 -26.67667 8 -18.73807 -52.87326 8 -36.94142 -27.63614 8 -17.29172 -22.11297 8 -23.95364 -45.18502 8 -46.02785 -23.35649 8 -22.74279 -46.85496 8 -44.32677 -24.53381 8 -21.46747 -48.46091 8 -42.56513 -50.00065 8 -40.74536 6.891074 8 -31.86335 11.85184 8 -63.40177 5.18547 8 -32.18495 9.500961 8 -63.79641 3.465168 8 -32.41531 20.80676 8 -25.09659 39.81444 8 -50.74505 19.44158 8 -26.1684 37.91215 8 -52.1816 18.02128 8 -27.16603 19.44158 8 26.1684 39.81444 8 50.74505 20.80676 8 25.09659 41.66236 8 49.23919 43.45337 8 47.66608 16.54991 8 28.08666 33.95487 8 54.839 18.02128 8 27.16603 35.95807 8 53.54687 37.91215 8 52.1816 11.87164 8 30.36156 25.5066 8 59.24241 13.47072 8 29.68669 27.67828 8 58.25944 15.03162 8 28.92768 29.81215 8 57.1969 31.9053 8 56.05624 -27.67828 8 58.25944 -25.5066 8 59.24241 -11.87164 8 30.36156 -23.30009 8 60.14446 -21.06175 8 60.96435 -32.58845 8 0.867829 -64.4009 8 3.57404 -32.49607 8 2.601027 -64.22486 8 5.951309 -32.31158 8 4.326852 -31.9053 8 -56.05624 -33.95487 8 -54.839 -18.02128 8 -27.16603 -35.95807 8 -53.54687 -19.44158 8 -26.1684 -1.735043 8 -32.55379 -4.763488 8 -64.32387 -3.465168 8 -32.41531 -7.137098 8 -64.10392 -9.500961 8 -63.79641 7.137098 8 -64.10392 4.763488 8 -64.32387 1.735043 8 -32.55379 2.383372 8 -64.45595 0 8 -32.6 0 8 -64.5 -2.383372 8 -64.45595 35.95807 8 -53.54687 33.95487 8 -54.839 16.54991 8 -28.08666 31.9053 8 -56.05624 15.03162 8 -28.92768 29.81215 8 -57.1969 13.47072 8 -29.68669 23.35649 8 -22.74279 45.18502 8 -46.02785 22.11297 8 -23.95364 43.45337 8 -47.66608 41.66236 8 -49.23919 16.50186 8 62.35334 18.79464 8 61.70098 10.2389 8 30.95036 21.06175 8 60.96435 23.30009 8 60.14446 -63.96108 8 8.32045 -63.60995 8 10.67823 -32.0355 8 6.040412 -63.17193 8 13.02141 -31.66862 8 7.736851 -62.64762 8 15.34682 -31.21196 8 9.411357 -37.91215 8 -52.1816 -39.81444 8 -50.74505 -20.80676 8 -25.09659 -41.66236 8 -49.23919 -43.45337 8 -47.66608 10.2389 8 -30.95036 18.79464 8 -61.70098 8.577144 8 -31.45143 16.50186 8 -62.35334 14.18654 8 -62.92052 27.67828 8 -58.25944 25.5066 8 -59.24241 11.87164 8 -30.36156 23.30009 8 -60.14446 21.06175 8 -60.96435 30.03477 8 -12.67567 58.76096 8 -26.59698 29.31758 8 -14.25622 57.73803 8 -28.75012 28.51728 8 -15.79636 -28.51728 8 15.79636 -55.45709 8 32.93571 -27.63614 8 17.29172 -54.20219 8 34.96244 -26.67667 8 18.73807 -32.49607 8 -2.601027 -64.4009 8 -3.57404 -32.58845 8 -0.867829 -64.48899 8 -1.191889 -64.48899 8 1.191889 -54.20219 8 -34.96244 -55.45709 8 -32.93571 -28.51728 8 -15.79636 -56.63624 8 -30.864 -29.31758 8 -14.25622 26.67667 8 -18.73807 51.47211 8 -38.86993 25.64158 8 -20.1313 50.00065 8 -40.74536 24.53381 8 -21.46747 48.46091 8 -42.56513 46.85496 8 -44.32677 56.63624 8 -30.864 55.45709 8 -32.93571 27.63614 8 -17.29172 54.20219 8 -34.96244 52.87326 8 -36.94142 62.03775 8 -17.65126 61.34314 8 -19.9316 30.66683 8 -11.05919 60.56475 8 -22.18471 59.70363 8 -24.40751 -52.87326 8 36.94142 -51.47211 8 38.86993 -25.64158 8 20.1313 -50.00065 8 40.74536 -24.53381 8 21.46747 -48.46091 8 42.56513 -46.85496 8 44.32677 -32.0355 8 -6.040412 -63.60995 8 -10.67823 -32.31158 8 -4.326852 -63.96108 8 -8.32045 -64.22486 8 -5.951309 -30.66683 8 -11.05919 -61.34314 8 -19.9316 -31.21196 8 -9.411357 -62.03775 8 -17.65126 -31.66862 8 -7.736851 -62.64762 8 -15.34682 -63.17193 8 -13.02141 -30.03477 8 12.67567 -58.76096 8 26.59698 -29.31758 8 14.25622 -57.73803 8 28.75012 -56.63624 8 30.864 -62.03775 8 17.65126 -61.34314 8 19.9316 -30.66683 8 11.05919 -60.56475 8 22.18471 -59.70363 8 24.40751 -57.73803 8 -28.75012 -58.76096 8 -26.59698 -30.03477 8 -12.67567 -59.70363 8 -24.40751 -60.56475 8 -22.18471 0 0 67.5 0 0 0 0 5 67.5 0 8 64.5 1.681821 7 31.55521 1.71079 6 31.55366 0 6 31.6 1.71079 7 31.55366 3.358874 7 31.42098 3.416561 6 31.41476 3.416561 7 31.41476 5.026407 7 31.19768 5.112311 6 31.18372 5.112311 7 31.18372 6.679691 7 30.88595 6.793066 6 30.86121 6.793066 7 30.86121 8.314042 7 30.48666 8.453896 6 30.44818 8.453896 7 30.44818 9.924825 7 30.00097 10.08993 6 29.94584 10.08993 7 29.94584 11.50747 7 29.43022 11.69637 6 29.35566 11.69637 7 29.35566 13.0575 7 28.77606 13.2685 6 28.67938 13.2685 7 28.67938 14.57052 7 28.04033 14.80171 6 27.91898 14.80171 7 27.91898 16.04224 7 27.22511 16.2915 6 27.07669 16.2915 7 27.07669 17.46848 7 26.33272 17.73351 6 26.15497 17.73351 7 26.15497 18.84521 7 25.36569 19.12351 6 25.15654 19.12351 7 25.15654 20.16852 7 24.32676 20.45741 6 24.08432 20.45741 7 24.08432 21.43465 7 23.21886 21.7313 6 22.94146 21.7313 7 22.94146 22.64003 7 22.04516 22.94146 6 21.7313 22.94146 7 21.7313 23.78124 7 20.80896 24.08432 6 20.45741 24.08432 7 20.45741 24.85503 7 19.51378 25.15654 6 19.12351 25.15654 7 19.12351 25.85837 7 18.16328 26.15497 6 17.73351 26.15497 7 17.73351 26.78841 7 16.7613 27.07669 6 16.2915 27.07669 7 16.2915 27.91898 6 14.80171 27.64251 7 15.31181 27.91898 7 14.80171 28.67938 6 13.2685 28.41826 7 13.81891 28.67938 7 13.2685 29.35566 6 11.69637 29.11346 7 12.28684 29.35566 7 11.69637 29.94584 6 10.08993 29.72613 7 10.71995 29.94584 7 10.08993 30.44818 6 8.453896 30.25454 7 9.122667 30.44818 7 8.453896 30.86121 6 6.793066 30.69719 7 7.499524 30.86121 7 6.793066 31.18372 6 5.112311 31.05282 7 5.855123 31.18372 7 5.112311 31.41476 6 3.416561 31.32043 7 4.194127 31.41476 7 3.416561 31.55366 6 1.71079 31.49926 7 2.521241 31.55366 7 1.71079 31.6 6 0 31.5888 7 0.8412085 31.6 7 0 31.5888 7 -0.8412085 31.55366 6 -1.71079 31.55366 7 -1.71079 31.49926 7 -2.521241 31.41476 6 -3.416561 31.41476 7 -3.416561 31.32043 7 -4.194127 31.18372 6 -5.112311 31.18372 7 -5.112311 31.05282 7 -5.855123 30.86121 6 -6.793066 30.86121 7 -6.793066 30.69719 7 -7.499524 30.44818 6 -8.453896 30.44818 7 -8.453896 30.25454 7 -9.122667 29.94584 6 -10.08993 29.94584 7 -10.08993 29.72613 7 -10.71995 29.35566 6 -11.69637 29.35566 7 -11.69637 29.11346 7 -12.28684 28.67938 6 -13.2685 28.67938 7 -13.2685 28.41826 7 -13.81891 27.91898 6 -14.80171 27.91898 7 -14.80171 27.64251 7 -15.31181 27.07669 6 -16.2915 27.07669 7 -16.2915 26.78841 7 -16.7613 26.15497 6 -17.73351 26.15497 7 -17.73351 25.85837 7 -18.16328 25.15654 6 -19.12351 25.15654 7 -19.12351 24.85503 7 -19.51378 24.08432 6 -20.45741 24.08432 7 -20.45741 23.78124 7 -20.80896 22.94146 6 -21.7313 22.94146 7 -21.7313 22.64003 7 -22.04516 21.7313 6 -22.94146 21.7313 7 -22.94146 21.43465 7 -23.21886 20.45741 6 -24.08432 20.45741 7 -24.08432 20.16852 7 -24.32676 19.12351 6 -25.15654 19.12351 7 -25.15654 18.84521 7 -25.36569 17.73351 6 -26.15497 17.73351 7 -26.15497 17.46848 7 -26.33272 16.2915 6 -27.07669 16.2915 7 -27.07669 16.04224 7 -27.22511 14.80171 6 -27.91898 14.80171 7 -27.91898 14.57052 7 -28.04033 13.2685 6 -28.67938 13.2685 7 -28.67938 13.0575 7 -28.77606 11.69637 6 -29.35566 11.69637 7 -29.35566 11.50747 7 -29.43022 10.08993 6 -29.94584 10.08993 7 -29.94584 9.924825 7 -30.00097 8.453896 6 -30.44818 8.453896 7 -30.44818 8.314042 7 -30.48666 6.793066 6 -30.86121 6.793066 7 -30.86121 6.679691 7 -30.88595 5.112311 6 -31.18372 5.112311 7 -31.18372 5.026407 7 -31.19768 3.416561 6 -31.41476 3.416561 7 -31.41476 3.358874 7 -31.42098 1.71079 6 -31.55366 1.71079 7 -31.55366 1.681821 7 -31.55521 0 6 -31.6 0 7 -31.6 -1.681821 7 -31.55521 -1.71079 6 -31.55366 -1.71079 7 -31.55366 -3.358874 7 -31.42098 -3.416561 6 -31.41476 -3.416561 7 -31.41476 -5.026407 7 -31.19768 -5.112311 6 -31.18372 -5.112311 7 -31.18372 -6.679691 7 -30.88595 -6.793066 6 -30.86121 -6.793066 7 -30.86121 -8.314042 7 -30.48666 -8.453896 6 -30.44818 -8.453896 7 -30.44818 -9.924825 7 -30.00097 -10.08993 6 -29.94584 -10.08993 7 -29.94584 -11.50747 7 -29.43022 -11.69637 6 -29.35566 -11.69637 7 -29.35566 -13.0575 7 -28.77606 -13.2685 6 -28.67938 -13.2685 7 -28.67938 -14.57052 7 -28.04033 -14.80171 6 -27.91898 -14.80171 7 -27.91898 -16.04224 7 -27.22511 -16.2915 6 -27.07669 -16.2915 7 -27.07669 -17.46848 7 -26.33272 -17.73351 6 -26.15497 -17.73351 7 -26.15497 -18.84521 7 -25.36569 -19.12351 6 -25.15654 -19.12351 7 -25.15654 -20.16852 7 -24.32676 -20.45741 6 -24.08432 -20.45741 7 -24.08432 -21.43465 7 -23.21886 -21.7313 6 -22.94146 -21.7313 7 -22.94146 -22.64003 7 -22.04516 -22.94146 6 -21.7313 -22.94146 7 -21.7313 -23.78124 7 -20.80896 -24.08432 6 -20.45741 -24.08432 7 -20.45741 -24.85503 7 -19.51378 -25.15654 6 -19.12351 -25.15654 7 -19.12351 -25.85837 7 -18.16328 -26.15497 6 -17.73351 -26.15497 7 -17.73351 -26.78841 7 -16.7613 -27.07669 6 -16.2915 -27.07669 7 -16.2915 -27.91898 6 -14.80171 -27.64251 7 -15.31181 -27.91898 7 -14.80171 -28.67938 6 -13.2685 -28.41826 7 -13.81891 -28.67938 7 -13.2685 -29.35566 6 -11.69637 -29.11346 7 -12.28684 -29.35566 7 -11.69637 -29.94584 6 -10.08993 -29.72613 7 -10.71995 -29.94584 7 -10.08993 -30.44818 6 -8.453896 -30.25454 7 -9.122667 -30.44818 7 -8.453896 -30.86121 6 -6.793066 -30.69719 7 -7.499524 -30.86121 7 -6.793066 -31.18372 6 -5.112311 -31.05282 7 -5.855123 -31.18372 7 -5.112311 -31.41476 6 -3.416561 -31.32043 7 -4.194127 -31.41476 7 -3.416561 -31.55366 6 -1.71079 -31.49926 7 -2.521241 -31.55366 7 -1.71079 -31.6 6 0 -31.5888 7 -0.8412085 -31.6 7 0 -31.5888 7 0.8412085 -31.55366 6 1.71079 -31.55366 7 1.71079 -31.49926 7 2.521241 -31.41476 6 3.416561 -31.41476 7 3.416561 -31.32043 7 4.194127 -31.18372 6 5.112311 -31.18372 7 5.112311 -31.05282 7 5.855123 -30.86121 6 6.793066 -30.86121 7 6.793066 -30.69719 7 7.499524 -30.44818 6 8.453896 -30.44818 7 8.453896 -30.25454 7 9.122667 -29.94584 6 10.08993 -29.94584 7 10.08993 -29.72613 7 10.71995 -29.35566 6 11.69637 -29.35566 7 11.69637 -29.11346 7 12.28684 -28.67938 6 13.2685 -28.67938 7 13.2685 -28.41826 7 13.81891 -27.91898 6 14.80171 -27.91898 7 14.80171 -27.64251 7 15.31181 -27.07669 6 16.2915 -27.07669 7 16.2915 -26.78841 7 16.7613 -26.15497 6 17.73351 -26.15497 7 17.73351 -25.85837 7 18.16328 -25.15654 6 19.12351 -25.15654 7 19.12351 -24.85503 7 19.51378 -24.08432 6 20.45741 -24.08432 7 20.45741 -23.78124 7 20.80896 -22.94146 6 21.7313 -22.94146 7 21.7313 -22.64003 7 22.04516 -21.7313 6 22.94146 -21.7313 7 22.94146 -21.43465 7 23.21886 -20.45741 6 24.08432 -20.45741 7 24.08432 -20.16852 7 24.32676 -19.12351 6 25.15654 -19.12351 7 25.15654 -18.84521 7 25.36569 -17.73351 6 26.15497 -17.73351 7 26.15497 -17.46848 7 26.33272 -16.2915 6 27.07669 -16.2915 7 27.07669 -16.04224 7 27.22511 -14.80171 6 27.91898 -14.80171 7 27.91898 -14.57052 7 28.04033 -13.2685 6 28.67938 -13.2685 7 28.67938 -13.0575 7 28.77606 -11.69637 6 29.35566 -11.69637 7 29.35566 -11.50747 7 29.43022 -10.08993 6 29.94584 -10.08993 7 29.94584 -9.924825 7 30.00097 -8.453896 6 30.44818 -8.453896 7 30.44818 -8.314042 7 30.48666 -6.793066 6 30.86121 -6.793066 7 30.86121 -6.679691 7 30.88595 -5.112311 6 31.18372 -5.112311 7 31.18372 -5.026407 7 31.19768 -3.416561 6 31.41476 -3.416561 7 31.41476 -3.358874 7 31.42098 -1.71079 6 31.55366 -1.71079 7 31.55366 -1.681821 7 31.55521 0 7 31.6 0 6 0 0 8 -32.6 0 7 -31.6 0 7 31.6 + + + + + + + + + + -0.9993171 0 -0.03695338 -0.9972693 0 -0.07385182 -0.9972693 0 -0.07385182 -0.9938592 0 -0.1106523 -0.9938592 0 -0.1106524 -0.9890915 0 -0.147303 -0.9890915 0 -0.1473029 -0.9829728 0 -0.1837518 -0.9829728 0 -0.1837517 -0.9755126 0 -0.2199438 -0.9667186 0 -0.255842 -0.9667186 0 -0.2558423 -0.9566048 0 -0.2913888 -0.9566047 0 -0.2913892 -0.9451836 0 -0.3265393 -0.9451838 0 -0.3265389 -0.9324718 0 -0.3612432 -0.9324718 0 -0.3612428 -0.9184876 0 -0.3954501 -0.9184871 0 -0.395451 -0.9032473 0 -0.4291204 -0.9032469 0 -0.4291213 -0.8867733 0 -0.4622046 -0.8867728 0 -0.4622057 -0.8690901 0 -0.4946538 -0.8690896 0 -0.4946548 -0.8502169 0 -0.5264327 -0.8502162 0 -0.5264337 -0.8301846 0 -0.5574886 -0.8301839 0 -0.5574898 -0.8090174 0 -0.5877848 -0.8090166 0 -0.587786 -0.7867455 0 -0.6172777 -0.7633974 0 -0.6459292 -0.7633985 0 -0.645928 -0.7390089 0 -0.6736958 -0.73901 0 -0.6736945 -0.7136095 0 -0.7005438 -0.7136107 0 -0.7005426 -0.687236 0 -0.7264342 -0.6599259 0 -0.7513308 -0.6599245 0 -0.7513319 -0.6317113 0 -0.7752039 -0.6317083 0 -0.7752063 -0.6026359 0 -0.7980163 -0.5727343 0 -0.8197411 -0.5420531 0 -0.8403443 -0.5106335 0 -0.8597986 -0.5106299 0 -0.8598006 -0.4785133 0 -0.8780804 -0.4457345 0 -0.8951652 -0.4457384 0 -0.8951633 -0.4123567 0 -0.9110225 -0.3784121 0 -0.9256374 -0.3784162 0 -0.9256356 -0.3439484 0 -0.9389885 -0.3090157 0 -0.951057 -0.2736572 0 -0.9618273 -0.2736617 0 -0.9618261 -0.2379357 0 -0.971281 -0.2018867 0 -0.9794089 -0.2018821 0 -0.9794099 -0.1655591 0 -0.9861999 -0.1655496 0 -0.9862015 -0.1290014 0 -0.9916445 -0.1289918 0 -0.9916457 -0.09226769 0 -0.9957343 -0.09227252 0 -0.9957338 -0.05540663 0 -0.9984639 -0.05541151 0 -0.9984637 -0.01847702 0 -0.9998294 -0.01848679 0 -0.9998292 0.01848679 0 -0.9998292 -0.9993171 0 -0.03695338 -1 0 0 -0.9993171 0 0.03695338 -0.9993171 0 0.03695338 -0.9972693 0 0.07385182 -0.9972693 0 0.07385182 -0.9938592 0 0.1106523 -0.9938592 0 0.1106524 -0.9890915 0 0.147303 -0.9890915 0 0.1473029 -0.9829728 0 0.1837518 -0.9829728 0 0.1837517 -0.9755126 0 0.2199438 -0.9667186 0 0.255842 -0.9667186 0 0.2558423 -0.9566048 0 0.2913888 -0.9566047 0 0.2913892 -0.9451836 0 0.3265393 -0.9451838 0 0.3265389 -0.9324718 0 0.3612432 -0.9324718 0 0.3612428 -0.9184876 0 0.3954501 -0.9184871 0 0.395451 -0.9032473 0 0.4291204 -0.9032469 0 0.4291213 -0.8867733 0 0.4622046 -0.8867728 0 0.4622057 -0.8690901 0 0.4946538 -0.8690896 0 0.4946548 -0.8502169 0 0.5264327 -0.8502162 0 0.5264337 -0.8301846 0 0.5574886 -0.8301839 0 0.5574898 -0.8090174 0 0.5877848 -0.8090166 0 0.587786 -0.7867455 0 0.6172777 -0.7633974 0 0.6459292 -0.7633985 0 0.645928 -0.7390089 0 0.6736958 -0.73901 0 0.6736945 -0.7136095 0 0.7005438 -0.7136107 0 0.7005426 -0.687236 0 0.7264342 -0.6599259 0 0.7513308 -0.6599245 0 0.7513319 -0.6317113 0 0.7752039 -0.6317083 0 0.7752063 -0.6026359 0 0.7980163 -0.5727343 0 0.8197411 -0.5420531 0 0.8403443 -0.5106335 0 0.8597986 -0.5106299 0 0.8598006 -0.4785133 0 0.8780804 -0.4457345 0 0.8951652 -0.4457384 0 0.8951633 -0.4123567 0 0.9110225 -0.3784121 0 0.9256374 -0.3784162 0 0.9256356 -0.3439484 0 0.9389885 -0.3090157 0 0.951057 -0.2736572 0 0.9618273 -0.2736617 0 0.9618261 -0.2379357 0 0.971281 -0.2018867 0 0.9794089 -0.2018821 0 0.9794099 -0.1655591 0 0.9861999 -0.1655496 0 0.9862015 -0.1290014 0 0.9916445 -0.1289918 0 0.9916457 -0.09226769 0 0.9957343 -0.09227252 0 0.9957338 -0.05540663 0 0.9984639 -0.05541151 0 0.9984637 -0.01847702 0 0.9998294 -0.01848679 0 0.9998292 0.01848679 0 0.9998292 0.01847702 0 0.9998294 0.05541151 0 0.9984637 0.05540663 0 0.9984639 0.09227252 0 0.9957338 0.09226769 0 0.9957343 0.1289918 0 0.9916457 0.1290014 0 0.9916445 0.1655496 0 0.9862015 0.1655591 0 0.9861999 0.2018821 0 0.9794099 0.2018867 0 0.9794089 0.2379357 0 0.971281 0.2736617 0 0.9618261 0.2736572 0 0.9618273 0.3090157 0 0.951057 0.3439484 0 0.9389885 0.3784162 0 0.9256356 0.3784121 0 0.9256374 0.4123567 0 0.9110225 0.4457384 0 0.8951633 0.4457345 0 0.8951652 0.4785133 0 0.8780804 0.5106299 0 0.8598006 0.5106335 0 0.8597986 0.5420531 0 0.8403443 0.5727343 0 0.8197411 0.6026359 0 0.7980163 0.6317083 0 0.7752063 0.6317113 0 0.7752039 0.6599245 0 0.7513319 0.6599259 0 0.7513308 0.687236 0 0.7264342 0.7136107 0 0.7005426 0.7136095 0 0.7005438 0.73901 0 0.6736945 0.7390089 0 0.6736958 0.7633985 0 0.645928 0.7633974 0 0.6459292 0.7867455 0 0.6172777 0.8090166 0 0.587786 0.8090174 0 0.5877848 0.8301839 0 0.5574898 0.8301846 0 0.5574886 0.8502162 0 0.5264337 0.8502169 0 0.5264327 0.8690896 0 0.4946548 0.8690901 0 0.4946538 0.8867728 0 0.4622057 0.8867733 0 0.4622046 0.9032469 0 0.4291213 0.9032473 0 0.4291204 0.9184871 0 0.395451 0.9184876 0 0.3954501 0.9324718 0 0.3612428 0.9324718 0 0.3612432 0.9451838 0 0.3265389 0.9451836 0 0.3265393 0.9566047 0 0.2913892 0.9566048 0 0.2913888 0.9667186 0 0.2558423 0.9667186 0 0.255842 0.9755126 0 0.2199438 0.9829728 0 0.1837517 0.9829728 0 0.1837518 0.9890915 0 0.1473029 0.9890915 0 0.147303 0.9938592 0 0.1106524 0.9938592 0 0.1106523 0.9972693 0 0.07385182 0.9972693 0 0.07385182 0.9993171 0 0.03695338 0.9993171 0 0.03695338 1 0 0 0.9993171 0 -0.03695338 0.9993171 0 -0.03695338 0.9972693 0 -0.07385182 0.9972693 0 -0.07385182 0.9938592 0 -0.1106523 0.9938592 0 -0.1106524 0.9890915 0 -0.147303 0.9890915 0 -0.1473029 0.9829728 0 -0.1837518 0.9829728 0 -0.1837517 0.9755126 0 -0.2199438 0.9667186 0 -0.255842 0.9667186 0 -0.2558423 0.9566048 0 -0.2913888 0.9566047 0 -0.2913892 0.9451836 0 -0.3265393 0.9451838 0 -0.3265389 0.9324718 0 -0.3612432 0.9324718 0 -0.3612428 0.9184876 0 -0.3954501 0.9184871 0 -0.395451 0.9032473 0 -0.4291204 0.9032469 0 -0.4291213 0.8867733 0 -0.4622046 0.8867728 0 -0.4622057 0.8690901 0 -0.4946538 0.8690896 0 -0.4946548 0.8502169 0 -0.5264327 0.8502162 0 -0.5264337 0.8301846 0 -0.5574886 0.8301839 0 -0.5574898 0.8090174 0 -0.5877848 0.8090166 0 -0.587786 0.7867455 0 -0.6172777 0.7633974 0 -0.6459292 0.7633985 0 -0.645928 0.7390089 0 -0.6736958 0.73901 0 -0.6736945 0.7136095 0 -0.7005438 0.7136107 0 -0.7005426 0.687236 0 -0.7264342 0.6599259 0 -0.7513308 0.6599245 0 -0.7513319 0.6317113 0 -0.7752039 0.6317083 0 -0.7752063 0.6026359 0 -0.7980163 0.5727343 0 -0.8197411 0.5420531 0 -0.8403443 0.5106335 0 -0.8597986 0.5106299 0 -0.8598006 0.4785133 0 -0.8780804 0.4457345 0 -0.8951652 0.4457384 0 -0.8951633 0.4123567 0 -0.9110225 0.3784121 0 -0.9256374 0.3784162 0 -0.9256356 0.3439484 0 -0.9389885 0.3090157 0 -0.951057 0.2736572 0 -0.9618273 0.2736617 0 -0.9618261 0.2379357 0 -0.971281 0.2018867 0 -0.9794089 0.2018821 0 -0.9794099 0.1655591 0 -0.9861999 0.1655496 0 -0.9862015 0.1290014 0 -0.9916445 0.1289918 0 -0.9916457 0.09226769 0 -0.9957343 0.09227252 0 -0.9957338 0.05540663 0 -0.9984639 0.05541151 0 -0.9984637 0.01847702 0 -0.9998294 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.00691e-7 0 1 -2.00598e-7 0 1 0 0 1 0 0 1 2.00691e-7 0 1 0 0 1 2.00598e-7 0 -1 0 -0.7066863 0.7070444 -0.02613228 -0.705236 0.7070465 -0.05222612 -0.705237 0.7070456 -0.05222558 -0.7028246 0.7070465 -0.07824981 -0.7028256 0.7070454 -0.07824981 -0.6994533 0.7070464 -0.1041659 -0.6994523 0.7070471 -0.1041678 -0.6951274 0.7070453 -0.1299421 -0.6951261 0.7070463 -0.129943 -0.6898502 0.7070461 -0.1555399 -0.6898498 0.7070471 -0.1555369 -0.6836302 0.7070479 -0.1809227 -0.6836308 0.7070474 -0.1809231 -0.6764789 0.7070466 -0.2060618 -0.6764786 0.7070474 -0.2060603 -0.6684014 0.7070483 -0.2309161 -0.6684039 0.7070454 -0.2309181 -0.6594125 0.7070477 -0.2554581 -0.6594139 0.7070459 -0.2554597 -0.649523 0.7070474 -0.2796495 -0.649524 0.7070468 -0.279649 -0.6387454 0.7070479 -0.3034593 -0.6387463 0.7070468 -0.3034601 -0.6270971 0.7070466 -0.3268554 -0.6270979 0.7070454 -0.3268566 -0.6145917 0.7070454 -0.3498055 -0.6145909 0.7070475 -0.3498027 -0.6012451 0.7070465 -0.3722764 -0.6012451 0.7070471 -0.3722754 -0.5870792 0.707046 -0.3942383 -0.5870798 0.7070461 -0.3942373 -0.5721093 0.7070471 -0.4156627 -0.5721113 0.7070455 -0.4156627 -0.5563594 0.7070469 -0.4365192 -0.5563603 0.7070466 -0.4365186 -0.5398514 0.7070459 -0.4567786 -0.5398489 0.7070466 -0.4567803 -0.5226036 0.707046 -0.4764153 -0.5226029 0.7070465 -0.4764155 -0.5046442 0.7070451 -0.4954004 -0.5046401 0.7070472 -0.4954016 -0.4859899 0.7070473 -0.51371 -0.4859914 0.7070455 -0.5137111 -0.4666789 0.7070452 -0.5313171 -0.466678 0.7070459 -0.5313171 -0.4467247 0.7070471 -0.5481984 -0.4467222 0.7070472 -0.5482004 -0.4261673 0.7070448 -0.5643307 -0.4261613 0.7070478 -0.5643315 -0.4050209 0.7070446 -0.5796948 -0.4050187 0.7070468 -0.5796937 -0.3833214 0.7070474 -0.5942633 -0.3833225 0.7070458 -0.5942645 -0.3611019 0.7070471 -0.6080213 -0.3611044 0.7070451 -0.6080222 -0.3383852 0.7070469 -0.6209511 -0.3383861 0.7070475 -0.6209499 -0.3152144 0.7070457 -0.6330295 -0.3152105 0.7070466 -0.6330304 -0.2916036 0.7070463 -0.6442459 -0.2916051 0.7070466 -0.6442451 -0.2676026 0.707046 -0.6545799 -0.2675989 0.707047 -0.6545804 -0.2432284 0.7070472 -0.6640213 -0.2432289 0.7070468 -0.6640216 -0.2185279 0.7070473 -0.6725547 -0.2185279 0.7070464 -0.6725556 -0.1935231 0.7070465 -0.680172 -0.1935269 0.7070458 -0.6801717 -0.1682584 0.7070459 -0.6868591 -0.1682602 0.7070468 -0.6868576 -0.1427642 0.707047 -0.6926059 -0.1427689 0.7070456 -0.6926063 -0.1170712 0.7070462 -0.6974095 -0.1170728 0.7070471 -0.6974084 -0.09122979 0.7070463 -0.701258 -0.09122115 0.7070453 -0.7012601 -0.06525015 0.7070454 -0.7041515 -0.06524533 0.7070454 -0.7041519 -0.03918266 0.7070453 -0.706082 -0.03918862 0.7070459 -0.706081 -0.01306384 0.7070461 -0.7070469 -0.01307153 0.7070463 -0.7070464 0.01306688 0.7070464 -0.7070465 -0.7066853 0.7070454 -0.02613008 -0.7071648 0.7070487 0 -0.7071675 0.7070461 0 -0.7066863 0.7070443 0.02613228 -0.7066857 0.707045 0.02613008 -0.7052367 0.7070458 0.05222558 -0.7052363 0.7070462 0.05222612 -0.702825 0.707046 0.07824975 -0.7028251 0.7070459 0.07824987 -0.6994522 0.7070473 0.1041677 -0.6994535 0.7070462 0.104166 -0.6951268 0.7070456 0.1299433 -0.6951267 0.7070461 0.1299418 -0.6898494 0.7070475 0.1555368 -0.6898512 0.707045 0.1555401 -0.6836304 0.7070477 0.180923 -0.6836306 0.7070476 0.1809228 -0.67648 0.7070459 0.2060607 -0.6764782 0.7070474 0.2060616 -0.6684021 0.7070472 0.2309175 -0.6684032 0.7070465 0.2309167 -0.6594133 0.7070466 0.2554589 -0.6594137 0.7070462 0.2554592 -0.649524 0.7070468 0.279649 -0.649523 0.7070474 0.2796495 -0.6387435 0.7070496 0.3034595 -0.6387484 0.707045 0.30346 -0.627097 0.707046 0.3268569 -0.6270986 0.7070452 0.3268554 -0.6145915 0.7070468 0.3498031 -0.614591 0.7070462 0.3498052 -0.6012438 0.7070475 0.3722764 -0.6012464 0.707046 0.3722754 -0.587078 0.7070473 0.3942381 -0.5870813 0.7070448 0.3942376 -0.5721105 0.7070452 0.4156642 -0.5721101 0.7070474 0.4156611 -0.5563604 0.7070457 0.4365198 -0.5563593 0.7070478 0.4365178 -0.539851 0.7070455 0.4567795 -0.5398493 0.707047 0.4567793 -0.5226054 0.7070447 0.4764152 -0.5226008 0.7070479 0.4764155 -0.5046412 0.7070476 0.4953998 -0.504643 0.7070446 0.4954022 -0.4859904 0.7070469 0.51371 -0.485991 0.7070458 0.5137111 -0.4666793 0.7070463 0.5313153 -0.4666776 0.7070447 0.531319 -0.4467217 0.7070479 0.5481998 -0.4467252 0.7070463 0.5481989 -0.4261662 0.7070457 0.5643304 -0.4261619 0.7070474 0.5643315 -0.4050213 0.7070456 0.5796933 -0.4050182 0.7070459 0.5796952 -0.3833217 0.7070472 0.5942632 -0.383322 0.7070462 0.5942642 -0.3611015 0.7070465 0.6080222 -0.3611049 0.7070456 0.6080213 -0.338389 0.7070461 0.6209499 -0.3383823 0.7070479 0.6209514 -0.3152158 0.7070454 0.6330292 -0.315209 0.7070467 0.633031 -0.2916053 0.707046 0.6442456 -0.2916031 0.7070475 0.6442449 -0.2676016 0.7070463 0.65458 -0.2675997 0.7070471 0.6545799 -0.2432289 0.7070469 0.6640214 -0.2432284 0.707047 0.6640215 -0.2185276 0.7070471 0.6725549 -0.2185282 0.7070464 0.6725555 -0.1935211 0.7070475 0.6801717 -0.1935292 0.7070448 0.6801722 -0.1682603 0.707046 0.6868584 -0.1682583 0.7070465 0.6868584 -0.142766 0.7070465 0.6926062 -0.1427672 0.7070463 0.6926061 -0.11707 0.707047 0.697409 -0.1170741 0.7070463 0.6974089 -0.09122389 0.7070465 0.7012585 -0.09122699 0.7070452 0.7012594 -0.06524819 0.7070455 0.7041516 -0.06524711 0.7070455 0.7041517 -0.03918868 0.7070452 0.7060818 -0.0391826 0.707046 0.7060813 -0.01306861 0.7070459 0.7070469 -0.01306688 0.7070464 0.7070465 0.01307153 0.7070463 0.7070464 0.01306384 0.7070461 0.7070469 0.03918862 0.7070459 0.706081 0.03918266 0.7070453 0.706082 0.06524527 0.7070454 0.7041519 0.06525015 0.7070454 0.7041515 0.09122115 0.7070453 0.7012602 0.09122985 0.7070464 0.7012579 0.1170728 0.7070472 0.6974083 0.1170711 0.7070463 0.6974093 0.1427689 0.7070457 0.6926063 0.1427642 0.707047 0.6926059 0.1682602 0.7070468 0.6868577 0.1682585 0.7070457 0.6868592 0.193527 0.7070457 0.6801719 0.1935231 0.7070467 0.680172 0.2185279 0.7070464 0.6725556 0.2185279 0.7070472 0.6725547 0.243229 0.7070465 0.6640217 0.2432283 0.7070474 0.6640211 0.2675988 0.7070473 0.6545801 0.2676024 0.7070464 0.6545795 0.291605 0.7070468 0.6442449 0.2916037 0.707046 0.6442463 0.3152105 0.7070466 0.6330304 0.3152145 0.7070454 0.6330297 0.3383862 0.7070471 0.6209502 0.3383854 0.7070465 0.6209515 0.3611044 0.7070451 0.6080222 0.3611019 0.7070471 0.6080213 0.3833225 0.7070458 0.5942645 0.3833212 0.7070477 0.594263 0.4050187 0.7070468 0.5796937 0.4050211 0.7070443 0.5796951 0.4261613 0.7070478 0.5643315 0.4261673 0.7070448 0.5643307 0.4467222 0.7070472 0.5482004 0.4467247 0.7070471 0.5481984 0.466678 0.7070459 0.5313171 0.4666789 0.7070452 0.5313171 0.4859909 0.7070462 0.5137106 0.4859904 0.7070465 0.5137105 0.5046401 0.7070472 0.4954016 0.5046442 0.7070451 0.4954004 0.5226029 0.7070465 0.4764155 0.5226036 0.707046 0.4764153 0.5398489 0.7070466 0.4567803 0.5398514 0.7070459 0.4567786 0.5563603 0.7070466 0.4365186 0.5563594 0.7070469 0.4365192 0.5721113 0.7070455 0.4156627 0.5721093 0.7070471 0.4156627 0.5870798 0.7070461 0.3942373 0.5870792 0.707046 0.3942383 0.6012451 0.7070471 0.3722754 0.6012451 0.7070465 0.3722764 0.6145909 0.7070475 0.3498027 0.6145917 0.7070454 0.3498055 0.6270979 0.7070454 0.3268566 0.6270971 0.7070466 0.3268554 0.6387457 0.7070475 0.3034598 0.6387461 0.7070472 0.3034596 0.649524 0.7070468 0.279649 0.6495237 0.7070466 0.2796498 0.6594139 0.7070459 0.2554597 0.6594128 0.7070474 0.2554583 0.6684035 0.7070457 0.230918 0.6684021 0.7070475 0.2309163 0.6764786 0.7070474 0.2060603 0.6764793 0.7070462 0.2060619 0.6836304 0.7070477 0.180923 0.6836306 0.7070476 0.1809228 0.6898494 0.7070475 0.1555368 0.6898505 0.7070457 0.1555399 0.6951258 0.7070468 0.129943 0.695127 0.7070457 0.1299421 0.699452 0.7070475 0.1041678 0.6994527 0.7070469 0.1041659 0.702825 0.707046 0.07824975 0.7028244 0.7070466 0.07824975 0.7052368 0.7070457 0.05222558 0.705236 0.7070465 0.05222612 0.7066863 0.7070444 0.02613228 0.7066853 0.7070454 0.02613008 0.7071648 0.7070487 0 0.7071675 0.7070461 0 0.7066863 0.7070443 -0.02613228 0.7066857 0.707045 -0.02613008 0.7052367 0.7070458 -0.05222558 0.7052363 0.7070462 -0.05222612 0.702825 0.707046 -0.07824975 0.7028251 0.7070459 -0.07824987 0.6994522 0.7070473 -0.1041677 0.6994535 0.7070462 -0.104166 0.6951268 0.7070456 -0.1299433 0.6951267 0.7070461 -0.1299418 0.6898494 0.7070475 -0.1555368 0.6898512 0.707045 -0.1555401 0.6836304 0.7070477 -0.180923 0.6836306 0.7070476 -0.1809228 0.67648 0.7070459 -0.2060607 0.6764782 0.7070474 -0.2060616 0.6684021 0.7070472 -0.2309175 0.6684032 0.7070465 -0.2309167 0.6594133 0.7070466 -0.2554589 0.6594137 0.7070462 -0.2554592 0.649524 0.7070468 -0.279649 0.649523 0.7070474 -0.2796495 0.6387435 0.7070496 -0.3034595 0.6387484 0.707045 -0.30346 0.627097 0.707046 -0.3268569 0.6270986 0.7070452 -0.3268554 0.6145915 0.7070468 -0.3498031 0.614591 0.7070462 -0.3498052 0.6012438 0.7070475 -0.3722764 0.6012464 0.707046 -0.3722754 0.587078 0.7070473 -0.3942381 0.5870813 0.7070448 -0.3942376 0.5721105 0.7070452 -0.4156642 0.5721101 0.7070474 -0.4156611 0.5563604 0.7070457 -0.4365198 0.5563593 0.7070478 -0.4365178 0.539851 0.7070455 -0.4567795 0.5398493 0.707047 -0.4567793 0.5226054 0.7070447 -0.4764152 0.5226008 0.7070479 -0.4764155 0.5046412 0.7070476 -0.4953998 0.504643 0.7070446 -0.4954022 0.4859904 0.7070469 -0.51371 0.485991 0.7070458 -0.5137111 0.4666793 0.7070463 -0.5313153 0.4666776 0.7070447 -0.531319 0.4467217 0.7070479 -0.5481998 0.4467252 0.7070463 -0.5481989 0.4261662 0.7070457 -0.5643304 0.4261619 0.7070474 -0.5643315 0.4050213 0.7070456 -0.5796933 0.4050182 0.7070459 -0.5796952 0.3833217 0.7070472 -0.5942632 0.383322 0.7070462 -0.5942642 0.3611015 0.7070465 -0.6080222 0.3611049 0.7070456 -0.6080213 0.338389 0.7070461 -0.6209499 0.3383823 0.7070479 -0.6209514 0.3152158 0.7070454 -0.6330292 0.315209 0.7070467 -0.633031 0.2916053 0.707046 -0.6442456 0.2916031 0.7070475 -0.6442449 0.2676016 0.7070463 -0.65458 0.2675997 0.7070471 -0.6545799 0.2432289 0.7070469 -0.6640214 0.2432284 0.707047 -0.6640215 0.2185276 0.7070471 -0.6725549 0.2185282 0.7070464 -0.6725555 0.1935211 0.7070475 -0.6801717 0.1935292 0.7070448 -0.6801722 0.1682603 0.707046 -0.6868584 0.1682583 0.7070465 -0.6868584 0.142766 0.7070465 -0.6926062 0.1427672 0.7070463 -0.6926061 0.11707 0.707047 -0.697409 0.1170741 0.7070463 -0.6974089 0.09122389 0.7070465 -0.7012585 0.09122699 0.7070452 -0.7012594 0.06524819 0.7070455 -0.7041516 0.06524711 0.7070455 -0.7041517 0.03918868 0.7070452 -0.7060818 0.0391826 0.707046 -0.7060813 0.01306861 0.7070459 -0.7070469 -0.02707749 7.73295e-4 -0.9996331 -0.05378031 0 -0.9985529 -0.08024305 0 -0.9967753 -0.08115893 0.001519381 -0.9967001 -0.1072324 0 -0.994234 -0.1336354 0 -0.9910306 -0.1349994 0.002237081 -0.9908432 -0.1604226 0 -0.9870485 -0.1866419 0 -0.982428 -0.1884431 0.002930104 -0.9820798 -0.2131828 0 -0.9770123 -0.2391106 0 -0.9709923 -0.2413357 0.003594875 -0.970435 -0.2653264 0 -0.9641587 -0.2908887 0 -0.9567569 -0.2935174 0.00423485 -0.9559444 -0.3167011 0 -0.9485254 -0.3418288 0 -0.9397624 -0.3448423 0.004848182 -0.9386482 -0.3671652 0 -0.9301558 -0.3917823 0 -0.920058 -0.3951507 0.005431175 -0.9186003 -0.416554 0 -0.909111 -0.4406067 0 -0.8977003 -0.4443052 0.00599116 -0.8958555 -0.4647442 0 -0.8854451 -0.4881618 0 -0.8727533 -0.4921516 0.006525456 -0.8704852 -0.5116193 0 -0.8592123 -0.5343049 0 -0.8452919 -0.5385544 0.007032454 -0.8425614 -0.557007 0 -0.8305078 -0.5789119 0 -0.8153901 -0.583378 0.00750941 -0.8121661 -0.6007791 0 -0.7994152 -0.6218472 0 -0.7831388 -0.6264904 0.007964372 -0.7793885 -0.64283 0 -0.7660089 -0.6629897 0 -0.7486286 -0.6677649 0.008387863 -0.7443251 -0.6830197 0 -0.7304 -0.7022215 0 -0.7119586 -0.7070795 0.008788466 -0.7070795 -0.7212428 0 -0.6926824 -0.7394275 0 -0.6732363 -0.7443206 0.009160637 -0.6677597 -0.7573863 0 -0.652967 -0.7745012 0 -0.6325724 -0.779378 0.009507238 -0.626482 -0.7913447 0 -0.6113705 -0.8073415 0 -0.5900844 -0.8121498 0.009825885 -0.5833662 -0.823023 0 -0.568008 -0.8378526 0 -0.5458967 -0.8425388 0.01012343 -0.5385407 -0.8523305 0 -0.5230037 -0.8705031 0 -0.4921628 -0.8658422 0.01570725 -0.5000706 -0.8791733 0 -0.4765022 -0.8958724 0 -0.4443113 -0.8914272 0.01649403 -0.4528638 -0.9034845 0 -0.428621 -0.9186134 0 -0.3951575 -0.9144396 0.01727712 -0.4043534 -0.9251919 0 -0.3794996 -0.938659 0 -0.3448471 -0.9348126 0.01807087 -0.3546814 -0.9442296 0 -0.3292878 -0.9559524 0 -0.2935218 -0.9524911 0.01885354 -0.3039826 -0.960545 0 -0.2781249 -0.9704411 0 -0.2413383 -0.9674209 0.01963973 -0.252411 -0.9740896 0 -0.2261626 -0.9820838 0 -0.1884449 -0.9795606 0.0204178 -0.2001104 -0.9848256 0 -0.1735473 -0.9908456 0 -0.1349998 -0.9888736 0.02121156 -0.1472384 -0.992722 0 -0.1204289 -0.9967013 0 -0.08115899 -0.9953348 0.02199715 -0.09394073 -0.9977552 0 -0.06696707 -0.9996334 0 -0.02707862 -0.9989254 0.02276504 -0.04037231 -0.9999114 0 -0.01331067 -0.9999114 0 0.01331067 -0.9995664 0.01157867 0.02707678 -0.9991844 0 0.0403828 -0.9977552 0 0.06696707 -0.9966347 0.01156085 0.08115357 -0.9955757 0 0.0939635 -0.992722 0 0.1204289 -0.9907801 0.01150739 0.1349909 -0.9890962 0 0.1472714 -0.9848256 0 0.1735473 -0.9820198 0.01142269 0.1884325 -0.9797648 0 0.2001521 -0.9740896 0 0.2261626 -0.9703789 0.01132017 0.2413229 -0.9676074 0 0.2524597 -0.960545 0 0.2781249 -0.9558926 0.01118648 0.2935034 -0.9526605 0 0.3040366 -0.9442296 0 0.3292878 -0.9386017 0.01102823 0.3448265 -0.9349654 0 0.3547387 -0.9251919 0 0.3794996 -0.9185597 0.0108366 0.3951339 -0.9145759 0 0.4044145 -0.9034845 0 0.428621 -0.8958219 0.01062488 0.4442863 -0.8915485 0 0.4529254 -0.8791733 0 0.4765022 -0.8704566 0.0103842 0.4921358 -0.8659486 0 0.5001331 -0.8523305 0 0.5230037 -0.8425388 0.01012343 0.5385407 -0.8378526 0 0.5458967 -0.823023 0 0.568008 -0.8121499 0.009824812 0.5833663 -0.8073415 0 0.5900844 -0.7913447 0 0.6113705 -0.779378 0.009506106 0.626482 -0.7745012 0 0.6325724 -0.7573863 0 0.652967 -0.7443206 0.009160637 0.6677597 -0.7394275 0 0.6732363 -0.7212428 0 0.6926824 -0.7070795 0.008788466 0.7070795 -0.7022215 0 0.7119586 -0.6830197 0 0.7304 -0.6677649 0.008387267 0.7443251 -0.6629897 0 0.7486286 -0.64283 0 0.7660089 -0.6264904 0.007963836 0.7793885 -0.6218472 0 0.7831388 -0.6007791 0 0.7994152 -0.583378 0.007509171 0.8121661 -0.5789119 0 0.8153901 -0.557007 0 0.8305078 -0.5385544 0.007032215 0.8425614 -0.5343049 0 0.8452919 -0.5116193 0 0.8592123 -0.4921516 0.006525158 0.8704852 -0.4881618 0 0.8727533 -0.4647442 0 0.8854451 -0.4443052 0.005991339 0.8958555 -0.4406067 0 0.8977003 -0.416554 0 0.909111 -0.3951507 0.005431354 0.9186003 -0.3917823 0 0.920058 -0.3671652 0 0.9301558 -0.3448421 0.004847943 0.9386482 -0.3418288 0 0.9397624 -0.3167011 0 0.9485254 -0.2935174 0.004234969 0.9559444 -0.2908887 0 0.9567569 -0.2653264 0 0.9641587 -0.2413357 0.003594994 0.970435 -0.2391106 0 0.9709923 -0.2131828 0 0.9770123 -0.1884431 0.002930104 0.9820797 -0.1866419 0 0.982428 -0.1604226 0 0.9870485 -0.1349993 0.002237081 0.9908432 -0.1336354 0 0.9910306 -0.1072324 0 0.994234 -0.08115887 0.001519381 0.9967001 -0.08024305 0 0.9967753 -0.05378031 0 0.9985529 -0.02707749 7.73295e-4 0.9996331 -0.02661913 0 0.9996457 0.02661913 0 0.9996457 0.02707749 7.73296e-4 0.9996331 0.05378031 0 0.9985529 0.08024305 0 0.9967753 0.08115893 0.001519381 0.9967001 0.1072324 0 0.994234 0.1336354 0 0.9910306 0.1349994 0.002237081 0.9908432 0.1604226 0 0.9870485 0.1866419 0 0.982428 0.1884431 0.002930104 0.9820798 0.2131828 0 0.9770123 0.2391106 0 0.9709923 0.2413357 0.003594875 0.970435 0.2653264 0 0.9641587 0.2908887 0 0.9567569 0.2935174 0.00423485 0.9559444 0.3167011 0 0.9485254 0.3418288 0 0.9397624 0.3448423 0.004848182 0.9386482 0.3671652 0 0.9301558 0.3917823 0 0.920058 0.3951507 0.005431175 0.9186003 0.416554 0 0.909111 0.4406067 0 0.8977003 0.4443052 0.00599116 0.8958555 0.4647442 0 0.8854451 0.4881618 0 0.8727533 0.4921516 0.006525456 0.8704852 0.5116193 0 0.8592123 0.5343049 0 0.8452919 0.5385544 0.007032454 0.8425614 0.557007 0 0.8305078 0.5789119 0 0.8153901 0.583378 0.00750941 0.8121661 0.6007791 0 0.7994152 0.6218472 0 0.7831388 0.6264904 0.007964372 0.7793885 0.64283 0 0.7660089 0.6629897 0 0.7486286 0.6677649 0.008387863 0.7443251 0.6830197 0 0.7304 0.7022215 0 0.7119586 0.7070795 0.008788466 0.7070795 0.7212428 0 0.6926824 0.7394275 0 0.6732363 0.7443206 0.009160637 0.6677597 0.7573863 0 0.652967 0.7745012 0 0.6325724 0.779378 0.009507238 0.626482 0.7913447 0 0.6113705 0.8073415 0 0.5900844 0.8121498 0.009825885 0.5833662 0.823023 0 0.568008 0.8378526 0 0.5458967 0.8425388 0.01012343 0.5385407 0.8523305 0 0.5230037 0.8705031 0 0.4921628 0.8658422 0.01570725 0.5000706 0.8791733 0 0.4765022 0.8958724 0 0.4443113 0.8914272 0.01649403 0.4528638 0.9034845 0 0.428621 0.9186134 0 0.3951575 0.9144396 0.01727712 0.4043534 0.9251919 0 0.3794996 0.938659 0 0.3448471 0.9348126 0.01807087 0.3546814 0.9442296 0 0.3292878 0.9559524 0 0.2935218 0.9524911 0.01885354 0.3039826 0.960545 0 0.2781249 0.9704411 0 0.2413383 0.9674209 0.01963973 0.252411 0.9740896 0 0.2261626 0.9820838 0 0.1884449 0.9795606 0.0204178 0.2001104 0.9848256 0 0.1735473 0.9908456 0 0.1349998 0.9888736 0.02121156 0.1472384 0.992722 0 0.1204289 0.9967013 0 0.08115899 0.9953348 0.02199715 0.09394073 0.9977552 0 0.06696707 0.9996334 0 0.02707862 0.9989254 0.02276504 0.04037231 0.9999114 0 0.01331067 0.9999114 0 -0.01331067 0.9995664 0.01157867 -0.02707678 0.9991844 0 -0.0403828 0.9977552 0 -0.06696707 0.9966347 0.01156085 -0.08115357 0.9955757 0 -0.0939635 0.992722 0 -0.1204289 0.9907801 0.01150739 -0.1349909 0.9890962 0 -0.1472714 0.9848256 0 -0.1735473 0.9820198 0.01142269 -0.1884325 0.9797648 0 -0.2001521 0.9740896 0 -0.2261626 0.9703789 0.01132017 -0.2413229 0.9676074 0 -0.2524597 0.960545 0 -0.2781249 0.9558926 0.01118648 -0.2935034 0.9526605 0 -0.3040366 0.9442296 0 -0.3292878 0.9386017 0.01102823 -0.3448265 0.9349654 0 -0.3547387 0.9251919 0 -0.3794996 0.9185597 0.0108366 -0.3951339 0.9145759 0 -0.4044145 0.9034845 0 -0.428621 0.8958219 0.01062488 -0.4442863 0.8915485 0 -0.4529254 0.8791733 0 -0.4765022 0.8704566 0.0103842 -0.4921358 0.8659486 0 -0.5001331 0.8523305 0 -0.5230037 0.8425388 0.01012343 -0.5385407 0.8378526 0 -0.5458967 0.823023 0 -0.568008 0.8121499 0.009824812 -0.5833663 0.8073415 0 -0.5900844 0.7913447 0 -0.6113705 0.779378 0.009506106 -0.626482 0.7745012 0 -0.6325724 0.7573863 0 -0.652967 0.7443206 0.009160637 -0.6677597 0.7394275 0 -0.6732363 0.7212428 0 -0.6926824 0.7070795 0.008788466 -0.7070795 0.7022215 0 -0.7119586 0.6830197 0 -0.7304 0.6677649 0.008387267 -0.7443251 0.6629897 0 -0.7486286 0.64283 0 -0.7660089 0.6264904 0.007963836 -0.7793885 0.6218472 0 -0.7831388 0.6007791 0 -0.7994152 0.583378 0.007509171 -0.8121661 0.5789119 0 -0.8153901 0.557007 0 -0.8305078 0.5385544 0.007032215 -0.8425614 0.5343049 0 -0.8452919 0.5116193 0 -0.8592123 0.4921516 0.006525158 -0.8704852 0.4881618 0 -0.8727533 0.4647442 0 -0.8854451 0.4443052 0.005991339 -0.8958555 0.4406067 0 -0.8977003 0.416554 0 -0.909111 0.3951507 0.005431354 -0.9186003 0.3917823 0 -0.920058 0.3671652 0 -0.9301558 0.3448421 0.004847943 -0.9386482 0.3418288 0 -0.9397624 0.3167011 0 -0.9485254 0.2935174 0.004234969 -0.9559444 0.2908887 0 -0.9567569 0.2653264 0 -0.9641587 0.2413357 0.003594994 -0.970435 0.2391106 0 -0.9709923 0.2131828 0 -0.9770123 0.1884431 0.002930104 -0.9820797 0.1866419 0 -0.982428 0.1604226 0 -0.9870485 0.1349993 0.002237081 -0.9908432 0.1336354 0 -0.9910306 0.1072324 0 -0.994234 0.08115887 0.001519381 -0.9967001 0.08024305 0 -0.9967753 0.05378031 0 -0.9985529 0.02707749 7.73295e-4 -0.9996331 0.02661913 0 -0.9996457 -0.02661913 0 -0.9996457 0 1 0 0 1 0 0 1 -2.11689e-7 0 1 1.41126e-7 0 1 2.82251e-7 0 1 -1.41126e-7 0 1 -2.82251e-7 0 1 -5.64503e-7 0 1 2.82251e-7 0 1 -5.64504e-7 0 1 2.82252e-7 0 1 1.41126e-7 0 1 5.64503e-7 0 1 -2.82252e-7 0 1 4.23377e-7 0 1 -1.41126e-7 0 1 -1.41126e-7 0 1 1.41126e-7 0 1 -5.64503e-7 0 1 5.64504e-7 0 1 -4.23377e-7 0 1 2.82252e-7 0 1 5.64503e-7 0 1 -1.41126e-7 0 1 -2.82252e-7 0 1 -2.82251e-7 0 1 2.82251e-7 0 1 1.41126e-7 0 1 -2.82251e-7 0 1 2.11689e-7 0 1 0 0 1 0 0 1 0 0 1 2.82251e-7 0 1 0 0 1 -2.82251e-7 0 1 0 0 1 -1.41126e-7 0 1 5.64503e-7 0 1 4.23378e-7 0 1 -4.23377e-7 0 1 2.82252e-7 0 1 -2.82252e-7 0 1 5.64503e-7 0 1 4.23377e-7 0 1 -4.23378e-7 0 1 -5.64503e-7 0 1 1.41126e-7 0 1 0 0 1 0 0 1 0 0.05644863 0.7067127 -0.7052451 0.05675011 0.7069851 -0.7049479 0.0758711 0.7071029 -0.7030286 0.09393608 0.7064535 -0.7014981 0.09450995 0.7069898 -0.7008805 0.1134358 0.7071077 -0.6979478 0.1311877 0.7062027 -0.6957497 0.1319953 0.7069936 -0.6947931 0.1507436 0.7071041 -0.6908547 0.1680853 0.7059621 -0.6880152 0.1691042 0.7069985 -0.6867001 0.1875966 0.7071075 -0.6817672 0.2045333 0.7057301 -0.6783149 0.2057201 0.7070017 -0.6766298 0.2239279 0.7071057 -0.6707145 0.2404194 0.7055064 -0.6666778 0.2417441 0.7070057 -0.6646072 0.2596126 0.7071091 -0.6577219 0.2756432 0.7052941 -0.6531319 0.2770701 0.70701 -0.6506683 0.294549 0.7071048 -0.6428404 0.3101022 0.7050895 -0.6377191 0.3115982 0.7070136 -0.634853 0.3286238 0.7071065 -0.6261044 0.3436974 0.704895 -0.6204799 0.3452265 0.7070174 -0.6172076 0.3617715 0.7071028 -0.6075583 0.3763307 0.7047102 -0.6014639 0.3778585 0.7070198 -0.5977843 0.3938607 0.7071013 -0.5872663 0.4079095 0.7045342 -0.5807248 0.4094007 0.7070237 -0.5766357 0.4248224 0.7071027 -0.5652715 0.4383406 0.7043671 -0.5583231 0.4397622 0.7070266 -0.5538256 0.4545509 0.7071045 -0.5416519 0.4675386 0.704209 -0.5343196 0.4688541 0.707032 -0.5294164 0.4829716 0.7071014 -0.5164747 0.4954162 0.7040601 -0.508785 0.4965962 0.7070346 -0.5034821 0.5100022 0.7070977 -0.4898067 0.5218915 0.7039242 -0.4817883 0.522906 0.7070369 -0.4760971 0.5355589 0.7070991 -0.4617224 0.5468935 0.7037938 -0.4534114 0.5477059 0.7070412 -0.4473377 0.5595749 0.7070945 -0.4323117 0.5703426 0.7036768 -0.4237315 0.5709295 0.7070423 -0.4172897 0.5819738 0.7070964 -0.4016483 0.5921777 0.7035663 -0.392836 0.5924996 0.7070482 -0.3860402 0.6027027 0.7070903 -0.3698281 0.6123315 0.7034658 -0.3608132 0.6123675 0.7070502 -0.3536753 0.6216849 0.7070898 -0.3369451 0.630747 0.7033745 -0.3277537 0.6304665 0.7070546 -0.3202903 0.6388754 0.7070897 -0.3030881 0.6473695 0.7032939 -0.2937523 0.6467493 0.7070562 -0.2859842 0.654228 0.7070872 -0.2683535 0.6621527 0.7032218 -0.2589073 0.6611666 0.7070574 -0.2508562 0.6676881 0.7070889 -0.2328475 0.6750536 0.7031579 -0.2233197 0.6736763 0.707061 -0.2150003 0.6792268 0.7070872 -0.1966695 0.6860312 0.7031069 -0.1870878 0.6842426 0.7070646 -0.1785266 0.6888086 0.7070829 -0.1599265 0.6950581 0.7030634 -0.1503199 0.6928379 0.7070665 -0.141537 0.6964004 0.7070829 -0.1227205 0.7021074 0.7030288 -0.1131188 0.6994346 0.7070684 -0.1041423 0.7019872 0.7070799 -0.0851593 0.7071567 0.7030042 -0.07559484 0.7040149 0.70707 -0.06644564 0.7055491 0.7070772 -0.04735487 0.7101919 0.7029899 -0.03785204 0.7065618 0.707075 -0.02855622 0.7072299 0.7069838 0 0.715291 0.6987619 -0.009521842 0.7070735 0.7070775 0.009412407 0.7062305 0.7069807 0.03764092 0.7144889 0.6990507 0.0288766 0.7055491 0.7070772 0.04735487 0.7032279 0.706979 0.0751748 0.7116259 0.6993409 0.067164 0.7019872 0.7070799 0.0851593 0.6982288 0.7069807 0.1124939 0.7067168 0.6996276 0.1052266 0.6964004 0.7070829 0.1227205 0.6912519 0.7069807 0.1494968 0.699769 0.6999198 0.1429529 0.6888086 0.7070829 0.1599265 0.682314 0.7069824 0.1860742 0.6908161 0.7002043 0.1802415 0.6792268 0.7070872 0.1966695 0.671444 0.7069818 0.2221255 0.6798796 0.7004881 0.21698 0.6676881 0.7070889 0.2328475 0.6586729 0.7069793 0.2575466 0.6669824 0.7007808 0.2530628 0.654228 0.7070872 0.2683535 0.6440282 0.7069836 0.2922361 0.6521825 0.7010643 0.2883867 0.6388754 0.7070897 0.3030881 0.6275629 0.7069824 0.3260991 0.6355109 0.7013501 0.3228529 0.6216849 0.7070898 0.3369451 0.6093199 0.7069803 0.3590378 0.6170178 0.7016373 0.3563625 0.6027027 0.7070903 0.3698281 0.5893462 0.7069817 0.3909576 0.596762 0.7019232 0.3888174 0.5819738 0.7070964 0.4016483 0.5677033 0.706982 0.4217695 0.5748066 0.7022054 0.4201251 0.5595749 0.7070945 0.4323117 0.5444511 0.7069818 0.4513865 0.5512098 0.7024873 0.4501994 0.5355589 0.7070991 0.4617224 0.519657 0.7069805 0.4797241 0.5260371 0.7027745 0.4789499 0.5100022 0.7070977 0.4898067 0.4933879 0.7069805 0.506702 0.4993742 0.7030557 0.5062986 0.4829716 0.7071014 0.5164747 0.4657204 0.706982 0.5322417 0.4712896 0.7033386 0.5321664 0.4545509 0.7071045 0.5416519 0.436734 0.7069809 0.5562747 0.4418677 0.7036218 0.5564795 0.4248224 0.7071027 0.5652715 0.4065088 0.7069805 0.5787307 0.4111973 0.7039059 0.5791661 0.3938607 0.7071013 0.5872663 0.3751302 0.7069817 0.5995451 0.3793665 0.7041856 0.6001699 0.3617715 0.7071028 0.6075583 0.3426899 0.7069812 0.6186608 0.3464662 0.7044677 0.6194244 0.3286238 0.7071065 0.6261044 0.3092786 0.7069814 0.6360222 0.3125914 0.7047485 0.63688 0.294549 0.7071048 0.6428404 0.274989 0.7069817 0.6515811 0.2778435 0.7050293 0.6524851 0.2596126 0.7071091 0.6577219 0.2399206 0.7069802 0.6652948 0.2423225 0.7053091 0.6661974 0.2239279 0.7071057 0.6707145 0.2041743 0.7069813 0.6771193 0.2061284 0.7055891 0.6779787 0.1875966 0.7071075 0.6817672 0.167845 0.7069823 0.6870256 0.1693726 0.7058677 0.6877964 0.1507436 0.7071041 0.6908547 0.1310423 0.7069804 0.6949868 0.1321547 0.7061471 0.695623 0.1134358 0.7071077 0.6979478 0.09386605 0.7069815 0.7009754 0.09458529 0.7064254 0.7014392 0.0758711 0.7071029 0.7030286 0.05642724 0.7069812 0.7049778 0.0567727 0.7067035 0.7052284 0.03793579 0.7071058 0.7060894 0.01882666 0.706981 0.706982 0.01882588 0.7069826 0.7069804 -0.0188266 0.7069829 0.7069801 -0.01882594 0.7069808 0.7069823 -0.03793579 0.7071058 0.7060894 -0.05644863 0.7067129 0.705245 -0.05675011 0.7069851 0.7049479 -0.0758711 0.7071029 0.7030286 -0.09393608 0.7064535 0.7014981 -0.09450995 0.7069898 0.7008805 -0.1134358 0.7071077 0.6979478 -0.1311877 0.7062027 0.6957497 -0.1319953 0.7069936 0.6947931 -0.1507436 0.7071041 0.6908547 -0.1680853 0.7059621 0.6880152 -0.1691042 0.7069985 0.6867001 -0.1875966 0.7071075 0.6817672 -0.2045333 0.7057301 0.6783149 -0.2057201 0.7070017 0.6766298 -0.2239279 0.7071057 0.6707145 -0.2404194 0.7055064 0.6666778 -0.2417441 0.7070057 0.6646072 -0.2596126 0.7071091 0.6577219 -0.2756432 0.7052941 0.6531319 -0.2770701 0.70701 0.6506683 -0.294549 0.7071048 0.6428404 -0.3101022 0.7050895 0.6377191 -0.3115982 0.7070136 0.634853 -0.3286238 0.7071065 0.6261044 -0.3436974 0.704895 0.6204799 -0.3452265 0.7070174 0.6172076 -0.3617715 0.7071028 0.6075583 -0.3763307 0.7047102 0.6014639 -0.3778585 0.7070198 0.5977843 -0.3938607 0.7071013 0.5872663 -0.4079095 0.7045342 0.5807248 -0.4094007 0.7070237 0.5766357 -0.4248224 0.7071027 0.5652715 -0.4383406 0.7043671 0.5583231 -0.4397622 0.7070266 0.5538256 -0.4545509 0.7071045 0.5416519 -0.4675386 0.704209 0.5343196 -0.4688541 0.707032 0.5294164 -0.4829716 0.7071014 0.5164747 -0.4954162 0.7040601 0.508785 -0.4965962 0.7070346 0.5034821 -0.5100022 0.7070977 0.4898067 -0.5218915 0.7039242 0.4817883 -0.522906 0.7070369 0.4760971 -0.5355589 0.7070991 0.4617224 -0.5468935 0.7037938 0.4534114 -0.5477059 0.7070412 0.4473377 -0.5595749 0.7070945 0.4323117 -0.5703426 0.7036768 0.4237315 -0.5709295 0.7070423 0.4172897 -0.5819738 0.7070964 0.4016483 -0.5921777 0.7035663 0.392836 -0.5924996 0.7070482 0.3860402 -0.6027027 0.7070903 0.3698281 -0.6123315 0.7034658 0.3608132 -0.6123675 0.7070502 0.3536753 -0.6216849 0.7070898 0.3369451 -0.630747 0.7033745 0.3277537 -0.6304665 0.7070546 0.3202903 -0.6388754 0.7070897 0.3030881 -0.6473695 0.7032939 0.2937523 -0.6467493 0.7070562 0.2859842 -0.654228 0.7070872 0.2683535 -0.6621527 0.7032218 0.2589073 -0.6611666 0.7070574 0.2508562 -0.6676881 0.7070889 0.2328475 -0.6750536 0.7031579 0.2233197 -0.6736763 0.707061 0.2150003 -0.6792268 0.7070872 0.1966695 -0.6860312 0.7031069 0.1870878 -0.6842426 0.7070646 0.1785266 -0.6888086 0.7070829 0.1599265 -0.6950581 0.7030634 0.1503199 -0.6928379 0.7070665 0.141537 -0.6964004 0.7070829 0.1227205 -0.7021074 0.7030288 0.1131188 -0.6994346 0.7070684 0.1041423 -0.7019872 0.7070799 0.0851593 -0.7071567 0.7030042 0.07559484 -0.7040149 0.70707 0.06644564 -0.7055491 0.7070772 0.04735487 -0.7101919 0.7029899 0.03785204 -0.7065618 0.707075 0.02855622 -0.7072299 0.7069838 0 -0.715291 0.6987619 0.009521842 -0.7070735 0.7070775 -0.009412407 -0.7062305 0.7069807 -0.03764092 -0.7144889 0.6990507 -0.0288766 -0.7055491 0.7070772 -0.04735487 -0.7032279 0.706979 -0.0751748 -0.7116259 0.6993409 -0.067164 -0.7019872 0.7070799 -0.0851593 -0.6982288 0.7069807 -0.1124939 -0.7067168 0.6996276 -0.1052266 -0.6964004 0.7070829 -0.1227205 -0.6912519 0.7069807 -0.1494968 -0.699769 0.6999198 -0.1429529 -0.6888086 0.7070829 -0.1599265 -0.682314 0.7069824 -0.1860742 -0.6908161 0.7002043 -0.1802415 -0.6792268 0.7070872 -0.1966695 -0.671444 0.7069818 -0.2221255 -0.6798796 0.7004881 -0.21698 -0.6676881 0.7070889 -0.2328475 -0.6586729 0.7069793 -0.2575466 -0.6669824 0.7007808 -0.2530628 -0.654228 0.7070872 -0.2683535 -0.6440282 0.7069836 -0.2922361 -0.6521825 0.7010643 -0.2883867 -0.6388754 0.7070897 -0.3030881 -0.6275629 0.7069824 -0.3260991 -0.6355109 0.7013501 -0.3228529 -0.6216849 0.7070898 -0.3369451 -0.6093199 0.7069803 -0.3590378 -0.6170178 0.7016373 -0.3563625 -0.6027027 0.7070903 -0.3698281 -0.5893462 0.7069817 -0.3909576 -0.596762 0.7019232 -0.3888174 -0.5819738 0.7070964 -0.4016483 -0.5677033 0.706982 -0.4217695 -0.5748066 0.7022054 -0.4201251 -0.5595749 0.7070945 -0.4323117 -0.5444511 0.7069818 -0.4513865 -0.5512098 0.7024873 -0.4501994 -0.5355589 0.7070991 -0.4617224 -0.519657 0.7069805 -0.4797241 -0.5260371 0.7027745 -0.4789499 -0.5100022 0.7070977 -0.4898067 -0.4933879 0.7069805 -0.506702 -0.4993742 0.7030557 -0.5062986 -0.4829716 0.7071014 -0.5164747 -0.4657204 0.706982 -0.5322417 -0.4712896 0.7033386 -0.5321664 -0.4545509 0.7071045 -0.5416519 -0.436734 0.7069809 -0.5562747 -0.4418677 0.7036218 -0.5564795 -0.4248224 0.7071027 -0.5652715 -0.4065088 0.7069805 -0.5787307 -0.4111973 0.7039059 -0.5791661 -0.3938607 0.7071013 -0.5872663 -0.3751302 0.7069817 -0.5995451 -0.3793665 0.7041856 -0.6001699 -0.3617715 0.7071028 -0.6075583 -0.3426899 0.7069812 -0.6186608 -0.3464662 0.7044677 -0.6194244 -0.3286238 0.7071065 -0.6261044 -0.3092786 0.7069814 -0.6360222 -0.3125914 0.7047485 -0.63688 -0.294549 0.7071048 -0.6428404 -0.274989 0.7069817 -0.6515811 -0.2778435 0.7050293 -0.6524851 -0.2596126 0.7071091 -0.6577219 -0.2399206 0.7069802 -0.6652948 -0.2423225 0.7053091 -0.6661974 -0.2239279 0.7071057 -0.6707145 -0.2041743 0.7069813 -0.6771193 -0.2061284 0.7055891 -0.6779787 -0.1875966 0.7071075 -0.6817672 -0.167845 0.7069823 -0.6870256 -0.1693726 0.7058677 -0.6877964 -0.1507436 0.7071041 -0.6908547 -0.1310423 0.7069804 -0.6949868 -0.1321547 0.7061471 -0.695623 -0.1134358 0.7071077 -0.6979478 -0.09386605 0.7069815 -0.7009754 -0.09458529 0.7064254 -0.7014392 -0.0758711 0.7071029 -0.7030286 -0.05642724 0.7069812 -0.7049778 -0.0567727 0.7067035 -0.7052284 -0.03793579 0.7071058 -0.7060894 -0.01882666 0.706981 -0.706982 -0.01882588 0.7069826 -0.7069804 0.0188266 0.7069829 -0.7069801 0.01882594 0.7069807 -0.7069824 0.03793579 0.7071058 -0.7060894 + + + + + + + + + + + + + + +

0 0 1 0 2 0 2 1 1 1 3 1 2 2 3 2 4 2 4 3 3 3 5 3 4 4 5 4 6 4 6 5 5 5 7 5 6 6 7 6 8 6 8 7 7 7 9 7 8 8 9 8 10 8 10 9 9 9 11 9 10 9 11 9 12 9 12 10 11 10 13 10 12 11 13 11 14 11 14 12 13 12 15 12 14 13 15 13 16 13 16 14 15 14 17 14 16 15 17 15 18 15 18 16 17 16 19 16 18 17 19 17 20 17 20 18 19 18 21 18 20 19 21 19 22 19 22 20 21 20 23 20 22 21 23 21 24 21 24 22 23 22 25 22 24 23 25 23 26 23 26 24 25 24 27 24 26 25 27 25 28 25 28 26 27 26 29 26 28 27 29 27 30 27 30 28 29 28 31 28 30 29 31 29 32 29 32 30 31 30 33 30 32 31 33 31 34 31 34 32 33 32 35 32 34 32 35 32 36 32 36 33 35 33 37 33 36 34 37 34 38 34 38 35 37 35 39 35 38 36 39 36 40 36 40 37 39 37 41 37 40 38 41 38 42 38 42 39 41 39 43 39 42 39 43 39 44 39 44 40 43 40 45 40 44 41 45 41 46 41 46 42 45 42 47 42 46 43 47 43 48 43 48 44 47 44 49 44 48 44 49 44 50 44 50 45 49 45 51 45 50 45 51 45 52 45 52 46 51 46 53 46 52 46 53 46 54 46 54 47 53 47 55 47 54 48 55 48 56 48 56 49 55 49 57 49 56 49 57 49 58 49 58 50 57 50 59 50 58 51 59 51 60 51 60 52 59 52 61 52 60 52 61 52 62 52 62 53 61 53 63 53 62 54 63 54 64 54 64 55 63 55 65 55 64 55 65 55 66 55 66 56 65 56 67 56 66 56 67 56 68 56 68 57 67 57 69 57 68 58 69 58 70 58 70 59 69 59 71 59 70 59 71 59 72 59 72 60 71 60 73 60 72 61 73 61 74 61 74 62 73 62 75 62 74 63 75 63 76 63 76 64 75 64 77 64 76 65 77 65 78 65 78 66 77 66 79 66 78 67 79 67 80 67 80 68 79 68 81 68 80 69 81 69 82 69 82 70 81 70 83 70 82 71 83 71 84 71 84 72 83 72 85 72 1 73 0 73 86 73 86 74 0 74 87 74 86 74 87 74 88 74 88 75 87 75 89 75 88 76 89 76 90 76 90 77 89 77 91 77 90 78 91 78 92 78 92 79 91 79 93 79 92 80 93 80 94 80 94 81 93 81 95 81 94 82 95 82 96 82 96 83 95 83 97 83 96 84 97 84 98 84 98 85 97 85 99 85 98 85 99 85 100 85 100 86 99 86 101 86 100 87 101 87 102 87 102 88 101 88 103 88 102 89 103 89 104 89 104 90 103 90 105 90 104 91 105 91 106 91 106 92 105 92 107 92 106 93 107 93 108 93 108 94 107 94 109 94 108 95 109 95 110 95 110 96 109 96 111 96 110 97 111 97 112 97 112 98 111 98 113 98 112 99 113 99 114 99 114 100 113 100 115 100 114 101 115 101 116 101 116 102 115 102 117 102 116 103 117 103 118 103 118 104 117 104 119 104 118 105 119 105 120 105 120 106 119 106 121 106 120 107 121 107 122 107 122 108 121 108 123 108 122 108 123 108 124 108 124 109 123 109 125 109 124 110 125 110 126 110 126 111 125 111 127 111 126 112 127 112 128 112 128 113 127 113 129 113 128 114 129 114 130 114 130 115 129 115 131 115 130 115 131 115 132 115 132 116 131 116 133 116 132 117 133 117 134 117 134 118 133 118 135 118 134 119 135 119 136 119 136 120 135 120 137 120 136 120 137 120 138 120 138 121 137 121 139 121 138 121 139 121 140 121 140 122 139 122 141 122 140 122 141 122 142 122 142 123 141 123 143 123 142 124 143 124 144 124 144 125 143 125 145 125 144 125 145 125 146 125 146 126 145 126 147 126 146 127 147 127 148 127 148 128 147 128 149 128 148 128 149 128 150 128 150 129 149 129 151 129 150 130 151 130 152 130 152 131 151 131 153 131 152 131 153 131 154 131 154 132 153 132 155 132 154 132 155 132 156 132 156 133 155 133 157 133 156 134 157 134 158 134 158 135 157 135 159 135 158 135 159 135 160 135 160 136 159 136 161 136 160 137 161 137 162 137 162 138 161 138 163 138 162 139 163 139 164 139 164 140 163 140 165 140 164 141 165 141 166 141 166 142 165 142 167 142 166 143 167 143 168 143 168 144 167 144 169 144 168 145 169 145 170 145 170 146 169 146 171 146 170 147 171 147 172 147 172 148 171 148 173 148 172 149 173 149 174 149 174 150 173 150 175 150 174 151 175 151 176 151 176 152 175 152 177 152 176 153 177 153 178 153 178 154 177 154 179 154 178 155 179 155 180 155 180 156 179 156 181 156 180 157 181 157 182 157 182 158 181 158 183 158 182 159 183 159 184 159 184 160 183 160 185 160 184 160 185 160 186 160 186 161 185 161 187 161 186 162 187 162 188 162 188 163 187 163 189 163 188 163 189 163 190 163 190 164 189 164 191 164 190 164 191 164 192 164 192 165 191 165 193 165 192 166 193 166 194 166 194 167 193 167 195 167 194 167 195 167 196 167 196 168 195 168 197 168 196 169 197 169 198 169 198 170 197 170 199 170 198 170 199 170 200 170 200 171 199 171 201 171 200 172 201 172 202 172 202 173 201 173 203 173 202 173 203 173 204 173 204 174 203 174 205 174 204 174 205 174 206 174 206 175 205 175 207 175 206 175 207 175 208 175 208 176 207 176 209 176 208 177 209 177 210 177 210 178 209 178 211 178 210 179 211 179 212 179 212 180 211 180 213 180 212 180 213 180 214 180 214 181 213 181 215 181 214 182 215 182 216 182 216 183 215 183 217 183 216 184 217 184 218 184 218 185 217 185 219 185 218 186 219 186 220 186 220 187 219 187 221 187 220 187 221 187 222 187 222 188 221 188 223 188 222 189 223 189 224 189 224 190 223 190 225 190 224 191 225 191 226 191 226 192 225 192 227 192 226 193 227 193 228 193 228 194 227 194 229 194 228 195 229 195 230 195 230 196 229 196 231 196 230 197 231 197 232 197 232 198 231 198 233 198 232 199 233 199 234 199 234 200 233 200 235 200 234 201 235 201 236 201 236 202 235 202 237 202 236 203 237 203 238 203 238 204 237 204 239 204 238 205 239 205 240 205 240 206 239 206 241 206 240 207 241 207 242 207 242 208 241 208 243 208 242 209 243 209 244 209 244 210 243 210 245 210 244 210 245 210 246 210 246 211 245 211 247 211 246 212 247 212 248 212 248 213 247 213 249 213 248 214 249 214 250 214 250 215 249 215 251 215 250 216 251 216 252 216 252 217 251 217 253 217 252 218 253 218 254 218 254 219 253 219 255 219 254 220 255 220 256 220 256 221 255 221 257 221 256 221 257 221 258 221 258 222 257 222 259 222 258 223 259 223 260 223 260 224 259 224 261 224 260 225 261 225 262 225 262 226 261 226 263 226 262 227 263 227 264 227 264 228 263 228 265 228 264 229 265 229 266 229 266 230 265 230 267 230 266 231 267 231 268 231 268 232 267 232 269 232 268 232 269 232 270 232 270 233 269 233 271 233 270 234 271 234 272 234 272 235 271 235 273 235 272 236 273 236 274 236 274 237 273 237 275 237 274 238 275 238 276 238 276 239 275 239 277 239 276 240 277 240 278 240 278 241 277 241 279 241 278 242 279 242 280 242 280 243 279 243 281 243 280 244 281 244 282 244 282 245 281 245 283 245 282 246 283 246 284 246 284 247 283 247 285 247 284 248 285 248 286 248 286 249 285 249 287 249 286 250 287 250 288 250 288 251 287 251 289 251 288 252 289 252 290 252 290 253 289 253 291 253 290 254 291 254 292 254 292 255 291 255 293 255 292 255 293 255 294 255 294 256 293 256 295 256 294 257 295 257 296 257 296 258 295 258 297 258 296 259 297 259 298 259 298 260 297 260 299 260 298 261 299 261 300 261 300 262 299 262 301 262 300 262 301 262 302 262 302 263 301 263 303 263 302 264 303 264 304 264 304 265 303 265 305 265 304 266 305 266 306 266 306 267 305 267 307 267 306 267 307 267 308 267 308 268 307 268 309 268 308 268 309 268 310 268 310 269 309 269 311 269 310 269 311 269 312 269 312 270 311 270 313 270 312 271 313 271 314 271 314 272 313 272 315 272 314 272 315 272 316 272 316 273 315 273 317 273 316 274 317 274 318 274 318 275 317 275 319 275 318 275 319 275 320 275 320 276 319 276 321 276 320 277 321 277 322 277 322 278 321 278 323 278 322 278 323 278 324 278 324 279 323 279 325 279 324 279 325 279 326 279 326 280 325 280 327 280 326 281 327 281 328 281 328 282 327 282 329 282 328 282 329 282 330 282 330 283 329 283 331 283 330 284 331 284 332 284 332 285 331 285 333 285 332 286 333 286 334 286 334 287 333 287 335 287 334 288 335 288 336 288 336 289 335 289 337 289 336 290 337 290 338 290 338 291 337 291 339 291 338 292 339 292 85 292 85 293 339 293 84 293 340 294 341 294 342 294 342 294 341 294 343 294 342 294 343 294 344 294 345 294 346 294 347 294 347 294 346 294 348 294 347 294 348 294 349 294 350 294 351 294 352 294 352 294 351 294 353 294 352 294 353 294 354 294 354 294 353 294 355 294 354 294 355 294 356 294 348 294 357 294 349 294 349 294 357 294 358 294 349 294 358 294 359 294 359 294 358 294 360 294 359 294 360 294 361 294 361 294 360 294 362 294 361 294 362 294 363 294 343 294 364 294 344 294 344 294 364 294 365 294 344 294 365 294 366 294 366 294 365 294 367 294 366 294 367 294 345 294 345 294 367 294 368 294 345 294 368 294 346 294 355 294 369 294 356 294 356 294 369 294 370 294 356 295 370 295 371 295 371 294 370 294 372 294 371 294 372 294 373 294 374 294 375 294 376 294 376 294 375 294 377 294 376 294 377 294 350 294 350 296 377 296 378 296 350 294 378 294 351 294 379 294 380 294 381 294 381 294 380 294 382 294 381 294 382 294 383 294 384 294 385 294 386 294 386 294 385 294 387 294 386 294 387 294 388 294 389 294 390 294 391 294 391 294 390 294 392 294 391 294 392 294 374 294 374 297 392 297 393 297 374 294 393 294 375 294 394 294 395 294 396 294 396 294 395 294 397 294 396 294 397 294 398 294 398 298 397 298 399 298 398 294 399 294 400 294 401 294 402 294 403 294 403 294 402 294 404 294 403 294 404 294 394 294 394 294 404 294 405 294 394 294 405 294 395 294 406 294 407 294 408 294 408 294 407 294 409 294 408 294 409 294 401 294 401 294 409 294 410 294 401 294 410 294 402 294 411 294 412 294 413 294 413 294 412 294 414 294 413 294 414 294 415 294 415 294 414 294 416 294 415 294 416 294 417 294 382 294 418 294 383 294 383 294 418 294 419 294 383 294 419 294 420 294 420 294 419 294 421 294 420 294 421 294 411 294 411 294 421 294 422 294 411 294 422 294 412 294 387 294 423 294 388 294 388 294 423 294 424 294 388 294 424 294 425 294 425 294 424 294 426 294 425 294 426 294 427 294 427 294 426 294 428 294 427 294 428 294 340 294 340 294 428 294 429 294 340 294 429 294 341 294 430 294 431 294 432 294 432 294 431 294 433 294 432 294 433 294 384 294 384 294 433 294 434 294 384 294 434 294 385 294 435 294 436 294 437 294 437 294 436 294 438 294 437 294 438 294 430 294 430 294 438 294 439 294 430 294 439 294 431 294 440 294 441 294 442 294 442 294 441 294 443 294 442 294 443 294 444 294 444 294 443 294 445 294 444 294 445 294 435 294 435 294 445 294 446 294 435 294 446 294 436 294 372 294 447 294 373 294 373 294 447 294 448 294 373 294 448 294 449 294 449 294 448 294 450 294 449 294 450 294 451 294 452 294 453 294 454 294 454 294 453 294 455 294 454 294 455 294 456 294 457 294 458 294 459 294 459 294 458 294 460 294 459 294 460 294 461 294 461 294 460 294 462 294 461 294 462 294 452 294 452 294 462 294 463 294 452 294 463 294 453 294 464 294 465 294 466 294 466 294 465 294 467 294 466 294 467 294 468 294 469 294 470 294 471 294 471 294 470 294 472 294 471 294 472 294 473 294 474 294 475 294 476 294 476 294 475 294 477 294 476 294 477 294 440 294 440 294 477 294 478 294 440 294 478 294 441 294 479 294 480 294 481 294 481 294 480 294 482 294 481 294 482 294 474 294 474 294 482 294 483 294 474 294 483 294 475 294 484 294 485 294 486 294 486 294 485 294 487 294 486 294 487 294 488 294 488 294 487 294 489 294 488 294 489 294 479 294 479 294 489 294 490 294 479 294 490 294 480 294 399 299 491 299 400 299 400 294 491 294 492 294 400 294 492 294 493 294 493 294 492 294 494 294 493 294 494 294 389 294 389 294 494 294 495 294 389 294 495 294 390 294 496 294 497 294 498 294 498 294 497 294 499 294 498 294 499 294 500 294 416 294 501 294 417 294 417 294 501 294 502 294 417 294 502 294 503 294 503 294 502 294 504 294 503 294 504 294 505 294 506 300 507 300 508 300 508 294 507 294 509 294 508 294 509 294 379 294 379 294 509 294 510 294 379 294 510 294 380 294 467 301 511 301 468 301 468 294 511 294 512 294 468 294 512 294 513 294 513 294 512 294 514 294 513 294 514 294 515 294 515 294 514 294 516 294 515 294 516 294 506 294 506 294 516 294 517 294 506 294 517 294 507 294 472 294 518 294 473 294 473 294 518 294 519 294 473 294 519 294 520 294 520 294 519 294 521 294 520 294 521 294 522 294 522 302 521 302 523 302 522 294 523 294 524 294 525 294 526 294 527 294 527 294 526 294 528 294 527 294 528 294 469 294 469 294 528 294 529 294 469 294 529 294 470 294 450 294 530 294 451 294 451 294 530 294 531 294 451 294 531 294 532 294 532 294 531 294 533 294 532 294 533 294 484 294 484 294 533 294 534 294 484 294 534 294 485 294 499 294 535 294 500 294 500 294 535 294 536 294 500 294 536 294 537 294 537 294 536 294 538 294 537 294 538 294 539 294 539 294 538 294 540 294 539 294 540 294 541 294 504 294 542 294 505 294 505 294 542 294 543 294 505 294 543 294 544 294 544 294 543 294 545 294 544 294 545 294 457 294 457 294 545 294 546 294 457 294 546 294 458 294 547 294 548 294 549 294 549 294 548 294 550 294 549 294 550 294 464 294 464 303 550 303 551 303 464 294 551 294 465 294 523 304 552 304 524 304 524 294 552 294 553 294 524 294 553 294 554 294 554 294 553 294 555 294 554 294 555 294 547 294 547 294 555 294 556 294 547 294 556 294 548 294 557 294 558 294 559 294 559 294 558 294 560 294 559 294 560 294 561 294 562 294 563 294 564 294 564 294 563 294 565 294 564 294 565 294 566 294 567 294 568 294 569 294 569 294 568 294 570 294 569 294 570 294 496 294 496 294 570 294 571 294 496 294 571 294 497 294 455 294 572 294 456 294 456 294 572 294 573 294 456 294 573 294 574 294 574 294 573 294 575 294 574 294 575 294 576 294 577 294 578 294 579 294 579 294 578 294 580 294 579 294 580 294 581 294 581 294 580 294 582 294 581 294 582 294 525 294 525 294 582 294 583 294 525 294 583 294 526 294 560 294 584 294 561 294 561 294 584 294 585 294 561 294 585 294 586 294 586 294 585 294 587 294 586 294 587 294 577 294 577 294 587 294 588 294 577 294 588 294 578 294 362 294 589 294 363 294 363 294 589 294 590 294 363 294 590 294 591 294 591 294 590 294 592 294 591 294 592 294 557 294 557 294 592 294 593 294 557 294 593 294 558 294 565 294 594 294 566 294 566 294 594 294 595 294 566 294 595 294 596 294 596 294 595 294 597 294 596 294 597 294 598 294 598 294 597 294 599 294 598 294 599 294 406 294 406 294 599 294 600 294 406 294 600 294 407 294 601 294 602 294 603 294 603 294 602 294 604 294 603 294 604 294 567 294 567 294 604 294 605 294 567 294 605 294 568 294 606 294 607 294 608 294 608 294 607 294 609 294 608 294 609 294 610 294 610 294 609 294 611 294 610 294 611 294 601 294 601 294 611 294 612 294 601 294 612 294 602 294 613 294 614 294 615 294 615 294 614 294 616 294 615 294 616 294 562 294 562 294 616 294 617 294 562 294 617 294 563 294 540 294 618 294 541 294 541 294 618 294 619 294 541 294 619 294 620 294 620 294 619 294 621 294 620 294 621 294 613 294 613 294 621 294 622 294 613 294 622 294 614 294 575 294 623 294 576 294 576 294 623 294 624 294 576 294 624 294 625 294 625 294 624 294 626 294 625 294 626 294 606 294 606 294 626 294 627 294 606 294 627 294 607 294 628 305 169 305 629 305 628 305 629 305 173 305 179 305 177 305 629 305 629 305 177 305 175 305 629 305 175 305 173 305 185 305 183 305 629 305 629 305 183 305 181 305 629 305 181 305 179 305 191 305 189 305 629 305 629 305 189 305 187 305 629 305 187 305 185 305 197 305 195 305 629 305 629 305 195 305 193 305 629 305 193 305 191 305 203 305 201 305 629 305 629 305 201 305 199 305 629 305 199 305 197 305 209 305 207 305 629 305 629 305 207 305 205 305 629 305 205 305 203 305 215 305 213 305 629 305 629 305 213 305 211 305 629 305 211 305 209 305 221 305 219 305 629 305 629 305 219 305 217 305 629 305 217 305 215 305 227 305 225 305 629 305 629 305 225 305 223 305 629 305 223 305 221 305 233 305 231 305 629 305 629 305 231 305 229 305 629 305 229 305 227 305 239 305 237 305 629 305 629 305 237 305 235 305 629 305 235 305 233 305 245 305 243 305 629 305 629 305 243 305 241 305 629 305 241 305 239 305 251 305 249 305 629 305 629 305 249 305 247 305 629 305 247 305 245 305 257 305 255 305 629 305 629 305 255 305 253 305 629 305 253 305 251 305 263 305 261 305 629 305 629 305 261 305 259 305 629 305 259 305 257 305 269 305 267 305 629 305 629 305 267 305 265 305 629 305 265 305 263 305 275 305 273 305 629 305 629 305 273 305 271 305 629 305 271 305 269 305 281 305 279 305 629 305 629 305 279 305 277 305 629 305 277 305 275 305 287 305 285 305 629 305 629 305 285 305 283 305 629 305 283 305 281 305 293 305 291 305 629 305 629 305 291 305 289 305 629 305 289 305 287 305 299 305 297 305 629 305 629 305 297 305 295 305 629 305 295 305 293 305 305 305 303 305 629 305 629 305 303 305 301 305 629 305 301 305 299 305 311 305 309 305 629 305 629 305 309 305 307 305 629 305 307 305 305 305 317 305 315 305 629 305 629 305 315 305 313 305 629 305 313 305 311 305 323 305 321 305 629 305 629 305 321 305 319 305 629 305 319 305 317 305 329 305 327 305 629 305 629 305 327 305 325 305 629 305 325 305 323 305 335 305 333 305 629 305 629 305 333 305 331 305 629 305 331 305 329 305 84 305 339 305 629 305 629 305 339 305 337 305 629 305 337 305 335 305 78 305 80 305 629 305 629 305 80 305 82 305 629 305 82 305 84 305 72 305 74 305 629 305 629 305 74 305 76 305 629 305 76 305 78 305 66 305 68 305 629 305 629 305 68 305 70 305 629 305 70 305 72 305 60 305 62 305 629 305 629 305 62 305 64 305 629 305 64 305 66 305 54 305 56 305 629 305 629 305 56 305 58 305 629 305 58 305 60 305 48 305 50 305 629 305 629 305 50 305 52 305 629 305 52 305 54 305 42 305 44 305 629 305 629 305 44 305 46 305 629 305 46 305 48 305 36 305 38 305 629 305 629 305 38 305 40 305 629 305 40 305 42 305 30 305 32 305 629 305 629 305 32 305 34 305 629 305 34 305 36 305 24 305 26 305 629 305 629 305 26 305 28 305 629 305 28 305 30 305 18 305 20 305 629 305 629 305 20 305 22 305 629 305 22 305 24 305 12 305 14 305 629 305 629 305 14 305 16 305 629 305 16 305 18 305 6 305 8 305 629 305 629 305 8 305 10 305 629 305 10 305 12 305 0 305 2 305 629 305 629 305 2 305 4 305 629 305 4 305 6 305 91 305 89 305 629 305 629 305 89 305 87 305 629 305 87 305 0 305 97 305 95 305 629 305 629 305 95 305 93 305 629 305 93 305 91 305 103 305 101 305 629 305 629 305 101 305 99 305 629 305 99 305 97 305 109 305 107 305 629 305 629 305 107 305 105 305 629 305 105 305 103 305 115 305 113 305 629 305 629 305 113 305 111 305 629 305 111 305 109 305 121 305 119 305 629 305 629 305 119 305 117 305 629 305 117 305 115 305 127 305 125 305 629 305 629 305 125 305 123 305 629 305 123 305 121 305 133 305 131 305 629 305 629 305 131 305 129 305 629 305 129 305 127 305 139 305 137 305 629 305 629 305 137 305 135 305 629 305 135 305 133 305 145 305 143 305 629 305 629 305 143 305 141 305 629 305 141 305 139 305 151 305 149 305 629 305 629 305 149 305 147 305 629 305 147 305 145 305 157 305 155 305 629 305 629 305 155 305 153 305 629 305 153 305 151 305 163 305 161 305 629 305 629 305 161 305 159 305 629 305 159 305 157 305 169 305 167 305 629 305 629 305 167 305 165 305 629 305 165 305 163 305 86 306 568 306 1 306 1 307 568 307 605 307 1 308 605 308 3 308 3 309 605 309 604 309 3 310 604 310 5 310 5 311 604 311 602 311 5 312 602 312 7 312 7 313 602 313 612 313 7 314 612 314 9 314 9 315 612 315 611 315 9 316 611 316 11 316 11 317 611 317 609 317 11 318 609 318 13 318 13 319 609 319 607 319 13 320 607 320 15 320 15 321 607 321 627 321 15 322 627 322 17 322 17 323 627 323 626 323 17 324 626 324 19 324 19 325 626 325 624 325 19 326 624 326 21 326 21 327 624 327 623 327 21 328 623 328 23 328 23 329 623 329 575 329 23 330 575 330 25 330 25 331 575 331 573 331 25 332 573 332 27 332 27 333 573 333 572 333 27 334 572 334 29 334 29 335 572 335 455 335 29 336 455 336 31 336 31 337 455 337 453 337 31 338 453 338 33 338 33 339 453 339 463 339 33 340 463 340 35 340 35 341 463 341 462 341 35 342 462 342 37 342 37 343 462 343 460 343 37 344 460 344 39 344 39 345 460 345 458 345 39 346 458 346 41 346 41 347 458 347 546 347 41 348 546 348 43 348 43 349 546 349 545 349 43 350 545 350 45 350 45 351 545 351 543 351 45 352 543 352 47 352 47 353 543 353 542 353 47 354 542 354 49 354 49 355 542 355 504 355 49 356 504 356 51 356 51 357 504 357 502 357 51 358 502 358 53 358 53 359 502 359 501 359 53 360 501 360 55 360 55 361 501 361 416 361 55 362 416 362 57 362 57 363 416 363 414 363 57 364 414 364 59 364 59 365 414 365 412 365 59 366 412 366 61 366 61 367 412 367 422 367 61 368 422 368 63 368 63 369 422 369 421 369 63 370 421 370 65 370 65 371 421 371 419 371 65 372 419 372 67 372 67 373 419 373 418 373 67 374 418 374 69 374 69 375 418 375 382 375 69 376 382 376 71 376 71 377 382 377 380 377 71 378 380 378 73 378 73 379 380 379 510 379 73 380 510 380 75 380 75 381 510 381 509 381 75 382 509 382 77 382 77 383 509 383 507 383 77 384 507 384 79 384 79 385 507 385 517 385 79 386 517 386 81 386 81 387 517 387 516 387 81 388 516 388 83 388 83 389 516 389 514 389 568 390 86 390 570 390 570 391 86 391 88 391 570 392 88 392 571 392 571 393 88 393 90 393 571 394 90 394 497 394 497 395 90 395 92 395 497 396 92 396 499 396 499 397 92 397 94 397 499 398 94 398 535 398 535 399 94 399 96 399 535 400 96 400 536 400 536 401 96 401 98 401 536 402 98 402 538 402 538 403 98 403 100 403 538 404 100 404 540 404 540 405 100 405 102 405 540 406 102 406 618 406 618 407 102 407 104 407 618 408 104 408 619 408 619 409 104 409 106 409 619 410 106 410 621 410 621 411 106 411 108 411 621 412 108 412 622 412 622 413 108 413 110 413 622 414 110 414 614 414 614 415 110 415 112 415 614 416 112 416 616 416 616 417 112 417 114 417 616 418 114 418 617 418 617 419 114 419 116 419 617 420 116 420 563 420 563 421 116 421 118 421 563 422 118 422 565 422 565 423 118 423 120 423 565 424 120 424 594 424 594 425 120 425 122 425 594 426 122 426 595 426 595 427 122 427 124 427 595 428 124 428 597 428 597 429 124 429 126 429 597 430 126 430 599 430 599 431 126 431 128 431 599 432 128 432 600 432 600 433 128 433 130 433 600 434 130 434 407 434 407 435 130 435 132 435 407 436 132 436 409 436 409 437 132 437 134 437 409 438 134 438 410 438 410 439 134 439 136 439 410 440 136 440 402 440 402 441 136 441 138 441 402 442 138 442 404 442 404 443 138 443 140 443 404 444 140 444 405 444 405 445 140 445 142 445 405 446 142 446 395 446 395 447 142 447 144 447 395 448 144 448 397 448 397 449 144 449 146 449 397 450 146 450 399 450 399 451 146 451 148 451 399 452 148 452 491 452 491 453 148 453 150 453 491 454 150 454 492 454 492 455 150 455 152 455 492 456 152 456 494 456 494 457 152 457 154 457 494 458 154 458 495 458 495 459 154 459 156 459 495 460 156 460 390 460 390 461 156 461 158 461 390 462 158 462 392 462 392 463 158 463 160 463 392 464 160 464 393 464 393 465 160 465 162 465 393 466 162 466 375 466 375 467 162 467 164 467 375 468 164 468 377 468 377 469 164 469 166 469 377 470 166 470 378 470 378 471 166 471 168 471 378 472 168 472 351 472 351 473 168 473 170 473 351 474 170 474 353 474 353 475 170 475 630 475 353 476 630 476 631 476 631 477 630 477 174 477 631 478 174 478 369 478 369 479 174 479 176 479 369 480 176 480 370 480 370 481 176 481 178 481 370 482 178 482 372 482 372 483 178 483 180 483 372 484 180 484 447 484 447 485 180 485 182 485 447 486 182 486 448 486 448 487 182 487 184 487 448 488 184 488 450 488 450 489 184 489 186 489 450 490 186 490 530 490 530 491 186 491 188 491 530 492 188 492 531 492 531 493 188 493 190 493 531 494 190 494 533 494 533 495 190 495 192 495 533 496 192 496 534 496 534 497 192 497 194 497 534 498 194 498 485 498 485 499 194 499 196 499 485 500 196 500 487 500 487 501 196 501 198 501 487 502 198 502 489 502 489 503 198 503 200 503 489 504 200 504 490 504 490 505 200 505 202 505 490 506 202 506 480 506 480 507 202 507 204 507 480 508 204 508 482 508 482 509 204 509 206 509 482 510 206 510 483 510 483 511 206 511 208 511 483 512 208 512 475 512 475 513 208 513 210 513 475 514 210 514 477 514 477 515 210 515 212 515 477 516 212 516 478 516 478 517 212 517 214 517 478 518 214 518 441 518 441 519 214 519 216 519 441 520 216 520 443 520 443 521 216 521 218 521 443 522 218 522 445 522 445 523 218 523 220 523 445 524 220 524 446 524 446 525 220 525 222 525 446 526 222 526 436 526 436 527 222 527 224 527 436 528 224 528 438 528 438 529 224 529 226 529 438 530 226 530 439 530 439 531 226 531 228 531 439 532 228 532 431 532 431 533 228 533 230 533 431 534 230 534 433 534 433 535 230 535 232 535 433 536 232 536 434 536 434 537 232 537 234 537 434 538 234 538 385 538 385 539 234 539 236 539 385 540 236 540 387 540 387 541 236 541 238 541 387 542 238 542 423 542 423 543 238 543 240 543 423 544 240 544 424 544 424 545 240 545 242 545 424 546 242 546 426 546 426 547 242 547 244 547 426 548 244 548 428 548 428 549 244 549 246 549 428 550 246 550 429 550 429 551 246 551 248 551 429 552 248 552 341 552 341 553 248 553 250 553 341 554 250 554 343 554 343 555 250 555 252 555 343 556 252 556 364 556 364 557 252 557 254 557 364 558 254 558 365 558 365 559 254 559 256 559 365 560 256 560 367 560 367 561 256 561 258 561 367 562 258 562 368 562 368 563 258 563 260 563 368 564 260 564 346 564 346 565 260 565 262 565 346 566 262 566 348 566 348 567 262 567 264 567 348 568 264 568 357 568 357 569 264 569 266 569 357 570 266 570 358 570 358 571 266 571 268 571 358 572 268 572 360 572 360 573 268 573 270 573 360 574 270 574 362 574 362 575 270 575 272 575 362 576 272 576 589 576 589 577 272 577 274 577 589 578 274 578 590 578 590 579 274 579 276 579 590 580 276 580 592 580 592 581 276 581 278 581 592 582 278 582 593 582 593 583 278 583 280 583 593 584 280 584 558 584 558 585 280 585 282 585 558 586 282 586 560 586 560 587 282 587 284 587 560 588 284 588 584 588 584 589 284 589 286 589 584 590 286 590 585 590 585 591 286 591 288 591 585 592 288 592 587 592 587 593 288 593 290 593 587 594 290 594 588 594 588 595 290 595 292 595 588 596 292 596 578 596 578 597 292 597 294 597 578 598 294 598 580 598 580 599 294 599 296 599 580 600 296 600 582 600 582 601 296 601 298 601 582 602 298 602 583 602 583 603 298 603 300 603 583 604 300 604 526 604 526 605 300 605 302 605 526 606 302 606 528 606 528 607 302 607 304 607 528 608 304 608 529 608 529 609 304 609 306 609 529 610 306 610 470 610 470 611 306 611 308 611 470 612 308 612 472 612 472 613 308 613 310 613 472 614 310 614 518 614 518 615 310 615 312 615 518 616 312 616 519 616 519 617 312 617 314 617 519 618 314 618 521 618 521 619 314 619 316 619 521 620 316 620 523 620 523 621 316 621 318 621 523 622 318 622 552 622 552 623 318 623 320 623 552 624 320 624 553 624 553 625 320 625 322 625 553 626 322 626 555 626 555 627 322 627 324 627 555 628 324 628 556 628 556 629 324 629 326 629 556 630 326 630 548 630 548 631 326 631 328 631 548 632 328 632 550 632 550 633 328 633 330 633 550 634 330 634 551 634 551 635 330 635 332 635 551 636 332 636 465 636 465 637 332 637 334 637 465 638 334 638 467 638 467 639 334 639 336 639 467 640 336 640 511 640 511 641 336 641 338 641 511 642 338 642 512 642 512 643 338 643 85 643 512 644 85 644 514 644 514 645 85 645 83 645 632 646 633 646 634 646 632 647 635 647 633 647 633 648 635 648 636 648 633 649 636 649 637 649 636 650 638 650 637 650 637 651 638 651 639 651 637 652 639 652 640 652 639 653 641 653 640 653 640 654 641 654 642 654 640 655 642 655 643 655 642 656 644 656 643 656 643 657 644 657 645 657 643 658 645 658 646 658 645 659 647 659 646 659 646 660 647 660 648 660 646 661 648 661 649 661 648 662 650 662 649 662 649 663 650 663 651 663 649 664 651 664 652 664 651 665 653 665 652 665 652 666 653 666 654 666 652 667 654 667 655 667 654 668 656 668 655 668 655 669 656 669 657 669 655 670 657 670 658 670 657 671 659 671 658 671 658 672 659 672 660 672 658 673 660 673 661 673 660 674 662 674 661 674 661 675 662 675 663 675 661 676 663 676 664 676 663 677 665 677 664 677 664 678 665 678 666 678 664 679 666 679 667 679 666 680 668 680 667 680 667 681 668 681 669 681 667 682 669 682 670 682 669 683 671 683 670 683 670 684 671 684 672 684 670 685 672 685 673 685 672 686 674 686 673 686 673 687 674 687 675 687 673 688 675 688 676 688 675 689 677 689 676 689 676 690 677 690 678 690 676 691 678 691 679 691 678 692 680 692 679 692 679 693 680 693 681 693 679 694 681 694 682 694 681 695 683 695 682 695 682 696 683 696 684 696 682 697 684 697 685 697 684 698 686 698 685 698 685 699 686 699 687 699 685 700 687 700 688 700 688 701 687 701 689 701 688 702 689 702 690 702 689 703 691 703 690 703 690 704 691 704 692 704 690 705 692 705 693 705 692 706 694 706 693 706 693 707 694 707 695 707 693 708 695 708 696 708 695 709 697 709 696 709 696 710 697 710 698 710 696 711 698 711 699 711 698 712 700 712 699 712 699 713 700 713 701 713 699 714 701 714 702 714 701 715 703 715 702 715 702 716 703 716 704 716 702 717 704 717 705 717 704 718 706 718 705 718 705 719 706 719 707 719 705 720 707 720 708 720 707 721 709 721 708 721 708 722 709 722 710 722 708 723 710 723 711 723 710 724 712 724 711 724 711 725 712 725 713 725 711 726 713 726 714 726 713 727 715 727 714 727 714 728 715 728 716 728 714 729 716 729 717 729 717 730 716 730 718 730 718 731 719 731 717 731 717 732 719 732 720 732 717 733 720 733 721 733 720 734 722 734 721 734 721 735 722 735 723 735 721 736 723 736 724 736 723 737 725 737 724 737 724 738 725 738 726 738 724 739 726 739 727 739 726 740 728 740 727 740 727 741 728 741 729 741 727 742 729 742 730 742 729 743 731 743 730 743 730 744 731 744 732 744 730 745 732 745 733 745 732 746 734 746 733 746 733 747 734 747 735 747 733 748 735 748 736 748 735 749 737 749 736 749 736 750 737 750 738 750 736 751 738 751 739 751 738 752 740 752 739 752 739 753 740 753 741 753 739 754 741 754 742 754 741 755 743 755 742 755 742 756 743 756 744 756 742 757 744 757 745 757 744 758 746 758 745 758 745 759 746 759 747 759 745 760 747 760 748 760 747 761 749 761 748 761 748 762 749 762 750 762 748 763 750 763 751 763 750 764 752 764 751 764 751 765 752 765 753 765 751 766 753 766 754 766 753 767 755 767 754 767 754 768 755 768 756 768 754 769 756 769 757 769 756 770 758 770 757 770 757 771 758 771 759 771 757 772 759 772 760 772 759 773 761 773 760 773 760 774 761 774 762 774 760 775 762 775 763 775 762 776 764 776 763 776 763 777 764 777 765 777 763 778 765 778 766 778 765 779 767 779 766 779 766 780 767 780 768 780 766 781 768 781 769 781 768 782 770 782 769 782 769 783 770 783 771 783 769 784 771 784 772 784 771 785 773 785 772 785 772 786 773 786 774 786 772 787 774 787 775 787 774 788 776 788 775 788 775 789 776 789 777 789 775 790 777 790 778 790 777 791 779 791 778 791 778 792 779 792 780 792 778 793 780 793 781 793 780 794 782 794 781 794 781 795 782 795 783 795 781 796 783 796 784 796 783 797 785 797 784 797 784 798 785 798 786 798 784 799 786 799 787 799 786 800 788 800 787 800 787 801 788 801 789 801 787 802 789 802 790 802 789 803 791 803 790 803 790 804 791 804 792 804 790 805 792 805 793 805 792 806 794 806 793 806 793 807 794 807 795 807 793 808 795 808 796 808 795 809 797 809 796 809 796 810 797 810 798 810 796 811 798 811 799 811 798 812 800 812 799 812 799 813 800 813 801 813 799 814 801 814 802 814 801 815 803 815 802 815 802 816 803 816 804 816 802 817 804 817 805 817 804 818 806 818 805 818 805 819 806 819 807 819 805 820 807 820 808 820 807 821 809 821 808 821 808 822 809 822 810 822 808 823 810 823 811 823 810 824 812 824 811 824 811 825 812 825 813 825 811 826 813 826 814 826 813 827 815 827 814 827 814 828 815 828 816 828 814 829 816 829 817 829 816 830 818 830 817 830 817 831 818 831 819 831 817 832 819 832 820 832 819 833 821 833 820 833 820 834 821 834 822 834 820 835 822 835 823 835 822 836 824 836 823 836 823 837 824 837 825 837 823 838 825 838 826 838 825 839 827 839 826 839 826 840 827 840 828 840 826 841 828 841 829 841 828 842 830 842 829 842 829 843 830 843 831 843 829 844 831 844 832 844 831 845 833 845 832 845 832 846 833 846 834 846 832 847 834 847 835 847 834 848 836 848 835 848 835 849 836 849 837 849 835 850 837 850 838 850 837 851 839 851 838 851 838 852 839 852 840 852 838 853 840 853 841 853 840 854 842 854 841 854 841 855 842 855 843 855 841 856 843 856 844 856 843 857 845 857 844 857 844 858 845 858 846 858 844 859 846 859 847 859 846 860 848 860 847 860 847 861 848 861 849 861 847 862 849 862 850 862 849 863 851 863 850 863 850 864 851 864 852 864 850 865 852 865 853 865 852 866 854 866 853 866 853 867 854 867 855 867 853 868 855 868 856 868 855 869 857 869 856 869 856 870 857 870 858 870 856 871 858 871 859 871 858 872 860 872 859 872 859 873 860 873 861 873 859 874 861 874 862 874 862 875 861 875 863 875 862 876 863 876 864 876 863 877 865 877 864 877 864 878 865 878 866 878 864 879 866 879 867 879 866 880 868 880 867 880 867 881 868 881 869 881 867 882 869 882 870 882 869 883 871 883 870 883 870 884 871 884 872 884 870 885 872 885 873 885 872 886 874 886 873 886 873 887 874 887 875 887 873 888 875 888 876 888 875 889 877 889 876 889 876 890 877 890 878 890 876 891 878 891 879 891 878 892 880 892 879 892 879 893 880 893 881 893 879 894 881 894 882 894 881 895 883 895 882 895 882 896 883 896 884 896 882 897 884 897 885 897 884 898 886 898 885 898 885 899 886 899 887 899 885 900 887 900 888 900 887 901 889 901 888 901 888 902 889 902 890 902 888 903 890 903 891 903 891 904 890 904 892 904 892 905 893 905 891 905 891 906 893 906 894 906 891 907 894 907 895 907 894 908 896 908 895 908 895 909 896 909 897 909 895 910 897 910 898 910 897 911 899 911 898 911 898 912 899 912 900 912 898 913 900 913 901 913 900 914 902 914 901 914 901 915 902 915 903 915 901 916 903 916 904 916 903 917 905 917 904 917 904 918 905 918 906 918 904 919 906 919 907 919 906 920 908 920 907 920 907 921 908 921 909 921 907 922 909 922 910 922 909 923 911 923 910 923 910 924 911 924 912 924 910 925 912 925 913 925 912 926 914 926 913 926 913 927 914 927 915 927 913 928 915 928 916 928 915 929 917 929 916 929 916 930 917 930 918 930 916 931 918 931 919 931 918 932 920 932 919 932 919 933 920 933 921 933 919 934 921 934 922 934 921 935 923 935 922 935 922 936 923 936 924 936 922 937 924 937 925 937 924 938 926 938 925 938 925 939 926 939 927 939 925 940 927 940 928 940 927 941 929 941 928 941 928 942 929 942 930 942 928 943 930 943 931 943 930 944 932 944 931 944 931 945 932 945 933 945 931 946 933 946 934 946 933 947 935 947 934 947 934 948 935 948 936 948 934 949 936 949 937 949 936 950 938 950 937 950 937 951 938 951 939 951 937 952 939 952 940 952 939 953 941 953 940 953 940 954 941 954 942 954 940 955 942 955 943 955 942 956 944 956 943 956 943 957 944 957 945 957 943 958 945 958 946 958 945 959 947 959 946 959 946 960 947 960 948 960 946 961 948 961 949 961 948 962 950 962 949 962 949 963 950 963 951 963 949 964 951 964 952 964 951 965 953 965 952 965 952 966 953 966 954 966 952 967 954 967 955 967 954 968 956 968 955 968 955 969 956 969 957 969 955 970 957 970 958 970 957 971 959 971 958 971 958 972 959 972 960 972 958 973 960 973 961 973 960 974 962 974 961 974 961 975 962 975 963 975 961 976 963 976 964 976 963 977 965 977 964 977 964 978 965 978 966 978 964 979 966 979 967 979 966 980 968 980 967 980 967 981 968 981 969 981 967 982 969 982 970 982 969 983 971 983 970 983 970 984 971 984 972 984 970 985 972 985 973 985 972 986 974 986 973 986 973 987 974 987 975 987 973 988 975 988 976 988 975 989 977 989 976 989 976 990 977 990 978 990 976 991 978 991 634 991 634 992 978 992 979 992 634 993 979 993 632 993 634 294 633 294 980 294 634 294 980 294 976 294 967 294 970 294 980 294 980 994 970 994 973 994 980 294 973 294 976 294 958 294 961 294 980 294 980 995 961 995 964 995 980 294 964 294 967 294 949 294 952 294 980 294 980 996 952 996 955 996 980 997 955 997 958 997 940 294 943 294 980 294 980 998 943 998 946 998 980 999 946 999 949 999 931 294 934 294 980 294 980 1000 934 1000 937 1000 980 294 937 294 940 294 922 1001 925 1001 980 1001 980 1002 925 1002 928 1002 980 294 928 294 931 294 913 1003 916 1003 980 1003 980 1004 916 1004 919 1004 980 1005 919 1005 922 1005 904 1006 907 1006 980 1006 980 1007 907 1007 910 1007 980 1008 910 1008 913 1008 895 294 898 294 980 294 980 294 898 294 901 294 980 1009 901 1009 904 1009 885 294 888 294 980 294 980 1010 888 1010 891 1010 980 1011 891 1011 895 1011 876 1012 879 1012 980 1012 980 997 879 997 882 997 980 294 882 294 885 294 867 1013 870 1013 980 1013 980 1014 870 1014 873 1014 980 1015 873 1015 876 1015 859 1016 862 1016 980 1016 980 1017 862 1017 864 1017 980 1018 864 1018 867 1018 850 294 853 294 980 294 980 294 853 294 856 294 980 1019 856 1019 859 1019 841 294 844 294 980 294 980 294 844 294 847 294 980 1020 847 1020 850 1020 832 294 835 294 980 294 980 1021 835 1021 838 1021 980 1022 838 1022 841 1022 823 294 826 294 980 294 980 1009 826 1009 829 1009 980 1023 829 1023 832 1023 814 294 817 294 980 294 980 294 817 294 820 294 980 1024 820 1024 823 1024 805 294 808 294 980 294 980 294 808 294 811 294 980 1025 811 1025 814 1025 796 294 799 294 980 294 980 294 799 294 802 294 980 294 802 294 805 294 787 294 790 294 980 294 980 294 790 294 793 294 980 1026 793 1026 796 1026 778 1027 781 1027 980 1027 980 1009 781 1009 784 1009 980 1028 784 1028 787 1028 769 1029 772 1029 980 1029 980 1021 772 1021 775 1021 980 1030 775 1030 778 1030 760 294 763 294 980 294 980 294 763 294 766 294 980 294 766 294 769 294 751 294 754 294 980 294 980 294 754 294 757 294 980 1031 757 1031 760 1031 742 294 745 294 980 294 980 1017 745 1017 748 1017 980 1032 748 1032 751 1032 733 294 736 294 980 294 980 1014 736 1014 739 1014 980 1033 739 1033 742 1033 724 294 727 294 980 294 980 997 727 997 730 997 980 1034 730 1034 733 1034 714 294 717 294 980 294 980 1010 717 1010 721 1010 980 1035 721 1035 724 1035 705 294 708 294 980 294 980 294 708 294 711 294 980 1036 711 1036 714 1036 696 1037 699 1037 980 1037 980 1007 699 1007 702 1007 980 1038 702 1038 705 1038 688 294 690 294 980 294 980 1004 690 1004 693 1004 980 1039 693 1039 696 1039 679 294 682 294 980 294 980 1002 682 1002 685 1002 980 1040 685 1040 688 1040 670 294 673 294 980 294 980 1000 673 1000 676 1000 980 1041 676 1041 679 1041 661 294 664 294 980 294 980 998 664 998 667 998 980 294 667 294 670 294 652 294 655 294 980 294 980 996 655 996 658 996 980 1042 658 1042 661 1042 643 294 646 294 980 294 980 995 646 995 649 995 980 1043 649 1043 652 1043 633 294 637 294 980 294 980 994 637 994 640 994 980 1044 640 1044 643 1044 350 1045 352 1045 977 1045 977 1046 975 1046 350 1046 350 1047 975 1047 974 1047 350 1048 974 1048 376 1048 974 1049 972 1049 376 1049 376 1050 972 1050 971 1050 376 1051 971 1051 374 1051 971 1052 969 1052 374 1052 374 1053 969 1053 968 1053 374 1054 968 1054 391 1054 968 1055 966 1055 391 1055 391 1056 966 1056 965 1056 391 1057 965 1057 389 1057 965 1058 963 1058 389 1058 389 1059 963 1059 962 1059 389 1060 962 1060 493 1060 962 1061 960 1061 493 1061 493 1062 960 1062 959 1062 493 1063 959 1063 400 1063 959 1064 957 1064 400 1064 400 1065 957 1065 956 1065 400 1066 956 1066 398 1066 956 1067 954 1067 398 1067 398 1068 954 1068 953 1068 398 1069 953 1069 396 1069 953 1070 951 1070 396 1070 396 1071 951 1071 950 1071 396 1072 950 1072 394 1072 950 1073 948 1073 394 1073 394 1074 948 1074 947 1074 394 1075 947 1075 403 1075 947 1076 945 1076 403 1076 403 1077 945 1077 944 1077 403 1078 944 1078 401 1078 944 1079 942 1079 401 1079 401 1080 942 1080 941 1080 401 1081 941 1081 408 1081 941 1082 939 1082 408 1082 408 1083 939 1083 938 1083 408 1084 938 1084 406 1084 938 1085 936 1085 406 1085 406 1086 936 1086 935 1086 406 1087 935 1087 598 1087 935 1088 933 1088 598 1088 598 1089 933 1089 932 1089 598 1090 932 1090 596 1090 932 1091 930 1091 596 1091 596 1092 930 1092 929 1092 596 1093 929 1093 566 1093 929 1094 927 1094 566 1094 566 1095 927 1095 926 1095 566 1096 926 1096 564 1096 926 1097 924 1097 564 1097 564 1098 924 1098 923 1098 564 1099 923 1099 562 1099 923 1100 921 1100 562 1100 562 1101 921 1101 920 1101 562 1102 920 1102 615 1102 920 1103 918 1103 615 1103 615 1104 918 1104 917 1104 615 1105 917 1105 613 1105 917 1106 915 1106 613 1106 613 1107 915 1107 914 1107 613 1108 914 1108 620 1108 914 1109 912 1109 620 1109 620 1110 912 1110 911 1110 620 1111 911 1111 541 1111 911 1112 909 1112 541 1112 541 1113 909 1113 908 1113 541 1114 908 1114 539 1114 908 1115 906 1115 539 1115 539 1116 906 1116 905 1116 539 1117 905 1117 537 1117 905 1118 903 1118 537 1118 537 1119 903 1119 902 1119 537 1120 902 1120 500 1120 902 1121 900 1121 500 1121 500 1122 900 1122 899 1122 500 1123 899 1123 498 1123 899 1124 897 1124 498 1124 498 1125 897 1125 896 1125 498 1126 896 1126 496 1126 496 1127 896 1127 894 1127 496 1128 894 1128 569 1128 894 1129 893 1129 569 1129 569 1130 893 1130 892 1130 569 1131 892 1131 567 1131 892 1132 890 1132 567 1132 567 1133 890 1133 889 1133 567 1134 889 1134 603 1134 889 1135 887 1135 603 1135 603 1136 887 1136 886 1136 603 1137 886 1137 601 1137 886 1138 884 1138 601 1138 601 1139 884 1139 883 1139 601 1140 883 1140 610 1140 883 1141 881 1141 610 1141 610 1142 881 1142 880 1142 610 1143 880 1143 608 1143 880 1144 878 1144 608 1144 608 1145 878 1145 877 1145 608 1146 877 1146 606 1146 877 1147 875 1147 606 1147 606 1148 875 1148 874 1148 606 1149 874 1149 625 1149 874 1150 872 1150 625 1150 625 1151 872 1151 871 1151 625 1152 871 1152 576 1152 871 1153 869 1153 576 1153 576 1154 869 1154 868 1154 576 1155 868 1155 574 1155 868 1156 866 1156 574 1156 574 1157 866 1157 865 1157 574 1158 865 1158 456 1158 865 1159 863 1159 456 1159 456 1160 863 1160 861 1160 456 1161 861 1161 454 1161 861 1162 860 1162 454 1162 454 1163 860 1163 858 1163 454 1164 858 1164 452 1164 858 1165 857 1165 452 1165 452 1166 857 1166 855 1166 452 1167 855 1167 461 1167 855 1168 854 1168 461 1168 461 1169 854 1169 852 1169 461 1170 852 1170 459 1170 852 1171 851 1171 459 1171 459 1172 851 1172 849 1172 459 1173 849 1173 457 1173 849 1174 848 1174 457 1174 457 1175 848 1175 846 1175 457 1176 846 1176 544 1176 846 1177 845 1177 544 1177 544 1178 845 1178 843 1178 544 1179 843 1179 505 1179 843 1180 842 1180 505 1180 505 1181 842 1181 840 1181 505 1182 840 1182 503 1182 840 1183 839 1183 503 1183 503 1184 839 1184 837 1184 503 1185 837 1185 417 1185 837 1186 836 1186 417 1186 417 1187 836 1187 834 1187 417 1188 834 1188 415 1188 834 1189 833 1189 415 1189 415 1190 833 1190 831 1190 415 1191 831 1191 413 1191 831 1192 830 1192 413 1192 413 1193 830 1193 828 1193 413 1194 828 1194 411 1194 828 1195 827 1195 411 1195 411 1196 827 1196 825 1196 411 1197 825 1197 420 1197 825 1198 824 1198 420 1198 420 1199 824 1199 822 1199 420 1200 822 1200 383 1200 822 1201 821 1201 383 1201 383 1202 821 1202 819 1202 383 1203 819 1203 381 1203 819 1204 818 1204 381 1204 381 1205 818 1205 816 1205 381 1206 816 1206 379 1206 816 1207 815 1207 379 1207 379 1208 815 1208 813 1208 379 1209 813 1209 508 1209 813 1210 812 1210 508 1210 508 1211 812 1211 810 1211 508 1212 810 1212 506 1212 810 1213 809 1213 506 1213 506 1214 809 1214 807 1214 506 1215 807 1215 981 1215 981 1216 807 1216 982 1216 981 1217 982 1217 513 1217 982 1218 804 1218 513 1218 513 1219 804 1219 803 1219 513 1220 803 1220 468 1220 803 1221 801 1221 468 1221 468 1222 801 1222 800 1222 468 1223 800 1223 466 1223 800 1224 798 1224 466 1224 466 1225 798 1225 797 1225 466 1226 797 1226 464 1226 797 1227 795 1227 464 1227 464 1228 795 1228 794 1228 464 1229 794 1229 549 1229 794 1230 792 1230 549 1230 549 1231 792 1231 791 1231 549 1232 791 1232 547 1232 791 1233 789 1233 547 1233 547 1234 789 1234 788 1234 547 1235 788 1235 554 1235 788 1236 786 1236 554 1236 554 1237 786 1237 785 1237 554 1238 785 1238 524 1238 785 1239 783 1239 524 1239 524 1240 783 1240 782 1240 524 1241 782 1241 522 1241 782 1242 780 1242 522 1242 522 1243 780 1243 779 1243 522 1244 779 1244 520 1244 779 1245 777 1245 520 1245 520 1246 777 1246 776 1246 520 1247 776 1247 473 1247 776 1248 774 1248 473 1248 473 1249 774 1249 773 1249 473 1250 773 1250 471 1250 773 1251 771 1251 471 1251 471 1252 771 1252 770 1252 471 1253 770 1253 469 1253 770 1254 768 1254 469 1254 469 1255 768 1255 767 1255 469 1256 767 1256 527 1256 767 1257 765 1257 527 1257 527 1258 765 1258 764 1258 527 1259 764 1259 525 1259 764 1260 762 1260 525 1260 525 1261 762 1261 761 1261 525 1262 761 1262 581 1262 761 1263 759 1263 581 1263 581 1264 759 1264 758 1264 581 1265 758 1265 579 1265 758 1266 756 1266 579 1266 579 1267 756 1267 755 1267 579 1268 755 1268 577 1268 755 1269 753 1269 577 1269 577 1270 753 1270 752 1270 577 1271 752 1271 586 1271 752 1272 750 1272 586 1272 586 1273 750 1273 749 1273 586 1274 749 1274 561 1274 749 1275 747 1275 561 1275 561 1276 747 1276 746 1276 561 1277 746 1277 559 1277 746 1278 744 1278 559 1278 559 1279 744 1279 743 1279 559 1280 743 1280 557 1280 743 1281 741 1281 557 1281 557 1282 741 1282 740 1282 557 1283 740 1283 591 1283 740 1284 738 1284 591 1284 591 1285 738 1285 737 1285 591 1286 737 1286 363 1286 737 1287 735 1287 363 1287 363 1288 735 1288 734 1288 363 1289 734 1289 361 1289 734 1290 732 1290 361 1290 361 1291 732 1291 731 1291 361 1292 731 1292 359 1292 731 1293 729 1293 359 1293 359 1294 729 1294 728 1294 359 1295 728 1295 349 1295 728 1296 726 1296 349 1296 349 1297 726 1297 725 1297 349 1298 725 1298 347 1298 725 1299 723 1299 347 1299 347 1300 723 1300 722 1300 347 1301 722 1301 345 1301 345 1302 722 1302 720 1302 345 1303 720 1303 366 1303 720 1304 719 1304 366 1304 366 1305 719 1305 718 1305 366 1306 718 1306 344 1306 718 1307 716 1307 344 1307 344 1308 716 1308 715 1308 344 1309 715 1309 342 1309 715 1310 713 1310 342 1310 342 1311 713 1311 712 1311 342 1312 712 1312 340 1312 712 1313 710 1313 340 1313 340 1314 710 1314 709 1314 340 1315 709 1315 427 1315 709 1316 707 1316 427 1316 427 1317 707 1317 706 1317 427 1318 706 1318 425 1318 706 1319 704 1319 425 1319 425 1320 704 1320 703 1320 425 1321 703 1321 388 1321 703 1322 701 1322 388 1322 388 1323 701 1323 700 1323 388 1324 700 1324 386 1324 700 1325 698 1325 386 1325 386 1326 698 1326 697 1326 386 1327 697 1327 384 1327 697 1328 695 1328 384 1328 384 1329 695 1329 694 1329 384 1330 694 1330 432 1330 694 1331 692 1331 432 1331 432 1332 692 1332 691 1332 432 1333 691 1333 430 1333 691 1334 689 1334 430 1334 430 1335 689 1335 687 1335 430 1336 687 1336 437 1336 687 1337 686 1337 437 1337 437 1338 686 1338 684 1338 437 1339 684 1339 435 1339 684 1340 683 1340 435 1340 435 1341 683 1341 681 1341 435 1342 681 1342 444 1342 681 1343 680 1343 444 1343 444 1344 680 1344 678 1344 444 1345 678 1345 442 1345 678 1346 677 1346 442 1346 442 1347 677 1347 675 1347 442 1348 675 1348 440 1348 675 1349 674 1349 440 1349 440 1350 674 1350 672 1350 440 1351 672 1351 476 1351 672 1352 671 1352 476 1352 476 1353 671 1353 669 1353 476 1354 669 1354 474 1354 669 1355 668 1355 474 1355 474 1356 668 1356 666 1356 474 1357 666 1357 481 1357 666 1358 665 1358 481 1358 481 1359 665 1359 663 1359 481 1360 663 1360 479 1360 663 1361 662 1361 479 1361 479 1362 662 1362 660 1362 479 1363 660 1363 488 1363 660 1364 659 1364 488 1364 488 1365 659 1365 657 1365 488 1366 657 1366 486 1366 657 1367 656 1367 486 1367 486 1368 656 1368 654 1368 486 1369 654 1369 484 1369 654 1370 653 1370 484 1370 484 1371 653 1371 651 1371 484 1372 651 1372 532 1372 651 1373 650 1373 532 1373 532 1374 650 1374 648 1374 532 1375 648 1375 451 1375 648 1376 647 1376 451 1376 451 1377 647 1377 645 1377 451 1378 645 1378 449 1378 645 1379 644 1379 449 1379 449 1380 644 1380 642 1380 449 1381 642 1381 373 1381 642 1382 641 1382 373 1382 373 1383 641 1383 639 1383 373 1384 639 1384 371 1384 639 1385 638 1385 371 1385 371 1386 638 1386 636 1386 371 1387 636 1387 356 1387 636 1388 635 1388 356 1388 356 1389 635 1389 632 1389 356 1390 632 1390 354 1390 354 1391 632 1391 983 1391 354 1392 983 1392 352 1392 352 1393 983 1393 978 1393 352 1394 978 1394 977 1394

+
+
+
+
+ + + + 1 0 0 0 0 -4.37114e-8 1 0 0 -1 -4.37114e-8 6 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_E4.dae b/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_E4.dae new file mode 100644 index 0000000..2c261a7 --- /dev/null +++ b/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_E4.dae @@ -0,0 +1,107 @@ + + + + + + Blender User + Blender 2.82.7 + + 2022-03-18T13:40:55 + 2022-03-18T13:40:55 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.80848 0.80848 0.80848 1 + + + 1 + + + + + + + + + + + + + + + + + -67.48848 0 -1.247326 -67.3963 5 -3.740275 -67.3963 0 -3.740275 -67.21206 5 -6.228115 -67.21206 0 -6.228115 -66.93602 5 -8.707448 -66.93602 0 -8.707448 -66.56855 5 -11.17489 -66.56855 0 -11.17489 -66.11016 5 -13.62706 -66.11016 0 -13.62706 -65.56147 5 -16.06063 -65.56147 0 -16.06063 -64.92324 5 -18.47225 -64.92324 0 -18.47225 -64.19632 5 -20.85865 -64.19632 0 -20.85865 -63.38172 5 -23.21655 -63.38172 0 -23.21655 -62.48054 5 -25.54275 -62.48054 0 -25.54275 -61.49403 5 -27.83405 -61.49403 0 -27.83405 -60.42352 5 -30.08734 -60.42352 0 -30.08734 -59.27048 5 -32.29953 -59.27048 0 -32.29953 -58.03649 5 -34.4676 -58.03649 0 -34.4676 -56.72322 5 -36.5886 -56.72322 0 -36.5886 -55.33248 5 -38.65962 -55.33248 0 -38.65962 -53.86616 5 -40.67784 -53.86616 0 -40.67784 -52.32627 5 -42.64049 -52.32627 0 -42.64049 -50.7149 5 -44.54491 -50.7149 0 -44.54491 -49.03427 5 -46.38848 -49.03427 0 -46.38848 -47.28665 5 -48.16868 -47.28665 0 -48.16868 -45.47445 5 -49.8831 -45.47445 0 -49.8831 -43.60015 5 -51.52938 -43.60015 0 -51.52938 -41.66628 5 -53.10528 -41.66628 0 -53.10528 -39.6755 5 -54.60865 -39.6755 0 -54.60865 -37.63053 5 -56.03742 -37.63053 0 -56.03742 -35.53417 5 -57.38965 -35.53417 0 -57.38965 -33.38927 5 -58.6635 -33.38927 0 -58.6635 -31.19876 5 -59.85722 -31.19876 0 -59.85722 -28.96564 5 -60.96918 -28.96564 0 -60.96918 -26.69296 5 -61.99787 -26.69296 0 -61.99787 -24.38381 5 -62.94188 -24.38381 0 -62.94188 -22.04136 5 -63.79991 -22.04136 0 -63.79991 -19.66881 5 -64.5708 -19.66881 0 -64.5708 -17.26939 5 -65.25349 -17.26939 0 -65.25349 -14.84638 5 -65.84706 -14.84638 0 -65.84706 -12.40309 5 -66.35069 -12.40309 0 -66.35069 -9.942866 5 -66.76369 -9.942866 0 -66.76369 -7.469056 5 -67.08549 -7.469056 0 -67.08549 -4.985045 5 -67.31567 -4.985045 0 -67.31567 -2.494226 5 -67.4539 -2.494226 0 -67.4539 0 5 -67.5 0 0 -67.5 2.494226 5 -67.4539 -67.48848 5 -1.247326 -67.48848 0 1.247326 -67.48848 5 1.247326 -67.3963 0 3.740275 -67.3963 5 3.740275 -67.21206 0 6.228115 -67.21206 5 6.228115 -66.93602 0 8.707448 -66.93602 5 8.707448 -66.56855 0 11.17489 -66.56855 5 11.17489 -66.11016 0 13.62706 -66.11016 5 13.62706 -65.56147 0 16.06063 -65.56147 5 16.06063 -64.92324 0 18.47225 -64.92324 5 18.47225 -64.19632 0 20.85865 -64.19632 5 20.85865 -63.38172 0 23.21655 -63.38172 5 23.21655 -62.48054 0 25.54275 -62.48054 5 25.54275 -61.49403 0 27.83405 -61.49403 5 27.83405 -60.42352 0 30.08734 -60.42352 5 30.08734 -59.27048 0 32.29953 -59.27048 5 32.29953 -58.03649 0 34.4676 -58.03649 5 34.4676 -56.72322 0 36.5886 -56.72322 5 36.5886 -55.33248 0 38.65962 -55.33248 5 38.65962 -53.86616 0 40.67784 -53.86616 5 40.67784 -52.32627 0 42.64049 -52.32627 5 42.64049 -50.7149 0 44.54491 -50.7149 5 44.54491 -49.03427 0 46.38848 -49.03427 5 46.38848 -47.28665 0 48.16868 -47.28665 5 48.16868 -45.47445 0 49.8831 -45.47445 5 49.8831 -43.60015 0 51.52938 -43.60015 5 51.52938 -41.66628 0 53.10528 -41.66628 5 53.10528 -39.6755 0 54.60865 -39.6755 5 54.60865 -37.63053 0 56.03742 -37.63053 5 56.03742 -35.53417 0 57.38965 -35.53417 5 57.38965 -33.38927 0 58.6635 -33.38927 5 58.6635 -31.19876 0 59.85722 -31.19876 5 59.85722 -28.96564 0 60.96918 -28.96564 5 60.96918 -26.69296 0 61.99787 -26.69296 5 61.99787 -24.38381 0 62.94188 -24.38381 5 62.94188 -22.04136 0 63.79991 -22.04136 5 63.79991 -19.66881 0 64.5708 -19.66881 5 64.5708 -17.26939 0 65.25349 -17.26939 5 65.25349 -14.84638 0 65.84706 -14.84638 5 65.84706 -12.40309 0 66.35069 -12.40309 5 66.35069 -9.942866 0 66.76369 -9.942866 5 66.76369 -7.469056 0 67.08549 -7.469056 5 67.08549 -4.985045 0 67.31567 -4.985045 5 67.31567 -2.494226 0 67.4539 -2.494226 5 67.4539 0 0 67.5 0 5 67.5 2.494226 0 67.4539 2.494226 5 67.4539 4.985045 0 67.31567 4.985045 5 67.31567 7.469056 0 67.08549 7.469056 5 67.08549 9.942866 0 66.76369 9.942866 5 66.76369 12.40309 0 66.35069 12.40309 5 66.35069 14.84638 0 65.84706 14.84638 5 65.84706 17.26939 0 65.25349 17.26939 5 65.25349 19.66881 0 64.5708 19.66881 5 64.5708 22.04136 0 63.79991 22.04136 5 63.79991 24.38381 0 62.94188 24.38381 5 62.94188 26.69296 0 61.99787 26.69296 5 61.99787 28.96564 0 60.96918 28.96564 5 60.96918 31.19876 0 59.85722 31.19876 5 59.85722 33.38927 0 58.6635 33.38927 5 58.6635 35.53417 0 57.38965 35.53417 5 57.38965 37.63053 0 56.03742 37.63053 5 56.03742 39.6755 0 54.60865 39.6755 5 54.60865 41.66628 0 53.10528 41.66628 5 53.10528 43.60015 0 51.52938 43.60015 5 51.52938 45.47445 0 49.8831 45.47445 5 49.8831 47.28665 0 48.16868 47.28665 5 48.16868 49.03427 0 46.38848 49.03427 5 46.38848 50.7149 0 44.54491 50.7149 5 44.54491 52.32627 0 42.64049 52.32627 5 42.64049 53.86616 0 40.67784 53.86616 5 40.67784 55.33248 0 38.65962 55.33248 5 38.65962 56.72322 0 36.5886 56.72322 5 36.5886 58.03649 0 34.4676 58.03649 5 34.4676 59.27048 0 32.29953 59.27048 5 32.29953 60.42352 0 30.08734 60.42352 5 30.08734 61.49403 0 27.83405 61.49403 5 27.83405 62.48054 0 25.54275 62.48054 5 25.54275 63.38172 0 23.21655 63.38172 5 23.21655 64.19632 0 20.85865 64.19632 5 20.85865 64.92324 0 18.47225 64.92324 5 18.47225 65.56147 0 16.06063 65.56147 5 16.06063 66.11016 0 13.62706 66.11016 5 13.62706 66.56855 0 11.17489 66.56855 5 11.17489 66.93602 0 8.707448 66.93602 5 8.707448 67.21206 0 6.228115 67.21206 5 6.228115 67.3963 0 3.740275 67.3963 5 3.740275 67.48848 0 1.247326 67.48848 5 1.247326 67.48848 0 -1.247326 67.48848 5 -1.247326 67.3963 0 -3.740275 67.3963 5 -3.740275 67.21206 0 -6.228115 67.21206 5 -6.228115 66.93602 0 -8.707448 66.93602 5 -8.707448 66.56855 0 -11.17489 66.56855 5 -11.17489 66.11016 0 -13.62706 66.11016 5 -13.62706 65.56147 0 -16.06063 65.56147 5 -16.06063 64.92324 0 -18.47225 64.92324 5 -18.47225 64.19632 0 -20.85865 64.19632 5 -20.85865 63.38172 0 -23.21655 63.38172 5 -23.21655 62.48054 0 -25.54275 62.48054 5 -25.54275 61.49403 0 -27.83405 61.49403 5 -27.83405 60.42352 0 -30.08734 60.42352 5 -30.08734 59.27048 0 -32.29953 59.27048 5 -32.29953 58.03649 0 -34.4676 58.03649 5 -34.4676 56.72322 0 -36.5886 56.72322 5 -36.5886 55.33248 0 -38.65962 55.33248 5 -38.65962 53.86616 0 -40.67784 53.86616 5 -40.67784 52.32627 0 -42.64049 52.32627 5 -42.64049 50.7149 0 -44.54491 50.7149 5 -44.54491 49.03427 0 -46.38848 49.03427 5 -46.38848 47.28665 0 -48.16868 47.28665 5 -48.16868 45.47445 0 -49.8831 45.47445 5 -49.8831 43.60015 0 -51.52938 43.60015 5 -51.52938 41.66628 0 -53.10528 41.66628 5 -53.10528 39.6755 0 -54.60865 39.6755 5 -54.60865 37.63053 0 -56.03742 37.63053 5 -56.03742 35.53417 0 -57.38965 35.53417 5 -57.38965 33.38927 0 -58.6635 33.38927 5 -58.6635 31.19876 0 -59.85722 31.19876 5 -59.85722 28.96564 0 -60.96918 28.96564 5 -60.96918 26.69296 0 -61.99787 26.69296 5 -61.99787 24.38381 0 -62.94188 24.38381 5 -62.94188 22.04136 0 -63.79991 22.04136 5 -63.79991 19.66881 0 -64.5708 19.66881 5 -64.5708 17.26939 0 -65.25349 17.26939 5 -65.25349 14.84638 0 -65.84706 14.84638 5 -65.84706 12.40309 0 -66.35069 12.40309 5 -66.35069 9.942866 0 -66.76369 9.942866 5 -66.76369 7.469056 0 -67.08549 7.469056 5 -67.08549 4.985045 0 -67.31567 4.985045 5 -67.31567 2.494226 0 -67.4539 32.0355 8 6.040412 63.60995 8 10.67823 32.31158 8 4.326852 63.96108 8 8.32045 32.49607 8 2.601027 32.58845 8 -0.867829 64.4009 8 -3.57404 32.49607 8 -2.601027 64.22486 8 -5.951309 32.31158 8 -4.326852 -3.465168 8 32.41531 -4.763488 8 64.32387 -1.735043 8 32.55379 -2.383372 8 64.45595 0 8 32.6 0 8 64.5 1.735043 8 32.55379 63.96108 8 -8.32045 63.60995 8 -10.67823 32.0355 8 -6.040412 63.17193 8 -13.02141 31.66862 8 -7.736851 62.64762 8 -15.34682 31.21196 8 -9.411357 64.22486 8 5.951309 64.4009 8 3.57404 32.58845 8 0.867829 64.48899 8 1.191889 64.48899 8 -1.191889 2.383372 8 64.45595 4.763488 8 64.32387 3.465168 8 32.41531 7.137098 8 64.10392 5.18547 8 32.18495 -6.891074 8 31.86335 -11.85184 8 63.40177 -5.18547 8 32.18495 -9.500961 8 63.79641 -7.137098 8 64.10392 -5.18547 8 -32.18495 -11.85184 8 -63.40177 -6.891074 8 -31.86335 -14.18654 8 -62.92052 -8.577144 8 -31.45143 29.31758 8 14.25622 58.76096 8 26.59698 30.03477 8 12.67567 59.70363 8 24.40751 30.66683 8 11.05919 -10.2389 8 30.95036 -18.79464 8 61.70098 -8.577144 8 31.45143 -16.50186 8 62.35334 -14.18654 8 62.92052 -18.02128 8 27.16603 -33.95487 8 54.839 -16.54991 8 28.08666 -31.9053 8 56.05624 -15.03162 8 28.92768 -29.81215 8 57.1969 -13.47072 8 29.68669 -20.80676 8 25.09659 -39.81444 8 50.74505 -19.44158 8 26.1684 -37.91215 8 52.1816 -35.95807 8 53.54687 -23.35649 8 22.74279 -45.18502 8 46.02785 -22.11297 8 23.95364 -43.45337 8 47.66608 -41.66236 8 49.23919 -11.87164 8 -30.36156 -25.5066 8 -59.24241 -13.47072 8 -29.68669 -27.67828 8 -58.25944 -15.03162 8 -28.92768 -29.81215 8 -57.1969 -16.54991 8 -28.08666 -16.50186 8 -62.35334 -18.79464 8 -61.70098 -10.2389 8 -30.95036 -21.06175 8 -60.96435 -23.30009 8 -60.14446 60.56475 8 22.18471 61.34314 8 19.9316 31.21196 8 9.411357 62.03775 8 17.65126 31.66862 8 7.736851 62.64762 8 15.34682 63.17193 8 13.02141 27.63614 8 17.29172 55.45709 8 32.93571 28.51728 8 15.79636 56.63624 8 30.864 57.73803 8 28.75012 25.64158 8 20.1313 51.47211 8 38.86993 26.67667 8 18.73807 52.87326 8 36.94142 54.20219 8 34.96244 22.11297 8 23.95364 45.18502 8 46.02785 23.35649 8 22.74279 46.85496 8 44.32677 24.53381 8 21.46747 48.46091 8 42.56513 50.00065 8 40.74536 9.500961 8 63.79641 11.85184 8 63.40177 6.891074 8 31.86335 14.18654 8 62.92052 8.577144 8 31.45143 -25.64158 8 -20.1313 -51.47211 8 -38.86993 -26.67667 8 -18.73807 -52.87326 8 -36.94142 -27.63614 8 -17.29172 -22.11297 8 -23.95364 -45.18502 8 -46.02785 -23.35649 8 -22.74279 -46.85496 8 -44.32677 -24.53381 8 -21.46747 -48.46091 8 -42.56513 -50.00065 8 -40.74536 6.891074 8 -31.86335 11.85184 8 -63.40177 5.18547 8 -32.18495 9.500961 8 -63.79641 3.465168 8 -32.41531 20.80676 8 -25.09659 39.81444 8 -50.74505 19.44158 8 -26.1684 37.91215 8 -52.1816 18.02128 8 -27.16603 19.44158 8 26.1684 39.81444 8 50.74505 20.80676 8 25.09659 41.66236 8 49.23919 43.45337 8 47.66608 16.54991 8 28.08666 33.95487 8 54.839 18.02128 8 27.16603 35.95807 8 53.54687 37.91215 8 52.1816 11.87164 8 30.36156 25.5066 8 59.24241 13.47072 8 29.68669 27.67828 8 58.25944 15.03162 8 28.92768 29.81215 8 57.1969 31.9053 8 56.05624 -27.67828 8 58.25944 -25.5066 8 59.24241 -11.87164 8 30.36156 -23.30009 8 60.14446 -21.06175 8 60.96435 -32.58845 8 0.867829 -64.4009 8 3.57404 -32.49607 8 2.601027 -64.22486 8 5.951309 -32.31158 8 4.326852 -31.9053 8 -56.05624 -33.95487 8 -54.839 -18.02128 8 -27.16603 -35.95807 8 -53.54687 -19.44158 8 -26.1684 -1.735043 8 -32.55379 -4.763488 8 -64.32387 -3.465168 8 -32.41531 -7.137098 8 -64.10392 -9.500961 8 -63.79641 7.137098 8 -64.10392 4.763488 8 -64.32387 1.735043 8 -32.55379 2.383372 8 -64.45595 0 8 -32.6 0 8 -64.5 -2.383372 8 -64.45595 35.95807 8 -53.54687 33.95487 8 -54.839 16.54991 8 -28.08666 31.9053 8 -56.05624 15.03162 8 -28.92768 29.81215 8 -57.1969 13.47072 8 -29.68669 23.35649 8 -22.74279 45.18502 8 -46.02785 22.11297 8 -23.95364 43.45337 8 -47.66608 41.66236 8 -49.23919 16.50186 8 62.35334 18.79464 8 61.70098 10.2389 8 30.95036 21.06175 8 60.96435 23.30009 8 60.14446 -63.96108 8 8.32045 -63.60995 8 10.67823 -32.0355 8 6.040412 -63.17193 8 13.02141 -31.66862 8 7.736851 -62.64762 8 15.34682 -31.21196 8 9.411357 -37.91215 8 -52.1816 -39.81444 8 -50.74505 -20.80676 8 -25.09659 -41.66236 8 -49.23919 -43.45337 8 -47.66608 10.2389 8 -30.95036 18.79464 8 -61.70098 8.577144 8 -31.45143 16.50186 8 -62.35334 14.18654 8 -62.92052 27.67828 8 -58.25944 25.5066 8 -59.24241 11.87164 8 -30.36156 23.30009 8 -60.14446 21.06175 8 -60.96435 30.03477 8 -12.67567 58.76096 8 -26.59698 29.31758 8 -14.25622 57.73803 8 -28.75012 28.51728 8 -15.79636 -28.51728 8 15.79636 -55.45709 8 32.93571 -27.63614 8 17.29172 -54.20219 8 34.96244 -26.67667 8 18.73807 -32.49607 8 -2.601027 -64.4009 8 -3.57404 -32.58845 8 -0.867829 -64.48899 8 -1.191889 -64.48899 8 1.191889 -54.20219 8 -34.96244 -55.45709 8 -32.93571 -28.51728 8 -15.79636 -56.63624 8 -30.864 -29.31758 8 -14.25622 26.67667 8 -18.73807 51.47211 8 -38.86993 25.64158 8 -20.1313 50.00065 8 -40.74536 24.53381 8 -21.46747 48.46091 8 -42.56513 46.85496 8 -44.32677 56.63624 8 -30.864 55.45709 8 -32.93571 27.63614 8 -17.29172 54.20219 8 -34.96244 52.87326 8 -36.94142 62.03775 8 -17.65126 61.34314 8 -19.9316 30.66683 8 -11.05919 60.56475 8 -22.18471 59.70363 8 -24.40751 -52.87326 8 36.94142 -51.47211 8 38.86993 -25.64158 8 20.1313 -50.00065 8 40.74536 -24.53381 8 21.46747 -48.46091 8 42.56513 -46.85496 8 44.32677 -32.0355 8 -6.040412 -63.60995 8 -10.67823 -32.31158 8 -4.326852 -63.96108 8 -8.32045 -64.22486 8 -5.951309 -30.66683 8 -11.05919 -61.34314 8 -19.9316 -31.21196 8 -9.411357 -62.03775 8 -17.65126 -31.66862 8 -7.736851 -62.64762 8 -15.34682 -63.17193 8 -13.02141 -30.03477 8 12.67567 -58.76096 8 26.59698 -29.31758 8 14.25622 -57.73803 8 28.75012 -56.63624 8 30.864 -62.03775 8 17.65126 -61.34314 8 19.9316 -30.66683 8 11.05919 -60.56475 8 22.18471 -59.70363 8 24.40751 -57.73803 8 -28.75012 -58.76096 8 -26.59698 -30.03477 8 -12.67567 -59.70363 8 -24.40751 -60.56475 8 -22.18471 0 0 67.5 0 0 0 0 5 67.5 0 8 64.5 1.681821 7 31.55521 1.71079 6 31.55366 0 6 31.6 1.71079 7 31.55366 3.358874 7 31.42098 3.416561 6 31.41476 3.416561 7 31.41476 5.026407 7 31.19768 5.112311 6 31.18372 5.112311 7 31.18372 6.679691 7 30.88595 6.793066 6 30.86121 6.793066 7 30.86121 8.314042 7 30.48666 8.453896 6 30.44818 8.453896 7 30.44818 9.924825 7 30.00097 10.08993 6 29.94584 10.08993 7 29.94584 11.50747 7 29.43022 11.69637 6 29.35566 11.69637 7 29.35566 13.0575 7 28.77606 13.2685 6 28.67938 13.2685 7 28.67938 14.57052 7 28.04033 14.80171 6 27.91898 14.80171 7 27.91898 16.04224 7 27.22511 16.2915 6 27.07669 16.2915 7 27.07669 17.46848 7 26.33272 17.73351 6 26.15497 17.73351 7 26.15497 18.84521 7 25.36569 19.12351 6 25.15654 19.12351 7 25.15654 20.16852 7 24.32676 20.45741 6 24.08432 20.45741 7 24.08432 21.43465 7 23.21886 21.7313 6 22.94146 21.7313 7 22.94146 22.64003 7 22.04516 22.94146 6 21.7313 22.94146 7 21.7313 23.78124 7 20.80896 24.08432 6 20.45741 24.08432 7 20.45741 24.85503 7 19.51378 25.15654 6 19.12351 25.15654 7 19.12351 25.85837 7 18.16328 26.15497 6 17.73351 26.15497 7 17.73351 26.78841 7 16.7613 27.07669 6 16.2915 27.07669 7 16.2915 27.91898 6 14.80171 27.64251 7 15.31181 27.91898 7 14.80171 28.67938 6 13.2685 28.41826 7 13.81891 28.67938 7 13.2685 29.35566 6 11.69637 29.11346 7 12.28684 29.35566 7 11.69637 29.94584 6 10.08993 29.72613 7 10.71995 29.94584 7 10.08993 30.44818 6 8.453896 30.25454 7 9.122667 30.44818 7 8.453896 30.86121 6 6.793066 30.69719 7 7.499524 30.86121 7 6.793066 31.18372 6 5.112311 31.05282 7 5.855123 31.18372 7 5.112311 31.41476 6 3.416561 31.32043 7 4.194127 31.41476 7 3.416561 31.55366 6 1.71079 31.49926 7 2.521241 31.55366 7 1.71079 31.6 6 0 31.5888 7 0.8412085 31.6 7 0 31.5888 7 -0.8412085 31.55366 6 -1.71079 31.55366 7 -1.71079 31.49926 7 -2.521241 31.41476 6 -3.416561 31.41476 7 -3.416561 31.32043 7 -4.194127 31.18372 6 -5.112311 31.18372 7 -5.112311 31.05282 7 -5.855123 30.86121 6 -6.793066 30.86121 7 -6.793066 30.69719 7 -7.499524 30.44818 6 -8.453896 30.44818 7 -8.453896 30.25454 7 -9.122667 29.94584 6 -10.08993 29.94584 7 -10.08993 29.72613 7 -10.71995 29.35566 6 -11.69637 29.35566 7 -11.69637 29.11346 7 -12.28684 28.67938 6 -13.2685 28.67938 7 -13.2685 28.41826 7 -13.81891 27.91898 6 -14.80171 27.91898 7 -14.80171 27.64251 7 -15.31181 27.07669 6 -16.2915 27.07669 7 -16.2915 26.78841 7 -16.7613 26.15497 6 -17.73351 26.15497 7 -17.73351 25.85837 7 -18.16328 25.15654 6 -19.12351 25.15654 7 -19.12351 24.85503 7 -19.51378 24.08432 6 -20.45741 24.08432 7 -20.45741 23.78124 7 -20.80896 22.94146 6 -21.7313 22.94146 7 -21.7313 22.64003 7 -22.04516 21.7313 6 -22.94146 21.7313 7 -22.94146 21.43465 7 -23.21886 20.45741 6 -24.08432 20.45741 7 -24.08432 20.16852 7 -24.32676 19.12351 6 -25.15654 19.12351 7 -25.15654 18.84521 7 -25.36569 17.73351 6 -26.15497 17.73351 7 -26.15497 17.46848 7 -26.33272 16.2915 6 -27.07669 16.2915 7 -27.07669 16.04224 7 -27.22511 14.80171 6 -27.91898 14.80171 7 -27.91898 14.57052 7 -28.04033 13.2685 6 -28.67938 13.2685 7 -28.67938 13.0575 7 -28.77606 11.69637 6 -29.35566 11.69637 7 -29.35566 11.50747 7 -29.43022 10.08993 6 -29.94584 10.08993 7 -29.94584 9.924825 7 -30.00097 8.453896 6 -30.44818 8.453896 7 -30.44818 8.314042 7 -30.48666 6.793066 6 -30.86121 6.793066 7 -30.86121 6.679691 7 -30.88595 5.112311 6 -31.18372 5.112311 7 -31.18372 5.026407 7 -31.19768 3.416561 6 -31.41476 3.416561 7 -31.41476 3.358874 7 -31.42098 1.71079 6 -31.55366 1.71079 7 -31.55366 1.681821 7 -31.55521 0 6 -31.6 0 7 -31.6 -1.681821 7 -31.55521 -1.71079 6 -31.55366 -1.71079 7 -31.55366 -3.358874 7 -31.42098 -3.416561 6 -31.41476 -3.416561 7 -31.41476 -5.026407 7 -31.19768 -5.112311 6 -31.18372 -5.112311 7 -31.18372 -6.679691 7 -30.88595 -6.793066 6 -30.86121 -6.793066 7 -30.86121 -8.314042 7 -30.48666 -8.453896 6 -30.44818 -8.453896 7 -30.44818 -9.924825 7 -30.00097 -10.08993 6 -29.94584 -10.08993 7 -29.94584 -11.50747 7 -29.43022 -11.69637 6 -29.35566 -11.69637 7 -29.35566 -13.0575 7 -28.77606 -13.2685 6 -28.67938 -13.2685 7 -28.67938 -14.57052 7 -28.04033 -14.80171 6 -27.91898 -14.80171 7 -27.91898 -16.04224 7 -27.22511 -16.2915 6 -27.07669 -16.2915 7 -27.07669 -17.46848 7 -26.33272 -17.73351 6 -26.15497 -17.73351 7 -26.15497 -18.84521 7 -25.36569 -19.12351 6 -25.15654 -19.12351 7 -25.15654 -20.16852 7 -24.32676 -20.45741 6 -24.08432 -20.45741 7 -24.08432 -21.43465 7 -23.21886 -21.7313 6 -22.94146 -21.7313 7 -22.94146 -22.64003 7 -22.04516 -22.94146 6 -21.7313 -22.94146 7 -21.7313 -23.78124 7 -20.80896 -24.08432 6 -20.45741 -24.08432 7 -20.45741 -24.85503 7 -19.51378 -25.15654 6 -19.12351 -25.15654 7 -19.12351 -25.85837 7 -18.16328 -26.15497 6 -17.73351 -26.15497 7 -17.73351 -26.78841 7 -16.7613 -27.07669 6 -16.2915 -27.07669 7 -16.2915 -27.91898 6 -14.80171 -27.64251 7 -15.31181 -27.91898 7 -14.80171 -28.67938 6 -13.2685 -28.41826 7 -13.81891 -28.67938 7 -13.2685 -29.35566 6 -11.69637 -29.11346 7 -12.28684 -29.35566 7 -11.69637 -29.94584 6 -10.08993 -29.72613 7 -10.71995 -29.94584 7 -10.08993 -30.44818 6 -8.453896 -30.25454 7 -9.122667 -30.44818 7 -8.453896 -30.86121 6 -6.793066 -30.69719 7 -7.499524 -30.86121 7 -6.793066 -31.18372 6 -5.112311 -31.05282 7 -5.855123 -31.18372 7 -5.112311 -31.41476 6 -3.416561 -31.32043 7 -4.194127 -31.41476 7 -3.416561 -31.55366 6 -1.71079 -31.49926 7 -2.521241 -31.55366 7 -1.71079 -31.6 6 0 -31.5888 7 -0.8412085 -31.6 7 0 -31.5888 7 0.8412085 -31.55366 6 1.71079 -31.55366 7 1.71079 -31.49926 7 2.521241 -31.41476 6 3.416561 -31.41476 7 3.416561 -31.32043 7 4.194127 -31.18372 6 5.112311 -31.18372 7 5.112311 -31.05282 7 5.855123 -30.86121 6 6.793066 -30.86121 7 6.793066 -30.69719 7 7.499524 -30.44818 6 8.453896 -30.44818 7 8.453896 -30.25454 7 9.122667 -29.94584 6 10.08993 -29.94584 7 10.08993 -29.72613 7 10.71995 -29.35566 6 11.69637 -29.35566 7 11.69637 -29.11346 7 12.28684 -28.67938 6 13.2685 -28.67938 7 13.2685 -28.41826 7 13.81891 -27.91898 6 14.80171 -27.91898 7 14.80171 -27.64251 7 15.31181 -27.07669 6 16.2915 -27.07669 7 16.2915 -26.78841 7 16.7613 -26.15497 6 17.73351 -26.15497 7 17.73351 -25.85837 7 18.16328 -25.15654 6 19.12351 -25.15654 7 19.12351 -24.85503 7 19.51378 -24.08432 6 20.45741 -24.08432 7 20.45741 -23.78124 7 20.80896 -22.94146 6 21.7313 -22.94146 7 21.7313 -22.64003 7 22.04516 -21.7313 6 22.94146 -21.7313 7 22.94146 -21.43465 7 23.21886 -20.45741 6 24.08432 -20.45741 7 24.08432 -20.16852 7 24.32676 -19.12351 6 25.15654 -19.12351 7 25.15654 -18.84521 7 25.36569 -17.73351 6 26.15497 -17.73351 7 26.15497 -17.46848 7 26.33272 -16.2915 6 27.07669 -16.2915 7 27.07669 -16.04224 7 27.22511 -14.80171 6 27.91898 -14.80171 7 27.91898 -14.57052 7 28.04033 -13.2685 6 28.67938 -13.2685 7 28.67938 -13.0575 7 28.77606 -11.69637 6 29.35566 -11.69637 7 29.35566 -11.50747 7 29.43022 -10.08993 6 29.94584 -10.08993 7 29.94584 -9.924825 7 30.00097 -8.453896 6 30.44818 -8.453896 7 30.44818 -8.314042 7 30.48666 -6.793066 6 30.86121 -6.793066 7 30.86121 -6.679691 7 30.88595 -5.112311 6 31.18372 -5.112311 7 31.18372 -5.026407 7 31.19768 -3.416561 6 31.41476 -3.416561 7 31.41476 -3.358874 7 31.42098 -1.71079 6 31.55366 -1.71079 7 31.55366 -1.681821 7 31.55521 0 7 31.6 0 6 0 0 8 -32.6 0 7 -31.6 0 7 31.6 + + + + + + + + + + -0.9993171 0 -0.03695338 -0.9972693 0 -0.07385182 -0.9972693 0 -0.07385182 -0.9938592 0 -0.1106523 -0.9938592 0 -0.1106524 -0.9890915 0 -0.147303 -0.9890915 0 -0.1473029 -0.9829728 0 -0.1837518 -0.9829728 0 -0.1837517 -0.9755126 0 -0.2199438 -0.9667186 0 -0.255842 -0.9667186 0 -0.2558423 -0.9566048 0 -0.2913888 -0.9566047 0 -0.2913892 -0.9451836 0 -0.3265393 -0.9451838 0 -0.3265389 -0.9324718 0 -0.3612432 -0.9324718 0 -0.3612428 -0.9184876 0 -0.3954501 -0.9184871 0 -0.395451 -0.9032473 0 -0.4291204 -0.9032469 0 -0.4291213 -0.8867733 0 -0.4622046 -0.8867728 0 -0.4622057 -0.8690901 0 -0.4946538 -0.8690896 0 -0.4946548 -0.8502169 0 -0.5264327 -0.8502162 0 -0.5264337 -0.8301846 0 -0.5574886 -0.8301839 0 -0.5574898 -0.8090174 0 -0.5877848 -0.8090166 0 -0.587786 -0.7867455 0 -0.6172777 -0.7633974 0 -0.6459292 -0.7633985 0 -0.645928 -0.7390089 0 -0.6736958 -0.73901 0 -0.6736945 -0.7136095 0 -0.7005438 -0.7136107 0 -0.7005426 -0.687236 0 -0.7264342 -0.6599259 0 -0.7513308 -0.6599245 0 -0.7513319 -0.6317113 0 -0.7752039 -0.6317083 0 -0.7752063 -0.6026359 0 -0.7980163 -0.5727343 0 -0.8197411 -0.5420531 0 -0.8403443 -0.5106335 0 -0.8597986 -0.5106299 0 -0.8598006 -0.4785133 0 -0.8780804 -0.4457345 0 -0.8951652 -0.4457384 0 -0.8951633 -0.4123567 0 -0.9110225 -0.3784121 0 -0.9256374 -0.3784162 0 -0.9256356 -0.3439484 0 -0.9389885 -0.3090157 0 -0.951057 -0.2736572 0 -0.9618273 -0.2736617 0 -0.9618261 -0.2379357 0 -0.971281 -0.2018867 0 -0.9794089 -0.2018821 0 -0.9794099 -0.1655591 0 -0.9861999 -0.1655496 0 -0.9862015 -0.1290014 0 -0.9916445 -0.1289918 0 -0.9916457 -0.09226769 0 -0.9957343 -0.09227252 0 -0.9957338 -0.05540663 0 -0.9984639 -0.05541151 0 -0.9984637 -0.01847702 0 -0.9998294 -0.01848679 0 -0.9998292 0.01848679 0 -0.9998292 -0.9993171 0 -0.03695338 -1 0 0 -0.9993171 0 0.03695338 -0.9993171 0 0.03695338 -0.9972693 0 0.07385182 -0.9972693 0 0.07385182 -0.9938592 0 0.1106523 -0.9938592 0 0.1106524 -0.9890915 0 0.147303 -0.9890915 0 0.1473029 -0.9829728 0 0.1837518 -0.9829728 0 0.1837517 -0.9755126 0 0.2199438 -0.9667186 0 0.255842 -0.9667186 0 0.2558423 -0.9566048 0 0.2913888 -0.9566047 0 0.2913892 -0.9451836 0 0.3265393 -0.9451838 0 0.3265389 -0.9324718 0 0.3612432 -0.9324718 0 0.3612428 -0.9184876 0 0.3954501 -0.9184871 0 0.395451 -0.9032473 0 0.4291204 -0.9032469 0 0.4291213 -0.8867733 0 0.4622046 -0.8867728 0 0.4622057 -0.8690901 0 0.4946538 -0.8690896 0 0.4946548 -0.8502169 0 0.5264327 -0.8502162 0 0.5264337 -0.8301846 0 0.5574886 -0.8301839 0 0.5574898 -0.8090174 0 0.5877848 -0.8090166 0 0.587786 -0.7867455 0 0.6172777 -0.7633974 0 0.6459292 -0.7633985 0 0.645928 -0.7390089 0 0.6736958 -0.73901 0 0.6736945 -0.7136095 0 0.7005438 -0.7136107 0 0.7005426 -0.687236 0 0.7264342 -0.6599259 0 0.7513308 -0.6599245 0 0.7513319 -0.6317113 0 0.7752039 -0.6317083 0 0.7752063 -0.6026359 0 0.7980163 -0.5727343 0 0.8197411 -0.5420531 0 0.8403443 -0.5106335 0 0.8597986 -0.5106299 0 0.8598006 -0.4785133 0 0.8780804 -0.4457345 0 0.8951652 -0.4457384 0 0.8951633 -0.4123567 0 0.9110225 -0.3784121 0 0.9256374 -0.3784162 0 0.9256356 -0.3439484 0 0.9389885 -0.3090157 0 0.951057 -0.2736572 0 0.9618273 -0.2736617 0 0.9618261 -0.2379357 0 0.971281 -0.2018867 0 0.9794089 -0.2018821 0 0.9794099 -0.1655591 0 0.9861999 -0.1655496 0 0.9862015 -0.1290014 0 0.9916445 -0.1289918 0 0.9916457 -0.09226769 0 0.9957343 -0.09227252 0 0.9957338 -0.05540663 0 0.9984639 -0.05541151 0 0.9984637 -0.01847702 0 0.9998294 -0.01848679 0 0.9998292 0.01848679 0 0.9998292 0.01847702 0 0.9998294 0.05541151 0 0.9984637 0.05540663 0 0.9984639 0.09227252 0 0.9957338 0.09226769 0 0.9957343 0.1289918 0 0.9916457 0.1290014 0 0.9916445 0.1655496 0 0.9862015 0.1655591 0 0.9861999 0.2018821 0 0.9794099 0.2018867 0 0.9794089 0.2379357 0 0.971281 0.2736617 0 0.9618261 0.2736572 0 0.9618273 0.3090157 0 0.951057 0.3439484 0 0.9389885 0.3784162 0 0.9256356 0.3784121 0 0.9256374 0.4123567 0 0.9110225 0.4457384 0 0.8951633 0.4457345 0 0.8951652 0.4785133 0 0.8780804 0.5106299 0 0.8598006 0.5106335 0 0.8597986 0.5420531 0 0.8403443 0.5727343 0 0.8197411 0.6026359 0 0.7980163 0.6317083 0 0.7752063 0.6317113 0 0.7752039 0.6599245 0 0.7513319 0.6599259 0 0.7513308 0.687236 0 0.7264342 0.7136107 0 0.7005426 0.7136095 0 0.7005438 0.73901 0 0.6736945 0.7390089 0 0.6736958 0.7633985 0 0.645928 0.7633974 0 0.6459292 0.7867455 0 0.6172777 0.8090166 0 0.587786 0.8090174 0 0.5877848 0.8301839 0 0.5574898 0.8301846 0 0.5574886 0.8502162 0 0.5264337 0.8502169 0 0.5264327 0.8690896 0 0.4946548 0.8690901 0 0.4946538 0.8867728 0 0.4622057 0.8867733 0 0.4622046 0.9032469 0 0.4291213 0.9032473 0 0.4291204 0.9184871 0 0.395451 0.9184876 0 0.3954501 0.9324718 0 0.3612428 0.9324718 0 0.3612432 0.9451838 0 0.3265389 0.9451836 0 0.3265393 0.9566047 0 0.2913892 0.9566048 0 0.2913888 0.9667186 0 0.2558423 0.9667186 0 0.255842 0.9755126 0 0.2199438 0.9829728 0 0.1837517 0.9829728 0 0.1837518 0.9890915 0 0.1473029 0.9890915 0 0.147303 0.9938592 0 0.1106524 0.9938592 0 0.1106523 0.9972693 0 0.07385182 0.9972693 0 0.07385182 0.9993171 0 0.03695338 0.9993171 0 0.03695338 1 0 0 0.9993171 0 -0.03695338 0.9993171 0 -0.03695338 0.9972693 0 -0.07385182 0.9972693 0 -0.07385182 0.9938592 0 -0.1106523 0.9938592 0 -0.1106524 0.9890915 0 -0.147303 0.9890915 0 -0.1473029 0.9829728 0 -0.1837518 0.9829728 0 -0.1837517 0.9755126 0 -0.2199438 0.9667186 0 -0.255842 0.9667186 0 -0.2558423 0.9566048 0 -0.2913888 0.9566047 0 -0.2913892 0.9451836 0 -0.3265393 0.9451838 0 -0.3265389 0.9324718 0 -0.3612432 0.9324718 0 -0.3612428 0.9184876 0 -0.3954501 0.9184871 0 -0.395451 0.9032473 0 -0.4291204 0.9032469 0 -0.4291213 0.8867733 0 -0.4622046 0.8867728 0 -0.4622057 0.8690901 0 -0.4946538 0.8690896 0 -0.4946548 0.8502169 0 -0.5264327 0.8502162 0 -0.5264337 0.8301846 0 -0.5574886 0.8301839 0 -0.5574898 0.8090174 0 -0.5877848 0.8090166 0 -0.587786 0.7867455 0 -0.6172777 0.7633974 0 -0.6459292 0.7633985 0 -0.645928 0.7390089 0 -0.6736958 0.73901 0 -0.6736945 0.7136095 0 -0.7005438 0.7136107 0 -0.7005426 0.687236 0 -0.7264342 0.6599259 0 -0.7513308 0.6599245 0 -0.7513319 0.6317113 0 -0.7752039 0.6317083 0 -0.7752063 0.6026359 0 -0.7980163 0.5727343 0 -0.8197411 0.5420531 0 -0.8403443 0.5106335 0 -0.8597986 0.5106299 0 -0.8598006 0.4785133 0 -0.8780804 0.4457345 0 -0.8951652 0.4457384 0 -0.8951633 0.4123567 0 -0.9110225 0.3784121 0 -0.9256374 0.3784162 0 -0.9256356 0.3439484 0 -0.9389885 0.3090157 0 -0.951057 0.2736572 0 -0.9618273 0.2736617 0 -0.9618261 0.2379357 0 -0.971281 0.2018867 0 -0.9794089 0.2018821 0 -0.9794099 0.1655591 0 -0.9861999 0.1655496 0 -0.9862015 0.1290014 0 -0.9916445 0.1289918 0 -0.9916457 0.09226769 0 -0.9957343 0.09227252 0 -0.9957338 0.05540663 0 -0.9984639 0.05541151 0 -0.9984637 0.01847702 0 -0.9998294 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.00691e-7 0 1 -2.00598e-7 0 1 0 0 1 0 0 1 2.00691e-7 0 1 0 0 1 2.00598e-7 0 -1 0 -0.7066863 0.7070444 -0.02613228 -0.705236 0.7070465 -0.05222612 -0.705237 0.7070456 -0.05222558 -0.7028246 0.7070465 -0.07824981 -0.7028256 0.7070454 -0.07824981 -0.6994533 0.7070464 -0.1041659 -0.6994523 0.7070471 -0.1041678 -0.6951274 0.7070453 -0.1299421 -0.6951261 0.7070463 -0.129943 -0.6898502 0.7070461 -0.1555399 -0.6898498 0.7070471 -0.1555369 -0.6836302 0.7070479 -0.1809227 -0.6836308 0.7070474 -0.1809231 -0.6764789 0.7070466 -0.2060618 -0.6764786 0.7070474 -0.2060603 -0.6684014 0.7070483 -0.2309161 -0.6684039 0.7070454 -0.2309181 -0.6594125 0.7070477 -0.2554581 -0.6594139 0.7070459 -0.2554597 -0.649523 0.7070474 -0.2796495 -0.649524 0.7070468 -0.279649 -0.6387454 0.7070479 -0.3034593 -0.6387463 0.7070468 -0.3034601 -0.6270971 0.7070466 -0.3268554 -0.6270979 0.7070454 -0.3268566 -0.6145917 0.7070454 -0.3498055 -0.6145909 0.7070475 -0.3498027 -0.6012451 0.7070465 -0.3722764 -0.6012451 0.7070471 -0.3722754 -0.5870792 0.707046 -0.3942383 -0.5870798 0.7070461 -0.3942373 -0.5721093 0.7070471 -0.4156627 -0.5721113 0.7070455 -0.4156627 -0.5563594 0.7070469 -0.4365192 -0.5563603 0.7070466 -0.4365186 -0.5398514 0.7070459 -0.4567786 -0.5398489 0.7070466 -0.4567803 -0.5226036 0.707046 -0.4764153 -0.5226029 0.7070465 -0.4764155 -0.5046442 0.7070451 -0.4954004 -0.5046401 0.7070472 -0.4954016 -0.4859899 0.7070473 -0.51371 -0.4859914 0.7070455 -0.5137111 -0.4666789 0.7070452 -0.5313171 -0.466678 0.7070459 -0.5313171 -0.4467247 0.7070471 -0.5481984 -0.4467222 0.7070472 -0.5482004 -0.4261673 0.7070448 -0.5643307 -0.4261613 0.7070478 -0.5643315 -0.4050209 0.7070446 -0.5796948 -0.4050187 0.7070468 -0.5796937 -0.3833214 0.7070474 -0.5942633 -0.3833225 0.7070458 -0.5942645 -0.3611019 0.7070471 -0.6080213 -0.3611044 0.7070451 -0.6080222 -0.3383852 0.7070469 -0.6209511 -0.3383861 0.7070475 -0.6209499 -0.3152144 0.7070457 -0.6330295 -0.3152105 0.7070466 -0.6330304 -0.2916036 0.7070463 -0.6442459 -0.2916051 0.7070466 -0.6442451 -0.2676026 0.707046 -0.6545799 -0.2675989 0.707047 -0.6545804 -0.2432284 0.7070472 -0.6640213 -0.2432289 0.7070468 -0.6640216 -0.2185279 0.7070473 -0.6725547 -0.2185279 0.7070464 -0.6725556 -0.1935231 0.7070465 -0.680172 -0.1935269 0.7070458 -0.6801717 -0.1682584 0.7070459 -0.6868591 -0.1682602 0.7070468 -0.6868576 -0.1427642 0.707047 -0.6926059 -0.1427689 0.7070456 -0.6926063 -0.1170712 0.7070462 -0.6974095 -0.1170728 0.7070471 -0.6974084 -0.09122979 0.7070463 -0.701258 -0.09122115 0.7070453 -0.7012601 -0.06525015 0.7070454 -0.7041515 -0.06524533 0.7070454 -0.7041519 -0.03918266 0.7070453 -0.706082 -0.03918862 0.7070459 -0.706081 -0.01306384 0.7070461 -0.7070469 -0.01307153 0.7070463 -0.7070464 0.01306688 0.7070464 -0.7070465 -0.7066853 0.7070454 -0.02613008 -0.7071648 0.7070487 0 -0.7071675 0.7070461 0 -0.7066863 0.7070443 0.02613228 -0.7066857 0.707045 0.02613008 -0.7052367 0.7070458 0.05222558 -0.7052363 0.7070462 0.05222612 -0.702825 0.707046 0.07824975 -0.7028251 0.7070459 0.07824987 -0.6994522 0.7070473 0.1041677 -0.6994535 0.7070462 0.104166 -0.6951268 0.7070456 0.1299433 -0.6951267 0.7070461 0.1299418 -0.6898494 0.7070475 0.1555368 -0.6898512 0.707045 0.1555401 -0.6836304 0.7070477 0.180923 -0.6836306 0.7070476 0.1809228 -0.67648 0.7070459 0.2060607 -0.6764782 0.7070474 0.2060616 -0.6684021 0.7070472 0.2309175 -0.6684032 0.7070465 0.2309167 -0.6594133 0.7070466 0.2554589 -0.6594137 0.7070462 0.2554592 -0.649524 0.7070468 0.279649 -0.649523 0.7070474 0.2796495 -0.6387435 0.7070496 0.3034595 -0.6387484 0.707045 0.30346 -0.627097 0.707046 0.3268569 -0.6270986 0.7070452 0.3268554 -0.6145915 0.7070468 0.3498031 -0.614591 0.7070462 0.3498052 -0.6012438 0.7070475 0.3722764 -0.6012464 0.707046 0.3722754 -0.587078 0.7070473 0.3942381 -0.5870813 0.7070448 0.3942376 -0.5721105 0.7070452 0.4156642 -0.5721101 0.7070474 0.4156611 -0.5563604 0.7070457 0.4365198 -0.5563593 0.7070478 0.4365178 -0.539851 0.7070455 0.4567795 -0.5398493 0.707047 0.4567793 -0.5226054 0.7070447 0.4764152 -0.5226008 0.7070479 0.4764155 -0.5046412 0.7070476 0.4953998 -0.504643 0.7070446 0.4954022 -0.4859904 0.7070469 0.51371 -0.485991 0.7070458 0.5137111 -0.4666793 0.7070463 0.5313153 -0.4666776 0.7070447 0.531319 -0.4467217 0.7070479 0.5481998 -0.4467252 0.7070463 0.5481989 -0.4261662 0.7070457 0.5643304 -0.4261619 0.7070474 0.5643315 -0.4050213 0.7070456 0.5796933 -0.4050182 0.7070459 0.5796952 -0.3833217 0.7070472 0.5942632 -0.383322 0.7070462 0.5942642 -0.3611015 0.7070465 0.6080222 -0.3611049 0.7070456 0.6080213 -0.338389 0.7070461 0.6209499 -0.3383823 0.7070479 0.6209514 -0.3152158 0.7070454 0.6330292 -0.315209 0.7070467 0.633031 -0.2916053 0.707046 0.6442456 -0.2916031 0.7070475 0.6442449 -0.2676016 0.7070463 0.65458 -0.2675997 0.7070471 0.6545799 -0.2432289 0.7070469 0.6640214 -0.2432284 0.707047 0.6640215 -0.2185276 0.7070471 0.6725549 -0.2185282 0.7070464 0.6725555 -0.1935211 0.7070475 0.6801717 -0.1935292 0.7070448 0.6801722 -0.1682603 0.707046 0.6868584 -0.1682583 0.7070465 0.6868584 -0.142766 0.7070465 0.6926062 -0.1427672 0.7070463 0.6926061 -0.11707 0.707047 0.697409 -0.1170741 0.7070463 0.6974089 -0.09122389 0.7070465 0.7012585 -0.09122699 0.7070452 0.7012594 -0.06524819 0.7070455 0.7041516 -0.06524711 0.7070455 0.7041517 -0.03918868 0.7070452 0.7060818 -0.0391826 0.707046 0.7060813 -0.01306861 0.7070459 0.7070469 -0.01306688 0.7070464 0.7070465 0.01307153 0.7070463 0.7070464 0.01306384 0.7070461 0.7070469 0.03918862 0.7070459 0.706081 0.03918266 0.7070453 0.706082 0.06524527 0.7070454 0.7041519 0.06525015 0.7070454 0.7041515 0.09122115 0.7070453 0.7012602 0.09122985 0.7070464 0.7012579 0.1170728 0.7070472 0.6974083 0.1170711 0.7070463 0.6974093 0.1427689 0.7070457 0.6926063 0.1427642 0.707047 0.6926059 0.1682602 0.7070468 0.6868577 0.1682585 0.7070457 0.6868592 0.193527 0.7070457 0.6801719 0.1935231 0.7070467 0.680172 0.2185279 0.7070464 0.6725556 0.2185279 0.7070472 0.6725547 0.243229 0.7070465 0.6640217 0.2432283 0.7070474 0.6640211 0.2675988 0.7070473 0.6545801 0.2676024 0.7070464 0.6545795 0.291605 0.7070468 0.6442449 0.2916037 0.707046 0.6442463 0.3152105 0.7070466 0.6330304 0.3152145 0.7070454 0.6330297 0.3383862 0.7070471 0.6209502 0.3383854 0.7070465 0.6209515 0.3611044 0.7070451 0.6080222 0.3611019 0.7070471 0.6080213 0.3833225 0.7070458 0.5942645 0.3833212 0.7070477 0.594263 0.4050187 0.7070468 0.5796937 0.4050211 0.7070443 0.5796951 0.4261613 0.7070478 0.5643315 0.4261673 0.7070448 0.5643307 0.4467222 0.7070472 0.5482004 0.4467247 0.7070471 0.5481984 0.466678 0.7070459 0.5313171 0.4666789 0.7070452 0.5313171 0.4859909 0.7070462 0.5137106 0.4859904 0.7070465 0.5137105 0.5046401 0.7070472 0.4954016 0.5046442 0.7070451 0.4954004 0.5226029 0.7070465 0.4764155 0.5226036 0.707046 0.4764153 0.5398489 0.7070466 0.4567803 0.5398514 0.7070459 0.4567786 0.5563603 0.7070466 0.4365186 0.5563594 0.7070469 0.4365192 0.5721113 0.7070455 0.4156627 0.5721093 0.7070471 0.4156627 0.5870798 0.7070461 0.3942373 0.5870792 0.707046 0.3942383 0.6012451 0.7070471 0.3722754 0.6012451 0.7070465 0.3722764 0.6145909 0.7070475 0.3498027 0.6145917 0.7070454 0.3498055 0.6270979 0.7070454 0.3268566 0.6270971 0.7070466 0.3268554 0.6387457 0.7070475 0.3034598 0.6387461 0.7070472 0.3034596 0.649524 0.7070468 0.279649 0.6495237 0.7070466 0.2796498 0.6594139 0.7070459 0.2554597 0.6594128 0.7070474 0.2554583 0.6684035 0.7070457 0.230918 0.6684021 0.7070475 0.2309163 0.6764786 0.7070474 0.2060603 0.6764793 0.7070462 0.2060619 0.6836304 0.7070477 0.180923 0.6836306 0.7070476 0.1809228 0.6898494 0.7070475 0.1555368 0.6898505 0.7070457 0.1555399 0.6951258 0.7070468 0.129943 0.695127 0.7070457 0.1299421 0.699452 0.7070475 0.1041678 0.6994527 0.7070469 0.1041659 0.702825 0.707046 0.07824975 0.7028244 0.7070466 0.07824975 0.7052368 0.7070457 0.05222558 0.705236 0.7070465 0.05222612 0.7066863 0.7070444 0.02613228 0.7066853 0.7070454 0.02613008 0.7071648 0.7070487 0 0.7071675 0.7070461 0 0.7066863 0.7070443 -0.02613228 0.7066857 0.707045 -0.02613008 0.7052367 0.7070458 -0.05222558 0.7052363 0.7070462 -0.05222612 0.702825 0.707046 -0.07824975 0.7028251 0.7070459 -0.07824987 0.6994522 0.7070473 -0.1041677 0.6994535 0.7070462 -0.104166 0.6951268 0.7070456 -0.1299433 0.6951267 0.7070461 -0.1299418 0.6898494 0.7070475 -0.1555368 0.6898512 0.707045 -0.1555401 0.6836304 0.7070477 -0.180923 0.6836306 0.7070476 -0.1809228 0.67648 0.7070459 -0.2060607 0.6764782 0.7070474 -0.2060616 0.6684021 0.7070472 -0.2309175 0.6684032 0.7070465 -0.2309167 0.6594133 0.7070466 -0.2554589 0.6594137 0.7070462 -0.2554592 0.649524 0.7070468 -0.279649 0.649523 0.7070474 -0.2796495 0.6387435 0.7070496 -0.3034595 0.6387484 0.707045 -0.30346 0.627097 0.707046 -0.3268569 0.6270986 0.7070452 -0.3268554 0.6145915 0.7070468 -0.3498031 0.614591 0.7070462 -0.3498052 0.6012438 0.7070475 -0.3722764 0.6012464 0.707046 -0.3722754 0.587078 0.7070473 -0.3942381 0.5870813 0.7070448 -0.3942376 0.5721105 0.7070452 -0.4156642 0.5721101 0.7070474 -0.4156611 0.5563604 0.7070457 -0.4365198 0.5563593 0.7070478 -0.4365178 0.539851 0.7070455 -0.4567795 0.5398493 0.707047 -0.4567793 0.5226054 0.7070447 -0.4764152 0.5226008 0.7070479 -0.4764155 0.5046412 0.7070476 -0.4953998 0.504643 0.7070446 -0.4954022 0.4859904 0.7070469 -0.51371 0.485991 0.7070458 -0.5137111 0.4666793 0.7070463 -0.5313153 0.4666776 0.7070447 -0.531319 0.4467217 0.7070479 -0.5481998 0.4467252 0.7070463 -0.5481989 0.4261662 0.7070457 -0.5643304 0.4261619 0.7070474 -0.5643315 0.4050213 0.7070456 -0.5796933 0.4050182 0.7070459 -0.5796952 0.3833217 0.7070472 -0.5942632 0.383322 0.7070462 -0.5942642 0.3611015 0.7070465 -0.6080222 0.3611049 0.7070456 -0.6080213 0.338389 0.7070461 -0.6209499 0.3383823 0.7070479 -0.6209514 0.3152158 0.7070454 -0.6330292 0.315209 0.7070467 -0.633031 0.2916053 0.707046 -0.6442456 0.2916031 0.7070475 -0.6442449 0.2676016 0.7070463 -0.65458 0.2675997 0.7070471 -0.6545799 0.2432289 0.7070469 -0.6640214 0.2432284 0.707047 -0.6640215 0.2185276 0.7070471 -0.6725549 0.2185282 0.7070464 -0.6725555 0.1935211 0.7070475 -0.6801717 0.1935292 0.7070448 -0.6801722 0.1682603 0.707046 -0.6868584 0.1682583 0.7070465 -0.6868584 0.142766 0.7070465 -0.6926062 0.1427672 0.7070463 -0.6926061 0.11707 0.707047 -0.697409 0.1170741 0.7070463 -0.6974089 0.09122389 0.7070465 -0.7012585 0.09122699 0.7070452 -0.7012594 0.06524819 0.7070455 -0.7041516 0.06524711 0.7070455 -0.7041517 0.03918868 0.7070452 -0.7060818 0.0391826 0.707046 -0.7060813 0.01306861 0.7070459 -0.7070469 -0.02707749 7.73295e-4 -0.9996331 -0.05378031 0 -0.9985529 -0.08024305 0 -0.9967753 -0.08115893 0.001519381 -0.9967001 -0.1072324 0 -0.994234 -0.1336354 0 -0.9910306 -0.1349994 0.002237081 -0.9908432 -0.1604226 0 -0.9870485 -0.1866419 0 -0.982428 -0.1884431 0.002930104 -0.9820798 -0.2131828 0 -0.9770123 -0.2391106 0 -0.9709923 -0.2413357 0.003594875 -0.970435 -0.2653264 0 -0.9641587 -0.2908887 0 -0.9567569 -0.2935174 0.00423485 -0.9559444 -0.3167011 0 -0.9485254 -0.3418288 0 -0.9397624 -0.3448423 0.004848182 -0.9386482 -0.3671652 0 -0.9301558 -0.3917823 0 -0.920058 -0.3951507 0.005431175 -0.9186003 -0.416554 0 -0.909111 -0.4406067 0 -0.8977003 -0.4443052 0.00599116 -0.8958555 -0.4647442 0 -0.8854451 -0.4881618 0 -0.8727533 -0.4921516 0.006525456 -0.8704852 -0.5116193 0 -0.8592123 -0.5343049 0 -0.8452919 -0.5385544 0.007032454 -0.8425614 -0.557007 0 -0.8305078 -0.5789119 0 -0.8153901 -0.583378 0.00750941 -0.8121661 -0.6007791 0 -0.7994152 -0.6218472 0 -0.7831388 -0.6264904 0.007964372 -0.7793885 -0.64283 0 -0.7660089 -0.6629897 0 -0.7486286 -0.6677649 0.008387863 -0.7443251 -0.6830197 0 -0.7304 -0.7022215 0 -0.7119586 -0.7070795 0.008788466 -0.7070795 -0.7212428 0 -0.6926824 -0.7394275 0 -0.6732363 -0.7443206 0.009160637 -0.6677597 -0.7573863 0 -0.652967 -0.7745012 0 -0.6325724 -0.779378 0.009507238 -0.626482 -0.7913447 0 -0.6113705 -0.8073415 0 -0.5900844 -0.8121498 0.009825885 -0.5833662 -0.823023 0 -0.568008 -0.8378526 0 -0.5458967 -0.8425388 0.01012343 -0.5385407 -0.8523305 0 -0.5230037 -0.8705031 0 -0.4921628 -0.8658422 0.01570725 -0.5000706 -0.8791733 0 -0.4765022 -0.8958724 0 -0.4443113 -0.8914272 0.01649403 -0.4528638 -0.9034845 0 -0.428621 -0.9186134 0 -0.3951575 -0.9144396 0.01727712 -0.4043534 -0.9251919 0 -0.3794996 -0.938659 0 -0.3448471 -0.9348126 0.01807087 -0.3546814 -0.9442296 0 -0.3292878 -0.9559524 0 -0.2935218 -0.9524911 0.01885354 -0.3039826 -0.960545 0 -0.2781249 -0.9704411 0 -0.2413383 -0.9674209 0.01963973 -0.252411 -0.9740896 0 -0.2261626 -0.9820838 0 -0.1884449 -0.9795606 0.0204178 -0.2001104 -0.9848256 0 -0.1735473 -0.9908456 0 -0.1349998 -0.9888736 0.02121156 -0.1472384 -0.992722 0 -0.1204289 -0.9967013 0 -0.08115899 -0.9953348 0.02199715 -0.09394073 -0.9977552 0 -0.06696707 -0.9996334 0 -0.02707862 -0.9989254 0.02276504 -0.04037231 -0.9999114 0 -0.01331067 -0.9999114 0 0.01331067 -0.9995664 0.01157867 0.02707678 -0.9991844 0 0.0403828 -0.9977552 0 0.06696707 -0.9966347 0.01156085 0.08115357 -0.9955757 0 0.0939635 -0.992722 0 0.1204289 -0.9907801 0.01150739 0.1349909 -0.9890962 0 0.1472714 -0.9848256 0 0.1735473 -0.9820198 0.01142269 0.1884325 -0.9797648 0 0.2001521 -0.9740896 0 0.2261626 -0.9703789 0.01132017 0.2413229 -0.9676074 0 0.2524597 -0.960545 0 0.2781249 -0.9558926 0.01118648 0.2935034 -0.9526605 0 0.3040366 -0.9442296 0 0.3292878 -0.9386017 0.01102823 0.3448265 -0.9349654 0 0.3547387 -0.9251919 0 0.3794996 -0.9185597 0.0108366 0.3951339 -0.9145759 0 0.4044145 -0.9034845 0 0.428621 -0.8958219 0.01062488 0.4442863 -0.8915485 0 0.4529254 -0.8791733 0 0.4765022 -0.8704566 0.0103842 0.4921358 -0.8659486 0 0.5001331 -0.8523305 0 0.5230037 -0.8425388 0.01012343 0.5385407 -0.8378526 0 0.5458967 -0.823023 0 0.568008 -0.8121499 0.009824812 0.5833663 -0.8073415 0 0.5900844 -0.7913447 0 0.6113705 -0.779378 0.009506106 0.626482 -0.7745012 0 0.6325724 -0.7573863 0 0.652967 -0.7443206 0.009160637 0.6677597 -0.7394275 0 0.6732363 -0.7212428 0 0.6926824 -0.7070795 0.008788466 0.7070795 -0.7022215 0 0.7119586 -0.6830197 0 0.7304 -0.6677649 0.008387267 0.7443251 -0.6629897 0 0.7486286 -0.64283 0 0.7660089 -0.6264904 0.007963836 0.7793885 -0.6218472 0 0.7831388 -0.6007791 0 0.7994152 -0.583378 0.007509171 0.8121661 -0.5789119 0 0.8153901 -0.557007 0 0.8305078 -0.5385544 0.007032215 0.8425614 -0.5343049 0 0.8452919 -0.5116193 0 0.8592123 -0.4921516 0.006525158 0.8704852 -0.4881618 0 0.8727533 -0.4647442 0 0.8854451 -0.4443052 0.005991339 0.8958555 -0.4406067 0 0.8977003 -0.416554 0 0.909111 -0.3951507 0.005431354 0.9186003 -0.3917823 0 0.920058 -0.3671652 0 0.9301558 -0.3448421 0.004847943 0.9386482 -0.3418288 0 0.9397624 -0.3167011 0 0.9485254 -0.2935174 0.004234969 0.9559444 -0.2908887 0 0.9567569 -0.2653264 0 0.9641587 -0.2413357 0.003594994 0.970435 -0.2391106 0 0.9709923 -0.2131828 0 0.9770123 -0.1884431 0.002930104 0.9820797 -0.1866419 0 0.982428 -0.1604226 0 0.9870485 -0.1349993 0.002237081 0.9908432 -0.1336354 0 0.9910306 -0.1072324 0 0.994234 -0.08115887 0.001519381 0.9967001 -0.08024305 0 0.9967753 -0.05378031 0 0.9985529 -0.02707749 7.73295e-4 0.9996331 -0.02661913 0 0.9996457 0.02661913 0 0.9996457 0.02707749 7.73296e-4 0.9996331 0.05378031 0 0.9985529 0.08024305 0 0.9967753 0.08115893 0.001519381 0.9967001 0.1072324 0 0.994234 0.1336354 0 0.9910306 0.1349994 0.002237081 0.9908432 0.1604226 0 0.9870485 0.1866419 0 0.982428 0.1884431 0.002930104 0.9820798 0.2131828 0 0.9770123 0.2391106 0 0.9709923 0.2413357 0.003594875 0.970435 0.2653264 0 0.9641587 0.2908887 0 0.9567569 0.2935174 0.00423485 0.9559444 0.3167011 0 0.9485254 0.3418288 0 0.9397624 0.3448423 0.004848182 0.9386482 0.3671652 0 0.9301558 0.3917823 0 0.920058 0.3951507 0.005431175 0.9186003 0.416554 0 0.909111 0.4406067 0 0.8977003 0.4443052 0.00599116 0.8958555 0.4647442 0 0.8854451 0.4881618 0 0.8727533 0.4921516 0.006525456 0.8704852 0.5116193 0 0.8592123 0.5343049 0 0.8452919 0.5385544 0.007032454 0.8425614 0.557007 0 0.8305078 0.5789119 0 0.8153901 0.583378 0.00750941 0.8121661 0.6007791 0 0.7994152 0.6218472 0 0.7831388 0.6264904 0.007964372 0.7793885 0.64283 0 0.7660089 0.6629897 0 0.7486286 0.6677649 0.008387863 0.7443251 0.6830197 0 0.7304 0.7022215 0 0.7119586 0.7070795 0.008788466 0.7070795 0.7212428 0 0.6926824 0.7394275 0 0.6732363 0.7443206 0.009160637 0.6677597 0.7573863 0 0.652967 0.7745012 0 0.6325724 0.779378 0.009507238 0.626482 0.7913447 0 0.6113705 0.8073415 0 0.5900844 0.8121498 0.009825885 0.5833662 0.823023 0 0.568008 0.8378526 0 0.5458967 0.8425388 0.01012343 0.5385407 0.8523305 0 0.5230037 0.8705031 0 0.4921628 0.8658422 0.01570725 0.5000706 0.8791733 0 0.4765022 0.8958724 0 0.4443113 0.8914272 0.01649403 0.4528638 0.9034845 0 0.428621 0.9186134 0 0.3951575 0.9144396 0.01727712 0.4043534 0.9251919 0 0.3794996 0.938659 0 0.3448471 0.9348126 0.01807087 0.3546814 0.9442296 0 0.3292878 0.9559524 0 0.2935218 0.9524911 0.01885354 0.3039826 0.960545 0 0.2781249 0.9704411 0 0.2413383 0.9674209 0.01963973 0.252411 0.9740896 0 0.2261626 0.9820838 0 0.1884449 0.9795606 0.0204178 0.2001104 0.9848256 0 0.1735473 0.9908456 0 0.1349998 0.9888736 0.02121156 0.1472384 0.992722 0 0.1204289 0.9967013 0 0.08115899 0.9953348 0.02199715 0.09394073 0.9977552 0 0.06696707 0.9996334 0 0.02707862 0.9989254 0.02276504 0.04037231 0.9999114 0 0.01331067 0.9999114 0 -0.01331067 0.9995664 0.01157867 -0.02707678 0.9991844 0 -0.0403828 0.9977552 0 -0.06696707 0.9966347 0.01156085 -0.08115357 0.9955757 0 -0.0939635 0.992722 0 -0.1204289 0.9907801 0.01150739 -0.1349909 0.9890962 0 -0.1472714 0.9848256 0 -0.1735473 0.9820198 0.01142269 -0.1884325 0.9797648 0 -0.2001521 0.9740896 0 -0.2261626 0.9703789 0.01132017 -0.2413229 0.9676074 0 -0.2524597 0.960545 0 -0.2781249 0.9558926 0.01118648 -0.2935034 0.9526605 0 -0.3040366 0.9442296 0 -0.3292878 0.9386017 0.01102823 -0.3448265 0.9349654 0 -0.3547387 0.9251919 0 -0.3794996 0.9185597 0.0108366 -0.3951339 0.9145759 0 -0.4044145 0.9034845 0 -0.428621 0.8958219 0.01062488 -0.4442863 0.8915485 0 -0.4529254 0.8791733 0 -0.4765022 0.8704566 0.0103842 -0.4921358 0.8659486 0 -0.5001331 0.8523305 0 -0.5230037 0.8425388 0.01012343 -0.5385407 0.8378526 0 -0.5458967 0.823023 0 -0.568008 0.8121499 0.009824812 -0.5833663 0.8073415 0 -0.5900844 0.7913447 0 -0.6113705 0.779378 0.009506106 -0.626482 0.7745012 0 -0.6325724 0.7573863 0 -0.652967 0.7443206 0.009160637 -0.6677597 0.7394275 0 -0.6732363 0.7212428 0 -0.6926824 0.7070795 0.008788466 -0.7070795 0.7022215 0 -0.7119586 0.6830197 0 -0.7304 0.6677649 0.008387267 -0.7443251 0.6629897 0 -0.7486286 0.64283 0 -0.7660089 0.6264904 0.007963836 -0.7793885 0.6218472 0 -0.7831388 0.6007791 0 -0.7994152 0.583378 0.007509171 -0.8121661 0.5789119 0 -0.8153901 0.557007 0 -0.8305078 0.5385544 0.007032215 -0.8425614 0.5343049 0 -0.8452919 0.5116193 0 -0.8592123 0.4921516 0.006525158 -0.8704852 0.4881618 0 -0.8727533 0.4647442 0 -0.8854451 0.4443052 0.005991339 -0.8958555 0.4406067 0 -0.8977003 0.416554 0 -0.909111 0.3951507 0.005431354 -0.9186003 0.3917823 0 -0.920058 0.3671652 0 -0.9301558 0.3448421 0.004847943 -0.9386482 0.3418288 0 -0.9397624 0.3167011 0 -0.9485254 0.2935174 0.004234969 -0.9559444 0.2908887 0 -0.9567569 0.2653264 0 -0.9641587 0.2413357 0.003594994 -0.970435 0.2391106 0 -0.9709923 0.2131828 0 -0.9770123 0.1884431 0.002930104 -0.9820797 0.1866419 0 -0.982428 0.1604226 0 -0.9870485 0.1349993 0.002237081 -0.9908432 0.1336354 0 -0.9910306 0.1072324 0 -0.994234 0.08115887 0.001519381 -0.9967001 0.08024305 0 -0.9967753 0.05378031 0 -0.9985529 0.02707749 7.73295e-4 -0.9996331 0.02661913 0 -0.9996457 -0.02661913 0 -0.9996457 0 1 0 0 1 0 0 1 -2.11689e-7 0 1 1.41126e-7 0 1 2.82251e-7 0 1 -1.41126e-7 0 1 -2.82251e-7 0 1 -5.64503e-7 0 1 2.82251e-7 0 1 -5.64504e-7 0 1 2.82252e-7 0 1 1.41126e-7 0 1 5.64503e-7 0 1 -2.82252e-7 0 1 4.23377e-7 0 1 -1.41126e-7 0 1 -1.41126e-7 0 1 1.41126e-7 0 1 -5.64503e-7 0 1 5.64504e-7 0 1 -4.23377e-7 0 1 2.82252e-7 0 1 5.64503e-7 0 1 -1.41126e-7 0 1 -2.82252e-7 0 1 -2.82251e-7 0 1 2.82251e-7 0 1 1.41126e-7 0 1 -2.82251e-7 0 1 2.11689e-7 0 1 0 0 1 0 0 1 0 0 1 2.82251e-7 0 1 0 0 1 -2.82251e-7 0 1 0 0 1 -1.41126e-7 0 1 5.64503e-7 0 1 4.23378e-7 0 1 -4.23377e-7 0 1 2.82252e-7 0 1 -2.82252e-7 0 1 5.64503e-7 0 1 4.23377e-7 0 1 -4.23378e-7 0 1 -5.64503e-7 0 1 1.41126e-7 0 1 0 0 1 0 0 1 0 0.05644863 0.7067127 -0.7052451 0.05675011 0.7069851 -0.7049479 0.0758711 0.7071029 -0.7030286 0.09393608 0.7064535 -0.7014981 0.09450995 0.7069898 -0.7008805 0.1134358 0.7071077 -0.6979478 0.1311877 0.7062027 -0.6957497 0.1319953 0.7069936 -0.6947931 0.1507436 0.7071041 -0.6908547 0.1680853 0.7059621 -0.6880152 0.1691042 0.7069985 -0.6867001 0.1875966 0.7071075 -0.6817672 0.2045333 0.7057301 -0.6783149 0.2057201 0.7070017 -0.6766298 0.2239279 0.7071057 -0.6707145 0.2404194 0.7055064 -0.6666778 0.2417441 0.7070057 -0.6646072 0.2596126 0.7071091 -0.6577219 0.2756432 0.7052941 -0.6531319 0.2770701 0.70701 -0.6506683 0.294549 0.7071048 -0.6428404 0.3101022 0.7050895 -0.6377191 0.3115982 0.7070136 -0.634853 0.3286238 0.7071065 -0.6261044 0.3436974 0.704895 -0.6204799 0.3452265 0.7070174 -0.6172076 0.3617715 0.7071028 -0.6075583 0.3763307 0.7047102 -0.6014639 0.3778585 0.7070198 -0.5977843 0.3938607 0.7071013 -0.5872663 0.4079095 0.7045342 -0.5807248 0.4094007 0.7070237 -0.5766357 0.4248224 0.7071027 -0.5652715 0.4383406 0.7043671 -0.5583231 0.4397622 0.7070266 -0.5538256 0.4545509 0.7071045 -0.5416519 0.4675386 0.704209 -0.5343196 0.4688541 0.707032 -0.5294164 0.4829716 0.7071014 -0.5164747 0.4954162 0.7040601 -0.508785 0.4965962 0.7070346 -0.5034821 0.5100022 0.7070977 -0.4898067 0.5218915 0.7039242 -0.4817883 0.522906 0.7070369 -0.4760971 0.5355589 0.7070991 -0.4617224 0.5468935 0.7037938 -0.4534114 0.5477059 0.7070412 -0.4473377 0.5595749 0.7070945 -0.4323117 0.5703426 0.7036768 -0.4237315 0.5709295 0.7070423 -0.4172897 0.5819738 0.7070964 -0.4016483 0.5921777 0.7035663 -0.392836 0.5924996 0.7070482 -0.3860402 0.6027027 0.7070903 -0.3698281 0.6123315 0.7034658 -0.3608132 0.6123675 0.7070502 -0.3536753 0.6216849 0.7070898 -0.3369451 0.630747 0.7033745 -0.3277537 0.6304665 0.7070546 -0.3202903 0.6388754 0.7070897 -0.3030881 0.6473695 0.7032939 -0.2937523 0.6467493 0.7070562 -0.2859842 0.654228 0.7070872 -0.2683535 0.6621527 0.7032218 -0.2589073 0.6611666 0.7070574 -0.2508562 0.6676881 0.7070889 -0.2328475 0.6750536 0.7031579 -0.2233197 0.6736763 0.707061 -0.2150003 0.6792268 0.7070872 -0.1966695 0.6860312 0.7031069 -0.1870878 0.6842426 0.7070646 -0.1785266 0.6888086 0.7070829 -0.1599265 0.6950581 0.7030634 -0.1503199 0.6928379 0.7070665 -0.141537 0.6964004 0.7070829 -0.1227205 0.7021074 0.7030288 -0.1131188 0.6994346 0.7070684 -0.1041423 0.7019872 0.7070799 -0.0851593 0.7071567 0.7030042 -0.07559484 0.7040149 0.70707 -0.06644564 0.7055491 0.7070772 -0.04735487 0.7101919 0.7029899 -0.03785204 0.7065618 0.707075 -0.02855622 0.7072299 0.7069838 0 0.715291 0.6987619 -0.009521842 0.7070735 0.7070775 0.009412407 0.7062305 0.7069807 0.03764092 0.7144889 0.6990507 0.0288766 0.7055491 0.7070772 0.04735487 0.7032279 0.706979 0.0751748 0.7116259 0.6993409 0.067164 0.7019872 0.7070799 0.0851593 0.6982288 0.7069807 0.1124939 0.7067168 0.6996276 0.1052266 0.6964004 0.7070829 0.1227205 0.6912519 0.7069807 0.1494968 0.699769 0.6999198 0.1429529 0.6888086 0.7070829 0.1599265 0.682314 0.7069824 0.1860742 0.6908161 0.7002043 0.1802415 0.6792268 0.7070872 0.1966695 0.671444 0.7069818 0.2221255 0.6798796 0.7004881 0.21698 0.6676881 0.7070889 0.2328475 0.6586729 0.7069793 0.2575466 0.6669824 0.7007808 0.2530628 0.654228 0.7070872 0.2683535 0.6440282 0.7069836 0.2922361 0.6521825 0.7010643 0.2883867 0.6388754 0.7070897 0.3030881 0.6275629 0.7069824 0.3260991 0.6355109 0.7013501 0.3228529 0.6216849 0.7070898 0.3369451 0.6093199 0.7069803 0.3590378 0.6170178 0.7016373 0.3563625 0.6027027 0.7070903 0.3698281 0.5893462 0.7069817 0.3909576 0.596762 0.7019232 0.3888174 0.5819738 0.7070964 0.4016483 0.5677033 0.706982 0.4217695 0.5748066 0.7022054 0.4201251 0.5595749 0.7070945 0.4323117 0.5444511 0.7069818 0.4513865 0.5512098 0.7024873 0.4501994 0.5355589 0.7070991 0.4617224 0.519657 0.7069805 0.4797241 0.5260371 0.7027745 0.4789499 0.5100022 0.7070977 0.4898067 0.4933879 0.7069805 0.506702 0.4993742 0.7030557 0.5062986 0.4829716 0.7071014 0.5164747 0.4657204 0.706982 0.5322417 0.4712896 0.7033386 0.5321664 0.4545509 0.7071045 0.5416519 0.436734 0.7069809 0.5562747 0.4418677 0.7036218 0.5564795 0.4248224 0.7071027 0.5652715 0.4065088 0.7069805 0.5787307 0.4111973 0.7039059 0.5791661 0.3938607 0.7071013 0.5872663 0.3751302 0.7069817 0.5995451 0.3793665 0.7041856 0.6001699 0.3617715 0.7071028 0.6075583 0.3426899 0.7069812 0.6186608 0.3464662 0.7044677 0.6194244 0.3286238 0.7071065 0.6261044 0.3092786 0.7069814 0.6360222 0.3125914 0.7047485 0.63688 0.294549 0.7071048 0.6428404 0.274989 0.7069817 0.6515811 0.2778435 0.7050293 0.6524851 0.2596126 0.7071091 0.6577219 0.2399206 0.7069802 0.6652948 0.2423225 0.7053091 0.6661974 0.2239279 0.7071057 0.6707145 0.2041743 0.7069813 0.6771193 0.2061284 0.7055891 0.6779787 0.1875966 0.7071075 0.6817672 0.167845 0.7069823 0.6870256 0.1693726 0.7058677 0.6877964 0.1507436 0.7071041 0.6908547 0.1310423 0.7069804 0.6949868 0.1321547 0.7061471 0.695623 0.1134358 0.7071077 0.6979478 0.09386605 0.7069815 0.7009754 0.09458529 0.7064254 0.7014392 0.0758711 0.7071029 0.7030286 0.05642724 0.7069812 0.7049778 0.0567727 0.7067035 0.7052284 0.03793579 0.7071058 0.7060894 0.01882666 0.706981 0.706982 0.01882588 0.7069826 0.7069804 -0.0188266 0.7069829 0.7069801 -0.01882594 0.7069808 0.7069823 -0.03793579 0.7071058 0.7060894 -0.05644863 0.7067129 0.705245 -0.05675011 0.7069851 0.7049479 -0.0758711 0.7071029 0.7030286 -0.09393608 0.7064535 0.7014981 -0.09450995 0.7069898 0.7008805 -0.1134358 0.7071077 0.6979478 -0.1311877 0.7062027 0.6957497 -0.1319953 0.7069936 0.6947931 -0.1507436 0.7071041 0.6908547 -0.1680853 0.7059621 0.6880152 -0.1691042 0.7069985 0.6867001 -0.1875966 0.7071075 0.6817672 -0.2045333 0.7057301 0.6783149 -0.2057201 0.7070017 0.6766298 -0.2239279 0.7071057 0.6707145 -0.2404194 0.7055064 0.6666778 -0.2417441 0.7070057 0.6646072 -0.2596126 0.7071091 0.6577219 -0.2756432 0.7052941 0.6531319 -0.2770701 0.70701 0.6506683 -0.294549 0.7071048 0.6428404 -0.3101022 0.7050895 0.6377191 -0.3115982 0.7070136 0.634853 -0.3286238 0.7071065 0.6261044 -0.3436974 0.704895 0.6204799 -0.3452265 0.7070174 0.6172076 -0.3617715 0.7071028 0.6075583 -0.3763307 0.7047102 0.6014639 -0.3778585 0.7070198 0.5977843 -0.3938607 0.7071013 0.5872663 -0.4079095 0.7045342 0.5807248 -0.4094007 0.7070237 0.5766357 -0.4248224 0.7071027 0.5652715 -0.4383406 0.7043671 0.5583231 -0.4397622 0.7070266 0.5538256 -0.4545509 0.7071045 0.5416519 -0.4675386 0.704209 0.5343196 -0.4688541 0.707032 0.5294164 -0.4829716 0.7071014 0.5164747 -0.4954162 0.7040601 0.508785 -0.4965962 0.7070346 0.5034821 -0.5100022 0.7070977 0.4898067 -0.5218915 0.7039242 0.4817883 -0.522906 0.7070369 0.4760971 -0.5355589 0.7070991 0.4617224 -0.5468935 0.7037938 0.4534114 -0.5477059 0.7070412 0.4473377 -0.5595749 0.7070945 0.4323117 -0.5703426 0.7036768 0.4237315 -0.5709295 0.7070423 0.4172897 -0.5819738 0.7070964 0.4016483 -0.5921777 0.7035663 0.392836 -0.5924996 0.7070482 0.3860402 -0.6027027 0.7070903 0.3698281 -0.6123315 0.7034658 0.3608132 -0.6123675 0.7070502 0.3536753 -0.6216849 0.7070898 0.3369451 -0.630747 0.7033745 0.3277537 -0.6304665 0.7070546 0.3202903 -0.6388754 0.7070897 0.3030881 -0.6473695 0.7032939 0.2937523 -0.6467493 0.7070562 0.2859842 -0.654228 0.7070872 0.2683535 -0.6621527 0.7032218 0.2589073 -0.6611666 0.7070574 0.2508562 -0.6676881 0.7070889 0.2328475 -0.6750536 0.7031579 0.2233197 -0.6736763 0.707061 0.2150003 -0.6792268 0.7070872 0.1966695 -0.6860312 0.7031069 0.1870878 -0.6842426 0.7070646 0.1785266 -0.6888086 0.7070829 0.1599265 -0.6950581 0.7030634 0.1503199 -0.6928379 0.7070665 0.141537 -0.6964004 0.7070829 0.1227205 -0.7021074 0.7030288 0.1131188 -0.6994346 0.7070684 0.1041423 -0.7019872 0.7070799 0.0851593 -0.7071567 0.7030042 0.07559484 -0.7040149 0.70707 0.06644564 -0.7055491 0.7070772 0.04735487 -0.7101919 0.7029899 0.03785204 -0.7065618 0.707075 0.02855622 -0.7072299 0.7069838 0 -0.715291 0.6987619 0.009521842 -0.7070735 0.7070775 -0.009412407 -0.7062305 0.7069807 -0.03764092 -0.7144889 0.6990507 -0.0288766 -0.7055491 0.7070772 -0.04735487 -0.7032279 0.706979 -0.0751748 -0.7116259 0.6993409 -0.067164 -0.7019872 0.7070799 -0.0851593 -0.6982288 0.7069807 -0.1124939 -0.7067168 0.6996276 -0.1052266 -0.6964004 0.7070829 -0.1227205 -0.6912519 0.7069807 -0.1494968 -0.699769 0.6999198 -0.1429529 -0.6888086 0.7070829 -0.1599265 -0.682314 0.7069824 -0.1860742 -0.6908161 0.7002043 -0.1802415 -0.6792268 0.7070872 -0.1966695 -0.671444 0.7069818 -0.2221255 -0.6798796 0.7004881 -0.21698 -0.6676881 0.7070889 -0.2328475 -0.6586729 0.7069793 -0.2575466 -0.6669824 0.7007808 -0.2530628 -0.654228 0.7070872 -0.2683535 -0.6440282 0.7069836 -0.2922361 -0.6521825 0.7010643 -0.2883867 -0.6388754 0.7070897 -0.3030881 -0.6275629 0.7069824 -0.3260991 -0.6355109 0.7013501 -0.3228529 -0.6216849 0.7070898 -0.3369451 -0.6093199 0.7069803 -0.3590378 -0.6170178 0.7016373 -0.3563625 -0.6027027 0.7070903 -0.3698281 -0.5893462 0.7069817 -0.3909576 -0.596762 0.7019232 -0.3888174 -0.5819738 0.7070964 -0.4016483 -0.5677033 0.706982 -0.4217695 -0.5748066 0.7022054 -0.4201251 -0.5595749 0.7070945 -0.4323117 -0.5444511 0.7069818 -0.4513865 -0.5512098 0.7024873 -0.4501994 -0.5355589 0.7070991 -0.4617224 -0.519657 0.7069805 -0.4797241 -0.5260371 0.7027745 -0.4789499 -0.5100022 0.7070977 -0.4898067 -0.4933879 0.7069805 -0.506702 -0.4993742 0.7030557 -0.5062986 -0.4829716 0.7071014 -0.5164747 -0.4657204 0.706982 -0.5322417 -0.4712896 0.7033386 -0.5321664 -0.4545509 0.7071045 -0.5416519 -0.436734 0.7069809 -0.5562747 -0.4418677 0.7036218 -0.5564795 -0.4248224 0.7071027 -0.5652715 -0.4065088 0.7069805 -0.5787307 -0.4111973 0.7039059 -0.5791661 -0.3938607 0.7071013 -0.5872663 -0.3751302 0.7069817 -0.5995451 -0.3793665 0.7041856 -0.6001699 -0.3617715 0.7071028 -0.6075583 -0.3426899 0.7069812 -0.6186608 -0.3464662 0.7044677 -0.6194244 -0.3286238 0.7071065 -0.6261044 -0.3092786 0.7069814 -0.6360222 -0.3125914 0.7047485 -0.63688 -0.294549 0.7071048 -0.6428404 -0.274989 0.7069817 -0.6515811 -0.2778435 0.7050293 -0.6524851 -0.2596126 0.7071091 -0.6577219 -0.2399206 0.7069802 -0.6652948 -0.2423225 0.7053091 -0.6661974 -0.2239279 0.7071057 -0.6707145 -0.2041743 0.7069813 -0.6771193 -0.2061284 0.7055891 -0.6779787 -0.1875966 0.7071075 -0.6817672 -0.167845 0.7069823 -0.6870256 -0.1693726 0.7058677 -0.6877964 -0.1507436 0.7071041 -0.6908547 -0.1310423 0.7069804 -0.6949868 -0.1321547 0.7061471 -0.695623 -0.1134358 0.7071077 -0.6979478 -0.09386605 0.7069815 -0.7009754 -0.09458529 0.7064254 -0.7014392 -0.0758711 0.7071029 -0.7030286 -0.05642724 0.7069812 -0.7049778 -0.0567727 0.7067035 -0.7052284 -0.03793579 0.7071058 -0.7060894 -0.01882666 0.706981 -0.706982 -0.01882588 0.7069826 -0.7069804 0.0188266 0.7069829 -0.7069801 0.01882594 0.7069807 -0.7069824 0.03793579 0.7071058 -0.7060894 + + + + + + + + + + + + + + +

0 0 1 0 2 0 2 1 1 1 3 1 2 2 3 2 4 2 4 3 3 3 5 3 4 4 5 4 6 4 6 5 5 5 7 5 6 6 7 6 8 6 8 7 7 7 9 7 8 8 9 8 10 8 10 9 9 9 11 9 10 9 11 9 12 9 12 10 11 10 13 10 12 11 13 11 14 11 14 12 13 12 15 12 14 13 15 13 16 13 16 14 15 14 17 14 16 15 17 15 18 15 18 16 17 16 19 16 18 17 19 17 20 17 20 18 19 18 21 18 20 19 21 19 22 19 22 20 21 20 23 20 22 21 23 21 24 21 24 22 23 22 25 22 24 23 25 23 26 23 26 24 25 24 27 24 26 25 27 25 28 25 28 26 27 26 29 26 28 27 29 27 30 27 30 28 29 28 31 28 30 29 31 29 32 29 32 30 31 30 33 30 32 31 33 31 34 31 34 32 33 32 35 32 34 32 35 32 36 32 36 33 35 33 37 33 36 34 37 34 38 34 38 35 37 35 39 35 38 36 39 36 40 36 40 37 39 37 41 37 40 38 41 38 42 38 42 39 41 39 43 39 42 39 43 39 44 39 44 40 43 40 45 40 44 41 45 41 46 41 46 42 45 42 47 42 46 43 47 43 48 43 48 44 47 44 49 44 48 44 49 44 50 44 50 45 49 45 51 45 50 45 51 45 52 45 52 46 51 46 53 46 52 46 53 46 54 46 54 47 53 47 55 47 54 48 55 48 56 48 56 49 55 49 57 49 56 49 57 49 58 49 58 50 57 50 59 50 58 51 59 51 60 51 60 52 59 52 61 52 60 52 61 52 62 52 62 53 61 53 63 53 62 54 63 54 64 54 64 55 63 55 65 55 64 55 65 55 66 55 66 56 65 56 67 56 66 56 67 56 68 56 68 57 67 57 69 57 68 58 69 58 70 58 70 59 69 59 71 59 70 59 71 59 72 59 72 60 71 60 73 60 72 61 73 61 74 61 74 62 73 62 75 62 74 63 75 63 76 63 76 64 75 64 77 64 76 65 77 65 78 65 78 66 77 66 79 66 78 67 79 67 80 67 80 68 79 68 81 68 80 69 81 69 82 69 82 70 81 70 83 70 82 71 83 71 84 71 84 72 83 72 85 72 1 73 0 73 86 73 86 74 0 74 87 74 86 74 87 74 88 74 88 75 87 75 89 75 88 76 89 76 90 76 90 77 89 77 91 77 90 78 91 78 92 78 92 79 91 79 93 79 92 80 93 80 94 80 94 81 93 81 95 81 94 82 95 82 96 82 96 83 95 83 97 83 96 84 97 84 98 84 98 85 97 85 99 85 98 85 99 85 100 85 100 86 99 86 101 86 100 87 101 87 102 87 102 88 101 88 103 88 102 89 103 89 104 89 104 90 103 90 105 90 104 91 105 91 106 91 106 92 105 92 107 92 106 93 107 93 108 93 108 94 107 94 109 94 108 95 109 95 110 95 110 96 109 96 111 96 110 97 111 97 112 97 112 98 111 98 113 98 112 99 113 99 114 99 114 100 113 100 115 100 114 101 115 101 116 101 116 102 115 102 117 102 116 103 117 103 118 103 118 104 117 104 119 104 118 105 119 105 120 105 120 106 119 106 121 106 120 107 121 107 122 107 122 108 121 108 123 108 122 108 123 108 124 108 124 109 123 109 125 109 124 110 125 110 126 110 126 111 125 111 127 111 126 112 127 112 128 112 128 113 127 113 129 113 128 114 129 114 130 114 130 115 129 115 131 115 130 115 131 115 132 115 132 116 131 116 133 116 132 117 133 117 134 117 134 118 133 118 135 118 134 119 135 119 136 119 136 120 135 120 137 120 136 120 137 120 138 120 138 121 137 121 139 121 138 121 139 121 140 121 140 122 139 122 141 122 140 122 141 122 142 122 142 123 141 123 143 123 142 124 143 124 144 124 144 125 143 125 145 125 144 125 145 125 146 125 146 126 145 126 147 126 146 127 147 127 148 127 148 128 147 128 149 128 148 128 149 128 150 128 150 129 149 129 151 129 150 130 151 130 152 130 152 131 151 131 153 131 152 131 153 131 154 131 154 132 153 132 155 132 154 132 155 132 156 132 156 133 155 133 157 133 156 134 157 134 158 134 158 135 157 135 159 135 158 135 159 135 160 135 160 136 159 136 161 136 160 137 161 137 162 137 162 138 161 138 163 138 162 139 163 139 164 139 164 140 163 140 165 140 164 141 165 141 166 141 166 142 165 142 167 142 166 143 167 143 168 143 168 144 167 144 169 144 168 145 169 145 170 145 170 146 169 146 171 146 170 147 171 147 172 147 172 148 171 148 173 148 172 149 173 149 174 149 174 150 173 150 175 150 174 151 175 151 176 151 176 152 175 152 177 152 176 153 177 153 178 153 178 154 177 154 179 154 178 155 179 155 180 155 180 156 179 156 181 156 180 157 181 157 182 157 182 158 181 158 183 158 182 159 183 159 184 159 184 160 183 160 185 160 184 160 185 160 186 160 186 161 185 161 187 161 186 162 187 162 188 162 188 163 187 163 189 163 188 163 189 163 190 163 190 164 189 164 191 164 190 164 191 164 192 164 192 165 191 165 193 165 192 166 193 166 194 166 194 167 193 167 195 167 194 167 195 167 196 167 196 168 195 168 197 168 196 169 197 169 198 169 198 170 197 170 199 170 198 170 199 170 200 170 200 171 199 171 201 171 200 172 201 172 202 172 202 173 201 173 203 173 202 173 203 173 204 173 204 174 203 174 205 174 204 174 205 174 206 174 206 175 205 175 207 175 206 175 207 175 208 175 208 176 207 176 209 176 208 177 209 177 210 177 210 178 209 178 211 178 210 179 211 179 212 179 212 180 211 180 213 180 212 180 213 180 214 180 214 181 213 181 215 181 214 182 215 182 216 182 216 183 215 183 217 183 216 184 217 184 218 184 218 185 217 185 219 185 218 186 219 186 220 186 220 187 219 187 221 187 220 187 221 187 222 187 222 188 221 188 223 188 222 189 223 189 224 189 224 190 223 190 225 190 224 191 225 191 226 191 226 192 225 192 227 192 226 193 227 193 228 193 228 194 227 194 229 194 228 195 229 195 230 195 230 196 229 196 231 196 230 197 231 197 232 197 232 198 231 198 233 198 232 199 233 199 234 199 234 200 233 200 235 200 234 201 235 201 236 201 236 202 235 202 237 202 236 203 237 203 238 203 238 204 237 204 239 204 238 205 239 205 240 205 240 206 239 206 241 206 240 207 241 207 242 207 242 208 241 208 243 208 242 209 243 209 244 209 244 210 243 210 245 210 244 210 245 210 246 210 246 211 245 211 247 211 246 212 247 212 248 212 248 213 247 213 249 213 248 214 249 214 250 214 250 215 249 215 251 215 250 216 251 216 252 216 252 217 251 217 253 217 252 218 253 218 254 218 254 219 253 219 255 219 254 220 255 220 256 220 256 221 255 221 257 221 256 221 257 221 258 221 258 222 257 222 259 222 258 223 259 223 260 223 260 224 259 224 261 224 260 225 261 225 262 225 262 226 261 226 263 226 262 227 263 227 264 227 264 228 263 228 265 228 264 229 265 229 266 229 266 230 265 230 267 230 266 231 267 231 268 231 268 232 267 232 269 232 268 232 269 232 270 232 270 233 269 233 271 233 270 234 271 234 272 234 272 235 271 235 273 235 272 236 273 236 274 236 274 237 273 237 275 237 274 238 275 238 276 238 276 239 275 239 277 239 276 240 277 240 278 240 278 241 277 241 279 241 278 242 279 242 280 242 280 243 279 243 281 243 280 244 281 244 282 244 282 245 281 245 283 245 282 246 283 246 284 246 284 247 283 247 285 247 284 248 285 248 286 248 286 249 285 249 287 249 286 250 287 250 288 250 288 251 287 251 289 251 288 252 289 252 290 252 290 253 289 253 291 253 290 254 291 254 292 254 292 255 291 255 293 255 292 255 293 255 294 255 294 256 293 256 295 256 294 257 295 257 296 257 296 258 295 258 297 258 296 259 297 259 298 259 298 260 297 260 299 260 298 261 299 261 300 261 300 262 299 262 301 262 300 262 301 262 302 262 302 263 301 263 303 263 302 264 303 264 304 264 304 265 303 265 305 265 304 266 305 266 306 266 306 267 305 267 307 267 306 267 307 267 308 267 308 268 307 268 309 268 308 268 309 268 310 268 310 269 309 269 311 269 310 269 311 269 312 269 312 270 311 270 313 270 312 271 313 271 314 271 314 272 313 272 315 272 314 272 315 272 316 272 316 273 315 273 317 273 316 274 317 274 318 274 318 275 317 275 319 275 318 275 319 275 320 275 320 276 319 276 321 276 320 277 321 277 322 277 322 278 321 278 323 278 322 278 323 278 324 278 324 279 323 279 325 279 324 279 325 279 326 279 326 280 325 280 327 280 326 281 327 281 328 281 328 282 327 282 329 282 328 282 329 282 330 282 330 283 329 283 331 283 330 284 331 284 332 284 332 285 331 285 333 285 332 286 333 286 334 286 334 287 333 287 335 287 334 288 335 288 336 288 336 289 335 289 337 289 336 290 337 290 338 290 338 291 337 291 339 291 338 292 339 292 85 292 85 293 339 293 84 293 340 294 341 294 342 294 342 294 341 294 343 294 342 294 343 294 344 294 345 294 346 294 347 294 347 294 346 294 348 294 347 294 348 294 349 294 350 294 351 294 352 294 352 294 351 294 353 294 352 294 353 294 354 294 354 294 353 294 355 294 354 294 355 294 356 294 348 294 357 294 349 294 349 294 357 294 358 294 349 294 358 294 359 294 359 294 358 294 360 294 359 294 360 294 361 294 361 294 360 294 362 294 361 294 362 294 363 294 343 294 364 294 344 294 344 294 364 294 365 294 344 294 365 294 366 294 366 294 365 294 367 294 366 294 367 294 345 294 345 294 367 294 368 294 345 294 368 294 346 294 355 294 369 294 356 294 356 294 369 294 370 294 356 295 370 295 371 295 371 294 370 294 372 294 371 294 372 294 373 294 374 294 375 294 376 294 376 294 375 294 377 294 376 294 377 294 350 294 350 296 377 296 378 296 350 294 378 294 351 294 379 294 380 294 381 294 381 294 380 294 382 294 381 294 382 294 383 294 384 294 385 294 386 294 386 294 385 294 387 294 386 294 387 294 388 294 389 294 390 294 391 294 391 294 390 294 392 294 391 294 392 294 374 294 374 297 392 297 393 297 374 294 393 294 375 294 394 294 395 294 396 294 396 294 395 294 397 294 396 294 397 294 398 294 398 298 397 298 399 298 398 294 399 294 400 294 401 294 402 294 403 294 403 294 402 294 404 294 403 294 404 294 394 294 394 294 404 294 405 294 394 294 405 294 395 294 406 294 407 294 408 294 408 294 407 294 409 294 408 294 409 294 401 294 401 294 409 294 410 294 401 294 410 294 402 294 411 294 412 294 413 294 413 294 412 294 414 294 413 294 414 294 415 294 415 294 414 294 416 294 415 294 416 294 417 294 382 294 418 294 383 294 383 294 418 294 419 294 383 294 419 294 420 294 420 294 419 294 421 294 420 294 421 294 411 294 411 294 421 294 422 294 411 294 422 294 412 294 387 294 423 294 388 294 388 294 423 294 424 294 388 294 424 294 425 294 425 294 424 294 426 294 425 294 426 294 427 294 427 294 426 294 428 294 427 294 428 294 340 294 340 294 428 294 429 294 340 294 429 294 341 294 430 294 431 294 432 294 432 294 431 294 433 294 432 294 433 294 384 294 384 294 433 294 434 294 384 294 434 294 385 294 435 294 436 294 437 294 437 294 436 294 438 294 437 294 438 294 430 294 430 294 438 294 439 294 430 294 439 294 431 294 440 294 441 294 442 294 442 294 441 294 443 294 442 294 443 294 444 294 444 294 443 294 445 294 444 294 445 294 435 294 435 294 445 294 446 294 435 294 446 294 436 294 372 294 447 294 373 294 373 294 447 294 448 294 373 294 448 294 449 294 449 294 448 294 450 294 449 294 450 294 451 294 452 294 453 294 454 294 454 294 453 294 455 294 454 294 455 294 456 294 457 294 458 294 459 294 459 294 458 294 460 294 459 294 460 294 461 294 461 294 460 294 462 294 461 294 462 294 452 294 452 294 462 294 463 294 452 294 463 294 453 294 464 294 465 294 466 294 466 294 465 294 467 294 466 294 467 294 468 294 469 294 470 294 471 294 471 294 470 294 472 294 471 294 472 294 473 294 474 294 475 294 476 294 476 294 475 294 477 294 476 294 477 294 440 294 440 294 477 294 478 294 440 294 478 294 441 294 479 294 480 294 481 294 481 294 480 294 482 294 481 294 482 294 474 294 474 294 482 294 483 294 474 294 483 294 475 294 484 294 485 294 486 294 486 294 485 294 487 294 486 294 487 294 488 294 488 294 487 294 489 294 488 294 489 294 479 294 479 294 489 294 490 294 479 294 490 294 480 294 399 299 491 299 400 299 400 294 491 294 492 294 400 294 492 294 493 294 493 294 492 294 494 294 493 294 494 294 389 294 389 294 494 294 495 294 389 294 495 294 390 294 496 294 497 294 498 294 498 294 497 294 499 294 498 294 499 294 500 294 416 294 501 294 417 294 417 294 501 294 502 294 417 294 502 294 503 294 503 294 502 294 504 294 503 294 504 294 505 294 506 300 507 300 508 300 508 294 507 294 509 294 508 294 509 294 379 294 379 294 509 294 510 294 379 294 510 294 380 294 467 301 511 301 468 301 468 294 511 294 512 294 468 294 512 294 513 294 513 294 512 294 514 294 513 294 514 294 515 294 515 294 514 294 516 294 515 294 516 294 506 294 506 294 516 294 517 294 506 294 517 294 507 294 472 294 518 294 473 294 473 294 518 294 519 294 473 294 519 294 520 294 520 294 519 294 521 294 520 294 521 294 522 294 522 302 521 302 523 302 522 294 523 294 524 294 525 294 526 294 527 294 527 294 526 294 528 294 527 294 528 294 469 294 469 294 528 294 529 294 469 294 529 294 470 294 450 294 530 294 451 294 451 294 530 294 531 294 451 294 531 294 532 294 532 294 531 294 533 294 532 294 533 294 484 294 484 294 533 294 534 294 484 294 534 294 485 294 499 294 535 294 500 294 500 294 535 294 536 294 500 294 536 294 537 294 537 294 536 294 538 294 537 294 538 294 539 294 539 294 538 294 540 294 539 294 540 294 541 294 504 294 542 294 505 294 505 294 542 294 543 294 505 294 543 294 544 294 544 294 543 294 545 294 544 294 545 294 457 294 457 294 545 294 546 294 457 294 546 294 458 294 547 294 548 294 549 294 549 294 548 294 550 294 549 294 550 294 464 294 464 303 550 303 551 303 464 294 551 294 465 294 523 304 552 304 524 304 524 294 552 294 553 294 524 294 553 294 554 294 554 294 553 294 555 294 554 294 555 294 547 294 547 294 555 294 556 294 547 294 556 294 548 294 557 294 558 294 559 294 559 294 558 294 560 294 559 294 560 294 561 294 562 294 563 294 564 294 564 294 563 294 565 294 564 294 565 294 566 294 567 294 568 294 569 294 569 294 568 294 570 294 569 294 570 294 496 294 496 294 570 294 571 294 496 294 571 294 497 294 455 294 572 294 456 294 456 294 572 294 573 294 456 294 573 294 574 294 574 294 573 294 575 294 574 294 575 294 576 294 577 294 578 294 579 294 579 294 578 294 580 294 579 294 580 294 581 294 581 294 580 294 582 294 581 294 582 294 525 294 525 294 582 294 583 294 525 294 583 294 526 294 560 294 584 294 561 294 561 294 584 294 585 294 561 294 585 294 586 294 586 294 585 294 587 294 586 294 587 294 577 294 577 294 587 294 588 294 577 294 588 294 578 294 362 294 589 294 363 294 363 294 589 294 590 294 363 294 590 294 591 294 591 294 590 294 592 294 591 294 592 294 557 294 557 294 592 294 593 294 557 294 593 294 558 294 565 294 594 294 566 294 566 294 594 294 595 294 566 294 595 294 596 294 596 294 595 294 597 294 596 294 597 294 598 294 598 294 597 294 599 294 598 294 599 294 406 294 406 294 599 294 600 294 406 294 600 294 407 294 601 294 602 294 603 294 603 294 602 294 604 294 603 294 604 294 567 294 567 294 604 294 605 294 567 294 605 294 568 294 606 294 607 294 608 294 608 294 607 294 609 294 608 294 609 294 610 294 610 294 609 294 611 294 610 294 611 294 601 294 601 294 611 294 612 294 601 294 612 294 602 294 613 294 614 294 615 294 615 294 614 294 616 294 615 294 616 294 562 294 562 294 616 294 617 294 562 294 617 294 563 294 540 294 618 294 541 294 541 294 618 294 619 294 541 294 619 294 620 294 620 294 619 294 621 294 620 294 621 294 613 294 613 294 621 294 622 294 613 294 622 294 614 294 575 294 623 294 576 294 576 294 623 294 624 294 576 294 624 294 625 294 625 294 624 294 626 294 625 294 626 294 606 294 606 294 626 294 627 294 606 294 627 294 607 294 628 305 169 305 629 305 628 305 629 305 173 305 179 305 177 305 629 305 629 305 177 305 175 305 629 305 175 305 173 305 185 305 183 305 629 305 629 305 183 305 181 305 629 305 181 305 179 305 191 305 189 305 629 305 629 305 189 305 187 305 629 305 187 305 185 305 197 305 195 305 629 305 629 305 195 305 193 305 629 305 193 305 191 305 203 305 201 305 629 305 629 305 201 305 199 305 629 305 199 305 197 305 209 305 207 305 629 305 629 305 207 305 205 305 629 305 205 305 203 305 215 305 213 305 629 305 629 305 213 305 211 305 629 305 211 305 209 305 221 305 219 305 629 305 629 305 219 305 217 305 629 305 217 305 215 305 227 305 225 305 629 305 629 305 225 305 223 305 629 305 223 305 221 305 233 305 231 305 629 305 629 305 231 305 229 305 629 305 229 305 227 305 239 305 237 305 629 305 629 305 237 305 235 305 629 305 235 305 233 305 245 305 243 305 629 305 629 305 243 305 241 305 629 305 241 305 239 305 251 305 249 305 629 305 629 305 249 305 247 305 629 305 247 305 245 305 257 305 255 305 629 305 629 305 255 305 253 305 629 305 253 305 251 305 263 305 261 305 629 305 629 305 261 305 259 305 629 305 259 305 257 305 269 305 267 305 629 305 629 305 267 305 265 305 629 305 265 305 263 305 275 305 273 305 629 305 629 305 273 305 271 305 629 305 271 305 269 305 281 305 279 305 629 305 629 305 279 305 277 305 629 305 277 305 275 305 287 305 285 305 629 305 629 305 285 305 283 305 629 305 283 305 281 305 293 305 291 305 629 305 629 305 291 305 289 305 629 305 289 305 287 305 299 305 297 305 629 305 629 305 297 305 295 305 629 305 295 305 293 305 305 305 303 305 629 305 629 305 303 305 301 305 629 305 301 305 299 305 311 305 309 305 629 305 629 305 309 305 307 305 629 305 307 305 305 305 317 305 315 305 629 305 629 305 315 305 313 305 629 305 313 305 311 305 323 305 321 305 629 305 629 305 321 305 319 305 629 305 319 305 317 305 329 305 327 305 629 305 629 305 327 305 325 305 629 305 325 305 323 305 335 305 333 305 629 305 629 305 333 305 331 305 629 305 331 305 329 305 84 305 339 305 629 305 629 305 339 305 337 305 629 305 337 305 335 305 78 305 80 305 629 305 629 305 80 305 82 305 629 305 82 305 84 305 72 305 74 305 629 305 629 305 74 305 76 305 629 305 76 305 78 305 66 305 68 305 629 305 629 305 68 305 70 305 629 305 70 305 72 305 60 305 62 305 629 305 629 305 62 305 64 305 629 305 64 305 66 305 54 305 56 305 629 305 629 305 56 305 58 305 629 305 58 305 60 305 48 305 50 305 629 305 629 305 50 305 52 305 629 305 52 305 54 305 42 305 44 305 629 305 629 305 44 305 46 305 629 305 46 305 48 305 36 305 38 305 629 305 629 305 38 305 40 305 629 305 40 305 42 305 30 305 32 305 629 305 629 305 32 305 34 305 629 305 34 305 36 305 24 305 26 305 629 305 629 305 26 305 28 305 629 305 28 305 30 305 18 305 20 305 629 305 629 305 20 305 22 305 629 305 22 305 24 305 12 305 14 305 629 305 629 305 14 305 16 305 629 305 16 305 18 305 6 305 8 305 629 305 629 305 8 305 10 305 629 305 10 305 12 305 0 305 2 305 629 305 629 305 2 305 4 305 629 305 4 305 6 305 91 305 89 305 629 305 629 305 89 305 87 305 629 305 87 305 0 305 97 305 95 305 629 305 629 305 95 305 93 305 629 305 93 305 91 305 103 305 101 305 629 305 629 305 101 305 99 305 629 305 99 305 97 305 109 305 107 305 629 305 629 305 107 305 105 305 629 305 105 305 103 305 115 305 113 305 629 305 629 305 113 305 111 305 629 305 111 305 109 305 121 305 119 305 629 305 629 305 119 305 117 305 629 305 117 305 115 305 127 305 125 305 629 305 629 305 125 305 123 305 629 305 123 305 121 305 133 305 131 305 629 305 629 305 131 305 129 305 629 305 129 305 127 305 139 305 137 305 629 305 629 305 137 305 135 305 629 305 135 305 133 305 145 305 143 305 629 305 629 305 143 305 141 305 629 305 141 305 139 305 151 305 149 305 629 305 629 305 149 305 147 305 629 305 147 305 145 305 157 305 155 305 629 305 629 305 155 305 153 305 629 305 153 305 151 305 163 305 161 305 629 305 629 305 161 305 159 305 629 305 159 305 157 305 169 305 167 305 629 305 629 305 167 305 165 305 629 305 165 305 163 305 86 306 568 306 1 306 1 307 568 307 605 307 1 308 605 308 3 308 3 309 605 309 604 309 3 310 604 310 5 310 5 311 604 311 602 311 5 312 602 312 7 312 7 313 602 313 612 313 7 314 612 314 9 314 9 315 612 315 611 315 9 316 611 316 11 316 11 317 611 317 609 317 11 318 609 318 13 318 13 319 609 319 607 319 13 320 607 320 15 320 15 321 607 321 627 321 15 322 627 322 17 322 17 323 627 323 626 323 17 324 626 324 19 324 19 325 626 325 624 325 19 326 624 326 21 326 21 327 624 327 623 327 21 328 623 328 23 328 23 329 623 329 575 329 23 330 575 330 25 330 25 331 575 331 573 331 25 332 573 332 27 332 27 333 573 333 572 333 27 334 572 334 29 334 29 335 572 335 455 335 29 336 455 336 31 336 31 337 455 337 453 337 31 338 453 338 33 338 33 339 453 339 463 339 33 340 463 340 35 340 35 341 463 341 462 341 35 342 462 342 37 342 37 343 462 343 460 343 37 344 460 344 39 344 39 345 460 345 458 345 39 346 458 346 41 346 41 347 458 347 546 347 41 348 546 348 43 348 43 349 546 349 545 349 43 350 545 350 45 350 45 351 545 351 543 351 45 352 543 352 47 352 47 353 543 353 542 353 47 354 542 354 49 354 49 355 542 355 504 355 49 356 504 356 51 356 51 357 504 357 502 357 51 358 502 358 53 358 53 359 502 359 501 359 53 360 501 360 55 360 55 361 501 361 416 361 55 362 416 362 57 362 57 363 416 363 414 363 57 364 414 364 59 364 59 365 414 365 412 365 59 366 412 366 61 366 61 367 412 367 422 367 61 368 422 368 63 368 63 369 422 369 421 369 63 370 421 370 65 370 65 371 421 371 419 371 65 372 419 372 67 372 67 373 419 373 418 373 67 374 418 374 69 374 69 375 418 375 382 375 69 376 382 376 71 376 71 377 382 377 380 377 71 378 380 378 73 378 73 379 380 379 510 379 73 380 510 380 75 380 75 381 510 381 509 381 75 382 509 382 77 382 77 383 509 383 507 383 77 384 507 384 79 384 79 385 507 385 517 385 79 386 517 386 81 386 81 387 517 387 516 387 81 388 516 388 83 388 83 389 516 389 514 389 568 390 86 390 570 390 570 391 86 391 88 391 570 392 88 392 571 392 571 393 88 393 90 393 571 394 90 394 497 394 497 395 90 395 92 395 497 396 92 396 499 396 499 397 92 397 94 397 499 398 94 398 535 398 535 399 94 399 96 399 535 400 96 400 536 400 536 401 96 401 98 401 536 402 98 402 538 402 538 403 98 403 100 403 538 404 100 404 540 404 540 405 100 405 102 405 540 406 102 406 618 406 618 407 102 407 104 407 618 408 104 408 619 408 619 409 104 409 106 409 619 410 106 410 621 410 621 411 106 411 108 411 621 412 108 412 622 412 622 413 108 413 110 413 622 414 110 414 614 414 614 415 110 415 112 415 614 416 112 416 616 416 616 417 112 417 114 417 616 418 114 418 617 418 617 419 114 419 116 419 617 420 116 420 563 420 563 421 116 421 118 421 563 422 118 422 565 422 565 423 118 423 120 423 565 424 120 424 594 424 594 425 120 425 122 425 594 426 122 426 595 426 595 427 122 427 124 427 595 428 124 428 597 428 597 429 124 429 126 429 597 430 126 430 599 430 599 431 126 431 128 431 599 432 128 432 600 432 600 433 128 433 130 433 600 434 130 434 407 434 407 435 130 435 132 435 407 436 132 436 409 436 409 437 132 437 134 437 409 438 134 438 410 438 410 439 134 439 136 439 410 440 136 440 402 440 402 441 136 441 138 441 402 442 138 442 404 442 404 443 138 443 140 443 404 444 140 444 405 444 405 445 140 445 142 445 405 446 142 446 395 446 395 447 142 447 144 447 395 448 144 448 397 448 397 449 144 449 146 449 397 450 146 450 399 450 399 451 146 451 148 451 399 452 148 452 491 452 491 453 148 453 150 453 491 454 150 454 492 454 492 455 150 455 152 455 492 456 152 456 494 456 494 457 152 457 154 457 494 458 154 458 495 458 495 459 154 459 156 459 495 460 156 460 390 460 390 461 156 461 158 461 390 462 158 462 392 462 392 463 158 463 160 463 392 464 160 464 393 464 393 465 160 465 162 465 393 466 162 466 375 466 375 467 162 467 164 467 375 468 164 468 377 468 377 469 164 469 166 469 377 470 166 470 378 470 378 471 166 471 168 471 378 472 168 472 351 472 351 473 168 473 170 473 351 474 170 474 353 474 353 475 170 475 630 475 353 476 630 476 631 476 631 477 630 477 174 477 631 478 174 478 369 478 369 479 174 479 176 479 369 480 176 480 370 480 370 481 176 481 178 481 370 482 178 482 372 482 372 483 178 483 180 483 372 484 180 484 447 484 447 485 180 485 182 485 447 486 182 486 448 486 448 487 182 487 184 487 448 488 184 488 450 488 450 489 184 489 186 489 450 490 186 490 530 490 530 491 186 491 188 491 530 492 188 492 531 492 531 493 188 493 190 493 531 494 190 494 533 494 533 495 190 495 192 495 533 496 192 496 534 496 534 497 192 497 194 497 534 498 194 498 485 498 485 499 194 499 196 499 485 500 196 500 487 500 487 501 196 501 198 501 487 502 198 502 489 502 489 503 198 503 200 503 489 504 200 504 490 504 490 505 200 505 202 505 490 506 202 506 480 506 480 507 202 507 204 507 480 508 204 508 482 508 482 509 204 509 206 509 482 510 206 510 483 510 483 511 206 511 208 511 483 512 208 512 475 512 475 513 208 513 210 513 475 514 210 514 477 514 477 515 210 515 212 515 477 516 212 516 478 516 478 517 212 517 214 517 478 518 214 518 441 518 441 519 214 519 216 519 441 520 216 520 443 520 443 521 216 521 218 521 443 522 218 522 445 522 445 523 218 523 220 523 445 524 220 524 446 524 446 525 220 525 222 525 446 526 222 526 436 526 436 527 222 527 224 527 436 528 224 528 438 528 438 529 224 529 226 529 438 530 226 530 439 530 439 531 226 531 228 531 439 532 228 532 431 532 431 533 228 533 230 533 431 534 230 534 433 534 433 535 230 535 232 535 433 536 232 536 434 536 434 537 232 537 234 537 434 538 234 538 385 538 385 539 234 539 236 539 385 540 236 540 387 540 387 541 236 541 238 541 387 542 238 542 423 542 423 543 238 543 240 543 423 544 240 544 424 544 424 545 240 545 242 545 424 546 242 546 426 546 426 547 242 547 244 547 426 548 244 548 428 548 428 549 244 549 246 549 428 550 246 550 429 550 429 551 246 551 248 551 429 552 248 552 341 552 341 553 248 553 250 553 341 554 250 554 343 554 343 555 250 555 252 555 343 556 252 556 364 556 364 557 252 557 254 557 364 558 254 558 365 558 365 559 254 559 256 559 365 560 256 560 367 560 367 561 256 561 258 561 367 562 258 562 368 562 368 563 258 563 260 563 368 564 260 564 346 564 346 565 260 565 262 565 346 566 262 566 348 566 348 567 262 567 264 567 348 568 264 568 357 568 357 569 264 569 266 569 357 570 266 570 358 570 358 571 266 571 268 571 358 572 268 572 360 572 360 573 268 573 270 573 360 574 270 574 362 574 362 575 270 575 272 575 362 576 272 576 589 576 589 577 272 577 274 577 589 578 274 578 590 578 590 579 274 579 276 579 590 580 276 580 592 580 592 581 276 581 278 581 592 582 278 582 593 582 593 583 278 583 280 583 593 584 280 584 558 584 558 585 280 585 282 585 558 586 282 586 560 586 560 587 282 587 284 587 560 588 284 588 584 588 584 589 284 589 286 589 584 590 286 590 585 590 585 591 286 591 288 591 585 592 288 592 587 592 587 593 288 593 290 593 587 594 290 594 588 594 588 595 290 595 292 595 588 596 292 596 578 596 578 597 292 597 294 597 578 598 294 598 580 598 580 599 294 599 296 599 580 600 296 600 582 600 582 601 296 601 298 601 582 602 298 602 583 602 583 603 298 603 300 603 583 604 300 604 526 604 526 605 300 605 302 605 526 606 302 606 528 606 528 607 302 607 304 607 528 608 304 608 529 608 529 609 304 609 306 609 529 610 306 610 470 610 470 611 306 611 308 611 470 612 308 612 472 612 472 613 308 613 310 613 472 614 310 614 518 614 518 615 310 615 312 615 518 616 312 616 519 616 519 617 312 617 314 617 519 618 314 618 521 618 521 619 314 619 316 619 521 620 316 620 523 620 523 621 316 621 318 621 523 622 318 622 552 622 552 623 318 623 320 623 552 624 320 624 553 624 553 625 320 625 322 625 553 626 322 626 555 626 555 627 322 627 324 627 555 628 324 628 556 628 556 629 324 629 326 629 556 630 326 630 548 630 548 631 326 631 328 631 548 632 328 632 550 632 550 633 328 633 330 633 550 634 330 634 551 634 551 635 330 635 332 635 551 636 332 636 465 636 465 637 332 637 334 637 465 638 334 638 467 638 467 639 334 639 336 639 467 640 336 640 511 640 511 641 336 641 338 641 511 642 338 642 512 642 512 643 338 643 85 643 512 644 85 644 514 644 514 645 85 645 83 645 632 646 633 646 634 646 632 647 635 647 633 647 633 648 635 648 636 648 633 649 636 649 637 649 636 650 638 650 637 650 637 651 638 651 639 651 637 652 639 652 640 652 639 653 641 653 640 653 640 654 641 654 642 654 640 655 642 655 643 655 642 656 644 656 643 656 643 657 644 657 645 657 643 658 645 658 646 658 645 659 647 659 646 659 646 660 647 660 648 660 646 661 648 661 649 661 648 662 650 662 649 662 649 663 650 663 651 663 649 664 651 664 652 664 651 665 653 665 652 665 652 666 653 666 654 666 652 667 654 667 655 667 654 668 656 668 655 668 655 669 656 669 657 669 655 670 657 670 658 670 657 671 659 671 658 671 658 672 659 672 660 672 658 673 660 673 661 673 660 674 662 674 661 674 661 675 662 675 663 675 661 676 663 676 664 676 663 677 665 677 664 677 664 678 665 678 666 678 664 679 666 679 667 679 666 680 668 680 667 680 667 681 668 681 669 681 667 682 669 682 670 682 669 683 671 683 670 683 670 684 671 684 672 684 670 685 672 685 673 685 672 686 674 686 673 686 673 687 674 687 675 687 673 688 675 688 676 688 675 689 677 689 676 689 676 690 677 690 678 690 676 691 678 691 679 691 678 692 680 692 679 692 679 693 680 693 681 693 679 694 681 694 682 694 681 695 683 695 682 695 682 696 683 696 684 696 682 697 684 697 685 697 684 698 686 698 685 698 685 699 686 699 687 699 685 700 687 700 688 700 688 701 687 701 689 701 688 702 689 702 690 702 689 703 691 703 690 703 690 704 691 704 692 704 690 705 692 705 693 705 692 706 694 706 693 706 693 707 694 707 695 707 693 708 695 708 696 708 695 709 697 709 696 709 696 710 697 710 698 710 696 711 698 711 699 711 698 712 700 712 699 712 699 713 700 713 701 713 699 714 701 714 702 714 701 715 703 715 702 715 702 716 703 716 704 716 702 717 704 717 705 717 704 718 706 718 705 718 705 719 706 719 707 719 705 720 707 720 708 720 707 721 709 721 708 721 708 722 709 722 710 722 708 723 710 723 711 723 710 724 712 724 711 724 711 725 712 725 713 725 711 726 713 726 714 726 713 727 715 727 714 727 714 728 715 728 716 728 714 729 716 729 717 729 717 730 716 730 718 730 718 731 719 731 717 731 717 732 719 732 720 732 717 733 720 733 721 733 720 734 722 734 721 734 721 735 722 735 723 735 721 736 723 736 724 736 723 737 725 737 724 737 724 738 725 738 726 738 724 739 726 739 727 739 726 740 728 740 727 740 727 741 728 741 729 741 727 742 729 742 730 742 729 743 731 743 730 743 730 744 731 744 732 744 730 745 732 745 733 745 732 746 734 746 733 746 733 747 734 747 735 747 733 748 735 748 736 748 735 749 737 749 736 749 736 750 737 750 738 750 736 751 738 751 739 751 738 752 740 752 739 752 739 753 740 753 741 753 739 754 741 754 742 754 741 755 743 755 742 755 742 756 743 756 744 756 742 757 744 757 745 757 744 758 746 758 745 758 745 759 746 759 747 759 745 760 747 760 748 760 747 761 749 761 748 761 748 762 749 762 750 762 748 763 750 763 751 763 750 764 752 764 751 764 751 765 752 765 753 765 751 766 753 766 754 766 753 767 755 767 754 767 754 768 755 768 756 768 754 769 756 769 757 769 756 770 758 770 757 770 757 771 758 771 759 771 757 772 759 772 760 772 759 773 761 773 760 773 760 774 761 774 762 774 760 775 762 775 763 775 762 776 764 776 763 776 763 777 764 777 765 777 763 778 765 778 766 778 765 779 767 779 766 779 766 780 767 780 768 780 766 781 768 781 769 781 768 782 770 782 769 782 769 783 770 783 771 783 769 784 771 784 772 784 771 785 773 785 772 785 772 786 773 786 774 786 772 787 774 787 775 787 774 788 776 788 775 788 775 789 776 789 777 789 775 790 777 790 778 790 777 791 779 791 778 791 778 792 779 792 780 792 778 793 780 793 781 793 780 794 782 794 781 794 781 795 782 795 783 795 781 796 783 796 784 796 783 797 785 797 784 797 784 798 785 798 786 798 784 799 786 799 787 799 786 800 788 800 787 800 787 801 788 801 789 801 787 802 789 802 790 802 789 803 791 803 790 803 790 804 791 804 792 804 790 805 792 805 793 805 792 806 794 806 793 806 793 807 794 807 795 807 793 808 795 808 796 808 795 809 797 809 796 809 796 810 797 810 798 810 796 811 798 811 799 811 798 812 800 812 799 812 799 813 800 813 801 813 799 814 801 814 802 814 801 815 803 815 802 815 802 816 803 816 804 816 802 817 804 817 805 817 804 818 806 818 805 818 805 819 806 819 807 819 805 820 807 820 808 820 807 821 809 821 808 821 808 822 809 822 810 822 808 823 810 823 811 823 810 824 812 824 811 824 811 825 812 825 813 825 811 826 813 826 814 826 813 827 815 827 814 827 814 828 815 828 816 828 814 829 816 829 817 829 816 830 818 830 817 830 817 831 818 831 819 831 817 832 819 832 820 832 819 833 821 833 820 833 820 834 821 834 822 834 820 835 822 835 823 835 822 836 824 836 823 836 823 837 824 837 825 837 823 838 825 838 826 838 825 839 827 839 826 839 826 840 827 840 828 840 826 841 828 841 829 841 828 842 830 842 829 842 829 843 830 843 831 843 829 844 831 844 832 844 831 845 833 845 832 845 832 846 833 846 834 846 832 847 834 847 835 847 834 848 836 848 835 848 835 849 836 849 837 849 835 850 837 850 838 850 837 851 839 851 838 851 838 852 839 852 840 852 838 853 840 853 841 853 840 854 842 854 841 854 841 855 842 855 843 855 841 856 843 856 844 856 843 857 845 857 844 857 844 858 845 858 846 858 844 859 846 859 847 859 846 860 848 860 847 860 847 861 848 861 849 861 847 862 849 862 850 862 849 863 851 863 850 863 850 864 851 864 852 864 850 865 852 865 853 865 852 866 854 866 853 866 853 867 854 867 855 867 853 868 855 868 856 868 855 869 857 869 856 869 856 870 857 870 858 870 856 871 858 871 859 871 858 872 860 872 859 872 859 873 860 873 861 873 859 874 861 874 862 874 862 875 861 875 863 875 862 876 863 876 864 876 863 877 865 877 864 877 864 878 865 878 866 878 864 879 866 879 867 879 866 880 868 880 867 880 867 881 868 881 869 881 867 882 869 882 870 882 869 883 871 883 870 883 870 884 871 884 872 884 870 885 872 885 873 885 872 886 874 886 873 886 873 887 874 887 875 887 873 888 875 888 876 888 875 889 877 889 876 889 876 890 877 890 878 890 876 891 878 891 879 891 878 892 880 892 879 892 879 893 880 893 881 893 879 894 881 894 882 894 881 895 883 895 882 895 882 896 883 896 884 896 882 897 884 897 885 897 884 898 886 898 885 898 885 899 886 899 887 899 885 900 887 900 888 900 887 901 889 901 888 901 888 902 889 902 890 902 888 903 890 903 891 903 891 904 890 904 892 904 892 905 893 905 891 905 891 906 893 906 894 906 891 907 894 907 895 907 894 908 896 908 895 908 895 909 896 909 897 909 895 910 897 910 898 910 897 911 899 911 898 911 898 912 899 912 900 912 898 913 900 913 901 913 900 914 902 914 901 914 901 915 902 915 903 915 901 916 903 916 904 916 903 917 905 917 904 917 904 918 905 918 906 918 904 919 906 919 907 919 906 920 908 920 907 920 907 921 908 921 909 921 907 922 909 922 910 922 909 923 911 923 910 923 910 924 911 924 912 924 910 925 912 925 913 925 912 926 914 926 913 926 913 927 914 927 915 927 913 928 915 928 916 928 915 929 917 929 916 929 916 930 917 930 918 930 916 931 918 931 919 931 918 932 920 932 919 932 919 933 920 933 921 933 919 934 921 934 922 934 921 935 923 935 922 935 922 936 923 936 924 936 922 937 924 937 925 937 924 938 926 938 925 938 925 939 926 939 927 939 925 940 927 940 928 940 927 941 929 941 928 941 928 942 929 942 930 942 928 943 930 943 931 943 930 944 932 944 931 944 931 945 932 945 933 945 931 946 933 946 934 946 933 947 935 947 934 947 934 948 935 948 936 948 934 949 936 949 937 949 936 950 938 950 937 950 937 951 938 951 939 951 937 952 939 952 940 952 939 953 941 953 940 953 940 954 941 954 942 954 940 955 942 955 943 955 942 956 944 956 943 956 943 957 944 957 945 957 943 958 945 958 946 958 945 959 947 959 946 959 946 960 947 960 948 960 946 961 948 961 949 961 948 962 950 962 949 962 949 963 950 963 951 963 949 964 951 964 952 964 951 965 953 965 952 965 952 966 953 966 954 966 952 967 954 967 955 967 954 968 956 968 955 968 955 969 956 969 957 969 955 970 957 970 958 970 957 971 959 971 958 971 958 972 959 972 960 972 958 973 960 973 961 973 960 974 962 974 961 974 961 975 962 975 963 975 961 976 963 976 964 976 963 977 965 977 964 977 964 978 965 978 966 978 964 979 966 979 967 979 966 980 968 980 967 980 967 981 968 981 969 981 967 982 969 982 970 982 969 983 971 983 970 983 970 984 971 984 972 984 970 985 972 985 973 985 972 986 974 986 973 986 973 987 974 987 975 987 973 988 975 988 976 988 975 989 977 989 976 989 976 990 977 990 978 990 976 991 978 991 634 991 634 992 978 992 979 992 634 993 979 993 632 993 634 294 633 294 980 294 634 294 980 294 976 294 967 294 970 294 980 294 980 994 970 994 973 994 980 294 973 294 976 294 958 294 961 294 980 294 980 995 961 995 964 995 980 294 964 294 967 294 949 294 952 294 980 294 980 996 952 996 955 996 980 997 955 997 958 997 940 294 943 294 980 294 980 998 943 998 946 998 980 999 946 999 949 999 931 294 934 294 980 294 980 1000 934 1000 937 1000 980 294 937 294 940 294 922 1001 925 1001 980 1001 980 1002 925 1002 928 1002 980 294 928 294 931 294 913 1003 916 1003 980 1003 980 1004 916 1004 919 1004 980 1005 919 1005 922 1005 904 1006 907 1006 980 1006 980 1007 907 1007 910 1007 980 1008 910 1008 913 1008 895 294 898 294 980 294 980 294 898 294 901 294 980 1009 901 1009 904 1009 885 294 888 294 980 294 980 1010 888 1010 891 1010 980 1011 891 1011 895 1011 876 1012 879 1012 980 1012 980 997 879 997 882 997 980 294 882 294 885 294 867 1013 870 1013 980 1013 980 1014 870 1014 873 1014 980 1015 873 1015 876 1015 859 1016 862 1016 980 1016 980 1017 862 1017 864 1017 980 1018 864 1018 867 1018 850 294 853 294 980 294 980 294 853 294 856 294 980 1019 856 1019 859 1019 841 294 844 294 980 294 980 294 844 294 847 294 980 1020 847 1020 850 1020 832 294 835 294 980 294 980 1021 835 1021 838 1021 980 1022 838 1022 841 1022 823 294 826 294 980 294 980 1009 826 1009 829 1009 980 1023 829 1023 832 1023 814 294 817 294 980 294 980 294 817 294 820 294 980 1024 820 1024 823 1024 805 294 808 294 980 294 980 294 808 294 811 294 980 1025 811 1025 814 1025 796 294 799 294 980 294 980 294 799 294 802 294 980 294 802 294 805 294 787 294 790 294 980 294 980 294 790 294 793 294 980 1026 793 1026 796 1026 778 1027 781 1027 980 1027 980 1009 781 1009 784 1009 980 1028 784 1028 787 1028 769 1029 772 1029 980 1029 980 1021 772 1021 775 1021 980 1030 775 1030 778 1030 760 294 763 294 980 294 980 294 763 294 766 294 980 294 766 294 769 294 751 294 754 294 980 294 980 294 754 294 757 294 980 1031 757 1031 760 1031 742 294 745 294 980 294 980 1017 745 1017 748 1017 980 1032 748 1032 751 1032 733 294 736 294 980 294 980 1014 736 1014 739 1014 980 1033 739 1033 742 1033 724 294 727 294 980 294 980 997 727 997 730 997 980 1034 730 1034 733 1034 714 294 717 294 980 294 980 1010 717 1010 721 1010 980 1035 721 1035 724 1035 705 294 708 294 980 294 980 294 708 294 711 294 980 1036 711 1036 714 1036 696 1037 699 1037 980 1037 980 1007 699 1007 702 1007 980 1038 702 1038 705 1038 688 294 690 294 980 294 980 1004 690 1004 693 1004 980 1039 693 1039 696 1039 679 294 682 294 980 294 980 1002 682 1002 685 1002 980 1040 685 1040 688 1040 670 294 673 294 980 294 980 1000 673 1000 676 1000 980 1041 676 1041 679 1041 661 294 664 294 980 294 980 998 664 998 667 998 980 294 667 294 670 294 652 294 655 294 980 294 980 996 655 996 658 996 980 1042 658 1042 661 1042 643 294 646 294 980 294 980 995 646 995 649 995 980 1043 649 1043 652 1043 633 294 637 294 980 294 980 994 637 994 640 994 980 1044 640 1044 643 1044 350 1045 352 1045 977 1045 977 1046 975 1046 350 1046 350 1047 975 1047 974 1047 350 1048 974 1048 376 1048 974 1049 972 1049 376 1049 376 1050 972 1050 971 1050 376 1051 971 1051 374 1051 971 1052 969 1052 374 1052 374 1053 969 1053 968 1053 374 1054 968 1054 391 1054 968 1055 966 1055 391 1055 391 1056 966 1056 965 1056 391 1057 965 1057 389 1057 965 1058 963 1058 389 1058 389 1059 963 1059 962 1059 389 1060 962 1060 493 1060 962 1061 960 1061 493 1061 493 1062 960 1062 959 1062 493 1063 959 1063 400 1063 959 1064 957 1064 400 1064 400 1065 957 1065 956 1065 400 1066 956 1066 398 1066 956 1067 954 1067 398 1067 398 1068 954 1068 953 1068 398 1069 953 1069 396 1069 953 1070 951 1070 396 1070 396 1071 951 1071 950 1071 396 1072 950 1072 394 1072 950 1073 948 1073 394 1073 394 1074 948 1074 947 1074 394 1075 947 1075 403 1075 947 1076 945 1076 403 1076 403 1077 945 1077 944 1077 403 1078 944 1078 401 1078 944 1079 942 1079 401 1079 401 1080 942 1080 941 1080 401 1081 941 1081 408 1081 941 1082 939 1082 408 1082 408 1083 939 1083 938 1083 408 1084 938 1084 406 1084 938 1085 936 1085 406 1085 406 1086 936 1086 935 1086 406 1087 935 1087 598 1087 935 1088 933 1088 598 1088 598 1089 933 1089 932 1089 598 1090 932 1090 596 1090 932 1091 930 1091 596 1091 596 1092 930 1092 929 1092 596 1093 929 1093 566 1093 929 1094 927 1094 566 1094 566 1095 927 1095 926 1095 566 1096 926 1096 564 1096 926 1097 924 1097 564 1097 564 1098 924 1098 923 1098 564 1099 923 1099 562 1099 923 1100 921 1100 562 1100 562 1101 921 1101 920 1101 562 1102 920 1102 615 1102 920 1103 918 1103 615 1103 615 1104 918 1104 917 1104 615 1105 917 1105 613 1105 917 1106 915 1106 613 1106 613 1107 915 1107 914 1107 613 1108 914 1108 620 1108 914 1109 912 1109 620 1109 620 1110 912 1110 911 1110 620 1111 911 1111 541 1111 911 1112 909 1112 541 1112 541 1113 909 1113 908 1113 541 1114 908 1114 539 1114 908 1115 906 1115 539 1115 539 1116 906 1116 905 1116 539 1117 905 1117 537 1117 905 1118 903 1118 537 1118 537 1119 903 1119 902 1119 537 1120 902 1120 500 1120 902 1121 900 1121 500 1121 500 1122 900 1122 899 1122 500 1123 899 1123 498 1123 899 1124 897 1124 498 1124 498 1125 897 1125 896 1125 498 1126 896 1126 496 1126 496 1127 896 1127 894 1127 496 1128 894 1128 569 1128 894 1129 893 1129 569 1129 569 1130 893 1130 892 1130 569 1131 892 1131 567 1131 892 1132 890 1132 567 1132 567 1133 890 1133 889 1133 567 1134 889 1134 603 1134 889 1135 887 1135 603 1135 603 1136 887 1136 886 1136 603 1137 886 1137 601 1137 886 1138 884 1138 601 1138 601 1139 884 1139 883 1139 601 1140 883 1140 610 1140 883 1141 881 1141 610 1141 610 1142 881 1142 880 1142 610 1143 880 1143 608 1143 880 1144 878 1144 608 1144 608 1145 878 1145 877 1145 608 1146 877 1146 606 1146 877 1147 875 1147 606 1147 606 1148 875 1148 874 1148 606 1149 874 1149 625 1149 874 1150 872 1150 625 1150 625 1151 872 1151 871 1151 625 1152 871 1152 576 1152 871 1153 869 1153 576 1153 576 1154 869 1154 868 1154 576 1155 868 1155 574 1155 868 1156 866 1156 574 1156 574 1157 866 1157 865 1157 574 1158 865 1158 456 1158 865 1159 863 1159 456 1159 456 1160 863 1160 861 1160 456 1161 861 1161 454 1161 861 1162 860 1162 454 1162 454 1163 860 1163 858 1163 454 1164 858 1164 452 1164 858 1165 857 1165 452 1165 452 1166 857 1166 855 1166 452 1167 855 1167 461 1167 855 1168 854 1168 461 1168 461 1169 854 1169 852 1169 461 1170 852 1170 459 1170 852 1171 851 1171 459 1171 459 1172 851 1172 849 1172 459 1173 849 1173 457 1173 849 1174 848 1174 457 1174 457 1175 848 1175 846 1175 457 1176 846 1176 544 1176 846 1177 845 1177 544 1177 544 1178 845 1178 843 1178 544 1179 843 1179 505 1179 843 1180 842 1180 505 1180 505 1181 842 1181 840 1181 505 1182 840 1182 503 1182 840 1183 839 1183 503 1183 503 1184 839 1184 837 1184 503 1185 837 1185 417 1185 837 1186 836 1186 417 1186 417 1187 836 1187 834 1187 417 1188 834 1188 415 1188 834 1189 833 1189 415 1189 415 1190 833 1190 831 1190 415 1191 831 1191 413 1191 831 1192 830 1192 413 1192 413 1193 830 1193 828 1193 413 1194 828 1194 411 1194 828 1195 827 1195 411 1195 411 1196 827 1196 825 1196 411 1197 825 1197 420 1197 825 1198 824 1198 420 1198 420 1199 824 1199 822 1199 420 1200 822 1200 383 1200 822 1201 821 1201 383 1201 383 1202 821 1202 819 1202 383 1203 819 1203 381 1203 819 1204 818 1204 381 1204 381 1205 818 1205 816 1205 381 1206 816 1206 379 1206 816 1207 815 1207 379 1207 379 1208 815 1208 813 1208 379 1209 813 1209 508 1209 813 1210 812 1210 508 1210 508 1211 812 1211 810 1211 508 1212 810 1212 506 1212 810 1213 809 1213 506 1213 506 1214 809 1214 807 1214 506 1215 807 1215 981 1215 981 1216 807 1216 982 1216 981 1217 982 1217 513 1217 982 1218 804 1218 513 1218 513 1219 804 1219 803 1219 513 1220 803 1220 468 1220 803 1221 801 1221 468 1221 468 1222 801 1222 800 1222 468 1223 800 1223 466 1223 800 1224 798 1224 466 1224 466 1225 798 1225 797 1225 466 1226 797 1226 464 1226 797 1227 795 1227 464 1227 464 1228 795 1228 794 1228 464 1229 794 1229 549 1229 794 1230 792 1230 549 1230 549 1231 792 1231 791 1231 549 1232 791 1232 547 1232 791 1233 789 1233 547 1233 547 1234 789 1234 788 1234 547 1235 788 1235 554 1235 788 1236 786 1236 554 1236 554 1237 786 1237 785 1237 554 1238 785 1238 524 1238 785 1239 783 1239 524 1239 524 1240 783 1240 782 1240 524 1241 782 1241 522 1241 782 1242 780 1242 522 1242 522 1243 780 1243 779 1243 522 1244 779 1244 520 1244 779 1245 777 1245 520 1245 520 1246 777 1246 776 1246 520 1247 776 1247 473 1247 776 1248 774 1248 473 1248 473 1249 774 1249 773 1249 473 1250 773 1250 471 1250 773 1251 771 1251 471 1251 471 1252 771 1252 770 1252 471 1253 770 1253 469 1253 770 1254 768 1254 469 1254 469 1255 768 1255 767 1255 469 1256 767 1256 527 1256 767 1257 765 1257 527 1257 527 1258 765 1258 764 1258 527 1259 764 1259 525 1259 764 1260 762 1260 525 1260 525 1261 762 1261 761 1261 525 1262 761 1262 581 1262 761 1263 759 1263 581 1263 581 1264 759 1264 758 1264 581 1265 758 1265 579 1265 758 1266 756 1266 579 1266 579 1267 756 1267 755 1267 579 1268 755 1268 577 1268 755 1269 753 1269 577 1269 577 1270 753 1270 752 1270 577 1271 752 1271 586 1271 752 1272 750 1272 586 1272 586 1273 750 1273 749 1273 586 1274 749 1274 561 1274 749 1275 747 1275 561 1275 561 1276 747 1276 746 1276 561 1277 746 1277 559 1277 746 1278 744 1278 559 1278 559 1279 744 1279 743 1279 559 1280 743 1280 557 1280 743 1281 741 1281 557 1281 557 1282 741 1282 740 1282 557 1283 740 1283 591 1283 740 1284 738 1284 591 1284 591 1285 738 1285 737 1285 591 1286 737 1286 363 1286 737 1287 735 1287 363 1287 363 1288 735 1288 734 1288 363 1289 734 1289 361 1289 734 1290 732 1290 361 1290 361 1291 732 1291 731 1291 361 1292 731 1292 359 1292 731 1293 729 1293 359 1293 359 1294 729 1294 728 1294 359 1295 728 1295 349 1295 728 1296 726 1296 349 1296 349 1297 726 1297 725 1297 349 1298 725 1298 347 1298 725 1299 723 1299 347 1299 347 1300 723 1300 722 1300 347 1301 722 1301 345 1301 345 1302 722 1302 720 1302 345 1303 720 1303 366 1303 720 1304 719 1304 366 1304 366 1305 719 1305 718 1305 366 1306 718 1306 344 1306 718 1307 716 1307 344 1307 344 1308 716 1308 715 1308 344 1309 715 1309 342 1309 715 1310 713 1310 342 1310 342 1311 713 1311 712 1311 342 1312 712 1312 340 1312 712 1313 710 1313 340 1313 340 1314 710 1314 709 1314 340 1315 709 1315 427 1315 709 1316 707 1316 427 1316 427 1317 707 1317 706 1317 427 1318 706 1318 425 1318 706 1319 704 1319 425 1319 425 1320 704 1320 703 1320 425 1321 703 1321 388 1321 703 1322 701 1322 388 1322 388 1323 701 1323 700 1323 388 1324 700 1324 386 1324 700 1325 698 1325 386 1325 386 1326 698 1326 697 1326 386 1327 697 1327 384 1327 697 1328 695 1328 384 1328 384 1329 695 1329 694 1329 384 1330 694 1330 432 1330 694 1331 692 1331 432 1331 432 1332 692 1332 691 1332 432 1333 691 1333 430 1333 691 1334 689 1334 430 1334 430 1335 689 1335 687 1335 430 1336 687 1336 437 1336 687 1337 686 1337 437 1337 437 1338 686 1338 684 1338 437 1339 684 1339 435 1339 684 1340 683 1340 435 1340 435 1341 683 1341 681 1341 435 1342 681 1342 444 1342 681 1343 680 1343 444 1343 444 1344 680 1344 678 1344 444 1345 678 1345 442 1345 678 1346 677 1346 442 1346 442 1347 677 1347 675 1347 442 1348 675 1348 440 1348 675 1349 674 1349 440 1349 440 1350 674 1350 672 1350 440 1351 672 1351 476 1351 672 1352 671 1352 476 1352 476 1353 671 1353 669 1353 476 1354 669 1354 474 1354 669 1355 668 1355 474 1355 474 1356 668 1356 666 1356 474 1357 666 1357 481 1357 666 1358 665 1358 481 1358 481 1359 665 1359 663 1359 481 1360 663 1360 479 1360 663 1361 662 1361 479 1361 479 1362 662 1362 660 1362 479 1363 660 1363 488 1363 660 1364 659 1364 488 1364 488 1365 659 1365 657 1365 488 1366 657 1366 486 1366 657 1367 656 1367 486 1367 486 1368 656 1368 654 1368 486 1369 654 1369 484 1369 654 1370 653 1370 484 1370 484 1371 653 1371 651 1371 484 1372 651 1372 532 1372 651 1373 650 1373 532 1373 532 1374 650 1374 648 1374 532 1375 648 1375 451 1375 648 1376 647 1376 451 1376 451 1377 647 1377 645 1377 451 1378 645 1378 449 1378 645 1379 644 1379 449 1379 449 1380 644 1380 642 1380 449 1381 642 1381 373 1381 642 1382 641 1382 373 1382 373 1383 641 1383 639 1383 373 1384 639 1384 371 1384 639 1385 638 1385 371 1385 371 1386 638 1386 636 1386 371 1387 636 1387 356 1387 636 1388 635 1388 356 1388 356 1389 635 1389 632 1389 356 1390 632 1390 354 1390 354 1391 632 1391 983 1391 354 1392 983 1392 352 1392 352 1393 983 1393 978 1393 352 1394 978 1394 977 1394

+
+
+
+
+ + + + 1 0 0 0 0 -4.37114e-8 1 0 0 -1 -4.37114e-8 6 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_G1M5.dae b/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_G1M5.dae new file mode 100644 index 0000000..83b489a --- /dev/null +++ b/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_G1M5.dae @@ -0,0 +1,107 @@ + + + + + + Blender User + Blender 2.82.7 + + 2022-03-16T10:59:58 + 2022-03-16T10:59:58 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.80848 0.80848 0.80848 1 + + + 1 + + + + + + + + + + + + + + + + + -58.47636 -28.43613 -1 -58.47636 25.65426 -1 -31.80329 1.724324 -1 -32.11308 53.5 -1 -13.37347 28.90628 -1 -36.64468 52.9364 -1 -19.2748 25.35556 -1 -24.27486 20.61925 -1 -44.62028 48.63158 -1 -40.90018 51.27995 -1 -54.57127 -37.1211 -1 -26.3619 -17.87381 -1 -51.42906 -41.36486 -1 -21.90323 -23.12296 -1 -46.92084 -45.84035 -1 -41.53325 -49.20607 -1 -58.1428 29.15144 -1 -57.15417 32.52251 -1 -28.13986 14.91881 -1 -55.5461 35.64591 -1 -50.5023 42.49138 -1 -30.68907 8.520778 -1 -35.53397 -51.29479 -1 -16.42039 -27.2909 -1 -29.22106 -52.00276 -1 46.92084 -45.84035 -1 21.90323 -23.12296 -1 51.42906 -41.36486 -1 26.3619 -17.87381 -1 54.57127 -37.1211 -1 57.36417 -32.63973 -1 -31.43042 -5.152756 -1 -29.58791 -11.7889 -1 -58.1936 -30.61026 -1 -57.36417 -32.63973 -1 3.443591 -31.66329 -1 29.22106 -52.00276 -1 -3.443591 -31.66329 -1 -10.16975 -30.18276 -1 10.16975 -30.18276 -1 16.42039 -27.2909 -1 35.53397 -51.29479 -1 41.53325 -49.20607 -1 58.1936 -30.61026 -1 29.58791 -11.7889 -1 58.47636 -28.43613 -1 31.43042 -5.152756 -1 58.47636 25.65426 -1 31.80329 1.724324 -1 30.68907 8.520778 -1 58.1428 29.15144 -1 28.13986 14.91881 -1 57.15417 32.52251 -1 55.5461 35.64591 -1 13.37347 28.90628 -1 6.846808 31.10536 -1 32.11308 53.5 -1 0 31.85 -1 -6.846808 31.10536 -1 50.5023 42.49138 -1 24.27486 20.61925 -1 44.62028 48.63158 -1 19.2748 25.35556 -1 40.90018 51.27995 -1 36.64468 52.9364 -1 52.5979 -42.30497 5 55.81153 -37.96477 5 29.22106 -53.50276 5 -29.22106 -53.50276 5 32.11308 55 5 56.80851 36.45605 5 51.65008 43.45709 5 -55.81153 -37.96477 5 59.97636 25.65426 5 59.61576 29.43499 5 -32.11308 55 5 -59.97636 25.65426 5 -59.97636 -28.43613 5 -59.64371 -30.99393 5 58.6679 -33.38155 5 -58.6679 -33.38155 5 58.54696 33.07939 5 45.63438 49.73684 5 41.61265 52.59995 5 37.01211 54.39071 5 -51.65008 43.45709 5 -56.80851 36.45605 5 35.86623 -52.75754 5 42.18126 -50.55887 5 47.8524 -47.01601 5 59.64371 -30.99393 5 59.97636 -28.43613 5 -45.63438 49.73684 5 -37.01211 54.39071 5 -41.61265 52.59995 5 -52.5979 -42.30497 5 -35.86623 -52.75754 5 -47.8524 -47.01601 5 -42.18126 -50.55887 5 -58.54696 33.07939 5 -59.61576 29.43499 5 45.63438 49.73684 0.5 51.65008 43.45709 0.5 56.80851 36.45605 0.5 58.54696 33.07939 0.5 59.61576 29.43499 0.5 59.97636 25.65426 0.5 59.97636 -28.43613 0.5 59.64371 -30.99393 0.5 58.6679 -33.38155 0.5 55.81153 -37.96477 0.5 52.5979 -42.30497 0.5 47.8524 -47.01601 0.5 42.18126 -50.55887 0.5 35.86623 -52.75754 0.5 29.22106 -53.50276 0.5 -29.22106 -53.50276 0.5 -35.86623 -52.75754 0.5 -42.18126 -50.55887 0.5 -47.8524 -47.01601 0.5 -52.5979 -42.30497 0.5 -55.81153 -37.96477 0.5 -58.6679 -33.38155 0.5 -59.64371 -30.99393 0.5 -59.97636 -28.43613 0.5 -59.97636 25.65426 0.5 -59.61576 29.43499 0.5 -58.54696 33.07939 0.5 -56.80851 36.45605 0.5 -51.65008 43.45709 0.5 -45.63438 49.73684 0.5 -41.61265 52.59995 0.5 -37.01211 54.39071 0.5 -32.11308 55 0.5 32.11308 55 0.5 37.01211 54.39071 0.5 41.61265 52.59995 0.5 0 31.6 0 6.793066 30.86121 0 0 3.0287e-7 0 -6.793066 30.86121 0 -24.08432 20.45741 0 -19.12351 25.15654 0 -13.2685 28.67938 0 -31.55366 1.71079 0 -30.44818 8.453896 0 -27.91898 14.80171 0 -26.15497 -17.73351 0 -29.35566 -11.69637 0 -31.18372 -5.11231 0 -10.08993 -29.94584 0 -16.2915 -27.07669 0 -21.7313 -22.94146 0 10.08993 -29.94584 0 3.416561 -31.41476 0 -3.416561 -31.41476 0 26.15497 -17.73351 0 21.7313 -22.94146 0 16.2915 -27.07669 0 31.55366 1.71079 0 31.18372 -5.11231 0 29.35566 -11.69637 0 24.08432 20.45741 0 27.91898 14.80171 0 30.44818 8.453896 0 13.2685 28.67938 0 19.12351 25.15654 0 0 31.6 -0.75 6.793066 30.86121 -0.75 13.2685 28.67938 -0.75 19.12351 25.15654 -0.75 24.08432 20.45741 -0.75 27.91898 14.80171 -0.75 30.44818 8.453896 -0.75 31.55366 1.71079 -0.75 31.18372 -5.11231 -0.75 29.35566 -11.69637 -0.75 26.15497 -17.73351 -0.75 21.7313 -22.94146 -0.75 16.2915 -27.07669 -0.75 10.08993 -29.94584 -0.75 3.416561 -31.41476 -0.75 -3.416561 -31.41476 -0.75 -10.08993 -29.94584 -0.75 -16.2915 -27.07669 -0.75 -21.7313 -22.94146 -0.75 -26.15497 -17.73351 -0.75 -29.35566 -11.69637 -0.75 -31.18372 -5.11231 -0.75 -31.55366 1.71079 -0.75 -30.44818 8.453896 -0.75 -27.91898 14.80171 -0.75 -24.08432 20.45741 -0.75 -19.12351 25.15654 -0.75 -13.2685 28.67938 -0.75 -6.793066 30.86121 -0.75 0 31.6 -0.75 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 -1.24202e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.7221248 0.6917629 0 0.7221252 0.6917625 0 0.805069 0.5931813 0 0.8050694 0.5931808 0 0.8890857 0.457741 0 0.8890864 0.4577395 0 0.9595845 0.2814207 0 0.9595856 0.2814174 0 0.9954821 0.09494972 0 0.9954825 0.0949462 0 1 0 0 0.9916493 -0.1289642 0 0.9916486 -0.1289694 0 0.9256745 -0.3783209 0 0.8486757 -0.5289137 0 0.8486751 -0.5289146 0 0.8036763 -0.5950668 0 0.7045252 -0.7096791 0 0.7045257 -0.7096785 0 0.5298262 -0.8481063 0 0.3288049 -0.9443979 0 0.3288056 -0.9443977 0 0.1114459 -0.9937705 0 0.111446 -0.9937705 0 0 -1 0 -0.111446 -0.9937705 0 -0.1114459 -0.9937705 0 -0.3288056 -0.9443977 0 -0.3288049 -0.9443979 0 -0.5298262 -0.8481063 0 -0.7045257 -0.7096785 0 -0.7045252 -0.7096791 0 -0.8036763 -0.5950668 0 -0.8486739 -0.5289164 0 -0.8486757 -0.5289137 0 -0.9256745 -0.3783209 0 -0.9256764 -0.3783165 0 -0.9916486 -0.1289694 0 -0.9916493 -0.1289642 0 -1 0 0 -0.9954825 0.0949462 0 -0.9954822 0.09494972 0 -0.9595854 0.2814174 0 -0.9595846 0.2814207 0 -0.8890864 0.4577395 0 -0.8890857 0.457741 0 -0.8050694 0.5931808 0 -0.805069 0.5931813 0 -0.7221252 0.6917625 0 -0.7221248 0.6917629 0 -0.5799561 0.8146479 0 -0.3627386 0.931891 0 -0.3627391 0.9318909 0 -0.1234189 0.9923547 0 0 1 0 0.1234189 0.9923547 0 0.3627391 0.9318909 0 0.3627386 0.931891 0 0.5799561 0.8146479 0 0.5111502 0.4896582 -0.7063714 0.5111504 0.4896579 -0.7063713 0.5698606 0.419878 -0.706372 0.5698613 0.4198782 -0.7063714 0.6300999 0.3244041 -0.7055041 0.6301005 0.3244051 -0.7055032 0.6800642 0.1994429 -0.7055036 0.6800632 0.1994426 -0.7055045 0.7055048 0.06728899 -0.7055035 0.705505 0.06729024 -0.7055032 0.08760476 0.70439 -0.7043864 0.08760458 0.7043873 -0.7043892 0.2574776 0.6614703 -0.7043879 0.2574765 0.6614676 -0.704391 0.4116606 0.578248 -0.7043898 0.4116618 0.5782502 -0.7043873 0.7071077 0 -0.7071059 0 0.7071064 -0.7071072 0.7041367 -0.09157311 -0.704135 0.7041342 -0.09157931 -0.7041366 0.657289 -0.2686334 -0.7041359 0.6572903 -0.2686279 -0.7041367 -0.4116606 0.578248 -0.7043898 -0.4116615 0.5782499 -0.7043877 -0.2574771 0.661469 -0.7043894 -0.257477 0.6614689 -0.7043895 -0.08760476 0.70439 -0.7043864 -0.0876047 0.7043886 -0.7043878 0.6003445 -0.3741495 -0.706823 0.6003434 -0.3741486 -0.7068244 0.5685124 -0.4209442 -0.7068237 0.5685108 -0.4209436 -0.7068253 -0.5698615 0.4198777 -0.7063714 -0.5698606 0.4198786 -0.7063717 -0.5111502 0.4896582 -0.7063714 -0.5111503 0.4896578 -0.7063716 0.4997279 -0.5033825 -0.7048959 0.4997299 -0.5033856 -0.7048922 0.3758123 -0.6015722 -0.7048944 0.3758127 -0.601572 -0.7048944 0.2332262 -0.6698753 -0.704892 0.233224 -0.6698704 -0.7048973 0.07904952 -0.7048892 -0.7048989 0.07905149 -0.7048968 -0.7048911 -0.705505 0.06728899 -0.7055032 -0.7055045 0.06729018 -0.7055037 -0.680063 0.1994444 -0.7055043 -0.6800645 0.1994409 -0.7055038 -0.6301008 0.3244046 -0.7055032 -0.6300996 0.3244047 -0.7055042 0 -0.7071072 -0.7071065 -0.7071077 0 -0.7071059 -0.07905 -0.7048935 -0.7048946 -0.07905107 -0.7048931 -0.7048949 -0.2332264 -0.6698747 -0.7048925 -0.2332243 -0.6698727 -0.704895 -0.3758134 -0.601574 -0.7048923 -0.3758125 -0.6015717 -0.7048947 -0.499729 -0.5033848 -0.7048933 -0.4997289 -0.5033833 -0.7048946 -0.6572901 -0.2686311 -0.7041357 -0.657289 -0.2686306 -0.704137 -0.7041344 -0.09157562 -0.7041369 -0.7041369 -0.09157639 -0.7041344 -0.5685114 -0.4209434 -0.706825 -0.5685119 -0.4209443 -0.706824 -0.6003445 -0.3741495 -0.706823 -0.6003431 -0.3741484 -0.7068247 -0.108119 -0.994138 0 -0.3193014 -0.9476532 0 -0.3193014 -0.9476532 0 -0.5155538 -0.8568572 0 -0.6876999 -0.7259951 0 -0.6876996 -0.7259955 0 -0.8276886 -0.5611877 0 -0.8276894 -0.5611867 0 -0.9289767 -0.3701383 0 -0.928977 -0.3701377 0 -0.9868265 -0.1617824 0 -0.9868266 -0.1617817 0 -0.9985336 0.05413836 0 -0.9985334 0.05413907 0 -0.96355 0.2675283 0 -0.9635498 0.267529 0 -0.8835123 0.468408 0 -0.762162 0.6473865 0 -0.605174 0.7960932 0 -0.6051738 0.7960934 0 -0.4198896 0.9075753 0 -0.2149705 0.9766206 0 0.2149705 0.9766206 0 0.4198896 0.9075753 0 0.6051738 0.7960934 0 0.605174 0.7960932 0 0.762162 0.6473865 0 0.8835123 0.468408 0 0.9635498 0.267529 0 0.96355 0.2675283 0 0.9985334 0.05413907 0 0.9985336 0.05413836 0 0.9868266 -0.1617817 0 0.9868265 -0.1617824 0 0.928977 -0.3701377 0 0.9289767 -0.3701383 0 0.8276894 -0.5611867 0 0.8276886 -0.5611877 0 0.6876996 -0.7259955 0 0.6876999 -0.7259951 0 0.5155538 -0.8568572 0 0.3193014 -0.9476532 0 0.3193014 -0.9476532 0 0.108119 -0.994138 0 -0.2264446 -0.6720637 -0.7050201 -0.226441 -0.6720534 -0.705031 -0.365621 -0.607667 -0.7050263 -0.365625 -0.6076738 -0.7050184 -0.4877037 -0.5148619 -0.7050265 -0.4877066 -0.514866 -0.7050216 -0.5869801 -0.3979823 -0.7050279 -0.5869801 -0.3979825 -0.7050279 -0.6588143 -0.2624954 -0.7050248 -0.658812 -0.2624945 -0.7050273 -0.6998383 -0.1147326 -0.7050268 -0.6998426 -0.114733 -0.7050225 -0.7081443 0.03839409 -0.7050232 -0.7081435 0.03839427 -0.705024 -0.6833338 0.1897269 -0.7050239 -0.6833326 0.1897261 -0.7050252 -0.6265704 0.3321862 -0.7050262 -0.6265715 0.3321871 -0.7050248 -0.5405132 0.4591163 -0.7050232 -0.5405098 0.4591132 -0.7050279 -0.4291818 0.5645792 -0.7050202 -0.4291791 0.5645755 -0.7050248 -0.2977777 0.6436352 -0.7050264 -0.2977781 0.6436368 -0.7050247 -0.152453 0.6926008 -0.7050265 -0.1524543 0.6926086 -0.7050185 0 0.7091875 -0.7050201 0 0.7091891 -0.7050184 0.1524557 0.6926132 -0.7050137 0.1524516 0.6925963 -0.7050312 0.2977803 0.643641 -0.7050201 0.2977755 0.6436311 -0.705031 0.4291779 0.5645744 -0.7050264 0.429183 0.5645803 -0.7050186 0.5405133 0.4591163 -0.7050231 0.5405095 0.4591133 -0.705028 0.6265704 0.3321862 -0.7050262 0.6265715 0.3321871 -0.7050248 0.6833327 0.1897262 -0.7050251 0.6833337 0.1897268 -0.705024 0.7081434 0.03839397 -0.705024 0.7081443 0.03839439 -0.7050231 0.6998423 -0.1147332 -0.7050228 0.6998387 -0.1147325 -0.7050265 0.6588126 -0.2624949 -0.7050266 0.6588137 -0.262495 -0.7050255 0.5869789 -0.3979815 -0.7050296 0.5869801 -0.3979825 -0.7050279 0.4877035 -0.5148622 -0.7050264 0.4877069 -0.5148656 -0.7050216 0.365621 -0.607667 -0.7050263 0.365625 -0.6076738 -0.7050184 0.2264446 -0.6720637 -0.7050201 0.226441 -0.6720533 -0.705031 0.07667666 -0.7050302 -0.7050201 0.07667607 -0.7050255 -0.7050248 -0.07667666 -0.7050302 -0.7050201 -0.07667607 -0.7050255 -0.7050248 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 5 1 4 1 6 1 7 1 8 1 6 1 6 1 8 1 9 1 6 1 9 1 5 1 10 1 11 1 12 1 12 1 11 1 13 1 12 1 13 1 14 1 14 1 13 1 15 1 16 1 17 1 18 1 18 1 17 1 19 1 18 2 19 2 7 2 7 1 19 1 20 1 7 1 20 1 8 1 16 1 18 1 1 1 1 3 18 3 21 3 1 1 21 1 2 1 15 1 13 1 22 1 22 1 13 1 23 1 22 1 23 1 24 1 25 1 26 1 27 1 27 1 26 1 28 1 27 1 28 1 29 1 29 1 28 1 30 1 2 1 31 1 0 1 0 4 31 4 32 4 0 1 32 1 33 1 33 1 32 1 11 1 33 1 11 1 34 1 34 1 11 1 10 1 35 1 36 1 37 1 37 1 36 1 24 1 37 1 24 1 38 1 38 1 24 1 23 1 35 1 39 1 36 1 36 1 39 1 40 1 36 1 40 1 41 1 41 1 40 1 26 1 41 1 26 1 42 1 42 1 26 1 25 1 30 1 28 1 43 1 43 1 28 1 44 1 43 1 44 1 45 1 45 5 44 5 46 5 45 6 46 6 47 6 46 1 48 1 47 1 47 1 48 1 49 1 47 1 49 1 50 1 50 7 49 7 51 7 50 1 51 1 52 1 52 1 51 1 53 1 54 1 55 1 56 1 56 1 55 1 57 1 56 1 57 1 3 1 3 1 57 1 58 1 3 1 58 1 4 1 53 1 51 1 59 1 59 8 51 8 60 8 59 1 60 1 61 1 61 1 60 1 62 1 61 1 62 1 63 1 54 1 56 1 62 1 62 1 56 1 64 1 62 1 64 1 63 1 65 9 66 9 67 9 67 9 66 9 68 9 69 9 70 9 71 9 72 10 73 10 74 10 69 9 75 9 76 9 69 11 76 11 70 11 70 9 76 9 77 9 70 12 77 12 78 12 72 9 66 9 79 9 78 9 80 9 70 9 70 13 80 13 72 13 70 9 72 9 81 9 81 9 72 9 74 9 71 9 82 9 69 9 69 9 82 9 83 9 69 9 83 9 84 9 75 9 85 9 86 9 87 9 88 9 67 9 67 9 88 9 89 9 67 9 89 9 65 9 79 9 90 9 72 9 72 9 90 9 91 9 72 14 91 14 73 14 85 9 75 9 92 9 92 9 75 9 93 9 92 9 93 9 94 9 66 9 72 9 68 9 68 15 72 15 95 15 68 9 95 9 96 9 96 9 95 9 97 9 96 9 97 9 98 9 86 9 99 9 75 9 75 16 99 16 100 16 75 17 100 17 76 17 101 18 82 18 71 18 101 19 71 19 102 19 102 20 71 20 70 20 102 21 70 21 103 21 103 22 70 22 81 22 103 23 81 23 104 23 104 24 81 24 74 24 104 25 74 25 105 25 105 26 74 26 73 26 105 27 73 27 106 27 106 28 73 28 107 28 107 28 73 28 91 28 107 29 91 29 90 29 107 30 90 30 108 30 108 31 90 31 79 31 108 31 79 31 109 31 109 32 79 32 66 32 109 33 66 33 110 33 110 34 66 34 65 34 110 34 65 34 111 34 111 35 65 35 89 35 111 36 89 36 112 36 112 37 89 37 88 37 112 37 88 37 113 37 113 38 88 38 87 38 113 39 87 39 114 39 114 40 87 40 67 40 114 41 67 41 115 41 115 42 67 42 116 42 116 42 67 42 68 42 116 43 68 43 96 43 116 44 96 44 117 44 117 45 96 45 98 45 117 46 98 46 118 46 118 47 98 47 97 47 118 47 97 47 119 47 119 48 97 48 95 48 119 49 95 49 120 49 120 50 95 50 72 50 120 50 72 50 121 50 121 51 72 51 80 51 121 52 80 52 122 52 122 53 80 53 78 53 122 54 78 54 123 54 123 55 78 55 77 55 123 56 77 56 124 56 124 57 77 57 125 57 125 57 77 57 76 57 125 58 76 58 100 58 125 59 100 59 126 59 126 60 100 60 99 60 126 61 99 61 127 61 127 62 99 62 86 62 127 63 86 63 128 63 128 64 86 64 85 64 128 65 85 65 129 65 129 66 85 66 92 66 129 67 92 67 130 67 130 68 92 68 94 68 130 68 94 68 131 68 131 69 94 69 93 69 131 70 93 70 132 70 132 71 93 71 75 71 132 71 75 71 133 71 133 72 75 72 134 72 134 72 75 72 69 72 134 73 69 73 84 73 134 73 84 73 135 73 135 74 84 74 83 74 135 75 83 75 136 75 136 76 83 76 82 76 136 76 82 76 101 76 61 77 101 77 102 77 61 78 102 78 59 78 59 79 102 79 103 79 59 80 103 80 53 80 53 81 103 81 104 81 53 82 104 82 52 82 52 83 104 83 105 83 52 84 105 84 50 84 50 85 105 85 106 85 50 86 106 86 47 86 56 87 134 87 135 87 56 88 135 88 64 88 64 89 135 89 136 89 64 90 136 90 63 90 63 91 136 91 101 91 63 92 101 92 61 92 107 93 45 93 106 93 106 93 45 93 47 93 3 94 133 94 56 94 56 94 133 94 134 94 45 95 107 95 108 95 45 96 108 96 43 96 43 97 108 97 109 97 43 98 109 98 30 98 8 99 130 99 131 99 8 100 131 100 9 100 9 101 131 101 132 101 9 102 132 102 5 102 5 103 132 103 133 103 5 104 133 104 3 104 30 105 109 105 110 105 30 106 110 106 29 106 29 107 110 107 111 107 29 108 111 108 27 108 19 109 128 109 129 109 19 110 129 110 20 110 20 111 129 111 130 111 20 112 130 112 8 112 27 113 111 113 112 113 27 114 112 114 25 114 25 115 112 115 113 115 25 116 113 116 42 116 42 117 113 117 114 117 42 118 114 118 41 118 41 119 114 119 115 119 41 120 115 120 36 120 1 121 125 121 126 121 1 122 126 122 16 122 16 123 126 123 127 123 16 124 127 124 17 124 17 125 127 125 128 125 17 126 128 126 19 126 36 127 115 127 24 127 24 127 115 127 116 127 0 128 124 128 1 128 1 128 124 128 125 128 24 129 116 129 117 129 24 130 117 130 22 130 22 131 117 131 118 131 22 132 118 132 15 132 15 133 118 133 119 133 15 134 119 134 14 134 14 135 119 135 120 135 14 136 120 136 12 136 34 137 122 137 123 137 34 138 123 138 33 138 33 139 123 139 124 139 33 140 124 140 0 140 12 141 120 141 121 141 12 142 121 142 10 142 10 143 121 143 122 143 10 144 122 144 34 144 137 1 138 1 139 1 137 1 139 1 140 1 141 1 142 1 139 1 139 1 142 1 143 1 139 1 143 1 140 1 144 1 145 1 139 1 139 1 145 1 146 1 139 1 146 1 141 1 147 1 148 1 139 1 139 1 148 1 149 1 139 1 149 1 144 1 150 1 151 1 139 1 139 1 151 1 152 1 139 1 152 1 147 1 153 1 154 1 139 1 139 1 154 1 155 1 139 1 155 1 150 1 156 1 157 1 139 1 139 1 157 1 158 1 139 1 158 1 153 1 159 1 160 1 139 1 139 1 160 1 161 1 139 1 161 1 156 1 162 1 163 1 139 1 139 1 163 1 164 1 139 1 164 1 159 1 138 1 165 1 139 1 139 1 165 1 166 1 139 1 166 1 162 1 137 145 167 145 138 145 138 145 167 145 168 145 138 146 168 146 165 146 165 147 168 147 169 147 165 148 169 148 166 148 166 148 169 148 170 148 166 149 170 149 162 149 162 150 170 150 171 150 162 151 171 151 163 151 163 152 171 152 172 152 163 153 172 153 164 153 164 154 172 154 173 154 164 155 173 155 159 155 159 156 173 156 174 156 159 157 174 157 160 157 160 158 174 158 175 158 160 159 175 159 161 159 161 160 175 160 176 160 161 161 176 161 156 161 156 161 176 161 177 161 156 162 177 162 157 162 157 162 177 162 178 162 157 163 178 163 158 163 158 164 178 164 179 164 158 165 179 165 153 165 153 165 179 165 180 165 153 166 180 166 154 166 154 166 180 166 181 166 154 72 181 72 155 72 155 72 181 72 182 72 155 167 182 167 150 167 150 167 182 167 183 167 150 168 183 168 151 168 151 168 183 168 184 168 151 169 184 169 152 169 152 170 184 170 185 170 152 171 185 171 147 171 147 171 185 171 186 171 147 172 186 172 148 172 148 172 186 172 187 172 148 173 187 173 149 173 149 174 187 174 188 174 149 175 188 175 144 175 144 176 188 176 189 176 144 177 189 177 145 177 145 178 189 178 190 178 145 179 190 179 146 179 146 180 190 180 191 180 146 181 191 181 141 181 141 182 191 182 192 182 141 183 192 183 142 183 142 184 192 184 193 184 142 185 193 185 143 185 143 185 193 185 194 185 143 186 194 186 140 186 140 187 194 187 195 187 140 188 195 188 137 188 137 188 195 188 167 188 168 189 55 189 169 189 169 190 55 190 54 190 169 191 54 191 170 191 170 192 54 192 62 192 170 193 62 193 171 193 171 194 62 194 60 194 171 195 60 195 172 195 172 196 60 196 51 196 172 197 51 197 173 197 173 198 51 198 49 198 173 199 49 199 174 199 174 200 49 200 48 200 174 201 48 201 175 201 175 202 48 202 46 202 175 203 46 203 176 203 176 204 46 204 44 204 176 205 44 205 177 205 177 206 44 206 28 206 177 207 28 207 178 207 178 208 28 208 26 208 178 209 26 209 179 209 179 210 26 210 40 210 179 211 40 211 180 211 180 212 40 212 39 212 180 213 39 213 181 213 181 214 39 214 35 214 181 215 35 215 182 215 182 216 35 216 37 216 182 217 37 217 183 217 183 218 37 218 38 218 183 219 38 219 184 219 184 220 38 220 23 220 184 221 23 221 185 221 185 222 23 222 13 222 185 223 13 223 186 223 186 224 13 224 11 224 186 225 11 225 187 225 187 226 11 226 32 226 187 227 32 227 188 227 188 228 32 228 31 228 188 229 31 229 189 229 189 230 31 230 2 230 189 231 2 231 190 231 190 232 2 232 21 232 190 233 21 233 191 233 191 234 21 234 18 234 191 235 18 235 192 235 192 236 18 236 7 236 192 237 7 237 193 237 193 238 7 238 6 238 193 239 6 239 194 239 194 240 6 240 4 240 194 241 4 241 195 241 195 242 4 242 58 242 195 243 58 243 196 243 196 244 58 244 57 244 196 245 57 245 168 245 168 246 57 246 55 246

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_G4.dae b/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_G4.dae new file mode 100644 index 0000000..a6d8970 --- /dev/null +++ b/URDFs/sr_description/meshes/components/mounting_plate/mounting_plate_G4.dae @@ -0,0 +1,107 @@ + + + + + + Blender User + Blender 2.82.7 + + 2022-03-16T10:59:58 + 2022-03-16T10:59:58 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.80848 0.80848 0.80848 1 + + + 1 + + + + + + + + + + + + + + + + + -58.47636 -28.43613 -1 -58.47636 25.65426 -1 -31.80329 1.724324 -1 -32.11308 53.5 -1 -13.37347 28.90628 -1 -36.64468 52.9364 -1 -19.2748 25.35556 -1 -24.27486 20.61925 -1 -44.62028 48.63158 -1 -40.90018 51.27995 -1 -54.57127 -37.1211 -1 -26.3619 -17.87381 -1 -51.42906 -41.36486 -1 -21.90323 -23.12296 -1 -46.92084 -45.84035 -1 -41.53325 -49.20607 -1 -58.1428 29.15144 -1 -57.15417 32.52251 -1 -28.13986 14.91881 -1 -55.5461 35.64591 -1 -50.5023 42.49138 -1 -30.68907 8.520778 -1 -35.53397 -51.29479 -1 -16.42039 -27.2909 -1 -29.22106 -52.00276 -1 46.92084 -45.84035 -1 21.90323 -23.12296 -1 51.42906 -41.36486 -1 26.3619 -17.87381 -1 54.57127 -37.1211 -1 57.36417 -32.63973 -1 -31.43042 -5.152756 -1 -29.58791 -11.7889 -1 -58.1936 -30.61026 -1 -57.36417 -32.63973 -1 3.443591 -31.66329 -1 29.22106 -52.00276 -1 -3.443591 -31.66329 -1 -10.16975 -30.18276 -1 10.16975 -30.18276 -1 16.42039 -27.2909 -1 35.53397 -51.29479 -1 41.53325 -49.20607 -1 58.1936 -30.61026 -1 29.58791 -11.7889 -1 58.47636 -28.43613 -1 31.43042 -5.152756 -1 58.47636 25.65426 -1 31.80329 1.724324 -1 30.68907 8.520778 -1 58.1428 29.15144 -1 28.13986 14.91881 -1 57.15417 32.52251 -1 55.5461 35.64591 -1 13.37347 28.90628 -1 6.846808 31.10536 -1 32.11308 53.5 -1 0 31.85 -1 -6.846808 31.10536 -1 50.5023 42.49138 -1 24.27486 20.61925 -1 44.62028 48.63158 -1 19.2748 25.35556 -1 40.90018 51.27995 -1 36.64468 52.9364 -1 52.5979 -42.30497 5 55.81153 -37.96477 5 29.22106 -53.50276 5 -29.22106 -53.50276 5 32.11308 55 5 56.80851 36.45605 5 51.65008 43.45709 5 -55.81153 -37.96477 5 59.97636 25.65426 5 59.61576 29.43499 5 -32.11308 55 5 -59.97636 25.65426 5 -59.97636 -28.43613 5 -59.64371 -30.99393 5 58.6679 -33.38155 5 -58.6679 -33.38155 5 58.54696 33.07939 5 45.63438 49.73684 5 41.61265 52.59995 5 37.01211 54.39071 5 -51.65008 43.45709 5 -56.80851 36.45605 5 35.86623 -52.75754 5 42.18126 -50.55887 5 47.8524 -47.01601 5 59.64371 -30.99393 5 59.97636 -28.43613 5 -45.63438 49.73684 5 -37.01211 54.39071 5 -41.61265 52.59995 5 -52.5979 -42.30497 5 -35.86623 -52.75754 5 -47.8524 -47.01601 5 -42.18126 -50.55887 5 -58.54696 33.07939 5 -59.61576 29.43499 5 45.63438 49.73684 0.5 51.65008 43.45709 0.5 56.80851 36.45605 0.5 58.54696 33.07939 0.5 59.61576 29.43499 0.5 59.97636 25.65426 0.5 59.97636 -28.43613 0.5 59.64371 -30.99393 0.5 58.6679 -33.38155 0.5 55.81153 -37.96477 0.5 52.5979 -42.30497 0.5 47.8524 -47.01601 0.5 42.18126 -50.55887 0.5 35.86623 -52.75754 0.5 29.22106 -53.50276 0.5 -29.22106 -53.50276 0.5 -35.86623 -52.75754 0.5 -42.18126 -50.55887 0.5 -47.8524 -47.01601 0.5 -52.5979 -42.30497 0.5 -55.81153 -37.96477 0.5 -58.6679 -33.38155 0.5 -59.64371 -30.99393 0.5 -59.97636 -28.43613 0.5 -59.97636 25.65426 0.5 -59.61576 29.43499 0.5 -58.54696 33.07939 0.5 -56.80851 36.45605 0.5 -51.65008 43.45709 0.5 -45.63438 49.73684 0.5 -41.61265 52.59995 0.5 -37.01211 54.39071 0.5 -32.11308 55 0.5 32.11308 55 0.5 37.01211 54.39071 0.5 41.61265 52.59995 0.5 0 31.6 0 6.793066 30.86121 0 0 3.0287e-7 0 -6.793066 30.86121 0 -24.08432 20.45741 0 -19.12351 25.15654 0 -13.2685 28.67938 0 -31.55366 1.71079 0 -30.44818 8.453896 0 -27.91898 14.80171 0 -26.15497 -17.73351 0 -29.35566 -11.69637 0 -31.18372 -5.11231 0 -10.08993 -29.94584 0 -16.2915 -27.07669 0 -21.7313 -22.94146 0 10.08993 -29.94584 0 3.416561 -31.41476 0 -3.416561 -31.41476 0 26.15497 -17.73351 0 21.7313 -22.94146 0 16.2915 -27.07669 0 31.55366 1.71079 0 31.18372 -5.11231 0 29.35566 -11.69637 0 24.08432 20.45741 0 27.91898 14.80171 0 30.44818 8.453896 0 13.2685 28.67938 0 19.12351 25.15654 0 0 31.6 -0.75 6.793066 30.86121 -0.75 13.2685 28.67938 -0.75 19.12351 25.15654 -0.75 24.08432 20.45741 -0.75 27.91898 14.80171 -0.75 30.44818 8.453896 -0.75 31.55366 1.71079 -0.75 31.18372 -5.11231 -0.75 29.35566 -11.69637 -0.75 26.15497 -17.73351 -0.75 21.7313 -22.94146 -0.75 16.2915 -27.07669 -0.75 10.08993 -29.94584 -0.75 3.416561 -31.41476 -0.75 -3.416561 -31.41476 -0.75 -10.08993 -29.94584 -0.75 -16.2915 -27.07669 -0.75 -21.7313 -22.94146 -0.75 -26.15497 -17.73351 -0.75 -29.35566 -11.69637 -0.75 -31.18372 -5.11231 -0.75 -31.55366 1.71079 -0.75 -30.44818 8.453896 -0.75 -27.91898 14.80171 -0.75 -24.08432 20.45741 -0.75 -19.12351 25.15654 -0.75 -13.2685 28.67938 -0.75 -6.793066 30.86121 -0.75 0 31.6 -0.75 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 -1.24202e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.7221248 0.6917629 0 0.7221252 0.6917625 0 0.805069 0.5931813 0 0.8050694 0.5931808 0 0.8890857 0.457741 0 0.8890864 0.4577395 0 0.9595845 0.2814207 0 0.9595856 0.2814174 0 0.9954821 0.09494972 0 0.9954825 0.0949462 0 1 0 0 0.9916493 -0.1289642 0 0.9916486 -0.1289694 0 0.9256745 -0.3783209 0 0.8486757 -0.5289137 0 0.8486751 -0.5289146 0 0.8036763 -0.5950668 0 0.7045252 -0.7096791 0 0.7045257 -0.7096785 0 0.5298262 -0.8481063 0 0.3288049 -0.9443979 0 0.3288056 -0.9443977 0 0.1114459 -0.9937705 0 0.111446 -0.9937705 0 0 -1 0 -0.111446 -0.9937705 0 -0.1114459 -0.9937705 0 -0.3288056 -0.9443977 0 -0.3288049 -0.9443979 0 -0.5298262 -0.8481063 0 -0.7045257 -0.7096785 0 -0.7045252 -0.7096791 0 -0.8036763 -0.5950668 0 -0.8486739 -0.5289164 0 -0.8486757 -0.5289137 0 -0.9256745 -0.3783209 0 -0.9256764 -0.3783165 0 -0.9916486 -0.1289694 0 -0.9916493 -0.1289642 0 -1 0 0 -0.9954825 0.0949462 0 -0.9954822 0.09494972 0 -0.9595854 0.2814174 0 -0.9595846 0.2814207 0 -0.8890864 0.4577395 0 -0.8890857 0.457741 0 -0.8050694 0.5931808 0 -0.805069 0.5931813 0 -0.7221252 0.6917625 0 -0.7221248 0.6917629 0 -0.5799561 0.8146479 0 -0.3627386 0.931891 0 -0.3627391 0.9318909 0 -0.1234189 0.9923547 0 0 1 0 0.1234189 0.9923547 0 0.3627391 0.9318909 0 0.3627386 0.931891 0 0.5799561 0.8146479 0 0.5111502 0.4896582 -0.7063714 0.5111504 0.4896579 -0.7063713 0.5698606 0.419878 -0.706372 0.5698613 0.4198782 -0.7063714 0.6300999 0.3244041 -0.7055041 0.6301005 0.3244051 -0.7055032 0.6800642 0.1994429 -0.7055036 0.6800632 0.1994426 -0.7055045 0.7055048 0.06728899 -0.7055035 0.705505 0.06729024 -0.7055032 0.08760476 0.70439 -0.7043864 0.08760458 0.7043873 -0.7043892 0.2574776 0.6614703 -0.7043879 0.2574765 0.6614676 -0.704391 0.4116606 0.578248 -0.7043898 0.4116618 0.5782502 -0.7043873 0.7071077 0 -0.7071059 0 0.7071064 -0.7071072 0.7041367 -0.09157311 -0.704135 0.7041342 -0.09157931 -0.7041366 0.657289 -0.2686334 -0.7041359 0.6572903 -0.2686279 -0.7041367 -0.4116606 0.578248 -0.7043898 -0.4116615 0.5782499 -0.7043877 -0.2574771 0.661469 -0.7043894 -0.257477 0.6614689 -0.7043895 -0.08760476 0.70439 -0.7043864 -0.0876047 0.7043886 -0.7043878 0.6003445 -0.3741495 -0.706823 0.6003434 -0.3741486 -0.7068244 0.5685124 -0.4209442 -0.7068237 0.5685108 -0.4209436 -0.7068253 -0.5698615 0.4198777 -0.7063714 -0.5698606 0.4198786 -0.7063717 -0.5111502 0.4896582 -0.7063714 -0.5111503 0.4896578 -0.7063716 0.4997279 -0.5033825 -0.7048959 0.4997299 -0.5033856 -0.7048922 0.3758123 -0.6015722 -0.7048944 0.3758127 -0.601572 -0.7048944 0.2332262 -0.6698753 -0.704892 0.233224 -0.6698704 -0.7048973 0.07904952 -0.7048892 -0.7048989 0.07905149 -0.7048968 -0.7048911 -0.705505 0.06728899 -0.7055032 -0.7055045 0.06729018 -0.7055037 -0.680063 0.1994444 -0.7055043 -0.6800645 0.1994409 -0.7055038 -0.6301008 0.3244046 -0.7055032 -0.6300996 0.3244047 -0.7055042 0 -0.7071072 -0.7071065 -0.7071077 0 -0.7071059 -0.07905 -0.7048935 -0.7048946 -0.07905107 -0.7048931 -0.7048949 -0.2332264 -0.6698747 -0.7048925 -0.2332243 -0.6698727 -0.704895 -0.3758134 -0.601574 -0.7048923 -0.3758125 -0.6015717 -0.7048947 -0.499729 -0.5033848 -0.7048933 -0.4997289 -0.5033833 -0.7048946 -0.6572901 -0.2686311 -0.7041357 -0.657289 -0.2686306 -0.704137 -0.7041344 -0.09157562 -0.7041369 -0.7041369 -0.09157639 -0.7041344 -0.5685114 -0.4209434 -0.706825 -0.5685119 -0.4209443 -0.706824 -0.6003445 -0.3741495 -0.706823 -0.6003431 -0.3741484 -0.7068247 -0.108119 -0.994138 0 -0.3193014 -0.9476532 0 -0.3193014 -0.9476532 0 -0.5155538 -0.8568572 0 -0.6876999 -0.7259951 0 -0.6876996 -0.7259955 0 -0.8276886 -0.5611877 0 -0.8276894 -0.5611867 0 -0.9289767 -0.3701383 0 -0.928977 -0.3701377 0 -0.9868265 -0.1617824 0 -0.9868266 -0.1617817 0 -0.9985336 0.05413836 0 -0.9985334 0.05413907 0 -0.96355 0.2675283 0 -0.9635498 0.267529 0 -0.8835123 0.468408 0 -0.762162 0.6473865 0 -0.605174 0.7960932 0 -0.6051738 0.7960934 0 -0.4198896 0.9075753 0 -0.2149705 0.9766206 0 0.2149705 0.9766206 0 0.4198896 0.9075753 0 0.6051738 0.7960934 0 0.605174 0.7960932 0 0.762162 0.6473865 0 0.8835123 0.468408 0 0.9635498 0.267529 0 0.96355 0.2675283 0 0.9985334 0.05413907 0 0.9985336 0.05413836 0 0.9868266 -0.1617817 0 0.9868265 -0.1617824 0 0.928977 -0.3701377 0 0.9289767 -0.3701383 0 0.8276894 -0.5611867 0 0.8276886 -0.5611877 0 0.6876996 -0.7259955 0 0.6876999 -0.7259951 0 0.5155538 -0.8568572 0 0.3193014 -0.9476532 0 0.3193014 -0.9476532 0 0.108119 -0.994138 0 -0.2264446 -0.6720637 -0.7050201 -0.226441 -0.6720534 -0.705031 -0.365621 -0.607667 -0.7050263 -0.365625 -0.6076738 -0.7050184 -0.4877037 -0.5148619 -0.7050265 -0.4877066 -0.514866 -0.7050216 -0.5869801 -0.3979823 -0.7050279 -0.5869801 -0.3979825 -0.7050279 -0.6588143 -0.2624954 -0.7050248 -0.658812 -0.2624945 -0.7050273 -0.6998383 -0.1147326 -0.7050268 -0.6998426 -0.114733 -0.7050225 -0.7081443 0.03839409 -0.7050232 -0.7081435 0.03839427 -0.705024 -0.6833338 0.1897269 -0.7050239 -0.6833326 0.1897261 -0.7050252 -0.6265704 0.3321862 -0.7050262 -0.6265715 0.3321871 -0.7050248 -0.5405132 0.4591163 -0.7050232 -0.5405098 0.4591132 -0.7050279 -0.4291818 0.5645792 -0.7050202 -0.4291791 0.5645755 -0.7050248 -0.2977777 0.6436352 -0.7050264 -0.2977781 0.6436368 -0.7050247 -0.152453 0.6926008 -0.7050265 -0.1524543 0.6926086 -0.7050185 0 0.7091875 -0.7050201 0 0.7091891 -0.7050184 0.1524557 0.6926132 -0.7050137 0.1524516 0.6925963 -0.7050312 0.2977803 0.643641 -0.7050201 0.2977755 0.6436311 -0.705031 0.4291779 0.5645744 -0.7050264 0.429183 0.5645803 -0.7050186 0.5405133 0.4591163 -0.7050231 0.5405095 0.4591133 -0.705028 0.6265704 0.3321862 -0.7050262 0.6265715 0.3321871 -0.7050248 0.6833327 0.1897262 -0.7050251 0.6833337 0.1897268 -0.705024 0.7081434 0.03839397 -0.705024 0.7081443 0.03839439 -0.7050231 0.6998423 -0.1147332 -0.7050228 0.6998387 -0.1147325 -0.7050265 0.6588126 -0.2624949 -0.7050266 0.6588137 -0.262495 -0.7050255 0.5869789 -0.3979815 -0.7050296 0.5869801 -0.3979825 -0.7050279 0.4877035 -0.5148622 -0.7050264 0.4877069 -0.5148656 -0.7050216 0.365621 -0.607667 -0.7050263 0.365625 -0.6076738 -0.7050184 0.2264446 -0.6720637 -0.7050201 0.226441 -0.6720533 -0.705031 0.07667666 -0.7050302 -0.7050201 0.07667607 -0.7050255 -0.7050248 -0.07667666 -0.7050302 -0.7050201 -0.07667607 -0.7050255 -0.7050248 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 5 1 4 1 6 1 7 1 8 1 6 1 6 1 8 1 9 1 6 1 9 1 5 1 10 1 11 1 12 1 12 1 11 1 13 1 12 1 13 1 14 1 14 1 13 1 15 1 16 1 17 1 18 1 18 1 17 1 19 1 18 2 19 2 7 2 7 1 19 1 20 1 7 1 20 1 8 1 16 1 18 1 1 1 1 3 18 3 21 3 1 1 21 1 2 1 15 1 13 1 22 1 22 1 13 1 23 1 22 1 23 1 24 1 25 1 26 1 27 1 27 1 26 1 28 1 27 1 28 1 29 1 29 1 28 1 30 1 2 1 31 1 0 1 0 4 31 4 32 4 0 1 32 1 33 1 33 1 32 1 11 1 33 1 11 1 34 1 34 1 11 1 10 1 35 1 36 1 37 1 37 1 36 1 24 1 37 1 24 1 38 1 38 1 24 1 23 1 35 1 39 1 36 1 36 1 39 1 40 1 36 1 40 1 41 1 41 1 40 1 26 1 41 1 26 1 42 1 42 1 26 1 25 1 30 1 28 1 43 1 43 1 28 1 44 1 43 1 44 1 45 1 45 5 44 5 46 5 45 6 46 6 47 6 46 1 48 1 47 1 47 1 48 1 49 1 47 1 49 1 50 1 50 7 49 7 51 7 50 1 51 1 52 1 52 1 51 1 53 1 54 1 55 1 56 1 56 1 55 1 57 1 56 1 57 1 3 1 3 1 57 1 58 1 3 1 58 1 4 1 53 1 51 1 59 1 59 8 51 8 60 8 59 1 60 1 61 1 61 1 60 1 62 1 61 1 62 1 63 1 54 1 56 1 62 1 62 1 56 1 64 1 62 1 64 1 63 1 65 9 66 9 67 9 67 9 66 9 68 9 69 9 70 9 71 9 72 10 73 10 74 10 69 9 75 9 76 9 69 11 76 11 70 11 70 9 76 9 77 9 70 12 77 12 78 12 72 9 66 9 79 9 78 9 80 9 70 9 70 13 80 13 72 13 70 9 72 9 81 9 81 9 72 9 74 9 71 9 82 9 69 9 69 9 82 9 83 9 69 9 83 9 84 9 75 9 85 9 86 9 87 9 88 9 67 9 67 9 88 9 89 9 67 9 89 9 65 9 79 9 90 9 72 9 72 9 90 9 91 9 72 14 91 14 73 14 85 9 75 9 92 9 92 9 75 9 93 9 92 9 93 9 94 9 66 9 72 9 68 9 68 15 72 15 95 15 68 9 95 9 96 9 96 9 95 9 97 9 96 9 97 9 98 9 86 9 99 9 75 9 75 16 99 16 100 16 75 17 100 17 76 17 101 18 82 18 71 18 101 19 71 19 102 19 102 20 71 20 70 20 102 21 70 21 103 21 103 22 70 22 81 22 103 23 81 23 104 23 104 24 81 24 74 24 104 25 74 25 105 25 105 26 74 26 73 26 105 27 73 27 106 27 106 28 73 28 107 28 107 28 73 28 91 28 107 29 91 29 90 29 107 30 90 30 108 30 108 31 90 31 79 31 108 31 79 31 109 31 109 32 79 32 66 32 109 33 66 33 110 33 110 34 66 34 65 34 110 34 65 34 111 34 111 35 65 35 89 35 111 36 89 36 112 36 112 37 89 37 88 37 112 37 88 37 113 37 113 38 88 38 87 38 113 39 87 39 114 39 114 40 87 40 67 40 114 41 67 41 115 41 115 42 67 42 116 42 116 42 67 42 68 42 116 43 68 43 96 43 116 44 96 44 117 44 117 45 96 45 98 45 117 46 98 46 118 46 118 47 98 47 97 47 118 47 97 47 119 47 119 48 97 48 95 48 119 49 95 49 120 49 120 50 95 50 72 50 120 50 72 50 121 50 121 51 72 51 80 51 121 52 80 52 122 52 122 53 80 53 78 53 122 54 78 54 123 54 123 55 78 55 77 55 123 56 77 56 124 56 124 57 77 57 125 57 125 57 77 57 76 57 125 58 76 58 100 58 125 59 100 59 126 59 126 60 100 60 99 60 126 61 99 61 127 61 127 62 99 62 86 62 127 63 86 63 128 63 128 64 86 64 85 64 128 65 85 65 129 65 129 66 85 66 92 66 129 67 92 67 130 67 130 68 92 68 94 68 130 68 94 68 131 68 131 69 94 69 93 69 131 70 93 70 132 70 132 71 93 71 75 71 132 71 75 71 133 71 133 72 75 72 134 72 134 72 75 72 69 72 134 73 69 73 84 73 134 73 84 73 135 73 135 74 84 74 83 74 135 75 83 75 136 75 136 76 83 76 82 76 136 76 82 76 101 76 61 77 101 77 102 77 61 78 102 78 59 78 59 79 102 79 103 79 59 80 103 80 53 80 53 81 103 81 104 81 53 82 104 82 52 82 52 83 104 83 105 83 52 84 105 84 50 84 50 85 105 85 106 85 50 86 106 86 47 86 56 87 134 87 135 87 56 88 135 88 64 88 64 89 135 89 136 89 64 90 136 90 63 90 63 91 136 91 101 91 63 92 101 92 61 92 107 93 45 93 106 93 106 93 45 93 47 93 3 94 133 94 56 94 56 94 133 94 134 94 45 95 107 95 108 95 45 96 108 96 43 96 43 97 108 97 109 97 43 98 109 98 30 98 8 99 130 99 131 99 8 100 131 100 9 100 9 101 131 101 132 101 9 102 132 102 5 102 5 103 132 103 133 103 5 104 133 104 3 104 30 105 109 105 110 105 30 106 110 106 29 106 29 107 110 107 111 107 29 108 111 108 27 108 19 109 128 109 129 109 19 110 129 110 20 110 20 111 129 111 130 111 20 112 130 112 8 112 27 113 111 113 112 113 27 114 112 114 25 114 25 115 112 115 113 115 25 116 113 116 42 116 42 117 113 117 114 117 42 118 114 118 41 118 41 119 114 119 115 119 41 120 115 120 36 120 1 121 125 121 126 121 1 122 126 122 16 122 16 123 126 123 127 123 16 124 127 124 17 124 17 125 127 125 128 125 17 126 128 126 19 126 36 127 115 127 24 127 24 127 115 127 116 127 0 128 124 128 1 128 1 128 124 128 125 128 24 129 116 129 117 129 24 130 117 130 22 130 22 131 117 131 118 131 22 132 118 132 15 132 15 133 118 133 119 133 15 134 119 134 14 134 14 135 119 135 120 135 14 136 120 136 12 136 34 137 122 137 123 137 34 138 123 138 33 138 33 139 123 139 124 139 33 140 124 140 0 140 12 141 120 141 121 141 12 142 121 142 10 142 10 143 121 143 122 143 10 144 122 144 34 144 137 1 138 1 139 1 137 1 139 1 140 1 141 1 142 1 139 1 139 1 142 1 143 1 139 1 143 1 140 1 144 1 145 1 139 1 139 1 145 1 146 1 139 1 146 1 141 1 147 1 148 1 139 1 139 1 148 1 149 1 139 1 149 1 144 1 150 1 151 1 139 1 139 1 151 1 152 1 139 1 152 1 147 1 153 1 154 1 139 1 139 1 154 1 155 1 139 1 155 1 150 1 156 1 157 1 139 1 139 1 157 1 158 1 139 1 158 1 153 1 159 1 160 1 139 1 139 1 160 1 161 1 139 1 161 1 156 1 162 1 163 1 139 1 139 1 163 1 164 1 139 1 164 1 159 1 138 1 165 1 139 1 139 1 165 1 166 1 139 1 166 1 162 1 137 145 167 145 138 145 138 145 167 145 168 145 138 146 168 146 165 146 165 147 168 147 169 147 165 148 169 148 166 148 166 148 169 148 170 148 166 149 170 149 162 149 162 150 170 150 171 150 162 151 171 151 163 151 163 152 171 152 172 152 163 153 172 153 164 153 164 154 172 154 173 154 164 155 173 155 159 155 159 156 173 156 174 156 159 157 174 157 160 157 160 158 174 158 175 158 160 159 175 159 161 159 161 160 175 160 176 160 161 161 176 161 156 161 156 161 176 161 177 161 156 162 177 162 157 162 157 162 177 162 178 162 157 163 178 163 158 163 158 164 178 164 179 164 158 165 179 165 153 165 153 165 179 165 180 165 153 166 180 166 154 166 154 166 180 166 181 166 154 72 181 72 155 72 155 72 181 72 182 72 155 167 182 167 150 167 150 167 182 167 183 167 150 168 183 168 151 168 151 168 183 168 184 168 151 169 184 169 152 169 152 170 184 170 185 170 152 171 185 171 147 171 147 171 185 171 186 171 147 172 186 172 148 172 148 172 186 172 187 172 148 173 187 173 149 173 149 174 187 174 188 174 149 175 188 175 144 175 144 176 188 176 189 176 144 177 189 177 145 177 145 178 189 178 190 178 145 179 190 179 146 179 146 180 190 180 191 180 146 181 191 181 141 181 141 182 191 182 192 182 141 183 192 183 142 183 142 184 192 184 193 184 142 185 193 185 143 185 143 185 193 185 194 185 143 186 194 186 140 186 140 187 194 187 195 187 140 188 195 188 137 188 137 188 195 188 167 188 168 189 55 189 169 189 169 190 55 190 54 190 169 191 54 191 170 191 170 192 54 192 62 192 170 193 62 193 171 193 171 194 62 194 60 194 171 195 60 195 172 195 172 196 60 196 51 196 172 197 51 197 173 197 173 198 51 198 49 198 173 199 49 199 174 199 174 200 49 200 48 200 174 201 48 201 175 201 175 202 48 202 46 202 175 203 46 203 176 203 176 204 46 204 44 204 176 205 44 205 177 205 177 206 44 206 28 206 177 207 28 207 178 207 178 208 28 208 26 208 178 209 26 209 179 209 179 210 26 210 40 210 179 211 40 211 180 211 180 212 40 212 39 212 180 213 39 213 181 213 181 214 39 214 35 214 181 215 35 215 182 215 182 216 35 216 37 216 182 217 37 217 183 217 183 218 37 218 38 218 183 219 38 219 184 219 184 220 38 220 23 220 184 221 23 221 185 221 185 222 23 222 13 222 185 223 13 223 186 223 186 224 13 224 11 224 186 225 11 225 187 225 187 226 11 226 32 226 187 227 32 227 188 227 188 228 32 228 31 228 188 229 31 229 189 229 189 230 31 230 2 230 189 231 2 231 190 231 190 232 2 232 21 232 190 233 21 233 191 233 191 234 21 234 18 234 191 235 18 235 192 235 192 236 18 236 7 236 192 237 7 237 193 237 193 238 7 238 6 238 193 239 6 239 194 239 194 240 6 240 4 240 194 241 4 241 195 241 195 242 4 242 58 242 195 243 58 243 196 243 196 244 58 244 57 244 196 245 57 245 168 245 168 246 57 246 55 246

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/palm/palm_C6M2.dae b/URDFs/sr_description/meshes/components/palm/palm_C6M2.dae new file mode 100644 index 0000000..c9453f9 --- /dev/null +++ b/URDFs/sr_description/meshes/components/palm/palm_C6M2.dae @@ -0,0 +1,132 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:41:20 + 2022-02-10T09:41:20 + + Z_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.31886 3.11933 88.42472 -2.31886 5.63812 90.39955 -2.86901 3.312 88.37461 -2.86901 5.74386 90.32435 -1.99945 5.53833 89.58848 -1.99944 4.28706 88.5514 -4.23984 10.89921 90.28441 -4.50802 10.95645 89.19076 -6.2616 11.1753 88.8843 -5.23617 7.94142 90.03388 -6.04362 7.94142 89.22799 -4.23845 5.63631 88.40637 -3.48421 10.27552 97.62239 -3.92405 9.96326 98.56784 -2.62062 9.46742 96.43927 -4.00144 10.43204 98.33806 -3.42962 8.64119 95.29342 -2.77315 8.93963 95.8138 -3.29574 9.2523 97.00844 -2.62016 8.73646 95.12654 -4.25756 11.04698 96.20256 -4.15142 11.04698 95.04393 -5.75123 11.49697 95.45497 -5.99619 11.49697 96.64929 -4.60233 11.04699 97.44501 -6.50894 11.49697 97.75499 -5.2387 11.04699 98.70365 -2.4043 8.83116 95.13356 -2.78691 9.19201 96.43332 -2.25253 9.009302 95.10453 -2.19861 9.23126 95.04592 -2.72672 9.94482 96.26662 -2.2479 9.44767 94.97078 -5.28283 10.68463 99.7013 -5.9089 10.75973 100.2209 -5.71777 10.27446 100.3477 -6.03239 9.87593 100.1751 -5.43032 9.8037 99.67538 -4.79349 9.69696 99.05484 -4.62052 10.57362 99.05593 -4.19838 9.560872 98.36477 -3.70107 9.41038 97.67668 -3.06268 10.11112 96.92743 -2.72672 10.02494 95.04329 -4.08456 8.54095 95.21244 -7.70988 9.10508 98.62049 -6.18704 11.04698 99.873 -2.72672 9.955222 93.81955 -3.31068 10.4765 94.44256 -4.62794 7.94142 90.84272 -4.18119 7.94142 91.62484 -3.86182 7.94142 92.36641 -3.64156 7.94142 93.06499 -2.86899 7.19214 93.23298 -1.99944 7.99697 92.1724 -1.99944 7.30184 92.4242 -1.99944 6.94656 91.57982 -1.99944 6.38827 90.62459 -1.99944 8.25571 93.05318 -1.99944 7.51917 93.15264 -3.96819 10.81415 91.43007 -6.88093 11.39697 89.68384 -5.65019 11.34554 91.02043 -4.49718 11.01932 91.70684 -3.71003 10.70574 92.56484 -4.65287 11.17864 92.9042 -5.12373 11.27726 91.90458 -3.48535 10.58686 93.59964 -4.22323 11.04697 94.01065 -2.44319 8.56278 94.71521 -3.05339 8.50667 94.93193 -2.66969 8.34255 94.60556 -2.07694 8.79775 92.93055 -2.25794 9.21523 92.83738 -2.50042 9.656762 93.29489 -2.19144 9.3299 94.73648 -2.19702 7.58718 93.89461 -2.00608 7.87464 93.62246 -2.32404 7.07942 93.26065 -5.97059 11.49697 93.17299 -5.78696 11.49697 94.23915 -6.20346 11.49697 92.22731 -6.87369 8.496972 90.33946 -6.23881 8.496972 90.99005 -5.75942 8.496972 91.64044 -5.40616 8.496972 92.26857 -5.15264 8.496972 92.86425 -4.97702 8.496972 93.42589 -2.0713 8.649621 92.46511 -3.27289 7.83903 94.26452 -3.50552 7.94157 93.72605 -2.62331 7.53031 93.96105 -2.30936 8.16196 94.33181 -4.41073 8.496972 95.04093 -4.62775 8.49544 94.56347 -4.86253 8.496972 93.95772 -2.2273 8.656372 94.6345 -2.05462 8.88449 94.20365 -2.00608 8.38057 93.92615 -2.01864 8.653962 94.05004 -2.00608 8.3286 93.39334 -18.41133 1.43357 87.00081 -19.12988 1.27291 87.70231 -19.12988 -0.003029882 87.59163 -18.84514 -0.003029882 87.29075 -18.54927 -0.003029882 87.00081 -19.12988 2.37195 87.98259 -18.00349 2.81535 87.00081 -17.3473 4.08411 87.00081 -18.66365 4.10292 88.26278 -19.12988 4.09936 88.83101 -16.49944 5.99697 87.00081 -17.8421 6.16047 88.98506 -15.99944 6.96932 88.11705 -15.99944 7.74294 89.00081 -16.49944 7.94142 89.74383 -9.94944 7.47344 87.00081 -8.57618 7.14735 87.00081 -9.94944 7.94142 87.46534 -8.391242 7.94142 87.85357 -7.30655 6.582 87.00083 -7.08771 7.94142 88.47516 -6.1286 5.76542 87.00083 -5.04713 4.64133 87.00083 -4.06877 2.916 87.00083 -3.63364 1.65375 87.00083 -3.44961 -0.003029882 87.00083 -3.15375 -0.003029882 87.29077 -2.86901 -0.003029882 87.59163 -2.86901 1.2735 87.70243 -2.86901 2.37288 87.98291 -15.99944 8.496972 87.00081 -12.03442 8.496972 87.00081 -15.99944 8.496972 89.00081 -4.76363 10.98769 88.17483 -4.99944 10.99697 87.25485 -13.90792 11.39697 88.93673 -16.99944 10.99697 87.25485 -15.73728 11.26217 88.8843 -15.16828 10.99697 86.13398 -12.50619 11.39697 88.44628 -13.13533 10.99697 85.43849 -10.99994 11.39697 88.27532 -10.99945 10.99697 85.20285 -9.49355 11.39697 88.44607 -8.863592 10.99697 85.43849 -6.83064 10.99697 86.13395 -8.09143 11.39697 88.9365 -17.23631 10.9876 88.179 -17.4921 10.95624 89.19575 -19.68002 3.11935 88.42472 -19.99944 4.28585 88.55059 -19.99944 2.47985 87.66356 -19.56388 -0.003029882 87.75068 -19.99944 1.33074 87.37055 -19.99944 -0.003029882 87.25485 -19.94282 -0.003029882 87.48596 -19.78578 -0.003029882 87.66474 -19.3274 -0.003029882 87.72432 -1.99945 1.33136 87.37066 -2.435 -0.003029882 87.75068 -2.2131 -0.003029882 87.66474 -2.05606 -0.003029882 87.48597 -1.99944 -0.003029882 87.25486 -1.99945 2.48084 87.6639 -2.67149 -0.003029882 87.72432 -10.99943 11.49528 88.98594 -9.94944 8.496972 88.86506 -8.718502 8.496972 89.20881 -9.96445 8.496972 87.00081 -19.12987 -8.00303 87.59163 -18.90861 -9.0346 87.35697 -18.36907 -9.82743 86.83525 -18.54927 -4.00303 87.00083 -17.61403 -10.3084 86.21868 -16.91593 -4.00303 85.72747 -16.73857 -10.50303 85.61666 -15.6181 -10.50303 85.01744 -15.88833 -9.00303 85.14695 -15.52103 -9.4878 84.9731 -15.88833 -6.00303 85.14695 -15.41294 -5.67444 84.92507 -15.07323 -5.46536 84.78298 -15.06578 -4.00303 84.78002 -14.74852 -5.29607 84.65947 -15.0433 -10.02226 84.77111 -14.44095 -10.49866 84.5542 -14.27803 -5.11393 84.50078 -13.5644 -5.00303 84.30406 -13.06992 -4.00303 84.19744 -11.8618 -5.00303 84.03469 -10.99943 -4.00303 84.00083 -10.13707 -5.00303 84.03469 -8.92895 -4.00303 84.19744 -8.434472 -5.00303 84.30406 -7.75159 -5.10488 84.49124 -7.14236 -5.34857 84.69922 -6.9331 -4.00303 84.78002 -6.60089 -5.66467 84.91852 -5.26031 -10.50303 85.61666 -6.11055 -6.00303 85.14695 -6.11055 -9.00303 85.14695 -6.38052 -10.50303 85.01755 -5.08295 -4.00303 85.72747 -4.31402 -10.5013 86.22204 -3.64806 -9.84937 86.81808 -3.44961 -4.00303 87.00083 -3.09106 -9.0365 87.35614 -2.86901 -8.00303 87.59163 -13.03604 -5.00303 84.67029 -8.96283 -5.00303 84.67029 -12.5984 -5.00303 85.13996 -9.40047 -5.00303 85.13996 -12.27033 -5.00303 85.69278 -9.72854 -5.00303 85.69278 -12.06769 -5.00303 86.30226 -9.93118 -5.00303 86.30226 -11.99943 -5.00303 86.93856 -9.99943 -5.00303 86.93856 -10.99943 -10.00303 85.00083 -10.99943 -10.00303 85.40252 -12.66555 -10.00303 85.05361 -12.38011 -10.00303 85.47597 -10.99943 -10.00303 85.74328 -12.17045 -10.00303 85.94014 -10.99943 -10.00303 86.01088 -9.95637 -10.00303 86.43206 -12.04251 -10.00303 86.43202 -9.99943 -10.00303 86.93856 -11.99943 -10.00303 86.93856 -6.58866 -6.00303 84.98121 -6.58878 -9.00303 84.98118 -7.0945 -6.00303 84.94082 -7.09457 -9.00303 84.94084 -7.59312 -6.00303 85.02871 -7.59319 -9.00303 85.02874 -8.05351 -6.00303 85.23889 -8.05357 -9.00303 85.23892 -8.4464 -6.00303 85.55789 -8.44646 -9.00303 85.55793 -8.74675 -6.00303 85.96547 -8.74683 -9.00303 85.96562 -8.9354 -6.00303 86.43654 -8.93547 -9.00303 86.43677 -8.99943 -6.00303 86.93856 -8.99943 -9.00303 86.93856 -15.41021 -9.00303 84.98121 -15.41021 -6.00303 84.98121 -14.90438 -9.00303 84.94082 -14.90438 -6.00303 84.94082 -14.40575 -9.00303 85.02871 -14.40575 -6.00303 85.02871 -13.94536 -9.00303 85.23889 -13.94536 -6.00303 85.23889 -13.55247 -9.00303 85.55789 -13.55247 -6.00303 85.55789 -13.25213 -9.00303 85.96547 -13.25213 -6.00303 85.96547 -13.06347 -9.00303 86.43654 -13.06347 -6.00303 86.43654 -12.99944 -9.00303 86.93856 -12.99944 -6.00303 86.93856 -13.71113 -5.29592 85.04183 -12.97319 -5.29592 85.86539 -12.70656 -5.29593 86.93856 -12.92332 -5.62036 86.93856 -12.38214 -5.07915 86.93856 -7.25136 -5.30497 84.66201 -8.28282 -5.29592 85.03849 -9.02428 -5.29592 85.86277 -9.61675 -5.07915 86.93856 -9.29233 -5.29592 86.93856 -9.07556 -5.62034 86.93856 -15.20861 -9.24626 84.91934 -14.45941 -9.511981 84.86864 -13.92234 -9.70494 84.92412 -13.03527 -9.71013 85.7556 -12.97082 -9.982001 85.01441 -13.25342 -9.92569 84.99267 -13.5218 -9.845001 84.9712 -12.38212 -9.92691 86.93856 -12.70654 -9.71013 86.93856 -12.92332 -9.38571 86.93856 -19.32739 -8.00303 87.72432 -19.56388 -8.00303 87.75068 -19.78578 -8.00303 87.66474 -19.94282 -8.00303 87.48597 -19.99944 -8.00303 87.25486 -2.67151 -8.00302 87.72431 -2.43502 -8.00302 87.7507 -2.21312 -8.00302 87.66475 -2.05606 -8.00302 87.48597 -1.99944 -8.00303 87.25486 -5.22536 -10.75303 85.55951 -3.52903 -9.98157 86.87934 -2.86596 -9.193262 87.46949 -4.23798 -10.62444 86.18592 -3.30825 -10.1712 86.83069 -2.61141 -9.29184 87.43207 -5.13856 -10.9194 85.41758 -3.15324 -10.23448 86.72433 -2.31082 -9.29155 87.14128 -4.99944 -11.00303 85.19011 -4.00331 -10.79866 85.9662 -2.97677 -10.21861 86.44617 -3.91117 -10.77342 85.81321 -2.27803 -9.24322 87.00869 -16.98495 -10.99559 85.21382 -15.42694 -11.00303 84.38729 -16.869 -10.93604 85.40339 -14.52264 -10.85658 84.42583 -16.78412 -10.77336 85.54217 -13.76685 -11.00303 83.83877 -12.04944 -10.85241 83.89984 -10.99943 -10.6697 84.02233 -13.47455 -10.61703 84.28743 -10.99943 -10.97928 83.70178 -10.99943 -11.00303 83.54885 -8.2317 -11.00303 83.83885 -9.94944 -10.85241 83.89984 -7.47623 -10.85658 84.42583 -6.57136 -11.00303 84.38752 -19.08425 -9.16383 87.46038 -17.71125 -10.54603 86.2146 -18.57539 -10.08604 86.87477 -19.28141 -9.25626 87.46589 -17.83893 -10.7081 86.13066 -18.7582 -10.2036 86.79393 -19.46508 -9.30571 87.39328 -17.99289 -10.79692 85.97328 -18.92981 -10.24095 86.64248 -19.63477 -9.30826 87.23494 -18.09775 -10.76947 85.81949 -19.02166 -10.21902 86.44584 -19.72185 -9.240942 87.00955 -10.99943 -10.40319 84.16567 -12.78643 -10.32127 84.33208 -10.99943 -10.18686 84.38906 -12.73147 -10.1721 84.6602 -10.99943 -10.04902 84.66846 -6.78915 -9.24626 84.91934 -6.47673 -9.4878 84.9731 -6.95446 -10.02226 84.77111 -7.53835 -9.511981 84.86864 -7.55681 -10.49866 84.5542 -8.07543 -9.70494 84.92412 -8.47597 -9.845001 84.9712 -8.523221 -10.61703 84.28743 -8.74434 -9.92569 84.99267 -9.02695 -9.982001 85.01441 -9.266302 -10.1721 84.6602 -9.21134 -10.32127 84.33208 -9.33221 -10.00303 85.05361 -9.07556 -9.38571 86.93856 -9.29233 -9.71013 86.93856 -8.9625 -9.71013 85.7556 -9.61675 -9.92691 86.93856 -9.82731 -10.00303 85.94014 -9.61765 -10.00303 85.47597 -9.99943 -5.00303 93.26877 -11.99943 -5.00303 93.26877 -9.76705 -5.00303 94.09375 -11.62292 -5.00303 94.21898 -11.22196 -5.00303 94.0259 -10.77691 -5.00303 94.0259 -10.37594 -5.00303 94.21898 -12.36546 -5.07242 94.00083 -9.72595 -5.02203 94.5056 -11.9004 -5.00303 94.56694 -10.09847 -5.00303 94.56694 -12.16913 -5.00303 94.92147 -9.82974 -5.00303 94.92148 -11.99943 -5.00303 95.00083 -9.99943 -5.00303 95.00083 -9.91382 -5.00303 95.44345 -12.07844 -5.00303 95.45932 -10.13171 -5.00303 95.49787 -11.86516 -5.00303 95.50135 -10.49671 -5.00303 95.86528 -10.23375 -5.00303 95.88864 -11.75377 -5.00303 95.8983 -11.49825 -5.00303 95.86753 -10.99721 -5.00303 96.00081 -10.71798 -5.00303 96.13891 -11.2647 -5.00303 96.1428 -8.99943 -9.00303 94.00083 -8.99906 -6.00303 94.00081 -12.99944 -9.00303 94.00083 -12.99944 -6.00303 93.96101 -12.69802 -5.2875 94.00083 -12.92101 -5.61481 94.00083 -12.9945 -6.00303 94.1412 -9.5678 -5.1104 94.23588 -9.30086 -5.28749 94.00083 -9.07786 -5.61481 94.00083 -9.13342 -9.50305 94.00083 -9.499462 -9.869071 94.00083 -9.99943 -10.00303 94.00083 -11.99943 -10.00303 94.00083 -12.49944 -9.86905 94.00083 -12.86546 -9.50303 94.00083 -10.99943 -5.00303 95.00083 -12.73674 -5.33823 94.1848 -12.92749 -5.64578 94.15258 -9.26214 -5.33822 94.18481 -9.071392 -5.64578 94.15258 -12.81211 -5.27567 95.41165 -13.10184 -5.9457 95.54119 -12.15939 -5.27567 96.45308 -12.32968 -5.9457 96.71621 -10.99944 -5.9457 97.17156 -10.99944 -5.27567 96.85948 -9.66919 -5.9457 96.71621 -9.83949 -5.27567 96.45308 -8.89703 -5.9457 95.54119 -9.18676 -5.27567 95.41165 -9.99943 -10.00303 95.50083 -11.99943 -10.00303 95.50083 -8.89703 -8.9457 95.54119 -13.10184 -8.9457 95.54119 -12.32968 -8.9457 96.71621 -10.99944 -8.9457 97.17156 -9.66919 -8.9457 96.71621 -19.12988 5.2965 89.82287 -16.49944 8.496972 92.08535 -15.11795 11.39697 89.68384 -17.75948 10.8991 90.28621 -19.68002 5.63813 90.39956 -13.73816 11.49697 89.71026 -12.6984 11.49697 89.29082 -18.50646 10.59098 93.56623 -18.68239 10.48045 94.41388 -17.3459 11.17867 92.90397 -17.50171 11.01932 91.70685 -16.34875 11.34554 91.02054 -19.62539 9.636342 95.45105 -19.80692 9.23126 95.04592 -19.3814 9.77928 96.36007 -19.75098 9.44767 94.97078 -19.1299 7.19214 93.23297 -18.73264 7.83903 94.26452 -19.38222 7.53031 93.96105 -19.69616 8.16196 94.33181 -19.32961 8.34236 94.60522 -18.56921 8.64121 95.29347 -17.92096 8.54095 95.21244 -17.37778 8.49544 94.56346 -19.55777 8.55985 94.71041 -19.38537 8.73646 95.12652 -19.753 9.009302 95.10453 -19.77822 8.656372 94.6345 -19.95091 8.88449 94.20365 -19.82544 9.29202 94.66218 -19.85573 8.20532 94.23194 -14.1751 8.6999 97.51353 -10.99944 8.55728 98.13482 -14.289 9.105072 98.62049 -17.11091 7.94142 90.46917 -17.5802 7.94142 91.18251 -17.93302 7.94142 91.86851 -16.02825 11.49697 93.17279 -17.77565 11.08882 94.01065 -16.21191 11.49697 94.23915 -15.79537 11.49697 92.22714 -16.87505 11.27728 91.90441 -15.49461 11.49697 91.41564 -15.11051 11.49697 90.7632 -14.64758 11.49697 90.29109 -14.60171 11.04698 100.825 -13.23189 11.04697 101.4749 -13.7854 11.49697 99.47166 -13.27012 11.48797 100.0102 -15.80674 11.04699 99.87802 -14.73763 11.49697 98.71241 -16.75669 11.04699 98.70907 -15.48995 11.49697 97.75497 -17.3948 11.04699 97.4496 -16.0027 11.49697 96.64927 -17.74075 11.04698 96.20579 -16.24766 11.49697 95.45497 -17.84745 11.04698 95.04558 -13.59535 9.968562 101.5481 -14.10851 10.3817 101.6682 -14.86599 9.951332 100.9168 -12.05994 9.968562 101.9637 -12.06741 10.38028 102.2918 -13.63363 10.85606 101.6447 -19.02626 9.09237 96.37292 -18.21762 9.4337 97.78476 -19.40844 9.572001 96.42621 -18.07484 9.96326 98.56782 -19.27217 9.94482 96.26661 -18.64199 10.22999 97.42498 -18.22036 10.36962 98.04489 -17.71625 10.50161 98.68008 -16.28111 10.27446 100.3477 -16.96824 9.74083 99.29841 -16.5328 10.70933 99.86162 -15.84827 9.88731 100.2647 -15.96703 10.77157 100.3141 -14.94548 10.83814 100.9923 -19.45986 9.80788 95.89679 -19.56388 7.03771 93.27092 -19.80851 7.58718 93.8946 -19.99944 7.87464 93.62245 -19.99944 7.42452 92.80275 -19.99944 5.53739 89.58751 -19.12988 6.30681 91.12614 -19.99944 7.99697 92.1724 -19.99944 8.3286 93.39332 -19.92759 8.649621 92.46511 -19.74095 9.21523 92.83737 -19.49847 9.656762 93.29487 -19.27217 9.95521 93.81954 -19.27217 10.01127 94.47571 -19.27217 10.0246 95.09308 -19.27217 10.00166 95.68509 -14.33799 9.49194 99.7704 -13.54441 9.65113 100.6214 -10.99943 11.49697 95.12439 -18.28336 10.70835 92.54011 -17.95351 10.83841 91.10441 -19.0442 10.19218 94.41816 -10.99944 8.496972 95.00081 -7.69372 8.496972 89.72613 -6.88885 11.49697 90.76256 -7.35129 11.49697 90.29109 -6.50431 11.49697 91.41555 -8.26082 11.49697 89.71022 -9.300601 11.49697 89.29078 -7.39114 11.04698 100.8213 -7.00228 10.83605 100.9621 -8.76036 11.04697 101.4726 -8.42268 10.85606 101.6672 -8.9534 10.85606 101.8487 -10.23691 11.04697 101.8064 -10.17666 10.85606 102.1003 -11.75499 11.04697 101.8072 -9.69498 9.65113 101.0324 -8.45173 9.65113 100.6214 -8.98314 9.968562 101.7492 -10.18862 9.968562 101.9972 -10.99948 9.65113 101.1718 -7.66148 9.492382 99.77202 -7.55751 9.96396 101.1531 -7.89038 10.3817 101.6682 -9.93147 10.38028 102.2918 -11.4601 10.85606 102.133 -10.99944 11.48797 100.5008 -8.21348 11.49697 99.47166 -8.72876 11.48797 100.0102 -7.26126 11.49697 98.71241 -9.86098 11.48797 100.3768 -12.16097 11.48797 100.3768 -12.65105 10.85606 101.9544 -12.30398 9.65113 101.0324 19.68114 3.11933 92.42472 19.68114 5.63812 94.39955 19.13099 3.312 92.37461 19.13099 5.74386 94.32435 20.00056 4.28707 92.55139 17.76016 10.89921 94.28441 17.49198 10.95645 93.19076 15.7384 11.1753 92.8843 16.76383 7.94142 94.03388 15.95638 7.94142 93.22799 17.76155 5.63631 92.40637 18.51579 10.27552 101.6224 18.07596 9.96326 102.5678 19.37938 9.46742 100.4393 17.99856 10.43204 102.3381 18.57038 8.64119 99.29342 19.22685 8.93964 99.8138 18.70426 9.2523 101.0084 19.37984 8.73646 99.12654 17.74244 11.04698 100.2026 17.84858 11.04698 99.04393 16.24877 11.49697 99.45497 16.00381 11.49697 100.6493 17.39767 11.04699 101.445 15.49106 11.49697 101.755 16.7613 11.04699 102.7036 19.59571 8.83116 99.13356 19.21309 9.19201 100.4333 19.74747 9.009302 99.10453 19.80139 9.23127 99.04592 19.27328 9.94482 100.2666 19.7521 9.44767 98.97078 16.71717 10.68463 103.7013 16.0911 10.75973 104.2209 16.28223 10.27446 104.3477 15.96762 9.87593 104.1751 16.56968 9.8037 103.6754 17.20651 9.69696 103.0548 17.37948 10.57362 103.0559 17.80162 9.560872 102.3648 18.29893 9.41038 101.6767 18.93732 10.11113 100.9274 19.27329 10.02495 99.04329 17.91544 8.54095 99.21244 14.29012 9.10508 102.6205 15.81296 11.04698 103.873 19.27328 9.955222 97.81954 18.68931 10.4765 98.44255 17.37206 7.94142 94.84272 17.81881 7.94142 95.62484 18.13819 7.94142 96.36641 18.35844 7.94142 97.06499 19.13101 7.19214 97.23298 20.00056 7.99697 96.1724 20.00056 7.4246 96.80301 20.00056 6.94656 95.57982 20.00056 6.38827 94.62459 20.00056 8.25571 97.05318 20.00056 7.58539 97.30754 18.03181 10.81416 95.43007 15.11907 11.39697 93.68384 16.34981 11.34554 95.02043 17.50282 11.01933 95.70684 18.28996 10.70574 96.56483 17.34713 11.17865 96.9042 16.87627 11.27726 95.90458 18.51465 10.58686 97.59963 17.77677 11.04697 98.01065 19.55681 8.56278 98.71521 18.94661 8.50667 98.93193 19.33031 8.34255 98.60556 19.92306 8.79775 96.93055 19.74206 9.21523 96.83737 19.49958 9.656762 97.29487 19.80856 9.3299 98.73648 19.99392 7.87464 97.62246 19.80298 7.58718 97.89461 19.67596 7.07942 97.26065 16.02941 11.49697 97.17299 16.21304 11.49697 98.23915 15.79654 11.49697 96.22731 15.12631 8.496972 94.33946 15.76119 8.496972 94.99005 16.24058 8.496972 95.64044 16.59384 8.496972 96.26857 16.84736 8.496972 96.86425 17.02299 8.496972 97.42589 19.92871 8.649621 96.46511 18.72711 7.83903 98.26452 18.49448 7.94157 97.72605 19.37669 7.53031 97.96105 19.69064 8.16196 98.33181 17.58927 8.496972 99.04093 17.37226 8.49544 98.56347 17.13748 8.496972 97.95772 19.7727 8.656372 98.6345 19.94539 8.88449 98.20365 19.99392 8.38057 97.92615 19.99392 8.3286 97.39334 3.58867 1.43357 91.00081 2.87013 1.27291 91.70231 2.87013 -0.003029882 91.59163 3.15487 -0.003029882 91.29075 3.45073 -0.003029882 91.00081 2.87013 2.37195 91.98259 3.99651 2.81535 91.00081 4.65271 4.08412 91.00081 3.33635 4.10292 92.26278 2.87013 4.09936 92.83101 5.50056 5.99697 91.00081 4.1579 6.16047 92.98506 6.00056 6.96932 92.11705 6.00056 7.74294 93.00081 5.50056 7.94142 93.74383 12.05057 7.47344 91.00081 13.42382 7.14735 91.00081 12.05057 7.94142 91.46534 13.60876 7.94142 91.85357 14.69345 6.582 91.00083 14.91229 7.94142 92.47516 15.99923 5.63255 91.00083 16.95287 4.64133 91.00083 17.93123 2.916 91.00083 18.36637 1.65375 91.00083 18.55039 -0.003029882 91.00083 18.84625 -0.003029882 91.29077 19.13099 -0.003029882 91.59163 19.13099 1.27351 91.70243 19.13099 2.37288 91.98291 6.00056 8.496972 91.00081 9.96558 8.496972 91.00081 6.00056 8.496972 93.00081 17.23637 10.98769 92.17483 17.00056 10.99697 91.25485 8.092082 11.39697 92.93673 5.00056 10.99697 91.25485 6.26273 11.26217 92.8843 6.83172 10.99697 90.13398 9.49381 11.39697 92.44628 8.86467 10.99697 89.43849 11.00006 11.39697 92.27532 11.00054 10.99697 89.20285 12.50645 11.39697 92.44607 13.13641 10.99697 89.43849 15.16936 10.99697 90.13395 13.90857 11.39697 92.9365 4.7637 10.9876 92.179 4.5079 10.95624 93.19575 2.31998 3.11935 92.42472 2.00056 4.28585 92.55059 2.00056 2.47986 91.66356 2.32517 -0.003029882 91.70771 2.00056 1.33074 91.37054 2.00056 -0.003029882 91.25485 2.05718 -0.003029882 91.48596 2.21422 -0.003029882 91.66474 2.43612 -0.003029882 91.75068 2.67261 -0.003029882 91.72432 20.00056 1.33136 91.37065 19.565 -0.003029882 91.75068 19.7869 -0.003029882 91.66474 19.94394 -0.003029882 91.48597 20.00056 -0.003029882 91.25485 20.00056 2.48084 91.66389 19.32852 -0.003029882 91.72432 11.00057 11.49528 92.98594 12.05057 8.496972 92.86506 13.2815 8.496972 93.20881 12.03555 8.496972 91.00081 2.87013 -8.00303 91.59163 3.0914 -9.0346 91.35697 3.63093 -9.82743 90.83525 3.45073 -4.00303 91.00083 4.38597 -10.3084 90.21868 5.08407 -4.00303 89.72747 5.26143 -10.50303 89.61666 6.3819 -10.50303 89.01744 6.11167 -9.00303 89.14695 6.47897 -9.4878 88.9731 6.11167 -6.00303 89.14695 6.58706 -5.67444 88.92507 6.92677 -5.46536 88.78298 6.93422 -4.00303 88.78002 7.25148 -5.29607 88.65947 6.9567 -10.02226 88.77111 7.55905 -10.49866 88.5542 7.72198 -5.11393 88.50078 8.4356 -5.00303 88.30406 8.93008 -4.00303 88.19744 10.1382 -5.00303 88.03469 11.00057 -4.00303 88.00083 11.86293 -5.00303 88.03469 13.07105 -4.00303 88.19744 13.56553 -5.00303 88.30406 14.24841 -5.10488 88.49124 14.85765 -5.34857 88.69922 15.0669 -4.00303 88.78002 15.39911 -5.66467 88.91852 16.73969 -10.50303 89.61666 15.88945 -6.00303 89.14695 15.88945 -9.00303 89.14695 15.61948 -10.50303 89.01755 16.91706 -4.00303 89.72747 17.68598 -10.5013 90.22204 18.35194 -9.84937 90.81808 18.55039 -4.00303 91.00083 18.90894 -9.0365 91.35614 19.13099 -8.00303 91.59163 8.96396 -5.00303 88.67029 13.03717 -5.00303 88.67029 9.4016 -5.00303 89.13996 12.59953 -5.00303 89.13996 9.72967 -5.00303 89.69278 12.27146 -5.00303 89.69278 9.932312 -5.00303 90.30226 12.06882 -5.00303 90.30226 10.00057 -5.00303 90.93856 12.00057 -5.00303 90.93856 11.00057 -10.00303 89.00083 11.00057 -10.00303 89.40252 9.33445 -10.00303 89.05361 9.619892 -10.00303 89.47597 11.00057 -10.00303 89.74328 9.82955 -10.00303 89.94014 11.00057 -10.00303 90.01088 12.04364 -10.00303 90.43206 9.95749 -10.00303 90.43201 12.00057 -10.00303 90.93856 10.00057 -10.00303 90.93856 15.41134 -6.00303 88.98121 15.41122 -9.00303 88.98118 14.9055 -6.00303 88.94082 14.90544 -9.00303 88.94084 14.40688 -6.00303 89.02871 14.40681 -9.00303 89.02874 13.94649 -6.00303 89.23889 13.94644 -9.00303 89.23891 13.5536 -6.00303 89.55789 13.55354 -9.00303 89.55793 13.25326 -6.00303 89.96547 13.25317 -9.00303 89.96562 13.0646 -6.00303 90.43654 13.06454 -9.00303 90.43677 13.00057 -6.00303 90.93856 13.00057 -9.00303 90.93856 6.58979 -9.00303 88.98121 6.58979 -6.00303 88.98121 7.09562 -9.00303 88.94082 7.09562 -6.00303 88.94082 7.59425 -9.00303 89.02871 7.59425 -6.00303 89.02871 8.05464 -9.00303 89.23889 8.05464 -6.00303 89.23889 8.44753 -9.00303 89.55789 8.44753 -6.00303 89.55789 8.74787 -9.00303 89.96547 8.74787 -6.00303 89.96547 8.936532 -9.00303 90.43654 8.936532 -6.00303 90.43654 9.00056 -9.00303 90.93856 9.00056 -6.00303 90.93856 8.28888 -5.29592 89.04183 9.02681 -5.29592 89.86539 9.29344 -5.29593 90.93856 9.076682 -5.62035 90.93856 9.61786 -5.07915 90.93856 14.74864 -5.30497 88.66201 13.71718 -5.29592 89.03849 12.97572 -5.29592 89.86277 12.38325 -5.07915 90.93856 12.70767 -5.29592 90.93856 12.92444 -5.62034 90.93856 6.79139 -9.246252 88.91934 7.54059 -9.511981 88.86864 8.077672 -9.70493 88.92412 8.96474 -9.71013 89.7556 9.02918 -9.982001 89.01441 8.746582 -9.92569 88.99267 8.4782 -9.84499 88.9712 9.61788 -9.92691 90.93856 9.29346 -9.71013 90.93856 9.07669 -9.38571 90.93856 2.67261 -8.00303 91.72432 2.43612 -8.00303 91.75068 2.21422 -8.00303 91.66474 2.05718 -8.00303 91.48597 2.00056 -8.00303 91.25485 19.32849 -8.00302 91.72431 19.56498 -8.00302 91.7507 19.78688 -8.00302 91.66475 19.94394 -8.00302 91.48597 20.00056 -8.00303 91.25486 16.77464 -10.75303 89.55951 18.47097 -9.98157 90.87934 19.13404 -9.193262 91.46949 17.76203 -10.62444 90.18592 18.69175 -10.17119 90.83069 19.38859 -9.29184 91.43207 16.86144 -10.9194 89.41758 18.84677 -10.23448 90.72433 19.68918 -9.29155 91.14128 17.00056 -11.00303 89.19011 17.99669 -10.79865 89.9662 17.73979 -10.91053 89.59456 19.02323 -10.21861 90.44617 18.08883 -10.77341 89.81321 19.72198 -9.24321 91.00869 5.01505 -10.99559 89.2138 6.57306 -11.00303 88.38727 5.131 -10.93604 89.40339 7.47736 -10.85658 88.42583 5.21588 -10.77336 89.54217 8.23315 -11.00303 87.83876 9.950572 -10.85241 87.89984 11.00057 -10.6697 88.02233 8.52545 -10.61703 88.28743 11.00057 -10.97928 87.70178 11.00056 -11.00303 87.54885 13.7683 -11.00303 87.83885 12.05057 -10.85241 87.89984 14.52377 -10.85658 88.42583 15.42864 -11.00303 88.38752 2.91575 -9.16382 91.46038 4.28875 -10.54603 90.2146 3.42461 -10.08604 90.87477 2.71859 -9.25626 91.46589 4.16107 -10.70809 90.13066 3.2418 -10.2036 90.79393 2.53492 -9.30571 91.39328 4.00711 -10.79692 89.97328 3.07019 -10.24095 90.64248 2.36523 -9.30826 91.23494 3.90226 -10.76947 89.81949 2.97833 -10.21902 90.44583 2.27815 -9.240942 91.00953 11.00057 -10.40319 88.16567 9.213582 -10.32127 88.33208 11.00057 -10.18686 88.38906 9.26853 -10.1721 88.6602 11.00057 -10.04902 88.66846 15.21085 -9.246252 88.91934 15.52327 -9.4878 88.9731 15.04554 -10.02226 88.77111 14.46165 -9.511981 88.86864 14.44319 -10.49865 88.5542 13.92457 -9.70493 88.92412 13.52403 -9.84499 88.9712 13.47679 -10.61703 88.28743 13.25566 -9.92569 88.99267 12.97305 -9.982001 89.01441 12.73371 -10.1721 88.6602 12.78866 -10.32127 88.33208 12.66779 -10.00303 89.05361 12.92445 -9.38571 90.93856 12.70767 -9.71013 90.93856 13.0375 -9.71013 89.7556 12.38325 -9.92691 90.93856 12.17269 -10.00303 89.94014 12.38235 -10.00303 89.47597 12.00057 -5.00303 97.26877 10.00057 -5.00303 97.26877 12.23295 -5.00303 98.09375 10.37708 -5.00303 98.21898 10.77804 -5.00303 98.0259 11.22309 -5.00303 98.0259 11.62406 -5.00303 98.21898 9.63454 -5.07242 98.00083 12.27405 -5.02203 98.5056 10.0996 -5.00303 98.56694 11.90153 -5.00303 98.56694 9.83087 -5.00303 98.92147 12.17026 -5.00303 98.92148 10.00057 -5.00303 99.00083 12.00057 -5.00303 99.00083 12.08618 -5.00303 99.44345 9.92156 -5.00303 99.45932 11.86829 -5.00303 99.49787 10.13484 -5.00303 99.50135 11.50329 -5.00303 99.86528 11.76625 -5.00303 99.88864 10.24623 -5.00303 99.8983 10.50175 -5.00303 99.86753 11.00279 -5.00303 100.0008 11.28202 -5.00303 100.1389 10.7353 -5.00303 100.1428 13.00057 -9.00303 98.00083 13.00094 -6.00303 98.00081 9.00056 -9.00303 98.00083 9.00056 -6.00303 97.96101 9.30198 -5.2875 98.00083 9.079001 -5.61481 98.00083 9.0055 -6.00303 98.1412 12.4322 -5.1104 98.23588 12.69915 -5.28749 98.00083 12.92214 -5.61481 98.00083 12.86658 -9.50305 98.00083 12.50054 -9.869071 98.00083 12.00057 -10.00303 98.00083 10.00057 -10.00303 98.00083 9.50056 -9.86905 98.00083 9.13454 -9.50303 98.00083 11.00057 -5.00303 99.00083 9.26326 -5.33823 98.1848 9.07251 -5.64578 98.15258 12.73786 -5.33822 98.18481 12.92861 -5.64578 98.15258 9.187891 -5.27567 99.41165 8.89816 -5.9457 99.54119 9.84061 -5.27567 100.4531 9.67032 -5.9457 100.7162 11.00056 -5.9457 101.1716 11.00056 -5.27567 100.8595 12.33081 -5.9457 100.7162 12.16051 -5.27567 100.4531 13.10297 -5.9457 99.54119 12.81324 -5.27567 99.41165 12.00057 -10.00303 99.50083 10.00057 -10.00303 99.50083 13.10297 -8.9457 99.54119 8.89816 -8.9457 99.54119 9.67032 -8.9457 100.7162 11.00056 -8.9457 101.1716 12.33081 -8.9457 100.7162 2.87012 5.2965 93.82287 5.50056 8.496972 96.08535 6.88205 11.39697 93.68384 4.24052 10.8991 94.28621 2.31998 5.63813 94.39956 8.26184 11.49697 93.71026 9.3016 11.49697 93.29082 3.49354 10.59098 97.56623 3.31761 10.48045 98.41388 4.6541 11.17867 96.90397 4.49829 11.01932 95.70685 5.65125 11.34554 95.02054 2.37461 9.636342 99.45105 2.19308 9.23126 99.04592 2.61861 9.77928 100.3601 2.24902 9.44767 98.97078 2.87011 7.19214 97.23297 3.26737 7.83903 98.26452 2.61779 7.53031 97.96104 2.30384 8.16196 98.33181 2.6704 8.34236 98.60522 3.43079 8.64121 99.29347 4.07904 8.54095 99.21244 4.62223 8.49544 98.56346 2.44224 8.55985 98.71041 2.61464 8.73646 99.12652 2.24701 9.009302 99.10453 2.22178 8.656372 98.6345 2.04909 8.88449 98.20365 2.17456 9.29202 98.66218 2.14427 8.20532 98.23194 7.8249 8.6999 101.5135 11.00056 8.55728 102.1348 7.711 9.10508 102.6205 4.8891 7.94142 94.46917 4.41981 7.94142 95.18251 4.06698 7.94142 95.86851 5.97176 11.49697 97.17279 4.22435 11.08882 98.01065 5.78809 11.49697 98.23915 6.20463 11.49697 96.22714 5.12495 11.27728 95.90441 6.50539 11.49697 95.41564 6.88949 11.49697 94.7632 7.35242 11.49697 94.29109 7.39829 11.04698 104.825 8.76811 11.04697 105.4749 8.2146 11.49697 103.4717 8.72988 11.48797 104.0102 6.19326 11.04699 103.878 7.26237 11.49697 102.7124 5.24331 11.04699 102.7091 6.51005 11.49697 101.755 4.6052 11.04699 101.4496 5.9973 11.49697 100.6493 4.25925 11.04698 100.2058 5.75235 11.49697 99.45497 4.15255 11.04698 99.04558 8.40465 9.968562 105.5481 7.8915 10.3817 105.6682 7.13401 9.951332 104.9168 9.94006 9.968562 105.9637 9.9326 10.38028 106.2918 8.366372 10.85606 105.6447 2.97374 9.09237 100.3729 3.78238 9.4337 101.7848 2.59157 9.572001 100.4262 3.92516 9.96326 102.5678 2.72783 9.94482 100.2666 3.35801 10.22999 101.425 3.77964 10.36962 102.0449 4.28376 10.50161 102.6801 5.71889 10.27446 104.3477 5.03176 9.74083 103.2984 5.46721 10.70933 103.8616 6.15173 9.88731 104.2647 6.03297 10.77157 104.3141 7.05452 10.83814 104.9923 2.54015 9.80788 99.89679 2.43612 7.03771 97.27092 2.1915 7.58718 97.8946 2.00056 7.42452 96.80275 2.00056 7.87464 97.62245 2.00056 5.53739 93.58751 2.87012 6.30681 95.12614 2.00056 7.99697 96.1724 2.00056 8.3286 97.39332 2.07241 8.649621 96.46511 2.25906 9.21523 96.83737 2.50154 9.656762 97.29487 2.72783 9.955222 97.81954 2.72783 10.01127 98.47571 2.72783 10.0246 99.09308 2.72783 10.00166 99.68509 7.66201 9.49194 103.7704 8.455592 9.65113 104.6214 11.00057 11.49697 99.12439 3.71665 10.70835 96.54011 4.04649 10.83841 95.10441 2.9558 10.19218 98.41816 11.00057 8.496972 99.00081 14.30628 8.496972 93.72613 15.11115 11.49697 94.76256 14.64871 11.49697 94.29109 15.49569 11.49697 95.41555 13.73918 11.49697 93.71022 12.6994 11.49697 93.29078 14.60886 11.04698 104.8213 14.99772 10.83605 104.9621 13.23964 11.04697 105.4726 13.57732 10.85606 105.6672 13.0466 10.85606 105.8487 11.76309 11.04697 105.8064 11.82334 10.85606 106.1003 10.24501 11.04697 105.8072 12.30502 9.65113 105.0324 13.54827 9.65113 104.6214 13.01686 9.968562 105.7492 11.81138 9.968562 105.9972 11.00053 9.65113 105.1718 14.67593 8.71842 101.5759 14.33852 9.492382 103.772 14.4425 9.96396 105.1531 14.10963 10.38171 105.6682 12.06853 10.38028 106.2918 10.5399 10.85606 106.133 11.00056 11.48797 104.5008 13.27124 11.48797 104.0102 13.78652 11.49697 103.4717 14.73874 11.49697 102.7124 12.13903 11.48797 104.3768 9.83903 11.48797 104.3768 9.34895 10.85606 105.9544 9.696022 9.65113 105.0324 24.65771 9.874462 80.00003 24.9558 10.19218 94.41816 25.31761 10.48045 94.41388 24.31694 9.33731 80.00232 24.50154 9.656762 93.29487 24.72783 9.955222 93.81954 25.49354 10.59098 93.56623 39.00026 -10.99969 80.00003 39.76828 -10.89972 80.00003 39.00056 -11.00303 85.19011 39.7398 -10.91053 85.59456 40.08883 -10.77342 85.81321 40.50205 -10.59673 80.00003 41.02324 -10.21861 86.44617 41.1212 -10.12139 80.00003 41.72198 -9.24321 87.00869 41.59687 -9.502222 80.00003 41.90019 -8.768052 80.00003 42.00026 -7.99969 80.00003 42.00056 -8.00303 87.25486 27.01505 -10.99559 85.21382 26.2241 -10.90081 80.00083 26.99799 -11.0065 79.96547 25.90226 -10.76947 85.81949 25.49917 -10.59693 80.00003 24.97834 -10.21902 86.44584 24.40259 -9.49962 80.00003 24.27815 -9.240942 87.00955 24.10026 -8.76782 80.00003 24.00026 -7.99969 80.00003 24.00056 -8.00303 87.25486 37.42865 -11.00303 84.38752 28.57306 -11.00303 84.38729 42.00026 8.00031 80.00003 42.00056 7.99698 92.1724 42.00026 6.00031 80.00003 42.00056 4.28707 88.5514 42.00056 2.48084 87.6639 42.00056 1.33137 87.37066 42.00056 -0.003029882 87.25486 24.00026 8.00031 80.00003 24.00056 7.42452 92.80275 24.00056 7.99697 92.1724 24.00056 5.53739 89.58751 24.00056 4.28586 88.55059 24.00056 2.47986 87.66356 24.00056 1.33074 87.37055 24.00056 -0.003029882 87.25485 24.00026 -3.99969 80.00003 24.00026 6.00031 80.00003 41.92687 8.65984 80.00003 41.92871 8.64963 92.46511 41.74207 9.21523 92.83738 41.70312 9.30205 80.00003 41.49958 9.656762 93.29489 41.34298 9.87424 80.00003 40.87493 10.34245 80.00003 40.68932 10.4765 94.44256 40.28997 10.70574 92.56484 40.51466 10.58686 93.59964 40.30249 10.70294 80.00003 40.03181 10.81415 91.43007 39.76017 10.89921 90.28441 39.00026 11.00031 68.44584 39.49199 10.95645 89.19076 39.23637 10.98769 88.17483 39.00056 10.99697 87.25485 24.07241 8.649621 92.46511 24.07367 8.659892 80.00003 24.25905 9.21523 92.83737 25.1258 10.34262 80.00003 25.71664 10.70835 92.54011 25.66303 10.68178 80.0016 26.04649 10.83841 91.10441 26.24052 10.8991 90.28621 27.00026 11.00031 80.00003 27.00056 10.99697 87.25485 26.76369 10.98761 88.179 26.5079 10.95624 89.19575 28.83172 10.99697 86.13398 30.86467 10.99697 85.43849 33.00055 10.99697 85.20285 41.27329 9.955222 93.81955 3.69851 10.70317 84.00003 5.00026 11.00031 84.00003 3.12632 10.34303 84.00003 -3.49865 -10.59694 80.00003 -4.99944 -11.00303 80.00083 -2.87826 -10.12085 80.00003 -2.40227 -9.49953 80 -2.09974 -8.76782 80.00003 -2.05395 -8.57232 87.20533 -1.99974 -7.99969 80.00003 -17.7759 -10.90081 80.00083 -16.99944 -11.00303 83.00083 -16.99974 -10.9997 80.00003 -18.50153 -10.59674 80.00003 -19.12068 -10.1214 80.00003 -19.59635 -9.502222 80.00003 -19.89967 -8.768052 80.00003 -19.99974 -7.99969 80.00003 -10.99974 -11.00136 78.34411 -1.99944 7.99697 80.00083 -1.99974 6.00031 80.00003 -1.99974 -3.99969 80.00003 -19.99974 8.00031 71.65831 -2.34403 9.3815 80.00061 -2.65719 9.87445 80.00003 -3.12528 10.34261 80.00003 -3.62834 10.66877 79.99942 -4.34009 10.92688 80.00003 -4.99974 11.00031 80.00003 -19.92632 8.66 80.00003 -19.70237 9.30253 80.00003 -19.34188 9.87497 80.00003 -18.87368 10.34303 80.00003 -18.30149 10.70316 80.00003 -16.99974 11.00031 80.00003 17.00026 -10.99969 84.00003 17.76828 -10.89972 84.00003 18.50205 -10.59673 84.00003 19.1212 -10.12139 84.00003 19.59687 -9.502222 84.00003 19.90018 -8.768052 84.00003 19.94605 -8.57232 91.20533 20.00026 -7.99969 84.00003 4.2241 -10.90081 84.00081 5.00026 -10.99969 84.00003 3.49847 -10.59674 84.00003 2.87932 -10.1214 84.00003 2.40364 -9.502222 84.00003 2.10032 -8.768052 84.00003 2.00026 -7.99969 84.00003 11.00056 -11.00303 82.164 20.00026 8.00031 84.00003 20.00026 6.00031 84.00003 2.00026 8.00031 84.00003 19.92683 8.66001 84.00003 19.70288 9.30254 84.00003 19.3424 9.87498 84.00003 18.8742 10.34303 84.00003 18.30201 10.70317 84.00003 17.00026 11.00031 84.00003 2.07369 8.66001 84.00003 2.29763 9.30254 84.00003 2.65812 9.87498 84.00003 4.3327 10.83834 80.00003 3.58877 10.63364 80.00016 3.12979 10.3458 80.00003 20.00026 -7.99969 80.00003 20.00026 6.00031 80.00003 2.00087 7.9986 80.00003 2.00026 -7.99969 80.00003 4.92874 11.00031 79.1574 5.00026 11.00031 80.00003 3.71604 -10.59802 79.60369 3.86241 -10.59802 81.40355 2.42948 -9.53943 80.0016 4.98589 -10.99969 79.62123 5.01205 -10.99969 81.49244 5.00026 -10.99969 82.40481 17.17464 -10.99969 78.69107 17.00672 -10.99969 81.49743 -16.99974 -10.99969 71.07357 2.11456 -8.8199 80.00003 -2.8341 -10.59802 77.81888 -4.20597 -11.00002 77.5193 -2.16309 -9.498332 78.95822 -1.73179 -7.99969 79.00003 -1.49683 -9.498332 78.12275 -1.41395 -7.99969 78.58583 -0.99974 -7.99969 78.26799 -2.13715 -10.99969 75.47991 -0.91783 -10.59777 76.62258 -0.53404 -9.498332 77.65908 -0.51738 -7.99969 78.06819 -1.22603 -10.99969 75.15274 0.59526 -10.59777 76.55097 0.69725 -10.99969 75.04885 -0.26943 -10.99969 75.0073 2.6e-4 -7.99969 78.00003 0.53456 -9.498332 77.65908 0.51789 -7.99969 78.06819 1.6381 -10.99969 75.2759 1.9969 -10.59777 77.12541 2.51731 -10.99969 75.67978 1.49734 -9.498332 78.12275 1.00026 -7.99969 78.26799 1.41447 -7.99969 78.58583 3.30253 -10.99969 76.24569 3.02454 -10.59777 78.23831 3.96375 -10.99969 76.95195 2.16361 -9.498332 78.95822 1.73231 -7.99969 79.00003 4.4766 -10.99969 77.77239 4.82196 -10.99969 78.67671 1.93211 -7.99969 79.48239 18.40394 -10.64841 79.90622 19.58443 -9.498022 79.9998 19.89211 -8.797942 80.00003 19.92081 -9.498332 78.79946 20.06841 -7.99969 79.48239 18.99247 -10.59777 78.21028 17.51946 -10.99969 77.78138 20.26821 -7.99969 79.00003 18.03361 -10.99969 76.95607 20.79969 -9.498332 77.92057 20.03621 -10.59777 77.10305 20.58604 -7.99969 78.58583 21.00025 -7.99969 78.26799 18.69775 -10.99969 76.24591 19.48711 -10.99969 75.67753 21.45118 -10.59777 76.54338 20.37126 -10.99969 75.27282 21.48263 -7.99969 78.06817 22.00026 -9.498332 77.59889 22.0002 -7.99969 78.00003 21.31737 -10.99969 75.04689 22.28898 -10.99969 75.00837 36.38472 -10.99969 74.66987 -4.24974 -10.99969 75.50003 3.15365 10.59839 78.48143 4.70803 11.00031 78.31571 2.65477 9.87078 80.00003 2.34381 9.38248 79.99777 2.16361 9.49895 78.95822 2.07547 8.66787 80.00003 1.81694 7.99696 79.12403 4.33671 11.00031 77.51101 2.18247 10.59839 77.26362 3.19481 11.00031 76.15364 3.82524 11.00031 76.77986 1.49734 9.49895 78.12275 1.35816 7.99634 78.50424 2.47028 11.00031 75.65274 0.77908 10.59839 76.58777 1.67287 11.00031 75.2881 0.53456 9.49895 77.65908 0.70652 7.9977 78.11434 0.82237 11.00031 75.06807 0.003619909 7.99684 77.98102 -0.77857 10.59839 76.58777 -0.93444 11.00031 75.08818 -0.05690991 11.00031 75.00036 -0.53405 9.49895 77.65908 -0.73896 7.99722 78.12483 -1.7798 11.00031 75.32762 -2.18196 10.59839 77.26362 -2.56862 11.00031 75.71041 -1.49683 9.49895 78.12275 -1.3497 7.99713 78.50263 -3.28124 11.00031 76.22753 -3.15313 10.59839 78.48143 -4.38788 10.99998 77.50109 -2.16309 9.49895 78.95822 -1.81518 7.9965 79.11428 -4.96166 11.00031 79.38407 -4.846 11.00031 78.76966 17.668 10.88732 80.00003 17.00026 11.00031 80.00003 18.39397 10.64952 80.00267 18.87074 10.3458 80.00003 19.34576 9.87077 80.00003 19.65764 9.37099 80.00058 20.0261 8.00223 79.78579 21.22144 10.59839 76.58777 22.77908 10.59839 76.58777 21.17697 11.00031 75.06827 22.05642 11.00031 75.00035 22.53456 9.49895 77.65908 21.46596 9.49895 77.65908 22.00362 7.99684 77.98102 21.26106 7.99722 78.12483 20.32602 11.00031 75.28868 19.81805 10.59839 77.26362 19.52892 11.00031 75.65348 20.50317 9.49895 78.12275 20.65031 7.99713 78.50263 18.80557 11.00031 76.15374 18.84687 10.59839 78.48143 17.66463 11.00031 77.50957 18.17623 11.00031 76.77873 19.83691 9.49895 78.95822 20.18043 7.99652 79.12062 17.29248 11.00031 78.31575 17.07212 11.00031 79.15538 33.00041 -11.01419 78.34452 35.76831 -11.00303 83.83885 33.00057 -11.00303 83.54885 30.23315 -11.00303 83.83877 42 -4.37194 66.4732 39.02267 -11.00002 75.08294 40.44828 -10.60419 74.80902 22.96992 -10.59777 76.63703 23.24969 -10.99969 75.15866 22.51792 -7.99969 78.06819 23.20083 -9.498332 77.92057 24.16356 -10.99969 75.49224 23.00026 -7.99969 78.26799 24.4262 -10.59802 77.57001 25.97642 -11.00002 77.80838 25.02965 -10.99969 76.31192 24.07971 -9.498332 78.79946 23.41448 -7.99969 78.58583 23.73231 -7.99969 79.00003 23.93211 -7.99969 79.48239 41.17694 -10.06092 74.9608 41.68639 -9.552021 74.60721 41.99767 -8.01113 74.09465 42 -5.53847 70.52472 26.96239 11.00031 79.38578 25.15365 10.59839 78.48143 25.81986 10.88883 78.11775 26.77643 10.99998 78.09215 26.84682 11.00031 78.77086 24.16361 9.49895 78.95822 23.94208 7.99737 79.45581 23.60646 7.99701 78.77993 24.18247 10.59839 77.26362 25.28084 11.00031 76.22673 23.49735 9.49895 78.12275 23.20683 8.00031 78.40497 24.56712 11.00031 75.70919 23.77808 11.00031 75.32676 22.70653 7.99771 78.11434 22.93337 11.00031 75.08786 28.40349 -8.47888 11.38139 32.41966 -10.39946 12.09684 32.07041 -8.486082 13.14744 24.01463 -8.49968 5.09246 25.93359 -9.85955 5.58086 26.40131 0.004699945 11.02765 27.30582 -10.22031 6.25849 26.51307 -10.34244 5.16882 27.05665 0.00901997 11.89372 28.55564 -9.64302 7.14186 29.56896 -8.933712 8.01146 30.37484 -8.14502 8.837532 35.00025 -7.43725 9.41716 35.00025 -5.76714 10.52316 35.00025 -3.93633 11.33593 26.34064 -17.95326 2.99867 26.92072 -18.59914 4.80043 25.76056 -17.30739 1.19691 27.72791 -19.13109 6.6871 28.53512 -19.66305 8.57377 32.07253 -12.24215 12.44397 25.97391 -12.57047 6.52178 31.50558 -13.97236 13.01092 25.38119 -14.24428 7.11449 30.73585 -15.5381 13.78065 24.59638 -15.75172 7.89931 29.78649 -16.89231 14.73002 23.64218 -17.04913 8.8535 28.686 -17.99429 15.83051 22.54626 -18.09895 9.94944 21.34031 -18.87077 11.15537 27.46747 -18.81092 17.04904 31.63869 -14.49044 14.44563 35.00025 -8.90012 8.04876 35.00025 -10.11498 6.45608 35.00025 -11.04798 4.68351 27.40025 -11.09018 4.58269 35.00025 -11.67312 2.78043 27.40025 -11.64889 2.88028 27.40025 -11.94789 1.11366 35.00025 -11.97299 0.79989 27.40787 -11.94871 -0.93186 27.92001 -11.98834 -0.52151 28.45432 -11.99809 -0.19525 28.99234 -11.99966 -0.01994997 29.53337 -11.99967 0.01541996 35.00025 -11.93923 -1.20295 30.05848 -11.99939 -0.08360999 30.60025 -11.99514 -0.3301 31.96513 -11.92772 -1.31218 35.00025 -11.57278 -3.17227 33.17361 -11.74079 -2.47917 26.69314 -11.32162 2.97827 26.40025 -10.42215 3.51742 26.40025 -10.82463 1.95457 26.69314 -11.69481 0.52945 26.40025 -10.99412 0.34963 27.09578 -11.87235 -1.37935 26.71759 -11.59961 -1.87068 26.40025 -10.92695 -1.26282 26.40025 -10.62459 -2.848 26.45649 -11.05894 -2.46479 22.28349 -8.49967 5.96955 22.19817 -9.88384 6.05487 23.33167 -11.28459 5.48867 24.85194 -11.60693 5.52242 21.94514 -11.22494 6.30791 22.47212 -13.82473 6.34822 21.53238 -12.48305 6.72066 23.8929 -14.44108 6.48147 20.97256 -13.6208 7.28049 21.12374 -15.89684 7.69661 20.28258 -14.60443 7.97046 22.38843 -16.75303 7.98593 19.48311 -15.40482 8.76993 19.40502 -17.3188 9.41533 20.47079 -18.33958 9.90358 18.59801 -15.99816 9.65504 17.46704 -17.96563 11.35331 17.65359 -16.36674 10.59945 18.30849 -19.06128 12.06588 20.05931 -19.34222 12.43639 18.74032 -19.49967 13.75538 33.46514 -13.23542 -4.38076 32.28778 -13.85514 -3.54525 31.81377 -14.02564 -3.2714 30.60025 -14.46437 -2.79934 31.22617 -14.24843 -3.01115 29.9921 -14.63437 -2.69853 29.33738 -14.75585 -2.73755 28.62729 -14.79947 -2.94482 28.06561 -14.7988 -3.22255 27.51717 -14.71325 -3.63394 27.05751 -14.55941 -4.13271 26.67791 -14.31856 -4.75935 26.48153 -14.05493 -5.30128 26.40025 -13.70245 -5.92586 25.69386 -14.36625 -4.94372 23.40025 -15.35262 -3.49112 24.57748 -13.49051 -6.58541 26.40025 -12.58132 -7.37889 24.43242 -12.36088 -7.8829 26.40025 -11.22704 -8.632081 24.26431 -11.0518 -8.980502 26.40025 -9.674262 -9.6486 24.07885 -9.60768 -9.85022 26.40025 -7.98379 -10.39032 23.88002 -8.059472 -10.48215 26.40025 -6.18543 -10.84599 23.67152 -6.43582 -10.86809 23.45517 -4.75135 -10.99998 26.40025 -4.32847 -10.99998 26.40025 3.2e-4 -10.99998 20.80625 -4.91046 -11.00022 18.49701 -4.88507 -10.99054 17.80788 0.01880997 -10.9689 22.28349 -7.74968 5.96955 16.67795 -16.49934 11.57509 19.83408 -7.73186 8.35991 17.67848 -2.25269 -10.97997 17.34177 -13.08415 -7.20827 19.67205 -14.44833 -5.4625 17.10318 -14.40371 -5.27381 21.01717 -14.45248 -5.46438 20.86789 -13.10861 -7.33403 17.48629 -11.32987 -8.83812 20.8567 -11.35649 -8.91332 17.65667 -9.2618 -10.04914 20.84362 -9.30734 -10.08299 17.84032 -7.0325 -10.77014 20.82957 -7.10759 -10.77832 16.21432 -4.66904 -11.01523 17.62941 -16.83755 -0.5810599 20.1615 -16.82432 -1.00218 23.59675 -18.29618 2.50571 18.73591 -18.84136 3.9695 21.2089 -18.77235 3.32658 25.02458 -19.7664 6.56035 20.33439 -20.43481 8.38561 16.32313 -18.63193 4.7582 22.72505 -20.30991 7.52829 17.9938 -20.21678 9.37161 26.83457 -20.85997 10.49577 22.33832 -21.628 12.67456 24.62881 -21.45601 11.60831 20.08241 -21.41371 13.85312 15.74767 -19.64619 10.48574 17.90191 -20.78959 15.13328 29.58687 -20.05982 10.55783 28.95048 -21.59927 14.31421 30.63861 -20.45659 12.5419 26.83901 -22.22966 15.57205 29.24789 -16.00011 0.24119 32.72167 -14.68274 -0.7800599 33.49831 -15.35544 1.85466 30.21492 -16.97527 3.37437 34.47482 -15.903 4.43261 31.44747 -17.74713 6.43113 32.90879 -18.32579 9.408902 35.62984 -16.33092 6.95043 34.56216 -18.72138 12.30514 31.93859 -20.68924 14.62077 26.40025 -5.99968 6.00002 26.39507 -7.73162 5.01777 42.02021 -13.83867 14.29794 42.00025 -11.52747 14.08449 42.00025 -13.19034 14.22324 36.07827 -8.49957 15.91769 30.44322 -16.8216 15.96259 41.79856 -15.10147 14.19988 41.72396 -14.98816 14.96006 41.57338 -15.56666 14.15114 41.17762 -15.92868 15.16058 41.90142 -13.68791 14.8816 41.47512 -13.70568 15.47655 40.1245 -15.27101 15.93375 40.58631 -14.5679 15.87018 40.74386 -13.57435 15.74587 41.99378 -9.96123 14.29538 42.01282 -6.8414 14.96249 41.68601 -7.84641 15.45743 42.00025 -9.20317 14.24873 41.76836 -10.68854 14.90432 36.80173 -18.68935 15.87163 36.39445 -18.92611 15.09958 40.17875 -16.92108 14.2656 40.32484 -16.7515 15.04228 42.00025 3.2e-4 18.4377 42.00025 -2.45947 16.88493 42.00025 -11.5709 7.14655 42.00025 -4.59768 15.6645 42.00025 -12.6909 10.55045 35.70737 -3.55614 11.15385 35.02811 3.8e-4 11.99572 36.00025 -1.84419 10.84427 36.00025 -3.63533 10.38183 35.70737 -6.77643 9.54632 36.00025 -5.3225 9.62642 36.00025 -6.8584 8.599902 35.70737 -9.356202 7.03648 36.00025 -8.204812 7.32639 36.00025 -9.31814 5.84519 35.70737 -11.05159 3.86156 36.00025 -10.16628 4.20001 41.57278 -13.76807 8.916602 41.54034 -12.20096 3.64142 40.27235 -13.74717 5.04463 40.17191 -14.74203 7.98176 40.18572 -15.74563 10.95823 38.94659 -14.4825 5.4868 36.94197 -16.64471 9.40475 38.38988 -16.84989 11.7922 42.00025 -10.67037 4.09574 42.00025 3.41451 23.22383 42.00025 2.48337 21.60508 42.00025 8.00032 2e-5 26.46544 8.99548 11.93412 26.40025 11.00032 12.00002 35.0163 10.99907 11.99931 35.77664 10.99998 11.66451 35.50025 3.2e-4 11.86604 35.70735 3.2e-4 11.70713 35.86629 3.2e-4 11.50002 36.00155 2.1e-4 11.04207 36.00002 10.99987 11.00577 40.37364 3.2e-4 17.38355 27.01681 -0.01592993 12.24287 35.02872 -8.8e-4 13.18408 42.00025 1.33143 20.13088 35.08573 -11.80042 -6.21055 35.6059 -10.89876 -7.17275 35.39104 -11.27122 -6.77528 36.00025 -10.7261 2.43799 35.70737 -11.70236 0.32165 36.00025 -10.98286 0.60792 36.00025 -10.92969 -1.23884 35.70737 -11.24701 -3.24866 36.00025 -10.56956 -3.04589 35.00025 -10.88384 -5.05319 36.00025 -9.911642 -4.76999 35.75685 -9.60337 -6.61508 35.5237 -10.17083 -6.08431 35.279 -10.59459 -5.5635 36.00025 -8.97281 -6.3626 36.00025 -7.77785 -7.77815 35.9585 -8.66244 -7.28348 34.20457 -11.39358 -3.76549 41.7905 -3.19041 -8.87215 41.74584 -1.03501 -9.19167 42.00025 -2.56724 -7.87044 41.12244 -3.40579 -9.86748 41.19122 -1.03675 -10.06104 40.10453 -3.96232 -10.42355 39.16365 -2.79369 -10.86731 39.00025 -1.03347 -10.99998 40.21046 -1.03285 -10.73259 39.3138 -4.48102 -10.48149 42.00025 -4.01987 -7.49524 41.7905 -5.24932 -8.18534 41.12244 -5.67564 -9.11018 40.10453 -6.72086 -9.32951 39.45084 -6.08439 -9.85265 42.00025 -5.36798 -6.89018 41.7905 -7.10811 -7.05961 41.12244 -7.73129 -7.86504 39.57241 -7.56018 -9.00133 40.10453 -9.11759 -7.54226 39.67771 -8.880762 -7.94826 42.00025 -6.5857 -6.06749 41.7905 -8.662281 -5.53635 42.00025 -7.60726 -5.08037 41.12244 -9.45589 -6.17451 39.76682 -10.0302 -6.70475 40.45203 -11.22837 -3.75614 39.88445 -11.55432 -3.6065 42.00025 -8.435001 -3.93784 41.7905 -9.81318 -3.68584 40.9985 -10.87407 -3.69893 42.00025 -9.03509 -2.69427 42.00025 -9.39662 -1.4047 41.83179 -10.32557 -1.5804 41.3948 -11.0788 -1.49077 35.70857 -12.46417 -4.83861 35.9755 -13.18312 -2.76718 38.22656 -12.1883 -3.49941 34.38255 -12.56367 -5.28364 38.50327 -9.6095 -7.80173 35.90602 -9.91289 -8.07624 37.77982 -7.1914 -9.58309 36.00025 -8.87659 -8.876892 36.00025 -7.36012 -9.77793 36.9552 -4.63787 -10.65916 36.00025 -5.67979 -10.45227 36.00025 -3.91054 -10.86221 36.00243 -2.08998 -11.00132 37.007 -1.75784 -10.99998 42.00025 -9.964241 1.3075 39.99825 -12.45262 -0.54363 36.62261 -13.68488 -0.23197 42.00025 5.13849 -6.1318 42.00025 6.12571 -5.14582 42.00025 6.92669 -4.00314 42.00025 7.51684 -2.73896 42.00025 7.87836 -1.39154 42.00025 3.99485 -6.93134 42.00025 2.73022 -7.5198 42.00025 1.38154 -7.87984 42.00025 -1.03347 -7.99998 42.00025 3.2e-4 -7.99998 36.00025 3.2e-4 -10.99998 36.00025 10.86488 -1.72084 36.00025 10.46189 -3.39933 36.00025 9.80128 -4.99409 36.00025 8.899312 -6.46588 36.00025 7.77821 -7.77843 36.00025 6.46557 -8.89945 36.00025 4.99391 -9.80121 36.00025 3.39927 -10.46168 36.00025 1.72095 -10.86458 36.00025 11.00032 2e-5 39.00025 1.64007 -10.87708 39.00025 3.2e-4 -10.99998 39.00025 3.24445 -10.51072 39.00025 4.7755 -9.90945 39.00025 6.1986 -9.08741 39.00025 7.48293 -8.0629 39.00025 8.60061 -6.85818 38.97711 10.48833 -3.49898 39.00025 11.00032 2e-5 39.00025 10.89241 -1.81744 40.4095 7.5e-4 -10.63608 39.66782 3.2e-4 -10.92476 41.59834 2.4591 -9.17628 41.92503 3.2e-4 -8.66754 41.64241 0.002799928 -9.40393 40.49889 2.87802 -10.2007 41.34576 3.2e-4 -9.87045 40.87072 3.2e-4 -10.34547 41.59834 4.75032 -8.22722 40.49889 5.53952 -9.03619 41.59834 6.71784 -6.71749 40.49889 7.78487 -7.19279 41.59834 8.22756 -4.74998 40.44881 9.92724 -3.464 41.59834 9.17661 -2.45876 39.66782 10.9251 2e-5 40.39354 10.64984 -0.002829909 40.87072 10.34581 2e-5 41.34576 9.87079 2e-5 41.69691 9.311882 5e-5 41.92503 8.667881 2e-5 38.00713 -1.40528 -10.99998 39.68842 -1.03347 -10.91998 41.92567 -1.03347 -8.664792 39.03521 10.99585 49.49406 42.00125 -0.71631 18.43795 42.00025 4.55122 26.76701 42.00025 4.1072 24.95292 42.00047 4.69463 28.6318 41.81115 -1.86582 18.29768 41.23049 -3.3002 17.89993 41.47659 -2.75849 18.06089 12.48855 3.2e-4 15.79748 42.00025 3.2e-4 18.84805 37.1356 3.2e-4 19.3314 33.23856 -20.92189 16.69965 40.76066 -15.52186 15.75186 40.06757 -16.00425 15.87182 40.22589 -16.42364 15.52246 33.35737 -19.37798 18.47003 36.38074 -17.22534 16.86729 34.80528 -18.14896 17.55974 36.71384 -18.03838 16.64432 38.0946 -16.32222 16.33485 33.58095 -19.83546 18.33454 33.70298 -20.36124 17.97837 33.54759 -20.85854 17.23245 30.69171 -22.24771 18.43515 31.41272 -21.9537 17.9378 31.62679 -21.89856 18.60094 31.84028 -21.44528 19.19137 31.80485 -20.76753 19.56405 32.26551 -19.55745 19.0903 41.25215 -11.00445 15.38839 40.64713 -11.32652 15.5772 40.52986 -9.02008 15.7978 41.13953 -8.51999 15.75002 40.40797 -6.80917 16.37213 41.01591 -6.13438 16.52875 41.58786 -5.17697 16.53332 40.38424 -4.48807 17.39218 41.93192 -4.01259 16.46582 40.92645 -3.84365 17.70303 35.71275 -9.705142 15.91657 35.29206 -10.91734 16.03666 39.14009 -13.04748 15.91207 36.25659 -12.37569 16.18199 35.09933 -11.52614 16.16336 34.118 -13.0561 16.55865 38.58134 -14.43949 16.13066 41.26543 -14.7604 15.59121 31.477 -15.17923 17.95153 29.34525 -16.44808 19.29175 33.81829 -18.5521 18.04126 35.41711 -17.43465 17.18347 33.03078 -13.91455 16.94669 36.99712 -16.05521 16.52683 29.02715 -17.60599 18.87498 30.80184 -16.13773 17.10029 28.50963 -18.42133 17.89618 33.63822 -12.77722 15.80506 19.14005 -0.003129959 29.62204 19.25456 -9.92532 29.53012 19.10081 -10.63181 29.65857 19.40948 -9.26246 29.4442 19.71731 -0.01337999 29.35701 19.56011 -8.67049 29.39129 19.77643 -7.90248 29.36016 20.02914 -7.07309 29.38228 20.37775 -0.00296998 29.53156 20.26107 -6.37132 29.4636 20.44985 -5.8276 29.58583 20.7931 -0.0173999 30.14644 20.6622 -5.25023 29.82252 20.78845 -4.83021 30.14517 26.16752 -19.31767 18.34898 24.82522 -19.49928 19.69128 23.48092 -19.35032 21.03558 17.42155 -19.33856 15.07414 22.17502 -18.87526 22.34149 16.1412 -18.86353 16.3545 20.94673 -18.08838 23.56977 14.93633 -18.08837 17.55936 16.27308 3.1e-4 32.48607 18.94978 -11.71702 29.80163 16.99428 -9.818001 31.76487 19.11136 -12.30309 29.54573 16.69925 -10.41788 31.94676 19.6621 -13.33201 28.79598 20.01768 -13.85381 28.33473 19.37698 -12.71614 29.27196 20.37682 -14.31138 27.89106 16.30979 -10.98208 32.00586 15.84935 -11.48071 31.94183 21.59014 -15.58498 26.50465 22.34574 -16.22029 25.72818 20.96544 -14.97776 27.1939 23.14839 -16.87866 24.86746 22.80765 -17.27495 24.78397 15.35213 -11.88407 31.76529 22.34495 -17.61963 24.59531 21.90648 -17.85584 24.34608 14.83885 -12.18266 31.4894 21.39506 -18.03484 23.97552 14.32936 -12.36808 31.12733 28.39665 -17.08982 20.17261 26.32936 -19.14903 20.07644 27.02606 -18.2739 20.87608 27.43289 -17.51014 21.05084 26.40682 -17.71803 21.98106 24.09405 -18.94074 22.31176 24.97444 -18.08273 22.9277 25.32321 -17.67927 22.96893 24.25482 -17.38544 23.94788 15.52851 -17.95703 24.59626 20.26193 -19.8896 26.44864 19.21382 -18.99056 27.48281 21.24988 -20.69806 25.57821 19.74209 -20.53287 23.21115 21.68996 -20.62116 26.04128 18.19185 -18.06313 28.61582 18.99066 -17.98845 29.04796 16.93622 -16.85897 30.15848 22.36362 -20.15979 26.4117 19.74082 -17.36263 29.20481 16.33141 -15.51816 32.23312 22.83073 -19.52563 26.367 20.1572 -16.65143 28.87078 17.21596 -14.86782 32.39308 21.27265 -17.60897 27.6795 23.00918 -19.02773 26.10273 30.56804 -19.94081 20.11286 31.13405 -20.31158 19.93937 29.85641 -20.68763 20.83753 28.9377 -20.18408 21.221 28.59649 -20.85482 21.73916 27.35306 -20.11139 22.33947 27.13896 -20.80618 22.81975 25.85386 -19.72125 23.44513 25.655 -20.47569 23.97182 24.46295 -19.04943 24.50942 24.21118 -19.83891 25.12656 23.19882 -18.14021 25.50323 22.07966 -17.02658 26.40912 21.12335 -15.73274 27.21873 17.49983 -14.38133 32.22545 24.66112 -22.43105 16.84363 22.5027 -22.21692 18.20887 20.40215 -21.55375 19.64544 16.91113 -19.99842 18.42206 18.23429 -20.36765 20.84409 29.12959 -22.67236 19.52596 29.80934 -22.52407 19.04911 27.17079 -22.85069 20.93243 27.99811 -22.82753 20.33094 25.20728 -22.62564 22.41558 26.17777 -22.79241 21.67212 22.79481 -21.72366 24.32347 23.60282 -22.11311 23.67622 24.43566 -22.42148 23.0167 22.01063 -21.2525 24.95752 29.93627 -21.36656 20.86929 29.86304 -22.07504 20.56567 29.57405 -22.5463 20.02341 28.03761 -21.54364 22.23441 27.85562 -22.26048 22.00524 27.48744 -22.73599 21.51744 26.18318 -21.30885 23.6408 25.89422 -22.0113 23.49062 25.44652 -22.47526 23.06171 24.41178 -20.65827 25.0442 24.02091 -21.32278 24.97271 23.50173 -21.75924 24.59907 17.11525 -13.81543 32.82057 -2.29975 -2.19968 10.00002 1.41852 -2.18136 8.50479 2.10002 -2.1863 8.88863 2.29769 -2.19447 9.43571 2.30026 -2.19968 10.00002 15.58798 -19.62919 16.00003 13.38918 -18.54927 11.10375 14.01899 -18.14679 5.70158 11.69067 -17.19778 6.20609 15.7002 -16.39166 12.55285 14.74955 -16.0464 13.5035 13.85454 -15.47327 14.39851 7.96479 -5.69968 20.28825 6.74123 -9.818001 21.51182 6.44189 -9.49952 21.81116 6.15404 -8.86181 22.10996 6.22134 -0.003749907 22.03882 6.02004 -8.07461 22.23301 15.4237 -15.28663 32.26079 12.34679 -14.95873 28.08375 8.56765 -12.45528 30.71025 6.45156 -12.39952 27.24239 9.72782 -15.05955 23.61681 13.13618 -17.59838 20.42722 4.79622 -12.34811 23.80456 7.3538 -14.73762 19.06055 3.31448 -12.27908 19.90975 11.06191 -17.0369 16.10123 5.7965 -14.29902 15.81472 2.03309 -12.17345 15.57592 2.30026 -12.41869 14.50002 9.326022 -16.29676 11.64083 4.45563 -13.7603 8.99367 2.30026 -12.7135 9.36678 7.94874 -15.40209 7.06861 2.30026 -12.66151 4.17627 2.30026 3.2e-4 10.00002 2.30026 -5.99968 14.50002 2.29793 -6.49553 9.455471 1.35699 -6.49441 8.502962 -1.36301 -6.49383 8.50314 -1.37883 -2.19331 8.503372 1.9934 -6.4836 8.769742 6.02004 -8.074602 26.47565 5.60269 -8.074602 25.95281 6.02004 3.1e-4 26.47565 5.60119 3.1e-4 25.95042 5.31731 -8.074602 25.36663 5.30971 3.1e-4 25.34517 5.16495 -8.074602 24.72983 5.16022 3.1e-4 24.69022 5.15527 -8.074602 24.06575 5.16022 3.1e-4 24.01844 5.29752 -8.074602 23.39905 5.30971 3.1e-4 23.36349 5.59 -8.074602 22.77618 5.60119 3.2e-4 22.75823 5.67436 -9.66423 22.90164 6.56361 -10.39752 21.79493 6.50046 -10.93473 22.15888 5.54018 -10.15569 23.95551 6.54932 -11.42115 22.59446 6.71143 -11.83646 23.08675 5.83148 -10.48407 25.04063 6.98741 -12.15973 23.61972 7.36413 -12.36337 24.15835 6.71724 -11.05583 25.77845 6.10162 -9.14249 26.39407 6.33935 -10.15108 26.15634 7.21442 -11.82133 25.28127 7.82302 -12.43309 24.67267 14.49035 -18.0228 17.06126 14.0894 -17.80055 16.48177 13.84051 -17.51784 16.00994 13.66921 -17.10376 15.50945 13.6162 -16.65177 15.09983 13.67642 -16.05519 14.68301 16.09159 -18.85471 14.28278 15.48012 -17.78049 13.34023 13.83343 -12.4331 30.68308 12.03045 3.1e-4 32.48607 12.03045 -8.074602 32.48607 13.21518 -11.80923 31.30133 12.70999 -11.02191 31.80652 12.33751 -10.1127 32.17901 12.1093 -9.12466 32.40722 1.7e-4 -11.18913 19.04369 -0.07635998 -11.28434 16.80128 0.5104 -11.45072 16.74273 1.36779 -11.78772 16.34723 1.75114 -11.99076 15.99146 2.55636 -11.7272 21.34209 0.96721 -11.61329 16.58688 1.51737 -11.1812 23.97205 -0.46236 -10.99969 24.08346 4.38211 -11.7272 26.07354 1.31037 -10.99969 28.35049 3.5336 -11.1812 28.57728 3.40761 -10.99969 32.26215 6.74065 -11.7272 30.53661 6.07224 -11.1812 32.91627 -0.277 3.2e-4 16.78325 0.27751 3.2e-4 16.78325 0.8159 3.2e-4 16.65054 1.30688 3.2e-4 16.39283 1.7219 3.2e-4 16.02512 2.03685 3.2e-4 15.5688 2.23344 3.2e-4 15.05038 2.30026 3.2e-4 14.50002 18.44563 3.2e-4 14.19056 7.94215 -9.49526 -8.74049 5.79498 -8.75979 -8.48912 11.03062 -9.83635 -9.103401 16.37179 -9.38429 -9.929182 5.20335 -6.40573 -7.44079 16.19582 -6.6725 -7.99255 16.19854 -5.91443 -7.05481 5.21083 -5.34324 -6.28933 16.20295 -5.21217 -6.09823 5.21083 -4.46593 -4.8577 16.21576 -4.45627 -4.43457 5.21083 -3.82337 -3.30643 16.20252 -3.79117 -2.54029 5.21083 -3.43141 -1.67376 16.19454 -3.58016 -1.05025 5.21083 -3.29968 2e-5 16.22372 -3.54935 -0.03472989 16.20554 -2.27144 2e-5 4.65165 -6.42327 -9.95994 4.67074 -4.85293 -10.53826 4.75562 -5.59203 -10.16753 2.5e-4 -6.49968 2e-5 2.5e-4 -2.19968 2e-5 2.5e-4 -6.49968 1.50002 2.5e-4 -2.19968 1.50002 5.211 -7.77663 -8.83886 5.10653 -8.62178 -8.75723 4.67872 -7.97769 -9.10889 5.56788 -9.22203 -8.36796 4.77767 -3.38496 -10.84126 5.21512 -3.95656 -10.43942 5.211 -5.29716 -9.87299 5.21083 -6.45814 -9.39643 4.52895 -2.93278 -10.9321 4.68751 -1.54675 -8.49243 5.21083 -2.71436 -8.735001 5.21083 -1.68769 -7.07249 5.21083 -0.88467 -5.29111 5.21083 -0.31883 -3.42085 5.21083 3.2e-4 0.02375996 16.20164 -3.87406 -8.524291 16.20554 -8.50857 -9.78222 16.19149 -7.38475 -10.66326 15.68676 -10.02945 -9.58225 13.70732 -10.13295 -9.30496 2.30026 -12.2811 -1.05123 2.30026 -11.93863 -2.86297 4.55497 -12.84383 -1.73477 7.08376 -13.40058 -2.55376 9.88299 -13.91818 -3.49883 2.30025 -11.27331 -4.62131 10.07449 -13.24681 -5.12989 2.30025 -10.29997 -6.25599 10.33482 -12.33418 -6.62453 2.30025 -9.043931 -7.71364 10.65601 -11.20818 -7.94218 2.30025 -7.52813 -8.955471 2.30025 -5.81076 -9.92659 2.30025 -3.94129 -10.59819 2.30025 -1.96335 -10.9499 1.40157 -6.49028 1.49476 1.40112 -2.19185 1.49557 2.29917 -6.49742 0.52472 2.01772 -6.48097 1.21033 2.28986 -2.1686 0.7134 1.91201 -2.18626 1.29958 -2.29975 -6.49968 2e-5 2.30028 -0.53686 -8.14923 2.31554 0.01653999 -3.92797 2.29455 -1.26716 -0.9975399 2.28722 -1.81631 -0.7952899 2.27369 -2.19633 -0.16031 10.51843 -15.63732 1.33572 6.95038 -14.37706 2.40713 3.51229 -13.13803 3.88576 17.23772 -3.05346 -10.96482 16.18242 -3.40822 -11.02232 17.22123 -1.64601 -8.41791 16.2002 -2.61073 -9.88012 16.20301 -3.46626 -7.26 16.20633 -3.06177 -5.94197 16.24841 -1.38861 -7.1104 16.20823 -2.70407 -4.54705 16.20536 -2.4366 -3.05215 16.19878 -2.29308 -1.47717 13.68469 -14.26965 -4.67984 13.77124 -13.2465 -6.4377 14.00948 -11.86053 -8.03449 15.15664 -16.66497 0.006769955 12.79545 -16.31463 0.77954 -2.31627 -2.09971 -0.45265 16.29574 0.01832991 0.009949982 17.69897 6.92263 -0.90656 17.7 8.17118 -6.31599 17.70071 6.93745 -7.57629 17.7 9.01431 -5.2704 17.70026 9.00032 -3.32453 17.69255 9.02092 -0.82214 17.9133 7.12353 -8.09596 18.281 7.47546 -8.13672 18.281 8.714672 -6.71267 18.281 9.49011 -5.5627 18.28946 10.09972 -4.3549 17.7 9.62212 -4.30022 17.80645 10.63646 -0.01969999 17.63077 10.52348 0.25821 17.94184 10.79483 0.38153 18.09589 10.91687 0.92458 17.46791 10.46586 0.40571 17.83099 10.86485 1.34917 18.27831 10.98081 1.4733 18.43223 10.99463 1.9448 17.64867 10.12079 -0.44572 17.70586 10.24945 -2.09048 17.70026 9.79379 -3.02493 18.28079 10.77432 -2.24154 18.33503 10.99501 -0.001329958 17.70025 3.2e-4 2e-5 17.70026 3.2e-4 -6.72382 17.58226 3.2e-4 -4.95369 17.15031 3.2e-4 2e-5 17.21782 5.8e-4 -2.76679 17.70026 -1.22318 -9.62563 17.70026 -0.55721 -8.19757 17.22123 -0.61647 -5.65771 16.26741 -0.45891 -4.49718 16.2005 3.2e-4 -1.73222 16.20426 -0.28531 -3.352 16.70025 9.00032 2e-5 16.75961 6.80614 0.1259999 3.21558 7.33902 0.009579956 17.70026 5.92604 -8.363492 17.91993 4.97721 -9.56273 17.70026 4.86644 -9.02125 18.45026 5.90116 -9.28331 18.45026 4.61769 -9.98395 17.70026 3.7954 -9.521532 17.91993 2.56215 -10.47149 18.45026 3.34297 -10.4798 17.70026 2.74612 -9.87536 18.45026 2.12328 -10.79317 17.70026 1.74768 -10.09994 18.45026 0.99835 -10.95461 3.26448 10.99998 1.82656 3.17098 10.89998 1.30254 17.2886 10.70415 0.94977 3.23595 9.184 -4.1e-4 16.71546 9.70102 0.11947 17.68258 0.41522 -10.32299 17.7 6.04312 -0.72008 17.70026 5.1811 -0.259 26.31675 0.004699945 11.43307 37.50025 3.2e-4 21.00002 8.00662 3.2e-4 20.25202 37.40801 3.2e-4 20.14595 26.40025 11.00032 2e-5 26.40025 3.2e-4 6.00002 26.40025 1.72095 -10.86458 26.40025 3.39927 -10.46168 26.40025 4.99391 -9.80121 26.40025 6.46557 -8.89945 26.40025 7.77821 -7.77843 26.40025 8.899312 -6.46588 26.40025 9.80128 -4.99409 26.40025 10.46189 -3.39932 26.40025 10.86488 -1.72084 -0.81539 3.2e-4 16.65054 -1.30637 3.2e-4 16.39283 -1.72139 3.2e-4 16.02512 -2.03634 3.2e-4 15.5688 -0.05216991 10.99998 3.2123 2.61186 10.99627 0.89395 -3.23746 10.99975 1.76078 -2.30683 5.2997 -0.9867799 2.30025 3.2e-4 -0.99998 2.30887 7.50036 -0.98328 -2.32838 9.09664 -0.9664999 2.34565 9.219861 -0.94769 3.30625 9.92307 0.20289 3.30676 10.56971 0.72338 16.80244 10.21738 0.39948 -2.3191 -1.65903 -0.89956 -2.29975 3.2e-4 10.00002 -2.3217 10.08648 -0.6967099 2.30311 9.91917 -0.7764099 2.54243 10.73518 0.2392399 -2.48352 10.76608 0.16778 2.60148 8.999361 -0.25303 2.55547 7.5018 -0.29981 2.59315 9.78928 -0.15286 5.15499 0.00225991 -2.3248 3.40026 3.2e-4 2e-5 5.07386 3.2e-4 -3.17212 4.39345 0.02717 -3.11122 4.96766 -0.61587 -5.85918 17.34274 6.79722 -0.13385 17.26482 9.028182 -0.14884 17.18981 9.87308 0.04524993 17.31603 10.44393 0.51954 17.06789 10.45824 0.64089 37.50025 2.19422 22.05426 37.40435 0.73243 20.1451 37.50909 3.57046 33.79905 37.50026 3.23185 35.25447 37.50021 3.75936 32.92622 37.50006 3.92558 32.07096 37.50026 4.06082 31.35498 37.50026 4.26847 29.53544 37.50026 4.21362 27.70218 37.49462 3.94249 26.10388 37.50025 3.32473 24.15278 42 4.60716 30.81114 41.70798 3.88144 30.84091 41.61946 3.73011 28.65682 41.23909 3.51172 30.85785 40.9242 3.26715 28.67483 40.68318 3.30035 30.86494 40.01752 3.32974 28.77479 40.09034 3.37438 30.86367 41.94769 3.2e-4 19.36702 41.71842 -0.00575 20.01342 41.67065 2.00021 22.58903 41.14101 -0.0231499 20.675 39.83923 2.33243 24.11971 39.72058 0.01236999 20.58068 40.32361 -0.009799957 20.87785 40.82568 1.72519 23.15768 41.67065 3.29589 25.50533 40.82568 2.83887 25.81911 39.83923 2.94015 25.74441 39.83924 3.25593 27.19053 38.53032 3.82532 31.03301 38.97182 3.2e-4 20.13458 38.07147 3.2e-4 19.68671 38.71609 3.23855 25.0583 42.00026 -3.329 61.7503 42.00026 -2.68931 58.80988 42.00026 -2.01866 56.14605 42.00026 -1.33825 53.7342 42.00026 -0.66312 51.54677 42 0.01940995 49.44598 42.00026 0.90463 46.98814 42.00026 1.27223 45.9909 42.00026 2.64223 42.40157 42.00026 3.26882 40.78415 42.00026 3.80804 39.20903 42.00026 4.26056 37.45743 42 4.41831 35.70793 39.00605 10.99998 50.90361 40.77634 1.29834 41.78917 37.50026 2.06831 38.47021 37.50026 2.36053 37.78063 39.12905 2.10223 39.00677 40.75076 1.88919 40.25134 37.50026 1.7721 39.16009 40.80231 0.65552 43.46877 37.50026 1.47398 39.84916 37.50026 1.17579 40.53642 40.88453 0.006799936 45.22028 37.50026 0.87904 41.2211 37.50026 0.58421 41.90438 37.50026 0.29134 42.58811 37.50026 3.1e-4 43.27425 37.86468 -1.28829 46.67348 40.95145 -1.31296 49.00166 40.8881 -2.05795 51.15124 40.9055 -2.78022 53.51792 40.92114 -3.49185 56.08376 40.93563 -4.22286 59.0684 38.00026 -4.32987 56.00671 40.94827 -4.89696 62.31458 40.99276 -6.27097 69.4598 39.56744 -6.94584 69.68528 34.57989 -2.49604 47.51221 31.2798 -8.57772 66.95871 31.61232 -6.53616 57.16278 40.39569 3.1014 35.40696 39.23923 3.58346 31.84347 40.61332 2.37786 38.01184 37.50026 2.82658 36.56094 40.81791 3.10269 35.64901 41.35299 2.08151 40.32797 41.38855 3.3211 35.68163 41.89888 2.6874 40.56078 41.78449 3.78594 35.75154 41.42602 0.11571 45.58867 41.92104 0.6899 45.90022 36.98519 -10.49187 73.65435 40.50635 -9.57438 73.47957 40.05586 -10.39787 74.10015 39.10843 -10.81996 74.49618 34.98815 -10.54967 73.19113 40.75598 -9.05269 73.0357 33.17701 -10.60156 72.65687 40.74006 -8.1737 72.10389 33.82185 -9.33063 71.18477 40.78117 -7.47096 71.16957 40.90627 -6.78083 70.13558 33.58817 -8.448902 69.18836 41.62707 -0.92331 48.99156 41.68417 -3.34011 57.58212 41.73455 -5.01147 66.37409 41.13453 -8.96965 73.12194 41.55864 -6.3484 70.15403 41.40157 -8.820052 73.27262 41.60799 -8.70256 73.39331 41.87943 -5.99443 70.34275 41.7471 -8.55435 73.54315 41.88245 -8.39852 73.70246 41.01022 -9.77275 73.81822 35.06305 -10.90893 73.79316 34.055 -10.99969 74.02668 -34.39244 11.00066 18.74109 -19.54399 11.00031 39.92647 -15.61547 11.00031 37.17568 -16.99974 11.00031 50.35272 -19.99974 -3.07323 57.68965 -19.99974 -4.33871 56.89844 -19.99974 -5.60764 55.77404 -19.99974 -6.84118 54.29292 -19.99974 -7.99843 52.44464 -19.94339 8.57903 52.41387 -19.99974 7.99879 52.44456 -19.7647 9.164361 52.28874 -19.45675 9.721672 52.07313 -19.01309 10.22437 51.76247 -18.43685 10.6337 51.35898 -17.75019 10.90493 50.87818 -20.9757 6.66662 53.13669 -19.99974 6.81651 54.32783 -19.99974 5.56375 55.81978 -21.76647 5.15921 53.69042 -19.99974 4.28182 56.94116 -22.34637 3.51567 54.09646 -19.99974 3.01323 57.72006 -22.70031 1.77899 54.34429 -19.99974 1.78033 58.20073 -19.99974 0.57544 58.42724 -22.81889 -0.004569888 54.42732 -19.99974 -0.62254 58.42272 -22.69871 -1.79026 54.34317 -19.99974 -1.8346 58.18479 -22.34294 -3.52745 54.09406 -21.76038 -5.17257 53.68614 -20.96898 -6.67675 53.13199 -34.89827 10.93751 20.04468 -21.02757 10.85019 40.96528 -22.47069 10.4039 41.97576 -35.94353 10.52684 22.1564 -23.83393 9.67363 42.93031 -36.26926 10.29696 23.0083 -36.98425 9.50867 24.39766 -37.5463 8.92159 25.43557 -25.08009 8.6793 43.80288 -37.79276 8.57469 25.87788 -38.3259 7.55097 26.86639 -26.17513 7.44804 44.56965 -38.86015 6.57738 27.71237 -27.08917 6.01347 45.20966 -39.6272 5.08638 28.24948 -27.79724 4.41473 45.70546 -40.18956 3.4651 28.64325 -7.71932 9.42093 43.85449 -6.7816 8.39193 43.19789 -12.98907 3.1e-4 47.54441 -5.94083 7.17651 42.53286 -3.90136 3.1e-4 41.24137 -3.9784 -2.99969 41.23506 -3.9784 -10.99969 41.23506 -16.99974 -10.99969 50.35271 -17.49796 -10.95803 50.70156 -17.99345 -10.83033 51.04851 -18.44906 -10.62637 51.36753 -18.85875 -10.35427 51.65439 -9.879712 11.00031 45.3672 -8.75665 10.29449 44.58083 -19.22317 -10.01373 51.90957 -19.54042 -9.59498 52.13171 -19.7899 -9.101962 52.30641 -19.94936 -8.547182 52.41805 -10.53331 -10.99969 33.61712 -10.39859 0.006929934 33.55042 -11.19383 6.33192 34.07963 -10.50889 4.72718 33.60003 -13.11352 9.0764 35.4238 -14.30466 10.15367 36.25786 -19.54399 3.1e-4 39.92647 -12.06864 7.79271 34.69217 -19.55254 -11.00203 39.92437 -21.00856 -10.85341 40.95197 -22.44876 -10.41244 41.96041 -23.8161 -9.68477 42.91783 -25.0408 -8.75295 43.74733 -26.18835 -7.46677 44.55593 -27.15089 -5.95878 45.22414 -27.9874 -3.99307 45.73754 -5.21253 5.84098 42.12602 -4.69914 4.61927 41.82666 -9.84612 3.17395 33.60003 -4.37969 3.41569 41.53367 -4.11728 2.24397 41.40828 -9.454152 1.59322 33.60003 -4.0032 1.10051 41.28576 -9.21055 0.02210998 33.70506 -2.66889 -10.99969 58.10774 -0.27107 -10.99969 68.60695 11.95373 -10.99924 54.07261 14.65039 -10.99969 57.10166 11.26303 -11.00247 52.76605 10.93462 -11.00078 51.02588 10.92849 -10.99944 49.00001 11.21852 -10.99969 46.78524 11.69197 -10.99969 44.64638 12.28615 -10.99969 42.55488 8.89405 -10.99969 39.42825 -9.148612 -11.00002 33.85217 5.89719 -10.99969 35.93081 -9.23438 -10.99969 31.98067 -30.48229 -11.00002 24.31039 9.64666 -11.7272 34.63953 9.14133 -11.1812 36.89915 -9.14059 -2.99969 33.86269 -9.5621 -11.00002 33.51436 -9.72471 0.009139955 33.46122 -10.03276 -11.00002 33.42926 -18.49975 11.00032 3e-5 -21.19975 10.85058 -1.8088 -21.19975 11.00032 3e-5 -18.5 10.34273 -3.49771 -21.19975 10.40543 -3.5684 -21.19975 9.67698 -5.23087 -18.49975 8.534932 -6.93974 -21.19975 8.68505 -6.75093 -17.79844 10.99998 -0.002489984 -16.91649 9.68695 -3.50188 -15.54072 8.754961 -0.6660799 -15.55918 8.56459 -0.96403 -15.88354 9.44507 -0.80489 -21.20026 0.001449882 11.01394 -21.28766 0.02173 11.85505 -21.20044 10.99998 11.01762 -2.29975 4.68862 -0.95292 -2.59805 5.3017 -0.25482 -3.21332 9.000741 0.005569994 -2.55236 8.99997 -0.30387 -3.19026 5.3014 0.004939973 -3.30688 9.55089 0.05248993 -2.59264 9.78984 -0.1526499 -3.3059 10.27285 0.43032 -2.69517 11.00598 1.04606 -3.30505 10.99998 1.06113 -15.92924 10.33615 0.42254 -16.47413 10.36967 0.38119 -17.279 10.99998 1.29354 -16.91968 10.57752 -0.002319931 -14.65761 8.99585 -0.002359986 -14.94063 8.91659 -0.05849999 -15.34548 9.84637 0.19979 -15.65766 9.70758 -0.002089977 -15.17003 8.858922 -0.1529999 -15.94733 9.65974 -0.31976 -15.33845 8.81154 -0.32356 -15.48324 8.770522 -0.51661 -14.58253 7.93702 -0.006569921 -14.53943 8.47437 5e-4 -15.08167 7.9332 -0.17254 -15.41384 7.93282 -0.57846 -15.49975 7.93757 -0.99997 -14.58696 5.3001 0.005089998 -15.24522 5.30287 -0.29855 -15.49562 5.30014 -0.88208 -15.90167 8.695611 -3.82645 -15.49975 7.62971 -2.40672 -15.49975 7.07219 -3.74012 -15.90167 6.98317 -6.44123 -15.49975 6.28421 -4.951 -17.00111 7.33618 -7.64988 -15.49975 5.29115 -6.00057 -18.49975 7.30819 -8.22159 -15.90167 4.51484 -8.35875 -15.49975 4.1255 -6.85437 -17.00111 4.69491 -9.50243 -18.49975 5.89133 -9.28954 -18.49975 4.3212 -10.1158 -15.49975 2.82533 -7.48457 -15.90167 1.55781 -9.37144 -15.49975 1.43289 -7.87066 -17.00111 1.61866 -10.47455 -18.49975 2.63864 -10.6789 -18.49975 0.8875 -10.96415 -15.49975 -0.005999982 -7.99997 -15.90167 -1.56781 -9.36966 -17.00111 -1.60754 -10.47618 -21.19975 7.45665 -8.08719 -21.19975 6.02522 -9.20327 -21.19975 4.42972 -10.06875 -21.19975 2.71362 -10.66008 -21.19975 0.92363 -10.96116 -18.49975 -0.88677 -10.96415 -2.29975 -1.19968 -0.99998 -21.19975 -10.99968 12.00002 -21.19975 -10.99968 2e-5 -21.19975 -10.8493 -1.81266 -21.19975 -10.40283 -3.5741 -21.19975 -9.67123 -5.24033 -21.19975 -8.67606 -6.76166 -21.19975 -7.44421 -8.098072 -21.19975 -6.00708 -9.2147 -21.19975 -4.40793 -10.07804 -21.19975 -2.68749 -10.66654 -15.49975 0.08439999 -0.89748 -15.49975 -7.07442 -3.73469 -15.5383 -5.19961 -0.8982599 -15.49975 -7.63069 -2.40159 -15.49975 -6.28827 -4.94504 -15.49975 -5.2969 -5.99493 -15.49975 -4.13314 -6.84939 -15.49975 -2.83463 -7.48083 -15.49975 -1.44397 -7.86852 -21.19975 -0.89245 -10.96369 -15.54911 -8.07651 -0.98456 -18.5 -10.25767 -3.32629 -18.49975 -10.97317 -0.76319 -18.49975 -10.99968 2e-5 -18.49975 -8.53429 -6.93975 -18.49975 -7.30755 -8.22159 -18.49975 -5.89069 -9.28953 -18.49975 -4.32055 -10.11582 -18.49975 -2.63804 -10.67889 -17.27788 -10.65702 5e-5 -17.36909 -10.78195 0.7220001 -17 -9.92136 -3.43188 -16.07855 -9.68662 -0.56019 -16.69233 -10.37179 0.09990996 -15.90167 -8.69931 -3.81658 -17 -9.28786 -5.08862 -15.90167 -6.98984 -6.43329 -17.00111 -7.32789 -7.65721 -15.90167 -4.52369 -8.35361 -17.00111 -4.68476 -9.507122 -2.25981 -2.41399 0.05524992 -2.28917 -2.16863 9.28614 -1.91132 -2.18628 8.70037 -2.29975 -1.64968 10.00002 -2.30004 -11.00044 14.49994 -17.60893 -10.97441 1.55587 -2.29975 -10.99968 2.00002 -2.0171 -6.48071 8.789112 -2.29892 -6.49807 9.48269 -14.49975 -6.33126 2e-5 -3.29975 -5.19968 2e-5 -14.66082 -7.92152 0.001859903 -14.67584 -8.98036 -0.002439916 -2.29975 -8.99968 2e-5 -2.29975 -10.90406 1.38901 -2.29975 -10.61666 0.823 -2.29975 -10.17759 0.38369 -2.29975 -9.61116 0.09578996 -15.35954 -9.81387 0.16857 -16.29393 -10.41649 0.56217 -16.80311 -10.67837 0.91534 -15.30478 -8.81331 -0.28649 -15.68901 -9.705801 -0.0480799 -15.13338 -7.93045 -0.23262 -15.10497 -5.20571 -0.14485 -30.79928 10.99949 11.01068 -30.79975 11.00032 3e-5 -33.79974 11.00032 3e-5 -33.8092 11.00183 14.35476 -29.84198 10.99384 11.99814 -30.59873 10.98676 11.61281 -36.79974 -0.007789969 -7.99997 -36.79974 -1.3974 -7.87692 -36.79974 1.38282 -7.87961 -36.79974 2.73173 -7.51924 -36.79974 -2.74417 -7.51448 -36.79974 3.99724 -6.92995 -36.79974 -4.00772 -6.92353 -36.79974 5.14114 -6.12957 -36.79974 -5.14931 -6.12217 -36.79974 6.12841 -5.14259 -36.79974 -6.13455 -5.1345 -36.79974 6.92918 -3.99882 -36.79974 -6.93295 -3.99119 -36.79974 7.5187 -2.73382 -36.79974 -7.52079 -2.72632 -36.79974 7.87958 -1.38462 -36.79974 -7.88005 -1.37829 -36.79974 -7.99968 3e-5 -36.79974 8.00032 3e-5 -36.81443 -0.008089959 12.38541 -36.7967 3.53228 12.70871 -36.79967 7.1347 13.80731 -36.79974 8.00032 14.3549 -30.79856 -11.00002 11.02335 -30.79975 -10.99968 2e-5 -30.79975 -10.84952 -1.81135 -30.79975 10.85039 -1.80992 -30.79975 10.40469 -3.57055 -30.79975 -10.40324 -3.57293 -30.79975 9.67536 -5.23386 -30.79975 -9.67312 -5.23683 -30.79975 8.68226 -6.75451 -30.79975 -8.67907 -6.7578 -30.79975 7.45247 -8.091052 -30.79975 -7.44809 -8.0945 -30.79975 6.01951 -9.207001 -30.79975 -6.0136 -9.210452 -30.79975 4.42244 -10.07195 -30.79975 -4.41473 -10.07506 -30.79975 2.70481 -10.66232 -30.79975 -2.69563 -10.66448 -30.79975 -0.9032 -10.9628 -30.79975 0.91344 -10.962 -22.15526 0.007359921 11.99912 -29.86834 -11.00002 11.99651 -22.16006 10.99998 11.99842 -33.79974 -10.99968 2e-5 -33.79974 -10.47466 -3.49998 -33.79974 -8.52034 -6.95688 -33.79974 -7.29403 -8.233592 -33.79974 -5.87881 -9.29706 -33.79974 -4.31131 -10.11976 -33.79974 -2.63219 -10.68033 -33.79974 -0.88477 -10.9643 -33.79974 0.88549 -10.9643 -33.79974 2.63279 -10.68033 -33.79974 4.31196 -10.11974 -33.79974 5.87945 -9.29706 -33.79974 7.29467 -8.233592 -33.79974 8.52097 -6.95687 -33.8 10.20262 -3.50126 -33.79974 10.9746 -0.75178 -35.3938 10.77261 21.17249 -36.64715 -8.81307 26.97617 -38.85982 -6.57728 27.71215 -37.5093 -8.97024 25.36489 -35.21536 -9.8805 25.97361 -35.78766 -10.70378 22.41514 -33.65039 -10.60402 24.87781 -34.58218 -10.99969 19.69901 -38.93689 7.18572 20.70183 -38.32103 7.12673 19.06551 -39.02973 4.63813 17.88106 -39.97427 3.83272 18.59788 -38.75257 2.72742 17.02578 -40.5415 5.53276 21.42248 -38.65963 8.35522 23.49712 -40.50451 5.92099 24.8554 -38.76624 8.03745 24.72672 -40.83186 2.04116 19.19836 -38.70994 -0.01001 16.61259 -41.76626 2.94589 22.28006 -41.63396 3.10566 25.64625 -40.53284 1.75501 28.88361 -42.0234 0.007079899 25.91894 -42.19225 0.003619909 22.57835 -40.64822 8e-5 28.96441 -41.12955 -0.001779913 19.4068 -41.63728 -3.09212 25.64857 -40.53275 -1.75507 28.88355 -40.1894 -3.46507 28.64313 -41.7681 -2.93905 22.28136 -40.83067 -2.04447 19.19753 -38.65361 -2.75281 16.8334 -40.51082 -5.90924 24.85982 -39.62696 -5.08633 28.2493 -40.34552 -5.52707 21.42492 -39.97205 -3.83528 18.59632 -39.45963 -7.33046 24.22606 -38.99642 -6.80644 20.06094 -38.64497 -5.09668 17.59839 -38.54078 -6.84553 19.16336 -36.85474 -6.9e-4 12.8662 -36.8276 6.8699 14.41477 -37.17046 8.97825 18.0813 -36.94878 0.001249969 13.50854 -36.88181 3.44134 13.53781 -37.07059 8.2e-4 13.92412 -36.99055 6.43146 15.16721 -37.03085 3.32365 14.13068 -37.36453 4.3e-4 14.74741 -37.29959 8.25182 17.84789 -37.22893 3.20819 14.71189 -37.27509 6.01377 15.88424 -37.49868 3.09749 15.26971 -37.46149 8.891921 19.55739 -38.01134 -0.00702995 15.81522 -37.57735 5.71607 16.39532 -37.59179 7.81341 18.2093 -37.81487 2.99184 15.80115 -37.87581 8.755082 20.77565 -37.72676 9.17571 21.4162 -37.93076 5.43082 16.88496 -37.93949 7.38716 18.56075 -38.15658 8.820611 23.43726 -38.32058 2.86247 16.45829 -38.2977 8.201622 20.9743 -38.35055 5.17675 17.32112 -38.23787 8.66316 24.26988 -37.87741 8.8285 25.0882 -36.39843 -9.49824 3e-5 -36.69753 -8.776142 3e-5 -36.39861 -8.92548 -3.2487 -35.29974 -10.59776 2e-5 -35.92107 -10.121 2e-5 -36.39861 -7.27606 -6.10558 -35.29974 -7.48949 -7.49811 -36.39861 -4.749 -8.22603 -35.29974 -4.80793 -9.44454 -36.39861 -1.6491 -9.35431 -35.29974 -1.65636 -10.46776 -35.29974 1.65716 -10.46773 -36.39861 1.64974 -9.35431 -35.29974 4.80872 -9.44447 -36.39861 4.74964 -8.22603 -35.29974 7.49025 -7.49798 -36.39861 7.2767 -6.10558 -35.3 9.697001 -3.48608 -36.39861 8.92612 -3.2487 -36.72453 8.667881 3e-5 -36.47666 9.34764 -0.001729965 -36.14523 9.87079 3e-5 -35.67022 10.34581 3e-5 -35.1956 10.63941 -0.001009941 -34.46731 10.9251 3e-5 -34.93652 10.77807 14.35294 -35.58376 10.41524 14.35461 -36.21264 9.77333 14.35913 -36.54551 9.21337 14.35889 -36.74974 8.524291 14.35804 -35.6876 10.6461 18.53472 -36.53004 10.03759 18.28291 -36.51375 10.32512 21.99281 -36.95128 10.04975 21.78613 -37.3879 9.676671 21.55382 -30.54963 -11.00002 11.66705 -33.79976 -10.99968 14.35432 -36.80211 -3.57614 12.74256 -36.83413 -6.80393 14.48794 -36.79083 -7.04813 13.76283 -36.79802 -8.00355 14.36797 -36.85308 -8.2511 15.52943 -36.85374 -3.46387 13.32598 -36.98067 -3.33462 13.98191 -36.94965 -8.4689 16.47709 -36.98058 -6.44915 15.09954 -37.2118 -8.51306 17.67781 -37.17058 -6.12276 15.66232 -37.26193 -3.17345 14.8002 -37.16951 -8.873742 17.99794 -37.42837 -9.10094 19.63637 -37.50796 -5.75593 16.295 -37.6075 -7.75384 18.23821 -37.65326 -3.02726 15.54316 -37.73828 -9.155611 21.34813 -37.91945 -5.4259 16.86416 -38.33669 -8.166501 21.07709 -38.10238 -2.90063 16.18634 -38.15025 -7.1699 18.72193 -38.72624 -8.31356 23.17016 -38.38188 -5.17725 17.33244 -38.70362 -7.76277 21.09307 -38.28183 -8.521121 24.55593 -36.79264 -10.16235 21.86772 -35.07729 -10.92664 19.09571 -35.45325 -10.78913 18.5133 -35.89947 -10.55703 18.41647 -37.38953 -9.68077 21.55747 -36.47078 -10.08791 18.29239 -37.06798 -9.19611 18.17723 -34.48074 -10.91786 14.35774 -34.03627 -10.99969 16.91243 -34.34378 -10.99937 17.05174 -35.15562 -10.66385 14.35446 -35.06882 -10.81567 16.93252 -35.53715 -10.59231 16.85391 -35.98821 -10.04511 14.3575 -36.15683 -10.12153 16.75029 -36.41797 -9.45354 14.35341 -36.76658 -9.26479 16.64904 -36.69753 -8.77615 14.35433 -34.57621 -10.89746 2e-5 -35.29974 -9.68938 -3.36008 -33.88254 11.00032 15.89549 -34.0911 11.00032 17.35025 -1.46361 -10.99969 21.00948 -2.29974 -10.99968 17.78293 -2.29974 -11.00234 16.69962 -1.44589 -11.04272 16.30639 -2.29974 -1.03093 14.50002 -2.23293 3.2e-4 15.05038 -2.29974 3.2e-4 14.50002 -21.4021 10.99998 11.61422 12.5312 -10.58549 31.98531 16.64741 -13.38308 33.52113 22.43384 -2.43179 35.4638 21.78853 -2.89039 34.14166 22.43384 3.1e-4 35.4638 21.65439 3.1e-4 33.81064 21.3357 -3.4036 32.89512 21.10985 3.1e-4 32.06595 20.99578 -4.04728 31.53899 25.44507 -0.81405 36.97453 24.712 -1.22857 36.9809 25.15811 0.01659995 37.00175 24.26314 3.1e-4 36.89455 24.0104 -1.59847 36.81344 23.7072 3.1e-4 36.68168 23.36963 -1.92981 36.48375 23.20424 3.1e-4 36.36323 22.83476 -2.21207 36.02045 22.77413 3.1e-4 35.9518 26.92183 -0.003519952 36.82516 12.68278 -11.1535 40.6564 13.08471 -11.72125 38.31505 13.47464 -12.60679 36.32715 10.92894 -12.52152 33.74554 15.06748 -11.44301 37.1727 14.52405 -12.49547 36.58099 15.31516 -11.79939 36.40389 14.12754 -11.52959 38.50731 14.0189 -12.66681 36.52953 14.81115 -11.12672 38.0273 14.54371 -10.86076 38.96343 13.74406 -10.89054 40.62273 14.26397 -10.65805 39.96037 13.97252 -10.5293 40.97764 13.67023 -10.47681 41.968 13.28852 -10.5106 43.04077 12.63184 -10.60558 45.06305 12.07336 -10.70185 47.10023 11.36593 -10.94797 48.99927 11.70368 -10.78236 49.00006 16.57858 -9.282812 32.1871 15.60446 -9.66423 32.83175 16.32271 -8.59969 32.43644 16.27308 -8.07461 32.48607 15.75026 -8.074602 32.90342 15.16408 -8.074602 33.18879 14.55059 -10.15569 32.96592 14.52727 -8.074602 33.34115 13.86319 -8.074602 33.35082 13.46548 -10.48407 32.67463 13.19649 -8.074602 33.20858 12.57363 -8.074602 32.9161 15.74787 3.1e-4 32.90491 15.14261 3.1e-4 33.19639 14.48767 3.1e-4 33.34588 13.81588 3.1e-4 33.34588 13.16094 3.1e-4 33.19639 12.55568 3.1e-4 32.90491 14.00826 -13.53416 34.81597 16.81638 -15.27418 32.40682 15.12647 -14.0356 34.29336 15.84711 -13.60443 34.37607 15.89327 -12.56954 34.95239 11.73357 -10.92608 52.60124 11.55999 -10.87983 50.93766 12.53987 -10.94118 54.14971 14.98376 -10.93201 56.80618 17.00939 -11.00269 59.61676 22.76087 -10.99969 67.55108 26.29809 -10.03401 67.5 23.7424 -11.00002 68.4587 27.24411 -11.00002 70.83822 27.47768 -10.76175 70.15975 30.11902 -10.68794 71.44342 31.13271 -10.95601 72.55889 28.51817 -10.99969 71.69501 30.14903 -10.99969 72.51252 31.98543 -10.99969 73.29705 18.99706 -11.00134 62.1765 20.79791 -11.00002 64.63759 22.00057 -11.00002 66.67691 24.42076 -4.89193 45.53319 22.39955 -4.32243 42.36771 20.36497 -6.03566 44.81445 17.58012 -7.99503 48.14511 14.72139 -9.78387 51.55352 18.00202 -9.761631 55.00234 25.00082 -8.35501 56.99505 27.6925 -4.34221 46.92803 31.1672 -3.36012 47.48283 33.25978 3.1e-4 41.06783 15.86816 -8.3623 46.51122 20.13634 -4.13406 40.55924 14.39754 -9.204482 44.82517 18.38548 -6.26749 37.94863 17.21881 -8.33919 35.85539 16.77633 -10.93123 34.08899 4.37943 10.99998 41.38833 41.68114 3.11934 88.42472 41.68114 5.63812 90.39955 41.13099 3.312 88.37461 41.13099 5.74386 90.32435 37.7384 11.1753 88.8843 38.76384 7.94142 90.03388 37.95638 7.94142 89.22799 39.76155 5.63631 88.40637 40.51579 10.27552 97.62239 40.07596 9.96326 98.56784 41.37939 9.46742 96.43927 39.99857 10.43204 98.33806 40.57038 8.64119 95.29342 41.22685 8.93964 95.8138 40.70426 9.2523 97.00844 41.37984 8.73646 95.12654 39.74244 11.04698 96.20256 39.84858 11.04698 95.04393 38.24878 11.49697 95.45497 38.00381 11.49697 96.64929 39.39767 11.04699 97.44501 37.49107 11.49697 97.75499 38.76131 11.04699 98.70365 41.59571 8.83116 95.13356 41.2131 9.19201 96.43332 41.74747 9.009302 95.10453 41.8014 9.23127 95.04592 41.27328 9.94482 96.26662 41.7521 9.44767 94.97078 38.71717 10.68463 99.7013 38.0911 10.75973 100.2209 38.28223 10.27446 100.3477 37.96762 9.87593 100.1751 38.56969 9.8037 99.67538 39.20652 9.69696 99.05484 39.37949 10.57362 99.05593 39.80162 9.560872 98.36477 40.29893 9.41038 97.67668 40.93732 10.11112 96.92743 41.27329 10.02495 95.04329 39.91544 8.54095 95.21244 36.29012 9.10508 98.62049 37.81296 11.04698 99.873 39.37206 7.94142 90.84272 39.81881 7.94142 91.62484 40.13819 7.94142 92.36641 40.35844 7.94142 93.06499 41.13102 7.19214 93.23298 42.00056 7.30184 92.4242 42.00056 6.94657 91.57982 42.00056 6.38827 90.62459 42.00056 8.25571 93.05318 42.00056 7.7061 93.46572 37.11908 11.39697 89.68384 38.34981 11.34554 91.02043 39.50283 11.01932 91.70684 39.34713 11.17865 92.9042 38.87627 11.27726 91.90458 39.77678 11.04697 94.01065 41.55681 8.56278 94.71521 40.94661 8.50667 94.93193 41.33031 8.34255 94.60556 41.92306 8.79775 92.93055 41.80856 9.3299 94.73648 41.67596 7.07942 93.26065 41.80298 7.58719 93.89461 38.02941 11.49697 93.17299 38.21304 11.49697 94.23915 37.79654 11.49697 92.22731 37.12631 8.496972 90.33946 37.7612 8.496972 90.99005 38.24058 8.496972 91.64044 38.59385 8.496972 92.26857 38.84736 8.496972 92.86425 39.02299 8.496972 93.42589 40.72712 7.83903 94.26452 40.49448 7.94157 93.72605 41.37669 7.53031 93.96105 41.69064 8.16196 94.33181 39.58928 8.496972 95.04093 39.37226 8.49544 94.56347 39.13748 8.496972 93.95772 41.7727 8.656372 94.6345 41.94539 8.88449 94.20365 41.9566 8.2694 94.08396 41.98137 8.653962 94.05004 41.99392 8.3286 93.39334 25.58867 1.43357 87.00081 24.87012 1.27291 87.70231 24.87012 -0.003029882 87.59163 25.15486 -0.003029882 87.29075 25.45073 -0.003029882 87.00081 24.87012 2.37196 87.98259 25.99651 2.81535 87.00081 26.6527 4.08412 87.00081 25.33635 4.10292 88.26278 24.87012 4.09936 88.83101 27.50056 5.99697 87.00081 26.1579 6.16047 88.98506 28.00056 6.96932 88.11705 28.00056 7.74294 89.00081 27.50056 7.94142 89.74383 35.42382 7.14735 87.00081 34.05057 7.94142 87.46534 34.05057 7.47344 87.00081 35.60876 7.94142 87.85357 36.69345 6.582 87.00083 36.91229 7.94142 88.47516 37.99923 5.63255 87.00083 38.95287 4.64133 87.00083 39.93123 2.916 87.00083 40.36637 1.65375 87.00083 40.5504 -0.003029882 87.00083 40.84626 -0.003029882 87.29077 41.13099 -0.003029882 87.59163 41.13099 1.27351 87.70243 41.13099 2.37288 87.98291 28.00056 8.496972 87.00081 31.96557 8.496972 87.00081 28.00056 8.496972 89.00081 30.09208 11.39697 88.93673 28.26272 11.26217 88.8843 31.49381 11.39697 88.44628 33.00006 11.39697 88.27532 34.50645 11.39697 88.44607 35.13641 10.99697 85.43849 37.16936 10.99697 86.13395 35.90857 11.39697 88.9365 24.31998 3.11935 88.42472 24.32517 -0.003029882 87.70771 24.05718 -0.003029882 87.48596 24.21422 -0.003029882 87.66474 24.43612 -0.003029882 87.75068 24.6726 -0.003029882 87.72432 41.56501 -0.003029882 87.75068 41.7869 -0.003029882 87.66474 41.94394 -0.003029882 87.48597 41.32852 -0.003029882 87.72432 33.00057 11.49528 88.98594 34.05057 8.496972 88.86506 35.28151 8.496972 89.20881 34.03556 8.496972 87.00081 24.87013 -8.00303 87.59163 25.09139 -9.0346 87.35697 25.63093 -9.82743 86.83525 25.45073 -4.00303 87.00083 26.38597 -10.3084 86.21868 27.08407 -4.00303 85.72747 27.26143 -10.50303 85.61666 28.3819 -10.50303 85.01744 28.11167 -9.00303 85.14695 28.47897 -9.4878 84.9731 28.11167 -6.00303 85.14695 28.58706 -5.67444 84.92507 28.92677 -5.46536 84.78298 28.93422 -4.00303 84.78002 29.25148 -5.29607 84.65947 28.9567 -10.02226 84.77111 29.55905 -10.49865 84.5542 29.72197 -5.11393 84.50078 30.4356 -5.00303 84.30406 30.93008 -4.00303 84.19744 32.1382 -5.00303 84.03469 33.00057 -4.00303 84.00083 33.86293 -5.00303 84.03469 35.07105 -4.00302 84.19744 35.56553 -5.00302 84.30406 36.24842 -5.10488 84.49124 36.85765 -5.34857 84.69922 37.06691 -4.00302 84.78002 37.39911 -5.66466 84.91852 38.7397 -10.50303 85.61666 37.88945 -6.00302 85.14695 37.88945 -9.00303 85.14695 37.61948 -10.50303 85.01755 38.91706 -4.00302 85.72747 39.68599 -10.5013 86.22204 40.35194 -9.84937 86.81808 40.5504 -4.00302 87.00083 40.90894 -9.0365 87.35614 41.13099 -8.00303 87.59163 30.96395 -5.00303 84.67029 35.03717 -5.00302 84.67029 31.4016 -5.00303 85.13996 34.59953 -5.00303 85.13996 31.72967 -5.00303 85.69278 34.27146 -5.00303 85.69278 31.93231 -5.00303 86.30226 34.06882 -5.00303 86.30226 32.00057 -5.00303 86.93856 34.00057 -5.00303 86.93856 33.00057 -10.00303 85.00083 33.00057 -10.00303 85.40252 31.33445 -10.00303 85.05361 31.61989 -10.00303 85.47597 33.00057 -10.00303 85.74328 31.82955 -10.00303 85.94014 33.00057 -10.00303 86.01088 34.04364 -10.00303 86.43206 31.95749 -10.00303 86.43202 34.00057 -10.00303 86.93856 32.00057 -10.00303 86.93856 37.41134 -6.00302 84.98121 37.41122 -9.00303 84.98118 36.90551 -6.00302 84.94082 36.90544 -9.00303 84.94084 36.40688 -6.00302 85.02871 36.40681 -9.00303 85.02874 35.94649 -6.00302 85.23889 35.94644 -9.00303 85.23892 35.5536 -6.00302 85.55789 35.55355 -9.00303 85.55793 35.25326 -6.00302 85.96547 35.25317 -9.00303 85.96562 35.0646 -6.00302 86.43654 35.06454 -9.00303 86.43677 35.00057 -6.00302 86.93856 35.00057 -9.00303 86.93856 28.58979 -9.00303 84.98121 28.58979 -6.00303 84.98121 29.09562 -9.00303 84.94082 29.09562 -6.00303 84.94082 29.59425 -9.00303 85.02871 29.59425 -6.00303 85.02871 30.05464 -9.00303 85.23889 30.05463 -6.00303 85.23889 30.44753 -9.00303 85.55789 30.44753 -6.00303 85.55789 30.74787 -9.00303 85.96547 30.74787 -6.00303 85.96547 30.93653 -9.00303 86.43654 30.93653 -6.00303 86.43654 31.00056 -9.00303 86.93856 31.00056 -6.00303 86.93856 30.28887 -5.29592 85.04183 31.02681 -5.29592 85.86539 31.29344 -5.29593 86.93856 31.07668 -5.62035 86.93856 31.61786 -5.07915 86.93856 36.74865 -5.30497 84.66201 35.71718 -5.29592 85.03849 34.97572 -5.29592 85.86277 34.38325 -5.07915 86.93856 34.70768 -5.29592 86.93856 34.92445 -5.62034 86.93856 28.79139 -9.246252 84.91934 29.54059 -9.511981 84.86864 30.07767 -9.70493 84.92412 30.96474 -9.71013 85.7556 31.02918 -9.982001 85.01441 30.74658 -9.92569 84.99267 30.4782 -9.84499 84.9712 31.61788 -9.92691 86.93856 31.29346 -9.71013 86.93856 31.07668 -9.38571 86.93856 24.67261 -8.00303 87.72432 24.43612 -8.00303 87.75068 24.21422 -8.00303 87.66474 24.05718 -8.00303 87.48597 41.3285 -8.00302 87.72431 41.56498 -8.00302 87.7507 41.78688 -8.00302 87.66475 41.94394 -8.00302 87.48597 38.77465 -10.75303 85.55951 40.47097 -9.98157 86.87934 41.13404 -9.193262 87.46949 39.76203 -10.62444 86.18592 40.69175 -10.17119 86.83069 41.38859 -9.29184 87.43207 38.86145 -10.9194 85.41758 40.84677 -10.23448 86.72433 41.68918 -9.29155 87.14128 39.99669 -10.79865 85.9662 27.131 -10.93604 85.40339 29.47736 -10.85658 84.42583 27.21588 -10.77336 85.54217 31.95056 -10.85241 83.89984 33.00057 -10.6697 84.02233 30.52545 -10.61703 84.28743 33.00057 -10.97928 83.70178 34.05057 -10.85241 83.89984 36.52377 -10.85658 84.42583 24.91575 -9.16382 87.46038 26.28875 -10.54603 86.2146 25.42461 -10.08604 86.87477 24.71859 -9.25626 87.46589 26.16107 -10.70809 86.13066 25.2418 -10.2036 86.79393 24.53492 -9.30571 87.39328 26.00711 -10.79692 85.97328 25.07019 -10.24095 86.64248 24.36523 -9.30825 87.23494 33.00057 -10.40319 84.16567 31.21358 -10.32127 84.33208 33.00057 -10.18686 84.38906 31.26853 -10.1721 84.6602 33.00057 -10.04902 84.66846 37.21085 -9.246252 84.91934 37.52327 -9.4878 84.9731 37.04554 -10.02226 84.77111 36.46165 -9.511981 84.86864 36.4432 -10.49865 84.5542 35.92458 -9.70493 84.92412 35.52404 -9.84499 84.9712 35.47679 -10.61703 84.28743 35.25566 -9.92569 84.99267 34.97306 -9.982001 85.01441 34.73371 -10.1721 84.6602 34.78867 -10.32127 84.33208 34.66779 -10.00303 85.05361 34.92445 -9.38571 86.93856 34.70768 -9.71013 86.93856 35.03751 -9.71013 85.7556 34.38325 -9.92691 86.93856 34.17269 -10.00303 85.94014 34.38235 -10.00303 85.47597 34.00057 -5.00303 93.26877 32.00057 -5.00303 93.26877 34.23295 -5.00303 94.09375 32.37708 -5.00303 94.21898 32.77805 -5.00303 94.0259 33.22309 -5.00303 94.0259 33.62406 -5.00303 94.21898 31.63453 -5.07242 94.00083 34.27405 -5.02203 94.5056 32.0996 -5.00303 94.56694 33.90154 -5.00303 94.56694 31.83087 -5.00303 94.92147 34.17026 -5.00303 94.92148 32.00057 -5.00303 95.00083 34.00057 -5.00303 95.00083 34.08618 -5.00303 95.44345 31.92156 -5.00303 95.45932 33.86829 -5.00303 95.49787 32.13484 -5.00303 95.50135 33.50329 -5.00303 95.86528 33.76625 -5.00303 95.88864 32.24623 -5.00303 95.8983 32.50175 -5.00303 95.86753 33.00279 -5.00303 96.00081 33.28202 -5.00303 96.13891 32.7353 -5.00303 96.1428 35.00057 -9.00303 94.00083 35.00094 -6.00302 94.00081 31.00056 -9.00303 94.00083 31.00056 -6.00303 93.96101 31.30198 -5.28749 94.00083 31.07899 -5.61481 94.00083 31.0055 -6.00303 94.1412 34.4322 -5.1104 94.23588 34.69915 -5.28749 94.00083 34.92214 -5.61481 94.00083 34.86658 -9.50305 94.00083 34.50055 -9.869071 94.00083 34.00057 -10.00303 94.00083 32.00057 -10.00303 94.00083 31.50056 -9.86905 94.00083 31.13453 -9.50303 94.00083 31.26325 -5.33823 94.1848 31.07251 -5.64578 94.15258 34.73787 -5.33821 94.18481 34.92861 -5.64577 94.15258 31.18788 -5.27567 95.41165 30.89816 -5.9457 95.54119 31.8406 -5.27567 96.45308 31.67032 -5.9457 96.71621 33.00056 -5.9457 97.17156 33.00056 -5.27567 96.85948 34.33081 -5.9457 96.71621 34.16051 -5.27567 96.45308 35.10297 -5.9457 95.54119 34.81324 -5.27567 95.41165 34.00057 -10.00303 95.50083 32.00057 -10.00303 95.50083 35.10297 -8.9457 95.54119 30.89816 -8.9457 95.54119 31.67032 -8.9457 96.71621 33.00056 -8.9457 97.17156 34.33081 -8.9457 96.71621 24.87012 5.2965 89.82287 27.50056 8.496972 92.08535 28.88205 11.39697 89.68384 24.31998 5.63814 90.39956 30.26184 11.49697 89.71026 31.3016 11.49697 89.29082 26.6541 11.17867 92.90397 26.49829 11.01932 91.70685 27.65125 11.34554 91.02054 24.37461 9.636342 95.45105 24.19308 9.23127 95.04592 24.6186 9.77928 96.36007 24.24902 9.44767 94.97078 24.8701 7.19214 93.23297 25.26737 7.83903 94.26452 24.61778 7.53031 93.96105 24.30384 8.16196 94.33181 24.67039 8.34236 94.60522 25.43079 8.64121 95.29347 26.07904 8.54095 95.21244 26.62222 8.49544 94.56346 24.44224 8.559862 94.71041 24.61463 8.73646 95.12652 24.247 9.009302 95.10453 24.22178 8.656372 94.6345 24.04909 8.88449 94.20365 24.17456 9.29202 94.66218 24.14427 8.20532 94.23194 29.8249 8.6999 97.51353 33.00056 8.55728 98.13482 29.711 9.10508 98.62049 26.88909 7.94142 90.46917 26.4198 7.94142 91.18251 26.06698 7.94142 91.86851 27.97175 11.49697 93.17279 26.22435 11.08882 94.01065 27.78809 11.49697 94.23915 28.20463 11.49697 92.22714 27.12495 11.27728 91.90441 28.50539 11.49697 91.41564 28.88949 11.49697 90.7632 29.35241 11.49697 90.29109 29.39829 11.04698 100.825 30.76811 11.04697 101.4749 30.42106 11.49197 99.79165 30.72988 11.48798 100.0102 30.2146 11.49697 99.47166 28.19325 11.04699 99.87802 29.26237 11.49697 98.71241 27.24331 11.04699 98.70907 28.51005 11.49697 97.75497 26.6052 11.04699 97.4496 27.9973 11.49697 96.64927 26.25925 11.04698 96.20579 27.75234 11.49697 95.45497 26.15255 11.04698 95.04558 30.40465 9.968562 101.5481 29.89149 10.38171 101.6682 29.13401 9.951332 100.9168 31.94006 9.968562 101.9637 31.93259 10.38028 102.2918 30.36637 10.85606 101.6447 24.97374 9.09237 96.37292 25.78238 9.4337 97.78476 24.59157 9.572001 96.42621 25.92516 9.96326 98.56782 24.72783 9.94483 96.26661 25.35801 10.22999 97.42498 25.77964 10.36962 98.04489 26.28375 10.50161 98.68008 27.71889 10.27446 100.3477 27.03176 9.74083 99.29841 27.4672 10.70933 99.86162 28.15173 9.88731 100.2647 28.03297 10.77157 100.3141 29.05452 10.83815 100.9923 24.54014 9.80788 95.89679 24.43612 7.03771 93.27092 24.1915 7.58718 93.8946 24.00056 7.87464 93.62245 24.87012 6.30682 91.12614 24.00056 8.3286 93.39332 24.72783 10.01128 94.47571 24.72783 10.0246 95.09308 24.72783 10.00166 95.68509 29.66201 9.49194 99.7704 30.45559 9.65113 100.6214 33.00057 11.49697 95.12439 33.00056 8.496972 95.00081 36.30628 8.496972 89.72613 37.11116 11.49697 90.76256 36.64871 11.49697 90.29109 37.49569 11.49697 91.41555 35.73919 11.49697 89.71022 34.6994 11.49697 89.29078 36.60886 11.04698 100.8213 36.99772 10.83605 100.9621 35.23964 11.04697 101.4726 35.57732 10.85606 101.6672 35.0466 10.85606 101.8487 33.7631 11.04697 101.8064 33.82334 10.85606 102.1003 32.24501 11.04697 101.8072 34.30502 9.65113 101.0324 35.54827 9.65113 100.6214 35.01686 9.968562 101.7492 33.81138 9.968562 101.9972 33.00053 9.65113 101.1718 36.67593 8.71842 97.57588 36.4425 9.96396 101.1531 36.33852 9.492382 99.77202 36.10963 10.38171 101.6682 34.06853 10.38028 102.2918 32.5399 10.85606 102.133 33.00056 11.48798 100.5008 35.58015 11.49197 99.79156 35.27124 11.48798 100.0102 35.78653 11.49697 99.47166 36.73875 11.49697 98.71241 34.13903 11.48798 100.3768 31.83903 11.48798 100.3768 31.34895 10.85606 101.9544 31.69602 9.65113 101.0324 9.72146 11.00031 54.88706 30.6346 10.99998 64.29273 -1.22348 10.99998 31.37401 2.1925 11.00015 12.22485 39.01376 10.99859 12.24818 -22.29964 11.0002 21.38512 -28.44713 -2.03133 46.05944 -28.60279 3.1e-4 46.16707 -28.28 2.69548 46.0435 33.00057 -5.00303 95.00083 -2.3 -12.43498 14.32028 -2.3 -12.45382 14.27587 2.3 -12.45382 14.27587 2.3 -12.43498 14.32028 2.18743 -12.13355 15.03102 -2.18743 -12.13355 15.03102 -1.860739 -11.86163 15.67219 1.351906 -11.64583 16.18102 1.012173 -11.57242 16.35412 -1.012173 -11.57242 16.35412 1.860739 -11.86163 15.67219 -1.351906 -11.64583 16.18102 2.3 10 12 -2.3 10 12 2.3 10 14.32028 -2.3 10 14.32028 -2.18743 10 15.03102 1.351906 10 16.18102 -0.7107391 10 16.50771 0.7107391 10 16.50771 0 10 16.62028 -1.860739 10 15.67219 -1.351906 10 16.18102 1.860739 10 15.67219 2.18743 10 15.03102 2.3 16.79629 9.84629 2.3 15.71331 11.5 2.3 10.5 11.5 2.3 -4.871968 -18.94158 2.3 -1.858257 -19.47126 2.3 -18.13919 -7.216807 2.3 -19.03544 -4.291101 2.3 -19.46297 -1.261211 2.3 1.201211 -19.52297 2.3 4.231101 -19.09544 2.3 7.156807 -18.19919 2.3 9.906291 -16.85629 2.3 12.41184 -15.09982 2.3 -16.79629 -9.96629 2.3 -15.03982 -12.47185 2.3 -12.91301 -14.67178 2.3 -15.33123 11.89716 2.3 -16.45193 10.40824 2.3 -17.88697 7.705715 2.3 19.41126 -1.918256 2.3 19.46297 1.141211 2.3 19.03544 4.171102 2.3 -10.46824 -16.51193 2.3 -7.765715 -17.94697 2.3 -18.88158 4.811968 2.3 -19.41126 1.798256 2.3 14.61178 -12.97301 2.3 16.45193 -10.52824 2.3 17.88697 -7.825716 2.3 18.88158 -4.931968 2.3 18.13919 7.096807 -2.3 -15.33123 11.89716 -2.3 -19.03544 -4.291101 -2.3 -19.46297 -1.261211 -2.3 -19.41126 1.798256 -2.3 -18.88158 4.811968 -2.3 -12.91301 -14.67178 -2.3 -15.03982 -12.47185 -2.3 9.906291 -16.85629 -2.3 7.156807 -18.19919 -2.3 16.79629 9.84629 -2.3 4.231101 -19.09544 -2.3 -17.88697 7.705715 -2.3 -16.45193 10.40824 -2.3 -10.46824 -16.51193 -2.3 -16.79629 -9.96629 -2.3 -18.13919 -7.216807 -2.3 1.201211 -19.52297 -2.3 -1.858257 -19.47126 -2.3 15.71331 11.5 -2.3 10.5 11.5 -2.3 -4.871968 -18.94158 -2.3 -7.765715 -17.94697 -2.3 16.45193 -10.52824 -2.3 14.61178 -12.97301 -2.3 12.41184 -15.09982 -2.3 18.13919 7.096807 -2.3 19.03544 4.171102 -2.3 19.46297 1.141211 -2.3 19.41126 -1.918256 -2.3 18.88158 -4.931968 -2.3 17.88697 -7.825716 0.7107391 -11.19262 16.50771 0 -10.91424 16.62028 -0.7107391 -11.19262 16.50771 0 10 16.62028 0 -10.91424 16.62028 0 10 16.62028 0 -10.91424 16.62028 -35.30011 -21.37407 2.664984 -35.97731 -21.20598 2.742392 -35.70959 -20.85117 1.618092 -35.02501 -20.86087 1.319399 38.11269 -16.77327 0.6647549 40.2939 -16.31673 1.727976 39.90214 -16.63072 2.221127 37.91038 -17.23445 1.797287 41.94008 -10.54336 1.578489 42.01488 -10.96195 1.451645 41.97507 -10.79425 0.8358975 41.72119 -10.58321 0.8395424 -36.81101 -7.389069 3.04854 -36.75496 -7.258225 3.157454 -36.67926 -7.313999 1.528969 -36.68202 -7.420315 1.201839 41.10294 -16.78622 4.278839 40.2374 -17.22068 4.519073 -36.58536 -7.154157 3.076866 -36.40228 -7.313403 1.168158 -36.27677 -7.157767 2.975166 -35.185 -7.531498 0.9172001 -22.81298 -8.782184 0.4782181 -20.01383 -8.669778 0.5382938 -19.81993 -8.744164 0.2190952 -24.43715 -8.720823 0.1978855 -16.09681 -8.293219 0.5968685 -16.12562 -8.446867 0.2116146 -12.84886 -8.080644 0.5868664 -12.8592 -8.182985 0.1892279 -9.338077 -8.016757 0.5790596 -9.317935 -8.080241 0.1771926 -6.337596 -8.006975 0.5768795 -6.294147 -8.060143 0.173912 -2.522725 -8.022829 0.5748329 -2.491111 -8.029641 0.5728569 -2.505342 -8.080093 0.1727465 -2.534631 -8.074892 0.1731433 13.6234 -14.85789 0.2437191 20.02013 -16.21984 0.2199363 20.85444 -16.52285 0.02615922 17.34719 -16.45209 0.03100204 41.7199 -10.48944 1.784672 40.50849 -11.12467 0.8333645 -35.75578 -20.61316 1.398182 -34.914 -20.4599 0.7471657 -33.06443 -20.41025 0.4845829 -33.22402 -20.86695 1.118732 -29.78455 -20.38779 0.395258 -29.92773 -20.84934 1.005392 -25.80159 -20.38117 0.3758431 -25.91128 -20.83986 0.9682675 -21.62747 -20.38028 0.3758526 -21.63793 -20.84203 0.9770756 -17.45075 -20.38723 0.3872757 -17.37379 -20.87199 1.023111 -13.26461 -20.4174 0.4119663 -13.14162 -20.94333 1.099493 -9.211578 -20.4849 0.4067383 -9.162447 -21.01774 1.120949 -5.891845 -20.60078 0.3765431 -5.933184 -21.09855 1.10078 5.08159 -22.30381 0.1192588 6.227774 -22.29838 0.1060276 6.069337 -22.35332 0.751709 4.871313 -22.35009 0.797905 8.589437 -22.28036 0.08058166 8.513025 -22.35177 0.6742153 11.18799 -22.2173 0.06914329 11.15043 -22.30648 0.6414452 14.75098 -21.73004 0.1048717 16.66975 -21.39739 0.1352386 16.77512 -21.63473 0.94174 14.80499 -21.89464 0.8165684 20.42124 -20.87202 0.1748484 20.5043 -21.24291 1.096138 24.30422 -20.34383 0.2137432 24.31791 -20.81227 1.23002 27.83371 -19.68346 0.2604694 27.77166 -20.19741 1.348465 31.38448 -18.78649 0.310812 31.2583 -19.31107 1.463882 34.92764 -17.74555 0.3874893 34.75664 -18.25953 1.59688 37.9792 -18.09053 4.439198 34.79686 -19.20944 4.223764 31.32444 -20.29726 3.959854 27.85016 -21.18588 3.711298 24.40685 -21.73073 3.467194 20.73389 -21.95685 3.200054 17.25472 -22.04796 2.90728 13.12774 -22.27361 2.241177 11.12869 -22.3437 2.103764 12.91604 -22.1943 0.6663036 8.193588 -22.36276 2.107037 5.44805 -22.3448 2.222803 -4.616034 -21.82497 2.57395 -6.096391 -21.79971 2.583603 -4.345522 -21.14738 1.078341 -9.120854 -21.73867 2.602667 -12.96807 -21.63535 2.611956 -17.28125 -21.50387 2.564613 -21.71512 -21.4381 2.519438 -26.13951 -21.42959 2.499756 -30.21177 -21.44248 2.53014 -33.52912 -21.44941 2.597425 7.161726 -11.42326 49.89167 6.612938 -11.26008 51.49803 5.569353 -11.2263 51.70843 5.467674 -11.36983 49.88853 1.236763 -11.21067 49.42605 1.450103 -11.17832 50.75915 1.122014 -11.17747 50.5755 0.9234281 -11.20508 49.36167 -2.998834 -11.1718 48.61708 -2.961502 -11.17248 49.74878 -3.792537 -11.17069 49.79266 -3.802937 -11.16122 48.80295 -4.478267 -11.16244 49.87395 -4.657793 -11.13532 49.09914 41.93324 -10.57216 2.857588 41.98825 -10.75702 2.74156 41.95855 -10.98351 4.509445 41.99311 -11.19508 4.467781 41.96268 -11.55174 6.514654 41.99416 -11.76373 6.487608 41.96529 -12.20895 8.647776 41.99486 -12.40609 8.60363 41.96702 -12.87652 10.7005 41.99507 -13.0395 10.66644 41.96765 -13.38439 12.22506 41.99471 -13.4834 12.26416 41.9675 -13.64232 12.953 41.99407 -13.67916 13.07407 41.9669 -13.75352 13.20258 41.994 -13.75844 13.37009 41.89118 -10.42181 2.247049 41.93331 -10.57589 3.02527 41.94048 -10.97792 4.555925 41.94424 -11.53519 6.515211 41.94771 -12.18173 8.623154 41.95024 -12.83183 10.61734 41.95156 -13.33703 12.08548 41.95181 -13.61532 12.81659 41.95069 -13.73764 13.07428 26.02302 -16.07624 0.4377651 26.3522 -16.08447 0.499691 29.84541 -15.69423 0.6405029 29.34267 -15.74365 0.5811462 26.27949 -16.13967 0.5398331 29.41123 -15.76641 0.6598072 20.14659 -16.22975 0.3196659 21.06664 -16.46275 0.3703251 13.6891 -14.86659 0.3447418 17.2593 -16.101 0.3284283 4.440995 -11.15825 0.4163571 4.604897 -11.21737 0.536789 -2.517033 -8.003519 0.8194389 -2.484516 -8.011053 0.8161965 -9.34961 -7.990362 0.8210831 -6.501586 -7.987305 0.821764 -12.47713 -8.016142 0.8150692 -14.56205 -8.099836 0.7908325 -36.62672 -7.096894 4.834517 -36.4638 -7.053176 4.826397 -36.62275 -7.14702 6.31308 -36.46748 -7.106049 6.434866 -36.59059 -7.376173 8.315487 -36.42646 -7.337852 8.49055 -36.52581 -7.731776 11.31255 -36.34142 -7.68582 11.3981 -36.39369 -7.932583 14.05481 -36.2031 -7.902624 14.0451 -36.16974 -7.988173 15.82449 -36.08687 -7.966431 15.41235 -36.78794 -7.238184 4.771656 -36.79005 -7.304385 6.22394 -36.7719 -7.528042 8.318363 -36.73683 -7.822225 11.22915 -36.65214 -7.972874 13.82385 -36.45269 -8.016242 15.58446 -36.11119 -8.042043 16.8157 -35.83333 -8.013924 17.10123 -35.56558 -8.085133 17.91298 -35.22872 -8.049141 18.27757 -34.86817 -8.159539 18.98327 -34.384 -8.110838 19.50989 -32.94842 -8.307463 21.32121 -33.41526 -8.187998 20.73011 -34.49135 -8.236886 19.49442 -33.46362 -8.301357 20.72789 -33.63431 -21.69362 4.549654 -35.40287 -21.56243 4.341482 -33.49949 -21.54011 6.201679 -35.31956 -21.36517 5.95484 -33.28257 -21.10568 7.761314 -35.16823 -20.91771 7.581161 -33.06198 -20.48688 9.445326 -35.00679 -20.31765 9.237537 -32.82676 -19.78359 11.11652 -34.84514 -19.64111 10.79299 -32.56769 -19.04952 12.64141 -34.6817 -18.92238 12.17627 -32.24787 -18.26895 14.06724 -34.48963 -18.12374 13.48506 -31.85117 -17.40155 15.50278 -34.25033 -17.19833 14.85775 -31.41118 -16.49682 16.93528 -33.98197 -16.26469 16.19871 -30.86548 -15.60472 18.36082 -33.58787 -15.41574 17.43831 -30.12353 -14.59557 20.07506 -32.94009 -14.56047 18.78559 -29.16137 -13.28969 22.54388 -31.95442 -13.55313 20.60372 -28.24903 -11.68883 25.60439 -30.56924 -12.37402 23.07419 -26.66453 -11.2261 28.08129 -28.76291 -11.38232 25.59183 -30.32892 -21.71086 4.692966 -30.19079 -21.58539 6.38698 -29.98786 -21.16348 7.909922 -29.81719 -20.53598 9.655451 -29.61438 -19.81797 11.49886 -29.35424 -19.07382 13.25155 -29.00868 -18.30902 14.88243 -28.57906 -17.51688 16.40454 -28.08492 -16.69007 17.88909 -27.48873 -15.81365 19.4493 -26.76028 -14.74941 21.43992 -25.89497 -13.36833 24.39558 -24.91511 -11.94825 28.12407 -23.74046 -11.25164 31.33893 -26.28162 -21.70243 4.751694 -26.19053 -21.58473 6.465343 -26.03165 -21.16567 7.982695 -25.93095 -20.5287 9.798136 -25.7988 -19.79501 11.8049 -25.58779 -19.02635 13.81056 -25.282 -18.24186 15.71988 -24.93131 -17.48763 17.38769 -24.541 -16.73769 18.90348 -24.0322 -15.90733 20.5427 -23.39724 -14.87348 22.67848 -22.72778 -13.56697 25.73924 -22.1119 -12.28126 29.48116 -21.53761 -11.51972 32.81029 -21.00465 -11.24959 34.94894 -22.26935 -11.10422 33.9202 -21.86145 -21.70876 4.763004 -21.91417 -21.5855 6.480406 -21.87053 -21.16195 8.011705 -21.83417 -20.51289 9.885994 -21.75269 -19.76049 12.01123 -21.57889 -18.96048 14.22231 -21.30499 -18.13278 16.41209 -21.0412 -17.36784 18.29765 -20.82382 -16.67121 19.86373 -20.51482 -15.9003 21.53184 -20.06893 -14.94027 23.70562 -19.65364 -13.80625 26.56261 -19.41484 -12.71328 29.87424 -19.35526 -11.94166 33.04885 -19.45128 -11.54708 35.24667 -17.37312 -21.76919 4.689623 -17.55466 -21.61407 6.409542 -17.63945 -21.16862 7.99749 -17.67 -20.50785 9.91926 -17.63398 -19.7496 12.09075 -17.51952 -18.94899 14.3703 -17.30422 -18.11074 16.69655 -17.10604 -17.31567 18.79499 -17.02739 -16.61925 20.49926 -16.95327 -15.88821 22.2024 -16.80293 -15.02295 24.28839 -16.70928 -14.08278 26.7725 -16.72122 -13.15801 29.57964 -16.9755 -12.39051 32.42925 -18.18685 -11.862 34.67946 -13.01259 -21.8939 4.5198 -13.25778 -21.68047 6.232979 -13.44098 -21.18953 7.925114 -13.55748 -20.50988 9.90057 -13.54433 -19.7455 12.08819 -13.50317 -18.96345 14.34593 -13.43428 -18.18089 16.58761 -13.39584 -17.41121 18.67943 -13.47592 -16.68412 20.51261 -13.61296 -15.92344 22.34304 -13.71707 -15.11627 24.34671 -13.72703 -14.32421 26.52804 -13.49394 -13.47731 29.12257 -13.15874 -12.75873 31.55179 -9.213989 -21.99095 4.320826 -9.444961 -21.73699 6.029278 -9.642361 -21.21103 7.818623 -9.840244 -20.51507 9.823948 -9.797205 -19.73543 12.00654 -9.811623 -18.95024 14.23906 -9.955171 -18.2157 16.33741 -10.17356 -17.47457 18.30233 -10.45785 -16.70935 20.18147 -10.72708 -15.89086 22.14796 -10.74622 -15.09428 24.2276 -10.11993 -14.36083 26.58887 -8.959234 -13.47492 29.75427 -7.78652 -12.51241 33.35945 -6.313066 -22.03579 4.212561 -6.572788 -21.76304 5.912804 -6.821171 -21.22221 7.740869 -7.141098 -20.51812 9.730904 -7.043901 -19.72239 11.87527 -7.084663 -18.92053 14.06424 -7.42839 -18.19921 16.03834 -7.875904 -17.44457 17.91444 -8.317219 -16.64 19.8151 -8.553513 -15.77198 21.93812 -7.991435 -14.93458 24.42083 -6.06888 -14.18707 27.49698 -3.993188 -13.37483 31.15485 -3.030058 -12.52831 34.8143 -2.679989 -11.88906 37.93463 -5.260179 -11.76561 37.08031 -3.048668 -11.42895 40.67469 -4.419365 -11.37622 39.64513 -3.335678 -11.17205 43.40216 -4.586794 -11.03101 43.74386 -4.198322 -11.21456 41.3717 -3.702971 -11.08687 45.45313 -4.929506 -10.98159 45.83269 -3.770736 -11.12445 47.21876 -4.835072 -11.0593 47.62485 -4.90256 -22.04868 4.181139 -5.19279 -21.76968 5.87649 -5.493776 -21.2252 7.711784 -5.916909 -20.51994 9.67767 -5.771381 -19.72034 11.77725 -5.821372 -18.91473 13.91445 -6.285578 -18.19683 15.81439 -6.845972 -17.41558 17.67465 -7.323156 -16.58056 19.61864 -7.34659 -15.68038 21.91055 -5.959671 -14.78779 24.88821 -2.914312 -13.99746 28.64213 -0.7403982 -13.29729 32.32258 -0.3697909 -12.64936 35.51369 -0.8521655 -12.10239 38.24579 -1.546828 -11.64194 40.7782 -2.162509 -11.31676 43.19109 -2.637031 -11.18265 45.15727 -2.892631 -11.16754 46.93229 -2.599186 -19.81632 11.13044 -2.505284 -19.04213 12.91555 -3.137926 -19.07089 12.85494 -2.967586 -19.82085 11.14685 1.353678 -17.24962 18.73102 3.779271 -16.42411 22.0845 2.533208 -16.37174 21.67159 -0.5125179 -17.30455 18.08647 4.589026 -15.77458 24.77805 4.006723 -15.64866 24.6571 4.55863 -15.21243 27.18895 4.204599 -15.08311 27.20131 4.344059 -14.73354 29.63453 4.044514 -14.62376 29.69605 4.007811 -14.28928 32.12591 3.71534 -14.19065 32.20668 3.569865 -13.83402 34.62234 3.260134 -13.73824 34.70882 3.059531 -13.35043 37.12302 2.729572 -13.25586 37.2115 2.493083 -12.83209 39.65514 2.145679 -12.74005 39.74342 1.916209 -12.28807 42.24024 1.559409 -12.20441 42.31969 1.402332 -11.76229 44.84041 1.057292 -11.70155 44.89133 1.121293 -11.37018 47.31217 0.7995465 -11.34463 47.31543 7.936264 -22.20745 4.013002 4.927554 -22.17703 4.011955 7.950212 -21.9107 6.119356 4.709146 -21.80668 5.88965 8.24338 -21.57788 8.314259 4.812716 -21.30109 7.816393 8.813424 -21.24823 10.63368 5.286259 -20.71119 9.859704 9.810259 -20.96074 13.23676 6.465589 -20.11594 12.26828 10.60636 -20.69483 15.92372 7.570803 -19.60287 15.07797 11.09584 -20.44037 18.47469 8.50508 -19.2279 18.01737 11.27292 -20.11437 20.79997 8.909111 -18.87214 20.56171 11.31902 -19.68273 23.04287 8.960345 -18.42736 22.86718 11.36523 -19.17656 25.25642 8.928986 -17.90236 25.10999 11.42982 -18.59194 27.47038 8.905182 -17.31488 27.32307 11.4785 -17.86902 29.7668 8.903435 -16.6654 29.5557 11.44798 -16.9742 32.18213 8.882887 -15.97189 31.86319 11.12121 -15.94289 34.74478 8.652983 -15.27512 34.23242 10.24531 -14.8004 37.70924 7.997025 -14.52288 36.76848 9.167535 -13.54184 40.80737 7.058466 -13.65251 39.53998 8.421895 -12.488 43.3948 6.308364 -12.86992 42.14452 7.467833 -12.05999 45.40315 5.662557 -12.29035 44.57427 7.192803 -11.7565 47.47237 5.400252 -11.76523 47.15177 11.29141 -22.25764 4.234671 11.68488 -22.15949 6.67057 12.1451 -22.13179 9.135292 12.59427 -22.12653 11.55358 13.1365 -22.10903 14.03266 13.51677 -22.01366 16.45038 13.73996 -21.82071 18.76076 13.86176 -21.50956 21.00298 13.96519 -21.09398 23.21826 14.08627 -20.60088 25.39638 14.16302 -19.99044 27.56736 14.04099 -19.10376 29.83759 13.6224 -17.77049 32.3585 12.9129 -16.05868 35.41293 11.88367 -14.5055 39.14696 11.22711 -13.19093 41.94712 10.99132 -11.7676 44.27246 9.262909 -11.53849 46.12461 8.679059 -11.63292 47.54777 8.368472 -11.52432 49.10586 13.67987 -22.31238 4.61483 14.30659 -22.4492 7.231131 14.73847 -22.67075 9.730888 14.98744 -22.85956 12.07938 15.20856 -22.96379 14.39634 15.3883 -22.9423 16.66953 15.55128 -22.78449 18.9121 15.70268 -22.49674 21.13942 15.85886 -22.10121 23.33593 16.00703 -21.61551 25.46266 16.01684 -20.97786 27.5125 15.6298 -19.89334 29.65195 14.76568 -17.88511 32.33815 13.80947 -15.05079 36.23146 12.9622 -12.1977 41.90402 12.21831 -13.30841 41.36444 11.45508 -10.97672 44.26912 10.0326 -10.95388 45.52315 9.18474 -11.39536 46.73489 20.94557 -22.70824 5.631571 17.86835 -22.55486 5.41334 21.0481 -23.3579 7.917845 18.21051 -23.07836 7.812767 21.10231 -23.89685 10.1318 18.32175 -23.53222 10.0716 21.1503 -24.32473 12.37131 18.36937 -23.87111 12.31686 21.20141 -24.63205 14.65425 18.42781 -24.08399 14.58904 21.2576 -24.80459 16.95529 18.52226 -24.16659 16.87251 21.30218 -24.81248 19.21896 18.65787 -24.10986 19.14113 21.23154 -24.57151 21.39048 18.79716 -23.9017 21.35707 20.83161 -24.00028 23.45985 18.84715 -23.51282 23.47144 21.11734 -23.29006 24.58209 18.83909 -22.95549 25.31254 19.80482 -22.48366 26.26466 18.34665 -22.19298 27.01084 21.50403 -21.3598 25.75883 17.95197 -21.01152 28.26572 24.4722 -22.63317 5.873657 24.54682 -23.37091 8.094801 24.64755 -23.99362 10.27073 24.74739 -24.52226 12.48486 24.82077 -24.94331 14.73419 24.83892 -25.21681 16.95908 24.78623 -25.21856 19.04317 24.49672 -24.69516 20.98866 22.84243 -23.57034 23.47729 26.43498 -22.67524 21.82755 27.97394 -22.13621 6.16276 28.138 -22.91663 8.380322 28.32103 -23.5987 10.53221 28.48226 -24.20756 12.68997 28.5708 -24.71534 14.79865 28.58378 -25.01628 16.72187 28.80967 -24.80716 18.17724 29.75843 -23.72105 18.8944 31.48724 -21.24298 6.505793 31.69457 -22.02844 8.752724 31.90089 -22.73247 10.87632 32.04863 -23.37663 12.90975 32.07059 -23.90497 14.71453 32.06041 -24.1459 16.14177 32.68431 -23.63047 16.80489 34.96014 -20.1181 6.867506 35.16431 -20.86921 9.123514 35.32815 -21.54609 11.16023 35.36977 -22.1597 12.95196 35.16713 -22.67079 14.35411 34.6968 -23.00227 15.49002 38.1336 -18.94208 7.128994 38.30232 -19.65191 9.367857 38.39715 -20.28119 11.27499 38.28182 -20.84312 12.77792 37.65249 -21.40626 13.79478 40.40665 -18.0025 7.167845 40.51919 -18.70311 9.414122 40.53418 -19.32342 11.27445 40.11783 -19.95285 12.72747 37.89721 -21.214 14.38565 -36.0881 -21.33066 4.220787 -36.05186 -21.0993 5.824562 -35.96141 -20.64187 7.51071 -35.85749 -20.05537 9.168436 -35.74835 -19.40291 10.68301 -35.63321 -18.70693 12.02026 -35.50278 -17.91211 13.29751 -35.35233 -16.98262 14.63582 -35.19248 -16.08211 15.88281 -34.94097 -15.30672 16.95396 -34.48993 -14.60294 17.98092 -33.80134 -13.89195 19.14171 -32.97417 -13.23823 20.39732 41.32491 -17.5354 6.953783 41.40905 -18.24408 9.233017 41.45227 -18.84594 11.11261 41.38341 -19.27138 12.41116 40.9576 -19.5796 13.19855 40.67158 -19.45853 13.66543 36.7629 -21.12155 15.54278 39.98118 -19.14546 14.25811 34.46121 -21.01896 17.19146 39.62065 -18.0999 14.73878 30.94276 -20.81872 19.42435 42.02212 -11.24936 2.657364 42.0222 -11.6962 4.418465 42.02138 -12.24637 6.429634 42.02041 -12.83813 8.500488 42.01947 -13.36886 10.54647 42.01858 -13.66037 12.21734 42.01747 -13.74639 13.12822 42.01731 -13.78952 13.47634 -36.85607 -7.395843 4.673773 -36.86244 -7.501414 6.27482 -36.85443 -7.738445 8.601093 -36.83567 -7.952468 11.37269 -36.77519 -8.038483 13.76039 -36.60205 -8.066345 15.44303 -36.2764 -8.096558 16.64195 -35.77499 -8.143001 17.67924 -35.12307 -8.200977 18.67685 -34.68241 -8.198568 19.26147 -33.26307 -12.92019 20.38599 -31.78158 -11.90959 22.2854 -32.04178 -12.04864 21.98617 -33.05307 -12.68976 20.71327 -31.8394 -11.86966 22.2999 -32.79792 -12.42934 21.11204 -31.50097 -11.61521 22.78454 -32.51232 -12.16457 21.54295 -31.08798 -11.34693 23.29805 -32.20164 -11.91844 21.96888 -31.92384 -11.72417 22.29938 -30.42971 -11.01677 23.92545 -33.72209 -13.385 19.68676 -34.35958 -13.90201 18.79178 -34.24182 -13.66092 19.08411 -34.07139 -13.41623 19.39869 -33.89572 -13.15754 19.72511 -33.70595 -12.89231 20.06282 -33.49144 -12.64335 20.40171 -33.34536 -12.44411 20.63555 -34.91856 -14.49959 17.86984 -34.88898 -14.28979 18.09305 -34.78614 -14.05705 18.36421 -34.6797 -13.80885 18.63812 -34.56331 -13.54106 18.92437 -34.4249 -13.27511 19.21701 -34.28262 -13.02515 19.48587 -33.635 -12.44152 20.35917 -34.20999 -12.80259 19.66043 -33.55237 -12.22852 20.52293 -34.06434 -12.53416 19.91134 -33.35896 -11.95582 20.80633 -33.88796 -12.24849 20.18257 -33.15584 -11.64155 21.08966 -33.71679 -11.91976 20.43213 -32.99143 -11.24155 21.32189 -33.58039 -11.47476 20.63162 -32.87948 -10.71662 21.47712 -33.48582 -10.86885 20.76298 -32.81611 -10.03965 21.55943 -33.4344 -10.07763 20.82832 -32.77513 -9.358541 21.60309 -33.40245 -9.297863 20.86028 -32.73704 -8.885254 21.63297 -33.38896 -8.785936 20.86121 -32.59994 -8.737526 21.77011 -33.36264 -8.568209 20.87731 -33.27613 -8.532699 20.96158 -32.10611 -9.06354 22.28085 -32.65243 -8.510615 21.6787 -33.38269 -8.382586 20.83132 -35.30339 -15.12468 16.9743 -35.31856 -14.89096 17.21139 -35.27072 -14.65212 17.4725 -35.21757 -14.40735 17.72327 -35.15771 -14.13564 17.98704 -35.08335 -13.8503 18.25989 -34.98793 -13.57108 18.52471 -34.88953 -13.2881 18.76993 -34.76867 -12.99253 19.01898 -34.6389 -12.68298 19.25555 -34.51645 -12.30724 19.46019 -34.42037 -11.76436 19.61242 -34.35585 -11.01136 19.70569 -34.32761 -10.0782 19.7447 -34.31706 -9.208691 19.7558 -34.31378 -8.696844 19.74848 -34.31119 -8.485849 19.74055 -34.30192 -8.39706 19.74234 -34.34083 -8.316118 19.68758 -35.53507 -15.83242 15.99651 -35.60108 -15.54086 16.28528 -35.60736 -15.2655 16.57559 -35.60366 -15.00452 16.83481 -35.59341 -14.71907 17.09981 -35.56845 -14.40872 17.37648 -35.52155 -14.09844 17.6428 -35.46495 -13.78057 17.8906 -35.39009 -13.45905 18.12469 -35.30384 -13.11421 18.33671 -35.22117 -12.66761 18.50941 -35.16032 -12.00196 18.62023 -35.12374 -11.09155 18.67975 -35.11911 -10.02909 18.69781 -35.13887 -9.100384 18.6864 -35.15492 -8.612967 18.66639 -35.16034 -8.429986 18.6539 -35.15843 -8.341352 18.6496 -35.15615 -8.268471 18.64492 -35.68717 -16.67566 14.82292 -35.78983 -16.30861 15.18716 -35.83867 -15.95593 15.55545 -35.8748 -15.63446 15.87867 -35.90582 -15.30377 16.18704 -35.92576 -14.95224 16.49048 -35.92761 -14.60526 16.76546 -35.91864 -14.25905 17.00919 -35.88747 -13.90696 17.23156 -35.83759 -13.50729 17.42688 -35.78604 -12.96483 17.57687 -35.75378 -12.17144 17.6562 -35.73943 -11.12633 17.69044 -35.75066 -9.960366 17.69796 -35.78809 -9.01564 17.68032 -35.81733 -8.554998 17.65543 -35.82847 -8.384457 17.64028 -35.82886 -8.293377 17.63434 -35.82286 -8.215494 17.63356 -35.82019 -17.59743 13.49697 -35.93201 -17.20363 13.88599 -36.0055 -16.78902 14.31093 -36.07034 -16.38973 14.70973 -36.13318 -15.98062 15.09353 -36.19213 -15.55233 15.46035 -36.23843 -15.13665 15.77691 -36.26595 -14.74328 16.044 -36.26882 -14.33752 16.26975 -36.25067 -13.84792 16.45138 -36.22283 -13.1808 16.58531 -36.20738 -12.2496 16.6508 -36.211 -11.06486 16.66742 -36.23996 -9.797134 16.65898 -36.28373 -8.899738 16.63832 -36.31281 -8.49975 16.61983 -36.32289 -8.343882 16.61036 -36.32266 -8.249816 16.60793 -36.31622 -8.168642 16.60886 -35.94351 -18.41576 12.19112 -36.06027 -18.06297 12.53206 -36.14693 -17.6608 12.93231 -36.22693 -17.23451 13.34407 -36.30401 -16.77252 13.76768 -36.37992 -16.27618 14.18552 -36.45098 -15.77402 14.55504 -36.49912 -15.28497 14.87184 -36.52325 -14.75869 15.12343 -36.52832 -14.12005 15.3015 -36.51955 -13.30922 15.42243 -36.51644 -12.25375 15.47888 -36.53489 -10.93875 15.48343 -36.57871 -9.574894 15.46085 -36.61917 -8.755977 15.43261 -36.63842 -8.441082 15.42147 -36.64381 -8.310593 15.42044 -36.64358 -8.217754 15.42099 -36.63807 -8.135815 15.42081 -36.05645 -19.12145 10.84047 -36.18026 -18.80851 11.14056 -36.27402 -18.44958 11.49505 -36.36152 -18.04802 11.86771 -36.44362 -17.59296 12.2571 -36.5181 -17.08454 12.654 -36.58618 -16.51917 13.02603 -36.63179 -15.88979 13.35312 -36.65759 -15.1606 13.60083 -36.66949 -14.31153 13.76305 -36.6706 -13.35055 13.87347 -36.67498 -12.21533 13.93186 -36.70075 -10.83894 13.94116 -36.75183 -9.431036 13.91184 -36.7913 -8.661146 13.85343 -36.80614 -8.398252 13.8135 -36.80984 -8.287227 13.79548 -36.81016 -8.198473 13.7868 -36.80555 -8.115222 13.77533 -36.15699 -19.77678 9.320755 -36.28595 -19.48539 9.59652 -36.38371 -19.15653 9.915022 -36.47417 -18.77963 10.24468 -36.55548 -18.3439 10.58193 -36.61997 -17.83383 10.92379 -36.66873 -17.19534 11.23534 -36.69676 -16.38285 11.47362 -36.71079 -15.41202 11.61967 -36.71724 -14.35201 11.70414 -36.71905 -13.27095 11.7803 -36.72444 -12.11282 11.84461 -36.74841 -10.76309 11.87616 -36.79874 -9.382447 11.8625 -36.84418 -8.609251 11.79565 -36.86306 -8.343037 11.7102 -36.86714 -8.23945 11.6334 -36.86672 -8.156995 11.57681 -36.86177 -8.065346 11.51025 -36.24527 -20.37112 7.635973 -36.37511 -20.09805 7.872774 -36.47292 -19.79089 8.145779 -36.55957 -19.43139 8.427998 -36.63089 -18.99973 8.715209 -36.67977 -18.44266 8.996932 -36.70816 -17.6723 9.221403 -36.72057 -16.6648 9.338703 -36.72526 -15.50854 9.372429 -36.7269 -14.31368 9.381491 -36.72744 -13.15208 9.414635 -36.73046 -11.9855 9.462084 -36.74692 -10.70256 9.493195 -36.79131 -9.397882 9.50535 -36.84704 -8.585703 9.486574 -36.87622 -8.260355 9.361366 -36.8829 -8.128645 9.160624 -36.88142 -8.028159 8.986721 -36.87601 -7.905918 8.837479 -36.31449 -20.84494 5.883478 -36.44025 -20.59287 6.049192 -36.53398 -20.30571 6.2507 -36.61311 -19.95479 6.463415 -36.6711 -19.4995 6.683554 -36.70405 -18.85133 6.897192 -36.71759 -17.92801 7.0466 -36.7209 -16.77329 7.086811 -36.72354 -15.52833 7.064369 -36.72492 -14.27997 7.033516 -36.72567 -13.06331 7.025558 -36.72775 -11.8683 7.03981 -36.73902 -10.63657 7.064911 -36.77747 -9.422327 7.122877 -36.83988 -8.579374 7.187965 -36.87803 -8.173402 7.032911 -36.88816 -7.975402 6.691803 -36.88664 -7.8228 6.418871 -36.88095 -7.668562 6.315924 -36.32772 -21.09538 4.219208 -36.44505 -20.86098 4.290348 -36.53105 -20.58903 4.386248 -36.60121 -20.23964 4.489641 -36.64801 -19.75299 4.601101 -36.66933 -19.0163 4.721279 -36.6718 -17.94157 4.805738 -36.669 -16.63212 4.808561 -36.68042 -15.31922 4.76861 -36.69203 -14.07833 4.723072 -36.70032 -12.87556 4.687487 -36.70965 -11.69161 4.669777 -36.72529 -10.51592 4.68878 -36.76319 -9.400557 4.805399 -36.82586 -8.570715 4.998669 -36.86687 -8.117035 4.953316 -36.87939 -7.872468 4.686832 -36.87886 -7.69312 4.510555 -36.87355 -7.537912 4.543591 -36.18083 -20.98238 2.717182 -36.27899 -20.75062 2.695202 -36.35025 -20.48303 2.675388 -36.40692 -20.14353 2.654749 -36.44252 -19.66089 2.640625 -36.45211 -18.85704 2.651401 -36.43845 -17.54677 2.662956 -36.42837 -15.90187 2.629068 -36.46628 -14.40186 2.5744 -36.51602 -13.20871 2.524668 -36.56059 -12.16932 2.483271 -36.60793 -11.16613 2.456547 -36.65446 -10.17949 2.475063 -36.71043 -9.253643 2.615217 -36.77668 -8.523077 2.86599 -36.81381 -8.08227 2.934565 -36.82493 -7.830333 2.825344 -36.82607 -7.655776 2.793722 -36.82374 -7.515474 2.900669 42.02316 -14.06072 13.78062 42.01669 -14.16014 13.84588 42.01361 -14.21977 13.87856 42.02069 -14.14543 13.83161 42.01176 -14.26525 13.90042 42.01708 -14.23644 13.87864 42.02247 -13.82848 13.59253 42.02595 -13.81041 13.53643 42.02458 -13.85764 13.63431 42.02872 -13.83332 13.58158 42.0252 -13.89576 13.66695 42.02498 -13.96258 13.71499 42.03048 -13.87845 13.62613 42.03178 -13.94379 13.67815 42.03184 -14.01996 13.73313 42.02981 -14.11832 13.79473 42.01185 -14.34897 13.92237 42.02471 -14.2488 13.86041 41.99841 -14.52845 13.98769 42.01348 -14.4419 13.94049 41.98191 -14.70076 14.04512 41.99925 -14.63271 14.01034 41.95611 -14.85077 14.07793 41.98476 -14.77305 14.05396 41.95587 -14.90415 14.07416 41.82128 -15.17622 14.10398 41.81578 -15.18381 14.10352 41.09597 -16.24809 14.28495 41.51409 -15.47737 14.21697 39.41867 -17.28799 15.04852 41.27375 -16.15792 14.23559 41.83649 -15.37522 14.07145 41.46329 -16.74906 13.99814 41.89077 -15.69441 13.98248 41.79331 -16.60264 13.8604 41.91207 -15.92891 13.9281 41.83605 -16.67352 13.82178 41.89302 -16.23003 13.87011 42.02831 -13.77289 13.21006 42.03242 -13.77988 13.30709 42.03567 -13.81065 13.38941 42.03908 -13.85794 13.46299 42.04183 -13.91124 13.53551 42.04307 -13.98472 13.61449 42.04212 -14.09418 13.70326 42.03713 -14.26869 13.80734 42.02793 -14.47896 13.90462 42.0163 -14.67176 13.97481 42.00537 -14.82007 14.01071 41.98713 -14.98272 14.01363 41.94709 -15.23839 13.99269 41.98487 -15.52634 13.92889 41.98212 -15.76451 13.90002 41.96944 -15.87692 13.88838 41.94655 -16.2137 13.81926 41.82238 -16.61759 13.80491 41.88801 -16.88833 13.68379 41.40518 -17.43563 13.85478 41.57274 -18.04181 13.58982 42.03017 -13.75439 12.30819 42.03501 -13.78657 12.49122 42.03895 -13.83078 12.66764 42.04344 -13.87627 12.82371 42.04818 -13.90844 12.97514 42.05273 -13.94597 13.12934 42.05674 -14.00784 13.28949 42.05899 -14.12101 13.45427 42.05688 -14.30492 13.60597 42.04981 -14.5507 13.72773 42.04236 -14.85704 13.78957 42.03481 -15.26467 13.77605 42.02499 -15.84052 13.69532 42.01676 -16.44134 13.60932 42.00227 -16.73469 13.58963 41.98398 -16.82016 13.59329 41.95249 -17.20272 13.52631 41.89303 -17.84646 13.39943 41.69818 -18.65535 13.29778 42.03123 -13.60573 10.63279 42.0362 -13.74667 10.87335 42.04018 -13.86861 11.14101 42.04486 -13.96131 11.40328 42.05049 -14.01927 11.67433 42.05702 -14.06681 11.95362 42.06442 -14.11427 12.23267 42.07173 -14.16719 12.50021 42.07495 -14.26468 12.74725 42.07278 -14.49298 12.96026 42.07312 -14.99327 13.06776 42.0699 -15.73691 13.05628 42.0616 -16.64418 12.96231 42.04545 -17.44225 12.89465 42.01995 -17.84251 12.92055 41.98394 -18.00042 12.9813 41.93154 -18.30921 12.99535 41.8605 -18.68253 12.96702 41.70441 -19.05221 12.95475 42.0326 -13.17266 8.601936 42.03775 -13.39291 8.857866 42.04174 -13.5872 9.154993 42.04631 -13.76544 9.45182 42.05183 -13.93159 9.754416 42.05841 -14.09838 10.0618 42.06604 -14.25206 10.37019 42.07258 -14.34986 10.68375 42.07225 -14.38021 11.01506 42.07002 -14.51879 11.32631 42.08154 -15.08403 11.49292 42.08831 -15.93958 11.54087 42.08319 -16.89807 11.53478 42.06345 -17.68703 11.58524 42.0254 -18.14773 11.7329 41.96978 -18.40107 11.91466 41.89871 -18.64839 12.06949 41.82049 -18.86051 12.18148 41.71971 -19.02868 12.27261 42.03439 -12.61894 6.547531 42.03993 -12.86112 6.792585 42.04423 -13.07697 7.074137 42.04903 -13.2974 7.354483 42.05465 -13.53214 7.634462 42.06109 -13.78826 7.91435 42.06739 -14.0466 8.195271 42.06832 -14.23294 8.496786 42.05862 -14.29901 8.841469 42.0562 -14.49199 9.157398 42.07622 -15.12288 9.324745 42.08955 -15.94737 9.421494 42.08279 -16.76674 9.515152 42.05309 -17.40468 9.675482 42.00025 -17.8149 9.91141 41.93047 -18.08636 10.17565 41.85016 -18.31051 10.43671 41.76882 -18.49596 10.67951 41.68252 -18.6502 10.90388 42.03618 -12.07676 4.519627 42.0422 -12.31652 4.727747 42.0469 -12.5302 4.971395 42.05213 -12.75933 5.220737 42.05809 -13.01547 5.473398 42.06441 -13.30359 5.728067 42.06856 -13.60052 5.986002 42.06324 -13.83247 6.265583 42.05049 -14.01628 6.56612 42.05885 -14.44725 6.79847 42.08081 -15.1526 6.936983 42.08651 -15.85769 7.076239 42.06724 -16.46636 7.247091 42.02188 -16.92266 7.472715 41.95478 -17.24308 7.744789 41.87602 -17.4863 8.037134 41.79268 -17.69262 8.339209 41.71305 -17.87354 8.645031 41.63064 -18.03708 8.947842 42.03668 -11.61794 2.706692 42.04281 -11.8457 2.846216 42.04763 -12.04823 3.019407 42.05285 -12.2719 3.205856 42.05805 -12.53243 3.405245 42.06194 -12.83059 3.616236 42.06002 -13.12535 3.842117 42.04637 -13.34477 4.09528 42.03062 -13.6003 4.342342 42.04637 -14.22108 4.484289 42.06456 -14.96665 4.58349 42.05829 -15.57636 4.730656 42.02371 -16.03065 4.927685 41.96356 -16.35965 5.167492 41.88684 -16.61044 5.435045 41.80398 -16.81774 5.717688 41.72084 -16.99947 6.015131 41.64392 -17.16436 6.327253 41.56031 -17.32281 6.646069 42.02982 -11.26913 1.418776 42.03372 -11.46563 1.456161 42.03671 -11.64099 1.521643 42.03884 -11.84681 1.602282 42.03778 -12.11617 1.700245 42.03028 -12.45295 1.814238 42.01121 -12.8184 1.946474 41.99078 -13.13654 2.102501 41.96909 -13.48858 2.254438 41.96659 -14.10863 2.330334 41.9589 -14.74566 2.396385 41.92885 -15.22904 2.512629 41.872 -15.56409 2.672241 41.794 -15.80695 2.861013 41.70639 -16.00265 3.067123 41.61593 -16.16994 3.284151 41.52599 -16.31906 3.51436 41.442 -16.45595 3.759966 41.34638 -16.59219 4.015848 41.65081 -10.69341 0.5448074 40.22512 -11.34956 0.4944096 41.60861 -10.85296 0.4099617 40.08352 -11.54617 0.3248234 41.56562 -11.03407 0.3258972 39.94954 -11.76614 0.2027339 41.50797 -11.30563 0.2522774 39.79185 -12.08026 0.09512901 41.41135 -11.73528 0.189989 39.5692 -12.54633 0.01895141 41.20648 -12.30253 0.1428451 39.17453 -13.15871 -0.02358436 40.88038 -12.93863 0.1125488 38.6034 -13.84836 -0.04598808 40.64182 -13.47982 0.09576606 38.16476 -14.40221 -0.05935287 40.48696 -13.95817 0.08693313 37.87489 -14.8418 -0.06867599 40.35645 -14.45758 0.07795524 37.64141 -15.25888 -0.0751686 40.22465 -14.92723 0.07516479 37.4233 -15.66609 -0.07828903 40.06701 -15.30473 0.08567619 37.20043 -16.04189 -0.07656669 39.86701 -15.5899 0.106512 36.9574 -16.37667 -0.07037925 39.63615 -15.80853 0.1356334 36.69412 -16.65531 -0.05863571 39.39317 -15.98799 0.1718158 36.41522 -16.88337 -0.04066467 39.13941 -16.14641 0.2128829 36.1164 -17.06538 -0.01701164 38.87727 -16.29451 0.256485 35.80819 -17.22611 0.01005929 38.61753 -16.43247 0.302515 35.50133 -17.37586 0.03961563 38.36267 -16.57058 0.3755207 35.20108 -17.52562 0.09665107 36.84611 -12.98779 0.3249989 36.75281 -13.13268 0.207735 36.53324 -13.31984 0.116518 36.29039 -13.54477 0.0479831 36.02764 -13.83163 -0.01192277 35.7356 -14.19424 -0.05019372 35.35222 -14.63374 -0.06825256 34.86066 -15.12598 -0.07735824 34.46701 -15.53478 -0.08358764 34.16941 -15.87982 -0.08873939 33.91144 -16.21712 -0.09274673 33.66529 -16.56163 -0.09547042 33.4246 -16.90991 -0.0964775 33.18954 -17.25528 -0.09522819 32.96561 -17.58773 -0.09022331 32.74009 -17.9022 -0.07989501 32.48106 -18.12494 -0.06325531 32.20185 -18.28764 -0.04148674 31.91359 -18.43078 -0.01568222 31.62804 -18.57287 0.03651803 32.21892 -14.6718 0.07424736 32.18269 -14.79367 0.02611732 31.97911 -14.93995 -0.01202195 31.75808 -15.13787 -0.03655236 31.49835 -15.37993 -0.05583375 31.208 -15.65074 -0.0674076 30.88263 -15.94351 -0.07375526 30.50779 -16.25642 -0.07859992 30.16976 -16.5393 -0.08309745 29.88499 -16.80088 -0.08742523 29.66129 -17.06003 -0.09140014 29.4651 -17.32624 -0.09476089 29.27455 -17.60289 -0.09718704 29.09624 -17.90532 -0.09822082 28.95512 -18.28956 -0.09687995 28.8379 -18.75642 -0.09149169 28.68033 -19.06995 -0.08027648 28.48229 -19.242 -0.06371688 28.24813 -19.36836 -0.04277992 28.00811 -19.49031 0.003484666 26.67619 -15.86972 0.00170511 26.72613 -15.96439 -0.02492707 26.6838 -16.07523 -0.0440464 26.67621 -16.23911 -0.05533021 26.59187 -16.43027 -0.06263732 26.41802 -16.6309 -0.0675373 26.17766 -16.83428 -0.07178306 25.8782 -17.03959 -0.07614135 25.57381 -17.23051 -0.08065414 25.3234 -17.40394 -0.08524131 25.17639 -17.56703 -0.08970642 25.08835 -17.73264 -0.09368133 25.01352 -17.91527 -0.09676361 24.94282 -18.17042 -0.09862709 24.90145 -18.63422 -0.09880828 24.8915 -19.29851 -0.09622764 24.84617 -19.75072 -0.08927726 24.74462 -19.95728 -0.07803916 24.5761 -20.07303 -0.06286048 24.39396 -20.17632 -0.02341073 21.12437 -16.64016 -0.03286355 21.27569 -16.72411 -0.05047982 21.53054 -16.84308 -0.05784225 21.69728 -16.96698 -0.06258773 21.73134 -17.08498 -0.06667518 21.66529 -17.19994 -0.0708332 21.52992 -17.31583 -0.07528114 21.37038 -17.4291 -0.07995033 21.23513 -17.53703 -0.08473396 21.16349 -17.64364 -0.08940696 21.12379 -17.75807 -0.09356307 21.08155 -17.89977 -0.09677505 21.02243 -18.15256 -0.09876251 20.97708 -18.68797 -0.0993843 20.97381 -19.48899 -0.09819412 20.95076 -20.09322 -0.09389495 20.85836 -20.40551 -0.08574676 20.68146 -20.57579 -0.07311439 20.49367 -20.70831 -0.03752136 18.18169 -16.79913 -0.0349884 18.36208 -16.88047 -0.0519371 18.52703 -16.95384 -0.05801582 18.62346 -17.02673 -0.06225967 18.64292 -17.09676 -0.06639671 18.60858 -17.16789 -0.070755 18.54047 -17.24333 -0.07540512 18.45713 -17.32379 -0.08023262 18.37313 -17.41006 -0.08508682 18.30275 -17.50418 -0.08973121 18.2247 -17.61297 -0.09379768 18.1099 -17.7599 -0.09692001 17.94034 -18.03582 -0.0988655 17.77739 -18.59811 -0.09962654 17.68198 -19.44353 -0.09915924 17.58199 -20.19957 -0.09638977 17.39373 -20.70035 -0.08964729 17.11024 -21.0054 -0.07751083 16.82479 -21.21844 -0.04523849 17.17957 -16.70999 -0.02686882 17.46424 -16.83684 -0.04485702 17.51997 -16.87944 -0.05256074 17.53897 -16.92501 -0.05756378 17.52449 -16.97754 -0.06184762 17.48579 -17.03432 -0.06607627 17.43339 -17.09519 -0.07054519 17.37523 -17.16356 -0.07528495 17.30335 -17.23853 -0.08015251 17.21647 -17.32575 -0.08499526 17.11558 -17.42585 -0.08957481 16.96986 -17.54961 -0.09358978 16.74162 -17.72467 -0.09671401 16.42669 -18.02994 -0.09872055 16.13923 -18.58305 -0.09960937 15.96479 -19.40574 -0.09947967 15.81982 -20.24967 -0.09753608 15.59538 -20.89698 -0.09184265 15.27921 -21.29604 -0.08041381 14.96219 -21.54757 -0.05086129 3.135792 -10.68497 -0.01356506 10.97141 -14.16549 -0.0210151 11.49417 -14.43093 -0.0367183 3.36737 -10.83599 -0.02864068 11.5534 -14.5232 -0.04332154 3.41597 -10.95864 -0.03508752 11.62307 -14.73663 -0.04794687 3.643524 -11.38412 -0.03920364 12.06687 -15.42573 -0.05381768 4.534737 -12.66053 -0.04539299 12.91726 -16.61824 -0.06236642 6.122584 -14.75501 -0.05583375 13.21969 -17.40453 -0.06920242 7.026989 -16.20845 -0.06394004 13.00993 -17.83734 -0.07416725 7.222069 -17.02429 -0.06836318 12.74155 -18.23357 -0.07825851 7.468565 -17.85598 -0.06938552 12.58338 -18.71262 -0.08139991 8.063841 -18.91117 -0.06752014 12.27675 -19.09551 -0.08514595 8.289428 -19.54543 -0.06942558 11.88886 -19.43426 -0.08941268 8.213994 -19.89158 -0.07512664 11.5975 -19.75889 -0.09368324 8.127902 -20.17686 -0.08208274 11.41042 -20.14585 -0.09613609 8.071954 -20.47377 -0.08667182 11.31304 -20.70297 -0.09713363 8.081357 -20.90886 -0.0902462 11.28677 -21.36046 -0.09601974 8.201075 -21.48947 -0.09269523 11.27991 -21.84362 -0.08785438 8.380582 -21.94095 -0.08564567 11.24467 -22.09078 -0.06147766 8.532704 -22.16986 -0.05803871 3.857616 -18.22944 -0.05535119 4.763094 -19.40069 -0.0516662 4.977948 -19.87257 -0.05657005 5.007912 -20.21545 -0.06445121 5.022259 -20.55347 -0.07054519 5.121259 -20.9944 -0.0780754 5.381928 -21.56614 -0.08684921 5.729153 -21.99152 -0.08238029 6.065861 -22.20002 -0.05131912 3.076789 -19.194 -0.04224586 3.422324 -19.75474 -0.04574006 3.476819 -20.13908 -0.05372047 3.504965 -20.52551 -0.06054115 3.642211 -21.00255 -0.07051658 3.976061 -21.59403 -0.08362197 4.40381 -22.0101 -0.08104515 4.849295 -22.20953 -0.04825013 -2.510519 -8.13492 -0.03243446 -2.538321 -8.130533 -0.03278923 -2.508368 -8.188328 -0.08260917 -2.535842 -8.183856 -0.08319091 -2.507183 -8.24596 -0.09146881 -2.534976 -8.240826 -0.09214782 -2.531295 -8.311134 -0.09461593 -2.559838 -8.304312 -0.09536743 -2.667306 -8.392608 -0.09596824 -2.702248 -8.374975 -0.09677124 -3.003532 -8.57054 -0.09539604 -3.082252 -8.489487 -0.0960865 -3.294919 -9.154335 -0.09420394 -3.50823 -8.884418 -0.09426689 -3.118726 -10.486 -0.09482192 -3.459612 -10.03627 -0.09414863 -2.722002 -12.12324 -0.09655952 -2.936254 -11.85829 -0.09643554 -2.533488 -13.51721 -0.09738349 -2.615234 -13.44472 -0.09791183 -2.488599 -14.73109 -0.09692573 -2.531603 -14.72106 -0.09777069 -2.381843 -15.96039 -0.09156036 -2.464512 -15.9349 -0.09304046 -6.288774 -8.117205 -0.03306573 -9.32049 -8.150164 -0.03017044 -6.291289 -8.175621 -0.08413314 -9.336425 -8.23355 -0.08285522 -6.290299 -8.243785 -0.0933113 -9.332363 -8.344345 -0.0927124 -6.289753 -8.323805 -0.09667778 -9.334908 -8.494434 -0.09611129 -6.293797 -8.408473 -0.09849166 -9.35447 -8.670349 -0.09799766 -6.301784 -8.49868 -0.09875488 -9.359095 -8.843668 -0.09852981 -6.333815 -8.727794 -0.09773254 -9.361143 -9.10256 -0.09782791 -6.371882 -9.551823 -0.09682273 -9.379654 -9.7853 -0.09686279 -6.332421 -11.31986 -0.09769248 -9.390888 -11.26422 -0.09722518 -6.311552 -13.20806 -0.09914588 -9.414801 -13.11721 -0.09869003 -6.344861 -14.6702 -0.0998001 -9.438226 -14.65032 -0.09962463 -6.480588 -15.83498 -0.09980773 -9.487797 -15.82813 -0.09984016 -6.72555 -16.85689 -0.09905815 -9.580019 -16.83295 -0.09944725 -6.895052 -17.81244 -0.09441375 -9.640659 -17.76274 -0.09626579 -6.814986 -18.71251 -0.07591819 -9.60167 -18.60412 -0.08192253 -6.44521 -19.43857 -0.0373497 -9.434318 -19.2389 -0.04736137 -6.165432 -19.84759 0.007600784 -9.314538 -19.62066 0.004055023 -6.028835 -20.11359 0.0692768 -9.266279 -19.92616 0.08118629 -5.942776 -20.33947 0.1560363 -9.240927 -20.19273 0.1801624 -12.86568 -8.294795 -0.02044105 -12.90996 -8.431626 -0.07782554 -12.91392 -8.612597 -0.09046745 -12.96772 -8.87796 -0.09455871 -13.0388 -9.20673 -0.09674263 -13.04795 -9.545654 -0.0978794 -13.02 -10.00067 -0.09807205 -13.07183 -10.78766 -0.09780693 -13.20746 -12.07494 -0.09802818 -13.33966 -13.61394 -0.0989933 -13.39779 -14.89144 -0.09964561 -13.40648 -15.90095 -0.09984016 -13.40387 -16.83529 -0.09956359 -13.39234 -17.74419 -0.09706687 -13.3733 -18.55566 -0.08517265 -13.33076 -19.13418 -0.05359077 -13.30061 -19.49957 0.001283586 -13.29405 -19.82959 0.08728599 -13.29438 -20.11716 0.1915054 -16.01276 -8.598185 -0.006315231 -16.04854 -8.757514 -0.07032585 -16.16248 -8.950115 -0.08618354 -16.49531 -9.244151 -0.09143638 -16.70883 -9.609321 -0.09404373 -16.68113 -10.04168 -0.09560585 -16.55043 -10.74967 -0.0964756 -16.69211 -11.81124 -0.09703063 -17.07636 -13.12006 -0.09768676 -17.38873 -14.36039 -0.09863471 -17.51465 -15.28536 -0.09935951 -17.52157 -16.04096 -0.09971618 -17.48822 -16.86682 -0.09953308 -17.45737 -17.75244 -0.09714317 -17.45247 -18.55568 -0.08583831 -17.46173 -19.11275 -0.0553283 -17.46017 -19.47111 4.48227e-4 -17.46022 -19.80809 0.08866691 -17.46476 -20.09837 0.189888 -19.32188 -8.875013 -0.003156602 -19.26175 -9.007406 -0.069458 -19.78115 -9.171773 -0.08333778 -20.88096 -9.437892 -0.08746337 -21.45337 -9.78459 -0.08986663 -21.28159 -10.37428 -0.0915451 -20.79578 -11.46915 -0.09288024 -20.81965 -12.79701 -0.09431266 -21.2632 -14.0655 -0.09591102 -21.56329 -15.00631 -0.09757995 -21.65181 -15.59944 -0.09885978 -21.63749 -16.13838 -0.09952926 -21.59738 -16.88895 -0.09942436 -21.57351 -17.7667 -0.09699058 -21.58629 -18.56844 -0.08569145 -21.62199 -19.11522 -0.05545228 -21.63215 -19.46898 4.59671e-4 -21.63025 -19.80654 0.08912849 -21.62944 -20.09672 0.1894569 -24.09736 -8.893311 -0.01240158 -24.06587 -9.071297 -0.0709877 -25.04449 -9.239873 -0.08162879 -26.86536 -9.47921 -0.08508682 -27.80499 -9.826429 -0.0875225 -27.50755 -10.57421 -0.08939552 -26.56428 -11.91236 -0.09111022 -26.09949 -13.25514 -0.09305763 -26.06509 -14.35008 -0.09511947 -25.93306 -15.13699 -0.0969963 -25.80389 -15.63415 -0.09812927 -25.73128 -16.13426 -0.09876823 -25.69079 -16.88729 -0.09853172 -25.68114 -17.77714 -0.09584808 -25.71164 -18.58059 -0.08436012 -25.76707 -19.11998 -0.05420494 -25.78681 -19.47048 0.001771867 -25.78332 -19.80732 0.09036827 -25.78054 -20.09745 0.1907978 -30.78986 -8.233122 0.2188948 -30.64935 -8.522665 -0.01865196 -30.54172 -8.802933 -0.07648277 -31.01426 -9.013671 -0.08431434 -32.0558 -9.23234 -0.08750152 -32.52671 -9.515884 -0.08979034 -32.22899 -10.12431 -0.09154891 -31.45999 -11.22272 -0.09321594 -30.96246 -12.36768 -0.09439659 -30.62578 -13.46099 -0.09531974 -30.15192 -14.45472 -0.09520339 -29.83117 -15.19681 -0.0933361 -29.68816 -15.88671 -0.09212684 -29.63824 -16.76265 -0.09018325 -29.64126 -17.73281 -0.08570861 -29.68565 -18.57607 -0.0731678 -29.75295 -19.12396 -0.0423603 -29.77959 -19.47658 0.0141887 -29.77454 -19.81129 0.1020812 -29.76457 -20.10116 0.2035827 -34.9005 -7.848868 0.1326503 -34.77373 -8.094696 -0.04262346 -34.84069 -8.294034 -0.06703567 -35.10734 -8.520752 -0.07152557 -35.15282 -8.834897 -0.07136726 -34.89733 -9.384963 -0.0734539 -34.39122 -10.23275 -0.07933998 -34.02661 -11.12735 -0.08035469 -33.7338 -12.08113 -0.07859992 -33.35231 -13.08895 -0.07265663 -33.09558 -14.01139 -0.06158059 -32.9608 -14.98673 -0.05155366 -32.91198 -16.18527 -0.03952217 -32.93085 -17.46207 -0.02534675 -32.98314 -18.49863 -0.007575929 -33.04409 -19.12189 0.02660942 -33.06574 -19.49793 0.08534049 -33.05686 -19.82999 0.171669 -33.04255 -20.11883 0.2768307 -36.31511 -7.500227 0.3628712 -36.2713 -7.662882 0.1659449 -36.26383 -7.825589 0.1267108 -36.29377 -8.02965 0.1191272 -36.26789 -8.322197 0.1291999 -36.13433 -8.782298 0.1177406 -35.86248 -9.406517 0.08031654 -35.62982 -10.04387 0.06754684 -35.42382 -10.7217 0.07258033 -35.17846 -11.48838 0.08761215 -34.99768 -12.35012 0.1131305 -34.87939 -13.50141 0.1438102 -34.83412 -15.12161 0.1839523 -34.87035 -16.93517 0.2243461 -34.9232 -18.34911 0.2547798 -34.95834 -19.13559 0.2956658 -34.95864 -19.56373 0.3584004 -34.93804 -19.89465 0.4414368 -34.91305 -20.17806 0.5456982 -36.67678 -7.543246 1.062851 -36.67216 -7.681212 0.990799 -36.67078 -7.855196 0.9813557 -36.65945 -8.104311 1.018293 -36.60942 -8.502834 0.9710274 -36.4939 -9.077892 0.8339443 -36.37579 -9.722702 0.7674809 -36.25642 -10.39454 0.7658997 -36.1192 -11.10555 0.7874813 -36.00012 -11.92361 0.8229466 -35.89501 -13.08917 0.8726158 -35.83335 -14.83841 0.9396649 -35.85583 -16.86797 1.001202 -35.89318 -18.44311 1.034164 -35.90387 -19.31088 1.072241 -35.88506 -19.77228 1.132309 -35.84881 -20.09928 1.203157 -35.80396 -20.36991 1.282997 41.97917 -10.93343 0.7216797 41.97271 -11.08502 0.6775398 41.96556 -11.239 0.6626835 41.95315 -11.4492 0.6546784 41.92759 -11.7713 0.6495667 41.86847 -12.19701 0.6491966 41.76492 -12.67848 0.6624985 41.69072 -13.11809 0.6933594 41.63379 -13.55711 0.7307434 41.5846 -14.11338 0.7429218 41.52926 -14.6408 0.7592621 41.45178 -15.03538 0.8054733 41.34249 -15.30253 0.8756771 41.2119 -15.49663 0.9612675 41.07539 -15.65634 1.056864 40.93468 -15.79632 1.158733 40.78993 -15.92378 1.2668 40.64806 -16.04059 1.382051 40.50086 -16.15616 1.511709 18.07064 -19.65845 28.87366 16.92618 -19.09133 29.91193 20.35957 -20.79268 26.7971 19.21511 -20.22557 27.83538 -4.336961 -20.43736 0.1371536 -4.267405 -20.67881 0.3517552 -3.685057 -20.48744 0.125164 -3.611724 -20.72075 0.3367272 -3.264406 -20.52497 0.1154403 -3.192432 -20.75352 0.3253632 -2.872902 -20.56136 0.1061515 -2.801404 -20.78531 0.3144627 -2.486322 -20.59835 0.09722709 -2.413623 -20.81716 0.3034916 -4.459038 -20.23753 0.05872917 -3.817296 -20.29825 0.05071824 -3.399112 -20.3417 0.04370689 -3.009974 -20.38326 0.03706169 -2.626996 -20.42518 0.03089135 -4.648206 -19.99877 0.007820129 -4.027008 -20.07046 0.005041122 -3.621131 -20.11835 0.001308441 -3.243293 -20.16282 -0.002485275 -2.868089 -20.20811 -0.005945146 -5.032971 -19.57122 -0.03240388 -4.460654 -19.63297 -0.03245347 -4.086691 -19.67322 -0.03410339 -3.734483 -19.71106 -0.03588289 -3.360739 -19.75911 -0.03654474 -2.884476 -19.85502 -0.0326175 -2.472922 -20.26289 -0.008197784 -5.550193 -18.78176 -0.07297325 -5.058342 -18.81272 -0.07266044 -4.738711 -18.83377 -0.07296371 -4.425366 -18.85772 -0.07290458 -4.045032 -18.91692 -0.06976699 -3.443482 -19.09652 -0.05667877 -5.664455 -17.84439 -0.09354972 -5.196097 -17.85987 -0.09332847 -4.892832 -17.87094 -0.09317207 -4.588094 -17.88679 -0.09258842 -4.216337 -17.94869 -0.08884429 -3.633601 -18.15672 -0.07493972 -2.830148 -18.50828 -0.0511837 -2.606473 -19.39994 -0.0339241 -5.422783 -16.87342 -0.09885025 -4.91986 -16.88207 -0.09871673 -4.589645 -16.88704 -0.09859657 -4.258581 -16.89077 -0.09840583 -3.900914 -16.91227 -0.09706687 -3.464328 -17.00881 -0.09096145 -2.949723 -17.19129 -0.07940101 -5.067903 -15.84259 -0.09975814 -4.503591 -15.84445 -0.09970664 -4.132029 -15.84484 -0.09966468 -3.771672 -15.84376 -0.09963226 -3.41636 -15.84487 -0.09945869 -3.088669 -15.86425 -0.09820556 -2.818453 -15.91327 -0.09518241 -2.645246 -15.93617 -0.09388732 -2.571077 -17.28823 -0.07382202 -2.535498 -15.9377 -0.09352684 -2.326455 -17.30734 -0.07310867 -4.869623 -14.70596 -0.09989738 -4.268343 -14.71128 -0.09989929 -3.871547 -14.71101 -0.09988594 -3.496819 -14.71043 -0.09987258 -3.142967 -14.70996 -0.09985351 -2.861852 -14.71144 -0.09970283 -2.700788 -14.71883 -0.09917068 -2.620505 -14.72243 -0.09881019 -2.570062 -14.72187 -0.09837532 -4.831112 -13.36011 -0.09955024 -4.233442 -13.40248 -0.09964561 -3.844593 -13.40672 -0.09963417 -3.48226 -13.40712 -0.09960365 -3.145844 -13.40762 -0.09955787 -2.891103 -13.40817 -0.09946823 -2.764222 -13.40918 -0.09925842 -2.708489 -13.41015 -0.09893035 -2.669294 -13.41407 -0.09844779 -4.896924 -11.55967 -0.09832763 -4.356392 -11.65107 -0.09850883 -4.035308 -11.66749 -0.09846115 -3.745874 -11.6705 -0.09834098 -3.480136 -11.67257 -0.09817695 -3.280385 -11.67461 -0.09794425 -3.178553 -11.67653 -0.09761238 -3.127025 -11.68108 -0.0971508 -3.068794 -11.71439 -0.09665489 -4.990178 -9.613794 -0.09705924 -4.526864 -9.64685 -0.09705734 -4.310093 -9.654314 -0.09690093 -4.140108 -9.65901 -0.09664916 -3.990897 -9.663847 -0.09630203 -3.879389 -9.668783 -0.09585571 -3.815278 -9.674299 -0.09528732 -3.766117 -9.689577 -0.09462738 -3.677944 -9.768033 -0.09407997 -4.911118 -8.664226 -0.09776115 -4.408106 -8.660753 -0.09772109 -4.170438 -8.664212 -0.09760856 -3.999986 -8.66911 -0.0974102 -3.867919 -8.674738 -0.09710693 -3.781779 -8.681126 -0.0966835 -3.733328 -8.687853 -0.09611511 -3.695488 -8.697214 -0.09541893 -3.63975 -8.735485 -0.09469223 -4.828107 -8.420681 -0.09882736 -4.249778 -8.412794 -0.09883689 -3.913699 -8.414162 -0.09881019 -3.636077 -8.416725 -0.09874343 -3.411901 -8.420454 -0.09860801 -3.269396 -8.425787 -0.09837722 -3.202203 -8.432297 -0.0980072 -3.165681 -8.439336 -0.09747886 -3.132896 -8.450535 -0.09680366 -4.803923 -8.349543 -0.0986309 -4.193405 -8.343437 -0.09866523 -3.800076 -8.343567 -0.09867668 -3.44422 -8.34428 -0.09867477 -3.131182 -8.345784 -0.09864425 -2.912609 -8.348801 -0.09855461 -2.809553 -8.353425 -0.0983448 -2.763852 -8.359115 -0.0979824 -2.732659 -8.365494 -0.09745025 -4.80083 -8.287399 -0.09683036 -4.184867 -8.283644 -0.0968647 -3.777362 -8.283535 -0.09688186 -3.397972 -8.283672 -0.09689712 -3.049416 -8.284233 -0.09689712 -2.792527 -8.285961 -0.09685897 -2.671393 -8.289288 -0.09671211 -2.621177 -8.293638 -0.09642028 -2.588919 -8.298668 -0.09597206 -4.800748 -8.225028 -0.09343719 -4.18433 -8.223333 -0.09346389 -3.775205 -8.223278 -0.09348106 -3.39265 -8.223339 -0.09350013 -3.037244 -8.223731 -0.09350585 -2.771293 -8.225197 -0.09347724 -2.647367 -8.228243 -0.09334754 -2.596739 -8.232033 -0.09309005 -2.564088 -8.236205 -0.09268951 -4.80078 -8.167484 -0.08429527 -4.18427 -8.167027 -0.08432388 -3.775073 -8.16703 -0.08433914 -3.392403 -8.167087 -0.0843563 -3.036633 -8.16749 -0.08436203 -2.770453 -8.169013 -0.0843296 -2.648005 -8.172153 -0.08420372 -2.598104 -8.175867 -0.08396148 -2.565174 -8.17973 -0.08362579 -4.800514 -8.113774 -0.03348726 -4.184213 -8.113644 -0.03353112 -3.77502 -8.113644 -0.03354454 -3.392381 -8.113702 -0.03355789 -3.036839 -8.114113 -0.03355026 -2.77151 -8.11566 -0.03346443 -2.650652 -8.118826 -0.03324699 -2.601675 -8.122543 -0.03294938 -2.568449 -8.126406 -0.03281593 -4.801889 -8.058109 0.1734218 -4.184172 -8.057989 0.1733741 -3.774982 -8.057979 0.1733589 -3.392354 -8.05802 0.1733608 -3.036925 -8.058359 0.1734676 -2.7718 -8.059652 0.1738376 -2.650518 -8.06241 0.1745108 -2.601099 -8.065938 0.1750373 -2.566653 -8.070082 0.1744785 0.6152819 -11.1997 49.34731 0.4763087 -11.31884 47.32046 0.2886705 -11.19372 49.31867 0.1374685 -11.29081 47.31778 -0.06451606 -11.18763 49.25674 -0.2183568 -11.26226 47.29556 -0.4191171 -11.18202 49.18175 -0.576669 -11.2358 47.25928 -0.7691212 -11.1778 49.11305 -0.9420247 -11.21479 47.21434 -1.148824 -11.17592 49.02579 -1.321217 -11.20235 47.14506 -1.567363 -11.17518 48.91528 -1.697057 -11.19558 47.05837 -2.001602 -11.17457 48.80753 -2.066606 -11.18966 46.97429 -2.441913 -11.17363 48.6941 -2.421968 -11.18163 46.91203 0.7051944 -11.63759 44.94374 0.3403686 -11.56916 44.99866 -0.03103619 -11.4991 45.04771 -0.4005497 -11.43213 45.08582 -0.7775993 -11.37368 45.10554 -1.146681 -11.32988 45.09646 -1.476214 -11.29831 45.07274 -1.791468 -11.26826 45.05107 -2.126265 -11.2318 45.0596 1.20159 -12.11729 42.40301 0.8381037 -12.02588 42.48899 0.4708677 -11.93102 42.57621 0.1058752 -11.83569 42.66362 -0.2654219 -11.74212 42.74679 -0.6231241 -11.65627 42.81783 -0.9382622 -11.58007 42.88185 -1.246896 -11.50239 42.94991 -1.603561 -11.41503 43.04513 1.802164 -12.6454 39.83617 1.455176 -12.54666 39.93334 1.104952 -12.44371 40.03546 0.7617148 -12.33951 40.14058 0.4186565 -12.23366 40.24797 0.08181738 -12.12756 40.35545 -0.2345397 -12.0229 40.46313 -0.5547109 -11.91147 40.57554 -0.9257577 -11.78666 40.69549 2.408202 -13.15987 37.30498 2.088011 -13.06075 37.40495 1.768398 -12.95816 37.51147 1.455953 -12.85451 37.61933 1.146775 -12.74956 37.72826 0.8395577 -12.64201 37.83982 0.5334628 -12.52968 37.95494 0.213423 -12.40747 38.07471 -0.1536453 -12.27029 38.19677 2.960434 -13.64194 34.80014 2.66647 -13.54402 34.89781 2.38091 -13.44487 35.00247 2.101875 -13.34536 35.10794 1.822302 -13.24518 35.21167 1.544813 -13.14134 35.31758 1.249233 -13.03009 35.42323 0.9092618 -12.91105 35.51882 0.5335932 -12.78433 35.60515 3.429 -14.0928 32.29134 3.144329 -13.99355 32.3808 2.868426 -13.89387 32.47746 2.595743 -13.79602 32.57383 2.299587 -13.70094 32.65884 2.017255 -13.60032 32.75215 1.63637 -13.49776 32.81142 1.082103 -13.40273 32.79285 0.5366919 -13.32075 32.73919 3.756823 -14.51939 29.76594 3.458244 -14.4139 29.84243 3.123902 -14.30889 29.91862 2.737045 -14.21562 29.97253 2.212871 -14.14021 29.96694 1.73475 -14.05659 29.98247 0.9511393 -13.9883 29.86708 -0.2926699 -13.95632 29.53397 -1.331951 -13.93896 29.2346 3.879865 -14.96257 27.23455 3.454162 -14.84623 27.25238 2.77847 -14.74701 27.20155 1.894956 -14.6903 27.06212 0.672755 -14.68556 26.77268 -0.3368697 -14.66374 26.56404 -1.645129 -14.65807 26.21177 -3.512425 -14.70014 25.5964 -4.804956 -14.73163 25.2048 3.469867 -15.52627 24.56984 2.588628 -15.42516 24.38376 1.065608 -15.38082 23.9846 -0.6416104 -15.40385 23.5043 -2.558222 -15.493 22.9236 -3.826289 -15.54359 22.60264 -4.819341 -15.57146 22.37852 -6.026194 -15.6169 22.04718 -6.772022 -15.64465 21.91384 1.496227 -16.32186 21.3576 0.153223 -16.29889 20.9681 -1.838185 -16.33973 20.36485 -3.524066 -16.40517 19.88451 -4.929533 -16.48835 19.50877 -5.691327 -16.5317 19.3937 -6.130292 -16.54983 19.40793 -6.615186 -16.56457 19.4063 -6.944431 -16.56409 19.49162 -1.767717 -17.35099 17.6703 -2.758852 -17.38022 17.41507 -3.984097 -17.42638 17.11684 -4.830331 -17.45975 16.98199 -5.422729 -17.48478 16.95305 -5.762815 -17.48919 17.03388 -6.003963 -17.48129 17.16355 -6.254745 -17.4653 17.29806 -6.479642 -17.43111 17.48163 -2.713539 -18.28038 14.96058 -3.425339 -18.33489 14.77359 -3.838697 -18.35615 14.75391 -4.316243 -18.36329 14.76469 -4.646852 -18.35521 14.84926 -4.921346 -18.34055 14.96937 -5.164225 -18.31678 15.1214 -5.401242 -18.29135 15.27992 -5.644923 -18.27508 15.41186 -5.885387 -18.23719 15.59436 -3.455549 -19.09414 12.84243 -3.655881 -19.095 12.90609 -3.86764 -19.07955 13.00313 -4.056409 -19.05722 13.11557 -4.275888 -19.03252 13.23729 -4.526779 -19.00154 13.38037 -4.795133 -18.97522 13.51812 -5.079006 -18.97377 13.59943 -5.364158 -18.95225 13.7299 -3.295736 -19.82143 11.17295 -3.540514 -19.81537 11.21902 -3.72424 -19.80385 11.27856 -3.900899 -19.7916 11.33647 -4.125254 -19.77913 11.39891 -4.392333 -19.76247 11.47748 -4.679068 -19.74765 11.55691 -4.980744 -19.75174 11.59447 -5.291004 -19.74337 11.66371 -2.498993 -20.5653 9.424946 -3.031614 -20.55654 9.451754 -3.445613 -20.54973 9.476702 -3.73387 -20.54492 9.499378 -3.985959 -20.54144 9.518135 -4.255942 -20.53842 9.537907 -4.543558 -20.53405 9.563124 -4.836195 -20.52904 9.592312 -5.134024 -20.531 9.606478 -5.444872 -20.52866 9.632021 -2.508541 -21.23031 7.669472 -2.865733 -21.22922 7.674553 -3.204226 -21.22876 7.678028 -3.546553 -21.22847 7.681423 -3.891372 -21.22806 7.685249 -4.235413 -21.22717 7.691059 -4.580898 -21.22754 7.69437 -4.946553 -21.22716 7.699844 -2.313232 -21.77289 5.863703 -2.691774 -21.77259 5.864744 -3.070935 -21.77227 5.865469 -3.449896 -21.77198 5.865969 -3.828379 -21.77159 5.866899 -4.207645 -21.77127 5.867729 -4.607082 -21.77088 5.869204 -2.346862 -22.06508 4.154921 -2.733198 -22.06258 4.15905 -3.119555 -22.06008 4.162828 -3.505956 -22.05755 4.166618 -3.893322 -22.05492 4.170292 -4.301902 -22.05229 4.173988 -2.422012 -21.87706 2.533438 -2.809164 -21.86707 2.541899 -3.196829 -21.85705 2.550333 -3.585753 -21.84674 2.55854 -3.997582 -21.83654 2.566433 -4.918241 -7.987106 0.8214111 -4.820394 -8.006229 0.5764637 -4.209626 -7.987038 0.8212662 -4.186514 -8.006175 0.5764103 -3.77741 -7.987003 0.8212624 -3.774989 -8.006151 0.5764027 -3.395404 -7.986986 0.821415 -3.392614 -8.006147 0.5764637 -3.047687 -7.987071 0.8220749 -3.038229 -8.006289 0.5768261 -2.78754 -7.987583 0.8237114 -2.773381 -8.00703 0.5778732 -2.653173 -7.989077 0.8259945 -2.647716 -8.008942 0.5795212 -2.592601 -7.992016 0.826994 -2.594705 -8.012074 0.5804215 -2.552862 -7.996881 0.8244209 -2.557547 -8.016724 0.5785809 0.814838 -11.17668 50.53823 0.4990611 -11.17576 50.51537 0.1630624 -11.17482 50.46685 -0.1759476 -11.17395 50.40582 -0.5164986 -11.17327 50.34376 -0.8929696 -11.17303 50.25821 -1.314692 -11.17292 50.15004 -1.767041 -11.17281 50.0392 -2.283892 -11.17265 49.89416 -2.889363 -21.22135 1.039732 -2.500756 -21.24453 1.028406 -3.280152 -21.19785 1.050905 -3.697765 -21.17441 1.062796 2.655298 -21.89019 -0.01995277 3.107971 -22.05034 -0.03033256 3.533921 -22.28449 0.1404075 3.222687 -22.23455 0.1471633 3.461435 -22.13919 -0.03673928 3.812665 -22.30244 0.1357288 3.765758 -22.18961 -0.0414772 4.080649 -22.3088 0.1316184 4.046772 -22.20868 -0.0446701 4.344686 -22.30899 0.127758 4.356305 -22.21172 -0.04665756 4.630077 -22.30679 0.1241035 2.373362 -21.57922 -0.05233567 2.829775 -21.76576 -0.06287384 3.213582 -21.91284 -0.07221603 3.527967 -21.98714 -0.07792091 3.861139 -22.00938 -0.08020401 2.661378 -21.42126 -0.07067298 3.042421 -21.54195 -0.07842063 3.404617 -21.58739 -0.08185768 2.650247 -20.93566 -0.06409263 3.037872 -20.98023 -0.06718254 2.480802 -20.43003 -0.05320358 2.884548 -20.48226 -0.05625718 2.419207 -19.99279 -0.04545778 2.847667 -20.07131 -0.04888337 2.744626 -19.63874 -0.04150009 -2.480411 -13.54981 -0.0964756 -2.424246 -14.7608 -0.09510231 -2.439581 -13.56223 -0.09510231 -2.315778 -14.83028 -0.09196281 -2.596713 -12.26614 -0.09609794 -2.550651 -12.29833 -0.09507369 -2.526471 -12.30034 -0.09383201 -2.408713 -13.56208 -0.09383583 -2.503345 -12.30151 -0.09249305 -2.375028 -13.56402 -0.09244728 -2.4665 -12.32155 -0.091053 -2.300034 -13.60485 -0.0902996 -2.911341 -10.75256 -0.09471702 -2.840479 -10.82839 -0.09378814 -2.814341 -10.84201 -0.09251594 -2.785035 -10.86176 -0.09116554 -2.714931 -10.94252 -0.08996391 -2.593205 -11.09154 -0.08896064 -2.399591 -12.37579 -0.08945083 -2.496809 -11.17136 -0.08776473 -2.338924 -12.40247 -0.08787918 -3.170513 -9.302105 -0.09358024 -3.125759 -9.338926 -0.09243774 -3.098752 -9.35204 -0.09110641 -3.051049 -9.397722 -0.08981323 -2.9342 -9.549124 -0.08883476 -2.749526 -9.801449 -0.08818435 -2.623012 -9.951236 -0.08715629 -2.55123 -9.99672 -0.0857582 -2.41186 -11.19554 -0.08633422 -2.956098 -8.609086 -0.09442138 -2.929236 -8.619732 -0.09322357 -2.905015 -8.627856 -0.09191131 -2.870874 -8.652193 -0.09056663 -2.79685 -8.738224 -0.08937454 -2.679473 -8.89153 -0.08836555 -2.606496 -8.976449 -0.08706283 -2.570821 -8.999302 -0.08549308 -2.533817 -9.019629 -0.083395 -2.464175 -10.05065 -0.08389282 -2.638846 -8.402446 -0.0949974 -2.613048 -8.40971 -0.09388923 -2.587988 -8.417139 -0.09266662 -2.562199 -8.427036 -0.09134864 -2.52698 -8.452488 -0.09000587 -2.477194 -8.50134 -0.08867454 -2.444027 -8.526329 -0.08719825 -2.421052 -8.535644 -0.08560371 -2.39521 -8.545624 -0.08349609 -2.503967 -8.317747 -0.0937252 -2.477345 -8.324625 -0.09270668 -2.451416 -8.331753 -0.09157371 -2.426211 -8.339224 -0.09034156 -2.400792 -8.348381 -0.08902549 -2.373208 -8.361942 -0.08765411 -2.349343 -8.370968 -0.08620452 -2.327045 -8.378413 -0.08468055 -2.300117 -8.388176 -0.08265113 -2.480163 -8.25164 -0.09065818 -2.453768 -8.257736 -0.08973121 -2.428005 -8.264198 -0.08870124 -2.40292 -8.271061 -0.08757209 -2.378528 -8.278182 -0.08636474 -2.354563 -8.285753 -0.0850811 -2.33151 -8.292994 -0.08374023 -2.309077 -8.300253 -0.08232688 -2.481974 -8.193218 -0.08187294 -2.456213 -8.198548 -0.08106231 -2.431005 -8.204332 -0.0801773 -2.406375 -8.210577 -0.07923698 -2.382356 -8.217117 -0.07819366 -2.358964 -8.223839 -0.07703971 -2.336188 -8.230761 -0.07583808 -2.313988 -8.237833 -0.07458686 -2.484446 -8.13957 -0.03170776 -2.459225 -8.144596 -0.03109741 -2.434496 -8.150078 -0.03067016 -2.410236 -8.156103 -0.03036308 -2.386669 -8.162455 -0.02977943 -2.363886 -8.169049 -0.0287857 -2.341701 -8.175915 -0.02779763 -2.320001 -8.182979 -0.02692222 -2.47867 -8.085573 0.1734561 -2.453266 -8.091614 0.1734714 -2.428308 -8.098324 0.1722488 -2.4038 -8.105665 0.170351 -2.38052 -8.113129 0.1694164 -2.358754 -8.120628 0.169897 -2.337835 -8.12851 0.1703147 -2.317314 -8.136837 0.1699714 4.410289 -11.35174 49.80249 4.396636 -11.74157 46.99814 3.91375 -11.3412 49.82618 3.918632 -11.71219 46.99257 3.576938 -11.32581 49.91289 3.560763 -11.67274 47.05892 3.261417 -11.30742 50.01762 3.217235 -11.62771 47.14845 2.952571 -11.28954 50.11861 2.8827 -11.58356 47.23067 2.64881 -11.27294 50.19925 2.551465 -11.54072 47.29499 2.334027 -11.25618 50.21009 2.211627 -11.49627 47.34732 1.977154 -11.23742 50.02783 1.846416 -11.44809 47.36741 1.588119 -11.22043 49.6588 1.467913 -11.40311 47.32793 4.731654 -12.32084 44.2483 4.275052 -12.28281 44.22295 3.912491 -12.22473 44.29507 3.559804 -12.16177 44.38348 3.211904 -12.09949 44.46209 2.858676 -12.0363 44.53097 2.497764 -11.96924 44.60565 2.127883 -11.8973 44.69357 1.756871 -11.82623 44.77502 5.286054 -12.94935 41.6134 4.804568 -12.90892 41.55329 4.433127 -12.8395 41.62553 4.073715 -12.76627 41.71072 3.71711 -12.69216 41.79166 3.356099 -12.61559 41.87349 2.993994 -12.53587 41.96323 2.633723 -12.45339 42.05985 2.274512 -12.37044 42.15542 5.935037 -13.60101 39.02812 5.403451 -13.52055 38.97865 5.014232 -13.43799 39.05069 4.643348 -13.35537 39.1336 4.274352 -13.27106 39.21458 3.906906 -13.18505 39.29764 3.545647 -13.09805 39.38607 3.192041 -13.01034 39.4767 2.842837 -12.922 39.56703 6.636844 -14.25037 36.4633 6.011067 -14.10355 36.47641 5.598093 -14.00275 36.5582 5.213078 -13.90929 36.63817 4.827642 -13.81474 36.71252 4.449505 -13.72031 36.7877 4.085826 -13.62747 36.86749 3.736601 -13.53589 36.95066 3.396295 -13.44393 37.03624 7.168005 -14.83539 34.03702 6.515514 -14.64621 34.04833 6.093833 -14.53072 34.11456 5.69619 -14.42457 34.17972 5.297778 -14.31825 34.24044 4.914974 -14.21551 34.30585 4.555865 -14.11811 34.37873 4.217041 -14.02411 34.45659 3.890396 -13.92996 34.53861 7.456176 -15.41849 31.69676 6.846418 -15.19119 31.68535 6.441992 -15.05394 31.72099 6.056833 -14.92947 31.75976 5.670809 -14.80717 31.79798 5.302729 -14.6934 31.84656 4.957887 -14.58936 31.90714 4.630221 -14.49011 31.97474 4.315636 -14.39082 32.04922 7.576628 -16.04449 29.44701 7.025723 -15.78925 29.42714 6.660671 -15.62989 29.42722 6.313016 -15.48291 29.43073 5.960229 -15.33866 29.43529 5.617912 -15.20523 29.45251 5.290688 -15.08403 29.48527 4.973024 -14.96853 29.52778 4.660661 -14.85253 29.57959 7.653543 -16.67749 27.2506 7.141354 -16.41696 27.2224 6.804744 -16.25025 27.20066 6.488207 -16.09447 27.18502 6.167575 -15.93914 27.17007 5.849592 -15.78811 27.16166 5.537052 -15.64304 27.16212 5.224834 -15.50127 27.16612 4.904548 -15.35806 27.17737 7.736491 -17.27822 25.0326 7.252268 -17.02624 24.99616 6.930912 -16.86212 24.96654 6.624686 -16.70544 24.94179 6.31483 -16.54625 24.91806 6.005048 -16.38539 24.89982 5.697027 -16.22665 24.88398 5.378326 -16.07438 24.85611 5.029396 -15.92313 24.8369 7.796394 -17.817 22.76239 7.325362 -17.57153 22.71712 7.009737 -17.40876 22.68511 6.70226 -17.25078 22.65427 6.389866 -17.09007 22.62435 6.072776 -16.929 22.59437 5.730892 -16.77848 22.52681 5.277144 -16.65087 22.39298 4.652183 -16.5279 22.30132 7.666968 -18.27254 20.36716 7.152347 -18.03322 20.2824 6.82706 -17.87483 20.24402 6.516458 -17.72259 20.2105 6.192214 -17.57065 20.17188 5.828266 -17.42892 20.08732 5.320109 -17.32926 19.82846 4.3634 -17.29427 19.38762 2.943858 -17.26393 19.11244 6.9579 -18.66848 17.5447 6.277681 -18.47002 17.30917 5.911643 -18.3514 17.22933 5.590545 -18.24026 17.18429 5.230091 -18.1339 17.12294 4.775043 -18.05073 16.95734 4.022467 -18.03726 16.50404 2.42757 -18.11605 15.82466 5.633691 -19.15184 14.2511 4.759878 -19.03919 13.83406 4.339937 -18.99873 13.70199 4.007888 -18.96448 13.65237 3.634163 -18.93285 13.60735 3.169555 -18.91034 13.52061 2.399537 -18.91968 13.29319 4.537554 -19.81173 11.54314 3.755679 -19.75797 11.25033 3.373064 -19.75348 11.17857 3.048451 -19.75341 11.15435 2.674501 -19.75508 11.13259 3.475938 -20.55506 9.481697 2.764475 -20.53676 9.381937 2.343521 -20.53913 9.364418 3.165861 -21.23746 7.663626 2.511936 -21.23232 7.640364 3.154431 -21.78629 5.849045 2.524035 -21.78442 5.846533 3.440333 -22.16488 4.04954 2.828628 -22.16131 4.064077 4.060542 -22.32926 2.303587 3.490139 -22.32345 2.333818 2.426132 -22.15981 4.06983 3.122411 -22.32109 2.347116 -2.455482 -8.019227 0.8151283 -2.462937 -8.036926 0.5730286 -2.428197 -8.028725 0.8120136 -2.436397 -8.045289 0.5715523 -2.401428 -8.039793 0.8048821 -2.410265 -8.054937 0.5669232 -2.375652 -8.0517 0.7959976 -2.384813 -8.065411 0.5607853 -2.352551 -8.063076 0.7897148 -2.361597 -8.075552 0.5567913 -2.332544 -8.073683 0.786974 -2.341084 -8.085157 0.55583 -2.314132 -8.084675 0.7842503 -2.321936 -8.095167 0.5548115 4.650704 -11.21878 51.78007 4.148651 -11.21607 51.89867 3.819706 -11.21154 52.04767 3.523926 -11.20599 52.2026 3.233074 -11.20062 52.35163 2.94097 -11.19581 52.45698 2.624793 -11.19108 52.39079 2.249525 -11.18554 51.96311 1.831259 -11.18054 51.26119 4.398756 -22.35009 0.814024 4.097461 -22.35103 0.822176 2.778021 -22.31918 2.357981 3.81445 -22.3518 0.829628 2.433489 -22.3172 2.369081 3.530663 -22.35195 0.8371792 2.85118 -22.14377 0.1573791 2.958698 -22.34451 0.8533383 2.65737 -22.32688 0.8629875 3.245843 -22.35091 0.8449478 -2.303095 -8.106131 0.5517426 19.02963 -18.9675 28.35232 19.89625 -19.3423 27.54176 16.40124 -15.90285 32.13352 16.42977 -17.84309 30.78401 22.46849 -20.04267 25.42493 27.48709 -20.93374 21.70521 19.71293 -18.00554 27.81631 17.29639 -18.21789 29.97345 17.22916 -16.61773 31.05422 13.1055 -21.9384 -0.06017106 12.95284 -22.08302 0.07217216 13.28933 -21.68946 -0.08676528 13.45204 -21.21029 -0.09583282 13.57974 -20.48412 -0.0987358 13.72442 -19.74916 -0.09902191 13.96487 -19.17331 -0.09805679 14.34969 -18.74178 -0.09590148 14.84164 -18.37272 -0.09303092 15.28347 -18.06146 -0.08945465 15.6136 -17.78997 -0.08535385 15.90415 -17.56969 -0.0808258 16.14275 -17.36513 -0.07612991 16.19569 -17.10441 -0.07096672 16.02343 -16.72519 -0.0652008 15.98273 -16.52165 -0.06039232 16.03262 -16.44404 -0.05587387 16.05326 -16.39391 -0.05062866 15.81997 -16.25967 -0.04203599 9.053809 -13.28795 0.03221696 14.681 -15.74205 -0.01840394 5.829616 -11.82963 0.1771736 12.59357 -14.80939 0.03242874 14.44349 -14.13351 35.42015 14.19011 -11.41911 39.76467 15.43943 -17.65018 31.77589 16.42991 -20.2984 29.32496 17.00598 -21.52446 27.40424 17.08874 -22.18575 25.49136 16.95081 -22.67385 23.40665 16.76632 -23.05317 21.22178 16.58183 -23.31371 18.99688 16.41219 -23.43986 16.75757 16.27842 -23.42573 14.50823 16.17368 -23.28232 12.24839 16.05705 -23.02245 9.974503 15.76393 -22.67712 7.578558 15.12144 -22.3672 4.971643 14.32036 -22.19112 2.44319 13.90624 -22.05604 0.7279511 15.34528 -22.11644 2.657686 16.18921 -22.43334 5.218718 16.72788 -22.85342 7.73288 16.91181 -23.25304 10.04208 16.97631 -23.54401 12.29015 17.05012 -23.7103 14.54908 17.16915 -23.74956 16.80979 17.33792 -23.65141 19.0589 17.53183 -23.41693 21.2819 17.70975 -23.04938 23.44658 17.80599 -22.55414 25.4702 17.62578 -21.91121 27.23871 17.06447 -20.94379 28.76166 16.27959 -19.50962 30.20485 14.12045 -21.75256 -0.05609512 13.91446 -21.9198 0.08436203 14.39648 -21.50141 -0.08366966 14.66352 -21.05504 -0.09394454 14.85648 -20.33344 -0.09835243 15.00865 -19.49133 -0.09954261 15.23011 -18.75279 -0.09930419 15.59653 -18.23857 -0.09807777 16.0319 -17.89336 -0.0958271 16.38619 -17.6578 -0.0925579 16.62809 -17.4868 -0.08849143 16.79745 -17.35424 -0.08395004 16.93244 -17.24141 -0.07919502 17.01928 -17.14263 -0.07436752 17.04974 -17.0331 -0.06952095 17.10294 -16.96033 -0.06503105 17.1617 -16.90501 -0.06069374 17.2054 -16.85999 -0.0561161 17.19008 -16.8118 -0.05072212 16.88979 -16.66281 -0.041933 16.07426 -16.30368 -0.02459907 11.55439 -10.40809 43.95323 18.71143 -16.64527 28.79917 18.88501 -17.54294 28.89561 18.05709 -17.08033 29.97492 16.71938 -16.34073 30.92833 17.3834 -16.27406 30.80506 18.04741 -16.45967 29.50889 14.93293 -14.63891 34.59849 15.9118 -15.64972 32.95518 15.42236 -15.14431 33.77684 14.92929 -13.64353 34.38561 13.62173 -10.29624 41.92503 2.3 -10.21293 0.4570122 2.3 -10.24864 0.2026863 -2.3 -20.70844 9.047554 -2.3 -20.56779 9.415558 -2.3 -20.23535 10.1717 -2.3 -18.89005 13.35599 -2.147028 -18.25246 15.11031 -0.388123 -17.86278 16.55881 2.3 -10.27475 0.04191201 2.3 -10.28158 0.03198426 2.3 -10.30966 -0.01953506 2.3 -10.35877 -0.03488343 2.3 -10.4575 -0.04093742 2.3 -10.76475 -0.04533195 2.3 -11.58505 -0.05311012 2.3 -12.88048 -0.06454467 2.3 -13.97594 -0.07115173 2.3 -14.94092 -0.07268333 2.3 -16.17518 -0.06731224 2.3 -16.21734 -0.06696891 2.3 -17.80485 -0.05178445 2.3 -18.25087 -0.04749673 -2.3 -16.65676 -0.0826435 -2.3 -16.22536 -0.08781623 -2.3 -20.61697 0.09319686 -2.3 -20.82688 0.3003998 -2.3 -20.46242 0.0261116 -2.3 -20.41949 0.01731872 -2.3 -20.29147 -0.008405685 -2.3 -20.0054 -0.02374833 -2.3 -19.97506 -0.02406692 -2.3 -19.48351 -0.02844238 -2.3 -18.68578 -0.04034233 -2.3 -18.38044 -0.04686921 -2.3 -17.38351 -0.07122611 -2.3 -17.3085 -0.0731182 -2.3 -21.07469 8.08082 -2.3 -21.23178 7.665386 -2.3 -21.42671 7.015652 -2.3 -21.77291 5.863646 -2.3 -21.78396 5.799372 -2.3 -22.06538 4.154293 -2.3 -22.03833 3.909643 -2.3 -21.88029 2.530619 -2.3 -21.63625 1.93392 -2.3 -21.25673 1.022671 2.3 -21.96771 0.1735153 2.3 -21.96086 0.1685218 2.323315 -21.97548 0.1728229 2.3 -21.79805 0.03385728 2.3 -21.75486 -0.01023674 2.3 -21.65995 -0.0283432 2.3 -21.5484 -0.05071449 2.3 -21.52119 -0.0520153 2.3 -21.32151 -0.05995553 2.3 -21.27208 -0.06207841 2.3 -20.90846 -0.06006234 2.3 -20.85813 -0.05939286 2.3 -20.3997 -0.05151551 2.3 -19.97032 -0.04436677 2.3 -19.69654 -0.04226875 2.3 -19.49651 -0.04009056 -2.3 -16.01799 -0.08953475 2.3 -19.01131 -0.04117959 2.3 -18.92367 -0.04122918 -2.3 -15.46472 -0.0907135 -2.3 -14.88234 -0.09150314 -2.3 -14.83636 -0.0915699 -2.3 -14.37952 -0.09140586 -2.3 -13.98672 -0.091053 -2.3 -13.60497 -0.0902996 -2.3 -13.60487 -0.0902996 -2.3 -12.9122 -0.08848571 -2.3 -12.56441 -0.08746337 -2.3 -12.42203 -0.08716392 -2.3 -11.94359 -0.08598518 -2.3 -11.2541 -0.08466148 -2.3 -11.14624 -0.08434867 -2.3 -10.17288 -0.08256721 -2.3 -9.178707 -0.07881355 -2.3 -8.594099 -0.07999992 -2.3 -8.388229 -0.08264541 -2.3 -8.303503 -0.08167076 -2.3 -8.387676 -0.08263587 -2.3 -8.242856 -0.07360839 -2.3 -8.190367 -0.02579689 -2.3 -8.144541 0.1696681 0.9304676 -17.95517 16.39576 1.801134 -18.13516 15.73179 2.083319 -18.29332 15.23535 2.3 -18.92332 13.27265 -2.3 -19.03913 12.91042 2.3 -19.75823 11.11678 2.3 -19.63355 11.46788 2.3 -18.99278 13.10283 -2.3 -19.81462 11.10845 2.3 -20.53952 9.36343 2.3 -20.29354 9.923298 2.3 -20.01913 10.53666 2.3 -20.65596 9.073647 2.3 -21.23292 7.638298 2.3 -21.78436 5.846285 2.3 -22.01129 4.772398 2.3 -22.15935 4.071531 2.3 -22.21418 3.479506 2.3 -22.2893 2.667013 2.3 -22.31648 2.373568 -2.3 -8.102192 0.649538 -2.3 -8.108136 0.5509224 2.3 -22.32185 2.099318 2.3 -22.32789 1.687456 2.3 -22.32276 1.301071 2.3 -22.27419 0.8747521 2.3 -22.14586 0.5769501 -2.409708 -8.150076 16.52644 -1.232281 -7.982413 16.50328 -0.05485385 -7.814751 16.48011 1.122573 -7.647089 16.45695 2.005643 -7.521342 16.43958 2.3 -7.479426 16.43379 -2.393779 -8.139177 13.90274 -2.377849 -8.128275 11.27904 -2.36192 -8.117376 8.655344 -2.345991 -8.106475 6.031647 -2.330061 -8.095577 3.407948 -2.303533 -18.43139 2.094025 -2.307066 -14.98248 1.657434 -2.310599 -11.53358 1.220842 2.3 -8.390596 11.10819 2.3 -9.757349 3.119806 18.16301 -18.5927 29.16289 17.42473 -15.84954 30.68022 16.74241 -15.88508 31.64909 17.08357 -15.86731 31.16465 17.76589 -15.83177 30.19578 15.96509 -15.05381 32.31353 15.91996 -14.62929 32.65127 15.29728 -14.20836 33.82259 15.66526 -14.77319 33.25957 16.03325 -15.33802 32.69655 15.51678 -14.54549 33.69281 15.2108 -14.27143 33.69872 15.49232 -14.89933 33.01183 15.77384 -15.52723 32.32494 14.1925 -10.59738 39.42518 14.93168 -12.8218 34.04613 15.64029 -14.15519 33.42311 16.52476 -15.51255 31.86383 15.63393 -14.17591 33.42311 + + + + + + + + + + -0.2765447 -0.592944 0.7562676 -0.2212657 -0.6100217 0.7608647 0.8747938 -0.2989369 0.3812777 0.8968463 -0.2822684 0.3405752 0.1199291 0.9925267 0.02253621 -0.5501472 -0.6272987 0.551212 0.8536118 0.2229926 0.4707667 0.7894355 0.3702982 0.4895619 0.1710757 -0.9322445 0.3188313 0.1746811 -0.9329804 0.3146972 0.2767118 0.9606186 0.02534812 0.26317 0.9632382 0.0539782 0.2677208 0.960629 0.07428061 0.24571 0.962623 0.113946 0.247098 0.960903 0.1249321 0.3688484 -0.8658277 0.3380728 0.4026185 -0.8445642 0.3530011 0.3081951 -0.8786106 0.3647731 0.7923508 -0.4863699 0.3682725 0.7305727 -0.5583339 0.393099 0.9395656 -0.1465485 0.3094192 0.9284095 0.290232 0.2319945 0.9281899 0.2916527 0.2310892 0.6097095 0.4163729 0.6744538 0.4500837 -0.62959 0.633278 0.5276619 -0.5684976 0.6311763 0.5146104 -0.5832961 0.6284441 0.6990593 0.2892779 0.6539376 0.6960274 0.2585815 0.669837 0.7332832 0.3930132 0.5548301 0.5154359 -0.6393473 0.5705796 0.7147701 -0.4432616 0.5409463 0.5037135 -0.691259 0.5181059 0.6268956 -0.5820157 0.5179378 0.5468434 -0.6432543 0.5358977 0.8545949 0.2361555 0.4624913 0.873519 0.325152 0.3622716 0.7715808 0.6347715 0.04157382 0.1448656 -0.9397483 0.3096565 0.1440282 -0.9399664 0.3093851 0.1438872 -0.9399994 0.3093506 0.1437226 -0.9400304 0.3093326 0.143529 -0.9400593 0.3093347 0.1433919 -0.9400717 0.3093608 0.1033962 -0.9394608 0.3266844 0.4052432 0.8371916 0.3672715 0.4044128 0.8537445 0.3279801 0.4530757 0.8312953 0.3219794 0.4888515 0.83662 0.2471663 0.490127 0.8324387 0.2584985 0.5333662 0.8204041 0.2060525 0.5503033 0.8208833 0.1526995 0.5477446 0.8253551 0.1369855 0.5793745 0.8099979 0.0907123 0.5819871 0.8114485 0.05331581 0.5820926 0.8113842 0.05314046 0.638908 0.7680379 -0.04375588 0.5823468 0.811744 0.04409205 -0.6297532 -0.6157569 0.4735549 -0.6271243 -0.611812 0.4820802 -0.6740888 -0.6303579 0.3850367 -0.7233219 -0.6162514 0.3115118 -0.7775397 -0.5790786 0.2451533 -0.6944345 -0.6441223 0.3207294 1 0 0 1 4.34386e-5 -4.58585e-5 0.1012165 0.9936186 0.0497722 0.2418743 0.9669437 -0.08072596 0.3517704 0.8901444 -0.2896565 0.3195886 0.9434149 -0.08849561 0.3643614 0.9312378 0.006073713 0.4288724 0.9010857 -0.06413435 0.3415963 0.9305972 -0.1315324 0.3586348 0.9302843 -0.07715153 0.4497634 0.8931341 0.00495392 0.4393292 0.8979347 0.02652245 0.5673806 0.8141528 -0.1234284 0.5424702 0.8392283 -0.03771001 0.1955646 -0.8704735 0.4516973 0.2745289 -0.7721596 0.5730651 0.30523 -0.6570816 0.6892594 0.9903779 0.1327791 -0.03900569 0.9073733 0.4119871 0.08330959 0.9103984 0.3720177 0.1810463 0.8286002 0.5490756 -0.1092601 0.7531617 0.6424485 -0.1414474 0.7841851 0.6195226 -0.03529453 0.9000437 -0.3413186 0.2709667 0.8059368 -0.5302625 0.2632254 0.8074841 -0.456075 0.3741193 -0.2270628 -0.8699187 0.4378174 0.8582314 -0.4431294 0.2589889 0.9197093 -0.3618722 0.1522612 0.8714857 -0.43735 0.2218962 0.8124201 -0.558736 0.1666972 -0.2034402 -0.8764481 0.4364066 0.2270973 0.9730863 -0.03911411 0.2774356 0.9607216 0.006598591 0.2238269 0.9730694 -0.05511504 0.2000879 0.979775 0.002411663 0.188751 0.9813426 -0.03660368 0.266314 0.9637085 -0.01851809 0.2754487 0.9612818 -0.008094966 -0.2649554 -0.9269976 0.2654701 -0.2992177 -0.9272771 0.2250025 -0.2998428 -0.9280345 0.2210121 -0.3246496 -0.9274777 0.1854399 -0.3248428 -0.9279554 0.1826907 -0.3430572 -0.9276227 0.1477428 -0.3430489 -0.9279018 0.145999 -0.3559873 -0.9277255 0.1122432 -0.3559249 -0.9278639 0.1112928 0.9206781 0.3750267 -0.1081981 -0.6946316 -0.6997506 0.1668416 -0.19265 -0.8635104 0.4660857 0.1259086 -0.5479855 0.8269576 0.1832863 -0.6922962 0.6979486 0.2395898 -0.7246649 0.6461096 0.329984 -0.7194396 0.6111606 0.0436325 -0.7846593 0.61839 -0.1494628 -0.8515222 0.5025644 -0.3957171 -0.9000052 0.1827535 -0.4030994 -0.9021142 0.1539512 -0.3804669 -0.9247204 -0.01172095 0.249118 -0.6247054 0.7400563 0.3378812 -0.8061528 0.4857512 0.7484977 -0.587597 0.3073778 0.4964767 -0.681148 0.538097 0.9643661 -0.1841073 0.1900072 0.9985206 -0.05405414 0.005904197 0.9406744 -0.09921461 0.3244816 0.9400418 -0.0905314 0.3288244 0.4868053 -0.5134391 0.706683 0.8262358 -0.387472 0.4089009 -0.366611 -0.9272932 0.07565551 0.8761611 -0.1649724 0.4529082 -0.3647385 -0.9277935 0.07851946 0.2001894 -0.5680657 0.7982641 0.178703 -0.9140027 0.3642312 -0.1870661 -0.7481036 0.6366689 0.8344711 -0.2209006 0.5048376 0.8941505 -0.2304474 0.383913 0.9409714 0.3361849 -0.03940296 0.9844915 0.1730105 -0.02904826 0.9969031 0.06551212 -0.04350125 0.9905535 0.1364798 -0.01331132 0.9999344 0.005161762 0.01022672 -0.704903 -0.694278 0.1452239 0.9614039 0.2549173 0.103537 0.9998169 0.002561151 0.01896607 0.9902074 0.1392088 -0.01050025 0.9922795 0.1211506 -0.02653324 0.7042478 -0.06135392 0.7072983 0.7239662 -0.08034622 0.6851405 0.6983415 -0.06705236 0.7126172 0.7075442 -0.1746289 0.6847526 0.6875666 -0.2029372 0.6971863 0.6896808 -0.3566934 0.6301669 0.6601456 -0.2899676 0.6929116 0.7391219 -0.2969443 0.6045851 0.6596153 -0.2923738 0.6924054 0.7135636 -0.4679438 0.5213978 0.5224373 -0.7449324 0.4148916 0.5623661 -0.6221827 0.5446405 0.5389441 -0.639762 0.5479452 -0.1650034 -0.6948305 0.699989 -0.1721696 -0.7020143 0.691038 -0.296573 -0.6659904 0.6844716 -0.3183929 -0.6728949 0.6677113 -0.4357246 -0.6285604 0.6442484 -0.4550653 -0.6281802 0.6311144 -0.6628967 -0.375903 0.6475067 -0.5342018 -0.5139489 0.6711819 -0.4991679 -0.6101915 0.6152218 -0.6978044 -0.07751291 0.712082 -0.9061297 -0.312401 -0.2851921 -0.7172607 -0.1574011 0.6787946 -0.5739948 -0.07080996 0.8157917 -0.6710363 -0.1832849 0.7184129 -0.6809133 -0.2819241 0.6759259 -0.6374456 -0.3846918 0.6675892 -0.7220285 -0.4327786 0.539794 0 -1 0 0.1151525 0.9931564 -0.0194981 0.1239584 0.9922872 -6.71187e-4 -0.07000845 0.9917712 -0.1071863 -0.0679205 0.991501 -0.1109617 -0.04278165 0.9915737 -0.1222763 -0.04209768 0.9915069 -0.1230525 -0.01461929 0.991562 -0.1288068 -0.01424235 0.9915308 -0.1290888 0.01422005 0.9915563 -0.1288955 0.01463288 0.9915259 -0.1290828 0.04209464 0.9915073 -0.1230505 0.04277229 0.9915734 -0.1222823 0.06837445 0.9914934 -0.1107522 0.2103148 0.971813 -0.1065237 0.04527235 0.9962331 -0.07396119 -0.1653153 0.9857093 -0.03237706 -0.1740422 0.9846468 -0.01341545 0.1215367 -0.4375811 0.8909274 -0.7823969 -0.2745542 0.5589948 0.6407125 -0.1897284 0.7439696 0.4665691 -0.1700204 0.8679898 -0.8757793 -0.119269 0.4677453 -0.9418951 -0.02902966 0.3346503 -0.9712265 0.01020675 0.237939 -0.7445436 -0.1339645 0.6539943 -0.3530704 -0.2099543 0.9117349 0.1107715 -5.49711e-6 0.993846 0.5561744 -0.07181984 0.8279566 0.3572554 0.1461067 0.9225082 0.7510635 0.02514988 0.6597508 0.9710677 -0.02063882 0.2379112 0.8484069 -0.1308469 0.5129181 0.8678372 -0.1354736 0.4780225 -0.404849 -0.2260419 0.8860036 -0.7133229 -0.06060427 0.6982102 -0.5534498 -0.1223001 0.8238543 -0.1084439 -0.2059159 0.9725424 -0.2137923 -0.3760504 0.901598 0.7823921 -0.2746518 0.5589537 -0.01554942 0.9904477 -0.13701 0.015531 0.9904448 -0.1370324 -0.09152901 -0.9255648 0.3673585 -0.09961354 -0.9288848 0.3567215 -0.1623421 -0.926142 0.3404498 -0.9997834 -0.01466304 0.01477038 0.9470609 -0.1894142 -0.259226 0.7275759 1.10885e-6 0.6860272 0.7263351 -6.47436e-5 0.6873409 0.6954037 3.81418e-4 0.7186192 0.7153806 0.002266287 0.6987314 0.6999015 4.60437e-6 0.7142395 0.6315545 -0.002502381 0.7753275 0.6148212 -0.006633102 0.7886387 0.5668371 0.001422345 0.8238286 0.4715674 0.008823573 0.8817859 0.4264566 -0.001268327 0.9045072 0.4857828 -0.001645684 0.874078 0.4918568 0 0.8706762 0.4415683 -0.03337788 0.8966066 0.4167242 -0.0606988 0.9070042 0.4558038 -5.24582e-4 0.8900801 0.3554629 7.62319e-5 0.9346904 0.3920079 0.002701163 0.9199579 0.3657843 0.03911012 0.9298776 0.3227268 -0.009053826 0.9464489 0.2724103 -0.04837638 0.9609643 0.280018 -0.03618806 0.9593124 0.1562021 0.02802336 0.9873275 0.09442484 -0.04775995 0.9943857 0 0.03383988 0.9994273 -0.09442526 -0.04775947 0.9943857 -0.1562023 0.02802342 0.9873275 -0.2684333 -0.03007227 0.9628288 -0.3746126 -0.1566135 0.9138587 -0.2801765 -0.0140683 0.9598454 -0.3741351 0.002495288 0.9273709 -0.4835733 0 0.875304 -0.4715966 0.008808255 0.8817704 -0.4280529 -0.01026421 0.9036955 -0.4896452 -0.001503586 0.8719205 -0.4556709 -0.02415591 0.8898205 -0.5389025 3.44034e-4 0.8423681 -0.655739 -0.02015393 0.7547186 -0.614835 -0.003782629 0.7886468 -0.6950597 3.7897e-4 0.718952 -0.7273731 -8.2096e-5 0.6862422 -0.7262937 0 0.6873846 0 1 0 0 1 -2.5572e-6 0 1 -1.3574e-6 0 1 1.46475e-6 0 -1 6.31455e-6 0 -1 3.61024e-6 -0.3275545 0 0.9448324 -0.3275169 3.45434e-6 0.9448454 -0.07958412 -6.9301e-6 0.9968282 -0.07951229 6.93082e-6 0.9968339 0.1735915 1.02028e-6 0.9848178 0.1736306 5.96466e-6 0.9848108 0.4153032 -4.7109e-7 0.9096831 0.4152941 -1.25627e-6 0.9096872 0.6303031 -6.90967e-6 0.7763491 0.6303395 -6.28128e-7 0.7763196 0.8050383 -7.53443e-6 0.593223 0.80509 7.21915e-6 0.5931527 0.9283255 -6.89107e-6 0.3717684 0.9283549 6.26373e-6 0.3716952 0.991964 -1.3191e-5 0.1265206 0.9919742 0 0.1264407 0.3275484 0 0.9448344 0.3275125 0 0.9448469 0.07960563 0 0.9968265 -0.1735881 0 0.9848184 -0.173588 0 0.9848183 -0.41532 0 0.9096754 -0.4152866 0 0.9096907 -0.6303395 0 0.7763196 -0.6302911 0 0.776359 -0.8050481 0 0.5932095 -0.8050481 0 0.5932096 -0.9283191 0 0.3717847 -0.9919632 0 0.1265275 -0.9919645 0 0.1265174 0.3232119 0.1619936 0.9323584 0.1810335 0.3289422 0.9268355 0.1843681 0.3297118 0.9259042 0.07847696 0.1685387 0.9825661 -0.1594551 0.3951821 0.9046575 -0.04530203 0.9315407 0.3608044 -0.1745894 0.8633992 0.4733501 -0.4005755 0.264048 0.8773927 -0.3237485 0.351995 0.8782292 -0.2226087 0.9204905 0.3211581 -0.5800568 0.3912647 0.7144551 -0.7805817 0.2446395 0.5751904 -0.6942732 0.3619239 0.6220899 -0.2604741 0.9344743 0.2427163 -0.270695 0.9316082 0.2425499 -0.3349845 0.921014 0.1987929 -0.8562537 0.3863095 0.342921 -0.323743 0.9400021 0.1076408 -0.3640642 0.9269705 0.09045988 -0.9669691 0.2230696 0.1233315 -0.9754664 0.1940395 0.1039909 -0.8142951 0.5440515 0.2023155 -0.5472676 0.8189945 -0.1724712 -0.195034 0.9805733 0.02092307 -0.3232576 0.1610887 0.9324994 -0.07827657 0.1788812 0.9807519 -0.1834009 0.3286097 0.9264879 -0.1848244 0.3284257 0.9262702 0.1593246 0.3968471 0.9039514 0.3865851 0.3653581 0.8467972 0.3285694 0.3081343 0.892802 0.03930568 0.9309104 0.3631267 0.1814492 0.8602719 0.4764541 0.2225837 0.9205059 0.3211317 0.5802216 0.3906934 0.714634 0.2665995 0.9312447 0.2484114 0.2664144 0.9335919 0.2396447 0.7469069 0.3730877 0.5503961 0.7082587 0.3041164 0.6370894 0.3350256 0.9209918 0.1988267 0.8564051 0.3859346 0.3429648 0.356754 0.9266383 0.1186102 0.3222697 0.9460166 0.0345661 0.1943072 0.9768199 -0.08982032 0.5503162 0.8236199 0.1371222 0.924662 0.303178 0.2303984 0.8166602 0.5456547 -0.1879558 0.9731981 0.1935952 0.1241225 0.3273745 0.03110176 0.9443827 0.07822102 -0.184389 0.9797359 0.02501565 -0.1189278 0.9925877 -0.1666516 -0.279798 0.9454842 -0.1961248 -0.2753196 0.9411346 -0.3827014 -0.3884598 0.8382354 -0.6123525 -0.2370137 0.7542208 -0.646665 -0.3296771 0.6878498 -0.1074152 -0.9363859 0.3341308 -0.2087553 -0.9238804 0.3207279 -0.2956834 -0.8938331 0.3370961 -0.3452979 -0.8654572 0.3629782 -0.3200486 -0.9223811 0.2162918 -0.7414517 -0.3895511 0.546351 -0.3466377 -0.924839 0.1565729 -0.336254 -0.9377017 0.08745783 -0.2987635 -0.9539889 0.02541112 -0.1945869 -0.9782517 -0.07183051 -0.5490832 -0.8217217 0.1525814 -0.9094707 -0.2004849 0.3642373 -0.902157 -0.3510898 0.2506968 -0.8166332 -0.5456861 -0.1879811 -0.9732018 -0.1935746 0.1241261 0.5576342 7.51469e-7 0.8300868 0.557638 5.00983e-7 0.8300844 0.1108124 1.87874e-7 0.9938414 0.1107438 0 0.993849 -0.3611416 0 0.932511 -0.7513242 0 0.6599335 -0.7512963 1.25245e-6 0.6599652 -0.9712766 5.00997e-7 0.2379534 -0.9712766 5.00997e-7 0.2379534 -0.5576312 0 0.8300889 -0.557637 -1.56557e-7 0.8300849 -0.1108707 -1.6125e-6 0.9938349 -0.1108075 2.16828e-6 0.9938419 0.3611434 8.61033e-7 0.9325104 0.3611431 0 0.9325105 0.7512819 -1.22102e-6 0.6599816 0.7512957 0 0.6599659 0.9712764 0 0.2379541 0.9712764 0 0.2379544 -0.5202021 -0.2587857 0.8138917 -0.5562564 -0.06917119 0.8281269 -0.5763393 -0.1463345 0.8040021 -0.5728638 -0.1417655 0.8072978 -0.5029384 -0.1015877 0.8583315 -0.5349441 -0.169668 0.8276761 -0.3679282 -0.4636242 0.8060282 -0.4224231 -0.4853736 0.7654877 -0.2873646 -0.5379143 0.7925087 -0.210866 -0.4659557 0.8593142 -0.1089364 -0.1910601 0.9755147 0.04716867 -0.2458063 0.9681707 -0.07668215 -0.520735 0.8502676 -0.3118368 -0.7055625 0.6363485 0.03120207 -0.838321 0.5442835 0.2198941 -0.6634065 0.7152192 0.3478276 -0.2695963 0.897961 0.5071617 -0.6845972 0.5235588 0.6574991 -0.325843 0.6793535 0.008528947 -0.9368426 0.3496477 -0.01764112 -0.792544 0.6095597 -0.1934117 -0.8588067 0.4743872 0.7144376 -0.3091737 0.6276867 0.6160446 -0.7053954 0.35058 0.406179 -0.8900594 0.2069135 0.2214015 -0.9747955 -0.02747797 0.4447024 -0.8874117 0.1214101 0.9410014 -0.2477193 0.2305462 0.8154011 -0.5788217 -0.009303331 0.9582981 -0.2445758 0.1478089 0.1180269 -0.9657253 0.2311804 0.4715339 -0.01438331 0.8817307 0.4123373 -0.3059499 0.8581216 0.2931746 -0.7044122 0.6464149 0.1430624 -0.9533305 0.2658839 0.3391724 -0.385228 0.8582317 0.1304557 -0.9094452 0.3948302 0.07104355 -0.9424941 0.3265849 0.05431234 -0.7523031 0.6565746 0.2044878 -0.371491 0.9056375 0.03996735 -0.7316394 0.6805193 0.01607573 -0.9880259 0.1534489 -0.03998005 -0.7315895 0.6805721 -0.01607781 -0.9880257 0.1534495 -0.07104778 -0.942493 0.3265871 -0.130474 -0.9094431 0.394829 -0.4424552 -0.1168858 0.8891407 -0.1419817 -0.9500071 0.2780789 -0.1384986 -0.9539637 0.2660292 -0.2931654 -0.7044133 0.6464178 -0.4555945 -0.2584301 0.8518495 0.556284 -0.06905871 0.8281179 0.5464243 -0.0751962 0.834126 0.5760322 -0.1381621 0.8056663 0.4918599 -0.3073523 0.8146217 0.5331541 -0.2321003 0.8135577 0.5242645 -0.2285823 0.820303 0.4919357 -0.2657557 0.8290798 0.4866985 -0.2608633 0.8337117 0.2261431 -0.4302094 0.8739446 0.1192957 -0.196326 0.9732547 0.1085587 -0.1969446 0.9743859 0.2952561 -0.7045631 0.6453021 0.3609509 -0.6370854 0.6810556 0.2607312 -0.5979611 0.7579327 0.008400917 -0.5754379 0.8178024 0.1316797 -0.6925209 0.7092781 -0.2890243 -0.2736085 0.9173895 -0.1371402 -0.6223377 0.7706415 -0.3474865 -0.2725113 0.8972128 3.52841e-4 -0.9540959 0.299501 -0.06956505 -0.8381105 0.5410467 0.1195178 -0.9101297 0.3967108 -0.3796347 -0.7014829 0.6031578 -0.2014117 -0.8733096 0.4435806 -0.6472467 -0.3049419 0.6986289 -0.4819381 -0.6994643 0.5277172 -0.2139053 -0.9764404 -0.02843868 -0.4322174 -0.8915219 0.135562 -0.7187631 -0.2910751 0.6313913 -0.6910422 -0.6792832 0.2470529 -0.4514324 -0.8852328 0.112124 -0.9365106 -0.2651549 0.2294362 -0.9238879 -0.2623659 0.2785595 -0.7754997 -0.6209436 0.1141469 0.08395129 -0.4719871 0.8775993 0.07371973 -0.3143951 0.9464255 0.03183537 -0.7180128 0.6953015 0.05569833 -0.912407 0.4054765 0.06149959 -0.8951035 0.4415965 0.06956899 -0.9881621 0.1367333 0.01244974 -0.9194355 0.3930438 0 -1 1.70303e-7 0 -1 -2.52386e-7 1.36903e-5 0 1 -5.35298e-6 0 1 8.08107e-6 0 1 -1.63736e-5 0 1 -1.5586e-5 -7.84101e-6 1 5.31347e-6 2.30425e-6 1 0 0 1 3.53306e-6 2.76238e-6 1 0 1.83105e-6 1 8.11107e-7 3.04165e-7 1 -6.38804e-6 5.80304e-7 1 1.99552e-6 6.54721e-7 1 -2.66633e-6 4.07788e-7 1 0 1.41935e-7 1 0 5.72205e-6 1 -8.29148e-5 0 1 0.04408574 -0.7186179 0.6940064 -0.04408651 -0.7186173 0.6940069 0.1970235 -0.3283062 0.9237948 -0.1148208 -0.9055516 0.4084025 0.3531512 -0.8725569 0.3375332 0.197383 -0.8019847 0.5637912 -0.1888826 -0.6709993 0.716996 -0.2527263 -0.6501212 0.7165696 0.1260052 -0.653402 0.7464507 -0.2126826 -0.2951465 0.9314799 -0.2042688 -0.3007043 0.9315854 0.1040017 -0.3002218 0.9481829 -6.2745e-5 -0.1876349 0.9822388 0.2625882 -0.1267663 0.9565448 0.2700781 -0.1371663 0.953018 -0.2703456 -0.1375412 0.952888 -0.2625882 -0.1267647 0.956545 6.2745e-5 -0.1876351 0.9822388 -0.1040016 -0.3002231 0.9481824 0.2042653 -0.3007037 0.9315863 0.2126826 -0.2951459 0.93148 -0.1260037 -0.653402 0.746451 0.2527356 -0.6501182 0.716569 0.1888758 -0.6710079 0.7169898 -0.1973824 -0.8019845 0.5637918 -0.3531534 -0.8725568 0.3375315 0.1148249 -0.905551 0.4084025 -0.1970798 -0.3274866 0.9240736 -0.01244157 -0.9194347 0.3930459 -0.06952553 -0.9881651 0.136733 -0.06146097 -0.8951039 0.4416012 -0.05566424 -0.9124081 0.405479 -0.03181594 -0.7180131 0.695302 -0.07368135 -0.3143089 0.946457 -0.08391469 -0.4719886 0.8776021 -0.2046048 -0.3709528 0.9058316 -0.05429637 -0.752249 0.656638 -0.3395789 -0.3843509 0.858464 0.9732046 -0.1936094 0.1240491 0.8166169 -0.5456535 -0.1881468 0.9023509 -0.3499483 0.2515935 0.9094862 -0.2005922 0.3641397 0.5490384 -0.8216587 0.1530814 0.1945958 -0.9782631 -0.07165032 0.2984449 -0.9540896 0.02537357 0.3363728 -0.9375846 0.08825218 0.346641 -0.924838 0.156572 0.7418163 -0.3885824 0.5465459 0.3200514 -0.9223796 0.2162938 0.3452982 -0.8654571 0.3629785 0.2956917 -0.8938283 0.3371013 0.2087506 -0.9238803 0.3207311 0.1074181 -0.9363874 0.334126 0.6468895 -0.3287427 0.6880859 0.612537 -0.2361286 0.7543486 0.3827643 -0.3879507 0.8384425 0.1960151 -0.2749737 0.9412586 0.1666702 -0.2794895 0.9455721 -0.02492785 -0.1190542 0.9925749 -0.07813155 -0.1847195 0.9796807 -0.3273793 0.02955549 0.9444308 -0.3660949 0.03954553 0.9297369 -0.3923583 0.003088653 0.9198074 -0.4278048 -9.71918e-4 0.9038707 -0.7175689 0.002581298 0.6964827 -0.6999156 0 0.7142257 -0.9997619 -0.02028256 0.008049547 -0.1050837 0.9935913 0.04163873 0.009287655 0.9989367 0.0451579 -0.07535898 0.9953441 -0.06009548 0.04500985 0.9983416 -0.0358926 -0.07723832 0.9952924 -0.05854403 0.04527169 0.9983853 -0.0343151 0 1 1.17902e-6 0 1 -3.96106e-6 0 1 1.7681e-6 1 -1.23155e-4 0 -1 0 0 -0.5430648 0.8396907 4.8243e-4 -0.8264315 0.5630374 3.27285e-4 -0.9801973 0.1980232 0 -0.9803792 0.1952806 0.02687489 0.4829672 0.8754979 -0.01568543 0.552735 0.8333572 -1.38918e-4 0.8264318 0.5630369 3.26034e-4 0.9800147 0.1989253 1.63455e-4 0.9659199 -0.2588413 0 0.7070809 -0.7071163 0.004824042 0.2588038 -0.9659232 0.003612637 -0.2588232 -0.9659247 0 -0.7070981 -0.7070991 0.004824101 -0.9659172 -0.2588262 0.003614008 0 1 -9.59339e-7 0 1 1.90647e-6 0 1 -9.52163e-7 0 1 -2.04589e-7 0 1 -9.52417e-7 0 1 -5.49499e-7 0 1 2.19792e-6 0 1 -1.099e-6 0 1 1.09898e-6 -0.5393718 0.8339775 0.1164455 -0.8262842 0.5629437 -0.01867771 -0.8509892 0.5205124 0.06988853 -0.9828293 0.1844673 -0.004311978 0.6048252 0.791159 0.09085094 0.826304 0.5629148 -0.01867574 0.8509914 0.520501 0.069947 0.9800146 0.1989226 -0.001179873 -0.3826076 0.9238334 0.01196289 -0.6054968 0.7920567 -0.0775873 -0.9824233 0.1831236 0.03619861 -0.8434489 0.531382 -0.07891285 -0.9204112 0.3813338 -0.08618503 -0.3511084 0.9344615 0.05920118 -0.7671238 0.4246786 0.4808006 -0.3085543 0.9234256 0.2282096 -0.3523123 0.9094601 0.220813 -0.7682716 0.3935278 0.5048709 -0.1669287 0.9277174 0.333879 -0.2949073 0.4132841 0.8615254 -0.3027078 0.4024096 0.8639644 -0.1389548 0.9074007 0.3966304 0.002523839 0.9349595 0.3547455 0.2963585 0.4032516 0.8657712 0.3010102 0.4138927 0.8591192 0.139292 0.906939 0.3975669 0.1703296 0.9286363 0.3295792 0.7682678 0.3935388 0.5048681 0.349473 0.9026598 0.2511453 0.3348155 0.9186195 0.2098501 0.7671203 0.4246777 0.4808068 0.3527267 0.9339998 0.05681836 0.9204801 0.3834776 -0.0752415 0.6135852 0.7808452 0.1174477 0.4356986 0.8971672 -0.07251191 0.9823441 0.1835772 0.03604918 0.8434548 0.5313722 -0.07891529 0.6050711 0.7903802 0.09585493 0.4783646 0.8781316 -0.007226884 -0.9996244 3.63938e-4 0.02740442 0.9978137 0 -0.06609171 0.997798 -1.23135e-4 -0.06632667 -0.8357059 0 0.5491774 -0.8357015 0 0.549184 -0.3238538 0 0.9461072 -0.3238536 0 0.9461073 0.3238513 0 0.9461081 0.3238511 0 0.9461081 0.8357062 0 0.5491769 0.8357018 0 0.5491836 -0.9970436 0.005228877 -0.07665938 -0.9977977 0 -0.06633269 -0.964488 -0.2584432 -0.05449819 -0.6995551 -0.6995551 0.1457577 -0.6235514 -0.6657869 0.40977 -0.2084825 -0.7652289 0.6090648 0 -0.845002 0.5347632 0.2084811 -0.7652284 0.6090658 0.6235543 -0.6657841 0.4097701 0.9644858 -0.2584517 -0.05449753 0.6995359 -0.6995714 0.1457725 0 1 1.39909e-6 -0.1872088 0.9823201 -4.94121e-4 -0.6798587 -0.7150549 0.1627534 -0.2588247 -0.9659243 0 0.2588042 -0.9659299 0 0.6798609 -0.7150542 0.1627474 0.6806189 -0.4674208 0.5641594 0.6841515 -0.4691823 0.5583949 -0.06979531 0.9911364 -0.1130377 -0.1700219 0.9853903 0.009942173 0.4937713 -0.5547966 0.6696198 -0.8891671 -0.2823317 0.3600983 -0.06967383 0.9911667 -0.112846 -0.04752159 0.9918993 -0.1178025 0.829643 0 0.5582944 1 0 -5.23948e-5 -0.5555875 0.8314582 -3.20701e-4 -0.8314915 0.5555375 -1.64712e-4 -0.9807852 0.195091 1.67449e-4 0.1950896 0.9807813 0.002891361 0.5555682 0.831471 -3.21434e-4 0.8314709 0.5555682 -1.64136e-4 0.9807816 0.1951091 -5.13937e-5 0.9807696 -0.1951106 0.004793465 0.8314688 -0.5555663 -0.002418577 0.5555829 -0.8314577 -0.002417564 0.1950926 -0.9807848 0 -0.1950854 -0.9807746 0.004794239 -0.5555857 -0.8314559 -0.002417504 -0.8314536 -0.5555889 -0.002417385 -0.9807861 -0.1950863 0 -0.195077 0.9807879 0 -0.4398658 0.8976941 0.02576106 -0.34308 0.9296292 -0.1344832 -0.1209127 0.9899573 -0.07324439 -0.9531915 0.2032275 0.2238854 -0.9473348 0.291164 0.1333437 0.1918277 -0.8630211 0.4673296 -0.1259095 -0.5479833 0.826959 -0.1824622 -0.6903188 0.7001196 -0.2695378 -0.738236 0.6183503 -0.04402697 -0.7844834 0.6185849 0.344869 -0.8710687 0.349721 -0.2490009 -0.6207662 0.743403 -0.5327312 -0.6768568 0.5079985 -0.486621 -0.685864 0.5411012 -0.9643707 -0.1841045 0.1899858 -0.9393281 -0.2294028 0.2550237 -0.9744615 0.2097297 0.08024001 -0.9417698 -0.1188794 0.314543 -0.4720519 -0.5159724 0.7148004 -0.553003 -0.4998679 0.6665732 -0.1070454 -0.9371818 0.3320115 -0.08362567 -0.9754937 0.2035161 -0.9561886 0.2784952 0.09024399 0.8183959 -0.5591331 0.1326602 0.2641158 -0.9384392 0.222654 0.3083107 -0.9294105 0.2028313 0.3333432 -0.927087 0.1714411 0.342742 -0.9316169 0.1209048 0.4158292 -0.9039118 0.1001488 -0.02010136 -0.9983822 0.05318713 -0.2465067 0.9682108 -0.04245495 -0.2326099 0.9725037 -0.01136928 -0.2238139 0.9730722 -0.05511599 -0.2000839 0.9797759 0.002407371 -0.1797862 0.9814465 -0.06663262 -0.1646898 0.9861021 -0.02190947 -0.1375575 0.9871777 -0.08098256 -0.1393815 0.9861038 -0.0903995 -0.09302836 0.9914762 -0.09121805 -0.1179179 0.9614151 0.248549 -0.2802218 0.9171322 0.2834508 -0.17039 0.9612234 0.2168338 -0.1709746 0.9616591 0.2144284 -0.2144727 0.9610534 0.1742925 -0.2146787 0.9620075 0.1686855 -0.2470536 0.9608833 0.1251714 -0.2456626 0.9626379 0.1139221 -0.2677095 0.960619 0.07445007 -0.2631573 0.9632418 0.05397635 -0.2767171 0.9606145 0.02544927 -0.2688915 0.9631381 -0.007906138 -0.2554129 0.9665963 0.02135545 -0.06977146 0.9915633 -0.1092442 -0.3400493 -0.6262987 0.7015101 -0.2235314 -0.5177252 0.8258296 -0.2764585 0.3216236 0.9056097 -0.6454372 -0.570703 0.5076504 -0.6437076 -0.5743155 0.505769 -0.8400802 0.2612784 0.4753934 -0.6797812 0.6453116 0.3485261 -0.8839516 0.0880292 0.4592176 -0.8141447 0.3264302 0.4802207 -0.75747 0.3963561 0.5187882 -0.5314251 -0.5620095 0.6338239 -0.4964224 -0.6743913 0.5465908 -0.6934384 0.3281303 0.6414623 -0.6976405 0.3153176 0.6433293 -0.4526651 -0.6393352 0.6215665 -0.594153 0.4217028 0.6849445 -0.4963496 0.3667774 0.7868364 -0.5515133 0.1910762 0.8119871 -0.4038644 0.4439283 0.7998883 -0.4172114 -0.5408457 0.7303566 -0.4119694 -0.6064048 0.6801137 -0.7042332 -0.6028249 0.3750438 -0.5508975 -0.7064312 0.4443727 -0.9400377 -0.1471199 0.3077095 -0.9538535 0.1968067 0.2267833 -0.7761374 0.607508 0.1689519 -0.8967558 0.4056267 0.1769075 0.3300456 -0.8072393 0.4893208 -0.2001882 -0.568071 0.7982607 -0.1971265 -0.772678 0.6034153 -0.5600925 -0.4294145 0.7084487 -0.8671642 -0.4895982 0.09121441 -0.7916694 -0.5355212 0.2940694 -0.8690285 -0.3156554 0.3809871 0.4041023 -0.5643878 0.7198387 0.3380087 -0.8513076 0.4012801 0.5200874 -0.7874134 0.3308917 0.1497556 -0.7814193 0.6057698 -0.673095 -0.6536995 0.3458614 -0.7948695 -0.5233038 0.3071411 -0.9916679 0.1243159 -0.03376728 -0.9546882 0.2962352 0.02855378 -0.9338712 0.3528605 -0.05808752 -0.9701194 0.2232395 -0.0950405 -0.8466305 0.5286223 -0.06144392 -0.779816 0.6257029 -0.01956993 -0.7979571 0.6005268 -0.0513038 -0.76799 0.6403126 -0.01382827 -0.8011773 0.589332 -0.1039363 -0.7627707 0.6444361 -0.05369436 -0.727113 0.686003 0.02658373 -0.7186775 0.6953432 -7.03885e-4 -0.6761888 0.7332341 0.07167011 -0.1938166 -0.8716145 0.4502482 -0.334842 -0.6711639 0.6613773 -0.1441258 -0.9396893 0.3101801 -0.1445419 -0.939689 0.3099875 -0.1445435 -0.9396897 0.3099849 -0.1214971 -0.9360855 0.3301249 -0.1497856 -0.939287 0.308714 -0.1492024 -0.9378129 0.3134413 -0.1485664 -0.9376174 0.3143272 -0.1064835 -0.9430894 0.3150297 -0.164999 -0.9329215 0.3200513 -0.1735486 -0.9326429 0.3163195 0 1 4.53125e-7 0 1 0 0 1 -8.33491e-7 0 1 0 0 1 2.18866e-7 0 1 2.40837e-7 -0.1431157 -0.9386849 0.3136693 -0.5999672 0.7818619 -0.1695035 -0.3586148 0.9302918 -0.07715433 -0.3416084 0.9305922 -0.1315364 -0.4758468 0.8778123 -0.05491399 -0.3378105 0.9405947 0.03414219 -0.3705772 0.9288012 -9.99334e-4 -0.2694845 0.9591628 -0.08593535 -0.15145 0.9877588 0.03735691 -0.9987608 0.0224263 0.04443156 -1 -2.00674e-6 0 -0.001180112 -0.9999989 -0.001037061 0.6689726 -0.7179068 0.1925759 0.7136579 -0.6457908 0.2713793 0.6746123 -0.6515424 0.346974 0.6488733 -0.6298755 0.4268728 0.6481493 -0.6266586 0.432668 0.5822665 -0.6480965 0.4908532 0.6805555 -0.5790751 0.4489057 -0.5587534 0.8293173 -0.005236923 -0.6304401 0.7734203 -0.06607842 -0.6232864 0.7819261 -0.01027661 -0.623549 0.7816022 -0.01687884 -0.5816628 0.8124368 0.04018729 -0.5819034 0.8114953 0.05351597 -0.5660057 0.8204912 0.08019912 -0.5820396 0.8125507 0.03148519 -0.5772521 0.8084248 0.1150189 -0.543753 0.8255069 0.151232 -0.5412144 0.8206725 0.1832586 -0.4846063 0.8395687 0.2455226 -0.5106934 0.8274896 0.2333521 -0.4737957 0.816018 0.331108 -0.404368 0.8535255 0.3286046 -0.396876 0.8348733 0.3814132 -0.3206833 0.854772 0.4080774 -0.3302968 0.8481132 0.414256 -0.2594676 0.8268337 0.4990217 -0.2167969 0.8626586 0.4569675 2.42274e-4 -1 -3.12272e-5 -0.001079082 -0.9998143 0.01923954 -0.2663822 -0.9281531 0.2599468 -0.2226665 -0.9283238 0.2977156 0.09301239 0.9914765 -0.09123075 0.1393746 0.9861056 -0.09039115 0.1375457 0.9871777 -0.08100396 0.1494137 0.987223 -0.05537319 0.06819623 0.9915381 -0.1104608 0.07177007 0.99107 -0.1123802 0 1 -1.44674e-6 0 1 1.09329e-6 0 1 0 0 1 -1.00674e-6 0 1 5.00188e-7 0 1 5.85516e-7 0 1 5.62786e-7 -9.45881e-4 0.9999995 -2.75818e-4 -0.008570671 -0.9999616 0.001843988 -0.008046329 -0.9999645 0.002516627 -0.007454574 -0.9999672 0.003172457 -0.006781756 -0.9999697 0.003814816 -0.006014287 -0.9999721 0.004432618 -0.005140066 -0.9999743 0.005015373 -0.004145205 -0.9999762 0.005542695 -0.003021001 -0.9999776 0.005984246 0.3253078 0.86088 0.3912294 0.3353339 0.8403869 0.4257947 0.2328538 0.8649786 0.4445123 0.2502915 0.8126863 0.5262085 0.1764569 0.8381875 0.5160472 0.108153 0.8436713 0.5258532 0.111874 0.8617501 0.4948445 2.93952e-4 0.8386349 0.544694 -0.009137392 -0.9999578 0.001014053 -0.006301701 -0.9999618 0.006070911 0.1039888 -0.9435235 0.314563 0.07082712 -0.9362 0.3442571 -0.005549609 -0.9507325 0.3099626 0.04523348 -0.9048653 0.4232882 0.1445341 -0.9396936 0.3099772 0.1445415 -0.939691 0.309982 0.1273798 -0.9415358 0.3119052 0.1891222 -0.9183729 0.3475975 0.3039665 0.342953 0.8888125 0.2804162 0.2789188 0.9184613 0.1553155 -0.6371626 0.7549178 0.2523757 -0.5058097 0.8249018 0.1803314 0.445826 0.8767666 0.02352964 0.3836897 0.9231623 0 -0.5819038 0.8132576 0.4301446 -0.5448245 0.7198209 0.3903565 -0.607702 0.6916069 0.5324332 0.4040622 0.7438069 0.4447464 0.03826415 0.8948388 0.4621932 0.5201581 0.7182013 0.2946085 -0.6401373 0.7095282 1.71358e-4 0.9474422 0.3199272 0.1941332 0.9599966 0.2017894 0.1373166 0.9475201 0.2887035 0.1705607 0.9612523 0.2165713 0.171053 0.9616236 0.2145248 0.214577 0.961078 0.1740285 0.2147515 0.9619804 0.1687477 0.0580669 -0.9880303 0.1429136 0.1169387 -0.9522553 0.28202 0.032947 0.9525757 0.302513 0.07027965 0.9478498 0.3108724 0.09367543 0.9526427 0.2893038 0 1 4.53124e-7 0 1 -6.00837e-7 -0.04460245 0.9908387 -0.1274728 -0.02095264 0.9922768 -0.1222616 0.02095055 0.9922778 -0.1222537 0.04459178 0.9908378 -0.1274845 0.04751849 0.9919002 -0.1177966 -0.1672708 -0.9285645 0.3313435 -0.2199038 -0.9266221 0.3049817 -0.03233152 0.9524945 0.3028351 -0.07020843 0.947472 0.3120378 -0.09560763 0.9524616 0.2892684 -0.2322025 -0.6087526 0.7586187 -0.2873092 0.2939853 0.9116063 -0.1316278 0.4609094 0.8776313 -0.01399791 -0.6233049 0.7818536 0 0.316581 0.9485655 9.45796e-4 0.9999995 -2.75429e-4 -0.1050621 -0.9425588 0.317088 -0.09282612 -0.9347614 0.3429352 -0.03533965 -0.9430736 0.3307014 -0.1682182 0.8287444 0.5337466 -0.1321681 0.7983899 0.5874565 -0.06548124 0.8972908 0.4365563 0.01265799 0.8676803 0.4969617 0 -1 -2.4102e-7 0.04879713 -0.9986239 0.01921701 -0.2765444 -0.5929449 0.7562668 -0.2212658 -0.6100214 0.760865 0.889209 -0.2822818 0.3600338 0.1199291 0.9925267 0.02253824 -0.5501474 -0.6272983 0.5512121 0.8536071 0.2229846 0.470779 0.7894631 0.3702331 0.4895667 0.1710899 -0.9322401 0.3188365 0.1746863 -0.9329746 0.3147113 0.2767109 0.9606188 0.02534931 0.263171 0.9632381 0.05397689 0.2677149 0.9606305 0.074283 0.2457146 0.9626218 0.1139464 0.2470988 0.9609021 0.1249375 0.3688555 -0.8658204 0.338084 0.4026026 -0.8445747 0.3529942 0.308172 -0.8786218 0.3647655 0.7923155 -0.4864156 0.3682882 0.7305961 -0.5583033 0.3930992 0.9395703 -0.146551 0.3094035 0.928402 0.290261 0.2319882 0.9281877 0.2916604 0.2310886 0.6097099 0.4163735 0.6744531 0.4500975 -0.6295736 0.6332847 0.5276497 -0.5685282 0.6311589 0.5146833 -0.5832202 0.6284548 0.6990765 0.2892658 0.6539245 0.6960498 0.2586018 0.6698059 0.7332493 0.3929696 0.5549058 0.5154395 -0.6392898 0.5706407 0.7147256 -0.4433333 0.5409463 0.5036937 -0.6912699 0.5181106 0.6269823 -0.5819169 0.5179439 0.5468778 -0.6432105 0.535915 0.8545992 0.2362191 0.462451 0.8735074 0.3251897 0.3622661 0.7715933 0.6347557 0.04158359 0.1448653 -0.9397484 0.3096565 0.1440095 -0.939971 0.3093798 0.1439254 -0.9399907 0.3093592 0.1436874 -0.9400364 0.3093308 0.1435407 -0.9400591 0.3093301 0.1434216 -0.9400692 0.3093546 0.1033853 -0.93946 0.32669 0.4052484 0.8371889 0.3672718 0.4044098 0.8537505 0.3279677 0.4530866 0.8312945 0.3219658 0.4888369 0.8366282 0.2471675 0.4901078 0.8324457 0.2585124 0.5333601 0.82041 0.2060447 0.5503028 0.8208827 0.1527036 0.5477409 0.8253573 0.136986 0.5793785 0.809996 0.09070283 0.5819945 0.8114432 0.05331397 0.5820823 0.8113909 0.05315387 0.6388975 0.768046 -0.04376792 0.5823343 0.8117543 0.04406726 -0.6297601 -0.6157538 0.47355 -0.6271269 -0.61181 0.4820793 -0.6740816 -0.6303635 0.3850401 -0.7233169 -0.6162534 0.3115198 -0.7775487 -0.5790694 0.2451464 -0.694438 -0.6441196 0.320727 1 9.2081e-5 0 1 1.42916e-6 0 1 2.5156e-6 0 0.1012263 0.9936183 0.04976046 0.2418722 0.9669444 -0.08072465 0.3517644 0.8901475 -0.2896541 0.319589 0.9434137 -0.08850628 0.3643679 0.9312353 0.0060817 0.4288873 0.9010788 -0.06412988 0.341588 0.9306011 -0.1315265 0.358623 0.9302885 -0.07715469 0.4497612 0.8931353 0.004944205 0.439339 0.8979295 0.02652955 0.5673882 0.8141484 -0.1234225 0.542482 0.8392208 -0.03771036 0.1955649 -0.8704745 0.4516953 0.2745296 -0.7721582 0.5730665 0.3052283 -0.6570864 0.6892555 0.9903784 0.1327756 -0.03900408 0.9073802 0.4119725 0.0833047 0.9103939 0.3720304 0.1810426 0.8285985 0.5490783 -0.1092599 0.7531706 0.6424418 -0.1414313 0.7841973 0.6195065 -0.0353055 0.9006777 -0.3103618 0.3040649 0.7987238 -0.5374888 0.2704553 0.7540262 -0.4613333 0.4675641 -0.2270545 -0.8699207 0.4378176 0.8582275 -0.4431359 0.2589904 0.9269313 -0.3494888 0.1365875 0.8458942 -0.475709 0.2411722 0.8216131 -0.5431307 0.1730923 -0.2034394 -0.8764474 0.4364084 0.2270879 0.9730886 -0.03911292 0.2774384 0.9607207 0.006608605 0.2238214 0.9730706 -0.05511504 0.2000846 0.9797757 0.002401053 0.1887501 0.9813428 -0.03660351 0.2663174 0.9637076 -0.01851803 0.2754459 0.9612826 -0.008094966 -0.2649551 -0.9269974 0.2654709 -0.2992185 -0.9272766 0.2250031 -0.2998428 -0.9280344 0.2210121 -0.3246498 -0.9274775 0.18544 -0.3248423 -0.9279558 0.1826905 -0.3430553 -0.9276227 0.1477468 -0.3430472 -0.9279026 0.1459982 -0.3559868 -0.9277262 0.1122396 -0.3559244 -0.9278636 0.1112971 0.920683 0.3750211 -0.1081768 -0.6946235 -0.6997585 0.1668421 -0.1926451 -0.86351 0.4660886 0.1259085 -0.5479866 0.8269569 0.1832948 -0.6922963 0.6979463 0.2395914 -0.7246619 0.6461124 0.3299832 -0.7194402 0.6111603 0.04363238 -0.7846601 0.6183888 -0.3957128 -0.9000084 0.1827463 -0.4031018 -0.902113 0.1539521 -0.3804691 -0.9247195 -0.01172101 0.2491165 -0.6247045 0.7400577 0.337868 -0.8061593 0.4857493 0.7485208 -0.5875829 0.3073483 0.4964801 -0.6811447 0.5380981 0.9643742 -0.1840826 0.1899895 0.9985205 -0.05405628 0.005905687 0.9406706 -0.09921759 0.3244917 0.9400359 -0.09055209 0.3288356 0.4868083 -0.5134374 0.7066823 0.8262403 -0.3874608 0.4089024 -0.366616 -0.9272912 0.07565581 -0.3647415 -0.9277921 0.07852065 0.2002123 -0.5680648 0.798259 0.1786817 -0.9140068 0.3642312 -0.1870584 -0.7481064 0.6366679 0.8344709 -0.2208986 0.5048388 0.8941393 -0.2304596 0.3839313 0.9409665 0.3361978 -0.03941136 0.9936861 0.1094021 -0.02488267 0.990553 0.1364832 -0.01331132 1 -3.75782e-6 0 0.9998699 0.007268965 0.0144034 -0.704915 -0.6942662 0.1452219 0.9614057 0.2549124 0.1035314 0.9998137 0.00684899 0.01804786 0.9902083 0.1392028 -0.01050209 0.9922821 0.1211351 -0.0265069 0.7042585 -0.06135249 0.7072877 0.7239525 -0.08033877 0.6851558 0.6983557 -0.06705397 0.712603 0.7075556 -0.1746252 0.6847416 0.6875693 -0.2029396 0.6971829 0.6896845 -0.356697 0.6301608 0.660139 -0.289966 0.6929187 0.7391296 -0.2969395 0.6045779 0.6596161 -0.2923703 0.6924061 0.7135635 -0.4679442 0.5213977 0.5224345 -0.7449344 0.4148916 0.5623597 -0.6221847 0.5446446 0.538944 -0.6397623 0.547945 -0.1649883 -0.6948317 0.6999912 -0.1721705 -0.7020137 0.6910384 -0.2965725 -0.6659905 0.6844717 -0.3183978 -0.6728961 0.6677079 -0.4518458 -0.6214222 0.6400547 -0.458203 -0.6214787 0.6354638 -0.662901 -0.3759033 0.6475023 -0.534205 -0.5139482 0.6711797 -0.4940853 -0.6083303 0.6211394 -0.6978292 -0.07750886 0.7120581 -0.9061062 -0.3124067 -0.2852609 -0.7172482 -0.1574019 0.6788075 -0.5740024 -0.07080924 0.8157863 -0.6710348 -0.1832863 0.7184138 -0.6809132 -0.2819246 0.675926 -0.6374452 -0.3846929 0.667589 -0.7220264 -0.4327795 0.5397961 0.11515 0.9931567 -0.0194981 0.1239584 0.9922873 -6.71187e-4 -0.07000875 0.9917711 -0.1071866 -0.0679205 0.9915012 -0.1109606 -0.04278177 0.9915738 -0.1222749 -0.04209768 0.9915068 -0.123053 -0.01461929 0.9915618 -0.1288074 -0.01424247 0.9915309 -0.1290883 0.01421999 0.9915563 -0.1288954 0.01463288 0.9915258 -0.1290836 0.0420947 0.9915072 -0.1230506 0.04277223 0.9915734 -0.1222822 0.06837439 0.9914932 -0.1107526 0.2103151 0.9718128 -0.1065243 0.04527276 0.9962331 -0.07396137 -0.1653163 0.9857091 -0.03237485 -0.1740418 0.9846469 -0.01341986 0.1215348 -0.4375799 0.8909283 -0.782398 -0.2745555 0.5589927 0.5069853 -0.2130013 0.8352223 0.4329984 -0.2010579 0.8786855 -0.8757907 -0.1192685 0.467724 -0.9418911 -0.02902853 0.3346616 -0.9712263 0.01020473 0.23794 -0.7445427 -0.1339634 0.6539955 -0.3532124 -0.2099426 0.9116827 -0.3567031 0.1562505 0.9210585 0.1107664 -3.82817e-6 0.9938465 0.5561771 -0.07181984 0.8279547 0.3573404 0.146095 0.9224771 0.7510228 0.02514797 0.6597973 0.971076 -0.02064311 0.2378768 0.8483937 -0.1308526 0.5129385 0.867828 -0.1354771 0.4780381 -0.4048523 -0.2260404 0.8860025 -0.7133201 -0.06060367 0.6982132 -0.5534284 -0.1223115 0.8238672 -0.1083685 -0.2059179 0.9725504 -0.2138177 -0.3760483 0.901593 0.7823982 -0.2746399 0.5589509 -0.01554936 0.9904477 -0.1370099 0.01553106 0.9904451 -0.1370303 -0.0915296 -0.9255647 0.3673586 -0.09961438 -0.9288843 0.3567224 -0.162342 -0.9261422 0.3404493 -0.9997832 -0.01466882 0.01477956 0.947062 -0.1894124 -0.2592235 0.7275558 0 0.6860486 0.726333 -6.4839e-5 0.6873431 0.695419 3.81278e-4 0.7186044 0.7154067 0.002270877 0.6987046 0.6999159 2.7339e-6 0.7142254 0.6315467 -0.002501487 0.7753339 0.6148269 -0.006632447 0.7886343 0.5668371 0.001422405 0.8238286 0.4715737 0.008822381 0.8817825 0.4264562 -0.001268088 0.9045074 0.4857826 -0.001645624 0.8740781 0.4415702 -0.03337681 0.8966058 0.4167212 -0.06069684 0.9070057 0.4557999 -5.20191e-4 0.8900822 0.3554891 8.1172e-5 0.9346804 0.3657844 0.03910851 0.9298777 0.3227239 -0.009049594 0.9464499 0.272421 -0.04836589 0.9609619 0.2800182 -0.03618645 0.9593125 0.1562021 0.02802324 0.9873275 0.09442484 -0.04775547 0.994386 0 0.03384745 0.999427 -0.09442532 -0.04775494 0.994386 -0.1562021 0.02802312 0.9873275 -0.2684181 -0.03007429 0.962833 -0.3746107 -0.1566021 0.9138613 -0.2801716 -0.0140649 0.959847 -0.3741421 0.002497851 0.9273681 -0.4835739 0 0.8753036 -0.471597 0.008808493 0.8817701 -0.4280844 -0.01025849 0.9036805 -0.4896432 -0.001502633 0.8719217 -0.4556691 -0.02415341 0.8898215 -0.5389022 3.45079e-4 0.8423684 -0.6557434 -0.02015328 0.7547149 -0.61484 -0.003781557 0.7886428 -0.6950601 3.79004e-4 0.7189515 -0.7273829 -8.18578e-5 0.6862319 -0.7262931 0 0.6873852 0 1 -2.5572e-6 0 1 1.99401e-6 0 1 1.46475e-6 0 -1 6.31455e-6 0 -1 3.61023e-6 -0.3275542 0 0.9448325 -0.3275166 3.14031e-6 0.9448455 -0.079584 -6.96924e-6 0.9968281 -0.07951372 6.65685e-6 0.9968338 0.1735915 1.56966e-6 0.9848178 0.1736273 5.96455e-6 0.9848114 0.4152699 -6.28131e-7 0.9096983 0.4152849 0 0.9096914 0.6303395 -4.3969e-6 0.7763196 0.6303293 -6.28118e-7 0.776328 0.8050481 -6.90664e-6 0.5932096 0.805091 5.02203e-6 0.5931515 0.9283191 -9.39685e-6 0.3717847 0.9283614 1.0022e-5 0.371679 0.9919638 -1.06784e-5 0.1265224 0.9919716 0 0.1264611 0.07958567 0 0.996828 0.07962554 0 0.9968249 -0.1735882 0 0.9848183 -0.1735882 0 0.9848183 -0.4153034 0 0.909683 -0.4152699 0 0.9096983 -0.6303153 0 0.7763394 -0.9283177 0 0.3717879 -0.9919636 0 0.1265239 -0.9919649 0 0.1265137 0.3232129 0.1619913 0.9323585 0.1810334 0.3289432 0.9268351 0.1843685 0.3297115 0.9259042 0.07847672 0.1685379 0.9825663 -0.1594553 0.3951826 0.9046573 -0.04530256 0.9315405 0.3608049 -0.1745921 0.8633985 0.4733505 -0.4005588 0.2640538 0.8773986 -0.3237463 0.3519926 0.8782309 -0.2226099 0.9204897 0.3211598 -0.5800693 0.3912622 0.7144463 -0.7805877 0.2446452 0.5751796 -0.6942772 0.3619237 0.6220855 -0.2604727 0.9344747 0.242716 -0.2706985 0.9316072 0.2425498 -0.3349857 0.9210135 0.1987932 -0.8562473 0.3863154 0.34293 -0.323743 0.9400021 0.1076416 -0.3640635 0.9269708 0.09046024 -0.966971 0.2230652 0.1233251 -0.975467 0.194036 0.1039916 -0.8142861 0.5440649 0.202316 -0.5472677 0.8189947 -0.1724703 -0.195034 0.9805734 0.02092117 -0.07827651 0.1788819 0.9807518 -0.1834024 0.3286129 0.9264866 -0.1848071 0.3284284 0.9262727 0.1593245 0.3968477 0.9039512 0.3865703 0.365348 0.8468083 0.3285778 0.3081328 0.8927994 0.03931337 0.9309094 0.3631283 0.1814485 0.860272 0.4764542 0.2225834 0.9205057 0.3211323 0.5802356 0.3906853 0.714627 0.2666 0.9312444 0.2484118 0.2664145 0.9335919 0.2396448 0.7469216 0.3730925 0.5503727 0.7082537 0.30412 0.6370932 0.3350259 0.9209917 0.1988269 0.8563952 0.3859448 0.342978 0.3222717 0.946016 0.03456628 0.1943064 0.9768201 -0.0898199 0.5503183 0.8236184 0.1371226 0.9246596 0.3031837 0.2304003 0.9731979 0.1935951 0.1241243 0.3273588 0.03110563 0.9443881 0.07822394 -0.1843963 0.9797343 0.02501583 -0.1189287 0.9925876 -0.196121 -0.2753202 0.9411352 -0.3826721 -0.3884667 0.8382456 -0.6123628 -0.2370278 0.7542079 -0.6466691 -0.3296824 0.6878436 -0.1074144 -0.9363869 0.3341283 -0.2087571 -0.9238796 0.320729 -0.2957141 -0.8938187 0.3371073 -0.3453073 -0.8654536 0.3629782 -0.3200519 -0.9223795 0.2162941 -0.7414494 -0.3895579 0.5463494 -0.346641 -0.924838 0.156572 -0.3362544 -0.9377009 0.08746469 -0.2987666 -0.953988 0.02540689 -0.1945877 -0.9782515 -0.07183074 -0.5490854 -0.821721 0.1525779 -0.9094669 -0.2004809 0.3642493 -0.9021546 -0.3511012 0.250689 -0.8166614 -0.5456555 -0.1879477 -0.9731968 -0.1936026 0.1241219 0.557637 0 0.830085 0.557637 0 0.8300849 0.1108072 0 0.993842 0.1107439 0 0.993849 -0.3611987 0 0.9324889 -0.3611429 0 0.9325106 -0.7512952 0 0.6599664 -0.7512953 1.28376e-6 0.6599663 -0.9712764 4.69684e-7 0.2379544 -0.97128 0 0.2379395 -0.5576308 0 0.8300892 -0.5576162 5.00963e-7 0.8300991 -0.1108706 -1.50291e-6 0.9938349 -0.1108117 2.19185e-6 0.9938415 0.3611447 1.00193e-6 0.9325098 0.3612005 1.00191e-6 0.9324883 0.7512809 -5.00929e-7 0.6599826 0.7512688 0 0.6599965 0.9712767 0 0.2379532 0.9712802 0 0.2379386 -0.5202017 -0.2587888 0.813891 -0.5562989 -0.06916588 0.8280989 -0.5763384 -0.1463436 0.804001 -0.572912 -0.1417641 0.8072638 -0.5029389 -0.1015896 0.858331 -0.5349465 -0.1696701 0.8276741 -0.3679513 -0.4636304 0.806014 -0.4224026 -0.4853973 0.7654839 -0.2873507 -0.5379293 0.7925035 -0.210828 -0.465965 0.8593184 -0.1088839 -0.1910625 0.9755201 0.04712587 -0.2458045 0.9681733 -0.07668268 -0.520735 0.8502677 -0.3118354 -0.7055594 0.6363526 0.03120064 -0.8383007 0.5443148 0.2198807 -0.6633926 0.7152362 0.3478292 -0.2695976 0.89796 0.5071625 -0.6845974 0.5235579 0.6574988 -0.325842 0.6793544 0.008528828 -0.9368424 0.3496479 -0.01762491 -0.7925555 0.6095452 -0.1933858 -0.8588144 0.4743835 -0.06005418 -0.9436043 0.3255833 0.7144359 -0.309176 0.6276875 0.6160334 -0.7054083 0.3505739 0.4061858 -0.8900607 0.2068941 0.3385329 -0.939684 0.04888141 0.4446725 -0.8874277 0.1214028 0.9410023 -0.2477176 0.2305449 0.8154081 -0.5788119 -0.009303331 0.9582853 -0.244593 0.1478638 0.1180189 -0.9657322 0.2311553 0.471534 -0.01438546 0.8817307 0.4123391 -0.3059462 0.8581221 0.2931734 -0.7044092 0.6464187 0.1430543 -0.9533349 0.2658724 0.3391726 -0.3852264 0.8582323 0.1304484 -0.909453 0.3948144 0.07104372 -0.9424966 0.3265779 0.05430996 -0.7523022 0.6565759 0.03996342 -0.7316475 0.6805108 0.01607513 -0.988026 0.1534482 -0.03997993 -0.7315849 0.6805771 -0.01607787 -0.9880257 0.15345 -0.07104831 -0.9424923 0.3265894 -0.130474 -0.9094444 0.3948258 -0.4424555 -0.1168809 0.8891412 -0.1419815 -0.9500072 0.2780786 -0.1384984 -0.9539638 0.266029 -0.293165 -0.7044141 0.6464171 -0.4555923 -0.2584289 0.8518511 0.5563261 -0.06905138 0.8280901 0.5464122 -0.07520806 0.8341329 0.5759911 -0.1381884 0.8056913 0.4918567 -0.3073551 0.8146227 0.5331567 -0.232103 0.8135553 0.5242867 -0.2285747 0.8202909 0.4919223 -0.2657617 0.8290858 0.4866643 -0.2608736 0.8337284 0.2261926 -0.4301855 0.8739436 0.1192962 -0.1963214 0.9732555 0.1085587 -0.196945 0.9743858 0.2952591 -0.7045558 0.6453087 0.3609427 -0.6371008 0.6810455 0.2607129 -0.597975 0.7579279 0.008454144 -0.5754375 0.8178021 0.1316787 -0.6925271 0.7092722 -0.2890246 -0.2736105 0.9173888 -0.1371398 -0.6223405 0.7706393 -0.3474874 -0.2725124 0.8972121 3.25673e-4 -0.9541056 0.2994701 -0.06953895 -0.8381013 0.5410645 0.1195502 -0.9101141 0.396737 -0.3796343 -0.7014837 0.6031571 -0.2014111 -0.8733103 0.4435794 -0.647301 -0.3049226 0.6985868 -0.4819368 -0.6994639 0.5277189 -0.2138976 -0.9764416 -0.02845561 -0.4322295 -0.891519 0.1355419 -0.7187423 -0.2910736 0.6314157 -0.6910426 -0.6792786 0.2470641 -0.4514073 -0.8852436 0.1121389 -0.9365185 -0.2651449 0.2294149 -0.9238848 -0.2623777 0.2785585 -0.7754887 -0.620957 0.1141481 0.08395129 -0.4719866 0.8775995 0.07372015 -0.3143979 0.9464246 0.03183543 -0.7180109 0.6953034 0.05569863 -0.9124087 0.4054729 0.06149965 -0.8951033 0.4415969 0.06956493 -0.9881619 0.1367365 0.01245504 -0.9194358 0.3930431 0 -1 4.95681e-7 0 -1 1.70304e-7 0 -1 -7.57151e-7 3.42246e-5 0 1 -5.35299e-6 0 1 2.29107e-6 0 1 -1.65208e-5 0 1 -1.21978e-5 -5.22733e-6 1 -2.79659e-7 1.53617e-6 1 2.64978e-6 1.84159e-6 1 0 1.2207e-6 1 4.05554e-6 2.02777e-7 1 -5.4755e-6 3.86866e-7 1 -1.33034e-6 4.36484e-7 1 1.33317e-6 2.71858e-7 1 0 0 1 0 3.8147e-6 1 0 0.8944273 0.4472137 0.04409027 -0.7186179 0.6940062 -0.04408603 -0.7186174 0.6940069 0.1970232 -0.3283033 0.9237959 -0.1148216 -0.9055503 0.4084052 0.3531453 -0.8725535 0.3375484 0.1973658 -0.8019872 0.5637937 -0.1888825 -0.6710053 0.7169905 -0.2527239 -0.6501148 0.7165762 0.1260042 -0.6533969 0.7464553 -0.2126848 -0.2951405 0.9314813 -0.2042585 -0.3007031 0.9315879 0.1040016 -0.3002238 0.9481822 -7.66877e-5 -0.1876338 0.9822391 0.262585 -0.1267623 0.9565461 0.2700877 -0.1371637 0.9530156 -0.2703549 -0.1375364 0.9528862 -0.2625849 -0.1267631 0.956546 7.66877e-5 -0.1876333 0.9822393 -0.1040025 -0.3002275 0.9481809 0.204261 -0.3007043 0.9315871 0.2126826 -0.295147 0.9314798 -0.1260036 -0.6533979 0.7464545 0.2527327 -0.6501175 0.7165706 0.188877 -0.6709991 0.7169978 -0.197368 -0.8019899 0.5637892 -0.3531457 -0.8725546 0.3375452 0.1148244 -0.9055503 0.4084042 -0.1970812 -0.3274851 0.9240739 -0.01244688 -0.9194329 0.3930503 -0.06952106 -0.9881661 0.1367288 -0.06146043 -0.8951025 0.4416044 -0.05566418 -0.9124081 0.4054787 -0.03181576 -0.7180101 0.6953052 -0.07368171 -0.3143135 0.9464555 -0.08391422 -0.471988 0.8776024 -0.2046118 -0.3709434 0.905834 -0.05429369 -0.7522509 0.6566359 -0.3395856 -0.3843429 0.8584651 0.9732077 -0.1935811 0.1240701 0.8165884 -0.5456888 -0.1881682 0.902351 -0.3499484 0.2515926 0.9094901 -0.2006197 0.3641147 0.5490403 -0.8216574 0.153082 0.194595 -0.9782633 -0.07165002 0.2984515 -0.9540874 0.0253781 0.3363723 -0.9375854 0.08824759 0.3466402 -0.9248383 0.1565716 0.7418172 -0.3885865 0.5465417 0.3200529 -0.9223789 0.2162948 0.3452972 -0.8654603 0.3629718 0.2957256 -0.8938149 0.3371075 0.2087482 -0.9238821 0.3207278 0.1074172 -0.9363877 0.3341253 0.6468898 -0.3287492 0.6880826 0.6125271 -0.2361273 0.754357 0.3827768 -0.3879485 0.8384377 0.1960151 -0.2749744 0.9412583 0.1666672 -0.2794893 0.9455727 -0.02492827 -0.1190554 0.9925747 -0.07816648 -0.1847264 0.9796766 -0.3273636 0.02955687 0.9444361 -0.3660877 0.03954648 0.9297397 -0.3923583 0.003088593 0.9198074 -0.4278048 -9.71403e-4 0.9038707 -0.7175288 0.002583503 0.6965241 -0.6999364 0 0.7142053 0 -1 9.88534e-7 -0.9997617 -0.02029365 0.008054614 0.009287655 0.9989368 0.04515784 -0.07535886 0.9953441 -0.06009387 0.04501003 0.9983416 -0.03589278 -0.0772376 0.9952924 -0.05854499 0.04527163 0.9983852 -0.03431504 0 1 1.17901e-6 0 1 -3.96071e-6 0 1 1.76805e-6 -1 3.62144e-7 0 -0.5430648 0.8396907 4.82393e-4 -0.8264437 0.5630194 3.2729e-4 -0.9801926 0.1980469 0 -0.9803741 0.1953064 0.02687472 0.4829632 0.8755002 -0.01568531 0.552717 0.8333691 -1.38812e-4 0.8264399 0.5630251 3.24843e-4 0.9800156 0.1989206 1.63328e-4 0.965921 -0.2588375 0 0.7070809 -0.7071163 0.004823923 0.2588038 -0.9659232 0.003612518 -0.7070981 -0.7070991 0.004823923 -0.9659167 -0.2588282 0.003612577 0 1 -9.59354e-7 0 1 1.90647e-6 0 1 -9.52167e-7 0 1 -2.04591e-7 0 1 2.19793e-6 -0.8263114 0.5629037 -0.01868373 -0.8509908 0.5205177 0.0698291 -0.9828236 0.184496 -0.004386663 0.6048265 0.7911542 0.09088516 0.8263018 0.5629194 -0.01863598 0.85099 0.5205044 0.06993812 0.9800146 0.1989226 -0.001185834 -0.3826095 0.9238328 0.01196295 -0.6055045 0.792051 -0.07758653 -0.9824225 0.1831277 0.03620064 -0.843442 0.5313928 -0.07891297 -0.9204106 0.381335 -0.08618521 -0.3511083 0.9344614 0.05920231 -0.7671368 0.4246712 0.4807865 -0.308559 0.923425 0.2282058 -0.3523127 0.9094608 0.2208097 -0.7682725 0.3935126 0.5048813 -0.1669071 0.9277224 0.3338763 -0.2949511 0.413254 0.8615249 -0.3026888 0.4024366 0.8639586 -0.1389601 0.9074052 0.3966183 0.002532839 0.934964 0.3547337 0.2963958 0.4032707 0.8657496 0.3009995 0.4138633 0.859137 0.1392869 0.9069462 0.3975523 0.1703251 0.9286412 0.329568 0.7682695 0.3935213 0.5048791 0.3494669 0.9026612 0.2511488 0.3348155 0.9186205 0.2098455 0.7671328 0.4246703 0.4807937 0.3527268 0.934 0.05681604 0.9204775 0.3834838 -0.07524281 0.6135864 0.7808443 0.1174479 0.9823466 0.1835634 0.03605121 0.8434485 0.5313822 -0.07891601 0.6050687 0.7903822 0.09585458 0.4783692 0.8781291 -0.007226943 -0.9996244 3.63717e-4 0.02740442 0.9978135 0 -0.06609231 0.997798 -1.22723e-4 -0.06632727 -0.8357018 0 0.5491836 -0.3238794 0 0.9460985 -0.3239053 0 0.9460896 0.3238773 0 0.9460991 0.3239032 0 0.9460903 0.8357015 0 0.549184 -0.9970437 0.00522834 -0.07665872 -0.9977977 0 -0.06633126 -0.9644887 -0.2584411 -0.05449753 -0.6995587 -0.6995517 0.1457571 -0.6235508 -0.6657857 0.4097731 -0.2085139 -0.7652241 0.60906 0 -0.8450086 0.5347527 0.208513 -0.7652225 0.6090624 0.6235525 -0.6657827 0.4097754 0.9644863 -0.2584495 -0.05449831 0.699537 -0.6995701 0.1457728 0 1 1.3991e-6 -0.1872099 0.9823199 -4.94085e-4 -0.6798563 -0.7150568 0.1627552 -0.2588235 -0.9659247 0 0.6798601 -0.7150551 0.1627472 0.6806184 -0.4674172 0.564163 0.6841571 -0.4691831 0.5583873 -0.06979548 0.991136 -0.1130406 -0.170021 0.9853904 0.0099442 0.4937721 -0.5547935 0.6696218 -0.8891666 -0.2823334 0.3600981 -0.06967383 0.9911669 -0.1128442 -0.04752171 0.9918996 -0.1178006 -0.8314865 0.5555451 -1.62786e-4 -0.9807835 0.1950996 1.69045e-4 0.1950907 0.980781 0.002891421 0.5555733 0.8314675 -3.22302e-4 0.8314709 0.5555682 -1.64222e-4 0.9807817 0.1951087 -5.13936e-5 0.9807748 -0.195084 0.004795312 0.831456 -0.5555855 -0.002417981 0.1950916 -0.9807851 0 -0.831469 -0.555566 -0.002418279 -0.9807803 -0.1951156 0 -0.1950764 0.9807881 0 -0.4398789 0.8976876 0.02576094 -0.3430815 0.9296283 -0.1344856 -0.1209136 0.9899572 -0.07324492 -0.9531877 0.2032364 0.2238936 -0.9473296 0.2911784 0.1333487 0.1918165 -0.8630225 0.4673315 -0.1259078 -0.5479939 0.8269522 -0.1824597 -0.6903181 0.7001211 -0.2695391 -0.7382368 0.6183487 -0.04402703 -0.7844842 0.6185842 0.3448621 -0.8710698 0.3497253 -0.2489994 -0.6207612 0.7434076 -0.5327301 -0.6768576 0.5079985 -0.4866027 -0.6858671 0.5411139 -0.9643545 -0.1841418 0.190032 -0.9393287 -0.2294 0.2550244 -0.9744618 0.2097287 0.08023798 -0.9417751 -0.1188753 0.3145288 -0.4720364 -0.5159699 0.7148124 -0.5530027 -0.4998729 0.6665697 -0.1070439 -0.9371827 0.3320096 -0.0836271 -0.9754928 0.2035198 -0.9561884 0.2784951 0.09024542 0.8183962 -0.5591324 0.1326602 0.2641212 -0.9384376 0.2226543 0.3083111 -0.9294101 0.2028331 0.3333421 -0.9270865 0.1714456 0.342742 -0.9316172 0.1209034 0.4158316 -0.9039108 0.1001474 -0.0201013 -0.9983823 0.05318653 -0.2465068 0.9682106 -0.0424571 -0.2326041 0.9725052 -0.01136684 -0.2238128 0.9730725 -0.05511569 -0.2000837 0.979776 0.002407371 -0.1797862 0.9814465 -0.06663262 -0.16469 0.9861021 -0.02191048 -0.1375573 0.987178 -0.08097976 -0.1393817 0.9861038 -0.09039956 -0.09302842 0.9914764 -0.0912162 -0.1179175 0.9614136 0.2485546 -0.2802109 0.9171363 0.2834487 -0.1703953 0.961222 0.2168358 -0.1709771 0.9616602 0.2144219 -0.2144709 0.961053 0.1742969 -0.2146719 0.9620078 0.1686921 -0.2470595 0.9608822 0.1251685 -0.2456666 0.9626367 0.1139232 -0.2677062 0.9606199 0.0744512 -0.2631598 0.9632415 0.05397272 -0.2767134 0.9606155 0.02544689 -0.2688917 0.963138 -0.007902383 -0.2554127 0.9665963 0.02135539 -0.06977152 0.9915631 -0.1092455 -0.3400506 -0.6262949 0.7015129 -0.2235324 -0.5177222 0.8258311 -0.2764585 0.321617 0.9056121 -0.6454427 -0.570711 0.5076345 -0.6437433 -0.5742677 0.5057778 -0.8400915 0.2612005 0.4754162 -0.6797545 0.6453481 0.3485107 -0.883956 0.08795714 0.4592226 -0.8141481 0.3264027 0.4802335 -0.7574682 0.3963346 0.5188073 -0.5314234 -0.562009 0.6338257 -0.4964349 -0.6743631 0.5466141 -0.6934512 0.3280935 0.6414672 -0.6976175 0.315371 0.6433281 -0.452671 -0.6393336 0.6215639 -0.5941925 0.4217058 0.6849085 -0.4963485 0.3667766 0.7868375 -0.5515128 0.1910685 0.8119893 -0.4038668 0.4439222 0.7998905 -0.4172113 -0.5408415 0.7303597 -0.4119686 -0.6064068 0.6801124 -0.7042384 -0.6028205 0.375041 -0.5508819 -0.70644 0.4443778 -0.9400337 -0.1471399 0.3077117 -0.9538562 0.1967629 0.2268096 -0.7761428 0.6075046 0.1689394 -0.8967269 0.4056941 0.1768991 0.3300494 -0.8072372 0.4893216 -0.2002112 -0.5680697 0.7982558 -0.1971077 -0.7726777 0.6034218 -0.5600557 -0.4294327 0.7084668 -0.7705113 -0.5968967 0.2236668 -0.8949348 -0.391108 0.2147701 -0.8690293 -0.315653 0.3809874 0.4041029 -0.5643869 0.719839 0.3379974 -0.8513121 0.4012802 0.5200824 -0.7874175 0.3308898 0.1497552 -0.7814211 0.6057678 -0.6730771 -0.6537163 0.3458647 -0.7948719 -0.5232999 0.3071419 -0.9916676 0.1243183 -0.03376781 -0.9546826 0.2962529 0.02855819 -0.9338624 0.3528826 -0.0580936 -0.9701182 0.2232418 -0.09504586 -0.8466302 0.5286223 -0.06144911 -0.7798349 0.625679 -0.01958382 -0.7979525 0.6005337 -0.05129379 -0.7679895 0.6403132 -0.01382827 -0.8011807 0.5893276 -0.103936 -0.7627812 0.6444238 -0.05369496 -0.7271135 0.6860024 0.02658373 -0.718687 0.6953335 -6.80152e-4 -0.6762196 0.7332058 0.07166862 -0.193817 -0.8716135 0.4502499 -0.3348465 -0.6711634 0.6613755 -0.1441255 -0.9396895 0.3101797 -0.1445419 -0.939689 0.3099874 -0.1214922 -0.9360873 0.3301218 -0.1497813 -0.9392885 0.3087114 -0.1491957 -0.9378121 0.3134471 -0.1485684 -0.9376184 0.3143234 -0.1064905 -0.9430905 0.3150243 -0.1650259 -0.9329177 0.3200489 -0.1735466 -0.932642 0.3163236 0 1 1.50206e-7 0 1 1.66698e-7 0 1 -1.00676e-6 0 1 7.00748e-7 0 1 2.18866e-7 0 1 -7.22511e-7 -0.1431156 -0.9386845 0.3136708 -0.5999617 0.7818661 -0.169504 -0.3586164 0.930291 -0.07715588 -0.3416075 0.9305926 -0.1315361 -0.47585 0.8778105 -0.05491495 -0.3378196 0.9405917 0.03413587 -0.3705795 0.9288002 -9.95159e-4 -0.2694837 0.9591629 -0.0859366 -0.1514496 0.9877588 0.03735685 -0.9987608 0.02242535 0.04443085 -1 -2.50843e-7 0 -1 2.62583e-7 0 -0.001180052 -0.9999988 -0.001037061 0.6689747 -0.7179054 0.1925743 0.7136602 -0.6457897 0.271376 0.674607 -0.6515443 0.3469805 0.6488716 -0.6298773 0.4268727 0.6481469 -0.6266615 0.4326674 0.5822712 -0.6480963 0.4908477 0.6805528 -0.5790771 0.4489071 -0.5587522 0.8293181 -0.005236923 -0.6304371 0.7734239 -0.06606578 -0.6232882 0.7819248 -0.01027661 -0.623547 0.7816037 -0.01687878 -0.5816592 0.8124393 0.04018914 -0.5819067 0.8114929 0.05351477 -0.5659896 0.8205019 0.08020216 -0.5820434 0.8125481 0.03148502 -0.5772616 0.8084186 0.1150153 -0.543751 0.8255084 0.1512314 -0.5412147 0.8206719 0.1832607 -0.4846062 0.8395693 0.2455201 -0.5106773 0.8274986 0.2333558 -0.4738001 0.8160095 0.3311226 -0.4043673 0.8535189 0.3286226 -0.3968949 0.8348726 0.3813952 -0.3206884 0.8547692 0.4080792 -0.3302846 0.8481233 0.4142452 -0.2594667 0.8268328 0.4990236 -0.2167976 0.8626578 0.4569688 2.42275e-4 -1 -3.12272e-5 -0.001079082 -0.9998144 0.01923978 -0.266382 -0.9281537 0.2599453 -0.2226662 -0.928324 0.2977151 0.09301203 0.9914766 -0.09123039 0.1393747 0.9861055 -0.09039163 0.1375457 0.9871779 -0.08100134 0.1494139 0.987223 -0.05537438 0.06819599 0.9915383 -0.1104595 0.07177025 0.99107 -0.1123805 0 1 -4.82248e-7 0 1 4.37318e-7 0 1 0 0 1 -1.00674e-6 0 1 5.00188e-7 0 1 5.62787e-7 -9.4588e-4 0.9999995 -2.75452e-4 -0.008570671 -0.9999616 0.00184381 -0.008046269 -0.9999645 0.002515912 -0.007454574 -0.9999673 0.003172695 -0.006781578 -0.9999697 0.003814816 -0.006014585 -0.9999722 0.004432618 -0.005140066 -0.9999743 0.005016386 -0.004145085 -0.9999762 0.005541861 -0.003021121 -0.9999775 0.005984425 0.3253084 0.8608779 0.3912339 0.3353385 0.840382 0.4258006 0.2502911 0.8126868 0.5262077 0.1764573 0.8381868 0.5160483 0.1081532 0.8436708 0.5258542 0.1118735 0.8617494 0.4948459 2.93952e-4 0.8386355 0.5446932 -0.009137392 -0.9999577 0.001014113 -0.006301462 -0.9999618 0.006071448 0.1039887 -0.9435238 0.3145619 0.070827 -0.9362001 0.3442574 -0.005549609 -0.9507325 0.3099629 0.04523396 -0.904865 0.4232887 0.2568375 -0.8716255 0.4174968 0.1445358 -0.9396914 0.3099829 0.144414 -0.9397074 0.3099916 0.1445428 -0.939692 0.3099781 0.1333981 -0.9358223 0.3262537 0.3039713 0.3429644 0.8888064 0.2804105 0.2789251 0.9184611 0.2523856 -0.5058045 0.8249021 0.1803315 0.4458271 0.876766 0.0235297 0.3836901 0.9231621 0 -0.5819054 0.8132566 0.4301447 -0.5448142 0.7198285 0.390359 -0.6076956 0.6916112 0.5324343 0.404063 0.7438057 0.4447454 0.03827071 0.894839 0.4621867 0.5201783 0.7181909 0.2946029 -0.6401318 0.7095354 1.71358e-4 0.9474426 0.3199259 0.1373168 0.9475201 0.2887039 0.1941308 0.959995 0.2017992 0.1705669 0.9612503 0.2165753 0.1710501 0.9616259 0.2145165 0.2145826 0.961078 0.1740215 0.2147532 0.9619787 0.168755 0.05806624 -0.9880304 0.1429136 0.06865459 -0.9834027 0.1679461 0.03294676 0.9525756 0.3025133 0.07027977 0.9478501 0.3108715 0.09367614 0.952643 0.2893027 0.09771275 -0.9210393 0.3770131 0 1 4.53123e-7 0 1 -1.12655e-6 -0.04460245 0.9908383 -0.1274763 0.02095049 0.9922776 -0.1222549 0.04459178 0.9908378 -0.1274842 0.04751855 0.9919002 -0.1177967 -0.1672713 -0.9285645 0.3313434 -0.2199036 -0.9266226 0.3049804 -0.03233146 0.9524942 0.3028358 -0.0702086 0.9474718 0.3120387 -0.09560775 0.9524615 0.2892688 -0.2322034 -0.6087489 0.7586215 -0.2873106 0.2939821 0.9116069 -0.1316283 0.460908 0.8776319 -0.01399797 -0.6233045 0.781854 0 0.3165808 0.9485656 9.45798e-4 0.9999995 -2.7543e-4 -0.09282612 -0.9347619 0.342934 -0.03533941 -0.9430732 0.3307025 -0.1682189 0.8287429 0.5337487 -0.1321688 0.7983937 0.5874513 -0.06548088 0.8972885 0.4365614 0.01265799 0.86768 0.4969621 0 -1 -2.58616e-7 0 -1 -2.41021e-7 0.04879814 -0.9986238 0.01921683 -0.6231691 0.7820751 -0.004350185 -0.7938043 0.6081628 -0.003591954 -0.7201294 0.6938397 -4.00613e-4 -0.5626699 0.8266329 -0.00899285 0.129077 -0.9916344 -6.45319e-4 0.1248509 -0.9921747 -0.001281738 0.3668264 -0.9302869 -0.002200245 0.3816626 -0.9243018 1.56751e-4 0.5131084 -0.8583085 -0.00514692 0.6088515 -0.7930525 0.01917397 0.8109589 -0.5850596 0.007145702 0.7930011 -0.6092135 0.002863049 0.9242299 -0.381829 -0.00238651 0.9914898 -0.1291405 0.0164563 0.9756928 -0.2191429 -1.41413e-4 -0.1352024 -0.9908149 0.002499163 -0.1931217 -0.9811079 0.01146376 -0.3865935 -0.9222501 -5.65866e-4 -0.5070083 -0.8618882 0.00956428 -0.7072537 -0.7067853 -0.0157091 -0.8111371 -0.5848122 0.007181882 -0.9242294 -0.3818309 -0.002316951 -0.9916318 -0.129099 -1.84976e-5 -0.9753018 -0.220657 0.009857714 3.28566e-4 -0.9999998 -6.43411e-4 -0.00366652 -0.9999911 0.002090811 1 0 -2.47578e-5 1 2.89659e-5 -2.94772e-5 1 0 -3.52414e-5 1 5.37577e-5 -1.19856e-4 1 2.12807e-5 -6.03893e-5 1 0 -4.59341e-5 1 0 -4.15393e-5 -1 3.09405e-5 2.46086e-5 -1 -3.75432e-5 2.17251e-5 -1 -2.30673e-5 2.57528e-5 -1 -1.38441e-5 2.88632e-5 -1 -7.95959e-6 3.30116e-5 -1 -3.55304e-6 3.76715e-5 -1 0 4.12765e-5 -1 0 4.12765e-5 0.9938653 0.1105988 5.65232e-6 0.993991 0.1094625 -5.69874e-5 0.9496613 0.3132788 1.16469e-4 0.9443236 0.3290176 -6.40189e-4 0.8767703 0.4809093 5.92134e-4 0.8463136 0.5326835 -0.001255333 0.7072225 0.7069866 0.002527058 0.4787645 0.877938 -0.00309509 0.5328802 0.8461908 3.42442e-4 0.3865119 0.9222844 1.7967e-4 0.3065028 0.9518678 -0.002002656 0.2614942 0.9651941 -0.004630804 0.2211157 0.9752425 -0.003179252 0.1246716 0.9921977 -8.57262e-4 0.03863555 0.9992535 1.76838e-4 -0.9939972 0.1094059 5.44798e-5 -0.9938629 0.1106194 -9.36669e-6 -0.9496678 0.3132589 1.6209e-4 -0.941152 0.3379819 -0.001030325 -0.8767775 0.480896 6.19348e-4 -0.8444126 0.5356924 0.001153945 -0.7071437 0.7070426 0.006224453 -0.4769447 0.8789277 -0.003162264 -0.5338333 0.8455649 0.006508231 -0.3969817 0.9177913 -0.008063077 -0.3090421 0.9510445 -0.002742946 -0.2317181 0.9727829 4.57865e-4 -0.12067 0.9924733 -0.02087718 -0.1740253 0.9846501 -0.0134015 -0.237044 0.9714721 -0.007217466 2.81785e-4 1 4.6035e-4 6.2819e-5 0.9999999 5.69168e-4 1.69007e-4 1 4.93775e-4 0.5373366 0.8433674 -9.22213e-4 0.6653178 0.7465596 -0.001019597 0.7972739 0.6036175 4.83351e-4 -0.2332267 0.9724024 -0.006232798 -0.1693604 0.9854786 -0.01221376 -0.1154012 0.9931274 -0.01950681 -0.2225384 0.9749239 4.5799e-4 -0.3061909 0.9519681 -0.001999139 -0.5326671 0.8463008 0.006385266 0.2143282 -0.976655 -0.01444053 0.2611925 -0.9652869 0 0.5131276 -0.8582968 -0.005175113 0.6086885 -0.793179 0.01911449 0.8109914 -0.5850161 0.00701791 0.7938222 -0.6081431 0.002908229 0.9241245 -0.382084 -0.002408564 0.9482622 -0.3174778 0.002587735 0.9916281 -0.1290963 -0.002799093 0.9954479 -0.09530782 -8.50438e-5 -0.1467857 -0.9891591 0.004287362 -0.1263885 -0.9919803 -0.0010885 -0.1931204 -0.9811082 0.01146352 -0.3864818 -0.922297 -5.59516e-4 -0.506996 -0.861895 0.009595513 -0.608959 -0.7931973 -0.002657949 -0.7930048 -0.6092082 0.002955794 -0.8111073 -0.584852 0.007278144 -0.9242252 -0.381841 -0.002314388 -0.9916263 -0.1291409 -1.85131e-5 -0.9753021 -0.2206552 0.009855568 -2.53244e-4 -1 -9.0733e-5 1.20489e-4 -1 -3.64696e-4 3.36168e-5 -1 -3.20651e-4 -3.36119e-5 -1 -3.20721e-4 -1.20463e-4 -1 -3.64222e-4 -5.82992e-4 -0.9999992 -0.001109302 1.48022e-4 -1 -1.6804e-4 -0.002981603 -0.9999899 0.003380656 1 -1.50218e-4 0 1 2.63366e-5 -2.89774e-5 1 0 -3.02485e-5 1 1.90184e-4 -2.17667e-4 1 0 -3.50881e-5 1 3.90593e-5 -9.22453e-5 1 1.49627e-5 -5.81192e-5 1 1.22007e-5 -5.48812e-5 1 0 -4.13586e-5 -1 2.07935e-5 1.46001e-5 -1 -2.33887e-5 1.35343e-5 -1 -1.23631e-5 1.49953e-5 -1 -7.7869e-6 1.59994e-5 -1 -4.24185e-6 1.71972e-5 -1 -3.16016e-6 1.83817e-5 -1 0 1.92001e-5 -1 2.18265e-5 4.12863e-5 0.9703965 0.2415179 0 0.9931328 0.1160387 -0.01491671 0.9491825 0.3147183 -0.002289235 0.8440755 0.5362229 0.001284658 0.8754606 0.4832835 -0.002409994 0.707156 0.7070502 0.003238499 0.7919594 0.6105471 -0.005725443 0.6669142 0.7451328 0.001653492 0.5440167 0.8390741 -7.95128e-4 0.5360404 0.8441923 -5.51505e-4 0.4661409 0.8847106 4.27561e-4 0.340917 0.9400933 -5.49652e-4 0.4022942 0.9155015 -0.004060268 0.3001999 0.9538763 -3.5995e-4 0.110633 0.9938601 0.001595199 0.240801 0.9705395 -0.008251249 0.1300229 0.9915086 -0.002224743 0.03753817 0.9992952 4.58538e-4 -0.9939971 0.1094069 3.2328e-5 -0.9938503 0.1107324 -9.09638e-6 -0.9496659 0.3132648 1.64047e-4 -0.9442877 0.3291208 -5.99689e-4 -0.8767977 0.4808592 6.35043e-4 -0.8461852 0.5328877 0.001174211 -0.7933856 0.6087061 -0.004050612 -0.7201671 0.6938006 -3.95679e-4 -0.7069916 0.7071947 0.006211638 -0.5626358 0.8266561 -0.008982479 -0.623164 0.7820793 -0.004340171 -0.4769105 0.8789462 -0.003154873 -0.5326532 0.8463096 0.006383776 -0.3969376 0.9178103 -0.00805217 -0.3061936 0.9519672 -0.001999735 -0.222546 0.9749221 4.5799e-4 -0.1154013 0.9931275 -0.019508 -0.1693698 0.9854769 -0.01221483 -0.2332298 0.9724017 -0.006233334 2.81785e-4 0.9999999 4.6035e-4 0 1 5.44372e-4 -2.81797e-4 1 4.60455e-4 -4.30319e-4 0.9999991 0.001258671 -8.11354e-5 0.9999998 7.35516e-4 6.2819e-5 0.9999999 5.69168e-4 1.69007e-4 1 4.94331e-4 0.1248509 -0.9921747 -0.001281321 0.3668352 -0.9302834 -0.002198457 0.3816663 -0.9243003 1.57396e-4 0.5131085 -0.8583084 -0.005146682 0.6088515 -0.7930525 0.01917606 0.8109562 -0.5850632 0.007145643 0.7929967 -0.6092193 0.002864122 0.9242299 -0.381829 -0.002387285 0.9482654 -0.3174684 0.002587258 0.9916201 -0.1291586 -0.0028041 0.9954479 -0.09530764 -8.49718e-5 -0.1263745 -0.9919819 0.001138925 -0.1931228 -0.9811077 0.0114637 -0.3864809 -0.9222972 -5.58473e-4 -0.5069879 -0.8618998 0.009595513 -0.6089608 -0.7931959 -0.002658665 -0.7929983 -0.6092168 0.002954244 -0.811111 -0.584847 0.007278978 -0.9242249 -0.3818418 -0.002313077 -0.9916272 -0.1291342 -1.84072e-5 -0.9753022 -0.220655 0.009856879 3.28565e-4 -0.9999998 -6.43409e-4 7.11595e-4 -0.9999997 -5.06464e-4 0 -1 4.82655e-7 -7.11486e-4 -0.9999997 -5.06146e-4 -0.004351794 -0.9999903 7.98798e-4 1 0 -2.46011e-5 1 2.81614e-5 -2.92906e-5 1 0 -3.50183e-5 1 6.04839e-5 -1.1911e-4 1 1.59602e-5 -6.00064e-5 1 3.48588e-6 -4.5643e-5 1 0 -4.12765e-5 -1 2.68334e-5 2.46674e-5 -1 -3.69566e-5 2.1777e-5 -1 -2.13632e-5 2.58143e-5 -1 -1.42386e-5 2.8932e-5 -1 -8.42851e-6 3.30906e-5 -1 -3.40687e-6 3.77616e-5 -1 0 4.13751e-5 -1 0 4.13752e-5 0.9938629 0.1106192 5.91644e-6 0.9939911 0.1094614 -5.86029e-5 0.9496549 0.3132981 1.17983e-4 0.9442846 0.3291297 -6.43575e-4 0.876782 0.4808879 5.94673e-4 0.8461946 0.5328726 -0.001257836 0.7972459 0.6036546 4.82637e-4 0.6653304 0.7465484 -0.00100702 0.7069923 0.7072167 0.002515137 0.5373126 0.8433827 -9.15531e-4 0.4787251 0.8779594 -0.00308448 0.5326772 0.8463184 3.37685e-4 0.3865384 0.9222733 1.82131e-4 0.3064589 0.9518819 -0.001998722 0.2225327 0.9749011 -0.006859004 0.2407992 0.97054 -0.008251667 0.1300224 0.9915086 -0.002224743 0.03753745 0.9992951 4.5853e-4 -0.9939974 0.1094041 5.45394e-5 -0.9938623 0.1106249 -9.86928e-6 -0.9496611 0.3132792 1.63597e-4 -0.944291 0.3291113 -5.98789e-4 -0.8767971 0.4808601 6.36177e-4 -0.8461892 0.5328815 0.00117433 -0.7934094 0.608675 -0.004048287 -0.7201443 0.6938242 -3.959e-4 -0.7069793 0.707207 0.006211519 -0.562636 0.826656 -0.008982121 -0.6231654 0.7820781 -0.004339635 -0.4768999 0.8789521 -0.003155589 -0.3969455 0.9178069 -0.008051574 2.81785e-4 1 4.60421e-4 0 0.9999999 5.44579e-4 -2.81798e-4 0.9999999 4.60528e-4 -4.30319e-4 0.9999991 0.001257956 -8.11348e-5 0.9999998 7.36297e-4 6.28193e-5 0.9999999 5.69475e-4 1.69007e-4 0.9999999 4.94053e-4 -0.2225382 0.9749212 -0.002338051 -0.2652899 0.9641222 -0.009481191 -0.5312964 0.8471861 -1.50181e-4 -0.5326779 0.8463181 1.23777e-4 -1 0 -1.52528e-4 -1 3.8151e-5 0 -0.2652935 0.9641649 -0.002329587 -0.2357423 0.9716097 0.02000755 -0.625132 -0.7788618 0.05083727 -0.3018028 -0.9530544 0.02454334 -0.3301534 -0.9439162 0.004615485 -0.3295322 -0.9441348 -0.004258632 -8.49062e-5 -0.9999994 -0.001111805 5.59778e-4 -0.9999999 3.28077e-5 -0.1263882 -0.9919809 -1.09236e-6 -0.1263767 -0.9919824 0 -0.2736922 -0.9589906 -0.07368582 -0.3858768 -0.9209901 -0.05363303 -0.5434745 -0.8359996 -0.07576513 -0.6082919 -0.7923274 -0.04688727 -0.7930032 -0.6092174 5.44508e-4 -0.9242249 -0.381841 -0.002419412 -0.9160984 -0.400949 0.001935958 -0.9904294 -0.1380206 0 -0.9916253 -0.1291347 -0.001856267 0.5985463 -0.7799643 0.1827514 0.7851468 -0.6014923 0.1474844 0.2639735 -0.9611311 0.08090245 0.2603494 -0.9620193 0.08208018 0.7517032 -0.6367183 0.1718488 0.9040821 -0.3738057 0.2071352 0.9911794 -0.1290387 0.03020948 0.9288848 -0.274271 0.2488948 0.5199321 -0.7468301 0.4146269 0.7598344 -0.2355769 0.6059333 0.7728052 -0.2259914 0.593043 0.5864069 -0.2685678 0.764198 0.1279677 -0.9704073 0.2047783 0.2270326 -0.9462998 0.2301585 0.3979157 -0.6599739 0.6372579 0.422745 -0.2252912 0.8777987 0.3706977 -0.2484214 0.8949134 0.3066739 -0.7074083 0.6368082 0.08815091 -0.9653817 0.245495 0.03413552 -0.6918563 0.7212279 0.01226896 -0.9657358 0.2592371 -0.01021254 -0.9713129 0.2375858 0.03891921 -0.9659032 0.2559617 0.125943 -0.2625576 0.9566619 0 -0.2218374 0.9750837 0 -0.7098814 0.7043213 -0.1259453 -0.2625583 0.9566614 -0.06132078 -0.9652315 0.2541024 -0.09605556 -0.9673879 0.2343802 -0.1020579 -0.9696502 0.2221772 -0.274443 -0.6900983 0.6696606 -0.304606 -0.7121607 0.632489 -0.4208787 -0.2432441 0.8738956 -0.3740085 -0.2115666 0.9029713 -0.5864077 -0.2685642 0.7641984 -0.1535176 -0.9649147 0.2130068 -0.1830023 -0.9684808 0.1689825 -0.182753 -0.9681568 0.1710965 -0.5328544 -0.6884571 0.4920296 -0.547204 -0.714239 0.4363836 -0.7609418 -0.2295922 0.6068402 -0.7705011 -0.238238 0.5912451 -0.2224743 -0.9649689 0.139069 -0.245252 -0.9614925 0.124031 -0.2384098 -0.9668871 0.09105014 -0.6326465 -0.7051126 0.3202728 -0.8904529 -0.2665572 0.3688372 -0.6073523 -0.784718 0.1238579 -0.9457823 -0.2272621 0.2320517 -0.3018279 -0.9519221 0.05238604 -0.9821153 -0.1368619 0.1292997 -0.8739315 -0.3831439 -0.2990729 0.1290758 -0.9916347 3.33593e-4 0.3816635 -0.9242979 0.002521812 0.6081036 -0.7920857 -0.05301398 0.6982097 -0.715852 -0.007696032 0.793 -0.6092138 -0.003106176 0.9242318 -0.3818309 9.88811e-4 0.915481 -0.4023481 -0.003269672 0.9909467 -0.1342528 -9.95982e-4 0.9916234 -0.1291631 0 0.6774286 -0.7106201 0.1900259 0.8867164 -0.38979 0.248592 0.9858306 -0.133561 0.1014868 0.9794273 -0.1552268 0.1289458 0.1090447 -0.9940155 0.006524562 0.2876167 -0.9576415 -0.01412796 0.6853936 -0.6950594 0.21709 0.2473377 -0.9672542 0.05695009 0.2029162 -0.9761706 0.07691532 0.8929699 -0.2565014 0.369881 0.2228595 -0.9649136 0.1388361 0.49581 -0.7129843 0.4958084 0.5191845 -0.7006574 0.4894147 0.6846059 -0.2503171 0.6845846 0.7837226 -0.1552311 0.6014003 0.5884032 -0.2565087 0.7668018 0.18134 -0.9684495 0.1709428 0.1825512 -0.9682609 0.170722 0.1533647 -0.9649432 0.2129879 0.2670726 -0.6875556 0.675233 0.09074652 -0.9690868 0.2294252 0.10609 -0.9669688 0.2317678 0.3699092 -0.2565096 0.8929558 0.1779118 -0.7262867 0.6639692 0.2531294 -0.2083967 0.9447202 0.1261722 -0.256498 0.9582743 0.06061547 -0.9653428 0.2538485 0.01024764 -0.9659534 0.2585132 0 -1 -1.3154e-5 0 -1 -7.17001e-6 -1.55498e-6 -1 -1.62717e-4 0 -1 3.16456e-6 0 -1 -1.43998e-6 1.76921e-4 -1 -1.68624e-4 0 -1 2.71459e-6 0 -1 -2.61615e-6 5.19923e-5 -0.9999993 -0.001195847 -2.7702e-4 -1 -1.42449e-6 -5.58569e-4 -1 8.18299e-6 -5.56901e-4 -1 -8.3661e-6 5.56213e-4 -1 2.03089e-6 -5.56597e-4 -1 0 -0.2452715 0.9682754 0.04779791 -0.2282696 0.9717563 0.05985605 -0.5267138 0.8398235 0.1314126 -0.7031312 0.7031294 0.1059045 -0.8432829 0.5371094 -0.01968157 -0.6844264 0.7018835 0.1972821 -0.9174895 0.3451434 0.1977092 -0.9938359 0.1107787 0.004289388 -0.9498568 0.2411993 0.198985 -0.2378441 0.965083 0.1097502 -0.5599566 0.697885 0.4465481 -0.2044416 0.9652057 0.1630387 -0.1639249 0.9725712 0.1650274 -0.208741 0.9670078 0.1460244 -0.5599454 0.6978913 0.4465525 -0.7586141 0.2418795 0.6049785 -0.7841817 0.2199489 0.5802428 -0.148227 0.9654339 0.214397 -0.1083347 0.9683286 0.2249521 -0.1022337 0.9693092 0.2235799 -0.3107614 0.6978862 0.6452768 -0.3107564 0.6978859 0.6452796 -0.4190116 0.2597001 0.870049 -0.5030179 0.1975403 0.8413981 -0.06555408 0.9651415 0.2533864 -0.1799161 0.2665368 0.9468834 0 0.9659085 0.258884 0.02339667 0.9720075 0.2337823 -0.01964509 0.9667126 0.2551095 0 0.6978855 0.7162094 0 0.2095644 0.9777949 0 0.6978866 0.7162083 0.1832786 0.2683005 0.9457398 0.07118129 0.965284 0.2513171 0.1077889 0.968651 0.2238231 0.1082217 0.9687908 0.223008 0.3107567 0.6978845 0.645281 0.3107632 0.6978883 0.6452738 0.423744 0.2150648 0.8798796 0.508274 0.2576521 0.8217501 0.1535161 0.9652343 0.2115551 0.1929849 0.9690569 0.1539014 0.1941048 0.9663287 0.1689148 0.5599554 0.6978867 0.446547 0.7612237 0.2281213 0.6070414 0.7724136 0.2399384 0.5880536 0.5599544 0.6978898 0.4465435 0.6896296 0.7005511 0.1834102 0.3402868 0.938207 0.06302905 0.1097323 0.985755 -0.1274597 0.2234852 0.9746094 0.01381415 0.2379807 0.9702363 0.04479783 0.2442579 0.965713 0.08795714 0.8264533 0.5252715 0.2026447 0.7048761 0.7047727 0.08028095 0.5358645 0.8261544 -0.1741215 0.9514753 0.2402932 0.1922341 0.9512569 0.2367905 0.1975864 -0.2357891 0.9718043 0 -0.7071065 0.7071072 -1.23862e-4 -0.7069937 0.7072198 -1.50536e-4 -0.8461899 0.5328815 1.49052e-4 -0.843488 0.5371472 9.96185e-4 -0.944291 0.3291119 2.2644e-4 -0.936171 0.3515248 -0.003780484 -0.9938451 0.1107783 -2.24597e-4 -0.9938622 0.110625 -1.98899e-4 0.1668414 0.9859838 0 0.2225278 0.974879 0.009609758 0.3113011 0.9502949 -0.005592405 0.5326783 0.8463174 8.95596e-4 0.53728 0.843404 1.19358e-4 0.7071139 0.7070997 -1.50123e-4 0.706993 0.7072206 -1.22085e-4 0.8461977 0.5328692 1.49962e-4 0.8483656 0.5294108 -5.35515e-4 0.9442745 0.3291203 -0.005048453 0.9658445 0.2590525 0.006040215 0.9927561 0.1104986 -0.047176 0 0.9667528 0.255713 0.01834553 0.9712025 0.2375485 0 0.2095643 0.9777949 0 0.697885 0.7162098 0.1832832 0.2683003 0.945739 0.06562757 0.9651408 0.2533698 0.3107574 0.6978856 0.6452794 0.1072144 0.9689907 0.2226255 0.1042047 0.9681391 0.2277015 0.310761 0.6978868 0.6452763 0.42374 0.2150684 0.8798807 0.5082675 0.2576551 0.8217532 0.1482546 0.9654361 0.2143685 0.1986084 0.9671962 0.1583864 0.1969158 0.9706819 0.137844 0.1822648 0.9659683 0.1835346 0.559955 0.6978842 0.4465515 0.5599543 0.6978883 0.4465458 0.7612228 0.228128 0.6070401 0.7726202 0.2401776 0.5876844 0.2378416 0.9650793 0.1097883 0.6901725 0.7004004 0.1819377 0.3105177 0.9486364 0.06056278 0.1665622 0.9843248 -0.05798166 0.2278265 0.9735088 0.01938384 0.2434371 0.9678102 0.06389111 0.8300043 0.5181775 0.2063613 0.704804 0.7047931 0.08073502 0.5272727 0.8292859 -0.185118 0.9517843 0.2384747 0.192968 0.9503403 0.2215198 0.2185913 -0.9914448 3.7848e-5 0.1305265 -0.9786565 -0.002442538 0.2054886 -0.9238765 0.001921355 0.382686 -0.793349 3.12625e-4 0.608767 -0.803758 -3.59585e-4 0.5949562 -0.6087708 0.001903831 0.7933439 -0.5134404 -0.001185655 0.8581245 -0.3826521 0.001846909 0.9238908 -0.1863344 -6.3698e-4 0.9824863 -0.130551 0.001205742 0.991441 0.1305485 0.001150906 0.9914413 0.190133 -8.42167e-4 0.981758 0.3826685 0.002029895 0.9238835 0.5260806 -9.64971e-4 0.8504341 0.6087705 0.001681447 0.7933446 0.793357 -2.12318e-4 0.6087567 0.7957606 -4.61992e-5 0.6056113 0.9659256 0 0.2588198 0.9659249 0 0.2588227 0.9773253 0.003582715 0.2117132 0.130537 0.001150429 0.9914427 0.1901181 -8.43579e-4 0.9817609 0.3827049 0.002028703 0.9238685 0.5260743 -9.65935e-4 0.8504381 0.6087693 0.001680672 0.7933456 0.7933558 -2.35463e-4 0.6087583 0.796032 -5.02225e-5 0.6052547 0.9238752 0.002184748 0.382688 0.9741204 -0.00170958 0.2260235 0.991445 0 0.130526 0.9924661 3.00905e-4 0.12252 0.9790756 -2.28704e-4 0.2034971 0.9999062 -0.01225125 0.006125628 -2.73316e-5 1 -2.70099e-4 0 1 0 0.002390384 -0.9999971 9.49515e-5 -8.05278e-4 -0.9999967 0.002437651 -2.24676e-4 -0.9999977 0.002144098 2.24643e-4 -0.9999977 0.002144277 8.0512e-4 -0.9999968 0.002437353 -9.75495e-4 -0.9999989 0.00113213 1 0 -1.91766e-5 0.1290761 -0.9916345 6.55101e-4 0.2638501 -0.9643493 -0.02033817 -0.04512673 -0.6800214 0.7318022 -0.01599919 -0.9656132 0.2594904 -0.03665977 -0.9714599 0.2343538 -0.1261917 -0.2565107 0.9582682 -0.1764255 -0.7316542 0.65845 -0.253129 -0.2084063 0.9447183 -0.08960133 -0.9652557 0.2454649 -0.3698869 -0.2565133 0.892964 -0.4071354 -0.6562027 0.6353257 -0.2883681 -0.845251 0.4498829 -0.1736642 -0.978681 0.1096563 -0.1624994 -0.9716547 0.1717014 -0.4966855 -0.7117722 0.4966728 -0.684592 -0.2503267 0.684595 -0.601384 -0.1552248 0.7837364 -0.7668195 -0.2564963 0.5883856 -0.8929696 -0.2565026 0.3698808 -0.6949734 -0.6945185 0.1861619 -0.7352178 -0.5948907 0.3248996 -0.9444828 -0.2086727 0.2537877 -0.9832879 -0.1280099 0.129455 -0.8930937 -0.3689596 -0.257396 -0.3812087 -0.9089608 0.1687313 -0.2608523 -0.9626127 0.07302725 -0.1323925 -0.9893963 0.05972814 0.3816633 -0.9242977 -0.002624511 0.5984002 -0.8011815 -0.005046844 0.6089544 -0.7932004 -0.002782762 0.7064949 -0.7077178 -6.78513e-4 0.7928587 -0.609116 0.01878619 0.9240664 -0.3817664 0.01886475 0.9916265 -0.1291389 -1.84736e-4 0.979529 -0.201074 -0.009603083 0.9999988 -0.001573503 -4.35569e-4 -1.66325e-5 -0.9999998 -6.95287e-4 -2.02984e-5 -1 1.26465e-4 -2.06476e-5 -1 5.72482e-5 -2.15789e-5 -1 2.19127e-5 -0.002101957 -0.9999972 0.001108884 -4.83557e-4 -0.9999862 -0.005236983 0.002395093 -0.9999972 7.80011e-5 -0.001855075 -0.999996 -0.002125442 -0.2316784 0.9726876 0.01428282 -0.5294724 0.8380821 0.1314445 -0.7032116 0.7031059 0.1055251 -0.8442716 0.535526 -0.02043467 -0.3655189 0.9280483 0.07157039 -0.1122282 0.9887061 0.09932452 -0.2363772 0.971364 0.02403903 -0.219406 0.9747619 0.04123717 -0.9247313 0.3314515 0.1871153 -0.9938578 0.1106168 0.003287792 -0.9784321 0.1786922 0.1036339 -0.6800279 0.7028621 0.2086793 -0.8626525 0.2691712 0.4282261 -0.5599555 0.6978864 0.4465473 -0.2016932 0.9661513 0.1608468 -0.3262218 0.9336315 0.1480253 -0.5599522 0.6978868 0.4465509 -0.7642102 0.2111435 0.609427 -0.6594612 0.2606201 0.7051158 -0.1534435 0.9652345 0.211607 -0.107634 0.9687434 0.2234978 -0.1083887 0.9686284 0.2236316 -0.3107616 0.6978862 0.6452767 -0.4205459 0.2459834 0.8732888 -0.492914 0.2003042 0.8467078 -0.3107532 0.6978877 0.6452793 -0.07108342 0.9652831 0.2513478 -0.1799148 0.2665371 0.9468836 0 0.6978856 0.7162093 -0.02557474 0.966261 0.2562922 -0.9943342 0 0.1062993 -0.9943343 0 0.1062982 -0.9943345 0 0.1062964 -0.9914444 8.34443e-4 0.1305273 -0.923878 0.001211643 0.3826853 -0.8956499 -9.26938e-4 0.4447588 -0.7933666 0.002134442 0.6087404 -0.6842283 -6.37026e-4 0.7292676 -0.6087584 0.001067399 0.7933549 -0.5023187 -9.1768e-4 0.8646821 -0.3826972 0.001846611 0.923872 -0.1863318 -6.3722e-4 0.9824867 -0.1305289 0.001206219 0.9914439 -0.112559 0.9895226 0.09041821 -0.3771478 -0.4977047 0.7810567 -0.5938155 -0.6883011 0.416683 -0.4531128 -0.8043228 0.3843876 0.7434602 0.3355858 -0.5784887 0.7512954 0.3323918 -0.57015 0.3633313 0.4563143 -0.8122609 0.3741158 0.4557352 -0.8076775 0.3790549 0.4560438 -0.8051965 0.05928039 0.3714101 -0.9265746 0.2494852 0.5346788 -0.8073883 0.1360694 0.4019794 -0.9054821 0.8389613 0 -0.5441911 0.5105388 0.8598548 0 -0.6741006 0.257412 0.6923348 -0.6843224 0.229991 0.6919589 -0.6436331 0.4204518 0.6394973 -0.6303927 0.4477756 0.6341152 -0.5824812 0.5708336 0.5786751 -0.5677219 0.5929023 0.5711031 -0.5038743 0.7040554 0.5004166 -0.4885634 0.7208648 0.491589 -0.4101598 0.8161256 0.4070724 -0.3952291 0.8279414 0.3978782 -0.2904149 0.9110461 0.2926677 -0.890258 0.08335798 -0.4477638 -0.9869892 0.09845042 0.1271219 -0.8390627 0.0996924 -0.5348228 2.70965e-4 0.7231497 -0.6906914 -7.52451e-4 0.7950972 -0.6064816 -0.009415268 0.7802208 -0.6254334 0.002680897 0.8353554 -0.549704 -1.5277e-4 0.884904 -0.4657737 0.001182556 0.8875786 -0.460655 -0.001135289 0.9500544 -0.3120824 -0.001067578 0.9501392 -0.3118243 9.51006e-4 0.9859774 -0.1668764 -0.002914965 0.988727 -0.1497011 0.07723903 0.9970127 -1.1221e-4 0.02791786 0.9994846 -0.01585006 0.01220434 0.9995191 -0.02850878 0.0027498 0.9991238 -0.04176449 0.00147289 0.9990198 -0.04424238 -0.008354187 0.9998231 0.01685363 -0.003001928 0.9999099 -0.01309162 -0.01646089 0.9996851 -0.0189464 0.001255512 0.9975304 0.07022547 -0.05103343 0.9930328 0.1062155 0.4226028 0.8139204 -0.3986736 0.473546 0.8179398 -0.3266936 0.9325067 0.3520213 -0.08069819 0.3686162 0.8832325 -0.2898663 0.9292338 0.3578174 -0.09214812 0.4314796 0.8918259 -0.1359112 0.3975144 0.9047292 -0.1531255 0.910652 0.4084586 -0.06224715 0.9255003 0.3766523 -0.03977662 0.3363329 0.9417428 8.75299e-4 0.5509508 0.833641 0.03867852 0.2786143 0.9599183 -0.03051108 0.920066 0.3909726 0.02488011 0.9101961 0.4138187 0.01723855 0.9876722 0.1537647 0.0293284 0.9026346 0.4303784 -0.00502634 0.4517914 0.02711701 0.8917115 0.460098 0.01347011 0.887766 -0.1891884 0.08439064 0.9783078 0.007497847 0.1390455 0.9902576 0.5096908 0.0656957 0.8578458 -0.4943362 0.2784597 0.8234634 0.5064991 0.117649 0.8541765 0.5090385 0.1129382 0.8533024 0.04395335 0.3068457 0.9507439 -0.3845657 0.4099982 0.8270494 -0.4010248 0.4286856 0.8095726 0.043949 0.3068507 0.9507425 0.5365477 0.1450437 0.8313117 -0.3833342 0.5756236 0.7222967 0.1274873 0.481359 0.8672027 0.5434232 0.1799464 0.8199455 0.536799 0.1986386 0.8199936 -0.2620797 0.6403601 0.7219788 -0.2899719 0.696212 0.6566621 0.1274884 0.4813555 0.8672046 0.5785382 0.209509 0.7882891 -0.2018024 0.8002145 0.5647411 0.5807597 0.2387432 0.7782801 0.2435359 0.6135582 0.7511569 -0.1071608 0.8160356 0.5679811 0.2435371 0.6135595 0.7511554 0.6056722 0.2319532 0.7611564 -0.1125308 0.8841904 0.4533696 0.6352382 0.2674841 0.7245168 0.632637 0.25378 0.7316872 0.3818923 0.6918341 0.6128 0.3818919 0.6918337 0.6128008 0.04978328 0.9313733 0.360646 0.0623511 0.9148168 0.3990271 0.1080878 0.9686424 0.2237163 -0.6572673 0.5402966 -0.5254325 -0.624855 0.5441068 -0.5599145 -0.5524313 0.5898724 -0.5889571 -0.4776741 0.6212202 -0.6212189 -0.4348464 0.6179786 -0.6549895 -0.5026471 0.6091389 -0.6134296 -0.3003395 0.6744622 -0.6744605 -0.3104793 0.6735184 -0.6708022 -0.1327344 0.6998506 -0.7018481 -0.08938032 0.707036 -0.7015065 0.04632556 0.7042871 -0.7084022 0.1590789 0.7031884 -0.692979 0.2262287 0.6893938 -0.6881548 0.3289839 0.671754 -0.663714 0.4073334 0.6437223 -0.6478434 0.5384637 0.5982347 -0.593441 0.5258163 0.6050944 -0.5978111 0.7053032 0.5095769 -0.4928274 0.7646628 0.4558568 -0.4555057 0.8193933 0.4045076 -0.4061629 0.8488252 0.3790981 -0.368484 0.9453508 0.2308415 -0.2302699 0.9509572 0.2168191 -0.2206127 0.9953019 0.06845957 -0.06846696 0.9930554 0.08515626 -0.08117526 0.1306185 -0.8720973 -0.4715774 -0.2886868 0.939889 0.1823972 0.07548344 -0.8667988 -0.4929119 0.07969188 -0.8636419 -0.497767 0.1279236 -0.7852202 -0.6058588 0.08530372 -0.7467164 -0.65965 0.1112099 -0.6749705 -0.7294157 0.07329988 -0.6352246 -0.7688413 0.09116071 -0.5454367 -0.8331798 0.05995345 -0.5093212 -0.8584856 0.06785219 -0.4008651 -0.913621 0.04496318 -0.3725645 -0.9269165 0.04265838 -0.2453956 -0.9684841 0.02877289 -0.2276608 -0.9733154 0.01186519 -0.08263629 -0.9965092 0.01505935 -0.07612735 -0.9969844 9.35715e-5 -5.81744e-5 -1 -1.49612e-7 0 -1 -0.00415039 0.003829538 -0.9999841 0.4519554 0 0.8920406 0.7067568 0.005009591 0.7074388 0.7060443 0.005374193 0.7081473 0.7052096 0.005628347 0.7089765 0.7042238 0.005725562 0.709955 0.6984286 0 0.7156798 0.698594 0.001042783 0.7155176 0.6994475 0.002879798 0.7146782 0.7005989 0.004240572 0.7135428 0.7018715 0.005129754 0.7122851 0.7030957 0.005588769 0.7110733 0.002337396 0.004740536 -0.9999861 -0.05594265 -0.8215866 -0.5673322 0.1841984 -0.7910799 -0.5833211 0.01475805 -0.8591935 -0.511438 -0.02639675 -0.8127173 -0.58206 -0.003294229 -0.7900847 -0.612989 0.05581611 -0.749934 -0.6591537 -0.03087157 -0.6789569 -0.7335289 -0.02185475 -0.6694396 -0.742545 0.02602875 -0.6692037 -0.742623 0.04196757 -0.6387615 -0.7682594 -0.0232461 -0.5037534 -0.8635346 0.02718001 -0.4954178 -0.8682295 0.01391738 -0.5145499 -0.8573476 -0.01630628 -0.4957451 -0.868315 0.03194385 -0.3741886 -0.9268023 -0.0144909 -0.3066127 -0.9517241 -0.001476764 -0.3014049 -0.9534951 -0.01018053 -0.3014394 -0.953431 0.02323645 -0.2283675 -0.9732977 0.001066982 -0.1024205 -0.9947407 -0.005247771 -0.1005085 -0.9949223 -0.007656157 -0.1005616 -0.9949014 -0.005274832 -0.1005383 -0.9949193 0.004743158 -0.07745271 -0.9969847 -0.04889899 -0.8888797 -0.4555239 0.03656172 -0.8803262 -0.4729579 -0.003386557 -0.9113426 -0.4116351 -0.0723406 -0.8835468 -0.4627222 0.06737059 -0.8947737 -0.4414082 0.1392434 -0.88713 -0.4400134 -0.06006246 -0.9188514 -0.390006 0.03747391 -0.9078493 -0.4176188 -0.07677996 -0.9160442 -0.3936597 0.1820166 -0.9055491 -0.3832112 0.06209367 -0.9310846 -0.3594802 0.1892503 -0.8998785 -0.3929416 -0.0569511 -0.945517 -0.3205532 -0.1729782 -0.9447917 -0.2782935 0.06639808 -0.9290549 -0.3639346 -0.06605398 -0.944503 -0.3217935 -0.1954647 -0.9470937 -0.2545725 0.2296618 -0.9066499 -0.3538948 0.231958 -0.9044478 -0.3580079 0.09473073 -0.9470679 -0.3067389 -0.04324483 -0.9675459 -0.2489674 -0.0401563 -0.9666828 -0.2528082 -0.1699603 -0.9670357 -0.1896195 0.09834474 -0.9451784 -0.3113939 -0.2975556 -0.9478172 -0.1144699 -0.1825266 -0.9677875 -0.1734114 -0.3195262 -0.9438383 -0.08409792 0.2707759 -0.9062064 -0.3247622 0.12917 -0.9577383 -0.257007 0.2712092 -0.9057574 -0.3256519 0.2707762 -0.9062088 -0.3247552 -0.01230341 -0.9826731 -0.1849385 0.1220201 -0.899999 -0.4184652 0.1215417 -0.8996283 -0.4194002 0.1273263 -0.908676 -0.3976131 0.1304464 -0.9216029 -0.365557 0.1286338 -0.9563322 -0.2624542 0.2274439 -0.8957888 -0.3818792 0.1005201 -0.9854596 -0.1369861 0.1912815 -0.9359201 -0.2957447 0.206274 -0.9257832 -0.3168224 0.1360763 -0.9180184 -0.3724588 0.1981372 -0.8652434 -0.4605383 0.1607044 -0.9383504 -0.3060598 0.2087543 -0.9241911 -0.319832 0.2101308 -0.9235985 -0.3206412 0.2563297 -0.9157437 -0.3093684 0.2411032 -0.9030527 -0.3554787 0.2606135 -0.8791193 -0.3990361 0.2725011 -0.8916178 -0.3616086 0.2606132 -0.879115 -0.3990461 0.3032559 -0.9022665 -0.3065147 0.3092437 -0.8849613 -0.3481552 0.2916394 -0.8928928 -0.3430581 0.3003532 -0.8767207 -0.3756976 0.3003521 -0.8767194 -0.3757015 0.3392355 -0.878213 -0.3371368 0.333404 -0.8813056 -0.3348765 0.3345064 -0.8741334 -0.3521311 0.3345066 -0.8741351 -0.3521266 0.365529 -0.8712196 -0.3276662 0.365792 -0.8716266 -0.3262873 0.9999955 -0.003008186 3.31879e-5 1 8.33568e-5 3.34822e-4 0.9999641 -0.003407955 -0.007767379 0.9989812 0.04512751 -4.02687e-4 1 3.18097e-6 0 1 -4.10958e-6 0 0.837976 -0.5448289 -0.03094971 1 -6.79506e-6 0 1 1.34438e-5 0 1 -2.00195e-5 0 -0.7169734 0.05797815 0.6946853 -0.5549713 0.2137231 0.8039461 -0.8072304 0.5272586 0.2652876 -0.7212954 0.5976719 0.3500305 -0.7829425 0.61492 0.09420466 0.8831481 -0.4435193 0.1527743 0.8672657 -0.466992 0.1725364 0.9850745 -0.1274706 0.1156699 0.9523313 -0.1859377 0.2418517 0.8115993 -0.07581377 0.5792744 -0.06885635 0.1345952 0.9885054 0.9073557 -0.09318494 0.4099053 0.9999291 -0.007989108 0.008831083 0.9495443 -0.03318291 0.3118726 0.9979124 -0.00455445 0.06442272 0.9400027 -0.005737125 0.3411189 0.9998195 0.001581311 0.01893723 0.8120155 0.03160804 0.5827794 0.9828572 0.04224348 0.1794639 0.9811263 0.05167436 0.1863362 0.3059343 -0.9059434 -0.2926957 0.4717551 -0.8814688 0.02144956 0.4968281 -0.8626452 0.09489524 0.6975289 -0.7161151 0.02515166 0.6933256 -0.7204994 0.01342827 0.3783665 -0.8715115 -0.3119399 0.9997844 0.01108682 -0.01755666 -0.3252865 0.1585435 -0.9322299 -0.9276869 0.0933333 -0.3615051 -0.4257484 0.404133 -0.809577 -0.5642621 0.3349891 -0.7545798 -0.8919276 0.2019551 -0.4045732 -0.9167748 0.1632171 -0.364533 -0.3417892 0.5188846 -0.7835426 -0.9300447 0.204182 -0.3054941 -0.4618717 0.618493 -0.6357209 -0.5175392 0.5845273 -0.6248849 -0.8972272 0.307918 -0.3164966 -0.907122 0.2892009 -0.3057654 -0.334867 0.7491911 -0.5714691 -0.9308661 0.2920598 -0.2195212 -0.4885507 0.7696741 -0.410999 -0.8925575 0.4008068 -0.206628 -0.01301449 0.6830748 -0.7302325 0.9641014 -0.2528635 -0.08104687 0.6462079 -0.730469 -0.2209762 0.6524103 -0.7243067 -0.2230261 0.9632915 -0.2550083 -0.08390611 0.6579047 -0.7126979 -0.2433582 0.6563096 -0.7135223 -0.2452421 0.896542 -0.4188883 -0.1440318 0.9825614 -0.1659482 -0.08387202 0.9631568 -0.2556708 -0.08343547 0.664126 -0.7048932 -0.2491229 0.3392137 -0.8892906 -0.3067515 0.3536769 -0.8817612 -0.3121057 0.3657771 -0.8783155 -0.3078458 0.3577999 -0.8828725 -0.3041638 0.3911018 -0.8757024 -0.2831692 0.3912124 -0.8756377 -0.2832168 0.3633452 -0.8725323 -0.3266004 0.3842945 -0.8703666 -0.3078633 0.3798308 -0.8731902 -0.3053976 0.3974111 -0.8689829 -0.2948446 0.3826029 -0.8687322 -0.3145148 0.3914965 -0.8670657 -0.3081033 0.3906881 -0.8676319 -0.3075351 1 -1.45594e-6 0 0.9999477 -0.007441937 0.00701934 0.999961 0.00838536 -0.002759397 1 4.20238e-6 0 0.01280051 0.005337238 -0.9999039 0.04313379 0.03422349 -0.998483 -8.24405e-5 3.26281e-4 -1 -0.2648477 -0.01101124 -0.9642274 -0.4029927 -1.34009e-4 -0.9152032 -0.6087464 7.6092e-4 -0.7933646 -0.7933165 0.00263822 -0.6088038 -0.9590357 -0.003581225 -0.2832628 -0.9470306 -0.00119102 -0.3211416 -0.8891438 0.07034194 -0.4521896 -0.2607533 0.174937 -0.9494234 -0.604173 0.1224911 -0.7873824 -0.7834984 0.1568573 -0.6012705 -0.9585772 0.03104162 -0.2831363 0.01279819 0.1651923 -0.9861784 0.002169191 -0.9999946 -0.002475082 1 -3.91906e-7 0 0.0826016 -0.8260163 -0.557561 -0.473027 0.779642 -0.4103705 -0.904596 0.3760168 -0.2007923 -0.3369748 0.8944904 -0.2938284 -0.9300392 0.3502094 -0.1112678 -0.5068891 0.847804 -0.1558591 -0.4324777 0.8914842 -0.1349787 -0.9130982 0.4010199 -0.0737214 -0.8713573 0.4858902 -0.06817138 -0.3480546 0.9373412 0.01579988 -0.9276394 0.3733227 0.0107482 -0.9220491 0.3839629 0.0489701 -0.8396537 0.5326473 0.1061539 -0.5176714 0.848705 0.1082419 -0.3974717 0.9021294 0.1678661 -0.3677316 0.8732 0.3198364 -0.9235249 0.3583346 0.1367407 -0.7781924 0.5687875 0.2662661 -0.5976586 0.7359775 0.3180271 -0.3448134 0.8848772 0.3132032 -0.8938061 0.4080255 0.1860806 -0.9401326 0.2935921 0.1730736 -0.9932257 0.08879643 0.07495313 -0.9411617 0.3050418 0.1454796 -0.002855479 0.98312 0.18294 0.0144419 0.9623745 0.2713429 -0.04489737 0.9380477 0.3435853 0.9798713 -0.009259939 -0.1994156 0.8351706 -0.06883072 -0.5456669 0.3927136 -0.03281903 -0.9190751 0.5214909 -0.1081427 -0.846376 0.2021932 -0.2011665 -0.9584624 0.9830816 -0.04580318 -0.1773494 0.9803977 -0.06234812 -0.1869043 0.8346403 -0.174293 -0.5224919 0.5686165 -0.2603399 -0.7803195 0.8346127 -0.1743311 -0.5225233 0.5009738 -0.3190675 -0.8045007 0.2960548 -0.3521385 -0.8878908 0.3952938 -0.3059073 -0.8661199 0.9832931 -0.07453441 -0.1660702 0.980495 -0.1018169 -0.1681163 0.8345359 -0.2854113 -0.4712646 0.5823139 -0.4211835 -0.6953524 0.8344978 -0.2854725 -0.471295 0.2211773 -0.4735667 -0.8525347 0.4092233 -0.5454488 -0.7314519 0.3910048 -0.5545665 -0.7345551 0.4885603 -0.5215927 -0.6994641 0.9827491 -0.103533 -0.1532489 0.8344125 -0.3857802 -0.3936107 0.9811226 -0.1353658 -0.1381109 0.9815413 -0.1328969 -0.1375331 0.5879799 -0.566228 -0.5776379 0.8343735 -0.385847 -0.393628 0.2447948 -0.7031911 -0.6675311 0.3773239 -0.7937089 -0.4771299 0.6684799 -0.621816 -0.408019 0.3652368 -0.8297475 -0.422044 0.9829686 -0.1488209 -0.1078195 0.8342893 -0.4681679 -0.2911704 0.9801588 -0.1683184 -0.1046795 0.5273244 -0.7483755 -0.4023221 0.7689965 -0.5705307 -0.288339 0.9832546 -0.1641282 -0.07919901 0.9841111 -0.1671201 -0.05996942 0.9793814 -0.1945212 -0.05453193 0.792079 -0.5893573 -0.1589617 0.5484709 -0.8178105 -0.1742576 0.8375391 -0.5094164 -0.1975429 0.241163 -0.9067862 -0.3458023 0.2375695 -0.9098817 -0.340112 0.2824472 -0.8943927 -0.3468216 0.2118482 -0.8748407 -0.4356306 0.3511077 -0.7704287 -0.5321306 0.232459 -0.8299633 -0.5070738 0.366066 -0.7643359 -0.5308356 0.2980045 -0.8520066 -0.4304394 0.1512646 -0.8521116 -0.5010238 0.2663684 -0.8341907 -0.4828807 0.3598143 -0.7699436 -0.5269921 0.3396797 -0.6784154 -0.651437 0.1553544 -0.6927188 -0.7042768 0.2285076 -0.5321831 -0.8152089 0.1273329 -0.6121681 -0.780408 0.1914119 -0.544382 -0.8167067 0.1535148 -0.6128447 -0.7751482 0.1411277 -0.505691 -0.8510933 0.1797662 -0.4803889 -0.8584349 0.1666155 -0.3367291 -0.9267432 0.1356553 -0.3689977 -0.9194773 0.09008049 -0.3619101 -0.9278505 0.09373366 -0.3565605 -0.9295583 0.03520065 -0.2255817 -0.9735881 0.08755058 -0.2146376 -0.9727619 0.152049 -0.07548326 -0.9854864 0.01351892 -0.1281173 -0.9916669 0.0257917 -0.07398718 -0.9969257 -0.9973791 0.05116158 -0.05116266 -0.9989907 0.04470539 -0.00437361 -0.9845536 0.12134 -0.1262171 -0.9756032 0.1722715 -0.1360923 -0.9577188 0.2004516 -0.2063833 -0.9299393 0.2693272 -0.250351 -0.9373143 0.2690706 -0.2214562 -0.8970142 0.3118559 -0.3132278 -0.8614809 0.3651812 -0.3528364 -0.8497461 0.3646922 -0.3806984 -0.7709907 0.4575126 -0.4430074 -0.7493137 0.4599667 -0.4764029 0.9844859 -0.1717435 -0.03594112 0.8655419 -0.5006891 0.01215672 0.5810279 -0.7915049 -0.1895437 0.4533263 -0.8726853 -0.1814269 0.711342 -0.6668606 -0.2220125 0.6608183 -0.7234095 -0.1999949 0.9526451 -0.2903081 -0.09049093 0.9608675 -0.2685312 -0.06800651 0.9609282 -0.2654742 -0.07836276 0.2336835 -0.9208079 -0.3122579 0.3177284 -0.9114137 -0.2614837 0.2729938 -0.9280538 -0.2533586 0.2764288 -0.9084844 -0.3134377 0.3275251 -0.903297 -0.2770956 0.3086735 -0.9130226 -0.2666651 0.391942 -0.8758842 -0.2814397 0.3151012 -0.9210598 -0.2288236 0.3171176 -0.9131181 -0.2562261 0.3546198 -0.8782312 -0.3208656 -1 2.81594e-5 -1.00174e-4 -0.9999993 0.001195013 -1.55113e-5 -1 -3.42215e-6 0 -1 4.00597e-6 0 -1 -3.91011e-6 0 -1 5.84609e-6 0 -1 -1.58208e-5 0 -1 -2.87228e-6 0 -1 -4.32788e-6 0 -1 5.59387e-6 0 1 1.59008e-7 0 1 -3.41841e-7 0 1 -6.56388e-7 0 1 5.06396e-7 0 1 7.63867e-7 0 1 -1.32972e-6 0 -0.9999998 7.19153e-4 -1.07949e-4 -0.9999995 -0.001043856 5.90098e-5 -1 8.5599e-5 -1.88159e-5 -1 4.67023e-5 -1.74634e-5 -1 2.83076e-5 -1.62974e-5 -1 2.08523e-5 -1.52462e-5 -1 3.98774e-6 -1.42758e-5 -1 6.96199e-6 -1.33639e-5 -1 7.31263e-6 -1.24939e-5 -1 4.22351e-6 -1.16522e-5 -1 2.04503e-6 -1.08269e-5 -1 -1.39463e-4 5.90143e-5 -1 2.4555e-4 -2.07856e-5 -0.002139687 0.07474064 -0.9972007 0 0.07844948 -0.9969182 0.001940488 0.2226194 -0.9749035 -0.003848135 0.233428 -0.9723665 0.003648638 0.3655376 -0.9307895 -0.005474627 0.3826521 -0.9238764 0.005172431 0.5001814 -0.8659052 -0.006927251 0.5224548 -0.8526389 0.00651437 0.6235849 -0.7817286 -0.008185923 0.6493989 -0.7604039 0.007663547 0.7330715 -0.6801085 -0.009219765 0.7603515 -0.6494465 -0.02101194 0.9236682 -0.3826169 -0.01644933 0.9722355 -0.2334258 0 0.9982421 -0.05926978 0.3572145 0.1721246 -0.9180256 0.1116613 0.07427316 -0.9909669 0.9603779 0.02415013 -0.277653 0.9878751 0.1082264 -0.1113103 0.9324972 0.04988521 -0.3577157 0.6954702 0.078673 -0.7142351 0.8290958 0.1833786 -0.5281784 0.7014632 0.1259256 -0.7014928 0.5298852 0.1107677 -0.8408045 0.3147926 0.1324383 -0.9398755 0.2480992 0.2156604 -0.9444244 0.9672077 0.06550782 -0.2453939 0.9656521 0.1096204 -0.2355834 0.9625334 0.1037701 -0.2505221 0.7094444 0.2697033 -0.6511136 0.2713506 0.3518237 -0.8958733 0.3129349 0.3807169 -0.8701302 0.6932175 0.2889031 -0.6602913 0.2421434 0.4853014 -0.8401484 0.9657092 0.1487578 -0.2127839 0.714321 0.4260214 -0.555204 0.962507 0.1651319 -0.2152017 0.6887317 0.4600478 -0.5603613 0.2881979 0.5971384 -0.7485772 0.3055509 0.6041898 -0.7359303 0.9672052 0.1794922 -0.1797127 0.2399594 0.7116745 -0.6602567 0.7185348 0.5517703 -0.423388 0.9656643 0.2127342 -0.14912 0.9625293 0.2151396 -0.1650835 0.594534 0.7006126 -0.3945521 0.343833 0.8196363 -0.4582307 0.3245199 0.8220254 -0.4679331 0.9656971 0.2352957 -0.1098415 0.684109 0.6738597 -0.2791202 0.9625121 0.2505924 -0.1037986 0.9672056 0.2453187 -0.06581979 0.3518749 0.9090262 -0.2232835 0.347796 0.9188774 -0.1862857 0.7014545 0.70149 -0.1259903 0.8450646 0.5309293 -0.06308561 0.9653711 0.2554906 -0.05275517 0.9336958 0.3307455 -0.1371849 0.9936645 0.111959 -0.009812653 0.02595931 -0.07363975 -0.996947 0.027188 -0.07262027 -0.9969891 0.1141648 -0.1502323 -0.9820371 0.3358852 -0.1108185 -0.9353612 0.5627717 -0.08353137 -0.822381 0.8414813 -0.06212443 -0.5367027 0.9396346 -0.1202301 -0.3203617 0.9937228 -0.009413003 -0.1114741 1.85779e-6 0 -1 -4.51701e-7 0 -1 0.002134203 -0.002418816 -0.9999948 0 6.41014e-4 -0.9999999 0.9937669 0 -0.1114786 0.9937118 3.13093e-4 -0.1119681 0.9463925 -2.7175e-4 -0.3230191 0.9334436 0.01976442 -0.3581794 0.8427928 -0.02596616 -0.5376115 0.8436014 -0.02714461 -0.5362834 0.7068773 0.02457982 -0.706909 0.5640779 -0.05169218 -0.8241021 0.532926 -0.02365112 -0.8458312 0.3377405 0.02282607 -0.9409625 0.3627134 0.002918541 -0.9318962 0.1154714 -0.00229156 -0.9933083 0.1119697 0 -0.9937117 0.5306605 0.8313519 -0.1650864 0.6379931 0.7513809 -0.1684982 0.111774 0.9919868 -0.05889815 0.4088394 0.8973245 -0.1663107 -0.01167392 0.9968492 -0.07845658 -0.01643747 0.9722406 -0.2334057 0.04465347 0.8710399 -0.4891785 0.01656275 0.8525092 -0.5224499 1 3.10351e-7 0 6.5167e-4 0.9999998 5.29619e-5 0.9999966 0.001384198 -0.002208054 1 -5.70506e-4 -7.43023e-5 0.961086 -0.1840682 0.205992 -0.5362554 -0.007166206 0.8440253 -0.5504496 -0.01512283 0.8347315 -0.5472633 -0.01161706 0.83688 -0.543847 -4.66592e-4 0.8391844 0 -1 0 0.3776602 -0.8640482 -0.3328568 0.2368711 -0.1000133 0.9663796 0.4539434 -0.462877 0.7613675 0.5200549 -0.4869199 0.7017492 0.540436 -0.6388316 0.5475613 0.01391738 0.5844959 0.8112774 0.281876 -0.102458 0.9539645 0.1757532 0.03600156 0.9837757 0.3483712 -0.1124808 0.9305835 0.4815795 -0.02410346 0.8760709 0.4910525 -0.03749573 0.8703227 0.4554896 -0.4619738 0.7609923 0.5929015 -0.3527636 0.7238963 0.4971065 -0.665467 0.5568114 0.4847894 -0.6409465 0.5951193 0.652553 -0.5413008 0.530253 0.6161574 -0.7085257 0.3440079 0.5454206 -0.837594 -0.03086584 0.4653367 -0.8693268 -0.1665315 0.3553192 -0.9340108 -0.03704398 0.6188419 -0.7150431 0.3251893 0.4530512 -0.8885421 -0.07237243 0.401898 -0.9070776 -0.1252533 0.6277956 -0.7016445 0.3369981 0.6444604 -0.3422868 0.6837475 0.6469035 -0.3190512 0.6926199 0.4957444 -0.01489186 0.8683408 0.3104243 -0.9035879 -0.2952381 0.1971139 -0.9421263 -0.2711902 0.3059458 -0.9047393 -0.2963849 0.2562024 0.08328598 0.9630285 0.3544101 0.05971103 0.9331818 0.6558814 0.07864439 0.750756 0.3323323 -0.07304048 0.9403299 0.7050172 -0.07075542 0.7056518 0.1856285 -0.1332911 0.9735378 0.5935947 -0.1371243 0.7929957 0.2614477 -0.2291522 0.9376217 0.09384083 -0.3045476 0.9478632 0.6470505 -0.2060917 0.7340654 0.5062759 -0.3062883 0.8061466 0.9208592 -0.1161531 0.3721921 0.2041416 -0.392111 0.8969812 0.853789 -0.2250663 0.4694566 0.9941435 -0.02715778 0.1046006 0.03057163 -0.4550173 0.8899577 0.5837455 -0.3522214 0.7315608 0.9861252 -0.08229124 0.144171 0.3807926 -0.495814 0.7804907 0.497214 -0.4468709 0.7436966 0.8715755 -0.2325186 0.431615 0.9816727 -0.08870482 0.1686726 0.7329768 -0.4172288 0.5372758 -0.4978063 4.92779e-4 0.8672881 -0.5350548 -0.006736338 0.8447906 0.06064909 -0.4010703 0.9140374 -0.003353774 -0.251598 0.9678261 0.01576977 -0.09440422 0.9954091 0.06213581 -0.01976609 0.997872 0.09037846 0.06707292 0.9936464 0.09116744 0.07841539 0.9927435 0.194193 0.2960969 0.935209 0.1344234 0.1859015 0.9733299 0.1086314 0.1694635 0.9795313 0.1153102 0.1785046 0.977159 0.1175344 0.1078433 0.9871959 0.1712553 0.0853886 0.9815195 0.1237934 0.06446164 0.990212 0.2467819 -0.07473063 0.9661853 0.3504899 0.032076 0.9360171 0.39219 0.05271083 0.9183728 0.3678779 -0.04794323 0.9286374 0.7897607 -0.09106856 0.6066175 0.66966 -0.3006506 0.6790911 0.7231866 -0.2860631 0.6286247 0.3758314 0.296083 0.8781149 0.4605287 0.1928144 0.8664503 0.3948699 0.2972266 0.8693296 0.322137 0.2883487 0.901711 0.3822845 0.1526339 0.9113515 0.340965 0.2912679 0.8938155 0.3191721 0.2459022 0.9152384 0.2437549 0.2802867 0.928452 0.2842794 0.1267594 0.9503248 0.2139113 0.2091978 0.9541898 0.2097261 0.1696964 0.9629217 0.1626902 0.227898 0.9599972 0.1532691 0.09098947 0.9839866 0.1791455 0.02928829 0.9833866 0.1670357 0.07722926 0.9829216 0.1331938 0.1255831 0.9831014 -0.724617 0.6671788 -0.1726348 -0.6476532 0.4092508 -0.6426969 -0.7253689 0.6658846 -0.1744641 -0.5572745 0.8212862 0.122205 -0.7246153 0.6671814 -0.1726316 -0.5506164 0.7971789 0.2476436 -0.7811428 0.6123464 -0.1218515 -0.7337259 0.5925793 0.3324096 -0.7240674 0.3981922 0.563178 -0.09459418 0.02775603 0.9951289 -0.3720337 0.2184861 0.9021391 -0.4756997 0.3210244 0.8189342 -0.4001361 0.7468502 0.5311366 -0.605444 0.5395126 0.5851185 -0.7773556 0.6232603 -0.08523511 -0.1925814 0.7445091 0.6392329 -0.3248364 0.001050889 0.9457697 -0.5623628 0.1437551 0.8142988 -0.6403983 -2.75398e-4 -0.7680431 -0.4927611 0.002374589 -0.8701615 -0.4171549 0.005316793 -0.9088199 -0.3399441 0.002449393 -0.9404425 -0.1374762 -0.001425623 -0.9905041 0.08637279 2.49695e-4 -0.9962629 0.2553984 0.007820427 -0.9668043 0.319364 0.004260659 -0.9476225 0.5456354 -0.00105375 -0.8380221 0.7122352 0.02560454 -0.7014738 0.9316018 -8.03547e-4 -0.3634797 -0.3041583 0.9036665 0.3014544 -0.1890541 0.9640443 0.1867545 -0.1771622 0.9677659 0.1790049 -0.06827867 0.995454 0.06640398 -0.05876928 0.9964561 0.06017881 0.05451798 0.996944 -0.05595141 0.06133568 0.9962894 -0.06037753 0.1756668 0.9684722 -0.1766433 0.1796801 0.9672673 -0.17919 0.2917768 0.9108977 -0.2917733 -0.7067435 1.78016e-4 -0.7074699 -0.7061063 0.004922449 -0.7080888 -0.6119597 0.1686864 -0.7726904 -0.468113 0.3843582 -0.7957004 -0.4436371 0.4103727 -0.7967311 -0.6920805 0.03288418 -0.721071 -0.4801709 0.3866037 -0.7873842 -0.4034767 0.473141 -0.7831629 -0.3814563 0.4980608 -0.7787341 -0.3970223 0.4797436 -0.7824445 -0.4409829 0.4329608 -0.78618 -0.4022779 0.5065561 -0.7626097 -0.3429994 0.5387044 -0.7695122 -0.2432358 0.6246196 -0.7420827 -0.1983163 0.6618924 -0.7228894 -0.04254239 0.7614476 -0.646829 0.1082051 0.8284441 -0.5495198 0.2735553 0.8669303 -0.4166529 -0.4472646 0.8826857 0.1442926 -0.754242 0.3957766 -0.5239083 -0.3663402 0.9287732 -0.05634981 -0.3560209 0.9344417 0.008245348 -0.5741702 0.7522953 -0.3230799 -0.574168 0.7523019 -0.3230682 -0.6934132 0.4873071 -0.5307635 -0.6941183 0.4903302 -0.5270446 -0.2076989 0.9752555 -0.07574957 -0.6409539 0.4787076 -0.6000144 -0.1477187 0.9601676 -0.2371867 -0.1551241 0.9528726 -0.2607114 -0.4126851 0.7712969 -0.4845535 -0.412685 0.7712969 -0.4845539 -0.5455379 0.5850832 -0.6000552 -0.5546634 0.5438347 -0.6297558 0.02742677 0.9478965 -0.3173959 -0.5027874 0.5062291 -0.7006689 -0.2469331 0.7194184 -0.6492006 0.01821643 0.8902195 -0.4551676 0.143426 0.9481597 -0.2835883 0.02092045 0.851215 -0.5244001 -0.4318569 0.5257264 -0.7328789 -0.2768213 0.7199547 -0.6364238 -0.1701346 0.8470757 -0.5035048 -0.1966278 0.7393109 -0.6440164 -0.4539805 -0.8470877 0.2763046 -0.4533604 -0.848363 0.273395 -0.4522265 -0.8622987 0.2278861 -0.3093813 -0.8458716 0.4344936 -0.3163899 -0.8510039 0.4191538 -0.3273567 -0.8542048 0.4039453 -0.1925182 -0.8433929 0.5016226 -0.2101692 -0.8212646 0.5304276 0.09594672 -0.7045931 0.7030952 0.2792406 -0.5346295 0.7976191 0.3361161 -0.58741 0.7361899 0.5099868 -0.3193511 0.7987041 0.733245 -0.1144878 0.6702569 0.6976909 -0.07378655 0.7125891 0.710013 0.09333074 0.6979764 0.7134165 0.1114984 0.6918129 0.4465981 0.2848923 0.8481666 0.4257016 0.3456322 0.8362516 0.4930779 0.3589311 0.7924914 0.4719185 0.3397439 0.813552 0.4885823 0.3554179 0.7968472 0.5040731 0.3040662 0.8083651 0.5413032 0.3531867 0.7630532 0.5159114 0.3437187 0.7846612 0.5494706 0.3572877 0.7552667 0.5575377 0.3109859 0.769701 0.591749 0.3431873 0.7294215 0.5667667 0.3431259 0.7490262 0.6133757 0.3486296 0.7086802 0.615197 0.3111583 0.724371 0.6236216 0.3302645 0.7085348 0.6427235 0.3284323 0.6921263 0.6668816 0.3003149 0.6819678 0.668949 0.329252 0.6664086 0.673443 0.3098803 0.6711549 0.6873942 0.3079509 0.6577656 0.7139731 0.3024111 0.6314983 0.7095375 0.2794122 0.6469046 0.7122894 0.2819702 0.6427571 0.6883561 0.3482038 0.6363334 0.7484955 0.2538752 0.612619 0.7514767 0.2630101 0.6050691 0.8008257 0.2947502 0.5213449 0.7568158 0.259699 0.5998219 0.7844568 0.2281603 0.5766891 0.7800489 0.2070798 0.5904589 0.7911553 0.2045117 0.5764099 0.791697 0.2313679 0.5654068 0.8041592 0.1867533 0.564315 0.810909 0.1596022 0.5629865 0.822303 0.152372 0.5482705 0.8324447 0.1912182 0.5200688 0.8267803 0.1150134 0.5506415 0.8317025 0.08125221 0.5492441 0.8480792 -0.01668649 0.5296069 0.1309141 -0.9567632 -0.2597422 -0.1489591 -0.9831051 -0.1063742 -0.01483452 -0.983344 -0.1811482 -0.157014 -0.9831088 -0.09404176 -0.2850607 -0.9583344 -0.01832276 -0.2986577 -0.9543526 0.00386399 -0.4305515 -0.8984192 0.08642065 -0.4341226 -0.8952089 0.1006914 0.1649684 -0.9644543 -0.20643 0.02009177 -0.9922361 -0.1227352 0.09740692 -0.9812533 -0.1662945 0.1538771 -0.9648271 -0.2131441 -0.03211128 -0.996072 -0.08251976 0.03310126 -0.9890071 -0.1441156 -0.1173545 -0.9926416 -0.02984511 -0.2559156 -0.9640985 0.07086223 -0.1627967 -0.9866204 0.008806109 -0.101218 -0.9931936 -0.0576319 -0.3905496 -0.9016283 0.1858432 -0.3375369 -0.9310195 0.1388224 -0.2815854 -0.9552078 0.09103715 -0.2339371 -0.971796 0.02976554 -0.4134761 -0.8927356 0.1790552 -0.4475362 -0.8655835 0.22467 -0.4091256 -0.898095 0.1613749 0.5149334 0.1353662 0.8464748 0.5446342 0.1177519 0.8303663 0.609116 -0.3574458 0.707962 0.5471408 0.1032153 0.8306525 0.5465114 0.1220452 0.8285109 0.6069376 -0.365236 0.7058537 0.5168855 -0.7590422 0.395834 0.5123671 -0.7644433 0.3912883 0.3393955 -0.9385729 0.06238275 0.3359303 -0.9399943 0.05967992 0.2363325 -0.9710448 0.03491389 0.5694711 0.1051251 0.8152617 0.5641799 -0.3738059 0.7361863 0.5722686 0.1190496 0.811379 0.5623487 -0.377904 0.7354948 0.4067869 -0.7857065 0.4660364 0.1629788 -0.981235 0.103033 0.2621039 -0.9469704 0.1858724 0.4038135 -0.7885184 0.463868 0.1204777 -0.9844543 0.1278077 0.5950385 0.09131306 0.798493 0.5288107 -0.3773037 0.7602639 0.6095115 0.1208391 0.7835137 0.305981 -0.7867974 0.5360276 0.5274409 -0.3794801 0.7601323 0.3041718 -0.7881531 0.5350649 0.01436418 -0.9826554 0.1848838 0.1715607 -0.9370491 0.3041481 0.004896938 -0.9743567 0.224956 0.6228352 0.08588939 0.7776243 -0.06247884 -0.9667105 0.2481273 0.6408137 0.1040457 0.7606132 0.4895374 -0.3701714 0.7895103 0.2041695 -0.763458 0.612737 0.4879917 -0.3719904 0.7896122 -0.0653547 -0.9336504 0.352173 -0.06812214 -0.9340104 0.3506907 0.2022971 -0.7645498 0.6119964 0.6441358 0.08124589 0.7605842 -0.1773179 -0.9252502 0.3353663 0.4417296 -0.3487561 0.8265859 0.6896401 0.1308606 0.7122303 0.6629344 0.08756345 0.7435393 0.4928792 -0.3056233 0.814656 0.101081 -0.7136439 0.6931775 -0.2111451 -0.8786945 0.4281516 -0.1489601 -0.8729726 0.4644673 0.1056499 -0.7117836 0.6944079 -0.2880908 -0.8620641 0.4169524 0.9148553 -0.2015232 0.3498975 0.9031133 -0.1593846 0.3987268 0.8885876 -0.1125301 0.44469 0.8701869 -0.05657875 0.4894626 0.8524698 0.006777524 0.5227328 0.8021779 0.1295281 0.5828663 -1.44951e-4 -0.9999205 -0.0126118 -6.70002e-4 -0.9998919 -0.01469069 0 -0.9999574 -0.009231984 -0.4189233 -0.9034371 0.09113085 -0.4513366 -0.8922941 -0.01031994 -0.4237365 -0.9057359 -0.009479165 -0.3229871 -0.9301205 -0.1748005 -0.4440127 -0.8882246 -0.117941 -0.3960765 -0.9111062 -0.1140574 0.707355 0.004577517 0.7068437 0.7078469 0.004104912 0.706354 0.7082546 0.003603219 0.7059479 0.7090581 0.002358198 0.7051463 0.7071077 1.48968e-6 0.707106 0.7071048 2.49381e-6 0.7071089 0.7141139 -0.005651712 0.7000068 0.7089964 2.76803e-4 0.7052121 0.6787242 7.41029e-4 0.7343929 -0.2020025 -0.8484395 0.4892294 -0.4705632 -0.8393442 0.2721611 -0.473387 -0.8340765 0.2832335 -0.4162015 -0.8776567 0.2376872 -0.4561776 -0.8447028 0.2799631 -0.4694327 -0.8343262 0.2890204 -0.4522299 -0.8622989 0.2278788 -0.4151757 -0.8777239 0.2392278 -0.4663877 -0.8348957 0.2922869 -0.4155336 -0.8706414 0.263278 -0.4643027 -0.8646032 0.192053 -0.4801806 -0.8535674 0.2021126 -0.481458 -0.8666383 0.1309058 -0.4647725 -0.8599386 0.2109312 -0.4683038 -0.8644235 0.182931 -0.4704764 -0.8629807 0.1841642 -0.4860926 -0.8572657 0.1697345 -0.4900521 -0.8609444 0.1364691 -0.4861276 -0.8655043 0.1207573 -0.4610552 -0.8809291 0.1067338 -0.4962244 -0.8676235 0.03147923 -0.4632857 -0.8801629 0.1033431 -0.4963526 -0.8589547 0.1258216 -0.4939816 -0.8610604 0.1206532 -0.493997 -0.866242 0.07477986 -0.4624959 -0.8860082 0.03297209 -0.4802328 -0.8761584 0.04150992 -0.4906923 -0.8685566 -0.06950241 -0.480872 -0.8764255 0.0253095 -0.4716268 -0.881496 0.02309173 -0.4290171 -0.9018104 0.05179274 -0.4402626 -0.8968451 -0.04287093 -0.4436562 -0.8952342 -0.04153299 -0.4381151 -0.8988739 -0.009003639 -0.9999876 0.002013564 0.004572629 -1 -5.39082e-5 3.98456e-4 -1 -3.74985e-4 2.15369e-5 6.50333e-5 -4.24809e-4 1 -5.06079e-4 -5.57512e-5 1 -0.3866671 0.005125284 0.9222052 -0.4907739 -0.01192617 0.8712055 -0.9137964 0.0114395 0.4060117 -0.9404833 0.001508772 0.3398367 0.7815409 0 -0.623854 0.7818362 -3.9468e-5 -0.6234839 0.8991082 3.73172e-5 -0.4377264 0.9009633 -3.05202e-4 -0.4338952 0.9725511 2.96982e-4 -0.2326892 0.9749265 -5.2047e-4 -0.2225264 0.9998937 5.14272e-4 -0.01457464 0.9999999 -6.1295e-4 0 0.9779868 6.22991e-4 0.2086656 0.9749271 -4.91809e-4 0.222524 0.9051734 5.0537e-4 0.4250423 0.9009674 -2.841e-4 0.4338868 0.7840216 2.93386e-4 0.6207337 0.7574181 -0.003181219 0.6529224 0.7835052 0.03640609 0.620318 0.8094613 0.08876681 0.5804249 0.7949306 0.05166721 0.6044964 0.7886002 0.1922282 0.5840874 0.8077305 0.09172278 0.5823732 0.8285039 0.2440603 0.504 0.9021775 0.08131206 0.4236323 0.9646988 0.1642861 0.2058312 0.9650751 0.1678408 0.2011455 0.8773846 0.3659671 0.3102651 0.8706684 0.3939211 0.2945554 0.84607 0.5108379 0.1523495 0.9830855 0.182586 -0.01432925 0.940811 0.253387 -0.2250995 0.9552413 0.2291569 -0.1870864 0.8006203 0.5968629 -0.05255329 0.8098816 0.5852063 -0.04031652 0.6977439 0.6778292 -0.2317349 0.8720387 0.2435303 -0.4245488 0.6747517 0.6823436 -0.2812783 0.7464115 0.2964394 -0.5958135 0.9540877 0.0945965 -0.2841978 0.8288258 0.3057972 -0.4685466 0.721512 0.5009825 -0.477951 0.7578341 0.6213868 -0.1989122 0.4881312 0.8096939 -0.3257668 0.4235047 0.866217 -0.265164 0.4259545 0.8657706 -0.2626865 0.5695811 0.817996 -0.0803743 0.5655918 0.8202447 -0.08546644 0.6715647 0.7358602 0.08666449 0.6756845 0.7312198 0.09363776 0.7447523 0.616601 0.2552399 0.7488847 0.6071465 0.265603 0.7826386 0.4659016 0.4128106 0.7840834 0.4558948 0.4211569 0.7825797 0.3015406 0.5446488 0.7814826 0.2843788 0.5553501 0.7414415 0.09761834 0.663879 0.7413328 0.09719735 0.664062 0.4609431 0.8871734 0.02132809 0.369863 0.9045552 -0.2120883 0.6576377 0.5467707 0.5182225 0.6573826 0.6755391 0.333909 0.5922223 0.7895867 0.1607033 0.4596391 0.8880764 -0.007225751 0.7613793 0.2650636 0.5916442 0.6766765 0.1457223 0.7217159 0.7459275 0.3292196 0.5789703 0.6873157 0.6590932 0.305276 0.344111 0.9389194 -0.0042423 0.7285835 0.2467918 0.6389522 0.2611839 0.9543986 0.1445901 0.2660969 0.9474036 0.1778172 0.5303927 0.7093008 0.4643017 0.6950469 0.2734687 0.6649246 0.6934548 0.2690451 0.6683826 0.5303921 0.7093014 0.4643014 0.6667519 0.2527706 0.7011056 0.265514 0.8662636 -0.4231902 0.09697586 0.8238956 -0.5583832 -0.07391184 0.7423495 -0.6659236 -0.5468373 0.2954072 -0.7833924 0.7071074 0 -0.7071062 0.7071074 0 -0.7071063 0.4096584 0.8150839 -0.4096564 0.4105514 0.8140231 -0.4108698 0.5209229 0.6764619 -0.5206137 0.5232887 0.6720031 -0.5240046 0.6091818 0.5085818 -0.6084753 0.6114826 0.501312 -0.612189 0.6711772 0.3162326 -0.6704612 0.6720027 0.3105002 -0.672311 0.7031762 0.1074113 -0.7028557 0.7031536 0.1056004 -0.7031527 0.346513 0.8716984 -0.346512 0.3465135 0.8716986 -0.3465114 0.2925519 0.9102368 -0.293057 -0.2678399 -0.9621656 0.04999279 -0.3982558 -0.912675 0.09174168 -0.4276668 -0.8978684 0.1045632 -0.2519304 -0.9662386 0.05398416 -0.3096126 -0.9474257 0.08077543 -0.3494175 -0.9321954 0.09444266 -0.4345346 -0.8933826 0.1142257 -0.280151 -0.9559341 0.08778226 -0.08963286 -0.9955469 0.02919584 -0.4012507 -0.9057256 0.1365985 -0.2556677 -0.9617177 0.09865641 -0.427843 -0.8886474 0.1650946 -0.08917099 -0.9953272 0.03704524 -0.08508962 -0.9956766 0.03725343 -0.2684402 -0.9561001 0.1175266 -0.3924307 -0.902892 0.1754549 -0.08595442 -0.9952327 0.04608476 -0.2418359 -0.9618641 0.1278001 -0.4102364 -0.8858371 0.2167922 -0.3791043 -0.899583 0.2168653 -0.2532933 -0.9559711 0.1481958 0 -0.001597702 -0.9999988 -0.09886491 0.001510381 -0.9950997 -0.2393283 -0.001431763 -0.9709377 -0.3225793 9.85645e-4 -0.946542 -0.4647574 -0.001201629 -0.8854373 -0.513181 6.6851e-4 -0.8582803 -0.6631585 -5.31175e-4 -0.7484788 -0.6801328 3.99355e-4 -0.7330888 -0.8275149 -7.27179e-5 -0.5614439 -0.8230035 -4.12378e-4 -0.5680362 -0.9705158 1.58771e-4 -0.2410378 -0.9349754 0.01068174 -0.3545518 -0.9927102 0 -0.1205261 0.7083307 -0.006050109 0.7058548 0.2152365 -0.5630365 0.7979118 -0.1169027 -0.001858413 -0.9931417 -0.1411382 -0.1261157 -0.9819241 -0.1023715 0.383092 -0.91802 -0.02680289 0.5798054 -0.8143141 -0.01268023 0.7776266 -0.6285986 -0.00903517 0.7349285 -0.6780844 6.76478e-4 0.8060946 -0.5917865 -0.001083076 0.8526382 -0.5225006 0.01510781 0.9102824 -0.413712 0.01390153 0.92379 -0.3826472 0.02031373 0.9433811 -0.3310884 0.01342141 0.9722836 -0.2334191 0.02135747 0.9899111 -0.1400707 0.01795202 0.9967567 -0.07844686 0.02255636 0.999266 -0.03096526 -0.00253874 0.02714657 -0.9996283 0.7002778 -0.2541831 -0.6670847 0.8518192 0.376347 -0.3643722 0.4903462 -0.1436392 -0.8596094 0.3366999 -0.1316734 -0.9323601 0.2727416 -0.3670957 -0.889299 -0.1718104 -0.1699352 -0.9703624 0.880852 -0.2154452 -0.421525 0.5265473 -0.3589505 -0.7706508 0.4399925 -0.2661986 -0.8576392 0.831632 -0.169717 -0.5287573 0.6470477 -0.2984358 -0.7016164 0.6459695 -0.293848 -0.7045401 -0.9997085 0.009312331 0.02228057 0.8435385 0.4415805 -0.3056949 0.8523254 0.4236877 -0.3066433 0.8454534 0.3922232 -0.3624497 0.9999922 -0.00153613 0.003636598 1 -4.40956e-5 2.50424e-4 1 3.81855e-5 -2.15945e-4 0.9999846 -8.01703e-5 0.005550563 0.9999982 -0.001665532 0.001028537 0.9999847 -0.001161873 -0.005423545 1 1.33553e-7 0 1 -1.7308e-7 0 -0.9999848 0.001047372 -0.005425035 -0.9999829 4.0838e-4 -0.005849599 -0.9515626 -0.2171736 0.2176335 -0.9713483 -0.1540325 -0.1809874 -0.1102128 -0.3669064 -0.9237061 -0.1102118 -0.3774132 -0.9194633 -0.2887054 -0.9407582 -0.1778299 -0.2737306 -0.9393494 -0.2066264 -0.2643916 -0.9237189 -0.2772013 -0.2641182 -0.9020748 -0.3413252 -0.2502977 -0.8845947 -0.3935015 -0.2439798 -0.8332548 -0.4961456 -0.2302222 -0.8122005 -0.5360301 -0.2164828 -0.7395884 -0.6372945 -0.2044018 -0.7190129 -0.6642593 -0.1861287 -0.6226618 -0.7600318 -0.1848658 -0.6344809 -0.7505056 -0.194454 -0.6345547 -0.748016 -0.1570996 -0.5516017 -0.8191798 -0.1586353 -0.6123095 -0.77454 -0.190328 -0.6460444 -0.7391901 -0.1475515 -0.4868354 -0.8609414 -0.1367073 -0.4775584 -0.8678992 -0.1008981 -0.3363657 -0.9363107 -0.1080862 -0.3424044 -0.9333149 -0.008674979 -0.201533 -0.9794433 -0.05391848 -0.2044529 -0.9773904 -0.06813019 -0.1746635 -0.9822683 -0.003753602 0 -0.999993 -0.003177762 1.88114e-4 -0.9999949 -0.924865 0.0145747 -0.3800164 -0.840346 -0.009421348 -0.5419687 -0.4192137 0.008547782 -0.9078475 -0.3581739 1.38414e-4 -0.9336549 -5.61768e-4 -0.9999996 8.61526e-4 -0.05785393 -0.9983251 2.03282e-4 0.01407217 -0.9998986 -0.002243757 0.006702721 -0.9999766 -0.001414 -0.1145752 -0.9928461 0.03360474 0.01814156 -0.9998317 -0.002762138 -1 2.4553e-6 9.37157e-6 -1 3.471e-6 6.26154e-6 -1 3.7072e-6 4.56118e-6 -0.9999936 1.87408e-4 0.003590404 -0.9999987 0.001240789 0.001069128 -0.9999988 0.001306474 7.77942e-4 -0.9999991 0.001323223 5.06233e-4 -0.9999728 -4.82474e-4 -0.007373869 -0.9999992 0.001300036 2.45736e-4 -1 -1.84774e-4 -1.34456e-5 -0.9999991 -5.24427e-4 0.0012331 -0.9820407 -0.05352365 -0.1809182 -0.9995699 -0.01029503 -0.02745991 -0.9998227 -0.002960801 0.01859796 -1 -3.72739e-4 -1.38769e-4 -1 -1.77812e-4 -1.78148e-6 -0.268144 -0.9182851 -0.2912929 -0.3769391 -0.9068272 -0.1886302 -0.2701635 -0.9432855 -0.192936 -0.2694007 -0.9578105 -0.1001126 -0.3814453 -0.9167324 -0.1187486 -0.3789718 -0.9229676 -0.06716555 -0.3788593 -0.9039307 -0.1984311 -0.4489918 -0.8880225 -0.09910857 -0.3817814 -0.9164614 -0.1197565 -0.4380425 -0.8985005 -0.02856105 -0.3745914 -0.926162 -0.04364895 -0.02661353 -0.004262447 -0.9996367 0.04035472 0.04176372 -0.9983123 0.01030802 -0.005361795 -0.9999326 -0.8478515 0.4617443 -0.2606533 -0.1318634 0.8672449 -0.4801025 -0.2381291 0.7980723 -0.5535117 -0.9999969 0.002278864 0.001057028 -0.9999166 0.008903384 0.009352862 -0.9999995 6.26034e-4 8.82795e-4 -0.9999924 0.003165483 0.002286016 -0.9999995 1.41934e-5 0.001077771 -0.9999748 0.003959 0.005900263 -0.9999958 0.00228101 0.001818239 -0.9995821 0.02850633 0.004820764 -0.9999895 -0.003032743 0.003450095 -0.9999885 -0.004141032 0.002423942 -0.9999749 -0.00464183 -0.005358994 -0.9999969 0.001284539 -0.002148747 -0.9999857 7.17588e-5 -0.00536549 -0.9999889 0.001848459 -0.004346787 -0.9998855 -0.01435577 0.004785716 -0.999518 0.01269304 0.02833378 -0.9996761 -0.02527791 0.002978086 -0.9994114 0.01254117 0.03193277 -0.2049688 -0.896389 -0.3930326 -0.1773713 -0.8467383 -0.5015712 -0.1210752 -0.8553029 -0.5037833 -0.1893836 -0.823015 -0.5355187 -0.08551704 -0.818138 -0.5686273 -0.1608434 -0.7333628 -0.6605365 -0.15808 -0.7313078 -0.6634755 -0.1088457 -0.7426179 -0.6608111 -0.06638288 -0.6762052 -0.7337166 -0.1413075 -0.6168396 -0.7743005 -0.09200024 -0.6003286 -0.7944443 -0.1260766 -0.6019377 -0.7885275 -0.0326761 -0.5030406 -0.8636449 0.01233756 -0.4837051 -0.8751442 -0.08330184 -0.5792713 -0.8108673 0.004136621 -0.3080316 -0.9513671 -0.05414748 -0.3484268 -0.9357707 -0.03686916 -0.1281383 -0.9910708 -0.1125457 -0.8871731 -0.4475013 -0.1599214 -0.8984308 -0.4089589 -0.2550567 -0.8911059 -0.375335 -0.1993896 -0.9065436 -0.3720518 -0.3353774 -0.900687 -0.2761976 -0.151363 -0.9177034 -0.3673008 -0.1897391 -0.9227646 -0.3354171 -0.2407427 -0.9162504 -0.3202002 -0.3324269 -0.9079114 -0.2553218 -0.4054808 -0.8943605 -0.1889564 -0.3016276 -0.9156136 -0.2658432 -0.2854925 -0.9334266 -0.2172763 0.001473486 -0.9999989 0 0.005607068 -0.9999683 0.005659341 0.0150122 -0.999831 0.0106157 0.09285223 -0.9952319 0.02986824 -0.01021814 -0.9861576 -0.1654961 -0.001252889 0.004385948 -0.9999896 -1 -3.07588e-4 -2.61775e-4 -1 1.82076e-4 -1.48305e-4 -0.9999998 7.82143e-4 1.38939e-4 -0.9999911 -0.002938926 -0.00305736 -0.919341 0.2809095 -0.2755032 -0.6221973 0.5905665 -0.5139083 -0.7568091 0.5196204 -0.3965283 -0.7566587 0.5420819 -0.3655337 -0.690002 0.563445 -0.4543424 -0.6915109 0.646816 -0.3216236 -0.592689 0.682546 -0.4276105 -0.6344888 0.7677957 -0.08895921 -0.6615512 0.7496544 0.01919561 -0.4701437 0.863682 -0.18171 -0.4673519 0.864352 -0.1856825 -0.2423684 0.9696425 -0.03241991 -0.2656977 0.9622778 0.05853426 -0.9989492 -0.02723044 -0.03686493 -0.9539238 0.299892 -0.009709715 -0.9998636 0.01640158 -0.002003967 -0.6887392 0.6979256 -0.1963115 -0.6244903 0.7433002 -0.2398265 -0.6851564 0.7212867 -0.1015195 -0.5584479 0.8267541 -0.06792527 -0.1061056 0.9943397 0.005492329 -0.3220087 0.9467312 -0.003268539 -0.5527118 0.821884 -0.1379006 -0.4947187 0.8673378 -0.05457812 -0.9999946 0.001167833 -0.003091156 -0.9999359 0.01132225 4.71741e-4 -1 -7.94338e-5 2.14296e-4 -1 -2.04081e-4 1.31795e-4 0 1 0 0 1 0 0.001496374 0.9999989 1.30483e-4 0.02107721 0.9997777 6.08223e-4 -0.9093911 0.3380467 -0.2423477 -0.2822736 0.8794949 -0.3831586 -0.8813602 0.4281744 -0.1996769 -0.216539 0.9147156 -0.3411837 -0.8915888 0.424292 -0.1582587 -0.8936868 0.4196648 -0.1587622 -0.8327754 0.5508205 -0.05551427 -0.2426601 0.914548 -0.323602 -0.09216773 0.9737858 -0.2079577 -0.7833909 0.6076484 -0.1306221 -0.1685231 0.97171 -0.1654686 -0.01020032 0.9999002 -0.009778976 -0.9997458 0.02213084 -0.004313528 -0.9996268 0.02649706 -0.006659209 -0.998517 -0.008014261 -0.05384755 -0.9999911 -0.001081705 -0.00407958 -0.9999971 4.84433e-4 -0.002406001 -0.9999889 0.001256763 0.004557549 -0.9977687 0.03906857 0.05414134 -0.9996494 0.02639657 -0.002122759 -0.4188753 0.8940788 -0.1586395 0.006332933 -0.05714911 -0.9983456 -0.9267013 0.231075 -0.2963595 -0.9033291 0.2401164 -0.3554443 -0.9207643 0.2057535 -0.3314494 -0.4789333 0.4942929 -0.7254635 -0.5234429 0.4641446 -0.7145469 -0.3489233 0.4490349 -0.8225693 -0.9256721 0.1601096 -0.3427772 -0.4704908 0.310767 -0.8258707 -0.4432406 0.3249691 -0.8354238 -0.9004545 0.1531812 -0.4070838 -0.9173164 0.1272222 -0.3772866 -0.356484 0.2324959 -0.9049115 -0.9265884 0.08252972 -0.3669099 -0.2781873 0.1961504 -0.9402856 -0.4348198 0.127923 -0.8913851 -0.9397397 0.1050327 -0.3253574 0.002019226 0.9766474 -0.2148395 0.00341916 0.9261009 -0.3772609 0.002323269 0.1679984 -0.9857845 -0.9980025 0.05698579 -0.02726864 -0.9865032 -0.07302439 -0.1465567 -0.999157 0.006472051 0.04053902 -1 8.35988e-7 0 -1 -5.72268e-7 0 -1 5.30475e-7 0 -0.9999999 1.41112e-5 5.53611e-4 -1 6.204e-5 -2.3457e-5 -1 3.27814e-5 -2.61019e-4 -1 -1.84652e-4 -1.70201e-6 -0.9999247 0.001418232 0.01219159 -0.9999998 3.43512e-5 6.25155e-4 3.5936e-4 0.9999997 -8.50457e-4 -7.40409e-4 -0.9999868 0.005084753 -0.006421625 -0.999781 -0.01991832 -0.0062626 -0.9996674 0.02502143 -4.43714e-4 -0.9999997 7.56921e-4 0.06325995 0.9530309 -0.2961934 1.25689e-4 -1 -1.33372e-4 5.63404e-5 -0.9999976 -0.002221465 0 -1 0 0 -1 0 0 -1 0 -7.14057e-4 0.9999998 0 -6.58427e-4 0.9999998 2.28456e-4 0.9999979 -0.002053201 -2.09145e-4 1 -2.08662e-6 0 1 1.1923e-5 -4.75464e-5 1 2.06879e-5 -4.63189e-5 1 2.83237e-5 -4.43978e-5 1 3.43781e-5 -4.16779e-5 1 4.43815e-5 -3.80006e-5 0.9999709 -0.006778717 -0.003507316 0.9999766 0.005830824 -0.003573298 0.9999594 0.008340716 -0.00345385 0.9999153 0.01266342 -0.003040134 0.9997536 0.02213245 -0.001742243 0.9994719 0.03249943 0 -0.003580212 0.01693403 -0.9998503 0.004159033 0.07844877 -0.9969095 -0.00170207 0.1420554 -0.9898573 0.003893315 0.2488425 -0.9685362 5.62959e-4 0.2334299 -0.9723735 -4.43083e-4 0.3625256 -0.9319737 0.003127932 0.3826562 -0.9238855 -0.002499163 0.4791488 -0.8777301 0.004077374 0.5224629 -0.8526523 -0.002746105 0.5885288 -0.8084717 0.009340643 0.6493924 -0.7603963 8.39371e-4 0.7543671 -0.6564523 0.002449214 0.7603818 -0.6494718 -0.001861214 0.829112 -0.5590797 0.003916382 0.8526192 -0.5225182 -0.002659559 0.8927369 -0.4505707 0.003834605 0.9238658 -0.3826974 -0.006707966 0.9526135 -0.3041092 0.00412631 0.972359 -0.2334549 -0.004819989 0.9951824 -0.0979225 -6.43227e-4 0.996917 -0.07846164 0.7960914 0.05508351 -0.6026644 -0.003608047 0.004158914 -0.9999849 0.8287035 0.005043327 -0.5596652 1 0 -2.10932e-4 0 -1 0 -2.75147e-4 -1 2.19419e-4 -2.51305e-4 -1 1.21024e-4 -2.32415e-4 -1 5.30488e-5 -2.15541e-4 -1 0 -1.99076e-4 -1 -4.54391e-5 -1.76186e-4 -1 -1.01368e-4 -0.002018332 -0.9999904 0.003917396 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 4.31231e-4 0.9999994 -0.001105248 -0.07286357 0.9819766 -0.174393 0.09330505 0.9900181 0.1056337 -7.14978e-6 1 -1.71598e-5 -0.005053281 -0.001902341 -0.9999855 -3.0353e-4 0.002226948 -0.9999976 0.003479897 0.02061891 -0.9997814 -4.1924e-5 -0.005414128 -0.9999854 -0.001603662 0.2653653 -0.9641466 -0.002326369 0.6270264 -0.7789947 -3.30502e-4 0.8686488 -0.4954283 0.002951383 0.9821726 -0.1879587 0.01462584 -0.858115 -0.5132493 0.009435951 -0.3456978 -0.9382985 -0.008150696 0.2374205 -0.9713729 0.01098859 0.928408 -0.3713999 0.0137149 0.7779062 -0.6282308 0.9369826 -0.01281577 -0.3491408 0.9405003 -0.01829624 -0.3393001 0.3653695 0.01784718 -0.9306915 0.4224374 -0.009571671 -0.9063416 0.336315 0.1219647 -0.9338185 0.9430256 0.1321551 -0.3053489 0.9098356 0.06163299 -0.4103666 0.405523 0.2063769 -0.890483 0.9031061 0.2048665 -0.3773981 0.3568853 0.3739794 -0.8560212 0.5325916 0.5304426 -0.6595278 0.4165644 0.828377 -0.3745209 0.4164859 0.828327 -0.3747187 -0.9999765 0.004486918 -0.005196928 -1.08341e-5 0.9999998 8.26283e-4 -0.003672957 0.9999915 -0.001937806 0.04137194 0.9989054 0.02182757 -0.005012035 0.9999724 0.00551325 0.279649 0.8268695 -0.4879378 0.046036 0.9904432 -0.1300119 -0.007558941 0.9999521 0.006216526 0.364331 0.8298283 -0.4226678 0.7074095 -6.98707e-4 0.7068036 1 1.37355e-7 0 0.8558652 0.4400526 -0.2717511 0.8356484 0.4838561 -0.2599521 0.8914898 0.4130164 -0.186182 0.8625032 0.4843688 -0.1465446 0.8659469 0.4789409 -0.1440542 0.8894211 0.4488893 -0.08618885 0.9688905 0.2464345 -0.02283304 0.018386 0.974377 -0.2241683 -6.72768e-4 0.007193684 -0.9999739 0.1884723 0.9642542 -0.1862586 0.3229725 0.8809741 -0.3457939 0.7049357 -6.64896e-4 0.7092709 -0.908913 0.01398503 -0.4167514 -0.8437784 -0.03306895 -0.5356721 -0.4072045 -0.02035832 -0.9131101 -0.2515869 -0.06225973 -0.9658301 -0.7649502 0.5974295 -0.240685 -0.7288852 0.5546277 -0.4013909 -0.6450799 0.5945251 -0.4800124 -0.5304828 0.6080412 -0.5906555 -0.3042643 0.6476573 -0.6985437 -0.3062797 0.4931384 -0.8142527 -0.008366346 0.7124717 -0.7016509 0.9928977 0.05152982 -0.1072329 0.9985327 0.004922807 -0.05392879 0.948361 0.004379987 -0.317163 0.9999083 -0.01321697 0.002993822 0.9997985 0.0191459 -0.006029903 1 3.53775e-4 -1.09141e-4 0.9999999 -4.81745e-4 1.90219e-4 1 -1.59972e-6 -2.49136e-7 1 -4.14841e-6 0 0.9999588 0.007681846 -0.004833638 0.9999839 -0.003909945 0.004124104 -0.3255857 0.9092779 -0.2592448 -0.1336529 0.9147942 -0.3811675 0.359624 0.5876311 -0.7248175 -0.2118138 0.1687 -0.9626398 -0.2590506 0.1943407 -0.9461102 -0.7488939 0.08450257 -0.6572802 -0.8339809 0.148599 -0.5314078 0.927399 -0.3737809 -0.01480239 0.9298827 -0.3676535 -0.01221442 0.619563 -0.7844023 0.0292387 0.5544282 -0.8321262 0.01324939 0.3554904 -0.9331609 0.05326741 -0.06802839 -0.9976542 0.007637262 -0.1239227 -0.9919637 0.02551847 0.9902527 -0.0966559 0.1002869 0.9195506 -0.2222741 0.3240694 0.9503159 -0.2368006 0.2020526 0.9611477 -0.2175061 0.1699591 0.5934496 -0.6296312 0.5013803 -0.2910826 -0.795597 0.5313157 0.5608987 -0.6416709 0.5231168 0.1312948 -0.8026035 0.5818842 0.08355575 -0.8017702 0.5917628 0.9401589 -0.2953581 0.1698967 0.9463987 -0.2951787 0.1311457 0.9562072 -0.2717004 0.1088433 0.4956529 -0.7937101 0.3526366 -0.1879935 -0.9060434 0.3791356 -0.1217802 -0.9296506 0.3477349 0.5404254 -0.7761765 0.3247932 0.9413361 -0.3277946 0.08023113 0.9286494 -0.365149 0.06539589 0.961643 -0.2735056 0.02092009 0.507673 -0.8523334 0.1256826 -0.1156812 -0.9704195 0.2119055 0.5530733 -0.8265057 0.1048734 -0.1980081 -0.9683348 0.1520547 -0.06289684 -0.9965847 0.05350768 -0.2745485 -0.9611018 0.03011047 -0.3367016 -0.7377874 0.5850656 -0.3022667 -0.7344393 0.6076462 -0.3970602 -0.7189812 0.5704467 -0.2626711 -0.6725482 0.6918691 -0.4060206 -0.7579737 0.5105128 -0.4200506 -0.8499844 0.3179374 -0.3257352 -0.8443655 0.4253745 -0.383799 -0.8129539 0.4379547 -0.3632602 -0.9102383 0.198767 -0.2801457 -0.9154125 0.2890301 -0.3581888 -0.9128196 0.1961153 -0.3138513 -0.9461466 0.07939928 -0.3856433 -0.9094269 0.1556345 -0.3279863 -0.9446426 -0.008694589 -0.427953 -0.9033969 0.02702939 -0.2539839 -0.9609709 -0.109668 0.9937127 0.1119608 -1.26434e-7 0.9426113 0.3338922 1.18998e-5 0.8467501 0.5319909 -3.61206e-7 0.7070948 0.7071188 -5.93583e-6 0.5373345 0.8433693 7.16338e-6 0.3546353 0.9350048 -2.16994e-4 -0.9254779 -0.1788794 -0.3339054 -0.8985208 -0.09204894 -0.4291705 -0.9743472 0.04967176 -0.2194998 0.002589523 0.7814381 -0.6239776 0.001488924 0.7070907 -0.7071213 0.002418816 0.4763811 -0.8792357 1 -6.98387e-6 0 -7.97776e-4 -0.999953 -0.009672939 -0.002029955 -0.9999897 0.004080832 -0.03005784 -0.9965494 0.07736909 -0.003503561 -0.9995632 -0.02934694 -0.02316039 -0.9993519 -0.02755737 1 -7.54539e-5 3.83553e-5 1 1.95094e-6 0 1 -2.45063e-6 0 1 -8.57932e-7 0 1 2.25101e-4 -5.17223e-5 1 -2.05414e-4 3.16624e-5 1 2.65882e-6 0 1 -1.72558e-6 0 1 3.78805e-6 0 1 1.0671e-6 0 0.9999998 8.27771e-4 -7.31935e-5 1 -4.35883e-5 -1.89105e-6 0.9999979 -0.002070128 1.34167e-4 1 6.83156e-5 -1.43043e-7 0.1415971 0.9899244 2.81365e-5 0.1085429 0.9940918 -3.38015e-5 0.2140609 0.9768198 0.001014351 0.5328855 0.8461874 4.48019e-5 0.7072293 0.7069843 -7.50871e-6 0.8463197 0.5326755 6.46216e-6 0.9443244 0.3290158 -3.28754e-5 0.993865 0.1106007 -1.1726e-5 0.1760877 -0.9063529 -0.3840803 0.09975576 -0.9386106 -0.3302407 0.1526376 -0.9216807 -0.3566601 0.1807117 -0.9037523 -0.38804 0.2034283 -0.8985968 -0.3887683 0.1517844 -0.9223296 -0.3553445 0.2045128 -0.8979811 -0.389621 0.1649194 -0.9223597 -0.3493624 0.2273359 -0.8935043 -0.3872578 0.22556 -0.8945078 -0.3859775 0.2231776 -0.8960372 -0.3838087 0.2207193 -0.8979066 -0.3808501 0.2123153 -0.9059876 -0.3662087 0.2285431 -0.9219208 -0.3127782 0.2369599 -0.9159456 -0.3238729 0.1874396 -0.9391138 -0.2879788 0.2739867 -0.9338153 -0.2300445 0.2413733 -0.9499744 -0.1982114 0.2129999 -0.9592269 -0.185782 0.3897479 -0.8952633 -0.2158708 0.2372152 -0.899676 -0.3664863 0.1294394 -0.9553148 -0.2657429 0.2702637 -0.91424 -0.3018655 0.2598927 -0.9169959 -0.3026125 0.2548688 -0.9439575 -0.2097288 0.2616177 -0.9163236 -0.3031622 -0.2802768 -0.9591352 -0.03879255 -0.1052476 -0.9894365 -0.09969222 -0.03191983 -0.9734483 -0.2266705 -0.02945131 -0.9637354 -0.2652298 4.13872e-4 -0.9551025 -0.2962756 -0.04267185 -0.9766634 -0.2104943 0.1775664 -0.9051184 -0.3863043 0.1196913 -0.927413 -0.3543718 -0.1617613 -0.975425 -0.1495974 -0.281467 -0.9587406 -0.03991204 -0.3051204 -0.9314032 -0.1984683 -0.2764685 -0.943381 -0.1832969 -0.2720334 -0.9455534 -0.1786801 0.5017039 -0.8382288 -0.2136954 0.1614738 -0.9473162 -0.2766194 -0.123639 -0.9910038 -0.05123317 0.02714645 -0.9987475 -0.04203009 0.3227751 -0.9163478 -0.2369031 0.3590193 -0.9024697 -0.2380201 0.3594515 -0.9318961 -0.04862475 0.3544587 -0.9338448 -0.047885 0.7632202 -0.6257334 -0.1610989 0.6172836 -0.7851406 -0.05015242 0.7631555 -0.6258116 -0.161101 0.7628613 -0.6460998 -0.02445119 0.9400089 -0.3270505 -0.09706383 0.9458875 -0.3238125 -0.02103495 0.9867432 -0.1582716 -0.03588891 0.9274069 -0.3737763 -0.0144149 0.9999996 -9.17838e-4 -2.27767e-4 1 -4.28147e-4 -1.50951e-4 0.3310409 -0.8797057 -0.3413648 0.3289586 -0.8802478 -0.3419799 0.3250807 -0.8809494 -0.343876 0.3947951 -0.8588355 -0.3264025 0.7653114 -0.5993843 -0.2345997 0.7943932 -0.5678073 -0.215718 0.9870088 -0.1490936 -0.05987393 0.9900225 -0.1313964 -0.05089843 0.9906854 -0.1272195 -0.04855513 0.9999996 -9.87542e-4 -2.79771e-4 0.1294597 -0.6409711 -0.7565689 0.1100846 -0.8002188 -0.5895178 0.1579405 -0.6826351 -0.7134873 0.1673113 -0.7614156 -0.6263013 0.1915856 -0.7975618 -0.5720055 0.1797449 -0.7140406 -0.6766372 0.2087545 -0.7859613 -0.5819678 0.2087785 -0.7836321 -0.5850917 0.2189413 -0.8235958 -0.5232158 0.2829174 -0.7827305 -0.5543383 0.253291 -0.8631873 -0.4367509 0.2529324 -0.8737232 -0.4154915 0.2547164 -0.9441245 -0.2091617 0.9410039 -0.3218023 -0.1046664 0.9371364 -0.3334425 -0.102916 0.9219451 -0.3727718 -0.1051592 0.9376876 -0.3328194 -0.0998665 0.5865759 -0.7795065 -0.219769 0.6552885 -0.7211241 -0.2248937 0.6751486 -0.702938 -0.2237244 0.4822707 -0.842445 -0.2402119 0.9468972 -0.311807 -0.07850086 0.5543984 -0.8077327 -0.2005255 0.9431468 -0.3247797 -0.07065665 0.9445284 -0.3207141 -0.07077223 0.9250382 -0.3721839 -0.07605046 0.6514732 -0.7442591 -0.1471771 0.6790699 -0.7182093 -0.1517875 0.6141547 -0.7746479 -0.1507805 -0.6515077 -0.5922797 -0.4740701 0.2983582 -0.7588099 -0.5789559 0.4743295 -0.6923699 -0.5437237 0.4932813 -0.7235894 -0.4827961 0.6180691 -0.6309404 -0.4689403 0.6272729 -0.6254296 -0.4640761 0.7773426 -0.5031926 -0.3775391 0.7745686 -0.6067619 -0.1785598 0.8311404 -0.4504856 -0.3259884 0.9231412 -0.3639666 -0.1238499 0.8511587 -0.4265249 -0.3059502 0.969431 -0.199123 -0.1433655 0.9708631 -0.2302814 -0.06629961 0.9781036 -0.1713885 -0.1180644 0.2213925 -0.6612526 -0.7167499 0.1979601 -0.6884124 -0.6977823 0.3015044 -0.6507887 -0.696828 0.3922005 -0.8019897 -0.4505456 0.2343123 -0.8909326 -0.3890205 0.6222634 -0.5655628 -0.5412273 0.2120811 -0.9425153 -0.2582378 0.6318198 -0.5640345 -0.5316662 0.6980609 -0.5647023 -0.4402526 0.590187 -0.7511847 -0.2956365 0.8333127 -0.4261968 -0.3520601 0.8532586 -0.4038364 -0.3299489 0.6121371 -0.7613176 -0.2137373 0.9731557 -0.2195509 -0.06903213 0.04483354 -0.9568561 -0.2870826 0.1242132 -0.7776114 -0.6163535 0.05319547 -0.9818876 -0.1818436 0.1450359 -0.8415976 -0.5202675 0.04814887 -0.9834967 -0.1744017 0.3857413 -0.8689323 -0.3100977 0.4760893 -0.8328139 -0.2824183 0.7946657 -0.5658835 -0.2197324 0.9397612 -0.3314501 -0.08360534 0.9904782 -0.1295601 -0.04655432 0.9907284 -0.1274753 -0.04698431 1 -7.63032e-7 -4.63851e-7 1 -8.55687e-6 -4.98491e-7 1 1.34337e-5 -5.12035e-7 1 -8.08992e-6 -5.13496e-7 1 -1.03492e-5 -5.14218e-7 1 1.38018e-5 -5.14443e-7 1 -1.61781e-5 -5.14375e-7 1 5.23183e-6 -5.14167e-7 1 1.16989e-6 -5.13937e-7 1 -1.88309e-5 -5.13782e-7 0.2570858 -0.9147795 -0.3115853 7.75979e-6 1 1.09455e-5 -1.85183e-4 1 9.8128e-5 0 1 7.09662e-7 0 1 -2.98879e-7 0 1 -1.00155e-6 2.61636e-5 1 0 -1 5.34251e-7 0 -1 1.14108e-6 0 -1 -1.48358e-6 0 -0.9953162 0.09667277 3.32156e-4 -0.9938519 0.1107189 -8.74835e-6 -0.9564408 0.2919265 -2.64973e-4 -0.9442882 0.3291193 4.82949e-4 -0.8753359 0.4835152 -4.41924e-4 -0.8461895 0.532882 5.55476e-4 -0.7499316 0.6615152 -5.46581e-4 -0.7070015 0.7072119 5.18649e-4 -0.5326669 0.8463245 -9.26646e-4 -0.5787569 0.8154997 7.57585e-4 -0.3676887 0.9299489 -5.17529e-4 -0.1229472 0.9924028 0.004548311 -0.2225453 0.9749224 0 -0.6145356 0.6681406 0.4194452 -0.6699659 0.5685433 0.4773932 -0.6955999 0.5392723 0.4746854 -0.726719 0.4522794 0.5170328 -0.7579405 0.3955738 0.5186979 -0.7692406 0.3343254 0.544514 -0.7994202 0.218225 0.5597367 -0.7989186 0.2414311 0.5508541 -0.814423 0.1072092 0.5702821 -0.820191 0.08089405 0.5663416 -0.8172328 -0.002174139 0.5763037 -0.8202545 -0.08187985 0.5661081 -0.8137095 -0.111968 0.5703859 -0.8041676 -0.2206366 0.5519366 -0.7951281 -0.2425445 0.555827 -0.7677845 -0.339664 0.5432635 -0.7576175 -0.3967864 0.5182434 -0.7246111 -0.4570474 0.5157971 -0.6953606 -0.5403892 0.4737648 -0.6676818 -0.5720394 0.4764159 -0.614748 -0.6684996 0.4185611 -0.0668801 0.9965814 0.04850238 -0.2002549 0.9693779 0.1421428 -0.3273844 0.9157119 0.233005 -0.4010217 0.873254 0.2767834 -0.4474981 0.8370589 0.3147663 -0.4963673 0.7955765 0.347387 -0.5841711 0.7003335 0.4102159 -0.5565637 0.7355448 0.3862782 -0.5970784 0.6872137 0.4138053 -0.6456247 0.6139581 0.4541193 -0.6946043 0.5318456 0.4844226 -0.719582 0.4756093 0.5059621 -0.7552493 0.3899239 0.5268376 -0.5735784 8.76742e-7 -0.8191507 -0.596748 0.02602171 -0.8020067 -0.5698591 -0.0140872 -0.8216217 -0.5698394 0.01636141 -0.8215933 -0.5735771 0 -0.8191516 -0.5735771 5.23585e-7 -0.8191517 -0.5735672 -5.67146e-6 -0.8191586 -0.5735774 3.77233e-6 -0.8191514 -0.57358 -5.24715e-7 -0.8191497 -0.5735659 -4.41491e-6 -0.8191596 -0.5735852 -2.43034e-6 -0.819146 -0.5735686 1.42376e-6 -0.8191576 -0.5735719 5.24574e-6 -0.8191552 -0.5735785 -4.78774e-7 -0.8191507 -0.573571 -2.0405e-6 -0.8191559 -0.5735775 -2.06499e-6 -0.8191514 -0.5735899 1.08269e-5 -0.8191427 -0.5735756 0 -0.8191527 -0.5735778 -1.65241e-6 -0.8191511 -0.5735775 1.5844e-7 -0.8191514 -0.5735516 0 -0.8191695 -0.5736018 -1.0471e-6 -0.8191344 -0.5735957 -1.05184e-6 -0.8191387 -0.5735033 -2.32154e-7 -0.8192033 -0.4671649 -5.29395e-5 -0.8841702 -0.4782204 -4.52959e-6 -0.8782399 -0.5784782 -4.11403e-6 -0.8156979 -0.5784758 -4.05922e-6 -0.8156995 -0.573583 -5.92388e-7 -0.8191475 -0.5735934 1.14611e-6 -0.8191401 -0.5735886 1.04006e-6 -0.8191435 0.5451903 -0.001592993 0.838311 0.5814579 0.005036711 0.8135609 0.5735809 -4.22789e-6 0.8191491 0.5735707 -7.15342e-7 0.8191562 0.573575 -3.53788e-7 0.8191532 0.5735769 2.4586e-7 0.8191518 0.5730837 -6.01709e-4 0.8194968 0.576574 -6.03849e-4 0.8170447 0.5735765 -3.83947e-7 0.8191521 0.5735775 0 0.8191514 0.5735677 4.05024e-6 0.8191582 0.5735793 0 0.81915 0.5735747 0 0.8191533 0.5735728 -1.91475e-7 0.8191547 0.5735787 9.57364e-7 0.8191505 0.5640264 0.006244063 0.8257333 0.5721818 -0.001323938 0.8201258 0.5735749 7.65882e-7 0.8191531 0.5750188 -0.001310944 0.8181392 0.5745356 -0.001262247 0.8184786 0.5689357 -0.001260995 0.8223811 0.5756536 -0.001978397 0.8176913 0.5202558 -0.001649141 0.854009 -0.3737807 -0.8890925 0.264202 -0.3830876 -0.8839069 0.26824 -0.4659548 -0.8231451 0.3245278 -0.48598 -0.8035161 0.343781 -0.5489001 -0.7437035 0.3815938 -0.5791238 -0.7048527 0.409632 -0.6157022 -0.6607896 0.4292646 -0.65792 -0.5901657 0.4678095 -0.69672 -0.527899 0.4856994 -0.7249998 -0.4620863 0.5107363 -0.7377006 -0.4362507 0.5152506 -0.7706735 -0.3363095 0.5412563 -0.7731431 -0.3299044 0.5416761 -0.7964227 -0.2378594 0.5559983 -0.8117133 -0.1416932 0.5666078 -0.8013281 -0.1987029 0.5642609 -0.8151633 -0.08812069 0.5724889 -0.8136717 -0.09843355 0.5729305 0 -1 0 -8.20801e-6 -1 -1.41044e-4 6.22223e-4 -0.9999976 0.002142488 -5.3329e-4 -0.9999995 -8.69812e-4 -4.23781e-4 -0.9999998 -6.60052e-4 1.02974e-4 -1 1.2552e-4 0 -1 1.25367e-6 0 -1 0 0 -1 0 0 -1 6.58043e-7 2.4876e-5 -1 -2.07211e-5 5.7119e-6 -1 4.06404e-5 5.82966e-4 -0.9999997 4.64723e-4 8.29458e-5 -1 -1.86727e-4 -0.9958124 -0.09141999 -4.18046e-6 -0.9916259 -0.1291419 7.52288e-4 -0.9611123 -0.2761576 -4.79873e-4 -0.9242274 -0.3818414 9.40605e-4 -0.8923059 -0.4514312 -2.88271e-4 -0.7930088 -0.6092101 4.36203e-4 -0.7969281 -0.6040741 5.92197e-4 -0.6828801 -0.7305305 -3.0857e-4 -0.6089604 -0.7932002 8.8924e-4 -0.5533295 -0.8329625 -1.51997e-4 -0.3864821 -0.922297 2.46224e-4 -0.4080954 -0.9129389 8.44022e-4 -0.2498838 -0.9682758 -4.79412e-4 -0.08251857 -0.996589 0.001163482 -0.1263754 -0.9919826 0 -0.07920688 -0.9957805 0.04634213 -0.08133816 -0.9951571 0.0551964 -0.2231199 -0.961896 0.1580313 -0.3785265 -0.8859114 0.2681024 -0.2323501 -0.9560111 0.1790422 -0.07235914 -0.9958189 0.05575758 -0.07481259 -0.995135 0.06410485 -0.9113514 3.7257e-4 0.4116294 -0.632664 0.006780505 0.7743968 -0.4284642 -0.001967251 0.9035567 -0.177915 0.002121746 0.9840435 0.1312291 -0.006550073 0.9913305 0.3513884 0.001372754 0.9362289 -0.0370506 -0.009188771 0.9992712 -0.02604758 -0.01111447 0.9995989 -0.4297068 0.04045569 -0.9020619 -0.1441454 0.1977762 -0.969591 -0.6375281 -0.06058651 -0.7680412 -0.407925 0.05693882 -0.9112383 -0.5887272 -0.02189135 -0.8080353 -9.38921e-4 -0.9999993 -7.46211e-4 3.74548e-5 -1 -2.06066e-4 1.49649e-4 -1 -1.82447e-4 4.65845e-5 -1 -1.78874e-4 -0.8191179 0 0.5736253 -0.8191519 6.70928e-5 0.5735766 -0.8189911 0.01982569 0.5734637 -0.8174414 0.01111662 0.5759046 0.1307982 -0.1086906 0.985433 -0.4283635 -0.006013989 0.9035865 -1 2.35072e-6 0 -1 -1.94983e-6 0 -1 -3.31192e-7 0 -1 9.72851e-7 0 -1 1.16886e-6 0 -1 -2.28419e-7 0 -1 2.35815e-6 0 -1 -2.02953e-6 0 0 0.9965911 -0.08250045 0.06911551 0.9804314 -0.1843297 0.02892476 0.9690525 -0.2451544 0.0317645 0.9154687 -0.4011336 0.07992714 0.8824904 -0.4634895 0.008346259 0.8374336 -0.5464755 0.370607 0.8964493 -0.2429594 -1.88177e-4 0.9827821 -0.1847681 0.8780164 0.3767946 -0.2951492 -0.9946448 1.84568e-5 -0.1033527 -0.928736 -0.03123027 -0.3694241 -0.4240022 -0.002488791 -0.9056577 -0.4016724 -0.007183134 -0.9157553 -0.9476478 0.007473647 -0.3192304 -0.9291578 -0.003299117 -0.3696687 -0.4239902 0.005134165 -0.9056524 -0.3221305 0.1621391 -0.9327073 -0.9478265 0.0126487 -0.3185359 -0.9126432 0.1132107 -0.3927668 -0.4581097 0.3230206 -0.8281264 -0.3790973 0.4294723 -0.8196578 -0.9159575 0.2138344 -0.339554 -0.01607769 0.9635441 -0.2670662 -0.5356388 0.5537267 -0.6375561 -0.009805262 0.9999512 0.0012753 0.0913279 0.8551701 -0.5102385 0.5117732 0.8484937 -0.1347095 0.1016802 0.3071302 -0.94622 0.3689035 0.3944309 -0.8416261 0.2211357 0.6097297 -0.7611365 0.09709531 0.5856058 -0.8047599 0.288851 0.3260385 -0.9001467 0.5551017 0.8052276 -0.2084962 0.4777544 0.6929338 -0.5399941 0.6171602 0.4671947 -0.6331212 0.5836918 0.4221096 -0.6936335 0.6541031 0.4721949 -0.5909156 0.793572 0.493095 -0.3565121 0.6211355 0.7436337 -0.2473857 0.8989672 0.4319052 -0.07291066 0.06064045 0.008268475 -0.9981254 0.1898587 0.01736623 -0.9816579 0.3144187 0.06473422 -0.9470747 0.3685195 0.05476403 -0.9280055 0.6977545 0.08162385 -0.7116715 0.768581 0.1165354 -0.6290492 0.7837696 0.1100592 -0.611222 0.9246711 0.1036548 -0.3663867 0.9797675 0.135512 -0.1472829 0.9747995 0.1037114 -0.1975095 0.4188417 -0.004719018 -0.9080471 0.3152425 0.02584499 -0.9486592 0.7737935 -0.01777899 -0.6331884 0.9188041 0.01693844 -0.3943504 0.9798122 -0.007395327 -0.1997834 -0.003050327 0.2629845 -0.9647953 0.01788187 0.787659 -0.6158519 -0.00582534 0.9642863 -0.2647983 0.4269145 0.887957 -0.171104 0 1 -1.88224e-7 4.84643e-4 1 1.49723e-4 0.6559143 0.7316629 -0.1855962 0.4223842 0.8785119 -0.223178 0.9611114 0.2666363 -0.07190257 0.906399 0.3705635 -0.2027896 0.9952076 0.09552538 -0.02090531 0.6556635 0.7319176 -0.1854776 0.9672288 0.2342543 -0.0979461 0.5402349 0.7039797 -0.4610412 0.9612367 0.2306609 -0.1510621 0.9615778 0.2301017 -0.1497381 0.6400693 0.6627621 -0.3886616 0.336782 0.8162149 -0.4694373 0.4384584 0.7956957 -0.417879 0.9672638 0.1843381 -0.174414 0.2427804 0.7008506 -0.6707206 0.9625434 0.1663325 -0.2141118 0.9587322 0.1680014 -0.2293648 0.7290444 0.4199087 -0.5405284 0.2887509 0.5497648 -0.783825 0.3446028 0.5650439 -0.7496495 0.6871017 0.4172092 -0.5948343 0.2389392 0.4522023 -0.8593145 0.9669207 0.1112571 -0.2295352 0.9641485 0.0859763 -0.2510494 0.9549828 0.0792663 -0.2858758 0.7198964 0.2248793 -0.656642 0.6975048 0.2159202 -0.6832756 0.3005535 0.2873897 -0.9094366 0.3263987 0.2999854 -0.8963665 0.2370513 0.1561917 -0.9588592 0.9661811 0.02308201 -0.2568294 0.9595911 -1.60644e-4 -0.2813985 0.7082721 -4.0201e-4 -0.7059395 0.3103312 4.80773e-4 -0.9506284 6.5404e-4 0.08508783 -0.9963732 -0.006361961 0.2263588 -0.9740233 5.39896e-4 0.463678 -0.8860037 0.002649366 0.4166054 -0.9090837 0.003751516 0.6552975 -0.7553617 -0.01024723 0.7875786 -0.616129 1.73446e-4 1 3.12265e-4 -0.006393909 0.7361786 -0.6767572 0.005308091 0.7224562 -0.6913964 -0.005446672 0.6148737 -0.7886069 0.004332542 0.6019061 -0.7985552 -0.004440844 0.4768109 -0.8789948 0.003296315 0.4656894 -0.8849421 -0.003381669 0.3257777 -0.9454404 0.002203047 0.3173666 -0.9483004 -0.002267897 0.1658715 -0.9861448 0.001059412 0.1607745 -0.9869907 -0.001107633 0 -0.9999994 -0.00178337 0.00533092 -0.9999843 5.60904e-4 0.002031564 -0.9999978 -0.981355 -6.78631e-4 -0.1922031 -0.9547787 0.005409359 0.2972679 6.95189e-4 -0.005326747 -0.9999856 -1.64427e-4 0.01316916 -0.9999133 0.001481711 -0.004424214 -0.9999892 -1.31833e-5 1.70224e-4 -1 -1 -5.56023e-5 -1.01938e-4 -1 -1.63698e-5 -6.26694e-5 -1 1.91721e-7 0 -1 -1.9982e-7 0 -1 2.20573e-7 0 -1 2.29594e-7 0 -1 -3.66957e-7 0 -1 -5.90653e-7 0 0 1 3.07766e-5 -3.22887e-5 1 -8.761e-5 0.002125442 0.9999445 0.01032942 1 -1.49479e-6 0 1 1.49152e-6 0 0.9999997 -7.90194e-4 -5.36022e-4 0.9999995 5.91535e-4 -8.07801e-4 0.9999994 8.55641e-4 -8.08263e-4 0.9999992 0.001136243 -7.39887e-4 0.9999989 0.001393258 -5.81919e-4 0.9999988 0.001550436 -3.39324e-4 0.9999068 0.01260364 0.005259156 0.9999236 0.01036888 0.006735622 0.9999417 0.007849693 0.007413506 0.9999572 0.00547719 0.007458925 0.9999601 -0.007295846 0.005170047 -1 5.97977e-7 0 -1 -2.36604e-7 0 -1 0 0 0.9994336 -0.004753708 0.03331792 0.06021386 -0.9614261 -0.2683916 -0.03233987 -0.9988745 -0.03469848 0 -0.9965766 -0.08267515 0.07446533 -0.9666551 -0.245016 0.0858162 -0.9122486 -0.4005475 -0.006095767 -0.7352719 -0.6777449 0.004936575 -0.7224558 -0.6913995 -0.005070388 -0.6135423 -0.7896457 0.003815054 -0.6019042 -0.7985593 -0.003908514 -0.4750596 -0.879945 0.002688229 -0.465701 -0.8849381 -0.002764582 -0.3236512 -0.9461725 0.001474738 -0.3173598 -0.9483041 -0.001520395 -0.1633164 -0.9865726 1.69604e-4 -0.1607686 -0.9869922 -1.71931e-4 0.001393139 -0.9999991 0.3194919 -0.9396709 -0.1222442 0.209841 -0.9771463 -0.03394126 0.6593334 -0.7364569 -0.1513628 0.4536312 -0.8782142 -0.1515212 0.3850248 -0.8889108 -0.2481807 0.20208 -0.9608408 -0.1896013 0.7056624 -0.6878014 -0.1702053 0.9568101 -0.2851912 -0.05639654 0.9452171 -0.323097 -0.04661786 0.9672303 -0.2343196 -0.09777539 0.674718 -0.6893954 -0.2636089 0.7343981 -0.5682116 -0.3712075 0.9611237 -0.2315596 -0.150404 0.961441 -0.230235 -0.1504097 0.6770417 -0.5849289 -0.4466238 0.1695755 -0.8895326 -0.4242357 -0.0284757 -0.9336646 -0.3570148 0.3298851 -0.7504199 -0.5727529 0.2430607 -0.7007983 -0.6706738 0.967261 -0.1845206 -0.1742365 0.9633613 -0.1587324 -0.2161924 0.9604315 -0.1711154 -0.2197518 0.7297238 -0.4200769 -0.53948 0.2807964 -0.5776919 -0.7664369 0.323984 -0.5424765 -0.775083 0.6862874 -0.4170544 -0.5958821 0.239113 -0.4521934 -0.8592708 0.9669205 -0.1115496 -0.229394 0.9650139 -0.07041132 -0.2525678 0.9598044 -0.09123736 -0.2654268 0.7207739 -0.2253292 -0.655524 0.69656 -0.2155162 -0.6843661 0.2943922 -0.3032954 -0.906281 0.3181262 -0.2847676 -0.9042694 0.2370921 -0.1561846 -0.9588503 0.9661915 -0.02346968 -0.2567551 0.3096097 0 -0.9508638 0.7093663 3.56237e-4 -0.7048399 0.06717389 -0.8450867 -0.5303925 -0.008420288 -0.7120541 -0.7020742 -0.002616405 -0.2134634 -0.9769476 -0.1159188 -0.9922445 -0.04487502 -0.01912593 -0.9996887 -0.01602381 0.004272639 -0.9999896 -0.001626551 5.02594e-7 0 1 2.67644e-4 -0.9999973 -0.002327382 -0.001648843 -0.9999987 -6.06001e-5 0.007037043 -0.9999753 0 0 -0.9998682 0.01623815 -2.13303e-4 -0.9999998 7.11689e-4 -0.01884585 -0.9998186 0.002763986 0.06188428 -0.9980834 1.64161e-4 0 0 -1 -0.0257321 0.01376366 -0.9995742 1.18107e-4 -0.001168966 -0.9999993 -0.001138687 0.004077076 -0.9999911 1.72215e-4 1.32473e-4 -1 1.98768e-4 0 -1 0.99989 -0.001582205 0.0147497 1 -2.22881e-4 2.3199e-5 1 -1.46311e-4 -2.28958e-5 1 -9.7248e-5 -4.94865e-5 1 -6.44529e-5 -6.49377e-5 1 -3.87177e-5 -7.56603e-5 1 -1.31637e-5 -8.40488e-5 1 0 -8.75213e-5 0.3469863 0.001225888 0.9378695 0.4007259 0.009060919 0.9161533 0.8401724 -0.009489953 0.5422366 0.9262061 0.01501661 0.3767185 -0.002370595 -0.1991148 -0.9799734 -4.51705e-5 -0.1547338 -0.9879562 0.002064943 -0.4531015 -0.8914566 -0.001380801 -0.5453383 -0.8382149 0.003058671 -0.7072941 -0.7069129 -3.77845e-4 -0.8030017 -0.5959766 9.11265e-4 -0.8916413 -0.4527418 -4.06847e-4 -0.9075418 -0.4199615 0.002854824 -0.9879705 -0.1546159 0.2732821 -0.9515416 -0.1410167 0.4491711 -0.8881704 -0.09694778 0.6632948 -0.3869379 -0.6405615 0.4696519 -0.7935276 -0.3869642 0.7026602 -0.4497786 -0.5513329 0.44405 -0.770565 -0.457219 0.4102658 -0.3960631 -0.8214719 0.1931112 -0.7286277 -0.6571224 0.2827866 -0.4098832 -0.8671953 0.8776828 -0.1424724 -0.4575748 0.4447393 -0.03172421 -0.8950981 0.4111305 -0.002128958 -0.911574 0.874166 0.0112794 -0.4854962 0.8668503 0.007018983 -0.4985191 0.4439841 0.02422314 -0.8957073 0.1957102 -0.02095705 -0.9804379 0.1084851 -0.8972765 -0.4279323 0.007833182 -0.8368299 -0.5474071 0.2290927 -0.9608433 -0.155874 0.2715669 -0.9124261 -0.3061537 0.2563239 -0.9157137 -0.3094618 0 1 7.55274e-5 -0.004107058 0.9999384 -0.01030761 0.01770657 0.9997271 0.01523762 6.61101e-4 0.9999999 -1.04788e-4 -1 -9.24796e-7 0 -1 -6.37225e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 5.48251e-7 0 -1 -3.69006e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.35052e-7 0 -1 2.20279e-7 0 -1 -2.03432e-7 0 -1 3.51244e-7 0 -0.9999865 0.004831016 0.001937687 -0.9999998 -8.12147e-4 -4.55294e-5 -1 -8.35031e-5 0 1 3.24671e-5 -1.07969e-4 1 2.51967e-7 -4.2614e-5 1 0 0 1 0 0 1 1.77824e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -3.56076e-7 0 1 -2.73599e-7 0 1 0 0 1 0 0 1 3.78746e-7 0 1.23536e-5 -8.07357e-5 -1 4.05288e-4 7.36185e-5 -1 3.61392e-5 -6.36628e-5 -1 0 -0.9889355 -0.1483462 -0.07778793 -0.993562 -0.08236414 0.01710331 -0.9692338 -0.2455474 0.01202851 -0.9156532 -0.4017891 -0.09268277 -0.8334745 -0.5447295 -0.01339972 -0.8704398 -0.4920928 0.00603336 -0.735584 -0.6774068 -0.004918634 -0.7211901 -0.6927198 0.005062401 -0.6140138 -0.7892791 -0.003911674 -0.6007379 -0.7994365 0.004022598 -0.4756636 -0.8796181 -0.002827346 -0.4647267 -0.8854497 0.002913296 -0.3243296 -0.9459397 -0.001684546 -0.3166665 -0.9485355 0.001740455 -0.1641752 -0.9864296 -4.91779e-4 -0.1604045 -0.9870513 4.99934e-4 0 -0.9999999 7.62953e-4 4.39921e-4 -0.9999997 -7.37704e-4 0.1604154 -0.9870494 0.001959562 0.1649976 -0.986292 -0.001907765 0.3166675 -0.9485347 0.003094434 0.3250458 -0.9456933 -0.003009259 0.4647203 -0.8854525 0.004164159 0.4762236 -0.8793144 -0.004047513 0.6007375 -0.7994362 0.005167782 0.614421 -0.7889616 -0.00502187 0.7211962 -0.6927127 0.006109356 0.73587 -0.6770953 -0.0188232 0.8990198 -0.4375034 -0.1662803 0.8256093 -0.5391849 -0.07077836 0.9135302 -0.4005659 -0.07078123 0.9669888 -0.2447915 -0.05539655 0.9612935 -0.2699 0.02930742 0.9989862 -0.0341745 0 0.9965866 -0.08255422 -0.04440712 0.9985281 0.03113979 -0.1272888 0.9879079 0.08851873 -0.1919764 0.971996 0.1355324 -0.237507 0.9568552 0.1673877 -0.4085989 0.8679904 0.282205 -0.5896056 -0.7101616 0.3847541 -0.4204149 -0.8533859 0.3081947 -0.4159412 -0.86902 0.2679504 -0.2518877 -0.933171 0.2564067 -0.05191326 -0.9949969 0.08535987 -0.106732 -0.989756 0.09482264 -0.8520151 0.4021583 -0.3351702 -0.6970461 0.2062797 -0.6867136 -0.7521197 0.5012068 -0.427911 -0.7300593 0.5107627 -0.4540208 -0.7447735 0.6386939 -0.193346 -0.7245594 0.6334912 0.2714824 -0.7306236 0.6177512 0.2908141 -0.7661489 0.6351892 0.09772688 -0.8107617 0.5825802 -0.05714786 -0.7849943 0.5232927 0.3315855 -0.8829498 0.3022508 -0.3592272 -0.7564446 0.08608323 -0.6483683 -0.7207499 0.1159441 -0.6834301 -0.8846095 0.3006407 -0.3564846 -0.9079273 0.4174535 -0.03742659 -0.9261304 0.3767489 0.01851725 -0.8493233 0.3828601 0.3634119 -0.8432897 0.4291871 0.3235135 -0.8864958 0.2340625 0.3991742 -0.9158612 0.1479566 0.3732388 -0.9904037 0.1288712 0.04992645 -0.9887133 0.1463827 0.0319103 -0.9085034 0.07862299 0.4104143 -0.9429449 0.1044725 -0.3161339 -0.9426979 0.1050562 -0.3166764 -0.7551894 0.04330927 -0.6540744 -0.9332692 -0.07755625 0.3507046 -0.9015106 -0.1477999 0.4067358 -0.9905307 -0.1277857 0.05019873 -0.8863739 -0.2341295 0.3994054 -0.9430931 -0.1040601 -0.3158275 -0.9888131 -0.1457326 0.03179198 -0.7553091 -0.04352122 -0.6539222 -0.9425181 -0.1054197 -0.3170906 -0.7440542 -0.06877928 -0.6645697 -0.9265168 -0.3757778 0.01891422 -0.8689177 -0.3788201 0.3185551 -0.8324289 -0.4305317 0.3488621 -0.7848837 -0.523364 0.3317344 -0.8852242 -0.4557114 -0.09330278 -0.8617193 -0.353088 -0.3643745 -0.7489871 -0.1418223 -0.6472285 -0.8933722 -0.3237349 -0.3115798 -0.7159297 -0.6467757 0.2629181 -0.8209927 -0.5617519 -0.1020096 -0.7608877 -0.6279163 -0.1636193 -0.8089194 -0.4513398 -0.376752 -0.7703467 -0.466975 -0.4341664 -0.7113638 -0.2204344 -0.6673607 -0.8217526 -0.4064046 -0.3994472 -0.996408 0.01263606 -0.08373463 -0.9944046 0.01900696 -0.1039152 -0.9990923 0.0227127 -0.03603744 -0.9990969 0.01164025 -0.04086524 -0.9894008 0.009796202 -0.14488 -0.9947921 0.02021545 -0.09990125 -0.994392 0.04069286 -0.09761393 -0.9594226 0.02106994 -0.281184 -0.9828487 0.1044596 -0.1519761 -0.9822808 0.06087076 -0.1772548 -0.9700506 0.08807164 -0.226374 -0.9707147 0.02645146 -0.2387748 -0.9412925 0.032148 -0.336058 -0.9258497 0.2543582 -0.2794716 -0.9481039 0.03658169 -0.3158493 -0.9471427 0.112491 -0.3004437 -0.9443778 0.1134435 -0.3086766 -0.9444873 0.2107847 -0.2520193 -0.9023398 0.03338575 -0.4297305 -0.9011236 0.1544615 -0.4051148 -0.9579957 0.2267187 -0.1756215 -0.8543987 0.05021345 -0.5171864 -0.8876013 0.1591364 -0.4322496 -0.8875283 0.2983527 -0.3511117 -0.8868735 0.3987759 -0.2333096 -0.8862825 0.2994717 -0.353299 -0.8607461 0.178979 -0.4765319 -0.8628278 0.05416858 -0.5025873 -0.8733256 0.4180631 -0.2500514 -0.7855427 0.5851048 -0.2014327 -0.844719 0.3467761 -0.4076718 -0.8446934 0.1833282 -0.5028755 -0.8424605 0.3483155 -0.411019 -0.842624 0.4686614 -0.2652198 -0.8769377 0.4692035 -0.1040596 -0.7962025 0.04933249 -0.6030158 -0.7939663 0.2149806 -0.5686836 -0.808227 0.5111253 -0.2924381 -0.8082408 0.5803766 -0.09954875 -0.7506155 0.06643128 -0.6573913 -0.7634159 0.216939 -0.6083862 -0.7638848 0.4178681 -0.4917992 -0.8204135 0.3880577 -0.4199202 -0.7766782 0.5528714 -0.3018349 -0.7155137 0.6889013 0.1159964 -0.6725213 0.7364091 0.07359898 -0.6812868 0.7182169 -0.1414673 -0.8020722 0.07690471 -0.5922549 -0.8019977 0.1995236 -0.5630187 -0.7122604 0.1981002 -0.6733806 -0.7527995 0.4451657 -0.4848922 -0.7656361 0.564467 -0.3085103 -0.8179031 0.5551504 -0.1511383 -0.6993778 0.6522798 0.292236 -0.9092215 -0.3766141 -0.1774204 -0.9913836 -0.1305001 -0.01132696 -0.949055 -0.3044831 -0.08114677 -0.9649092 -0.2586047 -0.04554009 -0.5966526 -0.777577 -0.1984434 -0.7891349 -0.6048989 -0.1065998 -0.9657943 -0.235155 -0.1092869 -0.9490864 -0.2582734 -0.1803608 -0.9649135 -0.2273905 -0.1312841 -0.3877626 -0.8024071 -0.4536331 -0.2385865 -0.7003713 -0.6727232 -0.9657933 -0.1835868 -0.1831372 -0.7385994 -0.4333303 -0.516426 -0.9490706 -0.1810172 -0.2578715 -0.9649195 -0.1687619 -0.201121 -0.3305865 -0.566967 -0.7544939 -0.3050023 -0.5594328 -0.7707197 -0.6805779 -0.4303903 -0.5929401 -0.2377073 -0.4514084 -0.8600731 -0.9657891 -0.1098628 -0.2349078 -0.9490526 -0.08189117 -0.3042908 -0.9649252 -0.0897904 -0.2466925 -0.7275053 -0.2346612 -0.6447249 -0.322265 -0.2997724 -0.897932 -0.3098672 -0.2936034 -0.9043115 -0.6946948 -0.2221216 -0.68415 -0.2372568 -0.1558241 -0.9588681 -0.9657868 -0.0228762 -0.2583266 -0.3142737 0 -0.9493324 -0.31426 8.74341e-6 -0.949337 -0.9490262 0.02717965 -0.3140232 -0.9649398 0 -0.2624714 -0.7117421 5.30173e-6 -0.7024409 -0.7117519 0 -0.702431 -0.2372613 0.1558347 -0.9588653 -0.9657777 0.06694763 -0.2505825 -0.3066231 0.3014162 -0.9028459 -0.3182151 0.2927598 -0.9016822 -0.694701 0.2221306 -0.6841408 -0.9489522 0.1331467 -0.2859402 -0.9649646 0.08974051 -0.2465564 -0.7275002 0.2346638 -0.6447297 -0.2376979 0.4514032 -0.8600785 -0.9657641 0.1487216 -0.2125602 -0.6805854 0.4303969 -0.5929267 -0.2993382 0.5731975 -0.7627853 -0.3217291 0.5562056 -0.7662413 -0.7385926 0.4333356 -0.5164313 -0.9488759 0.2231664 -0.2232298 -0.964989 0.1685978 -0.2009255 -0.2385854 0.7003773 -0.6727173 -0.9657475 0.2125681 -0.148817 -0.2939365 0.8594491 -0.4182687 -0.3936309 0.8054496 -0.4430642 -0.615529 0.6905264 -0.3798651 -0.9588282 0.2459397 -0.1419935 -0.5820078 0.7042377 -0.4065909 -0.9657585 0.2351608 -0.1095905 -0.9657359 0.2507134 -0.06705999 -0.9487726 0.3147652 -0.0274471 -0.9896426 0.1114978 -0.09042066 -0.9374392 0.3416635 -0.06688767 -0.5873391 0.8006835 -0.1180628 -0.8226501 0.5219266 -0.2254763 -0.6924756 0.6924636 -0.2024151 -0.5147524 0.831374 -0.2093971 -0.3524112 0.9010128 -0.2529473 -0.3123171 0.9193571 -0.2392503 -0.3528842 0.9005162 -0.254054 -0.1119046 0.9931381 -0.03397244 -0.1119699 0.9937116 -1.78406e-4 -0.1946955 0.9808569 0.003682971 -0.3651767 0.9309352 -0.00240159 -0.5260813 0.8504334 0.001280069 -0.4889855 0.872291 -0.00127381 -0.7143178 0.6998209 9.17657e-4 -0.707122 0.7070901 0.001479625 -0.8595867 0.5109899 -5.67055e-4 -0.8447405 0.5351755 9.53597e-4 -0.9587785 0.2841482 -0.001939833 -0.9394835 0.3425897 0.001776456 -0.9954783 0.09498715 -7.97928e-4 -0.9937124 0.1119639 0 -0.7133834 0.6985089 -0.05629914 -0.5625953 0.8205677 -0.1007737 -0.8549636 0.508279 -0.1033917 -0.8415546 0.5292949 -0.1078557 -0.9490778 0.2814462 -0.1415614 -0.9878228 0.09500938 -0.1232047 -0.406057 0.9138467 0.001397609 -0.3324879 0.943072 -0.008196532 -0.2558831 0.9652795 -0.05252945 -0.7110176 0.6436711 0.283093 -0.5436429 0.7803342 0.3090808 -0.3353622 0.9420609 0.007323265 -0.6103575 0.7843998 0.1103666 -0.6920753 0.7032364 0.1627585 -0.5170993 0.8547837 -0.04419523 -0.5763878 0.8033123 0.1498892 -0.6578716 0.749139 0.07743287 -0.6678611 0.7414907 0.06444466 -0.6164978 0.7814478 -0.09627938 -0.5726468 0.8176057 -0.05997097 -0.8166515 0.5724842 -0.07309085 -0.8004091 0.5814624 -0.1457626 -0.8559814 0.4787226 -0.1952455 -0.8365836 0.5312302 -0.1338753 0.9487577 -1.5082e-4 -0.3160046 0.9326866 0.001193046 -0.360686 0.4537588 -0.00118494 -0.8911238 0.4353505 -4.55056e-4 -0.900261 -7.93739e-5 -1 2.98774e-5 -3.86575e-5 -1 8.15107e-5 0 -1 1.77169e-7 -1.47704e-4 -1 -3.08984e-5 -0.9964498 -0.01178532 -0.08336162 -0.9983762 -0.02492457 -0.05122333 -0.998402 -0.01889759 -0.05325752 -0.9983075 -0.02478682 -0.05261021 -0.9960803 -0.03421962 -0.08156597 -0.9962339 -0.01169383 -0.0859152 -0.9892727 -0.01950609 -0.144772 -0.9822662 -0.01710367 -0.1867101 -0.9819517 -0.06726473 -0.1767666 -0.9591674 -0.03072613 -0.2811654 -0.9905112 -0.07150346 -0.1173669 -0.9788526 -0.1252843 -0.161714 -0.9785422 -0.06961661 -0.1939297 -0.9627919 -0.1621823 -0.2161684 -0.9592568 -0.1722732 -0.2239382 -0.9586429 -0.0961523 -0.267878 -0.9413122 -0.03120034 -0.3360924 -0.9472403 -0.03591889 -0.3185055 -0.9460272 -0.1175846 -0.302004 -0.9425165 -0.2767438 -0.187285 -0.9054799 -0.1446663 -0.3989711 -0.9062985 -0.2631977 -0.3306813 -0.9178807 -0.2522543 -0.3063708 -0.9216434 -0.3316446 -0.201458 -0.8855422 -0.1666429 -0.4336419 -0.8871166 -0.0363301 -0.4601134 -0.8538761 -0.05461061 -0.5176036 -0.9337716 -0.3099125 -0.1789554 -0.8434594 -0.3523581 -0.4054874 -0.8440992 -0.18374 -0.5037223 -0.7847732 -0.552006 -0.2818163 -0.8232899 -0.04665136 -0.5657009 -0.8211603 -0.2026797 -0.5334947 -0.8080378 -0.5168795 -0.2826845 -0.8082885 -0.3758358 -0.4532298 -0.750651 -0.06076163 -0.6578992 -0.8160256 -0.5458183 -0.1902227 -0.7501133 -0.22158 -0.6230831 -0.7450543 -0.437609 -0.5033811 -0.7673738 -0.210667 -0.6056045 -0.7670268 -0.06712132 -0.6380947 -0.784841 -0.5459694 -0.2931591 -0.8126369 -0.3939298 -0.4294656 -0.6989669 -0.6212382 -0.3542716 -0.7312147 -0.6573439 -0.182275 -0.684179 -0.5085508 -0.5227574 -0.7260631 -0.215768 -0.6528986 -0.7226821 -0.678829 0.130084 -0.7277319 -0.5936058 -0.3435674 -0.264388 -0.95913 0.1008402 -0.4320181 -0.8969509 -0.09401935 -0.6050702 -0.7832266 0.142991 -0.3751323 -0.9266769 0.02336347 -0.4584776 -0.8885427 -0.01703929 -0.6055442 -0.7930687 -0.0660187 -0.6529601 -0.7511695 0.09688997 -0.6542546 -0.7504227 0.09389841 -0.7925587 -0.5891061 -0.1574957 -0.6224873 -0.7787278 -0.07805567 -0.7948885 -0.5878264 -0.1503739 -0.8105062 -0.5620998 -0.1646923 -0.8098721 -0.5634237 -0.1632822 -0.8986511 -0.3922554 -0.1963718 -0.1193391 -0.9927923 -0.01103776 -0.0144087 -0.9994608 -0.02950733 -0.001143455 -0.9999994 -2.23502e-4 -0.3521888 -0.9358712 -0.01041001 -0.131658 -0.9912229 -0.01197606 -0.2374448 -0.9700775 -0.05069363 -0.2377125 -0.9700925 -0.04912614 -0.2733497 -0.9605963 -0.05034786 -0.4170451 -0.9047861 -0.08623045 -0.424819 -0.9044398 -0.03895831 -0.4455932 -0.8913614 -0.08319658 -0.5952562 -0.8006581 -0.06794643 -0.5963745 -0.799857 -0.06757283 -0.5880718 -0.8001113 -0.118294 -0.6166662 -0.7797056 -0.1085458 -0.8064756 -0.5864192 -0.07556146 -0.8082581 -0.5840689 -0.07471626 -0.7971332 -0.5849951 -0.1495316 -0.9189757 -0.3791266 -0.1083826 -0.8150715 -0.5633074 -0.1354375 -0.9674891 -0.2398635 -0.08019047 -0.9115318 -0.37763 -0.1628052 -0.9430137 -0.2613941 -0.205909 -0.9927644 -0.04472106 -0.11144 -0.989093 -0.1273361 -0.07403099 -0.929939 -0.2990087 -0.2140266 -0.1305209 -0.9914456 -1.69666e-7 -0.1192955 -0.9928587 -6.1726e-4 -0.3826858 -0.9238786 -4.11445e-4 -0.3522574 -0.9359026 0.001012384 -0.6087589 -0.7933542 0.001346826 -0.5964696 -0.8026325 0.002293169 -0.8090472 -0.5877434 -6.7648e-4 -0.7936529 -0.6083704 8.1415e-4 -0.9243702 -0.3814969 -7.03132e-5 -0.9238858 -0.3826682 -2.55012e-7 -0.9916467 -0.1289845 0 -0.9914461 -0.1305168 8.3577e-5 -0.1291008 -0.9806596 -0.1471053 -0.3755054 -0.9065418 -0.1928151 -0.4680989 -0.8530529 -0.2306171 -0.4515169 -0.7878483 -0.4188406 -0.5465849 -0.7252127 -0.4187024 -0.6082782 -0.7008405 -0.372586 -0.5721026 -0.7917593 -0.2140467 -0.4746628 0.8510899 0.2243682 -0.4577124 0.8535903 0.2487632 -0.3598774 0.9262133 0.1123266 -0.5492996 0.8211207 0.1550191 -0.4882165 0.870643 -0.06021147 -0.194683 0.9808581 -0.004012584 -0.2049255 0.9787381 -0.008794546 -0.2408218 0.9699551 -0.03452485 -0.2553867 0.9652409 -0.05556869 -0.9999711 0.007605195 1.21785e-4 -0.9999952 -0.002997696 8.54734e-4 -0.9999939 -0.003353118 9.78871e-4 -0.9999994 0 -0.001186072 -0.8862363 -0.4370459 -0.1535461 -0.8596947 -0.4913477 -0.1396511 -0.7213765 -0.640836 0.2625741 -0.687279 -0.6679332 0.2855045 -0.5379254 -0.8254376 0.1711407 -0.089634 -0.9955468 0.02919554 -0.09554094 -0.9951177 0.02475494 -0.1069311 -0.9932101 0.04582095 -0.1259351 -0.9920355 0.002433717 -0.1173849 -0.9810523 -0.1541333 -0.9991533 -0.04114508 1.00893e-4 -0.04763281 -0.9988645 -8.5677e-4 1 -3.01314e-5 1.96228e-4 1 1.99712e-4 -5.40625e-5 1 0 -2.22524e-6 0.2393013 0.01659196 -0.9708037 0.340554 0.004552781 -0.940214 0.4647546 0.001059055 -0.8854389 0.6631556 -0.002519607 -0.7484775 0.8229896 0.006064116 -0.5680243 0.9347048 0.02630251 -0.3544504 0.9927123 0 -0.1205085 0.9927189 -2.88792e-5 -0.1204546 0.9040649 0.01585537 -0.4271011 3.95195e-5 -0.9999998 -6.03869e-4 -2.46076e-5 -1 1.03468e-4 -2.52e-5 -1 2.31361e-4 4.41908e-7 -1 -4.49938e-6 1.29983e-7 -1 -2.30838e-6 3.28781e-7 -1 6.8647e-7 0 -1 -6.07353e-7 1.03811e-5 -1 -8.06934e-5 0 -1 -2.9669e-7 1.10848e-5 -1 1.22027e-5 -0.947209 -0.01689749 -0.3201715 -0.1633957 -0.02333933 -0.9862846 -0.4521208 -2.54416e-4 -0.8919568 -0.9946249 -0.00928992 -0.1031258 -0.1635607 -0.01427954 -0.9864299 0 -1 0 0 -1 0 0 -1 0 0 -0.9701426 0.2425356 0.815125 -0.05270439 0.5768826 0.8986712 0 -0.438623 0.9044824 -0.006862699 -0.426456 0.9393242 0.004310369 -0.3430036 0.9545444 -0.009238779 -0.2979258 0.9694658 0.004599153 -0.2451834 0.9866577 -9.10171e-4 -0.1628062 0.9898295 -0.009415447 -0.141947 -0.02275341 0.02489012 -0.9994313 0.1193639 -0.02614277 -0.9925064 0.2252363 0.01381814 -0.9742063 0.3575754 -0.009148716 -0.9338395 0.4524347 0.01231402 -0.8917125 0.5349345 -0.006917893 -0.8448653 0.6521134 0.008543729 -0.7580733 0.6912466 -0.003481268 -0.7226107 0.8106769 0.004049777 -0.5854799 0.8202673 0 -0.5719806 -0.09965127 -0.001815855 -0.9950208 -0.06235259 -0.9957591 0.06764686 -0.2023846 -0.9591159 0.1978318 -0.06164848 -0.9959497 0.06545031 -0.3453996 -0.8805637 0.32451 -0.3388894 -0.890093 0.3047761 -0.1991704 -0.9617902 0.1878585 -0.3668327 -0.8914704 0.2659214 0.636735 -0.6006257 0.4835467 0.2391135 -0.8473774 0.474106 -0.2736889 -0.8272328 0.4906939 0.08862429 -0.9032942 0.4197685 0.6647042 -0.6040238 0.4396858 0.6847661 -0.5922917 0.4246011 0.6514908 -0.6602333 0.3737001 0.1170858 -0.9446147 0.3065844 0.2397288 -0.9332714 0.2674601 0.6956524 -0.6429955 0.3203508 0.687515 -0.6494031 0.3249595 0.6645329 -0.6935549 0.2781682 0.7263695 -0.6447274 0.2381473 0.6908797 -0.6795063 0.2468938 0.2417125 -0.9505735 0.194898 0.3729038 -0.9153248 0.1520641 0.4021362 -0.9113624 0.0877785 0.3472985 -0.9325497 0.09866535 0.3556221 -0.9313089 0.07871842 0.3150433 -0.948167 0.04155969 0.1168699 -0.9930276 0.0154156 0.4402564 -0.8978334 -0.00833708 0.3215475 -0.9466273 0.02245247 -0.649764 0.09072822 -0.7547021 -0.5724436 0.08332246 -0.8156996 -0.5177595 0.03186547 -0.8549327 -0.6212203 0.09206414 -0.7782092 -0.5780669 0.1097511 -0.808575 -0.4363008 0.08042341 -0.8961996 -0.4955585 0.2551012 -0.8302682 -0.1986351 0.162071 -0.9665801 -0.2292833 0.1702266 -0.9583591 -0.2924733 0.3886293 -0.8737429 -0.2980372 0.3872548 -0.8724721 -0.01434177 0.1772686 -0.984058 -0.1274458 0.5253184 -0.8413075 0.03705573 0.591821 -0.8052173 0.08401024 0.594484 -0.7997068 0.1842444 0.2372649 -0.9538131 0.2028936 0.2333935 -0.9509793 0.4125478 0.2407467 -0.8785473 0.2440397 0.6798533 -0.691552 0.4809156 0.4938198 -0.7244738 0.3262248 0.6498309 -0.6865109 0.02677047 0.7169066 -0.696655 0.4363033 0.6820588 -0.5868861 0.549539 0.2822183 -0.7863587 0.6172931 0.1049016 -0.7797084 0.3379444 0.285219 -0.896908 -0.08532345 0.3475857 -0.933758 -0.6238679 0 -0.7815298 -0.6234945 -3.99086e-5 -0.7818278 -0.4377225 3.64117e-5 -0.8991103 -0.4338716 -3.05726e-4 -0.9009746 -0.2326864 2.96529e-4 -0.9725518 -0.2225331 -5.20208e-4 -0.9749251 -0.01456749 5.14326e-4 -0.9998938 0 -6.11776e-4 -0.9999998 0.2086611 6.24165e-4 -0.9779879 0.2225221 -4.92212e-4 -0.9749276 0.4250475 5.04517e-4 -0.905171 0.4338808 -2.83749e-4 -0.9009703 0.6207233 2.93722e-4 -0.7840299 0.623473 0 -0.7818449 -0.7070778 0 -0.7071359 -0.707079 -2.35906e-6 -0.7071346 -0.7104153 -0.00923711 -0.7037222 -0.7046052 0.01245737 -0.7094902 -0.661574 0.1000357 -0.7431775 -0.4219263 -0.8521161 0.3096395 -0.4038802 -0.8363662 0.3706381 -0.4013476 -0.8437567 0.3563635 -0.2014473 -0.84829 0.4897173 0.1538095 -0.757456 0.6345101 0.4889825 -0.4556807 0.7438086 0.7088915 -0.1785257 0.6823499 -0.1675468 -0.8655346 0.4719939 -0.2499654 -0.8760294 0.4124197 -0.1294784 -0.8392081 0.5281714 -0.2039812 -0.8563758 0.4743547 0.1536067 -0.7572695 0.6347818 0.3293162 -0.6767236 0.6584802 0.491304 -0.4580534 0.7408155 0.354331 -0.709137 0.609569 0.220324 -0.8119357 0.5405718 0.5934155 -0.5175992 0.6164002 0.7374612 -0.209017 0.6422328 0.8160329 -0.3085777 0.4887436 0.7259456 -0.3590474 0.5865902 0.7405961 -0.2001601 0.6414464 0.1168556 -0.9931485 -0.001008868 0.1501712 -0.9882257 -0.0293008 0.1360949 -0.988255 -0.06950169 0.1833649 -0.9819478 -0.04643225 0.1919435 -0.9812871 0.01527905 0.1068691 -0.9921252 -0.06532013 0.4402417 -0.8977922 -0.01251453 0.1109331 -0.9889203 -0.09864336 0.1121163 -0.9886544 -0.0999614 0.1090295 -0.9886416 -0.1034424 0.2499032 -0.9296916 -0.2705954 0.1828768 -0.9455833 -0.2691254 0.2156059 -0.9133102 -0.3455122 0.1611708 -0.9472076 -0.2771676 0.1785748 -0.9074363 -0.380356 0.03253912 -0.9983173 -0.04799997 0.04872357 -0.9940711 -0.09720379 0.04951423 -0.9920257 -0.115903 0.1734674 -0.8360562 -0.5204991 0.1712641 -0.8500947 -0.4980036 0.1757156 -0.9089293 -0.3781159 0.04759436 -0.9923745 -0.1136998 0.05362218 -0.9869092 -0.1521018 0.253569 -0.9447026 -0.2079415 0.2840487 -0.8643482 -0.4149925 0.2602985 -0.8956975 -0.3605148 0.2666859 -0.8230801 -0.5014158 0.2478 -0.7843751 -0.5686395 -6.56949e-5 -0.9999994 -0.001131415 -2.05054e-4 -0.9999998 6.86732e-4 -2.0504e-4 -0.9999998 6.86062e-4 -1.68216e-5 -1 1.06803e-5 -2.07044e-4 -0.9999999 5.55598e-4 2.25611e-4 -0.9999998 -6.05423e-4 -2.95175e-5 -1 4.35961e-5 -1.22186e-5 -1 2.78497e-6 0 -1 4.036e-7 -4.91502e-5 -1 4.56323e-4 0 -1 4.41363e-6 0.3525553 -0.8555891 -0.3790411 0.3116161 -0.8804436 -0.3573716 0.3061493 -0.910061 -0.2793951 0.3423857 -0.9190624 -0.1951834 0.2929202 -0.9164159 -0.2727267 0.2386974 -0.9456217 -0.2209595 0.2381839 -0.9469295 -0.2158546 0.2469198 -0.9477921 -0.2017945 0.2470577 -0.94852 -0.1981722 0.2674833 -0.9185493 -0.2910668 0.2569962 -0.9456889 -0.1990618 0.2777743 -0.9156069 -0.2906985 0.3134286 -0.86365 -0.3948054 0.256459 -0.9482637 -0.187149 0.2863978 -0.9431062 -0.1688995 0.2216923 -0.9559361 -0.1924548 0.3077291 -0.8655282 -0.3951758 0.3023807 -0.9104925 -0.2820807 0.2564381 -0.9490117 -0.1833474 0.2560515 -0.8881105 -0.3817031 0.2650578 -0.9465113 -0.1840127 0.2565774 -0.9478963 -0.1888403 0.25937 -0.9140505 -0.3118314 0.2356683 -0.9201387 -0.3127386 0.2905758 -0.9386476 -0.185759 0.228971 -0.8909945 -0.3920472 0.2026887 -0.8984285 -0.3895427 0.3008745 -0.9391363 -0.1658239 0.260475 -0.9274561 -0.2682876 0.3878899 -0.8987562 -0.2043988 0.3247321 -0.8801459 -0.3462547 0.3460811 -0.925378 -0.1546077 0.2665843 -0.8656461 -0.4237803 0.2790189 -0.8544856 -0.4381812 0.4687653 -0.8755775 -0.1167182 0.4902011 -0.8681079 -0.07804828 0.4814864 -0.8716093 -0.09202271 0.4902051 -0.8678818 -0.0805 0.4474827 -0.8914318 -0.07147413 0.5005629 -0.8656901 -0.004194021 0.4995087 -0.8662844 -0.00653398 0.6005955 -0.7889509 -0.1297753 0.5074489 -0.8594309 -0.0622428 0.7013735 -0.7049167 0.1056779 0.6956553 -0.7094041 0.1131802 0.6289874 -0.762393 -0.1520922 0.664568 -0.7442901 -0.06619393 0.5952162 -0.7993766 0.08194464 0.6265507 -0.761123 0.1677084 0.6269951 -0.7671248 0.135635 0.691171 -0.7164412 0.0948401 0.7182928 -0.6952803 0.0253154 0.7580253 -0.6227501 0.1938552 0.7604596 -0.5803706 0.2913271 0.7575163 -0.5975437 0.2628894 0.7544999 -0.6070907 0.2493409 0.7991358 -0.5859143 0.1344864 0.790567 -0.6058165 0.08938848 0.8215386 -0.5405208 0.1814157 0.8207837 -0.4692702 0.3257293 0.835345 -0.3997552 0.3773519 0.8150735 -0.3789454 0.4382415 0.8246665 -0.4032723 0.3966066 0.8262979 -0.4337514 0.3592935 0.8732556 -0.3672801 0.3202035 0.8743069 -0.4323125 0.2206662 0.8756905 -0.4198485 0.2385237 0.8797497 -0.372007 0.2960597 0.8811836 -0.3304143 0.3381449 0.8816385 -0.2787825 0.3807807 0.8599933 -0.2211823 0.4598806 0.8817104 -0.2316821 0.4109869 0.8767298 -0.1035447 0.4697057 0.7611622 -0.1840569 0.6218965 0.830002 -0.1669018 0.5322036 0.8491138 0.0220589 0.5277491 8.00675e-4 0.9999955 -0.002914607 1.9192e-4 -1 -4.49039e-7 0.04146784 -0.9978154 -0.05142813 -0.007111132 -0.9999207 0.01039898 0.003337204 -0.9999825 -0.00488013 -8.85215e-4 -0.9999996 2.76288e-4 -9.95798e-4 -0.9999994 4.69509e-4 -0.001082301 -0.9999991 7.54711e-4 -0.001183986 -0.9999986 0.00123775 -0.001281738 -0.9999972 0.002024412 -0.002108991 -0.9999896 0.004053294 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.001348614 -0.999993 0.003522038 0.002055346 -0.9910548 0.1334401 0.2772106 -0.546256 0.7904167 -0.1166644 0.03638851 0.9925045 -0.604407 0.2074012 0.7692055 -0.7454774 -0.1872649 0.6396838 -0.4285294 -0.1607231 0.8891179 0.9962196 0.04058206 -0.0768094 0.9986143 0.03368157 -0.04043662 -0.2765302 -0.5929502 0.756268 -0.2212674 -0.610017 0.7608678 0.8892003 -0.2822961 0.3600443 0.119928 0.9925268 0.02254009 -0.5501428 -0.6272999 0.5512149 0.8536086 0.2230147 0.470762 0.7894388 0.3703002 0.4895551 0.1710877 -0.9322435 0.3188278 0.1746862 -0.9329741 0.3147128 0.2767142 0.9606179 0.02535039 0.2631711 0.9632378 0.05398029 0.2677219 0.9606288 0.07427906 0.2457112 0.962623 0.1139428 0.2470989 0.9609029 0.1249308 0.4025743 -0.8445901 0.3529898 0.3081626 -0.8786294 0.364755 0.7923493 -0.4863711 0.3682739 0.7305902 -0.558321 0.3930849 0.9395609 -0.1465769 0.3094196 0.9284021 0.2902551 0.2319945 0.9281854 0.2916861 0.2310658 0.4500841 -0.6295917 0.6332762 0.5276674 -0.5684834 0.6311845 0.5146169 -0.5832913 0.6284432 0.6990584 0.2892754 0.6539397 0.6960245 0.2585659 0.6698459 0.7332835 0.3930097 0.5548322 0.5154362 -0.6393492 0.570577 0.7147649 -0.4432713 0.5409453 0.5036952 -0.691275 0.5181024 0.6268921 -0.5820151 0.5179428 0.5468419 -0.6432567 0.5358963 0.8545953 0.2361623 0.4624871 0.8735178 0.3251657 0.3622626 0.7715947 0.6347539 0.04158365 0.1448652 -0.9397484 0.3096566 0.1440281 -0.9399671 0.3093829 0.1438862 -0.9399999 0.3093492 0.1437261 -0.9400291 0.3093352 0.1435278 -0.9400614 0.309329 0.1433923 -0.9400712 0.3093619 0.1033968 -0.9394602 0.3266857 0.4052397 0.8371928 0.3672726 0.4044088 0.8537462 0.3279804 0.4530766 0.8312925 0.321985 0.4888494 0.8366226 0.2471617 0.4901289 0.8324376 0.2584983 0.5333691 0.8204042 0.2060449 0.5503007 0.8208852 0.1526988 0.5477446 0.8253548 0.1369865 0.5793759 0.8099972 0.0907095 0.5819862 0.8114492 0.05331397 0.5820849 0.811389 0.05315369 0.638897 0.7680466 -0.04376387 0.5823409 0.811749 0.04407769 -0.6297558 -0.6157594 0.4735484 -0.6271258 -0.6118091 0.482082 -0.6740891 -0.630357 0.3850376 -0.723318 -0.6162527 0.3115186 -0.7775484 -0.5790691 0.2451478 -0.6944273 -0.6441287 0.3207319 1 -1.13442e-5 0 1 5.63126e-6 0 0.101216 0.9936187 0.04977393 0.2418761 0.9669432 -0.08072793 0.3517692 0.8901457 -0.2896535 0.31959 0.943414 -0.08850127 0.3643687 0.931235 0.006072521 0.4288782 0.9010828 -0.0641359 0.3415879 0.9306011 -0.1315277 0.3586279 0.9302865 -0.07715725 0.449767 0.8931323 0.004947423 0.4393381 0.89793 0.02652996 0.5673802 0.8141534 -0.1234261 0.5424739 0.8392261 -0.03770589 0.1955621 -0.8704785 0.4516888 0.274533 -0.7721518 0.5730736 0.3052313 -0.6570793 0.689261 0.9903775 0.1327829 -0.03900474 0.9073784 0.411969 0.08334356 0.9104006 0.3720211 0.1810277 0.8286084 0.5490634 -0.1092587 0.7531545 0.6424612 -0.1414283 0.784201 0.6195023 -0.03529936 0.8274941 -0.507332 0.2405576 0.754019 -0.4613307 0.4675784 -0.2270602 -0.8699226 0.4378109 0.85823 -0.4431261 0.2589995 0.9197178 -0.361854 0.1522533 0.8714846 -0.4373522 0.2218957 0.8436255 -0.50055 0.1942832 -0.2034449 -0.8764452 0.4364104 0.2774363 0.9607213 0.006606578 0.22382 0.973071 -0.05511474 0.2000837 0.9797759 0.002401053 0.1887516 0.9813424 -0.03660464 0.2663145 0.9637085 -0.01851433 0.2754479 0.961282 -0.008096873 -0.2649534 -0.9269973 0.2654727 -0.2992206 -0.9272764 0.225001 -0.2998445 -0.9280356 0.2210054 -0.3246492 -0.9274775 0.1854411 -0.324842 -0.9279549 0.1826956 -0.3430567 -0.9276224 0.1477458 -0.3430482 -0.9279028 0.1459948 -0.3559871 -0.927726 0.1122397 -0.3559255 -0.9278632 0.1112974 0.9206955 0.3749945 -0.1081624 -0.6946241 -0.6997562 0.1668493 -0.1926552 -0.8635072 0.4660895 0.1259099 -0.5479894 0.8269549 0.1832878 -0.6922945 0.6979498 0.2395914 -0.7246621 0.6461121 0.3299891 -0.7194282 0.6111713 0.04363244 -0.7846608 0.618388 -0.1494645 -0.8515249 0.5025594 -0.395716 -0.9000057 0.182753 -0.4030987 -0.9021146 0.1539509 -0.3804663 -0.9247206 -0.01171642 0.2491181 -0.6247086 0.7400537 0.3378735 -0.8061549 0.4857529 0.7485205 -0.5875902 0.3073351 0.9643633 -0.18411 0.1900181 0.9985203 -0.05406308 0.005875289 0.9406666 -0.09922671 0.3245003 0.9360032 -0.05074065 0.3483154 0.4868131 -0.5134187 0.7066926 0.6986203 -0.4543404 0.5527246 -0.3666114 -0.927293 0.07565563 0.9591943 -0.03705906 0.2803088 0.9970113 -0.05994153 0.04874056 -0.3647407 -0.9277926 0.07852053 0.2002142 -0.568073 0.7982528 0.1787045 -0.9140034 0.3642288 -0.1870661 -0.7481045 0.6366679 0.7113925 -0.332099 0.6193796 0.9002285 0.05974829 0.431299 0.9730402 -0.2282612 0.03301316 0.94095 0.3362436 -0.03941237 0.9844909 0.1730127 -0.02905726 0.9928646 0.1133093 -0.03716176 -0.7048978 -0.6942834 0.1452228 0.9613913 0.2549741 0.1035134 0.999779 0.0126211 0.01681411 0.9902083 0.1392028 -0.0104978 0.9922839 0.1211212 -0.02650296 0.7042478 -0.06135284 0.7072983 0.7239643 -0.08033967 0.6851433 0.6983438 -0.0670526 0.7126149 0.7075543 -0.1746249 0.6847431 0.6875606 -0.2029415 0.6971909 0.6896713 -0.3566929 0.6301776 0.660143 -0.2899693 0.6929134 0.7391242 -0.2969423 0.6045832 0.659618 -0.292375 0.6924024 0.7135634 -0.467945 0.5213969 0.5224366 -0.7449336 0.4148904 0.562367 -0.622181 0.5446413 0.5389438 -0.6397625 0.5479448 -0.1650041 -0.6948294 0.6999899 -0.1721704 -0.7020143 0.6910379 -0.296572 -0.6659918 0.6844707 -0.3183932 -0.6728965 0.6677097 -0.4518482 -0.6214181 0.6400569 -0.4581964 -0.6214816 0.6354659 -0.6628969 -0.3759046 0.6475055 -0.5342051 -0.5139497 0.6711787 -0.4940941 -0.6083242 0.6211383 -0.697804 -0.07751375 0.7120823 -0.9061217 -0.3124027 -0.2852159 -0.7172728 -0.1574089 0.6787799 -0.5740024 -0.07080948 0.8157863 -0.6710349 -0.1832858 0.7184139 -0.6374457 -0.3846909 0.6675896 -0.7220277 -0.4327798 0.5397941 0.1151524 0.9931565 -0.01949805 0.1239578 0.9922873 -6.73406e-4 -0.07000857 0.9917713 -0.1071851 -0.0679205 0.991501 -0.1109617 -0.04278165 0.9915738 -0.1222754 -0.04209762 0.991507 -0.1230517 -0.01424241 0.9915308 -0.1290884 0.01422011 0.9915562 -0.1288958 0.01463288 0.9915258 -0.1290833 0.04209452 0.9915074 -0.1230499 0.04277229 0.9915734 -0.1222823 0.06837427 0.9914932 -0.1107528 0.2103157 0.9718128 -0.1065233 0.04527235 0.9962331 -0.07396161 -0.1653037 0.9857109 -0.03238445 -0.1740404 0.9846473 -0.01340448 0.1215655 -0.4375817 0.8909232 -0.7824028 -0.2745493 0.5589889 0.506957 -0.2130027 0.8352393 0.4330044 -0.2010571 0.8786827 -0.875782 -0.1192691 0.4677402 -0.9418951 -0.02903002 0.3346503 -0.9712265 0.01020163 0.237939 -0.7445402 -0.1339588 0.6539992 -0.3530753 -0.2099598 0.9117317 -0.3567022 0.1562464 0.9210596 0.1107707 -4.31913e-6 0.9938461 0.556178 -0.07181996 0.8279541 0.3572683 0.1461029 0.9225038 0.7510623 0.02514004 0.6597526 0.9710683 -0.02064198 0.2379083 0.8484043 -0.1308479 0.5129221 0.8678233 -0.1354776 0.4780468 -0.4048344 -0.2260442 0.8860098 -0.7133215 -0.06060332 0.6982119 -0.5534311 -0.1223077 0.8238659 -0.1083631 -0.2059153 0.9725515 -0.2137928 -0.3760545 0.9015962 0.782373 -0.2746481 0.558982 0.015531 0.9904449 -0.1370318 -0.09152913 -0.9255649 0.3673583 -0.09961342 -0.9288846 0.3567221 -0.1623431 -0.9261415 0.3404508 -0.9997835 -0.01465904 0.01476758 0.7275759 7.39232e-7 0.6860272 0.7263327 -6.49982e-5 0.6873434 0.6954023 3.81417e-4 0.7186205 0.7153871 0.002266645 0.6987247 0.6999038 4.60439e-6 0.7142372 0.6315554 -0.002503454 0.7753267 0.6148208 -0.006632685 0.788639 0.5668371 0.001422405 0.8238287 0.4715675 0.008821845 0.8817859 0.4264562 -0.001268327 0.9045074 0.4857826 -0.001645982 0.8740782 0.4918571 0 0.8706759 0.4415683 -0.03337556 0.8966068 0.4167242 -0.06069928 0.9070042 0.4558042 -5.24582e-4 0.89008 0.3554621 7.62318e-5 0.9346908 0.3920073 0.002701163 0.9199582 0.3657767 0.03910827 0.9298807 0.322727 -0.009053826 0.9464488 0.2724107 -0.04837489 0.9609643 0.2800182 -0.03618669 0.9593125 0.1562021 0.02802312 0.9873275 0.09442484 -0.04776018 0.9943857 0 0.03383982 0.9994273 -0.09442496 -0.04775863 0.9943858 -0.1562018 0.02802222 0.9873276 -0.2684122 -0.03007036 0.9628348 -0.3746393 -0.1566197 0.9138466 -0.2801734 -0.01406919 0.9598463 -0.3741711 0.002496123 0.9273563 -0.4835759 0 0.8753026 -0.4715933 0.008809924 0.8817722 -0.4280501 -0.01026046 0.9036969 -0.4896407 -0.001503765 0.871923 -0.4556706 -0.02415466 0.8898207 -0.5389024 3.43773e-4 0.8423682 -0.6557487 -0.02015483 0.7547103 -0.6148345 -0.003781855 0.7886472 -0.6950608 3.79409e-4 0.7189509 -0.7273753 -8.15432e-5 0.6862399 -0.7263069 0 0.6873706 -1.95194e-6 1 -2.48458e-5 -1.95193e-6 1 2.03044e-6 -2.45848e-6 1 -2.5572e-6 -2.45837e-6 1 1.99401e-6 0 1 2.03182e-5 0 1 -1.3574e-6 0 1 1.46475e-6 0 -1 6.31453e-6 -0.3275347 0 0.9448391 -0.3275162 3.14031e-6 0.9448456 -0.07958555 -6.73445e-6 0.9968281 -0.07951301 6.7351e-6 0.9968339 0.1735875 6.27848e-7 0.9848185 0.1736083 6.27851e-6 0.9848148 0.4153171 1.25622e-6 0.9096767 0.4152984 -6.28144e-7 0.9096853 0.6303045 -5.02523e-6 0.7763481 0.6303653 0 0.7762988 0.8050445 -2.51149e-6 0.5932145 0.8050652 5.02211e-6 0.5931865 0.9283186 -1.00233e-5 0.3717857 0.9283615 1.0022e-5 0.3716786 0.9919646 -1.00499e-5 0.126516 0.9919711 0 0.1264653 0.327549 0 0.9448342 0.327513 0 0.9448466 0.07960546 0 0.9968265 -0.415295 -1.25628e-6 0.9096868 -0.6303404 -1.25626e-6 0.7763189 -0.6302809 0 0.7763673 -0.8050472 0 0.5932108 -0.8050472 0 0.5932108 -0.9919634 0 0.1265257 -0.9919646 0 0.1265156 0.3232126 0.1619968 0.9323576 0.1810331 0.3289416 0.9268358 0.184368 0.3297136 0.9259036 0.07847672 0.1685382 0.9825662 -0.159455 0.3951819 0.9046576 -0.04530227 0.9315398 0.3608065 -0.174589 0.8633994 0.4733501 -0.4005866 0.2640361 0.8773912 -0.3237472 0.352005 0.8782256 -0.2226132 0.9204893 0.3211584 -0.5800468 0.3912677 0.7144616 -0.7805791 0.244649 0.5751898 -0.6942726 0.3619258 0.6220894 -0.2604711 0.9344742 0.2427198 -0.2706961 0.9316076 0.2425511 -0.3349846 0.9210141 0.1987925 -0.8562552 0.3863052 0.3429216 -0.3237393 0.9400035 0.1076404 -0.3640657 0.9269699 0.09046077 -0.9669717 0.2230598 0.1233299 -0.9754656 0.1940457 0.103987 -0.8142781 0.5440774 0.2023139 -0.5472675 0.8189943 -0.1724721 -0.1950362 0.9805729 0.0209214 -0.3232564 0.1610867 0.9325001 -0.07827818 0.1788802 0.9807519 -0.1833869 0.3286159 0.9264885 -0.1849232 0.3284342 0.9262475 0.1593427 0.3968459 0.9039488 0.3865718 0.3653618 0.8468017 0.3285615 0.3081375 0.8928039 0.03931218 0.930907 0.3631347 0.1814484 0.8602703 0.4764572 0.2225986 0.920499 0.3211412 0.580243 0.3906866 0.7146202 0.2665967 0.9312395 0.2484336 0.2664141 0.9335923 0.2396434 0.7469158 0.3730921 0.550381 0.7082531 0.3041261 0.6370911 0.3350259 0.9209915 0.1988278 0.8563929 0.3859483 0.34298 0.3567547 0.9266382 0.1186075 0.3222737 0.9460151 0.03456979 0.5503025 0.8236308 0.137112 0.9246653 0.3031751 0.230389 0.8166505 0.5456643 -0.1879696 0.9731957 0.1936072 0.1241229 0.3273594 0.03110331 0.9443879 0.07822382 -0.1843956 0.9797344 0.025016 -0.1189304 0.9925875 -0.1666514 -0.2797943 0.9454853 -0.1961208 -0.2753227 0.9411345 -0.3827057 -0.3884672 0.83823 -0.6123507 -0.2370259 0.7542185 -0.6466637 -0.3296902 0.6878447 -0.1074151 -0.9363853 0.3341325 -0.2087538 -0.923882 0.320724 -0.2957175 -0.8938161 0.3371111 -0.345305 -0.8654537 0.36298 -0.3200525 -0.922379 0.2162945 -0.7414488 -0.3895595 0.5463489 -0.3466394 -0.9248387 0.1565713 -0.3362553 -0.9377008 0.0874626 -0.2987656 -0.9539883 0.02540749 -0.1945886 -0.9782513 -0.07183104 -0.5490779 -0.8217259 0.1525779 -0.9094717 -0.2004799 0.3642377 -0.9021558 -0.3510975 0.2506904 -0.8166311 -0.5456895 -0.1879807 -0.9732011 -0.1935793 0.1241236 0.5576379 7.51474e-7 0.8300844 0.557638 7.51474e-7 0.8300844 0.1108116 1.25248e-7 0.9938415 -0.3611443 0 0.93251 -0.7513202 0 0.6599379 -0.7512923 1.00196e-6 0.6599697 -0.5576122 0 0.8301017 -0.5576199 -1.00193e-6 0.8300965 -0.110875 -1.62822e-6 0.9938344 -0.1108064 2.25436e-6 0.9938421 0.361142 5.00963e-7 0.9325108 0.3611582 -2.50493e-7 0.9325045 0.7512848 -1.00186e-6 0.6599782 0.7512966 0 0.6599647 0.9712749 0 0.2379607 0.9712747 0 0.237961 -0.5562368 -0.06918132 0.8281392 -0.5763472 -0.146318 0.8039994 -0.5728635 -0.14177 0.8072972 -0.5029354 -0.1015779 0.8583345 -0.5349422 -0.1696743 0.8276761 -0.3679262 -0.4636331 0.806024 -0.4224179 -0.4853927 0.7654783 -0.2873509 -0.5379242 0.7925068 -0.2108699 -0.4659608 0.8593106 -0.1089406 -0.1910624 0.9755138 0.04716914 -0.2458047 0.9681711 -0.07668322 -0.5207386 0.8502653 -0.3118429 -0.7055487 0.636361 0.03120106 -0.8382958 0.5443221 0.2198841 -0.6633877 0.7152397 0.3478258 -0.2696009 0.8979602 0.6574984 -0.3258451 0.6793534 0.008529186 -0.9368405 0.3496529 -0.01760828 -0.7925553 0.609546 -0.1933844 -0.8588166 0.4743801 -0.06004387 -0.9436027 0.3255898 0.7144407 -0.3091722 0.6276839 0.6160475 -0.7053889 0.3505883 0.4061797 -0.890061 0.2069048 0.3384894 -0.9396987 0.04890048 0.4446636 -0.8874267 0.1214423 0.9409967 -0.2477312 0.2305526 0.815414 -0.5788037 -0.00930339 0.9582869 -0.2445883 0.1478614 0.118026 -0.965727 0.2311738 0.4715322 -0.01438325 0.8817316 0.412339 -0.3059516 0.8581201 0.2931747 -0.7044059 0.6464217 0.1430625 -0.9533309 0.2658821 0.3391804 -0.3852117 0.8582358 0.1304555 -0.9094468 0.3948265 0.07104367 -0.9424946 0.3265838 0.0543124 -0.7523027 0.6565752 0.2044921 -0.3714818 0.9056403 0.03996741 -0.7316387 0.68052 0.01607573 -0.9880259 0.1534491 -0.03997969 -0.7315848 0.6805772 -0.01607775 -0.9880258 0.1534489 -0.07104778 -0.9424942 0.3265836 -0.1304734 -0.909444 0.394827 -0.4424511 -0.1168897 0.8891422 -0.1419802 -0.950008 0.2780762 -0.1385004 -0.9539611 0.2660372 -0.2931624 -0.7044206 0.6464112 -0.4555909 -0.2584397 0.8518486 0.5562838 -0.06906259 0.8281176 0.5464311 -0.07520049 0.8341212 0.5760222 -0.1381741 0.8056714 0.491858 -0.3073638 0.8146185 0.5331549 -0.2320942 0.8135589 0.5242691 -0.2285705 0.8203033 0.4866642 -0.2608661 0.8337307 0.226194 -0.4301882 0.8739418 0.1192969 -0.1963207 0.9732556 0.1085587 -0.1969413 0.9743866 0.2952621 -0.7045485 0.6453152 0.3609424 -0.637109 0.681038 0.2607138 -0.5979807 0.7579233 0.008400857 -0.5754423 0.8177993 -0.2890245 -0.2736122 0.9173884 -0.1371408 -0.6223332 0.7706451 -0.3474891 -0.2725104 0.8972121 3.39265e-4 -0.9540952 0.2995033 -0.06953859 -0.8381032 0.5410615 0.1195395 -0.9101155 0.3967369 -0.379635 -0.7014769 0.6031645 -0.2014105 -0.8733112 0.4435782 -0.6472467 -0.3049449 0.6986275 -0.4819357 -0.6994797 0.5276989 -0.2139152 -0.9764378 -0.02845585 -0.4322341 -0.8915166 0.1355434 -0.7187637 -0.2910695 0.6313932 -0.6910665 -0.679261 0.2470458 -0.4514328 -0.8852335 0.1121171 -0.9365108 -0.2651551 0.2294348 -0.9238853 -0.262365 0.2785691 -0.7754824 -0.6209607 0.1141712 0.08395135 -0.4719861 0.8775998 0.07371973 -0.3143962 0.9464252 0.03183543 -0.7180108 0.6953036 0.05569863 -0.9124087 0.4054726 0.06149959 -0.8951037 0.4415962 0.06956887 -0.9881621 0.1367331 0.0124498 -0.9194352 0.3930448 3.90352e-6 -1 9.41801e-6 5.20875e-7 -1 -2.04363e-6 6.27698e-7 -1 -1.19883e-6 6.63163e-7 -1 -7.93599e-7 -4.10701e-5 0 1 1.6059e-5 0 1 -6.87323e-6 0 1 9.01135e-6 0 1 -1.5586e-5 -7.84104e-6 1 -3.63556e-6 2.30426e-6 1 3.53302e-6 2.76238e-6 1 0 1.83106e-6 1 -2.43332e-6 3.04165e-7 1 -3.65032e-6 5.80305e-7 1 3.99102e-6 6.54716e-7 1 -2.66633e-6 4.07785e-7 1 -2.7439e-6 1.41935e-7 1 0 5.72204e-6 1 0.04408562 -0.7186193 0.6940049 -0.04408627 -0.7186175 0.6940068 0.1970235 -0.3283075 0.9237944 -0.1148183 -0.9055542 0.4083974 0.3531469 -0.8725537 0.3375462 0.1973821 -0.8019853 0.5637908 -0.1888835 -0.6710025 0.7169929 -0.2527742 -0.650106 0.7165665 0.1260037 -0.6533983 0.7464541 -0.2126874 -0.2951406 0.9314806 -0.2042734 -0.3007056 0.931584 0.1040272 -0.3002272 0.9481782 -7.66877e-5 -0.1876331 0.9822393 0.2625849 -0.1267631 0.956546 0.2700877 -0.1371639 0.9530156 -0.2703548 -0.1375392 0.9528859 7.66877e-5 -0.1876352 0.9822388 -0.1040279 -0.3002293 0.9481775 0.2042766 -0.3006989 0.9315853 0.2126827 -0.2951478 0.9314795 -0.1260026 -0.6533963 0.7464561 0.2527777 -0.6501016 0.7165693 0.1888812 -0.6710073 0.7169889 -0.1973825 -0.8019827 0.5637942 -0.3531537 -0.8725557 0.3375337 0.1148201 -0.9055529 0.4083998 -0.1970813 -0.3274838 0.9240744 -0.01244151 -0.919433 0.3930501 -0.06952518 -0.9881662 0.1367257 -0.06146055 -0.8951021 0.4416051 -0.05566406 -0.9124087 0.4054775 -0.03181552 -0.7180086 0.6953067 -0.07368135 -0.3143103 0.9464566 -0.2046101 -0.3709416 0.905835 -0.05429589 -0.7522495 0.6566374 -0.3395892 -0.3843276 0.8584704 0.9732064 -0.1935856 0.1240735 0.8166108 -0.5456638 -0.188143 0.9023569 -0.3499321 0.2515942 0.9094913 -0.2006037 0.3641209 0.5490273 -0.8216667 0.1530783 0.1945943 -0.9782637 -0.0716477 0.2984476 -0.9540886 0.02538162 0.3363667 -0.9375879 0.08824169 0.3466362 -0.9248397 0.1565722 0.7418124 -0.3885729 0.5465579 0.3200497 -0.9223806 0.2162926 0.3452997 -0.8654575 0.3629759 0.2957094 -0.8938256 0.3370933 0.2087602 -0.9238765 0.3207358 0.107412 -0.9363892 0.3341228 0.6468907 -0.3287454 0.6880835 0.6125394 -0.2361295 0.7543464 0.3827741 -0.3879532 0.8384369 0.1960179 -0.2749704 0.941259 0.1666682 -0.279492 0.9455718 -0.02492821 -0.1190559 0.9925746 -0.078166 -0.1847254 0.9796769 -0.3273641 0.02956467 0.9444357 -0.366091 0.03954058 0.9297386 -0.3923577 0.003085732 0.9198076 -0.4278044 -9.70372e-4 0.9038708 -0.7175811 0.002586185 0.6964702 -0.6999162 0 0.714225 -0.9997621 -0.02027523 0.008047997 -0.1050825 0.9935915 0.04163748 0.009287655 0.9989368 0.04515779 -0.07535785 0.9953442 -0.0600931 0.04501128 0.9983414 -0.03589534 -0.07723855 0.9952924 -0.05854493 0.04527288 0.9983851 -0.03431439 0 1 -3.96134e-6 0 1 1.76811e-6 1 -1.23874e-4 0 -0.543058 0.839695 4.81564e-4 -0.8264393 0.563026 3.26399e-4 -0.9801963 0.1980285 0 -0.9803798 0.1952774 0.02687489 0.4829752 0.8754935 -0.01568573 0.552717 0.8333691 -1.38711e-4 0.8264394 0.5630257 3.26037e-4 0.9800179 0.1989096 1.65037e-4 0.9659219 -0.2588335 0 0.7070871 -0.7071101 0.004824459 0.2587996 -0.9659243 0.003612041 -0.2588242 -0.9659245 0 -0.7070856 -0.7071117 0.004823327 -0.9659214 -0.2588106 0.003612875 -0.5393827 0.8339684 0.1164609 -0.8263171 0.5628948 -0.01869899 -0.8509969 0.5205001 0.06988495 -0.9828308 0.1844589 -0.004311978 0.6048113 0.7911733 0.09082007 0.8263233 0.5628854 -0.0187093 0.8509936 0.5205033 0.069902 0.9800152 0.1989188 -0.001196682 -0.3826013 0.9238361 0.01196557 -0.6054936 0.7920593 -0.07758605 -0.982422 0.1831318 0.03619015 -0.8434682 0.5313514 -0.07891225 -0.9204171 0.3813195 -0.08618438 -0.3511031 0.9344635 0.05920141 -0.7671253 0.4246752 0.4808014 -0.30855 0.9234274 0.2282076 -0.3523108 0.909461 0.2208118 -0.768274 0.3935215 0.5048722 -0.1669273 0.9277191 0.333875 -0.2949079 0.4132785 0.8615279 -0.3027046 0.4024117 0.8639647 -0.1389532 0.9074012 0.3966298 0.002523839 0.9349589 0.3547472 0.2963587 0.4032523 0.8657708 0.3010104 0.4138914 0.8591198 0.1392916 0.9069396 0.3975657 0.1703311 0.928636 0.3295797 0.7682684 0.3935372 0.5048685 0.349474 0.9026596 0.2511447 0.7671205 0.4246799 0.4808049 0.3527261 0.9340001 0.05681711 0.9204785 0.383482 -0.07523989 0.6135499 0.7808734 0.1174457 0.4356908 0.8971719 -0.07250112 0.9823441 0.1835767 0.03605121 0.8434673 0.5313539 -0.07890462 0.6050399 0.7904077 0.09582602 0.4783669 0.8781304 -0.007226884 0.9978135 0 -0.06609296 0.997798 -1.25194e-4 -0.06632816 -0.8357062 0 0.5491769 -0.323853 0 0.9461075 -0.3238531 0 0.9461074 0.3238514 0 0.946108 -0.9970437 0.005227029 -0.07665872 -0.9977977 0 -0.06633216 -0.9644939 -0.258421 -0.05449843 -0.6995447 -0.6995636 0.1457675 -0.6235514 -0.6657878 0.4097685 -0.2084822 -0.765229 0.6090648 0.2084813 -0.7652282 0.6090662 0.623553 -0.6657857 0.4097695 0.9644863 -0.2584495 -0.05449891 0.6995447 -0.6995636 0.1457672 0 1 1.39909e-6 -0.1872045 0.9823209 -4.94347e-4 -0.6798595 -0.715054 0.1627544 0.2588017 -0.9659305 0 0.6798594 -0.7150544 0.1627527 0.680618 -0.4674216 0.5641598 0.684151 -0.4691834 0.5583946 -0.06979513 0.991136 -0.11304 0.4937724 -0.5547939 0.6696213 -0.8891696 -0.2823281 0.3600952 -0.06967383 0.9911667 -0.112846 1 0 -5.2395e-5 -0.5555935 0.8314541 -3.21888e-4 -0.8314814 0.5555528 -1.63858e-4 -0.9807841 0.1950969 1.67725e-4 0.1950917 0.9807808 0.002891421 0.5555554 0.8314796 -3.21513e-4 0.8314709 0.5555682 -1.62751e-4 0.9807818 0.1951081 -5.13732e-5 0.9807748 -0.195084 0.004795193 0.8314688 -0.5555663 -0.002417623 0.5555701 -0.8314662 -0.002418398 0.1950905 -0.9807853 0 -0.1950844 -0.9807748 0.004794239 -0.5555857 -0.8314559 -0.002417564 -0.8314639 -0.5555737 -0.002418637 -0.9807841 -0.1950969 0 -0.1950758 0.9807882 0 -0.4398642 0.8976948 0.02575904 -0.3430797 0.9296294 -0.1344832 -0.1209133 0.9899573 -0.07324415 -0.9531854 0.2032546 0.2238866 -0.9473337 0.2911731 0.1333307 0.1918236 -0.8630234 0.4673269 -0.1259078 -0.5479844 0.8269586 -0.1824608 -0.6903202 0.7001187 -0.2695353 -0.7382375 0.6183496 -0.04402703 -0.7844851 0.6185829 0.3448712 -0.8710669 0.3497232 -0.2490041 -0.6207391 0.7434245 -0.5327382 -0.6768699 0.5079737 -0.4865662 -0.685885 0.5411241 -0.9643704 -0.1841113 0.1899811 -0.9393291 -0.2293926 0.2550294 -0.9744558 0.2097574 0.0802353 -0.9417689 -0.1188918 0.3145411 -0.47203 -0.5159705 0.7148162 -0.5530092 -0.4998651 0.6665701 -0.107047 -0.9371785 0.3320203 -0.08362579 -0.9754936 0.2035164 -0.9561833 0.278514 0.09024131 0.818397 -0.5591312 0.1326603 0.2641158 -0.9384393 0.2226534 0.3083099 -0.9294109 0.2028315 0.3333426 -0.9270873 0.1714409 0.4158322 -0.9039104 0.100148 -0.0201013 -0.9983823 0.05318695 -0.2465073 0.9682106 -0.04245507 -0.2326105 0.9725036 -0.01136696 -0.2238139 0.9730722 -0.05511879 -0.179786 0.9814466 -0.06663066 -0.09303051 0.9914761 -0.09121805 -0.1322363 0.9512194 0.278739 -0.1913794 0.9384491 0.2875542 -0.2423986 0.9549323 0.171311 -0.1703892 0.9612234 0.2168343 -0.170974 0.9616594 0.2144276 -0.214473 0.9610535 0.174292 -0.2146787 0.9620076 0.1686846 -0.2470538 0.9608834 0.1251707 -0.245663 0.9626376 0.1139242 -0.26771 0.9606189 0.07445025 -0.2631568 0.9632421 0.05397623 -0.2767165 0.9606146 0.02544921 -0.2688905 0.9631384 -0.007906079 -0.2554128 0.9665963 0.02135545 -0.06977128 0.9915631 -0.1092462 -0.3400523 -0.6262935 0.7015134 -0.2235274 -0.5177186 0.8258348 -0.2764627 0.3216268 0.9056074 -0.6454439 -0.570694 0.507652 -0.6437101 -0.5743148 0.5057665 -0.8400881 0.2612391 0.475401 -0.6797994 0.6452875 0.3485353 -0.8839502 0.08803063 0.4592198 -0.8141434 0.3264344 0.4802199 -0.7574713 0.3963568 0.5187858 -0.5314271 -0.5620051 0.6338263 -0.49642 -0.6743949 0.5465882 -0.6976424 0.3153098 0.6433311 -0.452665 -0.639333 0.6215688 -0.4963524 0.3667766 0.786835 -0.5515167 0.1910752 0.8119851 -0.4038561 0.4439343 0.7998891 -0.4172182 -0.5408343 0.7303611 -0.7042384 -0.60282 0.3750419 -0.5508995 -0.7064279 0.4443755 -0.9400312 -0.1471374 0.3077208 -0.9538579 0.1967604 0.226805 -0.7761563 0.6074858 0.1689454 -0.8967693 0.4055957 0.1769102 0.3300452 -0.8072382 0.4893227 -0.2001935 -0.568071 0.7982594 -0.1971307 -0.7726789 0.6034126 -0.5600999 -0.4294062 0.708448 -0.7705115 -0.5968961 0.2236676 -0.8949335 -0.3911104 0.214771 -0.8690226 -0.3156638 0.380994 0.4041016 -0.5643867 0.7198401 0.3380058 -0.8513108 0.4012756 0.5200937 -0.7874122 0.3308845 0.1497383 -0.7814201 0.6057733 -0.6730825 -0.653711 0.3458641 -0.7948731 -0.5232976 0.3071425 -0.9338671 0.3528715 -0.05808728 -0.8466212 0.5286374 -0.06144374 -0.7798328 0.6256815 -0.0195834 -0.7979624 0.6005198 -0.05130374 -0.7679969 0.6403045 -0.0138157 -0.8011792 0.5893303 -0.1039317 -0.7627705 0.644436 -0.05369722 -0.7271161 0.6859998 0.02658385 -0.7186803 0.6953403 -6.99698e-4 -0.6761894 0.7332347 0.07165735 -0.1938185 -0.8716284 0.4502205 -0.3348625 -0.67114 0.6613912 -0.1441257 -0.9396895 0.31018 -0.1445418 -0.9396896 0.3099858 -0.1497857 -0.939287 0.3087141 -0.1492024 -0.9378128 0.3134419 -0.148566 -0.937618 0.3143259 -0.1064831 -0.9430903 0.3150271 -0.1649997 -0.9329211 0.3200522 0 1 6.04166e-7 0 1 -5.00094e-7 0 1 1.1898e-6 0 1 -2.00214e-7 0 1 2.18865e-7 0 1 -7.22525e-7 -0.1431158 -0.9386849 0.3136695 -0.5999657 0.7818635 -0.1695013 -0.3586198 0.9302898 -0.07715541 -0.341605 0.9305937 -0.1315351 -0.4758468 0.8778123 -0.05491286 -0.3378086 0.9405955 0.0341413 -0.3705793 0.9288004 -9.99339e-4 -0.2694854 0.9591626 -0.08593559 -0.9987608 0.02242249 0.04443156 -1 2.00674e-6 0 -1 2.10068e-6 0 -0.001180112 -0.9999988 -0.001037061 0.6689701 -0.7179104 0.1925714 0.7136576 -0.6457921 0.271377 0.6746108 -0.6515443 0.3469732 0.6488735 -0.6298767 0.4268708 0.6481448 -0.6266615 0.4326704 0.5822682 -0.648095 0.490853 0.6805571 -0.5790713 0.4489082 -0.5587527 0.8293179 -0.005236923 -0.630417 0.7734391 -0.06608015 -0.6232809 0.7819285 -0.01042681 -0.6235331 0.781615 -0.01686447 -0.5816636 0.8124362 0.04018729 -0.5818997 0.8114981 0.0535137 -0.5660055 0.8204928 0.08018398 -0.5820387 0.8125513 0.03148514 -0.5772525 0.8084238 0.115024 -0.5437502 0.8255088 0.1512322 -0.5412142 0.8206722 0.1832606 -0.4846042 0.8395704 0.2455208 -0.5106952 0.8274887 0.233352 -0.4737935 0.8160199 0.3311064 -0.4043738 0.8535223 0.3286055 -0.3968793 0.8348701 0.3814169 -0.3206759 0.8547791 0.4080683 -0.3303018 0.84811 0.4142587 -0.2594583 0.826846 0.4990063 -0.2167979 0.862659 0.4569661 2.42275e-4 -1 -3.1378e-5 -0.001079082 -0.9998143 0.01923954 -0.2663806 -0.9281529 0.2599495 -0.2226665 -0.9283239 0.2977155 0.09301066 0.9914767 -0.09123086 0.1393759 0.9861054 -0.09039157 0.1375467 0.9871779 -0.08099925 0.1494146 0.9872229 -0.05537468 0.06819528 0.9915382 -0.1104601 0.07177078 0.9910705 -0.1123766 0 1 -1.44673e-6 0 1 1.0933e-6 0 1 0 0 1 -6.40653e-7 0 1 1.6673e-7 0 1 5.85521e-7 0 1 -5.62779e-7 -0.008570611 -0.9999616 0.001845896 -0.008046269 -0.9999645 0.002514541 -0.007454633 -0.9999673 0.003173112 -0.006781637 -0.9999697 0.003814041 -0.006014466 -0.9999721 0.004433453 -0.005139946 -0.9999743 0.00501579 -0.004145205 -0.9999762 0.005542337 -0.003021061 -0.9999776 0.005984127 0.3253074 0.8608788 0.3912326 0.3353319 0.840389 0.4257922 0.2328515 0.8649798 0.4445111 0.2502908 0.8126875 0.526207 0.1764578 0.8381843 0.5160521 0.1081538 0.843666 0.5258616 0.1118743 0.8617493 0.4948459 2.93948e-4 0.8386362 0.5446921 -0.009137392 -0.9999578 0.001012504 -0.006301641 -0.9999617 0.006072342 0.1039898 -0.9435225 0.3145655 0.07082647 -0.9362012 0.3442546 -0.005549609 -0.9507322 0.3099638 0.04523396 -0.9048668 0.4232848 0.2568309 -0.8716326 0.417486 0.1445409 -0.9396912 0.3099815 0.1273782 -0.9415367 0.3119029 0.1891195 -0.9183754 0.3475924 0.3039706 0.3429703 0.8888044 0.2804107 0.2789239 0.9184614 0.155316 -0.6371596 0.7549203 0.2523853 -0.5058062 0.8249012 0.1803311 0.4458267 0.8767665 0.02352958 0.3836879 0.9231631 0 -0.5819049 0.8132569 0.4301431 -0.544819 0.7198258 0.3903653 -0.6076905 0.6916121 0.532432 0.4040668 0.7438052 0.4447466 0.03825753 0.8948391 0.4621858 0.5201829 0.7181881 0.2946035 -0.6401302 0.7095367 1.71357e-4 0.9474398 0.3199343 0.1638165 0.9545846 0.2488626 0.1373203 0.9475179 0.2887093 0.2419497 0.9550979 0.1710216 0.1705617 0.9612518 0.2165725 0.1710535 0.961623 0.2145273 0.2145774 0.9610776 0.1740304 0.2147516 0.9619802 0.1687477 0.05806809 -0.9880299 0.1429166 0.06865692 -0.9834015 0.1679516 0.03294652 0.9525738 0.3025193 0.07027983 0.9478479 0.3108783 0.09368062 0.9526406 0.2893094 0.09771579 -0.9210404 0.3770098 0 1 3.02083e-7 0 1 0 -0.04460233 0.9908385 -0.1274741 0.02095043 0.9922779 -0.1222524 0.04459172 0.9908376 -0.1274852 0.04751843 0.9919 -0.1177978 -0.1672725 -0.9285646 0.3313425 -0.03233128 0.9524927 0.3028405 -0.07020837 0.9474694 0.3120462 -0.09561145 0.9524602 0.289272 -0.2322086 -0.6087495 0.7586194 -0.131628 0.4609077 0.8776322 -0.01399797 -0.6233036 0.7818546 0 0.3165827 0.948565 9.45799e-4 0.9999995 -2.75796e-4 -0.105062 -0.9425585 0.3170892 -0.0928263 -0.9347611 0.3429358 -0.03533935 -0.9430735 0.3307018 -0.1682178 0.8287453 0.5337454 -0.1321673 0.7983928 0.5874528 -0.06548112 0.8972913 0.4365556 0.01265805 0.8676763 0.4969684 0.04879659 -0.9986239 0.01921677 0.5249837 -0.6555281 0.5428399 0.1279134 -0.6148375 0.7782114 -0.8030136 -0.2009384 0.5610642 0 1 -8.31664e-7 0 1 -9.83897e-7 0 1 0 0 1 7.65709e-7 0 1 -7.57987e-7 -3.01003e-5 1 -1.88166e-5 1.63584e-4 1 4.54989e-5 4.78764e-4 0.9999999 8.98074e-5 7.1691e-5 1 -5.39712e-6 5.06954e-5 1 -9.53093e-6 -0.001268386 0.9999992 -3.54914e-4 -1.60798e-5 1 1.45829e-4 -5.2518e-5 1 1.53517e-4 -1.03263e-4 1 1.6907e-4 -1.27595e-4 1 1.77463e-4 3.25689e-5 1 -3.72173e-5 0 1 0 2.84776e-6 1 -2.85893e-5 2.17876e-5 1 -1.35249e-5 7.19316e-6 1 -2.50632e-5 1.11396e-5 1 -2.28981e-5 1.51282e-5 1 -1.96002e-5 0 -1 0 3.2689e-4 -1 1.88933e-4 -3.01921e-5 -1 -2.04903e-4 1.37127e-4 1 -7.66889e-5 2.13542e-4 1 -1.98559e-4 0 1 1.34263e-6 5.76875e-5 1 9.98095e-5 1.45004e-4 1 7.02342e-5 -0.0011065 0.9999994 2.04763e-4 -6.36644e-6 1 -1.72845e-5 -7.17073e-6 1 -1.73048e-5 -7.13223e-6 1 0 -6.94155e-6 1 7.56691e-6 -7.38992e-6 1 7.46295e-6 0.1119688 0.9937118 1.68058e-5 0.111816 0.9937289 8.69787e-6 3.66604e-4 1 1.40831e-4 0 1 4.09e-5 3.94434e-4 1 7.33121e-5 0 1 0 2.00161e-5 1 -1.11838e-5 4.4736e-7 1 0 1.78804e-5 1 -1.23145e-5 1.46971e-5 1 -3.01984e-5 0 1 0 0 1 9.08734e-7 -4.44284e-4 0.9999995 9.59907e-4 1.71729e-5 1 -1.4339e-5 1.71315e-5 1 -1.41936e-5 -7.9937e-4 0.9999997 -3.51273e-5 0.001091003 0.9999983 -0.00155431 2.13319e-5 1 -2.31298e-5 0.8296394 0 0.5582997 -0.8980236 -0.2616399 0.3536926 -0.9494912 -0.1210009 0.2895259 -0.8980271 -0.2616347 0.3536873 -0.949492 -0.1209999 0.2895236 -0.8980311 -0.2616292 0.353681 -0.9494931 -0.1209968 0.2895216 -0.06814444 -0.9965406 0.04757255 -0.1110144 -0.9912123 0.07193052 -0.1983147 -0.9699551 0.1409199 -0.2912737 -0.9351806 0.2014865 -0.3265832 -0.9166823 0.2302979 -0.4278199 -0.85344 0.2976753 -0.4369035 -0.8460813 0.3053884 -0.5801893 -0.7071943 0.4040504 -0.5580003 -0.7372873 0.3808454 -0.6899606 -0.5318908 0.4909651 -0.6509934 -0.6135658 0.4469279 -0.7514291 -0.3899708 0.532238 -0.7348878 -0.446139 0.5107837 -0.7939811 -0.2380669 0.559391 -0.7883638 -0.2750521 0.5502989 -0.8158121 -0.08005833 0.5727491 -0.815621 -0.09274435 0.5711051 -0.8165264 0.08000856 0.5717371 -0.8107988 0.1233395 0.5721825 -0.7965629 0.2380096 0.5557328 -0.7738796 0.3242682 0.5440226 -1.32173e-5 4.68658e-4 -0.9999999 -4.40064e-5 4.3556e-4 -1 0.4188722 0.003536522 -0.9080383 0.2125791 -0.01145368 -0.9770768 0.8668085 -0.006250202 -0.4986021 0.9189638 4.36298e-4 -0.3943418 0.9014806 0.005701541 -0.4327822 -0.9197242 -4.96325e-4 -0.3925648 -0.9988456 -0.03721529 -0.03037142 -0.9955021 -0.04019302 0.08579266 0.05326789 -8.75434e-5 -0.9985803 -0.4010694 -0.0543304 -0.9144352 0.01734858 0.01334506 -0.9997605 0.009241819 0.01646214 -0.9998218 -0.001242101 -0.002269923 -0.9999967 0.01311069 0.001632452 -0.9999128 0.4267706 0.01191771 -0.9042814 0.6719533 0.04612934 -0.7391555 0.9406457 -3.25418e-4 -0.3393899 -0.3213763 0.03813886 -0.9461833 -0.4072002 -0.01936894 -0.9131336 -0.007701277 -0.04993236 -0.998723 0 1 -1.21517e-6 0.01046025 0.9999229 0.006704032 -5.27824e-4 0.9999986 0.001597166 -1.78713e-4 0.9999986 0.001674294 1.82334e-4 0.9999986 0.001673996 5.18477e-4 0.9999986 0.001601278 -0.01046025 0.9999229 0.006702721 0 1 9.14827e-7 0 1 -3.03799e-7 0.0361911 -0.9402177 0.3386456 0.102649 -0.945005 0.3105301 0.1109401 -0.9433747 0.3126287 0.1227751 -0.9486515 0.2915248 -0.03619098 -0.9402182 0.3386442 -0.1028522 -0.9450126 0.3104398 -0.1226226 -0.9485899 0.2917895 -0.1109282 -0.9433673 0.3126552 -0.1109333 -0.9433687 0.312649 -0.122615 -0.948591 0.2917891 -0.1028584 -0.9450128 0.3104369 -0.03618693 -0.9402191 0.3386421 0.1227701 -0.9486529 0.2915222 0.1109383 -0.9433733 0.3126334 0.1026554 -0.9450048 0.3105282 0.03618752 -0.9402189 0.3386429 -0.1445484 -0.9396907 0.3099794 0 1 6.07609e-7 0 1 -3.04934e-7 -0.01046061 0.9999228 0.006703138 5.18481e-4 0.9999986 0.001601278 1.82333e-4 0.9999986 0.001674294 -1.78713e-4 0.9999986 0.001673996 -5.27824e-4 0.9999986 0.001597166 0.01046055 0.9999228 0.006704151 0 1 -1.21972e-6 0.01044809 0.9999231 0.006694853 -5.27214e-4 0.9999986 0.001595616 -1.78503e-4 0.9999986 0.001672208 1.82117e-4 0.9999986 0.001672387 5.17885e-4 0.9999986 0.001599192 -0.01044785 0.9999231 0.006695449 0 1 -3.04942e-7 0 1 -6.07595e-7 -0.1109365 -0.9433688 0.3126475 -0.1226224 -0.9485902 0.2917882 -0.03619074 -0.9402182 0.3386445 0.122775 -0.9486514 0.2915253 0.1109402 -0.9433748 0.3126282 0.1026494 -0.9450047 0.310531 0.03619146 -0.9402177 0.3386458 0.1445332 -0.9396937 0.3099773 -0.1214787 -0.9360836 0.3301371 -0.144547 -0.9396919 0.3099763 0 1 1.09897e-6 0 1 -1.09901e-6 0 1 2.19793e-6 0 1 -9.5241e-7 0 1 -9.52156e-7 0 1 9.59339e-7 -0.5736157 -4.58335e-7 -0.8191246 -0.573571 0 -0.8191559 -0.5735622 5.72753e-7 -0.8191621 -0.5735751 -9.35991e-7 -0.819153 0.6826881 -0.04833006 0.72911 0.5759342 8.1355e-4 0.8174957 0.58895 -0.01023763 0.8081047 0.5331689 -0.008830964 0.8459628 0 -0.920579 0.3905566 0 -0.9206038 0.3904983 0 -0.9206254 0.3904469 0 -0.9206275 0.390442 0 -0.9206291 0.3904386 0 -0.9206352 0.3904241 0 -0.9206277 0.3904418 0 -0.9206271 0.3904433 0 -0.9206248 0.3904484 0 -0.9206337 0.3904275 0 1 8.75091e-7 0 1 -4.10727e-6 0 1 -2.45366e-6 0 1 2.03994e-6 0 1 -7.99362e-7 0 1 4.31867e-6 0 1 -6.93178e-7 0 1 1.51088e-6 1 0 0 1 -1.99881e-7 0 1 -1.86259e-7 0 1 0 0 1 1.38721e-7 0 1 -1.24541e-7 0 1 2.07847e-7 0 1 -1.26333e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 6.51112e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.67476e-7 0 1 -2.08167e-7 0 1 2.35828e-7 0 1 -2.70312e-7 0 1 -4.43117e-7 0 1 4.3766e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.37803e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.85363e-7 0 -1 1.38721e-7 0 -1 -2.43752e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.08167e-7 0 -1 2.51215e-7 0 -1 0 0 -1 0 0 -1 1.35157e-7 0 -1 6.51115e-7 0 -1.90104e-5 -0.3749045 0.9270635 3.53855e-6 -0.37489 0.9270693 0 -0.3748994 0.9270656 0 0.7071075 0.7071061 0 0.7071063 0.7071073 0 0.8365738 0.5478542 0 0.8365731 0.5478554 0 0.898551 0.4388694 0 0.9561426 0.2929018 0 0.9901912 0.1397194 0 0.9998573 -0.01689833 0 0.9998572 -0.01690053 0 0.9849037 -0.173103 0 0.984904 -0.173102 0 0.9456979 -0.3250472 0 0.9456982 -0.3250463 0 0.8832074 -0.4689828 0 0.7989683 -0.6013732 0 0.7989673 -0.6013746 0 0.6950564 -0.7189553 0 0.6950558 -0.7189558 0 0.5740295 -0.8188347 0 0.574029 -0.8188351 0 0.4388697 -0.8985507 0 0.2929012 -0.9561427 0 0.2929012 -0.9561428 0 0.1397201 -0.9901911 0 0.1397201 -0.9901911 0 -0.01689922 -0.9998573 0 -0.01689922 -0.9998573 0 -0.1731035 -0.9849037 0 -0.325046 -0.9456983 0 -0.3250458 -0.9456983 0 -0.4689828 -0.8832073 0 -0.601374 -0.7989677 0 -0.718954 -0.6950578 0 -0.8188356 -0.5740282 0 -0.8188362 -0.5740275 0 -0.898551 -0.4388694 0 -0.9561426 -0.2929017 0 -0.9901912 -0.1397194 0 -0.9998573 0.01689833 0 -0.9998572 0.01690053 0 -0.9849037 0.173103 0 -0.9849039 0.173102 0 -0.9456978 0.3250473 0 -0.9456982 0.3250463 0 -0.8832074 0.4689828 0 -0.7989655 0.6013768 0 -0.7989665 0.6013757 0 -0.6371554 0.7707355 0 -0.637155 0.7707358 -0.8910075 0 0.4539886 -0.891008 0 0.4539879 -0.7071043 0 0.7071092 -0.7071043 0 0.7071093 0.7071043 0 0.7071093 0.7071043 0 0.7071092 0.891008 0 0.4539879 0.8910075 0 0.4539886 0.9876884 0 0.1564343 0.9876883 0 0.1564348 -0.9876883 0 0.1564348 -0.9876884 0 0.1564343 -0.4539912 0 0.8910062 -0.4539892 0 0.8910072 -0.4539963 0 0.8910036 0.453992 0 0.8910058 0.4539846 0 0.8910096 0.4539942 0 0.8910046 -0.1564362 0 0.9876881 -0.1564289 0 0.9876893 0.15643 0 0.9876891 0.1564352 0 0.9876883 -0.2631011 -0.9002954 -0.3467652 -0.1796959 -0.906349 -0.3824149 0.334348 -0.8925247 -0.3026732 0.3349564 -0.8920447 -0.3034148 0.9835327 0.1801463 -0.01452398 0.6210286 0.7509599 -0.224461 -0.8998233 0.4325617 -0.05664354 -0.9667052 0.2456487 -0.07167977 0.3670322 -0.8866896 -0.2811921 0.3622159 -0.8894866 -0.2785917 -0.5605934 0.8190392 -0.1221058 -0.04968655 0.9980979 -0.03649336 -0.05698674 0.9765571 -0.2075784 0.16266 0.9844366 -0.06652981 -0.03361511 0.968647 -0.2461568 0.004083693 0.9815441 0.1911924 -0.08374708 0.9277295 -0.3637368 -0.07776176 0.9594801 -0.2708344 -0.06404066 0.9668525 -0.2471742 -0.07747024 0.9280424 -0.3643293 -0.01831793 0.9874434 -0.1569079 -0.02893555 0.9682159 -0.2484369 -0.00332719 0.991356 -0.1311576 -0.006734251 0.9876766 -0.1563639 0.2011194 0.9709568 -0.1295914 0.1715711 0.9763386 -0.1316298 0.173201 0.8229304 -0.5410979 0.001363456 0.1353878 -0.9907917 0.1497246 0.9839175 -0.09741157 -0.405629 0.9095177 -0.09079104 -0.316255 -0.7470064 -0.5847771 -0.3020465 -0.677889 -0.6702495 -0.06273508 -0.80231 -0.5936017 -0.0675047 -0.8108865 -0.581297 -0.01102149 -0.7962208 -0.6049057 -0.0158571 -0.8094701 -0.5869469 -0.001671433 -0.7905492 -0.6123963 -0.003700077 -0.7970896 -0.6038498 1.70641e-4 -0.7930918 -0.6091021 8.59998e-4 -0.7907761 -0.6121049 3.34939e-4 -0.7952235 -0.6063164 0.001003265 -0.793096 -0.609096 -0.002143561 -0.7944436 -0.6073343 -0.002468287 -0.7953861 -0.6060981 -0.01412522 -0.8018992 -0.5972926 -0.01160174 -0.7952094 -0.606224 -0.03387957 -0.822739 -0.5674089 -0.0237981 -0.802073 -0.5967516 0.003752768 -0.9964701 -0.08386564 -0.00537616 -0.9975541 -0.06969141 0.006298243 -0.9929187 -0.118629 -0.002072274 -0.9963548 -0.08528172 0.02330636 -0.9880397 -0.1524287 0.01559203 -0.9929573 -0.1174432 0.167618 -0.9396044 -0.2984088 0.1417362 -0.9620317 -0.2332508 0.1322015 -0.9153221 -0.3804055 0.1119063 -0.949243 -0.2939642 0.1266259 -0.9002087 -0.4166416 0.1169542 -0.9175869 -0.379942 0.1727983 -0.8943608 -0.4126254 0.1732788 -0.8935391 -0.4142009 0.2314541 -0.8948121 -0.3817599 0.2379328 -0.8833972 -0.4037296 0.271546 -0.898977 -0.3436616 0.2801473 -0.8849685 -0.3719521 0.3021169 -0.900515 -0.3127269 0.3104805 -0.8898628 -0.3342844 0.3523783 -0.8875541 -0.2967784 0.3325268 -0.9006499 -0.2797425 0.3331861 -0.8850267 -0.3251382 0.3120599 -0.9013831 -0.3002122 0.3038468 -0.8832855 -0.3570489 0.2832205 -0.9005038 -0.3299686 0.254615 -0.8890826 -0.3803989 0.2408921 -0.9004493 -0.362163 0.1707873 -0.909079 -0.3800094 0.174545 -0.9062883 -0.3849359 0.08180826 -0.9410387 -0.3282588 0.1169403 -0.9170857 -0.3811545 0.04369992 -0.9754717 -0.2157435 0.1121444 -0.9372021 -0.3302665 0.03673708 -0.9990152 -0.02488321 0.06412231 -0.9962092 -0.05878603 0.006486654 -0.9999596 -0.006224274 0.01685124 -0.9995407 -0.02518939 -0.006411135 -0.9999747 0.003084719 3.941e-4 -0.9999712 -0.007586121 -0.01820814 -0.9031013 -0.4290413 -0.03382843 -0.9080421 -0.417511 -0.02090251 -0.8992473 -0.436941 -0.02527123 -0.90266 -0.4296118 -0.02544122 -0.9101434 -0.4135116 -0.0144596 -0.899278 -0.4371386 -0.02406436 -0.9255183 -0.3779374 -0.007837831 -0.9096472 -0.4153078 -0.01015609 -0.9325473 -0.3609051 -0.002408087 -0.9253288 -0.379158 -1.95964e-4 -0.9331931 -0.3593754 2.69207e-4 -0.9327709 -0.3604698 2.45261e-4 -0.9319823 -0.3625037 -0.001120448 -0.933146 -0.3594958 -0.005510628 -0.9300172 -0.3674748 -0.007530868 -0.9314656 -0.3637515 -0.05347251 -0.9293251 -0.3653705 -0.04481071 -0.9262985 -0.3741165 -0.01270705 -0.9952268 0.0967592 -0.03157055 -0.9962677 0.08033758 -0.01775789 -0.9994752 0.0270946 -0.02328169 -0.9993767 0.02653986 -0.002181887 -0.9999975 -5.30424e-4 -0.01532971 -0.9998383 -0.009405374 -0.01314747 -0.9998692 -0.009429931 -0.03922861 -0.9988954 -0.025873 0.9165164 0.3692579 -0.1537739 0.3680654 0.9170877 0.1532258 0.987372 0.1566114 0.02386635 0.9664543 0.2495845 0.06060969 0.9891315 0.1419847 0.0382027 0.9873234 0.1529161 0.04253619 0.9894094 0.139052 0.0416373 0.9890341 0.1414088 0.04260689 0.9859603 0.1590346 0.05089563 0.9893915 0.1389067 0.04253959 0.9491924 0.2986972 0.09906506 0.9860555 0.1602815 0.04477125 -0.2099127 0.9215956 0.3264939 0.954777 0.2888276 0.07056701 -0.9183346 0.3623638 0.1592294 0.158396 0.9537277 0.2555667 0.9562438 0.2925073 0.006112396 0.7768988 -0.5968516 -0.2004906 0.6856722 0.7048334 0.1818339 0.9978555 0.06544679 0.001051008 0.6570678 0.7254196 0.2050083 0.7049594 0.6827739 0.191969 0.7314615 0.6522355 0.1988794 0.6550024 0.7223555 0.2217531 0.7080669 0.6716321 0.2180637 0.7211474 0.6589841 0.2137439 -0.03964489 0.9448269 0.3251627 0.6934807 0.6836228 0.2274737 -0.8301616 0.5209454 0.1986145 -0.1216284 0.9356269 0.3313742 -0.9250524 0.344706 0.1595491 -0.8879563 0.4208752 0.1854664 -0.1087345 0.7297829 0.6749769 -0.1007312 0.9945974 0.02508699 -0.1083323 0.6740674 0.7306827 -0.1149891 0.8354136 0.5374586 -0.0270465 0.9907785 0.1327644 -0.03387826 0.9513012 0.3063959 -0.03683108 0.07128745 0.9967757 -0.0372495 0.619345 0.7842348 0.2061033 0.9772589 -0.04986548 0.2048478 0.9649795 -0.1638655 -0.01687055 -0.06198197 0.9979347 0.1713996 0.801404 0.5730393 0.371371 0.9271211 -0.05030208 0.3663611 0.9167321 -0.1593171 0.2172067 0.9726887 -0.0818423 0.205179 0.9754444 -0.08006131 -0.001041054 0.9941 -0.1084627 -0.003308773 0.9966046 -0.08227062 -0.007456183 0.9653831 -0.2607296 -0.01832842 0.9938445 -0.1092582 -0.02516967 0.8004436 -0.5988795 -0.06486183 0.9829284 -0.1721766 -0.26073 0.9646807 -0.03756356 -0.00714904 0.9983414 -0.05712723 -0.2793248 0.9596197 0.03328484 -0.2575873 0.9657527 0.03115463 -0.3380373 0.9344004 0.1123686 -0.334851 0.93557 0.1121767 -0.29172 0.9490829 0.1189166 -0.3467069 0.9300773 0.1214521 -0.1508471 0.9853612 0.07942557 -0.2811547 0.9551535 0.09291988 -0.06495279 0.9971046 0.03954356 -0.1520716 0.9866089 0.05896723 -0.6539103 0.75623 -0.02274864 -0.5363406 0.8430492 -0.04008746 -0.6937384 0.7195252 0.0317896 -0.6647983 0.7465315 0.02709347 -0.6388543 0.7643744 0.08716028 -0.7076966 0.700562 0.09153437 -0.4240021 0.9005454 0.09612572 -0.6376255 0.763248 0.1043381 -0.2088628 0.9758827 0.06347751 -0.4211513 0.9028652 0.08640545 -0.1316061 0.9905225 0.03930819 -0.2027762 0.9776013 0.0563696 -0.1687934 0.9833432 0.06741708 -0.1478809 0.987251 0.05888038 -0.3022449 0.9347101 0.1869895 -0.2656577 0.9498472 0.1649745 -0.481154 0.7952775 0.3688149 -0.490535 0.7863144 0.3756128 -0.7822627 0.02323788 0.6225152 -0.6620623 0.4947506 0.5629347 -0.6362959 0.5327154 0.5579802 -0.6569643 0.4890578 0.5737774 -0.05849879 -0.9901745 -0.1270133 -0.04657799 -0.992348 -0.1143513 -0.1087211 -0.988952 0.100766 -0.08806014 -0.9881938 0.1253734 -0.121807 -0.9516453 0.2820187 -0.1287865 -0.9530123 0.2741929 -0.118702 -0.9268656 0.3561319 -0.1258957 -0.9287317 0.3487231 -0.1281728 -0.9075279 0.3999561 -0.1222209 -0.9054321 0.4065155 -0.1518524 -0.8802543 0.4495477 -0.1368208 -0.8723182 0.4694052 -0.1854301 -0.8438335 0.5035482 -0.1668558 -0.8305785 0.5313178 -0.2157816 -0.8081929 0.5479624 -0.1999549 -0.7959153 0.5714341 -0.2343256 -0.7878445 0.5695548 -0.2236571 -0.7783299 0.5866687 -0.2505379 -0.7746306 0.5806705 -0.2406616 -0.7634437 0.5993628 -0.2719075 -0.7732284 0.5728736 -0.2567475 -0.7553393 0.6029457 -0.2964558 -0.7916272 0.5342662 -0.2729541 -0.7711161 0.5752182 -0.3241026 -0.7951514 0.5125349 -0.3039461 -0.7822549 0.5437777 -0.4674369 -0.7655708 0.4420455 -0.4277171 -0.693318 0.5799727 1.62555e-4 -0.99239 -0.1231338 -4.454e-4 -0.9922635 -0.1241489 -0.01786136 -0.9970011 0.07529902 -0.009236633 -0.9955982 0.09326833 -0.0290811 -0.9622901 0.2704662 -0.0283907 -0.9619107 0.271886 -0.03630965 -0.9392845 0.341213 -0.0321505 -0.9367811 0.3484359 -0.05368155 -0.9284565 0.3675419 -0.03930968 -0.919007 0.3922767 -0.08282434 -0.9128272 0.3998582 -0.06212288 -0.8951259 0.4414638 -0.1223578 -0.888369 0.442526 -0.1005167 -0.8630478 0.4950202 -0.1656263 -0.8548939 0.4916549 -0.146372 -0.8282511 0.5409024 -0.1990116 -0.8265146 0.5265626 -0.1839694 -0.8045661 0.5646492 -0.2245538 -0.8104489 0.5410622 -0.2108803 -0.7902959 0.5752929 -0.2506961 -0.8125854 0.5261716 -0.231398 -0.7912847 0.5659713 -0.2883771 -0.8323338 0.473349 -0.2510946 -0.8117685 0.5272415 -0.3777623 -0.8278912 0.4145984 -0.3092835 -0.8016744 0.5115291 -0.3678145 -0.8718828 0.3233155 -0.3596819 -0.8483156 0.3885738 0.00380969 -0.9927618 -0.1200394 0.002223312 -0.9924011 -0.1230244 -0.00117892 -0.9976446 0.06858605 0.001006722 -0.997274 0.07378119 -0.005440354 -0.9637541 0.2667368 -0.005083382 -0.9635149 0.2676069 -0.01040655 -0.9433721 0.3315733 -0.006754457 -0.9408096 0.3388685 -0.02198988 -0.9385021 0.3445725 -0.01162081 -0.9313164 0.3640258 -0.04189741 -0.9314734 0.3613891 -0.02606952 -0.91876 0.3939549 -0.0708093 -0.9186089 0.3887725 -0.05294889 -0.8997594 0.4331622 -0.1082811 -0.8970576 0.4284424 -0.0921489 -0.8724011 0.4800261 -0.1458427 -0.8712775 0.4686208 -0.1321532 -0.8466291 0.5155141 -0.1775322 -0.8545945 0.4880068 -0.1628262 -0.8323583 0.5297805 -0.2066265 -0.8551701 0.4753836 -0.1856676 -0.8366829 0.5152566 -0.2349788 -0.8743482 0.4246177 -0.2021975 -0.863227 0.4625532 -0.2769287 -0.8938221 0.3526936 -0.2245646 -0.8895547 0.397823 -0.286087 -0.9221708 0.2602985 -0.2508547 -0.92304 0.2916661 -0.2588828 -0.9481678 0.1842762 -0.2451546 -0.9498822 0.1939668 -0.001115202 -0.9927926 -0.1198406 -0.001373708 -0.9927291 -0.1203626 -4.31406e-4 -0.9974354 0.07157254 -0.001604318 -0.9976426 0.06860578 -9.96806e-4 -0.963804 0.2666102 -0.001111268 -0.9638839 0.2663205 -0.003372073 -0.9449178 0.3272903 -0.001464903 -0.943578 0.3311474 -0.008992433 -0.9425209 0.3340262 -0.003744542 -0.9391115 0.3435924 -0.01963895 -0.939665 0.3415319 -0.01033329 -0.9333599 0.3587934 -0.03659808 -0.9332597 0.3573332 -0.02419185 -0.9233288 0.3832475 -0.06109613 -0.9219124 0.3825505 -0.04824209 -0.9062507 0.4199792 -0.09108692 -0.9051283 0.4152662 -0.07999479 -0.8850877 0.4584982 -0.1204772 -0.8924518 0.4347585 -0.1072379 -0.8731166 0.4755706 -0.149046 -0.8928827 0.4249068 -0.1283816 -0.8771401 0.4627565 -0.1736768 -0.9064158 0.3850283 -0.146165 -0.8978921 0.4152418 -0.1951467 -0.9270857 0.3200468 -0.164241 -0.9242676 0.3446075 -0.2091919 -0.949301 0.2346626 -0.1885398 -0.9497689 0.249784 -0.2156877 -0.9626919 0.1634116 -0.2051464 -0.9633556 0.1728036 -0.01539355 -0.9920959 -0.1245346 -0.01349508 -0.9926062 -0.1206272 -0.005075752 -0.9959926 0.08929187 -0.01226449 -0.9973861 0.07120877 -6.10579e-4 -0.9628424 0.2700635 -0.001982033 -0.9637941 0.2666402 -0.001452267 -0.9456674 0.3251327 -3.9043e-4 -0.9449427 0.3272357 -0.003869593 -0.9440714 0.3297187 -0.001524984 -0.9426484 0.3337838 -0.009425222 -0.9433106 0.3317774 -0.004087984 -0.9402304 0.3405148 -0.01903098 -0.9400506 0.3405036 -0.01028394 -0.9349334 0.3546741 -0.03271865 -0.9336017 0.3568158 -0.02181088 -0.9253616 0.3784578 -0.05093616 -0.9236692 0.3797906 -0.03983187 -0.9108921 0.4107179 -0.07145917 -0.915445 0.3960478 -0.0592705 -0.9019277 0.427801 -0.09230935 -0.917373 0.3871768 -0.07519423 -0.9063799 0.415718 -0.1124851 -0.9279098 0.3554302 -0.09090507 -0.9210083 0.3787877 -0.1217584 -0.9428753 0.3100987 -0.1111251 -0.9413234 0.3186874 -0.1166425 -0.9615637 0.2485758 -0.1330533 -0.9624934 0.2364392 -0.1845719 -0.9742549 0.1294629 -0.1400011 -0.9756156 0.1690382 -0.03357875 -0.9902786 -0.1349853 -0.02885818 -0.9917282 -0.1250699 -0.01031672 -0.9924562 0.122165 -0.02508687 -0.9958774 0.08717191 2.02784e-5 -0.9603943 0.2786449 -0.003788948 -0.9628802 0.2699025 0.001011669 -0.9455811 0.3253849 8.95447e-4 -0.945658 0.3251622 0.001152932 -0.9440325 0.3298507 0.001031696 -0.944103 0.329649 -0.001415908 -0.9449092 0.3273298 0.001153349 -0.9435181 0.331319 -0.007828235 -0.94402 0.3297954 -0.001329362 -0.9407445 0.3391136 -0.01340121 -0.9383229 0.3455007 -0.006956815 -0.9348891 0.3548718 -0.01836442 -0.9296718 0.3679311 -0.01203417 -0.9254337 0.3787186 -0.02582556 -0.92381 0.3819794 -0.01826208 -0.9184849 0.3950344 -0.03508096 -0.9276236 0.3718654 -0.02592515 -0.9227159 0.384608 -0.04808253 -0.9389357 0.3407167 -0.03496021 -0.9342483 0.3549056 -0.04934751 -0.9481624 0.3139311 -0.05119699 -0.9486075 0.3122862 -0.0264241 -0.9575935 0.2869088 -0.05942821 -0.9652028 0.2546605 -0.03295445 -0.9885959 -0.1469429 -0.02692645 -0.9904988 -0.1348601 -0.006857633 -0.9892427 0.1461226 -0.01902258 -0.9924797 0.1209228 0.002483189 -0.9593338 0.2822634 6.53523e-4 -0.9603777 0.2787014 0.005449295 -0.9445413 0.3283475 0.003774344 -0.9455249 0.3255282 0.009856641 -0.9417383 0.3362022 0.005480408 -0.9440275 0.3298215 0.01298218 -0.9432498 0.3318303 0.009667396 -0.9449287 0.3271339 0.01438122 -0.9434383 0.3312363 0.01290923 -0.9441687 0.3292095 0.0231772 -0.9345523 0.3550701 0.01542264 -0.938467 0.3450245 0.03411948 -0.9238003 0.3813515 0.02497869 -0.9288896 0.3695136 0.03664201 -0.920814 0.3882766 0.03461545 -0.9219602 0.3857349 0.02125483 -0.933562 0.3577851 0.03580951 -0.9263222 0.3750265 -0.01474481 -0.9537724 0.300168 0.02063971 -0.9397221 0.3413159 -0.03884756 -0.9584811 0.2824975 -0.01489889 -0.9501361 0.3114795 -0.04746854 -0.9611147 0.2720394 -0.0396794 -0.9566681 0.2884642 -0.02074038 -0.9890521 -0.1461021 -0.02088248 -0.989013 -0.1463467 -0.002547562 -0.9874338 0.1580131 -0.009852766 -0.9892765 0.145723 0.00403285 -0.9587582 0.2841942 0.002746939 -0.9593255 0.2822889 0.01048433 -0.9421501 0.3350272 0.005305528 -0.944547 0.3283334 0.02098399 -0.9376354 0.3469864 0.01052474 -0.9417356 0.3361894 0.03229558 -0.9382975 0.3443182 0.02028739 -0.943121 0.33183 0.047544 -0.9355036 0.3501036 0.03156405 -0.9426965 0.3321553 0.07747834 -0.9184339 0.3879128 0.0483663 -0.9327742 0.3572018 0.099128 -0.9078845 0.407332 0.07716941 -0.9192597 0.3860139 0.08744251 -0.9186288 0.3853248 0.0970025 -0.9140895 0.3937398 0.03309822 -0.9492779 0.3126916 0.08534693 -0.9301686 0.3570747 -0.01305973 -0.9697352 0.2438102 0.03528505 -0.9570091 0.2879039 -0.04898607 -0.9688078 0.242924 -0.02077484 -0.9607848 0.276516 -0.07789456 -0.9666159 0.2441029 -0.05826067 -0.9596332 0.2751542 -0.116576 -0.9703214 0.2118644 -0.07889693 -0.9656985 0.2473896 -0.1462917 -0.9786096 0.1446443 -0.1075395 -0.9771014 0.183598 -0.08890759 -0.9924809 0.08412528 -0.1529265 -0.9869042 0.05132007 -0.07700663 -0.9966485 0.027601 -0.110571 -0.9938538 0.005373775 -0.07016968 -0.9972484 -0.02391874 -0.09712934 -0.9945459 -0.03800743 -0.03857135 -0.9989684 -0.02397173 -0.07703882 -0.9961389 -0.04209995 -0.0121662 -0.9900795 -0.139981 -0.01782935 -0.989164 -0.1457284 -4.77836e-4 -0.9867408 0.1623035 -0.005513846 -0.9874926 0.1575695 0.00408709 -0.9585096 0.2850312 0.002860248 -0.9588051 0.2840504 0.01339596 -0.9402577 0.3402001 0.00520271 -0.9424573 0.3342861 0.0287761 -0.9347981 0.3540121 0.01370948 -0.9376468 0.3473193 0.04617923 -0.9343739 0.3532888 0.02803337 -0.9384443 0.3442913 0.07410007 -0.926756 0.3682832 0.04577976 -0.9356821 0.3498619 0.1220742 -0.9014343 0.4153482 0.07794636 -0.9183604 0.3879933 0.1364986 -0.8976323 0.4190757 0.1210457 -0.9037194 0.4106569 0.07874178 -0.9276164 0.3651404 0.1311731 -0.9124247 0.3876531 0.003532946 -0.9583346 0.2856265 0.07899963 -0.9498705 0.3024982 -0.02254229 -0.9744564 0.223443 0.01859986 -0.9741588 0.2250972 -0.05497771 -0.9744327 0.2178501 -0.02511829 -0.9728032 0.2302675 -0.09922909 -0.9728563 0.2090561 -0.06332623 -0.9685288 0.240711 -0.1427408 -0.9750505 0.1700048 -0.09956932 -0.9725298 0.2104083 -0.1483584 -0.9793462 0.137371 -0.1391316 -0.9794886 0.1457554 -0.1027218 -0.9889315 0.1070648 -0.145233 -0.986348 0.07762092 -0.07570189 -0.9958933 0.0496571 -0.1188637 -0.9927104 0.01994264 -0.04851901 -0.9988212 0.001515924 -0.09631311 -0.9950402 -0.02487421 -0.01394379 -0.9998971 -0.003408551 -0.05691254 -0.9980829 -0.02432256 0.003607273 -0.9174987 0.3977226 0.02924668 -0.9141625 0.4042915 -0.1510202 -0.9289819 0.3379135 -0.08088296 -0.9457136 0.3147758 -0.2606998 -0.9177302 0.2996783 -0.1381313 -0.9448303 0.297011 -0.3289278 -0.9205938 0.210508 -0.2508915 -0.940634 0.228607 -0.3114387 -0.9373372 0.1562207 -0.334613 -0.9303674 0.1498357 -0.284116 -0.9497955 0.1310214 -0.319757 -0.9398432 0.1202095 -0.2599349 -0.9569814 0.1289208 -0.2874674 -0.950303 0.1195275 -0.238751 -0.961342 0.1371846 -0.2597995 -0.9569575 0.1293704 -0.2177584 -0.9646015 0.1487463 -0.2376469 -0.9610656 0.140986 -0.1911525 -0.9682489 0.1611055 -0.217104 -0.9643827 0.1511022 -0.1467893 -0.9747797 0.1681002 -0.19348 -0.9692962 0.1517581 -0.07680797 -0.9860469 0.1476892 -0.1536054 -0.9798154 0.1279353 -0.0336039 -0.9964625 0.07702744 -0.07822501 -0.9942929 0.07254481 -0.01010572 -0.9967548 0.07986056 -0.002608358 -0.9956993 0.09260779 -0.04164993 -0.9893239 0.1396555 -0.009988307 -0.98127 0.1923782 -0.1027618 -0.981338 0.16253 -0.04912716 -0.9654346 0.2559739 -0.1871369 -0.9651077 0.1831582 -0.120002 -0.9460636 0.3009372 -0.297579 -0.9297911 0.2166457 -0.2126623 -0.9192443 0.3313074 -0.3808824 -0.9022576 0.2021386 -0.3120838 -0.9053252 0.2880798 -0.4423471 -0.8800659 0.1726654 -0.386572 -0.8913981 0.2365832 -0.4717832 -0.867524 0.1575527 -0.4436371 -0.8752173 0.1928234 -0.4726864 -0.8634982 0.1758937 -0.4717705 -0.8637478 0.1771224 -0.463172 -0.8618176 0.2067417 -0.4721065 -0.8597815 0.1946569 -0.4492775 -0.8604624 0.2403209 -0.4622853 -0.8582687 0.2228609 -0.4252495 -0.8606886 0.2799609 -0.4486672 -0.8582208 0.2493092 -0.379113 -0.8692668 0.3172519 -0.4264356 -0.8672805 0.2568607 -0.3088476 -0.8953292 0.3209345 -0.3788098 -0.8971799 0.2270937 -0.2351873 -0.9282256 0.2882434 -0.2944836 -0.9342887 0.2009578 -0.1479108 -0.9331585 0.3276241 -0.2121821 -0.950579 0.226668 -0.04785007 -0.9298108 0.3649141 -0.1048603 -0.9603418 0.2583561 0.02382493 -0.9753916 0.2191886 0.03319519 -0.9701474 0.2402339 -0.02064818 -0.9895939 0.1423996 0.03184854 -0.978735 0.2026409 -0.03148257 -0.9902101 0.1359887 -0.02083963 -0.9894362 0.1434642 -0.01769852 -0.9989737 0.04169583 0.006563305 -0.9966028 0.08209598 -0.07403022 -0.9958949 0.05208563 -0.02403265 -0.9899134 0.1396208 -0.1484543 -0.9881569 0.03882294 -0.08923524 -0.982918 0.1609641 -0.2366582 -0.9705002 0.04606807 -0.1754068 -0.967779 0.1806552 -0.3426154 -0.9359303 0.08154255 -0.2688563 -0.9407066 0.206851 -0.4258928 -0.8989551 0.1024465 -0.361768 -0.9111391 0.1973561 -0.4695585 -0.8749225 0.1184294 -0.4321885 -0.8853747 0.1712453 -0.4781778 -0.8660174 0.1461508 -0.4703391 -0.868308 0.1575518 -0.472018 -0.8622187 0.1837885 -0.4776822 -0.8608284 0.175483 -0.4612378 -0.8595123 0.2202236 -0.4710811 -0.8577069 0.2059651 -0.4474452 -0.8566786 0.2566996 -0.4599195 -0.8551291 0.2392245 -0.4195684 -0.8529383 0.3105782 -0.4454105 -0.8512617 0.2774221 -0.3440933 -0.8524129 0.3936905 -0.4195569 -0.8529067 0.3106806 -0.2195584 -0.8719235 0.4376569 -0.3489512 -0.8839473 0.3112397 -0.1381626 -0.9273834 0.3476654 -0.1754538 -0.9349129 0.3084701 -0.07196295 -0.9092487 0.4099859 -0.1262324 -0.9336003 0.3353444 0.05849009 -0.8487957 0.5254759 -0.04410564 -0.9296048 0.3659095 0.1659846 -0.9478328 0.2721439 0.1687093 -0.9446262 0.2814582 0.08440703 -0.9959347 -0.03145694 0.2116005 -0.9625803 0.1693059 -0.0439558 -0.9971852 0.06074243 0.07517546 -0.9877122 0.1370158 -0.02109426 -0.9997123 -0.0114209 0.03241521 -0.9987572 0.03786134 -0.1040779 -0.9942011 -0.02705907 -0.0300619 -0.9985306 0.04508841 -0.1913192 -0.9800519 -0.05380696 -0.1167341 -0.9926164 0.03295248 -0.283091 -0.9579406 -0.04700422 -0.212444 -0.9762881 0.04158234 -0.3805463 -0.9247469 -0.005280435 -0.3068634 -0.9488868 0.07381677 -0.4481738 -0.892869 0.04387879 -0.3941637 -0.9137958 0.09804159 -0.4738011 -0.87538 0.09603345 -0.4524126 -0.8840299 0.117533 -0.4759207 -0.8675483 0.1444282 -0.4741758 -0.8682005 0.1462374 -0.4702761 -0.8621138 0.1886806 -0.4750846 -0.8605682 0.1836223 -0.4609203 -0.8576577 0.2279818 -0.4687283 -0.8555727 0.2197487 -0.4467709 -0.853662 0.2676885 -0.4584532 -0.8511856 0.2555459 -0.3804675 -0.8508052 0.3624572 -0.4404979 -0.8440069 0.3059639 -0.07080835 -0.8096985 0.5825587 -0.3745061 -0.843906 0.3841456 0.2787301 -0.7425549 0.6090337 -0.07954066 -0.8773459 0.4732205 0.4500086 -0.7690104 0.4539991 0.7591634 -0.6137473 0.2167607 0.4777904 -0.7565971 0.4464047 0.6573375 -0.09650772 0.7473914 0.6524212 -0.3798012 0.6558184 0.7010161 -0.6691099 0.2467154 0.7070053 -0.6630215 0.2460613 -0.02685779 -0.955734 -0.2930036 0.0431087 -0.9771355 -0.2082016 -0.08456408 -0.959464 -0.2688457 -0.03393882 -0.9774513 -0.2084161 -0.1215369 -0.9651021 -0.2319628 -0.08917117 -0.9773392 -0.1919809 -0.1548199 -0.9709963 -0.1822009 -0.1255424 -0.9813666 -0.1454604 -0.1894145 -0.9736717 -0.1268289 -0.1586859 -0.9833948 -0.08805453 -0.224695 -0.972095 -0.06740731 -0.1931546 -0.9807834 -0.02748662 -0.2568457 -0.966451 0.001690983 -0.2280729 -0.9729038 0.03796178 -0.2652636 -0.9592018 0.09781223 -0.2582654 -0.9601933 0.1064324 -0.231668 -0.9482851 0.2169917 -0.2632316 -0.9476919 0.1805251 0.04400914 -0.8492078 0.5262217 -0.2273704 -0.9323149 0.2812322 0.06710749 -0.8783374 0.4733077 -0.002916336 -0.9125801 0.4088876 0.4986566 -0.4102755 0.7635548 0.2264113 -0.6726326 0.7044879 0.04405516 -0.9350239 -0.3518374 0.08037412 -0.9503359 -0.3006691 0.01243215 -0.9488232 -0.3155629 0.03931069 -0.9607104 -0.2747551 -0.01548987 -0.9614794 -0.2744404 0.008359551 -0.9715441 -0.2367116 -0.04612028 -0.9720939 -0.2300142 -0.01947104 -0.9821233 -0.1872292 -0.08030313 -0.9802235 -0.1808682 -0.05019074 -0.9899595 -0.1321408 -0.1133915 -0.9862391 -0.1203115 -0.08386802 -0.993838 -0.07247382 -0.115957 -0.9932471 -0.003763914 -0.1143466 -0.9934402 -0.001208782 -0.004684746 -0.9658284 0.2591401 -0.1098337 -0.9882717 0.1060925 0.1768505 -0.8474303 0.5005856 -0.003850579 -0.9641318 0.2653962 0.4618275 -0.357388 0.8117816 0.1777524 -0.8513656 0.4935393 0.1602572 -0.9175868 -0.3638026 0.1705614 -0.9210762 -0.3500393 0.1445141 -0.9299921 -0.3379802 0.1588349 -0.9353651 -0.3160121 0.1233884 -0.9429051 -0.3093631 0.1422917 -0.9498609 -0.2784195 0.09576982 -0.9561018 -0.2769432 0.1204474 -0.9643397 -0.2356724 0.06300705 -0.9696723 -0.2361476 0.09264004 -0.9781497 -0.1861211 0.04305183 -0.9870175 -0.1547356 0.06231802 -0.9905381 -0.1222729 0.1268629 -0.9844191 0.1217581 0.05350404 -0.9985676 5.14949e-4 0.3688575 -0.7146466 0.5943269 0.1567848 -0.94762 0.2782716 0.2627719 -0.8988674 -0.3506969 0.2552517 -0.8970924 -0.3606548 0.2612134 -0.9034488 -0.3399235 0.2627648 -0.9038912 -0.3375434 0.2518296 -0.9110326 -0.3264991 0.260816 -0.913657 -0.3117787 0.2338293 -0.921862 -0.3090215 0.2511246 -0.9265117 -0.2802008 0.2104268 -0.9375397 -0.2770195 0.234278 -0.9428681 -0.2368829 0.2143054 -0.9633898 -0.1611001 0.2194745 -0.9636617 -0.1522731 0.3773422 -0.8689006 0.3203511 0.257076 -0.961385 0.098239 0.321874 -0.8890856 -0.3254597 0.304214 -0.8864717 -0.3487433 0.33074 -0.8860228 -0.3249225 0.3216696 -0.8841766 -0.3387633 0.3334272 -0.8863095 -0.3213752 0.3307279 -0.8857156 -0.3257716 0.3302997 -0.8905838 -0.3126702 0.3339422 -0.8913277 -0.3066229 0.3267956 -0.9021637 -0.2816121 0.3344202 -0.9033596 -0.268523 0.3712083 -0.9213786 -0.115178 0.350391 -0.9239446 -0.1534681 0.3530907 -0.8859348 -0.3007431 0.3332039 -0.8851429 -0.3248034 0.364919 -0.8792266 -0.3062595 0.3520918 -0.8780269 -0.3241915 0.372405 -0.875664 -0.3074528 0.3642024 -0.8746291 -0.3199697 0.3783023 -0.8762077 -0.2985755 0.3723157 -0.8753572 -0.308433 0.3950734 -0.885181 -0.2457066 0.3837535 -0.884059 -0.2667831 0.3703563 -0.8842005 -0.2846503 0.3520493 -0.8863282 -0.3008052 0.3814013 -0.8768782 -0.2926055 0.3681349 -0.8779432 -0.3060924 0.3908459 -0.8722438 -0.2939901 0.3798918 -0.8726605 -0.3068321 0.4157016 -0.8719616 -0.2586026 0.3905991 -0.8716923 -0.2959474 0.5256429 -0.8486955 0.05844318 0.4198812 -0.8787821 -0.2268084 -0.2981425 -0.9463537 -0.124602 -0.250445 -0.9629549 -0.09997653 -0.3588903 -0.9240681 0.1315139 -0.3394881 -0.9298589 0.1418116 -0.3374437 -0.8991185 0.278779 -0.3701665 -0.89135 0.2616716 -0.3018152 -0.8865623 0.3505924 -0.3359774 -0.8811161 0.3327966 -0.2789427 -0.8696777 0.407249 -0.2997878 -0.8681247 0.3955842 -0.2674852 -0.8417421 0.4689586 -0.2783275 -0.8419778 0.4621766 -0.2662963 -0.8049308 0.5302575 -0.2689719 -0.8051808 0.5285244 -0.2669155 -0.7768815 0.5702732 -0.2677655 -0.7769832 0.5697357 -0.2682585 -0.7645944 0.5860316 -0.2677389 -0.7644934 0.5864008 -0.2756551 -0.7499877 0.6012759 -0.2708677 -0.7484297 0.6053791 -0.2962054 -0.7355141 0.6093288 -0.2819513 -0.7291761 0.623543 -0.3300297 -0.7384307 0.5880481 -0.3031701 -0.721925 0.6220227 -0.345941 -0.7564878 0.5550236 -0.3443217 -0.7204875 0.6019472 0.3830988 -0.8807353 -0.2784613 0.3656868 -0.8860617 -0.2848994 0.3926033 -0.8740262 -0.2862535 0.3784056 -0.878098 -0.2928365 0.4015061 -0.8695096 -0.2876562 0.3902235 -0.8724954 -0.2940707 0.4049007 -0.8750514 -0.2652179 0.4086202 -0.8743851 -0.2616877 0.4324645 -0.89414 -0.1161376 0.4632499 -0.8846732 -0.05246698 0.5314753 -0.6819683 0.5024473 0.5468911 -0.5998479 0.5840315 0.5273544 -0.323993 0.7854463 0.5270299 -0.3813111 0.7595007 0.5140514 -0.2055852 0.8327581 0.514366 -0.2161346 0.8298876 0.9969195 0.07333236 -0.02781873 0.9855659 0.1659177 0.03363275 0.9983174 0.05681353 0.01160448 0.9976966 0.06576222 0.01664543 0.9984027 0.05451732 0.01483136 0.9982836 0.05638438 0.01583194 0.9983437 0.05514407 0.0164051 0.9983929 0.05436277 0.01600676 0.99758 0.06649386 0.02032113 0.9983482 0.05550175 0.01485353 0.9916025 0.1245479 0.03482049 0.9975156 0.06930518 0.0126248 0.9134302 0.3954344 0.09631699 0.9914086 0.1301031 0.01349842 0.1079776 0.960331 0.2571096 0.9316424 0.3605664 0.04510378 -0.9122866 0.4088726 -0.02358841 -0.9116509 0.4102807 -0.02371853 -0.9368572 0.3491795 0.01929688 -0.9214891 0.3880601 0.01634818 -0.9075973 0.4173529 0.04564881 -0.9337635 0.3549228 0.04599475 -0.7654519 0.6411647 0.0546925 -0.9027929 0.4266722 0.05399966 -0.487511 0.8720195 0.04376178 -0.7607584 0.6460343 0.06234097 -0.3620374 0.9306749 0.05266165 -0.5000511 0.8624858 0.07789319 -0.4419661 0.885662 0.1423687 -0.4299318 0.8922611 0.1379458 -0.5513123 0.7779781 0.3013384 -0.5821598 0.7479455 0.3188535 -0.6521664 0.6016873 0.4611414 -0.6915671 0.5328294 0.4876759 -0.7612177 -0.2998287 0.5750221 -0.7217873 0.4300552 0.5422875 -0.4480584 -0.5958563 0.6664825 -0.5802089 -0.4424502 0.6838096 -0.3212727 -0.7183685 0.6170337 -0.5438646 -0.499606 0.6742442 -0.3502233 -0.7061768 0.615352 -0.5563187 -0.4910098 0.6703872 -0.750343 -0.09660112 0.6539523 -0.5905084 -0.4330709 0.6809916 -0.7692191 0.01311933 0.6388505 -0.5651587 0.8077204 0.1678792 -0.4826873 -0.6051719 0.6330719 -0.3989727 -0.6417772 0.6549373 -0.6221145 -0.3989896 0.6736326 -0.4386854 -0.5984956 0.6703419 -0.5640923 -0.4599831 0.6857227 -0.5076067 -0.5248436 0.6832823 -0.4428157 -0.5942549 0.6713981 -0.5301041 -0.5021556 0.6832492 -0.4276117 -0.6157957 0.6617732 -0.5615618 -0.4674891 0.6827168 -0.5462624 -0.4882979 0.6805606 -0.5974673 -0.4172917 0.6847631 -0.7919336 0.110805 0.6004695 -0.6336002 -0.3469631 0.6914966 -0.3877336 -0.6655932 0.63769 -0.3330432 -0.6861893 0.6467044 -0.4903249 -0.5650799 0.6635257 -0.3803079 -0.6482318 0.6596677 -0.5857186 -0.4547212 0.6709414 -0.4494474 -0.5864338 0.673864 -0.5495627 -0.4850839 0.6802018 -0.4967207 -0.5383223 0.680792 -0.5542817 -0.4743251 0.68395 -0.5292655 -0.501487 0.6843895 -0.5875568 -0.4282884 0.6865465 -0.5564983 -0.4667216 0.6873724 -0.6471123 -0.3314251 0.6865881 -0.598624 -0.4034936 0.6919844 -0.6602657 -0.298543 0.6891455 -0.632691 -0.3394673 0.6960345 -0.669453 -0.2718579 0.691322 -0.6550215 -0.2948625 0.6957033 -0.6867761 -0.2295817 0.6896601 -0.6853862 -0.232171 0.6901757 -0.7191492 -0.1473455 0.6790536 -0.7246865 -0.1355869 0.6756078 -0.7406019 -0.08274555 0.6668299 -0.7477329 -0.06696319 0.6606146 -0.7548255 -0.03274589 0.6551077 -0.7597565 -0.02228933 0.6498256 -0.7614818 -0.007521569 0.6481428 -0.763462 -0.003721415 0.6458423 -0.7636702 0.004563331 0.6455906 -0.7637954 0.004837989 0.6454403 -0.763007 0.02062457 0.6460611 -0.7625874 0.01892602 0.6466084 -0.7541431 0.09694594 0.6495151 -0.7555872 0.04297649 0.6536368 -0.7537536 -0.02981895 0.6564805 -0.7546362 0.03297376 0.6553145 -0.751536 0.0609436 0.656871 -0.7520106 0.08335334 0.6538596 -0.3324094 -0.7035362 0.6281249 -0.3197003 -0.7069787 0.6308509 -0.4899126 -0.601859 0.6306753 -0.3711182 -0.6730466 0.6397497 -0.6753524 -0.4132667 0.6108272 -0.4296944 -0.6256802 0.651066 -0.6491266 -0.4209277 0.6336045 -0.4883868 -0.5704364 0.6603642 -0.6408561 -0.4131167 0.6470225 -0.5188636 -0.5338523 0.6676694 -0.6511867 -0.3824551 0.6555028 -0.5397394 -0.5040593 0.6742445 -0.6757441 -0.3263311 0.6609675 -0.5813748 -0.4464549 0.6802069 -0.6772581 -0.3043613 0.66984 -0.6280619 -0.3732488 0.6828057 -0.7020027 -0.2444107 0.6689212 -0.6671172 -0.3012749 0.6813134 -0.7225013 -0.1861031 0.6658511 -0.7051877 -0.2195751 0.6741641 -0.7467151 -0.1092854 0.6561046 -0.7437987 -0.1160936 0.6582444 -0.7595466 -0.0576387 0.6478943 -0.7646076 -0.04496383 0.6429259 -0.7689764 -0.0185126 0.6390092 -0.7712669 -0.01274055 0.6363844 -0.7720171 -0.002317547 0.6355976 -0.7716404 -0.003231227 0.6360508 -0.7716339 0.005549907 0.6360428 -0.7701557 0.001197934 0.6378548 -0.7693026 0.01912397 0.6385983 -0.768426 0.01406663 0.6397841 -0.7664822 0.04526883 0.6406683 -0.7661784 0.03355318 0.6417514 -0.7263287 0.2826035 0.6265636 -0.7598735 0.06625682 0.6466857 -0.7641523 0.01708662 0.6448097 -0.7628275 0.06831783 0.6429829 -0.7636044 0.05805164 0.6430696 -0.7602611 0.1145427 0.6394395 -0.3307473 -0.7258607 0.6031023 -0.3289766 -0.7262389 0.6036154 -0.5375238 -0.6174771 0.5742738 -0.3978523 -0.6894889 0.6052426 -0.7398698 -0.4234209 0.5227882 -0.437937 -0.6569843 0.6136634 -0.7280085 -0.4070432 0.5516517 -0.4872086 -0.6119347 0.6230279 -0.7042954 -0.4085004 0.5805991 -0.5268531 -0.5680259 0.6322757 -0.6969254 -0.3923949 0.6002677 -0.5606222 -0.5254431 0.6400097 -0.7270305 -0.3251212 0.6047503 -0.6096876 -0.4611596 0.6446805 -0.7425336 -0.2721804 0.6120144 -0.656997 -0.3872655 0.6468232 -0.7621389 -0.2056363 0.6138877 -0.6986409 -0.3076492 0.6459512 -0.775751 -0.1442811 0.6143236 -0.745104 -0.2040372 0.6349716 -0.7915068 -0.07254976 0.6068391 -0.7826893 -0.09308552 0.6154125 -0.7980499 -0.02756899 0.6019604 -0.7981888 -0.02721613 0.6017924 -0.8009758 -0.005525946 0.5986713 -0.8003035 -0.007037162 0.599554 -0.8005563 -8.22485e-4 0.5992571 -0.7978127 -0.006774842 0.6028674 -0.7976331 0.001977562 0.6031398 -0.7933365 -0.009403109 0.6087107 -0.7921607 0.01380741 0.6101565 -0.7895538 -8.02031e-4 0.613681 -0.7878671 0.03277677 0.6149725 -0.7873446 0.01873594 0.6162285 -0.7843088 0.06950956 0.6164643 -0.785018 0.04686486 0.6176977 -0.7854052 0.04032415 0.6176673 -0.7847024 0.0640819 0.6165515 -0.7876098 0.005852758 0.6161465 -0.7856185 0.09587419 0.611238 -0.3466414 -0.7387918 0.5779502 -0.3541514 -0.7371208 0.5755257 -0.531435 -0.653795 0.5386363 -0.4661351 -0.6854542 0.5593484 -0.6879862 -0.5338779 0.4915785 -0.5108394 -0.6537458 0.5582648 -0.7345422 -0.4729012 0.4866337 -0.5338587 -0.6286071 0.5655511 -0.7472919 -0.4375165 0.5001341 -0.5725453 -0.5872453 0.572132 -0.7594305 -0.3978356 0.514774 -0.6193035 -0.5328561 0.5766521 -0.7905977 -0.3256418 0.518568 -0.6727656 -0.4617062 0.5781123 -0.8059587 -0.268011 0.5278264 -0.7155255 -0.3896352 0.5798344 -0.8255115 -0.1937305 0.5300936 -0.7645033 -0.2944704 0.57343 -0.8430662 -0.1124946 0.5259129 -0.8169991 -0.1676648 0.5517255 -0.8535715 -0.04277116 0.5192171 -0.843783 -0.06704348 0.5324805 -0.854088 -0.008510947 0.5200591 -0.8500135 -0.01808112 0.5264505 -0.8515688 -5.19528e-5 0.5242429 -0.8489077 -0.005662918 0.5285109 -0.8489139 -0.005278825 0.5285049 -0.8457678 -0.01158517 0.5334254 -0.8457624 -0.01144647 0.5334371 -0.8409085 -0.02322262 0.540679 -0.8404399 -0.005432665 0.5418776 -0.8368272 -0.02355766 0.5469601 -0.8360381 0.01266658 0.5485252 -0.8350375 -0.005661308 0.5501639 -0.8331696 0.04479908 0.5512002 -0.8333347 0.03227722 0.5518257 -0.8315553 0.06154233 0.5520222 -0.8312175 0.06943631 0.5515941 -0.8228449 0.1431891 0.5499302 -0.8156867 0.1956587 0.5444016 -0.3696606 -0.7431785 0.5577068 -0.3855344 -0.7390329 0.5524433 -0.5424593 -0.6632934 0.5155384 -0.5424256 -0.6633322 0.5155239 -0.6549718 -0.5872504 0.4755512 -0.6139659 -0.6154407 0.4942457 -0.7104743 -0.5370333 0.4547764 -0.6386222 -0.5932444 0.4901254 -0.7616907 -0.4786687 0.4366962 -0.6721437 -0.5588839 0.4856662 -0.8085825 -0.4100632 0.4219511 -0.712331 -0.5105498 0.4815843 -0.8485634 -0.3313658 0.4124764 -0.7549608 -0.4484732 0.4784414 -0.8662657 -0.2723929 0.4187911 -0.7940707 -0.3784648 0.475622 -0.8928453 -0.1813418 0.4122409 -0.8527575 -0.2585198 0.4538416 -0.9136732 -0.08065581 0.3983666 -0.8975142 -0.1237448 0.4232676 -0.917779 -0.02239787 0.3964593 -0.9106289 -0.04447066 0.4108253 -0.9148839 -0.003174543 0.403705 -0.911033 -0.0138697 0.4121002 -0.9114969 -9.57742e-4 0.4113061 -0.9083225 -0.008637845 0.4181814 -0.90836 -0.01145088 0.4180323 -0.9056302 -0.01785945 0.4236922 -0.9060299 -0.0280084 0.4222859 -0.9039883 -0.0342887 0.4261801 -0.9039896 -0.03435832 0.4261719 -0.9020729 -0.04573678 0.4291535 -0.9023021 -0.02070355 0.4306069 -0.9015366 -0.03203999 0.431515 -0.90086 0.02437144 0.4334251 -0.9008329 0.01339727 0.4339594 -0.8974766 0.07348895 0.4348968 -0.8978423 0.06625902 0.4353035 -0.8550488 0.2967337 0.4252536 -0.8597924 0.2784306 0.428058 -0.4227815 -0.7494265 0.5095252 -0.4226645 -0.7494615 0.5095707 -0.633476 -0.6273328 0.452948 -0.5959448 -0.6512542 0.4698062 -0.7128875 -0.5595632 0.4227063 -0.6820752 -0.5844532 0.4395316 -0.7397852 -0.531799 0.4121987 -0.7296366 -0.5409854 0.4182885 -0.7816229 -0.4863839 0.3905078 -0.7780069 -0.4901573 0.3930029 -0.8320365 -0.4224522 0.359513 -0.8212385 -0.4357327 0.368381 -0.8795191 -0.3464021 0.3262696 -0.8596933 -0.37606 0.3456968 -0.9163228 -0.2668296 0.2985872 -0.9027903 -0.2928914 0.3149356 -0.9538103 -0.1511859 0.2595937 -0.9457995 -0.1743454 0.2739835 -0.9708599 -0.05088019 0.2341847 -0.9647674 -0.07774811 0.2513547 -0.9716686 -0.006868779 0.2362479 -0.9678928 -0.0268107 0.2499296 -0.9689186 -0.001322209 0.2473766 -0.9668747 -0.01078444 0.2550237 -0.9669141 -0.006538569 0.2550189 -0.9648507 -0.0144481 0.2624014 -0.9649102 -0.0202943 0.2617949 -0.9632174 -0.0265159 0.2674122 -0.9634336 -0.04089975 0.2648075 -0.9638728 -0.03852188 0.263563 -0.9635534 -0.05799549 0.2611541 -0.9644281 -0.04978883 0.2596139 -0.96454 -0.04655086 0.2597991 -0.9650755 -0.03784924 0.2592236 -0.9653988 0.009047508 0.2606213 -0.9653314 9.35546e-4 0.2610258 -0.9622361 0.07334882 0.2621482 -0.9626942 0.06526756 0.2626029 -0.8914119 0.3767369 0.2519015 -0.8898093 0.3809111 0.2512894 -0.4749339 -0.7632098 0.4381193 -0.4735478 -0.7637625 0.4386566 -0.7142307 -0.5940507 0.3701058 -0.653169 -0.6425659 0.400599 -0.7897285 -0.5097976 0.3412265 -0.7381673 -0.5617389 0.3735754 -0.8155009 -0.4739255 0.3321942 -0.7980448 -0.4940713 0.3449902 -0.8472231 -0.4288432 0.3135389 -0.8569853 -0.4154891 0.3048686 -0.882063 -0.3750085 0.2851905 -0.906349 -0.3344023 0.2582764 -0.9173787 -0.3118169 0.2473593 -0.9465979 -0.2488654 0.204984 -0.9571648 -0.2178009 0.1907836 -0.9789032 -0.145493 0.1434585 -0.9859362 -0.1067102 0.1286196 -0.9917826 -0.07118946 0.106299 -0.9946725 -0.03494572 0.09698128 -0.9949293 -0.03215599 0.09529805 -0.9957791 -0.002901792 0.09173643 -0.9951712 -0.01234591 0.09737586 -0.9952705 -0.002259314 0.09711641 -0.9947716 -0.009067893 0.1017215 -0.9947239 -0.01430535 0.1015864 -0.9942135 -0.01933014 0.1056692 -0.9940195 -0.03019833 0.1049446 -0.9935865 -0.03379911 0.1079051 -0.993245 -0.0453906 0.1067906 -0.9934709 -0.0429064 0.1057114 -0.9928584 -0.05700379 0.1047992 -0.9938972 -0.04054242 0.1025899 -0.9939089 -0.04023545 0.1025983 -0.9947079 -0.01661241 0.1013914 -0.9948163 0.001853883 0.1016713 -0.9948172 0.006339132 0.1014821 -0.9925334 0.06694269 0.1019626 -0.9924028 0.06898647 0.1018706 -0.8959298 0.4335604 0.09661859 -0.91828 0.3828784 0.1008277 -0.5164602 -0.7722932 0.3699086 -0.5274303 -0.7669137 0.3655967 -0.7504533 -0.5873996 0.302955 -0.7155514 -0.6204559 0.3209685 -0.8332241 -0.4831755 0.2688477 -0.8054581 -0.5181154 0.2877392 -0.8721951 -0.4210612 0.2489643 -0.8663032 -0.4301216 0.2539967 -0.9081182 -0.3544931 0.2228366 -0.9181567 -0.3350481 0.2114974 -0.9387003 -0.2868121 0.1912606 -0.9621306 -0.2248981 0.1540315 -0.9650903 -0.2148174 0.1498479 -0.9886353 -0.1198027 0.09081715 -0.9888156 -0.1186397 0.09037929 -0.9977223 -0.04824513 0.047145 -0.9975131 -0.05159562 0.04801815 -0.9993953 -0.01884114 0.02922749 -0.9993777 -0.0196079 0.02932494 -0.999696 -0.007952392 0.02334022 -0.9997222 -0.003825485 0.02325993 -0.9997298 -0.003294408 0.02301359 -0.9997241 -0.005032002 0.02294719 -0.9997087 -0.005947172 0.02339577 -0.9995629 -0.01887297 0.02275806 -0.9995821 -0.01827824 0.0223993 -0.9991226 -0.03579592 0.0217452 -0.9991021 -0.03620022 0.02201288 -0.998536 -0.04955655 0.02168345 -0.9981054 -0.05656051 0.02422219 -0.9983171 -0.05264151 0.02432572 -0.9977132 -0.06265497 0.02535575 -0.9992347 -0.02897477 0.02627921 -0.9994605 -0.02000689 0.02604568 -0.9996491 -0.001081287 0.0264703 -0.9993997 0.02289009 0.0260083 -0.9979075 0.05891263 0.02664524 -0.996985 0.07298344 0.02635234 -0.9273402 0.3729141 0.03123039 -0.9638559 0.2642542 0.03393334 -0.5595992 -0.7696522 0.3073829 -0.5874429 -0.7530227 0.2964249 -0.779965 -0.5762336 0.2441505 -0.7743851 -0.5824761 0.2470818 -0.8644531 -0.4579088 0.207462 -0.8630266 -0.4601255 0.2084938 -0.9087629 -0.3761649 0.1806932 -0.9189426 -0.3555107 0.1707533 -0.9448224 -0.2917054 0.1490592 -0.9625385 -0.2413029 0.1236636 -0.974687 -0.1956877 0.1081284 -0.9901238 -0.1219034 0.069242 -0.9921141 -0.1073447 0.06470525 -0.9984959 -0.04565286 0.03036117 -0.998623 -0.04318934 0.0297805 -0.9998203 -0.01381629 0.01297712 -0.9997759 -0.01645386 0.01332366 -0.9999691 -0.004250884 0.006620824 -0.9999556 -0.006615102 0.006722688 -0.9999905 -0.001401841 0.00413531 -0.9999896 -0.00196737 0.004126071 -0.9999937 -5.65569e-4 0.003518998 -0.999983 -0.004836499 0.003304362 -0.9999936 -0.002689659 0.002383112 -0.9998405 -0.01779288 0.001575231 -0.9999176 -0.01280814 -9.51156e-4 -0.9993348 -0.03643912 -0.00155127 -0.9994181 -0.03398472 -0.002928197 -0.9982607 -0.05889028 -0.002761304 -0.9976542 -0.06845289 5.38156e-4 -0.9975061 -0.07058006 5.16157e-4 -0.9960811 -0.08841121 0.002469539 -0.9993382 -0.03611928 0.004327476 -0.9990238 -0.04395633 0.004398167 -0.9999294 0.009740114 0.00681132 -0.9996145 0.0268681 0.007009804 -0.9981553 0.06009274 0.008658885 -0.998465 0.05471974 0.008580029 -0.968502 0.2482039 0.01996958 -0.9879699 0.1535312 0.01853901 -0.6136374 -0.7531092 0.237225 -0.6522855 -0.7248139 0.2217396 -0.8188014 -0.5452118 0.1797457 -0.8311383 -0.5284429 0.1730821 -0.8984308 -0.4146264 0.1445929 -0.9097597 -0.3922669 0.1358827 -0.9407095 -0.3184637 0.1168186 -0.9560043 -0.2759395 0.09956634 -0.9725864 -0.2167433 0.08425128 -0.9865165 -0.1533246 0.05724388 -0.9927303 -0.1108429 0.04691058 -0.9980382 -0.05827623 0.02288269 -0.9988958 -0.04258835 0.01984149 -0.9998583 -0.01566833 0.006177127 -0.9998984 -0.01299631 0.005863845 -0.9999959 -0.002874255 2.84149e-4 -0.9999918 -0.004059553 3.41506e-4 -0.9999974 -0.002139687 -7.27109e-4 -0.9999988 -0.001370012 -7.33676e-4 -0.9999991 -0.001119613 -8.59393e-4 -0.9999996 -4.52978e-4 -8.49553e-4 -0.9999995 -6.14345e-4 -7.64016e-4 -0.9999964 -0.002555429 -8.35718e-4 -0.9999979 -0.001722693 -0.00120157 -0.9999168 -0.01278859 -0.0017367 -0.9999528 -0.009070217 -0.003499925 -0.9994142 -0.03397101 -0.00417453 -0.9994922 -0.03138834 -0.005483925 -0.9976329 -0.06857639 -0.005091607 -0.9972838 -0.07358074 -0.00330913 -0.9958829 -0.09058809 -0.003351688 -0.99551 -0.09461688 -0.002759873 -0.9986239 -0.05243122 -0.001183032 -0.9985892 -0.05308824 -0.001168966 -0.9997811 0.02064228 0.003410696 -0.9998689 0.01585602 0.003301739 -0.9986419 0.05173343 0.006165564 -0.9991548 0.0406993 0.005789399 -0.9885467 0.1500583 0.01606327 -0.9933996 0.1137189 0.01500785 -0.6766434 -0.7264527 0.1200844 -0.6965627 -0.7086723 0.1121788 -0.8698862 -0.4866961 0.08015549 -0.8827802 -0.4640562 0.07315051 -0.9371579 -0.3445312 0.05507558 -0.9475908 -0.3160787 0.04654055 -0.9701579 -0.2399441 0.03493773 -0.9787942 -0.2034979 0.02346503 -0.9910831 -0.1325945 0.01315993 -0.9953943 -0.09586358 6.33547e-4 -0.9987811 -0.04909557 -0.005099117 -0.9995477 -0.02665704 -0.01392716 -0.9998125 -0.01222461 -0.01502496 -0.9997912 -6.97131e-4 -0.02042633 -0.9997893 -0.002151906 -0.02041751 -0.9997414 0.002183139 -0.02263718 -0.9997339 -0.00253278 -0.02292943 -0.9997643 -0.0092929 -0.01962327 -0.9998198 -0.001567363 -0.01892125 -0.9998371 -0.00990808 -0.01509779 -0.9998976 -7.10218e-4 -0.01429605 -0.9999087 -0.007227659 -0.01142287 -0.9999386 -0.001612186 -0.01097184 -0.9999341 -0.007996678 -0.008233487 -0.9999251 -0.008985817 -0.008306145 -0.9998922 -0.01319497 -0.006447374 -0.9994829 -0.03130155 -0.007364153 -0.9994252 -0.03327763 -0.006471872 -0.9972856 -0.07331264 -0.006834685 -0.997254 -0.07375627 -0.006677567 -0.9953481 -0.09610795 -0.006753742 -0.9958378 -0.09080857 -0.007804334 -0.9979722 -0.06325817 -0.007068693 -0.9982231 -0.05912756 -0.007404088 -0.9999883 0.00233376 -0.004252493 -0.9999908 -0.001146554 -0.004152297 -0.9993594 0.03575205 -0.001643478 -0.9994017 0.03454953 -0.001626968 -0.9938094 0.1110259 0.00403738 -0.9929242 0.1186865 0.003872036 -0.6958391 -0.7094154 -0.1119727 -0.7271418 -0.6755708 -0.1219382 -0.9018576 -0.4151976 -0.119432 -0.9097008 -0.3968892 -0.1221617 -0.958012 -0.2614044 -0.1178175 -0.9574258 -0.2636783 -0.1175152 -0.9800291 -0.1631616 -0.1136727 -0.9789507 -0.170241 -0.1125761 -0.9915753 -0.07047009 -0.1086852 -0.9912776 -0.07626032 -0.1074852 -0.9944267 -0.011684 -0.1047815 -0.9944003 -0.01046729 -0.1051598 -0.9945682 0.005885839 -0.103921 -0.9942812 0.01130235 -0.1061943 -0.9941664 0.002351105 -0.107831 -0.994093 0.003859996 -0.1084637 -0.9934371 -0.01210021 -0.1137381 -0.9936016 -0.02909028 -0.1091311 -0.9946436 -0.01307064 -0.1025345 -0.9941844 -0.04551404 -0.09760075 -0.9964663 -0.009337604 -0.08347308 -0.9959154 -0.04580831 -0.07780891 -0.9977748 -0.008844316 -0.0660867 -0.9971703 -0.04858654 -0.05736464 -0.9987272 -0.0124967 -0.04886788 -0.9981651 -0.04633826 -0.03897911 -0.9988781 -0.03012645 -0.03653657 -0.9980366 -0.05612397 -0.0278055 -0.9972307 -0.06863945 -0.02862602 -0.9963366 -0.08184331 -0.02480322 -0.9954 -0.09248262 -0.02501952 -0.9964434 -0.07962965 -0.02756273 -0.9963259 -0.08108079 -0.02758419 -0.9978941 -0.05725049 -0.03049194 -0.9992069 -0.02637827 -0.02983105 -0.9994459 -0.01213365 -0.03099656 -0.9987327 0.04053664 -0.0298292 -0.9987874 0.03922861 -0.02974635 -0.9886998 0.1472782 -0.027965 -0.9909774 0.131296 -0.02692759 0.9922385 0.01694869 0.1231893 0.3610363 0.472621 0.8039168 0.9334124 0.1231616 0.337005 0.832801 0.2277678 0.5045438 0.1171876 0.9430172 0.3114253 0.9472963 0.2830352 0.15007 0.284264 0.8623394 0.4190046 0.9809333 0.1353674 0.1394474 0.9951396 0.05544143 0.08138513 0.4216659 0.6447656 0.6375541 0.990906 0.06129008 0.1197868 0.5530551 0.526145 0.6459888 0.9848278 0.06754386 0.1598499 0.4954792 0.5082241 0.7044208 0.9821166 0.05437082 0.1802516 0.6366192 0.3997702 0.6594693 0.9819818 0.02693057 0.1870466 0.7613335 0.2680106 0.5903742 0.9786376 0.001426994 0.2055881 0.728545 0.2258998 0.6466772 0.9377101 0.02587467 0.346454 0.6098994 0.2318683 0.7577993 0.9568146 -0.1054208 0.2709102 -0.008726298 0.2977958 0.9545898 0.720126 -0.05217647 0.6918787 0.3442754 -0.0677073 0.9364241 0.5558897 -0.3574309 -0.7504864 0.8027731 -0.5725299 -0.1666287 -0.512602 0.2045431 -0.8339074 -0.5062216 0.2006464 -0.8387377 0.4684029 -0.1415563 0.8721013 0.4422192 -0.1318929 0.8871564 0.4985944 -0.1806817 0.8477959 0.4479873 -0.1685491 0.8780084 0.4416127 -0.1659128 0.8817319 0.4354328 -0.165652 0.8848491 0.4879717 -0.1720115 0.8557427 0.7775681 -0.165948 0.6065058 0.8388403 0.5401907 0.06738764 0.828824 0.555147 0.06973427 0.9975638 0.06471925 0.02603596 0.8050048 0.565414 0.1796508 0.9981937 0.04831218 0.03571188 0.9380564 0.3098253 0.1551083 0.9982253 0.03528445 0.0479716 0.8677959 0.4155796 0.272441 0.9980763 0.01673448 0.05969786 0.8445525 0.3985276 0.3576408 0.9974742 -0.00322622 0.07095718 0.8399999 0.3373364 0.4249756 0.9957209 -0.0205366 0.09010034 0.8133597 0.2806024 0.5096158 0.9882016 -0.01791703 0.1521071 0.8261394 0.2063723 0.5243131 0.9758718 -0.03371089 0.2157264 0.8490946 0.1347146 0.5107743 0.9711777 -0.1922843 0.140857 0.7004516 0.1187188 0.7037566 0.8925943 -0.4344278 0.1206156 0.5011943 -0.0407018 0.8643772 0.5977277 -0.1579748 0.7859807 0.5549535 -0.265666 0.78832 0.3285688 0.2574416 0.9087169 0.6447187 -0.08378434 0.7598145 0.6298237 -0.1073188 0.7692885 0.6226931 -0.1012504 0.7758876 0.6096577 -0.1261109 0.7825686 0.6512797 -0.1504661 0.7437706 0.6656053 -0.1815133 0.723894 0.7060117 -0.1881099 0.6827607 0.7060735 -0.2407282 0.6659656 0.5863736 -0.2080927 0.7828561 0.5449742 -0.2287675 0.8066404 0.5308211 -0.2119294 0.8205577 0.4989507 -0.2275882 0.8362128 0.5002738 -0.21329 0.8391863 0.8626689 0.5034355 0.04853147 0.9919242 0.1267474 0.004648387 0.7575211 0.6526394 0.01495695 0.9872793 0.158985 0.001832306 0.9938409 0.1107941 0.002245426 0.995375 0.09604746 0.001844346 0.9971238 0.07575184 0.002421855 0.9938689 0.1105065 0.00361073 0.9982797 0.0584079 0.005131602 0.9793879 0.2016255 0.01210659 0.9995116 0.02907007 0.01147466 0.9563994 0.2890057 0.04214197 0.9997566 0.00803411 0.02054983 0.9420425 0.3202147 0.1000933 0.9994011 -0.008578062 0.03352606 0.9485577 0.2668308 0.17041 0.9983662 -0.01870083 0.0539931 0.9770163 0.1289033 0.1697736 0.9964401 -0.03161102 0.07815307 0.9861313 0.05002075 0.15825 0.992633 -0.04606753 0.1120603 0.9865003 0.009027779 0.1635102 0.9776512 -0.1064014 0.1813204 0.9738554 -0.02551633 0.2257316 0.9053387 -0.17351 0.3876289 0.9217279 -0.06922918 0.3816084 0.9912917 0.1315181 -0.006625413 0.9723212 -0.04612171 0.2290508 0.8414676 -0.1487172 0.5194379 0.830216 -0.1547439 0.5355331 0.7780103 -0.1766271 0.6029121 0.7966139 -0.1672998 0.5808762 0.7026411 -0.1981692 0.6833919 0.7001085 -0.1997921 0.6855154 0.5958032 -0.2256354 0.7707836 0.6001424 -0.2404283 0.7629046 0.5278955 -0.274621 0.8036851 0.5303364 -0.318149 0.7858274 0.9887645 0.1471641 0.02621906 0.9986592 0.05150586 0.005195975 0.9545958 0.2966856 0.02691888 0.9992721 0.03811502 0.001674771 0.9948261 0.1015419 0.003237187 0.9994674 0.032633 -2.06764e-6 0.9956579 0.09307634 -0.001503825 0.998959 0.04558688 -0.001726567 0.9930357 0.1176574 -0.006060063 0.9971643 0.07511335 -0.004632711 0.9954675 0.09489309 -0.006309807 0.9951161 0.09849816 -0.0064978 0.9982858 0.05848032 -0.002376079 0.9922916 0.1238135 -0.005258798 0.999634 0.0266661 0.004588484 0.9866287 0.162899 0.005283832 0.9999105 -5.17386e-4 0.01337158 0.9949153 0.09743392 0.02550387 0.9996215 -0.01872807 0.02015626 0.9993109 0.01979517 0.03140121 0.9994214 -0.01854056 0.02851992 0.9991228 0.009453356 0.04079759 0.9987245 -0.02004659 0.04634392 0.9986313 -0.005126416 0.05205082 0.9967411 -0.02465683 0.07680815 0.9966375 -0.02673089 0.07745581 0.9261048 -0.184127 0.3292828 0.9618712 -0.1259201 0.2427921 0.9654572 -0.1199533 0.231309 0.9504873 -0.1488904 0.2727737 0.9586853 -0.1376197 0.2489645 0.9266917 -0.2004906 0.3178774 0.857621 -0.2621828 0.4424325 0.8245148 -0.3625504 0.4344338 0.6146445 -0.5102741 0.6015252 0.5988092 -0.6057528 0.5239191 0.9983827 0.05491864 0.01470208 0.9991933 0.03913301 0.00902456 0.9982756 0.05727344 0.01286512 0.9995183 0.03042763 0.006120204 0.9983826 0.05586218 0.01056122 0.9996037 0.02775537 0.004716098 0.9960664 0.08762168 0.01320105 0.9994729 0.03221869 0.003979742 0.9823002 0.1863054 0.01941305 0.9992904 0.03759038 0.002415955 0.9817836 0.1897723 0.00935626 0.9992152 0.03961235 7.52277e-5 0.9895191 0.1443924 -0.001681506 0.9989974 0.044703 -0.002437651 0.9946377 0.1031996 -0.006766319 0.9986617 0.0515024 -0.004723548 0.9996255 0.02727633 -0.002272546 0.9998727 -0.01595383 -4.83799e-4 0.9999466 -0.01029741 -8.698e-4 0.9998136 -0.01925981 -0.001386404 0.9999986 3.26718e-4 -0.001695215 0.9997586 0.02158635 0.00410068 0.9999746 -0.00440967 0.005600273 0.9999031 0.008526682 0.01100629 0.9998525 -0.01055371 0.01355773 0.9998558 -0.005441844 0.01608872 0.9995807 -0.02185171 0.01900005 0.9995504 -0.02383148 0.01819866 0.9977586 -0.06195223 0.02529442 0.996922 -0.07470786 0.0237782 0.9778981 -0.2013779 0.05623364 0.9826961 -0.1773135 0.05355799 0.985092 -0.164938 0.04887968 0.9682603 -0.24382 0.05498927 0.9813032 -0.1893382 0.03457188 0.9424948 -0.3330913 0.02745485 0.9199637 -0.389805 0.04145866 0.8581174 -0.5134515 0.001533448 0.5734261 -0.8191126 -0.01540094 0.5848711 -0.8111255 -0.001217782 0.9991284 0.04001086 0.01190423 0.9991971 0.03845781 0.01123392 0.9993135 0.0355485 0.01043665 0.9994333 0.03232681 0.009385108 0.9992817 0.0364266 0.01045542 0.9994608 0.0315997 0.008932828 0.9988317 0.04664611 0.01263105 0.9994298 0.03265553 0.00859487 0.9980993 0.05986016 0.01464694 0.9994307 0.03288769 0.007528781 0.9978558 0.06406533 0.01339703 0.9994889 0.03144323 0.005788803 0.9972438 0.07324904 0.01181793 0.9996047 0.02792477 0.003258943 0.9951121 0.09825408 0.009901702 0.9999963 0.002008438 -0.001841723 0.9969924 -0.07726359 -0.006048679 0.9759742 -0.2174198 -0.01424807 0.9994282 -0.03297281 -0.007497549 0.9997032 -0.02343422 -0.006659924 0.9998088 0.0185641 -0.006141483 0.9995175 0.03091603 -0.003007173 0.9999666 0.007761478 -0.002593457 0.9998683 0.01622414 5.25245e-4 0.9999856 -0.005341053 6.04627e-4 0.9999651 -0.008332669 -7.38372e-4 0.9996827 -0.0251255 -0.00183022 0.9986819 -0.04971539 -0.01276665 0.995936 -0.08815735 -0.01843863 0.9876872 -0.1509149 -0.04121595 0.9651239 -0.2548503 -0.05989396 0.944156 -0.3198345 -0.07921773 0.9437646 -0.3209395 -0.0794112 0.8815746 -0.4563645 -0.1206562 0.9126932 -0.3939355 -0.1086556 0.8044745 -0.5702915 -0.1660981 0.8034489 -0.5716508 -0.1663889 0.6905524 -0.6920866 -0.2101274 0.4996498 -0.8313134 -0.2434507 0.4866195 -0.8375034 -0.2485749 0.9992054 0.03833866 0.01089709 0.9991427 0.03976821 0.01151353 0.9994229 0.03259068 0.009586513 0.9993814 0.03371661 0.01000744 0.9994217 0.03260046 0.009678363 0.9993965 0.03328818 0.009928524 0.9993347 0.03497302 0.01035529 0.999387 0.03357321 0.009927332 0.9992678 0.03673368 0.01070106 0.9994297 0.03244763 0.009361088 0.9992858 0.03635942 0.01028466 0.9995498 0.02893894 0.007929444 0.9993696 0.03431189 0.009119808 0.999839 0.01748615 0.004062652 0.9999605 0.008594453 0.00227648 0.9994328 -0.03267627 -0.0081501 0.3668299 -0.9155386 -0.1649998 0.9954616 -0.09393781 -0.01523524 0.999713 -0.02307611 -0.006443262 0.999795 0.02019464 0.001506984 0.9994806 0.03218334 0.001733601 0.9995052 0.03141802 0.001531422 0.9998645 0.01637202 0.001719474 0.9999686 0.007874906 -9.94781e-4 0.9999632 -0.008428156 -0.001618802 0.9993263 -0.03486371 -0.01146942 0.9986653 -0.04986667 -0.0134536 0.992162 -0.1183956 -0.03996551 0.9868176 -0.1546115 -0.04781645 0.955454 -0.2798055 -0.0938965 0.9310008 -0.3476387 -0.1112882 0.8714293 -0.4660623 -0.152961 0.8552597 -0.4928571 -0.1600714 0.7724434 -0.6031513 -0.1988459 0.7757647 -0.5992299 -0.1977696 0.6856095 -0.6906423 -0.2301148 0.6601263 -0.7130447 -0.2362216 0.5841764 -0.7699203 -0.2568283 0.4649254 -0.8412266 -0.2760115 0.4336438 -0.8552218 -0.2838113 0.9991763 0.0393458 0.009938538 0.9991068 0.04090064 0.01062417 0.9994382 0.03242313 0.008491337 0.9994523 0.03202694 0.008332967 0.9994763 0.03131556 0.008150517 0.9995014 0.03056448 0.007923483 0.9994617 0.03176391 0.008215129 0.9995339 0.02958893 0.007514595 0.9994884 0.03100663 0.00786215 0.9996904 0.02423387 0.005649209 0.999598 0.02761524 0.006424963 0.9998926 0.01451236 0.002084374 0.9998676 0.01609313 0.002435564 0.9999124 -0.01151722 -0.006534278 0.9992092 -0.03779488 -0.01235765 0.9949831 -0.09567999 -0.02922445 0.9910269 -0.1285526 -0.03660446 0.9960319 -0.08544862 -0.02488005 0.9998509 0.01623284 -0.005898594 0.9996911 0.02467596 -0.002980053 0.9995273 0.03064942 -0.00239551 0.999706 0.02372157 -0.005028307 0.9999564 0.006831467 -0.006365299 0.9998146 -0.01357817 -0.01365816 0.9992095 -0.03622919 -0.01636773 0.9951789 -0.09129947 -0.03582638 0.9920653 -0.1188681 -0.04094851 0.9680094 -0.2370058 -0.0823785 0.9559985 -0.2785078 -0.09219729 0.8934907 -0.4257388 -0.1429018 0.8711409 -0.4664595 -0.1533918 0.7934148 -0.5778717 -0.1911995 0.77389 -0.6017439 -0.1974811 0.6913544 -0.6862459 -0.2260436 0.6912111 -0.68638 -0.2260748 0.6071314 -0.7545895 -0.2489704 0.5929352 -0.7648954 -0.25172 0.5179877 -0.812343 -0.267932 0.4394592 -0.8540175 -0.278442 0.4104715 -0.8663476 -0.2845263 0.9991951 0.03996115 0.003521502 0.9988301 0.04775333 0.007618606 0.9995951 0.0283569 0.002353608 0.9998074 0.01958996 -0.001175701 0.9997186 0.02372634 -3.92962e-5 0.9998677 0.01600152 -0.002954304 0.9997506 0.02230179 -0.00122559 0.9999477 0.007738113 -0.00669074 0.9998518 0.01666426 -0.00432372 0.9998595 -0.009077787 -0.01409447 0.9999292 0.005582809 -0.01051735 0.9992534 -0.0303418 -0.02391993 0.9994637 -0.02375119 -0.02254527 0.9972167 -0.06516551 -0.03622668 0.9927124 -0.1122916 -0.04373514 0.9959896 -0.08176219 -0.03632682 0.9944632 -0.09798228 -0.03798115 0.99656 -0.07583534 -0.0334261 0.9994179 0.01884019 -0.02844464 0.9992609 -0.00861746 -0.03746151 0.9991605 0.01958298 -0.03598517 0.9986016 -0.0172196 -0.04998391 0.998471 -0.02246785 -0.05050569 0.9944092 -0.07873696 -0.07036268 0.9913498 -0.107883 -0.07474625 0.9699255 -0.2170602 -0.1101337 0.9578935 -0.2615169 -0.118529 0.8943184 -0.4157478 -0.1653742 0.8752183 -0.4518769 -0.1726277 0.7924991 -0.5734613 -0.2075746 0.7724574 -0.5984664 -0.2124801 0.6945613 -0.6800729 -0.2347033 0.674932 -0.6984179 -0.2380745 0.6052265 -0.7549286 -0.2525547 0.5996313 -0.7591404 -0.2532751 0.5364427 -0.8017702 -0.2634275 0.524696 -0.809144 -0.2645376 0.4700214 -0.8398526 -0.271528 0.4217999 -0.8641839 -0.2743558 0.3969467 -0.8747502 -0.2779311 -0.3950266 0.8874415 -0.2374904 -0.3970353 0.8821412 -0.2533571 -0.2800031 0.6618061 -0.6954214 -0.3017365 0.737964 -0.603626 -0.15338 0.4457573 -0.8819156 -0.1942383 0.5638419 -0.8027166 -0.04955548 0.2711204 -0.961269 -0.07590341 0.3570296 -0.9310041 0.02879804 0.1370697 -0.9901428 0.02614367 0.1490735 -0.9884805 0.06662809 0.05871933 -0.9960486 0.07205551 0.02282267 -0.9971395 0.07862973 0.007169425 -0.9968782 0.08429628 -0.03746283 -0.9957363 0.06930446 3.85849e-4 -0.9975956 0.07580178 -0.03598845 -0.9964733 0.06326091 -0.002051591 -0.997995 0.06727242 -0.02320402 -0.9974648 0.05857789 0.002637743 -0.9982793 0.061926 -0.01913088 -0.9978975 0.05947071 -0.01075947 -0.9981722 0.06130164 -0.02518767 -0.9978014 0.06952959 -0.05676674 -0.9959635 0.06794762 -0.04486507 -0.9966797 0.09074002 -0.1357237 -0.9865827 0.08134573 -0.0774191 -0.9936746 0.1295092 -0.2640558 -0.9557729 0.1056743 -0.1413347 -0.9843056 0.1804739 -0.4233552 -0.8878061 0.1438693 -0.2513628 -0.9571408 0.2275367 -0.5692784 -0.790031 0.2013943 -0.4441009 -0.8730492 0.2539913 -0.658222 -0.7086834 0.2415907 -0.5926777 -0.7683536 0.2701765 -0.7214005 -0.6376409 0.2622604 -0.6737638 -0.6908414 0.2874675 -0.8048941 -0.5191416 0.2852092 -0.7825726 -0.5533858 0.2987076 -0.8834556 -0.3609431 0.3001827 -0.8751201 -0.3795462 -0.4142082 0.8788367 -0.2368076 -0.3132119 0.7111186 -0.6294512 -0.3329005 0.7418507 -0.5820953 -0.2995467 0.6783817 -0.6708726 -0.2441898 0.5800489 -0.7771193 -0.1918782 0.4697254 -0.8617081 -0.1495214 0.38678 -0.9099695 -0.1133804 0.3015561 -0.9466831 -0.05999845 0.1888658 -0.9801684 -0.04137003 0.1377627 -0.989601 -0.01629704 0.07973295 -0.9966831 -0.006279349 0.04652142 -0.9988976 -0.001248538 0.03350132 -0.999438 0.003135621 0.01536506 -0.9998771 1.97778e-4 0.02396708 -0.9997128 0.002675592 0.01266056 -0.9999163 7.26634e-5 0.02115595 -0.9997762 0.001624226 0.01352828 -0.9999072 0.001249551 0.01486563 -0.9998888 0.002066373 0.0102995 -0.9999449 0.003181755 0.005958437 -0.9999772 0.003239333 0.005591273 -0.9999791 0.006595969 -0.008494675 -0.9999422 0.005478858 -8.94823e-4 -0.9999847 0.01142454 -0.02676773 -0.9995765 0.008840858 -0.009634017 -0.9999145 0.02101868 -0.06191575 -0.9978601 0.01470935 -0.02495604 -0.9995804 0.04022938 -0.1272927 -0.9910491 0.0246486 -0.05046874 -0.9984214 0.08245158 -0.2603778 -0.9619798 0.05163973 -0.1339844 -0.9896371 0.1273437 -0.397253 -0.9088309 0.1027644 -0.3031151 -0.9473968 0.1564544 -0.4898779 -0.8576373 0.1473235 -0.4550052 -0.8782176 0.2140355 -0.6917728 -0.689666 0.2118631 -0.6826871 -0.6993228 0.2625873 -0.8722058 -0.4126803 0.2622082 -0.8603055 -0.4371745 -0.2155211 0.6944181 -0.6865378 -0.1063167 0.3924245 -0.9136192 -0.1865938 0.5985813 -0.7790271 -0.1162483 0.3989433 -0.9095773 -0.1180769 0.4038875 -0.9071564 -0.04040026 0.1672096 -0.9850934 -0.07747042 0.2713078 -0.9593699 -0.02751755 0.10868 -0.9936959 -0.03605717 0.133567 -0.9903836 -0.01515513 0.05890727 -0.9981484 -0.01307016 0.05243057 -0.9985391 -0.007592558 0.03010892 -0.9995179 -0.005921006 0.02440547 -0.9996846 -0.005420982 0.02197229 -0.9997439 -0.004895627 0.01994937 -0.999789 -0.005313992 0.0222451 -0.9997385 -0.004513561 0.018821 -0.9998127 -0.005042612 0.02202987 -0.9997447 -0.003423333 0.01449763 -0.9998891 -0.004051804 0.01883316 -0.9998145 -0.002195835 0.009474515 -0.9999528 -0.002848982 0.0147224 -0.9998877 -7.95374e-4 0.003441214 -0.9999939 -0.001461386 0.009775876 -0.9999512 8.74364e-4 -0.004212379 -0.9999908 2.07721e-4 0.003295719 -0.9999946 0.003495216 -0.01740652 -0.9998424 0.002426385 -0.004380702 -0.9999875 0.00846374 -0.03888756 -0.9992077 0.005817532 -0.0130009 -0.9998986 0.02577543 -0.104248 -0.9942173 0.01526576 -0.04340499 -0.9989409 0.06379115 -0.2391091 -0.9688951 0.04302763 -0.1446715 -0.9885438 0.09990966 -0.3678582 -0.924499 0.08921253 -0.3215292 -0.9426877 0.1617825 -0.6100721 -0.7756537 0.162419 -0.6130135 -0.7731977 0.2209299 -0.8548135 -0.4695573 0.2205252 -0.8457004 -0.4859625 -0.07107532 0.3845961 -0.9203446 -0.04432952 0.2487989 -0.9675403 -0.06250411 0.3323547 -0.9410811 -0.03311079 0.1821609 -0.9827111 -0.02666097 0.1522245 -0.9879863 -0.01131147 0.0692085 -0.9975381 -0.01758837 0.09813159 -0.9950181 -0.007498264 0.04149848 -0.9991105 -0.01005977 0.05346041 -0.9985193 -0.006038963 0.02964454 -0.9995422 -0.005705118 0.02801287 -0.9995913 -0.005629301 0.02752047 -0.9996054 -0.004332244 0.02066892 -0.999777 -0.005470037 0.02919739 -0.9995588 -0.004035711 0.02071797 -0.9997773 -0.005372643 0.03219056 -0.9994673 -0.003610312 0.02047145 -0.999784 -0.004910588 0.03352463 -0.9994259 -0.002828955 0.01777768 -0.9998381 -0.003864705 0.03084808 -0.9995166 -0.001968622 0.01407408 -0.999899 -0.002602934 0.02537745 -0.9996746 -0.001133382 0.009549856 -0.9999538 -0.00137782 0.01743936 -0.999847 -3.65778e-4 0.003633856 -0.9999934 -3.74972e-4 0.007407248 -0.9999725 3.28241e-4 -0.003610134 -0.9999935 4.45866e-4 3.50885e-4 -1 0.001488685 -0.01191449 -0.9999279 0.001737236 -0.003910779 -0.9999909 0.006561815 -0.03904056 -0.9992161 0.005167663 -0.01588553 -0.9998605 0.0242359 -0.1233825 -0.9920632 0.01569092 -0.06200963 -0.9979523 0.05312317 -0.2582787 -0.9646088 0.04170292 -0.1893585 -0.9810221 0.1059659 -0.52818 -0.8424947 0.1027665 -0.5078788 -0.8552767 0.1630544 -0.8386547 -0.5196841 0.1630011 -0.8338829 -0.5273235 -0.03263133 0.2546766 -0.9664756 -0.04309451 0.368138 -0.928772 -0.02000206 0.1773618 -0.9839425 -0.01942586 0.1716713 -0.9849627 -0.007094264 0.06901842 -0.9975902 -0.005407035 0.05022042 -0.9987236 -0.004213452 0.04005342 -0.9991887 -0.003666579 0.0333454 -0.9994372 -0.002969324 0.02698701 -0.9996315 -0.003441691 0.03362506 -0.9994287 -0.002491176 0.02381449 -0.9997134 -0.00329262 0.03803628 -0.999271 -0.002188742 0.02441358 -0.9996996 -0.002844929 0.04167085 -0.9991274 -0.001890301 0.0266422 -0.9996433 -0.002263545 0.04437029 -0.9990127 -0.001520156 0.02863383 -0.9995889 -0.001631736 0.04631698 -0.9989256 -0.001045644 0.02831023 -0.9995987 -9.22332e-4 0.04440855 -0.9990131 -5.38138e-4 0.02428084 -0.9997051 -2.63217e-4 0.03638762 -0.9993378 -1.38432e-4 0.01693135 -0.9998567 9.21381e-5 0.02263408 -0.9997438 3.16682e-5 0.007294416 -0.9999734 7.02859e-5 0.007845461 -0.9999693 3.63062e-5 3.87425e-4 -1 1.31029e-4 0.00115019 -0.9999994 2.00031e-4 -0.003887772 -0.9999924 5.74303e-4 -0.001488149 -0.9999988 0.001255154 -0.01549381 -0.9998792 0.001817047 -0.007184207 -0.9999727 0.006228327 -0.05737775 -0.9983332 0.005166947 -0.02761018 -0.9996055 0.02029478 -0.1589868 -0.9870722 0.01404398 -0.08847838 -0.9959792 0.06002378 -0.4467686 -0.8926337 0.04719841 -0.3209457 -0.9459208 0.1153654 -0.831385 -0.5435899 0.1153718 -0.8053382 -0.5814808 0.008145391 0.4643368 -0.8856214 -0.008332669 0.1674225 -0.98585 -0.009497761 0.1889373 -0.9819433 -0.009382545 0.1839948 -0.9828824 -0.002526044 0.05637514 -0.9984065 -0.002759754 0.07639968 -0.9970734 -0.001289665 0.03653955 -0.9993314 -0.001205503 0.05653649 -0.9983999 -7.75236e-4 0.03439474 -0.999408 -3.14611e-4 0.0588864 -0.9982647 -2.28474e-4 0.03627693 -0.9993419 6.12649e-4 0.06086361 -0.998146 3.72026e-4 0.0379185 -0.9992808 0.001500725 0.06017357 -0.9981869 0.001005947 0.03977108 -0.9992084 0.002180397 0.05764156 -0.998335 0.001623988 0.04224824 -0.9991059 0.002507269 0.05374175 -0.9985518 0.002006292 0.04244709 -0.9990968 0.002427399 0.0474717 -0.9988697 0.001851379 0.03565466 -0.9993625 0.001882791 0.03600341 -0.99935 0.001197218 0.02230495 -0.9997505 0.00101155 0.02045589 -0.9997903 4.14254e-4 0.007764875 -0.9999698 2.93641e-4 0.006870388 -0.9999765 7.71484e-5 0.00115478 -0.9999994 1.128e-4 0.001320719 -0.9999992 3.39785e-5 -0.001485943 -0.999999 2.85106e-4 -5.84918e-4 -0.9999998 1.9482e-4 -0.007122337 -0.9999746 8.59795e-4 -0.003776788 -0.9999926 0.00157845 -0.02654951 -0.9996463 0.002346396 -0.01434463 -0.9998944 0.008132398 -0.08237916 -0.9965679 0.006767094 -0.04603046 -0.9989171 0.03841829 -0.3096374 -0.9500784 0.02796018 -0.1862344 -0.9821074 0.1131813 -0.8051996 -0.5821027 0.1121866 -0.7521253 -0.6494012 0.01095384 0.2121556 -0.9771745 0.005570411 0.1526415 -0.988266 0.002454996 0.2092097 -0.9778677 9.47689e-4 0.1791366 -0.9838238 8.41295e-4 0.0844472 -0.9964276 0.002763032 0.1102749 -0.9938974 0.00128895 0.05982524 -0.9982081 0.00322473 0.08039259 -0.9967582 0.002293825 0.05960702 -0.9982194 0.003599643 0.07182639 -0.9974107 0.002947151 0.05973941 -0.9982097 0.004132568 0.06968343 -0.9975606 0.003436326 0.05843085 -0.9982857 0.004377722 0.06545066 -0.9978462 0.003733277 0.05603772 -0.9984217 0.004407525 0.06058281 -0.9981535 0.003808617 0.05247849 -0.9986149 0.003694355 0.05176907 -0.9986523 0.003332138 0.04680013 -0.9988988 0.002704262 0.04298126 -0.9990723 0.002227604 0.03575766 -0.9993581 0.001389026 0.03078913 -0.999525 8.72716e-4 0.02056449 -0.9997882 2.9886e-4 0.01745432 -0.9998477 3.05099e-5 0.007031977 -0.9999753 -6.99414e-5 0.006645023 -0.999978 -9.03959e-5 0.001379609 -0.9999991 4.26937e-6 0.001604676 -0.9999988 -1.5542e-5 -5.50987e-4 -1 1.82272e-4 -1.96304e-4 -1 1.05677e-4 -0.00367707 -0.9999933 7.19493e-4 -0.002426564 -0.9999969 0.001044332 -0.01385533 -0.9999035 0.002268314 -0.009581565 -0.9999516 0.006194353 -0.04549944 -0.9989452 0.007009148 -0.03417545 -0.9993914 0.03193473 -0.1913905 -0.9809944 0.03021454 -0.1541169 -0.9875906 0.136123 -0.7594749 -0.6361355 0.1371715 -0.7301145 -0.6694153 0.180921 0.4092181 -0.89432 0.1272814 0.2898666 -0.9485657 0.04257565 0.09848147 -0.9942277 0.02657431 0.06297028 -0.9976616 0.009892582 0.02489268 -0.9996412 0.003828763 0.01172089 -0.999924 0.003404796 0.01071178 -0.9999369 8.89721e-4 0.005470156 -0.9999847 0.002049803 0.008630156 -0.9999607 5.11946e-4 0.005372941 -0.9999855 0.001590251 0.009305179 -0.9999555 2.58504e-4 0.005738019 -0.9999835 0.001248776 0.01086515 -0.9999403 -2.49588e-4 0.005361795 -0.9999857 4.08751e-4 0.01004803 -0.9999495 -0.001629233 7.46348e-4 -0.9999985 -0.001185059 0.006948649 -0.9999752 -0.002920925 -0.003415584 -0.9999899 -0.003628194 0.01268839 -0.999913 -0.004116296 0.001540064 -0.9999904 -0.006158292 0.01964432 -0.9997881 -0.006101608 0.01779693 -0.999823 -0.006217956 0.01873314 -0.9998052 -0.006515443 0.02634096 -0.9996319 -0.004360795 0.008446753 -0.9999549 -0.004434525 0.01628941 -0.9998576 -0.003063321 0.002325952 -0.9999926 -0.002650856 0.00815767 -0.9999633 -0.002028405 -0.00161308 -0.9999967 -0.001242995 0.003961622 -0.9999915 -3.70995e-4 -0.01689213 -0.9998573 -2.34477e-4 -0.01570576 -0.9998767 0.002818107 -0.1065128 -0.9943073 0.002190351 -0.1183001 -0.9929755 0.02019155 -0.7225137 -0.6910616 0.0161342 -0.7786274 -0.6272792 -0.002553343 0.002095997 -0.9999946 -0.005334377 -0.007269978 -0.9999594 -0.004320859 0.01740896 -0.9998391 -0.00568819 0.007801592 -0.9999534 -0.005579113 0.02605807 -0.9996449 -0.005927443 0.02246111 -0.9997302 -0.005855083 0.01655703 -0.9998458 -0.005751729 0.01778137 -0.9998254 -0.005499243 0.008096039 -0.9999521 -0.004574775 0.01604831 -0.9998608 -0.004208326 0.003350198 -0.9999856 -0.002460241 0.01422256 -0.9998959 -0.00163114 -0.01626098 -0.9998666 -0.001015245 -0.01133364 -0.9999353 0.00104773 -0.1190505 -0.9928877 -8.75194e-4 -0.1487292 -0.9888776 0.00783801 -0.780377 -0.6252603 7.50378e-4 -0.8476032 -0.5306302 -0.004567325 0.008311927 -0.9999551 -0.006807327 0.002036571 -0.9999747 -0.005254149 0.02251976 -0.9997326 -0.006014108 0.01990658 -0.9997838 -0.006121158 0.01776552 -0.9998235 -0.006275415 0.01719045 -0.9998326 -0.006303846 0.01566022 -0.9998576 -0.005216479 0.01940608 -0.9997981 -0.00518161 0.01298183 -0.9999024 -0.002704203 0.02062565 -0.9997836 -0.002053737 -0.0121814 -0.9999237 -9.0745e-4 -0.007125973 -0.9999743 0.001045763 -0.1456943 -0.9893292 -0.001199245 -0.1648716 -0.9863144 0.005262315 -0.8454911 -0.5339637 -0.001510739 -0.8723549 -0.4888709 0.1654831 0.951733 -0.2584951 0.15373 0.9532119 -0.2602963 0.1168994 0.6825086 -0.7214683 0.1266096 0.6844699 -0.7179631 0.04575955 0.1527087 -0.9872113 0.05288875 0.1558767 -0.9863596 0.03118103 0.03669619 -0.9988399 0.03511351 0.03689843 -0.998702 0.02164602 -0.01954394 -0.9995747 0.01636105 -0.01311057 -0.9997802 0.01092928 -0.02386748 -0.9996554 5.91824e-4 -0.007943451 -0.9999683 0.004404783 -0.004240512 -0.9999814 -0.002340495 -0.002082884 -0.9999951 0.00105971 6.0428e-4 -0.9999994 -0.002235054 -1.97011e-4 -0.9999975 -8.45105e-4 8.56508e-4 -0.9999993 0.001509726 0.001688778 -0.9999975 1.82854e-4 6.15832e-4 -0.9999999 0.008881866 0.002727806 -0.9999569 0.00633645 -1.42788e-4 -0.9999799 0.01992332 0.001194834 -0.9998008 0.01901215 -0.002712666 -0.9998157 0.01698946 -0.002957224 -0.9998514 -0.006695568 0.9639691 -0.2659299 -0.01060634 0.9475626 -0.3193944 -0.007875859 0.6583367 -0.7526825 -0.01054215 0.5355471 -0.8444396 -0.002953648 0.133403 -0.9910575 -0.003121674 0.08850324 -0.9960711 -0.001585781 0.04202324 -0.9991155 -0.001455903 0.02266478 -0.9997421 -0.001389801 0.02148443 -0.9997683 -0.001089155 0.01084363 -0.9999407 -4.14213e-4 0.002954661 -0.9999957 -4.21356e-4 0.00308156 -0.9999952 4.36786e-4 -0.004523158 -0.9999897 3.67493e-4 -0.002714037 -0.9999963 1.69153e-4 -0.001111865 -0.9999994 1.23306e-4 -0.001416921 -0.9999991 -2.48228e-5 4.91376e-4 -0.9999999 -1.48314e-4 2.46163e-4 -1 -1.38816e-4 7.68193e-4 -0.9999998 -1.23701e-4 7.92131e-4 -0.9999998 -1.33704e-4 4.50486e-4 -0.9999999 -5.2805e-5 6.10413e-4 -0.9999998 -5.66409e-5 1.31503e-5 -1 1.11962e-5 1.82521e-4 -1 9.10126e-6 -7.35691e-4 -0.9999998 1.32932e-4 -4.03223e-4 -1 9.54018e-5 -0.004877269 -0.9999881 6.11879e-4 -0.003461539 -0.9999939 3.03002e-4 -0.02051776 -0.9997895 0.00149405 -0.01697564 -0.9998549 9.019e-5 -0.05299925 -0.9985947 -2.92299e-4 -0.05444252 -0.9985169 -0.00415647 -0.1120484 -0.9936941 -0.0086959 -0.1361519 -0.9906499 -0.01573199 -0.2335034 -0.9722288 -0.01788741 -0.2474097 -0.9687458 -0.02464622 -0.3666125 -0.9300473 -0.02241694 -0.3498654 -0.9365318 -0.03441315 -0.6484425 -0.7604855 -0.0286169 -0.614359 -0.7885076 -0.02856874 0.9472978 -0.3190782 -0.03728038 0.882243 -0.469316 -0.02423322 0.5372903 -0.8430492 -0.02307641 0.3929854 -0.9192552 -0.006301045 0.08838587 -0.9960665 -0.005854129 0.06981337 -0.9975429 -0.002325236 0.02267926 -0.9997402 -0.002099692 0.01584124 -0.9998723 -0.001577854 0.01089799 -0.9999395 -0.001350164 0.006934344 -0.9999751 -7.90701e-4 0.003091394 -0.9999949 -8.18796e-4 0.003376126 -0.999994 3.40123e-4 -0.002713799 -0.9999963 -3.66458e-5 4.2114e-4 -1 4.16482e-4 -0.001424849 -0.999999 3.53492e-4 -3.60161e-4 -1 1.89583e-4 2.43597e-4 -1 1.77863e-4 1.53135e-4 -1 4.25905e-5 7.89984e-4 -0.9999998 -2.11994e-6 6.2729e-4 -0.9999999 0 6.09603e-4 -0.9999999 -2.58686e-5 5.11788e-4 -1 -5.85903e-6 1.83239e-4 -1 -3.58395e-6 1.92748e-4 -1 7.27839e-6 -3.91691e-4 -1 3.06014e-5 -2.95916e-4 -1 3.25203e-5 -0.00342375 -0.9999942 1.99958e-4 -0.002744376 -0.9999963 1.29252e-4 -0.01703876 -0.9998549 6.73534e-4 -0.01464027 -0.9998926 1.62486e-4 -0.05432283 -0.9985234 1.31643e-4 -0.05449974 -0.9985138 -0.002019703 -0.1341006 -0.9909657 -0.003833413 -0.1488217 -0.9888567 -0.006793022 -0.2457993 -0.969297 -0.007514595 -0.2523077 -0.9676179 -0.009783685 -0.3488751 -0.9371183 -0.008982717 -0.3407041 -0.9401277 -0.01364928 -0.6136172 -0.7894857 -0.01090693 -0.5925276 -0.8054763 -0.07436758 0.8808874 -0.4674472 -0.07970046 0.7989874 -0.5960429 -0.04248762 0.3980613 -0.9163745 -0.04171764 0.3805161 -0.9238329 -0.009640812 0.06989353 -0.9975079 -0.01047801 0.08820766 -0.996047 -0.002982974 0.01602023 -0.9998673 -0.003103613 0.02137362 -0.9997668 -0.001610755 0.00699073 -0.9999743 -0.001622617 0.008088588 -0.999966 -0.00110656 0.003383874 -0.9999938 -0.001109302 0.003541886 -0.9999932 -6.7789e-4 3.81749e-4 -0.9999998 -6.8596e-4 0.001101791 -0.9999992 -3.86122e-4 -3.11451e-4 -1 -3.76462e-4 5.73083e-4 -0.9999998 -2.71099e-4 2.0044e-4 -1 -2.42942e-4 5.72633e-4 -0.9999998 -2.6377e-4 6.49766e-4 -0.9999998 -2.4063e-4 8.24875e-4 -0.9999997 -1.84236e-4 5.18993e-4 -0.9999998 -1.46378e-4 8.03521e-4 -0.9999997 -8.80019e-5 1.93474e-4 -1 -4.6203e-5 4.72453e-4 -1 -2.00542e-5 -2.96057e-4 -1 -5.75524e-6 -2.21939e-4 -1 1.37346e-5 -0.00274676 -0.9999963 2.42424e-5 -0.002697706 -0.9999964 4.85043e-5 -0.01465487 -0.9998927 1.63233e-4 -0.01407164 -0.9999011 1.63199e-4 -0.05449795 -0.9985139 1.36275e-4 -0.05468857 -0.9985035 -3.54671e-4 -0.1485443 -0.9889057 -8.53807e-4 -0.1537948 -0.9881025 -0.001531183 -0.2522078 -0.967672 -0.001627564 -0.2532544 -0.9673984 -0.00206995 -0.3407292 -0.9401592 -0.00111711 -0.3292386 -0.9442461 -0.002354681 -0.5920104 -0.8059269 8.03863e-4 -0.5641639 -0.8256624 -0.06584596 0.8033311 -0.5918815 -0.06646955 0.7875682 -0.6126321 -0.03257876 0.3788847 -0.9248704 -0.0340808 0.4351007 -0.8997367 -0.006968855 0.08614897 -0.996258 -0.007346451 0.1071702 -0.9942137 -0.002020359 0.02014774 -0.999795 -0.001945495 0.02353906 -0.9997211 -0.001253664 0.007872879 -0.9999682 -0.001210212 0.008929729 -0.9999594 -0.001011431 0.003548145 -0.9999933 -0.001065969 0.00253576 -0.9999963 -9.58698e-4 0.001051485 -0.9999991 -9.79879e-4 7.84668e-4 -0.9999992 -9.57151e-4 6.50588e-4 -0.9999994 -9.20079e-4 0.001095235 -0.9999991 -8.36905e-4 7.47017e-4 -0.9999995 -7.69412e-4 0.001529037 -0.9999986 -6.32688e-4 9.23612e-4 -0.9999994 -5.54505e-4 0.00195074 -0.999998 -3.81954e-4 8.35591e-4 -0.9999997 -2.87863e-4 0.002200663 -0.9999976 -1.56736e-4 4.73466e-4 -0.9999999 -7.47669e-5 0.001240193 -0.9999992 -4.01301e-5 -2.23326e-4 -1 -2.56978e-5 -1.41129e-4 -1 -1.19214e-5 -0.002698957 -0.9999964 -2.74659e-5 -0.002773463 -0.9999963 1.16851e-5 -0.01407253 -0.999901 7.97847e-6 -0.01409196 -0.9999007 1.33338e-4 -0.05468851 -0.9985035 6.25449e-5 -0.05522406 -0.9984741 1.20755e-4 -0.1537922 -0.9881033 -8.24295e-5 -0.1561098 -0.9877398 -1.31985e-4 -0.2532567 -0.9673991 -2.01529e-4 -0.2540545 -0.96719 -2.26955e-4 -0.3292586 -0.9442398 -3.16159e-5 -0.3267608 -0.9451071 -1.38047e-4 -0.5642037 -0.8256357 0.001371324 -0.5492802 -0.8356372 0.00666815 0.8681851 -0.4961958 -0.001726329 0.7718039 -0.6358584 1.52033e-5 0.4477829 -0.8941424 -0.00384742 0.312045 -0.9500595 -8.36751e-4 0.08676862 -0.9962282 -0.001231014 0.07011431 -0.9975383 -5.54869e-4 0.01779347 -0.9998416 -5.24331e-4 0.01843494 -0.99983 -4.501e-4 0.007674753 -0.9999705 -4.22788e-4 0.008158683 -0.9999667 -3.87067e-4 0.002733588 -0.9999963 -4.20324e-4 0.002337574 -0.9999973 -3.79019e-4 0.001051247 -0.9999995 -3.84471e-4 0.001010358 -0.9999995 -3.90263e-4 0.001085698 -0.9999994 -3.52941e-4 0.00132811 -0.9999991 -3.57891e-4 0.001385152 -0.9999991 -2.75924e-4 0.001874387 -0.9999983 -2.75174e-4 0.001861691 -0.9999983 -2.03869e-4 0.002350807 -0.9999973 -1.98981e-4 0.00218743 -0.9999976 -1.94563e-4 0.002228319 -0.9999976 -1.86279e-4 0.001237213 -0.9999992 -1.84637e-4 0.001250803 -0.9999993 -1.86045e-4 -1.49699e-4 -1 -2.18201e-4 -3.25801e-4 -1 -2.19194e-4 -0.002778649 -0.9999962 -2.70469e-4 -0.003018736 -0.9999954 -2.42304e-4 -0.01408791 -0.9999008 -2.8061e-4 -0.01428616 -0.999898 -1.59626e-4 -0.05520945 -0.9984748 -2.36386e-4 -0.05579465 -0.9984423 -1.1795e-4 -0.1561094 -0.9877398 -2.5492e-4 -0.1576904 -0.9874886 -2.13698e-4 -0.2540605 -0.9671884 -2.40921e-4 -0.2543721 -0.9671064 -2.20755e-4 -0.3267694 -0.9451041 -2.47691e-4 -0.3271089 -0.9449867 -1.73266e-4 -0.5492953 -0.8356283 1.18473e-4 -0.54629 -0.8375961 0.06088495 0.8177348 -0.5723659 0.03719151 0.6445642 -0.7636451 0.01875835 0.3155964 -0.9487082 0.009347021 0.2055146 -0.9786095 0.002789497 0.04686033 -0.9988976 0.001711487 0.03330391 -0.9994438 7.74126e-4 0.008558273 -0.9999632 9.44447e-4 0.01007616 -0.9999488 7.07751e-4 0.005099415 -0.9999868 9.11609e-4 0.006558001 -0.9999782 6.62362e-4 0.002768218 -0.999996 7.6728e-4 0.003265798 -0.9999945 6.19823e-4 0.001718282 -0.9999984 7.14354e-4 0.002017736 -0.9999977 6.66927e-4 0.001681089 -0.9999985 5.03444e-4 0.001249909 -0.9999992 6.2255e-4 0.00190258 -0.999998 2.21836e-4 9.12673e-4 -0.9999996 5.26082e-4 0.002473294 -0.9999969 -4.81004e-4 -3.4645e-4 -0.9999999 -5.89089e-5 0.002263545 -0.9999975 -0.001535475 -0.003179907 -0.9999938 -0.001068234 0.001122474 -0.9999989 -0.001811563 -0.002128303 -0.9999961 -0.001703798 -4.05685e-4 -0.9999985 -0.002188861 -0.002343595 -0.9999949 -0.002210855 -0.003039777 -0.999993 -0.002611875 -0.004604041 -0.9999861 -0.002718985 -0.01419353 -0.9998956 -0.00283277 -0.01472103 -0.9998877 -0.002875149 -0.05552399 -0.9984533 -0.002911329 -0.0557841 -0.9984387 -0.002777218 -0.157555 -0.9875063 -0.002829074 -0.1581356 -0.9874134 -0.002618849 -0.2543959 -0.9670967 -0.002585768 -0.2540203 -0.9671955 -0.002447843 -0.3271271 -0.9449772 -0.002720773 -0.330568 -0.9437783 -0.002179503 -0.5461701 -0.8376716 -0.003128945 -0.5557308 -0.8313565 -0.02355319 0.6272432 -0.7784672 0.1364327 0.9345697 -0.3285815 -0.003010809 0.200973 -0.9795922 0.09581851 0.6101546 -0.7864668 -0.001294314 0.04003536 -0.9991974 0.01729637 0.115813 -0.9931205 -9.35811e-4 0.01902997 -0.9998186 -4.8434e-4 0.02036935 -0.9997924 -0.002416729 0.01208543 -0.9999241 -0.006887257 4.93425e-4 -0.9999762 -0.00717628 -6.21395e-4 -0.9999741 -0.006576478 7.38711e-4 -0.9999781 -0.007891416 -0.00400716 -0.9999608 -0.002992212 0.005156457 -0.9999822 -0.005139827 -0.001202285 -0.9999862 -0.004938125 -8.78429e-4 -0.9999875 -0.004844665 -6.47529e-4 -0.9999881 -0.007173955 -0.004042148 -0.9999662 -0.006889998 -0.00340259 -0.9999706 -0.01140242 -0.01021271 -0.9998829 -0.009954273 -0.006818473 -0.9999272 -0.01566785 -0.01636481 -0.9997434 -0.0112071 -0.004075765 -0.999929 -0.015823 -0.01246494 -0.9997972 -0.01321375 -0.002971708 -0.9999083 -0.01736652 -0.01074379 -0.9997915 -0.01627719 -0.004560887 -0.9998572 -0.01923501 -0.0108152 -0.9997566 -0.01948326 -0.01384192 -0.9997144 -0.02026325 -0.01611602 -0.9996649 -0.02111583 -0.05354237 -0.9983423 -0.0209555 -0.05271142 -0.9983899 -0.02079117 -0.15678 -0.9874148 -0.02039718 -0.1531339 -0.987995 -0.01928496 -0.2542073 -0.9669575 -0.01907622 -0.2520439 -0.9675278 -0.01811635 -0.3309874 -0.9434612 -0.01913827 -0.3428924 -0.9391797 -0.01559174 -0.5550633 -0.8316621 -0.01822137 -0.5794825 -0.814781 0.09671258 0.9343786 -0.3429043 0.2035953 0.9583477 -0.2002961 0.01206016 0.5846146 -0.8112215 0.1392323 0.7784853 -0.6120255 -0.09326136 0.1518356 -0.9839962 -0.05597865 0.2316198 -0.9711945 -0.09227412 0.1280811 -0.9874618 -0.1355059 0.05663508 -0.9891566 -0.1500513 0.02123028 -0.9884503 -0.1996188 -0.05135041 -0.9785273 -0.2198271 -0.09842157 -0.9705613 -0.1636113 -0.02293056 -0.9862584 -0.2070688 -0.1168715 -0.9713206 -0.09858363 0.01671904 -0.9949883 -0.1383403 -0.05526226 -0.9888418 -0.1039094 -0.0180068 -0.9944238 -0.1170768 -0.03776806 -0.9924045 -0.1251797 -0.04540228 -0.9910948 -0.1339963 -0.0565564 -0.9893667 -0.1440253 -0.06545233 -0.9874072 -0.1287667 -0.04773074 -0.9905257 -0.1423976 -0.05913138 -0.9880418 -0.1138853 -0.02594769 -0.9931551 -0.1317721 -0.03993314 -0.9904754 -0.1124374 -0.01455432 -0.9935523 -0.1308276 -0.02820861 -0.9910038 -0.120524 -0.009238839 -0.9926674 -0.1328502 -0.01941764 -0.9909459 -0.1304631 -0.01041615 -0.9913985 -0.1352241 -0.01626825 -0.9906815 -0.1369934 -0.04089009 -0.9897277 -0.1387273 -0.04523164 -0.9892972 -0.136692 -0.1451739 -0.9799184 -0.1364087 -0.1435321 -0.9801996 -0.1295292 -0.2527368 -0.9588255 -0.1290967 -0.2488993 -0.9598872 -0.121615 -0.3448845 -0.9307333 -0.1222299 -0.3521453 -0.9279298 -0.09883797 -0.5727162 -0.8137735 -0.09942054 -0.5784344 -0.8096476 -0.3236444 0.9133862 -0.2469416 -0.4405691 0.8548496 -0.2741006 -0.8760577 0.2575513 -0.4076645 -0.79539 0.438779 -0.4181241 -0.9066244 0.05920135 -0.4177648 -0.8716073 0.2036283 -0.4459104 -0.8847464 0.1462595 -0.442529 -0.9150521 0.01463389 -0.4030705 -0.9190197 -0.09446203 -0.3827267 -0.9194064 -0.09831064 -0.380824 -0.9064658 -0.2547517 -0.3367808 -0.8798847 -0.05444824 -0.4720577 -0.8617156 -0.3534607 -0.364022 -0.7667322 -9.86673e-4 -0.6419664 -0.7925114 -0.2784345 -0.5425863 -0.695422 -0.05351561 -0.7166061 -0.7163292 -0.22261 -0.6612997 -0.6620897 -0.115899 -0.7404084 -0.6745055 -0.2296168 -0.701654 -0.6277887 -0.1443779 -0.7648768 -0.6294449 -0.1545936 -0.7615116 -0.6077158 -0.122477 -0.7846535 -0.599121 -0.08277863 -0.796368 -0.6041365 -0.08822959 -0.7919815 -0.5923665 -0.0364952 -0.8048416 -0.6116999 -0.0518161 -0.7893912 -0.6042213 -0.005677223 -0.7967963 -0.6197016 -0.01692664 -0.784655 -0.6188043 0.006218433 -0.7855206 -0.6262716 -0.001463174 -0.7796037 -0.6255691 -0.01260137 -0.780067 -0.631559 -0.02621835 -0.7748844 -0.6179202 -0.1135846 -0.7779931 -0.619109 -0.1261413 -0.775108 -0.5927473 -0.23053 -0.7716907 -0.5926319 -0.2327548 -0.7711113 -0.56128 -0.3289026 -0.7594655 -0.5627815 -0.3183125 -0.7628592 -0.481257 -0.5086802 -0.7138881 -0.4935665 -0.4501266 -0.7441627 0.997475 0.05350142 -0.04670494 0.996669 0.06725281 -0.04613 0.997133 0.005372464 -0.07547843 0.9965032 -0.01871246 -0.08143222 0.9957719 -0.01674616 -0.09032112 0.9946967 -0.03691989 -0.09599727 0.9942934 -0.02978986 -0.1024369 0.9926834 -0.05452513 -0.1077349 0.9916946 -0.04741919 -0.1195546 0.989616 -0.0765962 -0.1216273 0.9854586 -0.07375884 -0.1530721 0.9796994 -0.1359167 -0.147363 0.9720646 -0.1230596 -0.1998671 0.9606583 -0.2115911 -0.1799024 0.9644458 -0.1636571 -0.2075108 0.9628753 -0.1768299 -0.2039669 0.9671707 -0.1486003 -0.2061522 0.9676102 -0.1431839 -0.2079157 0.9717541 -0.03254288 -0.2337411 0.9734583 -0.09066885 -0.2101384 0.9659364 -0.03820013 -0.2559447 0.9665703 -0.1086004 -0.2322668 0.9515461 -0.1265286 -0.280269 0.9410768 -0.2153503 -0.260766 0.902107 -0.3005409 -0.3096418 0.8574303 -0.4264695 -0.2879884 0.7957006 -0.5097812 -0.3270835 0.7232064 -0.6203822 -0.3034775 0.6848516 -0.6511195 -0.3271417 0.6239699 -0.717988 -0.308472 0.5949426 -0.7371963 -0.3202888 0.5505003 -0.7765118 -0.3065599 0.5219591 -0.7943911 -0.310647 0.4933096 -0.8159168 -0.3015383 0.4697557 -0.8296211 -0.3017591 0.4522172 -0.8413371 -0.29606 0.4300076 -0.8536691 -0.2938408 0.4195398 -0.8600627 -0.2903078 0.390114 -0.8755856 -0.2848878 0.3855265 -0.8781988 -0.2830833 -0.6579256 -0.6430068 -0.3920156 -0.8110395 -0.4740761 -0.3427347 -0.835586 -0.3905466 -0.3863539 -0.859709 -0.3475309 -0.37433 -0.889751 -0.2645023 -0.371997 -0.8929191 -0.2570198 -0.3696437 -0.9175299 -0.1748788 -0.3571503 -0.9160625 -0.1792646 -0.3587393 -0.9372618 -0.07907408 -0.3395403 -0.9363877 -0.08258908 -0.3411117 -0.9445792 -0.006872475 -0.328212 -0.9455919 -0.002624332 -0.3253446 -0.9452157 0.01272529 -0.3261986 -0.9462619 0.01568192 -0.3230209 -0.9429944 -0.001078009 -0.3328073 -0.9437336 4.27599e-4 -0.3307062 -0.9386265 -0.03621947 -0.3430286 -0.9326323 -0.04658728 -0.3578079 -0.9438456 -0.0529353 -0.3261185 -0.9177579 -0.09916108 -0.3845617 -0.9579408 -0.0523169 -0.2821568 -0.9093493 -0.1492052 -0.3883575 -0.9727549 -0.05192434 -0.2259463 -0.9155175 -0.1874945 -0.3559127 -0.9841225 -0.04318553 -0.1721569 -0.947167 -0.1676454 -0.2734403 -0.9913617 -0.04106593 -0.1245614 -0.9672572 -0.1565809 -0.1997401 -0.9942869 -0.05982506 -0.08840018 -0.9771596 -0.1641363 -0.1349761 -0.9942907 -0.07143247 -0.07926982 -0.989561 -0.1136943 -0.08855843 -0.9934677 -0.07938277 -0.08197808 -0.9951997 -0.05706155 -0.0795086 -0.9961637 -0.02187174 -0.08473205 -0.9965223 -0.003372907 -0.08325874 -0.9936878 0.07798969 -0.08063691 -0.9963011 0.01111924 -0.08520907 -0.9806062 0.1824488 -0.07158219 -0.9955904 0.04842585 -0.08034187 0.4641222 0.5700562 -0.6779577 0.6712378 0.6273335 -0.3948324 0.5763779 0.2057179 -0.7908658 0.689565 0.3523634 -0.6327244 0.6111265 0.04785621 -0.790085 0.6838164 0.1673388 -0.7102063 0.6415122 -0.008646428 -0.7670642 0.679149 0.05425965 -0.7319922 0.6627486 -0.04072749 -0.7477337 0.6627944 -0.04065352 -0.7476971 0.658638 -0.09083145 -0.7469577 0.6156804 -0.158191 -0.7719542 0.6156632 -0.1537694 -0.7728608 0.5632864 -0.2512788 -0.787126 0.5535908 -0.1509249 -0.8189988 0.5379225 -0.2118225 -0.8159478 0.5260961 -0.1396563 -0.8388797 0.5241246 -0.1542167 -0.8375623 0.5053321 -0.06352418 -0.8605837 0.4976349 -0.114586 -0.8597847 0.4915723 -0.07844734 -0.8672963 0.482727 -0.1303263 -0.8660194 0.488761 -0.1955571 -0.8502178 0.4835026 -0.2254511 -0.8458114 0.4826586 -0.401921 -0.7781391 0.4839119 -0.3964089 -0.7801854 0.4589185 -0.5983663 -0.6567736 0.4651492 -0.5802081 -0.6685767 0.4333367 -0.7058175 -0.5603936 0.4349013 -0.7024518 -0.5634026 0.4097662 -0.7689758 -0.4906809 0.4059364 -0.7755668 -0.4834374 0.3883669 -0.8113944 -0.4368185 0.3871521 -0.8132066 -0.4345208 0.3713741 -0.8404308 -0.3946611 0.3738621 -0.8371087 -0.3993447 0.3580943 -0.8610847 -0.360973 0.3604599 -0.8582782 -0.3652769 0.3436011 -0.8809779 -0.3252945 0.3420537 -0.8824991 -0.3227921 -0.7392538 -0.07059282 0.6697168 -0.7142847 0.0132988 0.6997289 -0.6782106 -0.006291389 0.7348408 -0.7263168 -0.04284644 0.6860234 -0.66205 -0.2899598 0.6910957 -0.6099271 -0.3206478 0.7246889 0.1657058 -0.7172631 0.6768127 -0.6536967 -0.01389634 0.7566291 -0.6686353 -0.02775883 0.7430723 -0.6914887 -0.2154459 0.6895118 -0.6899006 -0.06604135 0.7208855 -0.6995837 -0.1212775 0.7041836 -0.7151927 -0.1647824 0.6792247 -0.5350872 -0.4980502 0.6823692 -0.4705199 -0.6237894 0.6240977 -0.5987427 -0.4993056 0.6262597 -0.60255 -0.4116976 0.6836948 0.5050661 -0.3901878 0.7698453 0.5050656 -0.3901814 0.7698489 -0.3651484 -0.1825742 -0.912871 0.5050643 -0.3901911 0.7698447 0.4038575 -0.6613951 0.632025 0.4988614 -0.410766 0.763157 0.364162 -0.7336733 0.5736808 0.459129 -0.5334061 0.7104073 0.4374569 -0.8614361 0.257991 0.4148644 -0.7252271 0.5494845 0.467944 -0.8789368 0.09218841 0.4704262 -0.8802521 -0.06209385 -0.04962563 -0.6714565 -0.7393805 -0.04277276 -0.6491881 -0.7594244 -0.06576246 -0.6815472 -0.7288132 -0.05993127 -0.6727235 -0.7374627 -0.07803273 -0.6876108 -0.7218742 -0.07304883 -0.6824503 -0.7272727 -0.08138239 -0.6926142 -0.7167025 -0.07601863 -0.6873849 -0.7223041 -0.08321088 -0.6980603 -0.7111876 -0.0771529 -0.6921446 -0.7176235 -0.03654396 -0.3843548 -0.9224619 -0.03344053 -0.3694362 -0.9286543 -0.04883623 -0.3951125 -0.9173339 -0.0468468 -0.3896002 -0.9197919 -0.05688393 -0.3998675 -0.9148061 -0.05680948 -0.3997139 -0.9148778 -0.05831193 -0.3997353 -0.9147741 -0.05897706 -0.40116 -0.9141075 -0.05832636 -0.3980926 -0.9154892 -0.05942487 -0.4004464 -0.9143913 -0.02231472 -0.2253614 -0.9740197 -0.0253241 -0.238124 -0.9709046 -0.03010499 -0.223093 -0.9743322 -0.03429925 -0.2343278 -0.9715525 -0.03489553 -0.2197585 -0.97493 -0.04040813 -0.232083 -0.9718564 -0.0347566 -0.211994 -0.9766528 -0.04067754 -0.2252277 -0.9734566 -0.03356784 -0.2033376 -0.9785332 -0.03943926 -0.2167332 -0.975434 -0.005798757 -0.09883689 -0.9950868 -0.01151591 -0.117013 -0.9930636 -0.01040273 -0.09561878 -0.9953637 -0.01700347 -0.1088091 -0.9939172 -0.0145533 -0.09441071 -0.995427 -0.02173644 -0.1067407 -0.9940493 -0.01465302 -0.0895543 -0.9958742 -0.02200639 -0.102135 -0.9945271 -0.01222079 -0.08132898 -0.9966124 -0.02078473 -0.09616732 -0.9951483 -0.004772603 -0.06456106 -0.9979024 -0.01779407 -0.08740323 -0.9960141 -5.02621e-4 -0.05164951 -0.9986652 -0.001559913 -0.05383765 -0.9985486 -0.002563893 -0.05082297 -0.9987044 -0.006049931 -0.05527216 -0.9984531 -0.00420773 -0.04950392 -0.9987651 -0.01049482 -0.056584 -0.9983428 -0.003330051 -0.04603391 -0.9989344 -0.01092195 -0.05470412 -0.998443 0.002413094 -0.03745889 -0.9992953 -0.008191704 -0.04996061 -0.9987176 0.01574754 -0.02010607 -0.9996739 3.60901e-4 -0.03912413 -0.9992344 1.32577e-4 -0.02192986 -0.9997596 0.001208901 -0.02043706 -0.9997904 -2.45632e-4 -0.02172118 -0.9997641 -7.51322e-4 -0.02203738 -0.9997569 -2.51782e-4 -0.02102422 -0.999779 -0.002399504 -0.02203226 -0.9997544 8.68181e-4 -0.02012336 -0.9997971 -0.001432776 -0.02121311 -0.999774 0.00699532 -0.0184617 -0.9998052 0.005229353 -0.01939272 -0.9997984 0.01823627 -0.01573574 -0.99971 0.01675552 -0.01673334 -0.9997196 0.02369016 -0.01340687 -0.9996295 0.02172827 -0.01502817 -0.999651 9.00437e-5 -0.005481302 -0.999985 5.73287e-4 -0.004962027 -0.9999876 1.69892e-4 -0.005558431 -0.9999846 2.89569e-4 -0.005531013 -0.9999847 2.79569e-4 -0.00559926 -0.9999844 3.11381e-4 -0.005598425 -0.9999844 5.08424e-4 -0.006008744 -0.9999818 0.001602768 -0.006007075 -0.9999808 0.003207802 -0.008909463 -0.9999552 0.008623182 -0.008692979 -0.9999251 0.01055216 -0.01551091 -0.9998241 0.01896268 -0.01370257 -0.9997264 0.01535677 -0.02002441 -0.9996816 0.02202957 -0.01720041 -0.9996094 3.03041e-5 -8.91172e-4 -0.9999997 1.49825e-4 -7.69424e-4 -0.9999998 8.79866e-5 -9.89328e-4 -0.9999996 2.4887e-4 -9.6642e-4 -0.9999996 1.1181e-4 -0.001073896 -0.9999995 3.47402e-4 -0.001093387 -0.9999994 9.3614e-5 -0.001214861 -0.9999994 5.61815e-4 -0.001271545 -0.9999991 4.80815e-4 -0.002458989 -0.999997 0.003573238 -0.002833068 -0.9999896 0.003383994 -0.007439613 -0.9999666 0.01225709 -0.007804751 -0.9998944 0.008782923 -0.01324886 -0.9998738 0.01810801 -0.01227086 -0.9997608 0.005554676 -0.01453405 -0.999879 0.01127439 -0.01350444 -0.9998453 0.00308305 -0.01443547 -0.9998911 0.001764118 -0.01474207 -0.9998899 -6.86171e-5 -1.10529e-4 -1 3.51103e-5 2.45801e-6 -1 -4.71525e-6 -1.69038e-4 -1 9.08064e-5 -1.38339e-4 -1 3.37888e-5 -2.02906e-4 -1 1.12758e-4 -1.93413e-4 -1 3.6013e-5 -2.20782e-4 -1 9.06395e-5 -2.15965e-4 -1 5.43768e-5 -3.60988e-4 -1 4.87477e-4 -3.30272e-4 -0.9999998 5.28602e-4 -0.001402795 -0.9999989 0.003750085 -0.00125122 -0.9999923 0.003136515 -0.003647923 -0.9999885 0.0105741 -0.003379166 -0.9999385 0.004304409 -0.004143595 -0.9999822 0.006944954 -0.004023015 -0.9999679 0.008662223 -0.003741323 -0.9999555 0.003227055 -0.004121661 -0.9999863 0.01578313 -0.003024041 -0.9998709 0.007000803 -0.00378859 -0.9999684 -2.45914e-4 2.64968e-4 -1 -5.50589e-5 4.48695e-4 -1 -1.45568e-4 1.97711e-4 -1 -9.0939e-7 2.57958e-4 -1 3.14892e-5 1.92381e-4 -1 3.3557e-5 1.92936e-4 -1 8.44392e-5 2.05399e-4 -1 3.53127e-5 1.92301e-4 -1 1.36384e-4 2.27307e-4 -1 5.36703e-5 2.05744e-4 -1 3.52173e-4 1.87913e-4 -1 5.37248e-4 2.28193e-4 -0.9999999 0.001653671 1.3098e-5 -0.9999987 0.003315687 2.54423e-4 -0.9999945 0.00589168 3.03448e-4 -0.9999826 0.004496991 1.50815e-4 -0.9999899 0.01239979 8.85421e-4 -0.9999228 0.008615374 4.86058e-4 -0.9999628 0.01023131 5.59808e-4 -0.9999476 0.01569527 0.001135528 -0.9998763 -3.31037e-4 6.66961e-4 -0.9999998 -1.94299e-4 7.6758e-4 -0.9999998 -2.28171e-4 6.33046e-4 -0.9999998 -1.11728e-4 6.7498e-4 -0.9999998 1.84028e-4 6.94626e-4 -0.9999998 3.64609e-5 6.51628e-4 -0.9999999 4.2342e-4 7.91357e-4 -0.9999997 8.4982e-5 6.83767e-4 -0.9999998 6.24429e-4 9.16199e-4 -0.9999995 1.37229e-4 7.47914e-4 -0.9999997 0.001176595 0.001143276 -0.9999987 3.53726e-4 8.64052e-4 -0.9999997 0.003291666 0.001737117 -0.9999931 0.001663625 0.001252651 -0.9999979 0.009245991 0.003267168 -0.999952 0.005927503 0.002367436 -0.9999796 0.01053589 0.003531157 -0.9999383 0.01272124 0.004108428 -0.9999107 0.003415942 0.001621723 -0.9999929 0.01212728 0.003905236 -0.9999189 -1.42255e-4 6.45016e-4 -0.9999999 -3.61621e-4 4.83859e-4 -0.9999998 5.60884e-5 7.28988e-4 -0.9999998 -2.26818e-4 6.40961e-4 -0.9999998 7.51735e-4 8.77616e-4 -0.9999994 1.86367e-4 7.40062e-4 -0.9999997 0.001512527 0.001137495 -0.9999983 4.23864e-4 8.32855e-4 -0.9999996 0.002376079 0.001537561 -0.999996 6.24799e-4 9.63527e-4 -0.9999994 0.004102766 0.002266407 -0.9999891 0.001177549 0.001232743 -0.9999986 0.00921756 0.004092335 -0.9999492 0.00329715 0.002025842 -0.9999926 0.01534664 0.00619173 -0.9998631 0.009321272 0.004125416 -0.9999482 0.01023554 0.004526197 -0.9999375 0.01131802 0.004899084 -0.999924 0.001897156 0.0018 -0.9999967 0.004682064 0.002788305 -0.9999852 1.29645e-5 -7.40262e-4 -0.9999998 -2.20238e-4 -0.001093864 -0.9999994 8.43666e-5 -6.83266e-4 -0.9999998 -4.83494e-5 -7.35157e-4 -0.9999998 4.62141e-4 -7.79886e-4 -0.9999997 6.95527e-4 -7.56868e-4 -0.9999995 0.001136958 -9.29748e-4 -0.9999989 0.001455724 -9.20026e-4 -0.9999985 0.002249658 -0.001093447 -0.999997 0.002291023 -0.001093089 -0.9999968 0.004818022 -0.001314282 -0.9999876 0.003944694 -0.001304209 -0.9999914 0.0114817 -0.001792907 -0.9999325 0.008719027 -0.001699805 -0.9999606 0.01788288 -0.002070248 -0.999838 0.01283085 -0.001905024 -0.999916 0.01231688 -0.001048505 -0.9999236 0.005171 -0.001165628 -0.9999861 0.003274142 3.55298e-5 -0.9999946 -9.97649e-4 -5.56058e-4 -0.9999994 1.85877e-4 -0.004441201 -0.9999901 1.80399e-4 -0.004487335 -0.99999 4.53098e-5 -0.00452876 -0.9999898 1.10118e-4 -0.004415333 -0.9999903 5.95949e-5 -0.004866719 -0.9999883 4.04275e-4 -0.00475794 -0.9999886 1.89146e-4 -0.005555152 -0.9999846 9.96171e-4 -0.00582832 -0.9999825 4.91209e-4 -0.006783843 -0.9999769 0.001951396 -0.00809592 -0.9999654 0.00127536 -0.009192049 -0.999957 0.003951907 -0.01299011 -0.9999079 0.003986418 -0.01568758 -0.9998691 0.008451998 -0.02359223 -0.999686 0.009255647 -0.02700018 -0.9995926 0.01093578 -0.03012812 -0.9994863 0.01123136 -0.0273844 -0.999562 0.00313282 -0.0144236 -0.9998911 0.005802452 -0.01086568 -0.9999242 -0.001710772 -0.004366636 -0.999989 -2.05459e-4 0.002831459 -0.999996 -2.04585e-4 0.002936065 -0.9999957 -8.16451e-5 0.002541303 -0.9999968 -5.43853e-5 0.002780318 -0.9999962 -2.84946e-5 0.001936972 -0.9999982 8.92265e-5 0.002402544 -0.9999971 7.25901e-6 9.28654e-4 -0.9999996 2.54134e-4 0.001482069 -0.9999989 9.34979e-5 -8.36728e-4 -0.9999997 5.93674e-4 -6.24485e-4 -0.9999997 3.55489e-4 -0.003951847 -0.9999922 0.001403689 -0.005762577 -0.9999824 0.001506984 -0.01178306 -0.9999295 0.003645896 -0.01919966 -0.9998091 0.004401326 -0.02831941 -0.9995893 0.006955206 -0.03890353 -0.9992188 0.007892668 -0.04474264 -0.9989674 0.006799638 -0.04033082 -0.9991633 0.01005047 -0.03932613 -0.9991759 0.001799106 -0.01606965 -0.9998694 -8.1154e-4 0.02900069 -0.9995791 -9.42415e-4 0.02146387 -0.9997693 -2.39412e-4 0.03013283 -0.999546 -3.46071e-4 0.02897882 -0.99958 -5.00834e-5 0.02990359 -0.9995528 -1.90889e-5 0.03010106 -0.999547 -2.96273e-5 0.02934044 -0.9995695 6.5169e-5 0.02985966 -0.9995541 4.55511e-5 0.02831262 -0.9995991 2.37411e-4 0.02913683 -0.9995754 3.25692e-4 0.02635103 -0.9996527 7.87243e-4 0.02732944 -0.9996263 0.001804411 0.0215637 -0.9997659 0.002989709 0.02126497 -0.9997695 0.006627261 0.00941646 -0.9999337 0.008750915 0.006602585 -0.9999399 0.01298582 -0.005815267 -0.9998988 0.01517432 -0.009210646 -0.9998425 0.01770961 -0.0158329 -0.9997178 0.01748895 -0.01550358 -0.9997269 -7.6846e-4 0.0543226 -0.9985232 -0.001129984 0.04202687 -0.999116 -1.98047e-4 0.05630064 -0.9984139 -3.86833e-4 0.05432474 -0.9985233 -4.93731e-5 0.05635064 -0.9984111 -5.70219e-5 0.05629748 -0.9984141 -4.09304e-5 0.05621778 -0.9984186 -1.99121e-5 0.05634981 -0.9984112 4.57862e-5 0.05595642 -0.9984332 9.04032e-5 0.05620712 -0.9984192 4.12948e-4 0.05542594 -0.9984627 5.24001e-4 0.0558604 -0.9984385 0.002374827 0.05410051 -0.9985327 0.002710759 0.05462259 -0.9985034 0.008857429 0.05047321 -0.9986862 0.01022326 0.05101943 -0.9986454 0.01804202 0.04531544 -0.9988098 0.02099764 0.04566031 -0.9987364 0.02506852 0.04083782 -0.9988514 0.02873468 0.04106324 -0.9987434 -9.64071e-4 0.1569027 -0.9876136 -0.00176388 0.1334202 -0.9910581 -1.64539e-4 0.1602336 -0.9870792 -4.74135e-4 0.1568973 -0.9876148 -3.56658e-5 0.1604241 -0.9870483 -6.27174e-5 0.1602314 -0.9870795 -2.0242e-5 0.160445 -0.9870448 -2.40288e-5 0.160422 -0.9870486 1.66029e-4 0.1604691 -0.9870409 1.61464e-4 0.1604449 -0.9870448 0.001039028 0.160681 -0.9870059 9.90575e-4 0.1604589 -0.9870421 0.005142271 0.1609463 -0.9869499 0.00498116 0.1606267 -0.9870027 0.01675641 0.1607912 -0.9868463 0.01707601 0.1610641 -0.9867962 0.02870523 0.1589315 -0.9868723 0.03268468 0.1611157 -0.9863942 0.03654748 0.1557546 -0.9871196 0.04361289 0.1591265 -0.9862945 -0.001790165 0.687221 -0.7264462 -0.00367558 0.6582312 -0.752807 -1.96641e-4 0.6893167 -0.7244602 -5.429e-4 0.6872002 -0.7264679 -2.36587e-5 0.6893004 -0.7244757 -2.21884e-5 0.6893073 -0.7244692 7.95491e-5 0.6893299 -0.7244476 7.05838e-5 0.6893065 -0.7244699 8.12641e-4 0.6894781 -0.7243061 7.69956e-4 0.6893544 -0.7244238 0.004257261 0.6900814 -0.7237194 0.004030823 0.6894848 -0.724289 0.01940858 0.6912434 -0.7223613 0.01844304 0.690109 -0.7234705 0.05689126 0.6921231 -0.7195339 0.0549404 0.6912482 -0.7205258 0.08313012 0.6901077 -0.7189164 0.08845317 0.6916657 -0.7167809 0.09462124 0.6861699 -0.7212612 0.1075913 0.6892727 -0.7164688 -0.001401662 0.9656627 -0.2597959 -0.002297878 0.9640152 -0.2658375 -2.07903e-4 0.9656722 -0.2597637 -2.2172e-4 0.9656639 -0.2597947 -3.21547e-5 0.9656629 -0.2597982 -8.48216e-6 0.9656743 -0.2597561 1.04776e-4 0.9656462 -0.2598605 1.37749e-4 0.9656645 -0.2597926 9.97899e-4 0.965593 -0.2600558 0.001121938 0.965648 -0.2598513 0.005072712 0.965373 -0.2608242 0.005713403 0.9655795 -0.2600456 0.02339416 0.9647828 -0.2620059 0.0257517 0.9650753 -0.260704 0.07150751 0.9623842 -0.2621133 0.07461333 0.9623486 -0.2613773 0.1110988 0.9587923 -0.2614853 0.1125215 0.9586994 -0.2612171 0.1327753 0.9562337 -0.2607449 0.13122 0.9563813 -0.2609906 -0.02064353 -0.9973844 0.06926953 -0.0783807 -0.9948765 0.06385385 -0.02355378 -0.9979041 0.06027328 -0.08275002 -0.995077 0.05453699 -0.02605426 -0.9983885 0.05041325 -0.08265364 -0.9955902 0.04436933 -0.02424234 -0.998909 0.03991478 -0.07704448 -0.9964414 0.0341894 -0.01782411 -0.9994083 0.02941894 -0.0604518 -0.9978595 0.02494317 -0.009629487 -0.9997465 0.02035164 -0.03594726 -0.9992033 0.01733744 -0.005613803 -0.9998782 0.01456576 -0.02087759 -0.9997047 0.01244151 -0.004201769 -0.9999276 0.01127785 -0.01803278 -0.9997981 0.008869051 -0.004294931 -0.9999557 0.008381843 -0.0233308 -0.999719 0.004227817 -0.003900885 -0.9999826 0.004446804 -0.03011429 -0.9995366 -0.004424929 -0.07665342 -0.9875652 0.1372563 -0.1607911 -0.9801521 0.1159669 -0.08277535 -0.9887444 0.124631 -0.1683861 -0.9803321 0.1029326 -0.08638334 -0.9900289 0.1112694 -0.1732807 -0.9808514 0.08890616 -0.08311462 -0.9917524 0.09756678 -0.1703451 -0.9825301 0.07494866 -0.06754416 -0.9941461 0.0843293 -0.1496847 -0.9867452 0.0626769 -0.04575216 -0.9963902 0.07150691 -0.1189413 -0.9915599 0.05159324 -0.03167569 -0.997731 0.05941206 -0.09818083 -0.9943431 0.04052513 -0.02705979 -0.9984496 0.04864531 -0.09668141 -0.9949537 0.02683317 -0.02899736 -0.9989065 0.03667569 -0.1080124 -0.9941024 0.009682059 -0.02895182 -0.9993289 0.02244228 -0.09682095 -0.9952868 -0.005468487 -0.1531909 -0.9750348 0.1607475 -0.2024911 -0.9687368 0.1433405 -0.1599027 -0.9752219 0.1528834 -0.2117125 -0.9680761 0.1341882 -0.1649097 -0.9756158 0.1448399 -0.220375 -0.9674602 0.1243211 -0.1628694 -0.9769964 0.137665 -0.2253915 -0.9675663 0.1140801 -0.1450306 -0.9804435 0.1330289 -0.221211 -0.9697248 0.1034397 -0.1199806 -0.984525 0.1277311 -0.215541 -0.9723612 0.08975529 -0.1031022 -0.9876726 0.1177831 -0.2208055 -0.9727385 0.07088571 -0.1013631 -0.9895682 0.1023742 -0.2339193 -0.9710912 0.04758024 -0.1057972 -0.9909179 0.08299767 -0.2305894 -0.9726299 0.02863359 -0.08247131 -0.9941998 0.0690307 -0.1662166 -0.9857164 0.02711713 -0.1992796 -0.9674779 0.1558017 -0.2261668 -0.9631978 0.1452541 -0.2075269 -0.9666114 0.1503168 -0.2347323 -0.9620186 0.1393598 -0.2150637 -0.965794 0.1448781 -0.2436073 -0.9607032 0.1330601 -0.2186163 -0.9656722 0.1403009 -0.252678 -0.9593265 0.1258833 -0.2128971 -0.9673059 0.1378191 -0.2589596 -0.9586912 0.117691 -0.2059655 -0.9693021 0.1342827 -0.2675978 -0.9576077 0.1066727 -0.2089422 -0.9698028 0.1258001 -0.2844052 -0.9542828 0.09196794 -0.2188238 -0.9691102 0.1137611 -0.3042007 -0.949656 0.07493799 -0.209688 -0.9719695 0.1063315 -0.2994622 -0.9519473 0.06417667 -0.1430078 -0.9831063 0.1142407 -0.2166891 -0.9732876 0.07587605 -0.2265374 -0.9632985 0.1440035 -0.2470607 -0.9594295 0.1358538 -0.2347383 -0.9620216 0.1393282 -0.2556957 -0.9578723 0.1307684 -0.2431713 -0.9606194 0.134455 -0.2651577 -0.9560465 0.1251661 -0.2515551 -0.959157 0.1293752 -0.2753717 -0.9539401 0.1190333 -0.2565438 -0.9583991 0.1251264 -0.2834156 -0.9523069 0.1130807 -0.263255 -0.9572441 0.1199194 -0.2941713 -0.9498959 0.1056466 -0.277724 -0.9541712 0.1114755 -0.3109618 -0.9455783 0.09583616 -0.2949782 -0.9500823 0.1016449 -0.3270947 -0.9410542 0.08617502 -0.2878745 -0.9523835 0.1004691 -0.3248591 -0.9422026 0.08198124 -0.2096529 -0.9700133 0.122964 -0.2245832 -0.9677226 0.1143481 -0.2481384 -0.9596392 0.1323632 -0.2689402 -0.9550742 0.1245172 -0.2566649 -0.9580152 0.1277892 -0.2777576 -0.9531714 0.1196461 -0.2659229 -0.9561224 0.1229438 -0.2883027 -0.9507237 0.1140446 -0.2758331 -0.95397 0.1177182 -0.2970988 -0.9486058 0.1089932 -0.2833587 -0.9523036 0.1132515 -0.3003175 -0.9479234 0.1060698 -0.29318 -0.9498951 0.1083734 -0.3155413 -0.9437742 0.09861093 -0.3091354 -0.9456639 0.1007735 -0.3205071 -0.9424036 0.09565937 -0.324105 -0.9412971 0.09442341 -0.3024072 -0.9474506 0.1043419 -0.3193858 -0.9424667 0.0987392 -0.2948808 -0.9491732 0.1100704 -0.2228503 -0.9658105 0.1324689 -0.1621425 -0.9726861 0.1661075 -0.2691934 -0.9551068 0.1237177 -0.2901526 -0.9498617 0.1165084 -0.2778352 -0.9531788 0.1194065 -0.2951207 -0.948706 0.1134056 -0.2878999 -0.9507144 0.1151348 -0.3035225 -0.9464879 0.109704 -0.2961447 -0.9486123 0.1115038 -0.3011218 -0.9472464 0.1097728 -0.29873 -0.9479355 0.1103577 -0.2722074 -0.9547812 0.1195665 -0.3111189 -0.9439422 0.1103551 -0.2997965 -0.9471381 0.1142429 -0.3152279 -0.9425516 0.11058 -0.2376276 -0.9616507 0.1369708 -0.2962056 -0.9468253 0.1256352 -0.172033 -0.9712958 0.1642836 -0.2841914 -0.9465286 0.1527054 -0.1635975 -0.9697201 0.181325 -0.1632451 -0.9697776 0.1813353 -0.08568668 -0.9744116 0.2077978 -0.2871825 -0.9495325 0.1261516 -0.3130571 -0.9423079 0.1185376 -0.2922621 -0.9484886 0.1222794 -0.3035149 -0.9453647 0.1190148 -0.3000127 -0.9464052 0.1196224 -0.2705815 -0.954184 0.1277447 -0.2960137 -0.9470934 0.1240561 -0.2128748 -0.966363 0.1443154 -0.2661975 -0.9537871 0.1393887 -0.1421879 -0.9761801 0.1638755 -0.2828555 -0.9451516 0.1633441 -0.163999 -0.9705221 0.1766104 -0.2293624 -0.9563743 0.180945 -0.1128141 -0.9755178 0.1887801 -0.1720763 -0.9644171 0.2007222 -0.07841503 -0.9768533 0.1990193 -0.1669384 -0.9580021 0.2331598 -0.07768648 -0.9739106 0.213221 -0.0892924 -0.9716292 0.219006 -0.04295605 -0.9765109 0.211143 -0.3037911 -0.9402699 0.1536349 -0.3309412 -0.9321151 0.1471034 -0.2947288 -0.9435956 0.1508718 -0.2540135 -0.9539366 0.1596313 -0.2626069 -0.9516682 0.1592658 -0.1559904 -0.9718542 0.1765406 -0.206546 -0.9614937 0.1812971 -0.09217262 -0.9781776 0.1862064 -0.1416267 -0.969685 0.1991308 -0.04904061 -0.9803605 0.1910194 -0.1596389 -0.9574486 0.2404326 -0.06499552 -0.9749847 0.2125573 -0.1197372 -0.9624798 0.2435074 -0.06453561 -0.9724452 0.2240211 -0.08925998 -0.9665367 0.2404987 -0.05287849 -0.9724718 0.2269418 -0.08956658 -0.962755 0.255109 -0.04633963 -0.9718268 0.2310963 -0.05254578 -0.9702961 0.2361451 -0.01141172 -0.9765774 0.2148634 -0.3180227 -0.919954 0.2292299 -0.2524222 -0.9380728 0.2372819 -0.246886 -0.939675 0.2367662 -0.1608223 -0.9569439 0.2416498 -0.1587297 -0.9574282 0.2411145 -0.0907315 -0.9668221 0.2387949 -0.1003474 -0.964697 0.243496 -0.05216598 -0.9713166 0.2319975 -0.05993181 -0.969612 0.2371935 -0.02227437 -0.9745338 0.2231317 -0.07555079 -0.9612655 0.2650678 -0.02041864 -0.9720503 0.2338829 -0.08036112 -0.9557298 0.2830598 -0.03055572 -0.966311 0.2555574 -0.07352209 -0.954693 0.2883676 -0.03965538 -0.9603016 0.2761313 -0.06545782 -0.9539421 0.2927625 -0.01334059 -0.9614349 0.2747091 -0.03143078 -0.9581302 0.2846028 0.05841445 -0.9634113 0.2615847 -0.2617369 -0.9004954 0.347278 -0.1417111 -0.9370487 0.3191516 -0.177407 -0.9243012 0.3379261 -0.1083927 -0.9418059 0.3182023 -0.1112599 -0.9408609 0.320003 -0.07477229 -0.9474707 0.31098 -0.07469141 -0.9474971 0.310919 -0.04924619 -0.9518687 0.3025242 -0.04682421 -0.9525427 0.3007823 -0.0219919 -0.95561 0.2938127 -0.03911995 -0.951689 0.3045618 0.01090633 -0.9574258 0.2884731 -0.04515993 -0.9470585 0.3178694 0.04893124 -0.9548906 0.292899 -0.05648177 -0.9406229 0.3347215 0.02754491 -0.942813 0.3321822 -0.02635663 -0.9390227 0.3428435 0.08880323 -0.9332997 0.3479452 0.05612134 -0.9347574 0.3508263 0.1614041 -0.9180149 0.362212 -0.1563692 -0.9153668 0.3710152 -0.07402437 -0.941654 0.3283417 -0.1217426 -0.9228789 0.3653401 -0.05828428 -0.9407413 0.334079 -0.08871656 -0.9303242 0.3558459 -0.04886096 -0.9370437 0.3457772 -0.06491935 -0.9326416 0.3549156 -0.01864111 -0.9370003 0.3488308 -0.04025763 -0.9331716 0.3571699 0.02185189 -0.9328899 0.3594983 -0.001906991 -0.9315655 0.3635687 0.1002615 -0.9230141 0.3714736 0.05037331 -0.9259835 0.3741888 0.1777545 -0.9053248 0.3857339 0.02675414 -0.922752 0.3844645 0.1633206 -0.8968458 0.411089 0.1038154 -0.9080823 0.4057203 0.2163529 -0.8772796 0.4284532 0.1809566 -0.8871502 0.4245225 0.186987 -0.8851395 0.4261032 -0.08101677 -0.9337819 0.3485509 -0.01405686 -0.9442995 0.3287872 -0.06346297 -0.9333411 0.3533369 0.03264921 -0.9425666 0.3324186 -0.05325615 -0.9303456 0.3627961 0.02219229 -0.9298588 0.3672469 -0.02281731 -0.9276608 0.3727263 0.07777839 -0.9168272 0.3916359 0.01994353 -0.9212285 0.3885104 0.1364609 -0.8966009 0.42129 0.1108477 -0.9020457 0.4171646 0.188969 -0.8782855 0.43921 0.2095575 -0.8717716 0.4428318 0.2007529 -0.8750041 0.4405293 0.1777316 -0.8821085 0.4362292 0.1772041 -0.8822928 0.4360713 0.2328947 -0.8640663 0.4462618 0.1924319 -0.8791006 0.4360644 0.1924989 -0.8790771 0.4360821 0.1398445 -0.8971914 0.4189165 -0.02175241 -0.934526 0.3552294 0.05368357 -0.9295996 0.3646404 0.03045743 -0.930387 0.3653115 0.1243769 -0.9170116 0.3789726 0.0222879 -0.9275318 0.3730792 0.1167006 -0.9092975 0.3994487 0.07800424 -0.9164398 0.3924964 0.13885 -0.9005663 0.4119476 0.1312757 -0.9025179 0.4101561 0.1243055 -0.9046075 0.4077173 0.1765919 -0.8896048 0.4212111 0.1158509 -0.9091653 0.3999963 0.1835826 -0.8900464 0.4172709 0.1121463 -0.9127283 0.3928743 0.1587428 -0.9007658 0.4042548 0.1059724 -0.9162613 0.3863098 0.1598255 -0.9032998 0.3981274 0.1053065 -0.9183006 0.381621 0.1190014 -0.9154757 0.3843734 0.07246071 -0.9270067 0.3679782 0.05081957 -0.9125728 0.4057442 0.03358054 -0.9150846 0.4018615 0.1330659 -0.9039034 0.4065122 0.05166381 -0.9171606 0.3951549 0.1153542 -0.910658 0.396731 0.06923514 -0.9177055 0.3911817 0.1263765 -0.9107999 0.3930299 0.06251436 -0.9205988 0.3854737 0.111919 -0.9150508 0.3875 0.05429738 -0.9235826 0.3795355 0.1041715 -0.918461 0.3815464 0.05225771 -0.9259678 0.3739692 0.1024503 -0.9211117 0.3755759 0.05416816 -0.9279727 0.3686904 0.1011943 -0.9236029 0.3697532 0.05787163 -0.9297549 0.3636024 0.09671342 -0.9262997 0.364164 0.0549184 -0.9318248 0.358729 0.06845694 -0.9308821 0.3588486 0.03867858 -0.93473 0.3532475 0.03377598 -0.9139826 0.4043452 0.004675567 -0.9193675 0.3933721 0.0524311 -0.9154403 0.399024 0.008274734 -0.9212998 0.3887651 0.06904923 -0.9179408 0.3906624 0.01483559 -0.9230515 0.3843901 0.06180202 -0.9214783 0.3834819 0.01554894 -0.9246233 0.3805655 0.05398845 -0.9240183 0.3785178 0.01722759 -0.9261854 0.3766749 0.05230236 -0.9259127 0.3740994 0.01855868 -0.9278455 0.3725026 0.05443459 -0.9276064 0.3695719 0.02079278 -0.9295694 0.3680604 0.05803328 -0.9292206 0.3649401 0.02341014 -0.9313845 0.3632836 0.05538016 -0.9310426 0.3606839 0.0224719 -0.9330847 0.3589541 0.03979158 -0.9330198 0.3576184 0.01704281 -0.93478 0.3548184 0.01259112 -0.933592 0.3581168 0.002155005 -0.9359934 0.3520113 0.01364737 -0.9340889 0.3567799 0.002328634 -0.9364569 0.350775 0.01559782 -0.9344775 0.3556805 0.002668976 -0.9370061 0.349303 0.01683109 -0.9350939 0.3540003 0.002742171 -0.9376809 0.3474867 0.01913154 -0.9356414 0.3524332 0.00340557 -0.9383605 0.3456417 0.02285689 -0.9361132 0.3509554 0.004296362 -0.9391915 0.343367 0.02151274 -0.9373638 0.3476871 0.004127383 -0.9400854 0.3409142 0.01587587 -0.9390004 0.3435495 0.004012882 -0.9409793 0.3384405 0.001656055 -0.9576259 0.2880102 2.73028e-5 -0.9578462 0.2872818 0.002043843 -0.9576871 0.2878044 -2.5688e-4 -0.9579881 0.286808 0.002049446 -0.957821 0.2873584 -3.54641e-4 -0.9581184 0.286372 0.002365469 -0.9579351 0.2869753 -2.86726e-4 -0.9582518 0.2859258 0.003773629 -0.9579952 0.2867593 -1.84797e-4 -0.9584506 0.2852586 0.003285646 -0.9582502 0.2859122 1.16976e-4 -0.9586054 0.2847379 0.002788484 -0.9584663 0.2851924 0.001577436 -0.9586279 0.2846579 -5.0609e-4 -0.9856995 0.1685123 -0.004593849 -0.9859749 0.166831 -5.33145e-4 -0.9858523 0.1676162 -0.004759669 -0.9861333 0.1658869 -6.0929e-4 -0.986012 0.1666734 -0.004842698 -0.986288 0.1649625 -4.69933e-4 -0.9861649 0.1657664 -0.00513935 -0.9864652 0.1638908 -3.52512e-4 -0.9863348 0.1647535 -0.004877746 -0.9866297 0.1629052 1.6541e-5 -0.9865 0.1637616 -0.004006803 -0.9868294 0.161715 -0.007552027 -0.9933592 -0.114807 -0.028297 -0.9919368 -0.123534 -0.007676959 -0.9927822 -0.1196848 -0.02841436 -0.9913147 -0.1284049 -0.007913708 -0.9921771 -0.1245875 -0.02908033 -0.9906213 -0.1335054 -0.00755465 -0.9915496 -0.1295078 -0.02716296 -0.9900574 -0.1380168 -0.007556676 -0.990896 -0.1344177 -0.02023452 -0.9897497 -0.1413723 -1.43343e-4 0.9967826 -0.08015239 -5.11433e-4 0.9969504 -0.07803773 -1.11184e-4 0.996963 -0.07787686 -9.0571e-5 0.9969594 -0.07792305 -8.20846e-5 0.9969592 -0.07792645 -6.14963e-5 0.9969567 -0.07795935 -1.24156e-5 0.9969568 -0.07795685 2.47825e-6 0.9969545 -0.07798534 3.91352e-4 0.9969547 -0.07798099 4.79622e-4 0.9969453 -0.07810199 0.002453386 0.9969486 -0.07802319 0.003100216 0.9968953 -0.07867765 0.01241111 0.996865 -0.07814121 0.01621389 0.996665 -0.07997447 0.04961079 0.9956279 -0.07914561 0.06015926 0.994861 -0.08144122 0.1159128 0.9899088 -0.08151668 0.1197487 0.9894011 -0.08213216 0.1704221 0.9819115 -0.08249974 0.1635906 0.9831627 -0.08142006 -0.005437076 -0.999706 0.02363014 -0.01849865 -0.9995775 0.02242118 -0.004365563 -0.9997894 0.02005481 -0.01992356 -0.9996303 0.01850503 -0.00509119 -0.9998607 0.01590114 -0.01974534 -0.9997029 0.01429617 -0.004630506 -0.9999237 0.01145595 -0.01796448 -0.9997871 0.0101602 -0.003318309 -0.9999682 0.007252573 -0.01331466 -0.9998908 0.006413638 -0.001544356 -0.9999909 0.003998458 -0.005766808 -0.9999772 0.00354278 -9.12265e-4 -0.9999964 0.002534985 -0.002380013 -0.9999946 0.002317488 -7.27445e-4 -0.9999979 0.001979112 -0.00184524 -0.9999967 0.001781702 -7.51241e-4 -0.9999985 0.001573145 -0.002428412 -0.9999964 0.001136779 -4.3817e-4 -0.9999996 8.73781e-4 -0.003217637 -0.9999947 -4.96201e-4 -0.03230369 -0.918861 -0.3932569 -0.06615471 -0.917981 -0.3910685 -0.0327304 -0.9156157 -0.4007201 -0.0664035 -0.9147713 -0.3984773 -0.03041547 -0.912521 -0.4078977 -0.06273019 -0.9120466 -0.4052605 -0.02206331 -0.9091497 -0.4158846 -0.04785096 -0.9105942 -0.4105222 -0.04852366 -0.8370241 -0.5450103 -0.0333243 -0.8227728 -0.5673928 -0.06614607 -0.8426692 -0.5343534 -0.04800951 -0.8370707 -0.5449843 -0.08039391 -0.8456689 -0.5276182 -0.06252861 -0.843062 -0.5341691 -0.08358532 -0.8495258 -0.5208835 -0.06602114 -0.8473522 -0.5269114 -0.08466273 -0.8538625 -0.5135671 -0.06595313 -0.8516128 -0.5200057 -5.2252e-4 0.991814 -0.1276901 -0.001394391 0.9913868 -0.1309596 -9.43258e-5 0.9918373 -0.1275104 -2.02779e-4 0.9918164 -0.1276724 -6.21074e-5 0.991833 -0.1275439 -2.78343e-5 0.9918379 -0.1275061 1.04754e-5 0.9918217 -0.1276321 1.06913e-4 0.9918334 -0.1275406 5.28589e-4 0.9917709 -0.1280246 9.83086e-4 0.991821 -0.1276332 0.003284931 0.991621 -0.12914 0.005016028 0.9917606 -0.1280078 0.01680034 0.9912438 -0.1309711 0.02326041 0.9913687 -0.1290239 0.06069827 0.9893347 -0.1324113 0.07199507 0.9887606 -0.1310319 0.116609 0.9842872 -0.1325937 0.1162581 0.9843244 -0.1326262 0.1574194 0.9787341 -0.1315253 0.1418261 0.9809536 -0.1327233 -0.3140181 -0.8617738 -0.3984201 -0.1097932 -0.5745246 -0.8110901 -0.2323034 -0.8970372 -0.3759782 -0.05464375 -0.6512854 -0.756863 -0.1585095 -0.9240207 -0.3479378 -0.02796262 -0.7537855 -0.6565254 -0.06631976 -0.9080393 -0.4136018 -0.008727431 -0.8309255 -0.5563152 -0.01168924 -0.8815106 -0.4720197 2.16817e-4 -0.8642054 -0.5031393 0.002272307 -0.8701037 -0.4928634 5.36298e-4 -0.8733404 -0.4871103 -0.1559789 -0.3290235 -0.9313508 -0.04868799 -0.122214 -0.9913089 -0.2289204 -0.5461923 -0.8057726 -0.03738182 -0.1325513 -0.990471 -0.109579 -0.3935926 -0.9127308 -0.02159708 -0.1528242 -0.9880174 -0.02092218 -0.2131422 -0.9767972 -0.007968008 -0.1666517 -0.9859837 -0.001748442 -0.16606 -0.9861142 -0.00243175 -0.1693514 -0.9855528 -0.03157132 -0.03555458 -0.998869 -0.02368205 -0.02346533 -0.9994442 -0.01154613 -0.01640892 -0.9997988 -0.007470965 -0.009270668 -0.9999292 -0.003197431 -0.009480178 -0.99995 -0.00155735 -0.005603432 -0.9999831 -0.005578458 0.02079516 -0.9997683 -0.007099509 0.01903504 -0.9997936 -0.004797577 0.01944458 -0.9997994 -0.002825617 0.02245712 -0.9997438 -0.004919946 0.02041977 -0.9997794 -0.005714178 0.01961618 -0.9997913 -0.005557477 0.01930791 -0.9997981 -0.004759609 0.02046924 -0.9997792 -0.004784703 0.01751095 -0.9998353 -0.005368649 0.01695632 -0.9998419 -0.005831718 0.01722282 -0.9998348 -0.005688607 0.0174297 -0.999832 -0.002768993 0.02036684 -0.9997888 -0.006002783 0.01563608 -0.9998598 0.01688754 -3.50639e-4 -0.9998574 0.0286377 6.82075e-4 -0.9995896 0.03386801 8.32161e-4 -0.999426 0.02906918 2.14677e-4 -0.9995774 0.004482865 7.00354e-4 -0.9999898 0.01904714 0.003166794 -0.9998136 0.0237016 0.002105474 -0.9997169 0.03465837 0.003434062 -0.9993934 0.05168366 0.004826605 -0.9986519 0.0409764 0.003623545 -0.9991536 0.05809605 0.005868494 -0.9982938 0.04140847 0.003867626 -0.9991348 0.04166972 0.004818737 -0.9991198 0.03028106 0.003041386 -0.9995369 0.002290427 0.00138843 -0.9999965 0.006763696 0.002700209 -0.9999735 0.01779639 0.004383385 -0.9998321 0.02675139 0.006472766 -0.9996213 0.05469119 0.01169681 -0.9984349 0.05220746 0.01116693 -0.9985738 0.05371093 0.0114293 -0.9984911 0.05842524 0.01243376 -0.9982144 0.02277117 0.004891753 -0.9997288 0.04425448 0.009579539 -0.9989744 0.01068007 0.001991748 -0.999941 0.02877765 0.005973696 -0.999568 0.01396489 0.001883864 -0.9999008 0.02791422 0.004589915 -0.9995998 0.007545709 0.002131998 -0.9999693 0.00132817 6.39801e-4 -0.999999 0.03117281 0.006876766 -0.9994904 0.01724171 0.003864407 -0.9998439 0.05475324 0.01139587 -0.9984349 0.05450898 0.01134544 -0.9984489 0.03387039 0.007077217 -0.9994012 0.05353164 0.01116299 -0.9985038 0.01183646 0.00267291 -0.9999264 0.0230177 0.005105674 -0.9997221 0.005205929 0.001232504 -0.9999857 0.0114367 0.002609968 -0.9999312 0.009932279 0.001525998 -0.9999495 0.01434206 0.002339482 -0.9998944 0.02134937 0.00296235 -0.9997678 0.01749396 0.002308011 -0.9998443 0.01562947 -0.006049096 -0.9998596 0.001624584 -0.002852857 -0.9999947 0.03980809 -0.01196956 -0.9991357 0.01954853 -0.007261633 -0.9997826 0.04930996 -0.01430159 -0.9986811 0.04300874 -0.01284396 -0.9989922 0.0329644 -0.008976638 -0.9994162 0.02072799 -0.006656408 -0.999763 0.01280772 -0.002834975 -0.9999141 0.005379676 -0.002310633 -0.9999829 0.00757426 -7.82259e-4 -0.9999711 0.002121508 -0.001024961 -0.9999973 0.01761257 -2.02555e-4 -0.999845 0.007230937 -7.55832e-4 -0.9999737 0.04468995 0.001143276 -0.9990003 0.01932638 -2.3159e-4 -0.9998133 0.0590552 0.004470944 -0.9982447 0.02185291 6.9498e-4 -0.9997611 0.02163761 -0.03600507 -0.9991174 0.007071971 -0.01657849 -0.9998376 0.02949523 -0.04756945 -0.9984325 0.02699744 -0.04423278 -0.9986564 0.03293877 -0.05313378 -0.998044 0.03521811 -0.05618321 -0.9977992 0.03255909 -0.04810374 -0.9983116 0.01776146 -0.03030467 -0.999383 0.02169948 -0.02270305 -0.9995068 0.004652917 -0.009851872 -0.9999407 0.01720613 -0.009711623 -0.9998048 0.002556562 -0.004624068 -0.9999861 0.03479218 -0.01285868 -0.9993119 0.01055878 -0.00626558 -0.9999247 0.06115347 -0.01999157 -0.9979282 0.03555583 -0.01313436 -0.9992814 0.07299578 -0.02155786 -0.9970993 0.04798251 -0.01573741 -0.9987243 0.02613437 -0.0266065 -0.9993043 0.02525168 -0.02556777 -0.9993542 0.02960467 -0.03333353 -0.9990057 0.03253853 -0.03681361 -0.9987923 0.03275299 -0.03960454 -0.9986785 0.03586661 -0.04332733 -0.9984169 0.0357787 -0.04395741 -0.9983926 0.03465646 -0.04265254 -0.9984887 0.03834253 -0.0370723 -0.9985768 0.02189123 -0.02243864 -0.9995086 0.03896939 -0.021757 -0.9990036 0.0164321 -0.01050174 -0.9998099 0.05124634 -0.02484571 -0.998377 0.03200525 -0.01655936 -0.9993506 0.05848437 -0.02910834 -0.997864 0.05761033 -0.02872741 -0.9979258 0.06326055 -0.03285425 -0.9974562 0.06790137 -0.03474342 -0.997087 0.03691107 0.03304737 -0.998772 0.04058533 0.03320652 -0.9986242 0.04192137 0.0296489 -0.998681 0.0459004 0.02979737 -0.9985015 0.04652625 0.02633541 -0.99857 0.05089926 0.02646929 -0.998353 0.05125069 0.02305394 -0.9984198 0.0556603 0.02315521 -0.9981814 0.05533462 0.02028805 -0.9982618 0.05901819 0.02038592 -0.9980487 0.05950427 0.01914292 -0.9980446 0.05901777 0.0191124 -0.998074 0.06339114 0.01703757 -0.9978433 0.06712412 0.01726263 -0.9975954 0.06754958 0.01451367 -0.9976104 0.07309544 0.01479858 -0.9972152 0.05534869 0.1501502 -0.9871127 0.0617336 0.1528967 -0.9863122 0.06150794 0.1471335 -0.9872024 0.06937855 0.1504452 -0.986181 0.0676912 0.1439618 -0.9872654 0.07644289 0.1475864 -0.9860907 0.07326602 0.1402657 -0.9873995 0.08393692 0.1445764 -0.9859272 0.08022141 0.1371347 -0.9872986 0.08996421 0.1410011 -0.9859134 0.08732074 0.1344106 -0.9870709 0.09637385 0.1379426 -0.9857403 0.09225982 0.132248 -0.9869137 0.0997833 0.1351306 -0.9857906 0.0970211 0.1299891 -0.9867572 0.1051456 0.1330426 -0.9855173 0.1412743 0.6796087 -0.7198429 0.146084 0.6804621 -0.7180745 0.152179 0.6761354 -0.7208902 0.1628141 0.6778731 -0.7169238 0.1612483 0.6708775 -0.7238248 0.1797674 0.6737875 -0.7167246 0.174188 0.6644108 -0.7267853 0.196734 0.6677557 -0.7179123 0.1955787 0.6588416 -0.7264137 0.2112374 0.6609912 -0.7200483 0.2212429 0.6556671 -0.7219088 0.2240843 0.6560184 -0.7207123 0.2343873 0.6537854 -0.7194631 0.2366762 0.6540304 -0.7184906 0.2410996 0.6514941 -0.7193236 0.2481369 0.6522582 -0.7162314 0.2011068 0.9459024 -0.2546069 0.1765952 0.9497991 -0.2582552 0.2241324 0.9418253 -0.2504593 0.1949089 0.9471544 -0.2547731 0.2403114 0.9388067 -0.2467643 0.2136703 0.9441728 -0.2507647 0.2609859 0.9342228 -0.2431341 0.2364844 0.9397441 -0.2468931 0.2878121 0.927497 -0.2385658 0.2580546 0.9350101 -0.2432365 0.3214179 0.9180673 -0.2320411 0.2795504 0.9299341 -0.2389023 0.3475077 0.9103766 -0.2246176 0.2969716 0.9259414 -0.2333252 0.363879 0.9057605 -0.2172328 0.3097282 0.9233333 -0.226989 -0.02861231 -0.9892185 0.1436253 -0.04441422 -0.9894692 0.1377609 -0.01444935 -0.9903631 0.1377393 -0.0623331 -0.9896238 0.1294587 -0.01189506 -0.9914705 0.1297875 -0.08663606 -0.9889009 0.1207027 -0.01776456 -0.9925236 0.1207529 -0.100425 -0.9886311 0.1119083 -0.02114701 -0.9935687 0.1112388 -0.1051575 -0.9890819 0.1032423 -0.02729076 -0.9944201 0.1019014 -0.1095386 -0.9894419 0.09490048 -0.04972726 -0.9943906 0.09335237 -0.1158676 -0.9893651 0.08792853 -0.09669518 -0.9914793 0.08728647 -0.1257601 -0.9884595 0.08445304 -0.123199 -0.9887905 0.08435297 -0.1262226 -0.9884409 0.08397895 -0.08195757 -0.9932509 0.08207213 -0.09788399 -0.9919612 0.08019846 -0.0528196 -0.9795411 0.194189 -0.03849625 -0.9787344 0.2014871 -0.0624327 -0.9781224 0.198441 -0.0919466 -0.9775524 0.1895712 -0.07222074 -0.9786677 0.1923378 -0.1206641 -0.9763059 0.17963 -0.08005964 -0.9793936 0.1854152 -0.1310807 -0.9762789 0.1723299 -0.08542799 -0.9801806 0.1787407 -0.1373935 -0.9765673 0.1656485 -0.09350675 -0.9807124 0.1716382 -0.1436991 -0.9767395 0.1591556 -0.1029902 -0.9809954 0.164442 -0.1498687 -0.9768162 0.1528704 -0.1207155 -0.9802718 0.1565083 -0.1548539 -0.976818 0.1478072 -0.1321411 -0.9797111 0.150682 -0.1554987 -0.97723 0.1443662 -0.1003144 -0.9833345 0.1516257 -0.1510578 -0.9788308 0.1381011 -0.04525804 -0.9743624 0.2203853 -0.040582 -0.9738025 0.2237451 -0.0928176 -0.9727427 0.2125011 -0.1074689 -0.9724724 0.2067558 -0.1148899 -0.9719609 0.205164 -0.1433027 -0.9701822 0.1954759 -0.1234458 -0.9720344 0.1997757 -0.1525657 -0.9698543 0.1900171 -0.1300033 -0.972173 0.1948817 -0.1595199 -0.9696994 0.1850309 -0.1368976 -0.9722179 0.1898722 -0.1647469 -0.9696723 0.1805388 -0.1423189 -0.9723193 0.1853125 -0.1698464 -0.9696223 0.1760253 -0.1461032 -0.972549 0.181114 -0.1761146 -0.9694278 0.1708612 -0.1475145 -0.9730706 0.1771249 -0.1797664 -0.9696172 0.1659113 -0.1436038 -0.9742168 0.1740109 -0.1851679 -0.9696791 0.1594847 -0.06551963 -0.9606878 0.2697892 -0.1395702 -0.9679173 0.2089412 -0.1085796 -0.9700552 0.2172631 -0.164291 -0.9676148 0.1916506 -0.1429199 -0.9698968 0.1971656 -0.1707343 -0.9675337 0.1863557 -0.1522982 -0.969699 0.1910213 -0.1747294 -0.9675458 0.1825512 -0.1591602 -0.9694902 0.1864322 -0.1819225 -0.9670855 0.1779047 -0.1643018 -0.9694299 0.1822382 -0.1870477 -0.9668622 0.1737551 -0.1692714 -0.9693433 0.1781039 -0.1912021 -0.9667258 0.1699498 -0.1752192 -0.9690524 0.1738845 -0.1972092 -0.9662553 0.1657084 -0.1784565 -0.9690856 0.1703716 -0.2026118 -0.9658777 0.161334 -0.1833896 -0.96889 0.1661947 -0.2087181 -0.9653604 0.1565763 -0.156508 -0.9562173 0.2472931 -0.2316765 -0.9562374 0.1787071 -0.1647657 -0.9659514 0.1994746 -0.2217223 -0.9601984 0.1698773 -0.1712681 -0.9679045 0.183924 -0.201466 -0.9643955 0.171327 -0.175834 -0.96816 0.1781817 -0.1992688 -0.9653013 0.1687762 -0.1831448 -0.9677447 0.1729978 -0.2049906 -0.9648702 0.1643306 -0.1883656 -0.9675222 0.1685803 -0.2089763 -0.964653 0.1605415 -0.1926649 -0.9673534 0.1646445 -0.2117148 -0.9645811 0.1573538 -0.1986418 -0.96682 0.1606258 -0.2161606 -0.9641374 0.1539922 -0.2038137 -0.9663215 0.1571081 -0.2225884 -0.9633061 0.1499861 -0.2096317 -0.9656862 0.1533135 -0.2296532 -0.9623178 0.1456158 -0.2386661 -0.9461085 0.2188997 -0.2996547 -0.940342 0.1611332 -0.2209489 -0.9580338 0.1826274 -0.2725917 -0.9494695 0.1555688 -0.2009097 -0.9640823 0.173726 -0.2375093 -0.9583063 0.1588663 -0.1994169 -0.9653847 0.1681232 -0.2308294 -0.9604171 0.1559383 -0.2055283 -0.9651656 0.1619058 -0.2332874 -0.9605678 0.1512832 -0.2098606 -0.9650992 0.1566591 -0.2326589 -0.9612079 0.1481525 -0.212877 -0.9650831 0.1526366 -0.2312704 -0.9618799 0.1459485 -0.2174491 -0.964617 0.149097 -0.2338898 -0.9616608 0.1431929 -0.223819 -0.963704 0.1455325 -0.2418878 -0.9602939 0.1390175 -0.230758 -0.9626419 0.1416737 -0.2518886 -0.9584422 0.1339426 -0.3046048 -0.9213777 0.2414109 -0.3739285 -0.9097005 0.1806169 -0.2695378 -0.9416853 0.2014403 -0.3472426 -0.9232689 0.1643087 -0.2319275 -0.9544615 0.1876509 -0.3044355 -0.9388379 0.1609424 -0.2267857 -0.9578385 0.1763911 -0.289788 -0.9446359 0.1539028 -0.2306231 -0.9588345 0.165679 -0.2856248 -0.9471586 0.1459767 -0.2309001 -0.9602354 0.1569497 -0.2752581 -0.9509174 0.1413828 -0.2302173 -0.961427 0.1505266 -0.2635485 -0.9545594 0.1391354 -0.2333416 -0.9614682 0.1453639 -0.2614111 -0.9556114 0.1359093 -0.2415905 -0.9602157 0.1400711 -0.2702026 -0.953926 0.1304452 -0.2517528 -0.9584103 0.1344254 -0.2828904 -0.951126 0.1238242 -0.3754178 -0.888549 0.2637087 -0.4281718 -0.8762825 0.2209028 -0.3433907 -0.9094052 0.2346594 -0.4177362 -0.8859508 0.2014641 -0.2956605 -0.9290058 0.2225606 -0.3928684 -0.9000587 0.1885443 -0.2817087 -0.9366126 0.2083199 -0.3820012 -0.9076964 0.1736732 -0.2789535 -0.9407391 0.1928603 -0.371811 -0.9143902 0.1601472 -0.2687305 -0.946258 0.179944 -0.352398 -0.9235785 0.1510583 -0.2572454 -0.9513599 0.1695267 -0.3308629 -0.9324734 0.1449936 -0.2558783 -0.9534465 0.1595812 -0.3220702 -0.9366039 0.1380003 -0.2653554 -0.9525574 0.1490668 -0.3262575 -0.9363714 0.1294791 -0.2789008 -0.9502524 0.1386896 -0.3305058 -0.93585 0.1222736 -0.4270246 -0.8683381 0.2522682 -0.4520213 -0.8612089 0.2323709 -0.4153237 -0.8778643 0.2384549 -0.4517318 -0.864014 0.2223023 -0.3889901 -0.8912032 0.2333319 -0.444611 -0.8698838 0.2135959 -0.3774147 -0.8980928 0.2258044 -0.4403883 -0.8743799 0.2037595 -0.3669838 -0.9044038 0.2176616 -0.4350434 -0.8794164 0.1932985 -0.3457942 -0.9143412 0.2107291 -0.4257645 -0.8862512 0.1824377 -0.3222113 -0.924713 0.2026967 -0.414608 -0.8937711 0.1710954 -0.3127928 -0.9304755 0.1907248 -0.4064496 -0.8996258 0.1596 -0.3168176 -0.9319304 0.1764433 -0.3991884 -0.9045443 0.1498275 -0.322082 -0.9324808 0.1635324 -0.3797337 -0.9135697 0.1455781 -0.4525139 -0.863101 0.2242494 -0.4637666 -0.8593713 0.2154106 -0.4520173 -0.8651105 0.217404 -0.4636173 -0.8602185 0.2123284 -0.4445168 -0.8693903 0.2157901 -0.4599573 -0.8626801 0.2102909 -0.4398238 -0.8722061 0.2140366 -0.4588168 -0.863986 0.2074019 -0.434059 -0.8755688 0.212066 -0.459716 -0.8645511 0.2030089 -0.4239994 -0.8810301 0.2097871 -0.4609326 -0.865332 0.1968289 -0.411733 -0.8876905 0.2061108 -0.4574372 -0.868619 0.1904006 -0.4029256 -0.8930065 0.2004759 -0.4367409 -0.8794715 0.1891751 -0.3944692 -0.8976548 0.1964944 -0.3990906 -0.8959317 0.1950207 -0.3746179 -0.9056444 0.1986692 -0.337573 -0.9176417 0.2097103 -0.464689 -0.8635882 0.1956524 -0.4692652 -0.861894 0.1921695 -0.4643326 -0.8644001 0.1928933 -0.4680053 -0.8627467 0.1914139 -0.4603363 -0.8666043 0.1925815 -0.4651368 -0.8643793 0.1910396 -0.4592695 -0.8673116 0.1919434 -0.4636817 -0.8652679 0.1905542 -0.4600965 -0.8670592 0.1911011 -0.4634568 -0.8655008 0.1900431 -0.4612193 -0.8666214 0.1903789 -0.4588365 -0.8677212 0.1911258 -0.4573907 -0.868438 0.1913357 -0.4276549 -0.8814896 0.2002188 -0.4365964 -0.8773452 0.1991205 -0.3253692 -0.9176529 0.2281406 -0.3979338 -0.8895127 0.224535 -0.2227664 -0.9402744 0.2574089 -0.3398362 -0.9021622 0.2657344 -0.1820228 -0.9420243 0.2818828 -0.4695211 -0.8649362 0.1773 -0.450783 -0.8721295 0.1902233 -0.4680334 -0.8631644 0.1894518 -0.439919 -0.8760758 0.1973897 -0.4650765 -0.8631359 0.1967241 -0.4479102 -0.8714451 0.1999003 -0.4635744 -0.8633021 0.1995201 -0.4485384 -0.8705943 0.2021856 -0.4632691 -0.8629304 0.2018245 -0.4352341 -0.8762488 0.2067836 -0.4585694 -0.8643721 0.2063374 -0.3975531 -0.8916543 0.2165738 -0.4289236 -0.8769634 0.2167016 -0.3007408 -0.9244331 0.2344751 -0.3270781 -0.914914 0.2365424 -0.1503898 -0.9563724 0.2504692 -0.223745 -0.9369049 0.2686026 -0.07104182 -0.9629085 0.2603082 -0.1890068 -0.9297903 0.3158582 -0.07848566 -0.9533591 0.291456 -0.4509127 -0.8713545 0.1934405 -0.3910933 -0.8928022 0.2234958 -0.4413383 -0.8667086 0.2324581 -0.3464225 -0.9080842 0.2353177 -0.4474104 -0.8564728 0.2574458 -0.3472269 -0.9042881 0.2483877 -0.4470945 -0.8525926 0.2705412 -0.3482263 -0.900465 0.2605788 -0.4345052 -0.8562322 0.2794133 -0.3142949 -0.9108732 0.2674487 -0.404879 -0.867803 0.2880814 -0.2684419 -0.9235616 0.2738117 -0.3234429 -0.9013849 0.2879062 -0.1806442 -0.945242 0.2718185 -0.1563385 -0.9518402 0.2637395 -0.06131809 -0.9647735 0.2558364 -0.3938178 -0.8877297 0.2384192 -0.3240782 -0.9085542 0.2636338 -0.3556077 -0.8935372 0.2741068 -0.2444145 -0.9342288 0.2597656 -0.3525967 -0.8866477 0.299218 -0.1707199 -0.9528316 0.2509319 -0.3496319 -0.8814324 0.3175445 -0.1371514 -0.9564726 0.2575842 -0.3181158 -0.8905496 0.3251521 -0.1133344 -0.9564987 0.2688229 -0.2856727 -0.8983034 0.3338296 -0.09937977 -0.9533934 0.2848941 -0.2155242 -0.9188641 0.3305118 -0.07715392 -0.9507254 0.3002806 -0.3343209 -0.8951122 0.2949643 -0.2665789 -0.9060332 0.3286938 -0.2744014 -0.9028241 0.3310781 -0.1872546 -0.9251666 0.3301554 -0.1933642 -0.9232497 0.3319947 -0.06929433 -0.9481618 0.3101415 -0.1460102 -0.9310449 0.3344197 -0.02327072 -0.9507137 0.309196 -0.1199506 -0.9325316 0.3405829 -0.0144124 -0.9472075 0.3202973 -0.2746024 -0.8935168 0.3552766 -0.1626291 -0.8984993 0.4077387 -0.2210727 -0.8755569 0.4295662 -0.08216965 -0.903674 0.4202636 -0.09000265 -0.9014223 0.4234825 -0.0116207 -0.9151622 0.4029182 -0.1449189 -0.9411654 0.3052968 -0.06941252 -0.9300122 0.3609146 -0.07459914 -0.9293619 0.3615542 -0.02057284 -0.9274455 0.373392 -0.06105685 -0.964639 0.2564055 -0.02011257 -0.9569482 0.2895613 -0.01782339 -0.956994 0.2895597 -0.004005849 -0.9557563 0.2941327 -0.01787066 -0.9813346 0.1914762 -0.002803087 -0.9786632 0.2054522 -0.003720104 -0.9786902 0.2053093 -7.9438e-4 -0.9783955 0.2067406 -0.00581789 -0.9957712 0.0916844 -0.005813717 -0.9957712 0.09168416 -0.003611624 -0.9957095 0.09246438 -0.005304396 -0.9958105 0.09128808 -0.002392768 -0.9957201 0.09239041 -0.003067791 -0.9957562 0.09197926 0.2673967 0.9602104 -0.08059191 0.2500184 0.9650733 -0.07825887 0.3196771 0.9442377 -0.07887858 0.2958726 0.9522249 -0.07567858 0.3635205 0.9284514 -0.07636004 0.3341398 0.9397531 -0.07221263 0.3974249 0.9147289 -0.07297062 0.3655338 0.9282854 -0.06834727 0.425494 0.9023136 -0.0691747 0.3901604 0.9184958 -0.06434535 0.4604349 0.8852881 -0.06530463 0.4209336 0.9050726 -0.06048691 0.5049238 0.8609786 -0.06138497 0.4601892 0.8860424 -0.05616807 -0.002020061 -0.9968935 0.0787357 -0.02274274 -0.9973006 0.06981688 0.01017051 -0.9977778 0.06584823 -0.01820844 -0.9978905 0.06231349 0.0128858 -0.9981862 0.05880653 -0.03094047 -0.9978985 0.05693346 0.008742213 -0.9985849 0.05245751 -0.0411427 -0.9978374 0.05126345 0.005008995 -0.9989395 0.04577136 -0.04301959 -0.9980537 0.04514664 -0.002011954 -0.9991961 0.04004073 -0.04398769 -0.9982393 0.0397945 -0.02270257 -0.9990549 0.03706806 -0.05187135 -0.9979789 0.03670907 -0.05739331 -0.9976496 0.03743404 -0.07116079 -0.9967882 0.03673672 -0.07428932 -0.9965439 0.03716939 -0.07830685 -0.9962543 0.03668141 -0.04817664 -0.9983209 0.03216278 -0.0489692 -0.9982857 0.03206104 -0.01072931 -0.99991 0.00805974 -0.002512931 -0.9999858 0.004728376 -0.009558141 -0.9998847 0.01180952 4.80674e-4 -0.9999007 0.01408964 -0.005845606 -0.9998567 0.01589584 0.003653526 -0.9997991 0.01971095 -0.004976093 -0.9998263 0.01796358 0.003287553 -0.9997586 0.02172893 -0.005133032 -0.9998063 0.01900279 0.001118779 -0.9997552 0.02209991 -0.2368042 -0.9426324 -0.2353041 -0.06480956 -0.9614343 -0.2672901 -0.1597874 -0.974552 -0.1572151 -0.02676314 -0.9861691 -0.1635675 -0.06557571 -0.9931739 -0.09646451 -0.006261885 -0.9953239 -0.09639048 -0.02475655 -0.9971781 -0.0708732 -0.00135827 -0.9974787 -0.07095414 -0.001605689 -0.9981367 -0.06099742 0.001102924 -0.9981334 -0.06106281 0.006919026 -0.9981547 -0.06032854 0.001494586 -0.9982032 -0.05990374 0.005873262 -0.9977876 -0.06622356 -0.002161204 -0.9979885 -0.06336015 0.2490476 0.9601678 -0.1267012 0.2028554 0.9705938 -0.1296052 0.2920745 0.9484853 -0.1227527 0.2295795 0.965031 -0.1265254 0.3254446 0.9381678 -0.1180132 0.252089 0.959933 -0.1223918 0.3547183 0.9281265 -0.112944 0.2765709 0.9537841 -0.117493 0.3823519 0.9177188 -0.1077001 0.299305 0.9475325 -0.1122431 0.4178811 0.9027466 -0.1020971 0.3259682 0.9393013 -0.1070412 0.4571544 0.8842363 -0.09558296 0.35255 0.9302563 -0.1016451 0.4902759 0.8671137 -0.0879969 0.3728981 0.9229488 -0.09545993 0.5461017 -0.6541648 0.5232986 0.5174307 -0.4872983 0.7034243 0.5484551 -0.5971296 0.5853489 0.5162255 -0.4326077 0.739163 0.5142561 -0.4258543 0.7444387 0.5427455 -0.3046531 0.7826965 0.5196405 -0.180809 0.8350341 -0.6367401 0.1592943 -0.7544451 -0.5881579 0.2316814 -0.774851 0.4970697 -0.2174758 0.8400155 0.4930441 -0.2003297 0.8466261 0.4823232 -0.1889359 0.8553757 0.4618089 -0.4861234 0.7419007 0.5121636 -0.1919625 0.8371612 -0.006671786 0.5709244 -0.8209756 0.5811213 -0.2274345 0.7813908 -0.5052621 -0.3612315 -0.7837232 -0.5589112 0.2056093 -0.8033325 0.1604309 -0.878484 0.4500312 0.6214066 -0.074961 0.7798941 -0.4658992 0.5006154 -0.7296042 -0.5321246 0.4584201 -0.7118248 0.9981634 -0.01520824 0.05864071 0.9963281 -0.02829557 0.08080714 0.991503 -0.05557447 0.1176164 0.9910577 -0.05702984 0.1206328 0.9615234 -0.06538969 0.2668278 0.9793174 -0.03544408 0.1992016 0.05837339 -0.7067965 -0.7050045 0.05666047 -0.7293177 -0.6818249 0.009202957 -0.1129369 -0.9935595 0.009496986 -0.1074508 -0.9941651 0.00143218 -0.01940608 -0.9998107 0.001840233 -0.01692348 -0.9998551 -3.26401e-4 -0.003940224 -0.9999922 2.04387e-4 -0.001702308 -0.9999986 -0.001221597 -1.48807e-4 -0.9999993 -8.948e-4 0.001946866 -0.9999978 -0.002522468 0.002729237 -0.9999931 -0.002544522 0.007568717 -0.9999682 -0.005396127 0.009806334 -0.9999374 -0.006555855 0.01903653 -0.9997974 -0.008432328 0.01901644 -0.9997836 -0.009117007 0.02303111 -0.9996932 -0.008746147 0.0239011 -0.9996761 -0.007529556 0.01581209 -0.9998466 -0.005912721 0.02229064 -0.9997341 -0.004959225 0.008194684 -0.9999542 -0.004783391 0.02685719 -0.999628 -0.004539787 0.01339942 -0.9999 -0.00272119 0.02612227 -0.9996551 -0.003518879 0.0131756 -0.9999071 3.04239e-4 0.01973801 -0.9998052 -0.002474188 0.007741928 -0.999967 0.002487421 0.01633232 -0.9998636 -0.001744627 0.005924403 -0.999981 0.00742352 0.02510064 -0.9996575 -1.00095e-4 0.00845474 -0.9999643 0.01735335 0.04699307 -0.9987446 0.006944596 0.02393102 -0.9996896 0.03550922 0.0895248 -0.9953514 0.03827369 0.09575062 -0.9946693 0.09079128 0.2199543 -0.971276 0.1378674 0.326827 -0.9349742 0.2219631 0.5258938 -0.8210775 0.2764974 0.6472914 -0.710326 0.166136 0.4204459 -0.8919776 0.3665574 0.8483853 -0.38194 0.8393103 -0.4377179 0.3224302 0.8880364 -0.343626 0.3054713 0.8716561 -0.2113796 0.4421926 0.6434513 -0.5349869 0.547503 0.6688813 -0.3545304 0.6533805 -0.1882743 -0.81468 0.5484974 -0.2375774 -0.8495243 0.471026 -0.4241737 -0.8363656 0.3472309 -0.441555 -0.8537193 0.2760304 -0.4549963 -0.8496828 0.266491 -0.4584885 -0.8580884 0.2312414 -0.4637479 -0.8561698 0.2278403 -0.4656172 -0.864481 0.1894024 -0.4666412 -0.8640662 0.1887746 -0.4674575 -0.8727056 0.1409555 -0.4614055 -0.8753507 0.1444513 -0.4606819 -0.8835175 0.08467125 -0.4416921 -0.8921357 0.09487849 -0.4384061 -0.8985448 0.02042871 -0.3996286 -0.9157928 0.04025691 -0.3925464 -0.9188569 -0.0401172 -0.3343604 -0.942387 -0.01048368 -0.3227646 -0.9420839 -0.09111016 -0.2484953 -0.9672672 -0.05142152 -0.2371072 -0.9652233 -0.1101105 -0.1394114 -0.9881967 -0.06349712 -0.1343251 -0.9873474 -0.08427423 -0.02662682 -0.9985938 -0.04584342 -0.02250999 -0.9978003 -0.0623539 0.07463204 -0.9966436 -0.03363966 0.07911032 -0.9950137 -0.060741 0.1442641 -0.983151 -0.112259 0.07494509 -0.9809725 -0.1790986 0.06479114 -0.9866378 -0.1494926 -0.6713226 0.3909963 -0.6296411 0.0932126 -0.9905596 -0.1005154 0.1905476 -0.9664313 -0.1723436 -0.03581398 -0.9931648 -0.1110907 0.09278732 -0.9908122 -0.09839636 -0.1582694 -0.9788484 -0.1296401 -0.03627437 -0.9933627 -0.1091551 -0.2468801 -0.9579666 -0.146117 -0.1596931 -0.9796412 -0.1216601 -0.3026103 -0.9462965 -0.1137983 -0.2520667 -0.9628251 -0.09710925 -0.3427066 -0.9376611 -0.05782592 -0.3074835 -0.9504379 -0.0460633 -0.3788966 -0.9254309 0.003880023 -0.3466303 -0.9378863 0.01472342 -0.4116128 -0.9086249 0.07054013 -0.3822023 -0.9205385 0.08081012 -0.4338741 -0.891273 0.131855 -0.4133427 -0.8998041 0.139644 -0.4436206 -0.8768402 0.1853438 -0.4335172 -0.8809832 0.1895558 -0.438822 -0.8677758 0.2332388 -0.4411566 -0.8668827 0.2321536 -0.4596669 -0.8486621 0.2616847 -0.43239 -0.8578116 0.2778456 -0.5319104 -0.7897275 0.3056174 -0.4047513 -0.8209935 0.4026736 -0.1947484 -0.7466548 0.6360659 -0.5315816 -0.6738115 0.5132243 0.1363976 -0.7302379 -0.669439 0.1343318 -0.7424113 -0.6563388 0.02610772 -0.1374105 -0.9901701 0.02703571 -0.125903 -0.9916741 0.004881024 -0.0259307 -0.9996519 0.006376504 -0.02108412 -0.9997574 0.001054406 -0.006390273 -0.9999791 0.002118647 -0.004370212 -0.9999882 -1.26303e-4 -0.001390457 -0.9999991 3.54455e-4 -4.59059e-4 -0.9999998 -0.001214206 6.86924e-4 -0.9999991 -8.09828e-4 0.0020141 -0.9999977 -0.003801047 0.005093514 -0.9999798 -0.003760218 0.008347511 -0.9999582 -0.01010757 0.01926565 -0.9997633 -0.01056897 0.02186393 -0.9997051 -0.01754862 0.0402587 -0.9990352 -0.01627576 0.0345844 -0.9992693 -0.01764553 0.04871124 -0.9986571 -0.01502639 0.03336662 -0.9993302 -0.01696872 0.05587977 -0.9982933 -0.01522982 0.04062384 -0.9990585 -0.01287961 0.05747741 -0.9982637 -0.01256042 0.03758889 -0.9992144 -0.001786053 0.05037945 -0.9987286 -0.007211744 0.02126324 -0.9997479 0.008360087 0.04188281 -0.9990876 -0.003497064 0.01361483 -0.9999012 0.01554381 0.05025267 -0.9986156 0.003060936 0.02422869 -0.9997018 0.0193153 0.05774754 -0.9981443 0.01488673 0.0485751 -0.9987087 0.02603036 0.07608199 -0.9967618 0.03276044 0.09064882 -0.995344 0.04407268 0.12496 -0.9911825 0.06976658 0.1840051 -0.9804462 0.08459639 0.2277231 -0.9700442 0.1019665 0.2680997 -0.9579799 0.1562154 0.3983788 -0.9038203 0.1616343 0.4106718 -0.8973422 0.1663753 -0.9651133 -0.2021771 0.1467697 -0.9738689 -0.1733152 0.5628829 -0.3437236 0.7516762 0.3762471 -0.5467758 0.7479802 0.3426187 -0.6278476 0.6988704 -0.1847994 -0.858963 0.4775267 -0.2489892 -0.9084677 0.3356946 -0.305915 -0.9043515 0.2975975 -0.3116348 -0.9098233 0.2740534 -0.3709966 -0.897787 0.2373604 -0.3747271 -0.9102243 0.1762707 -0.3611523 -0.9139972 0.1848735 -0.3612767 -0.925984 0.1096948 -0.3325003 -0.9344356 0.127568 -0.3301958 -0.942918 0.04331779 -0.2966315 -0.9528558 0.06384128 -0.2935068 -0.9556939 -0.02243071 -0.2617039 -0.9651436 -0.00298345 -0.2586132 -0.9623643 -0.08351248 -0.2269534 -0.9717926 -0.06412059 -0.2237514 -0.9644196 -0.1408205 -0.1903871 -0.9742687 -0.1206376 -0.1871758 -0.9648174 -0.1846418 -0.1397866 -0.9774906 -0.1580253 -0.1370514 -0.971688 -0.1924559 -0.0536313 -0.9867117 -0.1533746 -0.04940974 -0.9812355 -0.1863755 0.05376523 -0.9886828 -0.1400563 0.05310362 -0.9894512 -0.1347825 0.1418415 -0.9611767 -0.2366862 0.1875865 -0.754206 -0.6292731 0.186987 -0.7565711 -0.6266068 0.04321181 -0.1701278 -0.9844741 0.04439681 -0.1571148 -0.986582 0.008212268 -0.03512698 -0.9993491 0.01050114 -0.02929019 -0.9995158 0.001662254 -0.009371459 -0.9999548 0.003447949 -0.007030308 -0.9999694 2.76244e-4 -0.002350449 -0.9999973 9.85819e-4 -0.001591444 -0.9999983 -3.18864e-4 -9.00402e-5 -1 3.79583e-5 3.11447e-4 -1 -0.001355111 0.00231117 -0.9999964 -9.00837e-4 0.003026902 -0.9999951 -0.00372523 0.01041573 -0.9999389 -0.003532111 0.01097387 -0.9999336 -0.006690979 0.02656328 -0.9996249 -0.00707668 0.02451741 -0.9996743 -0.007356107 0.04107588 -0.9991289 -0.008365333 0.03559881 -0.9993312 -0.006009221 0.05174422 -0.9986423 -0.007734715 0.04410761 -0.9989969 -0.003030896 0.05844736 -0.998286 -0.005827188 0.04906284 -0.9987787 0.001171648 0.06367564 -0.99797 -0.002977192 0.05142241 -0.9986726 0.007500171 0.06280565 -0.9979977 2.39499e-5 0.04419821 -0.9990228 0.009802818 0.06481951 -0.9978489 0.006530761 0.05682271 -0.998363 0.01027953 0.0672903 -0.9976805 0.01028347 0.06730473 -0.9976795 0.01093208 0.0782808 -0.9968714 0.01430368 0.08739441 -0.9960711 0.01838952 0.1166764 -0.9929997 0.01850247 0.1170341 -0.9929555 0.07884126 0.2763332 -0.9578226 0.01107877 0.08112758 -0.9966422 0.2196707 0.6018743 -0.767784 0.03032261 0.1167673 -0.9926963 0.2204855 -0.9465005 -0.2356332 0.1923058 -0.9605542 -0.2008839 0.6360942 0.2868405 0.7163147 -0.8172233 -0.2154514 -0.5345344 0.39036 -0.7807201 0.48795 -0.5030611 -0.8464038 0.174729 -0.2691748 -0.9630914 2.35858e-5 -0.09761983 -0.5550746 -0.8260524 -0.8172222 -0.215453 -0.5345352 -0.835546 -0.0229842 -0.5489398 0.5590077 -0.515052 0.6497939 0.6769667 -0.4858 0.5529146 0.5590022 -0.5150571 0.6497945 0.9032881 -0.3382036 0.2639868 0.4874141 -0.4244721 0.7630538 0.5799763 -0.3992679 0.7100793 0.3559157 -0.5903168 0.7244654 0.4392999 -0.7456811 0.5009745 0.8695285 -0.3058853 0.3877556 0.6669508 0.2694315 0.6946823 0.7452138 -0.265241 0.6118037 -0.1188148 -0.9870657 0.1076307 0.3878984 0.8889915 -0.2433702 0.404703 0.9055659 -0.1271458 0.4004274 0.9111043 -0.0977078 0.005157768 -0.9340878 0.3570061 0.02939635 -0.9125102 0.4079964 0.007327437 -0.9171352 0.3985089 0.01950651 -0.9152573 0.4023975 -0.04489064 -0.9376425 0.3446903 0.009068787 -0.9367597 0.3498558 -0.04490035 -0.9376428 0.3446885 -0.0962069 -0.9288639 0.3577097 -0.03069239 -0.9552332 0.2942577 -0.03069102 -0.9552355 0.2942504 0.7719478 0.2618046 -0.5792711 -0.7248072 0.2043684 0.6579424 0.9709165 0.23221 0.05830818 -0.6528772 0.7530159 0.08196747 0.4058707 0.9078236 -0.1054769 0.4028532 0.9034301 -0.146709 0.3780867 0.8486367 -0.3699545 0.3389187 0.7641748 -0.5487905 0.3433084 0.7737518 -0.5323981 0.3695539 0.8158999 -0.4446768 0.1553168 0.3310765 -0.9307337 0.1376328 0.2954676 -0.9453867 0.03556692 0.06650626 -0.997152 0.03269851 0.06117022 -0.9975916 0.01261335 0.01641768 -0.9997857 0.01115322 0.01430046 -0.9998356 0.0100218 0.01184582 -0.9998797 0.00801593 0.00948137 -0.9999229 0.009212851 0.01196867 -0.999886 0.006606876 0.008826255 -0.9999393 0.007214963 0.01006639 -0.9999234 0.004374027 0.006031095 -0.9999723 0.004606246 0.006522834 -0.9999682 0.001549482 0.001587152 -0.9999976 0.001598536 0.001702964 -0.9999973 -0.001816213 -0.004351615 -0.999989 -0.001195251 -0.002442061 -0.9999964 -0.004377961 -0.009162664 -0.9999485 -0.003901422 -0.008143365 -0.9999593 -0.004896819 -0.00956434 -0.9999424 -0.004910051 -0.009612679 -0.9999418 -0.006596803 -0.008245885 -0.9999443 -0.004910051 -0.009611248 -0.9999418 0.01447796 -0.011101 -0.9998336 0.006926953 -0.01198935 -0.9999042 -0.08516162 -0.6982831 -0.7107378 -0.07921051 -0.7002906 -0.7094497 -0.05874645 -0.3983641 -0.9153441 -0.05953043 -0.3974671 -0.9156835 -0.0338003 -0.2035865 -0.9784734 -0.03712385 -0.2005067 -0.9789888 -0.03714728 -0.2005324 -0.9789826 -0.03371888 -0.1968896 -0.9798457 -3.09881e-4 -0.06007665 -0.9981938 -0.01005142 -0.05355274 -0.9985145 0.02139729 -0.01594132 -0.999644 0.01246142 -0.01049816 -0.9998673 0.01247334 -0.01049041 -0.9998672 0.01545661 -0.008899807 -0.999841 0.01524609 -0.01552772 -0.9997632 0.01381582 -0.01491415 -0.9997934 0.01328825 -0.02136874 -0.9996834 0.009466469 -0.02056062 -0.9997438 0.01328903 -0.02137124 -0.9996833 0.001007556 -0.02441978 -0.9997014 8.16042e-4 -0.02442437 -0.9997014 -0.001466989 -0.02521562 -0.999681 -0.001001358 -0.01461338 -0.9998927 0.007394313 -0.01377725 -0.9998778 -9.41409e-4 -0.01461607 -0.9998928 0.002475798 -0.9349778 0.3546978 -7.64918e-4 -0.9351382 0.3542823 0.006108462 -0.9343177 0.3563891 3.09442e-4 -0.9357872 0.3525653 0.002342879 -0.9353601 0.3536891 -0.001122415 -0.957821 0.2873633 3.82071e-4 -0.9576893 0.287804 0.001175582 -0.957666 0.2878792 -1.70301e-4 -0.9577177 0.2877098 -7.07995e-4 -0.9855293 0.1695044 -3.18051e-4 -0.9855121 0.169605 -0.00409168 -0.9858109 0.1678098 -4.74386e-4 -0.9856815 0.1686174 -0.007864534 -0.9939119 -0.1098973 -0.02884501 -0.9930834 -0.1138131 -0.007651627 -0.9933558 -0.1148298 -0.02891206 -0.9930813 -0.113815 -0.03322356 -0.9250739 -0.3783314 -0.03213965 -0.9251806 -0.3781641 -0.06695121 -0.9178719 -0.391189 -0.04056733 -0.9223778 -0.3841531 -0.06666201 -0.8559994 -0.512661 -0.08709526 -0.8560647 -0.509478 -0.2151373 -0.5752058 -0.7892112 -0.2015632 -0.5583333 -0.8047586 -0.2214472 -0.6215283 -0.7514412 -0.311172 -0.777746 -0.5461531 -0.1552678 -0.5425189 -0.8255698 -0.2443856 -0.6927201 -0.6785386 -0.09776937 -0.1864994 -0.9775782 -0.1169359 -0.2274871 -0.9667346 -0.07769024 -0.1557744 -0.9847328 -0.09696239 -0.1957061 -0.9758574 -0.04210627 -0.04771858 -0.997973 -0.03974056 -0.04083311 -0.9983754 -0.03577119 -0.03970754 -0.9985709 -0.04185312 -0.04388147 -0.9981597 -0.04012471 -0.04129123 -0.9983412 -0.04114234 -0.0428676 -0.9982334 -0.02148872 0.005543112 -0.9997537 -0.009553372 0.017448 -0.9998021 -0.01773464 0.008189201 -0.9998093 -0.0133742 0.01329934 -0.9998222 -0.006063342 0.0194993 -0.9997916 -0.009612679 0.0171799 -0.9998062 -0.005970537 0.01687133 -0.9998399 -0.006542325 0.01664638 -0.9998401 -0.007707178 0.007662832 -0.999941 0.002478241 0.01765608 -0.9998411 -0.006501317 0.008147954 -0.9999457 -0.004625916 0.01088845 -0.9999301 0.0189132 -0.008285343 -0.9997868 -0.00388813 -0.002244591 -0.99999 0.001094579 0.006905794 -0.9999756 -0.007020354 -0.004464268 -0.9999654 -0.004438221 -5.65854e-4 -0.99999 0.02308309 -0.002358794 -0.9997308 0.02770435 -0.001342475 -0.9996153 0.02464365 -0.002129793 -0.9996941 0.02811956 -0.001269042 -0.9996038 0.02465271 -0.001355469 -0.9996951 0.02433365 -0.001451551 -0.9997029 -0.004550397 -0.009315133 -0.9999463 0.0250324 3.58967e-4 -0.9996866 0.04098719 0.001527905 -0.9991586 0.02504163 3.58642e-4 -0.9996864 0.04133129 0.00252664 -0.9991424 0.02363806 8.98066e-4 -0.9997202 0.02970069 0.001974701 -0.999557 0.007038652 0.001949787 -0.9999734 0.001404106 0.002602756 -0.9999957 0.02621841 0.002814054 -0.9996523 0.02378278 0.002616822 -0.9997138 0.02733713 0.003277003 -0.999621 0.0229063 0.002938687 -0.9997334 0.01942908 0.002102732 -0.9998091 0.0196101 0.002463161 -0.9998047 0.01750236 0.002337515 -0.9998442 0.0195989 0.002464175 -0.9998049 0.01595687 0.001919567 -0.9998708 0.01647007 0.002899706 -0.9998602 0.02340477 0.003201305 -0.9997211 0.01647627 0.002884984 -0.9998601 0.009436607 0.001830101 -0.9999539 0.02087765 0.001892924 -0.9997802 0.01088464 0.003775358 -0.9999337 0.03184992 -0.00952661 -0.9994474 0.01821047 -0.002028942 -0.9998322 0.03015798 -0.01285082 -0.9994626 0.04302567 -0.01281243 -0.9989919 0.07651746 0.01243269 -0.9969907 0.08107757 0.01141566 -0.9966424 0.07926726 0.01143145 -0.9967879 0.05644375 0.01716876 -0.9982582 0.1159939 0.1312063 -0.9845458 0.118008 0.1308676 -0.9843515 0.2789516 0.6471046 -0.7095363 0.2816846 0.6461377 -0.7093377 0.3939313 0.8936842 -0.214818 0.3490485 0.9123662 -0.2138999 -0.007843315 -0.9676845 0.2520427 -0.07111579 -0.9627965 0.2607021 -0.007843852 -0.9676868 0.2520337 -0.08904623 -0.9376187 0.3360683 -0.03402876 -0.9622433 0.2700552 -0.02764213 -0.9526703 0.3027463 -0.08189266 -0.9496622 0.3023829 -0.02766984 -0.9526726 0.3027367 -0.01472938 -0.955101 0.295914 0.02178192 -0.9481003 0.3172246 -0.00541085 -0.9483502 0.3171793 -0.1142189 -0.9208498 0.3728134 -0.04167813 -0.9415274 0.3343492 -0.09719777 -0.9250903 0.3670975 -0.0140978 -0.9309554 0.364861 -0.0442323 -0.9246633 0.3782083 0.03433591 -0.9175523 0.3961299 0.02329105 -0.9183011 0.395197 -7.63401e-4 -0.9174624 0.3978219 -0.03134268 -0.9081346 0.4175036 -0.009770929 -0.9154905 0.4022212 -0.02012139 -0.9093433 0.4155598 -0.0129618 -0.9127334 0.4083503 -0.009643733 -0.9119703 0.4101431 0.0352776 -0.9116479 0.4094554 -0.001002192 -0.9278457 0.3729631 -0.01026511 -0.9281108 0.3721626 -0.0010311 -0.9278469 0.3729598 -1.22791e-4 -0.9278938 0.3728449 -5.8515e-4 -0.9557564 0.2941589 -1.57063e-4 -0.9557721 0.2941085 -6.94641e-4 -0.9784016 0.2067121 -4.95466e-4 -0.9783853 0.20679 -6.29922e-4 -0.9783937 0.2067493 -7.76992e-4 -0.9784045 0.2066983 -0.002614438 -0.9957465 0.09209883 -0.002384424 -0.9957322 0.09225994 -0.002460479 -0.9957348 0.09222865 -0.002757608 -0.9957535 0.09201931 -0.002726614 -0.9957497 0.09206002 -0.002277851 -0.9957353 0.09222918 0.5179862 0.8535115 -0.0566442 0.496164 0.8667511 -0.05063623 0.5334024 0.8443294 -0.05088979 -0.00475198 -0.9998032 0.01926368 -0.004750251 -0.9997969 0.01958435 -0.003086745 -0.9997828 0.02061378 -0.02221703 -0.9997504 0.002375543 -0.01127785 -0.9998291 0.01465666 -0.05961406 -0.9974498 -0.03924578 -0.04200077 -0.9990295 -0.01326674 -0.1485518 -0.9825477 -0.1119491 -0.3020734 -0.8720507 -0.3850705 -0.29045 -0.8756162 -0.3859214 -0.1489724 -0.946423 -0.2865151 -0.2853861 -0.8801665 -0.3792909 0.5250427 0.8465496 -0.08765894 0.4037473 0.9107285 -0.08695864 0.5228875 -0.2164052 0.8244741 0.4519396 -0.2010204 0.8691039 -0.3427015 -0.3470915 -0.8729738 0.7401359 -0.0218665 -0.6721018 0.9940571 0.04003751 -0.1012304 -0.03907757 0.1377179 -0.9897004 0.6283962 0.04932564 -0.776328 -0.01864558 -0.007212221 -0.9998002 -0.122974 -0.003693997 -0.9924031 -0.02056914 0.006317973 -0.9997685 -0.6964497 0.07476443 -0.7137003 -0.0205608 0.006317973 -0.9997687 -0.9937607 0.00528866 -0.1114081 -0.05677872 0.2658283 -0.962347 -0.8768789 -0.1443179 0.4585366 0.06015312 -0.9406965 0.3338741 0.9999525 0.008953988 -0.00385338 0.999949 0.008047401 0.00610429 0.9999516 0.008988797 -0.003999173 0.9999672 0.005345165 0.006093561 0.9999749 0.00663799 -0.002537012 0.9999997 -8.23723e-4 0 0.9999724 0.004261732 0.006088793 0.9999749 0.006633639 -0.002511739 0.9999873 0.004830837 -0.001449286 0.9999938 0.003377676 -0.001015007 0.9999739 0.003902256 0.006087243 0.9999942 0.003372251 -5.77009e-4 0.9999785 0.002476751 0.0060817 0.9999976 0.002164959 2.48116e-4 0.9987782 0 -0.04941868 0.99998 0.001793563 0.006078481 -0.7525767 0 0.6585046 0.9999799 0.001793861 0.006078422 0.9999976 0.002164602 2.39329e-4 0.9999986 4.75561e-5 0.001651823 0.9999919 -7.13571e-6 0.004036605 0.9999841 0.001706302 0.005387961 0.9999994 0.001080989 4.47012e-4 1 4.98325e-6 0 0.9999994 9.60149e-4 7.65397e-4 1 -1.64046e-6 0 0.9999987 2.46012e-5 0.001652359 0.9999991 2.87319e-4 0.001425743 1 -1.77006e-6 0 0.9999986 4.06531e-5 0.001644372 0.9999986 4.02378e-5 0.001651227 0.9999986 3.64907e-5 0.001651108 0.9999965 0.001317143 0.002312719 0.9999918 2.18887e-5 0.004053592 -0.9999672 1.82905e-5 -0.00811249 1 -7.38704e-6 0 1 4.50101e-5 0 0.9946324 0.01399707 0.102522 0.9999672 -3.03744e-5 0.008099615 0.9999666 1.65487e-5 0.008185148 0.9999954 -0.003044247 2.68633e-4 1 1.40543e-6 0 0.9999915 -0.002006828 0.003613293 -1 5.53234e-7 0 -1 0 0 -1 5.67086e-5 0 -1 -2.19552e-7 0 -1 -3.04314e-7 0 -1 0 0 -1 9.03969e-7 0 -1 -6.32253e-7 0 -1 2.67614e-7 0 -1 -5.95968e-7 0 -1 1.03398e-5 0 -1 0 0 -1 2.39789e-6 0 -0.6110162 0.2271704 -0.7583225 -0.7896494 0.0176739 -0.6133037 -0.5462286 0.3662254 -0.7533348 -0.7452912 0.1701958 -0.6446507 -0.4817775 0.47648 -0.73543 -0.6878117 0.305402 -0.6585171 -0.5982013 0.2577606 -0.7587588 -0.5414443 0.3260763 -0.7749274 -0.6134775 0.2210775 -0.758136 -0.5593448 0.2917323 -0.7759032 -0.6261638 0.1884177 -0.756583 -0.574791 0.2603446 -0.775781 -0.8917185 -0.04560673 -0.4502869 -0.8127122 -0.09015727 -0.5756479 -0.812707 -0.09016466 -0.5756542 -0.5809443 0.468021 -0.6659281 -0.79658 0.2466412 -0.5519317 -0.7795476 -0.2818812 -0.5593287 -0.7795452 -0.2818711 -0.5593371 -0.7795504 -0.2818796 -0.5593255 -0.5809383 0.4680345 -0.6659238 0.8141095 0.07346433 0.5760458 0.894159 0.1694083 0.4144642 0 0.8479983 -0.529999 0.891953 0.4459765 0.07432937 0 -0.3162278 0.9486834 -0.8126994 -0.09011876 -0.575672 -0.1611782 0.9131802 -0.3743309 -0.8540712 -0.1820275 -0.4872664 -0.612577 -0.6921572 0.3816648 -0.6125808 -0.6921617 0.3816503 -0.6125687 -0.6921695 0.3816556 -0.3210265 -0.7969595 0.5116617 -0.8524331 0.04312527 -0.5210547 -0.841789 0.05741018 -0.5367453 -0.8417911 0.05741196 -0.5367417 -0.8417893 0.05741196 -0.5367445 -0.9920295 -0.04563826 -0.1174509 -0.9920298 -0.04563415 -0.1174501 -0.8842 -0.04168379 -0.4652451 -0.8841884 -0.0416696 -0.4652684 -0.4814717 0.1477566 -0.8639174 0.8581808 0.1938771 0.4753288 0.7976446 0.1510681 0.5839021 + + + + + + + + + + + + + + +

0 0 1 0 2 0 1 1 3 1 2 1 1 2 0 2 4 2 0 3 5 3 4 3 6 4 7 4 8 4 9 5 10 5 11 5 12 6 13 6 14 6 12 7 15 7 13 7 16 8 17 8 18 8 19 9 17 9 16 9 20 10 21 10 22 10 22 11 23 11 20 11 24 12 20 12 23 12 23 13 25 13 24 13 26 14 24 14 25 14 27 15 17 15 19 15 27 16 28 16 17 16 28 17 18 17 17 17 14 18 28 18 27 18 27 19 29 19 14 19 29 20 30 20 14 20 31 21 14 21 30 21 30 22 32 22 31 22 33 23 34 23 35 23 36 24 37 24 35 24 13 25 35 25 38 25 35 26 37 26 38 26 35 27 13 27 33 27 13 28 39 28 33 28 15 29 39 29 13 29 38 30 40 30 13 30 13 31 28 31 14 31 18 32 28 32 13 32 13 33 41 33 18 33 13 34 40 34 41 34 14 35 42 35 12 35 42 36 14 36 31 36 32 37 43 37 31 37 44 38 36 38 45 38 44 39 37 39 36 39 44 40 38 40 37 40 44 41 40 41 38 41 44 42 41 42 40 42 44 43 18 43 41 43 18 44 44 44 16 44 34 45 33 45 46 45 26 46 46 46 33 46 33 47 39 47 26 47 24 48 26 48 15 48 26 49 39 49 15 49 15 50 12 50 24 50 20 51 24 51 42 51 24 52 12 52 42 52 42 53 31 53 20 53 21 54 20 54 31 54 31 55 43 55 21 55 43 56 47 56 48 56 21 57 43 57 48 57 3 58 49 58 9 58 11 59 3 59 9 59 50 60 49 60 3 60 51 61 50 61 3 61 52 62 51 62 3 62 52 63 3 63 53 63 54 64 55 64 56 64 54 64 56 64 57 64 54 65 57 65 4 65 54 64 58 64 55 64 59 64 55 64 58 64 60 66 6 66 8 66 60 67 8 67 61 67 60 68 61 68 62 68 63 69 60 69 62 69 64 70 60 70 63 70 63 71 65 71 64 71 63 72 62 72 66 72 65 73 63 73 66 73 67 74 64 74 65 74 48 75 67 75 65 75 65 76 68 76 48 76 48 77 68 77 21 77 69 78 19 78 16 78 16 79 70 79 69 79 70 80 71 80 69 80 58 81 54 81 72 81 72 82 73 82 74 82 72 83 74 83 47 83 75 84 72 84 47 84 43 85 32 85 75 85 47 86 43 86 75 86 76 87 59 87 77 87 78 88 59 88 76 88 4 89 57 89 1 89 1 90 78 90 3 90 1 91 57 91 56 91 1 92 56 92 55 92 1 93 55 93 78 93 59 94 78 94 55 94 3 95 78 95 53 95 65 96 79 96 80 96 65 97 80 97 68 97 81 98 79 98 65 98 65 99 66 99 81 99 81 100 66 100 62 100 22 101 21 101 68 101 22 102 68 102 80 102 10 103 9 103 82 103 9 104 49 104 83 104 84 105 83 105 49 105 49 106 50 106 84 106 85 107 84 107 50 107 50 108 51 108 85 108 86 109 85 109 51 109 51 110 52 110 86 110 87 111 86 111 52 111 88 112 73 112 72 112 53 113 89 113 90 113 53 114 91 114 89 114 92 115 89 115 91 115 71 116 89 116 92 116 71 117 70 117 89 117 70 118 16 118 89 118 44 119 89 119 16 119 93 120 89 120 44 120 94 121 89 121 93 121 95 122 89 122 94 122 90 123 89 123 95 123 71 124 92 124 69 124 69 125 27 125 19 125 69 126 29 126 27 126 69 127 96 127 29 127 30 128 29 128 96 128 75 129 30 129 96 129 97 130 75 130 96 130 97 131 96 131 98 131 92 132 96 132 69 132 92 133 98 133 96 133 95 134 52 134 90 134 97 135 98 135 99 135 52 136 95 136 87 136 76 137 92 137 91 137 91 138 53 138 76 138 76 139 53 139 78 139 92 140 76 140 98 140 76 141 77 141 98 141 72 142 75 142 97 142 72 143 97 143 99 143 72 144 99 144 98 144 72 145 98 145 100 145 100 64 98 64 77 64 59 146 100 146 77 146 90 147 52 147 53 147 75 148 32 148 30 148 58 149 100 149 59 149 58 150 72 150 100 150 88 151 72 151 54 151 101 152 102 152 103 152 101 153 103 153 104 153 105 154 101 154 104 154 106 155 102 155 101 155 101 156 107 156 106 156 106 157 107 157 108 157 109 158 106 158 108 158 109 159 110 159 106 159 108 160 111 160 109 160 112 161 109 161 111 161 113 162 112 162 111 162 113 163 114 163 115 163 112 164 113 164 115 164 116 165 117 165 118 165 119 166 118 166 117 166 117 167 120 167 119 167 121 168 119 168 120 168 120 169 122 169 121 169 10 170 121 170 122 170 123 171 124 171 11 171 11 172 122 172 123 172 122 173 11 173 10 173 125 174 126 174 127 174 124 175 125 175 127 175 124 176 127 176 128 176 124 177 128 177 129 177 124 178 129 178 130 178 2 179 124 179 130 179 124 180 2 180 11 180 11 181 2 181 3 181 131 182 132 182 133 182 134 183 135 183 8 183 7 184 134 184 8 184 136 185 137 185 138 185 139 186 137 186 136 186 136 187 140 187 139 187 141 188 139 188 140 188 140 189 142 189 141 189 143 190 141 190 142 190 144 191 145 191 143 191 142 192 144 192 143 192 146 193 145 193 144 193 144 194 147 194 146 194 146 195 147 195 61 195 146 196 61 196 8 196 135 197 146 197 8 197 137 198 148 198 138 198 148 199 149 199 138 199 150 200 106 200 110 200 151 201 152 201 150 201 153 202 102 202 106 202 150 203 153 203 106 203 150 204 152 204 154 204 150 205 154 205 155 205 150 206 155 206 156 206 150 207 156 207 157 207 153 208 150 208 157 208 102 209 153 209 158 209 103 210 102 210 158 210 159 211 160 211 161 211 159 212 161 212 162 212 163 213 159 213 162 213 160 214 159 214 164 214 0 215 160 215 164 215 0 216 130 216 129 216 0 217 129 217 128 217 0 218 128 218 165 218 0 219 165 219 160 219 2 220 130 220 0 220 0 221 164 221 5 221 142 222 140 222 166 222 144 223 142 223 166 223 119 224 167 224 118 224 168 225 167 225 119 225 119 226 121 226 168 226 116 227 118 227 169 227 131 64 114 64 113 64 131 228 113 228 111 228 133 64 114 64 131 64 103 229 170 229 171 229 104 230 103 230 171 230 171 231 172 231 104 231 104 232 172 232 173 232 105 233 104 233 173 233 173 234 172 234 174 234 175 235 173 235 174 235 174 236 176 236 175 236 176 237 177 237 178 237 179 238 178 238 177 238 175 239 176 239 178 239 175 240 178 240 180 240 175 241 180 241 181 241 175 242 181 242 182 242 183 243 175 243 182 243 182 244 184 244 183 244 185 245 179 245 177 245 177 246 186 246 185 246 183 247 184 247 187 247 183 248 187 248 188 248 189 249 183 249 188 249 188 250 190 250 189 250 191 251 189 251 190 251 190 252 192 252 191 252 193 253 191 253 192 253 192 254 194 254 193 254 193 255 194 255 195 255 193 256 195 256 196 256 197 257 193 257 196 257 196 258 198 258 197 258 199 259 200 259 201 259 202 260 199 260 201 260 197 261 198 261 200 261 200 262 199 262 203 262 203 263 197 263 200 263 199 264 204 264 203 264 203 265 204 265 205 265 206 266 203 266 205 266 205 267 207 267 127 267 127 268 207 268 208 268 128 269 127 269 208 269 190 270 188 270 192 270 194 270 192 270 188 270 188 270 209 270 194 270 210 271 194 271 209 271 209 270 211 270 210 270 212 270 210 270 211 270 211 270 213 270 212 270 214 272 212 272 213 272 213 270 215 270 214 270 216 273 214 273 215 273 215 270 217 270 216 270 218 270 216 270 217 270 219 182 220 182 221 182 222 274 221 274 220 274 220 182 223 182 222 182 224 182 222 182 223 182 223 182 225 182 224 182 224 182 225 182 226 182 227 182 224 182 226 182 226 275 228 275 227 275 229 182 227 182 228 182 200 276 230 276 201 276 231 277 201 277 230 277 230 278 232 278 231 278 233 279 231 279 232 279 232 280 234 280 233 280 235 281 233 281 234 281 234 282 236 282 235 282 237 283 235 283 236 283 236 284 238 284 237 284 239 285 237 285 238 285 238 286 240 286 239 286 241 287 239 287 240 287 240 288 242 288 241 288 243 289 241 289 242 289 242 290 244 290 243 290 245 291 243 291 244 291 178 292 246 292 180 292 247 293 180 293 246 293 246 294 248 294 247 294 249 294 247 294 248 294 248 295 250 295 249 295 251 296 249 296 250 296 250 297 252 297 251 297 253 298 251 298 252 298 252 299 254 299 253 299 255 300 253 300 254 300 254 301 256 301 255 301 257 302 255 302 256 302 256 303 258 303 257 303 259 303 257 303 258 303 258 304 260 304 259 304 261 305 259 305 260 305 247 306 181 306 180 306 249 307 184 307 182 307 249 308 182 308 181 308 247 309 249 309 181 309 249 310 251 310 184 310 262 311 188 311 187 311 262 312 187 312 184 312 184 313 251 313 253 313 262 314 184 314 253 314 209 315 188 315 262 315 253 316 255 316 262 316 262 317 255 317 257 317 263 318 262 318 257 318 263 319 211 319 209 319 262 320 263 320 209 320 213 321 211 321 263 321 257 322 259 322 263 322 264 323 215 323 213 323 263 324 264 324 213 324 263 325 259 325 261 325 263 326 261 326 265 326 264 327 263 327 265 327 215 328 264 328 266 328 217 329 215 329 266 329 200 330 198 330 230 330 232 331 230 331 198 331 198 332 196 332 232 332 232 333 196 333 267 333 234 334 232 334 267 334 268 335 236 335 234 335 267 336 268 336 234 336 195 337 194 337 268 337 268 338 267 338 195 338 194 339 210 339 268 339 238 340 236 340 268 340 268 341 210 341 212 341 269 342 268 342 212 342 269 343 240 343 238 343 268 344 269 344 238 344 212 345 214 345 269 345 242 346 240 346 269 346 269 347 214 347 216 347 216 348 218 348 269 348 269 349 218 349 270 349 271 350 269 350 270 350 269 351 271 351 242 351 242 352 271 352 272 352 244 353 242 353 272 353 178 354 273 354 246 354 248 355 246 355 273 355 273 356 274 356 248 356 250 357 248 357 274 357 274 358 275 358 250 358 252 359 250 359 275 359 276 360 254 360 252 360 275 361 276 361 252 361 277 362 221 362 276 362 278 363 277 363 276 363 279 364 278 364 276 364 276 365 275 365 279 365 221 366 222 366 276 366 256 367 254 367 276 367 276 368 222 368 224 368 276 369 224 369 227 369 276 370 227 370 229 370 276 371 229 371 280 371 281 372 276 372 280 372 281 373 258 373 256 373 276 374 281 374 256 374 258 375 281 375 282 375 260 376 258 376 282 376 103 377 158 377 170 377 283 378 170 378 158 378 158 379 153 379 283 379 284 380 283 380 153 380 153 381 157 381 284 381 285 381 284 381 157 381 157 382 156 382 285 382 286 383 285 383 156 383 156 384 155 384 286 384 287 385 286 385 155 385 208 386 288 386 128 386 165 387 128 387 288 387 288 388 289 388 165 388 160 389 165 389 289 389 289 390 290 390 160 390 161 391 160 391 290 391 290 392 291 392 161 392 162 393 161 393 291 393 291 394 292 394 162 394 163 395 162 395 292 395 199 396 293 396 204 396 288 397 208 397 207 397 294 398 205 398 204 398 205 399 294 399 207 399 207 400 295 400 288 400 295 401 207 401 294 401 204 402 296 402 294 402 296 403 204 403 293 403 297 404 294 404 296 404 294 405 297 405 295 405 289 406 288 406 295 406 295 407 298 407 289 407 298 408 295 408 297 408 293 409 299 409 296 409 300 410 297 410 296 410 297 411 300 411 298 411 290 412 289 412 298 412 301 413 298 413 300 413 298 414 301 414 290 414 299 415 302 415 296 415 296 416 303 416 300 416 303 417 296 417 302 417 291 418 290 418 301 418 300 419 304 419 301 419 304 420 300 420 303 420 305 421 303 421 302 421 303 422 305 422 304 422 292 423 291 423 301 423 304 424 306 424 301 424 301 425 306 425 292 425 307 426 308 426 309 426 310 427 177 427 176 427 310 428 176 428 311 428 309 429 310 429 311 429 310 430 309 430 308 430 186 431 177 431 310 431 308 432 312 432 310 432 313 433 310 433 312 433 313 434 314 434 315 434 315 435 186 435 310 435 316 436 313 436 312 436 312 437 317 437 316 437 318 438 319 438 316 438 317 439 318 439 316 439 320 440 319 440 318 440 318 441 321 441 320 441 320 442 293 442 202 442 320 443 321 443 302 443 320 444 302 444 299 444 293 445 320 445 299 445 199 446 202 446 293 446 170 447 283 447 171 447 322 448 171 448 283 448 171 449 322 449 172 449 311 450 176 450 174 450 174 451 323 451 311 451 323 452 174 452 172 452 172 453 324 453 323 453 324 454 172 454 322 454 322 455 325 455 324 455 325 456 322 456 283 456 283 457 284 457 325 457 309 458 311 458 323 458 323 459 326 459 309 459 326 460 323 460 324 460 327 461 324 461 325 461 324 462 327 462 326 462 328 463 325 463 284 463 325 464 328 464 327 464 284 465 285 465 328 465 307 466 309 466 326 466 329 467 326 467 327 467 326 468 329 468 307 468 330 469 327 469 328 469 327 470 330 470 329 470 331 471 328 471 285 471 328 472 331 472 330 472 332 473 307 473 329 473 332 474 329 474 330 474 285 475 286 475 331 475 333 476 330 476 331 476 330 477 333 477 332 477 286 478 287 478 331 478 334 479 331 479 287 479 331 480 334 480 333 480 335 481 315 481 314 481 336 482 315 482 335 482 335 483 337 483 336 483 338 484 336 484 337 484 337 485 339 485 338 485 338 486 339 486 219 486 338 487 219 487 221 487 173 182 175 182 183 182 173 182 183 182 189 182 173 182 189 182 191 182 173 182 191 182 193 182 173 488 193 488 197 488 173 489 197 489 203 489 206 182 173 182 203 182 206 490 125 490 124 490 206 491 124 491 123 491 206 492 123 492 122 492 206 493 122 493 120 493 206 494 120 494 117 494 206 495 117 495 116 495 116 496 169 496 132 496 206 497 116 497 132 497 206 498 132 498 131 498 206 499 131 499 111 499 206 500 111 500 108 500 206 501 108 501 107 501 206 502 107 502 101 502 206 503 101 503 105 503 173 504 206 504 105 504 126 505 125 505 206 505 196 270 195 270 267 270 314 506 313 506 316 506 316 507 319 507 314 507 310 508 313 508 315 508 221 509 277 509 338 509 315 510 336 510 338 510 277 511 315 511 338 511 277 512 278 512 315 512 278 513 279 513 315 513 186 514 315 514 279 514 186 515 279 515 275 515 186 516 275 516 274 516 185 517 186 517 274 517 185 518 274 518 273 518 179 519 185 519 273 519 178 520 179 520 273 520 201 521 340 521 341 521 341 522 340 522 342 522 342 523 340 523 343 523 342 524 343 524 344 524 344 525 343 525 345 525 344 526 345 526 346 526 344 527 346 527 347 527 348 528 347 528 346 528 349 529 347 529 348 529 349 530 350 530 347 530 347 531 350 531 351 531 352 532 350 532 349 532 320 533 347 533 319 533 350 534 352 534 219 534 350 535 219 535 339 535 337 536 350 536 339 536 350 537 337 537 351 537 335 538 351 538 337 538 351 539 335 539 347 539 335 540 314 540 347 540 347 541 320 541 344 541 319 542 347 542 314 542 344 543 320 543 202 543 245 544 353 544 243 544 243 545 353 545 354 545 355 546 241 546 354 546 354 547 241 547 243 547 354 548 356 548 355 548 355 549 356 549 228 549 355 550 228 550 226 550 355 551 226 551 357 551 355 552 357 552 358 552 241 553 355 553 239 553 352 554 355 554 358 554 355 555 346 555 345 555 346 556 355 556 348 556 348 557 355 557 349 557 349 558 355 558 352 558 345 559 237 559 355 559 355 560 237 560 239 560 237 561 345 561 235 561 343 562 235 562 345 562 235 563 343 563 233 563 340 564 233 564 343 564 233 565 340 565 231 565 201 566 231 566 340 566 223 182 357 182 225 182 357 182 223 182 358 182 220 182 358 182 223 182 358 182 220 182 352 182 219 182 352 182 220 182 202 567 342 567 344 567 342 568 202 568 341 568 341 569 202 569 201 569 225 182 357 182 226 182 127 570 206 570 205 570 126 571 206 571 127 571 169 182 167 182 132 182 169 572 118 572 167 572 359 270 218 270 360 270 361 270 359 270 360 270 362 270 363 270 360 270 364 270 365 270 361 270 360 573 366 573 362 573 367 574 361 574 365 574 368 575 362 575 366 575 365 576 369 576 367 576 366 577 370 577 368 577 371 578 367 578 369 578 372 270 368 270 370 270 369 270 373 270 371 270 374 270 371 270 373 270 370 270 375 270 372 270 373 270 376 270 374 270 377 579 372 579 375 579 374 580 376 580 378 580 379 270 374 270 378 270 380 270 381 270 377 270 375 270 380 270 377 270 382 270 381 270 380 270 378 270 382 270 379 270 383 270 379 270 382 270 384 270 383 270 382 270 380 581 384 581 382 581 385 582 245 582 386 582 387 583 388 583 261 583 389 584 366 584 266 584 390 585 389 585 264 585 390 586 261 586 388 586 391 587 390 587 388 587 361 270 218 270 359 270 218 588 361 588 392 588 392 589 393 589 270 589 393 590 394 590 271 590 394 591 386 591 272 591 385 592 395 592 245 592 395 593 396 593 354 593 396 594 397 594 356 594 398 595 399 595 229 595 399 596 400 596 281 596 400 597 387 597 282 597 401 598 376 598 373 598 378 599 376 599 401 599 382 600 378 600 401 600 381 601 382 601 401 601 377 602 381 602 401 602 372 270 377 270 401 270 401 603 368 603 372 603 362 604 368 604 401 604 363 270 362 270 401 270 364 270 363 270 401 270 365 605 364 605 401 605 369 606 365 606 401 606 373 270 369 270 401 270 402 607 366 607 389 607 389 608 390 608 402 608 403 609 402 609 390 609 390 610 391 610 403 610 392 611 404 611 393 611 394 612 393 612 404 612 404 613 405 613 394 613 394 614 405 614 386 614 406 615 370 615 366 615 402 616 406 616 366 616 403 617 391 617 406 617 402 618 403 618 406 618 391 619 407 619 406 619 375 620 370 620 406 620 408 621 406 621 407 621 408 622 380 622 375 622 406 623 408 623 375 623 407 624 409 624 408 624 384 625 380 625 408 625 408 626 409 626 410 626 411 627 408 627 410 627 408 628 411 628 384 628 383 629 384 629 411 629 410 630 412 630 411 630 413 631 411 631 412 631 411 632 413 632 383 632 379 633 383 633 413 633 412 634 414 634 413 634 415 635 374 635 379 635 413 636 415 636 379 636 415 637 413 637 414 637 371 638 374 638 415 638 414 639 386 639 415 639 404 640 367 640 371 640 415 641 404 641 371 641 415 642 386 642 405 642 415 643 405 643 404 643 392 644 367 644 404 644 367 645 392 645 361 645 229 182 397 182 398 182 398 182 416 182 417 182 397 182 416 182 398 182 391 646 388 646 387 646 386 647 414 647 418 647 418 648 385 648 386 648 409 649 407 649 419 649 419 650 420 650 409 650 410 651 409 651 420 651 420 652 421 652 410 652 421 653 422 653 412 653 412 654 410 654 421 654 422 655 418 655 414 655 414 656 412 656 422 656 407 657 391 657 387 657 387 658 419 658 407 658 400 659 419 659 387 659 399 660 419 660 400 660 417 661 420 661 419 661 417 662 421 662 420 662 417 663 416 663 421 663 416 664 422 664 421 664 418 665 422 665 416 665 395 666 385 666 418 666 395 667 418 667 396 667 360 668 364 668 361 668 360 270 363 270 364 270 360 669 266 669 366 669 399 670 417 670 419 670 398 671 417 671 399 671 397 672 396 672 416 672 396 673 418 673 416 673 112 674 423 674 110 674 109 675 112 675 110 675 424 182 133 182 132 182 425 676 136 676 138 676 149 677 426 677 138 677 150 678 110 678 423 678 150 679 427 679 151 679 136 680 425 680 428 680 428 681 429 681 136 681 115 682 114 682 133 682 244 683 386 683 245 683 228 182 397 182 229 182 260 583 387 583 261 583 266 684 264 684 389 684 264 685 265 685 390 685 390 686 265 686 261 686 270 687 218 687 392 687 271 688 270 688 393 688 272 689 271 689 394 689 244 690 272 690 386 690 395 691 353 691 245 691 354 692 353 692 395 692 356 693 354 693 396 693 228 694 356 694 397 694 399 695 280 695 229 695 281 696 280 696 399 696 282 697 281 697 400 697 260 698 282 698 387 698 360 270 218 270 217 270 217 699 266 699 360 699 430 700 431 700 432 700 138 701 433 701 434 701 425 702 138 702 434 702 435 703 436 703 437 703 435 704 438 704 436 704 439 705 440 705 441 705 441 706 440 706 442 706 442 707 440 707 443 707 443 708 440 708 444 708 444 709 440 709 445 709 445 710 440 710 446 710 443 711 447 711 442 711 448 712 449 712 447 712 447 713 449 713 450 713 436 714 450 714 449 714 451 715 450 715 436 715 452 716 451 716 436 716 451 717 453 717 450 717 442 718 447 718 450 718 442 719 450 719 453 719 454 720 455 720 456 720 445 721 455 721 454 721 436 722 438 722 452 722 424 723 115 723 133 723 457 724 115 724 424 724 458 725 457 725 424 725 459 726 458 726 424 726 424 727 446 727 459 727 440 728 459 728 446 728 455 729 445 729 446 729 460 730 461 730 462 730 432 731 461 731 460 731 460 732 463 732 432 732 464 733 432 733 463 733 463 734 465 734 464 734 465 735 434 735 464 735 465 736 466 736 434 736 425 737 434 737 466 737 467 738 425 738 466 738 468 739 469 739 470 739 469 740 471 740 470 740 472 741 468 741 470 741 470 742 473 742 472 742 474 743 472 743 473 743 473 744 475 744 474 744 476 745 474 745 475 745 475 746 477 746 476 746 478 747 476 747 477 747 477 748 479 748 478 748 480 749 478 749 479 749 479 750 462 750 480 750 480 751 462 751 461 751 428 752 425 752 467 752 481 753 482 753 483 753 482 754 481 754 484 754 485 755 486 755 482 755 487 756 488 756 489 756 490 757 489 757 488 757 490 758 437 758 489 758 490 759 491 759 437 759 490 760 492 760 491 760 490 761 493 761 492 761 494 762 493 762 490 762 495 763 490 763 496 763 490 764 488 764 496 764 490 765 495 765 494 765 495 766 497 766 494 766 496 767 498 767 495 767 499 768 497 768 495 768 495 769 482 769 499 769 482 770 500 770 499 770 482 771 486 771 500 771 495 772 483 772 482 772 495 773 498 773 483 773 489 774 448 774 487 774 449 775 448 775 489 775 436 776 449 776 489 776 489 777 437 777 436 777 437 778 491 778 501 778 501 779 435 779 437 779 502 780 439 780 441 780 503 781 441 781 442 781 441 782 503 782 502 782 442 783 453 783 503 783 503 784 504 784 502 784 502 785 504 785 505 785 427 786 506 786 151 786 427 787 150 787 423 787 427 788 439 788 502 788 427 789 507 789 439 789 427 790 423 790 507 790 427 791 502 791 506 791 502 792 505 792 506 792 508 793 509 793 510 793 511 794 510 794 509 794 511 795 451 795 452 795 511 796 509 796 451 796 452 797 512 797 511 797 452 798 513 798 512 798 452 799 514 799 513 799 515 800 514 800 438 800 514 801 452 801 438 801 438 802 435 802 515 802 516 803 515 803 435 803 435 804 501 804 516 804 491 805 516 805 501 805 448 806 447 806 444 806 443 807 444 807 447 807 517 808 518 808 483 808 483 809 498 809 517 809 498 810 456 810 517 810 498 811 454 811 456 811 445 812 454 812 488 812 454 813 496 813 488 813 454 814 498 814 496 814 445 815 488 815 444 815 488 816 487 816 444 816 448 817 444 817 487 817 519 818 477 818 475 818 519 819 479 819 477 819 462 270 479 270 519 270 519 820 460 820 462 820 519 821 463 821 460 821 519 270 465 270 463 270 519 822 466 822 465 822 519 823 467 823 466 823 481 824 483 824 518 824 432 825 431 825 461 825 433 826 432 826 464 826 464 827 434 827 433 827 432 828 433 828 430 828 433 829 520 829 430 829 521 830 520 830 433 830 521 831 433 831 138 831 426 832 521 832 138 832 509 833 504 833 451 833 505 834 504 834 509 834 509 583 508 583 505 583 446 835 424 835 132 835 439 836 459 836 440 836 459 837 439 837 507 837 459 838 507 838 458 838 507 839 457 839 458 839 112 840 457 840 507 840 457 841 112 841 115 841 507 842 423 842 112 842 461 843 431 843 480 843 513 844 514 844 522 844 431 845 522 845 514 845 514 846 515 846 431 846 515 847 480 847 431 847 478 848 480 848 491 848 480 849 516 849 491 849 480 850 515 850 516 850 491 851 492 851 478 851 476 852 478 852 492 852 492 853 493 853 476 853 474 854 476 854 494 854 476 855 493 855 494 855 494 856 497 856 474 856 472 857 474 857 497 857 497 858 499 858 472 858 468 859 472 859 500 859 472 860 499 860 500 860 500 861 486 861 468 861 469 862 468 862 486 862 523 863 446 863 132 863 446 864 523 864 455 864 83 865 82 865 9 865 82 866 524 866 10 866 525 867 61 867 526 867 62 868 61 868 525 868 525 869 527 869 62 869 527 870 81 870 62 870 147 871 526 871 61 871 147 872 528 872 526 872 22 270 80 270 519 270 519 873 525 873 526 873 519 874 527 874 525 874 519 875 81 875 527 875 519 876 79 876 81 876 519 877 80 877 79 877 526 878 528 878 519 878 528 879 529 879 519 879 166 880 519 880 529 880 455 881 87 881 95 881 455 882 86 882 87 882 455 883 85 883 86 883 455 884 84 884 85 884 455 885 83 885 84 885 455 886 82 886 83 886 455 887 524 887 82 887 455 888 168 888 524 888 530 889 531 889 34 889 46 890 530 890 34 890 532 891 533 891 531 891 530 892 532 892 531 892 534 893 533 893 532 893 535 894 536 894 534 894 532 895 535 895 534 895 535 896 537 896 536 896 455 897 95 897 94 897 455 898 94 898 93 898 538 899 539 899 540 899 540 900 541 900 538 900 538 901 541 901 484 901 542 902 538 902 484 902 543 903 45 903 36 903 36 904 544 904 543 904 544 905 540 905 543 905 539 906 543 906 540 906 545 907 533 907 534 907 546 908 545 908 534 908 546 909 541 909 540 909 546 910 540 910 545 910 534 911 536 911 546 911 546 912 536 912 547 912 546 913 485 913 541 913 545 914 544 914 36 914 35 915 545 915 36 915 35 916 34 916 531 916 35 917 531 917 533 917 35 918 533 918 545 918 544 919 545 919 540 919 537 920 535 920 548 920 530 921 549 921 550 921 532 922 530 922 550 922 530 923 46 923 549 923 551 924 549 924 46 924 46 925 26 925 551 925 25 926 551 926 26 926 93 927 44 927 455 927 455 928 44 928 45 928 535 929 552 929 548 929 532 930 552 930 535 930 532 931 550 931 552 931 519 932 25 932 23 932 519 933 23 933 22 933 140 934 136 934 429 934 429 935 166 935 140 935 166 936 529 936 144 936 147 937 144 937 529 937 529 938 528 938 147 938 524 939 168 939 121 939 121 940 10 940 524 940 548 941 553 941 537 941 469 942 537 942 553 942 471 943 469 943 553 943 485 944 482 944 484 944 485 945 554 945 486 945 485 946 547 946 554 946 485 947 484 947 541 947 485 948 546 948 547 948 428 270 467 270 519 270 429 270 428 270 519 270 519 949 166 949 429 949 518 950 555 950 481 950 484 951 481 951 555 951 555 952 542 952 484 952 554 953 469 953 486 953 537 954 469 954 547 954 469 955 554 955 547 955 537 956 547 956 536 956 523 182 132 182 167 182 523 957 167 957 168 957 523 958 168 958 455 958 556 959 557 959 558 959 557 960 559 960 558 960 557 961 556 961 560 961 561 962 562 962 563 962 564 963 565 963 566 963 567 964 568 964 569 964 567 965 570 965 568 965 571 966 572 966 573 966 574 967 572 967 571 967 575 968 576 968 577 968 577 969 578 969 575 969 579 970 575 970 578 970 578 971 580 971 579 971 581 972 579 972 580 972 582 973 572 973 574 973 582 974 583 974 572 974 583 975 573 975 572 975 569 976 583 976 582 976 582 977 584 977 569 977 584 978 585 978 569 978 586 979 569 979 585 979 585 980 587 980 586 980 588 981 589 981 590 981 591 982 592 982 590 982 568 983 590 983 593 983 590 984 592 984 593 984 590 985 568 985 588 985 568 986 594 986 588 986 570 987 594 987 568 987 593 988 595 988 568 988 568 989 583 989 569 989 573 990 583 990 568 990 568 991 596 991 573 991 568 992 595 992 596 992 569 993 597 993 567 993 597 994 569 994 586 994 587 995 598 995 586 995 599 996 591 996 600 996 599 997 592 997 591 997 599 998 593 998 592 998 599 999 595 999 593 999 599 1000 596 1000 595 1000 599 1001 573 1001 596 1001 573 1002 599 1002 571 1002 589 1003 588 1003 601 1003 581 1004 601 1004 588 1004 588 1005 594 1005 581 1005 579 1006 581 1006 570 1006 581 1007 594 1007 570 1007 570 1008 567 1008 579 1008 575 1009 579 1009 597 1009 579 1010 567 1010 597 1010 597 1011 586 1011 575 1011 576 1012 575 1012 586 1012 586 1013 598 1013 576 1013 598 1014 602 1014 603 1014 576 1015 598 1015 603 1015 559 1016 604 1016 564 1016 566 1017 559 1017 564 1017 605 1018 604 1018 559 1018 606 1019 605 1019 559 1019 607 1020 606 1020 559 1020 607 1021 559 1021 608 1021 609 64 610 64 611 64 609 64 611 64 612 64 609 1022 612 1022 560 1022 609 1023 613 1023 610 1023 614 1024 610 1024 613 1024 615 1025 561 1025 563 1025 615 1026 563 1026 616 1026 615 1027 616 1027 617 1027 618 1028 615 1028 617 1028 619 1029 615 1029 618 1029 618 1030 620 1030 619 1030 618 1031 617 1031 621 1031 620 1032 618 1032 621 1032 622 1033 619 1033 620 1033 603 1034 622 1034 620 1034 620 1035 623 1035 603 1035 603 1036 623 1036 576 1036 624 1037 574 1037 571 1037 571 1038 625 1038 624 1038 625 1039 626 1039 624 1039 613 1040 609 1040 627 1040 627 1041 628 1041 629 1041 627 1042 629 1042 602 1042 630 1043 627 1043 602 1043 598 1044 587 1044 630 1044 602 1045 598 1045 630 1045 631 1046 632 1046 614 1046 633 1047 614 1047 632 1047 560 1048 612 1048 557 1048 557 1049 633 1049 559 1049 557 1050 612 1050 611 1050 557 1051 611 1051 610 1051 557 1052 610 1052 633 1052 614 1053 633 1053 610 1053 559 1054 633 1054 608 1054 620 1055 634 1055 635 1055 620 1056 635 1056 623 1056 636 1057 634 1057 620 1057 620 1058 621 1058 636 1058 636 1059 621 1059 617 1059 577 1060 576 1060 623 1060 577 1061 623 1061 635 1061 565 1062 564 1062 637 1062 564 1063 604 1063 638 1063 639 1064 638 1064 604 1064 604 1065 605 1065 639 1065 640 1066 639 1066 605 1066 605 1067 606 1067 640 1067 641 1068 640 1068 606 1068 606 1069 607 1069 641 1069 642 1070 641 1070 607 1070 643 1071 628 1071 627 1071 608 1072 644 1072 645 1072 608 1073 646 1073 644 1073 647 1074 644 1074 646 1074 626 1075 644 1075 647 1075 626 1076 625 1076 644 1076 625 1077 571 1077 644 1077 599 1078 644 1078 571 1078 648 120 644 120 599 120 649 1079 644 1079 648 1079 650 1080 644 1080 649 1080 645 1081 644 1081 650 1081 626 1082 647 1082 624 1082 624 1083 582 1083 574 1083 624 1084 584 1084 582 1084 624 1085 651 1085 584 1085 585 1086 584 1086 651 1086 630 1087 585 1087 651 1087 652 1088 630 1088 651 1088 652 1089 651 1089 653 1089 647 1090 651 1090 624 1090 647 1091 653 1091 651 1091 650 1092 607 1092 645 1092 607 1093 650 1093 642 1093 632 1094 647 1094 646 1094 646 1095 608 1095 632 1095 632 1096 608 1096 633 1096 647 1097 632 1097 653 1097 632 1098 631 1098 653 1098 627 1099 630 1099 652 1099 627 1100 652 1100 653 1100 627 1101 653 1101 654 1101 654 1102 653 1102 631 1102 654 1103 631 1103 614 1103 645 1104 607 1104 608 1104 630 1105 587 1105 585 1105 613 1106 654 1106 614 1106 613 1107 627 1107 654 1107 643 1108 627 1108 609 1108 655 1109 656 1109 657 1109 655 1110 657 1110 658 1110 659 1111 655 1111 658 1111 660 1112 656 1112 655 1112 655 1113 661 1113 660 1113 660 1114 661 1114 662 1114 663 1115 660 1115 662 1115 663 1116 664 1116 660 1116 662 1117 665 1117 663 1117 666 1118 663 1118 665 1118 667 1119 666 1119 665 1119 667 1120 668 1120 669 1120 666 1121 667 1121 669 1121 670 1122 671 1122 672 1122 673 1123 672 1123 671 1123 671 1124 674 1124 673 1124 675 1125 673 1125 674 1125 674 1126 676 1126 675 1126 565 1127 675 1127 676 1127 677 1128 678 1128 566 1128 566 1129 676 1129 677 1129 676 1130 566 1130 565 1130 679 1131 680 1131 681 1131 678 1132 679 1132 681 1132 678 1133 681 1133 682 1133 678 1134 682 1134 683 1134 678 1135 683 1135 684 1135 558 1136 678 1136 684 1136 678 1137 558 1137 566 1137 566 1138 558 1138 559 1138 685 182 686 182 687 182 688 1139 689 1139 563 1139 562 1140 688 1140 563 1140 690 1141 691 1141 692 1141 693 1142 691 1142 690 1142 690 1143 694 1143 693 1143 695 1144 693 1144 694 1144 694 1145 696 1145 695 1145 697 1146 695 1146 696 1146 698 1147 699 1147 697 1147 696 1148 698 1148 697 1148 700 1149 699 1149 698 1149 698 1150 701 1150 700 1150 700 1151 701 1151 616 1151 700 1152 616 1152 563 1152 689 1153 700 1153 563 1153 691 1154 702 1154 692 1154 702 1155 703 1155 692 1155 704 1156 660 1156 664 1156 705 1157 706 1157 704 1157 707 1158 656 1158 660 1158 704 1159 707 1159 660 1159 704 1160 706 1160 708 1160 704 1161 708 1161 709 1161 704 1162 709 1162 710 1162 704 1163 710 1163 711 1163 707 1164 704 1164 711 1164 656 1165 707 1165 712 1165 656 1166 712 1166 713 1166 657 1167 656 1167 713 1167 714 1168 715 1168 716 1168 714 1169 716 1169 717 1169 718 1170 714 1170 717 1170 715 1171 714 1171 719 1171 556 1172 715 1172 719 1172 556 1173 684 1173 683 1173 556 1174 683 1174 682 1174 556 1175 682 1175 720 1175 556 1176 720 1176 715 1176 558 1177 684 1177 556 1177 556 1178 719 1178 560 1178 696 1179 694 1179 721 1179 698 1180 696 1180 721 1180 673 1181 722 1181 672 1181 723 1182 722 1182 673 1182 673 1183 675 1183 723 1183 670 1184 672 1184 724 1184 685 64 668 64 667 64 685 1185 667 1185 665 1185 687 64 668 64 685 64 657 1186 725 1186 726 1186 658 1187 657 1187 726 1187 726 1188 727 1188 658 1188 658 1189 727 1189 728 1189 659 1190 658 1190 728 1190 728 1191 727 1191 729 1191 730 1192 728 1192 729 1192 729 1193 731 1193 730 1193 731 1194 732 1194 733 1194 734 1195 733 1195 732 1195 730 1196 731 1196 733 1196 730 240 733 240 735 240 730 1197 735 1197 736 1197 730 1198 736 1198 737 1198 738 1199 730 1199 737 1199 737 1200 739 1200 738 1200 740 245 734 245 732 245 732 1201 741 1201 740 1201 738 1202 739 1202 742 1202 738 1203 742 1203 743 1203 744 1204 738 1204 743 1204 743 1205 745 1205 744 1205 746 1206 744 1206 745 1206 745 1207 747 1207 746 1207 748 1208 746 1208 747 1208 747 1209 749 1209 748 1209 748 1210 749 1210 750 1210 748 1211 750 1211 751 1211 752 1212 748 1212 751 1212 751 1213 753 1213 752 1213 754 1214 755 1214 756 1214 757 1215 754 1215 756 1215 752 1216 753 1216 755 1216 755 1217 754 1217 758 1217 758 1218 752 1218 755 1218 754 1219 759 1219 758 1219 758 1220 759 1220 760 1220 761 1221 758 1221 760 1221 760 1222 762 1222 681 1222 681 1223 762 1223 763 1223 682 1224 681 1224 763 1224 745 270 743 270 747 270 749 270 747 270 743 270 743 270 764 270 749 270 765 1225 749 1225 764 1225 764 1226 766 1226 765 1226 767 270 765 270 766 270 766 270 768 270 767 270 769 272 767 272 768 272 768 270 770 270 769 270 771 1227 769 1227 770 1227 770 270 772 270 771 270 773 270 771 270 772 270 774 182 775 182 776 182 777 1228 776 1228 775 1228 775 182 778 182 777 182 779 182 777 182 778 182 778 182 780 182 779 182 779 182 780 182 781 182 782 182 779 182 781 182 781 1229 783 1229 782 1229 784 182 782 182 783 182 755 1230 785 1230 756 1230 786 1231 756 1231 785 1231 785 1232 787 1232 786 1232 788 1233 786 1233 787 1233 787 1234 789 1234 788 1234 790 1235 788 1235 789 1235 789 1236 791 1236 790 1236 792 1237 790 1237 791 1237 791 1238 793 1238 792 1238 794 1239 792 1239 793 1239 793 1240 795 1240 794 1240 796 1241 794 1241 795 1241 795 1242 797 1242 796 1242 798 1243 796 1243 797 1243 797 1244 799 1244 798 1244 800 1245 798 1245 799 1245 733 292 801 292 735 292 802 293 735 293 801 293 801 1246 803 1246 802 1246 804 1247 802 1247 803 1247 803 1248 805 1248 804 1248 806 1249 804 1249 805 1249 805 1250 807 1250 806 1250 808 1251 806 1251 807 1251 807 299 809 299 808 299 810 1252 808 1252 809 1252 809 301 811 301 810 301 812 302 810 302 811 302 811 1253 813 1253 812 1253 814 1253 812 1253 813 1253 813 1254 815 1254 814 1254 816 1255 814 1255 815 1255 802 1256 736 1256 735 1256 804 1257 739 1257 737 1257 804 1258 737 1258 736 1258 802 1259 804 1259 736 1259 804 1260 806 1260 739 1260 817 1261 743 1261 742 1261 817 1262 742 1262 739 1262 739 1263 806 1263 808 1263 817 1264 739 1264 808 1264 764 1265 743 1265 817 1265 808 1266 810 1266 817 1266 817 1267 810 1267 812 1267 818 1268 817 1268 812 1268 818 1269 766 1269 764 1269 817 1270 818 1270 764 1270 768 1271 766 1271 818 1271 812 1272 814 1272 818 1272 819 1273 770 1273 768 1273 818 1274 819 1274 768 1274 818 1275 814 1275 816 1275 818 1276 816 1276 820 1276 819 1277 818 1277 820 1277 770 1278 819 1278 821 1278 772 1279 770 1279 821 1279 755 330 753 330 785 330 787 1280 785 1280 753 1280 753 1281 751 1281 787 1281 787 1282 751 1282 822 1282 789 1283 787 1283 822 1283 823 1284 791 1284 789 1284 822 1285 823 1285 789 1285 750 1286 749 1286 823 1286 823 1287 822 1287 750 1287 749 1288 765 1288 823 1288 793 1289 791 1289 823 1289 823 1290 765 1290 767 1290 824 1291 823 1291 767 1291 824 1292 795 1292 793 1292 823 1293 824 1293 793 1293 767 1294 769 1294 824 1294 797 1295 795 1295 824 1295 824 347 769 347 771 347 771 1296 773 1296 824 1296 824 1297 773 1297 825 1297 826 1298 824 1298 825 1298 824 1299 826 1299 797 1299 797 352 826 352 827 352 799 1300 797 1300 827 1300 733 1301 828 1301 801 1301 803 1302 801 1302 828 1302 828 1303 829 1303 803 1303 805 357 803 357 829 357 829 1304 830 1304 805 1304 807 1305 805 1305 830 1305 831 1306 809 1306 807 1306 830 1307 831 1307 807 1307 832 1308 776 1308 831 1308 833 1309 832 1309 831 1309 834 1310 833 1310 831 1310 831 1311 830 1311 834 1311 776 1312 777 1312 831 1312 811 1313 809 1313 831 1313 831 1314 777 1314 779 1314 831 1315 779 1315 782 1315 831 1316 782 1316 784 1316 831 1317 784 1317 835 1317 836 1318 831 1318 835 1318 836 1319 813 1319 811 1319 831 1320 836 1320 811 1320 813 1321 836 1321 837 1321 815 1322 813 1322 837 1322 657 1323 713 1323 725 1323 838 1324 725 1324 713 1324 713 1325 712 1325 838 1325 839 1326 838 1326 712 1326 712 1327 711 1327 839 1327 840 1328 839 1328 711 1328 711 1329 710 1329 840 1329 841 1330 840 1330 710 1330 710 1331 709 1331 841 1331 842 1332 841 1332 709 1332 763 1333 843 1333 682 1333 720 1334 682 1334 843 1334 843 1335 844 1335 720 1335 715 1336 720 1336 844 1336 844 1337 845 1337 715 1337 716 1338 715 1338 845 1338 845 1339 846 1339 716 1339 717 1340 716 1340 846 1340 846 1341 847 1341 717 1341 718 1342 717 1342 847 1342 754 1343 848 1343 759 1343 843 1344 763 1344 762 1344 849 1345 760 1345 759 1345 760 1346 849 1346 762 1346 762 1347 850 1347 843 1347 850 1348 762 1348 849 1348 759 1349 851 1349 849 1349 851 1350 759 1350 848 1350 852 1351 849 1351 851 1351 849 1352 852 1352 850 1352 844 1353 843 1353 850 1353 850 1354 853 1354 844 1354 853 1355 850 1355 852 1355 848 1356 854 1356 851 1356 855 1357 852 1357 851 1357 852 1358 855 1358 853 1358 845 1359 844 1359 853 1359 856 1360 853 1360 855 1360 853 1361 856 1361 845 1361 854 1362 857 1362 851 1362 851 1363 858 1363 855 1363 858 1364 851 1364 857 1364 857 1365 859 1365 858 1365 846 1366 845 1366 856 1366 855 1367 860 1367 856 1367 860 1368 855 1368 858 1368 861 1369 858 1369 859 1369 858 1370 861 1370 860 1370 847 1371 846 1371 856 1371 860 1372 862 1372 856 1372 856 1373 862 1373 847 1373 863 1374 864 1374 865 1374 866 1375 732 1375 731 1375 866 1376 731 1376 867 1376 865 1377 866 1377 867 1377 866 1378 865 1378 864 1378 741 1379 732 1379 866 1379 864 1380 868 1380 866 1380 869 1381 866 1381 868 1381 869 1382 870 1382 871 1382 871 435 741 435 866 435 872 1383 869 1383 868 1383 868 1384 873 1384 872 1384 874 1385 875 1385 872 1385 873 1386 874 1386 872 1386 876 1387 875 1387 874 1387 874 1388 877 1388 876 1388 876 1389 848 1389 757 1389 876 1390 877 1390 857 1390 876 1391 857 1391 854 1391 848 1392 876 1392 854 1392 754 1393 757 1393 848 1393 725 1394 838 1394 726 1394 878 1395 726 1395 838 1395 726 1396 878 1396 727 1396 867 1397 731 1397 729 1397 729 1398 879 1398 867 1398 879 1399 729 1399 727 1399 727 1400 880 1400 879 1400 880 1401 727 1401 878 1401 878 1402 881 1402 880 1402 881 1403 878 1403 838 1403 838 1404 839 1404 881 1404 865 1405 867 1405 879 1405 879 1406 882 1406 865 1406 882 1407 879 1407 880 1407 883 1408 880 1408 881 1408 880 1409 883 1409 882 1409 884 1410 881 1410 839 1410 881 1411 884 1411 883 1411 839 1412 840 1412 884 1412 863 1413 865 1413 882 1413 885 1414 882 1414 883 1414 882 1415 885 1415 863 1415 886 1416 883 1416 884 1416 883 1417 886 1417 885 1417 887 1418 884 1418 840 1418 884 1419 887 1419 886 1419 888 1420 863 1420 885 1420 888 1421 885 1421 886 1421 840 1422 841 1422 887 1422 889 1423 886 1423 887 1423 886 1424 889 1424 888 1424 841 1425 842 1425 887 1425 890 1426 887 1426 842 1426 887 1427 890 1427 889 1427 891 1428 871 1428 870 1428 892 1429 871 1429 891 1429 891 1430 893 1430 892 1430 894 1431 892 1431 893 1431 893 1432 895 1432 894 1432 894 1433 895 1433 774 1433 894 1434 774 1434 776 1434 728 182 730 182 738 182 728 182 738 182 744 182 728 182 744 182 746 182 728 1435 746 1435 748 1435 728 1436 748 1436 752 1436 728 1437 752 1437 758 1437 761 182 728 182 758 182 761 1438 679 1438 678 1438 761 1439 678 1439 677 1439 761 1440 677 1440 676 1440 761 1441 676 1441 674 1441 761 1442 674 1442 671 1442 761 1443 671 1443 670 1443 670 496 724 496 686 496 761 1444 670 1444 686 1444 761 1445 686 1445 685 1445 761 1446 685 1446 665 1446 761 1447 665 1447 662 1447 761 1448 662 1448 661 1448 761 1449 661 1449 655 1449 761 1450 655 1450 659 1450 728 1451 761 1451 659 1451 680 496 679 496 761 496 707 182 711 182 712 182 751 1452 750 1452 822 1452 870 1453 869 1453 872 1453 872 1454 875 1454 870 1454 866 1455 869 1455 871 1455 776 1456 832 1456 894 1456 871 1457 892 1457 894 1457 832 1458 871 1458 894 1458 832 1459 833 1459 871 1459 833 1460 834 1460 871 1460 741 1461 871 1461 834 1461 741 1462 834 1462 830 1462 741 1463 830 1463 829 1463 740 1464 741 1464 829 1464 740 1465 829 1465 828 1465 734 1466 740 1466 828 1466 733 1467 734 1467 828 1467 756 1468 896 1468 897 1468 897 1469 896 1469 898 1469 898 1470 896 1470 899 1470 898 1471 899 1471 900 1471 900 1472 899 1472 901 1472 900 1473 901 1473 902 1473 900 1474 902 1474 903 1474 904 1475 903 1475 902 1475 905 1476 903 1476 904 1476 905 1477 906 1477 903 1477 903 1478 906 1478 907 1478 908 1479 906 1479 905 1479 876 1480 903 1480 875 1480 906 1481 908 1481 774 1481 906 1482 774 1482 895 1482 893 1483 906 1483 895 1483 906 1484 893 1484 907 1484 891 1485 907 1485 893 1485 907 1486 891 1486 903 1486 891 1487 870 1487 903 1487 903 1488 876 1488 900 1488 875 1489 903 1489 870 1489 900 1490 876 1490 757 1490 800 1491 909 1491 798 1491 798 1492 909 1492 910 1492 911 1493 796 1493 910 1493 910 1494 796 1494 798 1494 910 1495 912 1495 911 1495 911 1496 912 1496 783 1496 911 1497 783 1497 781 1497 911 1498 781 1498 913 1498 911 1499 913 1499 914 1499 796 1500 911 1500 794 1500 908 1501 911 1501 914 1501 911 1502 902 1502 901 1502 902 1503 911 1503 904 1503 904 1504 911 1504 905 1504 905 1505 911 1505 908 1505 901 1506 792 1506 911 1506 911 1507 792 1507 794 1507 792 1508 901 1508 790 1508 899 1509 790 1509 901 1509 790 1510 899 1510 788 1510 896 1511 788 1511 899 1511 788 1512 896 1512 786 1512 756 1513 786 1513 896 1513 778 182 913 182 780 182 913 182 778 182 914 182 775 182 914 182 778 182 914 182 775 182 908 182 774 182 908 182 775 182 757 1514 898 1514 900 1514 898 1515 757 1515 897 1515 897 1516 757 1516 756 1516 780 182 913 182 781 182 681 1517 761 1517 760 1517 680 1518 761 1518 681 1518 724 1519 722 1519 686 1519 724 1520 672 1520 722 1520 915 270 773 270 916 270 917 270 915 270 916 270 918 270 919 270 916 270 920 270 921 270 917 270 916 573 922 573 918 573 923 1521 917 1521 921 1521 924 1522 918 1522 922 1522 921 1523 925 1523 923 1523 922 1524 926 1524 924 1524 927 1525 923 1525 925 1525 928 270 924 270 926 270 925 270 929 270 927 270 930 270 927 270 929 270 926 270 931 270 928 270 929 270 932 270 930 270 933 1526 928 1526 931 1526 930 1527 932 1527 934 1527 935 270 930 270 934 270 936 270 937 270 933 270 931 270 936 270 933 270 938 270 937 270 936 270 934 270 938 270 935 270 939 270 935 270 938 270 940 270 939 270 938 270 936 1528 940 1528 938 1528 941 582 800 582 942 582 943 1529 944 1529 816 1529 945 1530 922 1530 821 1530 946 1531 945 1531 819 1531 946 1532 816 1532 944 1532 947 1533 946 1533 944 1533 917 270 773 270 915 270 773 1534 917 1534 948 1534 948 1535 949 1535 825 1535 949 1536 950 1536 826 1536 950 1537 942 1537 827 1537 941 1538 951 1538 800 1538 951 1539 952 1539 910 1539 952 1540 953 1540 912 1540 954 595 955 595 784 595 955 1541 956 1541 836 1541 956 1542 943 1542 837 1542 957 1543 932 1543 929 1543 934 1544 932 1544 957 1544 938 1545 934 1545 957 1545 937 1546 938 1546 957 1546 933 602 937 602 957 602 928 270 933 270 957 270 957 603 924 603 928 603 918 1547 924 1547 957 1547 919 270 918 270 957 270 920 270 919 270 957 270 921 605 920 605 957 605 925 606 921 606 957 606 929 270 925 270 957 270 958 607 922 607 945 607 945 1548 946 1548 958 1548 959 1549 958 1549 946 1549 946 1550 947 1550 959 1550 948 1551 960 1551 949 1551 950 1552 949 1552 960 1552 960 1553 961 1553 950 1553 950 1554 961 1554 942 1554 962 1555 926 1555 922 1555 958 1556 962 1556 922 1556 959 1557 947 1557 962 1557 958 1558 959 1558 962 1558 947 1559 963 1559 962 1559 931 1560 926 1560 962 1560 964 1561 962 1561 963 1561 964 1562 936 1562 931 1562 962 1563 964 1563 931 1563 963 1564 965 1564 964 1564 940 1565 936 1565 964 1565 964 1566 965 1566 966 1566 967 1567 964 1567 966 1567 964 1568 967 1568 940 1568 939 1569 940 1569 967 1569 966 1570 968 1570 967 1570 969 1571 967 1571 968 1571 967 1572 969 1572 939 1572 935 1573 939 1573 969 1573 968 1574 970 1574 969 1574 971 1575 930 1575 935 1575 969 1576 971 1576 935 1576 971 1577 969 1577 970 1577 927 1578 930 1578 971 1578 970 1579 942 1579 971 1579 960 1580 923 1580 927 1580 971 641 960 641 927 641 971 1581 942 1581 961 1581 971 1582 961 1582 960 1582 948 1583 923 1583 960 1583 923 1584 948 1584 917 1584 784 182 953 182 954 182 954 182 972 182 973 182 953 182 972 182 954 182 947 1585 944 1585 943 1585 942 1586 970 1586 974 1586 974 1587 941 1587 942 1587 965 1588 963 1588 975 1588 975 1588 976 1588 965 1588 966 1589 965 1589 976 1589 976 1590 977 1590 966 1590 977 1591 978 1591 968 1591 968 1592 966 1592 977 1592 978 1593 974 1593 970 1593 970 1593 968 1593 978 1593 963 1594 947 1594 943 1594 943 1595 975 1595 963 1595 956 1596 975 1596 943 1596 955 1597 975 1597 956 1597 973 1598 976 1598 975 1598 973 1599 977 1599 976 1599 973 1600 972 1600 977 1600 972 1601 978 1601 977 1601 974 1602 978 1602 972 1602 951 1603 941 1603 974 1603 951 1604 974 1604 952 1604 916 1605 920 1605 917 1605 916 270 919 270 920 270 916 1606 821 1606 922 1606 955 1607 973 1607 975 1607 954 1608 973 1608 955 1608 953 672 952 672 972 672 952 1609 974 1609 972 1609 666 1610 979 1610 664 1610 663 1611 666 1611 664 1611 980 182 687 182 686 182 981 1612 690 1612 692 1612 703 1613 982 1613 692 1613 704 1614 664 1614 979 1614 704 1615 983 1615 705 1615 690 1616 981 1616 984 1616 984 1617 985 1617 690 1617 799 683 942 683 800 683 783 182 953 182 784 182 815 583 943 583 816 583 821 684 819 684 945 684 819 1618 820 1618 946 1618 946 1619 820 1619 816 1619 825 1620 773 1620 948 1620 826 1621 825 1621 949 1621 827 1622 826 1622 950 1622 799 1623 827 1623 942 1623 951 1624 909 1624 800 1624 910 1625 909 1625 951 1625 912 693 910 693 952 693 783 1626 912 1626 953 1626 955 695 835 695 784 695 836 696 835 696 955 696 837 1627 836 1627 956 1627 815 1628 837 1628 943 1628 916 270 773 270 772 270 772 1629 821 1629 916 1629 986 1630 987 1630 988 1630 692 1631 989 1631 990 1631 981 1632 692 1632 990 1632 991 1633 992 1633 993 1633 991 1634 994 1634 992 1634 995 1635 996 1635 997 1635 997 1636 996 1636 998 1636 998 1637 996 1637 999 1637 999 1638 996 1638 1000 1638 1000 1639 996 1639 1001 1639 1001 1640 996 1640 1002 1640 999 1641 1003 1641 998 1641 1004 1642 1005 1642 1003 1642 1003 1643 1005 1643 1006 1643 992 1644 1006 1644 1005 1644 1007 1645 1006 1645 992 1645 1008 1646 1007 1646 992 1646 1007 1647 1009 1647 1006 1647 998 1648 1003 1648 1006 1648 998 1649 1006 1649 1009 1649 1010 1650 1011 1650 1012 1650 1001 1651 1011 1651 1010 1651 992 1652 994 1652 1008 1652 980 1653 669 1653 687 1653 1013 1654 669 1654 980 1654 1014 1655 1013 1655 980 1655 1015 1656 1014 1656 980 1656 980 1657 1002 1657 1015 1657 996 1658 1015 1658 1002 1658 1011 1659 1001 1659 1002 1659 1016 1660 1017 1660 1018 1660 988 1661 1017 1661 1016 1661 1016 1662 1019 1662 988 1662 1020 1663 988 1663 1019 1663 1019 1664 1021 1664 1020 1664 1021 1665 990 1665 1020 1665 1021 1666 1022 1666 990 1666 981 1667 990 1667 1022 1667 1023 1668 981 1668 1022 1668 1024 1669 1025 1669 1026 1669 1025 1670 1027 1670 1026 1670 1028 1671 1024 1671 1026 1671 1026 1672 1029 1672 1028 1672 1030 1673 1028 1673 1029 1673 1029 1674 1031 1674 1030 1674 1032 1675 1030 1675 1031 1675 1031 1676 1033 1676 1032 1676 1034 1677 1032 1677 1033 1677 1033 1678 1035 1678 1034 1678 1036 1679 1034 1679 1035 1679 1035 1680 1018 1680 1036 1680 1036 1681 1018 1681 1017 1681 984 1682 981 1682 1023 1682 1037 1683 1038 1683 1039 1683 1038 1684 1037 1684 1040 1684 1041 1685 1042 1685 1038 1685 1043 1686 1044 1686 1045 1686 1046 1687 1045 1687 1044 1687 1046 1688 993 1688 1045 1688 1046 1689 1047 1689 993 1689 1046 1690 1048 1690 1047 1690 1046 1691 1049 1691 1048 1691 1050 1692 1049 1692 1046 1692 1051 1693 1046 1693 1052 1693 1046 1694 1044 1694 1052 1694 1046 1695 1051 1695 1050 1695 1051 1696 1053 1696 1050 1696 1052 1697 1054 1697 1051 1697 1055 1698 1053 1698 1051 1698 1051 1699 1038 1699 1055 1699 1038 1700 1056 1700 1055 1700 1038 1701 1042 1701 1056 1701 1051 1702 1039 1702 1038 1702 1051 1703 1054 1703 1039 1703 1045 1704 1004 1704 1043 1704 1005 1705 1004 1705 1045 1705 992 1706 1005 1706 1045 1706 1045 1707 993 1707 992 1707 993 1708 1047 1708 1057 1708 1057 1709 991 1709 993 1709 1058 1710 995 1710 997 1710 1059 1711 997 1711 998 1711 997 1712 1059 1712 1058 1712 998 1713 1009 1713 1059 1713 1060 1714 1058 1714 1059 1714 1059 1715 1061 1715 1060 1715 983 1716 1062 1716 705 1716 983 1717 704 1717 979 1717 983 1718 995 1718 1058 1718 983 1719 1063 1719 995 1719 983 1720 979 1720 1063 1720 983 1721 1058 1721 1062 1721 1058 1722 1060 1722 1062 1722 1064 1723 1065 1723 1066 1723 1067 1724 1066 1724 1065 1724 1067 1725 1007 1725 1008 1725 1067 1726 1065 1726 1007 1726 1008 1727 1068 1727 1067 1727 1008 1728 1069 1728 1068 1728 1008 1729 1070 1729 1069 1729 1071 1730 1070 1730 994 1730 1070 1731 1008 1731 994 1731 994 1732 991 1732 1071 1732 1072 1733 1071 1733 991 1733 991 1734 1057 1734 1072 1734 1047 1735 1072 1735 1057 1735 1004 1736 1003 1736 1000 1736 999 1737 1000 1737 1003 1737 1073 1738 1074 1738 1039 1738 1039 1739 1054 1739 1073 1739 1054 1740 1010 1740 1012 1740 1001 1741 1010 1741 1044 1741 1010 1742 1052 1742 1044 1742 1010 1743 1054 1743 1052 1743 1001 1744 1044 1744 1000 1744 1044 1745 1043 1745 1000 1745 1004 1746 1000 1746 1043 1746 1075 270 1033 270 1031 270 1075 1747 1035 1747 1033 1747 1018 270 1035 270 1075 270 1075 1748 1016 1748 1018 1748 1075 1749 1019 1749 1016 1749 1075 1750 1021 1750 1019 1750 1075 1751 1022 1751 1021 1751 1075 1752 1023 1752 1022 1752 1037 1753 1039 1753 1074 1753 988 1754 987 1754 1017 1754 989 1755 988 1755 1020 1755 1020 1756 990 1756 989 1756 988 1757 989 1757 986 1757 989 1758 1076 1758 986 1758 1077 1759 1076 1759 989 1759 1077 1760 989 1760 692 1760 982 1761 1077 1761 692 1761 1065 1762 1061 1762 1007 1762 1060 1763 1061 1763 1065 1763 1065 1764 1064 1764 1060 1764 1002 1765 980 1765 686 1765 995 1766 1015 1766 996 1766 1015 1767 995 1767 1063 1767 1015 1768 1063 1768 1014 1768 1063 1769 1013 1769 1014 1769 666 1770 1013 1770 1063 1770 1013 1771 666 1771 669 1771 666 1772 1063 1772 979 1772 1017 1773 987 1773 1036 1773 1069 1774 1070 1774 1078 1774 987 1775 1078 1775 1070 1775 1070 1776 1071 1776 987 1776 1071 1777 1036 1777 987 1777 1034 1778 1036 1778 1047 1778 1036 1779 1072 1779 1047 1779 1036 1780 1071 1780 1072 1780 1047 1781 1048 1781 1034 1781 1032 1782 1034 1782 1048 1782 1048 1783 1049 1783 1032 1783 1030 1784 1032 1784 1050 1784 1032 1785 1049 1785 1050 1785 1050 1786 1053 1786 1030 1786 1028 1787 1030 1787 1053 1787 1053 1788 1055 1788 1028 1788 1024 1789 1028 1789 1056 1789 1028 1790 1055 1790 1056 1790 1056 1791 1042 1791 1024 1791 1025 1792 1024 1792 1042 1792 1079 1793 1002 1793 686 1793 1002 1794 1079 1794 1011 1794 638 1795 637 1795 564 1795 637 1796 1080 1796 565 1796 1081 1797 616 1797 1082 1797 617 1798 616 1798 1081 1798 1081 1799 1083 1799 617 1799 1083 1800 636 1800 617 1800 701 1801 1082 1801 616 1801 701 1802 1084 1802 1082 1802 577 270 635 270 1075 270 1075 1803 1081 1803 1082 1803 1075 1804 1083 1804 1081 1804 1075 1805 636 1805 1083 1805 1075 1806 634 1806 636 1806 1075 1807 635 1807 634 1807 1082 878 1084 878 1075 878 1084 1808 1085 1808 1075 1808 721 1809 1075 1809 1085 1809 1011 1810 642 1810 650 1810 1011 1811 641 1811 642 1811 1011 1812 640 1812 641 1812 1011 1813 639 1813 640 1813 1011 1814 638 1814 639 1814 1011 1815 637 1815 638 1815 1011 1816 1080 1816 637 1816 1011 1817 723 1817 1080 1817 1086 1818 1087 1818 589 1818 601 1819 1086 1819 589 1819 1088 891 1089 891 1087 891 1086 1820 1088 1820 1087 1820 1090 1821 1089 1821 1088 1821 1091 1822 1092 1822 1090 1822 1088 1823 1091 1823 1090 1823 1091 1824 1093 1824 1092 1824 1011 1825 650 1825 649 1825 1011 1826 649 1826 648 1826 1094 1827 1095 1827 1096 1827 1096 1828 1097 1828 1094 1828 1094 1829 1097 1829 1040 1829 1098 1830 1094 1830 1040 1830 1099 1831 599 1831 600 1831 1100 1832 600 1832 591 1832 1101 1833 1095 1833 1100 1833 591 1834 1101 1834 1100 1834 1101 1835 1096 1835 1095 1835 1102 1836 1089 1836 1090 1836 1103 1837 1102 1837 1090 1837 1103 909 1097 909 1096 909 1103 1838 1096 1838 1102 1838 1090 1839 1092 1839 1103 1839 1103 1840 1092 1840 1104 1840 1103 1841 1041 1841 1097 1841 1102 1842 1101 1842 591 1842 590 1843 1102 1843 591 1843 590 1844 589 1844 1087 1844 590 1845 1087 1845 1089 1845 590 1846 1089 1846 1102 1846 1101 1847 1102 1847 1096 1847 1093 1848 1091 1848 1105 1848 1088 1849 1086 1849 1106 1849 1107 1850 1106 1850 1086 1850 1086 1851 601 1851 1107 1851 1108 1852 1107 1852 601 1852 601 1853 581 1853 1108 1853 580 1854 1108 1854 581 1854 648 1855 599 1855 1011 1855 1011 1856 599 1856 1099 1856 1091 1857 1109 1857 1105 1857 1088 1858 1109 1858 1091 1858 1088 1859 1106 1859 1109 1859 600 1860 1011 1860 1099 1860 1075 1861 580 1861 578 1861 1075 1862 578 1862 577 1862 694 1863 690 1863 985 1863 985 935 721 935 694 935 721 1864 1085 1864 698 1864 701 1865 698 1865 1085 1865 1085 1866 1084 1866 701 1866 1080 1867 723 1867 675 1867 675 1868 565 1868 1080 1868 1105 1869 1110 1869 1093 1869 1025 1870 1093 1870 1110 1870 1027 1871 1025 1871 1110 1871 1041 1872 1038 1872 1040 1872 1041 1873 1111 1873 1042 1873 1041 1874 1104 1874 1111 1874 1041 1875 1040 1875 1097 1875 1041 1876 1103 1876 1104 1876 984 270 1023 270 1075 270 985 270 984 270 1075 270 1075 1877 721 1877 985 1877 1074 950 1112 950 1037 950 1040 1878 1037 1878 1112 1878 1112 1879 1098 1879 1040 1879 1111 1880 1025 1880 1042 1880 1093 1881 1025 1881 1104 1881 1025 1882 1111 1882 1104 1882 1093 1883 1104 1883 1092 1883 1079 1884 686 1884 722 1884 1079 1885 722 1885 723 1885 1079 1886 723 1886 1011 1886 1113 1887 1114 1887 1115 1887 1116 1888 1117 1888 1118 1888 1118 1889 1114 1889 1113 1889 1113 1890 1115 1890 1119 1890 1120 1891 1121 1891 1122 1891 1123 1892 1122 1892 1121 1892 1124 1893 1123 1893 1125 1893 1123 1894 1121 1894 1125 1894 1126 1895 1124 1895 1127 1895 1124 1896 1125 1896 1127 1896 1128 1897 1126 1897 1129 1897 1126 1898 1127 1898 1129 1898 1130 1899 1128 1899 1129 1899 1130 1900 1131 1900 1128 1900 1132 1901 1128 1901 1131 1901 1133 1902 1134 1902 1135 1902 1133 1903 1136 1903 1134 1903 1136 1904 1137 1904 1134 1904 1136 1905 1138 1905 1137 1905 1138 1906 1139 1906 1137 1906 1138 1907 1140 1907 1139 1907 1139 1908 1140 1908 1141 1908 1142 1909 1141 1909 1143 1909 1141 1910 1140 1910 1143 1910 1122 1911 1144 1911 1120 1911 1145 1912 1133 1912 1135 1912 1146 1913 1147 1913 1148 1913 1147 1914 1149 1914 1148 1914 1149 1915 1131 1915 1148 1915 1149 1916 1150 1916 1131 1916 1150 1917 1151 1917 1131 1917 1151 1918 1152 1918 1131 1918 1132 1919 1131 1919 1152 1919 1153 1920 1154 1920 1155 1920 1156 1921 1154 1921 1153 1921 1153 1922 1157 1922 1156 1922 1153 1923 1158 1923 1157 1923 1153 1924 1159 1924 1158 1924 1153 1925 1160 1925 1159 1925 1153 1926 1143 1926 1160 1926 1142 1927 1143 1927 1161 1927 1143 1927 1162 1927 1161 1927 1143 1927 1153 1927 1162 1927 1146 1928 1163 1928 1147 1928 1163 1929 1164 1929 1147 1929 1165 1930 1164 1930 1163 1930 1163 1931 1166 1931 1165 1931 1167 1932 1165 1932 1166 1932 1166 1933 1168 1933 1167 1933 1168 1934 1169 1934 1170 1934 1171 1935 1172 1935 1169 1935 1169 1936 1173 1936 1171 1936 1173 1937 1174 1937 1171 1937 1175 1938 1174 1938 1173 1938 1173 1939 1176 1939 1175 1939 1176 1940 1177 1940 1175 1940 1176 1941 1178 1941 1177 1941 1179 1942 1178 1942 1176 1942 1155 1943 1180 1943 1153 1943 1181 1944 1153 1944 1180 1944 1180 1945 1182 1945 1181 1945 1116 1946 1181 1946 1182 1946 1182 1947 1117 1947 1116 1947 1113 1948 1116 1948 1118 1948 1183 1949 1113 1949 1119 1949 1119 1950 1184 1950 1183 1950 1185 1951 1183 1951 1186 1951 1183 1952 1184 1952 1186 1952 1186 1953 1187 1953 1185 1953 1188 1954 1185 1954 1189 1954 1185 1955 1190 1955 1189 1955 1185 1956 1191 1956 1190 1956 1185 1957 1187 1957 1191 1957 1192 1958 1188 1958 1189 1958 1188 1959 1193 1959 1194 1959 1188 1960 1192 1960 1193 1960 1169 1961 1172 1961 1170 1961 1170 1962 1195 1962 1168 1962 1168 1963 1195 1963 1167 1963 1196 1964 982 1964 703 1964 1196 1965 703 1965 702 1965 1196 1966 702 1966 691 1966 1197 1967 1196 1967 691 1967 982 1968 1196 1968 1077 1968 1196 1969 1198 1969 1077 1969 305 1970 302 1970 1199 1970 302 1971 1200 1971 1199 1971 304 1972 305 1972 1201 1972 305 1973 1199 1973 1201 1973 306 1974 304 1974 1202 1974 304 1975 1201 1975 1202 1975 1203 1976 306 1976 1202 1976 1204 1977 306 1977 1203 1977 1203 1978 1205 1978 1204 1978 292 1979 1204 1979 1205 1979 307 1980 1206 1980 1207 1980 1207 1981 1206 1981 1208 1981 307 1982 332 1982 1206 1982 332 1983 1209 1983 1206 1983 332 1984 333 1984 1209 1984 333 1985 1210 1985 1209 1985 333 1986 1211 1986 1210 1986 333 1987 334 1987 1211 1987 1211 1988 334 1988 1212 1988 1213 1989 1212 1989 287 1989 1212 1990 334 1990 287 1990 302 182 321 182 1200 182 1200 1991 321 1991 1214 1991 321 1992 318 1992 1214 1992 318 1993 317 1993 1214 1993 317 1994 312 1994 1214 1994 312 1995 308 1995 1214 1995 1208 1996 1214 1996 1207 1996 1214 1997 308 1997 1207 1997 308 1998 307 1998 1207 1998 1215 1999 54 1999 1216 1999 54 2000 4 2000 1216 2000 4 2001 1217 2001 1216 2001 4 2002 5 2002 1217 2002 5 2003 1205 2003 1217 2003 5 2004 164 2004 1205 2004 164 2005 159 2005 1205 2005 159 2006 163 2006 1205 2006 292 2007 1205 2007 163 2007 508 2008 1218 2008 505 2008 1218 2009 506 2009 505 2009 1218 2010 151 2010 506 2010 1218 2011 152 2011 151 2011 1218 2012 154 2012 152 2012 1218 2013 155 2013 154 2013 1218 2014 287 2014 155 2014 287 2015 1218 2015 1213 2015 1215 2016 1219 2016 54 2016 1219 2017 88 2017 54 2017 73 2018 88 2018 1219 2018 1219 2019 1220 2019 73 2019 74 2020 73 2020 1220 2020 1220 2021 1221 2021 74 2021 1221 2022 47 2022 74 2022 48 2023 47 2023 1221 2023 1221 2024 1222 2024 48 2024 1222 2025 67 2025 48 2025 64 2026 67 2026 1222 2026 1222 2027 1223 2027 64 2027 1223 2028 60 2028 64 2028 6 2029 60 2029 1223 2029 1223 2030 1224 2030 6 2030 1224 2031 7 2031 6 2031 1224 2032 134 2032 7 2032 135 2033 134 2033 1224 2033 508 2034 510 2034 1218 2034 1225 2035 1218 2035 510 2035 510 2036 511 2036 1225 2036 1226 2037 1225 2037 511 2037 511 2038 512 2038 1226 2038 1227 2039 1226 2039 513 2039 1226 2040 512 2040 513 2040 513 2041 522 2041 1227 2041 1228 2042 1227 2042 430 2042 1227 2043 431 2043 430 2043 1227 2044 522 2044 431 2044 430 2045 520 2045 1228 2045 1229 2046 1228 2046 521 2046 1228 2047 520 2047 521 2047 521 2048 426 2048 1229 2048 1230 2049 1229 2049 137 2049 1229 2050 148 2050 137 2050 1229 2051 149 2051 148 2051 1229 2052 426 2052 149 2052 139 2053 1230 2053 137 2053 1224 2054 1230 2054 146 2054 146 2055 135 2055 1224 2055 1230 2056 145 2056 146 2056 1230 2057 143 2057 145 2057 1230 2058 141 2058 143 2058 1230 2059 139 2059 141 2059 1231 1891 1232 1891 857 1891 859 2060 857 2060 1232 2060 861 2061 859 2061 1233 2061 859 2062 1232 2062 1233 2062 860 2063 861 2063 1234 2063 861 2064 1233 2064 1234 2064 862 2065 860 2065 1235 2065 860 2066 1234 2066 1235 2066 1236 2067 862 2067 1235 2067 1237 2068 862 2068 1236 2068 1236 2069 1238 2069 1237 2069 847 2070 1237 2070 1238 2070 863 2071 1239 2071 1240 2071 863 2072 888 2072 1239 2072 888 2073 1241 2073 1239 2073 888 2074 889 2074 1241 2074 889 2075 1242 2075 1241 2075 889 2076 1243 2076 1242 2076 889 2077 890 2077 1243 2077 1243 2078 890 2078 1244 2078 1245 2079 1244 2079 842 2079 1244 2080 890 2080 842 2080 857 2081 877 2081 1231 2081 1231 2082 877 2082 1246 2082 877 2083 874 2083 1246 2083 874 182 873 182 1246 182 873 182 868 182 1246 182 868 182 864 182 1246 182 1246 2084 864 2084 1240 2084 864 2085 863 2085 1240 2085 1247 2086 609 2086 1248 2086 609 2087 560 2087 1248 2087 560 2088 1238 2088 1248 2088 560 2089 719 2089 1238 2089 719 2090 714 2090 1238 2090 714 2091 718 2091 1238 2091 847 2092 1238 2092 718 2092 1064 2093 1249 2093 1060 2093 1249 2094 1062 2094 1060 2094 1249 2095 705 2095 1062 2095 1249 2096 706 2096 705 2096 1249 2097 708 2097 706 2097 1249 2098 709 2098 708 2098 1249 2099 842 2099 709 2099 842 2100 1249 2100 1245 2100 1247 2101 1250 2101 609 2101 1250 2102 643 2102 609 2102 628 2103 643 2103 1250 2103 1250 2104 1251 2104 628 2104 629 2105 628 2105 1251 2105 1251 2106 1252 2106 629 2106 1252 2107 602 2107 629 2107 603 2108 602 2108 1252 2108 1252 2109 1253 2109 603 2109 1253 2110 622 2110 603 2110 619 2111 622 2111 1253 2111 1253 2112 1254 2112 619 2112 1254 2113 615 2113 619 2113 561 2114 615 2114 1254 2114 1254 2115 1255 2115 561 2115 1255 2116 562 2116 561 2116 1255 2117 688 2117 562 2117 689 2118 688 2118 1255 2118 1064 2119 1066 2119 1249 2119 1256 2120 1249 2120 1066 2120 1066 2121 1067 2121 1256 2121 1257 2122 1256 2122 1067 2122 1067 2123 1068 2123 1257 2123 1258 2124 1257 2124 1069 2124 1257 2125 1068 2125 1069 2125 1069 2126 1078 2126 1258 2126 1198 2127 1258 2127 986 2127 1258 2128 987 2128 986 2128 1258 2129 1078 2129 987 2129 986 2130 1076 2130 1198 2130 1198 2131 1076 2131 1077 2131 693 2132 1197 2132 691 2132 1255 2133 1197 2133 700 2133 700 2134 689 2134 1255 2134 1197 2135 699 2135 700 2135 1197 2136 697 2136 699 2136 1197 2137 695 2137 697 2137 1197 2138 693 2138 695 2138 1259 2139 1196 2139 1197 2139 1260 2140 1196 2140 1259 2140 1261 2141 1196 2141 1260 2141 1198 2142 1196 2142 1261 2142 1238 64 1262 64 1248 64 1263 64 1248 64 1262 64 1249 2143 1264 2143 1245 2143 1265 2144 1245 2144 1264 2144 1266 2145 1260 2145 1259 2145 1266 2146 1259 2146 1267 2146 1268 2147 1269 2147 1270 2147 1271 2148 1269 2148 1268 2148 1272 2149 1269 2149 1271 2149 1273 2150 1269 2150 1272 2150 1246 2151 1271 2151 1274 2151 1275 2152 1246 2152 1274 2152 1208 2153 1206 2153 1276 2153 1240 2154 1239 2154 1273 2154 1239 2155 1269 2155 1273 2155 1239 2156 1241 2156 1269 2156 1270 2157 1269 2157 1241 2157 1241 2158 1242 2158 1270 2158 1242 2159 1243 2159 1270 2159 1243 2160 1244 2160 1270 2160 1244 2161 1277 2161 1270 2161 1265 2162 1277 2162 1245 2162 1277 2163 1244 2163 1245 2163 1199 2164 1278 2164 1201 2164 1278 2165 1202 2165 1201 2165 1199 2166 1279 2166 1278 2166 1199 2167 1200 2167 1279 2167 1280 2168 1202 2168 1278 2168 1202 2169 1280 2169 1203 2169 1280 2170 1205 2170 1203 2170 1280 2171 1281 2171 1205 2171 1282 2172 1280 2172 1278 2172 1280 2173 1282 2173 1281 2173 1282 2174 1283 2174 1281 2174 1284 2175 1283 2175 1282 2175 1278 2176 1285 2176 1286 2176 1278 2177 1279 2177 1285 2177 1278 2178 1286 2178 1282 2178 1282 2179 1287 2179 1284 2179 1287 2180 1288 2180 1284 2180 1287 2181 1282 2181 1286 2181 1285 2182 1289 2182 1286 2182 1286 2183 1290 2183 1287 2183 1290 2184 1286 2184 1291 2184 1286 2185 1292 2185 1291 2185 1286 2186 1289 2186 1292 2186 1293 2187 1288 2187 1287 2187 1287 2188 1294 2188 1293 2188 1294 2189 1287 2189 1290 2189 1295 2190 1293 2190 1294 2190 1291 2191 1296 2191 1290 2191 1297 2192 1290 2192 1298 2192 1290 2193 1296 2193 1298 2193 1290 2194 1297 2194 1294 2194 1299 2195 1294 2195 1297 2195 1294 2196 1299 2196 1295 2196 1299 2197 1300 2197 1295 2197 1301 2198 1300 2198 1299 2198 1298 2199 1302 2199 1297 2199 1303 2200 1297 2200 1304 2200 1297 2201 1302 2201 1304 2201 1297 2202 1303 2202 1299 2202 1305 2203 1299 2203 1303 2203 1299 2204 1305 2204 1301 2204 1305 2205 1306 2205 1301 2205 1304 2206 1307 2206 1303 2206 1303 2207 1308 2207 1268 2207 1303 2208 1307 2208 1308 2208 1303 2209 1268 2209 1305 2209 1309 2210 1306 2210 1305 2210 1305 2211 1268 2211 1270 2211 1305 2212 1270 2212 1309 2212 1308 2213 1271 2213 1268 2213 1265 2214 1309 2214 1277 2214 1309 2215 1270 2215 1277 2215 1275 2216 1232 2216 1231 2216 1233 2217 1232 2217 1310 2217 1234 2218 1233 2218 1311 2218 1233 2219 1310 2219 1311 2219 1235 2220 1234 2220 1311 2220 1236 2221 1235 2221 1312 2221 1235 2222 1311 2222 1312 2222 1312 2223 1262 2223 1236 2223 1238 2224 1236 2224 1262 2224 1313 2225 1311 2225 1310 2225 1311 2226 1313 2226 1312 2226 1313 2227 1262 2227 1312 2227 1313 2228 1314 2228 1262 2228 1275 2229 1274 2229 1232 2229 1274 2230 1310 2230 1232 2230 1310 2231 1315 2231 1313 2231 1315 2232 1310 2232 1316 2232 1310 2233 1274 2233 1316 2233 1317 2234 1314 2234 1313 2234 1316 2235 1318 2235 1315 2235 1319 2236 1313 2236 1320 2236 1313 2237 1315 2237 1320 2237 1313 2238 1319 2238 1317 2238 1319 2239 1321 2239 1317 2239 1319 2240 1322 2240 1321 2240 1320 2241 1315 2241 1323 2241 1315 2242 1318 2242 1323 2242 1323 2243 1324 2243 1320 2243 1320 2244 1325 2244 1319 2244 1325 2245 1320 2245 1326 2245 1320 2246 1324 2246 1326 2246 1327 2247 1322 2247 1319 2247 1328 2248 1319 2248 1325 2248 1319 2249 1328 2249 1327 2249 1328 2250 1329 2250 1327 2250 1326 2251 1330 2251 1325 2251 1325 2252 1330 2252 1331 2252 1331 182 1292 182 1332 182 1291 182 1292 182 1330 182 1292 2253 1331 2253 1330 2253 1330 182 1326 182 1291 182 1296 2254 1291 2254 1326 2254 1326 182 1324 182 1296 182 1298 182 1296 182 1324 182 1279 2255 1333 2255 1285 2255 1324 2256 1323 2256 1298 2256 1302 182 1298 182 1323 182 1323 182 1318 182 1302 182 1318 2257 1304 2257 1302 2257 1333 2258 1279 2258 1214 2258 1307 182 1304 182 1318 182 1318 182 1316 182 1307 182 1308 182 1307 182 1316 182 1316 2259 1274 2259 1308 2259 1271 2260 1308 2260 1274 2260 1279 2261 1200 2261 1214 2261 1208 2262 1276 2262 1214 2262 1272 2263 1271 2263 1246 2263 1273 2264 1272 2264 1246 2264 1275 2265 1231 2265 1246 2265 1240 2266 1273 2266 1246 2266 1334 2267 1260 2267 1335 2267 1260 2268 1266 2268 1335 2268 1260 2269 1334 2269 1261 2269 1334 2270 1336 2270 1261 2270 1334 2271 1337 2271 1336 2271 1338 2272 1337 2272 1334 2272 1338 2273 1339 2273 1337 2273 1338 2274 1264 2274 1339 2274 1338 2275 1340 2275 1264 2275 1335 2276 1341 2276 1334 2276 1334 2277 1342 2277 1338 2277 1342 2278 1334 2278 1343 2278 1334 2279 1344 2279 1343 2279 1334 2280 1341 2280 1344 2280 1345 2281 1338 2281 1342 2281 1338 2282 1345 2282 1340 2282 1345 2283 1346 2283 1340 2283 1343 2284 1347 2284 1342 2284 1348 2285 1342 2285 1349 2285 1342 2286 1347 2286 1349 2286 1342 2287 1348 2287 1345 2287 1350 2288 1345 2288 1348 2288 1345 2289 1350 2289 1346 2289 1350 2290 1351 2290 1346 2290 1349 2291 1352 2291 1348 2291 1353 2292 1351 2292 1350 2292 1354 2293 1348 2293 1355 2293 1348 2294 1356 2294 1355 2294 1352 2295 1356 2295 1348 2295 1348 2296 1354 2296 1350 2296 1350 2297 1357 2297 1353 2297 1357 2298 1350 2298 1354 2298 1358 2299 1353 2299 1357 2299 1355 2300 1359 2300 1354 2300 1360 2301 1354 2301 1361 2301 1354 2302 1359 2302 1361 2302 1354 2303 1360 2303 1357 2303 1362 2304 1357 2304 1360 2304 1357 2305 1362 2305 1358 2305 1362 2306 1363 2306 1358 2306 1361 2307 1364 2307 1360 2307 1365 2308 1360 2308 1366 2308 1360 2309 1364 2309 1366 2309 1360 2310 1365 2310 1362 2310 1362 2311 1367 2311 1363 2311 1367 2312 1368 2312 1363 2312 1367 2313 1362 2313 1365 2313 1365 2314 1222 2314 1367 2314 1365 2315 1223 2315 1222 2315 1365 2316 1224 2316 1223 2316 1365 2317 1369 2317 1224 2317 1365 2318 1370 2318 1369 2318 1365 2319 1366 2319 1370 2319 1219 2320 1367 2320 1220 2320 1367 2321 1221 2321 1220 2321 1367 2322 1222 2322 1221 2322 1367 2323 1219 2323 1368 2323 1368 2324 1219 2324 1215 2324 1267 2325 1259 2325 1197 2325 1261 2326 1336 2326 1198 2326 1336 2327 1258 2327 1198 2327 1257 2328 1258 2328 1336 2328 1336 2329 1337 2329 1257 2329 1256 2330 1257 2330 1339 2330 1257 2331 1337 2331 1339 2331 1339 2332 1264 2332 1256 2332 1249 2333 1256 2333 1264 2333 1255 2334 1371 2334 1372 2334 1255 2335 1254 2335 1371 2335 1254 2336 1373 2336 1371 2336 1254 2337 1253 2337 1373 2337 1253 2338 1374 2338 1373 2338 1375 2339 1374 2339 1252 2339 1374 2340 1253 2340 1252 2340 1252 2341 1251 2341 1375 2341 1376 2342 1375 2342 1251 2342 1251 2343 1250 2343 1376 2343 1377 2344 1376 2344 1247 2344 1376 2345 1250 2345 1247 2345 1378 2346 1379 2346 1380 2346 1379 2347 1381 2347 1380 2347 1382 2348 1383 2348 1384 2348 1383 2349 1382 2349 1378 2349 1385 2350 1384 2350 1383 2350 1380 2351 1386 2351 1378 2351 1378 2352 1387 2352 1383 2352 1387 2353 1378 2353 1388 2353 1378 2354 1386 2354 1388 2354 1389 2355 1383 2355 1387 2355 1383 2356 1389 2356 1385 2356 1389 2357 1390 2357 1385 2357 1388 2358 1391 2358 1387 2358 1392 2359 1387 2359 1393 2359 1387 2360 1394 2360 1393 2360 1387 2361 1391 2361 1394 2361 1387 2362 1392 2362 1389 2362 1395 2363 1389 2363 1392 2363 1389 2364 1395 2364 1390 2364 1395 2365 1396 2365 1390 2365 1393 2366 1397 2366 1392 2366 1392 2367 1373 2367 1395 2367 1392 2368 1371 2368 1373 2368 1392 2369 1372 2369 1371 2369 1392 2370 1398 2370 1372 2370 1392 2371 1397 2371 1398 2371 1376 2372 1395 2372 1375 2372 1395 2373 1374 2373 1375 2373 1395 2374 1373 2374 1374 2374 1395 2375 1376 2375 1396 2375 1376 2376 1377 2376 1396 2376 1309 2377 1265 2377 1264 2377 1264 2378 1340 2378 1309 2378 1306 2379 1309 2379 1340 2379 1301 2380 1306 2380 1346 2380 1306 2381 1340 2381 1346 2381 1300 2382 1301 2382 1346 2382 1346 2383 1351 2383 1300 2383 1295 2384 1300 2384 1351 2384 1351 2385 1353 2385 1295 2385 1293 2386 1295 2386 1353 2386 1288 2387 1293 2387 1353 2387 1353 2388 1358 2388 1288 2388 1284 2389 1288 2389 1358 2389 1358 2390 1363 2390 1284 2390 1283 2391 1284 2391 1363 2391 1281 2392 1283 2392 1368 2392 1283 2393 1363 2393 1368 2393 1205 2394 1281 2394 1217 2394 1281 2395 1216 2395 1217 2395 1281 2396 1368 2396 1216 2396 1327 2397 1329 2397 1384 2397 1384 2398 1385 2398 1327 2398 1322 2399 1327 2399 1385 2399 1385 2400 1390 2400 1322 2400 1321 2401 1322 2401 1390 2401 1317 2402 1321 2402 1396 2402 1321 2403 1390 2403 1396 2403 1314 2404 1317 2404 1396 2404 1396 2405 1377 2405 1314 2405 1314 2406 1263 2406 1262 2406 1314 2407 1377 2407 1263 2407 1368 2408 1215 2408 1216 2408 1377 2409 1247 2409 1263 2409 1248 64 1263 64 1247 64 1255 270 1372 270 1197 270 1267 270 1197 270 1372 270 1224 270 1369 270 1230 270 1230 2410 1370 2410 1366 2410 1230 2411 1369 2411 1370 2411 1120 2412 1144 2412 1399 2412 1144 2413 1400 2413 1399 2413 1400 2414 1401 2414 1399 2414 1401 2415 1402 2415 1399 2415 1402 2416 1145 2416 1399 2416 1399 2417 1145 2417 1135 2417 1131 2418 1403 2418 1148 2418 1120 2419 1404 2419 1121 2419 1405 2420 1121 2420 1404 2420 1325 2421 1406 2421 1328 2421 1406 2422 1325 2422 1407 2422 1325 2423 1331 2423 1407 2423 1408 2424 1329 2424 1328 2424 1409 2425 1328 2425 1406 2425 1328 2426 1409 2426 1408 2426 1407 2427 1410 2427 1406 2427 1411 2428 1408 2428 1409 2428 1406 2429 1412 2429 1409 2429 1412 2430 1406 2430 1413 2430 1406 2431 1414 2431 1413 2431 1406 2432 1410 2432 1414 2432 1415 2433 1409 2433 1412 2433 1409 2434 1415 2434 1411 2434 1415 2435 1416 2435 1411 2435 1415 2436 1417 2436 1416 2436 1418 2437 1417 2437 1415 2437 1415 2438 1137 2438 1139 2438 1415 2439 1412 2439 1137 2439 1415 2440 1139 2440 1418 2440 1142 2441 1418 2441 1141 2441 1418 2442 1139 2442 1141 2442 1137 2443 1412 2443 1134 2443 1412 2444 1413 2444 1134 2444 1413 2445 1135 2445 1134 2445 1405 2446 1125 2446 1121 2446 1405 2447 1419 2447 1125 2447 1127 2448 1125 2448 1419 2448 1419 2449 1420 2449 1127 2449 1420 2450 1129 2450 1127 2450 1129 2451 1420 2451 1130 2451 1131 2452 1130 2452 1421 2452 1130 2453 1420 2453 1421 2453 1131 2454 1421 2454 1422 2454 1332 2455 1404 2455 1331 2455 1404 2456 1407 2456 1331 2456 1410 2457 1407 2457 1404 2457 1414 2458 1410 2458 1404 2458 1413 2459 1414 2459 1399 2459 1414 2460 1404 2460 1399 2460 1404 2461 1120 2461 1399 2461 1399 2462 1135 2462 1413 2462 1423 2463 1185 2463 1188 2463 1185 2464 1424 2464 1183 2464 1424 2465 1113 2465 1183 2465 1424 2466 1116 2466 1113 2466 1424 2467 1185 2467 1425 2467 1185 2468 1426 2468 1425 2468 1185 2469 1427 2469 1426 2469 1185 2470 1423 2470 1427 2470 1181 2471 1116 2471 1428 2471 1428 2472 1153 2472 1181 2472 1428 2473 1429 2473 1153 2473 1428 2474 1116 2474 1424 2474 1430 2475 1429 2475 1428 2475 1424 2476 1431 2476 1428 2476 1431 2477 1424 2477 1432 2477 1424 2478 1425 2478 1432 2478 1433 2479 1428 2479 1431 2479 1428 2480 1433 2480 1430 2480 1434 2481 1430 2481 1433 2481 1432 2482 1435 2482 1431 2482 1379 2483 1431 2483 1436 2483 1431 2484 1435 2484 1436 2484 1431 2485 1379 2485 1433 2485 1433 2486 1382 2486 1434 2486 1382 2487 1437 2487 1434 2487 1382 2488 1433 2488 1379 2488 1436 2489 1438 2489 1379 2489 1384 2490 1437 2490 1382 2490 1379 2491 1378 2491 1382 2491 1438 2492 1381 2492 1379 2492 1153 2493 1429 2493 1162 2493 1429 2494 1161 2494 1162 2494 1429 2495 1142 2495 1161 2495 1418 2496 1142 2496 1429 2496 1417 2497 1418 2497 1429 2497 1429 2498 1430 2498 1417 2498 1416 2499 1417 2499 1430 2499 1430 2500 1434 2500 1416 2500 1411 2501 1416 2501 1434 2501 1434 2502 1437 2502 1411 2502 1408 2503 1411 2503 1437 2503 1437 2504 1384 2504 1408 2504 1329 2505 1408 2505 1384 2505 1425 2506 1426 2506 1432 2506 1439 2507 1440 2507 1441 2507 1442 2508 1443 2508 1439 2508 1443 2509 1440 2509 1439 2509 1444 2510 1445 2510 1446 2510 1444 2511 1447 2511 1445 2511 1447 2512 1448 2512 1445 2512 1447 2513 1449 2513 1448 2513 1447 2514 1450 2514 1449 2514 1447 2515 1451 2515 1450 2515 1447 2516 1452 2516 1451 2516 1447 2517 1453 2517 1452 2517 1454 2518 1455 2518 1456 2518 1457 2519 1458 2519 1455 2519 1459 2520 1440 2520 1443 2520 1443 2521 1460 2521 1459 2521 1461 2522 1459 2522 1460 2522 1460 2523 1462 2523 1461 2523 1463 2524 1461 2524 1462 2524 1462 2525 1464 2525 1463 2525 1465 2526 1463 2526 1464 2526 1464 2527 1466 2527 1465 2527 1467 2528 1465 2528 1466 2528 1466 2529 1468 2529 1467 2529 1468 2530 1469 2530 1470 2530 1440 2531 1459 2531 1441 2531 1471 2532 1441 2532 1461 2532 1441 2533 1459 2533 1461 2533 1449 2534 1450 2534 1472 2534 1472 2535 1473 2535 1449 2535 1473 2536 1448 2536 1449 2536 1445 2537 1448 2537 1473 2537 1473 2538 1474 2538 1445 2538 1475 2539 1445 2539 1474 2539 1474 2540 1476 2540 1475 2540 1476 2541 1477 2541 1475 2541 1478 2542 1477 2542 1476 2542 1476 2543 1479 2543 1478 2543 1480 2544 1478 2544 1481 2544 1478 2545 1482 2545 1481 2545 1478 2546 1483 2546 1482 2546 1478 2547 1484 2547 1483 2547 1478 2548 1479 2548 1484 2548 1479 2549 1485 2549 1486 2549 1486 2550 1484 2550 1479 2550 1485 2551 1487 2551 1486 2551 1488 2552 1487 2552 1485 2552 1489 2553 1490 2553 1488 2553 1445 2554 1475 2554 1446 2554 1491 2555 1446 2555 1475 2555 1491 2556 1492 2556 1446 2556 1475 2557 1477 2557 1491 2557 1493 2558 1492 2558 1491 2558 1494 2559 1491 2559 1478 2559 1491 2560 1477 2560 1478 2560 1491 2561 1494 2561 1493 2561 1495 2562 1493 2562 1494 2562 1478 2563 1480 2563 1494 2563 1494 2564 1496 2564 1497 2564 1494 2565 1480 2565 1496 2565 1494 2566 1497 2566 1495 2566 1497 2567 1498 2567 1495 2567 1499 2568 1498 2568 1500 2568 1498 2569 1497 2569 1500 2569 1501 2570 1502 2570 1442 2570 1503 2571 1442 2571 1502 2571 1504 2572 1443 2572 1442 2572 1504 2573 1442 2573 1503 2573 1502 2574 1505 2574 1503 2574 1460 2575 1443 2575 1504 2575 1506 2576 1503 2576 1507 2576 1503 2577 1505 2577 1507 2577 1503 2578 1506 2578 1504 2578 1504 2579 1508 2579 1460 2579 1508 2580 1462 2580 1460 2580 1508 2581 1504 2581 1506 2581 1507 2582 1509 2582 1506 2582 1464 2583 1462 2583 1508 2583 1506 2584 1510 2584 1508 2584 1510 2585 1506 2585 1511 2585 1506 2586 1509 2586 1511 2586 1508 2587 1512 2587 1464 2587 1512 2588 1466 2588 1464 2588 1512 2589 1508 2589 1510 2589 1511 2590 1513 2590 1510 2590 1468 2591 1466 2591 1512 2591 1514 2592 1510 2592 1513 2592 1510 2593 1514 2593 1512 2593 1512 2594 1515 2594 1468 2594 1515 2595 1512 2595 1514 2595 1513 2596 1516 2596 1514 2596 1469 2597 1468 2597 1515 2597 1517 2598 1514 2598 1518 2598 1514 2599 1516 2599 1518 2599 1514 2600 1517 2600 1515 2600 1519 2601 1515 2601 1517 2601 1515 2602 1519 2602 1469 2602 1519 2603 1520 2603 1469 2603 1521 2604 1520 2604 1519 2604 1522 2605 1523 2605 1490 2605 1488 2606 1490 2606 1523 2606 1523 2607 1524 2607 1488 2607 1487 2608 1488 2608 1525 2608 1488 2609 1526 2609 1525 2609 1488 2610 1524 2610 1526 2610 1525 2611 1527 2611 1487 2611 1527 2612 1486 2612 1487 2612 1484 2613 1486 2613 1527 2613 1527 2614 1528 2614 1484 2614 1483 2615 1484 2615 1528 2615 1528 2616 1529 2616 1483 2616 1482 2617 1483 2617 1529 2617 1529 2618 1530 2618 1482 2618 1481 2619 1482 2619 1530 2619 1530 2620 1531 2620 1481 2620 1480 2621 1481 2621 1531 2621 1531 2622 1532 2622 1480 2622 1532 2623 1496 2623 1480 2623 1497 2624 1496 2624 1532 2624 1532 2625 1533 2625 1497 2625 1533 2626 1534 2626 1497 2626 1500 2627 1497 2627 1534 2627 1499 2628 1500 2628 1535 2628 1500 2629 1534 2629 1535 2629 1534 2630 1533 2630 1536 2630 1536 2631 1537 2631 1534 2631 1537 2632 1538 2632 1534 2632 1538 2633 1535 2633 1534 2633 1539 2634 1535 2634 1538 2634 1538 2635 1540 2635 1539 2635 1541 2636 1539 2636 1540 2636 1540 2637 1542 2637 1541 2637 1543 2638 1541 2638 1542 2638 1542 2639 1544 2639 1543 2639 1545 2640 1543 2640 1544 2640 1544 2641 1546 2641 1545 2641 1547 2642 1545 2642 1546 2642 1546 2643 1548 2643 1547 2643 1547 2644 1549 2644 1550 2644 1547 2645 1548 2645 1549 2645 1551 2646 1549 2646 1552 2646 1551 2647 1550 2647 1549 2647 1552 2648 1553 2648 1554 2648 1501 2649 1442 2649 1555 2649 1556 2650 1518 2650 1557 2650 1518 2651 1516 2651 1557 2651 1516 2652 1513 2652 1557 2652 1513 2653 1511 2653 1557 2653 1555 2654 1557 2654 1501 2654 1557 2655 1502 2655 1501 2655 1557 2656 1505 2656 1502 2656 1557 2657 1507 2657 1505 2657 1557 2658 1509 2658 1507 2658 1557 2659 1511 2659 1509 2659 1553 2660 1558 2660 1554 2660 1559 2661 1560 2661 1561 2661 1562 2662 1563 2662 1537 2662 1563 2663 1538 2663 1537 2663 1563 2664 1562 2664 1559 2664 1562 2665 1560 2665 1559 2665 1540 2666 1538 2666 1563 2666 1559 2667 1564 2667 1563 2667 1565 2668 1563 2668 1564 2668 1563 2669 1565 2669 1540 2669 1542 2670 1540 2670 1565 2670 1564 2671 1566 2671 1565 2671 1565 2672 1567 2672 1542 2672 1567 2673 1544 2673 1542 2673 1567 2674 1565 2674 1566 2674 1546 2675 1544 2675 1567 2675 1566 2676 1568 2676 1567 2676 1567 2677 1569 2677 1546 2677 1569 2678 1567 2678 1568 2678 1548 2679 1546 2679 1569 2679 1568 2680 1570 2680 1553 2680 1553 2681 1569 2681 1568 2681 1569 2682 1552 2682 1548 2682 1569 2683 1553 2683 1552 2683 1548 2684 1552 2684 1549 2684 1571 2685 1561 2685 1560 2685 1572 2686 1560 2686 1537 2686 1560 2687 1562 2687 1537 2687 1560 2688 1572 2688 1571 2688 1537 2689 1573 2689 1572 2689 1573 2690 1537 2690 1456 2690 1574 2691 1571 2691 1572 2691 1575 2692 1572 2692 1573 2692 1572 2693 1575 2693 1574 2693 1456 2694 1455 2694 1573 2694 1573 2695 1576 2695 1575 2695 1576 2696 1573 2696 1455 2696 1577 2697 1574 2697 1575 2697 1574 2698 1577 2698 1578 2698 1579 2699 1575 2699 1576 2699 1575 2700 1579 2700 1577 2700 1580 2701 1578 2701 1577 2701 1455 2702 1458 2702 1576 2702 1581 2703 1576 2703 1458 2703 1576 2704 1581 2704 1579 2704 1582 2705 1577 2705 1583 2705 1577 2706 1579 2706 1583 2706 1577 2707 1582 2707 1580 2707 1583 2708 1579 2708 1581 2708 1580 2709 1584 2709 1585 2709 1584 2710 1580 2710 1582 2710 1586 2711 1585 2711 1584 2711 1458 2712 1587 2712 1581 2712 1581 2713 1588 2713 1583 2713 1588 2714 1581 2714 1589 2714 1581 2715 1587 2715 1589 2715 1583 2716 1590 2716 1582 2716 1536 2717 1533 2717 1537 2717 1533 2718 1532 2718 1537 2718 1532 2719 1531 2719 1537 2719 1531 2720 1530 2720 1537 2720 1530 2721 1529 2721 1537 2721 1591 2722 1529 2722 1592 2722 1529 2723 1528 2723 1592 2723 1528 2724 1527 2724 1592 2724 1527 2725 1525 2725 1592 2725 1529 2726 1591 2726 1537 2726 1456 2727 1537 2727 1591 2727 1523 2728 1592 2728 1524 2728 1592 2729 1526 2729 1524 2729 1592 2730 1525 2730 1526 2730 1592 2731 1593 2731 1591 2731 1591 2732 1594 2732 1456 2732 1594 2733 1454 2733 1456 2733 1594 2734 1591 2734 1593 2734 1455 2735 1454 2735 1594 2735 1593 2736 1595 2736 1594 2736 1596 2737 1594 2737 1595 2737 1594 2738 1596 2738 1455 2738 1596 2739 1457 2739 1455 2739 1458 2740 1457 2740 1596 2740 1597 2741 1596 2741 1598 2741 1596 2742 1597 2742 1458 2742 1597 2743 1587 2743 1458 2743 1589 2744 1587 2744 1597 2744 1597 2745 1599 2745 1589 2745 1600 2746 1589 2746 1599 2746 1601 64 1550 64 1551 64 1547 64 1550 64 1601 64 1601 2747 1602 2747 1547 2747 1545 2748 1547 2748 1602 2748 1543 2749 1545 2749 1446 2749 1545 2750 1602 2750 1446 2750 1541 2751 1543 2751 1499 2751 1543 2752 1492 2752 1499 2752 1543 2753 1446 2753 1492 2753 1492 2754 1493 2754 1499 2754 1498 2755 1499 2755 1493 2755 1499 64 1535 64 1541 64 1535 64 1539 64 1541 64 1493 2756 1495 2756 1498 2756 1603 2757 1604 2757 1605 2757 1441 2758 1471 2758 1606 2758 1461 2759 1463 2759 1471 2759 1607 2760 1471 2760 1465 2760 1471 2761 1463 2761 1465 2761 1608 2762 1609 2762 1610 2762 1609 2763 1611 2763 1610 2763 1609 2764 1608 2764 1612 2764 1608 2765 1603 2765 1612 2765 1612 2766 1613 2766 1609 2766 1614 2767 1615 2767 1616 2767 1617 2768 1618 2768 1619 2768 1617 2769 1620 2769 1618 2769 1619 2770 1621 2770 1617 2770 1604 2771 1620 2771 1617 2771 1605 2772 1617 2772 1621 2772 1617 2773 1605 2773 1604 2773 1621 2774 1613 2774 1612 2774 1621 2775 1612 2775 1605 2775 1603 2776 1605 2776 1612 2776 1589 2777 1600 2777 1588 2777 1622 2778 1623 2778 1624 2778 1624 2779 1625 2779 1622 2779 1625 2780 1624 2780 1610 2780 1610 2781 1611 2781 1625 2781 1599 2782 1623 2782 1600 2782 1626 64 1627 64 1628 64 1627 64 1629 64 1630 64 1629 2783 1618 2783 1630 2783 1631 2784 1453 2784 1632 2784 1633 2785 1634 2785 1631 2785 1631 2786 1635 2786 1453 2786 1635 2787 1452 2787 1453 2787 1635 2788 1631 2788 1636 2788 1631 2789 1634 2789 1636 2789 1451 2790 1452 2790 1635 2790 1636 2791 1637 2791 1635 2791 1635 2792 1638 2792 1451 2792 1638 2793 1472 2793 1451 2793 1638 2794 1635 2794 1639 2794 1635 2795 1637 2795 1639 2795 1473 2796 1472 2796 1638 2796 1639 2797 1640 2797 1638 2797 1638 2798 1641 2798 1473 2798 1638 2799 1640 2799 1642 2799 1451 2800 1472 2800 1450 2800 1643 2801 1644 2801 1628 2801 1644 2802 1643 2802 1645 2802 1643 2803 1646 2803 1645 2803 1628 2804 1630 2804 1643 2804 1647 2805 1646 2805 1643 2805 1643 2806 1610 2806 1647 2806 1610 2807 1643 2807 1608 2807 1643 2808 1603 2808 1608 2808 1643 2809 1630 2809 1603 2809 1647 2810 1610 2810 1624 2810 1595 2811 1598 2811 1596 2811 1598 2812 1595 2812 1648 2812 1598 2813 1649 2813 1597 2813 1649 2814 1598 2814 1648 2814 1648 2815 1646 2815 1649 2815 1645 2816 1646 2816 1648 2816 1599 2817 1597 2817 1649 2817 1649 2818 1650 2818 1599 2818 1650 2819 1649 2819 1646 2819 1646 2820 1647 2820 1650 2820 1623 2821 1599 2821 1650 2821 1650 2822 1624 2822 1623 2822 1624 2823 1650 2823 1647 2823 1626 64 1628 64 1651 64 1627 2824 1630 2824 1628 2824 1618 2825 1620 2825 1630 2825 1620 64 1604 64 1630 64 1630 2826 1604 2826 1603 2826 1652 2827 1653 2827 1654 2827 1447 2828 1655 2828 1632 2828 1632 2829 1655 2829 1656 2829 1657 2830 1632 2830 1656 2830 1658 2831 1659 2831 1632 2831 1657 2832 1658 2832 1632 2832 1660 2833 1659 2833 1658 2833 1661 2834 1660 2834 1658 2834 1662 2835 1661 2835 1658 2835 1658 2836 1663 2836 1662 2836 1631 2837 1660 2837 1633 2837 1631 2838 1632 2838 1659 2838 1660 2839 1631 2839 1659 2839 1633 2840 1660 2840 1661 2840 1633 2841 1661 2841 1662 2841 1632 2842 1453 2842 1447 2842 1664 2843 1665 2843 1666 2843 1653 64 1667 64 1654 64 1667 64 1626 64 1654 64 1651 2844 1654 2844 1626 2844 1668 2845 1669 2845 1670 2845 1641 2846 1474 2846 1473 2846 1641 2847 1638 2847 1642 2847 1476 2848 1474 2848 1641 2848 1642 2849 1671 2849 1641 2849 1641 2850 1672 2850 1476 2850 1672 2851 1479 2851 1476 2851 1672 2852 1641 2852 1673 2852 1641 2853 1671 2853 1673 2853 1485 2854 1479 2854 1672 2854 1673 2855 1674 2855 1672 2855 1675 2856 1672 2856 1676 2856 1672 2857 1674 2857 1676 2857 1672 2858 1675 2858 1485 2858 1675 2859 1489 2859 1485 2859 1677 2860 1489 2860 1675 2860 1676 2861 1678 2861 1675 2861 1679 2862 1680 2862 1675 2862 1680 2863 1681 2863 1675 2863 1681 2864 1677 2864 1675 2864 1679 2865 1675 2865 1678 2865 1678 2866 1682 2866 1679 2866 1682 2867 1683 2867 1684 2867 1684 2868 1679 2868 1682 2868 1485 2869 1489 2869 1488 2869 1685 2870 1490 2870 1489 2870 1489 2871 1677 2871 1685 2871 1686 2872 1687 2872 1688 2872 1689 2873 1690 2873 1686 2873 1691 2874 1692 2874 1693 2874 1691 2875 1694 2875 1689 2875 1695 2876 1692 2876 1691 2876 1688 2877 1696 2877 1686 2877 1697 2878 1686 2878 1696 2878 1686 2879 1697 2879 1689 2879 1689 2880 1698 2880 1691 2880 1698 2881 1689 2881 1697 2881 1699 2882 1691 2882 1698 2882 1691 2883 1699 2883 1695 2883 1699 2884 1700 2884 1695 2884 1696 2885 1701 2885 1697 2885 1702 2886 1697 2886 1701 2886 1697 2887 1702 2887 1698 2887 1698 2888 1703 2888 1699 2888 1703 2889 1698 2889 1702 2889 1704 2890 1700 2890 1699 2890 1699 2891 1705 2891 1704 2891 1705 2892 1706 2892 1704 2892 1705 2893 1699 2893 1703 2893 1701 2894 1707 2894 1702 2894 1702 2895 1708 2895 1703 2895 1708 2896 1702 2896 1709 2896 1702 2897 1707 2897 1709 2897 1703 2898 1710 2898 1705 2898 1710 2899 1703 2899 1708 2899 1711 2900 1706 2900 1705 2900 1712 2901 1705 2901 1710 2901 1705 2902 1712 2902 1711 2902 1712 2903 1713 2903 1711 2903 1709 2904 1714 2904 1708 2904 1708 2905 1715 2905 1710 2905 1715 2906 1708 2906 1714 2906 1710 2907 1716 2907 1712 2907 1716 2908 1710 2908 1715 2908 1714 2909 1717 2909 1715 2909 1715 2910 1718 2910 1719 2910 1715 2911 1717 2911 1718 2911 1715 2912 1719 2912 1716 2912 1712 2913 1716 2913 1720 2913 1716 2914 1719 2914 1720 2914 1721 2915 1722 2915 1522 2915 1722 2916 1523 2916 1522 2916 1722 2917 1721 2917 1723 2917 1522 2918 1724 2918 1721 2918 1670 2919 1721 2919 1668 2919 1721 2920 1724 2920 1668 2920 1721 2921 1670 2921 1723 2921 1713 2922 1723 2922 1711 2922 1723 2923 1725 2923 1711 2923 1725 2924 1723 2924 1669 2924 1723 2925 1670 2925 1669 2925 1706 2926 1711 2926 1725 2926 1669 2927 1726 2927 1725 2927 1725 2928 1727 2928 1706 2928 1727 2929 1704 2929 1706 2929 1727 2930 1725 2930 1728 2930 1725 2931 1726 2931 1728 2931 1728 2932 1729 2932 1727 2932 1700 2933 1704 2933 1727 2933 1730 2934 1727 2934 1731 2934 1727 2935 1729 2935 1731 2935 1727 2936 1730 2936 1700 2936 1730 2937 1695 2937 1700 2937 1731 2938 1732 2938 1730 2938 1692 2939 1695 2939 1730 2939 1730 2940 1732 2940 1733 2940 1730 2941 1733 2941 1692 2941 1692 2942 1733 2942 1734 2942 1728 2943 1726 2943 1683 2943 1726 2944 1684 2944 1683 2944 1679 2945 1684 2945 1726 2945 1726 2946 1669 2946 1679 2946 1680 2947 1679 2947 1669 2947 1669 2948 1668 2948 1680 2948 1668 2949 1681 2949 1680 2949 1677 2950 1681 2950 1668 2950 1668 2951 1724 2951 1677 2951 1685 2952 1677 2952 1724 2952 1724 2953 1522 2953 1685 2953 1490 2954 1685 2954 1522 2954 1718 2955 1735 2955 1719 2955 1735 2956 1720 2956 1719 2956 1644 2957 1712 2957 1720 2957 1644 2958 1713 2958 1712 2958 1644 2959 1736 2959 1713 2959 1644 2960 1645 2960 1736 2960 1644 2961 1720 2961 1735 2961 1735 2962 1651 2962 1644 2962 1644 2963 1651 2963 1628 2963 1592 2964 1523 2964 1722 2964 1737 2965 1722 2965 1723 2965 1722 2966 1737 2966 1592 2966 1593 2967 1592 2967 1737 2967 1713 2968 1736 2968 1723 2968 1736 2969 1737 2969 1723 2969 1737 2970 1645 2970 1648 2970 1737 2971 1736 2971 1645 2971 1737 2972 1648 2972 1593 2972 1595 2973 1593 2973 1648 2973 1634 2974 1633 2974 1733 2974 1733 2975 1732 2975 1634 2975 1636 583 1634 583 1732 583 1732 2976 1731 2976 1636 2976 1637 2977 1636 2977 1731 2977 1731 2978 1729 2978 1637 2978 1639 2979 1637 2979 1683 2979 1637 2980 1729 2980 1683 2980 1729 2981 1728 2981 1683 2981 1683 583 1682 583 1639 583 1640 2982 1639 2982 1682 2982 1682 2983 1678 2983 1640 2983 1642 583 1640 583 1678 583 1678 583 1676 583 1642 583 1671 583 1642 583 1676 583 1676 583 1674 583 1671 583 1673 583 1671 583 1674 583 1707 64 1701 64 1738 64 1709 64 1707 64 1739 64 1714 64 1709 64 1740 64 1717 64 1714 64 1741 64 1742 64 1718 64 1717 64 1735 2984 1718 2984 1654 2984 1718 64 1742 64 1654 64 1741 2985 1742 2985 1717 2985 1740 64 1741 64 1714 64 1739 64 1740 64 1709 64 1738 2986 1739 2986 1707 2986 1743 2987 1738 2987 1701 2987 1701 64 1696 64 1743 64 1744 64 1743 64 1696 64 1696 2988 1688 2988 1744 2988 1745 2989 1744 2989 1688 2989 1688 64 1746 64 1745 64 1747 64 1745 64 1746 64 1733 2990 1633 2990 1662 2990 1748 2991 1733 2991 1662 2991 1663 2992 1749 2992 1750 2992 1663 2993 1750 2993 1751 2993 1663 2994 1751 2994 1752 2994 1663 2995 1752 2995 1753 2995 1663 2996 1753 2996 1754 2996 1663 2997 1754 2997 1755 2997 1663 2998 1755 2998 1756 2998 1663 2999 1756 2999 1757 2999 1663 3000 1757 3000 1748 3000 1662 3001 1663 3001 1748 3001 1758 3002 1749 3002 1663 3002 1757 3003 1759 3003 1760 3003 1748 3004 1757 3004 1760 3004 1761 3005 1759 3005 1757 3005 1757 3006 1756 3006 1761 3006 1762 3007 1761 3007 1756 3007 1756 3008 1755 3008 1762 3008 1763 3009 1762 3009 1755 3009 1755 3010 1754 3010 1763 3010 1764 3011 1763 3011 1754 3011 1754 3012 1753 3012 1764 3012 1765 3013 1764 3013 1753 3013 1753 3014 1752 3014 1765 3014 1751 3015 1750 3015 1766 3015 1750 3016 1749 3016 1766 3016 1767 3017 1768 3017 1758 3017 1759 3018 1769 3018 1770 3018 1760 3019 1759 3019 1770 3019 1771 3020 1745 3020 1747 3020 1771 3021 1747 3021 1772 3021 1771 3022 1772 3022 1773 3022 1774 3023 1771 3023 1773 3023 1774 3024 1773 3024 1775 3024 1774 3025 1775 3025 1776 3025 1769 3026 1774 3026 1776 3026 1774 3027 1769 3027 1759 3027 1759 3028 1761 3028 1774 3028 1744 3029 1745 3029 1771 3029 1777 3030 1743 3030 1744 3030 1771 3031 1777 3031 1744 3031 1777 3032 1771 3032 1774 3032 1774 3033 1761 3033 1762 3033 1778 3034 1774 3034 1762 3034 1774 3035 1778 3035 1777 3035 1762 3036 1763 3036 1778 3036 1738 3037 1743 3037 1777 3037 1779 3038 1777 3038 1778 3038 1777 3039 1779 3039 1738 3039 1778 3040 1780 3040 1779 3040 1778 3041 1763 3041 1764 3041 1780 3042 1778 3042 1764 3042 1739 3043 1738 3043 1779 3043 1764 3044 1765 3044 1780 3044 1781 3045 1779 3045 1780 3045 1781 3046 1740 3046 1739 3046 1779 3047 1781 3047 1739 3047 1780 3048 1782 3048 1781 3048 1780 3049 1765 3049 1766 3049 1780 3050 1766 3050 1782 3050 1741 3051 1740 3051 1781 3051 1783 3052 1781 3052 1782 3052 1781 3053 1783 3053 1741 3053 1742 3054 1741 3054 1783 3054 1782 3055 1766 3055 1768 3055 1782 3056 1784 3056 1785 3056 1783 3057 1786 3057 1787 3057 1788 3058 1783 3058 1787 3058 1783 3059 1788 3059 1742 3059 1742 3060 1788 3060 1789 3060 1654 3061 1742 3061 1789 3061 1692 3062 1734 3062 1790 3062 1693 3063 1692 3063 1790 3063 1691 3064 1693 3064 1791 3064 1694 3065 1691 3065 1791 3065 1689 3066 1694 3066 1690 3066 1686 3067 1690 3067 1687 3067 1688 3068 1687 3068 1792 3068 1746 3069 1688 3069 1792 3069 1693 3070 1790 3070 1760 3070 1760 3071 1790 3071 1734 3071 1760 3072 1734 3072 1733 3072 1748 3073 1760 3073 1733 3073 1746 3074 1792 3074 1747 3074 1772 3075 1747 3075 1792 3075 1792 3076 1687 3076 1772 3076 1773 3077 1772 3077 1687 3077 1687 3078 1690 3078 1773 3078 1775 3079 1773 3079 1690 3079 1776 3080 1775 3080 1690 3080 1690 3081 1694 3081 1776 3081 1769 3082 1776 3082 1694 3082 1694 3083 1791 3083 1769 3083 1770 3084 1769 3084 1791 3084 1791 3085 1693 3085 1770 3085 1760 3086 1770 3086 1693 3086 1786 3087 1782 3087 1785 3087 1786 3088 1783 3088 1782 3088 1767 3089 1784 3089 1768 3089 1768 3090 1784 3090 1782 3090 1758 3091 1768 3091 1749 3091 1749 3092 1768 3092 1766 3092 1751 3093 1766 3093 1765 3093 1751 3094 1765 3094 1752 3094 1651 3095 1735 3095 1654 3095 1793 3096 1663 3096 1658 3096 1794 3097 1627 3097 1626 3097 1795 64 1796 64 1654 64 1797 3098 1795 3098 1654 3098 1627 3099 1794 3099 1798 3099 1664 3100 1799 3100 1800 3100 1664 3101 1800 3101 1798 3101 1798 3102 1794 3102 1664 3102 1664 3103 1794 3103 1626 3103 1664 182 1626 182 1801 182 1801 3104 1802 3104 1803 3104 1801 182 1626 182 1802 182 1796 64 1652 64 1654 64 1623 3105 1804 3105 1600 3105 1805 3106 1614 3106 1806 3106 1806 3107 1807 3107 1805 3107 1611 3108 1805 3108 1807 3108 1807 3109 1625 3109 1611 3109 1808 3110 1809 3110 1810 3110 1811 3111 1806 3111 1614 3111 1811 3112 1614 3112 1812 3112 1811 3113 1812 3113 1809 3113 1809 3114 1808 3114 1813 3114 1811 3115 1809 3115 1813 3115 1807 3116 1806 3116 1811 3116 1813 3117 1814 3117 1811 3117 1622 3118 1625 3118 1807 3118 1811 3119 1622 3119 1807 3119 1622 3120 1811 3120 1814 3120 1814 3121 1815 3121 1622 3121 1623 3122 1622 3122 1815 3122 1815 3123 1804 3123 1623 3123 1816 3124 1817 3124 1818 3124 1818 3125 1815 3125 1819 3125 1818 3126 1817 3126 1804 3126 1818 3127 1804 3127 1815 3127 1819 3128 1815 3128 1814 3128 1819 3129 1814 3129 1820 3129 1820 3130 1814 3130 1813 3130 1821 3131 1813 3131 1808 3131 1600 3132 1804 3132 1817 3132 1590 3133 1817 3133 1816 3133 1588 3134 1600 3134 1817 3134 1822 3135 1823 3135 1616 3135 1822 3136 1616 3136 1613 3136 1621 3137 1822 3137 1613 3137 1824 3138 1823 3138 1822 3138 1825 3139 1822 3139 1621 3139 1822 3140 1825 3140 1824 3140 1621 3141 1619 3141 1825 3141 1826 3142 1824 3142 1825 3142 1825 3143 1827 3143 1826 3143 1827 3144 1825 3144 1619 3144 1619 3145 1828 3145 1827 3145 1828 3146 1619 3146 1618 3146 1829 3147 1826 3147 1827 3147 1618 3148 1830 3148 1828 3148 1830 3149 1618 3149 1629 3149 1831 3150 1829 3150 1827 3150 1831 3151 1827 3151 1828 3151 1629 3152 1627 3152 1830 3152 1799 3153 1831 3153 1828 3153 1828 3154 1800 3154 1799 3154 1800 3155 1828 3155 1830 3155 1798 3156 1830 3156 1627 3156 1830 3157 1798 3157 1800 3157 1664 3158 1829 3158 1831 3158 1664 3159 1831 3159 1799 3159 1829 3160 1606 3160 1826 3160 1824 3161 1826 3161 1606 3161 1823 3162 1824 3162 1606 3162 1606 3163 1832 3163 1823 3163 1823 3164 1832 3164 1833 3164 1616 3165 1823 3165 1833 3165 1834 3166 1616 3166 1833 3166 1835 3167 1834 3167 1833 3167 1833 3168 1836 3168 1835 3168 1835 3169 1836 3169 1837 3169 1834 3170 1835 3170 1838 3170 1838 3171 1614 3171 1834 3171 1616 3172 1834 3172 1614 3172 1614 3173 1805 3173 1615 3173 1839 3174 1613 3174 1616 3174 1839 3175 1616 3175 1615 3175 1839 3176 1615 3176 1805 3176 1839 3177 1609 3177 1613 3177 1839 3178 1805 3178 1611 3178 1609 3179 1839 3179 1611 3179 1840 3180 1841 3180 1821 3180 1842 3181 1821 3181 1808 3181 1821 3182 1842 3182 1840 3182 1808 3183 1810 3183 1842 3183 1843 3184 1842 3184 1810 3184 1843 3185 1844 3185 1840 3185 1842 3186 1843 3186 1840 3186 1810 3187 1809 3187 1843 3187 1845 3188 1843 3188 1809 3188 1843 3189 1845 3189 1844 3189 1809 3190 1812 3190 1845 3190 1838 3191 1837 3191 1844 3191 1845 3192 1838 3192 1844 3192 1845 3193 1812 3193 1614 3193 1845 3194 1614 3194 1838 3194 1837 3195 1838 3195 1835 3195 1846 3196 1847 3196 1848 3196 1846 3197 1841 3197 1840 3197 1847 3198 1846 3198 1840 3198 1848 3199 1607 3199 1467 3199 1607 3200 1848 3200 1847 3200 1465 3201 1467 3201 1607 3201 1847 3202 1849 3202 1607 3202 1471 3203 1607 3203 1849 3203 1849 3204 1606 3204 1471 3204 1832 3205 1606 3205 1849 3205 1833 3206 1832 3206 1849 3206 1849 3207 1836 3207 1833 3207 1849 3208 1844 3208 1837 3208 1849 3209 1837 3209 1836 3209 1840 3210 1849 3210 1847 3210 1840 3211 1844 3211 1849 3211 1664 3212 1606 3212 1829 3212 1664 3213 1441 3213 1606 3213 1850 3214 1851 3214 1852 3214 1853 3215 1851 3215 1850 3215 1850 3216 1854 3216 1853 3216 1854 3217 1855 3217 1853 3217 1856 3218 1855 3218 1854 3218 1857 3219 1856 3219 1854 3219 1854 3220 1858 3220 1857 3220 1859 3221 1857 3221 1858 3221 1860 3222 1859 3222 1858 3222 1861 3223 1862 3223 1860 3223 1863 3224 1862 3224 1861 3224 1470 3225 1467 3225 1468 3225 1864 3226 1470 3226 1469 3226 1469 3227 1520 3227 1864 3227 1865 3228 1864 3228 1520 3228 1520 3229 1521 3229 1865 3229 1866 3230 1865 3230 1521 3230 1521 3231 1867 3231 1866 3231 1868 3232 1866 3232 1867 3232 1867 3233 1869 3233 1868 3233 1870 3234 1868 3234 1871 3234 1852 3235 1872 3235 1850 3235 1873 3236 1874 3236 1852 3236 1874 3237 1873 3237 1875 3237 1876 3238 1877 3238 1878 3238 1876 3239 1879 3239 1877 3239 1876 3240 1875 3240 1879 3240 1878 3241 1880 3241 1881 3241 1882 3242 1881 3242 1883 3242 1883 3243 1884 3243 1882 3243 1881 3244 1885 3244 1883 3244 1881 3245 1880 3245 1885 3245 1886 3246 1887 3246 1884 3246 1887 3247 1882 3247 1884 3247 1888 3248 1882 3248 1887 3248 1887 3249 1889 3249 1888 3249 1889 3250 1890 3250 1891 3250 1890 3251 1892 3251 1893 3251 1893 3252 1892 3252 1870 3252 1467 3253 1470 3253 1848 3253 1894 3254 1841 3254 1846 3254 1895 3255 1848 3255 1864 3255 1848 3256 1470 3256 1864 3256 1848 3257 1895 3257 1846 3257 1896 3258 1846 3258 1895 3258 1846 3259 1896 3259 1894 3259 1896 3260 1897 3260 1894 3260 1864 3261 1865 3261 1895 3261 1898 3262 1897 3262 1896 3262 1899 3263 1895 3263 1866 3263 1895 3264 1865 3264 1866 3264 1895 3265 1899 3265 1896 3265 1900 3266 1896 3266 1899 3266 1896 3267 1900 3267 1898 3267 1900 3268 1901 3268 1898 3268 1866 3269 1868 3269 1899 3269 1902 3270 1901 3270 1900 3270 1899 3271 1890 3271 1900 3271 1899 3272 1892 3272 1890 3272 1899 3273 1870 3273 1892 3273 1899 3274 1868 3274 1870 3274 1886 3275 1900 3275 1887 3275 1900 3276 1889 3276 1887 3276 1900 3277 1890 3277 1889 3277 1900 3278 1886 3278 1902 3278 1903 3279 1904 3279 1905 3279 1903 3280 1906 3280 1904 3280 1903 3281 1907 3281 1906 3281 1906 3282 1908 3282 1904 3282 1908 3283 1905 3283 1904 3283 1908 3284 1909 3284 1905 3284 1910 3285 1911 3285 1909 3285 1910 3286 1909 3286 1908 3286 1908 3287 1912 3287 1910 3287 1913 3288 1910 3288 1912 3288 1910 3289 1913 3289 1914 3289 1912 3290 1915 3290 1913 3290 1913 3291 1916 3291 1917 3291 1913 3292 1918 3292 1916 3292 1913 3293 1919 3293 1918 3293 1913 3294 1915 3294 1919 3294 1920 3295 1921 3295 1821 3295 1920 3296 1821 3296 1841 3296 1841 3297 1894 3297 1920 3297 1922 3298 1921 3298 1920 3298 1923 3299 1920 3299 1894 3299 1920 3300 1923 3300 1922 3300 1894 3301 1897 3301 1923 3301 1924 3302 1922 3302 1923 3302 1925 3303 1923 3303 1897 3303 1923 3304 1925 3304 1924 3304 1897 3305 1898 3305 1925 3305 1926 3306 1924 3306 1925 3306 1927 3307 1925 3307 1898 3307 1925 3308 1927 3308 1926 3308 1928 3309 1926 3309 1927 3309 1898 3310 1901 3310 1927 3310 1927 3311 1929 3311 1928 3311 1929 3312 1927 3312 1901 3312 1930 3313 1928 3313 1929 3313 1901 3314 1902 3314 1929 3314 1931 3315 1929 3315 1902 3315 1929 3316 1931 3316 1930 3316 1919 3317 1930 3317 1931 3317 1902 3318 1886 3318 1931 3318 1931 3319 1932 3319 1919 3319 1932 3320 1931 3320 1884 3320 1931 3321 1886 3321 1884 3321 1918 3322 1919 3322 1932 3322 1884 3323 1883 3323 1932 3323 1932 3324 1933 3324 1918 3324 1933 3325 1916 3325 1918 3325 1933 3326 1932 3326 1883 3326 1883 3327 1885 3327 1933 3327 1933 3328 1880 3328 1916 3328 1880 3329 1934 3329 1916 3329 1933 3330 1885 3330 1880 3330 1880 3331 1878 3331 1934 3331 1878 3332 1877 3332 1934 3332 1877 3333 1879 3333 1934 3333 1590 3334 1583 3334 1588 3334 1582 3335 1935 3335 1584 3335 1935 3336 1582 3336 1590 3336 1936 3337 1584 3337 1935 3337 1584 3338 1936 3338 1586 3338 1937 3339 1586 3339 1936 3339 1586 3340 1937 3340 1938 3340 1937 3341 1939 3341 1938 3341 1588 3342 1817 3342 1590 3342 1590 3343 1940 3343 1935 3343 1940 3344 1590 3344 1941 3344 1590 3345 1816 3345 1941 3345 1942 3346 1935 3346 1943 3346 1935 3347 1940 3347 1943 3347 1935 3348 1942 3348 1936 3348 1936 3349 1944 3349 1937 3349 1936 3350 1945 3350 1944 3350 1936 3351 1942 3351 1945 3351 1907 3352 1939 3352 1937 3352 1946 3353 1937 3353 1947 3353 1937 3354 1948 3354 1947 3354 1937 3355 1944 3355 1948 3355 1937 3356 1946 3356 1907 3356 1906 3357 1907 3357 1949 3357 1907 3358 1946 3358 1949 3358 1820 3359 1813 3359 1821 3359 1821 3360 1921 3360 1820 3360 1820 3361 1950 3361 1819 3361 1950 3362 1820 3362 1922 3362 1820 3363 1921 3363 1922 3363 1951 3364 1819 3364 1950 3364 1819 3365 1951 3365 1818 3365 1952 3366 1818 3366 1951 3366 1818 3367 1952 3367 1816 3367 1952 3368 1941 3368 1816 3368 1940 3369 1941 3369 1952 3369 1922 3370 1924 3370 1950 3370 1950 3371 1953 3371 1951 3371 1953 3372 1950 3372 1924 3372 1954 3373 1951 3373 1953 3373 1951 3374 1954 3374 1952 3374 1952 3375 1955 3375 1940 3375 1955 3376 1943 3376 1940 3376 1955 3377 1952 3377 1954 3377 1942 3378 1943 3378 1955 3378 1924 3379 1926 3379 1953 3379 1953 3380 1956 3380 1954 3380 1956 3381 1953 3381 1926 3381 1954 3382 1957 3382 1955 3382 1957 3383 1954 3383 1956 3383 1958 3384 1955 3384 1957 3384 1955 3385 1958 3385 1942 3385 1958 3386 1945 3386 1942 3386 1958 3387 1944 3387 1945 3387 1926 3388 1928 3388 1956 3388 1948 3389 1944 3389 1958 3389 1959 3390 1956 3390 1928 3390 1956 3391 1959 3391 1957 3391 1957 3392 1960 3392 1958 3392 1960 3393 1957 3393 1959 3393 1958 3394 1961 3394 1948 3394 1961 3395 1947 3395 1948 3395 1961 3396 1958 3396 1960 3396 1928 3397 1930 3397 1959 3397 1946 3398 1947 3398 1961 3398 1959 3399 1915 3399 1960 3399 1959 3400 1919 3400 1915 3400 1959 3401 1930 3401 1919 3401 1960 3402 1915 3402 1912 3402 1960 3403 1912 3403 1961 3403 1961 3404 1908 3404 1946 3404 1908 3405 1949 3405 1946 3405 1961 3406 1912 3406 1908 3406 1906 3407 1949 3407 1908 3407 1962 3408 1853 3408 1855 3408 1962 3409 1851 3409 1853 3409 1962 3410 1852 3410 1851 3410 1962 3411 1873 3411 1852 3411 1962 3412 1875 3412 1873 3412 1934 3413 1879 3413 1875 3413 1963 3414 1964 3414 1965 3414 1963 3415 1965 3415 1966 3415 1967 3416 1963 3416 1966 3416 1938 3417 1968 3417 1586 3417 1585 3418 1586 3418 1968 3418 1968 3419 1969 3419 1585 3419 1585 3420 1970 3420 1580 3420 1970 3421 1585 3421 1969 3421 1969 3422 1971 3422 1970 3422 1972 3423 1556 3423 1557 3423 1973 3424 1972 3424 1557 3424 1974 3425 1973 3425 1557 3425 1974 3426 1557 3426 1975 3426 1976 3427 1974 3427 1975 3427 1977 3428 1976 3428 1975 3428 1978 3429 1977 3429 1975 3429 1979 3430 1978 3430 1975 3430 1980 3431 1978 3431 1979 3431 1910 3432 1981 3432 1911 3432 1982 3433 1909 3433 1911 3433 1982 3434 1911 3434 1981 3434 1982 3435 1981 3435 1983 3435 1909 3436 1903 3436 1905 3436 1903 3437 1909 3437 1982 3437 1939 3438 1907 3438 1903 3438 1983 3439 1984 3439 1982 3439 1982 3440 1985 3440 1903 3440 1985 3441 1982 3441 1984 3441 1986 3442 1903 3442 1985 3442 1903 3443 1986 3443 1939 3443 1938 3444 1939 3444 1986 3444 1984 3445 1987 3445 1985 3445 1988 3446 1985 3446 1987 3446 1985 3447 1988 3447 1986 3447 1987 3448 1989 3448 1988 3448 1990 3449 1968 3449 1938 3449 1986 3450 1990 3450 1938 3450 1990 3451 1986 3451 1988 3451 1969 3452 1968 3452 1990 3452 1988 3453 1991 3453 1990 3453 1988 3454 1989 3454 1992 3454 1991 3455 1988 3455 1992 3455 1992 3456 1993 3456 1991 3456 1994 3457 1990 3457 1991 3457 1990 3458 1994 3458 1969 3458 1971 3459 1969 3459 1994 3459 1995 3460 1991 3460 1993 3460 1991 3461 1995 3461 1994 3461 1993 3462 1996 3462 1995 3462 1994 3463 1997 3463 1971 3463 1997 3464 1994 3464 1995 3464 1995 3465 1996 3465 1998 3465 1999 583 1993 583 2000 583 1993 583 1999 583 1967 583 1993 3466 1967 3466 1966 3466 1993 3467 1966 3467 2001 3467 1996 3468 1993 3468 2001 3468 2002 3469 1964 3469 2003 3469 2004 3470 2003 3470 1964 3470 2002 3471 2005 3471 1964 3471 1965 3472 1964 3472 2005 3472 2005 3473 2001 3473 1965 3473 1966 3474 1965 3474 2001 3474 2006 3475 2007 3475 2008 3475 2009 3476 2008 3476 2007 3476 2007 3477 2010 3477 2009 3477 2011 3478 2009 3478 2010 3478 2010 3479 2012 3479 2011 3479 2013 3480 2011 3480 2012 3480 2012 3481 2014 3481 2013 3481 2015 3482 2013 3482 2014 3482 2014 3483 2016 3483 2015 3483 2017 3484 2015 3484 2016 3484 2016 3485 2018 3485 2017 3485 2019 3486 2017 3486 2018 3486 2018 3487 1980 3487 2019 3487 1979 3488 2019 3488 1980 3488 1980 3489 2018 3489 1978 3489 2020 3490 1978 3490 2018 3490 2020 3491 2021 3491 1976 3491 2020 3492 1976 3492 1977 3492 1978 3493 2020 3493 1977 3493 2022 3494 2021 3494 2020 3494 2018 3495 2016 3495 2020 3495 2020 3496 2016 3496 2014 3496 2023 3497 2020 3497 2014 3497 2023 3498 2024 3498 2022 3498 2020 3499 2023 3499 2022 3499 2025 3500 2024 3500 2023 3500 2014 3501 2012 3501 2023 3501 2023 3502 2012 3502 2010 3502 2026 3503 2023 3503 2010 3503 2026 3504 2027 3504 2025 3504 2023 3505 2026 3505 2025 3505 2028 3506 2027 3506 2026 3506 2010 3507 2007 3507 2026 3507 2026 3508 2029 3508 2028 3508 2026 3509 2007 3509 2006 3509 2026 3510 2006 3510 2030 3510 2026 3511 2030 3511 2031 3511 2029 3512 2026 3512 2031 3512 2028 3513 2029 3513 2032 3513 2033 3514 2028 3514 2032 3514 1871 3515 2034 3515 2033 3515 2028 3516 2033 3516 2034 3516 2034 3517 2035 3517 2028 3517 2027 3518 2028 3518 2035 3518 2035 3519 2036 3519 2027 3519 2025 3520 2027 3520 2036 3520 2036 3521 2037 3521 2025 3521 2024 3522 2025 3522 2037 3522 2037 3523 2038 3523 2024 3523 2022 3524 2024 3524 2038 3524 2038 3525 2039 3525 2022 3525 2021 3526 2022 3526 2039 3526 2039 3527 1974 3527 2021 3527 1976 3528 2021 3528 1974 3528 1869 3529 2035 3529 2034 3529 1871 3530 1869 3530 2034 3530 2040 3531 2038 3531 2037 3531 2040 3532 2037 3532 2036 3532 2035 3533 2040 3533 2036 3533 2040 3534 2035 3534 1869 3534 2041 3535 1973 3535 1974 3535 2041 3536 1974 3536 2039 3536 2041 3537 2039 3537 2038 3537 2041 3538 2038 3538 2040 3538 1869 3539 1867 3539 2040 3539 1972 3540 1973 3540 2041 3540 2040 3541 1867 3541 1521 3541 1519 3542 2040 3542 1521 3542 2040 3543 1519 3543 2041 3543 1517 3544 1556 3544 1972 3544 2041 3545 1517 3545 1972 3545 1517 3546 2041 3546 1519 3546 1518 3547 1556 3547 1517 3547 2042 3548 1893 3548 1870 3548 1893 3549 1891 3549 1890 3549 1891 3550 1888 3550 1889 3550 1881 3551 1876 3551 1878 3551 2006 3552 2043 3552 2044 3552 2008 3553 2043 3553 2006 3553 2033 3554 2032 3554 2042 3554 2045 3555 2042 3555 2032 3555 2032 3556 2029 3556 2045 3556 2046 3557 2045 3557 2029 3557 2029 3558 2031 3558 2046 3558 2047 3559 2046 3559 2031 3559 2031 3560 2030 3560 2047 3560 2048 3561 2047 3561 2030 3561 2030 3562 2006 3562 2048 3562 2044 3563 2048 3563 2006 3563 2042 3564 1870 3564 2033 3564 1871 3565 2033 3565 1870 3565 1868 3566 1869 3566 1871 3566 2049 3567 2050 3567 2051 3567 1989 3568 2052 3568 2053 3568 1992 3569 1989 3569 2053 3569 2054 3570 2049 3570 2051 3570 2054 3571 2051 3571 2055 3571 2052 3572 2054 3572 2055 3572 2054 3573 2052 3573 1989 3573 2056 3574 2049 3574 2054 3574 2056 3575 2057 3575 2049 3575 1989 3576 1987 3576 2054 3576 2054 3577 2058 3577 2056 3577 2058 3578 2054 3578 1987 3578 2059 3579 2057 3579 2056 3579 2056 3580 2060 3580 2059 3580 2060 3581 2056 3581 2058 3581 1987 3582 1984 3582 2058 3582 2061 3583 2059 3583 2060 3583 2058 3584 2062 3584 2060 3584 2062 3585 2058 3585 1984 3585 1984 3586 1983 3586 2062 3586 2063 3587 2060 3587 2062 3587 2064 3588 2065 3588 2050 3588 2051 3589 2050 3589 2065 3589 2065 3590 2066 3590 2051 3590 2055 3591 2051 3591 2066 3591 2066 3592 2067 3592 2055 3592 2052 3593 2055 3593 2067 3593 2067 3594 2068 3594 2052 3594 2053 3595 2052 3595 2068 3595 2069 3596 1992 3596 2053 3596 2068 3597 2069 3597 2053 3597 1993 3598 1992 3598 2069 3598 2069 3599 2070 3599 1993 3599 2070 3600 2071 3600 1993 3600 1993 583 2071 583 2000 583 1801 3601 1975 3601 1557 3601 1801 3602 1557 3602 2072 3602 2073 3603 2074 3603 2075 3603 2075 3604 2074 3604 2076 3604 2076 3605 2074 3605 2077 3605 2078 3606 2076 3606 2077 3606 2079 3607 2078 3607 2077 3607 2079 3608 2077 3608 2080 3608 2081 3609 2079 3609 2080 3609 2081 3610 2080 3610 2082 3610 2083 3611 2081 3611 2082 3611 2083 3612 2082 3612 2084 3612 2085 3613 2083 3613 2084 3613 2085 3614 2084 3614 2086 3614 2087 3615 2085 3615 2086 3615 2087 3616 2086 3616 2088 3616 2087 3617 2088 3617 2089 3617 2090 3618 2089 3618 2088 3618 2091 3619 2092 3619 2093 3619 2094 64 2095 64 2096 64 2097 64 2096 64 2095 64 2074 3620 2098 3620 2077 3620 2099 3621 2100 3621 2098 3621 2098 3622 2074 3622 2099 3622 2074 3623 2101 3623 2099 3623 2074 3624 2073 3624 2101 3624 2100 3625 2091 3625 2093 3625 2093 3626 2098 3626 2100 3626 2093 3627 2102 3627 2103 3627 2093 3628 2092 3628 2102 3628 2104 3629 2093 3629 2103 3629 2093 3630 2104 3630 2098 3630 2104 3631 2105 3631 2098 3631 2106 3632 2107 3632 2108 3632 2108 3633 2103 3633 2106 3633 2103 3634 2102 3634 2106 3634 2103 3635 2108 3635 2104 3635 2108 3636 2105 3636 2104 3636 2108 3637 2098 3637 2105 3637 2077 3638 2098 3638 2108 3638 2108 3639 2109 3639 2077 3639 2080 3640 2077 3640 2109 3640 2109 3641 2110 3641 2080 3641 2082 64 2080 64 2110 64 2084 3642 2082 3642 2111 3642 2112 64 2086 64 2084 64 2088 64 2086 64 2112 64 2078 3643 2113 3643 1570 3643 1570 3644 2114 3644 2078 3644 2114 3645 2076 3645 2078 3645 2076 3646 2114 3646 2115 3646 2075 3647 2116 3647 2117 3647 2076 3648 2116 3648 2075 3648 2118 3649 2119 3649 2120 3649 2119 3650 2121 3650 2120 3650 2122 3651 2121 3651 2119 3651 2119 3652 2123 3652 2122 3652 2124 3653 2122 3653 2123 3653 2123 3654 2125 3654 2124 3654 2126 3655 2124 3655 2125 3655 2125 3656 2127 3656 2126 3656 2128 3657 2126 3657 2127 3657 2127 3658 2129 3658 2101 3658 2101 3659 2128 3659 2127 3659 2129 3660 2099 3660 2101 3660 2129 3661 2100 3661 2099 3661 2128 3662 2073 3662 2075 3662 2128 3663 2101 3663 2073 3663 2129 3664 2130 3664 2100 3664 2091 3665 2100 3665 2130 3665 2130 3666 2131 3666 2091 3666 2131 3667 2092 3667 2091 3667 2102 3668 2092 3668 2106 3668 2092 3669 2131 3669 2106 3669 2132 3670 2106 3670 2131 3670 2096 3671 2097 3671 2133 3671 2134 3672 2133 3672 2097 3672 2135 3673 2136 3673 2137 3673 2138 3674 2137 3674 2136 3674 2136 3675 2133 3675 2138 3675 2134 3676 2138 3676 2133 3676 2139 3677 2096 3677 2002 3677 2001 3678 2136 3678 2135 3678 2001 3679 2133 3679 2136 3679 2001 3680 2096 3680 2133 3680 2001 3681 2005 3681 2096 3681 2005 3682 2002 3682 2096 3682 2140 3683 2132 3683 2130 3683 2132 583 2131 583 2130 583 2130 3684 2129 3684 2140 3684 2129 3685 2127 3685 2140 3685 2141 3686 2140 3686 2127 3686 2127 3687 2125 3687 2141 3687 2141 3688 2125 3688 2123 3688 2123 3689 2119 3689 2141 3689 2141 3690 2118 3690 2142 3690 2141 3691 2119 3691 2118 3691 2118 3692 1998 3692 2135 3692 2135 3693 2142 3693 2118 3693 2135 3694 2143 3694 2142 3694 2135 3695 2144 3695 2143 3695 2137 3696 2144 3696 2135 3696 2001 3697 2135 3697 1996 3697 2135 3698 1998 3698 1996 3698 2122 3699 2145 3699 2121 3699 2146 3700 2121 3700 2145 3700 2121 3701 2146 3701 2120 3701 2120 3702 2147 3702 2118 3702 2147 3703 2120 3703 2146 3703 1998 3704 2118 3704 2147 3704 2145 3705 1971 3705 2146 3705 1971 3706 1997 3706 2146 3706 2146 3707 1997 3707 2147 3707 1995 3708 2147 3708 1997 3708 2147 3709 1995 3709 1998 3709 1553 3710 2148 3710 1558 3710 1553 3711 2149 3711 2148 3711 1553 3712 1570 3712 2149 3712 2150 3713 1558 3713 2148 3713 2150 3714 2148 3714 2151 3714 2148 3715 2149 3715 2151 3715 2079 3716 2113 3716 2078 3716 2151 3717 2149 3717 2113 3717 2152 3718 2113 3718 2081 3718 2113 3719 2079 3719 2081 3719 2113 3720 2152 3720 2151 3720 2081 3721 2083 3721 2152 3721 2152 3722 2153 3722 2151 3722 2153 3723 2154 3723 2151 3723 2153 3724 2152 3724 2083 3724 2155 3725 2153 3725 2083 3725 2083 3726 2085 3726 2155 3726 2156 3727 2155 3727 2085 3727 2085 3728 2087 3728 2156 3728 2157 3729 2156 3729 2087 3729 2090 3730 2157 3730 2089 3730 2157 3731 2087 3731 2089 3731 2113 3732 2149 3732 1570 3732 1570 3733 2115 3733 2114 3733 2122 3734 2124 3734 2158 3734 2159 3735 2158 3735 2124 3735 2159 3736 1561 3736 2158 3736 2124 3737 2126 3737 2159 3737 1559 3738 1561 3738 2159 3738 2160 3739 2159 3739 2128 3739 2159 3740 2126 3740 2128 3740 2159 3741 2160 3741 1559 3741 1564 3742 1559 3742 2160 3742 2128 3743 2075 3743 2160 3743 2160 3744 2117 3744 1564 3744 2160 3745 2075 3745 2117 3745 1566 3746 1564 3746 2076 3746 1564 3747 2116 3747 2076 3747 1564 3748 2117 3748 2116 3748 1568 3749 1566 3749 2115 3749 1566 3750 2076 3750 2115 3750 1568 3751 2115 3751 1570 3751 1561 3752 1571 3752 2158 3752 2161 3753 2158 3753 1571 3753 2162 3754 2158 3754 2161 3754 2162 3755 2122 3755 2158 3755 2145 3756 2122 3756 2162 3756 1571 3757 1574 3757 2161 3757 1578 3758 2161 3758 1574 3758 2161 3759 1578 3759 2162 3759 2162 3760 1970 3760 2145 3760 1970 3761 1971 3761 2145 3761 1970 3762 2162 3762 1578 3762 1578 3763 1580 3763 1970 3763 2095 3764 2144 3764 2097 3764 2144 3765 2134 3765 2097 3765 2144 3766 2138 3766 2134 3766 2144 3767 2137 3767 2138 3767 2163 3768 2144 3768 2095 3768 2164 3769 2090 3769 2112 3769 2165 3770 2166 3770 2167 3770 2168 3771 2166 3771 2165 3771 2165 3772 2169 3772 2168 3772 2165 3773 2170 3773 2169 3773 2171 3774 2167 3774 2166 3774 2172 3775 2171 3775 2173 3775 2173 3776 2171 3776 2166 3776 2174 3777 2173 3777 2166 3777 2168 3778 2174 3778 2166 3778 2174 3779 2168 3779 2175 3779 2175 3780 2168 3780 2176 3780 2177 3781 2178 3781 2179 3781 2180 3782 2179 3782 2178 3782 2178 3783 2181 3783 2180 3783 2182 3784 2180 3784 2181 3784 2183 3785 2180 3785 2182 3785 2184 3786 2183 3786 2182 3786 2170 3787 2185 3787 2186 3787 2186 3788 2185 3788 2177 3788 2186 3789 2176 3789 2187 3789 2186 3790 2188 3790 2176 3790 2188 3791 2175 3791 2176 3791 2188 3792 2186 3792 2177 3792 2177 3793 2189 3793 2188 3793 2189 3794 2183 3794 2184 3794 2189 3795 2180 3795 2183 3795 2189 3796 2177 3796 2179 3796 2179 3797 2180 3797 2189 3797 2169 3798 2170 3798 2187 3798 2170 3799 2186 3799 2187 3799 2187 3800 2176 3800 2169 3800 2176 3801 2168 3801 2169 3801 2190 3802 2191 3802 2192 3802 2192 3803 2193 3803 2190 3803 2192 3804 2194 3804 2193 3804 2194 3805 2164 3805 2193 3805 2150 3806 2195 3806 1558 3806 2151 3807 2154 3807 2150 3807 2196 3808 2195 3808 2150 3808 2197 3809 2150 3809 2154 3809 2150 3810 2197 3810 2196 3810 2197 3811 2191 3811 2196 3811 2197 3812 2192 3812 2191 3812 2154 3813 2198 3813 2197 3813 2194 3814 2197 3814 2198 3814 2197 3815 2194 3815 2192 3815 2198 3816 2199 3816 2194 3816 2164 3817 2194 3817 2199 3817 2155 3818 2154 3818 2153 3818 2155 3819 2156 3819 2198 3819 2200 3820 2198 3820 2156 3820 2156 3821 2157 3821 2200 3821 2157 3822 2199 3822 2200 3822 2157 3823 2090 3823 2199 3823 2164 3824 2199 3824 2090 3824 2154 3825 2155 3825 2198 3825 2199 3826 2198 3826 2200 3826 2201 3827 2202 3827 2203 3827 2167 3828 2171 3828 2204 3828 2205 3829 2204 3829 2171 3829 2205 3830 2206 3830 2204 3830 2205 3831 2171 3831 2207 3831 2171 3832 2172 3832 2207 3832 2207 3833 2208 3833 2205 3833 2209 3834 2206 3834 2205 3834 2210 3835 2205 3835 2211 3835 2205 3836 2208 3836 2211 3836 2205 3837 2210 3837 2209 3837 2210 3838 2212 3838 2209 3838 2211 3839 2213 3839 2210 3839 2214 3840 2212 3840 2210 3840 2210 3841 2215 3841 1554 3841 2210 3842 2213 3842 2215 3842 2210 3843 1554 3843 2214 3843 2184 3844 2182 3844 2216 3844 2217 3845 2182 3845 2218 3845 2219 3846 2220 3846 2201 3846 1558 3847 2195 3847 1554 3847 2195 3848 2221 3848 1554 3848 2195 3849 2214 3849 2221 3849 2195 3850 2212 3850 2214 3850 2209 3851 2212 3851 2195 3851 2195 583 2196 583 2209 583 2196 3852 2206 3852 2209 3852 2196 583 2204 583 2206 583 2167 3853 2204 3853 2196 3853 2196 3854 2191 3854 2167 3854 2165 3855 2167 3855 2191 3855 2191 3856 2190 3856 2165 3856 2190 3857 2222 3857 2165 3857 2190 3858 2223 3858 2222 3858 1656 3859 2184 3859 2216 3859 2072 3860 1665 3860 1664 3860 1665 3861 2072 3861 2224 3861 2008 3862 1854 3862 1850 3862 2008 3863 1850 3863 1872 3863 1858 3864 1854 3864 2008 3864 1858 3865 1979 3865 2225 3865 1979 3866 2226 3866 2225 3866 2227 3867 2225 3867 2226 3867 1801 3868 1803 3868 2227 3868 2226 182 1801 182 2227 182 1801 3869 2072 3869 1664 3869 2184 3870 1656 3870 2228 3870 2189 3871 2184 3871 2228 3871 2229 64 1601 64 1551 64 2230 3872 1444 3872 2229 3872 1551 3873 2230 3873 2229 3873 1444 3874 2230 3874 2231 3874 1444 3875 2231 3875 2232 3875 1444 3876 2232 3876 2233 3876 1444 3877 2233 3877 2234 3877 1444 3878 2234 3878 2235 3878 1655 3879 1444 3879 2235 3879 2235 3880 2236 3880 1655 3880 1655 3881 2236 3881 2237 3881 1655 3882 2237 3882 2238 3882 1655 3883 2238 3883 2228 3883 1656 3884 1655 3884 2228 3884 2215 3885 1551 3885 1554 3885 2230 3886 1551 3886 2215 3886 2215 3887 2213 3887 2230 3887 2230 3888 2213 3888 2211 3888 2231 3889 2230 3889 2211 3889 2211 3890 2208 3890 2231 3890 2232 3891 2231 3891 2208 3891 2208 3892 2207 3892 2232 3892 2233 3893 2232 3893 2207 3893 2172 3894 2233 3894 2207 3894 2234 3895 2233 3895 2172 3895 2234 3896 2172 3896 2173 3896 2235 3897 2234 3897 2173 3897 2173 3898 2174 3898 2235 3898 2236 3899 2235 3899 2174 3899 2236 3900 2174 3900 2175 3900 2236 3901 2175 3901 2237 3901 2188 3902 2237 3902 2175 3902 2238 3903 2237 3903 2188 3903 2238 3904 2188 3904 2189 3904 2228 3905 2238 3905 2189 3905 1447 3906 1444 3906 1655 3906 1554 3907 1551 3907 1552 3907 1858 3908 1861 3908 1860 3908 1444 3909 1601 3909 2229 3909 2043 3910 2008 3910 1872 3910 1858 3911 2008 3911 2009 3911 1858 3912 2009 3912 2011 3912 1858 3913 2011 3913 2013 3913 1858 3914 2013 3914 2015 3914 1858 3915 2015 3915 2017 3915 1858 3916 2017 3916 2019 3916 1858 3917 2019 3917 1979 3917 2071 182 2070 182 1999 182 1999 3918 2070 3918 2069 3918 1999 3919 2069 3919 2068 3919 1999 3920 2068 3920 2067 3920 1999 3921 2067 3921 2066 3921 1999 3922 2066 3922 2065 3922 1999 3923 2065 3923 2064 3923 1999 3924 2064 3924 2239 3924 1999 3925 2239 3925 2240 3925 1999 3926 2240 3926 2241 3926 1999 3927 2241 3927 2242 3927 2243 3928 2244 3928 2245 3928 2243 3929 2216 3929 2217 3929 2244 3930 2243 3930 2217 3930 2243 3931 1656 3931 2216 3931 2246 3932 2247 3932 2142 3932 2248 3933 2247 3933 2246 3933 2249 3934 2250 3934 2248 3934 2219 3935 2201 3935 2203 3935 2219 3936 2251 3936 2220 3936 2251 3937 2252 3937 2253 3937 2252 3938 2217 3938 2218 3938 2217 3939 2216 3939 2182 3939 2143 3940 2144 3940 2163 3940 2142 3941 2143 3941 2254 3941 1999 496 2255 496 1967 496 2256 3942 2257 3942 2250 3942 2244 3943 2258 3943 2259 3943 2257 3944 2259 3944 2258 3944 2250 3945 2260 3945 2248 3945 2261 3946 2248 3946 2260 3946 2260 3947 2219 3947 2261 3947 2203 3948 2261 3948 2219 3948 2262 3949 2219 3949 2260 3949 2260 3950 2250 3950 2257 3950 2262 3951 2260 3951 2257 3951 2251 3952 2219 3952 2262 3952 2257 3953 2258 3953 2262 3953 2262 3954 2258 3954 2251 3954 2252 3955 2251 3955 2258 3955 2258 3956 2244 3956 2252 3956 2217 3957 2252 3957 2244 3957 2071 583 1999 583 2000 583 2247 3958 2141 3958 2142 3958 2112 3959 2263 3959 2264 3959 2263 3960 2265 3960 2264 3960 2265 3961 2266 3961 2264 3961 2247 3962 2264 3962 2141 3962 2140 3963 2107 3963 2106 3963 2141 3964 2266 3964 2140 3964 2141 3965 2264 3965 2266 3965 2140 3966 2106 3966 2132 3966 2226 3967 1979 3967 1975 3967 2111 64 2112 64 2084 64 2110 3968 2111 3968 2082 3968 2109 3969 2108 3969 2107 3969 2107 3970 2267 3970 2109 3970 2110 3971 2109 3971 2267 3971 2265 3972 2111 3972 2110 3972 2267 3973 2265 3973 2110 3973 2111 3974 2265 3974 2263 3974 2112 3975 2111 3975 2263 3975 2265 3976 2267 3976 2266 3976 2090 3977 2088 3977 2112 3977 2140 3978 2266 3978 2267 3978 2140 3979 2267 3979 2107 3979 2226 3980 1975 3980 1801 3980 2165 3981 2268 3981 2170 3981 2268 3982 2269 3982 2170 3982 2202 3983 2269 3983 2268 3983 2201 3984 2269 3984 2202 3984 2177 3985 2270 3985 2178 3985 2185 3986 2270 3986 2177 3986 2270 3987 2181 3987 2178 3987 2271 3988 2181 3988 2270 3988 2272 3989 2271 3989 2270 3989 2220 3990 2253 3990 2270 3990 2253 3991 2272 3991 2270 3991 2225 3992 2227 3992 2273 3992 2227 3993 2274 3993 2273 3993 2227 3994 1803 3994 2274 3994 2225 3995 2275 3995 2276 3995 2225 3996 2277 3996 2275 3996 2225 3997 2278 3997 2277 3997 2225 3998 2279 3998 2278 3998 2225 3999 2280 3999 2279 3999 2225 4000 2281 4000 2280 4000 2225 4001 2282 4001 2281 4001 2225 4002 2283 4002 2282 4002 2225 64 2273 64 2283 64 2181 4003 2271 4003 2182 4003 2271 4004 2272 4004 2182 4004 2218 4005 2182 4005 2272 4005 2270 4006 2201 4006 2220 4006 2270 4007 2269 4007 2201 4007 2270 4008 2185 4008 2269 4008 2170 4009 2269 4009 2185 4009 2284 4010 2285 4010 1797 4010 2286 4011 1797 4011 2285 4011 2285 4012 2287 4012 2286 4012 2288 4013 2286 4013 2287 4013 2287 4014 2289 4014 2288 4014 2290 4015 2288 4015 2289 4015 2289 4016 2291 4016 2290 4016 1802 4017 1667 4017 2292 4017 1667 4018 2293 4018 2292 4018 2294 4019 2293 4019 1653 4019 2293 4020 1667 4020 1653 4020 2294 4021 2295 4021 2293 4021 2296 4022 2297 4022 2298 4022 2299 4023 2295 4023 2294 4023 2299 4024 2298 4024 2295 4024 2299 4025 2296 4025 2298 4025 1653 4026 1652 4026 2294 4026 2300 4027 2294 4027 1796 4027 2294 4028 1652 4028 1796 4028 2294 4029 2300 4029 2299 4029 2299 4030 2301 4030 2296 4030 2301 4031 2302 4031 2296 4031 2301 4032 2299 4032 2300 4032 1796 4033 1795 4033 2300 4033 2300 4034 1797 4034 2286 4034 2300 4035 1795 4035 1797 4035 2300 4036 2286 4036 2301 4036 2303 4037 2302 4037 2301 4037 2301 4038 2286 4038 2288 4038 2301 4039 2288 4039 2303 4039 2303 4040 2288 4040 2290 4040 2290 4041 2291 4041 2304 4041 2297 4042 2273 4042 2305 4042 2273 4043 2306 4043 2305 4043 2273 4044 2274 4044 2306 4044 2274 4045 1803 4045 2306 4045 2273 4046 2297 4046 2296 4046 2307 4047 2296 4047 2302 4047 2296 4048 2307 4048 2273 4048 2283 4049 2273 4049 2307 4049 2302 4050 2303 4050 2307 4050 2282 4051 2283 4051 2307 4051 2282 4052 2307 4052 2303 4052 2303 4053 2290 4053 2282 4053 2281 4054 2282 4054 2290 4054 2290 4055 2304 4055 2281 4055 2280 4056 2281 4056 2304 4056 2279 4057 2280 4057 2304 4057 1654 4058 1789 4058 1146 4058 1163 4059 1789 4059 1788 4059 1788 4060 1787 4060 1166 4060 1786 4061 1168 4061 1787 4061 1169 4062 1786 4062 1785 4062 1785 4063 1784 4063 1173 4063 2268 4064 2222 4064 2223 4064 2222 4065 2268 4065 2165 4065 1554 4066 2221 4066 2214 4066 2252 4067 2218 4067 2272 4067 2272 4068 2253 4068 2252 4068 2251 4069 2253 4069 2220 4069 1667 4070 1802 4070 1626 4070 1802 182 2292 182 1803 182 2306 182 1803 182 2292 182 2292 4071 2293 4071 2306 4071 2305 4072 2306 4072 2293 4072 2297 4073 2305 4073 2295 4073 2305 4074 2293 4074 2295 4074 2298 4075 2297 4075 2295 4075 1403 4076 2308 4076 1148 4076 1148 4077 2308 4077 2309 4077 1148 4078 2309 4078 2310 4078 1148 4079 2310 4079 2311 4079 1148 64 2311 64 2312 64 1148 4080 2312 4080 2313 4080 1148 4081 2313 4081 2314 4081 1148 4082 2314 4082 2315 4082 1146 64 1148 64 2315 64 1146 4083 2315 4083 2316 4083 1146 4084 2316 4084 2317 4084 1146 4085 2317 4085 2318 4085 1146 64 2318 64 2319 64 1146 4086 2319 4086 2320 4086 1146 4087 2320 4087 2284 4087 1146 4088 2284 4088 1797 4088 1654 4089 1146 4089 1797 4089 2321 4090 1176 4090 1793 4090 1784 4091 1793 4091 1176 4091 1176 4092 1173 4092 1784 4092 1169 4093 1785 4093 1173 4093 1169 4094 1168 4094 1786 4094 1168 4095 1166 4095 1787 4095 1166 4096 1163 4096 1788 4096 1789 4097 1163 4097 1146 4097 2322 4098 2323 4098 2324 4098 2322 4099 2324 4099 2325 4099 2326 4100 2322 4100 2325 4100 2327 4101 2323 4101 2322 4101 2328 4102 2329 4102 2327 4102 2322 4103 2328 4103 2327 4103 2330 4104 2329 4104 2328 4104 2328 4105 2331 4105 2330 4105 2332 4106 2330 4106 2331 4106 2333 4107 2332 4107 2331 4107 2334 4108 2333 4108 2331 4108 2331 4109 2335 4109 2334 4109 2336 4110 2335 4110 2331 4110 2337 4111 2338 4111 2336 4111 2331 4112 2337 4112 2336 4112 2338 4113 2339 4113 2336 4113 2340 4114 2341 4114 2342 4114 2341 4115 2343 4115 2342 4115 2343 4116 2344 4116 2342 4116 2342 4117 2344 4117 2345 4117 2346 4118 2335 4118 2336 4118 2336 4119 2339 4119 2340 4119 2336 4120 2340 4120 2342 4120 2346 4121 2336 4121 2342 4121 2342 4122 2345 4122 2347 4122 2346 4123 2342 4123 2348 4123 2291 4124 2349 4124 2350 4124 2275 4125 2350 4125 2349 4125 2276 4126 2275 4126 2349 4126 2349 4127 2351 4127 2276 4127 2352 4128 2276 4128 2351 4128 2351 4129 2326 4129 2352 4129 2352 4130 2326 4130 2325 4130 2324 4131 2352 4131 2325 4131 2304 4132 2350 4132 2275 4132 2350 4133 2304 4133 2291 4133 2275 4134 2277 4134 2304 4134 2277 4135 2278 4135 2304 4135 2278 4136 2279 4136 2304 4136 2353 4137 2326 4137 2351 4137 2353 4138 2351 4138 2349 4138 2349 4139 2291 4139 2289 4139 2353 4140 2349 4140 2289 4140 2354 4141 2326 4141 2353 4141 2353 4142 2355 4142 2354 4142 2355 4143 2353 4143 2289 4143 2289 4144 2287 4144 2355 4144 2356 4145 2354 4145 2355 4145 2287 4146 2285 4146 2355 4146 2355 4147 2357 4147 2356 4147 2357 4148 2355 4148 2285 4148 2357 4149 2320 4149 2356 4149 2320 4150 2357 4150 2285 4150 2317 4151 2356 4151 2320 4151 2285 4152 2284 4152 2320 4152 2320 4153 2319 4153 2318 4153 2320 4154 2318 4154 2317 4154 2354 4155 2331 4155 2328 4155 2354 4156 2328 4156 2322 4156 2326 4157 2354 4157 2322 4157 2358 4158 2331 4158 2354 4158 2354 4159 2356 4159 2358 4159 2359 4160 2358 4160 2356 4160 2356 4161 2317 4161 2359 4161 2359 4162 2317 4162 2316 4162 2359 4163 2316 4163 2315 4163 1131 4164 1422 4164 1403 4164 2360 4165 2361 4165 2362 4165 2363 4166 2360 4166 2362 4166 2364 4167 2365 4167 2361 4167 2360 4168 2364 4168 2361 4168 2365 4169 2364 4169 2366 4169 2367 4170 2365 4170 2366 4170 2368 4171 2369 4171 2367 4171 2366 4172 2368 4172 2367 4172 2370 4173 2369 4173 2368 4173 2344 4174 2370 4174 2345 4174 2371 4175 2345 4175 2370 4175 2368 4176 2371 4176 2370 4176 2345 4177 2371 4177 2347 4177 2372 4178 2313 4178 2312 4178 2372 4179 2312 4179 2311 4179 2372 4180 2311 4180 2310 4180 2373 4181 2372 4181 2310 4181 2373 4182 2340 4182 2339 4182 2373 4183 2339 4183 2338 4183 2373 4184 2338 4184 2337 4184 2373 4185 2337 4185 2372 4185 2310 4186 2309 4186 2373 4186 2341 4187 2340 4187 2373 4187 2373 4188 2309 4188 2308 4188 2373 4189 2308 4189 1403 4189 2373 4190 1403 4190 2374 4190 2374 4191 2344 4191 2343 4191 2374 4192 2343 4192 2341 4192 2373 4193 2374 4193 2341 4193 2370 4194 2367 4194 2369 4194 2375 4195 2365 4195 2370 4195 2370 4196 2376 4196 2375 4196 2376 4197 2370 4197 2344 4197 2377 4198 2375 4198 2376 4198 2378 4199 2377 4199 2376 4199 2376 4200 2379 4200 2378 4200 2379 4201 2376 4201 2374 4201 2380 4202 2378 4202 2379 4202 2379 4203 2374 4203 1403 4203 2381 4204 2380 4204 2379 4204 2379 4205 1422 4205 2381 4205 1422 4206 2379 4206 1403 4206 1421 4207 2381 4207 1422 4207 2361 4208 2382 4208 2362 4208 2382 4209 2361 4209 2365 4209 2365 4210 2375 4210 2382 4210 1405 4211 2362 4211 2382 4211 2362 4212 1405 4212 2363 4212 2375 4213 2377 4213 2382 4213 1404 4214 2363 4214 1405 4214 2377 4215 2378 4215 2382 4215 1420 4216 2382 4216 2378 4216 2382 4217 1420 4217 1405 4217 2378 4218 2380 4218 1420 4218 2380 4219 2381 4219 1420 4219 1419 4220 1405 4220 1420 4220 2381 4221 1421 4221 1420 4221 1332 4222 2363 4222 1404 4222 2383 4223 2360 4223 2363 4223 2383 4224 2363 4224 1332 4224 2364 4225 2360 4225 2383 4225 1332 4226 2384 4226 2383 4226 2331 4227 2358 4227 2337 4227 2372 4228 2337 4228 2358 4228 2358 4229 2359 4229 2372 4229 2313 4230 2372 4230 2359 4230 2314 4231 2313 4231 2359 4231 2359 4232 2315 4232 2314 4232 2225 4233 2276 4233 2352 4233 2225 4234 2352 4234 2324 4234 2225 4235 2324 4235 2323 4235 2225 4236 2323 4236 2327 4236 2225 4237 2327 4237 2329 4237 2225 4238 2329 4238 2330 4238 2225 4239 2330 4239 2332 4239 2225 4240 2332 4240 2333 4240 2225 4241 2333 4241 2334 4241 2335 4242 2225 4242 2334 4242 2344 4243 2374 4243 2376 4243 2385 4244 2386 4244 2387 4244 2388 4245 1366 4245 1364 4245 2388 4246 1364 4246 1361 4246 2388 4247 1361 4247 1359 4247 2388 4248 1359 4248 1355 4248 2388 4249 1230 4249 1366 4249 1213 4250 2389 4250 2390 4250 1213 4251 2390 4251 2391 4251 1213 4252 2391 4252 2392 4252 2393 583 1213 583 2392 583 1225 4253 2394 4253 2395 4253 1218 4254 1225 4254 2395 4254 2396 4255 2394 4255 1225 4255 1225 4256 1226 4256 2396 4256 2397 4257 2396 4257 1226 4257 1226 4258 1227 4258 2397 4258 2398 4259 2397 4259 1227 4259 1227 4260 1228 4260 2398 4260 2398 4261 1228 4261 1229 4261 2399 4262 2398 4262 1229 4262 2400 4263 2399 4263 1229 4263 2388 4264 2400 4264 1229 4264 1230 4265 2388 4265 1229 4265 2395 4266 2401 4266 2402 4266 2403 4267 2402 4267 2401 4267 2401 4268 2404 4268 2403 4268 2405 4269 2403 4269 2404 4269 2404 4270 2406 4270 2405 4270 2407 4271 2405 4271 2406 4271 2408 4272 2409 4272 2407 4272 2406 4273 2408 4273 2407 4273 2410 4274 2409 4274 2408 4274 2408 4275 2411 4275 2410 4275 2412 4276 2410 4276 2411 4276 2411 4277 2413 4277 2412 4277 2414 4278 2412 4278 2413 4278 2415 4279 2389 4279 2414 4279 2413 4280 2415 4280 2414 4280 2390 4281 2389 4281 2415 4281 2415 4282 2416 4282 2390 4282 2391 4283 2390 4283 2416 4283 2416 4284 2417 4284 2391 4284 2392 4285 2391 4285 2417 4285 2417 4286 2393 4286 2392 4286 2386 4287 2418 4287 2419 4287 2420 4288 2419 4288 2421 4288 2422 4289 2420 4289 2423 4289 2422 4290 2424 4290 2425 4290 2426 4291 2422 4291 2425 4291 2425 4292 2427 4292 2426 4292 2426 4293 2427 4293 2428 4293 2429 4294 2426 4294 2428 4294 2429 4295 2428 4295 2430 4295 2431 4296 2429 4296 2430 4296 2430 4297 2432 4297 2431 4297 2433 4298 2431 4298 2432 4298 2432 4299 2434 4299 2433 4299 2435 4300 2436 4300 2437 4300 2437 4301 2436 4301 2438 4301 2437 4302 2438 4302 2439 4302 2437 4303 2439 4303 2440 4303 2437 4304 2440 4304 2441 4304 2441 4305 2442 4305 2437 4305 2437 4306 2442 4306 2443 4306 2437 4307 2443 4307 2444 4307 2437 4308 2444 4308 2445 4308 2437 4309 2445 4309 2446 4309 2437 4310 2398 4310 2399 4310 2437 4311 2399 4311 2400 4311 2437 4312 2400 4312 2388 4312 2437 4313 2388 4313 2447 4313 2437 4314 2447 4314 2448 4314 2437 4315 2448 4315 2435 4315 2446 4316 2449 4316 2437 4316 2437 4317 2449 4317 2397 4317 2397 4318 2398 4318 2437 4318 2449 4319 2450 4319 2397 4319 2396 4320 2397 4320 2450 4320 2450 4321 2451 4321 2396 4321 2394 4322 2396 4322 2451 4322 2451 4323 2452 4323 2394 4323 2394 4324 2452 4324 2393 4324 2395 4325 2394 4325 2393 4325 2393 4326 2417 4326 2395 4326 2401 4327 2395 4327 2417 4327 2417 4328 2416 4328 2401 4328 2404 4329 2401 4329 2416 4329 2416 4330 2415 4330 2404 4330 2453 4331 2454 4331 2455 4331 2455 4332 2454 4332 2456 4332 2457 4333 2458 4333 2459 4333 2453 4334 2455 4334 2460 4334 2453 4335 2460 4335 2457 4335 2453 4336 2457 4336 2459 4336 2461 4337 2453 4337 2459 4337 2462 4338 2461 4338 2459 4338 2463 4339 2462 4339 2459 4339 2464 4340 2463 4340 2459 4340 2459 4341 2458 4341 2387 4341 2459 4342 2387 4342 2386 4342 2459 4343 2386 4343 2419 4343 2459 4344 2419 4344 2420 4344 2459 4345 2420 4345 2422 4345 2465 4346 2464 4346 2459 4346 2426 4347 2465 4347 2459 4347 2422 4348 2426 4348 2459 4348 2466 4349 2465 4349 2426 4349 2426 4350 2429 4350 2466 4350 2467 4351 2466 4351 2429 4351 2429 4352 2431 4352 2467 4352 2468 4353 2467 4353 2431 4353 2458 4354 2448 4354 2447 4354 2387 4355 2458 4355 2447 4355 2435 4356 2448 4356 2458 4356 2458 4357 2457 4357 2435 4357 2436 4358 2435 4358 2457 4358 2457 4359 2460 4359 2436 4359 2438 4360 2436 4360 2460 4360 2460 4361 2455 4361 2438 4361 2469 4362 2438 4362 2455 4362 2455 4363 2456 4363 2469 4363 2470 4364 2469 4364 2456 4364 2471 4365 2472 4365 2470 4365 2456 4366 2471 4366 2470 4366 2473 4367 2472 4367 2471 4367 2474 4368 2475 4368 2473 4368 2471 4369 2474 4369 2473 4369 2474 4370 2476 4370 2475 4370 2439 4371 2475 4371 2476 4371 1276 4372 2477 4372 2478 4372 2479 4373 2480 4373 2477 4373 2481 4374 2479 4374 2477 4374 2482 4375 2481 4375 2477 4375 1276 182 2442 182 2477 182 2483 4376 2482 4376 2477 4376 2484 4377 2483 4377 2477 4377 2485 4378 2484 4378 2477 4378 2486 182 2485 182 2477 182 2441 4379 2486 4379 2477 4379 2442 4380 2441 4380 2477 4380 2487 4381 2486 4381 2441 4381 2488 4382 2489 4382 2487 4382 2441 4383 2488 4383 2487 4383 2453 4384 2461 4384 2490 4384 2061 182 2489 182 2490 182 2059 182 2061 182 2490 182 2461 4385 2491 4385 2490 4385 2393 4386 2452 4386 1213 4386 1212 4387 1213 4387 2452 4387 2452 4388 2451 4388 1212 4388 1212 4389 2451 4389 1211 4389 2451 4390 2450 4390 1211 4390 1210 4391 1211 4391 2450 4391 2450 4392 2449 4392 1210 4392 2449 4393 2446 4393 1210 4393 1209 4394 1210 4394 2446 4394 2446 4395 2445 4395 1209 4395 1206 4396 1209 4396 2445 4396 2444 4397 1206 4397 2445 4397 2443 4398 1206 4398 2444 4398 2442 4399 1206 4399 2443 4399 1276 4400 1206 4400 2442 4400 2060 4401 2063 4401 2061 4401 2489 4402 2061 4402 2063 4402 2062 4403 2492 4403 2063 4403 2492 4404 2062 4404 1983 4404 2493 4405 2063 4405 2492 4405 2063 4406 2493 4406 2489 4406 2487 4407 2489 4407 2493 4407 2476 4408 2488 4408 2494 4408 2495 4409 2488 4409 2476 4409 2476 4410 2496 4410 2495 4410 2497 4411 2495 4411 2496 4411 2496 4412 2454 4412 2497 4412 2497 4413 2454 4413 2453 4413 2454 4414 2474 4414 2471 4414 2456 4415 2454 4415 2471 4415 2438 4416 2469 4416 2470 4416 2438 4417 2470 4417 2472 4417 2438 4418 2472 4418 2473 4418 2438 4419 2473 4419 2475 4419 2438 4420 2475 4420 2439 4420 2453 4421 2490 4421 2497 4421 2490 4422 2495 4422 2497 4422 2488 4423 2495 4423 2490 4423 2488 4424 2490 4424 2489 4424 2440 4425 2488 4425 2441 4425 2440 4426 2494 4426 2488 4426 2439 4427 2494 4427 2440 4427 2476 4428 2494 4428 2439 4428 2454 4429 2496 4429 2474 4429 2496 4430 2476 4430 2474 4430 1218 4431 2395 4431 2402 4431 1218 4432 2402 4432 2403 4432 1218 4433 2403 4433 2405 4433 1218 4434 2405 4434 2407 4434 1218 4435 2407 4435 2409 4435 1218 4436 2409 4436 1213 4436 2410 583 1213 583 2409 583 2410 4437 2412 4437 1213 4437 2412 583 2414 583 1213 583 2414 4438 2389 4438 1213 4438 2498 4439 2499 4439 2500 4439 2498 4440 2501 4440 2499 4440 2502 4441 2499 4441 2501 4441 2503 4442 2502 4442 2501 4442 2503 4443 2501 4443 2504 4443 2505 4444 2503 4444 2504 4444 2501 4445 2506 4445 2507 4445 2498 4446 2506 4446 2501 4446 2508 4447 2509 4447 2510 4447 2511 4448 2512 4448 2513 4448 2514 4449 2515 4449 2246 4449 2516 4450 2517 4450 2518 4450 2515 4451 2518 4451 2517 4451 2517 4452 2249 4452 2515 4452 2246 4453 2515 4453 2249 4453 2519 4454 2517 4454 2516 4454 2520 4455 2517 4455 2519 4455 2520 4456 2249 4456 2517 4456 2520 4457 2256 4457 2249 4457 2259 4458 2520 4458 2521 4458 2520 4459 2519 4459 2521 4459 2520 4460 2259 4460 2256 4460 2522 4461 2259 4461 2523 4461 2259 4462 2521 4462 2523 4462 2523 4463 2245 4463 2522 4463 2524 4464 2525 4464 2526 4464 2525 4465 2527 4465 2526 4465 2528 4466 2529 4466 2530 4466 2531 4467 2530 4467 2529 4467 2530 4468 2531 4468 2524 4468 2525 4469 2524 4469 2531 4469 2529 4470 2532 4470 2531 4470 2527 4471 2525 4471 2531 4471 2531 4472 2533 4472 2527 4472 2533 4473 2531 4473 2532 4473 2532 4474 2534 4474 2533 4474 2534 4475 2535 4475 2533 4475 2535 4476 2508 4476 2533 4476 2533 4477 2510 4477 2527 4477 2510 4478 2533 4478 2508 4478 2536 4479 2528 4479 2537 4479 2529 4480 2528 4480 2536 4480 2536 4481 2538 4481 2529 4481 2532 4482 2529 4482 2538 4482 2534 4483 2532 4483 2538 4483 2538 4484 2539 4484 2534 4484 2535 4485 2534 4485 2539 4485 2508 4486 2535 4486 2539 4486 2509 4487 2508 4487 2539 4487 2539 4488 2540 4488 2509 4488 2541 4489 2542 4489 2536 4489 2538 4490 2536 4490 2542 4490 2539 4491 2538 4491 2542 4491 2542 4492 2543 4492 2539 4492 2540 4493 2539 4493 2543 4493 2249 4494 2256 4494 2250 4494 2256 4495 2259 4495 2257 4495 2244 4496 2259 4496 2522 4496 2526 4497 2527 4497 2506 4497 2513 4498 2526 4498 2506 4498 2506 4499 2498 4499 2513 4499 2507 4500 2527 4500 2510 4500 2507 4501 2506 4501 2527 4501 2544 4502 2510 4502 2545 4502 2510 4503 2509 4503 2545 4503 2509 4504 2540 4504 2545 4504 2510 4505 2544 4505 2507 4505 2545 4506 2546 4506 2544 4506 2544 4507 2547 4507 2507 4507 2547 4508 2544 4508 2548 4508 2544 4509 2546 4509 2548 4509 2549 4510 2507 4510 2547 4510 2549 4511 2501 4511 2507 4511 2549 4512 2504 4512 2501 4512 2548 4513 2550 4513 2547 4513 2551 4514 2504 4514 2549 4514 2552 4515 2547 4515 2553 4515 2547 4516 2550 4516 2553 4516 2547 4517 2552 4517 2549 4517 2549 4518 2554 4518 2551 4518 2554 4519 2555 4519 2551 4519 2554 4520 2549 4520 2552 4520 2556 4521 2555 4521 2554 4521 2553 4522 2557 4522 2552 4522 2558 4523 2552 4523 2559 4523 2552 4524 2557 4524 2559 4524 2552 4525 2558 4525 2554 4525 2560 4526 2554 4526 2558 4526 2554 4527 2560 4527 2556 4527 2560 4528 2561 4528 2556 4528 2562 4529 2561 4529 2560 4529 2559 4530 2563 4530 2558 4530 2564 4531 2558 4531 2563 4531 2558 4532 2564 4532 2560 4532 2560 4533 2565 4533 2562 4533 2519 4534 2516 4534 2528 4534 2528 4535 2530 4535 2519 4535 2521 4536 2519 4536 2530 4536 2530 4537 2524 4537 2521 4537 2523 4538 2521 4538 2524 4538 2524 4539 2526 4539 2523 4539 2526 270 2513 270 2523 270 2245 4540 2523 4540 2513 4540 2566 4541 2505 4541 2504 4541 2504 4542 2551 4542 2566 4542 2567 4543 2566 4543 2551 4543 2551 4544 2555 4544 2567 4544 2568 4545 2567 4545 2555 4545 2555 4546 2556 4546 2568 4546 2569 4547 2568 4547 2556 4547 2556 4548 2561 4548 2569 4548 2570 4549 2569 4549 2561 4549 2561 4550 2562 4550 2570 4550 2570 4551 2562 4551 2571 4551 2246 4552 2249 4552 2248 4552 2572 4553 2246 4553 2142 4553 2572 4554 2254 4554 2246 4554 2254 4555 2514 4555 2246 4555 2528 4556 2516 4556 2537 4556 2516 4557 2536 4557 2537 4557 2516 4558 2541 4558 2536 4558 2518 4559 2541 4559 2516 4559 2573 4560 2511 4560 2500 4560 2513 4561 2500 4561 2511 4561 2500 4562 2499 4562 2574 4562 2499 4563 2502 4563 2575 4563 2502 4564 2503 4564 2576 4564 2503 583 2505 583 2577 583 2505 583 2566 583 2578 583 2566 4565 2567 4565 2579 4565 2567 4566 2568 4566 2580 4566 2568 583 2569 583 2581 583 2569 4567 2570 4567 2582 4567 2513 4568 2498 4568 2500 4568 2513 4569 2243 4569 2245 4569 2522 4570 2245 4570 2244 4570 2563 4571 2559 4571 2583 4571 2559 4572 2557 4572 2583 4572 2557 64 2553 64 2583 64 2553 4573 2543 4573 2583 4573 2553 4574 2550 4574 2543 4574 2550 4575 2548 4575 2543 4575 2548 4576 2546 4576 2543 4576 2546 4577 2545 4577 2543 4577 2545 4578 2540 4578 2543 4578 2584 4579 2585 4579 2586 4579 2587 4580 2585 4580 2584 4580 2588 4581 2585 4581 2587 4581 2589 4582 2585 4582 2588 4582 2589 4583 2583 4583 2585 4583 2590 64 2583 64 2589 64 2591 64 2583 64 2590 64 2563 64 2583 64 2591 64 2592 583 2582 583 2570 583 2582 4584 2581 4584 2569 4584 2581 583 2580 583 2568 583 2580 583 2579 583 2567 583 2579 583 2578 583 2566 583 2578 583 2577 583 2505 583 2577 4585 2576 4585 2503 4585 2576 583 2575 583 2502 583 2575 583 2574 583 2499 583 2574 4586 2573 4586 2500 4586 2593 4587 2586 4587 2585 4587 2575 4588 2594 4588 2595 4588 2575 4589 2595 4589 2596 4589 2574 4590 2575 4590 2596 4590 2575 4591 2576 4591 2594 4591 2576 4592 2577 4592 2594 4592 2578 4593 2579 4593 2597 4593 2598 4594 2597 4594 2579 4594 2579 4595 2580 4595 2598 4595 2599 4596 2598 4596 2580 4596 2580 4597 2581 4597 2599 4597 2600 4598 2599 4598 2581 4598 2581 4599 2582 4599 2600 4599 2601 4600 2600 4600 2582 4600 2582 4601 2592 4601 2601 4601 2571 4602 2601 4602 2592 4602 2592 4603 2570 4603 2571 4603 2595 4604 2602 4604 2603 4604 2596 4605 2595 4605 2603 4605 2604 4606 2605 4606 2606 4606 2602 4607 2604 4607 2606 4607 2602 4608 2595 4608 2594 4608 2602 4609 2594 4609 2604 4609 2607 4610 2605 4610 2604 4610 2607 4611 2586 4611 2593 4611 2607 4612 2593 4612 2605 4612 2584 4613 2586 4613 2607 4613 2607 4614 2604 4614 2608 4614 2609 4615 2607 4615 2608 4615 2609 4616 2587 4616 2584 4616 2607 4617 2609 4617 2584 4617 2608 4618 2610 4618 2609 4618 2604 4619 2594 4619 2597 4619 2608 4620 2604 4620 2597 4620 2610 4621 2608 4621 2597 4621 2597 4622 2598 4622 2610 4622 2588 4623 2587 4623 2609 4623 2611 4624 2589 4624 2588 4624 2609 4625 2611 4625 2588 4625 2611 4626 2609 4626 2610 4626 2610 4627 2598 4627 2599 4627 2612 4628 2610 4628 2599 4628 2610 4629 2612 4629 2611 4629 2599 4630 2600 4630 2612 4630 2590 4631 2589 4631 2611 4631 2564 4632 2591 4632 2590 4632 2611 4633 2564 4633 2590 4633 2564 4634 2611 4634 2612 4634 2612 4635 2565 4635 2564 4635 2612 4636 2600 4636 2601 4636 2565 4637 2612 4637 2601 4637 2601 4638 2571 4638 2565 4638 2563 4639 2591 4639 2564 4639 2565 4640 2571 4640 2562 4640 2564 4641 2565 4641 2560 4641 2613 4642 2163 4642 2095 4642 2163 4643 2254 4643 2143 4643 2254 4644 2572 4644 2142 4644 1963 4645 2614 4645 2615 4645 1963 4646 2615 4646 2004 4646 1963 4647 2004 4647 1964 4647 1967 4648 2255 4648 2616 4648 1963 496 1967 496 2616 496 2617 4649 2573 4649 2618 4649 2619 4650 2617 4650 2618 4650 2573 4651 2574 4651 2618 4651 2596 4652 2618 4652 2574 4652 2094 182 2096 182 2139 182 2139 4653 2002 4653 2003 4653 2139 4654 2003 4654 2620 4654 2139 4655 2620 4655 2621 4655 2094 4656 2139 4656 2095 4656 2095 4657 2139 4657 2613 4657 2622 4658 2623 4658 2624 4658 2625 4659 2624 4659 2623 4659 2625 4660 2623 4660 2139 4660 2626 4661 2625 4661 2139 4661 2614 4662 1963 4662 2621 4662 2617 4663 2619 4663 2621 4663 2621 4664 2619 4664 2627 4664 2621 4665 2627 4665 2628 4665 2621 4666 2628 4666 2629 4666 2621 4667 2629 4667 2630 4667 2621 4668 2630 4668 2626 4668 2139 4669 2621 4669 2626 4669 2004 4670 2615 4670 2003 4670 2620 4671 2003 4671 2615 4671 2615 4672 2614 4672 2620 4672 2621 4673 2620 4673 2614 4673 2630 4674 2631 4674 2625 4674 2626 4675 2630 4675 2625 4675 2630 4676 2629 4676 2631 4676 2632 4677 2631 4677 2629 4677 2629 4678 2628 4678 2632 4678 2633 4679 2632 4679 2628 4679 2628 4680 2627 4680 2633 4680 2618 4681 2633 4681 2627 4681 2627 4682 2619 4682 2618 4682 2596 4683 2603 4683 2618 4683 2602 4684 2606 4684 2603 4684 2593 4685 2634 4685 2605 4685 2605 4686 2635 4686 2606 4686 2635 4687 2605 4687 2634 4687 2632 4688 2606 4688 2635 4688 2631 4689 2635 4689 2634 4689 2635 4690 2631 4690 2632 4690 2634 4691 2625 4691 2631 4691 2634 4692 2593 4692 2636 4692 2636 4693 2624 4693 2634 4693 2625 4694 2634 4694 2624 4694 2585 4695 2636 4695 2593 4695 2585 4696 2637 4696 2636 4696 2624 4697 2636 4697 2637 4697 2624 4698 2637 4698 2622 4698 2577 4699 2597 4699 2594 4699 2578 4700 2597 4700 2577 4700 2603 4701 2633 4701 2618 4701 2603 4702 2606 4702 2633 4702 2606 4703 2632 4703 2633 4703 2638 4704 2639 4704 2640 4704 2641 4705 2642 4705 2643 4705 2641 4706 2643 4706 2638 4706 2640 4707 2641 4707 2638 4707 2644 4708 2645 4708 2646 4708 2647 4709 2646 4709 2645 4709 2645 4710 2648 4710 2647 4710 2649 4711 2647 4711 2648 4711 2648 4712 2650 4712 2649 4712 2651 4713 2649 4713 2650 4713 2650 4714 2652 4714 2651 4714 2653 4715 2651 4715 2652 4715 2652 4716 2654 4716 2653 4716 2655 4717 2653 4717 2654 4717 2654 4718 2656 4718 2655 4718 2657 4719 2655 4719 2656 4719 2656 4720 2658 4720 2657 4720 2659 4721 2657 4721 2658 4721 2658 4722 2660 4722 2659 4722 2659 4723 2660 4723 2661 4723 2662 583 2659 583 2661 583 2662 4724 2663 4724 2664 4724 2662 4725 2664 4725 2665 4725 2666 4726 2662 4726 2665 4726 2667 4727 2668 4727 2638 4727 2639 4728 2638 4728 2668 4728 2669 64 2670 64 2639 64 2668 64 2669 64 2639 64 2671 4729 2670 4729 2669 4729 2669 4730 2672 4730 2671 4730 2673 4731 2671 4731 2672 4731 2672 4732 2674 4732 2673 4732 2675 4733 2673 4733 2674 4733 2674 4734 2676 4734 2675 4734 2677 4735 2675 4735 2676 4735 2676 4736 2678 4736 2677 4736 2679 4737 2677 4737 2678 4737 2678 4738 2680 4738 2679 4738 2681 4739 2679 4739 2680 4739 2680 4740 2682 4740 2681 4740 2683 4741 2681 4741 2682 4741 2682 4742 2684 4742 2683 4742 2683 64 2684 64 2685 64 2686 64 2683 64 2685 64 2642 4743 2687 4743 2573 4743 2688 4744 2642 4744 2573 4744 2689 4745 2687 4745 2642 4745 2668 4746 2690 4746 2691 4746 2669 4747 2668 4747 2691 4747 2672 4748 2669 4748 2691 4748 2674 4749 2672 4749 2691 4749 2676 4750 2674 4750 2691 4750 2691 4751 2692 4751 2676 4751 2678 4752 2676 4752 2692 4752 2692 4753 2693 4753 2678 4753 2680 4754 2678 4754 2693 4754 2693 4755 2694 4755 2680 4755 2682 4756 2680 4756 2694 4756 2694 4757 2695 4757 2682 4757 2684 4758 2682 4758 2695 4758 2695 4759 2696 4759 2684 4759 2685 4760 2684 4760 2696 4760 2696 4761 2697 4761 2685 4761 2685 4762 2697 4762 2698 4762 2686 4763 2685 4763 2698 4763 2698 4764 2699 4764 2686 4764 2683 4765 2686 4765 2699 4765 2699 4766 2700 4766 2683 4766 2681 4767 2683 4767 2700 4767 2700 4768 2701 4768 2681 4768 2679 4769 2681 4769 2701 4769 2701 4770 2702 4770 2679 4770 2677 4771 2679 4771 2702 4771 2702 4772 2703 4772 2677 4772 2675 4773 2677 4773 2703 4773 2703 4774 2704 4774 2675 4774 2673 4775 2675 4775 2704 4775 2673 4776 2704 4776 2671 4776 2670 4777 2671 4777 2704 4777 2670 4778 2704 4778 2705 4778 2670 4779 2705 4779 2640 4779 2639 4780 2670 4780 2640 4780 2385 4781 2418 4781 2386 4781 2418 4782 2706 4782 2419 4782 2706 4783 2421 4783 2419 4783 2421 4784 2423 4784 2420 4784 2423 4785 2424 4785 2422 4785 2707 4786 2708 4786 2709 4786 2710 4787 2707 4787 2709 4787 2709 4788 2711 4788 2710 4788 2712 4789 2710 4789 2711 4789 2711 4790 2713 4790 2712 4790 2491 4791 2712 4791 2713 4791 2714 4792 2715 4792 2716 4792 2717 4793 2716 4793 2718 4793 2716 4794 2717 4794 2714 4794 2719 4795 2714 4795 2717 4795 2719 4796 2720 4796 2714 4796 2721 4797 2430 4797 2428 4797 2721 4798 2428 4798 2722 4798 2721 4799 2722 4799 2720 4799 2721 4800 2720 4800 2719 4800 2432 4801 2430 4801 2721 4801 2717 4802 2723 4802 2719 4802 2717 4803 2718 4803 2724 4803 2723 4804 2717 4804 2724 4804 2725 4805 2719 4805 2723 4805 2719 4806 2725 4806 2721 4806 2726 4807 2721 4807 2725 4807 2726 4808 2434 4808 2432 4808 2721 4809 2726 4809 2432 4809 2727 4810 2434 4810 2726 4810 2726 4811 2728 4811 2727 4811 2729 4812 2728 4812 2726 4812 2725 4813 2729 4813 2726 4813 2730 4814 2727 4814 2728 4814 2731 4815 2729 4815 2725 4815 2723 4816 2731 4816 2725 4816 2731 4817 2723 4817 2724 4817 2732 4818 2733 4818 2730 4818 2728 4819 2732 4819 2730 4819 2732 4820 2728 4820 2729 4820 2734 4821 2733 4821 2732 4821 2735 4822 2729 4822 2731 4822 2729 4823 2735 4823 2732 4823 2736 4824 2731 4824 2724 4824 2731 4825 2736 4825 2735 4825 2724 4826 2737 4826 2736 4826 2738 4827 2732 4827 2735 4827 2738 4828 2739 4828 2734 4828 2732 4829 2738 4829 2734 4829 2708 4830 2739 4830 2738 4830 2735 4831 2740 4831 2738 4831 2740 4832 2735 4832 2736 4832 2741 4833 2736 4833 2737 4833 2736 4834 2741 4834 2740 4834 2738 4835 2742 4835 2708 4835 2742 4836 2738 4836 2740 4836 2740 4837 2743 4837 2742 4837 2743 4838 2740 4838 2741 4838 2741 4839 2744 4839 2743 4839 2741 4840 2737 4840 2744 4840 2745 4841 2743 4841 2744 4841 2663 4842 2746 4842 2664 4842 2747 4843 2748 4843 2666 4843 2665 4844 2747 4844 2666 4844 2747 4845 2665 4845 2664 4845 2664 4846 2746 4846 2749 4846 2750 4847 2664 4847 2749 4847 2664 4848 2750 4848 2747 4848 2749 4849 2751 4849 2750 4849 2747 4850 2752 4850 2748 4850 2752 4851 2747 4851 2750 4851 2750 4852 2753 4852 2752 4852 2753 4853 2750 4853 2751 4853 2751 4854 2754 4854 2753 4854 2755 4855 2748 4855 2752 4855 2756 4856 2753 4856 2754 4856 2753 4857 2756 4857 2752 4857 2757 4858 2752 4858 2756 4858 2752 4859 2757 4859 2755 4859 2758 4860 2756 4860 2754 4860 2756 4861 2758 4861 2757 4861 2759 4862 2748 4862 2755 4862 2754 4863 2760 4863 2758 4863 2761 4864 2757 4864 2758 4864 2757 4865 2761 4865 2755 4865 2755 4866 2762 4866 2759 4866 2762 4867 2755 4867 2761 4867 2758 4868 2763 4868 2761 4868 2763 4869 2758 4869 2760 4869 2764 4870 2759 4870 2762 4870 2759 4871 2764 4871 2765 4871 2761 4872 2766 4872 2762 4872 2766 4873 2761 4873 2763 4873 2767 4874 2762 4874 2766 4874 2762 4875 2767 4875 2764 4875 2764 4876 2768 4876 2765 4876 2769 4877 2763 4877 2760 4877 2763 4878 2769 4878 2766 4878 2770 4879 2764 4879 2767 4879 2764 4880 2770 4880 2768 4880 2760 4881 2724 4881 2769 4881 2771 4882 2766 4882 2769 4882 2766 4883 2771 4883 2767 4883 2715 4884 2767 4884 2771 4884 2767 4885 2715 4885 2770 4885 2720 4886 2722 4886 2772 4886 2768 4887 2720 4887 2772 4887 2720 4888 2768 4888 2770 4888 2769 4889 2724 4889 2718 4889 2771 4890 2769 4890 2718 4890 2771 4891 2718 4891 2716 4891 2771 4892 2716 4892 2715 4892 2770 4893 2715 4893 2714 4893 2770 4894 2714 4894 2720 4894 2773 4895 2722 4895 2428 4895 2660 4896 2774 4896 2775 4896 2661 4897 2660 4897 2775 4897 2774 4898 2660 4898 2658 4898 2776 4899 2774 4899 2658 4899 2776 4900 2777 4900 2778 4900 2774 4901 2776 4901 2778 4901 2658 4902 2656 4902 2776 4902 2776 4903 2656 4903 2654 4903 2779 4904 2776 4904 2654 4904 2780 4905 2692 4905 2691 4905 2693 4906 2692 4906 2780 4906 2654 4907 2652 4907 2779 4907 2779 4908 2781 4908 2780 4908 2779 4909 2652 4909 2650 4909 2781 4910 2779 4910 2650 4910 2782 4911 2694 4911 2693 4911 2780 4912 2782 4912 2693 4912 2782 4913 2780 4913 2781 4913 2695 4914 2694 4914 2782 4914 2650 4915 2648 4915 2781 4915 2781 4916 2648 4916 2645 4916 2783 4917 2781 4917 2645 4917 2781 4918 2783 4918 2782 4918 2784 4919 2696 4919 2695 4919 2782 4920 2784 4920 2695 4920 2784 4921 2782 4921 2783 4921 2697 4922 2696 4922 2784 4922 2645 4923 2644 4923 2783 4923 2785 4924 2698 4924 2697 4924 2784 4925 2785 4925 2697 4925 2783 4926 2644 4926 2646 4926 2786 4927 2783 4927 2646 4927 2786 4928 2785 4928 2784 4928 2783 4929 2786 4929 2784 4929 2699 4930 2698 4930 2785 4930 2646 4931 2647 4931 2786 4931 2787 4932 2700 4932 2699 4932 2785 4933 2787 4933 2699 4933 2787 4934 2785 4934 2786 4934 2786 4935 2647 4935 2649 4935 2788 4936 2786 4936 2649 4936 2786 4937 2788 4937 2787 4937 2701 4938 2700 4938 2787 4938 2649 4939 2651 4939 2788 4939 2789 4940 2787 4940 2788 4940 2789 4941 2702 4941 2701 4941 2787 4942 2789 4942 2701 4942 2788 4943 2790 4943 2789 4943 2788 4944 2651 4944 2653 4944 2790 4945 2788 4945 2653 4945 2703 4946 2702 4946 2789 4946 2653 4947 2655 4947 2790 4947 2791 4948 2704 4948 2703 4948 2789 4949 2791 4949 2703 4949 2791 4950 2789 4950 2790 4950 2792 4951 2790 4951 2655 4951 2790 4952 2792 4952 2791 4952 2655 4953 2657 4953 2792 4953 2792 4954 2657 4954 2659 4954 2792 4955 2659 4955 2662 4955 2792 4956 2662 4956 2793 4956 2792 4957 2793 4957 2794 4957 2792 4958 2794 4958 2791 4958 2791 4959 2794 4959 2795 4959 2791 4960 2795 4960 2796 4960 2797 4961 2791 4961 2796 4961 2797 4962 2705 4962 2704 4962 2797 4963 2704 4963 2791 4963 2705 4964 2797 4964 2798 4964 2640 4965 2705 4965 2798 4965 2640 4966 2798 4966 2641 4966 2799 4967 2641 4967 2798 4967 2799 4968 2798 4968 2797 4968 2797 4969 2796 4969 2799 4969 2800 4970 2799 4970 2796 4970 2801 4971 2800 4971 2796 4971 2795 4972 2801 4972 2796 4972 2802 4973 2801 4973 2795 4973 2795 4974 2794 4974 2802 4974 2803 4975 2802 4975 2794 4975 2794 4976 2793 4976 2803 4976 2666 4977 2803 4977 2793 4977 2793 4978 2662 4978 2666 4978 2800 4979 2801 4979 2804 4979 2805 4980 2804 4980 2801 4980 2801 4981 2802 4981 2805 4981 2748 4982 2805 4982 2802 4982 2802 4983 2803 4983 2748 4983 2803 4984 2666 4984 2748 4984 2804 4985 2421 4985 2706 4985 2804 4986 2706 4986 2418 4986 2385 4987 2804 4987 2418 4987 2773 4988 2428 4988 2427 4988 2773 4989 2427 4989 2425 4989 2806 4990 2421 4990 2804 4990 2772 4991 2773 4991 2806 4991 2773 4992 2772 4992 2722 4992 2807 4993 2806 4993 2804 4993 2806 4994 2807 4994 2772 4994 2768 4995 2772 4995 2807 4995 2807 4996 2808 4996 2768 4996 2808 4997 2807 4997 2804 4997 2804 4998 2805 4998 2808 4998 2808 4999 2765 4999 2768 4999 2765 5000 2808 5000 2805 5000 2759 5001 2765 5001 2805 5001 2805 5002 2748 5002 2759 5002 2638 5003 2643 5003 2667 5003 2809 5004 2667 5004 2643 5004 2643 5005 2642 5005 2809 5005 2688 5006 2809 5006 2642 5006 2810 5007 2667 5007 2809 5007 2809 5008 2688 5008 2810 5008 2810 5009 2690 5009 2668 5009 2668 5010 2667 5010 2810 5010 2746 5011 2663 5011 2811 5011 2812 5012 2813 5012 2814 5012 2813 5013 2812 5013 2811 5013 2814 5014 2815 5014 2812 5014 2816 5015 2811 5015 2812 5015 2811 5016 2816 5016 2746 5016 2749 5017 2746 5017 2816 5017 2816 5018 2817 5018 2749 5018 2817 5019 2816 5019 2812 5019 2751 5020 2749 5020 2817 5020 2815 5021 2818 5021 2812 5021 2819 5022 2812 5022 2818 5022 2812 5023 2819 5023 2817 5023 2818 5024 2820 5024 2819 5024 2821 5025 2819 5025 2820 5025 2819 5026 2821 5026 2817 5026 2754 5027 2751 5027 2817 5027 2817 5028 2822 5028 2754 5028 2822 5029 2817 5029 2821 5029 2823 5030 2824 5030 2820 5030 2821 5031 2825 5031 2822 5031 2825 5032 2821 5032 2820 5032 2820 5033 2826 5033 2825 5033 2826 5034 2820 5034 2824 5034 2827 5035 2822 5035 2825 5035 2822 5036 2827 5036 2754 5036 2760 5037 2754 5037 2827 5037 2824 5038 2828 5038 2826 5038 2829 5039 2825 5039 2826 5039 2825 5040 2829 5040 2827 5040 2828 5041 2830 5041 2826 5041 2827 5042 2831 5042 2760 5042 2831 5043 2827 5043 2829 5043 2832 5044 2826 5044 2830 5044 2826 5045 2832 5045 2829 5045 2724 5046 2760 5046 2831 5046 2828 5047 2833 5047 2830 5047 2829 5048 2834 5048 2831 5048 2834 5049 2829 5049 2832 5049 2737 5050 2831 5050 2834 5050 2831 5051 2737 5051 2724 5051 2745 5052 2832 5052 2830 5052 2832 5053 2745 5053 2834 5053 2830 5054 2835 5054 2745 5054 2835 5055 2830 5055 2833 5055 2744 5056 2834 5056 2745 5056 2834 5057 2744 5057 2737 5057 2833 5058 2836 5058 2742 5058 2745 5059 2835 5059 2743 5059 2837 5060 2838 5060 2713 5060 2837 5061 2713 5061 2711 5061 2709 5062 2836 5062 2837 5062 2837 5063 2839 5063 2838 5063 2840 5064 2839 5064 2837 5064 2837 5065 2841 5065 2840 5065 2837 5066 2836 5066 2833 5066 2841 5067 2837 5067 2833 5067 2833 5068 2828 5068 2841 5068 2842 5069 2840 5069 2841 5069 2841 5070 2828 5070 2842 5070 2828 5071 2824 5071 2842 5071 2843 5072 2842 5072 2824 5072 2824 5073 2823 5073 2843 5073 2844 5074 2810 5074 2845 5074 2845 5075 2846 5075 2844 5075 2845 5076 2713 5076 2846 5076 2847 5077 2844 5077 2846 5077 2846 5078 2713 5078 2838 5078 2848 5079 2846 5079 2838 5079 2846 5080 2848 5080 2847 5080 2848 5081 2838 5081 2839 5081 2849 5082 2848 5082 2839 5082 2848 5083 2849 5083 2847 5083 2839 5084 2840 5084 2849 5084 2850 5085 2847 5085 2849 5085 2849 5086 2851 5086 2850 5086 2851 5087 2849 5087 2840 5087 2851 5088 2840 5088 2842 5088 2852 5089 2850 5089 2851 5089 2851 5090 2853 5090 2852 5090 2853 5091 2851 5091 2842 5091 2854 5092 2852 5092 2853 5092 2853 5093 2842 5093 2843 5093 2853 5094 2818 5094 2854 5094 2853 5095 2843 5095 2823 5095 2818 5096 2853 5096 2823 5096 2854 5097 2818 5097 2815 5097 2814 5098 2854 5098 2815 5098 2823 5099 2820 5099 2818 5099 2810 5100 2855 5100 2690 5100 2844 5101 2855 5101 2810 5101 2847 5102 2777 5102 2855 5102 2844 5103 2847 5103 2855 5103 2850 5104 2778 5104 2777 5104 2847 5105 2850 5105 2777 5105 2850 5106 2852 5106 2778 5106 2774 5107 2778 5107 2852 5107 2852 5108 2854 5108 2774 5108 2775 5109 2774 5109 2854 5109 2854 5110 2814 5110 2775 5110 2661 5111 2775 5111 2814 5111 2690 5112 2855 5112 2691 5112 2691 5113 2855 5113 2777 5113 2777 5114 2856 5114 2691 5114 2856 5115 2780 5115 2691 5115 2779 5116 2856 5116 2776 5116 2780 5117 2856 5117 2779 5117 2776 5118 2856 5118 2777 5118 2424 5119 2773 5119 2425 5119 2423 5120 2773 5120 2424 5120 2421 5121 2806 5121 2423 5121 2423 5122 2806 5122 2773 5122 2799 5123 2800 5123 2804 5123 2641 5124 2799 5124 2804 5124 2641 5125 2804 5125 2857 5125 2857 5126 2804 5126 2858 5126 2385 5127 2858 5127 2804 5127 2661 5128 2814 5128 2813 5128 2661 5129 2813 5129 2811 5129 2661 5130 2811 5130 2663 5130 2661 5131 2663 5131 2662 5131 2742 5132 2743 5132 2835 5132 2742 5133 2835 5133 2833 5133 2708 5134 2742 5134 2836 5134 2708 5135 2836 5135 2709 5135 2711 5136 2709 5136 2837 5136 2859 5137 2049 5137 2057 5137 2859 5138 2860 5138 2049 5138 2050 5139 2049 5139 2860 5139 2860 5140 2861 5140 2050 5140 2861 5141 2862 5141 2050 5141 2617 5142 2861 5142 2860 5142 2862 5143 2861 5143 2617 5143 2621 5144 2863 5144 2617 5144 2621 5145 1963 5145 2863 5145 2616 5146 2863 5146 1963 5146 2239 5147 2064 5147 2862 5147 2064 5148 2050 5148 2862 5148 2240 5149 2239 5149 2862 5149 2241 5150 2240 5150 2862 5150 2242 5151 2241 5151 2862 5151 2864 5152 2242 5152 2862 5152 2865 5153 2864 5153 2863 5153 2864 5154 2617 5154 2863 5154 2864 5155 2862 5155 2617 5155 2617 5156 2688 5156 2573 5156 2617 5157 2810 5157 2688 5157 2617 5158 2860 5158 2810 5158 2810 5159 2860 5159 2845 5159 2860 5160 2859 5160 2713 5160 2713 5161 2845 5161 2860 5161 2859 5162 2057 5162 2713 5162 2057 5163 2491 5163 2713 5163 2057 5164 2059 5164 2490 5164 2490 5165 2491 5165 2057 5165 2866 5166 2513 5166 2512 5166 2512 5167 2687 5167 2866 5167 2689 5168 2866 5168 2687 5168 2512 5169 2511 5169 2573 5169 2512 5170 2573 5170 2687 5170 2255 5171 1999 5171 2865 5171 1999 5172 2864 5172 2865 5172 1999 5173 2242 5173 2864 5173 2046 5174 2047 5174 2867 5174 1934 5175 1962 5175 2868 5175 2869 5176 2870 5176 2871 5176 2872 5177 2871 5177 2870 5177 2870 5178 2873 5178 2872 5178 2874 5179 2872 5179 2873 5179 2873 5180 2875 5180 2874 5180 1861 5181 2874 5181 1863 5181 2874 5182 2875 5182 1863 5182 2876 5183 2877 5183 2878 5183 2879 5184 2878 5184 2877 5184 2877 5185 2880 5185 2879 5185 2881 5186 2879 5186 2880 5186 2880 5187 2882 5187 2881 5187 2883 5188 2881 5188 2882 5188 2882 5189 2884 5189 2883 5189 2885 5190 2883 5190 2884 5190 2884 5191 2869 5191 2885 5191 2871 5192 2885 5192 2869 5192 2878 5193 2886 5193 2876 5193 2487 5194 2887 5194 2486 5194 2493 5195 2888 5195 2887 5195 2493 5196 2887 5196 2487 5196 2492 5197 2889 5197 2888 5197 2492 5198 2890 5198 2889 5198 2888 5199 2493 5199 2492 5199 1983 5200 2890 5200 2492 5200 2891 5201 2892 5201 2893 5201 2892 5202 2894 5202 2895 5202 2894 5203 2889 5203 2895 5203 2894 5204 2888 5204 2889 5204 2894 5205 2892 5205 2896 5205 2892 5206 2891 5206 2896 5206 2896 5207 2897 5207 2894 5207 2894 5208 2898 5208 2888 5208 2898 5209 2887 5209 2888 5209 2898 5210 2894 5210 2899 5210 2894 5211 2897 5211 2899 5211 2899 5212 2900 5212 2898 5212 2898 5213 2901 5213 2902 5213 2898 5214 2900 5214 2901 5214 2898 5215 2902 5215 2887 5215 2902 5216 2486 5216 2887 5216 2903 5217 2486 5217 2902 5217 2903 5218 2485 5218 2486 5218 2484 5219 2485 5219 2903 5219 2903 5220 2904 5220 2484 5220 2483 5221 2484 5221 2905 5221 2484 5222 2906 5222 2905 5222 2484 5223 2904 5223 2906 5223 1874 5224 1876 5224 2907 5224 2907 5225 2908 5225 2909 5225 2908 5226 2910 5226 2909 5226 2908 5227 2911 5227 2910 5227 2908 5228 2907 5228 1876 5228 2912 5229 2911 5229 2908 5229 1876 5230 1881 5230 2908 5230 2908 5231 2913 5231 2912 5231 2913 5232 2914 5232 2912 5232 2913 5233 2908 5233 1882 5233 2908 5234 1881 5234 1882 5234 2915 5235 2914 5235 2913 5235 1882 5236 1888 5236 2913 5236 2916 5237 2913 5237 1891 5237 2913 5238 1888 5238 1891 5238 2913 5239 2916 5239 2915 5239 2916 5240 2917 5240 2915 5240 2918 5241 2917 5241 2916 5241 1891 5242 1893 5242 2916 5242 2867 5243 2916 5243 2046 5243 2916 5244 2045 5244 2046 5244 2916 5245 2042 5245 2045 5245 2916 5246 1893 5246 2042 5246 2916 5247 2867 5247 2918 5247 2044 5248 2918 5248 2048 5248 2918 5249 2047 5249 2048 5249 2918 5250 2867 5250 2047 5250 2910 5251 2911 5251 1872 5251 2919 5252 1872 5252 2911 5252 2911 5253 2912 5253 2919 5253 2920 5254 2919 5254 2912 5254 2912 5255 2914 5255 2920 5255 2921 5256 2920 5256 2914 5256 2914 5257 2915 5257 2921 5257 2922 5258 2921 5258 2915 5258 2915 5259 2917 5259 2922 5259 2923 5260 2922 5260 2917 5260 2917 5261 2918 5261 2923 5261 2924 5262 2923 5262 2918 5262 2918 5263 2044 5263 2924 5263 2043 5264 2924 5264 2044 5264 1852 5265 2910 5265 1872 5265 1852 5266 2909 5266 2910 5266 1852 5267 2907 5267 2909 5267 1852 5268 1874 5268 2907 5268 1876 5269 1874 5269 1875 5269 1981 5270 2890 5270 1983 5270 2889 5271 2890 5271 2925 5271 2890 5272 1981 5272 2925 5272 1914 5273 1981 5273 1910 5273 1913 5274 2926 5274 1914 5274 1917 5275 2926 5275 1913 5275 1916 5276 1934 5276 1917 5276 2927 5277 2889 5277 2925 5277 2927 5278 2895 5278 2889 5278 2927 5279 2925 5279 1914 5279 2925 5280 1981 5280 1914 5280 1914 5281 2926 5281 2927 5281 2928 5282 2927 5282 1917 5282 2927 5283 2926 5283 1917 5283 2927 5284 2928 5284 2895 5284 2928 5285 2892 5285 2895 5285 2893 5286 2892 5286 2928 5286 1917 5287 1934 5287 2928 5287 2928 5288 2929 5288 2893 5288 2929 5289 2928 5289 2868 5289 2928 5290 1934 5290 2868 5290 2483 5291 2905 5291 2482 5291 2930 5292 2481 5292 2482 5292 2481 5293 2930 5293 2479 5293 2482 5294 2931 5294 2930 5294 2931 5295 2482 5295 2905 5295 2932 5296 2479 5296 2930 5296 2905 5297 2906 5297 2931 5297 2933 5298 2479 5298 2932 5298 2480 5299 2479 5299 2933 5299 2933 5300 2934 5300 2480 5300 2935 5301 2936 5301 2937 5301 2938 5302 2937 5302 2939 5302 2937 5303 2936 5303 2939 5303 2939 5304 2940 5304 2938 5304 2941 5305 2938 5305 2940 5305 2938 5306 2941 5306 2942 5306 2941 5307 2943 5307 2942 5307 2944 5308 2943 5308 2941 5308 2383 5309 2941 5309 2364 5309 2941 5310 2366 5310 2364 5310 2941 5311 2940 5311 2366 5311 2941 5312 2383 5312 2944 5312 2383 5313 2384 5313 2944 5313 2371 5314 2936 5314 2347 5314 2371 5315 2368 5315 2936 5315 2368 5316 2939 5316 2936 5316 2940 5317 2939 5317 2368 5317 2368 5318 2366 5318 2940 5318 2480 5319 2934 5319 2477 5319 2934 5320 2945 5320 2477 5320 2945 5321 2946 5321 2477 5321 2946 5322 2947 5322 2477 5322 2947 5323 2935 5323 2477 5323 2935 5324 2937 5324 2477 5324 2937 5325 2938 5325 2477 5325 2938 5326 2478 5326 2477 5326 2478 182 1332 182 1292 182 2478 5327 2384 5327 1332 5327 2938 5328 2942 5328 2478 5328 2942 182 2943 182 2478 182 2943 182 2944 182 2478 182 2944 5329 2384 5329 2478 5329 2948 5330 2949 5330 2886 5330 2949 5331 2948 5331 2950 5331 2948 5332 2951 5332 2950 5332 2948 5333 2952 5333 2951 5333 2948 5334 2953 5334 2952 5334 2953 5335 2932 5335 2952 5335 2933 5336 2932 5336 2953 5336 2934 5337 2933 5337 2953 5337 2954 5338 2945 5338 2953 5338 2954 5339 2953 5339 2948 5339 2945 5340 2934 5340 2953 5340 2948 5341 2955 5341 2954 5341 2955 5342 2948 5342 2886 5342 2946 5343 2945 5343 2954 5343 2947 5344 2946 5344 2954 5344 2935 5345 2947 5345 2954 5345 2955 5346 2886 5346 2956 5346 2955 5347 2956 5347 2954 5347 2936 5348 2935 5348 2954 5348 2886 5349 2957 5349 2956 5349 2348 5350 2936 5350 2954 5350 2348 5351 2347 5351 2936 5351 2348 5352 2954 5352 2956 5352 2956 5353 2346 5353 2348 5353 2348 5354 2342 5354 2347 5354 2957 5355 2346 5355 2956 5355 2346 5356 2957 5356 2335 5356 2932 5357 2930 5357 2952 5357 2930 5358 2951 5358 2952 5358 2951 5359 2958 5359 2950 5359 2958 5360 2949 5360 2950 5360 2958 5361 2951 5361 2930 5361 2959 5362 2949 5362 2958 5362 2959 5363 2886 5363 2949 5363 2959 5364 2876 5364 2886 5364 2959 5365 2877 5365 2876 5365 2959 5366 2880 5366 2877 5366 2959 5367 2882 5367 2880 5367 2930 5368 2931 5368 2958 5368 2960 5369 2958 5369 2906 5369 2958 5370 2931 5370 2906 5370 2958 5371 2960 5371 2959 5371 2884 5372 2882 5372 2959 5372 2961 5373 2959 5373 2960 5373 2959 5374 2961 5374 2884 5374 2961 5375 2869 5375 2884 5375 2961 5376 2870 5376 2869 5376 2906 5377 2904 5377 2960 5377 2902 5378 2960 5378 2903 5378 2960 5379 2904 5379 2903 5379 2960 5380 2902 5380 2961 5380 2873 5381 2870 5381 2961 5381 2962 5382 2961 5382 2899 5382 2961 5383 2900 5383 2899 5383 2961 5384 2901 5384 2900 5384 2961 5385 2902 5385 2901 5385 2961 5386 2962 5386 2873 5386 2962 5387 2875 5387 2873 5387 2962 5388 1863 5388 2875 5388 2899 5389 2897 5389 2962 5389 2963 5390 2962 5390 2893 5390 2962 5391 2891 5391 2893 5391 2962 5392 2896 5392 2891 5392 2962 5393 2897 5393 2896 5393 2962 5394 2963 5394 1863 5394 2963 5395 1862 5395 1863 5395 2963 5396 1860 5396 1862 5396 2963 5397 1859 5397 1860 5397 2963 5398 1857 5398 1859 5398 2963 5399 1856 5399 1857 5399 2893 5400 2929 5400 2963 5400 1855 5401 1856 5401 2963 5401 2963 5402 1962 5402 1855 5402 1962 5403 2963 5403 2868 5403 2963 5404 2929 5404 2868 5404 1962 5405 1934 5405 1875 5405 2321 5406 1793 5406 2964 5406 2225 5407 2335 5407 1858 5407 2335 5408 1861 5408 1858 5408 2335 5409 2874 5409 1861 5409 2335 5410 2886 5410 2874 5410 2886 5411 2872 5411 2874 5411 2886 5412 2871 5412 2872 5412 2886 5413 2885 5413 2871 5413 2886 5414 2883 5414 2885 5414 2886 5415 2881 5415 2883 5415 2335 5416 2957 5416 2886 5416 2919 5417 2043 5417 1872 5417 2924 5418 2043 5418 2919 5418 2919 5419 2920 5419 2924 5419 2923 5420 2924 5420 2920 5420 2920 182 2921 182 2923 182 2922 182 2923 182 2921 182 2879 5421 2881 5421 2886 5421 2879 5422 2886 5422 2878 5422 1557 5423 2224 5423 2072 5423 1441 5424 1666 5424 1665 5424 1441 5425 1664 5425 1666 5425 1665 5426 2224 5426 1439 5426 1441 5427 1665 5427 1439 5427 1601 5428 1446 5428 1602 5428 1601 5429 1444 5429 1446 5429 2965 5430 2966 5430 2967 5430 2966 5431 2968 5431 2967 5431 2966 5432 2965 5432 1149 5432 1175 5433 1177 5433 2969 5433 2970 5434 2971 5434 2972 5434 2973 5435 2974 5435 2975 5435 2973 5436 2976 5436 2974 5436 2977 5437 2978 5437 2979 5437 2980 5438 2978 5438 2977 5438 2981 5439 2982 5439 2983 5439 2983 5440 2984 5440 2981 5440 2985 5441 2981 5441 2984 5441 2984 5442 2986 5442 2985 5442 2987 5443 2985 5443 2986 5443 2988 973 2978 973 2980 973 2988 5444 2989 5444 2978 5444 2989 5445 2979 5445 2978 5445 2975 5446 2989 5446 2988 5446 2988 5447 2990 5447 2975 5447 2990 5448 2991 5448 2975 5448 2992 5449 2975 5449 2991 5449 2991 5450 2993 5450 2992 5450 2994 981 2995 981 2996 981 2997 5451 2998 5451 2996 5451 2974 5452 2996 5452 2999 5452 2996 5453 2998 5453 2999 5453 2996 5454 2974 5454 2994 5454 2974 5455 3000 5455 2994 5455 2976 5456 3000 5456 2974 5456 2999 5457 3001 5457 2974 5457 2974 5458 2989 5458 2975 5458 2979 5459 2989 5459 2974 5459 2974 5460 3002 5460 2979 5460 2974 5461 3001 5461 3002 5461 2975 5462 3003 5462 2973 5462 3003 5463 2975 5463 2992 5463 2993 5464 3004 5464 2992 5464 3005 5465 2997 5465 3006 5465 3005 5466 2998 5466 2997 5466 3005 5467 2999 5467 2998 5467 3005 5468 3001 5468 2999 5468 3005 5469 3002 5469 3001 5469 3005 5470 2979 5470 3002 5470 2979 5471 3005 5471 2977 5471 2995 5472 2994 5472 3007 5472 2987 5473 3007 5473 2994 5473 2994 5474 3000 5474 2987 5474 2985 5475 2987 5475 2976 5475 2987 5476 3000 5476 2976 5476 2976 5477 2973 5477 2985 5477 2981 5478 2985 5478 3003 5478 2985 5479 2973 5479 3003 5479 3003 5480 2992 5480 2981 5480 2982 5481 2981 5481 2992 5481 2992 5482 3004 5482 2982 5482 3004 5483 1195 5483 1170 5483 2982 5484 3004 5484 1170 5484 2968 5485 3008 5485 2970 5485 2972 5486 2968 5486 2970 5486 3009 5487 3008 5487 2968 5487 3010 5488 3009 5488 2968 5488 3011 5489 3010 5489 2968 5489 3011 5490 2968 5490 3012 5490 1147 64 3013 64 3014 64 1147 5491 3014 5491 3015 5491 1147 64 3015 64 1149 64 1147 5492 3016 5492 3013 5492 3017 64 3013 64 3016 64 1174 5493 1175 5493 2969 5493 1174 5494 2969 5494 3018 5494 1174 5495 3018 5495 3019 5495 3020 5496 1174 5496 3019 5496 1171 5497 1174 5497 3020 5497 3020 5498 3021 5498 1171 5498 3020 5499 3019 5499 3022 5499 3021 5500 3020 5500 3022 5500 1172 5501 1171 5501 3021 5501 1170 5502 1172 5502 3021 5502 3021 5503 3023 5503 1170 5503 1170 5504 3023 5504 2982 5504 3024 5505 2980 5505 2977 5505 2977 5506 3025 5506 3024 5506 3025 5507 3026 5507 3024 5507 3016 5508 1147 5508 3027 5508 3027 5509 1165 5509 1167 5509 3027 5510 1167 5510 1195 5510 3028 5511 3027 5511 1195 5511 3004 5512 2993 5512 3028 5512 1195 5513 3004 5513 3028 5513 3029 5514 3017 5514 3030 5514 1149 5515 3015 5515 2966 5515 2966 5516 3029 5516 2968 5516 2966 5517 3015 5517 3014 5517 2966 5518 3014 5518 3013 5518 2966 5519 3013 5519 3029 5519 3017 5520 3029 5520 3013 5520 2968 5521 3029 5521 3012 5521 3021 1055 3031 1055 3032 1055 3021 5522 3032 5522 3023 5522 3033 5523 3031 5523 3021 5523 3021 5524 3022 5524 3033 5524 3033 5525 3022 5525 3019 5525 2983 5526 2982 5526 3023 5526 2983 5527 3023 5527 3032 5527 2971 5528 2970 5528 3034 5528 2970 5529 3008 5529 3035 5529 3036 5530 3035 5530 3008 5530 3008 5531 3009 5531 3036 5531 3037 5532 3036 5532 3009 5532 3009 5533 3010 5533 3037 5533 3038 5534 3037 5534 3010 5534 3010 5535 3011 5535 3038 5535 3039 5536 3038 5536 3011 5536 1164 5537 1165 5537 3027 5537 3012 5538 3040 5538 3041 5538 3012 5539 3042 5539 3040 5539 3043 5540 3040 5540 3042 5540 3026 5541 3040 5541 3043 5541 3026 5542 3025 5542 3040 5542 3025 5543 2977 5543 3040 5543 3005 5544 3040 5544 2977 5544 3044 5545 3040 5545 3005 5545 3045 5546 3040 5546 3044 5546 3046 5547 3040 5547 3045 5547 3041 5548 3040 5548 3046 5548 3026 5549 3043 5549 3024 5549 3024 5550 2988 5550 2980 5550 3024 5551 2990 5551 2988 5551 3024 1085 3047 1085 2990 1085 2991 5552 2990 5552 3047 5552 3028 5553 2991 5553 3047 5553 3048 5554 3028 5554 3047 5554 3048 5555 3047 5555 3049 5555 3043 5556 3047 5556 3024 5556 3043 5557 3049 5557 3047 5557 3046 5558 3011 5558 3041 5558 3048 5559 3049 5559 3050 5559 3050 5560 3049 5560 3051 5560 3011 5561 3046 5561 3039 5561 3030 5562 3043 5562 3042 5562 3042 5563 3012 5563 3030 5563 3030 5564 3012 5564 3029 5564 3043 5565 3030 5565 3049 5565 3030 5566 3017 5566 3051 5566 3030 5567 3051 5567 3049 5567 3027 5568 3028 5568 3048 5568 3027 5569 3048 5569 3050 5569 3027 5570 3050 5570 3051 5570 3041 5571 3011 5571 3012 5571 3028 5572 2993 5572 2991 5572 3016 5573 3051 5573 3017 5573 3016 5574 3027 5574 3051 5574 1164 5575 3027 5575 1147 5575 3052 5576 3053 5576 3054 5576 3052 5577 3054 5577 3055 5577 3056 5578 3052 5578 3055 5578 3057 5579 3053 5579 3052 5579 3052 5580 3058 5580 3057 5580 3057 5581 3058 5581 3059 5581 3060 5582 3057 5582 3059 5582 3060 5583 3061 5583 3057 5583 3059 5584 3062 5584 3060 5584 3063 5585 3060 5585 3062 5585 3064 5586 3063 5586 3062 5586 3064 5587 3065 5587 3066 5587 3063 5588 3064 5588 3066 5588 3067 5589 3068 5589 3069 5589 3070 5590 3068 5590 3067 5590 3067 5591 3071 5591 3070 5591 3072 5592 3070 5592 3071 5592 3071 5593 3073 5593 3072 5593 2971 5594 3072 5594 3073 5594 3074 5595 3075 5595 2972 5595 2972 5596 3073 5596 3074 5596 3073 5597 2972 5597 2971 5597 3076 5598 3077 5598 3078 5598 3075 5599 3076 5599 3078 5599 3075 5600 3078 5600 3079 5600 3075 5601 3079 5601 3080 5601 3075 5602 3080 5602 3081 5602 2967 1136 3075 1136 3081 1136 3075 5603 2967 5603 2972 5603 2972 5604 2967 5604 2968 5604 3082 182 3083 182 3084 182 1178 5605 1179 5605 2969 5605 1177 5606 1178 5606 2969 5606 3085 5607 1189 5607 3086 5607 1192 5608 1189 5608 3085 5608 3085 5609 3087 5609 1192 5609 1193 5610 1192 5610 3087 5610 3087 1145 3088 1145 1193 1145 1194 5611 1193 5611 3088 5611 3089 5612 3090 5612 1194 5612 3088 5613 3089 5613 1194 5613 3091 5614 3090 5614 3089 5614 3089 5615 3092 5615 3091 5615 3091 5616 3092 5616 3018 5616 3091 5617 3018 5617 2969 5617 1179 5618 3091 5618 2969 5618 1189 5619 1190 5619 3086 5619 1190 5620 1191 5620 3086 5620 3093 5621 3057 5621 3061 5621 1157 5622 1158 5622 3093 5622 3094 5623 3053 5623 3057 5623 3093 5624 3094 5624 3057 5624 3093 5625 1158 5625 1159 5625 3093 5626 1159 5626 1160 5626 3093 5627 1160 5627 3095 5627 3093 5628 3095 5628 3096 5628 3094 5629 3093 5629 3096 5629 3053 5630 3094 5630 3097 5630 3053 5631 3097 5631 3098 5631 3054 5632 3053 5632 3098 5632 1151 5633 3099 5633 3100 5633 1151 5634 3100 5634 3101 5634 1152 5635 1151 5635 3101 5635 3099 5636 1151 5636 1150 5636 2965 5637 3099 5637 1150 5637 2965 5638 3081 5638 3080 5638 2965 5639 3080 5639 3079 5639 2965 5640 3079 5640 3102 5640 2965 5641 3102 5641 3099 5641 2967 5642 3081 5642 2965 5642 2965 5643 1150 5643 1149 5643 3088 222 3087 222 3103 222 3089 5644 3088 5644 3103 5644 3070 5645 3104 5645 3068 5645 3105 5646 3104 5646 3070 5646 3070 5647 3072 5647 3105 5647 3069 5648 3068 5648 3106 5648 3082 64 3065 64 3064 64 3082 228 3064 228 3062 228 3084 64 3065 64 3082 64 3054 5649 3107 5649 3108 5649 3055 5650 3054 5650 3108 5650 3108 5651 3109 5651 3055 5651 3055 5652 3109 5652 3110 5652 3056 5653 3055 5653 3110 5653 3110 5654 3109 5654 3111 5654 3112 5655 3110 5655 3111 5655 3111 5656 3113 5656 3112 5656 3113 5657 3114 5657 3115 5657 3116 5658 3115 5658 3114 5658 3112 5659 3113 5659 3115 5659 3112 5660 3115 5660 3117 5660 3112 5661 3117 5661 3118 5661 3112 5662 3118 5662 3119 5662 3120 5663 3112 5663 3119 5663 3119 5664 3121 5664 3120 5664 3122 5665 3116 5665 3114 5665 3114 5666 3123 5666 3122 5666 3120 5667 3121 5667 3124 5667 3120 5668 3124 5668 3125 5668 3126 5669 3120 5669 3125 5669 3125 5670 3127 5670 3126 5670 3128 5671 3126 5671 3127 5671 3127 5672 3129 5672 3128 5672 3130 5673 3128 5673 3129 5673 3129 5674 3131 5674 3130 5674 3130 5675 3131 5675 3132 5675 3130 5676 3132 5676 3133 5676 3134 5677 3130 5677 3133 5677 3133 5678 3135 5678 3134 5678 3136 5679 3137 5679 3138 5679 3139 5680 3136 5680 3138 5680 3134 5681 3135 5681 3137 5681 3137 5682 3136 5682 3140 5682 3140 5683 3134 5683 3137 5683 3136 5684 3141 5684 3140 5684 3140 5685 3141 5685 3142 5685 3143 5686 3140 5686 3142 5686 3142 5687 3144 5687 3078 5687 3078 5688 3144 5688 3145 5688 3079 5689 3078 5689 3145 5689 3127 270 3125 270 3129 270 3131 5690 3129 5690 3125 5690 3125 5691 3146 5691 3131 5691 3147 5692 3131 5692 3146 5692 3146 5693 3148 5693 3147 5693 3149 5694 3147 5694 3148 5694 3148 270 3150 270 3149 270 3151 5695 3149 5695 3150 5695 3150 270 3152 270 3151 270 3153 5696 3151 5696 3152 5696 3152 270 3154 270 3153 270 3155 270 3153 270 3154 270 3156 182 3157 182 3158 182 3159 5697 3158 5697 3157 5697 3157 182 3160 182 3159 182 3161 182 3159 182 3160 182 3160 182 3162 182 3161 182 3161 182 3162 182 3163 182 3164 182 3161 182 3163 182 3163 1229 3165 1229 3164 1229 3166 182 3164 182 3165 182 3137 5698 3167 5698 3138 5698 3168 5699 3138 5699 3167 5699 3167 5700 3169 5700 3168 5700 3170 5701 3168 5701 3169 5701 3169 5702 3171 5702 3170 5702 3172 5703 3170 5703 3171 5703 3171 5704 3173 5704 3172 5704 3174 5705 3172 5705 3173 5705 3173 5706 3175 5706 3174 5706 3176 5707 3174 5707 3175 5707 3175 5708 3177 5708 3176 5708 3178 5709 3176 5709 3177 5709 3177 5710 3179 5710 3178 5710 3180 5711 3178 5711 3179 5711 3179 5712 3181 5712 3180 5712 3182 5713 3180 5713 3181 5713 3115 5714 3183 5714 3117 5714 3184 5715 3117 5715 3183 5715 3183 5716 3185 5716 3184 5716 3186 5716 3184 5716 3185 5716 3185 295 3187 295 3186 295 3188 296 3186 296 3187 296 3187 297 3189 297 3188 297 3190 5717 3188 5717 3189 5717 3189 5718 3191 5718 3190 5718 3192 5719 3190 5719 3191 5719 3191 5720 3193 5720 3192 5720 3194 5721 3192 5721 3193 5721 3193 303 3195 303 3194 303 3196 303 3194 303 3195 303 3195 5722 3197 5722 3196 5722 3198 5723 3196 5723 3197 5723 3184 5724 3118 5724 3117 5724 3186 5725 3121 5725 3119 5725 3186 5726 3119 5726 3118 5726 3184 5727 3186 5727 3118 5727 3186 5728 3188 5728 3121 5728 3199 5729 3125 5729 3124 5729 3199 5730 3124 5730 3121 5730 3121 5731 3188 5731 3190 5731 3199 5732 3121 5732 3190 5732 3146 5733 3125 5733 3199 5733 3190 5734 3192 5734 3199 5734 3199 5735 3192 5735 3194 5735 3200 5736 3199 5736 3194 5736 3200 5737 3148 5737 3146 5737 3199 5738 3200 5738 3146 5738 3150 5739 3148 5739 3200 5739 3194 5740 3196 5740 3200 5740 3201 5741 3152 5741 3150 5741 3200 5742 3201 5742 3150 5742 3200 5743 3196 5743 3198 5743 3200 5744 3198 5744 3202 5744 3201 5745 3200 5745 3202 5745 3152 5746 3201 5746 3203 5746 3154 5747 3152 5747 3203 5747 3137 5748 3135 5748 3167 5748 3169 5749 3167 5749 3135 5749 3135 5750 3133 5750 3169 5750 3169 5751 3133 5751 3204 5751 3171 5752 3169 5752 3204 5752 3205 5753 3173 5753 3171 5753 3204 5754 3205 5754 3171 5754 3132 5755 3131 5755 3205 5755 3205 5756 3204 5756 3132 5756 3131 5757 3147 5757 3205 5757 3175 5758 3173 5758 3205 5758 3205 5759 3147 5759 3149 5759 3206 5760 3205 5760 3149 5760 3206 5761 3177 5761 3175 5761 3205 5762 3206 5762 3175 5762 3149 5763 3151 5763 3206 5763 3179 5764 3177 5764 3206 5764 3206 5765 3151 5765 3153 5765 3153 5766 3155 5766 3206 5766 3206 349 3155 349 3207 349 3208 5767 3206 5767 3207 5767 3206 5768 3208 5768 3179 5768 3179 5769 3208 5769 3209 5769 3181 5770 3179 5770 3209 5770 3115 5771 3210 5771 3183 5771 3185 5772 3183 5772 3210 5772 3210 5773 3211 5773 3185 5773 3187 5774 3185 5774 3211 5774 3211 5775 3212 5775 3187 5775 3189 5776 3187 5776 3212 5776 3213 5777 3191 5777 3189 5777 3212 5778 3213 5778 3189 5778 3214 5779 3158 5779 3213 5779 3215 5780 3214 5780 3213 5780 3216 5781 3215 5781 3213 5781 3213 5782 3212 5782 3216 5782 3158 5783 3159 5783 3213 5783 3193 5784 3191 5784 3213 5784 3213 5785 3159 5785 3161 5785 3213 5786 3161 5786 3164 5786 3213 5787 3164 5787 3166 5787 3213 5788 3166 5788 3217 5788 3218 5789 3213 5789 3217 5789 3218 5790 3195 5790 3193 5790 3213 5791 3218 5791 3193 5791 3195 5792 3218 5792 3219 5792 3197 5793 3195 5793 3219 5793 3054 5794 3098 5794 3107 5794 3220 5795 3107 5795 3098 5795 3098 5796 3097 5796 3220 5796 3221 380 3220 380 3097 380 3097 5797 3096 5797 3221 5797 3222 5797 3221 5797 3096 5797 3096 5798 3095 5798 3222 5798 3223 5799 3222 5799 3095 5799 3095 384 1160 384 3223 384 1143 385 3223 385 1160 385 3145 5800 3224 5800 3079 5800 3102 5801 3079 5801 3224 5801 3224 5802 3225 5802 3102 5802 3099 5803 3102 5803 3225 5803 3225 5804 3226 5804 3099 5804 3100 5805 3099 5805 3226 5805 3226 5806 3227 5806 3100 5806 3101 5807 3100 5807 3227 5807 3227 5808 1132 5808 3101 5808 1152 5809 3101 5809 1132 5809 3136 1343 3228 1343 3141 1343 3224 5810 3145 5810 3144 5810 3229 5811 3142 5811 3141 5811 3142 5812 3229 5812 3144 5812 3144 5813 3230 5813 3224 5813 3230 5814 3144 5814 3229 5814 3141 5815 3231 5815 3229 5815 3231 5816 3141 5816 3228 5816 3232 5817 3229 5817 3231 5817 3229 5818 3232 5818 3230 5818 3225 5819 3224 5819 3230 5819 3230 5820 3233 5820 3225 5820 3233 5821 3230 5821 3232 5821 3228 5822 3234 5822 3231 5822 3235 5823 3232 5823 3231 5823 3232 5824 3235 5824 3233 5824 3226 5825 3225 5825 3233 5825 3236 1360 3233 1360 3235 1360 3233 5826 3236 5826 3226 5826 3234 5827 1122 5827 3231 5827 3231 5828 3237 5828 3235 5828 3237 5829 3231 5829 1122 5829 1122 5830 1123 5830 3237 5830 3227 5831 3226 5831 3236 5831 3235 5832 1126 5832 3236 5832 1126 5833 3235 5833 3237 5833 1124 5834 3237 5834 1123 5834 3237 5835 1124 5835 1126 5835 1132 5836 3227 5836 3236 5836 1126 5837 1128 5837 3236 5837 3236 5838 1128 5838 1132 5838 1133 5839 1145 5839 3238 5839 3239 5840 3114 5840 3113 5840 3239 5841 3113 5841 3240 5841 3238 5842 3239 5842 3240 5842 3239 5843 3238 5843 1145 5843 3123 5844 3114 5844 3239 5844 1145 5845 1402 5845 3239 5845 3241 5846 3239 5846 1402 5846 3241 5847 3242 5847 3243 5847 3243 5848 3123 5848 3239 5848 3244 5849 3241 5849 1402 5849 1402 5850 1401 5850 3244 5850 1400 5851 3245 5851 3244 5851 1401 5852 1400 5852 3244 5852 3246 5853 3245 5853 1400 5853 1400 5854 1144 5854 3246 5854 3246 5855 3228 5855 3139 5855 3246 5856 1144 5856 1122 5856 3246 5857 1122 5857 3234 5857 3228 5858 3246 5858 3234 5858 3136 5859 3139 5859 3228 5859 3107 5860 3220 5860 3108 5860 3247 5861 3108 5861 3220 5861 3108 5862 3247 5862 3109 5862 3240 5863 3113 5863 3111 5863 3111 5864 3248 5864 3240 5864 3248 5865 3111 5865 3109 5865 3109 453 3249 453 3248 453 3249 5866 3109 5866 3247 5866 3247 5867 3250 5867 3249 5867 3250 5868 3247 5868 3220 5868 3220 5869 3221 5869 3250 5869 3238 5870 3240 5870 3248 5870 3248 5871 3251 5871 3238 5871 3251 5872 3248 5872 3249 5872 3252 5873 3249 5873 3250 5873 3249 462 3252 462 3251 462 3253 5874 3250 5874 3221 5874 3250 5875 3253 5875 3252 5875 3221 5876 3222 5876 3253 5876 1133 5877 3238 5877 3251 5877 3254 5878 3251 5878 3252 5878 3251 5879 3254 5879 1133 5879 3255 5880 3252 5880 3253 5880 3252 5881 3255 5881 3254 5881 3256 5882 3253 5882 3222 5882 3253 5883 3256 5883 3255 5883 1136 5884 1133 5884 3254 5884 1136 5885 3254 5885 3255 5885 3222 5886 3223 5886 3256 5886 1138 5887 3255 5887 3256 5887 3255 5888 1138 5888 1136 5888 3223 5889 1143 5889 3256 5889 1140 5890 3256 5890 1143 5890 3256 5891 1140 5891 1138 5891 3257 5892 3243 5892 3242 5892 3258 5893 3243 5893 3257 5893 3257 5894 3259 5894 3258 5894 3260 5895 3258 5895 3259 5895 3259 5896 3261 5896 3260 5896 3260 5897 3261 5897 3156 5897 3260 5898 3156 5898 3158 5898 3110 182 3112 182 3120 182 3110 182 3120 182 3126 182 3110 182 3126 182 3128 182 3110 5899 3128 5899 3130 5899 3110 5900 3130 5900 3134 5900 3110 5901 3134 5901 3140 5901 3143 5902 3110 5902 3140 5902 3143 5903 3076 5903 3075 5903 3143 5904 3075 5904 3074 5904 3143 5905 3074 5905 3073 5905 3143 5906 3073 5906 3071 5906 3143 5907 3071 5907 3067 5907 3143 5908 3067 5908 3069 5908 3069 496 3106 496 3083 496 3143 5909 3069 5909 3083 5909 3143 5910 3083 5910 3082 5910 3143 5911 3082 5911 3062 5911 3143 5912 3062 5912 3059 5912 3143 5913 3059 5913 3058 5913 3143 5914 3058 5914 3052 5914 3143 5915 3052 5915 3056 5915 3110 5916 3143 5916 3056 5916 3077 496 3076 496 3143 496 3094 496 3096 496 3097 496 3133 270 3132 270 3204 270 3242 5917 3241 5917 3244 5917 3244 5918 3245 5918 3242 5918 3239 5919 3241 5919 3243 5919 3158 5920 3214 5920 3260 5920 3243 5921 3258 5921 3260 5921 3214 5922 3243 5922 3260 5922 3214 5923 3215 5923 3243 5923 3215 5924 3216 5924 3243 5924 3123 5925 3243 5925 3216 5925 3123 5926 3216 5926 3212 5926 3123 5927 3212 5927 3211 5927 3122 5928 3123 5928 3211 5928 3122 5929 3211 5929 3210 5929 3116 5930 3122 5930 3210 5930 3115 5931 3116 5931 3210 5931 3138 5932 3262 5932 3263 5932 3263 1469 3262 1469 3264 1469 3264 5933 3262 5933 3265 5933 3264 5934 3265 5934 3266 5934 3266 5935 3265 5935 3267 5935 3266 5936 3267 5936 3268 5936 3266 5937 3268 5937 3269 5937 3270 5938 3269 5938 3268 5938 3271 5939 3269 5939 3270 5939 3271 5940 3272 5940 3269 5940 3269 5941 3272 5941 3273 5941 3274 5942 3272 5942 3271 5942 3246 5943 3269 5943 3245 5943 3272 5944 3274 5944 3156 5944 3272 5945 3156 5945 3261 5945 3259 5946 3272 5946 3261 5946 3272 5947 3259 5947 3273 5947 3257 5948 3273 5948 3259 5948 3273 5949 3257 5949 3269 5949 3257 1487 3242 1487 3269 1487 3269 5950 3246 5950 3266 5950 3245 5951 3269 5951 3242 5951 3266 5952 3246 5952 3139 5952 3182 5953 3275 5953 3180 5953 3180 5954 3275 5954 3276 5954 3277 5955 3178 5955 3276 5955 3276 5956 3178 5956 3180 5956 3276 5957 3278 5957 3277 5957 3277 5958 3278 5958 3165 5958 3277 5959 3165 5959 3163 5959 3277 5960 3163 5960 3279 5960 3277 5961 3279 5961 3280 5961 3178 5962 3277 5962 3176 5962 3274 5963 3277 5963 3280 5963 3277 5964 3268 5964 3267 5964 3268 5965 3277 5965 3270 5965 3270 5966 3277 5966 3271 5966 3271 5967 3277 5967 3274 5967 3267 5968 3174 5968 3277 5968 3277 5969 3174 5969 3176 5969 3174 5970 3267 5970 3172 5970 3265 5971 3172 5971 3267 5971 3172 5972 3265 5972 3170 5972 3262 5973 3170 5973 3265 5973 3170 5974 3262 5974 3168 5974 3138 5975 3168 5975 3262 5975 3160 182 3279 182 3162 182 3279 182 3160 182 3280 182 3157 182 3280 182 3160 182 3280 182 3157 182 3274 182 3156 182 3274 182 3157 182 3139 5976 3264 5976 3266 5976 3264 5977 3139 5977 3263 5977 3263 5978 3139 5978 3138 5978 3162 182 3279 182 3163 182 3078 5979 3143 5979 3142 5979 3077 5980 3143 5980 3078 5980 3106 182 3104 182 3083 182 3106 5981 3068 5981 3104 5981 3281 270 3155 270 3282 270 3283 270 3281 270 3282 270 3284 270 3285 270 3282 270 3286 270 3287 270 3283 270 3282 5982 3288 5982 3284 5982 3289 5983 3283 5983 3287 5983 3290 5984 3284 5984 3288 5984 3287 5985 3291 5985 3289 5985 3288 5986 3292 5986 3290 5986 3293 5987 3289 5987 3291 5987 3294 270 3290 270 3292 270 3291 270 3295 270 3293 270 3296 270 3293 270 3295 270 3292 270 3297 270 3294 270 3295 270 3298 270 3296 270 3299 579 3294 579 3297 579 3296 5988 3298 5988 3300 5988 3301 270 3296 270 3300 270 3302 270 3303 270 3299 270 3297 270 3302 270 3299 270 3304 270 3303 270 3302 270 3300 270 3304 270 3301 270 3305 270 3301 270 3304 270 3306 270 3305 270 3304 270 3302 5989 3306 5989 3304 5989 3307 5990 3182 5990 3308 5990 3309 583 3310 583 3198 583 3311 5991 3288 5991 3203 5991 3312 5992 3311 5992 3201 5992 3312 5993 3198 5993 3310 5993 3313 5994 3312 5994 3310 5994 3283 270 3155 270 3281 270 3155 5995 3283 5995 3314 5995 3314 5996 3315 5996 3207 5996 3315 5997 3316 5997 3208 5997 3316 5998 3308 5998 3209 5998 3307 5999 3317 5999 3182 5999 3317 6000 3318 6000 3276 6000 3318 6001 3319 6001 3278 6001 3320 6002 3321 6002 3166 6002 3321 6003 3322 6003 3218 6003 3322 6004 3309 6004 3219 6004 3323 6005 3288 6005 3311 6005 3311 6006 3312 6006 3323 6006 3324 6007 3323 6007 3312 6007 3312 6008 3313 6008 3324 6008 3314 6009 3325 6009 3315 6009 3316 6010 3315 6010 3325 6010 3325 6011 3326 6011 3316 6011 3316 6012 3326 6012 3308 6012 3327 6013 3292 6013 3288 6013 3323 6014 3327 6014 3288 6014 3324 6015 3313 6015 3327 6015 3323 6016 3324 6016 3327 6016 3313 6017 3328 6017 3327 6017 3297 6018 3292 6018 3327 6018 3329 6019 3327 6019 3328 6019 3329 6020 3302 6020 3297 6020 3327 6021 3329 6021 3297 6021 3328 6022 3330 6022 3329 6022 3306 6023 3302 6023 3329 6023 3329 6024 3330 6024 3331 6024 3332 6025 3329 6025 3331 6025 3329 6026 3332 6026 3306 6026 3305 6027 3306 6027 3332 6027 3331 6028 3333 6028 3332 6028 3334 6029 3332 6029 3333 6029 3332 6030 3334 6030 3305 6030 3301 6031 3305 6031 3334 6031 3333 6032 3335 6032 3334 6032 3336 6033 3296 6033 3301 6033 3334 636 3336 636 3301 636 3336 6034 3334 6034 3335 6034 3293 6035 3296 6035 3336 6035 3335 6036 3308 6036 3336 6036 3325 6037 3289 6037 3293 6037 3336 6038 3325 6038 3293 6038 3336 6039 3308 6039 3326 6039 3336 6040 3326 6040 3325 6040 3314 6041 3289 6041 3325 6041 3289 6042 3314 6042 3283 6042 3166 182 3319 182 3320 182 3320 182 3337 182 3338 182 3319 182 3337 182 3320 182 3313 1585 3310 1585 3309 1585 3308 6043 3335 6043 3339 6043 3339 6044 3307 6044 3308 6044 3330 6045 3328 6045 3340 6045 3340 1588 3341 1588 3330 1588 3331 6046 3330 6046 3341 6046 3341 6047 3342 6047 3331 6047 3342 6048 3343 6048 3333 6048 3333 6048 3331 6048 3342 6048 3343 655 3339 655 3335 655 3335 656 3333 656 3343 656 3328 6049 3313 6049 3309 6049 3309 6050 3340 6050 3328 6050 3322 6051 3340 6051 3309 6051 3321 6052 3340 6052 3322 6052 3338 6053 3341 6053 3340 6053 3338 6054 3342 6054 3341 6054 3338 663 3337 663 3342 663 3337 6055 3343 6055 3342 6055 3339 6056 3343 6056 3337 6056 3317 6057 3307 6057 3339 6057 3317 6058 3339 6058 3318 6058 3282 6059 3286 6059 3283 6059 3282 270 3285 270 3286 270 3282 6060 3203 6060 3288 6060 3321 6061 3338 6061 3340 6061 3320 1608 3338 1608 3321 1608 3319 6062 3318 6062 3337 6062 3318 6063 3339 6063 3337 6063 3063 6064 3344 6064 3061 6064 3060 6065 3063 6065 3061 6065 3345 182 3084 182 3083 182 3346 6066 3085 6066 3086 6066 1191 677 1187 677 3086 677 3093 6067 3061 6067 3344 6067 3093 6068 3347 6068 1157 6068 3085 6069 3346 6069 3348 6069 3348 681 3349 681 3085 681 3066 682 3065 682 3084 682 3181 6070 3308 6070 3182 6070 3165 182 3319 182 3166 182 3197 583 3309 583 3198 583 3203 6071 3201 6071 3311 6071 3201 6072 3202 6072 3312 6072 3312 6073 3202 6073 3198 6073 3207 6074 3155 6074 3314 6074 3208 6075 3207 6075 3315 6075 3209 6076 3208 6076 3316 6076 3181 6077 3209 6077 3308 6077 3317 6078 3275 6078 3182 6078 3276 6079 3275 6079 3317 6079 3278 6080 3276 6080 3318 6080 3165 6081 3278 6081 3319 6081 3321 6082 3217 6082 3166 6082 3218 6083 3217 6083 3321 6083 3219 6084 3218 6084 3322 6084 3197 6085 3219 6085 3309 6085 3282 270 3155 270 3154 270 3154 6086 3203 6086 3282 6086 1119 6087 1115 6087 3350 6087 3086 6088 3351 6088 3352 6088 3346 6089 3086 6089 3352 6089 3353 6090 3354 6090 3355 6090 3353 6091 3356 6091 3354 6091 3357 6092 3358 6092 3359 6092 3359 6093 3358 6093 3360 6093 3360 6094 3358 6094 3361 6094 3361 6095 3358 6095 3362 6095 3362 6096 3358 6096 3363 6096 3363 6097 3358 6097 3364 6097 3361 6098 3365 6098 3360 6098 3366 6099 3367 6099 3365 6099 3365 6100 3367 6100 3368 6100 3354 6101 3368 6101 3367 6101 3369 6102 3368 6102 3354 6102 3370 6103 3369 6103 3354 6103 3369 6104 3371 6104 3368 6104 3360 6105 3365 6105 3368 6105 3360 6106 3368 6106 3371 6106 3372 6107 3373 6107 3374 6107 3363 6108 3373 6108 3372 6108 3354 6109 3356 6109 3370 6109 3345 6110 3066 6110 3084 6110 3375 6111 3066 6111 3345 6111 3376 6112 3375 6112 3345 6112 3377 6113 3376 6113 3345 6113 3345 727 3364 727 3377 727 3358 6114 3377 6114 3364 6114 3373 6115 3363 6115 3364 6115 3378 6116 3379 6116 3380 6116 3350 6117 3379 6117 3378 6117 3378 6118 3381 6118 3350 6118 3382 733 3350 733 3381 733 3381 6119 3383 6119 3382 6119 3383 735 3352 735 3382 735 3383 736 3384 736 3352 736 3346 737 3352 737 3384 737 3385 6120 3346 6120 3384 6120 3386 6121 3387 6121 3388 6121 3387 6122 3389 6122 3388 6122 3388 6123 3390 6123 3386 6123 3391 6124 3386 6124 3390 6124 3390 6125 3392 6125 3391 6125 3393 6126 3391 6126 3392 6126 3392 6127 3394 6127 3393 6127 3395 6128 3393 6128 3394 6128 3394 6129 3396 6129 3395 6129 3397 6130 3395 6130 3396 6130 3396 6131 3398 6131 3397 6131 3399 6132 3397 6132 3398 6132 3398 6133 3380 6133 3399 6133 3399 6134 3380 6134 3379 6134 3348 6135 3346 6135 3385 6135 3400 6136 3401 6136 3402 6136 3401 6137 3400 6137 3403 6137 3404 6138 3405 6138 3401 6138 3406 6139 3407 6139 3408 6139 3409 6140 3408 6140 3407 6140 3409 6141 3355 6141 3408 6141 3409 6142 3410 6142 3355 6142 3409 6143 3411 6143 3410 6143 3409 6144 3412 6144 3411 6144 3413 6145 3412 6145 3409 6145 3414 6146 3409 6146 3415 6146 3409 6147 3407 6147 3415 6147 3409 765 3414 765 3413 765 3414 6148 3416 6148 3413 6148 3415 6149 3417 6149 3414 6149 3418 768 3416 768 3414 768 3414 6150 3401 6150 3418 6150 3401 6151 3419 6151 3418 6151 3401 6152 3405 6152 3419 6152 3414 6153 3402 6153 3401 6153 3414 1703 3417 1703 3402 1703 3408 6154 3366 6154 3406 6154 3367 6155 3366 6155 3408 6155 3354 6156 3367 6156 3408 6156 3408 6157 3355 6157 3354 6157 3355 6158 3410 6158 3420 6158 3420 6159 3353 6159 3355 6159 3421 6160 3357 6160 3359 6160 3422 6161 3359 6161 3360 6161 3359 6162 3422 6162 3421 6162 3360 6163 3371 6163 3422 6163 1154 6164 3421 6164 3422 6164 3422 6165 3423 6165 1154 6165 3347 6166 1156 6166 1157 6166 3347 6167 3093 6167 3344 6167 3347 6168 3357 6168 3421 6168 3347 6169 3424 6169 3357 6169 3347 6170 3344 6170 3424 6170 3347 6171 3421 6171 1156 6171 3421 6172 1154 6172 1156 6172 1155 793 3425 793 1180 793 1182 794 1180 794 3425 794 1182 6173 3369 6173 3370 6173 1182 796 3425 796 3369 796 3370 6174 1117 6174 1182 6174 3370 6175 1118 6175 1117 6175 3370 6176 3426 6176 1118 6176 3427 6177 3426 6177 3356 6177 3426 6178 3370 6178 3356 6178 3356 6179 3353 6179 3427 6179 3428 6180 3427 6180 3353 6180 3353 6181 3420 6181 3428 6181 3410 6182 3428 6182 3420 6182 3366 6183 3365 6183 3362 6183 3361 6184 3362 6184 3365 6184 3429 6185 3430 6185 3402 6185 3402 6186 3417 6186 3429 6186 3363 6187 3372 6187 3407 6187 3372 6188 3415 6188 3407 6188 3372 6189 3417 6189 3415 6189 3363 6190 3407 6190 3362 6190 3407 6191 3406 6191 3362 6191 3366 817 3362 817 3406 817 3431 6192 3396 6192 3394 6192 3431 819 3398 819 3396 819 3380 270 3398 270 3431 270 3431 6193 3378 6193 3380 6193 3431 6194 3381 6194 3378 6194 3431 6195 3383 6195 3381 6195 3431 6196 3384 6196 3383 6196 3431 6197 3385 6197 3384 6197 3400 6198 3402 6198 3430 6198 3350 6199 1115 6199 3379 6199 3351 6200 3350 6200 3382 6200 3382 6201 3352 6201 3351 6201 3350 6202 3351 6202 1119 6202 3351 6203 1184 6203 1119 6203 1186 6204 1184 6204 3351 6204 1186 6205 3351 6205 3086 6205 1187 832 1186 832 3086 832 3425 6206 3423 6206 3369 6206 1154 6207 3423 6207 3425 6207 3425 6208 1155 6208 1154 6208 3364 6209 3345 6209 3083 6209 3357 6210 3377 6210 3358 6210 3377 6211 3357 6211 3424 6211 3377 6212 3424 6212 3376 6212 3424 6213 3375 6213 3376 6213 3063 6214 3375 6214 3424 6214 3375 6215 3063 6215 3066 6215 3424 6216 3344 6216 3063 6216 3379 6217 1115 6217 3399 6217 1118 6218 3426 6218 1114 6218 1115 6219 1114 6219 3426 6219 3426 6220 3427 6220 1115 6220 3427 6221 3399 6221 1115 6221 3397 6222 3399 6222 3410 6222 3399 6223 3428 6223 3410 6223 3399 6224 3427 6224 3428 6224 3410 6225 3411 6225 3397 6225 3395 6226 3397 6226 3411 6226 3411 6227 3412 6227 3395 6227 3393 6228 3395 6228 3413 6228 3395 6229 3412 6229 3413 6229 3413 6230 3416 6230 3393 6230 3391 6231 3393 6231 3416 6231 3416 6232 3418 6232 3391 6232 3386 6233 3391 6233 3419 6233 3391 6234 3418 6234 3419 6234 3419 6235 3405 6235 3386 6235 3387 6236 3386 6236 3405 6236 3432 6237 3364 6237 3083 6237 3364 6238 3432 6238 3373 6238 3035 6239 3034 6239 2970 6239 3034 6240 3433 6240 2971 6240 3434 6241 3018 6241 3435 6241 3019 6242 3018 6242 3434 6242 3434 6243 3436 6243 3019 6243 3436 6244 3033 6244 3019 6244 3092 6245 3435 6245 3018 6245 3092 6246 3437 6246 3435 6246 2983 270 3032 270 3431 270 3431 6247 3434 6247 3435 6247 3431 6248 3436 6248 3434 6248 3431 6249 3033 6249 3436 6249 3431 6250 3031 6250 3033 6250 3431 6251 3032 6251 3031 6251 3435 6252 3437 6252 3431 6252 3437 6253 3438 6253 3431 6253 3103 1809 3431 1809 3438 1809 3373 6254 3039 6254 3046 6254 3373 6255 3038 6255 3039 6255 3373 6256 3037 6256 3038 6256 3373 6257 3036 6257 3037 6257 3373 6258 3035 6258 3036 6258 3373 6259 3034 6259 3035 6259 3373 6260 3433 6260 3034 6260 3373 6261 3105 6261 3433 6261 3439 6262 3440 6262 2995 6262 3007 6263 3439 6263 2995 6263 3441 6264 3442 6264 3440 6264 3439 6265 3441 6265 3440 6265 3443 6266 3442 6266 3441 6266 3444 6267 3445 6267 3443 6267 3441 6268 3444 6268 3443 6268 3444 6269 3446 6269 3445 6269 3373 6270 3046 6270 3045 6270 3373 6271 3045 6271 3044 6271 3447 6272 3448 6272 3449 6272 3449 6273 3450 6273 3447 6273 3447 6274 3450 6274 3403 6274 3451 6275 3447 6275 3403 6275 3452 6276 3005 6276 3006 6276 2997 6277 3453 6277 3454 6277 3453 6278 3449 6278 3454 6278 3448 6279 3454 6279 3449 6279 3455 6280 3442 6280 3443 6280 3456 6281 3455 6281 3443 6281 3456 6282 3450 6282 3449 6282 3456 6283 3449 6283 3455 6283 3443 6284 3445 6284 3456 6284 3456 6285 3445 6285 3457 6285 3456 6286 3404 6286 3450 6286 3455 6287 3453 6287 2997 6287 2996 6288 3455 6288 2997 6288 2996 6289 2995 6289 3440 6289 2996 6290 3440 6290 3442 6290 2996 6291 3442 6291 3455 6291 3453 6292 3455 6292 3449 6292 3446 6293 3444 6293 3458 6293 3439 6294 3459 6294 3460 6294 3441 6295 3439 6295 3460 6295 3461 6296 3459 6296 3439 6296 3439 6297 3007 6297 3461 6297 3462 6298 3461 6298 3007 6298 3007 6299 2987 6299 3462 6299 2986 6300 3462 6300 2987 6300 3044 6301 3005 6301 3373 6301 3373 6302 3005 6302 3452 6302 3444 6303 3463 6303 3458 6303 3441 6304 3463 6304 3444 6304 3441 6305 3460 6305 3463 6305 3006 6306 3373 6306 3452 6306 3431 6307 2986 6307 2984 6307 3431 6308 2984 6308 2983 6308 3087 6309 3085 6309 3349 6309 3349 935 3103 935 3087 935 3103 6310 3438 6310 3089 6310 3092 6311 3089 6311 3438 6311 3438 6312 3437 6312 3092 6312 3433 6313 3105 6313 3072 6313 3072 1868 2971 1868 3433 1868 3458 6314 3464 6314 3446 6314 3387 6315 3446 6315 3464 6315 3389 6316 3387 6316 3464 6316 3404 6317 3401 6317 3403 6317 3404 945 3465 945 3405 945 3404 6318 3457 6318 3465 6318 3404 6319 3403 6319 3450 6319 3404 6320 3456 6320 3457 6320 3348 270 3385 270 3431 270 3349 270 3348 270 3431 270 3431 6321 3103 6321 3349 6321 3430 6322 3466 6322 3400 6322 3403 6323 3400 6323 3466 6323 3466 6324 3451 6324 3403 6324 3465 6325 3387 6325 3405 6325 3446 6326 3387 6326 3457 6326 3387 6327 3465 6327 3457 6327 3446 6328 3457 6328 3445 6328 3432 182 3083 182 3104 182 3432 182 3104 182 3105 182 3432 6329 3105 6329 3373 6329 1555 6330 2224 6330 1557 6330 1442 6331 2224 6331 1555 6331 1439 6332 2224 6332 1442 6332 1352 6333 3467 6333 1356 6333 1349 270 3467 270 1352 270 1347 270 3467 270 1349 270 1343 270 3467 270 1347 270 1344 270 3467 270 1343 270 1341 6334 3467 6334 1344 6334 1335 270 3467 270 1341 270 1266 270 3467 270 1335 270 1267 270 3467 270 1266 270 1372 6335 3467 6335 1267 6335 1372 270 1398 270 3467 270 1398 270 1397 270 3467 270 1397 270 1393 270 3467 270 1393 270 1394 270 3467 270 1394 270 1391 270 3467 270 1391 6336 1388 6336 3467 6336 1388 6337 1386 6337 3467 6337 1386 270 1380 270 3467 270 1380 270 1381 270 3467 270 2321 6338 3468 6338 1176 6338 1426 6339 3468 6339 1432 6339 1194 6340 3468 6340 1188 6340 1188 6341 3468 6341 1423 6341 1423 6342 3468 6342 1427 6342 1427 6343 3468 6343 1426 6343 3090 6344 3468 6344 1194 6344 3091 6345 3468 6345 3090 6345 1179 6346 3468 6346 3091 6346 1179 6347 1176 6347 3468 6347 2964 6348 3467 6348 3468 6348 2321 6349 2964 6349 3468 6349 1381 6350 1438 6350 3468 6350 1381 6351 3468 6351 3467 6351 1436 6352 3468 6352 1438 6352 1435 6353 3468 6353 1436 6353 1435 6354 1432 6354 3468 6354 1289 6355 2478 6355 1292 6355 1289 182 1285 182 2478 182 1285 182 1333 182 2478 182 1214 6356 2478 6356 1333 6356 1214 6357 1276 6357 2478 6357 3469 6358 2964 6358 1793 6358 2387 6359 2858 6359 2385 6359 2689 6360 3469 6360 2866 6360 1656 6361 3469 6361 1793 6361 1656 6362 1793 6362 1657 6362 1793 6363 1658 6363 1657 6363 2513 6364 3470 6364 2243 6364 3470 6365 1656 6365 2243 6365 2866 6366 3470 6366 2513 6366 1656 6367 3470 6367 3469 6367 3470 6368 2866 6368 3469 6368 1767 6369 3471 6369 1784 6369 3471 6370 1793 6370 1784 6370 1663 6371 3471 6371 1767 6371 1663 6372 1767 6372 1758 6372 1663 6373 1793 6373 3471 6373 1355 6374 2447 6374 2388 6374 2447 6375 2964 6375 3469 6375 2858 6376 2387 6376 2857 6376 2447 6377 3469 6377 2387 6377 2447 6378 3467 6378 2964 6378 1355 6379 3467 6379 2447 6379 1355 6380 1356 6380 3467 6380 2857 6381 3472 6381 2641 6381 3469 6382 3472 6382 2387 6382 3472 6383 2857 6383 2387 6383 2689 6384 2642 6384 3472 6384 2641 6385 3472 6385 2642 6385 2689 6386 3472 6386 3469 6386 668 6387 687 6387 669 6387 3422 6388 3371 6388 3423 6388 3371 6389 3369 6389 3423 6389 1059 6390 1009 6390 1061 6390 1009 6391 1007 6391 1061 6391 503 6392 453 6392 504 6392 453 6393 451 6393 504 6393 2462 6394 2491 6394 2461 6394 2462 6395 2712 6395 2491 6395 2463 6396 2712 6396 2462 6396 2463 6397 2710 6397 2712 6397 2464 6398 2710 6398 2463 6398 2464 6399 2707 6399 2710 6399 2465 6400 2707 6400 2464 6400 2465 6401 2708 6401 2707 6401 2466 6402 2708 6402 2465 6402 2466 6403 2739 6403 2708 6403 2467 6404 2739 6404 2466 6404 2467 6405 2734 6405 2739 6405 2468 6406 2734 6406 2467 6406 2468 6407 2733 6407 2734 6407 3473 6408 2733 6408 2468 6408 3473 6409 2730 6409 2733 6409 3474 6410 2730 6410 3473 6410 3474 6411 2727 6411 2730 6411 3475 6412 2727 6412 3474 6412 2434 6413 2727 6413 3475 6413 2433 6414 2434 6414 3475 6414 2541 6415 2518 6415 2623 6415 2541 6416 2623 6416 2622 6416 2542 6417 2541 6417 2622 6417 2542 6418 2622 6418 2637 6418 2583 6419 2637 6419 2585 6419 2542 6420 2583 6420 2543 6420 2542 6421 2637 6421 2583 6421 2254 6422 2515 6422 2514 6422 2163 6423 2515 6423 2254 6423 2163 6424 2613 6424 2515 6424 2518 6425 2613 6425 2623 6425 2515 6426 2613 6426 2518 6426 2139 6427 2623 6427 2613 6427 2164 6428 2203 6428 2202 6428 2112 6429 2203 6429 2164 6429 2112 6430 2264 6430 2203 6430 2203 6431 2264 6431 2261 6431 2247 6432 2261 6432 2264 6432 2247 6433 2248 6433 2261 6433 2164 6434 2202 6434 2223 6434 2202 6435 2268 6435 2223 6435 2164 6436 2223 6436 2190 6436 473 6437 519 6437 475 6437 470 270 519 270 473 270 470 6438 471 6438 519 6438 519 6439 471 6439 553 6439 519 6440 553 6440 548 6440 519 6441 548 6441 552 6441 519 6442 552 6442 550 6442 519 6443 550 6443 549 6443 519 6444 549 6444 551 6444 519 6445 551 6445 25 6445 538 6446 542 6446 455 6446 539 6447 538 6447 455 6447 45 6448 543 6448 455 6448 539 6449 455 6449 543 6449 542 6450 555 6450 455 6450 455 6451 555 6451 518 6451 517 6452 455 6452 518 6452 456 6453 455 6453 517 6453 1012 6454 1011 6454 1073 6454 1073 6455 1011 6455 1074 6455 1011 6456 1112 6456 1074 6456 1098 6457 1112 6457 1011 6457 1095 6458 1011 6458 1100 6458 600 6459 1100 6459 1011 6459 1095 6460 1094 6460 1011 6460 1094 6461 1098 6461 1011 6461 1054 6462 1012 6462 1073 6462 1075 6463 1108 6463 580 6463 1075 6464 1107 6464 1108 6464 1075 6465 1106 6465 1107 6465 1075 6466 1109 6466 1106 6466 1075 6467 1105 6467 1109 6467 1075 6468 1110 6468 1105 6468 1075 6469 1027 6469 1110 6469 1026 6470 1027 6470 1075 6470 1026 6471 1075 6471 1029 6471 1029 270 1075 270 1031 270 3392 270 3431 270 3394 270 3390 270 3431 270 3392 270 3390 6472 3389 6472 3431 6472 3431 6473 3389 6473 3464 6473 3431 6474 3464 6474 3458 6474 3431 6475 3458 6475 3463 6475 3431 6476 3463 6476 3460 6476 3431 6477 3460 6477 3461 6477 3431 6478 3461 6478 3462 6478 3431 6479 3462 6479 2986 6479 3374 6480 3373 6480 3429 6480 3429 6481 3373 6481 3430 6481 3373 6451 3466 6451 3430 6451 3451 6482 3466 6482 3373 6482 3448 6483 3373 6483 3454 6483 3006 6484 3454 6484 3373 6484 3448 6485 3447 6485 3373 6485 3447 6486 3451 6486 3373 6486 3454 6487 3006 6487 2997 6487 3417 6488 3372 6488 3374 6488 3417 6489 3374 6489 3429 6489 3295 270 3291 270 3476 270 3291 6490 3287 6490 3476 6490 3287 605 3286 605 3476 605 3286 270 3285 270 3476 270 3285 6491 3284 6491 3476 6491 3284 6492 3290 6492 3476 6492 3476 603 3290 603 3294 603 3294 270 3299 270 3476 270 3299 6493 3303 6493 3476 6493 3303 1546 3304 1546 3476 1546 3304 6494 3300 6494 3476 6494 3300 270 3298 270 3476 270 3476 6495 3298 6495 3295 6495 2413 6496 2411 6496 2408 6496 2408 6497 2406 6497 2404 6497 2404 6498 2415 6498 2413 6498 2408 6499 2404 6499 2413 6499 2433 6500 3475 6500 3474 6500 3474 6501 3473 6501 2468 6501 2468 6502 2431 6502 2433 6502 3474 6503 2468 6503 2433 6503 3477 6504 3478 6504 3479 6504 3479 6505 3480 6505 3477 6505 3477 6506 3480 6506 3481 6506 3477 6507 3481 6507 3482 6507 3482 6508 3481 6508 3483 6508 3484 6509 3485 6509 3486 6509 3481 6510 3487 6510 3483 6510 3483 6511 3487 6511 3484 6511 3483 6512 3484 6512 3488 6512 3488 6513 3484 6513 3486 6513 3489 270 3490 270 3491 270 3491 270 3490 270 3492 270 3491 6514 3492 6514 3493 6514 3494 6515 3495 6515 3496 6515 3496 270 3495 270 3497 270 3493 6516 3498 6516 3491 6516 3491 6517 3498 6517 3499 6517 3491 6518 3499 6518 3495 6518 3494 6519 3500 6519 3495 6519 3495 6520 3500 6520 3501 6520 3495 6521 3501 6521 3491 6521 3502 64 3503 64 3504 64 3505 64 3506 64 3504 64 3507 6522 3504 6522 3508 6522 3508 6523 3504 6523 3489 6523 3508 64 3489 64 3509 64 3491 64 3480 64 3489 64 3489 6524 3480 6524 3479 6524 3504 6525 3506 6525 3502 6525 3502 6526 3506 6526 3510 6526 3502 6527 3510 6527 3511 6527 3511 6528 3512 6528 3502 6528 3502 6529 3512 6529 3513 6529 3502 6530 3513 6530 3514 6530 3507 64 3515 64 3504 64 3504 6531 3515 6531 3516 6531 3504 6532 3516 6532 3517 6532 3479 6533 3518 6533 3489 6533 3489 64 3518 64 3519 64 3489 64 3519 64 3520 64 3521 6534 3522 6534 3523 6534 3517 64 3524 64 3504 64 3504 6535 3524 6535 3525 6535 3504 6536 3525 6536 3505 6536 3520 64 3526 64 3489 64 3489 6537 3526 6537 3527 6537 3489 6538 3527 6538 3509 6538 3514 6539 3528 6539 3502 6539 3502 6540 3528 6540 3529 6540 3502 6541 3529 6541 3530 6541 3530 64 3531 64 3502 64 3502 6542 3531 6542 3521 6542 3502 6543 3521 6543 3532 6543 3532 6544 3521 6544 3523 6544 3477 583 3492 583 3478 583 3478 583 3492 583 3490 583 3478 6545 3490 6545 3533 6545 3534 583 3535 583 3490 583 3490 6546 3535 6546 3536 6546 3490 6547 3536 6547 3537 6547 3538 6548 3539 6548 3490 6548 3540 6549 3541 6549 3542 6549 3542 6550 3541 6550 3543 6550 3537 6551 3544 6551 3490 6551 3490 583 3544 583 3545 583 3490 583 3545 583 3533 583 3538 583 3490 583 3546 583 3539 583 3547 583 3490 583 3490 6552 3547 6552 3548 6552 3490 6553 3548 6553 3534 6553 3543 6554 3549 6554 3542 6554 3542 6555 3549 6555 3550 6555 3542 6556 3550 6556 3551 6556 3551 583 3550 583 3552 583 3552 6557 3550 6557 3553 6557 3552 583 3553 583 3490 583 3490 6558 3553 6558 3554 6558 3490 6559 3554 6559 3546 6559 3555 6560 3556 6560 3542 6560 3542 6561 3556 6561 3557 6561 3542 6562 3557 6562 3540 6562 3542 583 3558 583 3555 583 3555 6563 3558 6563 3559 6563 3555 6564 3559 6564 3560 6564 3560 583 3561 583 3555 583 3555 583 3561 583 3562 583 3555 6565 3562 6565 3563 6565 3564 6566 3565 6566 3485 6566 3485 6567 3565 6567 3566 6567 3485 6568 3566 6568 3486 6568 3490 6569 3489 6569 3552 6569 3552 6570 3489 6570 3504 6570 3552 496 3504 496 3551 496 3551 496 3504 496 3503 496 3551 6571 3503 6571 3542 6571 3542 6572 3503 6572 3502 6572 3542 6573 3502 6573 3558 6573 3558 6573 3502 6573 3532 6573 3558 6574 3532 6574 3559 6574 3559 6574 3532 6574 3523 6574 3559 6575 3523 6575 3560 6575 3560 6575 3523 6575 3522 6575 3560 6576 3522 6576 3561 6576 3561 6577 3522 6577 3521 6577 3561 6578 3521 6578 3562 6578 3562 6579 3521 6579 3531 6579 3562 6580 3531 6580 3563 6580 3563 6581 3531 6581 3530 6581 3563 6582 3530 6582 3555 6582 3555 6582 3530 6582 3529 6582 3555 6583 3529 6583 3556 6583 3556 6584 3529 6584 3528 6584 3556 6585 3528 6585 3557 6585 3557 6586 3528 6586 3514 6586 3557 6587 3514 6587 3540 6587 3540 6588 3514 6588 3513 6588 3540 6589 3513 6589 3541 6589 3541 6589 3513 6589 3512 6589 3541 6590 3512 6590 3543 6590 3543 6591 3512 6591 3511 6591 3543 6592 3511 6592 3549 6592 3549 6593 3511 6593 3510 6593 3549 6594 3510 6594 3550 6594 3550 6595 3510 6595 3506 6595 3550 6596 3506 6596 3553 6596 3553 6596 3506 6596 3505 6596 3553 6597 3505 6597 3554 6597 3554 6598 3505 6598 3525 6598 3554 6599 3525 6599 3546 6599 3546 6599 3525 6599 3524 6599 3546 6600 3524 6600 3538 6600 3538 6600 3524 6600 3517 6600 3538 6601 3517 6601 3539 6601 3539 6601 3517 6601 3516 6601 3539 6602 3516 6602 3547 6602 3547 6603 3516 6603 3515 6603 3547 6604 3515 6604 3548 6604 3548 6604 3515 6604 3507 6604 3548 6605 3507 6605 3534 6605 3534 6605 3507 6605 3508 6605 3534 6606 3508 6606 3535 6606 3535 6606 3508 6606 3509 6606 3535 6607 3509 6607 3536 6607 3536 6608 3509 6608 3527 6608 3536 6609 3527 6609 3537 6609 3537 6610 3527 6610 3526 6610 3537 6611 3526 6611 3544 6611 3544 6612 3526 6612 3520 6612 3544 6613 3520 6613 3545 6613 3545 6613 3520 6613 3519 6613 3545 6614 3519 6614 3533 6614 3533 6615 3519 6615 3518 6615 3518 6616 3479 6616 3533 6616 3533 6617 3479 6617 3478 6617 3498 6618 3493 6618 3483 6618 3483 6619 3493 6619 3482 6619 3499 6620 3498 6620 3488 6620 3488 6621 3498 6621 3483 6621 3500 6622 3494 6622 3487 6622 3487 6623 3494 6623 3484 6623 3501 6624 3500 6624 3481 6624 3481 6625 3500 6625 3487 6625 3491 6626 3501 6626 3480 6626 3480 6627 3501 6627 3481 6627 3493 6628 3492 6628 3482 6628 3482 6629 3492 6629 3477 6629 3566 6630 3495 6630 3486 6630 3486 6631 3495 6631 3499 6631 3486 6632 3499 6632 3488 6632 3496 6633 3564 6633 3494 6633 3494 6634 3564 6634 3485 6634 3494 6635 3485 6635 3484 6635 3495 6636 3566 6636 3567 6636 3567 6637 3566 6637 3568 6637 3569 6638 3570 6638 3496 6638 3496 6639 3570 6639 3564 6639 3571 6640 3572 6640 3573 6640 3571 6641 3573 6641 3574 6641 3575 6642 3576 6642 3577 6642 3575 6643 3577 6643 3578 6643 3579 6644 3580 6644 3581 6644 3579 6645 3581 6645 3582 6645 3583 6646 3584 6646 3585 6646 3583 6647 3585 6647 3586 6647 3587 6648 3588 6648 3577 6648 3587 6649 3577 6649 3576 6649 3584 6650 3589 6650 3590 6650 3584 6651 3590 6651 3585 6651 3589 6652 3591 6652 3592 6652 3589 6653 3592 6653 3590 6653 3593 6654 3594 6654 3595 6654 3593 6655 3595 6655 3596 6655 3594 6656 3597 6656 3598 6656 3594 6657 3598 6657 3595 6657 3597 6658 3599 6658 3600 6658 3597 6659 3600 6659 3598 6659 3599 6660 3601 6660 3602 6660 3599 6661 3602 6661 3600 6661 3601 6662 3603 6662 3604 6662 3601 6663 3604 6663 3602 6663 3605 6664 3606 6664 3607 6664 3605 6665 3607 6665 3608 6665 3609 6666 3610 6666 3611 6666 3609 6667 3611 6667 3612 6667 3613 6668 3579 6668 3582 6668 3613 6669 3582 6669 3614 6669 3615 6670 3616 6670 3574 6670 3615 6671 3574 6671 3573 6671 3616 6672 3617 6672 3618 6672 3616 6673 3618 6673 3574 6673 3617 6674 3619 6674 3620 6674 3617 6675 3620 6675 3618 6675 3619 6676 3621 6676 3622 6676 3619 6677 3622 6677 3620 6677 3621 6678 3623 6678 3624 6678 3621 6679 3624 6679 3622 6679 3623 6680 3625 6680 3626 6680 3623 6681 3626 6681 3624 6681 3625 6682 3627 6682 3628 6682 3625 6683 3628 6683 3626 6683 3627 6684 3629 6684 3630 6684 3627 6685 3630 6685 3628 6685 3629 6686 3631 6686 3632 6686 3629 6687 3632 6687 3630 6687 3633 6688 3634 6688 3635 6688 3633 6689 3635 6689 3636 6689 3634 6690 3637 6690 3638 6690 3634 6691 3638 6691 3635 6691 3637 6692 3639 6692 3640 6692 3637 6693 3640 6693 3638 6693 3641 6694 3642 6694 3643 6694 3641 6695 3643 6695 3644 6695 3642 6696 3645 6696 3646 6696 3642 6697 3646 6697 3643 6697 3645 6698 3647 6698 3648 6698 3645 6699 3648 6699 3646 6699 3647 6700 3649 6700 3650 6700 3647 6701 3650 6701 3648 6701 3649 6702 3651 6702 3652 6702 3649 6703 3652 6703 3650 6703 3651 6704 3653 6704 3654 6704 3651 6705 3654 6705 3652 6705 3653 6706 3575 6706 3578 6706 3653 6707 3578 6707 3654 6707 3588 6708 3655 6708 3578 6708 3588 6709 3578 6709 3577 6709 3655 6710 3656 6710 3654 6710 3655 6711 3654 6711 3578 6711 3656 6712 3657 6712 3652 6712 3656 6713 3652 6713 3654 6713 3657 6714 3658 6714 3650 6714 3657 6715 3650 6715 3652 6715 3658 6716 3659 6716 3648 6716 3658 6717 3648 6717 3650 6717 3659 6718 3660 6718 3646 6718 3659 6719 3646 6719 3648 6719 3660 6720 3661 6720 3643 6720 3660 6721 3643 6721 3646 6721 3662 6722 3663 6722 3640 6722 3662 6723 3640 6723 3664 6723 3663 6724 3665 6724 3638 6724 3663 6725 3638 6725 3640 6725 3665 6726 3666 6726 3635 6726 3665 6727 3635 6727 3638 6727 3667 6728 3668 6728 3632 6728 3667 6729 3632 6729 3669 6729 3668 6730 3670 6730 3630 6730 3668 6731 3630 6731 3632 6731 3670 6732 3671 6732 3628 6732 3670 6733 3628 6733 3630 6733 3671 6734 3672 6734 3626 6734 3671 6735 3626 6735 3628 6735 3672 6736 3673 6736 3624 6736 3672 6737 3624 6737 3626 6737 3673 6738 3674 6738 3622 6738 3673 6739 3622 6739 3624 6739 3674 6740 3675 6740 3620 6740 3674 6741 3620 6741 3622 6741 3675 6742 3676 6742 3618 6742 3675 6743 3618 6743 3620 6743 3676 6744 3571 6744 3574 6744 3676 6745 3574 6745 3618 6745 3677 6746 3678 6746 3679 6746 3677 6747 3679 6747 3680 6747 3681 6748 3682 6748 3683 6748 3681 6749 3683 6749 3684 6749 3685 6750 3686 6750 3687 6750 3685 6751 3687 6751 3688 6751 3688 6752 3687 6752 3689 6752 3688 6753 3689 6753 3690 6753 3613 6754 3691 6754 3692 6754 3613 6755 3692 6755 3579 6755 3691 6756 3693 6756 3694 6756 3691 6757 3694 6757 3692 6757 3693 6758 3695 6758 3696 6758 3693 6759 3696 6759 3694 6759 3695 6760 3697 6760 3698 6760 3695 6761 3698 6761 3696 6761 3697 6762 3699 6762 3700 6762 3697 6763 3700 6763 3698 6763 3699 6764 3701 6764 3702 6764 3699 6765 3702 6765 3700 6765 3701 6766 3703 6766 3704 6766 3701 6767 3704 6767 3702 6767 3703 6768 3705 6768 3706 6768 3703 6769 3706 6769 3704 6769 3707 6770 3708 6770 3691 6770 3707 6771 3691 6771 3613 6771 3708 6772 3709 6772 3693 6772 3708 6773 3693 6773 3691 6773 3709 6774 3710 6774 3695 6774 3709 6775 3695 6775 3693 6775 3710 6776 3711 6776 3697 6776 3710 6777 3697 6777 3695 6777 3711 6778 3712 6778 3699 6778 3711 6779 3699 6779 3697 6779 3712 6780 3713 6780 3701 6780 3712 6781 3701 6781 3699 6781 3713 6782 3714 6782 3703 6782 3713 6783 3703 6783 3701 6783 3714 6784 3715 6784 3705 6784 3714 6785 3705 6785 3703 6785 3716 6786 3717 6786 3718 6786 3716 6787 3718 6787 3719 6787 3717 6788 3720 6788 3721 6788 3717 6789 3721 6789 3718 6789 3610 6790 3722 6790 3717 6790 3610 6791 3717 6791 3716 6791 3722 6792 3723 6792 3720 6792 3722 6793 3720 6793 3717 6793 3609 6794 3724 6794 3722 6794 3609 6795 3722 6795 3610 6795 3724 6796 3725 6796 3723 6796 3724 6797 3723 6797 3722 6797 3726 6798 3727 6798 3724 6798 3726 6799 3724 6799 3609 6799 3605 6800 3728 6800 3729 6800 3605 6801 3729 6801 3606 6801 3601 6802 3730 6802 3731 6802 3601 6803 3731 6803 3603 6803 3599 6804 3732 6804 3730 6804 3599 6805 3730 6805 3601 6805 3597 6806 3733 6806 3732 6806 3597 6807 3732 6807 3599 6807 3589 6808 3734 6808 3735 6808 3589 6809 3735 6809 3591 6809 3734 6810 3736 6810 3737 6810 3734 6811 3737 6811 3735 6811 3736 6812 3738 6812 3739 6812 3736 6813 3739 6813 3737 6813 3738 6814 3740 6814 3741 6814 3738 6815 3741 6815 3739 6815 3740 6816 3742 6816 3743 6816 3740 6817 3743 6817 3741 6817 3742 6818 3744 6818 3745 6818 3742 6819 3745 6819 3743 6819 3584 6820 3746 6820 3734 6820 3584 6821 3734 6821 3589 6821 3746 6822 3747 6822 3736 6822 3746 6823 3736 6823 3734 6823 3747 6824 3748 6824 3738 6824 3747 6825 3738 6825 3736 6825 3748 6826 3749 6826 3740 6826 3748 6827 3740 6827 3738 6827 3749 6828 3750 6828 3742 6828 3749 6829 3742 6829 3740 6829 3750 6830 3751 6830 3744 6830 3750 6831 3744 6831 3742 6831 3751 6832 3752 6832 3753 6832 3751 6833 3753 6833 3744 6833 3752 6834 3754 6834 3755 6834 3752 6835 3755 6835 3753 6835 3754 6836 3756 6836 3757 6836 3754 6837 3757 6837 3755 6837 3758 6838 3759 6838 3757 6838 3757 6839 3756 6839 3760 6839 3760 6840 3761 6840 3758 6840 3757 6841 3760 6841 3758 6841 3676 6842 3762 6842 3763 6842 3676 6843 3763 6843 3571 6843 3762 6844 3764 6844 3765 6844 3762 6845 3765 6845 3763 6845 3764 6846 3766 6846 3767 6846 3764 6847 3767 6847 3765 6847 3766 6848 3768 6848 3769 6848 3766 6849 3769 6849 3767 6849 3768 6850 3770 6850 3771 6850 3768 6851 3771 6851 3769 6851 3770 6852 3772 6852 3773 6852 3770 6853 3773 6853 3771 6853 3772 6854 3774 6854 3775 6854 3772 6855 3775 6855 3773 6855 3774 6856 3776 6856 3777 6856 3774 6857 3777 6857 3775 6857 3776 6858 3778 6858 3779 6858 3776 6859 3779 6859 3777 6859 3778 6860 3780 6860 3781 6860 3778 6861 3781 6861 3779 6861 3780 6862 3782 6862 3783 6862 3780 6863 3783 6863 3781 6863 3782 6864 3784 6864 3785 6864 3782 6865 3785 6865 3783 6865 3784 6866 3786 6866 3787 6866 3784 6867 3787 6867 3785 6867 3786 6868 3788 6868 3789 6868 3786 6869 3789 6869 3787 6869 3675 6870 3790 6870 3762 6870 3675 6871 3762 6871 3676 6871 3790 6872 3791 6872 3764 6872 3790 6873 3764 6873 3762 6873 3791 6874 3792 6874 3766 6874 3791 6875 3766 6875 3764 6875 3792 6876 3793 6876 3768 6876 3792 6877 3768 6877 3766 6877 3793 6878 3794 6878 3770 6878 3793 6879 3770 6879 3768 6879 3794 6880 3795 6880 3772 6880 3794 6881 3772 6881 3770 6881 3795 6882 3796 6882 3774 6882 3795 6883 3774 6883 3772 6883 3796 6884 3797 6884 3776 6884 3796 6885 3776 6885 3774 6885 3797 6886 3798 6886 3778 6886 3797 6887 3778 6887 3776 6887 3798 6888 3799 6888 3780 6888 3798 6889 3780 6889 3778 6889 3799 6890 3800 6890 3782 6890 3799 6891 3782 6891 3780 6891 3800 6892 3801 6892 3784 6892 3800 6893 3784 6893 3782 6893 3801 6894 3802 6894 3786 6894 3801 6895 3786 6895 3784 6895 3802 6896 3803 6896 3788 6896 3802 6897 3788 6897 3786 6897 3674 6898 3804 6898 3790 6898 3674 6899 3790 6899 3675 6899 3804 6900 3805 6900 3791 6900 3804 6901 3791 6901 3790 6901 3805 6902 3806 6902 3792 6902 3805 6903 3792 6903 3791 6903 3806 6904 3807 6904 3793 6904 3806 6905 3793 6905 3792 6905 3807 6906 3808 6906 3794 6906 3807 6907 3794 6907 3793 6907 3808 6908 3809 6908 3795 6908 3808 6909 3795 6909 3794 6909 3809 6910 3810 6910 3796 6910 3809 6911 3796 6911 3795 6911 3810 6912 3811 6912 3797 6912 3810 6913 3797 6913 3796 6913 3811 6914 3812 6914 3798 6914 3811 6915 3798 6915 3797 6915 3812 6916 3813 6916 3799 6916 3812 6917 3799 6917 3798 6917 3813 6918 3814 6918 3800 6918 3813 6919 3800 6919 3799 6919 3814 6920 3815 6920 3801 6920 3814 6921 3801 6921 3800 6921 3815 6922 3816 6922 3802 6922 3815 6923 3802 6923 3801 6923 3816 6924 3817 6924 3803 6924 3816 6925 3803 6925 3802 6925 3817 6926 3818 6926 3819 6926 3817 6927 3819 6927 3803 6927 3673 6928 3820 6928 3804 6928 3673 6929 3804 6929 3674 6929 3820 6930 3821 6930 3805 6930 3820 6931 3805 6931 3804 6931 3821 6932 3822 6932 3806 6932 3821 6933 3806 6933 3805 6933 3822 6934 3823 6934 3807 6934 3822 6935 3807 6935 3806 6935 3823 6936 3824 6936 3808 6936 3823 6937 3808 6937 3807 6937 3824 6938 3825 6938 3809 6938 3824 6939 3809 6939 3808 6939 3825 6940 3826 6940 3810 6940 3825 6941 3810 6941 3809 6941 3826 6942 3827 6942 3811 6942 3826 6943 3811 6943 3810 6943 3827 6944 3828 6944 3812 6944 3827 6945 3812 6945 3811 6945 3828 6946 3829 6946 3813 6946 3828 6947 3813 6947 3812 6947 3829 6948 3830 6948 3814 6948 3829 6949 3814 6949 3813 6949 3830 6950 3831 6950 3815 6950 3830 6951 3815 6951 3814 6951 3831 6952 3832 6952 3816 6952 3831 6953 3816 6953 3815 6953 3832 6954 3833 6954 3817 6954 3832 6955 3817 6955 3816 6955 3833 6956 3834 6956 3818 6956 3833 6957 3818 6957 3817 6957 3672 6958 3835 6958 3820 6958 3672 6959 3820 6959 3673 6959 3835 6960 3836 6960 3821 6960 3835 6961 3821 6961 3820 6961 3836 6962 3837 6962 3822 6962 3836 6963 3822 6963 3821 6963 3837 6964 3838 6964 3823 6964 3837 6965 3823 6965 3822 6965 3838 6966 3839 6966 3824 6966 3838 6967 3824 6967 3823 6967 3839 6968 3840 6968 3825 6968 3839 6969 3825 6969 3824 6969 3840 6970 3841 6970 3826 6970 3840 6971 3826 6971 3825 6971 3841 6972 3842 6972 3827 6972 3841 6973 3827 6973 3826 6973 3842 6974 3843 6974 3828 6974 3842 6975 3828 6975 3827 6975 3843 6976 3844 6976 3829 6976 3843 6977 3829 6977 3828 6977 3844 6978 3845 6978 3830 6978 3844 6979 3830 6979 3829 6979 3845 6980 3846 6980 3831 6980 3845 6981 3831 6981 3830 6981 3846 6982 3847 6982 3832 6982 3846 6983 3832 6983 3831 6983 3847 6984 3848 6984 3833 6984 3847 6985 3833 6985 3832 6985 3848 6986 3849 6986 3834 6986 3848 6987 3834 6987 3833 6987 3671 6988 3850 6988 3835 6988 3671 6989 3835 6989 3672 6989 3850 6990 3851 6990 3836 6990 3850 6991 3836 6991 3835 6991 3851 6992 3852 6992 3837 6992 3851 6993 3837 6993 3836 6993 3852 6994 3853 6994 3838 6994 3852 6995 3838 6995 3837 6995 3853 6996 3854 6996 3839 6996 3853 6997 3839 6997 3838 6997 3854 6998 3855 6998 3840 6998 3854 6999 3840 6999 3839 6999 3855 7000 3856 7000 3841 7000 3855 7001 3841 7001 3840 7001 3856 7002 3857 7002 3842 7002 3856 7003 3842 7003 3841 7003 3857 7004 3858 7004 3843 7004 3857 7005 3843 7005 3842 7005 3858 7006 3859 7006 3844 7006 3858 7007 3844 7007 3843 7007 3859 7008 3860 7008 3845 7008 3859 7009 3845 7009 3844 7009 3860 7010 3861 7010 3846 7010 3860 7011 3846 7011 3845 7011 3861 7012 3862 7012 3847 7012 3861 7013 3847 7013 3846 7013 3862 7014 3863 7014 3848 7014 3862 7015 3848 7015 3847 7015 3670 7016 3864 7016 3850 7016 3670 7017 3850 7017 3671 7017 3864 7018 3865 7018 3851 7018 3864 7019 3851 7019 3850 7019 3865 7020 3866 7020 3852 7020 3865 7021 3852 7021 3851 7021 3866 7022 3867 7022 3853 7022 3866 7023 3853 7023 3852 7023 3867 7024 3868 7024 3854 7024 3867 7025 3854 7025 3853 7025 3868 7026 3869 7026 3855 7026 3868 7027 3855 7027 3854 7027 3869 7028 3870 7028 3856 7028 3869 7029 3856 7029 3855 7029 3870 7030 3871 7030 3857 7030 3870 7031 3857 7031 3856 7031 3871 7032 3872 7032 3858 7032 3871 7033 3858 7033 3857 7033 3872 7034 3873 7034 3859 7034 3872 7035 3859 7035 3858 7035 3873 7036 3874 7036 3860 7036 3873 7037 3860 7037 3859 7037 3874 7038 3875 7038 3861 7038 3874 7039 3861 7039 3860 7039 3875 7040 3876 7040 3862 7040 3875 7041 3862 7041 3861 7041 3876 7042 3877 7042 3863 7042 3876 7043 3863 7043 3862 7043 3668 7044 3878 7044 3864 7044 3668 7045 3864 7045 3670 7045 3878 7046 3879 7046 3865 7046 3878 7047 3865 7047 3864 7047 3879 7048 3880 7048 3866 7048 3879 7049 3866 7049 3865 7049 3880 7050 3881 7050 3867 7050 3880 7051 3867 7051 3866 7051 3881 7052 3882 7052 3868 7052 3881 7053 3868 7053 3867 7053 3882 7054 3883 7054 3869 7054 3882 7055 3869 7055 3868 7055 3883 7056 3884 7056 3870 7056 3883 7057 3870 7057 3869 7057 3884 7058 3885 7058 3871 7058 3884 7059 3871 7059 3870 7059 3885 7060 3886 7060 3872 7060 3885 7061 3872 7061 3871 7061 3886 7062 3887 7062 3873 7062 3886 7063 3873 7063 3872 7063 3887 7064 3888 7064 3874 7064 3887 7065 3874 7065 3873 7065 3888 7066 3889 7066 3875 7066 3888 7067 3875 7067 3874 7067 3889 7068 3890 7068 3876 7068 3889 7069 3876 7069 3875 7069 3890 7070 3891 7070 3877 7070 3890 7071 3877 7071 3876 7071 3891 7072 3892 7072 3893 7072 3891 7073 3893 7073 3877 7073 3892 7074 3894 7074 3895 7074 3892 7075 3895 7075 3893 7075 3894 7076 3896 7076 3897 7076 3894 7077 3897 7077 3898 7077 3896 7078 3899 7078 3900 7078 3896 7079 3900 7079 3897 7079 3899 7080 3901 7080 3902 7080 3899 7081 3902 7081 3900 7081 3901 7082 3688 7082 3690 7082 3901 7083 3690 7083 3902 7083 3667 7084 3903 7084 3878 7084 3667 7085 3878 7085 3668 7085 3903 7086 3904 7086 3879 7086 3903 7087 3879 7087 3878 7087 3904 7088 3905 7088 3880 7088 3904 7089 3880 7089 3879 7089 3905 7090 3906 7090 3881 7090 3905 7091 3881 7091 3880 7091 3906 7092 3907 7092 3882 7092 3906 7093 3882 7093 3881 7093 3907 7094 3908 7094 3883 7094 3907 7095 3883 7095 3882 7095 3908 7096 3909 7096 3884 7096 3908 7097 3884 7097 3883 7097 3909 7098 3910 7098 3885 7098 3909 7099 3885 7099 3884 7099 3910 7100 3911 7100 3886 7100 3910 7101 3886 7101 3885 7101 3911 7102 3912 7102 3887 7102 3911 7103 3887 7103 3886 7103 3912 7104 3913 7104 3888 7104 3912 7105 3888 7105 3887 7105 3913 7106 3914 7106 3889 7106 3913 7107 3889 7107 3888 7107 3914 7108 3915 7108 3890 7108 3914 7109 3890 7109 3889 7109 3915 7110 3916 7110 3891 7110 3915 7111 3891 7111 3890 7111 3916 7112 3917 7112 3892 7112 3916 7113 3892 7113 3891 7113 3917 7114 3918 7114 3894 7114 3917 7115 3894 7115 3892 7115 3918 7116 3919 7116 3896 7116 3918 7117 3896 7117 3894 7117 3919 7118 3920 7118 3899 7118 3919 7119 3899 7119 3896 7119 3920 7120 3921 7120 3901 7120 3920 7121 3901 7121 3899 7121 3921 7122 3685 7122 3688 7122 3921 7123 3688 7123 3901 7123 3922 7124 3923 7124 3924 7124 3922 7125 3924 7125 3925 7125 3926 7126 3927 7126 3928 7126 3926 7127 3928 7127 3929 7127 3927 7128 3930 7128 3931 7128 3927 7129 3931 7129 3928 7129 3930 7130 3932 7130 3933 7130 3930 7131 3933 7131 3931 7131 3932 7132 3934 7132 3935 7132 3932 7133 3935 7133 3933 7133 3934 7134 3936 7134 3937 7134 3934 7135 3937 7135 3935 7135 3936 7136 3938 7136 3939 7136 3936 7137 3939 7137 3937 7137 3938 7138 3940 7138 3941 7138 3938 7139 3941 7139 3939 7139 3940 7140 3942 7140 3943 7140 3940 7141 3943 7141 3941 7141 3942 7142 3944 7142 3945 7142 3942 7143 3945 7143 3943 7143 3944 7144 3946 7144 3947 7144 3944 7145 3947 7145 3945 7145 3946 7146 3948 7146 3949 7146 3946 7147 3949 7147 3947 7147 3948 7148 3681 7148 3684 7148 3948 7149 3684 7149 3949 7149 3665 7150 3950 7150 3951 7150 3665 7151 3951 7151 3666 7151 3950 7152 3952 7152 3953 7152 3950 7153 3953 7153 3951 7153 3952 7154 3954 7154 3955 7154 3952 7155 3955 7155 3953 7155 3954 7156 3956 7156 3957 7156 3954 7157 3957 7157 3955 7157 3956 7158 3958 7158 3959 7158 3956 7159 3959 7159 3957 7159 3958 7160 3960 7160 3961 7160 3958 7161 3961 7161 3959 7161 3960 7162 3962 7162 3963 7162 3960 7163 3963 7163 3961 7163 3962 7164 3964 7164 3965 7164 3962 7165 3965 7165 3963 7165 3964 7166 3966 7166 3967 7166 3964 7167 3967 7167 3965 7167 3966 7168 3968 7168 3969 7168 3966 7169 3969 7169 3967 7169 3968 7170 3970 7170 3971 7170 3968 7171 3971 7171 3969 7171 3970 7172 3972 7172 3973 7172 3970 7173 3973 7173 3971 7173 3972 7174 3974 7174 3975 7174 3972 7175 3975 7175 3973 7175 3974 7176 3976 7176 3977 7176 3974 7177 3977 7177 3975 7177 3976 7178 3978 7178 3979 7178 3976 7179 3979 7179 3977 7179 3978 7180 3980 7180 3981 7180 3978 7181 3981 7181 3979 7181 3980 7182 3982 7182 3983 7182 3980 7183 3983 7183 3981 7183 3982 7184 3984 7184 3985 7184 3982 7185 3985 7185 3983 7185 3984 7186 3986 7186 3987 7186 3984 7187 3987 7187 3985 7187 3986 7188 3677 7188 3680 7188 3986 7189 3680 7189 3987 7189 3663 7190 3988 7190 3950 7190 3663 7191 3950 7191 3665 7191 3988 7192 3989 7192 3952 7192 3988 7193 3952 7193 3950 7193 3989 7194 3990 7194 3954 7194 3989 7195 3954 7195 3952 7195 3990 7196 3991 7196 3956 7196 3990 7197 3956 7197 3954 7197 3991 7198 3992 7198 3958 7198 3991 7199 3958 7199 3956 7199 3992 7200 3993 7200 3960 7200 3992 7201 3960 7201 3958 7201 3993 7202 3994 7202 3962 7202 3993 7203 3962 7203 3960 7203 3994 7204 3995 7204 3964 7204 3994 7205 3964 7205 3962 7205 3995 7206 3996 7206 3966 7206 3995 7207 3966 7207 3964 7207 3996 7208 3997 7208 3968 7208 3996 7209 3968 7209 3966 7209 3997 7210 3998 7210 3970 7210 3997 7211 3970 7211 3968 7211 3998 7212 3999 7212 3972 7212 3998 7213 3972 7213 3970 7213 3999 7214 4000 7214 3974 7214 3999 7215 3974 7215 3972 7215 4000 7216 4001 7216 3976 7216 4000 7217 3976 7217 3974 7217 4001 7218 4002 7218 3978 7218 4001 7219 3978 7219 3976 7219 4002 7220 4003 7220 3980 7220 4002 7221 3980 7221 3978 7221 4003 7222 4004 7222 3982 7222 4003 7223 3982 7223 3980 7223 4004 7224 4005 7224 3984 7224 4004 7225 3984 7225 3982 7225 4005 7226 4006 7226 3986 7226 4005 7227 3986 7227 3984 7227 4006 7228 4007 7228 3677 7228 4006 7229 3677 7229 3986 7229 3662 7230 4008 7230 3988 7230 3662 7231 3988 7231 3663 7231 4008 7232 4009 7232 3989 7232 4008 7233 3989 7233 3988 7233 4009 7234 4010 7234 3990 7234 4009 7235 3990 7235 3989 7235 4010 7236 4011 7236 3991 7236 4010 7237 3991 7237 3990 7237 4011 7238 4012 7238 3992 7238 4011 7239 3992 7239 3991 7239 4012 7240 4013 7240 3993 7240 4012 7241 3993 7241 3992 7241 4013 7242 4014 7242 3994 7242 4013 7243 3994 7243 3993 7243 4014 7244 4015 7244 3995 7244 4014 7245 3995 7245 3994 7245 4015 7246 4016 7246 3996 7246 4015 7247 3996 7247 3995 7247 4016 7248 4017 7248 3997 7248 4016 7249 3997 7249 3996 7249 4017 7250 4018 7250 3998 7250 4017 7251 3998 7251 3997 7251 4018 7252 4019 7252 3999 7252 4018 7253 3999 7253 3998 7253 4019 7254 4020 7254 4000 7254 4019 7255 4000 7255 3999 7255 4020 7256 4021 7256 4001 7256 4020 7257 4001 7257 4000 7257 4001 7258 4021 7258 4022 7258 4022 7259 4023 7259 4002 7259 4022 7260 4002 7260 4001 7260 4024 7261 4025 7261 4005 7261 4024 7262 4005 7262 4004 7262 4025 7263 4026 7263 4005 7263 4026 7264 4006 7264 4005 7264 3660 7265 4027 7265 4028 7265 3660 7266 4028 7266 3661 7266 4027 7267 4029 7267 4030 7267 4027 7268 4030 7268 4028 7268 4029 7269 4031 7269 4032 7269 4029 7270 4032 7270 4030 7270 4031 7271 4033 7271 4034 7271 4031 7272 4034 7272 4032 7272 4033 7273 4035 7273 4036 7273 4033 7274 4036 7274 4034 7274 4035 7275 4037 7275 4038 7275 4035 7276 4038 7276 4036 7276 4037 7277 4039 7277 4040 7277 4037 7278 4040 7278 4038 7278 4039 7279 4041 7279 4042 7279 4039 7280 4042 7280 4040 7280 4041 7281 4043 7281 4044 7281 4041 7282 4044 7282 4042 7282 4043 7283 4045 7283 4046 7283 4043 7284 4046 7284 4044 7284 4045 7285 4047 7285 4048 7285 4045 7286 4048 7286 4046 7286 4047 7287 4049 7287 4050 7287 4047 7288 4050 7288 4048 7288 3659 7289 4051 7289 4027 7289 3659 7290 4027 7290 3660 7290 4051 7291 4052 7291 4029 7291 4051 7292 4029 7292 4027 7292 4052 7293 4053 7293 4031 7293 4052 7294 4031 7294 4029 7294 4053 7295 4054 7295 4033 7295 4053 7296 4033 7296 4031 7296 4054 7297 4055 7297 4035 7297 4054 7298 4035 7298 4033 7298 4055 7299 4056 7299 4037 7299 4055 7300 4037 7300 4035 7300 4056 7301 4057 7301 4039 7301 4056 7302 4039 7302 4037 7302 4057 7303 4058 7303 4041 7303 4057 7304 4041 7304 4039 7304 4058 7305 4059 7305 4043 7305 4058 7306 4043 7306 4041 7306 4059 7307 4060 7307 4045 7307 4059 7308 4045 7308 4043 7308 3658 7309 4061 7309 4051 7309 3658 7310 4051 7310 3659 7310 4061 7311 4062 7311 4052 7311 4061 7312 4052 7312 4051 7312 4062 7313 4063 7313 4053 7313 4062 7314 4053 7314 4052 7314 4063 7315 4064 7315 4054 7315 4063 7316 4054 7316 4053 7316 4064 7317 4065 7317 4055 7317 4064 7318 4055 7318 4054 7318 4065 7319 4066 7319 4056 7319 4065 7320 4056 7320 4055 7320 4066 7321 4067 7321 4057 7321 4066 7322 4057 7322 4056 7322 4067 7323 4068 7323 4058 7323 4067 7324 4058 7324 4057 7324 3657 7325 4069 7325 4061 7325 3657 7326 4061 7326 3658 7326 4069 7327 4070 7327 4062 7327 4069 7328 4062 7328 4061 7328 4070 7329 4071 7329 4063 7329 4070 7330 4063 7330 4062 7330 4071 7331 4072 7331 4064 7331 4071 7332 4064 7332 4063 7332 4072 7333 4073 7333 4065 7333 4072 7334 4065 7334 4064 7334 4073 7335 4074 7335 4066 7335 4073 7336 4066 7336 4065 7336 4074 7337 4075 7337 4067 7337 4074 7338 4067 7338 4066 7338 3656 7339 4076 7339 4069 7339 3656 7340 4069 7340 3657 7340 4076 7341 4077 7341 4070 7341 4076 7342 4070 7342 4069 7342 4077 7343 4078 7343 4071 7343 4077 7344 4071 7344 4070 7344 4078 7345 4079 7345 4072 7345 4078 7346 4072 7346 4071 7346 4079 7347 4080 7347 4073 7347 4079 7348 4073 7348 4072 7348 4080 7349 4081 7349 4074 7349 4080 7350 4074 7350 4073 7350 3655 7351 4082 7351 4076 7351 3655 7352 4076 7352 3656 7352 4082 7353 4083 7353 4077 7353 4082 7354 4077 7354 4076 7354 4083 7355 4084 7355 4078 7355 4083 7356 4078 7356 4077 7356 4084 7357 4085 7357 4079 7357 4084 7358 4079 7358 4078 7358 4085 7359 4086 7359 4080 7359 4085 7360 4080 7360 4079 7360 3588 7361 4087 7361 4082 7361 3588 7362 4082 7362 3655 7362 4087 7363 4088 7363 4083 7363 4087 7364 4083 7364 4082 7364 4088 7365 4089 7365 4084 7365 4088 7366 4084 7366 4083 7366 4089 7367 4090 7367 4085 7367 4089 7368 4085 7368 4084 7368 4090 7369 4091 7369 4086 7369 4090 7370 4086 7370 4085 7370 3571 7371 3763 7371 4092 7371 3571 7372 4092 7372 3572 7372 3763 7373 3765 7373 4093 7373 3763 7374 4093 7374 4092 7374 3765 7375 3767 7375 4094 7375 3765 7376 4094 7376 4093 7376 3767 7377 3769 7377 4095 7377 3767 7378 4095 7378 4094 7378 3769 7379 3771 7379 4096 7379 3769 7380 4096 7380 4095 7380 3771 7381 3773 7381 4097 7381 3771 7382 4097 7382 4096 7382 3773 7383 3775 7383 4098 7383 3773 7384 4098 7384 4097 7384 3775 7385 3777 7385 4099 7385 3775 7386 4099 7386 4098 7386 3777 7387 3779 7387 4100 7387 3777 7388 4100 7388 4099 7388 3779 7389 3781 7389 4101 7389 3779 7390 4101 7390 4100 7390 3781 7391 3783 7391 4102 7391 3781 7392 4102 7392 4101 7392 3783 7393 3785 7393 4103 7393 3783 7394 4103 7394 4102 7394 3785 7395 3787 7395 4104 7395 3785 7396 4104 7396 4103 7396 3587 7397 4105 7397 4087 7397 3587 7398 4087 7398 3588 7398 4105 7399 4106 7399 4088 7399 4105 7400 4088 7400 4087 7400 4106 7401 4107 7401 4089 7401 4106 7402 4089 7402 4088 7402 4107 7403 4108 7403 4090 7403 4107 7404 4090 7404 4089 7404 4108 7405 4109 7405 4091 7405 4108 7406 4091 7406 4090 7406 4109 7407 4110 7407 4111 7407 4109 7408 4111 7408 4091 7408 4110 7409 4112 7409 4113 7409 4110 7410 4113 7410 4111 7410 4112 7411 4114 7411 4115 7411 4112 7412 4115 7412 4113 7412 3579 7413 3692 7413 4116 7413 3579 7414 4116 7414 3580 7414 3692 7415 3694 7415 4117 7415 3692 7416 4117 7416 4116 7416 3694 7417 3696 7417 4118 7417 3694 7418 4118 7418 4117 7418 3696 7419 3698 7419 4119 7419 3696 7420 4119 7420 4118 7420 3698 7421 3700 7421 4120 7421 3698 7422 4120 7422 4119 7422 3700 7423 3702 7423 4121 7423 3700 7424 4121 7424 4120 7424 3702 7425 3704 7425 4122 7425 3702 7426 4122 7426 4121 7426 3704 7427 3706 7427 4123 7427 3704 7428 4123 7428 4122 7428 3583 7429 4124 7429 3746 7429 3583 7430 3746 7430 3584 7430 4124 7431 4125 7431 3747 7431 4124 7432 3747 7432 3746 7432 4125 7433 4126 7433 3748 7433 4125 7434 3748 7434 3747 7434 4126 7435 4127 7435 3749 7435 4126 7436 3749 7436 3748 7436 4127 7437 4128 7437 3750 7437 4127 7438 3750 7438 3749 7438 4128 7439 4129 7439 3751 7439 4128 7440 3751 7440 3750 7440 4129 7441 4130 7441 3752 7441 4129 7442 3752 7442 3751 7442 4130 7443 4131 7443 3754 7443 4130 7444 3754 7444 3752 7444 4131 7445 4132 7445 3756 7445 4131 7446 3756 7446 3754 7446 4132 7447 3760 7447 4133 7447 4132 7448 4133 7448 3756 7448 4134 7449 4135 7449 4136 7449 4134 7450 4136 7450 4137 7450 4137 7451 4136 7451 4138 7451 4137 7452 4138 7452 4139 7452 4139 7453 4138 7453 4140 7453 4139 7454 4140 7454 4141 7454 4141 7455 4140 7455 4142 7455 4141 7456 4142 7456 4143 7456 4143 7457 4142 7457 4144 7457 4142 7458 4145 7458 4144 7458 4103 7459 4104 7459 4146 7459 4103 7460 4146 7460 4147 7460 4147 7461 4146 7461 4134 7461 4147 7462 4134 7462 4148 7462 4148 7463 4134 7463 4137 7463 4148 7464 4137 7464 4149 7464 4149 7465 4137 7465 4139 7465 4149 7466 4139 7466 4150 7466 4150 7467 4139 7467 4141 7467 4150 7468 4141 7468 4151 7468 4151 7469 4141 7469 4143 7469 4151 7470 4143 7470 4152 7470 4152 7471 4143 7471 4144 7471 4152 7472 4144 7472 4153 7472 4102 7473 4103 7473 4147 7473 4102 7474 4147 7474 4154 7474 4154 7475 4147 7475 4148 7475 4154 7476 4148 7476 4155 7476 4155 7477 4148 7477 4149 7477 4155 7478 4149 7478 4156 7478 4156 7479 4149 7479 4150 7479 4156 7480 4150 7480 4157 7480 4157 7481 4150 7481 4151 7481 4157 7482 4151 7482 4158 7482 4158 7483 4151 7483 4152 7483 4158 7484 4152 7484 4159 7484 4159 7485 4152 7485 4153 7485 4159 7486 4153 7486 4160 7486 4160 7487 4153 7487 4161 7487 4160 7488 4161 7488 4162 7488 4162 7489 4161 7489 4163 7489 4162 7490 4163 7490 4164 7490 4164 7491 4163 7491 4165 7491 4164 7492 4165 7492 4166 7492 4166 7493 4165 7493 4167 7493 4166 7494 4167 7494 4168 7494 4168 7495 4167 7495 4169 7495 4168 7496 4169 7496 4170 7496 4170 7497 4169 7497 4171 7497 4170 7498 4171 7498 4172 7498 4172 7499 4171 7499 4173 7499 4172 7500 4173 7500 4174 7500 4174 7501 4173 7501 4175 7501 4174 7502 4175 7502 4176 7502 4176 7503 4175 7503 4177 7503 4176 7504 4177 7504 4178 7504 4178 7505 4177 7505 4179 7505 4178 7506 4179 7506 4180 7506 4181 7507 4182 7507 4183 7507 4181 7508 4183 7508 4184 7508 4184 7509 4183 7509 3758 7509 4184 7510 3758 7510 3761 7510 4101 7511 4102 7511 4154 7511 4101 7512 4154 7512 4185 7512 4185 7513 4154 7513 4155 7513 4185 7514 4155 7514 4186 7514 4186 7515 4155 7515 4156 7515 4186 7516 4156 7516 4187 7516 4187 7517 4156 7517 4157 7517 4187 7518 4157 7518 4188 7518 4188 7519 4157 7519 4158 7519 4188 7520 4158 7520 4189 7520 4189 7521 4158 7521 4159 7521 4189 7522 4159 7522 4190 7522 4190 7523 4159 7523 4160 7523 4190 7524 4160 7524 4191 7524 4191 7525 4160 7525 4162 7525 4191 7526 4162 7526 4192 7526 4192 7527 4162 7527 4164 7527 4192 7528 4164 7528 4193 7528 4193 7529 4164 7529 4166 7529 4193 7530 4166 7530 4194 7530 4194 7531 4166 7531 4168 7531 4194 7532 4168 7532 4195 7532 4195 7533 4168 7533 4170 7533 4195 7534 4170 7534 4196 7534 4196 7535 4170 7535 4172 7535 4196 7536 4172 7536 4197 7536 4197 7537 4172 7537 4174 7537 4197 7538 4174 7538 4198 7538 4198 7539 4174 7539 4176 7539 4198 7540 4176 7540 4199 7540 4199 7541 4176 7541 4178 7541 4199 7542 4178 7542 4200 7542 4200 7543 4178 7543 4180 7543 4200 7544 4180 7544 4201 7544 4201 7545 4180 7545 4181 7545 4201 7546 4181 7546 4202 7546 4202 7547 4181 7547 4184 7547 4202 7548 4184 7548 4203 7548 4203 7549 4184 7549 3761 7549 4203 7550 3761 7550 3760 7550 4100 7551 4101 7551 4185 7551 4100 7552 4185 7552 4204 7552 4204 7553 4185 7553 4186 7553 4204 7554 4186 7554 4205 7554 4205 7555 4186 7555 4187 7555 4205 7556 4187 7556 4206 7556 4206 7557 4187 7557 4188 7557 4206 7558 4188 7558 4207 7558 4207 7559 4188 7559 4189 7559 4207 7560 4189 7560 4208 7560 4208 7561 4189 7561 4190 7561 4208 7562 4190 7562 4209 7562 4209 7563 4190 7563 4191 7563 4209 7564 4191 7564 4210 7564 4210 7565 4191 7565 4192 7565 4210 7566 4192 7566 4211 7566 4211 7567 4192 7567 4193 7567 4211 7568 4193 7568 4212 7568 4212 7569 4193 7569 4194 7569 4212 7570 4194 7570 4213 7570 4213 7571 4194 7571 4195 7571 4213 7572 4195 7572 4214 7572 4214 7573 4195 7573 4196 7573 4214 7574 4196 7574 4215 7574 4215 7575 4196 7575 4197 7575 4215 7576 4197 7576 4216 7576 4216 7577 4197 7577 4198 7577 4216 7578 4198 7578 4217 7578 4217 7579 4198 7579 4199 7579 4217 7580 4199 7580 4218 7580 4218 7581 4199 7581 4200 7581 4218 7582 4200 7582 4219 7582 4219 7583 4200 7583 4201 7583 4219 7584 4201 7584 4220 7584 4220 7585 4201 7585 4202 7585 4220 7586 4202 7586 4221 7586 4221 7587 4202 7587 4203 7587 4221 7588 4203 7588 4222 7588 4222 7589 4203 7589 3760 7589 4222 7590 3760 7590 4132 7590 4099 7591 4100 7591 4204 7591 4099 7592 4204 7592 4223 7592 4223 7593 4204 7593 4205 7593 4223 7594 4205 7594 4224 7594 4224 7595 4205 7595 4206 7595 4224 7596 4206 7596 4225 7596 4225 7597 4206 7597 4207 7597 4225 7598 4207 7598 4226 7598 4226 7599 4207 7599 4208 7599 4226 7600 4208 7600 4227 7600 4227 7601 4208 7601 4209 7601 4227 7602 4209 7602 4228 7602 4228 7603 4209 7603 4210 7603 4228 7604 4210 7604 4229 7604 4229 7605 4210 7605 4211 7605 4229 7606 4211 7606 4230 7606 4230 7607 4211 7607 4212 7607 4230 7608 4212 7608 4231 7608 4231 7609 4212 7609 4213 7609 4231 7610 4213 7610 4232 7610 4232 7611 4213 7611 4214 7611 4232 7612 4214 7612 4233 7612 4233 7613 4214 7613 4215 7613 4233 7614 4215 7614 4234 7614 4234 7615 4215 7615 4216 7615 4234 7616 4216 7616 4235 7616 4235 7617 4216 7617 4217 7617 4235 7618 4217 7618 4236 7618 4236 7619 4217 7619 4218 7619 4236 7620 4218 7620 4237 7620 4237 7621 4218 7621 4219 7621 4237 7622 4219 7622 4238 7622 4238 7623 4219 7623 4220 7623 4238 7624 4220 7624 4239 7624 4239 7625 4220 7625 4221 7625 4239 7626 4221 7626 4240 7626 4240 7627 4221 7627 4222 7627 4240 7628 4222 7628 4241 7628 4241 7629 4222 7629 4132 7629 4241 7630 4132 7630 4131 7630 4098 7631 4099 7631 4223 7631 4098 7632 4223 7632 4242 7632 4242 7633 4223 7633 4224 7633 4242 7634 4224 7634 4243 7634 4243 7635 4224 7635 4225 7635 4243 7636 4225 7636 4244 7636 4244 7637 4225 7637 4226 7637 4244 7638 4226 7638 4245 7638 4245 7639 4226 7639 4227 7639 4245 7640 4227 7640 4246 7640 4246 7641 4227 7641 4228 7641 4246 7642 4228 7642 4247 7642 4247 7643 4228 7643 4229 7643 4247 7644 4229 7644 4248 7644 4248 7645 4229 7645 4230 7645 4248 7646 4230 7646 4249 7646 4249 7647 4230 7647 4231 7647 4249 7648 4231 7648 4250 7648 4250 7649 4231 7649 4232 7649 4250 7650 4232 7650 4251 7650 4251 7651 4232 7651 4233 7651 4251 7652 4233 7652 4252 7652 4252 7653 4233 7653 4234 7653 4252 7654 4234 7654 4253 7654 4253 7655 4234 7655 4235 7655 4253 7656 4235 7656 4254 7656 4254 7657 4235 7657 4236 7657 4254 7658 4236 7658 4255 7658 4255 7659 4236 7659 4237 7659 4255 7660 4237 7660 4256 7660 4256 7661 4237 7661 4238 7661 4256 7662 4238 7662 4257 7662 4257 7663 4238 7663 4239 7663 4257 7664 4239 7664 4258 7664 4258 7665 4239 7665 4240 7665 4258 7666 4240 7666 4259 7666 4259 7667 4240 7667 4241 7667 4259 7668 4241 7668 4260 7668 4260 7669 4241 7669 4131 7669 4260 7670 4131 7670 4130 7670 4097 7671 4098 7671 4242 7671 4097 7672 4242 7672 4261 7672 4261 7673 4242 7673 4243 7673 4261 7674 4243 7674 4262 7674 4262 7675 4243 7675 4244 7675 4262 7676 4244 7676 4263 7676 4263 7677 4244 7677 4245 7677 4263 7678 4245 7678 4264 7678 4264 7679 4245 7679 4246 7679 4264 7680 4246 7680 4265 7680 4265 7681 4246 7681 4247 7681 4265 7682 4247 7682 4266 7682 4266 7683 4247 7683 4248 7683 4266 7684 4248 7684 4267 7684 4267 7685 4248 7685 4249 7685 4267 7686 4249 7686 4268 7686 4268 7687 4249 7687 4250 7687 4268 7688 4250 7688 4269 7688 4269 7689 4250 7689 4251 7689 4269 7690 4251 7690 4270 7690 4270 7691 4251 7691 4252 7691 4270 7692 4252 7692 4271 7692 4271 7693 4252 7693 4253 7693 4271 7694 4253 7694 4272 7694 4272 7695 4253 7695 4254 7695 4272 7696 4254 7696 4273 7696 4273 7697 4254 7697 4255 7697 4273 7698 4255 7698 4274 7698 4274 7699 4255 7699 4256 7699 4274 7700 4256 7700 4275 7700 4275 7701 4256 7701 4257 7701 4275 7702 4257 7702 4276 7702 4276 7703 4257 7703 4258 7703 4276 7704 4258 7704 4277 7704 4277 7705 4258 7705 4259 7705 4277 7706 4259 7706 4278 7706 4278 7707 4259 7707 4260 7707 4278 7708 4260 7708 4279 7708 4279 7709 4260 7709 4130 7709 4279 7710 4130 7710 4129 7710 4096 7711 4097 7711 4261 7711 4096 7712 4261 7712 4280 7712 4280 7713 4261 7713 4262 7713 4280 7714 4262 7714 4281 7714 4281 7715 4262 7715 4263 7715 4281 7716 4263 7716 4282 7716 4282 7717 4263 7717 4264 7717 4282 7718 4264 7718 4283 7718 4283 7719 4264 7719 4265 7719 4283 7720 4265 7720 4284 7720 4284 7721 4265 7721 4266 7721 4284 7722 4266 7722 4285 7722 4285 7723 4266 7723 4267 7723 4285 7724 4267 7724 4286 7724 4286 7725 4267 7725 4268 7725 4286 7726 4268 7726 4287 7726 4287 7727 4268 7727 4269 7727 4287 7728 4269 7728 4288 7728 4288 7729 4269 7729 4270 7729 4288 7730 4270 7730 4289 7730 4289 7731 4270 7731 4271 7731 4289 7732 4271 7732 4290 7732 4290 7733 4271 7733 4272 7733 4290 7734 4272 7734 4291 7734 4291 7735 4272 7735 4273 7735 4291 7736 4273 7736 4292 7736 4292 7737 4273 7737 4274 7737 4292 7738 4274 7738 4293 7738 4293 7739 4274 7739 4275 7739 4293 7740 4275 7740 4294 7740 4294 7741 4275 7741 4276 7741 4294 7742 4276 7742 4295 7742 4295 7743 4276 7743 4277 7743 4295 7744 4277 7744 4296 7744 4296 7745 4277 7745 4278 7745 4296 7746 4278 7746 4297 7746 4297 7747 4278 7747 4279 7747 4297 7748 4279 7748 4298 7748 4298 7749 4279 7749 4129 7749 4298 7750 4129 7750 4128 7750 4095 7751 4096 7751 4280 7751 4095 7752 4280 7752 4299 7752 4299 7753 4280 7753 4281 7753 4299 7754 4281 7754 4300 7754 4300 7755 4281 7755 4282 7755 4300 7756 4282 7756 4301 7756 4301 7757 4282 7757 4283 7757 4301 7758 4283 7758 4302 7758 4302 7759 4283 7759 4284 7759 4302 7760 4284 7760 4303 7760 4303 7761 4284 7761 4285 7761 4303 7762 4285 7762 4304 7762 4304 7763 4285 7763 4286 7763 4304 7764 4286 7764 4305 7764 4305 7765 4286 7765 4287 7765 4305 7766 4287 7766 4306 7766 4306 7767 4287 7767 4288 7767 4306 7768 4288 7768 4307 7768 4307 7769 4288 7769 4289 7769 4307 7770 4289 7770 4308 7770 4308 7771 4289 7771 4290 7771 4308 7772 4290 7772 4309 7772 4309 7773 4290 7773 4291 7773 4309 7774 4291 7774 4310 7774 4310 7775 4291 7775 4292 7775 4310 7776 4292 7776 4311 7776 4311 7777 4292 7777 4293 7777 4311 7778 4293 7778 4312 7778 4312 7779 4293 7779 4294 7779 4312 7780 4294 7780 4313 7780 4313 7781 4294 7781 4295 7781 4313 7782 4295 7782 4314 7782 4314 7783 4295 7783 4296 7783 4314 7784 4296 7784 4315 7784 4315 7785 4296 7785 4297 7785 4315 7786 4297 7786 4316 7786 4316 7787 4297 7787 4298 7787 4316 7788 4298 7788 4317 7788 4317 7789 4298 7789 4128 7789 4317 7790 4128 7790 4127 7790 4094 7791 4095 7791 4299 7791 4094 7792 4299 7792 4318 7792 4318 7793 4299 7793 4300 7793 4318 7794 4300 7794 4319 7794 4319 7795 4300 7795 4301 7795 4319 7796 4301 7796 4320 7796 4320 7797 4301 7797 4302 7797 4320 7798 4302 7798 4321 7798 4321 7799 4302 7799 4303 7799 4321 7800 4303 7800 4322 7800 4322 7801 4303 7801 4304 7801 4322 7802 4304 7802 4323 7802 4323 7803 4304 7803 4305 7803 4323 7804 4305 7804 4324 7804 4324 7805 4305 7805 4306 7805 4324 7806 4306 7806 4325 7806 4325 7807 4306 7807 4307 7807 4325 7808 4307 7808 4326 7808 4326 7809 4307 7809 4308 7809 4326 7810 4308 7810 4327 7810 4327 7811 4308 7811 4309 7811 4327 7812 4309 7812 4328 7812 4328 7813 4309 7813 4310 7813 4328 7814 4310 7814 4329 7814 4329 7815 4310 7815 4311 7815 4329 7816 4311 7816 4330 7816 4330 7817 4311 7817 4312 7817 4330 7818 4312 7818 4331 7818 4331 7819 4312 7819 4313 7819 4331 7820 4313 7820 4332 7820 4332 7821 4313 7821 4314 7821 4332 7822 4314 7822 4333 7822 4333 7823 4314 7823 4315 7823 4333 7824 4315 7824 4334 7824 4334 7825 4315 7825 4316 7825 4334 7826 4316 7826 4335 7826 4335 7827 4316 7827 4317 7827 4335 7828 4317 7828 4336 7828 4336 7829 4317 7829 4127 7829 4336 7830 4127 7830 4126 7830 4093 7831 4094 7831 4318 7831 4093 7832 4318 7832 4337 7832 4337 7833 4318 7833 4319 7833 4337 7834 4319 7834 4338 7834 4338 7835 4319 7835 4320 7835 4338 7836 4320 7836 4339 7836 4339 7837 4320 7837 4321 7837 4339 7838 4321 7838 4340 7838 4340 7839 4321 7839 4322 7839 4340 7840 4322 7840 4341 7840 4341 7841 4322 7841 4323 7841 4341 7842 4323 7842 4342 7842 4342 7843 4323 7843 4324 7843 4342 7844 4324 7844 4343 7844 4343 7845 4324 7845 4325 7845 4343 7846 4325 7846 4344 7846 4344 7847 4325 7847 4326 7847 4344 7848 4326 7848 4345 7848 4345 7849 4326 7849 4327 7849 4345 7850 4327 7850 4346 7850 4346 7851 4327 7851 4328 7851 4346 7852 4328 7852 4347 7852 4347 7853 4328 7853 4329 7853 4347 7854 4329 7854 4348 7854 4348 7855 4329 7855 4330 7855 4348 7856 4330 7856 4349 7856 4349 7857 4330 7857 4331 7857 4349 7858 4331 7858 4350 7858 4350 7859 4331 7859 4332 7859 4350 7860 4332 7860 4351 7860 4351 7861 4332 7861 4333 7861 4351 7862 4333 7862 4352 7862 4352 7863 4333 7863 4334 7863 4352 7864 4334 7864 4353 7864 4353 7865 4334 7865 4335 7865 4353 7866 4335 7866 4354 7866 4354 7867 4335 7867 4336 7867 4354 7868 4336 7868 4355 7868 4355 7869 4336 7869 4126 7869 4355 7870 4126 7870 4125 7870 4092 7871 4093 7871 4337 7871 4092 7872 4337 7872 4356 7872 4356 7873 4337 7873 4338 7873 4356 7874 4338 7874 4357 7874 4357 7875 4338 7875 4339 7875 4357 7876 4339 7876 4358 7876 4358 7877 4339 7877 4340 7877 4358 7878 4340 7878 4359 7878 4359 7879 4340 7879 4341 7879 4359 7880 4341 7880 4360 7880 4360 7881 4341 7881 4342 7881 4360 7882 4342 7882 4361 7882 4361 7883 4342 7883 4343 7883 4361 7884 4343 7884 4362 7884 4362 7885 4343 7885 4344 7885 4362 7886 4344 7886 4363 7886 4363 7887 4344 7887 4345 7887 4363 7888 4345 7888 4364 7888 4364 7889 4345 7889 4346 7889 4364 7890 4346 7890 4365 7890 4365 7891 4346 7891 4347 7891 4365 7892 4347 7892 4366 7892 4366 7893 4347 7893 4348 7893 4366 7894 4348 7894 4367 7894 4367 7895 4348 7895 4349 7895 4367 7896 4349 7896 4368 7896 4368 7897 4349 7897 4350 7897 4368 7898 4350 7898 4369 7898 4369 7899 4350 7899 4351 7899 4369 7900 4351 7900 4370 7900 4370 7901 4351 7901 4352 7901 4370 7902 4352 7902 4371 7902 4371 7903 4352 7903 4353 7903 4371 7904 4353 7904 4372 7904 4372 7905 4353 7905 4354 7905 4372 7906 4354 7906 4373 7906 4373 7907 4354 7907 4355 7907 4373 7908 4355 7908 4374 7908 4374 7909 4355 7909 4125 7909 4374 7910 4125 7910 4124 7910 3572 7911 4092 7911 4356 7911 3572 7912 4356 7912 4375 7912 4375 7913 4356 7913 4357 7913 4375 7914 4357 7914 4376 7914 4376 7915 4357 7915 4358 7915 4376 7916 4358 7916 4377 7916 4377 7917 4358 7917 4359 7917 4377 7918 4359 7918 4378 7918 4378 7919 4359 7919 4360 7919 4378 7920 4360 7920 4379 7920 4379 7921 4360 7921 4361 7921 4379 7922 4361 7922 4380 7922 4380 7923 4361 7923 4362 7923 4380 7924 4362 7924 4381 7924 4381 7925 4362 7925 4363 7925 4381 7926 4363 7926 4382 7926 4382 7927 4363 7927 4364 7927 4382 7928 4364 7928 4383 7928 4383 7929 4364 7929 4365 7929 4383 7930 4365 7930 4384 7930 4384 7931 4365 7931 4366 7931 4384 7932 4366 7932 4385 7932 4385 7933 4366 7933 4367 7933 4385 7934 4367 7934 4386 7934 4386 7935 4367 7935 4368 7935 4386 7936 4368 7936 4387 7936 4387 7937 4368 7937 4369 7937 4387 7938 4369 7938 4388 7938 4388 7939 4369 7939 4370 7939 4388 7940 4370 7940 4389 7940 4389 7941 4370 7941 4371 7941 4389 7942 4371 7942 4390 7942 4390 7943 4371 7943 4372 7943 4390 7944 4372 7944 4391 7944 4391 7945 4372 7945 4373 7945 4391 7946 4373 7946 4392 7946 4392 7947 4373 7947 4374 7947 4392 7948 4374 7948 4393 7948 4393 7949 4374 7949 4124 7949 4393 7950 4124 7950 3583 7950 4394 7951 4395 7951 4396 7951 4394 7952 4396 7952 4397 7952 4397 7953 4396 7953 4398 7953 4397 7954 4398 7954 4399 7954 4123 7955 4400 7955 4401 7955 4400 7956 4402 7956 4401 7956 4401 7957 4402 7957 4403 7957 4402 7958 4404 7958 4403 7958 4403 7959 4404 7959 4405 7959 4403 7960 4405 7960 4406 7960 4406 7961 4405 7961 4394 7961 4406 7962 4394 7962 4407 7962 4407 7963 4394 7963 4397 7963 4407 7964 4397 7964 4408 7964 4408 7965 4397 7965 4399 7965 4408 7966 4399 7966 4409 7966 4409 7967 4399 7967 4410 7967 4409 7968 4410 7968 4411 7968 4411 7969 4410 7969 4412 7969 4411 7970 4412 7970 4413 7970 4413 7971 4412 7971 4414 7971 4413 7972 4414 7972 4415 7972 4415 7973 4414 7973 4416 7973 4415 7974 4416 7974 4417 7974 4417 7975 4416 7975 4418 7975 4416 7976 4419 7976 4418 7976 4418 7977 4419 7977 4420 7977 4419 7978 4421 7978 4420 7978 4420 7979 4421 7979 4422 7979 4421 7980 4423 7980 4422 7980 4422 7981 4423 7981 4424 7981 4422 7982 4424 7982 4425 7982 4425 7983 4424 7983 4426 7983 4425 7984 4426 7984 4427 7984 4427 7985 4426 7985 4428 7985 4427 7986 4428 7986 4429 7986 4429 7987 4428 7987 4430 7987 4429 7988 4430 7988 4431 7988 4122 7989 4123 7989 4401 7989 4122 7990 4401 7990 4432 7990 4433 7991 4403 7991 4406 7991 4433 7992 4406 7992 4434 7992 4434 7993 4406 7993 4407 7993 4434 7994 4407 7994 4435 7994 4435 7995 4407 7995 4408 7995 4435 7996 4408 7996 4436 7996 4436 7997 4408 7997 4409 7997 4436 7998 4409 7998 4437 7998 4437 7999 4409 7999 4411 7999 4437 8000 4411 8000 4438 8000 4438 8001 4411 8001 4413 8001 4438 8002 4413 8002 4439 8002 4439 8003 4413 8003 4415 8003 4439 8004 4415 8004 4440 8004 4440 8005 4415 8005 4417 8005 4440 8006 4417 8006 4441 8006 4441 8007 4417 8007 4418 8007 4441 8008 4418 8008 4442 8008 4442 8009 4418 8009 4420 8009 4442 8010 4420 8010 4443 8010 4443 8011 4420 8011 4444 8011 4420 8012 4422 8012 4444 8012 4444 8013 4422 8013 4425 8013 4444 8014 4425 8014 4445 8014 4445 8015 4425 8015 4427 8015 4445 8016 4427 8016 4446 8016 4446 8017 4427 8017 4429 8017 4446 8018 4429 8018 4447 8018 4447 8019 4429 8019 4431 8019 4447 8020 4431 8020 4448 8020 4448 8021 4431 8021 4449 8021 4448 8022 4449 8022 4450 8022 4450 8023 4449 8023 4451 8023 4450 8024 4451 8024 4452 8024 4452 8025 4451 8025 4114 8025 4452 8026 4114 8026 4112 8026 4121 8027 4122 8027 4432 8027 4121 8028 4432 8028 4453 8028 4453 8029 4432 8029 4433 8029 4453 8030 4433 8030 4454 8030 4454 8031 4433 8031 4434 8031 4454 8032 4434 8032 4455 8032 4455 8033 4434 8033 4435 8033 4455 8034 4435 8034 4456 8034 4456 8035 4435 8035 4436 8035 4456 8036 4436 8036 4457 8036 4457 8037 4436 8037 4437 8037 4457 8038 4437 8038 4458 8038 4458 8039 4437 8039 4438 8039 4458 8040 4438 8040 4459 8040 4459 8041 4438 8041 4439 8041 4459 8042 4439 8042 4460 8042 4460 8043 4439 8043 4440 8043 4460 8044 4440 8044 4461 8044 4461 8045 4440 8045 4441 8045 4461 8046 4441 8046 4462 8046 4462 8047 4441 8047 4442 8047 4462 8048 4442 8048 4463 8048 4463 8049 4442 8049 4443 8049 4463 8050 4443 8050 4464 8050 4464 8051 4443 8051 4444 8051 4464 8052 4444 8052 4465 8052 4465 8053 4444 8053 4445 8053 4465 8054 4445 8054 4466 8054 4467 8055 4446 8055 4447 8055 4467 8056 4447 8056 4468 8056 4468 8057 4447 8057 4448 8057 4468 8058 4448 8058 4469 8058 4469 8059 4448 8059 4450 8059 4469 8060 4450 8060 4470 8060 4470 8061 4450 8061 4452 8061 4470 8062 4452 8062 4471 8062 4471 8063 4452 8063 4112 8063 4471 8064 4112 8064 4110 8064 4120 8065 4121 8065 4453 8065 4120 8066 4453 8066 4472 8066 4472 8067 4453 8067 4454 8067 4472 8068 4454 8068 4473 8068 4473 8069 4454 8069 4455 8069 4473 8070 4455 8070 4474 8070 4474 8071 4455 8071 4456 8071 4474 8072 4456 8072 4475 8072 4475 8073 4456 8073 4457 8073 4475 8074 4457 8074 4476 8074 4476 8075 4457 8075 4458 8075 4476 8076 4458 8076 4477 8076 4477 8077 4458 8077 4459 8077 4477 8078 4459 8078 4478 8078 4478 8079 4459 8079 4460 8079 4478 8080 4460 8080 4479 8080 4479 8081 4460 8081 4461 8081 4479 8082 4461 8082 4480 8082 4480 8083 4461 8083 4462 8083 4480 8084 4462 8084 4481 8084 4481 8085 4462 8085 4463 8085 4481 8086 4463 8086 4482 8086 4482 8087 4463 8087 4464 8087 4482 8088 4464 8088 4483 8088 4484 8089 4465 8089 4466 8089 4484 8090 4466 8090 4485 8090 4486 8091 4467 8091 4468 8091 4486 8092 4468 8092 4487 8092 4487 8093 4468 8093 4469 8093 4487 8094 4469 8094 4488 8094 4488 8095 4469 8095 4470 8095 4488 8096 4470 8096 4489 8096 4489 8097 4470 8097 4471 8097 4489 8098 4471 8098 4490 8098 4490 8099 4471 8099 4110 8099 4490 8100 4110 8100 4109 8100 4119 8101 4120 8101 4472 8101 4119 8102 4472 8102 4491 8102 4491 8103 4472 8103 4473 8103 4491 8104 4473 8104 4492 8104 4492 8105 4473 8105 4474 8105 4492 8106 4474 8106 4493 8106 4493 8107 4474 8107 4475 8107 4493 8108 4475 8108 4494 8108 4494 8109 4475 8109 4476 8109 4494 8110 4476 8110 4495 8110 4495 8111 4476 8111 4477 8111 4495 8112 4477 8112 4496 8112 4496 8113 4477 8113 4478 8113 4496 8114 4478 8114 4497 8114 4497 8115 4478 8115 4479 8115 4497 8116 4479 8116 4498 8116 4498 8117 4479 8117 4480 8117 4498 8118 4480 8118 4499 8118 4499 8119 4480 8119 4481 8119 4499 8120 4481 8120 4500 8120 4500 8121 4481 8121 4482 8121 4500 8122 4482 8122 4501 8122 4501 8123 4482 8123 4483 8123 4501 8124 4483 8124 4502 8124 4502 8125 4483 8125 4484 8125 4502 8126 4484 8126 4503 8126 4503 8127 4484 8127 4485 8127 4503 8128 4485 8128 4504 8128 4504 8129 4485 8129 4486 8129 4504 8130 4486 8130 4505 8130 4505 8131 4486 8131 4487 8131 4505 8132 4487 8132 4506 8132 4506 8133 4487 8133 4488 8133 4506 8134 4488 8134 4507 8134 4507 8135 4488 8135 4489 8135 4507 8136 4489 8136 4508 8136 4508 8137 4489 8137 4490 8137 4508 8138 4490 8138 4509 8138 4509 8139 4490 8139 4109 8139 4509 8140 4109 8140 4108 8140 4118 8141 4119 8141 4491 8141 4118 8142 4491 8142 4510 8142 4510 8143 4491 8143 4492 8143 4510 8144 4492 8144 4511 8144 4511 8145 4492 8145 4493 8145 4511 8146 4493 8146 4512 8146 4512 8147 4493 8147 4494 8147 4512 8148 4494 8148 4513 8148 4513 8149 4494 8149 4495 8149 4513 8150 4495 8150 4514 8150 4514 8151 4495 8151 4496 8151 4514 8152 4496 8152 4515 8152 4515 8153 4496 8153 4497 8153 4515 8154 4497 8154 4516 8154 4516 8155 4497 8155 4498 8155 4516 8156 4498 8156 4517 8156 4517 8157 4498 8157 4499 8157 4517 8158 4499 8158 4518 8158 4518 8159 4499 8159 4500 8159 4518 8160 4500 8160 4519 8160 4519 8161 4500 8161 4501 8161 4519 8162 4501 8162 4520 8162 4520 8163 4501 8163 4502 8163 4520 8164 4502 8164 4521 8164 4521 8165 4502 8165 4503 8165 4521 8166 4503 8166 4522 8166 4522 8167 4503 8167 4504 8167 4522 8168 4504 8168 4523 8168 4523 8169 4504 8169 4505 8169 4523 8170 4505 8170 4524 8170 4524 8171 4505 8171 4506 8171 4524 8172 4506 8172 4525 8172 4525 8173 4506 8173 4507 8173 4525 8174 4507 8174 4526 8174 4526 8175 4507 8175 4508 8175 4526 8176 4508 8176 4527 8176 4527 8177 4508 8177 4509 8177 4527 8178 4509 8178 4528 8178 4528 8179 4509 8179 4108 8179 4528 8180 4108 8180 4107 8180 4117 8181 4118 8181 4510 8181 4117 8182 4510 8182 4529 8182 4529 8183 4510 8183 4511 8183 4529 8184 4511 8184 4530 8184 4530 8185 4511 8185 4512 8185 4530 8186 4512 8186 4531 8186 4531 8187 4512 8187 4513 8187 4531 8188 4513 8188 4532 8188 4532 8189 4513 8189 4514 8189 4532 8190 4514 8190 4533 8190 4533 8191 4514 8191 4515 8191 4533 8192 4515 8192 4534 8192 4534 8193 4515 8193 4516 8193 4534 8194 4516 8194 4535 8194 4535 8195 4516 8195 4517 8195 4535 8196 4517 8196 4536 8196 4536 8197 4517 8197 4518 8197 4536 8198 4518 8198 4537 8198 4537 8199 4518 8199 4519 8199 4537 8200 4519 8200 4538 8200 4538 8201 4519 8201 4520 8201 4538 8202 4520 8202 4539 8202 4539 8203 4520 8203 4521 8203 4539 8204 4521 8204 4540 8204 4540 8205 4521 8205 4522 8205 4540 8206 4522 8206 4541 8206 4541 8207 4522 8207 4523 8207 4541 8208 4523 8208 4542 8208 4542 8209 4523 8209 4524 8209 4542 8210 4524 8210 4543 8210 4543 8211 4524 8211 4525 8211 4543 8212 4525 8212 4544 8212 4544 8213 4525 8213 4526 8213 4544 8214 4526 8214 4545 8214 4545 8215 4526 8215 4527 8215 4545 8216 4527 8216 4546 8216 4546 8217 4527 8217 4528 8217 4546 8218 4528 8218 4547 8218 4547 8219 4528 8219 4107 8219 4547 8220 4107 8220 4106 8220 4116 8221 4117 8221 4529 8221 4116 8222 4529 8222 4548 8222 4548 8223 4529 8223 4530 8223 4548 8224 4530 8224 4549 8224 4549 8225 4530 8225 4531 8225 4549 8226 4531 8226 4550 8226 4550 8227 4531 8227 4532 8227 4550 8228 4532 8228 4551 8228 4551 8229 4532 8229 4533 8229 4551 8230 4533 8230 4552 8230 4552 8231 4533 8231 4534 8231 4552 8232 4534 8232 4553 8232 4553 8233 4534 8233 4535 8233 4553 8234 4535 8234 4554 8234 4554 8235 4535 8235 4536 8235 4554 8236 4536 8236 4555 8236 4555 8237 4536 8237 4537 8237 4555 8238 4537 8238 4556 8238 4556 8239 4537 8239 4538 8239 4556 8240 4538 8240 4557 8240 4557 8241 4538 8241 4539 8241 4557 8242 4539 8242 4558 8242 4558 8243 4539 8243 4540 8243 4558 8244 4540 8244 4559 8244 4559 8245 4540 8245 4541 8245 4559 8246 4541 8246 4560 8246 4560 8247 4541 8247 4542 8247 4560 8248 4542 8248 4561 8248 4561 8249 4542 8249 4543 8249 4561 8250 4543 8250 4562 8250 4562 8251 4543 8251 4544 8251 4562 8252 4544 8252 4563 8252 4563 8253 4544 8253 4545 8253 4563 8254 4545 8254 4564 8254 4564 8255 4545 8255 4546 8255 4564 8256 4546 8256 4565 8256 4565 8257 4546 8257 4547 8257 4565 8258 4547 8258 4566 8258 4566 8259 4547 8259 4106 8259 4566 8260 4106 8260 4105 8260 3580 8261 4116 8261 4548 8261 3580 8262 4548 8262 4567 8262 4567 8263 4548 8263 4549 8263 4567 8264 4549 8264 4568 8264 4568 8265 4549 8265 4550 8265 4568 8266 4550 8266 4569 8266 4569 8267 4550 8267 4551 8267 4569 8268 4551 8268 4570 8268 4570 8269 4551 8269 4552 8269 4570 8270 4552 8270 4571 8270 4571 8271 4552 8271 4553 8271 4571 8272 4553 8272 4572 8272 4572 8273 4553 8273 4554 8273 4572 8274 4554 8274 4573 8274 4573 8275 4554 8275 4555 8275 4573 8276 4555 8276 4574 8276 4574 8277 4555 8277 4556 8277 4574 8278 4556 8278 4575 8278 4575 8279 4556 8279 4557 8279 4575 8280 4557 8280 4576 8280 4576 8281 4557 8281 4558 8281 4576 8282 4558 8282 4577 8282 4577 8283 4558 8283 4559 8283 4577 8284 4559 8284 4578 8284 4578 8285 4559 8285 4560 8285 4578 8286 4560 8286 4579 8286 4579 8287 4560 8287 4561 8287 4579 8288 4561 8288 4580 8288 4580 8289 4561 8289 4562 8289 4580 8290 4562 8290 4581 8290 4581 8291 4562 8291 4563 8291 4581 8292 4563 8292 4582 8292 4582 8293 4563 8293 4564 8293 4582 8294 4564 8294 4583 8294 4583 8295 4564 8295 4565 8295 4583 8296 4565 8296 4584 8296 4584 8297 4565 8297 4566 8297 4584 8298 4566 8298 4585 8298 4585 8299 4566 8299 4105 8299 4585 8300 4105 8300 3587 8300 3614 8301 3582 8301 4586 8301 3614 8302 4586 8302 4587 8302 4587 8303 4586 8303 4588 8303 4587 8304 4588 8304 4589 8304 4589 8305 4588 8305 4590 8305 4589 8306 4590 8306 4591 8306 4591 8307 4590 8307 4592 8307 4591 8308 4592 8308 4593 8308 4593 8309 4592 8309 4594 8309 4593 8310 4594 8310 4595 8310 4595 8311 4594 8311 4596 8311 4595 8312 4596 8312 4597 8312 4597 8313 4596 8313 4598 8313 4597 8314 4598 8314 4599 8314 4599 8315 4598 8315 4600 8315 4599 8316 4600 8316 4601 8316 4601 8317 4600 8317 4602 8317 4601 8318 4602 8318 4603 8318 4603 8319 4602 8319 4604 8319 4603 8320 4604 8320 4605 8320 4605 8321 4604 8321 4606 8321 4605 8322 4606 8322 4607 8322 4607 8323 4606 8323 4608 8323 4607 8324 4608 8324 4609 8324 4609 8325 4608 8325 4610 8325 4609 8326 4610 8326 4611 8326 4611 8327 4610 8327 4612 8327 4611 8328 4612 8328 4613 8328 4613 8329 4612 8329 4614 8329 4613 8330 4614 8330 4615 8330 4615 8331 4614 8331 4616 8331 4615 8332 4616 8332 4617 8332 4617 8333 4616 8333 4618 8333 4617 8334 4618 8334 4619 8334 4619 8335 4618 8335 4620 8335 4619 8336 4620 8336 4621 8336 4621 8337 4620 8337 4622 8337 4621 8338 4622 8338 4623 8338 4623 8339 4622 8339 3575 8339 4623 8340 3575 8340 3653 8340 4624 8341 3614 8341 4587 8341 4624 8342 4587 8342 4625 8342 4625 8343 4587 8343 4589 8343 4625 8344 4589 8344 4626 8344 4626 8345 4589 8345 4591 8345 4626 8346 4591 8346 4627 8346 4627 8347 4591 8347 4593 8347 4627 8348 4593 8348 4628 8348 4628 8349 4593 8349 4595 8349 4628 8350 4595 8350 4629 8350 4629 8351 4595 8351 4597 8351 4629 8352 4597 8352 4630 8352 4630 8353 4597 8353 4599 8353 4630 8354 4599 8354 4631 8354 4631 8355 4599 8355 4601 8355 4631 8356 4601 8356 4632 8356 4632 8357 4601 8357 4603 8357 4632 8358 4603 8358 4633 8358 4633 8359 4603 8359 4605 8359 4633 8360 4605 8360 4634 8360 4634 8361 4605 8361 4607 8361 4634 8362 4607 8362 4635 8362 4635 8363 4607 8363 4609 8363 4635 8364 4609 8364 4636 8364 4636 8365 4609 8365 4611 8365 4636 8366 4611 8366 4637 8366 4637 8367 4611 8367 4613 8367 4637 8368 4613 8368 4638 8368 4638 8369 4613 8369 4615 8369 4638 8370 4615 8370 4639 8370 4639 8371 4615 8371 4617 8371 4639 8372 4617 8372 4640 8372 4640 8373 4617 8373 4619 8373 4640 8374 4619 8374 4641 8374 4641 8375 4619 8375 4621 8375 4641 8376 4621 8376 4642 8376 4642 8377 4621 8377 4623 8377 4642 8378 4623 8378 4643 8378 4643 8379 4623 8379 3653 8379 4643 8380 3653 8380 3651 8380 4644 8381 4624 8381 4625 8381 4644 8382 4625 8382 4645 8382 4645 8383 4625 8383 4626 8383 4645 8384 4626 8384 4646 8384 4646 8385 4626 8385 4627 8385 4646 8386 4627 8386 4647 8386 4647 8387 4627 8387 4628 8387 4647 8388 4628 8388 4648 8388 4648 8389 4628 8389 4629 8389 4648 8390 4629 8390 4649 8390 4649 8391 4629 8391 4630 8391 4649 8392 4630 8392 4650 8392 4650 8393 4630 8393 4631 8393 4650 8394 4631 8394 4651 8394 4651 8395 4631 8395 4632 8395 4651 8396 4632 8396 4652 8396 4652 8397 4632 8397 4633 8397 4652 8398 4633 8398 4653 8398 4653 8399 4633 8399 4634 8399 4653 8400 4634 8400 4654 8400 4654 8401 4634 8401 4635 8401 4654 8402 4635 8402 4655 8402 4655 8403 4635 8403 4636 8403 4655 8404 4636 8404 4656 8404 4656 8405 4636 8405 4637 8405 4656 8406 4637 8406 4657 8406 4657 8407 4637 8407 4638 8407 4657 8408 4638 8408 4658 8408 4658 8409 4638 8409 4639 8409 4658 8410 4639 8410 4659 8410 4659 8411 4639 8411 4640 8411 4659 8412 4640 8412 4660 8412 4660 8413 4640 8413 4641 8413 4660 8414 4641 8414 4661 8414 4661 8415 4641 8415 4642 8415 4661 8416 4642 8416 4662 8416 4662 8417 4642 8417 4643 8417 4662 8418 4643 8418 4663 8418 4663 8419 4643 8419 3651 8419 4663 8420 3651 8420 3649 8420 4664 8421 4644 8421 4645 8421 4664 8422 4645 8422 4665 8422 4665 8423 4645 8423 4646 8423 4665 8424 4646 8424 4666 8424 4666 8425 4646 8425 4647 8425 4666 8426 4647 8426 4667 8426 4667 8427 4647 8427 4648 8427 4667 8428 4648 8428 4668 8428 4668 8429 4648 8429 4649 8429 4668 8430 4649 8430 4669 8430 4669 8431 4649 8431 4650 8431 4669 8432 4650 8432 4670 8432 4670 8433 4650 8433 4651 8433 4670 8434 4651 8434 4671 8434 4671 8435 4651 8435 4652 8435 4671 8436 4652 8436 4672 8436 4672 8437 4652 8437 4653 8437 4672 8438 4653 8438 4673 8438 4673 8439 4653 8439 4654 8439 4673 8440 4654 8440 4674 8440 4674 8441 4654 8441 4655 8441 4674 8442 4655 8442 4675 8442 4675 8443 4655 8443 4656 8443 4675 8444 4656 8444 4676 8444 4676 8445 4656 8445 4657 8445 4676 8446 4657 8446 4677 8446 4677 8447 4657 8447 4658 8447 4677 8448 4658 8448 4678 8448 4678 8449 4658 8449 4659 8449 4678 8450 4659 8450 4679 8450 4679 8451 4659 8451 4660 8451 4679 8452 4660 8452 4680 8452 4680 8453 4660 8453 4661 8453 4680 8454 4661 8454 4681 8454 4681 8455 4661 8455 4662 8455 4681 8456 4662 8456 4682 8456 4682 8457 4662 8457 4663 8457 4682 8458 4663 8458 4683 8458 4683 8459 4663 8459 3649 8459 4683 8460 3649 8460 3647 8460 3611 8461 4664 8461 4665 8461 3611 8462 4665 8462 4684 8462 4684 8463 4665 8463 4666 8463 4684 8464 4666 8464 4685 8464 4685 8465 4666 8465 4667 8465 4685 8466 4667 8466 4686 8466 4686 8467 4667 8467 4668 8467 4686 8468 4668 8468 4687 8468 4687 8469 4668 8469 4669 8469 4687 8470 4669 8470 4688 8470 4688 8471 4669 8471 4670 8471 4688 8472 4670 8472 4689 8472 4689 8473 4670 8473 4671 8473 4689 8474 4671 8474 4690 8474 4690 8475 4671 8475 4672 8475 4690 8476 4672 8476 4691 8476 4691 8477 4672 8477 4673 8477 4691 8478 4673 8478 4692 8478 4692 8479 4673 8479 4674 8479 4692 8480 4674 8480 4693 8480 4693 8481 4674 8481 4675 8481 4693 8482 4675 8482 4694 8482 4694 8483 4675 8483 4676 8483 4694 8484 4676 8484 4695 8484 4695 8485 4676 8485 4677 8485 4695 8486 4677 8486 4696 8486 4696 8487 4677 8487 4678 8487 4696 8488 4678 8488 4697 8488 4697 8489 4678 8489 4679 8489 4697 8490 4679 8490 4698 8490 4698 8491 4679 8491 4680 8491 4698 8492 4680 8492 4699 8492 4699 8493 4680 8493 4681 8493 4699 8494 4681 8494 4700 8494 4700 8495 4681 8495 4682 8495 4700 8496 4682 8496 4701 8496 4701 8497 4682 8497 4683 8497 4701 8498 4683 8498 4702 8498 4702 8499 4683 8499 3647 8499 4702 8500 3647 8500 3645 8500 3612 8501 3611 8501 4684 8501 3612 8502 4684 8502 4703 8502 4703 8503 4684 8503 4685 8503 4703 8504 4685 8504 4704 8504 4704 8505 4685 8505 4686 8505 4704 8506 4686 8506 4705 8506 4705 8507 4686 8507 4687 8507 4705 8508 4687 8508 4706 8508 4706 8509 4687 8509 4688 8509 4706 8510 4688 8510 4707 8510 4707 8511 4688 8511 4689 8511 4707 8512 4689 8512 4708 8512 4708 8513 4689 8513 4690 8513 4708 8514 4690 8514 4709 8514 4709 8515 4690 8515 4691 8515 4709 8516 4691 8516 4710 8516 4710 8517 4691 8517 4692 8517 4710 8518 4692 8518 4711 8518 4711 8519 4692 8519 4693 8519 4711 8520 4693 8520 4712 8520 4712 8521 4693 8521 4694 8521 4712 8522 4694 8522 4713 8522 4713 8523 4694 8523 4695 8523 4713 8524 4695 8524 4714 8524 4714 8525 4695 8525 4696 8525 4714 8526 4696 8526 4715 8526 4715 8527 4696 8527 4697 8527 4715 8528 4697 8528 4716 8528 4716 8529 4697 8529 4698 8529 4716 8530 4698 8530 4717 8530 4717 8531 4698 8531 4699 8531 4717 8532 4699 8532 4718 8532 4718 8533 4699 8533 4700 8533 4718 8534 4700 8534 4719 8534 4719 8535 4700 8535 4701 8535 4719 8536 4701 8536 4720 8536 4720 8537 4701 8537 4702 8537 4720 8538 4702 8538 4721 8538 4721 8539 4702 8539 3645 8539 4721 8540 3645 8540 3642 8540 4722 8541 3612 8541 4703 8541 4722 8542 4703 8542 4723 8542 4723 8543 4703 8543 4704 8543 4723 8544 4704 8544 4724 8544 4724 8545 4704 8545 4705 8545 4724 8546 4705 8546 4725 8546 4725 8547 4705 8547 4706 8547 4725 8548 4706 8548 4726 8548 4726 8549 4706 8549 4707 8549 4726 8550 4707 8550 4727 8550 4727 8551 4707 8551 4708 8551 4727 8552 4708 8552 4728 8552 4728 8553 4708 8553 4709 8553 4728 8554 4709 8554 4729 8554 4729 8555 4709 8555 4710 8555 4729 8556 4710 8556 4730 8556 4730 8557 4710 8557 4711 8557 4730 8558 4711 8558 4731 8558 4731 8559 4711 8559 4712 8559 4731 8560 4712 8560 4732 8560 4732 8561 4712 8561 4713 8561 4732 8562 4713 8562 4733 8562 4733 8563 4713 8563 4714 8563 4733 8564 4714 8564 4734 8564 4734 8565 4714 8565 4715 8565 4734 8566 4715 8566 4735 8566 4735 8567 4715 8567 4716 8567 4735 8568 4716 8568 4736 8568 4736 8569 4716 8569 4717 8569 4736 8570 4717 8570 4737 8570 4737 8571 4717 8571 4718 8571 4737 8572 4718 8572 4738 8572 4738 8573 4718 8573 4719 8573 4738 8574 4719 8574 4739 8574 4739 8575 4719 8575 4720 8575 4739 8576 4720 8576 4740 8576 4740 8577 4720 8577 4721 8577 4740 8578 4721 8578 4741 8578 4741 8579 4721 8579 3642 8579 4741 8580 3642 8580 3641 8580 4742 8581 4743 8581 4744 8581 4742 8582 4744 8582 4745 8582 4745 8583 4744 8583 4746 8583 4745 8584 4746 8584 4747 8584 4747 8585 4746 8585 4748 8585 4747 8586 4748 8586 4749 8586 4749 8587 4748 8587 4750 8587 4749 8588 4750 8588 4751 8588 4751 8589 4750 8589 4752 8589 4751 8590 4752 8590 4753 8590 4753 8591 4752 8591 4754 8591 4753 8592 4754 8592 4755 8592 4755 8593 4754 8593 4756 8593 4755 8594 4756 8594 4757 8594 4757 8595 4756 8595 4758 8595 4757 8596 4758 8596 4759 8596 4759 8597 4758 8597 4760 8597 4759 8598 4760 8598 4761 8598 4761 8599 4760 8599 4762 8599 4761 8600 4762 8600 4763 8600 4763 8601 4762 8601 4764 8601 4763 8602 4764 8602 4765 8602 4765 8603 4764 8603 4766 8603 4765 8604 4766 8604 4767 8604 4767 8605 4766 8605 4768 8605 4767 8606 4768 8606 4769 8606 4769 8607 4768 8607 4770 8607 4769 8608 4770 8608 4771 8608 4771 8609 4770 8609 4772 8609 4771 8610 4772 8610 4773 8610 4773 8611 4772 8611 4774 8611 4773 8612 4774 8612 4775 8612 4775 8613 4774 8613 4776 8613 4775 8614 4776 8614 4777 8614 4777 8615 4776 8615 3639 8615 4777 8616 3639 8616 3637 8616 4778 8617 4761 8617 4763 8617 4778 8618 4763 8618 4779 8618 4779 8619 4763 8619 4765 8619 4779 8620 4765 8620 4780 8620 4780 8621 4765 8621 4767 8621 4780 8622 4767 8622 4781 8622 4781 8623 4767 8623 4769 8623 4781 8624 4769 8624 4782 8624 4782 8625 4769 8625 4771 8625 4782 8626 4771 8626 4783 8626 4783 8627 4771 8627 4773 8627 4783 8628 4773 8628 4784 8628 4784 8629 4773 8629 4775 8629 4784 8630 4775 8630 4785 8630 4785 8631 4775 8631 4777 8631 4785 8632 4777 8632 4786 8632 4786 8633 4777 8633 3637 8633 4786 8634 3637 8634 3634 8634 4787 8635 4779 8635 4780 8635 4787 8636 4780 8636 4788 8636 4788 8637 4780 8637 4781 8637 4788 8638 4781 8638 4789 8638 4789 8639 4781 8639 4782 8639 4789 8640 4782 8640 4790 8640 4790 8641 4782 8641 4783 8641 4790 8642 4783 8642 4791 8642 4791 8643 4783 8643 4784 8643 4791 8644 4784 8644 4792 8644 4792 8645 4784 8645 4785 8645 4792 8646 4785 8646 4793 8646 4793 8647 4785 8647 4786 8647 4793 8648 4786 8648 4794 8648 4794 8649 4786 8649 3634 8649 4794 8650 3634 8650 3633 8650 3608 8651 3607 8651 4795 8651 3608 8652 4795 8652 4796 8652 4796 8653 4795 8653 4797 8653 4796 8654 4797 8654 4798 8654 4798 8655 4797 8655 4799 8655 4798 8656 4799 8656 4800 8656 4800 8657 4799 8657 4801 8657 4800 8658 4801 8658 4802 8658 4802 8659 4801 8659 4803 8659 4802 8660 4803 8660 4804 8660 4804 8661 4803 8661 4805 8661 4804 8662 4805 8662 4806 8662 4806 8663 4805 8663 4807 8663 4806 8664 4807 8664 4808 8664 4808 8665 4807 8665 4809 8665 4808 8666 4809 8666 4810 8666 4810 8667 4809 8667 4811 8667 4810 8668 4811 8668 4812 8668 4812 8669 4811 8669 4813 8669 4812 8670 4813 8670 4814 8670 4814 8671 4813 8671 4815 8671 4814 8672 4815 8672 4816 8672 4816 8673 4815 8673 4817 8673 4816 8674 4817 8674 4818 8674 3602 8675 3604 8675 4819 8675 3602 8676 4819 8676 4820 8676 4820 8677 4819 8677 4821 8677 4820 8678 4821 8678 4822 8678 4822 8679 4821 8679 4823 8679 4822 8680 4823 8680 4824 8680 4824 8681 4823 8681 4825 8681 4824 8682 4825 8682 4826 8682 4826 8683 4825 8683 4827 8683 4826 8684 4827 8684 4828 8684 4828 8685 4827 8685 4829 8685 4828 8686 4829 8686 4830 8686 4830 8687 4829 8687 4831 8687 4830 8688 4831 8688 4832 8688 4832 8689 4831 8689 4833 8689 4832 8690 4833 8690 4834 8690 4834 8691 4833 8691 4835 8691 4834 8692 4835 8692 4836 8692 4836 8693 4835 8693 4837 8693 4836 8694 4837 8694 4838 8694 4838 8695 4837 8695 4839 8695 4838 8696 4839 8696 4840 8696 4840 8697 4839 8697 4841 8697 4840 8698 4841 8698 4842 8698 4842 8699 4841 8699 4843 8699 4842 8700 4843 8700 4844 8700 4844 8701 4843 8701 4845 8701 4844 8702 4845 8702 4846 8702 4846 8703 4845 8703 4847 8703 4846 8704 4847 8704 4848 8704 4848 8705 4847 8705 4849 8705 4848 8706 4849 8706 4850 8706 4850 8707 4849 8707 4851 8707 4850 8708 4851 8708 4852 8708 4852 8709 4851 8709 4853 8709 4852 8710 4853 8710 4854 8710 4854 8711 4853 8711 4855 8711 4854 8712 4855 8712 4856 8712 4856 8713 4855 8713 3631 8713 4856 8714 3631 8714 3629 8714 3600 8715 3602 8715 4820 8715 3600 8716 4820 8716 4857 8716 4857 8717 4820 8717 4822 8717 4857 8718 4822 8718 4858 8718 4858 8719 4822 8719 4824 8719 4858 8720 4824 8720 4859 8720 4859 8721 4824 8721 4826 8721 4859 8722 4826 8722 4860 8722 4860 8723 4826 8723 4828 8723 4860 8724 4828 8724 4861 8724 4861 8725 4828 8725 4830 8725 4861 8726 4830 8726 4862 8726 4862 8727 4830 8727 4832 8727 4862 8728 4832 8728 4863 8728 4863 8729 4832 8729 4834 8729 4863 8730 4834 8730 4864 8730 4864 8731 4834 8731 4836 8731 4864 8732 4836 8732 4865 8732 4865 8733 4836 8733 4838 8733 4865 8734 4838 8734 4866 8734 4866 8735 4838 8735 4840 8735 4866 8736 4840 8736 4867 8736 4867 8737 4840 8737 4842 8737 4867 8738 4842 8738 4868 8738 4868 8739 4842 8739 4844 8739 4868 8740 4844 8740 4869 8740 4869 8741 4844 8741 4846 8741 4869 8742 4846 8742 4870 8742 4870 8743 4846 8743 4848 8743 4870 8744 4848 8744 4871 8744 4871 8745 4848 8745 4850 8745 4871 8746 4850 8746 4872 8746 4872 8747 4850 8747 4852 8747 4872 8748 4852 8748 4873 8748 4873 8749 4852 8749 4854 8749 4873 8750 4854 8750 4874 8750 4874 8751 4854 8751 4856 8751 4874 8752 4856 8752 4875 8752 4875 8753 4856 8753 3629 8753 4875 8754 3629 8754 3627 8754 3598 8755 3600 8755 4857 8755 3598 8756 4857 8756 4876 8756 4876 8757 4857 8757 4858 8757 4876 8758 4858 8758 4877 8758 4877 8759 4858 8759 4859 8759 4877 8760 4859 8760 4878 8760 4878 8761 4859 8761 4860 8761 4878 8762 4860 8762 4879 8762 4879 8763 4860 8763 4861 8763 4879 8764 4861 8764 4880 8764 4880 8765 4861 8765 4862 8765 4880 8766 4862 8766 4881 8766 4881 8767 4862 8767 4863 8767 4881 8768 4863 8768 4882 8768 4882 8769 4863 8769 4864 8769 4882 8770 4864 8770 4883 8770 4883 8771 4864 8771 4865 8771 4883 8772 4865 8772 4884 8772 4884 8773 4865 8773 4866 8773 4884 8774 4866 8774 4885 8774 4885 8775 4866 8775 4867 8775 4885 8776 4867 8776 4886 8776 4886 8777 4867 8777 4868 8777 4886 8778 4868 8778 4887 8778 4887 8779 4868 8779 4869 8779 4887 8780 4869 8780 4888 8780 4888 8781 4869 8781 4870 8781 4888 8782 4870 8782 4889 8782 4889 8783 4870 8783 4871 8783 4889 8784 4871 8784 4890 8784 4890 8785 4871 8785 4872 8785 4890 8786 4872 8786 4891 8786 4891 8787 4872 8787 4873 8787 4891 8788 4873 8788 4892 8788 4892 8789 4873 8789 4874 8789 4892 8790 4874 8790 4893 8790 4893 8791 4874 8791 4875 8791 4893 8792 4875 8792 4894 8792 4894 8793 4875 8793 3627 8793 4894 8794 3627 8794 3625 8794 3595 8795 3598 8795 4876 8795 3595 8796 4876 8796 4895 8796 4895 8797 4876 8797 4877 8797 4895 8798 4877 8798 4896 8798 4896 8799 4877 8799 4878 8799 4896 8800 4878 8800 4897 8800 4897 8801 4878 8801 4879 8801 4897 8802 4879 8802 4898 8802 4898 8803 4879 8803 4880 8803 4898 8804 4880 8804 4899 8804 4899 8805 4880 8805 4881 8805 4899 8806 4881 8806 4900 8806 4900 8807 4881 8807 4882 8807 4900 8808 4882 8808 4901 8808 4901 8809 4882 8809 4883 8809 4901 8810 4883 8810 4902 8810 4902 8811 4883 8811 4884 8811 4902 8812 4884 8812 4903 8812 4903 8813 4884 8813 4885 8813 4903 8814 4885 8814 4904 8814 4904 8815 4885 8815 4886 8815 4904 8816 4886 8816 4905 8816 4905 8817 4886 8817 4887 8817 4905 8818 4887 8818 4906 8818 4906 8819 4887 8819 4888 8819 4906 8820 4888 8820 4907 8820 4907 8821 4888 8821 4889 8821 4907 8822 4889 8822 4908 8822 4908 8823 4889 8823 4890 8823 4908 8824 4890 8824 4909 8824 4909 8825 4890 8825 4891 8825 4909 8826 4891 8826 4910 8826 4910 8827 4891 8827 4892 8827 4910 8828 4892 8828 4911 8828 4911 8829 4892 8829 4893 8829 4911 8830 4893 8830 4912 8830 4912 8831 4893 8831 4894 8831 4912 8832 4894 8832 4913 8832 4913 8833 4894 8833 3625 8833 4913 8834 3625 8834 3623 8834 3596 8835 3595 8835 4895 8835 3596 8836 4895 8836 4914 8836 4914 8837 4895 8837 4896 8837 4914 8838 4896 8838 4915 8838 4915 8839 4896 8839 4897 8839 4915 8840 4897 8840 4916 8840 4916 8841 4897 8841 4898 8841 4916 8842 4898 8842 4917 8842 4917 8843 4898 8843 4899 8843 4917 8844 4899 8844 4918 8844 4918 8845 4899 8845 4900 8845 4918 8846 4900 8846 4919 8846 4919 8847 4900 8847 4901 8847 4919 8848 4901 8848 4920 8848 4920 8849 4901 8849 4902 8849 4920 8850 4902 8850 4921 8850 4921 8851 4902 8851 4903 8851 4921 8852 4903 8852 4922 8852 4922 8853 4903 8853 4904 8853 4922 8854 4904 8854 4923 8854 4923 8855 4904 8855 4905 8855 4923 8856 4905 8856 4924 8856 4924 8857 4905 8857 4906 8857 4924 8858 4906 8858 4925 8858 4925 8859 4906 8859 4907 8859 4925 8860 4907 8860 4926 8860 4926 8861 4907 8861 4908 8861 4926 8862 4908 8862 4927 8862 4927 8863 4908 8863 4909 8863 4927 8864 4909 8864 4928 8864 4928 8865 4909 8865 4910 8865 4928 8866 4910 8866 4929 8866 4929 8867 4910 8867 4911 8867 4929 8868 4911 8868 4930 8868 4930 8869 4911 8869 4912 8869 4930 8870 4912 8870 4931 8870 4931 8871 4912 8871 4913 8871 4931 8872 4913 8872 4932 8872 4932 8873 4913 8873 3623 8873 4932 8874 3623 8874 3621 8874 4933 8875 3596 8875 4914 8875 4933 8876 4914 8876 4934 8876 4934 8877 4914 8877 4915 8877 4934 8878 4915 8878 4935 8878 4935 8879 4915 8879 4916 8879 4935 8880 4916 8880 4936 8880 4936 8881 4916 8881 4917 8881 4936 8882 4917 8882 4937 8882 4937 8883 4917 8883 4918 8883 4937 8884 4918 8884 4938 8884 4938 8885 4918 8885 4919 8885 4938 8886 4919 8886 4939 8886 4939 8887 4919 8887 4920 8887 4939 8888 4920 8888 4940 8888 4940 8889 4920 8889 4921 8889 4940 8890 4921 8890 4941 8890 4941 8891 4921 8891 4922 8891 4941 8892 4922 8892 4942 8892 4942 8893 4922 8893 4923 8893 4942 8894 4923 8894 4943 8894 4943 8895 4923 8895 4924 8895 4943 8896 4924 8896 4944 8896 4944 8897 4924 8897 4925 8897 4944 8898 4925 8898 4945 8898 4945 8899 4925 8899 4926 8899 4945 8900 4926 8900 4946 8900 4946 8901 4926 8901 4927 8901 4946 8902 4927 8902 4947 8902 4947 8903 4927 8903 4928 8903 4947 8904 4928 8904 4948 8904 4948 8905 4928 8905 4929 8905 4948 8906 4929 8906 4949 8906 4949 8907 4929 8907 4930 8907 4949 8908 4930 8908 4950 8908 4950 8909 4930 8909 4931 8909 4950 8910 4931 8910 4951 8910 4951 8911 4931 8911 4932 8911 4951 8912 4932 8912 4952 8912 4952 8913 4932 8913 3621 8913 4952 8914 3621 8914 3619 8914 3592 8915 4933 8915 4934 8915 3592 8916 4934 8916 4953 8916 4953 8917 4934 8917 4935 8917 4953 8918 4935 8918 4954 8918 4954 8919 4935 8919 4936 8919 4954 8920 4936 8920 4955 8920 4955 8921 4936 8921 4937 8921 4955 8922 4937 8922 4956 8922 4956 8923 4937 8923 4938 8923 4956 8924 4938 8924 4957 8924 4957 8925 4938 8925 4939 8925 4957 8926 4939 8926 4958 8926 4958 8927 4939 8927 4940 8927 4958 8928 4940 8928 4959 8928 4959 8929 4940 8929 4941 8929 4959 8930 4941 8930 4960 8930 4960 8931 4941 8931 4942 8931 4960 8932 4942 8932 4961 8932 4961 8933 4942 8933 4943 8933 4961 8934 4943 8934 4962 8934 4962 8935 4943 8935 4944 8935 4962 8936 4944 8936 4963 8936 4963 8937 4944 8937 4945 8937 4963 8938 4945 8938 4964 8938 4964 8939 4945 8939 4946 8939 4964 8940 4946 8940 4965 8940 4965 8941 4946 8941 4947 8941 4965 8942 4947 8942 4966 8942 4966 8943 4947 8943 4948 8943 4966 8944 4948 8944 4967 8944 4967 8945 4948 8945 4949 8945 4967 8946 4949 8946 4968 8946 4968 8947 4949 8947 4950 8947 4968 8948 4950 8948 4969 8948 4969 8949 4950 8949 4951 8949 4969 8950 4951 8950 4970 8950 4970 8951 4951 8951 4952 8951 4970 8952 4952 8952 4971 8952 4971 8953 4952 8953 3619 8953 4971 8954 3619 8954 3617 8954 3590 8955 3592 8955 4953 8955 3590 8956 4953 8956 4972 8956 4972 8957 4953 8957 4954 8957 4972 8958 4954 8958 4973 8958 4973 8959 4954 8959 4955 8959 4973 8960 4955 8960 4974 8960 4974 8961 4955 8961 4956 8961 4974 8962 4956 8962 4975 8962 4975 8963 4956 8963 4957 8963 4975 8964 4957 8964 4976 8964 4976 8965 4957 8965 4958 8965 4976 8966 4958 8966 4977 8966 4977 8967 4958 8967 4959 8967 4977 8968 4959 8968 4978 8968 4978 8969 4959 8969 4960 8969 4978 8970 4960 8970 4979 8970 4979 8971 4960 8971 4961 8971 4979 8972 4961 8972 4980 8972 4980 8973 4961 8973 4962 8973 4980 8974 4962 8974 4981 8974 4981 8975 4962 8975 4963 8975 4981 8976 4963 8976 4982 8976 4982 8977 4963 8977 4964 8977 4982 8978 4964 8978 4983 8978 4983 8979 4964 8979 4965 8979 4983 8980 4965 8980 4984 8980 4984 8981 4965 8981 4966 8981 4984 8982 4966 8982 4985 8982 4985 8983 4966 8983 4967 8983 4985 8984 4967 8984 4986 8984 4986 8985 4967 8985 4968 8985 4986 8986 4968 8986 4987 8986 4987 8987 4968 8987 4969 8987 4987 8988 4969 8988 4988 8988 4988 8989 4969 8989 4970 8989 4988 8990 4970 8990 4989 8990 4989 8991 4970 8991 4971 8991 4989 8992 4971 8992 4990 8992 4990 8993 4971 8993 3617 8993 4990 8994 3617 8994 3616 8994 3585 8995 3590 8995 4972 8995 3585 8996 4972 8996 3586 8996 3586 8997 4972 8997 4973 8997 3586 8998 4973 8998 4991 8998 4991 8999 4973 8999 4974 8999 4991 9000 4974 9000 4992 9000 4992 9001 4974 9001 4975 9001 4992 9002 4975 9002 4993 9002 4993 9003 4975 9003 4976 9003 4993 9004 4976 9004 4994 9004 4994 9005 4976 9005 4977 9005 4994 9006 4977 9006 4995 9006 4995 9007 4977 9007 4978 9007 4995 9008 4978 9008 4996 9008 4996 9009 4978 9009 4979 9009 4996 9010 4979 9010 4997 9010 4997 9011 4979 9011 4980 9011 4997 9012 4980 9012 4998 9012 4998 9013 4980 9013 4981 9013 4998 9014 4981 9014 4999 9014 4999 9015 4981 9015 4982 9015 4999 9016 4982 9016 5000 9016 5000 9017 4982 9017 4983 9017 5000 9018 4983 9018 5001 9018 5001 9019 4983 9019 4984 9019 5001 9020 4984 9020 5002 9020 5002 9021 4984 9021 4985 9021 5002 9022 4985 9022 5003 9022 5003 9023 4985 9023 4986 9023 5003 9024 4986 9024 5004 9024 5004 9025 4986 9025 4987 9025 5004 9026 4987 9026 5005 9026 5005 9027 4987 9027 4988 9027 5005 9028 4988 9028 5006 9028 5006 9029 4988 9029 4989 9029 5006 9030 4989 9030 5007 9030 5007 9031 4989 9031 4990 9031 5007 9032 4990 9032 5008 9032 5008 9033 4990 9033 3616 9033 5008 9034 3616 9034 3615 9034 3580 9035 4567 9035 5009 9035 3580 9036 5009 9036 3581 9036 4567 9037 4568 9037 5010 9037 4567 9038 5010 9038 5009 9038 4568 9039 4569 9039 5011 9039 4568 9040 5011 9040 5010 9040 4569 9041 4570 9041 5012 9041 4569 9042 5012 9042 5011 9042 4570 9043 4571 9043 5013 9043 4570 9044 5013 9044 5012 9044 4571 9045 4572 9045 5014 9045 4571 9046 5014 9046 5013 9046 4572 9047 4573 9047 5015 9047 4572 9048 5015 9048 5014 9048 4573 9049 4574 9049 5016 9049 4573 9050 5016 9050 5015 9050 4574 9051 4575 9051 5017 9051 4574 9052 5017 9052 5016 9052 4575 9053 4576 9053 5018 9053 4575 9054 5018 9054 5017 9054 4576 9055 4577 9055 5019 9055 4576 9056 5019 9056 5018 9056 4577 9057 4578 9057 5020 9057 4577 9058 5020 9058 5019 9058 4578 9059 4579 9059 5021 9059 4578 9060 5021 9060 5020 9060 4579 9061 4580 9061 5022 9061 4579 9062 5022 9062 5021 9062 4580 9063 4581 9063 5023 9063 4580 9064 5023 9064 5022 9064 4581 9065 4582 9065 5024 9065 4581 9066 5024 9066 5023 9066 4582 9067 4583 9067 5025 9067 4582 9068 5025 9068 5024 9068 4583 9069 4584 9069 5026 9069 4583 9070 5026 9070 5025 9070 4584 9071 4585 9071 5027 9071 4584 9072 5027 9072 5026 9072 4585 9073 3587 9073 3576 9073 4585 9074 3576 9074 5027 9074 3572 9075 4375 9075 3615 9075 3572 9076 3615 9076 3573 9076 4375 9077 4376 9077 5008 9077 4375 9078 5008 9078 3615 9078 4376 9079 4377 9079 5007 9079 4376 9080 5007 9080 5008 9080 4377 9081 4378 9081 5006 9081 4377 9082 5006 9082 5007 9082 4378 9083 4379 9083 5005 9083 4378 9084 5005 9084 5006 9084 4379 9085 4380 9085 5004 9085 4379 9086 5004 9086 5005 9086 4380 9087 4381 9087 5003 9087 4380 9088 5003 9088 5004 9088 4381 9089 4382 9089 5002 9089 4381 9090 5002 9090 5003 9090 4382 9091 4383 9091 5001 9091 4382 9092 5001 9092 5002 9092 4383 9093 4384 9093 5000 9093 4383 9094 5000 9094 5001 9094 4384 9095 4385 9095 4999 9095 4384 9096 4999 9096 5000 9096 4385 9097 4386 9097 4998 9097 4385 9098 4998 9098 4999 9098 4386 9099 4387 9099 4997 9099 4386 9100 4997 9100 4998 9100 4387 9101 4388 9101 4996 9101 4387 9102 4996 9102 4997 9102 4388 9103 4389 9103 4995 9103 4388 9104 4995 9104 4996 9104 4389 9105 4390 9105 4994 9105 4389 9106 4994 9106 4995 9106 4390 9107 4391 9107 4993 9107 4390 9108 4993 9108 4994 9108 4391 9109 4392 9109 4992 9109 4391 9110 4992 9110 4993 9110 4392 9111 4393 9111 4991 9111 4392 9112 4991 9112 4992 9112 4393 9113 3583 9113 3586 9113 4393 9114 3586 9114 4991 9114 3582 9115 3581 9115 5009 9115 3582 9116 5009 9116 4586 9116 4586 9117 5009 9117 5010 9117 4586 9118 5010 9118 4588 9118 4588 9119 5010 9119 5011 9119 4588 9120 5011 9120 4590 9120 4590 9121 5011 9121 5012 9121 4590 9122 5012 9122 4592 9122 4592 9123 5012 9123 5013 9123 4592 9124 5013 9124 4594 9124 4594 9125 5013 9125 5014 9125 4594 9126 5014 9126 4596 9126 4596 9127 5014 9127 5015 9127 4596 9128 5015 9128 4598 9128 4598 9129 5015 9129 5016 9129 4598 9130 5016 9130 4600 9130 4600 9131 5016 9131 5017 9131 4600 9132 5017 9132 4602 9132 4602 9133 5017 9133 5018 9133 4602 9134 5018 9134 4604 9134 4604 9135 5018 9135 5019 9135 4604 9136 5019 9136 4606 9136 4606 9137 5019 9137 5020 9137 4606 9138 5020 9138 4608 9138 4608 9139 5020 9139 5021 9139 4608 9140 5021 9140 4610 9140 4610 9141 5021 9141 5022 9141 4610 9142 5022 9142 4612 9142 4612 9143 5022 9143 5023 9143 4612 9144 5023 9144 4614 9144 4614 9145 5023 9145 5024 9145 4614 9146 5024 9146 4616 9146 4616 9147 5024 9147 5025 9147 4616 9148 5025 9148 4618 9148 4618 9149 5025 9149 5026 9149 4618 9150 5026 9150 4620 9150 4620 9151 5026 9151 5027 9151 4620 9152 5027 9152 4622 9152 4622 9153 5027 9153 3576 9153 4622 9154 3576 9154 3575 9154 4145 9155 4182 9155 4179 9155 4179 9156 4177 9156 4175 9156 4179 9157 4175 9157 4173 9157 4144 9158 4145 9158 4179 9158 4161 9159 4153 9159 4144 9159 4165 9160 4163 9160 4161 9160 4167 9161 4165 9161 4161 9161 4144 9162 4179 9162 4173 9162 4144 9163 4173 9163 4171 9163 4167 9164 4161 9164 4144 9164 4144 9165 4171 9165 4169 9165 4169 9166 4167 9166 4144 9166 3789 9167 4145 9167 4135 9167 4135 9168 4134 9168 4146 9168 4146 9169 4104 9169 3787 9169 3787 9170 3789 9170 4135 9170 4135 9171 4146 9171 3787 9171 5028 9172 5029 9172 4050 9172 4050 9173 4049 9173 5030 9173 5030 9174 5031 9174 5028 9174 4050 9175 5030 9175 5028 9175 4047 9176 4045 9176 4060 9176 4047 9177 4060 9177 4049 9177 4059 9178 4058 9178 4068 9178 4059 9179 4068 9179 4060 9179 4075 9180 4074 9180 4081 9180 4068 9181 4067 9181 4075 9181 4080 9182 4086 9182 4091 9182 4080 9183 4091 9183 4081 9183 4855 9184 5032 9184 5033 9184 4855 9185 5033 9185 3631 9185 5032 9186 5034 9186 5035 9186 5032 9187 5035 9187 5033 9187 5034 9188 5036 9188 5037 9188 5034 9189 5037 9189 5035 9189 5036 9190 5038 9190 5039 9190 5036 9191 5039 9191 5037 9191 5038 9192 5040 9192 5041 9192 5038 9193 5041 9193 5039 9193 4853 9194 5042 9194 5032 9194 4853 9195 5032 9195 4855 9195 5042 9196 5043 9196 5034 9196 5042 9197 5034 9197 5032 9197 5043 9198 5044 9198 5036 9198 5043 9199 5036 9199 5034 9199 5044 9200 5045 9200 5038 9200 5044 9201 5038 9201 5036 9201 5045 9202 5046 9202 5040 9202 5045 9203 5040 9203 5038 9203 4851 9204 5047 9204 5042 9204 4851 9205 5042 9205 4853 9205 5047 9206 5048 9206 5043 9206 5047 9207 5043 9207 5042 9207 5048 9208 5049 9208 5044 9208 5048 9209 5044 9209 5043 9209 5049 9210 5050 9210 5045 9210 5049 9211 5045 9211 5044 9211 5050 9212 5051 9212 5046 9212 5050 9213 5046 9213 5045 9213 4849 9214 5052 9214 5047 9214 4849 9215 5047 9215 4851 9215 5052 9216 5053 9216 5048 9216 5052 9217 5048 9217 5047 9217 5053 9218 5054 9218 5049 9218 5053 9219 5049 9219 5048 9219 5054 9220 5055 9220 5050 9220 5054 9221 5050 9221 5049 9221 5055 9222 5056 9222 5051 9222 5055 9223 5051 9223 5050 9223 5056 9224 5057 9224 5058 9224 5056 9225 5058 9225 5051 9225 4847 9226 5059 9226 5052 9226 4847 9227 5052 9227 4849 9227 5059 9228 5060 9228 5053 9228 5059 9229 5053 9229 5052 9229 5060 9230 5061 9230 5054 9230 5060 9231 5054 9231 5053 9231 5061 9232 5062 9232 5055 9232 5061 9233 5055 9233 5054 9233 5062 9234 5063 9234 5056 9234 5062 9235 5056 9235 5055 9235 5063 9236 5064 9236 5057 9236 5063 9237 5057 9237 5056 9237 4845 9238 5065 9238 5059 9238 4845 9239 5059 9239 4847 9239 5065 9240 5066 9240 5060 9240 5065 9241 5060 9241 5059 9241 5066 9242 5067 9242 5061 9242 5066 9243 5061 9243 5060 9243 5067 9244 5068 9244 5062 9244 5067 9245 5062 9245 5061 9245 5068 9246 5069 9246 5063 9246 5068 9247 5063 9247 5062 9247 5069 9248 5070 9248 5064 9248 5069 9249 5064 9249 5063 9249 5070 9250 5071 9250 5072 9250 5070 9251 5072 9251 5064 9251 4843 9252 5073 9252 5065 9252 4843 9253 5065 9253 4845 9253 5073 9254 5074 9254 5066 9254 5073 9255 5066 9255 5065 9255 5074 9256 5075 9256 5067 9256 5074 9257 5067 9257 5066 9257 5075 9258 5076 9258 5068 9258 5075 9259 5068 9259 5067 9259 5076 9260 5077 9260 5069 9260 5076 9261 5069 9261 5068 9261 5077 9262 5078 9262 5070 9262 5077 9263 5070 9263 5069 9263 5078 9264 5079 9264 5071 9264 5078 9265 5071 9265 5070 9265 4841 9266 5080 9266 5073 9266 4841 9267 5073 9267 4843 9267 5080 9268 5081 9268 5074 9268 5080 9269 5074 9269 5073 9269 5081 9270 5082 9270 5075 9270 5081 9271 5075 9271 5074 9271 5082 9272 5083 9272 5076 9272 5082 9273 5076 9273 5075 9273 5083 9274 5084 9274 5077 9274 5083 9275 5077 9275 5076 9275 5084 9276 5085 9276 5078 9276 5084 9277 5078 9277 5077 9277 5085 9278 5086 9278 5079 9278 5085 9279 5079 9279 5078 9279 5086 9280 5087 9280 5088 9280 5086 9281 5088 9281 5079 9281 5087 9282 5089 9282 5090 9282 5087 9283 5090 9283 5088 9283 4839 9284 5091 9284 5080 9284 4839 9285 5080 9285 4841 9285 5091 9286 5092 9286 5081 9286 5091 9287 5081 9287 5080 9287 5092 9288 5093 9288 5082 9288 5092 9289 5082 9289 5081 9289 5093 9290 5094 9290 5083 9290 5093 9291 5083 9291 5082 9291 5094 9292 5095 9292 5084 9292 5094 9293 5084 9293 5083 9293 5095 9294 5096 9294 5085 9294 5095 9295 5085 9295 5084 9295 5096 9296 5097 9296 5086 9296 5096 9297 5086 9297 5085 9297 5097 9298 5098 9298 5087 9298 5097 9299 5087 9299 5086 9299 5098 9300 5099 9300 5089 9300 5098 9301 5089 9301 5087 9301 5099 9302 4816 9302 4818 9302 5099 9303 4818 9303 5089 9303 4837 9304 5100 9304 5091 9304 4837 9305 5091 9305 4839 9305 5100 9306 5101 9306 5092 9306 5100 9307 5092 9307 5091 9307 5101 9308 5102 9308 5093 9308 5101 9309 5093 9309 5092 9309 5102 9310 5103 9310 5094 9310 5102 9311 5094 9311 5093 9311 5103 9312 5104 9312 5095 9312 5103 9313 5095 9313 5094 9313 5104 9314 5105 9314 5096 9314 5104 9315 5096 9315 5095 9315 5105 9316 5106 9316 5097 9316 5105 9317 5097 9317 5096 9317 5106 9318 5107 9318 5098 9318 5106 9319 5098 9319 5097 9319 5107 9320 5108 9320 5099 9320 5107 9321 5099 9321 5098 9321 5108 9322 4814 9322 4816 9322 5108 9323 4816 9323 5099 9323 4835 9324 5109 9324 5100 9324 4835 9325 5100 9325 4837 9325 5109 9326 5110 9326 5101 9326 5109 9327 5101 9327 5100 9327 5110 9328 5111 9328 5102 9328 5110 9329 5102 9329 5101 9329 5111 9330 5112 9330 5103 9330 5111 9331 5103 9331 5102 9331 5112 9332 5113 9332 5104 9332 5112 9333 5104 9333 5103 9333 5113 9334 5114 9334 5105 9334 5113 9335 5105 9335 5104 9335 5114 9336 5115 9336 5106 9336 5114 9337 5106 9337 5105 9337 5115 9338 5116 9338 5107 9338 5115 9339 5107 9339 5106 9339 5116 9340 5117 9340 5108 9340 5116 9341 5108 9341 5107 9341 5117 9342 4812 9342 4814 9342 5117 9343 4814 9343 5108 9343 4833 9344 5118 9344 5109 9344 4833 9345 5109 9345 4835 9345 5118 9346 5119 9346 5110 9346 5118 9347 5110 9347 5109 9347 5119 9348 5120 9348 5111 9348 5119 9349 5111 9349 5110 9349 5120 9350 5121 9350 5112 9350 5120 9351 5112 9351 5111 9351 5121 9352 5122 9352 5113 9352 5121 9353 5113 9353 5112 9353 5122 9354 5123 9354 5114 9354 5122 9355 5114 9355 5113 9355 5123 9356 5124 9356 5115 9356 5123 9357 5115 9357 5114 9357 5124 9358 5125 9358 5116 9358 5124 9359 5116 9359 5115 9359 5125 9360 5126 9360 5117 9360 5125 9361 5117 9361 5116 9361 5126 9362 4810 9362 4812 9362 5126 9363 4812 9363 5117 9363 4831 9364 5127 9364 5118 9364 4831 9365 5118 9365 4833 9365 5127 9366 5128 9366 5119 9366 5127 9367 5119 9367 5118 9367 5128 9368 5129 9368 5120 9368 5128 9369 5120 9369 5119 9369 5129 9370 5130 9370 5121 9370 5129 9371 5121 9371 5120 9371 5130 9372 5131 9372 5122 9372 5130 9373 5122 9373 5121 9373 5131 9374 5132 9374 5123 9374 5131 9375 5123 9375 5122 9375 5132 9376 5133 9376 5124 9376 5132 9377 5124 9377 5123 9377 5133 9378 5134 9378 5125 9378 5133 9379 5125 9379 5124 9379 5134 9380 5135 9380 5126 9380 5134 9381 5126 9381 5125 9381 5135 9382 4808 9382 4810 9382 5135 9383 4810 9383 5126 9383 4829 9384 5136 9384 5127 9384 4829 9385 5127 9385 4831 9385 5136 9386 5137 9386 5128 9386 5136 9387 5128 9387 5127 9387 5137 9388 5138 9388 5129 9388 5137 9389 5129 9389 5128 9389 5138 9390 5139 9390 5130 9390 5138 9391 5130 9391 5129 9391 5139 9392 5140 9392 5131 9392 5139 9393 5131 9393 5130 9393 5140 9394 5141 9394 5132 9394 5140 9395 5132 9395 5131 9395 5141 9396 5142 9396 5133 9396 5141 9397 5133 9397 5132 9397 5142 9398 5143 9398 5134 9398 5142 9399 5134 9399 5133 9399 5143 9400 5144 9400 5135 9400 5143 9401 5135 9401 5134 9401 5144 9402 4806 9402 4808 9402 5144 9403 4808 9403 5135 9403 4827 9404 5145 9404 5136 9404 4827 9405 5136 9405 4829 9405 5145 9406 5146 9406 5137 9406 5145 9407 5137 9407 5136 9407 5146 9408 5147 9408 5138 9408 5146 9409 5138 9409 5137 9409 5147 9410 5148 9410 5139 9410 5147 9411 5139 9411 5138 9411 5148 9412 5149 9412 5140 9412 5148 9413 5140 9413 5139 9413 5149 9414 5150 9414 5141 9414 5149 9415 5141 9415 5140 9415 5150 9416 5151 9416 5142 9416 5150 9417 5142 9417 5141 9417 5151 9418 5152 9418 5143 9418 5151 9419 5143 9419 5142 9419 5152 9420 5153 9420 5144 9420 5152 9421 5144 9421 5143 9421 5153 9422 4804 9422 4806 9422 5153 9423 4806 9423 5144 9423 4825 9424 5154 9424 5145 9424 4825 9425 5145 9425 4827 9425 5154 9426 5155 9426 5146 9426 5154 9427 5146 9427 5145 9427 5155 9428 5156 9428 5147 9428 5155 9429 5147 9429 5146 9429 5156 9430 5157 9430 5148 9430 5156 9431 5148 9431 5147 9431 5157 9432 5158 9432 5149 9432 5157 9433 5149 9433 5148 9433 5158 9434 5159 9434 5150 9434 5158 9435 5150 9435 5149 9435 5159 9436 5160 9436 5151 9436 5159 9437 5151 9437 5150 9437 5160 9438 5161 9438 5152 9438 5160 9439 5152 9439 5151 9439 5161 9440 5162 9440 5153 9440 5161 9441 5153 9441 5152 9441 5162 9442 4802 9442 4804 9442 5162 9443 4804 9443 5153 9443 4823 9444 5163 9444 5154 9444 4823 9445 5154 9445 4825 9445 5163 9446 5164 9446 5155 9446 5163 9447 5155 9447 5154 9447 5164 9448 5165 9448 5156 9448 5164 9449 5156 9449 5155 9449 5165 9450 5166 9450 5157 9450 5165 9451 5157 9451 5156 9451 5166 9452 5167 9452 5158 9452 5166 9453 5158 9453 5157 9453 5167 9454 5168 9454 5159 9454 5167 9455 5159 9455 5158 9455 5168 9456 5169 9456 5160 9456 5168 9457 5160 9457 5159 9457 5169 9458 5170 9458 5161 9458 5169 9459 5161 9459 5160 9459 5170 9460 5171 9460 5162 9460 5170 9461 5162 9461 5161 9461 5171 9462 4800 9462 4802 9462 5171 9463 4802 9463 5162 9463 4821 9464 5172 9464 5163 9464 4821 9465 5163 9465 4823 9465 5172 9466 5173 9466 5164 9466 5172 9467 5164 9467 5163 9467 5173 9468 5174 9468 5165 9468 5173 9469 5165 9469 5164 9469 5174 9470 5175 9470 5166 9470 5174 9471 5166 9471 5165 9471 5175 9472 5176 9472 5167 9472 5175 9473 5167 9473 5166 9473 5176 9474 5177 9474 5168 9474 5176 9475 5168 9475 5167 9475 5177 9476 5178 9476 5169 9476 5177 9477 5169 9477 5168 9477 5178 9478 5179 9478 5170 9478 5178 9479 5170 9479 5169 9479 5179 9480 5180 9480 5171 9480 5179 9481 5171 9481 5170 9481 5180 9482 4798 9482 4800 9482 5180 9483 4800 9483 5171 9483 4819 9484 5181 9484 5172 9484 4819 9485 5172 9485 4821 9485 5181 9486 5182 9486 5173 9486 5181 9487 5173 9487 5172 9487 5182 9488 5183 9488 5174 9488 5182 9489 5174 9489 5173 9489 5183 9490 5184 9490 5175 9490 5183 9491 5175 9491 5174 9491 5184 9492 5185 9492 5176 9492 5184 9493 5176 9493 5175 9493 5185 9494 5186 9494 5177 9494 5185 9495 5177 9495 5176 9495 5186 9496 5187 9496 5178 9496 5186 9497 5178 9497 5177 9497 5187 9498 5188 9498 5179 9498 5187 9499 5179 9499 5178 9499 5188 9500 5189 9500 5180 9500 5188 9501 5180 9501 5179 9501 5189 9502 4796 9502 4798 9502 5189 9503 4798 9503 5180 9503 3604 9504 5190 9504 5181 9504 3604 9505 5181 9505 4819 9505 5190 9506 5191 9506 5182 9506 5190 9507 5182 9507 5181 9507 5191 9508 5192 9508 5183 9508 5191 9509 5183 9509 5182 9509 5192 9510 5193 9510 5184 9510 5192 9511 5184 9511 5183 9511 5193 9512 5194 9512 5185 9512 5193 9513 5185 9513 5184 9513 5194 9514 5195 9514 5186 9514 5194 9515 5186 9515 5185 9515 5195 9516 5196 9516 5187 9516 5195 9517 5187 9517 5186 9517 5196 9518 5197 9518 5188 9518 5196 9519 5188 9519 5187 9519 5197 9520 5198 9520 5189 9520 5197 9521 5189 9521 5188 9521 5198 9522 3608 9522 4796 9522 5198 9523 4796 9523 5189 9523 3949 9524 3684 9524 5199 9524 3949 9525 5199 9525 5200 9525 5200 9526 5199 9526 5201 9526 5200 9527 5201 9527 5202 9527 5202 9528 5201 9528 5203 9528 5202 9529 5203 9529 5204 9529 5204 9530 5203 9530 5205 9530 5204 9531 5205 9531 5206 9531 5206 9532 5205 9532 5207 9532 5206 9533 5207 9533 5208 9533 5208 9534 5207 9534 5209 9534 5208 9535 5209 9535 5210 9535 5210 9536 5209 9536 5211 9536 5210 9537 5211 9537 5212 9537 5212 9538 5211 9538 5213 9538 5212 9539 5213 9539 5214 9539 5214 9540 5213 9540 5215 9540 5214 9541 5215 9541 5216 9541 5216 9542 5215 9542 3685 9542 5216 9543 3685 9543 3921 9543 3947 9544 3949 9544 5200 9544 3947 9545 5200 9545 5217 9545 5217 9546 5200 9546 5202 9546 5217 9547 5202 9547 5218 9547 5218 9548 5202 9548 5204 9548 5218 9549 5204 9549 5219 9549 5219 9550 5204 9550 5206 9550 5219 9551 5206 9551 5220 9551 5220 9552 5206 9552 5208 9552 5220 9553 5208 9553 5221 9553 5221 9554 5208 9554 5210 9554 5221 9555 5210 9555 5222 9555 5222 9556 5210 9556 5212 9556 5222 9557 5212 9557 5223 9557 5223 9558 5212 9558 5214 9558 5223 9559 5214 9559 5224 9559 5224 9560 5214 9560 5216 9560 5224 9561 5216 9561 5225 9561 5225 9562 5216 9562 3921 9562 5225 9563 3921 9563 3920 9563 3945 9564 3947 9564 5217 9564 3945 9565 5217 9565 5226 9565 5226 9566 5217 9566 5218 9566 5226 9567 5218 9567 5227 9567 5227 9568 5218 9568 5219 9568 5227 9569 5219 9569 5228 9569 5228 9570 5219 9570 5220 9570 5228 9571 5220 9571 5229 9571 5229 9572 5220 9572 5221 9572 5229 9573 5221 9573 5230 9573 5230 9574 5221 9574 5222 9574 5230 9575 5222 9575 5231 9575 5231 9576 5222 9576 5223 9576 5231 9577 5223 9577 5232 9577 5232 9578 5223 9578 5224 9578 5232 9579 5224 9579 5233 9579 5233 9580 5224 9580 5225 9580 5233 9581 5225 9581 5234 9581 5234 9582 5225 9582 3920 9582 5234 9583 3920 9583 3919 9583 3943 9584 3945 9584 5226 9584 3943 9585 5226 9585 5235 9585 5235 9586 5226 9586 5227 9586 5235 9587 5227 9587 5236 9587 5236 9588 5227 9588 5228 9588 5236 9589 5228 9589 5237 9589 5237 9590 5228 9590 5229 9590 5237 9591 5229 9591 5238 9591 5238 9592 5229 9592 5230 9592 5238 9593 5230 9593 5239 9593 5239 9594 5230 9594 5231 9594 5239 9595 5231 9595 5240 9595 5240 9596 5231 9596 5232 9596 5240 9597 5232 9597 5241 9597 5241 9598 5232 9598 5233 9598 5241 9599 5233 9599 5242 9599 5242 9600 5233 9600 5234 9600 5242 9601 5234 9601 5243 9601 5243 9602 5234 9602 3919 9602 5243 9603 3919 9603 3918 9603 3941 9604 3943 9604 5235 9604 3941 9605 5235 9605 5244 9605 5244 9606 5235 9606 5236 9606 5244 9607 5236 9607 5245 9607 5245 9608 5236 9608 5237 9608 5245 9609 5237 9609 5246 9609 5246 9610 5237 9610 5238 9610 5246 9611 5238 9611 5247 9611 5247 9612 5238 9612 5239 9612 5247 9613 5239 9613 5248 9613 5248 9614 5239 9614 5240 9614 5248 9615 5240 9615 5249 9615 5249 9616 5240 9616 5241 9616 5249 9617 5241 9617 5250 9617 5250 9618 5241 9618 5242 9618 5250 9619 5242 9619 5251 9619 5251 9620 5242 9620 5243 9620 5251 9621 5243 9621 5252 9621 5252 9622 5243 9622 3918 9622 5252 9623 3918 9623 3917 9623 3939 9624 3941 9624 5244 9624 3939 9625 5244 9625 5253 9625 5253 9626 5244 9626 5245 9626 5253 9627 5245 9627 5254 9627 5254 9628 5245 9628 5246 9628 5254 9629 5246 9629 5255 9629 5255 9630 5246 9630 5247 9630 5255 9631 5247 9631 5256 9631 5256 9632 5247 9632 5248 9632 5256 9633 5248 9633 5257 9633 5257 9634 5248 9634 5249 9634 5257 9635 5249 9635 5258 9635 5258 9636 5249 9636 5250 9636 5258 9637 5250 9637 5259 9637 5259 9638 5250 9638 5251 9638 5259 9639 5251 9639 5260 9639 5260 9640 5251 9640 5252 9640 5260 9641 5252 9641 5261 9641 5261 9642 5252 9642 3917 9642 5261 9643 3917 9643 3916 9643 3937 9644 3939 9644 5253 9644 3937 9645 5253 9645 5262 9645 5262 9646 5253 9646 5254 9646 5262 9647 5254 9647 5263 9647 5263 9648 5254 9648 5255 9648 5263 9649 5255 9649 5264 9649 5264 9650 5255 9650 5256 9650 5264 9651 5256 9651 5265 9651 5265 9652 5256 9652 5257 9652 5265 9653 5257 9653 5266 9653 5266 9654 5257 9654 5258 9654 5266 9655 5258 9655 5267 9655 5267 9656 5258 9656 5259 9656 5267 9657 5259 9657 5268 9657 5268 9658 5259 9658 5260 9658 5268 9659 5260 9659 5269 9659 5269 9660 5260 9660 5261 9660 5269 9661 5261 9661 5270 9661 5270 9662 5261 9662 3916 9662 5270 9663 3916 9663 3915 9663 3935 9664 3937 9664 5262 9664 3935 9665 5262 9665 5271 9665 5271 9666 5262 9666 5263 9666 5271 9667 5263 9667 5272 9667 5272 9668 5263 9668 5264 9668 5272 9669 5264 9669 5273 9669 5273 9670 5264 9670 5265 9670 5273 9671 5265 9671 5274 9671 5274 9672 5265 9672 5266 9672 5274 9673 5266 9673 5275 9673 5275 9674 5266 9674 5267 9674 5275 9675 5267 9675 5276 9675 5276 9676 5267 9676 5268 9676 5276 9677 5268 9677 5277 9677 5277 9678 5268 9678 5269 9678 5277 9679 5269 9679 5278 9679 5278 9680 5269 9680 5270 9680 5278 9681 5270 9681 5279 9681 5279 9682 5270 9682 3915 9682 5279 9683 3915 9683 3914 9683 3933 9684 3935 9684 5271 9684 3933 9685 5271 9685 5280 9685 5280 9686 5271 9686 5272 9686 5280 9687 5272 9687 5281 9687 5281 9688 5272 9688 5273 9688 5281 9689 5273 9689 5282 9689 5282 9690 5273 9690 5274 9690 5282 9691 5274 9691 5283 9691 5283 9692 5274 9692 5275 9692 5283 9693 5275 9693 5284 9693 5284 9694 5275 9694 5276 9694 5284 9695 5276 9695 5285 9695 5285 9696 5276 9696 5277 9696 5285 9697 5277 9697 5286 9697 5286 9698 5277 9698 5278 9698 5286 9699 5278 9699 5287 9699 5287 9700 5278 9700 5279 9700 5287 9701 5279 9701 5288 9701 5288 9702 5279 9702 3914 9702 5288 9703 3914 9703 3913 9703 3931 9704 3933 9704 5280 9704 3931 9705 5280 9705 5289 9705 5289 9706 5280 9706 5281 9706 5289 9707 5281 9707 5290 9707 5290 9708 5281 9708 5282 9708 5290 9709 5282 9709 5291 9709 5291 9710 5282 9710 5283 9710 5291 9711 5283 9711 5292 9711 5292 9712 5283 9712 5284 9712 5292 9713 5284 9713 5293 9713 5293 9714 5284 9714 5285 9714 5293 9715 5285 9715 5294 9715 5294 9716 5285 9716 5286 9716 5294 9717 5286 9717 5295 9717 5295 9718 5286 9718 5287 9718 5295 9719 5287 9719 5296 9719 5296 9720 5287 9720 5288 9720 5296 9721 5288 9721 5297 9721 5297 9722 5288 9722 3913 9722 5297 9723 3913 9723 3912 9723 3928 9724 3931 9724 5289 9724 3928 9725 5289 9725 5298 9725 5298 9726 5289 9726 5290 9726 5298 9727 5290 9727 5299 9727 5299 9728 5290 9728 5291 9728 5299 9729 5291 9729 5300 9729 5300 9730 5291 9730 5292 9730 5300 9731 5292 9731 5301 9731 5301 9732 5292 9732 5293 9732 5301 9733 5293 9733 5302 9733 5302 9734 5293 9734 5294 9734 5302 9735 5294 9735 5303 9735 5303 9736 5294 9736 5295 9736 5303 9737 5295 9737 5304 9737 5304 9738 5295 9738 5296 9738 5304 9739 5296 9739 5305 9739 5305 9740 5296 9740 5297 9740 5305 9741 5297 9741 5306 9741 5306 9742 5297 9742 3912 9742 5306 9743 3912 9743 3911 9743 3929 9744 3928 9744 5298 9744 3929 9745 5298 9745 5307 9745 5307 9746 5298 9746 5299 9746 5307 9747 5299 9747 5308 9747 5308 9748 5299 9748 5300 9748 5308 9749 5300 9749 5309 9749 5309 9750 5300 9750 5301 9750 5309 9751 5301 9751 5310 9751 5310 9752 5301 9752 5302 9752 5310 9753 5302 9753 5311 9753 5311 9754 5302 9754 5303 9754 5311 9755 5303 9755 5312 9755 5312 9756 5303 9756 5304 9756 5312 9757 5304 9757 5313 9757 5313 9758 5304 9758 5305 9758 5313 9759 5305 9759 5314 9759 5314 9760 5305 9760 5306 9760 5314 9761 5306 9761 5315 9761 5315 9762 5306 9762 3911 9762 5315 9763 3911 9763 3910 9763 5316 9764 3929 9764 5307 9764 5316 9765 5307 9765 5317 9765 5317 9766 5307 9766 5308 9766 5317 9767 5308 9767 5318 9767 5318 9768 5308 9768 5309 9768 5318 9769 5309 9769 5319 9769 5319 9770 5309 9770 5310 9770 5319 9771 5310 9771 5320 9771 5320 9772 5310 9772 5311 9772 5320 9773 5311 9773 5321 9773 5321 9774 5311 9774 5312 9774 5321 9775 5312 9775 5322 9775 5322 9776 5312 9776 5313 9776 5322 9777 5313 9777 5323 9777 5323 9778 5313 9778 5314 9778 5323 9779 5314 9779 5324 9779 5324 9780 5314 9780 5315 9780 5324 9781 5315 9781 5325 9781 5325 9782 5315 9782 3910 9782 5325 9783 3910 9783 3909 9783 3924 9784 5316 9784 5317 9784 3924 9785 5317 9785 5326 9785 5326 9786 5317 9786 5318 9786 5326 9787 5318 9787 5327 9787 5327 9788 5318 9788 5319 9788 5327 9789 5319 9789 5328 9789 5328 9790 5319 9790 5320 9790 5328 9791 5320 9791 5329 9791 5329 9792 5320 9792 5321 9792 5329 9793 5321 9793 5330 9793 5330 9794 5321 9794 5322 9794 5330 9795 5322 9795 5331 9795 5331 9796 5322 9796 5323 9796 5331 9797 5323 9797 5332 9797 5332 9798 5323 9798 5324 9798 5332 9799 5324 9799 5333 9799 5333 9800 5324 9800 5325 9800 5333 9801 5325 9801 5334 9801 5334 9802 5325 9802 3909 9802 5334 9803 3909 9803 3908 9803 3925 9804 3924 9804 5326 9804 3925 9805 5326 9805 5335 9805 5335 9806 5326 9806 5327 9806 5335 9807 5327 9807 5336 9807 5336 9808 5327 9808 5328 9808 5336 9809 5328 9809 5337 9809 5337 9810 5328 9810 5329 9810 5337 9811 5329 9811 5338 9811 5338 9812 5329 9812 5330 9812 5338 9813 5330 9813 5339 9813 5339 9814 5330 9814 5331 9814 5339 9815 5331 9815 5340 9815 5340 9816 5331 9816 5332 9816 5340 9817 5332 9817 5341 9817 5341 9818 5332 9818 5333 9818 5341 9819 5333 9819 5342 9819 5342 9820 5333 9820 5334 9820 5342 9821 5334 9821 5343 9821 5343 9822 5334 9822 3908 9822 5343 9823 3908 9823 3907 9823 5344 9824 3925 9824 5335 9824 5344 9825 5335 9825 5345 9825 5345 9826 5335 9826 5336 9826 5345 9827 5336 9827 5346 9827 5346 9828 5336 9828 5337 9828 5346 9829 5337 9829 5347 9829 5347 9830 5337 9830 5338 9830 5347 9831 5338 9831 5348 9831 5348 9832 5338 9832 5339 9832 5348 9833 5339 9833 5349 9833 5349 9834 5339 9834 5340 9834 5349 9835 5340 9835 5350 9835 5350 9836 5340 9836 5341 9836 5350 9837 5341 9837 5351 9837 5351 9838 5341 9838 5342 9838 5351 9839 5342 9839 5352 9839 5352 9840 5342 9840 5343 9840 5352 9841 5343 9841 5353 9841 5353 9842 5343 9842 3907 9842 5353 9843 3907 9843 3906 9843 5354 9844 5346 9844 5347 9844 5354 9845 5347 9845 5355 9845 5355 9846 5347 9846 5348 9846 5355 9847 5348 9847 5356 9847 5356 9848 5348 9848 5349 9848 5356 9849 5349 9849 5357 9849 5357 9850 5349 9850 5350 9850 5357 9851 5350 9851 5358 9851 5358 9852 5350 9852 5351 9852 5358 9853 5351 9853 5359 9853 5359 9854 5351 9854 5352 9854 5359 9855 5352 9855 5360 9855 5360 9856 5352 9856 5353 9856 5360 9857 5353 9857 5361 9857 5361 9858 5353 9858 3906 9858 5361 9859 3906 9859 3905 9859 5362 9860 5355 9860 5356 9860 5362 9861 5356 9861 5363 9861 5363 9862 5356 9862 5357 9862 5363 9863 5357 9863 5364 9863 5364 9864 5357 9864 5358 9864 5364 9865 5358 9865 5365 9865 5365 9866 5358 9866 5359 9866 5365 9867 5359 9867 5366 9867 5366 9868 5359 9868 5360 9868 5366 9869 5360 9869 5367 9869 5367 9870 5360 9870 5361 9870 5367 9871 5361 9871 5368 9871 5368 9872 5361 9872 3905 9872 5368 9873 3905 9873 3904 9873 5369 9874 5363 9874 5364 9874 5369 9875 5364 9875 5370 9875 5370 9876 5364 9876 5365 9876 5370 9877 5365 9877 5371 9877 5371 9878 5365 9878 5366 9878 5371 9879 5366 9879 5372 9879 5372 9880 5366 9880 5367 9880 5372 9881 5367 9881 5373 9881 5373 9882 5367 9882 5368 9882 5373 9883 5368 9883 5374 9883 5374 9884 5368 9884 3904 9884 5374 9885 3904 9885 3903 9885 5375 9886 5370 9886 5371 9886 5375 9887 5371 9887 5376 9887 5376 9888 5371 9888 5372 9888 5376 9889 5372 9889 5377 9889 5377 9890 5372 9890 5373 9890 5377 9891 5373 9891 5378 9891 5378 9892 5373 9892 5374 9892 5378 9893 5374 9893 5379 9893 5379 9894 5374 9894 3903 9894 5379 9895 3903 9895 3667 9895 3603 9896 3731 9896 5380 9896 3603 9897 5380 9897 5381 9897 5381 9898 5380 9898 5382 9898 5381 9899 5382 9899 5383 9899 5383 9900 5382 9900 5384 9900 5383 9901 5384 9901 5385 9901 5385 9902 5384 9902 5386 9902 5385 9903 5386 9903 5387 9903 5387 9904 5386 9904 5388 9904 5387 9905 5388 9905 5389 9905 5389 9906 5388 9906 5390 9906 5389 9907 5390 9907 5391 9907 5391 9908 5390 9908 5392 9908 5391 9909 5392 9909 5393 9909 5393 9910 5392 9910 5394 9910 5393 9911 5394 9911 5395 9911 5395 9912 5394 9912 5396 9912 5395 9913 5396 9913 5397 9913 5397 9914 5396 9914 3728 9914 5397 9915 3728 9915 3605 9915 3684 9916 3683 9916 5398 9916 3684 9917 5398 9917 5199 9917 5199 9918 5398 9918 5399 9918 5199 9919 5399 9919 5201 9919 5201 9920 5399 9920 5400 9920 5201 9921 5400 9921 5203 9921 5203 9922 5400 9922 5401 9922 5203 9923 5401 9923 5205 9923 5205 9924 5401 9924 5402 9924 5205 9925 5402 9925 5207 9925 5207 9926 5402 9926 5403 9926 5207 9927 5403 9927 5209 9927 5209 9928 5403 9928 5404 9928 5209 9929 5404 9929 5211 9929 5211 9930 5404 9930 5405 9930 5211 9931 5405 9931 5213 9931 5213 9932 5405 9932 5406 9932 5213 9933 5406 9933 5215 9933 5215 9934 5406 9934 3686 9934 5215 9935 3686 9935 3685 9935 5376 9936 5377 9936 5407 9936 5376 9937 5407 9937 5408 9937 5377 9938 5378 9938 5409 9938 5377 9939 5409 9939 5407 9939 5378 9940 5379 9940 5410 9940 5378 9941 5410 9941 5409 9941 5379 9942 3667 9942 3669 9942 5379 9943 3669 9943 5410 9943 3631 9944 5033 9944 3669 9944 3631 9945 3669 9945 3632 9945 5033 9946 5035 9946 5410 9946 5033 9947 5410 9947 3669 9947 5035 9948 5037 9948 5409 9948 5035 9949 5409 9949 5410 9949 5037 9950 5039 9950 5407 9950 5037 9951 5407 9951 5409 9951 5039 9952 5041 9952 5408 9952 5039 9953 5408 9953 5407 9953 3603 9954 5381 9954 5190 9954 3603 9955 5190 9955 3604 9955 5381 9956 5383 9956 5191 9956 5381 9957 5191 9957 5190 9957 5383 9958 5385 9958 5192 9958 5383 9959 5192 9959 5191 9959 5385 9960 5387 9960 5193 9960 5385 9961 5193 9961 5192 9961 5387 9962 5389 9962 5194 9962 5387 9963 5194 9963 5193 9963 5389 9964 5391 9964 5195 9964 5389 9965 5195 9965 5194 9965 5391 9966 5393 9966 5196 9966 5391 9967 5196 9967 5195 9967 5393 9968 5395 9968 5197 9968 5393 9969 5197 9969 5196 9969 5395 9970 5397 9970 5198 9970 5395 9971 5198 9971 5197 9971 5397 9972 3605 9972 3608 9972 5397 9973 3608 9973 5198 9973 5411 9974 5412 9974 5413 9974 5411 9975 5413 9975 5414 9975 5412 9976 5415 9976 5416 9976 5412 9977 5416 9977 5413 9977 5415 9978 5417 9978 5418 9978 5415 9979 5418 9979 5416 9979 5417 9980 5419 9980 5420 9980 5417 9981 5420 9981 5418 9981 5419 9982 5421 9982 5422 9982 5419 9983 5422 9983 5420 9983 5421 9984 4794 9984 3633 9984 5421 9985 3633 9985 5422 9985 5423 9986 5424 9986 5415 9986 5423 9987 5415 9987 5412 9987 5424 9988 5425 9988 5417 9988 5424 9989 5417 9989 5415 9989 5425 9990 5426 9990 5419 9990 5425 9991 5419 9991 5417 9991 5426 9992 5427 9992 5421 9992 5426 9993 5421 9993 5419 9993 5427 9994 4793 9994 4794 9994 5427 9995 4794 9995 5421 9995 5428 9996 5429 9996 5426 9996 5428 9997 5426 9997 5425 9997 5429 9998 5430 9998 5427 9998 5429 9999 5427 9999 5426 9999 5430 10000 4792 10000 4793 10000 5430 10001 4793 10001 5427 10001 5431 10002 5432 10002 5430 10002 5431 10003 5430 10003 5429 10003 5432 10004 4791 10004 4792 10004 5432 10005 4792 10005 5430 10005 5433 10006 5434 10006 5432 10006 5433 10007 5432 10007 5431 10007 5434 10008 4790 10008 4791 10008 5434 10009 4791 10009 5432 10009 5435 10010 5436 10010 5434 10010 5435 10011 5434 10011 5433 10011 5436 10012 4789 10012 4790 10012 5436 10013 4790 10013 5434 10013 5437 10014 4788 10014 4789 10014 5437 10015 4789 10015 5436 10015 4813 10016 5438 10016 5439 10016 4813 10017 5439 10017 4815 10017 5438 10018 5440 10018 5441 10018 5438 10019 5441 10019 5439 10019 4811 10020 5442 10020 5438 10020 4811 10021 5438 10021 4813 10021 5442 10022 5443 10022 5440 10022 5442 10023 5440 10023 5438 10023 5443 10024 5444 10024 5445 10024 5443 10025 5445 10025 5440 10025 5444 10026 5446 10026 5447 10026 5444 10027 5447 10027 5445 10027 5446 10028 5448 10028 5449 10028 5446 10029 5449 10029 5447 10029 4809 10030 5450 10030 5442 10030 4809 10031 5442 10031 4811 10031 5450 10032 5451 10032 5443 10032 5450 10033 5443 10033 5442 10033 5451 10034 5452 10034 5444 10034 5451 10035 5444 10035 5443 10035 5452 10036 5453 10036 5446 10036 5452 10037 5446 10037 5444 10037 5453 10038 5454 10038 5448 10038 5453 10039 5448 10039 5446 10039 5454 10040 5455 10040 5456 10040 5454 10041 5456 10041 5448 10041 5455 10042 5457 10042 5458 10042 5455 10043 5458 10043 5456 10043 4807 10044 5459 10044 5450 10044 4807 10045 5450 10045 4809 10045 5459 10046 5460 10046 5451 10046 5459 10047 5451 10047 5450 10047 5460 10048 5461 10048 5452 10048 5460 10049 5452 10049 5451 10049 5461 10050 5462 10050 5453 10050 5461 10051 5453 10051 5452 10051 5462 10052 5463 10052 5454 10052 5462 10053 5454 10053 5453 10053 5463 10054 5464 10054 5455 10054 5463 10055 5455 10055 5454 10055 5464 10056 5465 10056 5457 10056 5464 10057 5457 10057 5455 10057 5465 10058 5466 10058 5467 10058 5465 10059 5467 10059 5457 10059 4805 10060 5468 10060 5459 10060 4805 10061 5459 10061 4807 10061 5468 10062 5469 10062 5460 10062 5468 10063 5460 10063 5459 10063 5469 10064 5470 10064 5461 10064 5469 10065 5461 10065 5460 10065 5470 10066 5471 10066 5462 10066 5470 10067 5462 10067 5461 10067 5471 10068 5472 10068 5463 10068 5471 10069 5463 10069 5462 10069 5472 10070 5473 10070 5464 10070 5472 10071 5464 10071 5463 10071 5473 10072 5474 10072 5465 10072 5473 10073 5465 10073 5464 10073 5474 10074 5475 10074 5466 10074 5474 10075 5466 10075 5465 10075 5475 10076 5476 10076 5477 10076 5475 10077 5477 10077 5466 10077 4803 10078 5478 10078 5468 10078 4803 10079 5468 10079 4805 10079 5478 10080 5479 10080 5469 10080 5478 10081 5469 10081 5468 10081 5479 10082 5480 10082 5470 10082 5479 10083 5470 10083 5469 10083 5480 10084 5481 10084 5471 10084 5480 10085 5471 10085 5470 10085 5481 10086 5482 10086 5472 10086 5481 10087 5472 10087 5471 10087 5482 10088 5483 10088 5473 10088 5482 10089 5473 10089 5472 10089 5483 10090 5484 10090 5474 10090 5483 10091 5474 10091 5473 10091 5484 10092 5485 10092 5475 10092 5484 10093 5475 10093 5474 10093 5485 10094 5486 10094 5476 10094 5485 10095 5476 10095 5475 10095 4801 10096 5487 10096 5478 10096 4801 10097 5478 10097 4803 10097 5487 10098 5488 10098 5479 10098 5487 10099 5479 10099 5478 10099 5488 10100 5489 10100 5480 10100 5488 10101 5480 10101 5479 10101 5489 10102 5490 10102 5481 10102 5489 10103 5481 10103 5480 10103 5490 10104 5491 10104 5482 10104 5490 10105 5482 10105 5481 10105 5491 10106 5492 10106 5483 10106 5491 10107 5483 10107 5482 10107 5492 10108 5493 10108 5484 10108 5492 10109 5484 10109 5483 10109 5493 10110 5494 10110 5485 10110 5493 10111 5485 10111 5484 10111 5494 10112 5495 10112 5486 10112 5494 10113 5486 10113 5485 10113 4799 10114 5496 10114 5487 10114 4799 10115 5487 10115 4801 10115 5496 10116 5497 10116 5488 10116 5496 10117 5488 10117 5487 10117 5497 10118 5498 10118 5489 10118 5497 10119 5489 10119 5488 10119 5498 10120 5499 10120 5490 10120 5498 10121 5490 10121 5489 10121 5499 10122 5500 10122 5491 10122 5499 10123 5491 10123 5490 10123 5500 10124 5501 10124 5492 10124 5500 10125 5492 10125 5491 10125 5501 10126 5502 10126 5493 10126 5501 10127 5493 10127 5492 10127 5502 10128 5503 10128 5494 10128 5502 10129 5494 10129 5493 10129 4797 10130 5504 10130 5496 10130 4797 10131 5496 10131 4799 10131 5504 10132 5505 10132 5497 10132 5504 10133 5497 10133 5496 10133 5505 10134 5506 10134 5498 10134 5505 10135 5498 10135 5497 10135 5506 10136 5507 10136 5499 10136 5506 10137 5499 10137 5498 10137 5507 10138 5508 10138 5500 10138 5507 10139 5500 10139 5499 10139 5508 10140 5509 10140 5501 10140 5508 10141 5501 10141 5500 10141 5509 10142 5510 10142 5502 10142 5509 10143 5502 10143 5501 10143 5510 10144 5511 10144 5503 10144 5510 10145 5503 10145 5502 10145 4795 10146 5512 10146 5504 10146 4795 10147 5504 10147 4797 10147 5512 10148 5513 10148 5505 10148 5512 10149 5505 10149 5504 10149 5513 10150 5514 10150 5506 10150 5513 10151 5506 10151 5505 10151 5514 10152 5515 10152 5507 10152 5514 10153 5507 10153 5506 10153 5515 10154 5516 10154 5508 10154 5515 10155 5508 10155 5507 10155 5516 10156 5517 10156 5509 10156 5516 10157 5509 10157 5508 10157 5517 10158 5518 10158 5510 10158 5517 10159 5510 10159 5509 10159 5518 10160 5519 10160 5511 10160 5518 10161 5511 10161 5510 10161 3607 10162 5520 10162 5512 10162 3607 10163 5512 10163 4795 10163 5520 10164 5521 10164 5513 10164 5520 10165 5513 10165 5512 10165 5521 10166 5522 10166 5514 10166 5521 10167 5514 10167 5513 10167 5522 10168 5523 10168 5515 10168 5522 10169 5515 10169 5514 10169 5523 10170 5524 10170 5516 10170 5523 10171 5516 10171 5515 10171 5524 10172 5525 10172 5517 10172 5524 10173 5517 10173 5516 10173 5525 10174 5526 10174 5518 10174 5525 10175 5518 10175 5517 10175 5526 10176 5527 10176 5519 10176 5526 10177 5519 10177 5518 10177 3987 10178 3680 10178 5528 10178 3987 10179 5528 10179 5529 10179 5529 10180 5528 10180 5530 10180 5529 10181 5530 10181 5531 10181 5531 10182 5530 10182 5532 10182 5531 10183 5532 10183 5533 10183 5533 10184 5532 10184 5534 10184 5533 10185 5534 10185 5535 10185 5535 10186 5534 10186 5536 10186 5535 10187 5536 10187 5537 10187 5537 10188 5536 10188 5538 10188 5537 10189 5538 10189 5539 10189 5539 10190 5538 10190 5540 10190 5539 10191 5540 10191 5541 10191 5541 10192 5540 10192 5542 10192 5541 10193 5542 10193 5543 10193 5543 10194 5542 10194 5544 10194 5543 10195 5544 10195 5545 10195 5545 10196 5544 10196 3681 10196 5545 10197 3681 10197 3948 10197 3985 10198 3987 10198 5529 10198 3985 10199 5529 10199 5546 10199 5546 10200 5529 10200 5531 10200 5546 10201 5531 10201 5547 10201 5547 10202 5531 10202 5533 10202 5547 10203 5533 10203 5548 10203 5548 10204 5533 10204 5535 10204 5548 10205 5535 10205 5549 10205 5549 10206 5535 10206 5537 10206 5549 10207 5537 10207 5550 10207 5550 10208 5537 10208 5539 10208 5550 10209 5539 10209 5551 10209 5551 10210 5539 10210 5541 10210 5551 10211 5541 10211 5552 10211 5552 10212 5541 10212 5543 10212 5552 10213 5543 10213 5553 10213 5553 10214 5543 10214 5545 10214 5553 10215 5545 10215 5554 10215 5554 10216 5545 10216 3948 10216 5554 10217 3948 10217 3946 10217 3983 10218 3985 10218 5546 10218 3983 10219 5546 10219 5555 10219 5555 10220 5546 10220 5547 10220 5555 10221 5547 10221 5556 10221 5556 10222 5547 10222 5548 10222 5556 10223 5548 10223 5557 10223 5557 10224 5548 10224 5549 10224 5557 10225 5549 10225 5558 10225 5558 10226 5549 10226 5550 10226 5558 10227 5550 10227 5559 10227 5559 10228 5550 10228 5551 10228 5559 10229 5551 10229 5560 10229 5560 10230 5551 10230 5552 10230 5560 10231 5552 10231 5561 10231 5561 10232 5552 10232 5553 10232 5561 10233 5553 10233 5562 10233 5562 10234 5553 10234 5554 10234 5562 10235 5554 10235 5563 10235 5563 10236 5554 10236 3946 10236 5563 10237 3946 10237 3944 10237 3981 10238 3983 10238 5555 10238 3981 10239 5555 10239 5564 10239 5564 10240 5555 10240 5556 10240 5564 10241 5556 10241 5565 10241 5565 10242 5556 10242 5557 10242 5565 10243 5557 10243 5566 10243 5566 10244 5557 10244 5558 10244 5566 10245 5558 10245 5567 10245 5567 10246 5558 10246 5559 10246 5567 10247 5559 10247 5568 10247 5568 10248 5559 10248 5560 10248 5568 10249 5560 10249 5569 10249 5569 10250 5560 10250 5561 10250 5569 10251 5561 10251 5570 10251 5570 10252 5561 10252 5562 10252 5570 10253 5562 10253 5571 10253 5571 10254 5562 10254 5563 10254 5571 10255 5563 10255 5572 10255 5572 10256 5563 10256 3944 10256 5572 10257 3944 10257 3942 10257 3979 10258 3981 10258 5564 10258 3979 10259 5564 10259 5573 10259 5573 10260 5564 10260 5565 10260 5573 10261 5565 10261 5574 10261 5574 10262 5565 10262 5566 10262 5574 10263 5566 10263 5575 10263 5575 10264 5566 10264 5567 10264 5575 10265 5567 10265 5576 10265 5576 10266 5567 10266 5568 10266 5576 10267 5568 10267 5577 10267 5577 10268 5568 10268 5569 10268 5577 10269 5569 10269 5578 10269 5578 10270 5569 10270 5570 10270 5578 10271 5570 10271 5579 10271 5579 10272 5570 10272 5571 10272 5579 10273 5571 10273 5580 10273 5580 10274 5571 10274 5572 10274 5580 10275 5572 10275 5581 10275 5581 10276 5572 10276 3942 10276 5581 10277 3942 10277 3940 10277 3977 10278 3979 10278 5573 10278 3977 10279 5573 10279 5582 10279 5582 10280 5573 10280 5574 10280 5582 10281 5574 10281 5583 10281 5583 10282 5574 10282 5575 10282 5583 10283 5575 10283 5584 10283 5584 10284 5575 10284 5576 10284 5584 10285 5576 10285 5585 10285 5585 10286 5576 10286 5577 10286 5585 10287 5577 10287 5586 10287 5586 10288 5577 10288 5578 10288 5586 10289 5578 10289 5587 10289 5587 10290 5578 10290 5579 10290 5587 10291 5579 10291 5588 10291 5588 10292 5579 10292 5580 10292 5588 10293 5580 10293 5589 10293 5589 10294 5580 10294 5581 10294 5589 10295 5581 10295 5590 10295 5590 10296 5581 10296 3940 10296 5590 10297 3940 10297 3938 10297 3975 10298 3977 10298 5582 10298 3975 10299 5582 10299 5591 10299 5591 10300 5582 10300 5583 10300 5591 10301 5583 10301 5592 10301 5592 10302 5583 10302 5584 10302 5592 10303 5584 10303 5593 10303 5593 10304 5584 10304 5585 10304 5593 10305 5585 10305 5594 10305 5594 10306 5585 10306 5586 10306 5594 10307 5586 10307 5595 10307 5595 10308 5586 10308 5587 10308 5595 10309 5587 10309 5596 10309 5596 10310 5587 10310 5588 10310 5596 10311 5588 10311 5597 10311 5597 10312 5588 10312 5589 10312 5597 10313 5589 10313 5598 10313 5598 10314 5589 10314 5590 10314 5598 10315 5590 10315 5599 10315 5599 10316 5590 10316 3938 10316 5599 10317 3938 10317 3936 10317 3973 10318 3975 10318 5591 10318 3973 10319 5591 10319 5600 10319 5600 10320 5591 10320 5592 10320 5600 10321 5592 10321 5601 10321 5601 10322 5592 10322 5593 10322 5601 10323 5593 10323 5602 10323 5602 10324 5593 10324 5594 10324 5602 10325 5594 10325 5603 10325 5603 10326 5594 10326 5595 10326 5603 10327 5595 10327 5604 10327 5604 10328 5595 10328 5596 10328 5604 10329 5596 10329 5605 10329 5605 10330 5596 10330 5597 10330 5605 10331 5597 10331 5606 10331 5606 10332 5597 10332 5598 10332 5606 10333 5598 10333 5607 10333 5607 10334 5598 10334 5599 10334 5607 10335 5599 10335 5608 10335 5608 10336 5599 10336 3936 10336 5608 10337 3936 10337 3934 10337 3971 10338 3973 10338 5600 10338 3971 10339 5600 10339 5609 10339 5609 10340 5600 10340 5601 10340 5609 10341 5601 10341 5610 10341 5610 10342 5601 10342 5602 10342 5610 10343 5602 10343 5611 10343 5611 10344 5602 10344 5603 10344 5611 10345 5603 10345 5612 10345 5612 10346 5603 10346 5604 10346 5612 10347 5604 10347 5613 10347 5613 10348 5604 10348 5605 10348 5613 10349 5605 10349 5614 10349 5614 10350 5605 10350 5606 10350 5614 10351 5606 10351 5615 10351 5615 10352 5606 10352 5607 10352 5615 10353 5607 10353 5616 10353 5616 10354 5607 10354 5608 10354 5616 10355 5608 10355 5617 10355 5617 10356 5608 10356 3934 10356 5617 10357 3934 10357 3932 10357 3969 10358 3971 10358 5609 10358 3969 10359 5609 10359 5618 10359 5618 10360 5609 10360 5610 10360 5618 10361 5610 10361 5619 10361 5619 10362 5610 10362 5611 10362 5619 10363 5611 10363 5620 10363 5620 10364 5611 10364 5612 10364 5620 10365 5612 10365 5621 10365 5621 10366 5612 10366 5613 10366 5621 10367 5613 10367 5622 10367 5622 10368 5613 10368 5614 10368 5622 10369 5614 10369 5623 10369 5623 10370 5614 10370 5615 10370 5623 10371 5615 10371 5624 10371 5624 10372 5615 10372 5616 10372 5624 10373 5616 10373 5625 10373 5625 10374 5616 10374 5617 10374 5625 10375 5617 10375 5626 10375 5626 10376 5617 10376 3932 10376 5626 10377 3932 10377 3930 10377 3967 10378 3969 10378 5618 10378 3967 10379 5618 10379 5627 10379 5627 10380 5618 10380 5619 10380 5627 10381 5619 10381 5628 10381 5628 10382 5619 10382 5620 10382 5628 10383 5620 10383 5629 10383 5629 10384 5620 10384 5621 10384 5629 10385 5621 10385 5630 10385 5630 10386 5621 10386 5622 10386 5630 10387 5622 10387 5631 10387 5631 10388 5622 10388 5623 10388 5631 10389 5623 10389 5632 10389 5632 10390 5623 10390 5624 10390 5632 10391 5624 10391 5633 10391 5633 10392 5624 10392 5625 10392 5633 10393 5625 10393 5634 10393 5634 10394 5625 10394 5626 10394 5634 10395 5626 10395 5635 10395 5635 10396 5626 10396 3930 10396 5635 10397 3930 10397 3927 10397 3965 10398 3967 10398 5627 10398 3965 10399 5627 10399 5636 10399 5636 10400 5627 10400 5628 10400 5636 10401 5628 10401 5637 10401 5637 10402 5628 10402 5629 10402 5637 10403 5629 10403 5638 10403 5638 10404 5629 10404 5630 10404 5638 10405 5630 10405 5639 10405 5639 10406 5630 10406 5631 10406 5639 10407 5631 10407 5640 10407 5640 10408 5631 10408 5632 10408 5640 10409 5632 10409 5641 10409 5641 10410 5632 10410 5633 10410 5641 10411 5633 10411 5642 10411 5642 10412 5633 10412 5634 10412 5642 10413 5634 10413 5643 10413 5643 10414 5634 10414 5635 10414 5643 10415 5635 10415 5644 10415 5644 10416 5635 10416 3927 10416 5644 10417 3927 10417 3926 10417 3963 10418 3965 10418 5636 10418 3963 10419 5636 10419 5645 10419 5645 10420 5636 10420 5637 10420 5645 10421 5637 10421 5646 10421 5646 10422 5637 10422 5638 10422 5646 10423 5638 10423 5647 10423 5647 10424 5638 10424 5639 10424 5647 10425 5639 10425 5648 10425 5648 10426 5639 10426 5640 10426 5648 10427 5640 10427 5649 10427 5649 10428 5640 10428 5641 10428 5649 10429 5641 10429 5650 10429 5650 10430 5641 10430 5642 10430 5650 10431 5642 10431 5651 10431 5651 10432 5642 10432 5643 10432 5651 10433 5643 10433 5652 10433 3961 10434 3963 10434 5645 10434 3961 10435 5645 10435 5653 10435 5653 10436 5645 10436 5646 10436 5653 10437 5646 10437 5654 10437 5654 10438 5646 10438 5647 10438 5654 10439 5647 10439 5655 10439 5655 10440 5647 10440 5648 10440 5655 10441 5648 10441 5656 10441 5656 10442 5648 10442 5649 10442 5656 10443 5649 10443 5657 10443 5657 10444 5649 10444 5650 10444 5657 10445 5650 10445 5658 10445 5658 10446 5650 10446 5651 10446 5658 10447 5651 10447 5659 10447 3959 10448 3961 10448 5653 10448 3959 10449 5653 10449 5660 10449 5660 10450 5653 10450 5654 10450 5660 10451 5654 10451 5661 10451 5661 10452 5654 10452 5655 10452 5661 10453 5655 10453 5662 10453 5662 10454 5655 10454 5656 10454 5662 10455 5656 10455 5663 10455 5663 10456 5656 10456 5657 10456 5663 10457 5657 10457 5664 10457 3957 10458 3959 10458 5660 10458 3957 10459 5660 10459 5665 10459 5665 10460 5660 10460 5661 10460 5665 10461 5661 10461 5666 10461 5666 10462 5661 10462 5662 10462 5666 10463 5662 10463 5667 10463 3955 10464 3957 10464 5665 10464 3955 10465 5665 10465 5668 10465 5668 10466 5665 10466 5666 10466 5668 10467 5666 10467 5669 10467 3953 10468 3955 10468 5668 10468 3953 10469 5668 10469 5670 10469 5670 10470 5668 10470 5669 10470 5670 10471 5669 10471 5671 10471 3951 10472 3953 10472 5670 10472 3951 10473 5670 10473 5672 10473 5672 10474 5670 10474 5671 10474 5672 10475 5671 10475 5673 10475 3666 10476 3951 10476 5672 10476 3666 10477 5672 10477 5674 10477 5674 10478 5672 10478 5673 10478 5674 10479 5673 10479 5675 10479 5675 10480 5673 10480 5676 10480 5675 10481 5676 10481 5677 10481 3606 10482 3729 10482 5678 10482 3606 10483 5678 10483 5679 10483 5679 10484 5678 10484 5680 10484 5679 10485 5680 10485 5681 10485 5681 10486 5680 10486 5682 10486 5681 10487 5682 10487 5683 10487 5683 10488 5682 10488 5684 10488 5683 10489 5684 10489 5685 10489 5685 10490 5684 10490 5686 10490 5685 10491 5686 10491 5687 10491 5687 10492 5686 10492 5688 10492 5687 10493 5688 10493 5689 10493 5689 10494 5688 10494 5690 10494 5689 10495 5690 10495 5691 10495 3680 10496 3679 10496 5692 10496 3680 10497 5692 10497 5528 10497 5528 10498 5692 10498 5693 10498 5528 10499 5693 10499 5530 10499 5530 10500 5693 10500 5694 10500 5530 10501 5694 10501 5532 10501 5532 10502 5694 10502 5695 10502 5532 10503 5695 10503 5534 10503 5534 10504 5695 10504 5696 10504 5534 10505 5696 10505 5536 10505 5536 10506 5696 10506 5697 10506 5536 10507 5697 10507 5538 10507 5538 10508 5697 10508 5698 10508 5538 10509 5698 10509 5540 10509 5540 10510 5698 10510 5699 10510 5540 10511 5699 10511 5542 10511 5542 10512 5699 10512 5700 10512 5542 10513 5700 10513 5544 10513 5544 10514 5700 10514 3682 10514 5544 10515 3682 10515 3681 10515 3666 10516 5674 10516 3636 10516 3666 10517 3636 10517 3635 10517 5674 10518 5675 10518 5701 10518 5674 10519 5701 10519 3636 10519 5675 10520 5677 10520 5702 10520 5675 10521 5702 10521 5701 10521 5677 10522 5703 10522 5704 10522 5677 10523 5704 10523 5702 10523 5703 10524 5705 10524 5706 10524 5703 10525 5706 10525 5704 10525 5707 10526 5414 10526 5708 10526 5707 10527 5708 10527 5709 10527 5414 10528 5413 10528 5710 10528 5414 10529 5710 10529 5708 10529 5413 10530 5416 10530 5706 10530 5413 10531 5706 10531 5710 10531 5416 10532 5418 10532 5704 10532 5416 10533 5704 10533 5706 10533 5418 10534 5420 10534 5702 10534 5418 10535 5702 10535 5704 10535 5420 10536 5422 10536 5701 10536 5420 10537 5701 10537 5702 10537 5422 10538 3633 10538 3636 10538 5422 10539 3636 10539 5701 10539 3606 10540 5679 10540 5520 10540 3606 10541 5520 10541 3607 10541 5679 10542 5681 10542 5521 10542 5679 10543 5521 10543 5520 10543 5681 10544 5683 10544 5522 10544 5681 10545 5522 10545 5521 10545 5683 10546 5685 10546 5523 10546 5683 10547 5523 10547 5522 10547 5685 10548 5687 10548 5524 10548 5685 10549 5524 10549 5523 10549 5687 10550 5689 10550 5525 10550 5687 10551 5525 10551 5524 10551 5689 10552 5691 10552 5526 10552 5689 10553 5526 10553 5525 10553 5691 10554 5711 10554 5527 10554 5691 10555 5527 10555 5526 10555 4081 10556 4091 10556 4075 10556 4111 10557 4068 10557 4075 10557 4111 10558 4075 10558 4091 10558 4113 10559 4060 10559 4068 10559 4113 10560 4068 10560 4111 10560 4115 10561 4049 10561 4060 10561 4115 10562 4060 10562 4113 10562 5712 10563 5713 10563 4049 10563 5712 10564 4049 10564 5030 10564 4114 10565 4451 10565 4426 10565 4424 10566 4423 10566 4114 10566 4424 10567 4114 10567 4426 10567 4060 10568 4049 10568 4059 10568 4115 10569 4114 10569 4423 10569 5714 10570 5029 10570 5715 10570 5716 10571 5713 10571 4049 10571 4115 10572 4049 10572 5717 10572 4049 10573 5716 10573 5717 10573 4002 10574 4023 10574 4003 10574 5716 10575 5718 10575 5713 10575 5719 10576 5715 10576 5714 10576 5719 10577 5714 10577 5720 10577 4484 10578 4483 10578 4464 10578 4484 10579 4464 10579 4465 10579 4486 10580 4485 10580 4466 10580 4486 10581 4466 10581 4467 10581 4446 10582 4467 10582 4466 10582 4446 10583 4466 10583 4445 10583 4776 10584 5721 10584 5722 10584 4776 10585 5722 10585 3639 10585 4774 10586 5723 10586 5721 10586 4774 10587 5721 10587 4776 10587 4772 10588 5724 10588 5723 10588 4772 10589 5723 10589 4774 10589 4770 10590 5725 10590 5724 10590 4770 10591 5724 10591 4772 10591 4768 10592 5726 10592 5725 10592 4768 10593 5725 10593 4770 10593 4766 10594 5727 10594 5726 10594 4766 10595 5726 10595 4768 10595 4764 10596 5728 10596 5727 10596 4764 10597 5727 10597 4766 10597 4762 10598 5729 10598 5728 10598 4762 10599 5728 10599 4764 10599 4760 10600 5730 10600 5729 10600 4760 10601 5729 10601 4762 10601 4758 10602 5731 10602 5730 10602 4758 10603 5730 10603 4760 10603 4756 10604 5732 10604 5731 10604 4756 10605 5731 10605 4758 10605 4754 10606 5733 10606 5732 10606 4754 10607 5732 10607 4756 10607 4752 10608 5734 10608 5733 10608 4752 10609 5733 10609 4754 10609 4750 10610 5735 10610 5734 10610 4750 10611 5734 10611 4752 10611 4748 10612 5736 10612 5735 10612 4748 10613 5735 10613 4750 10613 4746 10614 5737 10614 5736 10614 4746 10615 5736 10615 4748 10615 4744 10616 5738 10616 5737 10616 4744 10617 5737 10617 4746 10617 4743 10618 5739 10618 5738 10618 4743 10619 5738 10619 4744 10619 5740 10620 5741 10620 5739 10620 5740 10621 5739 10621 4743 10621 5742 10622 5743 10622 5741 10622 5742 10623 5741 10623 5740 10623 5744 10624 5745 10624 4022 10624 5744 10625 4022 10625 4021 10625 5746 10626 5744 10626 4021 10626 5746 10627 4021 10627 4020 10627 5747 10628 5746 10628 4020 10628 5747 10629 4020 10629 4019 10629 5748 10630 5747 10630 4019 10630 5748 10631 4019 10631 4018 10631 5749 10632 5748 10632 4018 10632 5749 10633 4018 10633 4017 10633 5750 10634 5749 10634 4017 10634 5750 10635 4017 10635 4016 10635 5751 10636 5750 10636 4016 10636 5751 10637 4016 10637 4015 10637 5752 10638 5751 10638 4015 10638 5752 10639 4015 10639 4014 10639 5753 10640 5752 10640 4014 10640 5753 10641 4014 10641 4013 10641 5754 10642 5753 10642 4013 10642 5754 10643 4013 10643 4012 10643 5755 10644 5754 10644 4012 10644 5755 10645 4012 10645 4011 10645 5756 10646 5755 10646 4011 10646 5756 10647 4011 10647 4010 10647 5757 10648 5756 10648 4010 10648 5757 10649 4010 10649 4009 10649 5758 10650 5757 10650 4009 10650 5758 10651 4009 10651 4008 10651 5759 10652 5758 10652 4008 10652 5759 10653 4008 10653 3662 10653 5759 10654 3662 10654 3664 10654 5759 10655 3664 10655 5760 10655 3639 10656 5722 10656 3664 10656 3639 10657 3664 10657 3640 10657 4024 10658 4022 10658 4004 10658 5761 10659 5759 10659 5760 10659 5761 10660 5760 10660 3644 10660 5761 10661 5762 10661 5758 10661 5761 10662 5758 10662 5759 10662 5762 10663 5763 10663 5757 10663 5762 10664 5757 10664 5758 10664 5763 10665 5764 10665 5756 10665 5763 10666 5756 10666 5757 10666 5764 10667 5765 10667 5755 10667 5764 10668 5755 10668 5756 10668 5765 10669 5766 10669 5754 10669 5765 10670 5754 10670 5755 10670 5766 10671 5767 10671 5753 10671 5766 10672 5753 10672 5754 10672 5767 10673 5768 10673 5752 10673 5767 10674 5752 10674 5753 10674 5768 10675 5769 10675 5751 10675 5768 10676 5751 10676 5752 10676 5769 10677 5770 10677 5750 10677 5769 10678 5750 10678 5751 10678 5770 10679 5771 10679 5749 10679 5770 10680 5749 10680 5750 10680 5771 10681 5772 10681 5748 10681 5771 10682 5748 10682 5749 10682 5772 10683 5773 10683 5747 10683 5772 10684 5747 10684 5748 10684 5773 10685 5774 10685 5747 10685 5774 10686 5746 10686 5747 10686 5721 10687 5775 10687 5776 10687 5721 10688 5776 10688 5722 10688 5723 10689 5777 10689 5775 10689 5723 10690 5775 10690 5721 10690 5724 10691 5778 10691 5777 10691 5724 10692 5777 10692 5723 10692 5725 10693 5779 10693 5778 10693 5725 10694 5778 10694 5724 10694 5726 10695 5780 10695 5779 10695 5726 10696 5779 10696 5725 10696 5727 10697 5781 10697 5780 10697 5727 10698 5780 10698 5726 10698 5728 10699 5782 10699 5781 10699 5728 10700 5781 10700 5727 10700 5729 10701 5783 10701 5782 10701 5729 10702 5782 10702 5728 10702 5730 10703 5784 10703 5783 10703 5730 10704 5783 10704 5729 10704 5731 10705 5785 10705 5784 10705 5731 10706 5784 10706 5730 10706 5732 10707 5786 10707 5785 10707 5732 10708 5785 10708 5731 10708 5733 10709 5787 10709 5786 10709 5733 10710 5786 10710 5732 10710 5734 10711 5788 10711 5787 10711 5734 10712 5787 10712 5733 10712 5735 10713 5789 10713 5788 10713 5735 10714 5788 10714 5734 10714 5736 10715 5790 10715 5789 10715 5736 10716 5789 10716 5735 10716 5737 10717 5791 10717 5790 10717 5737 10718 5790 10718 5736 10718 5738 10719 5792 10719 5791 10719 5738 10720 5791 10720 5737 10720 5739 10721 5793 10721 5792 10721 5739 10722 5792 10722 5738 10722 5741 10723 5794 10723 5793 10723 5741 10724 5793 10724 5739 10724 5743 10725 5795 10725 5794 10725 5743 10726 5794 10726 5741 10726 5722 10727 5776 10727 5760 10727 5722 10728 5760 10728 3664 10728 4050 10729 5029 10729 5774 10729 4050 10730 5774 10730 5773 10730 4048 10731 4050 10731 5773 10731 4048 10732 5773 10732 5772 10732 4046 10733 4048 10733 5772 10733 4046 10734 5772 10734 5771 10734 4044 10735 4046 10735 5771 10735 4044 10736 5771 10736 5770 10736 4042 10737 4044 10737 5770 10737 4042 10738 5770 10738 5769 10738 4040 10739 4042 10739 5769 10739 4040 10740 5769 10740 5768 10740 4038 10741 4040 10741 5768 10741 4038 10742 5768 10742 5767 10742 4036 10743 4038 10743 5767 10743 4036 10744 5767 10744 5766 10744 4034 10745 4036 10745 5766 10745 4034 10746 5766 10746 5765 10746 4032 10747 4034 10747 5765 10747 4032 10748 5765 10748 5764 10748 4030 10749 4032 10749 5764 10749 4030 10750 5764 10750 5763 10750 4028 10751 4030 10751 5763 10751 4028 10752 5763 10752 5762 10752 3661 10753 4028 10753 5762 10753 3661 10754 5762 10754 5761 10754 3661 10755 5761 10755 3644 10755 3661 10756 3644 10756 3643 10756 5775 10757 4741 10757 3641 10757 5775 10758 3641 10758 5776 10758 5777 10759 4740 10759 4741 10759 5777 10760 4741 10760 5775 10760 5778 10761 4739 10761 4740 10761 5778 10762 4740 10762 5777 10762 5779 10763 4738 10763 4739 10763 5779 10764 4739 10764 5778 10764 5780 10765 4737 10765 4738 10765 5780 10766 4738 10766 5779 10766 5781 10767 4736 10767 4737 10767 5781 10768 4737 10768 5780 10768 5782 10769 4735 10769 4736 10769 5782 10770 4736 10770 5781 10770 5783 10771 4734 10771 4735 10771 5783 10772 4735 10772 5782 10772 5784 10773 4733 10773 4734 10773 5784 10774 4734 10774 5783 10774 5785 10775 4732 10775 4733 10775 5785 10776 4733 10776 5784 10776 5786 10777 4731 10777 4732 10777 5786 10778 4732 10778 5785 10778 5787 10779 4730 10779 4731 10779 5787 10780 4731 10780 5786 10780 5788 10781 4729 10781 4730 10781 5788 10782 4730 10782 5787 10782 5789 10783 4728 10783 4729 10783 5789 10784 4729 10784 5788 10784 5790 10785 4727 10785 4728 10785 5790 10786 4728 10786 5789 10786 5791 10787 4726 10787 4727 10787 5791 10788 4727 10788 5790 10788 5792 10789 4725 10789 4726 10789 5792 10790 4726 10790 5791 10790 5793 10791 4724 10791 4725 10791 5793 10792 4725 10792 5792 10792 5794 10793 4723 10793 4724 10793 5794 10794 4724 10794 5793 10794 5795 10795 4722 10795 4723 10795 5795 10796 4723 10796 5794 10796 5776 10797 3641 10797 3644 10797 5776 10798 3644 10798 5760 10798 4024 10799 5796 10799 4025 10799 5797 10800 5718 10800 5798 10800 5798 10801 5799 10801 5720 10801 5720 10802 5714 10802 5800 10802 5801 10803 5802 10803 5797 10803 5720 10804 5800 10804 5801 10804 5797 10805 5798 10805 5720 10805 5720 10806 5801 10806 5797 10806 5803 10807 5744 10807 5746 10807 5746 10808 5714 10808 5804 10808 5804 4656 5805 4656 5803 4656 5746 10809 5804 10809 5803 10809 5744 10810 5806 10810 5745 10810 5714 10811 5746 10811 5774 10811 5714 10812 5774 10812 5029 10812 4003 10813 4023 10813 4022 10813 4003 10814 4022 10814 4004 10814 4022 10815 5745 10815 5807 10815 5807 10816 5796 10816 4024 10816 5807 10817 4024 10817 4022 10817 3895 10818 3894 10818 3898 10818 5808 10819 3726 10819 5742 10819 5808 10820 5742 10820 5809 10820 3727 10821 3726 10821 5808 10821 5344 10822 5810 10822 5811 10822 5812 10823 3922 10823 3925 10823 3925 10824 5344 10824 5811 10824 3925 10825 5811 10825 5812 10825 5813 10826 5814 10826 5316 10826 5316 10827 3924 10827 3923 10827 5316 10828 3923 10828 5813 10828 3926 10829 3929 10829 5316 10829 5316 10830 5814 10830 5815 10830 5316 10831 5815 10831 3926 10831 4179 10832 4182 10832 4181 10832 4180 10833 4179 10833 4181 10833 4401 10834 4403 10834 4433 10834 4432 10835 4401 10835 4433 10835 5809 10836 5742 10836 5740 10836 5809 10837 5740 10837 5816 10837 5816 10838 5740 10838 4743 10838 4743 10839 4742 10839 5817 10839 4743 10840 5817 10840 5816 10840 5817 10841 4742 10841 5818 10841 5818 10842 4742 10842 4745 10842 5818 10843 4745 10843 5819 10843 5819 10844 4745 10844 4747 10844 5819 10845 4747 10845 5820 10845 5820 10846 4747 10846 4749 10846 5820 10847 4749 10847 5821 10847 5821 10848 4749 10848 4751 10848 5821 10849 4751 10849 5822 10849 5822 10850 4751 10850 4753 10850 5822 10851 4753 10851 5823 10851 5823 10852 4753 10852 4755 10852 5823 10853 4755 10853 5824 10853 5824 10854 4755 10854 4757 10854 5824 10855 4757 10855 5825 10855 5825 10856 4757 10856 4759 10856 5825 10857 4759 10857 5826 10857 5826 10858 4759 10858 4761 10858 4761 10859 4778 10859 5827 10859 4761 10860 5827 10860 5826 10860 5827 10861 4778 10861 5828 10861 5829 10862 5828 10862 4778 10862 4778 10863 4779 10863 4787 10863 4778 10864 4787 10864 5829 10864 5830 10865 4818 10865 4817 10865 5830 10866 4817 10866 5831 10866 5041 10867 5040 10867 5832 10867 5041 10868 5832 10868 5833 10868 5040 10869 5046 10869 5834 10869 5040 10870 5834 10870 5832 10870 5046 10871 5051 10871 5058 10871 5058 10872 5835 10872 5834 10872 5058 10873 5834 10873 5046 10873 5058 10874 5836 10874 5835 10874 5058 10875 5057 10875 5837 10875 5058 10876 5837 10876 5836 10876 5057 10877 5064 10877 5072 10877 5072 10878 5838 10878 5837 10878 5072 10879 5837 10879 5057 10879 5072 10880 5839 10880 5838 10880 5072 10881 5071 10881 5840 10881 5072 10882 5840 10882 5839 10882 5841 10883 5840 10883 5071 10883 5071 10884 5079 10884 5088 10884 5071 10885 5088 10885 5841 10885 5841 10886 5088 10886 5090 10886 5841 10887 5090 10887 5842 10887 5090 10888 5843 10888 5842 10888 5830 10889 5843 10889 5090 10889 5090 10890 5089 10890 4818 10890 5090 10891 4818 10891 5830 10891 5344 10892 5345 10892 5844 10892 5344 10893 5844 10893 5810 10893 5844 10894 5345 10894 5346 10894 5346 10895 5354 10895 5845 10895 5346 10896 5845 10896 5844 10896 5354 10897 5846 10897 5845 10897 5847 10898 5846 10898 5354 10898 5354 10899 5355 10899 5362 10899 5354 10900 5362 10900 5847 10900 5362 10901 5848 10901 5847 10901 5848 10902 5362 10902 5363 10902 5363 10903 5369 10903 5849 10903 5363 10904 5849 10904 5848 10904 5369 10905 5850 10905 5849 10905 5851 10906 5850 10906 5369 10906 5369 10907 5370 10907 5375 10907 5369 10908 5375 10908 5851 10908 5375 10909 5852 10909 5851 10909 5852 10910 5375 10910 5376 10910 5376 10911 5408 10911 5853 10911 5376 10912 5853 10912 5852 10912 5853 10913 5408 10913 5041 10913 5853 10914 5041 10914 5833 10914 5854 10915 5855 10915 5856 10915 5707 10916 5856 10916 5855 10916 5707 10917 5855 10917 5857 10917 5858 10918 5411 10918 5414 10918 5414 10919 5707 10919 5857 10919 5414 10920 5857 10920 5858 10920 5859 10921 5411 10921 5858 10921 5860 10922 5423 10922 5412 10922 5412 10923 5411 10923 5859 10923 5412 10924 5859 10924 5860 10924 5861 10925 5423 10925 5860 10925 5862 10926 5424 10926 5423 10926 5862 10927 5423 10927 5861 10927 5863 10928 5428 10928 5425 10928 5425 10929 5424 10929 5862 10929 5425 10930 5862 10930 5863 10930 5864 10931 5428 10931 5863 10931 5865 10932 5431 10932 5429 10932 5429 10933 5428 10933 5864 10933 5429 10934 5864 10934 5865 10934 5866 10935 5433 10935 5431 10935 5866 10936 5431 10936 5865 10936 5867 10937 5435 10937 5433 10937 5867 10938 5433 10938 5866 10938 5868 10939 5435 10939 5867 10939 5869 10940 5437 10940 5436 10940 5436 10941 5435 10941 5868 10941 5436 10942 5868 10942 5869 10942 4817 10943 5870 10943 5831 10943 5871 10944 5437 10944 5869 10944 5872 10945 4787 10945 4788 10945 4788 10946 5437 10946 5871 10946 4788 10947 5871 10947 5872 10947 5870 10948 4817 10948 4815 10948 4815 10949 5439 10949 5873 10949 4815 10950 5873 10950 5870 10950 5873 10951 5439 10951 5441 10951 5873 10952 5441 10952 5874 10952 5441 10953 5875 10953 5874 10953 5829 10954 4787 10954 5872 10954 5876 10955 5875 10955 5441 10955 5441 10956 5440 10956 5445 10956 5441 10957 5445 10957 5876 10957 5876 10958 5445 10958 5447 10958 5876 10959 5447 10959 5877 10959 5877 10960 5447 10960 5449 10960 5877 10961 5449 10961 5878 10961 5449 4656 5879 4656 5878 4656 5880 10962 5879 10962 5449 10962 5449 10963 5448 10963 5456 10963 5449 10964 5456 10964 5880 10964 5880 10965 5456 10965 5458 10965 5880 10966 5458 10966 5881 10966 5458 10967 5882 10967 5881 10967 5883 10968 5882 10968 5458 10968 5458 10969 5457 10969 5467 10969 5458 10970 5467 10970 5883 10970 5467 10971 5884 10971 5883 10971 5885 10972 5884 10972 5467 10972 5467 10973 5466 10973 5477 10973 5467 10974 5477 10974 5885 10974 5477 10975 5886 10975 5885 10975 5477 10976 5476 10976 5887 10976 5477 10977 5887 10977 5886 10977 5476 10978 5486 10978 5888 10978 5476 10979 5888 10979 5887 10979 5888 10980 5486 10980 5495 10980 5888 10981 5495 10981 5889 10981 5494 10982 5503 10982 5890 10982 5890 10983 5891 10983 5495 10983 5890 10984 5495 10984 5494 10984 5495 10985 5891 10985 5889 10985 5503 10986 5511 10986 5892 10986 5503 10987 5892 10987 5890 10987 5511 10988 5519 10988 5893 10988 5511 10989 5893 10989 5892 10989 5519 10990 5527 10990 5894 10990 5519 10991 5894 10991 5893 10991 5895 10992 5896 10992 5652 10992 5652 10993 5643 10993 5644 10993 5652 10994 5644 10994 5895 10994 5644 10995 3926 10995 5815 10995 5644 10996 5815 10996 5895 10996 5897 10997 5898 10997 5659 10997 5659 10998 5651 10998 5652 10998 5659 10999 5652 10999 5897 10999 5897 11000 5652 11000 5896 11000 3923 11001 5899 11001 5813 11001 5900 11002 5664 11002 5657 11002 5657 11003 5658 11003 5901 11003 5657 11004 5901 11004 5900 11004 5901 11005 5658 11005 5659 11005 5901 11006 5659 11006 5902 11006 5898 11007 5902 11007 5659 11007 3923 11008 3922 11008 5903 11008 3923 11009 5903 11009 5899 11009 5904 11010 5667 11010 5662 11010 5662 11011 5663 11011 5905 11011 5662 11012 5905 11012 5904 11012 5663 11013 5664 11013 5906 11013 5663 11014 5906 11014 5905 11014 5664 11015 5900 11015 5906 11015 3922 11016 5812 11016 5903 11016 5907 11017 5908 11017 5669 11017 5669 11018 5666 11018 5667 11018 5669 11019 5667 11019 5907 11019 5904 11020 5907 11020 5667 11020 5909 11021 5671 11021 5669 11021 5909 11022 5669 11022 5908 11022 5910 11023 5676 11023 5673 11023 5673 11024 5671 11024 5909 11024 5673 11025 5909 11025 5910 11025 5910 11026 5911 11026 5676 11026 5912 11027 5703 11027 5677 11027 5677 11028 5676 11028 5911 11028 5677 11029 5911 11029 5912 11029 5913 11030 5705 11030 5703 11030 5913 11031 5703 11031 5912 11031 5913 11032 5914 11032 5705 11032 5691 11033 5690 11033 5915 11033 5691 11034 5915 11034 5711 11034 5711 11035 5915 11035 5916 11035 5706 11036 5705 11036 5914 11036 5914 11037 5917 11037 5710 11037 5914 11038 5710 11038 5706 11038 5918 11039 5708 11039 5710 11039 5918 11040 5710 11040 5917 11040 5919 11041 5709 11041 5708 11041 5919 11042 5708 11042 5918 11042 5709 11043 5919 11043 5920 11043 5854 11044 5856 11044 5921 11044 5921 11045 5856 11045 5707 11045 5707 11046 5709 11046 5920 11046 5707 11047 5920 11047 5921 11047 5527 11048 5711 11048 5916 11048 5527 11049 5916 11049 5894 11049 4426 11050 4451 11050 4449 11050 4430 11051 4428 11051 4426 11051 4426 11052 4449 11052 4430 11052 4449 11053 4431 11053 4430 11053 5814 11054 5813 11054 5922 11054 5814 11055 5922 11055 5923 11055 5815 11056 5814 11056 5923 11056 5815 11057 5923 11057 5924 11057 5895 11058 5815 11058 5924 11058 5895 11059 5924 11059 5925 11059 5926 11060 5897 11060 5895 11060 5926 11061 5895 11061 5925 11061 5898 11062 5897 11062 5926 11062 5898 11063 5926 11063 5927 11063 5922 11064 3923 11064 5813 11064 5895 11065 5897 11065 5896 11065 5899 11066 5903 11066 5928 11066 5899 11067 5928 11067 5922 11067 5812 64 5811 64 5903 64 5928 11068 5903 11068 5811 11068 5928 11069 5811 11069 5929 11069 5929 11070 5811 11070 5810 11070 5810 11071 5844 11071 5845 11071 5845 11072 5930 11072 5929 11072 5810 11073 5845 11073 5929 11073 5930 11074 5845 11074 5846 11074 5846 11075 5847 11075 5931 11075 5846 11076 5931 11076 5930 11076 5847 64 5848 64 5849 64 5847 11077 5849 11077 5931 11077 5932 11078 5931 11078 5849 11078 5932 11079 5850 11079 5851 11079 5851 11080 5933 11080 5934 11080 5935 11081 5690 11081 5932 11081 5851 11082 5934 11082 5935 11082 5851 11083 5935 11083 5932 11083 5849 11084 5850 11084 5932 11084 5843 11085 5933 11085 5842 11085 5878 11086 5934 11086 5877 11086 5935 11087 5934 11087 5879 11087 5933 11088 5851 11088 5853 11088 5833 11089 5832 11089 5834 11089 5834 11090 5933 11090 5853 11090 5834 11091 5853 11091 5833 11091 5839 11092 5840 11092 5933 11092 5933 11093 5834 11093 5836 11093 5836 11094 5838 11094 5839 11094 5839 11095 5933 11095 5836 11095 5841 11096 5842 11096 5933 11096 5841 11097 5933 11097 5840 11097 5934 11098 5933 11098 5843 11098 5934 11099 5843 11099 5877 11099 5886 11100 5878 11100 5935 11100 5888 64 5889 64 5891 64 5891 64 5890 64 5892 64 5892 11101 5893 11101 5894 11101 5894 11102 5916 11102 5915 11102 5915 11103 5690 11103 5935 11103 5935 11104 5886 11104 5887 11104 5888 64 5891 64 5892 64 5935 11105 5887 11105 5888 11105 5894 11106 5915 11106 5935 11106 5888 11107 5892 11107 5894 11107 5888 11108 5894 11108 5935 11108 5900 583 5901 583 5902 583 5902 11109 5898 11109 5927 11109 5927 11110 5936 11110 5904 11110 5904 583 5905 583 5906 583 5900 583 5902 583 5927 583 5904 11111 5906 11111 5900 11111 5900 11112 5927 11112 5904 11112 5908 583 5904 583 5936 583 5908 583 5936 583 5909 583 5909 583 5936 583 5937 583 5909 11113 5869 11113 5911 11113 5909 11114 5937 11114 5869 11114 5867 11115 5866 11115 5914 11115 5913 583 5912 583 5911 583 5867 11116 5914 11116 5913 11116 5869 583 5868 583 5867 583 5913 583 5911 583 5869 583 5913 11117 5869 11117 5867 11117 5863 583 5862 583 5920 583 5920 583 5919 583 5918 583 5918 583 5917 583 5914 583 5914 11118 5866 11118 5864 11118 5864 583 5863 583 5920 583 5920 11119 5918 11119 5914 11119 5920 583 5914 583 5864 583 5859 583 5858 583 5920 583 5920 11120 5862 11120 5860 11120 5920 11121 5860 11121 5859 11121 5854 583 5920 583 5858 583 5869 583 5937 583 5819 583 5713 11122 5712 11122 5798 11122 5713 11123 5798 11123 5718 11123 5712 11124 5938 11124 5799 11124 5712 11125 5799 11125 5798 11125 5938 11126 5719 11126 5720 11126 5938 11127 5720 11127 5799 11127 5715 11128 5719 11128 5028 11128 5715 11129 5028 11129 5029 11129 5719 11130 5938 11130 5031 11130 5719 11131 5031 11131 5028 11131 5938 11132 5712 11132 5030 11132 5938 11133 5030 11133 5031 11133 5939 11134 5802 11134 5801 11134 5801 11135 5940 11135 5941 11135 5801 11136 5941 11136 5939 11136 5942 11137 5797 11137 5802 11137 5942 11138 5802 11138 5939 11138 5941 11139 5940 11139 5943 11139 5941 11140 5943 11140 5939 11140 5942 11141 5939 11141 5943 11141 5942 11142 5943 11142 5944 11142 5940 11143 5944 11143 5714 11143 5714 11144 5944 11144 5806 11144 5806 11145 5945 11145 5946 11145 5946 11146 5947 11146 5714 11146 5806 11147 5946 11147 5714 11147 5714 11148 5940 11148 5801 11148 5714 11149 5801 11149 5800 11149 5744 11150 5806 11150 5948 11150 5806 11151 5949 11151 5948 11151 5949 11152 5950 11152 5948 11152 5950 11153 5951 11153 5948 11153 5951 11154 5714 11154 5948 11154 5714 11155 5804 11155 5948 11155 5804 11156 5805 11156 5948 11156 5805 11157 5803 11157 5948 11157 5803 11158 5744 11158 5948 11158 5806 11159 5745 11159 5952 11159 5806 11160 5952 11160 5953 11160 5714 11161 5948 11161 5954 11161 5714 11162 5954 11162 5955 11162 5956 11163 5953 11163 5954 11163 5953 11164 5806 11164 5948 11164 5953 11165 5948 11165 5954 11165

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/palm/palm_E2M3.dae b/URDFs/sr_description/meshes/components/palm/palm_E2M3.dae new file mode 100644 index 0000000..09dad6d --- /dev/null +++ b/URDFs/sr_description/meshes/components/palm/palm_E2M3.dae @@ -0,0 +1,143 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_decimate-ready.blend + + 2012-07-23T02:03:42.155704 + 2012-07-23T02:03:42.155716 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.78691 9.19201 96.43330 -3.92405 9.96326 98.56781 -2.62062 9.46742 96.43924 -5.43032 9.80370 99.67536 -4.79349 9.69696 99.05482 -4.19838 9.56087 98.36475 -3.70107 9.41038 97.67665 -3.29574 9.25230 97.00842 -2.77315 8.93963 95.81378 -5.28283 10.68463 99.70127 -4.62052 10.57362 99.05590 -4.00144 10.43204 98.33804 -3.48421 10.27552 97.62236 -4.60233 11.04699 97.44498 -3.06268 10.11112 96.92741 -4.25756 11.04698 96.20253 -2.72672 9.94482 96.26660 -2.72672 9.95522 93.81953 -2.72672 10.02494 95.04327 -4.15142 11.04698 95.04391 -4.22323 11.04697 94.01063 -2.86901 5.74386 90.32433 -4.62794 7.94142 90.84270 -4.18119 7.94142 91.62482 -3.86182 7.94142 92.36639 -3.64156 7.94142 93.06497 -2.86899 7.19214 93.23296 -1.99944 7.30184 92.42417 -1.99944 6.94656 91.57980 -1.99944 6.38827 90.62457 -1.99944 8.25571 93.05316 -1.99944 7.51917 93.15262 -2.00608 8.38057 93.92613 -2.01864 8.65396 94.05002 -2.00608 7.87464 93.62244 -4.49718 11.01932 91.70681 -4.65287 11.17864 92.90418 -5.12373 11.27726 91.90456 -2.62016 8.73646 95.12651 -3.42962 8.64119 95.29340 -2.44319 8.56278 94.71519 -3.05339 8.50667 94.93190 -2.66969 8.34255 94.60554 -2.07694 8.79775 92.93053 -2.19144 9.32990 94.73645 -2.05462 8.88449 94.20363 -2.24790 9.44767 94.97076 -2.19861 9.23126 95.04590 -2.19702 7.58718 93.89459 -2.32404 7.07942 93.26062 -2.31886 5.63812 90.39952 -3.27289 7.83903 94.26450 -2.40430 8.83116 95.13353 -2.22730 8.65637 94.63448 -2.25253 9.00930 95.10451 -2.62331 7.53031 93.96103 -2.30936 8.16196 94.33179 -2.00608 8.32860 93.39331 -3.50552 7.94157 93.72603 -6.26160 11.17530 88.88427 -9.96445 8.49697 87.00079 -4.23845 5.63631 88.40635 -1.99944 7.99697 92.17238 -2.07130 8.64962 92.46509 -2.25794 9.21523 92.83736 -2.50042 9.65676 93.29486 -3.31068 10.47650 94.44254 -3.48535 10.58686 93.59962 -3.71003 10.70574 92.56482 -3.96819 10.81415 91.43005 -4.23984 10.89921 90.28439 -13.13533 10.99697 85.43847 -10.99945 10.99697 85.20283 -8.86359 10.99697 85.43846 -6.83064 10.99697 86.13393 -4.99944 10.99697 87.25483 -17.23631 10.98760 88.17897 -4.76363 10.98769 88.17481 -4.50802 10.95645 89.19074 -18.41133 1.43357 87.00079 -19.12988 1.27291 87.70229 -19.12988 -0.00303 87.59161 -18.84514 -0.00303 87.29073 -18.54927 -0.00303 87.00079 -19.12988 2.37195 87.98257 -18.00349 2.81535 87.00079 -17.34730 4.08411 87.00079 -16.49944 5.99697 87.00079 -15.99944 6.96932 88.11702 -12.03442 8.49697 87.00079 -8.57618 7.14735 87.00079 -9.94944 7.94142 87.46532 -9.94944 7.47344 87.00079 -8.39124 7.94142 87.85355 -7.30655 6.58200 87.00080 -6.12860 5.76542 87.00080 -4.06877 2.91600 87.00080 -5.04713 4.64133 87.00080 -3.63364 1.65375 87.00080 -3.44961 -0.00303 87.00080 -3.15375 -0.00303 87.29074 -2.86901 -0.00303 87.59161 -2.86901 1.27350 87.70241 -2.86901 2.37288 87.98289 -2.86901 3.31200 88.37459 -15.99944 8.49697 87.00079 -19.99944 -0.00303 87.25483 -19.99944 1.33074 87.37052 -19.99944 2.47985 87.66354 -1.99944 -8.00303 87.25484 -1.99944 -0.00303 87.25484 -1.99944 4.28706 88.55138 -10.99994 11.39697 88.27529 -19.56388 -0.00303 87.75066 -19.94282 -0.00303 87.48594 -19.78578 -0.00303 87.66471 -19.32740 -0.00303 87.72430 -2.21310 -0.00303 87.66472 -2.05606 -0.00303 87.48595 -2.31886 3.11933 88.42470 -2.67149 -0.00303 87.72430 -2.43500 -0.00303 87.75066 -13.76685 -11.00303 83.83875 -10.99943 -11.00303 83.54883 -8.23170 -11.00303 83.83883 -6.57136 -11.00303 84.38750 -4.99944 -11.00303 85.19009 -19.72185 -9.24094 87.00952 -19.02166 -10.21902 86.44582 -2.27803 -9.24322 87.00867 -2.97677 -10.21861 86.44615 -3.91117 -10.77342 85.81319 -19.12987 -8.00303 87.59161 -18.90861 -9.03460 87.35694 -18.36907 -9.82743 86.83522 -18.54927 -4.00303 87.00080 -17.61403 -10.30840 86.21866 -16.91593 -4.00303 85.72745 -16.73857 -10.50303 85.61664 -15.61810 -10.50303 85.01742 -15.88833 -9.00303 85.14693 -15.52103 -9.48780 84.97308 -15.88833 -6.00303 85.14693 -15.41294 -5.67444 84.92504 -15.07323 -5.46536 84.78296 -15.06578 -4.00303 84.77999 -14.74852 -5.29607 84.65945 -15.04330 -10.02226 84.77108 -14.44095 -10.49866 84.55418 -14.27803 -5.11393 84.50076 -13.56440 -5.00303 84.30403 -13.06992 -4.00303 84.19742 -11.86180 -5.00303 84.03466 -10.99943 -4.00303 84.00080 -10.13707 -5.00303 84.03466 -8.92895 -4.00303 84.19742 -8.43447 -5.00303 84.30403 -7.75159 -5.10488 84.49121 -7.14236 -5.34857 84.69920 -6.93310 -4.00303 84.77999 -6.60089 -5.66467 84.91850 -6.38052 -10.50303 85.01753 -6.11055 -9.00303 85.14693 -5.26031 -10.50303 85.61664 -6.11055 -6.00303 85.14693 -5.08295 -4.00303 85.72745 -4.31402 -10.50130 86.22202 -3.64806 -9.84937 86.81806 -3.44961 -4.00303 87.00080 -3.09106 -9.03650 87.35612 -2.86901 -8.00303 87.59161 -13.03604 -5.00303 84.67027 -8.96283 -5.00303 84.67027 -12.59840 -5.00303 85.13993 -9.40047 -5.00303 85.13993 -12.27033 -5.00303 85.69276 -9.72854 -5.00303 85.69276 -12.06769 -5.00303 86.30224 -9.93118 -5.00303 86.30224 -10.99943 -10.00303 85.00080 -12.66555 -10.00303 85.05358 -10.99943 -10.00303 85.40250 -12.38011 -10.00303 85.47595 -10.99943 -10.00303 85.74326 -12.17045 -10.00303 85.94012 -10.99943 -10.00303 86.01086 -9.95637 -10.00303 86.43204 -12.04251 -10.00303 86.43199 -6.58866 -6.00303 84.98119 -6.58878 -9.00303 84.98116 -7.09450 -6.00303 84.94080 -7.09457 -9.00303 84.94081 -7.59312 -6.00303 85.02869 -7.59319 -9.00303 85.02872 -8.05351 -6.00303 85.23886 -8.05357 -9.00303 85.23889 -8.44640 -6.00303 85.55786 -8.44646 -9.00303 85.55791 -8.74675 -6.00303 85.96545 -8.74683 -9.00303 85.96560 -8.93540 -6.00303 86.43652 -8.93547 -9.00303 86.43675 -15.41021 -9.00303 84.98119 -15.41021 -6.00303 84.98119 -14.90438 -9.00303 84.94080 -14.90438 -6.00303 84.94080 -14.40575 -9.00303 85.02869 -14.40575 -6.00303 85.02869 -13.94536 -9.00303 85.23886 -13.94536 -6.00303 85.23886 -13.55247 -9.00303 85.55786 -13.55247 -6.00303 85.55786 -13.25213 -9.00303 85.96545 -13.25213 -6.00303 85.96545 -13.06347 -9.00303 86.43652 -13.06347 -6.00303 86.43652 -13.71113 -5.29592 85.04181 -12.97319 -5.29592 85.86537 -7.25136 -5.30497 84.66199 -8.28282 -5.29592 85.03847 -9.02428 -5.29592 85.86275 -15.20861 -9.24626 84.91932 -14.45941 -9.51198 84.86862 -13.92234 -9.70494 84.92410 -13.03527 -9.71013 85.75558 -12.97082 -9.98200 85.01439 -13.25342 -9.92569 84.99265 -13.52180 -9.84500 84.97118 -19.32739 -8.00303 87.72430 -19.56388 -8.00303 87.75066 -19.78578 -8.00303 87.66472 -19.94282 -8.00303 87.48595 -2.67151 -8.00302 87.72429 -2.43502 -8.00302 87.75067 -2.21312 -8.00302 87.66473 -2.05606 -8.00302 87.48595 -5.22536 -10.75303 85.55949 -3.52903 -9.98157 86.87932 -2.86596 -9.19326 87.46947 -4.23798 -10.62444 86.18590 -3.30825 -10.17120 86.83067 -2.61141 -9.29184 87.43205 -5.13856 -10.91940 85.41756 -3.15324 -10.23448 86.72431 -4.00331 -10.79866 85.96618 -2.31082 -9.29155 87.14125 -16.86900 -10.93604 85.40337 -14.52264 -10.85658 84.42581 -12.04944 -10.85241 83.89981 -10.99943 -10.66970 84.02230 -13.47455 -10.61703 84.28741 -10.99943 -10.97928 83.70176 -9.94944 -10.85241 83.89981 -7.47623 -10.85658 84.42581 -19.08425 -9.16383 87.46036 -16.78412 -10.77336 85.54215 -17.71125 -10.54603 86.21458 -18.57539 -10.08604 86.87474 -19.28141 -9.25626 87.46587 -17.83893 -10.70810 86.13063 -18.75820 -10.20360 86.79390 -19.46508 -9.30571 87.39326 -16.98495 -10.99559 85.21379 -17.99289 -10.79692 85.97325 -18.92981 -10.24095 86.64246 -19.63477 -9.30826 87.23492 -10.99943 -10.04902 84.66844 -10.99943 -10.18686 84.38903 -10.99943 -10.40319 84.16565 -12.78643 -10.32127 84.33206 -12.73147 -10.17210 84.66017 -9.26630 -10.17210 84.66017 -9.21134 -10.32127 84.33206 -8.52322 -10.61703 84.28741 -8.47597 -9.84500 84.97118 -8.74434 -9.92569 84.99265 -9.02695 -9.98200 85.01439 -8.96250 -9.71013 85.75558 -8.07543 -9.70494 84.92410 -7.53835 -9.51198 84.86862 -6.78915 -9.24626 84.91932 -9.82731 -10.00303 85.94012 -9.61765 -10.00303 85.47595 -9.33221 -10.00303 85.05358 -7.55681 -10.49866 84.55418 -6.95446 -10.02226 84.77108 -6.47673 -9.48780 84.97308 -9.99943 -5.00303 86.93854 -11.99943 -5.00303 93.26875 -9.99943 -5.00303 93.26875 -9.76705 -5.00303 94.09372 -11.22196 -5.00303 94.02587 -10.77691 -5.00303 94.02587 -11.62292 -5.00303 94.21896 -10.37594 -5.00303 94.21896 -12.36546 -5.07242 94.00080 -11.90040 -5.00303 94.56692 -10.09847 -5.00303 94.56692 -12.16913 -5.00303 94.92145 -9.82974 -5.00303 94.92146 -11.99943 -5.00303 95.00080 -9.99943 -5.00303 95.00080 -9.91382 -5.00303 95.44342 -12.07844 -5.00303 95.45930 -10.13171 -5.00303 95.49785 -11.86516 -5.00303 95.50132 -10.49671 -5.00303 95.86525 -10.23375 -5.00303 95.88861 -11.75377 -5.00303 95.89827 -11.49825 -5.00303 95.86751 -10.99721 -5.00303 96.00079 -10.71798 -5.00303 96.13889 -11.26470 -5.00303 96.14278 -8.99906 -6.00303 94.00079 -8.99943 -9.00303 86.93854 -8.99943 -9.00303 94.00080 -11.99943 -10.00303 86.93854 -9.99943 -10.00303 94.00080 -11.99943 -10.00303 94.00080 -12.99944 -9.00303 94.00080 -12.99944 -6.00303 93.96098 -12.99944 -6.00303 86.93854 -12.38214 -5.07915 86.93854 -12.69802 -5.28750 94.00080 -12.70656 -5.29593 86.93854 -12.92101 -5.61481 94.00080 -12.99450 -6.00303 94.14118 -9.56780 -5.11040 94.23586 -9.61675 -5.07915 86.93854 -9.30086 -5.28749 94.00080 -9.29233 -5.29592 86.93854 -9.07786 -5.61481 94.00080 -9.07556 -5.62034 86.93854 -9.13342 -9.50305 94.00080 -9.29233 -9.71013 86.93854 -9.49946 -9.86907 94.00080 -9.61675 -9.92691 86.93854 -12.49944 -9.86905 94.00080 -12.70654 -9.71013 86.93854 -12.86546 -9.50303 94.00080 -12.92332 -9.38571 86.93854 -10.99943 -5.00303 95.00080 -12.73674 -5.33823 94.18478 -12.92749 -5.64578 94.15256 -9.26214 -5.33822 94.18479 -9.07139 -5.64578 94.15256 -9.72595 -5.02203 94.50558 -12.81211 -5.27567 95.41162 -13.10184 -5.94570 95.54117 -12.15939 -5.27567 96.45306 -12.32968 -5.94570 96.71619 -10.99944 -5.94570 97.17154 -10.99944 -5.27567 96.85945 -9.66919 -5.94570 96.71619 -9.83949 -5.27567 96.45306 -8.89703 -5.94570 95.54117 -9.18676 -5.27567 95.41162 -11.99943 -10.00303 95.50080 -9.99943 -10.00303 95.50080 -8.89703 -8.94570 95.54117 -13.10184 -8.94570 95.54117 -12.32968 -8.94570 96.71619 -10.99944 -8.94570 97.17154 -9.66919 -8.94570 96.71619 -17.75948 10.89910 90.28619 -17.49210 10.95624 89.19573 -17.95351 10.83841 91.10439 -18.28336 10.70835 92.54009 -18.50646 10.59098 93.56621 -19.04420 10.19218 94.41814 -18.68239 10.48045 94.41386 -19.27217 9.95521 93.81952 -19.74095 9.21523 92.83735 -19.99944 7.99697 92.17237 -18.66365 4.10292 88.26276 -19.12988 4.09936 88.83099 -17.84210 6.16047 88.98504 -19.12988 5.29650 89.82285 -15.99944 7.74294 89.00079 -15.99944 8.49697 89.00079 -19.99944 4.28585 88.55056 -19.99944 5.53739 89.58749 -19.99944 7.42452 92.80273 -15.73728 11.26217 88.88427 -15.11795 11.39697 89.68382 -19.68002 5.63813 90.39954 -19.68002 3.11935 88.42470 -16.49944 8.49697 92.08532 -16.49944 7.94142 89.74381 -11.99943 -5.00303 86.93854 -8.99943 -6.00303 86.93854 -9.99943 -10.00303 86.93854 -12.99944 -9.00303 86.93854 -12.92332 -5.62036 86.93854 -9.07556 -9.38571 86.93854 -12.38212 -9.92691 86.93854 -18.73264 7.83903 94.26450 -14.28900 9.10507 98.62046 -13.78540 11.49697 99.47164 -18.07484 9.96326 98.56780 -16.28111 10.27446 100.34765 -19.40844 9.57200 96.42619 -19.38140 9.77928 96.36005 -19.77822 8.65637 94.63448 -19.75300 9.00930 95.10450 -19.80692 9.23126 95.04589 -19.80851 7.58718 93.89458 -19.85573 8.20532 94.23191 -19.56388 7.03771 93.27090 -19.82544 9.29202 94.66216 -19.75098 9.44767 94.97076 -19.62539 9.63634 95.45103 -19.45986 9.80788 95.89677 -19.38222 7.53031 93.96102 -19.55777 8.55985 94.71039 -18.56921 8.64121 95.29345 -19.32961 8.34236 94.60520 -19.69616 8.16196 94.33179 -13.54441 9.65113 100.62135 -14.33799 9.49194 99.77038 -16.96824 9.74083 99.29839 -15.84827 9.88731 100.26470 -14.17510 8.69990 97.51351 -17.92096 8.54095 95.21242 -18.21762 9.43370 97.78474 -19.38537 8.73646 95.12650 -19.02626 9.09237 96.37290 -14.73763 11.49697 98.71239 -15.48995 11.49697 97.75495 -16.00270 11.49697 96.64925 -16.24766 11.49697 95.45495 -16.21191 11.49697 94.23913 -16.02825 11.49697 93.17276 -15.79537 11.49697 92.22712 -15.49461 11.49697 91.41562 -15.11051 11.49697 90.76318 -14.86599 9.95133 100.91682 -16.87505 11.27728 91.90439 -17.34590 11.17867 92.90395 -16.34875 11.34554 91.02052 -17.50171 11.01932 91.70683 -19.95091 8.88449 94.20363 -19.99944 7.87464 93.62243 -19.99944 8.32860 93.39330 -17.37778 8.49544 94.56344 -19.12988 6.30681 91.12612 -19.12990 7.19214 93.23295 -17.93302 7.94142 91.86849 -17.58020 7.94142 91.18249 -17.11091 7.94142 90.46915 -17.77565 11.08882 94.01063 -19.27217 10.01127 94.47569 -19.27217 10.00166 95.68507 -19.27217 10.02460 95.09306 -17.84745 11.04698 95.04556 -19.27217 9.94482 96.26659 -17.74075 11.04698 96.20577 -18.64199 10.22999 97.42496 -18.22036 10.36962 98.04487 -17.39480 11.04699 97.44958 -17.71625 10.50161 98.68006 -16.75669 11.04699 98.70905 -16.53280 10.70933 99.86160 -15.96703 10.77157 100.31409 -15.80674 11.04699 99.87800 -14.94548 10.83814 100.99229 -14.60171 11.04698 100.82497 -4.08456 8.54095 95.21242 -5.75123 11.49697 95.45495 -6.88885 11.49697 90.76254 -6.50431 11.49697 91.41553 -6.20346 11.49697 92.22728 -5.97059 11.49697 93.17297 -5.78696 11.49697 94.23913 -7.35129 11.49697 90.29107 -8.26082 11.49697 89.71020 -9.30060 11.49697 89.29076 -10.99943 11.49697 95.12437 -10.99943 11.49528 88.98592 -8.09143 11.39697 88.93648 -5.65019 11.34554 91.02040 -6.88093 11.39697 89.68382 -10.99944 8.49697 95.00079 -9.94944 8.49697 88.86504 -4.41073 8.49697 95.04091 -4.62775 8.49544 94.56345 -4.86253 8.49697 93.95770 -4.97702 8.49697 93.42587 -5.15264 8.49697 92.86423 -5.40616 8.49697 92.26855 -5.75942 8.49697 91.64041 -6.23881 8.49697 90.99002 -6.87369 8.49697 90.33944 -7.69372 8.49697 89.72611 -8.71850 8.49697 89.20879 -10.99944 8.55728 98.13480 -5.23617 7.94142 90.03386 -6.04362 7.94142 89.22797 -5.23870 11.04699 98.70362 -6.18704 11.04698 99.87298 -5.90890 10.75973 100.22089 -7.39114 11.04698 100.82124 -7.00228 10.83605 100.96210 -8.76036 11.04697 101.47259 -8.42268 10.85606 101.66717 -8.95340 10.85606 101.84870 -10.23691 11.04697 101.80639 -10.17666 10.85606 102.10032 -11.75499 11.04697 101.80717 -11.46010 10.85606 102.13297 -8.98314 9.96856 101.74918 -8.45173 9.65113 100.62135 -9.69498 9.65113 101.03237 -10.18862 9.96856 101.99714 -12.05994 9.96856 101.96366 -10.99948 9.65113 101.17181 -6.50894 11.49697 97.75497 -5.99619 11.49697 96.64927 -7.26126 11.49697 98.71239 -8.21348 11.49697 99.47164 -6.03239 9.87593 100.17509 -7.70988 9.10508 98.62046 -7.66148 9.49238 99.77200 -7.55751 9.96396 101.15311 -7.89038 10.38170 101.66822 -9.93147 10.38028 102.29176 -12.06741 10.38028 102.29176 -5.71777 10.27446 100.34765 -10.99944 11.48797 100.50080 -8.72876 11.48797 100.01020 -9.86098 11.48797 100.37675 -7.08771 7.94142 88.47514 -13.90792 11.39697 88.93671 -12.50619 11.39697 88.44625 -9.49355 11.39697 88.44605 -12.69840 11.49697 89.29080 -13.73816 11.49697 89.71024 -12.16097 11.48797 100.37675 -13.27012 11.48797 100.01020 -14.10851 10.38170 101.66822 -14.64758 11.49697 90.29107 -13.59535 9.96856 101.54812 -12.30398 9.65113 101.03236 -13.63363 10.85606 101.64468 -12.65105 10.85606 101.95438 -13.23189 11.04697 101.47488 19.21309 9.19201 100.43330 18.07596 9.96326 102.56781 19.37938 9.46742 100.43924 16.56968 9.80370 103.67536 17.20651 9.69696 103.05482 17.80162 9.56087 102.36475 18.29893 9.41038 101.67665 18.70426 9.25230 101.00842 19.22685 8.93964 99.81378 16.71717 10.68463 103.70127 17.37948 10.57362 103.05590 17.99856 10.43204 102.33804 18.51579 10.27552 101.62236 17.39767 11.04699 101.44498 18.93732 10.11113 100.92741 17.74244 11.04698 100.20253 19.27328 9.94482 100.26660 19.27329 10.02495 99.04327 17.84858 11.04698 99.04391 17.77677 11.04697 98.01063 19.13099 5.74386 94.32433 17.37206 7.94142 94.84270 17.81881 7.94142 95.62482 18.13819 7.94142 96.36639 18.35844 7.94142 97.06497 19.13101 7.19214 97.23296 20.00056 7.42460 96.80299 20.00056 6.94656 95.57980 20.00056 6.38827 94.62457 20.00056 8.25571 97.05316 20.00056 7.58539 97.30751 19.99392 8.38057 97.92613 17.50282 11.01933 95.70681 17.34713 11.17865 96.90418 16.87627 11.27726 95.90456 19.37984 8.73646 99.12651 18.57038 8.64119 99.29340 19.55681 8.56278 98.71519 18.94661 8.50667 98.93190 19.33031 8.34255 98.60554 19.92306 8.79775 96.93053 19.80856 9.32990 98.73645 19.94539 8.88449 98.20363 19.75210 9.44767 98.97076 19.80139 9.23127 99.04590 19.99392 7.87464 97.62244 19.80298 7.58718 97.89459 19.67596 7.07942 97.26062 19.68114 5.63812 94.39952 18.72711 7.83903 98.26450 19.59571 8.83116 99.13353 19.77270 8.65637 98.63448 19.74747 9.00930 99.10451 19.37669 7.53031 97.96103 19.69064 8.16196 98.33179 19.99392 8.32860 97.39331 18.49448 7.94157 97.72603 15.73840 11.17530 92.88427 12.03555 8.49697 91.00079 17.76155 5.63631 92.40635 18.03181 10.81416 95.43005 17.76016 10.89921 94.28439 6.83172 10.99697 90.13396 8.86467 10.99697 89.43847 13.13641 10.99697 89.43846 15.16936 10.99697 90.13393 17.00056 10.99697 91.25483 4.76370 10.98760 92.17897 17.23637 10.98769 92.17481 17.49198 10.95645 93.19074 3.58867 1.43357 91.00079 2.87013 1.27291 91.70229 2.87013 -0.00303 91.59161 3.15487 -0.00303 91.29073 3.45073 -0.00303 91.00079 2.87013 2.37195 91.98257 3.99651 2.81535 91.00079 4.65271 4.08412 91.00079 5.50056 5.99697 91.00079 6.00056 6.96932 92.11702 9.96558 8.49697 91.00079 13.42382 7.14735 91.00079 12.05057 7.94142 91.46532 12.05057 7.47344 91.00079 13.60876 7.94142 91.85355 14.69345 6.58200 91.00080 15.99923 5.63255 91.00080 17.93123 2.91600 91.00080 16.95287 4.64133 91.00080 18.36637 1.65375 91.00080 18.55039 -0.00303 91.00080 18.84625 -0.00303 91.29074 19.13099 -0.00303 91.59161 19.13099 1.27351 91.70241 19.13099 2.37288 91.98289 19.13099 3.31200 92.37459 6.00056 8.49697 91.00079 2.00056 2.47986 91.66354 11.00006 11.39697 92.27529 2.32517 -0.00303 91.70768 2.05718 -0.00303 91.48594 2.21422 -0.00303 91.66471 2.43612 -0.00303 91.75066 2.67261 -0.00303 91.72430 19.78690 -0.00303 91.66472 19.94394 -0.00303 91.48595 19.68114 3.11933 92.42470 19.32852 -0.00303 91.72430 19.56500 -0.00303 91.75066 15.42864 -11.00303 88.38750 17.00056 -11.00303 89.19009 19.72198 -9.24321 91.00867 19.02323 -10.21861 90.44615 18.08883 -10.77341 89.81319 17.73979 -10.91053 89.59454 2.87013 -8.00303 91.59161 3.09140 -9.03460 91.35694 3.63093 -9.82743 90.83522 3.45073 -4.00303 91.00080 4.38597 -10.30840 90.21866 5.08407 -4.00303 89.72745 5.26143 -10.50303 89.61664 6.38190 -10.50303 89.01742 6.11167 -9.00303 89.14693 6.47897 -9.48780 88.97308 6.11167 -6.00303 89.14693 6.58706 -5.67444 88.92504 6.92677 -5.46536 88.78296 6.93422 -4.00303 88.77999 7.25148 -5.29607 88.65945 6.95670 -10.02226 88.77108 7.55905 -10.49866 88.55418 7.72198 -5.11393 88.50076 8.43560 -5.00303 88.30403 8.93008 -4.00303 88.19742 10.13820 -5.00303 88.03466 11.00057 -4.00303 88.00080 11.86293 -5.00303 88.03466 13.07105 -4.00303 88.19742 13.56553 -5.00303 88.30403 14.24841 -5.10488 88.49121 14.85765 -5.34857 88.69920 15.06690 -4.00303 88.77999 15.39911 -5.66467 88.91850 15.61948 -10.50303 89.01753 15.88945 -9.00303 89.14693 16.73969 -10.50303 89.61664 15.88945 -6.00303 89.14693 16.91706 -4.00303 89.72745 17.68598 -10.50130 90.22202 18.35194 -9.84937 90.81806 18.55039 -4.00303 91.00080 18.90894 -9.03650 91.35612 19.13099 -8.00303 91.59161 8.96396 -5.00303 88.67027 13.03717 -5.00303 88.67027 9.40160 -5.00303 89.13993 12.59953 -5.00303 89.13993 9.72967 -5.00303 89.69276 12.27146 -5.00303 89.69276 9.93231 -5.00303 90.30224 12.06882 -5.00303 90.30224 11.00057 -10.00303 89.00080 9.33445 -10.00303 89.05358 11.00057 -10.00303 89.40250 9.61989 -10.00303 89.47595 11.00057 -10.00303 89.74326 9.82955 -10.00303 89.94012 11.00057 -10.00303 90.01086 12.04364 -10.00303 90.43204 9.95749 -10.00303 90.43199 15.41134 -6.00303 88.98119 15.41122 -9.00303 88.98116 14.90550 -6.00303 88.94080 14.90544 -9.00303 88.94081 14.40688 -6.00303 89.02869 14.40681 -9.00303 89.02872 13.94649 -6.00303 89.23886 13.94644 -9.00303 89.23889 13.55360 -6.00303 89.55786 13.55354 -9.00303 89.55791 13.25326 -6.00303 89.96545 13.25317 -9.00303 89.96560 13.06460 -6.00303 90.43652 13.06454 -9.00303 90.43675 6.58979 -9.00303 88.98119 6.58979 -6.00303 88.98119 7.09562 -9.00303 88.94080 7.09562 -6.00303 88.94080 7.59425 -9.00303 89.02869 7.59425 -6.00303 89.02869 8.05464 -9.00303 89.23886 8.05464 -6.00303 89.23886 8.44753 -9.00303 89.55786 8.44753 -6.00303 89.55786 8.74787 -9.00303 89.96545 8.74787 -6.00303 89.96545 8.93653 -9.00303 90.43652 8.93653 -6.00303 90.43652 8.28888 -5.29592 89.04181 9.02681 -5.29592 89.86537 14.74864 -5.30497 88.66199 13.71718 -5.29592 89.03847 12.97572 -5.29592 89.86275 6.79139 -9.24625 88.91932 7.54059 -9.51198 88.86862 8.07767 -9.70493 88.92410 8.96474 -9.71013 89.75558 9.02918 -9.98200 89.01439 8.74658 -9.92569 88.99265 8.47820 -9.84499 88.97118 2.67261 -8.00303 91.72430 2.43612 -8.00303 91.75066 2.21422 -8.00303 91.66472 2.05718 -8.00303 91.48595 19.32849 -8.00302 91.72429 19.56498 -8.00302 91.75067 19.78688 -8.00302 91.66473 19.94394 -8.00302 91.48595 16.77464 -10.75303 89.55949 18.47097 -9.98157 90.87932 19.13404 -9.19326 91.46947 17.76203 -10.62444 90.18590 18.69175 -10.17119 90.83067 19.38859 -9.29184 91.43205 16.86144 -10.91940 89.41756 18.84677 -10.23448 90.72431 17.99669 -10.79865 89.96618 19.68918 -9.29155 91.14125 5.13100 -10.93604 89.40337 7.47736 -10.85658 88.42581 9.95057 -10.85241 87.89981 11.00057 -10.66970 88.02230 8.52545 -10.61703 88.28741 11.00057 -10.97928 87.70176 12.05057 -10.85241 87.89981 14.52377 -10.85658 88.42581 2.91575 -9.16382 91.46036 5.21588 -10.77336 89.54215 4.28875 -10.54603 90.21458 3.42461 -10.08604 90.87474 2.71859 -9.25626 91.46587 4.16107 -10.70809 90.13063 3.24180 -10.20360 90.79390 2.53492 -9.30571 91.39326 4.00711 -10.79692 89.97325 3.07019 -10.24095 90.64246 2.36523 -9.30826 91.23492 11.00057 -10.04902 88.66844 11.00057 -10.18686 88.38903 11.00057 -10.40319 88.16565 9.21358 -10.32127 88.33206 9.26853 -10.17210 88.66017 12.73371 -10.17210 88.66017 12.78866 -10.32127 88.33206 13.47679 -10.61703 88.28741 13.52403 -9.84499 88.97118 13.25566 -9.92569 88.99265 12.97305 -9.98200 89.01439 13.03750 -9.71013 89.75558 13.92457 -9.70493 88.92410 14.46165 -9.51198 88.86862 15.21085 -9.24625 88.91932 12.17269 -10.00303 89.94012 12.38235 -10.00303 89.47595 12.66779 -10.00303 89.05358 14.44319 -10.49865 88.55418 15.04554 -10.02226 88.77108 15.52327 -9.48780 88.97308 12.00057 -5.00303 90.93854 10.00057 -5.00303 97.26875 12.00057 -5.00303 97.26875 12.23295 -5.00303 98.09372 10.77804 -5.00303 98.02587 11.22309 -5.00303 98.02587 10.37708 -5.00303 98.21896 11.62406 -5.00303 98.21896 9.63454 -5.07242 98.00080 10.09960 -5.00303 98.56692 11.90153 -5.00303 98.56692 9.83087 -5.00303 98.92145 12.17026 -5.00303 98.92146 10.00057 -5.00303 99.00080 12.00057 -5.00303 99.00080 12.08618 -5.00303 99.44342 9.92156 -5.00303 99.45930 11.86829 -5.00303 99.49785 10.13484 -5.00303 99.50132 11.50329 -5.00303 99.86525 11.76625 -5.00303 99.88861 10.24623 -5.00303 99.89827 10.50175 -5.00303 99.86751 11.00279 -5.00303 100.00079 11.28202 -5.00303 100.13889 10.73530 -5.00303 100.14278 13.00094 -6.00303 98.00079 13.00057 -9.00303 90.93854 13.00057 -9.00303 98.00080 10.00057 -10.00303 90.93854 12.00057 -10.00303 98.00080 10.00057 -10.00303 98.00080 9.00056 -9.00303 98.00080 9.00056 -6.00303 97.96098 9.00056 -6.00303 90.93854 9.61786 -5.07915 90.93854 9.30198 -5.28750 98.00080 9.29344 -5.29593 90.93854 9.07900 -5.61481 98.00080 9.00550 -6.00303 98.14118 12.43220 -5.11040 98.23586 12.38325 -5.07915 90.93854 12.69915 -5.28749 98.00080 12.70767 -5.29592 90.93854 12.92214 -5.61481 98.00080 12.92444 -5.62034 90.93854 12.86658 -9.50305 98.00080 12.70767 -9.71013 90.93854 12.50054 -9.86907 98.00080 12.38325 -9.92691 90.93854 9.50056 -9.86905 98.00080 9.29346 -9.71013 90.93854 9.13454 -9.50303 98.00080 9.07669 -9.38571 90.93854 11.00057 -5.00303 99.00080 9.26326 -5.33823 98.18478 9.07251 -5.64578 98.15256 12.73786 -5.33822 98.18479 12.92861 -5.64578 98.15256 12.27405 -5.02203 98.50558 9.18789 -5.27567 99.41162 8.89816 -5.94570 99.54117 9.84061 -5.27567 100.45306 9.67032 -5.94570 100.71619 11.00056 -5.94570 101.17154 11.00056 -5.27567 100.85945 12.33081 -5.94570 100.71619 12.16051 -5.27567 100.45306 13.10297 -5.94570 99.54117 12.81324 -5.27567 99.41162 10.00057 -10.00303 99.50080 12.00057 -10.00303 99.50080 13.10297 -8.94570 99.54117 8.89816 -8.94570 99.54117 9.67032 -8.94570 100.71619 11.00056 -8.94570 101.17154 12.33081 -8.94570 100.71619 4.24052 10.89910 94.28619 4.50790 10.95624 93.19573 4.04649 10.83841 95.10439 3.71665 10.70835 96.54009 3.49354 10.59098 97.56621 2.95580 10.19218 98.41814 3.31761 10.48045 98.41386 2.72783 9.95522 97.81952 2.25906 9.21523 96.83735 2.07241 8.64962 96.46508 2.00056 7.99697 96.17237 3.33635 4.10292 92.26276 2.87013 4.09936 92.83099 4.15790 6.16047 92.98504 2.87012 5.29650 93.82285 6.00056 7.74294 93.00079 6.00056 8.49697 93.00079 2.00056 4.28585 92.55056 2.00056 5.53739 93.58749 2.00056 7.42452 96.80273 6.26273 11.26217 92.88427 6.88205 11.39697 93.68382 2.31998 5.63813 94.39954 2.31998 3.11935 92.42470 5.50056 8.49697 96.08532 5.50056 7.94142 93.74381 10.00057 -5.00303 90.93854 13.00057 -6.00303 90.93854 12.00057 -10.00303 90.93854 9.00056 -9.00303 90.93854 9.07668 -5.62035 90.93854 12.92445 -9.38571 90.93854 9.61788 -9.92691 90.93854 3.26737 7.83903 98.26450 8.21460 11.49697 103.47164 3.92516 9.96326 102.56780 5.71889 10.27446 104.34765 2.59157 9.57200 100.42619 2.61861 9.77928 100.36005 2.22178 8.65637 98.63448 2.24701 9.00930 99.10450 2.19308 9.23126 99.04589 2.19150 7.58718 97.89458 2.14427 8.20532 98.23191 2.43612 7.03771 97.27090 2.17456 9.29202 98.66216 2.24902 9.44767 98.97076 2.37461 9.63634 99.45103 2.54015 9.80788 99.89677 2.61779 7.53031 97.96102 2.44224 8.55985 98.71039 3.43079 8.64121 99.29345 2.67040 8.34236 98.60520 2.30384 8.16196 98.33179 8.45559 9.65113 104.62135 7.66201 9.49194 103.77038 5.03176 9.74083 103.29839 6.15173 9.88731 104.26470 7.82490 8.69990 101.51351 4.07904 8.54095 99.21242 3.78238 9.43370 101.78474 2.61464 8.73646 99.12650 2.97374 9.09237 100.37290 7.26237 11.49697 102.71239 6.51005 11.49697 101.75495 5.99730 11.49697 100.64925 5.75235 11.49697 99.45495 5.78809 11.49697 98.23913 5.97176 11.49697 97.17276 6.20463 11.49697 96.22712 6.50539 11.49697 95.41562 6.88949 11.49697 94.76318 7.13401 9.95133 104.91682 5.12495 11.27728 95.90439 4.65410 11.17867 96.90395 5.65125 11.34554 95.02052 4.49829 11.01932 95.70683 2.04909 8.88449 98.20363 2.00056 7.87464 97.62243 2.00056 8.32860 97.39330 4.62223 8.49544 98.56344 2.87012 6.30681 95.12612 2.87011 7.19214 97.23295 4.06698 7.94142 95.86849 4.41981 7.94142 95.18249 4.88910 7.94142 94.46915 4.22435 11.08882 98.01063 2.72783 10.01127 98.47569 2.72783 10.00166 99.68507 2.72783 10.02460 99.09306 4.15255 11.04698 99.04556 2.72783 9.94482 100.26659 4.25925 11.04698 100.20577 3.35801 10.22999 101.42496 3.77964 10.36962 102.04487 4.60520 11.04699 101.44958 4.28376 10.50161 102.68006 5.24331 11.04699 102.70905 5.46721 10.70933 103.86160 6.03297 10.77157 104.31409 6.19326 11.04699 103.87800 7.05452 10.83814 104.99229 7.39829 11.04698 104.82497 17.91544 8.54095 99.21242 16.24877 11.49697 99.45495 15.11115 11.49697 94.76254 15.49569 11.49697 95.41553 15.79654 11.49697 96.22728 16.02941 11.49697 97.17297 16.21304 11.49697 98.23913 14.64871 11.49697 94.29107 13.73918 11.49697 93.71020 12.69940 11.49697 93.29076 11.00057 11.49697 99.12437 11.00057 11.49528 92.98592 13.90857 11.39697 92.93648 16.34981 11.34554 95.02040 15.11907 11.39697 93.68382 11.00057 8.49697 99.00079 12.05057 8.49697 92.86504 17.58927 8.49697 99.04091 17.37226 8.49544 98.56345 17.13748 8.49697 97.95770 17.02299 8.49697 97.42587 16.84736 8.49697 96.86423 16.59384 8.49697 96.26855 16.24058 8.49697 95.64041 15.76119 8.49697 94.99002 15.12631 8.49697 94.33944 14.30628 8.49697 93.72611 13.28150 8.49697 93.20879 11.00056 8.55728 102.13480 16.76383 7.94142 94.03386 15.95638 7.94142 93.22797 16.76130 11.04699 102.70362 15.81296 11.04698 103.87298 16.09110 10.75973 104.22089 14.60886 11.04698 104.82124 14.99772 10.83605 104.96210 13.23964 11.04697 105.47259 13.57732 10.85606 105.66717 13.04660 10.85606 105.84870 11.76309 11.04697 105.80639 11.82334 10.85606 106.10032 10.24501 11.04697 105.80717 10.53990 10.85606 106.13297 13.01686 9.96856 105.74918 13.54827 9.65113 104.62135 12.30502 9.65113 105.03237 11.81138 9.96856 105.99714 9.94006 9.96856 105.96366 11.00053 9.65113 105.17181 16.00381 11.49697 100.64927 13.78652 11.49697 103.47164 15.96762 9.87593 104.17509 14.29012 9.10508 102.62046 14.67593 8.71842 101.57586 14.44250 9.96396 105.15311 14.10963 10.38171 105.66822 12.06853 10.38028 106.29176 9.93260 10.38028 106.29176 16.28223 10.27446 104.34765 11.00056 11.48797 104.50080 13.27124 11.48797 104.01020 12.13903 11.48797 104.37675 14.91229 7.94142 92.47514 8.09208 11.39697 92.93671 9.49381 11.39697 92.44625 12.50645 11.39697 92.44605 9.30160 11.49697 93.29080 8.26184 11.49697 93.71024 9.83903 11.48797 104.37675 8.72988 11.48797 104.01020 7.89150 10.38170 105.66822 7.35242 11.49697 94.29107 8.40465 9.96856 105.54812 9.69602 9.65113 105.03236 8.36637 10.85606 105.64468 9.34895 10.85606 105.95438 8.76811 11.04697 105.47488 24.00056 7.42452 92.80273 24.00056 5.53739 89.58749 24.00056 4.28586 88.55056 24.00056 7.99697 92.17237 24.07241 8.64962 92.46508 24.25905 9.21523 92.83735 24.50154 9.65676 93.29485 24.72783 9.95522 93.81952 25.31761 10.48045 94.41386 24.95580 10.19218 94.41814 25.49354 10.59098 93.56621 25.71664 10.70835 92.54009 26.04649 10.83841 91.10439 26.50790 10.95624 89.19573 26.24052 10.89910 90.28619 24.31694 9.33731 80.00230 24.65771 9.87446 80.00000 27.01505 -10.99559 85.21379 39.73980 -10.91053 85.59454 39.76828 -10.89972 80.00000 40.08883 -10.77342 85.81319 40.50205 -10.59673 80.00000 41.02324 -10.21861 86.44615 41.12120 -10.12139 80.00000 41.59687 -9.50222 80.00000 41.72198 -9.24321 87.00867 26.22410 -10.90081 80.00080 25.90226 -10.76947 85.81947 25.49917 -10.59693 80.00000 24.40259 -9.49962 80.00000 24.97834 -10.21902 86.44582 24.27815 -9.24094 87.00952 39.00056 -11.00303 85.19009 39.00026 -10.99969 80.00000 37.42865 -11.00303 84.38750 28.57306 -11.00303 84.38726 26.99799 -11.00650 79.96545 42.00056 4.28707 88.55138 42.00056 2.48084 87.66388 42.00056 1.33137 87.37064 42.00056 -0.00303 87.25484 42.00056 -8.00303 87.25484 24.00056 2.47986 87.66354 24.00056 1.33074 87.37052 24.00056 -0.00303 87.25483 24.00056 -8.00303 87.25484 39.49199 10.95645 89.19074 39.23637 10.98769 88.17481 26.76369 10.98761 88.17897 27.00056 10.99697 87.25483 39.00056 10.99697 87.25483 37.16936 10.99697 86.13393 35.13641 10.99697 85.43846 33.00055 10.99697 85.20283 30.86467 10.99697 85.43847 28.83172 10.99697 86.13396 41.90019 -8.76805 80.00000 24.10026 -8.76782 80.00000 42.00026 -7.99969 80.00000 24.00026 -3.99969 80.00000 24.00026 -7.99969 80.00000 24.00026 6.00031 80.00000 24.00026 8.00031 80.00000 24.07367 8.65989 80.00000 25.12580 10.34262 80.00000 25.66303 10.68178 80.00157 40.30249 10.70294 80.00000 40.87493 10.34245 80.00000 41.34298 9.87424 80.00000 41.70312 9.30205 80.00000 41.92687 8.65984 80.00000 42.00026 8.00031 80.00000 42.00026 6.00031 80.00000 27.00026 11.00031 80.00000 39.00026 11.00031 68.44582 39.76017 10.89921 90.28439 40.03181 10.81415 91.43005 40.28997 10.70574 92.56482 40.51466 10.58686 93.59962 40.68932 10.47650 94.44254 41.49958 9.65676 93.29486 41.74207 9.21523 92.83736 41.92871 8.64963 92.46509 42.00056 7.99698 92.17238 41.27329 9.95522 93.81953 3.69851 10.70317 84.00000 -4.99944 -11.00303 80.00080 -3.49865 -10.59694 80.00000 -2.87826 -10.12085 80.00000 -2.40227 -9.49953 79.99998 -2.05395 -8.57232 87.20531 -17.77590 -10.90081 80.00080 -18.09775 -10.76947 85.81947 -18.50153 -10.59674 80.00000 -19.12068 -10.12140 80.00000 -19.59635 -9.50222 80.00000 -15.42694 -11.00303 84.38726 -16.99944 -11.00303 83.00080 -1.99945 2.48084 87.66388 -1.99945 1.33136 87.37064 -1.99945 5.53833 89.58846 -19.99944 -8.00303 87.25484 -19.92759 8.64962 92.46508 -19.49847 9.65676 93.29485 -16.99944 10.99697 87.25483 -15.16828 10.99697 86.13396 5.01505 -10.99559 89.21378 17.76828 -10.89972 84.00000 18.50205 -10.59673 84.00000 19.12120 -10.12139 84.00000 19.59687 -9.50222 84.00000 19.94605 -8.57232 91.20531 4.22410 -10.90081 84.00079 3.90226 -10.76947 89.81947 3.49847 -10.59674 84.00000 2.87932 -10.12140 84.00000 2.97833 -10.21902 90.44581 2.40364 -9.50222 84.00000 2.27815 -9.24094 91.00951 17.00026 -10.99969 84.00000 13.76830 -11.00303 87.83882 11.00056 -11.00303 87.54882 8.23315 -11.00303 87.83874 6.57306 -11.00303 88.38725 5.00026 -10.99969 84.00000 20.00056 4.28707 92.55137 20.00056 2.48084 91.66387 20.00056 1.33136 91.37063 20.00056 -0.00303 91.25483 20.00056 -8.00303 91.25484 2.00056 1.33074 91.37052 2.00056 -0.00303 91.25483 2.00056 -8.00303 91.25483 20.00056 7.99697 96.17237 19.92871 8.64962 96.46508 19.74206 9.21523 96.83735 19.49958 9.65676 97.29485 19.27328 9.95522 97.81952 18.68931 10.47650 98.44253 18.51465 10.58686 97.59961 18.28996 10.70574 96.56481 2.50154 9.65676 97.29485 5.00056 10.99697 91.25483 11.00054 10.99697 89.20283 -19.89967 -8.76805 80.00000 -2.09974 -8.76782 80.00000 19.90018 -8.76805 84.00000 2.10032 -8.76805 84.00000 2.00026 -7.99969 84.00000 20.00026 -7.99969 84.00000 -16.99974 -10.99970 80.00000 -10.99974 -11.00136 78.34409 11.00056 -11.00303 82.16397 -1.99974 -7.99969 80.00000 -1.99974 -3.99969 80.00000 -19.99974 -7.99969 80.00000 -19.99974 8.00031 71.65829 -19.92632 8.66000 80.00000 -19.70237 9.30253 80.00000 -19.34188 9.87497 80.00000 -18.87368 10.34303 80.00000 -18.30149 10.70316 80.00000 -4.34009 10.92688 80.00000 -3.62834 10.66877 79.99939 -3.12528 10.34261 80.00000 -2.65719 9.87445 80.00000 -2.34403 9.38150 80.00058 -1.99944 7.99697 80.00080 -1.99974 6.00031 80.00000 2.00026 8.00031 84.00000 2.07369 8.66001 84.00000 2.29763 9.30254 84.00000 2.65812 9.87498 84.00000 3.12632 10.34303 84.00000 18.30201 10.70317 84.00000 18.87420 10.34303 84.00000 19.34240 9.87498 84.00000 19.70288 9.30254 84.00000 19.92683 8.66001 84.00000 20.00026 8.00031 84.00000 20.00026 6.00031 84.00000 17.00026 11.00031 84.00000 5.00026 11.00031 84.00000 -4.99974 11.00031 80.00000 -16.99974 11.00031 80.00000 3.86241 -10.59802 81.40353 2.42948 -9.53943 80.00157 -2.16309 -9.49833 78.95819 -2.83410 -10.59802 77.81886 -1.49683 -9.49833 78.12273 -0.91783 -10.59777 76.62256 -0.53404 -9.49833 77.65906 0.59526 -10.59777 76.55095 0.53456 -9.49833 77.65906 1.99690 -10.59777 77.12538 1.49734 -9.49833 78.12273 3.02454 -10.59777 78.23828 2.16361 -9.49833 78.95819 3.71604 -10.59802 79.60367 2.11456 -8.81990 80.00000 19.58443 -9.49802 79.99977 19.89211 -8.79794 80.00000 18.40394 -10.64841 79.90620 19.92081 -9.49833 78.79944 18.99247 -10.59777 78.21025 20.03621 -10.59777 77.10303 20.79969 -9.49833 77.92055 21.45118 -10.59777 76.54335 22.00026 -9.49833 77.59886 -1.22603 -10.99969 75.15271 36.38472 -10.99969 74.66985 22.28898 -10.99969 75.00835 -0.26943 -10.99969 75.00728 21.31737 -10.99969 75.04686 0.69725 -10.99969 75.04883 20.37126 -10.99969 75.27280 1.63810 -10.99969 75.27588 -2.13715 -10.99969 75.47989 19.48711 -10.99969 75.67751 2.51731 -10.99969 75.67976 18.69775 -10.99969 76.24588 3.30253 -10.99969 76.24567 -4.24974 -10.99969 75.50000 3.96375 -10.99969 76.95193 18.03361 -10.99969 76.95605 4.47660 -10.99969 77.77237 17.51946 -10.99969 77.78136 4.82196 -10.99969 78.67668 17.17464 -10.99969 78.69104 -4.20597 -11.00002 77.51928 -16.99974 -10.99969 71.07354 4.98589 -10.99969 79.62120 5.01205 -10.99969 81.49242 17.00672 -10.99969 81.49741 5.00026 -10.99969 82.40479 3.15365 10.59839 78.48140 2.16361 9.49895 78.95819 2.18247 10.59839 77.26360 1.49734 9.49895 78.12273 0.77908 10.59839 76.58775 0.53456 9.49895 77.65906 -0.77857 10.59839 76.58775 -0.53405 9.49895 77.65906 -2.18196 10.59839 77.26360 -1.49683 9.49895 78.12273 -3.15313 10.59839 78.48140 -2.16309 9.49895 78.95819 4.33270 10.83834 80.00000 3.58877 10.63364 80.00013 3.12979 10.34580 80.00000 2.65477 9.87078 80.00000 2.34381 9.38248 79.99774 2.07547 8.66787 80.00000 22.77908 10.59839 76.58775 22.53456 9.49895 77.65906 21.22144 10.59839 76.58775 21.46596 9.49895 77.65906 19.81805 10.59839 77.26360 20.50317 9.49895 78.12273 17.66800 10.88732 80.00000 18.84687 10.59839 78.48140 19.34576 9.87077 80.00000 18.87074 10.34580 80.00000 18.39397 10.64952 80.00264 19.83691 9.49895 78.95819 19.65764 9.37099 80.00056 2.00026 -7.99969 80.00000 1.93211 -7.99969 79.48236 1.81694 7.99696 79.12401 1.73231 -7.99969 79.00000 1.41447 -7.99969 78.58580 1.35816 7.99634 78.50421 1.00026 -7.99969 78.26796 0.70652 7.99770 78.11432 0.51789 -7.99969 78.06816 0.00026 -7.99969 78.00000 0.00362 7.99684 77.98100 -0.51738 -7.99969 78.06816 -0.73896 7.99722 78.12480 -0.99974 -7.99969 78.26796 -1.34970 7.99713 78.50260 -1.41395 -7.99969 78.58580 -1.73179 -7.99969 79.00000 22.00020 -7.99969 78.00000 22.00362 7.99684 77.98100 21.48263 -7.99969 78.06815 21.26106 7.99722 78.12480 21.00025 -7.99969 78.26796 20.65031 7.99713 78.50260 20.58604 -7.99969 78.58580 20.26821 -7.99969 79.00000 20.18043 7.99652 79.12059 20.00026 -7.99969 80.00000 20.06841 -7.99969 79.48236 -1.81518 7.99650 79.11426 2.00087 7.99860 80.00000 20.02610 8.00223 79.78577 20.00026 6.00031 80.00000 17.00026 11.00031 80.00000 5.00026 11.00031 80.00000 -4.84600 11.00031 78.76964 -4.96166 11.00031 79.38405 17.07212 11.00031 79.15535 4.92874 11.00031 79.15738 17.29248 11.00031 78.31572 4.70803 11.00031 78.31569 4.33671 11.00031 77.51099 17.66463 11.00031 77.50955 -0.93444 11.00031 75.08815 -1.77980 11.00031 75.32759 -2.56862 11.00031 75.71039 -4.38788 10.99998 77.50107 -3.28124 11.00031 76.22751 18.17623 11.00031 76.77870 3.82524 11.00031 76.77983 18.80557 11.00031 76.15372 3.19481 11.00031 76.15361 19.52892 11.00031 75.65346 2.47028 11.00031 75.65271 20.32602 11.00031 75.28865 1.67287 11.00031 75.28807 21.17697 11.00031 75.06825 22.05642 11.00031 75.00032 0.82237 11.00031 75.06805 -0.05691 11.00031 75.00034 35.76831 -11.00303 83.83883 33.00057 -11.00303 83.54883 30.23315 -11.00303 83.83875 22.96992 -10.59777 76.63701 23.20083 -9.49833 77.92055 24.07971 -9.49833 78.79944 24.42620 -10.59802 77.56999 40.44828 -10.60419 74.80899 41.17694 -10.06092 74.96077 41.68639 -9.55202 74.60719 42.00000 -5.53847 70.52470 41.99767 -8.01113 74.09462 23.24969 -10.99969 75.15863 39.02267 -11.00002 75.08292 24.16356 -10.99969 75.49222 25.02965 -10.99969 76.31189 25.97642 -11.00002 77.80835 33.00041 -11.01419 78.34450 25.15365 10.59839 78.48140 24.16361 9.49895 78.95819 24.18247 10.59839 77.26360 23.49735 9.49895 78.12273 23.93211 -7.99969 79.48236 23.94208 7.99737 79.45579 23.73231 -7.99969 79.00000 23.60646 7.99701 78.77991 23.41448 -7.99969 78.58580 23.20683 8.00031 78.40495 23.00026 -7.99969 78.26796 22.70653 7.99771 78.11432 22.51792 -7.99969 78.06816 42.00000 -4.37194 66.47318 26.96239 11.00031 79.38576 26.84682 11.00031 78.77084 24.56712 11.00031 75.70917 23.77808 11.00031 75.32674 22.93337 11.00031 75.08784 25.28084 11.00031 76.22670 26.77643 10.99998 78.09213 25.81986 10.88883 78.11772 32.41966 -10.39946 12.09682 32.07253 -12.24215 12.44395 31.50558 -13.97236 13.01090 30.73585 -15.53810 13.78063 31.63869 -14.49044 14.44561 29.78649 -16.89231 14.73000 28.68600 -17.99429 15.83049 27.46747 -18.81092 17.04902 32.07041 -8.48608 13.14742 28.40349 -8.47888 11.38137 35.00025 -3.93633 11.33591 35.00025 -5.76714 10.52314 35.00025 -7.43725 9.41714 35.00025 -8.90012 8.04874 35.00025 -10.11498 6.45606 35.00025 -11.04798 4.68349 35.00025 -11.67312 2.78041 35.00025 -11.97299 0.79987 35.00025 -11.93923 -1.20297 35.00025 -11.57278 -3.17229 29.56896 -8.93371 8.01144 30.37484 -8.14502 8.83751 28.55564 -9.64302 7.14184 27.30582 -10.22031 6.25847 27.40025 -11.09018 4.58267 27.40025 -11.64889 2.88026 26.69314 -11.32162 2.97825 27.40025 -11.94789 1.11364 26.69314 -11.69481 0.52943 25.93359 -9.85955 5.58084 23.33167 -11.28459 5.48865 25.97391 -12.57047 6.52176 24.85194 -11.60693 5.52240 25.38119 -14.24428 7.11447 22.47212 -13.82473 6.34820 24.59638 -15.75172 7.89929 23.89290 -14.44108 6.48145 23.64218 -17.04913 8.85348 21.12374 -15.89684 7.69659 22.38843 -16.75303 7.98591 22.54626 -18.09895 9.94942 19.40502 -17.31880 9.41531 20.47079 -18.33958 9.90356 21.34031 -18.87077 11.15535 20.05931 -19.34222 12.43637 17.46704 -17.96563 11.35329 18.30849 -19.06128 12.06586 18.74032 -19.49967 13.75536 33.46514 -13.23542 -4.38078 33.17361 -11.74079 -2.47919 31.96513 -11.92772 -1.31220 30.60025 -11.99514 -0.33012 30.05848 -11.99939 -0.08363 29.53337 -11.99967 0.01540 28.99234 -11.99966 -0.01997 28.45432 -11.99809 -0.19527 27.92001 -11.98834 -0.52153 27.40787 -11.94871 -0.93188 27.09578 -11.87235 -1.37937 26.71759 -11.59961 -1.87070 26.45649 -11.05894 -2.46481 26.48153 -14.05493 -5.30130 26.40025 -4.32847 -11.00000 24.01463 -8.49968 5.09244 16.67795 -16.49934 11.57507 17.65359 -16.36674 10.59943 18.59801 -15.99816 9.65502 19.48311 -15.40482 8.76991 22.28349 -8.49967 5.96953 22.19817 -9.88384 6.05485 21.94514 -11.22494 6.30789 21.53238 -12.48305 6.72064 20.97256 -13.62080 7.28047 20.28258 -14.60443 7.97044 22.28349 -7.74968 5.96953 19.83408 -7.73186 8.35989 24.57748 -13.49051 -6.58543 17.34177 -13.08415 -7.20829 20.86789 -13.10861 -7.33405 24.43242 -12.36088 -7.88292 17.48629 -11.32987 -8.83814 24.26431 -11.05180 -8.98052 20.85670 -11.35649 -8.91334 24.07885 -9.60768 -9.85024 17.65667 -9.26180 -10.04916 20.84362 -9.30734 -10.08301 23.88002 -8.05947 -10.48217 16.21432 -4.66904 -11.01525 17.84032 -7.03250 -10.77016 20.82957 -7.10759 -10.77834 23.45517 -4.75135 -11.00000 20.80625 -4.91046 -11.00024 23.67152 -6.43582 -10.86811 18.49701 -4.88507 -10.99056 17.10318 -14.40371 -5.27383 21.01717 -14.45248 -5.46440 19.67205 -14.44833 -5.46252 17.62941 -16.83755 -0.58108 20.16150 -16.82432 -1.00220 23.59675 -18.29618 2.50569 18.73591 -18.84136 3.96948 21.20890 -18.77235 3.32656 16.32313 -18.63193 4.75818 25.02458 -19.76640 6.56033 20.33439 -20.43481 8.38559 22.72505 -20.30991 7.52827 17.99380 -20.21678 9.37159 15.74767 -19.64619 10.48572 26.83457 -20.85997 10.49575 24.62881 -21.45601 11.60829 22.33832 -21.62800 12.67454 20.08241 -21.41371 13.85310 17.90191 -20.78959 15.13326 28.95048 -21.59927 14.31419 26.83901 -22.22966 15.57203 25.69386 -14.36625 -4.94374 26.67791 -14.31856 -4.75937 27.05751 -14.55941 -4.13273 27.51717 -14.71325 -3.63396 28.06561 -14.79880 -3.22257 29.33738 -14.75585 -2.73757 29.99210 -14.63437 -2.69855 28.62729 -14.79947 -2.94484 31.81377 -14.02564 -3.27142 31.22617 -14.24843 -3.01117 30.60025 -14.46437 -2.79936 32.28778 -13.85514 -3.54527 32.72167 -14.68274 -0.78008 25.76056 -17.30739 1.19689 29.24789 -16.00011 0.24117 26.34064 -17.95326 2.99865 33.49831 -15.35544 1.85464 30.21492 -16.97527 3.37435 26.92072 -18.59914 4.80041 27.72791 -19.13109 6.68708 34.47482 -15.90300 4.43259 31.44747 -17.74713 6.43111 28.53512 -19.66305 8.57375 35.62984 -16.33092 6.95041 29.58687 -20.05982 10.55781 32.90879 -18.32579 9.40888 30.63861 -20.45659 12.54188 31.93859 -20.68924 14.62075 34.56216 -18.72138 12.30512 23.40025 -15.35262 -3.49114 17.67848 -2.25269 -10.97999 26.40025 0.00032 -11.00000 26.40025 -5.99968 6.00000 26.40025 -6.18543 -10.84601 26.39507 -7.73162 5.01775 26.40025 -7.98379 -10.39034 26.51307 -10.34244 5.16880 26.40025 -9.67426 -9.64862 26.40025 -10.42215 3.51740 26.40025 -10.62459 -2.84802 26.40025 -11.22704 -8.63210 26.40025 -12.58132 -7.37891 26.40025 -13.70245 -5.92588 26.40025 -10.92695 -1.26284 26.40025 -10.99412 0.34961 26.40025 -10.82463 1.95455 17.80788 0.01881 -10.96892 26.40131 0.00470 11.02763 27.05665 0.00902 11.89370 35.02811 0.00038 11.99570 18.44563 0.00032 14.19054 30.44322 -16.82160 15.96257 41.72396 -14.98816 14.96004 40.58631 -14.56790 15.87016 36.07827 -8.49957 15.91767 41.68601 -7.84641 15.45741 41.99378 -9.96123 14.29536 41.76836 -10.68854 14.90430 41.47512 -13.70568 15.47653 40.74386 -13.57435 15.74585 41.90142 -13.68791 14.88158 42.00025 -13.19034 14.22322 36.80173 -18.68935 15.87161 40.32484 -16.75150 15.04226 41.17762 -15.92868 15.16056 40.12450 -15.27101 15.93373 41.79856 -15.10147 14.19986 41.57338 -15.56666 14.15112 36.39445 -18.92611 15.09956 38.38988 -16.84989 11.79218 40.17875 -16.92108 14.26558 42.00025 2.48337 21.60506 42.00025 -10.67037 4.09572 42.00025 -11.57090 7.14653 42.00025 -4.59768 15.66448 42.01282 -6.84140 14.96247 42.00025 -9.20317 14.24871 42.00025 1.33143 20.13086 42.02021 -13.83867 14.29792 42.00025 -11.52747 14.08447 42.00025 -12.69090 10.55043 42.00025 -2.45947 16.88491 40.37364 0.00032 17.38353 42.00025 0.00032 18.43768 26.40025 11.00032 12.00000 35.70737 -6.77643 9.54630 35.70737 -9.35620 7.03646 35.70737 -11.05159 3.86154 41.54034 -12.20096 3.64140 41.57278 -13.76807 8.91658 38.94659 -14.48250 5.48678 40.27235 -13.74717 5.04461 36.94197 -16.64471 9.40473 40.17191 -14.74203 7.98174 40.18572 -15.74563 10.95821 36.00025 -3.63533 10.38181 36.00025 -5.32250 9.62640 36.00025 -6.85840 8.59988 36.00025 -8.20481 7.32637 36.00025 -9.31814 5.84517 36.00025 -10.16628 4.19999 36.00002 10.99987 11.00575 39.03521 10.99585 49.49404 39.00025 11.00032 0.00000 35.77664 10.99998 11.66449 42.00025 8.00032 0.00000 42.00025 3.41451 23.22381 36.00025 -1.84419 10.84425 36.00155 0.00021 11.04205 39.66782 10.92510 0.00000 35.50025 0.00032 11.86602 35.70735 0.00032 11.70711 35.86629 0.00032 11.50000 35.70737 -3.55614 11.15383 35.01630 10.99907 11.99929 26.46544 8.99548 11.93410 35.02872 -0.00088 13.18406 27.01681 -0.01593 12.24285 35.70737 -11.70236 0.32163 35.70737 -11.24701 -3.24868 41.79050 -5.24932 -8.18536 41.12244 -5.67564 -9.11020 40.10453 -6.72086 -9.32953 41.79050 -7.10811 -7.05963 41.12244 -7.73129 -7.86506 40.10453 -9.11759 -7.54228 41.79050 -8.66228 -5.53637 41.12244 -9.45589 -6.17453 41.79050 -9.81318 -3.68586 40.99850 -10.87407 -3.69895 35.70857 -12.46417 -4.83863 35.39104 -11.27122 -6.77530 39.76682 -10.03020 -6.70477 39.67771 -8.88076 -7.94828 38.50327 -9.60950 -7.80175 39.57241 -7.56018 -9.00135 37.77982 -7.19140 -9.58311 39.45084 -6.08439 -9.85267 39.31380 -4.48102 -10.48151 36.95520 -4.63787 -10.65918 35.95850 -8.66244 -7.28350 35.90602 -9.91289 -8.07626 35.75685 -9.60337 -6.61510 35.60590 -10.89876 -7.17277 35.52370 -10.17083 -6.08433 35.27900 -10.59459 -5.56352 35.08573 -11.80042 -6.21057 35.00025 -10.88384 -5.05321 34.38255 -12.56367 -5.28366 34.20457 -11.39358 -3.76551 41.83179 -10.32557 -1.58042 40.45203 -11.22837 -3.75616 41.39480 -11.07880 -1.49079 35.97550 -13.18312 -2.76720 39.88445 -11.55432 -3.60652 38.22656 -12.18830 -3.49943 39.99825 -12.45262 -0.54365 36.62261 -13.68488 -0.23199 36.00025 -3.91054 -10.86223 36.00025 -5.67979 -10.45229 36.00025 -8.87659 -8.87691 36.00025 -7.36012 -9.77795 36.00025 -7.77785 -7.77817 36.00025 -8.97281 -6.36262 36.00025 -9.91164 -4.77001 36.00025 -10.56956 -3.04591 36.00025 -10.92969 -1.23886 36.00025 -10.72610 2.43797 36.00025 -10.98286 0.60790 36.00025 11.00032 0.00000 42.00025 -9.96424 1.30748 42.00025 -9.39662 -1.40472 42.00025 7.87836 -1.39156 42.00025 -9.03509 -2.69429 42.00025 7.51684 -2.73898 42.00025 -8.43500 -3.93786 42.00025 6.92669 -4.00316 42.00025 -7.60726 -5.08039 42.00025 6.12571 -5.14584 42.00025 -6.58570 -6.06751 42.00025 5.13849 -6.13182 42.00025 -5.36798 -6.89020 42.00025 3.99485 -6.93136 42.00025 -4.01987 -7.49526 42.00025 2.73022 -7.51982 42.00025 -2.56724 -7.87046 42.00025 1.38154 -7.87986 42.00025 -1.03347 -8.00000 42.00025 0.00032 -8.00000 36.00243 -2.08998 -11.00134 36.00025 0.00032 -11.00000 36.00025 10.86488 -1.72086 36.00025 10.46189 -3.39935 36.00025 9.80128 -4.99411 36.00025 8.89931 -6.46590 36.00025 7.77821 -7.77845 36.00025 6.46557 -8.89947 36.00025 4.99391 -9.80123 36.00025 3.39927 -10.46170 36.00025 1.72095 -10.86460 39.00025 1.64007 -10.87710 39.00025 0.00032 -11.00000 39.00025 3.24445 -10.51074 39.00025 4.77550 -9.90947 39.00025 6.19860 -9.08743 39.00025 7.48293 -8.06292 39.00025 8.60061 -6.85820 38.97711 10.48833 -3.49900 39.00025 10.89241 -1.81746 40.87072 10.34581 0.00000 40.39354 10.64984 -0.00285 40.44881 9.92724 -3.46402 41.34576 9.87079 0.00000 41.69691 9.31188 0.00003 41.92503 8.66788 0.00000 40.40950 0.00075 -10.63610 39.66782 0.00032 -10.92478 41.59834 2.45910 -9.17630 41.92503 0.00032 -8.66756 41.64241 0.00280 -9.40395 40.49889 2.87802 -10.20072 41.34576 0.00032 -9.87047 40.87072 0.00032 -10.34549 41.59834 4.75032 -8.22724 40.49889 5.53952 -9.03621 41.59834 6.71784 -6.71751 40.49889 7.78487 -7.19281 41.59834 8.22756 -4.75000 41.59834 9.17661 -2.45878 39.16365 -2.79369 -10.86733 37.00700 -1.75784 -11.00000 38.00713 -1.40528 -11.00000 39.00025 -1.03347 -11.00000 40.10453 -3.96232 -10.42357 41.12244 -3.40579 -9.86750 41.79050 -3.19041 -8.87217 40.21046 -1.03285 -10.73261 39.68842 -1.03347 -10.92000 41.19122 -1.03675 -10.06106 41.74584 -1.03501 -9.19169 41.92567 -1.03347 -8.66481 42.00125 -0.71631 18.43793 42.00047 4.69463 28.63178 42.00025 4.55122 26.76699 42.00025 0.00032 18.84803 37.13560 0.00032 19.33138 42.00025 4.10720 24.95290 12.48855 0.00032 15.79746 33.23856 -20.92189 16.69963 40.06757 -16.00425 15.87180 40.76066 -15.52186 15.75184 40.22589 -16.42364 15.52244 33.35737 -19.37798 18.47001 36.38074 -17.22534 16.86727 34.80528 -18.14896 17.55972 36.71384 -18.03838 16.64430 38.09460 -16.32222 16.33483 33.58095 -19.83546 18.33452 33.70298 -20.36124 17.97835 33.54759 -20.85854 17.23243 30.69171 -22.24771 18.43513 31.62679 -21.89856 18.60092 31.84028 -21.44528 19.19135 31.80485 -20.76753 19.56403 31.41272 -21.95370 17.93778 32.26551 -19.55745 19.09028 41.25215 -11.00445 15.38837 40.64713 -11.32652 15.57718 40.52986 -9.02008 15.79778 41.13953 -8.51999 15.75000 40.40797 -6.80917 16.37211 41.01591 -6.13438 16.52873 41.58786 -5.17697 16.53330 40.38424 -4.48807 17.39216 41.93192 -4.01259 16.46580 40.92645 -3.84365 17.70301 41.23049 -3.30020 17.89991 41.47659 -2.75849 18.06087 41.81115 -1.86582 18.29766 35.71275 -9.70514 15.91655 35.29206 -10.91734 16.03664 39.14009 -13.04748 15.91205 36.25659 -12.37569 16.18197 35.09933 -11.52614 16.16334 34.11800 -13.05610 16.55863 38.58134 -14.43949 16.13064 41.26543 -14.76040 15.59119 29.34525 -16.44808 19.29173 31.47700 -15.17923 17.95151 33.81829 -18.55210 18.04124 35.41711 -17.43465 17.18345 33.03078 -13.91455 16.94667 36.99712 -16.05521 16.52681 29.02715 -17.60599 18.87496 28.50963 -18.42133 17.89616 30.80184 -16.13773 17.10027 33.63822 -12.77722 15.80504 16.99428 -9.81800 31.76485 16.69925 -10.41788 31.94674 16.30979 -10.98208 32.00584 15.84935 -11.48071 31.94181 15.35213 -11.88407 31.76527 14.83885 -12.18266 31.48938 14.32936 -12.36808 31.12731 26.16752 -19.31767 18.34896 24.82522 -19.49928 19.69126 26.32936 -19.14903 20.07642 27.02606 -18.27390 20.87606 23.48092 -19.35032 21.03556 21.39506 -18.03484 23.97550 20.94673 -18.08838 23.56975 22.17502 -18.87526 22.34147 24.09405 -18.94074 22.31174 22.80765 -17.27495 24.78395 22.34495 -17.61963 24.59529 21.90648 -17.85584 24.34606 24.97444 -18.08273 22.92768 17.42155 -19.33856 15.07412 16.14120 -18.86353 16.35448 14.93633 -18.08837 17.55934 15.52851 -17.95703 24.59624 20.26193 -19.88960 26.44862 19.21382 -18.99056 27.48279 16.93622 -16.85897 30.15846 18.19185 -18.06313 28.61580 18.99066 -17.98845 29.04794 19.74082 -17.36263 29.20479 16.33141 -15.51816 32.23310 17.21596 -14.86782 32.39306 30.56804 -19.94081 20.11284 28.39665 -17.08982 20.17259 28.93770 -20.18408 21.22098 27.43289 -17.51014 21.05082 27.35306 -20.11139 22.33945 26.40682 -17.71803 21.98104 25.85386 -19.72125 23.44511 25.32321 -17.67927 22.96891 24.46295 -19.04943 24.50940 24.25482 -17.38544 23.94786 23.00918 -19.02773 26.10271 23.14839 -16.87866 24.86744 23.19882 -18.14021 25.50321 22.34574 -16.22029 25.72816 21.27265 -17.60897 27.67948 22.07966 -17.02658 26.40910 21.59014 -15.58498 26.50463 20.15720 -16.65143 28.87076 17.49983 -14.38133 32.22543 20.96544 -14.97776 27.19388 21.12335 -15.73274 27.21871 20.37682 -14.31138 27.89104 20.01768 -13.85381 28.33471 19.66210 -13.33201 28.79596 16.91113 -19.99842 18.42204 24.66112 -22.43105 16.84361 22.50270 -22.21692 18.20885 18.23429 -20.36765 20.84407 20.40215 -21.55375 19.64542 22.79481 -21.72366 24.32345 19.74209 -20.53287 23.21113 31.13405 -20.31158 19.93935 29.80934 -22.52407 19.04909 29.85641 -20.68763 20.83751 29.93627 -21.36656 20.86927 29.86304 -22.07504 20.56565 29.12959 -22.67236 19.52594 29.57405 -22.54630 20.02339 27.99811 -22.82753 20.33092 28.59649 -20.85482 21.73914 28.03761 -21.54364 22.23439 27.85562 -22.26048 22.00522 27.48744 -22.73599 21.51742 27.17079 -22.85069 20.93241 26.17777 -22.79241 21.67210 27.13896 -20.80618 22.81973 25.20728 -22.62564 22.41556 26.18318 -21.30885 23.64078 25.89422 -22.01130 23.49060 24.43566 -22.42148 23.01668 25.44652 -22.47526 23.06169 25.65500 -20.47569 23.97180 23.60282 -22.11311 23.67620 24.21118 -19.83891 25.12654 24.41178 -20.65827 25.04418 22.83073 -19.52563 26.36698 24.02091 -21.32278 24.97269 22.36362 -20.15979 26.41168 23.50173 -21.75924 24.59905 21.24988 -20.69806 25.57819 21.68996 -20.62116 26.04126 22.01063 -21.25250 24.95750 20.78845 -4.83021 30.14515 20.66220 -5.25023 29.82250 20.44985 -5.82760 29.58581 20.26107 -6.37132 29.46358 20.02914 -7.07309 29.38226 19.77643 -7.90248 29.36014 19.56011 -8.67049 29.39127 19.40948 -9.26246 29.44418 19.25456 -9.92532 29.53010 19.10081 -10.63181 29.65855 18.94978 -11.71702 29.80161 17.11525 -13.81543 32.82055 19.11136 -12.30309 29.54571 19.37698 -12.71614 29.27194 20.37775 -0.00297 29.53154 20.79310 -0.01740 30.14642 19.14005 -0.00313 29.62202 19.71731 -0.01338 29.35699 16.27308 0.00031 32.48605 12.03045 0.00031 32.48605 6.02004 0.00031 26.47563 5.60119 0.00031 25.95040 5.30971 0.00031 25.34515 5.16022 0.00031 24.69020 5.16022 0.00031 24.01842 5.30971 0.00031 23.36347 5.60119 0.00032 22.75821 6.22134 -0.00375 22.03880 2.30026 0.00032 14.50000 2.23344 0.00032 15.05036 2.30026 0.00032 10.00000 2.03685 0.00032 15.56878 1.72190 0.00032 16.02510 1.30688 0.00032 16.39281 0.81590 0.00032 16.65052 0.27751 0.00032 16.78323 -0.27700 0.00032 16.78323 -2.29975 -2.19968 10.00000 -1.37883 -2.19331 8.50335 1.41852 -2.18136 8.50477 2.10002 -2.18630 8.88861 2.29769 -2.19447 9.43569 2.30026 -2.19968 10.00000 3.40761 -10.99969 32.26213 1.31037 -10.99969 28.35047 -0.46236 -10.99969 24.08344 15.58798 -19.62919 16.00001 14.01899 -18.14679 5.70156 15.70020 -16.39166 12.55283 14.74955 -16.04640 13.50348 13.85454 -15.47327 14.39849 7.96479 -5.69968 20.28823 6.74123 -9.81800 21.51180 6.44189 -9.49952 21.81114 6.15404 -8.86181 22.10994 6.02004 -8.07461 22.23299 15.42370 -15.28663 32.26077 12.34679 -14.95873 28.08373 8.56765 -12.45528 30.71023 6.45156 -12.39952 27.24237 9.72782 -15.05955 23.61679 13.13618 -17.59838 20.42720 4.79622 -12.34811 23.80454 7.35380 -14.73762 19.06053 3.31448 -12.27908 19.90973 11.06191 -17.03690 16.10121 13.38918 -18.54927 11.10373 5.79650 -14.29902 15.81470 2.03309 -12.17345 15.57590 2.30026 -12.41869 14.50000 9.32602 -16.29676 11.64081 11.69067 -17.19778 6.20607 4.45563 -13.76030 8.99365 2.30026 -12.71350 9.36676 7.94874 -15.40209 7.06859 2.30026 -12.66151 4.17625 2.30026 -5.99968 14.50000 2.29793 -6.49553 9.45545 1.35699 -6.49441 8.50294 -1.36301 -6.49383 8.50312 1.99340 -6.48360 8.76972 6.02004 -8.07460 26.47563 5.60269 -8.07460 25.95279 5.31731 -8.07460 25.36661 5.16495 -8.07460 24.72981 5.15527 -8.07460 24.06573 5.29752 -8.07460 23.39903 5.59000 -8.07460 22.77616 5.67436 -9.66423 22.90162 6.56361 -10.39752 21.79491 6.50046 -10.93473 22.15886 5.54018 -10.15569 23.95549 6.54932 -11.42115 22.59444 6.71143 -11.83646 23.08673 5.83148 -10.48407 25.04061 6.98741 -12.15973 23.61970 7.36413 -12.36337 24.15833 6.10162 -9.14249 26.39405 6.33935 -10.15108 26.15632 6.71724 -11.05583 25.77843 7.21442 -11.82133 25.28125 7.82302 -12.43309 24.67265 14.49035 -18.02280 17.06124 14.08940 -17.80055 16.48175 13.84051 -17.51784 16.00992 13.66921 -17.10376 15.50943 13.61620 -16.65177 15.09981 13.67642 -16.05519 14.68299 16.09159 -18.85471 14.28276 15.48012 -17.78049 13.34021 13.83343 -12.43310 30.68306 12.03045 -8.07460 32.48605 13.21518 -11.80923 31.30131 12.70999 -11.02191 31.80650 12.33751 -10.11270 32.17899 12.10930 -9.12466 32.40720 0.00017 -11.18913 19.04367 -0.07636 -11.28434 16.80126 0.51040 -11.45072 16.74271 1.36779 -11.78772 16.34721 1.75114 -11.99076 15.99144 2.55636 -11.72720 21.34207 0.96721 -11.61329 16.58686 1.51737 -11.18120 23.97203 4.38211 -11.72720 26.07352 3.53360 -11.18120 28.57726 6.74065 -11.72720 30.53659 6.07224 -11.18120 32.91625 5.79498 -8.75979 -8.48914 4.75562 -5.59203 -10.16755 5.21512 -3.95656 -10.43944 5.21100 -5.29716 -9.87301 5.21083 -6.45814 -9.39645 5.21100 -7.77663 -8.83888 5.21083 -2.71436 -8.73502 5.20335 -6.40573 -7.44081 5.21083 -1.68769 -7.07251 5.21083 -5.34324 -6.28935 5.21083 -0.88467 -5.29113 5.21083 -4.46593 -4.85772 5.21083 -0.31883 -3.42087 5.21083 -3.82337 -3.30645 5.21083 -3.43141 -1.67378 5.21083 -3.29968 0.00000 5.10653 -8.62178 -8.75725 5.56788 -9.22203 -8.36798 7.94215 -9.49526 -8.74051 4.67872 -7.97769 -9.10891 4.65165 -6.42327 -9.95996 4.67074 -4.85293 -10.53828 4.77767 -3.38496 -10.84128 4.68751 -1.54675 -8.49245 4.52895 -2.93278 -10.93212 2.01772 -6.48097 1.21031 1.40157 -6.49028 1.49474 -2.29975 -6.49968 0.00000 0.00025 -6.49968 1.50000 0.00025 -6.49968 0.00000 5.21083 0.00032 0.02374 2.30025 -3.94129 -10.59821 2.30025 -1.96335 -10.94992 2.30025 -5.81076 -9.92661 2.30025 -7.52813 -8.95549 2.30028 -0.53686 -8.14925 2.30025 -9.04393 -7.71366 2.30025 -10.29997 -6.25601 2.30025 -11.27331 -4.62133 2.30026 -11.93863 -2.86299 2.31554 0.01654 -3.92799 2.29917 -6.49742 0.52470 7.08376 -13.40058 -2.55378 4.55497 -12.84383 -1.73479 2.30026 -12.28110 -1.05125 6.95038 -14.37706 2.40711 3.51229 -13.13803 3.88574 17.23772 -3.05346 -10.96484 17.22123 -1.64601 -8.41793 16.19582 -6.67250 -7.99257 16.20164 -3.87406 -8.52431 16.19854 -5.91443 -7.05483 16.20295 -5.21217 -6.09825 16.20301 -3.46626 -7.26002 16.21576 -4.45627 -4.43459 16.20633 -3.06177 -5.94199 16.20823 -2.70407 -4.54707 16.20252 -3.79117 -2.54031 16.20536 -2.43660 -3.05217 16.19454 -3.58016 -1.05027 16.22372 -3.54935 -0.03475 16.19878 -2.29308 -1.47719 16.20554 -2.27144 0.00000 16.18242 -3.40822 -11.02234 16.20020 -2.61073 -9.88014 16.24841 -1.38861 -7.11042 16.20554 -8.50857 -9.78224 13.68469 -14.26965 -4.67986 10.07449 -13.24681 -5.12991 10.33482 -12.33418 -6.62455 13.77124 -13.24650 -6.43772 10.65601 -11.20818 -7.94220 11.03062 -9.83635 -9.10342 14.00948 -11.86053 -8.03451 15.68676 -10.02945 -9.58227 13.70732 -10.13295 -9.30498 16.19149 -7.38475 -10.66328 16.37179 -9.38429 -9.92920 9.88299 -13.91818 -3.49885 15.15664 -16.66497 0.00675 10.51843 -15.63732 1.33570 12.79545 -16.31463 0.77952 0.00025 -2.19968 1.50000 1.40112 -2.19185 1.49555 1.91201 -2.18626 1.29956 2.28986 -2.16860 0.71338 2.28722 -1.81631 -0.79531 0.00025 -2.19968 0.00000 2.27369 -2.19633 -0.16033 2.29455 -1.26716 -0.99756 -2.31627 -2.09971 -0.45267 17.70000 8.17118 -6.31601 17.46791 10.46586 0.40569 17.63077 10.52348 0.25819 18.27831 10.98081 1.47328 17.80645 10.63646 -0.01972 18.09589 10.91687 0.92456 17.94184 10.79483 0.38151 17.64867 10.12079 -0.44574 17.70586 10.24945 -2.09050 17.70026 9.79379 -3.02495 17.70000 9.01431 -5.27042 17.70000 9.62212 -4.30024 17.70026 9.00032 -3.32455 17.69255 9.02092 -0.82216 17.15031 0.00032 0.00000 17.58226 0.00032 -4.95371 17.22123 -0.61647 -5.65773 17.21782 0.00058 -2.76681 16.29574 0.01833 0.00993 16.26741 -0.45891 -4.49720 16.20050 0.00032 -1.73224 16.20426 -0.28531 -3.35202 16.75961 6.80614 0.12598 17.91330 7.12353 -8.09598 17.91993 4.97721 -9.56275 17.91993 2.56215 -10.47151 17.83099 10.86485 1.34915 17.28860 10.70415 0.94975 16.71546 9.70102 0.11945 17.68258 0.41522 -10.32301 17.70026 1.74768 -10.09996 17.70026 2.74612 -9.87538 17.70026 -1.22318 -9.62565 17.70026 3.79540 -9.52155 17.70026 4.86644 -9.02127 17.70026 5.92604 -8.36351 17.70026 -0.55721 -8.19759 17.70071 6.93745 -7.57631 17.70026 0.00032 -6.72384 17.69897 6.92263 -0.90658 17.70000 6.04312 -0.72010 17.70026 5.18110 -0.25902 18.28079 10.77432 -2.24156 18.28946 10.09972 -4.35492 18.28100 9.49011 -5.56272 18.28100 8.71467 -6.71269 18.28100 7.47546 -8.13674 18.45026 5.90116 -9.28333 18.45026 4.61769 -9.98397 18.45026 3.34297 -10.47982 18.45026 2.12328 -10.79319 18.45026 0.99835 -10.95463 3.23595 9.18400 -0.00043 16.70025 9.00032 0.00000 3.21558 7.33902 0.00956 18.33503 10.99501 -0.00135 18.43223 10.99463 1.94478 3.26448 10.99998 1.82654 3.17098 10.89998 1.30252 17.70025 0.00032 0.00000 26.31675 0.00470 11.43305 37.50025 0.00032 21.00000 8.00662 0.00032 20.25200 37.40801 0.00032 20.14593 26.40025 0.00032 6.00000 26.40025 11.00032 0.00000 26.40025 1.72095 -10.86460 26.40025 3.39927 -10.46170 26.40025 4.99391 -9.80123 26.40025 6.46557 -8.89947 26.40025 7.77821 -7.77845 26.40025 8.89931 -6.46590 26.40025 9.80128 -4.99411 26.40025 10.46189 -3.39934 26.40025 10.86488 -1.72086 -0.81539 0.00032 16.65052 -1.30637 0.00032 16.39281 -1.72139 0.00032 16.02510 -2.03634 0.00032 15.56878 -2.29975 0.00032 10.00000 2.61186 10.99627 0.89393 -3.23746 10.99975 1.76076 -0.05217 10.99998 3.21228 -21.20044 10.99998 11.01760 -33.80920 11.00183 14.35474 -2.31910 -1.65903 -0.89958 -2.30683 5.29970 -0.98680 2.30025 0.00032 -1.00000 2.30887 7.50036 -0.98330 -2.32838 9.09664 -0.96652 2.34565 9.21986 -0.94771 3.30625 9.92307 0.20287 16.80244 10.21738 0.39946 3.30676 10.56971 0.72336 -2.48352 10.76608 0.16776 2.30311 9.91917 -0.77643 -2.32170 10.08648 -0.69673 2.54243 10.73518 0.23922 2.55547 7.50180 -0.29983 2.60148 8.99936 -0.25305 2.59315 9.78928 -0.15288 3.40026 0.00032 0.00000 5.15499 0.00226 -2.32482 5.07386 0.00032 -3.17214 4.39345 0.02717 -3.11124 4.96766 -0.61587 -5.85920 17.31603 10.44393 0.51952 17.18981 9.87308 0.04523 17.26482 9.02818 -0.14886 41.70798 3.88144 30.84089 41.23909 3.51172 30.85783 40.68318 3.30035 30.86492 41.67065 2.00021 22.58901 40.82568 1.72519 23.15766 41.67065 3.29589 25.50531 41.61946 3.73011 28.65680 40.82568 2.83887 25.81909 40.92420 3.26715 28.67481 37.50006 3.92558 32.07094 37.50021 3.75936 32.92620 37.50026 3.23185 35.25445 37.50909 3.57046 33.79903 40.09034 3.37438 30.86365 37.50025 2.19422 22.05424 37.40435 0.73243 20.14508 39.83923 2.33243 24.11969 39.83923 2.94015 25.74439 37.50025 3.32473 24.15276 38.71609 3.23855 25.05828 39.83924 3.25593 27.19051 37.49462 3.94249 26.10386 40.01752 3.32974 28.77477 37.50026 4.21362 27.70216 38.53032 3.82532 31.03299 37.50026 4.26847 29.53542 37.50026 4.06082 31.35496 17.34274 6.79722 -0.13387 17.06789 10.45824 0.64087 42.00000 4.60716 30.81112 -15.61547 11.00031 37.17566 41.94769 0.00032 19.36700 38.07147 0.00032 19.68669 41.71842 -0.00575 20.01340 38.97182 0.00032 20.13456 39.72058 0.01237 20.58066 41.14101 -0.02315 20.67498 40.32361 -0.00980 20.87783 37.50026 0.00031 43.27423 40.88453 0.00680 45.22026 33.25978 0.00031 41.06781 39.00605 10.99998 50.90359 42.00026 -3.32900 61.75028 42.00026 -2.68931 58.80986 42.00026 -2.01866 56.14603 42.00026 -1.33825 53.73418 42.00026 -0.66312 51.54675 42.00000 0.01941 49.44596 42.00026 0.90463 46.98812 42.00026 1.27223 45.99088 42.00026 2.64223 42.40155 42.00026 3.26882 40.78413 42.00026 3.80804 39.20901 42.00026 4.26056 37.45741 42.00000 4.41831 35.70791 40.77634 1.29834 41.78915 37.50026 2.06831 38.47019 37.50026 2.36053 37.78061 39.12905 2.10223 39.00675 40.75076 1.88919 40.25132 37.50026 1.77210 39.16007 40.80231 0.65552 43.46875 37.50026 1.47398 39.84914 37.50026 1.17579 40.53640 37.50026 0.87904 41.22108 37.50026 0.58421 41.90436 37.50026 0.29134 42.58809 37.86468 -1.28829 46.67346 40.95145 -1.31296 49.00164 40.88810 -2.05795 51.15122 40.90550 -2.78022 53.51790 40.92114 -3.49185 56.08374 40.93563 -4.22286 59.06838 38.00026 -4.32987 56.00669 40.94827 -4.89696 62.31456 40.99276 -6.27097 69.45977 39.56744 -6.94584 69.68526 34.57989 -2.49604 47.51219 31.27980 -8.57772 66.95869 31.61232 -6.53616 57.16276 40.39569 3.10140 35.40694 39.23923 3.58346 31.84345 40.61332 2.37786 38.01182 37.50026 2.82658 36.56092 40.81791 3.10269 35.64899 41.35299 2.08151 40.32795 41.38855 3.32110 35.68161 41.89888 2.68740 40.56076 41.78449 3.78594 35.75152 41.42602 0.11571 45.58865 41.92104 0.68990 45.90020 34.05500 -10.99969 74.02666 40.05586 -10.39787 74.10013 39.10843 -10.81996 74.49616 36.98519 -10.49187 73.65433 40.50635 -9.57438 73.47955 34.98815 -10.54967 73.19110 40.75598 -9.05269 73.03568 33.17701 -10.60156 72.65685 40.74006 -8.17370 72.10387 33.82185 -9.33063 71.18475 40.78117 -7.47096 71.16954 40.90627 -6.78083 70.13556 33.58817 -8.44890 69.18834 41.62707 -0.92331 48.99154 41.68417 -3.34011 57.58210 41.73455 -5.01147 66.37407 41.13453 -8.96965 73.12192 41.55864 -6.34840 70.15401 41.40157 -8.82005 73.27260 41.60799 -8.70256 73.39328 41.87943 -5.99443 70.34272 41.74710 -8.55435 73.54313 41.88245 -8.39852 73.70244 41.01022 -9.77275 73.81819 35.06305 -10.90893 73.79314 -10.39859 0.00693 33.55040 -9.72471 0.00914 33.46120 -9.21055 0.02211 33.70504 -3.90136 0.00031 41.24135 -19.54399 11.00031 39.92645 -34.39244 11.00066 18.74107 -9.87971 11.00031 45.36718 4.37943 10.99998 41.38831 -16.99974 11.00031 50.35270 -19.99974 0.57544 58.42723 -19.99974 -0.62254 58.42270 -19.99974 -1.83460 58.18477 -19.99974 -3.07323 57.68963 -19.99974 -4.33871 56.89842 -19.99974 -5.60764 55.77402 -19.99974 -6.84118 54.29290 -19.99974 -7.99843 52.44462 -19.99974 1.78033 58.20071 -19.99974 3.01323 57.72005 -19.99974 4.28182 56.94114 -19.99974 5.56375 55.81977 -19.99974 6.81651 54.32781 -19.99974 7.99879 52.44454 -19.94339 8.57903 52.41385 -19.76470 9.16436 52.28873 -19.45675 9.72167 52.07311 -19.01309 10.22437 51.76245 -18.43685 10.63370 51.35896 -17.75019 10.90493 50.87816 -20.97570 6.66662 53.13668 -21.76647 5.15921 53.69040 -22.34637 3.51567 54.09644 -22.70031 1.77899 54.34427 -22.81889 -0.00457 54.42730 -22.69871 -1.79026 54.34315 -22.34294 -3.52745 54.09404 -21.76038 -5.17257 53.68612 -20.96898 -6.67675 53.13198 -34.89827 10.93751 20.04466 -21.02757 10.85019 40.96526 -35.94353 10.52684 22.15638 -22.47069 10.40390 41.97574 -23.83393 9.67363 42.93029 -36.26926 10.29696 23.00828 -36.98425 9.50867 24.39764 -37.54630 8.92159 25.43555 -25.08009 8.67930 43.80286 -37.79276 8.57469 25.87786 -38.32590 7.55097 26.86637 -26.17513 7.44804 44.56963 -38.86015 6.57738 27.71235 -27.08917 6.01347 45.20964 -39.62720 5.08638 28.24946 -27.79724 4.41473 45.70544 -40.18956 3.46510 28.64323 -28.28000 2.69548 46.04348 -28.60279 0.00031 46.16705 -28.44713 -2.03133 46.05942 -27.98740 -3.99307 45.73752 -27.15089 -5.95878 45.22412 -26.18835 -7.46677 44.55591 -25.04080 -8.75295 43.74731 -23.81610 -9.68477 42.91781 -22.44876 -10.41244 41.96039 -21.00856 -10.85341 40.95195 -19.55254 -11.00203 39.92435 -3.97840 -2.99969 41.23504 -6.78160 8.39193 43.19787 -12.98907 0.00031 47.54439 -7.71932 9.42093 43.85447 -5.94083 7.17651 42.53284 -3.97840 -10.99969 41.23504 -16.99974 -10.99969 50.35269 -17.49796 -10.95803 50.70154 -17.99345 -10.83033 51.04849 -18.44906 -10.62637 51.36751 -18.85875 -10.35427 51.65438 -8.75665 10.29449 44.58081 -19.22317 -10.01373 51.90955 -19.54042 -9.59498 52.13169 -19.78990 -9.10196 52.30639 -19.94936 -8.54718 52.41803 -11.19383 6.33192 34.07961 -10.53331 -10.99969 33.61710 -10.50889 4.72718 33.60001 -13.11352 9.07640 35.42378 -14.30466 10.15367 36.25784 -19.54399 0.00031 39.92645 -12.06864 7.79271 34.69215 -5.21253 5.84098 42.12601 -4.69914 4.61927 41.82664 -9.84612 3.17395 33.60001 -4.37969 3.41569 41.53366 -4.11728 2.24397 41.40826 -9.45415 1.59322 33.60001 -4.00320 1.10051 41.28574 -30.48229 -11.00002 24.31037 -0.27107 -10.99969 68.60693 -2.66889 -10.99969 58.10773 14.65039 -10.99969 57.10164 11.95373 -10.99924 54.07259 11.26303 -11.00247 52.76604 10.93462 -11.00078 51.02586 10.92849 -10.99944 48.99999 11.21852 -10.99969 46.78522 11.69197 -10.99969 44.64636 12.28615 -10.99969 42.55486 8.89405 -10.99969 39.42823 -9.14861 -11.00002 33.85215 5.89719 -10.99969 35.93079 -9.23438 -10.99969 31.98065 -10.03276 -11.00002 33.42924 -9.56210 -11.00002 33.51434 9.64666 -11.72720 34.63951 9.14133 -11.18120 36.89913 -9.14059 -2.99969 33.86267 -2.59805 5.30170 -0.25484 -2.55236 8.99997 -0.30389 -2.59264 9.78984 -0.15267 -16.47413 10.36967 0.38117 -15.65766 9.70758 -0.00211 -15.94733 9.65974 -0.31978 -14.94063 8.91659 -0.05852 -15.17003 8.85892 -0.15302 -15.33845 8.81154 -0.32358 -15.48324 8.77052 -0.51663 -15.54072 8.75496 -0.66610 -15.08167 7.93320 -0.17256 -15.41384 7.93282 -0.57848 -15.24522 5.30287 -0.29857 -16.91968 10.57752 -0.00234 -17.79844 10.99998 -0.00251 -15.55918 8.56459 -0.96405 -15.88354 9.44507 -0.80491 -15.90167 8.69561 -3.82647 -16.91649 9.68695 -3.50190 -15.90167 6.98317 -6.44125 -17.00111 7.33618 -7.64990 -15.90167 4.51484 -8.35877 -17.00111 4.69491 -9.50245 -15.90167 1.55781 -9.37146 -17.00111 1.61866 -10.47457 -17.00111 -1.60754 -10.47620 -15.90167 -1.56781 -9.36968 -3.30688 9.55089 0.05247 -15.34548 9.84637 0.19977 -3.30590 10.27285 0.43030 -15.92924 10.33615 0.42252 -17.27900 10.99998 1.29352 -3.30505 10.99998 1.06111 -18.50000 10.34273 -3.49773 -18.49975 8.53493 -6.93976 -18.49975 7.30819 -8.22161 -18.49975 5.89133 -9.28956 -18.49975 4.32120 -10.11582 -18.49975 2.63864 -10.67892 -18.49975 0.88750 -10.96417 -18.49975 -0.88677 -10.96417 -2.29975 -1.19968 -1.00000 -2.29975 4.68862 -0.95294 -14.65761 8.99585 -0.00238 -14.53943 8.47437 0.00048 -14.58253 7.93702 -0.00659 -3.21332 9.00074 0.00555 -14.58696 5.30010 0.00507 -3.19026 5.30140 0.00492 -15.49975 -0.00600 -7.99999 -15.49975 1.43289 -7.87068 -15.49975 2.82533 -7.48459 -15.49975 4.12550 -6.85439 -15.49975 5.29115 -6.00059 -15.49975 6.28421 -4.95102 -15.49975 7.07219 -3.74014 -15.49975 7.62971 -2.40674 -15.49975 7.93757 -0.99999 -15.49562 5.30014 -0.88210 -15.49975 0.08440 -0.89750 -21.19975 -10.99968 0.00000 -21.19975 10.85058 -1.80882 -21.19975 -10.84930 -1.81268 -21.19975 10.40543 -3.56842 -21.19975 -10.40283 -3.57412 -21.19975 9.67698 -5.23089 -21.19975 -9.67123 -5.24035 -21.19975 8.68505 -6.75095 -21.19975 -8.67606 -6.76168 -21.19975 7.45665 -8.08721 -21.19975 -7.44421 -8.09809 -21.19975 6.02522 -9.20329 -21.19975 -6.00708 -9.21472 -21.19975 4.42972 -10.06877 -21.19975 -4.40793 -10.07806 -21.19975 2.71362 -10.66010 -21.19975 0.92363 -10.96118 -21.19975 -2.68749 -10.66656 -21.19975 -10.99968 12.00000 -21.19975 11.00032 0.00001 -18.49975 11.00032 0.00001 -2.69517 11.00598 1.04604 -21.28766 0.02173 11.85503 -21.20026 0.00145 11.01392 -21.19975 -0.89245 -10.96371 -15.53830 -5.19961 -0.89828 -15.49975 -7.63069 -2.40161 -15.54911 -8.07651 -0.98458 -15.49975 -7.07442 -3.73471 -15.49975 -6.28827 -4.94506 -15.49975 -5.29690 -5.99495 -15.49975 -4.13314 -6.84941 -15.49975 -2.83463 -7.48085 -15.49975 -1.44397 -7.86854 -2.25981 -2.41399 0.05523 -2.29975 -1.64968 10.00000 -18.50000 -10.25767 -3.32631 -18.49975 -10.97317 -0.76321 -18.49975 -10.99968 0.00000 -18.49975 -8.53429 -6.93977 -18.49975 -7.30755 -8.22161 -18.49975 -5.89069 -9.28955 -18.49975 -4.32055 -10.11584 -18.49975 -2.63804 -10.67891 -17.27788 -10.65702 0.00003 -17.36909 -10.78195 0.72198 -17.00000 -9.92136 -3.43190 -16.07855 -9.68662 -0.56021 -16.69233 -10.37179 0.09989 -15.90167 -8.69931 -3.81660 -17.00000 -9.28786 -5.08864 -15.90167 -6.98984 -6.43331 -17.00111 -7.32789 -7.65723 -15.90167 -4.52369 -8.35363 -17.00111 -4.68476 -9.50714 -2.28917 -2.16863 9.28612 -1.91132 -2.18628 8.70035 -2.30004 -11.00044 14.49992 -17.60893 -10.97441 1.55585 -2.29975 -10.99968 2.00000 -2.01710 -6.48071 8.78909 -2.29892 -6.49807 9.48267 -14.49975 -6.33126 0.00000 -3.29975 -5.19968 0.00000 -14.66082 -7.92152 0.00184 -14.67584 -8.98036 -0.00246 -2.29975 -8.99968 0.00000 -2.29975 -10.90406 1.38899 -2.29975 -10.61666 0.82298 -2.29975 -10.17759 0.38367 -2.29975 -9.61116 0.09577 -15.35954 -9.81387 0.16855 -16.29393 -10.41649 0.56215 -16.80311 -10.67837 0.91532 -15.30478 -8.81331 -0.28651 -15.68901 -9.70580 -0.04810 -15.13338 -7.93045 -0.23264 -15.10497 -5.20571 -0.14487 -22.15526 0.00736 11.99910 -33.79974 11.00032 0.00001 -30.79975 11.00032 0.00001 -30.79928 10.99949 11.01066 -22.16006 10.99998 11.99840 -29.84198 10.99384 11.99812 -30.59873 10.98676 11.61279 -33.88254 11.00032 15.89547 -34.09110 11.00032 17.35023 -36.79974 -0.00779 -7.99999 -36.79974 -1.39740 -7.87694 -36.79974 1.38282 -7.87963 -36.79974 2.73173 -7.51926 -36.79974 -2.74417 -7.51450 -36.79974 3.99724 -6.92997 -36.79974 -4.00772 -6.92355 -36.79974 5.14114 -6.12959 -36.79974 -5.14931 -6.12219 -36.79974 6.12841 -5.14261 -36.79974 -6.13455 -5.13452 -36.79974 6.92918 -3.99884 -36.79974 -6.93295 -3.99121 -36.79974 7.51870 -2.73384 -36.79974 -7.52079 -2.72634 -36.79974 7.87958 -1.38464 -36.79974 -7.88005 -1.37831 -36.79974 -7.99968 0.00001 -36.79974 8.00032 0.00001 -36.81443 -0.00809 12.38539 -36.80211 -3.57614 12.74254 -36.79083 -7.04813 13.76281 -36.79802 -8.00355 14.36795 -36.79670 3.53228 12.70869 -36.79967 7.13470 13.80729 -36.79974 8.00032 14.35488 -30.79856 -11.00002 11.02333 -30.79975 -10.99968 0.00000 -30.79975 -10.84952 -1.81137 -30.79975 10.85039 -1.80994 -30.79975 10.40469 -3.57057 -30.79975 -10.40324 -3.57295 -30.79975 9.67536 -5.23388 -30.79975 -9.67312 -5.23685 -30.79975 8.68226 -6.75453 -30.79975 -8.67907 -6.75782 -30.79975 7.45247 -8.09107 -30.79975 -7.44809 -8.09452 -30.79975 6.01951 -9.20702 -30.79975 -6.01360 -9.21047 -30.79975 4.42244 -10.07197 -30.79975 -4.41473 -10.07508 -30.79975 2.70481 -10.66234 -30.79975 -2.69563 -10.66450 -30.79975 -0.90320 -10.96282 -30.79975 0.91344 -10.96202 -29.86834 -11.00002 11.99649 -33.79974 -10.99968 0.00000 -33.79974 -10.47466 -3.50000 -33.79974 -8.52034 -6.95690 -33.79974 -7.29403 -8.23361 -33.79974 -5.87881 -9.29708 -33.79974 -4.31131 -10.11978 -33.79974 -2.63219 -10.68035 -33.79974 -0.88477 -10.96432 -33.79974 0.88549 -10.96432 -33.79974 2.63279 -10.68035 -33.79974 4.31196 -10.11976 -33.79974 5.87945 -9.29708 -33.79974 7.29467 -8.23361 -33.79974 8.52097 -6.95689 -33.80000 10.20262 -3.50128 -33.79974 10.97460 -0.75180 -35.39380 10.77261 21.17247 -40.53284 1.75501 28.88359 -40.64822 0.00008 28.96439 -40.53275 -1.75507 28.88353 -40.18940 -3.46507 28.64311 -39.62696 -5.08633 28.24928 -38.85982 -6.57728 27.71213 -37.50930 -8.97024 25.36487 -36.64715 -8.81307 26.97615 -35.21536 -9.88050 25.97359 -35.78766 -10.70378 22.41512 -33.65039 -10.60402 24.87779 -34.58218 -10.99969 19.69899 -39.02973 4.63813 17.88104 -38.32103 7.12673 19.06549 -38.93689 7.18572 20.70181 -38.75257 2.72742 17.02576 -39.97427 3.83272 18.59786 -40.54150 5.53276 21.42246 -38.65963 8.35522 23.49710 -40.50451 5.92099 24.85538 -38.76624 8.03745 24.72670 -40.83186 2.04116 19.19834 -38.70994 -0.01001 16.61257 -41.76626 2.94589 22.28004 -41.63396 3.10566 25.64623 -42.02340 0.00708 25.91892 -42.19225 0.00362 22.57833 -41.12955 -0.00178 19.40678 -41.63728 -3.09212 25.64855 -41.76810 -2.93905 22.28134 -40.83067 -2.04447 19.19751 -38.65361 -2.75281 16.83338 -40.51082 -5.90924 24.85980 -40.34552 -5.52707 21.42490 -39.97205 -3.83528 18.59630 -39.45963 -7.33046 24.22604 -38.28183 -8.52112 24.55591 -38.99642 -6.80644 20.06092 -38.72624 -8.31356 23.17014 -38.64497 -5.09668 17.59837 -38.54078 -6.84553 19.16334 -36.82760 6.86990 14.41475 -37.17046 8.97825 18.08128 -36.94878 0.00125 13.50852 -36.88181 3.44134 13.53779 -36.99055 6.43146 15.16719 -37.03085 3.32365 14.13066 -37.36453 0.00043 14.74739 -37.29959 8.25182 17.84787 -37.22893 3.20819 14.71187 -37.27509 6.01377 15.88422 -37.49868 3.09749 15.26969 -37.46149 8.89192 19.55737 -38.01134 -0.00703 15.81520 -37.57735 5.71607 16.39530 -37.59179 7.81341 18.20928 -37.81487 2.99184 15.80113 -37.87581 8.75508 20.77563 -37.72676 9.17571 21.41618 -37.93076 5.43082 16.88494 -37.93949 7.38716 18.56073 -38.15658 8.82061 23.43724 -38.32058 2.86247 16.45827 -38.29770 8.20162 20.97428 -38.23787 8.66316 24.26986 -38.35055 5.17675 17.32110 -37.87741 8.82850 25.08818 -36.39843 -9.49824 0.00001 -36.69753 -8.77614 0.00001 -35.29974 -10.59776 0.00000 -34.57621 -10.89746 0.00000 -36.39861 -8.92548 -3.24872 -35.92107 -10.12100 0.00000 -36.39861 -7.27606 -6.10560 -35.29974 -7.48949 -7.49813 -36.39861 -4.74900 -8.22605 -35.29974 -4.80793 -9.44456 -36.39861 -1.64910 -9.35433 -35.29974 -1.65636 -10.46778 -35.29974 1.65716 -10.46775 -36.39861 1.64974 -9.35433 -35.29974 4.80872 -9.44449 -36.39861 4.74964 -8.22605 -35.29974 7.49025 -7.49800 -36.39861 7.27670 -6.10560 -35.30000 9.69700 -3.48610 -36.39861 8.92612 -3.24872 -36.72453 8.66788 0.00001 -36.47666 9.34764 -0.00175 -36.14523 9.87079 0.00001 -35.67022 10.34581 0.00001 -35.19560 10.63941 -0.00103 -34.46731 10.92510 0.00001 -34.93652 10.77807 14.35292 -35.58376 10.41524 14.35459 -36.21264 9.77333 14.35911 -36.54551 9.21337 14.35887 -36.74974 8.52429 14.35802 -35.68760 10.64610 18.53470 -36.53004 10.03759 18.28289 -36.51375 10.32512 21.99279 -36.95128 10.04975 21.78611 -37.38790 9.67667 21.55380 -30.54963 -11.00002 11.66703 -34.03627 -10.99969 16.91241 -33.79976 -10.99968 14.35430 -36.85474 -0.00069 12.86618 -36.83413 -6.80393 14.48792 -36.85308 -8.25110 15.52941 -36.85374 -3.46387 13.32596 -36.98067 -3.33462 13.98189 -37.07059 0.00082 13.92410 -36.94965 -8.46890 16.47707 -36.98058 -6.44915 15.09952 -37.21180 -8.51306 17.67779 -37.17058 -6.12276 15.66230 -37.26193 -3.17345 14.80018 -37.16951 -8.87374 17.99792 -37.42837 -9.10094 19.63635 -37.50796 -5.75593 16.29498 -37.60750 -7.75384 18.23819 -37.65326 -3.02726 15.54314 -37.73828 -9.15561 21.34811 -37.91945 -5.42590 16.86414 -38.33669 -8.16650 21.07707 -38.10238 -2.90063 16.18632 -38.15025 -7.16990 18.72191 -38.38188 -5.17725 17.33242 -38.70362 -7.76277 21.09305 -36.79264 -10.16235 21.86770 -35.07729 -10.92664 19.09569 -35.45325 -10.78913 18.51328 -35.89947 -10.55703 18.41645 -37.38953 -9.68077 21.55745 -36.47078 -10.08791 18.29237 -37.06798 -9.19611 18.17721 -34.48074 -10.91786 14.35772 -34.34378 -10.99937 17.05172 -35.15562 -10.66385 14.35444 -35.06882 -10.81567 16.93250 -35.53715 -10.59231 16.85389 -35.98821 -10.04511 14.35748 -36.15683 -10.12153 16.75027 -36.41797 -9.45354 14.35339 -36.76658 -9.26479 16.64902 -36.69753 -8.77615 14.35431 -35.29974 -9.68938 -3.36010 -2.29974 -11.00234 16.69960 -1.44589 -11.04272 16.30637 -2.29974 -10.99968 17.78291 -1.46361 -10.99969 21.00946 -2.29974 -1.03093 14.50000 -21.40210 10.99998 11.61420 -2.29974 0.00032 14.50000 -2.23293 0.00032 15.05036 13.08471 -11.72125 38.31503 14.12754 -11.52959 38.50729 12.68278 -11.15350 40.65638 13.74406 -10.89054 40.62271 15.60446 -9.66423 32.83173 14.55059 -10.15569 32.96590 13.46548 -10.48407 32.67461 12.53120 -10.58549 31.98529 15.75026 -8.07460 32.90340 15.16408 -8.07460 33.18877 14.52727 -8.07460 33.34113 13.86319 -8.07460 33.35080 13.19649 -8.07460 33.20856 12.57363 -8.07460 32.91608 16.27308 -8.07461 32.48605 16.32271 -8.59969 32.43642 16.57858 -9.28281 32.18708 10.92894 -12.52152 33.74552 14.00826 -13.53416 34.81595 13.47464 -12.60679 36.32713 16.81638 -15.27418 32.40680 15.12647 -14.03560 34.29334 14.01890 -12.66681 36.52951 14.52405 -12.49547 36.58097 15.84711 -13.60443 34.37605 15.89327 -12.56954 34.95237 11.36593 -10.94797 48.99925 31.13271 -10.95601 72.55887 27.47768 -10.76175 70.15973 30.11902 -10.68794 71.44340 23.74240 -11.00002 68.45868 27.24411 -11.00002 70.83820 28.51817 -10.99969 71.69499 30.14903 -10.99969 72.51250 31.98543 -10.99969 73.29703 14.98376 -10.93201 56.80616 18.00202 -9.76163 55.00232 17.00939 -11.00269 59.61674 24.42076 -4.89193 45.53317 18.99706 -11.00134 62.17648 20.79791 -11.00002 64.63757 22.00057 -11.00002 66.67688 27.69250 -4.34221 46.92801 22.76087 -10.99969 67.55106 25.00082 -8.35501 56.99504 26.29809 -10.03401 67.49997 31.16720 -3.36012 47.48281 12.53987 -10.94118 54.14969 14.72139 -9.78387 51.55350 20.36497 -6.03566 44.81443 17.58012 -7.99503 48.14509 22.39955 -4.32243 42.36769 25.44507 -0.81405 36.97451 24.71200 -1.22857 36.98088 24.01040 -1.59847 36.81342 11.73357 -10.92608 52.60122 11.55999 -10.87983 50.93764 15.86816 -8.36230 46.51120 23.36963 -1.92981 36.48373 20.13634 -4.13406 40.55922 22.83476 -2.21207 36.02043 22.43384 -2.43179 35.46378 11.70368 -10.78236 49.00004 12.63184 -10.60558 45.06303 12.07336 -10.70185 47.10021 14.39754 -9.20448 44.82515 21.78853 -2.89039 34.14164 13.97252 -10.52930 40.97762 13.67023 -10.47681 41.96799 13.28852 -10.51060 43.04075 18.38548 -6.26749 37.94861 21.33570 -3.40360 32.89510 20.99578 -4.04728 31.53897 14.26397 -10.65805 39.96035 15.06748 -11.44301 37.17268 14.81115 -11.12672 38.02728 14.54371 -10.86076 38.96341 17.21881 -8.33919 35.85537 15.31516 -11.79939 36.40387 16.64741 -13.38308 33.52111 16.77633 -10.93123 34.08897 21.10985 0.00031 32.06593 21.65439 0.00031 33.81062 22.43384 0.00031 35.46378 22.77413 0.00031 35.95178 23.20424 0.00031 36.36321 26.92183 -0.00352 36.82514 15.74787 0.00031 32.90489 12.55568 0.00031 32.90489 15.14261 0.00031 33.19637 14.48767 0.00031 33.34586 13.16094 0.00031 33.19637 13.81588 0.00031 33.34586 23.70720 0.00031 36.68166 25.15811 0.01660 37.00173 24.26314 0.00031 36.89453 41.21310 9.19201 96.43330 40.07596 9.96326 98.56781 41.37939 9.46742 96.43924 38.56969 9.80370 99.67536 39.20652 9.69696 99.05482 39.80162 9.56087 98.36475 40.29893 9.41038 97.67665 40.70426 9.25230 97.00842 41.22685 8.93964 95.81378 38.71717 10.68463 99.70127 39.37949 10.57362 99.05590 39.99857 10.43204 98.33804 40.51579 10.27552 97.62236 39.39767 11.04699 97.44498 40.93732 10.11112 96.92741 39.74244 11.04698 96.20253 41.27328 9.94482 96.26660 41.27329 10.02495 95.04327 39.84858 11.04698 95.04391 39.77678 11.04697 94.01063 41.13099 5.74386 90.32433 39.37206 7.94142 90.84270 39.81881 7.94142 91.62482 40.13819 7.94142 92.36639 40.35844 7.94142 93.06497 41.13102 7.19214 93.23296 42.00056 7.30184 92.42417 42.00056 6.94657 91.57980 42.00056 6.38827 90.62457 42.00056 8.25571 93.05316 42.00056 7.70610 93.46570 41.99392 8.32860 93.39331 41.98137 8.65396 94.05002 39.50283 11.01932 91.70681 39.34713 11.17865 92.90418 38.87627 11.27726 91.90456 41.37984 8.73646 95.12651 40.57038 8.64119 95.29340 41.55681 8.56278 94.71519 40.94661 8.50667 94.93190 41.33031 8.34255 94.60554 41.92306 8.79775 92.93053 41.80856 9.32990 94.73645 41.94539 8.88449 94.20363 41.75210 9.44767 94.97076 41.80140 9.23127 95.04590 41.80298 7.58719 93.89459 41.67596 7.07942 93.26062 41.68114 5.63812 90.39952 40.72712 7.83903 94.26450 41.59571 8.83116 95.13353 41.77270 8.65637 94.63448 41.74747 9.00930 95.10451 41.95660 8.26940 94.08394 41.37669 7.53031 93.96103 41.69064 8.16196 94.33179 40.49448 7.94157 93.72603 37.73840 11.17530 88.88427 34.03556 8.49697 87.00079 39.76155 5.63631 88.40635 25.58867 1.43357 87.00079 24.87012 1.27291 87.70229 24.87012 -0.00303 87.59161 25.15486 -0.00303 87.29073 25.45073 -0.00303 87.00079 24.87012 2.37196 87.98257 25.99651 2.81535 87.00079 26.65270 4.08412 87.00079 27.50056 5.99697 87.00079 28.00056 6.96932 88.11702 31.96557 8.49697 87.00079 35.42382 7.14735 87.00079 34.05057 7.94142 87.46532 34.05057 7.47344 87.00079 35.60876 7.94142 87.85355 36.69345 6.58200 87.00080 37.99923 5.63255 87.00080 39.93123 2.91600 87.00080 38.95287 4.64133 87.00080 40.36637 1.65375 87.00080 40.55040 -0.00303 87.00080 40.84626 -0.00303 87.29074 41.13099 -0.00303 87.59161 41.13099 1.27351 87.70241 41.13099 2.37288 87.98289 41.13099 3.31200 88.37459 28.00056 8.49697 87.00079 33.00006 11.39697 88.27529 24.32517 -0.00303 87.70768 24.05718 -0.00303 87.48594 24.21422 -0.00303 87.66471 24.43612 -0.00303 87.75066 24.67260 -0.00303 87.72430 41.78690 -0.00303 87.66472 41.94394 -0.00303 87.48595 41.68114 3.11934 88.42470 41.32852 -0.00303 87.72430 41.56501 -0.00303 87.75066 24.87013 -8.00303 87.59161 25.09139 -9.03460 87.35694 25.63093 -9.82743 86.83522 25.45073 -4.00303 87.00080 26.38597 -10.30840 86.21866 27.08407 -4.00303 85.72745 27.26143 -10.50303 85.61664 28.38190 -10.50303 85.01742 28.11167 -9.00303 85.14693 28.47897 -9.48780 84.97308 28.11167 -6.00303 85.14693 28.58706 -5.67444 84.92504 28.92677 -5.46536 84.78296 28.93422 -4.00303 84.77999 29.25148 -5.29607 84.65945 28.95670 -10.02226 84.77108 29.55905 -10.49865 84.55418 29.72197 -5.11393 84.50076 30.43560 -5.00303 84.30403 30.93008 -4.00303 84.19742 32.13820 -5.00303 84.03466 33.00057 -4.00303 84.00080 33.86293 -5.00303 84.03466 35.07105 -4.00302 84.19742 35.56553 -5.00302 84.30403 36.24842 -5.10488 84.49121 36.85765 -5.34857 84.69920 37.06691 -4.00302 84.77999 37.39911 -5.66466 84.91850 37.61948 -10.50303 85.01753 37.88945 -9.00303 85.14693 38.73970 -10.50303 85.61664 37.88945 -6.00302 85.14693 38.91706 -4.00302 85.72745 39.68599 -10.50130 86.22202 40.35194 -9.84937 86.81806 40.55040 -4.00302 87.00080 40.90894 -9.03650 87.35612 41.13099 -8.00303 87.59161 30.96395 -5.00303 84.67027 35.03717 -5.00302 84.67027 31.40160 -5.00303 85.13993 34.59953 -5.00303 85.13993 31.72967 -5.00303 85.69276 34.27146 -5.00303 85.69276 31.93231 -5.00303 86.30224 34.06882 -5.00303 86.30224 33.00057 -10.00303 85.00080 31.33445 -10.00303 85.05358 33.00057 -10.00303 85.40250 31.61989 -10.00303 85.47595 33.00057 -10.00303 85.74326 31.82955 -10.00303 85.94012 33.00057 -10.00303 86.01086 34.04364 -10.00303 86.43204 31.95749 -10.00303 86.43199 37.41134 -6.00302 84.98119 37.41122 -9.00303 84.98116 36.90551 -6.00302 84.94080 36.90544 -9.00303 84.94081 36.40688 -6.00302 85.02869 36.40681 -9.00303 85.02872 35.94649 -6.00302 85.23886 35.94644 -9.00303 85.23889 35.55360 -6.00302 85.55786 35.55355 -9.00303 85.55791 35.25326 -6.00302 85.96545 35.25317 -9.00303 85.96560 35.06460 -6.00302 86.43652 35.06454 -9.00303 86.43675 28.58979 -9.00303 84.98119 28.58979 -6.00303 84.98119 29.09562 -9.00303 84.94080 29.09562 -6.00303 84.94080 29.59425 -9.00303 85.02869 29.59425 -6.00303 85.02869 30.05464 -9.00303 85.23886 30.05463 -6.00303 85.23886 30.44753 -9.00303 85.55786 30.44753 -6.00303 85.55786 30.74787 -9.00303 85.96545 30.74787 -6.00303 85.96545 30.93653 -9.00303 86.43652 30.93653 -6.00303 86.43652 30.28887 -5.29592 85.04181 31.02681 -5.29592 85.86537 36.74865 -5.30497 84.66199 35.71718 -5.29592 85.03847 34.97572 -5.29592 85.86275 28.79139 -9.24625 84.91932 29.54059 -9.51198 84.86862 30.07767 -9.70493 84.92410 30.96474 -9.71013 85.75558 31.02918 -9.98200 85.01439 30.74658 -9.92569 84.99265 30.47820 -9.84499 84.97118 24.67261 -8.00303 87.72430 24.43612 -8.00303 87.75066 24.21422 -8.00303 87.66472 24.05718 -8.00303 87.48595 41.32850 -8.00302 87.72429 41.56498 -8.00302 87.75067 41.78688 -8.00302 87.66473 41.94394 -8.00302 87.48595 38.77465 -10.75303 85.55949 40.47097 -9.98157 86.87932 41.13404 -9.19326 87.46947 39.76203 -10.62444 86.18590 40.69175 -10.17119 86.83067 41.38859 -9.29184 87.43205 38.86145 -10.91940 85.41756 40.84677 -10.23448 86.72431 39.99669 -10.79865 85.96618 41.68918 -9.29155 87.14125 27.13100 -10.93604 85.40337 29.47736 -10.85658 84.42581 31.95056 -10.85241 83.89981 33.00057 -10.66970 84.02230 30.52545 -10.61703 84.28741 33.00057 -10.97928 83.70176 34.05057 -10.85241 83.89981 36.52377 -10.85658 84.42581 24.91575 -9.16382 87.46036 27.21588 -10.77336 85.54215 26.28875 -10.54603 86.21458 25.42461 -10.08604 86.87474 24.71859 -9.25626 87.46587 26.16107 -10.70809 86.13063 25.24180 -10.20360 86.79390 24.53492 -9.30571 87.39326 26.00711 -10.79692 85.97325 25.07019 -10.24095 86.64246 24.36523 -9.30825 87.23492 33.00057 -10.04902 84.66844 33.00057 -10.18686 84.38903 33.00057 -10.40319 84.16565 31.21358 -10.32127 84.33206 31.26853 -10.17210 84.66017 34.73371 -10.17210 84.66017 34.78867 -10.32127 84.33206 35.47679 -10.61703 84.28741 35.52404 -9.84499 84.97118 35.25566 -9.92569 84.99265 34.97306 -9.98200 85.01439 35.03751 -9.71013 85.75558 35.92458 -9.70493 84.92410 36.46165 -9.51198 84.86862 37.21085 -9.24625 84.91932 34.17269 -10.00303 85.94012 34.38235 -10.00303 85.47595 34.66779 -10.00303 85.05358 36.44320 -10.49865 84.55418 37.04554 -10.02226 84.77108 37.52327 -9.48780 84.97308 34.00057 -5.00303 86.93854 32.00057 -5.00303 93.26875 34.00057 -5.00303 93.26875 34.23295 -5.00303 94.09372 32.77805 -5.00303 94.02587 33.22309 -5.00303 94.02587 32.37708 -5.00303 94.21896 33.62406 -5.00303 94.21896 31.63453 -5.07242 94.00080 32.09960 -5.00303 94.56692 33.90154 -5.00303 94.56692 31.83087 -5.00303 94.92145 34.17026 -5.00303 94.92146 32.00057 -5.00303 95.00080 34.00057 -5.00303 95.00080 34.08618 -5.00303 95.44342 31.92156 -5.00303 95.45930 33.86829 -5.00303 95.49785 32.13484 -5.00303 95.50132 33.50329 -5.00303 95.86525 33.76625 -5.00303 95.88861 32.24623 -5.00303 95.89827 32.50175 -5.00303 95.86751 33.00279 -5.00303 96.00079 33.28202 -5.00303 96.13889 32.73530 -5.00303 96.14278 35.00094 -6.00302 94.00079 35.00057 -9.00303 86.93854 35.00057 -9.00303 94.00080 32.00057 -10.00303 86.93854 34.00057 -10.00303 94.00080 32.00057 -10.00303 94.00080 31.00056 -9.00303 94.00080 31.00056 -6.00303 93.96098 31.00056 -6.00303 86.93854 31.61786 -5.07915 86.93854 31.30198 -5.28749 94.00080 31.29344 -5.29593 86.93854 31.07899 -5.61481 94.00080 31.00550 -6.00303 94.14118 34.43220 -5.11040 94.23586 34.38325 -5.07915 86.93854 34.69915 -5.28749 94.00080 34.70768 -5.29592 86.93854 34.92214 -5.61481 94.00080 34.92445 -5.62034 86.93854 34.86658 -9.50305 94.00080 34.70768 -9.71013 86.93854 34.50055 -9.86907 94.00080 34.38325 -9.92691 86.93854 31.50056 -9.86905 94.00080 31.29346 -9.71013 86.93854 31.13453 -9.50303 94.00080 31.07668 -9.38571 86.93854 31.26325 -5.33823 94.18478 31.07251 -5.64578 94.15256 34.73787 -5.33821 94.18479 34.92861 -5.64577 94.15256 34.27405 -5.02203 94.50558 31.18788 -5.27567 95.41162 30.89816 -5.94570 95.54117 31.84060 -5.27567 96.45306 31.67032 -5.94570 96.71619 33.00056 -5.94570 97.17154 33.00056 -5.27567 96.85945 34.33081 -5.94570 96.71619 34.16051 -5.27567 96.45306 35.10297 -5.94570 95.54117 34.81324 -5.27567 95.41162 32.00057 -10.00303 95.50080 34.00057 -10.00303 95.50080 35.10297 -8.94570 95.54117 30.89816 -8.94570 95.54117 31.67032 -8.94570 96.71619 33.00056 -8.94570 97.17154 34.33081 -8.94570 96.71619 25.33635 4.10292 88.26276 24.87012 4.09936 88.83099 26.15790 6.16047 88.98504 24.87012 5.29650 89.82285 28.00056 7.74294 89.00079 28.00056 8.49697 89.00079 28.26272 11.26217 88.88427 28.88205 11.39697 89.68382 24.31998 5.63814 90.39954 24.31998 3.11935 88.42470 27.50056 8.49697 92.08532 27.50056 7.94142 89.74381 32.00057 -5.00303 86.93854 35.00057 -6.00302 86.93854 34.00057 -10.00303 86.93854 31.00056 -9.00303 86.93854 31.07668 -5.62035 86.93854 34.92445 -9.38571 86.93854 31.61788 -9.92691 86.93854 25.26737 7.83903 94.26450 30.42106 11.49197 99.79163 25.92516 9.96326 98.56780 27.71889 10.27446 100.34765 24.59157 9.57200 96.42619 24.61860 9.77928 96.36005 24.22178 8.65637 94.63448 24.24700 9.00930 95.10450 24.19308 9.23127 95.04589 24.19150 7.58718 93.89458 24.14427 8.20532 94.23191 24.43612 7.03771 93.27090 24.17456 9.29202 94.66216 24.24902 9.44767 94.97076 24.37461 9.63634 95.45103 24.54014 9.80788 95.89677 24.61778 7.53031 93.96102 24.44224 8.55986 94.71039 25.43079 8.64121 95.29345 24.67039 8.34236 94.60520 24.30384 8.16196 94.33179 30.45559 9.65113 100.62135 29.66201 9.49194 99.77038 29.71100 9.10508 98.62046 27.03176 9.74083 99.29839 28.15173 9.88731 100.26470 29.82490 8.69990 97.51351 26.07904 8.54095 95.21242 25.78238 9.43370 97.78474 24.61463 8.73646 95.12650 24.97374 9.09237 96.37290 30.21460 11.49697 99.47164 29.26237 11.49697 98.71239 28.51005 11.49697 97.75495 27.99730 11.49697 96.64925 27.75234 11.49697 95.45495 27.78809 11.49697 94.23913 27.97175 11.49697 93.17276 28.20463 11.49697 92.22712 28.50539 11.49697 91.41562 28.88949 11.49697 90.76318 29.13401 9.95133 100.91682 27.12495 11.27728 91.90439 26.65410 11.17867 92.90395 27.65125 11.34554 91.02052 26.49829 11.01932 91.70683 24.04909 8.88449 94.20363 24.00056 7.87464 93.62243 24.00056 8.32860 93.39330 26.62222 8.49544 94.56344 24.87012 6.30682 91.12612 24.87010 7.19214 93.23295 26.06698 7.94142 91.86849 26.41980 7.94142 91.18249 26.88909 7.94142 90.46915 26.22435 11.08882 94.01063 24.72783 10.01128 94.47569 24.72783 10.00166 95.68507 24.72783 10.02460 95.09306 26.15255 11.04698 95.04556 24.72783 9.94483 96.26659 26.25925 11.04698 96.20577 25.35801 10.22999 97.42496 25.77964 10.36962 98.04487 26.60520 11.04699 97.44958 26.28375 10.50161 98.68006 27.24331 11.04699 98.70905 27.46720 10.70933 99.86160 28.03297 10.77157 100.31409 28.19325 11.04699 99.87800 29.05452 10.83815 100.99229 29.39829 11.04698 100.82497 39.91544 8.54095 95.21242 38.24878 11.49697 95.45495 37.11116 11.49697 90.76254 37.49569 11.49697 91.41553 37.79654 11.49697 92.22728 38.02941 11.49697 93.17297 38.21304 11.49697 94.23913 36.64871 11.49697 90.29107 35.73919 11.49697 89.71020 34.69940 11.49697 89.29076 33.00057 11.49697 95.12437 33.00057 11.49528 88.98592 35.90857 11.39697 88.93648 38.34981 11.34554 91.02040 37.11908 11.39697 89.68382 33.00056 8.49697 95.00079 34.05057 8.49697 88.86504 39.58928 8.49697 95.04091 39.37226 8.49544 94.56345 39.13748 8.49697 93.95770 39.02299 8.49697 93.42587 38.84736 8.49697 92.86423 38.59385 8.49697 92.26855 38.24058 8.49697 91.64041 37.76120 8.49697 90.99002 37.12631 8.49697 90.33944 36.30628 8.49697 89.72611 35.28151 8.49697 89.20879 33.00056 8.55728 98.13480 38.76384 7.94142 90.03386 37.95638 7.94142 89.22797 38.76131 11.04699 98.70362 37.81296 11.04698 99.87298 38.09110 10.75973 100.22089 36.60886 11.04698 100.82124 36.99772 10.83605 100.96210 35.23964 11.04697 101.47259 35.57732 10.85606 101.66717 35.04660 10.85606 101.84870 33.76310 11.04697 101.80639 33.82334 10.85606 102.10032 32.24501 11.04697 101.80717 32.53990 10.85606 102.13297 35.01686 9.96856 101.74918 35.54827 9.65113 100.62135 34.30502 9.65113 101.03237 33.81138 9.96856 101.99714 31.94006 9.96856 101.96366 33.00053 9.65113 101.17181 37.49107 11.49697 97.75497 38.00381 11.49697 96.64927 36.73875 11.49697 98.71239 35.78653 11.49697 99.47164 37.96762 9.87593 100.17509 36.29012 9.10508 98.62046 36.67593 8.71842 97.57586 36.33852 9.49238 99.77200 36.44250 9.96396 101.15311 36.10963 10.38171 101.66822 34.06853 10.38028 102.29176 31.93259 10.38028 102.29176 38.28223 10.27446 100.34765 33.00056 11.48798 100.50080 35.27124 11.48798 100.01020 35.58015 11.49197 99.79154 34.13903 11.48798 100.37675 36.91229 7.94142 88.47514 30.09208 11.39697 88.93671 31.49381 11.39697 88.44625 34.50645 11.39697 88.44605 31.30160 11.49697 89.29080 30.26184 11.49697 89.71024 31.83903 11.48798 100.37675 30.72988 11.48798 100.01020 29.89149 10.38171 101.66822 29.35241 11.49697 90.29107 30.40465 9.96856 101.54812 31.69602 9.65113 101.03236 30.36637 10.85606 101.64468 31.34895 10.85606 101.95438 30.76811 11.04697 101.47488 9.72146 11.00031 54.88705 30.63460 10.99998 64.29271 -1.22348 10.99998 31.37399 2.19250 11.00015 12.22483 39.01376 10.99859 12.24816 -22.29964 11.00020 21.38510 14.33852 9.49238 103.77200 7.71100 9.10508 102.62046 14.73874 11.49697 102.71239 15.49106 11.49697 101.75497 33.00057 -5.00303 95.00080 + + + + + + + + + + -0.27653 -0.59294 0.75627 -0.22124 -0.61003 0.76087 0.87478 -0.29895 0.38129 0.89685 -0.28227 0.34057 0.11993 0.99253 0.02254 -0.55015 -0.62730 0.55121 0.85361 0.22300 0.47076 0.78945 0.37028 0.48956 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24572 0.96262 0.11395 0.24710 0.96090 0.12493 0.36884 -0.86583 0.33807 0.40262 -0.84456 0.35300 0.30819 -0.87861 0.36477 0.79235 -0.48637 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14655 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23108 0.60973 0.41632 0.67447 0.45012 -0.62955 0.63329 0.52768 -0.56847 0.63119 0.51462 -0.58327 0.62846 0.69906 0.28925 0.65394 0.69603 0.25859 0.66983 0.73326 0.39301 0.55486 0.51544 -0.63934 0.57058 0.71478 -0.44325 0.54095 0.50371 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04158 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14387 -0.94000 0.30935 0.14373 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 0.40524 0.83720 0.36725 0.40441 0.85375 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24716 0.49012 0.83244 0.25851 0.53337 0.82040 0.20604 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09072 0.58199 0.81145 0.05332 0.58209 0.81139 0.05314 0.63891 0.76804 -0.04376 0.58234 0.81175 0.04408 -0.62975 -0.61576 0.47356 -0.62713 -0.61181 0.48208 -0.67408 -0.63036 0.38504 -0.72332 -0.61625 0.31151 -0.77754 -0.57908 0.24515 -0.69443 -0.64412 0.32073 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00001 -0.00001 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.10122 0.99362 0.04977 0.24187 0.96694 -0.08072 0.35177 0.89015 -0.28966 0.31960 0.94341 -0.08850 0.36436 0.93124 0.00607 0.42888 0.90108 -0.06413 0.34159 0.93060 -0.13153 0.35863 0.93029 -0.07715 0.44976 0.89314 0.00495 0.43933 0.89793 0.02653 0.56738 0.81415 -0.12343 0.54248 0.83922 -0.03771 0.19557 -0.87047 0.45170 0.27452 -0.77218 0.57305 0.30521 -0.65708 0.68927 0.99038 0.13278 -0.03900 0.90737 0.41198 0.08332 0.91040 0.37203 0.18104 0.82860 0.54907 -0.10926 0.75315 0.64246 -0.14144 0.78420 0.61951 -0.03530 0.90005 -0.34130 0.27096 0.80594 -0.53026 0.26322 0.80748 -0.45607 0.37412 -0.22704 -0.86992 0.43782 0.85822 -0.44314 0.25900 0.91971 -0.36186 0.15226 0.87148 -0.43736 0.22190 0.81241 -0.55874 0.16670 -0.20344 -0.87645 0.43641 0.22710 0.97309 -0.03911 0.27743 0.96072 0.00660 0.22383 0.97307 -0.05512 0.20009 0.97977 0.00241 0.18875 0.98134 -0.03660 0.26631 0.96371 -0.01852 0.27545 0.96128 -0.00810 -0.26496 -0.92700 0.26547 -0.29922 -0.92728 0.22501 -0.29985 -0.92803 0.22101 -0.32465 -0.92748 0.18544 -0.32484 -0.92795 0.18269 -0.34306 -0.92762 0.14774 -0.34305 -0.92790 0.14600 -0.35599 -0.92772 0.11224 -0.35592 -0.92787 0.11129 0.92069 0.37501 -0.10818 -0.69462 -0.69976 0.16684 -0.19265 -0.86351 0.46608 0.12591 -0.54798 0.82696 0.18329 -0.69229 0.69795 0.23960 -0.72465 0.64612 0.33000 -0.71943 0.61116 0.04364 -0.78466 0.61839 -0.14946 -0.85152 0.50256 -0.39572 -0.90000 0.18275 -0.40310 -0.90211 0.15396 -0.38048 -0.92472 -0.01171 0.24914 -0.62470 0.74005 0.33786 -0.80616 0.48576 0.74850 -0.58760 0.30737 0.49646 -0.68116 0.53810 0.96437 -0.18410 0.18999 0.99852 -0.05405 0.00589 0.94067 -0.09921 0.32450 0.94004 -0.09055 0.32883 0.48679 -0.51345 0.70669 0.82623 -0.38748 0.40890 -0.36662 -0.92729 0.07565 0.87625 -0.16493 0.45275 -0.36475 -0.92779 0.07852 0.20020 -0.56806 0.79827 0.17871 -0.91400 0.36422 -0.18706 -0.74811 0.63666 0.83447 -0.22089 0.50484 0.89415 -0.23045 0.38391 0.94096 0.33621 -0.03941 0.98449 0.17299 -0.02905 0.99690 0.06550 -0.04351 0.99055 0.13647 -0.01331 1.00000 0.00000 -0.00000 0.99993 0.00516 0.01023 -0.70491 -0.69427 0.14522 0.96140 0.25493 0.10352 0.99982 0.00256 0.01897 0.99021 0.13920 -0.01049 0.99228 0.12114 -0.02652 0.70425 -0.06136 0.70730 0.72397 -0.08034 0.68514 0.69834 -0.06705 0.71261 0.70755 -0.17462 0.68475 0.68757 -0.20294 0.69719 0.68968 -0.35670 0.63017 0.66014 -0.28997 0.69291 0.73912 -0.29694 0.60458 0.65962 -0.29237 0.69240 0.71356 -0.46795 0.52140 0.52244 -0.74493 0.41489 0.56236 -0.62219 0.54464 0.53895 -0.63976 0.54794 -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.29656 -0.66599 0.68448 -0.31840 -0.67290 0.66770 -0.43573 -0.62856 0.64424 -0.45505 -0.62819 0.63112 -0.66290 -0.37590 0.64750 -0.53420 -0.51395 0.67118 -0.49917 -0.61019 0.61522 -0.69782 -0.07751 0.71207 -0.90614 -0.31237 -0.28518 -0.71726 -0.15742 0.67879 -0.57400 -0.07080 0.81579 -0.67104 -0.18329 0.71841 -0.68092 -0.28192 0.67592 -0.63745 -0.38469 0.66759 -0.72203 -0.43278 0.53979 0.00000 -1.00000 0.00000 0.11515 0.99316 -0.01950 0.12396 0.99229 -0.00068 -0.07001 0.99177 -0.10718 -0.06792 0.99150 -0.11096 -0.04278 0.99157 -0.12227 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 0.04210 0.99151 -0.12305 0.04277 0.99157 -0.12228 0.06838 0.99149 -0.11075 0.21031 0.97181 -0.10652 0.04527 0.99623 -0.07396 -0.16531 0.98571 -0.03238 -0.17404 0.98465 -0.01341 0.12153 -0.43758 0.89093 -0.78240 -0.27455 0.55900 0.64069 -0.18973 0.74399 0.46658 -0.17002 0.86798 -0.87579 -0.11927 0.46772 -0.94190 -0.02903 0.33465 -0.97122 0.01020 0.23795 -0.74452 -0.13397 0.65402 -0.35313 -0.20995 0.91171 0.11078 -0.00001 0.99385 0.55619 -0.07182 0.82794 0.35731 0.14609 0.92249 0.75105 0.02515 0.65977 0.97107 -0.02064 0.23789 0.84841 -0.13085 0.51291 0.86783 -0.13547 0.47804 -0.40482 -0.22605 0.88602 -0.71334 -0.06060 0.69819 -0.55344 -0.12230 0.82386 -0.10840 -0.20591 0.97255 -0.21381 -0.37604 0.90160 0.78238 -0.27465 0.55896 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.16235 -0.92614 0.34045 -0.99978 -0.01466 0.01477 1.00000 -0.00000 0.00000 0.94706 -0.18941 -0.25923 1.00000 0.00000 -0.00000 0.72758 0.00000 0.68602 0.72632 -0.00007 0.68736 0.69543 0.00038 0.71860 0.71539 0.00227 0.69872 0.69992 0.00000 0.71422 0.63154 -0.00250 0.77534 0.61482 -0.00663 0.78864 0.56683 0.00142 0.82383 0.47157 0.00882 0.88178 0.42644 -0.00127 0.90452 0.48578 -0.00165 0.87408 0.49187 0.00000 0.87067 0.44156 -0.03337 0.89661 0.41672 -0.06071 0.90701 0.45581 -0.00052 0.89008 0.35546 0.00009 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37465 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00250 0.92737 -0.48356 0.00000 0.87531 -0.47159 0.00881 0.88178 -0.42806 -0.01025 0.90369 -0.48965 -0.00150 0.87192 -0.45567 -0.02415 0.88982 -0.53890 0.00034 0.84237 -0.65575 -0.02015 0.75471 -0.61483 -0.00378 0.78865 -0.69506 0.00038 0.71895 -0.72738 -0.00008 0.68623 -0.72632 -0.00000 0.68736 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.32754 0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90968 0.63033 -0.00000 0.77633 0.63035 0.00000 0.77631 0.80505 -0.00000 0.59321 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37168 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07960 0.00000 0.99683 0.07960 0.00000 0.99683 -0.17359 0.00000 0.98482 -0.17359 0.00000 0.98482 -0.41529 0.00000 0.90969 -0.41529 0.00000 0.90969 -0.63033 0.00000 0.77633 -0.63033 0.00000 0.77633 -0.80504 0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32893 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39518 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35199 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39126 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85625 0.38631 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12333 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81900 -0.17246 -0.19506 0.98057 0.02092 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15933 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30813 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26660 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37310 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18796 0.97320 0.19359 0.12413 0.32737 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23702 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86546 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54636 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29877 -0.95399 0.02541 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18797 -0.97320 -0.19359 0.12413 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 -0.36118 0.00000 0.93250 -0.36118 0.00000 0.93250 -0.75130 0.00000 0.65997 -0.75130 0.00000 0.65997 -0.97127 -0.00000 0.23796 -0.97127 0.00000 0.23798 -0.55763 -0.00000 0.83009 -0.55763 -0.00000 0.83009 -0.11087 -0.00000 0.99383 -0.11078 0.00000 0.99385 0.36114 -0.00000 0.93251 0.36118 0.00000 0.93250 0.75128 -0.00000 0.65998 0.75129 0.00000 0.65997 0.97128 0.00000 0.23795 0.97128 0.00000 0.23794 -0.52021 -0.25876 0.81390 -0.55629 -0.06917 0.82810 -0.57632 -0.14637 0.80401 -0.57290 -0.14179 0.80727 -0.50295 -0.10159 0.85832 -0.53494 -0.16968 0.82768 -0.36795 -0.46362 0.80602 -0.42242 -0.48537 0.76549 -0.28739 -0.53790 0.79251 -0.21087 -0.46595 0.85932 -0.10883 -0.19107 0.97553 0.04715 -0.24580 0.96817 -0.07666 -0.52074 0.85027 -0.31183 -0.70556 0.63636 0.03122 -0.83832 0.54428 0.21992 -0.66340 0.71522 0.34776 -0.26959 0.89799 0.50716 -0.68460 0.52355 0.65752 -0.32584 0.67933 0.00853 -0.93684 0.34965 -0.01764 -0.79254 0.60956 -0.19340 -0.85881 0.47439 0.71447 -0.30917 0.62765 0.61605 -0.70539 0.35058 0.40619 -0.89006 0.20691 0.22140 -0.97480 -0.02747 0.44467 -0.88743 0.12141 0.94100 -0.24772 0.23053 0.81543 -0.57879 -0.00930 0.95828 -0.24461 0.14786 0.11803 -0.96573 0.23118 0.47154 -0.01437 0.88173 0.41234 -0.30593 0.85813 0.29316 -0.70443 0.64640 0.14306 -0.95333 0.26588 0.33917 -0.38521 0.85824 0.13045 -0.90945 0.39482 0.07105 -0.94250 0.32658 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03997 -0.73161 0.68055 0.01607 -0.98803 0.15344 -0.03998 -0.73156 0.68061 -0.01608 -0.98803 0.15344 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 -0.13850 -0.95397 0.26603 -0.29317 -0.70441 0.64642 -0.45559 -0.25841 0.85186 0.55630 -0.06906 0.82810 0.54644 -0.07521 0.83412 0.57602 -0.13818 0.80567 0.49186 -0.30734 0.81463 0.53316 -0.23207 0.81356 0.52427 -0.22855 0.82031 0.49192 -0.26575 0.82909 0.48669 -0.26087 0.83372 0.22611 -0.43020 0.87395 0.11924 -0.19633 0.97326 0.10861 -0.19695 0.97438 0.29526 -0.70457 0.64529 0.36092 -0.63712 0.68104 0.26070 -0.59799 0.75792 0.00840 -0.57544 0.81780 0.13169 -0.69253 0.70927 -0.28897 -0.27361 0.91741 -0.13707 -0.62234 0.77065 -0.34751 -0.27251 0.89720 0.00035 -0.95410 0.29950 -0.06955 -0.83809 0.54107 0.11954 -0.91012 0.39673 -0.37961 -0.70148 0.60317 -0.20138 -0.87331 0.44359 -0.64729 -0.30492 0.69859 -0.48193 -0.69947 0.52772 -0.21391 -0.97644 -0.02847 -0.43222 -0.89152 0.13555 -0.71877 -0.29106 0.63139 -0.69107 -0.67926 0.24704 -0.45140 -0.88525 0.11212 -0.93651 -0.26515 0.22946 -0.92389 -0.26238 0.27854 -0.77550 -0.62094 0.11413 0.08395 -0.47203 0.87758 0.07372 -0.31442 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39305 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.42738 -0.87288 0.23542 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18886 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18766 0.98223 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18766 0.98223 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18886 -0.67101 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92408 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19359 0.12407 0.81663 -0.54564 -0.18814 0.90235 -0.34994 0.25159 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02538 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54656 0.32005 -0.92238 0.21629 0.34529 -0.86546 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68808 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 -0.71754 0.00259 0.69651 -0.69992 0.00000 0.71422 0.00000 -1.00000 -0.00000 -0.99976 -0.02028 0.00805 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 -0.00012 -0.00000 -1.00000 -0.00000 -0.00000 -0.54306 0.83970 0.00048 -0.82645 0.56302 0.00033 -0.98019 0.19804 -0.00000 -0.98037 0.19532 0.02685 -0.00000 1.00000 0.00000 0.48299 0.87548 -0.01569 0.55273 0.83336 -0.00014 0.82644 0.56303 0.00033 0.98001 0.19893 0.00016 0.96592 -0.25883 -0.00000 0.70708 -0.70711 0.00482 0.25880 -0.96592 0.00361 -0.25882 -0.96593 0.00000 -0.70710 -0.70710 0.00482 -0.96592 -0.25882 0.00361 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.53936 0.83398 0.11644 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06986 -0.98282 0.18451 -0.00432 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85102 0.52047 0.06989 0.98001 0.19893 -0.00121 -0.38262 0.92383 0.01196 -0.60549 0.79206 -0.07758 -0.98242 0.18315 0.03619 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86396 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92863 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48080 0.35274 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78087 0.11745 0.43570 0.89716 -0.07251 0.98234 0.18357 0.03605 0.84345 0.53137 -0.07891 0.60508 0.79038 0.09581 0.47838 0.87812 -0.00723 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02737 0.99781 -0.00006 -0.06621 -0.83570 0.00000 0.54918 -0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 0.83570 0.00000 0.54918 -0.99746 0.00249 -0.07125 -0.96449 -0.25844 -0.05450 -0.69956 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66578 0.40977 0.96449 -0.25845 -0.05450 0.69954 -0.69957 0.14577 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.18723 0.98232 -0.00049 -0.67986 -0.71506 0.16275 -0.25882 -0.96593 -0.00000 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 0.68062 -0.46742 0.56416 0.68415 -0.46919 0.55840 0.00000 -1.00000 0.00000 -0.06980 0.99114 -0.11304 -0.17002 0.98539 0.00995 0.49377 -0.55480 0.66962 -0.88917 -0.28233 0.36009 -0.06968 0.99117 -0.11285 -0.04752 0.99190 -0.11780 0.82964 0.00000 0.55830 1.00000 0.00000 -0.00005 0.00000 -1.00000 -0.00000 -1.00000 0.00000 -0.00000 -0.55558 0.83146 -0.00032 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 0.19509 0.98078 0.00289 0.55557 0.83147 -0.00032 0.83147 0.55556 -0.00016 0.98078 0.19510 -0.00005 0.98077 -0.19509 0.00479 0.83147 -0.55556 -0.00242 0.55557 -0.83147 -0.00242 0.19509 -0.98079 -0.00000 -0.19508 -0.98078 0.00479 -0.55557 -0.83147 -0.00242 -0.83147 -0.55557 -0.00242 -0.98078 -0.19510 -0.00000 0.00000 1.00000 -0.00000 -0.19510 0.98078 0.00000 -0.43988 0.89769 0.02576 -0.34308 0.92963 -0.13449 -0.12092 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29117 0.13333 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.26953 -0.73824 0.61835 -0.04401 -0.78448 0.61859 0.34486 -0.87107 0.34972 -0.24901 -0.62075 0.74341 -0.53274 -0.67686 0.50798 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71481 -0.55303 -0.49987 0.66655 -0.10705 -0.93718 0.33202 -0.08363 -0.97549 0.20352 -0.95619 0.27850 0.09024 0.81839 -0.55914 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34274 -0.93162 0.12091 0.41584 -0.90391 0.10015 -0.02010 -0.99838 0.05318 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.11792 0.96141 0.24855 -0.28024 0.91713 0.28345 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 -0.21447 0.96105 0.17429 -0.21468 0.96201 0.16869 -0.24705 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05398 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06977 0.99156 -0.10925 -0.34004 -0.62630 0.70151 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50577 -0.84008 0.26126 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08802 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67439 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41724 -0.54080 0.73037 -0.41201 -0.60635 0.68014 -0.70424 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95385 0.19679 0.22679 -0.77616 0.60749 0.16894 -0.89673 0.40568 0.17691 0.33004 -0.80724 0.48932 -0.20020 -0.56807 0.79826 -0.19713 -0.77268 0.60342 -0.56010 -0.42940 0.70845 -0.86716 -0.48961 0.09123 -0.79167 -0.53552 0.29407 -0.86902 -0.31567 0.38100 0.40409 -0.56439 0.71984 0.33802 -0.85130 0.40128 0.52007 -0.78742 0.33089 0.14974 -0.78142 0.60577 -0.67308 -0.65371 0.34586 -0.79487 -0.52330 0.30714 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02856 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01957 -0.79797 0.60051 -0.05130 -0.76800 0.64031 -0.01382 -0.80117 0.58934 -0.10394 -0.76278 0.64443 -0.05371 -0.72711 0.68601 0.02658 -0.71869 0.69533 -0.00068 -0.67621 0.73321 0.07167 -0.19381 -0.87163 0.45023 -0.33486 -0.67114 0.66139 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.10649 -0.94309 0.31503 -0.16500 -0.93292 0.32005 -0.17354 -0.93264 0.31632 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.14310 -0.93869 0.31366 -0.59996 0.78186 -0.16950 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.47585 0.87781 -0.05491 -0.33781 0.94059 0.03414 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.15144 0.98776 0.03735 -0.99876 0.02243 0.04443 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00118 -1.00000 -0.00103 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42687 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.68055 -0.57907 0.44891 -0.55875 0.82932 -0.00524 -0.63044 0.77342 -0.06608 -0.62318 0.78201 -0.01031 -0.62355 0.78160 -0.01687 -0.58167 0.81243 0.04018 -0.58190 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03148 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51069 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40436 0.85353 0.32861 -0.39688 0.83488 0.38139 -0.32068 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 0.00024 -1.00000 -0.00003 -0.00108 -0.99981 0.01924 -0.26638 -0.92815 0.25995 -0.22267 -0.92832 0.29772 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05538 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00095 1.00000 -0.00028 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00745 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 0.32528 0.86091 0.39118 0.33532 0.84040 0.42579 0.23285 0.86496 0.44455 0.25027 0.81275 0.52612 0.17651 0.83818 0.51604 0.10816 0.84369 0.52582 0.11187 0.86176 0.49483 0.00028 0.83866 0.54466 -0.00914 -0.99996 0.00102 -0.00630 -0.99996 0.00607 0.10399 -0.94352 0.31456 0.07081 -0.93620 0.34427 -0.00555 -0.95073 0.30998 0.04525 -0.90484 0.42333 0.14454 -0.93969 0.30998 0.14454 -0.93969 0.30997 0.12737 -0.94154 0.31190 0.18908 -0.91839 0.34758 0.30400 0.34310 0.88875 0.28039 0.27889 0.91848 0.15528 -0.63718 0.75491 0.25235 -0.50582 0.82490 0.18035 0.44574 0.87681 0.02349 0.38357 0.92321 0.00000 -0.58193 0.81324 0.43016 -0.54482 0.71982 0.39039 -0.60766 0.69162 0.53245 0.40400 0.74383 0.44473 0.03813 0.89485 0.46219 0.52024 0.71814 0.29459 -0.64015 0.70952 0.00016 0.94744 0.31993 0.19414 0.95999 0.20179 0.13733 0.94752 0.28870 0.17056 0.96125 0.21658 0.17105 0.96162 0.21453 0.21458 0.96108 0.17403 0.21475 0.96198 0.16875 0.05806 -0.98803 0.14291 0.11694 -0.95226 0.28202 0.03296 0.95258 0.30251 0.07028 0.94785 0.31086 0.09366 0.95264 0.28931 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.04460 0.99084 -0.12748 -0.02095 0.99228 -0.12226 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 0.04752 0.99190 -0.11780 -0.16727 -0.92856 0.33134 -0.21990 -0.92662 0.30498 -0.03234 0.95249 0.30284 -0.07021 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.23218 -0.60875 0.75863 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.01264 0.86767 0.49698 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.04879 -0.99862 0.01922 -0.27653 -0.59294 0.75627 -0.22124 -0.61003 0.76087 0.88921 -0.28229 0.36004 0.11993 0.99253 0.02254 -0.55015 -0.62730 0.55121 0.85361 0.22300 0.47076 0.78945 0.37028 0.48956 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24572 0.96262 0.11395 0.24710 0.96090 0.12493 0.36884 -0.86583 0.33807 0.40262 -0.84456 0.35300 0.30819 -0.87861 0.36477 0.79235 -0.48637 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14655 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23108 0.60973 0.41632 0.67447 0.45012 -0.62955 0.63329 0.52768 -0.56847 0.63119 0.51462 -0.58327 0.62846 0.69906 0.28925 0.65394 0.69603 0.25859 0.66983 0.73326 0.39301 0.55486 0.51544 -0.63934 0.57058 0.71478 -0.44325 0.54095 0.50370 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04158 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14387 -0.94000 0.30935 0.14373 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 0.40524 0.83720 0.36725 0.40441 0.85375 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24716 0.49012 0.83244 0.25851 0.53337 0.82040 0.20604 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09071 0.58199 0.81145 0.05332 0.58209 0.81139 0.05314 0.63891 0.76804 -0.04376 0.58234 0.81175 0.04408 -0.62975 -0.61576 0.47356 -0.62713 -0.61181 0.48208 -0.67408 -0.63036 0.38504 -0.72332 -0.61625 0.31151 -0.77754 -0.57908 0.24515 -0.69443 -0.64412 0.32073 1.00000 0.00000 -0.00000 1.00000 0.00001 -0.00000 1.00000 0.00017 -0.00017 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.10122 0.99362 0.04977 0.24187 0.96694 -0.08072 0.35177 0.89015 -0.28966 0.31960 0.94341 -0.08850 0.36436 0.93124 0.00607 0.42888 0.90108 -0.06413 0.34159 0.93060 -0.13153 0.35863 0.93029 -0.07715 0.44976 0.89314 0.00495 0.43934 0.89793 0.02653 0.56738 0.81415 -0.12343 0.54248 0.83922 -0.03771 0.19557 -0.87047 0.45170 0.27452 -0.77218 0.57305 0.30521 -0.65708 0.68927 0.99038 0.13278 -0.03901 0.90737 0.41199 0.08331 0.91039 0.37203 0.18103 0.82860 0.54908 -0.10926 0.75315 0.64246 -0.14144 0.78419 0.61951 -0.03530 0.90067 -0.31037 0.30406 0.79873 -0.53748 0.27045 0.75401 -0.46134 0.46757 -0.22704 -0.86992 0.43782 0.85822 -0.44314 0.25900 0.92693 -0.34949 0.13658 0.84589 -0.47572 0.24118 0.82161 -0.54314 0.17310 -0.20344 -0.87645 0.43641 0.22710 0.97309 -0.03911 0.27743 0.96072 0.00660 0.22383 0.97307 -0.05511 0.20009 0.97977 0.00241 0.18875 0.98134 -0.03660 0.26631 0.96371 -0.01852 0.27545 0.96128 -0.00810 -0.26496 -0.92700 0.26547 -0.29922 -0.92728 0.22501 -0.29985 -0.92803 0.22101 -0.32465 -0.92748 0.18544 -0.32485 -0.92795 0.18269 -0.34306 -0.92762 0.14775 -0.34305 -0.92790 0.14600 -0.35599 -0.92772 0.11224 -0.35592 -0.92787 0.11129 0.92068 0.37502 -0.10818 -0.69462 -0.69976 0.16684 -0.19265 -0.86351 0.46608 0.12591 -0.54798 0.82696 0.18329 -0.69229 0.69795 0.23961 -0.72465 0.64612 0.33000 -0.71943 0.61116 0.04364 -0.78466 0.61839 -0.14946 -0.85152 0.50256 -0.39572 -0.90000 0.18275 -0.40310 -0.90211 0.15396 -0.38048 -0.92472 -0.01172 0.24914 -0.62470 0.74005 0.33786 -0.80616 0.48576 0.74850 -0.58760 0.30737 0.49646 -0.68116 0.53810 0.96437 -0.18410 0.18999 0.99852 -0.05405 0.00589 0.94067 -0.09921 0.32450 0.94004 -0.09055 0.32883 0.48679 -0.51345 0.70669 0.82623 -0.38748 0.40890 -0.36662 -0.92729 0.07565 -0.36475 -0.92779 0.07852 0.20020 -0.56806 0.79827 0.17871 -0.91400 0.36422 -0.18706 -0.74811 0.63666 0.83447 -0.22089 0.50484 0.89415 -0.23045 0.38391 0.94096 0.33621 -0.03941 0.99369 0.10940 -0.02488 0.99055 0.13648 -0.01331 1.00000 -0.00000 0.00000 0.99987 0.00727 0.01441 -0.70491 -0.69427 0.14522 0.96140 0.25493 0.10352 0.99981 0.00685 0.01805 0.99021 0.13920 -0.01050 0.99228 0.12113 -0.02651 0.70425 -0.06136 0.70730 0.72397 -0.08033 0.68514 0.69834 -0.06705 0.71261 0.70755 -0.17462 0.68475 0.68757 -0.20294 0.69719 0.68968 -0.35670 0.63017 0.66014 -0.28997 0.69291 0.73912 -0.29694 0.60458 0.65962 -0.29237 0.69240 0.71356 -0.46795 0.52140 0.52244 -0.74493 0.41489 0.56236 -0.62219 0.54464 0.53895 -0.63976 0.54794 -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.29656 -0.66599 0.68448 -0.31840 -0.67290 0.66770 -0.45185 -0.62142 0.64005 -0.45819 -0.62148 0.63547 -0.66290 -0.37590 0.64750 -0.53420 -0.51395 0.67118 -0.49409 -0.60833 0.62114 -0.69782 -0.07751 0.71207 -0.90614 -0.31237 -0.28518 -0.71726 -0.15742 0.67879 -0.57400 -0.07080 0.81579 -0.67104 -0.18329 0.71841 -0.68092 -0.28192 0.67592 -0.63745 -0.38469 0.66759 -0.72203 -0.43278 0.53979 -0.00000 -1.00000 -0.00000 0.11515 0.99316 -0.01950 0.12396 0.99229 -0.00068 -0.07001 0.99177 -0.10718 -0.06792 0.99150 -0.11096 -0.04278 0.99157 -0.12227 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 0.04209 0.99151 -0.12305 0.04277 0.99157 -0.12228 0.06837 0.99149 -0.11075 0.21031 0.97181 -0.10652 0.04527 0.99623 -0.07396 -0.16531 0.98571 -0.03238 -0.17404 0.98465 -0.01341 0.12153 -0.43758 0.89093 -0.78240 -0.27455 0.55900 0.50696 -0.21300 0.83524 0.43301 -0.20106 0.87868 -0.87579 -0.11926 0.46772 -0.94189 -0.02903 0.33465 -0.97122 0.01020 0.23796 -0.74452 -0.13397 0.65402 -0.35310 -0.20995 0.91172 -0.35677 0.15627 0.92103 0.11078 -0.00001 0.99385 0.55619 -0.07182 0.82794 0.35730 0.14610 0.92249 0.75105 0.02515 0.65977 0.97108 -0.02064 0.23787 0.84841 -0.13085 0.51291 0.86783 -0.13547 0.47803 -0.40482 -0.22605 0.88602 -0.71334 -0.06060 0.69819 -0.55344 -0.12230 0.82386 -0.10840 -0.20591 0.97255 -0.21381 -0.37604 0.90160 0.78239 -0.27465 0.55896 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.16235 -0.92614 0.34045 -0.99978 -0.01466 0.01477 1.00000 -0.00000 0.00000 0.94706 -0.18941 -0.25923 1.00000 0.00000 -0.00000 0.72758 0.00000 0.68602 0.72631 -0.00007 0.68736 0.69543 0.00038 0.71859 0.71540 0.00227 0.69872 0.69992 0.00000 0.71422 0.63154 -0.00250 0.77534 0.61482 -0.00663 0.78864 0.56683 0.00142 0.82383 0.47157 0.00882 0.88178 0.42644 -0.00127 0.90452 0.48578 -0.00165 0.87408 0.49187 0.00000 0.87067 0.44156 -0.03337 0.89661 0.41672 -0.06071 0.90701 0.45581 -0.00052 0.89008 0.35546 0.00009 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37465 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00250 0.92737 -0.48356 0.00000 0.87531 -0.47159 0.00881 0.88178 -0.42806 -0.01025 0.90369 -0.48965 -0.00150 0.87192 -0.45567 -0.02415 0.88982 -0.53890 0.00034 0.84237 -0.65575 -0.02015 0.75471 -0.61483 -0.00378 0.78865 -0.69506 0.00038 0.71895 -0.72738 -0.00008 0.68623 -0.72632 0.00000 0.68736 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.32754 0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90968 0.63033 -0.00000 0.77633 0.63035 0.00000 0.77631 0.80505 -0.00000 0.59321 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37168 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07960 0.00000 0.99683 0.07960 0.00000 0.99683 -0.17359 0.00000 0.98482 -0.17359 0.00000 0.98482 -0.41529 0.00000 0.90969 -0.41529 0.00000 0.90969 -0.63033 0.00000 0.77633 -0.63033 0.00000 0.77633 -0.80504 0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 -0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32893 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39518 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35199 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39126 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85625 0.38631 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12333 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81900 -0.17246 -0.19506 0.98057 0.02092 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15933 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30813 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26660 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37310 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18796 0.97320 0.19359 0.12413 0.32737 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23702 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86546 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54636 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29876 -0.95399 0.02540 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18796 -0.97320 -0.19359 0.12413 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 -0.36118 0.00000 0.93250 -0.36118 0.00000 0.93250 -0.75130 0.00000 0.65997 -0.75130 0.00000 0.65997 -0.97127 0.00000 0.23797 -0.97127 -0.00000 0.23796 -0.55763 0.00000 0.83009 -0.55763 0.00000 0.83009 -0.11087 -0.00000 0.99383 -0.11078 0.00000 0.99385 0.36114 -0.00000 0.93251 0.36118 0.00000 0.93250 0.75128 -0.00000 0.65998 0.75129 0.00000 0.65997 0.97128 0.00000 0.23793 0.97128 0.00000 0.23792 -0.52021 -0.25876 0.81390 -0.55629 -0.06917 0.82810 -0.57632 -0.14637 0.80401 -0.57290 -0.14179 0.80727 -0.50295 -0.10159 0.85832 -0.53494 -0.16968 0.82768 -0.36795 -0.46362 0.80602 -0.42242 -0.48537 0.76549 -0.28739 -0.53790 0.79251 -0.21087 -0.46595 0.85932 -0.10883 -0.19107 0.97553 0.04715 -0.24580 0.96817 -0.07666 -0.52074 0.85027 -0.31183 -0.70556 0.63636 0.03122 -0.83832 0.54428 0.21992 -0.66340 0.71522 0.34776 -0.26959 0.89799 0.50716 -0.68460 0.52355 0.65752 -0.32584 0.67933 0.00853 -0.93684 0.34965 -0.01764 -0.79254 0.60956 -0.19340 -0.85881 0.47439 -0.06005 -0.94361 0.32556 0.71447 -0.30917 0.62765 0.61605 -0.70539 0.35058 0.40619 -0.89006 0.20691 0.33853 -0.93969 0.04886 0.44467 -0.88743 0.12141 0.94101 -0.24772 0.23052 0.81543 -0.57879 -0.00930 0.95828 -0.24461 0.14786 0.11803 -0.96573 0.23117 0.47154 -0.01437 0.88173 0.41234 -0.30593 0.85813 0.29316 -0.70443 0.64640 0.14305 -0.95333 0.26587 0.33917 -0.38521 0.85824 0.13045 -0.90945 0.39481 0.07104 -0.94250 0.32657 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03996 -0.73162 0.68054 0.01607 -0.98803 0.15343 -0.03998 -0.73156 0.68060 -0.01608 -0.98803 0.15343 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 -0.13850 -0.95397 0.26603 -0.29317 -0.70441 0.64642 -0.45559 -0.25841 0.85186 0.55630 -0.06906 0.82810 0.54643 -0.07521 0.83412 0.57602 -0.13818 0.80567 0.49186 -0.30734 0.81463 0.53316 -0.23207 0.81356 0.52427 -0.22855 0.82031 0.49192 -0.26575 0.82909 0.48669 -0.26087 0.83372 0.22611 -0.43020 0.87395 0.11924 -0.19633 0.97326 0.10861 -0.19695 0.97438 0.29526 -0.70457 0.64529 0.36092 -0.63712 0.68104 0.26070 -0.59799 0.75792 0.00840 -0.57544 0.81780 0.13169 -0.69253 0.70927 -0.28897 -0.27361 0.91741 -0.13707 -0.62234 0.77065 -0.34751 -0.27251 0.89720 0.00034 -0.95410 0.29949 -0.06955 -0.83809 0.54107 0.11955 -0.91012 0.39673 -0.37961 -0.70149 0.60317 -0.20139 -0.87331 0.44359 -0.64730 -0.30492 0.69859 -0.48193 -0.69947 0.52771 -0.21390 -0.97644 -0.02846 -0.43222 -0.89152 0.13554 -0.71877 -0.29107 0.63139 -0.69106 -0.67926 0.24705 -0.45140 -0.88525 0.11213 -0.93651 -0.26515 0.22944 -0.92389 -0.26237 0.27855 -0.77550 -0.62094 0.11414 0.08395 -0.47203 0.87758 0.07372 -0.31442 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39306 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 1.00000 0.00000 -0.42738 -0.87288 0.23542 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18886 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18765 0.98224 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18765 0.98224 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18886 -0.67100 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92408 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19359 0.12406 0.81662 -0.54564 -0.18814 0.90236 -0.34994 0.25159 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02537 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54656 0.32005 -0.92238 0.21629 0.34529 -0.86546 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68808 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 -0.71754 0.00259 0.69651 -0.69992 0.00000 0.71422 0.00000 -1.00000 -0.00000 -0.99976 -0.02028 0.00805 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 -0.00012 0.00000 -1.00000 -0.00000 -0.00000 -0.54306 0.83970 0.00048 -0.82645 0.56302 0.00033 -0.98019 0.19804 -0.00000 -0.98037 0.19532 0.02685 0.00000 1.00000 -0.00000 0.48299 0.87548 -0.01569 0.55272 0.83336 -0.00014 0.82644 0.56303 0.00033 0.98001 0.19893 0.00016 0.96592 -0.25883 0.00000 0.70708 -0.70711 0.00483 0.25880 -0.96592 0.00361 -0.25882 -0.96593 0.00000 -0.70710 -0.70710 0.00482 -0.96592 -0.25882 0.00361 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.53936 0.83398 0.11645 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06987 -0.98282 0.18451 -0.00432 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85102 0.52047 0.06989 0.98001 0.19893 -0.00121 -0.38262 0.92383 0.01196 -0.60549 0.79206 -0.07758 -0.98242 0.18315 0.03619 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86397 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92863 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48080 0.35274 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78087 0.11745 0.43570 0.89716 -0.07251 0.98234 0.18357 0.03605 0.84345 0.53137 -0.07891 0.60508 0.79038 0.09581 0.47838 0.87812 -0.00723 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02737 0.99781 -0.00006 -0.06621 -0.83570 0.00000 0.54918 -0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 0.83570 0.00000 0.54918 -0.99746 0.00249 -0.07125 -0.96449 -0.25844 -0.05450 -0.69956 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66578 0.40977 0.96449 -0.25845 -0.05450 0.69954 -0.69957 0.14577 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.18723 0.98232 -0.00049 -0.67986 -0.71506 0.16275 -0.25882 -0.96593 -0.00000 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 0.68062 -0.46742 0.56416 0.68415 -0.46919 0.55840 0.00000 -1.00000 0.00000 -0.06980 0.99114 -0.11304 -0.17002 0.98539 0.00995 0.49377 -0.55480 0.66962 -0.88917 -0.28233 0.36009 -0.06967 0.99117 -0.11285 -0.04752 0.99190 -0.11780 1.00000 0.00000 -0.00005 0.00000 -1.00000 0.00000 -1.00000 -0.00000 -0.00000 -0.55558 0.83146 -0.00032 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 0.19509 0.98078 0.00289 0.55557 0.83147 -0.00032 0.83147 0.55556 -0.00016 0.98078 0.19510 -0.00005 0.98077 -0.19509 0.00479 0.83147 -0.55556 -0.00242 0.55557 -0.83147 -0.00242 0.19509 -0.98079 0.00000 -0.19508 -0.98078 0.00479 -0.55557 -0.83147 -0.00242 -0.83147 -0.55557 -0.00242 -0.98078 -0.19510 -0.00000 0.00000 1.00000 -0.00000 -0.19510 0.98078 0.00000 -0.43988 0.89769 0.02576 -0.34308 0.92963 -0.13449 -0.12091 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29117 0.13333 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.26954 -0.73824 0.61835 -0.04401 -0.78448 0.61859 0.34486 -0.87107 0.34972 -0.24901 -0.62075 0.74341 -0.53274 -0.67686 0.50798 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71481 -0.55303 -0.49987 0.66655 -0.10705 -0.93718 0.33202 -0.08363 -0.97549 0.20352 -0.95619 0.27850 0.09024 0.81840 -0.55913 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34274 -0.93162 0.12091 0.41584 -0.90391 0.10015 -0.02010 -0.99838 0.05318 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.11791 0.96141 0.24855 -0.28024 0.91713 0.28345 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 -0.21448 0.96105 0.17429 -0.21468 0.96201 0.16869 -0.24706 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05397 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06977 0.99156 -0.10925 -0.34004 -0.62630 0.70151 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50576 -0.84008 0.26126 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08802 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67439 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41725 -0.54080 0.73037 -0.41201 -0.60635 0.68014 -0.70424 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95385 0.19679 0.22679 -0.77616 0.60749 0.16894 -0.89673 0.40568 0.17691 0.33004 -0.80724 0.48932 -0.20020 -0.56807 0.79826 -0.19713 -0.77268 0.60342 -0.56010 -0.42940 0.70845 -0.77051 -0.59690 0.22366 -0.89494 -0.39110 0.21476 -0.86902 -0.31567 0.38100 0.40409 -0.56439 0.71984 0.33802 -0.85130 0.40128 0.52007 -0.78743 0.33090 0.14974 -0.78142 0.60577 -0.67308 -0.65372 0.34586 -0.79487 -0.52330 0.30714 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02855 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01957 -0.79797 0.60051 -0.05130 -0.76800 0.64031 -0.01382 -0.80117 0.58934 -0.10394 -0.76278 0.64443 -0.05371 -0.72711 0.68601 0.02658 -0.71869 0.69533 -0.00068 -0.67621 0.73321 0.07167 -0.19381 -0.87163 0.45023 -0.33486 -0.67114 0.66139 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.10649 -0.94309 0.31503 -0.16500 -0.93292 0.32005 -0.17354 -0.93264 0.31632 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.14311 -0.93869 0.31366 -0.59996 0.78186 -0.16950 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.47585 0.87781 -0.05491 -0.33781 0.94059 0.03414 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.15145 0.98776 0.03735 -0.99876 0.02243 0.04443 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -0.00118 -1.00000 -0.00104 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42687 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.68055 -0.57907 0.44891 -0.55875 0.82932 -0.00524 -0.63044 0.77342 -0.06608 -0.62318 0.78201 -0.01031 -0.62355 0.78160 -0.01687 -0.58167 0.81243 0.04018 -0.58190 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03148 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51068 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40437 0.85353 0.32861 -0.39689 0.83488 0.38139 -0.32068 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 0.00024 -1.00000 -0.00003 -0.00108 -0.99981 0.01924 -0.26638 -0.92815 0.25995 -0.22267 -0.92832 0.29772 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05538 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00095 1.00000 -0.00028 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00746 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 0.32528 0.86091 0.39118 0.33532 0.84040 0.42579 0.23285 0.86496 0.44455 0.25027 0.81275 0.52612 0.17651 0.83818 0.51604 0.10816 0.84369 0.52582 0.11187 0.86176 0.49483 0.00028 0.83866 0.54466 -0.00914 -0.99996 0.00102 -0.00630 -0.99996 0.00607 0.10399 -0.94352 0.31456 0.07081 -0.93620 0.34427 -0.00555 -0.95073 0.30998 0.04525 -0.90484 0.42333 0.25684 -0.87163 0.41749 0.14454 -0.93969 0.30998 0.14440 -0.93971 0.30999 0.14454 -0.93969 0.30997 0.13338 -0.93583 0.32624 0.30399 0.34310 0.88875 0.28039 0.27889 0.91848 0.15528 -0.63718 0.75491 0.25235 -0.50582 0.82490 0.18035 0.44574 0.87681 0.02349 0.38357 0.92321 0.00000 -0.58193 0.81324 0.43016 -0.54482 0.71982 0.39039 -0.60766 0.69162 0.53245 0.40400 0.74383 0.44473 0.03813 0.89485 0.46219 0.52024 0.71814 0.29459 -0.64015 0.70952 0.00016 0.94744 0.31993 0.13733 0.94752 0.28870 0.19414 0.95999 0.20179 0.17056 0.96125 0.21658 0.17105 0.96162 0.21453 0.21458 0.96108 0.17403 0.21475 0.96198 0.16875 0.05806 -0.98803 0.14291 0.06866 -0.98340 0.16795 0.03296 0.95258 0.30251 0.07028 0.94785 0.31086 0.09366 0.95264 0.28931 0.09772 -0.92104 0.37701 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.04460 0.99084 -0.12748 -0.02095 0.99228 -0.12226 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 0.04752 0.99190 -0.11780 -0.16727 -0.92856 0.33134 -0.21990 -0.92662 0.30498 -0.03234 0.95249 0.30284 -0.07021 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.23218 -0.60875 0.75863 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.01264 0.86767 0.49698 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.04880 -0.99862 0.01922 -0.62317 0.78208 -0.00435 -0.79379 0.60818 -0.00359 -0.72015 0.69382 -0.00040 -0.56267 0.82663 -0.00899 0.12908 -0.99163 -0.00064 0.12485 -0.99217 -0.00128 0.36682 -0.93029 -0.00220 0.38166 -0.92430 0.00016 0.51311 -0.85831 -0.00515 0.60885 -0.79305 0.01918 0.81095 -0.58507 0.00715 0.79300 -0.60921 0.00286 0.92422 -0.38184 -0.00239 0.99149 -0.12913 0.01646 0.97569 -0.21914 -0.00014 -0.13521 -0.99081 0.00250 -0.19312 -0.98111 0.01146 -0.38658 -0.92225 -0.00057 -0.50701 -0.86189 0.00957 -0.70726 -0.70678 -0.01571 -0.81114 -0.58481 0.00718 -0.92423 -0.38183 -0.00232 -0.99163 -0.12910 -0.00002 -0.97530 -0.22066 0.00986 0.00033 -1.00000 -0.00064 -0.00366 -0.99999 0.00209 1.00000 0.00000 -0.00002 1.00000 0.00003 -0.00003 1.00000 0.00000 -0.00003 1.00000 0.00006 -0.00012 1.00000 0.00002 -0.00006 1.00000 0.00000 -0.00005 1.00000 0.00000 -0.00004 -1.00000 0.00003 0.00002 -1.00000 -0.00004 0.00002 -1.00000 -0.00002 0.00003 -1.00000 -0.00001 0.00003 -1.00000 -0.00001 0.00003 -1.00000 -0.00000 0.00004 -1.00000 -0.00000 0.00004 -1.00000 0.00000 0.00004 -1.00000 0.00000 0.00004 -1.00000 0.00000 0.00004 0.99387 0.11059 0.00001 0.99399 0.10945 -0.00006 0.94966 0.31330 0.00012 0.94433 0.32901 -0.00064 0.87678 0.48090 0.00059 0.84631 0.53268 -0.00126 0.70722 0.70699 0.00253 0.47877 0.87793 -0.00310 0.53288 0.84619 0.00034 0.38651 0.92228 0.00018 0.30651 0.95187 -0.00200 0.26150 0.96519 -0.00463 0.22112 0.97524 -0.00318 0.12467 0.99220 -0.00086 0.03864 0.99925 0.00018 -0.99400 0.10941 0.00005 -0.99386 0.11061 -0.00001 -0.94966 0.31327 0.00016 -0.94115 0.33798 -0.00103 -0.87679 0.48088 0.00062 -0.84441 0.53570 0.00115 -0.70715 0.70704 0.00622 -0.47694 0.87893 -0.00316 -0.53383 0.84556 0.00651 -0.39699 0.91779 -0.00806 -0.30905 0.95104 -0.00274 -0.23172 0.97278 0.00046 -0.12069 0.99247 -0.02087 -0.17400 0.98465 -0.01340 -0.23705 0.97147 -0.00722 0.00028 1.00000 0.00046 0.00006 1.00000 0.00057 0.00017 1.00000 0.00049 0.53733 0.84337 -0.00092 0.66533 0.74655 -0.00102 0.79725 0.60364 0.00048 -0.23323 0.97240 -0.00623 -0.16937 0.98548 -0.01221 -0.11540 0.99313 -0.01951 -0.22254 0.97492 0.00046 -0.30619 0.95197 -0.00200 -0.53267 0.84630 0.00638 0.21433 -0.97665 -0.01444 0.26119 -0.96529 0.00000 0.51313 -0.85830 -0.00517 0.60868 -0.79319 0.01911 0.81099 -0.58502 0.00702 0.79382 -0.60814 0.00291 0.92413 -0.38208 -0.00241 0.94827 -0.31747 0.00259 0.99163 -0.12910 -0.00280 0.99545 -0.09531 -0.00008 -0.14678 -0.98916 0.00429 -0.12639 -0.99198 -0.00109 -0.19312 -0.98111 0.01146 -0.38648 -0.92230 -0.00056 -0.50699 -0.86190 0.00960 -0.60896 -0.79320 -0.00266 -0.79300 -0.60921 0.00296 -0.81111 -0.58485 0.00728 -0.92422 -0.38184 -0.00231 -0.99163 -0.12915 -0.00002 -0.97530 -0.22066 0.00986 0.00000 -1.00000 0.00000 -0.00025 -1.00000 -0.00009 0.00012 -1.00000 -0.00036 0.00003 -1.00000 -0.00032 -0.00003 -1.00000 -0.00032 -0.00012 -1.00000 -0.00036 -0.00058 -1.00000 -0.00111 0.00015 -1.00000 -0.00017 -0.00298 -0.99999 0.00338 1.00000 -0.00015 -0.00000 1.00000 0.00003 -0.00003 1.00000 0.00000 -0.00003 1.00000 0.00015 -0.00018 1.00000 0.00000 -0.00003 1.00000 0.00005 -0.00011 1.00000 0.00002 -0.00006 1.00000 0.00001 -0.00005 1.00000 0.00000 -0.00004 -1.00000 0.00002 0.00001 -1.00000 -0.00002 0.00001 -1.00000 -0.00002 0.00001 -1.00000 -0.00001 0.00002 -1.00000 -0.00000 0.00002 -1.00000 -0.00000 0.00002 -1.00000 0.00000 0.00002 -1.00000 0.00002 0.00004 0.97040 0.24152 -0.00000 0.99313 0.11603 -0.01492 0.94918 0.31472 -0.00229 0.84408 0.53622 0.00128 0.87546 0.48329 -0.00241 0.70715 0.70705 0.00324 0.79196 0.61055 -0.00573 0.66692 0.74513 0.00165 0.54401 0.83908 -0.00079 0.53605 0.84418 -0.00055 0.46613 0.88471 0.00043 0.34092 0.94009 -0.00055 0.40230 0.91550 -0.00406 0.30021 0.95387 -0.00036 0.11062 0.99386 0.00160 0.24080 0.97054 -0.00825 0.13002 0.99151 -0.00223 0.03755 0.99929 0.00046 -0.99400 0.10941 0.00003 -0.99385 0.11074 -0.00001 -0.94966 0.31327 0.00016 -0.94429 0.32911 -0.00060 -0.87680 0.48086 0.00064 -0.84619 0.53288 0.00117 -0.79340 0.60869 -0.00405 -0.72016 0.69381 -0.00040 -0.70698 0.70721 0.00621 -0.56264 0.82666 -0.00898 -0.62316 0.78208 -0.00434 -0.47691 0.87895 -0.00316 -0.53267 0.84630 0.00638 -0.39694 0.91781 -0.00805 -0.30620 0.95197 -0.00200 -0.22254 0.97492 0.00046 -0.11540 0.99313 -0.01951 -0.16937 0.98548 -0.01221 -0.23323 0.97240 -0.00623 0.00028 1.00000 0.00046 -0.00000 1.00000 0.00054 -0.00028 1.00000 0.00046 -0.00043 1.00000 0.00126 -0.00008 1.00000 0.00073 0.00006 1.00000 0.00057 0.00017 1.00000 0.00049 0.12908 -0.99163 -0.00064 0.12485 -0.99217 -0.00128 0.36682 -0.93029 -0.00220 0.38167 -0.92430 0.00016 0.51311 -0.85831 -0.00515 0.60885 -0.79305 0.01918 0.81095 -0.58507 0.00715 0.79300 -0.60921 0.00286 0.92423 -0.38184 -0.00239 0.94827 -0.31747 0.00259 0.99162 -0.12915 -0.00280 0.99545 -0.09530 -0.00008 -0.12638 -0.99198 0.00114 -0.19312 -0.98111 0.01146 -0.38648 -0.92230 -0.00056 -0.50699 -0.86190 0.00960 -0.60896 -0.79320 -0.00266 -0.79300 -0.60921 0.00296 -0.81111 -0.58485 0.00728 -0.92423 -0.38184 -0.00231 -0.99163 -0.12914 -0.00002 -0.97530 -0.22066 0.00986 0.00033 -1.00000 -0.00064 0.00071 -1.00000 -0.00051 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00071 -1.00000 -0.00051 -0.00435 -0.99999 0.00080 1.00000 0.00000 -0.00002 1.00000 0.00003 -0.00003 1.00000 0.00000 -0.00004 1.00000 0.00006 -0.00012 1.00000 0.00002 -0.00006 1.00000 0.00000 -0.00005 1.00000 -0.00000 -0.00004 -1.00000 0.00003 0.00002 -1.00000 -0.00004 0.00002 -1.00000 -0.00002 0.00003 -1.00000 -0.00001 0.00003 -1.00000 -0.00001 0.00003 -1.00000 -0.00000 0.00004 -1.00000 -0.00000 0.00004 -1.00000 -0.00000 0.00004 0.99386 0.11062 0.00001 0.99399 0.10945 -0.00006 0.94965 0.31330 0.00012 0.94429 0.32911 -0.00064 0.87678 0.48090 0.00059 0.84619 0.53288 -0.00126 0.79725 0.60365 0.00048 0.66534 0.74654 -0.00101 0.70699 0.70722 0.00251 0.53731 0.84339 -0.00092 0.47873 0.87796 -0.00308 0.53268 0.84632 0.00034 0.38651 0.92228 0.00018 0.30648 0.95187 -0.00200 0.22253 0.97490 -0.00686 0.24080 0.97054 -0.00825 0.13002 0.99151 -0.00223 0.03755 0.99929 0.00046 -0.99400 0.10941 0.00005 -0.99386 0.11063 -0.00001 -0.94966 0.31327 0.00016 -0.94429 0.32911 -0.00060 -0.87680 0.48086 0.00064 -0.84619 0.53288 0.00117 -0.79340 0.60869 -0.00405 -0.72016 0.69381 -0.00040 -0.70698 0.70721 0.00621 -0.56264 0.82666 -0.00898 -0.62316 0.78208 -0.00434 -0.47691 0.87895 -0.00316 -0.39694 0.91781 -0.00805 0.00028 1.00000 0.00046 -0.00000 1.00000 0.00054 -0.00028 1.00000 0.00046 -0.00043 1.00000 0.00126 -0.00008 1.00000 0.00073 0.00006 1.00000 0.00057 0.00017 1.00000 0.00049 -0.22254 0.97492 -0.00234 -0.26529 0.96412 -0.00948 -0.53130 0.84719 -0.00015 -0.53268 0.84632 0.00012 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00015 -1.00000 0.00004 0.00000 -0.26530 0.96416 -0.00233 -0.23574 0.97161 0.02001 -0.62513 -0.77886 0.05084 -0.30181 -0.95305 0.02454 -0.33016 -0.94392 0.00462 -0.32954 -0.94413 -0.00426 -0.00008 -1.00000 -0.00111 0.00056 -1.00000 0.00003 -0.12638 -0.99198 -0.00000 -0.12638 -0.99198 0.00000 -0.27370 -0.95899 -0.07368 -0.38588 -0.92099 -0.05363 -0.54347 -0.83600 -0.07576 -0.60829 -0.79233 -0.04689 -0.79300 -0.60922 0.00054 -0.92423 -0.38184 -0.00242 -0.91610 -0.40095 0.00194 -0.99043 -0.13802 0.00000 -0.99162 -0.12914 -0.00186 0.59854 -0.77997 0.18275 0.78515 -0.60149 0.14748 0.26397 -0.96113 0.08090 0.26035 -0.96202 0.08208 0.75170 -0.63672 0.17185 0.90408 -0.37380 0.20713 0.99118 -0.12904 0.03021 0.92888 -0.27427 0.24889 0.51993 -0.74683 0.41463 0.75982 -0.23558 0.60594 0.77282 -0.22598 0.59303 0.58640 -0.26856 0.76420 0.12797 -0.97041 0.20478 0.22703 -0.94630 0.23016 0.39792 -0.65997 0.63726 0.42274 -0.22529 0.87780 0.37068 -0.24842 0.89492 0.30668 -0.70741 0.63681 0.08815 -0.96538 0.24549 0.03413 -0.69185 0.72123 0.01227 -0.96574 0.25923 -0.01021 -0.97131 0.23759 0.03891 -0.96590 0.25596 0.12597 -0.26255 0.95666 0.00000 -0.22183 0.97508 0.00000 -0.70988 0.70432 -0.12597 -0.26255 0.95666 -0.06132 -0.96523 0.25410 -0.09606 -0.96739 0.23438 -0.10206 -0.96965 0.22217 -0.27445 -0.69009 0.66966 -0.30460 -0.71216 0.63249 -0.42087 -0.24324 0.87390 -0.37402 -0.21156 0.90297 -0.58640 -0.26856 0.76420 -0.15351 -0.96492 0.21301 -0.18300 -0.96848 0.16898 -0.18275 -0.96816 0.17110 -0.53285 -0.68846 0.49203 -0.54720 -0.71424 0.43638 -0.76094 -0.22959 0.60684 -0.77050 -0.23824 0.59124 -0.22247 -0.96497 0.13907 -0.24525 -0.96149 0.12403 -0.23841 -0.96689 0.09105 -0.63264 -0.70511 0.32027 -0.89045 -0.26656 0.36884 -0.60736 -0.78471 0.12386 -0.94578 -0.22726 0.23205 -0.30183 -0.95192 0.05238 -0.98211 -0.13686 0.12930 -0.87393 -0.38315 -0.29908 0.12908 -0.99163 0.00033 0.38166 -0.92430 0.00252 0.60810 -0.79208 -0.05302 0.69821 -0.71585 -0.00770 0.79300 -0.60921 -0.00311 0.92423 -0.38184 0.00099 0.91548 -0.40234 -0.00327 0.99095 -0.13426 -0.00100 0.99163 -0.12915 -0.00000 0.67743 -0.71061 0.19003 0.88672 -0.38978 0.24859 0.98583 -0.13356 0.10149 0.97943 -0.15522 0.12895 0.10904 -0.99402 0.00652 0.28762 -0.95764 -0.01413 0.68539 -0.69506 0.21709 0.24734 -0.96725 0.05695 0.20292 -0.97617 0.07692 0.89297 -0.25650 0.36988 0.22286 -0.96491 0.13884 0.49582 -0.71298 0.49581 0.51918 -0.70066 0.48941 0.68460 -0.25032 0.68459 0.78373 -0.15523 0.60139 0.58840 -0.25650 0.76681 0.18134 -0.96845 0.17094 0.18256 -0.96826 0.17072 0.15336 -0.96494 0.21299 0.26708 -0.68755 0.67523 0.09075 -0.96909 0.22942 0.10609 -0.96697 0.23177 0.36989 -0.25651 0.89296 0.17791 -0.72629 0.66397 0.25313 -0.20840 0.94472 0.12617 -0.25650 0.95828 0.06062 -0.96534 0.25385 0.01025 -0.96595 0.25851 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00016 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00018 -1.00000 -0.00016 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00005 -1.00000 -0.00120 -0.00028 -1.00000 -0.00000 -0.00056 -1.00000 0.00001 -0.00056 -1.00000 -0.00001 0.00056 -1.00000 0.00000 -0.00056 -1.00000 0.00000 -0.24527 0.96827 0.04780 -0.22826 0.97176 0.05986 -0.52672 0.83982 0.13141 -0.70313 0.70313 0.10591 -0.84328 0.53711 -0.01968 -0.68443 0.70188 0.19728 -0.91749 0.34514 0.19771 -0.99384 0.11078 0.00430 -0.94986 0.24120 0.19899 -0.23784 0.96508 0.10975 -0.55995 0.69789 0.44655 -0.20444 0.96521 0.16304 -0.16393 0.97257 0.16503 -0.20874 0.96701 0.14602 -0.55995 0.69789 0.44655 -0.75861 0.24188 0.60498 -0.78418 0.21995 0.58024 -0.14822 0.96543 0.21440 -0.10833 0.96833 0.22495 -0.10224 0.96931 0.22358 -0.31075 0.69789 0.64528 -0.31076 0.69788 0.64528 -0.41901 0.25970 0.87005 -0.50302 0.19754 0.84140 -0.06555 0.96514 0.25339 -0.17992 0.26654 0.94688 0.00000 0.96591 0.25888 0.02339 0.97201 0.23378 -0.01965 0.96671 0.25511 -0.00000 0.69788 0.71621 -0.00000 0.20957 0.97779 0.00000 0.69788 0.71621 0.18328 0.26830 0.94574 0.07118 0.96528 0.25131 0.10779 0.96865 0.22382 0.10822 0.96879 0.22301 0.31075 0.69788 0.64528 0.31076 0.69789 0.64528 0.42374 0.21506 0.87988 0.50829 0.25765 0.82174 0.15352 0.96523 0.21155 0.19299 0.96906 0.15390 0.19411 0.96633 0.16891 0.55995 0.69789 0.44655 0.76121 0.22812 0.60705 0.77241 0.23995 0.58806 0.55995 0.69789 0.44655 0.68963 0.70055 0.18341 0.34029 0.93821 0.06303 0.10972 0.98575 -0.12748 0.22349 0.97461 0.01382 0.23798 0.97024 0.04480 0.24426 0.96571 0.08796 0.82646 0.52526 0.20264 0.70487 0.70478 0.08027 0.53585 0.82616 -0.17414 0.95148 0.24029 0.19223 0.95126 0.23679 0.19759 -0.23579 0.97181 0.00000 -0.70710 0.70711 -0.00012 -0.70699 0.70722 -0.00015 -0.84619 0.53288 0.00015 -0.84349 0.53714 0.00100 -0.94429 0.32911 0.00023 -0.93617 0.35152 -0.00378 -0.99384 0.11079 -0.00023 -0.99386 0.11063 -0.00020 0.16683 0.98599 0.00000 0.22253 0.97488 0.00961 0.31131 0.95029 -0.00559 0.53268 0.84632 0.00090 0.53728 0.84340 0.00012 0.70711 0.70710 -0.00015 0.70699 0.70722 -0.00012 0.84619 0.53288 0.00015 0.84836 0.52942 -0.00054 0.94428 0.32911 -0.00505 0.96584 0.25905 0.00604 0.99276 0.11050 -0.04718 0.00000 0.96675 0.25571 0.01835 0.97120 0.23754 -0.00000 0.20957 0.97779 0.00000 0.69788 0.71621 0.18328 0.26830 0.94574 0.06562 0.96514 0.25337 0.31075 0.69788 0.64528 0.10721 0.96899 0.22263 0.10421 0.96814 0.22770 0.31076 0.69789 0.64528 0.42374 0.21507 0.87988 0.50828 0.25766 0.82175 0.14825 0.96544 0.21437 0.19861 0.96720 0.15839 0.19691 0.97068 0.13784 0.18227 0.96597 0.18353 0.55995 0.69788 0.44655 0.55995 0.69789 0.44655 0.76122 0.22813 0.60705 0.77262 0.24018 0.58769 0.23784 0.96508 0.10979 0.69018 0.70040 0.18194 0.31053 0.94863 0.06057 0.16655 0.98433 -0.05799 0.22783 0.97351 0.01938 0.24344 0.96781 0.06389 0.83000 0.51819 0.20635 0.70480 0.70479 0.08073 0.52727 0.82929 -0.18511 0.95178 0.23848 0.19296 0.95034 0.22152 0.21859 -0.99144 0.00004 0.13053 -0.97866 -0.00244 0.20549 -0.92388 0.00192 0.38268 -0.79334 0.00031 0.60877 -0.80376 -0.00036 0.59495 -0.60876 0.00190 0.79335 -0.51344 -0.00119 0.85812 -0.38268 0.00185 0.92388 -0.18634 -0.00064 0.98248 -0.13055 0.00120 0.99144 0.13055 0.00115 0.99144 0.19012 -0.00084 0.98176 0.38268 0.00203 0.92388 0.52607 -0.00097 0.85044 0.60877 0.00168 0.79335 0.79334 -0.00021 0.60878 0.79577 -0.00005 0.60559 0.96593 0.00000 0.25882 0.96593 0.00000 0.25882 0.97732 0.00358 0.21172 0.13054 0.00115 0.99144 0.19012 -0.00084 0.98176 0.38269 0.00203 0.92387 0.52607 -0.00097 0.85044 0.60877 0.00168 0.79335 0.79335 -0.00024 0.60876 0.79603 -0.00005 0.60525 0.92388 0.00218 0.38269 0.97412 -0.00171 0.22602 0.99144 -0.00000 0.13053 0.99246 0.00030 0.12254 0.97908 -0.00023 0.20350 0.99991 -0.01225 0.00613 1.00000 0.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00003 1.00000 -0.00027 0.00000 1.00000 0.00000 0.00239 -1.00000 0.00010 -0.00081 -1.00000 0.00244 -0.00022 -1.00000 0.00214 0.00022 -1.00000 0.00214 0.00081 -1.00000 0.00244 -0.00097 -1.00000 0.00113 1.00000 0.00000 -0.00002 0.12908 -0.99163 0.00065 0.26385 -0.96435 -0.02034 -0.04513 -0.68002 0.73180 -0.01600 -0.96561 0.25949 -0.03666 -0.97146 0.23435 -0.12616 -0.25650 0.95827 -0.17643 -0.73165 0.65845 -0.25313 -0.20840 0.94472 -0.08960 -0.96526 0.24546 -0.36989 -0.25651 0.89296 -0.40714 -0.65620 0.63533 -0.28836 -0.84526 0.44988 -0.17366 -0.97868 0.10966 -0.16250 -0.97165 0.17170 -0.49668 -0.71177 0.49668 -0.68460 -0.25032 0.68459 -0.60138 -0.15522 0.78374 -0.76681 -0.25650 0.58840 -0.89297 -0.25650 0.36988 -0.69498 -0.69451 0.18616 -0.73522 -0.59489 0.32490 -0.94448 -0.20867 0.25378 -0.98329 -0.12801 0.12945 -0.89309 -0.36896 -0.25740 -0.38120 -0.90897 0.16872 -0.26085 -0.96261 0.07303 -0.13240 -0.98940 0.05973 0.38166 -0.92430 -0.00263 0.59840 -0.80118 -0.00505 0.60896 -0.79320 -0.00278 0.70648 -0.70773 -0.00068 0.79286 -0.60911 0.01879 0.92406 -0.38178 0.01887 0.99163 -0.12914 -0.00018 0.97953 -0.20107 -0.00960 1.00000 -0.00157 -0.00043 -0.00002 -1.00000 -0.00068 -0.00002 -1.00000 0.00013 -0.00002 -1.00000 0.00006 -0.00002 -1.00000 0.00002 -0.00210 -1.00000 0.00111 -0.00048 -0.99999 -0.00524 0.00239 -1.00000 0.00008 -0.00185 -1.00000 -0.00213 -0.23168 0.97269 0.01428 -0.52948 0.83808 0.13144 -0.70321 0.70311 0.10552 -0.84427 0.53553 -0.02043 -0.36553 0.92804 0.07157 -0.11223 0.98871 0.09933 -0.23637 0.97137 0.02405 -0.21941 0.97476 0.04124 -0.92473 0.33145 0.18711 -0.99386 0.11061 0.00329 -0.97843 0.17869 0.10364 -0.68003 0.70286 0.20867 -0.86266 0.26917 0.42822 -0.55995 0.69789 0.44655 -0.20169 0.96615 0.16085 -0.32623 0.93363 0.14802 -0.55996 0.69788 0.44655 -0.76421 0.21114 0.60943 -0.65944 0.26063 0.70514 -0.15344 0.96524 0.21161 -0.10763 0.96874 0.22350 -0.10839 0.96863 0.22363 -0.31075 0.69789 0.64528 -0.42056 0.24599 0.87328 -0.49292 0.20030 0.84671 -0.31076 0.69788 0.64528 -0.07108 0.96528 0.25135 -0.17992 0.26654 0.94688 -0.00000 0.69788 0.71621 -0.02558 0.96626 0.25629 -0.99433 0.00000 0.10630 -0.99433 0.00000 0.10630 -0.99433 0.00000 0.10630 -0.99144 0.00083 0.13052 -0.92388 0.00121 0.38268 -0.89566 -0.00093 0.44475 -0.79335 0.00213 0.60876 -0.68423 -0.00064 0.72926 -0.60876 0.00107 0.79336 -0.50231 -0.00092 0.86468 -0.38270 0.00185 0.92387 -0.18634 -0.00064 0.98249 -0.13053 0.00121 0.99144 -0.11256 0.98952 0.09042 -0.37715 -0.49770 0.78106 -0.59381 -0.68830 0.41668 -0.45311 -0.80432 0.38439 0.74346 0.33559 -0.57849 0.75130 0.33239 -0.57015 0.36334 0.45632 -0.81226 0.37411 0.45573 -0.80768 0.37906 0.45604 -0.80519 0.05928 0.37141 -0.92657 0.24949 0.53468 -0.80739 0.13607 0.40198 -0.90548 0.84200 0.53395 -0.07701 0.45374 0.88933 0.05672 -0.67410 0.25741 0.69233 -0.68432 0.22999 0.69196 -0.64363 0.42045 0.63950 -0.63039 0.44778 0.63411 -0.58248 0.57083 0.57868 -0.56772 0.59291 0.57110 -0.50387 0.70406 0.50042 -0.48856 0.72086 0.49159 -0.41016 0.81613 0.40707 -0.39523 0.82794 0.39788 -0.29042 0.91105 0.29267 -0.89026 0.08336 -0.44776 -0.98699 0.09845 0.12712 -0.83906 0.09969 -0.53482 0.00027 0.72315 -0.69069 -0.00075 0.79510 -0.60648 -0.00942 0.78022 -0.62544 0.00268 0.83536 -0.54970 -0.00015 0.88490 -0.46577 0.00118 0.88758 -0.46066 -0.00114 0.95005 -0.31208 -0.00107 0.95014 -0.31182 0.00095 0.98598 -0.16688 -0.00292 0.98873 -0.14970 0.07724 0.99701 -0.00011 0.02792 0.99948 -0.01585 0.01220 0.99952 -0.02851 0.00275 0.99912 -0.04177 0.00147 0.99902 -0.04424 -0.00835 0.99982 0.01685 -0.00300 0.99991 -0.01309 -0.01646 0.99969 -0.01894 0.00126 0.99753 0.07023 -0.05103 0.99303 0.10622 0.42260 0.81392 -0.39867 0.47354 0.81794 -0.32669 0.93251 0.35202 -0.08070 0.36861 0.88323 -0.28987 0.92923 0.35781 -0.09215 0.43148 0.89183 -0.13591 0.39751 0.90473 -0.15313 0.91065 0.40845 -0.06225 0.92550 0.37665 -0.03978 0.33633 0.94174 0.00087 0.55095 0.83364 0.03868 0.27862 0.95992 -0.03051 0.92007 0.39097 0.02488 0.91019 0.41383 0.01724 0.98768 0.15374 0.02932 0.90263 0.43039 -0.00503 0.45179 0.02711 0.89171 0.46010 0.01347 0.88777 -0.18918 0.08439 0.97831 0.00749 0.13905 0.99026 0.50969 0.06569 0.85785 -0.49433 0.27846 0.82347 0.50650 0.11765 0.85418 0.50904 0.11294 0.85330 0.04395 0.30685 0.95074 -0.38456 0.41000 0.82705 -0.40103 0.42869 0.80957 0.04395 0.30685 0.95074 0.53655 0.14504 0.83131 -0.38334 0.57562 0.72229 0.12749 0.48136 0.86720 0.54343 0.17994 0.81995 0.53680 0.19865 0.81999 -0.26208 0.64036 0.72198 -0.28997 0.69621 0.65666 0.12749 0.48136 0.86720 0.57854 0.20950 0.78829 -0.20180 0.80021 0.56474 0.58076 0.23874 0.77828 0.24354 0.61356 0.75116 -0.10716 0.81604 0.56798 0.24354 0.61356 0.75116 0.60567 0.23195 0.76116 -0.11253 0.88419 0.45337 0.63524 0.26748 0.72452 0.63264 0.25378 0.73169 0.38189 0.69184 0.61280 0.38189 0.69183 0.61280 0.04978 0.93137 0.36064 0.06235 0.91482 0.39903 0.10809 0.96864 0.22372 -0.65727 0.54030 -0.52543 -0.62486 0.54410 -0.55992 -0.55243 0.58988 -0.58896 -0.47768 0.62122 -0.62122 -0.43485 0.61798 -0.65499 -0.50265 0.60914 -0.61343 -0.30034 0.67446 -0.67446 -0.31049 0.67352 -0.67080 -0.13273 0.69985 -0.70185 -0.08938 0.70704 -0.70150 0.04633 0.70428 -0.70840 0.15908 0.70319 -0.69298 0.22622 0.68940 -0.68815 0.32898 0.67175 -0.66372 0.40733 0.64372 -0.64784 0.53846 0.59823 -0.59344 0.52581 0.60510 -0.59781 0.70531 0.50957 -0.49282 0.76467 0.45585 -0.45550 0.81939 0.40451 -0.40616 0.84882 0.37910 -0.36848 0.94535 0.23085 -0.23027 0.95095 0.21682 -0.22062 0.99530 0.06846 -0.06846 0.99306 0.08515 -0.08117 0.13061 -0.87210 -0.47158 -0.28867 0.93989 0.18241 0.07548 -0.86680 -0.49291 0.07969 -0.86364 -0.49776 0.12792 -0.78522 -0.60586 0.08530 -0.74672 -0.65965 0.11121 -0.67497 -0.72942 0.07330 -0.63522 -0.76884 0.09116 -0.54544 -0.83318 0.05995 -0.50932 -0.85849 0.06785 -0.40086 -0.91362 0.04496 -0.37257 -0.92692 0.04266 -0.24540 -0.96848 0.02877 -0.22766 -0.97332 0.01187 -0.08264 -0.99651 0.01506 -0.07613 -0.99698 0.00009 -0.00006 -1.00000 0.00000 0.00000 -1.00000 -0.00415 0.00383 -0.99998 0.45196 0.00000 0.89204 0.70676 0.00501 0.70744 0.70604 0.00537 0.70815 0.70521 0.00563 0.70898 0.70422 0.00573 0.70996 0.69843 0.00000 0.71568 0.69859 0.00104 0.71552 0.69945 0.00288 0.71468 0.70060 0.00424 0.71354 0.70187 0.00513 0.71229 0.70310 0.00559 0.71107 0.00232 0.00474 -0.99999 -0.05594 -0.82159 -0.56733 0.18420 -0.79108 -0.58332 0.01476 -0.85919 -0.51144 -0.02640 -0.81272 -0.58206 -0.00329 -0.79008 -0.61299 0.05582 -0.74993 -0.65915 -0.03087 -0.67896 -0.73353 -0.02185 -0.66944 -0.74255 0.02603 -0.66920 -0.74262 0.04197 -0.63876 -0.76826 -0.02325 -0.50375 -0.86353 0.02718 -0.49542 -0.86823 0.01392 -0.51455 -0.85735 -0.01631 -0.49574 -0.86832 0.03194 -0.37419 -0.92680 -0.01449 -0.30661 -0.95172 -0.00148 -0.30141 -0.95349 -0.01018 -0.30144 -0.95343 0.02324 -0.22837 -0.97330 0.00106 -0.10242 -0.99474 -0.00525 -0.10051 -0.99492 -0.00766 -0.10056 -0.99490 -0.00527 -0.10054 -0.99492 0.00474 -0.07745 -0.99698 -0.04890 -0.88888 -0.45552 0.03656 -0.88033 -0.47296 -0.00338 -0.91134 -0.41164 -0.07234 -0.88355 -0.46272 0.06737 -0.89477 -0.44141 0.13924 -0.88713 -0.44001 -0.06006 -0.91885 -0.39001 0.03747 -0.90785 -0.41762 -0.07678 -0.91604 -0.39366 0.18202 -0.90555 -0.38321 0.06209 -0.93108 -0.35948 0.18925 -0.89988 -0.39294 -0.05695 -0.94552 -0.32055 -0.17298 -0.94479 -0.27829 0.06640 -0.92905 -0.36394 -0.06606 -0.94450 -0.32179 -0.19546 -0.94709 -0.25457 0.22966 -0.90665 -0.35389 0.23196 -0.90445 -0.35801 0.09473 -0.94707 -0.30674 -0.04324 -0.96755 -0.24897 -0.04016 -0.96668 -0.25281 -0.16996 -0.96704 -0.18962 0.09834 -0.94518 -0.31139 -0.29756 -0.94782 -0.11447 -0.18253 -0.96779 -0.17341 -0.31953 -0.94384 -0.08410 0.27078 -0.90621 -0.32476 0.12917 -0.95774 -0.25701 0.27121 -0.90576 -0.32565 0.27078 -0.90621 -0.32476 -0.01230 -0.98267 -0.18494 0.12202 -0.90000 -0.41847 0.12154 -0.89963 -0.41940 0.12733 -0.90868 -0.39761 0.13045 -0.92160 -0.36555 0.12863 -0.95634 -0.26244 0.22744 -0.89579 -0.38188 0.10051 -0.98546 -0.13696 0.19128 -0.93592 -0.29575 0.20627 -0.92579 -0.31682 0.13608 -0.91802 -0.37246 0.19814 -0.86524 -0.46054 0.16070 -0.93835 -0.30605 0.20875 -0.92419 -0.31983 0.21013 -0.92360 -0.32064 0.25633 -0.91574 -0.30937 0.24110 -0.90305 -0.35548 0.26061 -0.87912 -0.39904 0.27250 -0.89162 -0.36161 0.26061 -0.87912 -0.39904 0.30326 -0.90227 -0.30651 0.30924 -0.88496 -0.34816 0.29164 -0.89289 -0.34306 0.30035 -0.87672 -0.37570 0.30035 -0.87672 -0.37570 0.33924 -0.87821 -0.33714 0.33340 -0.88131 -0.33488 0.33451 -0.87413 -0.35213 0.33451 -0.87413 -0.35213 0.36553 -0.87122 -0.32767 0.36579 -0.87163 -0.32628 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00301 0.00003 1.00000 0.00008 0.00033 0.99996 -0.00341 -0.00777 0.99898 0.04513 -0.00040 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 0.83796 -0.54485 -0.03095 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 -0.71717 0.05795 0.69448 -0.55497 0.21372 0.80395 -0.80723 0.52726 0.26529 -0.72129 0.59767 0.35003 -0.78294 0.61492 0.09420 0.88315 -0.44351 0.15278 0.86726 -0.46700 0.17254 0.98507 -0.12747 0.11567 0.95233 -0.18593 0.24185 0.81160 -0.07581 0.57928 -0.06885 0.13460 0.98851 0.90736 -0.09318 0.40990 0.99993 -0.00799 0.00884 0.94954 -0.03318 0.31188 0.99791 -0.00455 0.06442 0.94000 -0.00574 0.34113 0.99982 0.00158 0.01894 0.81201 0.03161 0.58278 0.98286 0.04225 0.17947 0.98113 0.05168 0.18633 0.30593 -0.90594 -0.29269 0.47175 -0.88147 0.02145 0.49683 -0.86265 0.09489 0.69753 -0.71612 0.02514 0.69333 -0.72050 0.01343 0.37837 -0.87151 -0.31194 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 0.99978 0.01109 -0.01755 -0.32529 0.15854 -0.93223 -0.92768 0.09334 -0.36152 -0.42575 0.40413 -0.80958 -0.56426 0.33499 -0.75458 -0.89192 0.20196 -0.40458 -0.91677 0.16322 -0.36454 -0.34179 0.51889 -0.78354 -0.93004 0.20418 -0.30550 -0.46187 0.61849 -0.63572 -0.51754 0.58453 -0.62488 -0.89722 0.30792 -0.31650 -0.90712 0.28921 -0.30577 -0.33487 0.74919 -0.57147 -0.93086 0.29206 -0.21953 -0.48856 0.76967 -0.41100 -0.89255 0.40082 -0.20663 -0.01301 0.68308 -0.73023 0.96410 -0.25286 -0.08105 0.64621 -0.73047 -0.22098 0.65241 -0.72431 -0.22303 0.96329 -0.25501 -0.08391 0.65790 -0.71270 -0.24336 0.65631 -0.71352 -0.24524 0.89654 -0.41889 -0.14403 0.98256 -0.16595 -0.08387 0.96316 -0.25567 -0.08343 0.66412 -0.70490 -0.24912 0.33921 -0.88929 -0.30675 0.35368 -0.88176 -0.31211 0.36578 -0.87832 -0.30785 0.35780 -0.88287 -0.30417 0.39110 -0.87570 -0.28317 0.39121 -0.87564 -0.28322 0.36335 -0.87253 -0.32660 0.38429 -0.87037 -0.30786 0.37983 -0.87319 -0.30540 0.39741 -0.86898 -0.29485 0.38260 -0.86873 -0.31451 0.39150 -0.86707 -0.30810 0.39069 -0.86763 -0.30753 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.99995 -0.00744 0.00702 1.00000 0.00000 0.00000 0.99996 0.00838 -0.00276 1.00000 0.00000 -0.00000 0.01280 0.00534 -0.99990 0.04314 0.03423 -0.99848 -0.00008 0.00033 -1.00000 -0.26483 -0.01101 -0.96423 -0.40300 -0.00013 -0.91520 -0.60877 0.00076 -0.79335 -0.79332 0.00264 -0.60880 -0.95903 -0.00358 -0.28327 -0.94703 -0.00119 -0.32113 -0.88914 0.07034 -0.45220 -0.26074 0.17494 -0.94943 -0.60418 0.12249 -0.78737 -0.78350 0.15685 -0.60126 -0.95857 0.03104 -0.28314 0.01280 0.16519 -0.98618 0.00217 -0.99999 -0.00248 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 0.22443 -0.76869 -0.59896 -0.47303 0.77964 -0.41037 -0.90459 0.37603 -0.20080 -0.33698 0.89449 -0.29383 -0.93004 0.35022 -0.11127 -0.50689 0.84780 -0.15586 -0.43248 0.89148 -0.13498 -0.91310 0.40102 -0.07372 -0.87135 0.48590 -0.06817 -0.34806 0.93734 0.01580 -0.92763 0.37333 0.01075 -0.92204 0.38397 0.04897 -0.83964 0.53267 0.10616 -0.51768 0.84870 0.10824 -0.39748 0.90213 0.16787 -0.36773 0.87320 0.31983 -0.92352 0.35834 0.13674 -0.77819 0.56879 0.26627 -0.59766 0.73597 0.31803 -0.34482 0.88488 0.31320 -0.89380 0.40803 0.18608 -0.94013 0.29360 0.17308 -0.99322 0.08881 0.07497 -0.94116 0.30504 0.14549 -0.00285 0.98312 0.18294 0.01444 0.96237 0.27134 -0.04490 0.93805 0.34359 0.97987 -0.00926 -0.19942 0.83517 -0.06883 -0.54566 0.39271 -0.03282 -0.91907 0.52149 -0.10815 -0.84638 0.20219 -0.20117 -0.95846 0.98308 -0.04581 -0.17736 0.98040 -0.06235 -0.18691 0.83464 -0.17429 -0.52249 0.56861 -0.26034 -0.78032 0.83461 -0.17433 -0.52252 0.50097 -0.31907 -0.80450 0.29605 -0.35214 -0.88789 0.39530 -0.30590 -0.86612 0.98329 -0.07454 -0.16608 0.98049 -0.10182 -0.16812 0.83454 -0.28541 -0.47126 0.58231 -0.42119 -0.69535 0.83450 -0.28547 -0.47129 0.22118 -0.47357 -0.85253 0.40922 -0.54545 -0.73145 0.39100 -0.55458 -0.73455 0.48856 -0.52159 -0.69946 0.98275 -0.10354 -0.15325 0.83441 -0.38578 -0.39361 0.98112 -0.13537 -0.13812 0.98154 -0.13290 -0.13754 0.58798 -0.56623 -0.57764 0.83438 -0.38585 -0.39362 0.24479 -0.70319 -0.66753 0.37732 -0.79371 -0.47713 0.66848 -0.62182 -0.40802 0.36523 -0.82975 -0.42204 0.98297 -0.14883 -0.10782 0.83429 -0.46816 -0.29117 0.98016 -0.16832 -0.10468 0.52732 -0.74838 -0.40232 0.76900 -0.57053 -0.28834 0.98325 -0.16413 -0.07920 0.98411 -0.16712 -0.05997 0.97938 -0.19452 -0.05453 0.79208 -0.58936 -0.15897 0.54847 -0.81781 -0.17425 0.83754 -0.50942 -0.19754 0.24116 -0.90679 -0.34580 0.23757 -0.90988 -0.34012 0.28245 -0.89439 -0.34682 0.21185 -0.87484 -0.43563 0.35111 -0.77042 -0.53213 0.23246 -0.82996 -0.50707 0.36607 -0.76433 -0.53084 0.29801 -0.85201 -0.43044 0.15126 -0.85211 -0.50103 0.26637 -0.83419 -0.48288 0.35981 -0.76995 -0.52699 0.33968 -0.67842 -0.65144 0.15536 -0.69272 -0.70427 0.22851 -0.53218 -0.81521 0.12734 -0.61217 -0.78041 0.19141 -0.54438 -0.81671 0.15352 -0.61284 -0.77515 0.14113 -0.50569 -0.85109 0.17977 -0.48039 -0.85844 0.16662 -0.33673 -0.92674 0.13565 -0.36900 -0.91948 0.09008 -0.36191 -0.92785 0.09373 -0.35656 -0.92956 0.03520 -0.22558 -0.97359 0.08755 -0.21464 -0.97276 0.15205 -0.07548 -0.98549 0.01352 -0.12812 -0.99167 0.02579 -0.07399 -0.99693 -0.99738 0.05116 -0.05116 -0.99899 0.04470 -0.00439 -0.98455 0.12134 -0.12622 -0.97560 0.17227 -0.13609 -0.95772 0.20045 -0.20639 -0.92994 0.26932 -0.25035 -0.93731 0.26907 -0.22147 -0.89702 0.31184 -0.31322 -0.86148 0.36518 -0.35284 -0.84974 0.36469 -0.38070 -0.77099 0.45751 -0.44301 -0.74932 0.45996 -0.47640 0.98449 -0.17173 -0.03594 0.86553 -0.50071 0.01216 0.58103 -0.79151 -0.18954 0.45332 -0.87269 -0.18143 0.71134 -0.66686 -0.22201 0.66082 -0.72341 -0.19999 0.95265 -0.29031 -0.09049 0.96087 -0.26854 -0.06801 0.96093 -0.26548 -0.07836 0.23368 -0.92081 -0.31226 0.31773 -0.91141 -0.26148 0.27299 -0.92805 -0.25336 0.27643 -0.90848 -0.31344 0.32752 -0.90330 -0.27710 0.30867 -0.91302 -0.26667 0.39194 -0.87588 -0.28144 0.31510 -0.92106 -0.22882 0.31712 -0.91312 -0.25623 0.35462 -0.87823 -0.32087 -1.00000 0.00003 -0.00010 -1.00000 0.00119 -0.00002 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00072 -0.00011 -1.00000 -0.00104 0.00006 -1.00000 0.00008 -0.00002 -1.00000 0.00004 -0.00002 -1.00000 0.00003 -0.00002 -1.00000 0.00002 -0.00002 -1.00000 0.00001 -0.00001 -1.00000 0.00001 -0.00001 -1.00000 0.00001 -0.00001 -1.00000 0.00000 -0.00001 -1.00000 0.00000 -0.00001 -1.00000 -0.00014 0.00006 -1.00000 0.00027 -0.00002 -0.00214 0.07474 -0.99720 -0.00000 0.07845 -0.99692 0.00194 0.22262 -0.97490 -0.00385 0.23343 -0.97237 0.00365 0.36554 -0.93079 -0.00548 0.38265 -0.92388 0.00517 0.50018 -0.86590 -0.00693 0.52245 -0.85264 0.00652 0.62359 -0.78173 -0.00818 0.64940 -0.76040 0.00767 0.73307 -0.68011 -0.00922 0.76035 -0.64944 -0.02101 0.92367 -0.38262 -0.01645 0.97224 -0.23343 -0.00000 0.99824 -0.05927 0.35722 0.17212 -0.91802 0.11166 0.07428 -0.99097 0.96038 0.02415 -0.27766 0.98787 0.10823 -0.11131 0.93250 0.04989 -0.35771 0.69547 0.07868 -0.71423 0.82909 0.18337 -0.52819 0.70147 0.12593 -0.70149 0.52989 0.11076 -0.84080 0.31479 0.13244 -0.93988 0.24810 0.21566 -0.94442 0.96721 0.06551 -0.24540 0.96565 0.10962 -0.23559 0.96253 0.10377 -0.25053 0.70945 0.26970 -0.65111 0.27135 0.35183 -0.89587 0.31293 0.38072 -0.87013 0.69322 0.28890 -0.66029 0.24214 0.48530 -0.84015 0.96571 0.14876 -0.21279 0.71432 0.42602 -0.55520 0.96251 0.16513 -0.21521 0.68874 0.46005 -0.56036 0.28820 0.59714 -0.74858 0.30555 0.60419 -0.73593 0.96720 0.17949 -0.17972 0.23996 0.71167 -0.66026 0.71854 0.55177 -0.42339 0.96566 0.21274 -0.14912 0.96253 0.21514 -0.16509 0.59454 0.70061 -0.39455 0.34383 0.81964 -0.45823 0.32452 0.82202 -0.46793 0.96570 0.23530 -0.10984 0.68411 0.67386 -0.27912 0.96251 0.25060 -0.10380 0.96720 0.24532 -0.06582 0.35188 0.90903 -0.22328 0.34778 0.91888 -0.18628 0.70146 0.70148 -0.12599 0.84506 0.53093 -0.06309 0.96537 0.25549 -0.05276 0.93369 0.33075 -0.13719 0.99366 0.11196 -0.00981 0.02596 -0.07364 -0.99695 0.02719 -0.07262 -0.99699 0.11416 -0.15023 -0.98204 0.33588 -0.11082 -0.93536 0.56277 -0.08353 -0.82238 0.84148 -0.06213 -0.53671 0.93964 -0.12022 -0.32035 0.99372 -0.00942 -0.11149 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00213 -0.00242 -0.99999 -0.00000 0.00064 -1.00000 0.99377 0.00000 -0.11149 0.99371 0.00031 -0.11197 0.94640 -0.00028 -0.32300 0.93344 0.01977 -0.35818 0.84279 -0.02596 -0.53761 0.84359 -0.02714 -0.53630 0.70688 0.02458 -0.70690 0.56408 -0.05169 -0.82410 0.53293 -0.02365 -0.84583 0.33773 0.02283 -0.94097 0.36271 0.00292 -0.93190 0.11547 -0.00229 -0.99331 0.11197 0.00000 -0.99371 0.53068 0.83134 -0.16509 0.63799 0.75138 -0.16850 0.11178 0.99199 -0.05890 0.40884 0.89732 -0.16631 -0.01167 0.99685 -0.07846 -0.01644 0.97224 -0.23341 0.04465 0.87104 -0.48918 0.01656 0.85251 -0.52245 1.00000 0.00000 0.00000 0.00068 1.00000 0.00005 1.00000 0.00139 -0.00221 1.00000 0.00000 -0.00000 1.00000 -0.00057 -0.00007 0.96108 -0.18408 0.20600 -0.53626 -0.00717 0.84402 -0.55044 -0.01512 0.83474 -0.54727 -0.01162 0.83688 -0.54385 -0.00046 0.83918 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 1.00000 0.00000 -0.00000 0.37766 -0.86405 -0.33286 0.23688 -0.10002 0.96638 0.45395 -0.46288 0.76137 0.52006 -0.48691 0.70175 0.54044 -0.63883 0.54756 0.01391 0.58449 0.81128 0.28188 -0.10246 0.95396 0.17574 0.03601 0.98378 0.34837 -0.11248 0.93058 0.48158 -0.02409 0.87607 0.49105 -0.03750 0.87032 0.45549 -0.46198 0.76099 0.59290 -0.35278 0.72389 0.49711 -0.66547 0.55681 0.48479 -0.64095 0.59512 0.65255 -0.54130 0.53025 0.61616 -0.70852 0.34402 0.54542 -0.83759 -0.03087 0.46533 -0.86933 -0.16653 0.35532 -0.93401 -0.03705 0.61884 -0.71504 0.32518 0.45305 -0.88854 -0.07238 0.40190 -0.90708 -0.12525 0.62780 -0.70164 0.33700 0.64446 -0.34229 0.68374 0.64690 -0.31906 0.69262 0.49574 -0.01488 0.86834 0.31042 -0.90359 -0.29524 0.19712 -0.94212 -0.27119 0.30595 -0.90474 -0.29638 0.25619 0.08329 0.96303 0.35441 0.05971 0.93318 0.65589 0.07864 0.75075 0.33233 -0.07304 0.94033 0.70502 -0.07075 0.70565 0.18563 -0.13329 0.97354 0.59359 -0.13713 0.79300 0.26145 -0.22915 0.93762 0.09384 -0.30455 0.94786 0.64705 -0.20609 0.73407 0.50628 -0.30629 0.80614 0.92086 -0.11615 0.37219 0.20414 -0.39211 0.89698 0.85379 -0.22507 0.46945 0.99414 -0.02716 0.10461 0.03058 -0.45502 0.88996 0.58375 -0.35222 0.73156 0.98612 -0.08230 0.14419 0.38079 -0.49582 0.78049 0.49721 -0.44686 0.74370 0.87158 -0.23252 0.43161 0.98167 -0.08871 0.16868 0.73298 -0.41723 0.53728 -0.49780 0.00049 0.86729 -0.53505 -0.00673 0.84479 0.06065 -0.40107 0.91404 -0.00335 -0.25160 0.96783 0.01577 -0.09440 0.99541 0.06214 -0.01977 0.99787 0.09038 0.06707 0.99365 0.09117 0.07842 0.99274 0.19419 0.29610 0.93521 0.13442 0.18590 0.97333 0.10863 0.16946 0.97953 0.11531 0.17850 0.97716 0.11753 0.10784 0.98720 0.17125 0.08539 0.98152 0.12379 0.06446 0.99021 0.24679 -0.07474 0.96618 0.35050 0.03207 0.93601 0.39220 0.05271 0.91837 0.36788 -0.04795 0.92864 0.78976 -0.09106 0.60662 0.66966 -0.30065 0.67909 0.72318 -0.28607 0.62863 0.37583 0.29608 0.87811 0.46053 0.19281 0.86645 0.39487 0.29723 0.86933 0.32214 0.28835 0.90171 0.38228 0.15263 0.91135 0.34096 0.29127 0.89382 0.31917 0.24590 0.91524 0.24376 0.28028 0.92845 0.28428 0.12676 0.95032 0.21391 0.20920 0.95419 0.20973 0.16969 0.96292 0.16269 0.22790 0.96000 0.15327 0.09099 0.98399 0.17915 0.02928 0.98339 0.16703 0.07723 0.98292 0.13319 0.12558 0.98310 -0.72461 0.66718 -0.17263 -0.64765 0.40925 -0.64270 -0.72537 0.66588 -0.17446 -0.55727 0.82129 0.12221 -0.72461 0.66718 -0.17263 -0.55062 0.79718 0.24764 -0.78114 0.61235 -0.12185 -0.73373 0.59258 0.33241 -0.72407 0.39819 0.56318 -0.09458 0.02775 0.99513 -0.37204 0.21849 0.90214 -0.47570 0.32103 0.81893 -0.40013 0.74685 0.53114 -0.60544 0.53951 0.58512 -0.77736 0.62326 -0.08523 -0.19258 0.74450 0.63924 -0.32484 0.00105 0.94577 -0.56236 0.14376 0.81430 -0.64037 -0.00028 -0.76806 -0.49276 0.00237 -0.87016 -0.41716 0.00532 -0.90882 -0.33998 0.00245 -0.94043 -0.13747 -0.00143 -0.99051 0.08637 0.00025 -0.99626 0.25539 0.00782 -0.96681 0.31937 0.00426 -0.94762 0.54563 -0.00105 -0.83803 0.71226 0.02560 -0.70144 0.93160 -0.00080 -0.36348 -0.30416 0.90367 0.30146 -0.18905 0.96405 0.18675 -0.17716 0.96777 0.17900 -0.06828 0.99545 0.06640 -0.05877 0.99646 0.06018 0.05452 0.99694 -0.05595 0.06133 0.99629 -0.06038 0.17567 0.96847 -0.17664 0.17968 0.96727 -0.17919 0.29178 0.91090 -0.29178 -0.70674 0.00018 -0.70747 -0.70611 0.00492 -0.70809 -0.61196 0.16866 -0.77269 -0.46813 0.38436 -0.79569 -0.44363 0.41038 -0.79673 -0.69206 0.03289 -0.72109 -0.48019 0.38657 -0.78739 -0.40348 0.47314 -0.78316 -0.38153 0.49799 -0.77874 -0.39694 0.47979 -0.78245 -0.44098 0.43297 -0.78618 -0.40228 0.50656 -0.76261 -0.34299 0.53871 -0.76951 -0.24323 0.62462 -0.74208 -0.19831 0.66189 -0.72289 -0.04255 0.76144 -0.64683 0.10821 0.82845 -0.54951 0.27356 0.86693 -0.41665 -0.44726 0.88269 0.14429 -0.75424 0.39578 -0.52391 -0.36634 0.92877 -0.05634 -0.35602 0.93444 0.00824 -0.57417 0.75230 -0.32308 -0.57417 0.75230 -0.32308 -0.69341 0.48731 -0.53076 -0.69411 0.49033 -0.52705 -0.20769 0.97526 -0.07574 -0.64096 0.47871 -0.60001 -0.14771 0.96017 -0.23718 -0.15512 0.95287 -0.26071 -0.41269 0.77129 -0.48456 -0.41269 0.77129 -0.48456 -0.54553 0.58509 -0.60005 -0.55466 0.54384 -0.62975 0.02743 0.94790 -0.31739 -0.50278 0.50624 -0.70066 -0.24694 0.71941 -0.64920 0.01823 0.89022 -0.45516 0.14343 0.94816 -0.28359 0.02092 0.85122 -0.52440 -0.43186 0.52573 -0.73288 -0.27682 0.71995 -0.63643 -0.17014 0.84707 -0.50352 -0.19663 0.73931 -0.64402 -0.45398 -0.84709 0.27630 -0.45336 -0.84836 0.27340 -0.45223 -0.86230 0.22788 -0.30938 -0.84587 0.43451 -0.31640 -0.85101 0.41914 -0.32734 -0.85421 0.40396 -0.19253 -0.84339 0.50162 -0.21017 -0.82126 0.53043 0.09595 -0.70459 0.70310 0.27925 -0.53463 0.79762 0.33612 -0.58740 0.73619 0.50998 -0.31935 0.79870 0.73324 -0.11449 0.67026 0.69769 -0.07380 0.71259 0.71001 0.09334 0.69797 0.71342 0.11150 0.69181 0.44660 0.28490 0.84817 0.42570 0.34563 0.83625 0.49308 0.35893 0.79249 0.47192 0.33974 0.81355 0.48858 0.35542 0.79685 0.50407 0.30407 0.80836 0.54130 0.35319 0.76306 0.51591 0.34372 0.78466 0.54947 0.35729 0.75527 0.55754 0.31099 0.76970 0.59175 0.34319 0.72942 0.56677 0.34312 0.74903 0.61338 0.34863 0.70868 0.61520 0.31115 0.72437 0.62363 0.33026 0.70853 0.64273 0.32843 0.69212 0.66688 0.30032 0.68197 0.66895 0.32925 0.66641 0.67344 0.30988 0.67116 0.68739 0.30795 0.65777 0.71397 0.30241 0.63150 0.70954 0.27941 0.64691 0.71229 0.28197 0.64275 0.68835 0.34821 0.63633 0.74850 0.25388 0.61262 0.75148 0.26301 0.60507 0.80083 0.29475 0.52134 0.75681 0.25970 0.59983 0.78445 0.22816 0.57669 0.78005 0.20708 0.59046 0.79116 0.20451 0.57641 0.79170 0.23137 0.56540 0.80416 0.18675 0.56432 0.81091 0.15960 0.56299 0.82230 0.15237 0.54827 0.83244 0.19121 0.52008 0.82678 0.11503 0.55064 0.83170 0.08125 0.54924 0.84808 -0.01669 0.52960 0.13091 -0.95676 -0.25974 -0.14896 -0.98311 -0.10637 -0.01483 -0.98334 -0.18115 -0.15702 -0.98311 -0.09404 -0.28506 -0.95833 -0.01832 -0.29866 -0.95435 0.00387 -0.43055 -0.89842 0.08642 -0.43412 -0.89521 0.10069 0.16497 -0.96445 -0.20643 0.02009 -0.99224 -0.12274 0.09740 -0.98125 -0.16629 0.15388 -0.96483 -0.21315 -0.03211 -0.99607 -0.08252 0.03310 -0.98901 -0.14411 -0.11736 -0.99264 -0.02984 -0.25592 -0.96410 0.07086 -0.16279 -0.98662 0.00880 -0.10122 -0.99319 -0.05763 -0.39055 -0.90163 0.18584 -0.33754 -0.93102 0.13882 -0.28158 -0.95521 0.09104 -0.23394 -0.97180 0.02977 -0.41348 -0.89274 0.17905 -0.44754 -0.86558 0.22467 -0.40912 -0.89810 0.16137 0.51493 0.13537 0.84647 0.54464 0.11776 0.83036 0.60911 -0.35745 0.70796 0.54714 0.10321 0.83065 0.54651 0.12203 0.82851 0.60694 -0.36523 0.70586 0.51688 -0.75905 0.39583 0.51237 -0.76444 0.39130 0.33939 -0.93857 0.06239 0.33594 -0.93999 0.05969 0.23633 -0.97104 0.03493 0.56947 0.10512 0.81526 0.56418 -0.37381 0.73619 0.57227 0.11905 0.81138 0.56235 -0.37791 0.73549 0.40679 -0.78570 0.46604 0.16299 -0.98123 0.10304 0.26209 -0.94698 0.18586 0.40382 -0.78852 0.46387 0.12047 -0.98446 0.12780 0.59504 0.09132 0.79849 0.52880 -0.37731 0.76026 0.60951 0.12085 0.78351 0.30599 -0.78679 0.53603 0.52745 -0.37947 0.76013 0.30417 -0.78816 0.53506 0.01435 -0.98266 0.18488 0.17156 -0.93705 0.30415 0.00491 -0.97436 0.22496 0.62284 0.08588 0.77762 -0.06248 -0.96671 0.24813 0.64081 0.10404 0.76061 0.48954 -0.37016 0.78951 0.20417 -0.76346 0.61273 0.48799 -0.37199 0.78961 -0.06535 -0.93365 0.35217 -0.06813 -0.93401 0.35068 0.20230 -0.76455 0.61199 0.64413 0.08126 0.76059 -0.17733 -0.92525 0.33536 0.44173 -0.34876 0.82659 0.68964 0.13086 0.71223 0.66294 0.08758 0.74353 0.49288 -0.30563 0.81466 0.10108 -0.71364 0.69318 -0.21116 -0.87870 0.42814 -0.14894 -0.87297 0.46448 0.10565 -0.71178 0.69441 -0.28808 -0.86206 0.41696 0.91485 -0.20150 0.34992 0.90311 -0.15938 0.39873 0.88859 -0.11254 0.44468 0.87019 -0.05658 0.48946 0.85247 0.00678 0.52274 0.80218 0.12953 0.58287 -0.00015 -0.99992 -0.01263 -0.00067 -0.99989 -0.01467 0.00000 -0.99996 -0.00925 -0.41892 -0.90344 0.09113 -0.45134 -0.89229 -0.01032 -0.42374 -0.90574 -0.00948 -0.32299 -0.93012 -0.17480 -0.44401 -0.88822 -0.11794 -0.39608 -0.91111 -0.11406 0.70735 0.00458 0.70685 0.70785 0.00410 0.70635 0.70825 0.00361 0.70595 0.70906 0.00236 0.70515 0.70711 0.00000 0.70711 0.70711 0.00000 0.70711 0.71412 -0.00566 0.70000 0.70900 0.00028 0.70521 0.67873 0.00074 0.73439 -0.20201 -0.84844 0.48923 -0.47056 -0.83934 0.27216 -0.47339 -0.83408 0.28323 -0.41620 -0.87766 0.23769 -0.45618 -0.84470 0.27996 -0.46943 -0.83433 0.28902 -0.45223 -0.86230 0.22788 -0.41518 -0.87772 0.23923 -0.46639 -0.83490 0.29229 -0.41553 -0.87064 0.26328 -0.46430 -0.86460 0.19205 -0.48018 -0.85357 0.20211 -0.48146 -0.86664 0.13091 -0.46477 -0.85994 0.21093 -0.46830 -0.86442 0.18293 -0.47048 -0.86298 0.18417 -0.48609 -0.85727 0.16973 -0.49005 -0.86094 0.13647 -0.48613 -0.86550 0.12076 -0.46105 -0.88093 0.10673 -0.49623 -0.86762 0.03148 -0.46329 -0.88016 0.10334 -0.49635 -0.85895 0.12582 -0.49398 -0.86106 0.12065 -0.49400 -0.86624 0.07478 -0.46250 -0.88601 0.03297 -0.48023 -0.87616 0.04151 -0.49069 -0.86856 -0.06950 -0.48087 -0.87643 0.02531 -0.47163 -0.88150 0.02309 -0.42902 -0.90181 0.05179 -0.44026 -0.89684 -0.04287 -0.44366 -0.89523 -0.04153 -0.43811 -0.89887 -0.00900 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.99999 0.00201 0.00456 -1.00000 -0.00005 0.00040 -1.00000 -0.00037 0.00002 0.00006 -0.00042 1.00000 -0.00051 -0.00006 1.00000 -0.38666 0.00513 0.92221 -0.49078 -0.01193 0.87120 -0.91380 0.01144 0.40601 -0.94048 0.00151 0.33984 0.78154 0.00000 -0.62385 0.78184 -0.00004 -0.62348 0.89911 0.00004 -0.43772 0.90097 -0.00030 -0.43389 0.97255 0.00030 -0.23269 0.97493 -0.00052 -0.22252 0.99989 0.00051 -0.01458 1.00000 -0.00061 -0.00000 0.97799 0.00062 0.20866 0.97493 -0.00049 0.22252 0.90518 0.00051 0.42504 0.90097 -0.00028 0.43388 0.78402 0.00029 0.62073 0.75741 -0.00318 0.65293 0.78350 0.03641 0.62032 0.80946 0.08877 0.58043 0.79493 0.05167 0.60450 0.78860 0.19223 0.58408 0.80773 0.09172 0.58237 0.82851 0.24406 0.50400 0.90218 0.08132 0.42363 0.96470 0.16429 0.20583 0.96508 0.16784 0.20114 0.87739 0.36596 0.31027 0.87067 0.39392 0.29455 0.84607 0.51084 0.15234 0.98309 0.18259 -0.01433 0.94081 0.25339 -0.22510 0.95524 0.22915 -0.18708 0.80063 0.59686 -0.05254 0.80988 0.58521 -0.04031 0.69774 0.67783 -0.23174 0.87204 0.24353 -0.42455 0.67475 0.68234 -0.28128 0.74641 0.29644 -0.59581 0.95409 0.09460 -0.28420 0.82883 0.30580 -0.46855 0.72151 0.50099 -0.47795 0.75783 0.62139 -0.19891 0.48814 0.80969 -0.32576 0.42350 0.86622 -0.26516 0.42596 0.86577 -0.26268 0.56958 0.81799 -0.08037 0.56559 0.82025 -0.08547 0.67156 0.73587 0.08665 0.67569 0.73122 0.09364 0.74476 0.61659 0.25525 0.74888 0.60716 0.26559 0.78264 0.46590 0.41281 0.78408 0.45589 0.42116 0.78258 0.30155 0.54464 0.78148 0.28438 0.55535 0.74144 0.09762 0.66388 0.74133 0.09720 0.66406 0.46094 0.88717 0.02133 0.36986 0.90455 -0.21209 0.65764 0.54677 0.51822 0.65738 0.67553 0.33391 0.59222 0.78959 0.16070 0.45964 0.88808 -0.00723 0.76138 0.26506 0.59165 0.67668 0.14572 0.72172 0.74593 0.32923 0.57896 0.68732 0.65909 0.30528 0.34411 0.93892 -0.00424 0.72858 0.24679 0.63895 0.26118 0.95440 0.14459 0.26610 0.94740 0.17782 0.53039 0.70930 0.46430 0.69505 0.27347 0.66493 0.69345 0.26904 0.66838 0.53039 0.70930 0.46430 0.66675 0.25277 0.70111 0.26551 0.86626 -0.42319 0.09698 0.82390 -0.55838 -0.07392 0.74235 -0.66593 -0.54683 0.29542 -0.78339 0.70711 0.00000 -0.70711 0.70711 0.00000 -0.70711 0.40966 0.81508 -0.40966 0.41055 0.81402 -0.41087 0.52092 0.67646 -0.52061 0.52329 0.67200 -0.52400 0.60918 0.50859 -0.60847 0.61148 0.50131 -0.61219 0.67118 0.31623 -0.67046 0.67200 0.31050 -0.67231 0.70318 0.10741 -0.70286 0.70315 0.10560 -0.70315 0.34651 0.87170 -0.34651 0.34651 0.87170 -0.34651 0.29255 0.91024 -0.29306 -0.26784 -0.96216 0.04999 -0.39825 -0.91268 0.09174 -0.42766 -0.89787 0.10456 -0.25193 -0.96624 0.05399 -0.30961 -0.94743 0.08078 -0.34942 -0.93219 0.09444 -0.43454 -0.89338 0.11423 -0.28015 -0.95593 0.08778 -0.08963 -0.99555 0.02920 -0.40126 -0.90572 0.13660 -0.25567 -0.96172 0.09866 -0.42785 -0.88864 0.16510 -0.08917 -0.99533 0.03705 -0.08509 -0.99568 0.03725 -0.26844 -0.95610 0.11753 -0.39243 -0.90289 0.17546 -0.08595 -0.99523 0.04608 -0.24184 -0.96186 0.12780 -0.41024 -0.88584 0.21679 -0.37911 -0.89958 0.21687 -0.25329 -0.95597 0.14820 0.00000 -0.00160 -1.00000 -0.09886 0.00151 -0.99510 -0.23933 -0.00143 -0.97094 -0.32258 0.00099 -0.94654 -0.46476 -0.00120 -0.88544 -0.51318 0.00067 -0.85828 -0.66316 -0.00053 -0.74848 -0.68014 0.00040 -0.73309 -0.82751 -0.00007 -0.56145 -0.82301 -0.00041 -0.56803 -0.97052 0.00016 -0.24103 -0.93498 0.01068 -0.35455 -0.99271 -0.00000 -0.12052 -0.26904 -0.00000 0.96313 0.70833 -0.00605 0.70585 0.21524 -0.56304 0.79791 -0.11691 -0.00186 -0.99314 -0.14114 -0.12611 -0.98192 -0.10237 0.38309 -0.91802 -0.02680 0.57981 -0.81431 -0.01268 0.77763 -0.62860 -0.00904 0.73493 -0.67808 0.00068 0.80610 -0.59178 -0.00108 0.85264 -0.52250 0.01511 0.91028 -0.41371 0.01390 0.92379 -0.38265 0.02031 0.94338 -0.33109 0.01342 0.97228 -0.23342 0.02136 0.98991 -0.14007 0.01795 0.99676 -0.07845 0.02256 0.99927 -0.03097 -0.00254 0.02715 -0.99963 0.70027 -0.25419 -0.66709 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.85182 0.37635 -0.36437 0.49035 -0.14364 -0.85961 0.33670 -0.13168 -0.93236 0.27274 -0.36710 -0.88930 -0.17181 -0.16994 -0.97036 0.88084 -0.21545 -0.42155 0.52655 -0.35895 -0.77065 0.43999 -0.26620 -0.85764 0.83164 -0.16971 -0.52875 0.64705 -0.29844 -0.70161 0.64597 -0.29385 -0.70454 -0.99972 0.00904 0.02167 0.84354 0.44158 -0.30569 0.85233 0.42369 -0.30664 0.84544 0.39219 -0.36251 0.99999 -0.00154 0.00364 1.00000 -0.00004 0.00024 1.00000 0.00004 -0.00021 0.99998 -0.00008 0.00555 1.00000 -0.00167 0.00103 0.99998 -0.00116 -0.00543 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 -0.99998 0.00105 -0.00542 -0.99998 0.00041 -0.00585 -0.95157 -0.21717 0.21763 -0.97135 -0.15403 -0.18098 -0.11021 -0.36691 -0.92371 -0.11021 -0.37742 -0.91946 -0.28870 -0.94076 -0.17783 -0.27373 -0.93935 -0.20663 -0.26439 -0.92372 -0.27720 -0.26412 -0.90207 -0.34133 -0.25030 -0.88459 -0.39350 -0.24398 -0.83325 -0.49615 -0.23022 -0.81220 -0.53603 -0.21648 -0.73959 -0.63729 -0.20440 -0.71901 -0.66426 -0.18613 -0.62266 -0.76003 -0.18487 -0.63448 -0.75051 -0.19445 -0.63456 -0.74801 -0.15710 -0.55161 -0.81917 -0.15864 -0.61231 -0.77454 -0.19033 -0.64605 -0.73919 -0.14755 -0.48683 -0.86094 -0.13671 -0.47755 -0.86790 -0.10090 -0.33636 -0.93631 -0.10809 -0.34240 -0.93331 -0.00869 -0.20153 -0.97944 -0.05392 -0.20445 -0.97739 -0.06813 -0.17466 -0.98227 -0.00375 0.00000 -0.99999 -0.00318 0.00019 -0.99999 -0.92486 0.01457 -0.38002 -0.84035 -0.00942 -0.54197 -0.41922 0.00855 -0.90784 -0.35818 0.00014 -0.93365 -0.00056 -1.00000 0.00086 -0.05784 -0.99833 0.00020 0.01407 -0.99990 -0.00224 0.00670 -0.99998 -0.00141 -0.11453 -0.99285 0.03360 0.01814 -0.99983 -0.00276 -1.00000 0.00000 0.00001 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00001 -1.00000 0.00000 0.00000 -0.99999 0.00019 0.00359 -1.00000 0.00124 0.00107 -1.00000 0.00131 0.00078 -1.00000 0.00132 0.00050 -0.99997 -0.00048 -0.00738 -1.00000 0.00130 0.00025 -1.00000 -0.00018 -0.00001 -1.00000 -0.00052 0.00124 -0.98205 -0.05351 -0.18088 -0.99957 -0.01030 -0.02746 -0.99982 -0.00296 0.01859 -1.00000 -0.00037 -0.00014 -1.00000 -0.00018 -0.00000 -0.26814 -0.91828 -0.29129 -0.37694 -0.90683 -0.18863 -0.27016 -0.94329 -0.19294 -0.26940 -0.95781 -0.10011 -0.38145 -0.91673 -0.11875 -0.37897 -0.92297 -0.06717 -0.37886 -0.90393 -0.19843 -0.44899 -0.88802 -0.09911 -0.38178 -0.91646 -0.11976 -0.43804 -0.89850 -0.02856 -0.37459 -0.92616 -0.04365 -0.02661 -0.00426 -0.99964 0.04036 0.04177 -0.99831 0.01030 -0.00537 -0.99993 -0.84785 0.46175 -0.26065 -0.13187 0.86725 -0.48010 -0.23813 0.79807 -0.55351 -1.00000 0.00228 0.00106 -0.99992 0.00890 0.00936 -1.00000 0.00062 0.00088 -0.99999 0.00317 0.00229 -1.00000 0.00002 0.00108 -0.99997 0.00396 0.00590 -1.00000 0.00227 0.00181 -0.99958 0.02851 0.00482 -0.99999 -0.00304 0.00344 -0.99999 -0.00414 0.00242 -0.99997 -0.00464 -0.00536 -1.00000 0.00129 -0.00214 -0.99999 0.00007 -0.00537 -0.99999 0.00185 -0.00435 -0.99989 -0.01436 0.00479 -0.99952 0.01269 0.02834 -0.99968 -0.02528 0.00298 -0.99941 0.01254 0.03195 -0.20497 -0.89639 -0.39303 -0.17737 -0.84674 -0.50157 -0.12108 -0.85530 -0.50378 -0.18938 -0.82301 -0.53552 -0.08552 -0.81814 -0.56863 -0.16084 -0.73336 -0.66054 -0.15808 -0.73131 -0.66347 -0.10885 -0.74262 -0.66081 -0.06638 -0.67620 -0.73372 -0.14131 -0.61684 -0.77430 -0.09200 -0.60033 -0.79444 -0.12608 -0.60194 -0.78853 -0.03267 -0.50304 -0.86364 0.01233 -0.48371 -0.87514 -0.08330 -0.57927 -0.81087 0.00414 -0.30803 -0.95137 -0.05415 -0.34842 -0.93577 -0.03687 -0.12814 -0.99107 -0.11255 -0.88717 -0.44750 -0.15992 -0.89843 -0.40896 -0.25506 -0.89111 -0.37534 -0.19939 -0.90654 -0.37205 -0.33538 -0.90069 -0.27620 -0.15136 -0.91770 -0.36730 -0.18974 -0.92276 -0.33542 -0.24074 -0.91625 -0.32020 -0.33243 -0.90791 -0.25532 -0.40548 -0.89436 -0.18896 -0.30163 -0.91561 -0.26584 -0.28549 -0.93343 -0.21728 0.00148 -1.00000 -0.00000 0.00561 -0.99997 0.00566 0.01502 -0.99983 0.01061 0.09285 -0.99523 0.02987 -0.01022 -0.98616 -0.16551 -0.00125 0.00438 -0.99999 -1.00000 -0.00030 -0.00026 -1.00000 0.00018 -0.00015 -1.00000 0.00078 0.00014 -0.99999 -0.00294 -0.00306 -0.91934 0.28091 -0.27551 -0.62221 0.59056 -0.51390 -0.75680 0.51962 -0.39653 -0.75665 0.54209 -0.36554 -0.69000 0.56345 -0.45435 -0.69150 0.64682 -0.32163 -0.59269 0.68255 -0.42761 -0.63449 0.76780 -0.08896 -0.66155 0.74966 0.01920 -0.47015 0.86368 -0.18171 -0.46735 0.86435 -0.18568 -0.24237 0.96964 -0.03241 -0.26569 0.96228 0.05851 -0.99895 -0.02723 -0.03686 -0.95393 0.29989 -0.00971 -0.99986 0.01641 -0.00201 -0.68874 0.69793 -0.19631 -0.62449 0.74330 -0.23983 -0.68515 0.72129 -0.10152 -0.55845 0.82676 -0.06792 -0.10616 0.99433 0.00549 -0.32199 0.94674 -0.00327 -0.55271 0.82188 -0.13791 -0.49471 0.86734 -0.05458 -0.99999 0.00117 -0.00309 -0.99994 0.01132 0.00047 -1.00000 -0.00008 0.00021 -1.00000 -0.00021 0.00013 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00148 1.00000 0.00013 0.02107 0.99978 0.00061 -0.90939 0.33804 -0.24235 -0.28227 0.87950 -0.38316 -0.88136 0.42817 -0.19967 -0.21653 0.91472 -0.34118 -0.89159 0.42429 -0.15826 -0.89369 0.41966 -0.15876 -0.83278 0.55081 -0.05551 -0.24266 0.91455 -0.32360 -0.09217 0.97379 -0.20796 -0.78340 0.60764 -0.13062 -0.16852 0.97171 -0.16547 -0.01020 0.99990 -0.00978 -0.99975 0.02213 -0.00431 -0.99963 0.02650 -0.00665 -0.99852 -0.00802 -0.05385 -0.99999 -0.00108 -0.00408 -1.00000 0.00049 -0.00240 -0.99999 0.00126 0.00456 -0.99777 0.03907 0.05414 -0.99965 0.02640 -0.00212 -0.41870 0.89416 -0.15864 0.00633 -0.05715 -0.99835 -0.92670 0.23108 -0.29636 -0.90333 0.24012 -0.35545 -0.92077 0.20575 -0.33145 -0.47893 0.49429 -0.72546 -0.52345 0.46413 -0.71455 -0.34893 0.44904 -0.82256 -0.92567 0.16011 -0.34278 -0.47049 0.31077 -0.82587 -0.44326 0.32496 -0.83542 -0.90046 0.15318 -0.40708 -0.91732 0.12723 -0.37729 -0.35648 0.23249 -0.90491 -0.92659 0.08253 -0.36691 -0.27818 0.19615 -0.94029 -0.43482 0.12792 -0.89139 -0.93974 0.10503 -0.32536 0.00202 0.97664 -0.21485 0.00342 0.92611 -0.37725 0.00232 0.16799 -0.98579 -0.99800 0.05699 -0.02727 -0.98650 -0.07302 -0.14655 -0.99916 0.00647 0.04052 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00001 0.00055 -1.00000 0.00006 -0.00002 -1.00000 0.00003 -0.00026 -1.00000 -0.00019 -0.00000 -0.99992 0.00141 0.01221 -1.00000 0.00003 0.00061 0.00036 1.00000 -0.00085 -0.00074 -0.99999 0.00508 -0.00642 -0.99978 -0.01992 -0.00626 -0.99967 0.02501 -0.00044 -1.00000 0.00076 0.06323 0.95308 -0.29603 0.00013 -1.00000 -0.00013 0.00006 -1.00000 -0.00222 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00071 1.00000 0.00000 -0.00066 1.00000 0.00022 1.00000 0.00000 -0.00000 1.00000 -0.00204 -0.00021 1.00000 0.00000 0.00000 1.00000 0.00001 -0.00005 1.00000 0.00002 -0.00005 1.00000 0.00003 -0.00004 1.00000 0.00004 -0.00004 1.00000 0.00004 -0.00004 0.99997 -0.00678 -0.00351 0.99998 0.00583 -0.00357 0.99996 0.00834 -0.00345 0.99992 0.01266 -0.00304 0.99975 0.02214 -0.00174 0.99947 0.03250 0.00000 -0.00358 0.01694 -0.99985 0.00416 0.07845 -0.99691 -0.00170 0.14206 -0.98986 0.00389 0.24884 -0.96854 0.00056 0.23343 -0.97237 -0.00044 0.36252 -0.93198 0.00313 0.38266 -0.92389 -0.00250 0.47916 -0.87773 0.00408 0.52246 -0.85265 -0.00275 0.58852 -0.80847 0.00934 0.64939 -0.76040 0.00084 0.75437 -0.65645 0.00245 0.76038 -0.64947 -0.00186 0.82911 -0.55908 0.00392 0.85262 -0.52252 -0.00266 0.89274 -0.45057 0.00384 0.92387 -0.38270 -0.00671 0.95261 -0.30411 0.00413 0.97236 -0.23345 -0.00482 0.99518 -0.09792 -0.00064 0.99692 -0.07846 0.79609 0.05508 -0.60266 -0.00361 0.00416 -0.99998 0.82870 0.00504 -0.55967 1.00000 0.00000 -0.00021 0.00000 -1.00000 -0.00000 -0.00028 -1.00000 0.00022 -0.00025 -1.00000 0.00012 -0.00023 -1.00000 0.00005 -0.00022 -1.00000 -0.00000 -0.00020 -1.00000 -0.00005 -0.00018 -1.00000 -0.00009 -0.00202 -0.99999 0.00391 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00043 1.00000 -0.00111 -0.07286 0.98198 -0.17439 0.09330 0.99002 0.10563 -0.00001 1.00000 -0.00002 -0.00505 -0.00190 -0.99999 -0.00030 0.00223 -1.00000 0.00348 0.02062 -0.99978 -0.00004 -0.00542 -0.99999 -0.00160 0.26537 -0.96414 -0.00233 0.62702 -0.77900 -0.00033 0.86865 -0.49543 0.00295 0.98217 -0.18796 0.01463 -0.85812 -0.51324 0.00944 -0.34570 -0.93830 0.00000 -0.00000 1.00000 -0.00815 0.23743 -0.97137 0.01099 0.92840 -0.37141 0.01372 0.77791 -0.62823 0.93698 -0.01282 -0.34914 0.94050 -0.01829 -0.33930 0.36536 0.01785 -0.93069 0.42245 -0.00957 -0.90634 0.33631 0.12197 -0.93382 0.94302 0.13216 -0.30535 0.90984 0.06164 -0.41036 0.40552 0.20639 -0.89048 0.90311 0.20486 -0.37740 0.35689 0.37398 -0.85602 0.53259 0.53044 -0.65953 0.41656 0.82837 -0.37453 0.41649 0.82833 -0.37472 -1.00000 -0.00000 0.00000 -0.99998 0.00449 -0.00520 -0.00001 1.00000 0.00083 -0.00368 0.99999 -0.00194 0.04138 0.99891 0.02183 -0.00501 0.99997 0.00552 0.27965 0.82687 -0.48793 0.04604 0.99044 -0.13001 -0.00756 0.99995 0.00622 0.36433 0.82983 -0.42267 0.70741 -0.00070 0.70680 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 0.85586 0.44005 -0.27175 0.83565 0.48386 -0.25995 0.89149 0.41302 -0.18618 0.86250 0.48437 -0.14654 0.86595 0.47894 -0.14405 0.88942 0.44889 -0.08619 0.96888 0.24646 -0.02283 0.01839 0.97438 -0.22417 -0.00067 0.00719 -0.99997 0.18847 0.96425 -0.18626 0.32297 0.88097 -0.34580 0.70494 -0.00066 0.70927 -0.90892 0.01399 -0.41675 -0.84378 -0.03307 -0.53567 -0.40721 -0.02036 -0.91311 -0.25160 -0.06226 -0.96583 -0.76494 0.59743 -0.24070 -0.72888 0.55463 -0.40139 -0.64509 0.59453 -0.48000 -0.53049 0.60804 -0.59065 -0.30426 0.64766 -0.69854 -0.30627 0.49315 -0.81425 -0.00837 0.71247 -0.70165 0.99290 0.05153 -0.10723 0.99853 0.00494 -0.05394 0.94836 0.00438 -0.31717 0.99991 -0.01321 0.00299 0.99980 0.01913 -0.00603 1.00000 0.00036 -0.00011 1.00000 -0.00048 0.00019 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 0.99996 0.00768 -0.00483 0.99998 -0.00391 0.00413 1.00000 0.00000 0.00000 -0.32558 0.90928 -0.25923 -0.13364 0.91479 -0.38117 0.35963 0.58764 -0.72481 -0.21180 0.16869 -0.96264 -0.25906 0.19434 -0.94611 -0.74889 0.08450 -0.65728 -0.83399 0.14860 -0.53140 0.92740 -0.37379 -0.01480 0.92989 -0.36764 -0.01221 0.61957 -0.78440 0.02924 0.55444 -0.83212 0.01325 0.35548 -0.93316 0.05327 -0.06803 -0.99765 0.00764 -0.12392 -0.99196 0.02552 0.99025 -0.09665 0.10029 0.91955 -0.22227 0.32407 0.95031 -0.23680 0.20206 0.96115 -0.21750 0.16996 0.59344 -0.62964 0.50139 -0.29108 -0.79559 0.53132 0.56090 -0.64167 0.52312 0.13129 -0.80261 0.58188 0.08355 -0.80177 0.59176 0.94016 -0.29536 0.16990 0.94639 -0.29519 0.13115 0.95621 -0.27170 0.10884 0.49565 -0.79371 0.35264 -0.18800 -0.90604 0.37914 -0.12178 -0.92965 0.34774 0.54043 -0.77618 0.32479 0.94133 -0.32780 0.08023 0.92865 -0.36514 0.06539 0.96164 -0.27352 0.02092 0.50768 -0.85233 0.12568 -0.11568 -0.97042 0.21191 0.55307 -0.82651 0.10487 -0.19801 -0.96833 0.15205 -0.06290 -0.99658 0.05351 -0.27455 -0.96110 0.03011 -0.33670 -0.73778 0.58507 -0.30227 -0.73444 0.60765 -0.39705 -0.71898 0.57045 -0.26267 -0.67255 0.69187 -0.40602 -0.75797 0.51051 -0.42005 -0.84998 0.31794 -0.32574 -0.84437 0.42537 -0.38379 -0.81296 0.43795 -0.36326 -0.91024 0.19877 -0.28014 -0.91541 0.28903 -0.35819 -0.91282 0.19611 -0.31385 -0.94615 0.07940 -0.38564 -0.90943 0.15563 -0.32799 -0.94464 -0.00870 -0.42796 -0.90339 0.02703 -0.25399 -0.96097 -0.10967 0.99371 0.11197 -0.00000 0.94261 0.33390 0.00001 0.84675 0.53200 -0.00000 0.70709 0.70712 -0.00001 0.53735 0.84336 0.00001 0.35463 0.93501 -0.00022 -0.92548 -0.17888 -0.33391 -0.89852 -0.09205 -0.42917 -0.97435 0.04967 -0.21949 0.00259 0.78144 -0.62398 0.00149 0.70709 -0.70712 0.00242 0.47639 -0.87923 1.00000 0.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00080 -0.99995 -0.00968 -0.00203 -0.99999 0.00408 -0.03006 -0.99655 0.07738 -0.00350 -0.99956 -0.02935 -0.02316 -0.99935 -0.02755 1.00000 -0.00007 0.00004 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00021 -0.00005 1.00000 -0.00020 0.00003 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00081 -0.00007 1.00000 -0.00005 -0.00000 1.00000 -0.00200 0.00013 1.00000 0.00006 -0.00000 0.14179 0.98990 0.00003 0.10853 0.99409 -0.00003 0.21406 0.97682 0.00101 0.53288 0.84619 0.00004 0.70722 0.70699 -0.00001 0.84631 0.53268 0.00001 0.94433 0.32901 -0.00003 0.99387 0.11059 -0.00001 0.17609 -0.90635 -0.38408 0.09976 -0.93861 -0.33025 0.15264 -0.92168 -0.35666 0.18071 -0.90375 -0.38804 0.20343 -0.89860 -0.38877 0.15178 -0.92233 -0.35534 0.20452 -0.89798 -0.38962 0.16493 -0.92236 -0.34937 0.22733 -0.89351 -0.38726 0.22556 -0.89451 -0.38597 0.22317 -0.89604 -0.38380 0.22072 -0.89791 -0.38085 0.21231 -0.90599 -0.36621 0.22855 -0.92192 -0.31278 0.23696 -0.91595 -0.32387 0.18744 -0.93911 -0.28798 0.27398 -0.93382 -0.23004 0.24137 -0.94997 -0.19821 0.21300 -0.95923 -0.18578 0.38974 -0.89527 -0.21587 0.23721 -0.89968 -0.36649 0.12944 -0.95531 -0.26574 0.27026 -0.91424 -0.30186 0.25989 -0.91700 -0.30261 0.25487 -0.94396 -0.20973 0.26162 -0.91632 -0.30316 -0.28027 -0.95914 -0.03879 -0.10525 -0.98944 -0.09969 -0.03192 -0.97345 -0.22666 -0.02945 -0.96374 -0.26523 0.00041 -0.95510 -0.29628 -0.04268 -0.97666 -0.21049 0.17756 -0.90512 -0.38631 0.11970 -0.92741 -0.35437 -0.16176 -0.97543 -0.14960 -0.28146 -0.95874 -0.03991 -0.30514 -0.93140 -0.19848 -0.27647 -0.94338 -0.18330 -0.27203 -0.94555 -0.17868 0.50172 -0.83822 -0.21369 0.16147 -0.94732 -0.27662 -0.12364 -0.99100 -0.05123 0.02715 -0.99875 -0.04203 0.32277 -0.91635 -0.23690 0.35902 -0.90247 -0.23802 0.35945 -0.93190 -0.04862 0.35445 -0.93385 -0.04788 0.76322 -0.62573 -0.16110 0.61729 -0.78514 -0.05015 0.76316 -0.62581 -0.16110 0.76286 -0.64610 -0.02445 0.94001 -0.32706 -0.09706 0.94589 -0.32382 -0.02104 0.98674 -0.15827 -0.03589 0.92741 -0.37378 -0.01442 1.00000 -0.00086 -0.00022 1.00000 -0.00043 -0.00015 0.33101 -0.87971 -0.34137 0.32896 -0.88025 -0.34197 0.32508 -0.88095 -0.34388 0.39482 -0.85882 -0.32640 0.76532 -0.59938 -0.23460 0.79439 -0.56782 -0.21572 0.98701 -0.14910 -0.05987 0.99002 -0.13138 -0.05090 0.99069 -0.12721 -0.04855 1.00000 -0.00096 -0.00028 0.12946 -0.64097 -0.75657 0.11008 -0.80022 -0.58951 0.15794 -0.68263 -0.71349 0.16731 -0.76142 -0.62630 0.19158 -0.79756 -0.57201 0.17975 -0.71404 -0.67664 0.20875 -0.78596 -0.58196 0.20878 -0.78363 -0.58509 0.21894 -0.82359 -0.52322 0.28291 -0.78273 -0.55434 0.25328 -0.86318 -0.43676 0.25293 -0.87372 -0.41549 0.25472 -0.94413 -0.20916 0.94100 -0.32180 -0.10466 0.93714 -0.33344 -0.10291 0.92195 -0.37275 -0.10516 0.93769 -0.33282 -0.09987 0.58658 -0.77950 -0.21977 0.65529 -0.72112 -0.22489 0.67515 -0.70294 -0.22372 0.48227 -0.84245 -0.24021 0.94690 -0.31180 -0.07850 0.55440 -0.80773 -0.20052 0.94315 -0.32478 -0.07066 0.94453 -0.32071 -0.07077 0.92504 -0.37218 -0.07605 0.65147 -0.74426 -0.14718 0.67907 -0.71821 -0.15179 0.61415 -0.77465 -0.15078 -0.65150 -0.59225 -0.47412 0.29836 -0.75880 -0.57896 0.47432 -0.69238 -0.54372 0.49329 -0.72359 -0.48279 0.61805 -0.63096 -0.46894 0.62730 -0.62540 -0.46407 0.77735 -0.50319 -0.37753 0.77458 -0.60675 -0.17856 0.83112 -0.45052 -0.32599 0.92313 -0.36398 -0.12385 0.85115 -0.42652 -0.30597 0.96943 -0.19914 -0.14337 0.97086 -0.23028 -0.06630 0.97810 -0.17138 -0.11807 0.22139 -0.66125 -0.71675 0.19795 -0.68841 -0.69778 0.30152 -0.65080 -0.69682 0.39222 -0.80198 -0.45054 0.23430 -0.89094 -0.38901 0.62223 -0.56557 -0.54126 0.21208 -0.94252 -0.25824 0.63186 -0.56401 -0.53164 0.69806 -0.56471 -0.44026 0.59018 -0.75119 -0.29564 0.83331 -0.42620 -0.35207 0.85326 -0.40383 -0.32996 0.61214 -0.76132 -0.21373 0.97316 -0.21955 -0.06903 0.04484 -0.95686 -0.28708 0.12421 -0.77762 -0.61635 0.05320 -0.98189 -0.18185 0.14504 -0.84160 -0.52026 0.04815 -0.98350 -0.17440 0.38576 -0.86893 -0.31009 0.47608 -0.83282 -0.28242 0.79467 -0.56588 -0.21974 0.93976 -0.33146 -0.08361 0.99048 -0.12954 -0.04655 0.99073 -0.12746 -0.04698 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.25709 -0.91478 -0.31159 0.00001 1.00000 0.00001 -0.00018 1.00000 0.00010 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00003 1.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -0.99532 0.09668 0.00033 -0.99385 0.11073 -0.00001 -0.95644 0.29193 -0.00026 -0.94429 0.32911 0.00048 -0.87534 0.48351 -0.00044 -0.84619 0.53288 0.00056 -0.74993 0.66152 -0.00055 -0.70699 0.70722 0.00052 -0.53268 0.84632 -0.00093 -0.57876 0.81550 0.00076 -0.36769 0.92995 -0.00052 -0.12295 0.99240 0.00455 -0.22254 0.97492 0.00000 -0.61454 0.66814 0.41945 -0.66996 0.56855 0.47739 -0.69560 0.53927 0.47469 -0.72672 0.45227 0.51703 -0.75794 0.39558 0.51870 -0.76924 0.33433 0.54451 -0.79942 0.21822 0.55974 -0.79892 0.24143 0.55085 -0.81442 0.10721 0.57028 -0.82019 0.08090 0.56634 -0.81723 -0.00218 0.57630 -0.82026 -0.08188 0.56611 -0.81371 -0.11197 0.57039 -0.80417 -0.22064 0.55194 -0.79513 -0.24254 0.55583 -0.76778 -0.33966 0.54326 -0.75762 -0.39679 0.51824 -0.72461 -0.45705 0.51580 -0.69536 -0.54039 0.47377 -0.66768 -0.57204 0.47642 -0.61475 -0.66850 0.41856 -0.06688 0.99658 0.04850 -0.20026 0.96938 0.14214 -0.32738 0.91571 0.23300 -0.40102 0.87325 0.27678 -0.44750 0.83706 0.31477 -0.49636 0.79558 0.34738 -0.58417 0.70034 0.41021 -0.55656 0.73554 0.38628 -0.59708 0.68721 0.41381 -0.64563 0.61396 0.45412 -0.69460 0.53185 0.48442 -0.71958 0.47561 0.50596 -0.75525 0.38992 0.52684 -0.57358 -0.00000 -0.81915 -0.59675 0.02602 -0.80201 -0.56986 -0.01409 -0.82162 -0.56984 0.01636 -0.82159 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57357 -0.00000 -0.81916 -0.57358 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57357 0.00000 -0.81915 -0.57357 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 0.00000 -0.81916 -0.57358 -0.00000 -0.81915 -0.57357 -0.00000 -0.81916 -0.57355 -0.00000 -0.81917 -0.46719 -0.00005 -0.88416 -0.47825 -0.00000 -0.87823 -0.57848 -0.00000 -0.81570 -0.57848 -0.00000 -0.81570 -0.57357 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81916 0.54519 -0.00159 0.83831 0.58146 0.00504 0.81356 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57357 -0.00000 0.81915 0.57358 0.00000 0.81915 0.57308 -0.00060 0.81950 0.57657 -0.00060 0.81705 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57357 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 0.00000 0.81915 0.56403 0.00624 0.82573 0.57218 -0.00132 0.82013 0.57358 0.00000 0.81915 0.57501 -0.00131 0.81814 0.57453 -0.00126 0.81848 0.56893 -0.00126 0.82238 0.57565 -0.00198 0.81769 0.52026 -0.00165 0.85400 0.58896 -0.01024 0.80810 0.54697 -0.00918 0.83710 0.61850 -0.01922 0.78555 0.44949 -0.01288 0.89319 -0.37378 -0.88909 0.26420 -0.38309 -0.88391 0.26824 -0.46596 -0.82314 0.32453 -0.48598 -0.80351 0.34378 -0.54890 -0.74371 0.38159 -0.57912 -0.70486 0.40963 -0.61570 -0.66079 0.42926 -0.65792 -0.59017 0.46781 -0.69672 -0.52790 0.48570 -0.72500 -0.46209 0.51074 -0.73770 -0.43625 0.51525 -0.77068 -0.33630 0.54126 -0.77314 -0.32991 0.54168 -0.79642 -0.23786 0.55600 -0.81171 -0.14170 0.56661 -0.80133 -0.19870 0.56426 -0.81516 -0.08812 0.57249 -0.81367 -0.09843 0.57293 -0.00000 -1.00000 -0.00000 -0.00001 -1.00000 -0.00014 0.00062 -1.00000 0.00215 -0.00053 -1.00000 -0.00087 0.00000 -1.00000 -0.00000 -0.00042 -1.00000 -0.00066 0.00010 -1.00000 0.00013 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00002 -1.00000 -0.00002 0.00001 -1.00000 0.00004 0.00058 -1.00000 0.00046 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00008 -1.00000 -0.00019 -0.99581 -0.09143 -0.00000 -0.99163 -0.12915 0.00075 -0.96111 -0.27616 -0.00048 -0.92423 -0.38184 0.00094 -0.89231 -0.45143 -0.00029 -0.79300 -0.60922 0.00044 -0.79693 -0.60407 0.00059 -0.68288 -0.73053 -0.00031 -0.60896 -0.79320 0.00089 -0.55333 -0.83296 -0.00015 -0.38648 -0.92230 0.00025 -0.40810 -0.91294 0.00084 -0.24988 -0.96828 -0.00048 -0.08252 -0.99659 0.00116 -0.12638 -0.99198 -0.00000 -0.07921 -0.99578 0.04634 -0.08134 -0.99516 0.05520 -0.22312 -0.96190 0.15803 -0.37853 -0.88591 0.26810 -0.23235 -0.95601 0.17904 -0.07236 -0.99582 0.05576 -0.07481 -0.99514 0.06410 -0.91134 0.00037 0.41165 -0.63266 0.00678 0.77440 -0.42847 -0.00197 0.90356 -0.17791 0.00212 0.98404 0.13124 -0.00655 0.99133 0.35137 0.00137 0.93623 -0.03705 -0.00919 0.99927 -0.02605 -0.01111 0.99960 -0.42970 0.04046 -0.90206 -0.14417 0.19776 -0.96959 -0.63748 -0.06056 -0.76808 -0.40795 0.05693 -0.91123 -0.58871 -0.02189 -0.80804 -0.00094 -1.00000 -0.00075 0.00004 -1.00000 -0.00021 0.00015 -1.00000 -0.00018 0.00005 -1.00000 -0.00018 -0.81912 0.00000 0.57363 -0.81915 0.00007 0.57358 -0.81899 0.01982 0.57346 -0.81744 0.01111 0.57590 0.13080 -0.10869 0.98543 -0.42838 -0.00601 0.90358 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -0.00000 0.99659 -0.08250 0.06911 0.98043 -0.18433 0.02892 0.96905 -0.24515 0.03176 0.91547 -0.40113 0.07993 0.88249 -0.46349 0.00835 0.83743 -0.54647 0.37061 0.89645 -0.24296 -0.00019 0.98278 -0.18477 0.87802 0.37680 -0.29514 -0.99464 0.00002 -0.10336 -0.92874 -0.03124 -0.36941 -0.42401 -0.00249 -0.90566 -0.40166 -0.00719 -0.91576 -0.94765 0.00747 -0.31923 -0.92916 -0.00330 -0.36966 -0.42400 0.00513 -0.90565 -0.32213 0.16214 -0.93271 -0.94783 0.01266 -0.31854 -0.91264 0.11321 -0.39276 -0.45811 0.32302 -0.82813 -0.37910 0.42947 -0.81966 -0.91596 0.21383 -0.33955 -0.01608 0.96354 -0.26707 -0.53564 0.55372 -0.63756 -0.00980 0.99995 0.00128 0.09133 0.85517 -0.51024 0.51178 0.84849 -0.13471 0.10167 0.30712 -0.94622 0.36890 0.39443 -0.84163 0.22113 0.60973 -0.76114 0.09710 0.58560 -0.80476 0.28887 0.32605 -0.90014 0.55510 0.80523 -0.20849 0.47776 0.69293 -0.53999 0.61716 0.46720 -0.63311 0.58369 0.42211 -0.69363 0.65409 0.47219 -0.59093 0.79357 0.49309 -0.35653 0.62114 0.74363 -0.24739 0.89897 0.43191 -0.07292 0.06069 0.00827 -0.99812 0.18985 0.01736 -0.98166 0.31441 0.06473 -0.94708 0.36855 0.05476 -0.92800 0.69775 0.08161 -0.71168 0.76859 0.11653 -0.62904 0.78377 0.11006 -0.61122 0.92466 0.10366 -0.36641 0.97977 0.13552 -0.14728 0.97480 0.10373 -0.19750 0.41884 -0.00472 -0.90805 0.31523 0.02585 -0.94866 0.77380 -0.01778 -0.63318 0.91880 0.01694 -0.39435 0.97981 -0.00740 -0.19978 -0.00305 0.26299 -0.96479 0.01788 0.78766 -0.61585 -0.00583 0.96429 -0.26480 0.42691 0.88796 -0.17110 0.00000 1.00000 -0.00000 0.00048 1.00000 0.00015 0.65592 0.73166 -0.18560 0.42238 0.87851 -0.22318 0.96111 0.26664 -0.07190 0.90640 0.37056 -0.20279 0.99521 0.09554 -0.02091 0.65566 0.73192 -0.18548 0.96723 0.23425 -0.09795 0.54023 0.70398 -0.46104 0.96124 0.23066 -0.15106 0.96158 0.23010 -0.14974 0.64007 0.66276 -0.38866 0.33679 0.81621 -0.46944 0.43846 0.79570 -0.41788 0.96726 0.18434 -0.17441 0.24278 0.70085 -0.67072 0.96254 0.16633 -0.21411 0.95873 0.16800 -0.22936 0.72904 0.41991 -0.54053 0.28875 0.54976 -0.78382 0.34460 0.56504 -0.74965 0.68710 0.41721 -0.59483 0.23894 0.45220 -0.85931 0.96692 0.11126 -0.22954 0.96415 0.08598 -0.25105 0.95498 0.07927 -0.28588 0.71990 0.22488 -0.65664 0.69751 0.21592 -0.68327 0.30055 0.28739 -0.90944 0.32639 0.29998 -0.89637 0.23705 0.15619 -0.95886 0.96618 0.02308 -0.25683 0.95959 -0.00016 -0.28140 0.70828 -0.00040 -0.70594 0.31033 0.00048 -0.95063 0.00065 0.08509 -0.99637 -0.00636 0.22636 -0.97402 0.00054 0.46368 -0.88600 0.00265 0.41660 -0.90908 0.00375 0.65529 -0.75536 -0.01025 0.78758 -0.61613 -0.00000 1.00000 -0.00000 0.00018 1.00000 0.00032 -0.00639 0.73618 -0.67676 0.00531 0.72246 -0.69140 -0.00545 0.61487 -0.78861 0.00433 0.60190 -0.79856 -0.00444 0.47681 -0.87899 0.00330 0.46569 -0.88494 -0.00338 0.32578 -0.94544 0.00221 0.31736 -0.94830 -0.00226 0.16587 -0.98615 0.00106 0.16078 -0.98699 -0.00111 0.00000 -1.00000 -0.00178 0.00533 -0.99998 0.00056 0.00203 -1.00000 -0.98134 -0.00068 -0.19227 -0.95470 0.00541 0.29753 0.00070 -0.00534 -0.99999 -0.00016 0.01317 -0.99991 0.00148 -0.00442 -0.99999 -0.00001 0.00017 -1.00000 -1.00000 -0.00006 -0.00010 -1.00000 -0.00002 -0.00006 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 0.00000 1.00000 0.00003 -0.00003 1.00000 -0.00009 0.00213 0.99994 0.01033 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00079 -0.00054 1.00000 0.00059 -0.00081 1.00000 0.00085 -0.00081 1.00000 0.00114 -0.00074 1.00000 0.00139 -0.00058 1.00000 0.00155 -0.00034 0.99991 0.01261 0.00526 0.99992 0.01037 0.00674 0.99994 0.00785 0.00742 0.99996 0.00548 0.00746 0.99996 -0.00730 0.00517 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 0.99943 -0.00475 0.03332 0.06021 -0.96143 -0.26839 -0.03234 -0.99887 -0.03470 -0.00000 -0.99658 -0.08268 0.07447 -0.96665 -0.24502 0.08582 -0.91225 -0.40055 -0.00609 -0.73527 -0.67775 0.00493 -0.72246 -0.69140 -0.00507 -0.61355 -0.78964 0.00381 -0.60190 -0.79856 -0.00391 -0.47506 -0.87995 0.00269 -0.46570 -0.88494 -0.00276 -0.32365 -0.94617 0.00148 -0.31736 -0.94830 -0.00152 -0.16331 -0.98657 0.00017 -0.16077 -0.98699 -0.00017 0.00139 -1.00000 0.31949 -0.93967 -0.12224 0.20985 -0.97715 -0.03394 0.65933 -0.73646 -0.15136 0.45363 -0.87821 -0.15152 0.38503 -0.88891 -0.24818 0.20208 -0.96084 -0.18960 0.70566 -0.68780 -0.17020 0.95681 -0.28519 -0.05639 0.94522 -0.32310 -0.04662 0.96723 -0.23432 -0.09778 0.67472 -0.68940 -0.26361 0.73440 -0.56821 -0.37121 0.96112 -0.23156 -0.15040 0.96144 -0.23023 -0.15041 0.67704 -0.58493 -0.44663 0.16958 -0.88953 -0.42424 -0.02848 -0.93367 -0.35701 0.32989 -0.75042 -0.57275 0.24307 -0.70080 -0.67067 0.96726 -0.18452 -0.17424 0.96336 -0.15873 -0.21619 0.96043 -0.17111 -0.21975 0.72972 -0.42008 -0.53948 0.28080 -0.57769 -0.76644 0.32399 -0.54248 -0.77508 0.68629 -0.41706 -0.59588 0.23911 -0.45219 -0.85927 0.96692 -0.11155 -0.22939 0.96501 -0.07041 -0.25257 0.95980 -0.09124 -0.26543 0.72077 -0.22533 -0.65552 0.69656 -0.21551 -0.68437 0.29439 -0.30330 -0.90628 0.31813 -0.28476 -0.90427 0.23709 -0.15619 -0.95885 0.96619 -0.02347 -0.25676 0.30961 0.00000 -0.95086 0.70937 0.00035 -0.70484 0.06717 -0.84509 -0.53039 -0.00842 -0.71206 -0.70207 -0.00262 -0.21345 -0.97695 -0.11591 -0.99224 -0.04487 -0.01912 -0.99969 -0.01602 0.00427 -0.99999 -0.00163 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00027 -1.00000 -0.00233 -0.00165 -1.00000 -0.00006 0.00704 -0.99998 -0.00000 0.00000 -0.99987 0.01624 -0.00000 -1.00000 -0.00000 -0.00021 -1.00000 0.00071 -0.01885 -0.99982 0.00276 0.06188 -0.99808 0.00016 -0.00000 0.00000 -1.00000 -0.02573 0.01376 -0.99957 0.00012 -0.00117 -1.00000 -0.00114 0.00408 -0.99999 0.00017 0.00013 -1.00000 0.00020 0.00000 -1.00000 0.99989 -0.00158 0.01474 1.00000 -0.00022 0.00002 1.00000 -0.00015 -0.00002 1.00000 -0.00010 -0.00005 1.00000 -0.00006 -0.00006 1.00000 -0.00004 -0.00008 1.00000 -0.00001 -0.00008 1.00000 0.00000 -0.00009 0.34698 0.00123 0.93787 0.40072 0.00906 0.91615 0.84017 -0.00949 0.54223 0.92621 0.01502 0.37671 -0.00237 -0.19912 -0.97997 -0.00004 -0.15473 -0.98796 0.00207 -0.45310 -0.89146 -0.00138 -0.54534 -0.83821 0.00306 -0.70730 -0.70691 -0.00038 -0.80300 -0.59598 0.00091 -0.89164 -0.45274 -0.00041 -0.90754 -0.41996 0.00285 -0.98797 -0.15461 0.27329 -0.95154 -0.14102 0.44918 -0.88817 -0.09694 0.66329 -0.38694 -0.64056 0.46965 -0.79353 -0.38696 0.70266 -0.44978 -0.55133 0.44405 -0.77056 -0.45722 0.41026 -0.39606 -0.82147 0.19310 -0.72862 -0.65713 0.28278 -0.40988 -0.86720 0.87768 -0.14247 -0.45758 0.44473 -0.03173 -0.89510 0.41113 -0.00213 -0.91158 0.87417 0.01128 -0.48550 0.86685 0.00702 -0.49852 0.44398 0.02422 -0.89571 0.19572 -0.02096 -0.98044 0.10848 -0.89728 -0.42793 0.00784 -0.83683 -0.54740 0.22909 -0.96084 -0.15588 0.27156 -0.91243 -0.30616 0.25632 -0.91571 -0.30946 0.00000 1.00000 0.00008 -0.00411 0.99994 -0.01031 0.01771 0.99973 0.01524 0.00066 1.00000 -0.00010 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.99999 0.00483 0.00194 -1.00000 -0.00081 -0.00005 -1.00000 -0.00008 0.00000 1.00000 0.00003 -0.00011 1.00000 0.00000 -0.00004 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 0.00001 -0.00008 -1.00000 0.00041 0.00007 -1.00000 0.00004 -0.00006 -1.00000 -0.00000 -0.98894 -0.14835 -0.07779 -0.99356 -0.08236 0.01710 -0.96923 -0.24555 0.01203 -0.91565 -0.40179 -0.09268 -0.83347 -0.54473 -0.01340 -0.87044 -0.49209 0.00603 -0.73558 -0.67741 -0.00492 -0.72119 -0.69272 0.00506 -0.61401 -0.78928 -0.00391 -0.60074 -0.79944 0.00402 -0.47567 -0.87962 -0.00283 -0.46472 -0.88545 0.00291 -0.32433 -0.94594 -0.00169 -0.31667 -0.94854 0.00174 -0.16417 -0.98643 -0.00049 -0.16041 -0.98705 0.00050 0.00000 -1.00000 0.00076 0.00044 -1.00000 -0.00074 0.16041 -0.98705 0.00196 0.16500 -0.98629 -0.00191 0.31667 -0.94854 0.00309 0.32505 -0.94569 -0.00301 0.46472 -0.88545 0.00416 0.47622 -0.87931 -0.00405 0.60074 -0.79944 0.00517 0.61442 -0.78896 -0.00502 0.72119 -0.69271 0.00611 0.73587 -0.67710 -0.01882 0.89902 -0.43750 -0.16628 0.82561 -0.53918 -0.07078 0.91353 -0.40057 -0.07078 0.96699 -0.24479 -0.05540 0.96129 -0.26990 0.02931 0.99899 -0.03418 -0.00000 0.99659 -0.08255 -0.04440 0.99853 0.03114 -0.12729 0.98791 0.08852 -0.19198 0.97199 0.13553 -0.23751 0.95685 0.16739 -0.40860 0.86799 0.28221 -0.58961 -0.71016 0.38475 -0.42041 -0.85339 0.30819 -0.41594 -0.86902 0.26795 -0.25189 -0.93317 0.25641 -0.05191 -0.99500 0.08536 -0.10673 -0.98976 0.09482 -0.85201 0.40216 -0.33517 -0.69704 0.20628 -0.68672 -0.75212 0.50121 -0.42791 -0.73006 0.51076 -0.45402 -0.74477 0.63870 -0.19335 -0.72456 0.63349 0.27148 -0.73062 0.61775 0.29081 -0.76615 0.63519 0.09773 -0.81076 0.58258 -0.05715 -0.78499 0.52329 0.33159 -0.88295 0.30225 -0.35923 -0.75644 0.08608 -0.64837 -0.72075 0.11594 -0.68343 -0.88461 0.30064 -0.35648 -0.90793 0.41745 -0.03742 -0.92613 0.37675 0.01852 -0.84932 0.38286 0.36341 -0.84329 0.42919 0.32351 -0.88650 0.23406 0.39918 -0.91586 0.14795 0.37324 -0.99040 0.12887 0.04993 -0.98871 0.14639 0.03191 -0.90850 0.07863 0.41042 -0.94294 0.10447 -0.31613 -0.94270 0.10506 -0.31668 -0.75519 0.04331 -0.65407 -0.93327 -0.07756 0.35070 -0.90151 -0.14780 0.40674 -0.99053 -0.12779 0.05020 -0.88637 -0.23413 0.39941 -0.94309 -0.10406 -0.31583 -0.98881 -0.14573 0.03179 -0.75531 -0.04352 -0.65392 -0.94252 -0.10542 -0.31709 -0.74405 -0.06878 -0.66457 -0.92652 -0.37577 0.01892 -0.86892 -0.37882 0.31856 -0.83243 -0.43053 0.34886 -0.78488 -0.52336 0.33174 -0.88522 -0.45571 -0.09330 -0.86172 -0.35309 -0.36437 -0.74899 -0.14182 -0.64723 -0.89337 -0.32373 -0.31158 -0.71593 -0.64677 0.26292 -0.82099 -0.56175 -0.10201 -0.76089 -0.62792 -0.16362 -0.80892 -0.45134 -0.37675 -0.77034 -0.46698 -0.43417 -0.71136 -0.22044 -0.66736 -0.82175 -0.40640 -0.39945 -0.99641 0.01264 -0.08372 -0.99440 0.01900 -0.10391 -0.99909 0.02271 -0.03604 -0.99910 0.01164 -0.04086 -0.98940 0.00979 -0.14488 -0.99479 0.02021 -0.09990 -0.99439 0.04069 -0.09761 -0.95942 0.02107 -0.28120 -0.98285 0.10447 -0.15198 -0.98228 0.06087 -0.17726 -0.97005 0.08808 -0.22637 -0.97071 0.02645 -0.23878 -0.94129 0.03215 -0.33606 -0.92585 0.25437 -0.27947 -0.94810 0.03658 -0.31585 -0.94714 0.11249 -0.30044 -0.94438 0.11344 -0.30867 -0.94449 0.21078 -0.25201 -0.90234 0.03339 -0.42973 -0.90112 0.15446 -0.40512 -0.95800 0.22671 -0.17562 -0.85440 0.05021 -0.51719 -0.88761 0.15914 -0.43224 -0.88753 0.29835 -0.35111 -0.88687 0.39878 -0.23331 -0.88628 0.29947 -0.35330 -0.86074 0.17898 -0.47653 -0.86283 0.05417 -0.50259 -0.87332 0.41807 -0.25005 -0.78554 0.58510 -0.20143 -0.84471 0.34678 -0.40768 -0.84469 0.18333 -0.50288 -0.84246 0.34832 -0.41101 -0.84263 0.46866 -0.26522 -0.87694 0.46920 -0.10406 -0.79621 0.04933 -0.60301 -0.79397 0.21498 -0.56868 -0.80822 0.51113 -0.29244 -0.80824 0.58037 -0.09955 -0.75062 0.06643 -0.65739 -0.76342 0.21694 -0.60839 -0.76389 0.41786 -0.49180 -0.82041 0.38806 -0.41992 -0.77668 0.55286 -0.30184 -0.71552 0.68890 0.11600 -0.67252 0.73641 0.07360 -0.68128 0.71822 -0.14147 -0.80207 0.07691 -0.59226 -0.80199 0.19953 -0.56302 -0.71226 0.19810 -0.67338 -0.75280 0.44516 -0.48489 -0.76563 0.56447 -0.30851 -0.81790 0.55515 -0.15114 -0.69938 0.65228 0.29223 -0.90923 -0.37661 -0.17741 -0.99138 -0.13051 -0.01133 -0.94905 -0.30449 -0.08115 -0.96491 -0.25861 -0.04554 -0.59666 -0.77757 -0.19844 -0.78914 -0.60489 -0.10660 -0.96579 -0.23516 -0.10929 -0.94908 -0.25828 -0.18036 -0.96491 -0.22739 -0.13129 -0.38776 -0.80241 -0.45363 -0.23859 -0.70037 -0.67272 -0.96579 -0.18359 -0.18314 -0.73860 -0.43333 -0.51643 -0.94907 -0.18102 -0.25788 -0.96492 -0.16876 -0.20112 -0.33059 -0.56697 -0.75449 -0.30501 -0.55943 -0.77072 -0.68058 -0.43039 -0.59294 -0.23770 -0.45140 -0.86008 -0.96579 -0.10987 -0.23491 -0.94905 -0.08189 -0.30430 -0.96492 -0.08979 -0.24670 -0.72751 -0.23466 -0.64472 -0.32226 -0.29977 -0.89793 -0.30986 -0.29360 -0.90431 -0.69470 -0.22212 -0.68415 -0.23725 -0.15583 -0.95887 -0.96579 -0.02288 -0.25833 -0.31427 0.00000 -0.94933 -0.31426 0.00001 -0.94934 -0.94902 0.02718 -0.31403 -0.96494 0.00000 -0.26248 -0.71175 0.00001 -0.70244 -0.71176 0.00000 -0.70243 -0.23726 0.15583 -0.95887 -0.96578 0.06695 -0.25059 -0.30662 0.30141 -0.90285 -0.31822 0.29276 -0.90168 -0.69471 0.22213 -0.68414 -0.94895 0.13315 -0.28595 -0.96496 0.08974 -0.24656 -0.72750 0.23466 -0.64473 -0.23770 0.45141 -0.86008 -0.96576 0.14873 -0.21256 -0.68059 0.43040 -0.59292 -0.29934 0.57319 -0.76279 -0.32173 0.55621 -0.76624 -0.73859 0.43333 -0.51643 -0.94887 0.22317 -0.22323 -0.96499 0.16860 -0.20093 -0.23859 0.70038 -0.67272 -0.96575 0.21257 -0.14882 -0.29394 0.85945 -0.41827 -0.39363 0.80545 -0.44306 -0.61553 0.69053 -0.37986 -0.95883 0.24595 -0.14200 -0.58201 0.70424 -0.40659 -0.96576 0.23516 -0.10959 -0.96573 0.25072 -0.06706 -0.94877 0.31477 -0.02745 -0.98964 0.11151 -0.09042 -0.93744 0.34165 -0.06689 -0.58734 0.80068 -0.11806 -0.82265 0.52193 -0.22548 -0.69248 0.69246 -0.20242 -0.51476 0.83137 -0.20939 -0.35241 0.90101 -0.25295 -0.31232 0.91936 -0.23925 -0.35288 0.90052 -0.25404 -0.11191 0.99314 -0.03398 -0.11197 0.99371 -0.00018 -0.19470 0.98086 0.00368 -0.36517 0.93094 -0.00240 -0.52609 0.85043 0.00128 -0.48899 0.87229 -0.00127 -0.71432 0.69982 0.00092 -0.70711 0.70710 0.00148 -0.85959 0.51099 -0.00057 -0.84474 0.53517 0.00095 -0.95877 0.28417 -0.00194 -0.93949 0.34257 0.00178 -0.99548 0.09500 -0.00080 -0.99371 0.11197 -0.00000 -0.71339 0.69851 -0.05630 -0.56259 0.82057 -0.10077 -0.85496 0.50828 -0.10339 -0.84155 0.52929 -0.10786 -0.94907 0.28146 -0.14156 -0.98782 0.09500 -0.12320 -0.40606 0.91384 0.00140 -0.33249 0.94307 -0.00820 -0.25589 0.96528 -0.05253 -0.71102 0.64366 0.28310 -0.54364 0.78034 0.30909 -0.33536 0.94206 0.00732 -0.61036 0.78440 0.11036 -0.69207 0.70324 0.16275 -0.51710 0.85478 -0.04420 -0.57639 0.80331 0.14989 -0.65788 0.74913 0.07743 -0.66787 0.74149 0.06445 -0.61650 0.78145 -0.09628 -0.57265 0.81761 -0.05997 -0.81666 0.57248 -0.07309 -0.80041 0.58146 -0.14577 -0.85598 0.47873 -0.19525 -0.83658 0.53124 -0.13387 0.94876 -0.00015 -0.31601 0.93268 0.00119 -0.36069 0.45376 -0.00118 -0.89112 0.43535 -0.00046 -0.90026 -0.00008 -1.00000 0.00003 -0.00004 -1.00000 0.00008 -0.00000 -1.00000 -0.00000 -0.00014 -1.00000 -0.00003 -0.99645 -0.01178 -0.08335 -0.99838 -0.02493 -0.05121 -0.99840 -0.01889 -0.05325 -0.99831 -0.02479 -0.05261 -0.99608 -0.03423 -0.08157 -0.99623 -0.01169 -0.08592 -0.98927 -0.01950 -0.14477 -0.98227 -0.01710 -0.18671 -0.98195 -0.06726 -0.17676 -0.95916 -0.03073 -0.28118 -0.99051 -0.07150 -0.11737 -0.97885 -0.12529 -0.16172 -0.97854 -0.06962 -0.19394 -0.96279 -0.16218 -0.21617 -0.95926 -0.17227 -0.22393 -0.95864 -0.09615 -0.26787 -0.94131 -0.03120 -0.33609 -0.94724 -0.03592 -0.31851 -0.94603 -0.11758 -0.30201 -0.94252 -0.27674 -0.18729 -0.90548 -0.14467 -0.39897 -0.90630 -0.26320 -0.33068 -0.91788 -0.25225 -0.30637 -0.92164 -0.33165 -0.20146 -0.88554 -0.16664 -0.43364 -0.88712 -0.03633 -0.46011 -0.85388 -0.05461 -0.51760 -0.93377 -0.30990 -0.17895 -0.84346 -0.35236 -0.40548 -0.84410 -0.18374 -0.50372 -0.78477 -0.55201 -0.28182 -0.82329 -0.04665 -0.56570 -0.82116 -0.20268 -0.53349 -0.80804 -0.51687 -0.28269 -0.80829 -0.37583 -0.45323 -0.75065 -0.06076 -0.65790 -0.81602 -0.54582 -0.19022 -0.75011 -0.22158 -0.62309 -0.74505 -0.43762 -0.50338 -0.76738 -0.21066 -0.60560 -0.76702 -0.06712 -0.63810 -0.78483 -0.54598 -0.29316 -0.81263 -0.39394 -0.42947 -0.69897 -0.62124 -0.35427 -0.73121 -0.65735 -0.18227 -0.68418 -0.50855 -0.52276 -0.72607 -0.21577 -0.65289 -0.72268 -0.67883 0.13008 -0.72773 -0.59361 -0.34357 -0.26439 -0.95913 0.10084 -0.43202 -0.89695 -0.09402 -0.60507 -0.78323 0.14299 -0.37513 -0.92668 0.02337 -0.45848 -0.88854 -0.01704 -0.60554 -0.79307 -0.06602 -0.65296 -0.75117 0.09689 -0.65425 -0.75042 0.09391 -0.79256 -0.58910 -0.15750 -0.62249 -0.77873 -0.07806 -0.79490 -0.58781 -0.15038 -0.81050 -0.56211 -0.16469 -0.80987 -0.56342 -0.16328 -0.89865 -0.39226 -0.19637 -0.11935 -0.99279 -0.01103 -0.01440 -0.99946 -0.02951 -0.00113 -1.00000 -0.00022 -0.35219 -0.93587 -0.01041 -0.13165 -0.99122 -0.01197 -0.23745 -0.97008 -0.05070 -0.23772 -0.97009 -0.04912 -0.27333 -0.96060 -0.05035 -0.41704 -0.90479 -0.08624 -0.42482 -0.90444 -0.03896 -0.44559 -0.89136 -0.08320 -0.59525 -0.80066 -0.06794 -0.59636 -0.79987 -0.06757 -0.58807 -0.80012 -0.11830 -0.61667 -0.77970 -0.10854 -0.80649 -0.58640 -0.07556 -0.80826 -0.58407 -0.07472 -0.79714 -0.58499 -0.14953 -0.91898 -0.37912 -0.10838 -0.81507 -0.56331 -0.13544 -0.96749 -0.23987 -0.08019 -0.91153 -0.37765 -0.16281 -0.94301 -0.26140 -0.20591 -0.99276 -0.04471 -0.11144 -0.98909 -0.12734 -0.07404 -0.92994 -0.29900 -0.21403 -0.13052 -0.99145 -0.00000 -0.11930 -0.99286 -0.00062 -0.38269 -0.92388 -0.00041 -0.35226 -0.93590 0.00101 -0.60876 -0.79335 0.00135 -0.59647 -0.80264 0.00229 -0.80905 -0.58775 -0.00068 -0.79366 -0.60836 0.00081 -0.92437 -0.38149 -0.00007 -0.92388 -0.38268 -0.00000 -0.99165 -0.12898 -0.00000 -0.99145 -0.13052 0.00008 -0.12910 -0.98066 -0.14711 -0.37551 -0.90654 -0.19282 -0.46810 -0.85305 -0.23062 -0.45151 -0.78785 -0.41884 -0.54659 -0.72521 -0.41870 -0.60828 -0.70084 -0.37259 -0.57211 -0.79176 -0.21405 -0.47465 0.85109 0.22437 -0.45770 0.85360 0.24877 -0.35988 0.92621 0.11233 -0.54930 0.82112 0.15502 -0.48822 0.87064 -0.06021 -0.19468 0.98086 -0.00401 -0.20492 0.97874 -0.00879 -0.24082 0.96995 -0.03453 -0.25539 0.96524 -0.05557 -0.99997 0.00760 0.00012 -1.00000 -0.00300 0.00085 -0.99999 -0.00336 0.00098 -1.00000 0.00000 -0.00119 -0.88623 -0.43705 -0.15354 -0.85970 -0.49134 -0.13965 -0.72137 -0.64084 0.26257 -0.68728 -0.66793 0.28550 -0.53792 -0.82544 0.17114 -0.08964 -0.99555 0.02920 -0.09554 -0.99512 0.02476 -0.10693 -0.99321 0.04582 -0.12593 -0.99204 0.00244 -0.11738 -0.98105 -0.15415 -0.99917 -0.04075 0.00010 -0.04763 -0.99886 -0.00086 1.00000 -0.00003 0.00020 1.00000 0.00020 -0.00005 1.00000 0.00000 -0.00000 0.23930 0.01659 -0.97080 0.34055 0.00455 -0.94021 0.46476 0.00106 -0.88544 0.66315 -0.00252 -0.74848 0.82299 0.00606 -0.56802 0.93471 0.02630 -0.35445 0.99271 0.00000 -0.12052 0.99272 -0.00003 -0.12047 0.90407 0.01585 -0.42710 0.00004 -1.00000 -0.00060 -0.00002 -1.00000 0.00010 -0.00003 -1.00000 0.00023 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00001 -1.00000 -0.00008 -0.00000 -1.00000 -0.00000 0.00001 -1.00000 0.00001 -0.94721 -0.01690 -0.32017 -0.16339 -0.02334 -0.98629 -0.45212 -0.00025 -0.89196 -0.99462 -0.00929 -0.10313 -0.16357 -0.01428 -0.98643 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -0.38032 0.92486 0.81513 -0.05270 0.57688 0.89867 0.00000 -0.43862 0.90448 -0.00686 -0.42646 0.93932 0.00431 -0.34300 0.95454 -0.00924 -0.29793 0.96947 0.00460 -0.24519 0.98666 -0.00091 -0.16281 0.98983 -0.00941 -0.14195 -0.02276 0.02489 -0.99943 0.11936 -0.02615 -0.99251 0.22525 0.01382 -0.97420 0.35757 -0.00915 -0.93384 0.45244 0.01231 -0.89171 0.53493 -0.00692 -0.84487 0.65212 0.00854 -0.75806 0.69123 -0.00348 -0.72263 0.81067 0.00405 -0.58549 0.82026 0.00000 -0.57198 -0.09964 -0.00182 -0.99502 -0.06235 -0.99576 0.06765 -0.20239 -0.95912 0.19783 -0.06165 -0.99595 0.06545 -0.34540 -0.88056 0.32451 -0.33889 -0.89009 0.30478 -0.19917 -0.96179 0.18786 -0.36683 -0.89147 0.26592 0.63673 -0.60063 0.48355 0.23912 -0.84737 0.47411 -0.27370 -0.82723 0.49069 0.08863 -0.90329 0.41977 0.66470 -0.60402 0.43969 0.68477 -0.59229 0.42460 0.65149 -0.66023 0.37370 0.11709 -0.94461 0.30658 0.23973 -0.93327 0.26746 0.69565 -0.64300 0.32035 0.68751 -0.64940 0.32496 0.66453 -0.69356 0.27817 0.72637 -0.64473 0.23814 0.69088 -0.67950 0.24689 0.24171 -0.95057 0.19490 0.37290 -0.91533 0.15207 0.40213 -0.91136 0.08778 0.34730 -0.93255 0.09866 0.35562 -0.93131 0.07872 0.31504 -0.94817 0.04156 0.11688 -0.99303 0.01542 0.44025 -0.89783 -0.00834 0.32155 -0.94663 0.02245 -0.64977 0.09072 -0.75470 -0.57243 0.08332 -0.81571 -0.51776 0.03186 -0.85493 -0.62121 0.09207 -0.77821 -0.57806 0.10976 -0.80858 -0.43630 0.08042 -0.89620 -0.49554 0.25511 -0.83027 -0.19864 0.16207 -0.96658 -0.22929 0.17023 -0.95836 -0.29247 0.38863 -0.87374 -0.29805 0.38725 -0.87247 -0.01434 0.17727 -0.98406 -0.12744 0.52532 -0.84131 0.03706 0.59182 -0.80522 0.08401 0.59448 -0.79971 0.18424 0.23727 -0.95381 0.20289 0.23340 -0.95098 0.41255 0.24075 -0.87855 0.24404 0.67986 -0.69155 0.48091 0.49382 -0.72447 0.32623 0.64983 -0.68651 0.02677 0.71691 -0.69666 0.43630 0.68206 -0.58689 0.54954 0.28222 -0.78636 0.61730 0.10490 -0.77970 0.33796 0.28522 -0.89690 -0.08532 0.34759 -0.93376 -0.62387 0.00000 -0.78153 -0.62349 -0.00004 -0.78183 -0.43771 0.00004 -0.89911 -0.43389 -0.00030 -0.90097 -0.23269 0.00030 -0.97255 -0.22252 -0.00052 -0.97493 -0.01457 0.00051 -0.99989 0.00000 -0.00061 -1.00000 0.20865 0.00062 -0.97799 0.22252 -0.00049 -0.97493 0.42505 0.00050 -0.90517 0.43389 -0.00028 -0.90097 0.62072 0.00029 -0.78403 0.62348 0.00000 -0.78184 -0.70708 -0.00000 -0.70713 -0.70708 0.00001 -0.70714 -0.71042 -0.00924 -0.70372 -0.70460 0.01247 -0.70949 -0.66158 0.10003 -0.74317 -0.42193 -0.85212 0.30964 -0.40388 -0.83637 0.37064 -0.40135 -0.84376 0.35636 -0.20145 -0.84829 0.48972 0.15380 -0.75746 0.63451 0.48899 -0.45568 0.74381 0.70889 -0.17853 0.68235 -0.16754 -0.86553 0.47200 -0.24997 -0.87603 0.41242 -0.12948 -0.83921 0.52817 -0.20398 -0.85638 0.47435 0.15361 -0.75727 0.63478 0.32932 -0.67672 0.65848 0.49130 -0.45805 0.74082 0.35433 -0.70914 0.60957 0.22033 -0.81194 0.54057 0.59342 -0.51760 0.61640 0.73746 -0.20902 0.64224 0.81603 -0.30858 0.48874 0.72594 -0.35905 0.58659 0.74060 -0.20016 0.64145 0.11686 -0.99315 -0.00101 0.15018 -0.98823 -0.02930 0.13610 -0.98825 -0.06950 0.18337 -0.98195 -0.04643 0.19195 -0.98129 0.01528 0.10686 -0.99213 -0.06532 0.44024 -0.89779 -0.01251 0.11093 -0.98892 -0.09864 0.11212 -0.98865 -0.09996 0.10903 -0.98864 -0.10344 0.24990 -0.92969 -0.27059 0.18287 -0.94559 -0.26912 0.21560 -0.91331 -0.34551 0.16117 -0.94721 -0.27716 0.17857 -0.90744 -0.38036 0.03254 -0.99832 -0.04801 0.04872 -0.99407 -0.09720 0.04951 -0.99203 -0.11590 0.17347 -0.83606 -0.52049 0.17126 -0.85009 -0.49801 0.17572 -0.90893 -0.37812 0.04759 -0.99237 -0.11371 0.05362 -0.98691 -0.15210 0.25357 -0.94470 -0.20794 0.28405 -0.86435 -0.41499 0.26030 -0.89570 -0.36051 0.26668 -0.82308 -0.50141 0.24780 -0.78437 -0.56864 -0.00007 -1.00000 -0.00113 -0.00020 -1.00000 0.00068 -0.00021 -1.00000 0.00069 -0.00002 -1.00000 0.00001 -0.00020 -1.00000 0.00055 0.00022 -1.00000 -0.00060 -0.00003 -1.00000 0.00004 -0.00001 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00005 -1.00000 0.00045 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.35255 -0.85559 -0.37904 0.31161 -0.88044 -0.35737 0.30615 -0.91006 -0.27940 0.34239 -0.91906 -0.19518 0.29292 -0.91642 -0.27273 0.23870 -0.94562 -0.22096 0.23818 -0.94693 -0.21585 0.24692 -0.94779 -0.20179 0.24706 -0.94852 -0.19817 0.26748 -0.91855 -0.29107 0.25699 -0.94569 -0.19906 0.27778 -0.91561 -0.29070 0.31343 -0.86365 -0.39480 0.25646 -0.94826 -0.18715 0.28640 -0.94311 -0.16890 0.22169 -0.95594 -0.19246 0.30773 -0.86553 -0.39518 0.30238 -0.91049 -0.28208 0.25644 -0.94901 -0.18335 0.25605 -0.88811 -0.38170 0.26506 -0.94651 -0.18401 0.25658 -0.94790 -0.18884 0.25937 -0.91405 -0.31183 0.23567 -0.92014 -0.31274 0.29058 -0.93865 -0.18576 0.22897 -0.89099 -0.39205 0.20269 -0.89843 -0.38954 0.30087 -0.93914 -0.16582 0.26048 -0.92746 -0.26829 0.38789 -0.89876 -0.20440 0.32473 -0.88015 -0.34626 0.34608 -0.92538 -0.15461 0.26658 -0.86565 -0.42378 0.27902 -0.85449 -0.43818 0.46876 -0.87558 -0.11673 0.49020 -0.86811 -0.07805 0.48150 -0.87160 -0.09202 0.49020 -0.86788 -0.08050 0.44748 -0.89143 -0.07148 0.50056 -0.86569 -0.00419 0.49951 -0.86628 -0.00653 0.60060 -0.78895 -0.12977 0.50745 -0.85943 -0.06224 0.70137 -0.70492 0.10568 0.69565 -0.70941 0.11318 0.62899 -0.76239 -0.15210 0.66457 -0.74429 -0.06619 0.59521 -0.79938 0.08194 0.62655 -0.76112 0.16771 0.62699 -0.76713 0.13564 0.69117 -0.71644 0.09484 0.71830 -0.69528 0.02532 0.75803 -0.62275 0.19386 0.76046 -0.58037 0.29133 0.75752 -0.59754 0.26289 0.75450 -0.60709 0.24934 0.79914 -0.58591 0.13449 0.79057 -0.60582 0.08939 0.82154 -0.54052 0.18141 0.82078 -0.46928 0.32573 0.83535 -0.39976 0.37735 0.81507 -0.37895 0.43824 0.82467 -0.40327 0.39661 0.82630 -0.43375 0.35929 0.87326 -0.36728 0.32020 0.87431 -0.43232 0.22066 0.87569 -0.41984 0.23853 0.87975 -0.37201 0.29606 0.88118 -0.33041 0.33815 0.88164 -0.27878 0.38078 0.85999 -0.22118 0.45988 0.88171 -0.23170 0.41098 0.87673 -0.10354 0.46971 0.76116 -0.18406 0.62190 0.83000 -0.16690 0.53220 0.84911 0.02206 0.52775 0.00080 1.00000 -0.00292 0.00019 -1.00000 -0.00000 0.04146 -0.99782 -0.05141 -0.00711 -0.99992 0.01040 0.00334 -0.99998 -0.00489 -0.00089 -1.00000 0.00028 -0.00100 -1.00000 0.00047 -0.00108 -1.00000 0.00076 -0.00119 -1.00000 0.00124 -0.00128 -1.00000 0.00203 -0.00211 -0.99999 0.00406 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00135 -0.99999 0.00353 0.00205 -0.99106 0.13340 0.27721 -0.54626 0.79042 -0.11666 0.03639 0.99250 -0.60441 0.20740 0.76921 -0.74548 -0.18726 0.63968 -0.42853 -0.16072 0.88912 0.99622 0.04058 -0.07681 0.99861 0.03368 -0.04044 -0.27653 -0.59294 0.75627 -0.22124 -0.61003 0.76087 0.88920 -0.28229 0.36004 0.11993 0.99253 0.02254 -0.55015 -0.62730 0.55121 0.85361 0.22300 0.47076 0.78945 0.37028 0.48956 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24572 0.96262 0.11395 0.24710 0.96090 0.12493 0.36884 -0.86583 0.33807 0.40262 -0.84456 0.35300 0.30819 -0.87861 0.36477 0.79235 -0.48637 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14654 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23107 0.60973 0.41632 0.67447 0.45012 -0.62955 0.63329 0.52768 -0.56847 0.63119 0.51462 -0.58327 0.62846 0.69906 0.28925 0.65394 0.69603 0.25859 0.66983 0.73326 0.39301 0.55486 0.51544 -0.63934 0.57058 0.71478 -0.44325 0.54095 0.50371 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04158 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14387 -0.94000 0.30935 0.14373 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 0.40524 0.83720 0.36725 0.40441 0.85375 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24716 0.49012 0.83244 0.25851 0.53337 0.82040 0.20604 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09072 0.58199 0.81145 0.05332 0.58209 0.81139 0.05314 0.63891 0.76804 -0.04376 0.58234 0.81175 0.04408 -0.62975 -0.61576 0.47356 -0.62713 -0.61181 0.48208 -0.67408 -0.63036 0.38504 -0.72332 -0.61625 0.31151 -0.77754 -0.57908 0.24515 -0.69443 -0.64412 0.32073 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 0.10122 0.99362 0.04977 0.24187 0.96694 -0.08072 0.35177 0.89015 -0.28966 0.31960 0.94341 -0.08850 0.36436 0.93124 0.00607 0.42888 0.90108 -0.06413 0.34159 0.93060 -0.13153 0.35863 0.93029 -0.07715 0.44976 0.89314 0.00495 0.43933 0.89793 0.02653 0.56738 0.81415 -0.12343 0.54248 0.83922 -0.03771 0.19557 -0.87047 0.45170 0.27452 -0.77218 0.57305 0.30521 -0.65708 0.68927 0.99038 0.13277 -0.03900 0.90737 0.41199 0.08332 0.91040 0.37203 0.18104 0.82860 0.54907 -0.10926 0.75316 0.64246 -0.14143 0.78419 0.61951 -0.03530 0.82750 -0.50733 0.24054 0.75402 -0.46134 0.46757 -0.22704 -0.86992 0.43782 0.85822 -0.44314 0.25900 0.91972 -0.36186 0.15225 0.87148 -0.43735 0.22190 0.84363 -0.50055 0.19429 -0.20344 -0.87645 0.43641 0.22710 0.97309 -0.03911 0.27743 0.96072 0.00660 0.22383 0.97307 -0.05512 0.20009 0.97977 0.00241 0.18875 0.98134 -0.03660 0.26631 0.96371 -0.01852 0.27545 0.96128 -0.00810 -0.26496 -0.92700 0.26547 -0.29922 -0.92728 0.22501 -0.29985 -0.92803 0.22101 -0.32465 -0.92748 0.18544 -0.32484 -0.92795 0.18269 -0.34306 -0.92762 0.14774 -0.34305 -0.92790 0.14600 -0.35599 -0.92772 0.11224 -0.35592 -0.92787 0.11129 0.92068 0.37502 -0.10818 -0.69462 -0.69976 0.16684 -0.19265 -0.86351 0.46608 0.12591 -0.54798 0.82696 0.18329 -0.69229 0.69795 0.23960 -0.72465 0.64612 0.33000 -0.71943 0.61116 0.04364 -0.78466 0.61839 -0.14946 -0.85152 0.50256 -0.39572 -0.90000 0.18275 -0.40310 -0.90211 0.15396 -0.38048 -0.92472 -0.01171 0.24914 -0.62470 0.74005 0.33786 -0.80616 0.48576 0.74850 -0.58760 0.30737 0.49646 -0.68116 0.53810 0.96437 -0.18410 0.18999 0.99852 -0.05405 0.00589 0.94067 -0.09921 0.32450 0.93601 -0.05072 0.34831 0.48679 -0.51345 0.70669 0.69862 -0.45435 0.55272 -0.36662 -0.92729 0.07565 0.95921 -0.03705 0.28026 0.99701 -0.05991 0.04874 -0.36474 -0.92779 0.07852 0.20020 -0.56806 0.79827 0.17871 -0.91400 0.36422 -0.18706 -0.74811 0.63666 0.71137 -0.33210 0.61940 0.90024 0.05975 0.43127 0.97304 -0.22827 0.03301 0.94096 0.33621 -0.03941 0.98449 0.17299 -0.02905 0.99287 0.11331 -0.03716 -0.70491 -0.69427 0.14522 0.96140 0.25493 0.10352 0.99978 0.01261 0.01681 0.99021 0.13919 -0.01050 0.99228 0.12113 -0.02651 0.70425 -0.06136 0.70730 0.72397 -0.08034 0.68514 0.69834 -0.06705 0.71261 0.70755 -0.17462 0.68475 0.68757 -0.20294 0.69719 0.68968 -0.35670 0.63017 0.66014 -0.28997 0.69291 0.73912 -0.29694 0.60458 0.65962 -0.29237 0.69240 0.71356 -0.46795 0.52140 0.52244 -0.74493 0.41489 0.56236 -0.62219 0.54464 0.53895 -0.63976 0.54794 -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.29656 -0.66599 0.68448 -0.31840 -0.67290 0.66770 -0.45185 -0.62142 0.64005 -0.45819 -0.62148 0.63547 -0.66290 -0.37590 0.64750 -0.53420 -0.51395 0.67118 -0.49409 -0.60833 0.62114 -0.69782 -0.07751 0.71207 -0.90614 -0.31237 -0.28518 -0.71726 -0.15742 0.67879 -0.57400 -0.07080 0.81579 -0.67104 -0.18329 0.71841 -0.68092 -0.28192 0.67592 -0.63745 -0.38469 0.66759 -0.72203 -0.43278 0.53979 -0.00000 -1.00000 -0.00000 0.11515 0.99316 -0.01950 0.12396 0.99229 -0.00068 -0.07001 0.99177 -0.10718 -0.06792 0.99150 -0.11096 -0.04278 0.99157 -0.12227 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 0.04210 0.99151 -0.12305 0.04277 0.99157 -0.12228 0.06838 0.99149 -0.11075 0.21031 0.97181 -0.10652 0.04527 0.99623 -0.07396 -0.16531 0.98571 -0.03238 -0.17404 0.98465 -0.01341 0.12153 -0.43758 0.89093 -0.78240 -0.27455 0.55900 0.50696 -0.21300 0.83524 0.43301 -0.20106 0.87868 -0.87579 -0.11927 0.46772 -0.94190 -0.02903 0.33465 -0.97122 0.01020 0.23795 -0.74452 -0.13397 0.65402 -0.35310 -0.20995 0.91172 -0.35677 0.15627 0.92103 0.11078 -0.00001 0.99385 0.55619 -0.07182 0.82794 0.35731 0.14609 0.92249 0.75105 0.02515 0.65977 0.97108 -0.02064 0.23788 0.84841 -0.13085 0.51291 0.86783 -0.13547 0.47804 -0.40482 -0.22605 0.88602 -0.71334 -0.06060 0.69819 -0.55344 -0.12230 0.82386 -0.10840 -0.20591 0.97255 -0.21381 -0.37604 0.90160 0.78239 -0.27465 0.55896 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.16235 -0.92614 0.34045 -0.99978 -0.01466 0.01477 1.00000 -0.00000 0.00000 0.94706 -0.18941 -0.25923 1.00000 0.00000 -0.00000 0.72758 0.00000 0.68602 0.72632 -0.00007 0.68736 0.69543 0.00038 0.71860 0.71539 0.00227 0.69872 0.69992 0.00000 0.71422 0.63154 -0.00250 0.77534 0.61482 -0.00663 0.78864 0.56683 0.00142 0.82383 0.47157 0.00882 0.88178 0.42644 -0.00127 0.90452 0.48578 -0.00165 0.87408 0.49187 0.00000 0.87067 0.44156 -0.03338 0.89661 0.41672 -0.06071 0.90701 0.45581 -0.00052 0.89008 0.35546 0.00009 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37465 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00250 0.92737 -0.48356 0.00000 0.87531 -0.47159 0.00881 0.88178 -0.42806 -0.01025 0.90369 -0.48964 -0.00150 0.87192 -0.45567 -0.02415 0.88982 -0.53890 0.00034 0.84237 -0.65575 -0.02015 0.75471 -0.61483 -0.00378 0.78865 -0.69506 0.00038 0.71895 -0.72738 -0.00008 0.68623 -0.72632 0.00000 0.68736 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.32754 0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90968 0.63033 -0.00000 0.77633 0.63035 0.00000 0.77631 0.80505 -0.00000 0.59321 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37168 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07960 0.00000 0.99683 0.07960 0.00000 0.99683 -0.17359 -0.00000 0.98482 -0.17359 -0.00000 0.98482 -0.41529 -0.00000 0.90969 -0.41529 -0.00000 0.90969 -0.63033 -0.00000 0.77633 -0.63033 -0.00000 0.77633 -0.80504 -0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32893 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39518 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35198 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39125 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85626 0.38630 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12333 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81901 -0.17245 -0.19506 0.98057 0.02093 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15933 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30813 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26659 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37310 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18796 0.97320 0.19359 0.12413 0.32737 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23702 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86546 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54636 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29877 -0.95399 0.02541 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18796 -0.97320 -0.19359 0.12413 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 -0.36118 0.00000 0.93250 -0.36118 0.00000 0.93250 -0.75130 0.00000 0.65997 -0.75130 0.00000 0.65997 -0.97127 -0.00000 0.23796 -0.97127 -0.00000 0.23796 -0.55763 0.00000 0.83009 -0.55763 0.00000 0.83009 -0.11087 -0.00000 0.99383 -0.11078 0.00000 0.99385 0.36114 -0.00000 0.93251 0.36118 0.00000 0.93250 0.75128 -0.00000 0.65998 0.75129 0.00000 0.65997 0.97128 0.00000 0.23793 0.97128 0.00000 0.23793 -0.52021 -0.25876 0.81390 -0.55629 -0.06917 0.82810 -0.57632 -0.14637 0.80401 -0.57290 -0.14179 0.80727 -0.50295 -0.10159 0.85832 -0.53494 -0.16968 0.82768 -0.36795 -0.46362 0.80602 -0.42242 -0.48537 0.76549 -0.28739 -0.53790 0.79251 -0.21087 -0.46595 0.85932 -0.10883 -0.19107 0.97553 0.04715 -0.24580 0.96817 -0.07666 -0.52074 0.85027 -0.31183 -0.70556 0.63636 0.03122 -0.83832 0.54428 0.21992 -0.66340 0.71522 0.34776 -0.26959 0.89799 0.50716 -0.68460 0.52355 0.65752 -0.32584 0.67933 0.00853 -0.93684 0.34965 -0.01764 -0.79254 0.60956 -0.19340 -0.85881 0.47439 -0.06005 -0.94361 0.32556 0.71448 -0.30917 0.62765 0.61605 -0.70539 0.35058 0.40619 -0.89006 0.20691 0.33853 -0.93969 0.04886 0.44467 -0.88743 0.12141 0.94101 -0.24772 0.23052 0.81543 -0.57879 -0.00930 0.95828 -0.24461 0.14786 0.11803 -0.96573 0.23118 0.47154 -0.01437 0.88173 0.41234 -0.30593 0.85813 0.29316 -0.70443 0.64640 0.14306 -0.95333 0.26588 0.33917 -0.38521 0.85824 0.13045 -0.90945 0.39482 0.07105 -0.94250 0.32658 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03997 -0.73161 0.68055 0.01607 -0.98803 0.15344 -0.03998 -0.73156 0.68061 -0.01608 -0.98803 0.15344 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 -0.13850 -0.95397 0.26603 -0.29317 -0.70441 0.64642 -0.45559 -0.25841 0.85186 0.55630 -0.06906 0.82810 0.54644 -0.07521 0.83412 0.57602 -0.13818 0.80567 0.49186 -0.30734 0.81463 0.53316 -0.23207 0.81356 0.52427 -0.22855 0.82031 0.49192 -0.26575 0.82909 0.48669 -0.26087 0.83372 0.22611 -0.43020 0.87395 0.11924 -0.19633 0.97326 0.10861 -0.19695 0.97438 0.29526 -0.70457 0.64529 0.36092 -0.63712 0.68104 0.26070 -0.59799 0.75792 0.00840 -0.57544 0.81780 0.13169 -0.69253 0.70927 -0.28897 -0.27361 0.91741 -0.13707 -0.62234 0.77065 -0.34751 -0.27251 0.89720 0.00035 -0.95410 0.29950 -0.06955 -0.83809 0.54107 0.11954 -0.91012 0.39673 -0.37961 -0.70148 0.60317 -0.20138 -0.87331 0.44359 -0.64729 -0.30492 0.69859 -0.48193 -0.69947 0.52772 -0.21391 -0.97644 -0.02847 -0.43222 -0.89152 0.13554 -0.71877 -0.29106 0.63139 -0.69107 -0.67926 0.24704 -0.45140 -0.88525 0.11212 -0.93651 -0.26515 0.22944 -0.92389 -0.26237 0.27854 -0.77550 -0.62094 0.11413 0.08395 -0.47203 0.87758 0.07372 -0.31441 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39305 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 1.00000 0.00000 -0.42738 -0.87288 0.23542 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18887 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18766 0.98223 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18766 0.98223 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18886 -0.67101 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92408 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19359 0.12407 0.81663 -0.54564 -0.18814 0.90235 -0.34994 0.25159 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02538 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54656 0.32005 -0.92238 0.21629 0.34529 -0.86546 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68808 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 -0.71754 0.00259 0.69651 -0.69992 0.00000 0.71422 0.00000 -1.00000 -0.00000 -0.99976 -0.02028 0.00805 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 -0.00012 0.00000 -1.00000 -0.00000 -0.00000 -0.54306 0.83970 0.00048 -0.82645 0.56302 0.00033 -0.98019 0.19804 -0.00000 -0.98037 0.19532 0.02686 -0.00000 1.00000 0.00000 0.48299 0.87548 -0.01569 0.55273 0.83336 -0.00014 0.82644 0.56303 0.00033 0.98001 0.19893 0.00016 0.96592 -0.25883 0.00000 0.70708 -0.70711 0.00483 0.25880 -0.96592 0.00361 -0.25882 -0.96593 0.00000 -0.70710 -0.70710 0.00482 -0.96592 -0.25882 0.00361 -0.53936 0.83398 0.11644 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06986 -0.98282 0.18451 -0.00432 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85102 0.52047 0.06989 0.98001 0.19893 -0.00121 -0.38262 0.92383 0.01196 -0.60549 0.79206 -0.07758 -0.98242 0.18314 0.03619 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86397 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92863 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48080 0.35274 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78087 0.11745 0.43570 0.89716 -0.07251 0.98234 0.18357 0.03605 0.84345 0.53137 -0.07891 0.60508 0.79038 0.09581 0.47838 0.87812 -0.00723 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02738 0.99781 -0.00006 -0.06621 -0.83570 0.00000 0.54918 -0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 0.83570 0.00000 0.54918 -0.99746 0.00249 -0.07125 -0.96449 -0.25844 -0.05450 -0.69956 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66578 0.40977 0.96449 -0.25845 -0.05450 0.69954 -0.69957 0.14577 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.18722 0.98232 -0.00049 -0.67985 -0.71506 0.16276 -0.25882 -0.96593 -0.00000 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 0.68062 -0.46742 0.56416 0.68415 -0.46919 0.55840 0.00000 -1.00000 0.00000 -0.06980 0.99114 -0.11304 -0.17002 0.98539 0.00995 0.49377 -0.55480 0.66962 -0.88917 -0.28233 0.36009 -0.06967 0.99117 -0.11285 -0.04752 0.99190 -0.11780 0.82964 0.00000 0.55830 1.00000 0.00000 -0.00005 0.00000 -1.00000 0.00000 -1.00000 0.00000 -0.00000 -0.55558 0.83146 -0.00032 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 0.19509 0.98078 0.00289 0.55557 0.83147 -0.00032 0.83147 0.55556 -0.00016 0.98078 0.19510 -0.00005 0.98077 -0.19509 0.00479 0.83147 -0.55556 -0.00242 0.55557 -0.83147 -0.00242 0.19509 -0.98079 0.00000 -0.19508 -0.98078 0.00479 -0.55557 -0.83147 -0.00242 -0.83147 -0.55556 -0.00242 -0.98078 -0.19510 -0.00000 0.00000 1.00000 -0.00000 -0.19510 0.98078 0.00000 -0.43988 0.89769 0.02576 -0.34308 0.92963 -0.13449 -0.12092 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29117 0.13333 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.26953 -0.73824 0.61835 -0.04401 -0.78448 0.61859 0.34486 -0.87107 0.34972 -0.24901 -0.62075 0.74341 -0.53274 -0.67686 0.50798 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71482 -0.55303 -0.49987 0.66655 -0.10705 -0.93718 0.33202 -0.08363 -0.97549 0.20352 -0.95619 0.27850 0.09024 0.81839 -0.55913 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34274 -0.93162 0.12091 0.41584 -0.90391 0.10015 -0.02010 -0.99838 0.05318 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.13224 0.95122 0.27873 -0.19139 0.93845 0.28755 -0.24237 0.95494 0.17133 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 -0.21448 0.96105 0.17429 -0.21468 0.96201 0.16868 -0.24705 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05398 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06977 0.99156 -0.10925 -0.34004 -0.62630 0.70151 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50576 -0.84009 0.26126 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08802 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67440 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41725 -0.54080 0.73037 -0.41201 -0.60635 0.68013 -0.70425 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95386 0.19678 0.22680 -0.77616 0.60749 0.16894 -0.89673 0.40568 0.17691 0.33004 -0.80724 0.48932 -0.20020 -0.56807 0.79826 -0.19713 -0.77268 0.60342 -0.56010 -0.42940 0.70845 -0.77051 -0.59690 0.22367 -0.89494 -0.39111 0.21477 -0.86902 -0.31567 0.38100 0.40409 -0.56439 0.71984 0.33802 -0.85130 0.40128 0.52007 -0.78742 0.33089 0.14974 -0.78142 0.60577 -0.67308 -0.65371 0.34586 -0.79487 -0.52330 0.30714 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02855 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01958 -0.79797 0.60051 -0.05130 -0.76800 0.64031 -0.01382 -0.80117 0.58934 -0.10394 -0.76278 0.64443 -0.05371 -0.72711 0.68601 0.02658 -0.71869 0.69533 -0.00068 -0.67621 0.73321 0.07167 -0.19381 -0.87163 0.45022 -0.33486 -0.67114 0.66139 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.10649 -0.94309 0.31503 -0.16500 -0.93292 0.32005 -0.17354 -0.93264 0.31632 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.14311 -0.93869 0.31366 -0.59996 0.78186 -0.16950 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.47585 0.87781 -0.05491 -0.33781 0.94059 0.03414 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.15144 0.98776 0.03735 -0.99876 0.02243 0.04443 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00118 -1.00000 -0.00104 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42687 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.68055 -0.57907 0.44891 -0.55875 0.82932 -0.00524 -0.63044 0.77342 -0.06608 -0.62318 0.78201 -0.01035 -0.62355 0.78160 -0.01687 -0.58167 0.81243 0.04018 -0.58190 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03148 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51069 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40437 0.85353 0.32861 -0.39689 0.83488 0.38139 -0.32067 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 0.00024 -1.00000 -0.00003 -0.00108 -0.99981 0.01924 -0.26638 -0.92815 0.25995 -0.22267 -0.92832 0.29771 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05538 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00095 1.00000 -0.00028 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00745 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 0.32528 0.86091 0.39118 0.33532 0.84040 0.42579 0.23285 0.86496 0.44455 0.25027 0.81275 0.52612 0.17651 0.83818 0.51604 0.10816 0.84369 0.52582 0.11187 0.86176 0.49483 0.00028 0.83866 0.54466 -0.00914 -0.99996 0.00102 -0.00630 -0.99996 0.00607 0.10399 -0.94352 0.31456 0.07081 -0.93620 0.34427 -0.00555 -0.95073 0.30998 0.04525 -0.90484 0.42333 0.25684 -0.87163 0.41749 0.14454 -0.93969 0.30997 0.12737 -0.94154 0.31190 0.18908 -0.91839 0.34758 0.30400 0.34310 0.88875 0.28039 0.27889 0.91848 0.15528 -0.63718 0.75491 0.25235 -0.50582 0.82490 0.18035 0.44574 0.87681 0.02349 0.38357 0.92321 0.00000 -0.58193 0.81324 0.43016 -0.54482 0.71982 0.39039 -0.60766 0.69162 0.53245 0.40400 0.74383 0.44473 0.03813 0.89485 0.46219 0.52024 0.71814 0.29459 -0.64015 0.70952 0.00016 0.94744 0.31993 0.16382 0.95459 0.24886 0.13733 0.94752 0.28870 0.24194 0.95510 0.17103 0.17056 0.96125 0.21658 0.17105 0.96162 0.21453 0.21458 0.96108 0.17403 0.21475 0.96198 0.16875 0.05806 -0.98803 0.14291 0.06866 -0.98340 0.16795 0.03296 0.95258 0.30251 0.07028 0.94785 0.31086 0.09366 0.95264 0.28931 0.09772 -0.92104 0.37701 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.04460 0.99084 -0.12748 -0.02095 0.99228 -0.12226 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 0.04752 0.99190 -0.11780 -0.16727 -0.92856 0.33134 -0.21990 -0.92662 0.30498 -0.03234 0.95249 0.30284 -0.07020 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.23218 -0.60875 0.75863 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.01264 0.86767 0.49698 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.04880 -0.99862 0.01922 0.52498 -0.65553 0.54284 0.12791 -0.61484 0.77821 -0.80301 -0.20094 0.56106 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00003 1.00000 -0.00002 0.00016 1.00000 0.00004 0.00048 1.00000 0.00009 0.00007 1.00000 -0.00000 0.00005 1.00000 -0.00001 -0.00125 1.00000 -0.00035 -0.00002 1.00000 0.00015 -0.00005 1.00000 0.00015 -0.00010 1.00000 0.00017 -0.00013 1.00000 0.00018 0.00003 1.00000 -0.00004 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00003 0.00002 1.00000 -0.00001 0.00001 1.00000 -0.00002 0.00001 1.00000 -0.00002 0.00001 1.00000 -0.00002 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00033 -1.00000 0.00019 -0.00003 -1.00000 -0.00020 0.00014 1.00000 -0.00008 0.00022 1.00000 -0.00020 -0.00000 1.00000 -0.00000 0.00006 1.00000 0.00010 0.00014 1.00000 0.00007 -0.00111 1.00000 0.00020 -0.00001 1.00000 -0.00002 -0.00001 1.00000 -0.00002 -0.00001 1.00000 -0.00000 -0.00001 1.00000 0.00001 -0.00001 1.00000 0.00001 0.11197 0.99371 0.00002 0.11183 0.99373 0.00001 0.00036 1.00000 0.00014 0.00000 1.00000 0.00004 0.00039 1.00000 0.00007 -0.00000 1.00000 0.00000 0.00002 1.00000 -0.00001 0.00000 1.00000 0.00000 0.00002 1.00000 -0.00001 0.00001 1.00000 -0.00003 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00045 1.00000 0.00096 0.00002 1.00000 -0.00001 0.00002 1.00000 -0.00001 -0.00080 1.00000 -0.00003 0.00109 1.00000 -0.00155 0.00002 1.00000 -0.00002 0.82964 0.00000 0.55829 -0.89803 -0.26163 0.35369 -0.94949 -0.12100 0.28953 -0.89803 -0.26163 0.35369 -0.94949 -0.12100 0.28953 -0.89803 -0.26163 0.35369 -0.94949 -0.12100 0.28953 -0.06815 -0.99654 0.04757 -0.11101 -0.99121 0.07193 -0.19831 -0.96996 0.14092 -0.29127 -0.93518 0.20149 -0.32658 -0.91668 0.23030 -0.42782 -0.85344 0.29767 -0.43690 -0.84608 0.30539 -0.58019 -0.70719 0.40405 -0.55800 -0.73729 0.38084 -0.68996 -0.53189 0.49096 -0.65099 -0.61356 0.44693 -0.75143 -0.38997 0.53224 -0.73489 -0.44614 0.51078 -0.79398 -0.23807 0.55939 -0.78836 -0.27505 0.55030 -0.81581 -0.08006 0.57275 -0.81562 -0.09275 0.57110 -0.81653 0.08001 0.57174 -0.81080 0.12334 0.57218 -0.79656 0.23801 0.55573 -0.77388 0.32427 0.54402 -0.00001 0.00047 -1.00000 -0.00004 0.00044 -1.00000 0.41887 0.00354 -0.90804 0.21259 -0.01145 -0.97707 0.86681 -0.00625 -0.49861 0.91896 0.00044 -0.39434 0.90148 0.00570 -0.43278 -0.91973 -0.00050 -0.39256 -0.99885 -0.03722 -0.03036 -0.99550 -0.04019 0.08580 0.05326 -0.00009 -0.99858 -0.40106 -0.05433 -0.91444 0.01735 0.01334 -0.99976 0.00924 0.01646 -0.99982 -0.00124 -0.00227 -1.00000 0.01311 0.00163 -0.99991 0.42678 0.01192 -0.90428 0.67196 0.04613 -0.73915 0.94064 -0.00032 -0.33939 -0.32138 0.03814 -0.94618 -0.40721 -0.01937 -0.91313 -0.00770 -0.04993 -0.99872 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.01046 0.99992 0.00670 -0.00053 1.00000 0.00160 -0.00018 1.00000 0.00167 0.00018 1.00000 0.00167 0.00052 1.00000 0.00160 -0.01046 0.99992 0.00670 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.03620 -0.94022 0.33864 0.10266 -0.94500 0.31053 0.11094 -0.94337 0.31263 0.12277 -0.94865 0.29153 -0.03620 -0.94022 0.33864 -0.10286 -0.94501 0.31044 -0.12261 -0.94859 0.29180 -0.11094 -0.94337 0.31265 -0.11094 -0.94337 0.31265 -0.12261 -0.94859 0.29179 -0.10286 -0.94501 0.31044 -0.03620 -0.94022 0.33864 0.12277 -0.94865 0.29153 0.11094 -0.94337 0.31263 0.10266 -0.94500 0.31053 0.03620 -0.94022 0.33864 -0.14454 -0.93969 0.30998 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.01046 0.99992 0.00670 0.00052 1.00000 0.00160 0.00018 1.00000 0.00167 -0.00018 1.00000 0.00167 -0.00053 1.00000 0.00160 0.01046 0.99992 0.00670 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.01046 0.99992 0.00670 -0.00053 1.00000 0.00160 -0.00018 1.00000 0.00167 0.00018 1.00000 0.00167 0.00052 1.00000 0.00160 -0.01046 0.99992 0.00670 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.11094 -0.94337 0.31265 -0.12261 -0.94859 0.29179 -0.10286 -0.94501 0.31044 -0.03620 -0.94022 0.33864 0.12277 -0.94865 0.29153 0.11094 -0.94337 0.31263 0.10266 -0.94500 0.31053 0.03620 -0.94022 0.33864 0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 -0.14454 -0.93969 0.30998 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 + + + + + + + + + + + + + + +

119 0 50 0 104 0 50 1 21 1 104 1 50 2 119 2 1172 2 119 3 111 3 1172 3 70 4 78 4 59 4 496 5 497 5 61 5 12 6 1 6 2 6 12 7 11 7 1 7 39 8 8 8 7 8 38 9 8 9 39 9 15 10 19 10 468 10 468 11 517 11 15 11 13 12 15 12 517 12 517 13 516 13 13 13 498 14 13 14 516 14 52 15 8 15 38 15 52 16 0 16 8 16 0 17 7 17 8 17 2 18 0 18 52 18 52 19 54 19 2 19 54 20 47 20 2 20 16 21 2 21 47 21 47 22 46 22 16 22 9 23 500 23 527 23 520 24 3 24 527 24 1 25 527 25 4 25 527 26 3 26 4 26 527 27 1 27 9 27 1 28 10 28 9 28 11 29 10 29 1 29 4 30 5 30 1 30 1 31 0 31 2 31 7 32 0 32 1 32 1 33 6 33 7 33 1 34 5 34 6 34 2 35 14 35 12 35 14 36 2 36 16 36 46 37 18 37 16 37 467 38 520 38 521 38 467 39 3 39 520 39 467 40 4 40 3 40 467 41 5 41 4 41 467 42 6 42 5 42 467 43 7 43 6 43 7 44 467 44 39 44 500 45 9 45 499 45 498 46 499 46 9 46 9 47 10 47 498 47 13 48 498 48 11 48 498 49 10 49 11 49 11 50 12 50 13 50 15 51 13 51 14 51 13 52 12 52 14 52 14 53 16 53 15 53 19 54 15 54 16 54 16 55 18 55 19 55 18 56 17 56 66 56 19 57 18 57 66 57 21 58 22 58 496 58 61 59 21 59 496 59 23 60 22 60 21 60 24 61 23 61 21 61 25 62 24 62 21 62 25 63 21 63 26 63 62 64 27 64 28 64 62 65 28 65 29 65 62 66 29 66 1172 66 62 67 30 67 27 67 31 68 27 68 30 68 69 69 70 69 59 69 69 70 59 70 481 70 69 71 481 71 480 71 35 72 69 72 480 72 68 73 69 73 35 73 35 74 36 74 68 74 35 75 480 75 37 75 36 76 35 76 37 76 67 77 68 77 36 77 66 78 67 78 36 78 36 79 20 79 66 79 66 80 20 80 19 80 40 81 38 81 39 81 39 82 41 82 40 82 41 83 42 83 40 83 30 84 62 84 43 84 43 85 64 85 65 85 43 86 65 86 17 86 44 87 43 87 17 87 18 88 46 88 44 88 17 89 18 89 44 89 48 90 31 90 34 90 49 91 31 91 48 91 1172 92 29 92 50 92 50 93 49 93 21 93 50 94 29 94 28 94 50 95 28 95 27 95 50 96 27 96 49 96 31 97 49 97 27 97 21 98 49 98 26 98 36 99 472 99 473 99 36 100 473 100 20 100 471 101 472 101 36 101 36 102 37 102 471 102 471 103 37 103 480 103 468 104 19 104 20 104 468 105 20 105 473 105 497 106 496 106 492 106 496 107 22 107 491 107 490 108 491 108 22 108 22 109 23 109 490 109 489 110 490 110 23 110 23 111 24 111 489 111 488 112 489 112 24 112 24 113 25 113 488 113 487 114 488 114 25 114 63 115 64 115 43 115 26 116 51 116 58 116 26 117 55 117 51 117 56 118 51 118 55 118 42 119 51 119 56 119 42 120 41 120 51 120 41 121 39 121 51 121 467 122 51 122 39 122 484 123 51 123 467 123 485 124 51 124 484 124 486 125 51 125 485 125 58 126 51 126 486 126 42 127 56 127 40 127 40 128 52 128 38 128 40 129 54 129 52 129 40 130 53 130 54 130 47 131 54 131 53 131 44 132 47 132 53 132 45 133 44 133 53 133 45 134 53 134 32 134 56 135 53 135 40 135 56 136 32 136 53 136 486 137 25 137 58 137 45 138 32 138 33 138 25 139 486 139 487 139 48 140 56 140 55 140 55 141 26 141 48 141 48 142 26 142 49 142 56 143 48 143 32 143 48 144 34 144 32 144 43 145 44 145 45 145 43 146 45 146 33 146 43 147 33 147 32 147 43 148 32 148 57 148 57 149 32 149 34 149 31 150 57 150 34 150 58 151 25 151 26 151 44 152 46 152 47 152 30 153 57 153 31 153 30 154 43 154 57 154 63 155 43 155 62 155 79 156 80 156 81 156 79 157 81 157 82 157 83 158 79 158 82 158 84 159 80 159 79 159 79 160 85 160 84 160 84 161 85 161 86 161 374 162 84 162 86 162 374 163 375 163 84 163 86 164 87 164 374 164 376 165 374 165 87 165 88 166 376 166 87 166 88 167 378 167 388 167 376 168 88 168 388 168 92 169 90 169 91 169 93 170 91 170 90 170 90 171 94 171 93 171 531 172 93 172 94 172 94 173 95 173 531 173 497 174 531 174 95 174 97 175 96 175 61 175 61 176 95 176 97 176 95 177 61 177 497 177 98 178 99 178 100 178 96 179 98 179 100 179 96 180 100 180 101 180 96 181 101 181 102 181 96 182 102 182 103 182 104 183 96 183 103 183 96 184 104 184 61 184 61 185 104 185 21 185 105 186 89 186 379 186 77 187 75 187 59 187 78 188 77 188 59 188 532 189 1176 189 383 189 1177 190 1176 190 532 190 532 191 533 191 1177 191 71 192 1177 192 533 192 533 193 112 193 71 193 72 194 71 194 112 194 534 195 73 195 72 195 112 196 534 196 72 196 74 197 73 197 534 197 534 198 479 198 74 198 74 199 479 199 481 199 74 200 481 200 59 200 75 201 74 201 59 201 1176 202 76 202 383 202 76 203 365 203 383 203 386 204 84 204 375 204 380 205 108 205 386 205 113 206 80 206 84 206 386 207 113 207 84 207 386 208 108 208 107 208 386 209 107 209 106 209 386 210 106 210 114 210 386 211 114 211 115 211 113 212 386 212 115 212 80 213 113 213 116 213 81 214 80 214 116 214 1171 215 121 215 117 215 1171 216 117 216 118 216 110 217 1171 217 118 217 121 218 1171 218 1170 218 119 219 121 219 1170 219 119 220 103 220 102 220 119 221 102 221 101 221 119 222 101 222 120 222 119 223 120 223 121 223 104 224 103 224 119 224 119 225 1170 225 111 225 112 226 533 226 478 226 534 227 112 227 478 227 93 228 483 228 91 228 494 229 483 229 93 229 93 230 531 230 494 230 92 231 91 231 60 231 105 232 378 232 88 232 105 233 88 233 87 233 379 234 378 234 105 234 81 235 132 235 133 235 82 236 81 236 133 236 133 237 134 237 82 237 82 238 134 238 135 238 83 239 82 239 135 239 135 240 134 240 136 240 137 241 135 241 136 241 136 242 138 242 137 242 138 243 139 243 140 243 141 244 140 244 139 244 137 245 138 245 140 245 137 246 140 246 142 246 137 247 142 247 143 247 137 248 143 248 144 248 145 249 137 249 144 249 144 250 146 250 145 250 147 251 141 251 139 251 139 252 148 252 147 252 145 253 146 253 149 253 145 254 149 254 150 254 151 255 145 255 150 255 150 256 152 256 151 256 153 257 151 257 152 257 152 258 154 258 153 258 155 259 153 259 154 259 154 260 156 260 155 260 155 261 156 261 157 261 155 262 157 262 158 262 159 263 155 263 158 263 158 264 160 264 159 264 163 265 164 265 162 265 161 266 163 266 162 266 159 267 160 267 164 267 164 268 163 268 165 268 165 269 159 269 164 269 163 270 166 270 165 270 165 271 166 271 167 271 168 272 165 272 167 272 167 273 169 273 100 273 100 274 169 274 170 274 101 275 100 275 170 275 152 276 150 276 154 276 156 277 154 277 150 277 150 278 171 278 156 278 172 279 156 279 171 279 171 280 173 280 172 280 174 281 172 281 173 281 173 282 175 282 174 282 176 283 174 283 175 283 175 284 177 284 176 284 178 285 176 285 177 285 177 286 389 286 178 286 287 287 178 287 389 287 179 288 181 288 180 288 182 289 180 289 181 289 181 290 183 290 182 290 184 291 182 291 183 291 183 292 185 292 184 292 184 293 185 293 186 293 187 294 184 294 186 294 186 295 391 295 187 295 316 296 187 296 391 296 164 297 188 297 162 297 189 298 162 298 188 298 188 299 190 299 189 299 191 300 189 300 190 300 190 301 192 301 191 301 193 302 191 302 192 302 192 303 194 303 193 303 195 304 193 304 194 304 194 305 196 305 195 305 197 306 195 306 196 306 196 307 198 307 197 307 199 308 197 308 198 308 198 309 200 309 199 309 201 310 199 310 200 310 200 311 390 311 201 311 314 312 201 312 390 312 140 313 202 313 142 313 203 314 142 314 202 314 202 315 204 315 203 315 205 316 203 316 204 316 204 317 206 317 205 317 207 318 205 318 206 318 206 319 208 319 207 319 209 320 207 320 208 320 208 321 210 321 209 321 211 322 209 322 210 322 210 323 212 323 211 323 213 324 211 324 212 324 212 325 214 325 213 325 215 326 213 326 214 326 214 327 392 327 215 327 321 328 215 328 392 328 203 329 143 329 142 329 205 330 146 330 144 330 205 331 144 331 143 331 203 332 205 332 143 332 205 333 207 333 146 333 216 334 150 334 149 334 216 335 149 335 146 335 146 336 207 336 209 336 216 337 146 337 209 337 171 338 150 338 216 338 209 339 211 339 216 339 216 340 211 340 213 340 217 341 216 341 213 341 217 342 173 342 171 342 216 343 217 343 171 343 175 344 173 344 217 344 213 345 215 345 217 345 324 346 177 346 175 346 217 347 324 347 175 347 217 348 215 348 321 348 217 349 321 349 393 349 324 350 217 350 393 350 177 351 324 351 322 351 389 352 177 352 322 352 164 353 160 353 188 353 190 354 188 354 160 354 160 355 158 355 190 355 190 356 158 356 218 356 192 357 190 357 218 357 219 358 194 358 192 358 218 359 219 359 192 359 157 360 156 360 219 360 219 361 218 361 157 361 156 362 172 362 219 362 196 363 194 363 219 363 219 364 172 364 174 364 220 365 219 365 174 365 220 366 198 366 196 366 219 367 220 367 196 367 174 368 176 368 220 368 200 369 198 369 220 369 220 370 176 370 178 370 178 371 287 371 220 371 220 372 287 372 328 372 330 373 220 373 328 373 220 374 330 374 200 374 200 375 330 375 332 375 390 376 200 376 332 376 140 377 221 377 202 377 204 378 202 378 221 378 221 379 222 379 204 379 206 380 204 380 222 380 222 381 223 381 206 381 208 382 206 382 223 382 224 383 210 383 208 383 223 384 224 384 208 384 225 385 180 385 224 385 226 386 225 386 224 386 227 387 226 387 224 387 224 388 223 388 227 388 180 389 182 389 224 389 212 390 210 390 224 390 224 391 182 391 184 391 224 392 184 392 187 392 224 393 187 393 316 393 224 394 316 394 395 394 338 395 224 395 395 395 338 396 214 396 212 396 224 397 338 397 212 397 214 398 338 398 340 398 392 399 214 399 340 399 81 400 116 400 132 400 228 401 132 401 116 401 116 402 113 402 228 402 229 403 228 403 113 403 113 404 115 404 229 404 230 405 229 405 115 405 115 406 114 406 230 406 231 407 230 407 114 407 114 408 106 408 231 408 1173 409 231 409 106 409 170 410 232 410 101 410 120 411 101 411 232 411 232 412 233 412 120 412 121 413 120 413 233 413 233 414 234 414 121 414 117 415 121 415 234 415 234 416 235 416 117 416 118 417 117 417 235 417 235 418 109 418 118 418 110 419 118 419 109 419 163 420 236 420 166 420 232 421 170 421 169 421 237 422 167 422 166 422 167 423 237 423 169 423 169 424 238 424 232 424 238 425 169 425 237 425 166 426 239 426 237 426 239 427 166 427 236 427 240 428 237 428 239 428 237 429 240 429 238 429 233 430 232 430 238 430 238 431 241 431 233 431 241 432 238 432 240 432 236 433 242 433 239 433 243 434 240 434 239 434 240 435 243 435 241 435 234 436 233 436 241 436 245 437 241 437 243 437 241 438 245 438 234 438 242 439 126 439 239 439 239 440 244 440 243 440 244 441 239 441 126 441 235 442 234 442 245 442 243 443 130 443 245 443 130 444 243 444 244 444 131 445 244 445 126 445 244 446 131 446 130 446 109 447 235 447 245 447 130 448 129 448 245 448 245 449 129 449 109 449 262 450 1168 450 246 450 247 451 139 451 138 451 247 452 138 452 255 452 246 453 247 453 255 453 247 454 246 454 1168 454 148 455 139 455 247 455 1168 456 122 456 247 456 248 457 247 457 122 457 248 458 249 458 250 458 250 459 148 459 247 459 251 460 248 460 122 460 122 461 123 461 251 461 124 462 252 462 251 462 123 463 124 463 251 463 253 464 252 464 124 464 124 465 125 465 253 465 253 466 236 466 161 466 253 467 125 467 126 467 253 468 126 468 242 468 236 469 253 469 242 469 163 470 161 470 236 470 132 471 228 471 133 471 254 472 133 472 228 472 133 473 254 473 134 473 255 474 138 474 136 474 136 475 256 475 255 475 256 476 136 476 134 476 134 477 257 477 256 477 257 478 134 478 254 478 254 479 258 479 257 479 258 480 254 480 228 480 228 481 229 481 258 481 246 482 255 482 256 482 256 483 259 483 246 483 259 484 256 484 257 484 260 485 257 485 258 485 257 486 260 486 259 486 261 487 258 487 229 487 258 488 261 488 260 488 229 489 230 489 261 489 262 490 246 490 259 490 263 491 259 491 260 491 259 492 263 492 262 492 264 493 260 493 261 493 260 494 264 494 263 494 265 495 261 495 230 495 261 496 265 496 264 496 1164 497 262 497 263 497 1164 498 263 498 264 498 230 499 231 499 265 499 128 500 264 500 265 500 264 501 128 501 1164 501 231 502 1173 502 265 502 127 503 265 503 1173 503 265 504 127 504 128 504 268 505 250 505 249 505 269 506 250 506 268 506 268 507 267 507 269 507 270 508 269 508 267 508 267 509 266 509 270 509 270 510 266 510 179 510 270 511 179 511 180 511 135 512 137 512 145 512 135 513 145 513 151 513 135 514 151 514 153 514 135 515 153 515 155 515 135 516 155 516 159 516 135 517 159 517 165 517 168 518 135 518 165 518 168 519 98 519 96 519 168 520 96 520 97 520 168 521 97 521 95 521 168 522 95 522 94 522 168 523 94 523 90 523 168 524 90 524 92 524 92 525 60 525 89 525 168 526 92 526 89 526 168 527 89 527 105 527 168 528 105 528 87 528 168 529 87 529 86 529 168 530 86 530 85 530 168 531 85 531 79 531 168 532 79 532 83 532 135 533 168 533 83 533 99 534 98 534 168 534 158 535 157 535 218 535 249 536 248 536 251 536 251 537 252 537 249 537 247 538 248 538 250 538 180 539 225 539 270 539 250 540 269 540 270 540 225 541 250 541 270 541 225 542 226 542 250 542 226 543 227 543 250 543 148 544 250 544 227 544 148 545 227 545 223 545 148 546 223 546 222 546 147 547 148 547 222 547 147 548 222 548 221 548 141 549 147 549 221 549 140 550 141 550 221 550 162 551 280 551 286 551 286 552 280 552 285 552 285 553 280 553 279 553 285 554 279 554 284 554 284 555 279 555 278 555 284 556 278 556 274 556 284 557 274 557 273 557 275 558 273 558 274 558 276 559 273 559 275 559 276 560 271 560 273 560 273 561 271 561 272 561 283 562 271 562 276 562 253 563 273 563 252 563 271 564 283 564 179 564 271 565 179 565 266 565 267 566 271 566 266 566 271 567 267 567 272 567 268 568 272 568 267 568 272 569 268 569 273 569 268 570 249 570 273 570 273 571 253 571 284 571 252 572 273 572 249 572 284 573 253 573 161 573 314 574 394 574 201 574 201 575 394 575 334 575 277 576 199 576 334 576 334 577 199 577 201 577 334 578 336 578 277 578 277 579 336 579 391 579 277 580 391 580 186 580 277 581 186 581 281 581 277 582 281 582 282 582 199 583 277 583 197 583 283 584 277 584 282 584 277 585 274 585 278 585 274 586 277 586 275 586 275 587 277 587 276 587 276 588 277 588 283 588 278 589 195 589 277 589 277 590 195 590 197 590 195 591 278 591 193 591 279 592 193 592 278 592 193 593 279 593 191 593 280 594 191 594 279 594 191 595 280 595 189 595 162 596 189 596 280 596 183 597 281 597 185 597 281 598 183 598 282 598 181 599 282 599 183 599 282 600 181 600 283 600 179 601 283 601 181 601 161 602 285 602 284 602 285 603 161 603 286 603 286 604 161 604 162 604 185 605 281 605 186 605 100 606 168 606 167 606 99 607 168 607 100 607 60 608 483 608 89 608 60 609 91 609 483 609 289 610 287 610 288 610 290 611 289 611 288 611 293 612 291 612 288 612 292 613 294 613 290 613 288 614 295 614 293 614 346 615 290 615 294 615 296 616 293 616 295 616 294 617 297 617 346 617 295 618 298 618 296 618 299 619 346 619 297 619 300 620 296 620 298 620 297 621 301 621 299 621 302 622 299 622 301 622 298 623 303 623 300 623 301 624 304 624 302 624 305 625 300 625 303 625 302 626 304 626 306 626 307 627 302 627 306 627 308 628 309 628 305 628 303 629 308 629 305 629 310 630 309 630 308 630 306 631 310 631 307 631 311 632 307 632 310 632 312 633 311 633 310 633 308 634 312 634 310 634 315 635 314 635 313 635 319 636 320 636 321 636 323 637 295 637 322 637 325 638 323 638 324 638 325 639 321 639 320 639 326 640 325 640 320 640 290 641 287 641 289 641 287 642 290 642 327 642 327 643 329 643 328 643 329 644 331 644 330 644 331 645 313 645 332 645 315 646 333 646 314 646 333 647 335 647 334 647 335 648 317 648 336 648 318 649 337 649 316 649 337 650 339 650 338 650 339 651 319 651 340 651 341 652 304 652 301 652 306 653 304 653 341 653 310 654 306 654 341 654 309 655 310 655 341 655 305 656 309 656 341 656 300 657 305 657 341 657 341 658 296 658 300 658 293 659 296 659 341 659 291 660 293 660 341 660 292 661 291 661 341 661 294 662 292 662 341 662 297 663 294 663 341 663 301 664 297 664 341 664 342 665 295 665 323 665 323 666 325 666 342 666 343 667 342 667 325 667 325 668 326 668 343 668 327 669 344 669 329 669 331 670 329 670 344 670 344 671 345 671 331 671 331 672 345 672 313 672 347 673 298 673 295 673 342 674 347 674 295 674 343 675 326 675 347 675 342 676 343 676 347 676 326 677 348 677 347 677 303 678 298 678 347 678 349 679 347 679 348 679 349 680 308 680 303 680 347 681 349 681 303 681 348 682 350 682 349 682 312 683 308 683 349 683 349 684 350 684 351 684 352 685 349 685 351 685 349 686 352 686 312 686 311 687 312 687 352 687 351 688 353 688 352 688 354 689 352 689 353 689 352 690 354 690 311 690 307 691 311 691 354 691 353 692 355 692 354 692 356 693 302 693 307 693 354 694 356 694 307 694 356 695 354 695 355 695 299 696 302 696 356 696 355 697 313 697 356 697 344 698 346 698 299 698 356 699 344 699 299 699 356 700 313 700 345 700 356 701 345 701 344 701 327 702 346 702 344 702 346 703 327 703 290 703 316 704 317 704 318 704 318 705 358 705 357 705 317 706 358 706 318 706 326 707 320 707 319 707 313 708 355 708 359 708 359 708 315 708 313 708 350 709 348 709 360 709 360 709 361 709 350 709 351 710 350 710 361 710 361 710 362 710 351 710 362 711 363 711 353 711 353 711 351 711 362 711 363 712 359 712 355 712 355 712 353 712 363 712 348 713 326 713 319 713 319 713 360 713 348 713 339 714 360 714 319 714 337 715 360 715 339 715 357 716 361 716 360 716 357 717 362 717 361 717 357 718 358 718 362 718 358 719 363 719 362 719 359 720 363 720 358 720 333 721 315 721 359 721 333 722 359 722 335 722 288 723 292 723 290 723 288 724 291 724 292 724 288 725 322 725 295 725 337 726 357 726 360 726 318 727 357 727 337 727 317 728 335 728 358 728 335 729 359 729 358 729 376 730 377 730 375 730 374 731 376 731 375 731 387 732 379 732 89 732 384 733 532 733 383 733 365 734 364 734 383 734 386 735 375 735 377 735 386 736 385 736 380 736 532 737 384 737 536 737 536 738 535 738 532 738 388 739 378 739 379 739 390 740 313 740 314 740 391 741 317 741 316 741 392 742 319 742 321 742 322 743 324 743 323 743 324 744 393 744 325 744 325 745 393 745 321 745 328 746 287 746 327 746 330 747 328 747 329 747 332 748 330 748 331 748 390 749 332 749 313 749 333 750 394 750 314 750 334 751 394 751 333 751 336 752 334 752 335 752 391 753 336 753 317 753 337 754 395 754 316 754 338 755 395 755 337 755 340 756 338 756 339 756 392 757 340 757 319 757 288 758 287 758 389 758 389 759 322 759 288 759 368 760 370 760 438 760 383 761 440 761 439 761 384 762 383 762 439 762 411 763 405 763 402 763 411 764 410 764 405 764 446 765 396 765 413 765 413 766 396 766 417 766 417 767 396 767 416 767 416 768 396 768 415 768 415 769 396 769 423 769 423 770 396 770 444 770 416 771 414 771 417 771 425 772 404 772 414 772 414 773 404 773 403 773 405 774 403 774 404 774 441 775 403 775 405 775 409 776 441 776 405 776 441 777 407 777 403 777 417 778 414 778 403 778 417 779 403 779 407 779 422 780 495 780 397 780 423 781 495 781 422 781 405 782 410 782 409 782 387 783 388 783 379 783 449 784 388 784 387 784 448 785 449 785 387 785 447 786 448 786 387 786 387 787 444 787 447 787 396 788 447 788 444 788 495 789 423 789 444 789 432 790 450 790 431 790 438 791 450 791 432 791 432 792 433 792 438 792 437 793 438 793 433 793 433 794 434 794 437 794 434 795 439 795 437 795 434 796 435 796 439 796 384 797 439 797 435 797 540 798 384 798 435 798 466 799 545 799 398 799 545 800 538 800 398 800 464 801 466 801 398 801 398 802 427 802 464 802 461 803 464 803 427 803 427 804 428 804 461 804 459 805 461 805 428 805 428 806 429 806 459 806 456 807 459 807 429 807 429 808 430 808 456 808 454 809 456 809 430 809 430 810 431 810 454 810 454 811 431 811 450 811 536 812 384 812 540 812 541 813 539 813 436 813 539 814 541 814 514 814 526 815 543 815 539 815 426 816 424 816 401 816 399 817 401 817 424 817 399 818 402 818 401 818 399 819 455 819 402 819 399 820 457 820 455 820 399 821 458 821 457 821 460 822 458 822 399 822 400 823 399 823 420 823 399 824 424 824 420 824 399 825 400 825 460 825 400 826 462 826 460 826 420 827 421 827 400 827 463 828 462 828 400 828 400 829 539 829 463 829 539 830 465 830 463 830 539 831 543 831 465 831 400 832 436 832 539 832 400 833 421 833 436 833 401 834 425 834 426 834 404 835 425 835 401 835 405 836 404 836 401 836 401 837 402 837 405 837 402 838 455 838 412 838 412 839 411 839 402 839 408 840 446 840 413 840 406 841 413 841 417 841 413 842 406 842 408 842 417 843 407 843 406 843 406 844 442 844 408 844 408 845 442 845 382 845 385 846 381 846 380 846 385 847 386 847 377 847 385 848 446 848 408 848 385 849 445 849 446 849 385 850 377 850 445 850 385 851 408 851 381 851 408 852 382 852 381 852 373 853 443 853 1174 853 372 854 1174 854 443 854 372 855 441 855 409 855 372 856 443 856 441 856 409 857 1175 857 372 857 409 858 371 858 1175 858 409 859 451 859 371 859 453 860 451 860 410 860 451 861 409 861 410 861 410 862 411 862 453 862 452 863 453 863 411 863 411 864 412 864 452 864 455 865 452 865 412 865 425 866 414 866 415 866 416 867 415 867 414 867 419 868 418 868 436 868 436 869 421 869 419 869 421 870 397 870 419 870 421 871 422 871 397 871 423 872 422 872 424 872 422 873 420 873 424 873 422 874 421 874 420 874 423 875 424 875 415 875 424 876 426 876 415 876 425 877 415 877 426 877 477 878 429 878 428 878 477 879 430 879 429 879 431 880 430 880 477 880 477 881 432 881 431 881 477 882 433 882 432 882 477 883 434 883 433 883 477 884 435 884 434 884 477 885 540 885 435 885 541 886 436 886 418 886 438 887 370 887 450 887 440 888 438 888 437 888 437 889 439 889 440 889 438 890 440 890 368 890 440 891 367 891 368 891 366 892 367 892 440 892 366 893 440 893 383 893 364 894 366 894 383 894 443 895 442 895 441 895 382 896 442 896 443 896 443 897 373 897 382 897 444 898 387 898 89 898 446 899 447 899 396 899 447 900 446 900 445 900 447 901 445 901 448 901 445 902 449 902 448 902 376 903 449 903 445 903 449 904 376 904 388 904 445 905 377 905 376 905 450 906 370 906 454 906 371 907 451 907 369 907 370 908 369 908 451 908 451 909 453 909 370 909 453 910 454 910 370 910 456 911 454 911 455 911 454 912 452 912 455 912 454 913 453 913 452 913 455 914 457 914 456 914 459 915 456 915 457 915 457 916 458 916 459 916 461 917 459 917 460 917 459 918 458 918 460 918 460 919 462 919 461 919 464 920 461 920 462 920 462 921 463 921 464 921 466 922 464 922 465 922 464 923 463 923 465 923 465 924 543 924 466 924 545 925 466 925 543 925 482 926 444 926 89 926 444 927 482 927 495 927 491 928 492 928 496 928 492 929 493 929 497 929 469 930 481 930 474 930 480 931 481 931 469 931 469 932 470 932 480 932 470 933 471 933 480 933 479 934 474 934 481 934 479 935 475 935 474 935 468 936 473 936 477 936 477 937 469 937 474 937 477 938 470 938 469 938 477 939 471 939 470 939 477 940 472 940 471 940 477 941 473 941 472 941 474 942 475 942 477 942 475 943 476 943 477 943 478 944 477 944 476 944 495 945 487 945 486 945 495 946 488 946 487 946 495 947 489 947 488 947 495 948 490 948 489 948 495 949 491 949 490 949 495 950 492 950 491 950 495 951 493 951 492 951 495 952 494 952 493 952 501 953 502 953 500 953 499 954 501 954 500 954 503 955 504 955 502 955 501 956 503 956 502 956 505 957 504 957 503 957 506 958 507 958 505 958 503 959 506 959 505 959 506 960 508 960 507 960 495 961 486 961 485 961 495 962 485 962 484 962 512 963 511 963 510 963 510 964 513 964 512 964 512 965 513 965 514 965 515 966 512 966 514 966 522 967 521 967 520 967 520 968 523 968 522 968 523 969 510 969 522 969 511 970 522 970 510 970 524 971 504 971 505 971 525 972 524 972 505 972 525 973 513 973 510 973 525 974 510 974 524 974 505 975 507 975 525 975 525 976 507 976 509 976 525 977 526 977 513 977 524 978 523 978 520 978 527 979 524 979 520 979 527 980 500 980 502 980 527 981 502 981 504 981 527 982 504 982 524 982 523 983 524 983 510 983 508 984 506 984 528 984 501 985 519 985 529 985 503 986 501 986 529 986 501 987 499 987 519 987 518 988 519 988 499 988 499 989 498 989 518 989 516 990 518 990 498 990 484 991 467 991 495 991 495 992 467 992 521 992 506 993 530 993 528 993 503 994 530 994 506 994 503 995 529 995 530 995 477 996 516 996 517 996 477 997 517 997 468 997 533 998 532 998 535 998 535 999 478 999 533 999 478 1000 476 1000 534 1000 479 1001 534 1001 476 1001 476 1002 475 1002 479 1002 493 1003 494 1003 531 1003 531 1004 497 1004 493 1004 528 1005 537 1005 508 1005 545 1006 508 1006 537 1006 538 1007 545 1007 537 1007 526 1008 539 1008 514 1008 526 1009 544 1009 543 1009 526 1010 509 1010 544 1010 526 1011 514 1011 513 1011 526 1012 525 1012 509 1012 536 1013 540 1013 477 1013 535 1014 536 1014 477 1014 477 1015 478 1015 535 1015 418 1016 542 1016 541 1016 514 1017 541 1017 542 1017 542 1018 515 1018 514 1018 544 1019 545 1019 543 1019 508 1020 545 1020 509 1020 545 1021 544 1021 509 1021 508 1022 509 1022 507 1022 482 1023 89 1023 483 1023 482 1024 483 1024 494 1024 482 1025 494 1025 495 1025 652 1026 594 1026 641 1026 594 1027 566 1027 641 1027 594 1028 652 1028 1197 1028 607 1029 615 1029 603 1029 1024 1030 1025 1030 605 1030 558 1031 547 1031 548 1031 558 1032 557 1032 547 1032 582 1033 554 1033 553 1033 581 1034 554 1034 582 1034 561 1035 564 1035 996 1035 996 1036 1044 1036 561 1036 559 1037 561 1037 1044 1037 1044 1038 3475 1038 559 1038 1026 1039 559 1039 3475 1039 596 1040 554 1040 581 1040 596 1041 546 1041 554 1041 546 1042 553 1042 554 1042 548 1043 546 1043 596 1043 596 1044 598 1044 548 1044 598 1045 590 1045 548 1045 562 1046 548 1046 590 1046 590 1047 589 1047 562 1047 555 1048 1028 1048 1053 1048 1046 1049 549 1049 1053 1049 547 1050 1053 1050 550 1050 1053 1051 549 1051 550 1051 1053 1052 547 1052 555 1052 547 1053 556 1053 555 1053 557 1054 556 1054 547 1054 550 1055 551 1055 547 1055 547 1056 546 1056 548 1056 553 1057 546 1057 547 1057 547 1058 552 1058 553 1058 547 1059 551 1059 552 1059 548 1060 560 1060 558 1060 560 1061 548 1061 562 1061 589 1062 563 1062 562 1062 995 1063 1046 1063 1047 1063 995 1064 549 1064 1046 1064 995 1065 550 1065 549 1065 995 1066 551 1066 550 1066 995 1067 552 1067 551 1067 995 1068 553 1068 552 1068 553 1069 995 1069 582 1069 1028 1070 555 1070 1027 1070 1026 1071 1027 1071 555 1071 555 1072 556 1072 1026 1072 559 1073 1026 1073 557 1073 1026 1074 556 1074 557 1074 557 1075 558 1075 559 1075 561 1076 559 1076 560 1076 559 1077 558 1077 560 1077 560 1078 562 1078 561 1078 564 1079 561 1079 562 1079 562 1080 563 1080 564 1080 563 1081 1209 1081 1210 1081 564 1082 563 1082 1210 1082 566 1083 567 1083 1024 1083 605 1084 566 1084 1024 1084 568 1085 567 1085 566 1085 569 1086 568 1086 566 1086 570 1087 569 1087 566 1087 570 1088 566 1088 571 1088 1205 1089 572 1089 573 1089 1205 1090 573 1090 574 1090 1205 1091 574 1091 1197 1091 1205 1092 575 1092 572 1092 576 1093 572 1093 575 1093 606 1094 607 1094 603 1094 606 1095 603 1095 1009 1095 606 1096 1009 1096 1008 1096 578 1097 606 1097 1008 1097 1212 1098 606 1098 578 1098 578 1099 579 1099 1212 1099 578 1100 1008 1100 580 1100 579 1101 578 1101 580 1101 1211 1102 1212 1102 579 1102 1210 1103 1211 1103 579 1103 579 1104 565 1104 1210 1104 1210 1105 565 1105 564 1105 583 1106 581 1106 582 1106 582 1107 584 1107 583 1107 584 1108 585 1108 583 1108 575 1109 1205 1109 586 1109 586 1110 1207 1110 1208 1110 586 1111 1208 1111 1209 1111 587 1112 586 1112 1209 1112 563 1113 589 1113 587 1113 1209 1114 563 1114 587 1114 591 1115 592 1115 576 1115 593 1116 576 1116 592 1116 1197 1117 574 1117 594 1117 594 1118 593 1118 566 1118 594 1119 574 1119 573 1119 594 1120 573 1120 572 1120 594 1121 572 1121 593 1121 576 1122 593 1122 572 1122 566 1123 593 1123 571 1123 579 1124 1000 1124 1001 1124 579 1125 1001 1125 565 1125 999 1126 1000 1126 579 1126 579 1127 580 1127 999 1127 999 1128 580 1128 1008 1128 996 1129 564 1129 565 1129 996 1130 565 1130 1001 1130 1025 1131 1024 1131 1020 1131 1024 1132 567 1132 1019 1132 1018 1133 1019 1133 567 1133 567 1134 568 1134 1018 1134 1017 1135 1018 1135 568 1135 568 1136 569 1136 1017 1136 1016 1137 1017 1137 569 1137 569 1138 570 1138 1016 1138 1015 1139 1016 1139 570 1139 1206 1140 1207 1140 586 1140 571 1141 595 1141 602 1141 571 1142 599 1142 595 1142 600 1143 595 1143 599 1143 585 1144 595 1144 600 1144 585 1145 584 1145 595 1145 584 1146 582 1146 595 1146 995 1147 595 1147 582 1147 1012 1148 595 1148 995 1148 1013 1149 595 1149 1012 1149 1014 1150 595 1150 1013 1150 602 1151 595 1151 1014 1151 585 1152 600 1152 583 1152 583 1153 596 1153 581 1153 583 1154 598 1154 596 1154 583 1155 597 1155 598 1155 590 1156 598 1156 597 1156 587 1157 590 1157 597 1157 588 1158 587 1158 597 1158 588 1159 597 1159 577 1159 600 1160 597 1160 583 1160 600 1161 577 1161 597 1161 1014 1162 570 1162 602 1162 570 1163 1014 1163 1015 1163 592 1164 600 1164 599 1164 599 1165 571 1165 592 1165 592 1166 571 1166 593 1166 600 1167 592 1167 577 1167 592 1168 591 1168 577 1168 586 1169 587 1169 588 1169 586 1170 588 1170 577 1170 586 1171 577 1171 601 1171 601 1172 577 1172 591 1172 601 1173 591 1173 576 1173 602 1174 570 1174 571 1174 587 1175 589 1175 590 1175 575 1176 601 1176 576 1176 575 1177 586 1177 601 1177 1206 1178 586 1178 1205 1178 616 1179 617 1179 618 1179 616 1180 618 1180 619 1180 620 1181 616 1181 619 1181 621 1182 617 1182 616 1182 616 1183 622 1183 621 1183 621 1184 622 1184 623 1184 903 1185 621 1185 623 1185 903 1186 904 1186 621 1186 623 1187 624 1187 903 1187 905 1188 903 1188 624 1188 625 1189 905 1189 624 1189 625 1190 907 1190 917 1190 905 1191 625 1191 917 1191 629 1192 627 1192 628 1192 630 1193 628 1193 627 1193 627 1194 631 1194 630 1194 1057 1195 630 1195 631 1195 631 1196 632 1196 1057 1196 1025 1197 1057 1197 632 1197 634 1198 633 1198 605 1198 605 1199 632 1199 634 1199 632 1200 605 1200 1025 1200 635 1201 636 1201 637 1201 633 1202 635 1202 637 1202 633 1203 637 1203 638 1203 633 1204 638 1204 639 1204 633 1205 639 1205 640 1205 641 1206 633 1206 640 1206 633 1207 641 1207 605 1207 605 1208 641 1208 566 1208 642 1209 626 1209 908 1209 614 1210 612 1210 603 1210 615 1211 614 1211 603 1211 1058 1212 1214 1212 912 1212 608 1213 1214 1213 1058 1213 1058 1214 1059 1214 608 1214 609 1215 608 1215 1059 1215 1059 1216 644 1216 609 1216 1215 1217 609 1217 644 1217 1060 1218 610 1218 1215 1218 644 1219 1060 1219 1215 1219 611 1220 610 1220 1060 1220 1060 1221 1007 1221 611 1221 611 1222 1007 1222 1009 1222 611 1223 1009 1223 603 1223 612 1224 611 1224 603 1224 1214 1225 613 1225 912 1225 613 1226 893 1226 912 1226 915 1227 621 1227 904 1227 909 1228 643 1228 915 1228 645 1229 617 1229 621 1229 915 1230 645 1230 621 1230 915 1231 643 1231 1202 1231 915 1232 1202 1232 1203 1232 915 1233 1203 1233 646 1233 915 1234 646 1234 647 1234 645 1235 915 1235 647 1235 617 1236 645 1236 648 1236 617 1237 648 1237 649 1237 618 1238 617 1238 649 1238 1199 1239 654 1239 650 1239 1199 1240 650 1240 651 1240 1200 1241 1199 1241 651 1241 654 1242 1199 1242 1198 1242 652 1243 654 1243 1198 1243 652 1244 640 1244 639 1244 652 1245 639 1245 638 1245 652 1246 638 1246 653 1246 652 1247 653 1247 654 1247 641 1248 640 1248 652 1248 652 1249 1198 1249 1197 1249 644 1250 1059 1250 1006 1250 1060 1251 644 1251 1006 1251 630 1252 1011 1252 628 1252 1022 1253 1011 1253 630 1253 630 1254 1057 1254 1022 1254 629 1255 628 1255 604 1255 642 1256 907 1256 625 1256 642 1257 625 1257 624 1257 908 1258 907 1258 642 1258 618 1259 661 1259 662 1259 619 1260 618 1260 662 1260 662 1261 663 1261 619 1261 619 1262 663 1262 664 1262 620 1263 619 1263 664 1263 664 1264 663 1264 665 1264 666 1265 664 1265 665 1265 665 1266 667 1266 666 1266 667 1267 668 1267 669 1267 670 1268 669 1268 668 1268 666 1269 667 1269 669 1269 666 1270 669 1270 671 1270 666 1271 671 1271 672 1271 666 1272 672 1272 673 1272 674 1273 666 1273 673 1273 673 1274 675 1274 674 1274 676 1275 670 1275 668 1275 668 1276 677 1276 676 1276 674 1277 675 1277 678 1277 674 1278 678 1278 679 1278 680 1279 674 1279 679 1279 679 1280 681 1280 680 1280 682 1281 680 1281 681 1281 681 1282 683 1282 682 1282 684 1283 682 1283 683 1283 683 1284 685 1284 684 1284 684 1285 685 1285 686 1285 684 1286 686 1286 687 1286 688 1287 684 1287 687 1287 687 1288 689 1288 688 1288 692 1289 693 1289 691 1289 690 1290 692 1290 691 1290 688 1291 689 1291 693 1291 693 1292 692 1292 694 1292 694 1293 688 1293 693 1293 692 1294 695 1294 694 1294 694 1295 695 1295 696 1295 697 1296 694 1296 696 1296 696 1297 698 1297 637 1297 637 1298 698 1298 699 1298 638 1299 637 1299 699 1299 681 1300 679 1300 683 1300 685 1301 683 1301 679 1301 679 1302 700 1302 685 1302 701 1303 685 1303 700 1303 700 1304 702 1304 701 1304 703 1305 701 1305 702 1305 702 1306 704 1306 703 1306 705 1307 703 1307 704 1307 704 1308 706 1308 705 1308 707 1309 705 1309 706 1309 706 1310 918 1310 707 1310 815 1311 707 1311 918 1311 708 1312 710 1312 709 1312 711 1313 709 1313 710 1313 710 1314 712 1314 711 1314 713 1315 711 1315 712 1315 712 1316 714 1316 713 1316 713 1317 714 1317 715 1317 716 1318 713 1318 715 1318 715 1319 920 1319 716 1319 844 1320 716 1320 920 1320 693 1321 717 1321 691 1321 718 1322 691 1322 717 1322 717 1323 719 1323 718 1323 720 1324 718 1324 719 1324 719 1325 721 1325 720 1325 722 1326 720 1326 721 1326 721 1327 723 1327 722 1327 724 1328 722 1328 723 1328 723 1329 725 1329 724 1329 726 1330 724 1330 725 1330 725 1331 727 1331 726 1331 728 1332 726 1332 727 1332 727 1333 729 1333 728 1333 730 1334 728 1334 729 1334 729 1335 919 1335 730 1335 842 1336 730 1336 919 1336 669 1337 731 1337 671 1337 732 1338 671 1338 731 1338 731 1339 733 1339 732 1339 734 1340 732 1340 733 1340 733 1341 735 1341 734 1341 736 1342 734 1342 735 1342 735 1343 737 1343 736 1343 738 1344 736 1344 737 1344 737 1345 739 1345 738 1345 740 1346 738 1346 739 1346 739 1347 741 1347 740 1347 742 1348 740 1348 741 1348 741 1349 743 1349 742 1349 744 1350 742 1350 743 1350 743 1351 921 1351 744 1351 849 1352 744 1352 921 1352 732 1353 672 1353 671 1353 734 1354 675 1354 673 1354 734 1355 673 1355 672 1355 732 1356 734 1356 672 1356 734 1357 736 1357 675 1357 745 1358 679 1358 678 1358 745 1359 678 1359 675 1359 675 1360 736 1360 738 1360 745 1361 675 1361 738 1361 700 1362 679 1362 745 1362 738 1363 740 1363 745 1363 745 1364 740 1364 742 1364 746 1365 745 1365 742 1365 746 1366 702 1366 700 1366 745 1367 746 1367 700 1367 704 1368 702 1368 746 1368 742 1369 744 1369 746 1369 852 1370 706 1370 704 1370 746 1371 852 1371 704 1371 746 1372 744 1372 849 1372 746 1373 849 1373 922 1373 852 1374 746 1374 922 1374 706 1375 852 1375 850 1375 918 1376 706 1376 850 1376 693 1377 689 1377 717 1377 719 1378 717 1378 689 1378 689 1379 687 1379 719 1379 719 1380 687 1380 747 1380 721 1381 719 1381 747 1381 748 1382 723 1382 721 1382 747 1383 748 1383 721 1383 686 1384 685 1384 748 1384 748 1385 747 1385 686 1385 685 1386 701 1386 748 1386 725 1387 723 1387 748 1387 748 1388 701 1388 703 1388 749 1389 748 1389 703 1389 749 1390 727 1390 725 1390 748 1391 749 1391 725 1391 703 1392 705 1392 749 1392 729 1393 727 1393 749 1393 749 1394 705 1394 707 1394 707 1395 815 1395 749 1395 749 1396 815 1396 856 1396 858 1397 749 1397 856 1397 749 1398 858 1398 729 1398 729 1399 858 1399 860 1399 919 1400 729 1400 860 1400 669 1401 750 1401 731 1401 733 1402 731 1402 750 1402 750 1403 751 1403 733 1403 735 1404 733 1404 751 1404 751 1405 752 1405 735 1405 737 1406 735 1406 752 1406 753 1407 739 1407 737 1407 752 1408 753 1408 737 1408 754 1409 709 1409 753 1409 755 1410 754 1410 753 1410 756 1411 755 1411 753 1411 753 1412 752 1412 756 1412 709 1413 711 1413 753 1413 741 1414 739 1414 753 1414 753 1415 711 1415 713 1415 753 1416 713 1416 716 1416 753 1417 716 1417 844 1417 753 1418 844 1418 924 1418 866 1419 753 1419 924 1419 866 1420 743 1420 741 1420 753 1421 866 1421 741 1421 743 1422 866 1422 868 1422 921 1423 743 1423 868 1423 618 1424 649 1424 661 1424 757 1425 661 1425 649 1425 649 1426 648 1426 757 1426 758 1427 757 1427 648 1427 648 1428 647 1428 758 1428 759 1429 758 1429 647 1429 647 1430 646 1430 759 1430 760 1431 759 1431 646 1431 646 1432 1203 1432 760 1432 1204 1433 760 1433 1203 1433 699 1434 761 1434 638 1434 653 1435 638 1435 761 1435 761 1436 762 1436 653 1436 654 1437 653 1437 762 1437 762 1438 763 1438 654 1438 650 1439 654 1439 763 1439 763 1440 764 1440 650 1440 651 1441 650 1441 764 1441 764 1442 1201 1442 651 1442 1200 1443 651 1443 1201 1443 692 1444 765 1444 695 1444 761 1445 699 1445 698 1445 766 1446 696 1446 695 1446 696 1447 766 1447 698 1447 698 1448 767 1448 761 1448 767 1449 698 1449 766 1449 695 1450 768 1450 766 1450 768 1451 695 1451 765 1451 769 1452 766 1452 768 1452 766 1453 769 1453 767 1453 762 1454 761 1454 767 1454 767 1455 770 1455 762 1455 770 1456 767 1456 769 1456 765 1457 771 1457 768 1457 772 1458 769 1458 768 1458 769 1459 772 1459 770 1459 763 1460 762 1460 770 1460 774 1461 770 1461 772 1461 770 1462 774 1462 763 1462 771 1463 656 1463 768 1463 768 1464 773 1464 772 1464 773 1465 768 1465 656 1465 656 1466 660 1466 773 1466 764 1467 763 1467 774 1467 772 1468 658 1468 774 1468 658 1469 772 1469 773 1469 659 1470 773 1470 660 1470 773 1471 659 1471 658 1471 1201 1472 764 1472 774 1472 658 1473 657 1473 774 1473 774 1474 657 1474 1201 1474 1178 1475 1195 1475 775 1475 776 1476 668 1476 667 1476 776 1477 667 1477 784 1477 775 1478 776 1478 784 1478 776 1479 775 1479 1195 1479 677 1480 668 1480 776 1480 1195 1481 1194 1481 776 1481 777 1482 776 1482 1194 1482 777 1483 778 1483 779 1483 779 1484 677 1484 776 1484 780 1485 777 1485 1194 1485 1194 1486 1193 1486 780 1486 1192 1487 781 1487 780 1487 1193 1488 1192 1488 780 1488 782 1489 781 1489 1192 1489 1192 1490 655 1490 782 1490 782 1491 765 1491 690 1491 782 1492 655 1492 656 1492 782 1493 656 1493 771 1493 765 1494 782 1494 771 1494 692 1495 690 1495 765 1495 661 1496 757 1496 662 1496 783 1497 662 1497 757 1497 662 1498 783 1498 663 1498 784 1499 667 1499 665 1499 665 1500 785 1500 784 1500 785 1501 665 1501 663 1501 663 1502 786 1502 785 1502 786 1503 663 1503 783 1503 783 1504 787 1504 786 1504 787 1505 783 1505 757 1505 757 1506 758 1506 787 1506 775 1507 784 1507 785 1507 785 1508 788 1508 775 1508 788 1509 785 1509 786 1509 789 1510 786 1510 787 1510 786 1511 789 1511 788 1511 790 1512 787 1512 758 1512 787 1513 790 1513 789 1513 758 1514 759 1514 790 1514 1178 1515 775 1515 788 1515 791 1516 788 1516 789 1516 788 1517 791 1517 1178 1517 792 1518 789 1518 790 1518 789 1519 792 1519 791 1519 793 1520 790 1520 759 1520 790 1521 793 1521 792 1521 1185 1522 1178 1522 791 1522 1185 1523 791 1523 792 1523 759 1524 760 1524 793 1524 1188 1525 792 1525 793 1525 792 1526 1188 1526 1185 1526 760 1527 1204 1527 793 1527 1190 1528 793 1528 1204 1528 793 1529 1190 1529 1188 1529 796 1530 779 1530 778 1530 797 1531 779 1531 796 1531 796 1532 795 1532 797 1532 798 1533 797 1533 795 1533 795 1534 794 1534 798 1534 798 1535 794 1535 708 1535 798 1536 708 1536 709 1536 664 1537 666 1537 674 1537 664 1538 674 1538 680 1538 664 1539 680 1539 682 1539 664 1540 682 1540 684 1540 664 1541 684 1541 688 1541 664 1542 688 1542 694 1542 697 1543 664 1543 694 1543 697 1544 635 1544 633 1544 697 1545 633 1545 634 1545 697 1546 634 1546 632 1546 697 1547 632 1547 631 1547 697 1548 631 1548 627 1548 697 1549 627 1549 629 1549 629 1550 604 1550 626 1550 697 1551 629 1551 626 1551 697 1552 626 1552 642 1552 697 1553 642 1553 624 1553 697 1554 624 1554 623 1554 697 1555 623 1555 622 1555 697 1556 622 1556 616 1556 697 1557 616 1557 620 1557 664 1558 697 1558 620 1558 636 1559 635 1559 697 1559 645 1560 647 1560 648 1560 687 1561 686 1561 747 1561 778 1562 777 1562 780 1562 780 1563 781 1563 778 1563 776 1564 777 1564 779 1564 709 1565 754 1565 798 1565 779 1566 797 1566 798 1566 754 1567 779 1567 798 1567 754 1568 755 1568 779 1568 755 1569 756 1569 779 1569 677 1570 779 1570 756 1570 677 1571 756 1571 752 1571 677 1572 752 1572 751 1572 676 1573 677 1573 751 1573 676 1574 751 1574 750 1574 670 1575 676 1575 750 1575 669 1576 670 1576 750 1576 691 1577 808 1577 814 1577 814 1578 808 1578 813 1578 813 1579 808 1579 807 1579 813 1580 807 1580 812 1580 812 1581 807 1581 806 1581 812 1582 806 1582 802 1582 812 1583 802 1583 801 1583 803 1584 801 1584 802 1584 804 1585 801 1585 803 1585 804 1586 799 1586 801 1586 801 1587 799 1587 800 1587 811 1588 799 1588 804 1588 782 1589 801 1589 781 1589 799 1590 811 1590 708 1590 799 1591 708 1591 794 1591 795 1592 799 1592 794 1592 799 1593 795 1593 800 1593 796 1594 800 1594 795 1594 800 1595 796 1595 801 1595 796 1596 778 1596 801 1596 801 1597 782 1597 812 1597 781 1598 801 1598 778 1598 812 1599 782 1599 690 1599 842 1600 923 1600 730 1600 730 1601 923 1601 862 1601 805 1602 728 1602 862 1602 862 1603 728 1603 730 1603 862 1604 864 1604 805 1604 805 1605 864 1605 920 1605 805 1606 920 1606 715 1606 805 1607 715 1607 809 1607 805 1608 809 1608 810 1608 728 1609 805 1609 726 1609 811 1610 805 1610 810 1610 805 1611 802 1611 806 1611 802 1612 805 1612 803 1612 803 1613 805 1613 804 1613 804 1614 805 1614 811 1614 806 1615 724 1615 805 1615 805 1616 724 1616 726 1616 724 1617 806 1617 722 1617 807 1618 722 1618 806 1618 722 1619 807 1619 720 1619 808 1620 720 1620 807 1620 720 1621 808 1621 718 1621 691 1622 718 1622 808 1622 712 1623 809 1623 714 1623 809 1624 712 1624 810 1624 710 1625 810 1625 712 1625 810 1626 710 1626 811 1626 708 1627 811 1627 710 1627 690 1628 813 1628 812 1628 813 1629 690 1629 814 1629 814 1630 690 1630 691 1630 714 1631 809 1631 715 1631 637 1632 697 1632 696 1632 636 1633 697 1633 637 1633 604 1634 1011 1634 626 1634 604 1635 628 1635 1011 1635 817 1636 815 1636 816 1636 818 1637 817 1637 816 1637 821 1638 819 1638 816 1638 820 1639 822 1639 818 1639 816 1640 823 1640 821 1640 874 1641 818 1641 822 1641 824 1642 821 1642 823 1642 822 1643 825 1643 874 1643 823 1644 826 1644 824 1644 827 1645 874 1645 825 1645 828 1646 824 1646 826 1646 825 1647 829 1647 827 1647 830 1648 827 1648 829 1648 826 1649 831 1649 828 1649 829 1650 832 1650 830 1650 833 1651 828 1651 831 1651 830 1652 832 1652 834 1652 835 1653 830 1653 834 1653 836 1654 837 1654 833 1654 831 1655 836 1655 833 1655 838 1656 837 1656 836 1656 834 1657 838 1657 835 1657 839 1658 835 1658 838 1658 840 1659 839 1659 838 1659 836 1660 840 1660 838 1660 843 1661 842 1661 841 1661 847 1662 848 1662 849 1662 851 1663 823 1663 850 1663 853 1664 851 1664 852 1664 853 1665 849 1665 848 1665 854 1666 853 1666 848 1666 818 1667 815 1667 817 1667 815 1668 818 1668 855 1668 855 1669 857 1669 856 1669 857 1670 859 1670 858 1670 859 1671 841 1671 860 1671 843 1672 861 1672 842 1672 861 1673 863 1673 862 1673 863 1674 845 1674 864 1674 846 1675 865 1675 844 1675 865 1676 867 1676 866 1676 867 1677 847 1677 868 1677 869 1678 832 1678 829 1678 834 1679 832 1679 869 1679 838 1680 834 1680 869 1680 837 1681 838 1681 869 1681 833 1682 837 1682 869 1682 828 1683 833 1683 869 1683 869 1684 824 1684 828 1684 821 1685 824 1685 869 1685 819 1686 821 1686 869 1686 820 1687 819 1687 869 1687 822 1688 820 1688 869 1688 825 1689 822 1689 869 1689 829 1690 825 1690 869 1690 870 1691 823 1691 851 1691 851 1692 853 1692 870 1692 871 1693 870 1693 853 1693 853 1694 854 1694 871 1694 855 1695 872 1695 857 1695 859 1696 857 1696 872 1696 872 1697 873 1697 859 1697 859 1698 873 1698 841 1698 875 1699 826 1699 823 1699 870 1700 875 1700 823 1700 871 1701 854 1701 875 1701 870 1702 871 1702 875 1702 854 1703 876 1703 875 1703 831 1704 826 1704 875 1704 877 1705 875 1705 876 1705 877 1706 836 1706 831 1706 875 1707 877 1707 831 1707 876 1708 878 1708 877 1708 840 1709 836 1709 877 1709 877 1710 878 1710 879 1710 880 1711 877 1711 879 1711 877 1712 880 1712 840 1712 839 1713 840 1713 880 1713 879 1714 881 1714 880 1714 882 1715 880 1715 881 1715 880 1716 882 1716 839 1716 835 1717 839 1717 882 1717 881 1718 883 1718 882 1718 884 1719 830 1719 835 1719 882 1720 884 1720 835 1720 884 1721 882 1721 883 1721 827 1722 830 1722 884 1722 883 1723 841 1723 884 1723 872 1724 874 1724 827 1724 884 1725 872 1725 827 1725 884 1726 841 1726 873 1726 884 1727 873 1727 872 1727 855 1728 874 1728 872 1728 874 1729 855 1729 818 1729 844 1730 845 1730 846 1730 846 1731 886 1731 885 1731 845 1732 886 1732 846 1732 854 1733 848 1733 847 1733 841 1734 883 1734 887 1734 887 1734 843 1734 841 1734 878 1735 876 1735 888 1735 888 1735 889 1735 878 1735 879 1736 878 1736 889 1736 889 1736 890 1736 879 1736 890 1737 891 1737 881 1737 881 1737 879 1737 890 1737 891 1738 887 1738 883 1738 883 1738 881 1738 891 1738 876 1739 854 1739 847 1739 847 1739 888 1739 876 1739 867 1740 888 1740 847 1740 865 1741 888 1741 867 1741 885 1742 889 1742 888 1742 885 1743 890 1743 889 1743 885 1744 886 1744 890 1744 886 1745 891 1745 890 1745 887 1746 891 1746 886 1746 861 1747 843 1747 887 1747 861 1748 887 1748 863 1748 816 1749 820 1749 818 1749 816 1750 819 1750 820 1750 816 1751 850 1751 823 1751 865 1752 885 1752 888 1752 846 1753 885 1753 865 1753 845 1754 863 1754 886 1754 863 1755 887 1755 886 1755 905 1756 906 1756 904 1756 903 1757 905 1757 904 1757 916 1758 908 1758 626 1758 913 1759 1058 1759 912 1759 893 1760 892 1760 912 1760 915 1761 904 1761 906 1761 915 1762 914 1762 909 1762 1058 1763 913 1763 1062 1763 1062 1764 1061 1764 1058 1764 919 1765 841 1765 842 1765 920 1766 845 1766 844 1766 921 1767 847 1767 849 1767 850 1768 852 1768 851 1768 852 1769 922 1769 853 1769 853 1770 922 1770 849 1770 856 1771 815 1771 855 1771 858 1772 856 1772 857 1772 860 1773 858 1773 859 1773 919 1774 860 1774 841 1774 861 1775 923 1775 842 1775 862 1776 923 1776 861 1776 864 1777 862 1777 863 1777 920 1778 864 1778 845 1778 865 1779 924 1779 844 1779 866 1780 924 1780 865 1780 868 1781 866 1781 867 1781 921 1782 868 1782 847 1782 816 1783 815 1783 918 1783 918 1784 850 1784 816 1784 896 1785 898 1785 966 1785 912 1786 968 1786 967 1786 913 1787 912 1787 967 1787 939 1788 933 1788 930 1788 939 1789 938 1789 933 1789 974 1790 925 1790 941 1790 941 1791 925 1791 945 1791 945 1792 925 1792 944 1792 944 1793 925 1793 943 1793 943 1794 925 1794 951 1794 951 1795 925 1795 972 1795 944 1796 942 1796 945 1796 953 1797 932 1797 942 1797 942 1798 932 1798 931 1798 933 1799 931 1799 932 1799 969 1800 931 1800 933 1800 937 1801 969 1801 933 1801 969 1802 935 1802 931 1802 945 1803 942 1803 931 1803 945 1804 931 1804 935 1804 950 1805 1023 1805 3473 1805 951 1806 1023 1806 950 1806 933 1807 938 1807 937 1807 916 1808 917 1808 908 1808 977 1809 917 1809 916 1809 976 1810 977 1810 916 1810 975 1811 976 1811 916 1811 916 1812 972 1812 975 1812 925 1813 975 1813 972 1813 1023 1814 951 1814 972 1814 960 1815 978 1815 959 1815 966 1816 978 1816 960 1816 960 1817 961 1817 966 1817 965 1818 966 1818 961 1818 961 1819 962 1819 965 1819 962 1820 967 1820 965 1820 962 1821 963 1821 967 1821 913 1822 967 1822 963 1822 1066 1823 913 1823 963 1823 994 1824 1071 1824 926 1824 1071 1825 1064 1825 926 1825 992 1826 994 1826 926 1826 926 1827 955 1827 992 1827 989 1828 992 1828 955 1828 955 1829 956 1829 989 1829 987 1830 989 1830 956 1830 956 1831 957 1831 987 1831 984 1832 987 1832 957 1832 957 1833 958 1833 984 1833 982 1834 984 1834 958 1834 958 1835 959 1835 982 1835 982 1836 959 1836 978 1836 1062 1837 913 1837 1066 1837 1067 1838 1065 1838 964 1838 1065 1839 1067 1839 1042 1839 1052 1840 1069 1840 1065 1840 954 1841 952 1841 929 1841 927 1842 929 1842 952 1842 927 1843 930 1843 929 1843 927 1844 983 1844 930 1844 927 1845 985 1845 983 1845 927 1846 986 1846 985 1846 988 1847 986 1847 927 1847 928 1848 927 1848 948 1848 927 1849 952 1849 948 1849 927 1850 928 1850 988 1850 928 1851 990 1851 988 1851 948 1852 949 1852 928 1852 991 1853 990 1853 928 1853 928 1854 1065 1854 991 1854 1065 1855 993 1855 991 1855 1065 1856 1069 1856 993 1856 928 1857 964 1857 1065 1857 928 1858 949 1858 964 1858 929 1859 953 1859 954 1859 932 1860 953 1860 929 1860 933 1861 932 1861 929 1861 929 1862 930 1862 933 1862 930 1863 983 1863 940 1863 940 1864 939 1864 930 1864 936 1865 974 1865 941 1865 934 1866 941 1866 945 1866 941 1867 934 1867 936 1867 945 1868 935 1868 934 1868 911 1869 936 1869 934 1869 934 1870 970 1870 911 1870 914 1871 910 1871 909 1871 914 1872 915 1872 906 1872 914 1873 974 1873 936 1873 914 1874 973 1874 974 1874 914 1875 906 1875 973 1875 914 1876 936 1876 910 1876 936 1877 911 1877 910 1877 902 1878 971 1878 901 1878 900 1879 901 1879 971 1879 900 1880 969 1880 937 1880 900 1881 971 1881 969 1881 937 1882 1213 1882 900 1882 937 1883 899 1883 1213 1883 937 1884 979 1884 899 1884 981 1885 979 1885 938 1885 979 1886 937 1886 938 1886 938 1887 939 1887 981 1887 980 1888 981 1888 939 1888 939 1889 940 1889 980 1889 983 1890 980 1890 940 1890 953 1891 942 1891 943 1891 944 1892 943 1892 942 1892 947 1893 946 1893 964 1893 964 1894 949 1894 947 1894 949 1895 950 1895 3473 1895 951 1896 950 1896 952 1896 950 1897 948 1897 952 1897 950 1898 949 1898 948 1898 951 1899 952 1899 943 1899 952 1900 954 1900 943 1900 953 1901 943 1901 954 1901 1005 1902 957 1902 956 1902 1005 1903 958 1903 957 1903 959 1904 958 1904 1005 1904 1005 1905 960 1905 959 1905 1005 1906 961 1906 960 1906 1005 1907 962 1907 961 1907 1005 1908 963 1908 962 1908 1005 1909 1066 1909 963 1909 1067 1910 964 1910 946 1910 966 1911 898 1911 978 1911 968 1912 966 1912 965 1912 965 1913 967 1913 968 1913 966 1914 968 1914 896 1914 968 1915 895 1915 896 1915 894 1916 895 1916 968 1916 894 1917 968 1917 912 1917 892 1918 894 1918 912 1918 971 1919 970 1919 969 1919 911 1920 970 1920 971 1920 971 1921 902 1921 911 1921 972 1922 916 1922 626 1922 974 1923 975 1923 925 1923 975 1924 974 1924 973 1924 975 1925 973 1925 976 1925 973 1926 977 1926 976 1926 905 1927 977 1927 973 1927 977 1928 905 1928 917 1928 905 1929 973 1929 906 1929 978 1930 898 1930 982 1930 899 1931 979 1931 897 1931 898 1932 897 1932 979 1932 979 1933 981 1933 898 1933 981 1934 982 1934 898 1934 984 1935 982 1935 983 1935 982 1936 980 1936 983 1936 982 1937 981 1937 980 1937 983 1938 985 1938 984 1938 987 1939 984 1939 985 1939 985 1940 986 1940 987 1940 989 1941 987 1941 988 1941 987 1942 986 1942 988 1942 988 1943 990 1943 989 1943 992 1944 989 1944 990 1944 990 1945 991 1945 992 1945 994 1946 992 1946 993 1946 992 1947 991 1947 993 1947 993 1948 1069 1948 994 1948 1071 1949 994 1949 1069 1949 1010 1950 972 1950 626 1950 972 1951 1010 1951 1023 1951 1019 1952 1020 1952 1024 1952 1020 1953 1021 1953 1025 1953 997 1954 1009 1954 1002 1954 1008 1955 1009 1955 997 1955 997 1956 998 1956 1008 1956 998 1957 999 1957 1008 1957 1007 1958 1002 1958 1009 1958 1007 1959 1003 1959 1002 1959 996 1960 1001 1960 1005 1960 1005 1961 997 1961 1002 1961 1005 1962 998 1962 997 1962 1005 1963 999 1963 998 1963 1005 1964 1000 1964 999 1964 1005 1965 1001 1965 1000 1965 1002 1966 1003 1966 1005 1966 1003 1967 1004 1967 1005 1967 1006 1968 1005 1968 1004 1968 1023 1969 1015 1969 1014 1969 1023 1970 1016 1970 1015 1970 1023 1971 1017 1971 1016 1971 1023 1972 1018 1972 1017 1972 1023 1973 1019 1973 1018 1973 1023 1974 1020 1974 1019 1974 1023 1975 1021 1975 1020 1975 1023 1976 1022 1976 1021 1976 1029 1977 1030 1977 1028 1977 1027 1978 1029 1978 1028 1978 1031 1979 1032 1979 1030 1979 1029 1980 1031 1980 1030 1980 1033 1981 1032 1981 1031 1981 1034 1982 1035 1982 1033 1982 1031 1983 1034 1983 1033 1983 1034 1984 1036 1984 1035 1984 1023 1985 1014 1985 1013 1985 1023 1986 1013 1986 1012 1986 1040 1987 1039 1987 1038 1987 1038 1988 1041 1988 1040 1988 1040 1989 1041 1989 1042 1989 1043 1990 1040 1990 1042 1990 1048 1991 995 1991 1047 1991 3472 1992 1047 1992 1046 1992 1049 1993 1039 1993 3472 1993 1046 1994 1049 1994 3472 1994 1049 1995 1038 1995 1039 1995 1050 1996 1032 1996 1033 1996 1051 1997 1050 1997 1033 1997 1051 1998 1041 1998 1038 1998 1051 1999 1038 1999 1050 1999 1033 2000 1035 2000 1051 2000 1051 2001 1035 2001 1037 2001 1051 2002 1052 2002 1041 2002 1050 2003 1049 2003 1046 2003 1053 2004 1050 2004 1046 2004 1053 2005 1028 2005 1030 2005 1053 2006 1030 2006 1032 2006 1053 2007 1032 2007 1050 2007 1049 2008 1050 2008 1038 2008 1036 2009 1034 2009 1054 2009 1031 2010 1029 2010 1055 2010 1045 2011 1055 2011 1029 2011 1029 2012 1027 2012 1045 2012 3474 2013 1045 2013 1027 2013 1027 2014 1026 2014 3474 2014 3475 2015 3474 2015 1026 2015 1012 2016 995 2016 1023 2016 1023 2017 995 2017 1048 2017 1034 2018 1056 2018 1054 2018 1031 2019 1056 2019 1034 2019 1031 2020 1055 2020 1056 2020 1047 2021 1023 2021 1048 2021 1005 2022 3475 2022 1044 2022 1005 2023 1044 2023 996 2023 1059 2024 1058 2024 1061 2024 1061 2025 1006 2025 1059 2025 1006 2026 1004 2026 1060 2026 1007 2027 1060 2027 1004 2027 1004 2028 1003 2028 1007 2028 1021 2029 1022 2029 1057 2029 1057 2030 1025 2030 1021 2030 1054 2031 1063 2031 1036 2031 1071 2032 1036 2032 1063 2032 1064 2033 1071 2033 1063 2033 1052 2034 1065 2034 1042 2034 1052 2035 1070 2035 1069 2035 1052 2036 1037 2036 1070 2036 1052 2037 1042 2037 1041 2037 1052 2038 1051 2038 1037 2038 1062 2039 1066 2039 1005 2039 1061 2040 1062 2040 1005 2040 1005 2041 1006 2041 1061 2041 946 2042 1068 2042 1067 2042 1042 2043 1067 2043 1068 2043 1068 2044 1043 2044 1042 2044 1070 2045 1071 2045 1069 2045 1036 2046 1071 2046 1037 2046 1071 2047 1070 2047 1037 2047 1036 2048 1037 2048 1035 2048 1010 2049 626 2049 1011 2049 1010 2050 1011 2050 1022 2050 1010 2051 1022 2051 1023 2051 1088 2052 1081 2052 1080 2052 1087 2053 1078 2053 1079 2053 1079 2054 1081 2054 1088 2054 1088 2055 1080 2055 1082 2055 1105 2056 1091 2056 1104 2056 1090 2057 1104 2057 1091 2057 1092 2058 1090 2058 1093 2058 1090 2059 1091 2059 1093 2059 1094 2060 1092 2060 1095 2060 1092 2061 1093 2061 1095 2061 1097 2062 1094 2062 1096 2062 1094 2063 1095 2063 1096 2063 1128 2064 1097 2064 1096 2064 1128 2065 1130 2065 1097 2065 1113 2066 1097 2066 1130 2066 1089 2067 1098 2067 1108 2067 1089 2068 1099 2068 1098 2068 1099 2069 1100 2069 1098 2069 1099 2070 1102 2070 1100 2070 1102 2071 1101 2071 1100 2071 1102 2072 1103 2072 1101 2072 1101 2073 1103 2073 1129 2073 1132 2074 1129 2074 1117 2074 1129 2075 1103 2075 1117 2075 1104 2076 1106 2076 1105 2076 1107 2077 1089 2077 1108 2077 1143 2078 1155 2078 1144 2078 1155 2079 1109 2079 1144 2079 1109 2080 1130 2080 1144 2080 1109 2081 1110 2081 1130 2081 1110 2082 1111 2082 1130 2082 1111 2083 1112 2083 1130 2083 1113 2084 1130 2084 1112 2084 1134 2085 1072 2085 1075 2085 1073 2086 1072 2086 1134 2086 1134 2087 1074 2087 1073 2087 1134 2088 1114 2088 1074 2088 1134 2089 1115 2089 1114 2089 1134 2090 1116 2090 1115 2090 1134 2091 1117 2091 1116 2091 1132 2092 1117 2092 1131 2092 1117 2093 1133 2093 1131 2093 1117 2094 1134 2094 1133 2094 1143 2095 1142 2095 1155 2095 1142 2096 1154 2096 1155 2096 1153 2097 1154 2097 1142 2097 1142 2098 1141 2098 1153 2098 1152 2099 1153 2099 1141 2099 1141 2100 1140 2100 1152 2100 1140 2101 1139 2101 1151 2101 1149 2102 1150 2102 1139 2102 1139 2103 1138 2103 1149 2103 1138 2104 1148 2104 1149 2104 1147 2105 1148 2105 1138 2105 1138 2106 1146 2106 1147 2106 1146 2107 1118 2107 1147 2107 1146 2108 1119 2108 1118 2108 1122 2109 1119 2109 1146 2109 1075 2110 1076 2110 1134 2110 1135 2111 1134 2111 1076 2111 1076 2112 1077 2112 1135 2112 1087 2113 1135 2113 1077 2113 1077 2114 1078 2114 1087 2114 1088 2115 1087 2115 1079 2115 1136 2116 1088 2116 1082 2116 1082 2117 1083 2117 1136 2117 1137 2118 1136 2118 1084 2118 1136 2119 1083 2119 1084 2119 1084 2120 1086 2120 1137 2120 1145 2121 1137 2121 1121 2121 1137 2122 1120 2122 1121 2122 1137 2123 1085 2123 1120 2123 1137 2124 1086 2124 1085 2124 1127 2125 1145 2125 1121 2125 1145 2126 1126 2126 1125 2126 1145 2127 1127 2127 1126 2127 1139 2128 1150 2128 1151 2128 1151 2129 1156 2129 1140 2129 1140 2130 1156 2130 1152 2130 1157 2131 892 2131 893 2131 1157 2132 893 2132 613 2132 1157 2133 613 2133 1214 2133 1254 2134 1157 2134 1214 2134 892 2135 1157 2135 894 2135 1157 2136 1245 2136 894 2136 131 2137 126 2137 1159 2137 126 2138 1158 2138 1159 2138 130 2139 131 2139 1160 2139 131 2140 1159 2140 1160 2140 129 2141 130 2141 1161 2141 130 2142 1160 2142 1161 2142 1217 2143 129 2143 1161 2143 1162 2144 129 2144 1217 2144 1217 2145 1225 2145 1162 2145 109 2146 1162 2146 1225 2146 262 2147 1163 2147 1169 2147 1169 2148 1163 2148 1222 2148 262 2149 1164 2149 1163 2149 1164 2150 1165 2150 1163 2150 1164 2151 128 2151 1165 2151 128 2152 1166 2152 1165 2152 128 2153 1167 2153 1166 2153 128 2154 127 2154 1167 2154 1167 2155 127 2155 1216 2155 1227 2156 1216 2156 1173 2156 1216 2157 127 2157 1173 2157 126 2158 125 2158 1158 2158 1158 2159 125 2159 1223 2159 125 2160 124 2160 1223 2160 124 2161 123 2161 1223 2161 123 2162 122 2162 1223 2162 122 2163 1168 2163 1223 2163 1222 2164 1223 2164 1169 2164 1223 2165 1168 2165 1169 2165 1168 2166 262 2166 1169 2166 1239 2167 62 2167 1240 2167 62 2168 1172 2168 1240 2168 1172 2169 1226 2169 1240 2169 1172 2170 111 2170 1226 2170 111 2171 1225 2171 1226 2171 111 2172 1170 2172 1225 2172 1170 2173 1171 2173 1225 2173 1171 2174 110 2174 1225 2174 109 2175 1225 2175 110 2175 373 2176 1228 2176 382 2176 1228 2177 381 2177 382 2177 1228 2178 380 2178 381 2178 1228 2179 108 2179 380 2179 1228 2180 107 2180 108 2180 1228 2181 106 2181 107 2181 1228 2182 1173 2182 106 2182 1173 2183 1228 2183 1227 2183 1239 2184 1238 2184 62 2184 1238 2185 63 2185 62 2185 64 2186 63 2186 1238 2186 1238 2187 1237 2187 64 2187 65 2188 64 2188 1237 2188 1237 2189 1236 2189 65 2189 1236 2190 17 2190 65 2190 66 2191 17 2191 1236 2191 1236 2192 1235 2192 66 2192 1235 2193 67 2193 66 2193 68 2194 67 2194 1235 2194 1235 2195 1234 2195 68 2195 1234 2196 69 2196 68 2196 70 2197 69 2197 1234 2197 1234 2198 1255 2198 70 2198 1255 2199 78 2199 70 2199 1255 2200 77 2200 78 2200 75 2201 77 2201 1255 2201 373 2202 1174 2202 1228 2202 1229 2203 1228 2203 1174 2203 1174 2204 372 2204 1229 2204 1230 2205 1229 2205 372 2205 372 2206 1175 2206 1230 2206 1231 2207 1230 2207 371 2207 1230 2208 1175 2208 371 2208 371 2209 369 2209 1231 2209 1232 2210 1231 2210 368 2210 1231 2211 370 2211 368 2211 1231 2212 369 2212 370 2212 368 2213 367 2213 1232 2213 1233 2214 1232 2214 366 2214 1232 2215 367 2215 366 2215 366 2216 364 2216 1233 2216 1256 2217 1233 2217 1176 2217 1233 2218 76 2218 1176 2218 1233 2219 365 2219 76 2219 1233 2220 364 2220 365 2220 1177 2221 1256 2221 1176 2221 1255 2222 1256 2222 74 2222 74 2223 75 2223 1255 2223 1256 2224 73 2224 74 2224 1256 2225 72 2225 73 2225 1256 2226 71 2226 72 2226 1256 2227 1177 2227 71 2227 1191 2228 1179 2228 656 2228 660 2229 656 2229 1179 2229 659 2230 660 2230 1180 2230 660 2231 1179 2231 1180 2231 658 2232 659 2232 1181 2232 659 2233 1180 2233 1181 2233 657 2234 658 2234 1182 2234 658 2235 1181 2235 1182 2235 1218 2236 657 2236 1182 2236 1183 2237 657 2237 1218 2237 1218 2238 1221 2238 1183 2238 1201 2239 1183 2239 1221 2239 1178 2240 1184 2240 1196 2240 1178 2241 1185 2241 1184 2241 1185 2242 1186 2242 1184 2242 1185 2243 1188 2243 1186 2243 1188 2244 1187 2244 1186 2244 1188 2245 1189 2245 1187 2245 1188 2246 1190 2246 1189 2246 1189 2247 1190 2247 1219 2247 1220 2248 1219 2248 1204 2248 1219 2249 1190 2249 1204 2249 656 2250 655 2250 1191 2250 1191 2251 655 2251 1224 2251 655 2252 1192 2252 1224 2252 1192 2253 1193 2253 1224 2253 1193 2254 1194 2254 1224 2254 1194 2255 1195 2255 1224 2255 1224 2256 1195 2256 1196 2256 1195 2257 1178 2257 1196 2257 1251 2258 1205 2258 1252 2258 1205 2259 1197 2259 1252 2259 1197 2260 1221 2260 1252 2260 1197 2261 1198 2261 1221 2261 1198 2262 1199 2262 1221 2262 1199 2263 1200 2263 1221 2263 1201 2264 1221 2264 1200 2264 902 2265 1241 2265 911 2265 1241 2266 910 2266 911 2266 1241 2267 909 2267 910 2267 1241 2268 643 2268 909 2268 1241 2269 1202 2269 643 2269 1241 2270 1203 2270 1202 2270 1241 2271 1204 2271 1203 2271 1204 2272 1241 2272 1220 2272 1251 2273 1250 2273 1205 2273 1250 2274 1206 2274 1205 2274 1207 2275 1206 2275 1250 2275 1250 2276 1249 2276 1207 2276 1208 2277 1207 2277 1249 2277 1249 2278 1248 2278 1208 2278 1248 2279 1209 2279 1208 2279 1210 2280 1209 2280 1248 2280 1248 2281 1247 2281 1210 2281 1247 2282 1211 2282 1210 2282 1212 2283 1211 2283 1247 2283 1247 2284 1246 2284 1212 2284 1246 2285 606 2285 1212 2285 607 2286 606 2286 1246 2286 1246 2287 1253 2287 607 2287 1253 2288 615 2288 607 2288 1253 2289 614 2289 615 2289 612 2290 614 2290 1253 2290 902 2291 901 2291 1241 2291 1242 2292 1241 2292 901 2292 901 2293 900 2293 1242 2293 1243 2294 1242 2294 900 2294 900 2295 1213 2295 1243 2295 1244 2296 1243 2296 899 2296 1243 2297 1213 2297 899 2297 899 2298 897 2298 1244 2298 1245 2299 1244 2299 896 2299 1244 2300 898 2300 896 2300 1244 2301 897 2301 898 2301 896 2302 895 2302 1245 2302 1245 2303 895 2303 894 2303 608 2304 1254 2304 1214 2304 1253 2305 1254 2305 611 2305 611 2306 612 2306 1253 2306 1254 2307 610 2307 611 2307 1254 2308 1215 2308 610 2308 1254 2309 609 2309 1215 2309 1254 2310 608 2310 609 2310 1319 2311 1157 2311 1254 2311 1320 2312 1157 2312 1319 2312 1321 2313 1157 2313 1320 2313 1245 2314 1157 2314 1321 2314 1221 2315 1364 2315 1252 2315 1369 2316 1252 2316 1364 2316 1241 2317 1367 2317 1220 2317 1338 2318 1220 2318 1367 2318 1375 2319 1320 2319 1319 2319 1375 2320 1319 2320 1371 2320 1270 2321 1257 2321 1258 2321 1303 2322 1257 2322 1270 2322 1304 2323 1257 2323 1303 2323 1306 2324 1257 2324 1304 2324 1224 2325 1303 2325 1300 2325 1305 2326 1224 2326 1300 2326 1222 2327 1163 2327 1302 2327 1196 2328 1184 2328 1306 2328 1184 2329 1257 2329 1306 2329 1184 2330 1186 2330 1257 2330 1258 2331 1257 2331 1186 2331 1186 2332 1187 2332 1258 2332 1187 2333 1189 2333 1258 2333 1189 2334 1219 2334 1258 2334 1219 2335 1271 2335 1258 2335 1338 2336 1271 2336 1220 2336 1271 2337 1219 2337 1220 2337 1159 2338 1260 2338 1160 2338 1260 2339 1161 2339 1160 2339 1159 2340 1301 2340 1260 2340 1159 2341 1158 2341 1301 2341 1259 2342 1161 2342 1260 2342 1161 2343 1259 2343 1217 2343 1259 2344 1225 2344 1217 2344 1259 2345 1354 2345 1225 2345 1261 2346 1259 2346 1260 2346 1259 2347 1261 2347 1354 2347 1261 2348 1353 2348 1354 2348 1351 2349 1353 2349 1261 2349 1260 2350 1289 2350 1262 2350 1260 2351 1301 2351 1289 2351 1260 2352 1262 2352 1261 2352 1261 2353 1263 2353 1351 2353 1263 2354 1349 2354 1351 2354 1263 2355 1261 2355 1262 2355 1289 2356 1281 2356 1262 2356 1262 2357 1264 2357 1263 2357 1264 2358 1262 2358 1286 2358 1262 2359 1284 2359 1286 2359 1262 2360 1281 2360 1284 2360 1347 2361 1349 2361 1263 2361 1263 2362 1265 2362 1347 2362 1265 2363 1263 2363 1264 2363 1346 2364 1347 2364 1265 2364 1286 2365 1288 2365 1264 2365 1266 2366 1264 2366 1291 2366 1264 2367 1288 2367 1291 2367 1264 2368 1266 2368 1265 2368 1267 2369 1265 2369 1266 2369 1265 2370 1267 2370 1346 2370 1267 2371 1344 2371 1346 2371 1342 2372 1344 2372 1267 2372 1291 2373 1293 2373 1266 2373 1268 2374 1266 2374 1295 2374 1266 2375 1293 2375 1295 2375 1266 2376 1268 2376 1267 2376 1269 2377 1267 2377 1268 2377 1267 2378 1269 2378 1342 2378 1269 2379 1341 2379 1342 2379 1295 2380 1297 2380 1268 2380 1268 2381 1299 2381 1270 2381 1268 2382 1297 2382 1299 2382 1268 2383 1270 2383 1269 2383 1339 2384 1341 2384 1269 2384 1269 2385 1270 2385 1258 2385 1269 2386 1258 2386 1339 2386 1299 2387 1303 2387 1270 2387 1338 2388 1339 2388 1271 2388 1339 2389 1258 2389 1271 2389 1305 2390 1179 2390 1191 2390 1180 2391 1179 2391 1274 2391 1181 2392 1180 2392 1272 2392 1180 2393 1274 2393 1272 2393 1182 2394 1181 2394 1272 2394 1218 2395 1182 2395 1273 2395 1182 2396 1272 2396 1273 2396 1273 2397 1364 2397 1218 2397 1221 2398 1218 2398 1364 2398 1275 2399 1272 2399 1274 2399 1272 2400 1275 2400 1273 2400 1275 2401 1364 2401 1273 2401 1275 2402 1365 2402 1364 2402 1305 2403 1300 2403 1179 2403 1300 2404 1274 2404 1179 2404 1274 2405 1276 2405 1275 2405 1276 2406 1274 2406 1298 2406 1274 2407 1300 2407 1298 2407 1362 2408 1365 2408 1275 2408 1298 2409 1296 2409 1276 2409 1278 2410 1275 2410 1277 2410 1275 2411 1276 2411 1277 2411 1275 2412 1278 2412 1362 2412 1278 2413 1361 2413 1362 2413 1278 2414 1359 2414 1361 2414 1277 2415 1276 2415 1292 2415 1276 2416 1296 2416 1292 2416 1292 2417 1290 2417 1277 2417 1277 2418 1279 2418 1278 2418 1279 2419 1277 2419 1287 2419 1277 2420 1290 2420 1287 2420 1357 2421 1359 2421 1278 2421 1280 2422 1278 2422 1279 2422 1278 2423 1280 2423 1357 2423 1280 2424 1355 2424 1357 2424 1287 2425 1285 2425 1279 2425 1279 2426 1285 2426 1283 2426 1283 2427 1284 2427 1282 2427 1286 2428 1284 2428 1285 2428 1284 2429 1283 2429 1285 2429 1285 2430 1287 2430 1286 2430 1288 2431 1286 2431 1287 2431 1287 2432 1290 2432 1288 2432 1291 2433 1288 2433 1290 2433 1301 2434 1294 2434 1289 2434 1290 2435 1292 2435 1291 2435 1293 2436 1291 2436 1292 2436 1292 2437 1296 2437 1293 2437 1296 2438 1295 2438 1293 2438 1294 2439 1301 2439 1223 2439 1297 2440 1295 2440 1296 2440 1296 2441 1298 2441 1297 2441 1299 2442 1297 2442 1298 2442 1298 2443 1300 2443 1299 2443 1303 2444 1299 2444 1300 2444 1301 2445 1158 2445 1223 2445 1222 2446 1302 2446 1223 2446 1304 2447 1303 2447 1224 2447 1306 2448 1304 2448 1224 2448 1305 2449 1191 2449 1224 2449 1196 2450 1306 2450 1224 2450 1307 2451 1320 2451 1377 2451 1320 2452 1375 2452 1377 2452 1320 2453 1307 2453 1321 2453 1307 2454 1322 2454 1321 2454 1307 2455 1323 2455 1322 2455 1308 2456 1323 2456 1307 2456 1308 2457 1324 2457 1323 2457 1308 2458 1367 2458 1324 2458 1308 2459 1340 2459 1367 2459 1377 2460 1378 2460 1307 2460 1307 2461 1309 2461 1308 2461 1309 2462 1307 2462 1388 2462 1307 2463 1386 2463 1388 2463 1307 2464 1378 2464 1386 2464 1310 2465 1308 2465 1309 2465 1308 2466 1310 2466 1340 2466 1310 2467 1343 2467 1340 2467 1388 2468 1390 2468 1309 2468 1311 2469 1309 2469 1392 2469 1309 2470 1390 2470 1392 2470 1309 2471 1311 2471 1310 2471 1312 2472 1310 2472 1311 2472 1310 2473 1312 2473 1343 2473 1312 2474 1345 2474 1343 2474 1392 2475 1395 2475 1311 2475 1348 2476 1345 2476 1312 2476 1313 2477 1311 2477 1380 2477 1311 2478 1396 2478 1380 2478 1395 2479 1396 2479 1311 2479 1311 2480 1313 2480 1312 2480 1312 2481 1314 2481 1348 2481 1314 2482 1312 2482 1313 2482 1350 2483 1348 2483 1314 2483 1380 2484 1381 2484 1313 2484 1315 2485 1313 2485 1382 2485 1313 2486 1381 2486 1382 2486 1313 2487 1315 2487 1314 2487 1316 2488 1314 2488 1315 2488 1314 2489 1316 2489 1350 2489 1316 2490 1352 2490 1350 2490 1382 2491 1384 2491 1315 2491 1317 2492 1315 2492 1383 2492 1315 2493 1384 2493 1383 2493 1315 2494 1317 2494 1316 2494 1316 2495 1318 2495 1352 2495 1318 2496 1366 2496 1352 2496 1318 2497 1316 2497 1317 2497 1317 2498 1235 2498 1318 2498 1317 2499 1234 2499 1235 2499 1317 2500 1255 2500 1234 2500 1317 2501 1373 2501 1255 2501 1317 2502 1372 2502 1373 2502 1317 2503 1383 2503 1372 2503 1238 2504 1318 2504 1237 2504 1318 2505 1236 2505 1237 2505 1318 2506 1235 2506 1236 2506 1318 2507 1238 2507 1366 2507 1366 2508 1238 2508 1239 2508 1371 2509 1319 2509 1254 2509 1321 2510 1322 2510 1245 2510 1322 2511 1244 2511 1245 2511 1243 2512 1244 2512 1322 2512 1322 2513 1323 2513 1243 2513 1242 2514 1243 2514 1324 2514 1243 2515 1323 2515 1324 2515 1324 2516 1367 2516 1242 2516 1241 2517 1242 2517 1367 2517 1253 2518 1331 2518 1370 2518 1253 2519 1246 2519 1331 2519 1246 2520 1335 2520 1331 2520 1246 2521 1247 2521 1335 2521 1247 2522 1334 2522 1335 2522 1333 2523 1334 2523 1248 2523 1334 2524 1247 2524 1248 2524 1248 2525 1249 2525 1333 2525 1337 2526 1333 2526 1249 2526 1249 2527 1250 2527 1337 2527 1368 2528 1337 2528 1251 2528 1337 2529 1250 2529 1251 2529 1327 2530 1325 2530 1393 2530 1325 2531 1394 2531 1393 2531 1326 2532 1328 2532 1356 2532 1328 2533 1326 2533 1327 2533 1358 2534 1356 2534 1328 2534 1393 2535 1391 2535 1327 2535 1327 2536 1329 2536 1328 2536 1329 2537 1327 2537 1389 2537 1327 2538 1391 2538 1389 2538 1330 2539 1328 2539 1329 2539 1328 2540 1330 2540 1358 2540 1330 2541 1360 2541 1358 2541 1389 2542 1387 2542 1329 2542 1332 2543 1329 2543 1379 2543 1329 2544 1385 2544 1379 2544 1329 2545 1387 2545 1385 2545 1329 2546 1332 2546 1330 2546 1336 2547 1330 2547 1332 2547 1330 2548 1336 2548 1360 2548 1336 2549 1363 2549 1360 2549 1379 2550 1376 2550 1332 2550 1332 2551 1335 2551 1336 2551 1332 2552 1331 2552 1335 2552 1332 2553 1370 2553 1331 2553 1332 2554 1374 2554 1370 2554 1332 2555 1376 2555 1374 2555 1337 2556 1336 2556 1333 2556 1336 2557 1334 2557 1333 2557 1336 2558 1335 2558 1334 2558 1336 2559 1337 2559 1363 2559 1337 2560 1368 2560 1363 2560 1339 2561 1338 2561 1367 2561 1367 2562 1340 2562 1339 2562 1341 2563 1339 2563 1340 2563 1342 2564 1341 2564 1343 2564 1341 2565 1340 2565 1343 2565 1344 2566 1342 2566 1343 2566 1343 2567 1345 2567 1344 2567 1346 2568 1344 2568 1345 2568 1345 2569 1348 2569 1346 2569 1347 2570 1346 2570 1348 2570 1349 2571 1347 2571 1348 2571 1348 2572 1350 2572 1349 2572 1351 2573 1349 2573 1350 2573 1350 2574 1352 2574 1351 2574 1353 2575 1351 2575 1352 2575 1354 2576 1353 2576 1366 2576 1353 2577 1352 2577 1366 2577 1225 2578 1354 2578 1226 2578 1354 2579 1240 2579 1226 2579 1354 2580 1366 2580 1240 2580 1357 2581 1355 2581 1356 2581 1356 2582 1358 2582 1357 2582 1359 2583 1357 2583 1358 2583 1358 2584 1360 2584 1359 2584 1361 2585 1359 2585 1360 2585 1362 2586 1361 2586 1363 2586 1361 2587 1360 2587 1363 2587 1365 2588 1362 2588 1363 2588 1363 2589 1368 2589 1365 2589 1365 2590 1369 2590 1364 2590 1365 2591 1368 2591 1369 2591 1366 2592 1239 2592 1240 2592 1368 2593 1251 2593 1369 2593 1252 2594 1369 2594 1251 2594 1253 2595 1370 2595 1254 2595 1371 2596 1254 2596 1370 2596 1255 2597 1373 2597 1256 2597 1256 2598 1372 2598 1383 2598 1256 2599 1373 2599 1372 2599 1105 2600 1106 2600 1414 2600 1106 2601 1397 2601 1414 2601 1397 2602 1398 2602 1414 2602 1398 2603 1399 2603 1414 2603 1399 2604 1107 2604 1414 2604 1414 2605 1107 2605 1108 2605 1130 2606 1428 2606 1144 2606 1105 2607 1410 2607 1091 2607 1404 2608 1091 2608 1410 2608 1279 2609 1400 2609 1280 2609 1400 2610 1279 2610 1409 2610 1279 2611 1283 2611 1409 2611 1427 2612 1355 2612 1280 2612 1401 2613 1280 2613 1400 2613 1280 2614 1401 2614 1427 2614 1409 2615 1411 2615 1400 2615 1425 2616 1427 2616 1401 2616 1400 2617 1403 2617 1401 2617 1403 2618 1400 2618 1413 2618 1400 2619 1412 2619 1413 2619 1400 2620 1411 2620 1412 2620 1402 2621 1401 2621 1403 2621 1401 2622 1402 2622 1425 2622 1402 2623 1423 2623 1425 2623 1402 2624 1421 2624 1423 2624 1419 2625 1421 2625 1402 2625 1402 2626 1100 2626 1101 2626 1402 2627 1403 2627 1100 2627 1402 2628 1101 2628 1419 2628 1132 2629 1419 2629 1129 2629 1419 2630 1101 2630 1129 2630 1100 2631 1403 2631 1098 2631 1403 2632 1413 2632 1098 2632 1413 2633 1108 2633 1098 2633 1404 2634 1093 2634 1091 2634 1404 2635 1405 2635 1093 2635 1095 2636 1093 2636 1405 2636 1405 2637 1406 2637 1095 2637 1406 2638 1096 2638 1095 2638 1096 2639 1406 2639 1128 2639 1130 2640 1128 2640 1408 2640 1128 2641 1406 2641 1408 2641 1130 2642 1408 2642 1407 2642 1282 2643 1410 2643 1283 2643 1410 2644 1409 2644 1283 2644 1411 2645 1409 2645 1410 2645 1412 2646 1411 2646 1410 2646 1413 2647 1412 2647 1414 2647 1412 2648 1410 2648 1414 2648 1410 2649 1105 2649 1414 2649 1414 2650 1108 2650 1413 2650 1429 2651 1137 2651 1145 2651 1137 2652 1415 2652 1136 2652 1415 2653 1088 2653 1136 2653 1415 2654 1087 2654 1088 2654 1415 2655 1137 2655 1436 2655 1137 2656 1435 2656 1436 2656 1137 2657 1430 2657 1435 2657 1137 2658 1429 2658 1430 2658 1135 2659 1087 2659 1416 2659 1416 2660 1134 2660 1135 2660 1416 2661 1420 2661 1134 2661 1416 2662 1087 2662 1415 2662 1422 2663 1420 2663 1416 2663 1415 2664 1417 2664 1416 2664 1417 2665 1415 2665 1434 2665 1415 2666 1436 2666 1434 2666 1418 2667 1416 2667 1417 2667 1416 2668 1418 2668 1422 2668 1424 2669 1422 2669 1418 2669 1434 2670 1431 2670 1417 2670 1325 2671 1417 2671 1432 2671 1417 2672 1431 2672 1432 2672 1417 2673 1325 2673 1418 2673 1418 2674 1326 2674 1424 2674 1326 2675 1426 2675 1424 2675 1326 2676 1418 2676 1325 2676 1432 2677 1433 2677 1325 2677 1356 2678 1426 2678 1326 2678 1325 2679 1327 2679 1326 2679 1433 2680 1394 2680 1325 2680 1134 2681 1420 2681 1133 2681 1420 2682 1131 2682 1133 2682 1420 2683 1132 2683 1131 2683 1419 2684 1132 2684 1420 2684 1421 2685 1419 2685 1420 2685 1420 2686 1422 2686 1421 2686 1423 2687 1421 2687 1422 2687 1422 2688 1424 2688 1423 2688 1425 2689 1423 2689 1424 2689 1424 2690 1426 2690 1425 2690 1427 2691 1425 2691 1426 2691 1426 2692 1356 2692 1427 2692 1355 2693 1427 2693 1356 2693 1436 2694 1435 2694 1434 2694 1446 2695 1437 2695 1445 2695 1500 2696 1466 2696 1446 2696 1466 2697 1437 2697 1446 2697 1599 2698 1460 2698 1588 2698 1599 2699 1600 2699 1460 2699 1600 2700 1459 2700 1460 2700 1600 2701 1457 2701 1459 2701 1600 2702 1458 2702 1457 2702 1600 2703 1449 2703 1458 2703 1600 2704 1448 2704 1449 2704 1600 2705 1447 2705 1448 2705 1567 2706 1570 2706 1565 2706 1571 2707 1574 2707 1570 2707 1438 2708 1437 2708 1466 2708 1466 2709 1468 2709 1438 2709 1439 2710 1438 2710 1468 2710 1468 2711 1470 2711 1439 2711 1440 2712 1439 2712 1470 2712 1470 2713 1472 2713 1440 2713 1442 2714 1440 2714 1472 2714 1472 2715 1474 2715 1442 2715 1443 2716 1442 2716 1474 2716 1474 2717 1477 2717 1443 2717 1477 2718 1480 2718 1444 2718 1437 2719 1438 2719 1445 2719 1441 2720 1445 2720 1439 2720 1445 2721 1438 2721 1439 2721 1457 2722 1458 2722 1450 2722 1450 2723 1451 2723 1457 2723 1451 2724 1459 2724 1457 2724 1460 2725 1459 2725 1451 2725 1451 2726 1452 2726 1460 2726 1461 2727 1460 2727 1452 2727 1452 2728 1453 2728 1461 2728 1453 2729 1462 2729 1461 2729 1464 2730 1462 2730 1453 2730 1453 2731 1454 2731 1464 2731 1494 2732 1464 2732 1493 2732 1464 2733 1492 2733 1493 2733 1464 2734 1491 2734 1492 2734 1464 2735 1490 2735 1491 2735 1464 2736 1454 2736 1490 2736 1454 2737 1455 2737 1489 2737 1489 2738 1490 2738 1454 2738 1455 2739 1488 2739 1489 2739 1487 2740 1488 2740 1455 2740 1456 2741 1486 2741 1487 2741 1460 2742 1461 2742 1588 2742 1463 2743 1588 2743 1461 2743 1463 2744 1590 2744 1588 2744 1461 2745 1462 2745 1463 2745 1597 2746 1590 2746 1463 2746 1465 2747 1463 2747 1464 2747 1463 2748 1462 2748 1464 2748 1463 2749 1465 2749 1597 2749 1596 2750 1597 2750 1465 2750 1464 2751 1494 2751 1465 2751 1465 2752 1495 2752 1496 2752 1465 2753 1494 2753 1495 2753 1465 2754 1496 2754 1596 2754 1496 2755 1595 2755 1596 2755 1591 2756 1595 2756 1497 2756 1595 2757 1496 2757 1497 2757 1505 2758 1506 2758 1500 2758 1467 2759 1500 2759 1506 2759 1469 2760 1466 2760 1500 2760 1469 2761 1500 2761 1467 2761 1506 2762 1507 2762 1467 2762 1468 2763 1466 2763 1469 2763 1471 2764 1467 2764 1508 2764 1467 2765 1507 2765 1508 2765 1467 2766 1471 2766 1469 2766 1469 2767 1473 2767 1468 2767 1473 2768 1470 2768 1468 2768 1473 2769 1469 2769 1471 2769 1508 2770 1509 2770 1471 2770 1472 2771 1470 2771 1473 2771 1471 2772 1475 2772 1473 2772 1475 2773 1471 2773 1510 2773 1471 2774 1509 2774 1510 2774 1473 2775 1476 2775 1472 2775 1476 2776 1474 2776 1472 2776 1476 2777 1473 2777 1475 2777 1510 2778 1504 2778 1475 2778 1477 2779 1474 2779 1476 2779 1478 2780 1475 2780 1504 2780 1475 2781 1478 2781 1476 2781 1476 2782 1479 2782 1477 2782 1479 2783 1476 2783 1478 2783 1504 2784 1503 2784 1478 2784 1480 2785 1477 2785 1479 2785 1482 2786 1478 2786 1502 2786 1478 2787 1503 2787 1502 2787 1478 2788 1482 2788 1479 2788 1483 2789 1479 2789 1482 2789 1479 2790 1483 2790 1480 2790 1483 2791 1481 2791 1480 2791 1484 2792 1481 2792 1483 2792 1485 2793 1563 2793 1486 2793 1487 2794 1486 2794 1563 2794 1563 2795 1560 2795 1487 2795 1488 2796 1487 2796 1562 2796 1487 2797 1561 2797 1562 2797 1487 2798 1560 2798 1561 2798 1562 2799 1558 2799 1488 2799 1558 2800 1489 2800 1488 2800 1490 2801 1489 2801 1558 2801 1558 2802 1557 2802 1490 2802 1491 2803 1490 2803 1557 2803 1557 2804 1559 2804 1491 2804 1492 2805 1491 2805 1559 2805 1559 2806 1556 2806 1492 2806 1493 2807 1492 2807 1556 2807 1556 2808 1555 2808 1493 2808 1494 2809 1493 2809 1555 2809 1555 2810 1554 2810 1494 2810 1554 2811 1495 2811 1494 2811 1496 2812 1495 2812 1554 2812 1554 2813 1553 2813 1496 2813 1553 2814 1498 2814 1496 2814 1497 2815 1496 2815 1498 2815 1591 2816 1497 2816 1594 2816 1497 2817 1498 2817 1594 2817 1498 2818 1553 2818 1552 2818 1552 2819 1581 2819 1498 2819 1581 2820 1513 2820 1498 2820 1513 2821 1594 2821 1498 2821 1593 2822 1594 2822 1513 2822 1513 2823 1516 2823 1593 2823 1592 2824 1593 2824 1516 2824 1516 2825 1518 2825 1592 2825 1589 2826 1592 2826 1518 2826 1518 2827 1520 2827 1589 2827 1587 2828 1589 2828 1520 2828 1520 2829 1523 2829 1587 2829 1585 2830 1587 2830 1523 2830 1523 2831 1529 2831 1585 2831 1585 2832 1527 2832 1499 2832 1585 2833 1529 2833 1527 2833 1583 2834 1527 2834 1528 2834 1583 2835 1499 2835 1527 2835 1528 2836 1530 2836 1598 2836 1505 2837 1500 2837 1511 2837 1501 2838 1502 2838 1512 2838 1502 2839 1503 2839 1512 2839 1503 2840 1504 2840 1512 2840 1504 2841 1510 2841 1512 2841 1511 2842 1512 2842 1505 2842 1512 2843 1506 2843 1505 2843 1512 2844 1507 2844 1506 2844 1512 2845 1508 2845 1507 2845 1512 2846 1509 2846 1508 2846 1512 2847 1510 2847 1509 2847 1530 2848 1582 2848 1598 2848 1514 2849 1533 2849 1531 2849 1532 2850 1515 2850 1581 2850 1515 2851 1513 2851 1581 2851 1515 2852 1532 2852 1514 2852 1532 2853 1533 2853 1514 2853 1516 2854 1513 2854 1515 2854 1514 2855 1517 2855 1515 2855 1519 2856 1515 2856 1517 2856 1515 2857 1519 2857 1516 2857 1518 2858 1516 2858 1519 2858 1517 2859 1521 2859 1519 2859 1519 2860 1522 2860 1518 2860 1522 2861 1520 2861 1518 2861 1522 2862 1519 2862 1521 2862 1523 2863 1520 2863 1522 2863 1521 2864 1525 2864 1522 2864 1522 2865 1526 2865 1523 2865 1526 2866 1522 2866 1525 2866 1529 2867 1523 2867 1526 2867 1525 2868 1524 2868 1530 2868 1530 2869 1526 2869 1525 2869 1526 2870 1528 2870 1529 2870 1526 2871 1530 2871 1528 2871 1529 2872 1528 2872 1527 2872 1534 2873 1531 2873 1533 2873 1535 2874 1533 2874 1581 2874 1533 2875 1532 2875 1581 2875 1533 2876 1535 2876 1534 2876 1581 2877 1536 2877 1535 2877 1536 2878 1581 2878 1565 2878 1537 2879 1534 2879 1535 2879 1538 2880 1535 2880 1536 2880 1535 2881 1538 2881 1537 2881 1565 2882 1570 2882 1536 2882 1536 2883 1540 2883 1538 2883 1540 2884 1536 2884 1570 2884 1541 2885 1537 2885 1538 2885 1537 2886 1541 2886 1539 2886 1542 2887 1538 2887 1540 2887 1538 2888 1542 2888 1541 2888 1543 2889 1539 2889 1541 2889 1570 2890 1574 2890 1540 2890 1545 2891 1540 2891 1574 2891 1540 2892 1545 2892 1542 2892 1547 2893 1541 2893 1546 2893 1541 2894 1542 2894 1546 2894 1541 2895 1547 2895 1543 2895 1546 2896 1542 2896 1545 2896 1543 2897 1548 2897 1544 2897 1548 2898 1543 2898 1547 2898 1549 2899 1544 2899 1548 2899 1574 2900 1576 2900 1545 2900 1545 2901 1550 2901 1546 2901 1550 2902 1545 2902 1578 2902 1545 2903 1576 2903 1578 2903 1546 2904 1551 2904 1547 2904 1552 2905 1553 2905 1581 2905 1553 2906 1554 2906 1581 2906 1554 2907 1555 2907 1581 2907 1555 2908 1556 2908 1581 2908 1556 2909 1559 2909 1581 2909 1566 2910 1559 2910 1564 2910 1559 2911 1557 2911 1564 2911 1557 2912 1558 2912 1564 2912 1558 2913 1562 2913 1564 2913 1559 2914 1566 2914 1581 2914 1565 2915 1581 2915 1566 2915 1563 2916 1564 2916 1560 2916 1564 2917 1561 2917 1560 2917 1564 2918 1562 2918 1561 2918 1564 2919 1568 2919 1566 2919 1566 2920 1569 2920 1565 2920 1569 2921 1567 2921 1565 2921 1569 2922 1566 2922 1568 2922 1570 2923 1567 2923 1569 2923 1568 2924 1572 2924 1569 2924 1573 2925 1569 2925 1572 2925 1569 2926 1573 2926 1570 2926 1573 2927 1571 2927 1570 2927 1574 2928 1571 2928 1573 2928 1577 2929 1573 2929 1575 2929 1573 2930 1577 2930 1574 2930 1577 2931 1576 2931 1574 2931 1578 2932 1576 2932 1577 2932 1577 2933 1580 2933 1578 2933 1579 2934 1578 2934 1580 2934 1584 2935 1499 2935 1583 2935 1585 2936 1499 2936 1584 2936 1584 2937 1586 2937 1585 2937 1587 2938 1585 2938 1586 2938 1589 2939 1587 2939 1588 2939 1587 2940 1586 2940 1588 2940 1592 2941 1589 2941 1591 2941 1589 2942 1590 2942 1591 2942 1589 2943 1588 2943 1590 2943 1590 2944 1597 2944 1591 2944 1595 2945 1591 2945 1597 2945 1591 2946 1594 2946 1592 2946 1594 2947 1593 2947 1592 2947 1597 2948 1596 2948 1595 2948 1630 2949 1631 2949 1613 2949 1445 2950 1441 2950 1606 2950 1439 2951 1440 2951 1441 2951 1603 2952 1441 2952 1442 2952 1441 2953 1440 2953 1442 2953 1618 2954 1604 2954 1619 2954 1604 2955 1616 2955 1619 2955 1604 2956 1618 2956 1612 2956 1618 2957 1630 2957 1612 2957 1612 2958 1610 2958 1604 2958 1617 2959 1605 2959 1611 2959 1608 2960 1627 2960 1607 2960 1608 2961 1628 2961 1627 2961 1607 2962 1609 2962 1608 2962 1631 2963 1628 2963 1608 2963 1613 2964 1608 2964 1609 2964 1608 2965 1613 2965 1631 2965 1609 2966 1610 2966 1612 2966 1609 2967 1612 2967 1613 2967 1630 2968 1613 2968 1612 2968 1578 2969 1579 2969 1550 2969 1614 2970 1620 2970 1622 2970 1622 2971 1615 2971 1614 2971 1615 2972 1622 2972 1619 2972 1619 2973 1616 2973 1615 2973 1580 2974 1620 2974 1579 2974 1635 2975 1633 2975 1625 2975 1633 2976 1626 2976 1632 2976 1626 2977 1627 2977 1632 2977 1665 2978 1447 2978 1601 2978 1659 2979 1647 2979 1665 2979 1665 2980 1637 2980 1447 2980 1637 2981 1448 2981 1447 2981 1637 2982 1665 2982 1648 2982 1665 2983 1647 2983 1648 2983 1449 2984 1448 2984 1637 2984 1648 2985 1649 2985 1637 2985 1637 2986 1638 2986 1449 2986 1638 2987 1450 2987 1449 2987 1638 2988 1637 2988 1650 2988 1637 2989 1649 2989 1650 2989 1451 2990 1450 2990 1638 2990 1650 2991 1651 2991 1638 2991 1638 2992 1639 2992 1451 2992 1638 2993 1651 2993 1652 2993 1449 2994 1450 2994 1458 2994 1641 2995 1640 2995 1625 2995 1640 2996 1641 2996 1643 2996 1641 2997 1645 2997 1643 2997 1625 2998 1632 2998 1641 2998 1646 2999 1645 2999 1641 2999 1641 3000 1619 3000 1646 3000 1619 3001 1641 3001 1618 3001 1641 3002 1630 3002 1618 3002 1641 3003 1632 3003 1630 3003 1646 3004 1619 3004 1622 3004 1572 3005 1575 3005 1573 3005 1575 3006 1572 3006 1642 3006 1575 3007 1644 3007 1577 3007 1644 3008 1575 3008 1642 3008 1642 3009 1645 3009 1644 3009 1643 3010 1645 3010 1642 3010 1580 3011 1577 3011 1644 3011 1644 3012 1621 3012 1580 3012 1621 3013 1644 3013 1645 3013 1645 3014 1646 3014 1621 3014 1620 3015 1580 3015 1621 3015 1621 3016 1622 3016 1620 3016 1622 3017 1621 3017 1646 3017 1635 3018 1625 3018 1624 3018 1633 3019 1632 3019 1625 3019 1627 3020 1628 3020 1632 3020 1628 3021 1631 3021 1632 3021 1632 3022 1631 3022 1630 3022 1658 3023 1623 3023 1657 3023 1600 3024 1667 3024 1601 3024 1601 3025 1667 3025 1636 3025 1666 3026 1601 3026 1636 3026 1656 3027 1662 3027 1601 3027 1666 3028 1656 3028 1601 3028 1663 3029 1662 3029 1656 3029 1664 3030 1663 3030 1656 3030 1660 3031 1664 3031 1656 3031 1656 3032 1653 3032 1660 3032 1665 3033 1663 3033 1659 3033 1665 3034 1601 3034 1662 3034 1663 3035 1665 3035 1662 3035 1659 3036 1663 3036 1664 3036 1659 3037 1664 3037 1660 3037 1601 3038 1447 3038 1600 3038 1634 3039 1669 3039 1668 3039 1623 3040 1629 3040 1657 3040 1629 3041 1635 3041 1657 3041 1624 3042 1657 3042 1635 3042 1698 3043 1695 3043 1683 3043 1639 3044 1452 3044 1451 3044 1639 3045 1638 3045 1652 3045 1453 3046 1452 3046 1639 3046 1652 3047 1719 3047 1639 3047 1639 3048 1670 3048 1453 3048 1670 3049 1454 3049 1453 3049 1670 3050 1639 3050 1720 3050 1639 3051 1719 3051 1720 3051 1455 3052 1454 3052 1670 3052 1720 3053 1718 3053 1670 3053 1671 3054 1670 3054 1717 3054 1670 3055 1718 3055 1717 3055 1670 3056 1671 3056 1455 3056 1671 3057 1456 3057 1455 3057 1699 3058 1456 3058 1671 3058 1717 3059 1716 3059 1671 3059 1694 3060 1696 3060 1671 3060 1696 3061 1697 3061 1671 3061 1697 3062 1699 3062 1671 3062 1694 3063 1671 3063 1716 3063 1716 3064 1715 3064 1694 3064 1715 3065 1714 3065 1692 3065 1692 3066 1694 3066 1715 3066 1455 3067 1456 3067 1487 3067 1701 3068 1486 3068 1456 3068 1456 3069 1699 3069 1701 3069 1787 3070 1791 3070 1737 3070 1786 3071 1790 3071 1787 3071 1785 3072 1781 3072 1784 3072 1785 3073 1788 3073 1786 3073 1690 3074 1781 3074 1785 3074 1737 3075 1735 3075 1787 3075 1672 3076 1787 3076 1735 3076 1787 3077 1672 3077 1786 3077 1786 3078 1673 3078 1785 3078 1673 3079 1786 3079 1672 3079 1674 3080 1785 3080 1673 3080 1785 3081 1674 3081 1690 3081 1674 3082 1689 3082 1690 3082 1735 3083 1733 3083 1672 3083 1675 3084 1672 3084 1733 3084 1672 3085 1675 3085 1673 3085 1673 3086 1676 3086 1674 3086 1676 3087 1673 3087 1675 3087 1687 3088 1689 3088 1674 3088 1674 3089 1677 3089 1687 3089 1677 3090 1685 3090 1687 3090 1677 3091 1674 3091 1676 3091 1733 3092 1731 3092 1675 3092 1675 3093 1678 3093 1676 3093 1678 3094 1675 3094 1729 3094 1675 3095 1731 3095 1729 3095 1676 3096 1679 3096 1677 3096 1679 3097 1676 3097 1678 3097 1684 3098 1685 3098 1677 3098 1703 3099 1677 3099 1679 3099 1677 3100 1703 3100 1684 3100 1703 3101 1706 3101 1684 3101 1729 3102 1727 3102 1678 3102 1678 3103 1680 3103 1679 3103 1680 3104 1678 3104 1727 3104 1679 3105 1681 3105 1703 3105 1681 3106 1679 3106 1680 3106 1727 3107 1725 3107 1680 3107 1680 3108 1723 3108 1702 3108 1680 3109 1725 3109 1723 3109 1680 3110 1702 3110 1681 3110 1703 3111 1681 3111 1704 3111 1681 3112 1702 3112 1704 3112 1682 3113 1705 3113 1485 3113 1705 3114 1563 3114 1485 3114 1705 3115 1682 3115 1707 3115 1485 3116 1700 3116 1682 3116 1683 3117 1682 3117 1698 3117 1682 3118 1700 3118 1698 3118 1682 3119 1683 3119 1707 3119 1706 3120 1707 3120 1684 3120 1707 3121 1686 3121 1684 3121 1686 3122 1707 3122 1695 3122 1707 3123 1683 3123 1695 3123 1685 3124 1684 3124 1686 3124 1695 3125 1693 3125 1686 3125 1686 3126 1688 3126 1685 3126 1688 3127 1687 3127 1685 3127 1688 3128 1686 3128 1712 3128 1686 3129 1693 3129 1712 3129 1712 3130 1713 3130 1688 3130 1689 3131 1687 3131 1688 3131 1691 3132 1688 3132 1711 3132 1688 3133 1713 3133 1711 3133 1688 3134 1691 3134 1689 3134 1691 3135 1690 3135 1689 3135 1711 3136 1710 3136 1691 3136 1781 3137 1690 3137 1691 3137 1691 3138 1710 3138 1741 3138 1691 3139 1741 3139 1781 3139 1781 3140 1741 3140 1782 3140 1712 3141 1693 3141 1714 3141 1693 3142 1692 3142 1714 3142 1694 3143 1692 3143 1693 3143 1693 3144 1695 3144 1694 3144 1696 3145 1694 3145 1695 3145 1695 3146 1698 3146 1696 3146 1698 3147 1697 3147 1696 3147 1699 3148 1697 3148 1698 3148 1698 3149 1700 3149 1699 3149 1701 3150 1699 3150 1700 3150 1700 3151 1485 3151 1701 3151 1486 3152 1701 3152 1485 3152 1723 3153 1722 3153 1702 3153 1722 3154 1704 3154 1702 3154 1640 3155 1703 3155 1704 3155 1640 3156 1706 3156 1703 3156 1640 3157 1708 3157 1706 3157 1640 3158 1643 3158 1708 3158 1640 3159 1704 3159 1722 3159 1722 3160 1624 3160 1640 3160 1640 3161 1624 3161 1625 3161 1564 3162 1563 3162 1705 3162 1709 3163 1705 3163 1707 3163 1705 3164 1709 3164 1564 3164 1568 3165 1564 3165 1709 3165 1706 3166 1708 3166 1707 3166 1708 3167 1709 3167 1707 3167 1709 3168 1643 3168 1642 3168 1709 3169 1708 3169 1643 3169 1709 3170 1642 3170 1568 3170 1572 3171 1568 3171 1642 3171 1647 3172 1659 3172 1741 3172 1741 3173 1710 3173 1647 3173 1648 3174 1647 3174 1710 3174 1710 3175 1711 3175 1648 3175 1649 3176 1648 3176 1711 3176 1711 3177 1713 3177 1649 3177 1650 3178 1649 3178 1714 3178 1649 3179 1713 3179 1714 3179 1713 3180 1712 3180 1714 3180 1714 3181 1715 3181 1650 3181 1651 3182 1650 3182 1715 3182 1715 3183 1716 3183 1651 3183 1652 3184 1651 3184 1716 3184 1716 3185 1717 3185 1652 3185 1719 3186 1652 3186 1717 3186 1717 3187 1718 3187 1719 3187 1720 3188 1719 3188 1718 3188 1731 3189 1733 3189 1732 3189 1729 3190 1731 3190 1730 3190 1727 3191 1729 3191 1728 3191 1725 3192 1727 3192 1726 3192 1724 3193 1723 3193 1725 3193 1722 3194 1723 3194 1657 3194 1723 3195 1724 3195 1657 3195 1726 3196 1724 3196 1725 3196 1728 3197 1726 3197 1727 3197 1730 3198 1728 3198 1729 3198 1732 3199 1730 3199 1731 3199 1734 3200 1732 3200 1733 3200 1733 3201 1735 3201 1734 3201 1736 3202 1734 3202 1735 3202 1735 3203 1737 3203 1736 3203 1738 3204 1736 3204 1737 3204 1737 3205 1739 3205 1738 3205 1740 3206 1738 3206 1739 3206 1741 3207 1659 3207 1660 3207 1742 3208 1741 3208 1660 3208 1653 3209 1743 3209 1744 3209 1653 3210 1744 3210 1745 3210 1653 3211 1745 3211 1746 3211 1653 3212 1746 3212 1747 3212 1653 3213 1747 3213 1748 3213 1653 3214 1748 3214 1749 3214 1653 3215 1749 3215 1750 3215 1653 3216 1750 3216 1751 3216 1653 3217 1751 3217 1742 3217 1660 3218 1653 3218 1742 3218 1721 3219 1743 3219 1653 3219 1751 3220 1752 3220 1753 3220 1742 3221 1751 3221 1753 3221 1754 3222 1752 3222 1751 3222 1751 3223 1750 3223 1754 3223 1755 3224 1754 3224 1750 3224 1750 3225 1749 3225 1755 3225 1756 3226 1755 3226 1749 3226 1749 3227 1748 3227 1756 3227 1757 3228 1756 3228 1748 3228 1748 3229 1747 3229 1757 3229 1758 3230 1757 3230 1747 3230 1747 3231 1746 3231 1758 3231 1745 3232 1744 3232 1759 3232 1744 3233 1743 3233 1759 3233 1655 3234 1760 3234 1721 3234 1752 3235 1767 3235 1768 3235 1753 3236 1752 3236 1768 3236 1769 3237 1738 3237 1740 3237 1769 3238 1740 3238 1770 3238 1769 3239 1770 3239 1771 3239 1772 3240 1769 3240 1771 3240 1772 3241 1771 3241 1773 3241 1772 3242 1773 3242 1774 3242 1767 3243 1772 3243 1774 3243 1772 3244 1767 3244 1752 3244 1752 3245 1754 3245 1772 3245 1736 3246 1738 3246 1769 3246 1775 3247 1734 3247 1736 3247 1769 3248 1775 3248 1736 3248 1775 3249 1769 3249 1772 3249 1772 3250 1754 3250 1755 3250 1776 3251 1772 3251 1755 3251 1772 3252 1776 3252 1775 3252 1755 3253 1756 3253 1776 3253 1732 3254 1734 3254 1775 3254 1777 3255 1775 3255 1776 3255 1775 3256 1777 3256 1732 3256 1776 3257 1778 3257 1777 3257 1776 3258 1756 3258 1757 3258 1778 3259 1776 3259 1757 3259 1730 3260 1732 3260 1777 3260 1757 3261 1758 3261 1778 3261 1779 3262 1777 3262 1778 3262 1779 3263 1728 3263 1730 3263 1777 3264 1779 3264 1730 3264 1778 3265 1763 3265 1779 3265 1778 3266 1758 3266 1759 3266 1778 3267 1759 3267 1763 3267 1726 3268 1728 3268 1779 3268 1780 3269 1779 3269 1763 3269 1779 3270 1780 3270 1726 3270 1724 3271 1726 3271 1780 3271 1763 3272 1759 3272 1760 3272 1763 3273 1661 3273 1762 3273 1780 3274 1761 3274 1764 3274 1765 3275 1780 3275 1764 3275 1780 3276 1765 3276 1724 3276 1724 3277 1765 3277 1766 3277 1657 3278 1724 3278 1766 3278 1781 3279 1782 3279 1783 3279 1784 3280 1781 3280 1783 3280 1785 3281 1784 3281 1789 3281 1788 3282 1785 3282 1789 3282 1786 3283 1788 3283 1790 3283 1787 3284 1790 3284 1791 3284 1737 3285 1791 3285 1792 3285 1739 3286 1737 3286 1792 3286 1784 3287 1783 3287 1753 3287 1753 3288 1783 3288 1782 3288 1753 3289 1782 3289 1741 3289 1742 3290 1753 3290 1741 3290 1739 3291 1792 3291 1740 3291 1770 3292 1740 3292 1792 3292 1792 3293 1791 3293 1770 3293 1771 3294 1770 3294 1791 3294 1791 3295 1790 3295 1771 3295 1773 3296 1771 3296 1790 3296 1774 3297 1773 3297 1790 3297 1790 3298 1788 3298 1774 3298 1767 3299 1774 3299 1788 3299 1788 3300 1789 3300 1767 3300 1768 3301 1767 3301 1789 3301 1789 3302 1784 3302 1768 3302 1753 3303 1768 3303 1784 3303 1761 3304 1763 3304 1762 3304 1761 3305 1780 3305 1763 3305 1655 3306 1661 3306 1760 3306 1760 3307 1661 3307 1763 3307 1721 3308 1760 3308 1743 3308 1743 3309 1760 3309 1759 3309 1745 3310 1759 3310 1758 3310 1745 3311 1758 3311 1746 3311 1624 3312 1722 3312 1657 3312 1654 3313 1653 3313 1656 3313 1793 3314 1633 3314 1635 3314 1795 3315 1798 3315 1657 3315 1794 3316 1795 3316 1657 3316 1633 3317 1793 3317 1830 3317 1634 3318 1828 3318 1829 3318 1634 3319 1829 3319 1830 3319 1830 3320 1793 3320 1634 3320 1634 3321 1793 3321 1635 3321 1634 3322 1635 3322 1799 3322 1799 3323 1796 3323 1797 3323 1799 3324 1635 3324 1796 3324 1798 3325 1658 3325 1657 3325 1620 3326 1800 3326 1579 3326 1802 3327 1617 3327 1801 3327 1801 3328 1803 3328 1802 3328 1616 3329 1802 3329 1803 3329 1803 3330 1615 3330 1616 3330 1804 3331 1805 3331 1806 3331 1807 3332 1801 3332 1617 3332 1807 3333 1617 3333 1808 3333 1807 3334 1808 3334 1805 3334 1805 3335 1804 3335 1809 3335 1807 3336 1805 3336 1809 3336 1803 3337 1801 3337 1807 3337 1809 3338 1810 3338 1807 3338 1614 3339 1615 3339 1803 3339 1807 3340 1614 3340 1803 3340 1614 3341 1807 3341 1810 3341 1810 3342 1811 3342 1614 3342 1620 3343 1614 3343 1811 3343 1811 3344 1800 3344 1620 3344 1812 3345 1816 3345 1813 3345 1813 3346 1811 3346 1814 3346 1813 3347 1816 3347 1800 3347 1813 3348 1800 3348 1811 3348 1814 3349 1811 3349 1810 3349 1814 3350 1810 3350 1815 3350 1815 3351 1810 3351 1809 3351 1817 3352 1809 3352 1804 3352 1579 3353 1800 3353 1816 3353 1551 3354 1816 3354 1812 3354 1550 3355 1579 3355 1816 3355 1818 3356 1819 3356 1611 3356 1818 3357 1611 3357 1610 3357 1609 3358 1818 3358 1610 3358 1820 3359 1819 3359 1818 3359 1821 3360 1818 3360 1609 3360 1818 3361 1821 3361 1820 3361 1609 3362 1607 3362 1821 3362 1822 3363 1820 3363 1821 3363 1821 3364 1823 3364 1822 3364 1823 3365 1821 3365 1607 3365 1607 3366 1824 3366 1823 3366 1824 3367 1607 3367 1627 3367 1825 3368 1822 3368 1823 3368 1627 3369 1826 3369 1824 3369 1826 3370 1627 3370 1626 3370 1827 3371 1825 3371 1823 3371 1827 3372 1823 3372 1824 3372 1626 3373 1633 3373 1826 3373 1828 3374 1827 3374 1824 3374 1824 3375 1829 3375 1828 3375 1829 3376 1824 3376 1826 3376 1830 3377 1826 3377 1633 3377 1826 3378 1830 3378 1829 3378 1634 3379 1825 3379 1827 3379 1634 3380 1827 3380 1828 3380 1825 3381 1606 3381 1822 3381 1820 3382 1822 3382 1606 3382 1819 3383 1820 3383 1606 3383 1606 3384 1831 3384 1819 3384 1819 3385 1831 3385 1832 3385 1611 3386 1819 3386 1832 3386 1833 3387 1611 3387 1832 3387 1834 3388 1833 3388 1832 3388 1832 3389 1835 3389 1834 3389 1834 3390 1835 3390 1836 3390 1833 3391 1834 3391 1837 3391 1837 3392 1617 3392 1833 3392 1611 3393 1833 3393 1617 3393 1617 3394 1802 3394 1605 3394 1838 3395 1610 3395 1611 3395 1838 3396 1611 3396 1605 3396 1838 3397 1605 3397 1802 3397 1838 3398 1604 3398 1610 3398 1838 3399 1802 3399 1616 3399 1604 3400 1838 3400 1616 3400 1840 3401 1839 3401 1817 3401 1841 3402 1817 3402 1804 3402 1817 3403 1841 3403 1840 3403 1804 3404 1806 3404 1841 3404 1842 3405 1841 3405 1806 3405 1842 3406 1843 3406 1840 3406 1841 3407 1842 3407 1840 3407 1806 3408 1805 3408 1842 3408 1844 3409 1842 3409 1805 3409 1842 3410 1844 3410 1843 3410 1805 3411 1808 3411 1844 3411 1837 3412 1836 3412 1843 3412 1844 3413 1837 3413 1843 3413 1844 3414 1808 3414 1617 3414 1844 3415 1617 3415 1837 3415 1836 3416 1837 3416 1834 3416 1845 3417 1847 3417 1846 3417 1845 3418 1839 3418 1840 3418 1847 3419 1845 3419 1840 3419 1846 3420 1603 3420 1443 3420 1603 3421 1846 3421 1847 3421 1442 3422 1443 3422 1603 3422 1847 3423 1848 3423 1603 3423 1441 3424 1603 3424 1848 3424 1848 3425 1606 3425 1441 3425 1831 3426 1606 3426 1848 3426 1832 3427 1831 3427 1848 3427 1848 3428 1835 3428 1832 3428 1848 3429 1843 3429 1836 3429 1848 3430 1836 3430 1835 3430 1840 3431 1848 3431 1847 3431 1840 3432 1843 3432 1848 3432 1634 3433 1606 3433 1825 3433 1634 3434 1445 3434 1606 3434 1959 3435 1951 3435 1952 3435 1950 3436 1951 3436 1959 3436 1959 3437 1960 3437 1950 3437 1960 3438 1949 3438 1950 3438 1948 3439 1949 3439 1960 3439 1947 3440 1948 3440 1960 3440 1960 3441 1957 3441 1947 3441 1946 3442 1947 3442 1957 3442 1945 3443 1946 3443 1957 3443 1958 3444 1944 3444 1945 3444 1943 3445 1944 3445 1958 3445 1444 3446 1443 3446 1477 3446 1856 3447 1444 3447 1480 3447 1480 3448 1481 3448 1856 3448 1857 3449 1856 3449 1481 3449 1481 3450 1484 3450 1857 3450 1860 3451 1857 3451 1484 3451 1484 3452 1869 3452 1860 3452 1863 3453 1860 3453 1869 3453 1869 3454 1870 3454 1863 3454 1862 3455 1863 3455 1871 3455 1952 3456 1961 3456 1959 3456 1953 3457 1849 3457 1952 3457 1849 3458 1953 3458 1955 3458 1850 3459 1904 3459 1903 3459 1850 3460 1956 3460 1904 3460 1850 3461 1955 3461 1956 3461 1903 3462 1902 3462 1851 3462 1852 3463 1851 3463 1897 3463 1897 3464 1894 3464 1852 3464 1851 3465 1900 3465 1897 3465 1851 3466 1902 3466 1900 3466 1892 3467 1865 3467 1894 3467 1865 3468 1852 3468 1894 3468 1853 3469 1852 3469 1865 3469 1865 3470 1866 3470 1853 3470 1866 3471 1867 3471 1854 3471 1867 3472 1861 3472 1855 3472 1855 3473 1861 3473 1862 3473 1443 3474 1444 3474 1846 3474 1882 3475 1839 3475 1845 3475 1858 3476 1846 3476 1856 3476 1846 3477 1444 3477 1856 3477 1846 3478 1858 3478 1845 3478 1859 3479 1845 3479 1858 3479 1845 3480 1859 3480 1882 3480 1859 3481 1884 3481 1882 3481 1856 3482 1857 3482 1858 3482 1886 3483 1884 3483 1859 3483 1864 3484 1858 3484 1860 3484 1858 3485 1857 3485 1860 3485 1858 3486 1864 3486 1859 3486 1868 3487 1859 3487 1864 3487 1859 3488 1868 3488 1886 3488 1868 3489 1888 3489 1886 3489 1860 3490 1863 3490 1864 3490 1890 3491 1888 3491 1868 3491 1864 3492 1867 3492 1868 3492 1864 3493 1861 3493 1867 3493 1864 3494 1862 3494 1861 3494 1864 3495 1863 3495 1862 3495 1892 3496 1868 3496 1865 3496 1868 3497 1866 3497 1865 3497 1868 3498 1867 3498 1866 3498 1868 3499 1892 3499 1890 3499 1872 3500 1873 3500 1874 3500 1872 3501 1940 3501 1873 3501 1872 3502 1911 3502 1940 3502 1940 3503 1941 3503 1873 3503 1941 3504 1874 3504 1873 3504 1941 3505 1876 3505 1874 3505 1877 3506 1875 3506 1876 3506 1877 3507 1876 3507 1941 3507 1941 3508 1938 3508 1877 3508 1878 3509 1877 3509 1938 3509 1877 3510 1878 3510 1879 3510 1938 3511 1936 3511 1878 3511 1878 3512 1898 3512 1880 3512 1878 3513 1895 3513 1898 3513 1878 3514 1891 3514 1895 3514 1878 3515 1936 3515 1891 3515 1881 3516 1912 3516 1817 3516 1881 3517 1817 3517 1839 3517 1839 3518 1882 3518 1881 3518 1914 3519 1912 3519 1881 3519 1883 3520 1881 3520 1882 3520 1881 3521 1883 3521 1914 3521 1882 3522 1884 3522 1883 3522 1920 3523 1914 3523 1883 3523 1885 3524 1883 3524 1884 3524 1883 3525 1885 3525 1920 3525 1884 3526 1886 3526 1885 3526 1926 3527 1920 3527 1885 3527 1887 3528 1885 3528 1886 3528 1885 3529 1887 3529 1926 3529 1932 3530 1926 3530 1887 3530 1886 3531 1888 3531 1887 3531 1887 3532 1889 3532 1932 3532 1889 3533 1887 3533 1888 3533 1934 3534 1932 3534 1889 3534 1888 3535 1890 3535 1889 3535 1893 3536 1889 3536 1890 3536 1889 3537 1893 3537 1934 3537 1891 3538 1934 3538 1893 3538 1890 3539 1892 3539 1893 3539 1893 3540 1896 3540 1891 3540 1896 3541 1893 3541 1894 3541 1893 3542 1892 3542 1894 3542 1895 3543 1891 3543 1896 3543 1894 3544 1897 3544 1896 3544 1896 3545 1901 3545 1895 3545 1901 3546 1898 3546 1895 3546 1901 3547 1896 3547 1897 3547 1897 3548 1900 3548 1901 3548 1901 3549 1902 3549 1898 3549 1902 3550 1899 3550 1898 3550 1901 3551 1900 3551 1902 3551 1902 3552 1903 3552 1899 3552 1903 3553 1904 3553 1899 3553 1904 3554 1956 3554 1899 3554 1551 3555 1546 3555 1550 3555 1547 3556 1906 3556 1548 3556 1906 3557 1547 3557 1551 3557 1907 3558 1548 3558 1906 3558 1548 3559 1907 3559 1549 3559 1909 3560 1549 3560 1907 3560 1549 3561 1909 3561 1905 3561 1909 3562 1908 3562 1905 3562 1550 3563 1816 3563 1551 3563 1551 3564 1917 3564 1906 3564 1917 3565 1551 3565 1913 3565 1551 3566 1812 3566 1913 3566 1924 3567 1906 3567 1919 3567 1906 3568 1917 3568 1919 3568 1906 3569 1924 3569 1907 3569 1907 3570 1927 3570 1909 3570 1907 3571 1925 3571 1927 3571 1907 3572 1924 3572 1925 3572 1911 3573 1908 3573 1909 3573 1910 3574 1909 3574 1933 3574 1909 3575 1930 3575 1933 3575 1909 3576 1927 3576 1930 3576 1909 3577 1910 3577 1911 3577 1940 3578 1911 3578 1942 3578 1911 3579 1910 3579 1942 3579 1815 3580 1809 3580 1817 3580 1817 3581 1912 3581 1815 3581 1815 3582 1915 3582 1814 3582 1915 3583 1815 3583 1914 3583 1815 3584 1912 3584 1914 3584 1916 3585 1814 3585 1915 3585 1814 3586 1916 3586 1813 3586 1918 3587 1813 3587 1916 3587 1813 3588 1918 3588 1812 3588 1918 3589 1913 3589 1812 3589 1917 3590 1913 3590 1918 3590 1914 3591 1920 3591 1915 3591 1915 3592 1921 3592 1916 3592 1921 3593 1915 3593 1920 3593 1922 3594 1916 3594 1921 3594 1916 3595 1922 3595 1918 3595 1918 3596 1923 3596 1917 3596 1923 3597 1919 3597 1917 3597 1923 3598 1918 3598 1922 3598 1924 3599 1919 3599 1923 3599 1920 3600 1926 3600 1921 3600 1921 3601 1928 3601 1922 3601 1928 3602 1921 3602 1926 3602 1922 3603 1929 3603 1923 3603 1929 3604 1922 3604 1928 3604 1931 3605 1923 3605 1929 3605 1923 3606 1931 3606 1924 3606 1931 3607 1925 3607 1924 3607 1931 3608 1927 3608 1925 3608 1926 3609 1932 3609 1928 3609 1930 3610 1927 3610 1931 3610 1935 3611 1928 3611 1932 3611 1928 3612 1935 3612 1929 3612 1929 3613 1937 3613 1931 3613 1937 3614 1929 3614 1935 3614 1931 3615 1939 3615 1930 3615 1939 3616 1933 3616 1930 3616 1939 3617 1931 3617 1937 3617 1932 3618 1934 3618 1935 3618 1910 3619 1933 3619 1939 3619 1935 3620 1936 3620 1937 3620 1935 3621 1891 3621 1936 3621 1935 3622 1934 3622 1891 3622 1937 3623 1936 3623 1938 3623 1937 3624 1938 3624 1939 3624 1939 3625 1941 3625 1910 3625 1941 3626 1942 3626 1910 3626 1939 3627 1938 3627 1941 3627 1940 3628 1942 3628 1941 3628 1954 3629 1950 3629 1949 3629 1954 3630 1951 3630 1950 3630 1954 3631 1952 3631 1951 3631 1954 3632 1953 3632 1952 3632 1954 3633 1955 3633 1953 3633 1899 3634 1956 3634 1955 3634 1980 3635 1982 3635 1983 3635 1980 3636 1983 3636 1984 3636 1985 3637 1980 3637 1984 3637 1905 3638 1989 3638 1549 3638 1544 3639 1549 3639 1989 3639 1989 3640 2009 3640 1544 3640 1544 3641 1990 3641 1543 3641 1990 3642 1544 3642 2009 3642 2009 3643 2014 3643 1990 3643 1991 3644 1501 3644 1512 3644 1992 3645 1991 3645 1512 3645 1993 3646 1992 3646 1512 3646 1993 3647 1512 3647 1994 3647 1995 3648 1993 3648 1994 3648 1996 3649 1995 3649 1994 3649 1997 3650 1996 3650 1994 3650 1970 3651 1997 3651 1994 3651 1998 3652 1997 3652 1970 3652 1877 3653 1999 3653 1875 3653 2000 3654 1876 3654 1875 3654 2000 3655 1875 3655 1999 3655 2000 3656 1999 3656 2001 3656 1876 3657 1872 3657 1874 3657 1872 3658 1876 3658 2000 3658 1908 3659 1911 3659 1872 3659 2001 3660 2002 3660 2000 3660 2000 3661 2003 3661 1872 3661 2003 3662 2000 3662 2002 3662 2004 3663 1872 3663 2003 3663 1872 3664 2004 3664 1908 3664 1905 3665 1908 3665 2004 3665 2002 3666 2005 3666 2003 3666 2006 3667 2003 3667 2005 3667 2003 3668 2006 3668 2004 3668 2005 3669 2007 3669 2006 3669 2008 3670 1989 3670 1905 3670 2004 3671 2008 3671 1905 3671 2008 3672 2004 3672 2006 3672 2009 3673 1989 3673 2008 3673 2006 3674 2010 3674 2008 3674 2006 3675 2007 3675 2011 3675 2010 3676 2006 3676 2011 3676 2011 3677 2012 3677 2010 3677 2013 3678 2008 3678 2010 3678 2008 3679 2013 3679 2009 3679 2014 3680 2009 3680 2013 3680 2015 3681 2010 3681 2012 3681 2010 3682 2015 3682 2013 3682 2012 3683 2016 3683 2015 3683 2013 3684 2017 3684 2014 3684 2017 3685 2013 3685 2015 3685 2015 3686 2016 3686 2018 3686 1973 3687 2012 3687 2019 3687 2012 3688 1973 3688 1985 3688 2012 3689 1985 3689 1984 3689 2012 3690 1984 3690 2020 3690 2016 3691 2012 3691 2020 3691 2021 3692 1982 3692 2022 3692 1981 3693 2022 3693 1982 3693 2021 3694 2023 3694 1982 3694 1983 3695 1982 3695 2023 3695 2023 3696 2020 3696 1983 3696 1984 3697 1983 3697 2020 3697 2024 3698 2025 3698 1963 3698 1964 3699 1963 3699 2025 3699 2025 3700 2026 3700 1964 3700 1965 3701 1964 3701 2026 3701 2026 3702 2027 3702 1965 3702 1966 3703 1965 3703 2027 3703 2027 3704 2028 3704 1966 3704 1967 3705 1966 3705 2028 3705 2028 3706 2029 3706 1967 3706 1968 3707 1967 3707 2029 3707 2029 3708 2030 3708 1968 3708 1969 3709 1968 3709 2030 3709 2030 3710 1998 3710 1969 3710 1970 3711 1969 3711 1998 3711 1998 3712 2030 3712 1997 3712 2031 3713 1997 3713 2030 3713 2031 3714 2032 3714 1995 3714 2031 3715 1995 3715 1996 3715 1997 3716 2031 3716 1996 3716 2033 3717 2032 3717 2031 3717 2030 3718 2029 3718 2031 3718 2031 3719 2029 3719 2028 3719 2034 3720 2031 3720 2028 3720 2034 3721 2035 3721 2033 3721 2031 3722 2034 3722 2033 3722 2036 3723 2035 3723 2034 3723 2028 3724 2027 3724 2034 3724 2034 3725 2027 3725 2026 3725 2037 3726 2034 3726 2026 3726 2037 3727 2038 3727 2036 3727 2034 3728 2037 3728 2036 3728 2039 3729 2038 3729 2037 3729 2026 3730 2025 3730 2037 3730 2037 3731 2042 3731 2039 3731 2037 3732 2025 3732 2024 3732 2037 3733 2024 3733 2040 3733 2037 3734 2040 3734 2041 3734 2042 3735 2037 3735 2041 3735 2039 3736 2042 3736 2043 3736 2044 3737 2039 3737 2043 3737 1871 3738 2045 3738 2044 3738 2039 3739 2044 3739 2045 3739 2045 3740 2046 3740 2039 3740 2038 3741 2039 3741 2046 3741 2046 3742 2047 3742 2038 3742 2036 3743 2038 3743 2047 3743 2047 3744 2048 3744 2036 3744 2035 3745 2036 3745 2048 3745 2048 3746 2049 3746 2035 3746 2033 3747 2035 3747 2049 3747 2049 3748 2050 3748 2033 3748 2032 3749 2033 3749 2050 3749 2050 3750 1993 3750 2032 3750 1995 3751 2032 3751 1993 3751 1870 3752 2046 3752 2045 3752 1871 3753 1870 3753 2045 3753 2051 3754 2049 3754 2048 3754 2051 3755 2048 3755 2047 3755 2046 3756 2051 3756 2047 3756 2051 3757 2046 3757 1870 3757 2052 3758 1992 3758 1993 3758 2052 3759 1993 3759 2050 3759 2052 3760 2050 3760 2049 3760 2052 3761 2049 3761 2051 3761 1870 3762 1869 3762 2051 3762 1991 3763 1992 3763 2052 3763 2051 3764 1869 3764 1484 3764 1483 3765 2051 3765 1484 3765 2051 3766 1483 3766 2052 3766 1482 3767 1501 3767 1991 3767 2052 3768 1482 3768 1991 3768 1482 3769 2052 3769 1483 3769 1502 3770 1501 3770 1482 3770 2053 3771 1855 3771 1862 3771 1855 3772 1854 3772 1867 3772 1854 3773 1853 3773 1866 3773 1851 3774 1850 3774 1903 3774 2024 3775 1962 3775 2054 3775 1963 3776 1962 3776 2024 3776 2044 3777 2043 3777 2053 3777 2055 3778 2053 3778 2043 3778 2043 3779 2042 3779 2055 3779 2056 3780 2055 3780 2042 3780 2042 3781 2041 3781 2056 3781 2057 3782 2056 3782 2041 3782 2041 3783 2040 3783 2057 3783 2058 3784 2057 3784 2040 3784 2040 3785 2024 3785 2058 3785 2054 3786 2058 3786 2024 3786 2053 3787 1862 3787 2044 3787 1871 3788 2044 3788 1862 3788 1863 3789 1870 3789 1871 3789 2059 3790 2060 3790 2061 3790 2007 3791 2062 3791 2063 3791 2011 3792 2007 3792 2063 3792 2064 3793 2059 3793 2061 3793 2064 3794 2061 3794 2065 3794 2062 3795 2064 3795 2065 3795 2064 3796 2062 3796 2007 3796 2066 3797 2059 3797 2064 3797 2066 3798 1988 3798 2059 3798 2007 3799 2005 3799 2064 3799 2064 3800 2067 3800 2066 3800 2067 3801 2064 3801 2005 3801 1987 3802 1988 3802 2066 3802 2066 3803 2068 3803 1987 3803 2068 3804 2066 3804 2067 3804 2005 3805 2002 3805 2067 3805 1986 3806 1987 3806 2068 3806 2067 3807 2069 3807 2068 3807 2069 3808 2067 3808 2002 3808 2002 3809 2001 3809 2069 3809 2070 3810 2068 3810 2069 3810 1979 3811 1978 3811 2060 3811 2061 3812 2060 3812 1978 3812 1978 3813 1977 3813 2061 3813 2065 3814 2061 3814 1977 3814 1977 3815 1976 3815 2065 3815 2062 3816 2065 3816 1976 3816 1976 3817 1975 3817 2062 3817 2063 3818 2062 3818 1975 3818 1974 3819 2011 3819 2063 3819 1975 3820 1974 3820 2063 3820 2012 3821 2011 3821 1974 3821 1974 3822 1972 3822 2012 3822 1972 3823 1971 3823 2012 3823 2012 3824 1971 3824 2019 3824 1799 3825 1994 3825 1512 3825 1799 3826 1512 3826 1602 3826 2089 3827 2071 3827 2143 3827 2143 3828 2071 3828 2148 3828 2148 3829 2071 3829 2078 3829 2120 3830 2148 3830 2078 3830 2122 3831 2120 3831 2078 3831 2122 3832 2078 3832 2080 3832 2123 3833 2122 3833 2080 3833 2123 3834 2080 3834 2082 3834 2125 3835 2123 3835 2082 3835 2125 3836 2082 3836 2084 3836 2128 3837 2125 3837 2084 3837 2128 3838 2084 3838 2085 3838 2130 3839 2128 3839 2085 3839 2130 3840 2085 3840 2086 3840 2130 3841 2086 3841 2131 3841 2133 3842 2131 3842 2086 3842 2091 3843 2092 3843 2072 3843 2100 3844 2158 3844 2099 3844 2153 3845 2099 3845 2158 3845 2071 3846 2076 3846 2078 3846 2087 3847 2090 3847 2076 3847 2076 3848 2071 3848 2087 3848 2071 3849 2088 3849 2087 3849 2071 3850 2089 3850 2088 3850 2090 3851 2091 3851 2072 3851 2072 3852 2076 3852 2090 3852 2072 3853 2093 3853 2073 3853 2072 3854 2092 3854 2093 3854 2074 3855 2072 3855 2073 3855 2072 3856 2074 3856 2076 3856 2074 3857 2075 3857 2076 3857 2095 3858 2094 3858 2077 3858 2077 3859 2073 3859 2095 3859 2073 3860 2093 3860 2095 3860 2073 3861 2077 3861 2074 3861 2077 3862 2075 3862 2074 3862 2077 3863 2076 3863 2075 3863 2078 3864 2076 3864 2077 3864 2077 3865 2079 3865 2078 3865 2080 3866 2078 3866 2079 3866 2079 3867 2081 3867 2080 3867 2082 3868 2080 3868 2081 3868 2084 3869 2082 3869 2083 3869 2101 3870 2085 3870 2084 3870 2086 3871 2085 3871 2101 3871 2120 3872 2121 3872 1524 3872 1524 3873 2137 3873 2120 3873 2137 3874 2148 3874 2120 3874 2148 3875 2137 3875 2147 3875 2143 3876 2145 3876 2146 3876 2148 3877 2145 3877 2143 3877 2115 3878 2110 3878 2114 3878 2110 3879 2113 3879 2114 3879 2149 3880 2113 3880 2110 3880 2110 3881 2109 3881 2149 3881 2139 3882 2149 3882 2109 3882 2109 3883 2108 3883 2139 3883 2140 3884 2139 3884 2108 3884 2108 3885 2107 3885 2140 3885 2142 3886 2140 3886 2107 3886 2107 3887 2105 3887 2088 3887 2088 3888 2142 3888 2107 3888 2105 3889 2087 3889 2088 3889 2105 3890 2090 3890 2087 3890 2142 3891 2089 3891 2143 3891 2142 3892 2088 3892 2089 3892 2105 3893 2104 3893 2090 3893 2091 3894 2090 3894 2104 3894 2104 3895 2102 3895 2091 3895 2102 3896 2092 3896 2091 3896 2093 3897 2092 3897 2095 3897 2092 3898 2102 3898 2095 3898 2103 3899 2095 3899 2102 3899 2099 3900 2153 3900 2097 3900 2154 3901 2097 3901 2153 3901 2112 3902 2096 3902 2156 3902 2155 3903 2156 3903 2096 3903 2096 3904 2097 3904 2155 3904 2154 3905 2155 3905 2097 3905 2098 3906 2099 3906 2021 3906 2020 3907 2096 3907 2112 3907 2020 3908 2097 3908 2096 3908 2020 3909 2099 3909 2097 3909 2020 3910 2023 3910 2099 3910 2023 3911 2021 3911 2099 3911 2106 3912 2103 3912 2104 3912 2103 3913 2102 3913 2104 3913 2104 3914 2105 3914 2106 3914 2105 3915 2107 3915 2106 3915 2111 3916 2106 3916 2107 3916 2107 3917 2108 3917 2111 3917 2111 3918 2108 3918 2109 3918 2109 3919 2110 3919 2111 3919 2111 3920 2115 3920 2160 3920 2111 3921 2110 3921 2115 3921 2115 3922 2018 3922 2112 3922 2112 3923 2160 3923 2115 3923 2112 3924 2157 3924 2160 3924 2112 3925 2159 3925 2157 3925 2156 3926 2159 3926 2112 3926 2020 3927 2112 3927 2016 3927 2112 3928 2018 3928 2016 3928 2149 3929 2151 3929 2113 3929 2116 3930 2113 3930 2151 3930 2113 3931 2116 3931 2114 3931 2114 3932 2117 3932 2115 3932 2117 3933 2114 3933 2116 3933 2018 3934 2115 3934 2117 3934 2151 3935 2014 3935 2116 3935 2014 3936 2017 3936 2116 3936 2116 3937 2017 3937 2117 3937 2015 3938 2117 3938 2017 3938 2117 3939 2015 3939 2018 3939 1530 3940 2118 3940 1582 3940 1530 3941 2134 3941 2118 3941 1530 3942 1524 3942 2134 3942 2119 3943 1582 3943 2118 3943 2119 3944 2118 3944 2135 3944 2118 3945 2134 3945 2135 3945 2122 3946 2121 3946 2120 3946 2135 3947 2134 3947 2121 3947 2124 3948 2121 3948 2123 3948 2121 3949 2122 3949 2123 3949 2121 3950 2124 3950 2135 3950 2123 3951 2125 3951 2124 3951 2124 3952 2126 3952 2135 3952 2126 3953 2136 3953 2135 3953 2126 3954 2124 3954 2125 3954 2127 3955 2126 3955 2125 3955 2125 3956 2128 3956 2127 3956 2129 3957 2127 3957 2128 3957 2128 3958 2130 3958 2129 3958 2132 3959 2129 3959 2130 3959 2133 3960 2132 3960 2131 3960 2132 3961 2130 3961 2131 3961 2121 3962 2134 3962 1524 3962 1524 3963 2147 3963 2137 3963 2149 3964 2139 3964 2138 3964 2141 3965 2138 3965 2139 3965 2141 3966 1531 3966 2138 3966 2139 3967 2140 3967 2141 3967 1514 3968 1531 3968 2141 3968 2144 3969 2141 3969 2142 3969 2141 3970 2140 3970 2142 3970 2141 3971 2144 3971 1514 3971 1517 3972 1514 3972 2144 3972 2142 3973 2143 3973 2144 3973 2144 3974 2146 3974 1517 3974 2144 3975 2143 3975 2146 3975 1521 3976 1517 3976 2148 3976 1517 3977 2145 3977 2148 3977 1517 3978 2146 3978 2145 3978 1525 3979 1521 3979 2147 3979 1521 3980 2148 3980 2147 3980 1525 3981 2147 3981 1524 3981 1531 3982 1534 3982 2138 3982 2150 3983 2138 3983 1534 3983 2152 3984 2138 3984 2150 3984 2152 3985 2149 3985 2138 3985 2151 3986 2149 3986 2152 3986 1534 3987 1537 3987 2150 3987 1539 3988 2150 3988 1537 3988 2150 3989 1539 3989 2152 3989 2152 3990 1990 3990 2151 3990 1990 3991 2014 3991 2151 3991 1990 3992 2152 3992 1539 3992 1539 3993 1543 3993 1990 3993 2158 3994 2159 3994 2153 3994 2159 3995 2154 3995 2153 3995 2159 3996 2155 3996 2154 3996 2159 3997 2156 3997 2155 3997 2161 3998 2159 3998 2158 3998 2180 3999 2133 3999 2101 3999 2201 4000 2162 4000 2199 4000 2172 4001 2162 4001 2201 4001 2201 4002 2174 4002 2172 4002 2201 4003 2175 4003 2174 4003 2185 4004 2199 4004 2162 4004 2208 4005 2185 4005 2207 4005 2207 4006 2185 4006 2162 4006 2206 4007 2207 4007 2162 4007 2172 4008 2206 4008 2162 4008 2206 4009 2172 4009 2205 4009 2205 4010 2172 4010 2173 4010 2166 4011 2164 4011 2168 4011 2167 4012 2168 4012 2164 4012 2164 4013 2163 4013 2167 4013 2188 4014 2167 4014 2163 4014 2165 4015 2167 4015 2188 4015 2218 4016 2165 4016 2188 4016 2175 4017 2169 4017 2170 4017 2170 4018 2169 4018 2166 4018 2170 4019 2173 4019 2171 4019 2170 4020 2204 4020 2173 4020 2204 4021 2205 4021 2173 4021 2204 4022 2170 4022 2166 4022 2166 4023 2217 4023 2204 4023 2217 4024 2165 4024 2218 4024 2217 4025 2167 4025 2165 4025 2217 4026 2166 4026 2168 4026 2168 4027 2167 4027 2217 4027 2174 4028 2175 4028 2171 4028 2175 4029 2170 4029 2171 4029 2171 4030 2173 4030 2174 4030 2173 4031 2172 4031 2174 4031 2221 4032 2200 4032 2177 4032 2177 4033 2176 4033 2221 4033 2177 4034 2179 4034 2176 4034 2179 4035 2180 4035 2176 4035 2119 4036 2194 4036 1582 4036 2135 4037 2136 4037 2119 4037 2198 4038 2194 4038 2119 4038 2178 4039 2119 4039 2136 4039 2119 4040 2178 4040 2198 4040 2178 4041 2200 4041 2198 4041 2178 4042 2177 4042 2200 4042 2136 4043 2181 4043 2178 4043 2179 4044 2178 4044 2181 4044 2178 4045 2179 4045 2177 4045 2181 4046 2182 4046 2179 4046 2180 4047 2179 4047 2182 4047 2127 4048 2136 4048 2126 4048 2127 4049 2129 4049 2181 4049 2183 4050 2181 4050 2129 4050 2129 4051 2132 4051 2183 4051 2132 4052 2182 4052 2183 4052 2132 4053 2133 4053 2182 4053 2180 4054 2182 4054 2133 4054 2136 4055 2127 4055 2181 4055 2182 4056 2181 4056 2183 4056 2215 4057 2184 4057 2216 4057 2199 4058 2185 4058 2197 4058 2186 4059 2197 4059 2185 4059 2186 4060 2196 4060 2197 4060 2186 4061 2185 4061 2209 4061 2185 4062 2208 4062 2209 4062 2209 4063 2210 4063 2186 4063 2195 4064 2196 4064 2186 4064 2187 4065 2186 4065 2211 4065 2186 4066 2210 4066 2211 4066 2186 4067 2187 4067 2195 4067 2187 4068 2193 4068 2195 4068 2211 4069 2212 4069 2187 4069 2192 4070 2193 4070 2187 4070 2187 4071 2213 4071 1598 4071 2187 4072 2212 4072 2213 4072 2187 4073 1598 4073 2192 4073 2218 4074 2188 4074 2219 4074 2220 4075 2188 4075 2189 4075 2214 4076 2190 4076 2215 4076 1582 4077 2194 4077 1598 4077 2194 4078 2191 4078 1598 4078 2194 4079 2192 4079 2191 4079 2194 4080 2193 4080 2192 4080 2195 4081 2193 4081 2194 4081 2194 4082 2198 4082 2195 4082 2198 4083 2196 4083 2195 4083 2198 4084 2197 4084 2196 4084 2199 4085 2197 4085 2198 4085 2198 4086 2200 4086 2199 4086 2201 4087 2199 4087 2200 4087 2200 4088 2221 4088 2201 4088 2221 4089 2202 4089 2201 4089 2221 4090 2203 4090 2202 4090 1636 4091 2218 4091 2219 4091 1602 4092 1669 4092 1634 4092 1669 4093 1602 4093 2222 4093 1963 4094 1960 4094 1959 4094 1963 4095 1959 4095 1961 4095 1957 4096 1960 4096 1963 4096 1957 4097 1970 4097 2223 4097 1970 4098 2224 4098 2223 4098 2225 4099 2223 4099 2224 4099 1799 4100 1797 4100 2225 4100 2224 4101 1799 4101 2225 4101 1799 4102 1602 4102 1634 4102 2218 4103 1636 4103 2227 4103 2217 4104 2218 4104 2227 4104 2226 4105 1584 4105 1583 4105 2228 4106 1599 4106 2226 4106 1583 4107 2228 4107 2226 4107 1599 4108 2228 4108 2229 4108 1599 4109 2229 4109 2230 4109 1599 4110 2230 4110 2231 4110 1599 4111 2231 4111 2232 4111 1599 4112 2232 4112 2233 4112 1667 4113 1599 4113 2233 4113 2233 4114 2234 4114 1667 4114 1667 4115 2234 4115 2235 4115 1667 4116 2235 4116 2236 4116 1667 4117 2236 4117 2227 4117 1636 4118 1667 4118 2227 4118 2213 4119 1583 4119 1598 4119 2228 4120 1583 4120 2213 4120 2213 4121 2212 4121 2228 4121 2228 4122 2212 4122 2211 4122 2229 4123 2228 4123 2211 4123 2211 4124 2210 4124 2229 4124 2230 4125 2229 4125 2210 4125 2210 4126 2209 4126 2230 4126 2231 4127 2230 4127 2209 4127 2208 4128 2231 4128 2209 4128 2232 4129 2231 4129 2208 4129 2232 4130 2208 4130 2207 4130 2233 4131 2232 4131 2207 4131 2207 4132 2206 4132 2233 4132 2234 4133 2233 4133 2206 4133 2234 4134 2206 4134 2205 4134 2234 4135 2205 4135 2235 4135 2204 4136 2235 4136 2205 4136 2236 4137 2235 4137 2204 4137 2236 4138 2204 4138 2217 4138 2227 4139 2236 4139 2217 4139 1600 4140 1599 4140 1667 4140 1598 4141 1583 4141 1528 4141 1957 4142 1958 4142 1945 4142 1599 4143 1584 4143 2226 4143 1962 4144 1963 4144 1961 4144 1957 4145 1963 4145 1964 4145 1957 4146 1964 4146 1965 4146 1957 4147 1965 4147 1966 4147 1957 4148 1966 4148 1967 4148 1957 4149 1967 4149 1968 4149 1957 4150 1968 4150 1969 4150 1957 4151 1969 4151 1970 4151 1971 4152 1972 4152 1973 4152 1973 4153 1972 4153 1974 4153 1973 4154 1974 4154 1975 4154 1973 4155 1975 4155 1976 4155 1973 4156 1976 4156 1977 4156 1973 4157 1977 4157 1978 4157 1973 4158 1978 4158 1979 4158 1973 4159 1979 4159 2237 4159 1973 4160 2237 4160 2238 4160 1973 4161 2238 4161 2239 4161 1973 4162 2239 4162 2240 4162 2244 4163 2242 4163 2243 4163 2244 4164 2219 4164 2220 4164 2242 4165 2244 4165 2220 4165 2244 4166 1636 4166 2219 4166 2248 4167 2249 4167 2160 4167 2250 4168 2249 4168 2248 4168 2251 4169 2252 4169 2250 4169 2214 4170 2215 4170 2216 4170 2214 4171 2253 4171 2190 4171 2253 4172 2255 4172 2254 4172 2255 4173 2220 4173 2189 4173 2220 4174 2219 4174 2188 4174 2157 4175 2159 4175 2161 4175 2160 4176 2157 4176 2247 4176 1973 4177 2241 4177 1985 4177 2258 4178 2257 4178 2252 4178 2242 4179 2259 4179 2256 4179 2257 4180 2256 4180 2259 4180 2252 4181 2261 4181 2250 4181 2260 4182 2250 4182 2261 4182 2261 4183 2214 4183 2260 4183 2216 4184 2260 4184 2214 4184 2262 4185 2214 4185 2261 4185 2261 4186 2252 4186 2257 4186 2262 4187 2261 4187 2257 4187 2253 4188 2214 4188 2262 4188 2257 4189 2259 4189 2262 4189 2262 4190 2259 4190 2253 4190 2255 4191 2253 4191 2259 4191 2259 4192 2242 4192 2255 4192 2220 4193 2255 4193 2242 4193 1971 4194 1973 4194 2019 4194 2249 4195 2111 4195 2160 4195 2101 4196 2264 4196 2263 4196 2264 4197 2265 4197 2263 4197 2265 4198 2266 4198 2263 4198 2249 4199 2263 4199 2111 4199 2106 4200 2094 4200 2095 4200 2111 4201 2266 4201 2106 4201 2111 4202 2263 4202 2266 4202 2106 4203 2095 4203 2103 4203 2224 4204 1970 4204 1994 4204 2083 4205 2101 4205 2084 4205 2081 4206 2083 4206 2082 4206 2079 4207 2077 4207 2094 4207 2094 4208 2267 4208 2079 4208 2081 4209 2079 4209 2267 4209 2265 4210 2083 4210 2081 4210 2267 4211 2265 4211 2081 4211 2083 4212 2265 4212 2264 4212 2101 4213 2083 4213 2264 4213 2265 4214 2267 4214 2266 4214 2133 4215 2086 4215 2101 4215 2106 4216 2266 4216 2267 4216 2106 4217 2267 4217 2094 4217 2224 4218 1994 4218 1799 4218 2201 4219 2298 4219 2175 4219 2298 4220 2270 4220 2175 4220 2184 4221 2270 4221 2298 4221 2215 4222 2270 4222 2184 4222 2166 4223 2269 4223 2164 4223 2169 4224 2269 4224 2166 4224 2269 4225 2163 4225 2164 4225 2268 4226 2163 4226 2269 4226 2299 4227 2268 4227 2269 4227 2190 4228 2254 4228 2269 4228 2254 4229 2299 4229 2269 4229 2223 4230 2225 4230 2285 4230 2225 4231 2286 4231 2285 4231 2225 4232 1797 4232 2286 4232 2223 4233 2283 4233 2282 4233 2223 4234 2281 4234 2283 4234 2223 4235 2280 4235 2281 4235 2223 4236 2297 4236 2280 4236 2223 4237 2296 4237 2297 4237 2223 4238 2294 4238 2296 4238 2223 4239 2292 4239 2294 4239 2223 4240 2289 4240 2292 4240 2223 4241 2285 4241 2289 4241 2163 4242 2268 4242 2188 4242 2268 4243 2299 4243 2188 4243 2189 4244 2188 4244 2299 4244 2269 4245 2215 4245 2190 4245 2269 4246 2270 4246 2215 4246 2269 4247 2169 4247 2270 4247 2175 4248 2270 4248 2169 4248 2300 4249 2271 4249 1794 4249 2277 4250 1794 4250 2271 4250 2271 4251 2272 4251 2277 4251 2279 4252 2277 4252 2272 4252 2272 4253 2273 4253 2279 4253 2293 4254 2279 4254 2273 4254 2273 4255 2284 4255 2293 4255 1796 4256 1629 4256 2302 4256 1629 4257 2304 4257 2302 4257 2274 4258 2304 4258 1623 4258 2304 4259 1629 4259 1623 4259 2274 4260 2307 4260 2304 4260 2287 4261 2306 4261 2308 4261 2275 4262 2307 4262 2274 4262 2275 4263 2308 4263 2307 4263 2275 4264 2287 4264 2308 4264 1623 4265 1658 4265 2274 4265 2276 4266 2274 4266 1798 4266 2274 4267 1658 4267 1798 4267 2274 4268 2276 4268 2275 4268 2275 4269 2278 4269 2287 4269 2278 4270 2288 4270 2287 4270 2278 4271 2275 4271 2276 4271 1798 4272 1795 4272 2276 4272 2276 4273 1794 4273 2277 4273 2276 4274 1795 4274 1794 4274 2276 4275 2277 4275 2278 4275 2291 4276 2288 4276 2278 4276 2278 4277 2277 4277 2279 4277 2278 4278 2279 4278 2291 4278 2291 4279 2279 4279 2293 4279 2293 4280 2284 4280 2295 4280 2306 4281 2285 4281 2305 4281 2285 4282 2303 4282 2305 4282 2285 4283 2286 4283 2303 4283 2286 4284 1797 4284 2303 4284 2285 4285 2306 4285 2287 4285 2290 4286 2287 4286 2288 4286 2287 4287 2290 4287 2285 4287 2289 4288 2285 4288 2290 4288 2288 4289 2291 4289 2290 4289 2292 4290 2289 4290 2290 4290 2292 4291 2290 4291 2291 4291 2291 4292 2293 4292 2292 4292 2294 4293 2292 4293 2293 4293 2293 4294 2295 4294 2294 4294 2296 4295 2294 4295 2295 4295 2297 4296 2296 4296 2295 4296 1657 4297 1766 4297 1143 4297 1142 4298 1766 4298 1765 4298 1765 4299 1764 4299 1141 4299 1761 4300 1140 4300 1764 4300 1139 4301 1761 4301 1762 4301 1762 4302 1661 4302 1138 4302 2298 4303 2202 4303 2203 4303 2202 4304 2298 4304 2201 4304 1598 4305 2191 4305 2192 4305 2255 4306 2189 4306 2299 4306 2299 4307 2254 4307 2255 4307 2253 4308 2254 4308 2190 4308 1629 4309 1796 4309 1635 4309 1796 4310 2302 4310 1797 4310 2303 4311 1797 4311 2302 4311 2302 4312 2304 4312 2303 4312 2305 4313 2303 4313 2304 4313 2306 4314 2305 4314 2307 4314 2305 4315 2304 4315 2307 4315 2308 4316 2306 4316 2307 4316 1428 4317 2313 4317 1144 4317 1144 4318 2313 4318 2314 4318 1144 4319 2314 4319 2315 4319 1144 4320 2315 4320 2316 4320 1144 4321 2316 4321 2317 4321 1144 4322 2317 4322 2318 4322 1144 4323 2318 4323 2319 4323 1144 4324 2319 4324 2320 4324 1143 4325 1144 4325 2320 4325 1143 4326 2320 4326 2321 4326 1143 4327 2321 4327 2322 4327 1143 4328 2322 4328 2323 4328 1143 4329 2323 4329 2324 4329 1143 4330 2324 4330 2325 4330 1143 4331 2325 4331 2300 4331 1143 4332 2300 4332 1794 4332 1657 4333 1143 4333 1794 4333 2312 4334 1146 4334 1654 4334 1661 4335 1654 4335 1146 4335 1146 4336 1138 4336 1661 4336 1139 4337 1762 4337 1138 4337 1139 4338 1140 4338 1761 4338 1140 4339 1141 4339 1764 4339 1141 4340 1142 4340 1765 4340 1766 4341 1142 4341 1143 4341 2326 4342 2327 4342 2328 4342 2326 4343 2328 4343 2329 4343 2330 4344 2326 4344 2329 4344 2331 4345 2327 4345 2326 4345 2332 4346 2333 4346 2331 4346 2326 4347 2332 4347 2331 4347 2334 4348 2333 4348 2332 4348 2332 4349 2310 4349 2334 4349 2335 4350 2334 4350 2310 4350 2336 4351 2335 4351 2310 4351 2337 4352 2336 4352 2310 4352 2310 4353 2309 4353 2337 4353 2338 4354 2309 4354 2310 4354 2339 4355 2340 4355 2338 4355 2310 4356 2339 4356 2338 4356 2340 4357 2341 4357 2338 4357 2342 4358 2343 4358 2344 4358 2343 4359 2345 4359 2344 4359 2345 4360 2346 4360 2344 4360 2344 4361 2346 4361 2347 4361 2348 4362 2309 4362 2338 4362 2338 4363 2341 4363 2342 4363 2338 4364 2342 4364 2344 4364 2348 4365 2338 4365 2344 4365 2344 4366 2347 4366 2349 4366 2348 4367 2344 4367 2350 4367 2284 4368 2351 4368 2352 4368 2283 4369 2352 4369 2351 4369 2282 4370 2283 4370 2351 4370 2351 4371 2353 4371 2282 4371 2354 4372 2282 4372 2353 4372 2353 4373 2330 4373 2354 4373 2354 4374 2330 4374 2329 4374 2328 4375 2354 4375 2329 4375 2295 4376 2352 4376 2283 4376 2352 4377 2295 4377 2284 4377 2283 4378 2281 4378 2295 4378 2281 4379 2280 4379 2295 4379 2280 4380 2297 4380 2295 4380 2355 4381 2330 4381 2353 4381 2355 4382 2353 4382 2351 4382 2351 4383 2284 4383 2273 4383 2355 4384 2351 4384 2273 4384 2356 4385 2330 4385 2355 4385 2355 4386 2357 4386 2356 4386 2357 4387 2355 4387 2273 4387 2273 4388 2272 4388 2357 4388 2358 4389 2356 4389 2357 4389 2272 4390 2271 4390 2357 4390 2357 4391 2359 4391 2358 4391 2359 4392 2357 4392 2271 4392 2359 4393 2325 4393 2358 4393 2325 4394 2359 4394 2271 4394 2322 4395 2358 4395 2325 4395 2271 4396 2300 4396 2325 4396 2325 4397 2324 4397 2323 4397 2325 4398 2323 4398 2322 4398 2356 4399 2310 4399 2332 4399 2356 4400 2332 4400 2326 4400 2330 4401 2356 4401 2326 4401 2360 4402 2310 4402 2356 4402 2356 4403 2358 4403 2360 4403 2361 4404 2360 4404 2358 4404 2358 4405 2322 4405 2361 4405 2361 4406 2322 4406 2321 4406 2361 4407 2321 4407 2320 4407 1130 4408 1407 4408 1428 4408 2365 4409 2366 4409 2363 4409 2364 4410 2365 4410 2363 4410 2367 4411 2368 4411 2366 4411 2365 4412 2367 4412 2366 4412 2368 4413 2367 4413 2369 4413 2370 4414 2368 4414 2369 4414 2371 4415 2372 4415 2370 4415 2369 4416 2371 4416 2370 4416 2373 4417 2372 4417 2371 4417 2346 4418 2373 4418 2347 4418 2374 4419 2347 4419 2373 4419 2371 4420 2374 4420 2373 4420 2347 4421 2374 4421 2349 4421 2375 4422 2318 4422 2317 4422 2375 4423 2317 4423 2316 4423 2375 4424 2316 4424 2315 4424 2376 4425 2375 4425 2315 4425 2376 4426 2342 4426 2341 4426 2376 4427 2341 4427 2340 4427 2376 4428 2340 4428 2339 4428 2376 4429 2339 4429 2375 4429 2315 4430 2314 4430 2376 4430 2343 4431 2342 4431 2376 4431 2376 4432 2314 4432 2313 4432 2376 4433 2313 4433 1428 4433 2376 4434 1428 4434 2377 4434 2377 4435 2346 4435 2345 4435 2377 4436 2345 4436 2343 4436 2376 4437 2377 4437 2343 4437 2373 4438 2370 4438 2372 4438 2378 4439 2368 4439 2373 4439 2373 4440 2379 4440 2378 4440 2379 4441 2373 4441 2346 4441 2380 4442 2378 4442 2379 4442 2381 4443 2380 4443 2379 4443 2379 4444 2382 4444 2381 4444 2382 4445 2379 4445 2377 4445 2383 4446 2381 4446 2382 4446 2382 4447 2377 4447 1428 4447 2384 4448 2383 4448 2382 4448 2382 4449 1407 4449 2384 4449 1407 4450 2382 4450 1428 4450 1408 4451 2384 4451 1407 4451 2366 4452 2385 4452 2363 4452 2385 4453 2366 4453 2368 4453 2368 4454 2378 4454 2385 4454 1404 4455 2363 4455 2385 4455 2363 4456 1404 4456 2364 4456 2378 4457 2380 4457 2385 4457 1410 4458 2364 4458 1404 4458 2380 4459 2381 4459 2385 4459 1406 4460 2385 4460 2381 4460 2385 4461 1406 4461 1404 4461 2381 4462 2383 4462 1406 4462 2383 4463 2384 4463 1406 4463 1405 4464 1404 4464 1406 4464 2384 4465 1408 4465 1406 4465 1282 4466 2364 4466 1410 4466 2386 4467 2365 4467 2364 4467 2386 4468 2364 4468 1282 4468 2367 4469 2365 4469 2386 4469 1282 4470 2362 4470 2386 4470 2310 4471 2360 4471 2339 4471 2375 4472 2339 4472 2360 4472 2360 4473 2361 4473 2375 4473 2318 4474 2375 4474 2361 4474 2319 4475 2318 4475 2361 4475 2361 4476 2320 4476 2319 4476 2223 4477 2282 4477 2354 4477 2223 4478 2354 4478 2328 4478 2223 4479 2328 4479 2327 4479 2223 4480 2327 4480 2331 4480 2223 4481 2331 4481 2333 4481 2223 4482 2333 4482 2334 4482 2223 4483 2334 4483 2335 4483 2223 4484 2335 4484 2336 4484 2223 4485 2336 4485 2337 4485 2309 4486 2223 4486 2337 4486 2346 4487 2377 4487 2379 4487 2392 4488 2391 4488 2301 4488 2395 4489 1383 4489 1384 4489 2395 4490 1384 4490 1382 4490 2395 4491 1382 4491 1381 4491 2395 4492 1381 4492 1380 4492 2395 4493 1256 4493 1383 4493 1227 4494 2399 4494 2400 4494 1227 4495 2400 4495 2401 4495 1227 4496 2401 4496 2402 4496 2403 4497 1227 4497 2402 4497 1229 4498 2410 4498 2409 4498 1228 4499 1229 4499 2409 4499 2411 4500 2410 4500 1229 4500 1229 4501 1230 4501 2411 4501 2412 4502 2411 4502 1230 4502 1230 4503 1231 4503 2412 4503 2413 4504 2412 4504 1231 4504 1231 4505 1232 4505 2413 4505 2413 4506 1232 4506 1233 4506 2414 4507 2413 4507 1233 4507 2415 4508 2414 4508 1233 4508 2395 4509 2415 4509 1233 4509 1256 4510 2395 4510 1233 4510 2409 4511 2416 4511 2408 4511 2407 4512 2408 4512 2416 4512 2416 4513 2417 4513 2407 4513 2406 4514 2407 4514 2417 4514 2417 4515 2418 4515 2406 4515 2405 4516 2406 4516 2418 4516 2419 4517 2404 4517 2405 4517 2418 4518 2419 4518 2405 4518 2396 4519 2404 4519 2419 4519 2419 4520 2420 4520 2396 4520 2397 4521 2396 4521 2420 4521 2420 4522 2421 4522 2397 4522 2398 4523 2397 4523 2421 4523 2422 4524 2399 4524 2398 4524 2421 4525 2422 4525 2398 4525 2400 4526 2399 4526 2422 4526 2422 4527 2423 4527 2400 4527 2401 4528 2400 4528 2423 4528 2423 4529 2424 4529 2401 4529 2402 4530 2401 4530 2424 4530 2424 4531 2403 4531 2402 4531 2391 4532 2425 4532 2426 4532 2428 4533 2426 4533 2427 4533 2429 4534 2428 4534 2430 4534 2429 4535 2431 4535 2432 4535 2433 4536 2429 4536 2432 4536 2432 4537 2434 4537 2433 4537 2433 4538 2434 4538 2435 4538 2436 4539 2433 4539 2435 4539 2436 4540 2435 4540 2437 4540 2438 4541 2436 4541 2437 4541 2437 4542 2439 4542 2438 4542 2440 4543 2438 4543 2439 4543 2439 4544 2441 4544 2440 4544 2456 4545 2454 4545 2455 4545 2455 4546 2454 4546 2457 4546 2455 4547 2457 4547 2390 4547 2455 4548 2390 4548 2453 4548 2455 4549 2453 4549 2458 4549 2458 4550 2459 4550 2455 4550 2455 4551 2459 4551 2460 4551 2455 4552 2460 4552 2461 4552 2455 4553 2461 4553 2462 4553 2455 4554 2462 4554 2463 4554 2455 4555 2413 4555 2414 4555 2455 4556 2414 4556 2415 4556 2455 4557 2415 4557 2395 4557 2455 4558 2395 4558 2393 4558 2455 4559 2393 4559 2464 4559 2455 4560 2464 4560 2456 4560 2463 4561 2465 4561 2455 4561 2455 4562 2465 4562 2412 4562 2412 4563 2413 4563 2455 4563 2465 4564 2466 4564 2412 4564 2411 4565 2412 4565 2466 4565 2466 4566 2467 4566 2411 4566 2410 4567 2411 4567 2467 4567 2467 4568 2468 4568 2410 4568 2410 4569 2468 4569 2403 4569 2409 4570 2410 4570 2403 4570 2403 4571 2424 4571 2409 4571 2416 4572 2409 4572 2424 4572 2424 4573 2423 4573 2416 4573 2417 4574 2416 4574 2423 4574 2423 4575 2422 4575 2417 4575 2418 4576 2417 4576 2422 4576 2422 4577 2421 4577 2418 4577 2419 4578 2418 4578 2421 4578 2421 4579 2420 4579 2419 4579 2470 4580 2387 4580 2469 4580 2469 4581 2387 4581 2471 4581 2472 4582 2473 4582 2474 4582 2470 4583 2469 4583 2475 4583 2470 4584 2475 4584 2472 4584 2470 4585 2472 4585 2474 4585 2452 4586 2470 4586 2474 4586 2451 4587 2452 4587 2474 4587 2450 4588 2451 4588 2474 4588 2449 4589 2450 4589 2474 4589 2474 4590 2473 4590 2301 4590 2474 4591 2301 4591 2391 4591 2474 4592 2391 4592 2426 4592 2474 4593 2426 4593 2428 4593 2474 4594 2428 4594 2429 4594 2448 4595 2449 4595 2474 4595 2433 4596 2448 4596 2474 4596 2429 4597 2433 4597 2474 4597 2447 4598 2448 4598 2433 4598 2433 4599 2436 4599 2447 4599 2446 4600 2447 4600 2436 4600 2436 4601 2438 4601 2446 4601 2445 4602 2446 4602 2438 4602 2438 4603 2440 4603 2445 4603 2444 4604 2445 4604 2440 4604 2440 4605 2442 4605 2444 4605 2443 4606 2444 4606 2442 4606 2473 4607 2464 4607 2393 4607 2301 4608 2473 4608 2393 4608 2456 4609 2464 4609 2473 4609 2473 4610 2472 4610 2456 4610 2454 4611 2456 4611 2472 4611 2472 4612 2475 4612 2454 4612 2457 4613 2454 4613 2475 4613 2475 4614 2469 4614 2457 4614 2476 4615 2457 4615 2469 4615 2469 4616 2471 4616 2476 4616 2477 4617 2476 4617 2471 4617 2478 4618 2479 4618 2477 4618 2471 4619 2478 4619 2477 4619 2480 4620 2479 4620 2478 4620 2481 4621 2482 4621 2480 4621 2478 4622 2481 4622 2480 4622 2481 4623 2389 4623 2482 4623 2390 4624 2482 4624 2389 4624 1302 4625 2485 4625 2484 4625 2487 4626 2486 4626 2485 4626 2488 4627 2487 4627 2485 4627 2489 4628 2488 4628 2485 4628 1302 4629 2459 4629 2485 4629 2490 4630 2489 4630 2485 4630 2491 4631 2490 4631 2485 4631 2492 4632 2491 4632 2485 4632 2493 4633 2492 4633 2485 4633 2458 4634 2493 4634 2485 4634 2459 4635 2458 4635 2485 4635 2494 4636 2493 4636 2458 4636 2495 4637 2496 4637 2494 4637 2458 4638 2495 4638 2494 4638 2470 4639 2452 4639 2497 4639 1986 4640 2496 4640 2497 4640 1987 4641 1986 4641 2497 4641 2452 4642 2483 4642 2497 4642 2403 4643 2468 4643 1227 4643 1216 4644 1227 4644 2468 4644 2468 4645 2467 4645 1216 4645 1216 4646 2467 4646 1167 4646 2467 4647 2466 4647 1167 4647 1166 4648 1167 4648 2466 4648 2466 4649 2465 4649 1166 4649 2465 4650 2463 4650 1166 4650 1165 4651 1166 4651 2463 4651 2463 4652 2462 4652 1165 4652 1163 4653 1165 4653 2462 4653 2461 4654 1163 4654 2462 4654 2460 4655 1163 4655 2461 4655 2459 4656 1163 4656 2460 4656 1302 4657 1163 4657 2459 4657 2068 4658 2070 4658 1986 4658 2496 4659 1986 4659 2070 4659 2069 4660 2500 4660 2070 4660 2500 4661 2069 4661 2001 4661 2501 4662 2070 4662 2500 4662 2070 4663 2501 4663 2496 4663 2494 4664 2496 4664 2501 4664 2389 4665 2495 4665 2502 4665 2499 4666 2495 4666 2389 4666 2389 4667 2388 4667 2499 4667 2498 4668 2499 4668 2388 4668 2388 4669 2387 4669 2498 4669 2498 4670 2387 4670 2470 4670 2387 4671 2481 4671 2478 4671 2471 4672 2387 4672 2478 4672 2457 4673 2476 4673 2477 4673 2457 4674 2477 4674 2479 4674 2457 4675 2479 4675 2480 4675 2457 4676 2480 4676 2482 4676 2457 4677 2482 4677 2390 4677 2470 4678 2497 4678 2498 4678 2497 4679 2499 4679 2498 4679 2495 4680 2499 4680 2497 4680 2495 4681 2497 4681 2496 4681 2453 4682 2495 4682 2458 4682 2453 4683 2502 4683 2495 4683 2390 4684 2502 4684 2453 4684 2389 4685 2502 4685 2390 4685 2387 4686 2388 4686 2481 4686 2388 4687 2389 4687 2481 4687 1228 4688 2409 4688 2408 4688 1228 4689 2408 4689 2407 4689 1228 4690 2407 4690 2406 4690 1228 4691 2406 4691 2405 4691 1228 4692 2405 4692 2404 4692 1228 4693 2404 4693 1227 4693 2396 4694 1227 4694 2404 4694 2396 4695 2397 4695 1227 4695 2397 4696 2398 4696 1227 4696 2398 4697 2399 4697 1227 4697 2584 4698 2565 4698 2583 4698 2584 4699 2537 4699 2565 4699 2567 4700 2565 4700 2537 4700 2569 4701 2567 4701 2537 4701 2569 4702 2537 4702 2538 4702 2571 4703 2569 4703 2538 4703 2537 4704 2518 4704 2522 4704 2584 4705 2518 4705 2537 4705 2513 4706 2519 4706 2520 4706 2587 4707 2586 4707 2245 4707 2546 4708 2503 4708 2248 4708 2550 4709 2504 4709 2552 4709 2503 4710 2552 4710 2504 4710 2504 4711 2251 4711 2503 4711 2248 4712 2503 4712 2251 4712 2531 4713 2504 4713 2550 4713 2505 4714 2504 4714 2531 4714 2505 4715 2251 4715 2504 4715 2505 4716 2258 4716 2251 4716 2256 4717 2505 4717 2533 4717 2505 4718 2531 4718 2533 4718 2505 4719 2256 4719 2258 4719 2585 4720 2256 4720 2536 4720 2256 4721 2533 4721 2536 4721 2536 4722 2243 4722 2585 4722 2534 4723 2506 4723 2535 4723 2506 4724 2517 4724 2535 4724 2547 4725 2509 4725 2532 4725 2507 4726 2532 4726 2509 4726 2532 4727 2507 4727 2534 4727 2506 4728 2534 4728 2507 4728 2509 4729 2510 4729 2507 4729 2517 4730 2506 4730 2507 4730 2507 4731 2508 4731 2517 4731 2508 4732 2507 4732 2510 4732 2510 4733 2511 4733 2508 4733 2511 4734 2512 4734 2508 4734 2512 4735 2513 4735 2508 4735 2508 4736 2520 4736 2517 4736 2520 4737 2508 4737 2513 4737 2549 4738 2547 4738 2548 4738 2509 4739 2547 4739 2549 4739 2549 4740 2514 4740 2509 4740 2510 4741 2509 4741 2514 4741 2511 4742 2510 4742 2514 4742 2514 4743 2515 4743 2511 4743 2512 4744 2511 4744 2515 4744 2513 4745 2512 4745 2515 4745 2519 4746 2513 4746 2515 4746 2515 4747 2561 4747 2519 4747 2551 4748 2516 4748 2549 4748 2514 4749 2549 4749 2516 4749 2515 4750 2514 4750 2516 4750 2516 4751 2562 4751 2515 4751 2561 4752 2515 4752 2562 4752 2251 4753 2258 4753 2252 4753 2258 4754 2256 4754 2257 4754 2242 4755 2256 4755 2585 4755 2535 4756 2517 4756 2518 4756 2245 4757 2535 4757 2518 4757 2518 4758 2584 4758 2245 4758 2522 4759 2517 4759 2520 4759 2522 4760 2518 4760 2517 4760 2521 4761 2520 4761 2560 4761 2520 4762 2519 4762 2560 4762 2519 4763 2561 4763 2560 4763 2520 4764 2521 4764 2522 4764 2560 4765 2559 4765 2521 4765 2521 4766 2523 4766 2522 4766 2523 4767 2521 4767 2558 4767 2521 4768 2559 4768 2558 4768 2524 4769 2522 4769 2523 4769 2524 4770 2537 4770 2522 4770 2524 4771 2538 4771 2537 4771 2558 4772 2557 4772 2523 4772 2539 4773 2538 4773 2524 4773 2525 4774 2523 4774 2556 4774 2523 4775 2557 4775 2556 4775 2523 4776 2525 4776 2524 4776 2524 4777 2526 4777 2539 4777 2526 4778 2540 4778 2539 4778 2526 4779 2524 4779 2525 4779 2541 4780 2540 4780 2526 4780 2556 4781 2555 4781 2525 4781 2527 4782 2525 4782 2554 4782 2525 4783 2555 4783 2554 4783 2525 4784 2527 4784 2526 4784 2528 4785 2526 4785 2527 4785 2526 4786 2528 4786 2541 4786 2528 4787 2542 4787 2541 4787 2543 4788 2542 4788 2528 4788 2554 4789 2553 4789 2527 4789 2530 4790 2527 4790 2553 4790 2527 4791 2530 4791 2528 4791 2528 4792 2529 4792 2543 4792 2531 4793 2550 4793 2547 4793 2547 4794 2532 4794 2531 4794 2533 4795 2531 4795 2532 4795 2532 4796 2534 4796 2533 4796 2536 4797 2533 4797 2534 4797 2534 4798 2535 4798 2536 4798 2535 4799 2245 4799 2536 4799 2243 4800 2536 4800 2245 4800 2573 4801 2571 4801 2538 4801 2538 4802 2539 4802 2573 4802 2575 4803 2573 4803 2539 4803 2539 4804 2540 4804 2575 4804 2577 4805 2575 4805 2540 4805 2540 4806 2541 4806 2577 4806 2579 4807 2577 4807 2541 4807 2541 4808 2542 4808 2579 4808 2580 4809 2579 4809 2542 4809 2542 4810 2543 4810 2580 4810 2580 4811 2543 4811 2544 4811 2248 4812 2251 4812 2250 4812 2545 4813 2248 4813 2160 4813 2545 4814 2247 4814 2248 4814 2247 4815 2546 4815 2248 4815 2547 4816 2550 4816 2548 4816 2550 4817 2549 4817 2548 4817 2550 4818 2551 4818 2549 4818 2552 4819 2551 4819 2550 4819 2582 4820 2587 4820 2583 4820 2245 4821 2583 4821 2587 4821 2583 4822 2565 4822 2564 4822 2565 4823 2567 4823 2566 4823 2567 4824 2569 4824 2568 4824 2569 4825 2571 4825 2570 4825 2571 4826 2573 4826 2572 4826 2573 4827 2575 4827 2574 4827 2575 4828 2577 4828 2576 4828 2577 4829 2579 4829 2578 4829 2579 4830 2580 4830 2581 4830 2245 4831 2584 4831 2583 4831 2245 4832 2244 4832 2243 4832 2585 4833 2243 4833 2242 4833 2553 4834 2554 4834 2563 4834 2554 4835 2555 4835 2563 4835 2555 4836 2556 4836 2563 4836 2556 4837 2562 4837 2563 4837 2556 4838 2557 4838 2562 4838 2557 4839 2558 4839 2562 4839 2558 4840 2559 4840 2562 4840 2559 4841 2560 4841 2562 4841 2560 4842 2561 4842 2562 4842 2592 4843 2589 4843 2590 4843 2593 4844 2589 4844 2592 4844 2594 4845 2589 4845 2593 4845 2595 4846 2589 4846 2594 4846 2595 4847 2563 4847 2589 4847 2596 4848 2563 4848 2595 4848 2597 4849 2563 4849 2596 4849 2553 4850 2563 4850 2597 4850 2588 4851 2581 4851 2580 4851 2581 4852 2578 4852 2579 4852 2578 4853 2576 4853 2577 4853 2576 4854 2574 4854 2575 4854 2574 4855 2572 4855 2573 4855 2572 4856 2570 4856 2571 4856 2570 4857 2568 4857 2569 4857 2568 4858 2566 4858 2567 4858 2566 4859 2564 4859 2565 4859 2564 4860 2582 4860 2583 4860 2591 4861 2590 4861 2589 4861 2566 4862 2600 4862 2601 4862 2566 4863 2601 4863 2602 4863 2564 4864 2566 4864 2602 4864 2566 4865 2568 4865 2600 4865 2568 4866 2570 4866 2600 4866 2572 4867 2574 4867 2603 4867 2604 4868 2603 4868 2574 4868 2574 4869 2576 4869 2604 4869 2605 4870 2604 4870 2576 4870 2576 4871 2578 4871 2605 4871 2606 4872 2605 4872 2578 4872 2578 4873 2581 4873 2606 4873 2607 4874 2606 4874 2581 4874 2581 4875 2588 4875 2607 4875 2544 4876 2607 4876 2588 4876 2588 4877 2580 4877 2544 4877 2601 4878 2608 4878 2609 4878 2602 4879 2601 4879 2609 4879 2610 4880 2611 4880 2612 4880 2608 4881 2610 4881 2612 4881 2608 4882 2601 4882 2600 4882 2608 4883 2600 4883 2610 4883 2613 4884 2611 4884 2610 4884 2613 4885 2590 4885 2591 4885 2613 4886 2591 4886 2611 4886 2592 4887 2590 4887 2613 4887 2613 4888 2610 4888 2614 4888 2615 4889 2613 4889 2614 4889 2615 4890 2593 4890 2592 4890 2613 4891 2615 4891 2592 4891 2614 4892 2616 4892 2615 4892 2610 4893 2600 4893 2603 4893 2614 4894 2610 4894 2603 4894 2616 4895 2614 4895 2603 4895 2603 4896 2604 4896 2616 4896 2594 4897 2593 4897 2615 4897 2617 4898 2595 4898 2594 4898 2615 4899 2617 4899 2594 4899 2617 4900 2615 4900 2616 4900 2616 4901 2604 4901 2605 4901 2618 4902 2616 4902 2605 4902 2616 4903 2618 4903 2617 4903 2605 4904 2606 4904 2618 4904 2596 4905 2595 4905 2617 4905 2530 4906 2597 4906 2596 4906 2617 4907 2530 4907 2596 4907 2530 4908 2617 4908 2618 4908 2618 4909 2529 4909 2530 4909 2618 4910 2606 4910 2607 4910 2529 4911 2618 4911 2607 4911 2607 4912 2544 4912 2529 4912 2553 4913 2597 4913 2530 4913 2529 4914 2544 4914 2543 4914 2530 4915 2529 4915 2528 4915 2598 4916 2161 4916 2158 4916 2161 4917 2247 4917 2157 4917 2247 4918 2545 4918 2160 4918 1980 4919 2619 4919 2620 4919 1980 4920 2620 4920 1981 4920 1980 4921 1981 4921 1982 4921 1985 4922 2241 4922 2599 4922 1980 4923 1985 4923 2599 4923 2621 4924 2582 4924 2622 4924 2623 4925 2621 4925 2622 4925 2582 4926 2564 4926 2622 4926 2602 4927 2622 4927 2564 4927 2100 4928 2099 4928 2098 4928 2098 4929 2021 4929 2022 4929 2098 4930 2022 4930 2624 4930 2098 4931 2624 4931 2625 4931 2100 4932 2098 4932 2158 4932 2158 4933 2098 4933 2598 4933 2626 4934 2627 4934 2628 4934 2629 4935 2628 4935 2627 4935 2629 4936 2627 4936 2098 4936 2630 4937 2629 4937 2098 4937 2619 4938 1980 4938 2625 4938 2621 4939 2623 4939 2625 4939 2625 4940 2623 4940 2631 4940 2625 4941 2631 4941 2632 4941 2625 4942 2632 4942 2633 4942 2625 4943 2633 4943 2634 4943 2625 4944 2634 4944 2630 4944 2098 4945 2625 4945 2630 4945 1981 4946 2620 4946 2022 4946 2624 4947 2022 4947 2620 4947 2620 4948 2619 4948 2624 4948 2625 4949 2624 4949 2619 4949 2634 4950 2635 4950 2629 4950 2630 4951 2634 4951 2629 4951 2634 4952 2633 4952 2635 4952 2636 4953 2635 4953 2633 4953 2633 4954 2632 4954 2636 4954 2637 4955 2636 4955 2632 4955 2632 4956 2631 4956 2637 4956 2622 4957 2637 4957 2631 4957 2631 4958 2623 4958 2622 4958 2602 4959 2609 4959 2622 4959 2608 4960 2612 4960 2609 4960 2591 4961 2638 4961 2611 4961 2611 4962 2639 4962 2612 4962 2639 4963 2611 4963 2638 4963 2636 4964 2612 4964 2639 4964 2635 4965 2639 4965 2638 4965 2639 4966 2635 4966 2636 4966 2638 4967 2629 4967 2635 4967 2638 4968 2591 4968 2640 4968 2640 4969 2628 4969 2638 4969 2629 4970 2638 4970 2628 4970 2589 4971 2640 4971 2591 4971 2589 4972 2641 4972 2640 4972 2628 4973 2640 4973 2641 4973 2628 4974 2641 4974 2626 4974 2570 4975 2603 4975 2600 4975 2572 4976 2603 4976 2570 4976 2609 4977 2637 4977 2622 4977 2609 4978 2612 4978 2637 4978 2612 4979 2636 4979 2637 4979 2645 4980 2644 4980 2643 4980 2246 4981 2647 4981 2648 4981 2246 4982 2648 4982 2645 4982 2643 4983 2246 4983 2645 4983 2651 4984 2652 4984 2653 4984 2654 4985 2653 4985 2652 4985 2652 4986 2655 4986 2654 4986 2656 4987 2654 4987 2655 4987 2655 4988 2657 4988 2656 4988 2658 4989 2656 4989 2657 4989 2657 4990 2659 4990 2658 4990 2660 4991 2658 4991 2659 4991 2659 4992 2661 4992 2660 4992 2662 4993 2660 4993 2661 4993 2661 4994 2663 4994 2662 4994 2664 4995 2662 4995 2663 4995 2663 4996 2665 4996 2664 4996 2666 4997 2664 4997 2665 4997 2665 4998 2667 4998 2666 4998 2666 4999 2667 4999 2668 4999 2669 5000 2666 5000 2668 5000 2669 5001 2670 5001 2674 5001 2669 5002 2674 5002 2675 5002 2676 5003 2669 5003 2675 5003 2677 5004 2678 5004 2645 5004 2644 5005 2645 5005 2678 5005 2679 5006 2680 5006 2644 5006 2678 5007 2679 5007 2644 5007 2681 5008 2680 5008 2679 5008 2679 5009 2682 5009 2681 5009 2683 5010 2681 5010 2682 5010 2682 5011 2684 5011 2683 5011 2685 5012 2683 5012 2684 5012 2684 5013 2686 5013 2685 5013 2687 5014 2685 5014 2686 5014 2686 5015 2688 5015 2687 5015 2689 5016 2687 5016 2688 5016 2688 5017 2690 5017 2689 5017 2691 5018 2689 5018 2690 5018 2690 5019 2692 5019 2691 5019 2693 5020 2691 5020 2692 5020 2692 5021 2694 5021 2693 5021 2693 5022 2694 5022 2695 5022 2696 5023 2693 5023 2695 5023 2647 5024 2642 5024 2582 5024 2697 5025 2647 5025 2582 5025 2646 5026 2642 5026 2647 5026 2678 5027 2698 5027 2699 5027 2679 5028 2678 5028 2699 5028 2682 5029 2679 5029 2699 5029 2684 5030 2682 5030 2699 5030 2686 5031 2684 5031 2699 5031 2699 5032 2700 5032 2686 5032 2688 5033 2686 5033 2700 5033 2700 5034 2701 5034 2688 5034 2690 5035 2688 5035 2701 5035 2701 5036 2702 5036 2690 5036 2692 5037 2690 5037 2702 5037 2702 5038 2703 5038 2692 5038 2694 5039 2692 5039 2703 5039 2703 5040 2704 5040 2694 5040 2695 5041 2694 5041 2704 5041 2704 5042 2705 5042 2695 5042 2695 5043 2705 5043 2706 5043 2696 5044 2695 5044 2706 5044 2706 5045 2707 5045 2696 5045 2693 5046 2696 5046 2707 5046 2707 5047 2708 5047 2693 5047 2691 5048 2693 5048 2708 5048 2708 5049 2709 5049 2691 5049 2689 5050 2691 5050 2709 5050 2709 5051 2710 5051 2689 5051 2687 5052 2689 5052 2710 5052 2710 5053 2711 5053 2687 5053 2685 5054 2687 5054 2711 5054 2711 5055 2712 5055 2685 5055 2683 5056 2685 5056 2712 5056 2683 5057 2712 5057 2681 5057 2680 5058 2681 5058 2712 5058 2680 5059 2712 5059 2713 5059 2680 5060 2713 5060 2643 5060 2644 5061 2680 5061 2643 5061 2392 5062 2425 5062 2391 5062 2425 5063 2714 5063 2426 5063 2714 5064 2427 5064 2426 5064 2427 5065 2430 5065 2428 5065 2430 5066 2431 5066 2429 5066 2722 5067 2720 5067 2721 5067 2723 5068 2722 5068 2721 5068 2721 5069 2724 5069 2723 5069 2725 5070 2723 5070 2724 5070 2724 5071 2726 5071 2725 5071 2483 5072 2725 5072 2726 5072 2729 5073 2728 5073 2727 5073 2731 5074 2727 5074 2730 5074 2727 5075 2731 5075 2729 5075 2732 5076 2729 5076 2731 5076 2732 5077 2733 5077 2729 5077 2734 5078 2437 5078 2435 5078 2734 5079 2435 5079 2735 5079 2734 5080 2735 5080 2733 5080 2734 5081 2733 5081 2732 5081 2439 5082 2437 5082 2734 5082 2731 5083 2736 5083 2732 5083 2731 5084 2730 5084 2737 5084 2736 5085 2731 5085 2737 5085 2738 5086 2732 5086 2736 5086 2732 5087 2738 5087 2734 5087 2739 5088 2734 5088 2738 5088 2739 5089 2441 5089 2439 5089 2734 5090 2739 5090 2439 5090 2715 5091 2441 5091 2739 5091 2739 5092 2740 5092 2715 5092 2741 5093 2740 5093 2739 5093 2738 5094 2741 5094 2739 5094 2716 5095 2715 5095 2740 5095 2742 5096 2741 5096 2738 5096 2736 5097 2742 5097 2738 5097 2742 5098 2736 5098 2737 5098 2743 5099 2717 5099 2716 5099 2740 5100 2743 5100 2716 5100 2743 5101 2740 5101 2741 5101 2718 5102 2717 5102 2743 5102 2744 5103 2741 5103 2742 5103 2741 5104 2744 5104 2743 5104 2745 5105 2742 5105 2737 5105 2742 5106 2745 5106 2744 5106 2737 5107 2746 5107 2745 5107 2747 5108 2743 5108 2744 5108 2747 5109 2719 5109 2718 5109 2743 5110 2747 5110 2718 5110 2720 5111 2719 5111 2747 5111 2744 5112 2748 5112 2747 5112 2748 5113 2744 5113 2745 5113 2749 5114 2745 5114 2746 5114 2745 5115 2749 5115 2748 5115 2747 5116 2750 5116 2720 5116 2750 5117 2747 5117 2748 5117 2748 5118 2752 5118 2750 5118 2752 5119 2748 5119 2749 5119 2749 5120 2754 5120 2752 5120 2749 5121 2746 5121 2754 5121 2755 5122 2752 5122 2754 5122 2670 5123 2821 5123 2674 5123 2756 5124 2757 5124 2676 5124 2675 5125 2756 5125 2676 5125 2756 5126 2675 5126 2674 5126 2674 5127 2821 5127 2758 5127 2759 5128 2674 5128 2758 5128 2674 5129 2759 5129 2756 5129 2758 5130 2826 5130 2759 5130 2756 5131 2760 5131 2757 5131 2760 5132 2756 5132 2759 5132 2759 5133 2761 5133 2760 5133 2761 5134 2759 5134 2826 5134 2826 5135 2762 5135 2761 5135 2763 5136 2757 5136 2760 5136 2764 5137 2761 5137 2762 5137 2761 5138 2764 5138 2760 5138 2765 5139 2760 5139 2764 5139 2760 5140 2765 5140 2763 5140 2766 5141 2764 5141 2762 5141 2764 5142 2766 5142 2765 5142 2767 5143 2757 5143 2763 5143 2762 5144 2768 5144 2766 5144 2769 5145 2765 5145 2766 5145 2765 5146 2769 5146 2763 5146 2763 5147 2770 5147 2767 5147 2770 5148 2763 5148 2769 5148 2766 5149 2771 5149 2769 5149 2771 5150 2766 5150 2768 5150 2772 5151 2767 5151 2770 5151 2767 5152 2772 5152 2773 5152 2769 5153 2774 5153 2770 5153 2774 5154 2769 5154 2771 5154 2775 5155 2770 5155 2774 5155 2770 5156 2775 5156 2772 5156 2772 5157 2776 5157 2773 5157 2777 5158 2771 5158 2768 5158 2771 5159 2777 5159 2774 5159 2778 5160 2772 5160 2775 5160 2772 5161 2778 5161 2776 5161 2768 5162 2737 5162 2777 5162 2780 5163 2774 5163 2777 5163 2774 5164 2780 5164 2775 5164 2728 5165 2775 5165 2780 5165 2775 5166 2728 5166 2778 5166 2733 5167 2735 5167 2779 5167 2776 5168 2733 5168 2779 5168 2733 5169 2776 5169 2778 5169 2777 5170 2737 5170 2730 5170 2780 5171 2777 5171 2730 5171 2780 5172 2730 5172 2727 5172 2780 5173 2727 5173 2728 5173 2778 5174 2728 5174 2729 5174 2778 5175 2729 5175 2733 5175 2781 5176 2735 5176 2435 5176 2667 5177 2782 5177 2783 5177 2668 5178 2667 5178 2783 5178 2782 5179 2667 5179 2665 5179 2786 5180 2782 5180 2665 5180 2786 5181 2784 5181 2787 5181 2782 5182 2786 5182 2787 5182 2665 5183 2663 5183 2786 5183 2786 5184 2663 5184 2661 5184 2788 5185 2786 5185 2661 5185 2789 5186 2700 5186 2699 5186 2701 5187 2700 5187 2789 5187 2661 5188 2659 5188 2788 5188 2788 5189 2790 5189 2789 5189 2788 5190 2659 5190 2657 5190 2790 5191 2788 5191 2657 5191 2791 5192 2702 5192 2701 5192 2789 5193 2791 5193 2701 5193 2791 5194 2789 5194 2790 5194 2703 5195 2702 5195 2791 5195 2657 5196 2655 5196 2790 5196 2790 5197 2655 5197 2652 5197 2792 5198 2790 5198 2652 5198 2790 5199 2792 5199 2791 5199 2793 5200 2704 5200 2703 5200 2791 5201 2793 5201 2703 5201 2793 5202 2791 5202 2792 5202 2705 5203 2704 5203 2793 5203 2652 5204 2651 5204 2792 5204 2794 5205 2706 5205 2705 5205 2793 5206 2794 5206 2705 5206 2792 5207 2651 5207 2653 5207 2795 5208 2792 5208 2653 5208 2795 5209 2794 5209 2793 5209 2792 5210 2795 5210 2793 5210 2707 5211 2706 5211 2794 5211 2653 5212 2654 5212 2795 5212 2796 5213 2708 5213 2707 5213 2794 5214 2796 5214 2707 5214 2796 5215 2794 5215 2795 5215 2795 5216 2654 5216 2656 5216 2797 5217 2795 5217 2656 5217 2795 5218 2797 5218 2796 5218 2709 5219 2708 5219 2796 5219 2656 5220 2658 5220 2797 5220 2798 5221 2796 5221 2797 5221 2798 5222 2710 5222 2709 5222 2796 5223 2798 5223 2709 5223 2797 5224 2799 5224 2798 5224 2797 5225 2658 5225 2660 5225 2799 5226 2797 5226 2660 5226 2711 5227 2710 5227 2798 5227 2660 5228 2662 5228 2799 5228 2800 5229 2712 5229 2711 5229 2798 5230 2800 5230 2711 5230 2800 5231 2798 5231 2799 5231 2801 5232 2799 5232 2662 5232 2799 5233 2801 5233 2800 5233 2662 5234 2664 5234 2801 5234 2801 5235 2664 5235 2666 5235 2801 5236 2666 5236 2669 5236 2801 5237 2669 5237 2802 5237 2801 5238 2802 5238 2803 5238 2801 5239 2803 5239 2800 5239 2800 5240 2803 5240 2804 5240 2800 5241 2804 5241 2805 5241 2806 5242 2800 5242 2805 5242 2806 5243 2713 5243 2712 5243 2806 5244 2712 5244 2800 5244 2713 5245 2806 5245 2807 5245 2643 5246 2713 5246 2807 5246 2643 5247 2807 5247 2246 5247 2808 5248 2246 5248 2807 5248 2808 5249 2807 5249 2806 5249 2806 5250 2805 5250 2808 5250 2809 5251 2808 5251 2805 5251 2810 5252 2809 5252 2805 5252 2804 5253 2810 5253 2805 5253 2811 5254 2810 5254 2804 5254 2804 5255 2803 5255 2811 5255 2812 5256 2811 5256 2803 5256 2803 5257 2802 5257 2812 5257 2676 5258 2812 5258 2802 5258 2802 5259 2669 5259 2676 5259 2809 5260 2810 5260 2813 5260 2814 5261 2813 5261 2810 5261 2810 5262 2811 5262 2814 5262 2757 5263 2814 5263 2811 5263 2811 5264 2812 5264 2757 5264 2812 5265 2676 5265 2757 5265 2813 5266 2427 5266 2714 5266 2813 5267 2714 5267 2425 5267 2392 5268 2813 5268 2425 5268 2781 5269 2435 5269 2434 5269 2781 5270 2434 5270 2432 5270 2815 5271 2427 5271 2813 5271 2779 5272 2781 5272 2815 5272 2781 5273 2779 5273 2735 5273 2816 5274 2815 5274 2813 5274 2815 5275 2816 5275 2779 5275 2776 5276 2779 5276 2816 5276 2816 5277 2817 5277 2776 5277 2817 5278 2816 5278 2813 5278 2813 5279 2814 5279 2817 5279 2817 5280 2773 5280 2776 5280 2773 5281 2817 5281 2814 5281 2767 5282 2773 5282 2814 5282 2814 5283 2757 5283 2767 5283 2645 5284 2648 5284 2677 5284 2818 5285 2677 5285 2648 5285 2648 5286 2647 5286 2818 5286 2697 5287 2818 5287 2647 5287 2820 5288 2677 5288 2818 5288 2818 5289 2697 5289 2820 5289 2820 5290 2698 5290 2678 5290 2678 5291 2677 5291 2820 5291 2821 5292 2670 5292 2671 5292 2822 5293 2672 5293 2673 5293 2672 5294 2822 5294 2671 5294 2673 5295 2823 5295 2822 5295 2824 5296 2671 5296 2822 5296 2671 5297 2824 5297 2821 5297 2758 5298 2821 5298 2824 5298 2824 5299 2825 5299 2758 5299 2825 5300 2824 5300 2822 5300 2826 5301 2758 5301 2825 5301 2823 5302 2827 5302 2822 5302 2828 5303 2822 5303 2827 5303 2822 5304 2828 5304 2825 5304 2827 5305 2829 5305 2828 5305 2830 5306 2828 5306 2829 5306 2828 5307 2830 5307 2825 5307 2762 5308 2826 5308 2825 5308 2825 5309 2831 5309 2762 5309 2831 5310 2825 5310 2830 5310 2832 5311 2833 5311 2829 5311 2830 5312 2834 5312 2831 5312 2834 5313 2830 5313 2829 5313 2829 5314 2835 5314 2834 5314 2835 5315 2829 5315 2833 5315 2836 5316 2831 5316 2834 5316 2831 5317 2836 5317 2762 5317 2768 5318 2762 5318 2836 5318 2833 5319 2837 5319 2835 5319 2838 5320 2834 5320 2835 5320 2834 5321 2838 5321 2836 5321 2837 5322 2839 5322 2835 5322 2836 5323 2840 5323 2768 5323 2840 5324 2836 5324 2838 5324 2841 5325 2835 5325 2839 5325 2835 5326 2841 5326 2838 5326 2737 5327 2768 5327 2840 5327 2837 5328 2753 5328 2839 5328 2838 5329 2842 5329 2840 5329 2842 5330 2838 5330 2841 5330 2746 5331 2840 5331 2842 5331 2840 5332 2746 5332 2737 5332 2755 5333 2841 5333 2839 5333 2841 5334 2755 5334 2842 5334 2839 5335 2843 5335 2755 5335 2843 5336 2839 5336 2753 5336 2754 5337 2842 5337 2755 5337 2842 5338 2754 5338 2746 5338 2753 5339 2751 5339 2750 5339 2755 5340 2843 5340 2752 5340 2844 5341 2845 5341 2726 5341 2844 5342 2726 5342 2724 5342 2721 5343 2751 5343 2844 5343 2844 5344 2846 5344 2845 5344 2847 5345 2846 5345 2844 5345 2844 5346 2848 5346 2847 5346 2844 5347 2751 5347 2753 5347 2848 5348 2844 5348 2753 5348 2753 5349 2837 5349 2848 5349 2849 5350 2847 5350 2848 5350 2848 5351 2837 5351 2849 5351 2837 5352 2833 5352 2849 5352 2850 5353 2849 5353 2833 5353 2833 5354 2832 5354 2850 5354 2851 5355 2820 5355 2819 5355 2819 5356 2852 5356 2851 5356 2819 5357 2726 5357 2852 5357 2853 5358 2851 5358 2852 5358 2852 5359 2726 5359 2845 5359 2854 5360 2852 5360 2845 5360 2852 5361 2854 5361 2853 5361 2854 5362 2845 5362 2846 5362 2855 5363 2854 5363 2846 5363 2854 5364 2855 5364 2853 5364 2846 5365 2847 5365 2855 5365 2856 5366 2853 5366 2855 5366 2855 5367 2857 5367 2856 5367 2857 5368 2855 5368 2847 5368 2857 5369 2847 5369 2849 5369 2858 5370 2856 5370 2857 5370 2857 5371 2859 5371 2858 5371 2859 5372 2857 5372 2849 5372 2860 5373 2858 5373 2859 5373 2859 5374 2849 5374 2850 5374 2859 5375 2827 5375 2860 5375 2859 5376 2850 5376 2832 5376 2827 5377 2859 5377 2832 5377 2860 5378 2827 5378 2823 5378 2673 5379 2860 5379 2823 5379 2832 5380 2829 5380 2827 5380 2820 5381 2785 5381 2698 5381 2851 5382 2785 5382 2820 5382 2853 5383 2784 5383 2785 5383 2851 5384 2853 5384 2785 5384 2856 5385 2787 5385 2784 5385 2853 5386 2856 5386 2784 5386 2856 5387 2858 5387 2787 5387 2782 5388 2787 5388 2858 5388 2858 5389 2860 5389 2782 5389 2783 5390 2782 5390 2860 5390 2860 5391 2673 5391 2783 5391 2668 5392 2783 5392 2673 5392 2698 5393 2785 5393 2699 5393 2699 5394 2785 5394 2784 5394 2784 5395 2861 5395 2699 5395 2861 5396 2789 5396 2699 5396 2788 5397 2861 5397 2786 5397 2789 5398 2861 5398 2788 5398 2786 5399 2861 5399 2784 5399 2431 5400 2781 5400 2432 5400 2430 5401 2781 5401 2431 5401 2427 5402 2815 5402 2430 5402 2430 5403 2815 5403 2781 5403 2808 5404 2809 5404 2813 5404 2246 5405 2808 5405 2813 5405 2246 5406 2813 5406 2649 5406 2649 5407 2813 5407 2650 5407 2392 5408 2650 5408 2813 5408 2668 5409 2673 5409 2672 5409 2668 5410 2672 5410 2671 5410 2668 5411 2671 5411 2670 5411 2668 5412 2670 5412 2669 5412 2750 5413 2752 5413 2843 5413 2750 5414 2843 5414 2753 5414 2720 5415 2750 5415 2751 5415 2720 5416 2751 5416 2721 5416 2724 5417 2721 5417 2844 5417 2865 5418 2059 5418 1988 5418 2865 5419 2864 5419 2059 5419 2060 5420 2059 5420 2864 5420 2864 5421 2862 5421 2060 5421 2862 5422 2863 5422 2060 5422 2621 5423 2862 5423 2864 5423 2863 5424 2862 5424 2621 5424 2625 5425 2866 5425 2621 5425 2625 5426 1980 5426 2866 5426 2599 5427 2866 5427 1980 5427 2237 5428 1979 5428 2863 5428 1979 5429 2060 5429 2863 5429 2238 5430 2237 5430 2863 5430 2239 5431 2238 5431 2863 5431 2240 5432 2239 5432 2863 5432 2869 5433 2240 5433 2863 5433 2868 5434 2869 5434 2866 5434 2869 5435 2621 5435 2866 5435 2869 5436 2863 5436 2621 5436 2621 5437 2697 5437 2582 5437 2621 5438 2820 5438 2697 5438 2621 5439 2864 5439 2820 5439 2820 5440 2864 5440 2819 5440 2864 5441 2865 5441 2726 5441 2726 5442 2819 5442 2864 5442 2865 5443 1988 5443 2726 5443 1988 5444 2483 5444 2726 5444 1988 5445 1987 5445 2497 5445 2497 5446 2483 5446 1988 5446 2867 5447 2245 5447 2586 5447 2586 5448 2642 5448 2867 5448 2646 5449 2867 5449 2642 5449 2586 5450 2587 5450 2582 5450 2586 5451 2582 5451 2642 5451 2241 5452 1973 5452 2868 5452 1973 5453 2869 5453 2868 5453 1973 5454 2240 5454 2869 5454 2056 5455 2057 5455 2877 5455 1899 5456 1954 5456 2949 5456 2931 5457 2936 5457 2953 5457 2952 5458 2953 5458 2936 5458 2936 5459 2941 5459 2952 5459 2951 5460 2952 5460 2941 5460 2941 5461 2942 5461 2951 5461 1958 5462 2951 5462 1943 5462 2951 5463 2942 5463 1943 5463 2922 5464 2923 5464 2964 5464 2965 5465 2964 5465 2923 5465 2923 5466 2924 5466 2965 5466 2963 5467 2965 5467 2924 5467 2924 5468 2928 5468 2963 5468 2955 5469 2963 5469 2928 5469 2928 5470 2930 5470 2955 5470 2954 5471 2955 5471 2930 5471 2930 5472 2931 5472 2954 5472 2953 5473 2954 5473 2931 5473 2964 5474 2956 5474 2922 5474 2494 5475 2872 5475 2493 5475 2501 5476 2870 5476 2872 5476 2501 5477 2872 5477 2494 5477 2500 5478 2889 5478 2870 5478 2500 5479 2887 5479 2889 5479 2870 5480 2501 5480 2500 5480 2001 5481 2887 5481 2500 5481 2944 5482 2893 5482 2948 5482 2893 5483 2871 5483 2892 5483 2871 5484 2889 5484 2892 5484 2871 5485 2870 5485 2889 5485 2871 5486 2893 5486 2945 5486 2893 5487 2944 5487 2945 5487 2945 5488 2946 5488 2871 5488 2871 5489 2873 5489 2870 5489 2873 5490 2872 5490 2870 5490 2873 5491 2871 5491 2943 5491 2871 5492 2946 5492 2943 5492 2943 5493 2937 5493 2873 5493 2873 5494 2938 5494 2939 5494 2873 5495 2937 5495 2938 5495 2873 5496 2939 5496 2872 5496 2939 5497 2493 5497 2872 5497 2933 5498 2493 5498 2939 5498 2933 5499 2492 5499 2493 5499 2491 5500 2492 5500 2933 5500 2933 5501 2934 5501 2491 5501 2490 5502 2491 5502 2896 5502 2491 5503 2932 5503 2896 5503 2491 5504 2934 5504 2932 5504 1849 5505 1850 5505 2886 5505 2886 5506 2874 5506 2885 5506 2874 5507 2884 5507 2885 5507 2874 5508 2878 5508 2884 5508 2874 5509 2886 5509 1850 5509 2879 5510 2878 5510 2874 5510 1850 5511 1851 5511 2874 5511 2874 5512 2875 5512 2879 5512 2875 5513 2880 5513 2879 5513 2875 5514 2874 5514 1852 5514 2874 5515 1851 5515 1852 5515 2881 5516 2880 5516 2875 5516 1852 5517 1853 5517 2875 5517 2876 5518 2875 5518 1854 5518 2875 5519 1853 5519 1854 5519 2875 5520 2876 5520 2881 5520 2876 5521 2882 5521 2881 5521 2883 5522 2882 5522 2876 5522 1854 5523 1855 5523 2876 5523 2877 5524 2876 5524 2056 5524 2876 5525 2055 5525 2056 5525 2876 5526 2053 5526 2055 5526 2876 5527 1855 5527 2053 5527 2876 5528 2877 5528 2883 5528 2054 5529 2883 5529 2058 5529 2883 5530 2057 5530 2058 5530 2883 5531 2877 5531 2057 5531 2884 5532 2878 5532 1961 5532 2957 5533 1961 5533 2878 5533 2878 5534 2879 5534 2957 5534 2959 5535 2957 5535 2879 5535 2879 5536 2880 5536 2959 5536 2960 5537 2959 5537 2880 5537 2880 5538 2881 5538 2960 5538 2962 5539 2960 5539 2881 5539 2881 5540 2882 5540 2962 5540 2961 5541 2962 5541 2882 5541 2882 5542 2883 5542 2961 5542 2958 5543 2961 5543 2883 5543 2883 5544 2054 5544 2958 5544 1962 5545 2958 5545 2054 5545 1952 5546 2884 5546 1961 5546 1952 5547 2885 5547 2884 5547 1952 5548 2886 5548 2885 5548 1952 5549 1849 5549 2886 5549 1850 5550 1849 5550 1955 5550 1999 5551 2887 5551 2001 5551 2889 5552 2887 5552 2888 5552 2887 5553 1999 5553 2888 5553 1879 5554 1999 5554 1877 5554 1878 5555 2890 5555 1879 5555 1880 5556 2890 5556 1878 5556 1898 5557 1899 5557 1880 5557 2891 5558 2889 5558 2888 5558 2891 5559 2892 5559 2889 5559 2891 5560 2888 5560 1879 5560 2888 5561 1999 5561 1879 5561 1879 5562 2890 5562 2891 5562 2894 5563 2891 5563 1880 5563 2891 5564 2890 5564 1880 5564 2891 5565 2894 5565 2892 5565 2894 5566 2893 5566 2892 5566 2948 5567 2893 5567 2894 5567 1880 5568 1899 5568 2894 5568 2894 5569 2895 5569 2948 5569 2895 5570 2894 5570 2949 5570 2894 5571 1899 5571 2949 5571 2490 5572 2896 5572 2489 5572 2925 5573 2488 5573 2489 5573 2488 5574 2925 5574 2487 5574 2489 5575 2926 5575 2925 5575 2926 5576 2489 5576 2896 5576 2917 5577 2487 5577 2925 5577 2896 5578 2932 5578 2926 5578 2905 5579 2487 5579 2917 5579 2486 5580 2487 5580 2905 5580 2905 5581 2907 5581 2486 5581 2913 5582 2915 5582 2900 5582 2901 5583 2900 5583 2898 5583 2900 5584 2915 5584 2898 5584 2898 5585 2899 5585 2901 5585 2897 5586 2901 5586 2899 5586 2901 5587 2897 5587 2902 5587 2897 5588 2903 5588 2902 5588 2904 5589 2903 5589 2897 5589 2386 5590 2897 5590 2367 5590 2897 5591 2369 5591 2367 5591 2897 5592 2899 5592 2369 5592 2897 5593 2386 5593 2904 5593 2386 5594 2362 5594 2904 5594 2374 5595 2915 5595 2349 5595 2374 5596 2371 5596 2915 5596 2371 5597 2898 5597 2915 5597 2899 5598 2898 5598 2371 5598 2371 5599 2369 5599 2899 5599 2486 5600 2907 5600 2485 5600 2907 5601 2909 5601 2485 5601 2909 5602 2910 5602 2485 5602 2910 5603 2911 5603 2485 5603 2911 5604 2913 5604 2485 5604 2913 5605 2900 5605 2485 5605 2900 5606 2901 5606 2485 5606 2901 5607 2484 5607 2485 5607 2484 5608 1282 5608 1284 5608 2484 5609 2362 5609 1282 5609 2901 5610 2902 5610 2484 5610 2902 5611 2903 5611 2484 5611 2903 5612 2904 5612 2484 5612 2904 5613 2362 5613 2484 5613 2908 5614 2921 5614 2956 5614 2921 5615 2908 5615 2919 5615 2908 5616 2920 5616 2919 5616 2908 5617 2918 5617 2920 5617 2908 5618 2906 5618 2918 5618 2906 5619 2917 5619 2918 5619 2905 5620 2917 5620 2906 5620 2907 5621 2905 5621 2906 5621 2914 5622 2909 5622 2906 5622 2914 5623 2906 5623 2908 5623 2909 5624 2907 5624 2906 5624 2908 5625 2912 5625 2914 5625 2912 5626 2908 5626 2956 5626 2910 5627 2909 5627 2914 5627 2911 5628 2910 5628 2914 5628 2913 5629 2911 5629 2914 5629 2912 5630 2956 5630 2916 5630 2912 5631 2916 5631 2914 5631 2915 5632 2913 5632 2914 5632 2956 5633 2311 5633 2916 5633 2350 5634 2915 5634 2914 5634 2350 5635 2349 5635 2915 5635 2350 5636 2914 5636 2916 5636 2916 5637 2348 5637 2350 5637 2350 5638 2344 5638 2349 5638 2311 5639 2348 5639 2916 5639 2348 5640 2311 5640 2309 5640 2917 5641 2925 5641 2918 5641 2925 5642 2920 5642 2918 5642 2920 5643 2927 5643 2919 5643 2927 5644 2921 5644 2919 5644 2927 5645 2920 5645 2925 5645 2929 5646 2921 5646 2927 5646 2929 5647 2956 5647 2921 5647 2929 5648 2922 5648 2956 5648 2929 5649 2923 5649 2922 5649 2929 5650 2924 5650 2923 5650 2929 5651 2928 5651 2924 5651 2925 5652 2926 5652 2927 5652 2935 5653 2927 5653 2932 5653 2927 5654 2926 5654 2932 5654 2927 5655 2935 5655 2929 5655 2930 5656 2928 5656 2929 5656 2940 5657 2929 5657 2935 5657 2929 5658 2940 5658 2930 5658 2940 5659 2931 5659 2930 5659 2940 5660 2936 5660 2931 5660 2932 5661 2934 5661 2935 5661 2939 5662 2935 5662 2933 5662 2935 5663 2934 5663 2933 5663 2935 5664 2939 5664 2940 5664 2941 5665 2936 5665 2940 5665 2947 5666 2940 5666 2943 5666 2940 5667 2937 5667 2943 5667 2940 5668 2938 5668 2937 5668 2940 5669 2939 5669 2938 5669 2940 5670 2947 5670 2941 5670 2947 5671 2942 5671 2941 5671 2947 5672 1943 5672 2942 5672 2943 5673 2946 5673 2947 5673 2950 5674 2947 5674 2948 5674 2947 5675 2944 5675 2948 5675 2947 5676 2945 5676 2944 5676 2947 5677 2946 5677 2945 5677 2947 5678 2950 5678 1943 5678 2950 5679 1944 5679 1943 5679 2950 5680 1945 5680 1944 5680 2950 5681 1946 5681 1945 5681 2950 5682 1947 5682 1946 5682 2950 5683 1948 5683 1947 5683 2948 5684 2895 5684 2950 5684 1949 5685 1948 5685 2950 5685 2950 5686 1954 5686 1949 5686 1954 5687 2950 5687 2949 5687 2950 5688 2895 5688 2949 5688 1954 5689 1899 5689 1955 5689 2312 5690 1654 5690 2394 5690 2223 5691 2309 5691 1957 5691 2309 5692 1958 5692 1957 5692 2309 5693 2951 5693 1958 5693 2309 5694 2956 5694 2951 5694 2956 5695 2952 5695 2951 5695 2956 5696 2953 5696 2952 5696 2956 5697 2954 5697 2953 5697 2956 5698 2955 5698 2954 5698 2956 5699 2963 5699 2955 5699 2309 5700 2311 5700 2956 5700 2957 5701 1962 5701 1961 5701 2958 5702 1962 5702 2957 5702 2957 5703 2959 5703 2958 5703 2961 5704 2958 5704 2959 5704 2959 5705 2960 5705 2961 5705 2962 5706 2961 5706 2960 5706 2965 5707 2963 5707 2956 5707 2965 5708 2956 5708 2964 5708 1512 5709 2222 5709 1602 5709 1445 5710 1668 5710 1669 5710 1445 5711 1634 5711 1668 5711 1669 5712 2222 5712 1446 5712 1445 5713 1669 5713 1446 5713 1584 5714 1588 5714 1586 5714 1584 5715 1599 5715 1588 5715 3061 5716 3014 5716 3051 5716 3014 5717 2986 5717 3051 5717 3014 5718 3061 5718 1109 5718 1147 5719 1118 5719 3023 5719 3414 5720 3415 5720 3025 5720 2978 5721 2967 5721 2968 5721 2978 5722 2977 5722 2967 5722 3003 5723 2974 5723 2973 5723 3002 5724 2974 5724 3003 5724 2981 5725 2984 5725 3386 5725 3386 5726 3435 5726 2981 5726 2979 5727 2981 5727 3435 5727 3435 5728 3434 5728 2979 5728 3416 5729 2979 5729 3434 5729 3016 5730 2974 5730 3002 5730 3016 5731 2966 5731 2974 5731 2966 5732 2973 5732 2974 5732 2968 5733 2966 5733 3016 5733 3016 5734 3018 5734 2968 5734 3018 5735 3011 5735 2968 5735 2982 5736 2968 5736 3011 5736 3011 5737 3010 5737 2982 5737 2975 5738 3418 5738 3446 5738 3438 5739 2969 5739 3446 5739 2967 5740 3446 5740 2970 5740 3446 5741 2969 5741 2970 5741 3446 5742 2967 5742 2975 5742 2967 5743 2976 5743 2975 5743 2977 5744 2976 5744 2967 5744 2970 5745 2971 5745 2967 5745 2967 5746 2966 5746 2968 5746 2973 5747 2966 5747 2967 5747 2967 5748 2972 5748 2973 5748 2967 5749 2971 5749 2972 5749 2968 5750 2980 5750 2978 5750 2980 5751 2968 5751 2982 5751 3010 5752 2983 5752 2982 5752 3385 5753 3438 5753 3439 5753 3385 5754 2969 5754 3438 5754 3385 5755 2970 5755 2969 5755 3385 5756 2971 5756 2970 5756 3385 5757 2972 5757 2971 5757 3385 5758 2973 5758 2972 5758 2973 5759 3385 5759 3003 5759 3418 5760 2975 5760 3417 5760 3416 5761 3417 5761 2975 5761 2975 5762 2976 5762 3416 5762 2979 5763 3416 5763 2977 5763 3416 5764 2976 5764 2977 5764 2977 5765 2978 5765 2979 5765 2981 5766 2979 5766 2980 5766 2979 5767 2978 5767 2980 5767 2980 5768 2982 5768 2981 5768 2984 5769 2981 5769 2982 5769 2982 5770 2983 5770 2984 5770 2983 5771 1156 5771 1151 5771 2984 5772 2983 5772 1151 5772 2986 5773 2987 5773 3414 5773 3025 5774 2986 5774 3414 5774 2988 5775 2987 5775 2986 5775 2989 5776 2988 5776 2986 5776 2990 5777 2989 5777 2986 5777 2990 5778 2986 5778 2991 5778 1155 5779 2992 5779 2993 5779 1155 5780 2993 5780 2994 5780 1155 5781 2994 5781 1109 5781 1155 5782 2995 5782 2992 5782 2996 5783 2992 5783 2995 5783 1148 5784 1147 5784 3023 5784 1148 5785 3023 5785 3399 5785 1148 5786 3399 5786 3398 5786 2999 5787 1148 5787 3398 5787 1149 5788 1148 5788 2999 5788 2999 5789 3000 5789 1149 5789 2999 5790 3398 5790 3001 5790 3000 5791 2999 5791 3001 5791 1150 5792 1149 5792 3000 5792 1151 5793 1150 5793 3000 5793 3000 5794 2985 5794 1151 5794 1151 5795 2985 5795 2984 5795 3004 5796 3002 5796 3003 5796 3003 5797 3005 5797 3004 5797 3005 5798 3006 5798 3004 5798 2995 5799 1155 5799 3007 5799 3007 5800 1153 5800 1152 5800 3007 5801 1152 5801 1156 5801 3008 5802 3007 5802 1156 5802 2983 5803 3010 5803 3008 5803 1156 5804 2983 5804 3008 5804 3013 5805 2996 5805 3012 5805 1109 5806 2994 5806 3014 5806 3014 5807 3013 5807 2986 5807 3014 5808 2994 5808 2993 5808 3014 5809 2993 5809 2992 5809 3014 5810 2992 5810 3013 5810 2996 5811 3013 5811 2992 5811 2986 5812 3013 5812 2991 5812 3000 5813 3390 5813 3391 5813 3000 5814 3391 5814 2985 5814 3389 5815 3390 5815 3000 5815 3000 5816 3001 5816 3389 5816 3389 5817 3001 5817 3398 5817 3386 5818 2984 5818 2985 5818 3386 5819 2985 5819 3391 5819 3415 5820 3414 5820 3410 5820 3414 5821 2987 5821 3409 5821 3408 5822 3409 5822 2987 5822 2987 5823 2988 5823 3408 5823 3407 5824 3408 5824 2988 5824 2988 5825 2989 5825 3407 5825 3406 5826 3407 5826 2989 5826 2989 5827 2990 5827 3406 5827 3405 5828 3406 5828 2990 5828 1154 5829 1153 5829 3007 5829 2991 5830 3015 5830 3022 5830 2991 5831 3020 5831 3015 5831 3021 5832 3015 5832 3020 5832 3006 5833 3015 5833 3021 5833 3006 5834 3005 5834 3015 5834 3005 5835 3003 5835 3015 5835 3385 5836 3015 5836 3003 5836 3402 5837 3015 5837 3385 5837 3403 5838 3015 5838 3402 5838 3404 5839 3015 5839 3403 5839 3022 5840 3015 5840 3404 5840 3006 5841 3021 5841 3004 5841 3004 5842 3016 5842 3002 5842 3004 5843 3018 5843 3016 5843 3004 5844 3017 5844 3018 5844 3011 5845 3018 5845 3017 5845 3008 5846 3011 5846 3017 5846 3009 5847 3008 5847 3017 5847 3009 5848 3017 5848 3019 5848 3021 5849 3017 5849 3004 5849 3021 5850 3019 5850 3017 5850 3404 5851 2990 5851 3022 5851 3009 5852 3019 5852 2998 5852 2998 5853 3019 5853 2997 5853 2990 5854 3404 5854 3405 5854 3012 5855 3021 5855 3020 5855 3020 5856 2991 5856 3012 5856 3012 5857 2991 5857 3013 5857 3021 5858 3012 5858 3019 5858 3012 5859 2996 5859 2997 5859 3012 5860 2997 5860 3019 5860 3007 5861 3008 5861 3009 5861 3007 5862 3009 5862 2998 5862 3007 5863 2998 5863 2997 5863 3022 5864 2990 5864 2991 5864 3008 5865 3010 5865 3011 5865 2995 5866 2997 5866 2996 5866 2995 5867 3007 5867 2997 5867 1154 5868 3007 5868 1155 5868 3026 5869 3027 5869 3028 5869 3026 5870 3028 5870 3029 5870 3030 5871 3026 5871 3029 5871 3031 5872 3027 5872 3026 5872 3026 5873 3032 5873 3031 5873 3031 5874 3032 5874 3033 5874 3294 5875 3031 5875 3033 5875 3294 5876 3295 5876 3031 5876 3033 5877 3034 5877 3294 5877 3296 5878 3294 5878 3034 5878 3035 5879 3296 5879 3034 5879 3035 5880 3298 5880 3305 5880 3296 5881 3035 5881 3305 5881 3037 5882 3038 5882 3039 5882 3040 5883 3038 5883 3037 5883 3037 5884 3041 5884 3040 5884 3451 5885 3040 5885 3041 5885 3041 5886 3042 5886 3451 5886 3415 5887 3451 5887 3042 5887 3044 5888 3043 5888 3025 5888 3025 5889 3042 5889 3044 5889 3042 5890 3025 5890 3415 5890 3045 5891 3046 5891 3047 5891 3043 5892 3045 5892 3047 5892 3043 5893 3047 5893 3048 5893 3043 5894 3048 5894 3049 5894 3043 5895 3049 5895 3050 5895 3051 5896 3043 5896 3050 5896 3043 5897 3051 5897 3025 5897 3025 5898 3051 5898 2986 5898 3052 5899 3036 5899 3299 5899 1119 5900 1122 5900 3023 5900 1118 5901 1119 5901 3023 5901 3452 5902 1121 5902 3300 5902 1127 5903 1121 5903 3452 5903 3452 5904 3453 5904 1127 5904 1126 5905 1127 5905 3453 5905 3453 5906 3053 5906 1126 5906 1125 5907 1126 5907 3053 5907 3454 5908 1124 5908 1125 5908 3053 5909 3454 5909 1125 5909 1123 5910 1124 5910 3454 5910 3454 5911 3397 5911 1123 5911 1123 5912 3397 5912 3399 5912 1123 5913 3399 5913 3023 5913 1122 5914 1123 5914 3023 5914 1121 5915 1120 5915 3300 5915 1120 5916 1085 5916 3300 5916 3303 5917 3031 5917 3295 5917 1074 5918 1114 5918 3303 5918 3054 5919 3027 5919 3031 5919 3303 5920 3054 5920 3031 5920 3303 5921 1114 5921 1115 5921 3303 5922 1115 5922 1116 5922 3303 5923 1116 5923 3055 5923 3303 5924 3055 5924 3056 5924 3054 5925 3303 5925 3056 5925 3027 5926 3054 5926 3057 5926 3027 5927 3057 5927 3058 5927 3028 5928 3027 5928 3058 5928 1111 5929 3063 5929 3059 5929 1111 5930 3059 5930 3060 5930 1112 5931 1111 5931 3060 5931 3063 5932 1111 5932 1110 5932 3061 5933 3063 5933 1110 5933 3061 5934 3050 5934 3049 5934 3061 5935 3049 5935 3048 5935 3061 5936 3048 5936 3062 5936 3061 5937 3062 5937 3063 5937 3051 5938 3050 5938 3061 5938 3061 5939 1110 5939 1109 5939 3053 5940 3453 5940 3396 5940 3454 5941 3053 5941 3396 5941 3040 5942 3401 5942 3038 5942 3412 5943 3401 5943 3040 5943 3040 5944 3451 5944 3412 5944 3039 5945 3038 5945 3024 5945 3052 5946 3298 5946 3035 5946 3052 5947 3035 5947 3034 5947 3299 5948 3298 5948 3052 5948 3028 5949 3064 5949 3065 5949 3029 5950 3028 5950 3065 5950 3065 5951 3066 5951 3029 5951 3029 5952 3066 5952 3067 5952 3030 5953 3029 5953 3067 5953 3067 5954 3066 5954 3068 5954 3069 5955 3067 5955 3068 5955 3068 5956 3070 5956 3069 5956 3070 5957 3071 5957 3072 5957 3073 5958 3072 5958 3071 5958 3069 5959 3070 5959 3072 5959 3069 5960 3072 5960 3074 5960 3069 5961 3074 5961 3075 5961 3069 5962 3075 5962 3076 5962 3077 5963 3069 5963 3076 5963 3076 5964 3078 5964 3077 5964 3079 5965 3073 5965 3071 5965 3071 5966 3080 5966 3079 5966 3077 5967 3078 5967 3081 5967 3077 5968 3081 5968 3082 5968 3083 5969 3077 5969 3082 5969 3082 5970 3084 5970 3083 5970 3085 5971 3083 5971 3084 5971 3084 5972 3086 5972 3085 5972 3087 5973 3085 5973 3086 5973 3086 5974 3088 5974 3087 5974 3087 5975 3088 5975 3089 5975 3087 5976 3089 5976 3090 5976 3091 5977 3087 5977 3090 5977 3090 5978 3092 5978 3091 5978 3095 5979 3096 5979 3094 5979 3093 5980 3095 5980 3094 5980 3091 5981 3092 5981 3096 5981 3096 5982 3095 5982 3097 5982 3097 5983 3091 5983 3096 5983 3095 5984 3098 5984 3097 5984 3097 5985 3098 5985 3099 5985 3100 5986 3097 5986 3099 5986 3099 5987 3101 5987 3047 5987 3047 5988 3101 5988 3102 5988 3048 5989 3047 5989 3102 5989 3084 5990 3082 5990 3086 5990 3088 5991 3086 5991 3082 5991 3082 5992 3103 5992 3088 5992 3104 5993 3088 5993 3103 5993 3103 5994 3105 5994 3104 5994 3106 5995 3104 5995 3105 5995 3105 5996 3107 5996 3106 5996 3108 5997 3106 5997 3107 5997 3107 5998 3109 5998 3108 5998 3110 5999 3108 5999 3109 5999 3109 6000 3306 6000 3110 6000 3218 6001 3110 6001 3306 6001 3111 6002 3113 6002 3112 6002 3114 6003 3112 6003 3113 6003 3113 6004 3115 6004 3114 6004 3116 6005 3114 6005 3115 6005 3115 6006 3117 6006 3116 6006 3116 6007 3117 6007 3118 6007 3119 6008 3116 6008 3118 6008 3118 6009 3308 6009 3119 6009 3247 6010 3119 6010 3308 6010 3096 6011 3120 6011 3094 6011 3121 6012 3094 6012 3120 6012 3120 6013 3122 6013 3121 6013 3123 6014 3121 6014 3122 6014 3122 6015 3124 6015 3123 6015 3125 6016 3123 6016 3124 6016 3124 6017 3126 6017 3125 6017 3127 6018 3125 6018 3126 6018 3126 6019 3128 6019 3127 6019 3129 6020 3127 6020 3128 6020 3128 6021 3130 6021 3129 6021 3131 6022 3129 6022 3130 6022 3130 6023 3132 6023 3131 6023 3133 6024 3131 6024 3132 6024 3132 6025 3307 6025 3133 6025 3245 6026 3133 6026 3307 6026 3072 6027 3134 6027 3074 6027 3135 6028 3074 6028 3134 6028 3134 6029 3136 6029 3135 6029 3137 6030 3135 6030 3136 6030 3136 6031 3138 6031 3137 6031 3139 6032 3137 6032 3138 6032 3138 6033 3140 6033 3139 6033 3141 6034 3139 6034 3140 6034 3140 6035 3142 6035 3141 6035 3143 6036 3141 6036 3142 6036 3142 6037 3144 6037 3143 6037 3145 6038 3143 6038 3144 6038 3144 6039 3146 6039 3145 6039 3147 6040 3145 6040 3146 6040 3146 6041 3309 6041 3147 6041 3252 6042 3147 6042 3309 6042 3135 6043 3075 6043 3074 6043 3137 6044 3078 6044 3076 6044 3137 6045 3076 6045 3075 6045 3135 6046 3137 6046 3075 6046 3137 6047 3139 6047 3078 6047 3148 6048 3082 6048 3081 6048 3148 6049 3081 6049 3078 6049 3078 6050 3139 6050 3141 6050 3148 6051 3078 6051 3141 6051 3103 6052 3082 6052 3148 6052 3141 6053 3143 6053 3148 6053 3148 6054 3143 6054 3145 6054 3149 6055 3148 6055 3145 6055 3149 6056 3105 6056 3103 6056 3148 6057 3149 6057 3103 6057 3107 6058 3105 6058 3149 6058 3145 6059 3147 6059 3149 6059 3255 6060 3109 6060 3107 6060 3149 6061 3255 6061 3107 6061 3149 6062 3147 6062 3252 6062 3149 6063 3252 6063 3310 6063 3255 6064 3149 6064 3310 6064 3109 6065 3255 6065 3253 6065 3306 6066 3109 6066 3253 6066 3096 6067 3092 6067 3120 6067 3122 6068 3120 6068 3092 6068 3092 6069 3090 6069 3122 6069 3122 6070 3090 6070 3150 6070 3124 6071 3122 6071 3150 6071 3151 6072 3126 6072 3124 6072 3150 6073 3151 6073 3124 6073 3089 6074 3088 6074 3151 6074 3151 6075 3150 6075 3089 6075 3088 6076 3104 6076 3151 6076 3128 6077 3126 6077 3151 6077 3151 6078 3104 6078 3106 6078 3152 6079 3151 6079 3106 6079 3152 6080 3130 6080 3128 6080 3151 6081 3152 6081 3128 6081 3106 6082 3108 6082 3152 6082 3132 6083 3130 6083 3152 6083 3152 6084 3108 6084 3110 6084 3110 6085 3218 6085 3152 6085 3152 6086 3218 6086 3259 6086 3261 6087 3152 6087 3259 6087 3152 6088 3261 6088 3132 6088 3132 6089 3261 6089 3263 6089 3307 6090 3132 6090 3263 6090 3072 6091 3153 6091 3134 6091 3136 6092 3134 6092 3153 6092 3153 6093 3154 6093 3136 6093 3138 6094 3136 6094 3154 6094 3154 6095 3155 6095 3138 6095 3140 6096 3138 6096 3155 6096 3156 6097 3142 6097 3140 6097 3155 6098 3156 6098 3140 6098 3157 6099 3112 6099 3156 6099 3158 6100 3157 6100 3156 6100 3159 6101 3158 6101 3156 6101 3156 6102 3155 6102 3159 6102 3112 6103 3114 6103 3156 6103 3144 6104 3142 6104 3156 6104 3156 6105 3114 6105 3116 6105 3156 6106 3116 6106 3119 6106 3156 6107 3119 6107 3247 6107 3156 6108 3247 6108 3312 6108 3269 6109 3156 6109 3312 6109 3269 6110 3146 6110 3144 6110 3156 6111 3269 6111 3144 6111 3146 6112 3269 6112 3271 6112 3309 6113 3146 6113 3271 6113 3028 6114 3058 6114 3064 6114 3160 6115 3064 6115 3058 6115 3058 6116 3057 6116 3160 6116 3161 6117 3160 6117 3057 6117 3057 6118 3056 6118 3161 6118 3162 6119 3161 6119 3056 6119 3056 6120 3055 6120 3162 6120 3163 6121 3162 6121 3055 6121 3055 6122 1116 6122 3163 6122 1117 6123 3163 6123 1116 6123 3102 6124 3164 6124 3048 6124 3062 6125 3048 6125 3164 6125 3164 6126 3165 6126 3062 6126 3063 6127 3062 6127 3165 6127 3165 6128 3166 6128 3063 6128 3059 6129 3063 6129 3166 6129 3166 6130 3167 6130 3059 6130 3060 6131 3059 6131 3167 6131 3167 6132 1113 6132 3060 6132 1112 6133 3060 6133 1113 6133 3095 6134 3168 6134 3098 6134 3164 6135 3102 6135 3101 6135 3169 6136 3099 6136 3098 6136 3099 6137 3169 6137 3101 6137 3101 6138 3170 6138 3164 6138 3170 6139 3101 6139 3169 6139 3098 6140 3171 6140 3169 6140 3171 6141 3098 6141 3168 6141 3172 6142 3169 6142 3171 6142 3169 6143 3172 6143 3170 6143 3165 6144 3164 6144 3170 6144 3170 6145 3173 6145 3165 6145 3173 6146 3170 6146 3172 6146 3168 6147 3174 6147 3171 6147 3175 6148 3172 6148 3171 6148 3172 6149 3175 6149 3173 6149 3166 6150 3165 6150 3173 6150 3177 6151 3173 6151 3175 6151 3173 6152 3177 6152 3166 6152 3174 6153 1104 6153 3171 6153 3171 6154 3176 6154 3175 6154 3176 6155 3171 6155 1104 6155 1104 6156 1090 6156 3176 6156 3167 6157 3166 6157 3177 6157 3175 6158 1094 6158 3177 6158 1094 6159 3175 6159 3176 6159 1092 6160 3176 6160 1090 6160 3176 6161 1092 6161 1094 6161 1113 6162 3167 6162 3177 6162 1094 6163 1097 6163 3177 6163 3177 6164 1097 6164 1113 6164 1089 6165 1107 6165 3178 6165 3179 6166 3071 6166 3070 6166 3179 6167 3070 6167 3187 6167 3178 6168 3179 6168 3187 6168 3179 6169 3178 6169 1107 6169 3080 6170 3071 6170 3179 6170 1107 6171 1399 6171 3179 6171 3180 6172 3179 6172 1399 6172 3180 6173 3181 6173 3182 6173 3182 6174 3080 6174 3179 6174 3183 6175 3180 6175 1399 6175 1399 6176 1398 6176 3183 6176 1397 6177 3184 6177 3183 6177 1398 6178 1397 6178 3183 6178 3185 6179 3184 6179 1397 6179 1397 6180 1106 6180 3185 6180 3185 6181 3168 6181 3093 6181 3185 6182 1106 6182 1104 6182 3185 6183 1104 6183 3174 6183 3168 6184 3185 6184 3174 6184 3095 6185 3093 6185 3168 6185 3064 6186 3160 6186 3065 6186 3186 6187 3065 6187 3160 6187 3065 6188 3186 6188 3066 6188 3187 6189 3070 6189 3068 6189 3068 6190 3188 6190 3187 6190 3188 6191 3068 6191 3066 6191 3066 6192 3189 6192 3188 6192 3189 6193 3066 6193 3186 6193 3186 6194 3190 6194 3189 6194 3190 6195 3186 6195 3160 6195 3160 6196 3161 6196 3190 6196 3178 6197 3187 6197 3188 6197 3188 6198 3191 6198 3178 6198 3191 6199 3188 6199 3189 6199 3192 6200 3189 6200 3190 6200 3189 6201 3192 6201 3191 6201 3193 6202 3190 6202 3161 6202 3190 6203 3193 6203 3192 6203 3161 6204 3162 6204 3193 6204 1089 6205 3178 6205 3191 6205 3194 6206 3191 6206 3192 6206 3191 6207 3194 6207 1089 6207 3195 6208 3192 6208 3193 6208 3192 6209 3195 6209 3194 6209 3196 6210 3193 6210 3162 6210 3193 6211 3196 6211 3195 6211 1099 6212 1089 6212 3194 6212 1099 6213 3194 6213 3195 6213 3162 6214 3163 6214 3196 6214 1102 6215 3195 6215 3196 6215 3195 6216 1102 6216 1099 6216 3163 6217 1117 6217 3196 6217 1103 6218 3196 6218 1117 6218 3196 6219 1103 6219 1102 6219 3199 6220 3182 6220 3181 6220 3200 6221 3182 6221 3199 6221 3199 6222 3198 6222 3200 6222 3201 6223 3200 6223 3198 6223 3198 6224 3197 6224 3201 6224 3201 6225 3197 6225 3111 6225 3201 6226 3111 6226 3112 6226 3067 6227 3069 6227 3077 6227 3067 6228 3077 6228 3083 6228 3067 6229 3083 6229 3085 6229 3067 6230 3085 6230 3087 6230 3067 6231 3087 6231 3091 6231 3067 6232 3091 6232 3097 6232 3100 6233 3067 6233 3097 6233 3100 6234 3045 6234 3043 6234 3100 6235 3043 6235 3044 6235 3100 6236 3044 6236 3042 6236 3100 6237 3042 6237 3041 6237 3100 6238 3041 6238 3037 6238 3100 6239 3037 6239 3039 6239 3039 6240 3024 6240 3036 6240 3100 6241 3039 6241 3036 6241 3100 6242 3036 6242 3052 6242 3100 6243 3052 6243 3034 6243 3100 6244 3034 6244 3033 6244 3100 6245 3033 6245 3032 6245 3100 6246 3032 6246 3026 6246 3100 6247 3026 6247 3030 6247 3067 6248 3100 6248 3030 6248 3046 6249 3045 6249 3100 6249 3054 6250 3056 6250 3057 6250 3090 6251 3089 6251 3150 6251 3181 6252 3180 6252 3183 6252 3183 6253 3184 6253 3181 6253 3179 6254 3180 6254 3182 6254 3112 6255 3157 6255 3201 6255 3182 6256 3200 6256 3201 6256 3157 6257 3182 6257 3201 6257 3157 6258 3158 6258 3182 6258 3158 6259 3159 6259 3182 6259 3080 6260 3182 6260 3159 6260 3080 6261 3159 6261 3155 6261 3080 6262 3155 6262 3154 6262 3079 6263 3080 6263 3154 6263 3079 6264 3154 6264 3153 6264 3073 6265 3079 6265 3153 6265 3072 6266 3073 6266 3153 6266 3094 6267 3211 6267 3217 6267 3217 6268 3211 6268 3216 6268 3216 6269 3211 6269 3210 6269 3216 6270 3210 6270 3215 6270 3215 6271 3210 6271 3209 6271 3215 6272 3209 6272 3205 6272 3215 6273 3205 6273 3204 6273 3206 6274 3204 6274 3205 6274 3207 6275 3204 6275 3206 6275 3207 6276 3202 6276 3204 6276 3204 6277 3202 6277 3203 6277 3214 6278 3202 6278 3207 6278 3185 6279 3204 6279 3184 6279 3202 6280 3214 6280 3111 6280 3202 6281 3111 6281 3197 6281 3198 6282 3202 6282 3197 6282 3202 6283 3198 6283 3203 6283 3199 6284 3203 6284 3198 6284 3203 6285 3199 6285 3204 6285 3199 6286 3181 6286 3204 6286 3204 6287 3185 6287 3215 6287 3184 6288 3204 6288 3181 6288 3215 6289 3185 6289 3093 6289 3245 6290 3311 6290 3133 6290 3133 6291 3311 6291 3265 6291 3208 6292 3131 6292 3265 6292 3265 6293 3131 6293 3133 6293 3265 6294 3267 6294 3208 6294 3208 6295 3267 6295 3308 6295 3208 6296 3308 6296 3118 6296 3208 6297 3118 6297 3212 6297 3208 6298 3212 6298 3213 6298 3131 6299 3208 6299 3129 6299 3214 6300 3208 6300 3213 6300 3208 6301 3205 6301 3209 6301 3205 6302 3208 6302 3206 6302 3206 6303 3208 6303 3207 6303 3207 6304 3208 6304 3214 6304 3209 6305 3127 6305 3208 6305 3208 6306 3127 6306 3129 6306 3127 6307 3209 6307 3125 6307 3210 6308 3125 6308 3209 6308 3125 6309 3210 6309 3123 6309 3211 6310 3123 6310 3210 6310 3123 6311 3211 6311 3121 6311 3094 6312 3121 6312 3211 6312 3115 6313 3212 6313 3117 6313 3212 6314 3115 6314 3213 6314 3113 6315 3213 6315 3115 6315 3213 6316 3113 6316 3214 6316 3111 6317 3214 6317 3113 6317 3093 6318 3216 6318 3215 6318 3216 6319 3093 6319 3217 6319 3217 6320 3093 6320 3094 6320 3117 6321 3212 6321 3118 6321 3047 6322 3100 6322 3099 6322 3046 6323 3100 6323 3047 6323 3024 6324 3401 6324 3036 6324 3024 6325 3038 6325 3401 6325 3220 6326 3218 6326 3219 6326 3221 6327 3220 6327 3219 6327 3224 6328 3222 6328 3219 6328 3223 6329 3225 6329 3221 6329 3219 6330 3226 6330 3224 6330 3276 6331 3221 6331 3225 6331 3227 6332 3224 6332 3226 6332 3225 6333 3228 6333 3276 6333 3226 6334 3229 6334 3227 6334 3230 6335 3276 6335 3228 6335 3231 6336 3227 6336 3229 6336 3228 6337 3232 6337 3230 6337 3233 6338 3230 6338 3232 6338 3229 6339 3234 6339 3231 6339 3232 6340 3235 6340 3233 6340 3236 6341 3231 6341 3234 6341 3233 6342 3235 6342 3237 6342 3238 6343 3233 6343 3237 6343 3239 6344 3240 6344 3236 6344 3234 6345 3239 6345 3236 6345 3241 6346 3240 6346 3239 6346 3237 6347 3241 6347 3238 6347 3242 6348 3238 6348 3241 6348 3243 6349 3242 6349 3241 6349 3239 6350 3243 6350 3241 6350 3246 6351 3245 6351 3244 6351 3250 6352 3251 6352 3252 6352 3254 6353 3226 6353 3253 6353 3256 6354 3254 6354 3255 6354 3256 6355 3252 6355 3251 6355 3257 6356 3256 6356 3251 6356 3221 6357 3218 6357 3220 6357 3218 6358 3221 6358 3258 6358 3258 6359 3260 6359 3259 6359 3260 6360 3262 6360 3261 6360 3262 6361 3244 6361 3263 6361 3246 6362 3264 6362 3245 6362 3264 6363 3266 6363 3265 6363 3266 6364 3248 6364 3267 6364 3249 6365 3268 6365 3247 6365 3268 6366 3270 6366 3269 6366 3270 6367 3250 6367 3271 6367 3272 6368 3226 6368 3254 6368 3254 6369 3256 6369 3272 6369 3273 6370 3272 6370 3256 6370 3256 6371 3257 6371 3273 6371 3258 6372 3274 6372 3260 6372 3262 6373 3260 6373 3274 6373 3274 6374 3275 6374 3262 6374 3262 6375 3275 6375 3244 6375 3277 6376 3229 6376 3226 6376 3272 6377 3277 6377 3226 6377 3273 6378 3257 6378 3277 6378 3272 6379 3273 6379 3277 6379 3257 6380 3278 6380 3277 6380 3234 6381 3229 6381 3277 6381 3279 6382 3277 6382 3278 6382 3279 6383 3239 6383 3234 6383 3277 6384 3279 6384 3234 6384 3278 6385 3280 6385 3279 6385 3243 6386 3239 6386 3279 6386 3279 6387 3280 6387 3281 6387 3282 6388 3279 6388 3281 6388 3279 6389 3282 6389 3243 6389 3242 6390 3243 6390 3282 6390 3281 6391 3283 6391 3282 6391 3284 6392 3282 6392 3283 6392 3282 6393 3284 6393 3242 6393 3238 6394 3242 6394 3284 6394 3283 6395 3285 6395 3284 6395 3286 6396 3233 6396 3238 6396 3284 6397 3286 6397 3238 6397 3286 6398 3284 6398 3285 6398 3230 6399 3233 6399 3286 6399 3285 6400 3244 6400 3286 6400 3274 6401 3276 6401 3230 6401 3286 6402 3274 6402 3230 6402 3286 6403 3244 6403 3275 6403 3286 6404 3275 6404 3274 6404 3258 6405 3276 6405 3274 6405 3276 6406 3258 6406 3221 6406 3247 6407 3248 6407 3249 6407 3249 6408 3288 6408 3287 6408 3248 6409 3288 6409 3249 6409 3257 6410 3251 6410 3250 6410 3244 6411 3285 6411 3289 6411 3289 6411 3246 6411 3244 6411 3280 6412 3278 6412 3290 6412 3290 6412 3291 6412 3280 6412 3281 6413 3280 6413 3291 6413 3291 6413 3292 6413 3281 6413 3292 6414 3293 6414 3283 6414 3283 6414 3281 6414 3292 6414 3293 6415 3289 6415 3285 6415 3285 6415 3283 6415 3293 6415 3278 6416 3257 6416 3250 6416 3250 6416 3290 6416 3278 6416 3270 6417 3290 6417 3250 6417 3268 6418 3290 6418 3270 6418 3287 6419 3291 6419 3290 6419 3287 6420 3292 6420 3291 6420 3287 6421 3288 6421 3292 6421 3288 6422 3293 6422 3292 6422 3289 6423 3293 6423 3288 6423 3264 6424 3246 6424 3289 6424 3264 6425 3289 6425 3266 6425 3219 6426 3223 6426 3221 6426 3219 6427 3222 6427 3223 6427 3219 6428 3253 6428 3226 6428 3268 6429 3287 6429 3290 6429 3249 6430 3287 6430 3268 6430 3248 6431 3266 6431 3288 6431 3266 6432 3289 6432 3288 6432 3296 6433 3297 6433 3295 6433 3294 6434 3296 6434 3295 6434 3304 6435 3299 6435 3036 6435 3301 6436 3452 6436 3300 6436 1085 6437 1086 6437 3300 6437 3303 6438 3295 6438 3297 6438 3303 6439 3302 6439 1074 6439 3452 6440 3301 6440 3456 6440 3456 6441 3455 6441 3452 6441 3305 6442 3298 6442 3299 6442 3307 6443 3244 6443 3245 6443 3308 6444 3248 6444 3247 6444 3309 6445 3250 6445 3252 6445 3253 6446 3255 6446 3254 6446 3255 6447 3310 6447 3256 6447 3256 6448 3310 6448 3252 6448 3259 6449 3218 6449 3258 6449 3261 6450 3259 6450 3260 6450 3263 6451 3261 6451 3262 6451 3307 6452 3263 6452 3244 6452 3264 6453 3311 6453 3245 6453 3265 6454 3311 6454 3264 6454 3267 6455 3265 6455 3266 6455 3308 6456 3267 6456 3248 6456 3268 6457 3312 6457 3247 6457 3269 6458 3312 6458 3268 6458 3271 6459 3269 6459 3270 6459 3309 6460 3271 6460 3250 6460 3219 6461 3218 6461 3306 6461 3306 6462 3253 6462 3219 6462 1082 6463 1080 6463 3356 6463 3300 6464 3358 6464 3357 6464 3301 6465 3300 6465 3357 6465 3327 6466 3321 6466 3318 6466 3327 6467 3326 6467 3321 6467 3364 6468 3313 6468 3329 6468 3329 6469 3313 6469 3333 6469 3333 6470 3313 6470 3332 6470 3332 6471 3313 6471 3331 6471 3331 6472 3313 6472 3340 6472 3340 6473 3313 6473 3362 6473 3332 6474 3330 6474 3333 6474 3342 6475 3320 6475 3330 6475 3330 6476 3320 6476 3319 6476 3321 6477 3319 6477 3320 6477 3359 6478 3319 6478 3321 6478 3325 6479 3359 6479 3321 6479 3359 6480 3323 6480 3319 6480 3333 6481 3330 6481 3319 6481 3333 6482 3319 6482 3323 6482 3339 6483 3413 6483 3336 6483 3340 6484 3413 6484 3339 6484 3321 6485 3326 6485 3325 6485 3304 6486 3305 6486 3299 6486 3367 6487 3305 6487 3304 6487 3366 6488 3367 6488 3304 6488 3365 6489 3366 6489 3304 6489 3304 6490 3362 6490 3365 6490 3313 6491 3365 6491 3362 6491 3413 6492 3340 6492 3362 6492 3350 6493 3368 6493 3349 6493 3356 6494 3368 6494 3350 6494 3350 6495 3351 6495 3356 6495 3355 6496 3356 6496 3351 6496 3351 6497 3352 6497 3355 6497 3352 6498 3357 6498 3355 6498 3352 6499 3353 6499 3357 6499 3301 6500 3357 6500 3353 6500 3460 6501 3301 6501 3353 6501 3384 6502 3465 6502 3314 6502 3465 6503 3458 6503 3314 6503 3314 6504 3344 6504 3384 6504 3382 6505 3384 6505 3344 6505 3344 6506 3345 6506 3382 6506 3379 6507 3382 6507 3345 6507 3345 6508 3346 6508 3379 6508 3377 6509 3379 6509 3346 6509 3346 6510 3347 6510 3377 6510 3374 6511 3377 6511 3347 6511 3347 6512 3348 6512 3374 6512 3372 6513 3374 6513 3348 6513 3348 6514 3349 6514 3372 6514 3372 6515 3349 6515 3368 6515 3456 6516 3301 6516 3460 6516 3461 6517 3459 6517 3354 6517 3459 6518 3461 6518 3432 6518 3445 6519 3463 6519 3459 6519 3343 6520 3341 6520 3317 6520 3315 6521 3317 6521 3341 6521 3315 6522 3318 6522 3317 6522 3315 6523 3373 6523 3318 6523 3315 6524 3375 6524 3373 6524 3315 6525 3376 6525 3375 6525 3378 6526 3376 6526 3315 6526 3316 6527 3315 6527 3337 6527 3315 6528 3341 6528 3337 6528 3315 6529 3316 6529 3378 6529 3316 6530 3380 6530 3378 6530 3337 6531 3338 6531 3316 6531 3381 6532 3380 6532 3316 6532 3316 6533 3459 6533 3381 6533 3459 6534 3383 6534 3381 6534 3459 6535 3463 6535 3383 6535 3316 6536 3354 6536 3459 6536 3316 6537 3338 6537 3354 6537 3317 6538 3342 6538 3343 6538 3320 6539 3342 6539 3317 6539 3321 6540 3320 6540 3317 6540 3317 6541 3318 6541 3321 6541 3318 6542 3373 6542 3328 6542 3328 6543 3327 6543 3318 6543 3324 6544 3364 6544 3329 6544 3322 6545 3329 6545 3333 6545 3329 6546 3322 6546 3324 6546 3333 6547 3323 6547 3322 6547 1072 6548 3324 6548 3322 6548 3322 6549 3360 6549 1072 6549 3302 6550 1073 6550 1074 6550 3302 6551 3303 6551 3297 6551 3302 6552 3364 6552 3324 6552 3302 6553 3363 6553 3364 6553 3302 6554 3297 6554 3363 6554 3302 6555 3324 6555 1073 6555 3324 6556 1072 6556 1073 6556 1075 6557 3361 6557 1076 6557 1077 6558 1076 6558 3361 6558 1077 6559 3359 6559 3325 6559 1077 6560 3361 6560 3359 6560 3325 6561 1078 6561 1077 6561 3325 6562 1079 6562 1078 6562 3325 6563 3369 6563 1079 6563 3371 6564 3369 6564 3326 6564 3369 6565 3325 6565 3326 6565 3326 6566 3327 6566 3371 6566 3370 6567 3371 6567 3327 6567 3327 6568 3328 6568 3370 6568 3373 6569 3370 6569 3328 6569 3342 6570 3330 6570 3331 6570 3332 6571 3331 6571 3330 6571 3335 6572 3334 6572 3354 6572 3354 6573 3338 6573 3335 6573 3340 6574 3339 6574 3341 6574 3339 6575 3337 6575 3341 6575 3339 6576 3338 6576 3337 6576 3340 6577 3341 6577 3331 6577 3341 6578 3343 6578 3331 6578 3342 6579 3331 6579 3343 6579 3395 6580 3347 6580 3346 6580 3395 6581 3348 6581 3347 6581 3349 6582 3348 6582 3395 6582 3395 6583 3350 6583 3349 6583 3395 6584 3351 6584 3350 6584 3395 6585 3352 6585 3351 6585 3395 6586 3353 6586 3352 6586 3395 6587 3460 6587 3353 6587 3461 6588 3354 6588 3334 6588 3356 6589 1080 6589 3368 6589 3358 6590 3356 6590 3355 6590 3355 6591 3357 6591 3358 6591 3356 6592 3358 6592 1082 6592 3358 6593 1083 6593 1082 6593 1084 6594 1083 6594 3358 6594 1084 6595 3358 6595 3300 6595 1086 6596 1084 6596 3300 6596 3361 6597 3360 6597 3359 6597 1072 6598 3360 6598 3361 6598 3361 6599 1075 6599 1072 6599 3362 6600 3304 6600 3036 6600 3364 6601 3365 6601 3313 6601 3365 6602 3364 6602 3363 6602 3365 6603 3363 6603 3366 6603 3363 6604 3367 6604 3366 6604 3296 6605 3367 6605 3363 6605 3367 6606 3296 6606 3305 6606 3363 6607 3297 6607 3296 6607 3368 6608 1080 6608 3372 6608 1079 6609 3369 6609 1081 6609 1080 6610 1081 6610 3369 6610 3369 6611 3371 6611 1080 6611 3371 6612 3372 6612 1080 6612 3374 6613 3372 6613 3373 6613 3372 6614 3370 6614 3373 6614 3372 6615 3371 6615 3370 6615 3373 6616 3375 6616 3374 6616 3377 6617 3374 6617 3375 6617 3375 6618 3376 6618 3377 6618 3379 6619 3377 6619 3378 6619 3377 6620 3376 6620 3378 6620 3378 6621 3380 6621 3379 6621 3382 6622 3379 6622 3380 6622 3380 6623 3381 6623 3382 6623 3384 6624 3382 6624 3383 6624 3382 6625 3381 6625 3383 6625 3383 6626 3463 6626 3384 6626 3465 6627 3384 6627 3463 6627 3400 6628 3362 6628 3036 6628 3362 6629 3400 6629 3413 6629 3409 6630 3410 6630 3414 6630 3410 6631 3411 6631 3415 6631 3387 6632 3399 6632 3392 6632 3398 6633 3399 6633 3387 6633 3387 6634 3388 6634 3398 6634 3388 6635 3389 6635 3398 6635 3397 6636 3392 6636 3399 6636 3397 6637 3393 6637 3392 6637 3386 6638 3391 6638 3395 6638 3395 6639 3387 6639 3392 6639 3395 6640 3388 6640 3387 6640 3395 6641 3389 6641 3388 6641 3395 6642 3390 6642 3389 6642 3395 6643 3391 6643 3390 6643 3392 6644 3393 6644 3395 6644 3393 6645 3394 6645 3395 6645 3396 6646 3395 6646 3394 6646 3413 6647 3405 6647 3404 6647 3413 6648 3406 6648 3405 6648 3413 6649 3407 6649 3406 6649 3413 6650 3408 6650 3407 6650 3413 6651 3409 6651 3408 6651 3413 6652 3410 6652 3409 6652 3413 6653 3411 6653 3410 6653 3413 6654 3412 6654 3411 6654 3419 6655 3420 6655 3418 6655 3417 6656 3419 6656 3418 6656 3421 6657 3422 6657 3420 6657 3419 6658 3421 6658 3420 6658 3423 6659 3422 6659 3421 6659 3424 6660 3425 6660 3423 6660 3421 6661 3424 6661 3423 6661 3424 6662 3426 6662 3425 6662 3413 6663 3404 6663 3403 6663 3413 6664 3403 6664 3402 6664 3430 6665 3429 6665 3428 6665 3428 6666 3431 6666 3430 6666 3430 6667 3431 6667 3432 6667 3433 6668 3430 6668 3432 6668 3440 6669 3385 6669 3439 6669 3438 6670 3442 6670 3441 6670 3442 6671 3428 6671 3441 6671 3429 6672 3441 6672 3428 6672 3443 6673 3422 6673 3423 6673 3444 6674 3443 6674 3423 6674 3444 6675 3431 6675 3428 6675 3444 6676 3428 6676 3443 6676 3423 6677 3425 6677 3444 6677 3444 6678 3425 6678 3427 6678 3444 6679 3445 6679 3431 6679 3443 6680 3442 6680 3438 6680 3446 6681 3443 6681 3438 6681 3446 6682 3418 6682 3420 6682 3446 6683 3420 6683 3422 6683 3446 6684 3422 6684 3443 6684 3442 6685 3443 6685 3428 6685 3426 6686 3424 6686 3447 6686 3419 6687 3449 6687 3448 6687 3421 6688 3419 6688 3448 6688 3437 6689 3449 6689 3419 6689 3419 6690 3417 6690 3437 6690 3436 6691 3437 6691 3417 6691 3417 6692 3416 6692 3436 6692 3434 6693 3436 6693 3416 6693 3402 6694 3385 6694 3413 6694 3413 6695 3385 6695 3440 6695 3424 6696 3450 6696 3447 6696 3421 6697 3450 6697 3424 6697 3421 6698 3448 6698 3450 6698 3439 6699 3413 6699 3440 6699 3395 6700 3434 6700 3435 6700 3395 6701 3435 6701 3386 6701 3453 6702 3452 6702 3455 6702 3455 6703 3396 6703 3453 6703 3396 6704 3394 6704 3454 6704 3397 6705 3454 6705 3394 6705 3394 6706 3393 6706 3397 6706 3411 6707 3412 6707 3451 6707 3451 6708 3415 6708 3411 6708 3447 6709 3457 6709 3426 6709 3465 6710 3426 6710 3457 6710 3458 6711 3465 6711 3457 6711 3445 6712 3459 6712 3432 6712 3445 6713 3464 6713 3463 6713 3445 6714 3427 6714 3464 6714 3445 6715 3432 6715 3431 6715 3445 6716 3444 6716 3427 6716 3456 6717 3460 6717 3395 6717 3455 6718 3456 6718 3395 6718 3395 6719 3396 6719 3455 6719 3334 6720 3462 6720 3461 6720 3432 6721 3461 6721 3462 6721 3462 6722 3433 6722 3432 6722 3464 6723 3465 6723 3463 6723 3426 6724 3465 6724 3427 6724 3465 6725 3464 6725 3427 6725 3426 6726 3427 6726 3425 6726 3400 6727 3036 6727 3401 6727 3400 6728 3401 6728 3412 6728 3400 6729 3412 6729 3413 6729 1511 6730 2222 6730 1512 6730 1500 6731 2222 6731 1511 6731 1446 6732 2222 6732 1500 6732 1395 6733 3466 6733 1396 6733 1392 6734 3466 6734 1395 6734 1390 6735 3466 6735 1392 6735 1388 6736 3466 6736 1390 6736 1386 6737 3466 6737 1388 6737 1378 6738 3466 6738 1386 6738 1377 6739 3466 6739 1378 6739 1375 6740 3466 6740 1377 6740 1371 6741 3466 6741 1375 6741 1370 6742 3466 6742 1371 6742 1370 6743 1374 6743 3466 6743 1374 6744 1376 6744 3466 6744 1376 6745 1379 6745 3466 6745 1379 6746 1385 6746 3466 6746 1385 6747 1387 6747 3466 6747 1387 6748 1389 6748 3466 6748 1389 6749 1391 6749 3466 6749 1391 6750 1393 6750 3466 6750 1393 6751 1394 6751 3466 6751 2312 6752 3467 6752 1146 6752 1435 6753 3467 6753 1434 6753 1125 6754 3467 6754 1145 6754 1145 6755 3467 6755 1429 6755 1429 6756 3467 6756 1430 6756 1430 6757 3467 6757 1435 6757 1124 6758 3467 6758 1125 6758 1123 6759 3467 6759 1124 6759 1122 6760 3467 6760 1123 6760 1122 6761 1146 6761 3467 6761 2394 6762 3466 6762 3467 6762 2312 6763 2394 6763 3467 6763 1394 6764 1433 6764 3467 6764 1394 6765 3467 6765 3466 6765 1432 6766 3467 6766 1433 6766 1431 6767 3467 6767 1432 6767 1431 6768 1434 6768 3467 6768 1281 6769 2484 6769 1284 6769 1281 6770 1289 6770 2484 6770 1289 6771 1294 6771 2484 6771 1223 6772 2484 6772 1294 6772 1223 6773 1302 6773 2484 6773 3468 6774 2394 6774 1654 6774 2301 6775 2650 6775 2392 6775 2646 6776 3468 6776 2867 6776 1636 6777 3468 6777 1654 6777 1636 6778 1654 6778 1666 6778 1654 6779 1656 6779 1666 6779 2245 6780 3469 6780 2244 6780 3469 6781 1636 6781 2244 6781 2867 6782 3469 6782 2245 6782 1636 6783 3469 6783 3468 6783 3469 6784 2867 6784 3468 6784 1655 6785 3470 6785 1661 6785 3470 6786 1654 6786 1661 6786 1653 6787 3470 6787 1655 6787 1653 6788 1655 6788 1721 6788 1653 6789 1654 6789 3470 6789 1380 6790 2393 6790 2395 6790 2393 6791 2394 6791 3468 6791 2650 6792 2301 6792 2649 6792 2393 6793 3468 6793 2301 6793 2393 6794 3466 6794 2394 6794 1380 6795 3466 6795 2393 6795 1380 6796 1396 6796 3466 6796 2649 6797 3471 6797 2246 6797 3468 6798 3471 6798 2301 6798 3471 6799 2649 6799 2301 6799 2646 6800 2647 6800 3471 6800 2246 6801 3471 6801 2647 6801 2646 6802 3471 6802 3468 6802 907 6803 908 6803 917 6803 3322 6804 3323 6804 3360 6804 3323 6805 3359 6805 3360 6805 934 6806 935 6806 970 6806 935 6807 969 6807 970 6807 406 6808 407 6808 442 6808 407 6809 441 6809 442 6809 2451 6810 2483 6810 2452 6810 2451 6811 2725 6811 2483 6811 2450 6812 2725 6812 2451 6812 2450 6813 2723 6813 2725 6813 2449 6814 2723 6814 2450 6814 2449 6815 2722 6815 2723 6815 2448 6816 2722 6816 2449 6816 2448 6817 2720 6817 2722 6817 2447 6818 2720 6818 2448 6818 2447 6819 2719 6819 2720 6819 2446 6820 2719 6820 2447 6820 2446 6821 2718 6821 2719 6821 2445 6822 2718 6822 2446 6822 2445 6823 2717 6823 2718 6823 2444 6824 2717 6824 2445 6824 2444 6825 2716 6825 2717 6825 2443 6826 2716 6826 2444 6826 2443 6827 2715 6827 2716 6827 2442 6828 2715 6828 2443 6828 2441 6829 2715 6829 2442 6829 2440 6830 2441 6830 2442 6830 2551 6831 2552 6831 2627 6831 2551 6832 2627 6832 2626 6832 2516 6833 2551 6833 2626 6833 2516 6834 2626 6834 2641 6834 2563 6835 2641 6835 2589 6835 2516 6836 2563 6836 2562 6836 2516 6837 2641 6837 2563 6837 2247 6838 2503 6838 2546 6838 2161 6839 2503 6839 2247 6839 2161 6840 2598 6840 2503 6840 2552 6841 2598 6841 2627 6841 2503 6842 2598 6842 2552 6842 2098 6843 2627 6843 2598 6843 2180 6844 2216 6844 2184 6844 2101 6845 2216 6845 2180 6845 2101 6846 2263 6846 2216 6846 2216 6847 2263 6847 2260 6847 2249 6848 2260 6848 2263 6848 2249 6849 2250 6849 2260 6849 2180 6850 2184 6850 2203 6850 2184 6851 2298 6851 2203 6851 2180 6852 2203 6852 2221 6852 427 6853 477 6853 428 6853 398 6854 477 6854 427 6854 398 6855 538 6855 477 6855 477 6856 538 6856 537 6856 477 6857 537 6857 528 6857 477 6858 528 6858 530 6858 477 6859 530 6859 529 6859 477 6860 529 6860 519 6860 477 6861 519 6861 518 6861 477 6862 518 6862 516 6862 512 6863 515 6863 495 6863 511 6864 512 6864 495 6864 521 6865 522 6865 495 6865 511 6866 495 6866 522 6866 515 6867 542 6867 495 6867 495 6868 542 6868 418 6868 419 6869 495 6869 418 6869 397 6870 495 6870 419 6870 3473 6871 1023 6871 947 6871 947 6872 1023 6872 946 6872 1023 6873 1068 6873 946 6873 1043 6874 1068 6874 1023 6874 1039 6875 1023 6875 3472 6875 1047 6876 3472 6876 1023 6876 1039 6877 1040 6877 1023 6877 1040 6878 1043 6878 1023 6878 949 6879 3473 6879 947 6879 1005 6880 3474 6880 3475 6880 1005 6881 1045 6881 3474 6881 1005 6882 1055 6882 1045 6882 1005 6883 1056 6883 1055 6883 1005 6884 1054 6884 1056 6884 1005 6885 1063 6885 1054 6885 1005 6886 1064 6886 1063 6886 926 6887 1064 6887 1005 6887 926 6888 1005 6888 955 6888 955 6889 1005 6889 956 6889 3345 6890 3395 6890 3346 6890 3344 6891 3395 6891 3345 6891 3344 6892 3458 6892 3395 6892 3395 6893 3458 6893 3457 6893 3395 6894 3457 6894 3447 6894 3395 6895 3447 6895 3450 6895 3395 6896 3450 6896 3448 6896 3395 6897 3448 6897 3437 6897 3395 6898 3437 6898 3436 6898 3395 6899 3436 6899 3434 6899 3336 6900 3413 6900 3335 6900 3335 6901 3413 6901 3334 6901 3413 6902 3462 6902 3334 6902 3433 6903 3462 6903 3413 6903 3429 6904 3413 6904 3441 6904 3439 6905 3441 6905 3413 6905 3429 6906 3430 6906 3413 6906 3430 6907 3433 6907 3413 6907 3441 6908 3439 6908 3438 6908 3338 6909 3339 6909 3336 6909 3338 6910 3336 6910 3335 6910 3232 6911 3228 6911 3476 6911 3228 6912 3225 6912 3476 6912 3225 6913 3223 6913 3476 6913 3223 6914 3222 6914 3476 6914 3222 6915 3224 6915 3476 6915 3224 6916 3227 6916 3476 6916 3476 6917 3227 6917 3231 6917 3231 6918 3236 6918 3476 6918 3236 6919 3240 6919 3476 6919 3240 6920 3241 6920 3476 6920 3241 6921 3237 6921 3476 6921 3237 6922 3235 6922 3476 6922 3476 6923 3235 6923 3232 6923

+
+ + +

1601 1634

+
+
+
+
+ + + + 0.00000 0.00002 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/palm/palm_E3M5.dae b/URDFs/sr_description/meshes/components/palm/palm_E3M5.dae new file mode 100644 index 0000000..3a0b710 --- /dev/null +++ b/URDFs/sr_description/meshes/components/palm/palm_E3M5.dae @@ -0,0 +1,132 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:42:02 + 2022-02-10T09:42:02 + + Z_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.31886 3.11933 88.42472 -2.31886 5.63812 90.39955 -2.86901 3.312 88.37461 -2.86901 5.74386 90.32435 -1.99945 5.53833 89.58848 -1.99944 4.28706 88.5514 -4.23984 10.89921 90.28441 -4.50802 10.95645 89.19076 -6.2616 11.1753 88.8843 -5.23617 7.94142 90.03388 -6.04362 7.94142 89.22799 -4.23845 5.63631 88.40637 -3.48421 10.27552 97.62239 -3.92405 9.96326 98.56784 -2.62062 9.46742 96.43927 -4.00144 10.43204 98.33806 -3.42962 8.64119 95.29342 -2.77315 8.93963 95.8138 -3.29574 9.2523 97.00844 -2.62016 8.73646 95.12654 -4.25756 11.04698 96.20256 -4.15142 11.04698 95.04393 -5.75123 11.49697 95.45497 -5.99619 11.49697 96.64929 -4.60233 11.04699 97.44501 -6.50894 11.49697 97.75499 -5.2387 11.04699 98.70365 -2.4043 8.83116 95.13356 -2.78691 9.19201 96.43332 -2.25253 9.009302 95.10453 -2.19861 9.23126 95.04592 -2.72672 9.94482 96.26662 -2.2479 9.44767 94.97078 -5.28283 10.68463 99.7013 -5.9089 10.75973 100.2209 -5.71777 10.27446 100.3477 -6.03239 9.87593 100.1751 -5.43032 9.8037 99.67538 -4.79349 9.69696 99.05484 -4.62052 10.57362 99.05593 -4.19838 9.560872 98.36477 -3.70107 9.41038 97.67668 -3.06268 10.11112 96.92743 -2.72672 10.02494 95.04329 -4.08456 8.54095 95.21244 -7.70988 9.10508 98.62049 -6.18704 11.04698 99.873 -2.72672 9.955222 93.81955 -3.31068 10.4765 94.44256 -4.62794 7.94142 90.84272 -4.18119 7.94142 91.62484 -3.86182 7.94142 92.36641 -3.64156 7.94142 93.06499 -2.86899 7.19214 93.23298 -1.99944 7.99697 92.1724 -1.99944 7.30184 92.4242 -1.99944 6.94656 91.57982 -1.99944 6.38827 90.62459 -1.99944 8.25571 93.05318 -1.99944 7.51917 93.15264 -3.96819 10.81415 91.43007 -6.88093 11.39697 89.68384 -5.65019 11.34554 91.02043 -4.49718 11.01932 91.70684 -3.71003 10.70574 92.56484 -4.65287 11.17864 92.9042 -5.12373 11.27726 91.90458 -3.48535 10.58686 93.59964 -4.22323 11.04697 94.01065 -2.44319 8.56278 94.71521 -3.05339 8.50667 94.93193 -2.66969 8.34255 94.60556 -2.07694 8.79775 92.93055 -2.25794 9.21523 92.83738 -2.50042 9.656762 93.29489 -2.19144 9.3299 94.73648 -2.19702 7.58718 93.89461 -2.00608 7.87464 93.62246 -2.32404 7.07942 93.26065 -5.97059 11.49697 93.17299 -5.78696 11.49697 94.23915 -6.20346 11.49697 92.22731 -6.87369 8.496972 90.33946 -6.23881 8.496972 90.99005 -5.75942 8.496972 91.64044 -5.40616 8.496972 92.26857 -5.15264 8.496972 92.86425 -4.97702 8.496972 93.42589 -2.0713 8.649621 92.46511 -3.27289 7.83903 94.26452 -3.50552 7.94157 93.72605 -2.62331 7.53031 93.96105 -2.30936 8.16196 94.33181 -4.41073 8.496972 95.04093 -4.62775 8.49544 94.56347 -4.86253 8.496972 93.95772 -2.2273 8.656372 94.6345 -2.05462 8.88449 94.20365 -2.00608 8.38057 93.92615 -2.01864 8.653962 94.05004 -2.00608 8.3286 93.39334 -18.41133 1.43357 87.00081 -19.12988 1.27291 87.70231 -19.12988 -0.003029882 87.59163 -18.84514 -0.003029882 87.29075 -18.54927 -0.003029882 87.00081 -19.12988 2.37195 87.98259 -18.00349 2.81535 87.00081 -17.3473 4.08411 87.00081 -18.66365 4.10292 88.26278 -19.12988 4.09936 88.83101 -16.49944 5.99697 87.00081 -17.8421 6.16047 88.98506 -15.99944 6.96932 88.11705 -15.99944 7.74294 89.00081 -16.49944 7.94142 89.74383 -9.94944 7.47344 87.00081 -8.57618 7.14735 87.00081 -9.94944 7.94142 87.46534 -8.391242 7.94142 87.85357 -7.30655 6.582 87.00083 -7.08771 7.94142 88.47516 -6.1286 5.76542 87.00083 -5.04713 4.64133 87.00083 -4.06877 2.916 87.00083 -3.63364 1.65375 87.00083 -3.44961 -0.003029882 87.00083 -3.15375 -0.003029882 87.29077 -2.86901 -0.003029882 87.59163 -2.86901 1.2735 87.70243 -2.86901 2.37288 87.98291 -15.99944 8.496972 87.00081 -12.03442 8.496972 87.00081 -15.99944 8.496972 89.00081 -4.76363 10.98769 88.17483 -4.99944 10.99697 87.25485 -13.90792 11.39697 88.93673 -16.99944 10.99697 87.25485 -15.73728 11.26217 88.8843 -15.16828 10.99697 86.13398 -12.50619 11.39697 88.44628 -13.13533 10.99697 85.43849 -10.99994 11.39697 88.27532 -10.99945 10.99697 85.20285 -9.49355 11.39697 88.44607 -8.863592 10.99697 85.43849 -6.83064 10.99697 86.13395 -8.09143 11.39697 88.9365 -17.23631 10.9876 88.179 -17.4921 10.95624 89.19575 -19.68002 3.11935 88.42472 -19.99944 4.28585 88.55059 -19.99944 2.47985 87.66356 -19.56388 -0.003029882 87.75068 -19.99944 1.33074 87.37055 -19.99944 -0.003029882 87.25485 -19.94282 -0.003029882 87.48596 -19.78578 -0.003029882 87.66474 -19.3274 -0.003029882 87.72432 -1.99945 1.33136 87.37066 -2.435 -0.003029882 87.75068 -2.2131 -0.003029882 87.66474 -2.05606 -0.003029882 87.48597 -1.99944 -0.003029882 87.25486 -1.99945 2.48084 87.6639 -2.67149 -0.003029882 87.72432 -10.99943 11.49528 88.98594 -9.94944 8.496972 88.86506 -8.718502 8.496972 89.20881 -9.96445 8.496972 87.00081 -19.12987 -8.00303 87.59163 -18.90861 -9.0346 87.35697 -18.36907 -9.82743 86.83525 -18.54927 -4.00303 87.00083 -17.61403 -10.3084 86.21868 -16.91593 -4.00303 85.72747 -16.73857 -10.50303 85.61666 -15.6181 -10.50303 85.01744 -15.88833 -9.00303 85.14695 -15.52103 -9.4878 84.9731 -15.88833 -6.00303 85.14695 -15.41294 -5.67444 84.92507 -15.07323 -5.46536 84.78298 -15.06578 -4.00303 84.78002 -14.74852 -5.29607 84.65947 -15.0433 -10.02226 84.77111 -14.44095 -10.49866 84.5542 -14.27803 -5.11393 84.50078 -13.5644 -5.00303 84.30406 -13.06992 -4.00303 84.19744 -11.8618 -5.00303 84.03469 -10.99943 -4.00303 84.00083 -10.13707 -5.00303 84.03469 -8.92895 -4.00303 84.19744 -8.434472 -5.00303 84.30406 -7.75159 -5.10488 84.49124 -7.14236 -5.34857 84.69922 -6.9331 -4.00303 84.78002 -6.60089 -5.66467 84.91852 -5.26031 -10.50303 85.61666 -6.11055 -6.00303 85.14695 -6.11055 -9.00303 85.14695 -6.38052 -10.50303 85.01755 -5.08295 -4.00303 85.72747 -4.31402 -10.5013 86.22204 -3.64806 -9.84937 86.81808 -3.44961 -4.00303 87.00083 -3.09106 -9.0365 87.35614 -2.86901 -8.00303 87.59163 -13.03604 -5.00303 84.67029 -8.96283 -5.00303 84.67029 -12.5984 -5.00303 85.13996 -9.40047 -5.00303 85.13996 -12.27033 -5.00303 85.69278 -9.72854 -5.00303 85.69278 -12.06769 -5.00303 86.30226 -9.93118 -5.00303 86.30226 -11.99943 -5.00303 86.93856 -9.99943 -5.00303 86.93856 -10.99943 -10.00303 85.00083 -10.99943 -10.00303 85.40252 -12.66555 -10.00303 85.05361 -12.38011 -10.00303 85.47597 -10.99943 -10.00303 85.74328 -12.17045 -10.00303 85.94014 -10.99943 -10.00303 86.01088 -9.95637 -10.00303 86.43206 -12.04251 -10.00303 86.43202 -9.99943 -10.00303 86.93856 -11.99943 -10.00303 86.93856 -6.58866 -6.00303 84.98121 -6.58878 -9.00303 84.98118 -7.0945 -6.00303 84.94082 -7.09457 -9.00303 84.94084 -7.59312 -6.00303 85.02871 -7.59319 -9.00303 85.02874 -8.05351 -6.00303 85.23889 -8.05357 -9.00303 85.23892 -8.4464 -6.00303 85.55789 -8.44646 -9.00303 85.55793 -8.74675 -6.00303 85.96547 -8.74683 -9.00303 85.96562 -8.9354 -6.00303 86.43654 -8.93547 -9.00303 86.43677 -8.99943 -6.00303 86.93856 -8.99943 -9.00303 86.93856 -15.41021 -9.00303 84.98121 -15.41021 -6.00303 84.98121 -14.90438 -9.00303 84.94082 -14.90438 -6.00303 84.94082 -14.40575 -9.00303 85.02871 -14.40575 -6.00303 85.02871 -13.94536 -9.00303 85.23889 -13.94536 -6.00303 85.23889 -13.55247 -9.00303 85.55789 -13.55247 -6.00303 85.55789 -13.25213 -9.00303 85.96547 -13.25213 -6.00303 85.96547 -13.06347 -9.00303 86.43654 -13.06347 -6.00303 86.43654 -12.99944 -9.00303 86.93856 -12.99944 -6.00303 86.93856 -13.71113 -5.29592 85.04183 -12.97319 -5.29592 85.86539 -12.70656 -5.29593 86.93856 -12.92332 -5.62036 86.93856 -12.38214 -5.07915 86.93856 -7.25136 -5.30497 84.66201 -8.28282 -5.29592 85.03849 -9.02428 -5.29592 85.86277 -9.61675 -5.07915 86.93856 -9.29233 -5.29592 86.93856 -9.07556 -5.62034 86.93856 -15.20861 -9.24626 84.91934 -14.45941 -9.511981 84.86864 -13.92234 -9.70494 84.92412 -13.03527 -9.71013 85.7556 -12.97082 -9.982001 85.01441 -13.25342 -9.92569 84.99267 -13.5218 -9.845001 84.9712 -12.38212 -9.92691 86.93856 -12.70654 -9.71013 86.93856 -12.92332 -9.38571 86.93856 -19.32739 -8.00303 87.72432 -19.56388 -8.00303 87.75068 -19.78578 -8.00303 87.66474 -19.94282 -8.00303 87.48597 -19.99944 -8.00303 87.25486 -2.67151 -8.00302 87.72431 -2.43502 -8.00302 87.7507 -2.21312 -8.00302 87.66475 -2.05606 -8.00302 87.48597 -1.99944 -8.00303 87.25486 -5.22536 -10.75303 85.55951 -3.52903 -9.98157 86.87934 -2.86596 -9.193262 87.46949 -4.23798 -10.62444 86.18592 -3.30825 -10.1712 86.83069 -2.61141 -9.29184 87.43207 -5.13856 -10.9194 85.41758 -3.15324 -10.23448 86.72433 -2.31082 -9.29155 87.14128 -4.99944 -11.00303 85.19011 -4.00331 -10.79866 85.9662 -2.97677 -10.21861 86.44617 -3.91117 -10.77342 85.81321 -2.27803 -9.24322 87.00869 -16.98495 -10.99559 85.21382 -15.42694 -11.00303 84.38729 -16.869 -10.93604 85.40339 -14.52264 -10.85658 84.42583 -16.78412 -10.77336 85.54217 -13.76685 -11.00303 83.83877 -12.04944 -10.85241 83.89984 -10.99943 -10.6697 84.02233 -13.47455 -10.61703 84.28743 -10.99943 -10.97928 83.70178 -10.99943 -11.00303 83.54885 -8.2317 -11.00303 83.83885 -9.94944 -10.85241 83.89984 -7.47623 -10.85658 84.42583 -6.57136 -11.00303 84.38752 -19.08425 -9.16383 87.46038 -17.71125 -10.54603 86.2146 -18.57539 -10.08604 86.87477 -19.28141 -9.25626 87.46589 -17.83893 -10.7081 86.13066 -18.7582 -10.2036 86.79393 -19.46508 -9.30571 87.39328 -17.99289 -10.79692 85.97328 -18.92981 -10.24095 86.64248 -19.63477 -9.30826 87.23494 -18.09775 -10.76947 85.81949 -19.02166 -10.21902 86.44584 -19.72185 -9.240942 87.00955 -10.99943 -10.40319 84.16567 -12.78643 -10.32127 84.33208 -10.99943 -10.18686 84.38906 -12.73147 -10.1721 84.6602 -10.99943 -10.04902 84.66846 -6.78915 -9.24626 84.91934 -6.47673 -9.4878 84.9731 -6.95446 -10.02226 84.77111 -7.53835 -9.511981 84.86864 -7.55681 -10.49866 84.5542 -8.07543 -9.70494 84.92412 -8.47597 -9.845001 84.9712 -8.523221 -10.61703 84.28743 -8.74434 -9.92569 84.99267 -9.02695 -9.982001 85.01441 -9.266302 -10.1721 84.6602 -9.21134 -10.32127 84.33208 -9.33221 -10.00303 85.05361 -9.07556 -9.38571 86.93856 -9.29233 -9.71013 86.93856 -8.9625 -9.71013 85.7556 -9.61675 -9.92691 86.93856 -9.82731 -10.00303 85.94014 -9.61765 -10.00303 85.47597 -9.99943 -5.00303 93.26877 -11.99943 -5.00303 93.26877 -9.76705 -5.00303 94.09375 -11.62292 -5.00303 94.21898 -11.22196 -5.00303 94.0259 -10.77691 -5.00303 94.0259 -10.37594 -5.00303 94.21898 -12.36546 -5.07242 94.00083 -9.72595 -5.02203 94.5056 -11.9004 -5.00303 94.56694 -10.09847 -5.00303 94.56694 -12.16913 -5.00303 94.92147 -9.82974 -5.00303 94.92148 -11.99943 -5.00303 95.00083 -9.99943 -5.00303 95.00083 -9.91382 -5.00303 95.44345 -12.07844 -5.00303 95.45932 -10.13171 -5.00303 95.49787 -11.86516 -5.00303 95.50135 -10.49671 -5.00303 95.86528 -10.23375 -5.00303 95.88864 -11.75377 -5.00303 95.8983 -11.49825 -5.00303 95.86753 -10.99721 -5.00303 96.00081 -10.71798 -5.00303 96.13891 -11.2647 -5.00303 96.1428 -8.99943 -9.00303 94.00083 -8.99906 -6.00303 94.00081 -12.99944 -9.00303 94.00083 -12.99944 -6.00303 93.96101 -12.69802 -5.2875 94.00083 -12.92101 -5.61481 94.00083 -12.9945 -6.00303 94.1412 -9.5678 -5.1104 94.23588 -9.30086 -5.28749 94.00083 -9.07786 -5.61481 94.00083 -9.13342 -9.50305 94.00083 -9.499462 -9.869071 94.00083 -9.99943 -10.00303 94.00083 -11.99943 -10.00303 94.00083 -12.49944 -9.86905 94.00083 -12.86546 -9.50303 94.00083 -10.99943 -5.00303 95.00083 -12.73674 -5.33823 94.1848 -12.92749 -5.64578 94.15258 -9.26214 -5.33822 94.18481 -9.071392 -5.64578 94.15258 -12.81211 -5.27567 95.41165 -13.10184 -5.9457 95.54119 -12.15939 -5.27567 96.45308 -12.32968 -5.9457 96.71621 -10.99944 -5.9457 97.17156 -10.99944 -5.27567 96.85948 -9.66919 -5.9457 96.71621 -9.83949 -5.27567 96.45308 -8.89703 -5.9457 95.54119 -9.18676 -5.27567 95.41165 -9.99943 -10.00303 95.50083 -11.99943 -10.00303 95.50083 -8.89703 -8.9457 95.54119 -13.10184 -8.9457 95.54119 -12.32968 -8.9457 96.71621 -10.99944 -8.9457 97.17156 -9.66919 -8.9457 96.71621 -19.12988 5.2965 89.82287 -16.49944 8.496972 92.08535 -15.11795 11.39697 89.68384 -17.75948 10.8991 90.28621 -19.68002 5.63813 90.39956 -13.73816 11.49697 89.71026 -12.6984 11.49697 89.29082 -18.50646 10.59098 93.56623 -18.68239 10.48045 94.41388 -17.3459 11.17867 92.90397 -17.50171 11.01932 91.70685 -16.34875 11.34554 91.02054 -19.62539 9.636342 95.45105 -19.80692 9.23126 95.04592 -19.3814 9.77928 96.36007 -19.75098 9.44767 94.97078 -19.1299 7.19214 93.23297 -18.73264 7.83903 94.26452 -19.38222 7.53031 93.96105 -19.69616 8.16196 94.33181 -19.32961 8.34236 94.60522 -18.56921 8.64121 95.29347 -17.92096 8.54095 95.21244 -17.37778 8.49544 94.56346 -19.55777 8.55985 94.71041 -19.38537 8.73646 95.12652 -19.753 9.009302 95.10453 -19.77822 8.656372 94.6345 -19.95091 8.88449 94.20365 -19.82544 9.29202 94.66218 -19.85573 8.20532 94.23194 -14.1751 8.6999 97.51353 -10.99944 8.55728 98.13482 -14.289 9.105072 98.62049 -17.11091 7.94142 90.46917 -17.5802 7.94142 91.18251 -17.93302 7.94142 91.86851 -16.02825 11.49697 93.17279 -17.77565 11.08882 94.01065 -16.21191 11.49697 94.23915 -15.79537 11.49697 92.22714 -16.87505 11.27728 91.90441 -15.49461 11.49697 91.41564 -15.11051 11.49697 90.7632 -14.64758 11.49697 90.29109 -14.60171 11.04698 100.825 -13.23189 11.04697 101.4749 -13.7854 11.49697 99.47166 -13.27012 11.48797 100.0102 -15.80674 11.04699 99.87802 -14.73763 11.49697 98.71241 -16.75669 11.04699 98.70907 -15.48995 11.49697 97.75497 -17.3948 11.04699 97.4496 -16.0027 11.49697 96.64927 -17.74075 11.04698 96.20579 -16.24766 11.49697 95.45497 -17.84745 11.04698 95.04558 -13.59535 9.968562 101.5481 -14.10851 10.3817 101.6682 -14.86599 9.951332 100.9168 -12.05994 9.968562 101.9637 -12.06741 10.38028 102.2918 -13.63363 10.85606 101.6447 -19.02626 9.09237 96.37292 -18.21762 9.4337 97.78476 -19.40844 9.572001 96.42621 -18.07484 9.96326 98.56782 -19.27217 9.94482 96.26661 -18.64199 10.22999 97.42498 -18.22036 10.36962 98.04489 -17.71625 10.50161 98.68008 -16.28111 10.27446 100.3477 -16.96824 9.74083 99.29841 -16.5328 10.70933 99.86162 -15.84827 9.88731 100.2647 -15.96703 10.77157 100.3141 -14.94548 10.83814 100.9923 -19.45986 9.80788 95.89679 -19.56388 7.03771 93.27092 -19.80851 7.58718 93.8946 -19.99944 7.87464 93.62245 -19.99944 7.42452 92.80275 -19.99944 5.53739 89.58751 -19.12988 6.30681 91.12614 -19.99944 7.99697 92.1724 -19.99944 8.3286 93.39332 -19.92759 8.649621 92.46511 -19.74095 9.21523 92.83737 -19.49847 9.656762 93.29487 -19.27217 9.95521 93.81954 -19.27217 10.01127 94.47571 -19.27217 10.0246 95.09308 -19.27217 10.00166 95.68509 -14.33799 9.49194 99.7704 -13.54441 9.65113 100.6214 -10.99943 11.49697 95.12439 -18.28336 10.70835 92.54011 -17.95351 10.83841 91.10441 -19.0442 10.19218 94.41816 -10.99944 8.496972 95.00081 -7.69372 8.496972 89.72613 -6.88885 11.49697 90.76256 -7.35129 11.49697 90.29109 -6.50431 11.49697 91.41555 -8.26082 11.49697 89.71022 -9.300601 11.49697 89.29078 -7.39114 11.04698 100.8213 -7.00228 10.83605 100.9621 -8.76036 11.04697 101.4726 -8.42268 10.85606 101.6672 -8.9534 10.85606 101.8487 -10.23691 11.04697 101.8064 -10.17666 10.85606 102.1003 -11.75499 11.04697 101.8072 -9.69498 9.65113 101.0324 -8.45173 9.65113 100.6214 -8.98314 9.968562 101.7492 -10.18862 9.968562 101.9972 -10.99948 9.65113 101.1718 -7.66148 9.492382 99.77202 -7.55751 9.96396 101.1531 -7.89038 10.3817 101.6682 -9.93147 10.38028 102.2918 -11.4601 10.85606 102.133 -10.99944 11.48797 100.5008 -8.21348 11.49697 99.47166 -8.72876 11.48797 100.0102 -7.26126 11.49697 98.71241 -9.86098 11.48797 100.3768 -12.16097 11.48797 100.3768 -12.65105 10.85606 101.9544 -12.30398 9.65113 101.0324 19.68114 3.11933 92.42472 19.68114 5.63812 94.39955 19.13099 3.312 92.37461 19.13099 5.74386 94.32435 20.00056 4.28707 92.55139 17.76016 10.89921 94.28441 17.49198 10.95645 93.19076 15.7384 11.1753 92.8843 16.76383 7.94142 94.03388 15.95638 7.94142 93.22799 17.76155 5.63631 92.40637 18.51579 10.27552 101.6224 18.07596 9.96326 102.5678 19.37938 9.46742 100.4393 17.99856 10.43204 102.3381 18.57038 8.64119 99.29342 19.22685 8.93964 99.8138 18.70426 9.2523 101.0084 19.37984 8.73646 99.12654 17.74244 11.04698 100.2026 17.84858 11.04698 99.04393 16.24877 11.49697 99.45497 16.00381 11.49697 100.6493 17.39767 11.04699 101.445 15.49106 11.49697 101.755 16.7613 11.04699 102.7036 19.59571 8.83116 99.13356 19.21309 9.19201 100.4333 19.74747 9.009302 99.10453 19.80139 9.23127 99.04592 19.27328 9.94482 100.2666 19.7521 9.44767 98.97078 16.71717 10.68463 103.7013 16.0911 10.75973 104.2209 16.28223 10.27446 104.3477 15.96762 9.87593 104.1751 16.56968 9.8037 103.6754 17.20651 9.69696 103.0548 17.37948 10.57362 103.0559 17.80162 9.560872 102.3648 18.29893 9.41038 101.6767 18.93732 10.11113 100.9274 19.27329 10.02495 99.04329 17.91544 8.54095 99.21244 14.29012 9.10508 102.6205 15.81296 11.04698 103.873 19.27328 9.955222 97.81954 18.68931 10.4765 98.44255 17.37206 7.94142 94.84272 17.81881 7.94142 95.62484 18.13819 7.94142 96.36641 18.35844 7.94142 97.06499 19.13101 7.19214 97.23298 20.00056 7.99697 96.1724 20.00056 7.4246 96.80301 20.00056 6.94656 95.57982 20.00056 6.38827 94.62459 20.00056 8.25571 97.05318 20.00056 7.58539 97.30754 18.03181 10.81416 95.43007 15.11907 11.39697 93.68384 16.34981 11.34554 95.02043 17.50282 11.01933 95.70684 18.28996 10.70574 96.56483 17.34713 11.17865 96.9042 16.87627 11.27726 95.90458 18.51465 10.58686 97.59963 17.77677 11.04697 98.01065 19.55681 8.56278 98.71521 18.94661 8.50667 98.93193 19.33031 8.34255 98.60556 19.92306 8.79775 96.93055 19.74206 9.21523 96.83737 19.49958 9.656762 97.29487 19.80856 9.3299 98.73648 19.99392 7.87464 97.62246 19.80298 7.58718 97.89461 19.67596 7.07942 97.26065 16.02941 11.49697 97.17299 16.21304 11.49697 98.23915 15.79654 11.49697 96.22731 15.12631 8.496972 94.33946 15.76119 8.496972 94.99005 16.24058 8.496972 95.64044 16.59384 8.496972 96.26857 16.84736 8.496972 96.86425 17.02299 8.496972 97.42589 19.92871 8.649621 96.46511 18.72711 7.83903 98.26452 18.49448 7.94157 97.72605 19.37669 7.53031 97.96105 19.69064 8.16196 98.33181 17.58927 8.496972 99.04093 17.37226 8.49544 98.56347 17.13748 8.496972 97.95772 19.7727 8.656372 98.6345 19.94539 8.88449 98.20365 19.99392 8.38057 97.92615 19.99392 8.3286 97.39334 3.58867 1.43357 91.00081 2.87013 1.27291 91.70231 2.87013 -0.003029882 91.59163 3.15487 -0.003029882 91.29075 3.45073 -0.003029882 91.00081 2.87013 2.37195 91.98259 3.99651 2.81535 91.00081 4.65271 4.08412 91.00081 3.33635 4.10292 92.26278 2.87013 4.09936 92.83101 5.50056 5.99697 91.00081 4.1579 6.16047 92.98506 6.00056 6.96932 92.11705 6.00056 7.74294 93.00081 5.50056 7.94142 93.74383 12.05057 7.47344 91.00081 13.42382 7.14735 91.00081 12.05057 7.94142 91.46534 13.60876 7.94142 91.85357 14.69345 6.582 91.00083 14.91229 7.94142 92.47516 15.99923 5.63255 91.00083 16.95287 4.64133 91.00083 17.93123 2.916 91.00083 18.36637 1.65375 91.00083 18.55039 -0.003029882 91.00083 18.84625 -0.003029882 91.29077 19.13099 -0.003029882 91.59163 19.13099 1.27351 91.70243 19.13099 2.37288 91.98291 6.00056 8.496972 91.00081 9.96558 8.496972 91.00081 6.00056 8.496972 93.00081 17.23637 10.98769 92.17483 17.00056 10.99697 91.25485 8.092082 11.39697 92.93673 5.00056 10.99697 91.25485 6.26273 11.26217 92.8843 6.83172 10.99697 90.13398 9.49381 11.39697 92.44628 8.86467 10.99697 89.43849 11.00006 11.39697 92.27532 11.00054 10.99697 89.20285 12.50645 11.39697 92.44607 13.13641 10.99697 89.43849 15.16936 10.99697 90.13395 13.90857 11.39697 92.9365 4.7637 10.9876 92.179 4.5079 10.95624 93.19575 2.31998 3.11935 92.42472 2.00056 4.28585 92.55059 2.00056 2.47986 91.66356 2.32517 -0.003029882 91.70771 2.00056 1.33074 91.37054 2.00056 -0.003029882 91.25485 2.05718 -0.003029882 91.48596 2.21422 -0.003029882 91.66474 2.43612 -0.003029882 91.75068 2.67261 -0.003029882 91.72432 20.00056 1.33136 91.37065 19.565 -0.003029882 91.75068 19.7869 -0.003029882 91.66474 19.94394 -0.003029882 91.48597 20.00056 -0.003029882 91.25485 20.00056 2.48084 91.66389 19.32852 -0.003029882 91.72432 11.00057 11.49528 92.98594 12.05057 8.496972 92.86506 13.2815 8.496972 93.20881 12.03555 8.496972 91.00081 2.87013 -8.00303 91.59163 3.0914 -9.0346 91.35697 3.63093 -9.82743 90.83525 3.45073 -4.00303 91.00083 4.38597 -10.3084 90.21868 5.08407 -4.00303 89.72747 5.26143 -10.50303 89.61666 6.3819 -10.50303 89.01744 6.11167 -9.00303 89.14695 6.47897 -9.4878 88.9731 6.11167 -6.00303 89.14695 6.58706 -5.67444 88.92507 6.92677 -5.46536 88.78298 6.93422 -4.00303 88.78002 7.25148 -5.29607 88.65947 6.9567 -10.02226 88.77111 7.55905 -10.49866 88.5542 7.72198 -5.11393 88.50078 8.4356 -5.00303 88.30406 8.93008 -4.00303 88.19744 10.1382 -5.00303 88.03469 11.00057 -4.00303 88.00083 11.86293 -5.00303 88.03469 13.07105 -4.00303 88.19744 13.56553 -5.00303 88.30406 14.24841 -5.10488 88.49124 14.85765 -5.34857 88.69922 15.0669 -4.00303 88.78002 15.39911 -5.66467 88.91852 16.73969 -10.50303 89.61666 15.88945 -6.00303 89.14695 15.88945 -9.00303 89.14695 15.61948 -10.50303 89.01755 16.91706 -4.00303 89.72747 17.68598 -10.5013 90.22204 18.35194 -9.84937 90.81808 18.55039 -4.00303 91.00083 18.90894 -9.0365 91.35614 19.13099 -8.00303 91.59163 8.96396 -5.00303 88.67029 13.03717 -5.00303 88.67029 9.4016 -5.00303 89.13996 12.59953 -5.00303 89.13996 9.72967 -5.00303 89.69278 12.27146 -5.00303 89.69278 9.932312 -5.00303 90.30226 12.06882 -5.00303 90.30226 10.00057 -5.00303 90.93856 12.00057 -5.00303 90.93856 11.00057 -10.00303 89.00083 11.00057 -10.00303 89.40252 9.33445 -10.00303 89.05361 9.619892 -10.00303 89.47597 11.00057 -10.00303 89.74328 9.82955 -10.00303 89.94014 11.00057 -10.00303 90.01088 12.04364 -10.00303 90.43206 9.95749 -10.00303 90.43201 12.00057 -10.00303 90.93856 10.00057 -10.00303 90.93856 15.41134 -6.00303 88.98121 15.41122 -9.00303 88.98118 14.9055 -6.00303 88.94082 14.90544 -9.00303 88.94084 14.40688 -6.00303 89.02871 14.40681 -9.00303 89.02874 13.94649 -6.00303 89.23889 13.94644 -9.00303 89.23891 13.5536 -6.00303 89.55789 13.55354 -9.00303 89.55793 13.25326 -6.00303 89.96547 13.25317 -9.00303 89.96562 13.0646 -6.00303 90.43654 13.06454 -9.00303 90.43677 13.00057 -6.00303 90.93856 13.00057 -9.00303 90.93856 6.58979 -9.00303 88.98121 6.58979 -6.00303 88.98121 7.09562 -9.00303 88.94082 7.09562 -6.00303 88.94082 7.59425 -9.00303 89.02871 7.59425 -6.00303 89.02871 8.05464 -9.00303 89.23889 8.05464 -6.00303 89.23889 8.44753 -9.00303 89.55789 8.44753 -6.00303 89.55789 8.74787 -9.00303 89.96547 8.74787 -6.00303 89.96547 8.936532 -9.00303 90.43654 8.936532 -6.00303 90.43654 9.00056 -9.00303 90.93856 9.00056 -6.00303 90.93856 8.28888 -5.29592 89.04183 9.02681 -5.29592 89.86539 9.29344 -5.29593 90.93856 9.076682 -5.62035 90.93856 9.61786 -5.07915 90.93856 14.74864 -5.30497 88.66201 13.71718 -5.29592 89.03849 12.97572 -5.29592 89.86277 12.38325 -5.07915 90.93856 12.70767 -5.29592 90.93856 12.92444 -5.62034 90.93856 6.79139 -9.246252 88.91934 7.54059 -9.511981 88.86864 8.077672 -9.70493 88.92412 8.96474 -9.71013 89.7556 9.02918 -9.982001 89.01441 8.746582 -9.92569 88.99267 8.4782 -9.84499 88.9712 9.61788 -9.92691 90.93856 9.29346 -9.71013 90.93856 9.07669 -9.38571 90.93856 2.67261 -8.00303 91.72432 2.43612 -8.00303 91.75068 2.21422 -8.00303 91.66474 2.05718 -8.00303 91.48597 2.00056 -8.00303 91.25485 19.32849 -8.00302 91.72431 19.56498 -8.00302 91.7507 19.78688 -8.00302 91.66475 19.94394 -8.00302 91.48597 20.00056 -8.00303 91.25486 16.77464 -10.75303 89.55951 18.47097 -9.98157 90.87934 19.13404 -9.193262 91.46949 17.76203 -10.62444 90.18592 18.69175 -10.17119 90.83069 19.38859 -9.29184 91.43207 16.86144 -10.9194 89.41758 18.84677 -10.23448 90.72433 19.68918 -9.29155 91.14128 17.00056 -11.00303 89.19011 17.99669 -10.79865 89.9662 17.73979 -10.91053 89.59456 19.02323 -10.21861 90.44617 18.08883 -10.77341 89.81321 19.72198 -9.24321 91.00869 5.01505 -10.99559 89.2138 6.57306 -11.00303 88.38727 5.131 -10.93604 89.40339 7.47736 -10.85658 88.42583 5.21588 -10.77336 89.54217 8.23315 -11.00303 87.83876 9.950572 -10.85241 87.89984 11.00057 -10.6697 88.02233 8.52545 -10.61703 88.28743 11.00057 -10.97928 87.70178 11.00056 -11.00303 87.54885 13.7683 -11.00303 87.83885 12.05057 -10.85241 87.89984 14.52377 -10.85658 88.42583 15.42864 -11.00303 88.38752 2.91575 -9.16382 91.46038 4.28875 -10.54603 90.2146 3.42461 -10.08604 90.87477 2.71859 -9.25626 91.46589 4.16107 -10.70809 90.13066 3.2418 -10.2036 90.79393 2.53492 -9.30571 91.39328 4.00711 -10.79692 89.97328 3.07019 -10.24095 90.64248 2.36523 -9.30826 91.23494 3.90226 -10.76947 89.81949 2.97833 -10.21902 90.44583 2.27815 -9.240942 91.00953 11.00057 -10.40319 88.16567 9.213582 -10.32127 88.33208 11.00057 -10.18686 88.38906 9.26853 -10.1721 88.6602 11.00057 -10.04902 88.66846 15.21085 -9.246252 88.91934 15.52327 -9.4878 88.9731 15.04554 -10.02226 88.77111 14.46165 -9.511981 88.86864 14.44319 -10.49865 88.5542 13.92457 -9.70493 88.92412 13.52403 -9.84499 88.9712 13.47679 -10.61703 88.28743 13.25566 -9.92569 88.99267 12.97305 -9.982001 89.01441 12.73371 -10.1721 88.6602 12.78866 -10.32127 88.33208 12.66779 -10.00303 89.05361 12.92445 -9.38571 90.93856 12.70767 -9.71013 90.93856 13.0375 -9.71013 89.7556 12.38325 -9.92691 90.93856 12.17269 -10.00303 89.94014 12.38235 -10.00303 89.47597 12.00057 -5.00303 97.26877 10.00057 -5.00303 97.26877 12.23295 -5.00303 98.09375 10.37708 -5.00303 98.21898 10.77804 -5.00303 98.0259 11.22309 -5.00303 98.0259 11.62406 -5.00303 98.21898 9.63454 -5.07242 98.00083 12.27405 -5.02203 98.5056 10.0996 -5.00303 98.56694 11.90153 -5.00303 98.56694 9.83087 -5.00303 98.92147 12.17026 -5.00303 98.92148 10.00057 -5.00303 99.00083 12.00057 -5.00303 99.00083 12.08618 -5.00303 99.44345 9.92156 -5.00303 99.45932 11.86829 -5.00303 99.49787 10.13484 -5.00303 99.50135 11.50329 -5.00303 99.86528 11.76625 -5.00303 99.88864 10.24623 -5.00303 99.8983 10.50175 -5.00303 99.86753 11.00279 -5.00303 100.0008 11.28202 -5.00303 100.1389 10.7353 -5.00303 100.1428 13.00057 -9.00303 98.00083 13.00094 -6.00303 98.00081 9.00056 -9.00303 98.00083 9.00056 -6.00303 97.96101 9.30198 -5.2875 98.00083 9.079001 -5.61481 98.00083 9.0055 -6.00303 98.1412 12.4322 -5.1104 98.23588 12.69915 -5.28749 98.00083 12.92214 -5.61481 98.00083 12.86658 -9.50305 98.00083 12.50054 -9.869071 98.00083 12.00057 -10.00303 98.00083 10.00057 -10.00303 98.00083 9.50056 -9.86905 98.00083 9.13454 -9.50303 98.00083 11.00057 -5.00303 99.00083 9.26326 -5.33823 98.1848 9.07251 -5.64578 98.15258 12.73786 -5.33822 98.18481 12.92861 -5.64578 98.15258 9.187891 -5.27567 99.41165 8.89816 -5.9457 99.54119 9.84061 -5.27567 100.4531 9.67032 -5.9457 100.7162 11.00056 -5.9457 101.1716 11.00056 -5.27567 100.8595 12.33081 -5.9457 100.7162 12.16051 -5.27567 100.4531 13.10297 -5.9457 99.54119 12.81324 -5.27567 99.41165 12.00057 -10.00303 99.50083 10.00057 -10.00303 99.50083 13.10297 -8.9457 99.54119 8.89816 -8.9457 99.54119 9.67032 -8.9457 100.7162 11.00056 -8.9457 101.1716 12.33081 -8.9457 100.7162 2.87012 5.2965 93.82287 5.50056 8.496972 96.08535 6.88205 11.39697 93.68384 4.24052 10.8991 94.28621 2.31998 5.63813 94.39956 8.26184 11.49697 93.71026 9.3016 11.49697 93.29082 3.49354 10.59098 97.56623 3.31761 10.48045 98.41388 4.6541 11.17867 96.90397 4.49829 11.01932 95.70685 5.65125 11.34554 95.02054 2.37461 9.636342 99.45105 2.19308 9.23126 99.04592 2.61861 9.77928 100.3601 2.24902 9.44767 98.97078 2.87011 7.19214 97.23297 3.26737 7.83903 98.26452 2.61779 7.53031 97.96104 2.30384 8.16196 98.33181 2.6704 8.34236 98.60522 3.43079 8.64121 99.29347 4.07904 8.54095 99.21244 4.62223 8.49544 98.56346 2.44224 8.55985 98.71041 2.61464 8.73646 99.12652 2.24701 9.009302 99.10453 2.22178 8.656372 98.6345 2.04909 8.88449 98.20365 2.17456 9.29202 98.66218 2.14427 8.20532 98.23194 7.8249 8.6999 101.5135 11.00056 8.55728 102.1348 7.711 9.10508 102.6205 4.8891 7.94142 94.46917 4.41981 7.94142 95.18251 4.06698 7.94142 95.86851 5.97176 11.49697 97.17279 4.22435 11.08882 98.01065 5.78809 11.49697 98.23915 6.20463 11.49697 96.22714 5.12495 11.27728 95.90441 6.50539 11.49697 95.41564 6.88949 11.49697 94.7632 7.35242 11.49697 94.29109 7.39829 11.04698 104.825 8.76811 11.04697 105.4749 8.2146 11.49697 103.4717 8.72988 11.48797 104.0102 6.19326 11.04699 103.878 7.26237 11.49697 102.7124 5.24331 11.04699 102.7091 6.51005 11.49697 101.755 4.6052 11.04699 101.4496 5.9973 11.49697 100.6493 4.25925 11.04698 100.2058 5.75235 11.49697 99.45497 4.15255 11.04698 99.04558 8.40465 9.968562 105.5481 7.8915 10.3817 105.6682 7.13401 9.951332 104.9168 9.94006 9.968562 105.9637 9.9326 10.38028 106.2918 8.366372 10.85606 105.6447 2.97374 9.09237 100.3729 3.78238 9.4337 101.7848 2.59157 9.572001 100.4262 3.92516 9.96326 102.5678 2.72783 9.94482 100.2666 3.35801 10.22999 101.425 3.77964 10.36962 102.0449 4.28376 10.50161 102.6801 5.71889 10.27446 104.3477 5.03176 9.74083 103.2984 5.46721 10.70933 103.8616 6.15173 9.88731 104.2647 6.03297 10.77157 104.3141 7.05452 10.83814 104.9923 2.54015 9.80788 99.89679 2.43612 7.03771 97.27092 2.1915 7.58718 97.8946 2.00056 7.42452 96.80275 2.00056 7.87464 97.62245 2.00056 5.53739 93.58751 2.87012 6.30681 95.12614 2.00056 7.99697 96.1724 2.00056 8.3286 97.39332 2.07241 8.649621 96.46511 2.25906 9.21523 96.83737 2.50154 9.656762 97.29487 2.72783 9.955222 97.81954 2.72783 10.01127 98.47571 2.72783 10.0246 99.09308 2.72783 10.00166 99.68509 7.66201 9.49194 103.7704 8.455592 9.65113 104.6214 11.00057 11.49697 99.12439 3.71665 10.70835 96.54011 4.04649 10.83841 95.10441 2.9558 10.19218 98.41816 11.00057 8.496972 99.00081 14.30628 8.496972 93.72613 15.11115 11.49697 94.76256 14.64871 11.49697 94.29109 15.49569 11.49697 95.41555 13.73918 11.49697 93.71022 12.6994 11.49697 93.29078 14.60886 11.04698 104.8213 14.99772 10.83605 104.9621 13.23964 11.04697 105.4726 13.57732 10.85606 105.6672 13.0466 10.85606 105.8487 11.76309 11.04697 105.8064 11.82334 10.85606 106.1003 10.24501 11.04697 105.8072 12.30502 9.65113 105.0324 13.54827 9.65113 104.6214 13.01686 9.968562 105.7492 11.81138 9.968562 105.9972 11.00053 9.65113 105.1718 14.67593 8.71842 101.5759 14.33852 9.492382 103.772 14.4425 9.96396 105.1531 14.10963 10.38171 105.6682 12.06853 10.38028 106.2918 10.5399 10.85606 106.133 11.00056 11.48797 104.5008 13.27124 11.48797 104.0102 13.78652 11.49697 103.4717 14.73874 11.49697 102.7124 12.13903 11.48797 104.3768 9.83903 11.48797 104.3768 9.34895 10.85606 105.9544 9.696022 9.65113 105.0324 24.65771 9.874462 80.00003 24.9558 10.19218 94.41816 25.31761 10.48045 94.41388 24.31694 9.33731 80.00232 24.50154 9.656762 93.29487 24.72783 9.955222 93.81954 25.49354 10.59098 93.56623 39.00026 -10.99969 80.00003 39.76828 -10.89972 80.00003 39.00056 -11.00303 85.19011 39.7398 -10.91053 85.59456 40.08883 -10.77342 85.81321 40.50205 -10.59673 80.00003 41.02324 -10.21861 86.44617 41.1212 -10.12139 80.00003 41.72198 -9.24321 87.00869 41.59687 -9.502222 80.00003 41.90019 -8.768052 80.00003 42.00026 -7.99969 80.00003 42.00056 -8.00303 87.25486 27.01505 -10.99559 85.21382 26.2241 -10.90081 80.00083 26.99799 -11.0065 79.96547 25.90226 -10.76947 85.81949 25.49917 -10.59693 80.00003 24.97834 -10.21902 86.44584 24.40259 -9.49962 80.00003 24.27815 -9.240942 87.00955 24.10026 -8.76782 80.00003 24.00026 -7.99969 80.00003 24.00056 -8.00303 87.25486 37.42865 -11.00303 84.38752 28.57306 -11.00303 84.38729 42.00026 8.00031 80.00003 42.00056 7.99698 92.1724 42.00026 6.00031 80.00003 42.00056 4.28707 88.5514 42.00056 2.48084 87.6639 42.00056 1.33137 87.37066 42.00056 -0.003029882 87.25486 24.00026 8.00031 80.00003 24.00056 7.42452 92.80275 24.00056 7.99697 92.1724 24.00056 5.53739 89.58751 24.00056 4.28586 88.55059 24.00056 2.47986 87.66356 24.00056 1.33074 87.37055 24.00056 -0.003029882 87.25485 24.00026 -3.99969 80.00003 24.00026 6.00031 80.00003 41.92687 8.65984 80.00003 41.92871 8.64963 92.46511 41.74207 9.21523 92.83738 41.70312 9.30205 80.00003 41.49958 9.656762 93.29489 41.34298 9.87424 80.00003 40.87493 10.34245 80.00003 40.68932 10.4765 94.44256 40.28997 10.70574 92.56484 40.51466 10.58686 93.59964 40.30249 10.70294 80.00003 40.03181 10.81415 91.43007 39.76017 10.89921 90.28441 39.00026 11.00031 68.44584 39.49199 10.95645 89.19076 39.23637 10.98769 88.17483 39.00056 10.99697 87.25485 24.07241 8.649621 92.46511 24.07367 8.659892 80.00003 24.25905 9.21523 92.83737 25.1258 10.34262 80.00003 25.71664 10.70835 92.54011 25.66303 10.68178 80.0016 26.04649 10.83841 91.10441 26.24052 10.8991 90.28621 27.00026 11.00031 80.00003 27.00056 10.99697 87.25485 26.76369 10.98761 88.179 26.5079 10.95624 89.19575 28.83172 10.99697 86.13398 30.86467 10.99697 85.43849 33.00055 10.99697 85.20285 41.27329 9.955222 93.81955 3.69851 10.70317 84.00003 5.00026 11.00031 84.00003 3.12632 10.34303 84.00003 -3.49865 -10.59694 80.00003 -4.99944 -11.00303 80.00083 -2.87826 -10.12085 80.00003 -2.40227 -9.49953 80 -2.09974 -8.76782 80.00003 -2.05395 -8.57232 87.20533 -1.99974 -7.99969 80.00003 -17.7759 -10.90081 80.00083 -16.99944 -11.00303 83.00083 -16.99974 -10.9997 80.00003 -18.50153 -10.59674 80.00003 -19.12068 -10.1214 80.00003 -19.59635 -9.502222 80.00003 -19.89967 -8.768052 80.00003 -19.99974 -7.99969 80.00003 -10.99974 -11.00136 78.34411 -1.99944 7.99697 80.00083 -1.99974 6.00031 80.00003 -1.99974 -3.99969 80.00003 -19.99974 8.00031 71.65831 -2.34403 9.3815 80.00061 -2.65719 9.87445 80.00003 -3.12528 10.34261 80.00003 -3.62834 10.66877 79.99942 -4.34009 10.92688 80.00003 -4.99974 11.00031 80.00003 -19.92632 8.66 80.00003 -19.70237 9.30253 80.00003 -19.34188 9.87497 80.00003 -18.87368 10.34303 80.00003 -18.30149 10.70316 80.00003 -16.99974 11.00031 80.00003 17.00026 -10.99969 84.00003 17.76828 -10.89972 84.00003 18.50205 -10.59673 84.00003 19.1212 -10.12139 84.00003 19.59687 -9.502222 84.00003 19.90018 -8.768052 84.00003 19.94605 -8.57232 91.20533 20.00026 -7.99969 84.00003 4.2241 -10.90081 84.00081 5.00026 -10.99969 84.00003 3.49847 -10.59674 84.00003 2.87932 -10.1214 84.00003 2.40364 -9.502222 84.00003 2.10032 -8.768052 84.00003 2.00026 -7.99969 84.00003 11.00056 -11.00303 82.164 20.00026 8.00031 84.00003 20.00026 6.00031 84.00003 2.00026 8.00031 84.00003 19.92683 8.66001 84.00003 19.70288 9.30254 84.00003 19.3424 9.87498 84.00003 18.8742 10.34303 84.00003 18.30201 10.70317 84.00003 17.00026 11.00031 84.00003 2.07369 8.66001 84.00003 2.29763 9.30254 84.00003 2.65812 9.87498 84.00003 4.3327 10.83834 80.00003 3.58877 10.63364 80.00016 3.12979 10.3458 80.00003 20.00026 -7.99969 80.00003 20.00026 6.00031 80.00003 2.00087 7.9986 80.00003 2.00026 -7.99969 80.00003 4.92874 11.00031 79.1574 5.00026 11.00031 80.00003 3.71604 -10.59802 79.60369 3.86241 -10.59802 81.40355 2.42948 -9.53943 80.0016 4.98589 -10.99969 79.62123 5.01205 -10.99969 81.49244 5.00026 -10.99969 82.40481 17.17464 -10.99969 78.69107 17.00672 -10.99969 81.49743 -16.99974 -10.99969 71.07357 2.11456 -8.8199 80.00003 -2.8341 -10.59802 77.81888 -4.20597 -11.00002 77.5193 -2.16309 -9.498332 78.95822 -1.73179 -7.99969 79.00003 -1.49683 -9.498332 78.12275 -1.41395 -7.99969 78.58583 -0.99974 -7.99969 78.26799 -2.13715 -10.99969 75.47991 -0.91783 -10.59777 76.62258 -0.53404 -9.498332 77.65908 -0.51738 -7.99969 78.06819 -1.22603 -10.99969 75.15274 0.59526 -10.59777 76.55097 0.69725 -10.99969 75.04885 -0.26943 -10.99969 75.0073 2.6e-4 -7.99969 78.00003 0.53456 -9.498332 77.65908 0.51789 -7.99969 78.06819 1.6381 -10.99969 75.2759 1.9969 -10.59777 77.12541 2.51731 -10.99969 75.67978 1.49734 -9.498332 78.12275 1.00026 -7.99969 78.26799 1.41447 -7.99969 78.58583 3.30253 -10.99969 76.24569 3.02454 -10.59777 78.23831 3.96375 -10.99969 76.95195 2.16361 -9.498332 78.95822 1.73231 -7.99969 79.00003 4.4766 -10.99969 77.77239 4.82196 -10.99969 78.67671 1.93211 -7.99969 79.48239 18.40394 -10.64841 79.90622 19.58443 -9.498022 79.9998 19.89211 -8.797942 80.00003 19.92081 -9.498332 78.79946 20.06841 -7.99969 79.48239 18.99247 -10.59777 78.21028 17.51946 -10.99969 77.78138 20.26821 -7.99969 79.00003 18.03361 -10.99969 76.95607 20.79969 -9.498332 77.92057 20.03621 -10.59777 77.10305 20.58604 -7.99969 78.58583 21.00025 -7.99969 78.26799 18.69775 -10.99969 76.24591 19.48711 -10.99969 75.67753 21.45118 -10.59777 76.54338 20.37126 -10.99969 75.27282 21.48263 -7.99969 78.06817 22.00026 -9.498332 77.59889 22.0002 -7.99969 78.00003 21.31737 -10.99969 75.04689 22.28898 -10.99969 75.00837 36.38472 -10.99969 74.66987 -4.24974 -10.99969 75.50003 3.15365 10.59839 78.48143 4.70803 11.00031 78.31571 2.65477 9.87078 80.00003 2.34381 9.38248 79.99777 2.16361 9.49895 78.95822 2.07547 8.66787 80.00003 1.81694 7.99696 79.12403 4.33671 11.00031 77.51101 2.18247 10.59839 77.26362 3.19481 11.00031 76.15364 3.82524 11.00031 76.77986 1.49734 9.49895 78.12275 1.35816 7.99634 78.50424 2.47028 11.00031 75.65274 0.77908 10.59839 76.58777 1.67287 11.00031 75.2881 0.53456 9.49895 77.65908 0.70652 7.9977 78.11434 0.82237 11.00031 75.06807 0.003619909 7.99684 77.98102 -0.77857 10.59839 76.58777 -0.93444 11.00031 75.08818 -0.05690991 11.00031 75.00036 -0.53405 9.49895 77.65908 -0.73896 7.99722 78.12483 -1.7798 11.00031 75.32762 -2.18196 10.59839 77.26362 -2.56862 11.00031 75.71041 -1.49683 9.49895 78.12275 -1.3497 7.99713 78.50263 -3.28124 11.00031 76.22753 -3.15313 10.59839 78.48143 -4.38788 10.99998 77.50109 -2.16309 9.49895 78.95822 -1.81518 7.9965 79.11428 -4.96166 11.00031 79.38407 -4.846 11.00031 78.76966 17.668 10.88732 80.00003 17.00026 11.00031 80.00003 18.39397 10.64952 80.00267 18.87074 10.3458 80.00003 19.34576 9.87077 80.00003 19.65764 9.37099 80.00058 20.0261 8.00223 79.78579 21.22144 10.59839 76.58777 22.77908 10.59839 76.58777 21.17697 11.00031 75.06827 22.05642 11.00031 75.00035 22.53456 9.49895 77.65908 21.46596 9.49895 77.65908 22.00362 7.99684 77.98102 21.26106 7.99722 78.12483 20.32602 11.00031 75.28868 19.81805 10.59839 77.26362 19.52892 11.00031 75.65348 20.50317 9.49895 78.12275 20.65031 7.99713 78.50263 18.80557 11.00031 76.15374 18.84687 10.59839 78.48143 17.66463 11.00031 77.50957 18.17623 11.00031 76.77873 19.83691 9.49895 78.95822 20.18043 7.99652 79.12062 17.29248 11.00031 78.31575 17.07212 11.00031 79.15538 33.00041 -11.01419 78.34452 35.76831 -11.00303 83.83885 33.00057 -11.00303 83.54885 30.23315 -11.00303 83.83877 42 -4.37194 66.4732 39.02267 -11.00002 75.08294 40.44828 -10.60419 74.80902 22.96992 -10.59777 76.63703 23.24969 -10.99969 75.15866 22.51792 -7.99969 78.06819 23.20083 -9.498332 77.92057 24.16356 -10.99969 75.49224 23.00026 -7.99969 78.26799 24.4262 -10.59802 77.57001 25.97642 -11.00002 77.80838 25.02965 -10.99969 76.31192 24.07971 -9.498332 78.79946 23.41448 -7.99969 78.58583 23.73231 -7.99969 79.00003 23.93211 -7.99969 79.48239 41.17694 -10.06092 74.9608 41.68639 -9.552021 74.60721 41.99767 -8.01113 74.09465 42 -5.53847 70.52472 26.96239 11.00031 79.38578 25.15365 10.59839 78.48143 25.81986 10.88883 78.11775 26.77643 10.99998 78.09215 26.84682 11.00031 78.77086 24.16361 9.49895 78.95822 23.94208 7.99737 79.45581 23.60646 7.99701 78.77993 24.18247 10.59839 77.26362 25.28084 11.00031 76.22673 23.49735 9.49895 78.12275 23.20683 8.00031 78.40497 24.56712 11.00031 75.70919 23.77808 11.00031 75.32676 22.70653 7.99771 78.11434 22.93337 11.00031 75.08786 28.40349 -8.47888 11.38139 32.41966 -10.39946 12.09684 32.07041 -8.486082 13.14744 24.01463 -8.49968 5.09246 25.93359 -9.85955 5.58086 26.40131 0.004699945 11.02765 27.30582 -10.22031 6.25849 26.51307 -10.34244 5.16882 27.05665 0.00901997 11.89372 28.55564 -9.64302 7.14186 29.56896 -8.933712 8.01146 30.37484 -8.14502 8.837532 35.00025 -7.43725 9.41716 35.00025 -5.76714 10.52316 35.00025 -3.93633 11.33593 26.34064 -17.95326 2.99867 26.92072 -18.59914 4.80043 25.76056 -17.30739 1.19691 27.72791 -19.13109 6.6871 28.53512 -19.66305 8.57377 32.07253 -12.24215 12.44397 25.97391 -12.57047 6.52178 31.50558 -13.97236 13.01092 25.38119 -14.24428 7.11449 30.73585 -15.5381 13.78065 24.59638 -15.75172 7.89931 29.78649 -16.89231 14.73002 23.64218 -17.04913 8.8535 28.686 -17.99429 15.83051 22.54626 -18.09895 9.94944 21.34031 -18.87077 11.15537 27.46747 -18.81092 17.04904 31.63869 -14.49044 14.44563 35.00025 -8.90012 8.04876 35.00025 -10.11498 6.45608 35.00025 -11.04798 4.68351 27.40025 -11.09018 4.58269 35.00025 -11.67312 2.78043 27.40025 -11.64889 2.88028 27.40025 -11.94789 1.11366 35.00025 -11.97299 0.79989 27.40787 -11.94871 -0.93186 27.92001 -11.98834 -0.52151 28.45432 -11.99809 -0.19525 28.99234 -11.99966 -0.01994997 29.53337 -11.99967 0.01541996 35.00025 -11.93923 -1.20295 30.05848 -11.99939 -0.08360999 30.60025 -11.99514 -0.3301 31.96513 -11.92772 -1.31218 35.00025 -11.57278 -3.17227 33.17361 -11.74079 -2.47917 26.69314 -11.32162 2.97827 26.40025 -10.42215 3.51742 26.40025 -10.82463 1.95457 26.69314 -11.69481 0.52945 26.40025 -10.99412 0.34963 27.09578 -11.87235 -1.37935 26.71759 -11.59961 -1.87068 26.40025 -10.92695 -1.26282 26.40025 -10.62459 -2.848 26.45649 -11.05894 -2.46479 22.28349 -8.49967 5.96955 22.19817 -9.88384 6.05487 23.33167 -11.28459 5.48867 24.85194 -11.60693 5.52242 21.94514 -11.22494 6.30791 22.47212 -13.82473 6.34822 21.53238 -12.48305 6.72066 23.8929 -14.44108 6.48147 20.97256 -13.6208 7.28049 21.12374 -15.89684 7.69661 20.28258 -14.60443 7.97046 22.38843 -16.75303 7.98593 19.48311 -15.40482 8.76993 19.40502 -17.3188 9.41533 20.47079 -18.33958 9.90358 18.59801 -15.99816 9.65504 17.46704 -17.96563 11.35331 17.65359 -16.36674 10.59945 18.30849 -19.06128 12.06588 20.05931 -19.34222 12.43639 18.74032 -19.49967 13.75538 33.46514 -13.23542 -4.38076 32.28778 -13.85514 -3.54525 31.81377 -14.02564 -3.2714 30.60025 -14.46437 -2.79934 31.22617 -14.24843 -3.01115 29.9921 -14.63437 -2.69853 29.33738 -14.75585 -2.73755 28.62729 -14.79947 -2.94482 28.06561 -14.7988 -3.22255 27.51717 -14.71325 -3.63394 27.05751 -14.55941 -4.13271 26.67791 -14.31856 -4.75935 26.48153 -14.05493 -5.30128 26.40025 -13.70245 -5.92586 25.69386 -14.36625 -4.94372 23.40025 -15.35262 -3.49112 24.57748 -13.49051 -6.58541 26.40025 -12.58132 -7.37889 24.43242 -12.36088 -7.8829 26.40025 -11.22704 -8.632081 24.26431 -11.0518 -8.980502 26.40025 -9.674262 -9.6486 24.07885 -9.60768 -9.85022 26.40025 -7.98379 -10.39032 23.88002 -8.059472 -10.48215 26.40025 -6.18543 -10.84599 23.67152 -6.43582 -10.86809 23.45517 -4.75135 -10.99998 26.40025 -4.32847 -10.99998 26.40025 3.2e-4 -10.99998 20.80625 -4.91046 -11.00022 18.49701 -4.88507 -10.99054 17.80788 0.01880997 -10.9689 22.28349 -7.74968 5.96955 16.67795 -16.49934 11.57509 19.83408 -7.73186 8.35991 17.67848 -2.25269 -10.97997 17.34177 -13.08415 -7.20827 19.67205 -14.44833 -5.4625 17.10318 -14.40371 -5.27381 21.01717 -14.45248 -5.46438 20.86789 -13.10861 -7.33403 17.48629 -11.32987 -8.83812 20.8567 -11.35649 -8.91332 17.65667 -9.2618 -10.04914 20.84362 -9.30734 -10.08299 17.84032 -7.0325 -10.77014 20.82957 -7.10759 -10.77832 16.21432 -4.66904 -11.01523 17.62941 -16.83755 -0.5810599 20.1615 -16.82432 -1.00218 23.59675 -18.29618 2.50571 18.73591 -18.84136 3.9695 21.2089 -18.77235 3.32658 25.02458 -19.7664 6.56035 20.33439 -20.43481 8.38561 16.32313 -18.63193 4.7582 22.72505 -20.30991 7.52829 17.9938 -20.21678 9.37161 26.83457 -20.85997 10.49577 22.33832 -21.628 12.67456 24.62881 -21.45601 11.60831 20.08241 -21.41371 13.85312 15.74767 -19.64619 10.48574 17.90191 -20.78959 15.13328 29.58687 -20.05982 10.55783 28.95048 -21.59927 14.31421 30.63861 -20.45659 12.5419 26.83901 -22.22966 15.57205 29.24789 -16.00011 0.24119 32.72167 -14.68274 -0.7800599 33.49831 -15.35544 1.85466 30.21492 -16.97527 3.37437 34.47482 -15.903 4.43261 31.44747 -17.74713 6.43113 32.90879 -18.32579 9.408902 35.62984 -16.33092 6.95043 34.56216 -18.72138 12.30514 31.93859 -20.68924 14.62077 26.40025 -5.99968 6.00002 26.39507 -7.73162 5.01777 42.02021 -13.83867 14.29794 42.00025 -11.52747 14.08449 42.00025 -13.19034 14.22324 36.07827 -8.49957 15.91769 30.44322 -16.8216 15.96259 41.79856 -15.10147 14.19988 41.72396 -14.98816 14.96006 41.57338 -15.56666 14.15114 41.17762 -15.92868 15.16058 41.90142 -13.68791 14.8816 41.47512 -13.70568 15.47655 40.1245 -15.27101 15.93375 40.58631 -14.5679 15.87018 40.74386 -13.57435 15.74587 41.99378 -9.96123 14.29538 42.01282 -6.8414 14.96249 41.68601 -7.84641 15.45743 42.00025 -9.20317 14.24873 41.76836 -10.68854 14.90432 36.80173 -18.68935 15.87163 36.39445 -18.92611 15.09958 40.17875 -16.92108 14.2656 40.32484 -16.7515 15.04228 42.00025 3.2e-4 18.4377 42.00025 -2.45947 16.88493 42.00025 -11.5709 7.14655 42.00025 -4.59768 15.6645 42.00025 -12.6909 10.55045 35.70737 -3.55614 11.15385 35.02811 3.8e-4 11.99572 36.00025 -1.84419 10.84427 36.00025 -3.63533 10.38183 35.70737 -6.77643 9.54632 36.00025 -5.3225 9.62642 36.00025 -6.8584 8.599902 35.70737 -9.356202 7.03648 36.00025 -8.204812 7.32639 36.00025 -9.31814 5.84519 35.70737 -11.05159 3.86156 36.00025 -10.16628 4.20001 41.57278 -13.76807 8.916602 41.54034 -12.20096 3.64142 40.27235 -13.74717 5.04463 40.17191 -14.74203 7.98176 40.18572 -15.74563 10.95823 38.94659 -14.4825 5.4868 36.94197 -16.64471 9.40475 38.38988 -16.84989 11.7922 42.00025 -10.67037 4.09574 42.00025 3.41451 23.22383 42.00025 2.48337 21.60508 42.00025 8.00032 2e-5 26.46544 8.99548 11.93412 26.40025 11.00032 12.00002 35.0163 10.99907 11.99931 35.77664 10.99998 11.66451 35.50025 3.2e-4 11.86604 35.70735 3.2e-4 11.70713 35.86629 3.2e-4 11.50002 36.00155 2.1e-4 11.04207 36.00002 10.99987 11.00577 40.37364 3.2e-4 17.38355 27.01681 -0.01592993 12.24287 35.02872 -8.8e-4 13.18408 42.00025 1.33143 20.13088 35.08573 -11.80042 -6.21055 35.6059 -10.89876 -7.17275 35.39104 -11.27122 -6.77528 36.00025 -10.7261 2.43799 35.70737 -11.70236 0.32165 36.00025 -10.98286 0.60792 36.00025 -10.92969 -1.23884 35.70737 -11.24701 -3.24866 36.00025 -10.56956 -3.04589 35.00025 -10.88384 -5.05319 36.00025 -9.911642 -4.76999 35.75685 -9.60337 -6.61508 35.5237 -10.17083 -6.08431 35.279 -10.59459 -5.5635 36.00025 -8.97281 -6.3626 36.00025 -7.77785 -7.77815 35.9585 -8.66244 -7.28348 34.20457 -11.39358 -3.76549 41.7905 -3.19041 -8.87215 41.74584 -1.03501 -9.19167 42.00025 -2.56724 -7.87044 41.12244 -3.40579 -9.86748 41.19122 -1.03675 -10.06104 40.10453 -3.96232 -10.42355 39.16365 -2.79369 -10.86731 39.00025 -1.03347 -10.99998 40.21046 -1.03285 -10.73259 39.3138 -4.48102 -10.48149 42.00025 -4.01987 -7.49524 41.7905 -5.24932 -8.18534 41.12244 -5.67564 -9.11018 40.10453 -6.72086 -9.32951 39.45084 -6.08439 -9.85265 42.00025 -5.36798 -6.89018 41.7905 -7.10811 -7.05961 41.12244 -7.73129 -7.86504 39.57241 -7.56018 -9.00133 40.10453 -9.11759 -7.54226 39.67771 -8.880762 -7.94826 42.00025 -6.5857 -6.06749 41.7905 -8.662281 -5.53635 42.00025 -7.60726 -5.08037 41.12244 -9.45589 -6.17451 39.76682 -10.0302 -6.70475 40.45203 -11.22837 -3.75614 39.88445 -11.55432 -3.6065 42.00025 -8.435001 -3.93784 41.7905 -9.81318 -3.68584 40.9985 -10.87407 -3.69893 42.00025 -9.03509 -2.69427 42.00025 -9.39662 -1.4047 41.83179 -10.32557 -1.5804 41.3948 -11.0788 -1.49077 35.70857 -12.46417 -4.83861 35.9755 -13.18312 -2.76718 38.22656 -12.1883 -3.49941 34.38255 -12.56367 -5.28364 38.50327 -9.6095 -7.80173 35.90602 -9.91289 -8.07624 37.77982 -7.1914 -9.58309 36.00025 -8.87659 -8.876892 36.00025 -7.36012 -9.77793 36.9552 -4.63787 -10.65916 36.00025 -5.67979 -10.45227 36.00025 -3.91054 -10.86221 36.00243 -2.08998 -11.00132 37.007 -1.75784 -10.99998 42.00025 -9.964241 1.3075 39.99825 -12.45262 -0.54363 36.62261 -13.68488 -0.23197 42.00025 5.13849 -6.1318 42.00025 6.12571 -5.14582 42.00025 6.92669 -4.00314 42.00025 7.51684 -2.73896 42.00025 7.87836 -1.39154 42.00025 3.99485 -6.93134 42.00025 2.73022 -7.5198 42.00025 1.38154 -7.87984 42.00025 -1.03347 -7.99998 42.00025 3.2e-4 -7.99998 36.00025 3.2e-4 -10.99998 36.00025 10.86488 -1.72084 36.00025 10.46189 -3.39933 36.00025 9.80128 -4.99409 36.00025 8.899312 -6.46588 36.00025 7.77821 -7.77843 36.00025 6.46557 -8.89945 36.00025 4.99391 -9.80121 36.00025 3.39927 -10.46168 36.00025 1.72095 -10.86458 36.00025 11.00032 2e-5 39.00025 1.64007 -10.87708 39.00025 3.2e-4 -10.99998 39.00025 3.24445 -10.51072 39.00025 4.7755 -9.90945 39.00025 6.1986 -9.08741 39.00025 7.48293 -8.0629 39.00025 8.60061 -6.85818 38.97711 10.48833 -3.49898 39.00025 11.00032 2e-5 39.00025 10.89241 -1.81744 40.4095 7.5e-4 -10.63608 39.66782 3.2e-4 -10.92476 41.59834 2.4591 -9.17628 41.92503 3.2e-4 -8.66754 41.64241 0.002799928 -9.40393 40.49889 2.87802 -10.2007 41.34576 3.2e-4 -9.87045 40.87072 3.2e-4 -10.34547 41.59834 4.75032 -8.22722 40.49889 5.53952 -9.03619 41.59834 6.71784 -6.71749 40.49889 7.78487 -7.19279 41.59834 8.22756 -4.74998 40.44881 9.92724 -3.464 41.59834 9.17661 -2.45876 39.66782 10.9251 2e-5 40.39354 10.64984 -0.002829909 40.87072 10.34581 2e-5 41.34576 9.87079 2e-5 41.69691 9.311882 5e-5 41.92503 8.667881 2e-5 38.00713 -1.40528 -10.99998 39.68842 -1.03347 -10.91998 41.92567 -1.03347 -8.664792 39.03521 10.99585 49.49406 42.00125 -0.71631 18.43795 42.00025 4.55122 26.76701 42.00025 4.1072 24.95292 42.00047 4.69463 28.6318 41.81115 -1.86582 18.29768 41.23049 -3.3002 17.89993 41.47659 -2.75849 18.06089 12.48855 3.2e-4 15.79748 42.00025 3.2e-4 18.84805 37.1356 3.2e-4 19.3314 33.23856 -20.92189 16.69965 40.76066 -15.52186 15.75186 40.06757 -16.00425 15.87182 40.22589 -16.42364 15.52246 33.35737 -19.37798 18.47003 36.38074 -17.22534 16.86729 34.80528 -18.14896 17.55974 36.71384 -18.03838 16.64432 38.0946 -16.32222 16.33485 33.58095 -19.83546 18.33454 33.70298 -20.36124 17.97837 33.54759 -20.85854 17.23245 30.69171 -22.24771 18.43515 31.41272 -21.9537 17.9378 31.62679 -21.89856 18.60094 31.84028 -21.44528 19.19137 31.80485 -20.76753 19.56405 32.26551 -19.55745 19.0903 41.25215 -11.00445 15.38839 40.64713 -11.32652 15.5772 40.52986 -9.02008 15.7978 41.13953 -8.51999 15.75002 40.40797 -6.80917 16.37213 41.01591 -6.13438 16.52875 41.58786 -5.17697 16.53332 40.38424 -4.48807 17.39218 41.93192 -4.01259 16.46582 40.92645 -3.84365 17.70303 35.71275 -9.705142 15.91657 35.29206 -10.91734 16.03666 39.14009 -13.04748 15.91207 36.25659 -12.37569 16.18199 35.09933 -11.52614 16.16336 34.118 -13.0561 16.55865 38.58134 -14.43949 16.13066 41.26543 -14.7604 15.59121 31.477 -15.17923 17.95153 29.34525 -16.44808 19.29175 33.81829 -18.5521 18.04126 35.41711 -17.43465 17.18347 33.03078 -13.91455 16.94669 36.99712 -16.05521 16.52683 29.02715 -17.60599 18.87498 30.80184 -16.13773 17.10029 28.50963 -18.42133 17.89618 33.63822 -12.77722 15.80506 19.14005 -0.003129959 29.62204 19.25456 -9.92532 29.53012 19.10081 -10.63181 29.65857 19.40948 -9.26246 29.4442 19.71731 -0.01337999 29.35701 19.56011 -8.67049 29.39129 19.77643 -7.90248 29.36016 20.02914 -7.07309 29.38228 20.37775 -0.00296998 29.53156 20.26107 -6.37132 29.4636 20.44985 -5.8276 29.58583 20.7931 -0.0173999 30.14644 20.6622 -5.25023 29.82252 20.78845 -4.83021 30.14517 26.16752 -19.31767 18.34898 24.82522 -19.49928 19.69128 23.48092 -19.35032 21.03558 17.42155 -19.33856 15.07414 22.17502 -18.87526 22.34149 16.1412 -18.86353 16.3545 20.94673 -18.08838 23.56977 14.93633 -18.08837 17.55936 16.27308 3.1e-4 32.48607 18.94978 -11.71702 29.80163 16.99428 -9.818001 31.76487 19.11136 -12.30309 29.54573 16.69925 -10.41788 31.94676 19.6621 -13.33201 28.79598 20.01768 -13.85381 28.33473 19.37698 -12.71614 29.27196 20.37682 -14.31138 27.89106 16.30979 -10.98208 32.00586 15.84935 -11.48071 31.94183 21.59014 -15.58498 26.50465 22.34574 -16.22029 25.72818 20.96544 -14.97776 27.1939 23.14839 -16.87866 24.86746 22.80765 -17.27495 24.78397 15.35213 -11.88407 31.76529 22.34495 -17.61963 24.59531 21.90648 -17.85584 24.34608 14.83885 -12.18266 31.4894 21.39506 -18.03484 23.97552 14.32936 -12.36808 31.12733 28.39665 -17.08982 20.17261 26.32936 -19.14903 20.07644 27.02606 -18.2739 20.87608 27.43289 -17.51014 21.05084 26.40682 -17.71803 21.98106 24.09405 -18.94074 22.31176 24.97444 -18.08273 22.9277 25.32321 -17.67927 22.96893 24.25482 -17.38544 23.94788 15.52851 -17.95703 24.59626 20.26193 -19.8896 26.44864 19.21382 -18.99056 27.48281 21.24988 -20.69806 25.57821 19.74209 -20.53287 23.21115 21.68996 -20.62116 26.04128 18.19185 -18.06313 28.61582 18.99066 -17.98845 29.04796 16.93622 -16.85897 30.15848 22.36362 -20.15979 26.4117 19.74082 -17.36263 29.20481 16.33141 -15.51816 32.23312 22.83073 -19.52563 26.367 20.1572 -16.65143 28.87078 17.21596 -14.86782 32.39308 21.27265 -17.60897 27.6795 23.00918 -19.02773 26.10273 30.56804 -19.94081 20.11286 31.13405 -20.31158 19.93937 29.85641 -20.68763 20.83753 28.9377 -20.18408 21.221 28.59649 -20.85482 21.73916 27.35306 -20.11139 22.33947 27.13896 -20.80618 22.81975 25.85386 -19.72125 23.44513 25.655 -20.47569 23.97182 24.46295 -19.04943 24.50942 24.21118 -19.83891 25.12656 23.19882 -18.14021 25.50323 22.07966 -17.02658 26.40912 21.12335 -15.73274 27.21873 17.49983 -14.38133 32.22545 24.66112 -22.43105 16.84363 22.5027 -22.21692 18.20887 20.40215 -21.55375 19.64544 16.91113 -19.99842 18.42206 18.23429 -20.36765 20.84409 29.12959 -22.67236 19.52596 29.80934 -22.52407 19.04911 27.17079 -22.85069 20.93243 27.99811 -22.82753 20.33094 25.20728 -22.62564 22.41558 26.17777 -22.79241 21.67212 22.79481 -21.72366 24.32347 23.60282 -22.11311 23.67622 24.43566 -22.42148 23.0167 22.01063 -21.2525 24.95752 29.93627 -21.36656 20.86929 29.86304 -22.07504 20.56567 29.57405 -22.5463 20.02341 28.03761 -21.54364 22.23441 27.85562 -22.26048 22.00524 27.48744 -22.73599 21.51744 26.18318 -21.30885 23.6408 25.89422 -22.0113 23.49062 25.44652 -22.47526 23.06171 24.41178 -20.65827 25.0442 24.02091 -21.32278 24.97271 23.50173 -21.75924 24.59907 17.11525 -13.81543 32.82057 -2.29975 -2.19968 10.00002 1.41852 -2.18136 8.50479 2.10002 -2.1863 8.88863 2.29769 -2.19447 9.43571 2.30026 -2.19968 10.00002 15.58798 -19.62919 16.00003 13.38918 -18.54927 11.10375 14.01899 -18.14679 5.70158 11.69067 -17.19778 6.20609 15.7002 -16.39166 12.55285 14.74955 -16.0464 13.5035 13.85454 -15.47327 14.39851 7.96479 -5.69968 20.28825 6.74123 -9.818001 21.51182 6.44189 -9.49952 21.81116 6.15404 -8.86181 22.10996 6.22134 -0.003749907 22.03882 6.02004 -8.07461 22.23301 15.4237 -15.28663 32.26079 12.34679 -14.95873 28.08375 8.56765 -12.45528 30.71025 6.45156 -12.39952 27.24239 9.72782 -15.05955 23.61681 13.13618 -17.59838 20.42722 4.79622 -12.34811 23.80456 7.3538 -14.73762 19.06055 3.31448 -12.27908 19.90975 11.06191 -17.0369 16.10123 5.7965 -14.29902 15.81472 2.03309 -12.17345 15.57592 2.30026 -12.41869 14.50002 9.326022 -16.29676 11.64083 4.45563 -13.7603 8.99367 2.30026 -12.7135 9.36678 7.94874 -15.40209 7.06861 2.30026 -12.66151 4.17627 2.30026 3.2e-4 10.00002 2.30026 -5.99968 14.50002 2.29793 -6.49553 9.455471 1.35699 -6.49441 8.502962 -1.36301 -6.49383 8.50314 -1.37883 -2.19331 8.503372 1.9934 -6.4836 8.769742 6.02004 -8.074602 26.47565 5.60269 -8.074602 25.95281 6.02004 3.1e-4 26.47565 5.60119 3.1e-4 25.95042 5.31731 -8.074602 25.36663 5.30971 3.1e-4 25.34517 5.16495 -8.074602 24.72983 5.16022 3.1e-4 24.69022 5.15527 -8.074602 24.06575 5.16022 3.1e-4 24.01844 5.29752 -8.074602 23.39905 5.30971 3.1e-4 23.36349 5.59 -8.074602 22.77618 5.60119 3.2e-4 22.75823 5.67436 -9.66423 22.90164 6.56361 -10.39752 21.79493 6.50046 -10.93473 22.15888 5.54018 -10.15569 23.95551 6.54932 -11.42115 22.59446 6.71143 -11.83646 23.08675 5.83148 -10.48407 25.04063 6.98741 -12.15973 23.61972 7.36413 -12.36337 24.15835 6.71724 -11.05583 25.77845 6.10162 -9.14249 26.39407 6.33935 -10.15108 26.15634 7.21442 -11.82133 25.28127 7.82302 -12.43309 24.67267 14.49035 -18.0228 17.06126 14.0894 -17.80055 16.48177 13.84051 -17.51784 16.00994 13.66921 -17.10376 15.50945 13.6162 -16.65177 15.09983 13.67642 -16.05519 14.68301 16.09159 -18.85471 14.28278 15.48012 -17.78049 13.34023 13.83343 -12.4331 30.68308 12.03045 3.1e-4 32.48607 12.03045 -8.074602 32.48607 13.21518 -11.80923 31.30133 12.70999 -11.02191 31.80652 12.33751 -10.1127 32.17901 12.1093 -9.12466 32.40722 1.7e-4 -11.18913 19.04369 -0.07635998 -11.28434 16.80128 0.5104 -11.45072 16.74273 1.36779 -11.78772 16.34723 1.75114 -11.99076 15.99146 2.55636 -11.7272 21.34209 0.96721 -11.61329 16.58688 1.51737 -11.1812 23.97205 -0.46236 -10.99969 24.08346 4.38211 -11.7272 26.07354 1.31037 -10.99969 28.35049 3.5336 -11.1812 28.57728 3.40761 -10.99969 32.26215 6.74065 -11.7272 30.53661 6.07224 -11.1812 32.91627 -0.277 3.2e-4 16.78325 0.27751 3.2e-4 16.78325 0.8159 3.2e-4 16.65054 1.30688 3.2e-4 16.39283 1.7219 3.2e-4 16.02512 2.03685 3.2e-4 15.5688 2.23344 3.2e-4 15.05038 2.30026 3.2e-4 14.50002 18.44563 3.2e-4 14.19056 7.94215 -9.49526 -8.74049 5.79498 -8.75979 -8.48912 11.03062 -9.83635 -9.103401 16.37179 -9.38429 -9.929182 5.20335 -6.40573 -7.44079 16.19582 -6.6725 -7.99255 16.19854 -5.91443 -7.05481 5.21083 -5.34324 -6.28933 16.20295 -5.21217 -6.09823 5.21083 -4.46593 -4.8577 16.21576 -4.45627 -4.43457 5.21083 -3.82337 -3.30643 16.20252 -3.79117 -2.54029 5.21083 -3.43141 -1.67376 16.19454 -3.58016 -1.05025 5.21083 -3.29968 2e-5 16.22372 -3.54935 -0.03472989 16.20554 -2.27144 2e-5 4.65165 -6.42327 -9.95994 4.67074 -4.85293 -10.53826 4.75562 -5.59203 -10.16753 2.5e-4 -6.49968 2e-5 2.5e-4 -2.19968 2e-5 2.5e-4 -6.49968 1.50002 2.5e-4 -2.19968 1.50002 5.211 -7.77663 -8.83886 5.10653 -8.62178 -8.75723 4.67872 -7.97769 -9.10889 5.56788 -9.22203 -8.36796 4.77767 -3.38496 -10.84126 5.21512 -3.95656 -10.43942 5.211 -5.29716 -9.87299 5.21083 -6.45814 -9.39643 4.52895 -2.93278 -10.9321 4.68751 -1.54675 -8.49243 5.21083 -2.71436 -8.735001 5.21083 -1.68769 -7.07249 5.21083 -0.88467 -5.29111 5.21083 -0.31883 -3.42085 5.21083 3.2e-4 0.02375996 16.20164 -3.87406 -8.524291 16.20554 -8.50857 -9.78222 16.19149 -7.38475 -10.66326 15.68676 -10.02945 -9.58225 13.70732 -10.13295 -9.30496 2.30026 -12.2811 -1.05123 2.30026 -11.93863 -2.86297 4.55497 -12.84383 -1.73477 7.08376 -13.40058 -2.55376 9.88299 -13.91818 -3.49883 2.30025 -11.27331 -4.62131 10.07449 -13.24681 -5.12989 2.30025 -10.29997 -6.25599 10.33482 -12.33418 -6.62453 2.30025 -9.043931 -7.71364 10.65601 -11.20818 -7.94218 2.30025 -7.52813 -8.955471 2.30025 -5.81076 -9.92659 2.30025 -3.94129 -10.59819 2.30025 -1.96335 -10.9499 1.40157 -6.49028 1.49476 1.40112 -2.19185 1.49557 2.29917 -6.49742 0.52472 2.01772 -6.48097 1.21033 2.28986 -2.1686 0.7134 1.91201 -2.18626 1.29958 -2.29975 -6.49968 2e-5 2.30028 -0.53686 -8.14923 2.31554 0.01653999 -3.92797 2.29455 -1.26716 -0.9975399 2.28722 -1.81631 -0.7952899 2.27369 -2.19633 -0.16031 10.51843 -15.63732 1.33572 6.95038 -14.37706 2.40713 3.51229 -13.13803 3.88576 17.23772 -3.05346 -10.96482 16.18242 -3.40822 -11.02232 17.22123 -1.64601 -8.41791 16.2002 -2.61073 -9.88012 16.20301 -3.46626 -7.26 16.20633 -3.06177 -5.94197 16.24841 -1.38861 -7.1104 16.20823 -2.70407 -4.54705 16.20536 -2.4366 -3.05215 16.19878 -2.29308 -1.47717 13.68469 -14.26965 -4.67984 13.77124 -13.2465 -6.4377 14.00948 -11.86053 -8.03449 15.15664 -16.66497 0.006769955 12.79545 -16.31463 0.77954 -2.31627 -2.09971 -0.45265 16.29574 0.01832991 0.009949982 17.69897 6.92263 -0.90656 17.7 8.17118 -6.31599 17.70071 6.93745 -7.57629 17.7 9.01431 -5.2704 17.70026 9.00032 -3.32453 17.69255 9.02092 -0.82214 17.9133 7.12353 -8.09596 18.281 7.47546 -8.13672 18.281 8.714672 -6.71267 18.281 9.49011 -5.5627 18.28946 10.09972 -4.3549 17.7 9.62212 -4.30022 17.80645 10.63646 -0.01969999 17.63077 10.52348 0.25821 17.94184 10.79483 0.38153 18.09589 10.91687 0.92458 17.46791 10.46586 0.40571 17.83099 10.86485 1.34917 18.27831 10.98081 1.4733 18.43223 10.99463 1.9448 17.64867 10.12079 -0.44572 17.70586 10.24945 -2.09048 17.70026 9.79379 -3.02493 18.28079 10.77432 -2.24154 18.33503 10.99501 -0.001329958 17.70025 3.2e-4 2e-5 17.70026 3.2e-4 -6.72382 17.58226 3.2e-4 -4.95369 17.15031 3.2e-4 2e-5 17.21782 5.8e-4 -2.76679 17.70026 -1.22318 -9.62563 17.70026 -0.55721 -8.19757 17.22123 -0.61647 -5.65771 16.26741 -0.45891 -4.49718 16.2005 3.2e-4 -1.73222 16.20426 -0.28531 -3.352 16.70025 9.00032 2e-5 16.75961 6.80614 0.1259999 3.21558 7.33902 0.009579956 17.70026 5.92604 -8.363492 17.91993 4.97721 -9.56273 17.70026 4.86644 -9.02125 18.45026 5.90116 -9.28331 18.45026 4.61769 -9.98395 17.70026 3.7954 -9.521532 17.91993 2.56215 -10.47149 18.45026 3.34297 -10.4798 17.70026 2.74612 -9.87536 18.45026 2.12328 -10.79317 17.70026 1.74768 -10.09994 18.45026 0.99835 -10.95461 3.26448 10.99998 1.82656 3.17098 10.89998 1.30254 17.2886 10.70415 0.94977 3.23595 9.184 -4.1e-4 16.71546 9.70102 0.11947 17.68258 0.41522 -10.32299 17.7 6.04312 -0.72008 17.70026 5.1811 -0.259 26.31675 0.004699945 11.43307 37.50025 3.2e-4 21.00002 8.00662 3.2e-4 20.25202 37.40801 3.2e-4 20.14595 26.40025 11.00032 2e-5 26.40025 3.2e-4 6.00002 26.40025 1.72095 -10.86458 26.40025 3.39927 -10.46168 26.40025 4.99391 -9.80121 26.40025 6.46557 -8.89945 26.40025 7.77821 -7.77843 26.40025 8.899312 -6.46588 26.40025 9.80128 -4.99409 26.40025 10.46189 -3.39932 26.40025 10.86488 -1.72084 -0.81539 3.2e-4 16.65054 -1.30637 3.2e-4 16.39283 -1.72139 3.2e-4 16.02512 -2.03634 3.2e-4 15.5688 -0.05216991 10.99998 3.2123 2.61186 10.99627 0.89395 -3.23746 10.99975 1.76078 -2.30683 5.2997 -0.9867799 2.30025 3.2e-4 -0.99998 2.30887 7.50036 -0.98328 -2.32838 9.09664 -0.9664999 2.34565 9.219861 -0.94769 3.30625 9.92307 0.20289 3.30676 10.56971 0.72338 16.80244 10.21738 0.39948 -2.3191 -1.65903 -0.89956 -2.29975 3.2e-4 10.00002 -2.3217 10.08648 -0.6967099 2.30311 9.91917 -0.7764099 2.54243 10.73518 0.2392399 -2.48352 10.76608 0.16778 2.60148 8.999361 -0.25303 2.55547 7.5018 -0.29981 2.59315 9.78928 -0.15286 5.15499 0.00225991 -2.3248 3.40026 3.2e-4 2e-5 5.07386 3.2e-4 -3.17212 4.39345 0.02717 -3.11122 4.96766 -0.61587 -5.85918 17.34274 6.79722 -0.13385 17.26482 9.028182 -0.14884 17.18981 9.87308 0.04524993 17.31603 10.44393 0.51954 17.06789 10.45824 0.64089 37.50025 2.19422 22.05426 37.40435 0.73243 20.1451 37.50909 3.57046 33.79905 37.50026 3.23185 35.25447 37.50021 3.75936 32.92622 37.50006 3.92558 32.07096 37.50026 4.06082 31.35498 37.50026 4.26847 29.53544 37.50026 4.21362 27.70218 37.49462 3.94249 26.10388 37.50025 3.32473 24.15278 42 4.60716 30.81114 41.70798 3.88144 30.84091 41.61946 3.73011 28.65682 41.23909 3.51172 30.85785 40.9242 3.26715 28.67483 40.68318 3.30035 30.86494 40.01752 3.32974 28.77479 40.09034 3.37438 30.86367 41.94769 3.2e-4 19.36702 41.71842 -0.00575 20.01342 41.67065 2.00021 22.58903 41.14101 -0.0231499 20.675 39.83923 2.33243 24.11971 39.72058 0.01236999 20.58068 40.32361 -0.009799957 20.87785 40.82568 1.72519 23.15768 41.67065 3.29589 25.50533 40.82568 2.83887 25.81911 39.83923 2.94015 25.74441 39.83924 3.25593 27.19053 38.53032 3.82532 31.03301 38.97182 3.2e-4 20.13458 38.07147 3.2e-4 19.68671 38.71609 3.23855 25.0583 42.00026 -3.329 61.7503 42.00026 -2.68931 58.80988 42.00026 -2.01866 56.14605 42.00026 -1.33825 53.7342 42.00026 -0.66312 51.54677 42 0.01940995 49.44598 42.00026 0.90463 46.98814 42.00026 1.27223 45.9909 42.00026 2.64223 42.40157 42.00026 3.26882 40.78415 42.00026 3.80804 39.20903 42.00026 4.26056 37.45743 42 4.41831 35.70793 39.00605 10.99998 50.90361 40.77634 1.29834 41.78917 37.50026 2.06831 38.47021 37.50026 2.36053 37.78063 39.12905 2.10223 39.00677 40.75076 1.88919 40.25134 37.50026 1.7721 39.16009 40.80231 0.65552 43.46877 37.50026 1.47398 39.84916 37.50026 1.17579 40.53642 40.88453 0.006799936 45.22028 37.50026 0.87904 41.2211 37.50026 0.58421 41.90438 37.50026 0.29134 42.58811 37.50026 3.1e-4 43.27425 37.86468 -1.28829 46.67348 40.95145 -1.31296 49.00166 40.8881 -2.05795 51.15124 40.9055 -2.78022 53.51792 40.92114 -3.49185 56.08376 40.93563 -4.22286 59.0684 38.00026 -4.32987 56.00671 40.94827 -4.89696 62.31458 40.99276 -6.27097 69.4598 39.56744 -6.94584 69.68528 34.57989 -2.49604 47.51221 31.2798 -8.57772 66.95871 31.61232 -6.53616 57.16278 40.39569 3.1014 35.40696 39.23923 3.58346 31.84347 40.61332 2.37786 38.01184 37.50026 2.82658 36.56094 40.81791 3.10269 35.64901 41.35299 2.08151 40.32797 41.38855 3.3211 35.68163 41.89888 2.6874 40.56078 41.78449 3.78594 35.75154 41.42602 0.11571 45.58867 41.92104 0.6899 45.90022 36.98519 -10.49187 73.65435 40.50635 -9.57438 73.47957 40.05586 -10.39787 74.10015 39.10843 -10.81996 74.49618 34.98815 -10.54967 73.19113 40.75598 -9.05269 73.0357 33.17701 -10.60156 72.65687 40.74006 -8.1737 72.10389 33.82185 -9.33063 71.18477 40.78117 -7.47096 71.16957 40.90627 -6.78083 70.13558 33.58817 -8.448902 69.18836 41.62707 -0.92331 48.99156 41.68417 -3.34011 57.58212 41.73455 -5.01147 66.37409 41.13453 -8.96965 73.12194 41.55864 -6.3484 70.15403 41.40157 -8.820052 73.27262 41.60799 -8.70256 73.39331 41.87943 -5.99443 70.34275 41.7471 -8.55435 73.54315 41.88245 -8.39852 73.70246 41.01022 -9.77275 73.81822 35.06305 -10.90893 73.79316 34.055 -10.99969 74.02668 -34.39244 11.00066 18.74109 -19.54399 11.00031 39.92647 -15.61547 11.00031 37.17568 -16.99974 11.00031 50.35272 -19.99974 -3.07323 57.68965 -19.99974 -4.33871 56.89844 -19.99974 -5.60764 55.77404 -19.99974 -6.84118 54.29292 -19.99974 -7.99843 52.44464 -19.94339 8.57903 52.41387 -19.99974 7.99879 52.44456 -19.7647 9.164361 52.28874 -19.45675 9.721672 52.07313 -19.01309 10.22437 51.76247 -18.43685 10.6337 51.35898 -17.75019 10.90493 50.87818 -20.9757 6.66662 53.13669 -19.99974 6.81651 54.32783 -19.99974 5.56375 55.81978 -21.76647 5.15921 53.69042 -19.99974 4.28182 56.94116 -22.34637 3.51567 54.09646 -19.99974 3.01323 57.72006 -22.70031 1.77899 54.34429 -19.99974 1.78033 58.20073 -19.99974 0.57544 58.42724 -22.81889 -0.004569888 54.42732 -19.99974 -0.62254 58.42272 -22.69871 -1.79026 54.34317 -19.99974 -1.8346 58.18479 -22.34294 -3.52745 54.09406 -21.76038 -5.17257 53.68614 -20.96898 -6.67675 53.13199 -34.89827 10.93751 20.04468 -21.02757 10.85019 40.96528 -22.47069 10.4039 41.97576 -35.94353 10.52684 22.1564 -23.83393 9.67363 42.93031 -36.26926 10.29696 23.0083 -36.98425 9.50867 24.39766 -37.5463 8.92159 25.43557 -25.08009 8.6793 43.80288 -37.79276 8.57469 25.87788 -38.3259 7.55097 26.86639 -26.17513 7.44804 44.56965 -38.86015 6.57738 27.71237 -27.08917 6.01347 45.20966 -39.6272 5.08638 28.24948 -27.79724 4.41473 45.70546 -40.18956 3.4651 28.64325 -7.71932 9.42093 43.85449 -6.7816 8.39193 43.19789 -12.98907 3.1e-4 47.54441 -5.94083 7.17651 42.53286 -3.90136 3.1e-4 41.24137 -3.9784 -2.99969 41.23506 -3.9784 -10.99969 41.23506 -16.99974 -10.99969 50.35271 -17.49796 -10.95803 50.70156 -17.99345 -10.83033 51.04851 -18.44906 -10.62637 51.36753 -18.85875 -10.35427 51.65439 -9.879712 11.00031 45.3672 -8.75665 10.29449 44.58083 -19.22317 -10.01373 51.90957 -19.54042 -9.59498 52.13171 -19.7899 -9.101962 52.30641 -19.94936 -8.547182 52.41805 -10.53331 -10.99969 33.61712 -10.39859 0.006929934 33.55042 -11.19383 6.33192 34.07963 -10.50889 4.72718 33.60003 -13.11352 9.0764 35.4238 -14.30466 10.15367 36.25786 -19.54399 3.1e-4 39.92647 -12.06864 7.79271 34.69217 -19.55254 -11.00203 39.92437 -21.00856 -10.85341 40.95197 -22.44876 -10.41244 41.96041 -23.8161 -9.68477 42.91783 -25.0408 -8.75295 43.74733 -26.18835 -7.46677 44.55593 -27.15089 -5.95878 45.22414 -27.9874 -3.99307 45.73754 -5.21253 5.84098 42.12602 -4.69914 4.61927 41.82666 -9.84612 3.17395 33.60003 -4.37969 3.41569 41.53367 -4.11728 2.24397 41.40828 -9.454152 1.59322 33.60003 -4.0032 1.10051 41.28576 -9.21055 0.02210998 33.70506 -2.66889 -10.99969 58.10774 -0.27107 -10.99969 68.60695 11.95373 -10.99924 54.07261 14.65039 -10.99969 57.10166 11.26303 -11.00247 52.76605 10.93462 -11.00078 51.02588 10.92849 -10.99944 49.00001 11.21852 -10.99969 46.78524 11.69197 -10.99969 44.64638 12.28615 -10.99969 42.55488 8.89405 -10.99969 39.42825 -9.148612 -11.00002 33.85217 5.89719 -10.99969 35.93081 -9.23438 -10.99969 31.98067 -30.48229 -11.00002 24.31039 9.64666 -11.7272 34.63953 9.14133 -11.1812 36.89915 -9.14059 -2.99969 33.86269 -9.5621 -11.00002 33.51436 -9.72471 0.009139955 33.46122 -10.03276 -11.00002 33.42926 -18.49975 11.00032 3e-5 -21.19975 10.85058 -1.8088 -21.19975 11.00032 3e-5 -18.5 10.34273 -3.49771 -21.19975 10.40543 -3.5684 -21.19975 9.67698 -5.23087 -18.49975 8.534932 -6.93974 -21.19975 8.68505 -6.75093 -17.79844 10.99998 -0.002489984 -16.91649 9.68695 -3.50188 -15.54072 8.754961 -0.6660799 -15.55918 8.56459 -0.96403 -15.88354 9.44507 -0.80489 -21.20026 0.001449882 11.01394 -21.28766 0.02173 11.85505 -21.20044 10.99998 11.01762 -2.29975 4.68862 -0.95292 -2.59805 5.3017 -0.25482 -3.21332 9.000741 0.005569994 -2.55236 8.99997 -0.30387 -3.19026 5.3014 0.004939973 -3.30688 9.55089 0.05248993 -2.59264 9.78984 -0.1526499 -3.3059 10.27285 0.43032 -2.69517 11.00598 1.04606 -3.30505 10.99998 1.06113 -15.92924 10.33615 0.42254 -16.47413 10.36967 0.38119 -17.279 10.99998 1.29354 -16.91968 10.57752 -0.002319931 -14.65761 8.99585 -0.002359986 -14.94063 8.91659 -0.05849999 -15.34548 9.84637 0.19979 -15.65766 9.70758 -0.002089977 -15.17003 8.858922 -0.1529999 -15.94733 9.65974 -0.31976 -15.33845 8.81154 -0.32356 -15.48324 8.770522 -0.51661 -14.58253 7.93702 -0.006569921 -14.53943 8.47437 5e-4 -15.08167 7.9332 -0.17254 -15.41384 7.93282 -0.57846 -15.49975 7.93757 -0.99997 -14.58696 5.3001 0.005089998 -15.24522 5.30287 -0.29855 -15.49562 5.30014 -0.88208 -15.90167 8.695611 -3.82645 -15.49975 7.62971 -2.40672 -15.49975 7.07219 -3.74012 -15.90167 6.98317 -6.44123 -15.49975 6.28421 -4.951 -17.00111 7.33618 -7.64988 -15.49975 5.29115 -6.00057 -18.49975 7.30819 -8.22159 -15.90167 4.51484 -8.35875 -15.49975 4.1255 -6.85437 -17.00111 4.69491 -9.50243 -18.49975 5.89133 -9.28954 -18.49975 4.3212 -10.1158 -15.49975 2.82533 -7.48457 -15.90167 1.55781 -9.37144 -15.49975 1.43289 -7.87066 -17.00111 1.61866 -10.47455 -18.49975 2.63864 -10.6789 -18.49975 0.8875 -10.96415 -15.49975 -0.005999982 -7.99997 -15.90167 -1.56781 -9.36966 -17.00111 -1.60754 -10.47618 -21.19975 7.45665 -8.08719 -21.19975 6.02522 -9.20327 -21.19975 4.42972 -10.06875 -21.19975 2.71362 -10.66008 -21.19975 0.92363 -10.96116 -18.49975 -0.88677 -10.96415 -2.29975 -1.19968 -0.99998 -21.19975 -10.99968 12.00002 -21.19975 -10.99968 2e-5 -21.19975 -10.8493 -1.81266 -21.19975 -10.40283 -3.5741 -21.19975 -9.67123 -5.24033 -21.19975 -8.67606 -6.76166 -21.19975 -7.44421 -8.098072 -21.19975 -6.00708 -9.2147 -21.19975 -4.40793 -10.07804 -21.19975 -2.68749 -10.66654 -15.49975 0.08439999 -0.89748 -15.49975 -7.07442 -3.73469 -15.5383 -5.19961 -0.8982599 -15.49975 -7.63069 -2.40159 -15.49975 -6.28827 -4.94504 -15.49975 -5.2969 -5.99493 -15.49975 -4.13314 -6.84939 -15.49975 -2.83463 -7.48083 -15.49975 -1.44397 -7.86852 -21.19975 -0.89245 -10.96369 -15.54911 -8.07651 -0.98456 -18.5 -10.25767 -3.32629 -18.49975 -10.97317 -0.76319 -18.49975 -10.99968 2e-5 -18.49975 -8.53429 -6.93975 -18.49975 -7.30755 -8.22159 -18.49975 -5.89069 -9.28953 -18.49975 -4.32055 -10.11582 -18.49975 -2.63804 -10.67889 -17.27788 -10.65702 5e-5 -17.36909 -10.78195 0.7220001 -17 -9.92136 -3.43188 -16.07855 -9.68662 -0.56019 -16.69233 -10.37179 0.09990996 -15.90167 -8.69931 -3.81658 -17 -9.28786 -5.08862 -15.90167 -6.98984 -6.43329 -17.00111 -7.32789 -7.65721 -15.90167 -4.52369 -8.35361 -17.00111 -4.68476 -9.507122 -2.25981 -2.41399 0.05524992 -2.28917 -2.16863 9.28614 -1.91132 -2.18628 8.70037 -2.29975 -1.64968 10.00002 -2.30004 -11.00044 14.49994 -17.60893 -10.97441 1.55587 -2.29975 -10.99968 2.00002 -2.0171 -6.48071 8.789112 -2.29892 -6.49807 9.48269 -14.49975 -6.33126 2e-5 -3.29975 -5.19968 2e-5 -14.66082 -7.92152 0.001859903 -14.67584 -8.98036 -0.002439916 -2.29975 -8.99968 2e-5 -2.29975 -10.90406 1.38901 -2.29975 -10.61666 0.823 -2.29975 -10.17759 0.38369 -2.29975 -9.61116 0.09578996 -15.35954 -9.81387 0.16857 -16.29393 -10.41649 0.56217 -16.80311 -10.67837 0.91534 -15.30478 -8.81331 -0.28649 -15.68901 -9.705801 -0.0480799 -15.13338 -7.93045 -0.23262 -15.10497 -5.20571 -0.14485 -30.79928 10.99949 11.01068 -30.79975 11.00032 3e-5 -33.79974 11.00032 3e-5 -33.8092 11.00183 14.35476 -29.84198 10.99384 11.99814 -30.59873 10.98676 11.61281 -36.79974 -0.007789969 -7.99997 -36.79974 -1.3974 -7.87692 -36.79974 1.38282 -7.87961 -36.79974 2.73173 -7.51924 -36.79974 -2.74417 -7.51448 -36.79974 3.99724 -6.92995 -36.79974 -4.00772 -6.92353 -36.79974 5.14114 -6.12957 -36.79974 -5.14931 -6.12217 -36.79974 6.12841 -5.14259 -36.79974 -6.13455 -5.1345 -36.79974 6.92918 -3.99882 -36.79974 -6.93295 -3.99119 -36.79974 7.5187 -2.73382 -36.79974 -7.52079 -2.72632 -36.79974 7.87958 -1.38462 -36.79974 -7.88005 -1.37829 -36.79974 -7.99968 3e-5 -36.79974 8.00032 3e-5 -36.81443 -0.008089959 12.38541 -36.7967 3.53228 12.70871 -36.79967 7.1347 13.80731 -36.79974 8.00032 14.3549 -30.79856 -11.00002 11.02335 -30.79975 -10.99968 2e-5 -30.79975 -10.84952 -1.81135 -30.79975 10.85039 -1.80992 -30.79975 10.40469 -3.57055 -30.79975 -10.40324 -3.57293 -30.79975 9.67536 -5.23386 -30.79975 -9.67312 -5.23683 -30.79975 8.68226 -6.75451 -30.79975 -8.67907 -6.7578 -30.79975 7.45247 -8.091052 -30.79975 -7.44809 -8.0945 -30.79975 6.01951 -9.207001 -30.79975 -6.0136 -9.210452 -30.79975 4.42244 -10.07195 -30.79975 -4.41473 -10.07506 -30.79975 2.70481 -10.66232 -30.79975 -2.69563 -10.66448 -30.79975 -0.9032 -10.9628 -30.79975 0.91344 -10.962 -22.15526 0.007359921 11.99912 -29.86834 -11.00002 11.99651 -22.16006 10.99998 11.99842 -33.79974 -10.99968 2e-5 -33.79974 -10.47466 -3.49998 -33.79974 -8.52034 -6.95688 -33.79974 -7.29403 -8.233592 -33.79974 -5.87881 -9.29706 -33.79974 -4.31131 -10.11976 -33.79974 -2.63219 -10.68033 -33.79974 -0.88477 -10.9643 -33.79974 0.88549 -10.9643 -33.79974 2.63279 -10.68033 -33.79974 4.31196 -10.11974 -33.79974 5.87945 -9.29706 -33.79974 7.29467 -8.233592 -33.79974 8.52097 -6.95687 -33.8 10.20262 -3.50126 -33.79974 10.9746 -0.75178 -35.3938 10.77261 21.17249 -36.64715 -8.81307 26.97617 -38.85982 -6.57728 27.71215 -37.5093 -8.97024 25.36489 -35.21536 -9.8805 25.97361 -35.78766 -10.70378 22.41514 -33.65039 -10.60402 24.87781 -34.58218 -10.99969 19.69901 -38.93689 7.18572 20.70183 -38.32103 7.12673 19.06551 -39.02973 4.63813 17.88106 -39.97427 3.83272 18.59788 -38.75257 2.72742 17.02578 -40.5415 5.53276 21.42248 -38.65963 8.35522 23.49712 -40.50451 5.92099 24.8554 -38.76624 8.03745 24.72672 -40.83186 2.04116 19.19836 -38.70994 -0.01001 16.61259 -41.76626 2.94589 22.28006 -41.63396 3.10566 25.64625 -40.53284 1.75501 28.88361 -42.0234 0.007079899 25.91894 -42.19225 0.003619909 22.57835 -40.64822 8e-5 28.96441 -41.12955 -0.001779913 19.4068 -41.63728 -3.09212 25.64857 -40.53275 -1.75507 28.88355 -40.1894 -3.46507 28.64313 -41.7681 -2.93905 22.28136 -40.83067 -2.04447 19.19753 -38.65361 -2.75281 16.8334 -40.51082 -5.90924 24.85982 -39.62696 -5.08633 28.2493 -40.34552 -5.52707 21.42492 -39.97205 -3.83528 18.59632 -39.45963 -7.33046 24.22606 -38.99642 -6.80644 20.06094 -38.64497 -5.09668 17.59839 -38.54078 -6.84553 19.16336 -36.85474 -6.9e-4 12.8662 -36.8276 6.8699 14.41477 -37.17046 8.97825 18.0813 -36.94878 0.001249969 13.50854 -36.88181 3.44134 13.53781 -37.07059 8.2e-4 13.92412 -36.99055 6.43146 15.16721 -37.03085 3.32365 14.13068 -37.36453 4.3e-4 14.74741 -37.29959 8.25182 17.84789 -37.22893 3.20819 14.71189 -37.27509 6.01377 15.88424 -37.49868 3.09749 15.26971 -37.46149 8.891921 19.55739 -38.01134 -0.00702995 15.81522 -37.57735 5.71607 16.39532 -37.59179 7.81341 18.2093 -37.81487 2.99184 15.80115 -37.87581 8.755082 20.77565 -37.72676 9.17571 21.4162 -37.93076 5.43082 16.88496 -37.93949 7.38716 18.56075 -38.15658 8.820611 23.43726 -38.32058 2.86247 16.45829 -38.2977 8.201622 20.9743 -38.35055 5.17675 17.32112 -38.23787 8.66316 24.26988 -37.87741 8.8285 25.0882 -36.39843 -9.49824 3e-5 -36.69753 -8.776142 3e-5 -36.39861 -8.92548 -3.2487 -35.29974 -10.59776 2e-5 -35.92107 -10.121 2e-5 -36.39861 -7.27606 -6.10558 -35.29974 -7.48949 -7.49811 -36.39861 -4.749 -8.22603 -35.29974 -4.80793 -9.44454 -36.39861 -1.6491 -9.35431 -35.29974 -1.65636 -10.46776 -35.29974 1.65716 -10.46773 -36.39861 1.64974 -9.35431 -35.29974 4.80872 -9.44447 -36.39861 4.74964 -8.22603 -35.29974 7.49025 -7.49798 -36.39861 7.2767 -6.10558 -35.3 9.697001 -3.48608 -36.39861 8.92612 -3.2487 -36.72453 8.667881 3e-5 -36.47666 9.34764 -0.001729965 -36.14523 9.87079 3e-5 -35.67022 10.34581 3e-5 -35.1956 10.63941 -0.001009941 -34.46731 10.9251 3e-5 -34.93652 10.77807 14.35294 -35.58376 10.41524 14.35461 -36.21264 9.77333 14.35913 -36.54551 9.21337 14.35889 -36.74974 8.524291 14.35804 -35.6876 10.6461 18.53472 -36.53004 10.03759 18.28291 -36.51375 10.32512 21.99281 -36.95128 10.04975 21.78613 -37.3879 9.676671 21.55382 -30.54963 -11.00002 11.66705 -33.79976 -10.99968 14.35432 -36.80211 -3.57614 12.74256 -36.83413 -6.80393 14.48794 -36.79083 -7.04813 13.76283 -36.79802 -8.00355 14.36797 -36.85308 -8.2511 15.52943 -36.85374 -3.46387 13.32598 -36.98067 -3.33462 13.98191 -36.94965 -8.4689 16.47709 -36.98058 -6.44915 15.09954 -37.2118 -8.51306 17.67781 -37.17058 -6.12276 15.66232 -37.26193 -3.17345 14.8002 -37.16951 -8.873742 17.99794 -37.42837 -9.10094 19.63637 -37.50796 -5.75593 16.295 -37.6075 -7.75384 18.23821 -37.65326 -3.02726 15.54316 -37.73828 -9.155611 21.34813 -37.91945 -5.4259 16.86416 -38.33669 -8.166501 21.07709 -38.10238 -2.90063 16.18634 -38.15025 -7.1699 18.72193 -38.72624 -8.31356 23.17016 -38.38188 -5.17725 17.33244 -38.70362 -7.76277 21.09307 -38.28183 -8.521121 24.55593 -36.79264 -10.16235 21.86772 -35.07729 -10.92664 19.09571 -35.45325 -10.78913 18.5133 -35.89947 -10.55703 18.41647 -37.38953 -9.68077 21.55747 -36.47078 -10.08791 18.29239 -37.06798 -9.19611 18.17723 -34.48074 -10.91786 14.35774 -34.03627 -10.99969 16.91243 -34.34378 -10.99937 17.05174 -35.15562 -10.66385 14.35446 -35.06882 -10.81567 16.93252 -35.53715 -10.59231 16.85391 -35.98821 -10.04511 14.3575 -36.15683 -10.12153 16.75029 -36.41797 -9.45354 14.35341 -36.76658 -9.26479 16.64904 -36.69753 -8.77615 14.35433 -34.57621 -10.89746 2e-5 -35.29974 -9.68938 -3.36008 -33.88254 11.00032 15.89549 -34.0911 11.00032 17.35025 -1.46361 -10.99969 21.00948 -2.29974 -10.99968 17.78293 -2.29974 -11.00234 16.69962 -1.44589 -11.04272 16.30639 -2.29974 -1.03093 14.50002 -2.23293 3.2e-4 15.05038 -2.29974 3.2e-4 14.50002 -21.4021 10.99998 11.61422 12.5312 -10.58549 31.98531 16.64741 -13.38308 33.52113 22.43384 -2.43179 35.4638 21.78853 -2.89039 34.14166 22.43384 3.1e-4 35.4638 21.65439 3.1e-4 33.81064 21.3357 -3.4036 32.89512 21.10985 3.1e-4 32.06595 20.99578 -4.04728 31.53899 25.44507 -0.81405 36.97453 24.712 -1.22857 36.9809 25.15811 0.01659995 37.00175 24.26314 3.1e-4 36.89455 24.0104 -1.59847 36.81344 23.7072 3.1e-4 36.68168 23.36963 -1.92981 36.48375 23.20424 3.1e-4 36.36323 22.83476 -2.21207 36.02045 22.77413 3.1e-4 35.9518 26.92183 -0.003519952 36.82516 12.68278 -11.1535 40.6564 13.08471 -11.72125 38.31505 13.47464 -12.60679 36.32715 10.92894 -12.52152 33.74554 15.06748 -11.44301 37.1727 14.52405 -12.49547 36.58099 15.31516 -11.79939 36.40389 14.12754 -11.52959 38.50731 14.0189 -12.66681 36.52953 14.81115 -11.12672 38.0273 14.54371 -10.86076 38.96343 13.74406 -10.89054 40.62273 14.26397 -10.65805 39.96037 13.97252 -10.5293 40.97764 13.67023 -10.47681 41.968 13.28852 -10.5106 43.04077 12.63184 -10.60558 45.06305 12.07336 -10.70185 47.10023 11.36593 -10.94797 48.99927 11.70368 -10.78236 49.00006 16.57858 -9.282812 32.1871 15.60446 -9.66423 32.83175 16.32271 -8.59969 32.43644 16.27308 -8.07461 32.48607 15.75026 -8.074602 32.90342 15.16408 -8.074602 33.18879 14.55059 -10.15569 32.96592 14.52727 -8.074602 33.34115 13.86319 -8.074602 33.35082 13.46548 -10.48407 32.67463 13.19649 -8.074602 33.20858 12.57363 -8.074602 32.9161 15.74787 3.1e-4 32.90491 15.14261 3.1e-4 33.19639 14.48767 3.1e-4 33.34588 13.81588 3.1e-4 33.34588 13.16094 3.1e-4 33.19639 12.55568 3.1e-4 32.90491 14.00826 -13.53416 34.81597 16.81638 -15.27418 32.40682 15.12647 -14.0356 34.29336 15.84711 -13.60443 34.37607 15.89327 -12.56954 34.95239 11.73357 -10.92608 52.60124 11.55999 -10.87983 50.93766 12.53987 -10.94118 54.14971 14.98376 -10.93201 56.80618 17.00939 -11.00269 59.61676 22.76087 -10.99969 67.55108 26.29809 -10.03401 67.5 23.7424 -11.00002 68.4587 27.24411 -11.00002 70.83822 27.47768 -10.76175 70.15975 30.11902 -10.68794 71.44342 31.13271 -10.95601 72.55889 28.51817 -10.99969 71.69501 30.14903 -10.99969 72.51252 31.98543 -10.99969 73.29705 18.99706 -11.00134 62.1765 20.79791 -11.00002 64.63759 22.00057 -11.00002 66.67691 24.42076 -4.89193 45.53319 22.39955 -4.32243 42.36771 20.36497 -6.03566 44.81445 17.58012 -7.99503 48.14511 14.72139 -9.78387 51.55352 18.00202 -9.761631 55.00234 25.00082 -8.35501 56.99505 27.6925 -4.34221 46.92803 31.1672 -3.36012 47.48283 33.25978 3.1e-4 41.06783 15.86816 -8.3623 46.51122 20.13634 -4.13406 40.55924 14.39754 -9.204482 44.82517 18.38548 -6.26749 37.94863 17.21881 -8.33919 35.85539 16.77633 -10.93123 34.08899 4.37943 10.99998 41.38833 41.68114 3.11934 88.42472 41.68114 5.63812 90.39955 41.13099 3.312 88.37461 41.13099 5.74386 90.32435 37.7384 11.1753 88.8843 38.76384 7.94142 90.03388 37.95638 7.94142 89.22799 39.76155 5.63631 88.40637 40.51579 10.27552 97.62239 40.07596 9.96326 98.56784 41.37939 9.46742 96.43927 39.99857 10.43204 98.33806 40.57038 8.64119 95.29342 41.22685 8.93964 95.8138 40.70426 9.2523 97.00844 41.37984 8.73646 95.12654 39.74244 11.04698 96.20256 39.84858 11.04698 95.04393 38.24878 11.49697 95.45497 38.00381 11.49697 96.64929 39.39767 11.04699 97.44501 37.49107 11.49697 97.75499 38.76131 11.04699 98.70365 41.59571 8.83116 95.13356 41.2131 9.19201 96.43332 41.74747 9.009302 95.10453 41.8014 9.23127 95.04592 41.27328 9.94482 96.26662 41.7521 9.44767 94.97078 38.71717 10.68463 99.7013 38.0911 10.75973 100.2209 38.28223 10.27446 100.3477 37.96762 9.87593 100.1751 38.56969 9.8037 99.67538 39.20652 9.69696 99.05484 39.37949 10.57362 99.05593 39.80162 9.560872 98.36477 40.29893 9.41038 97.67668 40.93732 10.11112 96.92743 41.27329 10.02495 95.04329 39.91544 8.54095 95.21244 36.29012 9.10508 98.62049 37.81296 11.04698 99.873 39.37206 7.94142 90.84272 39.81881 7.94142 91.62484 40.13819 7.94142 92.36641 40.35844 7.94142 93.06499 41.13102 7.19214 93.23298 42.00056 7.30184 92.4242 42.00056 6.94657 91.57982 42.00056 6.38827 90.62459 42.00056 8.25571 93.05318 42.00056 7.7061 93.46572 37.11908 11.39697 89.68384 38.34981 11.34554 91.02043 39.50283 11.01932 91.70684 39.34713 11.17865 92.9042 38.87627 11.27726 91.90458 39.77678 11.04697 94.01065 41.55681 8.56278 94.71521 40.94661 8.50667 94.93193 41.33031 8.34255 94.60556 41.92306 8.79775 92.93055 41.80856 9.3299 94.73648 41.67596 7.07942 93.26065 41.80298 7.58719 93.89461 38.02941 11.49697 93.17299 38.21304 11.49697 94.23915 37.79654 11.49697 92.22731 37.12631 8.496972 90.33946 37.7612 8.496972 90.99005 38.24058 8.496972 91.64044 38.59385 8.496972 92.26857 38.84736 8.496972 92.86425 39.02299 8.496972 93.42589 40.72712 7.83903 94.26452 40.49448 7.94157 93.72605 41.37669 7.53031 93.96105 41.69064 8.16196 94.33181 39.58928 8.496972 95.04093 39.37226 8.49544 94.56347 39.13748 8.496972 93.95772 41.7727 8.656372 94.6345 41.94539 8.88449 94.20365 41.9566 8.2694 94.08396 41.98137 8.653962 94.05004 41.99392 8.3286 93.39334 25.58867 1.43357 87.00081 24.87012 1.27291 87.70231 24.87012 -0.003029882 87.59163 25.15486 -0.003029882 87.29075 25.45073 -0.003029882 87.00081 24.87012 2.37196 87.98259 25.99651 2.81535 87.00081 26.6527 4.08412 87.00081 25.33635 4.10292 88.26278 24.87012 4.09936 88.83101 27.50056 5.99697 87.00081 26.1579 6.16047 88.98506 28.00056 6.96932 88.11705 28.00056 7.74294 89.00081 27.50056 7.94142 89.74383 35.42382 7.14735 87.00081 34.05057 7.94142 87.46534 34.05057 7.47344 87.00081 35.60876 7.94142 87.85357 36.69345 6.582 87.00083 36.91229 7.94142 88.47516 37.99923 5.63255 87.00083 38.95287 4.64133 87.00083 39.93123 2.916 87.00083 40.36637 1.65375 87.00083 40.5504 -0.003029882 87.00083 40.84626 -0.003029882 87.29077 41.13099 -0.003029882 87.59163 41.13099 1.27351 87.70243 41.13099 2.37288 87.98291 28.00056 8.496972 87.00081 31.96557 8.496972 87.00081 28.00056 8.496972 89.00081 30.09208 11.39697 88.93673 28.26272 11.26217 88.8843 31.49381 11.39697 88.44628 33.00006 11.39697 88.27532 34.50645 11.39697 88.44607 35.13641 10.99697 85.43849 37.16936 10.99697 86.13395 35.90857 11.39697 88.9365 24.31998 3.11935 88.42472 24.32517 -0.003029882 87.70771 24.05718 -0.003029882 87.48596 24.21422 -0.003029882 87.66474 24.43612 -0.003029882 87.75068 24.6726 -0.003029882 87.72432 41.56501 -0.003029882 87.75068 41.7869 -0.003029882 87.66474 41.94394 -0.003029882 87.48597 41.32852 -0.003029882 87.72432 33.00057 11.49528 88.98594 34.05057 8.496972 88.86506 35.28151 8.496972 89.20881 34.03556 8.496972 87.00081 24.87013 -8.00303 87.59163 25.09139 -9.0346 87.35697 25.63093 -9.82743 86.83525 25.45073 -4.00303 87.00083 26.38597 -10.3084 86.21868 27.08407 -4.00303 85.72747 27.26143 -10.50303 85.61666 28.3819 -10.50303 85.01744 28.11167 -9.00303 85.14695 28.47897 -9.4878 84.9731 28.11167 -6.00303 85.14695 28.58706 -5.67444 84.92507 28.92677 -5.46536 84.78298 28.93422 -4.00303 84.78002 29.25148 -5.29607 84.65947 28.9567 -10.02226 84.77111 29.55905 -10.49865 84.5542 29.72197 -5.11393 84.50078 30.4356 -5.00303 84.30406 30.93008 -4.00303 84.19744 32.1382 -5.00303 84.03469 33.00057 -4.00303 84.00083 33.86293 -5.00303 84.03469 35.07105 -4.00302 84.19744 35.56553 -5.00302 84.30406 36.24842 -5.10488 84.49124 36.85765 -5.34857 84.69922 37.06691 -4.00302 84.78002 37.39911 -5.66466 84.91852 38.7397 -10.50303 85.61666 37.88945 -6.00302 85.14695 37.88945 -9.00303 85.14695 37.61948 -10.50303 85.01755 38.91706 -4.00302 85.72747 39.68599 -10.5013 86.22204 40.35194 -9.84937 86.81808 40.5504 -4.00302 87.00083 40.90894 -9.0365 87.35614 41.13099 -8.00303 87.59163 30.96395 -5.00303 84.67029 35.03717 -5.00302 84.67029 31.4016 -5.00303 85.13996 34.59953 -5.00303 85.13996 31.72967 -5.00303 85.69278 34.27146 -5.00303 85.69278 31.93231 -5.00303 86.30226 34.06882 -5.00303 86.30226 32.00057 -5.00303 86.93856 34.00057 -5.00303 86.93856 33.00057 -10.00303 85.00083 33.00057 -10.00303 85.40252 31.33445 -10.00303 85.05361 31.61989 -10.00303 85.47597 33.00057 -10.00303 85.74328 31.82955 -10.00303 85.94014 33.00057 -10.00303 86.01088 34.04364 -10.00303 86.43206 31.95749 -10.00303 86.43202 34.00057 -10.00303 86.93856 32.00057 -10.00303 86.93856 37.41134 -6.00302 84.98121 37.41122 -9.00303 84.98118 36.90551 -6.00302 84.94082 36.90544 -9.00303 84.94084 36.40688 -6.00302 85.02871 36.40681 -9.00303 85.02874 35.94649 -6.00302 85.23889 35.94644 -9.00303 85.23892 35.5536 -6.00302 85.55789 35.55355 -9.00303 85.55793 35.25326 -6.00302 85.96547 35.25317 -9.00303 85.96562 35.0646 -6.00302 86.43654 35.06454 -9.00303 86.43677 35.00057 -6.00302 86.93856 35.00057 -9.00303 86.93856 28.58979 -9.00303 84.98121 28.58979 -6.00303 84.98121 29.09562 -9.00303 84.94082 29.09562 -6.00303 84.94082 29.59425 -9.00303 85.02871 29.59425 -6.00303 85.02871 30.05464 -9.00303 85.23889 30.05463 -6.00303 85.23889 30.44753 -9.00303 85.55789 30.44753 -6.00303 85.55789 30.74787 -9.00303 85.96547 30.74787 -6.00303 85.96547 30.93653 -9.00303 86.43654 30.93653 -6.00303 86.43654 31.00056 -9.00303 86.93856 31.00056 -6.00303 86.93856 30.28887 -5.29592 85.04183 31.02681 -5.29592 85.86539 31.29344 -5.29593 86.93856 31.07668 -5.62035 86.93856 31.61786 -5.07915 86.93856 36.74865 -5.30497 84.66201 35.71718 -5.29592 85.03849 34.97572 -5.29592 85.86277 34.38325 -5.07915 86.93856 34.70768 -5.29592 86.93856 34.92445 -5.62034 86.93856 28.79139 -9.246252 84.91934 29.54059 -9.511981 84.86864 30.07767 -9.70493 84.92412 30.96474 -9.71013 85.7556 31.02918 -9.982001 85.01441 30.74658 -9.92569 84.99267 30.4782 -9.84499 84.9712 31.61788 -9.92691 86.93856 31.29346 -9.71013 86.93856 31.07668 -9.38571 86.93856 24.67261 -8.00303 87.72432 24.43612 -8.00303 87.75068 24.21422 -8.00303 87.66474 24.05718 -8.00303 87.48597 41.3285 -8.00302 87.72431 41.56498 -8.00302 87.7507 41.78688 -8.00302 87.66475 41.94394 -8.00302 87.48597 38.77465 -10.75303 85.55951 40.47097 -9.98157 86.87934 41.13404 -9.193262 87.46949 39.76203 -10.62444 86.18592 40.69175 -10.17119 86.83069 41.38859 -9.29184 87.43207 38.86145 -10.9194 85.41758 40.84677 -10.23448 86.72433 41.68918 -9.29155 87.14128 39.99669 -10.79865 85.9662 27.131 -10.93604 85.40339 29.47736 -10.85658 84.42583 27.21588 -10.77336 85.54217 31.95056 -10.85241 83.89984 33.00057 -10.6697 84.02233 30.52545 -10.61703 84.28743 33.00057 -10.97928 83.70178 34.05057 -10.85241 83.89984 36.52377 -10.85658 84.42583 24.91575 -9.16382 87.46038 26.28875 -10.54603 86.2146 25.42461 -10.08604 86.87477 24.71859 -9.25626 87.46589 26.16107 -10.70809 86.13066 25.2418 -10.2036 86.79393 24.53492 -9.30571 87.39328 26.00711 -10.79692 85.97328 25.07019 -10.24095 86.64248 24.36523 -9.30825 87.23494 33.00057 -10.40319 84.16567 31.21358 -10.32127 84.33208 33.00057 -10.18686 84.38906 31.26853 -10.1721 84.6602 33.00057 -10.04902 84.66846 37.21085 -9.246252 84.91934 37.52327 -9.4878 84.9731 37.04554 -10.02226 84.77111 36.46165 -9.511981 84.86864 36.4432 -10.49865 84.5542 35.92458 -9.70493 84.92412 35.52404 -9.84499 84.9712 35.47679 -10.61703 84.28743 35.25566 -9.92569 84.99267 34.97306 -9.982001 85.01441 34.73371 -10.1721 84.6602 34.78867 -10.32127 84.33208 34.66779 -10.00303 85.05361 34.92445 -9.38571 86.93856 34.70768 -9.71013 86.93856 35.03751 -9.71013 85.7556 34.38325 -9.92691 86.93856 34.17269 -10.00303 85.94014 34.38235 -10.00303 85.47597 34.00057 -5.00303 93.26877 32.00057 -5.00303 93.26877 34.23295 -5.00303 94.09375 32.37708 -5.00303 94.21898 32.77805 -5.00303 94.0259 33.22309 -5.00303 94.0259 33.62406 -5.00303 94.21898 31.63453 -5.07242 94.00083 34.27405 -5.02203 94.5056 32.0996 -5.00303 94.56694 33.90154 -5.00303 94.56694 31.83087 -5.00303 94.92147 34.17026 -5.00303 94.92148 32.00057 -5.00303 95.00083 34.00057 -5.00303 95.00083 34.08618 -5.00303 95.44345 31.92156 -5.00303 95.45932 33.86829 -5.00303 95.49787 32.13484 -5.00303 95.50135 33.50329 -5.00303 95.86528 33.76625 -5.00303 95.88864 32.24623 -5.00303 95.8983 32.50175 -5.00303 95.86753 33.00279 -5.00303 96.00081 33.28202 -5.00303 96.13891 32.7353 -5.00303 96.1428 35.00057 -9.00303 94.00083 35.00094 -6.00302 94.00081 31.00056 -9.00303 94.00083 31.00056 -6.00303 93.96101 31.30198 -5.28749 94.00083 31.07899 -5.61481 94.00083 31.0055 -6.00303 94.1412 34.4322 -5.1104 94.23588 34.69915 -5.28749 94.00083 34.92214 -5.61481 94.00083 34.86658 -9.50305 94.00083 34.50055 -9.869071 94.00083 34.00057 -10.00303 94.00083 32.00057 -10.00303 94.00083 31.50056 -9.86905 94.00083 31.13453 -9.50303 94.00083 31.26325 -5.33823 94.1848 31.07251 -5.64578 94.15258 34.73787 -5.33821 94.18481 34.92861 -5.64577 94.15258 31.18788 -5.27567 95.41165 30.89816 -5.9457 95.54119 31.8406 -5.27567 96.45308 31.67032 -5.9457 96.71621 33.00056 -5.9457 97.17156 33.00056 -5.27567 96.85948 34.33081 -5.9457 96.71621 34.16051 -5.27567 96.45308 35.10297 -5.9457 95.54119 34.81324 -5.27567 95.41165 34.00057 -10.00303 95.50083 32.00057 -10.00303 95.50083 35.10297 -8.9457 95.54119 30.89816 -8.9457 95.54119 31.67032 -8.9457 96.71621 33.00056 -8.9457 97.17156 34.33081 -8.9457 96.71621 24.87012 5.2965 89.82287 27.50056 8.496972 92.08535 28.88205 11.39697 89.68384 24.31998 5.63814 90.39956 30.26184 11.49697 89.71026 31.3016 11.49697 89.29082 26.6541 11.17867 92.90397 26.49829 11.01932 91.70685 27.65125 11.34554 91.02054 24.37461 9.636342 95.45105 24.19308 9.23127 95.04592 24.6186 9.77928 96.36007 24.24902 9.44767 94.97078 24.8701 7.19214 93.23297 25.26737 7.83903 94.26452 24.61778 7.53031 93.96105 24.30384 8.16196 94.33181 24.67039 8.34236 94.60522 25.43079 8.64121 95.29347 26.07904 8.54095 95.21244 26.62222 8.49544 94.56346 24.44224 8.559862 94.71041 24.61463 8.73646 95.12652 24.247 9.009302 95.10453 24.22178 8.656372 94.6345 24.04909 8.88449 94.20365 24.17456 9.29202 94.66218 24.14427 8.20532 94.23194 29.8249 8.6999 97.51353 33.00056 8.55728 98.13482 29.711 9.10508 98.62049 26.88909 7.94142 90.46917 26.4198 7.94142 91.18251 26.06698 7.94142 91.86851 27.97175 11.49697 93.17279 26.22435 11.08882 94.01065 27.78809 11.49697 94.23915 28.20463 11.49697 92.22714 27.12495 11.27728 91.90441 28.50539 11.49697 91.41564 28.88949 11.49697 90.7632 29.35241 11.49697 90.29109 29.39829 11.04698 100.825 30.76811 11.04697 101.4749 30.42106 11.49197 99.79165 30.72988 11.48798 100.0102 30.2146 11.49697 99.47166 28.19325 11.04699 99.87802 29.26237 11.49697 98.71241 27.24331 11.04699 98.70907 28.51005 11.49697 97.75497 26.6052 11.04699 97.4496 27.9973 11.49697 96.64927 26.25925 11.04698 96.20579 27.75234 11.49697 95.45497 26.15255 11.04698 95.04558 30.40465 9.968562 101.5481 29.89149 10.38171 101.6682 29.13401 9.951332 100.9168 31.94006 9.968562 101.9637 31.93259 10.38028 102.2918 30.36637 10.85606 101.6447 24.97374 9.09237 96.37292 25.78238 9.4337 97.78476 24.59157 9.572001 96.42621 25.92516 9.96326 98.56782 24.72783 9.94483 96.26661 25.35801 10.22999 97.42498 25.77964 10.36962 98.04489 26.28375 10.50161 98.68008 27.71889 10.27446 100.3477 27.03176 9.74083 99.29841 27.4672 10.70933 99.86162 28.15173 9.88731 100.2647 28.03297 10.77157 100.3141 29.05452 10.83815 100.9923 24.54014 9.80788 95.89679 24.43612 7.03771 93.27092 24.1915 7.58718 93.8946 24.00056 7.87464 93.62245 24.87012 6.30682 91.12614 24.00056 8.3286 93.39332 24.72783 10.01128 94.47571 24.72783 10.0246 95.09308 24.72783 10.00166 95.68509 29.66201 9.49194 99.7704 30.45559 9.65113 100.6214 33.00057 11.49697 95.12439 33.00056 8.496972 95.00081 36.30628 8.496972 89.72613 37.11116 11.49697 90.76256 36.64871 11.49697 90.29109 37.49569 11.49697 91.41555 35.73919 11.49697 89.71022 34.6994 11.49697 89.29078 36.60886 11.04698 100.8213 36.99772 10.83605 100.9621 35.23964 11.04697 101.4726 35.57732 10.85606 101.6672 35.0466 10.85606 101.8487 33.7631 11.04697 101.8064 33.82334 10.85606 102.1003 32.24501 11.04697 101.8072 34.30502 9.65113 101.0324 35.54827 9.65113 100.6214 35.01686 9.968562 101.7492 33.81138 9.968562 101.9972 33.00053 9.65113 101.1718 36.67593 8.71842 97.57588 36.4425 9.96396 101.1531 36.33852 9.492382 99.77202 36.10963 10.38171 101.6682 34.06853 10.38028 102.2918 32.5399 10.85606 102.133 33.00056 11.48798 100.5008 35.58015 11.49197 99.79156 35.27124 11.48798 100.0102 35.78653 11.49697 99.47166 36.73875 11.49697 98.71241 34.13903 11.48798 100.3768 31.83903 11.48798 100.3768 31.34895 10.85606 101.9544 31.69602 9.65113 101.0324 9.72146 11.00031 54.88706 30.6346 10.99998 64.29273 -1.22348 10.99998 31.37401 2.1925 11.00015 12.22485 39.01376 10.99859 12.24818 -22.29964 11.0002 21.38512 -28.44713 -2.03133 46.05944 -28.60279 3.1e-4 46.16707 -28.28 2.69548 46.0435 33.00057 -5.00303 95.00083 -2.3 -12.43498 14.32028 -2.3 -12.45382 14.27587 2.3 -12.45382 14.27587 2.3 -12.43498 14.32028 2.18743 -12.13355 15.03102 -2.18743 -12.13355 15.03102 -1.860739 -11.86163 15.67219 1.351906 -11.64583 16.18102 1.012173 -11.57242 16.35412 -1.012173 -11.57242 16.35412 1.860739 -11.86163 15.67219 -1.351906 -11.64583 16.18102 2.3 10 12 -2.3 10 12 2.3 10 14.32028 -2.3 10 14.32028 -2.18743 10 15.03102 1.351906 10 16.18102 -0.7107391 10 16.50771 0.7107391 10 16.50771 0 10 16.62028 -1.860739 10 15.67219 -1.351906 10 16.18102 1.860739 10 15.67219 2.18743 10 15.03102 2.3 16.79629 9.84629 2.3 15.71331 11.5 2.3 10.5 11.5 2.3 -4.871968 -18.94158 2.3 -1.858257 -19.47126 2.3 -18.13919 -7.216807 2.3 -19.03544 -4.291101 2.3 -19.46297 -1.261211 2.3 1.201211 -19.52297 2.3 4.231101 -19.09544 2.3 7.156807 -18.19919 2.3 9.906291 -16.85629 2.3 12.41184 -15.09982 2.3 -16.79629 -9.96629 2.3 -15.03982 -12.47185 2.3 -12.91301 -14.67178 2.3 -15.33123 11.89716 2.3 -16.45193 10.40824 2.3 -17.88697 7.705715 2.3 19.41126 -1.918256 2.3 19.46297 1.141211 2.3 19.03544 4.171102 2.3 -10.46824 -16.51193 2.3 -7.765715 -17.94697 2.3 -18.88158 4.811968 2.3 -19.41126 1.798256 2.3 14.61178 -12.97301 2.3 16.45193 -10.52824 2.3 17.88697 -7.825716 2.3 18.88158 -4.931968 2.3 18.13919 7.096807 -2.3 -15.33123 11.89716 -2.3 -19.03544 -4.291101 -2.3 -19.46297 -1.261211 -2.3 -19.41126 1.798256 -2.3 -18.88158 4.811968 -2.3 -12.91301 -14.67178 -2.3 -15.03982 -12.47185 -2.3 9.906291 -16.85629 -2.3 7.156807 -18.19919 -2.3 16.79629 9.84629 -2.3 4.231101 -19.09544 -2.3 -17.88697 7.705715 -2.3 -16.45193 10.40824 -2.3 -10.46824 -16.51193 -2.3 -16.79629 -9.96629 -2.3 -18.13919 -7.216807 -2.3 1.201211 -19.52297 -2.3 -1.858257 -19.47126 -2.3 15.71331 11.5 -2.3 10.5 11.5 -2.3 -4.871968 -18.94158 -2.3 -7.765715 -17.94697 -2.3 16.45193 -10.52824 -2.3 14.61178 -12.97301 -2.3 12.41184 -15.09982 -2.3 18.13919 7.096807 -2.3 19.03544 4.171102 -2.3 19.46297 1.141211 -2.3 19.41126 -1.918256 -2.3 18.88158 -4.931968 -2.3 17.88697 -7.825716 0.7107391 -11.19262 16.50771 0 -10.91424 16.62028 -0.7107391 -11.19262 16.50771 0 10 16.62028 0 -10.91424 16.62028 0 10 16.62028 0 -10.91424 16.62028 -35.30011 -21.37407 2.664984 -35.97731 -21.20598 2.742392 -35.70959 -20.85117 1.618092 -35.02501 -20.86087 1.319399 38.11269 -16.77327 0.6647549 40.2939 -16.31673 1.727976 39.90214 -16.63072 2.221127 37.91038 -17.23445 1.797287 41.94008 -10.54336 1.578489 42.01488 -10.96195 1.451645 41.97507 -10.79425 0.8358975 41.72119 -10.58321 0.8395424 -36.81101 -7.389069 3.04854 -36.75496 -7.258225 3.157454 -36.67926 -7.313999 1.528969 -36.68202 -7.420315 1.201839 41.10294 -16.78622 4.278839 40.2374 -17.22068 4.519073 -36.58536 -7.154157 3.076866 -36.40228 -7.313403 1.168158 -36.27677 -7.157767 2.975166 -35.185 -7.531498 0.9172001 -22.81298 -8.782184 0.4782181 -20.01383 -8.669778 0.5382938 -19.81993 -8.744164 0.2190952 -24.43715 -8.720823 0.1978855 -16.09681 -8.293219 0.5968685 -16.12562 -8.446867 0.2116146 -12.84886 -8.080644 0.5868664 -12.8592 -8.182985 0.1892279 -9.338077 -8.016757 0.5790596 -9.317935 -8.080241 0.1771926 -6.337596 -8.006975 0.5768795 -6.294147 -8.060143 0.173912 -2.522725 -8.022829 0.5748329 -2.491111 -8.029641 0.5728569 -2.505342 -8.080093 0.1727465 -2.534631 -8.074892 0.1731433 13.6234 -14.85789 0.2437191 20.02013 -16.21984 0.2199363 20.85444 -16.52285 0.02615922 17.34719 -16.45209 0.03100204 41.7199 -10.48944 1.784672 40.50849 -11.12467 0.8333645 -35.75578 -20.61316 1.398182 -34.914 -20.4599 0.7471657 -33.06443 -20.41025 0.4845829 -33.22402 -20.86695 1.118732 -29.78455 -20.38779 0.395258 -29.92773 -20.84934 1.005392 -25.80159 -20.38117 0.3758431 -25.91128 -20.83986 0.9682675 -21.62747 -20.38028 0.3758526 -21.63793 -20.84203 0.9770756 -17.45075 -20.38723 0.3872757 -17.37379 -20.87199 1.023111 -13.26461 -20.4174 0.4119663 -13.14162 -20.94333 1.099493 -9.211578 -20.4849 0.4067383 -9.162447 -21.01774 1.120949 -5.891845 -20.60078 0.3765431 -5.933184 -21.09855 1.10078 5.08159 -22.30381 0.1192588 6.227774 -22.29838 0.1060276 6.069337 -22.35332 0.751709 4.871313 -22.35009 0.797905 8.589437 -22.28036 0.08058166 8.513025 -22.35177 0.6742153 11.18799 -22.2173 0.06914329 11.15043 -22.30648 0.6414452 14.75098 -21.73004 0.1048717 16.66975 -21.39739 0.1352386 16.77512 -21.63473 0.94174 14.80499 -21.89464 0.8165684 20.42124 -20.87202 0.1748484 20.5043 -21.24291 1.096138 24.30422 -20.34383 0.2137432 24.31791 -20.81227 1.23002 27.83371 -19.68346 0.2604694 27.77166 -20.19741 1.348465 31.38448 -18.78649 0.310812 31.2583 -19.31107 1.463882 34.92764 -17.74555 0.3874893 34.75664 -18.25953 1.59688 37.9792 -18.09053 4.439198 34.79686 -19.20944 4.223764 31.32444 -20.29726 3.959854 27.85016 -21.18588 3.711298 24.40685 -21.73073 3.467194 20.73389 -21.95685 3.200054 17.25472 -22.04796 2.90728 13.12774 -22.27361 2.241177 11.12869 -22.3437 2.103764 12.91604 -22.1943 0.6663036 8.193588 -22.36276 2.107037 5.44805 -22.3448 2.222803 -4.616034 -21.82497 2.57395 -6.096391 -21.79971 2.583603 -4.345522 -21.14738 1.078341 -9.120854 -21.73867 2.602667 -12.96807 -21.63535 2.611956 -17.28125 -21.50387 2.564613 -21.71512 -21.4381 2.519438 -26.13951 -21.42959 2.499756 -30.21177 -21.44248 2.53014 -33.52912 -21.44941 2.597425 7.161726 -11.42326 49.89167 6.612938 -11.26008 51.49803 5.569353 -11.2263 51.70843 5.467674 -11.36983 49.88853 1.236763 -11.21067 49.42605 1.450103 -11.17832 50.75915 1.122014 -11.17747 50.5755 0.9234281 -11.20508 49.36167 -2.998834 -11.1718 48.61708 -2.961502 -11.17248 49.74878 -3.792537 -11.17069 49.79266 -3.802937 -11.16122 48.80295 -4.478267 -11.16244 49.87395 -4.657793 -11.13532 49.09914 41.93324 -10.57216 2.857588 41.98825 -10.75702 2.74156 41.95855 -10.98351 4.509445 41.99311 -11.19508 4.467781 41.96268 -11.55174 6.514654 41.99416 -11.76373 6.487608 41.96529 -12.20895 8.647776 41.99486 -12.40609 8.60363 41.96702 -12.87652 10.7005 41.99507 -13.0395 10.66644 41.96765 -13.38439 12.22506 41.99471 -13.4834 12.26416 41.9675 -13.64232 12.953 41.99407 -13.67916 13.07407 41.9669 -13.75352 13.20258 41.994 -13.75844 13.37009 41.89118 -10.42181 2.247049 41.93331 -10.57589 3.02527 41.94048 -10.97792 4.555925 41.94424 -11.53519 6.515211 41.94771 -12.18173 8.623154 41.95024 -12.83183 10.61734 41.95156 -13.33703 12.08548 41.95181 -13.61532 12.81659 41.95069 -13.73764 13.07428 26.02302 -16.07624 0.4377651 26.3522 -16.08447 0.499691 29.84541 -15.69423 0.6405029 29.34267 -15.74365 0.5811462 26.27949 -16.13967 0.5398331 29.41123 -15.76641 0.6598072 20.14659 -16.22975 0.3196659 21.06664 -16.46275 0.3703251 13.6891 -14.86659 0.3447418 17.2593 -16.101 0.3284283 4.440995 -11.15825 0.4163571 4.604897 -11.21737 0.536789 -2.517033 -8.003519 0.8194389 -2.484516 -8.011053 0.8161965 -9.34961 -7.990362 0.8210831 -6.501586 -7.987305 0.821764 -12.47713 -8.016142 0.8150692 -14.56205 -8.099836 0.7908325 -36.62672 -7.096894 4.834517 -36.4638 -7.053176 4.826397 -36.62275 -7.14702 6.31308 -36.46748 -7.106049 6.434866 -36.59059 -7.376173 8.315487 -36.42646 -7.337852 8.49055 -36.52581 -7.731776 11.31255 -36.34142 -7.68582 11.3981 -36.39369 -7.932583 14.05481 -36.2031 -7.902624 14.0451 -36.16974 -7.988173 15.82449 -36.08687 -7.966431 15.41235 -36.78794 -7.238184 4.771656 -36.79005 -7.304385 6.22394 -36.7719 -7.528042 8.318363 -36.73683 -7.822225 11.22915 -36.65214 -7.972874 13.82385 -36.45269 -8.016242 15.58446 -36.11119 -8.042043 16.8157 -35.83333 -8.013924 17.10123 -35.56558 -8.085133 17.91298 -35.22872 -8.049141 18.27757 -34.86817 -8.159539 18.98327 -34.384 -8.110838 19.50989 -32.94842 -8.307463 21.32121 -33.41526 -8.187998 20.73011 -34.49135 -8.236886 19.49442 -33.46362 -8.301357 20.72789 -33.63431 -21.69362 4.549654 -35.40287 -21.56243 4.341482 -33.49949 -21.54011 6.201679 -35.31956 -21.36517 5.95484 -33.28257 -21.10568 7.761314 -35.16823 -20.91771 7.581161 -33.06198 -20.48688 9.445326 -35.00679 -20.31765 9.237537 -32.82676 -19.78359 11.11652 -34.84514 -19.64111 10.79299 -32.56769 -19.04952 12.64141 -34.6817 -18.92238 12.17627 -32.24787 -18.26895 14.06724 -34.48963 -18.12374 13.48506 -31.85117 -17.40155 15.50278 -34.25033 -17.19833 14.85775 -31.41118 -16.49682 16.93528 -33.98197 -16.26469 16.19871 -30.86548 -15.60472 18.36082 -33.58787 -15.41574 17.43831 -30.12353 -14.59557 20.07506 -32.94009 -14.56047 18.78559 -29.16137 -13.28969 22.54388 -31.95442 -13.55313 20.60372 -28.24903 -11.68883 25.60439 -30.56924 -12.37402 23.07419 -26.66453 -11.2261 28.08129 -28.76291 -11.38232 25.59183 -30.32892 -21.71086 4.692966 -30.19079 -21.58539 6.38698 -29.98786 -21.16348 7.909922 -29.81719 -20.53598 9.655451 -29.61438 -19.81797 11.49886 -29.35424 -19.07382 13.25155 -29.00868 -18.30902 14.88243 -28.57906 -17.51688 16.40454 -28.08492 -16.69007 17.88909 -27.48873 -15.81365 19.4493 -26.76028 -14.74941 21.43992 -25.89497 -13.36833 24.39558 -24.91511 -11.94825 28.12407 -23.74046 -11.25164 31.33893 -26.28162 -21.70243 4.751694 -26.19053 -21.58473 6.465343 -26.03165 -21.16567 7.982695 -25.93095 -20.5287 9.798136 -25.7988 -19.79501 11.8049 -25.58779 -19.02635 13.81056 -25.282 -18.24186 15.71988 -24.93131 -17.48763 17.38769 -24.541 -16.73769 18.90348 -24.0322 -15.90733 20.5427 -23.39724 -14.87348 22.67848 -22.72778 -13.56697 25.73924 -22.1119 -12.28126 29.48116 -21.53761 -11.51972 32.81029 -21.00465 -11.24959 34.94894 -22.26935 -11.10422 33.9202 -21.86145 -21.70876 4.763004 -21.91417 -21.5855 6.480406 -21.87053 -21.16195 8.011705 -21.83417 -20.51289 9.885994 -21.75269 -19.76049 12.01123 -21.57889 -18.96048 14.22231 -21.30499 -18.13278 16.41209 -21.0412 -17.36784 18.29765 -20.82382 -16.67121 19.86373 -20.51482 -15.9003 21.53184 -20.06893 -14.94027 23.70562 -19.65364 -13.80625 26.56261 -19.41484 -12.71328 29.87424 -19.35526 -11.94166 33.04885 -19.45128 -11.54708 35.24667 -17.37312 -21.76919 4.689623 -17.55466 -21.61407 6.409542 -17.63945 -21.16862 7.99749 -17.67 -20.50785 9.91926 -17.63398 -19.7496 12.09075 -17.51952 -18.94899 14.3703 -17.30422 -18.11074 16.69655 -17.10604 -17.31567 18.79499 -17.02739 -16.61925 20.49926 -16.95327 -15.88821 22.2024 -16.80293 -15.02295 24.28839 -16.70928 -14.08278 26.7725 -16.72122 -13.15801 29.57964 -16.9755 -12.39051 32.42925 -18.18685 -11.862 34.67946 -13.01259 -21.8939 4.5198 -13.25778 -21.68047 6.232979 -13.44098 -21.18953 7.925114 -13.55748 -20.50988 9.90057 -13.54433 -19.7455 12.08819 -13.50317 -18.96345 14.34593 -13.43428 -18.18089 16.58761 -13.39584 -17.41121 18.67943 -13.47592 -16.68412 20.51261 -13.61296 -15.92344 22.34304 -13.71707 -15.11627 24.34671 -13.72703 -14.32421 26.52804 -13.49394 -13.47731 29.12257 -13.15874 -12.75873 31.55179 -9.213989 -21.99095 4.320826 -9.444961 -21.73699 6.029278 -9.642361 -21.21103 7.818623 -9.840244 -20.51507 9.823948 -9.797205 -19.73543 12.00654 -9.811623 -18.95024 14.23906 -9.955171 -18.2157 16.33741 -10.17356 -17.47457 18.30233 -10.45785 -16.70935 20.18147 -10.72708 -15.89086 22.14796 -10.74622 -15.09428 24.2276 -10.11993 -14.36083 26.58887 -8.959234 -13.47492 29.75427 -7.78652 -12.51241 33.35945 -6.313066 -22.03579 4.212561 -6.572788 -21.76304 5.912804 -6.821171 -21.22221 7.740869 -7.141098 -20.51812 9.730904 -7.043901 -19.72239 11.87527 -7.084663 -18.92053 14.06424 -7.42839 -18.19921 16.03834 -7.875904 -17.44457 17.91444 -8.317219 -16.64 19.8151 -8.553513 -15.77198 21.93812 -7.991435 -14.93458 24.42083 -6.06888 -14.18707 27.49698 -3.993188 -13.37483 31.15485 -3.030058 -12.52831 34.8143 -2.679989 -11.88906 37.93463 -5.260179 -11.76561 37.08031 -3.048668 -11.42895 40.67469 -4.419365 -11.37622 39.64513 -3.335678 -11.17205 43.40216 -4.586794 -11.03101 43.74386 -4.198322 -11.21456 41.3717 -3.702971 -11.08687 45.45313 -4.929506 -10.98159 45.83269 -3.770736 -11.12445 47.21876 -4.835072 -11.0593 47.62485 -4.90256 -22.04868 4.181139 -5.19279 -21.76968 5.87649 -5.493776 -21.2252 7.711784 -5.916909 -20.51994 9.67767 -5.771381 -19.72034 11.77725 -5.821372 -18.91473 13.91445 -6.285578 -18.19683 15.81439 -6.845972 -17.41558 17.67465 -7.323156 -16.58056 19.61864 -7.34659 -15.68038 21.91055 -5.959671 -14.78779 24.88821 -2.914312 -13.99746 28.64213 -0.7403982 -13.29729 32.32258 -0.3697909 -12.64936 35.51369 -0.8521655 -12.10239 38.24579 -1.546828 -11.64194 40.7782 -2.162509 -11.31676 43.19109 -2.637031 -11.18265 45.15727 -2.892631 -11.16754 46.93229 -2.599186 -19.81632 11.13044 -2.505284 -19.04213 12.91555 -3.137926 -19.07089 12.85494 -2.967586 -19.82085 11.14685 1.353678 -17.24962 18.73102 3.779271 -16.42411 22.0845 2.533208 -16.37174 21.67159 -0.5125179 -17.30455 18.08647 4.589026 -15.77458 24.77805 4.006723 -15.64866 24.6571 4.55863 -15.21243 27.18895 4.204599 -15.08311 27.20131 4.344059 -14.73354 29.63453 4.044514 -14.62376 29.69605 4.007811 -14.28928 32.12591 3.71534 -14.19065 32.20668 3.569865 -13.83402 34.62234 3.260134 -13.73824 34.70882 3.059531 -13.35043 37.12302 2.729572 -13.25586 37.2115 2.493083 -12.83209 39.65514 2.145679 -12.74005 39.74342 1.916209 -12.28807 42.24024 1.559409 -12.20441 42.31969 1.402332 -11.76229 44.84041 1.057292 -11.70155 44.89133 1.121293 -11.37018 47.31217 0.7995465 -11.34463 47.31543 7.936264 -22.20745 4.013002 4.927554 -22.17703 4.011955 7.950212 -21.9107 6.119356 4.709146 -21.80668 5.88965 8.24338 -21.57788 8.314259 4.812716 -21.30109 7.816393 8.813424 -21.24823 10.63368 5.286259 -20.71119 9.859704 9.810259 -20.96074 13.23676 6.465589 -20.11594 12.26828 10.60636 -20.69483 15.92372 7.570803 -19.60287 15.07797 11.09584 -20.44037 18.47469 8.50508 -19.2279 18.01737 11.27292 -20.11437 20.79997 8.909111 -18.87214 20.56171 11.31902 -19.68273 23.04287 8.960345 -18.42736 22.86718 11.36523 -19.17656 25.25642 8.928986 -17.90236 25.10999 11.42982 -18.59194 27.47038 8.905182 -17.31488 27.32307 11.4785 -17.86902 29.7668 8.903435 -16.6654 29.5557 11.44798 -16.9742 32.18213 8.882887 -15.97189 31.86319 11.12121 -15.94289 34.74478 8.652983 -15.27512 34.23242 10.24531 -14.8004 37.70924 7.997025 -14.52288 36.76848 9.167535 -13.54184 40.80737 7.058466 -13.65251 39.53998 8.421895 -12.488 43.3948 6.308364 -12.86992 42.14452 7.467833 -12.05999 45.40315 5.662557 -12.29035 44.57427 7.192803 -11.7565 47.47237 5.400252 -11.76523 47.15177 11.29141 -22.25764 4.234671 11.68488 -22.15949 6.67057 12.1451 -22.13179 9.135292 12.59427 -22.12653 11.55358 13.1365 -22.10903 14.03266 13.51677 -22.01366 16.45038 13.73996 -21.82071 18.76076 13.86176 -21.50956 21.00298 13.96519 -21.09398 23.21826 14.08627 -20.60088 25.39638 14.16302 -19.99044 27.56736 14.04099 -19.10376 29.83759 13.6224 -17.77049 32.3585 12.9129 -16.05868 35.41293 11.88367 -14.5055 39.14696 11.22711 -13.19093 41.94712 10.99132 -11.7676 44.27246 9.262909 -11.53849 46.12461 8.679059 -11.63292 47.54777 8.368472 -11.52432 49.10586 13.67987 -22.31238 4.61483 14.30659 -22.4492 7.231131 14.73847 -22.67075 9.730888 14.98744 -22.85956 12.07938 15.20856 -22.96379 14.39634 15.3883 -22.9423 16.66953 15.55128 -22.78449 18.9121 15.70268 -22.49674 21.13942 15.85886 -22.10121 23.33593 16.00703 -21.61551 25.46266 16.01684 -20.97786 27.5125 15.6298 -19.89334 29.65195 14.76568 -17.88511 32.33815 13.80947 -15.05079 36.23146 12.9622 -12.1977 41.90402 12.21831 -13.30841 41.36444 11.45508 -10.97672 44.26912 10.0326 -10.95388 45.52315 9.18474 -11.39536 46.73489 20.94557 -22.70824 5.631571 17.86835 -22.55486 5.41334 21.0481 -23.3579 7.917845 18.21051 -23.07836 7.812767 21.10231 -23.89685 10.1318 18.32175 -23.53222 10.0716 21.1503 -24.32473 12.37131 18.36937 -23.87111 12.31686 21.20141 -24.63205 14.65425 18.42781 -24.08399 14.58904 21.2576 -24.80459 16.95529 18.52226 -24.16659 16.87251 21.30218 -24.81248 19.21896 18.65787 -24.10986 19.14113 21.23154 -24.57151 21.39048 18.79716 -23.9017 21.35707 20.83161 -24.00028 23.45985 18.84715 -23.51282 23.47144 21.11734 -23.29006 24.58209 18.83909 -22.95549 25.31254 19.80482 -22.48366 26.26466 18.34665 -22.19298 27.01084 21.50403 -21.3598 25.75883 17.95197 -21.01152 28.26572 24.4722 -22.63317 5.873657 24.54682 -23.37091 8.094801 24.64755 -23.99362 10.27073 24.74739 -24.52226 12.48486 24.82077 -24.94331 14.73419 24.83892 -25.21681 16.95908 24.78623 -25.21856 19.04317 24.49672 -24.69516 20.98866 22.84243 -23.57034 23.47729 26.43498 -22.67524 21.82755 27.97394 -22.13621 6.16276 28.138 -22.91663 8.380322 28.32103 -23.5987 10.53221 28.48226 -24.20756 12.68997 28.5708 -24.71534 14.79865 28.58378 -25.01628 16.72187 28.80967 -24.80716 18.17724 29.75843 -23.72105 18.8944 31.48724 -21.24298 6.505793 31.69457 -22.02844 8.752724 31.90089 -22.73247 10.87632 32.04863 -23.37663 12.90975 32.07059 -23.90497 14.71453 32.06041 -24.1459 16.14177 32.68431 -23.63047 16.80489 34.96014 -20.1181 6.867506 35.16431 -20.86921 9.123514 35.32815 -21.54609 11.16023 35.36977 -22.1597 12.95196 35.16713 -22.67079 14.35411 34.6968 -23.00227 15.49002 38.1336 -18.94208 7.128994 38.30232 -19.65191 9.367857 38.39715 -20.28119 11.27499 38.28182 -20.84312 12.77792 37.65249 -21.40626 13.79478 40.40665 -18.0025 7.167845 40.51919 -18.70311 9.414122 40.53418 -19.32342 11.27445 40.11783 -19.95285 12.72747 37.89721 -21.214 14.38565 -36.0881 -21.33066 4.220787 -36.05186 -21.0993 5.824562 -35.96141 -20.64187 7.51071 -35.85749 -20.05537 9.168436 -35.74835 -19.40291 10.68301 -35.63321 -18.70693 12.02026 -35.50278 -17.91211 13.29751 -35.35233 -16.98262 14.63582 -35.19248 -16.08211 15.88281 -34.94097 -15.30672 16.95396 -34.48993 -14.60294 17.98092 -33.80134 -13.89195 19.14171 -32.97417 -13.23823 20.39732 41.32491 -17.5354 6.953783 41.40905 -18.24408 9.233017 41.45227 -18.84594 11.11261 41.38341 -19.27138 12.41116 40.9576 -19.5796 13.19855 40.67158 -19.45853 13.66543 36.7629 -21.12155 15.54278 39.98118 -19.14546 14.25811 34.46121 -21.01896 17.19146 39.62065 -18.0999 14.73878 30.94276 -20.81872 19.42435 42.02212 -11.24936 2.657364 42.0222 -11.6962 4.418465 42.02138 -12.24637 6.429634 42.02041 -12.83813 8.500488 42.01947 -13.36886 10.54647 42.01858 -13.66037 12.21734 42.01747 -13.74639 13.12822 42.01731 -13.78952 13.47634 -36.85607 -7.395843 4.673773 -36.86244 -7.501414 6.27482 -36.85443 -7.738445 8.601093 -36.83567 -7.952468 11.37269 -36.77519 -8.038483 13.76039 -36.60205 -8.066345 15.44303 -36.2764 -8.096558 16.64195 -35.77499 -8.143001 17.67924 -35.12307 -8.200977 18.67685 -34.68241 -8.198568 19.26147 -33.26307 -12.92019 20.38599 -31.78158 -11.90959 22.2854 -32.04178 -12.04864 21.98617 -33.05307 -12.68976 20.71327 -31.8394 -11.86966 22.2999 -32.79792 -12.42934 21.11204 -31.50097 -11.61521 22.78454 -32.51232 -12.16457 21.54295 -31.08798 -11.34693 23.29805 -32.20164 -11.91844 21.96888 -31.92384 -11.72417 22.29938 -30.42971 -11.01677 23.92545 -33.72209 -13.385 19.68676 -34.35958 -13.90201 18.79178 -34.24182 -13.66092 19.08411 -34.07139 -13.41623 19.39869 -33.89572 -13.15754 19.72511 -33.70595 -12.89231 20.06282 -33.49144 -12.64335 20.40171 -33.34536 -12.44411 20.63555 -34.91856 -14.49959 17.86984 -34.88898 -14.28979 18.09305 -34.78614 -14.05705 18.36421 -34.6797 -13.80885 18.63812 -34.56331 -13.54106 18.92437 -34.4249 -13.27511 19.21701 -34.28262 -13.02515 19.48587 -33.635 -12.44152 20.35917 -34.20999 -12.80259 19.66043 -33.55237 -12.22852 20.52293 -34.06434 -12.53416 19.91134 -33.35896 -11.95582 20.80633 -33.88796 -12.24849 20.18257 -33.15584 -11.64155 21.08966 -33.71679 -11.91976 20.43213 -32.99143 -11.24155 21.32189 -33.58039 -11.47476 20.63162 -32.87948 -10.71662 21.47712 -33.48582 -10.86885 20.76298 -32.81611 -10.03965 21.55943 -33.4344 -10.07763 20.82832 -32.77513 -9.358541 21.60309 -33.40245 -9.297863 20.86028 -32.73704 -8.885254 21.63297 -33.38896 -8.785936 20.86121 -32.59994 -8.737526 21.77011 -33.36264 -8.568209 20.87731 -33.27613 -8.532699 20.96158 -32.10611 -9.06354 22.28085 -32.65243 -8.510615 21.6787 -33.38269 -8.382586 20.83132 -35.30339 -15.12468 16.9743 -35.31856 -14.89096 17.21139 -35.27072 -14.65212 17.4725 -35.21757 -14.40735 17.72327 -35.15771 -14.13564 17.98704 -35.08335 -13.8503 18.25989 -34.98793 -13.57108 18.52471 -34.88953 -13.2881 18.76993 -34.76867 -12.99253 19.01898 -34.6389 -12.68298 19.25555 -34.51645 -12.30724 19.46019 -34.42037 -11.76436 19.61242 -34.35585 -11.01136 19.70569 -34.32761 -10.0782 19.7447 -34.31706 -9.208691 19.7558 -34.31378 -8.696844 19.74848 -34.31119 -8.485849 19.74055 -34.30192 -8.39706 19.74234 -34.34083 -8.316118 19.68758 -35.53507 -15.83242 15.99651 -35.60108 -15.54086 16.28528 -35.60736 -15.2655 16.57559 -35.60366 -15.00452 16.83481 -35.59341 -14.71907 17.09981 -35.56845 -14.40872 17.37648 -35.52155 -14.09844 17.6428 -35.46495 -13.78057 17.8906 -35.39009 -13.45905 18.12469 -35.30384 -13.11421 18.33671 -35.22117 -12.66761 18.50941 -35.16032 -12.00196 18.62023 -35.12374 -11.09155 18.67975 -35.11911 -10.02909 18.69781 -35.13887 -9.100384 18.6864 -35.15492 -8.612967 18.66639 -35.16034 -8.429986 18.6539 -35.15843 -8.341352 18.6496 -35.15615 -8.268471 18.64492 -35.68717 -16.67566 14.82292 -35.78983 -16.30861 15.18716 -35.83867 -15.95593 15.55545 -35.8748 -15.63446 15.87867 -35.90582 -15.30377 16.18704 -35.92576 -14.95224 16.49048 -35.92761 -14.60526 16.76546 -35.91864 -14.25905 17.00919 -35.88747 -13.90696 17.23156 -35.83759 -13.50729 17.42688 -35.78604 -12.96483 17.57687 -35.75378 -12.17144 17.6562 -35.73943 -11.12633 17.69044 -35.75066 -9.960366 17.69796 -35.78809 -9.01564 17.68032 -35.81733 -8.554998 17.65543 -35.82847 -8.384457 17.64028 -35.82886 -8.293377 17.63434 -35.82286 -8.215494 17.63356 -35.82019 -17.59743 13.49697 -35.93201 -17.20363 13.88599 -36.0055 -16.78902 14.31093 -36.07034 -16.38973 14.70973 -36.13318 -15.98062 15.09353 -36.19213 -15.55233 15.46035 -36.23843 -15.13665 15.77691 -36.26595 -14.74328 16.044 -36.26882 -14.33752 16.26975 -36.25067 -13.84792 16.45138 -36.22283 -13.1808 16.58531 -36.20738 -12.2496 16.6508 -36.211 -11.06486 16.66742 -36.23996 -9.797134 16.65898 -36.28373 -8.899738 16.63832 -36.31281 -8.49975 16.61983 -36.32289 -8.343882 16.61036 -36.32266 -8.249816 16.60793 -36.31622 -8.168642 16.60886 -35.94351 -18.41576 12.19112 -36.06027 -18.06297 12.53206 -36.14693 -17.6608 12.93231 -36.22693 -17.23451 13.34407 -36.30401 -16.77252 13.76768 -36.37992 -16.27618 14.18552 -36.45098 -15.77402 14.55504 -36.49912 -15.28497 14.87184 -36.52325 -14.75869 15.12343 -36.52832 -14.12005 15.3015 -36.51955 -13.30922 15.42243 -36.51644 -12.25375 15.47888 -36.53489 -10.93875 15.48343 -36.57871 -9.574894 15.46085 -36.61917 -8.755977 15.43261 -36.63842 -8.441082 15.42147 -36.64381 -8.310593 15.42044 -36.64358 -8.217754 15.42099 -36.63807 -8.135815 15.42081 -36.05645 -19.12145 10.84047 -36.18026 -18.80851 11.14056 -36.27402 -18.44958 11.49505 -36.36152 -18.04802 11.86771 -36.44362 -17.59296 12.2571 -36.5181 -17.08454 12.654 -36.58618 -16.51917 13.02603 -36.63179 -15.88979 13.35312 -36.65759 -15.1606 13.60083 -36.66949 -14.31153 13.76305 -36.6706 -13.35055 13.87347 -36.67498 -12.21533 13.93186 -36.70075 -10.83894 13.94116 -36.75183 -9.431036 13.91184 -36.7913 -8.661146 13.85343 -36.80614 -8.398252 13.8135 -36.80984 -8.287227 13.79548 -36.81016 -8.198473 13.7868 -36.80555 -8.115222 13.77533 -36.15699 -19.77678 9.320755 -36.28595 -19.48539 9.59652 -36.38371 -19.15653 9.915022 -36.47417 -18.77963 10.24468 -36.55548 -18.3439 10.58193 -36.61997 -17.83383 10.92379 -36.66873 -17.19534 11.23534 -36.69676 -16.38285 11.47362 -36.71079 -15.41202 11.61967 -36.71724 -14.35201 11.70414 -36.71905 -13.27095 11.7803 -36.72444 -12.11282 11.84461 -36.74841 -10.76309 11.87616 -36.79874 -9.382447 11.8625 -36.84418 -8.609251 11.79565 -36.86306 -8.343037 11.7102 -36.86714 -8.23945 11.6334 -36.86672 -8.156995 11.57681 -36.86177 -8.065346 11.51025 -36.24527 -20.37112 7.635973 -36.37511 -20.09805 7.872774 -36.47292 -19.79089 8.145779 -36.55957 -19.43139 8.427998 -36.63089 -18.99973 8.715209 -36.67977 -18.44266 8.996932 -36.70816 -17.6723 9.221403 -36.72057 -16.6648 9.338703 -36.72526 -15.50854 9.372429 -36.7269 -14.31368 9.381491 -36.72744 -13.15208 9.414635 -36.73046 -11.9855 9.462084 -36.74692 -10.70256 9.493195 -36.79131 -9.397882 9.50535 -36.84704 -8.585703 9.486574 -36.87622 -8.260355 9.361366 -36.8829 -8.128645 9.160624 -36.88142 -8.028159 8.986721 -36.87601 -7.905918 8.837479 -36.31449 -20.84494 5.883478 -36.44025 -20.59287 6.049192 -36.53398 -20.30571 6.2507 -36.61311 -19.95479 6.463415 -36.6711 -19.4995 6.683554 -36.70405 -18.85133 6.897192 -36.71759 -17.92801 7.0466 -36.7209 -16.77329 7.086811 -36.72354 -15.52833 7.064369 -36.72492 -14.27997 7.033516 -36.72567 -13.06331 7.025558 -36.72775 -11.8683 7.03981 -36.73902 -10.63657 7.064911 -36.77747 -9.422327 7.122877 -36.83988 -8.579374 7.187965 -36.87803 -8.173402 7.032911 -36.88816 -7.975402 6.691803 -36.88664 -7.8228 6.418871 -36.88095 -7.668562 6.315924 -36.32772 -21.09538 4.219208 -36.44505 -20.86098 4.290348 -36.53105 -20.58903 4.386248 -36.60121 -20.23964 4.489641 -36.64801 -19.75299 4.601101 -36.66933 -19.0163 4.721279 -36.6718 -17.94157 4.805738 -36.669 -16.63212 4.808561 -36.68042 -15.31922 4.76861 -36.69203 -14.07833 4.723072 -36.70032 -12.87556 4.687487 -36.70965 -11.69161 4.669777 -36.72529 -10.51592 4.68878 -36.76319 -9.400557 4.805399 -36.82586 -8.570715 4.998669 -36.86687 -8.117035 4.953316 -36.87939 -7.872468 4.686832 -36.87886 -7.69312 4.510555 -36.87355 -7.537912 4.543591 -36.18083 -20.98238 2.717182 -36.27899 -20.75062 2.695202 -36.35025 -20.48303 2.675388 -36.40692 -20.14353 2.654749 -36.44252 -19.66089 2.640625 -36.45211 -18.85704 2.651401 -36.43845 -17.54677 2.662956 -36.42837 -15.90187 2.629068 -36.46628 -14.40186 2.5744 -36.51602 -13.20871 2.524668 -36.56059 -12.16932 2.483271 -36.60793 -11.16613 2.456547 -36.65446 -10.17949 2.475063 -36.71043 -9.253643 2.615217 -36.77668 -8.523077 2.86599 -36.81381 -8.08227 2.934565 -36.82493 -7.830333 2.825344 -36.82607 -7.655776 2.793722 -36.82374 -7.515474 2.900669 42.02316 -14.06072 13.78062 42.01669 -14.16014 13.84588 42.01361 -14.21977 13.87856 42.02069 -14.14543 13.83161 42.01176 -14.26525 13.90042 42.01708 -14.23644 13.87864 42.02247 -13.82848 13.59253 42.02595 -13.81041 13.53643 42.02458 -13.85764 13.63431 42.02872 -13.83332 13.58158 42.0252 -13.89576 13.66695 42.02498 -13.96258 13.71499 42.03048 -13.87845 13.62613 42.03178 -13.94379 13.67815 42.03184 -14.01996 13.73313 42.02981 -14.11832 13.79473 42.01185 -14.34897 13.92237 42.02471 -14.2488 13.86041 41.99841 -14.52845 13.98769 42.01348 -14.4419 13.94049 41.98191 -14.70076 14.04512 41.99925 -14.63271 14.01034 41.95611 -14.85077 14.07793 41.98476 -14.77305 14.05396 41.95587 -14.90415 14.07416 41.82128 -15.17622 14.10398 41.81578 -15.18381 14.10352 41.09597 -16.24809 14.28495 41.51409 -15.47737 14.21697 39.41867 -17.28799 15.04852 41.27375 -16.15792 14.23559 41.83649 -15.37522 14.07145 41.46329 -16.74906 13.99814 41.89077 -15.69441 13.98248 41.79331 -16.60264 13.8604 41.91207 -15.92891 13.9281 41.83605 -16.67352 13.82178 41.89302 -16.23003 13.87011 42.02831 -13.77289 13.21006 42.03242 -13.77988 13.30709 42.03567 -13.81065 13.38941 42.03908 -13.85794 13.46299 42.04183 -13.91124 13.53551 42.04307 -13.98472 13.61449 42.04212 -14.09418 13.70326 42.03713 -14.26869 13.80734 42.02793 -14.47896 13.90462 42.0163 -14.67176 13.97481 42.00537 -14.82007 14.01071 41.98713 -14.98272 14.01363 41.94709 -15.23839 13.99269 41.98487 -15.52634 13.92889 41.98212 -15.76451 13.90002 41.96944 -15.87692 13.88838 41.94655 -16.2137 13.81926 41.82238 -16.61759 13.80491 41.88801 -16.88833 13.68379 41.40518 -17.43563 13.85478 41.57274 -18.04181 13.58982 42.03017 -13.75439 12.30819 42.03501 -13.78657 12.49122 42.03895 -13.83078 12.66764 42.04344 -13.87627 12.82371 42.04818 -13.90844 12.97514 42.05273 -13.94597 13.12934 42.05674 -14.00784 13.28949 42.05899 -14.12101 13.45427 42.05688 -14.30492 13.60597 42.04981 -14.5507 13.72773 42.04236 -14.85704 13.78957 42.03481 -15.26467 13.77605 42.02499 -15.84052 13.69532 42.01676 -16.44134 13.60932 42.00227 -16.73469 13.58963 41.98398 -16.82016 13.59329 41.95249 -17.20272 13.52631 41.89303 -17.84646 13.39943 41.69818 -18.65535 13.29778 42.03123 -13.60573 10.63279 42.0362 -13.74667 10.87335 42.04018 -13.86861 11.14101 42.04486 -13.96131 11.40328 42.05049 -14.01927 11.67433 42.05702 -14.06681 11.95362 42.06442 -14.11427 12.23267 42.07173 -14.16719 12.50021 42.07495 -14.26468 12.74725 42.07278 -14.49298 12.96026 42.07312 -14.99327 13.06776 42.0699 -15.73691 13.05628 42.0616 -16.64418 12.96231 42.04545 -17.44225 12.89465 42.01995 -17.84251 12.92055 41.98394 -18.00042 12.9813 41.93154 -18.30921 12.99535 41.8605 -18.68253 12.96702 41.70441 -19.05221 12.95475 42.0326 -13.17266 8.601936 42.03775 -13.39291 8.857866 42.04174 -13.5872 9.154993 42.04631 -13.76544 9.45182 42.05183 -13.93159 9.754416 42.05841 -14.09838 10.0618 42.06604 -14.25206 10.37019 42.07258 -14.34986 10.68375 42.07225 -14.38021 11.01506 42.07002 -14.51879 11.32631 42.08154 -15.08403 11.49292 42.08831 -15.93958 11.54087 42.08319 -16.89807 11.53478 42.06345 -17.68703 11.58524 42.0254 -18.14773 11.7329 41.96978 -18.40107 11.91466 41.89871 -18.64839 12.06949 41.82049 -18.86051 12.18148 41.71971 -19.02868 12.27261 42.03439 -12.61894 6.547531 42.03993 -12.86112 6.792585 42.04423 -13.07697 7.074137 42.04903 -13.2974 7.354483 42.05465 -13.53214 7.634462 42.06109 -13.78826 7.91435 42.06739 -14.0466 8.195271 42.06832 -14.23294 8.496786 42.05862 -14.29901 8.841469 42.0562 -14.49199 9.157398 42.07622 -15.12288 9.324745 42.08955 -15.94737 9.421494 42.08279 -16.76674 9.515152 42.05309 -17.40468 9.675482 42.00025 -17.8149 9.91141 41.93047 -18.08636 10.17565 41.85016 -18.31051 10.43671 41.76882 -18.49596 10.67951 41.68252 -18.6502 10.90388 42.03618 -12.07676 4.519627 42.0422 -12.31652 4.727747 42.0469 -12.5302 4.971395 42.05213 -12.75933 5.220737 42.05809 -13.01547 5.473398 42.06441 -13.30359 5.728067 42.06856 -13.60052 5.986002 42.06324 -13.83247 6.265583 42.05049 -14.01628 6.56612 42.05885 -14.44725 6.79847 42.08081 -15.1526 6.936983 42.08651 -15.85769 7.076239 42.06724 -16.46636 7.247091 42.02188 -16.92266 7.472715 41.95478 -17.24308 7.744789 41.87602 -17.4863 8.037134 41.79268 -17.69262 8.339209 41.71305 -17.87354 8.645031 41.63064 -18.03708 8.947842 42.03668 -11.61794 2.706692 42.04281 -11.8457 2.846216 42.04763 -12.04823 3.019407 42.05285 -12.2719 3.205856 42.05805 -12.53243 3.405245 42.06194 -12.83059 3.616236 42.06002 -13.12535 3.842117 42.04637 -13.34477 4.09528 42.03062 -13.6003 4.342342 42.04637 -14.22108 4.484289 42.06456 -14.96665 4.58349 42.05829 -15.57636 4.730656 42.02371 -16.03065 4.927685 41.96356 -16.35965 5.167492 41.88684 -16.61044 5.435045 41.80398 -16.81774 5.717688 41.72084 -16.99947 6.015131 41.64392 -17.16436 6.327253 41.56031 -17.32281 6.646069 42.02982 -11.26913 1.418776 42.03372 -11.46563 1.456161 42.03671 -11.64099 1.521643 42.03884 -11.84681 1.602282 42.03778 -12.11617 1.700245 42.03028 -12.45295 1.814238 42.01121 -12.8184 1.946474 41.99078 -13.13654 2.102501 41.96909 -13.48858 2.254438 41.96659 -14.10863 2.330334 41.9589 -14.74566 2.396385 41.92885 -15.22904 2.512629 41.872 -15.56409 2.672241 41.794 -15.80695 2.861013 41.70639 -16.00265 3.067123 41.61593 -16.16994 3.284151 41.52599 -16.31906 3.51436 41.442 -16.45595 3.759966 41.34638 -16.59219 4.015848 41.65081 -10.69341 0.5448074 40.22512 -11.34956 0.4944096 41.60861 -10.85296 0.4099617 40.08352 -11.54617 0.3248234 41.56562 -11.03407 0.3258972 39.94954 -11.76614 0.2027339 41.50797 -11.30563 0.2522774 39.79185 -12.08026 0.09512901 41.41135 -11.73528 0.189989 39.5692 -12.54633 0.01895141 41.20648 -12.30253 0.1428451 39.17453 -13.15871 -0.02358436 40.88038 -12.93863 0.1125488 38.6034 -13.84836 -0.04598808 40.64182 -13.47982 0.09576606 38.16476 -14.40221 -0.05935287 40.48696 -13.95817 0.08693313 37.87489 -14.8418 -0.06867599 40.35645 -14.45758 0.07795524 37.64141 -15.25888 -0.0751686 40.22465 -14.92723 0.07516479 37.4233 -15.66609 -0.07828903 40.06701 -15.30473 0.08567619 37.20043 -16.04189 -0.07656669 39.86701 -15.5899 0.106512 36.9574 -16.37667 -0.07037925 39.63615 -15.80853 0.1356334 36.69412 -16.65531 -0.05863571 39.39317 -15.98799 0.1718158 36.41522 -16.88337 -0.04066467 39.13941 -16.14641 0.2128829 36.1164 -17.06538 -0.01701164 38.87727 -16.29451 0.256485 35.80819 -17.22611 0.01005929 38.61753 -16.43247 0.302515 35.50133 -17.37586 0.03961563 38.36267 -16.57058 0.3755207 35.20108 -17.52562 0.09665107 36.84611 -12.98779 0.3249989 36.75281 -13.13268 0.207735 36.53324 -13.31984 0.116518 36.29039 -13.54477 0.0479831 36.02764 -13.83163 -0.01192277 35.7356 -14.19424 -0.05019372 35.35222 -14.63374 -0.06825256 34.86066 -15.12598 -0.07735824 34.46701 -15.53478 -0.08358764 34.16941 -15.87982 -0.08873939 33.91144 -16.21712 -0.09274673 33.66529 -16.56163 -0.09547042 33.4246 -16.90991 -0.0964775 33.18954 -17.25528 -0.09522819 32.96561 -17.58773 -0.09022331 32.74009 -17.9022 -0.07989501 32.48106 -18.12494 -0.06325531 32.20185 -18.28764 -0.04148674 31.91359 -18.43078 -0.01568222 31.62804 -18.57287 0.03651803 32.21892 -14.6718 0.07424736 32.18269 -14.79367 0.02611732 31.97911 -14.93995 -0.01202195 31.75808 -15.13787 -0.03655236 31.49835 -15.37993 -0.05583375 31.208 -15.65074 -0.0674076 30.88263 -15.94351 -0.07375526 30.50779 -16.25642 -0.07859992 30.16976 -16.5393 -0.08309745 29.88499 -16.80088 -0.08742523 29.66129 -17.06003 -0.09140014 29.4651 -17.32624 -0.09476089 29.27455 -17.60289 -0.09718704 29.09624 -17.90532 -0.09822082 28.95512 -18.28956 -0.09687995 28.8379 -18.75642 -0.09149169 28.68033 -19.06995 -0.08027648 28.48229 -19.242 -0.06371688 28.24813 -19.36836 -0.04277992 28.00811 -19.49031 0.003484666 26.67619 -15.86972 0.00170511 26.72613 -15.96439 -0.02492707 26.6838 -16.07523 -0.0440464 26.67621 -16.23911 -0.05533021 26.59187 -16.43027 -0.06263732 26.41802 -16.6309 -0.0675373 26.17766 -16.83428 -0.07178306 25.8782 -17.03959 -0.07614135 25.57381 -17.23051 -0.08065414 25.3234 -17.40394 -0.08524131 25.17639 -17.56703 -0.08970642 25.08835 -17.73264 -0.09368133 25.01352 -17.91527 -0.09676361 24.94282 -18.17042 -0.09862709 24.90145 -18.63422 -0.09880828 24.8915 -19.29851 -0.09622764 24.84617 -19.75072 -0.08927726 24.74462 -19.95728 -0.07803916 24.5761 -20.07303 -0.06286048 24.39396 -20.17632 -0.02341073 21.12437 -16.64016 -0.03286355 21.27569 -16.72411 -0.05047982 21.53054 -16.84308 -0.05784225 21.69728 -16.96698 -0.06258773 21.73134 -17.08498 -0.06667518 21.66529 -17.19994 -0.0708332 21.52992 -17.31583 -0.07528114 21.37038 -17.4291 -0.07995033 21.23513 -17.53703 -0.08473396 21.16349 -17.64364 -0.08940696 21.12379 -17.75807 -0.09356307 21.08155 -17.89977 -0.09677505 21.02243 -18.15256 -0.09876251 20.97708 -18.68797 -0.0993843 20.97381 -19.48899 -0.09819412 20.95076 -20.09322 -0.09389495 20.85836 -20.40551 -0.08574676 20.68146 -20.57579 -0.07311439 20.49367 -20.70831 -0.03752136 18.18169 -16.79913 -0.0349884 18.36208 -16.88047 -0.0519371 18.52703 -16.95384 -0.05801582 18.62346 -17.02673 -0.06225967 18.64292 -17.09676 -0.06639671 18.60858 -17.16789 -0.070755 18.54047 -17.24333 -0.07540512 18.45713 -17.32379 -0.08023262 18.37313 -17.41006 -0.08508682 18.30275 -17.50418 -0.08973121 18.2247 -17.61297 -0.09379768 18.1099 -17.7599 -0.09692001 17.94034 -18.03582 -0.0988655 17.77739 -18.59811 -0.09962654 17.68198 -19.44353 -0.09915924 17.58199 -20.19957 -0.09638977 17.39373 -20.70035 -0.08964729 17.11024 -21.0054 -0.07751083 16.82479 -21.21844 -0.04523849 17.17957 -16.70999 -0.02686882 17.46424 -16.83684 -0.04485702 17.51997 -16.87944 -0.05256074 17.53897 -16.92501 -0.05756378 17.52449 -16.97754 -0.06184762 17.48579 -17.03432 -0.06607627 17.43339 -17.09519 -0.07054519 17.37523 -17.16356 -0.07528495 17.30335 -17.23853 -0.08015251 17.21647 -17.32575 -0.08499526 17.11558 -17.42585 -0.08957481 16.96986 -17.54961 -0.09358978 16.74162 -17.72467 -0.09671401 16.42669 -18.02994 -0.09872055 16.13923 -18.58305 -0.09960937 15.96479 -19.40574 -0.09947967 15.81982 -20.24967 -0.09753608 15.59538 -20.89698 -0.09184265 15.27921 -21.29604 -0.08041381 14.96219 -21.54757 -0.05086129 3.135792 -10.68497 -0.01356506 10.97141 -14.16549 -0.0210151 11.49417 -14.43093 -0.0367183 3.36737 -10.83599 -0.02864068 11.5534 -14.5232 -0.04332154 3.41597 -10.95864 -0.03508752 11.62307 -14.73663 -0.04794687 3.643524 -11.38412 -0.03920364 12.06687 -15.42573 -0.05381768 4.534737 -12.66053 -0.04539299 12.91726 -16.61824 -0.06236642 6.122584 -14.75501 -0.05583375 13.21969 -17.40453 -0.06920242 7.026989 -16.20845 -0.06394004 13.00993 -17.83734 -0.07416725 7.222069 -17.02429 -0.06836318 12.74155 -18.23357 -0.07825851 7.468565 -17.85598 -0.06938552 12.58338 -18.71262 -0.08139991 8.063841 -18.91117 -0.06752014 12.27675 -19.09551 -0.08514595 8.289428 -19.54543 -0.06942558 11.88886 -19.43426 -0.08941268 8.213994 -19.89158 -0.07512664 11.5975 -19.75889 -0.09368324 8.127902 -20.17686 -0.08208274 11.41042 -20.14585 -0.09613609 8.071954 -20.47377 -0.08667182 11.31304 -20.70297 -0.09713363 8.081357 -20.90886 -0.0902462 11.28677 -21.36046 -0.09601974 8.201075 -21.48947 -0.09269523 11.27991 -21.84362 -0.08785438 8.380582 -21.94095 -0.08564567 11.24467 -22.09078 -0.06147766 8.532704 -22.16986 -0.05803871 3.857616 -18.22944 -0.05535119 4.763094 -19.40069 -0.0516662 4.977948 -19.87257 -0.05657005 5.007912 -20.21545 -0.06445121 5.022259 -20.55347 -0.07054519 5.121259 -20.9944 -0.0780754 5.381928 -21.56614 -0.08684921 5.729153 -21.99152 -0.08238029 6.065861 -22.20002 -0.05131912 3.076789 -19.194 -0.04224586 3.422324 -19.75474 -0.04574006 3.476819 -20.13908 -0.05372047 3.504965 -20.52551 -0.06054115 3.642211 -21.00255 -0.07051658 3.976061 -21.59403 -0.08362197 4.40381 -22.0101 -0.08104515 4.849295 -22.20953 -0.04825013 -2.510519 -8.13492 -0.03243446 -2.538321 -8.130533 -0.03278923 -2.508368 -8.188328 -0.08260917 -2.535842 -8.183856 -0.08319091 -2.507183 -8.24596 -0.09146881 -2.534976 -8.240826 -0.09214782 -2.531295 -8.311134 -0.09461593 -2.559838 -8.304312 -0.09536743 -2.667306 -8.392608 -0.09596824 -2.702248 -8.374975 -0.09677124 -3.003532 -8.57054 -0.09539604 -3.082252 -8.489487 -0.0960865 -3.294919 -9.154335 -0.09420394 -3.50823 -8.884418 -0.09426689 -3.118726 -10.486 -0.09482192 -3.459612 -10.03627 -0.09414863 -2.722002 -12.12324 -0.09655952 -2.936254 -11.85829 -0.09643554 -2.533488 -13.51721 -0.09738349 -2.615234 -13.44472 -0.09791183 -2.488599 -14.73109 -0.09692573 -2.531603 -14.72106 -0.09777069 -2.381843 -15.96039 -0.09156036 -2.464512 -15.9349 -0.09304046 -6.288774 -8.117205 -0.03306573 -9.32049 -8.150164 -0.03017044 -6.291289 -8.175621 -0.08413314 -9.336425 -8.23355 -0.08285522 -6.290299 -8.243785 -0.0933113 -9.332363 -8.344345 -0.0927124 -6.289753 -8.323805 -0.09667778 -9.334908 -8.494434 -0.09611129 -6.293797 -8.408473 -0.09849166 -9.35447 -8.670349 -0.09799766 -6.301784 -8.49868 -0.09875488 -9.359095 -8.843668 -0.09852981 -6.333815 -8.727794 -0.09773254 -9.361143 -9.10256 -0.09782791 -6.371882 -9.551823 -0.09682273 -9.379654 -9.7853 -0.09686279 -6.332421 -11.31986 -0.09769248 -9.390888 -11.26422 -0.09722518 -6.311552 -13.20806 -0.09914588 -9.414801 -13.11721 -0.09869003 -6.344861 -14.6702 -0.0998001 -9.438226 -14.65032 -0.09962463 -6.480588 -15.83498 -0.09980773 -9.487797 -15.82813 -0.09984016 -6.72555 -16.85689 -0.09905815 -9.580019 -16.83295 -0.09944725 -6.895052 -17.81244 -0.09441375 -9.640659 -17.76274 -0.09626579 -6.814986 -18.71251 -0.07591819 -9.60167 -18.60412 -0.08192253 -6.44521 -19.43857 -0.0373497 -9.434318 -19.2389 -0.04736137 -6.165432 -19.84759 0.007600784 -9.314538 -19.62066 0.004055023 -6.028835 -20.11359 0.0692768 -9.266279 -19.92616 0.08118629 -5.942776 -20.33947 0.1560363 -9.240927 -20.19273 0.1801624 -12.86568 -8.294795 -0.02044105 -12.90996 -8.431626 -0.07782554 -12.91392 -8.612597 -0.09046745 -12.96772 -8.87796 -0.09455871 -13.0388 -9.20673 -0.09674263 -13.04795 -9.545654 -0.0978794 -13.02 -10.00067 -0.09807205 -13.07183 -10.78766 -0.09780693 -13.20746 -12.07494 -0.09802818 -13.33966 -13.61394 -0.0989933 -13.39779 -14.89144 -0.09964561 -13.40648 -15.90095 -0.09984016 -13.40387 -16.83529 -0.09956359 -13.39234 -17.74419 -0.09706687 -13.3733 -18.55566 -0.08517265 -13.33076 -19.13418 -0.05359077 -13.30061 -19.49957 0.001283586 -13.29405 -19.82959 0.08728599 -13.29438 -20.11716 0.1915054 -16.01276 -8.598185 -0.006315231 -16.04854 -8.757514 -0.07032585 -16.16248 -8.950115 -0.08618354 -16.49531 -9.244151 -0.09143638 -16.70883 -9.609321 -0.09404373 -16.68113 -10.04168 -0.09560585 -16.55043 -10.74967 -0.0964756 -16.69211 -11.81124 -0.09703063 -17.07636 -13.12006 -0.09768676 -17.38873 -14.36039 -0.09863471 -17.51465 -15.28536 -0.09935951 -17.52157 -16.04096 -0.09971618 -17.48822 -16.86682 -0.09953308 -17.45737 -17.75244 -0.09714317 -17.45247 -18.55568 -0.08583831 -17.46173 -19.11275 -0.0553283 -17.46017 -19.47111 4.48227e-4 -17.46022 -19.80809 0.08866691 -17.46476 -20.09837 0.189888 -19.32188 -8.875013 -0.003156602 -19.26175 -9.007406 -0.069458 -19.78115 -9.171773 -0.08333778 -20.88096 -9.437892 -0.08746337 -21.45337 -9.78459 -0.08986663 -21.28159 -10.37428 -0.0915451 -20.79578 -11.46915 -0.09288024 -20.81965 -12.79701 -0.09431266 -21.2632 -14.0655 -0.09591102 -21.56329 -15.00631 -0.09757995 -21.65181 -15.59944 -0.09885978 -21.63749 -16.13838 -0.09952926 -21.59738 -16.88895 -0.09942436 -21.57351 -17.7667 -0.09699058 -21.58629 -18.56844 -0.08569145 -21.62199 -19.11522 -0.05545228 -21.63215 -19.46898 4.59671e-4 -21.63025 -19.80654 0.08912849 -21.62944 -20.09672 0.1894569 -24.09736 -8.893311 -0.01240158 -24.06587 -9.071297 -0.0709877 -25.04449 -9.239873 -0.08162879 -26.86536 -9.47921 -0.08508682 -27.80499 -9.826429 -0.0875225 -27.50755 -10.57421 -0.08939552 -26.56428 -11.91236 -0.09111022 -26.09949 -13.25514 -0.09305763 -26.06509 -14.35008 -0.09511947 -25.93306 -15.13699 -0.0969963 -25.80389 -15.63415 -0.09812927 -25.73128 -16.13426 -0.09876823 -25.69079 -16.88729 -0.09853172 -25.68114 -17.77714 -0.09584808 -25.71164 -18.58059 -0.08436012 -25.76707 -19.11998 -0.05420494 -25.78681 -19.47048 0.001771867 -25.78332 -19.80732 0.09036827 -25.78054 -20.09745 0.1907978 -30.78986 -8.233122 0.2188948 -30.64935 -8.522665 -0.01865196 -30.54172 -8.802933 -0.07648277 -31.01426 -9.013671 -0.08431434 -32.0558 -9.23234 -0.08750152 -32.52671 -9.515884 -0.08979034 -32.22899 -10.12431 -0.09154891 -31.45999 -11.22272 -0.09321594 -30.96246 -12.36768 -0.09439659 -30.62578 -13.46099 -0.09531974 -30.15192 -14.45472 -0.09520339 -29.83117 -15.19681 -0.0933361 -29.68816 -15.88671 -0.09212684 -29.63824 -16.76265 -0.09018325 -29.64126 -17.73281 -0.08570861 -29.68565 -18.57607 -0.0731678 -29.75295 -19.12396 -0.0423603 -29.77959 -19.47658 0.0141887 -29.77454 -19.81129 0.1020812 -29.76457 -20.10116 0.2035827 -34.9005 -7.848868 0.1326503 -34.77373 -8.094696 -0.04262346 -34.84069 -8.294034 -0.06703567 -35.10734 -8.520752 -0.07152557 -35.15282 -8.834897 -0.07136726 -34.89733 -9.384963 -0.0734539 -34.39122 -10.23275 -0.07933998 -34.02661 -11.12735 -0.08035469 -33.7338 -12.08113 -0.07859992 -33.35231 -13.08895 -0.07265663 -33.09558 -14.01139 -0.06158059 -32.9608 -14.98673 -0.05155366 -32.91198 -16.18527 -0.03952217 -32.93085 -17.46207 -0.02534675 -32.98314 -18.49863 -0.007575929 -33.04409 -19.12189 0.02660942 -33.06574 -19.49793 0.08534049 -33.05686 -19.82999 0.171669 -33.04255 -20.11883 0.2768307 -36.31511 -7.500227 0.3628712 -36.2713 -7.662882 0.1659449 -36.26383 -7.825589 0.1267108 -36.29377 -8.02965 0.1191272 -36.26789 -8.322197 0.1291999 -36.13433 -8.782298 0.1177406 -35.86248 -9.406517 0.08031654 -35.62982 -10.04387 0.06754684 -35.42382 -10.7217 0.07258033 -35.17846 -11.48838 0.08761215 -34.99768 -12.35012 0.1131305 -34.87939 -13.50141 0.1438102 -34.83412 -15.12161 0.1839523 -34.87035 -16.93517 0.2243461 -34.9232 -18.34911 0.2547798 -34.95834 -19.13559 0.2956658 -34.95864 -19.56373 0.3584004 -34.93804 -19.89465 0.4414368 -34.91305 -20.17806 0.5456982 -36.67678 -7.543246 1.062851 -36.67216 -7.681212 0.990799 -36.67078 -7.855196 0.9813557 -36.65945 -8.104311 1.018293 -36.60942 -8.502834 0.9710274 -36.4939 -9.077892 0.8339443 -36.37579 -9.722702 0.7674809 -36.25642 -10.39454 0.7658997 -36.1192 -11.10555 0.7874813 -36.00012 -11.92361 0.8229466 -35.89501 -13.08917 0.8726158 -35.83335 -14.83841 0.9396649 -35.85583 -16.86797 1.001202 -35.89318 -18.44311 1.034164 -35.90387 -19.31088 1.072241 -35.88506 -19.77228 1.132309 -35.84881 -20.09928 1.203157 -35.80396 -20.36991 1.282997 41.97917 -10.93343 0.7216797 41.97271 -11.08502 0.6775398 41.96556 -11.239 0.6626835 41.95315 -11.4492 0.6546784 41.92759 -11.7713 0.6495667 41.86847 -12.19701 0.6491966 41.76492 -12.67848 0.6624985 41.69072 -13.11809 0.6933594 41.63379 -13.55711 0.7307434 41.5846 -14.11338 0.7429218 41.52926 -14.6408 0.7592621 41.45178 -15.03538 0.8054733 41.34249 -15.30253 0.8756771 41.2119 -15.49663 0.9612675 41.07539 -15.65634 1.056864 40.93468 -15.79632 1.158733 40.78993 -15.92378 1.2668 40.64806 -16.04059 1.382051 40.50086 -16.15616 1.511709 18.07064 -19.65845 28.87366 16.92618 -19.09133 29.91193 20.35957 -20.79268 26.7971 19.21511 -20.22557 27.83538 -4.336961 -20.43736 0.1371536 -4.267405 -20.67881 0.3517552 -3.685057 -20.48744 0.125164 -3.611724 -20.72075 0.3367272 -3.264406 -20.52497 0.1154403 -3.192432 -20.75352 0.3253632 -2.872902 -20.56136 0.1061515 -2.801404 -20.78531 0.3144627 -2.486322 -20.59835 0.09722709 -2.413623 -20.81716 0.3034916 -4.459038 -20.23753 0.05872917 -3.817296 -20.29825 0.05071824 -3.399112 -20.3417 0.04370689 -3.009974 -20.38326 0.03706169 -2.626996 -20.42518 0.03089135 -4.648206 -19.99877 0.007820129 -4.027008 -20.07046 0.005041122 -3.621131 -20.11835 0.001308441 -3.243293 -20.16282 -0.002485275 -2.868089 -20.20811 -0.005945146 -5.032971 -19.57122 -0.03240388 -4.460654 -19.63297 -0.03245347 -4.086691 -19.67322 -0.03410339 -3.734483 -19.71106 -0.03588289 -3.360739 -19.75911 -0.03654474 -2.884476 -19.85502 -0.0326175 -2.472922 -20.26289 -0.008197784 -5.550193 -18.78176 -0.07297325 -5.058342 -18.81272 -0.07266044 -4.738711 -18.83377 -0.07296371 -4.425366 -18.85772 -0.07290458 -4.045032 -18.91692 -0.06976699 -3.443482 -19.09652 -0.05667877 -5.664455 -17.84439 -0.09354972 -5.196097 -17.85987 -0.09332847 -4.892832 -17.87094 -0.09317207 -4.588094 -17.88679 -0.09258842 -4.216337 -17.94869 -0.08884429 -3.633601 -18.15672 -0.07493972 -2.830148 -18.50828 -0.0511837 -2.606473 -19.39994 -0.0339241 -5.422783 -16.87342 -0.09885025 -4.91986 -16.88207 -0.09871673 -4.589645 -16.88704 -0.09859657 -4.258581 -16.89077 -0.09840583 -3.900914 -16.91227 -0.09706687 -3.464328 -17.00881 -0.09096145 -2.949723 -17.19129 -0.07940101 -5.067903 -15.84259 -0.09975814 -4.503591 -15.84445 -0.09970664 -4.132029 -15.84484 -0.09966468 -3.771672 -15.84376 -0.09963226 -3.41636 -15.84487 -0.09945869 -3.088669 -15.86425 -0.09820556 -2.818453 -15.91327 -0.09518241 -2.645246 -15.93617 -0.09388732 -2.571077 -17.28823 -0.07382202 -2.535498 -15.9377 -0.09352684 -2.326455 -17.30734 -0.07310867 -4.869623 -14.70596 -0.09989738 -4.268343 -14.71128 -0.09989929 -3.871547 -14.71101 -0.09988594 -3.496819 -14.71043 -0.09987258 -3.142967 -14.70996 -0.09985351 -2.861852 -14.71144 -0.09970283 -2.700788 -14.71883 -0.09917068 -2.620505 -14.72243 -0.09881019 -2.570062 -14.72187 -0.09837532 -4.831112 -13.36011 -0.09955024 -4.233442 -13.40248 -0.09964561 -3.844593 -13.40672 -0.09963417 -3.48226 -13.40712 -0.09960365 -3.145844 -13.40762 -0.09955787 -2.891103 -13.40817 -0.09946823 -2.764222 -13.40918 -0.09925842 -2.708489 -13.41015 -0.09893035 -2.669294 -13.41407 -0.09844779 -4.896924 -11.55967 -0.09832763 -4.356392 -11.65107 -0.09850883 -4.035308 -11.66749 -0.09846115 -3.745874 -11.6705 -0.09834098 -3.480136 -11.67257 -0.09817695 -3.280385 -11.67461 -0.09794425 -3.178553 -11.67653 -0.09761238 -3.127025 -11.68108 -0.0971508 -3.068794 -11.71439 -0.09665489 -4.990178 -9.613794 -0.09705924 -4.526864 -9.64685 -0.09705734 -4.310093 -9.654314 -0.09690093 -4.140108 -9.65901 -0.09664916 -3.990897 -9.663847 -0.09630203 -3.879389 -9.668783 -0.09585571 -3.815278 -9.674299 -0.09528732 -3.766117 -9.689577 -0.09462738 -3.677944 -9.768033 -0.09407997 -4.911118 -8.664226 -0.09776115 -4.408106 -8.660753 -0.09772109 -4.170438 -8.664212 -0.09760856 -3.999986 -8.66911 -0.0974102 -3.867919 -8.674738 -0.09710693 -3.781779 -8.681126 -0.0966835 -3.733328 -8.687853 -0.09611511 -3.695488 -8.697214 -0.09541893 -3.63975 -8.735485 -0.09469223 -4.828107 -8.420681 -0.09882736 -4.249778 -8.412794 -0.09883689 -3.913699 -8.414162 -0.09881019 -3.636077 -8.416725 -0.09874343 -3.411901 -8.420454 -0.09860801 -3.269396 -8.425787 -0.09837722 -3.202203 -8.432297 -0.0980072 -3.165681 -8.439336 -0.09747886 -3.132896 -8.450535 -0.09680366 -4.803923 -8.349543 -0.0986309 -4.193405 -8.343437 -0.09866523 -3.800076 -8.343567 -0.09867668 -3.44422 -8.34428 -0.09867477 -3.131182 -8.345784 -0.09864425 -2.912609 -8.348801 -0.09855461 -2.809553 -8.353425 -0.0983448 -2.763852 -8.359115 -0.0979824 -2.732659 -8.365494 -0.09745025 -4.80083 -8.287399 -0.09683036 -4.184867 -8.283644 -0.0968647 -3.777362 -8.283535 -0.09688186 -3.397972 -8.283672 -0.09689712 -3.049416 -8.284233 -0.09689712 -2.792527 -8.285961 -0.09685897 -2.671393 -8.289288 -0.09671211 -2.621177 -8.293638 -0.09642028 -2.588919 -8.298668 -0.09597206 -4.800748 -8.225028 -0.09343719 -4.18433 -8.223333 -0.09346389 -3.775205 -8.223278 -0.09348106 -3.39265 -8.223339 -0.09350013 -3.037244 -8.223731 -0.09350585 -2.771293 -8.225197 -0.09347724 -2.647367 -8.228243 -0.09334754 -2.596739 -8.232033 -0.09309005 -2.564088 -8.236205 -0.09268951 -4.80078 -8.167484 -0.08429527 -4.18427 -8.167027 -0.08432388 -3.775073 -8.16703 -0.08433914 -3.392403 -8.167087 -0.0843563 -3.036633 -8.16749 -0.08436203 -2.770453 -8.169013 -0.0843296 -2.648005 -8.172153 -0.08420372 -2.598104 -8.175867 -0.08396148 -2.565174 -8.17973 -0.08362579 -4.800514 -8.113774 -0.03348726 -4.184213 -8.113644 -0.03353112 -3.77502 -8.113644 -0.03354454 -3.392381 -8.113702 -0.03355789 -3.036839 -8.114113 -0.03355026 -2.77151 -8.11566 -0.03346443 -2.650652 -8.118826 -0.03324699 -2.601675 -8.122543 -0.03294938 -2.568449 -8.126406 -0.03281593 -4.801889 -8.058109 0.1734218 -4.184172 -8.057989 0.1733741 -3.774982 -8.057979 0.1733589 -3.392354 -8.05802 0.1733608 -3.036925 -8.058359 0.1734676 -2.7718 -8.059652 0.1738376 -2.650518 -8.06241 0.1745108 -2.601099 -8.065938 0.1750373 -2.566653 -8.070082 0.1744785 0.6152819 -11.1997 49.34731 0.4763087 -11.31884 47.32046 0.2886705 -11.19372 49.31867 0.1374685 -11.29081 47.31778 -0.06451606 -11.18763 49.25674 -0.2183568 -11.26226 47.29556 -0.4191171 -11.18202 49.18175 -0.576669 -11.2358 47.25928 -0.7691212 -11.1778 49.11305 -0.9420247 -11.21479 47.21434 -1.148824 -11.17592 49.02579 -1.321217 -11.20235 47.14506 -1.567363 -11.17518 48.91528 -1.697057 -11.19558 47.05837 -2.001602 -11.17457 48.80753 -2.066606 -11.18966 46.97429 -2.441913 -11.17363 48.6941 -2.421968 -11.18163 46.91203 0.7051944 -11.63759 44.94374 0.3403686 -11.56916 44.99866 -0.03103619 -11.4991 45.04771 -0.4005497 -11.43213 45.08582 -0.7775993 -11.37368 45.10554 -1.146681 -11.32988 45.09646 -1.476214 -11.29831 45.07274 -1.791468 -11.26826 45.05107 -2.126265 -11.2318 45.0596 1.20159 -12.11729 42.40301 0.8381037 -12.02588 42.48899 0.4708677 -11.93102 42.57621 0.1058752 -11.83569 42.66362 -0.2654219 -11.74212 42.74679 -0.6231241 -11.65627 42.81783 -0.9382622 -11.58007 42.88185 -1.246896 -11.50239 42.94991 -1.603561 -11.41503 43.04513 1.802164 -12.6454 39.83617 1.455176 -12.54666 39.93334 1.104952 -12.44371 40.03546 0.7617148 -12.33951 40.14058 0.4186565 -12.23366 40.24797 0.08181738 -12.12756 40.35545 -0.2345397 -12.0229 40.46313 -0.5547109 -11.91147 40.57554 -0.9257577 -11.78666 40.69549 2.408202 -13.15987 37.30498 2.088011 -13.06075 37.40495 1.768398 -12.95816 37.51147 1.455953 -12.85451 37.61933 1.146775 -12.74956 37.72826 0.8395577 -12.64201 37.83982 0.5334628 -12.52968 37.95494 0.213423 -12.40747 38.07471 -0.1536453 -12.27029 38.19677 2.960434 -13.64194 34.80014 2.66647 -13.54402 34.89781 2.38091 -13.44487 35.00247 2.101875 -13.34536 35.10794 1.822302 -13.24518 35.21167 1.544813 -13.14134 35.31758 1.249233 -13.03009 35.42323 0.9092618 -12.91105 35.51882 0.5335932 -12.78433 35.60515 3.429 -14.0928 32.29134 3.144329 -13.99355 32.3808 2.868426 -13.89387 32.47746 2.595743 -13.79602 32.57383 2.299587 -13.70094 32.65884 2.017255 -13.60032 32.75215 1.63637 -13.49776 32.81142 1.082103 -13.40273 32.79285 0.5366919 -13.32075 32.73919 3.756823 -14.51939 29.76594 3.458244 -14.4139 29.84243 3.123902 -14.30889 29.91862 2.737045 -14.21562 29.97253 2.212871 -14.14021 29.96694 1.73475 -14.05659 29.98247 0.9511393 -13.9883 29.86708 -0.2926699 -13.95632 29.53397 -1.331951 -13.93896 29.2346 3.879865 -14.96257 27.23455 3.454162 -14.84623 27.25238 2.77847 -14.74701 27.20155 1.894956 -14.6903 27.06212 0.672755 -14.68556 26.77268 -0.3368697 -14.66374 26.56404 -1.645129 -14.65807 26.21177 -3.512425 -14.70014 25.5964 -4.804956 -14.73163 25.2048 3.469867 -15.52627 24.56984 2.588628 -15.42516 24.38376 1.065608 -15.38082 23.9846 -0.6416104 -15.40385 23.5043 -2.558222 -15.493 22.9236 -3.826289 -15.54359 22.60264 -4.819341 -15.57146 22.37852 -6.026194 -15.6169 22.04718 -6.772022 -15.64465 21.91384 1.496227 -16.32186 21.3576 0.153223 -16.29889 20.9681 -1.838185 -16.33973 20.36485 -3.524066 -16.40517 19.88451 -4.929533 -16.48835 19.50877 -5.691327 -16.5317 19.3937 -6.130292 -16.54983 19.40793 -6.615186 -16.56457 19.4063 -6.944431 -16.56409 19.49162 -1.767717 -17.35099 17.6703 -2.758852 -17.38022 17.41507 -3.984097 -17.42638 17.11684 -4.830331 -17.45975 16.98199 -5.422729 -17.48478 16.95305 -5.762815 -17.48919 17.03388 -6.003963 -17.48129 17.16355 -6.254745 -17.4653 17.29806 -6.479642 -17.43111 17.48163 -2.713539 -18.28038 14.96058 -3.425339 -18.33489 14.77359 -3.838697 -18.35615 14.75391 -4.316243 -18.36329 14.76469 -4.646852 -18.35521 14.84926 -4.921346 -18.34055 14.96937 -5.164225 -18.31678 15.1214 -5.401242 -18.29135 15.27992 -5.644923 -18.27508 15.41186 -5.885387 -18.23719 15.59436 -3.455549 -19.09414 12.84243 -3.655881 -19.095 12.90609 -3.86764 -19.07955 13.00313 -4.056409 -19.05722 13.11557 -4.275888 -19.03252 13.23729 -4.526779 -19.00154 13.38037 -4.795133 -18.97522 13.51812 -5.079006 -18.97377 13.59943 -5.364158 -18.95225 13.7299 -3.295736 -19.82143 11.17295 -3.540514 -19.81537 11.21902 -3.72424 -19.80385 11.27856 -3.900899 -19.7916 11.33647 -4.125254 -19.77913 11.39891 -4.392333 -19.76247 11.47748 -4.679068 -19.74765 11.55691 -4.980744 -19.75174 11.59447 -5.291004 -19.74337 11.66371 -2.498993 -20.5653 9.424946 -3.031614 -20.55654 9.451754 -3.445613 -20.54973 9.476702 -3.73387 -20.54492 9.499378 -3.985959 -20.54144 9.518135 -4.255942 -20.53842 9.537907 -4.543558 -20.53405 9.563124 -4.836195 -20.52904 9.592312 -5.134024 -20.531 9.606478 -5.444872 -20.52866 9.632021 -2.508541 -21.23031 7.669472 -2.865733 -21.22922 7.674553 -3.204226 -21.22876 7.678028 -3.546553 -21.22847 7.681423 -3.891372 -21.22806 7.685249 -4.235413 -21.22717 7.691059 -4.580898 -21.22754 7.69437 -4.946553 -21.22716 7.699844 -2.313232 -21.77289 5.863703 -2.691774 -21.77259 5.864744 -3.070935 -21.77227 5.865469 -3.449896 -21.77198 5.865969 -3.828379 -21.77159 5.866899 -4.207645 -21.77127 5.867729 -4.607082 -21.77088 5.869204 -2.346862 -22.06508 4.154921 -2.733198 -22.06258 4.15905 -3.119555 -22.06008 4.162828 -3.505956 -22.05755 4.166618 -3.893322 -22.05492 4.170292 -4.301902 -22.05229 4.173988 -2.422012 -21.87706 2.533438 -2.809164 -21.86707 2.541899 -3.196829 -21.85705 2.550333 -3.585753 -21.84674 2.55854 -3.997582 -21.83654 2.566433 -4.918241 -7.987106 0.8214111 -4.820394 -8.006229 0.5764637 -4.209626 -7.987038 0.8212662 -4.186514 -8.006175 0.5764103 -3.77741 -7.987003 0.8212624 -3.774989 -8.006151 0.5764027 -3.395404 -7.986986 0.821415 -3.392614 -8.006147 0.5764637 -3.047687 -7.987071 0.8220749 -3.038229 -8.006289 0.5768261 -2.78754 -7.987583 0.8237114 -2.773381 -8.00703 0.5778732 -2.653173 -7.989077 0.8259945 -2.647716 -8.008942 0.5795212 -2.592601 -7.992016 0.826994 -2.594705 -8.012074 0.5804215 -2.552862 -7.996881 0.8244209 -2.557547 -8.016724 0.5785809 0.814838 -11.17668 50.53823 0.4990611 -11.17576 50.51537 0.1630624 -11.17482 50.46685 -0.1759476 -11.17395 50.40582 -0.5164986 -11.17327 50.34376 -0.8929696 -11.17303 50.25821 -1.314692 -11.17292 50.15004 -1.767041 -11.17281 50.0392 -2.283892 -11.17265 49.89416 -2.889363 -21.22135 1.039732 -2.500756 -21.24453 1.028406 -3.280152 -21.19785 1.050905 -3.697765 -21.17441 1.062796 2.655298 -21.89019 -0.01995277 3.107971 -22.05034 -0.03033256 3.533921 -22.28449 0.1404075 3.222687 -22.23455 0.1471633 3.461435 -22.13919 -0.03673928 3.812665 -22.30244 0.1357288 3.765758 -22.18961 -0.0414772 4.080649 -22.3088 0.1316184 4.046772 -22.20868 -0.0446701 4.344686 -22.30899 0.127758 4.356305 -22.21172 -0.04665756 4.630077 -22.30679 0.1241035 2.373362 -21.57922 -0.05233567 2.829775 -21.76576 -0.06287384 3.213582 -21.91284 -0.07221603 3.527967 -21.98714 -0.07792091 3.861139 -22.00938 -0.08020401 2.661378 -21.42126 -0.07067298 3.042421 -21.54195 -0.07842063 3.404617 -21.58739 -0.08185768 2.650247 -20.93566 -0.06409263 3.037872 -20.98023 -0.06718254 2.480802 -20.43003 -0.05320358 2.884548 -20.48226 -0.05625718 2.419207 -19.99279 -0.04545778 2.847667 -20.07131 -0.04888337 2.744626 -19.63874 -0.04150009 -2.480411 -13.54981 -0.0964756 -2.424246 -14.7608 -0.09510231 -2.439581 -13.56223 -0.09510231 -2.315778 -14.83028 -0.09196281 -2.596713 -12.26614 -0.09609794 -2.550651 -12.29833 -0.09507369 -2.526471 -12.30034 -0.09383201 -2.408713 -13.56208 -0.09383583 -2.503345 -12.30151 -0.09249305 -2.375028 -13.56402 -0.09244728 -2.4665 -12.32155 -0.091053 -2.300034 -13.60485 -0.0902996 -2.911341 -10.75256 -0.09471702 -2.840479 -10.82839 -0.09378814 -2.814341 -10.84201 -0.09251594 -2.785035 -10.86176 -0.09116554 -2.714931 -10.94252 -0.08996391 -2.593205 -11.09154 -0.08896064 -2.399591 -12.37579 -0.08945083 -2.496809 -11.17136 -0.08776473 -2.338924 -12.40247 -0.08787918 -3.170513 -9.302105 -0.09358024 -3.125759 -9.338926 -0.09243774 -3.098752 -9.35204 -0.09110641 -3.051049 -9.397722 -0.08981323 -2.9342 -9.549124 -0.08883476 -2.749526 -9.801449 -0.08818435 -2.623012 -9.951236 -0.08715629 -2.55123 -9.99672 -0.0857582 -2.41186 -11.19554 -0.08633422 -2.956098 -8.609086 -0.09442138 -2.929236 -8.619732 -0.09322357 -2.905015 -8.627856 -0.09191131 -2.870874 -8.652193 -0.09056663 -2.79685 -8.738224 -0.08937454 -2.679473 -8.89153 -0.08836555 -2.606496 -8.976449 -0.08706283 -2.570821 -8.999302 -0.08549308 -2.533817 -9.019629 -0.083395 -2.464175 -10.05065 -0.08389282 -2.638846 -8.402446 -0.0949974 -2.613048 -8.40971 -0.09388923 -2.587988 -8.417139 -0.09266662 -2.562199 -8.427036 -0.09134864 -2.52698 -8.452488 -0.09000587 -2.477194 -8.50134 -0.08867454 -2.444027 -8.526329 -0.08719825 -2.421052 -8.535644 -0.08560371 -2.39521 -8.545624 -0.08349609 -2.503967 -8.317747 -0.0937252 -2.477345 -8.324625 -0.09270668 -2.451416 -8.331753 -0.09157371 -2.426211 -8.339224 -0.09034156 -2.400792 -8.348381 -0.08902549 -2.373208 -8.361942 -0.08765411 -2.349343 -8.370968 -0.08620452 -2.327045 -8.378413 -0.08468055 -2.300117 -8.388176 -0.08265113 -2.480163 -8.25164 -0.09065818 -2.453768 -8.257736 -0.08973121 -2.428005 -8.264198 -0.08870124 -2.40292 -8.271061 -0.08757209 -2.378528 -8.278182 -0.08636474 -2.354563 -8.285753 -0.0850811 -2.33151 -8.292994 -0.08374023 -2.309077 -8.300253 -0.08232688 -2.481974 -8.193218 -0.08187294 -2.456213 -8.198548 -0.08106231 -2.431005 -8.204332 -0.0801773 -2.406375 -8.210577 -0.07923698 -2.382356 -8.217117 -0.07819366 -2.358964 -8.223839 -0.07703971 -2.336188 -8.230761 -0.07583808 -2.313988 -8.237833 -0.07458686 -2.484446 -8.13957 -0.03170776 -2.459225 -8.144596 -0.03109741 -2.434496 -8.150078 -0.03067016 -2.410236 -8.156103 -0.03036308 -2.386669 -8.162455 -0.02977943 -2.363886 -8.169049 -0.0287857 -2.341701 -8.175915 -0.02779763 -2.320001 -8.182979 -0.02692222 -2.47867 -8.085573 0.1734561 -2.453266 -8.091614 0.1734714 -2.428308 -8.098324 0.1722488 -2.4038 -8.105665 0.170351 -2.38052 -8.113129 0.1694164 -2.358754 -8.120628 0.169897 -2.337835 -8.12851 0.1703147 -2.317314 -8.136837 0.1699714 4.410289 -11.35174 49.80249 4.396636 -11.74157 46.99814 3.91375 -11.3412 49.82618 3.918632 -11.71219 46.99257 3.576938 -11.32581 49.91289 3.560763 -11.67274 47.05892 3.261417 -11.30742 50.01762 3.217235 -11.62771 47.14845 2.952571 -11.28954 50.11861 2.8827 -11.58356 47.23067 2.64881 -11.27294 50.19925 2.551465 -11.54072 47.29499 2.334027 -11.25618 50.21009 2.211627 -11.49627 47.34732 1.977154 -11.23742 50.02783 1.846416 -11.44809 47.36741 1.588119 -11.22043 49.6588 1.467913 -11.40311 47.32793 4.731654 -12.32084 44.2483 4.275052 -12.28281 44.22295 3.912491 -12.22473 44.29507 3.559804 -12.16177 44.38348 3.211904 -12.09949 44.46209 2.858676 -12.0363 44.53097 2.497764 -11.96924 44.60565 2.127883 -11.8973 44.69357 1.756871 -11.82623 44.77502 5.286054 -12.94935 41.6134 4.804568 -12.90892 41.55329 4.433127 -12.8395 41.62553 4.073715 -12.76627 41.71072 3.71711 -12.69216 41.79166 3.356099 -12.61559 41.87349 2.993994 -12.53587 41.96323 2.633723 -12.45339 42.05985 2.274512 -12.37044 42.15542 5.935037 -13.60101 39.02812 5.403451 -13.52055 38.97865 5.014232 -13.43799 39.05069 4.643348 -13.35537 39.1336 4.274352 -13.27106 39.21458 3.906906 -13.18505 39.29764 3.545647 -13.09805 39.38607 3.192041 -13.01034 39.4767 2.842837 -12.922 39.56703 6.636844 -14.25037 36.4633 6.011067 -14.10355 36.47641 5.598093 -14.00275 36.5582 5.213078 -13.90929 36.63817 4.827642 -13.81474 36.71252 4.449505 -13.72031 36.7877 4.085826 -13.62747 36.86749 3.736601 -13.53589 36.95066 3.396295 -13.44393 37.03624 7.168005 -14.83539 34.03702 6.515514 -14.64621 34.04833 6.093833 -14.53072 34.11456 5.69619 -14.42457 34.17972 5.297778 -14.31825 34.24044 4.914974 -14.21551 34.30585 4.555865 -14.11811 34.37873 4.217041 -14.02411 34.45659 3.890396 -13.92996 34.53861 7.456176 -15.41849 31.69676 6.846418 -15.19119 31.68535 6.441992 -15.05394 31.72099 6.056833 -14.92947 31.75976 5.670809 -14.80717 31.79798 5.302729 -14.6934 31.84656 4.957887 -14.58936 31.90714 4.630221 -14.49011 31.97474 4.315636 -14.39082 32.04922 7.576628 -16.04449 29.44701 7.025723 -15.78925 29.42714 6.660671 -15.62989 29.42722 6.313016 -15.48291 29.43073 5.960229 -15.33866 29.43529 5.617912 -15.20523 29.45251 5.290688 -15.08403 29.48527 4.973024 -14.96853 29.52778 4.660661 -14.85253 29.57959 7.653543 -16.67749 27.2506 7.141354 -16.41696 27.2224 6.804744 -16.25025 27.20066 6.488207 -16.09447 27.18502 6.167575 -15.93914 27.17007 5.849592 -15.78811 27.16166 5.537052 -15.64304 27.16212 5.224834 -15.50127 27.16612 4.904548 -15.35806 27.17737 7.736491 -17.27822 25.0326 7.252268 -17.02624 24.99616 6.930912 -16.86212 24.96654 6.624686 -16.70544 24.94179 6.31483 -16.54625 24.91806 6.005048 -16.38539 24.89982 5.697027 -16.22665 24.88398 5.378326 -16.07438 24.85611 5.029396 -15.92313 24.8369 7.796394 -17.817 22.76239 7.325362 -17.57153 22.71712 7.009737 -17.40876 22.68511 6.70226 -17.25078 22.65427 6.389866 -17.09007 22.62435 6.072776 -16.929 22.59437 5.730892 -16.77848 22.52681 5.277144 -16.65087 22.39298 4.652183 -16.5279 22.30132 7.666968 -18.27254 20.36716 7.152347 -18.03322 20.2824 6.82706 -17.87483 20.24402 6.516458 -17.72259 20.2105 6.192214 -17.57065 20.17188 5.828266 -17.42892 20.08732 5.320109 -17.32926 19.82846 4.3634 -17.29427 19.38762 2.943858 -17.26393 19.11244 6.9579 -18.66848 17.5447 6.277681 -18.47002 17.30917 5.911643 -18.3514 17.22933 5.590545 -18.24026 17.18429 5.230091 -18.1339 17.12294 4.775043 -18.05073 16.95734 4.022467 -18.03726 16.50404 2.42757 -18.11605 15.82466 5.633691 -19.15184 14.2511 4.759878 -19.03919 13.83406 4.339937 -18.99873 13.70199 4.007888 -18.96448 13.65237 3.634163 -18.93285 13.60735 3.169555 -18.91034 13.52061 2.399537 -18.91968 13.29319 4.537554 -19.81173 11.54314 3.755679 -19.75797 11.25033 3.373064 -19.75348 11.17857 3.048451 -19.75341 11.15435 2.674501 -19.75508 11.13259 3.475938 -20.55506 9.481697 2.764475 -20.53676 9.381937 2.343521 -20.53913 9.364418 3.165861 -21.23746 7.663626 2.511936 -21.23232 7.640364 3.154431 -21.78629 5.849045 2.524035 -21.78442 5.846533 3.440333 -22.16488 4.04954 2.828628 -22.16131 4.064077 4.060542 -22.32926 2.303587 3.490139 -22.32345 2.333818 2.426132 -22.15981 4.06983 3.122411 -22.32109 2.347116 -2.455482 -8.019227 0.8151283 -2.462937 -8.036926 0.5730286 -2.428197 -8.028725 0.8120136 -2.436397 -8.045289 0.5715523 -2.401428 -8.039793 0.8048821 -2.410265 -8.054937 0.5669232 -2.375652 -8.0517 0.7959976 -2.384813 -8.065411 0.5607853 -2.352551 -8.063076 0.7897148 -2.361597 -8.075552 0.5567913 -2.332544 -8.073683 0.786974 -2.341084 -8.085157 0.55583 -2.314132 -8.084675 0.7842503 -2.321936 -8.095167 0.5548115 4.650704 -11.21878 51.78007 4.148651 -11.21607 51.89867 3.819706 -11.21154 52.04767 3.523926 -11.20599 52.2026 3.233074 -11.20062 52.35163 2.94097 -11.19581 52.45698 2.624793 -11.19108 52.39079 2.249525 -11.18554 51.96311 1.831259 -11.18054 51.26119 4.398756 -22.35009 0.814024 4.097461 -22.35103 0.822176 2.778021 -22.31918 2.357981 3.81445 -22.3518 0.829628 2.433489 -22.3172 2.369081 3.530663 -22.35195 0.8371792 2.85118 -22.14377 0.1573791 2.958698 -22.34451 0.8533383 2.65737 -22.32688 0.8629875 3.245843 -22.35091 0.8449478 -2.303095 -8.106131 0.5517426 19.02963 -18.9675 28.35232 19.89625 -19.3423 27.54176 16.40124 -15.90285 32.13352 16.42977 -17.84309 30.78401 22.46849 -20.04267 25.42493 27.48709 -20.93374 21.70521 19.71293 -18.00554 27.81631 17.29639 -18.21789 29.97345 17.22916 -16.61773 31.05422 13.1055 -21.9384 -0.06017106 12.95284 -22.08302 0.07217216 13.28933 -21.68946 -0.08676528 13.45204 -21.21029 -0.09583282 13.57974 -20.48412 -0.0987358 13.72442 -19.74916 -0.09902191 13.96487 -19.17331 -0.09805679 14.34969 -18.74178 -0.09590148 14.84164 -18.37272 -0.09303092 15.28347 -18.06146 -0.08945465 15.6136 -17.78997 -0.08535385 15.90415 -17.56969 -0.0808258 16.14275 -17.36513 -0.07612991 16.19569 -17.10441 -0.07096672 16.02343 -16.72519 -0.0652008 15.98273 -16.52165 -0.06039232 16.03262 -16.44404 -0.05587387 16.05326 -16.39391 -0.05062866 15.81997 -16.25967 -0.04203599 9.053809 -13.28795 0.03221696 14.681 -15.74205 -0.01840394 5.829616 -11.82963 0.1771736 12.59357 -14.80939 0.03242874 14.44349 -14.13351 35.42015 14.19011 -11.41911 39.76467 15.43943 -17.65018 31.77589 16.42991 -20.2984 29.32496 17.00598 -21.52446 27.40424 17.08874 -22.18575 25.49136 16.95081 -22.67385 23.40665 16.76632 -23.05317 21.22178 16.58183 -23.31371 18.99688 16.41219 -23.43986 16.75757 16.27842 -23.42573 14.50823 16.17368 -23.28232 12.24839 16.05705 -23.02245 9.974503 15.76393 -22.67712 7.578558 15.12144 -22.3672 4.971643 14.32036 -22.19112 2.44319 13.90624 -22.05604 0.7279511 15.34528 -22.11644 2.657686 16.18921 -22.43334 5.218718 16.72788 -22.85342 7.73288 16.91181 -23.25304 10.04208 16.97631 -23.54401 12.29015 17.05012 -23.7103 14.54908 17.16915 -23.74956 16.80979 17.33792 -23.65141 19.0589 17.53183 -23.41693 21.2819 17.70975 -23.04938 23.44658 17.80599 -22.55414 25.4702 17.62578 -21.91121 27.23871 17.06447 -20.94379 28.76166 16.27959 -19.50962 30.20485 14.12045 -21.75256 -0.05609512 13.91446 -21.9198 0.08436203 14.39648 -21.50141 -0.08366966 14.66352 -21.05504 -0.09394454 14.85648 -20.33344 -0.09835243 15.00865 -19.49133 -0.09954261 15.23011 -18.75279 -0.09930419 15.59653 -18.23857 -0.09807777 16.0319 -17.89336 -0.0958271 16.38619 -17.6578 -0.0925579 16.62809 -17.4868 -0.08849143 16.79745 -17.35424 -0.08395004 16.93244 -17.24141 -0.07919502 17.01928 -17.14263 -0.07436752 17.04974 -17.0331 -0.06952095 17.10294 -16.96033 -0.06503105 17.1617 -16.90501 -0.06069374 17.2054 -16.85999 -0.0561161 17.19008 -16.8118 -0.05072212 16.88979 -16.66281 -0.041933 16.07426 -16.30368 -0.02459907 11.55439 -10.40809 43.95323 18.71143 -16.64527 28.79917 18.88501 -17.54294 28.89561 18.05709 -17.08033 29.97492 16.71938 -16.34073 30.92833 17.3834 -16.27406 30.80506 18.04741 -16.45967 29.50889 14.93293 -14.63891 34.59849 15.9118 -15.64972 32.95518 15.42236 -15.14431 33.77684 14.92929 -13.64353 34.38561 13.62173 -10.29624 41.92503 2.3 -10.21293 0.4570122 2.3 -10.24864 0.2026863 -2.3 -20.70844 9.047554 -2.3 -20.56779 9.415558 -2.3 -20.23535 10.1717 -2.3 -18.89005 13.35599 -2.147028 -18.25246 15.11031 -0.388123 -17.86278 16.55881 2.3 -10.27475 0.04191201 2.3 -10.28158 0.03198426 2.3 -10.30966 -0.01953506 2.3 -10.35877 -0.03488343 2.3 -10.4575 -0.04093742 2.3 -10.76475 -0.04533195 2.3 -11.58505 -0.05311012 2.3 -12.88048 -0.06454467 2.3 -13.97594 -0.07115173 2.3 -14.94092 -0.07268333 2.3 -16.17518 -0.06731224 2.3 -16.21734 -0.06696891 2.3 -17.80485 -0.05178445 2.3 -18.25087 -0.04749673 -2.3 -16.65676 -0.0826435 -2.3 -16.22536 -0.08781623 -2.3 -20.61697 0.09319686 -2.3 -20.82688 0.3003998 -2.3 -20.46242 0.0261116 -2.3 -20.41949 0.01731872 -2.3 -20.29147 -0.008405685 -2.3 -20.0054 -0.02374833 -2.3 -19.97506 -0.02406692 -2.3 -19.48351 -0.02844238 -2.3 -18.68578 -0.04034233 -2.3 -18.38044 -0.04686921 -2.3 -17.38351 -0.07122611 -2.3 -17.3085 -0.0731182 -2.3 -21.07469 8.08082 -2.3 -21.23178 7.665386 -2.3 -21.42671 7.015652 -2.3 -21.77291 5.863646 -2.3 -21.78396 5.799372 -2.3 -22.06538 4.154293 -2.3 -22.03833 3.909643 -2.3 -21.88029 2.530619 -2.3 -21.63625 1.93392 -2.3 -21.25673 1.022671 2.3 -21.96771 0.1735153 2.3 -21.96086 0.1685218 2.323315 -21.97548 0.1728229 2.3 -21.79805 0.03385728 2.3 -21.75486 -0.01023674 2.3 -21.65995 -0.0283432 2.3 -21.5484 -0.05071449 2.3 -21.52119 -0.0520153 2.3 -21.32151 -0.05995553 2.3 -21.27208 -0.06207841 2.3 -20.90846 -0.06006234 2.3 -20.85813 -0.05939286 2.3 -20.3997 -0.05151551 2.3 -19.97032 -0.04436677 2.3 -19.69654 -0.04226875 2.3 -19.49651 -0.04009056 -2.3 -16.01799 -0.08953475 2.3 -19.01131 -0.04117959 2.3 -18.92367 -0.04122918 -2.3 -15.46472 -0.0907135 -2.3 -14.88234 -0.09150314 -2.3 -14.83636 -0.0915699 -2.3 -14.37952 -0.09140586 -2.3 -13.98672 -0.091053 -2.3 -13.60497 -0.0902996 -2.3 -13.60487 -0.0902996 -2.3 -12.9122 -0.08848571 -2.3 -12.56441 -0.08746337 -2.3 -12.42203 -0.08716392 -2.3 -11.94359 -0.08598518 -2.3 -11.2541 -0.08466148 -2.3 -11.14624 -0.08434867 -2.3 -10.17288 -0.08256721 -2.3 -9.178707 -0.07881355 -2.3 -8.594099 -0.07999992 -2.3 -8.388229 -0.08264541 -2.3 -8.303503 -0.08167076 -2.3 -8.387676 -0.08263587 -2.3 -8.242856 -0.07360839 -2.3 -8.190367 -0.02579689 -2.3 -8.144541 0.1696681 0.9304676 -17.95517 16.39576 1.801134 -18.13516 15.73179 2.083319 -18.29332 15.23535 2.3 -18.92332 13.27265 -2.3 -19.03913 12.91042 2.3 -19.75823 11.11678 2.3 -19.63355 11.46788 2.3 -18.99278 13.10283 -2.3 -19.81462 11.10845 2.3 -20.53952 9.36343 2.3 -20.29354 9.923298 2.3 -20.01913 10.53666 2.3 -20.65596 9.073647 2.3 -21.23292 7.638298 2.3 -21.78436 5.846285 2.3 -22.01129 4.772398 2.3 -22.15935 4.071531 2.3 -22.21418 3.479506 2.3 -22.2893 2.667013 2.3 -22.31648 2.373568 -2.3 -8.102192 0.649538 -2.3 -8.108136 0.5509224 2.3 -22.32185 2.099318 2.3 -22.32789 1.687456 2.3 -22.32276 1.301071 2.3 -22.27419 0.8747521 2.3 -22.14586 0.5769501 -2.409708 -8.150076 16.52644 -1.232281 -7.982413 16.50328 -0.05485385 -7.814751 16.48011 1.122573 -7.647089 16.45695 2.005643 -7.521342 16.43958 2.3 -7.479426 16.43379 -2.393779 -8.139177 13.90274 -2.377849 -8.128275 11.27904 -2.36192 -8.117376 8.655344 -2.345991 -8.106475 6.031647 -2.330061 -8.095577 3.407948 -2.303533 -18.43139 2.094025 -2.307066 -14.98248 1.657434 -2.310599 -11.53358 1.220842 2.3 -8.390596 11.10819 2.3 -9.757349 3.119806 18.16301 -18.5927 29.16289 17.42473 -15.84954 30.68022 16.74241 -15.88508 31.64909 17.08357 -15.86731 31.16465 17.76589 -15.83177 30.19578 15.96509 -15.05381 32.31353 15.91996 -14.62929 32.65127 15.29728 -14.20836 33.82259 15.66526 -14.77319 33.25957 16.03325 -15.33802 32.69655 15.51678 -14.54549 33.69281 15.2108 -14.27143 33.69872 15.49232 -14.89933 33.01183 15.77384 -15.52723 32.32494 14.1925 -10.59738 39.42518 14.93168 -12.8218 34.04613 15.64029 -14.15519 33.42311 16.52476 -15.51255 31.86383 15.63393 -14.17591 33.42311 + + + + + + + + + + -0.2765447 -0.592944 0.7562676 -0.2212657 -0.6100217 0.7608647 0.8747938 -0.2989369 0.3812777 0.8968463 -0.2822684 0.3405752 0.1199291 0.9925267 0.02253621 -0.5501472 -0.6272987 0.551212 0.8536118 0.2229926 0.4707667 0.7894355 0.3702982 0.4895619 0.1710757 -0.9322445 0.3188313 0.1746811 -0.9329804 0.3146972 0.2767118 0.9606186 0.02534812 0.26317 0.9632382 0.0539782 0.2677208 0.960629 0.07428061 0.24571 0.962623 0.113946 0.247098 0.960903 0.1249321 0.3688484 -0.8658277 0.3380728 0.4026185 -0.8445642 0.3530011 0.3081951 -0.8786106 0.3647731 0.7923508 -0.4863699 0.3682725 0.7305727 -0.5583339 0.393099 0.9395656 -0.1465485 0.3094192 0.9284095 0.290232 0.2319945 0.9281899 0.2916527 0.2310892 0.6097095 0.4163729 0.6744538 0.4500837 -0.62959 0.633278 0.5276619 -0.5684976 0.6311763 0.5146104 -0.5832961 0.6284441 0.6990593 0.2892779 0.6539376 0.6960274 0.2585815 0.669837 0.7332832 0.3930132 0.5548301 0.5154359 -0.6393473 0.5705796 0.7147701 -0.4432616 0.5409463 0.5037135 -0.691259 0.5181059 0.6268956 -0.5820157 0.5179378 0.5468434 -0.6432543 0.5358977 0.8545949 0.2361555 0.4624913 0.873519 0.325152 0.3622716 0.7715808 0.6347715 0.04157382 0.1448656 -0.9397483 0.3096565 0.1440282 -0.9399664 0.3093851 0.1438872 -0.9399994 0.3093506 0.1437226 -0.9400304 0.3093326 0.143529 -0.9400593 0.3093347 0.1433919 -0.9400717 0.3093608 0.1033962 -0.9394608 0.3266844 0.4052432 0.8371916 0.3672715 0.4044128 0.8537445 0.3279801 0.4530757 0.8312953 0.3219794 0.4888515 0.83662 0.2471663 0.490127 0.8324387 0.2584985 0.5333662 0.8204041 0.2060525 0.5503033 0.8208833 0.1526995 0.5477446 0.8253551 0.1369855 0.5793745 0.8099979 0.0907123 0.5819871 0.8114485 0.05331581 0.5820926 0.8113842 0.05314046 0.638908 0.7680379 -0.04375588 0.5823468 0.811744 0.04409205 -0.6297532 -0.6157569 0.4735549 -0.6271243 -0.611812 0.4820802 -0.6740888 -0.6303579 0.3850367 -0.7233219 -0.6162514 0.3115118 -0.7775397 -0.5790786 0.2451533 -0.6944345 -0.6441223 0.3207294 1 0 0 1 4.34386e-5 -4.58585e-5 0.1012165 0.9936186 0.0497722 0.2418743 0.9669437 -0.08072596 0.3517704 0.8901444 -0.2896565 0.3195886 0.9434149 -0.08849561 0.3643614 0.9312378 0.006073713 0.4288724 0.9010857 -0.06413435 0.3415963 0.9305972 -0.1315324 0.3586348 0.9302843 -0.07715153 0.4497634 0.8931341 0.00495392 0.4393292 0.8979347 0.02652245 0.5673806 0.8141528 -0.1234284 0.5424702 0.8392283 -0.03771001 0.1955646 -0.8704735 0.4516973 0.2745289 -0.7721596 0.5730651 0.30523 -0.6570816 0.6892594 0.9903779 0.1327791 -0.03900569 0.9073733 0.4119871 0.08330959 0.9103984 0.3720177 0.1810463 0.8286002 0.5490756 -0.1092601 0.7531617 0.6424485 -0.1414474 0.7841851 0.6195226 -0.03529453 0.9000437 -0.3413186 0.2709667 0.8059368 -0.5302625 0.2632254 0.8074841 -0.456075 0.3741193 -0.2270628 -0.8699187 0.4378174 0.8582314 -0.4431294 0.2589889 0.9197093 -0.3618722 0.1522612 0.8714857 -0.43735 0.2218962 0.8124201 -0.558736 0.1666972 -0.2034402 -0.8764481 0.4364066 0.2270973 0.9730863 -0.03911411 0.2774356 0.9607216 0.006598591 0.2238269 0.9730694 -0.05511504 0.2000879 0.979775 0.002411663 0.188751 0.9813426 -0.03660368 0.266314 0.9637085 -0.01851809 0.2754487 0.9612818 -0.008094966 -0.2649554 -0.9269976 0.2654701 -0.2992177 -0.9272771 0.2250025 -0.2998428 -0.9280345 0.2210121 -0.3246496 -0.9274777 0.1854399 -0.3248428 -0.9279554 0.1826907 -0.3430572 -0.9276227 0.1477428 -0.3430489 -0.9279018 0.145999 -0.3559873 -0.9277255 0.1122432 -0.3559249 -0.9278639 0.1112928 0.9206781 0.3750267 -0.1081981 -0.6946316 -0.6997506 0.1668416 -0.19265 -0.8635104 0.4660857 0.1259086 -0.5479855 0.8269576 0.1832863 -0.6922962 0.6979486 0.2395898 -0.7246649 0.6461096 0.329984 -0.7194396 0.6111606 0.0436325 -0.7846593 0.61839 -0.1494628 -0.8515222 0.5025644 -0.3957171 -0.9000052 0.1827535 -0.4030994 -0.9021142 0.1539512 -0.3804669 -0.9247204 -0.01172095 0.249118 -0.6247054 0.7400563 0.3378812 -0.8061528 0.4857512 0.7484977 -0.587597 0.3073778 0.4964767 -0.681148 0.538097 0.9643661 -0.1841073 0.1900072 0.9985206 -0.05405414 0.005904197 0.9406744 -0.09921461 0.3244816 0.9400418 -0.0905314 0.3288244 0.4868053 -0.5134391 0.706683 0.8262358 -0.387472 0.4089009 -0.366611 -0.9272932 0.07565551 0.8761611 -0.1649724 0.4529082 -0.3647385 -0.9277935 0.07851946 0.2001894 -0.5680657 0.7982641 0.178703 -0.9140027 0.3642312 -0.1870661 -0.7481036 0.6366689 0.8344711 -0.2209006 0.5048376 0.8941505 -0.2304474 0.383913 0.9409714 0.3361849 -0.03940296 0.9844915 0.1730105 -0.02904826 0.9969031 0.06551212 -0.04350125 0.9905535 0.1364798 -0.01331132 0.9999344 0.005161762 0.01022672 -0.704903 -0.694278 0.1452239 0.9614039 0.2549173 0.103537 0.9998169 0.002561151 0.01896607 0.9902074 0.1392088 -0.01050025 0.9922795 0.1211506 -0.02653324 0.7042478 -0.06135392 0.7072983 0.7239662 -0.08034622 0.6851405 0.6983415 -0.06705236 0.7126172 0.7075442 -0.1746289 0.6847526 0.6875666 -0.2029372 0.6971863 0.6896808 -0.3566934 0.6301669 0.6601456 -0.2899676 0.6929116 0.7391219 -0.2969443 0.6045851 0.6596153 -0.2923738 0.6924054 0.7135636 -0.4679438 0.5213978 0.5224373 -0.7449324 0.4148916 0.5623661 -0.6221827 0.5446405 0.5389441 -0.639762 0.5479452 -0.1650034 -0.6948305 0.699989 -0.1721696 -0.7020143 0.691038 -0.296573 -0.6659904 0.6844716 -0.3183929 -0.6728949 0.6677113 -0.4357246 -0.6285604 0.6442484 -0.4550653 -0.6281802 0.6311144 -0.6628967 -0.375903 0.6475067 -0.5342018 -0.5139489 0.6711819 -0.4991679 -0.6101915 0.6152218 -0.6978044 -0.07751291 0.712082 -0.9061297 -0.312401 -0.2851921 -0.7172607 -0.1574011 0.6787946 -0.5739948 -0.07080996 0.8157917 -0.6710363 -0.1832849 0.7184129 -0.6809133 -0.2819241 0.6759259 -0.6374456 -0.3846918 0.6675892 -0.7220285 -0.4327786 0.539794 0 -1 0 0.1151525 0.9931564 -0.0194981 0.1239584 0.9922872 -6.71187e-4 -0.07000845 0.9917712 -0.1071863 -0.0679205 0.991501 -0.1109617 -0.04278165 0.9915737 -0.1222763 -0.04209768 0.9915069 -0.1230525 -0.01461929 0.991562 -0.1288068 -0.01424235 0.9915308 -0.1290888 0.01422005 0.9915563 -0.1288955 0.01463288 0.9915259 -0.1290828 0.04209464 0.9915073 -0.1230505 0.04277229 0.9915734 -0.1222823 0.06837445 0.9914934 -0.1107522 0.2103148 0.971813 -0.1065237 0.04527235 0.9962331 -0.07396119 -0.1653153 0.9857093 -0.03237706 -0.1740422 0.9846468 -0.01341545 0.1215367 -0.4375811 0.8909274 -0.7823969 -0.2745542 0.5589948 0.6407125 -0.1897284 0.7439696 0.4665691 -0.1700204 0.8679898 -0.8757793 -0.119269 0.4677453 -0.9418951 -0.02902966 0.3346503 -0.9712265 0.01020675 0.237939 -0.7445436 -0.1339645 0.6539943 -0.3530704 -0.2099543 0.9117349 0.1107715 -5.49711e-6 0.993846 0.5561744 -0.07181984 0.8279566 0.3572554 0.1461067 0.9225082 0.7510635 0.02514988 0.6597508 0.9710677 -0.02063882 0.2379112 0.8484069 -0.1308469 0.5129181 0.8678372 -0.1354736 0.4780225 -0.404849 -0.2260419 0.8860036 -0.7133229 -0.06060427 0.6982102 -0.5534498 -0.1223001 0.8238543 -0.1084439 -0.2059159 0.9725424 -0.2137923 -0.3760504 0.901598 0.7823921 -0.2746518 0.5589537 -0.01554942 0.9904477 -0.13701 0.015531 0.9904448 -0.1370324 -0.09152901 -0.9255648 0.3673585 -0.09961354 -0.9288848 0.3567215 -0.1623421 -0.926142 0.3404498 -0.9997834 -0.01466304 0.01477038 0.9470609 -0.1894142 -0.259226 0.7275759 1.10885e-6 0.6860272 0.7263351 -6.47436e-5 0.6873409 0.6954037 3.81418e-4 0.7186192 0.7153806 0.002266287 0.6987314 0.6999015 4.60437e-6 0.7142395 0.6315545 -0.002502381 0.7753275 0.6148212 -0.006633102 0.7886387 0.5668371 0.001422345 0.8238286 0.4715674 0.008823573 0.8817859 0.4264566 -0.001268327 0.9045072 0.4857828 -0.001645684 0.874078 0.4918568 0 0.8706762 0.4415683 -0.03337788 0.8966066 0.4167242 -0.0606988 0.9070042 0.4558038 -5.24582e-4 0.8900801 0.3554629 7.62319e-5 0.9346904 0.3920079 0.002701163 0.9199579 0.3657843 0.03911012 0.9298776 0.3227268 -0.009053826 0.9464489 0.2724103 -0.04837638 0.9609643 0.280018 -0.03618806 0.9593124 0.1562021 0.02802336 0.9873275 0.09442484 -0.04775995 0.9943857 0 0.03383988 0.9994273 -0.09442526 -0.04775947 0.9943857 -0.1562023 0.02802342 0.9873275 -0.2684333 -0.03007227 0.9628288 -0.3746126 -0.1566135 0.9138587 -0.2801765 -0.0140683 0.9598454 -0.3741351 0.002495288 0.9273709 -0.4835733 0 0.875304 -0.4715966 0.008808255 0.8817704 -0.4280529 -0.01026421 0.9036955 -0.4896452 -0.001503586 0.8719205 -0.4556709 -0.02415591 0.8898205 -0.5389025 3.44034e-4 0.8423681 -0.655739 -0.02015393 0.7547186 -0.614835 -0.003782629 0.7886468 -0.6950597 3.7897e-4 0.718952 -0.7273731 -8.2096e-5 0.6862422 -0.7262937 0 0.6873846 0 1 0 0 1 -2.5572e-6 0 1 -1.3574e-6 0 1 1.46475e-6 0 -1 6.31455e-6 0 -1 3.61024e-6 -0.3275545 0 0.9448324 -0.3275169 3.45434e-6 0.9448454 -0.07958412 -6.9301e-6 0.9968282 -0.07951229 6.93082e-6 0.9968339 0.1735915 1.02028e-6 0.9848178 0.1736306 5.96466e-6 0.9848108 0.4153032 -4.7109e-7 0.9096831 0.4152941 -1.25627e-6 0.9096872 0.6303031 -6.90967e-6 0.7763491 0.6303395 -6.28128e-7 0.7763196 0.8050383 -7.53443e-6 0.593223 0.80509 7.21915e-6 0.5931527 0.9283255 -6.89107e-6 0.3717684 0.9283549 6.26373e-6 0.3716952 0.991964 -1.3191e-5 0.1265206 0.9919742 0 0.1264407 0.3275484 0 0.9448344 0.3275125 0 0.9448469 0.07960563 0 0.9968265 -0.1735881 0 0.9848184 -0.173588 0 0.9848183 -0.41532 0 0.9096754 -0.4152866 0 0.9096907 -0.6303395 0 0.7763196 -0.6302911 0 0.776359 -0.8050481 0 0.5932095 -0.8050481 0 0.5932096 -0.9283191 0 0.3717847 -0.9919632 0 0.1265275 -0.9919645 0 0.1265174 0.3232119 0.1619936 0.9323584 0.1810335 0.3289422 0.9268355 0.1843681 0.3297118 0.9259042 0.07847696 0.1685387 0.9825661 -0.1594551 0.3951821 0.9046575 -0.04530203 0.9315407 0.3608044 -0.1745894 0.8633992 0.4733501 -0.4005755 0.264048 0.8773927 -0.3237485 0.351995 0.8782292 -0.2226087 0.9204905 0.3211581 -0.5800568 0.3912647 0.7144551 -0.7805817 0.2446395 0.5751904 -0.6942732 0.3619239 0.6220899 -0.2604741 0.9344743 0.2427163 -0.270695 0.9316082 0.2425499 -0.3349845 0.921014 0.1987929 -0.8562537 0.3863095 0.342921 -0.323743 0.9400021 0.1076408 -0.3640642 0.9269705 0.09045988 -0.9669691 0.2230696 0.1233315 -0.9754664 0.1940395 0.1039909 -0.8142951 0.5440515 0.2023155 -0.5472676 0.8189945 -0.1724712 -0.195034 0.9805733 0.02092307 -0.3232576 0.1610887 0.9324994 -0.07827657 0.1788812 0.9807519 -0.1834009 0.3286097 0.9264879 -0.1848244 0.3284257 0.9262702 0.1593246 0.3968471 0.9039514 0.3865851 0.3653581 0.8467972 0.3285694 0.3081343 0.892802 0.03930568 0.9309104 0.3631267 0.1814492 0.8602719 0.4764541 0.2225837 0.9205059 0.3211317 0.5802216 0.3906934 0.714634 0.2665995 0.9312447 0.2484114 0.2664144 0.9335919 0.2396447 0.7469069 0.3730877 0.5503961 0.7082587 0.3041164 0.6370894 0.3350256 0.9209918 0.1988267 0.8564051 0.3859346 0.3429648 0.356754 0.9266383 0.1186102 0.3222697 0.9460166 0.0345661 0.1943072 0.9768199 -0.08982032 0.5503162 0.8236199 0.1371222 0.924662 0.303178 0.2303984 0.8166602 0.5456547 -0.1879558 0.9731981 0.1935952 0.1241225 0.3273745 0.03110176 0.9443827 0.07822102 -0.184389 0.9797359 0.02501565 -0.1189278 0.9925877 -0.1666516 -0.279798 0.9454842 -0.1961248 -0.2753196 0.9411346 -0.3827014 -0.3884598 0.8382354 -0.6123525 -0.2370137 0.7542208 -0.646665 -0.3296771 0.6878498 -0.1074152 -0.9363859 0.3341308 -0.2087553 -0.9238804 0.3207279 -0.2956834 -0.8938331 0.3370961 -0.3452979 -0.8654572 0.3629782 -0.3200486 -0.9223811 0.2162918 -0.7414517 -0.3895511 0.546351 -0.3466377 -0.924839 0.1565729 -0.336254 -0.9377017 0.08745783 -0.2987635 -0.9539889 0.02541112 -0.1945869 -0.9782517 -0.07183051 -0.5490832 -0.8217217 0.1525814 -0.9094707 -0.2004849 0.3642373 -0.902157 -0.3510898 0.2506968 -0.8166332 -0.5456861 -0.1879811 -0.9732018 -0.1935746 0.1241261 0.5576342 7.51469e-7 0.8300868 0.557638 5.00983e-7 0.8300844 0.1108124 1.87874e-7 0.9938414 0.1107438 0 0.993849 -0.3611416 0 0.932511 -0.7513242 0 0.6599335 -0.7512963 1.25245e-6 0.6599652 -0.9712766 5.00997e-7 0.2379534 -0.9712766 5.00997e-7 0.2379534 -0.5576312 0 0.8300889 -0.557637 -1.56557e-7 0.8300849 -0.1108707 -1.6125e-6 0.9938349 -0.1108075 2.16828e-6 0.9938419 0.3611434 8.61033e-7 0.9325104 0.3611431 0 0.9325105 0.7512819 -1.22102e-6 0.6599816 0.7512957 0 0.6599659 0.9712764 0 0.2379541 0.9712764 0 0.2379544 -0.5202021 -0.2587857 0.8138917 -0.5562564 -0.06917119 0.8281269 -0.5763393 -0.1463345 0.8040021 -0.5728638 -0.1417655 0.8072978 -0.5029384 -0.1015877 0.8583315 -0.5349441 -0.169668 0.8276761 -0.3679282 -0.4636242 0.8060282 -0.4224231 -0.4853736 0.7654877 -0.2873646 -0.5379143 0.7925087 -0.210866 -0.4659557 0.8593142 -0.1089364 -0.1910601 0.9755147 0.04716867 -0.2458063 0.9681707 -0.07668215 -0.520735 0.8502676 -0.3118368 -0.7055625 0.6363485 0.03120207 -0.838321 0.5442835 0.2198941 -0.6634065 0.7152192 0.3478276 -0.2695963 0.897961 0.5071617 -0.6845972 0.5235588 0.6574991 -0.325843 0.6793535 0.008528947 -0.9368426 0.3496477 -0.01764112 -0.792544 0.6095597 -0.1934117 -0.8588067 0.4743872 0.7144376 -0.3091737 0.6276867 0.6160446 -0.7053954 0.35058 0.406179 -0.8900594 0.2069135 0.2214015 -0.9747955 -0.02747797 0.4447024 -0.8874117 0.1214101 0.9410014 -0.2477193 0.2305462 0.8154011 -0.5788217 -0.009303331 0.9582981 -0.2445758 0.1478089 0.1180269 -0.9657253 0.2311804 0.4715339 -0.01438331 0.8817307 0.4123373 -0.3059499 0.8581216 0.2931746 -0.7044122 0.6464149 0.1430624 -0.9533305 0.2658839 0.3391724 -0.385228 0.8582317 0.1304557 -0.9094452 0.3948302 0.07104355 -0.9424941 0.3265849 0.05431234 -0.7523031 0.6565746 0.2044878 -0.371491 0.9056375 0.03996735 -0.7316394 0.6805193 0.01607573 -0.9880259 0.1534489 -0.03998005 -0.7315895 0.6805721 -0.01607781 -0.9880257 0.1534495 -0.07104778 -0.942493 0.3265871 -0.130474 -0.9094431 0.394829 -0.4424552 -0.1168858 0.8891407 -0.1419817 -0.9500071 0.2780789 -0.1384986 -0.9539637 0.2660292 -0.2931654 -0.7044133 0.6464178 -0.4555945 -0.2584301 0.8518495 0.556284 -0.06905871 0.8281179 0.5464243 -0.0751962 0.834126 0.5760322 -0.1381621 0.8056663 0.4918599 -0.3073523 0.8146217 0.5331541 -0.2321003 0.8135577 0.5242645 -0.2285823 0.820303 0.4919357 -0.2657557 0.8290798 0.4866985 -0.2608633 0.8337117 0.2261431 -0.4302094 0.8739446 0.1192957 -0.196326 0.9732547 0.1085587 -0.1969446 0.9743859 0.2952561 -0.7045631 0.6453021 0.3609509 -0.6370854 0.6810556 0.2607312 -0.5979611 0.7579327 0.008400917 -0.5754379 0.8178024 0.1316797 -0.6925209 0.7092781 -0.2890243 -0.2736085 0.9173895 -0.1371402 -0.6223377 0.7706415 -0.3474865 -0.2725113 0.8972128 3.52841e-4 -0.9540959 0.299501 -0.06956505 -0.8381105 0.5410467 0.1195178 -0.9101297 0.3967108 -0.3796347 -0.7014829 0.6031578 -0.2014117 -0.8733096 0.4435806 -0.6472467 -0.3049419 0.6986289 -0.4819381 -0.6994643 0.5277172 -0.2139053 -0.9764404 -0.02843868 -0.4322174 -0.8915219 0.135562 -0.7187631 -0.2910751 0.6313913 -0.6910422 -0.6792832 0.2470529 -0.4514324 -0.8852328 0.112124 -0.9365106 -0.2651549 0.2294362 -0.9238879 -0.2623659 0.2785595 -0.7754997 -0.6209436 0.1141469 0.08395129 -0.4719871 0.8775993 0.07371973 -0.3143951 0.9464255 0.03183537 -0.7180128 0.6953015 0.05569833 -0.912407 0.4054765 0.06149959 -0.8951035 0.4415965 0.06956899 -0.9881621 0.1367333 0.01244974 -0.9194355 0.3930438 0 -1 1.70303e-7 0 -1 -2.52386e-7 1.36903e-5 0 1 -5.35298e-6 0 1 8.08107e-6 0 1 -1.63736e-5 0 1 -1.5586e-5 -7.84101e-6 1 5.31347e-6 2.30425e-6 1 0 0 1 3.53306e-6 2.76238e-6 1 0 1.83105e-6 1 8.11107e-7 3.04165e-7 1 -6.38804e-6 5.80304e-7 1 1.99552e-6 6.54721e-7 1 -2.66633e-6 4.07788e-7 1 0 1.41935e-7 1 0 5.72205e-6 1 -8.29148e-5 0 1 0.04408574 -0.7186179 0.6940064 -0.04408651 -0.7186173 0.6940069 0.1970235 -0.3283062 0.9237948 -0.1148208 -0.9055516 0.4084025 0.3531512 -0.8725569 0.3375332 0.197383 -0.8019847 0.5637912 -0.1888826 -0.6709993 0.716996 -0.2527263 -0.6501212 0.7165696 0.1260052 -0.653402 0.7464507 -0.2126826 -0.2951465 0.9314799 -0.2042688 -0.3007043 0.9315854 0.1040017 -0.3002218 0.9481829 -6.2745e-5 -0.1876349 0.9822388 0.2625882 -0.1267663 0.9565448 0.2700781 -0.1371663 0.953018 -0.2703456 -0.1375412 0.952888 -0.2625882 -0.1267647 0.956545 6.2745e-5 -0.1876351 0.9822388 -0.1040016 -0.3002231 0.9481824 0.2042653 -0.3007037 0.9315863 0.2126826 -0.2951459 0.93148 -0.1260037 -0.653402 0.746451 0.2527356 -0.6501182 0.716569 0.1888758 -0.6710079 0.7169898 -0.1973824 -0.8019845 0.5637918 -0.3531534 -0.8725568 0.3375315 0.1148249 -0.905551 0.4084025 -0.1970798 -0.3274866 0.9240736 -0.01244157 -0.9194347 0.3930459 -0.06952553 -0.9881651 0.136733 -0.06146097 -0.8951039 0.4416012 -0.05566424 -0.9124081 0.405479 -0.03181594 -0.7180131 0.695302 -0.07368135 -0.3143089 0.946457 -0.08391469 -0.4719886 0.8776021 -0.2046048 -0.3709528 0.9058316 -0.05429637 -0.752249 0.656638 -0.3395789 -0.3843509 0.858464 0.9732046 -0.1936094 0.1240491 0.8166169 -0.5456535 -0.1881468 0.9023509 -0.3499483 0.2515935 0.9094862 -0.2005922 0.3641397 0.5490384 -0.8216587 0.1530814 0.1945958 -0.9782631 -0.07165032 0.2984449 -0.9540896 0.02537357 0.3363728 -0.9375846 0.08825218 0.346641 -0.924838 0.156572 0.7418163 -0.3885824 0.5465459 0.3200514 -0.9223796 0.2162938 0.3452982 -0.8654571 0.3629785 0.2956917 -0.8938283 0.3371013 0.2087506 -0.9238803 0.3207311 0.1074181 -0.9363874 0.334126 0.6468895 -0.3287427 0.6880859 0.612537 -0.2361286 0.7543486 0.3827643 -0.3879507 0.8384425 0.1960151 -0.2749737 0.9412586 0.1666702 -0.2794895 0.9455721 -0.02492785 -0.1190542 0.9925749 -0.07813155 -0.1847195 0.9796807 -0.3273793 0.02955549 0.9444308 -0.3660949 0.03954553 0.9297369 -0.3923583 0.003088653 0.9198074 -0.4278048 -9.71918e-4 0.9038707 -0.7175689 0.002581298 0.6964827 -0.6999156 0 0.7142257 -0.9997619 -0.02028256 0.008049547 -0.1050837 0.9935913 0.04163873 0.009287655 0.9989367 0.0451579 -0.07535898 0.9953441 -0.06009548 0.04500985 0.9983416 -0.0358926 -0.07723832 0.9952924 -0.05854403 0.04527169 0.9983853 -0.0343151 0 1 1.17902e-6 0 1 -3.96106e-6 0 1 1.7681e-6 1 -1.23155e-4 0 -1 0 0 -0.5430648 0.8396907 4.8243e-4 -0.8264315 0.5630374 3.27285e-4 -0.9801973 0.1980232 0 -0.9803792 0.1952806 0.02687489 0.4829672 0.8754979 -0.01568543 0.552735 0.8333572 -1.38918e-4 0.8264318 0.5630369 3.26034e-4 0.9800147 0.1989253 1.63455e-4 0.9659199 -0.2588413 0 0.7070809 -0.7071163 0.004824042 0.2588038 -0.9659232 0.003612637 -0.2588232 -0.9659247 0 -0.7070981 -0.7070991 0.004824101 -0.9659172 -0.2588262 0.003614008 0 1 -9.59339e-7 0 1 1.90647e-6 0 1 -9.52163e-7 0 1 -2.04589e-7 0 1 -9.52417e-7 0 1 -5.49499e-7 0 1 2.19792e-6 0 1 -1.099e-6 0 1 1.09898e-6 -0.5393718 0.8339775 0.1164455 -0.8262842 0.5629437 -0.01867771 -0.8509892 0.5205124 0.06988853 -0.9828293 0.1844673 -0.004311978 0.6048252 0.791159 0.09085094 0.826304 0.5629148 -0.01867574 0.8509914 0.520501 0.069947 0.9800146 0.1989226 -0.001179873 -0.3826076 0.9238334 0.01196289 -0.6054968 0.7920567 -0.0775873 -0.9824233 0.1831236 0.03619861 -0.8434489 0.531382 -0.07891285 -0.9204112 0.3813338 -0.08618503 -0.3511084 0.9344615 0.05920118 -0.7671238 0.4246786 0.4808006 -0.3085543 0.9234256 0.2282096 -0.3523123 0.9094601 0.220813 -0.7682716 0.3935278 0.5048709 -0.1669287 0.9277174 0.333879 -0.2949073 0.4132841 0.8615254 -0.3027078 0.4024096 0.8639644 -0.1389548 0.9074007 0.3966304 0.002523839 0.9349595 0.3547455 0.2963585 0.4032516 0.8657712 0.3010102 0.4138927 0.8591192 0.139292 0.906939 0.3975669 0.1703296 0.9286363 0.3295792 0.7682678 0.3935388 0.5048681 0.349473 0.9026598 0.2511453 0.3348155 0.9186195 0.2098501 0.7671203 0.4246777 0.4808068 0.3527267 0.9339998 0.05681836 0.9204801 0.3834776 -0.0752415 0.6135852 0.7808452 0.1174477 0.4356986 0.8971672 -0.07251191 0.9823441 0.1835772 0.03604918 0.8434548 0.5313722 -0.07891529 0.6050711 0.7903802 0.09585493 0.4783646 0.8781316 -0.007226884 -0.9996244 3.63938e-4 0.02740442 0.9978137 0 -0.06609171 0.997798 -1.23135e-4 -0.06632667 -0.8357059 0 0.5491774 -0.8357015 0 0.549184 -0.3238538 0 0.9461072 -0.3238536 0 0.9461073 0.3238513 0 0.9461081 0.3238511 0 0.9461081 0.8357062 0 0.5491769 0.8357018 0 0.5491836 -0.9970436 0.005228877 -0.07665938 -0.9977977 0 -0.06633269 -0.964488 -0.2584432 -0.05449819 -0.6995551 -0.6995551 0.1457577 -0.6235514 -0.6657869 0.40977 -0.2084825 -0.7652289 0.6090648 0 -0.845002 0.5347632 0.2084811 -0.7652284 0.6090658 0.6235543 -0.6657841 0.4097701 0.9644858 -0.2584517 -0.05449753 0.6995359 -0.6995714 0.1457725 0 1 1.39909e-6 -0.1872088 0.9823201 -4.94121e-4 -0.6798587 -0.7150549 0.1627534 -0.2588247 -0.9659243 0 0.2588042 -0.9659299 0 0.6798609 -0.7150542 0.1627474 0.6806189 -0.4674208 0.5641594 0.6841515 -0.4691823 0.5583949 -0.06979531 0.9911364 -0.1130377 -0.1700219 0.9853903 0.009942173 0.4937713 -0.5547966 0.6696198 -0.8891671 -0.2823317 0.3600983 -0.06967383 0.9911667 -0.112846 -0.04752159 0.9918993 -0.1178025 0.829643 0 0.5582944 1 0 -5.23948e-5 -0.5555875 0.8314582 -3.20701e-4 -0.8314915 0.5555375 -1.64712e-4 -0.9807852 0.195091 1.67449e-4 0.1950896 0.9807813 0.002891361 0.5555682 0.831471 -3.21434e-4 0.8314709 0.5555682 -1.64136e-4 0.9807816 0.1951091 -5.13937e-5 0.9807696 -0.1951106 0.004793465 0.8314688 -0.5555663 -0.002418577 0.5555829 -0.8314577 -0.002417564 0.1950926 -0.9807848 0 -0.1950854 -0.9807746 0.004794239 -0.5555857 -0.8314559 -0.002417504 -0.8314536 -0.5555889 -0.002417385 -0.9807861 -0.1950863 0 -0.195077 0.9807879 0 -0.4398658 0.8976941 0.02576106 -0.34308 0.9296292 -0.1344832 -0.1209127 0.9899573 -0.07324439 -0.9531915 0.2032275 0.2238854 -0.9473348 0.291164 0.1333437 0.1918277 -0.8630211 0.4673296 -0.1259095 -0.5479833 0.826959 -0.1824622 -0.6903188 0.7001196 -0.2695378 -0.738236 0.6183503 -0.04402697 -0.7844834 0.6185849 0.344869 -0.8710687 0.349721 -0.2490009 -0.6207662 0.743403 -0.5327312 -0.6768568 0.5079985 -0.486621 -0.685864 0.5411012 -0.9643707 -0.1841045 0.1899858 -0.9393281 -0.2294028 0.2550237 -0.9744615 0.2097297 0.08024001 -0.9417698 -0.1188794 0.314543 -0.4720519 -0.5159724 0.7148004 -0.553003 -0.4998679 0.6665732 -0.1070454 -0.9371818 0.3320115 -0.08362567 -0.9754937 0.2035161 -0.9561886 0.2784952 0.09024399 0.8183959 -0.5591331 0.1326602 0.2641158 -0.9384392 0.222654 0.3083107 -0.9294105 0.2028313 0.3333432 -0.927087 0.1714411 0.342742 -0.9316169 0.1209048 0.4158292 -0.9039118 0.1001488 -0.02010136 -0.9983822 0.05318713 -0.2465067 0.9682108 -0.04245495 -0.2326099 0.9725037 -0.01136928 -0.2238139 0.9730722 -0.05511599 -0.2000839 0.9797759 0.002407371 -0.1797862 0.9814465 -0.06663262 -0.1646898 0.9861021 -0.02190947 -0.1375575 0.9871777 -0.08098256 -0.1393815 0.9861038 -0.0903995 -0.09302836 0.9914762 -0.09121805 -0.1179179 0.9614151 0.248549 -0.2802218 0.9171322 0.2834508 -0.17039 0.9612234 0.2168338 -0.1709746 0.9616591 0.2144284 -0.2144727 0.9610534 0.1742925 -0.2146787 0.9620075 0.1686855 -0.2470536 0.9608833 0.1251714 -0.2456626 0.9626379 0.1139221 -0.2677095 0.960619 0.07445007 -0.2631573 0.9632418 0.05397635 -0.2767171 0.9606145 0.02544927 -0.2688915 0.9631381 -0.007906138 -0.2554129 0.9665963 0.02135545 -0.06977146 0.9915633 -0.1092442 -0.3400493 -0.6262987 0.7015101 -0.2235314 -0.5177252 0.8258296 -0.2764585 0.3216236 0.9056097 -0.6454372 -0.570703 0.5076504 -0.6437076 -0.5743155 0.505769 -0.8400802 0.2612784 0.4753934 -0.6797812 0.6453116 0.3485261 -0.8839516 0.0880292 0.4592176 -0.8141447 0.3264302 0.4802207 -0.75747 0.3963561 0.5187882 -0.5314251 -0.5620095 0.6338239 -0.4964224 -0.6743913 0.5465908 -0.6934384 0.3281303 0.6414623 -0.6976405 0.3153176 0.6433293 -0.4526651 -0.6393352 0.6215665 -0.594153 0.4217028 0.6849445 -0.4963496 0.3667774 0.7868364 -0.5515133 0.1910762 0.8119871 -0.4038644 0.4439283 0.7998883 -0.4172114 -0.5408457 0.7303566 -0.4119694 -0.6064048 0.6801137 -0.7042332 -0.6028249 0.3750438 -0.5508975 -0.7064312 0.4443727 -0.9400377 -0.1471199 0.3077095 -0.9538535 0.1968067 0.2267833 -0.7761374 0.607508 0.1689519 -0.8967558 0.4056267 0.1769075 0.3300456 -0.8072393 0.4893208 -0.2001882 -0.568071 0.7982607 -0.1971265 -0.772678 0.6034153 -0.5600925 -0.4294145 0.7084487 -0.8671642 -0.4895982 0.09121441 -0.7916694 -0.5355212 0.2940694 -0.8690285 -0.3156554 0.3809871 0.4041023 -0.5643878 0.7198387 0.3380087 -0.8513076 0.4012801 0.5200874 -0.7874134 0.3308917 0.1497556 -0.7814193 0.6057698 -0.673095 -0.6536995 0.3458614 -0.7948695 -0.5233038 0.3071411 -0.9916679 0.1243159 -0.03376728 -0.9546882 0.2962352 0.02855378 -0.9338712 0.3528605 -0.05808752 -0.9701194 0.2232395 -0.0950405 -0.8466305 0.5286223 -0.06144392 -0.779816 0.6257029 -0.01956993 -0.7979571 0.6005268 -0.0513038 -0.76799 0.6403126 -0.01382827 -0.8011773 0.589332 -0.1039363 -0.7627707 0.6444361 -0.05369436 -0.727113 0.686003 0.02658373 -0.7186775 0.6953432 -7.03885e-4 -0.6761888 0.7332341 0.07167011 -0.1938166 -0.8716145 0.4502482 -0.334842 -0.6711639 0.6613773 -0.1441258 -0.9396893 0.3101801 -0.1445419 -0.939689 0.3099875 -0.1445435 -0.9396897 0.3099849 -0.1214971 -0.9360855 0.3301249 -0.1497856 -0.939287 0.308714 -0.1492024 -0.9378129 0.3134413 -0.1485664 -0.9376174 0.3143272 -0.1064835 -0.9430894 0.3150297 -0.164999 -0.9329215 0.3200513 -0.1735486 -0.9326429 0.3163195 0 1 4.53125e-7 0 1 0 0 1 -8.33491e-7 0 1 0 0 1 2.18866e-7 0 1 2.40837e-7 -0.1431157 -0.9386849 0.3136693 -0.5999672 0.7818619 -0.1695035 -0.3586148 0.9302918 -0.07715433 -0.3416084 0.9305922 -0.1315364 -0.4758468 0.8778123 -0.05491399 -0.3378105 0.9405947 0.03414219 -0.3705772 0.9288012 -9.99334e-4 -0.2694845 0.9591628 -0.08593535 -0.15145 0.9877588 0.03735691 -0.9987608 0.0224263 0.04443156 -1 -2.00674e-6 0 -0.001180112 -0.9999989 -0.001037061 0.6689726 -0.7179068 0.1925759 0.7136579 -0.6457908 0.2713793 0.6746123 -0.6515424 0.346974 0.6488733 -0.6298755 0.4268728 0.6481493 -0.6266586 0.432668 0.5822665 -0.6480965 0.4908532 0.6805555 -0.5790751 0.4489057 -0.5587534 0.8293173 -0.005236923 -0.6304401 0.7734203 -0.06607842 -0.6232864 0.7819261 -0.01027661 -0.623549 0.7816022 -0.01687884 -0.5816628 0.8124368 0.04018729 -0.5819034 0.8114953 0.05351597 -0.5660057 0.8204912 0.08019912 -0.5820396 0.8125507 0.03148519 -0.5772521 0.8084248 0.1150189 -0.543753 0.8255069 0.151232 -0.5412144 0.8206725 0.1832586 -0.4846063 0.8395687 0.2455226 -0.5106934 0.8274896 0.2333521 -0.4737957 0.816018 0.331108 -0.404368 0.8535255 0.3286046 -0.396876 0.8348733 0.3814132 -0.3206833 0.854772 0.4080774 -0.3302968 0.8481132 0.414256 -0.2594676 0.8268337 0.4990217 -0.2167969 0.8626586 0.4569675 2.42274e-4 -1 -3.12272e-5 -0.001079082 -0.9998143 0.01923954 -0.2663822 -0.9281531 0.2599468 -0.2226665 -0.9283238 0.2977156 0.09301239 0.9914765 -0.09123075 0.1393746 0.9861056 -0.09039115 0.1375457 0.9871777 -0.08100396 0.1494137 0.987223 -0.05537319 0.06819623 0.9915381 -0.1104608 0.07177007 0.99107 -0.1123802 0 1 -1.44674e-6 0 1 1.09329e-6 0 1 0 0 1 -1.00674e-6 0 1 5.00188e-7 0 1 5.85516e-7 0 1 5.62786e-7 -9.45881e-4 0.9999995 -2.75818e-4 -0.008570671 -0.9999616 0.001843988 -0.008046329 -0.9999645 0.002516627 -0.007454574 -0.9999672 0.003172457 -0.006781756 -0.9999697 0.003814816 -0.006014287 -0.9999721 0.004432618 -0.005140066 -0.9999743 0.005015373 -0.004145205 -0.9999762 0.005542695 -0.003021001 -0.9999776 0.005984246 0.3253078 0.86088 0.3912294 0.3353339 0.8403869 0.4257947 0.2328538 0.8649786 0.4445123 0.2502915 0.8126863 0.5262085 0.1764569 0.8381875 0.5160472 0.108153 0.8436713 0.5258532 0.111874 0.8617501 0.4948445 2.93952e-4 0.8386349 0.544694 -0.009137392 -0.9999578 0.001014053 -0.006301701 -0.9999618 0.006070911 0.1039888 -0.9435235 0.314563 0.07082712 -0.9362 0.3442571 -0.005549609 -0.9507325 0.3099626 0.04523348 -0.9048653 0.4232882 0.1445341 -0.9396936 0.3099772 0.1445415 -0.939691 0.309982 0.1273798 -0.9415358 0.3119052 0.1891222 -0.9183729 0.3475975 0.3039665 0.342953 0.8888125 0.2804162 0.2789188 0.9184613 0.1553155 -0.6371626 0.7549178 0.2523757 -0.5058097 0.8249018 0.1803314 0.445826 0.8767666 0.02352964 0.3836897 0.9231623 0 -0.5819038 0.8132576 0.4301446 -0.5448245 0.7198209 0.3903565 -0.607702 0.6916069 0.5324332 0.4040622 0.7438069 0.4447464 0.03826415 0.8948388 0.4621932 0.5201581 0.7182013 0.2946085 -0.6401373 0.7095282 1.71358e-4 0.9474422 0.3199272 0.1941332 0.9599966 0.2017894 0.1373166 0.9475201 0.2887035 0.1705607 0.9612523 0.2165713 0.171053 0.9616236 0.2145248 0.214577 0.961078 0.1740285 0.2147515 0.9619804 0.1687477 0.0580669 -0.9880303 0.1429136 0.1169387 -0.9522553 0.28202 0.032947 0.9525757 0.302513 0.07027965 0.9478498 0.3108724 0.09367543 0.9526427 0.2893038 0 1 4.53124e-7 0 1 -6.00837e-7 -0.04460245 0.9908387 -0.1274728 -0.02095264 0.9922768 -0.1222616 0.02095055 0.9922778 -0.1222537 0.04459178 0.9908378 -0.1274845 0.04751849 0.9919002 -0.1177966 -0.1672708 -0.9285645 0.3313435 -0.2199038 -0.9266221 0.3049817 -0.03233152 0.9524945 0.3028351 -0.07020843 0.947472 0.3120378 -0.09560763 0.9524616 0.2892684 -0.2322025 -0.6087526 0.7586187 -0.2873092 0.2939853 0.9116063 -0.1316278 0.4609094 0.8776313 -0.01399791 -0.6233049 0.7818536 0 0.316581 0.9485655 9.45796e-4 0.9999995 -2.75429e-4 -0.1050621 -0.9425588 0.317088 -0.09282612 -0.9347614 0.3429352 -0.03533965 -0.9430736 0.3307014 -0.1682182 0.8287444 0.5337466 -0.1321681 0.7983899 0.5874565 -0.06548124 0.8972908 0.4365563 0.01265799 0.8676803 0.4969617 0 -1 -2.4102e-7 0.04879713 -0.9986239 0.01921701 -0.2765444 -0.5929449 0.7562668 -0.2212658 -0.6100214 0.760865 0.889209 -0.2822818 0.3600338 0.1199291 0.9925267 0.02253824 -0.5501474 -0.6272983 0.5512121 0.8536071 0.2229846 0.470779 0.7894631 0.3702331 0.4895667 0.1710899 -0.9322401 0.3188365 0.1746863 -0.9329746 0.3147113 0.2767109 0.9606188 0.02534931 0.263171 0.9632381 0.05397689 0.2677149 0.9606305 0.074283 0.2457146 0.9626218 0.1139464 0.2470988 0.9609021 0.1249375 0.3688555 -0.8658204 0.338084 0.4026026 -0.8445747 0.3529942 0.308172 -0.8786218 0.3647655 0.7923155 -0.4864156 0.3682882 0.7305961 -0.5583033 0.3930992 0.9395703 -0.146551 0.3094035 0.928402 0.290261 0.2319882 0.9281877 0.2916604 0.2310886 0.6097099 0.4163735 0.6744531 0.4500975 -0.6295736 0.6332847 0.5276497 -0.5685282 0.6311589 0.5146833 -0.5832202 0.6284548 0.6990765 0.2892658 0.6539245 0.6960498 0.2586018 0.6698059 0.7332493 0.3929696 0.5549058 0.5154395 -0.6392898 0.5706407 0.7147256 -0.4433333 0.5409463 0.5036937 -0.6912699 0.5181106 0.6269823 -0.5819169 0.5179439 0.5468778 -0.6432105 0.535915 0.8545992 0.2362191 0.462451 0.8735074 0.3251897 0.3622661 0.7715933 0.6347557 0.04158359 0.1448653 -0.9397484 0.3096565 0.1440095 -0.939971 0.3093798 0.1439254 -0.9399907 0.3093592 0.1436874 -0.9400364 0.3093308 0.1435407 -0.9400591 0.3093301 0.1434216 -0.9400692 0.3093546 0.1033853 -0.93946 0.32669 0.4052484 0.8371889 0.3672718 0.4044098 0.8537505 0.3279677 0.4530866 0.8312945 0.3219658 0.4888369 0.8366282 0.2471675 0.4901078 0.8324457 0.2585124 0.5333601 0.82041 0.2060447 0.5503028 0.8208827 0.1527036 0.5477409 0.8253573 0.136986 0.5793785 0.809996 0.09070283 0.5819945 0.8114432 0.05331397 0.5820823 0.8113909 0.05315387 0.6388975 0.768046 -0.04376792 0.5823343 0.8117543 0.04406726 -0.6297601 -0.6157538 0.47355 -0.6271269 -0.61181 0.4820793 -0.6740816 -0.6303635 0.3850401 -0.7233169 -0.6162534 0.3115198 -0.7775487 -0.5790694 0.2451464 -0.694438 -0.6441196 0.320727 1 9.2081e-5 0 1 1.42916e-6 0 1 2.5156e-6 0 0.1012263 0.9936183 0.04976046 0.2418722 0.9669444 -0.08072465 0.3517644 0.8901475 -0.2896541 0.319589 0.9434137 -0.08850628 0.3643679 0.9312353 0.0060817 0.4288873 0.9010788 -0.06412988 0.341588 0.9306011 -0.1315265 0.358623 0.9302885 -0.07715469 0.4497612 0.8931353 0.004944205 0.439339 0.8979295 0.02652955 0.5673882 0.8141484 -0.1234225 0.542482 0.8392208 -0.03771036 0.1955649 -0.8704745 0.4516953 0.2745296 -0.7721582 0.5730665 0.3052283 -0.6570864 0.6892555 0.9903784 0.1327756 -0.03900408 0.9073802 0.4119725 0.0833047 0.9103939 0.3720304 0.1810426 0.8285985 0.5490783 -0.1092599 0.7531706 0.6424418 -0.1414313 0.7841973 0.6195065 -0.0353055 0.9006777 -0.3103618 0.3040649 0.7987238 -0.5374888 0.2704553 0.7540262 -0.4613333 0.4675641 -0.2270545 -0.8699207 0.4378176 0.8582275 -0.4431359 0.2589904 0.9269313 -0.3494888 0.1365875 0.8458942 -0.475709 0.2411722 0.8216131 -0.5431307 0.1730923 -0.2034394 -0.8764474 0.4364084 0.2270879 0.9730886 -0.03911292 0.2774384 0.9607207 0.006608605 0.2238214 0.9730706 -0.05511504 0.2000846 0.9797757 0.002401053 0.1887501 0.9813428 -0.03660351 0.2663174 0.9637076 -0.01851803 0.2754459 0.9612826 -0.008094966 -0.2649551 -0.9269974 0.2654709 -0.2992185 -0.9272766 0.2250031 -0.2998428 -0.9280344 0.2210121 -0.3246498 -0.9274775 0.18544 -0.3248423 -0.9279558 0.1826905 -0.3430553 -0.9276227 0.1477468 -0.3430472 -0.9279026 0.1459982 -0.3559868 -0.9277262 0.1122396 -0.3559244 -0.9278636 0.1112971 0.920683 0.3750211 -0.1081768 -0.6946235 -0.6997585 0.1668421 -0.1926451 -0.86351 0.4660886 0.1259085 -0.5479866 0.8269569 0.1832948 -0.6922963 0.6979463 0.2395914 -0.7246619 0.6461124 0.3299832 -0.7194402 0.6111603 0.04363238 -0.7846601 0.6183888 -0.3957128 -0.9000084 0.1827463 -0.4031018 -0.902113 0.1539521 -0.3804691 -0.9247195 -0.01172101 0.2491165 -0.6247045 0.7400577 0.337868 -0.8061593 0.4857493 0.7485208 -0.5875829 0.3073483 0.4964801 -0.6811447 0.5380981 0.9643742 -0.1840826 0.1899895 0.9985205 -0.05405628 0.005905687 0.9406706 -0.09921759 0.3244917 0.9400359 -0.09055209 0.3288356 0.4868083 -0.5134374 0.7066823 0.8262403 -0.3874608 0.4089024 -0.366616 -0.9272912 0.07565581 -0.3647415 -0.9277921 0.07852065 0.2002123 -0.5680648 0.798259 0.1786817 -0.9140068 0.3642312 -0.1870584 -0.7481064 0.6366679 0.8344709 -0.2208986 0.5048388 0.8941393 -0.2304596 0.3839313 0.9409665 0.3361978 -0.03941136 0.9936861 0.1094021 -0.02488267 0.990553 0.1364832 -0.01331132 1 -3.75782e-6 0 0.9998699 0.007268965 0.0144034 -0.704915 -0.6942662 0.1452219 0.9614057 0.2549124 0.1035314 0.9998137 0.00684899 0.01804786 0.9902083 0.1392028 -0.01050209 0.9922821 0.1211351 -0.0265069 0.7042585 -0.06135249 0.7072877 0.7239525 -0.08033877 0.6851558 0.6983557 -0.06705397 0.712603 0.7075556 -0.1746252 0.6847416 0.6875693 -0.2029396 0.6971829 0.6896845 -0.356697 0.6301608 0.660139 -0.289966 0.6929187 0.7391296 -0.2969395 0.6045779 0.6596161 -0.2923703 0.6924061 0.7135635 -0.4679442 0.5213977 0.5224345 -0.7449344 0.4148916 0.5623597 -0.6221847 0.5446446 0.538944 -0.6397623 0.547945 -0.1649883 -0.6948317 0.6999912 -0.1721705 -0.7020137 0.6910384 -0.2965725 -0.6659905 0.6844717 -0.3183978 -0.6728961 0.6677079 -0.4518458 -0.6214222 0.6400547 -0.458203 -0.6214787 0.6354638 -0.662901 -0.3759033 0.6475023 -0.534205 -0.5139482 0.6711797 -0.4940853 -0.6083303 0.6211394 -0.6978292 -0.07750886 0.7120581 -0.9061062 -0.3124067 -0.2852609 -0.7172482 -0.1574019 0.6788075 -0.5740024 -0.07080924 0.8157863 -0.6710348 -0.1832863 0.7184138 -0.6809132 -0.2819246 0.675926 -0.6374452 -0.3846929 0.667589 -0.7220264 -0.4327795 0.5397961 0.11515 0.9931567 -0.0194981 0.1239584 0.9922873 -6.71187e-4 -0.07000875 0.9917711 -0.1071866 -0.0679205 0.9915012 -0.1109606 -0.04278177 0.9915738 -0.1222749 -0.04209768 0.9915068 -0.123053 -0.01461929 0.9915618 -0.1288074 -0.01424247 0.9915309 -0.1290883 0.01421999 0.9915563 -0.1288954 0.01463288 0.9915258 -0.1290836 0.0420947 0.9915072 -0.1230506 0.04277223 0.9915734 -0.1222822 0.06837439 0.9914932 -0.1107526 0.2103151 0.9718128 -0.1065243 0.04527276 0.9962331 -0.07396137 -0.1653163 0.9857091 -0.03237485 -0.1740418 0.9846469 -0.01341986 0.1215348 -0.4375799 0.8909283 -0.782398 -0.2745555 0.5589927 0.5069853 -0.2130013 0.8352223 0.4329984 -0.2010579 0.8786855 -0.8757907 -0.1192685 0.467724 -0.9418911 -0.02902853 0.3346616 -0.9712263 0.01020473 0.23794 -0.7445427 -0.1339634 0.6539955 -0.3532124 -0.2099426 0.9116827 -0.3567031 0.1562505 0.9210585 0.1107664 -3.82817e-6 0.9938465 0.5561771 -0.07181984 0.8279547 0.3573404 0.146095 0.9224771 0.7510228 0.02514797 0.6597973 0.971076 -0.02064311 0.2378768 0.8483937 -0.1308526 0.5129385 0.867828 -0.1354771 0.4780381 -0.4048523 -0.2260404 0.8860025 -0.7133201 -0.06060367 0.6982132 -0.5534284 -0.1223115 0.8238672 -0.1083685 -0.2059179 0.9725504 -0.2138177 -0.3760483 0.901593 0.7823982 -0.2746399 0.5589509 -0.01554936 0.9904477 -0.1370099 0.01553106 0.9904451 -0.1370303 -0.0915296 -0.9255647 0.3673586 -0.09961438 -0.9288843 0.3567224 -0.162342 -0.9261422 0.3404493 -0.9997832 -0.01466882 0.01477956 0.947062 -0.1894124 -0.2592235 0.7275558 0 0.6860486 0.726333 -6.4839e-5 0.6873431 0.695419 3.81278e-4 0.7186044 0.7154067 0.002270877 0.6987046 0.6999159 2.7339e-6 0.7142254 0.6315467 -0.002501487 0.7753339 0.6148269 -0.006632447 0.7886343 0.5668371 0.001422405 0.8238286 0.4715737 0.008822381 0.8817825 0.4264562 -0.001268088 0.9045074 0.4857826 -0.001645624 0.8740781 0.4415702 -0.03337681 0.8966058 0.4167212 -0.06069684 0.9070057 0.4557999 -5.20191e-4 0.8900822 0.3554891 8.1172e-5 0.9346804 0.3657844 0.03910851 0.9298777 0.3227239 -0.009049594 0.9464499 0.272421 -0.04836589 0.9609619 0.2800182 -0.03618645 0.9593125 0.1562021 0.02802324 0.9873275 0.09442484 -0.04775547 0.994386 0 0.03384745 0.999427 -0.09442532 -0.04775494 0.994386 -0.1562021 0.02802312 0.9873275 -0.2684181 -0.03007429 0.962833 -0.3746107 -0.1566021 0.9138613 -0.2801716 -0.0140649 0.959847 -0.3741421 0.002497851 0.9273681 -0.4835739 0 0.8753036 -0.471597 0.008808493 0.8817701 -0.4280844 -0.01025849 0.9036805 -0.4896432 -0.001502633 0.8719217 -0.4556691 -0.02415341 0.8898215 -0.5389022 3.45079e-4 0.8423684 -0.6557434 -0.02015328 0.7547149 -0.61484 -0.003781557 0.7886428 -0.6950601 3.79004e-4 0.7189515 -0.7273829 -8.18578e-5 0.6862319 -0.7262931 0 0.6873852 0 1 -2.5572e-6 0 1 1.99401e-6 0 1 1.46475e-6 0 -1 6.31455e-6 0 -1 3.61023e-6 -0.3275542 0 0.9448325 -0.3275166 3.14031e-6 0.9448455 -0.079584 -6.96924e-6 0.9968281 -0.07951372 6.65685e-6 0.9968338 0.1735915 1.56966e-6 0.9848178 0.1736273 5.96455e-6 0.9848114 0.4152699 -6.28131e-7 0.9096983 0.4152849 0 0.9096914 0.6303395 -4.3969e-6 0.7763196 0.6303293 -6.28118e-7 0.776328 0.8050481 -6.90664e-6 0.5932096 0.805091 5.02203e-6 0.5931515 0.9283191 -9.39685e-6 0.3717847 0.9283614 1.0022e-5 0.371679 0.9919638 -1.06784e-5 0.1265224 0.9919716 0 0.1264611 0.07958567 0 0.996828 0.07962554 0 0.9968249 -0.1735882 0 0.9848183 -0.1735882 0 0.9848183 -0.4153034 0 0.909683 -0.4152699 0 0.9096983 -0.6303153 0 0.7763394 -0.9283177 0 0.3717879 -0.9919636 0 0.1265239 -0.9919649 0 0.1265137 0.3232129 0.1619913 0.9323585 0.1810334 0.3289432 0.9268351 0.1843685 0.3297115 0.9259042 0.07847672 0.1685379 0.9825663 -0.1594553 0.3951826 0.9046573 -0.04530256 0.9315405 0.3608049 -0.1745921 0.8633985 0.4733505 -0.4005588 0.2640538 0.8773986 -0.3237463 0.3519926 0.8782309 -0.2226099 0.9204897 0.3211598 -0.5800693 0.3912622 0.7144463 -0.7805877 0.2446452 0.5751796 -0.6942772 0.3619237 0.6220855 -0.2604727 0.9344747 0.242716 -0.2706985 0.9316072 0.2425498 -0.3349857 0.9210135 0.1987932 -0.8562473 0.3863154 0.34293 -0.323743 0.9400021 0.1076416 -0.3640635 0.9269708 0.09046024 -0.966971 0.2230652 0.1233251 -0.975467 0.194036 0.1039916 -0.8142861 0.5440649 0.202316 -0.5472677 0.8189947 -0.1724703 -0.195034 0.9805734 0.02092117 -0.07827651 0.1788819 0.9807518 -0.1834024 0.3286129 0.9264866 -0.1848071 0.3284284 0.9262727 0.1593245 0.3968477 0.9039512 0.3865703 0.365348 0.8468083 0.3285778 0.3081328 0.8927994 0.03931337 0.9309094 0.3631283 0.1814485 0.860272 0.4764542 0.2225834 0.9205057 0.3211323 0.5802356 0.3906853 0.714627 0.2666 0.9312444 0.2484118 0.2664145 0.9335919 0.2396448 0.7469216 0.3730925 0.5503727 0.7082537 0.30412 0.6370932 0.3350259 0.9209917 0.1988269 0.8563952 0.3859448 0.342978 0.3222717 0.946016 0.03456628 0.1943064 0.9768201 -0.0898199 0.5503183 0.8236184 0.1371226 0.9246596 0.3031837 0.2304003 0.9731979 0.1935951 0.1241243 0.3273588 0.03110563 0.9443881 0.07822394 -0.1843963 0.9797343 0.02501583 -0.1189287 0.9925876 -0.196121 -0.2753202 0.9411352 -0.3826721 -0.3884667 0.8382456 -0.6123628 -0.2370278 0.7542079 -0.6466691 -0.3296824 0.6878436 -0.1074144 -0.9363869 0.3341283 -0.2087571 -0.9238796 0.320729 -0.2957141 -0.8938187 0.3371073 -0.3453073 -0.8654536 0.3629782 -0.3200519 -0.9223795 0.2162941 -0.7414494 -0.3895579 0.5463494 -0.346641 -0.924838 0.156572 -0.3362544 -0.9377009 0.08746469 -0.2987666 -0.953988 0.02540689 -0.1945877 -0.9782515 -0.07183074 -0.5490854 -0.821721 0.1525779 -0.9094669 -0.2004809 0.3642493 -0.9021546 -0.3511012 0.250689 -0.8166614 -0.5456555 -0.1879477 -0.9731968 -0.1936026 0.1241219 0.557637 0 0.830085 0.557637 0 0.8300849 0.1108072 0 0.993842 0.1107439 0 0.993849 -0.3611987 0 0.9324889 -0.3611429 0 0.9325106 -0.7512952 0 0.6599664 -0.7512953 1.28376e-6 0.6599663 -0.9712764 4.69684e-7 0.2379544 -0.97128 0 0.2379395 -0.5576308 0 0.8300892 -0.5576162 5.00963e-7 0.8300991 -0.1108706 -1.50291e-6 0.9938349 -0.1108117 2.19185e-6 0.9938415 0.3611447 1.00193e-6 0.9325098 0.3612005 1.00191e-6 0.9324883 0.7512809 -5.00929e-7 0.6599826 0.7512688 0 0.6599965 0.9712767 0 0.2379532 0.9712802 0 0.2379386 -0.5202017 -0.2587888 0.813891 -0.5562989 -0.06916588 0.8280989 -0.5763384 -0.1463436 0.804001 -0.572912 -0.1417641 0.8072638 -0.5029389 -0.1015896 0.858331 -0.5349465 -0.1696701 0.8276741 -0.3679513 -0.4636304 0.806014 -0.4224026 -0.4853973 0.7654839 -0.2873507 -0.5379293 0.7925035 -0.210828 -0.465965 0.8593184 -0.1088839 -0.1910625 0.9755201 0.04712587 -0.2458045 0.9681733 -0.07668268 -0.520735 0.8502677 -0.3118354 -0.7055594 0.6363526 0.03120064 -0.8383007 0.5443148 0.2198807 -0.6633926 0.7152362 0.3478292 -0.2695976 0.89796 0.5071625 -0.6845974 0.5235579 0.6574988 -0.325842 0.6793544 0.008528828 -0.9368424 0.3496479 -0.01762491 -0.7925555 0.6095452 -0.1933858 -0.8588144 0.4743835 -0.06005418 -0.9436043 0.3255833 0.7144359 -0.309176 0.6276875 0.6160334 -0.7054083 0.3505739 0.4061858 -0.8900607 0.2068941 0.3385329 -0.939684 0.04888141 0.4446725 -0.8874277 0.1214028 0.9410023 -0.2477176 0.2305449 0.8154081 -0.5788119 -0.009303331 0.9582853 -0.244593 0.1478638 0.1180189 -0.9657322 0.2311553 0.471534 -0.01438546 0.8817307 0.4123391 -0.3059462 0.8581221 0.2931734 -0.7044092 0.6464187 0.1430543 -0.9533349 0.2658724 0.3391726 -0.3852264 0.8582323 0.1304484 -0.909453 0.3948144 0.07104372 -0.9424966 0.3265779 0.05430996 -0.7523022 0.6565759 0.03996342 -0.7316475 0.6805108 0.01607513 -0.988026 0.1534482 -0.03997993 -0.7315849 0.6805771 -0.01607787 -0.9880257 0.15345 -0.07104831 -0.9424923 0.3265894 -0.130474 -0.9094444 0.3948258 -0.4424555 -0.1168809 0.8891412 -0.1419815 -0.9500072 0.2780786 -0.1384984 -0.9539638 0.266029 -0.293165 -0.7044141 0.6464171 -0.4555923 -0.2584289 0.8518511 0.5563261 -0.06905138 0.8280901 0.5464122 -0.07520806 0.8341329 0.5759911 -0.1381884 0.8056913 0.4918567 -0.3073551 0.8146227 0.5331567 -0.232103 0.8135553 0.5242867 -0.2285747 0.8202909 0.4919223 -0.2657617 0.8290858 0.4866643 -0.2608736 0.8337284 0.2261926 -0.4301855 0.8739436 0.1192962 -0.1963214 0.9732555 0.1085587 -0.196945 0.9743858 0.2952591 -0.7045558 0.6453087 0.3609427 -0.6371008 0.6810455 0.2607129 -0.597975 0.7579279 0.008454144 -0.5754375 0.8178021 0.1316787 -0.6925271 0.7092722 -0.2890246 -0.2736105 0.9173888 -0.1371398 -0.6223405 0.7706393 -0.3474874 -0.2725124 0.8972121 3.25673e-4 -0.9541056 0.2994701 -0.06953895 -0.8381013 0.5410645 0.1195502 -0.9101141 0.396737 -0.3796343 -0.7014837 0.6031571 -0.2014111 -0.8733103 0.4435794 -0.647301 -0.3049226 0.6985868 -0.4819368 -0.6994639 0.5277189 -0.2138976 -0.9764416 -0.02845561 -0.4322295 -0.891519 0.1355419 -0.7187423 -0.2910736 0.6314157 -0.6910426 -0.6792786 0.2470641 -0.4514073 -0.8852436 0.1121389 -0.9365185 -0.2651449 0.2294149 -0.9238848 -0.2623777 0.2785585 -0.7754887 -0.620957 0.1141481 0.08395129 -0.4719866 0.8775995 0.07372015 -0.3143979 0.9464246 0.03183543 -0.7180109 0.6953034 0.05569863 -0.9124087 0.4054729 0.06149965 -0.8951033 0.4415969 0.06956493 -0.9881619 0.1367365 0.01245504 -0.9194358 0.3930431 0 -1 4.95681e-7 0 -1 1.70304e-7 0 -1 -7.57151e-7 3.42246e-5 0 1 -5.35299e-6 0 1 2.29107e-6 0 1 -1.65208e-5 0 1 -1.21978e-5 -5.22733e-6 1 -2.79659e-7 1.53617e-6 1 2.64978e-6 1.84159e-6 1 0 1.2207e-6 1 4.05554e-6 2.02777e-7 1 -5.4755e-6 3.86866e-7 1 -1.33034e-6 4.36484e-7 1 1.33317e-6 2.71858e-7 1 0 0 1 0 3.8147e-6 1 0 0.8944273 0.4472137 0.04409027 -0.7186179 0.6940062 -0.04408603 -0.7186174 0.6940069 0.1970232 -0.3283033 0.9237959 -0.1148216 -0.9055503 0.4084052 0.3531453 -0.8725535 0.3375484 0.1973658 -0.8019872 0.5637937 -0.1888825 -0.6710053 0.7169905 -0.2527239 -0.6501148 0.7165762 0.1260042 -0.6533969 0.7464553 -0.2126848 -0.2951405 0.9314813 -0.2042585 -0.3007031 0.9315879 0.1040016 -0.3002238 0.9481822 -7.66877e-5 -0.1876338 0.9822391 0.262585 -0.1267623 0.9565461 0.2700877 -0.1371637 0.9530156 -0.2703549 -0.1375364 0.9528862 -0.2625849 -0.1267631 0.956546 7.66877e-5 -0.1876333 0.9822393 -0.1040025 -0.3002275 0.9481809 0.204261 -0.3007043 0.9315871 0.2126826 -0.295147 0.9314798 -0.1260036 -0.6533979 0.7464545 0.2527327 -0.6501175 0.7165706 0.188877 -0.6709991 0.7169978 -0.197368 -0.8019899 0.5637892 -0.3531457 -0.8725546 0.3375452 0.1148244 -0.9055503 0.4084042 -0.1970812 -0.3274851 0.9240739 -0.01244688 -0.9194329 0.3930503 -0.06952106 -0.9881661 0.1367288 -0.06146043 -0.8951025 0.4416044 -0.05566418 -0.9124081 0.4054787 -0.03181576 -0.7180101 0.6953052 -0.07368171 -0.3143135 0.9464555 -0.08391422 -0.471988 0.8776024 -0.2046118 -0.3709434 0.905834 -0.05429369 -0.7522509 0.6566359 -0.3395856 -0.3843429 0.8584651 0.9732077 -0.1935811 0.1240701 0.8165884 -0.5456888 -0.1881682 0.902351 -0.3499484 0.2515926 0.9094901 -0.2006197 0.3641147 0.5490403 -0.8216574 0.153082 0.194595 -0.9782633 -0.07165002 0.2984515 -0.9540874 0.0253781 0.3363723 -0.9375854 0.08824759 0.3466402 -0.9248383 0.1565716 0.7418172 -0.3885865 0.5465417 0.3200529 -0.9223789 0.2162948 0.3452972 -0.8654603 0.3629718 0.2957256 -0.8938149 0.3371075 0.2087482 -0.9238821 0.3207278 0.1074172 -0.9363877 0.3341253 0.6468898 -0.3287492 0.6880826 0.6125271 -0.2361273 0.754357 0.3827768 -0.3879485 0.8384377 0.1960151 -0.2749744 0.9412583 0.1666672 -0.2794893 0.9455727 -0.02492827 -0.1190554 0.9925747 -0.07816648 -0.1847264 0.9796766 -0.3273636 0.02955687 0.9444361 -0.3660877 0.03954648 0.9297397 -0.3923583 0.003088593 0.9198074 -0.4278048 -9.71403e-4 0.9038707 -0.7175288 0.002583503 0.6965241 -0.6999364 0 0.7142053 0 -1 9.88534e-7 -0.9997617 -0.02029365 0.008054614 0.009287655 0.9989368 0.04515784 -0.07535886 0.9953441 -0.06009387 0.04501003 0.9983416 -0.03589278 -0.0772376 0.9952924 -0.05854499 0.04527163 0.9983852 -0.03431504 0 1 1.17901e-6 0 1 -3.96071e-6 0 1 1.76805e-6 -1 3.62144e-7 0 -0.5430648 0.8396907 4.82393e-4 -0.8264437 0.5630194 3.2729e-4 -0.9801926 0.1980469 0 -0.9803741 0.1953064 0.02687472 0.4829632 0.8755002 -0.01568531 0.552717 0.8333691 -1.38812e-4 0.8264399 0.5630251 3.24843e-4 0.9800156 0.1989206 1.63328e-4 0.965921 -0.2588375 0 0.7070809 -0.7071163 0.004823923 0.2588038 -0.9659232 0.003612518 -0.7070981 -0.7070991 0.004823923 -0.9659167 -0.2588282 0.003612577 0 1 -9.59354e-7 0 1 1.90647e-6 0 1 -9.52167e-7 0 1 -2.04591e-7 0 1 2.19793e-6 -0.8263114 0.5629037 -0.01868373 -0.8509908 0.5205177 0.0698291 -0.9828236 0.184496 -0.004386663 0.6048265 0.7911542 0.09088516 0.8263018 0.5629194 -0.01863598 0.85099 0.5205044 0.06993812 0.9800146 0.1989226 -0.001185834 -0.3826095 0.9238328 0.01196295 -0.6055045 0.792051 -0.07758653 -0.9824225 0.1831277 0.03620064 -0.843442 0.5313928 -0.07891297 -0.9204106 0.381335 -0.08618521 -0.3511083 0.9344614 0.05920231 -0.7671368 0.4246712 0.4807865 -0.308559 0.923425 0.2282058 -0.3523127 0.9094608 0.2208097 -0.7682725 0.3935126 0.5048813 -0.1669071 0.9277224 0.3338763 -0.2949511 0.413254 0.8615249 -0.3026888 0.4024366 0.8639586 -0.1389601 0.9074052 0.3966183 0.002532839 0.934964 0.3547337 0.2963958 0.4032707 0.8657496 0.3009995 0.4138633 0.859137 0.1392869 0.9069462 0.3975523 0.1703251 0.9286412 0.329568 0.7682695 0.3935213 0.5048791 0.3494669 0.9026612 0.2511488 0.3348155 0.9186205 0.2098455 0.7671328 0.4246703 0.4807937 0.3527268 0.934 0.05681604 0.9204775 0.3834838 -0.07524281 0.6135864 0.7808443 0.1174479 0.9823466 0.1835634 0.03605121 0.8434485 0.5313822 -0.07891601 0.6050687 0.7903822 0.09585458 0.4783692 0.8781291 -0.007226943 -0.9996244 3.63717e-4 0.02740442 0.9978135 0 -0.06609231 0.997798 -1.22723e-4 -0.06632727 -0.8357018 0 0.5491836 -0.3238794 0 0.9460985 -0.3239053 0 0.9460896 0.3238773 0 0.9460991 0.3239032 0 0.9460903 0.8357015 0 0.549184 -0.9970437 0.00522834 -0.07665872 -0.9977977 0 -0.06633126 -0.9644887 -0.2584411 -0.05449753 -0.6995587 -0.6995517 0.1457571 -0.6235508 -0.6657857 0.4097731 -0.2085139 -0.7652241 0.60906 0 -0.8450086 0.5347527 0.208513 -0.7652225 0.6090624 0.6235525 -0.6657827 0.4097754 0.9644863 -0.2584495 -0.05449831 0.699537 -0.6995701 0.1457728 0 1 1.3991e-6 -0.1872099 0.9823199 -4.94085e-4 -0.6798563 -0.7150568 0.1627552 -0.2588235 -0.9659247 0 0.6798601 -0.7150551 0.1627472 0.6806184 -0.4674172 0.564163 0.6841571 -0.4691831 0.5583873 -0.06979548 0.991136 -0.1130406 -0.170021 0.9853904 0.0099442 0.4937721 -0.5547935 0.6696218 -0.8891666 -0.2823334 0.3600981 -0.06967383 0.9911669 -0.1128442 -0.04752171 0.9918996 -0.1178006 -0.8314865 0.5555451 -1.62786e-4 -0.9807835 0.1950996 1.69045e-4 0.1950907 0.980781 0.002891421 0.5555733 0.8314675 -3.22302e-4 0.8314709 0.5555682 -1.64222e-4 0.9807817 0.1951087 -5.13936e-5 0.9807748 -0.195084 0.004795312 0.831456 -0.5555855 -0.002417981 0.1950916 -0.9807851 0 -0.831469 -0.555566 -0.002418279 -0.9807803 -0.1951156 0 -0.1950764 0.9807881 0 -0.4398789 0.8976876 0.02576094 -0.3430815 0.9296283 -0.1344856 -0.1209136 0.9899572 -0.07324492 -0.9531877 0.2032364 0.2238936 -0.9473296 0.2911784 0.1333487 0.1918165 -0.8630225 0.4673315 -0.1259078 -0.5479939 0.8269522 -0.1824597 -0.6903181 0.7001211 -0.2695391 -0.7382368 0.6183487 -0.04402703 -0.7844842 0.6185842 0.3448621 -0.8710698 0.3497253 -0.2489994 -0.6207612 0.7434076 -0.5327301 -0.6768576 0.5079985 -0.4866027 -0.6858671 0.5411139 -0.9643545 -0.1841418 0.190032 -0.9393287 -0.2294 0.2550244 -0.9744618 0.2097287 0.08023798 -0.9417751 -0.1188753 0.3145288 -0.4720364 -0.5159699 0.7148124 -0.5530027 -0.4998729 0.6665697 -0.1070439 -0.9371827 0.3320096 -0.0836271 -0.9754928 0.2035198 -0.9561884 0.2784951 0.09024542 0.8183962 -0.5591324 0.1326602 0.2641212 -0.9384376 0.2226543 0.3083111 -0.9294101 0.2028331 0.3333421 -0.9270865 0.1714456 0.342742 -0.9316172 0.1209034 0.4158316 -0.9039108 0.1001474 -0.0201013 -0.9983823 0.05318653 -0.2465068 0.9682106 -0.0424571 -0.2326041 0.9725052 -0.01136684 -0.2238128 0.9730725 -0.05511569 -0.2000837 0.979776 0.002407371 -0.1797862 0.9814465 -0.06663262 -0.16469 0.9861021 -0.02191048 -0.1375573 0.987178 -0.08097976 -0.1393817 0.9861038 -0.09039956 -0.09302842 0.9914764 -0.0912162 -0.1179175 0.9614136 0.2485546 -0.2802109 0.9171363 0.2834487 -0.1703953 0.961222 0.2168358 -0.1709771 0.9616602 0.2144219 -0.2144709 0.961053 0.1742969 -0.2146719 0.9620078 0.1686921 -0.2470595 0.9608822 0.1251685 -0.2456666 0.9626367 0.1139232 -0.2677062 0.9606199 0.0744512 -0.2631598 0.9632415 0.05397272 -0.2767134 0.9606155 0.02544689 -0.2688917 0.963138 -0.007902383 -0.2554127 0.9665963 0.02135539 -0.06977152 0.9915631 -0.1092455 -0.3400506 -0.6262949 0.7015129 -0.2235324 -0.5177222 0.8258311 -0.2764585 0.321617 0.9056121 -0.6454427 -0.570711 0.5076345 -0.6437433 -0.5742677 0.5057778 -0.8400915 0.2612005 0.4754162 -0.6797545 0.6453481 0.3485107 -0.883956 0.08795714 0.4592226 -0.8141481 0.3264027 0.4802335 -0.7574682 0.3963346 0.5188073 -0.5314234 -0.562009 0.6338257 -0.4964349 -0.6743631 0.5466141 -0.6934512 0.3280935 0.6414672 -0.6976175 0.315371 0.6433281 -0.452671 -0.6393336 0.6215639 -0.5941925 0.4217058 0.6849085 -0.4963485 0.3667766 0.7868375 -0.5515128 0.1910685 0.8119893 -0.4038668 0.4439222 0.7998905 -0.4172113 -0.5408415 0.7303597 -0.4119686 -0.6064068 0.6801124 -0.7042384 -0.6028205 0.375041 -0.5508819 -0.70644 0.4443778 -0.9400337 -0.1471399 0.3077117 -0.9538562 0.1967629 0.2268096 -0.7761428 0.6075046 0.1689394 -0.8967269 0.4056941 0.1768991 0.3300494 -0.8072372 0.4893216 -0.2002112 -0.5680697 0.7982558 -0.1971077 -0.7726777 0.6034218 -0.5600557 -0.4294327 0.7084668 -0.7705113 -0.5968967 0.2236668 -0.8949348 -0.391108 0.2147701 -0.8690293 -0.315653 0.3809874 0.4041029 -0.5643869 0.719839 0.3379974 -0.8513121 0.4012802 0.5200824 -0.7874175 0.3308898 0.1497552 -0.7814211 0.6057678 -0.6730771 -0.6537163 0.3458647 -0.7948719 -0.5232999 0.3071419 -0.9916676 0.1243183 -0.03376781 -0.9546826 0.2962529 0.02855819 -0.9338624 0.3528826 -0.0580936 -0.9701182 0.2232418 -0.09504586 -0.8466302 0.5286223 -0.06144911 -0.7798349 0.625679 -0.01958382 -0.7979525 0.6005337 -0.05129379 -0.7679895 0.6403132 -0.01382827 -0.8011807 0.5893276 -0.103936 -0.7627812 0.6444238 -0.05369496 -0.7271135 0.6860024 0.02658373 -0.718687 0.6953335 -6.80152e-4 -0.6762196 0.7332058 0.07166862 -0.193817 -0.8716135 0.4502499 -0.3348465 -0.6711634 0.6613755 -0.1441255 -0.9396895 0.3101797 -0.1445419 -0.939689 0.3099874 -0.1214922 -0.9360873 0.3301218 -0.1497813 -0.9392885 0.3087114 -0.1491957 -0.9378121 0.3134471 -0.1485684 -0.9376184 0.3143234 -0.1064905 -0.9430905 0.3150243 -0.1650259 -0.9329177 0.3200489 -0.1735466 -0.932642 0.3163236 0 1 1.50206e-7 0 1 1.66698e-7 0 1 -1.00676e-6 0 1 7.00748e-7 0 1 2.18866e-7 0 1 -7.22511e-7 -0.1431156 -0.9386845 0.3136708 -0.5999617 0.7818661 -0.169504 -0.3586164 0.930291 -0.07715588 -0.3416075 0.9305926 -0.1315361 -0.47585 0.8778105 -0.05491495 -0.3378196 0.9405917 0.03413587 -0.3705795 0.9288002 -9.95159e-4 -0.2694837 0.9591629 -0.0859366 -0.1514496 0.9877588 0.03735685 -0.9987608 0.02242535 0.04443085 -1 -2.50843e-7 0 -1 2.62583e-7 0 -0.001180052 -0.9999988 -0.001037061 0.6689747 -0.7179054 0.1925743 0.7136602 -0.6457897 0.271376 0.674607 -0.6515443 0.3469805 0.6488716 -0.6298773 0.4268727 0.6481469 -0.6266615 0.4326674 0.5822712 -0.6480963 0.4908477 0.6805528 -0.5790771 0.4489071 -0.5587522 0.8293181 -0.005236923 -0.6304371 0.7734239 -0.06606578 -0.6232882 0.7819248 -0.01027661 -0.623547 0.7816037 -0.01687878 -0.5816592 0.8124393 0.04018914 -0.5819067 0.8114929 0.05351477 -0.5659896 0.8205019 0.08020216 -0.5820434 0.8125481 0.03148502 -0.5772616 0.8084186 0.1150153 -0.543751 0.8255084 0.1512314 -0.5412147 0.8206719 0.1832607 -0.4846062 0.8395693 0.2455201 -0.5106773 0.8274986 0.2333558 -0.4738001 0.8160095 0.3311226 -0.4043673 0.8535189 0.3286226 -0.3968949 0.8348726 0.3813952 -0.3206884 0.8547692 0.4080792 -0.3302846 0.8481233 0.4142452 -0.2594667 0.8268328 0.4990236 -0.2167976 0.8626578 0.4569688 2.42275e-4 -1 -3.12272e-5 -0.001079082 -0.9998144 0.01923978 -0.266382 -0.9281537 0.2599453 -0.2226662 -0.928324 0.2977151 0.09301203 0.9914766 -0.09123039 0.1393747 0.9861055 -0.09039163 0.1375457 0.9871779 -0.08100134 0.1494139 0.987223 -0.05537438 0.06819599 0.9915383 -0.1104595 0.07177025 0.99107 -0.1123805 0 1 -4.82248e-7 0 1 4.37318e-7 0 1 0 0 1 -1.00674e-6 0 1 5.00188e-7 0 1 5.62787e-7 -9.4588e-4 0.9999995 -2.75452e-4 -0.008570671 -0.9999616 0.00184381 -0.008046269 -0.9999645 0.002515912 -0.007454574 -0.9999673 0.003172695 -0.006781578 -0.9999697 0.003814816 -0.006014585 -0.9999722 0.004432618 -0.005140066 -0.9999743 0.005016386 -0.004145085 -0.9999762 0.005541861 -0.003021121 -0.9999775 0.005984425 0.3253084 0.8608779 0.3912339 0.3353385 0.840382 0.4258006 0.2502911 0.8126868 0.5262077 0.1764573 0.8381868 0.5160483 0.1081532 0.8436708 0.5258542 0.1118735 0.8617494 0.4948459 2.93952e-4 0.8386355 0.5446932 -0.009137392 -0.9999577 0.001014113 -0.006301462 -0.9999618 0.006071448 0.1039887 -0.9435238 0.3145619 0.070827 -0.9362001 0.3442574 -0.005549609 -0.9507325 0.3099629 0.04523396 -0.904865 0.4232887 0.2568375 -0.8716255 0.4174968 0.1445358 -0.9396914 0.3099829 0.144414 -0.9397074 0.3099916 0.1445428 -0.939692 0.3099781 0.1333981 -0.9358223 0.3262537 0.3039713 0.3429644 0.8888064 0.2804105 0.2789251 0.9184611 0.2523856 -0.5058045 0.8249021 0.1803315 0.4458271 0.876766 0.0235297 0.3836901 0.9231621 0 -0.5819054 0.8132566 0.4301447 -0.5448142 0.7198285 0.390359 -0.6076956 0.6916112 0.5324343 0.404063 0.7438057 0.4447454 0.03827071 0.894839 0.4621867 0.5201783 0.7181909 0.2946029 -0.6401318 0.7095354 1.71358e-4 0.9474426 0.3199259 0.1373168 0.9475201 0.2887039 0.1941308 0.959995 0.2017992 0.1705669 0.9612503 0.2165753 0.1710501 0.9616259 0.2145165 0.2145826 0.961078 0.1740215 0.2147532 0.9619787 0.168755 0.05806624 -0.9880304 0.1429136 0.06865459 -0.9834027 0.1679461 0.03294676 0.9525756 0.3025133 0.07027977 0.9478501 0.3108715 0.09367614 0.952643 0.2893027 0.09771275 -0.9210393 0.3770131 0 1 4.53123e-7 0 1 -1.12655e-6 -0.04460245 0.9908383 -0.1274763 0.02095049 0.9922776 -0.1222549 0.04459178 0.9908378 -0.1274842 0.04751855 0.9919002 -0.1177967 -0.1672713 -0.9285645 0.3313434 -0.2199036 -0.9266226 0.3049804 -0.03233146 0.9524942 0.3028358 -0.0702086 0.9474718 0.3120387 -0.09560775 0.9524615 0.2892688 -0.2322034 -0.6087489 0.7586215 -0.2873106 0.2939821 0.9116069 -0.1316283 0.460908 0.8776319 -0.01399797 -0.6233045 0.781854 0 0.3165808 0.9485656 9.45798e-4 0.9999995 -2.7543e-4 -0.09282612 -0.9347619 0.342934 -0.03533941 -0.9430732 0.3307025 -0.1682189 0.8287429 0.5337487 -0.1321688 0.7983937 0.5874513 -0.06548088 0.8972885 0.4365614 0.01265799 0.86768 0.4969621 0 -1 -2.58616e-7 0 -1 -2.41021e-7 0.04879814 -0.9986238 0.01921683 -0.6231691 0.7820751 -0.004350185 -0.7938043 0.6081628 -0.003591954 -0.7201294 0.6938397 -4.00613e-4 -0.5626699 0.8266329 -0.00899285 0.129077 -0.9916344 -6.45319e-4 0.1248509 -0.9921747 -0.001281738 0.3668264 -0.9302869 -0.002200245 0.3816626 -0.9243018 1.56751e-4 0.5131084 -0.8583085 -0.00514692 0.6088515 -0.7930525 0.01917397 0.8109589 -0.5850596 0.007145702 0.7930011 -0.6092135 0.002863049 0.9242299 -0.381829 -0.00238651 0.9914898 -0.1291405 0.0164563 0.9756928 -0.2191429 -1.41413e-4 -0.1352024 -0.9908149 0.002499163 -0.1931217 -0.9811079 0.01146376 -0.3865935 -0.9222501 -5.65866e-4 -0.5070083 -0.8618882 0.00956428 -0.7072537 -0.7067853 -0.0157091 -0.8111371 -0.5848122 0.007181882 -0.9242294 -0.3818309 -0.002316951 -0.9916318 -0.129099 -1.84976e-5 -0.9753018 -0.220657 0.009857714 3.28566e-4 -0.9999998 -6.43411e-4 -0.00366652 -0.9999911 0.002090811 1 0 -2.47578e-5 1 2.89659e-5 -2.94772e-5 1 0 -3.52414e-5 1 5.37577e-5 -1.19856e-4 1 2.12807e-5 -6.03893e-5 1 0 -4.59341e-5 1 0 -4.15393e-5 -1 3.09405e-5 2.46086e-5 -1 -3.75432e-5 2.17251e-5 -1 -2.30673e-5 2.57528e-5 -1 -1.38441e-5 2.88632e-5 -1 -7.95959e-6 3.30116e-5 -1 -3.55304e-6 3.76715e-5 -1 0 4.12765e-5 -1 0 4.12765e-5 0.9938653 0.1105988 5.65232e-6 0.993991 0.1094625 -5.69874e-5 0.9496613 0.3132788 1.16469e-4 0.9443236 0.3290176 -6.40189e-4 0.8767703 0.4809093 5.92134e-4 0.8463136 0.5326835 -0.001255333 0.7072225 0.7069866 0.002527058 0.4787645 0.877938 -0.00309509 0.5328802 0.8461908 3.42442e-4 0.3865119 0.9222844 1.7967e-4 0.3065028 0.9518678 -0.002002656 0.2614942 0.9651941 -0.004630804 0.2211157 0.9752425 -0.003179252 0.1246716 0.9921977 -8.57262e-4 0.03863555 0.9992535 1.76838e-4 -0.9939972 0.1094059 5.44798e-5 -0.9938629 0.1106194 -9.36669e-6 -0.9496678 0.3132589 1.6209e-4 -0.941152 0.3379819 -0.001030325 -0.8767775 0.480896 6.19348e-4 -0.8444126 0.5356924 0.001153945 -0.7071437 0.7070426 0.006224453 -0.4769447 0.8789277 -0.003162264 -0.5338333 0.8455649 0.006508231 -0.3969817 0.9177913 -0.008063077 -0.3090421 0.9510445 -0.002742946 -0.2317181 0.9727829 4.57865e-4 -0.12067 0.9924733 -0.02087718 -0.1740253 0.9846501 -0.0134015 -0.237044 0.9714721 -0.007217466 2.81785e-4 1 4.6035e-4 6.2819e-5 0.9999999 5.69168e-4 1.69007e-4 1 4.93775e-4 0.5373366 0.8433674 -9.22213e-4 0.6653178 0.7465596 -0.001019597 0.7972739 0.6036175 4.83351e-4 -0.2332267 0.9724024 -0.006232798 -0.1693604 0.9854786 -0.01221376 -0.1154012 0.9931274 -0.01950681 -0.2225384 0.9749239 4.5799e-4 -0.3061909 0.9519681 -0.001999139 -0.5326671 0.8463008 0.006385266 0.2143282 -0.976655 -0.01444053 0.2611925 -0.9652869 0 0.5131276 -0.8582968 -0.005175113 0.6086885 -0.793179 0.01911449 0.8109914 -0.5850161 0.00701791 0.7938222 -0.6081431 0.002908229 0.9241245 -0.382084 -0.002408564 0.9482622 -0.3174778 0.002587735 0.9916281 -0.1290963 -0.002799093 0.9954479 -0.09530782 -8.50438e-5 -0.1467857 -0.9891591 0.004287362 -0.1263885 -0.9919803 -0.0010885 -0.1931204 -0.9811082 0.01146352 -0.3864818 -0.922297 -5.59516e-4 -0.506996 -0.861895 0.009595513 -0.608959 -0.7931973 -0.002657949 -0.7930048 -0.6092082 0.002955794 -0.8111073 -0.584852 0.007278144 -0.9242252 -0.381841 -0.002314388 -0.9916263 -0.1291409 -1.85131e-5 -0.9753021 -0.2206552 0.009855568 -2.53244e-4 -1 -9.0733e-5 1.20489e-4 -1 -3.64696e-4 3.36168e-5 -1 -3.20651e-4 -3.36119e-5 -1 -3.20721e-4 -1.20463e-4 -1 -3.64222e-4 -5.82992e-4 -0.9999992 -0.001109302 1.48022e-4 -1 -1.6804e-4 -0.002981603 -0.9999899 0.003380656 1 -1.50218e-4 0 1 2.63366e-5 -2.89774e-5 1 0 -3.02485e-5 1 1.90184e-4 -2.17667e-4 1 0 -3.50881e-5 1 3.90593e-5 -9.22453e-5 1 1.49627e-5 -5.81192e-5 1 1.22007e-5 -5.48812e-5 1 0 -4.13586e-5 -1 2.07935e-5 1.46001e-5 -1 -2.33887e-5 1.35343e-5 -1 -1.23631e-5 1.49953e-5 -1 -7.7869e-6 1.59994e-5 -1 -4.24185e-6 1.71972e-5 -1 -3.16016e-6 1.83817e-5 -1 0 1.92001e-5 -1 2.18265e-5 4.12863e-5 0.9703965 0.2415179 0 0.9931328 0.1160387 -0.01491671 0.9491825 0.3147183 -0.002289235 0.8440755 0.5362229 0.001284658 0.8754606 0.4832835 -0.002409994 0.707156 0.7070502 0.003238499 0.7919594 0.6105471 -0.005725443 0.6669142 0.7451328 0.001653492 0.5440167 0.8390741 -7.95128e-4 0.5360404 0.8441923 -5.51505e-4 0.4661409 0.8847106 4.27561e-4 0.340917 0.9400933 -5.49652e-4 0.4022942 0.9155015 -0.004060268 0.3001999 0.9538763 -3.5995e-4 0.110633 0.9938601 0.001595199 0.240801 0.9705395 -0.008251249 0.1300229 0.9915086 -0.002224743 0.03753817 0.9992952 4.58538e-4 -0.9939971 0.1094069 3.2328e-5 -0.9938503 0.1107324 -9.09638e-6 -0.9496659 0.3132648 1.64047e-4 -0.9442877 0.3291208 -5.99689e-4 -0.8767977 0.4808592 6.35043e-4 -0.8461852 0.5328877 0.001174211 -0.7933856 0.6087061 -0.004050612 -0.7201671 0.6938006 -3.95679e-4 -0.7069916 0.7071947 0.006211638 -0.5626358 0.8266561 -0.008982479 -0.623164 0.7820793 -0.004340171 -0.4769105 0.8789462 -0.003154873 -0.5326532 0.8463096 0.006383776 -0.3969376 0.9178103 -0.00805217 -0.3061936 0.9519672 -0.001999735 -0.222546 0.9749221 4.5799e-4 -0.1154013 0.9931275 -0.019508 -0.1693698 0.9854769 -0.01221483 -0.2332298 0.9724017 -0.006233334 2.81785e-4 0.9999999 4.6035e-4 0 1 5.44372e-4 -2.81797e-4 1 4.60455e-4 -4.30319e-4 0.9999991 0.001258671 -8.11354e-5 0.9999998 7.35516e-4 6.2819e-5 0.9999999 5.69168e-4 1.69007e-4 1 4.94331e-4 0.1248509 -0.9921747 -0.001281321 0.3668352 -0.9302834 -0.002198457 0.3816663 -0.9243003 1.57396e-4 0.5131085 -0.8583084 -0.005146682 0.6088515 -0.7930525 0.01917606 0.8109562 -0.5850632 0.007145643 0.7929967 -0.6092193 0.002864122 0.9242299 -0.381829 -0.002387285 0.9482654 -0.3174684 0.002587258 0.9916201 -0.1291586 -0.0028041 0.9954479 -0.09530764 -8.49718e-5 -0.1263745 -0.9919819 0.001138925 -0.1931228 -0.9811077 0.0114637 -0.3864809 -0.9222972 -5.58473e-4 -0.5069879 -0.8618998 0.009595513 -0.6089608 -0.7931959 -0.002658665 -0.7929983 -0.6092168 0.002954244 -0.811111 -0.584847 0.007278978 -0.9242249 -0.3818418 -0.002313077 -0.9916272 -0.1291342 -1.84072e-5 -0.9753022 -0.220655 0.009856879 3.28565e-4 -0.9999998 -6.43409e-4 7.11595e-4 -0.9999997 -5.06464e-4 0 -1 4.82655e-7 -7.11486e-4 -0.9999997 -5.06146e-4 -0.004351794 -0.9999903 7.98798e-4 1 0 -2.46011e-5 1 2.81614e-5 -2.92906e-5 1 0 -3.50183e-5 1 6.04839e-5 -1.1911e-4 1 1.59602e-5 -6.00064e-5 1 3.48588e-6 -4.5643e-5 1 0 -4.12765e-5 -1 2.68334e-5 2.46674e-5 -1 -3.69566e-5 2.1777e-5 -1 -2.13632e-5 2.58143e-5 -1 -1.42386e-5 2.8932e-5 -1 -8.42851e-6 3.30906e-5 -1 -3.40687e-6 3.77616e-5 -1 0 4.13751e-5 -1 0 4.13752e-5 0.9938629 0.1106192 5.91644e-6 0.9939911 0.1094614 -5.86029e-5 0.9496549 0.3132981 1.17983e-4 0.9442846 0.3291297 -6.43575e-4 0.876782 0.4808879 5.94673e-4 0.8461946 0.5328726 -0.001257836 0.7972459 0.6036546 4.82637e-4 0.6653304 0.7465484 -0.00100702 0.7069923 0.7072167 0.002515137 0.5373126 0.8433827 -9.15531e-4 0.4787251 0.8779594 -0.00308448 0.5326772 0.8463184 3.37685e-4 0.3865384 0.9222733 1.82131e-4 0.3064589 0.9518819 -0.001998722 0.2225327 0.9749011 -0.006859004 0.2407992 0.97054 -0.008251667 0.1300224 0.9915086 -0.002224743 0.03753745 0.9992951 4.5853e-4 -0.9939974 0.1094041 5.45394e-5 -0.9938623 0.1106249 -9.86928e-6 -0.9496611 0.3132792 1.63597e-4 -0.944291 0.3291113 -5.98789e-4 -0.8767971 0.4808601 6.36177e-4 -0.8461892 0.5328815 0.00117433 -0.7934094 0.608675 -0.004048287 -0.7201443 0.6938242 -3.959e-4 -0.7069793 0.707207 0.006211519 -0.562636 0.826656 -0.008982121 -0.6231654 0.7820781 -0.004339635 -0.4768999 0.8789521 -0.003155589 -0.3969455 0.9178069 -0.008051574 2.81785e-4 1 4.60421e-4 0 0.9999999 5.44579e-4 -2.81798e-4 0.9999999 4.60528e-4 -4.30319e-4 0.9999991 0.001257956 -8.11348e-5 0.9999998 7.36297e-4 6.28193e-5 0.9999999 5.69475e-4 1.69007e-4 0.9999999 4.94053e-4 -0.2225382 0.9749212 -0.002338051 -0.2652899 0.9641222 -0.009481191 -0.5312964 0.8471861 -1.50181e-4 -0.5326779 0.8463181 1.23777e-4 -1 0 -1.52528e-4 -1 3.8151e-5 0 -0.2652935 0.9641649 -0.002329587 -0.2357423 0.9716097 0.02000755 -0.625132 -0.7788618 0.05083727 -0.3018028 -0.9530544 0.02454334 -0.3301534 -0.9439162 0.004615485 -0.3295322 -0.9441348 -0.004258632 -8.49062e-5 -0.9999994 -0.001111805 5.59778e-4 -0.9999999 3.28077e-5 -0.1263882 -0.9919809 -1.09236e-6 -0.1263767 -0.9919824 0 -0.2736922 -0.9589906 -0.07368582 -0.3858768 -0.9209901 -0.05363303 -0.5434745 -0.8359996 -0.07576513 -0.6082919 -0.7923274 -0.04688727 -0.7930032 -0.6092174 5.44508e-4 -0.9242249 -0.381841 -0.002419412 -0.9160984 -0.400949 0.001935958 -0.9904294 -0.1380206 0 -0.9916253 -0.1291347 -0.001856267 0.5985463 -0.7799643 0.1827514 0.7851468 -0.6014923 0.1474844 0.2639735 -0.9611311 0.08090245 0.2603494 -0.9620193 0.08208018 0.7517032 -0.6367183 0.1718488 0.9040821 -0.3738057 0.2071352 0.9911794 -0.1290387 0.03020948 0.9288848 -0.274271 0.2488948 0.5199321 -0.7468301 0.4146269 0.7598344 -0.2355769 0.6059333 0.7728052 -0.2259914 0.593043 0.5864069 -0.2685678 0.764198 0.1279677 -0.9704073 0.2047783 0.2270326 -0.9462998 0.2301585 0.3979157 -0.6599739 0.6372579 0.422745 -0.2252912 0.8777987 0.3706977 -0.2484214 0.8949134 0.3066739 -0.7074083 0.6368082 0.08815091 -0.9653817 0.245495 0.03413552 -0.6918563 0.7212279 0.01226896 -0.9657358 0.2592371 -0.01021254 -0.9713129 0.2375858 0.03891921 -0.9659032 0.2559617 0.125943 -0.2625576 0.9566619 0 -0.2218374 0.9750837 0 -0.7098814 0.7043213 -0.1259453 -0.2625583 0.9566614 -0.06132078 -0.9652315 0.2541024 -0.09605556 -0.9673879 0.2343802 -0.1020579 -0.9696502 0.2221772 -0.274443 -0.6900983 0.6696606 -0.304606 -0.7121607 0.632489 -0.4208787 -0.2432441 0.8738956 -0.3740085 -0.2115666 0.9029713 -0.5864077 -0.2685642 0.7641984 -0.1535176 -0.9649147 0.2130068 -0.1830023 -0.9684808 0.1689825 -0.182753 -0.9681568 0.1710965 -0.5328544 -0.6884571 0.4920296 -0.547204 -0.714239 0.4363836 -0.7609418 -0.2295922 0.6068402 -0.7705011 -0.238238 0.5912451 -0.2224743 -0.9649689 0.139069 -0.245252 -0.9614925 0.124031 -0.2384098 -0.9668871 0.09105014 -0.6326465 -0.7051126 0.3202728 -0.8904529 -0.2665572 0.3688372 -0.6073523 -0.784718 0.1238579 -0.9457823 -0.2272621 0.2320517 -0.3018279 -0.9519221 0.05238604 -0.9821153 -0.1368619 0.1292997 -0.8739315 -0.3831439 -0.2990729 0.1290758 -0.9916347 3.33593e-4 0.3816635 -0.9242979 0.002521812 0.6081036 -0.7920857 -0.05301398 0.6982097 -0.715852 -0.007696032 0.793 -0.6092138 -0.003106176 0.9242318 -0.3818309 9.88811e-4 0.915481 -0.4023481 -0.003269672 0.9909467 -0.1342528 -9.95982e-4 0.9916234 -0.1291631 0 0.6774286 -0.7106201 0.1900259 0.8867164 -0.38979 0.248592 0.9858306 -0.133561 0.1014868 0.9794273 -0.1552268 0.1289458 0.1090447 -0.9940155 0.006524562 0.2876167 -0.9576415 -0.01412796 0.6853936 -0.6950594 0.21709 0.2473377 -0.9672542 0.05695009 0.2029162 -0.9761706 0.07691532 0.8929699 -0.2565014 0.369881 0.2228595 -0.9649136 0.1388361 0.49581 -0.7129843 0.4958084 0.5191845 -0.7006574 0.4894147 0.6846059 -0.2503171 0.6845846 0.7837226 -0.1552311 0.6014003 0.5884032 -0.2565087 0.7668018 0.18134 -0.9684495 0.1709428 0.1825512 -0.9682609 0.170722 0.1533647 -0.9649432 0.2129879 0.2670726 -0.6875556 0.675233 0.09074652 -0.9690868 0.2294252 0.10609 -0.9669688 0.2317678 0.3699092 -0.2565096 0.8929558 0.1779118 -0.7262867 0.6639692 0.2531294 -0.2083967 0.9447202 0.1261722 -0.256498 0.9582743 0.06061547 -0.9653428 0.2538485 0.01024764 -0.9659534 0.2585132 0 -1 -1.3154e-5 0 -1 -7.17001e-6 -1.55498e-6 -1 -1.62717e-4 0 -1 3.16456e-6 0 -1 -1.43998e-6 1.76921e-4 -1 -1.68624e-4 0 -1 2.71459e-6 0 -1 -2.61615e-6 5.19923e-5 -0.9999993 -0.001195847 -2.7702e-4 -1 -1.42449e-6 -5.58569e-4 -1 8.18299e-6 -5.56901e-4 -1 -8.3661e-6 5.56213e-4 -1 2.03089e-6 -5.56597e-4 -1 0 -0.2452715 0.9682754 0.04779791 -0.2282696 0.9717563 0.05985605 -0.5267138 0.8398235 0.1314126 -0.7031312 0.7031294 0.1059045 -0.8432829 0.5371094 -0.01968157 -0.6844264 0.7018835 0.1972821 -0.9174895 0.3451434 0.1977092 -0.9938359 0.1107787 0.004289388 -0.9498568 0.2411993 0.198985 -0.2378441 0.965083 0.1097502 -0.5599566 0.697885 0.4465481 -0.2044416 0.9652057 0.1630387 -0.1639249 0.9725712 0.1650274 -0.208741 0.9670078 0.1460244 -0.5599454 0.6978913 0.4465525 -0.7586141 0.2418795 0.6049785 -0.7841817 0.2199489 0.5802428 -0.148227 0.9654339 0.214397 -0.1083347 0.9683286 0.2249521 -0.1022337 0.9693092 0.2235799 -0.3107614 0.6978862 0.6452768 -0.3107564 0.6978859 0.6452796 -0.4190116 0.2597001 0.870049 -0.5030179 0.1975403 0.8413981 -0.06555408 0.9651415 0.2533864 -0.1799161 0.2665368 0.9468834 0 0.9659085 0.258884 0.02339667 0.9720075 0.2337823 -0.01964509 0.9667126 0.2551095 0 0.6978855 0.7162094 0 0.2095644 0.9777949 0 0.6978866 0.7162083 0.1832786 0.2683005 0.9457398 0.07118129 0.965284 0.2513171 0.1077889 0.968651 0.2238231 0.1082217 0.9687908 0.223008 0.3107567 0.6978845 0.645281 0.3107632 0.6978883 0.6452738 0.423744 0.2150648 0.8798796 0.508274 0.2576521 0.8217501 0.1535161 0.9652343 0.2115551 0.1929849 0.9690569 0.1539014 0.1941048 0.9663287 0.1689148 0.5599554 0.6978867 0.446547 0.7612237 0.2281213 0.6070414 0.7724136 0.2399384 0.5880536 0.5599544 0.6978898 0.4465435 0.6896296 0.7005511 0.1834102 0.3402868 0.938207 0.06302905 0.1097323 0.985755 -0.1274597 0.2234852 0.9746094 0.01381415 0.2379807 0.9702363 0.04479783 0.2442579 0.965713 0.08795714 0.8264533 0.5252715 0.2026447 0.7048761 0.7047727 0.08028095 0.5358645 0.8261544 -0.1741215 0.9514753 0.2402932 0.1922341 0.9512569 0.2367905 0.1975864 -0.2357891 0.9718043 0 -0.7071065 0.7071072 -1.23862e-4 -0.7069937 0.7072198 -1.50536e-4 -0.8461899 0.5328815 1.49052e-4 -0.843488 0.5371472 9.96185e-4 -0.944291 0.3291119 2.2644e-4 -0.936171 0.3515248 -0.003780484 -0.9938451 0.1107783 -2.24597e-4 -0.9938622 0.110625 -1.98899e-4 0.1668414 0.9859838 0 0.2225278 0.974879 0.009609758 0.3113011 0.9502949 -0.005592405 0.5326783 0.8463174 8.95596e-4 0.53728 0.843404 1.19358e-4 0.7071139 0.7070997 -1.50123e-4 0.706993 0.7072206 -1.22085e-4 0.8461977 0.5328692 1.49962e-4 0.8483656 0.5294108 -5.35515e-4 0.9442745 0.3291203 -0.005048453 0.9658445 0.2590525 0.006040215 0.9927561 0.1104986 -0.047176 0 0.9667528 0.255713 0.01834553 0.9712025 0.2375485 0 0.2095643 0.9777949 0 0.697885 0.7162098 0.1832832 0.2683003 0.945739 0.06562757 0.9651408 0.2533698 0.3107574 0.6978856 0.6452794 0.1072144 0.9689907 0.2226255 0.1042047 0.9681391 0.2277015 0.310761 0.6978868 0.6452763 0.42374 0.2150684 0.8798807 0.5082675 0.2576551 0.8217532 0.1482546 0.9654361 0.2143685 0.1986084 0.9671962 0.1583864 0.1969158 0.9706819 0.137844 0.1822648 0.9659683 0.1835346 0.559955 0.6978842 0.4465515 0.5599543 0.6978883 0.4465458 0.7612228 0.228128 0.6070401 0.7726202 0.2401776 0.5876844 0.2378416 0.9650793 0.1097883 0.6901725 0.7004004 0.1819377 0.3105177 0.9486364 0.06056278 0.1665622 0.9843248 -0.05798166 0.2278265 0.9735088 0.01938384 0.2434371 0.9678102 0.06389111 0.8300043 0.5181775 0.2063613 0.704804 0.7047931 0.08073502 0.5272727 0.8292859 -0.185118 0.9517843 0.2384747 0.192968 0.9503403 0.2215198 0.2185913 -0.9914448 3.7848e-5 0.1305265 -0.9786565 -0.002442538 0.2054886 -0.9238765 0.001921355 0.382686 -0.793349 3.12625e-4 0.608767 -0.803758 -3.59585e-4 0.5949562 -0.6087708 0.001903831 0.7933439 -0.5134404 -0.001185655 0.8581245 -0.3826521 0.001846909 0.9238908 -0.1863344 -6.3698e-4 0.9824863 -0.130551 0.001205742 0.991441 0.1305485 0.001150906 0.9914413 0.190133 -8.42167e-4 0.981758 0.3826685 0.002029895 0.9238835 0.5260806 -9.64971e-4 0.8504341 0.6087705 0.001681447 0.7933446 0.793357 -2.12318e-4 0.6087567 0.7957606 -4.61992e-5 0.6056113 0.9659256 0 0.2588198 0.9659249 0 0.2588227 0.9773253 0.003582715 0.2117132 0.130537 0.001150429 0.9914427 0.1901181 -8.43579e-4 0.9817609 0.3827049 0.002028703 0.9238685 0.5260743 -9.65935e-4 0.8504381 0.6087693 0.001680672 0.7933456 0.7933558 -2.35463e-4 0.6087583 0.796032 -5.02225e-5 0.6052547 0.9238752 0.002184748 0.382688 0.9741204 -0.00170958 0.2260235 0.991445 0 0.130526 0.9924661 3.00905e-4 0.12252 0.9790756 -2.28704e-4 0.2034971 0.9999062 -0.01225125 0.006125628 -2.73316e-5 1 -2.70099e-4 0 1 0 0.002390384 -0.9999971 9.49515e-5 -8.05278e-4 -0.9999967 0.002437651 -2.24676e-4 -0.9999977 0.002144098 2.24643e-4 -0.9999977 0.002144277 8.0512e-4 -0.9999968 0.002437353 -9.75495e-4 -0.9999989 0.00113213 1 0 -1.91766e-5 0.1290761 -0.9916345 6.55101e-4 0.2638501 -0.9643493 -0.02033817 -0.04512673 -0.6800214 0.7318022 -0.01599919 -0.9656132 0.2594904 -0.03665977 -0.9714599 0.2343538 -0.1261917 -0.2565107 0.9582682 -0.1764255 -0.7316542 0.65845 -0.253129 -0.2084063 0.9447183 -0.08960133 -0.9652557 0.2454649 -0.3698869 -0.2565133 0.892964 -0.4071354 -0.6562027 0.6353257 -0.2883681 -0.845251 0.4498829 -0.1736642 -0.978681 0.1096563 -0.1624994 -0.9716547 0.1717014 -0.4966855 -0.7117722 0.4966728 -0.684592 -0.2503267 0.684595 -0.601384 -0.1552248 0.7837364 -0.7668195 -0.2564963 0.5883856 -0.8929696 -0.2565026 0.3698808 -0.6949734 -0.6945185 0.1861619 -0.7352178 -0.5948907 0.3248996 -0.9444828 -0.2086727 0.2537877 -0.9832879 -0.1280099 0.129455 -0.8930937 -0.3689596 -0.257396 -0.3812087 -0.9089608 0.1687313 -0.2608523 -0.9626127 0.07302725 -0.1323925 -0.9893963 0.05972814 0.3816633 -0.9242977 -0.002624511 0.5984002 -0.8011815 -0.005046844 0.6089544 -0.7932004 -0.002782762 0.7064949 -0.7077178 -6.78513e-4 0.7928587 -0.609116 0.01878619 0.9240664 -0.3817664 0.01886475 0.9916265 -0.1291389 -1.84736e-4 0.979529 -0.201074 -0.009603083 0.9999988 -0.001573503 -4.35569e-4 -1.66325e-5 -0.9999998 -6.95287e-4 -2.02984e-5 -1 1.26465e-4 -2.06476e-5 -1 5.72482e-5 -2.15789e-5 -1 2.19127e-5 -0.002101957 -0.9999972 0.001108884 -4.83557e-4 -0.9999862 -0.005236983 0.002395093 -0.9999972 7.80011e-5 -0.001855075 -0.999996 -0.002125442 -0.2316784 0.9726876 0.01428282 -0.5294724 0.8380821 0.1314445 -0.7032116 0.7031059 0.1055251 -0.8442716 0.535526 -0.02043467 -0.3655189 0.9280483 0.07157039 -0.1122282 0.9887061 0.09932452 -0.2363772 0.971364 0.02403903 -0.219406 0.9747619 0.04123717 -0.9247313 0.3314515 0.1871153 -0.9938578 0.1106168 0.003287792 -0.9784321 0.1786922 0.1036339 -0.6800279 0.7028621 0.2086793 -0.8626525 0.2691712 0.4282261 -0.5599555 0.6978864 0.4465473 -0.2016932 0.9661513 0.1608468 -0.3262218 0.9336315 0.1480253 -0.5599522 0.6978868 0.4465509 -0.7642102 0.2111435 0.609427 -0.6594612 0.2606201 0.7051158 -0.1534435 0.9652345 0.211607 -0.107634 0.9687434 0.2234978 -0.1083887 0.9686284 0.2236316 -0.3107616 0.6978862 0.6452767 -0.4205459 0.2459834 0.8732888 -0.492914 0.2003042 0.8467078 -0.3107532 0.6978877 0.6452793 -0.07108342 0.9652831 0.2513478 -0.1799148 0.2665371 0.9468836 0 0.6978856 0.7162093 -0.02557474 0.966261 0.2562922 -0.9943342 0 0.1062993 -0.9943343 0 0.1062982 -0.9943345 0 0.1062964 -0.9914444 8.34443e-4 0.1305273 -0.923878 0.001211643 0.3826853 -0.8956499 -9.26938e-4 0.4447588 -0.7933666 0.002134442 0.6087404 -0.6842283 -6.37026e-4 0.7292676 -0.6087584 0.001067399 0.7933549 -0.5023187 -9.1768e-4 0.8646821 -0.3826972 0.001846611 0.923872 -0.1863318 -6.3722e-4 0.9824867 -0.1305289 0.001206219 0.9914439 -0.112559 0.9895226 0.09041821 -0.3771478 -0.4977047 0.7810567 -0.5938155 -0.6883011 0.416683 -0.4531128 -0.8043228 0.3843876 0.7434602 0.3355858 -0.5784887 0.7512954 0.3323918 -0.57015 0.3633313 0.4563143 -0.8122609 0.3741158 0.4557352 -0.8076775 0.3790549 0.4560438 -0.8051965 0.05928039 0.3714101 -0.9265746 0.2494852 0.5346788 -0.8073883 0.1360694 0.4019794 -0.9054821 0.8389613 0 -0.5441911 0.5105388 0.8598548 0 -0.6741006 0.257412 0.6923348 -0.6843224 0.229991 0.6919589 -0.6436331 0.4204518 0.6394973 -0.6303927 0.4477756 0.6341152 -0.5824812 0.5708336 0.5786751 -0.5677219 0.5929023 0.5711031 -0.5038743 0.7040554 0.5004166 -0.4885634 0.7208648 0.491589 -0.4101598 0.8161256 0.4070724 -0.3952291 0.8279414 0.3978782 -0.2904149 0.9110461 0.2926677 -0.890258 0.08335798 -0.4477638 -0.9869892 0.09845042 0.1271219 -0.8390627 0.0996924 -0.5348228 2.70965e-4 0.7231497 -0.6906914 -7.52451e-4 0.7950972 -0.6064816 -0.009415268 0.7802208 -0.6254334 0.002680897 0.8353554 -0.549704 -1.5277e-4 0.884904 -0.4657737 0.001182556 0.8875786 -0.460655 -0.001135289 0.9500544 -0.3120824 -0.001067578 0.9501392 -0.3118243 9.51006e-4 0.9859774 -0.1668764 -0.002914965 0.988727 -0.1497011 0.07723903 0.9970127 -1.1221e-4 0.02791786 0.9994846 -0.01585006 0.01220434 0.9995191 -0.02850878 0.0027498 0.9991238 -0.04176449 0.00147289 0.9990198 -0.04424238 -0.008354187 0.9998231 0.01685363 -0.003001928 0.9999099 -0.01309162 -0.01646089 0.9996851 -0.0189464 0.001255512 0.9975304 0.07022547 -0.05103343 0.9930328 0.1062155 0.4226028 0.8139204 -0.3986736 0.473546 0.8179398 -0.3266936 0.9325067 0.3520213 -0.08069819 0.3686162 0.8832325 -0.2898663 0.9292338 0.3578174 -0.09214812 0.4314796 0.8918259 -0.1359112 0.3975144 0.9047292 -0.1531255 0.910652 0.4084586 -0.06224715 0.9255003 0.3766523 -0.03977662 0.3363329 0.9417428 8.75299e-4 0.5509508 0.833641 0.03867852 0.2786143 0.9599183 -0.03051108 0.920066 0.3909726 0.02488011 0.9101961 0.4138187 0.01723855 0.9876722 0.1537647 0.0293284 0.9026346 0.4303784 -0.00502634 0.4517914 0.02711701 0.8917115 0.460098 0.01347011 0.887766 -0.1891884 0.08439064 0.9783078 0.007497847 0.1390455 0.9902576 0.5096908 0.0656957 0.8578458 -0.4943362 0.2784597 0.8234634 0.5064991 0.117649 0.8541765 0.5090385 0.1129382 0.8533024 0.04395335 0.3068457 0.9507439 -0.3845657 0.4099982 0.8270494 -0.4010248 0.4286856 0.8095726 0.043949 0.3068507 0.9507425 0.5365477 0.1450437 0.8313117 -0.3833342 0.5756236 0.7222967 0.1274873 0.481359 0.8672027 0.5434232 0.1799464 0.8199455 0.536799 0.1986386 0.8199936 -0.2620797 0.6403601 0.7219788 -0.2899719 0.696212 0.6566621 0.1274884 0.4813555 0.8672046 0.5785382 0.209509 0.7882891 -0.2018024 0.8002145 0.5647411 0.5807597 0.2387432 0.7782801 0.2435359 0.6135582 0.7511569 -0.1071608 0.8160356 0.5679811 0.2435371 0.6135595 0.7511554 0.6056722 0.2319532 0.7611564 -0.1125308 0.8841904 0.4533696 0.6352382 0.2674841 0.7245168 0.632637 0.25378 0.7316872 0.3818923 0.6918341 0.6128 0.3818919 0.6918337 0.6128008 0.04978328 0.9313733 0.360646 0.0623511 0.9148168 0.3990271 0.1080878 0.9686424 0.2237163 -0.6572673 0.5402966 -0.5254325 -0.624855 0.5441068 -0.5599145 -0.5524313 0.5898724 -0.5889571 -0.4776741 0.6212202 -0.6212189 -0.4348464 0.6179786 -0.6549895 -0.5026471 0.6091389 -0.6134296 -0.3003395 0.6744622 -0.6744605 -0.3104793 0.6735184 -0.6708022 -0.1327344 0.6998506 -0.7018481 -0.08938032 0.707036 -0.7015065 0.04632556 0.7042871 -0.7084022 0.1590789 0.7031884 -0.692979 0.2262287 0.6893938 -0.6881548 0.3289839 0.671754 -0.663714 0.4073334 0.6437223 -0.6478434 0.5384637 0.5982347 -0.593441 0.5258163 0.6050944 -0.5978111 0.7053032 0.5095769 -0.4928274 0.7646628 0.4558568 -0.4555057 0.8193933 0.4045076 -0.4061629 0.8488252 0.3790981 -0.368484 0.9453508 0.2308415 -0.2302699 0.9509572 0.2168191 -0.2206127 0.9953019 0.06845957 -0.06846696 0.9930554 0.08515626 -0.08117526 0.1306185 -0.8720973 -0.4715774 -0.2886868 0.939889 0.1823972 0.07548344 -0.8667988 -0.4929119 0.07969188 -0.8636419 -0.497767 0.1279236 -0.7852202 -0.6058588 0.08530372 -0.7467164 -0.65965 0.1112099 -0.6749705 -0.7294157 0.07329988 -0.6352246 -0.7688413 0.09116071 -0.5454367 -0.8331798 0.05995345 -0.5093212 -0.8584856 0.06785219 -0.4008651 -0.913621 0.04496318 -0.3725645 -0.9269165 0.04265838 -0.2453956 -0.9684841 0.02877289 -0.2276608 -0.9733154 0.01186519 -0.08263629 -0.9965092 0.01505935 -0.07612735 -0.9969844 9.35715e-5 -5.81744e-5 -1 -1.49612e-7 0 -1 -0.00415039 0.003829538 -0.9999841 0.4519554 0 0.8920406 0.7067568 0.005009591 0.7074388 0.7060443 0.005374193 0.7081473 0.7052096 0.005628347 0.7089765 0.7042238 0.005725562 0.709955 0.6984286 0 0.7156798 0.698594 0.001042783 0.7155176 0.6994475 0.002879798 0.7146782 0.7005989 0.004240572 0.7135428 0.7018715 0.005129754 0.7122851 0.7030957 0.005588769 0.7110733 0.002337396 0.004740536 -0.9999861 -0.05594265 -0.8215866 -0.5673322 0.1841984 -0.7910799 -0.5833211 0.01475805 -0.8591935 -0.511438 -0.02639675 -0.8127173 -0.58206 -0.003294229 -0.7900847 -0.612989 0.05581611 -0.749934 -0.6591537 -0.03087157 -0.6789569 -0.7335289 -0.02185475 -0.6694396 -0.742545 0.02602875 -0.6692037 -0.742623 0.04196757 -0.6387615 -0.7682594 -0.0232461 -0.5037534 -0.8635346 0.02718001 -0.4954178 -0.8682295 0.01391738 -0.5145499 -0.8573476 -0.01630628 -0.4957451 -0.868315 0.03194385 -0.3741886 -0.9268023 -0.0144909 -0.3066127 -0.9517241 -0.001476764 -0.3014049 -0.9534951 -0.01018053 -0.3014394 -0.953431 0.02323645 -0.2283675 -0.9732977 0.001066982 -0.1024205 -0.9947407 -0.005247771 -0.1005085 -0.9949223 -0.007656157 -0.1005616 -0.9949014 -0.005274832 -0.1005383 -0.9949193 0.004743158 -0.07745271 -0.9969847 -0.04889899 -0.8888797 -0.4555239 0.03656172 -0.8803262 -0.4729579 -0.003386557 -0.9113426 -0.4116351 -0.0723406 -0.8835468 -0.4627222 0.06737059 -0.8947737 -0.4414082 0.1392434 -0.88713 -0.4400134 -0.06006246 -0.9188514 -0.390006 0.03747391 -0.9078493 -0.4176188 -0.07677996 -0.9160442 -0.3936597 0.1820166 -0.9055491 -0.3832112 0.06209367 -0.9310846 -0.3594802 0.1892503 -0.8998785 -0.3929416 -0.0569511 -0.945517 -0.3205532 -0.1729782 -0.9447917 -0.2782935 0.06639808 -0.9290549 -0.3639346 -0.06605398 -0.944503 -0.3217935 -0.1954647 -0.9470937 -0.2545725 0.2296618 -0.9066499 -0.3538948 0.231958 -0.9044478 -0.3580079 0.09473073 -0.9470679 -0.3067389 -0.04324483 -0.9675459 -0.2489674 -0.0401563 -0.9666828 -0.2528082 -0.1699603 -0.9670357 -0.1896195 0.09834474 -0.9451784 -0.3113939 -0.2975556 -0.9478172 -0.1144699 -0.1825266 -0.9677875 -0.1734114 -0.3195262 -0.9438383 -0.08409792 0.2707759 -0.9062064 -0.3247622 0.12917 -0.9577383 -0.257007 0.2712092 -0.9057574 -0.3256519 0.2707762 -0.9062088 -0.3247552 -0.01230341 -0.9826731 -0.1849385 0.1220201 -0.899999 -0.4184652 0.1215417 -0.8996283 -0.4194002 0.1273263 -0.908676 -0.3976131 0.1304464 -0.9216029 -0.365557 0.1286338 -0.9563322 -0.2624542 0.2274439 -0.8957888 -0.3818792 0.1005201 -0.9854596 -0.1369861 0.1912815 -0.9359201 -0.2957447 0.206274 -0.9257832 -0.3168224 0.1360763 -0.9180184 -0.3724588 0.1981372 -0.8652434 -0.4605383 0.1607044 -0.9383504 -0.3060598 0.2087543 -0.9241911 -0.319832 0.2101308 -0.9235985 -0.3206412 0.2563297 -0.9157437 -0.3093684 0.2411032 -0.9030527 -0.3554787 0.2606135 -0.8791193 -0.3990361 0.2725011 -0.8916178 -0.3616086 0.2606132 -0.879115 -0.3990461 0.3032559 -0.9022665 -0.3065147 0.3092437 -0.8849613 -0.3481552 0.2916394 -0.8928928 -0.3430581 0.3003532 -0.8767207 -0.3756976 0.3003521 -0.8767194 -0.3757015 0.3392355 -0.878213 -0.3371368 0.333404 -0.8813056 -0.3348765 0.3345064 -0.8741334 -0.3521311 0.3345066 -0.8741351 -0.3521266 0.365529 -0.8712196 -0.3276662 0.365792 -0.8716266 -0.3262873 0.9999955 -0.003008186 3.31879e-5 1 8.33568e-5 3.34822e-4 0.9999641 -0.003407955 -0.007767379 0.9989812 0.04512751 -4.02687e-4 1 3.18097e-6 0 1 -4.10958e-6 0 0.837976 -0.5448289 -0.03094971 1 -6.79506e-6 0 1 1.34438e-5 0 1 -2.00195e-5 0 -0.7169734 0.05797815 0.6946853 -0.5549713 0.2137231 0.8039461 -0.8072304 0.5272586 0.2652876 -0.7212954 0.5976719 0.3500305 -0.7829425 0.61492 0.09420466 0.8831481 -0.4435193 0.1527743 0.8672657 -0.466992 0.1725364 0.9850745 -0.1274706 0.1156699 0.9523313 -0.1859377 0.2418517 0.8115993 -0.07581377 0.5792744 -0.06885635 0.1345952 0.9885054 0.9073557 -0.09318494 0.4099053 0.9999291 -0.007989108 0.008831083 0.9495443 -0.03318291 0.3118726 0.9979124 -0.00455445 0.06442272 0.9400027 -0.005737125 0.3411189 0.9998195 0.001581311 0.01893723 0.8120155 0.03160804 0.5827794 0.9828572 0.04224348 0.1794639 0.9811263 0.05167436 0.1863362 0.3059343 -0.9059434 -0.2926957 0.4717551 -0.8814688 0.02144956 0.4968281 -0.8626452 0.09489524 0.6975289 -0.7161151 0.02515166 0.6933256 -0.7204994 0.01342827 0.3783665 -0.8715115 -0.3119399 0.9997844 0.01108682 -0.01755666 -0.3252865 0.1585435 -0.9322299 -0.9276869 0.0933333 -0.3615051 -0.4257484 0.404133 -0.809577 -0.5642621 0.3349891 -0.7545798 -0.8919276 0.2019551 -0.4045732 -0.9167748 0.1632171 -0.364533 -0.3417892 0.5188846 -0.7835426 -0.9300447 0.204182 -0.3054941 -0.4618717 0.618493 -0.6357209 -0.5175392 0.5845273 -0.6248849 -0.8972272 0.307918 -0.3164966 -0.907122 0.2892009 -0.3057654 -0.334867 0.7491911 -0.5714691 -0.9308661 0.2920598 -0.2195212 -0.4885507 0.7696741 -0.410999 -0.8925575 0.4008068 -0.206628 -0.01301449 0.6830748 -0.7302325 0.9641014 -0.2528635 -0.08104687 0.6462079 -0.730469 -0.2209762 0.6524103 -0.7243067 -0.2230261 0.9632915 -0.2550083 -0.08390611 0.6579047 -0.7126979 -0.2433582 0.6563096 -0.7135223 -0.2452421 0.896542 -0.4188883 -0.1440318 0.9825614 -0.1659482 -0.08387202 0.9631568 -0.2556708 -0.08343547 0.664126 -0.7048932 -0.2491229 0.3392137 -0.8892906 -0.3067515 0.3536769 -0.8817612 -0.3121057 0.3657771 -0.8783155 -0.3078458 0.3577999 -0.8828725 -0.3041638 0.3911018 -0.8757024 -0.2831692 0.3912124 -0.8756377 -0.2832168 0.3633452 -0.8725323 -0.3266004 0.3842945 -0.8703666 -0.3078633 0.3798308 -0.8731902 -0.3053976 0.3974111 -0.8689829 -0.2948446 0.3826029 -0.8687322 -0.3145148 0.3914965 -0.8670657 -0.3081033 0.3906881 -0.8676319 -0.3075351 1 -1.45594e-6 0 0.9999477 -0.007441937 0.00701934 0.999961 0.00838536 -0.002759397 1 4.20238e-6 0 0.01280051 0.005337238 -0.9999039 0.04313379 0.03422349 -0.998483 -8.24405e-5 3.26281e-4 -1 -0.2648477 -0.01101124 -0.9642274 -0.4029927 -1.34009e-4 -0.9152032 -0.6087464 7.6092e-4 -0.7933646 -0.7933165 0.00263822 -0.6088038 -0.9590357 -0.003581225 -0.2832628 -0.9470306 -0.00119102 -0.3211416 -0.8891438 0.07034194 -0.4521896 -0.2607533 0.174937 -0.9494234 -0.604173 0.1224911 -0.7873824 -0.7834984 0.1568573 -0.6012705 -0.9585772 0.03104162 -0.2831363 0.01279819 0.1651923 -0.9861784 0.002169191 -0.9999946 -0.002475082 1 -3.91906e-7 0 0.0826016 -0.8260163 -0.557561 -0.473027 0.779642 -0.4103705 -0.904596 0.3760168 -0.2007923 -0.3369748 0.8944904 -0.2938284 -0.9300392 0.3502094 -0.1112678 -0.5068891 0.847804 -0.1558591 -0.4324777 0.8914842 -0.1349787 -0.9130982 0.4010199 -0.0737214 -0.8713573 0.4858902 -0.06817138 -0.3480546 0.9373412 0.01579988 -0.9276394 0.3733227 0.0107482 -0.9220491 0.3839629 0.0489701 -0.8396537 0.5326473 0.1061539 -0.5176714 0.848705 0.1082419 -0.3974717 0.9021294 0.1678661 -0.3677316 0.8732 0.3198364 -0.9235249 0.3583346 0.1367407 -0.7781924 0.5687875 0.2662661 -0.5976586 0.7359775 0.3180271 -0.3448134 0.8848772 0.3132032 -0.8938061 0.4080255 0.1860806 -0.9401326 0.2935921 0.1730736 -0.9932257 0.08879643 0.07495313 -0.9411617 0.3050418 0.1454796 -0.002855479 0.98312 0.18294 0.0144419 0.9623745 0.2713429 -0.04489737 0.9380477 0.3435853 0.9798713 -0.009259939 -0.1994156 0.8351706 -0.06883072 -0.5456669 0.3927136 -0.03281903 -0.9190751 0.5214909 -0.1081427 -0.846376 0.2021932 -0.2011665 -0.9584624 0.9830816 -0.04580318 -0.1773494 0.9803977 -0.06234812 -0.1869043 0.8346403 -0.174293 -0.5224919 0.5686165 -0.2603399 -0.7803195 0.8346127 -0.1743311 -0.5225233 0.5009738 -0.3190675 -0.8045007 0.2960548 -0.3521385 -0.8878908 0.3952938 -0.3059073 -0.8661199 0.9832931 -0.07453441 -0.1660702 0.980495 -0.1018169 -0.1681163 0.8345359 -0.2854113 -0.4712646 0.5823139 -0.4211835 -0.6953524 0.8344978 -0.2854725 -0.471295 0.2211773 -0.4735667 -0.8525347 0.4092233 -0.5454488 -0.7314519 0.3910048 -0.5545665 -0.7345551 0.4885603 -0.5215927 -0.6994641 0.9827491 -0.103533 -0.1532489 0.8344125 -0.3857802 -0.3936107 0.9811226 -0.1353658 -0.1381109 0.9815413 -0.1328969 -0.1375331 0.5879799 -0.566228 -0.5776379 0.8343735 -0.385847 -0.393628 0.2447948 -0.7031911 -0.6675311 0.3773239 -0.7937089 -0.4771299 0.6684799 -0.621816 -0.408019 0.3652368 -0.8297475 -0.422044 0.9829686 -0.1488209 -0.1078195 0.8342893 -0.4681679 -0.2911704 0.9801588 -0.1683184 -0.1046795 0.5273244 -0.7483755 -0.4023221 0.7689965 -0.5705307 -0.288339 0.9832546 -0.1641282 -0.07919901 0.9841111 -0.1671201 -0.05996942 0.9793814 -0.1945212 -0.05453193 0.792079 -0.5893573 -0.1589617 0.5484709 -0.8178105 -0.1742576 0.8375391 -0.5094164 -0.1975429 0.241163 -0.9067862 -0.3458023 0.2375695 -0.9098817 -0.340112 0.2824472 -0.8943927 -0.3468216 0.2118482 -0.8748407 -0.4356306 0.3511077 -0.7704287 -0.5321306 0.232459 -0.8299633 -0.5070738 0.366066 -0.7643359 -0.5308356 0.2980045 -0.8520066 -0.4304394 0.1512646 -0.8521116 -0.5010238 0.2663684 -0.8341907 -0.4828807 0.3598143 -0.7699436 -0.5269921 0.3396797 -0.6784154 -0.651437 0.1553544 -0.6927188 -0.7042768 0.2285076 -0.5321831 -0.8152089 0.1273329 -0.6121681 -0.780408 0.1914119 -0.544382 -0.8167067 0.1535148 -0.6128447 -0.7751482 0.1411277 -0.505691 -0.8510933 0.1797662 -0.4803889 -0.8584349 0.1666155 -0.3367291 -0.9267432 0.1356553 -0.3689977 -0.9194773 0.09008049 -0.3619101 -0.9278505 0.09373366 -0.3565605 -0.9295583 0.03520065 -0.2255817 -0.9735881 0.08755058 -0.2146376 -0.9727619 0.152049 -0.07548326 -0.9854864 0.01351892 -0.1281173 -0.9916669 0.0257917 -0.07398718 -0.9969257 -0.9973791 0.05116158 -0.05116266 -0.9989907 0.04470539 -0.00437361 -0.9845536 0.12134 -0.1262171 -0.9756032 0.1722715 -0.1360923 -0.9577188 0.2004516 -0.2063833 -0.9299393 0.2693272 -0.250351 -0.9373143 0.2690706 -0.2214562 -0.8970142 0.3118559 -0.3132278 -0.8614809 0.3651812 -0.3528364 -0.8497461 0.3646922 -0.3806984 -0.7709907 0.4575126 -0.4430074 -0.7493137 0.4599667 -0.4764029 0.9844859 -0.1717435 -0.03594112 0.8655419 -0.5006891 0.01215672 0.5810279 -0.7915049 -0.1895437 0.4533263 -0.8726853 -0.1814269 0.711342 -0.6668606 -0.2220125 0.6608183 -0.7234095 -0.1999949 0.9526451 -0.2903081 -0.09049093 0.9608675 -0.2685312 -0.06800651 0.9609282 -0.2654742 -0.07836276 0.2336835 -0.9208079 -0.3122579 0.3177284 -0.9114137 -0.2614837 0.2729938 -0.9280538 -0.2533586 0.2764288 -0.9084844 -0.3134377 0.3275251 -0.903297 -0.2770956 0.3086735 -0.9130226 -0.2666651 0.391942 -0.8758842 -0.2814397 0.3151012 -0.9210598 -0.2288236 0.3171176 -0.9131181 -0.2562261 0.3546198 -0.8782312 -0.3208656 -1 2.81594e-5 -1.00174e-4 -0.9999993 0.001195013 -1.55113e-5 -1 -3.42215e-6 0 -1 4.00597e-6 0 -1 -3.91011e-6 0 -1 5.84609e-6 0 -1 -1.58208e-5 0 -1 -2.87228e-6 0 -1 -4.32788e-6 0 -1 5.59387e-6 0 1 1.59008e-7 0 1 -3.41841e-7 0 1 -6.56388e-7 0 1 5.06396e-7 0 1 7.63867e-7 0 1 -1.32972e-6 0 -0.9999998 7.19153e-4 -1.07949e-4 -0.9999995 -0.001043856 5.90098e-5 -1 8.5599e-5 -1.88159e-5 -1 4.67023e-5 -1.74634e-5 -1 2.83076e-5 -1.62974e-5 -1 2.08523e-5 -1.52462e-5 -1 3.98774e-6 -1.42758e-5 -1 6.96199e-6 -1.33639e-5 -1 7.31263e-6 -1.24939e-5 -1 4.22351e-6 -1.16522e-5 -1 2.04503e-6 -1.08269e-5 -1 -1.39463e-4 5.90143e-5 -1 2.4555e-4 -2.07856e-5 -0.002139687 0.07474064 -0.9972007 0 0.07844948 -0.9969182 0.001940488 0.2226194 -0.9749035 -0.003848135 0.233428 -0.9723665 0.003648638 0.3655376 -0.9307895 -0.005474627 0.3826521 -0.9238764 0.005172431 0.5001814 -0.8659052 -0.006927251 0.5224548 -0.8526389 0.00651437 0.6235849 -0.7817286 -0.008185923 0.6493989 -0.7604039 0.007663547 0.7330715 -0.6801085 -0.009219765 0.7603515 -0.6494465 -0.02101194 0.9236682 -0.3826169 -0.01644933 0.9722355 -0.2334258 0 0.9982421 -0.05926978 0.3572145 0.1721246 -0.9180256 0.1116613 0.07427316 -0.9909669 0.9603779 0.02415013 -0.277653 0.9878751 0.1082264 -0.1113103 0.9324972 0.04988521 -0.3577157 0.6954702 0.078673 -0.7142351 0.8290958 0.1833786 -0.5281784 0.7014632 0.1259256 -0.7014928 0.5298852 0.1107677 -0.8408045 0.3147926 0.1324383 -0.9398755 0.2480992 0.2156604 -0.9444244 0.9672077 0.06550782 -0.2453939 0.9656521 0.1096204 -0.2355834 0.9625334 0.1037701 -0.2505221 0.7094444 0.2697033 -0.6511136 0.2713506 0.3518237 -0.8958733 0.3129349 0.3807169 -0.8701302 0.6932175 0.2889031 -0.6602913 0.2421434 0.4853014 -0.8401484 0.9657092 0.1487578 -0.2127839 0.714321 0.4260214 -0.555204 0.962507 0.1651319 -0.2152017 0.6887317 0.4600478 -0.5603613 0.2881979 0.5971384 -0.7485772 0.3055509 0.6041898 -0.7359303 0.9672052 0.1794922 -0.1797127 0.2399594 0.7116745 -0.6602567 0.7185348 0.5517703 -0.423388 0.9656643 0.2127342 -0.14912 0.9625293 0.2151396 -0.1650835 0.594534 0.7006126 -0.3945521 0.343833 0.8196363 -0.4582307 0.3245199 0.8220254 -0.4679331 0.9656971 0.2352957 -0.1098415 0.684109 0.6738597 -0.2791202 0.9625121 0.2505924 -0.1037986 0.9672056 0.2453187 -0.06581979 0.3518749 0.9090262 -0.2232835 0.347796 0.9188774 -0.1862857 0.7014545 0.70149 -0.1259903 0.8450646 0.5309293 -0.06308561 0.9653711 0.2554906 -0.05275517 0.9336958 0.3307455 -0.1371849 0.9936645 0.111959 -0.009812653 0.02595931 -0.07363975 -0.996947 0.027188 -0.07262027 -0.9969891 0.1141648 -0.1502323 -0.9820371 0.3358852 -0.1108185 -0.9353612 0.5627717 -0.08353137 -0.822381 0.8414813 -0.06212443 -0.5367027 0.9396346 -0.1202301 -0.3203617 0.9937228 -0.009413003 -0.1114741 1.85779e-6 0 -1 -4.51701e-7 0 -1 0.002134203 -0.002418816 -0.9999948 0 6.41014e-4 -0.9999999 0.9937669 0 -0.1114786 0.9937118 3.13093e-4 -0.1119681 0.9463925 -2.7175e-4 -0.3230191 0.9334436 0.01976442 -0.3581794 0.8427928 -0.02596616 -0.5376115 0.8436014 -0.02714461 -0.5362834 0.7068773 0.02457982 -0.706909 0.5640779 -0.05169218 -0.8241021 0.532926 -0.02365112 -0.8458312 0.3377405 0.02282607 -0.9409625 0.3627134 0.002918541 -0.9318962 0.1154714 -0.00229156 -0.9933083 0.1119697 0 -0.9937117 0.5306605 0.8313519 -0.1650864 0.6379931 0.7513809 -0.1684982 0.111774 0.9919868 -0.05889815 0.4088394 0.8973245 -0.1663107 -0.01167392 0.9968492 -0.07845658 -0.01643747 0.9722406 -0.2334057 0.04465347 0.8710399 -0.4891785 0.01656275 0.8525092 -0.5224499 1 3.10351e-7 0 6.5167e-4 0.9999998 5.29619e-5 0.9999966 0.001384198 -0.002208054 1 -5.70506e-4 -7.43023e-5 0.961086 -0.1840682 0.205992 -0.5362554 -0.007166206 0.8440253 -0.5504496 -0.01512283 0.8347315 -0.5472633 -0.01161706 0.83688 -0.543847 -4.66592e-4 0.8391844 0 -1 0 0.3776602 -0.8640482 -0.3328568 0.2368711 -0.1000133 0.9663796 0.4539434 -0.462877 0.7613675 0.5200549 -0.4869199 0.7017492 0.540436 -0.6388316 0.5475613 0.01391738 0.5844959 0.8112774 0.281876 -0.102458 0.9539645 0.1757532 0.03600156 0.9837757 0.3483712 -0.1124808 0.9305835 0.4815795 -0.02410346 0.8760709 0.4910525 -0.03749573 0.8703227 0.4554896 -0.4619738 0.7609923 0.5929015 -0.3527636 0.7238963 0.4971065 -0.665467 0.5568114 0.4847894 -0.6409465 0.5951193 0.652553 -0.5413008 0.530253 0.6161574 -0.7085257 0.3440079 0.5454206 -0.837594 -0.03086584 0.4653367 -0.8693268 -0.1665315 0.3553192 -0.9340108 -0.03704398 0.6188419 -0.7150431 0.3251893 0.4530512 -0.8885421 -0.07237243 0.401898 -0.9070776 -0.1252533 0.6277956 -0.7016445 0.3369981 0.6444604 -0.3422868 0.6837475 0.6469035 -0.3190512 0.6926199 0.4957444 -0.01489186 0.8683408 0.3104243 -0.9035879 -0.2952381 0.1971139 -0.9421263 -0.2711902 0.3059458 -0.9047393 -0.2963849 0.2562024 0.08328598 0.9630285 0.3544101 0.05971103 0.9331818 0.6558814 0.07864439 0.750756 0.3323323 -0.07304048 0.9403299 0.7050172 -0.07075542 0.7056518 0.1856285 -0.1332911 0.9735378 0.5935947 -0.1371243 0.7929957 0.2614477 -0.2291522 0.9376217 0.09384083 -0.3045476 0.9478632 0.6470505 -0.2060917 0.7340654 0.5062759 -0.3062883 0.8061466 0.9208592 -0.1161531 0.3721921 0.2041416 -0.392111 0.8969812 0.853789 -0.2250663 0.4694566 0.9941435 -0.02715778 0.1046006 0.03057163 -0.4550173 0.8899577 0.5837455 -0.3522214 0.7315608 0.9861252 -0.08229124 0.144171 0.3807926 -0.495814 0.7804907 0.497214 -0.4468709 0.7436966 0.8715755 -0.2325186 0.431615 0.9816727 -0.08870482 0.1686726 0.7329768 -0.4172288 0.5372758 -0.4978063 4.92779e-4 0.8672881 -0.5350548 -0.006736338 0.8447906 0.06064909 -0.4010703 0.9140374 -0.003353774 -0.251598 0.9678261 0.01576977 -0.09440422 0.9954091 0.06213581 -0.01976609 0.997872 0.09037846 0.06707292 0.9936464 0.09116744 0.07841539 0.9927435 0.194193 0.2960969 0.935209 0.1344234 0.1859015 0.9733299 0.1086314 0.1694635 0.9795313 0.1153102 0.1785046 0.977159 0.1175344 0.1078433 0.9871959 0.1712553 0.0853886 0.9815195 0.1237934 0.06446164 0.990212 0.2467819 -0.07473063 0.9661853 0.3504899 0.032076 0.9360171 0.39219 0.05271083 0.9183728 0.3678779 -0.04794323 0.9286374 0.7897607 -0.09106856 0.6066175 0.66966 -0.3006506 0.6790911 0.7231866 -0.2860631 0.6286247 0.3758314 0.296083 0.8781149 0.4605287 0.1928144 0.8664503 0.3948699 0.2972266 0.8693296 0.322137 0.2883487 0.901711 0.3822845 0.1526339 0.9113515 0.340965 0.2912679 0.8938155 0.3191721 0.2459022 0.9152384 0.2437549 0.2802867 0.928452 0.2842794 0.1267594 0.9503248 0.2139113 0.2091978 0.9541898 0.2097261 0.1696964 0.9629217 0.1626902 0.227898 0.9599972 0.1532691 0.09098947 0.9839866 0.1791455 0.02928829 0.9833866 0.1670357 0.07722926 0.9829216 0.1331938 0.1255831 0.9831014 -0.724617 0.6671788 -0.1726348 -0.6476532 0.4092508 -0.6426969 -0.7253689 0.6658846 -0.1744641 -0.5572745 0.8212862 0.122205 -0.7246153 0.6671814 -0.1726316 -0.5506164 0.7971789 0.2476436 -0.7811428 0.6123464 -0.1218515 -0.7337259 0.5925793 0.3324096 -0.7240674 0.3981922 0.563178 -0.09459418 0.02775603 0.9951289 -0.3720337 0.2184861 0.9021391 -0.4756997 0.3210244 0.8189342 -0.4001361 0.7468502 0.5311366 -0.605444 0.5395126 0.5851185 -0.7773556 0.6232603 -0.08523511 -0.1925814 0.7445091 0.6392329 -0.3248364 0.001050889 0.9457697 -0.5623628 0.1437551 0.8142988 -0.6403983 -2.75398e-4 -0.7680431 -0.4927611 0.002374589 -0.8701615 -0.4171549 0.005316793 -0.9088199 -0.3399441 0.002449393 -0.9404425 -0.1374762 -0.001425623 -0.9905041 0.08637279 2.49695e-4 -0.9962629 0.2553984 0.007820427 -0.9668043 0.319364 0.004260659 -0.9476225 0.5456354 -0.00105375 -0.8380221 0.7122352 0.02560454 -0.7014738 0.9316018 -8.03547e-4 -0.3634797 -0.3041583 0.9036665 0.3014544 -0.1890541 0.9640443 0.1867545 -0.1771622 0.9677659 0.1790049 -0.06827867 0.995454 0.06640398 -0.05876928 0.9964561 0.06017881 0.05451798 0.996944 -0.05595141 0.06133568 0.9962894 -0.06037753 0.1756668 0.9684722 -0.1766433 0.1796801 0.9672673 -0.17919 0.2917768 0.9108977 -0.2917733 -0.7067435 1.78016e-4 -0.7074699 -0.7061063 0.004922449 -0.7080888 -0.6119597 0.1686864 -0.7726904 -0.468113 0.3843582 -0.7957004 -0.4436371 0.4103727 -0.7967311 -0.6920805 0.03288418 -0.721071 -0.4801709 0.3866037 -0.7873842 -0.4034767 0.473141 -0.7831629 -0.3814563 0.4980608 -0.7787341 -0.3970223 0.4797436 -0.7824445 -0.4409829 0.4329608 -0.78618 -0.4022779 0.5065561 -0.7626097 -0.3429994 0.5387044 -0.7695122 -0.2432358 0.6246196 -0.7420827 -0.1983163 0.6618924 -0.7228894 -0.04254239 0.7614476 -0.646829 0.1082051 0.8284441 -0.5495198 0.2735553 0.8669303 -0.4166529 -0.4472646 0.8826857 0.1442926 -0.754242 0.3957766 -0.5239083 -0.3663402 0.9287732 -0.05634981 -0.3560209 0.9344417 0.008245348 -0.5741702 0.7522953 -0.3230799 -0.574168 0.7523019 -0.3230682 -0.6934132 0.4873071 -0.5307635 -0.6941183 0.4903302 -0.5270446 -0.2076989 0.9752555 -0.07574957 -0.6409539 0.4787076 -0.6000144 -0.1477187 0.9601676 -0.2371867 -0.1551241 0.9528726 -0.2607114 -0.4126851 0.7712969 -0.4845535 -0.412685 0.7712969 -0.4845539 -0.5455379 0.5850832 -0.6000552 -0.5546634 0.5438347 -0.6297558 0.02742677 0.9478965 -0.3173959 -0.5027874 0.5062291 -0.7006689 -0.2469331 0.7194184 -0.6492006 0.01821643 0.8902195 -0.4551676 0.143426 0.9481597 -0.2835883 0.02092045 0.851215 -0.5244001 -0.4318569 0.5257264 -0.7328789 -0.2768213 0.7199547 -0.6364238 -0.1701346 0.8470757 -0.5035048 -0.1966278 0.7393109 -0.6440164 -0.4539805 -0.8470877 0.2763046 -0.4533604 -0.848363 0.273395 -0.4522265 -0.8622987 0.2278861 -0.3093813 -0.8458716 0.4344936 -0.3163899 -0.8510039 0.4191538 -0.3273567 -0.8542048 0.4039453 -0.1925182 -0.8433929 0.5016226 -0.2101692 -0.8212646 0.5304276 0.09594672 -0.7045931 0.7030952 0.2792406 -0.5346295 0.7976191 0.3361161 -0.58741 0.7361899 0.5099868 -0.3193511 0.7987041 0.733245 -0.1144878 0.6702569 0.6976909 -0.07378655 0.7125891 0.710013 0.09333074 0.6979764 0.7134165 0.1114984 0.6918129 0.4465981 0.2848923 0.8481666 0.4257016 0.3456322 0.8362516 0.4930779 0.3589311 0.7924914 0.4719185 0.3397439 0.813552 0.4885823 0.3554179 0.7968472 0.5040731 0.3040662 0.8083651 0.5413032 0.3531867 0.7630532 0.5159114 0.3437187 0.7846612 0.5494706 0.3572877 0.7552667 0.5575377 0.3109859 0.769701 0.591749 0.3431873 0.7294215 0.5667667 0.3431259 0.7490262 0.6133757 0.3486296 0.7086802 0.615197 0.3111583 0.724371 0.6236216 0.3302645 0.7085348 0.6427235 0.3284323 0.6921263 0.6668816 0.3003149 0.6819678 0.668949 0.329252 0.6664086 0.673443 0.3098803 0.6711549 0.6873942 0.3079509 0.6577656 0.7139731 0.3024111 0.6314983 0.7095375 0.2794122 0.6469046 0.7122894 0.2819702 0.6427571 0.6883561 0.3482038 0.6363334 0.7484955 0.2538752 0.612619 0.7514767 0.2630101 0.6050691 0.8008257 0.2947502 0.5213449 0.7568158 0.259699 0.5998219 0.7844568 0.2281603 0.5766891 0.7800489 0.2070798 0.5904589 0.7911553 0.2045117 0.5764099 0.791697 0.2313679 0.5654068 0.8041592 0.1867533 0.564315 0.810909 0.1596022 0.5629865 0.822303 0.152372 0.5482705 0.8324447 0.1912182 0.5200688 0.8267803 0.1150134 0.5506415 0.8317025 0.08125221 0.5492441 0.8480792 -0.01668649 0.5296069 0.1309141 -0.9567632 -0.2597422 -0.1489591 -0.9831051 -0.1063742 -0.01483452 -0.983344 -0.1811482 -0.157014 -0.9831088 -0.09404176 -0.2850607 -0.9583344 -0.01832276 -0.2986577 -0.9543526 0.00386399 -0.4305515 -0.8984192 0.08642065 -0.4341226 -0.8952089 0.1006914 0.1649684 -0.9644543 -0.20643 0.02009177 -0.9922361 -0.1227352 0.09740692 -0.9812533 -0.1662945 0.1538771 -0.9648271 -0.2131441 -0.03211128 -0.996072 -0.08251976 0.03310126 -0.9890071 -0.1441156 -0.1173545 -0.9926416 -0.02984511 -0.2559156 -0.9640985 0.07086223 -0.1627967 -0.9866204 0.008806109 -0.101218 -0.9931936 -0.0576319 -0.3905496 -0.9016283 0.1858432 -0.3375369 -0.9310195 0.1388224 -0.2815854 -0.9552078 0.09103715 -0.2339371 -0.971796 0.02976554 -0.4134761 -0.8927356 0.1790552 -0.4475362 -0.8655835 0.22467 -0.4091256 -0.898095 0.1613749 0.5149334 0.1353662 0.8464748 0.5446342 0.1177519 0.8303663 0.609116 -0.3574458 0.707962 0.5471408 0.1032153 0.8306525 0.5465114 0.1220452 0.8285109 0.6069376 -0.365236 0.7058537 0.5168855 -0.7590422 0.395834 0.5123671 -0.7644433 0.3912883 0.3393955 -0.9385729 0.06238275 0.3359303 -0.9399943 0.05967992 0.2363325 -0.9710448 0.03491389 0.5694711 0.1051251 0.8152617 0.5641799 -0.3738059 0.7361863 0.5722686 0.1190496 0.811379 0.5623487 -0.377904 0.7354948 0.4067869 -0.7857065 0.4660364 0.1629788 -0.981235 0.103033 0.2621039 -0.9469704 0.1858724 0.4038135 -0.7885184 0.463868 0.1204777 -0.9844543 0.1278077 0.5950385 0.09131306 0.798493 0.5288107 -0.3773037 0.7602639 0.6095115 0.1208391 0.7835137 0.305981 -0.7867974 0.5360276 0.5274409 -0.3794801 0.7601323 0.3041718 -0.7881531 0.5350649 0.01436418 -0.9826554 0.1848838 0.1715607 -0.9370491 0.3041481 0.004896938 -0.9743567 0.224956 0.6228352 0.08588939 0.7776243 -0.06247884 -0.9667105 0.2481273 0.6408137 0.1040457 0.7606132 0.4895374 -0.3701714 0.7895103 0.2041695 -0.763458 0.612737 0.4879917 -0.3719904 0.7896122 -0.0653547 -0.9336504 0.352173 -0.06812214 -0.9340104 0.3506907 0.2022971 -0.7645498 0.6119964 0.6441358 0.08124589 0.7605842 -0.1773179 -0.9252502 0.3353663 0.4417296 -0.3487561 0.8265859 0.6896401 0.1308606 0.7122303 0.6629344 0.08756345 0.7435393 0.4928792 -0.3056233 0.814656 0.101081 -0.7136439 0.6931775 -0.2111451 -0.8786945 0.4281516 -0.1489601 -0.8729726 0.4644673 0.1056499 -0.7117836 0.6944079 -0.2880908 -0.8620641 0.4169524 0.9148553 -0.2015232 0.3498975 0.9031133 -0.1593846 0.3987268 0.8885876 -0.1125301 0.44469 0.8701869 -0.05657875 0.4894626 0.8524698 0.006777524 0.5227328 0.8021779 0.1295281 0.5828663 -1.44951e-4 -0.9999205 -0.0126118 -6.70002e-4 -0.9998919 -0.01469069 0 -0.9999574 -0.009231984 -0.4189233 -0.9034371 0.09113085 -0.4513366 -0.8922941 -0.01031994 -0.4237365 -0.9057359 -0.009479165 -0.3229871 -0.9301205 -0.1748005 -0.4440127 -0.8882246 -0.117941 -0.3960765 -0.9111062 -0.1140574 0.707355 0.004577517 0.7068437 0.7078469 0.004104912 0.706354 0.7082546 0.003603219 0.7059479 0.7090581 0.002358198 0.7051463 0.7071077 1.48968e-6 0.707106 0.7071048 2.49381e-6 0.7071089 0.7141139 -0.005651712 0.7000068 0.7089964 2.76803e-4 0.7052121 0.6787242 7.41029e-4 0.7343929 -0.2020025 -0.8484395 0.4892294 -0.4705632 -0.8393442 0.2721611 -0.473387 -0.8340765 0.2832335 -0.4162015 -0.8776567 0.2376872 -0.4561776 -0.8447028 0.2799631 -0.4694327 -0.8343262 0.2890204 -0.4522299 -0.8622989 0.2278788 -0.4151757 -0.8777239 0.2392278 -0.4663877 -0.8348957 0.2922869 -0.4155336 -0.8706414 0.263278 -0.4643027 -0.8646032 0.192053 -0.4801806 -0.8535674 0.2021126 -0.481458 -0.8666383 0.1309058 -0.4647725 -0.8599386 0.2109312 -0.4683038 -0.8644235 0.182931 -0.4704764 -0.8629807 0.1841642 -0.4860926 -0.8572657 0.1697345 -0.4900521 -0.8609444 0.1364691 -0.4861276 -0.8655043 0.1207573 -0.4610552 -0.8809291 0.1067338 -0.4962244 -0.8676235 0.03147923 -0.4632857 -0.8801629 0.1033431 -0.4963526 -0.8589547 0.1258216 -0.4939816 -0.8610604 0.1206532 -0.493997 -0.866242 0.07477986 -0.4624959 -0.8860082 0.03297209 -0.4802328 -0.8761584 0.04150992 -0.4906923 -0.8685566 -0.06950241 -0.480872 -0.8764255 0.0253095 -0.4716268 -0.881496 0.02309173 -0.4290171 -0.9018104 0.05179274 -0.4402626 -0.8968451 -0.04287093 -0.4436562 -0.8952342 -0.04153299 -0.4381151 -0.8988739 -0.009003639 -0.9999876 0.002013564 0.004572629 -1 -5.39082e-5 3.98456e-4 -1 -3.74985e-4 2.15369e-5 6.50333e-5 -4.24809e-4 1 -5.06079e-4 -5.57512e-5 1 -0.3866671 0.005125284 0.9222052 -0.4907739 -0.01192617 0.8712055 -0.9137964 0.0114395 0.4060117 -0.9404833 0.001508772 0.3398367 0.7815409 0 -0.623854 0.7818362 -3.9468e-5 -0.6234839 0.8991082 3.73172e-5 -0.4377264 0.9009633 -3.05202e-4 -0.4338952 0.9725511 2.96982e-4 -0.2326892 0.9749265 -5.2047e-4 -0.2225264 0.9998937 5.14272e-4 -0.01457464 0.9999999 -6.1295e-4 0 0.9779868 6.22991e-4 0.2086656 0.9749271 -4.91809e-4 0.222524 0.9051734 5.0537e-4 0.4250423 0.9009674 -2.841e-4 0.4338868 0.7840216 2.93386e-4 0.6207337 0.7574181 -0.003181219 0.6529224 0.7835052 0.03640609 0.620318 0.8094613 0.08876681 0.5804249 0.7949306 0.05166721 0.6044964 0.7886002 0.1922282 0.5840874 0.8077305 0.09172278 0.5823732 0.8285039 0.2440603 0.504 0.9021775 0.08131206 0.4236323 0.9646988 0.1642861 0.2058312 0.9650751 0.1678408 0.2011455 0.8773846 0.3659671 0.3102651 0.8706684 0.3939211 0.2945554 0.84607 0.5108379 0.1523495 0.9830855 0.182586 -0.01432925 0.940811 0.253387 -0.2250995 0.9552413 0.2291569 -0.1870864 0.8006203 0.5968629 -0.05255329 0.8098816 0.5852063 -0.04031652 0.6977439 0.6778292 -0.2317349 0.8720387 0.2435303 -0.4245488 0.6747517 0.6823436 -0.2812783 0.7464115 0.2964394 -0.5958135 0.9540877 0.0945965 -0.2841978 0.8288258 0.3057972 -0.4685466 0.721512 0.5009825 -0.477951 0.7578341 0.6213868 -0.1989122 0.4881312 0.8096939 -0.3257668 0.4235047 0.866217 -0.265164 0.4259545 0.8657706 -0.2626865 0.5695811 0.817996 -0.0803743 0.5655918 0.8202447 -0.08546644 0.6715647 0.7358602 0.08666449 0.6756845 0.7312198 0.09363776 0.7447523 0.616601 0.2552399 0.7488847 0.6071465 0.265603 0.7826386 0.4659016 0.4128106 0.7840834 0.4558948 0.4211569 0.7825797 0.3015406 0.5446488 0.7814826 0.2843788 0.5553501 0.7414415 0.09761834 0.663879 0.7413328 0.09719735 0.664062 0.4609431 0.8871734 0.02132809 0.369863 0.9045552 -0.2120883 0.6576377 0.5467707 0.5182225 0.6573826 0.6755391 0.333909 0.5922223 0.7895867 0.1607033 0.4596391 0.8880764 -0.007225751 0.7613793 0.2650636 0.5916442 0.6766765 0.1457223 0.7217159 0.7459275 0.3292196 0.5789703 0.6873157 0.6590932 0.305276 0.344111 0.9389194 -0.0042423 0.7285835 0.2467918 0.6389522 0.2611839 0.9543986 0.1445901 0.2660969 0.9474036 0.1778172 0.5303927 0.7093008 0.4643017 0.6950469 0.2734687 0.6649246 0.6934548 0.2690451 0.6683826 0.5303921 0.7093014 0.4643014 0.6667519 0.2527706 0.7011056 0.265514 0.8662636 -0.4231902 0.09697586 0.8238956 -0.5583832 -0.07391184 0.7423495 -0.6659236 -0.5468373 0.2954072 -0.7833924 0.7071074 0 -0.7071062 0.7071074 0 -0.7071063 0.4096584 0.8150839 -0.4096564 0.4105514 0.8140231 -0.4108698 0.5209229 0.6764619 -0.5206137 0.5232887 0.6720031 -0.5240046 0.6091818 0.5085818 -0.6084753 0.6114826 0.501312 -0.612189 0.6711772 0.3162326 -0.6704612 0.6720027 0.3105002 -0.672311 0.7031762 0.1074113 -0.7028557 0.7031536 0.1056004 -0.7031527 0.346513 0.8716984 -0.346512 0.3465135 0.8716986 -0.3465114 0.2925519 0.9102368 -0.293057 -0.2678399 -0.9621656 0.04999279 -0.3982558 -0.912675 0.09174168 -0.4276668 -0.8978684 0.1045632 -0.2519304 -0.9662386 0.05398416 -0.3096126 -0.9474257 0.08077543 -0.3494175 -0.9321954 0.09444266 -0.4345346 -0.8933826 0.1142257 -0.280151 -0.9559341 0.08778226 -0.08963286 -0.9955469 0.02919584 -0.4012507 -0.9057256 0.1365985 -0.2556677 -0.9617177 0.09865641 -0.427843 -0.8886474 0.1650946 -0.08917099 -0.9953272 0.03704524 -0.08508962 -0.9956766 0.03725343 -0.2684402 -0.9561001 0.1175266 -0.3924307 -0.902892 0.1754549 -0.08595442 -0.9952327 0.04608476 -0.2418359 -0.9618641 0.1278001 -0.4102364 -0.8858371 0.2167922 -0.3791043 -0.899583 0.2168653 -0.2532933 -0.9559711 0.1481958 0 -0.001597702 -0.9999988 -0.09886491 0.001510381 -0.9950997 -0.2393283 -0.001431763 -0.9709377 -0.3225793 9.85645e-4 -0.946542 -0.4647574 -0.001201629 -0.8854373 -0.513181 6.6851e-4 -0.8582803 -0.6631585 -5.31175e-4 -0.7484788 -0.6801328 3.99355e-4 -0.7330888 -0.8275149 -7.27179e-5 -0.5614439 -0.8230035 -4.12378e-4 -0.5680362 -0.9705158 1.58771e-4 -0.2410378 -0.9349754 0.01068174 -0.3545518 -0.9927102 0 -0.1205261 0.7083307 -0.006050109 0.7058548 0.2152365 -0.5630365 0.7979118 -0.1169027 -0.001858413 -0.9931417 -0.1411382 -0.1261157 -0.9819241 -0.1023715 0.383092 -0.91802 -0.02680289 0.5798054 -0.8143141 -0.01268023 0.7776266 -0.6285986 -0.00903517 0.7349285 -0.6780844 6.76478e-4 0.8060946 -0.5917865 -0.001083076 0.8526382 -0.5225006 0.01510781 0.9102824 -0.413712 0.01390153 0.92379 -0.3826472 0.02031373 0.9433811 -0.3310884 0.01342141 0.9722836 -0.2334191 0.02135747 0.9899111 -0.1400707 0.01795202 0.9967567 -0.07844686 0.02255636 0.999266 -0.03096526 -0.00253874 0.02714657 -0.9996283 0.7002778 -0.2541831 -0.6670847 0.8518192 0.376347 -0.3643722 0.4903462 -0.1436392 -0.8596094 0.3366999 -0.1316734 -0.9323601 0.2727416 -0.3670957 -0.889299 -0.1718104 -0.1699352 -0.9703624 0.880852 -0.2154452 -0.421525 0.5265473 -0.3589505 -0.7706508 0.4399925 -0.2661986 -0.8576392 0.831632 -0.169717 -0.5287573 0.6470477 -0.2984358 -0.7016164 0.6459695 -0.293848 -0.7045401 -0.9997085 0.009312331 0.02228057 0.8435385 0.4415805 -0.3056949 0.8523254 0.4236877 -0.3066433 0.8454534 0.3922232 -0.3624497 0.9999922 -0.00153613 0.003636598 1 -4.40956e-5 2.50424e-4 1 3.81855e-5 -2.15945e-4 0.9999846 -8.01703e-5 0.005550563 0.9999982 -0.001665532 0.001028537 0.9999847 -0.001161873 -0.005423545 1 1.33553e-7 0 1 -1.7308e-7 0 -0.9999848 0.001047372 -0.005425035 -0.9999829 4.0838e-4 -0.005849599 -0.9515626 -0.2171736 0.2176335 -0.9713483 -0.1540325 -0.1809874 -0.1102128 -0.3669064 -0.9237061 -0.1102118 -0.3774132 -0.9194633 -0.2887054 -0.9407582 -0.1778299 -0.2737306 -0.9393494 -0.2066264 -0.2643916 -0.9237189 -0.2772013 -0.2641182 -0.9020748 -0.3413252 -0.2502977 -0.8845947 -0.3935015 -0.2439798 -0.8332548 -0.4961456 -0.2302222 -0.8122005 -0.5360301 -0.2164828 -0.7395884 -0.6372945 -0.2044018 -0.7190129 -0.6642593 -0.1861287 -0.6226618 -0.7600318 -0.1848658 -0.6344809 -0.7505056 -0.194454 -0.6345547 -0.748016 -0.1570996 -0.5516017 -0.8191798 -0.1586353 -0.6123095 -0.77454 -0.190328 -0.6460444 -0.7391901 -0.1475515 -0.4868354 -0.8609414 -0.1367073 -0.4775584 -0.8678992 -0.1008981 -0.3363657 -0.9363107 -0.1080862 -0.3424044 -0.9333149 -0.008674979 -0.201533 -0.9794433 -0.05391848 -0.2044529 -0.9773904 -0.06813019 -0.1746635 -0.9822683 -0.003753602 0 -0.999993 -0.003177762 1.88114e-4 -0.9999949 -0.924865 0.0145747 -0.3800164 -0.840346 -0.009421348 -0.5419687 -0.4192137 0.008547782 -0.9078475 -0.3581739 1.38414e-4 -0.9336549 -5.61768e-4 -0.9999996 8.61526e-4 -0.05785393 -0.9983251 2.03282e-4 0.01407217 -0.9998986 -0.002243757 0.006702721 -0.9999766 -0.001414 -0.1145752 -0.9928461 0.03360474 0.01814156 -0.9998317 -0.002762138 -1 2.4553e-6 9.37157e-6 -1 3.471e-6 6.26154e-6 -1 3.7072e-6 4.56118e-6 -0.9999936 1.87408e-4 0.003590404 -0.9999987 0.001240789 0.001069128 -0.9999988 0.001306474 7.77942e-4 -0.9999991 0.001323223 5.06233e-4 -0.9999728 -4.82474e-4 -0.007373869 -0.9999992 0.001300036 2.45736e-4 -1 -1.84774e-4 -1.34456e-5 -0.9999991 -5.24427e-4 0.0012331 -0.9820407 -0.05352365 -0.1809182 -0.9995699 -0.01029503 -0.02745991 -0.9998227 -0.002960801 0.01859796 -1 -3.72739e-4 -1.38769e-4 -1 -1.77812e-4 -1.78148e-6 -0.268144 -0.9182851 -0.2912929 -0.3769391 -0.9068272 -0.1886302 -0.2701635 -0.9432855 -0.192936 -0.2694007 -0.9578105 -0.1001126 -0.3814453 -0.9167324 -0.1187486 -0.3789718 -0.9229676 -0.06716555 -0.3788593 -0.9039307 -0.1984311 -0.4489918 -0.8880225 -0.09910857 -0.3817814 -0.9164614 -0.1197565 -0.4380425 -0.8985005 -0.02856105 -0.3745914 -0.926162 -0.04364895 -0.02661353 -0.004262447 -0.9996367 0.04035472 0.04176372 -0.9983123 0.01030802 -0.005361795 -0.9999326 -0.8478515 0.4617443 -0.2606533 -0.1318634 0.8672449 -0.4801025 -0.2381291 0.7980723 -0.5535117 -0.9999969 0.002278864 0.001057028 -0.9999166 0.008903384 0.009352862 -0.9999995 6.26034e-4 8.82795e-4 -0.9999924 0.003165483 0.002286016 -0.9999995 1.41934e-5 0.001077771 -0.9999748 0.003959 0.005900263 -0.9999958 0.00228101 0.001818239 -0.9995821 0.02850633 0.004820764 -0.9999895 -0.003032743 0.003450095 -0.9999885 -0.004141032 0.002423942 -0.9999749 -0.00464183 -0.005358994 -0.9999969 0.001284539 -0.002148747 -0.9999857 7.17588e-5 -0.00536549 -0.9999889 0.001848459 -0.004346787 -0.9998855 -0.01435577 0.004785716 -0.999518 0.01269304 0.02833378 -0.9996761 -0.02527791 0.002978086 -0.9994114 0.01254117 0.03193277 -0.2049688 -0.896389 -0.3930326 -0.1773713 -0.8467383 -0.5015712 -0.1210752 -0.8553029 -0.5037833 -0.1893836 -0.823015 -0.5355187 -0.08551704 -0.818138 -0.5686273 -0.1608434 -0.7333628 -0.6605365 -0.15808 -0.7313078 -0.6634755 -0.1088457 -0.7426179 -0.6608111 -0.06638288 -0.6762052 -0.7337166 -0.1413075 -0.6168396 -0.7743005 -0.09200024 -0.6003286 -0.7944443 -0.1260766 -0.6019377 -0.7885275 -0.0326761 -0.5030406 -0.8636449 0.01233756 -0.4837051 -0.8751442 -0.08330184 -0.5792713 -0.8108673 0.004136621 -0.3080316 -0.9513671 -0.05414748 -0.3484268 -0.9357707 -0.03686916 -0.1281383 -0.9910708 -0.1125457 -0.8871731 -0.4475013 -0.1599214 -0.8984308 -0.4089589 -0.2550567 -0.8911059 -0.375335 -0.1993896 -0.9065436 -0.3720518 -0.3353774 -0.900687 -0.2761976 -0.151363 -0.9177034 -0.3673008 -0.1897391 -0.9227646 -0.3354171 -0.2407427 -0.9162504 -0.3202002 -0.3324269 -0.9079114 -0.2553218 -0.4054808 -0.8943605 -0.1889564 -0.3016276 -0.9156136 -0.2658432 -0.2854925 -0.9334266 -0.2172763 0.001473486 -0.9999989 0 0.005607068 -0.9999683 0.005659341 0.0150122 -0.999831 0.0106157 0.09285223 -0.9952319 0.02986824 -0.01021814 -0.9861576 -0.1654961 -0.001252889 0.004385948 -0.9999896 -1 -3.07588e-4 -2.61775e-4 -1 1.82076e-4 -1.48305e-4 -0.9999998 7.82143e-4 1.38939e-4 -0.9999911 -0.002938926 -0.00305736 -0.919341 0.2809095 -0.2755032 -0.6221973 0.5905665 -0.5139083 -0.7568091 0.5196204 -0.3965283 -0.7566587 0.5420819 -0.3655337 -0.690002 0.563445 -0.4543424 -0.6915109 0.646816 -0.3216236 -0.592689 0.682546 -0.4276105 -0.6344888 0.7677957 -0.08895921 -0.6615512 0.7496544 0.01919561 -0.4701437 0.863682 -0.18171 -0.4673519 0.864352 -0.1856825 -0.2423684 0.9696425 -0.03241991 -0.2656977 0.9622778 0.05853426 -0.9989492 -0.02723044 -0.03686493 -0.9539238 0.299892 -0.009709715 -0.9998636 0.01640158 -0.002003967 -0.6887392 0.6979256 -0.1963115 -0.6244903 0.7433002 -0.2398265 -0.6851564 0.7212867 -0.1015195 -0.5584479 0.8267541 -0.06792527 -0.1061056 0.9943397 0.005492329 -0.3220087 0.9467312 -0.003268539 -0.5527118 0.821884 -0.1379006 -0.4947187 0.8673378 -0.05457812 -0.9999946 0.001167833 -0.003091156 -0.9999359 0.01132225 4.71741e-4 -1 -7.94338e-5 2.14296e-4 -1 -2.04081e-4 1.31795e-4 0 1 0 0 1 0 0.001496374 0.9999989 1.30483e-4 0.02107721 0.9997777 6.08223e-4 -0.9093911 0.3380467 -0.2423477 -0.2822736 0.8794949 -0.3831586 -0.8813602 0.4281744 -0.1996769 -0.216539 0.9147156 -0.3411837 -0.8915888 0.424292 -0.1582587 -0.8936868 0.4196648 -0.1587622 -0.8327754 0.5508205 -0.05551427 -0.2426601 0.914548 -0.323602 -0.09216773 0.9737858 -0.2079577 -0.7833909 0.6076484 -0.1306221 -0.1685231 0.97171 -0.1654686 -0.01020032 0.9999002 -0.009778976 -0.9997458 0.02213084 -0.004313528 -0.9996268 0.02649706 -0.006659209 -0.998517 -0.008014261 -0.05384755 -0.9999911 -0.001081705 -0.00407958 -0.9999971 4.84433e-4 -0.002406001 -0.9999889 0.001256763 0.004557549 -0.9977687 0.03906857 0.05414134 -0.9996494 0.02639657 -0.002122759 -0.4188753 0.8940788 -0.1586395 0.006332933 -0.05714911 -0.9983456 -0.9267013 0.231075 -0.2963595 -0.9033291 0.2401164 -0.3554443 -0.9207643 0.2057535 -0.3314494 -0.4789333 0.4942929 -0.7254635 -0.5234429 0.4641446 -0.7145469 -0.3489233 0.4490349 -0.8225693 -0.9256721 0.1601096 -0.3427772 -0.4704908 0.310767 -0.8258707 -0.4432406 0.3249691 -0.8354238 -0.9004545 0.1531812 -0.4070838 -0.9173164 0.1272222 -0.3772866 -0.356484 0.2324959 -0.9049115 -0.9265884 0.08252972 -0.3669099 -0.2781873 0.1961504 -0.9402856 -0.4348198 0.127923 -0.8913851 -0.9397397 0.1050327 -0.3253574 0.002019226 0.9766474 -0.2148395 0.00341916 0.9261009 -0.3772609 0.002323269 0.1679984 -0.9857845 -0.9980025 0.05698579 -0.02726864 -0.9865032 -0.07302439 -0.1465567 -0.999157 0.006472051 0.04053902 -1 8.35988e-7 0 -1 -5.72268e-7 0 -1 5.30475e-7 0 -0.9999999 1.41112e-5 5.53611e-4 -1 6.204e-5 -2.3457e-5 -1 3.27814e-5 -2.61019e-4 -1 -1.84652e-4 -1.70201e-6 -0.9999247 0.001418232 0.01219159 -0.9999998 3.43512e-5 6.25155e-4 3.5936e-4 0.9999997 -8.50457e-4 -7.40409e-4 -0.9999868 0.005084753 -0.006421625 -0.999781 -0.01991832 -0.0062626 -0.9996674 0.02502143 -4.43714e-4 -0.9999997 7.56921e-4 0.06325995 0.9530309 -0.2961934 1.25689e-4 -1 -1.33372e-4 5.63404e-5 -0.9999976 -0.002221465 0 -1 0 0 -1 0 0 -1 0 -7.14057e-4 0.9999998 0 -6.58427e-4 0.9999998 2.28456e-4 0.9999979 -0.002053201 -2.09145e-4 1 -2.08662e-6 0 1 1.1923e-5 -4.75464e-5 1 2.06879e-5 -4.63189e-5 1 2.83237e-5 -4.43978e-5 1 3.43781e-5 -4.16779e-5 1 4.43815e-5 -3.80006e-5 0.9999709 -0.006778717 -0.003507316 0.9999766 0.005830824 -0.003573298 0.9999594 0.008340716 -0.00345385 0.9999153 0.01266342 -0.003040134 0.9997536 0.02213245 -0.001742243 0.9994719 0.03249943 0 -0.003580212 0.01693403 -0.9998503 0.004159033 0.07844877 -0.9969095 -0.00170207 0.1420554 -0.9898573 0.003893315 0.2488425 -0.9685362 5.62959e-4 0.2334299 -0.9723735 -4.43083e-4 0.3625256 -0.9319737 0.003127932 0.3826562 -0.9238855 -0.002499163 0.4791488 -0.8777301 0.004077374 0.5224629 -0.8526523 -0.002746105 0.5885288 -0.8084717 0.009340643 0.6493924 -0.7603963 8.39371e-4 0.7543671 -0.6564523 0.002449214 0.7603818 -0.6494718 -0.001861214 0.829112 -0.5590797 0.003916382 0.8526192 -0.5225182 -0.002659559 0.8927369 -0.4505707 0.003834605 0.9238658 -0.3826974 -0.006707966 0.9526135 -0.3041092 0.00412631 0.972359 -0.2334549 -0.004819989 0.9951824 -0.0979225 -6.43227e-4 0.996917 -0.07846164 0.7960914 0.05508351 -0.6026644 -0.003608047 0.004158914 -0.9999849 0.8287035 0.005043327 -0.5596652 1 0 -2.10932e-4 0 -1 0 -2.75147e-4 -1 2.19419e-4 -2.51305e-4 -1 1.21024e-4 -2.32415e-4 -1 5.30488e-5 -2.15541e-4 -1 0 -1.99076e-4 -1 -4.54391e-5 -1.76186e-4 -1 -1.01368e-4 -0.002018332 -0.9999904 0.003917396 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 4.31231e-4 0.9999994 -0.001105248 -0.07286357 0.9819766 -0.174393 0.09330505 0.9900181 0.1056337 -7.14978e-6 1 -1.71598e-5 -0.005053281 -0.001902341 -0.9999855 -3.0353e-4 0.002226948 -0.9999976 0.003479897 0.02061891 -0.9997814 -4.1924e-5 -0.005414128 -0.9999854 -0.001603662 0.2653653 -0.9641466 -0.002326369 0.6270264 -0.7789947 -3.30502e-4 0.8686488 -0.4954283 0.002951383 0.9821726 -0.1879587 0.01462584 -0.858115 -0.5132493 0.009435951 -0.3456978 -0.9382985 -0.008150696 0.2374205 -0.9713729 0.01098859 0.928408 -0.3713999 0.0137149 0.7779062 -0.6282308 0.9369826 -0.01281577 -0.3491408 0.9405003 -0.01829624 -0.3393001 0.3653695 0.01784718 -0.9306915 0.4224374 -0.009571671 -0.9063416 0.336315 0.1219647 -0.9338185 0.9430256 0.1321551 -0.3053489 0.9098356 0.06163299 -0.4103666 0.405523 0.2063769 -0.890483 0.9031061 0.2048665 -0.3773981 0.3568853 0.3739794 -0.8560212 0.5325916 0.5304426 -0.6595278 0.4165644 0.828377 -0.3745209 0.4164859 0.828327 -0.3747187 -0.9999765 0.004486918 -0.005196928 -1.08341e-5 0.9999998 8.26283e-4 -0.003672957 0.9999915 -0.001937806 0.04137194 0.9989054 0.02182757 -0.005012035 0.9999724 0.00551325 0.279649 0.8268695 -0.4879378 0.046036 0.9904432 -0.1300119 -0.007558941 0.9999521 0.006216526 0.364331 0.8298283 -0.4226678 0.7074095 -6.98707e-4 0.7068036 1 1.37355e-7 0 0.8558652 0.4400526 -0.2717511 0.8356484 0.4838561 -0.2599521 0.8914898 0.4130164 -0.186182 0.8625032 0.4843688 -0.1465446 0.8659469 0.4789409 -0.1440542 0.8894211 0.4488893 -0.08618885 0.9688905 0.2464345 -0.02283304 0.018386 0.974377 -0.2241683 -6.72768e-4 0.007193684 -0.9999739 0.1884723 0.9642542 -0.1862586 0.3229725 0.8809741 -0.3457939 0.7049357 -6.64896e-4 0.7092709 -0.908913 0.01398503 -0.4167514 -0.8437784 -0.03306895 -0.5356721 -0.4072045 -0.02035832 -0.9131101 -0.2515869 -0.06225973 -0.9658301 -0.7649502 0.5974295 -0.240685 -0.7288852 0.5546277 -0.4013909 -0.6450799 0.5945251 -0.4800124 -0.5304828 0.6080412 -0.5906555 -0.3042643 0.6476573 -0.6985437 -0.3062797 0.4931384 -0.8142527 -0.008366346 0.7124717 -0.7016509 0.9928977 0.05152982 -0.1072329 0.9985327 0.004922807 -0.05392879 0.948361 0.004379987 -0.317163 0.9999083 -0.01321697 0.002993822 0.9997985 0.0191459 -0.006029903 1 3.53775e-4 -1.09141e-4 0.9999999 -4.81745e-4 1.90219e-4 1 -1.59972e-6 -2.49136e-7 1 -4.14841e-6 0 0.9999588 0.007681846 -0.004833638 0.9999839 -0.003909945 0.004124104 -0.3255857 0.9092779 -0.2592448 -0.1336529 0.9147942 -0.3811675 0.359624 0.5876311 -0.7248175 -0.2118138 0.1687 -0.9626398 -0.2590506 0.1943407 -0.9461102 -0.7488939 0.08450257 -0.6572802 -0.8339809 0.148599 -0.5314078 0.927399 -0.3737809 -0.01480239 0.9298827 -0.3676535 -0.01221442 0.619563 -0.7844023 0.0292387 0.5544282 -0.8321262 0.01324939 0.3554904 -0.9331609 0.05326741 -0.06802839 -0.9976542 0.007637262 -0.1239227 -0.9919637 0.02551847 0.9902527 -0.0966559 0.1002869 0.9195506 -0.2222741 0.3240694 0.9503159 -0.2368006 0.2020526 0.9611477 -0.2175061 0.1699591 0.5934496 -0.6296312 0.5013803 -0.2910826 -0.795597 0.5313157 0.5608987 -0.6416709 0.5231168 0.1312948 -0.8026035 0.5818842 0.08355575 -0.8017702 0.5917628 0.9401589 -0.2953581 0.1698967 0.9463987 -0.2951787 0.1311457 0.9562072 -0.2717004 0.1088433 0.4956529 -0.7937101 0.3526366 -0.1879935 -0.9060434 0.3791356 -0.1217802 -0.9296506 0.3477349 0.5404254 -0.7761765 0.3247932 0.9413361 -0.3277946 0.08023113 0.9286494 -0.365149 0.06539589 0.961643 -0.2735056 0.02092009 0.507673 -0.8523334 0.1256826 -0.1156812 -0.9704195 0.2119055 0.5530733 -0.8265057 0.1048734 -0.1980081 -0.9683348 0.1520547 -0.06289684 -0.9965847 0.05350768 -0.2745485 -0.9611018 0.03011047 -0.3367016 -0.7377874 0.5850656 -0.3022667 -0.7344393 0.6076462 -0.3970602 -0.7189812 0.5704467 -0.2626711 -0.6725482 0.6918691 -0.4060206 -0.7579737 0.5105128 -0.4200506 -0.8499844 0.3179374 -0.3257352 -0.8443655 0.4253745 -0.383799 -0.8129539 0.4379547 -0.3632602 -0.9102383 0.198767 -0.2801457 -0.9154125 0.2890301 -0.3581888 -0.9128196 0.1961153 -0.3138513 -0.9461466 0.07939928 -0.3856433 -0.9094269 0.1556345 -0.3279863 -0.9446426 -0.008694589 -0.427953 -0.9033969 0.02702939 -0.2539839 -0.9609709 -0.109668 0.9937127 0.1119608 -1.26434e-7 0.9426113 0.3338922 1.18998e-5 0.8467501 0.5319909 -3.61206e-7 0.7070948 0.7071188 -5.93583e-6 0.5373345 0.8433693 7.16338e-6 0.3546353 0.9350048 -2.16994e-4 -0.9254779 -0.1788794 -0.3339054 -0.8985208 -0.09204894 -0.4291705 -0.9743472 0.04967176 -0.2194998 0.002589523 0.7814381 -0.6239776 0.001488924 0.7070907 -0.7071213 0.002418816 0.4763811 -0.8792357 1 -6.98387e-6 0 -7.97776e-4 -0.999953 -0.009672939 -0.002029955 -0.9999897 0.004080832 -0.03005784 -0.9965494 0.07736909 -0.003503561 -0.9995632 -0.02934694 -0.02316039 -0.9993519 -0.02755737 1 -7.54539e-5 3.83553e-5 1 1.95094e-6 0 1 -2.45063e-6 0 1 -8.57932e-7 0 1 2.25101e-4 -5.17223e-5 1 -2.05414e-4 3.16624e-5 1 2.65882e-6 0 1 -1.72558e-6 0 1 3.78805e-6 0 1 1.0671e-6 0 0.9999998 8.27771e-4 -7.31935e-5 1 -4.35883e-5 -1.89105e-6 0.9999979 -0.002070128 1.34167e-4 1 6.83156e-5 -1.43043e-7 0.1415971 0.9899244 2.81365e-5 0.1085429 0.9940918 -3.38015e-5 0.2140609 0.9768198 0.001014351 0.5328855 0.8461874 4.48019e-5 0.7072293 0.7069843 -7.50871e-6 0.8463197 0.5326755 6.46216e-6 0.9443244 0.3290158 -3.28754e-5 0.993865 0.1106007 -1.1726e-5 0.1760877 -0.9063529 -0.3840803 0.09975576 -0.9386106 -0.3302407 0.1526376 -0.9216807 -0.3566601 0.1807117 -0.9037523 -0.38804 0.2034283 -0.8985968 -0.3887683 0.1517844 -0.9223296 -0.3553445 0.2045128 -0.8979811 -0.389621 0.1649194 -0.9223597 -0.3493624 0.2273359 -0.8935043 -0.3872578 0.22556 -0.8945078 -0.3859775 0.2231776 -0.8960372 -0.3838087 0.2207193 -0.8979066 -0.3808501 0.2123153 -0.9059876 -0.3662087 0.2285431 -0.9219208 -0.3127782 0.2369599 -0.9159456 -0.3238729 0.1874396 -0.9391138 -0.2879788 0.2739867 -0.9338153 -0.2300445 0.2413733 -0.9499744 -0.1982114 0.2129999 -0.9592269 -0.185782 0.3897479 -0.8952633 -0.2158708 0.2372152 -0.899676 -0.3664863 0.1294394 -0.9553148 -0.2657429 0.2702637 -0.91424 -0.3018655 0.2598927 -0.9169959 -0.3026125 0.2548688 -0.9439575 -0.2097288 0.2616177 -0.9163236 -0.3031622 -0.2802768 -0.9591352 -0.03879255 -0.1052476 -0.9894365 -0.09969222 -0.03191983 -0.9734483 -0.2266705 -0.02945131 -0.9637354 -0.2652298 4.13872e-4 -0.9551025 -0.2962756 -0.04267185 -0.9766634 -0.2104943 0.1775664 -0.9051184 -0.3863043 0.1196913 -0.927413 -0.3543718 -0.1617613 -0.975425 -0.1495974 -0.281467 -0.9587406 -0.03991204 -0.3051204 -0.9314032 -0.1984683 -0.2764685 -0.943381 -0.1832969 -0.2720334 -0.9455534 -0.1786801 0.5017039 -0.8382288 -0.2136954 0.1614738 -0.9473162 -0.2766194 -0.123639 -0.9910038 -0.05123317 0.02714645 -0.9987475 -0.04203009 0.3227751 -0.9163478 -0.2369031 0.3590193 -0.9024697 -0.2380201 0.3594515 -0.9318961 -0.04862475 0.3544587 -0.9338448 -0.047885 0.7632202 -0.6257334 -0.1610989 0.6172836 -0.7851406 -0.05015242 0.7631555 -0.6258116 -0.161101 0.7628613 -0.6460998 -0.02445119 0.9400089 -0.3270505 -0.09706383 0.9458875 -0.3238125 -0.02103495 0.9867432 -0.1582716 -0.03588891 0.9274069 -0.3737763 -0.0144149 0.9999996 -9.17838e-4 -2.27767e-4 1 -4.28147e-4 -1.50951e-4 0.3310409 -0.8797057 -0.3413648 0.3289586 -0.8802478 -0.3419799 0.3250807 -0.8809494 -0.343876 0.3947951 -0.8588355 -0.3264025 0.7653114 -0.5993843 -0.2345997 0.7943932 -0.5678073 -0.215718 0.9870088 -0.1490936 -0.05987393 0.9900225 -0.1313964 -0.05089843 0.9906854 -0.1272195 -0.04855513 0.9999996 -9.87542e-4 -2.79771e-4 0.1294597 -0.6409711 -0.7565689 0.1100846 -0.8002188 -0.5895178 0.1579405 -0.6826351 -0.7134873 0.1673113 -0.7614156 -0.6263013 0.1915856 -0.7975618 -0.5720055 0.1797449 -0.7140406 -0.6766372 0.2087545 -0.7859613 -0.5819678 0.2087785 -0.7836321 -0.5850917 0.2189413 -0.8235958 -0.5232158 0.2829174 -0.7827305 -0.5543383 0.253291 -0.8631873 -0.4367509 0.2529324 -0.8737232 -0.4154915 0.2547164 -0.9441245 -0.2091617 0.9410039 -0.3218023 -0.1046664 0.9371364 -0.3334425 -0.102916 0.9219451 -0.3727718 -0.1051592 0.9376876 -0.3328194 -0.0998665 0.5865759 -0.7795065 -0.219769 0.6552885 -0.7211241 -0.2248937 0.6751486 -0.702938 -0.2237244 0.4822707 -0.842445 -0.2402119 0.9468972 -0.311807 -0.07850086 0.5543984 -0.8077327 -0.2005255 0.9431468 -0.3247797 -0.07065665 0.9445284 -0.3207141 -0.07077223 0.9250382 -0.3721839 -0.07605046 0.6514732 -0.7442591 -0.1471771 0.6790699 -0.7182093 -0.1517875 0.6141547 -0.7746479 -0.1507805 -0.6515077 -0.5922797 -0.4740701 0.2983582 -0.7588099 -0.5789559 0.4743295 -0.6923699 -0.5437237 0.4932813 -0.7235894 -0.4827961 0.6180691 -0.6309404 -0.4689403 0.6272729 -0.6254296 -0.4640761 0.7773426 -0.5031926 -0.3775391 0.7745686 -0.6067619 -0.1785598 0.8311404 -0.4504856 -0.3259884 0.9231412 -0.3639666 -0.1238499 0.8511587 -0.4265249 -0.3059502 0.969431 -0.199123 -0.1433655 0.9708631 -0.2302814 -0.06629961 0.9781036 -0.1713885 -0.1180644 0.2213925 -0.6612526 -0.7167499 0.1979601 -0.6884124 -0.6977823 0.3015044 -0.6507887 -0.696828 0.3922005 -0.8019897 -0.4505456 0.2343123 -0.8909326 -0.3890205 0.6222634 -0.5655628 -0.5412273 0.2120811 -0.9425153 -0.2582378 0.6318198 -0.5640345 -0.5316662 0.6980609 -0.5647023 -0.4402526 0.590187 -0.7511847 -0.2956365 0.8333127 -0.4261968 -0.3520601 0.8532586 -0.4038364 -0.3299489 0.6121371 -0.7613176 -0.2137373 0.9731557 -0.2195509 -0.06903213 0.04483354 -0.9568561 -0.2870826 0.1242132 -0.7776114 -0.6163535 0.05319547 -0.9818876 -0.1818436 0.1450359 -0.8415976 -0.5202675 0.04814887 -0.9834967 -0.1744017 0.3857413 -0.8689323 -0.3100977 0.4760893 -0.8328139 -0.2824183 0.7946657 -0.5658835 -0.2197324 0.9397612 -0.3314501 -0.08360534 0.9904782 -0.1295601 -0.04655432 0.9907284 -0.1274753 -0.04698431 1 -7.63032e-7 -4.63851e-7 1 -8.55687e-6 -4.98491e-7 1 1.34337e-5 -5.12035e-7 1 -8.08992e-6 -5.13496e-7 1 -1.03492e-5 -5.14218e-7 1 1.38018e-5 -5.14443e-7 1 -1.61781e-5 -5.14375e-7 1 5.23183e-6 -5.14167e-7 1 1.16989e-6 -5.13937e-7 1 -1.88309e-5 -5.13782e-7 0.2570858 -0.9147795 -0.3115853 7.75979e-6 1 1.09455e-5 -1.85183e-4 1 9.8128e-5 0 1 7.09662e-7 0 1 -2.98879e-7 0 1 -1.00155e-6 2.61636e-5 1 0 -1 5.34251e-7 0 -1 1.14108e-6 0 -1 -1.48358e-6 0 -0.9953162 0.09667277 3.32156e-4 -0.9938519 0.1107189 -8.74835e-6 -0.9564408 0.2919265 -2.64973e-4 -0.9442882 0.3291193 4.82949e-4 -0.8753359 0.4835152 -4.41924e-4 -0.8461895 0.532882 5.55476e-4 -0.7499316 0.6615152 -5.46581e-4 -0.7070015 0.7072119 5.18649e-4 -0.5326669 0.8463245 -9.26646e-4 -0.5787569 0.8154997 7.57585e-4 -0.3676887 0.9299489 -5.17529e-4 -0.1229472 0.9924028 0.004548311 -0.2225453 0.9749224 0 -0.6145356 0.6681406 0.4194452 -0.6699659 0.5685433 0.4773932 -0.6955999 0.5392723 0.4746854 -0.726719 0.4522794 0.5170328 -0.7579405 0.3955738 0.5186979 -0.7692406 0.3343254 0.544514 -0.7994202 0.218225 0.5597367 -0.7989186 0.2414311 0.5508541 -0.814423 0.1072092 0.5702821 -0.820191 0.08089405 0.5663416 -0.8172328 -0.002174139 0.5763037 -0.8202545 -0.08187985 0.5661081 -0.8137095 -0.111968 0.5703859 -0.8041676 -0.2206366 0.5519366 -0.7951281 -0.2425445 0.555827 -0.7677845 -0.339664 0.5432635 -0.7576175 -0.3967864 0.5182434 -0.7246111 -0.4570474 0.5157971 -0.6953606 -0.5403892 0.4737648 -0.6676818 -0.5720394 0.4764159 -0.614748 -0.6684996 0.4185611 -0.0668801 0.9965814 0.04850238 -0.2002549 0.9693779 0.1421428 -0.3273844 0.9157119 0.233005 -0.4010217 0.873254 0.2767834 -0.4474981 0.8370589 0.3147663 -0.4963673 0.7955765 0.347387 -0.5841711 0.7003335 0.4102159 -0.5565637 0.7355448 0.3862782 -0.5970784 0.6872137 0.4138053 -0.6456247 0.6139581 0.4541193 -0.6946043 0.5318456 0.4844226 -0.719582 0.4756093 0.5059621 -0.7552493 0.3899239 0.5268376 -0.5735784 8.76742e-7 -0.8191507 -0.596748 0.02602171 -0.8020067 -0.5698591 -0.0140872 -0.8216217 -0.5698394 0.01636141 -0.8215933 -0.5735771 0 -0.8191516 -0.5735771 5.23585e-7 -0.8191517 -0.5735672 -5.67146e-6 -0.8191586 -0.5735774 3.77233e-6 -0.8191514 -0.57358 -5.24715e-7 -0.8191497 -0.5735659 -4.41491e-6 -0.8191596 -0.5735852 -2.43034e-6 -0.819146 -0.5735686 1.42376e-6 -0.8191576 -0.5735719 5.24574e-6 -0.8191552 -0.5735785 -4.78774e-7 -0.8191507 -0.573571 -2.0405e-6 -0.8191559 -0.5735775 -2.06499e-6 -0.8191514 -0.5735899 1.08269e-5 -0.8191427 -0.5735756 0 -0.8191527 -0.5735778 -1.65241e-6 -0.8191511 -0.5735775 1.5844e-7 -0.8191514 -0.5735516 0 -0.8191695 -0.5736018 -1.0471e-6 -0.8191344 -0.5735957 -1.05184e-6 -0.8191387 -0.5735033 -2.32154e-7 -0.8192033 -0.4671649 -5.29395e-5 -0.8841702 -0.4782204 -4.52959e-6 -0.8782399 -0.5784782 -4.11403e-6 -0.8156979 -0.5784758 -4.05922e-6 -0.8156995 -0.573583 -5.92388e-7 -0.8191475 -0.5735934 1.14611e-6 -0.8191401 -0.5735886 1.04006e-6 -0.8191435 0.5451903 -0.001592993 0.838311 0.5814579 0.005036711 0.8135609 0.5735809 -4.22789e-6 0.8191491 0.5735707 -7.15342e-7 0.8191562 0.573575 -3.53788e-7 0.8191532 0.5735769 2.4586e-7 0.8191518 0.5730837 -6.01709e-4 0.8194968 0.576574 -6.03849e-4 0.8170447 0.5735765 -3.83947e-7 0.8191521 0.5735775 0 0.8191514 0.5735677 4.05024e-6 0.8191582 0.5735793 0 0.81915 0.5735747 0 0.8191533 0.5735728 -1.91475e-7 0.8191547 0.5735787 9.57364e-7 0.8191505 0.5640264 0.006244063 0.8257333 0.5721818 -0.001323938 0.8201258 0.5735749 7.65882e-7 0.8191531 0.5750188 -0.001310944 0.8181392 0.5745356 -0.001262247 0.8184786 0.5689357 -0.001260995 0.8223811 0.5756536 -0.001978397 0.8176913 0.5202558 -0.001649141 0.854009 -0.3737807 -0.8890925 0.264202 -0.3830876 -0.8839069 0.26824 -0.4659548 -0.8231451 0.3245278 -0.48598 -0.8035161 0.343781 -0.5489001 -0.7437035 0.3815938 -0.5791238 -0.7048527 0.409632 -0.6157022 -0.6607896 0.4292646 -0.65792 -0.5901657 0.4678095 -0.69672 -0.527899 0.4856994 -0.7249998 -0.4620863 0.5107363 -0.7377006 -0.4362507 0.5152506 -0.7706735 -0.3363095 0.5412563 -0.7731431 -0.3299044 0.5416761 -0.7964227 -0.2378594 0.5559983 -0.8117133 -0.1416932 0.5666078 -0.8013281 -0.1987029 0.5642609 -0.8151633 -0.08812069 0.5724889 -0.8136717 -0.09843355 0.5729305 0 -1 0 -8.20801e-6 -1 -1.41044e-4 6.22223e-4 -0.9999976 0.002142488 -5.3329e-4 -0.9999995 -8.69812e-4 -4.23781e-4 -0.9999998 -6.60052e-4 1.02974e-4 -1 1.2552e-4 0 -1 1.25367e-6 0 -1 0 0 -1 0 0 -1 6.58043e-7 2.4876e-5 -1 -2.07211e-5 5.7119e-6 -1 4.06404e-5 5.82966e-4 -0.9999997 4.64723e-4 8.29458e-5 -1 -1.86727e-4 -0.9958124 -0.09141999 -4.18046e-6 -0.9916259 -0.1291419 7.52288e-4 -0.9611123 -0.2761576 -4.79873e-4 -0.9242274 -0.3818414 9.40605e-4 -0.8923059 -0.4514312 -2.88271e-4 -0.7930088 -0.6092101 4.36203e-4 -0.7969281 -0.6040741 5.92197e-4 -0.6828801 -0.7305305 -3.0857e-4 -0.6089604 -0.7932002 8.8924e-4 -0.5533295 -0.8329625 -1.51997e-4 -0.3864821 -0.922297 2.46224e-4 -0.4080954 -0.9129389 8.44022e-4 -0.2498838 -0.9682758 -4.79412e-4 -0.08251857 -0.996589 0.001163482 -0.1263754 -0.9919826 0 -0.07920688 -0.9957805 0.04634213 -0.08133816 -0.9951571 0.0551964 -0.2231199 -0.961896 0.1580313 -0.3785265 -0.8859114 0.2681024 -0.2323501 -0.9560111 0.1790422 -0.07235914 -0.9958189 0.05575758 -0.07481259 -0.995135 0.06410485 -0.9113514 3.7257e-4 0.4116294 -0.632664 0.006780505 0.7743968 -0.4284642 -0.001967251 0.9035567 -0.177915 0.002121746 0.9840435 0.1312291 -0.006550073 0.9913305 0.3513884 0.001372754 0.9362289 -0.0370506 -0.009188771 0.9992712 -0.02604758 -0.01111447 0.9995989 -0.4297068 0.04045569 -0.9020619 -0.1441454 0.1977762 -0.969591 -0.6375281 -0.06058651 -0.7680412 -0.407925 0.05693882 -0.9112383 -0.5887272 -0.02189135 -0.8080353 -9.38921e-4 -0.9999993 -7.46211e-4 3.74548e-5 -1 -2.06066e-4 1.49649e-4 -1 -1.82447e-4 4.65845e-5 -1 -1.78874e-4 -0.8191179 0 0.5736253 -0.8191519 6.70928e-5 0.5735766 -0.8189911 0.01982569 0.5734637 -0.8174414 0.01111662 0.5759046 0.1307982 -0.1086906 0.985433 -0.4283635 -0.006013989 0.9035865 -1 2.35072e-6 0 -1 -1.94983e-6 0 -1 -3.31192e-7 0 -1 9.72851e-7 0 -1 1.16886e-6 0 -1 -2.28419e-7 0 -1 2.35815e-6 0 -1 -2.02953e-6 0 0 0.9965911 -0.08250045 0.06911551 0.9804314 -0.1843297 0.02892476 0.9690525 -0.2451544 0.0317645 0.9154687 -0.4011336 0.07992714 0.8824904 -0.4634895 0.008346259 0.8374336 -0.5464755 0.370607 0.8964493 -0.2429594 -1.88177e-4 0.9827821 -0.1847681 0.8780164 0.3767946 -0.2951492 -0.9946448 1.84568e-5 -0.1033527 -0.928736 -0.03123027 -0.3694241 -0.4240022 -0.002488791 -0.9056577 -0.4016724 -0.007183134 -0.9157553 -0.9476478 0.007473647 -0.3192304 -0.9291578 -0.003299117 -0.3696687 -0.4239902 0.005134165 -0.9056524 -0.3221305 0.1621391 -0.9327073 -0.9478265 0.0126487 -0.3185359 -0.9126432 0.1132107 -0.3927668 -0.4581097 0.3230206 -0.8281264 -0.3790973 0.4294723 -0.8196578 -0.9159575 0.2138344 -0.339554 -0.01607769 0.9635441 -0.2670662 -0.5356388 0.5537267 -0.6375561 -0.009805262 0.9999512 0.0012753 0.0913279 0.8551701 -0.5102385 0.5117732 0.8484937 -0.1347095 0.1016802 0.3071302 -0.94622 0.3689035 0.3944309 -0.8416261 0.2211357 0.6097297 -0.7611365 0.09709531 0.5856058 -0.8047599 0.288851 0.3260385 -0.9001467 0.5551017 0.8052276 -0.2084962 0.4777544 0.6929338 -0.5399941 0.6171602 0.4671947 -0.6331212 0.5836918 0.4221096 -0.6936335 0.6541031 0.4721949 -0.5909156 0.793572 0.493095 -0.3565121 0.6211355 0.7436337 -0.2473857 0.8989672 0.4319052 -0.07291066 0.06064045 0.008268475 -0.9981254 0.1898587 0.01736623 -0.9816579 0.3144187 0.06473422 -0.9470747 0.3685195 0.05476403 -0.9280055 0.6977545 0.08162385 -0.7116715 0.768581 0.1165354 -0.6290492 0.7837696 0.1100592 -0.611222 0.9246711 0.1036548 -0.3663867 0.9797675 0.135512 -0.1472829 0.9747995 0.1037114 -0.1975095 0.4188417 -0.004719018 -0.9080471 0.3152425 0.02584499 -0.9486592 0.7737935 -0.01777899 -0.6331884 0.9188041 0.01693844 -0.3943504 0.9798122 -0.007395327 -0.1997834 -0.003050327 0.2629845 -0.9647953 0.01788187 0.787659 -0.6158519 -0.00582534 0.9642863 -0.2647983 0.4269145 0.887957 -0.171104 0 1 -1.88224e-7 4.84643e-4 1 1.49723e-4 0.6559143 0.7316629 -0.1855962 0.4223842 0.8785119 -0.223178 0.9611114 0.2666363 -0.07190257 0.906399 0.3705635 -0.2027896 0.9952076 0.09552538 -0.02090531 0.6556635 0.7319176 -0.1854776 0.9672288 0.2342543 -0.0979461 0.5402349 0.7039797 -0.4610412 0.9612367 0.2306609 -0.1510621 0.9615778 0.2301017 -0.1497381 0.6400693 0.6627621 -0.3886616 0.336782 0.8162149 -0.4694373 0.4384584 0.7956957 -0.417879 0.9672638 0.1843381 -0.174414 0.2427804 0.7008506 -0.6707206 0.9625434 0.1663325 -0.2141118 0.9587322 0.1680014 -0.2293648 0.7290444 0.4199087 -0.5405284 0.2887509 0.5497648 -0.783825 0.3446028 0.5650439 -0.7496495 0.6871017 0.4172092 -0.5948343 0.2389392 0.4522023 -0.8593145 0.9669207 0.1112571 -0.2295352 0.9641485 0.0859763 -0.2510494 0.9549828 0.0792663 -0.2858758 0.7198964 0.2248793 -0.656642 0.6975048 0.2159202 -0.6832756 0.3005535 0.2873897 -0.9094366 0.3263987 0.2999854 -0.8963665 0.2370513 0.1561917 -0.9588592 0.9661811 0.02308201 -0.2568294 0.9595911 -1.60644e-4 -0.2813985 0.7082721 -4.0201e-4 -0.7059395 0.3103312 4.80773e-4 -0.9506284 6.5404e-4 0.08508783 -0.9963732 -0.006361961 0.2263588 -0.9740233 5.39896e-4 0.463678 -0.8860037 0.002649366 0.4166054 -0.9090837 0.003751516 0.6552975 -0.7553617 -0.01024723 0.7875786 -0.616129 1.73446e-4 1 3.12265e-4 -0.006393909 0.7361786 -0.6767572 0.005308091 0.7224562 -0.6913964 -0.005446672 0.6148737 -0.7886069 0.004332542 0.6019061 -0.7985552 -0.004440844 0.4768109 -0.8789948 0.003296315 0.4656894 -0.8849421 -0.003381669 0.3257777 -0.9454404 0.002203047 0.3173666 -0.9483004 -0.002267897 0.1658715 -0.9861448 0.001059412 0.1607745 -0.9869907 -0.001107633 0 -0.9999994 -0.00178337 0.00533092 -0.9999843 5.60904e-4 0.002031564 -0.9999978 -0.981355 -6.78631e-4 -0.1922031 -0.9547787 0.005409359 0.2972679 6.95189e-4 -0.005326747 -0.9999856 -1.64427e-4 0.01316916 -0.9999133 0.001481711 -0.004424214 -0.9999892 -1.31833e-5 1.70224e-4 -1 -1 -5.56023e-5 -1.01938e-4 -1 -1.63698e-5 -6.26694e-5 -1 1.91721e-7 0 -1 -1.9982e-7 0 -1 2.20573e-7 0 -1 2.29594e-7 0 -1 -3.66957e-7 0 -1 -5.90653e-7 0 0 1 3.07766e-5 -3.22887e-5 1 -8.761e-5 0.002125442 0.9999445 0.01032942 1 -1.49479e-6 0 1 1.49152e-6 0 0.9999997 -7.90194e-4 -5.36022e-4 0.9999995 5.91535e-4 -8.07801e-4 0.9999994 8.55641e-4 -8.08263e-4 0.9999992 0.001136243 -7.39887e-4 0.9999989 0.001393258 -5.81919e-4 0.9999988 0.001550436 -3.39324e-4 0.9999068 0.01260364 0.005259156 0.9999236 0.01036888 0.006735622 0.9999417 0.007849693 0.007413506 0.9999572 0.00547719 0.007458925 0.9999601 -0.007295846 0.005170047 -1 5.97977e-7 0 -1 -2.36604e-7 0 -1 0 0 0.9994336 -0.004753708 0.03331792 0.06021386 -0.9614261 -0.2683916 -0.03233987 -0.9988745 -0.03469848 0 -0.9965766 -0.08267515 0.07446533 -0.9666551 -0.245016 0.0858162 -0.9122486 -0.4005475 -0.006095767 -0.7352719 -0.6777449 0.004936575 -0.7224558 -0.6913995 -0.005070388 -0.6135423 -0.7896457 0.003815054 -0.6019042 -0.7985593 -0.003908514 -0.4750596 -0.879945 0.002688229 -0.465701 -0.8849381 -0.002764582 -0.3236512 -0.9461725 0.001474738 -0.3173598 -0.9483041 -0.001520395 -0.1633164 -0.9865726 1.69604e-4 -0.1607686 -0.9869922 -1.71931e-4 0.001393139 -0.9999991 0.3194919 -0.9396709 -0.1222442 0.209841 -0.9771463 -0.03394126 0.6593334 -0.7364569 -0.1513628 0.4536312 -0.8782142 -0.1515212 0.3850248 -0.8889108 -0.2481807 0.20208 -0.9608408 -0.1896013 0.7056624 -0.6878014 -0.1702053 0.9568101 -0.2851912 -0.05639654 0.9452171 -0.323097 -0.04661786 0.9672303 -0.2343196 -0.09777539 0.674718 -0.6893954 -0.2636089 0.7343981 -0.5682116 -0.3712075 0.9611237 -0.2315596 -0.150404 0.961441 -0.230235 -0.1504097 0.6770417 -0.5849289 -0.4466238 0.1695755 -0.8895326 -0.4242357 -0.0284757 -0.9336646 -0.3570148 0.3298851 -0.7504199 -0.5727529 0.2430607 -0.7007983 -0.6706738 0.967261 -0.1845206 -0.1742365 0.9633613 -0.1587324 -0.2161924 0.9604315 -0.1711154 -0.2197518 0.7297238 -0.4200769 -0.53948 0.2807964 -0.5776919 -0.7664369 0.323984 -0.5424765 -0.775083 0.6862874 -0.4170544 -0.5958821 0.239113 -0.4521934 -0.8592708 0.9669205 -0.1115496 -0.229394 0.9650139 -0.07041132 -0.2525678 0.9598044 -0.09123736 -0.2654268 0.7207739 -0.2253292 -0.655524 0.69656 -0.2155162 -0.6843661 0.2943922 -0.3032954 -0.906281 0.3181262 -0.2847676 -0.9042694 0.2370921 -0.1561846 -0.9588503 0.9661915 -0.02346968 -0.2567551 0.3096097 0 -0.9508638 0.7093663 3.56237e-4 -0.7048399 0.06717389 -0.8450867 -0.5303925 -0.008420288 -0.7120541 -0.7020742 -0.002616405 -0.2134634 -0.9769476 -0.1159188 -0.9922445 -0.04487502 -0.01912593 -0.9996887 -0.01602381 0.004272639 -0.9999896 -0.001626551 5.02594e-7 0 1 2.67644e-4 -0.9999973 -0.002327382 -0.001648843 -0.9999987 -6.06001e-5 0.007037043 -0.9999753 0 0 -0.9998682 0.01623815 -2.13303e-4 -0.9999998 7.11689e-4 -0.01884585 -0.9998186 0.002763986 0.06188428 -0.9980834 1.64161e-4 0 0 -1 -0.0257321 0.01376366 -0.9995742 1.18107e-4 -0.001168966 -0.9999993 -0.001138687 0.004077076 -0.9999911 1.72215e-4 1.32473e-4 -1 1.98768e-4 0 -1 0.99989 -0.001582205 0.0147497 1 -2.22881e-4 2.3199e-5 1 -1.46311e-4 -2.28958e-5 1 -9.7248e-5 -4.94865e-5 1 -6.44529e-5 -6.49377e-5 1 -3.87177e-5 -7.56603e-5 1 -1.31637e-5 -8.40488e-5 1 0 -8.75213e-5 0.3469863 0.001225888 0.9378695 0.4007259 0.009060919 0.9161533 0.8401724 -0.009489953 0.5422366 0.9262061 0.01501661 0.3767185 -0.002370595 -0.1991148 -0.9799734 -4.51705e-5 -0.1547338 -0.9879562 0.002064943 -0.4531015 -0.8914566 -0.001380801 -0.5453383 -0.8382149 0.003058671 -0.7072941 -0.7069129 -3.77845e-4 -0.8030017 -0.5959766 9.11265e-4 -0.8916413 -0.4527418 -4.06847e-4 -0.9075418 -0.4199615 0.002854824 -0.9879705 -0.1546159 0.2732821 -0.9515416 -0.1410167 0.4491711 -0.8881704 -0.09694778 0.6632948 -0.3869379 -0.6405615 0.4696519 -0.7935276 -0.3869642 0.7026602 -0.4497786 -0.5513329 0.44405 -0.770565 -0.457219 0.4102658 -0.3960631 -0.8214719 0.1931112 -0.7286277 -0.6571224 0.2827866 -0.4098832 -0.8671953 0.8776828 -0.1424724 -0.4575748 0.4447393 -0.03172421 -0.8950981 0.4111305 -0.002128958 -0.911574 0.874166 0.0112794 -0.4854962 0.8668503 0.007018983 -0.4985191 0.4439841 0.02422314 -0.8957073 0.1957102 -0.02095705 -0.9804379 0.1084851 -0.8972765 -0.4279323 0.007833182 -0.8368299 -0.5474071 0.2290927 -0.9608433 -0.155874 0.2715669 -0.9124261 -0.3061537 0.2563239 -0.9157137 -0.3094618 0 1 7.55274e-5 -0.004107058 0.9999384 -0.01030761 0.01770657 0.9997271 0.01523762 6.61101e-4 0.9999999 -1.04788e-4 -1 -9.24796e-7 0 -1 -6.37225e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 5.48251e-7 0 -1 -3.69006e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.35052e-7 0 -1 2.20279e-7 0 -1 -2.03432e-7 0 -1 3.51244e-7 0 -0.9999865 0.004831016 0.001937687 -0.9999998 -8.12147e-4 -4.55294e-5 -1 -8.35031e-5 0 1 3.24671e-5 -1.07969e-4 1 2.51967e-7 -4.2614e-5 1 0 0 1 0 0 1 1.77824e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -3.56076e-7 0 1 -2.73599e-7 0 1 0 0 1 0 0 1 3.78746e-7 0 1.23536e-5 -8.07357e-5 -1 4.05288e-4 7.36185e-5 -1 3.61392e-5 -6.36628e-5 -1 0 -0.9889355 -0.1483462 -0.07778793 -0.993562 -0.08236414 0.01710331 -0.9692338 -0.2455474 0.01202851 -0.9156532 -0.4017891 -0.09268277 -0.8334745 -0.5447295 -0.01339972 -0.8704398 -0.4920928 0.00603336 -0.735584 -0.6774068 -0.004918634 -0.7211901 -0.6927198 0.005062401 -0.6140138 -0.7892791 -0.003911674 -0.6007379 -0.7994365 0.004022598 -0.4756636 -0.8796181 -0.002827346 -0.4647267 -0.8854497 0.002913296 -0.3243296 -0.9459397 -0.001684546 -0.3166665 -0.9485355 0.001740455 -0.1641752 -0.9864296 -4.91779e-4 -0.1604045 -0.9870513 4.99934e-4 0 -0.9999999 7.62953e-4 4.39921e-4 -0.9999997 -7.37704e-4 0.1604154 -0.9870494 0.001959562 0.1649976 -0.986292 -0.001907765 0.3166675 -0.9485347 0.003094434 0.3250458 -0.9456933 -0.003009259 0.4647203 -0.8854525 0.004164159 0.4762236 -0.8793144 -0.004047513 0.6007375 -0.7994362 0.005167782 0.614421 -0.7889616 -0.00502187 0.7211962 -0.6927127 0.006109356 0.73587 -0.6770953 -0.0188232 0.8990198 -0.4375034 -0.1662803 0.8256093 -0.5391849 -0.07077836 0.9135302 -0.4005659 -0.07078123 0.9669888 -0.2447915 -0.05539655 0.9612935 -0.2699 0.02930742 0.9989862 -0.0341745 0 0.9965866 -0.08255422 -0.04440712 0.9985281 0.03113979 -0.1272888 0.9879079 0.08851873 -0.1919764 0.971996 0.1355324 -0.237507 0.9568552 0.1673877 -0.4085989 0.8679904 0.282205 -0.5896056 -0.7101616 0.3847541 -0.4204149 -0.8533859 0.3081947 -0.4159412 -0.86902 0.2679504 -0.2518877 -0.933171 0.2564067 -0.05191326 -0.9949969 0.08535987 -0.106732 -0.989756 0.09482264 -0.8520151 0.4021583 -0.3351702 -0.6970461 0.2062797 -0.6867136 -0.7521197 0.5012068 -0.427911 -0.7300593 0.5107627 -0.4540208 -0.7447735 0.6386939 -0.193346 -0.7245594 0.6334912 0.2714824 -0.7306236 0.6177512 0.2908141 -0.7661489 0.6351892 0.09772688 -0.8107617 0.5825802 -0.05714786 -0.7849943 0.5232927 0.3315855 -0.8829498 0.3022508 -0.3592272 -0.7564446 0.08608323 -0.6483683 -0.7207499 0.1159441 -0.6834301 -0.8846095 0.3006407 -0.3564846 -0.9079273 0.4174535 -0.03742659 -0.9261304 0.3767489 0.01851725 -0.8493233 0.3828601 0.3634119 -0.8432897 0.4291871 0.3235135 -0.8864958 0.2340625 0.3991742 -0.9158612 0.1479566 0.3732388 -0.9904037 0.1288712 0.04992645 -0.9887133 0.1463827 0.0319103 -0.9085034 0.07862299 0.4104143 -0.9429449 0.1044725 -0.3161339 -0.9426979 0.1050562 -0.3166764 -0.7551894 0.04330927 -0.6540744 -0.9332692 -0.07755625 0.3507046 -0.9015106 -0.1477999 0.4067358 -0.9905307 -0.1277857 0.05019873 -0.8863739 -0.2341295 0.3994054 -0.9430931 -0.1040601 -0.3158275 -0.9888131 -0.1457326 0.03179198 -0.7553091 -0.04352122 -0.6539222 -0.9425181 -0.1054197 -0.3170906 -0.7440542 -0.06877928 -0.6645697 -0.9265168 -0.3757778 0.01891422 -0.8689177 -0.3788201 0.3185551 -0.8324289 -0.4305317 0.3488621 -0.7848837 -0.523364 0.3317344 -0.8852242 -0.4557114 -0.09330278 -0.8617193 -0.353088 -0.3643745 -0.7489871 -0.1418223 -0.6472285 -0.8933722 -0.3237349 -0.3115798 -0.7159297 -0.6467757 0.2629181 -0.8209927 -0.5617519 -0.1020096 -0.7608877 -0.6279163 -0.1636193 -0.8089194 -0.4513398 -0.376752 -0.7703467 -0.466975 -0.4341664 -0.7113638 -0.2204344 -0.6673607 -0.8217526 -0.4064046 -0.3994472 -0.996408 0.01263606 -0.08373463 -0.9944046 0.01900696 -0.1039152 -0.9990923 0.0227127 -0.03603744 -0.9990969 0.01164025 -0.04086524 -0.9894008 0.009796202 -0.14488 -0.9947921 0.02021545 -0.09990125 -0.994392 0.04069286 -0.09761393 -0.9594226 0.02106994 -0.281184 -0.9828487 0.1044596 -0.1519761 -0.9822808 0.06087076 -0.1772548 -0.9700506 0.08807164 -0.226374 -0.9707147 0.02645146 -0.2387748 -0.9412925 0.032148 -0.336058 -0.9258497 0.2543582 -0.2794716 -0.9481039 0.03658169 -0.3158493 -0.9471427 0.112491 -0.3004437 -0.9443778 0.1134435 -0.3086766 -0.9444873 0.2107847 -0.2520193 -0.9023398 0.03338575 -0.4297305 -0.9011236 0.1544615 -0.4051148 -0.9579957 0.2267187 -0.1756215 -0.8543987 0.05021345 -0.5171864 -0.8876013 0.1591364 -0.4322496 -0.8875283 0.2983527 -0.3511117 -0.8868735 0.3987759 -0.2333096 -0.8862825 0.2994717 -0.353299 -0.8607461 0.178979 -0.4765319 -0.8628278 0.05416858 -0.5025873 -0.8733256 0.4180631 -0.2500514 -0.7855427 0.5851048 -0.2014327 -0.844719 0.3467761 -0.4076718 -0.8446934 0.1833282 -0.5028755 -0.8424605 0.3483155 -0.411019 -0.842624 0.4686614 -0.2652198 -0.8769377 0.4692035 -0.1040596 -0.7962025 0.04933249 -0.6030158 -0.7939663 0.2149806 -0.5686836 -0.808227 0.5111253 -0.2924381 -0.8082408 0.5803766 -0.09954875 -0.7506155 0.06643128 -0.6573913 -0.7634159 0.216939 -0.6083862 -0.7638848 0.4178681 -0.4917992 -0.8204135 0.3880577 -0.4199202 -0.7766782 0.5528714 -0.3018349 -0.7155137 0.6889013 0.1159964 -0.6725213 0.7364091 0.07359898 -0.6812868 0.7182169 -0.1414673 -0.8020722 0.07690471 -0.5922549 -0.8019977 0.1995236 -0.5630187 -0.7122604 0.1981002 -0.6733806 -0.7527995 0.4451657 -0.4848922 -0.7656361 0.564467 -0.3085103 -0.8179031 0.5551504 -0.1511383 -0.6993778 0.6522798 0.292236 -0.9092215 -0.3766141 -0.1774204 -0.9913836 -0.1305001 -0.01132696 -0.949055 -0.3044831 -0.08114677 -0.9649092 -0.2586047 -0.04554009 -0.5966526 -0.777577 -0.1984434 -0.7891349 -0.6048989 -0.1065998 -0.9657943 -0.235155 -0.1092869 -0.9490864 -0.2582734 -0.1803608 -0.9649135 -0.2273905 -0.1312841 -0.3877626 -0.8024071 -0.4536331 -0.2385865 -0.7003713 -0.6727232 -0.9657933 -0.1835868 -0.1831372 -0.7385994 -0.4333303 -0.516426 -0.9490706 -0.1810172 -0.2578715 -0.9649195 -0.1687619 -0.201121 -0.3305865 -0.566967 -0.7544939 -0.3050023 -0.5594328 -0.7707197 -0.6805779 -0.4303903 -0.5929401 -0.2377073 -0.4514084 -0.8600731 -0.9657891 -0.1098628 -0.2349078 -0.9490526 -0.08189117 -0.3042908 -0.9649252 -0.0897904 -0.2466925 -0.7275053 -0.2346612 -0.6447249 -0.322265 -0.2997724 -0.897932 -0.3098672 -0.2936034 -0.9043115 -0.6946948 -0.2221216 -0.68415 -0.2372568 -0.1558241 -0.9588681 -0.9657868 -0.0228762 -0.2583266 -0.3142737 0 -0.9493324 -0.31426 8.74341e-6 -0.949337 -0.9490262 0.02717965 -0.3140232 -0.9649398 0 -0.2624714 -0.7117421 5.30173e-6 -0.7024409 -0.7117519 0 -0.702431 -0.2372613 0.1558347 -0.9588653 -0.9657777 0.06694763 -0.2505825 -0.3066231 0.3014162 -0.9028459 -0.3182151 0.2927598 -0.9016822 -0.694701 0.2221306 -0.6841408 -0.9489522 0.1331467 -0.2859402 -0.9649646 0.08974051 -0.2465564 -0.7275002 0.2346638 -0.6447297 -0.2376979 0.4514032 -0.8600785 -0.9657641 0.1487216 -0.2125602 -0.6805854 0.4303969 -0.5929267 -0.2993382 0.5731975 -0.7627853 -0.3217291 0.5562056 -0.7662413 -0.7385926 0.4333356 -0.5164313 -0.9488759 0.2231664 -0.2232298 -0.964989 0.1685978 -0.2009255 -0.2385854 0.7003773 -0.6727173 -0.9657475 0.2125681 -0.148817 -0.2939365 0.8594491 -0.4182687 -0.3936309 0.8054496 -0.4430642 -0.615529 0.6905264 -0.3798651 -0.9588282 0.2459397 -0.1419935 -0.5820078 0.7042377 -0.4065909 -0.9657585 0.2351608 -0.1095905 -0.9657359 0.2507134 -0.06705999 -0.9487726 0.3147652 -0.0274471 -0.9896426 0.1114978 -0.09042066 -0.9374392 0.3416635 -0.06688767 -0.5873391 0.8006835 -0.1180628 -0.8226501 0.5219266 -0.2254763 -0.6924756 0.6924636 -0.2024151 -0.5147524 0.831374 -0.2093971 -0.3524112 0.9010128 -0.2529473 -0.3123171 0.9193571 -0.2392503 -0.3528842 0.9005162 -0.254054 -0.1119046 0.9931381 -0.03397244 -0.1119699 0.9937116 -1.78406e-4 -0.1946955 0.9808569 0.003682971 -0.3651767 0.9309352 -0.00240159 -0.5260813 0.8504334 0.001280069 -0.4889855 0.872291 -0.00127381 -0.7143178 0.6998209 9.17657e-4 -0.707122 0.7070901 0.001479625 -0.8595867 0.5109899 -5.67055e-4 -0.8447405 0.5351755 9.53597e-4 -0.9587785 0.2841482 -0.001939833 -0.9394835 0.3425897 0.001776456 -0.9954783 0.09498715 -7.97928e-4 -0.9937124 0.1119639 0 -0.7133834 0.6985089 -0.05629914 -0.5625953 0.8205677 -0.1007737 -0.8549636 0.508279 -0.1033917 -0.8415546 0.5292949 -0.1078557 -0.9490778 0.2814462 -0.1415614 -0.9878228 0.09500938 -0.1232047 -0.406057 0.9138467 0.001397609 -0.3324879 0.943072 -0.008196532 -0.2558831 0.9652795 -0.05252945 -0.7110176 0.6436711 0.283093 -0.5436429 0.7803342 0.3090808 -0.3353622 0.9420609 0.007323265 -0.6103575 0.7843998 0.1103666 -0.6920753 0.7032364 0.1627585 -0.5170993 0.8547837 -0.04419523 -0.5763878 0.8033123 0.1498892 -0.6578716 0.749139 0.07743287 -0.6678611 0.7414907 0.06444466 -0.6164978 0.7814478 -0.09627938 -0.5726468 0.8176057 -0.05997097 -0.8166515 0.5724842 -0.07309085 -0.8004091 0.5814624 -0.1457626 -0.8559814 0.4787226 -0.1952455 -0.8365836 0.5312302 -0.1338753 0.9487577 -1.5082e-4 -0.3160046 0.9326866 0.001193046 -0.360686 0.4537588 -0.00118494 -0.8911238 0.4353505 -4.55056e-4 -0.900261 -7.93739e-5 -1 2.98774e-5 -3.86575e-5 -1 8.15107e-5 0 -1 1.77169e-7 -1.47704e-4 -1 -3.08984e-5 -0.9964498 -0.01178532 -0.08336162 -0.9983762 -0.02492457 -0.05122333 -0.998402 -0.01889759 -0.05325752 -0.9983075 -0.02478682 -0.05261021 -0.9960803 -0.03421962 -0.08156597 -0.9962339 -0.01169383 -0.0859152 -0.9892727 -0.01950609 -0.144772 -0.9822662 -0.01710367 -0.1867101 -0.9819517 -0.06726473 -0.1767666 -0.9591674 -0.03072613 -0.2811654 -0.9905112 -0.07150346 -0.1173669 -0.9788526 -0.1252843 -0.161714 -0.9785422 -0.06961661 -0.1939297 -0.9627919 -0.1621823 -0.2161684 -0.9592568 -0.1722732 -0.2239382 -0.9586429 -0.0961523 -0.267878 -0.9413122 -0.03120034 -0.3360924 -0.9472403 -0.03591889 -0.3185055 -0.9460272 -0.1175846 -0.302004 -0.9425165 -0.2767438 -0.187285 -0.9054799 -0.1446663 -0.3989711 -0.9062985 -0.2631977 -0.3306813 -0.9178807 -0.2522543 -0.3063708 -0.9216434 -0.3316446 -0.201458 -0.8855422 -0.1666429 -0.4336419 -0.8871166 -0.0363301 -0.4601134 -0.8538761 -0.05461061 -0.5176036 -0.9337716 -0.3099125 -0.1789554 -0.8434594 -0.3523581 -0.4054874 -0.8440992 -0.18374 -0.5037223 -0.7847732 -0.552006 -0.2818163 -0.8232899 -0.04665136 -0.5657009 -0.8211603 -0.2026797 -0.5334947 -0.8080378 -0.5168795 -0.2826845 -0.8082885 -0.3758358 -0.4532298 -0.750651 -0.06076163 -0.6578992 -0.8160256 -0.5458183 -0.1902227 -0.7501133 -0.22158 -0.6230831 -0.7450543 -0.437609 -0.5033811 -0.7673738 -0.210667 -0.6056045 -0.7670268 -0.06712132 -0.6380947 -0.784841 -0.5459694 -0.2931591 -0.8126369 -0.3939298 -0.4294656 -0.6989669 -0.6212382 -0.3542716 -0.7312147 -0.6573439 -0.182275 -0.684179 -0.5085508 -0.5227574 -0.7260631 -0.215768 -0.6528986 -0.7226821 -0.678829 0.130084 -0.7277319 -0.5936058 -0.3435674 -0.264388 -0.95913 0.1008402 -0.4320181 -0.8969509 -0.09401935 -0.6050702 -0.7832266 0.142991 -0.3751323 -0.9266769 0.02336347 -0.4584776 -0.8885427 -0.01703929 -0.6055442 -0.7930687 -0.0660187 -0.6529601 -0.7511695 0.09688997 -0.6542546 -0.7504227 0.09389841 -0.7925587 -0.5891061 -0.1574957 -0.6224873 -0.7787278 -0.07805567 -0.7948885 -0.5878264 -0.1503739 -0.8105062 -0.5620998 -0.1646923 -0.8098721 -0.5634237 -0.1632822 -0.8986511 -0.3922554 -0.1963718 -0.1193391 -0.9927923 -0.01103776 -0.0144087 -0.9994608 -0.02950733 -0.001143455 -0.9999994 -2.23502e-4 -0.3521888 -0.9358712 -0.01041001 -0.131658 -0.9912229 -0.01197606 -0.2374448 -0.9700775 -0.05069363 -0.2377125 -0.9700925 -0.04912614 -0.2733497 -0.9605963 -0.05034786 -0.4170451 -0.9047861 -0.08623045 -0.424819 -0.9044398 -0.03895831 -0.4455932 -0.8913614 -0.08319658 -0.5952562 -0.8006581 -0.06794643 -0.5963745 -0.799857 -0.06757283 -0.5880718 -0.8001113 -0.118294 -0.6166662 -0.7797056 -0.1085458 -0.8064756 -0.5864192 -0.07556146 -0.8082581 -0.5840689 -0.07471626 -0.7971332 -0.5849951 -0.1495316 -0.9189757 -0.3791266 -0.1083826 -0.8150715 -0.5633074 -0.1354375 -0.9674891 -0.2398635 -0.08019047 -0.9115318 -0.37763 -0.1628052 -0.9430137 -0.2613941 -0.205909 -0.9927644 -0.04472106 -0.11144 -0.989093 -0.1273361 -0.07403099 -0.929939 -0.2990087 -0.2140266 -0.1305209 -0.9914456 -1.69666e-7 -0.1192955 -0.9928587 -6.1726e-4 -0.3826858 -0.9238786 -4.11445e-4 -0.3522574 -0.9359026 0.001012384 -0.6087589 -0.7933542 0.001346826 -0.5964696 -0.8026325 0.002293169 -0.8090472 -0.5877434 -6.7648e-4 -0.7936529 -0.6083704 8.1415e-4 -0.9243702 -0.3814969 -7.03132e-5 -0.9238858 -0.3826682 -2.55012e-7 -0.9916467 -0.1289845 0 -0.9914461 -0.1305168 8.3577e-5 -0.1291008 -0.9806596 -0.1471053 -0.3755054 -0.9065418 -0.1928151 -0.4680989 -0.8530529 -0.2306171 -0.4515169 -0.7878483 -0.4188406 -0.5465849 -0.7252127 -0.4187024 -0.6082782 -0.7008405 -0.372586 -0.5721026 -0.7917593 -0.2140467 -0.4746628 0.8510899 0.2243682 -0.4577124 0.8535903 0.2487632 -0.3598774 0.9262133 0.1123266 -0.5492996 0.8211207 0.1550191 -0.4882165 0.870643 -0.06021147 -0.194683 0.9808581 -0.004012584 -0.2049255 0.9787381 -0.008794546 -0.2408218 0.9699551 -0.03452485 -0.2553867 0.9652409 -0.05556869 -0.9999711 0.007605195 1.21785e-4 -0.9999952 -0.002997696 8.54734e-4 -0.9999939 -0.003353118 9.78871e-4 -0.9999994 0 -0.001186072 -0.8862363 -0.4370459 -0.1535461 -0.8596947 -0.4913477 -0.1396511 -0.7213765 -0.640836 0.2625741 -0.687279 -0.6679332 0.2855045 -0.5379254 -0.8254376 0.1711407 -0.089634 -0.9955468 0.02919554 -0.09554094 -0.9951177 0.02475494 -0.1069311 -0.9932101 0.04582095 -0.1259351 -0.9920355 0.002433717 -0.1173849 -0.9810523 -0.1541333 -0.9991533 -0.04114508 1.00893e-4 -0.04763281 -0.9988645 -8.5677e-4 1 -3.01314e-5 1.96228e-4 1 1.99712e-4 -5.40625e-5 1 0 -2.22524e-6 0.2393013 0.01659196 -0.9708037 0.340554 0.004552781 -0.940214 0.4647546 0.001059055 -0.8854389 0.6631556 -0.002519607 -0.7484775 0.8229896 0.006064116 -0.5680243 0.9347048 0.02630251 -0.3544504 0.9927123 0 -0.1205085 0.9927189 -2.88792e-5 -0.1204546 0.9040649 0.01585537 -0.4271011 3.95195e-5 -0.9999998 -6.03869e-4 -2.46076e-5 -1 1.03468e-4 -2.52e-5 -1 2.31361e-4 4.41908e-7 -1 -4.49938e-6 1.29983e-7 -1 -2.30838e-6 3.28781e-7 -1 6.8647e-7 0 -1 -6.07353e-7 1.03811e-5 -1 -8.06934e-5 0 -1 -2.9669e-7 1.10848e-5 -1 1.22027e-5 -0.947209 -0.01689749 -0.3201715 -0.1633957 -0.02333933 -0.9862846 -0.4521208 -2.54416e-4 -0.8919568 -0.9946249 -0.00928992 -0.1031258 -0.1635607 -0.01427954 -0.9864299 0 -1 0 0 -1 0 0 -1 0 0 -0.9701426 0.2425356 0.815125 -0.05270439 0.5768826 0.8986712 0 -0.438623 0.9044824 -0.006862699 -0.426456 0.9393242 0.004310369 -0.3430036 0.9545444 -0.009238779 -0.2979258 0.9694658 0.004599153 -0.2451834 0.9866577 -9.10171e-4 -0.1628062 0.9898295 -0.009415447 -0.141947 -0.02275341 0.02489012 -0.9994313 0.1193639 -0.02614277 -0.9925064 0.2252363 0.01381814 -0.9742063 0.3575754 -0.009148716 -0.9338395 0.4524347 0.01231402 -0.8917125 0.5349345 -0.006917893 -0.8448653 0.6521134 0.008543729 -0.7580733 0.6912466 -0.003481268 -0.7226107 0.8106769 0.004049777 -0.5854799 0.8202673 0 -0.5719806 -0.09965127 -0.001815855 -0.9950208 -0.06235259 -0.9957591 0.06764686 -0.2023846 -0.9591159 0.1978318 -0.06164848 -0.9959497 0.06545031 -0.3453996 -0.8805637 0.32451 -0.3388894 -0.890093 0.3047761 -0.1991704 -0.9617902 0.1878585 -0.3668327 -0.8914704 0.2659214 0.636735 -0.6006257 0.4835467 0.2391135 -0.8473774 0.474106 -0.2736889 -0.8272328 0.4906939 0.08862429 -0.9032942 0.4197685 0.6647042 -0.6040238 0.4396858 0.6847661 -0.5922917 0.4246011 0.6514908 -0.6602333 0.3737001 0.1170858 -0.9446147 0.3065844 0.2397288 -0.9332714 0.2674601 0.6956524 -0.6429955 0.3203508 0.687515 -0.6494031 0.3249595 0.6645329 -0.6935549 0.2781682 0.7263695 -0.6447274 0.2381473 0.6908797 -0.6795063 0.2468938 0.2417125 -0.9505735 0.194898 0.3729038 -0.9153248 0.1520641 0.4021362 -0.9113624 0.0877785 0.3472985 -0.9325497 0.09866535 0.3556221 -0.9313089 0.07871842 0.3150433 -0.948167 0.04155969 0.1168699 -0.9930276 0.0154156 0.4402564 -0.8978334 -0.00833708 0.3215475 -0.9466273 0.02245247 -0.649764 0.09072822 -0.7547021 -0.5724436 0.08332246 -0.8156996 -0.5177595 0.03186547 -0.8549327 -0.6212203 0.09206414 -0.7782092 -0.5780669 0.1097511 -0.808575 -0.4363008 0.08042341 -0.8961996 -0.4955585 0.2551012 -0.8302682 -0.1986351 0.162071 -0.9665801 -0.2292833 0.1702266 -0.9583591 -0.2924733 0.3886293 -0.8737429 -0.2980372 0.3872548 -0.8724721 -0.01434177 0.1772686 -0.984058 -0.1274458 0.5253184 -0.8413075 0.03705573 0.591821 -0.8052173 0.08401024 0.594484 -0.7997068 0.1842444 0.2372649 -0.9538131 0.2028936 0.2333935 -0.9509793 0.4125478 0.2407467 -0.8785473 0.2440397 0.6798533 -0.691552 0.4809156 0.4938198 -0.7244738 0.3262248 0.6498309 -0.6865109 0.02677047 0.7169066 -0.696655 0.4363033 0.6820588 -0.5868861 0.549539 0.2822183 -0.7863587 0.6172931 0.1049016 -0.7797084 0.3379444 0.285219 -0.896908 -0.08532345 0.3475857 -0.933758 -0.6238679 0 -0.7815298 -0.6234945 -3.99086e-5 -0.7818278 -0.4377225 3.64117e-5 -0.8991103 -0.4338716 -3.05726e-4 -0.9009746 -0.2326864 2.96529e-4 -0.9725518 -0.2225331 -5.20208e-4 -0.9749251 -0.01456749 5.14326e-4 -0.9998938 0 -6.11776e-4 -0.9999998 0.2086611 6.24165e-4 -0.9779879 0.2225221 -4.92212e-4 -0.9749276 0.4250475 5.04517e-4 -0.905171 0.4338808 -2.83749e-4 -0.9009703 0.6207233 2.93722e-4 -0.7840299 0.623473 0 -0.7818449 -0.7070778 0 -0.7071359 -0.707079 -2.35906e-6 -0.7071346 -0.7104153 -0.00923711 -0.7037222 -0.7046052 0.01245737 -0.7094902 -0.661574 0.1000357 -0.7431775 -0.4219263 -0.8521161 0.3096395 -0.4038802 -0.8363662 0.3706381 -0.4013476 -0.8437567 0.3563635 -0.2014473 -0.84829 0.4897173 0.1538095 -0.757456 0.6345101 0.4889825 -0.4556807 0.7438086 0.7088915 -0.1785257 0.6823499 -0.1675468 -0.8655346 0.4719939 -0.2499654 -0.8760294 0.4124197 -0.1294784 -0.8392081 0.5281714 -0.2039812 -0.8563758 0.4743547 0.1536067 -0.7572695 0.6347818 0.3293162 -0.6767236 0.6584802 0.491304 -0.4580534 0.7408155 0.354331 -0.709137 0.609569 0.220324 -0.8119357 0.5405718 0.5934155 -0.5175992 0.6164002 0.7374612 -0.209017 0.6422328 0.8160329 -0.3085777 0.4887436 0.7259456 -0.3590474 0.5865902 0.7405961 -0.2001601 0.6414464 0.1168556 -0.9931485 -0.001008868 0.1501712 -0.9882257 -0.0293008 0.1360949 -0.988255 -0.06950169 0.1833649 -0.9819478 -0.04643225 0.1919435 -0.9812871 0.01527905 0.1068691 -0.9921252 -0.06532013 0.4402417 -0.8977922 -0.01251453 0.1109331 -0.9889203 -0.09864336 0.1121163 -0.9886544 -0.0999614 0.1090295 -0.9886416 -0.1034424 0.2499032 -0.9296916 -0.2705954 0.1828768 -0.9455833 -0.2691254 0.2156059 -0.9133102 -0.3455122 0.1611708 -0.9472076 -0.2771676 0.1785748 -0.9074363 -0.380356 0.03253912 -0.9983173 -0.04799997 0.04872357 -0.9940711 -0.09720379 0.04951423 -0.9920257 -0.115903 0.1734674 -0.8360562 -0.5204991 0.1712641 -0.8500947 -0.4980036 0.1757156 -0.9089293 -0.3781159 0.04759436 -0.9923745 -0.1136998 0.05362218 -0.9869092 -0.1521018 0.253569 -0.9447026 -0.2079415 0.2840487 -0.8643482 -0.4149925 0.2602985 -0.8956975 -0.3605148 0.2666859 -0.8230801 -0.5014158 0.2478 -0.7843751 -0.5686395 -6.56949e-5 -0.9999994 -0.001131415 -2.05054e-4 -0.9999998 6.86732e-4 -2.0504e-4 -0.9999998 6.86062e-4 -1.68216e-5 -1 1.06803e-5 -2.07044e-4 -0.9999999 5.55598e-4 2.25611e-4 -0.9999998 -6.05423e-4 -2.95175e-5 -1 4.35961e-5 -1.22186e-5 -1 2.78497e-6 0 -1 4.036e-7 -4.91502e-5 -1 4.56323e-4 0 -1 4.41363e-6 0.3525553 -0.8555891 -0.3790411 0.3116161 -0.8804436 -0.3573716 0.3061493 -0.910061 -0.2793951 0.3423857 -0.9190624 -0.1951834 0.2929202 -0.9164159 -0.2727267 0.2386974 -0.9456217 -0.2209595 0.2381839 -0.9469295 -0.2158546 0.2469198 -0.9477921 -0.2017945 0.2470577 -0.94852 -0.1981722 0.2674833 -0.9185493 -0.2910668 0.2569962 -0.9456889 -0.1990618 0.2777743 -0.9156069 -0.2906985 0.3134286 -0.86365 -0.3948054 0.256459 -0.9482637 -0.187149 0.2863978 -0.9431062 -0.1688995 0.2216923 -0.9559361 -0.1924548 0.3077291 -0.8655282 -0.3951758 0.3023807 -0.9104925 -0.2820807 0.2564381 -0.9490117 -0.1833474 0.2560515 -0.8881105 -0.3817031 0.2650578 -0.9465113 -0.1840127 0.2565774 -0.9478963 -0.1888403 0.25937 -0.9140505 -0.3118314 0.2356683 -0.9201387 -0.3127386 0.2905758 -0.9386476 -0.185759 0.228971 -0.8909945 -0.3920472 0.2026887 -0.8984285 -0.3895427 0.3008745 -0.9391363 -0.1658239 0.260475 -0.9274561 -0.2682876 0.3878899 -0.8987562 -0.2043988 0.3247321 -0.8801459 -0.3462547 0.3460811 -0.925378 -0.1546077 0.2665843 -0.8656461 -0.4237803 0.2790189 -0.8544856 -0.4381812 0.4687653 -0.8755775 -0.1167182 0.4902011 -0.8681079 -0.07804828 0.4814864 -0.8716093 -0.09202271 0.4902051 -0.8678818 -0.0805 0.4474827 -0.8914318 -0.07147413 0.5005629 -0.8656901 -0.004194021 0.4995087 -0.8662844 -0.00653398 0.6005955 -0.7889509 -0.1297753 0.5074489 -0.8594309 -0.0622428 0.7013735 -0.7049167 0.1056779 0.6956553 -0.7094041 0.1131802 0.6289874 -0.762393 -0.1520922 0.664568 -0.7442901 -0.06619393 0.5952162 -0.7993766 0.08194464 0.6265507 -0.761123 0.1677084 0.6269951 -0.7671248 0.135635 0.691171 -0.7164412 0.0948401 0.7182928 -0.6952803 0.0253154 0.7580253 -0.6227501 0.1938552 0.7604596 -0.5803706 0.2913271 0.7575163 -0.5975437 0.2628894 0.7544999 -0.6070907 0.2493409 0.7991358 -0.5859143 0.1344864 0.790567 -0.6058165 0.08938848 0.8215386 -0.5405208 0.1814157 0.8207837 -0.4692702 0.3257293 0.835345 -0.3997552 0.3773519 0.8150735 -0.3789454 0.4382415 0.8246665 -0.4032723 0.3966066 0.8262979 -0.4337514 0.3592935 0.8732556 -0.3672801 0.3202035 0.8743069 -0.4323125 0.2206662 0.8756905 -0.4198485 0.2385237 0.8797497 -0.372007 0.2960597 0.8811836 -0.3304143 0.3381449 0.8816385 -0.2787825 0.3807807 0.8599933 -0.2211823 0.4598806 0.8817104 -0.2316821 0.4109869 0.8767298 -0.1035447 0.4697057 0.7611622 -0.1840569 0.6218965 0.830002 -0.1669018 0.5322036 0.8491138 0.0220589 0.5277491 8.00675e-4 0.9999955 -0.002914607 1.9192e-4 -1 -4.49039e-7 0.04146784 -0.9978154 -0.05142813 -0.007111132 -0.9999207 0.01039898 0.003337204 -0.9999825 -0.00488013 -8.85215e-4 -0.9999996 2.76288e-4 -9.95798e-4 -0.9999994 4.69509e-4 -0.001082301 -0.9999991 7.54711e-4 -0.001183986 -0.9999986 0.00123775 -0.001281738 -0.9999972 0.002024412 -0.002108991 -0.9999896 0.004053294 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.001348614 -0.999993 0.003522038 0.002055346 -0.9910548 0.1334401 0.2772106 -0.546256 0.7904167 -0.1166644 0.03638851 0.9925045 -0.604407 0.2074012 0.7692055 -0.7454774 -0.1872649 0.6396838 -0.4285294 -0.1607231 0.8891179 0.9962196 0.04058206 -0.0768094 0.9986143 0.03368157 -0.04043662 -0.2765302 -0.5929502 0.756268 -0.2212674 -0.610017 0.7608678 0.8892003 -0.2822961 0.3600443 0.119928 0.9925268 0.02254009 -0.5501428 -0.6272999 0.5512149 0.8536086 0.2230147 0.470762 0.7894388 0.3703002 0.4895551 0.1710877 -0.9322435 0.3188278 0.1746862 -0.9329741 0.3147128 0.2767142 0.9606179 0.02535039 0.2631711 0.9632378 0.05398029 0.2677219 0.9606288 0.07427906 0.2457112 0.962623 0.1139428 0.2470989 0.9609029 0.1249308 0.4025743 -0.8445901 0.3529898 0.3081626 -0.8786294 0.364755 0.7923493 -0.4863711 0.3682739 0.7305902 -0.558321 0.3930849 0.9395609 -0.1465769 0.3094196 0.9284021 0.2902551 0.2319945 0.9281854 0.2916861 0.2310658 0.4500841 -0.6295917 0.6332762 0.5276674 -0.5684834 0.6311845 0.5146169 -0.5832913 0.6284432 0.6990584 0.2892754 0.6539397 0.6960245 0.2585659 0.6698459 0.7332835 0.3930097 0.5548322 0.5154362 -0.6393492 0.570577 0.7147649 -0.4432713 0.5409453 0.5036952 -0.691275 0.5181024 0.6268921 -0.5820151 0.5179428 0.5468419 -0.6432567 0.5358963 0.8545953 0.2361623 0.4624871 0.8735178 0.3251657 0.3622626 0.7715947 0.6347539 0.04158365 0.1448652 -0.9397484 0.3096566 0.1440281 -0.9399671 0.3093829 0.1438862 -0.9399999 0.3093492 0.1437261 -0.9400291 0.3093352 0.1435278 -0.9400614 0.309329 0.1433923 -0.9400712 0.3093619 0.1033968 -0.9394602 0.3266857 0.4052397 0.8371928 0.3672726 0.4044088 0.8537462 0.3279804 0.4530766 0.8312925 0.321985 0.4888494 0.8366226 0.2471617 0.4901289 0.8324376 0.2584983 0.5333691 0.8204042 0.2060449 0.5503007 0.8208852 0.1526988 0.5477446 0.8253548 0.1369865 0.5793759 0.8099972 0.0907095 0.5819862 0.8114492 0.05331397 0.5820849 0.811389 0.05315369 0.638897 0.7680466 -0.04376387 0.5823409 0.811749 0.04407769 -0.6297558 -0.6157594 0.4735484 -0.6271258 -0.6118091 0.482082 -0.6740891 -0.630357 0.3850376 -0.723318 -0.6162527 0.3115186 -0.7775484 -0.5790691 0.2451478 -0.6944273 -0.6441287 0.3207319 1 -1.13442e-5 0 1 5.63126e-6 0 0.101216 0.9936187 0.04977393 0.2418761 0.9669432 -0.08072793 0.3517692 0.8901457 -0.2896535 0.31959 0.943414 -0.08850127 0.3643687 0.931235 0.006072521 0.4288782 0.9010828 -0.0641359 0.3415879 0.9306011 -0.1315277 0.3586279 0.9302865 -0.07715725 0.449767 0.8931323 0.004947423 0.4393381 0.89793 0.02652996 0.5673802 0.8141534 -0.1234261 0.5424739 0.8392261 -0.03770589 0.1955621 -0.8704785 0.4516888 0.274533 -0.7721518 0.5730736 0.3052313 -0.6570793 0.689261 0.9903775 0.1327829 -0.03900474 0.9073784 0.411969 0.08334356 0.9104006 0.3720211 0.1810277 0.8286084 0.5490634 -0.1092587 0.7531545 0.6424612 -0.1414283 0.784201 0.6195023 -0.03529936 0.8274941 -0.507332 0.2405576 0.754019 -0.4613307 0.4675784 -0.2270602 -0.8699226 0.4378109 0.85823 -0.4431261 0.2589995 0.9197178 -0.361854 0.1522533 0.8714846 -0.4373522 0.2218957 0.8436255 -0.50055 0.1942832 -0.2034449 -0.8764452 0.4364104 0.2774363 0.9607213 0.006606578 0.22382 0.973071 -0.05511474 0.2000837 0.9797759 0.002401053 0.1887516 0.9813424 -0.03660464 0.2663145 0.9637085 -0.01851433 0.2754479 0.961282 -0.008096873 -0.2649534 -0.9269973 0.2654727 -0.2992206 -0.9272764 0.225001 -0.2998445 -0.9280356 0.2210054 -0.3246492 -0.9274775 0.1854411 -0.324842 -0.9279549 0.1826956 -0.3430567 -0.9276224 0.1477458 -0.3430482 -0.9279028 0.1459948 -0.3559871 -0.927726 0.1122397 -0.3559255 -0.9278632 0.1112974 0.9206955 0.3749945 -0.1081624 -0.6946241 -0.6997562 0.1668493 -0.1926552 -0.8635072 0.4660895 0.1259099 -0.5479894 0.8269549 0.1832878 -0.6922945 0.6979498 0.2395914 -0.7246621 0.6461121 0.3299891 -0.7194282 0.6111713 0.04363244 -0.7846608 0.618388 -0.1494645 -0.8515249 0.5025594 -0.395716 -0.9000057 0.182753 -0.4030987 -0.9021146 0.1539509 -0.3804663 -0.9247206 -0.01171642 0.2491181 -0.6247086 0.7400537 0.3378735 -0.8061549 0.4857529 0.7485205 -0.5875902 0.3073351 0.9643633 -0.18411 0.1900181 0.9985203 -0.05406308 0.005875289 0.9406666 -0.09922671 0.3245003 0.9360032 -0.05074065 0.3483154 0.4868131 -0.5134187 0.7066926 0.6986203 -0.4543404 0.5527246 -0.3666114 -0.927293 0.07565563 0.9591943 -0.03705906 0.2803088 0.9970113 -0.05994153 0.04874056 -0.3647407 -0.9277926 0.07852053 0.2002142 -0.568073 0.7982528 0.1787045 -0.9140034 0.3642288 -0.1870661 -0.7481045 0.6366679 0.7113925 -0.332099 0.6193796 0.9002285 0.05974829 0.431299 0.9730402 -0.2282612 0.03301316 0.94095 0.3362436 -0.03941237 0.9844909 0.1730127 -0.02905726 0.9928646 0.1133093 -0.03716176 -0.7048978 -0.6942834 0.1452228 0.9613913 0.2549741 0.1035134 0.999779 0.0126211 0.01681411 0.9902083 0.1392028 -0.0104978 0.9922839 0.1211212 -0.02650296 0.7042478 -0.06135284 0.7072983 0.7239643 -0.08033967 0.6851433 0.6983438 -0.0670526 0.7126149 0.7075543 -0.1746249 0.6847431 0.6875606 -0.2029415 0.6971909 0.6896713 -0.3566929 0.6301776 0.660143 -0.2899693 0.6929134 0.7391242 -0.2969423 0.6045832 0.659618 -0.292375 0.6924024 0.7135634 -0.467945 0.5213969 0.5224366 -0.7449336 0.4148904 0.562367 -0.622181 0.5446413 0.5389438 -0.6397625 0.5479448 -0.1650041 -0.6948294 0.6999899 -0.1721704 -0.7020143 0.6910379 -0.296572 -0.6659918 0.6844707 -0.3183932 -0.6728965 0.6677097 -0.4518482 -0.6214181 0.6400569 -0.4581964 -0.6214816 0.6354659 -0.6628969 -0.3759046 0.6475055 -0.5342051 -0.5139497 0.6711787 -0.4940941 -0.6083242 0.6211383 -0.697804 -0.07751375 0.7120823 -0.9061217 -0.3124027 -0.2852159 -0.7172728 -0.1574089 0.6787799 -0.5740024 -0.07080948 0.8157863 -0.6710349 -0.1832858 0.7184139 -0.6374457 -0.3846909 0.6675896 -0.7220277 -0.4327798 0.5397941 0.1151524 0.9931565 -0.01949805 0.1239578 0.9922873 -6.73406e-4 -0.07000857 0.9917713 -0.1071851 -0.0679205 0.991501 -0.1109617 -0.04278165 0.9915738 -0.1222754 -0.04209762 0.991507 -0.1230517 -0.01424241 0.9915308 -0.1290884 0.01422011 0.9915562 -0.1288958 0.01463288 0.9915258 -0.1290833 0.04209452 0.9915074 -0.1230499 0.04277229 0.9915734 -0.1222823 0.06837427 0.9914932 -0.1107528 0.2103157 0.9718128 -0.1065233 0.04527235 0.9962331 -0.07396161 -0.1653037 0.9857109 -0.03238445 -0.1740404 0.9846473 -0.01340448 0.1215655 -0.4375817 0.8909232 -0.7824028 -0.2745493 0.5589889 0.506957 -0.2130027 0.8352393 0.4330044 -0.2010571 0.8786827 -0.875782 -0.1192691 0.4677402 -0.9418951 -0.02903002 0.3346503 -0.9712265 0.01020163 0.237939 -0.7445402 -0.1339588 0.6539992 -0.3530753 -0.2099598 0.9117317 -0.3567022 0.1562464 0.9210596 0.1107707 -4.31913e-6 0.9938461 0.556178 -0.07181996 0.8279541 0.3572683 0.1461029 0.9225038 0.7510623 0.02514004 0.6597526 0.9710683 -0.02064198 0.2379083 0.8484043 -0.1308479 0.5129221 0.8678233 -0.1354776 0.4780468 -0.4048344 -0.2260442 0.8860098 -0.7133215 -0.06060332 0.6982119 -0.5534311 -0.1223077 0.8238659 -0.1083631 -0.2059153 0.9725515 -0.2137928 -0.3760545 0.9015962 0.782373 -0.2746481 0.558982 0.015531 0.9904449 -0.1370318 -0.09152913 -0.9255649 0.3673583 -0.09961342 -0.9288846 0.3567221 -0.1623431 -0.9261415 0.3404508 -0.9997835 -0.01465904 0.01476758 0.7275759 7.39232e-7 0.6860272 0.7263327 -6.49982e-5 0.6873434 0.6954023 3.81417e-4 0.7186205 0.7153871 0.002266645 0.6987247 0.6999038 4.60439e-6 0.7142372 0.6315554 -0.002503454 0.7753267 0.6148208 -0.006632685 0.788639 0.5668371 0.001422405 0.8238287 0.4715675 0.008821845 0.8817859 0.4264562 -0.001268327 0.9045074 0.4857826 -0.001645982 0.8740782 0.4918571 0 0.8706759 0.4415683 -0.03337556 0.8966068 0.4167242 -0.06069928 0.9070042 0.4558042 -5.24582e-4 0.89008 0.3554621 7.62318e-5 0.9346908 0.3920073 0.002701163 0.9199582 0.3657767 0.03910827 0.9298807 0.322727 -0.009053826 0.9464488 0.2724107 -0.04837489 0.9609643 0.2800182 -0.03618669 0.9593125 0.1562021 0.02802312 0.9873275 0.09442484 -0.04776018 0.9943857 0 0.03383982 0.9994273 -0.09442496 -0.04775863 0.9943858 -0.1562018 0.02802222 0.9873276 -0.2684122 -0.03007036 0.9628348 -0.3746393 -0.1566197 0.9138466 -0.2801734 -0.01406919 0.9598463 -0.3741711 0.002496123 0.9273563 -0.4835759 0 0.8753026 -0.4715933 0.008809924 0.8817722 -0.4280501 -0.01026046 0.9036969 -0.4896407 -0.001503765 0.871923 -0.4556706 -0.02415466 0.8898207 -0.5389024 3.43773e-4 0.8423682 -0.6557487 -0.02015483 0.7547103 -0.6148345 -0.003781855 0.7886472 -0.6950608 3.79409e-4 0.7189509 -0.7273753 -8.15432e-5 0.6862399 -0.7263069 0 0.6873706 -1.95194e-6 1 -2.48458e-5 -1.95193e-6 1 2.03044e-6 -2.45848e-6 1 -2.5572e-6 -2.45837e-6 1 1.99401e-6 0 1 2.03182e-5 0 1 -1.3574e-6 0 1 1.46475e-6 0 -1 6.31453e-6 -0.3275347 0 0.9448391 -0.3275162 3.14031e-6 0.9448456 -0.07958555 -6.73445e-6 0.9968281 -0.07951301 6.7351e-6 0.9968339 0.1735875 6.27848e-7 0.9848185 0.1736083 6.27851e-6 0.9848148 0.4153171 1.25622e-6 0.9096767 0.4152984 -6.28144e-7 0.9096853 0.6303045 -5.02523e-6 0.7763481 0.6303653 0 0.7762988 0.8050445 -2.51149e-6 0.5932145 0.8050652 5.02211e-6 0.5931865 0.9283186 -1.00233e-5 0.3717857 0.9283615 1.0022e-5 0.3716786 0.9919646 -1.00499e-5 0.126516 0.9919711 0 0.1264653 0.327549 0 0.9448342 0.327513 0 0.9448466 0.07960546 0 0.9968265 -0.415295 -1.25628e-6 0.9096868 -0.6303404 -1.25626e-6 0.7763189 -0.6302809 0 0.7763673 -0.8050472 0 0.5932108 -0.8050472 0 0.5932108 -0.9919634 0 0.1265257 -0.9919646 0 0.1265156 0.3232126 0.1619968 0.9323576 0.1810331 0.3289416 0.9268358 0.184368 0.3297136 0.9259036 0.07847672 0.1685382 0.9825662 -0.159455 0.3951819 0.9046576 -0.04530227 0.9315398 0.3608065 -0.174589 0.8633994 0.4733501 -0.4005866 0.2640361 0.8773912 -0.3237472 0.352005 0.8782256 -0.2226132 0.9204893 0.3211584 -0.5800468 0.3912677 0.7144616 -0.7805791 0.244649 0.5751898 -0.6942726 0.3619258 0.6220894 -0.2604711 0.9344742 0.2427198 -0.2706961 0.9316076 0.2425511 -0.3349846 0.9210141 0.1987925 -0.8562552 0.3863052 0.3429216 -0.3237393 0.9400035 0.1076404 -0.3640657 0.9269699 0.09046077 -0.9669717 0.2230598 0.1233299 -0.9754656 0.1940457 0.103987 -0.8142781 0.5440774 0.2023139 -0.5472675 0.8189943 -0.1724721 -0.1950362 0.9805729 0.0209214 -0.3232564 0.1610867 0.9325001 -0.07827818 0.1788802 0.9807519 -0.1833869 0.3286159 0.9264885 -0.1849232 0.3284342 0.9262475 0.1593427 0.3968459 0.9039488 0.3865718 0.3653618 0.8468017 0.3285615 0.3081375 0.8928039 0.03931218 0.930907 0.3631347 0.1814484 0.8602703 0.4764572 0.2225986 0.920499 0.3211412 0.580243 0.3906866 0.7146202 0.2665967 0.9312395 0.2484336 0.2664141 0.9335923 0.2396434 0.7469158 0.3730921 0.550381 0.7082531 0.3041261 0.6370911 0.3350259 0.9209915 0.1988278 0.8563929 0.3859483 0.34298 0.3567547 0.9266382 0.1186075 0.3222737 0.9460151 0.03456979 0.5503025 0.8236308 0.137112 0.9246653 0.3031751 0.230389 0.8166505 0.5456643 -0.1879696 0.9731957 0.1936072 0.1241229 0.3273594 0.03110331 0.9443879 0.07822382 -0.1843956 0.9797344 0.025016 -0.1189304 0.9925875 -0.1666514 -0.2797943 0.9454853 -0.1961208 -0.2753227 0.9411345 -0.3827057 -0.3884672 0.83823 -0.6123507 -0.2370259 0.7542185 -0.6466637 -0.3296902 0.6878447 -0.1074151 -0.9363853 0.3341325 -0.2087538 -0.923882 0.320724 -0.2957175 -0.8938161 0.3371111 -0.345305 -0.8654537 0.36298 -0.3200525 -0.922379 0.2162945 -0.7414488 -0.3895595 0.5463489 -0.3466394 -0.9248387 0.1565713 -0.3362553 -0.9377008 0.0874626 -0.2987656 -0.9539883 0.02540749 -0.1945886 -0.9782513 -0.07183104 -0.5490779 -0.8217259 0.1525779 -0.9094717 -0.2004799 0.3642377 -0.9021558 -0.3510975 0.2506904 -0.8166311 -0.5456895 -0.1879807 -0.9732011 -0.1935793 0.1241236 0.5576379 7.51474e-7 0.8300844 0.557638 7.51474e-7 0.8300844 0.1108116 1.25248e-7 0.9938415 -0.3611443 0 0.93251 -0.7513202 0 0.6599379 -0.7512923 1.00196e-6 0.6599697 -0.5576122 0 0.8301017 -0.5576199 -1.00193e-6 0.8300965 -0.110875 -1.62822e-6 0.9938344 -0.1108064 2.25436e-6 0.9938421 0.361142 5.00963e-7 0.9325108 0.3611582 -2.50493e-7 0.9325045 0.7512848 -1.00186e-6 0.6599782 0.7512966 0 0.6599647 0.9712749 0 0.2379607 0.9712747 0 0.237961 -0.5562368 -0.06918132 0.8281392 -0.5763472 -0.146318 0.8039994 -0.5728635 -0.14177 0.8072972 -0.5029354 -0.1015779 0.8583345 -0.5349422 -0.1696743 0.8276761 -0.3679262 -0.4636331 0.806024 -0.4224179 -0.4853927 0.7654783 -0.2873509 -0.5379242 0.7925068 -0.2108699 -0.4659608 0.8593106 -0.1089406 -0.1910624 0.9755138 0.04716914 -0.2458047 0.9681711 -0.07668322 -0.5207386 0.8502653 -0.3118429 -0.7055487 0.636361 0.03120106 -0.8382958 0.5443221 0.2198841 -0.6633877 0.7152397 0.3478258 -0.2696009 0.8979602 0.6574984 -0.3258451 0.6793534 0.008529186 -0.9368405 0.3496529 -0.01760828 -0.7925553 0.609546 -0.1933844 -0.8588166 0.4743801 -0.06004387 -0.9436027 0.3255898 0.7144407 -0.3091722 0.6276839 0.6160475 -0.7053889 0.3505883 0.4061797 -0.890061 0.2069048 0.3384894 -0.9396987 0.04890048 0.4446636 -0.8874267 0.1214423 0.9409967 -0.2477312 0.2305526 0.815414 -0.5788037 -0.00930339 0.9582869 -0.2445883 0.1478614 0.118026 -0.965727 0.2311738 0.4715322 -0.01438325 0.8817316 0.412339 -0.3059516 0.8581201 0.2931747 -0.7044059 0.6464217 0.1430625 -0.9533309 0.2658821 0.3391804 -0.3852117 0.8582358 0.1304555 -0.9094468 0.3948265 0.07104367 -0.9424946 0.3265838 0.0543124 -0.7523027 0.6565752 0.2044921 -0.3714818 0.9056403 0.03996741 -0.7316387 0.68052 0.01607573 -0.9880259 0.1534491 -0.03997969 -0.7315848 0.6805772 -0.01607775 -0.9880258 0.1534489 -0.07104778 -0.9424942 0.3265836 -0.1304734 -0.909444 0.394827 -0.4424511 -0.1168897 0.8891422 -0.1419802 -0.950008 0.2780762 -0.1385004 -0.9539611 0.2660372 -0.2931624 -0.7044206 0.6464112 -0.4555909 -0.2584397 0.8518486 0.5562838 -0.06906259 0.8281176 0.5464311 -0.07520049 0.8341212 0.5760222 -0.1381741 0.8056714 0.491858 -0.3073638 0.8146185 0.5331549 -0.2320942 0.8135589 0.5242691 -0.2285705 0.8203033 0.4866642 -0.2608661 0.8337307 0.226194 -0.4301882 0.8739418 0.1192969 -0.1963207 0.9732556 0.1085587 -0.1969413 0.9743866 0.2952621 -0.7045485 0.6453152 0.3609424 -0.637109 0.681038 0.2607138 -0.5979807 0.7579233 0.008400857 -0.5754423 0.8177993 -0.2890245 -0.2736122 0.9173884 -0.1371408 -0.6223332 0.7706451 -0.3474891 -0.2725104 0.8972121 3.39265e-4 -0.9540952 0.2995033 -0.06953859 -0.8381032 0.5410615 0.1195395 -0.9101155 0.3967369 -0.379635 -0.7014769 0.6031645 -0.2014105 -0.8733112 0.4435782 -0.6472467 -0.3049449 0.6986275 -0.4819357 -0.6994797 0.5276989 -0.2139152 -0.9764378 -0.02845585 -0.4322341 -0.8915166 0.1355434 -0.7187637 -0.2910695 0.6313932 -0.6910665 -0.679261 0.2470458 -0.4514328 -0.8852335 0.1121171 -0.9365108 -0.2651551 0.2294348 -0.9238853 -0.262365 0.2785691 -0.7754824 -0.6209607 0.1141712 0.08395135 -0.4719861 0.8775998 0.07371973 -0.3143962 0.9464252 0.03183543 -0.7180108 0.6953036 0.05569863 -0.9124087 0.4054726 0.06149959 -0.8951037 0.4415962 0.06956887 -0.9881621 0.1367331 0.0124498 -0.9194352 0.3930448 3.90352e-6 -1 9.41801e-6 5.20875e-7 -1 -2.04363e-6 6.27698e-7 -1 -1.19883e-6 6.63163e-7 -1 -7.93599e-7 -4.10701e-5 0 1 1.6059e-5 0 1 -6.87323e-6 0 1 9.01135e-6 0 1 -1.5586e-5 -7.84104e-6 1 -3.63556e-6 2.30426e-6 1 3.53302e-6 2.76238e-6 1 0 1.83106e-6 1 -2.43332e-6 3.04165e-7 1 -3.65032e-6 5.80305e-7 1 3.99102e-6 6.54716e-7 1 -2.66633e-6 4.07785e-7 1 -2.7439e-6 1.41935e-7 1 0 5.72204e-6 1 0.04408562 -0.7186193 0.6940049 -0.04408627 -0.7186175 0.6940068 0.1970235 -0.3283075 0.9237944 -0.1148183 -0.9055542 0.4083974 0.3531469 -0.8725537 0.3375462 0.1973821 -0.8019853 0.5637908 -0.1888835 -0.6710025 0.7169929 -0.2527742 -0.650106 0.7165665 0.1260037 -0.6533983 0.7464541 -0.2126874 -0.2951406 0.9314806 -0.2042734 -0.3007056 0.931584 0.1040272 -0.3002272 0.9481782 -7.66877e-5 -0.1876331 0.9822393 0.2625849 -0.1267631 0.956546 0.2700877 -0.1371639 0.9530156 -0.2703548 -0.1375392 0.9528859 7.66877e-5 -0.1876352 0.9822388 -0.1040279 -0.3002293 0.9481775 0.2042766 -0.3006989 0.9315853 0.2126827 -0.2951478 0.9314795 -0.1260026 -0.6533963 0.7464561 0.2527777 -0.6501016 0.7165693 0.1888812 -0.6710073 0.7169889 -0.1973825 -0.8019827 0.5637942 -0.3531537 -0.8725557 0.3375337 0.1148201 -0.9055529 0.4083998 -0.1970813 -0.3274838 0.9240744 -0.01244151 -0.919433 0.3930501 -0.06952518 -0.9881662 0.1367257 -0.06146055 -0.8951021 0.4416051 -0.05566406 -0.9124087 0.4054775 -0.03181552 -0.7180086 0.6953067 -0.07368135 -0.3143103 0.9464566 -0.2046101 -0.3709416 0.905835 -0.05429589 -0.7522495 0.6566374 -0.3395892 -0.3843276 0.8584704 0.9732064 -0.1935856 0.1240735 0.8166108 -0.5456638 -0.188143 0.9023569 -0.3499321 0.2515942 0.9094913 -0.2006037 0.3641209 0.5490273 -0.8216667 0.1530783 0.1945943 -0.9782637 -0.0716477 0.2984476 -0.9540886 0.02538162 0.3363667 -0.9375879 0.08824169 0.3466362 -0.9248397 0.1565722 0.7418124 -0.3885729 0.5465579 0.3200497 -0.9223806 0.2162926 0.3452997 -0.8654575 0.3629759 0.2957094 -0.8938256 0.3370933 0.2087602 -0.9238765 0.3207358 0.107412 -0.9363892 0.3341228 0.6468907 -0.3287454 0.6880835 0.6125394 -0.2361295 0.7543464 0.3827741 -0.3879532 0.8384369 0.1960179 -0.2749704 0.941259 0.1666682 -0.279492 0.9455718 -0.02492821 -0.1190559 0.9925746 -0.078166 -0.1847254 0.9796769 -0.3273641 0.02956467 0.9444357 -0.366091 0.03954058 0.9297386 -0.3923577 0.003085732 0.9198076 -0.4278044 -9.70372e-4 0.9038708 -0.7175811 0.002586185 0.6964702 -0.6999162 0 0.714225 -0.9997621 -0.02027523 0.008047997 -0.1050825 0.9935915 0.04163748 0.009287655 0.9989368 0.04515779 -0.07535785 0.9953442 -0.0600931 0.04501128 0.9983414 -0.03589534 -0.07723855 0.9952924 -0.05854493 0.04527288 0.9983851 -0.03431439 0 1 -3.96134e-6 0 1 1.76811e-6 1 -1.23874e-4 0 -0.543058 0.839695 4.81564e-4 -0.8264393 0.563026 3.26399e-4 -0.9801963 0.1980285 0 -0.9803798 0.1952774 0.02687489 0.4829752 0.8754935 -0.01568573 0.552717 0.8333691 -1.38711e-4 0.8264394 0.5630257 3.26037e-4 0.9800179 0.1989096 1.65037e-4 0.9659219 -0.2588335 0 0.7070871 -0.7071101 0.004824459 0.2587996 -0.9659243 0.003612041 -0.2588242 -0.9659245 0 -0.7070856 -0.7071117 0.004823327 -0.9659214 -0.2588106 0.003612875 -0.5393827 0.8339684 0.1164609 -0.8263171 0.5628948 -0.01869899 -0.8509969 0.5205001 0.06988495 -0.9828308 0.1844589 -0.004311978 0.6048113 0.7911733 0.09082007 0.8263233 0.5628854 -0.0187093 0.8509936 0.5205033 0.069902 0.9800152 0.1989188 -0.001196682 -0.3826013 0.9238361 0.01196557 -0.6054936 0.7920593 -0.07758605 -0.982422 0.1831318 0.03619015 -0.8434682 0.5313514 -0.07891225 -0.9204171 0.3813195 -0.08618438 -0.3511031 0.9344635 0.05920141 -0.7671253 0.4246752 0.4808014 -0.30855 0.9234274 0.2282076 -0.3523108 0.909461 0.2208118 -0.768274 0.3935215 0.5048722 -0.1669273 0.9277191 0.333875 -0.2949079 0.4132785 0.8615279 -0.3027046 0.4024117 0.8639647 -0.1389532 0.9074012 0.3966298 0.002523839 0.9349589 0.3547472 0.2963587 0.4032523 0.8657708 0.3010104 0.4138914 0.8591198 0.1392916 0.9069396 0.3975657 0.1703311 0.928636 0.3295797 0.7682684 0.3935372 0.5048685 0.349474 0.9026596 0.2511447 0.7671205 0.4246799 0.4808049 0.3527261 0.9340001 0.05681711 0.9204785 0.383482 -0.07523989 0.6135499 0.7808734 0.1174457 0.4356908 0.8971719 -0.07250112 0.9823441 0.1835767 0.03605121 0.8434673 0.5313539 -0.07890462 0.6050399 0.7904077 0.09582602 0.4783669 0.8781304 -0.007226884 0.9978135 0 -0.06609296 0.997798 -1.25194e-4 -0.06632816 -0.8357062 0 0.5491769 -0.323853 0 0.9461075 -0.3238531 0 0.9461074 0.3238514 0 0.946108 -0.9970437 0.005227029 -0.07665872 -0.9977977 0 -0.06633216 -0.9644939 -0.258421 -0.05449843 -0.6995447 -0.6995636 0.1457675 -0.6235514 -0.6657878 0.4097685 -0.2084822 -0.765229 0.6090648 0.2084813 -0.7652282 0.6090662 0.623553 -0.6657857 0.4097695 0.9644863 -0.2584495 -0.05449891 0.6995447 -0.6995636 0.1457672 0 1 1.39909e-6 -0.1872045 0.9823209 -4.94347e-4 -0.6798595 -0.715054 0.1627544 0.2588017 -0.9659305 0 0.6798594 -0.7150544 0.1627527 0.680618 -0.4674216 0.5641598 0.684151 -0.4691834 0.5583946 -0.06979513 0.991136 -0.11304 0.4937724 -0.5547939 0.6696213 -0.8891696 -0.2823281 0.3600952 -0.06967383 0.9911667 -0.112846 1 0 -5.2395e-5 -0.5555935 0.8314541 -3.21888e-4 -0.8314814 0.5555528 -1.63858e-4 -0.9807841 0.1950969 1.67725e-4 0.1950917 0.9807808 0.002891421 0.5555554 0.8314796 -3.21513e-4 0.8314709 0.5555682 -1.62751e-4 0.9807818 0.1951081 -5.13732e-5 0.9807748 -0.195084 0.004795193 0.8314688 -0.5555663 -0.002417623 0.5555701 -0.8314662 -0.002418398 0.1950905 -0.9807853 0 -0.1950844 -0.9807748 0.004794239 -0.5555857 -0.8314559 -0.002417564 -0.8314639 -0.5555737 -0.002418637 -0.9807841 -0.1950969 0 -0.1950758 0.9807882 0 -0.4398642 0.8976948 0.02575904 -0.3430797 0.9296294 -0.1344832 -0.1209133 0.9899573 -0.07324415 -0.9531854 0.2032546 0.2238866 -0.9473337 0.2911731 0.1333307 0.1918236 -0.8630234 0.4673269 -0.1259078 -0.5479844 0.8269586 -0.1824608 -0.6903202 0.7001187 -0.2695353 -0.7382375 0.6183496 -0.04402703 -0.7844851 0.6185829 0.3448712 -0.8710669 0.3497232 -0.2490041 -0.6207391 0.7434245 -0.5327382 -0.6768699 0.5079737 -0.4865662 -0.685885 0.5411241 -0.9643704 -0.1841113 0.1899811 -0.9393291 -0.2293926 0.2550294 -0.9744558 0.2097574 0.0802353 -0.9417689 -0.1188918 0.3145411 -0.47203 -0.5159705 0.7148162 -0.5530092 -0.4998651 0.6665701 -0.107047 -0.9371785 0.3320203 -0.08362579 -0.9754936 0.2035164 -0.9561833 0.278514 0.09024131 0.818397 -0.5591312 0.1326603 0.2641158 -0.9384393 0.2226534 0.3083099 -0.9294109 0.2028315 0.3333426 -0.9270873 0.1714409 0.4158322 -0.9039104 0.100148 -0.0201013 -0.9983823 0.05318695 -0.2465073 0.9682106 -0.04245507 -0.2326105 0.9725036 -0.01136696 -0.2238139 0.9730722 -0.05511879 -0.179786 0.9814466 -0.06663066 -0.09303051 0.9914761 -0.09121805 -0.1322363 0.9512194 0.278739 -0.1913794 0.9384491 0.2875542 -0.2423986 0.9549323 0.171311 -0.1703892 0.9612234 0.2168343 -0.170974 0.9616594 0.2144276 -0.214473 0.9610535 0.174292 -0.2146787 0.9620076 0.1686846 -0.2470538 0.9608834 0.1251707 -0.245663 0.9626376 0.1139242 -0.26771 0.9606189 0.07445025 -0.2631568 0.9632421 0.05397623 -0.2767165 0.9606146 0.02544921 -0.2688905 0.9631384 -0.007906079 -0.2554128 0.9665963 0.02135545 -0.06977128 0.9915631 -0.1092462 -0.3400523 -0.6262935 0.7015134 -0.2235274 -0.5177186 0.8258348 -0.2764627 0.3216268 0.9056074 -0.6454439 -0.570694 0.507652 -0.6437101 -0.5743148 0.5057665 -0.8400881 0.2612391 0.475401 -0.6797994 0.6452875 0.3485353 -0.8839502 0.08803063 0.4592198 -0.8141434 0.3264344 0.4802199 -0.7574713 0.3963568 0.5187858 -0.5314271 -0.5620051 0.6338263 -0.49642 -0.6743949 0.5465882 -0.6976424 0.3153098 0.6433311 -0.452665 -0.639333 0.6215688 -0.4963524 0.3667766 0.786835 -0.5515167 0.1910752 0.8119851 -0.4038561 0.4439343 0.7998891 -0.4172182 -0.5408343 0.7303611 -0.7042384 -0.60282 0.3750419 -0.5508995 -0.7064279 0.4443755 -0.9400312 -0.1471374 0.3077208 -0.9538579 0.1967604 0.226805 -0.7761563 0.6074858 0.1689454 -0.8967693 0.4055957 0.1769102 0.3300452 -0.8072382 0.4893227 -0.2001935 -0.568071 0.7982594 -0.1971307 -0.7726789 0.6034126 -0.5600999 -0.4294062 0.708448 -0.7705115 -0.5968961 0.2236676 -0.8949335 -0.3911104 0.214771 -0.8690226 -0.3156638 0.380994 0.4041016 -0.5643867 0.7198401 0.3380058 -0.8513108 0.4012756 0.5200937 -0.7874122 0.3308845 0.1497383 -0.7814201 0.6057733 -0.6730825 -0.653711 0.3458641 -0.7948731 -0.5232976 0.3071425 -0.9338671 0.3528715 -0.05808728 -0.8466212 0.5286374 -0.06144374 -0.7798328 0.6256815 -0.0195834 -0.7979624 0.6005198 -0.05130374 -0.7679969 0.6403045 -0.0138157 -0.8011792 0.5893303 -0.1039317 -0.7627705 0.644436 -0.05369722 -0.7271161 0.6859998 0.02658385 -0.7186803 0.6953403 -6.99698e-4 -0.6761894 0.7332347 0.07165735 -0.1938185 -0.8716284 0.4502205 -0.3348625 -0.67114 0.6613912 -0.1441257 -0.9396895 0.31018 -0.1445418 -0.9396896 0.3099858 -0.1497857 -0.939287 0.3087141 -0.1492024 -0.9378128 0.3134419 -0.148566 -0.937618 0.3143259 -0.1064831 -0.9430903 0.3150271 -0.1649997 -0.9329211 0.3200522 0 1 6.04166e-7 0 1 -5.00094e-7 0 1 1.1898e-6 0 1 -2.00214e-7 0 1 2.18865e-7 0 1 -7.22525e-7 -0.1431158 -0.9386849 0.3136695 -0.5999657 0.7818635 -0.1695013 -0.3586198 0.9302898 -0.07715541 -0.341605 0.9305937 -0.1315351 -0.4758468 0.8778123 -0.05491286 -0.3378086 0.9405955 0.0341413 -0.3705793 0.9288004 -9.99339e-4 -0.2694854 0.9591626 -0.08593559 -0.9987608 0.02242249 0.04443156 -1 2.00674e-6 0 -1 2.10068e-6 0 -0.001180112 -0.9999988 -0.001037061 0.6689701 -0.7179104 0.1925714 0.7136576 -0.6457921 0.271377 0.6746108 -0.6515443 0.3469732 0.6488735 -0.6298767 0.4268708 0.6481448 -0.6266615 0.4326704 0.5822682 -0.648095 0.490853 0.6805571 -0.5790713 0.4489082 -0.5587527 0.8293179 -0.005236923 -0.630417 0.7734391 -0.06608015 -0.6232809 0.7819285 -0.01042681 -0.6235331 0.781615 -0.01686447 -0.5816636 0.8124362 0.04018729 -0.5818997 0.8114981 0.0535137 -0.5660055 0.8204928 0.08018398 -0.5820387 0.8125513 0.03148514 -0.5772525 0.8084238 0.115024 -0.5437502 0.8255088 0.1512322 -0.5412142 0.8206722 0.1832606 -0.4846042 0.8395704 0.2455208 -0.5106952 0.8274887 0.233352 -0.4737935 0.8160199 0.3311064 -0.4043738 0.8535223 0.3286055 -0.3968793 0.8348701 0.3814169 -0.3206759 0.8547791 0.4080683 -0.3303018 0.84811 0.4142587 -0.2594583 0.826846 0.4990063 -0.2167979 0.862659 0.4569661 2.42275e-4 -1 -3.1378e-5 -0.001079082 -0.9998143 0.01923954 -0.2663806 -0.9281529 0.2599495 -0.2226665 -0.9283239 0.2977155 0.09301066 0.9914767 -0.09123086 0.1393759 0.9861054 -0.09039157 0.1375467 0.9871779 -0.08099925 0.1494146 0.9872229 -0.05537468 0.06819528 0.9915382 -0.1104601 0.07177078 0.9910705 -0.1123766 0 1 -1.44673e-6 0 1 1.0933e-6 0 1 0 0 1 -6.40653e-7 0 1 1.6673e-7 0 1 5.85521e-7 0 1 -5.62779e-7 -0.008570611 -0.9999616 0.001845896 -0.008046269 -0.9999645 0.002514541 -0.007454633 -0.9999673 0.003173112 -0.006781637 -0.9999697 0.003814041 -0.006014466 -0.9999721 0.004433453 -0.005139946 -0.9999743 0.00501579 -0.004145205 -0.9999762 0.005542337 -0.003021061 -0.9999776 0.005984127 0.3253074 0.8608788 0.3912326 0.3353319 0.840389 0.4257922 0.2328515 0.8649798 0.4445111 0.2502908 0.8126875 0.526207 0.1764578 0.8381843 0.5160521 0.1081538 0.843666 0.5258616 0.1118743 0.8617493 0.4948459 2.93948e-4 0.8386362 0.5446921 -0.009137392 -0.9999578 0.001012504 -0.006301641 -0.9999617 0.006072342 0.1039898 -0.9435225 0.3145655 0.07082647 -0.9362012 0.3442546 -0.005549609 -0.9507322 0.3099638 0.04523396 -0.9048668 0.4232848 0.2568309 -0.8716326 0.417486 0.1445409 -0.9396912 0.3099815 0.1273782 -0.9415367 0.3119029 0.1891195 -0.9183754 0.3475924 0.3039706 0.3429703 0.8888044 0.2804107 0.2789239 0.9184614 0.155316 -0.6371596 0.7549203 0.2523853 -0.5058062 0.8249012 0.1803311 0.4458267 0.8767665 0.02352958 0.3836879 0.9231631 0 -0.5819049 0.8132569 0.4301431 -0.544819 0.7198258 0.3903653 -0.6076905 0.6916121 0.532432 0.4040668 0.7438052 0.4447466 0.03825753 0.8948391 0.4621858 0.5201829 0.7181881 0.2946035 -0.6401302 0.7095367 1.71357e-4 0.9474398 0.3199343 0.1638165 0.9545846 0.2488626 0.1373203 0.9475179 0.2887093 0.2419497 0.9550979 0.1710216 0.1705617 0.9612518 0.2165725 0.1710535 0.961623 0.2145273 0.2145774 0.9610776 0.1740304 0.2147516 0.9619802 0.1687477 0.05806809 -0.9880299 0.1429166 0.06865692 -0.9834015 0.1679516 0.03294652 0.9525738 0.3025193 0.07027983 0.9478479 0.3108783 0.09368062 0.9526406 0.2893094 0.09771579 -0.9210404 0.3770098 0 1 3.02083e-7 0 1 0 -0.04460233 0.9908385 -0.1274741 0.02095043 0.9922779 -0.1222524 0.04459172 0.9908376 -0.1274852 0.04751843 0.9919 -0.1177978 -0.1672725 -0.9285646 0.3313425 -0.03233128 0.9524927 0.3028405 -0.07020837 0.9474694 0.3120462 -0.09561145 0.9524602 0.289272 -0.2322086 -0.6087495 0.7586194 -0.131628 0.4609077 0.8776322 -0.01399797 -0.6233036 0.7818546 0 0.3165827 0.948565 9.45799e-4 0.9999995 -2.75796e-4 -0.105062 -0.9425585 0.3170892 -0.0928263 -0.9347611 0.3429358 -0.03533935 -0.9430735 0.3307018 -0.1682178 0.8287453 0.5337454 -0.1321673 0.7983928 0.5874528 -0.06548112 0.8972913 0.4365556 0.01265805 0.8676763 0.4969684 0.04879659 -0.9986239 0.01921677 0.5249837 -0.6555281 0.5428399 0.1279134 -0.6148375 0.7782114 -0.8030136 -0.2009384 0.5610642 0 1 -8.31664e-7 0 1 -9.83897e-7 0 1 0 0 1 7.65709e-7 0 1 -7.57987e-7 -3.01003e-5 1 -1.88166e-5 1.63584e-4 1 4.54989e-5 4.78764e-4 0.9999999 8.98074e-5 7.1691e-5 1 -5.39712e-6 5.06954e-5 1 -9.53093e-6 -0.001268386 0.9999992 -3.54914e-4 -1.60798e-5 1 1.45829e-4 -5.2518e-5 1 1.53517e-4 -1.03263e-4 1 1.6907e-4 -1.27595e-4 1 1.77463e-4 3.25689e-5 1 -3.72173e-5 0 1 0 2.84776e-6 1 -2.85893e-5 2.17876e-5 1 -1.35249e-5 7.19316e-6 1 -2.50632e-5 1.11396e-5 1 -2.28981e-5 1.51282e-5 1 -1.96002e-5 0 -1 0 3.2689e-4 -1 1.88933e-4 -3.01921e-5 -1 -2.04903e-4 1.37127e-4 1 -7.66889e-5 2.13542e-4 1 -1.98559e-4 0 1 1.34263e-6 5.76875e-5 1 9.98095e-5 1.45004e-4 1 7.02342e-5 -0.0011065 0.9999994 2.04763e-4 -6.36644e-6 1 -1.72845e-5 -7.17073e-6 1 -1.73048e-5 -7.13223e-6 1 0 -6.94155e-6 1 7.56691e-6 -7.38992e-6 1 7.46295e-6 0.1119688 0.9937118 1.68058e-5 0.111816 0.9937289 8.69787e-6 3.66604e-4 1 1.40831e-4 0 1 4.09e-5 3.94434e-4 1 7.33121e-5 0 1 0 2.00161e-5 1 -1.11838e-5 4.4736e-7 1 0 1.78804e-5 1 -1.23145e-5 1.46971e-5 1 -3.01984e-5 0 1 0 0 1 9.08734e-7 -4.44284e-4 0.9999995 9.59907e-4 1.71729e-5 1 -1.4339e-5 1.71315e-5 1 -1.41936e-5 -7.9937e-4 0.9999997 -3.51273e-5 0.001091003 0.9999983 -0.00155431 2.13319e-5 1 -2.31298e-5 0.8296394 0 0.5582997 -0.8980236 -0.2616399 0.3536926 -0.9494912 -0.1210009 0.2895259 -0.8980271 -0.2616347 0.3536873 -0.949492 -0.1209999 0.2895236 -0.8980311 -0.2616292 0.353681 -0.9494931 -0.1209968 0.2895216 -0.06814444 -0.9965406 0.04757255 -0.1110144 -0.9912123 0.07193052 -0.1983147 -0.9699551 0.1409199 -0.2912737 -0.9351806 0.2014865 -0.3265832 -0.9166823 0.2302979 -0.4278199 -0.85344 0.2976753 -0.4369035 -0.8460813 0.3053884 -0.5801893 -0.7071943 0.4040504 -0.5580003 -0.7372873 0.3808454 -0.6899606 -0.5318908 0.4909651 -0.6509934 -0.6135658 0.4469279 -0.7514291 -0.3899708 0.532238 -0.7348878 -0.446139 0.5107837 -0.7939811 -0.2380669 0.559391 -0.7883638 -0.2750521 0.5502989 -0.8158121 -0.08005833 0.5727491 -0.815621 -0.09274435 0.5711051 -0.8165264 0.08000856 0.5717371 -0.8107988 0.1233395 0.5721825 -0.7965629 0.2380096 0.5557328 -0.7738796 0.3242682 0.5440226 -1.32173e-5 4.68658e-4 -0.9999999 -4.40064e-5 4.3556e-4 -1 0.4188722 0.003536522 -0.9080383 0.2125791 -0.01145368 -0.9770768 0.8668085 -0.006250202 -0.4986021 0.9189638 4.36298e-4 -0.3943418 0.9014806 0.005701541 -0.4327822 -0.9197242 -4.96325e-4 -0.3925648 -0.9988456 -0.03721529 -0.03037142 -0.9955021 -0.04019302 0.08579266 0.05326789 -8.75434e-5 -0.9985803 -0.4010694 -0.0543304 -0.9144352 0.01734858 0.01334506 -0.9997605 0.009241819 0.01646214 -0.9998218 -0.001242101 -0.002269923 -0.9999967 0.01311069 0.001632452 -0.9999128 0.4267706 0.01191771 -0.9042814 0.6719533 0.04612934 -0.7391555 0.9406457 -3.25418e-4 -0.3393899 -0.3213763 0.03813886 -0.9461833 -0.4072002 -0.01936894 -0.9131336 -0.007701277 -0.04993236 -0.998723 0 1 -1.21517e-6 0.01046025 0.9999229 0.006704032 -5.27824e-4 0.9999986 0.001597166 -1.78713e-4 0.9999986 0.001674294 1.82334e-4 0.9999986 0.001673996 5.18477e-4 0.9999986 0.001601278 -0.01046025 0.9999229 0.006702721 0 1 9.14827e-7 0 1 -3.03799e-7 0.0361911 -0.9402177 0.3386456 0.102649 -0.945005 0.3105301 0.1109401 -0.9433747 0.3126287 0.1227751 -0.9486515 0.2915248 -0.03619098 -0.9402182 0.3386442 -0.1028522 -0.9450126 0.3104398 -0.1226226 -0.9485899 0.2917895 -0.1109282 -0.9433673 0.3126552 -0.1109333 -0.9433687 0.312649 -0.122615 -0.948591 0.2917891 -0.1028584 -0.9450128 0.3104369 -0.03618693 -0.9402191 0.3386421 0.1227701 -0.9486529 0.2915222 0.1109383 -0.9433733 0.3126334 0.1026554 -0.9450048 0.3105282 0.03618752 -0.9402189 0.3386429 -0.1445484 -0.9396907 0.3099794 0 1 6.07609e-7 0 1 -3.04934e-7 -0.01046061 0.9999228 0.006703138 5.18481e-4 0.9999986 0.001601278 1.82333e-4 0.9999986 0.001674294 -1.78713e-4 0.9999986 0.001673996 -5.27824e-4 0.9999986 0.001597166 0.01046055 0.9999228 0.006704151 0 1 -1.21972e-6 0.01044809 0.9999231 0.006694853 -5.27214e-4 0.9999986 0.001595616 -1.78503e-4 0.9999986 0.001672208 1.82117e-4 0.9999986 0.001672387 5.17885e-4 0.9999986 0.001599192 -0.01044785 0.9999231 0.006695449 0 1 -3.04942e-7 0 1 -6.07595e-7 -0.1109365 -0.9433688 0.3126475 -0.1226224 -0.9485902 0.2917882 -0.03619074 -0.9402182 0.3386445 0.122775 -0.9486514 0.2915253 0.1109402 -0.9433748 0.3126282 0.1026494 -0.9450047 0.310531 0.03619146 -0.9402177 0.3386458 0.1445332 -0.9396937 0.3099773 -0.1214787 -0.9360836 0.3301371 -0.144547 -0.9396919 0.3099763 0 1 1.09897e-6 0 1 -1.09901e-6 0 1 2.19793e-6 0 1 -9.5241e-7 0 1 -9.52156e-7 0 1 9.59339e-7 -0.5736157 -4.58335e-7 -0.8191246 -0.573571 0 -0.8191559 -0.5735622 5.72753e-7 -0.8191621 -0.5735751 -9.35991e-7 -0.819153 0.6826881 -0.04833006 0.72911 0.5759342 8.1355e-4 0.8174957 0.58895 -0.01023763 0.8081047 0.5331689 -0.008830964 0.8459628 0 -0.920579 0.3905566 0 -0.9206038 0.3904983 0 -0.9206254 0.3904469 0 -0.9206275 0.390442 0 -0.9206291 0.3904386 0 -0.9206352 0.3904241 0 -0.9206277 0.3904418 0 -0.9206271 0.3904433 0 -0.9206248 0.3904484 0 -0.9206337 0.3904275 0 1 8.75091e-7 0 1 -4.10727e-6 0 1 -2.45366e-6 0 1 2.03994e-6 0 1 -7.99362e-7 0 1 4.31867e-6 0 1 -6.93178e-7 0 1 1.51088e-6 1 0 0 1 -1.99881e-7 0 1 -1.86259e-7 0 1 0 0 1 1.38721e-7 0 1 -1.24541e-7 0 1 2.07847e-7 0 1 -1.26333e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 6.51112e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.67476e-7 0 1 -2.08167e-7 0 1 2.35828e-7 0 1 -2.70312e-7 0 1 -4.43117e-7 0 1 4.3766e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.37803e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.85363e-7 0 -1 1.38721e-7 0 -1 -2.43752e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.08167e-7 0 -1 2.51215e-7 0 -1 0 0 -1 0 0 -1 1.35157e-7 0 -1 6.51115e-7 0 -1.90104e-5 -0.3749045 0.9270635 3.53855e-6 -0.37489 0.9270693 0 -0.3748994 0.9270656 0 0.7071075 0.7071061 0 0.7071063 0.7071073 0 0.8365738 0.5478542 0 0.8365731 0.5478554 0 0.898551 0.4388694 0 0.9561426 0.2929018 0 0.9901912 0.1397194 0 0.9998573 -0.01689833 0 0.9998572 -0.01690053 0 0.9849037 -0.173103 0 0.984904 -0.173102 0 0.9456979 -0.3250472 0 0.9456982 -0.3250463 0 0.8832074 -0.4689828 0 0.7989683 -0.6013732 0 0.7989673 -0.6013746 0 0.6950564 -0.7189553 0 0.6950558 -0.7189558 0 0.5740295 -0.8188347 0 0.574029 -0.8188351 0 0.4388697 -0.8985507 0 0.2929012 -0.9561427 0 0.2929012 -0.9561428 0 0.1397201 -0.9901911 0 0.1397201 -0.9901911 0 -0.01689922 -0.9998573 0 -0.01689922 -0.9998573 0 -0.1731035 -0.9849037 0 -0.325046 -0.9456983 0 -0.3250458 -0.9456983 0 -0.4689828 -0.8832073 0 -0.601374 -0.7989677 0 -0.718954 -0.6950578 0 -0.8188356 -0.5740282 0 -0.8188362 -0.5740275 0 -0.898551 -0.4388694 0 -0.9561426 -0.2929017 0 -0.9901912 -0.1397194 0 -0.9998573 0.01689833 0 -0.9998572 0.01690053 0 -0.9849037 0.173103 0 -0.9849039 0.173102 0 -0.9456978 0.3250473 0 -0.9456982 0.3250463 0 -0.8832074 0.4689828 0 -0.7989655 0.6013768 0 -0.7989665 0.6013757 0 -0.6371554 0.7707355 0 -0.637155 0.7707358 -0.8910075 0 0.4539886 -0.891008 0 0.4539879 -0.7071043 0 0.7071092 -0.7071043 0 0.7071093 0.7071043 0 0.7071093 0.7071043 0 0.7071092 0.891008 0 0.4539879 0.8910075 0 0.4539886 0.9876884 0 0.1564343 0.9876883 0 0.1564348 -0.9876883 0 0.1564348 -0.9876884 0 0.1564343 -0.4539912 0 0.8910062 -0.4539892 0 0.8910072 -0.4539963 0 0.8910036 0.453992 0 0.8910058 0.4539846 0 0.8910096 0.4539942 0 0.8910046 -0.1564362 0 0.9876881 -0.1564289 0 0.9876893 0.15643 0 0.9876891 0.1564352 0 0.9876883 -0.2631011 -0.9002954 -0.3467652 -0.1796959 -0.906349 -0.3824149 0.334348 -0.8925247 -0.3026732 0.3349564 -0.8920447 -0.3034148 0.9835327 0.1801463 -0.01452398 0.6210286 0.7509599 -0.224461 -0.8998233 0.4325617 -0.05664354 -0.9667052 0.2456487 -0.07167977 0.3670322 -0.8866896 -0.2811921 0.3622159 -0.8894866 -0.2785917 -0.5605934 0.8190392 -0.1221058 -0.04968655 0.9980979 -0.03649336 -0.05698674 0.9765571 -0.2075784 0.16266 0.9844366 -0.06652981 -0.03361511 0.968647 -0.2461568 0.004083693 0.9815441 0.1911924 -0.08374708 0.9277295 -0.3637368 -0.07776176 0.9594801 -0.2708344 -0.06404066 0.9668525 -0.2471742 -0.07747024 0.9280424 -0.3643293 -0.01831793 0.9874434 -0.1569079 -0.02893555 0.9682159 -0.2484369 -0.00332719 0.991356 -0.1311576 -0.006734251 0.9876766 -0.1563639 0.2011194 0.9709568 -0.1295914 0.1715711 0.9763386 -0.1316298 0.173201 0.8229304 -0.5410979 0.001363456 0.1353878 -0.9907917 0.1497246 0.9839175 -0.09741157 -0.405629 0.9095177 -0.09079104 -0.316255 -0.7470064 -0.5847771 -0.3020465 -0.677889 -0.6702495 -0.06273508 -0.80231 -0.5936017 -0.0675047 -0.8108865 -0.581297 -0.01102149 -0.7962208 -0.6049057 -0.0158571 -0.8094701 -0.5869469 -0.001671433 -0.7905492 -0.6123963 -0.003700077 -0.7970896 -0.6038498 1.70641e-4 -0.7930918 -0.6091021 8.59998e-4 -0.7907761 -0.6121049 3.34939e-4 -0.7952235 -0.6063164 0.001003265 -0.793096 -0.609096 -0.002143561 -0.7944436 -0.6073343 -0.002468287 -0.7953861 -0.6060981 -0.01412522 -0.8018992 -0.5972926 -0.01160174 -0.7952094 -0.606224 -0.03387957 -0.822739 -0.5674089 -0.0237981 -0.802073 -0.5967516 0.003752768 -0.9964701 -0.08386564 -0.00537616 -0.9975541 -0.06969141 0.006298243 -0.9929187 -0.118629 -0.002072274 -0.9963548 -0.08528172 0.02330636 -0.9880397 -0.1524287 0.01559203 -0.9929573 -0.1174432 0.167618 -0.9396044 -0.2984088 0.1417362 -0.9620317 -0.2332508 0.1322015 -0.9153221 -0.3804055 0.1119063 -0.949243 -0.2939642 0.1266259 -0.9002087 -0.4166416 0.1169542 -0.9175869 -0.379942 0.1727983 -0.8943608 -0.4126254 0.1732788 -0.8935391 -0.4142009 0.2314541 -0.8948121 -0.3817599 0.2379328 -0.8833972 -0.4037296 0.271546 -0.898977 -0.3436616 0.2801473 -0.8849685 -0.3719521 0.3021169 -0.900515 -0.3127269 0.3104805 -0.8898628 -0.3342844 0.3523783 -0.8875541 -0.2967784 0.3325268 -0.9006499 -0.2797425 0.3331861 -0.8850267 -0.3251382 0.3120599 -0.9013831 -0.3002122 0.3038468 -0.8832855 -0.3570489 0.2832205 -0.9005038 -0.3299686 0.254615 -0.8890826 -0.3803989 0.2408921 -0.9004493 -0.362163 0.1707873 -0.909079 -0.3800094 0.174545 -0.9062883 -0.3849359 0.08180826 -0.9410387 -0.3282588 0.1169403 -0.9170857 -0.3811545 0.04369992 -0.9754717 -0.2157435 0.1121444 -0.9372021 -0.3302665 0.03673708 -0.9990152 -0.02488321 0.06412231 -0.9962092 -0.05878603 0.006486654 -0.9999596 -0.006224274 0.01685124 -0.9995407 -0.02518939 -0.006411135 -0.9999747 0.003084719 3.941e-4 -0.9999712 -0.007586121 -0.01820814 -0.9031013 -0.4290413 -0.03382843 -0.9080421 -0.417511 -0.02090251 -0.8992473 -0.436941 -0.02527123 -0.90266 -0.4296118 -0.02544122 -0.9101434 -0.4135116 -0.0144596 -0.899278 -0.4371386 -0.02406436 -0.9255183 -0.3779374 -0.007837831 -0.9096472 -0.4153078 -0.01015609 -0.9325473 -0.3609051 -0.002408087 -0.9253288 -0.379158 -1.95964e-4 -0.9331931 -0.3593754 2.69207e-4 -0.9327709 -0.3604698 2.45261e-4 -0.9319823 -0.3625037 -0.001120448 -0.933146 -0.3594958 -0.005510628 -0.9300172 -0.3674748 -0.007530868 -0.9314656 -0.3637515 -0.05347251 -0.9293251 -0.3653705 -0.04481071 -0.9262985 -0.3741165 -0.01270705 -0.9952268 0.0967592 -0.03157055 -0.9962677 0.08033758 -0.01775789 -0.9994752 0.0270946 -0.02328169 -0.9993767 0.02653986 -0.002181887 -0.9999975 -5.30424e-4 -0.01532971 -0.9998383 -0.009405374 -0.01314747 -0.9998692 -0.009429931 -0.03922861 -0.9988954 -0.025873 0.9165164 0.3692579 -0.1537739 0.3680654 0.9170877 0.1532258 0.987372 0.1566114 0.02386635 0.9664543 0.2495845 0.06060969 0.9891315 0.1419847 0.0382027 0.9873234 0.1529161 0.04253619 0.9894094 0.139052 0.0416373 0.9890341 0.1414088 0.04260689 0.9859603 0.1590346 0.05089563 0.9893915 0.1389067 0.04253959 0.9491924 0.2986972 0.09906506 0.9860555 0.1602815 0.04477125 -0.2099127 0.9215956 0.3264939 0.954777 0.2888276 0.07056701 -0.9183346 0.3623638 0.1592294 0.158396 0.9537277 0.2555667 0.9562438 0.2925073 0.006112396 0.7768988 -0.5968516 -0.2004906 0.6856722 0.7048334 0.1818339 0.9978555 0.06544679 0.001051008 0.6570678 0.7254196 0.2050083 0.7049594 0.6827739 0.191969 0.7314615 0.6522355 0.1988794 0.6550024 0.7223555 0.2217531 0.7080669 0.6716321 0.2180637 0.7211474 0.6589841 0.2137439 -0.03964489 0.9448269 0.3251627 0.6934807 0.6836228 0.2274737 -0.8301616 0.5209454 0.1986145 -0.1216284 0.9356269 0.3313742 -0.9250524 0.344706 0.1595491 -0.8879563 0.4208752 0.1854664 -0.1087345 0.7297829 0.6749769 -0.1007312 0.9945974 0.02508699 -0.1083323 0.6740674 0.7306827 -0.1149891 0.8354136 0.5374586 -0.0270465 0.9907785 0.1327644 -0.03387826 0.9513012 0.3063959 -0.03683108 0.07128745 0.9967757 -0.0372495 0.619345 0.7842348 0.2061033 0.9772589 -0.04986548 0.2048478 0.9649795 -0.1638655 -0.01687055 -0.06198197 0.9979347 0.1713996 0.801404 0.5730393 0.371371 0.9271211 -0.05030208 0.3663611 0.9167321 -0.1593171 0.2172067 0.9726887 -0.0818423 0.205179 0.9754444 -0.08006131 -0.001041054 0.9941 -0.1084627 -0.003308773 0.9966046 -0.08227062 -0.007456183 0.9653831 -0.2607296 -0.01832842 0.9938445 -0.1092582 -0.02516967 0.8004436 -0.5988795 -0.06486183 0.9829284 -0.1721766 -0.26073 0.9646807 -0.03756356 -0.00714904 0.9983414 -0.05712723 -0.2793248 0.9596197 0.03328484 -0.2575873 0.9657527 0.03115463 -0.3380373 0.9344004 0.1123686 -0.334851 0.93557 0.1121767 -0.29172 0.9490829 0.1189166 -0.3467069 0.9300773 0.1214521 -0.1508471 0.9853612 0.07942557 -0.2811547 0.9551535 0.09291988 -0.06495279 0.9971046 0.03954356 -0.1520716 0.9866089 0.05896723 -0.6539103 0.75623 -0.02274864 -0.5363406 0.8430492 -0.04008746 -0.6937384 0.7195252 0.0317896 -0.6647983 0.7465315 0.02709347 -0.6388543 0.7643744 0.08716028 -0.7076966 0.700562 0.09153437 -0.4240021 0.9005454 0.09612572 -0.6376255 0.763248 0.1043381 -0.2088628 0.9758827 0.06347751 -0.4211513 0.9028652 0.08640545 -0.1316061 0.9905225 0.03930819 -0.2027762 0.9776013 0.0563696 -0.1687934 0.9833432 0.06741708 -0.1478809 0.987251 0.05888038 -0.3022449 0.9347101 0.1869895 -0.2656577 0.9498472 0.1649745 -0.481154 0.7952775 0.3688149 -0.490535 0.7863144 0.3756128 -0.7822627 0.02323788 0.6225152 -0.6620623 0.4947506 0.5629347 -0.6362959 0.5327154 0.5579802 -0.6569643 0.4890578 0.5737774 -0.05849879 -0.9901745 -0.1270133 -0.04657799 -0.992348 -0.1143513 -0.1087211 -0.988952 0.100766 -0.08806014 -0.9881938 0.1253734 -0.121807 -0.9516453 0.2820187 -0.1287865 -0.9530123 0.2741929 -0.118702 -0.9268656 0.3561319 -0.1258957 -0.9287317 0.3487231 -0.1281728 -0.9075279 0.3999561 -0.1222209 -0.9054321 0.4065155 -0.1518524 -0.8802543 0.4495477 -0.1368208 -0.8723182 0.4694052 -0.1854301 -0.8438335 0.5035482 -0.1668558 -0.8305785 0.5313178 -0.2157816 -0.8081929 0.5479624 -0.1999549 -0.7959153 0.5714341 -0.2343256 -0.7878445 0.5695548 -0.2236571 -0.7783299 0.5866687 -0.2505379 -0.7746306 0.5806705 -0.2406616 -0.7634437 0.5993628 -0.2719075 -0.7732284 0.5728736 -0.2567475 -0.7553393 0.6029457 -0.2964558 -0.7916272 0.5342662 -0.2729541 -0.7711161 0.5752182 -0.3241026 -0.7951514 0.5125349 -0.3039461 -0.7822549 0.5437777 -0.4674369 -0.7655708 0.4420455 -0.4277171 -0.693318 0.5799727 1.62555e-4 -0.99239 -0.1231338 -4.454e-4 -0.9922635 -0.1241489 -0.01786136 -0.9970011 0.07529902 -0.009236633 -0.9955982 0.09326833 -0.0290811 -0.9622901 0.2704662 -0.0283907 -0.9619107 0.271886 -0.03630965 -0.9392845 0.341213 -0.0321505 -0.9367811 0.3484359 -0.05368155 -0.9284565 0.3675419 -0.03930968 -0.919007 0.3922767 -0.08282434 -0.9128272 0.3998582 -0.06212288 -0.8951259 0.4414638 -0.1223578 -0.888369 0.442526 -0.1005167 -0.8630478 0.4950202 -0.1656263 -0.8548939 0.4916549 -0.146372 -0.8282511 0.5409024 -0.1990116 -0.8265146 0.5265626 -0.1839694 -0.8045661 0.5646492 -0.2245538 -0.8104489 0.5410622 -0.2108803 -0.7902959 0.5752929 -0.2506961 -0.8125854 0.5261716 -0.231398 -0.7912847 0.5659713 -0.2883771 -0.8323338 0.473349 -0.2510946 -0.8117685 0.5272415 -0.3777623 -0.8278912 0.4145984 -0.3092835 -0.8016744 0.5115291 -0.3678145 -0.8718828 0.3233155 -0.3596819 -0.8483156 0.3885738 0.00380969 -0.9927618 -0.1200394 0.002223312 -0.9924011 -0.1230244 -0.00117892 -0.9976446 0.06858605 0.001006722 -0.997274 0.07378119 -0.005440354 -0.9637541 0.2667368 -0.005083382 -0.9635149 0.2676069 -0.01040655 -0.9433721 0.3315733 -0.006754457 -0.9408096 0.3388685 -0.02198988 -0.9385021 0.3445725 -0.01162081 -0.9313164 0.3640258 -0.04189741 -0.9314734 0.3613891 -0.02606952 -0.91876 0.3939549 -0.0708093 -0.9186089 0.3887725 -0.05294889 -0.8997594 0.4331622 -0.1082811 -0.8970576 0.4284424 -0.0921489 -0.8724011 0.4800261 -0.1458427 -0.8712775 0.4686208 -0.1321532 -0.8466291 0.5155141 -0.1775322 -0.8545945 0.4880068 -0.1628262 -0.8323583 0.5297805 -0.2066265 -0.8551701 0.4753836 -0.1856676 -0.8366829 0.5152566 -0.2349788 -0.8743482 0.4246177 -0.2021975 -0.863227 0.4625532 -0.2769287 -0.8938221 0.3526936 -0.2245646 -0.8895547 0.397823 -0.286087 -0.9221708 0.2602985 -0.2508547 -0.92304 0.2916661 -0.2588828 -0.9481678 0.1842762 -0.2451546 -0.9498822 0.1939668 -0.001115202 -0.9927926 -0.1198406 -0.001373708 -0.9927291 -0.1203626 -4.31406e-4 -0.9974354 0.07157254 -0.001604318 -0.9976426 0.06860578 -9.96806e-4 -0.963804 0.2666102 -0.001111268 -0.9638839 0.2663205 -0.003372073 -0.9449178 0.3272903 -0.001464903 -0.943578 0.3311474 -0.008992433 -0.9425209 0.3340262 -0.003744542 -0.9391115 0.3435924 -0.01963895 -0.939665 0.3415319 -0.01033329 -0.9333599 0.3587934 -0.03659808 -0.9332597 0.3573332 -0.02419185 -0.9233288 0.3832475 -0.06109613 -0.9219124 0.3825505 -0.04824209 -0.9062507 0.4199792 -0.09108692 -0.9051283 0.4152662 -0.07999479 -0.8850877 0.4584982 -0.1204772 -0.8924518 0.4347585 -0.1072379 -0.8731166 0.4755706 -0.149046 -0.8928827 0.4249068 -0.1283816 -0.8771401 0.4627565 -0.1736768 -0.9064158 0.3850283 -0.146165 -0.8978921 0.4152418 -0.1951467 -0.9270857 0.3200468 -0.164241 -0.9242676 0.3446075 -0.2091919 -0.949301 0.2346626 -0.1885398 -0.9497689 0.249784 -0.2156877 -0.9626919 0.1634116 -0.2051464 -0.9633556 0.1728036 -0.01539355 -0.9920959 -0.1245346 -0.01349508 -0.9926062 -0.1206272 -0.005075752 -0.9959926 0.08929187 -0.01226449 -0.9973861 0.07120877 -6.10579e-4 -0.9628424 0.2700635 -0.001982033 -0.9637941 0.2666402 -0.001452267 -0.9456674 0.3251327 -3.9043e-4 -0.9449427 0.3272357 -0.003869593 -0.9440714 0.3297187 -0.001524984 -0.9426484 0.3337838 -0.009425222 -0.9433106 0.3317774 -0.004087984 -0.9402304 0.3405148 -0.01903098 -0.9400506 0.3405036 -0.01028394 -0.9349334 0.3546741 -0.03271865 -0.9336017 0.3568158 -0.02181088 -0.9253616 0.3784578 -0.05093616 -0.9236692 0.3797906 -0.03983187 -0.9108921 0.4107179 -0.07145917 -0.915445 0.3960478 -0.0592705 -0.9019277 0.427801 -0.09230935 -0.917373 0.3871768 -0.07519423 -0.9063799 0.415718 -0.1124851 -0.9279098 0.3554302 -0.09090507 -0.9210083 0.3787877 -0.1217584 -0.9428753 0.3100987 -0.1111251 -0.9413234 0.3186874 -0.1166425 -0.9615637 0.2485758 -0.1330533 -0.9624934 0.2364392 -0.1845719 -0.9742549 0.1294629 -0.1400011 -0.9756156 0.1690382 -0.03357875 -0.9902786 -0.1349853 -0.02885818 -0.9917282 -0.1250699 -0.01031672 -0.9924562 0.122165 -0.02508687 -0.9958774 0.08717191 2.02784e-5 -0.9603943 0.2786449 -0.003788948 -0.9628802 0.2699025 0.001011669 -0.9455811 0.3253849 8.95447e-4 -0.945658 0.3251622 0.001152932 -0.9440325 0.3298507 0.001031696 -0.944103 0.329649 -0.001415908 -0.9449092 0.3273298 0.001153349 -0.9435181 0.331319 -0.007828235 -0.94402 0.3297954 -0.001329362 -0.9407445 0.3391136 -0.01340121 -0.9383229 0.3455007 -0.006956815 -0.9348891 0.3548718 -0.01836442 -0.9296718 0.3679311 -0.01203417 -0.9254337 0.3787186 -0.02582556 -0.92381 0.3819794 -0.01826208 -0.9184849 0.3950344 -0.03508096 -0.9276236 0.3718654 -0.02592515 -0.9227159 0.384608 -0.04808253 -0.9389357 0.3407167 -0.03496021 -0.9342483 0.3549056 -0.04934751 -0.9481624 0.3139311 -0.05119699 -0.9486075 0.3122862 -0.0264241 -0.9575935 0.2869088 -0.05942821 -0.9652028 0.2546605 -0.03295445 -0.9885959 -0.1469429 -0.02692645 -0.9904988 -0.1348601 -0.006857633 -0.9892427 0.1461226 -0.01902258 -0.9924797 0.1209228 0.002483189 -0.9593338 0.2822634 6.53523e-4 -0.9603777 0.2787014 0.005449295 -0.9445413 0.3283475 0.003774344 -0.9455249 0.3255282 0.009856641 -0.9417383 0.3362022 0.005480408 -0.9440275 0.3298215 0.01298218 -0.9432498 0.3318303 0.009667396 -0.9449287 0.3271339 0.01438122 -0.9434383 0.3312363 0.01290923 -0.9441687 0.3292095 0.0231772 -0.9345523 0.3550701 0.01542264 -0.938467 0.3450245 0.03411948 -0.9238003 0.3813515 0.02497869 -0.9288896 0.3695136 0.03664201 -0.920814 0.3882766 0.03461545 -0.9219602 0.3857349 0.02125483 -0.933562 0.3577851 0.03580951 -0.9263222 0.3750265 -0.01474481 -0.9537724 0.300168 0.02063971 -0.9397221 0.3413159 -0.03884756 -0.9584811 0.2824975 -0.01489889 -0.9501361 0.3114795 -0.04746854 -0.9611147 0.2720394 -0.0396794 -0.9566681 0.2884642 -0.02074038 -0.9890521 -0.1461021 -0.02088248 -0.989013 -0.1463467 -0.002547562 -0.9874338 0.1580131 -0.009852766 -0.9892765 0.145723 0.00403285 -0.9587582 0.2841942 0.002746939 -0.9593255 0.2822889 0.01048433 -0.9421501 0.3350272 0.005305528 -0.944547 0.3283334 0.02098399 -0.9376354 0.3469864 0.01052474 -0.9417356 0.3361894 0.03229558 -0.9382975 0.3443182 0.02028739 -0.943121 0.33183 0.047544 -0.9355036 0.3501036 0.03156405 -0.9426965 0.3321553 0.07747834 -0.9184339 0.3879128 0.0483663 -0.9327742 0.3572018 0.099128 -0.9078845 0.407332 0.07716941 -0.9192597 0.3860139 0.08744251 -0.9186288 0.3853248 0.0970025 -0.9140895 0.3937398 0.03309822 -0.9492779 0.3126916 0.08534693 -0.9301686 0.3570747 -0.01305973 -0.9697352 0.2438102 0.03528505 -0.9570091 0.2879039 -0.04898607 -0.9688078 0.242924 -0.02077484 -0.9607848 0.276516 -0.07789456 -0.9666159 0.2441029 -0.05826067 -0.9596332 0.2751542 -0.116576 -0.9703214 0.2118644 -0.07889693 -0.9656985 0.2473896 -0.1462917 -0.9786096 0.1446443 -0.1075395 -0.9771014 0.183598 -0.08890759 -0.9924809 0.08412528 -0.1529265 -0.9869042 0.05132007 -0.07700663 -0.9966485 0.027601 -0.110571 -0.9938538 0.005373775 -0.07016968 -0.9972484 -0.02391874 -0.09712934 -0.9945459 -0.03800743 -0.03857135 -0.9989684 -0.02397173 -0.07703882 -0.9961389 -0.04209995 -0.0121662 -0.9900795 -0.139981 -0.01782935 -0.989164 -0.1457284 -4.77836e-4 -0.9867408 0.1623035 -0.005513846 -0.9874926 0.1575695 0.00408709 -0.9585096 0.2850312 0.002860248 -0.9588051 0.2840504 0.01339596 -0.9402577 0.3402001 0.00520271 -0.9424573 0.3342861 0.0287761 -0.9347981 0.3540121 0.01370948 -0.9376468 0.3473193 0.04617923 -0.9343739 0.3532888 0.02803337 -0.9384443 0.3442913 0.07410007 -0.926756 0.3682832 0.04577976 -0.9356821 0.3498619 0.1220742 -0.9014343 0.4153482 0.07794636 -0.9183604 0.3879933 0.1364986 -0.8976323 0.4190757 0.1210457 -0.9037194 0.4106569 0.07874178 -0.9276164 0.3651404 0.1311731 -0.9124247 0.3876531 0.003532946 -0.9583346 0.2856265 0.07899963 -0.9498705 0.3024982 -0.02254229 -0.9744564 0.223443 0.01859986 -0.9741588 0.2250972 -0.05497771 -0.9744327 0.2178501 -0.02511829 -0.9728032 0.2302675 -0.09922909 -0.9728563 0.2090561 -0.06332623 -0.9685288 0.240711 -0.1427408 -0.9750505 0.1700048 -0.09956932 -0.9725298 0.2104083 -0.1483584 -0.9793462 0.137371 -0.1391316 -0.9794886 0.1457554 -0.1027218 -0.9889315 0.1070648 -0.145233 -0.986348 0.07762092 -0.07570189 -0.9958933 0.0496571 -0.1188637 -0.9927104 0.01994264 -0.04851901 -0.9988212 0.001515924 -0.09631311 -0.9950402 -0.02487421 -0.01394379 -0.9998971 -0.003408551 -0.05691254 -0.9980829 -0.02432256 0.003607273 -0.9174987 0.3977226 0.02924668 -0.9141625 0.4042915 -0.1510202 -0.9289819 0.3379135 -0.08088296 -0.9457136 0.3147758 -0.2606998 -0.9177302 0.2996783 -0.1381313 -0.9448303 0.297011 -0.3289278 -0.9205938 0.210508 -0.2508915 -0.940634 0.228607 -0.3114387 -0.9373372 0.1562207 -0.334613 -0.9303674 0.1498357 -0.284116 -0.9497955 0.1310214 -0.319757 -0.9398432 0.1202095 -0.2599349 -0.9569814 0.1289208 -0.2874674 -0.950303 0.1195275 -0.238751 -0.961342 0.1371846 -0.2597995 -0.9569575 0.1293704 -0.2177584 -0.9646015 0.1487463 -0.2376469 -0.9610656 0.140986 -0.1911525 -0.9682489 0.1611055 -0.217104 -0.9643827 0.1511022 -0.1467893 -0.9747797 0.1681002 -0.19348 -0.9692962 0.1517581 -0.07680797 -0.9860469 0.1476892 -0.1536054 -0.9798154 0.1279353 -0.0336039 -0.9964625 0.07702744 -0.07822501 -0.9942929 0.07254481 -0.01010572 -0.9967548 0.07986056 -0.002608358 -0.9956993 0.09260779 -0.04164993 -0.9893239 0.1396555 -0.009988307 -0.98127 0.1923782 -0.1027618 -0.981338 0.16253 -0.04912716 -0.9654346 0.2559739 -0.1871369 -0.9651077 0.1831582 -0.120002 -0.9460636 0.3009372 -0.297579 -0.9297911 0.2166457 -0.2126623 -0.9192443 0.3313074 -0.3808824 -0.9022576 0.2021386 -0.3120838 -0.9053252 0.2880798 -0.4423471 -0.8800659 0.1726654 -0.386572 -0.8913981 0.2365832 -0.4717832 -0.867524 0.1575527 -0.4436371 -0.8752173 0.1928234 -0.4726864 -0.8634982 0.1758937 -0.4717705 -0.8637478 0.1771224 -0.463172 -0.8618176 0.2067417 -0.4721065 -0.8597815 0.1946569 -0.4492775 -0.8604624 0.2403209 -0.4622853 -0.8582687 0.2228609 -0.4252495 -0.8606886 0.2799609 -0.4486672 -0.8582208 0.2493092 -0.379113 -0.8692668 0.3172519 -0.4264356 -0.8672805 0.2568607 -0.3088476 -0.8953292 0.3209345 -0.3788098 -0.8971799 0.2270937 -0.2351873 -0.9282256 0.2882434 -0.2944836 -0.9342887 0.2009578 -0.1479108 -0.9331585 0.3276241 -0.2121821 -0.950579 0.226668 -0.04785007 -0.9298108 0.3649141 -0.1048603 -0.9603418 0.2583561 0.02382493 -0.9753916 0.2191886 0.03319519 -0.9701474 0.2402339 -0.02064818 -0.9895939 0.1423996 0.03184854 -0.978735 0.2026409 -0.03148257 -0.9902101 0.1359887 -0.02083963 -0.9894362 0.1434642 -0.01769852 -0.9989737 0.04169583 0.006563305 -0.9966028 0.08209598 -0.07403022 -0.9958949 0.05208563 -0.02403265 -0.9899134 0.1396208 -0.1484543 -0.9881569 0.03882294 -0.08923524 -0.982918 0.1609641 -0.2366582 -0.9705002 0.04606807 -0.1754068 -0.967779 0.1806552 -0.3426154 -0.9359303 0.08154255 -0.2688563 -0.9407066 0.206851 -0.4258928 -0.8989551 0.1024465 -0.361768 -0.9111391 0.1973561 -0.4695585 -0.8749225 0.1184294 -0.4321885 -0.8853747 0.1712453 -0.4781778 -0.8660174 0.1461508 -0.4703391 -0.868308 0.1575518 -0.472018 -0.8622187 0.1837885 -0.4776822 -0.8608284 0.175483 -0.4612378 -0.8595123 0.2202236 -0.4710811 -0.8577069 0.2059651 -0.4474452 -0.8566786 0.2566996 -0.4599195 -0.8551291 0.2392245 -0.4195684 -0.8529383 0.3105782 -0.4454105 -0.8512617 0.2774221 -0.3440933 -0.8524129 0.3936905 -0.4195569 -0.8529067 0.3106806 -0.2195584 -0.8719235 0.4376569 -0.3489512 -0.8839473 0.3112397 -0.1381626 -0.9273834 0.3476654 -0.1754538 -0.9349129 0.3084701 -0.07196295 -0.9092487 0.4099859 -0.1262324 -0.9336003 0.3353444 0.05849009 -0.8487957 0.5254759 -0.04410564 -0.9296048 0.3659095 0.1659846 -0.9478328 0.2721439 0.1687093 -0.9446262 0.2814582 0.08440703 -0.9959347 -0.03145694 0.2116005 -0.9625803 0.1693059 -0.0439558 -0.9971852 0.06074243 0.07517546 -0.9877122 0.1370158 -0.02109426 -0.9997123 -0.0114209 0.03241521 -0.9987572 0.03786134 -0.1040779 -0.9942011 -0.02705907 -0.0300619 -0.9985306 0.04508841 -0.1913192 -0.9800519 -0.05380696 -0.1167341 -0.9926164 0.03295248 -0.283091 -0.9579406 -0.04700422 -0.212444 -0.9762881 0.04158234 -0.3805463 -0.9247469 -0.005280435 -0.3068634 -0.9488868 0.07381677 -0.4481738 -0.892869 0.04387879 -0.3941637 -0.9137958 0.09804159 -0.4738011 -0.87538 0.09603345 -0.4524126 -0.8840299 0.117533 -0.4759207 -0.8675483 0.1444282 -0.4741758 -0.8682005 0.1462374 -0.4702761 -0.8621138 0.1886806 -0.4750846 -0.8605682 0.1836223 -0.4609203 -0.8576577 0.2279818 -0.4687283 -0.8555727 0.2197487 -0.4467709 -0.853662 0.2676885 -0.4584532 -0.8511856 0.2555459 -0.3804675 -0.8508052 0.3624572 -0.4404979 -0.8440069 0.3059639 -0.07080835 -0.8096985 0.5825587 -0.3745061 -0.843906 0.3841456 0.2787301 -0.7425549 0.6090337 -0.07954066 -0.8773459 0.4732205 0.4500086 -0.7690104 0.4539991 0.7591634 -0.6137473 0.2167607 0.4777904 -0.7565971 0.4464047 0.6573375 -0.09650772 0.7473914 0.6524212 -0.3798012 0.6558184 0.7010161 -0.6691099 0.2467154 0.7070053 -0.6630215 0.2460613 -0.02685779 -0.955734 -0.2930036 0.0431087 -0.9771355 -0.2082016 -0.08456408 -0.959464 -0.2688457 -0.03393882 -0.9774513 -0.2084161 -0.1215369 -0.9651021 -0.2319628 -0.08917117 -0.9773392 -0.1919809 -0.1548199 -0.9709963 -0.1822009 -0.1255424 -0.9813666 -0.1454604 -0.1894145 -0.9736717 -0.1268289 -0.1586859 -0.9833948 -0.08805453 -0.224695 -0.972095 -0.06740731 -0.1931546 -0.9807834 -0.02748662 -0.2568457 -0.966451 0.001690983 -0.2280729 -0.9729038 0.03796178 -0.2652636 -0.9592018 0.09781223 -0.2582654 -0.9601933 0.1064324 -0.231668 -0.9482851 0.2169917 -0.2632316 -0.9476919 0.1805251 0.04400914 -0.8492078 0.5262217 -0.2273704 -0.9323149 0.2812322 0.06710749 -0.8783374 0.4733077 -0.002916336 -0.9125801 0.4088876 0.4986566 -0.4102755 0.7635548 0.2264113 -0.6726326 0.7044879 0.04405516 -0.9350239 -0.3518374 0.08037412 -0.9503359 -0.3006691 0.01243215 -0.9488232 -0.3155629 0.03931069 -0.9607104 -0.2747551 -0.01548987 -0.9614794 -0.2744404 0.008359551 -0.9715441 -0.2367116 -0.04612028 -0.9720939 -0.2300142 -0.01947104 -0.9821233 -0.1872292 -0.08030313 -0.9802235 -0.1808682 -0.05019074 -0.9899595 -0.1321408 -0.1133915 -0.9862391 -0.1203115 -0.08386802 -0.993838 -0.07247382 -0.115957 -0.9932471 -0.003763914 -0.1143466 -0.9934402 -0.001208782 -0.004684746 -0.9658284 0.2591401 -0.1098337 -0.9882717 0.1060925 0.1768505 -0.8474303 0.5005856 -0.003850579 -0.9641318 0.2653962 0.4618275 -0.357388 0.8117816 0.1777524 -0.8513656 0.4935393 0.1602572 -0.9175868 -0.3638026 0.1705614 -0.9210762 -0.3500393 0.1445141 -0.9299921 -0.3379802 0.1588349 -0.9353651 -0.3160121 0.1233884 -0.9429051 -0.3093631 0.1422917 -0.9498609 -0.2784195 0.09576982 -0.9561018 -0.2769432 0.1204474 -0.9643397 -0.2356724 0.06300705 -0.9696723 -0.2361476 0.09264004 -0.9781497 -0.1861211 0.04305183 -0.9870175 -0.1547356 0.06231802 -0.9905381 -0.1222729 0.1268629 -0.9844191 0.1217581 0.05350404 -0.9985676 5.14949e-4 0.3688575 -0.7146466 0.5943269 0.1567848 -0.94762 0.2782716 0.2627719 -0.8988674 -0.3506969 0.2552517 -0.8970924 -0.3606548 0.2612134 -0.9034488 -0.3399235 0.2627648 -0.9038912 -0.3375434 0.2518296 -0.9110326 -0.3264991 0.260816 -0.913657 -0.3117787 0.2338293 -0.921862 -0.3090215 0.2511246 -0.9265117 -0.2802008 0.2104268 -0.9375397 -0.2770195 0.234278 -0.9428681 -0.2368829 0.2143054 -0.9633898 -0.1611001 0.2194745 -0.9636617 -0.1522731 0.3773422 -0.8689006 0.3203511 0.257076 -0.961385 0.098239 0.321874 -0.8890856 -0.3254597 0.304214 -0.8864717 -0.3487433 0.33074 -0.8860228 -0.3249225 0.3216696 -0.8841766 -0.3387633 0.3334272 -0.8863095 -0.3213752 0.3307279 -0.8857156 -0.3257716 0.3302997 -0.8905838 -0.3126702 0.3339422 -0.8913277 -0.3066229 0.3267956 -0.9021637 -0.2816121 0.3344202 -0.9033596 -0.268523 0.3712083 -0.9213786 -0.115178 0.350391 -0.9239446 -0.1534681 0.3530907 -0.8859348 -0.3007431 0.3332039 -0.8851429 -0.3248034 0.364919 -0.8792266 -0.3062595 0.3520918 -0.8780269 -0.3241915 0.372405 -0.875664 -0.3074528 0.3642024 -0.8746291 -0.3199697 0.3783023 -0.8762077 -0.2985755 0.3723157 -0.8753572 -0.308433 0.3950734 -0.885181 -0.2457066 0.3837535 -0.884059 -0.2667831 0.3703563 -0.8842005 -0.2846503 0.3520493 -0.8863282 -0.3008052 0.3814013 -0.8768782 -0.2926055 0.3681349 -0.8779432 -0.3060924 0.3908459 -0.8722438 -0.2939901 0.3798918 -0.8726605 -0.3068321 0.4157016 -0.8719616 -0.2586026 0.3905991 -0.8716923 -0.2959474 0.5256429 -0.8486955 0.05844318 0.4198812 -0.8787821 -0.2268084 -0.2981425 -0.9463537 -0.124602 -0.250445 -0.9629549 -0.09997653 -0.3588903 -0.9240681 0.1315139 -0.3394881 -0.9298589 0.1418116 -0.3374437 -0.8991185 0.278779 -0.3701665 -0.89135 0.2616716 -0.3018152 -0.8865623 0.3505924 -0.3359774 -0.8811161 0.3327966 -0.2789427 -0.8696777 0.407249 -0.2997878 -0.8681247 0.3955842 -0.2674852 -0.8417421 0.4689586 -0.2783275 -0.8419778 0.4621766 -0.2662963 -0.8049308 0.5302575 -0.2689719 -0.8051808 0.5285244 -0.2669155 -0.7768815 0.5702732 -0.2677655 -0.7769832 0.5697357 -0.2682585 -0.7645944 0.5860316 -0.2677389 -0.7644934 0.5864008 -0.2756551 -0.7499877 0.6012759 -0.2708677 -0.7484297 0.6053791 -0.2962054 -0.7355141 0.6093288 -0.2819513 -0.7291761 0.623543 -0.3300297 -0.7384307 0.5880481 -0.3031701 -0.721925 0.6220227 -0.345941 -0.7564878 0.5550236 -0.3443217 -0.7204875 0.6019472 0.3830988 -0.8807353 -0.2784613 0.3656868 -0.8860617 -0.2848994 0.3926033 -0.8740262 -0.2862535 0.3784056 -0.878098 -0.2928365 0.4015061 -0.8695096 -0.2876562 0.3902235 -0.8724954 -0.2940707 0.4049007 -0.8750514 -0.2652179 0.4086202 -0.8743851 -0.2616877 0.4324645 -0.89414 -0.1161376 0.4632499 -0.8846732 -0.05246698 0.5314753 -0.6819683 0.5024473 0.5468911 -0.5998479 0.5840315 0.5273544 -0.323993 0.7854463 0.5270299 -0.3813111 0.7595007 0.5140514 -0.2055852 0.8327581 0.514366 -0.2161346 0.8298876 0.9969195 0.07333236 -0.02781873 0.9855659 0.1659177 0.03363275 0.9983174 0.05681353 0.01160448 0.9976966 0.06576222 0.01664543 0.9984027 0.05451732 0.01483136 0.9982836 0.05638438 0.01583194 0.9983437 0.05514407 0.0164051 0.9983929 0.05436277 0.01600676 0.99758 0.06649386 0.02032113 0.9983482 0.05550175 0.01485353 0.9916025 0.1245479 0.03482049 0.9975156 0.06930518 0.0126248 0.9134302 0.3954344 0.09631699 0.9914086 0.1301031 0.01349842 0.1079776 0.960331 0.2571096 0.9316424 0.3605664 0.04510378 -0.9122866 0.4088726 -0.02358841 -0.9116509 0.4102807 -0.02371853 -0.9368572 0.3491795 0.01929688 -0.9214891 0.3880601 0.01634818 -0.9075973 0.4173529 0.04564881 -0.9337635 0.3549228 0.04599475 -0.7654519 0.6411647 0.0546925 -0.9027929 0.4266722 0.05399966 -0.487511 0.8720195 0.04376178 -0.7607584 0.6460343 0.06234097 -0.3620374 0.9306749 0.05266165 -0.5000511 0.8624858 0.07789319 -0.4419661 0.885662 0.1423687 -0.4299318 0.8922611 0.1379458 -0.5513123 0.7779781 0.3013384 -0.5821598 0.7479455 0.3188535 -0.6521664 0.6016873 0.4611414 -0.6915671 0.5328294 0.4876759 -0.7612177 -0.2998287 0.5750221 -0.7217873 0.4300552 0.5422875 -0.4480584 -0.5958563 0.6664825 -0.5802089 -0.4424502 0.6838096 -0.3212727 -0.7183685 0.6170337 -0.5438646 -0.499606 0.6742442 -0.3502233 -0.7061768 0.615352 -0.5563187 -0.4910098 0.6703872 -0.750343 -0.09660112 0.6539523 -0.5905084 -0.4330709 0.6809916 -0.7692191 0.01311933 0.6388505 -0.5651587 0.8077204 0.1678792 -0.4826873 -0.6051719 0.6330719 -0.3989727 -0.6417772 0.6549373 -0.6221145 -0.3989896 0.6736326 -0.4386854 -0.5984956 0.6703419 -0.5640923 -0.4599831 0.6857227 -0.5076067 -0.5248436 0.6832823 -0.4428157 -0.5942549 0.6713981 -0.5301041 -0.5021556 0.6832492 -0.4276117 -0.6157957 0.6617732 -0.5615618 -0.4674891 0.6827168 -0.5462624 -0.4882979 0.6805606 -0.5974673 -0.4172917 0.6847631 -0.7919336 0.110805 0.6004695 -0.6336002 -0.3469631 0.6914966 -0.3877336 -0.6655932 0.63769 -0.3330432 -0.6861893 0.6467044 -0.4903249 -0.5650799 0.6635257 -0.3803079 -0.6482318 0.6596677 -0.5857186 -0.4547212 0.6709414 -0.4494474 -0.5864338 0.673864 -0.5495627 -0.4850839 0.6802018 -0.4967207 -0.5383223 0.680792 -0.5542817 -0.4743251 0.68395 -0.5292655 -0.501487 0.6843895 -0.5875568 -0.4282884 0.6865465 -0.5564983 -0.4667216 0.6873724 -0.6471123 -0.3314251 0.6865881 -0.598624 -0.4034936 0.6919844 -0.6602657 -0.298543 0.6891455 -0.632691 -0.3394673 0.6960345 -0.669453 -0.2718579 0.691322 -0.6550215 -0.2948625 0.6957033 -0.6867761 -0.2295817 0.6896601 -0.6853862 -0.232171 0.6901757 -0.7191492 -0.1473455 0.6790536 -0.7246865 -0.1355869 0.6756078 -0.7406019 -0.08274555 0.6668299 -0.7477329 -0.06696319 0.6606146 -0.7548255 -0.03274589 0.6551077 -0.7597565 -0.02228933 0.6498256 -0.7614818 -0.007521569 0.6481428 -0.763462 -0.003721415 0.6458423 -0.7636702 0.004563331 0.6455906 -0.7637954 0.004837989 0.6454403 -0.763007 0.02062457 0.6460611 -0.7625874 0.01892602 0.6466084 -0.7541431 0.09694594 0.6495151 -0.7555872 0.04297649 0.6536368 -0.7537536 -0.02981895 0.6564805 -0.7546362 0.03297376 0.6553145 -0.751536 0.0609436 0.656871 -0.7520106 0.08335334 0.6538596 -0.3324094 -0.7035362 0.6281249 -0.3197003 -0.7069787 0.6308509 -0.4899126 -0.601859 0.6306753 -0.3711182 -0.6730466 0.6397497 -0.6753524 -0.4132667 0.6108272 -0.4296944 -0.6256802 0.651066 -0.6491266 -0.4209277 0.6336045 -0.4883868 -0.5704364 0.6603642 -0.6408561 -0.4131167 0.6470225 -0.5188636 -0.5338523 0.6676694 -0.6511867 -0.3824551 0.6555028 -0.5397394 -0.5040593 0.6742445 -0.6757441 -0.3263311 0.6609675 -0.5813748 -0.4464549 0.6802069 -0.6772581 -0.3043613 0.66984 -0.6280619 -0.3732488 0.6828057 -0.7020027 -0.2444107 0.6689212 -0.6671172 -0.3012749 0.6813134 -0.7225013 -0.1861031 0.6658511 -0.7051877 -0.2195751 0.6741641 -0.7467151 -0.1092854 0.6561046 -0.7437987 -0.1160936 0.6582444 -0.7595466 -0.0576387 0.6478943 -0.7646076 -0.04496383 0.6429259 -0.7689764 -0.0185126 0.6390092 -0.7712669 -0.01274055 0.6363844 -0.7720171 -0.002317547 0.6355976 -0.7716404 -0.003231227 0.6360508 -0.7716339 0.005549907 0.6360428 -0.7701557 0.001197934 0.6378548 -0.7693026 0.01912397 0.6385983 -0.768426 0.01406663 0.6397841 -0.7664822 0.04526883 0.6406683 -0.7661784 0.03355318 0.6417514 -0.7263287 0.2826035 0.6265636 -0.7598735 0.06625682 0.6466857 -0.7641523 0.01708662 0.6448097 -0.7628275 0.06831783 0.6429829 -0.7636044 0.05805164 0.6430696 -0.7602611 0.1145427 0.6394395 -0.3307473 -0.7258607 0.6031023 -0.3289766 -0.7262389 0.6036154 -0.5375238 -0.6174771 0.5742738 -0.3978523 -0.6894889 0.6052426 -0.7398698 -0.4234209 0.5227882 -0.437937 -0.6569843 0.6136634 -0.7280085 -0.4070432 0.5516517 -0.4872086 -0.6119347 0.6230279 -0.7042954 -0.4085004 0.5805991 -0.5268531 -0.5680259 0.6322757 -0.6969254 -0.3923949 0.6002677 -0.5606222 -0.5254431 0.6400097 -0.7270305 -0.3251212 0.6047503 -0.6096876 -0.4611596 0.6446805 -0.7425336 -0.2721804 0.6120144 -0.656997 -0.3872655 0.6468232 -0.7621389 -0.2056363 0.6138877 -0.6986409 -0.3076492 0.6459512 -0.775751 -0.1442811 0.6143236 -0.745104 -0.2040372 0.6349716 -0.7915068 -0.07254976 0.6068391 -0.7826893 -0.09308552 0.6154125 -0.7980499 -0.02756899 0.6019604 -0.7981888 -0.02721613 0.6017924 -0.8009758 -0.005525946 0.5986713 -0.8003035 -0.007037162 0.599554 -0.8005563 -8.22485e-4 0.5992571 -0.7978127 -0.006774842 0.6028674 -0.7976331 0.001977562 0.6031398 -0.7933365 -0.009403109 0.6087107 -0.7921607 0.01380741 0.6101565 -0.7895538 -8.02031e-4 0.613681 -0.7878671 0.03277677 0.6149725 -0.7873446 0.01873594 0.6162285 -0.7843088 0.06950956 0.6164643 -0.785018 0.04686486 0.6176977 -0.7854052 0.04032415 0.6176673 -0.7847024 0.0640819 0.6165515 -0.7876098 0.005852758 0.6161465 -0.7856185 0.09587419 0.611238 -0.3466414 -0.7387918 0.5779502 -0.3541514 -0.7371208 0.5755257 -0.531435 -0.653795 0.5386363 -0.4661351 -0.6854542 0.5593484 -0.6879862 -0.5338779 0.4915785 -0.5108394 -0.6537458 0.5582648 -0.7345422 -0.4729012 0.4866337 -0.5338587 -0.6286071 0.5655511 -0.7472919 -0.4375165 0.5001341 -0.5725453 -0.5872453 0.572132 -0.7594305 -0.3978356 0.514774 -0.6193035 -0.5328561 0.5766521 -0.7905977 -0.3256418 0.518568 -0.6727656 -0.4617062 0.5781123 -0.8059587 -0.268011 0.5278264 -0.7155255 -0.3896352 0.5798344 -0.8255115 -0.1937305 0.5300936 -0.7645033 -0.2944704 0.57343 -0.8430662 -0.1124946 0.5259129 -0.8169991 -0.1676648 0.5517255 -0.8535715 -0.04277116 0.5192171 -0.843783 -0.06704348 0.5324805 -0.854088 -0.008510947 0.5200591 -0.8500135 -0.01808112 0.5264505 -0.8515688 -5.19528e-5 0.5242429 -0.8489077 -0.005662918 0.5285109 -0.8489139 -0.005278825 0.5285049 -0.8457678 -0.01158517 0.5334254 -0.8457624 -0.01144647 0.5334371 -0.8409085 -0.02322262 0.540679 -0.8404399 -0.005432665 0.5418776 -0.8368272 -0.02355766 0.5469601 -0.8360381 0.01266658 0.5485252 -0.8350375 -0.005661308 0.5501639 -0.8331696 0.04479908 0.5512002 -0.8333347 0.03227722 0.5518257 -0.8315553 0.06154233 0.5520222 -0.8312175 0.06943631 0.5515941 -0.8228449 0.1431891 0.5499302 -0.8156867 0.1956587 0.5444016 -0.3696606 -0.7431785 0.5577068 -0.3855344 -0.7390329 0.5524433 -0.5424593 -0.6632934 0.5155384 -0.5424256 -0.6633322 0.5155239 -0.6549718 -0.5872504 0.4755512 -0.6139659 -0.6154407 0.4942457 -0.7104743 -0.5370333 0.4547764 -0.6386222 -0.5932444 0.4901254 -0.7616907 -0.4786687 0.4366962 -0.6721437 -0.5588839 0.4856662 -0.8085825 -0.4100632 0.4219511 -0.712331 -0.5105498 0.4815843 -0.8485634 -0.3313658 0.4124764 -0.7549608 -0.4484732 0.4784414 -0.8662657 -0.2723929 0.4187911 -0.7940707 -0.3784648 0.475622 -0.8928453 -0.1813418 0.4122409 -0.8527575 -0.2585198 0.4538416 -0.9136732 -0.08065581 0.3983666 -0.8975142 -0.1237448 0.4232676 -0.917779 -0.02239787 0.3964593 -0.9106289 -0.04447066 0.4108253 -0.9148839 -0.003174543 0.403705 -0.911033 -0.0138697 0.4121002 -0.9114969 -9.57742e-4 0.4113061 -0.9083225 -0.008637845 0.4181814 -0.90836 -0.01145088 0.4180323 -0.9056302 -0.01785945 0.4236922 -0.9060299 -0.0280084 0.4222859 -0.9039883 -0.0342887 0.4261801 -0.9039896 -0.03435832 0.4261719 -0.9020729 -0.04573678 0.4291535 -0.9023021 -0.02070355 0.4306069 -0.9015366 -0.03203999 0.431515 -0.90086 0.02437144 0.4334251 -0.9008329 0.01339727 0.4339594 -0.8974766 0.07348895 0.4348968 -0.8978423 0.06625902 0.4353035 -0.8550488 0.2967337 0.4252536 -0.8597924 0.2784306 0.428058 -0.4227815 -0.7494265 0.5095252 -0.4226645 -0.7494615 0.5095707 -0.633476 -0.6273328 0.452948 -0.5959448 -0.6512542 0.4698062 -0.7128875 -0.5595632 0.4227063 -0.6820752 -0.5844532 0.4395316 -0.7397852 -0.531799 0.4121987 -0.7296366 -0.5409854 0.4182885 -0.7816229 -0.4863839 0.3905078 -0.7780069 -0.4901573 0.3930029 -0.8320365 -0.4224522 0.359513 -0.8212385 -0.4357327 0.368381 -0.8795191 -0.3464021 0.3262696 -0.8596933 -0.37606 0.3456968 -0.9163228 -0.2668296 0.2985872 -0.9027903 -0.2928914 0.3149356 -0.9538103 -0.1511859 0.2595937 -0.9457995 -0.1743454 0.2739835 -0.9708599 -0.05088019 0.2341847 -0.9647674 -0.07774811 0.2513547 -0.9716686 -0.006868779 0.2362479 -0.9678928 -0.0268107 0.2499296 -0.9689186 -0.001322209 0.2473766 -0.9668747 -0.01078444 0.2550237 -0.9669141 -0.006538569 0.2550189 -0.9648507 -0.0144481 0.2624014 -0.9649102 -0.0202943 0.2617949 -0.9632174 -0.0265159 0.2674122 -0.9634336 -0.04089975 0.2648075 -0.9638728 -0.03852188 0.263563 -0.9635534 -0.05799549 0.2611541 -0.9644281 -0.04978883 0.2596139 -0.96454 -0.04655086 0.2597991 -0.9650755 -0.03784924 0.2592236 -0.9653988 0.009047508 0.2606213 -0.9653314 9.35546e-4 0.2610258 -0.9622361 0.07334882 0.2621482 -0.9626942 0.06526756 0.2626029 -0.8914119 0.3767369 0.2519015 -0.8898093 0.3809111 0.2512894 -0.4749339 -0.7632098 0.4381193 -0.4735478 -0.7637625 0.4386566 -0.7142307 -0.5940507 0.3701058 -0.653169 -0.6425659 0.400599 -0.7897285 -0.5097976 0.3412265 -0.7381673 -0.5617389 0.3735754 -0.8155009 -0.4739255 0.3321942 -0.7980448 -0.4940713 0.3449902 -0.8472231 -0.4288432 0.3135389 -0.8569853 -0.4154891 0.3048686 -0.882063 -0.3750085 0.2851905 -0.906349 -0.3344023 0.2582764 -0.9173787 -0.3118169 0.2473593 -0.9465979 -0.2488654 0.204984 -0.9571648 -0.2178009 0.1907836 -0.9789032 -0.145493 0.1434585 -0.9859362 -0.1067102 0.1286196 -0.9917826 -0.07118946 0.106299 -0.9946725 -0.03494572 0.09698128 -0.9949293 -0.03215599 0.09529805 -0.9957791 -0.002901792 0.09173643 -0.9951712 -0.01234591 0.09737586 -0.9952705 -0.002259314 0.09711641 -0.9947716 -0.009067893 0.1017215 -0.9947239 -0.01430535 0.1015864 -0.9942135 -0.01933014 0.1056692 -0.9940195 -0.03019833 0.1049446 -0.9935865 -0.03379911 0.1079051 -0.993245 -0.0453906 0.1067906 -0.9934709 -0.0429064 0.1057114 -0.9928584 -0.05700379 0.1047992 -0.9938972 -0.04054242 0.1025899 -0.9939089 -0.04023545 0.1025983 -0.9947079 -0.01661241 0.1013914 -0.9948163 0.001853883 0.1016713 -0.9948172 0.006339132 0.1014821 -0.9925334 0.06694269 0.1019626 -0.9924028 0.06898647 0.1018706 -0.8959298 0.4335604 0.09661859 -0.91828 0.3828784 0.1008277 -0.5164602 -0.7722932 0.3699086 -0.5274303 -0.7669137 0.3655967 -0.7504533 -0.5873996 0.302955 -0.7155514 -0.6204559 0.3209685 -0.8332241 -0.4831755 0.2688477 -0.8054581 -0.5181154 0.2877392 -0.8721951 -0.4210612 0.2489643 -0.8663032 -0.4301216 0.2539967 -0.9081182 -0.3544931 0.2228366 -0.9181567 -0.3350481 0.2114974 -0.9387003 -0.2868121 0.1912606 -0.9621306 -0.2248981 0.1540315 -0.9650903 -0.2148174 0.1498479 -0.9886353 -0.1198027 0.09081715 -0.9888156 -0.1186397 0.09037929 -0.9977223 -0.04824513 0.047145 -0.9975131 -0.05159562 0.04801815 -0.9993953 -0.01884114 0.02922749 -0.9993777 -0.0196079 0.02932494 -0.999696 -0.007952392 0.02334022 -0.9997222 -0.003825485 0.02325993 -0.9997298 -0.003294408 0.02301359 -0.9997241 -0.005032002 0.02294719 -0.9997087 -0.005947172 0.02339577 -0.9995629 -0.01887297 0.02275806 -0.9995821 -0.01827824 0.0223993 -0.9991226 -0.03579592 0.0217452 -0.9991021 -0.03620022 0.02201288 -0.998536 -0.04955655 0.02168345 -0.9981054 -0.05656051 0.02422219 -0.9983171 -0.05264151 0.02432572 -0.9977132 -0.06265497 0.02535575 -0.9992347 -0.02897477 0.02627921 -0.9994605 -0.02000689 0.02604568 -0.9996491 -0.001081287 0.0264703 -0.9993997 0.02289009 0.0260083 -0.9979075 0.05891263 0.02664524 -0.996985 0.07298344 0.02635234 -0.9273402 0.3729141 0.03123039 -0.9638559 0.2642542 0.03393334 -0.5595992 -0.7696522 0.3073829 -0.5874429 -0.7530227 0.2964249 -0.779965 -0.5762336 0.2441505 -0.7743851 -0.5824761 0.2470818 -0.8644531 -0.4579088 0.207462 -0.8630266 -0.4601255 0.2084938 -0.9087629 -0.3761649 0.1806932 -0.9189426 -0.3555107 0.1707533 -0.9448224 -0.2917054 0.1490592 -0.9625385 -0.2413029 0.1236636 -0.974687 -0.1956877 0.1081284 -0.9901238 -0.1219034 0.069242 -0.9921141 -0.1073447 0.06470525 -0.9984959 -0.04565286 0.03036117 -0.998623 -0.04318934 0.0297805 -0.9998203 -0.01381629 0.01297712 -0.9997759 -0.01645386 0.01332366 -0.9999691 -0.004250884 0.006620824 -0.9999556 -0.006615102 0.006722688 -0.9999905 -0.001401841 0.00413531 -0.9999896 -0.00196737 0.004126071 -0.9999937 -5.65569e-4 0.003518998 -0.999983 -0.004836499 0.003304362 -0.9999936 -0.002689659 0.002383112 -0.9998405 -0.01779288 0.001575231 -0.9999176 -0.01280814 -9.51156e-4 -0.9993348 -0.03643912 -0.00155127 -0.9994181 -0.03398472 -0.002928197 -0.9982607 -0.05889028 -0.002761304 -0.9976542 -0.06845289 5.38156e-4 -0.9975061 -0.07058006 5.16157e-4 -0.9960811 -0.08841121 0.002469539 -0.9993382 -0.03611928 0.004327476 -0.9990238 -0.04395633 0.004398167 -0.9999294 0.009740114 0.00681132 -0.9996145 0.0268681 0.007009804 -0.9981553 0.06009274 0.008658885 -0.998465 0.05471974 0.008580029 -0.968502 0.2482039 0.01996958 -0.9879699 0.1535312 0.01853901 -0.6136374 -0.7531092 0.237225 -0.6522855 -0.7248139 0.2217396 -0.8188014 -0.5452118 0.1797457 -0.8311383 -0.5284429 0.1730821 -0.8984308 -0.4146264 0.1445929 -0.9097597 -0.3922669 0.1358827 -0.9407095 -0.3184637 0.1168186 -0.9560043 -0.2759395 0.09956634 -0.9725864 -0.2167433 0.08425128 -0.9865165 -0.1533246 0.05724388 -0.9927303 -0.1108429 0.04691058 -0.9980382 -0.05827623 0.02288269 -0.9988958 -0.04258835 0.01984149 -0.9998583 -0.01566833 0.006177127 -0.9998984 -0.01299631 0.005863845 -0.9999959 -0.002874255 2.84149e-4 -0.9999918 -0.004059553 3.41506e-4 -0.9999974 -0.002139687 -7.27109e-4 -0.9999988 -0.001370012 -7.33676e-4 -0.9999991 -0.001119613 -8.59393e-4 -0.9999996 -4.52978e-4 -8.49553e-4 -0.9999995 -6.14345e-4 -7.64016e-4 -0.9999964 -0.002555429 -8.35718e-4 -0.9999979 -0.001722693 -0.00120157 -0.9999168 -0.01278859 -0.0017367 -0.9999528 -0.009070217 -0.003499925 -0.9994142 -0.03397101 -0.00417453 -0.9994922 -0.03138834 -0.005483925 -0.9976329 -0.06857639 -0.005091607 -0.9972838 -0.07358074 -0.00330913 -0.9958829 -0.09058809 -0.003351688 -0.99551 -0.09461688 -0.002759873 -0.9986239 -0.05243122 -0.001183032 -0.9985892 -0.05308824 -0.001168966 -0.9997811 0.02064228 0.003410696 -0.9998689 0.01585602 0.003301739 -0.9986419 0.05173343 0.006165564 -0.9991548 0.0406993 0.005789399 -0.9885467 0.1500583 0.01606327 -0.9933996 0.1137189 0.01500785 -0.6766434 -0.7264527 0.1200844 -0.6965627 -0.7086723 0.1121788 -0.8698862 -0.4866961 0.08015549 -0.8827802 -0.4640562 0.07315051 -0.9371579 -0.3445312 0.05507558 -0.9475908 -0.3160787 0.04654055 -0.9701579 -0.2399441 0.03493773 -0.9787942 -0.2034979 0.02346503 -0.9910831 -0.1325945 0.01315993 -0.9953943 -0.09586358 6.33547e-4 -0.9987811 -0.04909557 -0.005099117 -0.9995477 -0.02665704 -0.01392716 -0.9998125 -0.01222461 -0.01502496 -0.9997912 -6.97131e-4 -0.02042633 -0.9997893 -0.002151906 -0.02041751 -0.9997414 0.002183139 -0.02263718 -0.9997339 -0.00253278 -0.02292943 -0.9997643 -0.0092929 -0.01962327 -0.9998198 -0.001567363 -0.01892125 -0.9998371 -0.00990808 -0.01509779 -0.9998976 -7.10218e-4 -0.01429605 -0.9999087 -0.007227659 -0.01142287 -0.9999386 -0.001612186 -0.01097184 -0.9999341 -0.007996678 -0.008233487 -0.9999251 -0.008985817 -0.008306145 -0.9998922 -0.01319497 -0.006447374 -0.9994829 -0.03130155 -0.007364153 -0.9994252 -0.03327763 -0.006471872 -0.9972856 -0.07331264 -0.006834685 -0.997254 -0.07375627 -0.006677567 -0.9953481 -0.09610795 -0.006753742 -0.9958378 -0.09080857 -0.007804334 -0.9979722 -0.06325817 -0.007068693 -0.9982231 -0.05912756 -0.007404088 -0.9999883 0.00233376 -0.004252493 -0.9999908 -0.001146554 -0.004152297 -0.9993594 0.03575205 -0.001643478 -0.9994017 0.03454953 -0.001626968 -0.9938094 0.1110259 0.00403738 -0.9929242 0.1186865 0.003872036 -0.6958391 -0.7094154 -0.1119727 -0.7271418 -0.6755708 -0.1219382 -0.9018576 -0.4151976 -0.119432 -0.9097008 -0.3968892 -0.1221617 -0.958012 -0.2614044 -0.1178175 -0.9574258 -0.2636783 -0.1175152 -0.9800291 -0.1631616 -0.1136727 -0.9789507 -0.170241 -0.1125761 -0.9915753 -0.07047009 -0.1086852 -0.9912776 -0.07626032 -0.1074852 -0.9944267 -0.011684 -0.1047815 -0.9944003 -0.01046729 -0.1051598 -0.9945682 0.005885839 -0.103921 -0.9942812 0.01130235 -0.1061943 -0.9941664 0.002351105 -0.107831 -0.994093 0.003859996 -0.1084637 -0.9934371 -0.01210021 -0.1137381 -0.9936016 -0.02909028 -0.1091311 -0.9946436 -0.01307064 -0.1025345 -0.9941844 -0.04551404 -0.09760075 -0.9964663 -0.009337604 -0.08347308 -0.9959154 -0.04580831 -0.07780891 -0.9977748 -0.008844316 -0.0660867 -0.9971703 -0.04858654 -0.05736464 -0.9987272 -0.0124967 -0.04886788 -0.9981651 -0.04633826 -0.03897911 -0.9988781 -0.03012645 -0.03653657 -0.9980366 -0.05612397 -0.0278055 -0.9972307 -0.06863945 -0.02862602 -0.9963366 -0.08184331 -0.02480322 -0.9954 -0.09248262 -0.02501952 -0.9964434 -0.07962965 -0.02756273 -0.9963259 -0.08108079 -0.02758419 -0.9978941 -0.05725049 -0.03049194 -0.9992069 -0.02637827 -0.02983105 -0.9994459 -0.01213365 -0.03099656 -0.9987327 0.04053664 -0.0298292 -0.9987874 0.03922861 -0.02974635 -0.9886998 0.1472782 -0.027965 -0.9909774 0.131296 -0.02692759 0.9922385 0.01694869 0.1231893 0.3610363 0.472621 0.8039168 0.9334124 0.1231616 0.337005 0.832801 0.2277678 0.5045438 0.1171876 0.9430172 0.3114253 0.9472963 0.2830352 0.15007 0.284264 0.8623394 0.4190046 0.9809333 0.1353674 0.1394474 0.9951396 0.05544143 0.08138513 0.4216659 0.6447656 0.6375541 0.990906 0.06129008 0.1197868 0.5530551 0.526145 0.6459888 0.9848278 0.06754386 0.1598499 0.4954792 0.5082241 0.7044208 0.9821166 0.05437082 0.1802516 0.6366192 0.3997702 0.6594693 0.9819818 0.02693057 0.1870466 0.7613335 0.2680106 0.5903742 0.9786376 0.001426994 0.2055881 0.728545 0.2258998 0.6466772 0.9377101 0.02587467 0.346454 0.6098994 0.2318683 0.7577993 0.9568146 -0.1054208 0.2709102 -0.008726298 0.2977958 0.9545898 0.720126 -0.05217647 0.6918787 0.3442754 -0.0677073 0.9364241 0.5558897 -0.3574309 -0.7504864 0.8027731 -0.5725299 -0.1666287 -0.512602 0.2045431 -0.8339074 -0.5062216 0.2006464 -0.8387377 0.4684029 -0.1415563 0.8721013 0.4422192 -0.1318929 0.8871564 0.4985944 -0.1806817 0.8477959 0.4479873 -0.1685491 0.8780084 0.4416127 -0.1659128 0.8817319 0.4354328 -0.165652 0.8848491 0.4879717 -0.1720115 0.8557427 0.7775681 -0.165948 0.6065058 0.8388403 0.5401907 0.06738764 0.828824 0.555147 0.06973427 0.9975638 0.06471925 0.02603596 0.8050048 0.565414 0.1796508 0.9981937 0.04831218 0.03571188 0.9380564 0.3098253 0.1551083 0.9982253 0.03528445 0.0479716 0.8677959 0.4155796 0.272441 0.9980763 0.01673448 0.05969786 0.8445525 0.3985276 0.3576408 0.9974742 -0.00322622 0.07095718 0.8399999 0.3373364 0.4249756 0.9957209 -0.0205366 0.09010034 0.8133597 0.2806024 0.5096158 0.9882016 -0.01791703 0.1521071 0.8261394 0.2063723 0.5243131 0.9758718 -0.03371089 0.2157264 0.8490946 0.1347146 0.5107743 0.9711777 -0.1922843 0.140857 0.7004516 0.1187188 0.7037566 0.8925943 -0.4344278 0.1206156 0.5011943 -0.0407018 0.8643772 0.5977277 -0.1579748 0.7859807 0.5549535 -0.265666 0.78832 0.3285688 0.2574416 0.9087169 0.6447187 -0.08378434 0.7598145 0.6298237 -0.1073188 0.7692885 0.6226931 -0.1012504 0.7758876 0.6096577 -0.1261109 0.7825686 0.6512797 -0.1504661 0.7437706 0.6656053 -0.1815133 0.723894 0.7060117 -0.1881099 0.6827607 0.7060735 -0.2407282 0.6659656 0.5863736 -0.2080927 0.7828561 0.5449742 -0.2287675 0.8066404 0.5308211 -0.2119294 0.8205577 0.4989507 -0.2275882 0.8362128 0.5002738 -0.21329 0.8391863 0.8626689 0.5034355 0.04853147 0.9919242 0.1267474 0.004648387 0.7575211 0.6526394 0.01495695 0.9872793 0.158985 0.001832306 0.9938409 0.1107941 0.002245426 0.995375 0.09604746 0.001844346 0.9971238 0.07575184 0.002421855 0.9938689 0.1105065 0.00361073 0.9982797 0.0584079 0.005131602 0.9793879 0.2016255 0.01210659 0.9995116 0.02907007 0.01147466 0.9563994 0.2890057 0.04214197 0.9997566 0.00803411 0.02054983 0.9420425 0.3202147 0.1000933 0.9994011 -0.008578062 0.03352606 0.9485577 0.2668308 0.17041 0.9983662 -0.01870083 0.0539931 0.9770163 0.1289033 0.1697736 0.9964401 -0.03161102 0.07815307 0.9861313 0.05002075 0.15825 0.992633 -0.04606753 0.1120603 0.9865003 0.009027779 0.1635102 0.9776512 -0.1064014 0.1813204 0.9738554 -0.02551633 0.2257316 0.9053387 -0.17351 0.3876289 0.9217279 -0.06922918 0.3816084 0.9912917 0.1315181 -0.006625413 0.9723212 -0.04612171 0.2290508 0.8414676 -0.1487172 0.5194379 0.830216 -0.1547439 0.5355331 0.7780103 -0.1766271 0.6029121 0.7966139 -0.1672998 0.5808762 0.7026411 -0.1981692 0.6833919 0.7001085 -0.1997921 0.6855154 0.5958032 -0.2256354 0.7707836 0.6001424 -0.2404283 0.7629046 0.5278955 -0.274621 0.8036851 0.5303364 -0.318149 0.7858274 0.9887645 0.1471641 0.02621906 0.9986592 0.05150586 0.005195975 0.9545958 0.2966856 0.02691888 0.9992721 0.03811502 0.001674771 0.9948261 0.1015419 0.003237187 0.9994674 0.032633 -2.06764e-6 0.9956579 0.09307634 -0.001503825 0.998959 0.04558688 -0.001726567 0.9930357 0.1176574 -0.006060063 0.9971643 0.07511335 -0.004632711 0.9954675 0.09489309 -0.006309807 0.9951161 0.09849816 -0.0064978 0.9982858 0.05848032 -0.002376079 0.9922916 0.1238135 -0.005258798 0.999634 0.0266661 0.004588484 0.9866287 0.162899 0.005283832 0.9999105 -5.17386e-4 0.01337158 0.9949153 0.09743392 0.02550387 0.9996215 -0.01872807 0.02015626 0.9993109 0.01979517 0.03140121 0.9994214 -0.01854056 0.02851992 0.9991228 0.009453356 0.04079759 0.9987245 -0.02004659 0.04634392 0.9986313 -0.005126416 0.05205082 0.9967411 -0.02465683 0.07680815 0.9966375 -0.02673089 0.07745581 0.9261048 -0.184127 0.3292828 0.9618712 -0.1259201 0.2427921 0.9654572 -0.1199533 0.231309 0.9504873 -0.1488904 0.2727737 0.9586853 -0.1376197 0.2489645 0.9266917 -0.2004906 0.3178774 0.857621 -0.2621828 0.4424325 0.8245148 -0.3625504 0.4344338 0.6146445 -0.5102741 0.6015252 0.5988092 -0.6057528 0.5239191 0.9983827 0.05491864 0.01470208 0.9991933 0.03913301 0.00902456 0.9982756 0.05727344 0.01286512 0.9995183 0.03042763 0.006120204 0.9983826 0.05586218 0.01056122 0.9996037 0.02775537 0.004716098 0.9960664 0.08762168 0.01320105 0.9994729 0.03221869 0.003979742 0.9823002 0.1863054 0.01941305 0.9992904 0.03759038 0.002415955 0.9817836 0.1897723 0.00935626 0.9992152 0.03961235 7.52277e-5 0.9895191 0.1443924 -0.001681506 0.9989974 0.044703 -0.002437651 0.9946377 0.1031996 -0.006766319 0.9986617 0.0515024 -0.004723548 0.9996255 0.02727633 -0.002272546 0.9998727 -0.01595383 -4.83799e-4 0.9999466 -0.01029741 -8.698e-4 0.9998136 -0.01925981 -0.001386404 0.9999986 3.26718e-4 -0.001695215 0.9997586 0.02158635 0.00410068 0.9999746 -0.00440967 0.005600273 0.9999031 0.008526682 0.01100629 0.9998525 -0.01055371 0.01355773 0.9998558 -0.005441844 0.01608872 0.9995807 -0.02185171 0.01900005 0.9995504 -0.02383148 0.01819866 0.9977586 -0.06195223 0.02529442 0.996922 -0.07470786 0.0237782 0.9778981 -0.2013779 0.05623364 0.9826961 -0.1773135 0.05355799 0.985092 -0.164938 0.04887968 0.9682603 -0.24382 0.05498927 0.9813032 -0.1893382 0.03457188 0.9424948 -0.3330913 0.02745485 0.9199637 -0.389805 0.04145866 0.8581174 -0.5134515 0.001533448 0.5734261 -0.8191126 -0.01540094 0.5848711 -0.8111255 -0.001217782 0.9991284 0.04001086 0.01190423 0.9991971 0.03845781 0.01123392 0.9993135 0.0355485 0.01043665 0.9994333 0.03232681 0.009385108 0.9992817 0.0364266 0.01045542 0.9994608 0.0315997 0.008932828 0.9988317 0.04664611 0.01263105 0.9994298 0.03265553 0.00859487 0.9980993 0.05986016 0.01464694 0.9994307 0.03288769 0.007528781 0.9978558 0.06406533 0.01339703 0.9994889 0.03144323 0.005788803 0.9972438 0.07324904 0.01181793 0.9996047 0.02792477 0.003258943 0.9951121 0.09825408 0.009901702 0.9999963 0.002008438 -0.001841723 0.9969924 -0.07726359 -0.006048679 0.9759742 -0.2174198 -0.01424807 0.9994282 -0.03297281 -0.007497549 0.9997032 -0.02343422 -0.006659924 0.9998088 0.0185641 -0.006141483 0.9995175 0.03091603 -0.003007173 0.9999666 0.007761478 -0.002593457 0.9998683 0.01622414 5.25245e-4 0.9999856 -0.005341053 6.04627e-4 0.9999651 -0.008332669 -7.38372e-4 0.9996827 -0.0251255 -0.00183022 0.9986819 -0.04971539 -0.01276665 0.995936 -0.08815735 -0.01843863 0.9876872 -0.1509149 -0.04121595 0.9651239 -0.2548503 -0.05989396 0.944156 -0.3198345 -0.07921773 0.9437646 -0.3209395 -0.0794112 0.8815746 -0.4563645 -0.1206562 0.9126932 -0.3939355 -0.1086556 0.8044745 -0.5702915 -0.1660981 0.8034489 -0.5716508 -0.1663889 0.6905524 -0.6920866 -0.2101274 0.4996498 -0.8313134 -0.2434507 0.4866195 -0.8375034 -0.2485749 0.9992054 0.03833866 0.01089709 0.9991427 0.03976821 0.01151353 0.9994229 0.03259068 0.009586513 0.9993814 0.03371661 0.01000744 0.9994217 0.03260046 0.009678363 0.9993965 0.03328818 0.009928524 0.9993347 0.03497302 0.01035529 0.999387 0.03357321 0.009927332 0.9992678 0.03673368 0.01070106 0.9994297 0.03244763 0.009361088 0.9992858 0.03635942 0.01028466 0.9995498 0.02893894 0.007929444 0.9993696 0.03431189 0.009119808 0.999839 0.01748615 0.004062652 0.9999605 0.008594453 0.00227648 0.9994328 -0.03267627 -0.0081501 0.3668299 -0.9155386 -0.1649998 0.9954616 -0.09393781 -0.01523524 0.999713 -0.02307611 -0.006443262 0.999795 0.02019464 0.001506984 0.9994806 0.03218334 0.001733601 0.9995052 0.03141802 0.001531422 0.9998645 0.01637202 0.001719474 0.9999686 0.007874906 -9.94781e-4 0.9999632 -0.008428156 -0.001618802 0.9993263 -0.03486371 -0.01146942 0.9986653 -0.04986667 -0.0134536 0.992162 -0.1183956 -0.03996551 0.9868176 -0.1546115 -0.04781645 0.955454 -0.2798055 -0.0938965 0.9310008 -0.3476387 -0.1112882 0.8714293 -0.4660623 -0.152961 0.8552597 -0.4928571 -0.1600714 0.7724434 -0.6031513 -0.1988459 0.7757647 -0.5992299 -0.1977696 0.6856095 -0.6906423 -0.2301148 0.6601263 -0.7130447 -0.2362216 0.5841764 -0.7699203 -0.2568283 0.4649254 -0.8412266 -0.2760115 0.4336438 -0.8552218 -0.2838113 0.9991763 0.0393458 0.009938538 0.9991068 0.04090064 0.01062417 0.9994382 0.03242313 0.008491337 0.9994523 0.03202694 0.008332967 0.9994763 0.03131556 0.008150517 0.9995014 0.03056448 0.007923483 0.9994617 0.03176391 0.008215129 0.9995339 0.02958893 0.007514595 0.9994884 0.03100663 0.00786215 0.9996904 0.02423387 0.005649209 0.999598 0.02761524 0.006424963 0.9998926 0.01451236 0.002084374 0.9998676 0.01609313 0.002435564 0.9999124 -0.01151722 -0.006534278 0.9992092 -0.03779488 -0.01235765 0.9949831 -0.09567999 -0.02922445 0.9910269 -0.1285526 -0.03660446 0.9960319 -0.08544862 -0.02488005 0.9998509 0.01623284 -0.005898594 0.9996911 0.02467596 -0.002980053 0.9995273 0.03064942 -0.00239551 0.999706 0.02372157 -0.005028307 0.9999564 0.006831467 -0.006365299 0.9998146 -0.01357817 -0.01365816 0.9992095 -0.03622919 -0.01636773 0.9951789 -0.09129947 -0.03582638 0.9920653 -0.1188681 -0.04094851 0.9680094 -0.2370058 -0.0823785 0.9559985 -0.2785078 -0.09219729 0.8934907 -0.4257388 -0.1429018 0.8711409 -0.4664595 -0.1533918 0.7934148 -0.5778717 -0.1911995 0.77389 -0.6017439 -0.1974811 0.6913544 -0.6862459 -0.2260436 0.6912111 -0.68638 -0.2260748 0.6071314 -0.7545895 -0.2489704 0.5929352 -0.7648954 -0.25172 0.5179877 -0.812343 -0.267932 0.4394592 -0.8540175 -0.278442 0.4104715 -0.8663476 -0.2845263 0.9991951 0.03996115 0.003521502 0.9988301 0.04775333 0.007618606 0.9995951 0.0283569 0.002353608 0.9998074 0.01958996 -0.001175701 0.9997186 0.02372634 -3.92962e-5 0.9998677 0.01600152 -0.002954304 0.9997506 0.02230179 -0.00122559 0.9999477 0.007738113 -0.00669074 0.9998518 0.01666426 -0.00432372 0.9998595 -0.009077787 -0.01409447 0.9999292 0.005582809 -0.01051735 0.9992534 -0.0303418 -0.02391993 0.9994637 -0.02375119 -0.02254527 0.9972167 -0.06516551 -0.03622668 0.9927124 -0.1122916 -0.04373514 0.9959896 -0.08176219 -0.03632682 0.9944632 -0.09798228 -0.03798115 0.99656 -0.07583534 -0.0334261 0.9994179 0.01884019 -0.02844464 0.9992609 -0.00861746 -0.03746151 0.9991605 0.01958298 -0.03598517 0.9986016 -0.0172196 -0.04998391 0.998471 -0.02246785 -0.05050569 0.9944092 -0.07873696 -0.07036268 0.9913498 -0.107883 -0.07474625 0.9699255 -0.2170602 -0.1101337 0.9578935 -0.2615169 -0.118529 0.8943184 -0.4157478 -0.1653742 0.8752183 -0.4518769 -0.1726277 0.7924991 -0.5734613 -0.2075746 0.7724574 -0.5984664 -0.2124801 0.6945613 -0.6800729 -0.2347033 0.674932 -0.6984179 -0.2380745 0.6052265 -0.7549286 -0.2525547 0.5996313 -0.7591404 -0.2532751 0.5364427 -0.8017702 -0.2634275 0.524696 -0.809144 -0.2645376 0.4700214 -0.8398526 -0.271528 0.4217999 -0.8641839 -0.2743558 0.3969467 -0.8747502 -0.2779311 -0.3950266 0.8874415 -0.2374904 -0.3970353 0.8821412 -0.2533571 -0.2800031 0.6618061 -0.6954214 -0.3017365 0.737964 -0.603626 -0.15338 0.4457573 -0.8819156 -0.1942383 0.5638419 -0.8027166 -0.04955548 0.2711204 -0.961269 -0.07590341 0.3570296 -0.9310041 0.02879804 0.1370697 -0.9901428 0.02614367 0.1490735 -0.9884805 0.06662809 0.05871933 -0.9960486 0.07205551 0.02282267 -0.9971395 0.07862973 0.007169425 -0.9968782 0.08429628 -0.03746283 -0.9957363 0.06930446 3.85849e-4 -0.9975956 0.07580178 -0.03598845 -0.9964733 0.06326091 -0.002051591 -0.997995 0.06727242 -0.02320402 -0.9974648 0.05857789 0.002637743 -0.9982793 0.061926 -0.01913088 -0.9978975 0.05947071 -0.01075947 -0.9981722 0.06130164 -0.02518767 -0.9978014 0.06952959 -0.05676674 -0.9959635 0.06794762 -0.04486507 -0.9966797 0.09074002 -0.1357237 -0.9865827 0.08134573 -0.0774191 -0.9936746 0.1295092 -0.2640558 -0.9557729 0.1056743 -0.1413347 -0.9843056 0.1804739 -0.4233552 -0.8878061 0.1438693 -0.2513628 -0.9571408 0.2275367 -0.5692784 -0.790031 0.2013943 -0.4441009 -0.8730492 0.2539913 -0.658222 -0.7086834 0.2415907 -0.5926777 -0.7683536 0.2701765 -0.7214005 -0.6376409 0.2622604 -0.6737638 -0.6908414 0.2874675 -0.8048941 -0.5191416 0.2852092 -0.7825726 -0.5533858 0.2987076 -0.8834556 -0.3609431 0.3001827 -0.8751201 -0.3795462 -0.4142082 0.8788367 -0.2368076 -0.3132119 0.7111186 -0.6294512 -0.3329005 0.7418507 -0.5820953 -0.2995467 0.6783817 -0.6708726 -0.2441898 0.5800489 -0.7771193 -0.1918782 0.4697254 -0.8617081 -0.1495214 0.38678 -0.9099695 -0.1133804 0.3015561 -0.9466831 -0.05999845 0.1888658 -0.9801684 -0.04137003 0.1377627 -0.989601 -0.01629704 0.07973295 -0.9966831 -0.006279349 0.04652142 -0.9988976 -0.001248538 0.03350132 -0.999438 0.003135621 0.01536506 -0.9998771 1.97778e-4 0.02396708 -0.9997128 0.002675592 0.01266056 -0.9999163 7.26634e-5 0.02115595 -0.9997762 0.001624226 0.01352828 -0.9999072 0.001249551 0.01486563 -0.9998888 0.002066373 0.0102995 -0.9999449 0.003181755 0.005958437 -0.9999772 0.003239333 0.005591273 -0.9999791 0.006595969 -0.008494675 -0.9999422 0.005478858 -8.94823e-4 -0.9999847 0.01142454 -0.02676773 -0.9995765 0.008840858 -0.009634017 -0.9999145 0.02101868 -0.06191575 -0.9978601 0.01470935 -0.02495604 -0.9995804 0.04022938 -0.1272927 -0.9910491 0.0246486 -0.05046874 -0.9984214 0.08245158 -0.2603778 -0.9619798 0.05163973 -0.1339844 -0.9896371 0.1273437 -0.397253 -0.9088309 0.1027644 -0.3031151 -0.9473968 0.1564544 -0.4898779 -0.8576373 0.1473235 -0.4550052 -0.8782176 0.2140355 -0.6917728 -0.689666 0.2118631 -0.6826871 -0.6993228 0.2625873 -0.8722058 -0.4126803 0.2622082 -0.8603055 -0.4371745 -0.2155211 0.6944181 -0.6865378 -0.1063167 0.3924245 -0.9136192 -0.1865938 0.5985813 -0.7790271 -0.1162483 0.3989433 -0.9095773 -0.1180769 0.4038875 -0.9071564 -0.04040026 0.1672096 -0.9850934 -0.07747042 0.2713078 -0.9593699 -0.02751755 0.10868 -0.9936959 -0.03605717 0.133567 -0.9903836 -0.01515513 0.05890727 -0.9981484 -0.01307016 0.05243057 -0.9985391 -0.007592558 0.03010892 -0.9995179 -0.005921006 0.02440547 -0.9996846 -0.005420982 0.02197229 -0.9997439 -0.004895627 0.01994937 -0.999789 -0.005313992 0.0222451 -0.9997385 -0.004513561 0.018821 -0.9998127 -0.005042612 0.02202987 -0.9997447 -0.003423333 0.01449763 -0.9998891 -0.004051804 0.01883316 -0.9998145 -0.002195835 0.009474515 -0.9999528 -0.002848982 0.0147224 -0.9998877 -7.95374e-4 0.003441214 -0.9999939 -0.001461386 0.009775876 -0.9999512 8.74364e-4 -0.004212379 -0.9999908 2.07721e-4 0.003295719 -0.9999946 0.003495216 -0.01740652 -0.9998424 0.002426385 -0.004380702 -0.9999875 0.00846374 -0.03888756 -0.9992077 0.005817532 -0.0130009 -0.9998986 0.02577543 -0.104248 -0.9942173 0.01526576 -0.04340499 -0.9989409 0.06379115 -0.2391091 -0.9688951 0.04302763 -0.1446715 -0.9885438 0.09990966 -0.3678582 -0.924499 0.08921253 -0.3215292 -0.9426877 0.1617825 -0.6100721 -0.7756537 0.162419 -0.6130135 -0.7731977 0.2209299 -0.8548135 -0.4695573 0.2205252 -0.8457004 -0.4859625 -0.07107532 0.3845961 -0.9203446 -0.04432952 0.2487989 -0.9675403 -0.06250411 0.3323547 -0.9410811 -0.03311079 0.1821609 -0.9827111 -0.02666097 0.1522245 -0.9879863 -0.01131147 0.0692085 -0.9975381 -0.01758837 0.09813159 -0.9950181 -0.007498264 0.04149848 -0.9991105 -0.01005977 0.05346041 -0.9985193 -0.006038963 0.02964454 -0.9995422 -0.005705118 0.02801287 -0.9995913 -0.005629301 0.02752047 -0.9996054 -0.004332244 0.02066892 -0.999777 -0.005470037 0.02919739 -0.9995588 -0.004035711 0.02071797 -0.9997773 -0.005372643 0.03219056 -0.9994673 -0.003610312 0.02047145 -0.999784 -0.004910588 0.03352463 -0.9994259 -0.002828955 0.01777768 -0.9998381 -0.003864705 0.03084808 -0.9995166 -0.001968622 0.01407408 -0.999899 -0.002602934 0.02537745 -0.9996746 -0.001133382 0.009549856 -0.9999538 -0.00137782 0.01743936 -0.999847 -3.65778e-4 0.003633856 -0.9999934 -3.74972e-4 0.007407248 -0.9999725 3.28241e-4 -0.003610134 -0.9999935 4.45866e-4 3.50885e-4 -1 0.001488685 -0.01191449 -0.9999279 0.001737236 -0.003910779 -0.9999909 0.006561815 -0.03904056 -0.9992161 0.005167663 -0.01588553 -0.9998605 0.0242359 -0.1233825 -0.9920632 0.01569092 -0.06200963 -0.9979523 0.05312317 -0.2582787 -0.9646088 0.04170292 -0.1893585 -0.9810221 0.1059659 -0.52818 -0.8424947 0.1027665 -0.5078788 -0.8552767 0.1630544 -0.8386547 -0.5196841 0.1630011 -0.8338829 -0.5273235 -0.03263133 0.2546766 -0.9664756 -0.04309451 0.368138 -0.928772 -0.02000206 0.1773618 -0.9839425 -0.01942586 0.1716713 -0.9849627 -0.007094264 0.06901842 -0.9975902 -0.005407035 0.05022042 -0.9987236 -0.004213452 0.04005342 -0.9991887 -0.003666579 0.0333454 -0.9994372 -0.002969324 0.02698701 -0.9996315 -0.003441691 0.03362506 -0.9994287 -0.002491176 0.02381449 -0.9997134 -0.00329262 0.03803628 -0.999271 -0.002188742 0.02441358 -0.9996996 -0.002844929 0.04167085 -0.9991274 -0.001890301 0.0266422 -0.9996433 -0.002263545 0.04437029 -0.9990127 -0.001520156 0.02863383 -0.9995889 -0.001631736 0.04631698 -0.9989256 -0.001045644 0.02831023 -0.9995987 -9.22332e-4 0.04440855 -0.9990131 -5.38138e-4 0.02428084 -0.9997051 -2.63217e-4 0.03638762 -0.9993378 -1.38432e-4 0.01693135 -0.9998567 9.21381e-5 0.02263408 -0.9997438 3.16682e-5 0.007294416 -0.9999734 7.02859e-5 0.007845461 -0.9999693 3.63062e-5 3.87425e-4 -1 1.31029e-4 0.00115019 -0.9999994 2.00031e-4 -0.003887772 -0.9999924 5.74303e-4 -0.001488149 -0.9999988 0.001255154 -0.01549381 -0.9998792 0.001817047 -0.007184207 -0.9999727 0.006228327 -0.05737775 -0.9983332 0.005166947 -0.02761018 -0.9996055 0.02029478 -0.1589868 -0.9870722 0.01404398 -0.08847838 -0.9959792 0.06002378 -0.4467686 -0.8926337 0.04719841 -0.3209457 -0.9459208 0.1153654 -0.831385 -0.5435899 0.1153718 -0.8053382 -0.5814808 0.008145391 0.4643368 -0.8856214 -0.008332669 0.1674225 -0.98585 -0.009497761 0.1889373 -0.9819433 -0.009382545 0.1839948 -0.9828824 -0.002526044 0.05637514 -0.9984065 -0.002759754 0.07639968 -0.9970734 -0.001289665 0.03653955 -0.9993314 -0.001205503 0.05653649 -0.9983999 -7.75236e-4 0.03439474 -0.999408 -3.14611e-4 0.0588864 -0.9982647 -2.28474e-4 0.03627693 -0.9993419 6.12649e-4 0.06086361 -0.998146 3.72026e-4 0.0379185 -0.9992808 0.001500725 0.06017357 -0.9981869 0.001005947 0.03977108 -0.9992084 0.002180397 0.05764156 -0.998335 0.001623988 0.04224824 -0.9991059 0.002507269 0.05374175 -0.9985518 0.002006292 0.04244709 -0.9990968 0.002427399 0.0474717 -0.9988697 0.001851379 0.03565466 -0.9993625 0.001882791 0.03600341 -0.99935 0.001197218 0.02230495 -0.9997505 0.00101155 0.02045589 -0.9997903 4.14254e-4 0.007764875 -0.9999698 2.93641e-4 0.006870388 -0.9999765 7.71484e-5 0.00115478 -0.9999994 1.128e-4 0.001320719 -0.9999992 3.39785e-5 -0.001485943 -0.999999 2.85106e-4 -5.84918e-4 -0.9999998 1.9482e-4 -0.007122337 -0.9999746 8.59795e-4 -0.003776788 -0.9999926 0.00157845 -0.02654951 -0.9996463 0.002346396 -0.01434463 -0.9998944 0.008132398 -0.08237916 -0.9965679 0.006767094 -0.04603046 -0.9989171 0.03841829 -0.3096374 -0.9500784 0.02796018 -0.1862344 -0.9821074 0.1131813 -0.8051996 -0.5821027 0.1121866 -0.7521253 -0.6494012 0.01095384 0.2121556 -0.9771745 0.005570411 0.1526415 -0.988266 0.002454996 0.2092097 -0.9778677 9.47689e-4 0.1791366 -0.9838238 8.41295e-4 0.0844472 -0.9964276 0.002763032 0.1102749 -0.9938974 0.00128895 0.05982524 -0.9982081 0.00322473 0.08039259 -0.9967582 0.002293825 0.05960702 -0.9982194 0.003599643 0.07182639 -0.9974107 0.002947151 0.05973941 -0.9982097 0.004132568 0.06968343 -0.9975606 0.003436326 0.05843085 -0.9982857 0.004377722 0.06545066 -0.9978462 0.003733277 0.05603772 -0.9984217 0.004407525 0.06058281 -0.9981535 0.003808617 0.05247849 -0.9986149 0.003694355 0.05176907 -0.9986523 0.003332138 0.04680013 -0.9988988 0.002704262 0.04298126 -0.9990723 0.002227604 0.03575766 -0.9993581 0.001389026 0.03078913 -0.999525 8.72716e-4 0.02056449 -0.9997882 2.9886e-4 0.01745432 -0.9998477 3.05099e-5 0.007031977 -0.9999753 -6.99414e-5 0.006645023 -0.999978 -9.03959e-5 0.001379609 -0.9999991 4.26937e-6 0.001604676 -0.9999988 -1.5542e-5 -5.50987e-4 -1 1.82272e-4 -1.96304e-4 -1 1.05677e-4 -0.00367707 -0.9999933 7.19493e-4 -0.002426564 -0.9999969 0.001044332 -0.01385533 -0.9999035 0.002268314 -0.009581565 -0.9999516 0.006194353 -0.04549944 -0.9989452 0.007009148 -0.03417545 -0.9993914 0.03193473 -0.1913905 -0.9809944 0.03021454 -0.1541169 -0.9875906 0.136123 -0.7594749 -0.6361355 0.1371715 -0.7301145 -0.6694153 0.180921 0.4092181 -0.89432 0.1272814 0.2898666 -0.9485657 0.04257565 0.09848147 -0.9942277 0.02657431 0.06297028 -0.9976616 0.009892582 0.02489268 -0.9996412 0.003828763 0.01172089 -0.999924 0.003404796 0.01071178 -0.9999369 8.89721e-4 0.005470156 -0.9999847 0.002049803 0.008630156 -0.9999607 5.11946e-4 0.005372941 -0.9999855 0.001590251 0.009305179 -0.9999555 2.58504e-4 0.005738019 -0.9999835 0.001248776 0.01086515 -0.9999403 -2.49588e-4 0.005361795 -0.9999857 4.08751e-4 0.01004803 -0.9999495 -0.001629233 7.46348e-4 -0.9999985 -0.001185059 0.006948649 -0.9999752 -0.002920925 -0.003415584 -0.9999899 -0.003628194 0.01268839 -0.999913 -0.004116296 0.001540064 -0.9999904 -0.006158292 0.01964432 -0.9997881 -0.006101608 0.01779693 -0.999823 -0.006217956 0.01873314 -0.9998052 -0.006515443 0.02634096 -0.9996319 -0.004360795 0.008446753 -0.9999549 -0.004434525 0.01628941 -0.9998576 -0.003063321 0.002325952 -0.9999926 -0.002650856 0.00815767 -0.9999633 -0.002028405 -0.00161308 -0.9999967 -0.001242995 0.003961622 -0.9999915 -3.70995e-4 -0.01689213 -0.9998573 -2.34477e-4 -0.01570576 -0.9998767 0.002818107 -0.1065128 -0.9943073 0.002190351 -0.1183001 -0.9929755 0.02019155 -0.7225137 -0.6910616 0.0161342 -0.7786274 -0.6272792 -0.002553343 0.002095997 -0.9999946 -0.005334377 -0.007269978 -0.9999594 -0.004320859 0.01740896 -0.9998391 -0.00568819 0.007801592 -0.9999534 -0.005579113 0.02605807 -0.9996449 -0.005927443 0.02246111 -0.9997302 -0.005855083 0.01655703 -0.9998458 -0.005751729 0.01778137 -0.9998254 -0.005499243 0.008096039 -0.9999521 -0.004574775 0.01604831 -0.9998608 -0.004208326 0.003350198 -0.9999856 -0.002460241 0.01422256 -0.9998959 -0.00163114 -0.01626098 -0.9998666 -0.001015245 -0.01133364 -0.9999353 0.00104773 -0.1190505 -0.9928877 -8.75194e-4 -0.1487292 -0.9888776 0.00783801 -0.780377 -0.6252603 7.50378e-4 -0.8476032 -0.5306302 -0.004567325 0.008311927 -0.9999551 -0.006807327 0.002036571 -0.9999747 -0.005254149 0.02251976 -0.9997326 -0.006014108 0.01990658 -0.9997838 -0.006121158 0.01776552 -0.9998235 -0.006275415 0.01719045 -0.9998326 -0.006303846 0.01566022 -0.9998576 -0.005216479 0.01940608 -0.9997981 -0.00518161 0.01298183 -0.9999024 -0.002704203 0.02062565 -0.9997836 -0.002053737 -0.0121814 -0.9999237 -9.0745e-4 -0.007125973 -0.9999743 0.001045763 -0.1456943 -0.9893292 -0.001199245 -0.1648716 -0.9863144 0.005262315 -0.8454911 -0.5339637 -0.001510739 -0.8723549 -0.4888709 0.1654831 0.951733 -0.2584951 0.15373 0.9532119 -0.2602963 0.1168994 0.6825086 -0.7214683 0.1266096 0.6844699 -0.7179631 0.04575955 0.1527087 -0.9872113 0.05288875 0.1558767 -0.9863596 0.03118103 0.03669619 -0.9988399 0.03511351 0.03689843 -0.998702 0.02164602 -0.01954394 -0.9995747 0.01636105 -0.01311057 -0.9997802 0.01092928 -0.02386748 -0.9996554 5.91824e-4 -0.007943451 -0.9999683 0.004404783 -0.004240512 -0.9999814 -0.002340495 -0.002082884 -0.9999951 0.00105971 6.0428e-4 -0.9999994 -0.002235054 -1.97011e-4 -0.9999975 -8.45105e-4 8.56508e-4 -0.9999993 0.001509726 0.001688778 -0.9999975 1.82854e-4 6.15832e-4 -0.9999999 0.008881866 0.002727806 -0.9999569 0.00633645 -1.42788e-4 -0.9999799 0.01992332 0.001194834 -0.9998008 0.01901215 -0.002712666 -0.9998157 0.01698946 -0.002957224 -0.9998514 -0.006695568 0.9639691 -0.2659299 -0.01060634 0.9475626 -0.3193944 -0.007875859 0.6583367 -0.7526825 -0.01054215 0.5355471 -0.8444396 -0.002953648 0.133403 -0.9910575 -0.003121674 0.08850324 -0.9960711 -0.001585781 0.04202324 -0.9991155 -0.001455903 0.02266478 -0.9997421 -0.001389801 0.02148443 -0.9997683 -0.001089155 0.01084363 -0.9999407 -4.14213e-4 0.002954661 -0.9999957 -4.21356e-4 0.00308156 -0.9999952 4.36786e-4 -0.004523158 -0.9999897 3.67493e-4 -0.002714037 -0.9999963 1.69153e-4 -0.001111865 -0.9999994 1.23306e-4 -0.001416921 -0.9999991 -2.48228e-5 4.91376e-4 -0.9999999 -1.48314e-4 2.46163e-4 -1 -1.38816e-4 7.68193e-4 -0.9999998 -1.23701e-4 7.92131e-4 -0.9999998 -1.33704e-4 4.50486e-4 -0.9999999 -5.2805e-5 6.10413e-4 -0.9999998 -5.66409e-5 1.31503e-5 -1 1.11962e-5 1.82521e-4 -1 9.10126e-6 -7.35691e-4 -0.9999998 1.32932e-4 -4.03223e-4 -1 9.54018e-5 -0.004877269 -0.9999881 6.11879e-4 -0.003461539 -0.9999939 3.03002e-4 -0.02051776 -0.9997895 0.00149405 -0.01697564 -0.9998549 9.019e-5 -0.05299925 -0.9985947 -2.92299e-4 -0.05444252 -0.9985169 -0.00415647 -0.1120484 -0.9936941 -0.0086959 -0.1361519 -0.9906499 -0.01573199 -0.2335034 -0.9722288 -0.01788741 -0.2474097 -0.9687458 -0.02464622 -0.3666125 -0.9300473 -0.02241694 -0.3498654 -0.9365318 -0.03441315 -0.6484425 -0.7604855 -0.0286169 -0.614359 -0.7885076 -0.02856874 0.9472978 -0.3190782 -0.03728038 0.882243 -0.469316 -0.02423322 0.5372903 -0.8430492 -0.02307641 0.3929854 -0.9192552 -0.006301045 0.08838587 -0.9960665 -0.005854129 0.06981337 -0.9975429 -0.002325236 0.02267926 -0.9997402 -0.002099692 0.01584124 -0.9998723 -0.001577854 0.01089799 -0.9999395 -0.001350164 0.006934344 -0.9999751 -7.90701e-4 0.003091394 -0.9999949 -8.18796e-4 0.003376126 -0.999994 3.40123e-4 -0.002713799 -0.9999963 -3.66458e-5 4.2114e-4 -1 4.16482e-4 -0.001424849 -0.999999 3.53492e-4 -3.60161e-4 -1 1.89583e-4 2.43597e-4 -1 1.77863e-4 1.53135e-4 -1 4.25905e-5 7.89984e-4 -0.9999998 -2.11994e-6 6.2729e-4 -0.9999999 0 6.09603e-4 -0.9999999 -2.58686e-5 5.11788e-4 -1 -5.85903e-6 1.83239e-4 -1 -3.58395e-6 1.92748e-4 -1 7.27839e-6 -3.91691e-4 -1 3.06014e-5 -2.95916e-4 -1 3.25203e-5 -0.00342375 -0.9999942 1.99958e-4 -0.002744376 -0.9999963 1.29252e-4 -0.01703876 -0.9998549 6.73534e-4 -0.01464027 -0.9998926 1.62486e-4 -0.05432283 -0.9985234 1.31643e-4 -0.05449974 -0.9985138 -0.002019703 -0.1341006 -0.9909657 -0.003833413 -0.1488217 -0.9888567 -0.006793022 -0.2457993 -0.969297 -0.007514595 -0.2523077 -0.9676179 -0.009783685 -0.3488751 -0.9371183 -0.008982717 -0.3407041 -0.9401277 -0.01364928 -0.6136172 -0.7894857 -0.01090693 -0.5925276 -0.8054763 -0.07436758 0.8808874 -0.4674472 -0.07970046 0.7989874 -0.5960429 -0.04248762 0.3980613 -0.9163745 -0.04171764 0.3805161 -0.9238329 -0.009640812 0.06989353 -0.9975079 -0.01047801 0.08820766 -0.996047 -0.002982974 0.01602023 -0.9998673 -0.003103613 0.02137362 -0.9997668 -0.001610755 0.00699073 -0.9999743 -0.001622617 0.008088588 -0.999966 -0.00110656 0.003383874 -0.9999938 -0.001109302 0.003541886 -0.9999932 -6.7789e-4 3.81749e-4 -0.9999998 -6.8596e-4 0.001101791 -0.9999992 -3.86122e-4 -3.11451e-4 -1 -3.76462e-4 5.73083e-4 -0.9999998 -2.71099e-4 2.0044e-4 -1 -2.42942e-4 5.72633e-4 -0.9999998 -2.6377e-4 6.49766e-4 -0.9999998 -2.4063e-4 8.24875e-4 -0.9999997 -1.84236e-4 5.18993e-4 -0.9999998 -1.46378e-4 8.03521e-4 -0.9999997 -8.80019e-5 1.93474e-4 -1 -4.6203e-5 4.72453e-4 -1 -2.00542e-5 -2.96057e-4 -1 -5.75524e-6 -2.21939e-4 -1 1.37346e-5 -0.00274676 -0.9999963 2.42424e-5 -0.002697706 -0.9999964 4.85043e-5 -0.01465487 -0.9998927 1.63233e-4 -0.01407164 -0.9999011 1.63199e-4 -0.05449795 -0.9985139 1.36275e-4 -0.05468857 -0.9985035 -3.54671e-4 -0.1485443 -0.9889057 -8.53807e-4 -0.1537948 -0.9881025 -0.001531183 -0.2522078 -0.967672 -0.001627564 -0.2532544 -0.9673984 -0.00206995 -0.3407292 -0.9401592 -0.00111711 -0.3292386 -0.9442461 -0.002354681 -0.5920104 -0.8059269 8.03863e-4 -0.5641639 -0.8256624 -0.06584596 0.8033311 -0.5918815 -0.06646955 0.7875682 -0.6126321 -0.03257876 0.3788847 -0.9248704 -0.0340808 0.4351007 -0.8997367 -0.006968855 0.08614897 -0.996258 -0.007346451 0.1071702 -0.9942137 -0.002020359 0.02014774 -0.999795 -0.001945495 0.02353906 -0.9997211 -0.001253664 0.007872879 -0.9999682 -0.001210212 0.008929729 -0.9999594 -0.001011431 0.003548145 -0.9999933 -0.001065969 0.00253576 -0.9999963 -9.58698e-4 0.001051485 -0.9999991 -9.79879e-4 7.84668e-4 -0.9999992 -9.57151e-4 6.50588e-4 -0.9999994 -9.20079e-4 0.001095235 -0.9999991 -8.36905e-4 7.47017e-4 -0.9999995 -7.69412e-4 0.001529037 -0.9999986 -6.32688e-4 9.23612e-4 -0.9999994 -5.54505e-4 0.00195074 -0.999998 -3.81954e-4 8.35591e-4 -0.9999997 -2.87863e-4 0.002200663 -0.9999976 -1.56736e-4 4.73466e-4 -0.9999999 -7.47669e-5 0.001240193 -0.9999992 -4.01301e-5 -2.23326e-4 -1 -2.56978e-5 -1.41129e-4 -1 -1.19214e-5 -0.002698957 -0.9999964 -2.74659e-5 -0.002773463 -0.9999963 1.16851e-5 -0.01407253 -0.999901 7.97847e-6 -0.01409196 -0.9999007 1.33338e-4 -0.05468851 -0.9985035 6.25449e-5 -0.05522406 -0.9984741 1.20755e-4 -0.1537922 -0.9881033 -8.24295e-5 -0.1561098 -0.9877398 -1.31985e-4 -0.2532567 -0.9673991 -2.01529e-4 -0.2540545 -0.96719 -2.26955e-4 -0.3292586 -0.9442398 -3.16159e-5 -0.3267608 -0.9451071 -1.38047e-4 -0.5642037 -0.8256357 0.001371324 -0.5492802 -0.8356372 0.00666815 0.8681851 -0.4961958 -0.001726329 0.7718039 -0.6358584 1.52033e-5 0.4477829 -0.8941424 -0.00384742 0.312045 -0.9500595 -8.36751e-4 0.08676862 -0.9962282 -0.001231014 0.07011431 -0.9975383 -5.54869e-4 0.01779347 -0.9998416 -5.24331e-4 0.01843494 -0.99983 -4.501e-4 0.007674753 -0.9999705 -4.22788e-4 0.008158683 -0.9999667 -3.87067e-4 0.002733588 -0.9999963 -4.20324e-4 0.002337574 -0.9999973 -3.79019e-4 0.001051247 -0.9999995 -3.84471e-4 0.001010358 -0.9999995 -3.90263e-4 0.001085698 -0.9999994 -3.52941e-4 0.00132811 -0.9999991 -3.57891e-4 0.001385152 -0.9999991 -2.75924e-4 0.001874387 -0.9999983 -2.75174e-4 0.001861691 -0.9999983 -2.03869e-4 0.002350807 -0.9999973 -1.98981e-4 0.00218743 -0.9999976 -1.94563e-4 0.002228319 -0.9999976 -1.86279e-4 0.001237213 -0.9999992 -1.84637e-4 0.001250803 -0.9999993 -1.86045e-4 -1.49699e-4 -1 -2.18201e-4 -3.25801e-4 -1 -2.19194e-4 -0.002778649 -0.9999962 -2.70469e-4 -0.003018736 -0.9999954 -2.42304e-4 -0.01408791 -0.9999008 -2.8061e-4 -0.01428616 -0.999898 -1.59626e-4 -0.05520945 -0.9984748 -2.36386e-4 -0.05579465 -0.9984423 -1.1795e-4 -0.1561094 -0.9877398 -2.5492e-4 -0.1576904 -0.9874886 -2.13698e-4 -0.2540605 -0.9671884 -2.40921e-4 -0.2543721 -0.9671064 -2.20755e-4 -0.3267694 -0.9451041 -2.47691e-4 -0.3271089 -0.9449867 -1.73266e-4 -0.5492953 -0.8356283 1.18473e-4 -0.54629 -0.8375961 0.06088495 0.8177348 -0.5723659 0.03719151 0.6445642 -0.7636451 0.01875835 0.3155964 -0.9487082 0.009347021 0.2055146 -0.9786095 0.002789497 0.04686033 -0.9988976 0.001711487 0.03330391 -0.9994438 7.74126e-4 0.008558273 -0.9999632 9.44447e-4 0.01007616 -0.9999488 7.07751e-4 0.005099415 -0.9999868 9.11609e-4 0.006558001 -0.9999782 6.62362e-4 0.002768218 -0.999996 7.6728e-4 0.003265798 -0.9999945 6.19823e-4 0.001718282 -0.9999984 7.14354e-4 0.002017736 -0.9999977 6.66927e-4 0.001681089 -0.9999985 5.03444e-4 0.001249909 -0.9999992 6.2255e-4 0.00190258 -0.999998 2.21836e-4 9.12673e-4 -0.9999996 5.26082e-4 0.002473294 -0.9999969 -4.81004e-4 -3.4645e-4 -0.9999999 -5.89089e-5 0.002263545 -0.9999975 -0.001535475 -0.003179907 -0.9999938 -0.001068234 0.001122474 -0.9999989 -0.001811563 -0.002128303 -0.9999961 -0.001703798 -4.05685e-4 -0.9999985 -0.002188861 -0.002343595 -0.9999949 -0.002210855 -0.003039777 -0.999993 -0.002611875 -0.004604041 -0.9999861 -0.002718985 -0.01419353 -0.9998956 -0.00283277 -0.01472103 -0.9998877 -0.002875149 -0.05552399 -0.9984533 -0.002911329 -0.0557841 -0.9984387 -0.002777218 -0.157555 -0.9875063 -0.002829074 -0.1581356 -0.9874134 -0.002618849 -0.2543959 -0.9670967 -0.002585768 -0.2540203 -0.9671955 -0.002447843 -0.3271271 -0.9449772 -0.002720773 -0.330568 -0.9437783 -0.002179503 -0.5461701 -0.8376716 -0.003128945 -0.5557308 -0.8313565 -0.02355319 0.6272432 -0.7784672 0.1364327 0.9345697 -0.3285815 -0.003010809 0.200973 -0.9795922 0.09581851 0.6101546 -0.7864668 -0.001294314 0.04003536 -0.9991974 0.01729637 0.115813 -0.9931205 -9.35811e-4 0.01902997 -0.9998186 -4.8434e-4 0.02036935 -0.9997924 -0.002416729 0.01208543 -0.9999241 -0.006887257 4.93425e-4 -0.9999762 -0.00717628 -6.21395e-4 -0.9999741 -0.006576478 7.38711e-4 -0.9999781 -0.007891416 -0.00400716 -0.9999608 -0.002992212 0.005156457 -0.9999822 -0.005139827 -0.001202285 -0.9999862 -0.004938125 -8.78429e-4 -0.9999875 -0.004844665 -6.47529e-4 -0.9999881 -0.007173955 -0.004042148 -0.9999662 -0.006889998 -0.00340259 -0.9999706 -0.01140242 -0.01021271 -0.9998829 -0.009954273 -0.006818473 -0.9999272 -0.01566785 -0.01636481 -0.9997434 -0.0112071 -0.004075765 -0.999929 -0.015823 -0.01246494 -0.9997972 -0.01321375 -0.002971708 -0.9999083 -0.01736652 -0.01074379 -0.9997915 -0.01627719 -0.004560887 -0.9998572 -0.01923501 -0.0108152 -0.9997566 -0.01948326 -0.01384192 -0.9997144 -0.02026325 -0.01611602 -0.9996649 -0.02111583 -0.05354237 -0.9983423 -0.0209555 -0.05271142 -0.9983899 -0.02079117 -0.15678 -0.9874148 -0.02039718 -0.1531339 -0.987995 -0.01928496 -0.2542073 -0.9669575 -0.01907622 -0.2520439 -0.9675278 -0.01811635 -0.3309874 -0.9434612 -0.01913827 -0.3428924 -0.9391797 -0.01559174 -0.5550633 -0.8316621 -0.01822137 -0.5794825 -0.814781 0.09671258 0.9343786 -0.3429043 0.2035953 0.9583477 -0.2002961 0.01206016 0.5846146 -0.8112215 0.1392323 0.7784853 -0.6120255 -0.09326136 0.1518356 -0.9839962 -0.05597865 0.2316198 -0.9711945 -0.09227412 0.1280811 -0.9874618 -0.1355059 0.05663508 -0.9891566 -0.1500513 0.02123028 -0.9884503 -0.1996188 -0.05135041 -0.9785273 -0.2198271 -0.09842157 -0.9705613 -0.1636113 -0.02293056 -0.9862584 -0.2070688 -0.1168715 -0.9713206 -0.09858363 0.01671904 -0.9949883 -0.1383403 -0.05526226 -0.9888418 -0.1039094 -0.0180068 -0.9944238 -0.1170768 -0.03776806 -0.9924045 -0.1251797 -0.04540228 -0.9910948 -0.1339963 -0.0565564 -0.9893667 -0.1440253 -0.06545233 -0.9874072 -0.1287667 -0.04773074 -0.9905257 -0.1423976 -0.05913138 -0.9880418 -0.1138853 -0.02594769 -0.9931551 -0.1317721 -0.03993314 -0.9904754 -0.1124374 -0.01455432 -0.9935523 -0.1308276 -0.02820861 -0.9910038 -0.120524 -0.009238839 -0.9926674 -0.1328502 -0.01941764 -0.9909459 -0.1304631 -0.01041615 -0.9913985 -0.1352241 -0.01626825 -0.9906815 -0.1369934 -0.04089009 -0.9897277 -0.1387273 -0.04523164 -0.9892972 -0.136692 -0.1451739 -0.9799184 -0.1364087 -0.1435321 -0.9801996 -0.1295292 -0.2527368 -0.9588255 -0.1290967 -0.2488993 -0.9598872 -0.121615 -0.3448845 -0.9307333 -0.1222299 -0.3521453 -0.9279298 -0.09883797 -0.5727162 -0.8137735 -0.09942054 -0.5784344 -0.8096476 -0.3236444 0.9133862 -0.2469416 -0.4405691 0.8548496 -0.2741006 -0.8760577 0.2575513 -0.4076645 -0.79539 0.438779 -0.4181241 -0.9066244 0.05920135 -0.4177648 -0.8716073 0.2036283 -0.4459104 -0.8847464 0.1462595 -0.442529 -0.9150521 0.01463389 -0.4030705 -0.9190197 -0.09446203 -0.3827267 -0.9194064 -0.09831064 -0.380824 -0.9064658 -0.2547517 -0.3367808 -0.8798847 -0.05444824 -0.4720577 -0.8617156 -0.3534607 -0.364022 -0.7667322 -9.86673e-4 -0.6419664 -0.7925114 -0.2784345 -0.5425863 -0.695422 -0.05351561 -0.7166061 -0.7163292 -0.22261 -0.6612997 -0.6620897 -0.115899 -0.7404084 -0.6745055 -0.2296168 -0.701654 -0.6277887 -0.1443779 -0.7648768 -0.6294449 -0.1545936 -0.7615116 -0.6077158 -0.122477 -0.7846535 -0.599121 -0.08277863 -0.796368 -0.6041365 -0.08822959 -0.7919815 -0.5923665 -0.0364952 -0.8048416 -0.6116999 -0.0518161 -0.7893912 -0.6042213 -0.005677223 -0.7967963 -0.6197016 -0.01692664 -0.784655 -0.6188043 0.006218433 -0.7855206 -0.6262716 -0.001463174 -0.7796037 -0.6255691 -0.01260137 -0.780067 -0.631559 -0.02621835 -0.7748844 -0.6179202 -0.1135846 -0.7779931 -0.619109 -0.1261413 -0.775108 -0.5927473 -0.23053 -0.7716907 -0.5926319 -0.2327548 -0.7711113 -0.56128 -0.3289026 -0.7594655 -0.5627815 -0.3183125 -0.7628592 -0.481257 -0.5086802 -0.7138881 -0.4935665 -0.4501266 -0.7441627 0.997475 0.05350142 -0.04670494 0.996669 0.06725281 -0.04613 0.997133 0.005372464 -0.07547843 0.9965032 -0.01871246 -0.08143222 0.9957719 -0.01674616 -0.09032112 0.9946967 -0.03691989 -0.09599727 0.9942934 -0.02978986 -0.1024369 0.9926834 -0.05452513 -0.1077349 0.9916946 -0.04741919 -0.1195546 0.989616 -0.0765962 -0.1216273 0.9854586 -0.07375884 -0.1530721 0.9796994 -0.1359167 -0.147363 0.9720646 -0.1230596 -0.1998671 0.9606583 -0.2115911 -0.1799024 0.9644458 -0.1636571 -0.2075108 0.9628753 -0.1768299 -0.2039669 0.9671707 -0.1486003 -0.2061522 0.9676102 -0.1431839 -0.2079157 0.9717541 -0.03254288 -0.2337411 0.9734583 -0.09066885 -0.2101384 0.9659364 -0.03820013 -0.2559447 0.9665703 -0.1086004 -0.2322668 0.9515461 -0.1265286 -0.280269 0.9410768 -0.2153503 -0.260766 0.902107 -0.3005409 -0.3096418 0.8574303 -0.4264695 -0.2879884 0.7957006 -0.5097812 -0.3270835 0.7232064 -0.6203822 -0.3034775 0.6848516 -0.6511195 -0.3271417 0.6239699 -0.717988 -0.308472 0.5949426 -0.7371963 -0.3202888 0.5505003 -0.7765118 -0.3065599 0.5219591 -0.7943911 -0.310647 0.4933096 -0.8159168 -0.3015383 0.4697557 -0.8296211 -0.3017591 0.4522172 -0.8413371 -0.29606 0.4300076 -0.8536691 -0.2938408 0.4195398 -0.8600627 -0.2903078 0.390114 -0.8755856 -0.2848878 0.3855265 -0.8781988 -0.2830833 -0.6579256 -0.6430068 -0.3920156 -0.8110395 -0.4740761 -0.3427347 -0.835586 -0.3905466 -0.3863539 -0.859709 -0.3475309 -0.37433 -0.889751 -0.2645023 -0.371997 -0.8929191 -0.2570198 -0.3696437 -0.9175299 -0.1748788 -0.3571503 -0.9160625 -0.1792646 -0.3587393 -0.9372618 -0.07907408 -0.3395403 -0.9363877 -0.08258908 -0.3411117 -0.9445792 -0.006872475 -0.328212 -0.9455919 -0.002624332 -0.3253446 -0.9452157 0.01272529 -0.3261986 -0.9462619 0.01568192 -0.3230209 -0.9429944 -0.001078009 -0.3328073 -0.9437336 4.27599e-4 -0.3307062 -0.9386265 -0.03621947 -0.3430286 -0.9326323 -0.04658728 -0.3578079 -0.9438456 -0.0529353 -0.3261185 -0.9177579 -0.09916108 -0.3845617 -0.9579408 -0.0523169 -0.2821568 -0.9093493 -0.1492052 -0.3883575 -0.9727549 -0.05192434 -0.2259463 -0.9155175 -0.1874945 -0.3559127 -0.9841225 -0.04318553 -0.1721569 -0.947167 -0.1676454 -0.2734403 -0.9913617 -0.04106593 -0.1245614 -0.9672572 -0.1565809 -0.1997401 -0.9942869 -0.05982506 -0.08840018 -0.9771596 -0.1641363 -0.1349761 -0.9942907 -0.07143247 -0.07926982 -0.989561 -0.1136943 -0.08855843 -0.9934677 -0.07938277 -0.08197808 -0.9951997 -0.05706155 -0.0795086 -0.9961637 -0.02187174 -0.08473205 -0.9965223 -0.003372907 -0.08325874 -0.9936878 0.07798969 -0.08063691 -0.9963011 0.01111924 -0.08520907 -0.9806062 0.1824488 -0.07158219 -0.9955904 0.04842585 -0.08034187 0.4641222 0.5700562 -0.6779577 0.6712378 0.6273335 -0.3948324 0.5763779 0.2057179 -0.7908658 0.689565 0.3523634 -0.6327244 0.6111265 0.04785621 -0.790085 0.6838164 0.1673388 -0.7102063 0.6415122 -0.008646428 -0.7670642 0.679149 0.05425965 -0.7319922 0.6627486 -0.04072749 -0.7477337 0.6627944 -0.04065352 -0.7476971 0.658638 -0.09083145 -0.7469577 0.6156804 -0.158191 -0.7719542 0.6156632 -0.1537694 -0.7728608 0.5632864 -0.2512788 -0.787126 0.5535908 -0.1509249 -0.8189988 0.5379225 -0.2118225 -0.8159478 0.5260961 -0.1396563 -0.8388797 0.5241246 -0.1542167 -0.8375623 0.5053321 -0.06352418 -0.8605837 0.4976349 -0.114586 -0.8597847 0.4915723 -0.07844734 -0.8672963 0.482727 -0.1303263 -0.8660194 0.488761 -0.1955571 -0.8502178 0.4835026 -0.2254511 -0.8458114 0.4826586 -0.401921 -0.7781391 0.4839119 -0.3964089 -0.7801854 0.4589185 -0.5983663 -0.6567736 0.4651492 -0.5802081 -0.6685767 0.4333367 -0.7058175 -0.5603936 0.4349013 -0.7024518 -0.5634026 0.4097662 -0.7689758 -0.4906809 0.4059364 -0.7755668 -0.4834374 0.3883669 -0.8113944 -0.4368185 0.3871521 -0.8132066 -0.4345208 0.3713741 -0.8404308 -0.3946611 0.3738621 -0.8371087 -0.3993447 0.3580943 -0.8610847 -0.360973 0.3604599 -0.8582782 -0.3652769 0.3436011 -0.8809779 -0.3252945 0.3420537 -0.8824991 -0.3227921 -0.7392538 -0.07059282 0.6697168 -0.7142847 0.0132988 0.6997289 -0.6782106 -0.006291389 0.7348408 -0.7263168 -0.04284644 0.6860234 -0.66205 -0.2899598 0.6910957 -0.6099271 -0.3206478 0.7246889 0.1657058 -0.7172631 0.6768127 -0.6536967 -0.01389634 0.7566291 -0.6686353 -0.02775883 0.7430723 -0.6914887 -0.2154459 0.6895118 -0.6899006 -0.06604135 0.7208855 -0.6995837 -0.1212775 0.7041836 -0.7151927 -0.1647824 0.6792247 -0.5350872 -0.4980502 0.6823692 -0.4705199 -0.6237894 0.6240977 -0.5987427 -0.4993056 0.6262597 -0.60255 -0.4116976 0.6836948 0.5050661 -0.3901878 0.7698453 0.5050656 -0.3901814 0.7698489 -0.3651484 -0.1825742 -0.912871 0.5050643 -0.3901911 0.7698447 0.4038575 -0.6613951 0.632025 0.4988614 -0.410766 0.763157 0.364162 -0.7336733 0.5736808 0.459129 -0.5334061 0.7104073 0.4374569 -0.8614361 0.257991 0.4148644 -0.7252271 0.5494845 0.467944 -0.8789368 0.09218841 0.4704262 -0.8802521 -0.06209385 -0.04962563 -0.6714565 -0.7393805 -0.04277276 -0.6491881 -0.7594244 -0.06576246 -0.6815472 -0.7288132 -0.05993127 -0.6727235 -0.7374627 -0.07803273 -0.6876108 -0.7218742 -0.07304883 -0.6824503 -0.7272727 -0.08138239 -0.6926142 -0.7167025 -0.07601863 -0.6873849 -0.7223041 -0.08321088 -0.6980603 -0.7111876 -0.0771529 -0.6921446 -0.7176235 -0.03654396 -0.3843548 -0.9224619 -0.03344053 -0.3694362 -0.9286543 -0.04883623 -0.3951125 -0.9173339 -0.0468468 -0.3896002 -0.9197919 -0.05688393 -0.3998675 -0.9148061 -0.05680948 -0.3997139 -0.9148778 -0.05831193 -0.3997353 -0.9147741 -0.05897706 -0.40116 -0.9141075 -0.05832636 -0.3980926 -0.9154892 -0.05942487 -0.4004464 -0.9143913 -0.02231472 -0.2253614 -0.9740197 -0.0253241 -0.238124 -0.9709046 -0.03010499 -0.223093 -0.9743322 -0.03429925 -0.2343278 -0.9715525 -0.03489553 -0.2197585 -0.97493 -0.04040813 -0.232083 -0.9718564 -0.0347566 -0.211994 -0.9766528 -0.04067754 -0.2252277 -0.9734566 -0.03356784 -0.2033376 -0.9785332 -0.03943926 -0.2167332 -0.975434 -0.005798757 -0.09883689 -0.9950868 -0.01151591 -0.117013 -0.9930636 -0.01040273 -0.09561878 -0.9953637 -0.01700347 -0.1088091 -0.9939172 -0.0145533 -0.09441071 -0.995427 -0.02173644 -0.1067407 -0.9940493 -0.01465302 -0.0895543 -0.9958742 -0.02200639 -0.102135 -0.9945271 -0.01222079 -0.08132898 -0.9966124 -0.02078473 -0.09616732 -0.9951483 -0.004772603 -0.06456106 -0.9979024 -0.01779407 -0.08740323 -0.9960141 -5.02621e-4 -0.05164951 -0.9986652 -0.001559913 -0.05383765 -0.9985486 -0.002563893 -0.05082297 -0.9987044 -0.006049931 -0.05527216 -0.9984531 -0.00420773 -0.04950392 -0.9987651 -0.01049482 -0.056584 -0.9983428 -0.003330051 -0.04603391 -0.9989344 -0.01092195 -0.05470412 -0.998443 0.002413094 -0.03745889 -0.9992953 -0.008191704 -0.04996061 -0.9987176 0.01574754 -0.02010607 -0.9996739 3.60901e-4 -0.03912413 -0.9992344 1.32577e-4 -0.02192986 -0.9997596 0.001208901 -0.02043706 -0.9997904 -2.45632e-4 -0.02172118 -0.9997641 -7.51322e-4 -0.02203738 -0.9997569 -2.51782e-4 -0.02102422 -0.999779 -0.002399504 -0.02203226 -0.9997544 8.68181e-4 -0.02012336 -0.9997971 -0.001432776 -0.02121311 -0.999774 0.00699532 -0.0184617 -0.9998052 0.005229353 -0.01939272 -0.9997984 0.01823627 -0.01573574 -0.99971 0.01675552 -0.01673334 -0.9997196 0.02369016 -0.01340687 -0.9996295 0.02172827 -0.01502817 -0.999651 9.00437e-5 -0.005481302 -0.999985 5.73287e-4 -0.004962027 -0.9999876 1.69892e-4 -0.005558431 -0.9999846 2.89569e-4 -0.005531013 -0.9999847 2.79569e-4 -0.00559926 -0.9999844 3.11381e-4 -0.005598425 -0.9999844 5.08424e-4 -0.006008744 -0.9999818 0.001602768 -0.006007075 -0.9999808 0.003207802 -0.008909463 -0.9999552 0.008623182 -0.008692979 -0.9999251 0.01055216 -0.01551091 -0.9998241 0.01896268 -0.01370257 -0.9997264 0.01535677 -0.02002441 -0.9996816 0.02202957 -0.01720041 -0.9996094 3.03041e-5 -8.91172e-4 -0.9999997 1.49825e-4 -7.69424e-4 -0.9999998 8.79866e-5 -9.89328e-4 -0.9999996 2.4887e-4 -9.6642e-4 -0.9999996 1.1181e-4 -0.001073896 -0.9999995 3.47402e-4 -0.001093387 -0.9999994 9.3614e-5 -0.001214861 -0.9999994 5.61815e-4 -0.001271545 -0.9999991 4.80815e-4 -0.002458989 -0.999997 0.003573238 -0.002833068 -0.9999896 0.003383994 -0.007439613 -0.9999666 0.01225709 -0.007804751 -0.9998944 0.008782923 -0.01324886 -0.9998738 0.01810801 -0.01227086 -0.9997608 0.005554676 -0.01453405 -0.999879 0.01127439 -0.01350444 -0.9998453 0.00308305 -0.01443547 -0.9998911 0.001764118 -0.01474207 -0.9998899 -6.86171e-5 -1.10529e-4 -1 3.51103e-5 2.45801e-6 -1 -4.71525e-6 -1.69038e-4 -1 9.08064e-5 -1.38339e-4 -1 3.37888e-5 -2.02906e-4 -1 1.12758e-4 -1.93413e-4 -1 3.6013e-5 -2.20782e-4 -1 9.06395e-5 -2.15965e-4 -1 5.43768e-5 -3.60988e-4 -1 4.87477e-4 -3.30272e-4 -0.9999998 5.28602e-4 -0.001402795 -0.9999989 0.003750085 -0.00125122 -0.9999923 0.003136515 -0.003647923 -0.9999885 0.0105741 -0.003379166 -0.9999385 0.004304409 -0.004143595 -0.9999822 0.006944954 -0.004023015 -0.9999679 0.008662223 -0.003741323 -0.9999555 0.003227055 -0.004121661 -0.9999863 0.01578313 -0.003024041 -0.9998709 0.007000803 -0.00378859 -0.9999684 -2.45914e-4 2.64968e-4 -1 -5.50589e-5 4.48695e-4 -1 -1.45568e-4 1.97711e-4 -1 -9.0939e-7 2.57958e-4 -1 3.14892e-5 1.92381e-4 -1 3.3557e-5 1.92936e-4 -1 8.44392e-5 2.05399e-4 -1 3.53127e-5 1.92301e-4 -1 1.36384e-4 2.27307e-4 -1 5.36703e-5 2.05744e-4 -1 3.52173e-4 1.87913e-4 -1 5.37248e-4 2.28193e-4 -0.9999999 0.001653671 1.3098e-5 -0.9999987 0.003315687 2.54423e-4 -0.9999945 0.00589168 3.03448e-4 -0.9999826 0.004496991 1.50815e-4 -0.9999899 0.01239979 8.85421e-4 -0.9999228 0.008615374 4.86058e-4 -0.9999628 0.01023131 5.59808e-4 -0.9999476 0.01569527 0.001135528 -0.9998763 -3.31037e-4 6.66961e-4 -0.9999998 -1.94299e-4 7.6758e-4 -0.9999998 -2.28171e-4 6.33046e-4 -0.9999998 -1.11728e-4 6.7498e-4 -0.9999998 1.84028e-4 6.94626e-4 -0.9999998 3.64609e-5 6.51628e-4 -0.9999999 4.2342e-4 7.91357e-4 -0.9999997 8.4982e-5 6.83767e-4 -0.9999998 6.24429e-4 9.16199e-4 -0.9999995 1.37229e-4 7.47914e-4 -0.9999997 0.001176595 0.001143276 -0.9999987 3.53726e-4 8.64052e-4 -0.9999997 0.003291666 0.001737117 -0.9999931 0.001663625 0.001252651 -0.9999979 0.009245991 0.003267168 -0.999952 0.005927503 0.002367436 -0.9999796 0.01053589 0.003531157 -0.9999383 0.01272124 0.004108428 -0.9999107 0.003415942 0.001621723 -0.9999929 0.01212728 0.003905236 -0.9999189 -1.42255e-4 6.45016e-4 -0.9999999 -3.61621e-4 4.83859e-4 -0.9999998 5.60884e-5 7.28988e-4 -0.9999998 -2.26818e-4 6.40961e-4 -0.9999998 7.51735e-4 8.77616e-4 -0.9999994 1.86367e-4 7.40062e-4 -0.9999997 0.001512527 0.001137495 -0.9999983 4.23864e-4 8.32855e-4 -0.9999996 0.002376079 0.001537561 -0.999996 6.24799e-4 9.63527e-4 -0.9999994 0.004102766 0.002266407 -0.9999891 0.001177549 0.001232743 -0.9999986 0.00921756 0.004092335 -0.9999492 0.00329715 0.002025842 -0.9999926 0.01534664 0.00619173 -0.9998631 0.009321272 0.004125416 -0.9999482 0.01023554 0.004526197 -0.9999375 0.01131802 0.004899084 -0.999924 0.001897156 0.0018 -0.9999967 0.004682064 0.002788305 -0.9999852 1.29645e-5 -7.40262e-4 -0.9999998 -2.20238e-4 -0.001093864 -0.9999994 8.43666e-5 -6.83266e-4 -0.9999998 -4.83494e-5 -7.35157e-4 -0.9999998 4.62141e-4 -7.79886e-4 -0.9999997 6.95527e-4 -7.56868e-4 -0.9999995 0.001136958 -9.29748e-4 -0.9999989 0.001455724 -9.20026e-4 -0.9999985 0.002249658 -0.001093447 -0.999997 0.002291023 -0.001093089 -0.9999968 0.004818022 -0.001314282 -0.9999876 0.003944694 -0.001304209 -0.9999914 0.0114817 -0.001792907 -0.9999325 0.008719027 -0.001699805 -0.9999606 0.01788288 -0.002070248 -0.999838 0.01283085 -0.001905024 -0.999916 0.01231688 -0.001048505 -0.9999236 0.005171 -0.001165628 -0.9999861 0.003274142 3.55298e-5 -0.9999946 -9.97649e-4 -5.56058e-4 -0.9999994 1.85877e-4 -0.004441201 -0.9999901 1.80399e-4 -0.004487335 -0.99999 4.53098e-5 -0.00452876 -0.9999898 1.10118e-4 -0.004415333 -0.9999903 5.95949e-5 -0.004866719 -0.9999883 4.04275e-4 -0.00475794 -0.9999886 1.89146e-4 -0.005555152 -0.9999846 9.96171e-4 -0.00582832 -0.9999825 4.91209e-4 -0.006783843 -0.9999769 0.001951396 -0.00809592 -0.9999654 0.00127536 -0.009192049 -0.999957 0.003951907 -0.01299011 -0.9999079 0.003986418 -0.01568758 -0.9998691 0.008451998 -0.02359223 -0.999686 0.009255647 -0.02700018 -0.9995926 0.01093578 -0.03012812 -0.9994863 0.01123136 -0.0273844 -0.999562 0.00313282 -0.0144236 -0.9998911 0.005802452 -0.01086568 -0.9999242 -0.001710772 -0.004366636 -0.999989 -2.05459e-4 0.002831459 -0.999996 -2.04585e-4 0.002936065 -0.9999957 -8.16451e-5 0.002541303 -0.9999968 -5.43853e-5 0.002780318 -0.9999962 -2.84946e-5 0.001936972 -0.9999982 8.92265e-5 0.002402544 -0.9999971 7.25901e-6 9.28654e-4 -0.9999996 2.54134e-4 0.001482069 -0.9999989 9.34979e-5 -8.36728e-4 -0.9999997 5.93674e-4 -6.24485e-4 -0.9999997 3.55489e-4 -0.003951847 -0.9999922 0.001403689 -0.005762577 -0.9999824 0.001506984 -0.01178306 -0.9999295 0.003645896 -0.01919966 -0.9998091 0.004401326 -0.02831941 -0.9995893 0.006955206 -0.03890353 -0.9992188 0.007892668 -0.04474264 -0.9989674 0.006799638 -0.04033082 -0.9991633 0.01005047 -0.03932613 -0.9991759 0.001799106 -0.01606965 -0.9998694 -8.1154e-4 0.02900069 -0.9995791 -9.42415e-4 0.02146387 -0.9997693 -2.39412e-4 0.03013283 -0.999546 -3.46071e-4 0.02897882 -0.99958 -5.00834e-5 0.02990359 -0.9995528 -1.90889e-5 0.03010106 -0.999547 -2.96273e-5 0.02934044 -0.9995695 6.5169e-5 0.02985966 -0.9995541 4.55511e-5 0.02831262 -0.9995991 2.37411e-4 0.02913683 -0.9995754 3.25692e-4 0.02635103 -0.9996527 7.87243e-4 0.02732944 -0.9996263 0.001804411 0.0215637 -0.9997659 0.002989709 0.02126497 -0.9997695 0.006627261 0.00941646 -0.9999337 0.008750915 0.006602585 -0.9999399 0.01298582 -0.005815267 -0.9998988 0.01517432 -0.009210646 -0.9998425 0.01770961 -0.0158329 -0.9997178 0.01748895 -0.01550358 -0.9997269 -7.6846e-4 0.0543226 -0.9985232 -0.001129984 0.04202687 -0.999116 -1.98047e-4 0.05630064 -0.9984139 -3.86833e-4 0.05432474 -0.9985233 -4.93731e-5 0.05635064 -0.9984111 -5.70219e-5 0.05629748 -0.9984141 -4.09304e-5 0.05621778 -0.9984186 -1.99121e-5 0.05634981 -0.9984112 4.57862e-5 0.05595642 -0.9984332 9.04032e-5 0.05620712 -0.9984192 4.12948e-4 0.05542594 -0.9984627 5.24001e-4 0.0558604 -0.9984385 0.002374827 0.05410051 -0.9985327 0.002710759 0.05462259 -0.9985034 0.008857429 0.05047321 -0.9986862 0.01022326 0.05101943 -0.9986454 0.01804202 0.04531544 -0.9988098 0.02099764 0.04566031 -0.9987364 0.02506852 0.04083782 -0.9988514 0.02873468 0.04106324 -0.9987434 -9.64071e-4 0.1569027 -0.9876136 -0.00176388 0.1334202 -0.9910581 -1.64539e-4 0.1602336 -0.9870792 -4.74135e-4 0.1568973 -0.9876148 -3.56658e-5 0.1604241 -0.9870483 -6.27174e-5 0.1602314 -0.9870795 -2.0242e-5 0.160445 -0.9870448 -2.40288e-5 0.160422 -0.9870486 1.66029e-4 0.1604691 -0.9870409 1.61464e-4 0.1604449 -0.9870448 0.001039028 0.160681 -0.9870059 9.90575e-4 0.1604589 -0.9870421 0.005142271 0.1609463 -0.9869499 0.00498116 0.1606267 -0.9870027 0.01675641 0.1607912 -0.9868463 0.01707601 0.1610641 -0.9867962 0.02870523 0.1589315 -0.9868723 0.03268468 0.1611157 -0.9863942 0.03654748 0.1557546 -0.9871196 0.04361289 0.1591265 -0.9862945 -0.001790165 0.687221 -0.7264462 -0.00367558 0.6582312 -0.752807 -1.96641e-4 0.6893167 -0.7244602 -5.429e-4 0.6872002 -0.7264679 -2.36587e-5 0.6893004 -0.7244757 -2.21884e-5 0.6893073 -0.7244692 7.95491e-5 0.6893299 -0.7244476 7.05838e-5 0.6893065 -0.7244699 8.12641e-4 0.6894781 -0.7243061 7.69956e-4 0.6893544 -0.7244238 0.004257261 0.6900814 -0.7237194 0.004030823 0.6894848 -0.724289 0.01940858 0.6912434 -0.7223613 0.01844304 0.690109 -0.7234705 0.05689126 0.6921231 -0.7195339 0.0549404 0.6912482 -0.7205258 0.08313012 0.6901077 -0.7189164 0.08845317 0.6916657 -0.7167809 0.09462124 0.6861699 -0.7212612 0.1075913 0.6892727 -0.7164688 -0.001401662 0.9656627 -0.2597959 -0.002297878 0.9640152 -0.2658375 -2.07903e-4 0.9656722 -0.2597637 -2.2172e-4 0.9656639 -0.2597947 -3.21547e-5 0.9656629 -0.2597982 -8.48216e-6 0.9656743 -0.2597561 1.04776e-4 0.9656462 -0.2598605 1.37749e-4 0.9656645 -0.2597926 9.97899e-4 0.965593 -0.2600558 0.001121938 0.965648 -0.2598513 0.005072712 0.965373 -0.2608242 0.005713403 0.9655795 -0.2600456 0.02339416 0.9647828 -0.2620059 0.0257517 0.9650753 -0.260704 0.07150751 0.9623842 -0.2621133 0.07461333 0.9623486 -0.2613773 0.1110988 0.9587923 -0.2614853 0.1125215 0.9586994 -0.2612171 0.1327753 0.9562337 -0.2607449 0.13122 0.9563813 -0.2609906 -0.02064353 -0.9973844 0.06926953 -0.0783807 -0.9948765 0.06385385 -0.02355378 -0.9979041 0.06027328 -0.08275002 -0.995077 0.05453699 -0.02605426 -0.9983885 0.05041325 -0.08265364 -0.9955902 0.04436933 -0.02424234 -0.998909 0.03991478 -0.07704448 -0.9964414 0.0341894 -0.01782411 -0.9994083 0.02941894 -0.0604518 -0.9978595 0.02494317 -0.009629487 -0.9997465 0.02035164 -0.03594726 -0.9992033 0.01733744 -0.005613803 -0.9998782 0.01456576 -0.02087759 -0.9997047 0.01244151 -0.004201769 -0.9999276 0.01127785 -0.01803278 -0.9997981 0.008869051 -0.004294931 -0.9999557 0.008381843 -0.0233308 -0.999719 0.004227817 -0.003900885 -0.9999826 0.004446804 -0.03011429 -0.9995366 -0.004424929 -0.07665342 -0.9875652 0.1372563 -0.1607911 -0.9801521 0.1159669 -0.08277535 -0.9887444 0.124631 -0.1683861 -0.9803321 0.1029326 -0.08638334 -0.9900289 0.1112694 -0.1732807 -0.9808514 0.08890616 -0.08311462 -0.9917524 0.09756678 -0.1703451 -0.9825301 0.07494866 -0.06754416 -0.9941461 0.0843293 -0.1496847 -0.9867452 0.0626769 -0.04575216 -0.9963902 0.07150691 -0.1189413 -0.9915599 0.05159324 -0.03167569 -0.997731 0.05941206 -0.09818083 -0.9943431 0.04052513 -0.02705979 -0.9984496 0.04864531 -0.09668141 -0.9949537 0.02683317 -0.02899736 -0.9989065 0.03667569 -0.1080124 -0.9941024 0.009682059 -0.02895182 -0.9993289 0.02244228 -0.09682095 -0.9952868 -0.005468487 -0.1531909 -0.9750348 0.1607475 -0.2024911 -0.9687368 0.1433405 -0.1599027 -0.9752219 0.1528834 -0.2117125 -0.9680761 0.1341882 -0.1649097 -0.9756158 0.1448399 -0.220375 -0.9674602 0.1243211 -0.1628694 -0.9769964 0.137665 -0.2253915 -0.9675663 0.1140801 -0.1450306 -0.9804435 0.1330289 -0.221211 -0.9697248 0.1034397 -0.1199806 -0.984525 0.1277311 -0.215541 -0.9723612 0.08975529 -0.1031022 -0.9876726 0.1177831 -0.2208055 -0.9727385 0.07088571 -0.1013631 -0.9895682 0.1023742 -0.2339193 -0.9710912 0.04758024 -0.1057972 -0.9909179 0.08299767 -0.2305894 -0.9726299 0.02863359 -0.08247131 -0.9941998 0.0690307 -0.1662166 -0.9857164 0.02711713 -0.1992796 -0.9674779 0.1558017 -0.2261668 -0.9631978 0.1452541 -0.2075269 -0.9666114 0.1503168 -0.2347323 -0.9620186 0.1393598 -0.2150637 -0.965794 0.1448781 -0.2436073 -0.9607032 0.1330601 -0.2186163 -0.9656722 0.1403009 -0.252678 -0.9593265 0.1258833 -0.2128971 -0.9673059 0.1378191 -0.2589596 -0.9586912 0.117691 -0.2059655 -0.9693021 0.1342827 -0.2675978 -0.9576077 0.1066727 -0.2089422 -0.9698028 0.1258001 -0.2844052 -0.9542828 0.09196794 -0.2188238 -0.9691102 0.1137611 -0.3042007 -0.949656 0.07493799 -0.209688 -0.9719695 0.1063315 -0.2994622 -0.9519473 0.06417667 -0.1430078 -0.9831063 0.1142407 -0.2166891 -0.9732876 0.07587605 -0.2265374 -0.9632985 0.1440035 -0.2470607 -0.9594295 0.1358538 -0.2347383 -0.9620216 0.1393282 -0.2556957 -0.9578723 0.1307684 -0.2431713 -0.9606194 0.134455 -0.2651577 -0.9560465 0.1251661 -0.2515551 -0.959157 0.1293752 -0.2753717 -0.9539401 0.1190333 -0.2565438 -0.9583991 0.1251264 -0.2834156 -0.9523069 0.1130807 -0.263255 -0.9572441 0.1199194 -0.2941713 -0.9498959 0.1056466 -0.277724 -0.9541712 0.1114755 -0.3109618 -0.9455783 0.09583616 -0.2949782 -0.9500823 0.1016449 -0.3270947 -0.9410542 0.08617502 -0.2878745 -0.9523835 0.1004691 -0.3248591 -0.9422026 0.08198124 -0.2096529 -0.9700133 0.122964 -0.2245832 -0.9677226 0.1143481 -0.2481384 -0.9596392 0.1323632 -0.2689402 -0.9550742 0.1245172 -0.2566649 -0.9580152 0.1277892 -0.2777576 -0.9531714 0.1196461 -0.2659229 -0.9561224 0.1229438 -0.2883027 -0.9507237 0.1140446 -0.2758331 -0.95397 0.1177182 -0.2970988 -0.9486058 0.1089932 -0.2833587 -0.9523036 0.1132515 -0.3003175 -0.9479234 0.1060698 -0.29318 -0.9498951 0.1083734 -0.3155413 -0.9437742 0.09861093 -0.3091354 -0.9456639 0.1007735 -0.3205071 -0.9424036 0.09565937 -0.324105 -0.9412971 0.09442341 -0.3024072 -0.9474506 0.1043419 -0.3193858 -0.9424667 0.0987392 -0.2948808 -0.9491732 0.1100704 -0.2228503 -0.9658105 0.1324689 -0.1621425 -0.9726861 0.1661075 -0.2691934 -0.9551068 0.1237177 -0.2901526 -0.9498617 0.1165084 -0.2778352 -0.9531788 0.1194065 -0.2951207 -0.948706 0.1134056 -0.2878999 -0.9507144 0.1151348 -0.3035225 -0.9464879 0.109704 -0.2961447 -0.9486123 0.1115038 -0.3011218 -0.9472464 0.1097728 -0.29873 -0.9479355 0.1103577 -0.2722074 -0.9547812 0.1195665 -0.3111189 -0.9439422 0.1103551 -0.2997965 -0.9471381 0.1142429 -0.3152279 -0.9425516 0.11058 -0.2376276 -0.9616507 0.1369708 -0.2962056 -0.9468253 0.1256352 -0.172033 -0.9712958 0.1642836 -0.2841914 -0.9465286 0.1527054 -0.1635975 -0.9697201 0.181325 -0.1632451 -0.9697776 0.1813353 -0.08568668 -0.9744116 0.2077978 -0.2871825 -0.9495325 0.1261516 -0.3130571 -0.9423079 0.1185376 -0.2922621 -0.9484886 0.1222794 -0.3035149 -0.9453647 0.1190148 -0.3000127 -0.9464052 0.1196224 -0.2705815 -0.954184 0.1277447 -0.2960137 -0.9470934 0.1240561 -0.2128748 -0.966363 0.1443154 -0.2661975 -0.9537871 0.1393887 -0.1421879 -0.9761801 0.1638755 -0.2828555 -0.9451516 0.1633441 -0.163999 -0.9705221 0.1766104 -0.2293624 -0.9563743 0.180945 -0.1128141 -0.9755178 0.1887801 -0.1720763 -0.9644171 0.2007222 -0.07841503 -0.9768533 0.1990193 -0.1669384 -0.9580021 0.2331598 -0.07768648 -0.9739106 0.213221 -0.0892924 -0.9716292 0.219006 -0.04295605 -0.9765109 0.211143 -0.3037911 -0.9402699 0.1536349 -0.3309412 -0.9321151 0.1471034 -0.2947288 -0.9435956 0.1508718 -0.2540135 -0.9539366 0.1596313 -0.2626069 -0.9516682 0.1592658 -0.1559904 -0.9718542 0.1765406 -0.206546 -0.9614937 0.1812971 -0.09217262 -0.9781776 0.1862064 -0.1416267 -0.969685 0.1991308 -0.04904061 -0.9803605 0.1910194 -0.1596389 -0.9574486 0.2404326 -0.06499552 -0.9749847 0.2125573 -0.1197372 -0.9624798 0.2435074 -0.06453561 -0.9724452 0.2240211 -0.08925998 -0.9665367 0.2404987 -0.05287849 -0.9724718 0.2269418 -0.08956658 -0.962755 0.255109 -0.04633963 -0.9718268 0.2310963 -0.05254578 -0.9702961 0.2361451 -0.01141172 -0.9765774 0.2148634 -0.3180227 -0.919954 0.2292299 -0.2524222 -0.9380728 0.2372819 -0.246886 -0.939675 0.2367662 -0.1608223 -0.9569439 0.2416498 -0.1587297 -0.9574282 0.2411145 -0.0907315 -0.9668221 0.2387949 -0.1003474 -0.964697 0.243496 -0.05216598 -0.9713166 0.2319975 -0.05993181 -0.969612 0.2371935 -0.02227437 -0.9745338 0.2231317 -0.07555079 -0.9612655 0.2650678 -0.02041864 -0.9720503 0.2338829 -0.08036112 -0.9557298 0.2830598 -0.03055572 -0.966311 0.2555574 -0.07352209 -0.954693 0.2883676 -0.03965538 -0.9603016 0.2761313 -0.06545782 -0.9539421 0.2927625 -0.01334059 -0.9614349 0.2747091 -0.03143078 -0.9581302 0.2846028 0.05841445 -0.9634113 0.2615847 -0.2617369 -0.9004954 0.347278 -0.1417111 -0.9370487 0.3191516 -0.177407 -0.9243012 0.3379261 -0.1083927 -0.9418059 0.3182023 -0.1112599 -0.9408609 0.320003 -0.07477229 -0.9474707 0.31098 -0.07469141 -0.9474971 0.310919 -0.04924619 -0.9518687 0.3025242 -0.04682421 -0.9525427 0.3007823 -0.0219919 -0.95561 0.2938127 -0.03911995 -0.951689 0.3045618 0.01090633 -0.9574258 0.2884731 -0.04515993 -0.9470585 0.3178694 0.04893124 -0.9548906 0.292899 -0.05648177 -0.9406229 0.3347215 0.02754491 -0.942813 0.3321822 -0.02635663 -0.9390227 0.3428435 0.08880323 -0.9332997 0.3479452 0.05612134 -0.9347574 0.3508263 0.1614041 -0.9180149 0.362212 -0.1563692 -0.9153668 0.3710152 -0.07402437 -0.941654 0.3283417 -0.1217426 -0.9228789 0.3653401 -0.05828428 -0.9407413 0.334079 -0.08871656 -0.9303242 0.3558459 -0.04886096 -0.9370437 0.3457772 -0.06491935 -0.9326416 0.3549156 -0.01864111 -0.9370003 0.3488308 -0.04025763 -0.9331716 0.3571699 0.02185189 -0.9328899 0.3594983 -0.001906991 -0.9315655 0.3635687 0.1002615 -0.9230141 0.3714736 0.05037331 -0.9259835 0.3741888 0.1777545 -0.9053248 0.3857339 0.02675414 -0.922752 0.3844645 0.1633206 -0.8968458 0.411089 0.1038154 -0.9080823 0.4057203 0.2163529 -0.8772796 0.4284532 0.1809566 -0.8871502 0.4245225 0.186987 -0.8851395 0.4261032 -0.08101677 -0.9337819 0.3485509 -0.01405686 -0.9442995 0.3287872 -0.06346297 -0.9333411 0.3533369 0.03264921 -0.9425666 0.3324186 -0.05325615 -0.9303456 0.3627961 0.02219229 -0.9298588 0.3672469 -0.02281731 -0.9276608 0.3727263 0.07777839 -0.9168272 0.3916359 0.01994353 -0.9212285 0.3885104 0.1364609 -0.8966009 0.42129 0.1108477 -0.9020457 0.4171646 0.188969 -0.8782855 0.43921 0.2095575 -0.8717716 0.4428318 0.2007529 -0.8750041 0.4405293 0.1777316 -0.8821085 0.4362292 0.1772041 -0.8822928 0.4360713 0.2328947 -0.8640663 0.4462618 0.1924319 -0.8791006 0.4360644 0.1924989 -0.8790771 0.4360821 0.1398445 -0.8971914 0.4189165 -0.02175241 -0.934526 0.3552294 0.05368357 -0.9295996 0.3646404 0.03045743 -0.930387 0.3653115 0.1243769 -0.9170116 0.3789726 0.0222879 -0.9275318 0.3730792 0.1167006 -0.9092975 0.3994487 0.07800424 -0.9164398 0.3924964 0.13885 -0.9005663 0.4119476 0.1312757 -0.9025179 0.4101561 0.1243055 -0.9046075 0.4077173 0.1765919 -0.8896048 0.4212111 0.1158509 -0.9091653 0.3999963 0.1835826 -0.8900464 0.4172709 0.1121463 -0.9127283 0.3928743 0.1587428 -0.9007658 0.4042548 0.1059724 -0.9162613 0.3863098 0.1598255 -0.9032998 0.3981274 0.1053065 -0.9183006 0.381621 0.1190014 -0.9154757 0.3843734 0.07246071 -0.9270067 0.3679782 0.05081957 -0.9125728 0.4057442 0.03358054 -0.9150846 0.4018615 0.1330659 -0.9039034 0.4065122 0.05166381 -0.9171606 0.3951549 0.1153542 -0.910658 0.396731 0.06923514 -0.9177055 0.3911817 0.1263765 -0.9107999 0.3930299 0.06251436 -0.9205988 0.3854737 0.111919 -0.9150508 0.3875 0.05429738 -0.9235826 0.3795355 0.1041715 -0.918461 0.3815464 0.05225771 -0.9259678 0.3739692 0.1024503 -0.9211117 0.3755759 0.05416816 -0.9279727 0.3686904 0.1011943 -0.9236029 0.3697532 0.05787163 -0.9297549 0.3636024 0.09671342 -0.9262997 0.364164 0.0549184 -0.9318248 0.358729 0.06845694 -0.9308821 0.3588486 0.03867858 -0.93473 0.3532475 0.03377598 -0.9139826 0.4043452 0.004675567 -0.9193675 0.3933721 0.0524311 -0.9154403 0.399024 0.008274734 -0.9212998 0.3887651 0.06904923 -0.9179408 0.3906624 0.01483559 -0.9230515 0.3843901 0.06180202 -0.9214783 0.3834819 0.01554894 -0.9246233 0.3805655 0.05398845 -0.9240183 0.3785178 0.01722759 -0.9261854 0.3766749 0.05230236 -0.9259127 0.3740994 0.01855868 -0.9278455 0.3725026 0.05443459 -0.9276064 0.3695719 0.02079278 -0.9295694 0.3680604 0.05803328 -0.9292206 0.3649401 0.02341014 -0.9313845 0.3632836 0.05538016 -0.9310426 0.3606839 0.0224719 -0.9330847 0.3589541 0.03979158 -0.9330198 0.3576184 0.01704281 -0.93478 0.3548184 0.01259112 -0.933592 0.3581168 0.002155005 -0.9359934 0.3520113 0.01364737 -0.9340889 0.3567799 0.002328634 -0.9364569 0.350775 0.01559782 -0.9344775 0.3556805 0.002668976 -0.9370061 0.349303 0.01683109 -0.9350939 0.3540003 0.002742171 -0.9376809 0.3474867 0.01913154 -0.9356414 0.3524332 0.00340557 -0.9383605 0.3456417 0.02285689 -0.9361132 0.3509554 0.004296362 -0.9391915 0.343367 0.02151274 -0.9373638 0.3476871 0.004127383 -0.9400854 0.3409142 0.01587587 -0.9390004 0.3435495 0.004012882 -0.9409793 0.3384405 0.001656055 -0.9576259 0.2880102 2.73028e-5 -0.9578462 0.2872818 0.002043843 -0.9576871 0.2878044 -2.5688e-4 -0.9579881 0.286808 0.002049446 -0.957821 0.2873584 -3.54641e-4 -0.9581184 0.286372 0.002365469 -0.9579351 0.2869753 -2.86726e-4 -0.9582518 0.2859258 0.003773629 -0.9579952 0.2867593 -1.84797e-4 -0.9584506 0.2852586 0.003285646 -0.9582502 0.2859122 1.16976e-4 -0.9586054 0.2847379 0.002788484 -0.9584663 0.2851924 0.001577436 -0.9586279 0.2846579 -5.0609e-4 -0.9856995 0.1685123 -0.004593849 -0.9859749 0.166831 -5.33145e-4 -0.9858523 0.1676162 -0.004759669 -0.9861333 0.1658869 -6.0929e-4 -0.986012 0.1666734 -0.004842698 -0.986288 0.1649625 -4.69933e-4 -0.9861649 0.1657664 -0.00513935 -0.9864652 0.1638908 -3.52512e-4 -0.9863348 0.1647535 -0.004877746 -0.9866297 0.1629052 1.6541e-5 -0.9865 0.1637616 -0.004006803 -0.9868294 0.161715 -0.007552027 -0.9933592 -0.114807 -0.028297 -0.9919368 -0.123534 -0.007676959 -0.9927822 -0.1196848 -0.02841436 -0.9913147 -0.1284049 -0.007913708 -0.9921771 -0.1245875 -0.02908033 -0.9906213 -0.1335054 -0.00755465 -0.9915496 -0.1295078 -0.02716296 -0.9900574 -0.1380168 -0.007556676 -0.990896 -0.1344177 -0.02023452 -0.9897497 -0.1413723 -1.43343e-4 0.9967826 -0.08015239 -5.11433e-4 0.9969504 -0.07803773 -1.11184e-4 0.996963 -0.07787686 -9.0571e-5 0.9969594 -0.07792305 -8.20846e-5 0.9969592 -0.07792645 -6.14963e-5 0.9969567 -0.07795935 -1.24156e-5 0.9969568 -0.07795685 2.47825e-6 0.9969545 -0.07798534 3.91352e-4 0.9969547 -0.07798099 4.79622e-4 0.9969453 -0.07810199 0.002453386 0.9969486 -0.07802319 0.003100216 0.9968953 -0.07867765 0.01241111 0.996865 -0.07814121 0.01621389 0.996665 -0.07997447 0.04961079 0.9956279 -0.07914561 0.06015926 0.994861 -0.08144122 0.1159128 0.9899088 -0.08151668 0.1197487 0.9894011 -0.08213216 0.1704221 0.9819115 -0.08249974 0.1635906 0.9831627 -0.08142006 -0.005437076 -0.999706 0.02363014 -0.01849865 -0.9995775 0.02242118 -0.004365563 -0.9997894 0.02005481 -0.01992356 -0.9996303 0.01850503 -0.00509119 -0.9998607 0.01590114 -0.01974534 -0.9997029 0.01429617 -0.004630506 -0.9999237 0.01145595 -0.01796448 -0.9997871 0.0101602 -0.003318309 -0.9999682 0.007252573 -0.01331466 -0.9998908 0.006413638 -0.001544356 -0.9999909 0.003998458 -0.005766808 -0.9999772 0.00354278 -9.12265e-4 -0.9999964 0.002534985 -0.002380013 -0.9999946 0.002317488 -7.27445e-4 -0.9999979 0.001979112 -0.00184524 -0.9999967 0.001781702 -7.51241e-4 -0.9999985 0.001573145 -0.002428412 -0.9999964 0.001136779 -4.3817e-4 -0.9999996 8.73781e-4 -0.003217637 -0.9999947 -4.96201e-4 -0.03230369 -0.918861 -0.3932569 -0.06615471 -0.917981 -0.3910685 -0.0327304 -0.9156157 -0.4007201 -0.0664035 -0.9147713 -0.3984773 -0.03041547 -0.912521 -0.4078977 -0.06273019 -0.9120466 -0.4052605 -0.02206331 -0.9091497 -0.4158846 -0.04785096 -0.9105942 -0.4105222 -0.04852366 -0.8370241 -0.5450103 -0.0333243 -0.8227728 -0.5673928 -0.06614607 -0.8426692 -0.5343534 -0.04800951 -0.8370707 -0.5449843 -0.08039391 -0.8456689 -0.5276182 -0.06252861 -0.843062 -0.5341691 -0.08358532 -0.8495258 -0.5208835 -0.06602114 -0.8473522 -0.5269114 -0.08466273 -0.8538625 -0.5135671 -0.06595313 -0.8516128 -0.5200057 -5.2252e-4 0.991814 -0.1276901 -0.001394391 0.9913868 -0.1309596 -9.43258e-5 0.9918373 -0.1275104 -2.02779e-4 0.9918164 -0.1276724 -6.21074e-5 0.991833 -0.1275439 -2.78343e-5 0.9918379 -0.1275061 1.04754e-5 0.9918217 -0.1276321 1.06913e-4 0.9918334 -0.1275406 5.28589e-4 0.9917709 -0.1280246 9.83086e-4 0.991821 -0.1276332 0.003284931 0.991621 -0.12914 0.005016028 0.9917606 -0.1280078 0.01680034 0.9912438 -0.1309711 0.02326041 0.9913687 -0.1290239 0.06069827 0.9893347 -0.1324113 0.07199507 0.9887606 -0.1310319 0.116609 0.9842872 -0.1325937 0.1162581 0.9843244 -0.1326262 0.1574194 0.9787341 -0.1315253 0.1418261 0.9809536 -0.1327233 -0.3140181 -0.8617738 -0.3984201 -0.1097932 -0.5745246 -0.8110901 -0.2323034 -0.8970372 -0.3759782 -0.05464375 -0.6512854 -0.756863 -0.1585095 -0.9240207 -0.3479378 -0.02796262 -0.7537855 -0.6565254 -0.06631976 -0.9080393 -0.4136018 -0.008727431 -0.8309255 -0.5563152 -0.01168924 -0.8815106 -0.4720197 2.16817e-4 -0.8642054 -0.5031393 0.002272307 -0.8701037 -0.4928634 5.36298e-4 -0.8733404 -0.4871103 -0.1559789 -0.3290235 -0.9313508 -0.04868799 -0.122214 -0.9913089 -0.2289204 -0.5461923 -0.8057726 -0.03738182 -0.1325513 -0.990471 -0.109579 -0.3935926 -0.9127308 -0.02159708 -0.1528242 -0.9880174 -0.02092218 -0.2131422 -0.9767972 -0.007968008 -0.1666517 -0.9859837 -0.001748442 -0.16606 -0.9861142 -0.00243175 -0.1693514 -0.9855528 -0.03157132 -0.03555458 -0.998869 -0.02368205 -0.02346533 -0.9994442 -0.01154613 -0.01640892 -0.9997988 -0.007470965 -0.009270668 -0.9999292 -0.003197431 -0.009480178 -0.99995 -0.00155735 -0.005603432 -0.9999831 -0.005578458 0.02079516 -0.9997683 -0.007099509 0.01903504 -0.9997936 -0.004797577 0.01944458 -0.9997994 -0.002825617 0.02245712 -0.9997438 -0.004919946 0.02041977 -0.9997794 -0.005714178 0.01961618 -0.9997913 -0.005557477 0.01930791 -0.9997981 -0.004759609 0.02046924 -0.9997792 -0.004784703 0.01751095 -0.9998353 -0.005368649 0.01695632 -0.9998419 -0.005831718 0.01722282 -0.9998348 -0.005688607 0.0174297 -0.999832 -0.002768993 0.02036684 -0.9997888 -0.006002783 0.01563608 -0.9998598 0.01688754 -3.50639e-4 -0.9998574 0.0286377 6.82075e-4 -0.9995896 0.03386801 8.32161e-4 -0.999426 0.02906918 2.14677e-4 -0.9995774 0.004482865 7.00354e-4 -0.9999898 0.01904714 0.003166794 -0.9998136 0.0237016 0.002105474 -0.9997169 0.03465837 0.003434062 -0.9993934 0.05168366 0.004826605 -0.9986519 0.0409764 0.003623545 -0.9991536 0.05809605 0.005868494 -0.9982938 0.04140847 0.003867626 -0.9991348 0.04166972 0.004818737 -0.9991198 0.03028106 0.003041386 -0.9995369 0.002290427 0.00138843 -0.9999965 0.006763696 0.002700209 -0.9999735 0.01779639 0.004383385 -0.9998321 0.02675139 0.006472766 -0.9996213 0.05469119 0.01169681 -0.9984349 0.05220746 0.01116693 -0.9985738 0.05371093 0.0114293 -0.9984911 0.05842524 0.01243376 -0.9982144 0.02277117 0.004891753 -0.9997288 0.04425448 0.009579539 -0.9989744 0.01068007 0.001991748 -0.999941 0.02877765 0.005973696 -0.999568 0.01396489 0.001883864 -0.9999008 0.02791422 0.004589915 -0.9995998 0.007545709 0.002131998 -0.9999693 0.00132817 6.39801e-4 -0.999999 0.03117281 0.006876766 -0.9994904 0.01724171 0.003864407 -0.9998439 0.05475324 0.01139587 -0.9984349 0.05450898 0.01134544 -0.9984489 0.03387039 0.007077217 -0.9994012 0.05353164 0.01116299 -0.9985038 0.01183646 0.00267291 -0.9999264 0.0230177 0.005105674 -0.9997221 0.005205929 0.001232504 -0.9999857 0.0114367 0.002609968 -0.9999312 0.009932279 0.001525998 -0.9999495 0.01434206 0.002339482 -0.9998944 0.02134937 0.00296235 -0.9997678 0.01749396 0.002308011 -0.9998443 0.01562947 -0.006049096 -0.9998596 0.001624584 -0.002852857 -0.9999947 0.03980809 -0.01196956 -0.9991357 0.01954853 -0.007261633 -0.9997826 0.04930996 -0.01430159 -0.9986811 0.04300874 -0.01284396 -0.9989922 0.0329644 -0.008976638 -0.9994162 0.02072799 -0.006656408 -0.999763 0.01280772 -0.002834975 -0.9999141 0.005379676 -0.002310633 -0.9999829 0.00757426 -7.82259e-4 -0.9999711 0.002121508 -0.001024961 -0.9999973 0.01761257 -2.02555e-4 -0.999845 0.007230937 -7.55832e-4 -0.9999737 0.04468995 0.001143276 -0.9990003 0.01932638 -2.3159e-4 -0.9998133 0.0590552 0.004470944 -0.9982447 0.02185291 6.9498e-4 -0.9997611 0.02163761 -0.03600507 -0.9991174 0.007071971 -0.01657849 -0.9998376 0.02949523 -0.04756945 -0.9984325 0.02699744 -0.04423278 -0.9986564 0.03293877 -0.05313378 -0.998044 0.03521811 -0.05618321 -0.9977992 0.03255909 -0.04810374 -0.9983116 0.01776146 -0.03030467 -0.999383 0.02169948 -0.02270305 -0.9995068 0.004652917 -0.009851872 -0.9999407 0.01720613 -0.009711623 -0.9998048 0.002556562 -0.004624068 -0.9999861 0.03479218 -0.01285868 -0.9993119 0.01055878 -0.00626558 -0.9999247 0.06115347 -0.01999157 -0.9979282 0.03555583 -0.01313436 -0.9992814 0.07299578 -0.02155786 -0.9970993 0.04798251 -0.01573741 -0.9987243 0.02613437 -0.0266065 -0.9993043 0.02525168 -0.02556777 -0.9993542 0.02960467 -0.03333353 -0.9990057 0.03253853 -0.03681361 -0.9987923 0.03275299 -0.03960454 -0.9986785 0.03586661 -0.04332733 -0.9984169 0.0357787 -0.04395741 -0.9983926 0.03465646 -0.04265254 -0.9984887 0.03834253 -0.0370723 -0.9985768 0.02189123 -0.02243864 -0.9995086 0.03896939 -0.021757 -0.9990036 0.0164321 -0.01050174 -0.9998099 0.05124634 -0.02484571 -0.998377 0.03200525 -0.01655936 -0.9993506 0.05848437 -0.02910834 -0.997864 0.05761033 -0.02872741 -0.9979258 0.06326055 -0.03285425 -0.9974562 0.06790137 -0.03474342 -0.997087 0.03691107 0.03304737 -0.998772 0.04058533 0.03320652 -0.9986242 0.04192137 0.0296489 -0.998681 0.0459004 0.02979737 -0.9985015 0.04652625 0.02633541 -0.99857 0.05089926 0.02646929 -0.998353 0.05125069 0.02305394 -0.9984198 0.0556603 0.02315521 -0.9981814 0.05533462 0.02028805 -0.9982618 0.05901819 0.02038592 -0.9980487 0.05950427 0.01914292 -0.9980446 0.05901777 0.0191124 -0.998074 0.06339114 0.01703757 -0.9978433 0.06712412 0.01726263 -0.9975954 0.06754958 0.01451367 -0.9976104 0.07309544 0.01479858 -0.9972152 0.05534869 0.1501502 -0.9871127 0.0617336 0.1528967 -0.9863122 0.06150794 0.1471335 -0.9872024 0.06937855 0.1504452 -0.986181 0.0676912 0.1439618 -0.9872654 0.07644289 0.1475864 -0.9860907 0.07326602 0.1402657 -0.9873995 0.08393692 0.1445764 -0.9859272 0.08022141 0.1371347 -0.9872986 0.08996421 0.1410011 -0.9859134 0.08732074 0.1344106 -0.9870709 0.09637385 0.1379426 -0.9857403 0.09225982 0.132248 -0.9869137 0.0997833 0.1351306 -0.9857906 0.0970211 0.1299891 -0.9867572 0.1051456 0.1330426 -0.9855173 0.1412743 0.6796087 -0.7198429 0.146084 0.6804621 -0.7180745 0.152179 0.6761354 -0.7208902 0.1628141 0.6778731 -0.7169238 0.1612483 0.6708775 -0.7238248 0.1797674 0.6737875 -0.7167246 0.174188 0.6644108 -0.7267853 0.196734 0.6677557 -0.7179123 0.1955787 0.6588416 -0.7264137 0.2112374 0.6609912 -0.7200483 0.2212429 0.6556671 -0.7219088 0.2240843 0.6560184 -0.7207123 0.2343873 0.6537854 -0.7194631 0.2366762 0.6540304 -0.7184906 0.2410996 0.6514941 -0.7193236 0.2481369 0.6522582 -0.7162314 0.2011068 0.9459024 -0.2546069 0.1765952 0.9497991 -0.2582552 0.2241324 0.9418253 -0.2504593 0.1949089 0.9471544 -0.2547731 0.2403114 0.9388067 -0.2467643 0.2136703 0.9441728 -0.2507647 0.2609859 0.9342228 -0.2431341 0.2364844 0.9397441 -0.2468931 0.2878121 0.927497 -0.2385658 0.2580546 0.9350101 -0.2432365 0.3214179 0.9180673 -0.2320411 0.2795504 0.9299341 -0.2389023 0.3475077 0.9103766 -0.2246176 0.2969716 0.9259414 -0.2333252 0.363879 0.9057605 -0.2172328 0.3097282 0.9233333 -0.226989 -0.02861231 -0.9892185 0.1436253 -0.04441422 -0.9894692 0.1377609 -0.01444935 -0.9903631 0.1377393 -0.0623331 -0.9896238 0.1294587 -0.01189506 -0.9914705 0.1297875 -0.08663606 -0.9889009 0.1207027 -0.01776456 -0.9925236 0.1207529 -0.100425 -0.9886311 0.1119083 -0.02114701 -0.9935687 0.1112388 -0.1051575 -0.9890819 0.1032423 -0.02729076 -0.9944201 0.1019014 -0.1095386 -0.9894419 0.09490048 -0.04972726 -0.9943906 0.09335237 -0.1158676 -0.9893651 0.08792853 -0.09669518 -0.9914793 0.08728647 -0.1257601 -0.9884595 0.08445304 -0.123199 -0.9887905 0.08435297 -0.1262226 -0.9884409 0.08397895 -0.08195757 -0.9932509 0.08207213 -0.09788399 -0.9919612 0.08019846 -0.0528196 -0.9795411 0.194189 -0.03849625 -0.9787344 0.2014871 -0.0624327 -0.9781224 0.198441 -0.0919466 -0.9775524 0.1895712 -0.07222074 -0.9786677 0.1923378 -0.1206641 -0.9763059 0.17963 -0.08005964 -0.9793936 0.1854152 -0.1310807 -0.9762789 0.1723299 -0.08542799 -0.9801806 0.1787407 -0.1373935 -0.9765673 0.1656485 -0.09350675 -0.9807124 0.1716382 -0.1436991 -0.9767395 0.1591556 -0.1029902 -0.9809954 0.164442 -0.1498687 -0.9768162 0.1528704 -0.1207155 -0.9802718 0.1565083 -0.1548539 -0.976818 0.1478072 -0.1321411 -0.9797111 0.150682 -0.1554987 -0.97723 0.1443662 -0.1003144 -0.9833345 0.1516257 -0.1510578 -0.9788308 0.1381011 -0.04525804 -0.9743624 0.2203853 -0.040582 -0.9738025 0.2237451 -0.0928176 -0.9727427 0.2125011 -0.1074689 -0.9724724 0.2067558 -0.1148899 -0.9719609 0.205164 -0.1433027 -0.9701822 0.1954759 -0.1234458 -0.9720344 0.1997757 -0.1525657 -0.9698543 0.1900171 -0.1300033 -0.972173 0.1948817 -0.1595199 -0.9696994 0.1850309 -0.1368976 -0.9722179 0.1898722 -0.1647469 -0.9696723 0.1805388 -0.1423189 -0.9723193 0.1853125 -0.1698464 -0.9696223 0.1760253 -0.1461032 -0.972549 0.181114 -0.1761146 -0.9694278 0.1708612 -0.1475145 -0.9730706 0.1771249 -0.1797664 -0.9696172 0.1659113 -0.1436038 -0.9742168 0.1740109 -0.1851679 -0.9696791 0.1594847 -0.06551963 -0.9606878 0.2697892 -0.1395702 -0.9679173 0.2089412 -0.1085796 -0.9700552 0.2172631 -0.164291 -0.9676148 0.1916506 -0.1429199 -0.9698968 0.1971656 -0.1707343 -0.9675337 0.1863557 -0.1522982 -0.969699 0.1910213 -0.1747294 -0.9675458 0.1825512 -0.1591602 -0.9694902 0.1864322 -0.1819225 -0.9670855 0.1779047 -0.1643018 -0.9694299 0.1822382 -0.1870477 -0.9668622 0.1737551 -0.1692714 -0.9693433 0.1781039 -0.1912021 -0.9667258 0.1699498 -0.1752192 -0.9690524 0.1738845 -0.1972092 -0.9662553 0.1657084 -0.1784565 -0.9690856 0.1703716 -0.2026118 -0.9658777 0.161334 -0.1833896 -0.96889 0.1661947 -0.2087181 -0.9653604 0.1565763 -0.156508 -0.9562173 0.2472931 -0.2316765 -0.9562374 0.1787071 -0.1647657 -0.9659514 0.1994746 -0.2217223 -0.9601984 0.1698773 -0.1712681 -0.9679045 0.183924 -0.201466 -0.9643955 0.171327 -0.175834 -0.96816 0.1781817 -0.1992688 -0.9653013 0.1687762 -0.1831448 -0.9677447 0.1729978 -0.2049906 -0.9648702 0.1643306 -0.1883656 -0.9675222 0.1685803 -0.2089763 -0.964653 0.1605415 -0.1926649 -0.9673534 0.1646445 -0.2117148 -0.9645811 0.1573538 -0.1986418 -0.96682 0.1606258 -0.2161606 -0.9641374 0.1539922 -0.2038137 -0.9663215 0.1571081 -0.2225884 -0.9633061 0.1499861 -0.2096317 -0.9656862 0.1533135 -0.2296532 -0.9623178 0.1456158 -0.2386661 -0.9461085 0.2188997 -0.2996547 -0.940342 0.1611332 -0.2209489 -0.9580338 0.1826274 -0.2725917 -0.9494695 0.1555688 -0.2009097 -0.9640823 0.173726 -0.2375093 -0.9583063 0.1588663 -0.1994169 -0.9653847 0.1681232 -0.2308294 -0.9604171 0.1559383 -0.2055283 -0.9651656 0.1619058 -0.2332874 -0.9605678 0.1512832 -0.2098606 -0.9650992 0.1566591 -0.2326589 -0.9612079 0.1481525 -0.212877 -0.9650831 0.1526366 -0.2312704 -0.9618799 0.1459485 -0.2174491 -0.964617 0.149097 -0.2338898 -0.9616608 0.1431929 -0.223819 -0.963704 0.1455325 -0.2418878 -0.9602939 0.1390175 -0.230758 -0.9626419 0.1416737 -0.2518886 -0.9584422 0.1339426 -0.3046048 -0.9213777 0.2414109 -0.3739285 -0.9097005 0.1806169 -0.2695378 -0.9416853 0.2014403 -0.3472426 -0.9232689 0.1643087 -0.2319275 -0.9544615 0.1876509 -0.3044355 -0.9388379 0.1609424 -0.2267857 -0.9578385 0.1763911 -0.289788 -0.9446359 0.1539028 -0.2306231 -0.9588345 0.165679 -0.2856248 -0.9471586 0.1459767 -0.2309001 -0.9602354 0.1569497 -0.2752581 -0.9509174 0.1413828 -0.2302173 -0.961427 0.1505266 -0.2635485 -0.9545594 0.1391354 -0.2333416 -0.9614682 0.1453639 -0.2614111 -0.9556114 0.1359093 -0.2415905 -0.9602157 0.1400711 -0.2702026 -0.953926 0.1304452 -0.2517528 -0.9584103 0.1344254 -0.2828904 -0.951126 0.1238242 -0.3754178 -0.888549 0.2637087 -0.4281718 -0.8762825 0.2209028 -0.3433907 -0.9094052 0.2346594 -0.4177362 -0.8859508 0.2014641 -0.2956605 -0.9290058 0.2225606 -0.3928684 -0.9000587 0.1885443 -0.2817087 -0.9366126 0.2083199 -0.3820012 -0.9076964 0.1736732 -0.2789535 -0.9407391 0.1928603 -0.371811 -0.9143902 0.1601472 -0.2687305 -0.946258 0.179944 -0.352398 -0.9235785 0.1510583 -0.2572454 -0.9513599 0.1695267 -0.3308629 -0.9324734 0.1449936 -0.2558783 -0.9534465 0.1595812 -0.3220702 -0.9366039 0.1380003 -0.2653554 -0.9525574 0.1490668 -0.3262575 -0.9363714 0.1294791 -0.2789008 -0.9502524 0.1386896 -0.3305058 -0.93585 0.1222736 -0.4270246 -0.8683381 0.2522682 -0.4520213 -0.8612089 0.2323709 -0.4153237 -0.8778643 0.2384549 -0.4517318 -0.864014 0.2223023 -0.3889901 -0.8912032 0.2333319 -0.444611 -0.8698838 0.2135959 -0.3774147 -0.8980928 0.2258044 -0.4403883 -0.8743799 0.2037595 -0.3669838 -0.9044038 0.2176616 -0.4350434 -0.8794164 0.1932985 -0.3457942 -0.9143412 0.2107291 -0.4257645 -0.8862512 0.1824377 -0.3222113 -0.924713 0.2026967 -0.414608 -0.8937711 0.1710954 -0.3127928 -0.9304755 0.1907248 -0.4064496 -0.8996258 0.1596 -0.3168176 -0.9319304 0.1764433 -0.3991884 -0.9045443 0.1498275 -0.322082 -0.9324808 0.1635324 -0.3797337 -0.9135697 0.1455781 -0.4525139 -0.863101 0.2242494 -0.4637666 -0.8593713 0.2154106 -0.4520173 -0.8651105 0.217404 -0.4636173 -0.8602185 0.2123284 -0.4445168 -0.8693903 0.2157901 -0.4599573 -0.8626801 0.2102909 -0.4398238 -0.8722061 0.2140366 -0.4588168 -0.863986 0.2074019 -0.434059 -0.8755688 0.212066 -0.459716 -0.8645511 0.2030089 -0.4239994 -0.8810301 0.2097871 -0.4609326 -0.865332 0.1968289 -0.411733 -0.8876905 0.2061108 -0.4574372 -0.868619 0.1904006 -0.4029256 -0.8930065 0.2004759 -0.4367409 -0.8794715 0.1891751 -0.3944692 -0.8976548 0.1964944 -0.3990906 -0.8959317 0.1950207 -0.3746179 -0.9056444 0.1986692 -0.337573 -0.9176417 0.2097103 -0.464689 -0.8635882 0.1956524 -0.4692652 -0.861894 0.1921695 -0.4643326 -0.8644001 0.1928933 -0.4680053 -0.8627467 0.1914139 -0.4603363 -0.8666043 0.1925815 -0.4651368 -0.8643793 0.1910396 -0.4592695 -0.8673116 0.1919434 -0.4636817 -0.8652679 0.1905542 -0.4600965 -0.8670592 0.1911011 -0.4634568 -0.8655008 0.1900431 -0.4612193 -0.8666214 0.1903789 -0.4588365 -0.8677212 0.1911258 -0.4573907 -0.868438 0.1913357 -0.4276549 -0.8814896 0.2002188 -0.4365964 -0.8773452 0.1991205 -0.3253692 -0.9176529 0.2281406 -0.3979338 -0.8895127 0.224535 -0.2227664 -0.9402744 0.2574089 -0.3398362 -0.9021622 0.2657344 -0.1820228 -0.9420243 0.2818828 -0.4695211 -0.8649362 0.1773 -0.450783 -0.8721295 0.1902233 -0.4680334 -0.8631644 0.1894518 -0.439919 -0.8760758 0.1973897 -0.4650765 -0.8631359 0.1967241 -0.4479102 -0.8714451 0.1999003 -0.4635744 -0.8633021 0.1995201 -0.4485384 -0.8705943 0.2021856 -0.4632691 -0.8629304 0.2018245 -0.4352341 -0.8762488 0.2067836 -0.4585694 -0.8643721 0.2063374 -0.3975531 -0.8916543 0.2165738 -0.4289236 -0.8769634 0.2167016 -0.3007408 -0.9244331 0.2344751 -0.3270781 -0.914914 0.2365424 -0.1503898 -0.9563724 0.2504692 -0.223745 -0.9369049 0.2686026 -0.07104182 -0.9629085 0.2603082 -0.1890068 -0.9297903 0.3158582 -0.07848566 -0.9533591 0.291456 -0.4509127 -0.8713545 0.1934405 -0.3910933 -0.8928022 0.2234958 -0.4413383 -0.8667086 0.2324581 -0.3464225 -0.9080842 0.2353177 -0.4474104 -0.8564728 0.2574458 -0.3472269 -0.9042881 0.2483877 -0.4470945 -0.8525926 0.2705412 -0.3482263 -0.900465 0.2605788 -0.4345052 -0.8562322 0.2794133 -0.3142949 -0.9108732 0.2674487 -0.404879 -0.867803 0.2880814 -0.2684419 -0.9235616 0.2738117 -0.3234429 -0.9013849 0.2879062 -0.1806442 -0.945242 0.2718185 -0.1563385 -0.9518402 0.2637395 -0.06131809 -0.9647735 0.2558364 -0.3938178 -0.8877297 0.2384192 -0.3240782 -0.9085542 0.2636338 -0.3556077 -0.8935372 0.2741068 -0.2444145 -0.9342288 0.2597656 -0.3525967 -0.8866477 0.299218 -0.1707199 -0.9528316 0.2509319 -0.3496319 -0.8814324 0.3175445 -0.1371514 -0.9564726 0.2575842 -0.3181158 -0.8905496 0.3251521 -0.1133344 -0.9564987 0.2688229 -0.2856727 -0.8983034 0.3338296 -0.09937977 -0.9533934 0.2848941 -0.2155242 -0.9188641 0.3305118 -0.07715392 -0.9507254 0.3002806 -0.3343209 -0.8951122 0.2949643 -0.2665789 -0.9060332 0.3286938 -0.2744014 -0.9028241 0.3310781 -0.1872546 -0.9251666 0.3301554 -0.1933642 -0.9232497 0.3319947 -0.06929433 -0.9481618 0.3101415 -0.1460102 -0.9310449 0.3344197 -0.02327072 -0.9507137 0.309196 -0.1199506 -0.9325316 0.3405829 -0.0144124 -0.9472075 0.3202973 -0.2746024 -0.8935168 0.3552766 -0.1626291 -0.8984993 0.4077387 -0.2210727 -0.8755569 0.4295662 -0.08216965 -0.903674 0.4202636 -0.09000265 -0.9014223 0.4234825 -0.0116207 -0.9151622 0.4029182 -0.1449189 -0.9411654 0.3052968 -0.06941252 -0.9300122 0.3609146 -0.07459914 -0.9293619 0.3615542 -0.02057284 -0.9274455 0.373392 -0.06105685 -0.964639 0.2564055 -0.02011257 -0.9569482 0.2895613 -0.01782339 -0.956994 0.2895597 -0.004005849 -0.9557563 0.2941327 -0.01787066 -0.9813346 0.1914762 -0.002803087 -0.9786632 0.2054522 -0.003720104 -0.9786902 0.2053093 -7.9438e-4 -0.9783955 0.2067406 -0.00581789 -0.9957712 0.0916844 -0.005813717 -0.9957712 0.09168416 -0.003611624 -0.9957095 0.09246438 -0.005304396 -0.9958105 0.09128808 -0.002392768 -0.9957201 0.09239041 -0.003067791 -0.9957562 0.09197926 0.2673967 0.9602104 -0.08059191 0.2500184 0.9650733 -0.07825887 0.3196771 0.9442377 -0.07887858 0.2958726 0.9522249 -0.07567858 0.3635205 0.9284514 -0.07636004 0.3341398 0.9397531 -0.07221263 0.3974249 0.9147289 -0.07297062 0.3655338 0.9282854 -0.06834727 0.425494 0.9023136 -0.0691747 0.3901604 0.9184958 -0.06434535 0.4604349 0.8852881 -0.06530463 0.4209336 0.9050726 -0.06048691 0.5049238 0.8609786 -0.06138497 0.4601892 0.8860424 -0.05616807 -0.002020061 -0.9968935 0.0787357 -0.02274274 -0.9973006 0.06981688 0.01017051 -0.9977778 0.06584823 -0.01820844 -0.9978905 0.06231349 0.0128858 -0.9981862 0.05880653 -0.03094047 -0.9978985 0.05693346 0.008742213 -0.9985849 0.05245751 -0.0411427 -0.9978374 0.05126345 0.005008995 -0.9989395 0.04577136 -0.04301959 -0.9980537 0.04514664 -0.002011954 -0.9991961 0.04004073 -0.04398769 -0.9982393 0.0397945 -0.02270257 -0.9990549 0.03706806 -0.05187135 -0.9979789 0.03670907 -0.05739331 -0.9976496 0.03743404 -0.07116079 -0.9967882 0.03673672 -0.07428932 -0.9965439 0.03716939 -0.07830685 -0.9962543 0.03668141 -0.04817664 -0.9983209 0.03216278 -0.0489692 -0.9982857 0.03206104 -0.01072931 -0.99991 0.00805974 -0.002512931 -0.9999858 0.004728376 -0.009558141 -0.9998847 0.01180952 4.80674e-4 -0.9999007 0.01408964 -0.005845606 -0.9998567 0.01589584 0.003653526 -0.9997991 0.01971095 -0.004976093 -0.9998263 0.01796358 0.003287553 -0.9997586 0.02172893 -0.005133032 -0.9998063 0.01900279 0.001118779 -0.9997552 0.02209991 -0.2368042 -0.9426324 -0.2353041 -0.06480956 -0.9614343 -0.2672901 -0.1597874 -0.974552 -0.1572151 -0.02676314 -0.9861691 -0.1635675 -0.06557571 -0.9931739 -0.09646451 -0.006261885 -0.9953239 -0.09639048 -0.02475655 -0.9971781 -0.0708732 -0.00135827 -0.9974787 -0.07095414 -0.001605689 -0.9981367 -0.06099742 0.001102924 -0.9981334 -0.06106281 0.006919026 -0.9981547 -0.06032854 0.001494586 -0.9982032 -0.05990374 0.005873262 -0.9977876 -0.06622356 -0.002161204 -0.9979885 -0.06336015 0.2490476 0.9601678 -0.1267012 0.2028554 0.9705938 -0.1296052 0.2920745 0.9484853 -0.1227527 0.2295795 0.965031 -0.1265254 0.3254446 0.9381678 -0.1180132 0.252089 0.959933 -0.1223918 0.3547183 0.9281265 -0.112944 0.2765709 0.9537841 -0.117493 0.3823519 0.9177188 -0.1077001 0.299305 0.9475325 -0.1122431 0.4178811 0.9027466 -0.1020971 0.3259682 0.9393013 -0.1070412 0.4571544 0.8842363 -0.09558296 0.35255 0.9302563 -0.1016451 0.4902759 0.8671137 -0.0879969 0.3728981 0.9229488 -0.09545993 0.5461017 -0.6541648 0.5232986 0.5174307 -0.4872983 0.7034243 0.5484551 -0.5971296 0.5853489 0.5162255 -0.4326077 0.739163 0.5142561 -0.4258543 0.7444387 0.5427455 -0.3046531 0.7826965 0.5196405 -0.180809 0.8350341 -0.6367401 0.1592943 -0.7544451 -0.5881579 0.2316814 -0.774851 0.4970697 -0.2174758 0.8400155 0.4930441 -0.2003297 0.8466261 0.4823232 -0.1889359 0.8553757 0.4618089 -0.4861234 0.7419007 0.5121636 -0.1919625 0.8371612 -0.006671786 0.5709244 -0.8209756 0.5811213 -0.2274345 0.7813908 -0.5052621 -0.3612315 -0.7837232 -0.5589112 0.2056093 -0.8033325 0.1604309 -0.878484 0.4500312 0.6214066 -0.074961 0.7798941 -0.4658992 0.5006154 -0.7296042 -0.5321246 0.4584201 -0.7118248 0.9981634 -0.01520824 0.05864071 0.9963281 -0.02829557 0.08080714 0.991503 -0.05557447 0.1176164 0.9910577 -0.05702984 0.1206328 0.9615234 -0.06538969 0.2668278 0.9793174 -0.03544408 0.1992016 0.05837339 -0.7067965 -0.7050045 0.05666047 -0.7293177 -0.6818249 0.009202957 -0.1129369 -0.9935595 0.009496986 -0.1074508 -0.9941651 0.00143218 -0.01940608 -0.9998107 0.001840233 -0.01692348 -0.9998551 -3.26401e-4 -0.003940224 -0.9999922 2.04387e-4 -0.001702308 -0.9999986 -0.001221597 -1.48807e-4 -0.9999993 -8.948e-4 0.001946866 -0.9999978 -0.002522468 0.002729237 -0.9999931 -0.002544522 0.007568717 -0.9999682 -0.005396127 0.009806334 -0.9999374 -0.006555855 0.01903653 -0.9997974 -0.008432328 0.01901644 -0.9997836 -0.009117007 0.02303111 -0.9996932 -0.008746147 0.0239011 -0.9996761 -0.007529556 0.01581209 -0.9998466 -0.005912721 0.02229064 -0.9997341 -0.004959225 0.008194684 -0.9999542 -0.004783391 0.02685719 -0.999628 -0.004539787 0.01339942 -0.9999 -0.00272119 0.02612227 -0.9996551 -0.003518879 0.0131756 -0.9999071 3.04239e-4 0.01973801 -0.9998052 -0.002474188 0.007741928 -0.999967 0.002487421 0.01633232 -0.9998636 -0.001744627 0.005924403 -0.999981 0.00742352 0.02510064 -0.9996575 -1.00095e-4 0.00845474 -0.9999643 0.01735335 0.04699307 -0.9987446 0.006944596 0.02393102 -0.9996896 0.03550922 0.0895248 -0.9953514 0.03827369 0.09575062 -0.9946693 0.09079128 0.2199543 -0.971276 0.1378674 0.326827 -0.9349742 0.2219631 0.5258938 -0.8210775 0.2764974 0.6472914 -0.710326 0.166136 0.4204459 -0.8919776 0.3665574 0.8483853 -0.38194 0.8393103 -0.4377179 0.3224302 0.8880364 -0.343626 0.3054713 0.8716561 -0.2113796 0.4421926 0.6434513 -0.5349869 0.547503 0.6688813 -0.3545304 0.6533805 -0.1882743 -0.81468 0.5484974 -0.2375774 -0.8495243 0.471026 -0.4241737 -0.8363656 0.3472309 -0.441555 -0.8537193 0.2760304 -0.4549963 -0.8496828 0.266491 -0.4584885 -0.8580884 0.2312414 -0.4637479 -0.8561698 0.2278403 -0.4656172 -0.864481 0.1894024 -0.4666412 -0.8640662 0.1887746 -0.4674575 -0.8727056 0.1409555 -0.4614055 -0.8753507 0.1444513 -0.4606819 -0.8835175 0.08467125 -0.4416921 -0.8921357 0.09487849 -0.4384061 -0.8985448 0.02042871 -0.3996286 -0.9157928 0.04025691 -0.3925464 -0.9188569 -0.0401172 -0.3343604 -0.942387 -0.01048368 -0.3227646 -0.9420839 -0.09111016 -0.2484953 -0.9672672 -0.05142152 -0.2371072 -0.9652233 -0.1101105 -0.1394114 -0.9881967 -0.06349712 -0.1343251 -0.9873474 -0.08427423 -0.02662682 -0.9985938 -0.04584342 -0.02250999 -0.9978003 -0.0623539 0.07463204 -0.9966436 -0.03363966 0.07911032 -0.9950137 -0.060741 0.1442641 -0.983151 -0.112259 0.07494509 -0.9809725 -0.1790986 0.06479114 -0.9866378 -0.1494926 -0.6713226 0.3909963 -0.6296411 0.0932126 -0.9905596 -0.1005154 0.1905476 -0.9664313 -0.1723436 -0.03581398 -0.9931648 -0.1110907 0.09278732 -0.9908122 -0.09839636 -0.1582694 -0.9788484 -0.1296401 -0.03627437 -0.9933627 -0.1091551 -0.2468801 -0.9579666 -0.146117 -0.1596931 -0.9796412 -0.1216601 -0.3026103 -0.9462965 -0.1137983 -0.2520667 -0.9628251 -0.09710925 -0.3427066 -0.9376611 -0.05782592 -0.3074835 -0.9504379 -0.0460633 -0.3788966 -0.9254309 0.003880023 -0.3466303 -0.9378863 0.01472342 -0.4116128 -0.9086249 0.07054013 -0.3822023 -0.9205385 0.08081012 -0.4338741 -0.891273 0.131855 -0.4133427 -0.8998041 0.139644 -0.4436206 -0.8768402 0.1853438 -0.4335172 -0.8809832 0.1895558 -0.438822 -0.8677758 0.2332388 -0.4411566 -0.8668827 0.2321536 -0.4596669 -0.8486621 0.2616847 -0.43239 -0.8578116 0.2778456 -0.5319104 -0.7897275 0.3056174 -0.4047513 -0.8209935 0.4026736 -0.1947484 -0.7466548 0.6360659 -0.5315816 -0.6738115 0.5132243 0.1363976 -0.7302379 -0.669439 0.1343318 -0.7424113 -0.6563388 0.02610772 -0.1374105 -0.9901701 0.02703571 -0.125903 -0.9916741 0.004881024 -0.0259307 -0.9996519 0.006376504 -0.02108412 -0.9997574 0.001054406 -0.006390273 -0.9999791 0.002118647 -0.004370212 -0.9999882 -1.26303e-4 -0.001390457 -0.9999991 3.54455e-4 -4.59059e-4 -0.9999998 -0.001214206 6.86924e-4 -0.9999991 -8.09828e-4 0.0020141 -0.9999977 -0.003801047 0.005093514 -0.9999798 -0.003760218 0.008347511 -0.9999582 -0.01010757 0.01926565 -0.9997633 -0.01056897 0.02186393 -0.9997051 -0.01754862 0.0402587 -0.9990352 -0.01627576 0.0345844 -0.9992693 -0.01764553 0.04871124 -0.9986571 -0.01502639 0.03336662 -0.9993302 -0.01696872 0.05587977 -0.9982933 -0.01522982 0.04062384 -0.9990585 -0.01287961 0.05747741 -0.9982637 -0.01256042 0.03758889 -0.9992144 -0.001786053 0.05037945 -0.9987286 -0.007211744 0.02126324 -0.9997479 0.008360087 0.04188281 -0.9990876 -0.003497064 0.01361483 -0.9999012 0.01554381 0.05025267 -0.9986156 0.003060936 0.02422869 -0.9997018 0.0193153 0.05774754 -0.9981443 0.01488673 0.0485751 -0.9987087 0.02603036 0.07608199 -0.9967618 0.03276044 0.09064882 -0.995344 0.04407268 0.12496 -0.9911825 0.06976658 0.1840051 -0.9804462 0.08459639 0.2277231 -0.9700442 0.1019665 0.2680997 -0.9579799 0.1562154 0.3983788 -0.9038203 0.1616343 0.4106718 -0.8973422 0.1663753 -0.9651133 -0.2021771 0.1467697 -0.9738689 -0.1733152 0.5628829 -0.3437236 0.7516762 0.3762471 -0.5467758 0.7479802 0.3426187 -0.6278476 0.6988704 -0.1847994 -0.858963 0.4775267 -0.2489892 -0.9084677 0.3356946 -0.305915 -0.9043515 0.2975975 -0.3116348 -0.9098233 0.2740534 -0.3709966 -0.897787 0.2373604 -0.3747271 -0.9102243 0.1762707 -0.3611523 -0.9139972 0.1848735 -0.3612767 -0.925984 0.1096948 -0.3325003 -0.9344356 0.127568 -0.3301958 -0.942918 0.04331779 -0.2966315 -0.9528558 0.06384128 -0.2935068 -0.9556939 -0.02243071 -0.2617039 -0.9651436 -0.00298345 -0.2586132 -0.9623643 -0.08351248 -0.2269534 -0.9717926 -0.06412059 -0.2237514 -0.9644196 -0.1408205 -0.1903871 -0.9742687 -0.1206376 -0.1871758 -0.9648174 -0.1846418 -0.1397866 -0.9774906 -0.1580253 -0.1370514 -0.971688 -0.1924559 -0.0536313 -0.9867117 -0.1533746 -0.04940974 -0.9812355 -0.1863755 0.05376523 -0.9886828 -0.1400563 0.05310362 -0.9894512 -0.1347825 0.1418415 -0.9611767 -0.2366862 0.1875865 -0.754206 -0.6292731 0.186987 -0.7565711 -0.6266068 0.04321181 -0.1701278 -0.9844741 0.04439681 -0.1571148 -0.986582 0.008212268 -0.03512698 -0.9993491 0.01050114 -0.02929019 -0.9995158 0.001662254 -0.009371459 -0.9999548 0.003447949 -0.007030308 -0.9999694 2.76244e-4 -0.002350449 -0.9999973 9.85819e-4 -0.001591444 -0.9999983 -3.18864e-4 -9.00402e-5 -1 3.79583e-5 3.11447e-4 -1 -0.001355111 0.00231117 -0.9999964 -9.00837e-4 0.003026902 -0.9999951 -0.00372523 0.01041573 -0.9999389 -0.003532111 0.01097387 -0.9999336 -0.006690979 0.02656328 -0.9996249 -0.00707668 0.02451741 -0.9996743 -0.007356107 0.04107588 -0.9991289 -0.008365333 0.03559881 -0.9993312 -0.006009221 0.05174422 -0.9986423 -0.007734715 0.04410761 -0.9989969 -0.003030896 0.05844736 -0.998286 -0.005827188 0.04906284 -0.9987787 0.001171648 0.06367564 -0.99797 -0.002977192 0.05142241 -0.9986726 0.007500171 0.06280565 -0.9979977 2.39499e-5 0.04419821 -0.9990228 0.009802818 0.06481951 -0.9978489 0.006530761 0.05682271 -0.998363 0.01027953 0.0672903 -0.9976805 0.01028347 0.06730473 -0.9976795 0.01093208 0.0782808 -0.9968714 0.01430368 0.08739441 -0.9960711 0.01838952 0.1166764 -0.9929997 0.01850247 0.1170341 -0.9929555 0.07884126 0.2763332 -0.9578226 0.01107877 0.08112758 -0.9966422 0.2196707 0.6018743 -0.767784 0.03032261 0.1167673 -0.9926963 0.2204855 -0.9465005 -0.2356332 0.1923058 -0.9605542 -0.2008839 0.6360942 0.2868405 0.7163147 -0.8172233 -0.2154514 -0.5345344 0.39036 -0.7807201 0.48795 -0.5030611 -0.8464038 0.174729 -0.2691748 -0.9630914 2.35858e-5 -0.09761983 -0.5550746 -0.8260524 -0.8172222 -0.215453 -0.5345352 -0.835546 -0.0229842 -0.5489398 0.5590077 -0.515052 0.6497939 0.6769667 -0.4858 0.5529146 0.5590022 -0.5150571 0.6497945 0.9032881 -0.3382036 0.2639868 0.4874141 -0.4244721 0.7630538 0.5799763 -0.3992679 0.7100793 0.3559157 -0.5903168 0.7244654 0.4392999 -0.7456811 0.5009745 0.8695285 -0.3058853 0.3877556 0.6669508 0.2694315 0.6946823 0.7452138 -0.265241 0.6118037 -0.1188148 -0.9870657 0.1076307 0.3878984 0.8889915 -0.2433702 0.404703 0.9055659 -0.1271458 0.4004274 0.9111043 -0.0977078 0.005157768 -0.9340878 0.3570061 0.02939635 -0.9125102 0.4079964 0.007327437 -0.9171352 0.3985089 0.01950651 -0.9152573 0.4023975 -0.04489064 -0.9376425 0.3446903 0.009068787 -0.9367597 0.3498558 -0.04490035 -0.9376428 0.3446885 -0.0962069 -0.9288639 0.3577097 -0.03069239 -0.9552332 0.2942577 -0.03069102 -0.9552355 0.2942504 0.7719478 0.2618046 -0.5792711 -0.7248072 0.2043684 0.6579424 0.9709165 0.23221 0.05830818 -0.6528772 0.7530159 0.08196747 0.4058707 0.9078236 -0.1054769 0.4028532 0.9034301 -0.146709 0.3780867 0.8486367 -0.3699545 0.3389187 0.7641748 -0.5487905 0.3433084 0.7737518 -0.5323981 0.3695539 0.8158999 -0.4446768 0.1553168 0.3310765 -0.9307337 0.1376328 0.2954676 -0.9453867 0.03556692 0.06650626 -0.997152 0.03269851 0.06117022 -0.9975916 0.01261335 0.01641768 -0.9997857 0.01115322 0.01430046 -0.9998356 0.0100218 0.01184582 -0.9998797 0.00801593 0.00948137 -0.9999229 0.009212851 0.01196867 -0.999886 0.006606876 0.008826255 -0.9999393 0.007214963 0.01006639 -0.9999234 0.004374027 0.006031095 -0.9999723 0.004606246 0.006522834 -0.9999682 0.001549482 0.001587152 -0.9999976 0.001598536 0.001702964 -0.9999973 -0.001816213 -0.004351615 -0.999989 -0.001195251 -0.002442061 -0.9999964 -0.004377961 -0.009162664 -0.9999485 -0.003901422 -0.008143365 -0.9999593 -0.004896819 -0.00956434 -0.9999424 -0.004910051 -0.009612679 -0.9999418 -0.006596803 -0.008245885 -0.9999443 -0.004910051 -0.009611248 -0.9999418 0.01447796 -0.011101 -0.9998336 0.006926953 -0.01198935 -0.9999042 -0.08516162 -0.6982831 -0.7107378 -0.07921051 -0.7002906 -0.7094497 -0.05874645 -0.3983641 -0.9153441 -0.05953043 -0.3974671 -0.9156835 -0.0338003 -0.2035865 -0.9784734 -0.03712385 -0.2005067 -0.9789888 -0.03714728 -0.2005324 -0.9789826 -0.03371888 -0.1968896 -0.9798457 -3.09881e-4 -0.06007665 -0.9981938 -0.01005142 -0.05355274 -0.9985145 0.02139729 -0.01594132 -0.999644 0.01246142 -0.01049816 -0.9998673 0.01247334 -0.01049041 -0.9998672 0.01545661 -0.008899807 -0.999841 0.01524609 -0.01552772 -0.9997632 0.01381582 -0.01491415 -0.9997934 0.01328825 -0.02136874 -0.9996834 0.009466469 -0.02056062 -0.9997438 0.01328903 -0.02137124 -0.9996833 0.001007556 -0.02441978 -0.9997014 8.16042e-4 -0.02442437 -0.9997014 -0.001466989 -0.02521562 -0.999681 -0.001001358 -0.01461338 -0.9998927 0.007394313 -0.01377725 -0.9998778 -9.41409e-4 -0.01461607 -0.9998928 0.002475798 -0.9349778 0.3546978 -7.64918e-4 -0.9351382 0.3542823 0.006108462 -0.9343177 0.3563891 3.09442e-4 -0.9357872 0.3525653 0.002342879 -0.9353601 0.3536891 -0.001122415 -0.957821 0.2873633 3.82071e-4 -0.9576893 0.287804 0.001175582 -0.957666 0.2878792 -1.70301e-4 -0.9577177 0.2877098 -7.07995e-4 -0.9855293 0.1695044 -3.18051e-4 -0.9855121 0.169605 -0.00409168 -0.9858109 0.1678098 -4.74386e-4 -0.9856815 0.1686174 -0.007864534 -0.9939119 -0.1098973 -0.02884501 -0.9930834 -0.1138131 -0.007651627 -0.9933558 -0.1148298 -0.02891206 -0.9930813 -0.113815 -0.03322356 -0.9250739 -0.3783314 -0.03213965 -0.9251806 -0.3781641 -0.06695121 -0.9178719 -0.391189 -0.04056733 -0.9223778 -0.3841531 -0.06666201 -0.8559994 -0.512661 -0.08709526 -0.8560647 -0.509478 -0.2151373 -0.5752058 -0.7892112 -0.2015632 -0.5583333 -0.8047586 -0.2214472 -0.6215283 -0.7514412 -0.311172 -0.777746 -0.5461531 -0.1552678 -0.5425189 -0.8255698 -0.2443856 -0.6927201 -0.6785386 -0.09776937 -0.1864994 -0.9775782 -0.1169359 -0.2274871 -0.9667346 -0.07769024 -0.1557744 -0.9847328 -0.09696239 -0.1957061 -0.9758574 -0.04210627 -0.04771858 -0.997973 -0.03974056 -0.04083311 -0.9983754 -0.03577119 -0.03970754 -0.9985709 -0.04185312 -0.04388147 -0.9981597 -0.04012471 -0.04129123 -0.9983412 -0.04114234 -0.0428676 -0.9982334 -0.02148872 0.005543112 -0.9997537 -0.009553372 0.017448 -0.9998021 -0.01773464 0.008189201 -0.9998093 -0.0133742 0.01329934 -0.9998222 -0.006063342 0.0194993 -0.9997916 -0.009612679 0.0171799 -0.9998062 -0.005970537 0.01687133 -0.9998399 -0.006542325 0.01664638 -0.9998401 -0.007707178 0.007662832 -0.999941 0.002478241 0.01765608 -0.9998411 -0.006501317 0.008147954 -0.9999457 -0.004625916 0.01088845 -0.9999301 0.0189132 -0.008285343 -0.9997868 -0.00388813 -0.002244591 -0.99999 0.001094579 0.006905794 -0.9999756 -0.007020354 -0.004464268 -0.9999654 -0.004438221 -5.65854e-4 -0.99999 0.02308309 -0.002358794 -0.9997308 0.02770435 -0.001342475 -0.9996153 0.02464365 -0.002129793 -0.9996941 0.02811956 -0.001269042 -0.9996038 0.02465271 -0.001355469 -0.9996951 0.02433365 -0.001451551 -0.9997029 -0.004550397 -0.009315133 -0.9999463 0.0250324 3.58967e-4 -0.9996866 0.04098719 0.001527905 -0.9991586 0.02504163 3.58642e-4 -0.9996864 0.04133129 0.00252664 -0.9991424 0.02363806 8.98066e-4 -0.9997202 0.02970069 0.001974701 -0.999557 0.007038652 0.001949787 -0.9999734 0.001404106 0.002602756 -0.9999957 0.02621841 0.002814054 -0.9996523 0.02378278 0.002616822 -0.9997138 0.02733713 0.003277003 -0.999621 0.0229063 0.002938687 -0.9997334 0.01942908 0.002102732 -0.9998091 0.0196101 0.002463161 -0.9998047 0.01750236 0.002337515 -0.9998442 0.0195989 0.002464175 -0.9998049 0.01595687 0.001919567 -0.9998708 0.01647007 0.002899706 -0.9998602 0.02340477 0.003201305 -0.9997211 0.01647627 0.002884984 -0.9998601 0.009436607 0.001830101 -0.9999539 0.02087765 0.001892924 -0.9997802 0.01088464 0.003775358 -0.9999337 0.03184992 -0.00952661 -0.9994474 0.01821047 -0.002028942 -0.9998322 0.03015798 -0.01285082 -0.9994626 0.04302567 -0.01281243 -0.9989919 0.07651746 0.01243269 -0.9969907 0.08107757 0.01141566 -0.9966424 0.07926726 0.01143145 -0.9967879 0.05644375 0.01716876 -0.9982582 0.1159939 0.1312063 -0.9845458 0.118008 0.1308676 -0.9843515 0.2789516 0.6471046 -0.7095363 0.2816846 0.6461377 -0.7093377 0.3939313 0.8936842 -0.214818 0.3490485 0.9123662 -0.2138999 -0.007843315 -0.9676845 0.2520427 -0.07111579 -0.9627965 0.2607021 -0.007843852 -0.9676868 0.2520337 -0.08904623 -0.9376187 0.3360683 -0.03402876 -0.9622433 0.2700552 -0.02764213 -0.9526703 0.3027463 -0.08189266 -0.9496622 0.3023829 -0.02766984 -0.9526726 0.3027367 -0.01472938 -0.955101 0.295914 0.02178192 -0.9481003 0.3172246 -0.00541085 -0.9483502 0.3171793 -0.1142189 -0.9208498 0.3728134 -0.04167813 -0.9415274 0.3343492 -0.09719777 -0.9250903 0.3670975 -0.0140978 -0.9309554 0.364861 -0.0442323 -0.9246633 0.3782083 0.03433591 -0.9175523 0.3961299 0.02329105 -0.9183011 0.395197 -7.63401e-4 -0.9174624 0.3978219 -0.03134268 -0.9081346 0.4175036 -0.009770929 -0.9154905 0.4022212 -0.02012139 -0.9093433 0.4155598 -0.0129618 -0.9127334 0.4083503 -0.009643733 -0.9119703 0.4101431 0.0352776 -0.9116479 0.4094554 -0.001002192 -0.9278457 0.3729631 -0.01026511 -0.9281108 0.3721626 -0.0010311 -0.9278469 0.3729598 -1.22791e-4 -0.9278938 0.3728449 -5.8515e-4 -0.9557564 0.2941589 -1.57063e-4 -0.9557721 0.2941085 -6.94641e-4 -0.9784016 0.2067121 -4.95466e-4 -0.9783853 0.20679 -6.29922e-4 -0.9783937 0.2067493 -7.76992e-4 -0.9784045 0.2066983 -0.002614438 -0.9957465 0.09209883 -0.002384424 -0.9957322 0.09225994 -0.002460479 -0.9957348 0.09222865 -0.002757608 -0.9957535 0.09201931 -0.002726614 -0.9957497 0.09206002 -0.002277851 -0.9957353 0.09222918 0.5179862 0.8535115 -0.0566442 0.496164 0.8667511 -0.05063623 0.5334024 0.8443294 -0.05088979 -0.00475198 -0.9998032 0.01926368 -0.004750251 -0.9997969 0.01958435 -0.003086745 -0.9997828 0.02061378 -0.02221703 -0.9997504 0.002375543 -0.01127785 -0.9998291 0.01465666 -0.05961406 -0.9974498 -0.03924578 -0.04200077 -0.9990295 -0.01326674 -0.1485518 -0.9825477 -0.1119491 -0.3020734 -0.8720507 -0.3850705 -0.29045 -0.8756162 -0.3859214 -0.1489724 -0.946423 -0.2865151 -0.2853861 -0.8801665 -0.3792909 0.5250427 0.8465496 -0.08765894 0.4037473 0.9107285 -0.08695864 0.5228875 -0.2164052 0.8244741 0.4519396 -0.2010204 0.8691039 -0.3427015 -0.3470915 -0.8729738 0.7401359 -0.0218665 -0.6721018 0.9940571 0.04003751 -0.1012304 -0.03907757 0.1377179 -0.9897004 0.6283962 0.04932564 -0.776328 -0.01864558 -0.007212221 -0.9998002 -0.122974 -0.003693997 -0.9924031 -0.02056914 0.006317973 -0.9997685 -0.6964497 0.07476443 -0.7137003 -0.0205608 0.006317973 -0.9997687 -0.9937607 0.00528866 -0.1114081 -0.05677872 0.2658283 -0.962347 -0.8768789 -0.1443179 0.4585366 0.06015312 -0.9406965 0.3338741 0.9999525 0.008953988 -0.00385338 0.999949 0.008047401 0.00610429 0.9999516 0.008988797 -0.003999173 0.9999672 0.005345165 0.006093561 0.9999749 0.00663799 -0.002537012 0.9999997 -8.23723e-4 0 0.9999724 0.004261732 0.006088793 0.9999749 0.006633639 -0.002511739 0.9999873 0.004830837 -0.001449286 0.9999938 0.003377676 -0.001015007 0.9999739 0.003902256 0.006087243 0.9999942 0.003372251 -5.77009e-4 0.9999785 0.002476751 0.0060817 0.9999976 0.002164959 2.48116e-4 0.9987782 0 -0.04941868 0.99998 0.001793563 0.006078481 -0.7525767 0 0.6585046 0.9999799 0.001793861 0.006078422 0.9999976 0.002164602 2.39329e-4 0.9999986 4.75561e-5 0.001651823 0.9999919 -7.13571e-6 0.004036605 0.9999841 0.001706302 0.005387961 0.9999994 0.001080989 4.47012e-4 1 4.98325e-6 0 0.9999994 9.60149e-4 7.65397e-4 1 -1.64046e-6 0 0.9999987 2.46012e-5 0.001652359 0.9999991 2.87319e-4 0.001425743 1 -1.77006e-6 0 0.9999986 4.06531e-5 0.001644372 0.9999986 4.02378e-5 0.001651227 0.9999986 3.64907e-5 0.001651108 0.9999965 0.001317143 0.002312719 0.9999918 2.18887e-5 0.004053592 -0.9999672 1.82905e-5 -0.00811249 1 -7.38704e-6 0 1 4.50101e-5 0 0.9946324 0.01399707 0.102522 0.9999672 -3.03744e-5 0.008099615 0.9999666 1.65487e-5 0.008185148 0.9999954 -0.003044247 2.68633e-4 1 1.40543e-6 0 0.9999915 -0.002006828 0.003613293 -1 5.53234e-7 0 -1 0 0 -1 5.67086e-5 0 -1 -2.19552e-7 0 -1 -3.04314e-7 0 -1 0 0 -1 9.03969e-7 0 -1 -6.32253e-7 0 -1 2.67614e-7 0 -1 -5.95968e-7 0 -1 1.03398e-5 0 -1 0 0 -1 2.39789e-6 0 -0.6110162 0.2271704 -0.7583225 -0.7896494 0.0176739 -0.6133037 -0.5462286 0.3662254 -0.7533348 -0.7452912 0.1701958 -0.6446507 -0.4817775 0.47648 -0.73543 -0.6878117 0.305402 -0.6585171 -0.5982013 0.2577606 -0.7587588 -0.5414443 0.3260763 -0.7749274 -0.6134775 0.2210775 -0.758136 -0.5593448 0.2917323 -0.7759032 -0.6261638 0.1884177 -0.756583 -0.574791 0.2603446 -0.775781 -0.8917185 -0.04560673 -0.4502869 -0.8127122 -0.09015727 -0.5756479 -0.812707 -0.09016466 -0.5756542 -0.5809443 0.468021 -0.6659281 -0.79658 0.2466412 -0.5519317 -0.7795476 -0.2818812 -0.5593287 -0.7795452 -0.2818711 -0.5593371 -0.7795504 -0.2818796 -0.5593255 -0.5809383 0.4680345 -0.6659238 0.8141095 0.07346433 0.5760458 0.894159 0.1694083 0.4144642 0 0.8479983 -0.529999 0.891953 0.4459765 0.07432937 0 -0.3162278 0.9486834 -0.8126994 -0.09011876 -0.575672 -0.1611782 0.9131802 -0.3743309 -0.8540712 -0.1820275 -0.4872664 -0.612577 -0.6921572 0.3816648 -0.6125808 -0.6921617 0.3816503 -0.6125687 -0.6921695 0.3816556 -0.3210265 -0.7969595 0.5116617 -0.8524331 0.04312527 -0.5210547 -0.841789 0.05741018 -0.5367453 -0.8417911 0.05741196 -0.5367417 -0.8417893 0.05741196 -0.5367445 -0.9920295 -0.04563826 -0.1174509 -0.9920298 -0.04563415 -0.1174501 -0.8842 -0.04168379 -0.4652451 -0.8841884 -0.0416696 -0.4652684 -0.4814717 0.1477566 -0.8639174 0.8581808 0.1938771 0.4753288 0.7976446 0.1510681 0.5839021 + + + + + + + + + + + + + + +

0 0 1 0 2 0 1 1 3 1 2 1 1 2 0 2 4 2 0 3 5 3 4 3 6 4 7 4 8 4 9 5 10 5 11 5 12 6 13 6 14 6 12 7 15 7 13 7 16 8 17 8 18 8 19 9 17 9 16 9 20 10 21 10 22 10 22 11 23 11 20 11 24 12 20 12 23 12 23 13 25 13 24 13 26 14 24 14 25 14 27 15 17 15 19 15 27 16 28 16 17 16 28 17 18 17 17 17 14 18 28 18 27 18 27 19 29 19 14 19 29 20 30 20 14 20 31 21 14 21 30 21 30 22 32 22 31 22 33 23 34 23 35 23 36 24 37 24 35 24 13 25 35 25 38 25 35 26 37 26 38 26 35 27 13 27 33 27 13 28 39 28 33 28 15 29 39 29 13 29 38 30 40 30 13 30 13 31 28 31 14 31 18 32 28 32 13 32 13 33 41 33 18 33 13 34 40 34 41 34 14 35 42 35 12 35 42 36 14 36 31 36 32 37 43 37 31 37 44 38 36 38 45 38 44 39 37 39 36 39 44 40 38 40 37 40 44 41 40 41 38 41 44 42 41 42 40 42 44 43 18 43 41 43 18 44 44 44 16 44 34 45 33 45 46 45 26 46 46 46 33 46 33 47 39 47 26 47 24 48 26 48 15 48 26 49 39 49 15 49 15 50 12 50 24 50 20 51 24 51 42 51 24 52 12 52 42 52 42 53 31 53 20 53 21 54 20 54 31 54 31 55 43 55 21 55 43 56 47 56 48 56 21 57 43 57 48 57 3 58 49 58 9 58 11 59 3 59 9 59 50 60 49 60 3 60 51 61 50 61 3 61 52 62 51 62 3 62 52 63 3 63 53 63 54 64 55 64 56 64 54 64 56 64 57 64 54 65 57 65 4 65 54 64 58 64 55 64 59 64 55 64 58 64 60 66 6 66 8 66 60 67 8 67 61 67 60 68 61 68 62 68 63 69 60 69 62 69 64 70 60 70 63 70 63 71 65 71 64 71 63 72 62 72 66 72 65 73 63 73 66 73 67 74 64 74 65 74 48 75 67 75 65 75 65 76 68 76 48 76 48 77 68 77 21 77 69 78 19 78 16 78 16 79 70 79 69 79 70 80 71 80 69 80 58 81 54 81 72 81 72 82 73 82 74 82 72 83 74 83 47 83 75 84 72 84 47 84 43 85 32 85 75 85 47 86 43 86 75 86 76 87 59 87 77 87 78 88 59 88 76 88 4 89 57 89 1 89 1 90 78 90 3 90 1 91 57 91 56 91 1 92 56 92 55 92 1 93 55 93 78 93 59 94 78 94 55 94 3 95 78 95 53 95 65 96 79 96 80 96 65 97 80 97 68 97 81 98 79 98 65 98 65 99 66 99 81 99 81 100 66 100 62 100 22 101 21 101 68 101 22 102 68 102 80 102 10 103 9 103 82 103 9 104 49 104 83 104 84 105 83 105 49 105 49 106 50 106 84 106 85 107 84 107 50 107 50 108 51 108 85 108 86 109 85 109 51 109 51 110 52 110 86 110 87 111 86 111 52 111 88 112 73 112 72 112 53 113 89 113 90 113 53 114 91 114 89 114 92 115 89 115 91 115 71 116 89 116 92 116 71 117 70 117 89 117 70 118 16 118 89 118 44 119 89 119 16 119 93 120 89 120 44 120 94 121 89 121 93 121 95 122 89 122 94 122 90 123 89 123 95 123 71 124 92 124 69 124 69 125 27 125 19 125 69 126 29 126 27 126 69 127 96 127 29 127 30 128 29 128 96 128 75 129 30 129 96 129 97 130 75 130 96 130 97 131 96 131 98 131 92 132 96 132 69 132 92 133 98 133 96 133 95 134 52 134 90 134 97 135 98 135 99 135 52 136 95 136 87 136 76 137 92 137 91 137 91 138 53 138 76 138 76 139 53 139 78 139 92 140 76 140 98 140 76 141 77 141 98 141 72 142 75 142 97 142 72 143 97 143 99 143 72 144 99 144 98 144 72 145 98 145 100 145 100 64 98 64 77 64 59 146 100 146 77 146 90 147 52 147 53 147 75 148 32 148 30 148 58 149 100 149 59 149 58 150 72 150 100 150 88 151 72 151 54 151 101 152 102 152 103 152 101 153 103 153 104 153 105 154 101 154 104 154 106 155 102 155 101 155 101 156 107 156 106 156 106 157 107 157 108 157 109 158 106 158 108 158 109 159 110 159 106 159 108 160 111 160 109 160 112 161 109 161 111 161 113 162 112 162 111 162 113 163 114 163 115 163 112 164 113 164 115 164 116 165 117 165 118 165 119 166 118 166 117 166 117 167 120 167 119 167 121 168 119 168 120 168 120 169 122 169 121 169 10 170 121 170 122 170 123 171 124 171 11 171 11 172 122 172 123 172 122 173 11 173 10 173 125 174 126 174 127 174 124 175 125 175 127 175 124 176 127 176 128 176 124 177 128 177 129 177 124 178 129 178 130 178 2 179 124 179 130 179 124 180 2 180 11 180 11 181 2 181 3 181 131 182 132 182 133 182 134 183 135 183 8 183 7 184 134 184 8 184 136 185 137 185 138 185 139 186 137 186 136 186 136 187 140 187 139 187 141 188 139 188 140 188 140 189 142 189 141 189 143 190 141 190 142 190 144 191 145 191 143 191 142 192 144 192 143 192 146 193 145 193 144 193 144 194 147 194 146 194 146 195 147 195 61 195 146 196 61 196 8 196 135 197 146 197 8 197 137 198 148 198 138 198 148 199 149 199 138 199 150 200 106 200 110 200 151 201 152 201 150 201 153 202 102 202 106 202 150 203 153 203 106 203 150 204 152 204 154 204 150 205 154 205 155 205 150 206 155 206 156 206 150 207 156 207 157 207 153 208 150 208 157 208 102 209 153 209 158 209 103 210 102 210 158 210 159 211 160 211 161 211 159 212 161 212 162 212 163 213 159 213 162 213 160 214 159 214 164 214 0 215 160 215 164 215 0 216 130 216 129 216 0 217 129 217 128 217 0 218 128 218 165 218 0 219 165 219 160 219 2 220 130 220 0 220 0 221 164 221 5 221 142 222 140 222 166 222 144 223 142 223 166 223 119 224 167 224 118 224 168 225 167 225 119 225 119 226 121 226 168 226 116 227 118 227 169 227 131 64 114 64 113 64 131 228 113 228 111 228 133 64 114 64 131 64 103 229 170 229 171 229 104 230 103 230 171 230 171 231 172 231 104 231 104 232 172 232 173 232 105 233 104 233 173 233 173 234 172 234 174 234 175 235 173 235 174 235 174 236 176 236 175 236 176 237 177 237 178 237 179 238 178 238 177 238 175 239 176 239 178 239 175 240 178 240 180 240 175 241 180 241 181 241 175 242 181 242 182 242 183 243 175 243 182 243 182 244 184 244 183 244 185 245 179 245 177 245 177 246 186 246 185 246 183 247 184 247 187 247 183 248 187 248 188 248 189 249 183 249 188 249 188 250 190 250 189 250 191 251 189 251 190 251 190 252 192 252 191 252 193 253 191 253 192 253 192 254 194 254 193 254 193 255 194 255 195 255 193 256 195 256 196 256 197 257 193 257 196 257 196 258 198 258 197 258 199 259 200 259 201 259 202 260 199 260 201 260 197 261 198 261 200 261 200 262 199 262 203 262 203 263 197 263 200 263 199 264 204 264 203 264 203 265 204 265 205 265 206 266 203 266 205 266 205 267 207 267 127 267 127 268 207 268 208 268 128 269 127 269 208 269 190 270 188 270 192 270 194 270 192 270 188 270 188 270 209 270 194 270 210 271 194 271 209 271 209 270 211 270 210 270 212 270 210 270 211 270 211 270 213 270 212 270 214 272 212 272 213 272 213 270 215 270 214 270 216 273 214 273 215 273 215 270 217 270 216 270 218 270 216 270 217 270 219 182 220 182 221 182 222 274 221 274 220 274 220 182 223 182 222 182 224 182 222 182 223 182 223 182 225 182 224 182 224 182 225 182 226 182 227 182 224 182 226 182 226 275 228 275 227 275 229 182 227 182 228 182 200 276 230 276 201 276 231 277 201 277 230 277 230 278 232 278 231 278 233 279 231 279 232 279 232 280 234 280 233 280 235 281 233 281 234 281 234 282 236 282 235 282 237 283 235 283 236 283 236 284 238 284 237 284 239 285 237 285 238 285 238 286 240 286 239 286 241 287 239 287 240 287 240 288 242 288 241 288 243 289 241 289 242 289 242 290 244 290 243 290 245 291 243 291 244 291 178 292 246 292 180 292 247 293 180 293 246 293 246 294 248 294 247 294 249 294 247 294 248 294 248 295 250 295 249 295 251 296 249 296 250 296 250 297 252 297 251 297 253 298 251 298 252 298 252 299 254 299 253 299 255 300 253 300 254 300 254 301 256 301 255 301 257 302 255 302 256 302 256 303 258 303 257 303 259 303 257 303 258 303 258 304 260 304 259 304 261 305 259 305 260 305 247 306 181 306 180 306 249 307 184 307 182 307 249 308 182 308 181 308 247 309 249 309 181 309 249 310 251 310 184 310 262 311 188 311 187 311 262 312 187 312 184 312 184 313 251 313 253 313 262 314 184 314 253 314 209 315 188 315 262 315 253 316 255 316 262 316 262 317 255 317 257 317 263 318 262 318 257 318 263 319 211 319 209 319 262 320 263 320 209 320 213 321 211 321 263 321 257 322 259 322 263 322 264 323 215 323 213 323 263 324 264 324 213 324 263 325 259 325 261 325 263 326 261 326 265 326 264 327 263 327 265 327 215 328 264 328 266 328 217 329 215 329 266 329 200 330 198 330 230 330 232 331 230 331 198 331 198 332 196 332 232 332 232 333 196 333 267 333 234 334 232 334 267 334 268 335 236 335 234 335 267 336 268 336 234 336 195 337 194 337 268 337 268 338 267 338 195 338 194 339 210 339 268 339 238 340 236 340 268 340 268 341 210 341 212 341 269 342 268 342 212 342 269 343 240 343 238 343 268 344 269 344 238 344 212 345 214 345 269 345 242 346 240 346 269 346 269 347 214 347 216 347 216 348 218 348 269 348 269 349 218 349 270 349 271 350 269 350 270 350 269 351 271 351 242 351 242 352 271 352 272 352 244 353 242 353 272 353 178 354 273 354 246 354 248 355 246 355 273 355 273 356 274 356 248 356 250 357 248 357 274 357 274 358 275 358 250 358 252 359 250 359 275 359 276 360 254 360 252 360 275 361 276 361 252 361 277 362 221 362 276 362 278 363 277 363 276 363 279 364 278 364 276 364 276 365 275 365 279 365 221 366 222 366 276 366 256 367 254 367 276 367 276 368 222 368 224 368 276 369 224 369 227 369 276 370 227 370 229 370 276 371 229 371 280 371 281 372 276 372 280 372 281 373 258 373 256 373 276 374 281 374 256 374 258 375 281 375 282 375 260 376 258 376 282 376 103 377 158 377 170 377 283 378 170 378 158 378 158 379 153 379 283 379 284 380 283 380 153 380 153 381 157 381 284 381 285 381 284 381 157 381 157 382 156 382 285 382 286 383 285 383 156 383 156 384 155 384 286 384 287 385 286 385 155 385 208 386 288 386 128 386 165 387 128 387 288 387 288 388 289 388 165 388 160 389 165 389 289 389 289 390 290 390 160 390 161 391 160 391 290 391 290 392 291 392 161 392 162 393 161 393 291 393 291 394 292 394 162 394 163 395 162 395 292 395 199 396 293 396 204 396 288 397 208 397 207 397 294 398 205 398 204 398 205 399 294 399 207 399 207 400 295 400 288 400 295 401 207 401 294 401 204 402 296 402 294 402 296 403 204 403 293 403 297 404 294 404 296 404 294 405 297 405 295 405 289 406 288 406 295 406 295 407 298 407 289 407 298 408 295 408 297 408 293 409 299 409 296 409 300 410 297 410 296 410 297 411 300 411 298 411 290 412 289 412 298 412 301 413 298 413 300 413 298 414 301 414 290 414 299 415 302 415 296 415 296 416 303 416 300 416 303 417 296 417 302 417 291 418 290 418 301 418 300 419 304 419 301 419 304 420 300 420 303 420 305 421 303 421 302 421 303 422 305 422 304 422 292 423 291 423 301 423 304 424 306 424 301 424 301 425 306 425 292 425 307 426 308 426 309 426 310 427 177 427 176 427 310 428 176 428 311 428 309 429 310 429 311 429 310 430 309 430 308 430 186 431 177 431 310 431 308 432 312 432 310 432 313 433 310 433 312 433 313 434 314 434 315 434 315 435 186 435 310 435 316 436 313 436 312 436 312 437 317 437 316 437 318 438 319 438 316 438 317 439 318 439 316 439 320 440 319 440 318 440 318 441 321 441 320 441 320 442 293 442 202 442 320 443 321 443 302 443 320 444 302 444 299 444 293 445 320 445 299 445 199 446 202 446 293 446 170 447 283 447 171 447 322 448 171 448 283 448 171 449 322 449 172 449 311 450 176 450 174 450 174 451 323 451 311 451 323 452 174 452 172 452 172 453 324 453 323 453 324 454 172 454 322 454 322 455 325 455 324 455 325 456 322 456 283 456 283 457 284 457 325 457 309 458 311 458 323 458 323 459 326 459 309 459 326 460 323 460 324 460 327 461 324 461 325 461 324 462 327 462 326 462 328 463 325 463 284 463 325 464 328 464 327 464 284 465 285 465 328 465 307 466 309 466 326 466 329 467 326 467 327 467 326 468 329 468 307 468 330 469 327 469 328 469 327 470 330 470 329 470 331 471 328 471 285 471 328 472 331 472 330 472 332 473 307 473 329 473 332 474 329 474 330 474 285 475 286 475 331 475 333 476 330 476 331 476 330 477 333 477 332 477 286 478 287 478 331 478 334 479 331 479 287 479 331 480 334 480 333 480 335 481 315 481 314 481 336 482 315 482 335 482 335 483 337 483 336 483 338 484 336 484 337 484 337 485 339 485 338 485 338 486 339 486 219 486 338 487 219 487 221 487 173 182 175 182 183 182 173 182 183 182 189 182 173 182 189 182 191 182 173 182 191 182 193 182 173 488 193 488 197 488 173 489 197 489 203 489 206 182 173 182 203 182 206 490 125 490 124 490 206 491 124 491 123 491 206 492 123 492 122 492 206 493 122 493 120 493 206 494 120 494 117 494 206 495 117 495 116 495 116 496 169 496 132 496 206 497 116 497 132 497 206 498 132 498 131 498 206 499 131 499 111 499 206 500 111 500 108 500 206 501 108 501 107 501 206 502 107 502 101 502 206 503 101 503 105 503 173 504 206 504 105 504 126 505 125 505 206 505 196 270 195 270 267 270 314 506 313 506 316 506 316 507 319 507 314 507 310 508 313 508 315 508 221 509 277 509 338 509 315 510 336 510 338 510 277 511 315 511 338 511 277 512 278 512 315 512 278 513 279 513 315 513 186 514 315 514 279 514 186 515 279 515 275 515 186 516 275 516 274 516 185 517 186 517 274 517 185 518 274 518 273 518 179 519 185 519 273 519 178 520 179 520 273 520 201 521 340 521 341 521 341 522 340 522 342 522 342 523 340 523 343 523 342 524 343 524 344 524 344 525 343 525 345 525 344 526 345 526 346 526 344 527 346 527 347 527 348 528 347 528 346 528 349 529 347 529 348 529 349 530 350 530 347 530 347 531 350 531 351 531 352 532 350 532 349 532 320 533 347 533 319 533 350 534 352 534 219 534 350 535 219 535 339 535 337 536 350 536 339 536 350 537 337 537 351 537 335 538 351 538 337 538 351 539 335 539 347 539 335 540 314 540 347 540 347 541 320 541 344 541 319 542 347 542 314 542 344 543 320 543 202 543 245 544 353 544 243 544 243 545 353 545 354 545 355 546 241 546 354 546 354 547 241 547 243 547 354 548 356 548 355 548 355 549 356 549 228 549 355 550 228 550 226 550 355 551 226 551 357 551 355 552 357 552 358 552 241 553 355 553 239 553 352 554 355 554 358 554 355 555 346 555 345 555 346 556 355 556 348 556 348 557 355 557 349 557 349 558 355 558 352 558 345 559 237 559 355 559 355 560 237 560 239 560 237 561 345 561 235 561 343 562 235 562 345 562 235 563 343 563 233 563 340 564 233 564 343 564 233 565 340 565 231 565 201 566 231 566 340 566 223 182 357 182 225 182 357 182 223 182 358 182 220 182 358 182 223 182 358 182 220 182 352 182 219 182 352 182 220 182 202 567 342 567 344 567 342 568 202 568 341 568 341 569 202 569 201 569 225 182 357 182 226 182 127 570 206 570 205 570 126 571 206 571 127 571 169 182 167 182 132 182 169 572 118 572 167 572 359 270 218 270 360 270 361 270 359 270 360 270 362 270 363 270 360 270 364 270 365 270 361 270 360 573 366 573 362 573 367 574 361 574 365 574 368 575 362 575 366 575 365 576 369 576 367 576 366 577 370 577 368 577 371 578 367 578 369 578 372 270 368 270 370 270 369 270 373 270 371 270 374 270 371 270 373 270 370 270 375 270 372 270 373 270 376 270 374 270 377 579 372 579 375 579 374 580 376 580 378 580 379 270 374 270 378 270 380 270 381 270 377 270 375 270 380 270 377 270 382 270 381 270 380 270 378 270 382 270 379 270 383 270 379 270 382 270 384 270 383 270 382 270 380 581 384 581 382 581 385 582 245 582 386 582 387 583 388 583 261 583 389 584 366 584 266 584 390 585 389 585 264 585 390 586 261 586 388 586 391 587 390 587 388 587 361 270 218 270 359 270 218 588 361 588 392 588 392 589 393 589 270 589 393 590 394 590 271 590 394 591 386 591 272 591 385 592 395 592 245 592 395 593 396 593 354 593 396 594 397 594 356 594 398 595 399 595 229 595 399 596 400 596 281 596 400 597 387 597 282 597 401 598 376 598 373 598 378 599 376 599 401 599 382 600 378 600 401 600 381 601 382 601 401 601 377 602 381 602 401 602 372 270 377 270 401 270 401 603 368 603 372 603 362 604 368 604 401 604 363 270 362 270 401 270 364 270 363 270 401 270 365 605 364 605 401 605 369 606 365 606 401 606 373 270 369 270 401 270 402 607 366 607 389 607 389 608 390 608 402 608 403 609 402 609 390 609 390 610 391 610 403 610 392 611 404 611 393 611 394 612 393 612 404 612 404 613 405 613 394 613 394 614 405 614 386 614 406 615 370 615 366 615 402 616 406 616 366 616 403 617 391 617 406 617 402 618 403 618 406 618 391 619 407 619 406 619 375 620 370 620 406 620 408 621 406 621 407 621 408 622 380 622 375 622 406 623 408 623 375 623 407 624 409 624 408 624 384 625 380 625 408 625 408 626 409 626 410 626 411 627 408 627 410 627 408 628 411 628 384 628 383 629 384 629 411 629 410 630 412 630 411 630 413 631 411 631 412 631 411 632 413 632 383 632 379 633 383 633 413 633 412 634 414 634 413 634 415 635 374 635 379 635 413 636 415 636 379 636 415 637 413 637 414 637 371 638 374 638 415 638 414 639 386 639 415 639 404 640 367 640 371 640 415 641 404 641 371 641 415 642 386 642 405 642 415 643 405 643 404 643 392 644 367 644 404 644 367 645 392 645 361 645 229 182 397 182 398 182 398 182 416 182 417 182 397 182 416 182 398 182 391 646 388 646 387 646 386 647 414 647 418 647 418 648 385 648 386 648 409 649 407 649 419 649 419 650 420 650 409 650 410 651 409 651 420 651 420 652 421 652 410 652 421 653 422 653 412 653 412 654 410 654 421 654 422 655 418 655 414 655 414 656 412 656 422 656 407 657 391 657 387 657 387 658 419 658 407 658 400 659 419 659 387 659 399 660 419 660 400 660 417 661 420 661 419 661 417 662 421 662 420 662 417 663 416 663 421 663 416 664 422 664 421 664 418 665 422 665 416 665 395 666 385 666 418 666 395 667 418 667 396 667 360 668 364 668 361 668 360 270 363 270 364 270 360 669 266 669 366 669 399 670 417 670 419 670 398 671 417 671 399 671 397 672 396 672 416 672 396 673 418 673 416 673 112 674 423 674 110 674 109 675 112 675 110 675 424 182 133 182 132 182 425 676 136 676 138 676 149 677 426 677 138 677 150 678 110 678 423 678 150 679 427 679 151 679 136 680 425 680 428 680 428 681 429 681 136 681 115 682 114 682 133 682 244 683 386 683 245 683 228 182 397 182 229 182 260 583 387 583 261 583 266 684 264 684 389 684 264 685 265 685 390 685 390 686 265 686 261 686 270 687 218 687 392 687 271 688 270 688 393 688 272 689 271 689 394 689 244 690 272 690 386 690 395 691 353 691 245 691 354 692 353 692 395 692 356 693 354 693 396 693 228 694 356 694 397 694 399 695 280 695 229 695 281 696 280 696 399 696 282 697 281 697 400 697 260 698 282 698 387 698 360 270 218 270 217 270 217 699 266 699 360 699 430 700 431 700 432 700 138 701 433 701 434 701 425 702 138 702 434 702 435 703 436 703 437 703 435 704 438 704 436 704 439 705 440 705 441 705 441 706 440 706 442 706 442 707 440 707 443 707 443 708 440 708 444 708 444 709 440 709 445 709 445 710 440 710 446 710 443 711 447 711 442 711 448 712 449 712 447 712 447 713 449 713 450 713 436 714 450 714 449 714 451 715 450 715 436 715 452 716 451 716 436 716 451 717 453 717 450 717 442 718 447 718 450 718 442 719 450 719 453 719 454 720 455 720 456 720 445 721 455 721 454 721 436 722 438 722 452 722 424 723 115 723 133 723 457 724 115 724 424 724 458 725 457 725 424 725 459 726 458 726 424 726 424 727 446 727 459 727 440 728 459 728 446 728 455 729 445 729 446 729 460 730 461 730 462 730 432 731 461 731 460 731 460 732 463 732 432 732 464 733 432 733 463 733 463 734 465 734 464 734 465 735 434 735 464 735 465 736 466 736 434 736 425 737 434 737 466 737 467 738 425 738 466 738 468 739 469 739 470 739 469 740 471 740 470 740 472 741 468 741 470 741 470 742 473 742 472 742 474 743 472 743 473 743 473 744 475 744 474 744 476 745 474 745 475 745 475 746 477 746 476 746 478 747 476 747 477 747 477 748 479 748 478 748 480 749 478 749 479 749 479 750 462 750 480 750 480 751 462 751 461 751 428 752 425 752 467 752 481 753 482 753 483 753 482 754 481 754 484 754 485 755 486 755 482 755 487 756 488 756 489 756 490 757 489 757 488 757 490 758 437 758 489 758 490 759 491 759 437 759 490 760 492 760 491 760 490 761 493 761 492 761 494 762 493 762 490 762 495 763 490 763 496 763 490 764 488 764 496 764 490 765 495 765 494 765 495 766 497 766 494 766 496 767 498 767 495 767 499 768 497 768 495 768 495 769 482 769 499 769 482 770 500 770 499 770 482 771 486 771 500 771 495 772 483 772 482 772 495 773 498 773 483 773 489 774 448 774 487 774 449 775 448 775 489 775 436 776 449 776 489 776 489 777 437 777 436 777 437 778 491 778 501 778 501 779 435 779 437 779 502 780 439 780 441 780 503 781 441 781 442 781 441 782 503 782 502 782 442 783 453 783 503 783 503 784 504 784 502 784 502 785 504 785 505 785 427 786 506 786 151 786 427 787 150 787 423 787 427 788 439 788 502 788 427 789 507 789 439 789 427 790 423 790 507 790 427 791 502 791 506 791 502 792 505 792 506 792 508 793 509 793 510 793 511 794 510 794 509 794 511 795 451 795 452 795 511 796 509 796 451 796 452 797 512 797 511 797 452 798 513 798 512 798 452 799 514 799 513 799 515 800 514 800 438 800 514 801 452 801 438 801 438 802 435 802 515 802 516 803 515 803 435 803 435 804 501 804 516 804 491 805 516 805 501 805 448 806 447 806 444 806 443 807 444 807 447 807 517 808 518 808 483 808 483 809 498 809 517 809 498 810 456 810 517 810 498 811 454 811 456 811 445 812 454 812 488 812 454 813 496 813 488 813 454 814 498 814 496 814 445 815 488 815 444 815 488 816 487 816 444 816 448 817 444 817 487 817 519 818 477 818 475 818 519 819 479 819 477 819 462 270 479 270 519 270 519 820 460 820 462 820 519 821 463 821 460 821 519 270 465 270 463 270 519 822 466 822 465 822 519 823 467 823 466 823 481 824 483 824 518 824 432 825 431 825 461 825 433 826 432 826 464 826 464 827 434 827 433 827 432 828 433 828 430 828 433 829 520 829 430 829 521 830 520 830 433 830 521 831 433 831 138 831 426 832 521 832 138 832 509 833 504 833 451 833 505 834 504 834 509 834 509 583 508 583 505 583 446 835 424 835 132 835 439 836 459 836 440 836 459 837 439 837 507 837 459 838 507 838 458 838 507 839 457 839 458 839 112 840 457 840 507 840 457 841 112 841 115 841 507 842 423 842 112 842 461 843 431 843 480 843 513 844 514 844 522 844 431 845 522 845 514 845 514 846 515 846 431 846 515 847 480 847 431 847 478 848 480 848 491 848 480 849 516 849 491 849 480 850 515 850 516 850 491 851 492 851 478 851 476 852 478 852 492 852 492 853 493 853 476 853 474 854 476 854 494 854 476 855 493 855 494 855 494 856 497 856 474 856 472 857 474 857 497 857 497 858 499 858 472 858 468 859 472 859 500 859 472 860 499 860 500 860 500 861 486 861 468 861 469 862 468 862 486 862 523 863 446 863 132 863 446 864 523 864 455 864 83 865 82 865 9 865 82 866 524 866 10 866 525 867 61 867 526 867 62 868 61 868 525 868 525 869 527 869 62 869 527 870 81 870 62 870 147 871 526 871 61 871 147 872 528 872 526 872 22 270 80 270 519 270 519 873 525 873 526 873 519 874 527 874 525 874 519 875 81 875 527 875 519 876 79 876 81 876 519 877 80 877 79 877 526 878 528 878 519 878 528 879 529 879 519 879 166 880 519 880 529 880 455 881 87 881 95 881 455 882 86 882 87 882 455 883 85 883 86 883 455 884 84 884 85 884 455 885 83 885 84 885 455 886 82 886 83 886 455 887 524 887 82 887 455 888 168 888 524 888 530 889 531 889 34 889 46 890 530 890 34 890 532 891 533 891 531 891 530 892 532 892 531 892 534 893 533 893 532 893 535 894 536 894 534 894 532 895 535 895 534 895 535 896 537 896 536 896 455 897 95 897 94 897 455 898 94 898 93 898 538 899 539 899 540 899 540 900 541 900 538 900 538 901 541 901 484 901 542 902 538 902 484 902 543 903 45 903 36 903 36 904 544 904 543 904 544 905 540 905 543 905 539 906 543 906 540 906 545 907 533 907 534 907 546 908 545 908 534 908 546 909 541 909 540 909 546 910 540 910 545 910 534 911 536 911 546 911 546 912 536 912 547 912 546 913 485 913 541 913 545 914 544 914 36 914 35 915 545 915 36 915 35 916 34 916 531 916 35 917 531 917 533 917 35 918 533 918 545 918 544 919 545 919 540 919 537 920 535 920 548 920 530 921 549 921 550 921 532 922 530 922 550 922 530 923 46 923 549 923 551 924 549 924 46 924 46 925 26 925 551 925 25 926 551 926 26 926 93 927 44 927 455 927 455 928 44 928 45 928 535 929 552 929 548 929 532 930 552 930 535 930 532 931 550 931 552 931 519 932 25 932 23 932 519 933 23 933 22 933 140 934 136 934 429 934 429 935 166 935 140 935 166 936 529 936 144 936 147 937 144 937 529 937 529 938 528 938 147 938 524 939 168 939 121 939 121 940 10 940 524 940 548 941 553 941 537 941 469 942 537 942 553 942 471 943 469 943 553 943 485 944 482 944 484 944 485 945 554 945 486 945 485 946 547 946 554 946 485 947 484 947 541 947 485 948 546 948 547 948 428 270 467 270 519 270 429 270 428 270 519 270 519 949 166 949 429 949 518 950 555 950 481 950 484 951 481 951 555 951 555 952 542 952 484 952 554 953 469 953 486 953 537 954 469 954 547 954 469 955 554 955 547 955 537 956 547 956 536 956 523 182 132 182 167 182 523 957 167 957 168 957 523 958 168 958 455 958 556 959 557 959 558 959 557 960 559 960 558 960 557 961 556 961 560 961 561 962 562 962 563 962 564 963 565 963 566 963 567 964 568 964 569 964 567 965 570 965 568 965 571 966 572 966 573 966 574 967 572 967 571 967 575 968 576 968 577 968 577 969 578 969 575 969 579 970 575 970 578 970 578 971 580 971 579 971 581 972 579 972 580 972 582 973 572 973 574 973 582 974 583 974 572 974 583 975 573 975 572 975 569 976 583 976 582 976 582 977 584 977 569 977 584 978 585 978 569 978 586 979 569 979 585 979 585 980 587 980 586 980 588 981 589 981 590 981 591 982 592 982 590 982 568 983 590 983 593 983 590 984 592 984 593 984 590 985 568 985 588 985 568 986 594 986 588 986 570 987 594 987 568 987 593 988 595 988 568 988 568 989 583 989 569 989 573 990 583 990 568 990 568 991 596 991 573 991 568 992 595 992 596 992 569 993 597 993 567 993 597 994 569 994 586 994 587 995 598 995 586 995 599 996 591 996 600 996 599 997 592 997 591 997 599 998 593 998 592 998 599 999 595 999 593 999 599 1000 596 1000 595 1000 599 1001 573 1001 596 1001 573 1002 599 1002 571 1002 589 1003 588 1003 601 1003 581 1004 601 1004 588 1004 588 1005 594 1005 581 1005 579 1006 581 1006 570 1006 581 1007 594 1007 570 1007 570 1008 567 1008 579 1008 575 1009 579 1009 597 1009 579 1010 567 1010 597 1010 597 1011 586 1011 575 1011 576 1012 575 1012 586 1012 586 1013 598 1013 576 1013 598 1014 602 1014 603 1014 576 1015 598 1015 603 1015 559 1016 604 1016 564 1016 566 1017 559 1017 564 1017 605 1018 604 1018 559 1018 606 1019 605 1019 559 1019 607 1020 606 1020 559 1020 607 1021 559 1021 608 1021 609 64 610 64 611 64 609 64 611 64 612 64 609 1022 612 1022 560 1022 609 1023 613 1023 610 1023 614 1024 610 1024 613 1024 615 1025 561 1025 563 1025 615 1026 563 1026 616 1026 615 1027 616 1027 617 1027 618 1028 615 1028 617 1028 619 1029 615 1029 618 1029 618 1030 620 1030 619 1030 618 1031 617 1031 621 1031 620 1032 618 1032 621 1032 622 1033 619 1033 620 1033 603 1034 622 1034 620 1034 620 1035 623 1035 603 1035 603 1036 623 1036 576 1036 624 1037 574 1037 571 1037 571 1038 625 1038 624 1038 625 1039 626 1039 624 1039 613 1040 609 1040 627 1040 627 1041 628 1041 629 1041 627 1042 629 1042 602 1042 630 1043 627 1043 602 1043 598 1044 587 1044 630 1044 602 1045 598 1045 630 1045 631 1046 632 1046 614 1046 633 1047 614 1047 632 1047 560 1048 612 1048 557 1048 557 1049 633 1049 559 1049 557 1050 612 1050 611 1050 557 1051 611 1051 610 1051 557 1052 610 1052 633 1052 614 1053 633 1053 610 1053 559 1054 633 1054 608 1054 620 1055 634 1055 635 1055 620 1056 635 1056 623 1056 636 1057 634 1057 620 1057 620 1058 621 1058 636 1058 636 1059 621 1059 617 1059 577 1060 576 1060 623 1060 577 1061 623 1061 635 1061 565 1062 564 1062 637 1062 564 1063 604 1063 638 1063 639 1064 638 1064 604 1064 604 1065 605 1065 639 1065 640 1066 639 1066 605 1066 605 1067 606 1067 640 1067 641 1068 640 1068 606 1068 606 1069 607 1069 641 1069 642 1070 641 1070 607 1070 643 1071 628 1071 627 1071 608 1072 644 1072 645 1072 608 1073 646 1073 644 1073 647 1074 644 1074 646 1074 626 1075 644 1075 647 1075 626 1076 625 1076 644 1076 625 1077 571 1077 644 1077 599 1078 644 1078 571 1078 648 120 644 120 599 120 649 1079 644 1079 648 1079 650 1080 644 1080 649 1080 645 1081 644 1081 650 1081 626 1082 647 1082 624 1082 624 1083 582 1083 574 1083 624 1084 584 1084 582 1084 624 1085 651 1085 584 1085 585 1086 584 1086 651 1086 630 1087 585 1087 651 1087 652 1088 630 1088 651 1088 652 1089 651 1089 653 1089 647 1090 651 1090 624 1090 647 1091 653 1091 651 1091 650 1092 607 1092 645 1092 607 1093 650 1093 642 1093 632 1094 647 1094 646 1094 646 1095 608 1095 632 1095 632 1096 608 1096 633 1096 647 1097 632 1097 653 1097 632 1098 631 1098 653 1098 627 1099 630 1099 652 1099 627 1100 652 1100 653 1100 627 1101 653 1101 654 1101 654 1102 653 1102 631 1102 654 1103 631 1103 614 1103 645 1104 607 1104 608 1104 630 1105 587 1105 585 1105 613 1106 654 1106 614 1106 613 1107 627 1107 654 1107 643 1108 627 1108 609 1108 655 1109 656 1109 657 1109 655 1110 657 1110 658 1110 659 1111 655 1111 658 1111 660 1112 656 1112 655 1112 655 1113 661 1113 660 1113 660 1114 661 1114 662 1114 663 1115 660 1115 662 1115 663 1116 664 1116 660 1116 662 1117 665 1117 663 1117 666 1118 663 1118 665 1118 667 1119 666 1119 665 1119 667 1120 668 1120 669 1120 666 1121 667 1121 669 1121 670 1122 671 1122 672 1122 673 1123 672 1123 671 1123 671 1124 674 1124 673 1124 675 1125 673 1125 674 1125 674 1126 676 1126 675 1126 565 1127 675 1127 676 1127 677 1128 678 1128 566 1128 566 1129 676 1129 677 1129 676 1130 566 1130 565 1130 679 1131 680 1131 681 1131 678 1132 679 1132 681 1132 678 1133 681 1133 682 1133 678 1134 682 1134 683 1134 678 1135 683 1135 684 1135 558 1136 678 1136 684 1136 678 1137 558 1137 566 1137 566 1138 558 1138 559 1138 685 182 686 182 687 182 688 1139 689 1139 563 1139 562 1140 688 1140 563 1140 690 1141 691 1141 692 1141 693 1142 691 1142 690 1142 690 1143 694 1143 693 1143 695 1144 693 1144 694 1144 694 1145 696 1145 695 1145 697 1146 695 1146 696 1146 698 1147 699 1147 697 1147 696 1148 698 1148 697 1148 700 1149 699 1149 698 1149 698 1150 701 1150 700 1150 700 1151 701 1151 616 1151 700 1152 616 1152 563 1152 689 1153 700 1153 563 1153 691 1154 702 1154 692 1154 702 1155 703 1155 692 1155 704 1156 660 1156 664 1156 705 1157 706 1157 704 1157 707 1158 656 1158 660 1158 704 1159 707 1159 660 1159 704 1160 706 1160 708 1160 704 1161 708 1161 709 1161 704 1162 709 1162 710 1162 704 1163 710 1163 711 1163 707 1164 704 1164 711 1164 656 1165 707 1165 712 1165 656 1166 712 1166 713 1166 657 1167 656 1167 713 1167 714 1168 715 1168 716 1168 714 1169 716 1169 717 1169 718 1170 714 1170 717 1170 715 1171 714 1171 719 1171 556 1172 715 1172 719 1172 556 1173 684 1173 683 1173 556 1174 683 1174 682 1174 556 1175 682 1175 720 1175 556 1176 720 1176 715 1176 558 1177 684 1177 556 1177 556 1178 719 1178 560 1178 696 1179 694 1179 721 1179 698 1180 696 1180 721 1180 673 1181 722 1181 672 1181 723 1182 722 1182 673 1182 673 1183 675 1183 723 1183 670 1184 672 1184 724 1184 685 64 668 64 667 64 685 1185 667 1185 665 1185 687 64 668 64 685 64 657 1186 725 1186 726 1186 658 1187 657 1187 726 1187 726 1188 727 1188 658 1188 658 1189 727 1189 728 1189 659 1190 658 1190 728 1190 728 1191 727 1191 729 1191 730 1192 728 1192 729 1192 729 1193 731 1193 730 1193 731 1194 732 1194 733 1194 734 1195 733 1195 732 1195 730 1196 731 1196 733 1196 730 240 733 240 735 240 730 1197 735 1197 736 1197 730 1198 736 1198 737 1198 738 1199 730 1199 737 1199 737 1200 739 1200 738 1200 740 245 734 245 732 245 732 1201 741 1201 740 1201 738 1202 739 1202 742 1202 738 1203 742 1203 743 1203 744 1204 738 1204 743 1204 743 1205 745 1205 744 1205 746 1206 744 1206 745 1206 745 1207 747 1207 746 1207 748 1208 746 1208 747 1208 747 1209 749 1209 748 1209 748 1210 749 1210 750 1210 748 1211 750 1211 751 1211 752 1212 748 1212 751 1212 751 1213 753 1213 752 1213 754 1214 755 1214 756 1214 757 1215 754 1215 756 1215 752 1216 753 1216 755 1216 755 1217 754 1217 758 1217 758 1218 752 1218 755 1218 754 1219 759 1219 758 1219 758 1220 759 1220 760 1220 761 1221 758 1221 760 1221 760 1222 762 1222 681 1222 681 1223 762 1223 763 1223 682 1224 681 1224 763 1224 745 270 743 270 747 270 749 270 747 270 743 270 743 270 764 270 749 270 765 1225 749 1225 764 1225 764 1226 766 1226 765 1226 767 270 765 270 766 270 766 270 768 270 767 270 769 272 767 272 768 272 768 270 770 270 769 270 771 1227 769 1227 770 1227 770 270 772 270 771 270 773 270 771 270 772 270 774 182 775 182 776 182 777 1228 776 1228 775 1228 775 182 778 182 777 182 779 182 777 182 778 182 778 182 780 182 779 182 779 182 780 182 781 182 782 182 779 182 781 182 781 1229 783 1229 782 1229 784 182 782 182 783 182 755 1230 785 1230 756 1230 786 1231 756 1231 785 1231 785 1232 787 1232 786 1232 788 1233 786 1233 787 1233 787 1234 789 1234 788 1234 790 1235 788 1235 789 1235 789 1236 791 1236 790 1236 792 1237 790 1237 791 1237 791 1238 793 1238 792 1238 794 1239 792 1239 793 1239 793 1240 795 1240 794 1240 796 1241 794 1241 795 1241 795 1242 797 1242 796 1242 798 1243 796 1243 797 1243 797 1244 799 1244 798 1244 800 1245 798 1245 799 1245 733 292 801 292 735 292 802 293 735 293 801 293 801 1246 803 1246 802 1246 804 1247 802 1247 803 1247 803 1248 805 1248 804 1248 806 1249 804 1249 805 1249 805 1250 807 1250 806 1250 808 1251 806 1251 807 1251 807 299 809 299 808 299 810 1252 808 1252 809 1252 809 301 811 301 810 301 812 302 810 302 811 302 811 1253 813 1253 812 1253 814 1253 812 1253 813 1253 813 1254 815 1254 814 1254 816 1255 814 1255 815 1255 802 1256 736 1256 735 1256 804 1257 739 1257 737 1257 804 1258 737 1258 736 1258 802 1259 804 1259 736 1259 804 1260 806 1260 739 1260 817 1261 743 1261 742 1261 817 1262 742 1262 739 1262 739 1263 806 1263 808 1263 817 1264 739 1264 808 1264 764 1265 743 1265 817 1265 808 1266 810 1266 817 1266 817 1267 810 1267 812 1267 818 1268 817 1268 812 1268 818 1269 766 1269 764 1269 817 1270 818 1270 764 1270 768 1271 766 1271 818 1271 812 1272 814 1272 818 1272 819 1273 770 1273 768 1273 818 1274 819 1274 768 1274 818 1275 814 1275 816 1275 818 1276 816 1276 820 1276 819 1277 818 1277 820 1277 770 1278 819 1278 821 1278 772 1279 770 1279 821 1279 755 330 753 330 785 330 787 1280 785 1280 753 1280 753 1281 751 1281 787 1281 787 1282 751 1282 822 1282 789 1283 787 1283 822 1283 823 1284 791 1284 789 1284 822 1285 823 1285 789 1285 750 1286 749 1286 823 1286 823 1287 822 1287 750 1287 749 1288 765 1288 823 1288 793 1289 791 1289 823 1289 823 1290 765 1290 767 1290 824 1291 823 1291 767 1291 824 1292 795 1292 793 1292 823 1293 824 1293 793 1293 767 1294 769 1294 824 1294 797 1295 795 1295 824 1295 824 347 769 347 771 347 771 1296 773 1296 824 1296 824 1297 773 1297 825 1297 826 1298 824 1298 825 1298 824 1299 826 1299 797 1299 797 352 826 352 827 352 799 1300 797 1300 827 1300 733 1301 828 1301 801 1301 803 1302 801 1302 828 1302 828 1303 829 1303 803 1303 805 357 803 357 829 357 829 1304 830 1304 805 1304 807 1305 805 1305 830 1305 831 1306 809 1306 807 1306 830 1307 831 1307 807 1307 832 1308 776 1308 831 1308 833 1309 832 1309 831 1309 834 1310 833 1310 831 1310 831 1311 830 1311 834 1311 776 1312 777 1312 831 1312 811 1313 809 1313 831 1313 831 1314 777 1314 779 1314 831 1315 779 1315 782 1315 831 1316 782 1316 784 1316 831 1317 784 1317 835 1317 836 1318 831 1318 835 1318 836 1319 813 1319 811 1319 831 1320 836 1320 811 1320 813 1321 836 1321 837 1321 815 1322 813 1322 837 1322 657 1323 713 1323 725 1323 838 1324 725 1324 713 1324 713 1325 712 1325 838 1325 839 1326 838 1326 712 1326 712 1327 711 1327 839 1327 840 1328 839 1328 711 1328 711 1329 710 1329 840 1329 841 1330 840 1330 710 1330 710 1331 709 1331 841 1331 842 1332 841 1332 709 1332 763 1333 843 1333 682 1333 720 1334 682 1334 843 1334 843 1335 844 1335 720 1335 715 1336 720 1336 844 1336 844 1337 845 1337 715 1337 716 1338 715 1338 845 1338 845 1339 846 1339 716 1339 717 1340 716 1340 846 1340 846 1341 847 1341 717 1341 718 1342 717 1342 847 1342 754 1343 848 1343 759 1343 843 1344 763 1344 762 1344 849 1345 760 1345 759 1345 760 1346 849 1346 762 1346 762 1347 850 1347 843 1347 850 1348 762 1348 849 1348 759 1349 851 1349 849 1349 851 1350 759 1350 848 1350 852 1351 849 1351 851 1351 849 1352 852 1352 850 1352 844 1353 843 1353 850 1353 850 1354 853 1354 844 1354 853 1355 850 1355 852 1355 848 1356 854 1356 851 1356 855 1357 852 1357 851 1357 852 1358 855 1358 853 1358 845 1359 844 1359 853 1359 856 1360 853 1360 855 1360 853 1361 856 1361 845 1361 854 1362 857 1362 851 1362 851 1363 858 1363 855 1363 858 1364 851 1364 857 1364 857 1365 859 1365 858 1365 846 1366 845 1366 856 1366 855 1367 860 1367 856 1367 860 1368 855 1368 858 1368 861 1369 858 1369 859 1369 858 1370 861 1370 860 1370 847 1371 846 1371 856 1371 860 1372 862 1372 856 1372 856 1373 862 1373 847 1373 863 1374 864 1374 865 1374 866 1375 732 1375 731 1375 866 1376 731 1376 867 1376 865 1377 866 1377 867 1377 866 1378 865 1378 864 1378 741 1379 732 1379 866 1379 864 1380 868 1380 866 1380 869 1381 866 1381 868 1381 869 1382 870 1382 871 1382 871 435 741 435 866 435 872 1383 869 1383 868 1383 868 1384 873 1384 872 1384 874 1385 875 1385 872 1385 873 1386 874 1386 872 1386 876 1387 875 1387 874 1387 874 1388 877 1388 876 1388 876 1389 848 1389 757 1389 876 1390 877 1390 857 1390 876 1391 857 1391 854 1391 848 1392 876 1392 854 1392 754 1393 757 1393 848 1393 725 1394 838 1394 726 1394 878 1395 726 1395 838 1395 726 1396 878 1396 727 1396 867 1397 731 1397 729 1397 729 1398 879 1398 867 1398 879 1399 729 1399 727 1399 727 1400 880 1400 879 1400 880 1401 727 1401 878 1401 878 1402 881 1402 880 1402 881 1403 878 1403 838 1403 838 1404 839 1404 881 1404 865 1405 867 1405 879 1405 879 1406 882 1406 865 1406 882 1407 879 1407 880 1407 883 1408 880 1408 881 1408 880 1409 883 1409 882 1409 884 1410 881 1410 839 1410 881 1411 884 1411 883 1411 839 1412 840 1412 884 1412 863 1413 865 1413 882 1413 885 1414 882 1414 883 1414 882 1415 885 1415 863 1415 886 1416 883 1416 884 1416 883 1417 886 1417 885 1417 887 1418 884 1418 840 1418 884 1419 887 1419 886 1419 888 1420 863 1420 885 1420 888 1421 885 1421 886 1421 840 1422 841 1422 887 1422 889 1423 886 1423 887 1423 886 1424 889 1424 888 1424 841 1425 842 1425 887 1425 890 1426 887 1426 842 1426 887 1427 890 1427 889 1427 891 1428 871 1428 870 1428 892 1429 871 1429 891 1429 891 1430 893 1430 892 1430 894 1431 892 1431 893 1431 893 1432 895 1432 894 1432 894 1433 895 1433 774 1433 894 1434 774 1434 776 1434 728 182 730 182 738 182 728 182 738 182 744 182 728 182 744 182 746 182 728 1435 746 1435 748 1435 728 1436 748 1436 752 1436 728 1437 752 1437 758 1437 761 182 728 182 758 182 761 1438 679 1438 678 1438 761 1439 678 1439 677 1439 761 1440 677 1440 676 1440 761 1441 676 1441 674 1441 761 1442 674 1442 671 1442 761 1443 671 1443 670 1443 670 496 724 496 686 496 761 1444 670 1444 686 1444 761 1445 686 1445 685 1445 761 1446 685 1446 665 1446 761 1447 665 1447 662 1447 761 1448 662 1448 661 1448 761 1449 661 1449 655 1449 761 1450 655 1450 659 1450 728 1451 761 1451 659 1451 680 496 679 496 761 496 707 182 711 182 712 182 751 1452 750 1452 822 1452 870 1453 869 1453 872 1453 872 1454 875 1454 870 1454 866 1455 869 1455 871 1455 776 1456 832 1456 894 1456 871 1457 892 1457 894 1457 832 1458 871 1458 894 1458 832 1459 833 1459 871 1459 833 1460 834 1460 871 1460 741 1461 871 1461 834 1461 741 1462 834 1462 830 1462 741 1463 830 1463 829 1463 740 1464 741 1464 829 1464 740 1465 829 1465 828 1465 734 1466 740 1466 828 1466 733 1467 734 1467 828 1467 756 1468 896 1468 897 1468 897 1469 896 1469 898 1469 898 1470 896 1470 899 1470 898 1471 899 1471 900 1471 900 1472 899 1472 901 1472 900 1473 901 1473 902 1473 900 1474 902 1474 903 1474 904 1475 903 1475 902 1475 905 1476 903 1476 904 1476 905 1477 906 1477 903 1477 903 1478 906 1478 907 1478 908 1479 906 1479 905 1479 876 1480 903 1480 875 1480 906 1481 908 1481 774 1481 906 1482 774 1482 895 1482 893 1483 906 1483 895 1483 906 1484 893 1484 907 1484 891 1485 907 1485 893 1485 907 1486 891 1486 903 1486 891 1487 870 1487 903 1487 903 1488 876 1488 900 1488 875 1489 903 1489 870 1489 900 1490 876 1490 757 1490 800 1491 909 1491 798 1491 798 1492 909 1492 910 1492 911 1493 796 1493 910 1493 910 1494 796 1494 798 1494 910 1495 912 1495 911 1495 911 1496 912 1496 783 1496 911 1497 783 1497 781 1497 911 1498 781 1498 913 1498 911 1499 913 1499 914 1499 796 1500 911 1500 794 1500 908 1501 911 1501 914 1501 911 1502 902 1502 901 1502 902 1503 911 1503 904 1503 904 1504 911 1504 905 1504 905 1505 911 1505 908 1505 901 1506 792 1506 911 1506 911 1507 792 1507 794 1507 792 1508 901 1508 790 1508 899 1509 790 1509 901 1509 790 1510 899 1510 788 1510 896 1511 788 1511 899 1511 788 1512 896 1512 786 1512 756 1513 786 1513 896 1513 778 182 913 182 780 182 913 182 778 182 914 182 775 182 914 182 778 182 914 182 775 182 908 182 774 182 908 182 775 182 757 1514 898 1514 900 1514 898 1515 757 1515 897 1515 897 1516 757 1516 756 1516 780 182 913 182 781 182 681 1517 761 1517 760 1517 680 1518 761 1518 681 1518 724 1519 722 1519 686 1519 724 1520 672 1520 722 1520 915 270 773 270 916 270 917 270 915 270 916 270 918 270 919 270 916 270 920 270 921 270 917 270 916 573 922 573 918 573 923 1521 917 1521 921 1521 924 1522 918 1522 922 1522 921 1523 925 1523 923 1523 922 1524 926 1524 924 1524 927 1525 923 1525 925 1525 928 270 924 270 926 270 925 270 929 270 927 270 930 270 927 270 929 270 926 270 931 270 928 270 929 270 932 270 930 270 933 1526 928 1526 931 1526 930 1527 932 1527 934 1527 935 270 930 270 934 270 936 270 937 270 933 270 931 270 936 270 933 270 938 270 937 270 936 270 934 270 938 270 935 270 939 270 935 270 938 270 940 270 939 270 938 270 936 1528 940 1528 938 1528 941 582 800 582 942 582 943 1529 944 1529 816 1529 945 1530 922 1530 821 1530 946 1531 945 1531 819 1531 946 1532 816 1532 944 1532 947 1533 946 1533 944 1533 917 270 773 270 915 270 773 1534 917 1534 948 1534 948 1535 949 1535 825 1535 949 1536 950 1536 826 1536 950 1537 942 1537 827 1537 941 1538 951 1538 800 1538 951 1539 952 1539 910 1539 952 1540 953 1540 912 1540 954 595 955 595 784 595 955 1541 956 1541 836 1541 956 1542 943 1542 837 1542 957 1543 932 1543 929 1543 934 1544 932 1544 957 1544 938 1545 934 1545 957 1545 937 1546 938 1546 957 1546 933 602 937 602 957 602 928 270 933 270 957 270 957 603 924 603 928 603 918 1547 924 1547 957 1547 919 270 918 270 957 270 920 270 919 270 957 270 921 605 920 605 957 605 925 606 921 606 957 606 929 270 925 270 957 270 958 607 922 607 945 607 945 1548 946 1548 958 1548 959 1549 958 1549 946 1549 946 1550 947 1550 959 1550 948 1551 960 1551 949 1551 950 1552 949 1552 960 1552 960 1553 961 1553 950 1553 950 1554 961 1554 942 1554 962 1555 926 1555 922 1555 958 1556 962 1556 922 1556 959 1557 947 1557 962 1557 958 1558 959 1558 962 1558 947 1559 963 1559 962 1559 931 1560 926 1560 962 1560 964 1561 962 1561 963 1561 964 1562 936 1562 931 1562 962 1563 964 1563 931 1563 963 1564 965 1564 964 1564 940 1565 936 1565 964 1565 964 1566 965 1566 966 1566 967 1567 964 1567 966 1567 964 1568 967 1568 940 1568 939 1569 940 1569 967 1569 966 1570 968 1570 967 1570 969 1571 967 1571 968 1571 967 1572 969 1572 939 1572 935 1573 939 1573 969 1573 968 1574 970 1574 969 1574 971 1575 930 1575 935 1575 969 1576 971 1576 935 1576 971 1577 969 1577 970 1577 927 1578 930 1578 971 1578 970 1579 942 1579 971 1579 960 1580 923 1580 927 1580 971 641 960 641 927 641 971 1581 942 1581 961 1581 971 1582 961 1582 960 1582 948 1583 923 1583 960 1583 923 1584 948 1584 917 1584 784 182 953 182 954 182 954 182 972 182 973 182 953 182 972 182 954 182 947 1585 944 1585 943 1585 942 1586 970 1586 974 1586 974 1587 941 1587 942 1587 965 1588 963 1588 975 1588 975 1588 976 1588 965 1588 966 1589 965 1589 976 1589 976 1590 977 1590 966 1590 977 1591 978 1591 968 1591 968 1592 966 1592 977 1592 978 1593 974 1593 970 1593 970 1593 968 1593 978 1593 963 1594 947 1594 943 1594 943 1595 975 1595 963 1595 956 1596 975 1596 943 1596 955 1597 975 1597 956 1597 973 1598 976 1598 975 1598 973 1599 977 1599 976 1599 973 1600 972 1600 977 1600 972 1601 978 1601 977 1601 974 1602 978 1602 972 1602 951 1603 941 1603 974 1603 951 1604 974 1604 952 1604 916 1605 920 1605 917 1605 916 270 919 270 920 270 916 1606 821 1606 922 1606 955 1607 973 1607 975 1607 954 1608 973 1608 955 1608 953 672 952 672 972 672 952 1609 974 1609 972 1609 666 1610 979 1610 664 1610 663 1611 666 1611 664 1611 980 182 687 182 686 182 981 1612 690 1612 692 1612 703 1613 982 1613 692 1613 704 1614 664 1614 979 1614 704 1615 983 1615 705 1615 690 1616 981 1616 984 1616 984 1617 985 1617 690 1617 799 683 942 683 800 683 783 182 953 182 784 182 815 583 943 583 816 583 821 684 819 684 945 684 819 1618 820 1618 946 1618 946 1619 820 1619 816 1619 825 1620 773 1620 948 1620 826 1621 825 1621 949 1621 827 1622 826 1622 950 1622 799 1623 827 1623 942 1623 951 1624 909 1624 800 1624 910 1625 909 1625 951 1625 912 693 910 693 952 693 783 1626 912 1626 953 1626 955 695 835 695 784 695 836 696 835 696 955 696 837 1627 836 1627 956 1627 815 1628 837 1628 943 1628 916 270 773 270 772 270 772 1629 821 1629 916 1629 986 1630 987 1630 988 1630 692 1631 989 1631 990 1631 981 1632 692 1632 990 1632 991 1633 992 1633 993 1633 991 1634 994 1634 992 1634 995 1635 996 1635 997 1635 997 1636 996 1636 998 1636 998 1637 996 1637 999 1637 999 1638 996 1638 1000 1638 1000 1639 996 1639 1001 1639 1001 1640 996 1640 1002 1640 999 1641 1003 1641 998 1641 1004 1642 1005 1642 1003 1642 1003 1643 1005 1643 1006 1643 992 1644 1006 1644 1005 1644 1007 1645 1006 1645 992 1645 1008 1646 1007 1646 992 1646 1007 1647 1009 1647 1006 1647 998 1648 1003 1648 1006 1648 998 1649 1006 1649 1009 1649 1010 1650 1011 1650 1012 1650 1001 1651 1011 1651 1010 1651 992 1652 994 1652 1008 1652 980 1653 669 1653 687 1653 1013 1654 669 1654 980 1654 1014 1655 1013 1655 980 1655 1015 1656 1014 1656 980 1656 980 1657 1002 1657 1015 1657 996 1658 1015 1658 1002 1658 1011 1659 1001 1659 1002 1659 1016 1660 1017 1660 1018 1660 988 1661 1017 1661 1016 1661 1016 1662 1019 1662 988 1662 1020 1663 988 1663 1019 1663 1019 1664 1021 1664 1020 1664 1021 1665 990 1665 1020 1665 1021 1666 1022 1666 990 1666 981 1667 990 1667 1022 1667 1023 1668 981 1668 1022 1668 1024 1669 1025 1669 1026 1669 1025 1670 1027 1670 1026 1670 1028 1671 1024 1671 1026 1671 1026 1672 1029 1672 1028 1672 1030 1673 1028 1673 1029 1673 1029 1674 1031 1674 1030 1674 1032 1675 1030 1675 1031 1675 1031 1676 1033 1676 1032 1676 1034 1677 1032 1677 1033 1677 1033 1678 1035 1678 1034 1678 1036 1679 1034 1679 1035 1679 1035 1680 1018 1680 1036 1680 1036 1681 1018 1681 1017 1681 984 1682 981 1682 1023 1682 1037 1683 1038 1683 1039 1683 1038 1684 1037 1684 1040 1684 1041 1685 1042 1685 1038 1685 1043 1686 1044 1686 1045 1686 1046 1687 1045 1687 1044 1687 1046 1688 993 1688 1045 1688 1046 1689 1047 1689 993 1689 1046 1690 1048 1690 1047 1690 1046 1691 1049 1691 1048 1691 1050 1692 1049 1692 1046 1692 1051 1693 1046 1693 1052 1693 1046 1694 1044 1694 1052 1694 1046 1695 1051 1695 1050 1695 1051 1696 1053 1696 1050 1696 1052 1697 1054 1697 1051 1697 1055 1698 1053 1698 1051 1698 1051 1699 1038 1699 1055 1699 1038 1700 1056 1700 1055 1700 1038 1701 1042 1701 1056 1701 1051 1702 1039 1702 1038 1702 1051 1703 1054 1703 1039 1703 1045 1704 1004 1704 1043 1704 1005 1705 1004 1705 1045 1705 992 1706 1005 1706 1045 1706 1045 1707 993 1707 992 1707 993 1708 1047 1708 1057 1708 1057 1709 991 1709 993 1709 1058 1710 995 1710 997 1710 1059 1711 997 1711 998 1711 997 1712 1059 1712 1058 1712 998 1713 1009 1713 1059 1713 1060 1714 1058 1714 1059 1714 1059 1715 1061 1715 1060 1715 983 1716 1062 1716 705 1716 983 1717 704 1717 979 1717 983 1718 995 1718 1058 1718 983 1719 1063 1719 995 1719 983 1720 979 1720 1063 1720 983 1721 1058 1721 1062 1721 1058 1722 1060 1722 1062 1722 1064 1723 1065 1723 1066 1723 1067 1724 1066 1724 1065 1724 1067 1725 1007 1725 1008 1725 1067 1726 1065 1726 1007 1726 1008 1727 1068 1727 1067 1727 1008 1728 1069 1728 1068 1728 1008 1729 1070 1729 1069 1729 1071 1730 1070 1730 994 1730 1070 1731 1008 1731 994 1731 994 1732 991 1732 1071 1732 1072 1733 1071 1733 991 1733 991 1734 1057 1734 1072 1734 1047 1735 1072 1735 1057 1735 1004 1736 1003 1736 1000 1736 999 1737 1000 1737 1003 1737 1073 1738 1074 1738 1039 1738 1039 1739 1054 1739 1073 1739 1054 1740 1010 1740 1012 1740 1001 1741 1010 1741 1044 1741 1010 1742 1052 1742 1044 1742 1010 1743 1054 1743 1052 1743 1001 1744 1044 1744 1000 1744 1044 1745 1043 1745 1000 1745 1004 1746 1000 1746 1043 1746 1075 270 1033 270 1031 270 1075 1747 1035 1747 1033 1747 1018 270 1035 270 1075 270 1075 1748 1016 1748 1018 1748 1075 1749 1019 1749 1016 1749 1075 1750 1021 1750 1019 1750 1075 1751 1022 1751 1021 1751 1075 1752 1023 1752 1022 1752 1037 1753 1039 1753 1074 1753 988 1754 987 1754 1017 1754 989 1755 988 1755 1020 1755 1020 1756 990 1756 989 1756 988 1757 989 1757 986 1757 989 1758 1076 1758 986 1758 1077 1759 1076 1759 989 1759 1077 1760 989 1760 692 1760 982 1761 1077 1761 692 1761 1065 1762 1061 1762 1007 1762 1060 1763 1061 1763 1065 1763 1065 1764 1064 1764 1060 1764 1002 1765 980 1765 686 1765 995 1766 1015 1766 996 1766 1015 1767 995 1767 1063 1767 1015 1768 1063 1768 1014 1768 1063 1769 1013 1769 1014 1769 666 1770 1013 1770 1063 1770 1013 1771 666 1771 669 1771 666 1772 1063 1772 979 1772 1017 1773 987 1773 1036 1773 1069 1774 1070 1774 1078 1774 987 1775 1078 1775 1070 1775 1070 1776 1071 1776 987 1776 1071 1777 1036 1777 987 1777 1034 1778 1036 1778 1047 1778 1036 1779 1072 1779 1047 1779 1036 1780 1071 1780 1072 1780 1047 1781 1048 1781 1034 1781 1032 1782 1034 1782 1048 1782 1048 1783 1049 1783 1032 1783 1030 1784 1032 1784 1050 1784 1032 1785 1049 1785 1050 1785 1050 1786 1053 1786 1030 1786 1028 1787 1030 1787 1053 1787 1053 1788 1055 1788 1028 1788 1024 1789 1028 1789 1056 1789 1028 1790 1055 1790 1056 1790 1056 1791 1042 1791 1024 1791 1025 1792 1024 1792 1042 1792 1079 1793 1002 1793 686 1793 1002 1794 1079 1794 1011 1794 638 1795 637 1795 564 1795 637 1796 1080 1796 565 1796 1081 1797 616 1797 1082 1797 617 1798 616 1798 1081 1798 1081 1799 1083 1799 617 1799 1083 1800 636 1800 617 1800 701 1801 1082 1801 616 1801 701 1802 1084 1802 1082 1802 577 270 635 270 1075 270 1075 1803 1081 1803 1082 1803 1075 1804 1083 1804 1081 1804 1075 1805 636 1805 1083 1805 1075 1806 634 1806 636 1806 1075 1807 635 1807 634 1807 1082 878 1084 878 1075 878 1084 1808 1085 1808 1075 1808 721 1809 1075 1809 1085 1809 1011 1810 642 1810 650 1810 1011 1811 641 1811 642 1811 1011 1812 640 1812 641 1812 1011 1813 639 1813 640 1813 1011 1814 638 1814 639 1814 1011 1815 637 1815 638 1815 1011 1816 1080 1816 637 1816 1011 1817 723 1817 1080 1817 1086 1818 1087 1818 589 1818 601 1819 1086 1819 589 1819 1088 891 1089 891 1087 891 1086 1820 1088 1820 1087 1820 1090 1821 1089 1821 1088 1821 1091 1822 1092 1822 1090 1822 1088 1823 1091 1823 1090 1823 1091 1824 1093 1824 1092 1824 1011 1825 650 1825 649 1825 1011 1826 649 1826 648 1826 1094 1827 1095 1827 1096 1827 1096 1828 1097 1828 1094 1828 1094 1829 1097 1829 1040 1829 1098 1830 1094 1830 1040 1830 1099 1831 599 1831 600 1831 1100 1832 600 1832 591 1832 1101 1833 1095 1833 1100 1833 591 1834 1101 1834 1100 1834 1101 1835 1096 1835 1095 1835 1102 1836 1089 1836 1090 1836 1103 1837 1102 1837 1090 1837 1103 909 1097 909 1096 909 1103 1838 1096 1838 1102 1838 1090 1839 1092 1839 1103 1839 1103 1840 1092 1840 1104 1840 1103 1841 1041 1841 1097 1841 1102 1842 1101 1842 591 1842 590 1843 1102 1843 591 1843 590 1844 589 1844 1087 1844 590 1845 1087 1845 1089 1845 590 1846 1089 1846 1102 1846 1101 1847 1102 1847 1096 1847 1093 1848 1091 1848 1105 1848 1088 1849 1086 1849 1106 1849 1107 1850 1106 1850 1086 1850 1086 1851 601 1851 1107 1851 1108 1852 1107 1852 601 1852 601 1853 581 1853 1108 1853 580 1854 1108 1854 581 1854 648 1855 599 1855 1011 1855 1011 1856 599 1856 1099 1856 1091 1857 1109 1857 1105 1857 1088 1858 1109 1858 1091 1858 1088 1859 1106 1859 1109 1859 600 1860 1011 1860 1099 1860 1075 1861 580 1861 578 1861 1075 1862 578 1862 577 1862 694 1863 690 1863 985 1863 985 935 721 935 694 935 721 1864 1085 1864 698 1864 701 1865 698 1865 1085 1865 1085 1866 1084 1866 701 1866 1080 1867 723 1867 675 1867 675 1868 565 1868 1080 1868 1105 1869 1110 1869 1093 1869 1025 1870 1093 1870 1110 1870 1027 1871 1025 1871 1110 1871 1041 1872 1038 1872 1040 1872 1041 1873 1111 1873 1042 1873 1041 1874 1104 1874 1111 1874 1041 1875 1040 1875 1097 1875 1041 1876 1103 1876 1104 1876 984 270 1023 270 1075 270 985 270 984 270 1075 270 1075 1877 721 1877 985 1877 1074 950 1112 950 1037 950 1040 1878 1037 1878 1112 1878 1112 1879 1098 1879 1040 1879 1111 1880 1025 1880 1042 1880 1093 1881 1025 1881 1104 1881 1025 1882 1111 1882 1104 1882 1093 1883 1104 1883 1092 1883 1079 1884 686 1884 722 1884 1079 1885 722 1885 723 1885 1079 1886 723 1886 1011 1886 1113 1887 1114 1887 1115 1887 1116 1888 1117 1888 1118 1888 1118 1889 1114 1889 1113 1889 1113 1890 1115 1890 1119 1890 1120 1891 1121 1891 1122 1891 1123 1892 1122 1892 1121 1892 1124 1893 1123 1893 1125 1893 1123 1894 1121 1894 1125 1894 1126 1895 1124 1895 1127 1895 1124 1896 1125 1896 1127 1896 1128 1897 1126 1897 1129 1897 1126 1898 1127 1898 1129 1898 1130 1899 1128 1899 1129 1899 1130 1900 1131 1900 1128 1900 1132 1901 1128 1901 1131 1901 1133 1902 1134 1902 1135 1902 1133 1903 1136 1903 1134 1903 1136 1904 1137 1904 1134 1904 1136 1905 1138 1905 1137 1905 1138 1906 1139 1906 1137 1906 1138 1907 1140 1907 1139 1907 1139 1908 1140 1908 1141 1908 1142 1909 1141 1909 1143 1909 1141 1910 1140 1910 1143 1910 1122 1911 1144 1911 1120 1911 1145 1912 1133 1912 1135 1912 1146 1913 1147 1913 1148 1913 1147 1914 1149 1914 1148 1914 1149 1915 1131 1915 1148 1915 1149 1916 1150 1916 1131 1916 1150 1917 1151 1917 1131 1917 1151 1918 1152 1918 1131 1918 1132 1919 1131 1919 1152 1919 1153 1920 1154 1920 1155 1920 1156 1921 1154 1921 1153 1921 1153 1922 1157 1922 1156 1922 1153 1923 1158 1923 1157 1923 1153 1924 1159 1924 1158 1924 1153 1925 1160 1925 1159 1925 1153 1926 1143 1926 1160 1926 1142 1927 1143 1927 1161 1927 1143 1927 1162 1927 1161 1927 1143 1927 1153 1927 1162 1927 1146 1928 1163 1928 1147 1928 1163 1929 1164 1929 1147 1929 1165 1930 1164 1930 1163 1930 1163 1931 1166 1931 1165 1931 1167 1932 1165 1932 1166 1932 1166 1933 1168 1933 1167 1933 1168 1934 1169 1934 1170 1934 1171 1935 1172 1935 1169 1935 1169 1936 1173 1936 1171 1936 1173 1937 1174 1937 1171 1937 1175 1938 1174 1938 1173 1938 1173 1939 1176 1939 1175 1939 1176 1940 1177 1940 1175 1940 1176 1941 1178 1941 1177 1941 1179 1942 1178 1942 1176 1942 1155 1943 1180 1943 1153 1943 1181 1944 1153 1944 1180 1944 1180 1945 1182 1945 1181 1945 1116 1946 1181 1946 1182 1946 1182 1947 1117 1947 1116 1947 1113 1948 1116 1948 1118 1948 1183 1949 1113 1949 1119 1949 1119 1950 1184 1950 1183 1950 1185 1951 1183 1951 1186 1951 1183 1952 1184 1952 1186 1952 1186 1953 1187 1953 1185 1953 1188 1954 1185 1954 1189 1954 1185 1955 1190 1955 1189 1955 1185 1956 1191 1956 1190 1956 1185 1957 1187 1957 1191 1957 1192 1958 1188 1958 1189 1958 1188 1959 1193 1959 1194 1959 1188 1960 1192 1960 1193 1960 1169 1961 1172 1961 1170 1961 1170 1962 1195 1962 1168 1962 1168 1963 1195 1963 1167 1963 1196 1964 982 1964 703 1964 1196 1965 703 1965 702 1965 1196 1966 702 1966 691 1966 1197 1967 1196 1967 691 1967 982 1968 1196 1968 1077 1968 1196 1969 1198 1969 1077 1969 305 1970 302 1970 1199 1970 302 1971 1200 1971 1199 1971 304 1972 305 1972 1201 1972 305 1973 1199 1973 1201 1973 306 1974 304 1974 1202 1974 304 1975 1201 1975 1202 1975 1203 1976 306 1976 1202 1976 1204 1977 306 1977 1203 1977 1203 1978 1205 1978 1204 1978 292 1979 1204 1979 1205 1979 307 1980 1206 1980 1207 1980 1207 1981 1206 1981 1208 1981 307 1982 332 1982 1206 1982 332 1983 1209 1983 1206 1983 332 1984 333 1984 1209 1984 333 1985 1210 1985 1209 1985 333 1986 1211 1986 1210 1986 333 1987 334 1987 1211 1987 1211 1988 334 1988 1212 1988 1213 1989 1212 1989 287 1989 1212 1990 334 1990 287 1990 302 182 321 182 1200 182 1200 1991 321 1991 1214 1991 321 1992 318 1992 1214 1992 318 1993 317 1993 1214 1993 317 1994 312 1994 1214 1994 312 1995 308 1995 1214 1995 1208 1996 1214 1996 1207 1996 1214 1997 308 1997 1207 1997 308 1998 307 1998 1207 1998 1215 1999 54 1999 1216 1999 54 2000 4 2000 1216 2000 4 2001 1217 2001 1216 2001 4 2002 5 2002 1217 2002 5 2003 1205 2003 1217 2003 5 2004 164 2004 1205 2004 164 2005 159 2005 1205 2005 159 2006 163 2006 1205 2006 292 2007 1205 2007 163 2007 508 2008 1218 2008 505 2008 1218 2009 506 2009 505 2009 1218 2010 151 2010 506 2010 1218 2011 152 2011 151 2011 1218 2012 154 2012 152 2012 1218 2013 155 2013 154 2013 1218 2014 287 2014 155 2014 287 2015 1218 2015 1213 2015 1215 2016 1219 2016 54 2016 1219 2017 88 2017 54 2017 73 2018 88 2018 1219 2018 1219 2019 1220 2019 73 2019 74 2020 73 2020 1220 2020 1220 2021 1221 2021 74 2021 1221 2022 47 2022 74 2022 48 2023 47 2023 1221 2023 1221 2024 1222 2024 48 2024 1222 2025 67 2025 48 2025 64 2026 67 2026 1222 2026 1222 2027 1223 2027 64 2027 1223 2028 60 2028 64 2028 6 2029 60 2029 1223 2029 1223 2030 1224 2030 6 2030 1224 2031 7 2031 6 2031 1224 2032 134 2032 7 2032 135 2033 134 2033 1224 2033 508 2034 510 2034 1218 2034 1225 2035 1218 2035 510 2035 510 2036 511 2036 1225 2036 1226 2037 1225 2037 511 2037 511 2038 512 2038 1226 2038 1227 2039 1226 2039 513 2039 1226 2040 512 2040 513 2040 513 2041 522 2041 1227 2041 1228 2042 1227 2042 430 2042 1227 2043 431 2043 430 2043 1227 2044 522 2044 431 2044 430 2045 520 2045 1228 2045 1229 2046 1228 2046 521 2046 1228 2047 520 2047 521 2047 521 2048 426 2048 1229 2048 1230 2049 1229 2049 137 2049 1229 2050 148 2050 137 2050 1229 2051 149 2051 148 2051 1229 2052 426 2052 149 2052 139 2053 1230 2053 137 2053 1224 2054 1230 2054 146 2054 146 2055 135 2055 1224 2055 1230 2056 145 2056 146 2056 1230 2057 143 2057 145 2057 1230 2058 141 2058 143 2058 1230 2059 139 2059 141 2059 1231 1891 1232 1891 857 1891 859 2060 857 2060 1232 2060 861 2061 859 2061 1233 2061 859 2062 1232 2062 1233 2062 860 2063 861 2063 1234 2063 861 2064 1233 2064 1234 2064 862 2065 860 2065 1235 2065 860 2066 1234 2066 1235 2066 1236 2067 862 2067 1235 2067 1237 2068 862 2068 1236 2068 1236 2069 1238 2069 1237 2069 847 2070 1237 2070 1238 2070 863 2071 1239 2071 1240 2071 863 2072 888 2072 1239 2072 888 2073 1241 2073 1239 2073 888 2074 889 2074 1241 2074 889 2075 1242 2075 1241 2075 889 2076 1243 2076 1242 2076 889 2077 890 2077 1243 2077 1243 2078 890 2078 1244 2078 1245 2079 1244 2079 842 2079 1244 2080 890 2080 842 2080 857 2081 877 2081 1231 2081 1231 2082 877 2082 1246 2082 877 2083 874 2083 1246 2083 874 182 873 182 1246 182 873 182 868 182 1246 182 868 182 864 182 1246 182 1246 2084 864 2084 1240 2084 864 2085 863 2085 1240 2085 1247 2086 609 2086 1248 2086 609 2087 560 2087 1248 2087 560 2088 1238 2088 1248 2088 560 2089 719 2089 1238 2089 719 2090 714 2090 1238 2090 714 2091 718 2091 1238 2091 847 2092 1238 2092 718 2092 1064 2093 1249 2093 1060 2093 1249 2094 1062 2094 1060 2094 1249 2095 705 2095 1062 2095 1249 2096 706 2096 705 2096 1249 2097 708 2097 706 2097 1249 2098 709 2098 708 2098 1249 2099 842 2099 709 2099 842 2100 1249 2100 1245 2100 1247 2101 1250 2101 609 2101 1250 2102 643 2102 609 2102 628 2103 643 2103 1250 2103 1250 2104 1251 2104 628 2104 629 2105 628 2105 1251 2105 1251 2106 1252 2106 629 2106 1252 2107 602 2107 629 2107 603 2108 602 2108 1252 2108 1252 2109 1253 2109 603 2109 1253 2110 622 2110 603 2110 619 2111 622 2111 1253 2111 1253 2112 1254 2112 619 2112 1254 2113 615 2113 619 2113 561 2114 615 2114 1254 2114 1254 2115 1255 2115 561 2115 1255 2116 562 2116 561 2116 1255 2117 688 2117 562 2117 689 2118 688 2118 1255 2118 1064 2119 1066 2119 1249 2119 1256 2120 1249 2120 1066 2120 1066 2121 1067 2121 1256 2121 1257 2122 1256 2122 1067 2122 1067 2123 1068 2123 1257 2123 1258 2124 1257 2124 1069 2124 1257 2125 1068 2125 1069 2125 1069 2126 1078 2126 1258 2126 1198 2127 1258 2127 986 2127 1258 2128 987 2128 986 2128 1258 2129 1078 2129 987 2129 986 2130 1076 2130 1198 2130 1198 2131 1076 2131 1077 2131 693 2132 1197 2132 691 2132 1255 2133 1197 2133 700 2133 700 2134 689 2134 1255 2134 1197 2135 699 2135 700 2135 1197 2136 697 2136 699 2136 1197 2137 695 2137 697 2137 1197 2138 693 2138 695 2138 1259 2139 1196 2139 1197 2139 1260 2140 1196 2140 1259 2140 1261 2141 1196 2141 1260 2141 1198 2142 1196 2142 1261 2142 1238 64 1262 64 1248 64 1263 64 1248 64 1262 64 1249 2143 1264 2143 1245 2143 1265 2144 1245 2144 1264 2144 1266 2145 1260 2145 1259 2145 1266 2146 1259 2146 1267 2146 1268 2147 1269 2147 1270 2147 1271 2148 1269 2148 1268 2148 1272 2149 1269 2149 1271 2149 1273 2150 1269 2150 1272 2150 1246 2151 1271 2151 1274 2151 1275 2152 1246 2152 1274 2152 1208 2153 1206 2153 1276 2153 1240 2154 1239 2154 1273 2154 1239 2155 1269 2155 1273 2155 1239 2156 1241 2156 1269 2156 1270 2157 1269 2157 1241 2157 1241 2158 1242 2158 1270 2158 1242 2159 1243 2159 1270 2159 1243 2160 1244 2160 1270 2160 1244 2161 1277 2161 1270 2161 1265 2162 1277 2162 1245 2162 1277 2163 1244 2163 1245 2163 1199 2164 1278 2164 1201 2164 1278 2165 1202 2165 1201 2165 1199 2166 1279 2166 1278 2166 1199 2167 1200 2167 1279 2167 1280 2168 1202 2168 1278 2168 1202 2169 1280 2169 1203 2169 1280 2170 1205 2170 1203 2170 1280 2171 1281 2171 1205 2171 1282 2172 1280 2172 1278 2172 1280 2173 1282 2173 1281 2173 1282 2174 1283 2174 1281 2174 1284 2175 1283 2175 1282 2175 1278 2176 1285 2176 1286 2176 1278 2177 1279 2177 1285 2177 1278 2178 1286 2178 1282 2178 1282 2179 1287 2179 1284 2179 1287 2180 1288 2180 1284 2180 1287 2181 1282 2181 1286 2181 1285 2182 1289 2182 1286 2182 1286 2183 1290 2183 1287 2183 1290 2184 1286 2184 1291 2184 1286 2185 1292 2185 1291 2185 1286 2186 1289 2186 1292 2186 1293 2187 1288 2187 1287 2187 1287 2188 1294 2188 1293 2188 1294 2189 1287 2189 1290 2189 1295 2190 1293 2190 1294 2190 1291 2191 1296 2191 1290 2191 1297 2192 1290 2192 1298 2192 1290 2193 1296 2193 1298 2193 1290 2194 1297 2194 1294 2194 1299 2195 1294 2195 1297 2195 1294 2196 1299 2196 1295 2196 1299 2197 1300 2197 1295 2197 1301 2198 1300 2198 1299 2198 1298 2199 1302 2199 1297 2199 1303 2200 1297 2200 1304 2200 1297 2201 1302 2201 1304 2201 1297 2202 1303 2202 1299 2202 1305 2203 1299 2203 1303 2203 1299 2204 1305 2204 1301 2204 1305 2205 1306 2205 1301 2205 1304 2206 1307 2206 1303 2206 1303 2207 1308 2207 1268 2207 1303 2208 1307 2208 1308 2208 1303 2209 1268 2209 1305 2209 1309 2210 1306 2210 1305 2210 1305 2211 1268 2211 1270 2211 1305 2212 1270 2212 1309 2212 1308 2213 1271 2213 1268 2213 1265 2214 1309 2214 1277 2214 1309 2215 1270 2215 1277 2215 1275 2216 1232 2216 1231 2216 1233 2217 1232 2217 1310 2217 1234 2218 1233 2218 1311 2218 1233 2219 1310 2219 1311 2219 1235 2220 1234 2220 1311 2220 1236 2221 1235 2221 1312 2221 1235 2222 1311 2222 1312 2222 1312 2223 1262 2223 1236 2223 1238 2224 1236 2224 1262 2224 1313 2225 1311 2225 1310 2225 1311 2226 1313 2226 1312 2226 1313 2227 1262 2227 1312 2227 1313 2228 1314 2228 1262 2228 1275 2229 1274 2229 1232 2229 1274 2230 1310 2230 1232 2230 1310 2231 1315 2231 1313 2231 1315 2232 1310 2232 1316 2232 1310 2233 1274 2233 1316 2233 1317 2234 1314 2234 1313 2234 1316 2235 1318 2235 1315 2235 1319 2236 1313 2236 1320 2236 1313 2237 1315 2237 1320 2237 1313 2238 1319 2238 1317 2238 1319 2239 1321 2239 1317 2239 1319 2240 1322 2240 1321 2240 1320 2241 1315 2241 1323 2241 1315 2242 1318 2242 1323 2242 1323 2243 1324 2243 1320 2243 1320 2244 1325 2244 1319 2244 1325 2245 1320 2245 1326 2245 1320 2246 1324 2246 1326 2246 1327 2247 1322 2247 1319 2247 1328 2248 1319 2248 1325 2248 1319 2249 1328 2249 1327 2249 1328 2250 1329 2250 1327 2250 1326 2251 1330 2251 1325 2251 1325 2252 1330 2252 1331 2252 1331 182 1292 182 1332 182 1291 182 1292 182 1330 182 1292 2253 1331 2253 1330 2253 1330 182 1326 182 1291 182 1296 2254 1291 2254 1326 2254 1326 182 1324 182 1296 182 1298 182 1296 182 1324 182 1279 2255 1333 2255 1285 2255 1324 2256 1323 2256 1298 2256 1302 182 1298 182 1323 182 1323 182 1318 182 1302 182 1318 2257 1304 2257 1302 2257 1333 2258 1279 2258 1214 2258 1307 182 1304 182 1318 182 1318 182 1316 182 1307 182 1308 182 1307 182 1316 182 1316 2259 1274 2259 1308 2259 1271 2260 1308 2260 1274 2260 1279 2261 1200 2261 1214 2261 1208 2262 1276 2262 1214 2262 1272 2263 1271 2263 1246 2263 1273 2264 1272 2264 1246 2264 1275 2265 1231 2265 1246 2265 1240 2266 1273 2266 1246 2266 1334 2267 1260 2267 1335 2267 1260 2268 1266 2268 1335 2268 1260 2269 1334 2269 1261 2269 1334 2270 1336 2270 1261 2270 1334 2271 1337 2271 1336 2271 1338 2272 1337 2272 1334 2272 1338 2273 1339 2273 1337 2273 1338 2274 1264 2274 1339 2274 1338 2275 1340 2275 1264 2275 1335 2276 1341 2276 1334 2276 1334 2277 1342 2277 1338 2277 1342 2278 1334 2278 1343 2278 1334 2279 1344 2279 1343 2279 1334 2280 1341 2280 1344 2280 1345 2281 1338 2281 1342 2281 1338 2282 1345 2282 1340 2282 1345 2283 1346 2283 1340 2283 1343 2284 1347 2284 1342 2284 1348 2285 1342 2285 1349 2285 1342 2286 1347 2286 1349 2286 1342 2287 1348 2287 1345 2287 1350 2288 1345 2288 1348 2288 1345 2289 1350 2289 1346 2289 1350 2290 1351 2290 1346 2290 1349 2291 1352 2291 1348 2291 1353 2292 1351 2292 1350 2292 1354 2293 1348 2293 1355 2293 1348 2294 1356 2294 1355 2294 1352 2295 1356 2295 1348 2295 1348 2296 1354 2296 1350 2296 1350 2297 1357 2297 1353 2297 1357 2298 1350 2298 1354 2298 1358 2299 1353 2299 1357 2299 1355 2300 1359 2300 1354 2300 1360 2301 1354 2301 1361 2301 1354 2302 1359 2302 1361 2302 1354 2303 1360 2303 1357 2303 1362 2304 1357 2304 1360 2304 1357 2305 1362 2305 1358 2305 1362 2306 1363 2306 1358 2306 1361 2307 1364 2307 1360 2307 1365 2308 1360 2308 1366 2308 1360 2309 1364 2309 1366 2309 1360 2310 1365 2310 1362 2310 1362 2311 1367 2311 1363 2311 1367 2312 1368 2312 1363 2312 1367 2313 1362 2313 1365 2313 1365 2314 1222 2314 1367 2314 1365 2315 1223 2315 1222 2315 1365 2316 1224 2316 1223 2316 1365 2317 1369 2317 1224 2317 1365 2318 1370 2318 1369 2318 1365 2319 1366 2319 1370 2319 1219 2320 1367 2320 1220 2320 1367 2321 1221 2321 1220 2321 1367 2322 1222 2322 1221 2322 1367 2323 1219 2323 1368 2323 1368 2324 1219 2324 1215 2324 1267 2325 1259 2325 1197 2325 1261 2326 1336 2326 1198 2326 1336 2327 1258 2327 1198 2327 1257 2328 1258 2328 1336 2328 1336 2329 1337 2329 1257 2329 1256 2330 1257 2330 1339 2330 1257 2331 1337 2331 1339 2331 1339 2332 1264 2332 1256 2332 1249 2333 1256 2333 1264 2333 1255 2334 1371 2334 1372 2334 1255 2335 1254 2335 1371 2335 1254 2336 1373 2336 1371 2336 1254 2337 1253 2337 1373 2337 1253 2338 1374 2338 1373 2338 1375 2339 1374 2339 1252 2339 1374 2340 1253 2340 1252 2340 1252 2341 1251 2341 1375 2341 1376 2342 1375 2342 1251 2342 1251 2343 1250 2343 1376 2343 1377 2344 1376 2344 1247 2344 1376 2345 1250 2345 1247 2345 1378 2346 1379 2346 1380 2346 1379 2347 1381 2347 1380 2347 1382 2348 1383 2348 1384 2348 1383 2349 1382 2349 1378 2349 1385 2350 1384 2350 1383 2350 1380 2351 1386 2351 1378 2351 1378 2352 1387 2352 1383 2352 1387 2353 1378 2353 1388 2353 1378 2354 1386 2354 1388 2354 1389 2355 1383 2355 1387 2355 1383 2356 1389 2356 1385 2356 1389 2357 1390 2357 1385 2357 1388 2358 1391 2358 1387 2358 1392 2359 1387 2359 1393 2359 1387 2360 1394 2360 1393 2360 1387 2361 1391 2361 1394 2361 1387 2362 1392 2362 1389 2362 1395 2363 1389 2363 1392 2363 1389 2364 1395 2364 1390 2364 1395 2365 1396 2365 1390 2365 1393 2366 1397 2366 1392 2366 1392 2367 1373 2367 1395 2367 1392 2368 1371 2368 1373 2368 1392 2369 1372 2369 1371 2369 1392 2370 1398 2370 1372 2370 1392 2371 1397 2371 1398 2371 1376 2372 1395 2372 1375 2372 1395 2373 1374 2373 1375 2373 1395 2374 1373 2374 1374 2374 1395 2375 1376 2375 1396 2375 1376 2376 1377 2376 1396 2376 1309 2377 1265 2377 1264 2377 1264 2378 1340 2378 1309 2378 1306 2379 1309 2379 1340 2379 1301 2380 1306 2380 1346 2380 1306 2381 1340 2381 1346 2381 1300 2382 1301 2382 1346 2382 1346 2383 1351 2383 1300 2383 1295 2384 1300 2384 1351 2384 1351 2385 1353 2385 1295 2385 1293 2386 1295 2386 1353 2386 1288 2387 1293 2387 1353 2387 1353 2388 1358 2388 1288 2388 1284 2389 1288 2389 1358 2389 1358 2390 1363 2390 1284 2390 1283 2391 1284 2391 1363 2391 1281 2392 1283 2392 1368 2392 1283 2393 1363 2393 1368 2393 1205 2394 1281 2394 1217 2394 1281 2395 1216 2395 1217 2395 1281 2396 1368 2396 1216 2396 1327 2397 1329 2397 1384 2397 1384 2398 1385 2398 1327 2398 1322 2399 1327 2399 1385 2399 1385 2400 1390 2400 1322 2400 1321 2401 1322 2401 1390 2401 1317 2402 1321 2402 1396 2402 1321 2403 1390 2403 1396 2403 1314 2404 1317 2404 1396 2404 1396 2405 1377 2405 1314 2405 1314 2406 1263 2406 1262 2406 1314 2407 1377 2407 1263 2407 1368 2408 1215 2408 1216 2408 1377 2409 1247 2409 1263 2409 1248 64 1263 64 1247 64 1255 270 1372 270 1197 270 1267 270 1197 270 1372 270 1224 270 1369 270 1230 270 1230 2410 1370 2410 1366 2410 1230 2411 1369 2411 1370 2411 1120 2412 1144 2412 1399 2412 1144 2413 1400 2413 1399 2413 1400 2414 1401 2414 1399 2414 1401 2415 1402 2415 1399 2415 1402 2416 1145 2416 1399 2416 1399 2417 1145 2417 1135 2417 1131 2418 1403 2418 1148 2418 1120 2419 1404 2419 1121 2419 1405 2420 1121 2420 1404 2420 1325 2421 1406 2421 1328 2421 1406 2422 1325 2422 1407 2422 1325 2423 1331 2423 1407 2423 1408 2424 1329 2424 1328 2424 1409 2425 1328 2425 1406 2425 1328 2426 1409 2426 1408 2426 1407 2427 1410 2427 1406 2427 1411 2428 1408 2428 1409 2428 1406 2429 1412 2429 1409 2429 1412 2430 1406 2430 1413 2430 1406 2431 1414 2431 1413 2431 1406 2432 1410 2432 1414 2432 1415 2433 1409 2433 1412 2433 1409 2434 1415 2434 1411 2434 1415 2435 1416 2435 1411 2435 1415 2436 1417 2436 1416 2436 1418 2437 1417 2437 1415 2437 1415 2438 1137 2438 1139 2438 1415 2439 1412 2439 1137 2439 1415 2440 1139 2440 1418 2440 1142 2441 1418 2441 1141 2441 1418 2442 1139 2442 1141 2442 1137 2443 1412 2443 1134 2443 1412 2444 1413 2444 1134 2444 1413 2445 1135 2445 1134 2445 1405 2446 1125 2446 1121 2446 1405 2447 1419 2447 1125 2447 1127 2448 1125 2448 1419 2448 1419 2449 1420 2449 1127 2449 1420 2450 1129 2450 1127 2450 1129 2451 1420 2451 1130 2451 1131 2452 1130 2452 1421 2452 1130 2453 1420 2453 1421 2453 1131 2454 1421 2454 1422 2454 1332 2455 1404 2455 1331 2455 1404 2456 1407 2456 1331 2456 1410 2457 1407 2457 1404 2457 1414 2458 1410 2458 1404 2458 1413 2459 1414 2459 1399 2459 1414 2460 1404 2460 1399 2460 1404 2461 1120 2461 1399 2461 1399 2462 1135 2462 1413 2462 1423 2463 1185 2463 1188 2463 1185 2464 1424 2464 1183 2464 1424 2465 1113 2465 1183 2465 1424 2466 1116 2466 1113 2466 1424 2467 1185 2467 1425 2467 1185 2468 1426 2468 1425 2468 1185 2469 1427 2469 1426 2469 1185 2470 1423 2470 1427 2470 1181 2471 1116 2471 1428 2471 1428 2472 1153 2472 1181 2472 1428 2473 1429 2473 1153 2473 1428 2474 1116 2474 1424 2474 1430 2475 1429 2475 1428 2475 1424 2476 1431 2476 1428 2476 1431 2477 1424 2477 1432 2477 1424 2478 1425 2478 1432 2478 1433 2479 1428 2479 1431 2479 1428 2480 1433 2480 1430 2480 1434 2481 1430 2481 1433 2481 1432 2482 1435 2482 1431 2482 1379 2483 1431 2483 1436 2483 1431 2484 1435 2484 1436 2484 1431 2485 1379 2485 1433 2485 1433 2486 1382 2486 1434 2486 1382 2487 1437 2487 1434 2487 1382 2488 1433 2488 1379 2488 1436 2489 1438 2489 1379 2489 1384 2490 1437 2490 1382 2490 1379 2491 1378 2491 1382 2491 1438 2492 1381 2492 1379 2492 1153 2493 1429 2493 1162 2493 1429 2494 1161 2494 1162 2494 1429 2495 1142 2495 1161 2495 1418 2496 1142 2496 1429 2496 1417 2497 1418 2497 1429 2497 1429 2498 1430 2498 1417 2498 1416 2499 1417 2499 1430 2499 1430 2500 1434 2500 1416 2500 1411 2501 1416 2501 1434 2501 1434 2502 1437 2502 1411 2502 1408 2503 1411 2503 1437 2503 1437 2504 1384 2504 1408 2504 1329 2505 1408 2505 1384 2505 1425 2506 1426 2506 1432 2506 1439 2507 1440 2507 1441 2507 1442 2508 1443 2508 1439 2508 1443 2509 1440 2509 1439 2509 1444 2510 1445 2510 1446 2510 1444 2511 1447 2511 1445 2511 1447 2512 1448 2512 1445 2512 1447 2513 1449 2513 1448 2513 1447 2514 1450 2514 1449 2514 1447 2515 1451 2515 1450 2515 1447 2516 1452 2516 1451 2516 1447 2517 1453 2517 1452 2517 1454 2518 1455 2518 1456 2518 1457 2519 1458 2519 1455 2519 1459 2520 1440 2520 1443 2520 1443 2521 1460 2521 1459 2521 1461 2522 1459 2522 1460 2522 1460 2523 1462 2523 1461 2523 1463 2524 1461 2524 1462 2524 1462 2525 1464 2525 1463 2525 1465 2526 1463 2526 1464 2526 1464 2527 1466 2527 1465 2527 1467 2528 1465 2528 1466 2528 1466 2529 1468 2529 1467 2529 1468 2530 1469 2530 1470 2530 1440 2531 1459 2531 1441 2531 1471 2532 1441 2532 1461 2532 1441 2533 1459 2533 1461 2533 1449 2534 1450 2534 1472 2534 1472 2535 1473 2535 1449 2535 1473 2536 1448 2536 1449 2536 1445 2537 1448 2537 1473 2537 1473 2538 1474 2538 1445 2538 1475 2539 1445 2539 1474 2539 1474 2540 1476 2540 1475 2540 1476 2541 1477 2541 1475 2541 1478 2542 1477 2542 1476 2542 1476 2543 1479 2543 1478 2543 1480 2544 1478 2544 1481 2544 1478 2545 1482 2545 1481 2545 1478 2546 1483 2546 1482 2546 1478 2547 1484 2547 1483 2547 1478 2548 1479 2548 1484 2548 1479 2549 1485 2549 1486 2549 1486 2550 1484 2550 1479 2550 1485 2551 1487 2551 1486 2551 1488 2552 1487 2552 1485 2552 1489 2553 1490 2553 1488 2553 1445 2554 1475 2554 1446 2554 1491 2555 1446 2555 1475 2555 1491 2556 1492 2556 1446 2556 1475 2557 1477 2557 1491 2557 1493 2558 1492 2558 1491 2558 1494 2559 1491 2559 1478 2559 1491 2560 1477 2560 1478 2560 1491 2561 1494 2561 1493 2561 1495 2562 1493 2562 1494 2562 1478 2563 1480 2563 1494 2563 1494 2564 1496 2564 1497 2564 1494 2565 1480 2565 1496 2565 1494 2566 1497 2566 1495 2566 1497 2567 1498 2567 1495 2567 1499 2568 1498 2568 1500 2568 1498 2569 1497 2569 1500 2569 1501 2570 1502 2570 1442 2570 1503 2571 1442 2571 1502 2571 1504 2572 1443 2572 1442 2572 1504 2573 1442 2573 1503 2573 1502 2574 1505 2574 1503 2574 1460 2575 1443 2575 1504 2575 1506 2576 1503 2576 1507 2576 1503 2577 1505 2577 1507 2577 1503 2578 1506 2578 1504 2578 1504 2579 1508 2579 1460 2579 1508 2580 1462 2580 1460 2580 1508 2581 1504 2581 1506 2581 1507 2582 1509 2582 1506 2582 1464 2583 1462 2583 1508 2583 1506 2584 1510 2584 1508 2584 1510 2585 1506 2585 1511 2585 1506 2586 1509 2586 1511 2586 1508 2587 1512 2587 1464 2587 1512 2588 1466 2588 1464 2588 1512 2589 1508 2589 1510 2589 1511 2590 1513 2590 1510 2590 1468 2591 1466 2591 1512 2591 1514 2592 1510 2592 1513 2592 1510 2593 1514 2593 1512 2593 1512 2594 1515 2594 1468 2594 1515 2595 1512 2595 1514 2595 1513 2596 1516 2596 1514 2596 1469 2597 1468 2597 1515 2597 1517 2598 1514 2598 1518 2598 1514 2599 1516 2599 1518 2599 1514 2600 1517 2600 1515 2600 1519 2601 1515 2601 1517 2601 1515 2602 1519 2602 1469 2602 1519 2603 1520 2603 1469 2603 1521 2604 1520 2604 1519 2604 1522 2605 1523 2605 1490 2605 1488 2606 1490 2606 1523 2606 1523 2607 1524 2607 1488 2607 1487 2608 1488 2608 1525 2608 1488 2609 1526 2609 1525 2609 1488 2610 1524 2610 1526 2610 1525 2611 1527 2611 1487 2611 1527 2612 1486 2612 1487 2612 1484 2613 1486 2613 1527 2613 1527 2614 1528 2614 1484 2614 1483 2615 1484 2615 1528 2615 1528 2616 1529 2616 1483 2616 1482 2617 1483 2617 1529 2617 1529 2618 1530 2618 1482 2618 1481 2619 1482 2619 1530 2619 1530 2620 1531 2620 1481 2620 1480 2621 1481 2621 1531 2621 1531 2622 1532 2622 1480 2622 1532 2623 1496 2623 1480 2623 1497 2624 1496 2624 1532 2624 1532 2625 1533 2625 1497 2625 1533 2626 1534 2626 1497 2626 1500 2627 1497 2627 1534 2627 1499 2628 1500 2628 1535 2628 1500 2629 1534 2629 1535 2629 1534 2630 1533 2630 1536 2630 1536 2631 1537 2631 1534 2631 1537 2632 1538 2632 1534 2632 1538 2633 1535 2633 1534 2633 1539 2634 1535 2634 1538 2634 1538 2635 1540 2635 1539 2635 1541 2636 1539 2636 1540 2636 1540 2637 1542 2637 1541 2637 1543 2638 1541 2638 1542 2638 1542 2639 1544 2639 1543 2639 1545 2640 1543 2640 1544 2640 1544 2641 1546 2641 1545 2641 1547 2642 1545 2642 1546 2642 1546 2643 1548 2643 1547 2643 1547 2644 1549 2644 1550 2644 1547 2645 1548 2645 1549 2645 1551 2646 1549 2646 1552 2646 1551 2647 1550 2647 1549 2647 1552 2648 1553 2648 1554 2648 1501 2649 1442 2649 1555 2649 1556 2650 1518 2650 1557 2650 1518 2651 1516 2651 1557 2651 1516 2652 1513 2652 1557 2652 1513 2653 1511 2653 1557 2653 1555 2654 1557 2654 1501 2654 1557 2655 1502 2655 1501 2655 1557 2656 1505 2656 1502 2656 1557 2657 1507 2657 1505 2657 1557 2658 1509 2658 1507 2658 1557 2659 1511 2659 1509 2659 1553 2660 1558 2660 1554 2660 1559 2661 1560 2661 1561 2661 1562 2662 1563 2662 1537 2662 1563 2663 1538 2663 1537 2663 1563 2664 1562 2664 1559 2664 1562 2665 1560 2665 1559 2665 1540 2666 1538 2666 1563 2666 1559 2667 1564 2667 1563 2667 1565 2668 1563 2668 1564 2668 1563 2669 1565 2669 1540 2669 1542 2670 1540 2670 1565 2670 1564 2671 1566 2671 1565 2671 1565 2672 1567 2672 1542 2672 1567 2673 1544 2673 1542 2673 1567 2674 1565 2674 1566 2674 1546 2675 1544 2675 1567 2675 1566 2676 1568 2676 1567 2676 1567 2677 1569 2677 1546 2677 1569 2678 1567 2678 1568 2678 1548 2679 1546 2679 1569 2679 1568 2680 1570 2680 1553 2680 1553 2681 1569 2681 1568 2681 1569 2682 1552 2682 1548 2682 1569 2683 1553 2683 1552 2683 1548 2684 1552 2684 1549 2684 1571 2685 1561 2685 1560 2685 1572 2686 1560 2686 1537 2686 1560 2687 1562 2687 1537 2687 1560 2688 1572 2688 1571 2688 1537 2689 1573 2689 1572 2689 1573 2690 1537 2690 1456 2690 1574 2691 1571 2691 1572 2691 1575 2692 1572 2692 1573 2692 1572 2693 1575 2693 1574 2693 1456 2694 1455 2694 1573 2694 1573 2695 1576 2695 1575 2695 1576 2696 1573 2696 1455 2696 1577 2697 1574 2697 1575 2697 1574 2698 1577 2698 1578 2698 1579 2699 1575 2699 1576 2699 1575 2700 1579 2700 1577 2700 1580 2701 1578 2701 1577 2701 1455 2702 1458 2702 1576 2702 1581 2703 1576 2703 1458 2703 1576 2704 1581 2704 1579 2704 1582 2705 1577 2705 1583 2705 1577 2706 1579 2706 1583 2706 1577 2707 1582 2707 1580 2707 1583 2708 1579 2708 1581 2708 1580 2709 1584 2709 1585 2709 1584 2710 1580 2710 1582 2710 1586 2711 1585 2711 1584 2711 1458 2712 1587 2712 1581 2712 1581 2713 1588 2713 1583 2713 1588 2714 1581 2714 1589 2714 1581 2715 1587 2715 1589 2715 1583 2716 1590 2716 1582 2716 1536 2717 1533 2717 1537 2717 1533 2718 1532 2718 1537 2718 1532 2719 1531 2719 1537 2719 1531 2720 1530 2720 1537 2720 1530 2721 1529 2721 1537 2721 1591 2722 1529 2722 1592 2722 1529 2723 1528 2723 1592 2723 1528 2724 1527 2724 1592 2724 1527 2725 1525 2725 1592 2725 1529 2726 1591 2726 1537 2726 1456 2727 1537 2727 1591 2727 1523 2728 1592 2728 1524 2728 1592 2729 1526 2729 1524 2729 1592 2730 1525 2730 1526 2730 1592 2731 1593 2731 1591 2731 1591 2732 1594 2732 1456 2732 1594 2733 1454 2733 1456 2733 1594 2734 1591 2734 1593 2734 1455 2735 1454 2735 1594 2735 1593 2736 1595 2736 1594 2736 1596 2737 1594 2737 1595 2737 1594 2738 1596 2738 1455 2738 1596 2739 1457 2739 1455 2739 1458 2740 1457 2740 1596 2740 1597 2741 1596 2741 1598 2741 1596 2742 1597 2742 1458 2742 1597 2743 1587 2743 1458 2743 1589 2744 1587 2744 1597 2744 1597 2745 1599 2745 1589 2745 1600 2746 1589 2746 1599 2746 1601 64 1550 64 1551 64 1547 64 1550 64 1601 64 1601 2747 1602 2747 1547 2747 1545 2748 1547 2748 1602 2748 1543 2749 1545 2749 1446 2749 1545 2750 1602 2750 1446 2750 1541 2751 1543 2751 1499 2751 1543 2752 1492 2752 1499 2752 1543 2753 1446 2753 1492 2753 1492 2754 1493 2754 1499 2754 1498 2755 1499 2755 1493 2755 1499 64 1535 64 1541 64 1535 64 1539 64 1541 64 1493 2756 1495 2756 1498 2756 1603 2757 1604 2757 1605 2757 1441 2758 1471 2758 1606 2758 1461 2759 1463 2759 1471 2759 1607 2760 1471 2760 1465 2760 1471 2761 1463 2761 1465 2761 1608 2762 1609 2762 1610 2762 1609 2763 1611 2763 1610 2763 1609 2764 1608 2764 1612 2764 1608 2765 1603 2765 1612 2765 1612 2766 1613 2766 1609 2766 1614 2767 1615 2767 1616 2767 1617 2768 1618 2768 1619 2768 1617 2769 1620 2769 1618 2769 1619 2770 1621 2770 1617 2770 1604 2771 1620 2771 1617 2771 1605 2772 1617 2772 1621 2772 1617 2773 1605 2773 1604 2773 1621 2774 1613 2774 1612 2774 1621 2775 1612 2775 1605 2775 1603 2776 1605 2776 1612 2776 1589 2777 1600 2777 1588 2777 1622 2778 1623 2778 1624 2778 1624 2779 1625 2779 1622 2779 1625 2780 1624 2780 1610 2780 1610 2781 1611 2781 1625 2781 1599 2782 1623 2782 1600 2782 1626 64 1627 64 1628 64 1627 64 1629 64 1630 64 1629 2783 1618 2783 1630 2783 1631 2784 1453 2784 1632 2784 1633 2785 1634 2785 1631 2785 1631 2786 1635 2786 1453 2786 1635 2787 1452 2787 1453 2787 1635 2788 1631 2788 1636 2788 1631 2789 1634 2789 1636 2789 1451 2790 1452 2790 1635 2790 1636 2791 1637 2791 1635 2791 1635 2792 1638 2792 1451 2792 1638 2793 1472 2793 1451 2793 1638 2794 1635 2794 1639 2794 1635 2795 1637 2795 1639 2795 1473 2796 1472 2796 1638 2796 1639 2797 1640 2797 1638 2797 1638 2798 1641 2798 1473 2798 1638 2799 1640 2799 1642 2799 1451 2800 1472 2800 1450 2800 1643 2801 1644 2801 1628 2801 1644 2802 1643 2802 1645 2802 1643 2803 1646 2803 1645 2803 1628 2804 1630 2804 1643 2804 1647 2805 1646 2805 1643 2805 1643 2806 1610 2806 1647 2806 1610 2807 1643 2807 1608 2807 1643 2808 1603 2808 1608 2808 1643 2809 1630 2809 1603 2809 1647 2810 1610 2810 1624 2810 1595 2811 1598 2811 1596 2811 1598 2812 1595 2812 1648 2812 1598 2813 1649 2813 1597 2813 1649 2814 1598 2814 1648 2814 1648 2815 1646 2815 1649 2815 1645 2816 1646 2816 1648 2816 1599 2817 1597 2817 1649 2817 1649 2818 1650 2818 1599 2818 1650 2819 1649 2819 1646 2819 1646 2820 1647 2820 1650 2820 1623 2821 1599 2821 1650 2821 1650 2822 1624 2822 1623 2822 1624 2823 1650 2823 1647 2823 1626 64 1628 64 1651 64 1627 2824 1630 2824 1628 2824 1618 2825 1620 2825 1630 2825 1620 64 1604 64 1630 64 1630 2826 1604 2826 1603 2826 1652 2827 1653 2827 1654 2827 1447 2828 1655 2828 1632 2828 1632 2829 1655 2829 1656 2829 1657 2830 1632 2830 1656 2830 1658 2831 1659 2831 1632 2831 1657 2832 1658 2832 1632 2832 1660 2833 1659 2833 1658 2833 1661 2834 1660 2834 1658 2834 1662 2835 1661 2835 1658 2835 1658 2836 1663 2836 1662 2836 1631 2837 1660 2837 1633 2837 1631 2838 1632 2838 1659 2838 1660 2839 1631 2839 1659 2839 1633 2840 1660 2840 1661 2840 1633 2841 1661 2841 1662 2841 1632 2842 1453 2842 1447 2842 1664 2843 1665 2843 1666 2843 1653 64 1667 64 1654 64 1667 64 1626 64 1654 64 1651 2844 1654 2844 1626 2844 1668 2845 1669 2845 1670 2845 1641 2846 1474 2846 1473 2846 1641 2847 1638 2847 1642 2847 1476 2848 1474 2848 1641 2848 1642 2849 1671 2849 1641 2849 1641 2850 1672 2850 1476 2850 1672 2851 1479 2851 1476 2851 1672 2852 1641 2852 1673 2852 1641 2853 1671 2853 1673 2853 1485 2854 1479 2854 1672 2854 1673 2855 1674 2855 1672 2855 1675 2856 1672 2856 1676 2856 1672 2857 1674 2857 1676 2857 1672 2858 1675 2858 1485 2858 1675 2859 1489 2859 1485 2859 1677 2860 1489 2860 1675 2860 1676 2861 1678 2861 1675 2861 1679 2862 1680 2862 1675 2862 1680 2863 1681 2863 1675 2863 1681 2864 1677 2864 1675 2864 1679 2865 1675 2865 1678 2865 1678 2866 1682 2866 1679 2866 1682 2867 1683 2867 1684 2867 1684 2868 1679 2868 1682 2868 1485 2869 1489 2869 1488 2869 1685 2870 1490 2870 1489 2870 1489 2871 1677 2871 1685 2871 1686 2872 1687 2872 1688 2872 1689 2873 1690 2873 1686 2873 1691 2874 1692 2874 1693 2874 1691 2875 1694 2875 1689 2875 1695 2876 1692 2876 1691 2876 1688 2877 1696 2877 1686 2877 1697 2878 1686 2878 1696 2878 1686 2879 1697 2879 1689 2879 1689 2880 1698 2880 1691 2880 1698 2881 1689 2881 1697 2881 1699 2882 1691 2882 1698 2882 1691 2883 1699 2883 1695 2883 1699 2884 1700 2884 1695 2884 1696 2885 1701 2885 1697 2885 1702 2886 1697 2886 1701 2886 1697 2887 1702 2887 1698 2887 1698 2888 1703 2888 1699 2888 1703 2889 1698 2889 1702 2889 1704 2890 1700 2890 1699 2890 1699 2891 1705 2891 1704 2891 1705 2892 1706 2892 1704 2892 1705 2893 1699 2893 1703 2893 1701 2894 1707 2894 1702 2894 1702 2895 1708 2895 1703 2895 1708 2896 1702 2896 1709 2896 1702 2897 1707 2897 1709 2897 1703 2898 1710 2898 1705 2898 1710 2899 1703 2899 1708 2899 1711 2900 1706 2900 1705 2900 1712 2901 1705 2901 1710 2901 1705 2902 1712 2902 1711 2902 1712 2903 1713 2903 1711 2903 1709 2904 1714 2904 1708 2904 1708 2905 1715 2905 1710 2905 1715 2906 1708 2906 1714 2906 1710 2907 1716 2907 1712 2907 1716 2908 1710 2908 1715 2908 1714 2909 1717 2909 1715 2909 1715 2910 1718 2910 1719 2910 1715 2911 1717 2911 1718 2911 1715 2912 1719 2912 1716 2912 1712 2913 1716 2913 1720 2913 1716 2914 1719 2914 1720 2914 1721 2915 1722 2915 1522 2915 1722 2916 1523 2916 1522 2916 1722 2917 1721 2917 1723 2917 1522 2918 1724 2918 1721 2918 1670 2919 1721 2919 1668 2919 1721 2920 1724 2920 1668 2920 1721 2921 1670 2921 1723 2921 1713 2922 1723 2922 1711 2922 1723 2923 1725 2923 1711 2923 1725 2924 1723 2924 1669 2924 1723 2925 1670 2925 1669 2925 1706 2926 1711 2926 1725 2926 1669 2927 1726 2927 1725 2927 1725 2928 1727 2928 1706 2928 1727 2929 1704 2929 1706 2929 1727 2930 1725 2930 1728 2930 1725 2931 1726 2931 1728 2931 1728 2932 1729 2932 1727 2932 1700 2933 1704 2933 1727 2933 1730 2934 1727 2934 1731 2934 1727 2935 1729 2935 1731 2935 1727 2936 1730 2936 1700 2936 1730 2937 1695 2937 1700 2937 1731 2938 1732 2938 1730 2938 1692 2939 1695 2939 1730 2939 1730 2940 1732 2940 1733 2940 1730 2941 1733 2941 1692 2941 1692 2942 1733 2942 1734 2942 1728 2943 1726 2943 1683 2943 1726 2944 1684 2944 1683 2944 1679 2945 1684 2945 1726 2945 1726 2946 1669 2946 1679 2946 1680 2947 1679 2947 1669 2947 1669 2948 1668 2948 1680 2948 1668 2949 1681 2949 1680 2949 1677 2950 1681 2950 1668 2950 1668 2951 1724 2951 1677 2951 1685 2952 1677 2952 1724 2952 1724 2953 1522 2953 1685 2953 1490 2954 1685 2954 1522 2954 1718 2955 1735 2955 1719 2955 1735 2956 1720 2956 1719 2956 1644 2957 1712 2957 1720 2957 1644 2958 1713 2958 1712 2958 1644 2959 1736 2959 1713 2959 1644 2960 1645 2960 1736 2960 1644 2961 1720 2961 1735 2961 1735 2962 1651 2962 1644 2962 1644 2963 1651 2963 1628 2963 1592 2964 1523 2964 1722 2964 1737 2965 1722 2965 1723 2965 1722 2966 1737 2966 1592 2966 1593 2967 1592 2967 1737 2967 1713 2968 1736 2968 1723 2968 1736 2969 1737 2969 1723 2969 1737 2970 1645 2970 1648 2970 1737 2971 1736 2971 1645 2971 1737 2972 1648 2972 1593 2972 1595 2973 1593 2973 1648 2973 1634 2974 1633 2974 1733 2974 1733 2975 1732 2975 1634 2975 1636 583 1634 583 1732 583 1732 2976 1731 2976 1636 2976 1637 2977 1636 2977 1731 2977 1731 2978 1729 2978 1637 2978 1639 2979 1637 2979 1683 2979 1637 2980 1729 2980 1683 2980 1729 2981 1728 2981 1683 2981 1683 583 1682 583 1639 583 1640 2982 1639 2982 1682 2982 1682 2983 1678 2983 1640 2983 1642 583 1640 583 1678 583 1678 583 1676 583 1642 583 1671 583 1642 583 1676 583 1676 583 1674 583 1671 583 1673 583 1671 583 1674 583 1707 64 1701 64 1738 64 1709 64 1707 64 1739 64 1714 64 1709 64 1740 64 1717 64 1714 64 1741 64 1742 64 1718 64 1717 64 1735 2984 1718 2984 1654 2984 1718 64 1742 64 1654 64 1741 2985 1742 2985 1717 2985 1740 64 1741 64 1714 64 1739 64 1740 64 1709 64 1738 2986 1739 2986 1707 2986 1743 2987 1738 2987 1701 2987 1701 64 1696 64 1743 64 1744 64 1743 64 1696 64 1696 2988 1688 2988 1744 2988 1745 2989 1744 2989 1688 2989 1688 64 1746 64 1745 64 1747 64 1745 64 1746 64 1733 2990 1633 2990 1662 2990 1748 2991 1733 2991 1662 2991 1663 2992 1749 2992 1750 2992 1663 2993 1750 2993 1751 2993 1663 2994 1751 2994 1752 2994 1663 2995 1752 2995 1753 2995 1663 2996 1753 2996 1754 2996 1663 2997 1754 2997 1755 2997 1663 2998 1755 2998 1756 2998 1663 2999 1756 2999 1757 2999 1663 3000 1757 3000 1748 3000 1662 3001 1663 3001 1748 3001 1758 3002 1749 3002 1663 3002 1757 3003 1759 3003 1760 3003 1748 3004 1757 3004 1760 3004 1761 3005 1759 3005 1757 3005 1757 3006 1756 3006 1761 3006 1762 3007 1761 3007 1756 3007 1756 3008 1755 3008 1762 3008 1763 3009 1762 3009 1755 3009 1755 3010 1754 3010 1763 3010 1764 3011 1763 3011 1754 3011 1754 3012 1753 3012 1764 3012 1765 3013 1764 3013 1753 3013 1753 3014 1752 3014 1765 3014 1751 3015 1750 3015 1766 3015 1750 3016 1749 3016 1766 3016 1767 3017 1768 3017 1758 3017 1759 3018 1769 3018 1770 3018 1760 3019 1759 3019 1770 3019 1771 3020 1745 3020 1747 3020 1771 3021 1747 3021 1772 3021 1771 3022 1772 3022 1773 3022 1774 3023 1771 3023 1773 3023 1774 3024 1773 3024 1775 3024 1774 3025 1775 3025 1776 3025 1769 3026 1774 3026 1776 3026 1774 3027 1769 3027 1759 3027 1759 3028 1761 3028 1774 3028 1744 3029 1745 3029 1771 3029 1777 3030 1743 3030 1744 3030 1771 3031 1777 3031 1744 3031 1777 3032 1771 3032 1774 3032 1774 3033 1761 3033 1762 3033 1778 3034 1774 3034 1762 3034 1774 3035 1778 3035 1777 3035 1762 3036 1763 3036 1778 3036 1738 3037 1743 3037 1777 3037 1779 3038 1777 3038 1778 3038 1777 3039 1779 3039 1738 3039 1778 3040 1780 3040 1779 3040 1778 3041 1763 3041 1764 3041 1780 3042 1778 3042 1764 3042 1739 3043 1738 3043 1779 3043 1764 3044 1765 3044 1780 3044 1781 3045 1779 3045 1780 3045 1781 3046 1740 3046 1739 3046 1779 3047 1781 3047 1739 3047 1780 3048 1782 3048 1781 3048 1780 3049 1765 3049 1766 3049 1780 3050 1766 3050 1782 3050 1741 3051 1740 3051 1781 3051 1783 3052 1781 3052 1782 3052 1781 3053 1783 3053 1741 3053 1742 3054 1741 3054 1783 3054 1782 3055 1766 3055 1768 3055 1782 3056 1784 3056 1785 3056 1783 3057 1786 3057 1787 3057 1788 3058 1783 3058 1787 3058 1783 3059 1788 3059 1742 3059 1742 3060 1788 3060 1789 3060 1654 3061 1742 3061 1789 3061 1692 3062 1734 3062 1790 3062 1693 3063 1692 3063 1790 3063 1691 3064 1693 3064 1791 3064 1694 3065 1691 3065 1791 3065 1689 3066 1694 3066 1690 3066 1686 3067 1690 3067 1687 3067 1688 3068 1687 3068 1792 3068 1746 3069 1688 3069 1792 3069 1693 3070 1790 3070 1760 3070 1760 3071 1790 3071 1734 3071 1760 3072 1734 3072 1733 3072 1748 3073 1760 3073 1733 3073 1746 3074 1792 3074 1747 3074 1772 3075 1747 3075 1792 3075 1792 3076 1687 3076 1772 3076 1773 3077 1772 3077 1687 3077 1687 3078 1690 3078 1773 3078 1775 3079 1773 3079 1690 3079 1776 3080 1775 3080 1690 3080 1690 3081 1694 3081 1776 3081 1769 3082 1776 3082 1694 3082 1694 3083 1791 3083 1769 3083 1770 3084 1769 3084 1791 3084 1791 3085 1693 3085 1770 3085 1760 3086 1770 3086 1693 3086 1786 3087 1782 3087 1785 3087 1786 3088 1783 3088 1782 3088 1767 3089 1784 3089 1768 3089 1768 3090 1784 3090 1782 3090 1758 3091 1768 3091 1749 3091 1749 3092 1768 3092 1766 3092 1751 3093 1766 3093 1765 3093 1751 3094 1765 3094 1752 3094 1651 3095 1735 3095 1654 3095 1793 3096 1663 3096 1658 3096 1794 3097 1627 3097 1626 3097 1795 64 1796 64 1654 64 1797 3098 1795 3098 1654 3098 1627 3099 1794 3099 1798 3099 1664 3100 1799 3100 1800 3100 1664 3101 1800 3101 1798 3101 1798 3102 1794 3102 1664 3102 1664 3103 1794 3103 1626 3103 1664 182 1626 182 1801 182 1801 3104 1802 3104 1803 3104 1801 182 1626 182 1802 182 1796 64 1652 64 1654 64 1623 3105 1804 3105 1600 3105 1805 3106 1614 3106 1806 3106 1806 3107 1807 3107 1805 3107 1611 3108 1805 3108 1807 3108 1807 3109 1625 3109 1611 3109 1808 3110 1809 3110 1810 3110 1811 3111 1806 3111 1614 3111 1811 3112 1614 3112 1812 3112 1811 3113 1812 3113 1809 3113 1809 3114 1808 3114 1813 3114 1811 3115 1809 3115 1813 3115 1807 3116 1806 3116 1811 3116 1813 3117 1814 3117 1811 3117 1622 3118 1625 3118 1807 3118 1811 3119 1622 3119 1807 3119 1622 3120 1811 3120 1814 3120 1814 3121 1815 3121 1622 3121 1623 3122 1622 3122 1815 3122 1815 3123 1804 3123 1623 3123 1816 3124 1817 3124 1818 3124 1818 3125 1815 3125 1819 3125 1818 3126 1817 3126 1804 3126 1818 3127 1804 3127 1815 3127 1819 3128 1815 3128 1814 3128 1819 3129 1814 3129 1820 3129 1820 3130 1814 3130 1813 3130 1821 3131 1813 3131 1808 3131 1600 3132 1804 3132 1817 3132 1590 3133 1817 3133 1816 3133 1588 3134 1600 3134 1817 3134 1822 3135 1823 3135 1616 3135 1822 3136 1616 3136 1613 3136 1621 3137 1822 3137 1613 3137 1824 3138 1823 3138 1822 3138 1825 3139 1822 3139 1621 3139 1822 3140 1825 3140 1824 3140 1621 3141 1619 3141 1825 3141 1826 3142 1824 3142 1825 3142 1825 3143 1827 3143 1826 3143 1827 3144 1825 3144 1619 3144 1619 3145 1828 3145 1827 3145 1828 3146 1619 3146 1618 3146 1829 3147 1826 3147 1827 3147 1618 3148 1830 3148 1828 3148 1830 3149 1618 3149 1629 3149 1831 3150 1829 3150 1827 3150 1831 3151 1827 3151 1828 3151 1629 3152 1627 3152 1830 3152 1799 3153 1831 3153 1828 3153 1828 3154 1800 3154 1799 3154 1800 3155 1828 3155 1830 3155 1798 3156 1830 3156 1627 3156 1830 3157 1798 3157 1800 3157 1664 3158 1829 3158 1831 3158 1664 3159 1831 3159 1799 3159 1829 3160 1606 3160 1826 3160 1824 3161 1826 3161 1606 3161 1823 3162 1824 3162 1606 3162 1606 3163 1832 3163 1823 3163 1823 3164 1832 3164 1833 3164 1616 3165 1823 3165 1833 3165 1834 3166 1616 3166 1833 3166 1835 3167 1834 3167 1833 3167 1833 3168 1836 3168 1835 3168 1835 3169 1836 3169 1837 3169 1834 3170 1835 3170 1838 3170 1838 3171 1614 3171 1834 3171 1616 3172 1834 3172 1614 3172 1614 3173 1805 3173 1615 3173 1839 3174 1613 3174 1616 3174 1839 3175 1616 3175 1615 3175 1839 3176 1615 3176 1805 3176 1839 3177 1609 3177 1613 3177 1839 3178 1805 3178 1611 3178 1609 3179 1839 3179 1611 3179 1840 3180 1841 3180 1821 3180 1842 3181 1821 3181 1808 3181 1821 3182 1842 3182 1840 3182 1808 3183 1810 3183 1842 3183 1843 3184 1842 3184 1810 3184 1843 3185 1844 3185 1840 3185 1842 3186 1843 3186 1840 3186 1810 3187 1809 3187 1843 3187 1845 3188 1843 3188 1809 3188 1843 3189 1845 3189 1844 3189 1809 3190 1812 3190 1845 3190 1838 3191 1837 3191 1844 3191 1845 3192 1838 3192 1844 3192 1845 3193 1812 3193 1614 3193 1845 3194 1614 3194 1838 3194 1837 3195 1838 3195 1835 3195 1846 3196 1847 3196 1848 3196 1846 3197 1841 3197 1840 3197 1847 3198 1846 3198 1840 3198 1848 3199 1607 3199 1467 3199 1607 3200 1848 3200 1847 3200 1465 3201 1467 3201 1607 3201 1847 3202 1849 3202 1607 3202 1471 3203 1607 3203 1849 3203 1849 3204 1606 3204 1471 3204 1832 3205 1606 3205 1849 3205 1833 3206 1832 3206 1849 3206 1849 3207 1836 3207 1833 3207 1849 3208 1844 3208 1837 3208 1849 3209 1837 3209 1836 3209 1840 3210 1849 3210 1847 3210 1840 3211 1844 3211 1849 3211 1664 3212 1606 3212 1829 3212 1664 3213 1441 3213 1606 3213 1850 3214 1851 3214 1852 3214 1853 3215 1851 3215 1850 3215 1850 3216 1854 3216 1853 3216 1854 3217 1855 3217 1853 3217 1856 3218 1855 3218 1854 3218 1857 3219 1856 3219 1854 3219 1854 3220 1858 3220 1857 3220 1859 3221 1857 3221 1858 3221 1860 3222 1859 3222 1858 3222 1861 3223 1862 3223 1860 3223 1863 3224 1862 3224 1861 3224 1470 3225 1467 3225 1468 3225 1864 3226 1470 3226 1469 3226 1469 3227 1520 3227 1864 3227 1865 3228 1864 3228 1520 3228 1520 3229 1521 3229 1865 3229 1866 3230 1865 3230 1521 3230 1521 3231 1867 3231 1866 3231 1868 3232 1866 3232 1867 3232 1867 3233 1869 3233 1868 3233 1870 3234 1868 3234 1871 3234 1852 3235 1872 3235 1850 3235 1873 3236 1874 3236 1852 3236 1874 3237 1873 3237 1875 3237 1876 3238 1877 3238 1878 3238 1876 3239 1879 3239 1877 3239 1876 3240 1875 3240 1879 3240 1878 3241 1880 3241 1881 3241 1882 3242 1881 3242 1883 3242 1883 3243 1884 3243 1882 3243 1881 3244 1885 3244 1883 3244 1881 3245 1880 3245 1885 3245 1886 3246 1887 3246 1884 3246 1887 3247 1882 3247 1884 3247 1888 3248 1882 3248 1887 3248 1887 3249 1889 3249 1888 3249 1889 3250 1890 3250 1891 3250 1890 3251 1892 3251 1893 3251 1893 3252 1892 3252 1870 3252 1467 3253 1470 3253 1848 3253 1894 3254 1841 3254 1846 3254 1895 3255 1848 3255 1864 3255 1848 3256 1470 3256 1864 3256 1848 3257 1895 3257 1846 3257 1896 3258 1846 3258 1895 3258 1846 3259 1896 3259 1894 3259 1896 3260 1897 3260 1894 3260 1864 3261 1865 3261 1895 3261 1898 3262 1897 3262 1896 3262 1899 3263 1895 3263 1866 3263 1895 3264 1865 3264 1866 3264 1895 3265 1899 3265 1896 3265 1900 3266 1896 3266 1899 3266 1896 3267 1900 3267 1898 3267 1900 3268 1901 3268 1898 3268 1866 3269 1868 3269 1899 3269 1902 3270 1901 3270 1900 3270 1899 3271 1890 3271 1900 3271 1899 3272 1892 3272 1890 3272 1899 3273 1870 3273 1892 3273 1899 3274 1868 3274 1870 3274 1886 3275 1900 3275 1887 3275 1900 3276 1889 3276 1887 3276 1900 3277 1890 3277 1889 3277 1900 3278 1886 3278 1902 3278 1903 3279 1904 3279 1905 3279 1903 3280 1906 3280 1904 3280 1903 3281 1907 3281 1906 3281 1906 3282 1908 3282 1904 3282 1908 3283 1905 3283 1904 3283 1908 3284 1909 3284 1905 3284 1910 3285 1911 3285 1909 3285 1910 3286 1909 3286 1908 3286 1908 3287 1912 3287 1910 3287 1913 3288 1910 3288 1912 3288 1910 3289 1913 3289 1914 3289 1912 3290 1915 3290 1913 3290 1913 3291 1916 3291 1917 3291 1913 3292 1918 3292 1916 3292 1913 3293 1919 3293 1918 3293 1913 3294 1915 3294 1919 3294 1920 3295 1921 3295 1821 3295 1920 3296 1821 3296 1841 3296 1841 3297 1894 3297 1920 3297 1922 3298 1921 3298 1920 3298 1923 3299 1920 3299 1894 3299 1920 3300 1923 3300 1922 3300 1894 3301 1897 3301 1923 3301 1924 3302 1922 3302 1923 3302 1925 3303 1923 3303 1897 3303 1923 3304 1925 3304 1924 3304 1897 3305 1898 3305 1925 3305 1926 3306 1924 3306 1925 3306 1927 3307 1925 3307 1898 3307 1925 3308 1927 3308 1926 3308 1928 3309 1926 3309 1927 3309 1898 3310 1901 3310 1927 3310 1927 3311 1929 3311 1928 3311 1929 3312 1927 3312 1901 3312 1930 3313 1928 3313 1929 3313 1901 3314 1902 3314 1929 3314 1931 3315 1929 3315 1902 3315 1929 3316 1931 3316 1930 3316 1919 3317 1930 3317 1931 3317 1902 3318 1886 3318 1931 3318 1931 3319 1932 3319 1919 3319 1932 3320 1931 3320 1884 3320 1931 3321 1886 3321 1884 3321 1918 3322 1919 3322 1932 3322 1884 3323 1883 3323 1932 3323 1932 3324 1933 3324 1918 3324 1933 3325 1916 3325 1918 3325 1933 3326 1932 3326 1883 3326 1883 3327 1885 3327 1933 3327 1933 3328 1880 3328 1916 3328 1880 3329 1934 3329 1916 3329 1933 3330 1885 3330 1880 3330 1880 3331 1878 3331 1934 3331 1878 3332 1877 3332 1934 3332 1877 3333 1879 3333 1934 3333 1590 3334 1583 3334 1588 3334 1582 3335 1935 3335 1584 3335 1935 3336 1582 3336 1590 3336 1936 3337 1584 3337 1935 3337 1584 3338 1936 3338 1586 3338 1937 3339 1586 3339 1936 3339 1586 3340 1937 3340 1938 3340 1937 3341 1939 3341 1938 3341 1588 3342 1817 3342 1590 3342 1590 3343 1940 3343 1935 3343 1940 3344 1590 3344 1941 3344 1590 3345 1816 3345 1941 3345 1942 3346 1935 3346 1943 3346 1935 3347 1940 3347 1943 3347 1935 3348 1942 3348 1936 3348 1936 3349 1944 3349 1937 3349 1936 3350 1945 3350 1944 3350 1936 3351 1942 3351 1945 3351 1907 3352 1939 3352 1937 3352 1946 3353 1937 3353 1947 3353 1937 3354 1948 3354 1947 3354 1937 3355 1944 3355 1948 3355 1937 3356 1946 3356 1907 3356 1906 3357 1907 3357 1949 3357 1907 3358 1946 3358 1949 3358 1820 3359 1813 3359 1821 3359 1821 3360 1921 3360 1820 3360 1820 3361 1950 3361 1819 3361 1950 3362 1820 3362 1922 3362 1820 3363 1921 3363 1922 3363 1951 3364 1819 3364 1950 3364 1819 3365 1951 3365 1818 3365 1952 3366 1818 3366 1951 3366 1818 3367 1952 3367 1816 3367 1952 3368 1941 3368 1816 3368 1940 3369 1941 3369 1952 3369 1922 3370 1924 3370 1950 3370 1950 3371 1953 3371 1951 3371 1953 3372 1950 3372 1924 3372 1954 3373 1951 3373 1953 3373 1951 3374 1954 3374 1952 3374 1952 3375 1955 3375 1940 3375 1955 3376 1943 3376 1940 3376 1955 3377 1952 3377 1954 3377 1942 3378 1943 3378 1955 3378 1924 3379 1926 3379 1953 3379 1953 3380 1956 3380 1954 3380 1956 3381 1953 3381 1926 3381 1954 3382 1957 3382 1955 3382 1957 3383 1954 3383 1956 3383 1958 3384 1955 3384 1957 3384 1955 3385 1958 3385 1942 3385 1958 3386 1945 3386 1942 3386 1958 3387 1944 3387 1945 3387 1926 3388 1928 3388 1956 3388 1948 3389 1944 3389 1958 3389 1959 3390 1956 3390 1928 3390 1956 3391 1959 3391 1957 3391 1957 3392 1960 3392 1958 3392 1960 3393 1957 3393 1959 3393 1958 3394 1961 3394 1948 3394 1961 3395 1947 3395 1948 3395 1961 3396 1958 3396 1960 3396 1928 3397 1930 3397 1959 3397 1946 3398 1947 3398 1961 3398 1959 3399 1915 3399 1960 3399 1959 3400 1919 3400 1915 3400 1959 3401 1930 3401 1919 3401 1960 3402 1915 3402 1912 3402 1960 3403 1912 3403 1961 3403 1961 3404 1908 3404 1946 3404 1908 3405 1949 3405 1946 3405 1961 3406 1912 3406 1908 3406 1906 3407 1949 3407 1908 3407 1962 3408 1853 3408 1855 3408 1962 3409 1851 3409 1853 3409 1962 3410 1852 3410 1851 3410 1962 3411 1873 3411 1852 3411 1962 3412 1875 3412 1873 3412 1934 3413 1879 3413 1875 3413 1963 3414 1964 3414 1965 3414 1963 3415 1965 3415 1966 3415 1967 3416 1963 3416 1966 3416 1938 3417 1968 3417 1586 3417 1585 3418 1586 3418 1968 3418 1968 3419 1969 3419 1585 3419 1585 3420 1970 3420 1580 3420 1970 3421 1585 3421 1969 3421 1969 3422 1971 3422 1970 3422 1972 3423 1556 3423 1557 3423 1973 3424 1972 3424 1557 3424 1974 3425 1973 3425 1557 3425 1974 3426 1557 3426 1975 3426 1976 3427 1974 3427 1975 3427 1977 3428 1976 3428 1975 3428 1978 3429 1977 3429 1975 3429 1979 3430 1978 3430 1975 3430 1980 3431 1978 3431 1979 3431 1910 3432 1981 3432 1911 3432 1982 3433 1909 3433 1911 3433 1982 3434 1911 3434 1981 3434 1982 3435 1981 3435 1983 3435 1909 3436 1903 3436 1905 3436 1903 3437 1909 3437 1982 3437 1939 3438 1907 3438 1903 3438 1983 3439 1984 3439 1982 3439 1982 3440 1985 3440 1903 3440 1985 3441 1982 3441 1984 3441 1986 3442 1903 3442 1985 3442 1903 3443 1986 3443 1939 3443 1938 3444 1939 3444 1986 3444 1984 3445 1987 3445 1985 3445 1988 3446 1985 3446 1987 3446 1985 3447 1988 3447 1986 3447 1987 3448 1989 3448 1988 3448 1990 3449 1968 3449 1938 3449 1986 3450 1990 3450 1938 3450 1990 3451 1986 3451 1988 3451 1969 3452 1968 3452 1990 3452 1988 3453 1991 3453 1990 3453 1988 3454 1989 3454 1992 3454 1991 3455 1988 3455 1992 3455 1992 3456 1993 3456 1991 3456 1994 3457 1990 3457 1991 3457 1990 3458 1994 3458 1969 3458 1971 3459 1969 3459 1994 3459 1995 3460 1991 3460 1993 3460 1991 3461 1995 3461 1994 3461 1993 3462 1996 3462 1995 3462 1994 3463 1997 3463 1971 3463 1997 3464 1994 3464 1995 3464 1995 3465 1996 3465 1998 3465 1999 583 1993 583 2000 583 1993 583 1999 583 1967 583 1993 3466 1967 3466 1966 3466 1993 3467 1966 3467 2001 3467 1996 3468 1993 3468 2001 3468 2002 3469 1964 3469 2003 3469 2004 3470 2003 3470 1964 3470 2002 3471 2005 3471 1964 3471 1965 3472 1964 3472 2005 3472 2005 3473 2001 3473 1965 3473 1966 3474 1965 3474 2001 3474 2006 3475 2007 3475 2008 3475 2009 3476 2008 3476 2007 3476 2007 3477 2010 3477 2009 3477 2011 3478 2009 3478 2010 3478 2010 3479 2012 3479 2011 3479 2013 3480 2011 3480 2012 3480 2012 3481 2014 3481 2013 3481 2015 3482 2013 3482 2014 3482 2014 3483 2016 3483 2015 3483 2017 3484 2015 3484 2016 3484 2016 3485 2018 3485 2017 3485 2019 3486 2017 3486 2018 3486 2018 3487 1980 3487 2019 3487 1979 3488 2019 3488 1980 3488 1980 3489 2018 3489 1978 3489 2020 3490 1978 3490 2018 3490 2020 3491 2021 3491 1976 3491 2020 3492 1976 3492 1977 3492 1978 3493 2020 3493 1977 3493 2022 3494 2021 3494 2020 3494 2018 3495 2016 3495 2020 3495 2020 3496 2016 3496 2014 3496 2023 3497 2020 3497 2014 3497 2023 3498 2024 3498 2022 3498 2020 3499 2023 3499 2022 3499 2025 3500 2024 3500 2023 3500 2014 3501 2012 3501 2023 3501 2023 3502 2012 3502 2010 3502 2026 3503 2023 3503 2010 3503 2026 3504 2027 3504 2025 3504 2023 3505 2026 3505 2025 3505 2028 3506 2027 3506 2026 3506 2010 3507 2007 3507 2026 3507 2026 3508 2029 3508 2028 3508 2026 3509 2007 3509 2006 3509 2026 3510 2006 3510 2030 3510 2026 3511 2030 3511 2031 3511 2029 3512 2026 3512 2031 3512 2028 3513 2029 3513 2032 3513 2033 3514 2028 3514 2032 3514 1871 3515 2034 3515 2033 3515 2028 3516 2033 3516 2034 3516 2034 3517 2035 3517 2028 3517 2027 3518 2028 3518 2035 3518 2035 3519 2036 3519 2027 3519 2025 3520 2027 3520 2036 3520 2036 3521 2037 3521 2025 3521 2024 3522 2025 3522 2037 3522 2037 3523 2038 3523 2024 3523 2022 3524 2024 3524 2038 3524 2038 3525 2039 3525 2022 3525 2021 3526 2022 3526 2039 3526 2039 3527 1974 3527 2021 3527 1976 3528 2021 3528 1974 3528 1869 3529 2035 3529 2034 3529 1871 3530 1869 3530 2034 3530 2040 3531 2038 3531 2037 3531 2040 3532 2037 3532 2036 3532 2035 3533 2040 3533 2036 3533 2040 3534 2035 3534 1869 3534 2041 3535 1973 3535 1974 3535 2041 3536 1974 3536 2039 3536 2041 3537 2039 3537 2038 3537 2041 3538 2038 3538 2040 3538 1869 3539 1867 3539 2040 3539 1972 3540 1973 3540 2041 3540 2040 3541 1867 3541 1521 3541 1519 3542 2040 3542 1521 3542 2040 3543 1519 3543 2041 3543 1517 3544 1556 3544 1972 3544 2041 3545 1517 3545 1972 3545 1517 3546 2041 3546 1519 3546 1518 3547 1556 3547 1517 3547 2042 3548 1893 3548 1870 3548 1893 3549 1891 3549 1890 3549 1891 3550 1888 3550 1889 3550 1881 3551 1876 3551 1878 3551 2006 3552 2043 3552 2044 3552 2008 3553 2043 3553 2006 3553 2033 3554 2032 3554 2042 3554 2045 3555 2042 3555 2032 3555 2032 3556 2029 3556 2045 3556 2046 3557 2045 3557 2029 3557 2029 3558 2031 3558 2046 3558 2047 3559 2046 3559 2031 3559 2031 3560 2030 3560 2047 3560 2048 3561 2047 3561 2030 3561 2030 3562 2006 3562 2048 3562 2044 3563 2048 3563 2006 3563 2042 3564 1870 3564 2033 3564 1871 3565 2033 3565 1870 3565 1868 3566 1869 3566 1871 3566 2049 3567 2050 3567 2051 3567 1989 3568 2052 3568 2053 3568 1992 3569 1989 3569 2053 3569 2054 3570 2049 3570 2051 3570 2054 3571 2051 3571 2055 3571 2052 3572 2054 3572 2055 3572 2054 3573 2052 3573 1989 3573 2056 3574 2049 3574 2054 3574 2056 3575 2057 3575 2049 3575 1989 3576 1987 3576 2054 3576 2054 3577 2058 3577 2056 3577 2058 3578 2054 3578 1987 3578 2059 3579 2057 3579 2056 3579 2056 3580 2060 3580 2059 3580 2060 3581 2056 3581 2058 3581 1987 3582 1984 3582 2058 3582 2061 3583 2059 3583 2060 3583 2058 3584 2062 3584 2060 3584 2062 3585 2058 3585 1984 3585 1984 3586 1983 3586 2062 3586 2063 3587 2060 3587 2062 3587 2064 3588 2065 3588 2050 3588 2051 3589 2050 3589 2065 3589 2065 3590 2066 3590 2051 3590 2055 3591 2051 3591 2066 3591 2066 3592 2067 3592 2055 3592 2052 3593 2055 3593 2067 3593 2067 3594 2068 3594 2052 3594 2053 3595 2052 3595 2068 3595 2069 3596 1992 3596 2053 3596 2068 3597 2069 3597 2053 3597 1993 3598 1992 3598 2069 3598 2069 3599 2070 3599 1993 3599 2070 3600 2071 3600 1993 3600 1993 583 2071 583 2000 583 1801 3601 1975 3601 1557 3601 1801 3602 1557 3602 2072 3602 2073 3603 2074 3603 2075 3603 2075 3604 2074 3604 2076 3604 2076 3605 2074 3605 2077 3605 2078 3606 2076 3606 2077 3606 2079 3607 2078 3607 2077 3607 2079 3608 2077 3608 2080 3608 2081 3609 2079 3609 2080 3609 2081 3610 2080 3610 2082 3610 2083 3611 2081 3611 2082 3611 2083 3612 2082 3612 2084 3612 2085 3613 2083 3613 2084 3613 2085 3614 2084 3614 2086 3614 2087 3615 2085 3615 2086 3615 2087 3616 2086 3616 2088 3616 2087 3617 2088 3617 2089 3617 2090 3618 2089 3618 2088 3618 2091 3619 2092 3619 2093 3619 2094 64 2095 64 2096 64 2097 64 2096 64 2095 64 2074 3620 2098 3620 2077 3620 2099 3621 2100 3621 2098 3621 2098 3622 2074 3622 2099 3622 2074 3623 2101 3623 2099 3623 2074 3624 2073 3624 2101 3624 2100 3625 2091 3625 2093 3625 2093 3626 2098 3626 2100 3626 2093 3627 2102 3627 2103 3627 2093 3628 2092 3628 2102 3628 2104 3629 2093 3629 2103 3629 2093 3630 2104 3630 2098 3630 2104 3631 2105 3631 2098 3631 2106 3632 2107 3632 2108 3632 2108 3633 2103 3633 2106 3633 2103 3634 2102 3634 2106 3634 2103 3635 2108 3635 2104 3635 2108 3636 2105 3636 2104 3636 2108 3637 2098 3637 2105 3637 2077 3638 2098 3638 2108 3638 2108 3639 2109 3639 2077 3639 2080 3640 2077 3640 2109 3640 2109 3641 2110 3641 2080 3641 2082 64 2080 64 2110 64 2084 3642 2082 3642 2111 3642 2112 64 2086 64 2084 64 2088 64 2086 64 2112 64 2078 3643 2113 3643 1570 3643 1570 3644 2114 3644 2078 3644 2114 3645 2076 3645 2078 3645 2076 3646 2114 3646 2115 3646 2075 3647 2116 3647 2117 3647 2076 3648 2116 3648 2075 3648 2118 3649 2119 3649 2120 3649 2119 3650 2121 3650 2120 3650 2122 3651 2121 3651 2119 3651 2119 3652 2123 3652 2122 3652 2124 3653 2122 3653 2123 3653 2123 3654 2125 3654 2124 3654 2126 3655 2124 3655 2125 3655 2125 3656 2127 3656 2126 3656 2128 3657 2126 3657 2127 3657 2127 3658 2129 3658 2101 3658 2101 3659 2128 3659 2127 3659 2129 3660 2099 3660 2101 3660 2129 3661 2100 3661 2099 3661 2128 3662 2073 3662 2075 3662 2128 3663 2101 3663 2073 3663 2129 3664 2130 3664 2100 3664 2091 3665 2100 3665 2130 3665 2130 3666 2131 3666 2091 3666 2131 3667 2092 3667 2091 3667 2102 3668 2092 3668 2106 3668 2092 3669 2131 3669 2106 3669 2132 3670 2106 3670 2131 3670 2096 3671 2097 3671 2133 3671 2134 3672 2133 3672 2097 3672 2135 3673 2136 3673 2137 3673 2138 3674 2137 3674 2136 3674 2136 3675 2133 3675 2138 3675 2134 3676 2138 3676 2133 3676 2139 3677 2096 3677 2002 3677 2001 3678 2136 3678 2135 3678 2001 3679 2133 3679 2136 3679 2001 3680 2096 3680 2133 3680 2001 3681 2005 3681 2096 3681 2005 3682 2002 3682 2096 3682 2140 3683 2132 3683 2130 3683 2132 583 2131 583 2130 583 2130 3684 2129 3684 2140 3684 2129 3685 2127 3685 2140 3685 2141 3686 2140 3686 2127 3686 2127 3687 2125 3687 2141 3687 2141 3688 2125 3688 2123 3688 2123 3689 2119 3689 2141 3689 2141 3690 2118 3690 2142 3690 2141 3691 2119 3691 2118 3691 2118 3692 1998 3692 2135 3692 2135 3693 2142 3693 2118 3693 2135 3694 2143 3694 2142 3694 2135 3695 2144 3695 2143 3695 2137 3696 2144 3696 2135 3696 2001 3697 2135 3697 1996 3697 2135 3698 1998 3698 1996 3698 2122 3699 2145 3699 2121 3699 2146 3700 2121 3700 2145 3700 2121 3701 2146 3701 2120 3701 2120 3702 2147 3702 2118 3702 2147 3703 2120 3703 2146 3703 1998 3704 2118 3704 2147 3704 2145 3705 1971 3705 2146 3705 1971 3706 1997 3706 2146 3706 2146 3707 1997 3707 2147 3707 1995 3708 2147 3708 1997 3708 2147 3709 1995 3709 1998 3709 1553 3710 2148 3710 1558 3710 1553 3711 2149 3711 2148 3711 1553 3712 1570 3712 2149 3712 2150 3713 1558 3713 2148 3713 2150 3714 2148 3714 2151 3714 2148 3715 2149 3715 2151 3715 2079 3716 2113 3716 2078 3716 2151 3717 2149 3717 2113 3717 2152 3718 2113 3718 2081 3718 2113 3719 2079 3719 2081 3719 2113 3720 2152 3720 2151 3720 2081 3721 2083 3721 2152 3721 2152 3722 2153 3722 2151 3722 2153 3723 2154 3723 2151 3723 2153 3724 2152 3724 2083 3724 2155 3725 2153 3725 2083 3725 2083 3726 2085 3726 2155 3726 2156 3727 2155 3727 2085 3727 2085 3728 2087 3728 2156 3728 2157 3729 2156 3729 2087 3729 2090 3730 2157 3730 2089 3730 2157 3731 2087 3731 2089 3731 2113 3732 2149 3732 1570 3732 1570 3733 2115 3733 2114 3733 2122 3734 2124 3734 2158 3734 2159 3735 2158 3735 2124 3735 2159 3736 1561 3736 2158 3736 2124 3737 2126 3737 2159 3737 1559 3738 1561 3738 2159 3738 2160 3739 2159 3739 2128 3739 2159 3740 2126 3740 2128 3740 2159 3741 2160 3741 1559 3741 1564 3742 1559 3742 2160 3742 2128 3743 2075 3743 2160 3743 2160 3744 2117 3744 1564 3744 2160 3745 2075 3745 2117 3745 1566 3746 1564 3746 2076 3746 1564 3747 2116 3747 2076 3747 1564 3748 2117 3748 2116 3748 1568 3749 1566 3749 2115 3749 1566 3750 2076 3750 2115 3750 1568 3751 2115 3751 1570 3751 1561 3752 1571 3752 2158 3752 2161 3753 2158 3753 1571 3753 2162 3754 2158 3754 2161 3754 2162 3755 2122 3755 2158 3755 2145 3756 2122 3756 2162 3756 1571 3757 1574 3757 2161 3757 1578 3758 2161 3758 1574 3758 2161 3759 1578 3759 2162 3759 2162 3760 1970 3760 2145 3760 1970 3761 1971 3761 2145 3761 1970 3762 2162 3762 1578 3762 1578 3763 1580 3763 1970 3763 2095 3764 2144 3764 2097 3764 2144 3765 2134 3765 2097 3765 2144 3766 2138 3766 2134 3766 2144 3767 2137 3767 2138 3767 2163 3768 2144 3768 2095 3768 2164 3769 2090 3769 2112 3769 2165 3770 2166 3770 2167 3770 2168 3771 2166 3771 2165 3771 2165 3772 2169 3772 2168 3772 2165 3773 2170 3773 2169 3773 2171 3774 2167 3774 2166 3774 2172 3775 2171 3775 2173 3775 2173 3776 2171 3776 2166 3776 2174 3777 2173 3777 2166 3777 2168 3778 2174 3778 2166 3778 2174 3779 2168 3779 2175 3779 2175 3780 2168 3780 2176 3780 2177 3781 2178 3781 2179 3781 2180 3782 2179 3782 2178 3782 2178 3783 2181 3783 2180 3783 2182 3784 2180 3784 2181 3784 2183 3785 2180 3785 2182 3785 2184 3786 2183 3786 2182 3786 2170 3787 2185 3787 2186 3787 2186 3788 2185 3788 2177 3788 2186 3789 2176 3789 2187 3789 2186 3790 2188 3790 2176 3790 2188 3791 2175 3791 2176 3791 2188 3792 2186 3792 2177 3792 2177 3793 2189 3793 2188 3793 2189 3794 2183 3794 2184 3794 2189 3795 2180 3795 2183 3795 2189 3796 2177 3796 2179 3796 2179 3797 2180 3797 2189 3797 2169 3798 2170 3798 2187 3798 2170 3799 2186 3799 2187 3799 2187 3800 2176 3800 2169 3800 2176 3801 2168 3801 2169 3801 2190 3802 2191 3802 2192 3802 2192 3803 2193 3803 2190 3803 2192 3804 2194 3804 2193 3804 2194 3805 2164 3805 2193 3805 2150 3806 2195 3806 1558 3806 2151 3807 2154 3807 2150 3807 2196 3808 2195 3808 2150 3808 2197 3809 2150 3809 2154 3809 2150 3810 2197 3810 2196 3810 2197 3811 2191 3811 2196 3811 2197 3812 2192 3812 2191 3812 2154 3813 2198 3813 2197 3813 2194 3814 2197 3814 2198 3814 2197 3815 2194 3815 2192 3815 2198 3816 2199 3816 2194 3816 2164 3817 2194 3817 2199 3817 2155 3818 2154 3818 2153 3818 2155 3819 2156 3819 2198 3819 2200 3820 2198 3820 2156 3820 2156 3821 2157 3821 2200 3821 2157 3822 2199 3822 2200 3822 2157 3823 2090 3823 2199 3823 2164 3824 2199 3824 2090 3824 2154 3825 2155 3825 2198 3825 2199 3826 2198 3826 2200 3826 2201 3827 2202 3827 2203 3827 2167 3828 2171 3828 2204 3828 2205 3829 2204 3829 2171 3829 2205 3830 2206 3830 2204 3830 2205 3831 2171 3831 2207 3831 2171 3832 2172 3832 2207 3832 2207 3833 2208 3833 2205 3833 2209 3834 2206 3834 2205 3834 2210 3835 2205 3835 2211 3835 2205 3836 2208 3836 2211 3836 2205 3837 2210 3837 2209 3837 2210 3838 2212 3838 2209 3838 2211 3839 2213 3839 2210 3839 2214 3840 2212 3840 2210 3840 2210 3841 2215 3841 1554 3841 2210 3842 2213 3842 2215 3842 2210 3843 1554 3843 2214 3843 2184 3844 2182 3844 2216 3844 2217 3845 2182 3845 2218 3845 2219 3846 2220 3846 2201 3846 1558 3847 2195 3847 1554 3847 2195 3848 2221 3848 1554 3848 2195 3849 2214 3849 2221 3849 2195 3850 2212 3850 2214 3850 2209 3851 2212 3851 2195 3851 2195 583 2196 583 2209 583 2196 3852 2206 3852 2209 3852 2196 583 2204 583 2206 583 2167 3853 2204 3853 2196 3853 2196 3854 2191 3854 2167 3854 2165 3855 2167 3855 2191 3855 2191 3856 2190 3856 2165 3856 2190 3857 2222 3857 2165 3857 2190 3858 2223 3858 2222 3858 1656 3859 2184 3859 2216 3859 2072 3860 1665 3860 1664 3860 1665 3861 2072 3861 2224 3861 2008 3862 1854 3862 1850 3862 2008 3863 1850 3863 1872 3863 1858 3864 1854 3864 2008 3864 1858 3865 1979 3865 2225 3865 1979 3866 2226 3866 2225 3866 2227 3867 2225 3867 2226 3867 1801 3868 1803 3868 2227 3868 2226 182 1801 182 2227 182 1801 3869 2072 3869 1664 3869 2184 3870 1656 3870 2228 3870 2189 3871 2184 3871 2228 3871 2229 64 1601 64 1551 64 2230 3872 1444 3872 2229 3872 1551 3873 2230 3873 2229 3873 1444 3874 2230 3874 2231 3874 1444 3875 2231 3875 2232 3875 1444 3876 2232 3876 2233 3876 1444 3877 2233 3877 2234 3877 1444 3878 2234 3878 2235 3878 1655 3879 1444 3879 2235 3879 2235 3880 2236 3880 1655 3880 1655 3881 2236 3881 2237 3881 1655 3882 2237 3882 2238 3882 1655 3883 2238 3883 2228 3883 1656 3884 1655 3884 2228 3884 2215 3885 1551 3885 1554 3885 2230 3886 1551 3886 2215 3886 2215 3887 2213 3887 2230 3887 2230 3888 2213 3888 2211 3888 2231 3889 2230 3889 2211 3889 2211 3890 2208 3890 2231 3890 2232 3891 2231 3891 2208 3891 2208 3892 2207 3892 2232 3892 2233 3893 2232 3893 2207 3893 2172 3894 2233 3894 2207 3894 2234 3895 2233 3895 2172 3895 2234 3896 2172 3896 2173 3896 2235 3897 2234 3897 2173 3897 2173 3898 2174 3898 2235 3898 2236 3899 2235 3899 2174 3899 2236 3900 2174 3900 2175 3900 2236 3901 2175 3901 2237 3901 2188 3902 2237 3902 2175 3902 2238 3903 2237 3903 2188 3903 2238 3904 2188 3904 2189 3904 2228 3905 2238 3905 2189 3905 1447 3906 1444 3906 1655 3906 1554 3907 1551 3907 1552 3907 1858 3908 1861 3908 1860 3908 1444 3909 1601 3909 2229 3909 2043 3910 2008 3910 1872 3910 1858 3911 2008 3911 2009 3911 1858 3912 2009 3912 2011 3912 1858 3913 2011 3913 2013 3913 1858 3914 2013 3914 2015 3914 1858 3915 2015 3915 2017 3915 1858 3916 2017 3916 2019 3916 1858 3917 2019 3917 1979 3917 2071 182 2070 182 1999 182 1999 3918 2070 3918 2069 3918 1999 3919 2069 3919 2068 3919 1999 3920 2068 3920 2067 3920 1999 3921 2067 3921 2066 3921 1999 3922 2066 3922 2065 3922 1999 3923 2065 3923 2064 3923 1999 3924 2064 3924 2239 3924 1999 3925 2239 3925 2240 3925 1999 3926 2240 3926 2241 3926 1999 3927 2241 3927 2242 3927 2243 3928 2244 3928 2245 3928 2243 3929 2216 3929 2217 3929 2244 3930 2243 3930 2217 3930 2243 3931 1656 3931 2216 3931 2246 3932 2247 3932 2142 3932 2248 3933 2247 3933 2246 3933 2249 3934 2250 3934 2248 3934 2219 3935 2201 3935 2203 3935 2219 3936 2251 3936 2220 3936 2251 3937 2252 3937 2253 3937 2252 3938 2217 3938 2218 3938 2217 3939 2216 3939 2182 3939 2143 3940 2144 3940 2163 3940 2142 3941 2143 3941 2254 3941 1999 496 2255 496 1967 496 2256 3942 2257 3942 2250 3942 2244 3943 2258 3943 2259 3943 2257 3944 2259 3944 2258 3944 2250 3945 2260 3945 2248 3945 2261 3946 2248 3946 2260 3946 2260 3947 2219 3947 2261 3947 2203 3948 2261 3948 2219 3948 2262 3949 2219 3949 2260 3949 2260 3950 2250 3950 2257 3950 2262 3951 2260 3951 2257 3951 2251 3952 2219 3952 2262 3952 2257 3953 2258 3953 2262 3953 2262 3954 2258 3954 2251 3954 2252 3955 2251 3955 2258 3955 2258 3956 2244 3956 2252 3956 2217 3957 2252 3957 2244 3957 2071 583 1999 583 2000 583 2247 3958 2141 3958 2142 3958 2112 3959 2263 3959 2264 3959 2263 3960 2265 3960 2264 3960 2265 3961 2266 3961 2264 3961 2247 3962 2264 3962 2141 3962 2140 3963 2107 3963 2106 3963 2141 3964 2266 3964 2140 3964 2141 3965 2264 3965 2266 3965 2140 3966 2106 3966 2132 3966 2226 3967 1979 3967 1975 3967 2111 64 2112 64 2084 64 2110 3968 2111 3968 2082 3968 2109 3969 2108 3969 2107 3969 2107 3970 2267 3970 2109 3970 2110 3971 2109 3971 2267 3971 2265 3972 2111 3972 2110 3972 2267 3973 2265 3973 2110 3973 2111 3974 2265 3974 2263 3974 2112 3975 2111 3975 2263 3975 2265 3976 2267 3976 2266 3976 2090 3977 2088 3977 2112 3977 2140 3978 2266 3978 2267 3978 2140 3979 2267 3979 2107 3979 2226 3980 1975 3980 1801 3980 2165 3981 2268 3981 2170 3981 2268 3982 2269 3982 2170 3982 2202 3983 2269 3983 2268 3983 2201 3984 2269 3984 2202 3984 2177 3985 2270 3985 2178 3985 2185 3986 2270 3986 2177 3986 2270 3987 2181 3987 2178 3987 2271 3988 2181 3988 2270 3988 2272 3989 2271 3989 2270 3989 2220 3990 2253 3990 2270 3990 2253 3991 2272 3991 2270 3991 2225 3992 2227 3992 2273 3992 2227 3993 2274 3993 2273 3993 2227 3994 1803 3994 2274 3994 2225 3995 2275 3995 2276 3995 2225 3996 2277 3996 2275 3996 2225 3997 2278 3997 2277 3997 2225 3998 2279 3998 2278 3998 2225 3999 2280 3999 2279 3999 2225 4000 2281 4000 2280 4000 2225 4001 2282 4001 2281 4001 2225 4002 2283 4002 2282 4002 2225 64 2273 64 2283 64 2181 4003 2271 4003 2182 4003 2271 4004 2272 4004 2182 4004 2218 4005 2182 4005 2272 4005 2270 4006 2201 4006 2220 4006 2270 4007 2269 4007 2201 4007 2270 4008 2185 4008 2269 4008 2170 4009 2269 4009 2185 4009 2284 4010 2285 4010 1797 4010 2286 4011 1797 4011 2285 4011 2285 4012 2287 4012 2286 4012 2288 4013 2286 4013 2287 4013 2287 4014 2289 4014 2288 4014 2290 4015 2288 4015 2289 4015 2289 4016 2291 4016 2290 4016 1802 4017 1667 4017 2292 4017 1667 4018 2293 4018 2292 4018 2294 4019 2293 4019 1653 4019 2293 4020 1667 4020 1653 4020 2294 4021 2295 4021 2293 4021 2296 4022 2297 4022 2298 4022 2299 4023 2295 4023 2294 4023 2299 4024 2298 4024 2295 4024 2299 4025 2296 4025 2298 4025 1653 4026 1652 4026 2294 4026 2300 4027 2294 4027 1796 4027 2294 4028 1652 4028 1796 4028 2294 4029 2300 4029 2299 4029 2299 4030 2301 4030 2296 4030 2301 4031 2302 4031 2296 4031 2301 4032 2299 4032 2300 4032 1796 4033 1795 4033 2300 4033 2300 4034 1797 4034 2286 4034 2300 4035 1795 4035 1797 4035 2300 4036 2286 4036 2301 4036 2303 4037 2302 4037 2301 4037 2301 4038 2286 4038 2288 4038 2301 4039 2288 4039 2303 4039 2303 4040 2288 4040 2290 4040 2290 4041 2291 4041 2304 4041 2297 4042 2273 4042 2305 4042 2273 4043 2306 4043 2305 4043 2273 4044 2274 4044 2306 4044 2274 4045 1803 4045 2306 4045 2273 4046 2297 4046 2296 4046 2307 4047 2296 4047 2302 4047 2296 4048 2307 4048 2273 4048 2283 4049 2273 4049 2307 4049 2302 4050 2303 4050 2307 4050 2282 4051 2283 4051 2307 4051 2282 4052 2307 4052 2303 4052 2303 4053 2290 4053 2282 4053 2281 4054 2282 4054 2290 4054 2290 4055 2304 4055 2281 4055 2280 4056 2281 4056 2304 4056 2279 4057 2280 4057 2304 4057 1654 4058 1789 4058 1146 4058 1163 4059 1789 4059 1788 4059 1788 4060 1787 4060 1166 4060 1786 4061 1168 4061 1787 4061 1169 4062 1786 4062 1785 4062 1785 4063 1784 4063 1173 4063 2268 4064 2222 4064 2223 4064 2222 4065 2268 4065 2165 4065 1554 4066 2221 4066 2214 4066 2252 4067 2218 4067 2272 4067 2272 4068 2253 4068 2252 4068 2251 4069 2253 4069 2220 4069 1667 4070 1802 4070 1626 4070 1802 182 2292 182 1803 182 2306 182 1803 182 2292 182 2292 4071 2293 4071 2306 4071 2305 4072 2306 4072 2293 4072 2297 4073 2305 4073 2295 4073 2305 4074 2293 4074 2295 4074 2298 4075 2297 4075 2295 4075 1403 4076 2308 4076 1148 4076 1148 4077 2308 4077 2309 4077 1148 4078 2309 4078 2310 4078 1148 4079 2310 4079 2311 4079 1148 64 2311 64 2312 64 1148 4080 2312 4080 2313 4080 1148 4081 2313 4081 2314 4081 1148 4082 2314 4082 2315 4082 1146 64 1148 64 2315 64 1146 4083 2315 4083 2316 4083 1146 4084 2316 4084 2317 4084 1146 4085 2317 4085 2318 4085 1146 64 2318 64 2319 64 1146 4086 2319 4086 2320 4086 1146 4087 2320 4087 2284 4087 1146 4088 2284 4088 1797 4088 1654 4089 1146 4089 1797 4089 2321 4090 1176 4090 1793 4090 1784 4091 1793 4091 1176 4091 1176 4092 1173 4092 1784 4092 1169 4093 1785 4093 1173 4093 1169 4094 1168 4094 1786 4094 1168 4095 1166 4095 1787 4095 1166 4096 1163 4096 1788 4096 1789 4097 1163 4097 1146 4097 2322 4098 2323 4098 2324 4098 2322 4099 2324 4099 2325 4099 2326 4100 2322 4100 2325 4100 2327 4101 2323 4101 2322 4101 2328 4102 2329 4102 2327 4102 2322 4103 2328 4103 2327 4103 2330 4104 2329 4104 2328 4104 2328 4105 2331 4105 2330 4105 2332 4106 2330 4106 2331 4106 2333 4107 2332 4107 2331 4107 2334 4108 2333 4108 2331 4108 2331 4109 2335 4109 2334 4109 2336 4110 2335 4110 2331 4110 2337 4111 2338 4111 2336 4111 2331 4112 2337 4112 2336 4112 2338 4113 2339 4113 2336 4113 2340 4114 2341 4114 2342 4114 2341 4115 2343 4115 2342 4115 2343 4116 2344 4116 2342 4116 2342 4117 2344 4117 2345 4117 2346 4118 2335 4118 2336 4118 2336 4119 2339 4119 2340 4119 2336 4120 2340 4120 2342 4120 2346 4121 2336 4121 2342 4121 2342 4122 2345 4122 2347 4122 2346 4123 2342 4123 2348 4123 2291 4124 2349 4124 2350 4124 2275 4125 2350 4125 2349 4125 2276 4126 2275 4126 2349 4126 2349 4127 2351 4127 2276 4127 2352 4128 2276 4128 2351 4128 2351 4129 2326 4129 2352 4129 2352 4130 2326 4130 2325 4130 2324 4131 2352 4131 2325 4131 2304 4132 2350 4132 2275 4132 2350 4133 2304 4133 2291 4133 2275 4134 2277 4134 2304 4134 2277 4135 2278 4135 2304 4135 2278 4136 2279 4136 2304 4136 2353 4137 2326 4137 2351 4137 2353 4138 2351 4138 2349 4138 2349 4139 2291 4139 2289 4139 2353 4140 2349 4140 2289 4140 2354 4141 2326 4141 2353 4141 2353 4142 2355 4142 2354 4142 2355 4143 2353 4143 2289 4143 2289 4144 2287 4144 2355 4144 2356 4145 2354 4145 2355 4145 2287 4146 2285 4146 2355 4146 2355 4147 2357 4147 2356 4147 2357 4148 2355 4148 2285 4148 2357 4149 2320 4149 2356 4149 2320 4150 2357 4150 2285 4150 2317 4151 2356 4151 2320 4151 2285 4152 2284 4152 2320 4152 2320 4153 2319 4153 2318 4153 2320 4154 2318 4154 2317 4154 2354 4155 2331 4155 2328 4155 2354 4156 2328 4156 2322 4156 2326 4157 2354 4157 2322 4157 2358 4158 2331 4158 2354 4158 2354 4159 2356 4159 2358 4159 2359 4160 2358 4160 2356 4160 2356 4161 2317 4161 2359 4161 2359 4162 2317 4162 2316 4162 2359 4163 2316 4163 2315 4163 1131 4164 1422 4164 1403 4164 2360 4165 2361 4165 2362 4165 2363 4166 2360 4166 2362 4166 2364 4167 2365 4167 2361 4167 2360 4168 2364 4168 2361 4168 2365 4169 2364 4169 2366 4169 2367 4170 2365 4170 2366 4170 2368 4171 2369 4171 2367 4171 2366 4172 2368 4172 2367 4172 2370 4173 2369 4173 2368 4173 2344 4174 2370 4174 2345 4174 2371 4175 2345 4175 2370 4175 2368 4176 2371 4176 2370 4176 2345 4177 2371 4177 2347 4177 2372 4178 2313 4178 2312 4178 2372 4179 2312 4179 2311 4179 2372 4180 2311 4180 2310 4180 2373 4181 2372 4181 2310 4181 2373 4182 2340 4182 2339 4182 2373 4183 2339 4183 2338 4183 2373 4184 2338 4184 2337 4184 2373 4185 2337 4185 2372 4185 2310 4186 2309 4186 2373 4186 2341 4187 2340 4187 2373 4187 2373 4188 2309 4188 2308 4188 2373 4189 2308 4189 1403 4189 2373 4190 1403 4190 2374 4190 2374 4191 2344 4191 2343 4191 2374 4192 2343 4192 2341 4192 2373 4193 2374 4193 2341 4193 2370 4194 2367 4194 2369 4194 2375 4195 2365 4195 2370 4195 2370 4196 2376 4196 2375 4196 2376 4197 2370 4197 2344 4197 2377 4198 2375 4198 2376 4198 2378 4199 2377 4199 2376 4199 2376 4200 2379 4200 2378 4200 2379 4201 2376 4201 2374 4201 2380 4202 2378 4202 2379 4202 2379 4203 2374 4203 1403 4203 2381 4204 2380 4204 2379 4204 2379 4205 1422 4205 2381 4205 1422 4206 2379 4206 1403 4206 1421 4207 2381 4207 1422 4207 2361 4208 2382 4208 2362 4208 2382 4209 2361 4209 2365 4209 2365 4210 2375 4210 2382 4210 1405 4211 2362 4211 2382 4211 2362 4212 1405 4212 2363 4212 2375 4213 2377 4213 2382 4213 1404 4214 2363 4214 1405 4214 2377 4215 2378 4215 2382 4215 1420 4216 2382 4216 2378 4216 2382 4217 1420 4217 1405 4217 2378 4218 2380 4218 1420 4218 2380 4219 2381 4219 1420 4219 1419 4220 1405 4220 1420 4220 2381 4221 1421 4221 1420 4221 1332 4222 2363 4222 1404 4222 2383 4223 2360 4223 2363 4223 2383 4224 2363 4224 1332 4224 2364 4225 2360 4225 2383 4225 1332 4226 2384 4226 2383 4226 2331 4227 2358 4227 2337 4227 2372 4228 2337 4228 2358 4228 2358 4229 2359 4229 2372 4229 2313 4230 2372 4230 2359 4230 2314 4231 2313 4231 2359 4231 2359 4232 2315 4232 2314 4232 2225 4233 2276 4233 2352 4233 2225 4234 2352 4234 2324 4234 2225 4235 2324 4235 2323 4235 2225 4236 2323 4236 2327 4236 2225 4237 2327 4237 2329 4237 2225 4238 2329 4238 2330 4238 2225 4239 2330 4239 2332 4239 2225 4240 2332 4240 2333 4240 2225 4241 2333 4241 2334 4241 2335 4242 2225 4242 2334 4242 2344 4243 2374 4243 2376 4243 2385 4244 2386 4244 2387 4244 2388 4245 1366 4245 1364 4245 2388 4246 1364 4246 1361 4246 2388 4247 1361 4247 1359 4247 2388 4248 1359 4248 1355 4248 2388 4249 1230 4249 1366 4249 1213 4250 2389 4250 2390 4250 1213 4251 2390 4251 2391 4251 1213 4252 2391 4252 2392 4252 2393 583 1213 583 2392 583 1225 4253 2394 4253 2395 4253 1218 4254 1225 4254 2395 4254 2396 4255 2394 4255 1225 4255 1225 4256 1226 4256 2396 4256 2397 4257 2396 4257 1226 4257 1226 4258 1227 4258 2397 4258 2398 4259 2397 4259 1227 4259 1227 4260 1228 4260 2398 4260 2398 4261 1228 4261 1229 4261 2399 4262 2398 4262 1229 4262 2400 4263 2399 4263 1229 4263 2388 4264 2400 4264 1229 4264 1230 4265 2388 4265 1229 4265 2395 4266 2401 4266 2402 4266 2403 4267 2402 4267 2401 4267 2401 4268 2404 4268 2403 4268 2405 4269 2403 4269 2404 4269 2404 4270 2406 4270 2405 4270 2407 4271 2405 4271 2406 4271 2408 4272 2409 4272 2407 4272 2406 4273 2408 4273 2407 4273 2410 4274 2409 4274 2408 4274 2408 4275 2411 4275 2410 4275 2412 4276 2410 4276 2411 4276 2411 4277 2413 4277 2412 4277 2414 4278 2412 4278 2413 4278 2415 4279 2389 4279 2414 4279 2413 4280 2415 4280 2414 4280 2390 4281 2389 4281 2415 4281 2415 4282 2416 4282 2390 4282 2391 4283 2390 4283 2416 4283 2416 4284 2417 4284 2391 4284 2392 4285 2391 4285 2417 4285 2417 4286 2393 4286 2392 4286 2386 4287 2418 4287 2419 4287 2420 4288 2419 4288 2421 4288 2422 4289 2420 4289 2423 4289 2422 4290 2424 4290 2425 4290 2426 4291 2422 4291 2425 4291 2425 4292 2427 4292 2426 4292 2426 4293 2427 4293 2428 4293 2429 4294 2426 4294 2428 4294 2429 4295 2428 4295 2430 4295 2431 4296 2429 4296 2430 4296 2430 4297 2432 4297 2431 4297 2433 4298 2431 4298 2432 4298 2432 4299 2434 4299 2433 4299 2435 4300 2436 4300 2437 4300 2437 4301 2436 4301 2438 4301 2437 4302 2438 4302 2439 4302 2437 4303 2439 4303 2440 4303 2437 4304 2440 4304 2441 4304 2441 4305 2442 4305 2437 4305 2437 4306 2442 4306 2443 4306 2437 4307 2443 4307 2444 4307 2437 4308 2444 4308 2445 4308 2437 4309 2445 4309 2446 4309 2437 4310 2398 4310 2399 4310 2437 4311 2399 4311 2400 4311 2437 4312 2400 4312 2388 4312 2437 4313 2388 4313 2447 4313 2437 4314 2447 4314 2448 4314 2437 4315 2448 4315 2435 4315 2446 4316 2449 4316 2437 4316 2437 4317 2449 4317 2397 4317 2397 4318 2398 4318 2437 4318 2449 4319 2450 4319 2397 4319 2396 4320 2397 4320 2450 4320 2450 4321 2451 4321 2396 4321 2394 4322 2396 4322 2451 4322 2451 4323 2452 4323 2394 4323 2394 4324 2452 4324 2393 4324 2395 4325 2394 4325 2393 4325 2393 4326 2417 4326 2395 4326 2401 4327 2395 4327 2417 4327 2417 4328 2416 4328 2401 4328 2404 4329 2401 4329 2416 4329 2416 4330 2415 4330 2404 4330 2453 4331 2454 4331 2455 4331 2455 4332 2454 4332 2456 4332 2457 4333 2458 4333 2459 4333 2453 4334 2455 4334 2460 4334 2453 4335 2460 4335 2457 4335 2453 4336 2457 4336 2459 4336 2461 4337 2453 4337 2459 4337 2462 4338 2461 4338 2459 4338 2463 4339 2462 4339 2459 4339 2464 4340 2463 4340 2459 4340 2459 4341 2458 4341 2387 4341 2459 4342 2387 4342 2386 4342 2459 4343 2386 4343 2419 4343 2459 4344 2419 4344 2420 4344 2459 4345 2420 4345 2422 4345 2465 4346 2464 4346 2459 4346 2426 4347 2465 4347 2459 4347 2422 4348 2426 4348 2459 4348 2466 4349 2465 4349 2426 4349 2426 4350 2429 4350 2466 4350 2467 4351 2466 4351 2429 4351 2429 4352 2431 4352 2467 4352 2468 4353 2467 4353 2431 4353 2458 4354 2448 4354 2447 4354 2387 4355 2458 4355 2447 4355 2435 4356 2448 4356 2458 4356 2458 4357 2457 4357 2435 4357 2436 4358 2435 4358 2457 4358 2457 4359 2460 4359 2436 4359 2438 4360 2436 4360 2460 4360 2460 4361 2455 4361 2438 4361 2469 4362 2438 4362 2455 4362 2455 4363 2456 4363 2469 4363 2470 4364 2469 4364 2456 4364 2471 4365 2472 4365 2470 4365 2456 4366 2471 4366 2470 4366 2473 4367 2472 4367 2471 4367 2474 4368 2475 4368 2473 4368 2471 4369 2474 4369 2473 4369 2474 4370 2476 4370 2475 4370 2439 4371 2475 4371 2476 4371 1276 4372 2477 4372 2478 4372 2479 4373 2480 4373 2477 4373 2481 4374 2479 4374 2477 4374 2482 4375 2481 4375 2477 4375 1276 182 2442 182 2477 182 2483 4376 2482 4376 2477 4376 2484 4377 2483 4377 2477 4377 2485 4378 2484 4378 2477 4378 2486 182 2485 182 2477 182 2441 4379 2486 4379 2477 4379 2442 4380 2441 4380 2477 4380 2487 4381 2486 4381 2441 4381 2488 4382 2489 4382 2487 4382 2441 4383 2488 4383 2487 4383 2453 4384 2461 4384 2490 4384 2061 182 2489 182 2490 182 2059 182 2061 182 2490 182 2461 4385 2491 4385 2490 4385 2393 4386 2452 4386 1213 4386 1212 4387 1213 4387 2452 4387 2452 4388 2451 4388 1212 4388 1212 4389 2451 4389 1211 4389 2451 4390 2450 4390 1211 4390 1210 4391 1211 4391 2450 4391 2450 4392 2449 4392 1210 4392 2449 4393 2446 4393 1210 4393 1209 4394 1210 4394 2446 4394 2446 4395 2445 4395 1209 4395 1206 4396 1209 4396 2445 4396 2444 4397 1206 4397 2445 4397 2443 4398 1206 4398 2444 4398 2442 4399 1206 4399 2443 4399 1276 4400 1206 4400 2442 4400 2060 4401 2063 4401 2061 4401 2489 4402 2061 4402 2063 4402 2062 4403 2492 4403 2063 4403 2492 4404 2062 4404 1983 4404 2493 4405 2063 4405 2492 4405 2063 4406 2493 4406 2489 4406 2487 4407 2489 4407 2493 4407 2476 4408 2488 4408 2494 4408 2495 4409 2488 4409 2476 4409 2476 4410 2496 4410 2495 4410 2497 4411 2495 4411 2496 4411 2496 4412 2454 4412 2497 4412 2497 4413 2454 4413 2453 4413 2454 4414 2474 4414 2471 4414 2456 4415 2454 4415 2471 4415 2438 4416 2469 4416 2470 4416 2438 4417 2470 4417 2472 4417 2438 4418 2472 4418 2473 4418 2438 4419 2473 4419 2475 4419 2438 4420 2475 4420 2439 4420 2453 4421 2490 4421 2497 4421 2490 4422 2495 4422 2497 4422 2488 4423 2495 4423 2490 4423 2488 4424 2490 4424 2489 4424 2440 4425 2488 4425 2441 4425 2440 4426 2494 4426 2488 4426 2439 4427 2494 4427 2440 4427 2476 4428 2494 4428 2439 4428 2454 4429 2496 4429 2474 4429 2496 4430 2476 4430 2474 4430 1218 4431 2395 4431 2402 4431 1218 4432 2402 4432 2403 4432 1218 4433 2403 4433 2405 4433 1218 4434 2405 4434 2407 4434 1218 4435 2407 4435 2409 4435 1218 4436 2409 4436 1213 4436 2410 583 1213 583 2409 583 2410 4437 2412 4437 1213 4437 2412 583 2414 583 1213 583 2414 4438 2389 4438 1213 4438 2498 4439 2499 4439 2500 4439 2498 4440 2501 4440 2499 4440 2502 4441 2499 4441 2501 4441 2503 4442 2502 4442 2501 4442 2503 4443 2501 4443 2504 4443 2505 4444 2503 4444 2504 4444 2501 4445 2506 4445 2507 4445 2498 4446 2506 4446 2501 4446 2508 4447 2509 4447 2510 4447 2511 4448 2512 4448 2513 4448 2514 4449 2515 4449 2246 4449 2516 4450 2517 4450 2518 4450 2515 4451 2518 4451 2517 4451 2517 4452 2249 4452 2515 4452 2246 4453 2515 4453 2249 4453 2519 4454 2517 4454 2516 4454 2520 4455 2517 4455 2519 4455 2520 4456 2249 4456 2517 4456 2520 4457 2256 4457 2249 4457 2259 4458 2520 4458 2521 4458 2520 4459 2519 4459 2521 4459 2520 4460 2259 4460 2256 4460 2522 4461 2259 4461 2523 4461 2259 4462 2521 4462 2523 4462 2523 4463 2245 4463 2522 4463 2524 4464 2525 4464 2526 4464 2525 4465 2527 4465 2526 4465 2528 4466 2529 4466 2530 4466 2531 4467 2530 4467 2529 4467 2530 4468 2531 4468 2524 4468 2525 4469 2524 4469 2531 4469 2529 4470 2532 4470 2531 4470 2527 4471 2525 4471 2531 4471 2531 4472 2533 4472 2527 4472 2533 4473 2531 4473 2532 4473 2532 4474 2534 4474 2533 4474 2534 4475 2535 4475 2533 4475 2535 4476 2508 4476 2533 4476 2533 4477 2510 4477 2527 4477 2510 4478 2533 4478 2508 4478 2536 4479 2528 4479 2537 4479 2529 4480 2528 4480 2536 4480 2536 4481 2538 4481 2529 4481 2532 4482 2529 4482 2538 4482 2534 4483 2532 4483 2538 4483 2538 4484 2539 4484 2534 4484 2535 4485 2534 4485 2539 4485 2508 4486 2535 4486 2539 4486 2509 4487 2508 4487 2539 4487 2539 4488 2540 4488 2509 4488 2541 4489 2542 4489 2536 4489 2538 4490 2536 4490 2542 4490 2539 4491 2538 4491 2542 4491 2542 4492 2543 4492 2539 4492 2540 4493 2539 4493 2543 4493 2249 4494 2256 4494 2250 4494 2256 4495 2259 4495 2257 4495 2244 4496 2259 4496 2522 4496 2526 4497 2527 4497 2506 4497 2513 4498 2526 4498 2506 4498 2506 4499 2498 4499 2513 4499 2507 4500 2527 4500 2510 4500 2507 4501 2506 4501 2527 4501 2544 4502 2510 4502 2545 4502 2510 4503 2509 4503 2545 4503 2509 4504 2540 4504 2545 4504 2510 4505 2544 4505 2507 4505 2545 4506 2546 4506 2544 4506 2544 4507 2547 4507 2507 4507 2547 4508 2544 4508 2548 4508 2544 4509 2546 4509 2548 4509 2549 4510 2507 4510 2547 4510 2549 4511 2501 4511 2507 4511 2549 4512 2504 4512 2501 4512 2548 4513 2550 4513 2547 4513 2551 4514 2504 4514 2549 4514 2552 4515 2547 4515 2553 4515 2547 4516 2550 4516 2553 4516 2547 4517 2552 4517 2549 4517 2549 4518 2554 4518 2551 4518 2554 4519 2555 4519 2551 4519 2554 4520 2549 4520 2552 4520 2556 4521 2555 4521 2554 4521 2553 4522 2557 4522 2552 4522 2558 4523 2552 4523 2559 4523 2552 4524 2557 4524 2559 4524 2552 4525 2558 4525 2554 4525 2560 4526 2554 4526 2558 4526 2554 4527 2560 4527 2556 4527 2560 4528 2561 4528 2556 4528 2562 4529 2561 4529 2560 4529 2559 4530 2563 4530 2558 4530 2564 4531 2558 4531 2563 4531 2558 4532 2564 4532 2560 4532 2560 4533 2565 4533 2562 4533 2519 4534 2516 4534 2528 4534 2528 4535 2530 4535 2519 4535 2521 4536 2519 4536 2530 4536 2530 4537 2524 4537 2521 4537 2523 4538 2521 4538 2524 4538 2524 4539 2526 4539 2523 4539 2526 270 2513 270 2523 270 2245 4540 2523 4540 2513 4540 2566 4541 2505 4541 2504 4541 2504 4542 2551 4542 2566 4542 2567 4543 2566 4543 2551 4543 2551 4544 2555 4544 2567 4544 2568 4545 2567 4545 2555 4545 2555 4546 2556 4546 2568 4546 2569 4547 2568 4547 2556 4547 2556 4548 2561 4548 2569 4548 2570 4549 2569 4549 2561 4549 2561 4550 2562 4550 2570 4550 2570 4551 2562 4551 2571 4551 2246 4552 2249 4552 2248 4552 2572 4553 2246 4553 2142 4553 2572 4554 2254 4554 2246 4554 2254 4555 2514 4555 2246 4555 2528 4556 2516 4556 2537 4556 2516 4557 2536 4557 2537 4557 2516 4558 2541 4558 2536 4558 2518 4559 2541 4559 2516 4559 2573 4560 2511 4560 2500 4560 2513 4561 2500 4561 2511 4561 2500 4562 2499 4562 2574 4562 2499 4563 2502 4563 2575 4563 2502 4564 2503 4564 2576 4564 2503 583 2505 583 2577 583 2505 583 2566 583 2578 583 2566 4565 2567 4565 2579 4565 2567 4566 2568 4566 2580 4566 2568 583 2569 583 2581 583 2569 4567 2570 4567 2582 4567 2513 4568 2498 4568 2500 4568 2513 4569 2243 4569 2245 4569 2522 4570 2245 4570 2244 4570 2563 4571 2559 4571 2583 4571 2559 4572 2557 4572 2583 4572 2557 64 2553 64 2583 64 2553 4573 2543 4573 2583 4573 2553 4574 2550 4574 2543 4574 2550 4575 2548 4575 2543 4575 2548 4576 2546 4576 2543 4576 2546 4577 2545 4577 2543 4577 2545 4578 2540 4578 2543 4578 2584 4579 2585 4579 2586 4579 2587 4580 2585 4580 2584 4580 2588 4581 2585 4581 2587 4581 2589 4582 2585 4582 2588 4582 2589 4583 2583 4583 2585 4583 2590 64 2583 64 2589 64 2591 64 2583 64 2590 64 2563 64 2583 64 2591 64 2592 583 2582 583 2570 583 2582 4584 2581 4584 2569 4584 2581 583 2580 583 2568 583 2580 583 2579 583 2567 583 2579 583 2578 583 2566 583 2578 583 2577 583 2505 583 2577 4585 2576 4585 2503 4585 2576 583 2575 583 2502 583 2575 583 2574 583 2499 583 2574 4586 2573 4586 2500 4586 2593 4587 2586 4587 2585 4587 2575 4588 2594 4588 2595 4588 2575 4589 2595 4589 2596 4589 2574 4590 2575 4590 2596 4590 2575 4591 2576 4591 2594 4591 2576 4592 2577 4592 2594 4592 2578 4593 2579 4593 2597 4593 2598 4594 2597 4594 2579 4594 2579 4595 2580 4595 2598 4595 2599 4596 2598 4596 2580 4596 2580 4597 2581 4597 2599 4597 2600 4598 2599 4598 2581 4598 2581 4599 2582 4599 2600 4599 2601 4600 2600 4600 2582 4600 2582 4601 2592 4601 2601 4601 2571 4602 2601 4602 2592 4602 2592 4603 2570 4603 2571 4603 2595 4604 2602 4604 2603 4604 2596 4605 2595 4605 2603 4605 2604 4606 2605 4606 2606 4606 2602 4607 2604 4607 2606 4607 2602 4608 2595 4608 2594 4608 2602 4609 2594 4609 2604 4609 2607 4610 2605 4610 2604 4610 2607 4611 2586 4611 2593 4611 2607 4612 2593 4612 2605 4612 2584 4613 2586 4613 2607 4613 2607 4614 2604 4614 2608 4614 2609 4615 2607 4615 2608 4615 2609 4616 2587 4616 2584 4616 2607 4617 2609 4617 2584 4617 2608 4618 2610 4618 2609 4618 2604 4619 2594 4619 2597 4619 2608 4620 2604 4620 2597 4620 2610 4621 2608 4621 2597 4621 2597 4622 2598 4622 2610 4622 2588 4623 2587 4623 2609 4623 2611 4624 2589 4624 2588 4624 2609 4625 2611 4625 2588 4625 2611 4626 2609 4626 2610 4626 2610 4627 2598 4627 2599 4627 2612 4628 2610 4628 2599 4628 2610 4629 2612 4629 2611 4629 2599 4630 2600 4630 2612 4630 2590 4631 2589 4631 2611 4631 2564 4632 2591 4632 2590 4632 2611 4633 2564 4633 2590 4633 2564 4634 2611 4634 2612 4634 2612 4635 2565 4635 2564 4635 2612 4636 2600 4636 2601 4636 2565 4637 2612 4637 2601 4637 2601 4638 2571 4638 2565 4638 2563 4639 2591 4639 2564 4639 2565 4640 2571 4640 2562 4640 2564 4641 2565 4641 2560 4641 2613 4642 2163 4642 2095 4642 2163 4643 2254 4643 2143 4643 2254 4644 2572 4644 2142 4644 1963 4645 2614 4645 2615 4645 1963 4646 2615 4646 2004 4646 1963 4647 2004 4647 1964 4647 1967 4648 2255 4648 2616 4648 1963 496 1967 496 2616 496 2617 4649 2573 4649 2618 4649 2619 4650 2617 4650 2618 4650 2573 4651 2574 4651 2618 4651 2596 4652 2618 4652 2574 4652 2094 182 2096 182 2139 182 2139 4653 2002 4653 2003 4653 2139 4654 2003 4654 2620 4654 2139 4655 2620 4655 2621 4655 2094 4656 2139 4656 2095 4656 2095 4657 2139 4657 2613 4657 2622 4658 2623 4658 2624 4658 2625 4659 2624 4659 2623 4659 2625 4660 2623 4660 2139 4660 2626 4661 2625 4661 2139 4661 2614 4662 1963 4662 2621 4662 2617 4663 2619 4663 2621 4663 2621 4664 2619 4664 2627 4664 2621 4665 2627 4665 2628 4665 2621 4666 2628 4666 2629 4666 2621 4667 2629 4667 2630 4667 2621 4668 2630 4668 2626 4668 2139 4669 2621 4669 2626 4669 2004 4670 2615 4670 2003 4670 2620 4671 2003 4671 2615 4671 2615 4672 2614 4672 2620 4672 2621 4673 2620 4673 2614 4673 2630 4674 2631 4674 2625 4674 2626 4675 2630 4675 2625 4675 2630 4676 2629 4676 2631 4676 2632 4677 2631 4677 2629 4677 2629 4678 2628 4678 2632 4678 2633 4679 2632 4679 2628 4679 2628 4680 2627 4680 2633 4680 2618 4681 2633 4681 2627 4681 2627 4682 2619 4682 2618 4682 2596 4683 2603 4683 2618 4683 2602 4684 2606 4684 2603 4684 2593 4685 2634 4685 2605 4685 2605 4686 2635 4686 2606 4686 2635 4687 2605 4687 2634 4687 2632 4688 2606 4688 2635 4688 2631 4689 2635 4689 2634 4689 2635 4690 2631 4690 2632 4690 2634 4691 2625 4691 2631 4691 2634 4692 2593 4692 2636 4692 2636 4693 2624 4693 2634 4693 2625 4694 2634 4694 2624 4694 2585 4695 2636 4695 2593 4695 2585 4696 2637 4696 2636 4696 2624 4697 2636 4697 2637 4697 2624 4698 2637 4698 2622 4698 2577 4699 2597 4699 2594 4699 2578 4700 2597 4700 2577 4700 2603 4701 2633 4701 2618 4701 2603 4702 2606 4702 2633 4702 2606 4703 2632 4703 2633 4703 2638 4704 2639 4704 2640 4704 2641 4705 2642 4705 2643 4705 2641 4706 2643 4706 2638 4706 2640 4707 2641 4707 2638 4707 2644 4708 2645 4708 2646 4708 2647 4709 2646 4709 2645 4709 2645 4710 2648 4710 2647 4710 2649 4711 2647 4711 2648 4711 2648 4712 2650 4712 2649 4712 2651 4713 2649 4713 2650 4713 2650 4714 2652 4714 2651 4714 2653 4715 2651 4715 2652 4715 2652 4716 2654 4716 2653 4716 2655 4717 2653 4717 2654 4717 2654 4718 2656 4718 2655 4718 2657 4719 2655 4719 2656 4719 2656 4720 2658 4720 2657 4720 2659 4721 2657 4721 2658 4721 2658 4722 2660 4722 2659 4722 2659 4723 2660 4723 2661 4723 2662 583 2659 583 2661 583 2662 4724 2663 4724 2664 4724 2662 4725 2664 4725 2665 4725 2666 4726 2662 4726 2665 4726 2667 4727 2668 4727 2638 4727 2639 4728 2638 4728 2668 4728 2669 64 2670 64 2639 64 2668 64 2669 64 2639 64 2671 4729 2670 4729 2669 4729 2669 4730 2672 4730 2671 4730 2673 4731 2671 4731 2672 4731 2672 4732 2674 4732 2673 4732 2675 4733 2673 4733 2674 4733 2674 4734 2676 4734 2675 4734 2677 4735 2675 4735 2676 4735 2676 4736 2678 4736 2677 4736 2679 4737 2677 4737 2678 4737 2678 4738 2680 4738 2679 4738 2681 4739 2679 4739 2680 4739 2680 4740 2682 4740 2681 4740 2683 4741 2681 4741 2682 4741 2682 4742 2684 4742 2683 4742 2683 64 2684 64 2685 64 2686 64 2683 64 2685 64 2642 4743 2687 4743 2573 4743 2688 4744 2642 4744 2573 4744 2689 4745 2687 4745 2642 4745 2668 4746 2690 4746 2691 4746 2669 4747 2668 4747 2691 4747 2672 4748 2669 4748 2691 4748 2674 4749 2672 4749 2691 4749 2676 4750 2674 4750 2691 4750 2691 4751 2692 4751 2676 4751 2678 4752 2676 4752 2692 4752 2692 4753 2693 4753 2678 4753 2680 4754 2678 4754 2693 4754 2693 4755 2694 4755 2680 4755 2682 4756 2680 4756 2694 4756 2694 4757 2695 4757 2682 4757 2684 4758 2682 4758 2695 4758 2695 4759 2696 4759 2684 4759 2685 4760 2684 4760 2696 4760 2696 4761 2697 4761 2685 4761 2685 4762 2697 4762 2698 4762 2686 4763 2685 4763 2698 4763 2698 4764 2699 4764 2686 4764 2683 4765 2686 4765 2699 4765 2699 4766 2700 4766 2683 4766 2681 4767 2683 4767 2700 4767 2700 4768 2701 4768 2681 4768 2679 4769 2681 4769 2701 4769 2701 4770 2702 4770 2679 4770 2677 4771 2679 4771 2702 4771 2702 4772 2703 4772 2677 4772 2675 4773 2677 4773 2703 4773 2703 4774 2704 4774 2675 4774 2673 4775 2675 4775 2704 4775 2673 4776 2704 4776 2671 4776 2670 4777 2671 4777 2704 4777 2670 4778 2704 4778 2705 4778 2670 4779 2705 4779 2640 4779 2639 4780 2670 4780 2640 4780 2385 4781 2418 4781 2386 4781 2418 4782 2706 4782 2419 4782 2706 4783 2421 4783 2419 4783 2421 4784 2423 4784 2420 4784 2423 4785 2424 4785 2422 4785 2707 4786 2708 4786 2709 4786 2710 4787 2707 4787 2709 4787 2709 4788 2711 4788 2710 4788 2712 4789 2710 4789 2711 4789 2711 4790 2713 4790 2712 4790 2491 4791 2712 4791 2713 4791 2714 4792 2715 4792 2716 4792 2717 4793 2716 4793 2718 4793 2716 4794 2717 4794 2714 4794 2719 4795 2714 4795 2717 4795 2719 4796 2720 4796 2714 4796 2721 4797 2430 4797 2428 4797 2721 4798 2428 4798 2722 4798 2721 4799 2722 4799 2720 4799 2721 4800 2720 4800 2719 4800 2432 4801 2430 4801 2721 4801 2717 4802 2723 4802 2719 4802 2717 4803 2718 4803 2724 4803 2723 4804 2717 4804 2724 4804 2725 4805 2719 4805 2723 4805 2719 4806 2725 4806 2721 4806 2726 4807 2721 4807 2725 4807 2726 4808 2434 4808 2432 4808 2721 4809 2726 4809 2432 4809 2727 4810 2434 4810 2726 4810 2726 4811 2728 4811 2727 4811 2729 4812 2728 4812 2726 4812 2725 4813 2729 4813 2726 4813 2730 4814 2727 4814 2728 4814 2731 4815 2729 4815 2725 4815 2723 4816 2731 4816 2725 4816 2731 4817 2723 4817 2724 4817 2732 4818 2733 4818 2730 4818 2728 4819 2732 4819 2730 4819 2732 4820 2728 4820 2729 4820 2734 4821 2733 4821 2732 4821 2735 4822 2729 4822 2731 4822 2729 4823 2735 4823 2732 4823 2736 4824 2731 4824 2724 4824 2731 4825 2736 4825 2735 4825 2724 4826 2737 4826 2736 4826 2738 4827 2732 4827 2735 4827 2738 4828 2739 4828 2734 4828 2732 4829 2738 4829 2734 4829 2708 4830 2739 4830 2738 4830 2735 4831 2740 4831 2738 4831 2740 4832 2735 4832 2736 4832 2741 4833 2736 4833 2737 4833 2736 4834 2741 4834 2740 4834 2738 4835 2742 4835 2708 4835 2742 4836 2738 4836 2740 4836 2740 4837 2743 4837 2742 4837 2743 4838 2740 4838 2741 4838 2741 4839 2744 4839 2743 4839 2741 4840 2737 4840 2744 4840 2745 4841 2743 4841 2744 4841 2663 4842 2746 4842 2664 4842 2747 4843 2748 4843 2666 4843 2665 4844 2747 4844 2666 4844 2747 4845 2665 4845 2664 4845 2664 4846 2746 4846 2749 4846 2750 4847 2664 4847 2749 4847 2664 4848 2750 4848 2747 4848 2749 4849 2751 4849 2750 4849 2747 4850 2752 4850 2748 4850 2752 4851 2747 4851 2750 4851 2750 4852 2753 4852 2752 4852 2753 4853 2750 4853 2751 4853 2751 4854 2754 4854 2753 4854 2755 4855 2748 4855 2752 4855 2756 4856 2753 4856 2754 4856 2753 4857 2756 4857 2752 4857 2757 4858 2752 4858 2756 4858 2752 4859 2757 4859 2755 4859 2758 4860 2756 4860 2754 4860 2756 4861 2758 4861 2757 4861 2759 4862 2748 4862 2755 4862 2754 4863 2760 4863 2758 4863 2761 4864 2757 4864 2758 4864 2757 4865 2761 4865 2755 4865 2755 4866 2762 4866 2759 4866 2762 4867 2755 4867 2761 4867 2758 4868 2763 4868 2761 4868 2763 4869 2758 4869 2760 4869 2764 4870 2759 4870 2762 4870 2759 4871 2764 4871 2765 4871 2761 4872 2766 4872 2762 4872 2766 4873 2761 4873 2763 4873 2767 4874 2762 4874 2766 4874 2762 4875 2767 4875 2764 4875 2764 4876 2768 4876 2765 4876 2769 4877 2763 4877 2760 4877 2763 4878 2769 4878 2766 4878 2770 4879 2764 4879 2767 4879 2764 4880 2770 4880 2768 4880 2760 4881 2724 4881 2769 4881 2771 4882 2766 4882 2769 4882 2766 4883 2771 4883 2767 4883 2715 4884 2767 4884 2771 4884 2767 4885 2715 4885 2770 4885 2720 4886 2722 4886 2772 4886 2768 4887 2720 4887 2772 4887 2720 4888 2768 4888 2770 4888 2769 4889 2724 4889 2718 4889 2771 4890 2769 4890 2718 4890 2771 4891 2718 4891 2716 4891 2771 4892 2716 4892 2715 4892 2770 4893 2715 4893 2714 4893 2770 4894 2714 4894 2720 4894 2773 4895 2722 4895 2428 4895 2660 4896 2774 4896 2775 4896 2661 4897 2660 4897 2775 4897 2774 4898 2660 4898 2658 4898 2776 4899 2774 4899 2658 4899 2776 4900 2777 4900 2778 4900 2774 4901 2776 4901 2778 4901 2658 4902 2656 4902 2776 4902 2776 4903 2656 4903 2654 4903 2779 4904 2776 4904 2654 4904 2780 4905 2692 4905 2691 4905 2693 4906 2692 4906 2780 4906 2654 4907 2652 4907 2779 4907 2779 4908 2781 4908 2780 4908 2779 4909 2652 4909 2650 4909 2781 4910 2779 4910 2650 4910 2782 4911 2694 4911 2693 4911 2780 4912 2782 4912 2693 4912 2782 4913 2780 4913 2781 4913 2695 4914 2694 4914 2782 4914 2650 4915 2648 4915 2781 4915 2781 4916 2648 4916 2645 4916 2783 4917 2781 4917 2645 4917 2781 4918 2783 4918 2782 4918 2784 4919 2696 4919 2695 4919 2782 4920 2784 4920 2695 4920 2784 4921 2782 4921 2783 4921 2697 4922 2696 4922 2784 4922 2645 4923 2644 4923 2783 4923 2785 4924 2698 4924 2697 4924 2784 4925 2785 4925 2697 4925 2783 4926 2644 4926 2646 4926 2786 4927 2783 4927 2646 4927 2786 4928 2785 4928 2784 4928 2783 4929 2786 4929 2784 4929 2699 4930 2698 4930 2785 4930 2646 4931 2647 4931 2786 4931 2787 4932 2700 4932 2699 4932 2785 4933 2787 4933 2699 4933 2787 4934 2785 4934 2786 4934 2786 4935 2647 4935 2649 4935 2788 4936 2786 4936 2649 4936 2786 4937 2788 4937 2787 4937 2701 4938 2700 4938 2787 4938 2649 4939 2651 4939 2788 4939 2789 4940 2787 4940 2788 4940 2789 4941 2702 4941 2701 4941 2787 4942 2789 4942 2701 4942 2788 4943 2790 4943 2789 4943 2788 4944 2651 4944 2653 4944 2790 4945 2788 4945 2653 4945 2703 4946 2702 4946 2789 4946 2653 4947 2655 4947 2790 4947 2791 4948 2704 4948 2703 4948 2789 4949 2791 4949 2703 4949 2791 4950 2789 4950 2790 4950 2792 4951 2790 4951 2655 4951 2790 4952 2792 4952 2791 4952 2655 4953 2657 4953 2792 4953 2792 4954 2657 4954 2659 4954 2792 4955 2659 4955 2662 4955 2792 4956 2662 4956 2793 4956 2792 4957 2793 4957 2794 4957 2792 4958 2794 4958 2791 4958 2791 4959 2794 4959 2795 4959 2791 4960 2795 4960 2796 4960 2797 4961 2791 4961 2796 4961 2797 4962 2705 4962 2704 4962 2797 4963 2704 4963 2791 4963 2705 4964 2797 4964 2798 4964 2640 4965 2705 4965 2798 4965 2640 4966 2798 4966 2641 4966 2799 4967 2641 4967 2798 4967 2799 4968 2798 4968 2797 4968 2797 4969 2796 4969 2799 4969 2800 4970 2799 4970 2796 4970 2801 4971 2800 4971 2796 4971 2795 4972 2801 4972 2796 4972 2802 4973 2801 4973 2795 4973 2795 4974 2794 4974 2802 4974 2803 4975 2802 4975 2794 4975 2794 4976 2793 4976 2803 4976 2666 4977 2803 4977 2793 4977 2793 4978 2662 4978 2666 4978 2800 4979 2801 4979 2804 4979 2805 4980 2804 4980 2801 4980 2801 4981 2802 4981 2805 4981 2748 4982 2805 4982 2802 4982 2802 4983 2803 4983 2748 4983 2803 4984 2666 4984 2748 4984 2804 4985 2421 4985 2706 4985 2804 4986 2706 4986 2418 4986 2385 4987 2804 4987 2418 4987 2773 4988 2428 4988 2427 4988 2773 4989 2427 4989 2425 4989 2806 4990 2421 4990 2804 4990 2772 4991 2773 4991 2806 4991 2773 4992 2772 4992 2722 4992 2807 4993 2806 4993 2804 4993 2806 4994 2807 4994 2772 4994 2768 4995 2772 4995 2807 4995 2807 4996 2808 4996 2768 4996 2808 4997 2807 4997 2804 4997 2804 4998 2805 4998 2808 4998 2808 4999 2765 4999 2768 4999 2765 5000 2808 5000 2805 5000 2759 5001 2765 5001 2805 5001 2805 5002 2748 5002 2759 5002 2638 5003 2643 5003 2667 5003 2809 5004 2667 5004 2643 5004 2643 5005 2642 5005 2809 5005 2688 5006 2809 5006 2642 5006 2810 5007 2667 5007 2809 5007 2809 5008 2688 5008 2810 5008 2810 5009 2690 5009 2668 5009 2668 5010 2667 5010 2810 5010 2746 5011 2663 5011 2811 5011 2812 5012 2813 5012 2814 5012 2813 5013 2812 5013 2811 5013 2814 5014 2815 5014 2812 5014 2816 5015 2811 5015 2812 5015 2811 5016 2816 5016 2746 5016 2749 5017 2746 5017 2816 5017 2816 5018 2817 5018 2749 5018 2817 5019 2816 5019 2812 5019 2751 5020 2749 5020 2817 5020 2815 5021 2818 5021 2812 5021 2819 5022 2812 5022 2818 5022 2812 5023 2819 5023 2817 5023 2818 5024 2820 5024 2819 5024 2821 5025 2819 5025 2820 5025 2819 5026 2821 5026 2817 5026 2754 5027 2751 5027 2817 5027 2817 5028 2822 5028 2754 5028 2822 5029 2817 5029 2821 5029 2823 5030 2824 5030 2820 5030 2821 5031 2825 5031 2822 5031 2825 5032 2821 5032 2820 5032 2820 5033 2826 5033 2825 5033 2826 5034 2820 5034 2824 5034 2827 5035 2822 5035 2825 5035 2822 5036 2827 5036 2754 5036 2760 5037 2754 5037 2827 5037 2824 5038 2828 5038 2826 5038 2829 5039 2825 5039 2826 5039 2825 5040 2829 5040 2827 5040 2828 5041 2830 5041 2826 5041 2827 5042 2831 5042 2760 5042 2831 5043 2827 5043 2829 5043 2832 5044 2826 5044 2830 5044 2826 5045 2832 5045 2829 5045 2724 5046 2760 5046 2831 5046 2828 5047 2833 5047 2830 5047 2829 5048 2834 5048 2831 5048 2834 5049 2829 5049 2832 5049 2737 5050 2831 5050 2834 5050 2831 5051 2737 5051 2724 5051 2745 5052 2832 5052 2830 5052 2832 5053 2745 5053 2834 5053 2830 5054 2835 5054 2745 5054 2835 5055 2830 5055 2833 5055 2744 5056 2834 5056 2745 5056 2834 5057 2744 5057 2737 5057 2833 5058 2836 5058 2742 5058 2745 5059 2835 5059 2743 5059 2837 5060 2838 5060 2713 5060 2837 5061 2713 5061 2711 5061 2709 5062 2836 5062 2837 5062 2837 5063 2839 5063 2838 5063 2840 5064 2839 5064 2837 5064 2837 5065 2841 5065 2840 5065 2837 5066 2836 5066 2833 5066 2841 5067 2837 5067 2833 5067 2833 5068 2828 5068 2841 5068 2842 5069 2840 5069 2841 5069 2841 5070 2828 5070 2842 5070 2828 5071 2824 5071 2842 5071 2843 5072 2842 5072 2824 5072 2824 5073 2823 5073 2843 5073 2844 5074 2810 5074 2845 5074 2845 5075 2846 5075 2844 5075 2845 5076 2713 5076 2846 5076 2847 5077 2844 5077 2846 5077 2846 5078 2713 5078 2838 5078 2848 5079 2846 5079 2838 5079 2846 5080 2848 5080 2847 5080 2848 5081 2838 5081 2839 5081 2849 5082 2848 5082 2839 5082 2848 5083 2849 5083 2847 5083 2839 5084 2840 5084 2849 5084 2850 5085 2847 5085 2849 5085 2849 5086 2851 5086 2850 5086 2851 5087 2849 5087 2840 5087 2851 5088 2840 5088 2842 5088 2852 5089 2850 5089 2851 5089 2851 5090 2853 5090 2852 5090 2853 5091 2851 5091 2842 5091 2854 5092 2852 5092 2853 5092 2853 5093 2842 5093 2843 5093 2853 5094 2818 5094 2854 5094 2853 5095 2843 5095 2823 5095 2818 5096 2853 5096 2823 5096 2854 5097 2818 5097 2815 5097 2814 5098 2854 5098 2815 5098 2823 5099 2820 5099 2818 5099 2810 5100 2855 5100 2690 5100 2844 5101 2855 5101 2810 5101 2847 5102 2777 5102 2855 5102 2844 5103 2847 5103 2855 5103 2850 5104 2778 5104 2777 5104 2847 5105 2850 5105 2777 5105 2850 5106 2852 5106 2778 5106 2774 5107 2778 5107 2852 5107 2852 5108 2854 5108 2774 5108 2775 5109 2774 5109 2854 5109 2854 5110 2814 5110 2775 5110 2661 5111 2775 5111 2814 5111 2690 5112 2855 5112 2691 5112 2691 5113 2855 5113 2777 5113 2777 5114 2856 5114 2691 5114 2856 5115 2780 5115 2691 5115 2779 5116 2856 5116 2776 5116 2780 5117 2856 5117 2779 5117 2776 5118 2856 5118 2777 5118 2424 5119 2773 5119 2425 5119 2423 5120 2773 5120 2424 5120 2421 5121 2806 5121 2423 5121 2423 5122 2806 5122 2773 5122 2799 5123 2800 5123 2804 5123 2641 5124 2799 5124 2804 5124 2641 5125 2804 5125 2857 5125 2857 5126 2804 5126 2858 5126 2385 5127 2858 5127 2804 5127 2661 5128 2814 5128 2813 5128 2661 5129 2813 5129 2811 5129 2661 5130 2811 5130 2663 5130 2661 5131 2663 5131 2662 5131 2742 5132 2743 5132 2835 5132 2742 5133 2835 5133 2833 5133 2708 5134 2742 5134 2836 5134 2708 5135 2836 5135 2709 5135 2711 5136 2709 5136 2837 5136 2859 5137 2049 5137 2057 5137 2859 5138 2860 5138 2049 5138 2050 5139 2049 5139 2860 5139 2860 5140 2861 5140 2050 5140 2861 5141 2862 5141 2050 5141 2617 5142 2861 5142 2860 5142 2862 5143 2861 5143 2617 5143 2621 5144 2863 5144 2617 5144 2621 5145 1963 5145 2863 5145 2616 5146 2863 5146 1963 5146 2239 5147 2064 5147 2862 5147 2064 5148 2050 5148 2862 5148 2240 5149 2239 5149 2862 5149 2241 5150 2240 5150 2862 5150 2242 5151 2241 5151 2862 5151 2864 5152 2242 5152 2862 5152 2865 5153 2864 5153 2863 5153 2864 5154 2617 5154 2863 5154 2864 5155 2862 5155 2617 5155 2617 5156 2688 5156 2573 5156 2617 5157 2810 5157 2688 5157 2617 5158 2860 5158 2810 5158 2810 5159 2860 5159 2845 5159 2860 5160 2859 5160 2713 5160 2713 5161 2845 5161 2860 5161 2859 5162 2057 5162 2713 5162 2057 5163 2491 5163 2713 5163 2057 5164 2059 5164 2490 5164 2490 5165 2491 5165 2057 5165 2866 5166 2513 5166 2512 5166 2512 5167 2687 5167 2866 5167 2689 5168 2866 5168 2687 5168 2512 5169 2511 5169 2573 5169 2512 5170 2573 5170 2687 5170 2255 5171 1999 5171 2865 5171 1999 5172 2864 5172 2865 5172 1999 5173 2242 5173 2864 5173 2046 5174 2047 5174 2867 5174 1934 5175 1962 5175 2868 5175 2869 5176 2870 5176 2871 5176 2872 5177 2871 5177 2870 5177 2870 5178 2873 5178 2872 5178 2874 5179 2872 5179 2873 5179 2873 5180 2875 5180 2874 5180 1861 5181 2874 5181 1863 5181 2874 5182 2875 5182 1863 5182 2876 5183 2877 5183 2878 5183 2879 5184 2878 5184 2877 5184 2877 5185 2880 5185 2879 5185 2881 5186 2879 5186 2880 5186 2880 5187 2882 5187 2881 5187 2883 5188 2881 5188 2882 5188 2882 5189 2884 5189 2883 5189 2885 5190 2883 5190 2884 5190 2884 5191 2869 5191 2885 5191 2871 5192 2885 5192 2869 5192 2878 5193 2886 5193 2876 5193 2487 5194 2887 5194 2486 5194 2493 5195 2888 5195 2887 5195 2493 5196 2887 5196 2487 5196 2492 5197 2889 5197 2888 5197 2492 5198 2890 5198 2889 5198 2888 5199 2493 5199 2492 5199 1983 5200 2890 5200 2492 5200 2891 5201 2892 5201 2893 5201 2892 5202 2894 5202 2895 5202 2894 5203 2889 5203 2895 5203 2894 5204 2888 5204 2889 5204 2894 5205 2892 5205 2896 5205 2892 5206 2891 5206 2896 5206 2896 5207 2897 5207 2894 5207 2894 5208 2898 5208 2888 5208 2898 5209 2887 5209 2888 5209 2898 5210 2894 5210 2899 5210 2894 5211 2897 5211 2899 5211 2899 5212 2900 5212 2898 5212 2898 5213 2901 5213 2902 5213 2898 5214 2900 5214 2901 5214 2898 5215 2902 5215 2887 5215 2902 5216 2486 5216 2887 5216 2903 5217 2486 5217 2902 5217 2903 5218 2485 5218 2486 5218 2484 5219 2485 5219 2903 5219 2903 5220 2904 5220 2484 5220 2483 5221 2484 5221 2905 5221 2484 5222 2906 5222 2905 5222 2484 5223 2904 5223 2906 5223 1874 5224 1876 5224 2907 5224 2907 5225 2908 5225 2909 5225 2908 5226 2910 5226 2909 5226 2908 5227 2911 5227 2910 5227 2908 5228 2907 5228 1876 5228 2912 5229 2911 5229 2908 5229 1876 5230 1881 5230 2908 5230 2908 5231 2913 5231 2912 5231 2913 5232 2914 5232 2912 5232 2913 5233 2908 5233 1882 5233 2908 5234 1881 5234 1882 5234 2915 5235 2914 5235 2913 5235 1882 5236 1888 5236 2913 5236 2916 5237 2913 5237 1891 5237 2913 5238 1888 5238 1891 5238 2913 5239 2916 5239 2915 5239 2916 5240 2917 5240 2915 5240 2918 5241 2917 5241 2916 5241 1891 5242 1893 5242 2916 5242 2867 5243 2916 5243 2046 5243 2916 5244 2045 5244 2046 5244 2916 5245 2042 5245 2045 5245 2916 5246 1893 5246 2042 5246 2916 5247 2867 5247 2918 5247 2044 5248 2918 5248 2048 5248 2918 5249 2047 5249 2048 5249 2918 5250 2867 5250 2047 5250 2910 5251 2911 5251 1872 5251 2919 5252 1872 5252 2911 5252 2911 5253 2912 5253 2919 5253 2920 5254 2919 5254 2912 5254 2912 5255 2914 5255 2920 5255 2921 5256 2920 5256 2914 5256 2914 5257 2915 5257 2921 5257 2922 5258 2921 5258 2915 5258 2915 5259 2917 5259 2922 5259 2923 5260 2922 5260 2917 5260 2917 5261 2918 5261 2923 5261 2924 5262 2923 5262 2918 5262 2918 5263 2044 5263 2924 5263 2043 5264 2924 5264 2044 5264 1852 5265 2910 5265 1872 5265 1852 5266 2909 5266 2910 5266 1852 5267 2907 5267 2909 5267 1852 5268 1874 5268 2907 5268 1876 5269 1874 5269 1875 5269 1981 5270 2890 5270 1983 5270 2889 5271 2890 5271 2925 5271 2890 5272 1981 5272 2925 5272 1914 5273 1981 5273 1910 5273 1913 5274 2926 5274 1914 5274 1917 5275 2926 5275 1913 5275 1916 5276 1934 5276 1917 5276 2927 5277 2889 5277 2925 5277 2927 5278 2895 5278 2889 5278 2927 5279 2925 5279 1914 5279 2925 5280 1981 5280 1914 5280 1914 5281 2926 5281 2927 5281 2928 5282 2927 5282 1917 5282 2927 5283 2926 5283 1917 5283 2927 5284 2928 5284 2895 5284 2928 5285 2892 5285 2895 5285 2893 5286 2892 5286 2928 5286 1917 5287 1934 5287 2928 5287 2928 5288 2929 5288 2893 5288 2929 5289 2928 5289 2868 5289 2928 5290 1934 5290 2868 5290 2483 5291 2905 5291 2482 5291 2930 5292 2481 5292 2482 5292 2481 5293 2930 5293 2479 5293 2482 5294 2931 5294 2930 5294 2931 5295 2482 5295 2905 5295 2932 5296 2479 5296 2930 5296 2905 5297 2906 5297 2931 5297 2933 5298 2479 5298 2932 5298 2480 5299 2479 5299 2933 5299 2933 5300 2934 5300 2480 5300 2935 5301 2936 5301 2937 5301 2938 5302 2937 5302 2939 5302 2937 5303 2936 5303 2939 5303 2939 5304 2940 5304 2938 5304 2941 5305 2938 5305 2940 5305 2938 5306 2941 5306 2942 5306 2941 5307 2943 5307 2942 5307 2944 5308 2943 5308 2941 5308 2383 5309 2941 5309 2364 5309 2941 5310 2366 5310 2364 5310 2941 5311 2940 5311 2366 5311 2941 5312 2383 5312 2944 5312 2383 5313 2384 5313 2944 5313 2371 5314 2936 5314 2347 5314 2371 5315 2368 5315 2936 5315 2368 5316 2939 5316 2936 5316 2940 5317 2939 5317 2368 5317 2368 5318 2366 5318 2940 5318 2480 5319 2934 5319 2477 5319 2934 5320 2945 5320 2477 5320 2945 5321 2946 5321 2477 5321 2946 5322 2947 5322 2477 5322 2947 5323 2935 5323 2477 5323 2935 5324 2937 5324 2477 5324 2937 5325 2938 5325 2477 5325 2938 5326 2478 5326 2477 5326 2478 182 1332 182 1292 182 2478 5327 2384 5327 1332 5327 2938 5328 2942 5328 2478 5328 2942 182 2943 182 2478 182 2943 182 2944 182 2478 182 2944 5329 2384 5329 2478 5329 2948 5330 2949 5330 2886 5330 2949 5331 2948 5331 2950 5331 2948 5332 2951 5332 2950 5332 2948 5333 2952 5333 2951 5333 2948 5334 2953 5334 2952 5334 2953 5335 2932 5335 2952 5335 2933 5336 2932 5336 2953 5336 2934 5337 2933 5337 2953 5337 2954 5338 2945 5338 2953 5338 2954 5339 2953 5339 2948 5339 2945 5340 2934 5340 2953 5340 2948 5341 2955 5341 2954 5341 2955 5342 2948 5342 2886 5342 2946 5343 2945 5343 2954 5343 2947 5344 2946 5344 2954 5344 2935 5345 2947 5345 2954 5345 2955 5346 2886 5346 2956 5346 2955 5347 2956 5347 2954 5347 2936 5348 2935 5348 2954 5348 2886 5349 2957 5349 2956 5349 2348 5350 2936 5350 2954 5350 2348 5351 2347 5351 2936 5351 2348 5352 2954 5352 2956 5352 2956 5353 2346 5353 2348 5353 2348 5354 2342 5354 2347 5354 2957 5355 2346 5355 2956 5355 2346 5356 2957 5356 2335 5356 2932 5357 2930 5357 2952 5357 2930 5358 2951 5358 2952 5358 2951 5359 2958 5359 2950 5359 2958 5360 2949 5360 2950 5360 2958 5361 2951 5361 2930 5361 2959 5362 2949 5362 2958 5362 2959 5363 2886 5363 2949 5363 2959 5364 2876 5364 2886 5364 2959 5365 2877 5365 2876 5365 2959 5366 2880 5366 2877 5366 2959 5367 2882 5367 2880 5367 2930 5368 2931 5368 2958 5368 2960 5369 2958 5369 2906 5369 2958 5370 2931 5370 2906 5370 2958 5371 2960 5371 2959 5371 2884 5372 2882 5372 2959 5372 2961 5373 2959 5373 2960 5373 2959 5374 2961 5374 2884 5374 2961 5375 2869 5375 2884 5375 2961 5376 2870 5376 2869 5376 2906 5377 2904 5377 2960 5377 2902 5378 2960 5378 2903 5378 2960 5379 2904 5379 2903 5379 2960 5380 2902 5380 2961 5380 2873 5381 2870 5381 2961 5381 2962 5382 2961 5382 2899 5382 2961 5383 2900 5383 2899 5383 2961 5384 2901 5384 2900 5384 2961 5385 2902 5385 2901 5385 2961 5386 2962 5386 2873 5386 2962 5387 2875 5387 2873 5387 2962 5388 1863 5388 2875 5388 2899 5389 2897 5389 2962 5389 2963 5390 2962 5390 2893 5390 2962 5391 2891 5391 2893 5391 2962 5392 2896 5392 2891 5392 2962 5393 2897 5393 2896 5393 2962 5394 2963 5394 1863 5394 2963 5395 1862 5395 1863 5395 2963 5396 1860 5396 1862 5396 2963 5397 1859 5397 1860 5397 2963 5398 1857 5398 1859 5398 2963 5399 1856 5399 1857 5399 2893 5400 2929 5400 2963 5400 1855 5401 1856 5401 2963 5401 2963 5402 1962 5402 1855 5402 1962 5403 2963 5403 2868 5403 2963 5404 2929 5404 2868 5404 1962 5405 1934 5405 1875 5405 2321 5406 1793 5406 2964 5406 2225 5407 2335 5407 1858 5407 2335 5408 1861 5408 1858 5408 2335 5409 2874 5409 1861 5409 2335 5410 2886 5410 2874 5410 2886 5411 2872 5411 2874 5411 2886 5412 2871 5412 2872 5412 2886 5413 2885 5413 2871 5413 2886 5414 2883 5414 2885 5414 2886 5415 2881 5415 2883 5415 2335 5416 2957 5416 2886 5416 2919 5417 2043 5417 1872 5417 2924 5418 2043 5418 2919 5418 2919 5419 2920 5419 2924 5419 2923 5420 2924 5420 2920 5420 2920 182 2921 182 2923 182 2922 182 2923 182 2921 182 2879 5421 2881 5421 2886 5421 2879 5422 2886 5422 2878 5422 1557 5423 2224 5423 2072 5423 1441 5424 1666 5424 1665 5424 1441 5425 1664 5425 1666 5425 1665 5426 2224 5426 1439 5426 1441 5427 1665 5427 1439 5427 1601 5428 1446 5428 1602 5428 1601 5429 1444 5429 1446 5429 2965 5430 2966 5430 2967 5430 2966 5431 2968 5431 2967 5431 2966 5432 2965 5432 1149 5432 1175 5433 1177 5433 2969 5433 2970 5434 2971 5434 2972 5434 2973 5435 2974 5435 2975 5435 2973 5436 2976 5436 2974 5436 2977 5437 2978 5437 2979 5437 2980 5438 2978 5438 2977 5438 2981 5439 2982 5439 2983 5439 2983 5440 2984 5440 2981 5440 2985 5441 2981 5441 2984 5441 2984 5442 2986 5442 2985 5442 2987 5443 2985 5443 2986 5443 2988 973 2978 973 2980 973 2988 5444 2989 5444 2978 5444 2989 5445 2979 5445 2978 5445 2975 5446 2989 5446 2988 5446 2988 5447 2990 5447 2975 5447 2990 5448 2991 5448 2975 5448 2992 5449 2975 5449 2991 5449 2991 5450 2993 5450 2992 5450 2994 981 2995 981 2996 981 2997 5451 2998 5451 2996 5451 2974 5452 2996 5452 2999 5452 2996 5453 2998 5453 2999 5453 2996 5454 2974 5454 2994 5454 2974 5455 3000 5455 2994 5455 2976 5456 3000 5456 2974 5456 2999 5457 3001 5457 2974 5457 2974 5458 2989 5458 2975 5458 2979 5459 2989 5459 2974 5459 2974 5460 3002 5460 2979 5460 2974 5461 3001 5461 3002 5461 2975 5462 3003 5462 2973 5462 3003 5463 2975 5463 2992 5463 2993 5464 3004 5464 2992 5464 3005 5465 2997 5465 3006 5465 3005 5466 2998 5466 2997 5466 3005 5467 2999 5467 2998 5467 3005 5468 3001 5468 2999 5468 3005 5469 3002 5469 3001 5469 3005 5470 2979 5470 3002 5470 2979 5471 3005 5471 2977 5471 2995 5472 2994 5472 3007 5472 2987 5473 3007 5473 2994 5473 2994 5474 3000 5474 2987 5474 2985 5475 2987 5475 2976 5475 2987 5476 3000 5476 2976 5476 2976 5477 2973 5477 2985 5477 2981 5478 2985 5478 3003 5478 2985 5479 2973 5479 3003 5479 3003 5480 2992 5480 2981 5480 2982 5481 2981 5481 2992 5481 2992 5482 3004 5482 2982 5482 3004 5483 1195 5483 1170 5483 2982 5484 3004 5484 1170 5484 2968 5485 3008 5485 2970 5485 2972 5486 2968 5486 2970 5486 3009 5487 3008 5487 2968 5487 3010 5488 3009 5488 2968 5488 3011 5489 3010 5489 2968 5489 3011 5490 2968 5490 3012 5490 1147 64 3013 64 3014 64 1147 5491 3014 5491 3015 5491 1147 64 3015 64 1149 64 1147 5492 3016 5492 3013 5492 3017 64 3013 64 3016 64 1174 5493 1175 5493 2969 5493 1174 5494 2969 5494 3018 5494 1174 5495 3018 5495 3019 5495 3020 5496 1174 5496 3019 5496 1171 5497 1174 5497 3020 5497 3020 5498 3021 5498 1171 5498 3020 5499 3019 5499 3022 5499 3021 5500 3020 5500 3022 5500 1172 5501 1171 5501 3021 5501 1170 5502 1172 5502 3021 5502 3021 5503 3023 5503 1170 5503 1170 5504 3023 5504 2982 5504 3024 5505 2980 5505 2977 5505 2977 5506 3025 5506 3024 5506 3025 5507 3026 5507 3024 5507 3016 5508 1147 5508 3027 5508 3027 5509 1165 5509 1167 5509 3027 5510 1167 5510 1195 5510 3028 5511 3027 5511 1195 5511 3004 5512 2993 5512 3028 5512 1195 5513 3004 5513 3028 5513 3029 5514 3017 5514 3030 5514 1149 5515 3015 5515 2966 5515 2966 5516 3029 5516 2968 5516 2966 5517 3015 5517 3014 5517 2966 5518 3014 5518 3013 5518 2966 5519 3013 5519 3029 5519 3017 5520 3029 5520 3013 5520 2968 5521 3029 5521 3012 5521 3021 1055 3031 1055 3032 1055 3021 5522 3032 5522 3023 5522 3033 5523 3031 5523 3021 5523 3021 5524 3022 5524 3033 5524 3033 5525 3022 5525 3019 5525 2983 5526 2982 5526 3023 5526 2983 5527 3023 5527 3032 5527 2971 5528 2970 5528 3034 5528 2970 5529 3008 5529 3035 5529 3036 5530 3035 5530 3008 5530 3008 5531 3009 5531 3036 5531 3037 5532 3036 5532 3009 5532 3009 5533 3010 5533 3037 5533 3038 5534 3037 5534 3010 5534 3010 5535 3011 5535 3038 5535 3039 5536 3038 5536 3011 5536 1164 5537 1165 5537 3027 5537 3012 5538 3040 5538 3041 5538 3012 5539 3042 5539 3040 5539 3043 5540 3040 5540 3042 5540 3026 5541 3040 5541 3043 5541 3026 5542 3025 5542 3040 5542 3025 5543 2977 5543 3040 5543 3005 5544 3040 5544 2977 5544 3044 5545 3040 5545 3005 5545 3045 5546 3040 5546 3044 5546 3046 5547 3040 5547 3045 5547 3041 5548 3040 5548 3046 5548 3026 5549 3043 5549 3024 5549 3024 5550 2988 5550 2980 5550 3024 5551 2990 5551 2988 5551 3024 1085 3047 1085 2990 1085 2991 5552 2990 5552 3047 5552 3028 5553 2991 5553 3047 5553 3048 5554 3028 5554 3047 5554 3048 5555 3047 5555 3049 5555 3043 5556 3047 5556 3024 5556 3043 5557 3049 5557 3047 5557 3046 5558 3011 5558 3041 5558 3048 5559 3049 5559 3050 5559 3050 5560 3049 5560 3051 5560 3011 5561 3046 5561 3039 5561 3030 5562 3043 5562 3042 5562 3042 5563 3012 5563 3030 5563 3030 5564 3012 5564 3029 5564 3043 5565 3030 5565 3049 5565 3030 5566 3017 5566 3051 5566 3030 5567 3051 5567 3049 5567 3027 5568 3028 5568 3048 5568 3027 5569 3048 5569 3050 5569 3027 5570 3050 5570 3051 5570 3041 5571 3011 5571 3012 5571 3028 5572 2993 5572 2991 5572 3016 5573 3051 5573 3017 5573 3016 5574 3027 5574 3051 5574 1164 5575 3027 5575 1147 5575 3052 5576 3053 5576 3054 5576 3052 5577 3054 5577 3055 5577 3056 5578 3052 5578 3055 5578 3057 5579 3053 5579 3052 5579 3052 5580 3058 5580 3057 5580 3057 5581 3058 5581 3059 5581 3060 5582 3057 5582 3059 5582 3060 5583 3061 5583 3057 5583 3059 5584 3062 5584 3060 5584 3063 5585 3060 5585 3062 5585 3064 5586 3063 5586 3062 5586 3064 5587 3065 5587 3066 5587 3063 5588 3064 5588 3066 5588 3067 5589 3068 5589 3069 5589 3070 5590 3068 5590 3067 5590 3067 5591 3071 5591 3070 5591 3072 5592 3070 5592 3071 5592 3071 5593 3073 5593 3072 5593 2971 5594 3072 5594 3073 5594 3074 5595 3075 5595 2972 5595 2972 5596 3073 5596 3074 5596 3073 5597 2972 5597 2971 5597 3076 5598 3077 5598 3078 5598 3075 5599 3076 5599 3078 5599 3075 5600 3078 5600 3079 5600 3075 5601 3079 5601 3080 5601 3075 5602 3080 5602 3081 5602 2967 1136 3075 1136 3081 1136 3075 5603 2967 5603 2972 5603 2972 5604 2967 5604 2968 5604 3082 182 3083 182 3084 182 1178 5605 1179 5605 2969 5605 1177 5606 1178 5606 2969 5606 3085 5607 1189 5607 3086 5607 1192 5608 1189 5608 3085 5608 3085 5609 3087 5609 1192 5609 1193 5610 1192 5610 3087 5610 3087 1145 3088 1145 1193 1145 1194 5611 1193 5611 3088 5611 3089 5612 3090 5612 1194 5612 3088 5613 3089 5613 1194 5613 3091 5614 3090 5614 3089 5614 3089 5615 3092 5615 3091 5615 3091 5616 3092 5616 3018 5616 3091 5617 3018 5617 2969 5617 1179 5618 3091 5618 2969 5618 1189 5619 1190 5619 3086 5619 1190 5620 1191 5620 3086 5620 3093 5621 3057 5621 3061 5621 1157 5622 1158 5622 3093 5622 3094 5623 3053 5623 3057 5623 3093 5624 3094 5624 3057 5624 3093 5625 1158 5625 1159 5625 3093 5626 1159 5626 1160 5626 3093 5627 1160 5627 3095 5627 3093 5628 3095 5628 3096 5628 3094 5629 3093 5629 3096 5629 3053 5630 3094 5630 3097 5630 3053 5631 3097 5631 3098 5631 3054 5632 3053 5632 3098 5632 1151 5633 3099 5633 3100 5633 1151 5634 3100 5634 3101 5634 1152 5635 1151 5635 3101 5635 3099 5636 1151 5636 1150 5636 2965 5637 3099 5637 1150 5637 2965 5638 3081 5638 3080 5638 2965 5639 3080 5639 3079 5639 2965 5640 3079 5640 3102 5640 2965 5641 3102 5641 3099 5641 2967 5642 3081 5642 2965 5642 2965 5643 1150 5643 1149 5643 3088 222 3087 222 3103 222 3089 5644 3088 5644 3103 5644 3070 5645 3104 5645 3068 5645 3105 5646 3104 5646 3070 5646 3070 5647 3072 5647 3105 5647 3069 5648 3068 5648 3106 5648 3082 64 3065 64 3064 64 3082 228 3064 228 3062 228 3084 64 3065 64 3082 64 3054 5649 3107 5649 3108 5649 3055 5650 3054 5650 3108 5650 3108 5651 3109 5651 3055 5651 3055 5652 3109 5652 3110 5652 3056 5653 3055 5653 3110 5653 3110 5654 3109 5654 3111 5654 3112 5655 3110 5655 3111 5655 3111 5656 3113 5656 3112 5656 3113 5657 3114 5657 3115 5657 3116 5658 3115 5658 3114 5658 3112 5659 3113 5659 3115 5659 3112 5660 3115 5660 3117 5660 3112 5661 3117 5661 3118 5661 3112 5662 3118 5662 3119 5662 3120 5663 3112 5663 3119 5663 3119 5664 3121 5664 3120 5664 3122 5665 3116 5665 3114 5665 3114 5666 3123 5666 3122 5666 3120 5667 3121 5667 3124 5667 3120 5668 3124 5668 3125 5668 3126 5669 3120 5669 3125 5669 3125 5670 3127 5670 3126 5670 3128 5671 3126 5671 3127 5671 3127 5672 3129 5672 3128 5672 3130 5673 3128 5673 3129 5673 3129 5674 3131 5674 3130 5674 3130 5675 3131 5675 3132 5675 3130 5676 3132 5676 3133 5676 3134 5677 3130 5677 3133 5677 3133 5678 3135 5678 3134 5678 3136 5679 3137 5679 3138 5679 3139 5680 3136 5680 3138 5680 3134 5681 3135 5681 3137 5681 3137 5682 3136 5682 3140 5682 3140 5683 3134 5683 3137 5683 3136 5684 3141 5684 3140 5684 3140 5685 3141 5685 3142 5685 3143 5686 3140 5686 3142 5686 3142 5687 3144 5687 3078 5687 3078 5688 3144 5688 3145 5688 3079 5689 3078 5689 3145 5689 3127 270 3125 270 3129 270 3131 5690 3129 5690 3125 5690 3125 5691 3146 5691 3131 5691 3147 5692 3131 5692 3146 5692 3146 5693 3148 5693 3147 5693 3149 5694 3147 5694 3148 5694 3148 270 3150 270 3149 270 3151 5695 3149 5695 3150 5695 3150 270 3152 270 3151 270 3153 5696 3151 5696 3152 5696 3152 270 3154 270 3153 270 3155 270 3153 270 3154 270 3156 182 3157 182 3158 182 3159 5697 3158 5697 3157 5697 3157 182 3160 182 3159 182 3161 182 3159 182 3160 182 3160 182 3162 182 3161 182 3161 182 3162 182 3163 182 3164 182 3161 182 3163 182 3163 1229 3165 1229 3164 1229 3166 182 3164 182 3165 182 3137 5698 3167 5698 3138 5698 3168 5699 3138 5699 3167 5699 3167 5700 3169 5700 3168 5700 3170 5701 3168 5701 3169 5701 3169 5702 3171 5702 3170 5702 3172 5703 3170 5703 3171 5703 3171 5704 3173 5704 3172 5704 3174 5705 3172 5705 3173 5705 3173 5706 3175 5706 3174 5706 3176 5707 3174 5707 3175 5707 3175 5708 3177 5708 3176 5708 3178 5709 3176 5709 3177 5709 3177 5710 3179 5710 3178 5710 3180 5711 3178 5711 3179 5711 3179 5712 3181 5712 3180 5712 3182 5713 3180 5713 3181 5713 3115 5714 3183 5714 3117 5714 3184 5715 3117 5715 3183 5715 3183 5716 3185 5716 3184 5716 3186 5716 3184 5716 3185 5716 3185 295 3187 295 3186 295 3188 296 3186 296 3187 296 3187 297 3189 297 3188 297 3190 5717 3188 5717 3189 5717 3189 5718 3191 5718 3190 5718 3192 5719 3190 5719 3191 5719 3191 5720 3193 5720 3192 5720 3194 5721 3192 5721 3193 5721 3193 303 3195 303 3194 303 3196 303 3194 303 3195 303 3195 5722 3197 5722 3196 5722 3198 5723 3196 5723 3197 5723 3184 5724 3118 5724 3117 5724 3186 5725 3121 5725 3119 5725 3186 5726 3119 5726 3118 5726 3184 5727 3186 5727 3118 5727 3186 5728 3188 5728 3121 5728 3199 5729 3125 5729 3124 5729 3199 5730 3124 5730 3121 5730 3121 5731 3188 5731 3190 5731 3199 5732 3121 5732 3190 5732 3146 5733 3125 5733 3199 5733 3190 5734 3192 5734 3199 5734 3199 5735 3192 5735 3194 5735 3200 5736 3199 5736 3194 5736 3200 5737 3148 5737 3146 5737 3199 5738 3200 5738 3146 5738 3150 5739 3148 5739 3200 5739 3194 5740 3196 5740 3200 5740 3201 5741 3152 5741 3150 5741 3200 5742 3201 5742 3150 5742 3200 5743 3196 5743 3198 5743 3200 5744 3198 5744 3202 5744 3201 5745 3200 5745 3202 5745 3152 5746 3201 5746 3203 5746 3154 5747 3152 5747 3203 5747 3137 5748 3135 5748 3167 5748 3169 5749 3167 5749 3135 5749 3135 5750 3133 5750 3169 5750 3169 5751 3133 5751 3204 5751 3171 5752 3169 5752 3204 5752 3205 5753 3173 5753 3171 5753 3204 5754 3205 5754 3171 5754 3132 5755 3131 5755 3205 5755 3205 5756 3204 5756 3132 5756 3131 5757 3147 5757 3205 5757 3175 5758 3173 5758 3205 5758 3205 5759 3147 5759 3149 5759 3206 5760 3205 5760 3149 5760 3206 5761 3177 5761 3175 5761 3205 5762 3206 5762 3175 5762 3149 5763 3151 5763 3206 5763 3179 5764 3177 5764 3206 5764 3206 5765 3151 5765 3153 5765 3153 5766 3155 5766 3206 5766 3206 349 3155 349 3207 349 3208 5767 3206 5767 3207 5767 3206 5768 3208 5768 3179 5768 3179 5769 3208 5769 3209 5769 3181 5770 3179 5770 3209 5770 3115 5771 3210 5771 3183 5771 3185 5772 3183 5772 3210 5772 3210 5773 3211 5773 3185 5773 3187 5774 3185 5774 3211 5774 3211 5775 3212 5775 3187 5775 3189 5776 3187 5776 3212 5776 3213 5777 3191 5777 3189 5777 3212 5778 3213 5778 3189 5778 3214 5779 3158 5779 3213 5779 3215 5780 3214 5780 3213 5780 3216 5781 3215 5781 3213 5781 3213 5782 3212 5782 3216 5782 3158 5783 3159 5783 3213 5783 3193 5784 3191 5784 3213 5784 3213 5785 3159 5785 3161 5785 3213 5786 3161 5786 3164 5786 3213 5787 3164 5787 3166 5787 3213 5788 3166 5788 3217 5788 3218 5789 3213 5789 3217 5789 3218 5790 3195 5790 3193 5790 3213 5791 3218 5791 3193 5791 3195 5792 3218 5792 3219 5792 3197 5793 3195 5793 3219 5793 3054 5794 3098 5794 3107 5794 3220 5795 3107 5795 3098 5795 3098 5796 3097 5796 3220 5796 3221 380 3220 380 3097 380 3097 5797 3096 5797 3221 5797 3222 5797 3221 5797 3096 5797 3096 5798 3095 5798 3222 5798 3223 5799 3222 5799 3095 5799 3095 384 1160 384 3223 384 1143 385 3223 385 1160 385 3145 5800 3224 5800 3079 5800 3102 5801 3079 5801 3224 5801 3224 5802 3225 5802 3102 5802 3099 5803 3102 5803 3225 5803 3225 5804 3226 5804 3099 5804 3100 5805 3099 5805 3226 5805 3226 5806 3227 5806 3100 5806 3101 5807 3100 5807 3227 5807 3227 5808 1132 5808 3101 5808 1152 5809 3101 5809 1132 5809 3136 1343 3228 1343 3141 1343 3224 5810 3145 5810 3144 5810 3229 5811 3142 5811 3141 5811 3142 5812 3229 5812 3144 5812 3144 5813 3230 5813 3224 5813 3230 5814 3144 5814 3229 5814 3141 5815 3231 5815 3229 5815 3231 5816 3141 5816 3228 5816 3232 5817 3229 5817 3231 5817 3229 5818 3232 5818 3230 5818 3225 5819 3224 5819 3230 5819 3230 5820 3233 5820 3225 5820 3233 5821 3230 5821 3232 5821 3228 5822 3234 5822 3231 5822 3235 5823 3232 5823 3231 5823 3232 5824 3235 5824 3233 5824 3226 5825 3225 5825 3233 5825 3236 1360 3233 1360 3235 1360 3233 5826 3236 5826 3226 5826 3234 5827 1122 5827 3231 5827 3231 5828 3237 5828 3235 5828 3237 5829 3231 5829 1122 5829 1122 5830 1123 5830 3237 5830 3227 5831 3226 5831 3236 5831 3235 5832 1126 5832 3236 5832 1126 5833 3235 5833 3237 5833 1124 5834 3237 5834 1123 5834 3237 5835 1124 5835 1126 5835 1132 5836 3227 5836 3236 5836 1126 5837 1128 5837 3236 5837 3236 5838 1128 5838 1132 5838 1133 5839 1145 5839 3238 5839 3239 5840 3114 5840 3113 5840 3239 5841 3113 5841 3240 5841 3238 5842 3239 5842 3240 5842 3239 5843 3238 5843 1145 5843 3123 5844 3114 5844 3239 5844 1145 5845 1402 5845 3239 5845 3241 5846 3239 5846 1402 5846 3241 5847 3242 5847 3243 5847 3243 5848 3123 5848 3239 5848 3244 5849 3241 5849 1402 5849 1402 5850 1401 5850 3244 5850 1400 5851 3245 5851 3244 5851 1401 5852 1400 5852 3244 5852 3246 5853 3245 5853 1400 5853 1400 5854 1144 5854 3246 5854 3246 5855 3228 5855 3139 5855 3246 5856 1144 5856 1122 5856 3246 5857 1122 5857 3234 5857 3228 5858 3246 5858 3234 5858 3136 5859 3139 5859 3228 5859 3107 5860 3220 5860 3108 5860 3247 5861 3108 5861 3220 5861 3108 5862 3247 5862 3109 5862 3240 5863 3113 5863 3111 5863 3111 5864 3248 5864 3240 5864 3248 5865 3111 5865 3109 5865 3109 453 3249 453 3248 453 3249 5866 3109 5866 3247 5866 3247 5867 3250 5867 3249 5867 3250 5868 3247 5868 3220 5868 3220 5869 3221 5869 3250 5869 3238 5870 3240 5870 3248 5870 3248 5871 3251 5871 3238 5871 3251 5872 3248 5872 3249 5872 3252 5873 3249 5873 3250 5873 3249 462 3252 462 3251 462 3253 5874 3250 5874 3221 5874 3250 5875 3253 5875 3252 5875 3221 5876 3222 5876 3253 5876 1133 5877 3238 5877 3251 5877 3254 5878 3251 5878 3252 5878 3251 5879 3254 5879 1133 5879 3255 5880 3252 5880 3253 5880 3252 5881 3255 5881 3254 5881 3256 5882 3253 5882 3222 5882 3253 5883 3256 5883 3255 5883 1136 5884 1133 5884 3254 5884 1136 5885 3254 5885 3255 5885 3222 5886 3223 5886 3256 5886 1138 5887 3255 5887 3256 5887 3255 5888 1138 5888 1136 5888 3223 5889 1143 5889 3256 5889 1140 5890 3256 5890 1143 5890 3256 5891 1140 5891 1138 5891 3257 5892 3243 5892 3242 5892 3258 5893 3243 5893 3257 5893 3257 5894 3259 5894 3258 5894 3260 5895 3258 5895 3259 5895 3259 5896 3261 5896 3260 5896 3260 5897 3261 5897 3156 5897 3260 5898 3156 5898 3158 5898 3110 182 3112 182 3120 182 3110 182 3120 182 3126 182 3110 182 3126 182 3128 182 3110 5899 3128 5899 3130 5899 3110 5900 3130 5900 3134 5900 3110 5901 3134 5901 3140 5901 3143 5902 3110 5902 3140 5902 3143 5903 3076 5903 3075 5903 3143 5904 3075 5904 3074 5904 3143 5905 3074 5905 3073 5905 3143 5906 3073 5906 3071 5906 3143 5907 3071 5907 3067 5907 3143 5908 3067 5908 3069 5908 3069 496 3106 496 3083 496 3143 5909 3069 5909 3083 5909 3143 5910 3083 5910 3082 5910 3143 5911 3082 5911 3062 5911 3143 5912 3062 5912 3059 5912 3143 5913 3059 5913 3058 5913 3143 5914 3058 5914 3052 5914 3143 5915 3052 5915 3056 5915 3110 5916 3143 5916 3056 5916 3077 496 3076 496 3143 496 3094 496 3096 496 3097 496 3133 270 3132 270 3204 270 3242 5917 3241 5917 3244 5917 3244 5918 3245 5918 3242 5918 3239 5919 3241 5919 3243 5919 3158 5920 3214 5920 3260 5920 3243 5921 3258 5921 3260 5921 3214 5922 3243 5922 3260 5922 3214 5923 3215 5923 3243 5923 3215 5924 3216 5924 3243 5924 3123 5925 3243 5925 3216 5925 3123 5926 3216 5926 3212 5926 3123 5927 3212 5927 3211 5927 3122 5928 3123 5928 3211 5928 3122 5929 3211 5929 3210 5929 3116 5930 3122 5930 3210 5930 3115 5931 3116 5931 3210 5931 3138 5932 3262 5932 3263 5932 3263 1469 3262 1469 3264 1469 3264 5933 3262 5933 3265 5933 3264 5934 3265 5934 3266 5934 3266 5935 3265 5935 3267 5935 3266 5936 3267 5936 3268 5936 3266 5937 3268 5937 3269 5937 3270 5938 3269 5938 3268 5938 3271 5939 3269 5939 3270 5939 3271 5940 3272 5940 3269 5940 3269 5941 3272 5941 3273 5941 3274 5942 3272 5942 3271 5942 3246 5943 3269 5943 3245 5943 3272 5944 3274 5944 3156 5944 3272 5945 3156 5945 3261 5945 3259 5946 3272 5946 3261 5946 3272 5947 3259 5947 3273 5947 3257 5948 3273 5948 3259 5948 3273 5949 3257 5949 3269 5949 3257 1487 3242 1487 3269 1487 3269 5950 3246 5950 3266 5950 3245 5951 3269 5951 3242 5951 3266 5952 3246 5952 3139 5952 3182 5953 3275 5953 3180 5953 3180 5954 3275 5954 3276 5954 3277 5955 3178 5955 3276 5955 3276 5956 3178 5956 3180 5956 3276 5957 3278 5957 3277 5957 3277 5958 3278 5958 3165 5958 3277 5959 3165 5959 3163 5959 3277 5960 3163 5960 3279 5960 3277 5961 3279 5961 3280 5961 3178 5962 3277 5962 3176 5962 3274 5963 3277 5963 3280 5963 3277 5964 3268 5964 3267 5964 3268 5965 3277 5965 3270 5965 3270 5966 3277 5966 3271 5966 3271 5967 3277 5967 3274 5967 3267 5968 3174 5968 3277 5968 3277 5969 3174 5969 3176 5969 3174 5970 3267 5970 3172 5970 3265 5971 3172 5971 3267 5971 3172 5972 3265 5972 3170 5972 3262 5973 3170 5973 3265 5973 3170 5974 3262 5974 3168 5974 3138 5975 3168 5975 3262 5975 3160 182 3279 182 3162 182 3279 182 3160 182 3280 182 3157 182 3280 182 3160 182 3280 182 3157 182 3274 182 3156 182 3274 182 3157 182 3139 5976 3264 5976 3266 5976 3264 5977 3139 5977 3263 5977 3263 5978 3139 5978 3138 5978 3162 182 3279 182 3163 182 3078 5979 3143 5979 3142 5979 3077 5980 3143 5980 3078 5980 3106 182 3104 182 3083 182 3106 5981 3068 5981 3104 5981 3281 270 3155 270 3282 270 3283 270 3281 270 3282 270 3284 270 3285 270 3282 270 3286 270 3287 270 3283 270 3282 5982 3288 5982 3284 5982 3289 5983 3283 5983 3287 5983 3290 5984 3284 5984 3288 5984 3287 5985 3291 5985 3289 5985 3288 5986 3292 5986 3290 5986 3293 5987 3289 5987 3291 5987 3294 270 3290 270 3292 270 3291 270 3295 270 3293 270 3296 270 3293 270 3295 270 3292 270 3297 270 3294 270 3295 270 3298 270 3296 270 3299 579 3294 579 3297 579 3296 5988 3298 5988 3300 5988 3301 270 3296 270 3300 270 3302 270 3303 270 3299 270 3297 270 3302 270 3299 270 3304 270 3303 270 3302 270 3300 270 3304 270 3301 270 3305 270 3301 270 3304 270 3306 270 3305 270 3304 270 3302 5989 3306 5989 3304 5989 3307 5990 3182 5990 3308 5990 3309 583 3310 583 3198 583 3311 5991 3288 5991 3203 5991 3312 5992 3311 5992 3201 5992 3312 5993 3198 5993 3310 5993 3313 5994 3312 5994 3310 5994 3283 270 3155 270 3281 270 3155 5995 3283 5995 3314 5995 3314 5996 3315 5996 3207 5996 3315 5997 3316 5997 3208 5997 3316 5998 3308 5998 3209 5998 3307 5999 3317 5999 3182 5999 3317 6000 3318 6000 3276 6000 3318 6001 3319 6001 3278 6001 3320 6002 3321 6002 3166 6002 3321 6003 3322 6003 3218 6003 3322 6004 3309 6004 3219 6004 3323 6005 3288 6005 3311 6005 3311 6006 3312 6006 3323 6006 3324 6007 3323 6007 3312 6007 3312 6008 3313 6008 3324 6008 3314 6009 3325 6009 3315 6009 3316 6010 3315 6010 3325 6010 3325 6011 3326 6011 3316 6011 3316 6012 3326 6012 3308 6012 3327 6013 3292 6013 3288 6013 3323 6014 3327 6014 3288 6014 3324 6015 3313 6015 3327 6015 3323 6016 3324 6016 3327 6016 3313 6017 3328 6017 3327 6017 3297 6018 3292 6018 3327 6018 3329 6019 3327 6019 3328 6019 3329 6020 3302 6020 3297 6020 3327 6021 3329 6021 3297 6021 3328 6022 3330 6022 3329 6022 3306 6023 3302 6023 3329 6023 3329 6024 3330 6024 3331 6024 3332 6025 3329 6025 3331 6025 3329 6026 3332 6026 3306 6026 3305 6027 3306 6027 3332 6027 3331 6028 3333 6028 3332 6028 3334 6029 3332 6029 3333 6029 3332 6030 3334 6030 3305 6030 3301 6031 3305 6031 3334 6031 3333 6032 3335 6032 3334 6032 3336 6033 3296 6033 3301 6033 3334 636 3336 636 3301 636 3336 6034 3334 6034 3335 6034 3293 6035 3296 6035 3336 6035 3335 6036 3308 6036 3336 6036 3325 6037 3289 6037 3293 6037 3336 6038 3325 6038 3293 6038 3336 6039 3308 6039 3326 6039 3336 6040 3326 6040 3325 6040 3314 6041 3289 6041 3325 6041 3289 6042 3314 6042 3283 6042 3166 182 3319 182 3320 182 3320 182 3337 182 3338 182 3319 182 3337 182 3320 182 3313 1585 3310 1585 3309 1585 3308 6043 3335 6043 3339 6043 3339 6044 3307 6044 3308 6044 3330 6045 3328 6045 3340 6045 3340 1588 3341 1588 3330 1588 3331 6046 3330 6046 3341 6046 3341 6047 3342 6047 3331 6047 3342 6048 3343 6048 3333 6048 3333 6048 3331 6048 3342 6048 3343 655 3339 655 3335 655 3335 656 3333 656 3343 656 3328 6049 3313 6049 3309 6049 3309 6050 3340 6050 3328 6050 3322 6051 3340 6051 3309 6051 3321 6052 3340 6052 3322 6052 3338 6053 3341 6053 3340 6053 3338 6054 3342 6054 3341 6054 3338 663 3337 663 3342 663 3337 6055 3343 6055 3342 6055 3339 6056 3343 6056 3337 6056 3317 6057 3307 6057 3339 6057 3317 6058 3339 6058 3318 6058 3282 6059 3286 6059 3283 6059 3282 270 3285 270 3286 270 3282 6060 3203 6060 3288 6060 3321 6061 3338 6061 3340 6061 3320 1608 3338 1608 3321 1608 3319 6062 3318 6062 3337 6062 3318 6063 3339 6063 3337 6063 3063 6064 3344 6064 3061 6064 3060 6065 3063 6065 3061 6065 3345 182 3084 182 3083 182 3346 6066 3085 6066 3086 6066 1191 677 1187 677 3086 677 3093 6067 3061 6067 3344 6067 3093 6068 3347 6068 1157 6068 3085 6069 3346 6069 3348 6069 3348 681 3349 681 3085 681 3066 682 3065 682 3084 682 3181 6070 3308 6070 3182 6070 3165 182 3319 182 3166 182 3197 583 3309 583 3198 583 3203 6071 3201 6071 3311 6071 3201 6072 3202 6072 3312 6072 3312 6073 3202 6073 3198 6073 3207 6074 3155 6074 3314 6074 3208 6075 3207 6075 3315 6075 3209 6076 3208 6076 3316 6076 3181 6077 3209 6077 3308 6077 3317 6078 3275 6078 3182 6078 3276 6079 3275 6079 3317 6079 3278 6080 3276 6080 3318 6080 3165 6081 3278 6081 3319 6081 3321 6082 3217 6082 3166 6082 3218 6083 3217 6083 3321 6083 3219 6084 3218 6084 3322 6084 3197 6085 3219 6085 3309 6085 3282 270 3155 270 3154 270 3154 6086 3203 6086 3282 6086 1119 6087 1115 6087 3350 6087 3086 6088 3351 6088 3352 6088 3346 6089 3086 6089 3352 6089 3353 6090 3354 6090 3355 6090 3353 6091 3356 6091 3354 6091 3357 6092 3358 6092 3359 6092 3359 6093 3358 6093 3360 6093 3360 6094 3358 6094 3361 6094 3361 6095 3358 6095 3362 6095 3362 6096 3358 6096 3363 6096 3363 6097 3358 6097 3364 6097 3361 6098 3365 6098 3360 6098 3366 6099 3367 6099 3365 6099 3365 6100 3367 6100 3368 6100 3354 6101 3368 6101 3367 6101 3369 6102 3368 6102 3354 6102 3370 6103 3369 6103 3354 6103 3369 6104 3371 6104 3368 6104 3360 6105 3365 6105 3368 6105 3360 6106 3368 6106 3371 6106 3372 6107 3373 6107 3374 6107 3363 6108 3373 6108 3372 6108 3354 6109 3356 6109 3370 6109 3345 6110 3066 6110 3084 6110 3375 6111 3066 6111 3345 6111 3376 6112 3375 6112 3345 6112 3377 6113 3376 6113 3345 6113 3345 727 3364 727 3377 727 3358 6114 3377 6114 3364 6114 3373 6115 3363 6115 3364 6115 3378 6116 3379 6116 3380 6116 3350 6117 3379 6117 3378 6117 3378 6118 3381 6118 3350 6118 3382 733 3350 733 3381 733 3381 6119 3383 6119 3382 6119 3383 735 3352 735 3382 735 3383 736 3384 736 3352 736 3346 737 3352 737 3384 737 3385 6120 3346 6120 3384 6120 3386 6121 3387 6121 3388 6121 3387 6122 3389 6122 3388 6122 3388 6123 3390 6123 3386 6123 3391 6124 3386 6124 3390 6124 3390 6125 3392 6125 3391 6125 3393 6126 3391 6126 3392 6126 3392 6127 3394 6127 3393 6127 3395 6128 3393 6128 3394 6128 3394 6129 3396 6129 3395 6129 3397 6130 3395 6130 3396 6130 3396 6131 3398 6131 3397 6131 3399 6132 3397 6132 3398 6132 3398 6133 3380 6133 3399 6133 3399 6134 3380 6134 3379 6134 3348 6135 3346 6135 3385 6135 3400 6136 3401 6136 3402 6136 3401 6137 3400 6137 3403 6137 3404 6138 3405 6138 3401 6138 3406 6139 3407 6139 3408 6139 3409 6140 3408 6140 3407 6140 3409 6141 3355 6141 3408 6141 3409 6142 3410 6142 3355 6142 3409 6143 3411 6143 3410 6143 3409 6144 3412 6144 3411 6144 3413 6145 3412 6145 3409 6145 3414 6146 3409 6146 3415 6146 3409 6147 3407 6147 3415 6147 3409 765 3414 765 3413 765 3414 6148 3416 6148 3413 6148 3415 6149 3417 6149 3414 6149 3418 768 3416 768 3414 768 3414 6150 3401 6150 3418 6150 3401 6151 3419 6151 3418 6151 3401 6152 3405 6152 3419 6152 3414 6153 3402 6153 3401 6153 3414 1703 3417 1703 3402 1703 3408 6154 3366 6154 3406 6154 3367 6155 3366 6155 3408 6155 3354 6156 3367 6156 3408 6156 3408 6157 3355 6157 3354 6157 3355 6158 3410 6158 3420 6158 3420 6159 3353 6159 3355 6159 3421 6160 3357 6160 3359 6160 3422 6161 3359 6161 3360 6161 3359 6162 3422 6162 3421 6162 3360 6163 3371 6163 3422 6163 1154 6164 3421 6164 3422 6164 3422 6165 3423 6165 1154 6165 3347 6166 1156 6166 1157 6166 3347 6167 3093 6167 3344 6167 3347 6168 3357 6168 3421 6168 3347 6169 3424 6169 3357 6169 3347 6170 3344 6170 3424 6170 3347 6171 3421 6171 1156 6171 3421 6172 1154 6172 1156 6172 1155 793 3425 793 1180 793 1182 794 1180 794 3425 794 1182 6173 3369 6173 3370 6173 1182 796 3425 796 3369 796 3370 6174 1117 6174 1182 6174 3370 6175 1118 6175 1117 6175 3370 6176 3426 6176 1118 6176 3427 6177 3426 6177 3356 6177 3426 6178 3370 6178 3356 6178 3356 6179 3353 6179 3427 6179 3428 6180 3427 6180 3353 6180 3353 6181 3420 6181 3428 6181 3410 6182 3428 6182 3420 6182 3366 6183 3365 6183 3362 6183 3361 6184 3362 6184 3365 6184 3429 6185 3430 6185 3402 6185 3402 6186 3417 6186 3429 6186 3363 6187 3372 6187 3407 6187 3372 6188 3415 6188 3407 6188 3372 6189 3417 6189 3415 6189 3363 6190 3407 6190 3362 6190 3407 6191 3406 6191 3362 6191 3366 817 3362 817 3406 817 3431 6192 3396 6192 3394 6192 3431 819 3398 819 3396 819 3380 270 3398 270 3431 270 3431 6193 3378 6193 3380 6193 3431 6194 3381 6194 3378 6194 3431 6195 3383 6195 3381 6195 3431 6196 3384 6196 3383 6196 3431 6197 3385 6197 3384 6197 3400 6198 3402 6198 3430 6198 3350 6199 1115 6199 3379 6199 3351 6200 3350 6200 3382 6200 3382 6201 3352 6201 3351 6201 3350 6202 3351 6202 1119 6202 3351 6203 1184 6203 1119 6203 1186 6204 1184 6204 3351 6204 1186 6205 3351 6205 3086 6205 1187 832 1186 832 3086 832 3425 6206 3423 6206 3369 6206 1154 6207 3423 6207 3425 6207 3425 6208 1155 6208 1154 6208 3364 6209 3345 6209 3083 6209 3357 6210 3377 6210 3358 6210 3377 6211 3357 6211 3424 6211 3377 6212 3424 6212 3376 6212 3424 6213 3375 6213 3376 6213 3063 6214 3375 6214 3424 6214 3375 6215 3063 6215 3066 6215 3424 6216 3344 6216 3063 6216 3379 6217 1115 6217 3399 6217 1118 6218 3426 6218 1114 6218 1115 6219 1114 6219 3426 6219 3426 6220 3427 6220 1115 6220 3427 6221 3399 6221 1115 6221 3397 6222 3399 6222 3410 6222 3399 6223 3428 6223 3410 6223 3399 6224 3427 6224 3428 6224 3410 6225 3411 6225 3397 6225 3395 6226 3397 6226 3411 6226 3411 6227 3412 6227 3395 6227 3393 6228 3395 6228 3413 6228 3395 6229 3412 6229 3413 6229 3413 6230 3416 6230 3393 6230 3391 6231 3393 6231 3416 6231 3416 6232 3418 6232 3391 6232 3386 6233 3391 6233 3419 6233 3391 6234 3418 6234 3419 6234 3419 6235 3405 6235 3386 6235 3387 6236 3386 6236 3405 6236 3432 6237 3364 6237 3083 6237 3364 6238 3432 6238 3373 6238 3035 6239 3034 6239 2970 6239 3034 6240 3433 6240 2971 6240 3434 6241 3018 6241 3435 6241 3019 6242 3018 6242 3434 6242 3434 6243 3436 6243 3019 6243 3436 6244 3033 6244 3019 6244 3092 6245 3435 6245 3018 6245 3092 6246 3437 6246 3435 6246 2983 270 3032 270 3431 270 3431 6247 3434 6247 3435 6247 3431 6248 3436 6248 3434 6248 3431 6249 3033 6249 3436 6249 3431 6250 3031 6250 3033 6250 3431 6251 3032 6251 3031 6251 3435 6252 3437 6252 3431 6252 3437 6253 3438 6253 3431 6253 3103 1809 3431 1809 3438 1809 3373 6254 3039 6254 3046 6254 3373 6255 3038 6255 3039 6255 3373 6256 3037 6256 3038 6256 3373 6257 3036 6257 3037 6257 3373 6258 3035 6258 3036 6258 3373 6259 3034 6259 3035 6259 3373 6260 3433 6260 3034 6260 3373 6261 3105 6261 3433 6261 3439 6262 3440 6262 2995 6262 3007 6263 3439 6263 2995 6263 3441 6264 3442 6264 3440 6264 3439 6265 3441 6265 3440 6265 3443 6266 3442 6266 3441 6266 3444 6267 3445 6267 3443 6267 3441 6268 3444 6268 3443 6268 3444 6269 3446 6269 3445 6269 3373 6270 3046 6270 3045 6270 3373 6271 3045 6271 3044 6271 3447 6272 3448 6272 3449 6272 3449 6273 3450 6273 3447 6273 3447 6274 3450 6274 3403 6274 3451 6275 3447 6275 3403 6275 3452 6276 3005 6276 3006 6276 2997 6277 3453 6277 3454 6277 3453 6278 3449 6278 3454 6278 3448 6279 3454 6279 3449 6279 3455 6280 3442 6280 3443 6280 3456 6281 3455 6281 3443 6281 3456 6282 3450 6282 3449 6282 3456 6283 3449 6283 3455 6283 3443 6284 3445 6284 3456 6284 3456 6285 3445 6285 3457 6285 3456 6286 3404 6286 3450 6286 3455 6287 3453 6287 2997 6287 2996 6288 3455 6288 2997 6288 2996 6289 2995 6289 3440 6289 2996 6290 3440 6290 3442 6290 2996 6291 3442 6291 3455 6291 3453 6292 3455 6292 3449 6292 3446 6293 3444 6293 3458 6293 3439 6294 3459 6294 3460 6294 3441 6295 3439 6295 3460 6295 3461 6296 3459 6296 3439 6296 3439 6297 3007 6297 3461 6297 3462 6298 3461 6298 3007 6298 3007 6299 2987 6299 3462 6299 2986 6300 3462 6300 2987 6300 3044 6301 3005 6301 3373 6301 3373 6302 3005 6302 3452 6302 3444 6303 3463 6303 3458 6303 3441 6304 3463 6304 3444 6304 3441 6305 3460 6305 3463 6305 3006 6306 3373 6306 3452 6306 3431 6307 2986 6307 2984 6307 3431 6308 2984 6308 2983 6308 3087 6309 3085 6309 3349 6309 3349 935 3103 935 3087 935 3103 6310 3438 6310 3089 6310 3092 6311 3089 6311 3438 6311 3438 6312 3437 6312 3092 6312 3433 6313 3105 6313 3072 6313 3072 1868 2971 1868 3433 1868 3458 6314 3464 6314 3446 6314 3387 6315 3446 6315 3464 6315 3389 6316 3387 6316 3464 6316 3404 6317 3401 6317 3403 6317 3404 945 3465 945 3405 945 3404 6318 3457 6318 3465 6318 3404 6319 3403 6319 3450 6319 3404 6320 3456 6320 3457 6320 3348 270 3385 270 3431 270 3349 270 3348 270 3431 270 3431 6321 3103 6321 3349 6321 3430 6322 3466 6322 3400 6322 3403 6323 3400 6323 3466 6323 3466 6324 3451 6324 3403 6324 3465 6325 3387 6325 3405 6325 3446 6326 3387 6326 3457 6326 3387 6327 3465 6327 3457 6327 3446 6328 3457 6328 3445 6328 3432 182 3083 182 3104 182 3432 182 3104 182 3105 182 3432 6329 3105 6329 3373 6329 1555 6330 2224 6330 1557 6330 1442 6331 2224 6331 1555 6331 1439 6332 2224 6332 1442 6332 1352 6333 3467 6333 1356 6333 1349 270 3467 270 1352 270 1347 270 3467 270 1349 270 1343 270 3467 270 1347 270 1344 270 3467 270 1343 270 1341 6334 3467 6334 1344 6334 1335 270 3467 270 1341 270 1266 270 3467 270 1335 270 1267 270 3467 270 1266 270 1372 6335 3467 6335 1267 6335 1372 270 1398 270 3467 270 1398 270 1397 270 3467 270 1397 270 1393 270 3467 270 1393 270 1394 270 3467 270 1394 270 1391 270 3467 270 1391 6336 1388 6336 3467 6336 1388 6337 1386 6337 3467 6337 1386 270 1380 270 3467 270 1380 270 1381 270 3467 270 2321 6338 3468 6338 1176 6338 1426 6339 3468 6339 1432 6339 1194 6340 3468 6340 1188 6340 1188 6341 3468 6341 1423 6341 1423 6342 3468 6342 1427 6342 1427 6343 3468 6343 1426 6343 3090 6344 3468 6344 1194 6344 3091 6345 3468 6345 3090 6345 1179 6346 3468 6346 3091 6346 1179 6347 1176 6347 3468 6347 2964 6348 3467 6348 3468 6348 2321 6349 2964 6349 3468 6349 1381 6350 1438 6350 3468 6350 1381 6351 3468 6351 3467 6351 1436 6352 3468 6352 1438 6352 1435 6353 3468 6353 1436 6353 1435 6354 1432 6354 3468 6354 1289 6355 2478 6355 1292 6355 1289 182 1285 182 2478 182 1285 182 1333 182 2478 182 1214 6356 2478 6356 1333 6356 1214 6357 1276 6357 2478 6357 3469 6358 2964 6358 1793 6358 2387 6359 2858 6359 2385 6359 2689 6360 3469 6360 2866 6360 1656 6361 3469 6361 1793 6361 1656 6362 1793 6362 1657 6362 1793 6363 1658 6363 1657 6363 2513 6364 3470 6364 2243 6364 3470 6365 1656 6365 2243 6365 2866 6366 3470 6366 2513 6366 1656 6367 3470 6367 3469 6367 3470 6368 2866 6368 3469 6368 1767 6369 3471 6369 1784 6369 3471 6370 1793 6370 1784 6370 1663 6371 3471 6371 1767 6371 1663 6372 1767 6372 1758 6372 1663 6373 1793 6373 3471 6373 1355 6374 2447 6374 2388 6374 2447 6375 2964 6375 3469 6375 2858 6376 2387 6376 2857 6376 2447 6377 3469 6377 2387 6377 2447 6378 3467 6378 2964 6378 1355 6379 3467 6379 2447 6379 1355 6380 1356 6380 3467 6380 2857 6381 3472 6381 2641 6381 3469 6382 3472 6382 2387 6382 3472 6383 2857 6383 2387 6383 2689 6384 2642 6384 3472 6384 2641 6385 3472 6385 2642 6385 2689 6386 3472 6386 3469 6386 668 6387 687 6387 669 6387 3422 6388 3371 6388 3423 6388 3371 6389 3369 6389 3423 6389 1059 6390 1009 6390 1061 6390 1009 6391 1007 6391 1061 6391 503 6392 453 6392 504 6392 453 6393 451 6393 504 6393 2462 6394 2491 6394 2461 6394 2462 6395 2712 6395 2491 6395 2463 6396 2712 6396 2462 6396 2463 6397 2710 6397 2712 6397 2464 6398 2710 6398 2463 6398 2464 6399 2707 6399 2710 6399 2465 6400 2707 6400 2464 6400 2465 6401 2708 6401 2707 6401 2466 6402 2708 6402 2465 6402 2466 6403 2739 6403 2708 6403 2467 6404 2739 6404 2466 6404 2467 6405 2734 6405 2739 6405 2468 6406 2734 6406 2467 6406 2468 6407 2733 6407 2734 6407 3473 6408 2733 6408 2468 6408 3473 6409 2730 6409 2733 6409 3474 6410 2730 6410 3473 6410 3474 6411 2727 6411 2730 6411 3475 6412 2727 6412 3474 6412 2434 6413 2727 6413 3475 6413 2433 6414 2434 6414 3475 6414 2541 6415 2518 6415 2623 6415 2541 6416 2623 6416 2622 6416 2542 6417 2541 6417 2622 6417 2542 6418 2622 6418 2637 6418 2583 6419 2637 6419 2585 6419 2542 6420 2583 6420 2543 6420 2542 6421 2637 6421 2583 6421 2254 6422 2515 6422 2514 6422 2163 6423 2515 6423 2254 6423 2163 6424 2613 6424 2515 6424 2518 6425 2613 6425 2623 6425 2515 6426 2613 6426 2518 6426 2139 6427 2623 6427 2613 6427 2164 6428 2203 6428 2202 6428 2112 6429 2203 6429 2164 6429 2112 6430 2264 6430 2203 6430 2203 6431 2264 6431 2261 6431 2247 6432 2261 6432 2264 6432 2247 6433 2248 6433 2261 6433 2164 6434 2202 6434 2223 6434 2202 6435 2268 6435 2223 6435 2164 6436 2223 6436 2190 6436 473 6437 519 6437 475 6437 470 270 519 270 473 270 470 6438 471 6438 519 6438 519 6439 471 6439 553 6439 519 6440 553 6440 548 6440 519 6441 548 6441 552 6441 519 6442 552 6442 550 6442 519 6443 550 6443 549 6443 519 6444 549 6444 551 6444 519 6445 551 6445 25 6445 538 6446 542 6446 455 6446 539 6447 538 6447 455 6447 45 6448 543 6448 455 6448 539 6449 455 6449 543 6449 542 6450 555 6450 455 6450 455 6451 555 6451 518 6451 517 6452 455 6452 518 6452 456 6453 455 6453 517 6453 1012 6454 1011 6454 1073 6454 1073 6455 1011 6455 1074 6455 1011 6456 1112 6456 1074 6456 1098 6457 1112 6457 1011 6457 1095 6458 1011 6458 1100 6458 600 6459 1100 6459 1011 6459 1095 6460 1094 6460 1011 6460 1094 6461 1098 6461 1011 6461 1054 6462 1012 6462 1073 6462 1075 6463 1108 6463 580 6463 1075 6464 1107 6464 1108 6464 1075 6465 1106 6465 1107 6465 1075 6466 1109 6466 1106 6466 1075 6467 1105 6467 1109 6467 1075 6468 1110 6468 1105 6468 1075 6469 1027 6469 1110 6469 1026 6470 1027 6470 1075 6470 1026 6471 1075 6471 1029 6471 1029 270 1075 270 1031 270 3392 270 3431 270 3394 270 3390 270 3431 270 3392 270 3390 6472 3389 6472 3431 6472 3431 6473 3389 6473 3464 6473 3431 6474 3464 6474 3458 6474 3431 6475 3458 6475 3463 6475 3431 6476 3463 6476 3460 6476 3431 6477 3460 6477 3461 6477 3431 6478 3461 6478 3462 6478 3431 6479 3462 6479 2986 6479 3374 6480 3373 6480 3429 6480 3429 6481 3373 6481 3430 6481 3373 6451 3466 6451 3430 6451 3451 6482 3466 6482 3373 6482 3448 6483 3373 6483 3454 6483 3006 6484 3454 6484 3373 6484 3448 6485 3447 6485 3373 6485 3447 6486 3451 6486 3373 6486 3454 6487 3006 6487 2997 6487 3417 6488 3372 6488 3374 6488 3417 6489 3374 6489 3429 6489 3295 270 3291 270 3476 270 3291 6490 3287 6490 3476 6490 3287 605 3286 605 3476 605 3286 270 3285 270 3476 270 3285 6491 3284 6491 3476 6491 3284 6492 3290 6492 3476 6492 3476 603 3290 603 3294 603 3294 270 3299 270 3476 270 3299 6493 3303 6493 3476 6493 3303 1546 3304 1546 3476 1546 3304 6494 3300 6494 3476 6494 3300 270 3298 270 3476 270 3476 6495 3298 6495 3295 6495 2413 6496 2411 6496 2408 6496 2408 6497 2406 6497 2404 6497 2404 6498 2415 6498 2413 6498 2408 6499 2404 6499 2413 6499 2433 6500 3475 6500 3474 6500 3474 6501 3473 6501 2468 6501 2468 6502 2431 6502 2433 6502 3474 6503 2468 6503 2433 6503 3477 6504 3478 6504 3479 6504 3479 6505 3480 6505 3477 6505 3477 6506 3480 6506 3481 6506 3477 6507 3481 6507 3482 6507 3482 6508 3481 6508 3483 6508 3484 6509 3485 6509 3486 6509 3481 6510 3487 6510 3483 6510 3483 6511 3487 6511 3484 6511 3483 6512 3484 6512 3488 6512 3488 6513 3484 6513 3486 6513 3489 270 3490 270 3491 270 3491 270 3490 270 3492 270 3491 6514 3492 6514 3493 6514 3494 6515 3495 6515 3496 6515 3496 270 3495 270 3497 270 3493 6516 3498 6516 3491 6516 3491 6517 3498 6517 3499 6517 3491 6518 3499 6518 3495 6518 3494 6519 3500 6519 3495 6519 3495 6520 3500 6520 3501 6520 3495 6521 3501 6521 3491 6521 3502 64 3503 64 3504 64 3505 64 3506 64 3504 64 3507 6522 3504 6522 3508 6522 3508 6523 3504 6523 3489 6523 3508 64 3489 64 3509 64 3491 64 3480 64 3489 64 3489 6524 3480 6524 3479 6524 3504 6525 3506 6525 3502 6525 3502 6526 3506 6526 3510 6526 3502 6527 3510 6527 3511 6527 3511 6528 3512 6528 3502 6528 3502 6529 3512 6529 3513 6529 3502 6530 3513 6530 3514 6530 3507 64 3515 64 3504 64 3504 6531 3515 6531 3516 6531 3504 6532 3516 6532 3517 6532 3479 6533 3518 6533 3489 6533 3489 64 3518 64 3519 64 3489 64 3519 64 3520 64 3521 6534 3522 6534 3523 6534 3517 64 3524 64 3504 64 3504 6535 3524 6535 3525 6535 3504 6536 3525 6536 3505 6536 3520 64 3526 64 3489 64 3489 6537 3526 6537 3527 6537 3489 6538 3527 6538 3509 6538 3514 6539 3528 6539 3502 6539 3502 6540 3528 6540 3529 6540 3502 6541 3529 6541 3530 6541 3530 64 3531 64 3502 64 3502 6542 3531 6542 3521 6542 3502 6543 3521 6543 3532 6543 3532 6544 3521 6544 3523 6544 3477 583 3492 583 3478 583 3478 583 3492 583 3490 583 3478 6545 3490 6545 3533 6545 3534 583 3535 583 3490 583 3490 6546 3535 6546 3536 6546 3490 6547 3536 6547 3537 6547 3538 6548 3539 6548 3490 6548 3540 6549 3541 6549 3542 6549 3542 6550 3541 6550 3543 6550 3537 6551 3544 6551 3490 6551 3490 583 3544 583 3545 583 3490 583 3545 583 3533 583 3538 583 3490 583 3546 583 3539 583 3547 583 3490 583 3490 6552 3547 6552 3548 6552 3490 6553 3548 6553 3534 6553 3543 6554 3549 6554 3542 6554 3542 6555 3549 6555 3550 6555 3542 6556 3550 6556 3551 6556 3551 583 3550 583 3552 583 3552 6557 3550 6557 3553 6557 3552 583 3553 583 3490 583 3490 6558 3553 6558 3554 6558 3490 6559 3554 6559 3546 6559 3555 6560 3556 6560 3542 6560 3542 6561 3556 6561 3557 6561 3542 6562 3557 6562 3540 6562 3542 583 3558 583 3555 583 3555 6563 3558 6563 3559 6563 3555 6564 3559 6564 3560 6564 3560 583 3561 583 3555 583 3555 583 3561 583 3562 583 3555 6565 3562 6565 3563 6565 3564 6566 3565 6566 3485 6566 3485 6567 3565 6567 3566 6567 3485 6568 3566 6568 3486 6568 3490 6569 3489 6569 3552 6569 3552 6570 3489 6570 3504 6570 3552 496 3504 496 3551 496 3551 496 3504 496 3503 496 3551 6571 3503 6571 3542 6571 3542 6572 3503 6572 3502 6572 3542 6573 3502 6573 3558 6573 3558 6573 3502 6573 3532 6573 3558 6574 3532 6574 3559 6574 3559 6574 3532 6574 3523 6574 3559 6575 3523 6575 3560 6575 3560 6575 3523 6575 3522 6575 3560 6576 3522 6576 3561 6576 3561 6577 3522 6577 3521 6577 3561 6578 3521 6578 3562 6578 3562 6579 3521 6579 3531 6579 3562 6580 3531 6580 3563 6580 3563 6581 3531 6581 3530 6581 3563 6582 3530 6582 3555 6582 3555 6582 3530 6582 3529 6582 3555 6583 3529 6583 3556 6583 3556 6584 3529 6584 3528 6584 3556 6585 3528 6585 3557 6585 3557 6586 3528 6586 3514 6586 3557 6587 3514 6587 3540 6587 3540 6588 3514 6588 3513 6588 3540 6589 3513 6589 3541 6589 3541 6589 3513 6589 3512 6589 3541 6590 3512 6590 3543 6590 3543 6591 3512 6591 3511 6591 3543 6592 3511 6592 3549 6592 3549 6593 3511 6593 3510 6593 3549 6594 3510 6594 3550 6594 3550 6595 3510 6595 3506 6595 3550 6596 3506 6596 3553 6596 3553 6596 3506 6596 3505 6596 3553 6597 3505 6597 3554 6597 3554 6598 3505 6598 3525 6598 3554 6599 3525 6599 3546 6599 3546 6599 3525 6599 3524 6599 3546 6600 3524 6600 3538 6600 3538 6600 3524 6600 3517 6600 3538 6601 3517 6601 3539 6601 3539 6601 3517 6601 3516 6601 3539 6602 3516 6602 3547 6602 3547 6603 3516 6603 3515 6603 3547 6604 3515 6604 3548 6604 3548 6604 3515 6604 3507 6604 3548 6605 3507 6605 3534 6605 3534 6605 3507 6605 3508 6605 3534 6606 3508 6606 3535 6606 3535 6606 3508 6606 3509 6606 3535 6607 3509 6607 3536 6607 3536 6608 3509 6608 3527 6608 3536 6609 3527 6609 3537 6609 3537 6610 3527 6610 3526 6610 3537 6611 3526 6611 3544 6611 3544 6612 3526 6612 3520 6612 3544 6613 3520 6613 3545 6613 3545 6613 3520 6613 3519 6613 3545 6614 3519 6614 3533 6614 3533 6615 3519 6615 3518 6615 3518 6616 3479 6616 3533 6616 3533 6617 3479 6617 3478 6617 3498 6618 3493 6618 3483 6618 3483 6619 3493 6619 3482 6619 3499 6620 3498 6620 3488 6620 3488 6621 3498 6621 3483 6621 3500 6622 3494 6622 3487 6622 3487 6623 3494 6623 3484 6623 3501 6624 3500 6624 3481 6624 3481 6625 3500 6625 3487 6625 3491 6626 3501 6626 3480 6626 3480 6627 3501 6627 3481 6627 3493 6628 3492 6628 3482 6628 3482 6629 3492 6629 3477 6629 3566 6630 3495 6630 3486 6630 3486 6631 3495 6631 3499 6631 3486 6632 3499 6632 3488 6632 3496 6633 3564 6633 3494 6633 3494 6634 3564 6634 3485 6634 3494 6635 3485 6635 3484 6635 3495 6636 3566 6636 3567 6636 3567 6637 3566 6637 3568 6637 3569 6638 3570 6638 3496 6638 3496 6639 3570 6639 3564 6639 3571 6640 3572 6640 3573 6640 3571 6641 3573 6641 3574 6641 3575 6642 3576 6642 3577 6642 3575 6643 3577 6643 3578 6643 3579 6644 3580 6644 3581 6644 3579 6645 3581 6645 3582 6645 3583 6646 3584 6646 3585 6646 3583 6647 3585 6647 3586 6647 3587 6648 3588 6648 3577 6648 3587 6649 3577 6649 3576 6649 3584 6650 3589 6650 3590 6650 3584 6651 3590 6651 3585 6651 3589 6652 3591 6652 3592 6652 3589 6653 3592 6653 3590 6653 3593 6654 3594 6654 3595 6654 3593 6655 3595 6655 3596 6655 3594 6656 3597 6656 3598 6656 3594 6657 3598 6657 3595 6657 3597 6658 3599 6658 3600 6658 3597 6659 3600 6659 3598 6659 3599 6660 3601 6660 3602 6660 3599 6661 3602 6661 3600 6661 3601 6662 3603 6662 3604 6662 3601 6663 3604 6663 3602 6663 3605 6664 3606 6664 3607 6664 3605 6665 3607 6665 3608 6665 3609 6666 3610 6666 3611 6666 3609 6667 3611 6667 3612 6667 3613 6668 3579 6668 3582 6668 3613 6669 3582 6669 3614 6669 3615 6670 3616 6670 3574 6670 3615 6671 3574 6671 3573 6671 3616 6672 3617 6672 3618 6672 3616 6673 3618 6673 3574 6673 3617 6674 3619 6674 3620 6674 3617 6675 3620 6675 3618 6675 3619 6676 3621 6676 3622 6676 3619 6677 3622 6677 3620 6677 3621 6678 3623 6678 3624 6678 3621 6679 3624 6679 3622 6679 3623 6680 3625 6680 3626 6680 3623 6681 3626 6681 3624 6681 3625 6682 3627 6682 3628 6682 3625 6683 3628 6683 3626 6683 3627 6684 3629 6684 3630 6684 3627 6685 3630 6685 3628 6685 3629 6686 3631 6686 3632 6686 3629 6687 3632 6687 3630 6687 3633 6688 3634 6688 3635 6688 3633 6689 3635 6689 3636 6689 3634 6690 3637 6690 3638 6690 3634 6691 3638 6691 3635 6691 3637 6692 3639 6692 3640 6692 3637 6693 3640 6693 3638 6693 3641 6694 3642 6694 3643 6694 3641 6695 3643 6695 3644 6695 3642 6696 3645 6696 3646 6696 3642 6697 3646 6697 3643 6697 3645 6698 3647 6698 3648 6698 3645 6699 3648 6699 3646 6699 3647 6700 3649 6700 3650 6700 3647 6701 3650 6701 3648 6701 3649 6702 3651 6702 3652 6702 3649 6703 3652 6703 3650 6703 3651 6704 3653 6704 3654 6704 3651 6705 3654 6705 3652 6705 3653 6706 3575 6706 3578 6706 3653 6707 3578 6707 3654 6707 3588 6708 3655 6708 3578 6708 3588 6709 3578 6709 3577 6709 3655 6710 3656 6710 3654 6710 3655 6711 3654 6711 3578 6711 3656 6712 3657 6712 3652 6712 3656 6713 3652 6713 3654 6713 3657 6714 3658 6714 3650 6714 3657 6715 3650 6715 3652 6715 3658 6716 3659 6716 3648 6716 3658 6717 3648 6717 3650 6717 3659 6718 3660 6718 3646 6718 3659 6719 3646 6719 3648 6719 3660 6720 3661 6720 3643 6720 3660 6721 3643 6721 3646 6721 3662 6722 3663 6722 3640 6722 3662 6723 3640 6723 3664 6723 3663 6724 3665 6724 3638 6724 3663 6725 3638 6725 3640 6725 3665 6726 3666 6726 3635 6726 3665 6727 3635 6727 3638 6727 3667 6728 3668 6728 3632 6728 3667 6729 3632 6729 3669 6729 3668 6730 3670 6730 3630 6730 3668 6731 3630 6731 3632 6731 3670 6732 3671 6732 3628 6732 3670 6733 3628 6733 3630 6733 3671 6734 3672 6734 3626 6734 3671 6735 3626 6735 3628 6735 3672 6736 3673 6736 3624 6736 3672 6737 3624 6737 3626 6737 3673 6738 3674 6738 3622 6738 3673 6739 3622 6739 3624 6739 3674 6740 3675 6740 3620 6740 3674 6741 3620 6741 3622 6741 3675 6742 3676 6742 3618 6742 3675 6743 3618 6743 3620 6743 3676 6744 3571 6744 3574 6744 3676 6745 3574 6745 3618 6745 3677 6746 3678 6746 3679 6746 3677 6747 3679 6747 3680 6747 3681 6748 3682 6748 3683 6748 3681 6749 3683 6749 3684 6749 3685 6750 3686 6750 3687 6750 3685 6751 3687 6751 3688 6751 3688 6752 3687 6752 3689 6752 3688 6753 3689 6753 3690 6753 3613 6754 3691 6754 3692 6754 3613 6755 3692 6755 3579 6755 3691 6756 3693 6756 3694 6756 3691 6757 3694 6757 3692 6757 3693 6758 3695 6758 3696 6758 3693 6759 3696 6759 3694 6759 3695 6760 3697 6760 3698 6760 3695 6761 3698 6761 3696 6761 3697 6762 3699 6762 3700 6762 3697 6763 3700 6763 3698 6763 3699 6764 3701 6764 3702 6764 3699 6765 3702 6765 3700 6765 3701 6766 3703 6766 3704 6766 3701 6767 3704 6767 3702 6767 3703 6768 3705 6768 3706 6768 3703 6769 3706 6769 3704 6769 3707 6770 3708 6770 3691 6770 3707 6771 3691 6771 3613 6771 3708 6772 3709 6772 3693 6772 3708 6773 3693 6773 3691 6773 3709 6774 3710 6774 3695 6774 3709 6775 3695 6775 3693 6775 3710 6776 3711 6776 3697 6776 3710 6777 3697 6777 3695 6777 3711 6778 3712 6778 3699 6778 3711 6779 3699 6779 3697 6779 3712 6780 3713 6780 3701 6780 3712 6781 3701 6781 3699 6781 3713 6782 3714 6782 3703 6782 3713 6783 3703 6783 3701 6783 3714 6784 3715 6784 3705 6784 3714 6785 3705 6785 3703 6785 3716 6786 3717 6786 3718 6786 3716 6787 3718 6787 3719 6787 3717 6788 3720 6788 3721 6788 3717 6789 3721 6789 3718 6789 3610 6790 3722 6790 3717 6790 3610 6791 3717 6791 3716 6791 3722 6792 3723 6792 3720 6792 3722 6793 3720 6793 3717 6793 3609 6794 3724 6794 3722 6794 3609 6795 3722 6795 3610 6795 3724 6796 3725 6796 3723 6796 3724 6797 3723 6797 3722 6797 3726 6798 3727 6798 3724 6798 3726 6799 3724 6799 3609 6799 3605 6800 3728 6800 3729 6800 3605 6801 3729 6801 3606 6801 3601 6802 3730 6802 3731 6802 3601 6803 3731 6803 3603 6803 3599 6804 3732 6804 3730 6804 3599 6805 3730 6805 3601 6805 3597 6806 3733 6806 3732 6806 3597 6807 3732 6807 3599 6807 3589 6808 3734 6808 3735 6808 3589 6809 3735 6809 3591 6809 3734 6810 3736 6810 3737 6810 3734 6811 3737 6811 3735 6811 3736 6812 3738 6812 3739 6812 3736 6813 3739 6813 3737 6813 3738 6814 3740 6814 3741 6814 3738 6815 3741 6815 3739 6815 3740 6816 3742 6816 3743 6816 3740 6817 3743 6817 3741 6817 3742 6818 3744 6818 3745 6818 3742 6819 3745 6819 3743 6819 3584 6820 3746 6820 3734 6820 3584 6821 3734 6821 3589 6821 3746 6822 3747 6822 3736 6822 3746 6823 3736 6823 3734 6823 3747 6824 3748 6824 3738 6824 3747 6825 3738 6825 3736 6825 3748 6826 3749 6826 3740 6826 3748 6827 3740 6827 3738 6827 3749 6828 3750 6828 3742 6828 3749 6829 3742 6829 3740 6829 3750 6830 3751 6830 3744 6830 3750 6831 3744 6831 3742 6831 3751 6832 3752 6832 3753 6832 3751 6833 3753 6833 3744 6833 3752 6834 3754 6834 3755 6834 3752 6835 3755 6835 3753 6835 3754 6836 3756 6836 3757 6836 3754 6837 3757 6837 3755 6837 3758 6838 3759 6838 3757 6838 3757 6839 3756 6839 3760 6839 3760 6840 3761 6840 3758 6840 3757 6841 3760 6841 3758 6841 3676 6842 3762 6842 3763 6842 3676 6843 3763 6843 3571 6843 3762 6844 3764 6844 3765 6844 3762 6845 3765 6845 3763 6845 3764 6846 3766 6846 3767 6846 3764 6847 3767 6847 3765 6847 3766 6848 3768 6848 3769 6848 3766 6849 3769 6849 3767 6849 3768 6850 3770 6850 3771 6850 3768 6851 3771 6851 3769 6851 3770 6852 3772 6852 3773 6852 3770 6853 3773 6853 3771 6853 3772 6854 3774 6854 3775 6854 3772 6855 3775 6855 3773 6855 3774 6856 3776 6856 3777 6856 3774 6857 3777 6857 3775 6857 3776 6858 3778 6858 3779 6858 3776 6859 3779 6859 3777 6859 3778 6860 3780 6860 3781 6860 3778 6861 3781 6861 3779 6861 3780 6862 3782 6862 3783 6862 3780 6863 3783 6863 3781 6863 3782 6864 3784 6864 3785 6864 3782 6865 3785 6865 3783 6865 3784 6866 3786 6866 3787 6866 3784 6867 3787 6867 3785 6867 3786 6868 3788 6868 3789 6868 3786 6869 3789 6869 3787 6869 3675 6870 3790 6870 3762 6870 3675 6871 3762 6871 3676 6871 3790 6872 3791 6872 3764 6872 3790 6873 3764 6873 3762 6873 3791 6874 3792 6874 3766 6874 3791 6875 3766 6875 3764 6875 3792 6876 3793 6876 3768 6876 3792 6877 3768 6877 3766 6877 3793 6878 3794 6878 3770 6878 3793 6879 3770 6879 3768 6879 3794 6880 3795 6880 3772 6880 3794 6881 3772 6881 3770 6881 3795 6882 3796 6882 3774 6882 3795 6883 3774 6883 3772 6883 3796 6884 3797 6884 3776 6884 3796 6885 3776 6885 3774 6885 3797 6886 3798 6886 3778 6886 3797 6887 3778 6887 3776 6887 3798 6888 3799 6888 3780 6888 3798 6889 3780 6889 3778 6889 3799 6890 3800 6890 3782 6890 3799 6891 3782 6891 3780 6891 3800 6892 3801 6892 3784 6892 3800 6893 3784 6893 3782 6893 3801 6894 3802 6894 3786 6894 3801 6895 3786 6895 3784 6895 3802 6896 3803 6896 3788 6896 3802 6897 3788 6897 3786 6897 3674 6898 3804 6898 3790 6898 3674 6899 3790 6899 3675 6899 3804 6900 3805 6900 3791 6900 3804 6901 3791 6901 3790 6901 3805 6902 3806 6902 3792 6902 3805 6903 3792 6903 3791 6903 3806 6904 3807 6904 3793 6904 3806 6905 3793 6905 3792 6905 3807 6906 3808 6906 3794 6906 3807 6907 3794 6907 3793 6907 3808 6908 3809 6908 3795 6908 3808 6909 3795 6909 3794 6909 3809 6910 3810 6910 3796 6910 3809 6911 3796 6911 3795 6911 3810 6912 3811 6912 3797 6912 3810 6913 3797 6913 3796 6913 3811 6914 3812 6914 3798 6914 3811 6915 3798 6915 3797 6915 3812 6916 3813 6916 3799 6916 3812 6917 3799 6917 3798 6917 3813 6918 3814 6918 3800 6918 3813 6919 3800 6919 3799 6919 3814 6920 3815 6920 3801 6920 3814 6921 3801 6921 3800 6921 3815 6922 3816 6922 3802 6922 3815 6923 3802 6923 3801 6923 3816 6924 3817 6924 3803 6924 3816 6925 3803 6925 3802 6925 3817 6926 3818 6926 3819 6926 3817 6927 3819 6927 3803 6927 3673 6928 3820 6928 3804 6928 3673 6929 3804 6929 3674 6929 3820 6930 3821 6930 3805 6930 3820 6931 3805 6931 3804 6931 3821 6932 3822 6932 3806 6932 3821 6933 3806 6933 3805 6933 3822 6934 3823 6934 3807 6934 3822 6935 3807 6935 3806 6935 3823 6936 3824 6936 3808 6936 3823 6937 3808 6937 3807 6937 3824 6938 3825 6938 3809 6938 3824 6939 3809 6939 3808 6939 3825 6940 3826 6940 3810 6940 3825 6941 3810 6941 3809 6941 3826 6942 3827 6942 3811 6942 3826 6943 3811 6943 3810 6943 3827 6944 3828 6944 3812 6944 3827 6945 3812 6945 3811 6945 3828 6946 3829 6946 3813 6946 3828 6947 3813 6947 3812 6947 3829 6948 3830 6948 3814 6948 3829 6949 3814 6949 3813 6949 3830 6950 3831 6950 3815 6950 3830 6951 3815 6951 3814 6951 3831 6952 3832 6952 3816 6952 3831 6953 3816 6953 3815 6953 3832 6954 3833 6954 3817 6954 3832 6955 3817 6955 3816 6955 3833 6956 3834 6956 3818 6956 3833 6957 3818 6957 3817 6957 3672 6958 3835 6958 3820 6958 3672 6959 3820 6959 3673 6959 3835 6960 3836 6960 3821 6960 3835 6961 3821 6961 3820 6961 3836 6962 3837 6962 3822 6962 3836 6963 3822 6963 3821 6963 3837 6964 3838 6964 3823 6964 3837 6965 3823 6965 3822 6965 3838 6966 3839 6966 3824 6966 3838 6967 3824 6967 3823 6967 3839 6968 3840 6968 3825 6968 3839 6969 3825 6969 3824 6969 3840 6970 3841 6970 3826 6970 3840 6971 3826 6971 3825 6971 3841 6972 3842 6972 3827 6972 3841 6973 3827 6973 3826 6973 3842 6974 3843 6974 3828 6974 3842 6975 3828 6975 3827 6975 3843 6976 3844 6976 3829 6976 3843 6977 3829 6977 3828 6977 3844 6978 3845 6978 3830 6978 3844 6979 3830 6979 3829 6979 3845 6980 3846 6980 3831 6980 3845 6981 3831 6981 3830 6981 3846 6982 3847 6982 3832 6982 3846 6983 3832 6983 3831 6983 3847 6984 3848 6984 3833 6984 3847 6985 3833 6985 3832 6985 3848 6986 3849 6986 3834 6986 3848 6987 3834 6987 3833 6987 3671 6988 3850 6988 3835 6988 3671 6989 3835 6989 3672 6989 3850 6990 3851 6990 3836 6990 3850 6991 3836 6991 3835 6991 3851 6992 3852 6992 3837 6992 3851 6993 3837 6993 3836 6993 3852 6994 3853 6994 3838 6994 3852 6995 3838 6995 3837 6995 3853 6996 3854 6996 3839 6996 3853 6997 3839 6997 3838 6997 3854 6998 3855 6998 3840 6998 3854 6999 3840 6999 3839 6999 3855 7000 3856 7000 3841 7000 3855 7001 3841 7001 3840 7001 3856 7002 3857 7002 3842 7002 3856 7003 3842 7003 3841 7003 3857 7004 3858 7004 3843 7004 3857 7005 3843 7005 3842 7005 3858 7006 3859 7006 3844 7006 3858 7007 3844 7007 3843 7007 3859 7008 3860 7008 3845 7008 3859 7009 3845 7009 3844 7009 3860 7010 3861 7010 3846 7010 3860 7011 3846 7011 3845 7011 3861 7012 3862 7012 3847 7012 3861 7013 3847 7013 3846 7013 3862 7014 3863 7014 3848 7014 3862 7015 3848 7015 3847 7015 3670 7016 3864 7016 3850 7016 3670 7017 3850 7017 3671 7017 3864 7018 3865 7018 3851 7018 3864 7019 3851 7019 3850 7019 3865 7020 3866 7020 3852 7020 3865 7021 3852 7021 3851 7021 3866 7022 3867 7022 3853 7022 3866 7023 3853 7023 3852 7023 3867 7024 3868 7024 3854 7024 3867 7025 3854 7025 3853 7025 3868 7026 3869 7026 3855 7026 3868 7027 3855 7027 3854 7027 3869 7028 3870 7028 3856 7028 3869 7029 3856 7029 3855 7029 3870 7030 3871 7030 3857 7030 3870 7031 3857 7031 3856 7031 3871 7032 3872 7032 3858 7032 3871 7033 3858 7033 3857 7033 3872 7034 3873 7034 3859 7034 3872 7035 3859 7035 3858 7035 3873 7036 3874 7036 3860 7036 3873 7037 3860 7037 3859 7037 3874 7038 3875 7038 3861 7038 3874 7039 3861 7039 3860 7039 3875 7040 3876 7040 3862 7040 3875 7041 3862 7041 3861 7041 3876 7042 3877 7042 3863 7042 3876 7043 3863 7043 3862 7043 3668 7044 3878 7044 3864 7044 3668 7045 3864 7045 3670 7045 3878 7046 3879 7046 3865 7046 3878 7047 3865 7047 3864 7047 3879 7048 3880 7048 3866 7048 3879 7049 3866 7049 3865 7049 3880 7050 3881 7050 3867 7050 3880 7051 3867 7051 3866 7051 3881 7052 3882 7052 3868 7052 3881 7053 3868 7053 3867 7053 3882 7054 3883 7054 3869 7054 3882 7055 3869 7055 3868 7055 3883 7056 3884 7056 3870 7056 3883 7057 3870 7057 3869 7057 3884 7058 3885 7058 3871 7058 3884 7059 3871 7059 3870 7059 3885 7060 3886 7060 3872 7060 3885 7061 3872 7061 3871 7061 3886 7062 3887 7062 3873 7062 3886 7063 3873 7063 3872 7063 3887 7064 3888 7064 3874 7064 3887 7065 3874 7065 3873 7065 3888 7066 3889 7066 3875 7066 3888 7067 3875 7067 3874 7067 3889 7068 3890 7068 3876 7068 3889 7069 3876 7069 3875 7069 3890 7070 3891 7070 3877 7070 3890 7071 3877 7071 3876 7071 3891 7072 3892 7072 3893 7072 3891 7073 3893 7073 3877 7073 3892 7074 3894 7074 3895 7074 3892 7075 3895 7075 3893 7075 3894 7076 3896 7076 3897 7076 3894 7077 3897 7077 3898 7077 3896 7078 3899 7078 3900 7078 3896 7079 3900 7079 3897 7079 3899 7080 3901 7080 3902 7080 3899 7081 3902 7081 3900 7081 3901 7082 3688 7082 3690 7082 3901 7083 3690 7083 3902 7083 3667 7084 3903 7084 3878 7084 3667 7085 3878 7085 3668 7085 3903 7086 3904 7086 3879 7086 3903 7087 3879 7087 3878 7087 3904 7088 3905 7088 3880 7088 3904 7089 3880 7089 3879 7089 3905 7090 3906 7090 3881 7090 3905 7091 3881 7091 3880 7091 3906 7092 3907 7092 3882 7092 3906 7093 3882 7093 3881 7093 3907 7094 3908 7094 3883 7094 3907 7095 3883 7095 3882 7095 3908 7096 3909 7096 3884 7096 3908 7097 3884 7097 3883 7097 3909 7098 3910 7098 3885 7098 3909 7099 3885 7099 3884 7099 3910 7100 3911 7100 3886 7100 3910 7101 3886 7101 3885 7101 3911 7102 3912 7102 3887 7102 3911 7103 3887 7103 3886 7103 3912 7104 3913 7104 3888 7104 3912 7105 3888 7105 3887 7105 3913 7106 3914 7106 3889 7106 3913 7107 3889 7107 3888 7107 3914 7108 3915 7108 3890 7108 3914 7109 3890 7109 3889 7109 3915 7110 3916 7110 3891 7110 3915 7111 3891 7111 3890 7111 3916 7112 3917 7112 3892 7112 3916 7113 3892 7113 3891 7113 3917 7114 3918 7114 3894 7114 3917 7115 3894 7115 3892 7115 3918 7116 3919 7116 3896 7116 3918 7117 3896 7117 3894 7117 3919 7118 3920 7118 3899 7118 3919 7119 3899 7119 3896 7119 3920 7120 3921 7120 3901 7120 3920 7121 3901 7121 3899 7121 3921 7122 3685 7122 3688 7122 3921 7123 3688 7123 3901 7123 3922 7124 3923 7124 3924 7124 3922 7125 3924 7125 3925 7125 3926 7126 3927 7126 3928 7126 3926 7127 3928 7127 3929 7127 3927 7128 3930 7128 3931 7128 3927 7129 3931 7129 3928 7129 3930 7130 3932 7130 3933 7130 3930 7131 3933 7131 3931 7131 3932 7132 3934 7132 3935 7132 3932 7133 3935 7133 3933 7133 3934 7134 3936 7134 3937 7134 3934 7135 3937 7135 3935 7135 3936 7136 3938 7136 3939 7136 3936 7137 3939 7137 3937 7137 3938 7138 3940 7138 3941 7138 3938 7139 3941 7139 3939 7139 3940 7140 3942 7140 3943 7140 3940 7141 3943 7141 3941 7141 3942 7142 3944 7142 3945 7142 3942 7143 3945 7143 3943 7143 3944 7144 3946 7144 3947 7144 3944 7145 3947 7145 3945 7145 3946 7146 3948 7146 3949 7146 3946 7147 3949 7147 3947 7147 3948 7148 3681 7148 3684 7148 3948 7149 3684 7149 3949 7149 3665 7150 3950 7150 3951 7150 3665 7151 3951 7151 3666 7151 3950 7152 3952 7152 3953 7152 3950 7153 3953 7153 3951 7153 3952 7154 3954 7154 3955 7154 3952 7155 3955 7155 3953 7155 3954 7156 3956 7156 3957 7156 3954 7157 3957 7157 3955 7157 3956 7158 3958 7158 3959 7158 3956 7159 3959 7159 3957 7159 3958 7160 3960 7160 3961 7160 3958 7161 3961 7161 3959 7161 3960 7162 3962 7162 3963 7162 3960 7163 3963 7163 3961 7163 3962 7164 3964 7164 3965 7164 3962 7165 3965 7165 3963 7165 3964 7166 3966 7166 3967 7166 3964 7167 3967 7167 3965 7167 3966 7168 3968 7168 3969 7168 3966 7169 3969 7169 3967 7169 3968 7170 3970 7170 3971 7170 3968 7171 3971 7171 3969 7171 3970 7172 3972 7172 3973 7172 3970 7173 3973 7173 3971 7173 3972 7174 3974 7174 3975 7174 3972 7175 3975 7175 3973 7175 3974 7176 3976 7176 3977 7176 3974 7177 3977 7177 3975 7177 3976 7178 3978 7178 3979 7178 3976 7179 3979 7179 3977 7179 3978 7180 3980 7180 3981 7180 3978 7181 3981 7181 3979 7181 3980 7182 3982 7182 3983 7182 3980 7183 3983 7183 3981 7183 3982 7184 3984 7184 3985 7184 3982 7185 3985 7185 3983 7185 3984 7186 3986 7186 3987 7186 3984 7187 3987 7187 3985 7187 3986 7188 3677 7188 3680 7188 3986 7189 3680 7189 3987 7189 3663 7190 3988 7190 3950 7190 3663 7191 3950 7191 3665 7191 3988 7192 3989 7192 3952 7192 3988 7193 3952 7193 3950 7193 3989 7194 3990 7194 3954 7194 3989 7195 3954 7195 3952 7195 3990 7196 3991 7196 3956 7196 3990 7197 3956 7197 3954 7197 3991 7198 3992 7198 3958 7198 3991 7199 3958 7199 3956 7199 3992 7200 3993 7200 3960 7200 3992 7201 3960 7201 3958 7201 3993 7202 3994 7202 3962 7202 3993 7203 3962 7203 3960 7203 3994 7204 3995 7204 3964 7204 3994 7205 3964 7205 3962 7205 3995 7206 3996 7206 3966 7206 3995 7207 3966 7207 3964 7207 3996 7208 3997 7208 3968 7208 3996 7209 3968 7209 3966 7209 3997 7210 3998 7210 3970 7210 3997 7211 3970 7211 3968 7211 3998 7212 3999 7212 3972 7212 3998 7213 3972 7213 3970 7213 3999 7214 4000 7214 3974 7214 3999 7215 3974 7215 3972 7215 4000 7216 4001 7216 3976 7216 4000 7217 3976 7217 3974 7217 4001 7218 4002 7218 3978 7218 4001 7219 3978 7219 3976 7219 4002 7220 4003 7220 3980 7220 4002 7221 3980 7221 3978 7221 4003 7222 4004 7222 3982 7222 4003 7223 3982 7223 3980 7223 4004 7224 4005 7224 3984 7224 4004 7225 3984 7225 3982 7225 4005 7226 4006 7226 3986 7226 4005 7227 3986 7227 3984 7227 4006 7228 4007 7228 3677 7228 4006 7229 3677 7229 3986 7229 3662 7230 4008 7230 3988 7230 3662 7231 3988 7231 3663 7231 4008 7232 4009 7232 3989 7232 4008 7233 3989 7233 3988 7233 4009 7234 4010 7234 3990 7234 4009 7235 3990 7235 3989 7235 4010 7236 4011 7236 3991 7236 4010 7237 3991 7237 3990 7237 4011 7238 4012 7238 3992 7238 4011 7239 3992 7239 3991 7239 4012 7240 4013 7240 3993 7240 4012 7241 3993 7241 3992 7241 4013 7242 4014 7242 3994 7242 4013 7243 3994 7243 3993 7243 4014 7244 4015 7244 3995 7244 4014 7245 3995 7245 3994 7245 4015 7246 4016 7246 3996 7246 4015 7247 3996 7247 3995 7247 4016 7248 4017 7248 3997 7248 4016 7249 3997 7249 3996 7249 4017 7250 4018 7250 3998 7250 4017 7251 3998 7251 3997 7251 4018 7252 4019 7252 3999 7252 4018 7253 3999 7253 3998 7253 4019 7254 4020 7254 4000 7254 4019 7255 4000 7255 3999 7255 4020 7256 4021 7256 4001 7256 4020 7257 4001 7257 4000 7257 4001 7258 4021 7258 4022 7258 4022 7259 4023 7259 4002 7259 4022 7260 4002 7260 4001 7260 4024 7261 4025 7261 4005 7261 4024 7262 4005 7262 4004 7262 4025 7263 4026 7263 4005 7263 4026 7264 4006 7264 4005 7264 3660 7265 4027 7265 4028 7265 3660 7266 4028 7266 3661 7266 4027 7267 4029 7267 4030 7267 4027 7268 4030 7268 4028 7268 4029 7269 4031 7269 4032 7269 4029 7270 4032 7270 4030 7270 4031 7271 4033 7271 4034 7271 4031 7272 4034 7272 4032 7272 4033 7273 4035 7273 4036 7273 4033 7274 4036 7274 4034 7274 4035 7275 4037 7275 4038 7275 4035 7276 4038 7276 4036 7276 4037 7277 4039 7277 4040 7277 4037 7278 4040 7278 4038 7278 4039 7279 4041 7279 4042 7279 4039 7280 4042 7280 4040 7280 4041 7281 4043 7281 4044 7281 4041 7282 4044 7282 4042 7282 4043 7283 4045 7283 4046 7283 4043 7284 4046 7284 4044 7284 4045 7285 4047 7285 4048 7285 4045 7286 4048 7286 4046 7286 4047 7287 4049 7287 4050 7287 4047 7288 4050 7288 4048 7288 3659 7289 4051 7289 4027 7289 3659 7290 4027 7290 3660 7290 4051 7291 4052 7291 4029 7291 4051 7292 4029 7292 4027 7292 4052 7293 4053 7293 4031 7293 4052 7294 4031 7294 4029 7294 4053 7295 4054 7295 4033 7295 4053 7296 4033 7296 4031 7296 4054 7297 4055 7297 4035 7297 4054 7298 4035 7298 4033 7298 4055 7299 4056 7299 4037 7299 4055 7300 4037 7300 4035 7300 4056 7301 4057 7301 4039 7301 4056 7302 4039 7302 4037 7302 4057 7303 4058 7303 4041 7303 4057 7304 4041 7304 4039 7304 4058 7305 4059 7305 4043 7305 4058 7306 4043 7306 4041 7306 4059 7307 4060 7307 4045 7307 4059 7308 4045 7308 4043 7308 3658 7309 4061 7309 4051 7309 3658 7310 4051 7310 3659 7310 4061 7311 4062 7311 4052 7311 4061 7312 4052 7312 4051 7312 4062 7313 4063 7313 4053 7313 4062 7314 4053 7314 4052 7314 4063 7315 4064 7315 4054 7315 4063 7316 4054 7316 4053 7316 4064 7317 4065 7317 4055 7317 4064 7318 4055 7318 4054 7318 4065 7319 4066 7319 4056 7319 4065 7320 4056 7320 4055 7320 4066 7321 4067 7321 4057 7321 4066 7322 4057 7322 4056 7322 4067 7323 4068 7323 4058 7323 4067 7324 4058 7324 4057 7324 3657 7325 4069 7325 4061 7325 3657 7326 4061 7326 3658 7326 4069 7327 4070 7327 4062 7327 4069 7328 4062 7328 4061 7328 4070 7329 4071 7329 4063 7329 4070 7330 4063 7330 4062 7330 4071 7331 4072 7331 4064 7331 4071 7332 4064 7332 4063 7332 4072 7333 4073 7333 4065 7333 4072 7334 4065 7334 4064 7334 4073 7335 4074 7335 4066 7335 4073 7336 4066 7336 4065 7336 4074 7337 4075 7337 4067 7337 4074 7338 4067 7338 4066 7338 3656 7339 4076 7339 4069 7339 3656 7340 4069 7340 3657 7340 4076 7341 4077 7341 4070 7341 4076 7342 4070 7342 4069 7342 4077 7343 4078 7343 4071 7343 4077 7344 4071 7344 4070 7344 4078 7345 4079 7345 4072 7345 4078 7346 4072 7346 4071 7346 4079 7347 4080 7347 4073 7347 4079 7348 4073 7348 4072 7348 4080 7349 4081 7349 4074 7349 4080 7350 4074 7350 4073 7350 3655 7351 4082 7351 4076 7351 3655 7352 4076 7352 3656 7352 4082 7353 4083 7353 4077 7353 4082 7354 4077 7354 4076 7354 4083 7355 4084 7355 4078 7355 4083 7356 4078 7356 4077 7356 4084 7357 4085 7357 4079 7357 4084 7358 4079 7358 4078 7358 4085 7359 4086 7359 4080 7359 4085 7360 4080 7360 4079 7360 3588 7361 4087 7361 4082 7361 3588 7362 4082 7362 3655 7362 4087 7363 4088 7363 4083 7363 4087 7364 4083 7364 4082 7364 4088 7365 4089 7365 4084 7365 4088 7366 4084 7366 4083 7366 4089 7367 4090 7367 4085 7367 4089 7368 4085 7368 4084 7368 4090 7369 4091 7369 4086 7369 4090 7370 4086 7370 4085 7370 3571 7371 3763 7371 4092 7371 3571 7372 4092 7372 3572 7372 3763 7373 3765 7373 4093 7373 3763 7374 4093 7374 4092 7374 3765 7375 3767 7375 4094 7375 3765 7376 4094 7376 4093 7376 3767 7377 3769 7377 4095 7377 3767 7378 4095 7378 4094 7378 3769 7379 3771 7379 4096 7379 3769 7380 4096 7380 4095 7380 3771 7381 3773 7381 4097 7381 3771 7382 4097 7382 4096 7382 3773 7383 3775 7383 4098 7383 3773 7384 4098 7384 4097 7384 3775 7385 3777 7385 4099 7385 3775 7386 4099 7386 4098 7386 3777 7387 3779 7387 4100 7387 3777 7388 4100 7388 4099 7388 3779 7389 3781 7389 4101 7389 3779 7390 4101 7390 4100 7390 3781 7391 3783 7391 4102 7391 3781 7392 4102 7392 4101 7392 3783 7393 3785 7393 4103 7393 3783 7394 4103 7394 4102 7394 3785 7395 3787 7395 4104 7395 3785 7396 4104 7396 4103 7396 3587 7397 4105 7397 4087 7397 3587 7398 4087 7398 3588 7398 4105 7399 4106 7399 4088 7399 4105 7400 4088 7400 4087 7400 4106 7401 4107 7401 4089 7401 4106 7402 4089 7402 4088 7402 4107 7403 4108 7403 4090 7403 4107 7404 4090 7404 4089 7404 4108 7405 4109 7405 4091 7405 4108 7406 4091 7406 4090 7406 4109 7407 4110 7407 4111 7407 4109 7408 4111 7408 4091 7408 4110 7409 4112 7409 4113 7409 4110 7410 4113 7410 4111 7410 4112 7411 4114 7411 4115 7411 4112 7412 4115 7412 4113 7412 3579 7413 3692 7413 4116 7413 3579 7414 4116 7414 3580 7414 3692 7415 3694 7415 4117 7415 3692 7416 4117 7416 4116 7416 3694 7417 3696 7417 4118 7417 3694 7418 4118 7418 4117 7418 3696 7419 3698 7419 4119 7419 3696 7420 4119 7420 4118 7420 3698 7421 3700 7421 4120 7421 3698 7422 4120 7422 4119 7422 3700 7423 3702 7423 4121 7423 3700 7424 4121 7424 4120 7424 3702 7425 3704 7425 4122 7425 3702 7426 4122 7426 4121 7426 3704 7427 3706 7427 4123 7427 3704 7428 4123 7428 4122 7428 3583 7429 4124 7429 3746 7429 3583 7430 3746 7430 3584 7430 4124 7431 4125 7431 3747 7431 4124 7432 3747 7432 3746 7432 4125 7433 4126 7433 3748 7433 4125 7434 3748 7434 3747 7434 4126 7435 4127 7435 3749 7435 4126 7436 3749 7436 3748 7436 4127 7437 4128 7437 3750 7437 4127 7438 3750 7438 3749 7438 4128 7439 4129 7439 3751 7439 4128 7440 3751 7440 3750 7440 4129 7441 4130 7441 3752 7441 4129 7442 3752 7442 3751 7442 4130 7443 4131 7443 3754 7443 4130 7444 3754 7444 3752 7444 4131 7445 4132 7445 3756 7445 4131 7446 3756 7446 3754 7446 4132 7447 3760 7447 4133 7447 4132 7448 4133 7448 3756 7448 4134 7449 4135 7449 4136 7449 4134 7450 4136 7450 4137 7450 4137 7451 4136 7451 4138 7451 4137 7452 4138 7452 4139 7452 4139 7453 4138 7453 4140 7453 4139 7454 4140 7454 4141 7454 4141 7455 4140 7455 4142 7455 4141 7456 4142 7456 4143 7456 4143 7457 4142 7457 4144 7457 4142 7458 4145 7458 4144 7458 4103 7459 4104 7459 4146 7459 4103 7460 4146 7460 4147 7460 4147 7461 4146 7461 4134 7461 4147 7462 4134 7462 4148 7462 4148 7463 4134 7463 4137 7463 4148 7464 4137 7464 4149 7464 4149 7465 4137 7465 4139 7465 4149 7466 4139 7466 4150 7466 4150 7467 4139 7467 4141 7467 4150 7468 4141 7468 4151 7468 4151 7469 4141 7469 4143 7469 4151 7470 4143 7470 4152 7470 4152 7471 4143 7471 4144 7471 4152 7472 4144 7472 4153 7472 4102 7473 4103 7473 4147 7473 4102 7474 4147 7474 4154 7474 4154 7475 4147 7475 4148 7475 4154 7476 4148 7476 4155 7476 4155 7477 4148 7477 4149 7477 4155 7478 4149 7478 4156 7478 4156 7479 4149 7479 4150 7479 4156 7480 4150 7480 4157 7480 4157 7481 4150 7481 4151 7481 4157 7482 4151 7482 4158 7482 4158 7483 4151 7483 4152 7483 4158 7484 4152 7484 4159 7484 4159 7485 4152 7485 4153 7485 4159 7486 4153 7486 4160 7486 4160 7487 4153 7487 4161 7487 4160 7488 4161 7488 4162 7488 4162 7489 4161 7489 4163 7489 4162 7490 4163 7490 4164 7490 4164 7491 4163 7491 4165 7491 4164 7492 4165 7492 4166 7492 4166 7493 4165 7493 4167 7493 4166 7494 4167 7494 4168 7494 4168 7495 4167 7495 4169 7495 4168 7496 4169 7496 4170 7496 4170 7497 4169 7497 4171 7497 4170 7498 4171 7498 4172 7498 4172 7499 4171 7499 4173 7499 4172 7500 4173 7500 4174 7500 4174 7501 4173 7501 4175 7501 4174 7502 4175 7502 4176 7502 4176 7503 4175 7503 4177 7503 4176 7504 4177 7504 4178 7504 4178 7505 4177 7505 4179 7505 4178 7506 4179 7506 4180 7506 4181 7507 4182 7507 4183 7507 4181 7508 4183 7508 4184 7508 4184 7509 4183 7509 3758 7509 4184 7510 3758 7510 3761 7510 4101 7511 4102 7511 4154 7511 4101 7512 4154 7512 4185 7512 4185 7513 4154 7513 4155 7513 4185 7514 4155 7514 4186 7514 4186 7515 4155 7515 4156 7515 4186 7516 4156 7516 4187 7516 4187 7517 4156 7517 4157 7517 4187 7518 4157 7518 4188 7518 4188 7519 4157 7519 4158 7519 4188 7520 4158 7520 4189 7520 4189 7521 4158 7521 4159 7521 4189 7522 4159 7522 4190 7522 4190 7523 4159 7523 4160 7523 4190 7524 4160 7524 4191 7524 4191 7525 4160 7525 4162 7525 4191 7526 4162 7526 4192 7526 4192 7527 4162 7527 4164 7527 4192 7528 4164 7528 4193 7528 4193 7529 4164 7529 4166 7529 4193 7530 4166 7530 4194 7530 4194 7531 4166 7531 4168 7531 4194 7532 4168 7532 4195 7532 4195 7533 4168 7533 4170 7533 4195 7534 4170 7534 4196 7534 4196 7535 4170 7535 4172 7535 4196 7536 4172 7536 4197 7536 4197 7537 4172 7537 4174 7537 4197 7538 4174 7538 4198 7538 4198 7539 4174 7539 4176 7539 4198 7540 4176 7540 4199 7540 4199 7541 4176 7541 4178 7541 4199 7542 4178 7542 4200 7542 4200 7543 4178 7543 4180 7543 4200 7544 4180 7544 4201 7544 4201 7545 4180 7545 4181 7545 4201 7546 4181 7546 4202 7546 4202 7547 4181 7547 4184 7547 4202 7548 4184 7548 4203 7548 4203 7549 4184 7549 3761 7549 4203 7550 3761 7550 3760 7550 4100 7551 4101 7551 4185 7551 4100 7552 4185 7552 4204 7552 4204 7553 4185 7553 4186 7553 4204 7554 4186 7554 4205 7554 4205 7555 4186 7555 4187 7555 4205 7556 4187 7556 4206 7556 4206 7557 4187 7557 4188 7557 4206 7558 4188 7558 4207 7558 4207 7559 4188 7559 4189 7559 4207 7560 4189 7560 4208 7560 4208 7561 4189 7561 4190 7561 4208 7562 4190 7562 4209 7562 4209 7563 4190 7563 4191 7563 4209 7564 4191 7564 4210 7564 4210 7565 4191 7565 4192 7565 4210 7566 4192 7566 4211 7566 4211 7567 4192 7567 4193 7567 4211 7568 4193 7568 4212 7568 4212 7569 4193 7569 4194 7569 4212 7570 4194 7570 4213 7570 4213 7571 4194 7571 4195 7571 4213 7572 4195 7572 4214 7572 4214 7573 4195 7573 4196 7573 4214 7574 4196 7574 4215 7574 4215 7575 4196 7575 4197 7575 4215 7576 4197 7576 4216 7576 4216 7577 4197 7577 4198 7577 4216 7578 4198 7578 4217 7578 4217 7579 4198 7579 4199 7579 4217 7580 4199 7580 4218 7580 4218 7581 4199 7581 4200 7581 4218 7582 4200 7582 4219 7582 4219 7583 4200 7583 4201 7583 4219 7584 4201 7584 4220 7584 4220 7585 4201 7585 4202 7585 4220 7586 4202 7586 4221 7586 4221 7587 4202 7587 4203 7587 4221 7588 4203 7588 4222 7588 4222 7589 4203 7589 3760 7589 4222 7590 3760 7590 4132 7590 4099 7591 4100 7591 4204 7591 4099 7592 4204 7592 4223 7592 4223 7593 4204 7593 4205 7593 4223 7594 4205 7594 4224 7594 4224 7595 4205 7595 4206 7595 4224 7596 4206 7596 4225 7596 4225 7597 4206 7597 4207 7597 4225 7598 4207 7598 4226 7598 4226 7599 4207 7599 4208 7599 4226 7600 4208 7600 4227 7600 4227 7601 4208 7601 4209 7601 4227 7602 4209 7602 4228 7602 4228 7603 4209 7603 4210 7603 4228 7604 4210 7604 4229 7604 4229 7605 4210 7605 4211 7605 4229 7606 4211 7606 4230 7606 4230 7607 4211 7607 4212 7607 4230 7608 4212 7608 4231 7608 4231 7609 4212 7609 4213 7609 4231 7610 4213 7610 4232 7610 4232 7611 4213 7611 4214 7611 4232 7612 4214 7612 4233 7612 4233 7613 4214 7613 4215 7613 4233 7614 4215 7614 4234 7614 4234 7615 4215 7615 4216 7615 4234 7616 4216 7616 4235 7616 4235 7617 4216 7617 4217 7617 4235 7618 4217 7618 4236 7618 4236 7619 4217 7619 4218 7619 4236 7620 4218 7620 4237 7620 4237 7621 4218 7621 4219 7621 4237 7622 4219 7622 4238 7622 4238 7623 4219 7623 4220 7623 4238 7624 4220 7624 4239 7624 4239 7625 4220 7625 4221 7625 4239 7626 4221 7626 4240 7626 4240 7627 4221 7627 4222 7627 4240 7628 4222 7628 4241 7628 4241 7629 4222 7629 4132 7629 4241 7630 4132 7630 4131 7630 4098 7631 4099 7631 4223 7631 4098 7632 4223 7632 4242 7632 4242 7633 4223 7633 4224 7633 4242 7634 4224 7634 4243 7634 4243 7635 4224 7635 4225 7635 4243 7636 4225 7636 4244 7636 4244 7637 4225 7637 4226 7637 4244 7638 4226 7638 4245 7638 4245 7639 4226 7639 4227 7639 4245 7640 4227 7640 4246 7640 4246 7641 4227 7641 4228 7641 4246 7642 4228 7642 4247 7642 4247 7643 4228 7643 4229 7643 4247 7644 4229 7644 4248 7644 4248 7645 4229 7645 4230 7645 4248 7646 4230 7646 4249 7646 4249 7647 4230 7647 4231 7647 4249 7648 4231 7648 4250 7648 4250 7649 4231 7649 4232 7649 4250 7650 4232 7650 4251 7650 4251 7651 4232 7651 4233 7651 4251 7652 4233 7652 4252 7652 4252 7653 4233 7653 4234 7653 4252 7654 4234 7654 4253 7654 4253 7655 4234 7655 4235 7655 4253 7656 4235 7656 4254 7656 4254 7657 4235 7657 4236 7657 4254 7658 4236 7658 4255 7658 4255 7659 4236 7659 4237 7659 4255 7660 4237 7660 4256 7660 4256 7661 4237 7661 4238 7661 4256 7662 4238 7662 4257 7662 4257 7663 4238 7663 4239 7663 4257 7664 4239 7664 4258 7664 4258 7665 4239 7665 4240 7665 4258 7666 4240 7666 4259 7666 4259 7667 4240 7667 4241 7667 4259 7668 4241 7668 4260 7668 4260 7669 4241 7669 4131 7669 4260 7670 4131 7670 4130 7670 4097 7671 4098 7671 4242 7671 4097 7672 4242 7672 4261 7672 4261 7673 4242 7673 4243 7673 4261 7674 4243 7674 4262 7674 4262 7675 4243 7675 4244 7675 4262 7676 4244 7676 4263 7676 4263 7677 4244 7677 4245 7677 4263 7678 4245 7678 4264 7678 4264 7679 4245 7679 4246 7679 4264 7680 4246 7680 4265 7680 4265 7681 4246 7681 4247 7681 4265 7682 4247 7682 4266 7682 4266 7683 4247 7683 4248 7683 4266 7684 4248 7684 4267 7684 4267 7685 4248 7685 4249 7685 4267 7686 4249 7686 4268 7686 4268 7687 4249 7687 4250 7687 4268 7688 4250 7688 4269 7688 4269 7689 4250 7689 4251 7689 4269 7690 4251 7690 4270 7690 4270 7691 4251 7691 4252 7691 4270 7692 4252 7692 4271 7692 4271 7693 4252 7693 4253 7693 4271 7694 4253 7694 4272 7694 4272 7695 4253 7695 4254 7695 4272 7696 4254 7696 4273 7696 4273 7697 4254 7697 4255 7697 4273 7698 4255 7698 4274 7698 4274 7699 4255 7699 4256 7699 4274 7700 4256 7700 4275 7700 4275 7701 4256 7701 4257 7701 4275 7702 4257 7702 4276 7702 4276 7703 4257 7703 4258 7703 4276 7704 4258 7704 4277 7704 4277 7705 4258 7705 4259 7705 4277 7706 4259 7706 4278 7706 4278 7707 4259 7707 4260 7707 4278 7708 4260 7708 4279 7708 4279 7709 4260 7709 4130 7709 4279 7710 4130 7710 4129 7710 4096 7711 4097 7711 4261 7711 4096 7712 4261 7712 4280 7712 4280 7713 4261 7713 4262 7713 4280 7714 4262 7714 4281 7714 4281 7715 4262 7715 4263 7715 4281 7716 4263 7716 4282 7716 4282 7717 4263 7717 4264 7717 4282 7718 4264 7718 4283 7718 4283 7719 4264 7719 4265 7719 4283 7720 4265 7720 4284 7720 4284 7721 4265 7721 4266 7721 4284 7722 4266 7722 4285 7722 4285 7723 4266 7723 4267 7723 4285 7724 4267 7724 4286 7724 4286 7725 4267 7725 4268 7725 4286 7726 4268 7726 4287 7726 4287 7727 4268 7727 4269 7727 4287 7728 4269 7728 4288 7728 4288 7729 4269 7729 4270 7729 4288 7730 4270 7730 4289 7730 4289 7731 4270 7731 4271 7731 4289 7732 4271 7732 4290 7732 4290 7733 4271 7733 4272 7733 4290 7734 4272 7734 4291 7734 4291 7735 4272 7735 4273 7735 4291 7736 4273 7736 4292 7736 4292 7737 4273 7737 4274 7737 4292 7738 4274 7738 4293 7738 4293 7739 4274 7739 4275 7739 4293 7740 4275 7740 4294 7740 4294 7741 4275 7741 4276 7741 4294 7742 4276 7742 4295 7742 4295 7743 4276 7743 4277 7743 4295 7744 4277 7744 4296 7744 4296 7745 4277 7745 4278 7745 4296 7746 4278 7746 4297 7746 4297 7747 4278 7747 4279 7747 4297 7748 4279 7748 4298 7748 4298 7749 4279 7749 4129 7749 4298 7750 4129 7750 4128 7750 4095 7751 4096 7751 4280 7751 4095 7752 4280 7752 4299 7752 4299 7753 4280 7753 4281 7753 4299 7754 4281 7754 4300 7754 4300 7755 4281 7755 4282 7755 4300 7756 4282 7756 4301 7756 4301 7757 4282 7757 4283 7757 4301 7758 4283 7758 4302 7758 4302 7759 4283 7759 4284 7759 4302 7760 4284 7760 4303 7760 4303 7761 4284 7761 4285 7761 4303 7762 4285 7762 4304 7762 4304 7763 4285 7763 4286 7763 4304 7764 4286 7764 4305 7764 4305 7765 4286 7765 4287 7765 4305 7766 4287 7766 4306 7766 4306 7767 4287 7767 4288 7767 4306 7768 4288 7768 4307 7768 4307 7769 4288 7769 4289 7769 4307 7770 4289 7770 4308 7770 4308 7771 4289 7771 4290 7771 4308 7772 4290 7772 4309 7772 4309 7773 4290 7773 4291 7773 4309 7774 4291 7774 4310 7774 4310 7775 4291 7775 4292 7775 4310 7776 4292 7776 4311 7776 4311 7777 4292 7777 4293 7777 4311 7778 4293 7778 4312 7778 4312 7779 4293 7779 4294 7779 4312 7780 4294 7780 4313 7780 4313 7781 4294 7781 4295 7781 4313 7782 4295 7782 4314 7782 4314 7783 4295 7783 4296 7783 4314 7784 4296 7784 4315 7784 4315 7785 4296 7785 4297 7785 4315 7786 4297 7786 4316 7786 4316 7787 4297 7787 4298 7787 4316 7788 4298 7788 4317 7788 4317 7789 4298 7789 4128 7789 4317 7790 4128 7790 4127 7790 4094 7791 4095 7791 4299 7791 4094 7792 4299 7792 4318 7792 4318 7793 4299 7793 4300 7793 4318 7794 4300 7794 4319 7794 4319 7795 4300 7795 4301 7795 4319 7796 4301 7796 4320 7796 4320 7797 4301 7797 4302 7797 4320 7798 4302 7798 4321 7798 4321 7799 4302 7799 4303 7799 4321 7800 4303 7800 4322 7800 4322 7801 4303 7801 4304 7801 4322 7802 4304 7802 4323 7802 4323 7803 4304 7803 4305 7803 4323 7804 4305 7804 4324 7804 4324 7805 4305 7805 4306 7805 4324 7806 4306 7806 4325 7806 4325 7807 4306 7807 4307 7807 4325 7808 4307 7808 4326 7808 4326 7809 4307 7809 4308 7809 4326 7810 4308 7810 4327 7810 4327 7811 4308 7811 4309 7811 4327 7812 4309 7812 4328 7812 4328 7813 4309 7813 4310 7813 4328 7814 4310 7814 4329 7814 4329 7815 4310 7815 4311 7815 4329 7816 4311 7816 4330 7816 4330 7817 4311 7817 4312 7817 4330 7818 4312 7818 4331 7818 4331 7819 4312 7819 4313 7819 4331 7820 4313 7820 4332 7820 4332 7821 4313 7821 4314 7821 4332 7822 4314 7822 4333 7822 4333 7823 4314 7823 4315 7823 4333 7824 4315 7824 4334 7824 4334 7825 4315 7825 4316 7825 4334 7826 4316 7826 4335 7826 4335 7827 4316 7827 4317 7827 4335 7828 4317 7828 4336 7828 4336 7829 4317 7829 4127 7829 4336 7830 4127 7830 4126 7830 4093 7831 4094 7831 4318 7831 4093 7832 4318 7832 4337 7832 4337 7833 4318 7833 4319 7833 4337 7834 4319 7834 4338 7834 4338 7835 4319 7835 4320 7835 4338 7836 4320 7836 4339 7836 4339 7837 4320 7837 4321 7837 4339 7838 4321 7838 4340 7838 4340 7839 4321 7839 4322 7839 4340 7840 4322 7840 4341 7840 4341 7841 4322 7841 4323 7841 4341 7842 4323 7842 4342 7842 4342 7843 4323 7843 4324 7843 4342 7844 4324 7844 4343 7844 4343 7845 4324 7845 4325 7845 4343 7846 4325 7846 4344 7846 4344 7847 4325 7847 4326 7847 4344 7848 4326 7848 4345 7848 4345 7849 4326 7849 4327 7849 4345 7850 4327 7850 4346 7850 4346 7851 4327 7851 4328 7851 4346 7852 4328 7852 4347 7852 4347 7853 4328 7853 4329 7853 4347 7854 4329 7854 4348 7854 4348 7855 4329 7855 4330 7855 4348 7856 4330 7856 4349 7856 4349 7857 4330 7857 4331 7857 4349 7858 4331 7858 4350 7858 4350 7859 4331 7859 4332 7859 4350 7860 4332 7860 4351 7860 4351 7861 4332 7861 4333 7861 4351 7862 4333 7862 4352 7862 4352 7863 4333 7863 4334 7863 4352 7864 4334 7864 4353 7864 4353 7865 4334 7865 4335 7865 4353 7866 4335 7866 4354 7866 4354 7867 4335 7867 4336 7867 4354 7868 4336 7868 4355 7868 4355 7869 4336 7869 4126 7869 4355 7870 4126 7870 4125 7870 4092 7871 4093 7871 4337 7871 4092 7872 4337 7872 4356 7872 4356 7873 4337 7873 4338 7873 4356 7874 4338 7874 4357 7874 4357 7875 4338 7875 4339 7875 4357 7876 4339 7876 4358 7876 4358 7877 4339 7877 4340 7877 4358 7878 4340 7878 4359 7878 4359 7879 4340 7879 4341 7879 4359 7880 4341 7880 4360 7880 4360 7881 4341 7881 4342 7881 4360 7882 4342 7882 4361 7882 4361 7883 4342 7883 4343 7883 4361 7884 4343 7884 4362 7884 4362 7885 4343 7885 4344 7885 4362 7886 4344 7886 4363 7886 4363 7887 4344 7887 4345 7887 4363 7888 4345 7888 4364 7888 4364 7889 4345 7889 4346 7889 4364 7890 4346 7890 4365 7890 4365 7891 4346 7891 4347 7891 4365 7892 4347 7892 4366 7892 4366 7893 4347 7893 4348 7893 4366 7894 4348 7894 4367 7894 4367 7895 4348 7895 4349 7895 4367 7896 4349 7896 4368 7896 4368 7897 4349 7897 4350 7897 4368 7898 4350 7898 4369 7898 4369 7899 4350 7899 4351 7899 4369 7900 4351 7900 4370 7900 4370 7901 4351 7901 4352 7901 4370 7902 4352 7902 4371 7902 4371 7903 4352 7903 4353 7903 4371 7904 4353 7904 4372 7904 4372 7905 4353 7905 4354 7905 4372 7906 4354 7906 4373 7906 4373 7907 4354 7907 4355 7907 4373 7908 4355 7908 4374 7908 4374 7909 4355 7909 4125 7909 4374 7910 4125 7910 4124 7910 3572 7911 4092 7911 4356 7911 3572 7912 4356 7912 4375 7912 4375 7913 4356 7913 4357 7913 4375 7914 4357 7914 4376 7914 4376 7915 4357 7915 4358 7915 4376 7916 4358 7916 4377 7916 4377 7917 4358 7917 4359 7917 4377 7918 4359 7918 4378 7918 4378 7919 4359 7919 4360 7919 4378 7920 4360 7920 4379 7920 4379 7921 4360 7921 4361 7921 4379 7922 4361 7922 4380 7922 4380 7923 4361 7923 4362 7923 4380 7924 4362 7924 4381 7924 4381 7925 4362 7925 4363 7925 4381 7926 4363 7926 4382 7926 4382 7927 4363 7927 4364 7927 4382 7928 4364 7928 4383 7928 4383 7929 4364 7929 4365 7929 4383 7930 4365 7930 4384 7930 4384 7931 4365 7931 4366 7931 4384 7932 4366 7932 4385 7932 4385 7933 4366 7933 4367 7933 4385 7934 4367 7934 4386 7934 4386 7935 4367 7935 4368 7935 4386 7936 4368 7936 4387 7936 4387 7937 4368 7937 4369 7937 4387 7938 4369 7938 4388 7938 4388 7939 4369 7939 4370 7939 4388 7940 4370 7940 4389 7940 4389 7941 4370 7941 4371 7941 4389 7942 4371 7942 4390 7942 4390 7943 4371 7943 4372 7943 4390 7944 4372 7944 4391 7944 4391 7945 4372 7945 4373 7945 4391 7946 4373 7946 4392 7946 4392 7947 4373 7947 4374 7947 4392 7948 4374 7948 4393 7948 4393 7949 4374 7949 4124 7949 4393 7950 4124 7950 3583 7950 4394 7951 4395 7951 4396 7951 4394 7952 4396 7952 4397 7952 4397 7953 4396 7953 4398 7953 4397 7954 4398 7954 4399 7954 4123 7955 4400 7955 4401 7955 4400 7956 4402 7956 4401 7956 4401 7957 4402 7957 4403 7957 4402 7958 4404 7958 4403 7958 4403 7959 4404 7959 4405 7959 4403 7960 4405 7960 4406 7960 4406 7961 4405 7961 4394 7961 4406 7962 4394 7962 4407 7962 4407 7963 4394 7963 4397 7963 4407 7964 4397 7964 4408 7964 4408 7965 4397 7965 4399 7965 4408 7966 4399 7966 4409 7966 4409 7967 4399 7967 4410 7967 4409 7968 4410 7968 4411 7968 4411 7969 4410 7969 4412 7969 4411 7970 4412 7970 4413 7970 4413 7971 4412 7971 4414 7971 4413 7972 4414 7972 4415 7972 4415 7973 4414 7973 4416 7973 4415 7974 4416 7974 4417 7974 4417 7975 4416 7975 4418 7975 4416 7976 4419 7976 4418 7976 4418 7977 4419 7977 4420 7977 4419 7978 4421 7978 4420 7978 4420 7979 4421 7979 4422 7979 4421 7980 4423 7980 4422 7980 4422 7981 4423 7981 4424 7981 4422 7982 4424 7982 4425 7982 4425 7983 4424 7983 4426 7983 4425 7984 4426 7984 4427 7984 4427 7985 4426 7985 4428 7985 4427 7986 4428 7986 4429 7986 4429 7987 4428 7987 4430 7987 4429 7988 4430 7988 4431 7988 4122 7989 4123 7989 4401 7989 4122 7990 4401 7990 4432 7990 4433 7991 4403 7991 4406 7991 4433 7992 4406 7992 4434 7992 4434 7993 4406 7993 4407 7993 4434 7994 4407 7994 4435 7994 4435 7995 4407 7995 4408 7995 4435 7996 4408 7996 4436 7996 4436 7997 4408 7997 4409 7997 4436 7998 4409 7998 4437 7998 4437 7999 4409 7999 4411 7999 4437 8000 4411 8000 4438 8000 4438 8001 4411 8001 4413 8001 4438 8002 4413 8002 4439 8002 4439 8003 4413 8003 4415 8003 4439 8004 4415 8004 4440 8004 4440 8005 4415 8005 4417 8005 4440 8006 4417 8006 4441 8006 4441 8007 4417 8007 4418 8007 4441 8008 4418 8008 4442 8008 4442 8009 4418 8009 4420 8009 4442 8010 4420 8010 4443 8010 4443 8011 4420 8011 4444 8011 4420 8012 4422 8012 4444 8012 4444 8013 4422 8013 4425 8013 4444 8014 4425 8014 4445 8014 4445 8015 4425 8015 4427 8015 4445 8016 4427 8016 4446 8016 4446 8017 4427 8017 4429 8017 4446 8018 4429 8018 4447 8018 4447 8019 4429 8019 4431 8019 4447 8020 4431 8020 4448 8020 4448 8021 4431 8021 4449 8021 4448 8022 4449 8022 4450 8022 4450 8023 4449 8023 4451 8023 4450 8024 4451 8024 4452 8024 4452 8025 4451 8025 4114 8025 4452 8026 4114 8026 4112 8026 4121 8027 4122 8027 4432 8027 4121 8028 4432 8028 4453 8028 4453 8029 4432 8029 4433 8029 4453 8030 4433 8030 4454 8030 4454 8031 4433 8031 4434 8031 4454 8032 4434 8032 4455 8032 4455 8033 4434 8033 4435 8033 4455 8034 4435 8034 4456 8034 4456 8035 4435 8035 4436 8035 4456 8036 4436 8036 4457 8036 4457 8037 4436 8037 4437 8037 4457 8038 4437 8038 4458 8038 4458 8039 4437 8039 4438 8039 4458 8040 4438 8040 4459 8040 4459 8041 4438 8041 4439 8041 4459 8042 4439 8042 4460 8042 4460 8043 4439 8043 4440 8043 4460 8044 4440 8044 4461 8044 4461 8045 4440 8045 4441 8045 4461 8046 4441 8046 4462 8046 4462 8047 4441 8047 4442 8047 4462 8048 4442 8048 4463 8048 4463 8049 4442 8049 4443 8049 4463 8050 4443 8050 4464 8050 4464 8051 4443 8051 4444 8051 4464 8052 4444 8052 4465 8052 4465 8053 4444 8053 4445 8053 4465 8054 4445 8054 4466 8054 4467 8055 4446 8055 4447 8055 4467 8056 4447 8056 4468 8056 4468 8057 4447 8057 4448 8057 4468 8058 4448 8058 4469 8058 4469 8059 4448 8059 4450 8059 4469 8060 4450 8060 4470 8060 4470 8061 4450 8061 4452 8061 4470 8062 4452 8062 4471 8062 4471 8063 4452 8063 4112 8063 4471 8064 4112 8064 4110 8064 4120 8065 4121 8065 4453 8065 4120 8066 4453 8066 4472 8066 4472 8067 4453 8067 4454 8067 4472 8068 4454 8068 4473 8068 4473 8069 4454 8069 4455 8069 4473 8070 4455 8070 4474 8070 4474 8071 4455 8071 4456 8071 4474 8072 4456 8072 4475 8072 4475 8073 4456 8073 4457 8073 4475 8074 4457 8074 4476 8074 4476 8075 4457 8075 4458 8075 4476 8076 4458 8076 4477 8076 4477 8077 4458 8077 4459 8077 4477 8078 4459 8078 4478 8078 4478 8079 4459 8079 4460 8079 4478 8080 4460 8080 4479 8080 4479 8081 4460 8081 4461 8081 4479 8082 4461 8082 4480 8082 4480 8083 4461 8083 4462 8083 4480 8084 4462 8084 4481 8084 4481 8085 4462 8085 4463 8085 4481 8086 4463 8086 4482 8086 4482 8087 4463 8087 4464 8087 4482 8088 4464 8088 4483 8088 4484 8089 4465 8089 4466 8089 4484 8090 4466 8090 4485 8090 4486 8091 4467 8091 4468 8091 4486 8092 4468 8092 4487 8092 4487 8093 4468 8093 4469 8093 4487 8094 4469 8094 4488 8094 4488 8095 4469 8095 4470 8095 4488 8096 4470 8096 4489 8096 4489 8097 4470 8097 4471 8097 4489 8098 4471 8098 4490 8098 4490 8099 4471 8099 4110 8099 4490 8100 4110 8100 4109 8100 4119 8101 4120 8101 4472 8101 4119 8102 4472 8102 4491 8102 4491 8103 4472 8103 4473 8103 4491 8104 4473 8104 4492 8104 4492 8105 4473 8105 4474 8105 4492 8106 4474 8106 4493 8106 4493 8107 4474 8107 4475 8107 4493 8108 4475 8108 4494 8108 4494 8109 4475 8109 4476 8109 4494 8110 4476 8110 4495 8110 4495 8111 4476 8111 4477 8111 4495 8112 4477 8112 4496 8112 4496 8113 4477 8113 4478 8113 4496 8114 4478 8114 4497 8114 4497 8115 4478 8115 4479 8115 4497 8116 4479 8116 4498 8116 4498 8117 4479 8117 4480 8117 4498 8118 4480 8118 4499 8118 4499 8119 4480 8119 4481 8119 4499 8120 4481 8120 4500 8120 4500 8121 4481 8121 4482 8121 4500 8122 4482 8122 4501 8122 4501 8123 4482 8123 4483 8123 4501 8124 4483 8124 4502 8124 4502 8125 4483 8125 4484 8125 4502 8126 4484 8126 4503 8126 4503 8127 4484 8127 4485 8127 4503 8128 4485 8128 4504 8128 4504 8129 4485 8129 4486 8129 4504 8130 4486 8130 4505 8130 4505 8131 4486 8131 4487 8131 4505 8132 4487 8132 4506 8132 4506 8133 4487 8133 4488 8133 4506 8134 4488 8134 4507 8134 4507 8135 4488 8135 4489 8135 4507 8136 4489 8136 4508 8136 4508 8137 4489 8137 4490 8137 4508 8138 4490 8138 4509 8138 4509 8139 4490 8139 4109 8139 4509 8140 4109 8140 4108 8140 4118 8141 4119 8141 4491 8141 4118 8142 4491 8142 4510 8142 4510 8143 4491 8143 4492 8143 4510 8144 4492 8144 4511 8144 4511 8145 4492 8145 4493 8145 4511 8146 4493 8146 4512 8146 4512 8147 4493 8147 4494 8147 4512 8148 4494 8148 4513 8148 4513 8149 4494 8149 4495 8149 4513 8150 4495 8150 4514 8150 4514 8151 4495 8151 4496 8151 4514 8152 4496 8152 4515 8152 4515 8153 4496 8153 4497 8153 4515 8154 4497 8154 4516 8154 4516 8155 4497 8155 4498 8155 4516 8156 4498 8156 4517 8156 4517 8157 4498 8157 4499 8157 4517 8158 4499 8158 4518 8158 4518 8159 4499 8159 4500 8159 4518 8160 4500 8160 4519 8160 4519 8161 4500 8161 4501 8161 4519 8162 4501 8162 4520 8162 4520 8163 4501 8163 4502 8163 4520 8164 4502 8164 4521 8164 4521 8165 4502 8165 4503 8165 4521 8166 4503 8166 4522 8166 4522 8167 4503 8167 4504 8167 4522 8168 4504 8168 4523 8168 4523 8169 4504 8169 4505 8169 4523 8170 4505 8170 4524 8170 4524 8171 4505 8171 4506 8171 4524 8172 4506 8172 4525 8172 4525 8173 4506 8173 4507 8173 4525 8174 4507 8174 4526 8174 4526 8175 4507 8175 4508 8175 4526 8176 4508 8176 4527 8176 4527 8177 4508 8177 4509 8177 4527 8178 4509 8178 4528 8178 4528 8179 4509 8179 4108 8179 4528 8180 4108 8180 4107 8180 4117 8181 4118 8181 4510 8181 4117 8182 4510 8182 4529 8182 4529 8183 4510 8183 4511 8183 4529 8184 4511 8184 4530 8184 4530 8185 4511 8185 4512 8185 4530 8186 4512 8186 4531 8186 4531 8187 4512 8187 4513 8187 4531 8188 4513 8188 4532 8188 4532 8189 4513 8189 4514 8189 4532 8190 4514 8190 4533 8190 4533 8191 4514 8191 4515 8191 4533 8192 4515 8192 4534 8192 4534 8193 4515 8193 4516 8193 4534 8194 4516 8194 4535 8194 4535 8195 4516 8195 4517 8195 4535 8196 4517 8196 4536 8196 4536 8197 4517 8197 4518 8197 4536 8198 4518 8198 4537 8198 4537 8199 4518 8199 4519 8199 4537 8200 4519 8200 4538 8200 4538 8201 4519 8201 4520 8201 4538 8202 4520 8202 4539 8202 4539 8203 4520 8203 4521 8203 4539 8204 4521 8204 4540 8204 4540 8205 4521 8205 4522 8205 4540 8206 4522 8206 4541 8206 4541 8207 4522 8207 4523 8207 4541 8208 4523 8208 4542 8208 4542 8209 4523 8209 4524 8209 4542 8210 4524 8210 4543 8210 4543 8211 4524 8211 4525 8211 4543 8212 4525 8212 4544 8212 4544 8213 4525 8213 4526 8213 4544 8214 4526 8214 4545 8214 4545 8215 4526 8215 4527 8215 4545 8216 4527 8216 4546 8216 4546 8217 4527 8217 4528 8217 4546 8218 4528 8218 4547 8218 4547 8219 4528 8219 4107 8219 4547 8220 4107 8220 4106 8220 4116 8221 4117 8221 4529 8221 4116 8222 4529 8222 4548 8222 4548 8223 4529 8223 4530 8223 4548 8224 4530 8224 4549 8224 4549 8225 4530 8225 4531 8225 4549 8226 4531 8226 4550 8226 4550 8227 4531 8227 4532 8227 4550 8228 4532 8228 4551 8228 4551 8229 4532 8229 4533 8229 4551 8230 4533 8230 4552 8230 4552 8231 4533 8231 4534 8231 4552 8232 4534 8232 4553 8232 4553 8233 4534 8233 4535 8233 4553 8234 4535 8234 4554 8234 4554 8235 4535 8235 4536 8235 4554 8236 4536 8236 4555 8236 4555 8237 4536 8237 4537 8237 4555 8238 4537 8238 4556 8238 4556 8239 4537 8239 4538 8239 4556 8240 4538 8240 4557 8240 4557 8241 4538 8241 4539 8241 4557 8242 4539 8242 4558 8242 4558 8243 4539 8243 4540 8243 4558 8244 4540 8244 4559 8244 4559 8245 4540 8245 4541 8245 4559 8246 4541 8246 4560 8246 4560 8247 4541 8247 4542 8247 4560 8248 4542 8248 4561 8248 4561 8249 4542 8249 4543 8249 4561 8250 4543 8250 4562 8250 4562 8251 4543 8251 4544 8251 4562 8252 4544 8252 4563 8252 4563 8253 4544 8253 4545 8253 4563 8254 4545 8254 4564 8254 4564 8255 4545 8255 4546 8255 4564 8256 4546 8256 4565 8256 4565 8257 4546 8257 4547 8257 4565 8258 4547 8258 4566 8258 4566 8259 4547 8259 4106 8259 4566 8260 4106 8260 4105 8260 3580 8261 4116 8261 4548 8261 3580 8262 4548 8262 4567 8262 4567 8263 4548 8263 4549 8263 4567 8264 4549 8264 4568 8264 4568 8265 4549 8265 4550 8265 4568 8266 4550 8266 4569 8266 4569 8267 4550 8267 4551 8267 4569 8268 4551 8268 4570 8268 4570 8269 4551 8269 4552 8269 4570 8270 4552 8270 4571 8270 4571 8271 4552 8271 4553 8271 4571 8272 4553 8272 4572 8272 4572 8273 4553 8273 4554 8273 4572 8274 4554 8274 4573 8274 4573 8275 4554 8275 4555 8275 4573 8276 4555 8276 4574 8276 4574 8277 4555 8277 4556 8277 4574 8278 4556 8278 4575 8278 4575 8279 4556 8279 4557 8279 4575 8280 4557 8280 4576 8280 4576 8281 4557 8281 4558 8281 4576 8282 4558 8282 4577 8282 4577 8283 4558 8283 4559 8283 4577 8284 4559 8284 4578 8284 4578 8285 4559 8285 4560 8285 4578 8286 4560 8286 4579 8286 4579 8287 4560 8287 4561 8287 4579 8288 4561 8288 4580 8288 4580 8289 4561 8289 4562 8289 4580 8290 4562 8290 4581 8290 4581 8291 4562 8291 4563 8291 4581 8292 4563 8292 4582 8292 4582 8293 4563 8293 4564 8293 4582 8294 4564 8294 4583 8294 4583 8295 4564 8295 4565 8295 4583 8296 4565 8296 4584 8296 4584 8297 4565 8297 4566 8297 4584 8298 4566 8298 4585 8298 4585 8299 4566 8299 4105 8299 4585 8300 4105 8300 3587 8300 3614 8301 3582 8301 4586 8301 3614 8302 4586 8302 4587 8302 4587 8303 4586 8303 4588 8303 4587 8304 4588 8304 4589 8304 4589 8305 4588 8305 4590 8305 4589 8306 4590 8306 4591 8306 4591 8307 4590 8307 4592 8307 4591 8308 4592 8308 4593 8308 4593 8309 4592 8309 4594 8309 4593 8310 4594 8310 4595 8310 4595 8311 4594 8311 4596 8311 4595 8312 4596 8312 4597 8312 4597 8313 4596 8313 4598 8313 4597 8314 4598 8314 4599 8314 4599 8315 4598 8315 4600 8315 4599 8316 4600 8316 4601 8316 4601 8317 4600 8317 4602 8317 4601 8318 4602 8318 4603 8318 4603 8319 4602 8319 4604 8319 4603 8320 4604 8320 4605 8320 4605 8321 4604 8321 4606 8321 4605 8322 4606 8322 4607 8322 4607 8323 4606 8323 4608 8323 4607 8324 4608 8324 4609 8324 4609 8325 4608 8325 4610 8325 4609 8326 4610 8326 4611 8326 4611 8327 4610 8327 4612 8327 4611 8328 4612 8328 4613 8328 4613 8329 4612 8329 4614 8329 4613 8330 4614 8330 4615 8330 4615 8331 4614 8331 4616 8331 4615 8332 4616 8332 4617 8332 4617 8333 4616 8333 4618 8333 4617 8334 4618 8334 4619 8334 4619 8335 4618 8335 4620 8335 4619 8336 4620 8336 4621 8336 4621 8337 4620 8337 4622 8337 4621 8338 4622 8338 4623 8338 4623 8339 4622 8339 3575 8339 4623 8340 3575 8340 3653 8340 4624 8341 3614 8341 4587 8341 4624 8342 4587 8342 4625 8342 4625 8343 4587 8343 4589 8343 4625 8344 4589 8344 4626 8344 4626 8345 4589 8345 4591 8345 4626 8346 4591 8346 4627 8346 4627 8347 4591 8347 4593 8347 4627 8348 4593 8348 4628 8348 4628 8349 4593 8349 4595 8349 4628 8350 4595 8350 4629 8350 4629 8351 4595 8351 4597 8351 4629 8352 4597 8352 4630 8352 4630 8353 4597 8353 4599 8353 4630 8354 4599 8354 4631 8354 4631 8355 4599 8355 4601 8355 4631 8356 4601 8356 4632 8356 4632 8357 4601 8357 4603 8357 4632 8358 4603 8358 4633 8358 4633 8359 4603 8359 4605 8359 4633 8360 4605 8360 4634 8360 4634 8361 4605 8361 4607 8361 4634 8362 4607 8362 4635 8362 4635 8363 4607 8363 4609 8363 4635 8364 4609 8364 4636 8364 4636 8365 4609 8365 4611 8365 4636 8366 4611 8366 4637 8366 4637 8367 4611 8367 4613 8367 4637 8368 4613 8368 4638 8368 4638 8369 4613 8369 4615 8369 4638 8370 4615 8370 4639 8370 4639 8371 4615 8371 4617 8371 4639 8372 4617 8372 4640 8372 4640 8373 4617 8373 4619 8373 4640 8374 4619 8374 4641 8374 4641 8375 4619 8375 4621 8375 4641 8376 4621 8376 4642 8376 4642 8377 4621 8377 4623 8377 4642 8378 4623 8378 4643 8378 4643 8379 4623 8379 3653 8379 4643 8380 3653 8380 3651 8380 4644 8381 4624 8381 4625 8381 4644 8382 4625 8382 4645 8382 4645 8383 4625 8383 4626 8383 4645 8384 4626 8384 4646 8384 4646 8385 4626 8385 4627 8385 4646 8386 4627 8386 4647 8386 4647 8387 4627 8387 4628 8387 4647 8388 4628 8388 4648 8388 4648 8389 4628 8389 4629 8389 4648 8390 4629 8390 4649 8390 4649 8391 4629 8391 4630 8391 4649 8392 4630 8392 4650 8392 4650 8393 4630 8393 4631 8393 4650 8394 4631 8394 4651 8394 4651 8395 4631 8395 4632 8395 4651 8396 4632 8396 4652 8396 4652 8397 4632 8397 4633 8397 4652 8398 4633 8398 4653 8398 4653 8399 4633 8399 4634 8399 4653 8400 4634 8400 4654 8400 4654 8401 4634 8401 4635 8401 4654 8402 4635 8402 4655 8402 4655 8403 4635 8403 4636 8403 4655 8404 4636 8404 4656 8404 4656 8405 4636 8405 4637 8405 4656 8406 4637 8406 4657 8406 4657 8407 4637 8407 4638 8407 4657 8408 4638 8408 4658 8408 4658 8409 4638 8409 4639 8409 4658 8410 4639 8410 4659 8410 4659 8411 4639 8411 4640 8411 4659 8412 4640 8412 4660 8412 4660 8413 4640 8413 4641 8413 4660 8414 4641 8414 4661 8414 4661 8415 4641 8415 4642 8415 4661 8416 4642 8416 4662 8416 4662 8417 4642 8417 4643 8417 4662 8418 4643 8418 4663 8418 4663 8419 4643 8419 3651 8419 4663 8420 3651 8420 3649 8420 4664 8421 4644 8421 4645 8421 4664 8422 4645 8422 4665 8422 4665 8423 4645 8423 4646 8423 4665 8424 4646 8424 4666 8424 4666 8425 4646 8425 4647 8425 4666 8426 4647 8426 4667 8426 4667 8427 4647 8427 4648 8427 4667 8428 4648 8428 4668 8428 4668 8429 4648 8429 4649 8429 4668 8430 4649 8430 4669 8430 4669 8431 4649 8431 4650 8431 4669 8432 4650 8432 4670 8432 4670 8433 4650 8433 4651 8433 4670 8434 4651 8434 4671 8434 4671 8435 4651 8435 4652 8435 4671 8436 4652 8436 4672 8436 4672 8437 4652 8437 4653 8437 4672 8438 4653 8438 4673 8438 4673 8439 4653 8439 4654 8439 4673 8440 4654 8440 4674 8440 4674 8441 4654 8441 4655 8441 4674 8442 4655 8442 4675 8442 4675 8443 4655 8443 4656 8443 4675 8444 4656 8444 4676 8444 4676 8445 4656 8445 4657 8445 4676 8446 4657 8446 4677 8446 4677 8447 4657 8447 4658 8447 4677 8448 4658 8448 4678 8448 4678 8449 4658 8449 4659 8449 4678 8450 4659 8450 4679 8450 4679 8451 4659 8451 4660 8451 4679 8452 4660 8452 4680 8452 4680 8453 4660 8453 4661 8453 4680 8454 4661 8454 4681 8454 4681 8455 4661 8455 4662 8455 4681 8456 4662 8456 4682 8456 4682 8457 4662 8457 4663 8457 4682 8458 4663 8458 4683 8458 4683 8459 4663 8459 3649 8459 4683 8460 3649 8460 3647 8460 3611 8461 4664 8461 4665 8461 3611 8462 4665 8462 4684 8462 4684 8463 4665 8463 4666 8463 4684 8464 4666 8464 4685 8464 4685 8465 4666 8465 4667 8465 4685 8466 4667 8466 4686 8466 4686 8467 4667 8467 4668 8467 4686 8468 4668 8468 4687 8468 4687 8469 4668 8469 4669 8469 4687 8470 4669 8470 4688 8470 4688 8471 4669 8471 4670 8471 4688 8472 4670 8472 4689 8472 4689 8473 4670 8473 4671 8473 4689 8474 4671 8474 4690 8474 4690 8475 4671 8475 4672 8475 4690 8476 4672 8476 4691 8476 4691 8477 4672 8477 4673 8477 4691 8478 4673 8478 4692 8478 4692 8479 4673 8479 4674 8479 4692 8480 4674 8480 4693 8480 4693 8481 4674 8481 4675 8481 4693 8482 4675 8482 4694 8482 4694 8483 4675 8483 4676 8483 4694 8484 4676 8484 4695 8484 4695 8485 4676 8485 4677 8485 4695 8486 4677 8486 4696 8486 4696 8487 4677 8487 4678 8487 4696 8488 4678 8488 4697 8488 4697 8489 4678 8489 4679 8489 4697 8490 4679 8490 4698 8490 4698 8491 4679 8491 4680 8491 4698 8492 4680 8492 4699 8492 4699 8493 4680 8493 4681 8493 4699 8494 4681 8494 4700 8494 4700 8495 4681 8495 4682 8495 4700 8496 4682 8496 4701 8496 4701 8497 4682 8497 4683 8497 4701 8498 4683 8498 4702 8498 4702 8499 4683 8499 3647 8499 4702 8500 3647 8500 3645 8500 3612 8501 3611 8501 4684 8501 3612 8502 4684 8502 4703 8502 4703 8503 4684 8503 4685 8503 4703 8504 4685 8504 4704 8504 4704 8505 4685 8505 4686 8505 4704 8506 4686 8506 4705 8506 4705 8507 4686 8507 4687 8507 4705 8508 4687 8508 4706 8508 4706 8509 4687 8509 4688 8509 4706 8510 4688 8510 4707 8510 4707 8511 4688 8511 4689 8511 4707 8512 4689 8512 4708 8512 4708 8513 4689 8513 4690 8513 4708 8514 4690 8514 4709 8514 4709 8515 4690 8515 4691 8515 4709 8516 4691 8516 4710 8516 4710 8517 4691 8517 4692 8517 4710 8518 4692 8518 4711 8518 4711 8519 4692 8519 4693 8519 4711 8520 4693 8520 4712 8520 4712 8521 4693 8521 4694 8521 4712 8522 4694 8522 4713 8522 4713 8523 4694 8523 4695 8523 4713 8524 4695 8524 4714 8524 4714 8525 4695 8525 4696 8525 4714 8526 4696 8526 4715 8526 4715 8527 4696 8527 4697 8527 4715 8528 4697 8528 4716 8528 4716 8529 4697 8529 4698 8529 4716 8530 4698 8530 4717 8530 4717 8531 4698 8531 4699 8531 4717 8532 4699 8532 4718 8532 4718 8533 4699 8533 4700 8533 4718 8534 4700 8534 4719 8534 4719 8535 4700 8535 4701 8535 4719 8536 4701 8536 4720 8536 4720 8537 4701 8537 4702 8537 4720 8538 4702 8538 4721 8538 4721 8539 4702 8539 3645 8539 4721 8540 3645 8540 3642 8540 4722 8541 3612 8541 4703 8541 4722 8542 4703 8542 4723 8542 4723 8543 4703 8543 4704 8543 4723 8544 4704 8544 4724 8544 4724 8545 4704 8545 4705 8545 4724 8546 4705 8546 4725 8546 4725 8547 4705 8547 4706 8547 4725 8548 4706 8548 4726 8548 4726 8549 4706 8549 4707 8549 4726 8550 4707 8550 4727 8550 4727 8551 4707 8551 4708 8551 4727 8552 4708 8552 4728 8552 4728 8553 4708 8553 4709 8553 4728 8554 4709 8554 4729 8554 4729 8555 4709 8555 4710 8555 4729 8556 4710 8556 4730 8556 4730 8557 4710 8557 4711 8557 4730 8558 4711 8558 4731 8558 4731 8559 4711 8559 4712 8559 4731 8560 4712 8560 4732 8560 4732 8561 4712 8561 4713 8561 4732 8562 4713 8562 4733 8562 4733 8563 4713 8563 4714 8563 4733 8564 4714 8564 4734 8564 4734 8565 4714 8565 4715 8565 4734 8566 4715 8566 4735 8566 4735 8567 4715 8567 4716 8567 4735 8568 4716 8568 4736 8568 4736 8569 4716 8569 4717 8569 4736 8570 4717 8570 4737 8570 4737 8571 4717 8571 4718 8571 4737 8572 4718 8572 4738 8572 4738 8573 4718 8573 4719 8573 4738 8574 4719 8574 4739 8574 4739 8575 4719 8575 4720 8575 4739 8576 4720 8576 4740 8576 4740 8577 4720 8577 4721 8577 4740 8578 4721 8578 4741 8578 4741 8579 4721 8579 3642 8579 4741 8580 3642 8580 3641 8580 4742 8581 4743 8581 4744 8581 4742 8582 4744 8582 4745 8582 4745 8583 4744 8583 4746 8583 4745 8584 4746 8584 4747 8584 4747 8585 4746 8585 4748 8585 4747 8586 4748 8586 4749 8586 4749 8587 4748 8587 4750 8587 4749 8588 4750 8588 4751 8588 4751 8589 4750 8589 4752 8589 4751 8590 4752 8590 4753 8590 4753 8591 4752 8591 4754 8591 4753 8592 4754 8592 4755 8592 4755 8593 4754 8593 4756 8593 4755 8594 4756 8594 4757 8594 4757 8595 4756 8595 4758 8595 4757 8596 4758 8596 4759 8596 4759 8597 4758 8597 4760 8597 4759 8598 4760 8598 4761 8598 4761 8599 4760 8599 4762 8599 4761 8600 4762 8600 4763 8600 4763 8601 4762 8601 4764 8601 4763 8602 4764 8602 4765 8602 4765 8603 4764 8603 4766 8603 4765 8604 4766 8604 4767 8604 4767 8605 4766 8605 4768 8605 4767 8606 4768 8606 4769 8606 4769 8607 4768 8607 4770 8607 4769 8608 4770 8608 4771 8608 4771 8609 4770 8609 4772 8609 4771 8610 4772 8610 4773 8610 4773 8611 4772 8611 4774 8611 4773 8612 4774 8612 4775 8612 4775 8613 4774 8613 4776 8613 4775 8614 4776 8614 4777 8614 4777 8615 4776 8615 3639 8615 4777 8616 3639 8616 3637 8616 4778 8617 4761 8617 4763 8617 4778 8618 4763 8618 4779 8618 4779 8619 4763 8619 4765 8619 4779 8620 4765 8620 4780 8620 4780 8621 4765 8621 4767 8621 4780 8622 4767 8622 4781 8622 4781 8623 4767 8623 4769 8623 4781 8624 4769 8624 4782 8624 4782 8625 4769 8625 4771 8625 4782 8626 4771 8626 4783 8626 4783 8627 4771 8627 4773 8627 4783 8628 4773 8628 4784 8628 4784 8629 4773 8629 4775 8629 4784 8630 4775 8630 4785 8630 4785 8631 4775 8631 4777 8631 4785 8632 4777 8632 4786 8632 4786 8633 4777 8633 3637 8633 4786 8634 3637 8634 3634 8634 4787 8635 4779 8635 4780 8635 4787 8636 4780 8636 4788 8636 4788 8637 4780 8637 4781 8637 4788 8638 4781 8638 4789 8638 4789 8639 4781 8639 4782 8639 4789 8640 4782 8640 4790 8640 4790 8641 4782 8641 4783 8641 4790 8642 4783 8642 4791 8642 4791 8643 4783 8643 4784 8643 4791 8644 4784 8644 4792 8644 4792 8645 4784 8645 4785 8645 4792 8646 4785 8646 4793 8646 4793 8647 4785 8647 4786 8647 4793 8648 4786 8648 4794 8648 4794 8649 4786 8649 3634 8649 4794 8650 3634 8650 3633 8650 3608 8651 3607 8651 4795 8651 3608 8652 4795 8652 4796 8652 4796 8653 4795 8653 4797 8653 4796 8654 4797 8654 4798 8654 4798 8655 4797 8655 4799 8655 4798 8656 4799 8656 4800 8656 4800 8657 4799 8657 4801 8657 4800 8658 4801 8658 4802 8658 4802 8659 4801 8659 4803 8659 4802 8660 4803 8660 4804 8660 4804 8661 4803 8661 4805 8661 4804 8662 4805 8662 4806 8662 4806 8663 4805 8663 4807 8663 4806 8664 4807 8664 4808 8664 4808 8665 4807 8665 4809 8665 4808 8666 4809 8666 4810 8666 4810 8667 4809 8667 4811 8667 4810 8668 4811 8668 4812 8668 4812 8669 4811 8669 4813 8669 4812 8670 4813 8670 4814 8670 4814 8671 4813 8671 4815 8671 4814 8672 4815 8672 4816 8672 4816 8673 4815 8673 4817 8673 4816 8674 4817 8674 4818 8674 3602 8675 3604 8675 4819 8675 3602 8676 4819 8676 4820 8676 4820 8677 4819 8677 4821 8677 4820 8678 4821 8678 4822 8678 4822 8679 4821 8679 4823 8679 4822 8680 4823 8680 4824 8680 4824 8681 4823 8681 4825 8681 4824 8682 4825 8682 4826 8682 4826 8683 4825 8683 4827 8683 4826 8684 4827 8684 4828 8684 4828 8685 4827 8685 4829 8685 4828 8686 4829 8686 4830 8686 4830 8687 4829 8687 4831 8687 4830 8688 4831 8688 4832 8688 4832 8689 4831 8689 4833 8689 4832 8690 4833 8690 4834 8690 4834 8691 4833 8691 4835 8691 4834 8692 4835 8692 4836 8692 4836 8693 4835 8693 4837 8693 4836 8694 4837 8694 4838 8694 4838 8695 4837 8695 4839 8695 4838 8696 4839 8696 4840 8696 4840 8697 4839 8697 4841 8697 4840 8698 4841 8698 4842 8698 4842 8699 4841 8699 4843 8699 4842 8700 4843 8700 4844 8700 4844 8701 4843 8701 4845 8701 4844 8702 4845 8702 4846 8702 4846 8703 4845 8703 4847 8703 4846 8704 4847 8704 4848 8704 4848 8705 4847 8705 4849 8705 4848 8706 4849 8706 4850 8706 4850 8707 4849 8707 4851 8707 4850 8708 4851 8708 4852 8708 4852 8709 4851 8709 4853 8709 4852 8710 4853 8710 4854 8710 4854 8711 4853 8711 4855 8711 4854 8712 4855 8712 4856 8712 4856 8713 4855 8713 3631 8713 4856 8714 3631 8714 3629 8714 3600 8715 3602 8715 4820 8715 3600 8716 4820 8716 4857 8716 4857 8717 4820 8717 4822 8717 4857 8718 4822 8718 4858 8718 4858 8719 4822 8719 4824 8719 4858 8720 4824 8720 4859 8720 4859 8721 4824 8721 4826 8721 4859 8722 4826 8722 4860 8722 4860 8723 4826 8723 4828 8723 4860 8724 4828 8724 4861 8724 4861 8725 4828 8725 4830 8725 4861 8726 4830 8726 4862 8726 4862 8727 4830 8727 4832 8727 4862 8728 4832 8728 4863 8728 4863 8729 4832 8729 4834 8729 4863 8730 4834 8730 4864 8730 4864 8731 4834 8731 4836 8731 4864 8732 4836 8732 4865 8732 4865 8733 4836 8733 4838 8733 4865 8734 4838 8734 4866 8734 4866 8735 4838 8735 4840 8735 4866 8736 4840 8736 4867 8736 4867 8737 4840 8737 4842 8737 4867 8738 4842 8738 4868 8738 4868 8739 4842 8739 4844 8739 4868 8740 4844 8740 4869 8740 4869 8741 4844 8741 4846 8741 4869 8742 4846 8742 4870 8742 4870 8743 4846 8743 4848 8743 4870 8744 4848 8744 4871 8744 4871 8745 4848 8745 4850 8745 4871 8746 4850 8746 4872 8746 4872 8747 4850 8747 4852 8747 4872 8748 4852 8748 4873 8748 4873 8749 4852 8749 4854 8749 4873 8750 4854 8750 4874 8750 4874 8751 4854 8751 4856 8751 4874 8752 4856 8752 4875 8752 4875 8753 4856 8753 3629 8753 4875 8754 3629 8754 3627 8754 3598 8755 3600 8755 4857 8755 3598 8756 4857 8756 4876 8756 4876 8757 4857 8757 4858 8757 4876 8758 4858 8758 4877 8758 4877 8759 4858 8759 4859 8759 4877 8760 4859 8760 4878 8760 4878 8761 4859 8761 4860 8761 4878 8762 4860 8762 4879 8762 4879 8763 4860 8763 4861 8763 4879 8764 4861 8764 4880 8764 4880 8765 4861 8765 4862 8765 4880 8766 4862 8766 4881 8766 4881 8767 4862 8767 4863 8767 4881 8768 4863 8768 4882 8768 4882 8769 4863 8769 4864 8769 4882 8770 4864 8770 4883 8770 4883 8771 4864 8771 4865 8771 4883 8772 4865 8772 4884 8772 4884 8773 4865 8773 4866 8773 4884 8774 4866 8774 4885 8774 4885 8775 4866 8775 4867 8775 4885 8776 4867 8776 4886 8776 4886 8777 4867 8777 4868 8777 4886 8778 4868 8778 4887 8778 4887 8779 4868 8779 4869 8779 4887 8780 4869 8780 4888 8780 4888 8781 4869 8781 4870 8781 4888 8782 4870 8782 4889 8782 4889 8783 4870 8783 4871 8783 4889 8784 4871 8784 4890 8784 4890 8785 4871 8785 4872 8785 4890 8786 4872 8786 4891 8786 4891 8787 4872 8787 4873 8787 4891 8788 4873 8788 4892 8788 4892 8789 4873 8789 4874 8789 4892 8790 4874 8790 4893 8790 4893 8791 4874 8791 4875 8791 4893 8792 4875 8792 4894 8792 4894 8793 4875 8793 3627 8793 4894 8794 3627 8794 3625 8794 3595 8795 3598 8795 4876 8795 3595 8796 4876 8796 4895 8796 4895 8797 4876 8797 4877 8797 4895 8798 4877 8798 4896 8798 4896 8799 4877 8799 4878 8799 4896 8800 4878 8800 4897 8800 4897 8801 4878 8801 4879 8801 4897 8802 4879 8802 4898 8802 4898 8803 4879 8803 4880 8803 4898 8804 4880 8804 4899 8804 4899 8805 4880 8805 4881 8805 4899 8806 4881 8806 4900 8806 4900 8807 4881 8807 4882 8807 4900 8808 4882 8808 4901 8808 4901 8809 4882 8809 4883 8809 4901 8810 4883 8810 4902 8810 4902 8811 4883 8811 4884 8811 4902 8812 4884 8812 4903 8812 4903 8813 4884 8813 4885 8813 4903 8814 4885 8814 4904 8814 4904 8815 4885 8815 4886 8815 4904 8816 4886 8816 4905 8816 4905 8817 4886 8817 4887 8817 4905 8818 4887 8818 4906 8818 4906 8819 4887 8819 4888 8819 4906 8820 4888 8820 4907 8820 4907 8821 4888 8821 4889 8821 4907 8822 4889 8822 4908 8822 4908 8823 4889 8823 4890 8823 4908 8824 4890 8824 4909 8824 4909 8825 4890 8825 4891 8825 4909 8826 4891 8826 4910 8826 4910 8827 4891 8827 4892 8827 4910 8828 4892 8828 4911 8828 4911 8829 4892 8829 4893 8829 4911 8830 4893 8830 4912 8830 4912 8831 4893 8831 4894 8831 4912 8832 4894 8832 4913 8832 4913 8833 4894 8833 3625 8833 4913 8834 3625 8834 3623 8834 3596 8835 3595 8835 4895 8835 3596 8836 4895 8836 4914 8836 4914 8837 4895 8837 4896 8837 4914 8838 4896 8838 4915 8838 4915 8839 4896 8839 4897 8839 4915 8840 4897 8840 4916 8840 4916 8841 4897 8841 4898 8841 4916 8842 4898 8842 4917 8842 4917 8843 4898 8843 4899 8843 4917 8844 4899 8844 4918 8844 4918 8845 4899 8845 4900 8845 4918 8846 4900 8846 4919 8846 4919 8847 4900 8847 4901 8847 4919 8848 4901 8848 4920 8848 4920 8849 4901 8849 4902 8849 4920 8850 4902 8850 4921 8850 4921 8851 4902 8851 4903 8851 4921 8852 4903 8852 4922 8852 4922 8853 4903 8853 4904 8853 4922 8854 4904 8854 4923 8854 4923 8855 4904 8855 4905 8855 4923 8856 4905 8856 4924 8856 4924 8857 4905 8857 4906 8857 4924 8858 4906 8858 4925 8858 4925 8859 4906 8859 4907 8859 4925 8860 4907 8860 4926 8860 4926 8861 4907 8861 4908 8861 4926 8862 4908 8862 4927 8862 4927 8863 4908 8863 4909 8863 4927 8864 4909 8864 4928 8864 4928 8865 4909 8865 4910 8865 4928 8866 4910 8866 4929 8866 4929 8867 4910 8867 4911 8867 4929 8868 4911 8868 4930 8868 4930 8869 4911 8869 4912 8869 4930 8870 4912 8870 4931 8870 4931 8871 4912 8871 4913 8871 4931 8872 4913 8872 4932 8872 4932 8873 4913 8873 3623 8873 4932 8874 3623 8874 3621 8874 4933 8875 3596 8875 4914 8875 4933 8876 4914 8876 4934 8876 4934 8877 4914 8877 4915 8877 4934 8878 4915 8878 4935 8878 4935 8879 4915 8879 4916 8879 4935 8880 4916 8880 4936 8880 4936 8881 4916 8881 4917 8881 4936 8882 4917 8882 4937 8882 4937 8883 4917 8883 4918 8883 4937 8884 4918 8884 4938 8884 4938 8885 4918 8885 4919 8885 4938 8886 4919 8886 4939 8886 4939 8887 4919 8887 4920 8887 4939 8888 4920 8888 4940 8888 4940 8889 4920 8889 4921 8889 4940 8890 4921 8890 4941 8890 4941 8891 4921 8891 4922 8891 4941 8892 4922 8892 4942 8892 4942 8893 4922 8893 4923 8893 4942 8894 4923 8894 4943 8894 4943 8895 4923 8895 4924 8895 4943 8896 4924 8896 4944 8896 4944 8897 4924 8897 4925 8897 4944 8898 4925 8898 4945 8898 4945 8899 4925 8899 4926 8899 4945 8900 4926 8900 4946 8900 4946 8901 4926 8901 4927 8901 4946 8902 4927 8902 4947 8902 4947 8903 4927 8903 4928 8903 4947 8904 4928 8904 4948 8904 4948 8905 4928 8905 4929 8905 4948 8906 4929 8906 4949 8906 4949 8907 4929 8907 4930 8907 4949 8908 4930 8908 4950 8908 4950 8909 4930 8909 4931 8909 4950 8910 4931 8910 4951 8910 4951 8911 4931 8911 4932 8911 4951 8912 4932 8912 4952 8912 4952 8913 4932 8913 3621 8913 4952 8914 3621 8914 3619 8914 3592 8915 4933 8915 4934 8915 3592 8916 4934 8916 4953 8916 4953 8917 4934 8917 4935 8917 4953 8918 4935 8918 4954 8918 4954 8919 4935 8919 4936 8919 4954 8920 4936 8920 4955 8920 4955 8921 4936 8921 4937 8921 4955 8922 4937 8922 4956 8922 4956 8923 4937 8923 4938 8923 4956 8924 4938 8924 4957 8924 4957 8925 4938 8925 4939 8925 4957 8926 4939 8926 4958 8926 4958 8927 4939 8927 4940 8927 4958 8928 4940 8928 4959 8928 4959 8929 4940 8929 4941 8929 4959 8930 4941 8930 4960 8930 4960 8931 4941 8931 4942 8931 4960 8932 4942 8932 4961 8932 4961 8933 4942 8933 4943 8933 4961 8934 4943 8934 4962 8934 4962 8935 4943 8935 4944 8935 4962 8936 4944 8936 4963 8936 4963 8937 4944 8937 4945 8937 4963 8938 4945 8938 4964 8938 4964 8939 4945 8939 4946 8939 4964 8940 4946 8940 4965 8940 4965 8941 4946 8941 4947 8941 4965 8942 4947 8942 4966 8942 4966 8943 4947 8943 4948 8943 4966 8944 4948 8944 4967 8944 4967 8945 4948 8945 4949 8945 4967 8946 4949 8946 4968 8946 4968 8947 4949 8947 4950 8947 4968 8948 4950 8948 4969 8948 4969 8949 4950 8949 4951 8949 4969 8950 4951 8950 4970 8950 4970 8951 4951 8951 4952 8951 4970 8952 4952 8952 4971 8952 4971 8953 4952 8953 3619 8953 4971 8954 3619 8954 3617 8954 3590 8955 3592 8955 4953 8955 3590 8956 4953 8956 4972 8956 4972 8957 4953 8957 4954 8957 4972 8958 4954 8958 4973 8958 4973 8959 4954 8959 4955 8959 4973 8960 4955 8960 4974 8960 4974 8961 4955 8961 4956 8961 4974 8962 4956 8962 4975 8962 4975 8963 4956 8963 4957 8963 4975 8964 4957 8964 4976 8964 4976 8965 4957 8965 4958 8965 4976 8966 4958 8966 4977 8966 4977 8967 4958 8967 4959 8967 4977 8968 4959 8968 4978 8968 4978 8969 4959 8969 4960 8969 4978 8970 4960 8970 4979 8970 4979 8971 4960 8971 4961 8971 4979 8972 4961 8972 4980 8972 4980 8973 4961 8973 4962 8973 4980 8974 4962 8974 4981 8974 4981 8975 4962 8975 4963 8975 4981 8976 4963 8976 4982 8976 4982 8977 4963 8977 4964 8977 4982 8978 4964 8978 4983 8978 4983 8979 4964 8979 4965 8979 4983 8980 4965 8980 4984 8980 4984 8981 4965 8981 4966 8981 4984 8982 4966 8982 4985 8982 4985 8983 4966 8983 4967 8983 4985 8984 4967 8984 4986 8984 4986 8985 4967 8985 4968 8985 4986 8986 4968 8986 4987 8986 4987 8987 4968 8987 4969 8987 4987 8988 4969 8988 4988 8988 4988 8989 4969 8989 4970 8989 4988 8990 4970 8990 4989 8990 4989 8991 4970 8991 4971 8991 4989 8992 4971 8992 4990 8992 4990 8993 4971 8993 3617 8993 4990 8994 3617 8994 3616 8994 3585 8995 3590 8995 4972 8995 3585 8996 4972 8996 3586 8996 3586 8997 4972 8997 4973 8997 3586 8998 4973 8998 4991 8998 4991 8999 4973 8999 4974 8999 4991 9000 4974 9000 4992 9000 4992 9001 4974 9001 4975 9001 4992 9002 4975 9002 4993 9002 4993 9003 4975 9003 4976 9003 4993 9004 4976 9004 4994 9004 4994 9005 4976 9005 4977 9005 4994 9006 4977 9006 4995 9006 4995 9007 4977 9007 4978 9007 4995 9008 4978 9008 4996 9008 4996 9009 4978 9009 4979 9009 4996 9010 4979 9010 4997 9010 4997 9011 4979 9011 4980 9011 4997 9012 4980 9012 4998 9012 4998 9013 4980 9013 4981 9013 4998 9014 4981 9014 4999 9014 4999 9015 4981 9015 4982 9015 4999 9016 4982 9016 5000 9016 5000 9017 4982 9017 4983 9017 5000 9018 4983 9018 5001 9018 5001 9019 4983 9019 4984 9019 5001 9020 4984 9020 5002 9020 5002 9021 4984 9021 4985 9021 5002 9022 4985 9022 5003 9022 5003 9023 4985 9023 4986 9023 5003 9024 4986 9024 5004 9024 5004 9025 4986 9025 4987 9025 5004 9026 4987 9026 5005 9026 5005 9027 4987 9027 4988 9027 5005 9028 4988 9028 5006 9028 5006 9029 4988 9029 4989 9029 5006 9030 4989 9030 5007 9030 5007 9031 4989 9031 4990 9031 5007 9032 4990 9032 5008 9032 5008 9033 4990 9033 3616 9033 5008 9034 3616 9034 3615 9034 3580 9035 4567 9035 5009 9035 3580 9036 5009 9036 3581 9036 4567 9037 4568 9037 5010 9037 4567 9038 5010 9038 5009 9038 4568 9039 4569 9039 5011 9039 4568 9040 5011 9040 5010 9040 4569 9041 4570 9041 5012 9041 4569 9042 5012 9042 5011 9042 4570 9043 4571 9043 5013 9043 4570 9044 5013 9044 5012 9044 4571 9045 4572 9045 5014 9045 4571 9046 5014 9046 5013 9046 4572 9047 4573 9047 5015 9047 4572 9048 5015 9048 5014 9048 4573 9049 4574 9049 5016 9049 4573 9050 5016 9050 5015 9050 4574 9051 4575 9051 5017 9051 4574 9052 5017 9052 5016 9052 4575 9053 4576 9053 5018 9053 4575 9054 5018 9054 5017 9054 4576 9055 4577 9055 5019 9055 4576 9056 5019 9056 5018 9056 4577 9057 4578 9057 5020 9057 4577 9058 5020 9058 5019 9058 4578 9059 4579 9059 5021 9059 4578 9060 5021 9060 5020 9060 4579 9061 4580 9061 5022 9061 4579 9062 5022 9062 5021 9062 4580 9063 4581 9063 5023 9063 4580 9064 5023 9064 5022 9064 4581 9065 4582 9065 5024 9065 4581 9066 5024 9066 5023 9066 4582 9067 4583 9067 5025 9067 4582 9068 5025 9068 5024 9068 4583 9069 4584 9069 5026 9069 4583 9070 5026 9070 5025 9070 4584 9071 4585 9071 5027 9071 4584 9072 5027 9072 5026 9072 4585 9073 3587 9073 3576 9073 4585 9074 3576 9074 5027 9074 3572 9075 4375 9075 3615 9075 3572 9076 3615 9076 3573 9076 4375 9077 4376 9077 5008 9077 4375 9078 5008 9078 3615 9078 4376 9079 4377 9079 5007 9079 4376 9080 5007 9080 5008 9080 4377 9081 4378 9081 5006 9081 4377 9082 5006 9082 5007 9082 4378 9083 4379 9083 5005 9083 4378 9084 5005 9084 5006 9084 4379 9085 4380 9085 5004 9085 4379 9086 5004 9086 5005 9086 4380 9087 4381 9087 5003 9087 4380 9088 5003 9088 5004 9088 4381 9089 4382 9089 5002 9089 4381 9090 5002 9090 5003 9090 4382 9091 4383 9091 5001 9091 4382 9092 5001 9092 5002 9092 4383 9093 4384 9093 5000 9093 4383 9094 5000 9094 5001 9094 4384 9095 4385 9095 4999 9095 4384 9096 4999 9096 5000 9096 4385 9097 4386 9097 4998 9097 4385 9098 4998 9098 4999 9098 4386 9099 4387 9099 4997 9099 4386 9100 4997 9100 4998 9100 4387 9101 4388 9101 4996 9101 4387 9102 4996 9102 4997 9102 4388 9103 4389 9103 4995 9103 4388 9104 4995 9104 4996 9104 4389 9105 4390 9105 4994 9105 4389 9106 4994 9106 4995 9106 4390 9107 4391 9107 4993 9107 4390 9108 4993 9108 4994 9108 4391 9109 4392 9109 4992 9109 4391 9110 4992 9110 4993 9110 4392 9111 4393 9111 4991 9111 4392 9112 4991 9112 4992 9112 4393 9113 3583 9113 3586 9113 4393 9114 3586 9114 4991 9114 3582 9115 3581 9115 5009 9115 3582 9116 5009 9116 4586 9116 4586 9117 5009 9117 5010 9117 4586 9118 5010 9118 4588 9118 4588 9119 5010 9119 5011 9119 4588 9120 5011 9120 4590 9120 4590 9121 5011 9121 5012 9121 4590 9122 5012 9122 4592 9122 4592 9123 5012 9123 5013 9123 4592 9124 5013 9124 4594 9124 4594 9125 5013 9125 5014 9125 4594 9126 5014 9126 4596 9126 4596 9127 5014 9127 5015 9127 4596 9128 5015 9128 4598 9128 4598 9129 5015 9129 5016 9129 4598 9130 5016 9130 4600 9130 4600 9131 5016 9131 5017 9131 4600 9132 5017 9132 4602 9132 4602 9133 5017 9133 5018 9133 4602 9134 5018 9134 4604 9134 4604 9135 5018 9135 5019 9135 4604 9136 5019 9136 4606 9136 4606 9137 5019 9137 5020 9137 4606 9138 5020 9138 4608 9138 4608 9139 5020 9139 5021 9139 4608 9140 5021 9140 4610 9140 4610 9141 5021 9141 5022 9141 4610 9142 5022 9142 4612 9142 4612 9143 5022 9143 5023 9143 4612 9144 5023 9144 4614 9144 4614 9145 5023 9145 5024 9145 4614 9146 5024 9146 4616 9146 4616 9147 5024 9147 5025 9147 4616 9148 5025 9148 4618 9148 4618 9149 5025 9149 5026 9149 4618 9150 5026 9150 4620 9150 4620 9151 5026 9151 5027 9151 4620 9152 5027 9152 4622 9152 4622 9153 5027 9153 3576 9153 4622 9154 3576 9154 3575 9154 4145 9155 4182 9155 4179 9155 4179 9156 4177 9156 4175 9156 4179 9157 4175 9157 4173 9157 4144 9158 4145 9158 4179 9158 4161 9159 4153 9159 4144 9159 4165 9160 4163 9160 4161 9160 4167 9161 4165 9161 4161 9161 4144 9162 4179 9162 4173 9162 4144 9163 4173 9163 4171 9163 4167 9164 4161 9164 4144 9164 4144 9165 4171 9165 4169 9165 4169 9166 4167 9166 4144 9166 3789 9167 4145 9167 4135 9167 4135 9168 4134 9168 4146 9168 4146 9169 4104 9169 3787 9169 3787 9170 3789 9170 4135 9170 4135 9171 4146 9171 3787 9171 5028 9172 5029 9172 4050 9172 4050 9173 4049 9173 5030 9173 5030 9174 5031 9174 5028 9174 4050 9175 5030 9175 5028 9175 4047 9176 4045 9176 4060 9176 4047 9177 4060 9177 4049 9177 4059 9178 4058 9178 4068 9178 4059 9179 4068 9179 4060 9179 4075 9180 4074 9180 4081 9180 4068 9181 4067 9181 4075 9181 4080 9182 4086 9182 4091 9182 4080 9183 4091 9183 4081 9183 4855 9184 5032 9184 5033 9184 4855 9185 5033 9185 3631 9185 5032 9186 5034 9186 5035 9186 5032 9187 5035 9187 5033 9187 5034 9188 5036 9188 5037 9188 5034 9189 5037 9189 5035 9189 5036 9190 5038 9190 5039 9190 5036 9191 5039 9191 5037 9191 5038 9192 5040 9192 5041 9192 5038 9193 5041 9193 5039 9193 4853 9194 5042 9194 5032 9194 4853 9195 5032 9195 4855 9195 5042 9196 5043 9196 5034 9196 5042 9197 5034 9197 5032 9197 5043 9198 5044 9198 5036 9198 5043 9199 5036 9199 5034 9199 5044 9200 5045 9200 5038 9200 5044 9201 5038 9201 5036 9201 5045 9202 5046 9202 5040 9202 5045 9203 5040 9203 5038 9203 4851 9204 5047 9204 5042 9204 4851 9205 5042 9205 4853 9205 5047 9206 5048 9206 5043 9206 5047 9207 5043 9207 5042 9207 5048 9208 5049 9208 5044 9208 5048 9209 5044 9209 5043 9209 5049 9210 5050 9210 5045 9210 5049 9211 5045 9211 5044 9211 5050 9212 5051 9212 5046 9212 5050 9213 5046 9213 5045 9213 4849 9214 5052 9214 5047 9214 4849 9215 5047 9215 4851 9215 5052 9216 5053 9216 5048 9216 5052 9217 5048 9217 5047 9217 5053 9218 5054 9218 5049 9218 5053 9219 5049 9219 5048 9219 5054 9220 5055 9220 5050 9220 5054 9221 5050 9221 5049 9221 5055 9222 5056 9222 5051 9222 5055 9223 5051 9223 5050 9223 5056 9224 5057 9224 5058 9224 5056 9225 5058 9225 5051 9225 4847 9226 5059 9226 5052 9226 4847 9227 5052 9227 4849 9227 5059 9228 5060 9228 5053 9228 5059 9229 5053 9229 5052 9229 5060 9230 5061 9230 5054 9230 5060 9231 5054 9231 5053 9231 5061 9232 5062 9232 5055 9232 5061 9233 5055 9233 5054 9233 5062 9234 5063 9234 5056 9234 5062 9235 5056 9235 5055 9235 5063 9236 5064 9236 5057 9236 5063 9237 5057 9237 5056 9237 4845 9238 5065 9238 5059 9238 4845 9239 5059 9239 4847 9239 5065 9240 5066 9240 5060 9240 5065 9241 5060 9241 5059 9241 5066 9242 5067 9242 5061 9242 5066 9243 5061 9243 5060 9243 5067 9244 5068 9244 5062 9244 5067 9245 5062 9245 5061 9245 5068 9246 5069 9246 5063 9246 5068 9247 5063 9247 5062 9247 5069 9248 5070 9248 5064 9248 5069 9249 5064 9249 5063 9249 5070 9250 5071 9250 5072 9250 5070 9251 5072 9251 5064 9251 4843 9252 5073 9252 5065 9252 4843 9253 5065 9253 4845 9253 5073 9254 5074 9254 5066 9254 5073 9255 5066 9255 5065 9255 5074 9256 5075 9256 5067 9256 5074 9257 5067 9257 5066 9257 5075 9258 5076 9258 5068 9258 5075 9259 5068 9259 5067 9259 5076 9260 5077 9260 5069 9260 5076 9261 5069 9261 5068 9261 5077 9262 5078 9262 5070 9262 5077 9263 5070 9263 5069 9263 5078 9264 5079 9264 5071 9264 5078 9265 5071 9265 5070 9265 4841 9266 5080 9266 5073 9266 4841 9267 5073 9267 4843 9267 5080 9268 5081 9268 5074 9268 5080 9269 5074 9269 5073 9269 5081 9270 5082 9270 5075 9270 5081 9271 5075 9271 5074 9271 5082 9272 5083 9272 5076 9272 5082 9273 5076 9273 5075 9273 5083 9274 5084 9274 5077 9274 5083 9275 5077 9275 5076 9275 5084 9276 5085 9276 5078 9276 5084 9277 5078 9277 5077 9277 5085 9278 5086 9278 5079 9278 5085 9279 5079 9279 5078 9279 5086 9280 5087 9280 5088 9280 5086 9281 5088 9281 5079 9281 5087 9282 5089 9282 5090 9282 5087 9283 5090 9283 5088 9283 4839 9284 5091 9284 5080 9284 4839 9285 5080 9285 4841 9285 5091 9286 5092 9286 5081 9286 5091 9287 5081 9287 5080 9287 5092 9288 5093 9288 5082 9288 5092 9289 5082 9289 5081 9289 5093 9290 5094 9290 5083 9290 5093 9291 5083 9291 5082 9291 5094 9292 5095 9292 5084 9292 5094 9293 5084 9293 5083 9293 5095 9294 5096 9294 5085 9294 5095 9295 5085 9295 5084 9295 5096 9296 5097 9296 5086 9296 5096 9297 5086 9297 5085 9297 5097 9298 5098 9298 5087 9298 5097 9299 5087 9299 5086 9299 5098 9300 5099 9300 5089 9300 5098 9301 5089 9301 5087 9301 5099 9302 4816 9302 4818 9302 5099 9303 4818 9303 5089 9303 4837 9304 5100 9304 5091 9304 4837 9305 5091 9305 4839 9305 5100 9306 5101 9306 5092 9306 5100 9307 5092 9307 5091 9307 5101 9308 5102 9308 5093 9308 5101 9309 5093 9309 5092 9309 5102 9310 5103 9310 5094 9310 5102 9311 5094 9311 5093 9311 5103 9312 5104 9312 5095 9312 5103 9313 5095 9313 5094 9313 5104 9314 5105 9314 5096 9314 5104 9315 5096 9315 5095 9315 5105 9316 5106 9316 5097 9316 5105 9317 5097 9317 5096 9317 5106 9318 5107 9318 5098 9318 5106 9319 5098 9319 5097 9319 5107 9320 5108 9320 5099 9320 5107 9321 5099 9321 5098 9321 5108 9322 4814 9322 4816 9322 5108 9323 4816 9323 5099 9323 4835 9324 5109 9324 5100 9324 4835 9325 5100 9325 4837 9325 5109 9326 5110 9326 5101 9326 5109 9327 5101 9327 5100 9327 5110 9328 5111 9328 5102 9328 5110 9329 5102 9329 5101 9329 5111 9330 5112 9330 5103 9330 5111 9331 5103 9331 5102 9331 5112 9332 5113 9332 5104 9332 5112 9333 5104 9333 5103 9333 5113 9334 5114 9334 5105 9334 5113 9335 5105 9335 5104 9335 5114 9336 5115 9336 5106 9336 5114 9337 5106 9337 5105 9337 5115 9338 5116 9338 5107 9338 5115 9339 5107 9339 5106 9339 5116 9340 5117 9340 5108 9340 5116 9341 5108 9341 5107 9341 5117 9342 4812 9342 4814 9342 5117 9343 4814 9343 5108 9343 4833 9344 5118 9344 5109 9344 4833 9345 5109 9345 4835 9345 5118 9346 5119 9346 5110 9346 5118 9347 5110 9347 5109 9347 5119 9348 5120 9348 5111 9348 5119 9349 5111 9349 5110 9349 5120 9350 5121 9350 5112 9350 5120 9351 5112 9351 5111 9351 5121 9352 5122 9352 5113 9352 5121 9353 5113 9353 5112 9353 5122 9354 5123 9354 5114 9354 5122 9355 5114 9355 5113 9355 5123 9356 5124 9356 5115 9356 5123 9357 5115 9357 5114 9357 5124 9358 5125 9358 5116 9358 5124 9359 5116 9359 5115 9359 5125 9360 5126 9360 5117 9360 5125 9361 5117 9361 5116 9361 5126 9362 4810 9362 4812 9362 5126 9363 4812 9363 5117 9363 4831 9364 5127 9364 5118 9364 4831 9365 5118 9365 4833 9365 5127 9366 5128 9366 5119 9366 5127 9367 5119 9367 5118 9367 5128 9368 5129 9368 5120 9368 5128 9369 5120 9369 5119 9369 5129 9370 5130 9370 5121 9370 5129 9371 5121 9371 5120 9371 5130 9372 5131 9372 5122 9372 5130 9373 5122 9373 5121 9373 5131 9374 5132 9374 5123 9374 5131 9375 5123 9375 5122 9375 5132 9376 5133 9376 5124 9376 5132 9377 5124 9377 5123 9377 5133 9378 5134 9378 5125 9378 5133 9379 5125 9379 5124 9379 5134 9380 5135 9380 5126 9380 5134 9381 5126 9381 5125 9381 5135 9382 4808 9382 4810 9382 5135 9383 4810 9383 5126 9383 4829 9384 5136 9384 5127 9384 4829 9385 5127 9385 4831 9385 5136 9386 5137 9386 5128 9386 5136 9387 5128 9387 5127 9387 5137 9388 5138 9388 5129 9388 5137 9389 5129 9389 5128 9389 5138 9390 5139 9390 5130 9390 5138 9391 5130 9391 5129 9391 5139 9392 5140 9392 5131 9392 5139 9393 5131 9393 5130 9393 5140 9394 5141 9394 5132 9394 5140 9395 5132 9395 5131 9395 5141 9396 5142 9396 5133 9396 5141 9397 5133 9397 5132 9397 5142 9398 5143 9398 5134 9398 5142 9399 5134 9399 5133 9399 5143 9400 5144 9400 5135 9400 5143 9401 5135 9401 5134 9401 5144 9402 4806 9402 4808 9402 5144 9403 4808 9403 5135 9403 4827 9404 5145 9404 5136 9404 4827 9405 5136 9405 4829 9405 5145 9406 5146 9406 5137 9406 5145 9407 5137 9407 5136 9407 5146 9408 5147 9408 5138 9408 5146 9409 5138 9409 5137 9409 5147 9410 5148 9410 5139 9410 5147 9411 5139 9411 5138 9411 5148 9412 5149 9412 5140 9412 5148 9413 5140 9413 5139 9413 5149 9414 5150 9414 5141 9414 5149 9415 5141 9415 5140 9415 5150 9416 5151 9416 5142 9416 5150 9417 5142 9417 5141 9417 5151 9418 5152 9418 5143 9418 5151 9419 5143 9419 5142 9419 5152 9420 5153 9420 5144 9420 5152 9421 5144 9421 5143 9421 5153 9422 4804 9422 4806 9422 5153 9423 4806 9423 5144 9423 4825 9424 5154 9424 5145 9424 4825 9425 5145 9425 4827 9425 5154 9426 5155 9426 5146 9426 5154 9427 5146 9427 5145 9427 5155 9428 5156 9428 5147 9428 5155 9429 5147 9429 5146 9429 5156 9430 5157 9430 5148 9430 5156 9431 5148 9431 5147 9431 5157 9432 5158 9432 5149 9432 5157 9433 5149 9433 5148 9433 5158 9434 5159 9434 5150 9434 5158 9435 5150 9435 5149 9435 5159 9436 5160 9436 5151 9436 5159 9437 5151 9437 5150 9437 5160 9438 5161 9438 5152 9438 5160 9439 5152 9439 5151 9439 5161 9440 5162 9440 5153 9440 5161 9441 5153 9441 5152 9441 5162 9442 4802 9442 4804 9442 5162 9443 4804 9443 5153 9443 4823 9444 5163 9444 5154 9444 4823 9445 5154 9445 4825 9445 5163 9446 5164 9446 5155 9446 5163 9447 5155 9447 5154 9447 5164 9448 5165 9448 5156 9448 5164 9449 5156 9449 5155 9449 5165 9450 5166 9450 5157 9450 5165 9451 5157 9451 5156 9451 5166 9452 5167 9452 5158 9452 5166 9453 5158 9453 5157 9453 5167 9454 5168 9454 5159 9454 5167 9455 5159 9455 5158 9455 5168 9456 5169 9456 5160 9456 5168 9457 5160 9457 5159 9457 5169 9458 5170 9458 5161 9458 5169 9459 5161 9459 5160 9459 5170 9460 5171 9460 5162 9460 5170 9461 5162 9461 5161 9461 5171 9462 4800 9462 4802 9462 5171 9463 4802 9463 5162 9463 4821 9464 5172 9464 5163 9464 4821 9465 5163 9465 4823 9465 5172 9466 5173 9466 5164 9466 5172 9467 5164 9467 5163 9467 5173 9468 5174 9468 5165 9468 5173 9469 5165 9469 5164 9469 5174 9470 5175 9470 5166 9470 5174 9471 5166 9471 5165 9471 5175 9472 5176 9472 5167 9472 5175 9473 5167 9473 5166 9473 5176 9474 5177 9474 5168 9474 5176 9475 5168 9475 5167 9475 5177 9476 5178 9476 5169 9476 5177 9477 5169 9477 5168 9477 5178 9478 5179 9478 5170 9478 5178 9479 5170 9479 5169 9479 5179 9480 5180 9480 5171 9480 5179 9481 5171 9481 5170 9481 5180 9482 4798 9482 4800 9482 5180 9483 4800 9483 5171 9483 4819 9484 5181 9484 5172 9484 4819 9485 5172 9485 4821 9485 5181 9486 5182 9486 5173 9486 5181 9487 5173 9487 5172 9487 5182 9488 5183 9488 5174 9488 5182 9489 5174 9489 5173 9489 5183 9490 5184 9490 5175 9490 5183 9491 5175 9491 5174 9491 5184 9492 5185 9492 5176 9492 5184 9493 5176 9493 5175 9493 5185 9494 5186 9494 5177 9494 5185 9495 5177 9495 5176 9495 5186 9496 5187 9496 5178 9496 5186 9497 5178 9497 5177 9497 5187 9498 5188 9498 5179 9498 5187 9499 5179 9499 5178 9499 5188 9500 5189 9500 5180 9500 5188 9501 5180 9501 5179 9501 5189 9502 4796 9502 4798 9502 5189 9503 4798 9503 5180 9503 3604 9504 5190 9504 5181 9504 3604 9505 5181 9505 4819 9505 5190 9506 5191 9506 5182 9506 5190 9507 5182 9507 5181 9507 5191 9508 5192 9508 5183 9508 5191 9509 5183 9509 5182 9509 5192 9510 5193 9510 5184 9510 5192 9511 5184 9511 5183 9511 5193 9512 5194 9512 5185 9512 5193 9513 5185 9513 5184 9513 5194 9514 5195 9514 5186 9514 5194 9515 5186 9515 5185 9515 5195 9516 5196 9516 5187 9516 5195 9517 5187 9517 5186 9517 5196 9518 5197 9518 5188 9518 5196 9519 5188 9519 5187 9519 5197 9520 5198 9520 5189 9520 5197 9521 5189 9521 5188 9521 5198 9522 3608 9522 4796 9522 5198 9523 4796 9523 5189 9523 3949 9524 3684 9524 5199 9524 3949 9525 5199 9525 5200 9525 5200 9526 5199 9526 5201 9526 5200 9527 5201 9527 5202 9527 5202 9528 5201 9528 5203 9528 5202 9529 5203 9529 5204 9529 5204 9530 5203 9530 5205 9530 5204 9531 5205 9531 5206 9531 5206 9532 5205 9532 5207 9532 5206 9533 5207 9533 5208 9533 5208 9534 5207 9534 5209 9534 5208 9535 5209 9535 5210 9535 5210 9536 5209 9536 5211 9536 5210 9537 5211 9537 5212 9537 5212 9538 5211 9538 5213 9538 5212 9539 5213 9539 5214 9539 5214 9540 5213 9540 5215 9540 5214 9541 5215 9541 5216 9541 5216 9542 5215 9542 3685 9542 5216 9543 3685 9543 3921 9543 3947 9544 3949 9544 5200 9544 3947 9545 5200 9545 5217 9545 5217 9546 5200 9546 5202 9546 5217 9547 5202 9547 5218 9547 5218 9548 5202 9548 5204 9548 5218 9549 5204 9549 5219 9549 5219 9550 5204 9550 5206 9550 5219 9551 5206 9551 5220 9551 5220 9552 5206 9552 5208 9552 5220 9553 5208 9553 5221 9553 5221 9554 5208 9554 5210 9554 5221 9555 5210 9555 5222 9555 5222 9556 5210 9556 5212 9556 5222 9557 5212 9557 5223 9557 5223 9558 5212 9558 5214 9558 5223 9559 5214 9559 5224 9559 5224 9560 5214 9560 5216 9560 5224 9561 5216 9561 5225 9561 5225 9562 5216 9562 3921 9562 5225 9563 3921 9563 3920 9563 3945 9564 3947 9564 5217 9564 3945 9565 5217 9565 5226 9565 5226 9566 5217 9566 5218 9566 5226 9567 5218 9567 5227 9567 5227 9568 5218 9568 5219 9568 5227 9569 5219 9569 5228 9569 5228 9570 5219 9570 5220 9570 5228 9571 5220 9571 5229 9571 5229 9572 5220 9572 5221 9572 5229 9573 5221 9573 5230 9573 5230 9574 5221 9574 5222 9574 5230 9575 5222 9575 5231 9575 5231 9576 5222 9576 5223 9576 5231 9577 5223 9577 5232 9577 5232 9578 5223 9578 5224 9578 5232 9579 5224 9579 5233 9579 5233 9580 5224 9580 5225 9580 5233 9581 5225 9581 5234 9581 5234 9582 5225 9582 3920 9582 5234 9583 3920 9583 3919 9583 3943 9584 3945 9584 5226 9584 3943 9585 5226 9585 5235 9585 5235 9586 5226 9586 5227 9586 5235 9587 5227 9587 5236 9587 5236 9588 5227 9588 5228 9588 5236 9589 5228 9589 5237 9589 5237 9590 5228 9590 5229 9590 5237 9591 5229 9591 5238 9591 5238 9592 5229 9592 5230 9592 5238 9593 5230 9593 5239 9593 5239 9594 5230 9594 5231 9594 5239 9595 5231 9595 5240 9595 5240 9596 5231 9596 5232 9596 5240 9597 5232 9597 5241 9597 5241 9598 5232 9598 5233 9598 5241 9599 5233 9599 5242 9599 5242 9600 5233 9600 5234 9600 5242 9601 5234 9601 5243 9601 5243 9602 5234 9602 3919 9602 5243 9603 3919 9603 3918 9603 3941 9604 3943 9604 5235 9604 3941 9605 5235 9605 5244 9605 5244 9606 5235 9606 5236 9606 5244 9607 5236 9607 5245 9607 5245 9608 5236 9608 5237 9608 5245 9609 5237 9609 5246 9609 5246 9610 5237 9610 5238 9610 5246 9611 5238 9611 5247 9611 5247 9612 5238 9612 5239 9612 5247 9613 5239 9613 5248 9613 5248 9614 5239 9614 5240 9614 5248 9615 5240 9615 5249 9615 5249 9616 5240 9616 5241 9616 5249 9617 5241 9617 5250 9617 5250 9618 5241 9618 5242 9618 5250 9619 5242 9619 5251 9619 5251 9620 5242 9620 5243 9620 5251 9621 5243 9621 5252 9621 5252 9622 5243 9622 3918 9622 5252 9623 3918 9623 3917 9623 3939 9624 3941 9624 5244 9624 3939 9625 5244 9625 5253 9625 5253 9626 5244 9626 5245 9626 5253 9627 5245 9627 5254 9627 5254 9628 5245 9628 5246 9628 5254 9629 5246 9629 5255 9629 5255 9630 5246 9630 5247 9630 5255 9631 5247 9631 5256 9631 5256 9632 5247 9632 5248 9632 5256 9633 5248 9633 5257 9633 5257 9634 5248 9634 5249 9634 5257 9635 5249 9635 5258 9635 5258 9636 5249 9636 5250 9636 5258 9637 5250 9637 5259 9637 5259 9638 5250 9638 5251 9638 5259 9639 5251 9639 5260 9639 5260 9640 5251 9640 5252 9640 5260 9641 5252 9641 5261 9641 5261 9642 5252 9642 3917 9642 5261 9643 3917 9643 3916 9643 3937 9644 3939 9644 5253 9644 3937 9645 5253 9645 5262 9645 5262 9646 5253 9646 5254 9646 5262 9647 5254 9647 5263 9647 5263 9648 5254 9648 5255 9648 5263 9649 5255 9649 5264 9649 5264 9650 5255 9650 5256 9650 5264 9651 5256 9651 5265 9651 5265 9652 5256 9652 5257 9652 5265 9653 5257 9653 5266 9653 5266 9654 5257 9654 5258 9654 5266 9655 5258 9655 5267 9655 5267 9656 5258 9656 5259 9656 5267 9657 5259 9657 5268 9657 5268 9658 5259 9658 5260 9658 5268 9659 5260 9659 5269 9659 5269 9660 5260 9660 5261 9660 5269 9661 5261 9661 5270 9661 5270 9662 5261 9662 3916 9662 5270 9663 3916 9663 3915 9663 3935 9664 3937 9664 5262 9664 3935 9665 5262 9665 5271 9665 5271 9666 5262 9666 5263 9666 5271 9667 5263 9667 5272 9667 5272 9668 5263 9668 5264 9668 5272 9669 5264 9669 5273 9669 5273 9670 5264 9670 5265 9670 5273 9671 5265 9671 5274 9671 5274 9672 5265 9672 5266 9672 5274 9673 5266 9673 5275 9673 5275 9674 5266 9674 5267 9674 5275 9675 5267 9675 5276 9675 5276 9676 5267 9676 5268 9676 5276 9677 5268 9677 5277 9677 5277 9678 5268 9678 5269 9678 5277 9679 5269 9679 5278 9679 5278 9680 5269 9680 5270 9680 5278 9681 5270 9681 5279 9681 5279 9682 5270 9682 3915 9682 5279 9683 3915 9683 3914 9683 3933 9684 3935 9684 5271 9684 3933 9685 5271 9685 5280 9685 5280 9686 5271 9686 5272 9686 5280 9687 5272 9687 5281 9687 5281 9688 5272 9688 5273 9688 5281 9689 5273 9689 5282 9689 5282 9690 5273 9690 5274 9690 5282 9691 5274 9691 5283 9691 5283 9692 5274 9692 5275 9692 5283 9693 5275 9693 5284 9693 5284 9694 5275 9694 5276 9694 5284 9695 5276 9695 5285 9695 5285 9696 5276 9696 5277 9696 5285 9697 5277 9697 5286 9697 5286 9698 5277 9698 5278 9698 5286 9699 5278 9699 5287 9699 5287 9700 5278 9700 5279 9700 5287 9701 5279 9701 5288 9701 5288 9702 5279 9702 3914 9702 5288 9703 3914 9703 3913 9703 3931 9704 3933 9704 5280 9704 3931 9705 5280 9705 5289 9705 5289 9706 5280 9706 5281 9706 5289 9707 5281 9707 5290 9707 5290 9708 5281 9708 5282 9708 5290 9709 5282 9709 5291 9709 5291 9710 5282 9710 5283 9710 5291 9711 5283 9711 5292 9711 5292 9712 5283 9712 5284 9712 5292 9713 5284 9713 5293 9713 5293 9714 5284 9714 5285 9714 5293 9715 5285 9715 5294 9715 5294 9716 5285 9716 5286 9716 5294 9717 5286 9717 5295 9717 5295 9718 5286 9718 5287 9718 5295 9719 5287 9719 5296 9719 5296 9720 5287 9720 5288 9720 5296 9721 5288 9721 5297 9721 5297 9722 5288 9722 3913 9722 5297 9723 3913 9723 3912 9723 3928 9724 3931 9724 5289 9724 3928 9725 5289 9725 5298 9725 5298 9726 5289 9726 5290 9726 5298 9727 5290 9727 5299 9727 5299 9728 5290 9728 5291 9728 5299 9729 5291 9729 5300 9729 5300 9730 5291 9730 5292 9730 5300 9731 5292 9731 5301 9731 5301 9732 5292 9732 5293 9732 5301 9733 5293 9733 5302 9733 5302 9734 5293 9734 5294 9734 5302 9735 5294 9735 5303 9735 5303 9736 5294 9736 5295 9736 5303 9737 5295 9737 5304 9737 5304 9738 5295 9738 5296 9738 5304 9739 5296 9739 5305 9739 5305 9740 5296 9740 5297 9740 5305 9741 5297 9741 5306 9741 5306 9742 5297 9742 3912 9742 5306 9743 3912 9743 3911 9743 3929 9744 3928 9744 5298 9744 3929 9745 5298 9745 5307 9745 5307 9746 5298 9746 5299 9746 5307 9747 5299 9747 5308 9747 5308 9748 5299 9748 5300 9748 5308 9749 5300 9749 5309 9749 5309 9750 5300 9750 5301 9750 5309 9751 5301 9751 5310 9751 5310 9752 5301 9752 5302 9752 5310 9753 5302 9753 5311 9753 5311 9754 5302 9754 5303 9754 5311 9755 5303 9755 5312 9755 5312 9756 5303 9756 5304 9756 5312 9757 5304 9757 5313 9757 5313 9758 5304 9758 5305 9758 5313 9759 5305 9759 5314 9759 5314 9760 5305 9760 5306 9760 5314 9761 5306 9761 5315 9761 5315 9762 5306 9762 3911 9762 5315 9763 3911 9763 3910 9763 5316 9764 3929 9764 5307 9764 5316 9765 5307 9765 5317 9765 5317 9766 5307 9766 5308 9766 5317 9767 5308 9767 5318 9767 5318 9768 5308 9768 5309 9768 5318 9769 5309 9769 5319 9769 5319 9770 5309 9770 5310 9770 5319 9771 5310 9771 5320 9771 5320 9772 5310 9772 5311 9772 5320 9773 5311 9773 5321 9773 5321 9774 5311 9774 5312 9774 5321 9775 5312 9775 5322 9775 5322 9776 5312 9776 5313 9776 5322 9777 5313 9777 5323 9777 5323 9778 5313 9778 5314 9778 5323 9779 5314 9779 5324 9779 5324 9780 5314 9780 5315 9780 5324 9781 5315 9781 5325 9781 5325 9782 5315 9782 3910 9782 5325 9783 3910 9783 3909 9783 3924 9784 5316 9784 5317 9784 3924 9785 5317 9785 5326 9785 5326 9786 5317 9786 5318 9786 5326 9787 5318 9787 5327 9787 5327 9788 5318 9788 5319 9788 5327 9789 5319 9789 5328 9789 5328 9790 5319 9790 5320 9790 5328 9791 5320 9791 5329 9791 5329 9792 5320 9792 5321 9792 5329 9793 5321 9793 5330 9793 5330 9794 5321 9794 5322 9794 5330 9795 5322 9795 5331 9795 5331 9796 5322 9796 5323 9796 5331 9797 5323 9797 5332 9797 5332 9798 5323 9798 5324 9798 5332 9799 5324 9799 5333 9799 5333 9800 5324 9800 5325 9800 5333 9801 5325 9801 5334 9801 5334 9802 5325 9802 3909 9802 5334 9803 3909 9803 3908 9803 3925 9804 3924 9804 5326 9804 3925 9805 5326 9805 5335 9805 5335 9806 5326 9806 5327 9806 5335 9807 5327 9807 5336 9807 5336 9808 5327 9808 5328 9808 5336 9809 5328 9809 5337 9809 5337 9810 5328 9810 5329 9810 5337 9811 5329 9811 5338 9811 5338 9812 5329 9812 5330 9812 5338 9813 5330 9813 5339 9813 5339 9814 5330 9814 5331 9814 5339 9815 5331 9815 5340 9815 5340 9816 5331 9816 5332 9816 5340 9817 5332 9817 5341 9817 5341 9818 5332 9818 5333 9818 5341 9819 5333 9819 5342 9819 5342 9820 5333 9820 5334 9820 5342 9821 5334 9821 5343 9821 5343 9822 5334 9822 3908 9822 5343 9823 3908 9823 3907 9823 5344 9824 3925 9824 5335 9824 5344 9825 5335 9825 5345 9825 5345 9826 5335 9826 5336 9826 5345 9827 5336 9827 5346 9827 5346 9828 5336 9828 5337 9828 5346 9829 5337 9829 5347 9829 5347 9830 5337 9830 5338 9830 5347 9831 5338 9831 5348 9831 5348 9832 5338 9832 5339 9832 5348 9833 5339 9833 5349 9833 5349 9834 5339 9834 5340 9834 5349 9835 5340 9835 5350 9835 5350 9836 5340 9836 5341 9836 5350 9837 5341 9837 5351 9837 5351 9838 5341 9838 5342 9838 5351 9839 5342 9839 5352 9839 5352 9840 5342 9840 5343 9840 5352 9841 5343 9841 5353 9841 5353 9842 5343 9842 3907 9842 5353 9843 3907 9843 3906 9843 5354 9844 5346 9844 5347 9844 5354 9845 5347 9845 5355 9845 5355 9846 5347 9846 5348 9846 5355 9847 5348 9847 5356 9847 5356 9848 5348 9848 5349 9848 5356 9849 5349 9849 5357 9849 5357 9850 5349 9850 5350 9850 5357 9851 5350 9851 5358 9851 5358 9852 5350 9852 5351 9852 5358 9853 5351 9853 5359 9853 5359 9854 5351 9854 5352 9854 5359 9855 5352 9855 5360 9855 5360 9856 5352 9856 5353 9856 5360 9857 5353 9857 5361 9857 5361 9858 5353 9858 3906 9858 5361 9859 3906 9859 3905 9859 5362 9860 5355 9860 5356 9860 5362 9861 5356 9861 5363 9861 5363 9862 5356 9862 5357 9862 5363 9863 5357 9863 5364 9863 5364 9864 5357 9864 5358 9864 5364 9865 5358 9865 5365 9865 5365 9866 5358 9866 5359 9866 5365 9867 5359 9867 5366 9867 5366 9868 5359 9868 5360 9868 5366 9869 5360 9869 5367 9869 5367 9870 5360 9870 5361 9870 5367 9871 5361 9871 5368 9871 5368 9872 5361 9872 3905 9872 5368 9873 3905 9873 3904 9873 5369 9874 5363 9874 5364 9874 5369 9875 5364 9875 5370 9875 5370 9876 5364 9876 5365 9876 5370 9877 5365 9877 5371 9877 5371 9878 5365 9878 5366 9878 5371 9879 5366 9879 5372 9879 5372 9880 5366 9880 5367 9880 5372 9881 5367 9881 5373 9881 5373 9882 5367 9882 5368 9882 5373 9883 5368 9883 5374 9883 5374 9884 5368 9884 3904 9884 5374 9885 3904 9885 3903 9885 5375 9886 5370 9886 5371 9886 5375 9887 5371 9887 5376 9887 5376 9888 5371 9888 5372 9888 5376 9889 5372 9889 5377 9889 5377 9890 5372 9890 5373 9890 5377 9891 5373 9891 5378 9891 5378 9892 5373 9892 5374 9892 5378 9893 5374 9893 5379 9893 5379 9894 5374 9894 3903 9894 5379 9895 3903 9895 3667 9895 3603 9896 3731 9896 5380 9896 3603 9897 5380 9897 5381 9897 5381 9898 5380 9898 5382 9898 5381 9899 5382 9899 5383 9899 5383 9900 5382 9900 5384 9900 5383 9901 5384 9901 5385 9901 5385 9902 5384 9902 5386 9902 5385 9903 5386 9903 5387 9903 5387 9904 5386 9904 5388 9904 5387 9905 5388 9905 5389 9905 5389 9906 5388 9906 5390 9906 5389 9907 5390 9907 5391 9907 5391 9908 5390 9908 5392 9908 5391 9909 5392 9909 5393 9909 5393 9910 5392 9910 5394 9910 5393 9911 5394 9911 5395 9911 5395 9912 5394 9912 5396 9912 5395 9913 5396 9913 5397 9913 5397 9914 5396 9914 3728 9914 5397 9915 3728 9915 3605 9915 3684 9916 3683 9916 5398 9916 3684 9917 5398 9917 5199 9917 5199 9918 5398 9918 5399 9918 5199 9919 5399 9919 5201 9919 5201 9920 5399 9920 5400 9920 5201 9921 5400 9921 5203 9921 5203 9922 5400 9922 5401 9922 5203 9923 5401 9923 5205 9923 5205 9924 5401 9924 5402 9924 5205 9925 5402 9925 5207 9925 5207 9926 5402 9926 5403 9926 5207 9927 5403 9927 5209 9927 5209 9928 5403 9928 5404 9928 5209 9929 5404 9929 5211 9929 5211 9930 5404 9930 5405 9930 5211 9931 5405 9931 5213 9931 5213 9932 5405 9932 5406 9932 5213 9933 5406 9933 5215 9933 5215 9934 5406 9934 3686 9934 5215 9935 3686 9935 3685 9935 5376 9936 5377 9936 5407 9936 5376 9937 5407 9937 5408 9937 5377 9938 5378 9938 5409 9938 5377 9939 5409 9939 5407 9939 5378 9940 5379 9940 5410 9940 5378 9941 5410 9941 5409 9941 5379 9942 3667 9942 3669 9942 5379 9943 3669 9943 5410 9943 3631 9944 5033 9944 3669 9944 3631 9945 3669 9945 3632 9945 5033 9946 5035 9946 5410 9946 5033 9947 5410 9947 3669 9947 5035 9948 5037 9948 5409 9948 5035 9949 5409 9949 5410 9949 5037 9950 5039 9950 5407 9950 5037 9951 5407 9951 5409 9951 5039 9952 5041 9952 5408 9952 5039 9953 5408 9953 5407 9953 3603 9954 5381 9954 5190 9954 3603 9955 5190 9955 3604 9955 5381 9956 5383 9956 5191 9956 5381 9957 5191 9957 5190 9957 5383 9958 5385 9958 5192 9958 5383 9959 5192 9959 5191 9959 5385 9960 5387 9960 5193 9960 5385 9961 5193 9961 5192 9961 5387 9962 5389 9962 5194 9962 5387 9963 5194 9963 5193 9963 5389 9964 5391 9964 5195 9964 5389 9965 5195 9965 5194 9965 5391 9966 5393 9966 5196 9966 5391 9967 5196 9967 5195 9967 5393 9968 5395 9968 5197 9968 5393 9969 5197 9969 5196 9969 5395 9970 5397 9970 5198 9970 5395 9971 5198 9971 5197 9971 5397 9972 3605 9972 3608 9972 5397 9973 3608 9973 5198 9973 5411 9974 5412 9974 5413 9974 5411 9975 5413 9975 5414 9975 5412 9976 5415 9976 5416 9976 5412 9977 5416 9977 5413 9977 5415 9978 5417 9978 5418 9978 5415 9979 5418 9979 5416 9979 5417 9980 5419 9980 5420 9980 5417 9981 5420 9981 5418 9981 5419 9982 5421 9982 5422 9982 5419 9983 5422 9983 5420 9983 5421 9984 4794 9984 3633 9984 5421 9985 3633 9985 5422 9985 5423 9986 5424 9986 5415 9986 5423 9987 5415 9987 5412 9987 5424 9988 5425 9988 5417 9988 5424 9989 5417 9989 5415 9989 5425 9990 5426 9990 5419 9990 5425 9991 5419 9991 5417 9991 5426 9992 5427 9992 5421 9992 5426 9993 5421 9993 5419 9993 5427 9994 4793 9994 4794 9994 5427 9995 4794 9995 5421 9995 5428 9996 5429 9996 5426 9996 5428 9997 5426 9997 5425 9997 5429 9998 5430 9998 5427 9998 5429 9999 5427 9999 5426 9999 5430 10000 4792 10000 4793 10000 5430 10001 4793 10001 5427 10001 5431 10002 5432 10002 5430 10002 5431 10003 5430 10003 5429 10003 5432 10004 4791 10004 4792 10004 5432 10005 4792 10005 5430 10005 5433 10006 5434 10006 5432 10006 5433 10007 5432 10007 5431 10007 5434 10008 4790 10008 4791 10008 5434 10009 4791 10009 5432 10009 5435 10010 5436 10010 5434 10010 5435 10011 5434 10011 5433 10011 5436 10012 4789 10012 4790 10012 5436 10013 4790 10013 5434 10013 5437 10014 4788 10014 4789 10014 5437 10015 4789 10015 5436 10015 4813 10016 5438 10016 5439 10016 4813 10017 5439 10017 4815 10017 5438 10018 5440 10018 5441 10018 5438 10019 5441 10019 5439 10019 4811 10020 5442 10020 5438 10020 4811 10021 5438 10021 4813 10021 5442 10022 5443 10022 5440 10022 5442 10023 5440 10023 5438 10023 5443 10024 5444 10024 5445 10024 5443 10025 5445 10025 5440 10025 5444 10026 5446 10026 5447 10026 5444 10027 5447 10027 5445 10027 5446 10028 5448 10028 5449 10028 5446 10029 5449 10029 5447 10029 4809 10030 5450 10030 5442 10030 4809 10031 5442 10031 4811 10031 5450 10032 5451 10032 5443 10032 5450 10033 5443 10033 5442 10033 5451 10034 5452 10034 5444 10034 5451 10035 5444 10035 5443 10035 5452 10036 5453 10036 5446 10036 5452 10037 5446 10037 5444 10037 5453 10038 5454 10038 5448 10038 5453 10039 5448 10039 5446 10039 5454 10040 5455 10040 5456 10040 5454 10041 5456 10041 5448 10041 5455 10042 5457 10042 5458 10042 5455 10043 5458 10043 5456 10043 4807 10044 5459 10044 5450 10044 4807 10045 5450 10045 4809 10045 5459 10046 5460 10046 5451 10046 5459 10047 5451 10047 5450 10047 5460 10048 5461 10048 5452 10048 5460 10049 5452 10049 5451 10049 5461 10050 5462 10050 5453 10050 5461 10051 5453 10051 5452 10051 5462 10052 5463 10052 5454 10052 5462 10053 5454 10053 5453 10053 5463 10054 5464 10054 5455 10054 5463 10055 5455 10055 5454 10055 5464 10056 5465 10056 5457 10056 5464 10057 5457 10057 5455 10057 5465 10058 5466 10058 5467 10058 5465 10059 5467 10059 5457 10059 4805 10060 5468 10060 5459 10060 4805 10061 5459 10061 4807 10061 5468 10062 5469 10062 5460 10062 5468 10063 5460 10063 5459 10063 5469 10064 5470 10064 5461 10064 5469 10065 5461 10065 5460 10065 5470 10066 5471 10066 5462 10066 5470 10067 5462 10067 5461 10067 5471 10068 5472 10068 5463 10068 5471 10069 5463 10069 5462 10069 5472 10070 5473 10070 5464 10070 5472 10071 5464 10071 5463 10071 5473 10072 5474 10072 5465 10072 5473 10073 5465 10073 5464 10073 5474 10074 5475 10074 5466 10074 5474 10075 5466 10075 5465 10075 5475 10076 5476 10076 5477 10076 5475 10077 5477 10077 5466 10077 4803 10078 5478 10078 5468 10078 4803 10079 5468 10079 4805 10079 5478 10080 5479 10080 5469 10080 5478 10081 5469 10081 5468 10081 5479 10082 5480 10082 5470 10082 5479 10083 5470 10083 5469 10083 5480 10084 5481 10084 5471 10084 5480 10085 5471 10085 5470 10085 5481 10086 5482 10086 5472 10086 5481 10087 5472 10087 5471 10087 5482 10088 5483 10088 5473 10088 5482 10089 5473 10089 5472 10089 5483 10090 5484 10090 5474 10090 5483 10091 5474 10091 5473 10091 5484 10092 5485 10092 5475 10092 5484 10093 5475 10093 5474 10093 5485 10094 5486 10094 5476 10094 5485 10095 5476 10095 5475 10095 4801 10096 5487 10096 5478 10096 4801 10097 5478 10097 4803 10097 5487 10098 5488 10098 5479 10098 5487 10099 5479 10099 5478 10099 5488 10100 5489 10100 5480 10100 5488 10101 5480 10101 5479 10101 5489 10102 5490 10102 5481 10102 5489 10103 5481 10103 5480 10103 5490 10104 5491 10104 5482 10104 5490 10105 5482 10105 5481 10105 5491 10106 5492 10106 5483 10106 5491 10107 5483 10107 5482 10107 5492 10108 5493 10108 5484 10108 5492 10109 5484 10109 5483 10109 5493 10110 5494 10110 5485 10110 5493 10111 5485 10111 5484 10111 5494 10112 5495 10112 5486 10112 5494 10113 5486 10113 5485 10113 4799 10114 5496 10114 5487 10114 4799 10115 5487 10115 4801 10115 5496 10116 5497 10116 5488 10116 5496 10117 5488 10117 5487 10117 5497 10118 5498 10118 5489 10118 5497 10119 5489 10119 5488 10119 5498 10120 5499 10120 5490 10120 5498 10121 5490 10121 5489 10121 5499 10122 5500 10122 5491 10122 5499 10123 5491 10123 5490 10123 5500 10124 5501 10124 5492 10124 5500 10125 5492 10125 5491 10125 5501 10126 5502 10126 5493 10126 5501 10127 5493 10127 5492 10127 5502 10128 5503 10128 5494 10128 5502 10129 5494 10129 5493 10129 4797 10130 5504 10130 5496 10130 4797 10131 5496 10131 4799 10131 5504 10132 5505 10132 5497 10132 5504 10133 5497 10133 5496 10133 5505 10134 5506 10134 5498 10134 5505 10135 5498 10135 5497 10135 5506 10136 5507 10136 5499 10136 5506 10137 5499 10137 5498 10137 5507 10138 5508 10138 5500 10138 5507 10139 5500 10139 5499 10139 5508 10140 5509 10140 5501 10140 5508 10141 5501 10141 5500 10141 5509 10142 5510 10142 5502 10142 5509 10143 5502 10143 5501 10143 5510 10144 5511 10144 5503 10144 5510 10145 5503 10145 5502 10145 4795 10146 5512 10146 5504 10146 4795 10147 5504 10147 4797 10147 5512 10148 5513 10148 5505 10148 5512 10149 5505 10149 5504 10149 5513 10150 5514 10150 5506 10150 5513 10151 5506 10151 5505 10151 5514 10152 5515 10152 5507 10152 5514 10153 5507 10153 5506 10153 5515 10154 5516 10154 5508 10154 5515 10155 5508 10155 5507 10155 5516 10156 5517 10156 5509 10156 5516 10157 5509 10157 5508 10157 5517 10158 5518 10158 5510 10158 5517 10159 5510 10159 5509 10159 5518 10160 5519 10160 5511 10160 5518 10161 5511 10161 5510 10161 3607 10162 5520 10162 5512 10162 3607 10163 5512 10163 4795 10163 5520 10164 5521 10164 5513 10164 5520 10165 5513 10165 5512 10165 5521 10166 5522 10166 5514 10166 5521 10167 5514 10167 5513 10167 5522 10168 5523 10168 5515 10168 5522 10169 5515 10169 5514 10169 5523 10170 5524 10170 5516 10170 5523 10171 5516 10171 5515 10171 5524 10172 5525 10172 5517 10172 5524 10173 5517 10173 5516 10173 5525 10174 5526 10174 5518 10174 5525 10175 5518 10175 5517 10175 5526 10176 5527 10176 5519 10176 5526 10177 5519 10177 5518 10177 3987 10178 3680 10178 5528 10178 3987 10179 5528 10179 5529 10179 5529 10180 5528 10180 5530 10180 5529 10181 5530 10181 5531 10181 5531 10182 5530 10182 5532 10182 5531 10183 5532 10183 5533 10183 5533 10184 5532 10184 5534 10184 5533 10185 5534 10185 5535 10185 5535 10186 5534 10186 5536 10186 5535 10187 5536 10187 5537 10187 5537 10188 5536 10188 5538 10188 5537 10189 5538 10189 5539 10189 5539 10190 5538 10190 5540 10190 5539 10191 5540 10191 5541 10191 5541 10192 5540 10192 5542 10192 5541 10193 5542 10193 5543 10193 5543 10194 5542 10194 5544 10194 5543 10195 5544 10195 5545 10195 5545 10196 5544 10196 3681 10196 5545 10197 3681 10197 3948 10197 3985 10198 3987 10198 5529 10198 3985 10199 5529 10199 5546 10199 5546 10200 5529 10200 5531 10200 5546 10201 5531 10201 5547 10201 5547 10202 5531 10202 5533 10202 5547 10203 5533 10203 5548 10203 5548 10204 5533 10204 5535 10204 5548 10205 5535 10205 5549 10205 5549 10206 5535 10206 5537 10206 5549 10207 5537 10207 5550 10207 5550 10208 5537 10208 5539 10208 5550 10209 5539 10209 5551 10209 5551 10210 5539 10210 5541 10210 5551 10211 5541 10211 5552 10211 5552 10212 5541 10212 5543 10212 5552 10213 5543 10213 5553 10213 5553 10214 5543 10214 5545 10214 5553 10215 5545 10215 5554 10215 5554 10216 5545 10216 3948 10216 5554 10217 3948 10217 3946 10217 3983 10218 3985 10218 5546 10218 3983 10219 5546 10219 5555 10219 5555 10220 5546 10220 5547 10220 5555 10221 5547 10221 5556 10221 5556 10222 5547 10222 5548 10222 5556 10223 5548 10223 5557 10223 5557 10224 5548 10224 5549 10224 5557 10225 5549 10225 5558 10225 5558 10226 5549 10226 5550 10226 5558 10227 5550 10227 5559 10227 5559 10228 5550 10228 5551 10228 5559 10229 5551 10229 5560 10229 5560 10230 5551 10230 5552 10230 5560 10231 5552 10231 5561 10231 5561 10232 5552 10232 5553 10232 5561 10233 5553 10233 5562 10233 5562 10234 5553 10234 5554 10234 5562 10235 5554 10235 5563 10235 5563 10236 5554 10236 3946 10236 5563 10237 3946 10237 3944 10237 3981 10238 3983 10238 5555 10238 3981 10239 5555 10239 5564 10239 5564 10240 5555 10240 5556 10240 5564 10241 5556 10241 5565 10241 5565 10242 5556 10242 5557 10242 5565 10243 5557 10243 5566 10243 5566 10244 5557 10244 5558 10244 5566 10245 5558 10245 5567 10245 5567 10246 5558 10246 5559 10246 5567 10247 5559 10247 5568 10247 5568 10248 5559 10248 5560 10248 5568 10249 5560 10249 5569 10249 5569 10250 5560 10250 5561 10250 5569 10251 5561 10251 5570 10251 5570 10252 5561 10252 5562 10252 5570 10253 5562 10253 5571 10253 5571 10254 5562 10254 5563 10254 5571 10255 5563 10255 5572 10255 5572 10256 5563 10256 3944 10256 5572 10257 3944 10257 3942 10257 3979 10258 3981 10258 5564 10258 3979 10259 5564 10259 5573 10259 5573 10260 5564 10260 5565 10260 5573 10261 5565 10261 5574 10261 5574 10262 5565 10262 5566 10262 5574 10263 5566 10263 5575 10263 5575 10264 5566 10264 5567 10264 5575 10265 5567 10265 5576 10265 5576 10266 5567 10266 5568 10266 5576 10267 5568 10267 5577 10267 5577 10268 5568 10268 5569 10268 5577 10269 5569 10269 5578 10269 5578 10270 5569 10270 5570 10270 5578 10271 5570 10271 5579 10271 5579 10272 5570 10272 5571 10272 5579 10273 5571 10273 5580 10273 5580 10274 5571 10274 5572 10274 5580 10275 5572 10275 5581 10275 5581 10276 5572 10276 3942 10276 5581 10277 3942 10277 3940 10277 3977 10278 3979 10278 5573 10278 3977 10279 5573 10279 5582 10279 5582 10280 5573 10280 5574 10280 5582 10281 5574 10281 5583 10281 5583 10282 5574 10282 5575 10282 5583 10283 5575 10283 5584 10283 5584 10284 5575 10284 5576 10284 5584 10285 5576 10285 5585 10285 5585 10286 5576 10286 5577 10286 5585 10287 5577 10287 5586 10287 5586 10288 5577 10288 5578 10288 5586 10289 5578 10289 5587 10289 5587 10290 5578 10290 5579 10290 5587 10291 5579 10291 5588 10291 5588 10292 5579 10292 5580 10292 5588 10293 5580 10293 5589 10293 5589 10294 5580 10294 5581 10294 5589 10295 5581 10295 5590 10295 5590 10296 5581 10296 3940 10296 5590 10297 3940 10297 3938 10297 3975 10298 3977 10298 5582 10298 3975 10299 5582 10299 5591 10299 5591 10300 5582 10300 5583 10300 5591 10301 5583 10301 5592 10301 5592 10302 5583 10302 5584 10302 5592 10303 5584 10303 5593 10303 5593 10304 5584 10304 5585 10304 5593 10305 5585 10305 5594 10305 5594 10306 5585 10306 5586 10306 5594 10307 5586 10307 5595 10307 5595 10308 5586 10308 5587 10308 5595 10309 5587 10309 5596 10309 5596 10310 5587 10310 5588 10310 5596 10311 5588 10311 5597 10311 5597 10312 5588 10312 5589 10312 5597 10313 5589 10313 5598 10313 5598 10314 5589 10314 5590 10314 5598 10315 5590 10315 5599 10315 5599 10316 5590 10316 3938 10316 5599 10317 3938 10317 3936 10317 3973 10318 3975 10318 5591 10318 3973 10319 5591 10319 5600 10319 5600 10320 5591 10320 5592 10320 5600 10321 5592 10321 5601 10321 5601 10322 5592 10322 5593 10322 5601 10323 5593 10323 5602 10323 5602 10324 5593 10324 5594 10324 5602 10325 5594 10325 5603 10325 5603 10326 5594 10326 5595 10326 5603 10327 5595 10327 5604 10327 5604 10328 5595 10328 5596 10328 5604 10329 5596 10329 5605 10329 5605 10330 5596 10330 5597 10330 5605 10331 5597 10331 5606 10331 5606 10332 5597 10332 5598 10332 5606 10333 5598 10333 5607 10333 5607 10334 5598 10334 5599 10334 5607 10335 5599 10335 5608 10335 5608 10336 5599 10336 3936 10336 5608 10337 3936 10337 3934 10337 3971 10338 3973 10338 5600 10338 3971 10339 5600 10339 5609 10339 5609 10340 5600 10340 5601 10340 5609 10341 5601 10341 5610 10341 5610 10342 5601 10342 5602 10342 5610 10343 5602 10343 5611 10343 5611 10344 5602 10344 5603 10344 5611 10345 5603 10345 5612 10345 5612 10346 5603 10346 5604 10346 5612 10347 5604 10347 5613 10347 5613 10348 5604 10348 5605 10348 5613 10349 5605 10349 5614 10349 5614 10350 5605 10350 5606 10350 5614 10351 5606 10351 5615 10351 5615 10352 5606 10352 5607 10352 5615 10353 5607 10353 5616 10353 5616 10354 5607 10354 5608 10354 5616 10355 5608 10355 5617 10355 5617 10356 5608 10356 3934 10356 5617 10357 3934 10357 3932 10357 3969 10358 3971 10358 5609 10358 3969 10359 5609 10359 5618 10359 5618 10360 5609 10360 5610 10360 5618 10361 5610 10361 5619 10361 5619 10362 5610 10362 5611 10362 5619 10363 5611 10363 5620 10363 5620 10364 5611 10364 5612 10364 5620 10365 5612 10365 5621 10365 5621 10366 5612 10366 5613 10366 5621 10367 5613 10367 5622 10367 5622 10368 5613 10368 5614 10368 5622 10369 5614 10369 5623 10369 5623 10370 5614 10370 5615 10370 5623 10371 5615 10371 5624 10371 5624 10372 5615 10372 5616 10372 5624 10373 5616 10373 5625 10373 5625 10374 5616 10374 5617 10374 5625 10375 5617 10375 5626 10375 5626 10376 5617 10376 3932 10376 5626 10377 3932 10377 3930 10377 3967 10378 3969 10378 5618 10378 3967 10379 5618 10379 5627 10379 5627 10380 5618 10380 5619 10380 5627 10381 5619 10381 5628 10381 5628 10382 5619 10382 5620 10382 5628 10383 5620 10383 5629 10383 5629 10384 5620 10384 5621 10384 5629 10385 5621 10385 5630 10385 5630 10386 5621 10386 5622 10386 5630 10387 5622 10387 5631 10387 5631 10388 5622 10388 5623 10388 5631 10389 5623 10389 5632 10389 5632 10390 5623 10390 5624 10390 5632 10391 5624 10391 5633 10391 5633 10392 5624 10392 5625 10392 5633 10393 5625 10393 5634 10393 5634 10394 5625 10394 5626 10394 5634 10395 5626 10395 5635 10395 5635 10396 5626 10396 3930 10396 5635 10397 3930 10397 3927 10397 3965 10398 3967 10398 5627 10398 3965 10399 5627 10399 5636 10399 5636 10400 5627 10400 5628 10400 5636 10401 5628 10401 5637 10401 5637 10402 5628 10402 5629 10402 5637 10403 5629 10403 5638 10403 5638 10404 5629 10404 5630 10404 5638 10405 5630 10405 5639 10405 5639 10406 5630 10406 5631 10406 5639 10407 5631 10407 5640 10407 5640 10408 5631 10408 5632 10408 5640 10409 5632 10409 5641 10409 5641 10410 5632 10410 5633 10410 5641 10411 5633 10411 5642 10411 5642 10412 5633 10412 5634 10412 5642 10413 5634 10413 5643 10413 5643 10414 5634 10414 5635 10414 5643 10415 5635 10415 5644 10415 5644 10416 5635 10416 3927 10416 5644 10417 3927 10417 3926 10417 3963 10418 3965 10418 5636 10418 3963 10419 5636 10419 5645 10419 5645 10420 5636 10420 5637 10420 5645 10421 5637 10421 5646 10421 5646 10422 5637 10422 5638 10422 5646 10423 5638 10423 5647 10423 5647 10424 5638 10424 5639 10424 5647 10425 5639 10425 5648 10425 5648 10426 5639 10426 5640 10426 5648 10427 5640 10427 5649 10427 5649 10428 5640 10428 5641 10428 5649 10429 5641 10429 5650 10429 5650 10430 5641 10430 5642 10430 5650 10431 5642 10431 5651 10431 5651 10432 5642 10432 5643 10432 5651 10433 5643 10433 5652 10433 3961 10434 3963 10434 5645 10434 3961 10435 5645 10435 5653 10435 5653 10436 5645 10436 5646 10436 5653 10437 5646 10437 5654 10437 5654 10438 5646 10438 5647 10438 5654 10439 5647 10439 5655 10439 5655 10440 5647 10440 5648 10440 5655 10441 5648 10441 5656 10441 5656 10442 5648 10442 5649 10442 5656 10443 5649 10443 5657 10443 5657 10444 5649 10444 5650 10444 5657 10445 5650 10445 5658 10445 5658 10446 5650 10446 5651 10446 5658 10447 5651 10447 5659 10447 3959 10448 3961 10448 5653 10448 3959 10449 5653 10449 5660 10449 5660 10450 5653 10450 5654 10450 5660 10451 5654 10451 5661 10451 5661 10452 5654 10452 5655 10452 5661 10453 5655 10453 5662 10453 5662 10454 5655 10454 5656 10454 5662 10455 5656 10455 5663 10455 5663 10456 5656 10456 5657 10456 5663 10457 5657 10457 5664 10457 3957 10458 3959 10458 5660 10458 3957 10459 5660 10459 5665 10459 5665 10460 5660 10460 5661 10460 5665 10461 5661 10461 5666 10461 5666 10462 5661 10462 5662 10462 5666 10463 5662 10463 5667 10463 3955 10464 3957 10464 5665 10464 3955 10465 5665 10465 5668 10465 5668 10466 5665 10466 5666 10466 5668 10467 5666 10467 5669 10467 3953 10468 3955 10468 5668 10468 3953 10469 5668 10469 5670 10469 5670 10470 5668 10470 5669 10470 5670 10471 5669 10471 5671 10471 3951 10472 3953 10472 5670 10472 3951 10473 5670 10473 5672 10473 5672 10474 5670 10474 5671 10474 5672 10475 5671 10475 5673 10475 3666 10476 3951 10476 5672 10476 3666 10477 5672 10477 5674 10477 5674 10478 5672 10478 5673 10478 5674 10479 5673 10479 5675 10479 5675 10480 5673 10480 5676 10480 5675 10481 5676 10481 5677 10481 3606 10482 3729 10482 5678 10482 3606 10483 5678 10483 5679 10483 5679 10484 5678 10484 5680 10484 5679 10485 5680 10485 5681 10485 5681 10486 5680 10486 5682 10486 5681 10487 5682 10487 5683 10487 5683 10488 5682 10488 5684 10488 5683 10489 5684 10489 5685 10489 5685 10490 5684 10490 5686 10490 5685 10491 5686 10491 5687 10491 5687 10492 5686 10492 5688 10492 5687 10493 5688 10493 5689 10493 5689 10494 5688 10494 5690 10494 5689 10495 5690 10495 5691 10495 3680 10496 3679 10496 5692 10496 3680 10497 5692 10497 5528 10497 5528 10498 5692 10498 5693 10498 5528 10499 5693 10499 5530 10499 5530 10500 5693 10500 5694 10500 5530 10501 5694 10501 5532 10501 5532 10502 5694 10502 5695 10502 5532 10503 5695 10503 5534 10503 5534 10504 5695 10504 5696 10504 5534 10505 5696 10505 5536 10505 5536 10506 5696 10506 5697 10506 5536 10507 5697 10507 5538 10507 5538 10508 5697 10508 5698 10508 5538 10509 5698 10509 5540 10509 5540 10510 5698 10510 5699 10510 5540 10511 5699 10511 5542 10511 5542 10512 5699 10512 5700 10512 5542 10513 5700 10513 5544 10513 5544 10514 5700 10514 3682 10514 5544 10515 3682 10515 3681 10515 3666 10516 5674 10516 3636 10516 3666 10517 3636 10517 3635 10517 5674 10518 5675 10518 5701 10518 5674 10519 5701 10519 3636 10519 5675 10520 5677 10520 5702 10520 5675 10521 5702 10521 5701 10521 5677 10522 5703 10522 5704 10522 5677 10523 5704 10523 5702 10523 5703 10524 5705 10524 5706 10524 5703 10525 5706 10525 5704 10525 5707 10526 5414 10526 5708 10526 5707 10527 5708 10527 5709 10527 5414 10528 5413 10528 5710 10528 5414 10529 5710 10529 5708 10529 5413 10530 5416 10530 5706 10530 5413 10531 5706 10531 5710 10531 5416 10532 5418 10532 5704 10532 5416 10533 5704 10533 5706 10533 5418 10534 5420 10534 5702 10534 5418 10535 5702 10535 5704 10535 5420 10536 5422 10536 5701 10536 5420 10537 5701 10537 5702 10537 5422 10538 3633 10538 3636 10538 5422 10539 3636 10539 5701 10539 3606 10540 5679 10540 5520 10540 3606 10541 5520 10541 3607 10541 5679 10542 5681 10542 5521 10542 5679 10543 5521 10543 5520 10543 5681 10544 5683 10544 5522 10544 5681 10545 5522 10545 5521 10545 5683 10546 5685 10546 5523 10546 5683 10547 5523 10547 5522 10547 5685 10548 5687 10548 5524 10548 5685 10549 5524 10549 5523 10549 5687 10550 5689 10550 5525 10550 5687 10551 5525 10551 5524 10551 5689 10552 5691 10552 5526 10552 5689 10553 5526 10553 5525 10553 5691 10554 5711 10554 5527 10554 5691 10555 5527 10555 5526 10555 4081 10556 4091 10556 4075 10556 4111 10557 4068 10557 4075 10557 4111 10558 4075 10558 4091 10558 4113 10559 4060 10559 4068 10559 4113 10560 4068 10560 4111 10560 4115 10561 4049 10561 4060 10561 4115 10562 4060 10562 4113 10562 5712 10563 5713 10563 4049 10563 5712 10564 4049 10564 5030 10564 4114 10565 4451 10565 4426 10565 4424 10566 4423 10566 4114 10566 4424 10567 4114 10567 4426 10567 4060 10568 4049 10568 4059 10568 4115 10569 4114 10569 4423 10569 5714 10570 5029 10570 5715 10570 5716 10571 5713 10571 4049 10571 4115 10572 4049 10572 5717 10572 4049 10573 5716 10573 5717 10573 4002 10574 4023 10574 4003 10574 5716 10575 5718 10575 5713 10575 5719 10576 5715 10576 5714 10576 5719 10577 5714 10577 5720 10577 4484 10578 4483 10578 4464 10578 4484 10579 4464 10579 4465 10579 4486 10580 4485 10580 4466 10580 4486 10581 4466 10581 4467 10581 4446 10582 4467 10582 4466 10582 4446 10583 4466 10583 4445 10583 4776 10584 5721 10584 5722 10584 4776 10585 5722 10585 3639 10585 4774 10586 5723 10586 5721 10586 4774 10587 5721 10587 4776 10587 4772 10588 5724 10588 5723 10588 4772 10589 5723 10589 4774 10589 4770 10590 5725 10590 5724 10590 4770 10591 5724 10591 4772 10591 4768 10592 5726 10592 5725 10592 4768 10593 5725 10593 4770 10593 4766 10594 5727 10594 5726 10594 4766 10595 5726 10595 4768 10595 4764 10596 5728 10596 5727 10596 4764 10597 5727 10597 4766 10597 4762 10598 5729 10598 5728 10598 4762 10599 5728 10599 4764 10599 4760 10600 5730 10600 5729 10600 4760 10601 5729 10601 4762 10601 4758 10602 5731 10602 5730 10602 4758 10603 5730 10603 4760 10603 4756 10604 5732 10604 5731 10604 4756 10605 5731 10605 4758 10605 4754 10606 5733 10606 5732 10606 4754 10607 5732 10607 4756 10607 4752 10608 5734 10608 5733 10608 4752 10609 5733 10609 4754 10609 4750 10610 5735 10610 5734 10610 4750 10611 5734 10611 4752 10611 4748 10612 5736 10612 5735 10612 4748 10613 5735 10613 4750 10613 4746 10614 5737 10614 5736 10614 4746 10615 5736 10615 4748 10615 4744 10616 5738 10616 5737 10616 4744 10617 5737 10617 4746 10617 4743 10618 5739 10618 5738 10618 4743 10619 5738 10619 4744 10619 5740 10620 5741 10620 5739 10620 5740 10621 5739 10621 4743 10621 5742 10622 5743 10622 5741 10622 5742 10623 5741 10623 5740 10623 5744 10624 5745 10624 4022 10624 5744 10625 4022 10625 4021 10625 5746 10626 5744 10626 4021 10626 5746 10627 4021 10627 4020 10627 5747 10628 5746 10628 4020 10628 5747 10629 4020 10629 4019 10629 5748 10630 5747 10630 4019 10630 5748 10631 4019 10631 4018 10631 5749 10632 5748 10632 4018 10632 5749 10633 4018 10633 4017 10633 5750 10634 5749 10634 4017 10634 5750 10635 4017 10635 4016 10635 5751 10636 5750 10636 4016 10636 5751 10637 4016 10637 4015 10637 5752 10638 5751 10638 4015 10638 5752 10639 4015 10639 4014 10639 5753 10640 5752 10640 4014 10640 5753 10641 4014 10641 4013 10641 5754 10642 5753 10642 4013 10642 5754 10643 4013 10643 4012 10643 5755 10644 5754 10644 4012 10644 5755 10645 4012 10645 4011 10645 5756 10646 5755 10646 4011 10646 5756 10647 4011 10647 4010 10647 5757 10648 5756 10648 4010 10648 5757 10649 4010 10649 4009 10649 5758 10650 5757 10650 4009 10650 5758 10651 4009 10651 4008 10651 5759 10652 5758 10652 4008 10652 5759 10653 4008 10653 3662 10653 5759 10654 3662 10654 3664 10654 5759 10655 3664 10655 5760 10655 3639 10656 5722 10656 3664 10656 3639 10657 3664 10657 3640 10657 4024 10658 4022 10658 4004 10658 5761 10659 5759 10659 5760 10659 5761 10660 5760 10660 3644 10660 5761 10661 5762 10661 5758 10661 5761 10662 5758 10662 5759 10662 5762 10663 5763 10663 5757 10663 5762 10664 5757 10664 5758 10664 5763 10665 5764 10665 5756 10665 5763 10666 5756 10666 5757 10666 5764 10667 5765 10667 5755 10667 5764 10668 5755 10668 5756 10668 5765 10669 5766 10669 5754 10669 5765 10670 5754 10670 5755 10670 5766 10671 5767 10671 5753 10671 5766 10672 5753 10672 5754 10672 5767 10673 5768 10673 5752 10673 5767 10674 5752 10674 5753 10674 5768 10675 5769 10675 5751 10675 5768 10676 5751 10676 5752 10676 5769 10677 5770 10677 5750 10677 5769 10678 5750 10678 5751 10678 5770 10679 5771 10679 5749 10679 5770 10680 5749 10680 5750 10680 5771 10681 5772 10681 5748 10681 5771 10682 5748 10682 5749 10682 5772 10683 5773 10683 5747 10683 5772 10684 5747 10684 5748 10684 5773 10685 5774 10685 5747 10685 5774 10686 5746 10686 5747 10686 5721 10687 5775 10687 5776 10687 5721 10688 5776 10688 5722 10688 5723 10689 5777 10689 5775 10689 5723 10690 5775 10690 5721 10690 5724 10691 5778 10691 5777 10691 5724 10692 5777 10692 5723 10692 5725 10693 5779 10693 5778 10693 5725 10694 5778 10694 5724 10694 5726 10695 5780 10695 5779 10695 5726 10696 5779 10696 5725 10696 5727 10697 5781 10697 5780 10697 5727 10698 5780 10698 5726 10698 5728 10699 5782 10699 5781 10699 5728 10700 5781 10700 5727 10700 5729 10701 5783 10701 5782 10701 5729 10702 5782 10702 5728 10702 5730 10703 5784 10703 5783 10703 5730 10704 5783 10704 5729 10704 5731 10705 5785 10705 5784 10705 5731 10706 5784 10706 5730 10706 5732 10707 5786 10707 5785 10707 5732 10708 5785 10708 5731 10708 5733 10709 5787 10709 5786 10709 5733 10710 5786 10710 5732 10710 5734 10711 5788 10711 5787 10711 5734 10712 5787 10712 5733 10712 5735 10713 5789 10713 5788 10713 5735 10714 5788 10714 5734 10714 5736 10715 5790 10715 5789 10715 5736 10716 5789 10716 5735 10716 5737 10717 5791 10717 5790 10717 5737 10718 5790 10718 5736 10718 5738 10719 5792 10719 5791 10719 5738 10720 5791 10720 5737 10720 5739 10721 5793 10721 5792 10721 5739 10722 5792 10722 5738 10722 5741 10723 5794 10723 5793 10723 5741 10724 5793 10724 5739 10724 5743 10725 5795 10725 5794 10725 5743 10726 5794 10726 5741 10726 5722 10727 5776 10727 5760 10727 5722 10728 5760 10728 3664 10728 4050 10729 5029 10729 5774 10729 4050 10730 5774 10730 5773 10730 4048 10731 4050 10731 5773 10731 4048 10732 5773 10732 5772 10732 4046 10733 4048 10733 5772 10733 4046 10734 5772 10734 5771 10734 4044 10735 4046 10735 5771 10735 4044 10736 5771 10736 5770 10736 4042 10737 4044 10737 5770 10737 4042 10738 5770 10738 5769 10738 4040 10739 4042 10739 5769 10739 4040 10740 5769 10740 5768 10740 4038 10741 4040 10741 5768 10741 4038 10742 5768 10742 5767 10742 4036 10743 4038 10743 5767 10743 4036 10744 5767 10744 5766 10744 4034 10745 4036 10745 5766 10745 4034 10746 5766 10746 5765 10746 4032 10747 4034 10747 5765 10747 4032 10748 5765 10748 5764 10748 4030 10749 4032 10749 5764 10749 4030 10750 5764 10750 5763 10750 4028 10751 4030 10751 5763 10751 4028 10752 5763 10752 5762 10752 3661 10753 4028 10753 5762 10753 3661 10754 5762 10754 5761 10754 3661 10755 5761 10755 3644 10755 3661 10756 3644 10756 3643 10756 5775 10757 4741 10757 3641 10757 5775 10758 3641 10758 5776 10758 5777 10759 4740 10759 4741 10759 5777 10760 4741 10760 5775 10760 5778 10761 4739 10761 4740 10761 5778 10762 4740 10762 5777 10762 5779 10763 4738 10763 4739 10763 5779 10764 4739 10764 5778 10764 5780 10765 4737 10765 4738 10765 5780 10766 4738 10766 5779 10766 5781 10767 4736 10767 4737 10767 5781 10768 4737 10768 5780 10768 5782 10769 4735 10769 4736 10769 5782 10770 4736 10770 5781 10770 5783 10771 4734 10771 4735 10771 5783 10772 4735 10772 5782 10772 5784 10773 4733 10773 4734 10773 5784 10774 4734 10774 5783 10774 5785 10775 4732 10775 4733 10775 5785 10776 4733 10776 5784 10776 5786 10777 4731 10777 4732 10777 5786 10778 4732 10778 5785 10778 5787 10779 4730 10779 4731 10779 5787 10780 4731 10780 5786 10780 5788 10781 4729 10781 4730 10781 5788 10782 4730 10782 5787 10782 5789 10783 4728 10783 4729 10783 5789 10784 4729 10784 5788 10784 5790 10785 4727 10785 4728 10785 5790 10786 4728 10786 5789 10786 5791 10787 4726 10787 4727 10787 5791 10788 4727 10788 5790 10788 5792 10789 4725 10789 4726 10789 5792 10790 4726 10790 5791 10790 5793 10791 4724 10791 4725 10791 5793 10792 4725 10792 5792 10792 5794 10793 4723 10793 4724 10793 5794 10794 4724 10794 5793 10794 5795 10795 4722 10795 4723 10795 5795 10796 4723 10796 5794 10796 5776 10797 3641 10797 3644 10797 5776 10798 3644 10798 5760 10798 4024 10799 5796 10799 4025 10799 5797 10800 5718 10800 5798 10800 5798 10801 5799 10801 5720 10801 5720 10802 5714 10802 5800 10802 5801 10803 5802 10803 5797 10803 5720 10804 5800 10804 5801 10804 5797 10805 5798 10805 5720 10805 5720 10806 5801 10806 5797 10806 5803 10807 5744 10807 5746 10807 5746 10808 5714 10808 5804 10808 5804 4656 5805 4656 5803 4656 5746 10809 5804 10809 5803 10809 5744 10810 5806 10810 5745 10810 5714 10811 5746 10811 5774 10811 5714 10812 5774 10812 5029 10812 4003 10813 4023 10813 4022 10813 4003 10814 4022 10814 4004 10814 4022 10815 5745 10815 5807 10815 5807 10816 5796 10816 4024 10816 5807 10817 4024 10817 4022 10817 3895 10818 3894 10818 3898 10818 5808 10819 3726 10819 5742 10819 5808 10820 5742 10820 5809 10820 3727 10821 3726 10821 5808 10821 5344 10822 5810 10822 5811 10822 5812 10823 3922 10823 3925 10823 3925 10824 5344 10824 5811 10824 3925 10825 5811 10825 5812 10825 5813 10826 5814 10826 5316 10826 5316 10827 3924 10827 3923 10827 5316 10828 3923 10828 5813 10828 3926 10829 3929 10829 5316 10829 5316 10830 5814 10830 5815 10830 5316 10831 5815 10831 3926 10831 4179 10832 4182 10832 4181 10832 4180 10833 4179 10833 4181 10833 4401 10834 4403 10834 4433 10834 4432 10835 4401 10835 4433 10835 5809 10836 5742 10836 5740 10836 5809 10837 5740 10837 5816 10837 5816 10838 5740 10838 4743 10838 4743 10839 4742 10839 5817 10839 4743 10840 5817 10840 5816 10840 5817 10841 4742 10841 5818 10841 5818 10842 4742 10842 4745 10842 5818 10843 4745 10843 5819 10843 5819 10844 4745 10844 4747 10844 5819 10845 4747 10845 5820 10845 5820 10846 4747 10846 4749 10846 5820 10847 4749 10847 5821 10847 5821 10848 4749 10848 4751 10848 5821 10849 4751 10849 5822 10849 5822 10850 4751 10850 4753 10850 5822 10851 4753 10851 5823 10851 5823 10852 4753 10852 4755 10852 5823 10853 4755 10853 5824 10853 5824 10854 4755 10854 4757 10854 5824 10855 4757 10855 5825 10855 5825 10856 4757 10856 4759 10856 5825 10857 4759 10857 5826 10857 5826 10858 4759 10858 4761 10858 4761 10859 4778 10859 5827 10859 4761 10860 5827 10860 5826 10860 5827 10861 4778 10861 5828 10861 5829 10862 5828 10862 4778 10862 4778 10863 4779 10863 4787 10863 4778 10864 4787 10864 5829 10864 5830 10865 4818 10865 4817 10865 5830 10866 4817 10866 5831 10866 5041 10867 5040 10867 5832 10867 5041 10868 5832 10868 5833 10868 5040 10869 5046 10869 5834 10869 5040 10870 5834 10870 5832 10870 5046 10871 5051 10871 5058 10871 5058 10872 5835 10872 5834 10872 5058 10873 5834 10873 5046 10873 5058 10874 5836 10874 5835 10874 5058 10875 5057 10875 5837 10875 5058 10876 5837 10876 5836 10876 5057 10877 5064 10877 5072 10877 5072 10878 5838 10878 5837 10878 5072 10879 5837 10879 5057 10879 5072 10880 5839 10880 5838 10880 5072 10881 5071 10881 5840 10881 5072 10882 5840 10882 5839 10882 5841 10883 5840 10883 5071 10883 5071 10884 5079 10884 5088 10884 5071 10885 5088 10885 5841 10885 5841 10886 5088 10886 5090 10886 5841 10887 5090 10887 5842 10887 5090 10888 5843 10888 5842 10888 5830 10889 5843 10889 5090 10889 5090 10890 5089 10890 4818 10890 5090 10891 4818 10891 5830 10891 5344 10892 5345 10892 5844 10892 5344 10893 5844 10893 5810 10893 5844 10894 5345 10894 5346 10894 5346 10895 5354 10895 5845 10895 5346 10896 5845 10896 5844 10896 5354 10897 5846 10897 5845 10897 5847 10898 5846 10898 5354 10898 5354 10899 5355 10899 5362 10899 5354 10900 5362 10900 5847 10900 5362 10901 5848 10901 5847 10901 5848 10902 5362 10902 5363 10902 5363 10903 5369 10903 5849 10903 5363 10904 5849 10904 5848 10904 5369 10905 5850 10905 5849 10905 5851 10906 5850 10906 5369 10906 5369 10907 5370 10907 5375 10907 5369 10908 5375 10908 5851 10908 5375 10909 5852 10909 5851 10909 5852 10910 5375 10910 5376 10910 5376 10911 5408 10911 5853 10911 5376 10912 5853 10912 5852 10912 5853 10913 5408 10913 5041 10913 5853 10914 5041 10914 5833 10914 5854 10915 5855 10915 5856 10915 5707 10916 5856 10916 5855 10916 5707 10917 5855 10917 5857 10917 5858 10918 5411 10918 5414 10918 5414 10919 5707 10919 5857 10919 5414 10920 5857 10920 5858 10920 5859 10921 5411 10921 5858 10921 5860 10922 5423 10922 5412 10922 5412 10923 5411 10923 5859 10923 5412 10924 5859 10924 5860 10924 5861 10925 5423 10925 5860 10925 5862 10926 5424 10926 5423 10926 5862 10927 5423 10927 5861 10927 5863 10928 5428 10928 5425 10928 5425 10929 5424 10929 5862 10929 5425 10930 5862 10930 5863 10930 5864 10931 5428 10931 5863 10931 5865 10932 5431 10932 5429 10932 5429 10933 5428 10933 5864 10933 5429 10934 5864 10934 5865 10934 5866 10935 5433 10935 5431 10935 5866 10936 5431 10936 5865 10936 5867 10937 5435 10937 5433 10937 5867 10938 5433 10938 5866 10938 5868 10939 5435 10939 5867 10939 5869 10940 5437 10940 5436 10940 5436 10941 5435 10941 5868 10941 5436 10942 5868 10942 5869 10942 4817 10943 5870 10943 5831 10943 5871 10944 5437 10944 5869 10944 5872 10945 4787 10945 4788 10945 4788 10946 5437 10946 5871 10946 4788 10947 5871 10947 5872 10947 5870 10948 4817 10948 4815 10948 4815 10949 5439 10949 5873 10949 4815 10950 5873 10950 5870 10950 5873 10951 5439 10951 5441 10951 5873 10952 5441 10952 5874 10952 5441 10953 5875 10953 5874 10953 5829 10954 4787 10954 5872 10954 5876 10955 5875 10955 5441 10955 5441 10956 5440 10956 5445 10956 5441 10957 5445 10957 5876 10957 5876 10958 5445 10958 5447 10958 5876 10959 5447 10959 5877 10959 5877 10960 5447 10960 5449 10960 5877 10961 5449 10961 5878 10961 5449 4656 5879 4656 5878 4656 5880 10962 5879 10962 5449 10962 5449 10963 5448 10963 5456 10963 5449 10964 5456 10964 5880 10964 5880 10965 5456 10965 5458 10965 5880 10966 5458 10966 5881 10966 5458 10967 5882 10967 5881 10967 5883 10968 5882 10968 5458 10968 5458 10969 5457 10969 5467 10969 5458 10970 5467 10970 5883 10970 5467 10971 5884 10971 5883 10971 5885 10972 5884 10972 5467 10972 5467 10973 5466 10973 5477 10973 5467 10974 5477 10974 5885 10974 5477 10975 5886 10975 5885 10975 5477 10976 5476 10976 5887 10976 5477 10977 5887 10977 5886 10977 5476 10978 5486 10978 5888 10978 5476 10979 5888 10979 5887 10979 5888 10980 5486 10980 5495 10980 5888 10981 5495 10981 5889 10981 5494 10982 5503 10982 5890 10982 5890 10983 5891 10983 5495 10983 5890 10984 5495 10984 5494 10984 5495 10985 5891 10985 5889 10985 5503 10986 5511 10986 5892 10986 5503 10987 5892 10987 5890 10987 5511 10988 5519 10988 5893 10988 5511 10989 5893 10989 5892 10989 5519 10990 5527 10990 5894 10990 5519 10991 5894 10991 5893 10991 5895 10992 5896 10992 5652 10992 5652 10993 5643 10993 5644 10993 5652 10994 5644 10994 5895 10994 5644 10995 3926 10995 5815 10995 5644 10996 5815 10996 5895 10996 5897 10997 5898 10997 5659 10997 5659 10998 5651 10998 5652 10998 5659 10999 5652 10999 5897 10999 5897 11000 5652 11000 5896 11000 3923 11001 5899 11001 5813 11001 5900 11002 5664 11002 5657 11002 5657 11003 5658 11003 5901 11003 5657 11004 5901 11004 5900 11004 5901 11005 5658 11005 5659 11005 5901 11006 5659 11006 5902 11006 5898 11007 5902 11007 5659 11007 3923 11008 3922 11008 5903 11008 3923 11009 5903 11009 5899 11009 5904 11010 5667 11010 5662 11010 5662 11011 5663 11011 5905 11011 5662 11012 5905 11012 5904 11012 5663 11013 5664 11013 5906 11013 5663 11014 5906 11014 5905 11014 5664 11015 5900 11015 5906 11015 3922 11016 5812 11016 5903 11016 5907 11017 5908 11017 5669 11017 5669 11018 5666 11018 5667 11018 5669 11019 5667 11019 5907 11019 5904 11020 5907 11020 5667 11020 5909 11021 5671 11021 5669 11021 5909 11022 5669 11022 5908 11022 5910 11023 5676 11023 5673 11023 5673 11024 5671 11024 5909 11024 5673 11025 5909 11025 5910 11025 5910 11026 5911 11026 5676 11026 5912 11027 5703 11027 5677 11027 5677 11028 5676 11028 5911 11028 5677 11029 5911 11029 5912 11029 5913 11030 5705 11030 5703 11030 5913 11031 5703 11031 5912 11031 5913 11032 5914 11032 5705 11032 5691 11033 5690 11033 5915 11033 5691 11034 5915 11034 5711 11034 5711 11035 5915 11035 5916 11035 5706 11036 5705 11036 5914 11036 5914 11037 5917 11037 5710 11037 5914 11038 5710 11038 5706 11038 5918 11039 5708 11039 5710 11039 5918 11040 5710 11040 5917 11040 5919 11041 5709 11041 5708 11041 5919 11042 5708 11042 5918 11042 5709 11043 5919 11043 5920 11043 5854 11044 5856 11044 5921 11044 5921 11045 5856 11045 5707 11045 5707 11046 5709 11046 5920 11046 5707 11047 5920 11047 5921 11047 5527 11048 5711 11048 5916 11048 5527 11049 5916 11049 5894 11049 4426 11050 4451 11050 4449 11050 4430 11051 4428 11051 4426 11051 4426 11052 4449 11052 4430 11052 4449 11053 4431 11053 4430 11053 5814 11054 5813 11054 5922 11054 5814 11055 5922 11055 5923 11055 5815 11056 5814 11056 5923 11056 5815 11057 5923 11057 5924 11057 5895 11058 5815 11058 5924 11058 5895 11059 5924 11059 5925 11059 5926 11060 5897 11060 5895 11060 5926 11061 5895 11061 5925 11061 5898 11062 5897 11062 5926 11062 5898 11063 5926 11063 5927 11063 5922 11064 3923 11064 5813 11064 5895 11065 5897 11065 5896 11065 5899 11066 5903 11066 5928 11066 5899 11067 5928 11067 5922 11067 5812 64 5811 64 5903 64 5928 11068 5903 11068 5811 11068 5928 11069 5811 11069 5929 11069 5929 11070 5811 11070 5810 11070 5810 11071 5844 11071 5845 11071 5845 11072 5930 11072 5929 11072 5810 11073 5845 11073 5929 11073 5930 11074 5845 11074 5846 11074 5846 11075 5847 11075 5931 11075 5846 11076 5931 11076 5930 11076 5847 64 5848 64 5849 64 5847 11077 5849 11077 5931 11077 5932 11078 5931 11078 5849 11078 5932 11079 5850 11079 5851 11079 5851 11080 5933 11080 5934 11080 5935 11081 5690 11081 5932 11081 5851 11082 5934 11082 5935 11082 5851 11083 5935 11083 5932 11083 5849 11084 5850 11084 5932 11084 5843 11085 5933 11085 5842 11085 5878 11086 5934 11086 5877 11086 5935 11087 5934 11087 5879 11087 5933 11088 5851 11088 5853 11088 5833 11089 5832 11089 5834 11089 5834 11090 5933 11090 5853 11090 5834 11091 5853 11091 5833 11091 5839 11092 5840 11092 5933 11092 5933 11093 5834 11093 5836 11093 5836 11094 5838 11094 5839 11094 5839 11095 5933 11095 5836 11095 5841 11096 5842 11096 5933 11096 5841 11097 5933 11097 5840 11097 5934 11098 5933 11098 5843 11098 5934 11099 5843 11099 5877 11099 5886 11100 5878 11100 5935 11100 5888 64 5889 64 5891 64 5891 64 5890 64 5892 64 5892 11101 5893 11101 5894 11101 5894 11102 5916 11102 5915 11102 5915 11103 5690 11103 5935 11103 5935 11104 5886 11104 5887 11104 5888 64 5891 64 5892 64 5935 11105 5887 11105 5888 11105 5894 11106 5915 11106 5935 11106 5888 11107 5892 11107 5894 11107 5888 11108 5894 11108 5935 11108 5900 583 5901 583 5902 583 5902 11109 5898 11109 5927 11109 5927 11110 5936 11110 5904 11110 5904 583 5905 583 5906 583 5900 583 5902 583 5927 583 5904 11111 5906 11111 5900 11111 5900 11112 5927 11112 5904 11112 5908 583 5904 583 5936 583 5908 583 5936 583 5909 583 5909 583 5936 583 5937 583 5909 11113 5869 11113 5911 11113 5909 11114 5937 11114 5869 11114 5867 11115 5866 11115 5914 11115 5913 583 5912 583 5911 583 5867 11116 5914 11116 5913 11116 5869 583 5868 583 5867 583 5913 583 5911 583 5869 583 5913 11117 5869 11117 5867 11117 5863 583 5862 583 5920 583 5920 583 5919 583 5918 583 5918 583 5917 583 5914 583 5914 11118 5866 11118 5864 11118 5864 583 5863 583 5920 583 5920 11119 5918 11119 5914 11119 5920 583 5914 583 5864 583 5859 583 5858 583 5920 583 5920 11120 5862 11120 5860 11120 5920 11121 5860 11121 5859 11121 5854 583 5920 583 5858 583 5869 583 5937 583 5819 583 5713 11122 5712 11122 5798 11122 5713 11123 5798 11123 5718 11123 5712 11124 5938 11124 5799 11124 5712 11125 5799 11125 5798 11125 5938 11126 5719 11126 5720 11126 5938 11127 5720 11127 5799 11127 5715 11128 5719 11128 5028 11128 5715 11129 5028 11129 5029 11129 5719 11130 5938 11130 5031 11130 5719 11131 5031 11131 5028 11131 5938 11132 5712 11132 5030 11132 5938 11133 5030 11133 5031 11133 5939 11134 5802 11134 5801 11134 5801 11135 5940 11135 5941 11135 5801 11136 5941 11136 5939 11136 5942 11137 5797 11137 5802 11137 5942 11138 5802 11138 5939 11138 5941 11139 5940 11139 5943 11139 5941 11140 5943 11140 5939 11140 5942 11141 5939 11141 5943 11141 5942 11142 5943 11142 5944 11142 5940 11143 5944 11143 5714 11143 5714 11144 5944 11144 5806 11144 5806 11145 5945 11145 5946 11145 5946 11146 5947 11146 5714 11146 5806 11147 5946 11147 5714 11147 5714 11148 5940 11148 5801 11148 5714 11149 5801 11149 5800 11149 5744 11150 5806 11150 5948 11150 5806 11151 5949 11151 5948 11151 5949 11152 5950 11152 5948 11152 5950 11153 5951 11153 5948 11153 5951 11154 5714 11154 5948 11154 5714 11155 5804 11155 5948 11155 5804 11156 5805 11156 5948 11156 5805 11157 5803 11157 5948 11157 5803 11158 5744 11158 5948 11158 5806 11159 5745 11159 5952 11159 5806 11160 5952 11160 5953 11160 5714 11161 5948 11161 5954 11161 5714 11162 5954 11162 5955 11162 5956 11163 5953 11163 5954 11163 5953 11164 5806 11164 5948 11164 5953 11165 5948 11165 5954 11165

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/palm/palm_E3M5_scaled.dae b/URDFs/sr_description/meshes/components/palm/palm_E3M5_scaled.dae new file mode 100644 index 0000000..5f08d82 --- /dev/null +++ b/URDFs/sr_description/meshes/components/palm/palm_E3M5_scaled.dae @@ -0,0 +1,153 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:32:53 + 2025-02-20T09:32:53 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -2.31886 3.11933 88.42472 -2.31886 5.63812 90.39955 -2.86901 3.312 88.37461 -2.86901 5.74386 90.32435 -1.99945 5.53833 89.58848 -1.99944 4.28706 88.5514 -4.23984 10.89921 90.28441 -4.50802 10.95645 89.19076 -6.2616 11.1753 88.8843 -5.23617 7.94142 90.03388 -6.04362 7.94142 89.22799 -4.23845 5.63631 88.40637 -3.48421 10.27552 97.62239 -3.92405 9.96326 98.56784 -2.62062 9.46742 96.43927 -4.00144 10.43204 98.33806 -3.42962 8.64119 95.29342 -2.77315 8.93963 95.8138 -3.29574 9.2523 97.00844 -2.62016 8.73646 95.12654 -4.25756 11.04698 96.20256 -4.15142 11.04698 95.04393 -5.75123 11.49697 95.45497 -5.99619 11.49697 96.64929 -4.60233 11.04699 97.44501 -6.50894 11.49697 97.75499 -5.2387 11.04699 98.70365 -2.4043 8.83116 95.13356 -2.78691 9.19201 96.43332 -2.25253 9.009303 95.10453 -2.19861 9.23126 95.04592 -2.72672 9.94482 96.26662 -2.2479 9.44767 94.97078 -5.28283 10.68463 99.7013 -5.9089 10.75973 100.2209 -5.71777 10.27446 100.3477 -6.03239 9.87593 100.1751 -5.43032 9.8037 99.67538 -4.79349 9.69696 99.05484 -4.62052 10.57362 99.05593 -4.19838 9.560873 98.36477 -3.70107 9.41038 97.67668 -3.06268 10.11112 96.92743 -2.72672 10.02494 95.04329 -4.08456 8.54095 95.21244 -7.70988 9.10508 98.62049 -6.18704 11.04698 99.873 -2.72672 9.955223 93.81955 -3.31068 10.4765 94.44256 -4.62794 7.94142 90.84272 -4.18119 7.94142 91.62484 -3.86182 7.94142 92.36641 -3.64156 7.94142 93.06499 -2.86899 7.19214 93.23298 -1.99944 7.99697 92.1724 -1.99944 7.30184 92.4242 -1.99944 6.94656 91.57982 -1.99944 6.38827 90.62459 -1.99944 8.25571 93.05318 -1.99944 7.51917 93.15264 -3.96819 10.81415 91.43007 -6.88093 11.39697 89.68384 -5.65019 11.34554 91.02043 -4.49718 11.01932 91.70684 -3.71003 10.70574 92.56484 -4.65287 11.17864 92.9042 -5.12373 11.27726 91.90458 -3.48535 10.58686 93.59964 -4.22323 11.04697 94.01065 -2.44319 8.56278 94.71521 -3.05339 8.50667 94.93193 -2.66969 8.34255 94.60556 -2.07694 8.79775 92.93055 -2.25794 9.21523 92.83738 -2.50042 9.656763 93.29489 -2.19144 9.3299 94.73648 -2.19702 7.58718 93.89461 -2.00608 7.87464 93.62246 -2.32404 7.07942 93.26065 -5.97059 11.49697 93.17299 -5.78696 11.49697 94.23915 -6.20346 11.49697 92.22731 -6.87369 8.496973 90.33946 -6.23881 8.496973 90.99005 -5.75942 8.496973 91.64044 -5.40616 8.496973 92.26857 -5.15264 8.496973 92.86425 -4.97702 8.496973 93.42589 -2.0713 8.649621 92.46511 -3.27289 7.83903 94.26452 -3.50552 7.94157 93.72605 -2.62331 7.53031 93.96105 -2.30936 8.16196 94.33181 -4.41073 8.496973 95.04093 -4.62775 8.49544 94.56347 -4.86253 8.496973 93.95772 -2.2273 8.656373 94.6345 -2.05462 8.88449 94.20365 -2.00608 8.38057 93.92615 -2.01864 8.653963 94.05004 -2.00608 8.3286 93.39334 -18.41133 1.43357 87.00081 -19.12988 1.27291 87.70231 -19.12988 -0.003029823 87.59163 -18.84514 -0.003029823 87.29075 -18.54927 -0.003029823 87.00081 -19.12988 2.37195 87.98259 -18.00349 2.81535 87.00081 -17.3473 4.08411 87.00081 -18.66365 4.10292 88.26278 -19.12988 4.09936 88.83101 -16.49944 5.99697 87.00081 -17.8421 6.16047 88.98506 -15.99944 6.96932 88.11705 -15.99944 7.74294 89.00081 -16.49944 7.94142 89.74383 -9.94944 7.47344 87.00081 -8.57618 7.14735 87.00081 -9.94944 7.94142 87.46534 -8.391242 7.94142 87.85357 -7.30655 6.582 87.00083 -7.08771 7.94142 88.47516 -6.1286 5.76542 87.00083 -5.04713 4.64133 87.00083 -4.06877 2.916 87.00083 -3.63364 1.65375 87.00083 -3.44961 -0.003029823 87.00083 -3.15375 -0.003029823 87.29077 -2.86901 -0.003029823 87.59163 -2.86901 1.2735 87.70243 -2.86901 2.37288 87.98291 -15.99944 8.496973 87.00081 -12.03442 8.496973 87.00081 -15.99944 8.496973 89.00081 -4.76363 10.98769 88.17483 -4.99944 10.99697 87.25485 -13.90792 11.39697 88.93673 -16.99944 10.99697 87.25485 -15.73728 11.26217 88.8843 -15.16828 10.99697 86.13398 -12.50619 11.39697 88.44628 -13.13533 10.99697 85.43849 -10.99994 11.39697 88.27532 -10.99945 10.99697 85.20285 -9.49355 11.39697 88.44607 -8.863593 10.99697 85.43849 -6.83064 10.99697 86.13395 -8.09143 11.39697 88.9365 -17.23631 10.9876 88.179 -17.4921 10.95624 89.19575 -19.68002 3.11935 88.42472 -19.99944 4.28585 88.55059 -19.99944 2.47985 87.66356 -19.56388 -0.003029823 87.75068 -19.99944 1.33074 87.37055 -19.99944 -0.003029823 87.25485 -19.94282 -0.003029823 87.48596 -19.78578 -0.003029823 87.66474 -19.3274 -0.003029823 87.72432 -1.99945 1.33136 87.37066 -2.435 -0.003029823 87.75068 -2.2131 -0.003029823 87.66474 -2.05606 -0.003029823 87.48597 -1.99944 -0.003029823 87.25486 -1.99945 2.48084 87.6639 -2.67149 -0.003029823 87.72432 -10.99943 11.49528 88.98594 -9.94944 8.496973 88.86506 -8.718502 8.496973 89.20881 -9.96445 8.496973 87.00081 -19.12987 -8.00303 87.59163 -18.90861 -9.0346 87.35697 -18.36907 -9.82743 86.83525 -18.54927 -4.00303 87.00083 -17.61403 -10.3084 86.21868 -16.91593 -4.00303 85.72747 -16.73857 -10.50303 85.61666 -15.6181 -10.50303 85.01744 -15.88833 -9.00303 85.14695 -15.52103 -9.4878 84.9731 -15.88833 -6.00303 85.14695 -15.41294 -5.67444 84.92507 -15.07323 -5.46536 84.78298 -15.06578 -4.00303 84.78002 -14.74852 -5.29607 84.65947 -15.0433 -10.02226 84.77111 -14.44095 -10.49866 84.5542 -14.27803 -5.11393 84.50078 -13.5644 -5.00303 84.30406 -13.06992 -4.00303 84.19744 -11.8618 -5.00303 84.03469 -10.99943 -4.00303 84.00083 -10.13707 -5.00303 84.03469 -8.92895 -4.00303 84.19744 -8.434473 -5.00303 84.30406 -7.75159 -5.10488 84.49124 -7.14236 -5.34857 84.69922 -6.9331 -4.00303 84.78002 -6.60089 -5.66467 84.91852 -5.26031 -10.50303 85.61666 -6.11055 -6.00303 85.14695 -6.11055 -9.00303 85.14695 -6.38052 -10.50303 85.01755 -5.08295 -4.00303 85.72747 -4.31402 -10.5013 86.22204 -3.64806 -9.84937 86.81808 -3.44961 -4.00303 87.00083 -3.09106 -9.0365 87.35614 -2.86901 -8.00303 87.59163 -13.03604 -5.00303 84.67029 -8.96283 -5.00303 84.67029 -12.5984 -5.00303 85.13996 -9.40047 -5.00303 85.13996 -12.27033 -5.00303 85.69278 -9.72854 -5.00303 85.69278 -12.06769 -5.00303 86.30226 -9.93118 -5.00303 86.30226 -11.99943 -5.00303 86.93856 -9.99943 -5.00303 86.93856 -10.99943 -10.00303 85.00083 -10.99943 -10.00303 85.40252 -12.66555 -10.00303 85.05361 -12.38011 -10.00303 85.47597 -10.99943 -10.00303 85.74328 -12.17045 -10.00303 85.94014 -10.99943 -10.00303 86.01088 -9.95637 -10.00303 86.43206 -12.04251 -10.00303 86.43202 -9.99943 -10.00303 86.93856 -11.99943 -10.00303 86.93856 -6.58866 -6.00303 84.98121 -6.58878 -9.00303 84.98118 -7.0945 -6.00303 84.94082 -7.09457 -9.00303 84.94084 -7.59312 -6.00303 85.02871 -7.59319 -9.00303 85.02874 -8.05351 -6.00303 85.23889 -8.05357 -9.00303 85.23892 -8.4464 -6.00303 85.55789 -8.44646 -9.00303 85.55793 -8.74675 -6.00303 85.96547 -8.74683 -9.00303 85.96562 -8.9354 -6.00303 86.43654 -8.93547 -9.00303 86.43677 -8.99943 -6.00303 86.93856 -8.99943 -9.00303 86.93856 -15.41021 -9.00303 84.98121 -15.41021 -6.00303 84.98121 -14.90438 -9.00303 84.94082 -14.90438 -6.00303 84.94082 -14.40575 -9.00303 85.02871 -14.40575 -6.00303 85.02871 -13.94536 -9.00303 85.23889 -13.94536 -6.00303 85.23889 -13.55247 -9.00303 85.55789 -13.55247 -6.00303 85.55789 -13.25213 -9.00303 85.96547 -13.25213 -6.00303 85.96547 -13.06347 -9.00303 86.43654 -13.06347 -6.00303 86.43654 -12.99944 -9.00303 86.93856 -12.99944 -6.00303 86.93856 -13.71113 -5.29592 85.04183 -12.97319 -5.29592 85.86539 -12.70656 -5.29593 86.93856 -12.92332 -5.62036 86.93856 -12.38214 -5.07915 86.93856 -7.25136 -5.30497 84.66201 -8.28282 -5.29592 85.03849 -9.02428 -5.29592 85.86277 -9.61675 -5.07915 86.93856 -9.29233 -5.29592 86.93856 -9.07556 -5.62034 86.93856 -15.20861 -9.24626 84.91934 -14.45941 -9.511981 84.86864 -13.92234 -9.70494 84.92412 -13.03527 -9.71013 85.7556 -12.97082 -9.982002 85.01441 -13.25342 -9.92569 84.99267 -13.5218 -9.845002 84.9712 -12.38212 -9.92691 86.93856 -12.70654 -9.71013 86.93856 -12.92332 -9.38571 86.93856 -19.32739 -8.00303 87.72432 -19.56388 -8.00303 87.75068 -19.78578 -8.00303 87.66474 -19.94282 -8.00303 87.48597 -19.99944 -8.00303 87.25486 -2.67151 -8.00302 87.72431 -2.43502 -8.00302 87.7507 -2.21312 -8.00302 87.66475 -2.05606 -8.00302 87.48597 -1.99944 -8.00303 87.25486 -5.22536 -10.75303 85.55951 -3.52903 -9.98157 86.87934 -2.86596 -9.193263 87.46949 -4.23798 -10.62444 86.18592 -3.30825 -10.1712 86.83069 -2.61141 -9.29184 87.43207 -5.13856 -10.9194 85.41758 -3.15324 -10.23448 86.72433 -2.31082 -9.29155 87.14128 -4.99944 -11.00303 85.19011 -4.00331 -10.79866 85.9662 -2.97677 -10.21861 86.44617 -3.91117 -10.77342 85.81321 -2.27803 -9.24322 87.00869 -16.98495 -10.99559 85.21382 -15.42694 -11.00303 84.38729 -16.869 -10.93604 85.40339 -14.52264 -10.85658 84.42583 -16.78412 -10.77336 85.54217 -13.76685 -11.00303 83.83877 -12.04944 -10.85241 83.89984 -10.99943 -10.6697 84.02233 -13.47455 -10.61703 84.28743 -10.99943 -10.97928 83.70178 -10.99943 -11.00303 83.54885 -8.2317 -11.00303 83.83885 -9.94944 -10.85241 83.89984 -7.47623 -10.85658 84.42583 -6.57136 -11.00303 84.38752 -19.08425 -9.16383 87.46038 -17.71125 -10.54603 86.2146 -18.57539 -10.08604 86.87477 -19.28141 -9.25626 87.46589 -17.83893 -10.7081 86.13066 -18.7582 -10.2036 86.79393 -19.46508 -9.30571 87.39328 -17.99289 -10.79692 85.97328 -18.92981 -10.24095 86.64248 -19.63477 -9.30826 87.23494 -18.09775 -10.76947 85.81949 -19.02166 -10.21902 86.44584 -19.72185 -9.240942 87.00955 -10.99943 -10.40319 84.16567 -12.78643 -10.32127 84.33208 -10.99943 -10.18686 84.38906 -12.73147 -10.1721 84.6602 -10.99943 -10.04902 84.66846 -6.78915 -9.24626 84.91934 -6.47673 -9.4878 84.9731 -6.95446 -10.02226 84.77111 -7.53835 -9.511981 84.86864 -7.55681 -10.49866 84.5542 -8.07543 -9.70494 84.92412 -8.47597 -9.845002 84.9712 -8.523221 -10.61703 84.28743 -8.74434 -9.92569 84.99267 -9.02695 -9.982002 85.01441 -9.266303 -10.1721 84.6602 -9.21134 -10.32127 84.33208 -9.33221 -10.00303 85.05361 -9.07556 -9.38571 86.93856 -9.29233 -9.71013 86.93856 -8.9625 -9.71013 85.7556 -9.61675 -9.92691 86.93856 -9.82731 -10.00303 85.94014 -9.61765 -10.00303 85.47597 -9.99943 -5.00303 93.26877 -11.99943 -5.00303 93.26877 -9.76705 -5.00303 94.09375 -11.62292 -5.00303 94.21898 -11.22196 -5.00303 94.0259 -10.77691 -5.00303 94.0259 -10.37594 -5.00303 94.21898 -12.36546 -5.07242 94.00083 -9.72595 -5.02203 94.5056 -11.9004 -5.00303 94.56694 -10.09847 -5.00303 94.56694 -12.16913 -5.00303 94.92147 -9.82974 -5.00303 94.92148 -11.99943 -5.00303 95.00083 -9.99943 -5.00303 95.00083 -9.91382 -5.00303 95.44345 -12.07844 -5.00303 95.45932 -10.13171 -5.00303 95.49787 -11.86516 -5.00303 95.50135 -10.49671 -5.00303 95.86528 -10.23375 -5.00303 95.88864 -11.75377 -5.00303 95.8983 -11.49825 -5.00303 95.86753 -10.99721 -5.00303 96.00081 -10.71798 -5.00303 96.13891 -11.2647 -5.00303 96.1428 -8.99943 -9.00303 94.00083 -8.99906 -6.00303 94.00081 -12.99944 -9.00303 94.00083 -12.99944 -6.00303 93.96101 -12.69802 -5.2875 94.00083 -12.92101 -5.61481 94.00083 -12.9945 -6.00303 94.1412 -9.5678 -5.1104 94.23588 -9.30086 -5.28749 94.00083 -9.07786 -5.61481 94.00083 -9.13342 -9.50305 94.00083 -9.499463 -9.869071 94.00083 -9.99943 -10.00303 94.00083 -11.99943 -10.00303 94.00083 -12.49944 -9.86905 94.00083 -12.86546 -9.50303 94.00083 -10.99943 -5.00303 95.00083 -12.73674 -5.33823 94.1848 -12.92749 -5.64578 94.15258 -9.26214 -5.33822 94.18481 -9.071393 -5.64578 94.15258 -12.81211 -5.27567 95.41165 -13.10184 -5.9457 95.54119 -12.15939 -5.27567 96.45308 -12.32968 -5.9457 96.71621 -10.99944 -5.9457 97.17156 -10.99944 -5.27567 96.85948 -9.66919 -5.9457 96.71621 -9.83949 -5.27567 96.45308 -8.89703 -5.9457 95.54119 -9.18676 -5.27567 95.41165 -9.99943 -10.00303 95.50083 -11.99943 -10.00303 95.50083 -8.89703 -8.9457 95.54119 -13.10184 -8.9457 95.54119 -12.32968 -8.9457 96.71621 -10.99944 -8.9457 97.17156 -9.66919 -8.9457 96.71621 -19.12988 5.2965 89.82287 -16.49944 8.496973 92.08535 -15.11795 11.39697 89.68384 -17.75948 10.8991 90.28621 -19.68002 5.63813 90.39956 -13.73816 11.49697 89.71026 -12.6984 11.49697 89.29082 -18.50646 10.59098 93.56623 -18.68239 10.48045 94.41388 -17.3459 11.17867 92.90397 -17.50171 11.01932 91.70685 -16.34875 11.34554 91.02054 -19.62539 9.636343 95.45105 -19.80692 9.23126 95.04592 -19.3814 9.77928 96.36007 -19.75098 9.44767 94.97078 -19.1299 7.19214 93.23297 -18.73264 7.83903 94.26452 -19.38222 7.53031 93.96105 -19.69616 8.16196 94.33181 -19.32961 8.34236 94.60522 -18.56921 8.64121 95.29347 -17.92096 8.54095 95.21244 -17.37778 8.49544 94.56346 -19.55777 8.55985 94.71041 -19.38537 8.73646 95.12652 -19.753 9.009303 95.10453 -19.77822 8.656373 94.6345 -19.95091 8.88449 94.20365 -19.82544 9.29202 94.66218 -19.85573 8.20532 94.23194 -14.1751 8.6999 97.51353 -10.99944 8.55728 98.13482 -14.289 9.105072 98.62049 -17.11091 7.94142 90.46917 -17.5802 7.94142 91.18251 -17.93302 7.94142 91.86851 -16.02825 11.49697 93.17279 -17.77565 11.08882 94.01065 -16.21191 11.49697 94.23915 -15.79537 11.49697 92.22714 -16.87505 11.27728 91.90441 -15.49461 11.49697 91.41564 -15.11051 11.49697 90.7632 -14.64758 11.49697 90.29109 -14.60171 11.04698 100.825 -13.23189 11.04697 101.4749 -13.7854 11.49697 99.47166 -13.27012 11.48797 100.0102 -15.80674 11.04699 99.87802 -14.73763 11.49697 98.71241 -16.75669 11.04699 98.70907 -15.48995 11.49697 97.75497 -17.3948 11.04699 97.4496 -16.0027 11.49697 96.64927 -17.74075 11.04698 96.20579 -16.24766 11.49697 95.45497 -17.84745 11.04698 95.04558 -13.59535 9.968563 101.5481 -14.10851 10.3817 101.6682 -14.86599 9.951333 100.9168 -12.05994 9.968563 101.9637 -12.06741 10.38028 102.2918 -13.63363 10.85606 101.6447 -19.02626 9.09237 96.37292 -18.21762 9.4337 97.78476 -19.40844 9.572001 96.42621 -18.07484 9.96326 98.56782 -19.27217 9.94482 96.26661 -18.64199 10.22999 97.42498 -18.22036 10.36962 98.04489 -17.71625 10.50161 98.68008 -16.28111 10.27446 100.3477 -16.96824 9.74083 99.29841 -16.5328 10.70933 99.86162 -15.84827 9.88731 100.2647 -15.96703 10.77157 100.3141 -14.94548 10.83814 100.9923 -19.45986 9.80788 95.89679 -19.56388 7.03771 93.27092 -19.80851 7.58718 93.8946 -19.99944 7.87464 93.62245 -19.99944 7.42452 92.80275 -19.99944 5.53739 89.58751 -19.12988 6.30681 91.12614 -19.99944 7.99697 92.1724 -19.99944 8.3286 93.39332 -19.92759 8.649621 92.46511 -19.74095 9.21523 92.83737 -19.49847 9.656763 93.29487 -19.27217 9.95521 93.81954 -19.27217 10.01127 94.47571 -19.27217 10.0246 95.09308 -19.27217 10.00166 95.68509 -14.33799 9.49194 99.7704 -13.54441 9.65113 100.6214 -10.99943 11.49697 95.12439 -18.28336 10.70835 92.54011 -17.95351 10.83841 91.10441 -19.0442 10.19218 94.41816 -10.99944 8.496973 95.00081 -7.69372 8.496973 89.72613 -6.88885 11.49697 90.76256 -7.35129 11.49697 90.29109 -6.50431 11.49697 91.41555 -8.26082 11.49697 89.71022 -9.300601 11.49697 89.29078 -7.39114 11.04698 100.8213 -7.00228 10.83605 100.9621 -8.76036 11.04697 101.4726 -8.42268 10.85606 101.6672 -8.9534 10.85606 101.8487 -10.23691 11.04697 101.8064 -10.17666 10.85606 102.1003 -11.75499 11.04697 101.8072 -9.69498 9.65113 101.0324 -8.45173 9.65113 100.6214 -8.98314 9.968563 101.7492 -10.18862 9.968563 101.9972 -10.99948 9.65113 101.1718 -7.66148 9.492383 99.77202 -7.55751 9.96396 101.1531 -7.89038 10.3817 101.6682 -9.93147 10.38028 102.2918 -11.4601 10.85606 102.133 -10.99944 11.48797 100.5008 -8.21348 11.49697 99.47166 -8.72876 11.48797 100.0102 -7.26126 11.49697 98.71241 -9.86098 11.48797 100.3768 -12.16097 11.48797 100.3768 -12.65105 10.85606 101.9544 -12.30398 9.65113 101.0324 19.68114 3.11933 92.42472 19.68114 5.63812 94.39955 19.13099 3.312 92.37461 19.13099 5.74386 94.32435 20.00056 4.28707 92.55139 17.76016 10.89921 94.28441 17.49198 10.95645 93.19076 15.7384 11.1753 92.8843 16.76383 7.94142 94.03388 15.95638 7.94142 93.22799 17.76155 5.63631 92.40637 18.51579 10.27552 101.6224 18.07596 9.96326 102.5678 19.37938 9.46742 100.4393 17.99856 10.43204 102.3381 18.57038 8.64119 99.29342 19.22685 8.93964 99.8138 18.70426 9.2523 101.0084 19.37984 8.73646 99.12654 17.74244 11.04698 100.2026 17.84858 11.04698 99.04393 16.24877 11.49697 99.45497 16.00381 11.49697 100.6493 17.39767 11.04699 101.445 15.49106 11.49697 101.755 16.7613 11.04699 102.7036 19.59571 8.83116 99.13356 19.21309 9.19201 100.4333 19.74747 9.009303 99.10453 19.80139 9.23127 99.04592 19.27328 9.94482 100.2666 19.7521 9.44767 98.97078 16.71717 10.68463 103.7013 16.0911 10.75973 104.2209 16.28223 10.27446 104.3477 15.96762 9.87593 104.1751 16.56968 9.8037 103.6754 17.20651 9.69696 103.0548 17.37948 10.57362 103.0559 17.80162 9.560873 102.3648 18.29893 9.41038 101.6767 18.93732 10.11113 100.9274 19.27329 10.02495 99.04329 17.91544 8.54095 99.21244 14.29012 9.10508 102.6205 15.81296 11.04698 103.873 19.27328 9.955223 97.81954 18.68931 10.4765 98.44255 17.37206 7.94142 94.84272 17.81881 7.94142 95.62484 18.13819 7.94142 96.36641 18.35844 7.94142 97.06499 19.13101 7.19214 97.23298 20.00056 7.99697 96.1724 20.00056 7.4246 96.80301 20.00056 6.94656 95.57982 20.00056 6.38827 94.62459 20.00056 8.25571 97.05318 20.00056 7.58539 97.30754 18.03181 10.81416 95.43007 15.11907 11.39697 93.68384 16.34981 11.34554 95.02043 17.50282 11.01933 95.70684 18.28996 10.70574 96.56483 17.34713 11.17865 96.9042 16.87627 11.27726 95.90458 18.51465 10.58686 97.59963 17.77677 11.04697 98.01065 19.55681 8.56278 98.71521 18.94661 8.50667 98.93193 19.33031 8.34255 98.60556 19.92306 8.79775 96.93055 19.74206 9.21523 96.83737 19.49958 9.656763 97.29487 19.80856 9.3299 98.73648 19.99392 7.87464 97.62246 19.80298 7.58718 97.89461 19.67596 7.07942 97.26065 16.02941 11.49697 97.17299 16.21304 11.49697 98.23915 15.79654 11.49697 96.22731 15.12631 8.496973 94.33946 15.76119 8.496973 94.99005 16.24058 8.496973 95.64044 16.59384 8.496973 96.26857 16.84736 8.496973 96.86425 17.02299 8.496973 97.42589 19.92871 8.649621 96.46511 18.72711 7.83903 98.26452 18.49448 7.94157 97.72605 19.37669 7.53031 97.96105 19.69064 8.16196 98.33181 17.58927 8.496973 99.04093 17.37226 8.49544 98.56347 17.13748 8.496973 97.95772 19.7727 8.656373 98.6345 19.94539 8.88449 98.20365 19.99392 8.38057 97.92615 19.99392 8.3286 97.39334 3.58867 1.43357 91.00081 2.87013 1.27291 91.70231 2.87013 -0.003029823 91.59163 3.15487 -0.003029823 91.29075 3.45073 -0.003029823 91.00081 2.87013 2.37195 91.98259 3.99651 2.81535 91.00081 4.65271 4.08412 91.00081 3.33635 4.10292 92.26278 2.87013 4.09936 92.83101 5.50056 5.99697 91.00081 4.1579 6.16047 92.98506 6.00056 6.96932 92.11705 6.00056 7.74294 93.00081 5.50056 7.94142 93.74383 12.05057 7.47344 91.00081 13.42382 7.14735 91.00081 12.05057 7.94142 91.46534 13.60876 7.94142 91.85357 14.69345 6.582 91.00083 14.91229 7.94142 92.47516 15.99923 5.63255 91.00083 16.95287 4.64133 91.00083 17.93123 2.916 91.00083 18.36637 1.65375 91.00083 18.55039 -0.003029823 91.00083 18.84625 -0.003029823 91.29077 19.13099 -0.003029823 91.59163 19.13099 1.27351 91.70243 19.13099 2.37288 91.98291 6.00056 8.496973 91.00081 9.96558 8.496973 91.00081 6.00056 8.496973 93.00081 17.23637 10.98769 92.17483 17.00056 10.99697 91.25485 8.092082 11.39697 92.93673 5.00056 10.99697 91.25485 6.26273 11.26217 92.8843 6.83172 10.99697 90.13398 9.49381 11.39697 92.44628 8.86467 10.99697 89.43849 11.00006 11.39697 92.27532 11.00054 10.99697 89.20285 12.50645 11.39697 92.44607 13.13641 10.99697 89.43849 15.16936 10.99697 90.13395 13.90857 11.39697 92.9365 4.7637 10.9876 92.179 4.5079 10.95624 93.19575 2.31998 3.11935 92.42472 2.00056 4.28585 92.55059 2.00056 2.47986 91.66356 2.32517 -0.003029823 91.70771 2.00056 1.33074 91.37054 2.00056 -0.003029823 91.25485 2.05718 -0.003029823 91.48596 2.21422 -0.003029823 91.66474 2.43612 -0.003029823 91.75068 2.67261 -0.003029823 91.72432 20.00056 1.33136 91.37065 19.565 -0.003029823 91.75068 19.7869 -0.003029823 91.66474 19.94394 -0.003029823 91.48597 20.00056 -0.003029823 91.25485 20.00056 2.48084 91.66389 19.32852 -0.003029823 91.72432 11.00057 11.49528 92.98594 12.05057 8.496973 92.86506 13.2815 8.496973 93.20881 12.03555 8.496973 91.00081 2.87013 -8.00303 91.59163 3.0914 -9.0346 91.35697 3.63093 -9.82743 90.83525 3.45073 -4.00303 91.00083 4.38597 -10.3084 90.21868 5.08407 -4.00303 89.72747 5.26143 -10.50303 89.61666 6.3819 -10.50303 89.01744 6.11167 -9.00303 89.14695 6.47897 -9.4878 88.9731 6.11167 -6.00303 89.14695 6.58706 -5.67444 88.92507 6.92677 -5.46536 88.78298 6.93422 -4.00303 88.78002 7.25148 -5.29607 88.65947 6.9567 -10.02226 88.77111 7.55905 -10.49866 88.5542 7.72198 -5.11393 88.50078 8.4356 -5.00303 88.30406 8.93008 -4.00303 88.19744 10.1382 -5.00303 88.03469 11.00057 -4.00303 88.00083 11.86293 -5.00303 88.03469 13.07105 -4.00303 88.19744 13.56553 -5.00303 88.30406 14.24841 -5.10488 88.49124 14.85765 -5.34857 88.69922 15.0669 -4.00303 88.78002 15.39911 -5.66467 88.91852 16.73969 -10.50303 89.61666 15.88945 -6.00303 89.14695 15.88945 -9.00303 89.14695 15.61948 -10.50303 89.01755 16.91706 -4.00303 89.72747 17.68598 -10.5013 90.22204 18.35194 -9.84937 90.81808 18.55039 -4.00303 91.00083 18.90894 -9.0365 91.35614 19.13099 -8.00303 91.59163 8.96396 -5.00303 88.67029 13.03717 -5.00303 88.67029 9.4016 -5.00303 89.13996 12.59953 -5.00303 89.13996 9.72967 -5.00303 89.69278 12.27146 -5.00303 89.69278 9.932312 -5.00303 90.30226 12.06882 -5.00303 90.30226 10.00057 -5.00303 90.93856 12.00057 -5.00303 90.93856 11.00057 -10.00303 89.00083 11.00057 -10.00303 89.40252 9.33445 -10.00303 89.05361 9.619893 -10.00303 89.47597 11.00057 -10.00303 89.74328 9.82955 -10.00303 89.94014 11.00057 -10.00303 90.01088 12.04364 -10.00303 90.43206 9.95749 -10.00303 90.43201 12.00057 -10.00303 90.93856 10.00057 -10.00303 90.93856 15.41134 -6.00303 88.98121 15.41122 -9.00303 88.98118 14.9055 -6.00303 88.94082 14.90544 -9.00303 88.94084 14.40688 -6.00303 89.02871 14.40681 -9.00303 89.02874 13.94649 -6.00303 89.23889 13.94644 -9.00303 89.23891 13.5536 -6.00303 89.55789 13.55354 -9.00303 89.55793 13.25326 -6.00303 89.96547 13.25317 -9.00303 89.96562 13.0646 -6.00303 90.43654 13.06454 -9.00303 90.43677 13.00057 -6.00303 90.93856 13.00057 -9.00303 90.93856 6.58979 -9.00303 88.98121 6.58979 -6.00303 88.98121 7.09562 -9.00303 88.94082 7.09562 -6.00303 88.94082 7.59425 -9.00303 89.02871 7.59425 -6.00303 89.02871 8.05464 -9.00303 89.23889 8.05464 -6.00303 89.23889 8.44753 -9.00303 89.55789 8.44753 -6.00303 89.55789 8.74787 -9.00303 89.96547 8.74787 -6.00303 89.96547 8.936532 -9.00303 90.43654 8.936532 -6.00303 90.43654 9.00056 -9.00303 90.93856 9.00056 -6.00303 90.93856 8.28888 -5.29592 89.04183 9.02681 -5.29592 89.86539 9.29344 -5.29593 90.93856 9.076683 -5.62035 90.93856 9.61786 -5.07915 90.93856 14.74864 -5.30497 88.66201 13.71718 -5.29592 89.03849 12.97572 -5.29592 89.86277 12.38325 -5.07915 90.93856 12.70767 -5.29592 90.93856 12.92444 -5.62034 90.93856 6.79139 -9.246253 88.91934 7.54059 -9.511981 88.86864 8.077672 -9.70493 88.92412 8.96474 -9.71013 89.7556 9.02918 -9.982002 89.01441 8.746582 -9.92569 88.99267 8.4782 -9.84499 88.9712 9.61788 -9.92691 90.93856 9.29346 -9.71013 90.93856 9.07669 -9.38571 90.93856 2.67261 -8.00303 91.72432 2.43612 -8.00303 91.75068 2.21422 -8.00303 91.66474 2.05718 -8.00303 91.48597 2.00056 -8.00303 91.25485 19.32849 -8.00302 91.72431 19.56498 -8.00302 91.7507 19.78688 -8.00302 91.66475 19.94394 -8.00302 91.48597 20.00056 -8.00303 91.25486 16.77464 -10.75303 89.55951 18.47097 -9.98157 90.87934 19.13404 -9.193263 91.46949 17.76203 -10.62444 90.18592 18.69175 -10.17119 90.83069 19.38859 -9.29184 91.43207 16.86144 -10.9194 89.41758 18.84677 -10.23448 90.72433 19.68918 -9.29155 91.14128 17.00056 -11.00303 89.19011 17.99669 -10.79865 89.9662 17.73979 -10.91053 89.59456 19.02323 -10.21861 90.44617 18.08883 -10.77341 89.81321 19.72198 -9.24321 91.00869 5.01505 -10.99559 89.2138 6.57306 -11.00303 88.38727 5.131 -10.93604 89.40339 7.47736 -10.85658 88.42583 5.21588 -10.77336 89.54217 8.23315 -11.00303 87.83876 9.950572 -10.85241 87.89984 11.00057 -10.6697 88.02233 8.52545 -10.61703 88.28743 11.00057 -10.97928 87.70178 11.00056 -11.00303 87.54885 13.7683 -11.00303 87.83885 12.05057 -10.85241 87.89984 14.52377 -10.85658 88.42583 15.42864 -11.00303 88.38752 2.91575 -9.16382 91.46038 4.28875 -10.54603 90.2146 3.42461 -10.08604 90.87477 2.71859 -9.25626 91.46589 4.16107 -10.70809 90.13066 3.2418 -10.2036 90.79393 2.53492 -9.30571 91.39328 4.00711 -10.79692 89.97328 3.07019 -10.24095 90.64248 2.36523 -9.30826 91.23494 3.90226 -10.76947 89.81949 2.97833 -10.21902 90.44583 2.27815 -9.240942 91.00953 11.00057 -10.40319 88.16567 9.213582 -10.32127 88.33208 11.00057 -10.18686 88.38906 9.26853 -10.1721 88.6602 11.00057 -10.04902 88.66846 15.21085 -9.246253 88.91934 15.52327 -9.4878 88.9731 15.04554 -10.02226 88.77111 14.46165 -9.511981 88.86864 14.44319 -10.49865 88.5542 13.92457 -9.70493 88.92412 13.52403 -9.84499 88.9712 13.47679 -10.61703 88.28743 13.25566 -9.92569 88.99267 12.97305 -9.982002 89.01441 12.73371 -10.1721 88.6602 12.78866 -10.32127 88.33208 12.66779 -10.00303 89.05361 12.92445 -9.38571 90.93856 12.70767 -9.71013 90.93856 13.0375 -9.71013 89.7556 12.38325 -9.92691 90.93856 12.17269 -10.00303 89.94014 12.38235 -10.00303 89.47597 12.00057 -5.00303 97.26877 10.00057 -5.00303 97.26877 12.23295 -5.00303 98.09375 10.37708 -5.00303 98.21898 10.77804 -5.00303 98.0259 11.22309 -5.00303 98.0259 11.62406 -5.00303 98.21898 9.63454 -5.07242 98.00083 12.27405 -5.02203 98.5056 10.0996 -5.00303 98.56694 11.90153 -5.00303 98.56694 9.83087 -5.00303 98.92147 12.17026 -5.00303 98.92148 10.00057 -5.00303 99.00083 12.00057 -5.00303 99.00083 12.08618 -5.00303 99.44345 9.92156 -5.00303 99.45932 11.86829 -5.00303 99.49787 10.13484 -5.00303 99.50135 11.50329 -5.00303 99.86528 11.76625 -5.00303 99.88864 10.24623 -5.00303 99.8983 10.50175 -5.00303 99.86753 11.00279 -5.00303 100.0008 11.28202 -5.00303 100.1389 10.7353 -5.00303 100.1428 13.00057 -9.00303 98.00083 13.00094 -6.00303 98.00081 9.00056 -9.00303 98.00083 9.00056 -6.00303 97.96101 9.30198 -5.2875 98.00083 9.079002 -5.61481 98.00083 9.0055 -6.00303 98.1412 12.4322 -5.1104 98.23588 12.69915 -5.28749 98.00083 12.92214 -5.61481 98.00083 12.86658 -9.50305 98.00083 12.50054 -9.869071 98.00083 12.00057 -10.00303 98.00083 10.00057 -10.00303 98.00083 9.50056 -9.86905 98.00083 9.13454 -9.50303 98.00083 11.00057 -5.00303 99.00083 9.26326 -5.33823 98.1848 9.07251 -5.64578 98.15258 12.73786 -5.33822 98.18481 12.92861 -5.64578 98.15258 9.187891 -5.27567 99.41165 8.89816 -5.9457 99.54119 9.84061 -5.27567 100.4531 9.67032 -5.9457 100.7162 11.00056 -5.9457 101.1716 11.00056 -5.27567 100.8595 12.33081 -5.9457 100.7162 12.16051 -5.27567 100.4531 13.10297 -5.9457 99.54119 12.81324 -5.27567 99.41165 12.00057 -10.00303 99.50083 10.00057 -10.00303 99.50083 13.10297 -8.9457 99.54119 8.89816 -8.9457 99.54119 9.67032 -8.9457 100.7162 11.00056 -8.9457 101.1716 12.33081 -8.9457 100.7162 2.87012 5.2965 93.82287 5.50056 8.496973 96.08535 6.88205 11.39697 93.68384 4.24052 10.8991 94.28621 2.31998 5.63813 94.39956 8.26184 11.49697 93.71026 9.3016 11.49697 93.29082 3.49354 10.59098 97.56623 3.31761 10.48045 98.41388 4.6541 11.17867 96.90397 4.49829 11.01932 95.70685 5.65125 11.34554 95.02054 2.37461 9.636343 99.45105 2.19308 9.23126 99.04592 2.61861 9.77928 100.3601 2.24902 9.44767 98.97078 2.87011 7.19214 97.23297 3.26737 7.83903 98.26452 2.61779 7.53031 97.96104 2.30384 8.16196 98.33181 2.6704 8.34236 98.60522 3.43079 8.64121 99.29347 4.07904 8.54095 99.21244 4.62223 8.49544 98.56346 2.44224 8.55985 98.71041 2.61464 8.73646 99.12652 2.24701 9.009303 99.10453 2.22178 8.656373 98.6345 2.04909 8.88449 98.20365 2.17456 9.29202 98.66218 2.14427 8.20532 98.23194 7.8249 8.6999 101.5135 11.00056 8.55728 102.1348 7.711 9.10508 102.6205 4.8891 7.94142 94.46917 4.41981 7.94142 95.18251 4.06698 7.94142 95.86851 5.97176 11.49697 97.17279 4.22435 11.08882 98.01065 5.78809 11.49697 98.23915 6.20463 11.49697 96.22714 5.12495 11.27728 95.90441 6.50539 11.49697 95.41564 6.88949 11.49697 94.7632 7.35242 11.49697 94.29109 7.39829 11.04698 104.825 8.76811 11.04697 105.4749 8.2146 11.49697 103.4717 8.72988 11.48797 104.0102 6.19326 11.04699 103.878 7.26237 11.49697 102.7124 5.24331 11.04699 102.7091 6.51005 11.49697 101.755 4.6052 11.04699 101.4496 5.9973 11.49697 100.6493 4.25925 11.04698 100.2058 5.75235 11.49697 99.45497 4.15255 11.04698 99.04558 8.40465 9.968563 105.5481 7.8915 10.3817 105.6682 7.13401 9.951333 104.9168 9.94006 9.968563 105.9637 9.9326 10.38028 106.2918 8.366373 10.85606 105.6447 2.97374 9.09237 100.3729 3.78238 9.4337 101.7848 2.59157 9.572001 100.4262 3.92516 9.96326 102.5678 2.72783 9.94482 100.2666 3.35801 10.22999 101.425 3.77964 10.36962 102.0449 4.28376 10.50161 102.6801 5.71889 10.27446 104.3477 5.03176 9.74083 103.2984 5.46721 10.70933 103.8616 6.15173 9.88731 104.2647 6.03297 10.77157 104.3141 7.05452 10.83814 104.9923 2.54015 9.80788 99.89679 2.43612 7.03771 97.27092 2.1915 7.58718 97.8946 2.00056 7.42452 96.80275 2.00056 7.87464 97.62245 2.00056 5.53739 93.58751 2.87012 6.30681 95.12614 2.00056 7.99697 96.1724 2.00056 8.3286 97.39332 2.07241 8.649621 96.46511 2.25906 9.21523 96.83737 2.50154 9.656763 97.29487 2.72783 9.955223 97.81954 2.72783 10.01127 98.47571 2.72783 10.0246 99.09308 2.72783 10.00166 99.68509 7.66201 9.49194 103.7704 8.455593 9.65113 104.6214 11.00057 11.49697 99.12439 3.71665 10.70835 96.54011 4.04649 10.83841 95.10441 2.9558 10.19218 98.41816 11.00057 8.496973 99.00081 14.30628 8.496973 93.72613 15.11115 11.49697 94.76256 14.64871 11.49697 94.29109 15.49569 11.49697 95.41555 13.73918 11.49697 93.71022 12.6994 11.49697 93.29078 14.60886 11.04698 104.8213 14.99772 10.83605 104.9621 13.23964 11.04697 105.4726 13.57732 10.85606 105.6672 13.0466 10.85606 105.8487 11.76309 11.04697 105.8064 11.82334 10.85606 106.1003 10.24501 11.04697 105.8072 12.30502 9.65113 105.0324 13.54827 9.65113 104.6214 13.01686 9.968563 105.7492 11.81138 9.968563 105.9972 11.00053 9.65113 105.1718 14.67593 8.71842 101.5759 14.33852 9.492383 103.772 14.4425 9.96396 105.1531 14.10963 10.38171 105.6682 12.06853 10.38028 106.2918 10.5399 10.85606 106.133 11.00056 11.48797 104.5008 13.27124 11.48797 104.0102 13.78652 11.49697 103.4717 14.73874 11.49697 102.7124 12.13903 11.48797 104.3768 9.83903 11.48797 104.3768 9.34895 10.85606 105.9544 9.696022 9.65113 105.0324 24.65771 9.874463 80.00003 24.9558 10.19218 94.41816 25.31761 10.48045 94.41388 24.31694 9.33731 80.00232 24.50154 9.656763 93.29487 24.72783 9.955223 93.81954 25.49354 10.59098 93.56623 39.00026 -10.99969 80.00003 39.76828 -10.89972 80.00003 39.00056 -11.00303 85.19011 39.7398 -10.91053 85.59456 40.08883 -10.77342 85.81321 40.50205 -10.59673 80.00003 41.02324 -10.21861 86.44617 41.1212 -10.12139 80.00003 41.72198 -9.24321 87.00869 41.59687 -9.502223 80.00003 41.90019 -8.768053 80.00003 42.00026 -7.99969 80.00003 42.00056 -8.00303 87.25486 27.01505 -10.99559 85.21382 26.2241 -10.90081 80.00083 26.99799 -11.0065 79.96547 25.90226 -10.76947 85.81949 25.49917 -10.59693 80.00003 24.97834 -10.21902 86.44584 24.40259 -9.49962 80.00003 24.27815 -9.240942 87.00955 24.10026 -8.76782 80.00003 24.00026 -7.99969 80.00003 24.00056 -8.00303 87.25486 37.42865 -11.00303 84.38752 28.57306 -11.00303 84.38729 42.00026 8.00031 80.00003 42.00056 7.99698 92.1724 42.00026 6.00031 80.00003 42.00056 4.28707 88.5514 42.00056 2.48084 87.6639 42.00056 1.33137 87.37066 42.00056 -0.003029823 87.25486 24.00026 8.00031 80.00003 24.00056 7.42452 92.80275 24.00056 7.99697 92.1724 24.00056 5.53739 89.58751 24.00056 4.28586 88.55059 24.00056 2.47986 87.66356 24.00056 1.33074 87.37055 24.00056 -0.003029823 87.25485 24.00026 -3.99969 80.00003 24.00026 6.00031 80.00003 41.92687 8.65984 80.00003 41.92871 8.64963 92.46511 41.74207 9.21523 92.83738 41.70312 9.30205 80.00003 41.49958 9.656763 93.29489 41.34298 9.87424 80.00003 40.87493 10.34245 80.00003 40.68932 10.4765 94.44256 40.28997 10.70574 92.56484 40.51466 10.58686 93.59964 40.30249 10.70294 80.00003 40.03181 10.81415 91.43007 39.76017 10.89921 90.28441 39.00026 11.00031 68.44584 39.49199 10.95645 89.19076 39.23637 10.98769 88.17483 39.00056 10.99697 87.25485 24.07241 8.649621 92.46511 24.07367 8.659893 80.00003 24.25905 9.21523 92.83737 25.1258 10.34262 80.00003 25.71664 10.70835 92.54011 25.66303 10.68178 80.0016 26.04649 10.83841 91.10441 26.24052 10.8991 90.28621 27.00026 11.00031 80.00003 27.00056 10.99697 87.25485 26.76369 10.98761 88.179 26.5079 10.95624 89.19575 28.83172 10.99697 86.13398 30.86467 10.99697 85.43849 33.00055 10.99697 85.20285 41.27329 9.955223 93.81955 3.69851 10.70317 84.00003 5.00026 11.00031 84.00003 3.12632 10.34303 84.00003 -3.49865 -10.59694 80.00003 -4.99944 -11.00303 80.00083 -2.87826 -10.12085 80.00003 -2.40227 -9.49953 80 -2.09974 -8.76782 80.00003 -2.05395 -8.57232 87.20533 -1.99974 -7.99969 80.00003 -17.7759 -10.90081 80.00083 -16.99944 -11.00303 83.00083 -16.99974 -10.9997 80.00003 -18.50153 -10.59674 80.00003 -19.12068 -10.1214 80.00003 -19.59635 -9.502223 80.00003 -19.89967 -8.768053 80.00003 -19.99974 -7.99969 80.00003 -10.99974 -11.00136 78.34411 -1.99944 7.99697 80.00083 -1.99974 6.00031 80.00003 -1.99974 -3.99969 80.00003 -19.99974 8.00031 71.65831 -2.34403 9.3815 80.00061 -2.65719 9.87445 80.00003 -3.12528 10.34261 80.00003 -3.62834 10.66877 79.99942 -4.34009 10.92688 80.00003 -4.99974 11.00031 80.00003 -19.92632 8.66 80.00003 -19.70237 9.30253 80.00003 -19.34188 9.87497 80.00003 -18.87368 10.34303 80.00003 -18.30149 10.70316 80.00003 -16.99974 11.00031 80.00003 17.00026 -10.99969 84.00003 17.76828 -10.89972 84.00003 18.50205 -10.59673 84.00003 19.1212 -10.12139 84.00003 19.59687 -9.502223 84.00003 19.90018 -8.768053 84.00003 19.94605 -8.57232 91.20533 20.00026 -7.99969 84.00003 4.2241 -10.90081 84.00081 5.00026 -10.99969 84.00003 3.49847 -10.59674 84.00003 2.87932 -10.1214 84.00003 2.40364 -9.502223 84.00003 2.10032 -8.768053 84.00003 2.00026 -7.99969 84.00003 11.00056 -11.00303 82.164 20.00026 8.00031 84.00003 20.00026 6.00031 84.00003 2.00026 8.00031 84.00003 19.92683 8.66001 84.00003 19.70288 9.30254 84.00003 19.3424 9.87498 84.00003 18.8742 10.34303 84.00003 18.30201 10.70317 84.00003 17.00026 11.00031 84.00003 2.07369 8.66001 84.00003 2.29763 9.30254 84.00003 2.65812 9.87498 84.00003 4.3327 10.83834 80.00003 3.58877 10.63364 80.00016 3.12979 10.3458 80.00003 20.00026 -7.99969 80.00003 20.00026 6.00031 80.00003 2.00087 7.9986 80.00003 2.00026 -7.99969 80.00003 4.92874 11.00031 79.1574 5.00026 11.00031 80.00003 3.71604 -10.59802 79.60369 3.86241 -10.59802 81.40355 2.42948 -9.53943 80.0016 4.98589 -10.99969 79.62123 5.01205 -10.99969 81.49244 5.00026 -10.99969 82.40481 17.17464 -10.99969 78.69107 17.00672 -10.99969 81.49743 -16.99974 -10.99969 71.07357 2.11456 -8.8199 80.00003 -2.8341 -10.59802 77.81888 -4.20597 -11.00002 77.5193 -2.16309 -9.498332 78.95822 -1.73179 -7.99969 79.00003 -1.49683 -9.498332 78.12275 -1.41395 -7.99969 78.58583 -0.99974 -7.99969 78.26799 -2.13715 -10.99969 75.47991 -0.91783 -10.59777 76.62258 -0.53404 -9.498332 77.65908 -0.51738 -7.99969 78.06819 -1.22603 -10.99969 75.15274 0.59526 -10.59777 76.55097 0.69725 -10.99969 75.04885 -0.26943 -10.99969 75.0073 2.6e-4 -7.99969 78.00003 0.53456 -9.498332 77.65908 0.51789 -7.99969 78.06819 1.6381 -10.99969 75.2759 1.9969 -10.59777 77.12541 2.51731 -10.99969 75.67978 1.49734 -9.498332 78.12275 1.00026 -7.99969 78.26799 1.41447 -7.99969 78.58583 3.30253 -10.99969 76.24569 3.02454 -10.59777 78.23831 3.96375 -10.99969 76.95195 2.16361 -9.498332 78.95822 1.73231 -7.99969 79.00003 4.4766 -10.99969 77.77239 4.82196 -10.99969 78.67671 1.93211 -7.99969 79.48239 18.40394 -10.64841 79.90622 19.58443 -9.498023 79.9998 19.89211 -8.797943 80.00003 19.92081 -9.498332 78.79946 20.06841 -7.99969 79.48239 18.99247 -10.59777 78.21028 17.51946 -10.99969 77.78138 20.26821 -7.99969 79.00003 18.03361 -10.99969 76.95607 20.79969 -9.498332 77.92057 20.03621 -10.59777 77.10305 20.58604 -7.99969 78.58583 21.00025 -7.99969 78.26799 18.69775 -10.99969 76.24591 19.48711 -10.99969 75.67753 21.45118 -10.59777 76.54338 20.37126 -10.99969 75.27282 21.48263 -7.99969 78.06817 22.00026 -9.498332 77.59889 22.0002 -7.99969 78.00003 21.31737 -10.99969 75.04689 22.28898 -10.99969 75.00837 36.38472 -10.99969 74.66987 -4.24974 -10.99969 75.50003 3.15365 10.59839 78.48143 4.70803 11.00031 78.31571 2.65477 9.87078 80.00003 2.34381 9.38248 79.99777 2.16361 9.49895 78.95822 2.07547 8.66787 80.00003 1.81694 7.99696 79.12403 4.33671 11.00031 77.51101 2.18247 10.59839 77.26362 3.19481 11.00031 76.15364 3.82524 11.00031 76.77986 1.49734 9.49895 78.12275 1.35816 7.99634 78.50424 2.47028 11.00031 75.65274 0.77908 10.59839 76.58777 1.67287 11.00031 75.2881 0.53456 9.49895 77.65908 0.70652 7.9977 78.11434 0.82237 11.00031 75.06807 0.003619909 7.99684 77.98102 -0.77857 10.59839 76.58777 -0.93444 11.00031 75.08818 -0.05690985 11.00031 75.00036 -0.53405 9.49895 77.65908 -0.73896 7.99722 78.12483 -1.7798 11.00031 75.32762 -2.18196 10.59839 77.26362 -2.56862 11.00031 75.71041 -1.49683 9.49895 78.12275 -1.3497 7.99713 78.50263 -3.28124 11.00031 76.22753 -3.15313 10.59839 78.48143 -4.38788 10.99998 77.50109 -2.16309 9.49895 78.95822 -1.81518 7.9965 79.11428 -4.96166 11.00031 79.38407 -4.846 11.00031 78.76966 17.668 10.88732 80.00003 17.00026 11.00031 80.00003 18.39397 10.64952 80.00267 18.87074 10.3458 80.00003 19.34576 9.87077 80.00003 19.65764 9.37099 80.00058 20.0261 8.00223 79.78579 21.22144 10.59839 76.58777 22.77908 10.59839 76.58777 21.17697 11.00031 75.06827 22.05642 11.00031 75.00035 22.53456 9.49895 77.65908 21.46596 9.49895 77.65908 22.00362 7.99684 77.98102 21.26106 7.99722 78.12483 20.32602 11.00031 75.28868 19.81805 10.59839 77.26362 19.52892 11.00031 75.65348 20.50317 9.49895 78.12275 20.65031 7.99713 78.50263 18.80557 11.00031 76.15374 18.84687 10.59839 78.48143 17.66463 11.00031 77.50957 18.17623 11.00031 76.77873 19.83691 9.49895 78.95822 20.18043 7.99652 79.12062 17.29248 11.00031 78.31575 17.07212 11.00031 79.15538 33.00041 -11.01419 78.34452 35.76831 -11.00303 83.83885 33.00057 -11.00303 83.54885 30.23315 -11.00303 83.83877 42 -4.37194 66.4732 39.02267 -11.00002 75.08294 40.44828 -10.60419 74.80902 22.96992 -10.59777 76.63703 23.24969 -10.99969 75.15866 22.51792 -7.99969 78.06819 23.20083 -9.498332 77.92057 24.16356 -10.99969 75.49224 23.00026 -7.99969 78.26799 24.4262 -10.59802 77.57001 25.97642 -11.00002 77.80838 25.02965 -10.99969 76.31192 24.07971 -9.498332 78.79946 23.41448 -7.99969 78.58583 23.73231 -7.99969 79.00003 23.93211 -7.99969 79.48239 41.17694 -10.06092 74.9608 41.68639 -9.552021 74.60721 41.99767 -8.01113 74.09465 42 -5.53847 70.52472 26.96239 11.00031 79.38578 25.15365 10.59839 78.48143 25.81986 10.88883 78.11775 26.77643 10.99998 78.09215 26.84682 11.00031 78.77086 24.16361 9.49895 78.95822 23.94208 7.99737 79.45581 23.60646 7.99701 78.77993 24.18247 10.59839 77.26362 25.28084 11.00031 76.22673 23.49735 9.49895 78.12275 23.20683 8.00031 78.40497 24.56712 11.00031 75.70919 23.77808 11.00031 75.32676 22.70653 7.99771 78.11434 22.93337 11.00031 75.08786 28.40349 -8.47888 11.38139 32.41966 -10.39946 12.09684 32.07041 -8.486083 13.14744 24.01463 -8.49968 5.09246 25.93359 -9.85955 5.58086 26.40131 0.004699945 11.02765 27.30582 -10.22031 6.25849 26.51307 -10.34244 5.16882 27.05665 0.00901997 11.89372 28.55564 -9.64302 7.14186 29.56896 -8.933712 8.01146 30.37484 -8.14502 8.837532 35.00025 -7.43725 9.41716 35.00025 -5.76714 10.52316 35.00025 -3.93633 11.33593 26.34064 -17.95326 2.99867 26.92072 -18.59914 4.80043 25.76056 -17.30739 1.19691 27.72791 -19.13109 6.6871 28.53512 -19.66305 8.57377 32.07253 -12.24215 12.44397 25.97391 -12.57047 6.52178 31.50558 -13.97236 13.01092 25.38119 -14.24428 7.11449 30.73585 -15.5381 13.78065 24.59638 -15.75172 7.89931 29.78649 -16.89231 14.73002 23.64218 -17.04913 8.8535 28.686 -17.99429 15.83051 22.54626 -18.09895 9.94944 21.34031 -18.87077 11.15537 27.46747 -18.81092 17.04904 31.63869 -14.49044 14.44563 35.00025 -8.90012 8.04876 35.00025 -10.11498 6.45608 35.00025 -11.04798 4.68351 27.40025 -11.09018 4.58269 35.00025 -11.67312 2.78043 27.40025 -11.64889 2.88028 27.40025 -11.94789 1.11366 35.00025 -11.97299 0.79989 27.40787 -11.94871 -0.93186 27.92001 -11.98834 -0.52151 28.45432 -11.99809 -0.19525 28.99234 -11.99966 -0.01994997 29.53337 -11.99967 0.01541996 35.00025 -11.93923 -1.20295 30.05848 -11.99939 -0.08360999 30.60025 -11.99514 -0.3301 31.96513 -11.92772 -1.31218 35.00025 -11.57278 -3.17227 33.17361 -11.74079 -2.47917 26.69314 -11.32162 2.97827 26.40025 -10.42215 3.51742 26.40025 -10.82463 1.95457 26.69314 -11.69481 0.52945 26.40025 -10.99412 0.34963 27.09578 -11.87235 -1.37935 26.71759 -11.59961 -1.87068 26.40025 -10.92695 -1.26282 26.40025 -10.62459 -2.848 26.45649 -11.05894 -2.46479 22.28349 -8.49967 5.96955 22.19817 -9.88384 6.05487 23.33167 -11.28459 5.48867 24.85194 -11.60693 5.52242 21.94514 -11.22494 6.30791 22.47212 -13.82473 6.34822 21.53238 -12.48305 6.72066 23.8929 -14.44108 6.48147 20.97256 -13.6208 7.28049 21.12374 -15.89684 7.69661 20.28258 -14.60443 7.97046 22.38843 -16.75303 7.98593 19.48311 -15.40482 8.76993 19.40502 -17.3188 9.41533 20.47079 -18.33958 9.90358 18.59801 -15.99816 9.65504 17.46704 -17.96563 11.35331 17.65359 -16.36674 10.59945 18.30849 -19.06128 12.06588 20.05931 -19.34222 12.43639 18.74032 -19.49967 13.75538 33.46514 -13.23542 -4.38076 32.28778 -13.85514 -3.54525 31.81377 -14.02564 -3.2714 30.60025 -14.46437 -2.79934 31.22617 -14.24843 -3.01115 29.9921 -14.63437 -2.69853 29.33738 -14.75585 -2.73755 28.62729 -14.79947 -2.94482 28.06561 -14.7988 -3.22255 27.51717 -14.71325 -3.63394 27.05751 -14.55941 -4.13271 26.67791 -14.31856 -4.75935 26.48153 -14.05493 -5.30128 26.40025 -13.70245 -5.92586 25.69386 -14.36625 -4.94372 23.40025 -15.35262 -3.49112 24.57748 -13.49051 -6.58541 26.40025 -12.58132 -7.37889 24.43242 -12.36088 -7.8829 26.40025 -11.22704 -8.632081 24.26431 -11.0518 -8.980503 26.40025 -9.674263 -9.6486 24.07885 -9.60768 -9.85022 26.40025 -7.98379 -10.39032 23.88002 -8.059473 -10.48215 26.40025 -6.18543 -10.84599 23.67152 -6.43582 -10.86809 23.45517 -4.75135 -10.99998 26.40025 -4.32847 -10.99998 26.40025 3.2e-4 -10.99998 20.80625 -4.91046 -11.00022 18.49701 -4.88507 -10.99054 17.80788 0.01880997 -10.9689 22.28349 -7.74968 5.96955 16.67795 -16.49934 11.57509 19.83408 -7.73186 8.35991 17.67848 -2.25269 -10.97997 17.34177 -13.08415 -7.20827 19.67205 -14.44833 -5.4625 17.10318 -14.40371 -5.27381 21.01717 -14.45248 -5.46438 20.86789 -13.10861 -7.33403 17.48629 -11.32987 -8.83812 20.8567 -11.35649 -8.91332 17.65667 -9.2618 -10.04914 20.84362 -9.30734 -10.08299 17.84032 -7.0325 -10.77014 20.82957 -7.10759 -10.77832 16.21432 -4.66904 -11.01523 17.62941 -16.83755 -0.5810599 20.1615 -16.82432 -1.00218 23.59675 -18.29618 2.50571 18.73591 -18.84136 3.9695 21.2089 -18.77235 3.32658 25.02458 -19.7664 6.56035 20.33439 -20.43481 8.38561 16.32313 -18.63193 4.7582 22.72505 -20.30991 7.52829 17.9938 -20.21678 9.37161 26.83457 -20.85997 10.49577 22.33832 -21.628 12.67456 24.62881 -21.45601 11.60831 20.08241 -21.41371 13.85312 15.74767 -19.64619 10.48574 17.90191 -20.78959 15.13328 29.58687 -20.05982 10.55783 28.95048 -21.59927 14.31421 30.63861 -20.45659 12.5419 26.83901 -22.22966 15.57205 29.24789 -16.00011 0.24119 32.72167 -14.68274 -0.7800599 33.49831 -15.35544 1.85466 30.21492 -16.97527 3.37437 34.47482 -15.903 4.43261 31.44747 -17.74713 6.43113 32.90879 -18.32579 9.408903 35.62984 -16.33092 6.95043 34.56216 -18.72138 12.30514 31.93859 -20.68924 14.62077 26.40025 -5.99968 6.00002 26.39507 -7.73162 5.01777 42.02021 -13.83867 14.29794 42.00025 -11.52747 14.08449 42.00025 -13.19034 14.22324 36.07827 -8.49957 15.91769 30.44322 -16.8216 15.96259 41.79856 -15.10147 14.19988 41.72396 -14.98816 14.96006 41.57338 -15.56666 14.15114 41.17762 -15.92868 15.16058 41.90142 -13.68791 14.8816 41.47512 -13.70568 15.47655 40.1245 -15.27101 15.93375 40.58631 -14.5679 15.87018 40.74386 -13.57435 15.74587 41.99378 -9.96123 14.29538 42.01282 -6.8414 14.96249 41.68601 -7.84641 15.45743 42.00025 -9.20317 14.24873 41.76836 -10.68854 14.90432 36.80173 -18.68935 15.87163 36.39445 -18.92611 15.09958 40.17875 -16.92108 14.2656 40.32484 -16.7515 15.04228 42.00025 3.2e-4 18.4377 42.00025 -2.45947 16.88493 42.00025 -11.5709 7.14655 42.00025 -4.59768 15.6645 42.00025 -12.6909 10.55045 35.70737 -3.55614 11.15385 35.02811 3.8e-4 11.99572 36.00025 -1.84419 10.84427 36.00025 -3.63533 10.38183 35.70737 -6.77643 9.54632 36.00025 -5.3225 9.62642 36.00025 -6.8584 8.599903 35.70737 -9.356203 7.03648 36.00025 -8.204813 7.32639 36.00025 -9.31814 5.84519 35.70737 -11.05159 3.86156 36.00025 -10.16628 4.20001 41.57278 -13.76807 8.916603 41.54034 -12.20096 3.64142 40.27235 -13.74717 5.04463 40.17191 -14.74203 7.98176 40.18572 -15.74563 10.95823 38.94659 -14.4825 5.4868 36.94197 -16.64471 9.40475 38.38988 -16.84989 11.7922 42.00025 -10.67037 4.09574 42.00025 3.41451 23.22383 42.00025 2.48337 21.60508 42.00025 8.00032 2e-5 26.46544 8.99548 11.93412 26.40025 11.00032 12.00002 35.0163 10.99907 11.99931 35.77664 10.99998 11.66451 35.50025 3.2e-4 11.86604 35.70735 3.2e-4 11.70713 35.86629 3.2e-4 11.50002 36.00155 2.1e-4 11.04207 36.00002 10.99987 11.00577 40.37364 3.2e-4 17.38355 27.01681 -0.01592987 12.24287 35.02872 -8.8e-4 13.18408 42.00025 1.33143 20.13088 35.08573 -11.80042 -6.21055 35.6059 -10.89876 -7.17275 35.39104 -11.27122 -6.77528 36.00025 -10.7261 2.43799 35.70737 -11.70236 0.32165 36.00025 -10.98286 0.60792 36.00025 -10.92969 -1.23884 35.70737 -11.24701 -3.24866 36.00025 -10.56956 -3.04589 35.00025 -10.88384 -5.05319 36.00025 -9.911643 -4.76999 35.75685 -9.60337 -6.61508 35.5237 -10.17083 -6.08431 35.279 -10.59459 -5.5635 36.00025 -8.97281 -6.3626 36.00025 -7.77785 -7.77815 35.9585 -8.66244 -7.28348 34.20457 -11.39358 -3.76549 41.7905 -3.19041 -8.87215 41.74584 -1.03501 -9.19167 42.00025 -2.56724 -7.87044 41.12244 -3.40579 -9.86748 41.19122 -1.03675 -10.06104 40.10453 -3.96232 -10.42355 39.16365 -2.79369 -10.86731 39.00025 -1.03347 -10.99998 40.21046 -1.03285 -10.73259 39.3138 -4.48102 -10.48149 42.00025 -4.01987 -7.49524 41.7905 -5.24932 -8.18534 41.12244 -5.67564 -9.11018 40.10453 -6.72086 -9.32951 39.45084 -6.08439 -9.85265 42.00025 -5.36798 -6.89018 41.7905 -7.10811 -7.05961 41.12244 -7.73129 -7.86504 39.57241 -7.56018 -9.00133 40.10453 -9.11759 -7.54226 39.67771 -8.880763 -7.94826 42.00025 -6.5857 -6.06749 41.7905 -8.662281 -5.53635 42.00025 -7.60726 -5.08037 41.12244 -9.45589 -6.17451 39.76682 -10.0302 -6.70475 40.45203 -11.22837 -3.75614 39.88445 -11.55432 -3.6065 42.00025 -8.435002 -3.93784 41.7905 -9.81318 -3.68584 40.9985 -10.87407 -3.69893 42.00025 -9.03509 -2.69427 42.00025 -9.39662 -1.4047 41.83179 -10.32557 -1.5804 41.3948 -11.0788 -1.49077 35.70857 -12.46417 -4.83861 35.9755 -13.18312 -2.76718 38.22656 -12.1883 -3.49941 34.38255 -12.56367 -5.28364 38.50327 -9.6095 -7.80173 35.90602 -9.91289 -8.07624 37.77982 -7.1914 -9.58309 36.00025 -8.87659 -8.876893 36.00025 -7.36012 -9.77793 36.9552 -4.63787 -10.65916 36.00025 -5.67979 -10.45227 36.00025 -3.91054 -10.86221 36.00243 -2.08998 -11.00132 37.007 -1.75784 -10.99998 42.00025 -9.964241 1.3075 39.99825 -12.45262 -0.54363 36.62261 -13.68488 -0.23197 42.00025 5.13849 -6.1318 42.00025 6.12571 -5.14582 42.00025 6.92669 -4.00314 42.00025 7.51684 -2.73896 42.00025 7.87836 -1.39154 42.00025 3.99485 -6.93134 42.00025 2.73022 -7.5198 42.00025 1.38154 -7.87984 42.00025 -1.03347 -7.99998 42.00025 3.2e-4 -7.99998 36.00025 3.2e-4 -10.99998 36.00025 10.86488 -1.72084 36.00025 10.46189 -3.39933 36.00025 9.80128 -4.99409 36.00025 8.899312 -6.46588 36.00025 7.77821 -7.77843 36.00025 6.46557 -8.89945 36.00025 4.99391 -9.80121 36.00025 3.39927 -10.46168 36.00025 1.72095 -10.86458 36.00025 11.00032 2e-5 39.00025 1.64007 -10.87708 39.00025 3.2e-4 -10.99998 39.00025 3.24445 -10.51072 39.00025 4.7755 -9.90945 39.00025 6.1986 -9.08741 39.00025 7.48293 -8.0629 39.00025 8.60061 -6.85818 38.97711 10.48833 -3.49898 39.00025 11.00032 2e-5 39.00025 10.89241 -1.81744 40.4095 7.5e-4 -10.63608 39.66782 3.2e-4 -10.92476 41.59834 2.4591 -9.17628 41.92503 3.2e-4 -8.66754 41.64241 0.002799928 -9.40393 40.49889 2.87802 -10.2007 41.34576 3.2e-4 -9.87045 40.87072 3.2e-4 -10.34547 41.59834 4.75032 -8.22722 40.49889 5.53952 -9.03619 41.59834 6.71784 -6.71749 40.49889 7.78487 -7.19279 41.59834 8.22756 -4.74998 40.44881 9.92724 -3.464 41.59834 9.17661 -2.45876 39.66782 10.9251 2e-5 40.39354 10.64984 -0.002829909 40.87072 10.34581 2e-5 41.34576 9.87079 2e-5 41.69691 9.311882 5e-5 41.92503 8.667881 2e-5 38.00713 -1.40528 -10.99998 39.68842 -1.03347 -10.91998 41.92567 -1.03347 -8.664793 39.03521 10.99585 49.49406 42.00125 -0.71631 18.43795 42.00025 4.55122 26.76701 42.00025 4.1072 24.95292 42.00047 4.69463 28.6318 41.81115 -1.86582 18.29768 41.23049 -3.3002 17.89993 41.47659 -2.75849 18.06089 12.48855 3.2e-4 15.79748 42.00025 3.2e-4 18.84805 37.1356 3.2e-4 19.3314 33.23856 -20.92189 16.69965 40.76066 -15.52186 15.75186 40.06757 -16.00425 15.87182 40.22589 -16.42364 15.52246 33.35737 -19.37798 18.47003 36.38074 -17.22534 16.86729 34.80528 -18.14896 17.55974 36.71384 -18.03838 16.64432 38.0946 -16.32222 16.33485 33.58095 -19.83546 18.33454 33.70298 -20.36124 17.97837 33.54759 -20.85854 17.23245 30.69171 -22.24771 18.43515 31.41272 -21.9537 17.9378 31.62679 -21.89856 18.60094 31.84028 -21.44528 19.19137 31.80485 -20.76753 19.56405 32.26551 -19.55745 19.0903 41.25215 -11.00445 15.38839 40.64713 -11.32652 15.5772 40.52986 -9.02008 15.7978 41.13953 -8.51999 15.75002 40.40797 -6.80917 16.37213 41.01591 -6.13438 16.52875 41.58786 -5.17697 16.53332 40.38424 -4.48807 17.39218 41.93192 -4.01259 16.46582 40.92645 -3.84365 17.70303 35.71275 -9.705142 15.91657 35.29206 -10.91734 16.03666 39.14009 -13.04748 15.91207 36.25659 -12.37569 16.18199 35.09933 -11.52614 16.16336 34.118 -13.0561 16.55865 38.58134 -14.43949 16.13066 41.26543 -14.7604 15.59121 31.477 -15.17923 17.95153 29.34525 -16.44808 19.29175 33.81829 -18.5521 18.04126 35.41711 -17.43465 17.18347 33.03078 -13.91455 16.94669 36.99712 -16.05521 16.52683 29.02715 -17.60599 18.87498 30.80184 -16.13773 17.10029 28.50963 -18.42133 17.89618 33.63822 -12.77722 15.80506 19.14005 -0.003129959 29.62204 19.25456 -9.92532 29.53012 19.10081 -10.63181 29.65857 19.40948 -9.26246 29.4442 19.71731 -0.01337999 29.35701 19.56011 -8.67049 29.39129 19.77643 -7.90248 29.36016 20.02914 -7.07309 29.38228 20.37775 -0.00296998 29.53156 20.26107 -6.37132 29.4636 20.44985 -5.8276 29.58583 20.7931 -0.01739984 30.14644 20.6622 -5.25023 29.82252 20.78845 -4.83021 30.14517 26.16752 -19.31767 18.34898 24.82522 -19.49928 19.69128 23.48092 -19.35032 21.03558 17.42155 -19.33856 15.07414 22.17502 -18.87526 22.34149 16.1412 -18.86353 16.3545 20.94673 -18.08838 23.56977 14.93633 -18.08837 17.55936 16.27308 3.1e-4 32.48607 18.94978 -11.71702 29.80163 16.99428 -9.818001 31.76487 19.11136 -12.30309 29.54573 16.69925 -10.41788 31.94676 19.6621 -13.33201 28.79598 20.01768 -13.85381 28.33473 19.37698 -12.71614 29.27196 20.37682 -14.31138 27.89106 16.30979 -10.98208 32.00586 15.84935 -11.48071 31.94183 21.59014 -15.58498 26.50465 22.34574 -16.22029 25.72818 20.96544 -14.97776 27.1939 23.14839 -16.87866 24.86746 22.80765 -17.27495 24.78397 15.35213 -11.88407 31.76529 22.34495 -17.61963 24.59531 21.90648 -17.85584 24.34608 14.83885 -12.18266 31.4894 21.39506 -18.03484 23.97552 14.32936 -12.36808 31.12733 28.39665 -17.08982 20.17261 26.32936 -19.14903 20.07644 27.02606 -18.2739 20.87608 27.43289 -17.51014 21.05084 26.40682 -17.71803 21.98106 24.09405 -18.94074 22.31176 24.97444 -18.08273 22.9277 25.32321 -17.67927 22.96893 24.25482 -17.38544 23.94788 15.52851 -17.95703 24.59626 20.26193 -19.8896 26.44864 19.21382 -18.99056 27.48281 21.24988 -20.69806 25.57821 19.74209 -20.53287 23.21115 21.68996 -20.62116 26.04128 18.19185 -18.06313 28.61582 18.99066 -17.98845 29.04796 16.93622 -16.85897 30.15848 22.36362 -20.15979 26.4117 19.74082 -17.36263 29.20481 16.33141 -15.51816 32.23312 22.83073 -19.52563 26.367 20.1572 -16.65143 28.87078 17.21596 -14.86782 32.39308 21.27265 -17.60897 27.6795 23.00918 -19.02773 26.10273 30.56804 -19.94081 20.11286 31.13405 -20.31158 19.93937 29.85641 -20.68763 20.83753 28.9377 -20.18408 21.221 28.59649 -20.85482 21.73916 27.35306 -20.11139 22.33947 27.13896 -20.80618 22.81975 25.85386 -19.72125 23.44513 25.655 -20.47569 23.97182 24.46295 -19.04943 24.50942 24.21118 -19.83891 25.12656 23.19882 -18.14021 25.50323 22.07966 -17.02658 26.40912 21.12335 -15.73274 27.21873 17.49983 -14.38133 32.22545 24.66112 -22.43105 16.84363 22.5027 -22.21692 18.20887 20.40215 -21.55375 19.64544 16.91113 -19.99842 18.42206 18.23429 -20.36765 20.84409 29.12959 -22.67236 19.52596 29.80934 -22.52407 19.04911 27.17079 -22.85069 20.93243 27.99811 -22.82753 20.33094 25.20728 -22.62564 22.41558 26.17777 -22.79241 21.67212 22.79481 -21.72366 24.32347 23.60282 -22.11311 23.67622 24.43566 -22.42148 23.0167 22.01063 -21.2525 24.95752 29.93627 -21.36656 20.86929 29.86304 -22.07504 20.56567 29.57405 -22.5463 20.02341 28.03761 -21.54364 22.23441 27.85562 -22.26048 22.00524 27.48744 -22.73599 21.51744 26.18318 -21.30885 23.6408 25.89422 -22.0113 23.49062 25.44652 -22.47526 23.06171 24.41178 -20.65827 25.0442 24.02091 -21.32278 24.97271 23.50173 -21.75924 24.59907 17.11525 -13.81543 32.82057 -2.29975 -2.19968 10.00002 1.41852 -2.18136 8.50479 2.10002 -2.1863 8.88863 2.29769 -2.19447 9.43571 2.30026 -2.19968 10.00002 15.58798 -19.62919 16.00003 13.38918 -18.54927 11.10375 14.01899 -18.14679 5.70158 11.69067 -17.19778 6.20609 15.7002 -16.39166 12.55285 14.74955 -16.0464 13.5035 13.85454 -15.47327 14.39851 7.96479 -5.69968 20.28825 6.74123 -9.818001 21.51182 6.44189 -9.49952 21.81116 6.15404 -8.86181 22.10996 6.22134 -0.003749907 22.03882 6.02004 -8.07461 22.23301 15.4237 -15.28663 32.26079 12.34679 -14.95873 28.08375 8.56765 -12.45528 30.71025 6.45156 -12.39952 27.24239 9.72782 -15.05955 23.61681 13.13618 -17.59838 20.42722 4.79622 -12.34811 23.80456 7.3538 -14.73762 19.06055 3.31448 -12.27908 19.90975 11.06191 -17.0369 16.10123 5.7965 -14.29902 15.81472 2.03309 -12.17345 15.57592 2.30026 -12.41869 14.50002 9.326023 -16.29676 11.64083 4.45563 -13.7603 8.99367 2.30026 -12.7135 9.36678 7.94874 -15.40209 7.06861 2.30026 -12.66151 4.17627 2.30026 3.2e-4 10.00002 2.30026 -5.99968 14.50002 2.29793 -6.49553 9.455471 1.35699 -6.49441 8.502963 -1.36301 -6.49383 8.50314 -1.37883 -2.19331 8.503373 1.9934 -6.4836 8.769742 6.02004 -8.074603 26.47565 5.60269 -8.074603 25.95281 6.02004 3.1e-4 26.47565 5.60119 3.1e-4 25.95042 5.31731 -8.074603 25.36663 5.30971 3.1e-4 25.34517 5.16495 -8.074603 24.72983 5.16022 3.1e-4 24.69022 5.15527 -8.074603 24.06575 5.16022 3.1e-4 24.01844 5.29752 -8.074603 23.39905 5.30971 3.1e-4 23.36349 5.59 -8.074603 22.77618 5.60119 3.2e-4 22.75823 5.67436 -9.66423 22.90164 6.56361 -10.39752 21.79493 6.50046 -10.93473 22.15888 5.54018 -10.15569 23.95551 6.54932 -11.42115 22.59446 6.71143 -11.83646 23.08675 5.83148 -10.48407 25.04063 6.98741 -12.15973 23.61972 7.36413 -12.36337 24.15835 6.71724 -11.05583 25.77845 6.10162 -9.14249 26.39407 6.33935 -10.15108 26.15634 7.21442 -11.82133 25.28127 7.82302 -12.43309 24.67267 14.49035 -18.0228 17.06126 14.0894 -17.80055 16.48177 13.84051 -17.51784 16.00994 13.66921 -17.10376 15.50945 13.6162 -16.65177 15.09983 13.67642 -16.05519 14.68301 16.09159 -18.85471 14.28278 15.48012 -17.78049 13.34023 13.83343 -12.4331 30.68308 12.03045 3.1e-4 32.48607 12.03045 -8.074603 32.48607 13.21518 -11.80923 31.30133 12.70999 -11.02191 31.80652 12.33751 -10.1127 32.17901 12.1093 -9.12466 32.40722 1.7e-4 -11.18913 19.04369 -0.07635998 -11.28434 16.80128 0.5104 -11.45072 16.74273 1.36779 -11.78772 16.34723 1.75114 -11.99076 15.99146 2.55636 -11.7272 21.34209 0.96721 -11.61329 16.58688 1.51737 -11.1812 23.97205 -0.46236 -10.99969 24.08346 4.38211 -11.7272 26.07354 1.31037 -10.99969 28.35049 3.5336 -11.1812 28.57728 3.40761 -10.99969 32.26215 6.74065 -11.7272 30.53661 6.07224 -11.1812 32.91627 -0.277 3.2e-4 16.78325 0.27751 3.2e-4 16.78325 0.8159 3.2e-4 16.65054 1.30688 3.2e-4 16.39283 1.7219 3.2e-4 16.02512 2.03685 3.2e-4 15.5688 2.23344 3.2e-4 15.05038 2.30026 3.2e-4 14.50002 18.44563 3.2e-4 14.19056 7.94215 -9.49526 -8.74049 5.79498 -8.75979 -8.48912 11.03062 -9.83635 -9.103402 16.37179 -9.38429 -9.929183 5.20335 -6.40573 -7.44079 16.19582 -6.6725 -7.99255 16.19854 -5.91443 -7.05481 5.21083 -5.34324 -6.28933 16.20295 -5.21217 -6.09823 5.21083 -4.46593 -4.8577 16.21576 -4.45627 -4.43457 5.21083 -3.82337 -3.30643 16.20252 -3.79117 -2.54029 5.21083 -3.43141 -1.67376 16.19454 -3.58016 -1.05025 5.21083 -3.29968 2e-5 16.22372 -3.54935 -0.03472983 16.20554 -2.27144 2e-5 4.65165 -6.42327 -9.95994 4.67074 -4.85293 -10.53826 4.75562 -5.59203 -10.16753 2.5e-4 -6.49968 2e-5 2.5e-4 -2.19968 2e-5 2.5e-4 -6.49968 1.50002 2.5e-4 -2.19968 1.50002 5.211 -7.77663 -8.83886 5.10653 -8.62178 -8.75723 4.67872 -7.97769 -9.10889 5.56788 -9.22203 -8.36796 4.77767 -3.38496 -10.84126 5.21512 -3.95656 -10.43942 5.211 -5.29716 -9.87299 5.21083 -6.45814 -9.39643 4.52895 -2.93278 -10.9321 4.68751 -1.54675 -8.49243 5.21083 -2.71436 -8.735001 5.21083 -1.68769 -7.07249 5.21083 -0.88467 -5.29111 5.21083 -0.31883 -3.42085 5.21083 3.2e-4 0.02375996 16.20164 -3.87406 -8.524291 16.20554 -8.50857 -9.78222 16.19149 -7.38475 -10.66326 15.68676 -10.02945 -9.58225 13.70732 -10.13295 -9.30496 2.30026 -12.2811 -1.05123 2.30026 -11.93863 -2.86297 4.55497 -12.84383 -1.73477 7.08376 -13.40058 -2.55376 9.88299 -13.91818 -3.49883 2.30025 -11.27331 -4.62131 10.07449 -13.24681 -5.12989 2.30025 -10.29997 -6.25599 10.33482 -12.33418 -6.62453 2.30025 -9.043931 -7.71364 10.65601 -11.20818 -7.94218 2.30025 -7.52813 -8.955471 2.30025 -5.81076 -9.92659 2.30025 -3.94129 -10.59819 2.30025 -1.96335 -10.9499 1.40157 -6.49028 1.49476 1.40112 -2.19185 1.49557 2.29917 -6.49742 0.52472 2.01772 -6.48097 1.21033 2.28986 -2.1686 0.7134 1.91201 -2.18626 1.29958 -2.29975 -6.49968 2e-5 2.30028 -0.53686 -8.14923 2.31554 0.01653999 -3.92797 2.29455 -1.26716 -0.9975399 2.28722 -1.81631 -0.7952899 2.27369 -2.19633 -0.16031 10.51843 -15.63732 1.33572 6.95038 -14.37706 2.40713 3.51229 -13.13803 3.88576 17.23772 -3.05346 -10.96482 16.18242 -3.40822 -11.02232 17.22123 -1.64601 -8.41791 16.2002 -2.61073 -9.88012 16.20301 -3.46626 -7.26 16.20633 -3.06177 -5.94197 16.24841 -1.38861 -7.1104 16.20823 -2.70407 -4.54705 16.20536 -2.4366 -3.05215 16.19878 -2.29308 -1.47717 13.68469 -14.26965 -4.67984 13.77124 -13.2465 -6.4377 14.00948 -11.86053 -8.03449 15.15664 -16.66497 0.006769955 12.79545 -16.31463 0.77954 -2.31627 -2.09971 -0.45265 16.29574 0.01832985 0.009949982 17.69897 6.92263 -0.90656 17.7 8.17118 -6.31599 17.70071 6.93745 -7.57629 17.7 9.01431 -5.2704 17.70026 9.00032 -3.32453 17.69255 9.02092 -0.82214 17.9133 7.12353 -8.09596 18.281 7.47546 -8.13672 18.281 8.714673 -6.71267 18.281 9.49011 -5.5627 18.28946 10.09972 -4.3549 17.7 9.62212 -4.30022 17.80645 10.63646 -0.01969999 17.63077 10.52348 0.25821 17.94184 10.79483 0.38153 18.09589 10.91687 0.92458 17.46791 10.46586 0.40571 17.83099 10.86485 1.34917 18.27831 10.98081 1.4733 18.43223 10.99463 1.9448 17.64867 10.12079 -0.44572 17.70586 10.24945 -2.09048 17.70026 9.79379 -3.02493 18.28079 10.77432 -2.24154 18.33503 10.99501 -0.001329958 17.70025 3.2e-4 2e-5 17.70026 3.2e-4 -6.72382 17.58226 3.2e-4 -4.95369 17.15031 3.2e-4 2e-5 17.21782 5.8e-4 -2.76679 17.70026 -1.22318 -9.62563 17.70026 -0.55721 -8.19757 17.22123 -0.61647 -5.65771 16.26741 -0.45891 -4.49718 16.2005 3.2e-4 -1.73222 16.20426 -0.28531 -3.352 16.70025 9.00032 2e-5 16.75961 6.80614 0.1259999 3.21558 7.33902 0.009579956 17.70026 5.92604 -8.363492 17.91993 4.97721 -9.56273 17.70026 4.86644 -9.02125 18.45026 5.90116 -9.28331 18.45026 4.61769 -9.98395 17.70026 3.7954 -9.521533 17.91993 2.56215 -10.47149 18.45026 3.34297 -10.4798 17.70026 2.74612 -9.87536 18.45026 2.12328 -10.79317 17.70026 1.74768 -10.09994 18.45026 0.99835 -10.95461 3.26448 10.99998 1.82656 3.17098 10.89998 1.30254 17.2886 10.70415 0.94977 3.23595 9.184 -4.1e-4 16.71546 9.70102 0.11947 17.68258 0.41522 -10.32299 17.7 6.04312 -0.72008 17.70026 5.1811 -0.259 26.31675 0.004699945 11.43307 37.50025 3.2e-4 21.00002 8.00662 3.2e-4 20.25202 37.40801 3.2e-4 20.14595 26.40025 11.00032 2e-5 26.40025 3.2e-4 6.00002 26.40025 1.72095 -10.86458 26.40025 3.39927 -10.46168 26.40025 4.99391 -9.80121 26.40025 6.46557 -8.89945 26.40025 7.77821 -7.77843 26.40025 8.899312 -6.46588 26.40025 9.80128 -4.99409 26.40025 10.46189 -3.39932 26.40025 10.86488 -1.72084 -0.81539 3.2e-4 16.65054 -1.30637 3.2e-4 16.39283 -1.72139 3.2e-4 16.02512 -2.03634 3.2e-4 15.5688 -0.05216985 10.99998 3.2123 2.61186 10.99627 0.89395 -3.23746 10.99975 1.76078 -2.30683 5.2997 -0.9867799 2.30025 3.2e-4 -0.99998 2.30887 7.50036 -0.98328 -2.32838 9.09664 -0.9664999 2.34565 9.219861 -0.94769 3.30625 9.92307 0.20289 3.30676 10.56971 0.72338 16.80244 10.21738 0.39948 -2.3191 -1.65903 -0.89956 -2.29975 3.2e-4 10.00002 -2.3217 10.08648 -0.6967099 2.30311 9.91917 -0.7764099 2.54243 10.73518 0.2392399 -2.48352 10.76608 0.16778 2.60148 8.999361 -0.25303 2.55547 7.5018 -0.29981 2.59315 9.78928 -0.15286 5.15499 0.00225991 -2.3248 3.40026 3.2e-4 2e-5 5.07386 3.2e-4 -3.17212 4.39345 0.02717 -3.11122 4.96766 -0.61587 -5.85918 17.34274 6.79722 -0.13385 17.26482 9.028182 -0.14884 17.18981 9.87308 0.04524987 17.31603 10.44393 0.51954 17.06789 10.45824 0.64089 37.50025 2.19422 22.05426 37.40435 0.73243 20.1451 37.50909 3.57046 33.79905 37.50026 3.23185 35.25447 37.50021 3.75936 32.92622 37.50006 3.92558 32.07096 37.50026 4.06082 31.35498 37.50026 4.26847 29.53544 37.50026 4.21362 27.70218 37.49462 3.94249 26.10388 37.50025 3.32473 24.15278 42 4.60716 30.81114 41.70798 3.88144 30.84091 41.61946 3.73011 28.65682 41.23909 3.51172 30.85785 40.9242 3.26715 28.67483 40.68318 3.30035 30.86494 40.01752 3.32974 28.77479 40.09034 3.37438 30.86367 41.94769 3.2e-4 19.36702 41.71842 -0.00575 20.01342 41.67065 2.00021 22.58903 41.14101 -0.02314984 20.675 39.83923 2.33243 24.11971 39.72058 0.01236999 20.58068 40.32361 -0.009799957 20.87785 40.82568 1.72519 23.15768 41.67065 3.29589 25.50533 40.82568 2.83887 25.81911 39.83923 2.94015 25.74441 39.83924 3.25593 27.19053 38.53032 3.82532 31.03301 38.97182 3.2e-4 20.13458 38.07147 3.2e-4 19.68671 38.71609 3.23855 25.0583 42.00026 -3.329 61.7503 42.00026 -2.68931 58.80988 42.00026 -2.01866 56.14605 42.00026 -1.33825 53.7342 42.00026 -0.66312 51.54677 42 0.01940995 49.44598 42.00026 0.90463 46.98814 42.00026 1.27223 45.9909 42.00026 2.64223 42.40157 42.00026 3.26882 40.78415 42.00026 3.80804 39.20903 42.00026 4.26056 37.45743 42 4.41831 35.70793 39.00605 10.99998 50.90361 40.77634 1.29834 41.78917 37.50026 2.06831 38.47021 37.50026 2.36053 37.78063 39.12905 2.10223 39.00677 40.75076 1.88919 40.25134 37.50026 1.7721 39.16009 40.80231 0.65552 43.46877 37.50026 1.47398 39.84916 37.50026 1.17579 40.53642 40.88453 0.006799936 45.22028 37.50026 0.87904 41.2211 37.50026 0.58421 41.90438 37.50026 0.29134 42.58811 37.50026 3.1e-4 43.27425 37.86468 -1.28829 46.67348 40.95145 -1.31296 49.00166 40.8881 -2.05795 51.15124 40.9055 -2.78022 53.51792 40.92114 -3.49185 56.08376 40.93563 -4.22286 59.0684 38.00026 -4.32987 56.00671 40.94827 -4.89696 62.31458 40.99276 -6.27097 69.4598 39.56744 -6.94584 69.68528 34.57989 -2.49604 47.51221 31.2798 -8.57772 66.95871 31.61232 -6.53616 57.16278 40.39569 3.1014 35.40696 39.23923 3.58346 31.84347 40.61332 2.37786 38.01184 37.50026 2.82658 36.56094 40.81791 3.10269 35.64901 41.35299 2.08151 40.32797 41.38855 3.3211 35.68163 41.89888 2.6874 40.56078 41.78449 3.78594 35.75154 41.42602 0.11571 45.58867 41.92104 0.6899 45.90022 36.98519 -10.49187 73.65435 40.50635 -9.57438 73.47957 40.05586 -10.39787 74.10015 39.10843 -10.81996 74.49618 34.98815 -10.54967 73.19113 40.75598 -9.05269 73.0357 33.17701 -10.60156 72.65687 40.74006 -8.1737 72.10389 33.82185 -9.33063 71.18477 40.78117 -7.47096 71.16957 40.90627 -6.78083 70.13558 33.58817 -8.448903 69.18836 41.62707 -0.92331 48.99156 41.68417 -3.34011 57.58212 41.73455 -5.01147 66.37409 41.13453 -8.96965 73.12194 41.55864 -6.3484 70.15403 41.40157 -8.820053 73.27262 41.60799 -8.70256 73.39331 41.87943 -5.99443 70.34275 41.7471 -8.55435 73.54315 41.88245 -8.39852 73.70246 41.01022 -9.77275 73.81822 35.06305 -10.90893 73.79316 34.055 -10.99969 74.02668 -34.39244 11.00066 18.74109 -19.54399 11.00031 39.92647 -15.61547 11.00031 37.17568 -16.99974 11.00031 50.35272 -19.99974 -3.07323 57.68965 -19.99974 -4.33871 56.89844 -19.99974 -5.60764 55.77404 -19.99974 -6.84118 54.29292 -19.99974 -7.99843 52.44464 -19.94339 8.57903 52.41387 -19.99974 7.99879 52.44456 -19.7647 9.164361 52.28874 -19.45675 9.721673 52.07313 -19.01309 10.22437 51.76247 -18.43685 10.6337 51.35898 -17.75019 10.90493 50.87818 -20.9757 6.66662 53.13669 -19.99974 6.81651 54.32783 -19.99974 5.56375 55.81978 -21.76647 5.15921 53.69042 -19.99974 4.28182 56.94116 -22.34637 3.51567 54.09646 -19.99974 3.01323 57.72006 -22.70031 1.77899 54.34429 -19.99974 1.78033 58.20073 -19.99974 0.57544 58.42724 -22.81889 -0.004569888 54.42732 -19.99974 -0.62254 58.42272 -22.69871 -1.79026 54.34317 -19.99974 -1.8346 58.18479 -22.34294 -3.52745 54.09406 -21.76038 -5.17257 53.68614 -20.96898 -6.67675 53.13199 -34.89827 10.93751 20.04468 -21.02757 10.85019 40.96528 -22.47069 10.4039 41.97576 -35.94353 10.52684 22.1564 -23.83393 9.67363 42.93031 -36.26926 10.29696 23.0083 -36.98425 9.50867 24.39766 -37.5463 8.92159 25.43557 -25.08009 8.6793 43.80288 -37.79276 8.57469 25.87788 -38.3259 7.55097 26.86639 -26.17513 7.44804 44.56965 -38.86015 6.57738 27.71237 -27.08917 6.01347 45.20966 -39.6272 5.08638 28.24948 -27.79724 4.41473 45.70546 -40.18956 3.4651 28.64325 -7.71932 9.42093 43.85449 -6.7816 8.39193 43.19789 -12.98907 3.1e-4 47.54441 -5.94083 7.17651 42.53286 -3.90136 3.1e-4 41.24137 -3.9784 -2.99969 41.23506 -3.9784 -10.99969 41.23506 -16.99974 -10.99969 50.35271 -17.49796 -10.95803 50.70156 -17.99345 -10.83033 51.04851 -18.44906 -10.62637 51.36753 -18.85875 -10.35427 51.65439 -9.879713 11.00031 45.3672 -8.75665 10.29449 44.58083 -19.22317 -10.01373 51.90957 -19.54042 -9.59498 52.13171 -19.7899 -9.101963 52.30641 -19.94936 -8.547183 52.41805 -10.53331 -10.99969 33.61712 -10.39859 0.006929934 33.55042 -11.19383 6.33192 34.07963 -10.50889 4.72718 33.60003 -13.11352 9.0764 35.4238 -14.30466 10.15367 36.25786 -19.54399 3.1e-4 39.92647 -12.06864 7.79271 34.69217 -19.55254 -11.00203 39.92437 -21.00856 -10.85341 40.95197 -22.44876 -10.41244 41.96041 -23.8161 -9.68477 42.91783 -25.0408 -8.75295 43.74733 -26.18835 -7.46677 44.55593 -27.15089 -5.95878 45.22414 -27.9874 -3.99307 45.73754 -5.21253 5.84098 42.12602 -4.69914 4.61927 41.82666 -9.84612 3.17395 33.60003 -4.37969 3.41569 41.53367 -4.11728 2.24397 41.40828 -9.454153 1.59322 33.60003 -4.0032 1.10051 41.28576 -9.21055 0.02210998 33.70506 -2.66889 -10.99969 58.10774 -0.27107 -10.99969 68.60695 11.95373 -10.99924 54.07261 14.65039 -10.99969 57.10166 11.26303 -11.00247 52.76605 10.93462 -11.00078 51.02588 10.92849 -10.99944 49.00001 11.21852 -10.99969 46.78524 11.69197 -10.99969 44.64638 12.28615 -10.99969 42.55488 8.89405 -10.99969 39.42825 -9.148612 -11.00002 33.85217 5.89719 -10.99969 35.93081 -9.23438 -10.99969 31.98067 -30.48229 -11.00002 24.31039 9.64666 -11.7272 34.63953 9.14133 -11.1812 36.89915 -9.14059 -2.99969 33.86269 -9.5621 -11.00002 33.51436 -9.72471 0.009139955 33.46122 -10.03276 -11.00002 33.42926 -18.49975 11.00032 3e-5 -21.19975 10.85058 -1.8088 -21.19975 11.00032 3e-5 -18.5 10.34273 -3.49771 -21.19975 10.40543 -3.5684 -21.19975 9.67698 -5.23087 -18.49975 8.534933 -6.93974 -21.19975 8.68505 -6.75093 -17.79844 10.99998 -0.002489984 -16.91649 9.68695 -3.50188 -15.54072 8.754961 -0.6660799 -15.55918 8.56459 -0.96403 -15.88354 9.44507 -0.80489 -21.20026 0.001449823 11.01394 -21.28766 0.02173 11.85505 -21.20044 10.99998 11.01762 -2.29975 4.68862 -0.95292 -2.59805 5.3017 -0.25482 -3.21332 9.000741 0.005569994 -2.55236 8.99997 -0.30387 -3.19026 5.3014 0.004939973 -3.30688 9.55089 0.05248987 -2.59264 9.78984 -0.1526499 -3.3059 10.27285 0.43032 -2.69517 11.00598 1.04606 -3.30505 10.99998 1.06113 -15.92924 10.33615 0.42254 -16.47413 10.36967 0.38119 -17.279 10.99998 1.29354 -16.91968 10.57752 -0.002319872 -14.65761 8.99585 -0.002359986 -14.94063 8.91659 -0.05849999 -15.34548 9.84637 0.19979 -15.65766 9.70758 -0.002089977 -15.17003 8.858922 -0.1529999 -15.94733 9.65974 -0.31976 -15.33845 8.81154 -0.32356 -15.48324 8.770523 -0.51661 -14.58253 7.93702 -0.006569862 -14.53943 8.47437 5e-4 -15.08167 7.9332 -0.17254 -15.41384 7.93282 -0.57846 -15.49975 7.93757 -0.99997 -14.58696 5.3001 0.005089998 -15.24522 5.30287 -0.29855 -15.49562 5.30014 -0.88208 -15.90167 8.695611 -3.82645 -15.49975 7.62971 -2.40672 -15.49975 7.07219 -3.74012 -15.90167 6.98317 -6.44123 -15.49975 6.28421 -4.951 -17.00111 7.33618 -7.64988 -15.49975 5.29115 -6.00057 -18.49975 7.30819 -8.22159 -15.90167 4.51484 -8.35875 -15.49975 4.1255 -6.85437 -17.00111 4.69491 -9.50243 -18.49975 5.89133 -9.28954 -18.49975 4.3212 -10.1158 -15.49975 2.82533 -7.48457 -15.90167 1.55781 -9.37144 -15.49975 1.43289 -7.87066 -17.00111 1.61866 -10.47455 -18.49975 2.63864 -10.6789 -18.49975 0.8875 -10.96415 -15.49975 -0.005999982 -7.99997 -15.90167 -1.56781 -9.36966 -17.00111 -1.60754 -10.47618 -21.19975 7.45665 -8.08719 -21.19975 6.02522 -9.20327 -21.19975 4.42972 -10.06875 -21.19975 2.71362 -10.66008 -21.19975 0.92363 -10.96116 -18.49975 -0.88677 -10.96415 -2.29975 -1.19968 -0.99998 -21.19975 -10.99968 12.00002 -21.19975 -10.99968 2e-5 -21.19975 -10.8493 -1.81266 -21.19975 -10.40283 -3.5741 -21.19975 -9.67123 -5.24033 -21.19975 -8.67606 -6.76166 -21.19975 -7.44421 -8.098073 -21.19975 -6.00708 -9.2147 -21.19975 -4.40793 -10.07804 -21.19975 -2.68749 -10.66654 -15.49975 0.08439999 -0.89748 -15.49975 -7.07442 -3.73469 -15.5383 -5.19961 -0.8982599 -15.49975 -7.63069 -2.40159 -15.49975 -6.28827 -4.94504 -15.49975 -5.2969 -5.99493 -15.49975 -4.13314 -6.84939 -15.49975 -2.83463 -7.48083 -15.49975 -1.44397 -7.86852 -21.19975 -0.89245 -10.96369 -15.54911 -8.07651 -0.98456 -18.5 -10.25767 -3.32629 -18.49975 -10.97317 -0.76319 -18.49975 -10.99968 2e-5 -18.49975 -8.53429 -6.93975 -18.49975 -7.30755 -8.22159 -18.49975 -5.89069 -9.28953 -18.49975 -4.32055 -10.11582 -18.49975 -2.63804 -10.67889 -17.27788 -10.65702 5e-5 -17.36909 -10.78195 0.7220001 -17 -9.92136 -3.43188 -16.07855 -9.68662 -0.56019 -16.69233 -10.37179 0.09990996 -15.90167 -8.69931 -3.81658 -17 -9.28786 -5.08862 -15.90167 -6.98984 -6.43329 -17.00111 -7.32789 -7.65721 -15.90167 -4.52369 -8.35361 -17.00111 -4.68476 -9.507122 -2.25981 -2.41399 0.05524986 -2.28917 -2.16863 9.28614 -1.91132 -2.18628 8.70037 -2.29975 -1.64968 10.00002 -2.30004 -11.00044 14.49994 -17.60893 -10.97441 1.55587 -2.29975 -10.99968 2.00002 -2.0171 -6.48071 8.789113 -2.29892 -6.49807 9.48269 -14.49975 -6.33126 2e-5 -3.29975 -5.19968 2e-5 -14.66082 -7.92152 0.001859903 -14.67584 -8.98036 -0.002439916 -2.29975 -8.99968 2e-5 -2.29975 -10.90406 1.38901 -2.29975 -10.61666 0.823 -2.29975 -10.17759 0.38369 -2.29975 -9.61116 0.09578996 -15.35954 -9.81387 0.16857 -16.29393 -10.41649 0.56217 -16.80311 -10.67837 0.91534 -15.30478 -8.81331 -0.28649 -15.68901 -9.705801 -0.04807984 -15.13338 -7.93045 -0.23262 -15.10497 -5.20571 -0.14485 -30.79928 10.99949 11.01068 -30.79975 11.00032 3e-5 -33.79974 11.00032 3e-5 -33.8092 11.00183 14.35476 -29.84198 10.99384 11.99814 -30.59873 10.98676 11.61281 -36.79974 -0.007789969 -7.99997 -36.79974 -1.3974 -7.87692 -36.79974 1.38282 -7.87961 -36.79974 2.73173 -7.51924 -36.79974 -2.74417 -7.51448 -36.79974 3.99724 -6.92995 -36.79974 -4.00772 -6.92353 -36.79974 5.14114 -6.12957 -36.79974 -5.14931 -6.12217 -36.79974 6.12841 -5.14259 -36.79974 -6.13455 -5.1345 -36.79974 6.92918 -3.99882 -36.79974 -6.93295 -3.99119 -36.79974 7.5187 -2.73382 -36.79974 -7.52079 -2.72632 -36.79974 7.87958 -1.38462 -36.79974 -7.88005 -1.37829 -36.79974 -7.99968 3e-5 -36.79974 8.00032 3e-5 -36.81443 -0.008089959 12.38541 -36.7967 3.53228 12.70871 -36.79967 7.1347 13.80731 -36.79974 8.00032 14.3549 -30.79856 -11.00002 11.02335 -30.79975 -10.99968 2e-5 -30.79975 -10.84952 -1.81135 -30.79975 10.85039 -1.80992 -30.79975 10.40469 -3.57055 -30.79975 -10.40324 -3.57293 -30.79975 9.67536 -5.23386 -30.79975 -9.67312 -5.23683 -30.79975 8.68226 -6.75451 -30.79975 -8.67907 -6.7578 -30.79975 7.45247 -8.091053 -30.79975 -7.44809 -8.0945 -30.79975 6.01951 -9.207001 -30.79975 -6.0136 -9.210453 -30.79975 4.42244 -10.07195 -30.79975 -4.41473 -10.07506 -30.79975 2.70481 -10.66232 -30.79975 -2.69563 -10.66448 -30.79975 -0.9032 -10.9628 -30.79975 0.91344 -10.962 -22.15526 0.007359862 11.99912 -29.86834 -11.00002 11.99651 -22.16006 10.99998 11.99842 -33.79974 -10.99968 2e-5 -33.79974 -10.47466 -3.49998 -33.79974 -8.52034 -6.95688 -33.79974 -7.29403 -8.233592 -33.79974 -5.87881 -9.29706 -33.79974 -4.31131 -10.11976 -33.79974 -2.63219 -10.68033 -33.79974 -0.88477 -10.9643 -33.79974 0.88549 -10.9643 -33.79974 2.63279 -10.68033 -33.79974 4.31196 -10.11974 -33.79974 5.87945 -9.29706 -33.79974 7.29467 -8.233592 -33.79974 8.52097 -6.95687 -33.8 10.20262 -3.50126 -33.79974 10.9746 -0.75178 -35.3938 10.77261 21.17249 -36.64715 -8.81307 26.97617 -38.85982 -6.57728 27.71215 -37.5093 -8.97024 25.36489 -35.21536 -9.8805 25.97361 -35.78766 -10.70378 22.41514 -33.65039 -10.60402 24.87781 -34.58218 -10.99969 19.69901 -38.93689 7.18572 20.70183 -38.32103 7.12673 19.06551 -39.02973 4.63813 17.88106 -39.97427 3.83272 18.59788 -38.75257 2.72742 17.02578 -40.5415 5.53276 21.42248 -38.65963 8.35522 23.49712 -40.50451 5.92099 24.8554 -38.76624 8.03745 24.72672 -40.83186 2.04116 19.19836 -38.70994 -0.01001 16.61259 -41.76626 2.94589 22.28006 -41.63396 3.10566 25.64625 -40.53284 1.75501 28.88361 -42.0234 0.007079899 25.91894 -42.19225 0.003619909 22.57835 -40.64822 8e-5 28.96441 -41.12955 -0.001779854 19.4068 -41.63728 -3.09212 25.64857 -40.53275 -1.75507 28.88355 -40.1894 -3.46507 28.64313 -41.7681 -2.93905 22.28136 -40.83067 -2.04447 19.19753 -38.65361 -2.75281 16.8334 -40.51082 -5.90924 24.85982 -39.62696 -5.08633 28.2493 -40.34552 -5.52707 21.42492 -39.97205 -3.83528 18.59632 -39.45963 -7.33046 24.22606 -38.99642 -6.80644 20.06094 -38.64497 -5.09668 17.59839 -38.54078 -6.84553 19.16336 -36.85474 -6.9e-4 12.8662 -36.8276 6.8699 14.41477 -37.17046 8.97825 18.0813 -36.94878 0.001249969 13.50854 -36.88181 3.44134 13.53781 -37.07059 8.2e-4 13.92412 -36.99055 6.43146 15.16721 -37.03085 3.32365 14.13068 -37.36453 4.3e-4 14.74741 -37.29959 8.25182 17.84789 -37.22893 3.20819 14.71189 -37.27509 6.01377 15.88424 -37.49868 3.09749 15.26971 -37.46149 8.891921 19.55739 -38.01134 -0.00702995 15.81522 -37.57735 5.71607 16.39532 -37.59179 7.81341 18.2093 -37.81487 2.99184 15.80115 -37.87581 8.755083 20.77565 -37.72676 9.17571 21.4162 -37.93076 5.43082 16.88496 -37.93949 7.38716 18.56075 -38.15658 8.820611 23.43726 -38.32058 2.86247 16.45829 -38.2977 8.201622 20.9743 -38.35055 5.17675 17.32112 -38.23787 8.66316 24.26988 -37.87741 8.8285 25.0882 -36.39843 -9.49824 3e-5 -36.69753 -8.776143 3e-5 -36.39861 -8.92548 -3.2487 -35.29974 -10.59776 2e-5 -35.92107 -10.121 2e-5 -36.39861 -7.27606 -6.10558 -35.29974 -7.48949 -7.49811 -36.39861 -4.749 -8.22603 -35.29974 -4.80793 -9.44454 -36.39861 -1.6491 -9.35431 -35.29974 -1.65636 -10.46776 -35.29974 1.65716 -10.46773 -36.39861 1.64974 -9.35431 -35.29974 4.80872 -9.44447 -36.39861 4.74964 -8.22603 -35.29974 7.49025 -7.49798 -36.39861 7.2767 -6.10558 -35.3 9.697001 -3.48608 -36.39861 8.92612 -3.2487 -36.72453 8.667881 3e-5 -36.47666 9.34764 -0.001729965 -36.14523 9.87079 3e-5 -35.67022 10.34581 3e-5 -35.1956 10.63941 -0.001009941 -34.46731 10.9251 3e-5 -34.93652 10.77807 14.35294 -35.58376 10.41524 14.35461 -36.21264 9.77333 14.35913 -36.54551 9.21337 14.35889 -36.74974 8.524291 14.35804 -35.6876 10.6461 18.53472 -36.53004 10.03759 18.28291 -36.51375 10.32512 21.99281 -36.95128 10.04975 21.78613 -37.3879 9.676671 21.55382 -30.54963 -11.00002 11.66705 -33.79976 -10.99968 14.35432 -36.80211 -3.57614 12.74256 -36.83413 -6.80393 14.48794 -36.79083 -7.04813 13.76283 -36.79802 -8.00355 14.36797 -36.85308 -8.2511 15.52943 -36.85374 -3.46387 13.32598 -36.98067 -3.33462 13.98191 -36.94965 -8.4689 16.47709 -36.98058 -6.44915 15.09954 -37.2118 -8.51306 17.67781 -37.17058 -6.12276 15.66232 -37.26193 -3.17345 14.8002 -37.16951 -8.873743 17.99794 -37.42837 -9.10094 19.63637 -37.50796 -5.75593 16.295 -37.6075 -7.75384 18.23821 -37.65326 -3.02726 15.54316 -37.73828 -9.155611 21.34813 -37.91945 -5.4259 16.86416 -38.33669 -8.166501 21.07709 -38.10238 -2.90063 16.18634 -38.15025 -7.1699 18.72193 -38.72624 -8.31356 23.17016 -38.38188 -5.17725 17.33244 -38.70362 -7.76277 21.09307 -38.28183 -8.521121 24.55593 -36.79264 -10.16235 21.86772 -35.07729 -10.92664 19.09571 -35.45325 -10.78913 18.5133 -35.89947 -10.55703 18.41647 -37.38953 -9.68077 21.55747 -36.47078 -10.08791 18.29239 -37.06798 -9.19611 18.17723 -34.48074 -10.91786 14.35774 -34.03627 -10.99969 16.91243 -34.34378 -10.99937 17.05174 -35.15562 -10.66385 14.35446 -35.06882 -10.81567 16.93252 -35.53715 -10.59231 16.85391 -35.98821 -10.04511 14.3575 -36.15683 -10.12153 16.75029 -36.41797 -9.45354 14.35341 -36.76658 -9.26479 16.64904 -36.69753 -8.77615 14.35433 -34.57621 -10.89746 2e-5 -35.29974 -9.68938 -3.36008 -33.88254 11.00032 15.89549 -34.0911 11.00032 17.35025 -1.46361 -10.99969 21.00948 -2.29974 -10.99968 17.78293 -2.29974 -11.00234 16.69962 -1.44589 -11.04272 16.30639 -2.29974 -1.03093 14.50002 -2.23293 3.2e-4 15.05038 -2.29974 3.2e-4 14.50002 -21.4021 10.99998 11.61422 12.5312 -10.58549 31.98531 16.64741 -13.38308 33.52113 22.43384 -2.43179 35.4638 21.78853 -2.89039 34.14166 22.43384 3.1e-4 35.4638 21.65439 3.1e-4 33.81064 21.3357 -3.4036 32.89512 21.10985 3.1e-4 32.06595 20.99578 -4.04728 31.53899 25.44507 -0.81405 36.97453 24.712 -1.22857 36.9809 25.15811 0.01659995 37.00175 24.26314 3.1e-4 36.89455 24.0104 -1.59847 36.81344 23.7072 3.1e-4 36.68168 23.36963 -1.92981 36.48375 23.20424 3.1e-4 36.36323 22.83476 -2.21207 36.02045 22.77413 3.1e-4 35.9518 26.92183 -0.003519952 36.82516 12.68278 -11.1535 40.6564 13.08471 -11.72125 38.31505 13.47464 -12.60679 36.32715 10.92894 -12.52152 33.74554 15.06748 -11.44301 37.1727 14.52405 -12.49547 36.58099 15.31516 -11.79939 36.40389 14.12754 -11.52959 38.50731 14.0189 -12.66681 36.52953 14.81115 -11.12672 38.0273 14.54371 -10.86076 38.96343 13.74406 -10.89054 40.62273 14.26397 -10.65805 39.96037 13.97252 -10.5293 40.97764 13.67023 -10.47681 41.968 13.28852 -10.5106 43.04077 12.63184 -10.60558 45.06305 12.07336 -10.70185 47.10023 11.36593 -10.94797 48.99927 11.70368 -10.78236 49.00006 16.57858 -9.282813 32.1871 15.60446 -9.66423 32.83175 16.32271 -8.59969 32.43644 16.27308 -8.07461 32.48607 15.75026 -8.074603 32.90342 15.16408 -8.074603 33.18879 14.55059 -10.15569 32.96592 14.52727 -8.074603 33.34115 13.86319 -8.074603 33.35082 13.46548 -10.48407 32.67463 13.19649 -8.074603 33.20858 12.57363 -8.074603 32.9161 15.74787 3.1e-4 32.90491 15.14261 3.1e-4 33.19639 14.48767 3.1e-4 33.34588 13.81588 3.1e-4 33.34588 13.16094 3.1e-4 33.19639 12.55568 3.1e-4 32.90491 14.00826 -13.53416 34.81597 16.81638 -15.27418 32.40682 15.12647 -14.0356 34.29336 15.84711 -13.60443 34.37607 15.89327 -12.56954 34.95239 11.73357 -10.92608 52.60124 11.55999 -10.87983 50.93766 12.53987 -10.94118 54.14971 14.98376 -10.93201 56.80618 17.00939 -11.00269 59.61676 22.76087 -10.99969 67.55108 26.29809 -10.03401 67.5 23.7424 -11.00002 68.4587 27.24411 -11.00002 70.83822 27.47768 -10.76175 70.15975 30.11902 -10.68794 71.44342 31.13271 -10.95601 72.55889 28.51817 -10.99969 71.69501 30.14903 -10.99969 72.51252 31.98543 -10.99969 73.29705 18.99706 -11.00134 62.1765 20.79791 -11.00002 64.63759 22.00057 -11.00002 66.67691 24.42076 -4.89193 45.53319 22.39955 -4.32243 42.36771 20.36497 -6.03566 44.81445 17.58012 -7.99503 48.14511 14.72139 -9.78387 51.55352 18.00202 -9.761631 55.00234 25.00082 -8.35501 56.99505 27.6925 -4.34221 46.92803 31.1672 -3.36012 47.48283 33.25978 3.1e-4 41.06783 15.86816 -8.3623 46.51122 20.13634 -4.13406 40.55924 14.39754 -9.204483 44.82517 18.38548 -6.26749 37.94863 17.21881 -8.33919 35.85539 16.77633 -10.93123 34.08899 4.37943 10.99998 41.38833 41.68114 3.11934 88.42472 41.68114 5.63812 90.39955 41.13099 3.312 88.37461 41.13099 5.74386 90.32435 37.7384 11.1753 88.8843 38.76384 7.94142 90.03388 37.95638 7.94142 89.22799 39.76155 5.63631 88.40637 40.51579 10.27552 97.62239 40.07596 9.96326 98.56784 41.37939 9.46742 96.43927 39.99857 10.43204 98.33806 40.57038 8.64119 95.29342 41.22685 8.93964 95.8138 40.70426 9.2523 97.00844 41.37984 8.73646 95.12654 39.74244 11.04698 96.20256 39.84858 11.04698 95.04393 38.24878 11.49697 95.45497 38.00381 11.49697 96.64929 39.39767 11.04699 97.44501 37.49107 11.49697 97.75499 38.76131 11.04699 98.70365 41.59571 8.83116 95.13356 41.2131 9.19201 96.43332 41.74747 9.009303 95.10453 41.8014 9.23127 95.04592 41.27328 9.94482 96.26662 41.7521 9.44767 94.97078 38.71717 10.68463 99.7013 38.0911 10.75973 100.2209 38.28223 10.27446 100.3477 37.96762 9.87593 100.1751 38.56969 9.8037 99.67538 39.20652 9.69696 99.05484 39.37949 10.57362 99.05593 39.80162 9.560873 98.36477 40.29893 9.41038 97.67668 40.93732 10.11112 96.92743 41.27329 10.02495 95.04329 39.91544 8.54095 95.21244 36.29012 9.10508 98.62049 37.81296 11.04698 99.873 39.37206 7.94142 90.84272 39.81881 7.94142 91.62484 40.13819 7.94142 92.36641 40.35844 7.94142 93.06499 41.13102 7.19214 93.23298 42.00056 7.30184 92.4242 42.00056 6.94657 91.57982 42.00056 6.38827 90.62459 42.00056 8.25571 93.05318 42.00056 7.7061 93.46572 37.11908 11.39697 89.68384 38.34981 11.34554 91.02043 39.50283 11.01932 91.70684 39.34713 11.17865 92.9042 38.87627 11.27726 91.90458 39.77678 11.04697 94.01065 41.55681 8.56278 94.71521 40.94661 8.50667 94.93193 41.33031 8.34255 94.60556 41.92306 8.79775 92.93055 41.80856 9.3299 94.73648 41.67596 7.07942 93.26065 41.80298 7.58719 93.89461 38.02941 11.49697 93.17299 38.21304 11.49697 94.23915 37.79654 11.49697 92.22731 37.12631 8.496973 90.33946 37.7612 8.496973 90.99005 38.24058 8.496973 91.64044 38.59385 8.496973 92.26857 38.84736 8.496973 92.86425 39.02299 8.496973 93.42589 40.72712 7.83903 94.26452 40.49448 7.94157 93.72605 41.37669 7.53031 93.96105 41.69064 8.16196 94.33181 39.58928 8.496973 95.04093 39.37226 8.49544 94.56347 39.13748 8.496973 93.95772 41.7727 8.656373 94.6345 41.94539 8.88449 94.20365 41.9566 8.2694 94.08396 41.98137 8.653963 94.05004 41.99392 8.3286 93.39334 25.58867 1.43357 87.00081 24.87012 1.27291 87.70231 24.87012 -0.003029823 87.59163 25.15486 -0.003029823 87.29075 25.45073 -0.003029823 87.00081 24.87012 2.37196 87.98259 25.99651 2.81535 87.00081 26.6527 4.08412 87.00081 25.33635 4.10292 88.26278 24.87012 4.09936 88.83101 27.50056 5.99697 87.00081 26.1579 6.16047 88.98506 28.00056 6.96932 88.11705 28.00056 7.74294 89.00081 27.50056 7.94142 89.74383 35.42382 7.14735 87.00081 34.05057 7.94142 87.46534 34.05057 7.47344 87.00081 35.60876 7.94142 87.85357 36.69345 6.582 87.00083 36.91229 7.94142 88.47516 37.99923 5.63255 87.00083 38.95287 4.64133 87.00083 39.93123 2.916 87.00083 40.36637 1.65375 87.00083 40.5504 -0.003029823 87.00083 40.84626 -0.003029823 87.29077 41.13099 -0.003029823 87.59163 41.13099 1.27351 87.70243 41.13099 2.37288 87.98291 28.00056 8.496973 87.00081 31.96557 8.496973 87.00081 28.00056 8.496973 89.00081 30.09208 11.39697 88.93673 28.26272 11.26217 88.8843 31.49381 11.39697 88.44628 33.00006 11.39697 88.27532 34.50645 11.39697 88.44607 35.13641 10.99697 85.43849 37.16936 10.99697 86.13395 35.90857 11.39697 88.9365 24.31998 3.11935 88.42472 24.32517 -0.003029823 87.70771 24.05718 -0.003029823 87.48596 24.21422 -0.003029823 87.66474 24.43612 -0.003029823 87.75068 24.6726 -0.003029823 87.72432 41.56501 -0.003029823 87.75068 41.7869 -0.003029823 87.66474 41.94394 -0.003029823 87.48597 41.32852 -0.003029823 87.72432 33.00057 11.49528 88.98594 34.05057 8.496973 88.86506 35.28151 8.496973 89.20881 34.03556 8.496973 87.00081 24.87013 -8.00303 87.59163 25.09139 -9.0346 87.35697 25.63093 -9.82743 86.83525 25.45073 -4.00303 87.00083 26.38597 -10.3084 86.21868 27.08407 -4.00303 85.72747 27.26143 -10.50303 85.61666 28.3819 -10.50303 85.01744 28.11167 -9.00303 85.14695 28.47897 -9.4878 84.9731 28.11167 -6.00303 85.14695 28.58706 -5.67444 84.92507 28.92677 -5.46536 84.78298 28.93422 -4.00303 84.78002 29.25148 -5.29607 84.65947 28.9567 -10.02226 84.77111 29.55905 -10.49865 84.5542 29.72197 -5.11393 84.50078 30.4356 -5.00303 84.30406 30.93008 -4.00303 84.19744 32.1382 -5.00303 84.03469 33.00057 -4.00303 84.00083 33.86293 -5.00303 84.03469 35.07105 -4.00302 84.19744 35.56553 -5.00302 84.30406 36.24842 -5.10488 84.49124 36.85765 -5.34857 84.69922 37.06691 -4.00302 84.78002 37.39911 -5.66466 84.91852 38.7397 -10.50303 85.61666 37.88945 -6.00302 85.14695 37.88945 -9.00303 85.14695 37.61948 -10.50303 85.01755 38.91706 -4.00302 85.72747 39.68599 -10.5013 86.22204 40.35194 -9.84937 86.81808 40.5504 -4.00302 87.00083 40.90894 -9.0365 87.35614 41.13099 -8.00303 87.59163 30.96395 -5.00303 84.67029 35.03717 -5.00302 84.67029 31.4016 -5.00303 85.13996 34.59953 -5.00303 85.13996 31.72967 -5.00303 85.69278 34.27146 -5.00303 85.69278 31.93231 -5.00303 86.30226 34.06882 -5.00303 86.30226 32.00057 -5.00303 86.93856 34.00057 -5.00303 86.93856 33.00057 -10.00303 85.00083 33.00057 -10.00303 85.40252 31.33445 -10.00303 85.05361 31.61989 -10.00303 85.47597 33.00057 -10.00303 85.74328 31.82955 -10.00303 85.94014 33.00057 -10.00303 86.01088 34.04364 -10.00303 86.43206 31.95749 -10.00303 86.43202 34.00057 -10.00303 86.93856 32.00057 -10.00303 86.93856 37.41134 -6.00302 84.98121 37.41122 -9.00303 84.98118 36.90551 -6.00302 84.94082 36.90544 -9.00303 84.94084 36.40688 -6.00302 85.02871 36.40681 -9.00303 85.02874 35.94649 -6.00302 85.23889 35.94644 -9.00303 85.23892 35.5536 -6.00302 85.55789 35.55355 -9.00303 85.55793 35.25326 -6.00302 85.96547 35.25317 -9.00303 85.96562 35.0646 -6.00302 86.43654 35.06454 -9.00303 86.43677 35.00057 -6.00302 86.93856 35.00057 -9.00303 86.93856 28.58979 -9.00303 84.98121 28.58979 -6.00303 84.98121 29.09562 -9.00303 84.94082 29.09562 -6.00303 84.94082 29.59425 -9.00303 85.02871 29.59425 -6.00303 85.02871 30.05464 -9.00303 85.23889 30.05463 -6.00303 85.23889 30.44753 -9.00303 85.55789 30.44753 -6.00303 85.55789 30.74787 -9.00303 85.96547 30.74787 -6.00303 85.96547 30.93653 -9.00303 86.43654 30.93653 -6.00303 86.43654 31.00056 -9.00303 86.93856 31.00056 -6.00303 86.93856 30.28887 -5.29592 85.04183 31.02681 -5.29592 85.86539 31.29344 -5.29593 86.93856 31.07668 -5.62035 86.93856 31.61786 -5.07915 86.93856 36.74865 -5.30497 84.66201 35.71718 -5.29592 85.03849 34.97572 -5.29592 85.86277 34.38325 -5.07915 86.93856 34.70768 -5.29592 86.93856 34.92445 -5.62034 86.93856 28.79139 -9.246253 84.91934 29.54059 -9.511981 84.86864 30.07767 -9.70493 84.92412 30.96474 -9.71013 85.7556 31.02918 -9.982002 85.01441 30.74658 -9.92569 84.99267 30.4782 -9.84499 84.9712 31.61788 -9.92691 86.93856 31.29346 -9.71013 86.93856 31.07668 -9.38571 86.93856 24.67261 -8.00303 87.72432 24.43612 -8.00303 87.75068 24.21422 -8.00303 87.66474 24.05718 -8.00303 87.48597 41.3285 -8.00302 87.72431 41.56498 -8.00302 87.7507 41.78688 -8.00302 87.66475 41.94394 -8.00302 87.48597 38.77465 -10.75303 85.55951 40.47097 -9.98157 86.87934 41.13404 -9.193263 87.46949 39.76203 -10.62444 86.18592 40.69175 -10.17119 86.83069 41.38859 -9.29184 87.43207 38.86145 -10.9194 85.41758 40.84677 -10.23448 86.72433 41.68918 -9.29155 87.14128 39.99669 -10.79865 85.9662 27.131 -10.93604 85.40339 29.47736 -10.85658 84.42583 27.21588 -10.77336 85.54217 31.95056 -10.85241 83.89984 33.00057 -10.6697 84.02233 30.52545 -10.61703 84.28743 33.00057 -10.97928 83.70178 34.05057 -10.85241 83.89984 36.52377 -10.85658 84.42583 24.91575 -9.16382 87.46038 26.28875 -10.54603 86.2146 25.42461 -10.08604 86.87477 24.71859 -9.25626 87.46589 26.16107 -10.70809 86.13066 25.2418 -10.2036 86.79393 24.53492 -9.30571 87.39328 26.00711 -10.79692 85.97328 25.07019 -10.24095 86.64248 24.36523 -9.30825 87.23494 33.00057 -10.40319 84.16567 31.21358 -10.32127 84.33208 33.00057 -10.18686 84.38906 31.26853 -10.1721 84.6602 33.00057 -10.04902 84.66846 37.21085 -9.246253 84.91934 37.52327 -9.4878 84.9731 37.04554 -10.02226 84.77111 36.46165 -9.511981 84.86864 36.4432 -10.49865 84.5542 35.92458 -9.70493 84.92412 35.52404 -9.84499 84.9712 35.47679 -10.61703 84.28743 35.25566 -9.92569 84.99267 34.97306 -9.982002 85.01441 34.73371 -10.1721 84.6602 34.78867 -10.32127 84.33208 34.66779 -10.00303 85.05361 34.92445 -9.38571 86.93856 34.70768 -9.71013 86.93856 35.03751 -9.71013 85.7556 34.38325 -9.92691 86.93856 34.17269 -10.00303 85.94014 34.38235 -10.00303 85.47597 34.00057 -5.00303 93.26877 32.00057 -5.00303 93.26877 34.23295 -5.00303 94.09375 32.37708 -5.00303 94.21898 32.77805 -5.00303 94.0259 33.22309 -5.00303 94.0259 33.62406 -5.00303 94.21898 31.63453 -5.07242 94.00083 34.27405 -5.02203 94.5056 32.0996 -5.00303 94.56694 33.90154 -5.00303 94.56694 31.83087 -5.00303 94.92147 34.17026 -5.00303 94.92148 32.00057 -5.00303 95.00083 34.00057 -5.00303 95.00083 34.08618 -5.00303 95.44345 31.92156 -5.00303 95.45932 33.86829 -5.00303 95.49787 32.13484 -5.00303 95.50135 33.50329 -5.00303 95.86528 33.76625 -5.00303 95.88864 32.24623 -5.00303 95.8983 32.50175 -5.00303 95.86753 33.00279 -5.00303 96.00081 33.28202 -5.00303 96.13891 32.7353 -5.00303 96.1428 35.00057 -9.00303 94.00083 35.00094 -6.00302 94.00081 31.00056 -9.00303 94.00083 31.00056 -6.00303 93.96101 31.30198 -5.28749 94.00083 31.07899 -5.61481 94.00083 31.0055 -6.00303 94.1412 34.4322 -5.1104 94.23588 34.69915 -5.28749 94.00083 34.92214 -5.61481 94.00083 34.86658 -9.50305 94.00083 34.50055 -9.869071 94.00083 34.00057 -10.00303 94.00083 32.00057 -10.00303 94.00083 31.50056 -9.86905 94.00083 31.13453 -9.50303 94.00083 31.26325 -5.33823 94.1848 31.07251 -5.64578 94.15258 34.73787 -5.33821 94.18481 34.92861 -5.64577 94.15258 31.18788 -5.27567 95.41165 30.89816 -5.9457 95.54119 31.8406 -5.27567 96.45308 31.67032 -5.9457 96.71621 33.00056 -5.9457 97.17156 33.00056 -5.27567 96.85948 34.33081 -5.9457 96.71621 34.16051 -5.27567 96.45308 35.10297 -5.9457 95.54119 34.81324 -5.27567 95.41165 34.00057 -10.00303 95.50083 32.00057 -10.00303 95.50083 35.10297 -8.9457 95.54119 30.89816 -8.9457 95.54119 31.67032 -8.9457 96.71621 33.00056 -8.9457 97.17156 34.33081 -8.9457 96.71621 24.87012 5.2965 89.82287 27.50056 8.496973 92.08535 28.88205 11.39697 89.68384 24.31998 5.63814 90.39956 30.26184 11.49697 89.71026 31.3016 11.49697 89.29082 26.6541 11.17867 92.90397 26.49829 11.01932 91.70685 27.65125 11.34554 91.02054 24.37461 9.636343 95.45105 24.19308 9.23127 95.04592 24.6186 9.77928 96.36007 24.24902 9.44767 94.97078 24.8701 7.19214 93.23297 25.26737 7.83903 94.26452 24.61778 7.53031 93.96105 24.30384 8.16196 94.33181 24.67039 8.34236 94.60522 25.43079 8.64121 95.29347 26.07904 8.54095 95.21244 26.62222 8.49544 94.56346 24.44224 8.559863 94.71041 24.61463 8.73646 95.12652 24.247 9.009303 95.10453 24.22178 8.656373 94.6345 24.04909 8.88449 94.20365 24.17456 9.29202 94.66218 24.14427 8.20532 94.23194 29.8249 8.6999 97.51353 33.00056 8.55728 98.13482 29.711 9.10508 98.62049 26.88909 7.94142 90.46917 26.4198 7.94142 91.18251 26.06698 7.94142 91.86851 27.97175 11.49697 93.17279 26.22435 11.08882 94.01065 27.78809 11.49697 94.23915 28.20463 11.49697 92.22714 27.12495 11.27728 91.90441 28.50539 11.49697 91.41564 28.88949 11.49697 90.7632 29.35241 11.49697 90.29109 29.39829 11.04698 100.825 30.76811 11.04697 101.4749 30.42106 11.49197 99.79165 30.72988 11.48798 100.0102 30.2146 11.49697 99.47166 28.19325 11.04699 99.87802 29.26237 11.49697 98.71241 27.24331 11.04699 98.70907 28.51005 11.49697 97.75497 26.6052 11.04699 97.4496 27.9973 11.49697 96.64927 26.25925 11.04698 96.20579 27.75234 11.49697 95.45497 26.15255 11.04698 95.04558 30.40465 9.968563 101.5481 29.89149 10.38171 101.6682 29.13401 9.951333 100.9168 31.94006 9.968563 101.9637 31.93259 10.38028 102.2918 30.36637 10.85606 101.6447 24.97374 9.09237 96.37292 25.78238 9.4337 97.78476 24.59157 9.572001 96.42621 25.92516 9.96326 98.56782 24.72783 9.94483 96.26661 25.35801 10.22999 97.42498 25.77964 10.36962 98.04489 26.28375 10.50161 98.68008 27.71889 10.27446 100.3477 27.03176 9.74083 99.29841 27.4672 10.70933 99.86162 28.15173 9.88731 100.2647 28.03297 10.77157 100.3141 29.05452 10.83815 100.9923 24.54014 9.80788 95.89679 24.43612 7.03771 93.27092 24.1915 7.58718 93.8946 24.00056 7.87464 93.62245 24.87012 6.30682 91.12614 24.00056 8.3286 93.39332 24.72783 10.01128 94.47571 24.72783 10.0246 95.09308 24.72783 10.00166 95.68509 29.66201 9.49194 99.7704 30.45559 9.65113 100.6214 33.00057 11.49697 95.12439 33.00056 8.496973 95.00081 36.30628 8.496973 89.72613 37.11116 11.49697 90.76256 36.64871 11.49697 90.29109 37.49569 11.49697 91.41555 35.73919 11.49697 89.71022 34.6994 11.49697 89.29078 36.60886 11.04698 100.8213 36.99772 10.83605 100.9621 35.23964 11.04697 101.4726 35.57732 10.85606 101.6672 35.0466 10.85606 101.8487 33.7631 11.04697 101.8064 33.82334 10.85606 102.1003 32.24501 11.04697 101.8072 34.30502 9.65113 101.0324 35.54827 9.65113 100.6214 35.01686 9.968563 101.7492 33.81138 9.968563 101.9972 33.00053 9.65113 101.1718 36.67593 8.71842 97.57588 36.4425 9.96396 101.1531 36.33852 9.492383 99.77202 36.10963 10.38171 101.6682 34.06853 10.38028 102.2918 32.5399 10.85606 102.133 33.00056 11.48798 100.5008 35.58015 11.49197 99.79156 35.27124 11.48798 100.0102 35.78653 11.49697 99.47166 36.73875 11.49697 98.71241 34.13903 11.48798 100.3768 31.83903 11.48798 100.3768 31.34895 10.85606 101.9544 31.69602 9.65113 101.0324 9.72146 11.00031 54.88706 30.6346 10.99998 64.29273 -1.22348 10.99998 31.37401 2.1925 11.00015 12.22485 39.01376 10.99859 12.24818 -22.29964 11.0002 21.38512 -28.44713 -2.03133 46.05944 -28.60279 3.1e-4 46.16707 -28.28 2.69548 46.0435 33.00057 -5.00303 95.00083 -2.3 -12.43498 14.32028 -2.3 -12.45382 14.27587 2.3 -12.45382 14.27587 2.3 -12.43498 14.32028 2.18743 -12.13355 15.03102 -2.18743 -12.13355 15.03102 -1.860739 -11.86163 15.67219 1.351906 -11.64583 16.18102 1.012173 -11.57242 16.35412 -1.012173 -11.57242 16.35412 1.860739 -11.86163 15.67219 -1.351906 -11.64583 16.18102 2.3 10 12 -2.3 10 12 2.3 10 14.32028 -2.3 10 14.32028 -2.18743 10 15.03102 1.351906 10 16.18102 -0.7107391 10 16.50771 0.7107391 10 16.50771 0 10 16.62028 -1.860739 10 15.67219 -1.351906 10 16.18102 1.860739 10 15.67219 2.18743 10 15.03102 2.3 16.79629 9.84629 2.3 15.71331 11.5 2.3 10.5 11.5 2.3 -4.871968 -18.94158 2.3 -1.858257 -19.47126 2.3 -18.13919 -7.216807 2.3 -19.03544 -4.291101 2.3 -19.46297 -1.261211 2.3 1.201211 -19.52297 2.3 4.231101 -19.09544 2.3 7.156807 -18.19919 2.3 9.906291 -16.85629 2.3 12.41184 -15.09982 2.3 -16.79629 -9.96629 2.3 -15.03982 -12.47185 2.3 -12.91301 -14.67178 2.3 -15.33123 11.89716 2.3 -16.45193 10.40824 2.3 -17.88697 7.705715 2.3 19.41126 -1.918256 2.3 19.46297 1.141211 2.3 19.03544 4.171102 2.3 -10.46824 -16.51193 2.3 -7.765715 -17.94697 2.3 -18.88158 4.811968 2.3 -19.41126 1.798256 2.3 14.61178 -12.97301 2.3 16.45193 -10.52824 2.3 17.88697 -7.825716 2.3 18.88158 -4.931968 2.3 18.13919 7.096807 -2.3 -15.33123 11.89716 -2.3 -19.03544 -4.291101 -2.3 -19.46297 -1.261211 -2.3 -19.41126 1.798256 -2.3 -18.88158 4.811968 -2.3 -12.91301 -14.67178 -2.3 -15.03982 -12.47185 -2.3 9.906291 -16.85629 -2.3 7.156807 -18.19919 -2.3 16.79629 9.84629 -2.3 4.231101 -19.09544 -2.3 -17.88697 7.705715 -2.3 -16.45193 10.40824 -2.3 -10.46824 -16.51193 -2.3 -16.79629 -9.96629 -2.3 -18.13919 -7.216807 -2.3 1.201211 -19.52297 -2.3 -1.858257 -19.47126 -2.3 15.71331 11.5 -2.3 10.5 11.5 -2.3 -4.871968 -18.94158 -2.3 -7.765715 -17.94697 -2.3 16.45193 -10.52824 -2.3 14.61178 -12.97301 -2.3 12.41184 -15.09982 -2.3 18.13919 7.096807 -2.3 19.03544 4.171102 -2.3 19.46297 1.141211 -2.3 19.41126 -1.918256 -2.3 18.88158 -4.931968 -2.3 17.88697 -7.825716 0.7107391 -11.19262 16.50771 0 -10.91424 16.62028 -0.7107391 -11.19262 16.50771 0 10 16.62028 0 -10.91424 16.62028 0 10 16.62028 0 -10.91424 16.62028 -35.30011 -21.37407 2.664984 -35.97731 -21.20598 2.742392 -35.70959 -20.85117 1.618092 -35.02501 -20.86087 1.319399 38.11269 -16.77327 0.6647549 40.2939 -16.31673 1.727976 39.90214 -16.63072 2.221127 37.91038 -17.23445 1.797287 41.94008 -10.54336 1.578489 42.01488 -10.96195 1.451645 41.97507 -10.79425 0.8358975 41.72119 -10.58321 0.8395424 -36.81101 -7.389069 3.04854 -36.75496 -7.258225 3.157454 -36.67926 -7.313999 1.528969 -36.68202 -7.420315 1.201839 41.10294 -16.78622 4.278839 40.2374 -17.22068 4.519073 -36.58536 -7.154157 3.076866 -36.40228 -7.313403 1.168158 -36.27677 -7.157767 2.975166 -35.185 -7.531498 0.9172001 -22.81298 -8.782184 0.4782181 -20.01383 -8.669778 0.5382938 -19.81993 -8.744164 0.2190952 -24.43715 -8.720824 0.1978855 -16.09681 -8.293219 0.5968685 -16.12562 -8.446867 0.2116146 -12.84886 -8.080644 0.5868664 -12.8592 -8.182986 0.1892279 -9.338077 -8.016757 0.5790596 -9.317935 -8.080242 0.1771926 -6.337596 -8.006976 0.5768795 -6.294147 -8.060143 0.173912 -2.522725 -8.02283 0.5748329 -2.491111 -8.029642 0.5728569 -2.505342 -8.080094 0.1727465 -2.534631 -8.074892 0.1731433 13.6234 -14.85789 0.2437191 20.02013 -16.21984 0.2199363 20.85444 -16.52285 0.02615916 17.34719 -16.45209 0.03100204 41.7199 -10.48944 1.784672 40.50849 -11.12467 0.8333645 -35.75578 -20.61316 1.398182 -34.914 -20.4599 0.7471657 -33.06443 -20.41025 0.4845829 -33.22402 -20.86695 1.118732 -29.78455 -20.38779 0.395258 -29.92773 -20.84934 1.005392 -25.80159 -20.38117 0.3758431 -25.91128 -20.83986 0.9682675 -21.62747 -20.38028 0.3758526 -21.63793 -20.84203 0.9770756 -17.45075 -20.38723 0.3872757 -17.37379 -20.87199 1.023111 -13.26461 -20.4174 0.4119663 -13.14162 -20.94333 1.099493 -9.211579 -20.4849 0.4067383 -9.162447 -21.01774 1.120949 -5.891845 -20.60078 0.3765431 -5.933184 -21.09855 1.10078 5.08159 -22.30381 0.1192588 6.227774 -22.29838 0.1060276 6.069337 -22.35332 0.751709 4.871313 -22.35009 0.797905 8.589437 -22.28036 0.08058166 8.513026 -22.35177 0.6742153 11.18799 -22.2173 0.06914329 11.15043 -22.30648 0.6414452 14.75098 -21.73004 0.1048717 16.66975 -21.39739 0.1352386 16.77512 -21.63473 0.94174 14.80499 -21.89464 0.8165684 20.42124 -20.87202 0.1748484 20.5043 -21.24291 1.096138 24.30422 -20.34383 0.2137432 24.31791 -20.81227 1.23002 27.83371 -19.68346 0.2604694 27.77166 -20.19741 1.348465 31.38448 -18.78649 0.310812 31.2583 -19.31107 1.463882 34.92764 -17.74555 0.3874893 34.75664 -18.25953 1.59688 37.9792 -18.09053 4.439198 34.79686 -19.20944 4.223764 31.32444 -20.29726 3.959854 27.85016 -21.18588 3.711298 24.40685 -21.73073 3.467194 20.73389 -21.95685 3.200054 17.25472 -22.04796 2.90728 13.12774 -22.27361 2.241177 11.12869 -22.3437 2.103764 12.91604 -22.1943 0.6663036 8.193589 -22.36276 2.107037 5.44805 -22.3448 2.222803 -4.616034 -21.82497 2.57395 -6.096391 -21.79971 2.583603 -4.345522 -21.14738 1.078341 -9.120855 -21.73867 2.602667 -12.96807 -21.63535 2.611956 -17.28125 -21.50387 2.564613 -21.71512 -21.4381 2.519438 -26.13951 -21.42959 2.499756 -30.21177 -21.44248 2.53014 -33.52912 -21.44941 2.597425 7.161726 -11.42326 49.89167 6.612938 -11.26008 51.49803 5.569353 -11.2263 51.70843 5.467674 -11.36983 49.88853 1.236763 -11.21067 49.42605 1.450103 -11.17832 50.75915 1.122014 -11.17747 50.5755 0.9234281 -11.20508 49.36167 -2.998834 -11.1718 48.61708 -2.961502 -11.17248 49.74878 -3.792537 -11.17069 49.79266 -3.802937 -11.16122 48.80295 -4.478267 -11.16244 49.87395 -4.657793 -11.13532 49.09914 41.93324 -10.57216 2.857588 41.98825 -10.75702 2.74156 41.95855 -10.98351 4.509445 41.99311 -11.19508 4.467781 41.96268 -11.55174 6.514654 41.99416 -11.76373 6.487608 41.96529 -12.20895 8.647776 41.99486 -12.40609 8.603631 41.96702 -12.87652 10.7005 41.99507 -13.0395 10.66644 41.96765 -13.38439 12.22506 41.99471 -13.4834 12.26416 41.9675 -13.64232 12.953 41.99407 -13.67916 13.07407 41.9669 -13.75352 13.20258 41.994 -13.75844 13.37009 41.89118 -10.42181 2.247049 41.93331 -10.57589 3.02527 41.94048 -10.97792 4.555925 41.94424 -11.53519 6.515211 41.94771 -12.18173 8.623154 41.95024 -12.83183 10.61734 41.95156 -13.33703 12.08548 41.95181 -13.61532 12.81659 41.95069 -13.73764 13.07428 26.02302 -16.07624 0.4377651 26.3522 -16.08447 0.499691 29.84541 -15.69423 0.6405029 29.34267 -15.74365 0.5811462 26.27949 -16.13967 0.5398331 29.41123 -15.76641 0.6598072 20.14659 -16.22975 0.3196659 21.06664 -16.46275 0.3703251 13.6891 -14.86659 0.3447418 17.2593 -16.101 0.3284283 4.440995 -11.15825 0.4163571 4.604897 -11.21737 0.536789 -2.517033 -8.00352 0.8194389 -2.484516 -8.011054 0.8161965 -9.34961 -7.990362 0.8210831 -6.501586 -7.987305 0.821764 -12.47713 -8.016142 0.8150692 -14.56205 -8.099837 0.7908325 -36.62672 -7.096894 4.834517 -36.4638 -7.053176 4.826397 -36.62275 -7.14702 6.31308 -36.46748 -7.106049 6.434866 -36.59059 -7.376173 8.315487 -36.42646 -7.337852 8.49055 -36.52581 -7.731776 11.31255 -36.34142 -7.68582 11.3981 -36.39369 -7.932583 14.05481 -36.2031 -7.902624 14.0451 -36.16974 -7.988173 15.82449 -36.08687 -7.966431 15.41235 -36.78794 -7.238184 4.771656 -36.79005 -7.304385 6.22394 -36.7719 -7.528042 8.318364 -36.73683 -7.822225 11.22915 -36.65214 -7.972874 13.82385 -36.45269 -8.016242 15.58446 -36.11119 -8.042043 16.8157 -35.83333 -8.013924 17.10123 -35.56558 -8.085133 17.91298 -35.22872 -8.049141 18.27757 -34.86817 -8.15954 18.98327 -34.384 -8.110838 19.50989 -32.94842 -8.307463 21.32121 -33.41526 -8.187998 20.73011 -34.49135 -8.236886 19.49442 -33.46362 -8.301358 20.72789 -33.63431 -21.69362 4.549654 -35.40287 -21.56243 4.341482 -33.49949 -21.54011 6.201679 -35.31956 -21.36517 5.95484 -33.28257 -21.10568 7.761314 -35.16823 -20.91771 7.581161 -33.06198 -20.48688 9.445326 -35.00679 -20.31765 9.237538 -32.82676 -19.78359 11.11652 -34.84514 -19.64111 10.79299 -32.56769 -19.04952 12.64141 -34.6817 -18.92238 12.17627 -32.24787 -18.26895 14.06724 -34.48963 -18.12374 13.48506 -31.85117 -17.40155 15.50278 -34.25033 -17.19833 14.85775 -31.41118 -16.49682 16.93528 -33.98197 -16.26469 16.19871 -30.86548 -15.60472 18.36082 -33.58787 -15.41574 17.43831 -30.12353 -14.59557 20.07506 -32.94009 -14.56047 18.78559 -29.16137 -13.28969 22.54388 -31.95442 -13.55313 20.60372 -28.24903 -11.68883 25.60439 -30.56924 -12.37402 23.07419 -26.66453 -11.2261 28.08129 -28.76291 -11.38232 25.59183 -30.32892 -21.71086 4.692966 -30.19079 -21.58539 6.38698 -29.98786 -21.16348 7.909922 -29.81719 -20.53598 9.655451 -29.61438 -19.81797 11.49886 -29.35424 -19.07382 13.25155 -29.00868 -18.30902 14.88243 -28.57906 -17.51688 16.40454 -28.08492 -16.69007 17.88909 -27.48873 -15.81365 19.4493 -26.76028 -14.74941 21.43992 -25.89497 -13.36833 24.39558 -24.91511 -11.94825 28.12407 -23.74046 -11.25164 31.33893 -26.28162 -21.70243 4.751694 -26.19053 -21.58473 6.465343 -26.03165 -21.16567 7.982695 -25.93095 -20.5287 9.798136 -25.7988 -19.79501 11.8049 -25.58779 -19.02635 13.81056 -25.282 -18.24186 15.71988 -24.93131 -17.48763 17.38769 -24.541 -16.73769 18.90348 -24.0322 -15.90733 20.5427 -23.39724 -14.87348 22.67848 -22.72778 -13.56697 25.73924 -22.1119 -12.28126 29.48116 -21.53761 -11.51972 32.81029 -21.00465 -11.24959 34.94894 -22.26935 -11.10422 33.9202 -21.86145 -21.70876 4.763004 -21.91417 -21.5855 6.480406 -21.87053 -21.16195 8.011706 -21.83417 -20.51289 9.885994 -21.75269 -19.76049 12.01123 -21.57889 -18.96048 14.22231 -21.30499 -18.13278 16.41209 -21.0412 -17.36784 18.29765 -20.82382 -16.67121 19.86373 -20.51482 -15.9003 21.53184 -20.06893 -14.94027 23.70562 -19.65364 -13.80625 26.56261 -19.41484 -12.71328 29.87424 -19.35526 -11.94166 33.04885 -19.45128 -11.54708 35.24667 -17.37312 -21.76919 4.689623 -17.55466 -21.61407 6.409542 -17.63945 -21.16862 7.99749 -17.67 -20.50785 9.91926 -17.63398 -19.7496 12.09075 -17.51952 -18.94899 14.3703 -17.30422 -18.11074 16.69655 -17.10604 -17.31567 18.79499 -17.02739 -16.61925 20.49926 -16.95327 -15.88821 22.2024 -16.80293 -15.02295 24.28839 -16.70928 -14.08278 26.7725 -16.72122 -13.15801 29.57964 -16.9755 -12.39051 32.42925 -18.18685 -11.862 34.67946 -13.01259 -21.8939 4.5198 -13.25778 -21.68047 6.232979 -13.44098 -21.18953 7.925114 -13.55748 -20.50988 9.90057 -13.54433 -19.7455 12.08819 -13.50317 -18.96345 14.34593 -13.43428 -18.18089 16.58761 -13.39584 -17.41121 18.67943 -13.47592 -16.68412 20.51261 -13.61296 -15.92344 22.34304 -13.71707 -15.11627 24.34671 -13.72703 -14.32421 26.52804 -13.49394 -13.47731 29.12257 -13.15874 -12.75873 31.55179 -9.21399 -21.99095 4.320826 -9.444961 -21.73699 6.029278 -9.642361 -21.21103 7.818623 -9.840245 -20.51507 9.823948 -9.797205 -19.73543 12.00654 -9.811623 -18.95024 14.23906 -9.955171 -18.2157 16.33741 -10.17356 -17.47457 18.30233 -10.45785 -16.70935 20.18147 -10.72708 -15.89086 22.14796 -10.74622 -15.09428 24.2276 -10.11993 -14.36083 26.58887 -8.959235 -13.47492 29.75427 -7.78652 -12.51241 33.35945 -6.313066 -22.03579 4.212561 -6.572788 -21.76304 5.912804 -6.821171 -21.22221 7.740869 -7.141098 -20.51812 9.730904 -7.043901 -19.72239 11.87527 -7.084663 -18.92053 14.06424 -7.42839 -18.19921 16.03834 -7.875904 -17.44457 17.91444 -8.317219 -16.64 19.8151 -8.553513 -15.77198 21.93812 -7.991435 -14.93458 24.42083 -6.06888 -14.18707 27.49698 -3.993188 -13.37483 31.15485 -3.030058 -12.52831 34.8143 -2.679989 -11.88906 37.93463 -5.260179 -11.76561 37.08031 -3.048668 -11.42895 40.67469 -4.419365 -11.37622 39.64513 -3.335678 -11.17205 43.40216 -4.586794 -11.03101 43.74386 -4.198322 -11.21456 41.3717 -3.702971 -11.08687 45.45313 -4.929506 -10.98159 45.83269 -3.770736 -11.12445 47.21876 -4.835072 -11.0593 47.62485 -4.90256 -22.04868 4.181139 -5.19279 -21.76968 5.87649 -5.493776 -21.2252 7.711784 -5.916909 -20.51994 9.67767 -5.771381 -19.72034 11.77725 -5.821372 -18.91473 13.91445 -6.285578 -18.19683 15.81439 -6.845972 -17.41558 17.67465 -7.323156 -16.58056 19.61864 -7.34659 -15.68038 21.91055 -5.959671 -14.78779 24.88821 -2.914312 -13.99746 28.64213 -0.7403982 -13.29729 32.32258 -0.3697909 -12.64936 35.51369 -0.8521655 -12.10239 38.24579 -1.546828 -11.64194 40.7782 -2.162509 -11.31676 43.19109 -2.637031 -11.18265 45.15727 -2.892631 -11.16754 46.93229 -2.599186 -19.81632 11.13044 -2.505284 -19.04213 12.91555 -3.137926 -19.07089 12.85494 -2.967586 -19.82085 11.14685 1.353678 -17.24962 18.73102 3.779271 -16.42411 22.0845 2.533208 -16.37174 21.67159 -0.5125179 -17.30455 18.08647 4.589026 -15.77458 24.77805 4.006723 -15.64866 24.6571 4.55863 -15.21243 27.18895 4.204599 -15.08311 27.20131 4.344059 -14.73354 29.63453 4.044514 -14.62376 29.69605 4.007811 -14.28928 32.12591 3.71534 -14.19065 32.20668 3.569865 -13.83402 34.62234 3.260134 -13.73824 34.70882 3.059531 -13.35043 37.12302 2.729572 -13.25586 37.2115 2.493083 -12.83209 39.65514 2.145679 -12.74005 39.74342 1.916209 -12.28807 42.24024 1.559409 -12.20441 42.31969 1.402332 -11.76229 44.84041 1.057292 -11.70155 44.89133 1.121293 -11.37018 47.31217 0.7995465 -11.34463 47.31543 7.936264 -22.20745 4.013002 4.927554 -22.17703 4.011955 7.950212 -21.9107 6.119356 4.709146 -21.80668 5.88965 8.24338 -21.57788 8.314259 4.812716 -21.30109 7.816393 8.813425 -21.24823 10.63368 5.286259 -20.71119 9.859704 9.810259 -20.96074 13.23676 6.465589 -20.11594 12.26828 10.60636 -20.69483 15.92372 7.570803 -19.60287 15.07797 11.09584 -20.44037 18.47469 8.505081 -19.2279 18.01737 11.27292 -20.11437 20.79997 8.909111 -18.87214 20.56171 11.31902 -19.68273 23.04287 8.960346 -18.42736 22.86718 11.36523 -19.17656 25.25642 8.928986 -17.90236 25.10999 11.42982 -18.59194 27.47038 8.905182 -17.31488 27.32307 11.4785 -17.86902 29.7668 8.903435 -16.6654 29.5557 11.44798 -16.9742 32.18213 8.882887 -15.97189 31.86319 11.12121 -15.94289 34.74478 8.652983 -15.27512 34.23242 10.24531 -14.8004 37.70924 7.997025 -14.52288 36.76848 9.167535 -13.54184 40.80737 7.058466 -13.65251 39.53998 8.421895 -12.488 43.3948 6.308364 -12.86992 42.14452 7.467833 -12.05999 45.40315 5.662557 -12.29035 44.57427 7.192803 -11.7565 47.47237 5.400252 -11.76523 47.15177 11.29141 -22.25764 4.234671 11.68488 -22.15949 6.67057 12.1451 -22.13179 9.135293 12.59427 -22.12653 11.55358 13.1365 -22.10903 14.03266 13.51677 -22.01366 16.45038 13.73996 -21.82071 18.76076 13.86176 -21.50956 21.00298 13.96519 -21.09398 23.21826 14.08627 -20.60088 25.39638 14.16302 -19.99044 27.56736 14.04099 -19.10376 29.83759 13.6224 -17.77049 32.3585 12.9129 -16.05868 35.41293 11.88367 -14.5055 39.14696 11.22711 -13.19093 41.94712 10.99132 -11.7676 44.27246 9.262909 -11.53849 46.12461 8.679059 -11.63292 47.54777 8.368473 -11.52432 49.10586 13.67987 -22.31238 4.61483 14.30659 -22.4492 7.231131 14.73847 -22.67075 9.730889 14.98744 -22.85956 12.07938 15.20856 -22.96379 14.39634 15.3883 -22.9423 16.66953 15.55128 -22.78449 18.9121 15.70268 -22.49674 21.13942 15.85886 -22.10121 23.33593 16.00703 -21.61551 25.46266 16.01684 -20.97786 27.5125 15.6298 -19.89334 29.65195 14.76568 -17.88511 32.33815 13.80947 -15.05079 36.23146 12.9622 -12.1977 41.90402 12.21831 -13.30841 41.36444 11.45508 -10.97672 44.26912 10.0326 -10.95388 45.52315 9.184741 -11.39536 46.73489 20.94557 -22.70824 5.631571 17.86835 -22.55486 5.41334 21.0481 -23.3579 7.917845 18.21051 -23.07836 7.812767 21.10231 -23.89685 10.1318 18.32175 -23.53222 10.0716 21.1503 -24.32473 12.37131 18.36937 -23.87111 12.31686 21.20141 -24.63205 14.65425 18.42781 -24.08399 14.58904 21.2576 -24.80459 16.95529 18.52226 -24.16659 16.87251 21.30218 -24.81248 19.21896 18.65787 -24.10986 19.14113 21.23154 -24.57151 21.39048 18.79716 -23.9017 21.35707 20.83161 -24.00028 23.45985 18.84715 -23.51282 23.47144 21.11734 -23.29006 24.58209 18.83909 -22.95549 25.31254 19.80482 -22.48366 26.26466 18.34665 -22.19298 27.01084 21.50403 -21.3598 25.75883 17.95197 -21.01152 28.26572 24.4722 -22.63317 5.873657 24.54682 -23.37091 8.094801 24.64755 -23.99362 10.27073 24.74739 -24.52226 12.48486 24.82077 -24.94331 14.73419 24.83892 -25.21681 16.95908 24.78623 -25.21856 19.04317 24.49672 -24.69516 20.98866 22.84243 -23.57034 23.47729 26.43498 -22.67524 21.82755 27.97394 -22.13621 6.16276 28.138 -22.91663 8.380322 28.32103 -23.5987 10.53221 28.48226 -24.20756 12.68997 28.5708 -24.71534 14.79865 28.58378 -25.01628 16.72187 28.80967 -24.80716 18.17724 29.75843 -23.72105 18.8944 31.48724 -21.24298 6.505793 31.69457 -22.02844 8.752724 31.90089 -22.73247 10.87632 32.04863 -23.37663 12.90975 32.07059 -23.90497 14.71453 32.06041 -24.1459 16.14177 32.68431 -23.63047 16.80489 34.96014 -20.1181 6.867506 35.16431 -20.86921 9.123515 35.32815 -21.54609 11.16023 35.36977 -22.1597 12.95196 35.16713 -22.67079 14.35411 34.6968 -23.00227 15.49002 38.1336 -18.94208 7.128994 38.30232 -19.65191 9.367857 38.39715 -20.28119 11.27499 38.28182 -20.84312 12.77792 37.65249 -21.40626 13.79478 40.40665 -18.0025 7.167845 40.51919 -18.70311 9.414122 40.53418 -19.32342 11.27445 40.11783 -19.95285 12.72747 37.89721 -21.214 14.38565 -36.0881 -21.33066 4.220787 -36.05186 -21.0993 5.824562 -35.96141 -20.64187 7.51071 -35.85749 -20.05537 9.168437 -35.74835 -19.40291 10.68301 -35.63321 -18.70693 12.02026 -35.50278 -17.91211 13.29751 -35.35233 -16.98262 14.63582 -35.19248 -16.08211 15.88281 -34.94097 -15.30672 16.95396 -34.48993 -14.60294 17.98092 -33.80134 -13.89195 19.14171 -32.97417 -13.23823 20.39732 41.32491 -17.5354 6.953783 41.40905 -18.24408 9.233017 41.45227 -18.84594 11.11261 41.38341 -19.27138 12.41116 40.9576 -19.5796 13.19855 40.67158 -19.45853 13.66543 36.7629 -21.12155 15.54278 39.98118 -19.14546 14.25811 34.46121 -21.01896 17.19146 39.62065 -18.0999 14.73878 30.94276 -20.81872 19.42435 42.02212 -11.24936 2.657364 42.0222 -11.6962 4.418465 42.02138 -12.24637 6.429634 42.02041 -12.83813 8.500489 42.01947 -13.36886 10.54647 42.01858 -13.66037 12.21734 42.01747 -13.74639 13.12822 42.01731 -13.78952 13.47634 -36.85607 -7.395843 4.673773 -36.86244 -7.501414 6.27482 -36.85443 -7.738445 8.601094 -36.83567 -7.952468 11.37269 -36.77519 -8.038483 13.76039 -36.60205 -8.066346 15.44303 -36.2764 -8.096558 16.64195 -35.77499 -8.143001 17.67924 -35.12307 -8.200978 18.67685 -34.68241 -8.198569 19.26147 -33.26307 -12.92019 20.38599 -31.78158 -11.90959 22.2854 -32.04178 -12.04864 21.98617 -33.05307 -12.68976 20.71327 -31.8394 -11.86966 22.2999 -32.79792 -12.42934 21.11204 -31.50097 -11.61521 22.78454 -32.51232 -12.16457 21.54295 -31.08798 -11.34693 23.29805 -32.20164 -11.91844 21.96888 -31.92384 -11.72417 22.29938 -30.42971 -11.01677 23.92545 -33.72209 -13.385 19.68676 -34.35958 -13.90201 18.79178 -34.24182 -13.66092 19.08411 -34.07139 -13.41623 19.39869 -33.89572 -13.15754 19.72511 -33.70595 -12.89231 20.06282 -33.49144 -12.64335 20.40171 -33.34536 -12.44411 20.63555 -34.91856 -14.49959 17.86984 -34.88898 -14.28979 18.09305 -34.78614 -14.05705 18.36421 -34.6797 -13.80885 18.63812 -34.56331 -13.54106 18.92437 -34.4249 -13.27511 19.21701 -34.28262 -13.02515 19.48587 -33.635 -12.44152 20.35917 -34.20999 -12.80259 19.66043 -33.55237 -12.22852 20.52293 -34.06434 -12.53416 19.91134 -33.35896 -11.95582 20.80633 -33.88796 -12.24849 20.18257 -33.15584 -11.64155 21.08966 -33.71679 -11.91976 20.43213 -32.99143 -11.24155 21.32189 -33.58039 -11.47476 20.63162 -32.87948 -10.71662 21.47712 -33.48582 -10.86885 20.76298 -32.81611 -10.03965 21.55943 -33.4344 -10.07763 20.82832 -32.77513 -9.358541 21.60309 -33.40245 -9.297863 20.86028 -32.73704 -8.885254 21.63297 -33.38896 -8.785937 20.86121 -32.59994 -8.737526 21.77011 -33.36264 -8.568209 20.87731 -33.27613 -8.532699 20.96158 -32.10611 -9.06354 22.28085 -32.65243 -8.510616 21.6787 -33.38269 -8.382586 20.83132 -35.30339 -15.12468 16.9743 -35.31856 -14.89096 17.21139 -35.27072 -14.65212 17.4725 -35.21757 -14.40735 17.72327 -35.15771 -14.13564 17.98704 -35.08335 -13.8503 18.25989 -34.98793 -13.57108 18.52471 -34.88953 -13.2881 18.76993 -34.76867 -12.99253 19.01898 -34.6389 -12.68298 19.25555 -34.51645 -12.30724 19.46019 -34.42037 -11.76436 19.61242 -34.35585 -11.01136 19.70569 -34.32761 -10.0782 19.7447 -34.31706 -9.208691 19.7558 -34.31378 -8.696845 19.74848 -34.31119 -8.48585 19.74055 -34.30192 -8.39706 19.74234 -34.34083 -8.316119 19.68758 -35.53507 -15.83242 15.99651 -35.60108 -15.54086 16.28528 -35.60736 -15.2655 16.57559 -35.60366 -15.00452 16.83481 -35.59341 -14.71907 17.09981 -35.56845 -14.40872 17.37648 -35.52155 -14.09844 17.6428 -35.46495 -13.78057 17.8906 -35.39009 -13.45905 18.12469 -35.30384 -13.11421 18.33671 -35.22117 -12.66761 18.50941 -35.16032 -12.00196 18.62023 -35.12374 -11.09155 18.67975 -35.11911 -10.02909 18.69781 -35.13887 -9.100384 18.6864 -35.15492 -8.612967 18.66639 -35.16034 -8.429986 18.6539 -35.15843 -8.341352 18.6496 -35.15615 -8.268471 18.64492 -35.68717 -16.67566 14.82292 -35.78983 -16.30861 15.18716 -35.83867 -15.95593 15.55545 -35.8748 -15.63446 15.87867 -35.90582 -15.30377 16.18704 -35.92576 -14.95224 16.49048 -35.92761 -14.60526 16.76546 -35.91864 -14.25905 17.00919 -35.88747 -13.90696 17.23156 -35.83759 -13.50729 17.42688 -35.78604 -12.96483 17.57687 -35.75378 -12.17144 17.6562 -35.73943 -11.12633 17.69044 -35.75066 -9.960367 17.69796 -35.78809 -9.01564 17.68032 -35.81733 -8.554999 17.65543 -35.82847 -8.384457 17.64028 -35.82886 -8.293377 17.63434 -35.82286 -8.215495 17.63356 -35.82019 -17.59743 13.49697 -35.93201 -17.20363 13.88599 -36.0055 -16.78902 14.31093 -36.07034 -16.38973 14.70973 -36.13318 -15.98062 15.09353 -36.19213 -15.55233 15.46035 -36.23843 -15.13665 15.77691 -36.26595 -14.74328 16.044 -36.26882 -14.33752 16.26975 -36.25067 -13.84792 16.45138 -36.22283 -13.1808 16.58531 -36.20738 -12.2496 16.6508 -36.211 -11.06486 16.66742 -36.23996 -9.797135 16.65898 -36.28373 -8.899739 16.63832 -36.31281 -8.499751 16.61983 -36.32289 -8.343882 16.61036 -36.32266 -8.249816 16.60793 -36.31622 -8.168642 16.60886 -35.94351 -18.41576 12.19112 -36.06027 -18.06297 12.53206 -36.14693 -17.6608 12.93231 -36.22693 -17.23451 13.34407 -36.30401 -16.77252 13.76768 -36.37992 -16.27618 14.18552 -36.45098 -15.77402 14.55504 -36.49912 -15.28497 14.87184 -36.52325 -14.75869 15.12343 -36.52832 -14.12005 15.3015 -36.51955 -13.30922 15.42243 -36.51644 -12.25375 15.47888 -36.53489 -10.93875 15.48343 -36.57871 -9.574894 15.46085 -36.61917 -8.755977 15.43261 -36.63842 -8.441082 15.42147 -36.64381 -8.310593 15.42044 -36.64358 -8.217755 15.42099 -36.63807 -8.135815 15.42081 -36.05645 -19.12145 10.84047 -36.18026 -18.80851 11.14056 -36.27402 -18.44958 11.49505 -36.36152 -18.04802 11.86771 -36.44362 -17.59296 12.2571 -36.5181 -17.08454 12.654 -36.58618 -16.51917 13.02603 -36.63179 -15.88979 13.35312 -36.65759 -15.1606 13.60083 -36.66949 -14.31153 13.76305 -36.6706 -13.35055 13.87347 -36.67498 -12.21533 13.93186 -36.70075 -10.83894 13.94116 -36.75183 -9.431036 13.91184 -36.7913 -8.661147 13.85343 -36.80614 -8.398252 13.8135 -36.80984 -8.287227 13.79548 -36.81016 -8.198473 13.7868 -36.80555 -8.115222 13.77533 -36.15699 -19.77678 9.320755 -36.28595 -19.48539 9.59652 -36.38371 -19.15653 9.915022 -36.47417 -18.77963 10.24468 -36.55548 -18.3439 10.58193 -36.61997 -17.83383 10.92379 -36.66873 -17.19534 11.23534 -36.69676 -16.38285 11.47362 -36.71079 -15.41202 11.61967 -36.71724 -14.35201 11.70414 -36.71905 -13.27095 11.7803 -36.72444 -12.11282 11.84461 -36.74841 -10.76309 11.87616 -36.79874 -9.382448 11.8625 -36.84418 -8.609251 11.79565 -36.86306 -8.343037 11.7102 -36.86714 -8.23945 11.6334 -36.86672 -8.156995 11.57681 -36.86177 -8.065346 11.51025 -36.24527 -20.37112 7.635973 -36.37511 -20.09805 7.872774 -36.47292 -19.79089 8.145779 -36.55957 -19.43139 8.427998 -36.63089 -18.99973 8.715209 -36.67977 -18.44266 8.996932 -36.70816 -17.6723 9.221404 -36.72057 -16.6648 9.338704 -36.72526 -15.50854 9.372429 -36.7269 -14.31368 9.381491 -36.72744 -13.15208 9.414635 -36.73046 -11.9855 9.462084 -36.74692 -10.70256 9.493195 -36.79131 -9.397882 9.505351 -36.84704 -8.585703 9.486575 -36.87622 -8.260355 9.361367 -36.8829 -8.128645 9.160624 -36.88142 -8.02816 8.986721 -36.87601 -7.905918 8.837479 -36.31449 -20.84494 5.883478 -36.44025 -20.59287 6.049192 -36.53398 -20.30571 6.2507 -36.61311 -19.95479 6.463415 -36.6711 -19.4995 6.683554 -36.70405 -18.85133 6.897192 -36.71759 -17.92801 7.0466 -36.7209 -16.77329 7.086811 -36.72354 -15.52833 7.064369 -36.72492 -14.27997 7.033516 -36.72567 -13.06331 7.025558 -36.72775 -11.8683 7.03981 -36.73902 -10.63657 7.064911 -36.77747 -9.422327 7.122877 -36.83988 -8.579375 7.187965 -36.87803 -8.173402 7.032911 -36.88816 -7.975402 6.691803 -36.88664 -7.8228 6.418871 -36.88095 -7.668562 6.315924 -36.32772 -21.09538 4.219208 -36.44505 -20.86098 4.290348 -36.53105 -20.58903 4.386248 -36.60121 -20.23964 4.489641 -36.64801 -19.75299 4.601101 -36.66933 -19.0163 4.721279 -36.6718 -17.94157 4.805738 -36.669 -16.63212 4.808561 -36.68042 -15.31922 4.76861 -36.69203 -14.07833 4.723072 -36.70032 -12.87556 4.687487 -36.70965 -11.69161 4.669777 -36.72529 -10.51592 4.68878 -36.76319 -9.400557 4.805399 -36.82586 -8.570715 4.998669 -36.86687 -8.117035 4.953316 -36.87939 -7.872468 4.686832 -36.87886 -7.69312 4.510555 -36.87355 -7.537912 4.543591 -36.18083 -20.98238 2.717182 -36.27899 -20.75062 2.695202 -36.35025 -20.48303 2.675388 -36.40692 -20.14353 2.654749 -36.44252 -19.66089 2.640625 -36.45211 -18.85704 2.651401 -36.43845 -17.54677 2.662956 -36.42837 -15.90187 2.629068 -36.46628 -14.40186 2.5744 -36.51602 -13.20871 2.524668 -36.56059 -12.16932 2.483271 -36.60793 -11.16613 2.456547 -36.65446 -10.17949 2.475063 -36.71043 -9.253643 2.615217 -36.77668 -8.523077 2.86599 -36.81381 -8.08227 2.934565 -36.82493 -7.830333 2.825344 -36.82607 -7.655776 2.793722 -36.82374 -7.515474 2.900669 42.02316 -14.06072 13.78062 42.01669 -14.16014 13.84588 42.01361 -14.21977 13.87856 42.02069 -14.14543 13.83161 42.01176 -14.26525 13.90042 42.01708 -14.23644 13.87864 42.02247 -13.82848 13.59253 42.02595 -13.81041 13.53643 42.02458 -13.85764 13.63431 42.02872 -13.83332 13.58158 42.0252 -13.89576 13.66695 42.02498 -13.96258 13.71499 42.03048 -13.87845 13.62613 42.03178 -13.94379 13.67815 42.03184 -14.01996 13.73313 42.02981 -14.11832 13.79473 42.01185 -14.34897 13.92237 42.02471 -14.2488 13.86041 41.99841 -14.52845 13.98769 42.01348 -14.4419 13.94049 41.98191 -14.70076 14.04512 41.99925 -14.63271 14.01034 41.95611 -14.85077 14.07793 41.98476 -14.77305 14.05396 41.95587 -14.90415 14.07416 41.82128 -15.17622 14.10398 41.81578 -15.18381 14.10352 41.09597 -16.24809 14.28495 41.51409 -15.47737 14.21697 39.41867 -17.28799 15.04852 41.27375 -16.15792 14.23559 41.83649 -15.37522 14.07145 41.46329 -16.74906 13.99814 41.89077 -15.69441 13.98248 41.79331 -16.60264 13.8604 41.91207 -15.92891 13.9281 41.83605 -16.67352 13.82178 41.89302 -16.23003 13.87011 42.02831 -13.77289 13.21006 42.03242 -13.77988 13.30709 42.03567 -13.81065 13.38941 42.03908 -13.85794 13.46299 42.04183 -13.91124 13.53551 42.04307 -13.98472 13.61449 42.04212 -14.09418 13.70326 42.03713 -14.26869 13.80734 42.02793 -14.47896 13.90462 42.0163 -14.67176 13.97481 42.00537 -14.82007 14.01071 41.98713 -14.98272 14.01363 41.94709 -15.23839 13.99269 41.98487 -15.52634 13.92889 41.98212 -15.76451 13.90002 41.96944 -15.87692 13.88838 41.94655 -16.2137 13.81926 41.82238 -16.61759 13.80491 41.88801 -16.88833 13.68379 41.40518 -17.43563 13.85478 41.57274 -18.04181 13.58982 42.03017 -13.75439 12.30819 42.03501 -13.78657 12.49122 42.03895 -13.83078 12.66764 42.04344 -13.87627 12.82371 42.04818 -13.90844 12.97514 42.05273 -13.94597 13.12934 42.05674 -14.00784 13.28949 42.05899 -14.12101 13.45427 42.05688 -14.30492 13.60597 42.04981 -14.5507 13.72773 42.04236 -14.85704 13.78957 42.03481 -15.26467 13.77605 42.02499 -15.84052 13.69532 42.01676 -16.44134 13.60932 42.00227 -16.73469 13.58963 41.98398 -16.82016 13.59329 41.95249 -17.20272 13.52631 41.89303 -17.84646 13.39943 41.69818 -18.65535 13.29778 42.03123 -13.60573 10.63279 42.0362 -13.74667 10.87335 42.04018 -13.86861 11.14101 42.04486 -13.96131 11.40328 42.05049 -14.01927 11.67433 42.05702 -14.06681 11.95362 42.06442 -14.11427 12.23267 42.07173 -14.16719 12.50021 42.07495 -14.26468 12.74725 42.07278 -14.49298 12.96026 42.07312 -14.99327 13.06776 42.0699 -15.73691 13.05628 42.0616 -16.64418 12.96231 42.04545 -17.44225 12.89465 42.01995 -17.84251 12.92055 41.98394 -18.00042 12.9813 41.93154 -18.30921 12.99535 41.8605 -18.68253 12.96702 41.70441 -19.05221 12.95475 42.0326 -13.17266 8.601937 42.03775 -13.39291 8.857867 42.04174 -13.5872 9.154994 42.04631 -13.76544 9.45182 42.05183 -13.93159 9.754416 42.05841 -14.09838 10.0618 42.06604 -14.25206 10.37019 42.07258 -14.34986 10.68375 42.07225 -14.38021 11.01506 42.07002 -14.51879 11.32631 42.08154 -15.08403 11.49292 42.08831 -15.93958 11.54087 42.08319 -16.89807 11.53478 42.06345 -17.68703 11.58524 42.0254 -18.14773 11.7329 41.96978 -18.40107 11.91466 41.89871 -18.64839 12.06949 41.82049 -18.86051 12.18148 41.71971 -19.02868 12.27261 42.03439 -12.61894 6.547531 42.03993 -12.86112 6.792585 42.04423 -13.07697 7.074137 42.04903 -13.2974 7.354483 42.05465 -13.53214 7.634462 42.06109 -13.78826 7.91435 42.06739 -14.0466 8.195271 42.06832 -14.23294 8.496787 42.05862 -14.29901 8.841469 42.0562 -14.49199 9.157399 42.07622 -15.12288 9.324746 42.08955 -15.94737 9.421494 42.08279 -16.76674 9.515152 42.05309 -17.40468 9.675482 42.00025 -17.8149 9.91141 41.93047 -18.08636 10.17565 41.85016 -18.31051 10.43671 41.76882 -18.49596 10.67951 41.68252 -18.6502 10.90388 42.03618 -12.07676 4.519627 42.0422 -12.31652 4.727747 42.0469 -12.5302 4.971395 42.05213 -12.75933 5.220737 42.05809 -13.01547 5.473398 42.06441 -13.30359 5.728067 42.06856 -13.60052 5.986002 42.06324 -13.83247 6.265583 42.05049 -14.01628 6.56612 42.05885 -14.44725 6.79847 42.08081 -15.1526 6.936983 42.08651 -15.85769 7.076239 42.06724 -16.46636 7.247091 42.02188 -16.92266 7.472715 41.95478 -17.24308 7.744789 41.87602 -17.4863 8.037135 41.79268 -17.69262 8.339209 41.71305 -17.87354 8.645031 41.63064 -18.03708 8.947842 42.03668 -11.61794 2.706692 42.04281 -11.8457 2.846216 42.04763 -12.04823 3.019407 42.05285 -12.2719 3.205856 42.05805 -12.53243 3.405245 42.06194 -12.83059 3.616236 42.06002 -13.12535 3.842117 42.04637 -13.34477 4.09528 42.03062 -13.6003 4.342342 42.04637 -14.22108 4.484289 42.06456 -14.96665 4.58349 42.05829 -15.57636 4.730656 42.02371 -16.03065 4.927685 41.96356 -16.35965 5.167492 41.88684 -16.61044 5.435045 41.80398 -16.81774 5.717688 41.72084 -16.99947 6.015131 41.64392 -17.16436 6.327253 41.56031 -17.32281 6.646069 42.02982 -11.26913 1.418776 42.03372 -11.46563 1.456161 42.03671 -11.64099 1.521643 42.03884 -11.84681 1.602282 42.03778 -12.11617 1.700245 42.03028 -12.45295 1.814238 42.01121 -12.8184 1.946474 41.99078 -13.13654 2.102501 41.96909 -13.48858 2.254438 41.96659 -14.10863 2.330334 41.9589 -14.74566 2.396385 41.92885 -15.22904 2.512629 41.872 -15.56409 2.672241 41.794 -15.80695 2.861013 41.70639 -16.00265 3.067123 41.61593 -16.16994 3.284151 41.52599 -16.31906 3.51436 41.442 -16.45595 3.759966 41.34638 -16.59219 4.015848 41.65081 -10.69341 0.5448074 40.22512 -11.34956 0.4944096 41.60861 -10.85296 0.4099617 40.08352 -11.54617 0.3248234 41.56562 -11.03407 0.3258972 39.94954 -11.76614 0.2027339 41.50797 -11.30563 0.2522774 39.79185 -12.08026 0.09512901 41.41135 -11.73528 0.189989 39.5692 -12.54633 0.01895141 41.20648 -12.30253 0.1428451 39.17453 -13.15871 -0.02358436 40.88038 -12.93863 0.1125488 38.6034 -13.84836 -0.04598808 40.64182 -13.47982 0.09576606 38.16476 -14.40221 -0.05935287 40.48696 -13.95817 0.08693313 37.87489 -14.8418 -0.06867599 40.35645 -14.45758 0.07795524 37.64141 -15.25888 -0.0751686 40.22465 -14.92723 0.07516479 37.4233 -15.66609 -0.07828903 40.06701 -15.30473 0.08567619 37.20043 -16.04189 -0.07656669 39.86701 -15.5899 0.106512 36.9574 -16.37667 -0.07037925 39.63615 -15.80853 0.1356334 36.69412 -16.65531 -0.05863571 39.39317 -15.98799 0.1718158 36.41522 -16.88337 -0.04066467 39.13941 -16.14641 0.2128829 36.1164 -17.06538 -0.01701164 38.87727 -16.29451 0.256485 35.80819 -17.22611 0.01005923 38.61753 -16.43247 0.302515 35.50133 -17.37586 0.03961563 38.36267 -16.57058 0.3755207 35.20108 -17.52562 0.09665107 36.84611 -12.98779 0.3249989 36.75281 -13.13268 0.207735 36.53324 -13.31984 0.116518 36.29039 -13.54477 0.04798305 36.02764 -13.83163 -0.01192271 35.7356 -14.19424 -0.05019366 35.35222 -14.63374 -0.06825256 34.86066 -15.12598 -0.07735824 34.46701 -15.53478 -0.08358764 34.16941 -15.87982 -0.08873939 33.91144 -16.21712 -0.09274673 33.66529 -16.56163 -0.09547042 33.4246 -16.90991 -0.0964775 33.18954 -17.25528 -0.09522819 32.96561 -17.58773 -0.09022331 32.74009 -17.9022 -0.07989501 32.48106 -18.12494 -0.06325531 32.20185 -18.28764 -0.04148674 31.91359 -18.43078 -0.01568222 31.62804 -18.57287 0.03651797 32.21892 -14.6718 0.07424736 32.18269 -14.79367 0.02611732 31.97911 -14.93995 -0.01202189 31.75808 -15.13787 -0.0365523 31.49835 -15.37993 -0.05583369 31.208 -15.65074 -0.0674076 30.88263 -15.94351 -0.07375526 30.50779 -16.25642 -0.07859992 30.16976 -16.5393 -0.08309745 29.88499 -16.80088 -0.08742523 29.66129 -17.06003 -0.09140014 29.4651 -17.32624 -0.09476089 29.27455 -17.60289 -0.09718704 29.09624 -17.90532 -0.09822082 28.95512 -18.28956 -0.09687995 28.8379 -18.75642 -0.09149169 28.68033 -19.06995 -0.08027648 28.48229 -19.242 -0.06371688 28.24813 -19.36836 -0.04277992 28.00811 -19.49031 0.003484666 26.67619 -15.86972 0.00170511 26.72613 -15.96439 -0.02492702 26.6838 -16.07523 -0.0440464 26.67621 -16.23911 -0.05533015 26.59187 -16.43027 -0.06263732 26.41802 -16.6309 -0.0675373 26.17766 -16.83428 -0.07178306 25.8782 -17.03959 -0.07614135 25.57381 -17.23051 -0.08065414 25.3234 -17.40394 -0.08524131 25.17639 -17.56703 -0.08970642 25.08835 -17.73264 -0.09368133 25.01352 -17.91527 -0.09676361 24.94282 -18.17042 -0.09862709 24.90145 -18.63422 -0.09880828 24.8915 -19.29851 -0.09622764 24.84617 -19.75072 -0.08927726 24.74462 -19.95728 -0.07803916 24.5761 -20.07303 -0.06286048 24.39396 -20.17632 -0.02341067 21.12437 -16.64016 -0.03286349 21.27569 -16.72411 -0.05047976 21.53054 -16.84308 -0.05784225 21.69728 -16.96698 -0.06258773 21.73134 -17.08498 -0.06667518 21.66529 -17.19994 -0.0708332 21.52992 -17.31583 -0.07528114 21.37038 -17.4291 -0.07995033 21.23513 -17.53703 -0.08473396 21.16349 -17.64364 -0.08940696 21.12379 -17.75807 -0.09356307 21.08155 -17.89977 -0.09677505 21.02243 -18.15256 -0.09876251 20.97708 -18.68797 -0.0993843 20.97381 -19.48899 -0.09819412 20.95076 -20.09322 -0.09389495 20.85836 -20.40551 -0.08574676 20.68146 -20.57579 -0.07311439 20.49367 -20.70831 -0.03752136 18.18169 -16.79913 -0.0349884 18.36208 -16.88047 -0.0519371 18.52703 -16.95384 -0.05801582 18.62346 -17.02673 -0.06225967 18.64292 -17.09676 -0.06639671 18.60858 -17.16789 -0.070755 18.54047 -17.24333 -0.07540512 18.45713 -17.32379 -0.08023262 18.37313 -17.41006 -0.08508682 18.30275 -17.50418 -0.08973121 18.2247 -17.61297 -0.09379768 18.1099 -17.7599 -0.09692001 17.94034 -18.03582 -0.0988655 17.77739 -18.59811 -0.09962654 17.68198 -19.44353 -0.09915924 17.58199 -20.19957 -0.09638977 17.39373 -20.70035 -0.08964729 17.11024 -21.0054 -0.07751083 16.82479 -21.21844 -0.04523849 17.17957 -16.70999 -0.02686882 17.46424 -16.83684 -0.04485702 17.51997 -16.87944 -0.05256068 17.53897 -16.92501 -0.05756378 17.52449 -16.97754 -0.06184756 17.48579 -17.03432 -0.06607627 17.43339 -17.09519 -0.07054519 17.37523 -17.16356 -0.07528495 17.30335 -17.23853 -0.08015251 17.21647 -17.32575 -0.08499526 17.11558 -17.42585 -0.08957481 16.96986 -17.54961 -0.09358978 16.74162 -17.72467 -0.09671401 16.42669 -18.02994 -0.09872055 16.13923 -18.58305 -0.09960937 15.96479 -19.40574 -0.09947967 15.81982 -20.24967 -0.09753608 15.59538 -20.89698 -0.09184265 15.27921 -21.29604 -0.08041381 14.96219 -21.54757 -0.05086123 3.135792 -10.68497 -0.01356506 10.97141 -14.16549 -0.02101504 11.49417 -14.43093 -0.03671824 3.36737 -10.83599 -0.02864062 11.5534 -14.5232 -0.04332149 3.41597 -10.95864 -0.03508746 11.62307 -14.73663 -0.04794687 3.643524 -11.38412 -0.03920364 12.06687 -15.42573 -0.05381762 4.534737 -12.66053 -0.04539299 12.91726 -16.61824 -0.06236636 6.122584 -14.75501 -0.05583369 13.21969 -17.40453 -0.06920242 7.026989 -16.20845 -0.06394004 13.00993 -17.83734 -0.07416725 7.222069 -17.02429 -0.06836318 12.74155 -18.23357 -0.07825851 7.468565 -17.85598 -0.06938552 12.58338 -18.71262 -0.08139991 8.063841 -18.91117 -0.06752014 12.27675 -19.09551 -0.08514595 8.289428 -19.54543 -0.06942558 11.88886 -19.43426 -0.08941268 8.213994 -19.89158 -0.07512664 11.5975 -19.75889 -0.09368324 8.127902 -20.17686 -0.08208274 11.41042 -20.14585 -0.09613609 8.071954 -20.47377 -0.08667182 11.31304 -20.70297 -0.09713363 8.081357 -20.90886 -0.0902462 11.28677 -21.36046 -0.09601974 8.201075 -21.48947 -0.09269523 11.27991 -21.84362 -0.08785438 8.380582 -21.94095 -0.08564567 11.24467 -22.09078 -0.06147766 8.532705 -22.16986 -0.05803871 3.857616 -18.22944 -0.05535113 4.763094 -19.40069 -0.0516662 4.977948 -19.87257 -0.05657005 5.007912 -20.21545 -0.06445121 5.022259 -20.55347 -0.07054519 5.121259 -20.9944 -0.0780754 5.381928 -21.56614 -0.08684921 5.729153 -21.99152 -0.08238029 6.065861 -22.20002 -0.05131912 3.076789 -19.194 -0.04224586 3.422324 -19.75474 -0.04574 3.476819 -20.13908 -0.05372047 3.504965 -20.52551 -0.06054115 3.642211 -21.00255 -0.07051658 3.976061 -21.59403 -0.08362197 4.40381 -22.0101 -0.08104515 4.849295 -22.20953 -0.04825007 -2.510519 -8.134921 -0.03243446 -2.538321 -8.130534 -0.03278923 -2.508368 -8.188328 -0.08260917 -2.535842 -8.183856 -0.08319091 -2.507183 -8.245961 -0.09146881 -2.534976 -8.240826 -0.09214782 -2.531295 -8.311135 -0.09461593 -2.559838 -8.304312 -0.09536743 -2.667306 -8.392608 -0.09596824 -2.702248 -8.374976 -0.09677124 -3.003532 -8.57054 -0.09539604 -3.082252 -8.489487 -0.0960865 -3.294919 -9.154335 -0.09420394 -3.50823 -8.884418 -0.09426689 -3.118726 -10.486 -0.09482192 -3.459612 -10.03627 -0.09414863 -2.722002 -12.12324 -0.09655952 -2.936254 -11.85829 -0.09643554 -2.533488 -13.51721 -0.09738349 -2.615234 -13.44472 -0.09791183 -2.488599 -14.73109 -0.09692573 -2.531603 -14.72106 -0.09777069 -2.381843 -15.96039 -0.09156036 -2.464512 -15.9349 -0.09304046 -6.288774 -8.117205 -0.03306567 -9.32049 -8.150164 -0.03017044 -6.291289 -8.175621 -0.08413314 -9.336425 -8.233551 -0.08285522 -6.290299 -8.243785 -0.0933113 -9.332364 -8.344346 -0.0927124 -6.289753 -8.323805 -0.09667778 -9.334908 -8.494435 -0.09611129 -6.293797 -8.408473 -0.09849166 -9.35447 -8.67035 -0.09799766 -6.301784 -8.498681 -0.09875488 -9.359095 -8.843668 -0.09852981 -6.333815 -8.727794 -0.09773254 -9.361144 -9.10256 -0.09782791 -6.371882 -9.551823 -0.09682273 -9.379654 -9.7853 -0.09686279 -6.332421 -11.31986 -0.09769248 -9.390889 -11.26422 -0.09722518 -6.311552 -13.20806 -0.09914588 -9.414801 -13.11721 -0.09869003 -6.344861 -14.6702 -0.0998001 -9.438226 -14.65032 -0.09962463 -6.480588 -15.83498 -0.09980773 -9.487797 -15.82813 -0.09984016 -6.72555 -16.85689 -0.09905815 -9.580019 -16.83295 -0.09944725 -6.895052 -17.81244 -0.09441375 -9.64066 -17.76274 -0.09626579 -6.814986 -18.71251 -0.07591819 -9.60167 -18.60412 -0.08192253 -6.44521 -19.43857 -0.0373497 -9.434318 -19.2389 -0.04736137 -6.165432 -19.84759 0.007600784 -9.314538 -19.62066 0.004055023 -6.028835 -20.11359 0.0692768 -9.26628 -19.92616 0.08118629 -5.942776 -20.33947 0.1560363 -9.240927 -20.19273 0.1801624 -12.86568 -8.294795 -0.02044105 -12.90996 -8.431627 -0.07782554 -12.91392 -8.612597 -0.09046745 -12.96772 -8.877961 -0.09455871 -13.0388 -9.20673 -0.09674263 -13.04795 -9.545655 -0.0978794 -13.02 -10.00067 -0.09807205 -13.07183 -10.78766 -0.09780693 -13.20746 -12.07494 -0.09802818 -13.33966 -13.61394 -0.0989933 -13.39779 -14.89144 -0.09964561 -13.40648 -15.90095 -0.09984016 -13.40387 -16.83529 -0.09956359 -13.39234 -17.74419 -0.09706687 -13.3733 -18.55566 -0.08517265 -13.33076 -19.13418 -0.05359077 -13.30061 -19.49957 0.001283586 -13.29405 -19.82959 0.08728599 -13.29438 -20.11716 0.1915054 -16.01276 -8.598185 -0.006315231 -16.04854 -8.757514 -0.07032585 -16.16248 -8.950116 -0.08618354 -16.49531 -9.244152 -0.09143638 -16.70883 -9.609321 -0.09404373 -16.68113 -10.04168 -0.09560585 -16.55043 -10.74967 -0.0964756 -16.69211 -11.81124 -0.09703063 -17.07636 -13.12006 -0.09768676 -17.38873 -14.36039 -0.09863471 -17.51465 -15.28536 -0.09935951 -17.52157 -16.04096 -0.09971618 -17.48822 -16.86682 -0.09953308 -17.45737 -17.75244 -0.09714317 -17.45247 -18.55568 -0.08583831 -17.46173 -19.11275 -0.05532824 -17.46017 -19.47111 4.48227e-4 -17.46022 -19.80809 0.08866691 -17.46476 -20.09837 0.189888 -19.32188 -8.875014 -0.003156602 -19.26175 -9.007407 -0.069458 -19.78115 -9.171773 -0.08333778 -20.88096 -9.437892 -0.08746337 -21.45337 -9.78459 -0.08986663 -21.28159 -10.37428 -0.0915451 -20.79578 -11.46915 -0.09288024 -20.81965 -12.79701 -0.09431266 -21.2632 -14.0655 -0.09591102 -21.56329 -15.00631 -0.09757995 -21.65181 -15.59944 -0.09885978 -21.63749 -16.13838 -0.09952926 -21.59738 -16.88895 -0.09942436 -21.57351 -17.7667 -0.09699058 -21.58629 -18.56844 -0.08569145 -21.62199 -19.11522 -0.05545222 -21.63215 -19.46898 4.59671e-4 -21.63025 -19.80654 0.08912849 -21.62944 -20.09672 0.1894569 -24.09736 -8.893311 -0.01240158 -24.06587 -9.071297 -0.0709877 -25.04449 -9.239873 -0.08162879 -26.86536 -9.47921 -0.08508682 -27.80499 -9.82643 -0.0875225 -27.50755 -10.57421 -0.08939552 -26.56428 -11.91236 -0.09111022 -26.09949 -13.25514 -0.09305763 -26.06509 -14.35008 -0.09511947 -25.93306 -15.13699 -0.0969963 -25.80389 -15.63415 -0.09812927 -25.73128 -16.13426 -0.09876823 -25.69079 -16.88729 -0.09853172 -25.68114 -17.77714 -0.09584808 -25.71164 -18.58059 -0.08436012 -25.76707 -19.11998 -0.05420494 -25.78681 -19.47048 0.001771867 -25.78332 -19.80732 0.09036827 -25.78054 -20.09745 0.1907978 -30.78986 -8.233122 0.2188948 -30.64935 -8.522665 -0.01865196 -30.54172 -8.802933 -0.07648277 -31.01426 -9.013671 -0.08431434 -32.0558 -9.23234 -0.08750152 -32.52671 -9.515885 -0.08979034 -32.22899 -10.12431 -0.09154891 -31.45999 -11.22272 -0.09321594 -30.96246 -12.36768 -0.09439659 -30.62578 -13.46099 -0.09531974 -30.15192 -14.45472 -0.09520339 -29.83117 -15.19681 -0.0933361 -29.68816 -15.88671 -0.09212684 -29.63824 -16.76265 -0.09018325 -29.64126 -17.73281 -0.08570861 -29.68565 -18.57607 -0.0731678 -29.75295 -19.12396 -0.0423603 -29.77959 -19.47658 0.01418864 -29.77454 -19.81129 0.1020812 -29.76457 -20.10116 0.2035827 -34.9005 -7.848868 0.1326503 -34.77373 -8.094696 -0.04262346 -34.84069 -8.294034 -0.06703567 -35.10734 -8.520752 -0.07152557 -35.15282 -8.834897 -0.07136726 -34.89733 -9.384963 -0.0734539 -34.39122 -10.23275 -0.07933998 -34.02661 -11.12735 -0.08035469 -33.7338 -12.08113 -0.07859992 -33.35231 -13.08895 -0.07265663 -33.09558 -14.01139 -0.06158053 -32.9608 -14.98673 -0.0515536 -32.91198 -16.18527 -0.03952217 -32.93085 -17.46207 -0.02534675 -32.98314 -18.49863 -0.007575929 -33.04409 -19.12189 0.02660942 -33.06574 -19.49793 0.08534049 -33.05686 -19.82999 0.171669 -33.04255 -20.11883 0.2768307 -36.31511 -7.500227 0.3628712 -36.2713 -7.662882 0.1659449 -36.26383 -7.825589 0.1267108 -36.29377 -8.02965 0.1191272 -36.26789 -8.322197 0.1291999 -36.13433 -8.782299 0.1177406 -35.86248 -9.406517 0.08031654 -35.62982 -10.04387 0.06754684 -35.42382 -10.7217 0.07258033 -35.17846 -11.48838 0.08761215 -34.99768 -12.35012 0.1131305 -34.87939 -13.50141 0.1438102 -34.83412 -15.12161 0.1839523 -34.87035 -16.93517 0.2243461 -34.9232 -18.34911 0.2547798 -34.95834 -19.13559 0.2956658 -34.95864 -19.56373 0.3584004 -34.93804 -19.89465 0.4414368 -34.91305 -20.17806 0.5456982 -36.67678 -7.543246 1.062851 -36.67216 -7.681212 0.990799 -36.67078 -7.855196 0.9813557 -36.65945 -8.104311 1.018293 -36.60942 -8.502835 0.9710274 -36.4939 -9.077893 0.8339443 -36.37579 -9.722702 0.7674809 -36.25642 -10.39454 0.7658997 -36.1192 -11.10555 0.7874813 -36.00012 -11.92361 0.8229466 -35.89501 -13.08917 0.8726158 -35.83335 -14.83841 0.9396649 -35.85583 -16.86797 1.001202 -35.89318 -18.44311 1.034164 -35.90387 -19.31088 1.072241 -35.88506 -19.77228 1.132309 -35.84881 -20.09928 1.203157 -35.80396 -20.36991 1.282997 41.97917 -10.93343 0.7216797 41.97271 -11.08502 0.6775398 41.96556 -11.239 0.6626835 41.95315 -11.4492 0.6546784 41.92759 -11.7713 0.6495667 41.86847 -12.19701 0.6491966 41.76492 -12.67848 0.6624985 41.69072 -13.11809 0.6933594 41.63379 -13.55711 0.7307434 41.5846 -14.11338 0.7429218 41.52926 -14.6408 0.7592621 41.45178 -15.03538 0.8054733 41.34249 -15.30253 0.8756771 41.2119 -15.49663 0.9612675 41.07539 -15.65634 1.056864 40.93468 -15.79632 1.158733 40.78993 -15.92378 1.2668 40.64806 -16.04059 1.382051 40.50086 -16.15616 1.511709 18.07064 -19.65845 28.87366 16.92618 -19.09133 29.91193 20.35957 -20.79268 26.7971 19.21511 -20.22557 27.83538 -4.336961 -20.43736 0.1371536 -4.267405 -20.67881 0.3517552 -3.685057 -20.48744 0.125164 -3.611724 -20.72075 0.3367272 -3.264406 -20.52497 0.1154403 -3.192432 -20.75352 0.3253632 -2.872902 -20.56136 0.1061515 -2.801404 -20.78531 0.3144627 -2.486322 -20.59835 0.09722709 -2.413623 -20.81716 0.3034916 -4.459038 -20.23753 0.05872917 -3.817296 -20.29825 0.05071818 -3.399112 -20.3417 0.04370689 -3.009974 -20.38326 0.03706169 -2.626996 -20.42518 0.03089129 -4.648206 -19.99877 0.007820129 -4.027008 -20.07046 0.005041122 -3.621131 -20.11835 0.001308441 -3.243293 -20.16282 -0.002485275 -2.868089 -20.20811 -0.005945146 -5.032971 -19.57122 -0.03240382 -4.460654 -19.63297 -0.03245341 -4.086691 -19.67322 -0.03410339 -3.734483 -19.71106 -0.03588289 -3.360739 -19.75911 -0.03654474 -2.884476 -19.85502 -0.03261744 -2.472922 -20.26289 -0.008197784 -5.550193 -18.78176 -0.07297325 -5.058342 -18.81272 -0.07266044 -4.738711 -18.83377 -0.07296371 -4.425366 -18.85772 -0.07290458 -4.045032 -18.91692 -0.06976699 -3.443482 -19.09652 -0.05667877 -5.664455 -17.84439 -0.09354972 -5.196097 -17.85987 -0.09332847 -4.892832 -17.87094 -0.09317207 -4.588094 -17.88679 -0.09258842 -4.216337 -17.94869 -0.08884429 -3.633601 -18.15672 -0.07493972 -2.830148 -18.50828 -0.0511837 -2.606473 -19.39994 -0.0339241 -5.422783 -16.87342 -0.09885025 -4.91986 -16.88207 -0.09871673 -4.589645 -16.88704 -0.09859657 -4.258581 -16.89077 -0.09840583 -3.900914 -16.91227 -0.09706687 -3.464328 -17.00881 -0.09096145 -2.949723 -17.19129 -0.07940101 -5.067903 -15.84259 -0.09975814 -4.503591 -15.84445 -0.09970664 -4.132029 -15.84484 -0.09966468 -3.771672 -15.84376 -0.09963226 -3.41636 -15.84487 -0.09945869 -3.088669 -15.86425 -0.09820556 -2.818453 -15.91327 -0.09518241 -2.645246 -15.93617 -0.09388732 -2.571077 -17.28823 -0.07382202 -2.535498 -15.9377 -0.09352684 -2.326455 -17.30734 -0.07310867 -4.869623 -14.70596 -0.09989738 -4.268343 -14.71128 -0.09989929 -3.871547 -14.71101 -0.09988594 -3.496819 -14.71043 -0.09987258 -3.142967 -14.70996 -0.09985351 -2.861852 -14.71144 -0.09970283 -2.700788 -14.71883 -0.09917068 -2.620505 -14.72243 -0.09881019 -2.570062 -14.72187 -0.09837532 -4.831112 -13.36011 -0.09955024 -4.233442 -13.40248 -0.09964561 -3.844593 -13.40672 -0.09963417 -3.48226 -13.40712 -0.09960365 -3.145844 -13.40762 -0.09955787 -2.891103 -13.40817 -0.09946823 -2.764222 -13.40918 -0.09925842 -2.708489 -13.41015 -0.09893035 -2.669294 -13.41407 -0.09844779 -4.896924 -11.55967 -0.09832763 -4.356392 -11.65107 -0.09850883 -4.035308 -11.66749 -0.09846115 -3.745874 -11.6705 -0.09834098 -3.480136 -11.67257 -0.09817695 -3.280385 -11.67461 -0.09794425 -3.178553 -11.67653 -0.09761238 -3.127025 -11.68108 -0.0971508 -3.068794 -11.71439 -0.09665489 -4.990178 -9.613795 -0.09705924 -4.526864 -9.64685 -0.09705734 -4.310093 -9.654314 -0.09690093 -4.140108 -9.65901 -0.09664916 -3.990897 -9.663847 -0.09630203 -3.879389 -9.668784 -0.09585571 -3.815278 -9.6743 -0.09528732 -3.766117 -9.689578 -0.09462738 -3.677944 -9.768033 -0.09407997 -4.911118 -8.664226 -0.09776115 -4.408106 -8.660754 -0.09772109 -4.170438 -8.664213 -0.09760856 -3.999986 -8.66911 -0.0974102 -3.867919 -8.674738 -0.09710693 -3.781779 -8.681126 -0.0966835 -3.733328 -8.687853 -0.09611511 -3.695488 -8.697215 -0.09541893 -3.63975 -8.735486 -0.09469223 -4.828107 -8.420681 -0.09882736 -4.249778 -8.412795 -0.09883689 -3.913699 -8.414162 -0.09881019 -3.636077 -8.416726 -0.09874343 -3.411901 -8.420454 -0.09860801 -3.269396 -8.425787 -0.09837722 -3.202203 -8.432297 -0.0980072 -3.165681 -8.439336 -0.09747886 -3.132896 -8.450535 -0.09680366 -4.803923 -8.349543 -0.0986309 -4.193405 -8.343438 -0.09866523 -3.800076 -8.343567 -0.09867668 -3.44422 -8.344281 -0.09867477 -3.131182 -8.345785 -0.09864425 -2.912609 -8.348801 -0.09855461 -2.809553 -8.353425 -0.0983448 -2.763852 -8.359115 -0.0979824 -2.732659 -8.365494 -0.09745025 -4.80083 -8.2874 -0.09683036 -4.184867 -8.283644 -0.0968647 -3.777362 -8.283535 -0.09688186 -3.397972 -8.283673 -0.09689712 -3.049416 -8.284234 -0.09689712 -2.792527 -8.285962 -0.09685897 -2.671393 -8.289288 -0.09671211 -2.621177 -8.293639 -0.09642028 -2.588919 -8.298668 -0.09597206 -4.800748 -8.225028 -0.09343719 -4.18433 -8.223334 -0.09346389 -3.775205 -8.223278 -0.09348106 -3.39265 -8.22334 -0.09350013 -3.037244 -8.223731 -0.09350585 -2.771293 -8.225197 -0.09347724 -2.647367 -8.228243 -0.09334754 -2.596739 -8.232033 -0.09309005 -2.564088 -8.236206 -0.09268951 -4.80078 -8.167485 -0.08429527 -4.18427 -8.167027 -0.08432388 -3.775073 -8.16703 -0.08433914 -3.392403 -8.167087 -0.0843563 -3.036633 -8.16749 -0.08436203 -2.770453 -8.169013 -0.0843296 -2.648005 -8.172153 -0.08420372 -2.598104 -8.175868 -0.08396148 -2.565174 -8.17973 -0.08362579 -4.800514 -8.113775 -0.03348726 -4.184213 -8.113644 -0.03353106 -3.77502 -8.113644 -0.03354454 -3.392381 -8.113702 -0.03355789 -3.036839 -8.114113 -0.03355026 -2.77151 -8.11566 -0.03346443 -2.650652 -8.118826 -0.03324699 -2.601675 -8.122544 -0.03294932 -2.568449 -8.126406 -0.03281593 -4.801889 -8.05811 0.1734218 -4.184172 -8.05799 0.1733741 -3.774982 -8.057979 0.1733589 -3.392354 -8.05802 0.1733608 -3.036925 -8.05836 0.1734676 -2.7718 -8.059653 0.1738376 -2.650518 -8.06241 0.1745108 -2.601099 -8.065938 0.1750373 -2.566653 -8.070082 0.1744785 0.6152819 -11.1997 49.34731 0.4763087 -11.31884 47.32046 0.2886705 -11.19372 49.31867 0.1374685 -11.29081 47.31778 -0.06451606 -11.18763 49.25674 -0.2183568 -11.26226 47.29556 -0.4191171 -11.18202 49.18175 -0.576669 -11.2358 47.25928 -0.7691212 -11.1778 49.11305 -0.9420247 -11.21479 47.21434 -1.148824 -11.17592 49.02579 -1.321217 -11.20235 47.14506 -1.567363 -11.17518 48.91528 -1.697057 -11.19558 47.05837 -2.001602 -11.17457 48.80753 -2.066606 -11.18966 46.97429 -2.441913 -11.17363 48.6941 -2.421968 -11.18163 46.91203 0.7051944 -11.63759 44.94374 0.3403686 -11.56916 44.99866 -0.03103613 -11.4991 45.04771 -0.4005497 -11.43213 45.08582 -0.7775993 -11.37368 45.10554 -1.146681 -11.32988 45.09646 -1.476214 -11.29831 45.07274 -1.791468 -11.26826 45.05107 -2.126265 -11.2318 45.0596 1.20159 -12.11729 42.40301 0.8381037 -12.02588 42.48899 0.4708677 -11.93102 42.57621 0.1058752 -11.83569 42.66362 -0.2654219 -11.74212 42.74679 -0.6231241 -11.65627 42.81783 -0.9382622 -11.58007 42.88185 -1.246896 -11.50239 42.94991 -1.603561 -11.41503 43.04513 1.802164 -12.6454 39.83617 1.455176 -12.54666 39.93334 1.104952 -12.44371 40.03546 0.7617148 -12.33951 40.14058 0.4186565 -12.23366 40.24797 0.08181738 -12.12756 40.35545 -0.2345397 -12.0229 40.46313 -0.5547109 -11.91147 40.57554 -0.9257577 -11.78666 40.69549 2.408202 -13.15987 37.30498 2.088011 -13.06075 37.40495 1.768398 -12.95816 37.51147 1.455953 -12.85451 37.61933 1.146775 -12.74956 37.72826 0.8395577 -12.64201 37.83982 0.5334628 -12.52968 37.95494 0.213423 -12.40747 38.07471 -0.1536453 -12.27029 38.19677 2.960434 -13.64194 34.80014 2.66647 -13.54402 34.89781 2.38091 -13.44487 35.00247 2.101875 -13.34536 35.10794 1.822302 -13.24518 35.21167 1.544813 -13.14134 35.31758 1.249233 -13.03009 35.42323 0.9092618 -12.91105 35.51882 0.5335932 -12.78433 35.60515 3.429 -14.0928 32.29134 3.144329 -13.99355 32.3808 2.868426 -13.89387 32.47746 2.595743 -13.79602 32.57383 2.299587 -13.70094 32.65884 2.017255 -13.60032 32.75215 1.63637 -13.49776 32.81142 1.082103 -13.40273 32.79285 0.5366919 -13.32075 32.73919 3.756823 -14.51939 29.76594 3.458244 -14.4139 29.84243 3.123902 -14.30889 29.91862 2.737045 -14.21562 29.97253 2.212871 -14.14021 29.96694 1.73475 -14.05659 29.98247 0.9511393 -13.9883 29.86708 -0.2926699 -13.95632 29.53397 -1.331951 -13.93896 29.2346 3.879865 -14.96257 27.23455 3.454162 -14.84623 27.25238 2.77847 -14.74701 27.20155 1.894956 -14.6903 27.06212 0.672755 -14.68556 26.77268 -0.3368697 -14.66374 26.56404 -1.645129 -14.65807 26.21177 -3.512425 -14.70014 25.5964 -4.804956 -14.73163 25.2048 3.469867 -15.52627 24.56984 2.588628 -15.42516 24.38376 1.065608 -15.38082 23.9846 -0.6416104 -15.40385 23.5043 -2.558222 -15.493 22.9236 -3.826289 -15.54359 22.60264 -4.819341 -15.57146 22.37852 -6.026194 -15.6169 22.04718 -6.772022 -15.64465 21.91384 1.496227 -16.32186 21.3576 0.153223 -16.29889 20.9681 -1.838185 -16.33973 20.36485 -3.524066 -16.40517 19.88451 -4.929533 -16.48835 19.50877 -5.691327 -16.5317 19.3937 -6.130292 -16.54983 19.40793 -6.615186 -16.56457 19.4063 -6.944431 -16.56409 19.49162 -1.767717 -17.35099 17.6703 -2.758852 -17.38022 17.41507 -3.984097 -17.42638 17.11684 -4.830331 -17.45975 16.98199 -5.422729 -17.48478 16.95305 -5.762815 -17.48919 17.03388 -6.003963 -17.48129 17.16355 -6.254745 -17.4653 17.29806 -6.479642 -17.43111 17.48163 -2.713539 -18.28038 14.96058 -3.425339 -18.33489 14.77359 -3.838697 -18.35615 14.75391 -4.316243 -18.36329 14.76469 -4.646852 -18.35521 14.84926 -4.921346 -18.34055 14.96937 -5.164225 -18.31678 15.1214 -5.401242 -18.29135 15.27992 -5.644923 -18.27508 15.41186 -5.885387 -18.23719 15.59436 -3.455549 -19.09414 12.84243 -3.655881 -19.095 12.90609 -3.86764 -19.07955 13.00313 -4.056409 -19.05722 13.11557 -4.275888 -19.03252 13.23729 -4.526779 -19.00154 13.38037 -4.795133 -18.97522 13.51812 -5.079006 -18.97377 13.59943 -5.364158 -18.95225 13.7299 -3.295736 -19.82143 11.17295 -3.540514 -19.81537 11.21902 -3.72424 -19.80385 11.27856 -3.900899 -19.7916 11.33647 -4.125254 -19.77913 11.39891 -4.392333 -19.76247 11.47748 -4.679068 -19.74765 11.55691 -4.980744 -19.75174 11.59447 -5.291004 -19.74337 11.66371 -2.498993 -20.5653 9.424946 -3.031614 -20.55654 9.451754 -3.445613 -20.54973 9.476702 -3.73387 -20.54492 9.499379 -3.985959 -20.54144 9.518136 -4.255942 -20.53842 9.537907 -4.543558 -20.53405 9.563124 -4.836195 -20.52904 9.592312 -5.134024 -20.531 9.606478 -5.444872 -20.52866 9.632021 -2.508541 -21.23031 7.669472 -2.865733 -21.22922 7.674553 -3.204226 -21.22876 7.678028 -3.546553 -21.22847 7.681423 -3.891372 -21.22806 7.685249 -4.235413 -21.22717 7.691059 -4.580898 -21.22754 7.69437 -4.946553 -21.22716 7.699844 -2.313232 -21.77289 5.863703 -2.691774 -21.77259 5.864744 -3.070935 -21.77227 5.865469 -3.449896 -21.77198 5.865969 -3.828379 -21.77159 5.866899 -4.207645 -21.77127 5.867729 -4.607082 -21.77088 5.869204 -2.346862 -22.06508 4.154921 -2.733198 -22.06258 4.15905 -3.119555 -22.06008 4.162828 -3.505956 -22.05755 4.166618 -3.893322 -22.05492 4.170292 -4.301902 -22.05229 4.173988 -2.422012 -21.87706 2.533438 -2.809164 -21.86707 2.541899 -3.196829 -21.85705 2.550333 -3.585753 -21.84674 2.55854 -3.997582 -21.83654 2.566433 -4.918241 -7.987106 0.8214111 -4.820394 -8.00623 0.5764637 -4.209626 -7.987038 0.8212662 -4.186514 -8.006175 0.5764103 -3.77741 -7.987003 0.8212624 -3.774989 -8.006152 0.5764027 -3.395404 -7.986986 0.821415 -3.392614 -8.006148 0.5764637 -3.047687 -7.987071 0.8220749 -3.038229 -8.006289 0.5768261 -2.78754 -7.987583 0.8237114 -2.773381 -8.00703 0.5778732 -2.653173 -7.989077 0.8259945 -2.647716 -8.008942 0.5795212 -2.592601 -7.992016 0.826994 -2.594705 -8.012074 0.5804215 -2.552862 -7.996881 0.8244209 -2.557547 -8.016724 0.5785809 0.814838 -11.17668 50.53823 0.4990611 -11.17576 50.51537 0.1630624 -11.17482 50.46685 -0.1759476 -11.17395 50.40582 -0.5164986 -11.17327 50.34376 -0.8929696 -11.17303 50.25821 -1.314692 -11.17292 50.15004 -1.767041 -11.17281 50.0392 -2.283892 -11.17265 49.89416 -2.889363 -21.22135 1.039732 -2.500756 -21.24453 1.028406 -3.280152 -21.19785 1.050905 -3.697765 -21.17441 1.062796 2.655298 -21.89019 -0.01995277 3.107971 -22.05034 -0.03033256 3.533921 -22.28449 0.1404075 3.222687 -22.23455 0.1471633 3.461435 -22.13919 -0.03673923 3.812665 -22.30244 0.1357288 3.765758 -22.18961 -0.0414772 4.080649 -22.3088 0.1316184 4.046772 -22.20868 -0.0446701 4.344686 -22.30899 0.127758 4.356305 -22.21172 -0.04665756 4.630077 -22.30679 0.1241035 2.373362 -21.57922 -0.05233561 2.829775 -21.76576 -0.06287384 3.213582 -21.91284 -0.07221603 3.527967 -21.98714 -0.07792091 3.861139 -22.00938 -0.08020401 2.661378 -21.42126 -0.07067298 3.042421 -21.54195 -0.07842063 3.404617 -21.58739 -0.08185768 2.650247 -20.93566 -0.06409263 3.037872 -20.98023 -0.06718254 2.480802 -20.43003 -0.05320358 2.884548 -20.48226 -0.05625712 2.419207 -19.99279 -0.04545778 2.847667 -20.07131 -0.04888331 2.744626 -19.63874 -0.04150009 -2.480411 -13.54981 -0.0964756 -2.424246 -14.7608 -0.09510231 -2.439581 -13.56223 -0.09510231 -2.315778 -14.83028 -0.09196281 -2.596713 -12.26614 -0.09609794 -2.550651 -12.29833 -0.09507369 -2.526471 -12.30034 -0.09383201 -2.408713 -13.56208 -0.09383583 -2.503345 -12.30151 -0.09249305 -2.375028 -13.56402 -0.09244728 -2.4665 -12.32155 -0.091053 -2.300034 -13.60485 -0.0902996 -2.911341 -10.75256 -0.09471702 -2.840479 -10.82839 -0.09378814 -2.814341 -10.84201 -0.09251594 -2.785035 -10.86176 -0.09116554 -2.714931 -10.94252 -0.08996391 -2.593205 -11.09154 -0.08896064 -2.399591 -12.37579 -0.08945083 -2.496809 -11.17136 -0.08776473 -2.338924 -12.40247 -0.08787918 -3.170513 -9.302105 -0.09358024 -3.125759 -9.338927 -0.09243774 -3.098752 -9.35204 -0.09110641 -3.051049 -9.397723 -0.08981323 -2.9342 -9.549124 -0.08883476 -2.749526 -9.801449 -0.08818435 -2.623012 -9.951236 -0.08715629 -2.55123 -9.99672 -0.0857582 -2.41186 -11.19554 -0.08633422 -2.956098 -8.609086 -0.09442138 -2.929236 -8.619732 -0.09322357 -2.905015 -8.627857 -0.09191131 -2.870874 -8.652194 -0.09056663 -2.79685 -8.738224 -0.08937454 -2.679473 -8.89153 -0.08836555 -2.606496 -8.976449 -0.08706283 -2.570821 -8.999302 -0.08549308 -2.533817 -9.019629 -0.083395 -2.464175 -10.05065 -0.08389282 -2.638846 -8.402446 -0.0949974 -2.613048 -8.40971 -0.09388923 -2.587988 -8.41714 -0.09266662 -2.562199 -8.427037 -0.09134864 -2.52698 -8.452488 -0.09000587 -2.477194 -8.50134 -0.08867454 -2.444027 -8.526329 -0.08719825 -2.421052 -8.535644 -0.08560371 -2.39521 -8.545624 -0.08349609 -2.503967 -8.317748 -0.0937252 -2.477345 -8.324625 -0.09270668 -2.451416 -8.331753 -0.09157371 -2.426211 -8.339224 -0.09034156 -2.400792 -8.348381 -0.08902549 -2.373208 -8.361943 -0.08765411 -2.349343 -8.370968 -0.08620452 -2.327045 -8.378414 -0.08468055 -2.300117 -8.388176 -0.08265113 -2.480163 -8.25164 -0.09065818 -2.453768 -8.257737 -0.08973121 -2.428005 -8.264199 -0.08870124 -2.40292 -8.271061 -0.08757209 -2.378528 -8.278182 -0.08636474 -2.354563 -8.285754 -0.0850811 -2.33151 -8.292994 -0.08374023 -2.309077 -8.300253 -0.08232688 -2.481974 -8.193219 -0.08187294 -2.456213 -8.198549 -0.08106231 -2.431005 -8.204333 -0.0801773 -2.406375 -8.210577 -0.07923698 -2.382356 -8.217118 -0.07819366 -2.358964 -8.223839 -0.07703971 -2.336188 -8.230761 -0.07583808 -2.313988 -8.237833 -0.07458686 -2.484446 -8.139571 -0.03170776 -2.459225 -8.144597 -0.03109741 -2.434496 -8.150078 -0.03067016 -2.410236 -8.156104 -0.03036308 -2.386669 -8.162455 -0.02977943 -2.363886 -8.16905 -0.0287857 -2.341701 -8.175915 -0.02779757 -2.320001 -8.182979 -0.02692222 -2.47867 -8.085574 0.1734561 -2.453266 -8.091614 0.1734714 -2.428308 -8.098324 0.1722488 -2.4038 -8.105666 0.170351 -2.38052 -8.113129 0.1694164 -2.358754 -8.120629 0.169897 -2.337835 -8.12851 0.1703147 -2.317314 -8.136837 0.1699714 4.410289 -11.35174 49.80249 4.396636 -11.74157 46.99814 3.91375 -11.3412 49.82618 3.918632 -11.71219 46.99257 3.576938 -11.32581 49.91289 3.560763 -11.67274 47.05892 3.261417 -11.30742 50.01762 3.217235 -11.62771 47.14845 2.952571 -11.28954 50.11861 2.8827 -11.58356 47.23067 2.64881 -11.27294 50.19925 2.551465 -11.54072 47.29499 2.334027 -11.25618 50.21009 2.211627 -11.49627 47.34732 1.977154 -11.23742 50.02783 1.846416 -11.44809 47.36741 1.588119 -11.22043 49.6588 1.467913 -11.40311 47.32793 4.731654 -12.32084 44.2483 4.275052 -12.28281 44.22295 3.912491 -12.22473 44.29507 3.559804 -12.16177 44.38348 3.211904 -12.09949 44.46209 2.858676 -12.0363 44.53097 2.497764 -11.96924 44.60565 2.127883 -11.8973 44.69357 1.756871 -11.82623 44.77502 5.286054 -12.94935 41.6134 4.804568 -12.90892 41.55329 4.433127 -12.8395 41.62553 4.073715 -12.76627 41.71072 3.71711 -12.69216 41.79166 3.356099 -12.61559 41.87349 2.993994 -12.53587 41.96323 2.633723 -12.45339 42.05985 2.274512 -12.37044 42.15542 5.935037 -13.60101 39.02812 5.403451 -13.52055 38.97865 5.014232 -13.43799 39.05069 4.643348 -13.35537 39.1336 4.274352 -13.27106 39.21458 3.906906 -13.18505 39.29764 3.545647 -13.09805 39.38607 3.192041 -13.01034 39.4767 2.842837 -12.922 39.56703 6.636844 -14.25037 36.4633 6.011067 -14.10355 36.47641 5.598093 -14.00275 36.5582 5.213078 -13.90929 36.63817 4.827642 -13.81474 36.71252 4.449505 -13.72031 36.7877 4.085826 -13.62747 36.86749 3.736601 -13.53589 36.95066 3.396295 -13.44393 37.03624 7.168005 -14.83539 34.03702 6.515514 -14.64621 34.04833 6.093833 -14.53072 34.11456 5.69619 -14.42457 34.17972 5.297778 -14.31825 34.24044 4.914974 -14.21551 34.30585 4.555865 -14.11811 34.37873 4.217041 -14.02411 34.45659 3.890396 -13.92996 34.53861 7.456176 -15.41849 31.69676 6.846418 -15.19119 31.68535 6.441992 -15.05394 31.72099 6.056833 -14.92947 31.75976 5.670809 -14.80717 31.79798 5.302729 -14.6934 31.84656 4.957887 -14.58936 31.90714 4.630221 -14.49011 31.97474 4.315636 -14.39082 32.04922 7.576628 -16.04449 29.44701 7.025723 -15.78925 29.42714 6.660671 -15.62989 29.42722 6.313016 -15.48291 29.43073 5.960229 -15.33866 29.43529 5.617912 -15.20523 29.45251 5.290688 -15.08403 29.48527 4.973024 -14.96853 29.52778 4.660661 -14.85253 29.57959 7.653543 -16.67749 27.2506 7.141354 -16.41696 27.2224 6.804744 -16.25025 27.20066 6.488207 -16.09447 27.18502 6.167575 -15.93914 27.17007 5.849592 -15.78811 27.16166 5.537052 -15.64304 27.16212 5.224834 -15.50127 27.16612 4.904548 -15.35806 27.17737 7.736491 -17.27822 25.0326 7.252268 -17.02624 24.99616 6.930912 -16.86212 24.96654 6.624686 -16.70544 24.94179 6.31483 -16.54625 24.91806 6.005048 -16.38539 24.89982 5.697027 -16.22665 24.88398 5.378326 -16.07438 24.85611 5.029396 -15.92313 24.8369 7.796394 -17.817 22.76239 7.325362 -17.57153 22.71712 7.009737 -17.40876 22.68511 6.70226 -17.25078 22.65427 6.389866 -17.09007 22.62435 6.072776 -16.929 22.59437 5.730892 -16.77848 22.52681 5.277144 -16.65087 22.39298 4.652183 -16.5279 22.30132 7.666968 -18.27254 20.36716 7.152347 -18.03322 20.2824 6.82706 -17.87483 20.24402 6.516458 -17.72259 20.2105 6.192214 -17.57065 20.17188 5.828266 -17.42892 20.08732 5.320109 -17.32926 19.82846 4.3634 -17.29427 19.38762 2.943858 -17.26393 19.11244 6.9579 -18.66848 17.5447 6.277681 -18.47002 17.30917 5.911643 -18.3514 17.22933 5.590545 -18.24026 17.18429 5.230091 -18.1339 17.12294 4.775043 -18.05073 16.95734 4.022467 -18.03726 16.50404 2.42757 -18.11605 15.82466 5.633691 -19.15184 14.2511 4.759878 -19.03919 13.83406 4.339937 -18.99873 13.70199 4.007888 -18.96448 13.65237 3.634163 -18.93285 13.60735 3.169555 -18.91034 13.52061 2.399537 -18.91968 13.29319 4.537554 -19.81173 11.54314 3.755679 -19.75797 11.25033 3.373064 -19.75348 11.17857 3.048451 -19.75341 11.15435 2.674501 -19.75508 11.13259 3.475938 -20.55506 9.481698 2.764475 -20.53676 9.381937 2.343521 -20.53913 9.364418 3.165861 -21.23746 7.663626 2.511936 -21.23232 7.640364 3.154431 -21.78629 5.849045 2.524035 -21.78442 5.846533 3.440333 -22.16488 4.04954 2.828628 -22.16131 4.064077 4.060542 -22.32926 2.303587 3.490139 -22.32345 2.333818 2.426132 -22.15981 4.06983 3.122411 -22.32109 2.347116 -2.455482 -8.019227 0.8151283 -2.462937 -8.036927 0.5730286 -2.428197 -8.028725 0.8120136 -2.436397 -8.045289 0.5715523 -2.401428 -8.039793 0.8048821 -2.410265 -8.054938 0.5669232 -2.375652 -8.0517 0.7959976 -2.384813 -8.065411 0.5607853 -2.352551 -8.063076 0.7897148 -2.361597 -8.075552 0.5567913 -2.332544 -8.073683 0.786974 -2.341084 -8.085158 0.55583 -2.314132 -8.084675 0.7842503 -2.321936 -8.095168 0.5548115 4.650704 -11.21878 51.78007 4.148651 -11.21607 51.89867 3.819706 -11.21154 52.04767 3.523926 -11.20599 52.2026 3.233074 -11.20062 52.35163 2.94097 -11.19581 52.45698 2.624793 -11.19108 52.39079 2.249525 -11.18554 51.96311 1.831259 -11.18054 51.26119 4.398756 -22.35009 0.814024 4.097461 -22.35103 0.822176 2.778021 -22.31918 2.357981 3.81445 -22.3518 0.829628 2.433489 -22.3172 2.369081 3.530663 -22.35195 0.8371792 2.85118 -22.14377 0.1573791 2.958698 -22.34451 0.8533383 2.65737 -22.32688 0.8629875 3.245843 -22.35091 0.8449478 -2.303095 -8.106131 0.5517426 19.02963 -18.9675 28.35232 19.89625 -19.3423 27.54176 16.40124 -15.90285 32.13352 16.42977 -17.84309 30.78401 22.46849 -20.04267 25.42493 27.48709 -20.93374 21.70521 19.71293 -18.00554 27.81631 17.29639 -18.21789 29.97345 17.22916 -16.61773 31.05422 13.1055 -21.9384 -0.060171 12.95284 -22.08302 0.07217216 13.28933 -21.68946 -0.08676528 13.45204 -21.21029 -0.09583282 13.57974 -20.48412 -0.0987358 13.72442 -19.74916 -0.09902191 13.96487 -19.17331 -0.09805679 14.34969 -18.74178 -0.09590148 14.84164 -18.37272 -0.09303092 15.28347 -18.06146 -0.08945465 15.6136 -17.78997 -0.08535385 15.90415 -17.56969 -0.0808258 16.14275 -17.36513 -0.07612991 16.19569 -17.10441 -0.07096672 16.02343 -16.72519 -0.0652008 15.98273 -16.52165 -0.06039232 16.03262 -16.44404 -0.05587387 16.05326 -16.39391 -0.05062866 15.81997 -16.25967 -0.04203593 9.05381 -13.28795 0.0322169 14.681 -15.74205 -0.01840388 5.829616 -11.82963 0.1771736 12.59357 -14.80939 0.03242874 14.44349 -14.13351 35.42015 14.19011 -11.41911 39.76467 15.43943 -17.65018 31.77589 16.42991 -20.2984 29.32496 17.00598 -21.52446 27.40424 17.08874 -22.18575 25.49136 16.95081 -22.67385 23.40665 16.76632 -23.05317 21.22178 16.58183 -23.31371 18.99688 16.41219 -23.43986 16.75757 16.27842 -23.42573 14.50823 16.17368 -23.28232 12.24839 16.05705 -23.02245 9.974503 15.76393 -22.67712 7.578558 15.12144 -22.3672 4.971643 14.32036 -22.19112 2.44319 13.90624 -22.05604 0.7279511 15.34528 -22.11644 2.657686 16.18921 -22.43334 5.218718 16.72788 -22.85342 7.73288 16.91181 -23.25304 10.04208 16.97631 -23.54401 12.29015 17.05012 -23.7103 14.54908 17.16915 -23.74956 16.80979 17.33792 -23.65141 19.0589 17.53183 -23.41693 21.2819 17.70975 -23.04938 23.44658 17.80599 -22.55414 25.4702 17.62578 -21.91121 27.23871 17.06447 -20.94379 28.76166 16.27959 -19.50962 30.20485 14.12045 -21.75256 -0.05609512 13.91446 -21.9198 0.08436203 14.39648 -21.50141 -0.08366966 14.66352 -21.05504 -0.09394454 14.85648 -20.33344 -0.09835243 15.00865 -19.49133 -0.09954261 15.23011 -18.75279 -0.09930419 15.59653 -18.23857 -0.09807777 16.0319 -17.89336 -0.0958271 16.38619 -17.6578 -0.0925579 16.62809 -17.4868 -0.08849143 16.79745 -17.35424 -0.08395004 16.93244 -17.24141 -0.07919502 17.01928 -17.14263 -0.07436752 17.04974 -17.0331 -0.06952095 17.10294 -16.96033 -0.06503105 17.1617 -16.90501 -0.06069374 17.2054 -16.85999 -0.0561161 17.19008 -16.8118 -0.05072212 16.88979 -16.66281 -0.041933 16.07426 -16.30368 -0.02459907 11.55439 -10.40809 43.95323 18.71143 -16.64527 28.79917 18.88501 -17.54294 28.89561 18.05709 -17.08033 29.97492 16.71938 -16.34073 30.92833 17.3834 -16.27406 30.80506 18.04741 -16.45967 29.50889 14.93293 -14.63891 34.59849 15.9118 -15.64972 32.95518 15.42236 -15.14431 33.77684 14.92929 -13.64353 34.38561 13.62173 -10.29624 41.92503 2.3 -10.21293 0.4570122 2.3 -10.24864 0.2026863 -2.3 -20.70844 9.047554 -2.3 -20.56779 9.415558 -2.3 -20.23535 10.1717 -2.3 -18.89005 13.35599 -2.147028 -18.25246 15.11031 -0.388123 -17.86278 16.55881 2.3 -10.27475 0.04191195 2.3 -10.28158 0.03198421 2.3 -10.30966 -0.01953506 2.3 -10.35877 -0.03488337 2.3 -10.4575 -0.04093742 2.3 -10.76475 -0.04533195 2.3 -11.58505 -0.05311012 2.3 -12.88048 -0.06454467 2.3 -13.97594 -0.07115173 2.3 -14.94092 -0.07268333 2.3 -16.17518 -0.06731224 2.3 -16.21734 -0.06696891 2.3 -17.80485 -0.05178439 2.3 -18.25087 -0.04749667 -2.3 -16.65676 -0.0826435 -2.3 -16.22536 -0.08781623 -2.3 -20.61697 0.09319686 -2.3 -20.82688 0.3003998 -2.3 -20.46242 0.0261116 -2.3 -20.41949 0.01731872 -2.3 -20.29147 -0.008405685 -2.3 -20.0054 -0.02374827 -2.3 -19.97506 -0.02406692 -2.3 -19.48351 -0.02844238 -2.3 -18.68578 -0.04034233 -2.3 -18.38044 -0.04686915 -2.3 -17.38351 -0.07122611 -2.3 -17.3085 -0.0731182 -2.3 -21.07469 8.080821 -2.3 -21.23178 7.665386 -2.3 -21.42671 7.015652 -2.3 -21.77291 5.863646 -2.3 -21.78396 5.799372 -2.3 -22.06538 4.154293 -2.3 -22.03833 3.909643 -2.3 -21.88029 2.530619 -2.3 -21.63625 1.93392 -2.3 -21.25673 1.022671 2.3 -21.96771 0.1735153 2.3 -21.96086 0.1685218 2.323315 -21.97548 0.1728229 2.3 -21.79805 0.03385722 2.3 -21.75486 -0.01023674 2.3 -21.65995 -0.0283432 2.3 -21.5484 -0.05071449 2.3 -21.52119 -0.0520153 2.3 -21.32151 -0.05995547 2.3 -21.27208 -0.06207835 2.3 -20.90846 -0.06006228 2.3 -20.85813 -0.0593928 2.3 -20.3997 -0.05151546 2.3 -19.97032 -0.04436671 2.3 -19.69654 -0.04226875 2.3 -19.49651 -0.04009056 -2.3 -16.01799 -0.08953475 2.3 -19.01131 -0.04117953 2.3 -18.92367 -0.04122912 -2.3 -15.46472 -0.0907135 -2.3 -14.88234 -0.09150314 -2.3 -14.83636 -0.0915699 -2.3 -14.37952 -0.09140586 -2.3 -13.98672 -0.091053 -2.3 -13.60497 -0.0902996 -2.3 -13.60487 -0.0902996 -2.3 -12.9122 -0.08848571 -2.3 -12.56441 -0.08746337 -2.3 -12.42203 -0.08716392 -2.3 -11.94359 -0.08598518 -2.3 -11.2541 -0.08466148 -2.3 -11.14624 -0.08434867 -2.3 -10.17288 -0.08256721 -2.3 -9.178708 -0.07881355 -2.3 -8.594099 -0.07999992 -2.3 -8.38823 -0.08264541 -2.3 -8.303503 -0.08167076 -2.3 -8.387677 -0.08263587 -2.3 -8.242856 -0.07360839 -2.3 -8.190367 -0.02579689 -2.3 -8.144541 0.1696681 0.9304676 -17.95517 16.39576 1.801134 -18.13516 15.73179 2.083319 -18.29332 15.23535 2.3 -18.92332 13.27265 -2.3 -19.03913 12.91042 2.3 -19.75823 11.11678 2.3 -19.63355 11.46788 2.3 -18.99278 13.10283 -2.3 -19.81462 11.10845 2.3 -20.53952 9.36343 2.3 -20.29354 9.923298 2.3 -20.01913 10.53666 2.3 -20.65596 9.073647 2.3 -21.23292 7.638298 2.3 -21.78436 5.846285 2.3 -22.01129 4.772398 2.3 -22.15935 4.071531 2.3 -22.21418 3.479506 2.3 -22.2893 2.667013 2.3 -22.31648 2.373568 -2.3 -8.102192 0.649538 -2.3 -8.108137 0.5509224 2.3 -22.32185 2.099318 2.3 -22.32789 1.687456 2.3 -22.32276 1.301071 2.3 -22.27419 0.8747521 2.3 -22.14586 0.5769501 -2.409708 -8.150076 16.52644 -1.232281 -7.982413 16.50328 -0.05485379 -7.814751 16.48011 1.122573 -7.647089 16.45695 2.005643 -7.521342 16.43958 2.3 -7.479426 16.43379 -2.393779 -8.139178 13.90274 -2.377849 -8.128275 11.27904 -2.36192 -8.117377 8.655344 -2.345991 -8.106475 6.031647 -2.330061 -8.095578 3.407948 -2.303533 -18.43139 2.094025 -2.307066 -14.98248 1.657434 -2.310599 -11.53358 1.220842 2.3 -8.390597 11.10819 2.3 -9.757349 3.119806 18.16301 -18.5927 29.16289 17.42473 -15.84954 30.68022 16.74241 -15.88508 31.64909 17.08357 -15.86731 31.16465 17.76589 -15.83177 30.19578 15.96509 -15.05381 32.31353 15.91996 -14.62929 32.65127 15.29728 -14.20836 33.82259 15.66526 -14.77319 33.25957 16.03325 -15.33802 32.69655 15.51678 -14.54549 33.69281 15.2108 -14.27143 33.69872 15.49232 -14.89933 33.01183 15.77384 -15.52723 32.32494 14.1925 -10.59738 39.42518 14.93168 -12.8218 34.04613 15.64029 -14.15519 33.42311 16.52476 -15.51255 31.86383 15.63393 -14.17591 33.42311 + + + + + + + + + + -0.2765447 -0.592944 0.7562676 -0.2212657 -0.6100217 0.7608647 0.8747938 -0.2989369 0.3812777 0.8968463 -0.2822684 0.3405752 0.1199291 0.9925267 0.02253621 -0.5501472 -0.6272987 0.551212 0.8536118 0.2229926 0.4707667 0.7894355 0.3702982 0.4895619 0.1710757 -0.9322445 0.3188313 0.1746811 -0.9329804 0.3146972 0.2767118 0.9606186 0.02534812 0.26317 0.9632382 0.0539782 0.2677208 0.960629 0.07428061 0.24571 0.962623 0.113946 0.247098 0.960903 0.1249321 0.3688484 -0.8658277 0.3380728 0.4026185 -0.8445642 0.3530011 0.3081951 -0.8786106 0.3647731 0.7923508 -0.4863699 0.3682725 0.7305719 -0.5583333 0.3931014 0.9395668 -0.1465487 0.3094154 0.9284095 0.290232 0.2319945 0.9281899 0.2916527 0.2310892 0.6097095 0.4163729 0.6744538 0.4500837 -0.62959 0.633278 0.5276619 -0.5684976 0.6311763 0.5146104 -0.5832961 0.6284441 0.6990593 0.2892779 0.6539376 0.6960274 0.2585815 0.669837 0.7332832 0.3930132 0.5548301 0.5154243 -0.6393525 0.5705842 0.7147701 -0.4432616 0.5409463 0.5037135 -0.691259 0.5181059 0.6268956 -0.5820157 0.5179378 0.54685 -0.643252 0.5358937 0.8545949 0.2361555 0.4624913 0.873519 0.325152 0.3622716 0.7715808 0.6347715 0.04157382 0.1448656 -0.9397483 0.3096565 0.1440282 -0.9399664 0.3093851 0.1438872 -0.9399994 0.3093506 0.1437255 -0.94003 0.3093325 0.1435267 -0.9400595 0.3093354 0.1433919 -0.9400717 0.3093608 0.1033962 -0.9394608 0.3266844 0.4052432 0.8371916 0.3672715 0.4044128 0.8537445 0.3279801 0.4530757 0.8312953 0.3219794 0.4888515 0.83662 0.2471663 0.490127 0.8324387 0.2584985 0.5333662 0.8204041 0.2060525 0.5503033 0.8208833 0.1526995 0.5477446 0.8253551 0.1369855 0.5793745 0.8099979 0.0907123 0.5819871 0.8114485 0.05331581 0.5820926 0.8113842 0.05314046 0.638908 0.7680379 -0.04375588 0.5823468 0.811744 0.04409205 -0.6297532 -0.6157569 0.4735549 -0.6271243 -0.611812 0.4820802 -0.6740888 -0.6303579 0.3850367 -0.7233219 -0.6162514 0.3115118 -0.7775397 -0.5790786 0.2451533 -0.6944345 -0.6441223 0.3207294 1 0 0 1 4.34386e-5 -4.58585e-5 0.1012165 0.9936186 0.0497722 0.2418743 0.9669437 -0.08072596 0.3517704 0.8901444 -0.2896565 0.3195886 0.9434149 -0.08849561 0.3643614 0.9312378 0.006073713 0.4288724 0.9010857 -0.06413435 0.3415963 0.9305972 -0.1315324 0.3586348 0.9302843 -0.07715153 0.4497634 0.8931341 0.00495392 0.4393292 0.8979347 0.02652245 0.5673806 0.8141528 -0.1234284 0.5424702 0.8392283 -0.03771001 0.1955646 -0.8704735 0.4516973 0.2745289 -0.7721596 0.5730651 0.30523 -0.6570816 0.6892594 0.9903779 0.1327791 -0.03900569 0.9073786 0.411976 0.08330732 0.910391 0.3720313 0.1810554 0.8286027 0.549072 -0.1092594 0.7531617 0.6424485 -0.1414474 0.7841907 0.6195156 -0.03529417 0.9000437 -0.3413186 0.2709667 0.8059368 -0.5302625 0.2632254 0.8074841 -0.456075 0.3741193 -0.2270628 -0.8699187 0.4378174 0.8582314 -0.4431294 0.2589889 0.9197093 -0.3618722 0.1522612 0.8714857 -0.43735 0.2218962 0.8124201 -0.558736 0.1666972 -0.2034402 -0.8764481 0.4364066 0.2270973 0.9730863 -0.03911411 0.2774356 0.9607216 0.006598591 0.2238269 0.9730694 -0.05511504 0.2000879 0.979775 0.002411663 0.188751 0.9813426 -0.03660368 0.266314 0.9637085 -0.01851809 0.2754487 0.9612818 -0.008094966 -0.2649552 -0.926997 0.2654722 -0.2992176 -0.9272769 0.2250037 -0.2998429 -0.9280348 0.2210106 -0.3246495 -0.9274774 0.1854413 -0.3248429 -0.9279558 0.182689 -0.3430627 -0.9276205 0.1477441 -0.3430419 -0.927904 0.1460013 -0.3559872 -0.9277253 0.112245 -0.355925 -0.9278642 0.1112907 0.9206781 0.3750267 -0.1081981 -0.6946316 -0.6997506 0.1668416 -0.19265 -0.8635104 0.4660857 0.1259086 -0.5479855 0.8269576 0.1832863 -0.6922962 0.6979486 0.2395898 -0.7246649 0.6461096 0.329984 -0.7194396 0.6111606 0.0436325 -0.7846593 0.61839 -0.1494631 -0.8515238 0.5025616 -0.3957169 -0.9000048 0.1827558 -0.4030995 -0.9021145 0.1539493 -0.3804592 -0.9247236 -0.01171875 0.249118 -0.6247054 0.7400563 0.3378812 -0.8061528 0.4857512 0.7485287 -0.5875669 0.3073599 0.4964367 -0.6811649 0.5381125 0.964366 -0.1841072 0.1900076 0.9985204 -0.05405604 0.005904436 0.9406746 -0.09921461 0.3244809 0.9400416 -0.0905314 0.3288251 0.4867955 -0.5134432 0.7066869 0.8262394 -0.3874681 0.4088976 -0.3666176 -0.9272909 0.07565152 0.8761611 -0.1649724 0.4529082 -0.3647384 -0.9277932 0.07852208 0.2001894 -0.5680657 0.7982641 0.178703 -0.9140027 0.3642312 -0.1870661 -0.7481036 0.6366689 0.8344711 -0.2209006 0.5048376 0.8941505 -0.2304474 0.383913 0.9409714 0.3361849 -0.03940296 0.9844916 0.1730106 -0.02904784 0.9969033 0.06551134 -0.04350113 0.9905535 0.1364798 -0.01331132 0.9999344 0.005161762 0.01022672 -0.704903 -0.694278 0.1452239 0.9614039 0.2549173 0.103537 0.9998169 0.002561151 0.01896607 0.9902074 0.1392088 -0.01050025 0.9922795 0.1211506 -0.02653324 0.7042478 -0.06135392 0.7072982 0.723954 -0.08034771 0.6851532 0.6983546 -0.06705117 0.7126044 0.7075442 -0.1746289 0.6847526 0.6875666 -0.2029372 0.6971863 0.6896808 -0.3566934 0.6301669 0.6601456 -0.2899676 0.6929116 0.7391219 -0.2969443 0.6045851 0.6596153 -0.2923738 0.6924054 0.7135636 -0.4679438 0.5213978 0.5224373 -0.7449324 0.4148916 0.5623661 -0.6221827 0.5446405 0.5389441 -0.639762 0.5479452 -0.1650034 -0.6948305 0.699989 -0.1721698 -0.7020146 0.6910377 -0.2965728 -0.6659907 0.6844713 -0.3183926 -0.6728953 0.667711 -0.4357246 -0.6285604 0.6442484 -0.4550653 -0.6281802 0.6311144 -0.6628967 -0.375903 0.6475067 -0.5342018 -0.5139489 0.6711819 -0.4991679 -0.6101915 0.6152218 -0.6978044 -0.07751291 0.712082 -0.9061433 -0.3123796 -0.2851728 -0.7172607 -0.1574011 0.6787945 -0.5739893 -0.07081031 0.8157956 -0.6710363 -0.1832849 0.7184129 -0.6809133 -0.2819241 0.6759259 -0.6374456 -0.3846918 0.6675892 -0.7220285 -0.4327786 0.539794 0 -1 0 0.1151525 0.9931564 -0.0194981 0.1239584 0.9922872 -6.71187e-4 -0.07000845 0.9917712 -0.1071863 -0.0679205 0.991501 -0.1109617 -0.04278165 0.9915737 -0.1222763 -0.04209768 0.9915069 -0.1230525 -0.01461929 0.991562 -0.1288068 -0.01424235 0.9915308 -0.1290888 0.01422011 0.9915563 -0.128895 0.01463288 0.9915259 -0.1290828 0.04209464 0.9915072 -0.1230508 0.04277229 0.9915734 -0.1222823 0.06837445 0.9914934 -0.1107522 0.2103148 0.971813 -0.1065237 0.04527235 0.9962331 -0.07396119 -0.1653153 0.9857093 -0.03237706 -0.1740422 0.9846468 -0.01341545 0.1215367 -0.4375811 0.8909274 -0.7823969 -0.2745542 0.5589948 0.6407406 -0.1897227 0.7439468 0.4665691 -0.1700204 0.8679898 -0.8757793 -0.119269 0.4677453 -0.9418965 -0.02902936 0.3346465 -0.9712265 0.01020675 0.237939 -0.7445436 -0.1339645 0.6539942 -0.3530704 -0.2099543 0.9117349 0.1107219 -5.49714e-6 0.9938514 0.556209 -0.07181787 0.8279335 0.3572553 0.1461067 0.9225082 0.7510636 0.02514988 0.6597508 0.9710704 -0.02063786 0.2379 0.8484113 -0.1308451 0.5129112 0.8678372 -0.1354736 0.4780225 -0.404849 -0.2260419 0.8860036 -0.7133304 -0.06060361 0.6982027 -0.5534498 -0.1223001 0.8238543 -0.1084439 -0.2059159 0.9725424 -0.2137923 -0.3760504 0.901598 0.7823921 -0.2746518 0.5589537 -0.01554942 0.9904477 -0.13701 0.015531 0.9904448 -0.1370324 -0.09152907 -0.9255643 0.3673597 -0.09961771 -0.9288842 0.3567221 -0.1623418 -0.9261417 0.3404508 -0.9997834 -0.01466304 0.01477044 0.9470618 -0.1894124 -0.2592238 0.7275759 1.10885e-6 0.6860272 0.7263349 -6.47435e-5 0.6873409 0.6954037 3.81418e-4 0.7186192 0.7153806 0.002266287 0.6987314 0.6999015 4.60437e-6 0.7142395 0.6315545 -0.002502381 0.7753275 0.6148212 -0.006633102 0.7886387 0.5668371 0.001422345 0.8238286 0.4715674 0.008823573 0.8817859 0.4264566 -0.001268327 0.9045072 0.4857828 -0.001645684 0.874078 0.4918568 0 0.8706762 0.4415683 -0.03337788 0.8966066 0.4167242 -0.0606988 0.9070042 0.4558038 -5.24582e-4 0.8900801 0.3554629 7.62319e-5 0.9346904 0.3920079 0.002701163 0.9199579 0.3657843 0.03911012 0.9298776 0.3227268 -0.009053826 0.9464489 0.2724103 -0.04837638 0.9609643 0.280018 -0.03618806 0.9593124 0.1562021 0.02802336 0.9873275 0.09442484 -0.04775995 0.9943857 0 0.03383988 0.9994273 -0.09442526 -0.04775947 0.9943857 -0.1562024 0.0280233 0.9873275 -0.2684329 -0.03007185 0.9628289 -0.3746126 -0.1566135 0.9138587 -0.2801765 -0.0140683 0.9598454 -0.3741351 0.002495288 0.9273709 -0.4835733 0 0.875304 -0.4715966 0.008808255 0.8817704 -0.4280529 -0.01026421 0.9036955 -0.4896452 -0.001503586 0.8719205 -0.4556709 -0.02415591 0.8898205 -0.5389025 3.44034e-4 0.8423681 -0.655739 -0.02015393 0.7547186 -0.614835 -0.003782629 0.7886468 -0.6950597 3.7897e-4 0.718952 -0.7273731 -8.2096e-5 0.6862422 -0.7262937 0 0.6873846 0 1 0 0 1 -1.3574e-6 0 1 1.46475e-6 0 -1 6.31455e-6 0 -1 3.61024e-6 -0.3275545 0 0.9448324 -0.3275169 3.45434e-6 0.9448454 -0.07958412 -6.9301e-6 0.9968282 -0.07951229 6.93082e-6 0.9968339 0.1735915 1.02028e-6 0.9848178 0.1736306 5.96466e-6 0.9848108 0.4153032 -4.7109e-7 0.9096831 0.4152941 -1.25627e-6 0.9096872 0.6303031 -6.90967e-6 0.7763491 0.6303395 -6.28128e-7 0.7763196 0.8050383 -7.53443e-6 0.593223 0.80509 7.21915e-6 0.5931527 0.9283255 -6.89107e-6 0.3717684 0.9283549 6.26373e-6 0.3716952 0.991964 -1.3191e-5 0.1265206 0.9919742 0 0.1264407 0.3275484 0 0.9448344 0.3275125 0 0.9448469 0.07960563 0 0.9968265 -0.1735881 0 0.9848184 -0.173588 0 0.9848183 -0.41532 0 0.9096754 -0.4152866 0 0.9096907 -0.6303395 0 0.7763196 -0.6302911 0 0.776359 -0.8050481 0 0.5932095 -0.8050481 0 0.5932096 -0.9283191 0 0.3717847 -0.9919632 0 0.1265275 -0.9919645 0 0.1265174 0.3232119 0.1619936 0.9323584 0.1810335 0.3289422 0.9268355 0.1843681 0.3297118 0.9259042 0.07847696 0.1685387 0.9825661 -0.1594551 0.3951821 0.9046575 -0.04530203 0.9315407 0.3608044 -0.1745894 0.8633992 0.4733501 -0.4005755 0.264048 0.8773927 -0.3237485 0.351995 0.8782292 -0.2226087 0.9204905 0.3211581 -0.5800568 0.3912647 0.7144551 -0.7805817 0.2446395 0.5751904 -0.6942732 0.3619239 0.6220899 -0.2604741 0.9344743 0.2427163 -0.270695 0.9316082 0.2425499 -0.3349845 0.921014 0.1987929 -0.8562537 0.3863095 0.342921 -0.323743 0.9400021 0.1076408 -0.3640642 0.9269705 0.09045988 -0.9669691 0.2230696 0.1233315 -0.9754664 0.1940395 0.1039909 -0.8142951 0.5440515 0.2023155 -0.5472676 0.8189945 -0.1724712 -0.195034 0.9805733 0.02092307 -0.3232576 0.1610887 0.9324994 -0.07827657 0.1788812 0.9807519 -0.1834009 0.3286097 0.9264879 -0.1848244 0.3284257 0.9262702 0.1593246 0.3968471 0.9039514 0.3865851 0.3653581 0.8467972 0.3285694 0.3081343 0.892802 0.03930556 0.9309108 0.3631259 0.1814492 0.8602719 0.4764541 0.2225846 0.9205056 0.321132 0.5802216 0.3906934 0.714634 0.2665995 0.9312447 0.2484114 0.2664144 0.9335919 0.2396447 0.7469069 0.3730877 0.5503961 0.7082587 0.3041164 0.6370894 0.3350256 0.9209918 0.1988267 0.8564051 0.3859346 0.3429648 0.356754 0.9266383 0.1186102 0.3222697 0.9460166 0.0345661 0.1943072 0.9768199 -0.08982032 0.5503162 0.8236199 0.1371222 0.924662 0.303178 0.2303984 0.8166602 0.5456547 -0.1879558 0.9731981 0.1935952 0.1241225 0.3273745 0.03110176 0.9443827 0.07822102 -0.184389 0.9797359 0.02501565 -0.1189278 0.9925877 -0.1666516 -0.279798 0.9454842 -0.1961248 -0.2753196 0.9411346 -0.3827014 -0.3884598 0.8382354 -0.6123525 -0.2370137 0.7542208 -0.646665 -0.3296771 0.6878498 -0.1073998 -0.9363875 0.3341314 -0.2087712 -0.9238766 0.3207287 -0.2956834 -0.8938331 0.3370961 -0.3453026 -0.8654546 0.36298 -0.3200486 -0.9223811 0.2162918 -0.7414517 -0.3895511 0.546351 -0.3466377 -0.924839 0.1565729 -0.336254 -0.9377017 0.08745783 -0.2987635 -0.9539889 0.02541112 -0.1945869 -0.9782517 -0.07183051 -0.5490832 -0.8217217 0.1525814 -0.9094707 -0.2004849 0.3642373 -0.902157 -0.3510898 0.2506968 -0.8166332 -0.5456861 -0.1879811 -0.9732018 -0.1935746 0.1241261 0.5576342 7.51469e-7 0.8300868 0.557638 5.00983e-7 0.8300844 0.1108124 1.87874e-7 0.9938414 0.1107438 0 0.993849 -0.3611416 0 0.932511 -0.7513242 0 0.6599335 -0.7512963 1.25245e-6 0.6599652 -0.9712766 5.00997e-7 0.2379534 -0.9712766 5.00997e-7 0.2379534 -0.5576312 0 0.8300889 -0.557637 -1.56557e-7 0.8300849 -0.1108707 -1.6125e-6 0.9938349 -0.1108075 2.16828e-6 0.993842 0.3611434 8.61033e-7 0.9325104 0.3611431 0 0.9325105 0.7512819 -1.22102e-6 0.6599816 0.7512957 0 0.6599659 0.9712764 0 0.2379541 0.9712764 0 0.2379544 -0.5202021 -0.2587857 0.8138917 -0.5562564 -0.06917119 0.8281269 -0.5763393 -0.1463345 0.8040021 -0.5728638 -0.1417655 0.8072978 -0.5029378 -0.1015876 0.8583318 -0.5349453 -0.1696683 0.8276752 -0.3679282 -0.4636242 0.8060282 -0.4224231 -0.4853736 0.7654877 -0.2873646 -0.5379143 0.7925087 -0.210866 -0.4659557 0.8593142 -0.1088842 -0.1910612 0.9755204 0.04712593 -0.2458066 0.9681727 -0.07668215 -0.520735 0.8502676 -0.3118368 -0.7055625 0.6363485 0.03120207 -0.838321 0.5442835 0.2198941 -0.6634065 0.7152192 0.3478276 -0.2695963 0.897961 0.5071617 -0.6845972 0.5235588 0.6574991 -0.325843 0.6793535 0.008528947 -0.9368426 0.3496477 -0.01764112 -0.792544 0.6095597 -0.1934117 -0.8588067 0.4743872 0.7144376 -0.3091737 0.6276867 0.6160446 -0.7053954 0.35058 0.406179 -0.8900594 0.2069135 0.2214015 -0.9747955 -0.02747797 0.4447024 -0.8874117 0.1214101 0.9410014 -0.2477193 0.2305462 0.8154011 -0.5788217 -0.009303331 0.9582981 -0.2445758 0.1478089 0.1180269 -0.9657253 0.2311804 0.4715339 -0.01438331 0.8817307 0.4123373 -0.3059499 0.8581216 0.2931746 -0.7044122 0.6464149 0.1430624 -0.9533305 0.2658839 0.3391724 -0.385228 0.8582317 0.1304557 -0.9094452 0.3948302 0.07104355 -0.9424941 0.3265849 0.05431234 -0.7523031 0.6565746 0.2044878 -0.371491 0.9056375 0.03996735 -0.7316394 0.6805193 0.01607573 -0.9880259 0.1534489 -0.03998005 -0.7315895 0.6805721 -0.01607781 -0.9880257 0.1534495 -0.07104778 -0.942493 0.3265871 -0.130474 -0.9094431 0.394829 -0.4424552 -0.1168858 0.8891407 -0.1419817 -0.9500071 0.2780789 -0.1384986 -0.9539637 0.2660292 -0.2931654 -0.7044133 0.6464178 -0.4555945 -0.2584301 0.8518495 0.556284 -0.06905871 0.8281179 0.5464243 -0.0751962 0.834126 0.5760322 -0.1381621 0.8056663 0.4918599 -0.3073523 0.8146217 0.5331541 -0.2321003 0.8135577 0.5242645 -0.2285823 0.820303 0.4919357 -0.2657557 0.8290798 0.4866985 -0.2608633 0.8337117 0.2261431 -0.4302094 0.8739446 0.1192957 -0.196326 0.9732547 0.1085587 -0.1969446 0.9743859 0.2952561 -0.7045631 0.6453021 0.3609509 -0.6370854 0.6810556 0.2607312 -0.5979611 0.7579327 0.008400917 -0.5754379 0.8178024 0.1316797 -0.6925209 0.7092781 -0.2890243 -0.2736085 0.9173895 -0.1371402 -0.6223377 0.7706415 -0.3474865 -0.2725113 0.8972128 3.52841e-4 -0.9540959 0.299501 -0.06956505 -0.8381105 0.5410467 0.1195178 -0.9101297 0.3967108 -0.3796347 -0.7014829 0.6031578 -0.2014117 -0.8733096 0.4435806 -0.6472467 -0.3049419 0.6986289 -0.4819381 -0.6994643 0.5277172 -0.2139053 -0.9764404 -0.02843868 -0.4322174 -0.8915219 0.135562 -0.7187631 -0.2910751 0.6313913 -0.6910422 -0.6792832 0.2470529 -0.4514324 -0.8852328 0.112124 -0.9365106 -0.2651549 0.2294362 -0.9238876 -0.2623658 0.2785608 -0.7754997 -0.6209436 0.1141469 0.08395129 -0.4719871 0.8775993 0.07371973 -0.3143951 0.9464255 0.03183537 -0.7180128 0.6953015 0.05569833 -0.912407 0.4054765 0.06149959 -0.8951035 0.4415965 0.06956899 -0.9881621 0.1367333 0.01244974 -0.9194355 0.3930438 0 -1 1.70303e-7 0 -1 -2.52386e-7 1.36903e-5 0 1 -5.35298e-6 0 1 8.08107e-6 0 1 -1.63736e-5 0 1 -1.5586e-5 -7.84101e-6 1 5.31347e-6 2.30425e-6 1 0 0 1 7.94939e-6 2.76239e-6 1 0 1.83105e-6 1 -1.62221e-6 3.04165e-7 1 -6.38804e-6 5.80304e-7 1 1.99552e-6 6.54721e-7 1 -2.66633e-6 4.07788e-7 1 -1.37195e-6 1.41935e-7 1 0 5.72205e-6 1 0.04408574 -0.7186179 0.6940064 -0.04408651 -0.7186173 0.6940069 0.1970235 -0.3283062 0.9237948 -0.1148496 -0.9055472 0.4084042 0.3531512 -0.8725569 0.3375332 0.1973835 -0.8019867 0.5637883 -0.1888824 -0.6709985 0.7169969 -0.2527263 -0.650121 0.7165698 0.1260054 -0.653403 0.7464497 -0.2126865 -0.2951455 0.9314792 -0.2042688 -0.3007043 0.9315854 0.1040017 -0.3002218 0.9481829 -6.2745e-5 -0.1876349 0.9822388 0.2625882 -0.1267663 0.9565448 0.2700781 -0.1371663 0.953018 -0.2703456 -0.1375412 0.952888 -0.2625882 -0.1267647 0.956545 6.2745e-5 -0.1876351 0.9822388 -0.1040016 -0.3002231 0.9481824 0.2042653 -0.3007037 0.9315863 0.2126865 -0.295145 0.9314794 -0.1260039 -0.6534029 0.7464501 0.2527356 -0.6501181 0.7165691 0.1888756 -0.6710071 0.7169906 -0.1973823 -0.8019862 0.5637893 -0.3531547 -0.8725564 0.3375309 0.1148537 -0.9055467 0.4084042 -0.1970798 -0.3274866 0.9240736 -0.01244157 -0.9194347 0.3930459 -0.06952553 -0.9881651 0.136733 -0.06146097 -0.8951039 0.4416012 -0.05566424 -0.9124081 0.405479 -0.03181594 -0.7180131 0.695302 -0.07368135 -0.3143089 0.946457 -0.08391469 -0.4719886 0.8776021 -0.2046048 -0.3709528 0.9058316 -0.05429637 -0.752249 0.656638 -0.3395789 -0.3843509 0.858464 0.9732046 -0.1936094 0.1240491 0.8166169 -0.5456535 -0.1881468 0.9023509 -0.3499483 0.2515935 0.9094862 -0.2005922 0.3641397 0.5490384 -0.8216587 0.1530814 0.1945958 -0.9782631 -0.07165032 0.2984449 -0.9540896 0.02537357 0.3363728 -0.9375846 0.08825218 0.346641 -0.924838 0.156572 0.7418163 -0.3885824 0.5465459 0.3200514 -0.9223796 0.2162938 0.3453028 -0.8654544 0.3629802 0.2956917 -0.8938283 0.3371013 0.2087665 -0.9238765 0.3207318 0.1074026 -0.9363889 0.3341265 0.6468895 -0.3287427 0.6880859 0.612537 -0.2361286 0.7543486 0.3827643 -0.3879507 0.8384425 0.1960151 -0.2749737 0.9412586 0.1666702 -0.2794895 0.9455721 -0.02492785 -0.1190542 0.9925749 -0.07813155 -0.1847195 0.9796807 -0.3273793 0.02955549 0.9444308 -0.3660949 0.03954553 0.9297369 -0.3923583 0.003088653 0.9198074 -0.4278048 -9.71918e-4 0.9038707 -0.7175689 0.002581298 0.6964827 -0.6999155 0 0.7142257 -0.9997619 -0.02028256 0.008049547 -0.1050837 0.9935913 0.04163873 0.009287655 0.9989367 0.0451579 -0.07535898 0.9953441 -0.06009548 0.04500985 0.9983416 -0.0358926 -0.07723832 0.9952924 -0.05854403 0.04527169 0.9983853 -0.0343151 0 1 1.17902e-6 0 1 -3.96106e-6 0 1 1.7681e-6 1 -1.23155e-4 0 -1 0 0 -0.5430648 0.8396907 4.8243e-4 -0.8264315 0.5630374 3.27285e-4 -0.9801973 0.1980232 0 -0.9803792 0.1952806 0.02687489 0.4829672 0.8754979 -0.01568543 0.552735 0.8333572 -1.38918e-4 0.8264318 0.5630369 3.26034e-4 0.9800147 0.1989253 1.63455e-4 0.9659199 -0.2588413 0 0.7070788 -0.7071184 0.004824161 0.2588038 -0.9659232 0.003612756 -0.2588232 -0.9659247 0 -0.7070981 -0.7070991 0.004824101 -0.9659172 -0.2588262 0.003614008 0 1 -9.59339e-7 0 1 1.90647e-6 0 1 -9.52163e-7 0 1 -2.04589e-7 0 1 -9.52417e-7 0 1 -5.49499e-7 0 1 2.19792e-6 0 1 -1.099e-6 0 1 1.09898e-6 -0.5393718 0.8339775 0.1164455 -0.8262842 0.5629437 -0.01867771 -0.8509892 0.5205124 0.06988853 -0.9828293 0.1844673 -0.004311978 0.6048252 0.791159 0.09085094 0.826304 0.5629148 -0.01867574 0.8509948 0.5204946 0.06995165 0.9800137 0.1989264 -0.0011729 -0.3826076 0.9238334 0.01196289 -0.6054968 0.7920567 -0.0775873 -0.9824233 0.1831236 0.03619861 -0.8434489 0.531382 -0.07891285 -0.9204112 0.3813338 -0.08618503 -0.3511084 0.9344615 0.05920118 -0.7671238 0.4246786 0.4808006 -0.3085543 0.9234256 0.2282096 -0.3523123 0.9094601 0.220813 -0.7682716 0.3935278 0.5048709 -0.1669287 0.9277174 0.333879 -0.2949073 0.4132841 0.8615254 -0.3027078 0.4024096 0.8639644 -0.1389548 0.9074007 0.3966304 0.002523839 0.9349595 0.3547455 0.2963585 0.4032516 0.8657712 0.3010102 0.4138927 0.8591192 0.139292 0.906939 0.3975669 0.1703296 0.9286363 0.3295792 0.7682678 0.3935388 0.5048681 0.349473 0.9026598 0.2511453 0.3348155 0.9186195 0.2098501 0.7671203 0.4246777 0.4808068 0.3527267 0.9339998 0.05681836 0.9204801 0.3834776 -0.0752415 0.6135852 0.7808452 0.1174477 0.4356986 0.8971672 -0.07251191 0.9823441 0.1835778 0.03604722 0.8434548 0.5313722 -0.07891529 0.6050711 0.7903802 0.09585493 0.4783646 0.8781316 -0.007226884 -0.9996244 3.63938e-4 0.02740442 0.9978137 0 -0.06609171 0.997798 -1.23135e-4 -0.06632667 -0.8357059 0 0.5491774 -0.8357015 0 0.549184 -0.3238538 0 0.9461072 -0.3238536 0 0.9461073 0.3238513 0 0.9461081 0.3238511 0 0.9461081 0.8357062 0 0.5491769 0.8357018 0 0.5491836 -0.9970436 0.005228877 -0.07665938 -0.9977977 0 -0.06633269 -0.964488 -0.2584432 -0.05449819 -0.6995551 -0.6995551 0.1457577 -0.6235514 -0.6657869 0.40977 -0.2084825 -0.7652289 0.6090648 0 -0.845002 0.5347632 0.2084811 -0.7652284 0.6090658 0.6235543 -0.6657841 0.4097701 0.9644858 -0.2584517 -0.05449753 0.6995359 -0.6995714 0.1457725 0 1 1.39909e-6 -0.1872088 0.9823201 -4.94121e-4 -0.6798587 -0.7150549 0.1627534 -0.2588247 -0.9659243 0 0.2588048 -0.9659296 0 0.6798605 -0.7150546 0.1627473 0.6806189 -0.4674208 0.5641594 0.6841515 -0.4691823 0.5583949 -0.06979531 0.9911364 -0.1130377 -0.1700219 0.9853903 0.009942173 0.4937713 -0.5547966 0.6696198 -0.8891671 -0.2823317 0.3600983 -0.06967383 0.9911667 -0.112846 -0.04752159 0.9918993 -0.1178025 0.8296493 0 0.5582849 1 0 -5.23948e-5 -0.5555875 0.8314582 -3.20701e-4 -0.8314915 0.5555375 -1.64712e-4 -0.9807852 0.195091 1.67449e-4 0.1950896 0.9807813 0.002891361 0.5555682 0.831471 -3.21434e-4 0.8314709 0.5555682 -1.64136e-4 0.9807816 0.1951091 -5.13937e-5 0.9807696 -0.1951106 0.004793465 0.8314688 -0.5555663 -0.002418577 0.5555855 -0.831456 -0.002417385 0.1950926 -0.9807848 0 -0.1950854 -0.9807746 0.004794239 -0.5555857 -0.8314559 -0.002417504 -0.8314536 -0.5555889 -0.002417385 -0.9807861 -0.1950863 0 -0.195077 0.9807879 0 -0.4398658 0.8976941 0.02576106 -0.34308 0.9296292 -0.1344832 -0.1209127 0.9899573 -0.07324439 -0.9531908 0.2032274 0.2238882 -0.9473353 0.2911642 0.13334 0.1918277 -0.8630211 0.4673296 -0.1259095 -0.5479833 0.826959 -0.1824622 -0.6903188 0.7001196 -0.2695378 -0.738236 0.6183503 -0.04402697 -0.7844834 0.6185849 0.344869 -0.8710687 0.349721 -0.2490009 -0.6207662 0.743403 -0.5327315 -0.6768571 0.5079977 -0.4866598 -0.6858462 0.5410891 -0.9643707 -0.1841045 0.1899862 -0.9393259 -0.2294074 0.2550275 -0.9744615 0.2097297 0.08024001 -0.9417722 -0.1188765 0.314537 -0.4720413 -0.5159757 0.714805 -0.5530026 -0.4998676 0.6665738 -0.1070452 -0.9371812 0.3320133 -0.08362567 -0.9754937 0.2035161 -0.9561886 0.2784952 0.09024399 0.8183946 -0.5591347 0.1326605 0.2641203 -0.9384378 0.2226543 0.3083107 -0.9294105 0.2028321 0.333343 -0.9270867 0.1714428 0.342742 -0.931617 0.1209043 0.4158292 -0.9039118 0.1001488 -0.02010136 -0.9983822 0.05318713 -0.2465067 0.9682108 -0.04245495 -0.2326099 0.9725037 -0.01136928 -0.2238139 0.9730722 -0.05511599 -0.2000839 0.9797759 0.002407371 -0.1797862 0.9814465 -0.06663262 -0.1646898 0.9861021 -0.02190947 -0.1375575 0.9871777 -0.08098256 -0.1393815 0.9861038 -0.0903995 -0.09302836 0.9914762 -0.09121805 -0.1179179 0.9614151 0.248549 -0.2802218 0.9171322 0.2834508 -0.17039 0.9612234 0.2168338 -0.1709746 0.9616591 0.2144284 -0.2144727 0.9610534 0.1742925 -0.2146787 0.9620075 0.1686855 -0.2470536 0.9608833 0.1251714 -0.2456626 0.9626379 0.1139221 -0.2677095 0.960619 0.07445007 -0.2631573 0.9632418 0.05397635 -0.2767171 0.9606145 0.02544927 -0.2688915 0.9631381 -0.007906138 -0.2554129 0.9665963 0.02135545 -0.06977146 0.9915633 -0.1092442 -0.3400511 -0.6263021 0.7015063 -0.2235319 -0.5177263 0.8258288 -0.2764585 0.3216236 0.9056097 -0.6454372 -0.570703 0.5076504 -0.6437076 -0.5743155 0.505769 -0.8400802 0.2612784 0.4753934 -0.6797812 0.6453116 0.3485261 -0.8839516 0.0880292 0.4592176 -0.8141447 0.3264302 0.4802207 -0.75747 0.3963561 0.5187882 -0.5314251 -0.5620095 0.6338239 -0.4964224 -0.6743913 0.5465908 -0.6934384 0.3281303 0.6414623 -0.6976405 0.3153176 0.6433293 -0.4526651 -0.6393352 0.6215665 -0.594153 0.4217028 0.6849445 -0.4963496 0.3667774 0.7868364 -0.5515133 0.1910762 0.8119871 -0.4038644 0.4439283 0.7998883 -0.4172114 -0.5408457 0.7303566 -0.411972 -0.606404 0.6801127 -0.7042332 -0.6028249 0.3750438 -0.5508975 -0.7064312 0.4443727 -0.9400402 -0.1471168 0.3077031 -0.9538535 0.1968067 0.2267833 -0.7761374 0.607508 0.1689519 -0.8967558 0.4056267 0.1769075 0.3300456 -0.8072393 0.4893208 -0.2001882 -0.568071 0.7982607 -0.1971265 -0.772678 0.6034153 -0.5600925 -0.4294145 0.7084487 -0.8671642 -0.4895982 0.09121441 -0.7916694 -0.5355212 0.2940694 -0.8690285 -0.3156554 0.3809871 0.4041023 -0.5643878 0.7198387 0.3380087 -0.8513076 0.4012801 0.5200874 -0.7874134 0.3308917 0.1497556 -0.7814193 0.6057698 -0.673095 -0.6536995 0.3458614 -0.7948695 -0.5233038 0.3071411 -0.9916679 0.1243159 -0.03376728 -0.9546882 0.2962352 0.02855378 -0.9338712 0.3528605 -0.05808752 -0.9701194 0.2232395 -0.0950405 -0.8466305 0.5286223 -0.06144446 -0.7798141 0.6257053 -0.01956814 -0.7979571 0.6005268 -0.0513038 -0.76799 0.6403126 -0.01382827 -0.8011773 0.589332 -0.1039363 -0.7627707 0.6444361 -0.05369436 -0.727113 0.686003 0.02658373 -0.7186775 0.6953432 -7.03885e-4 -0.6761888 0.7332341 0.07167011 -0.1938166 -0.8716145 0.4502482 -0.334842 -0.6711639 0.6613773 -0.1441257 -0.939689 0.3101813 -0.1445419 -0.939689 0.3099875 -0.1445435 -0.9396897 0.3099849 -0.1214971 -0.9360854 0.330125 -0.1497856 -0.939287 0.308714 -0.1492024 -0.9378129 0.3134413 -0.1485664 -0.9376174 0.3143272 -0.1064835 -0.9430894 0.3150297 -0.164999 -0.9329215 0.3200513 -0.1735486 -0.9326429 0.3163195 0 1 4.53125e-7 0 1 0 0 1 -8.33491e-7 0 1 0 0 1 2.18866e-7 0 1 2.40837e-7 -0.1431156 -0.9386841 0.313672 -0.5999672 0.7818619 -0.1695035 -0.3586148 0.9302918 -0.07715433 -0.3416084 0.9305922 -0.1315364 -0.4758468 0.8778123 -0.05491399 -0.3378105 0.9405947 0.03414219 -0.3705772 0.9288012 -9.99334e-4 -0.2694845 0.9591628 -0.08593535 -0.15145 0.9877588 0.03735691 -0.9987608 0.0224263 0.04443156 -1 -2.00674e-6 0 -0.001180827 -0.9999989 -0.001035869 0.6689726 -0.7179068 0.1925759 0.7136579 -0.6457908 0.2713793 0.6746123 -0.6515424 0.346974 0.6488733 -0.6298755 0.4268728 0.6481493 -0.6266586 0.432668 0.5822665 -0.6480965 0.4908532 0.6805555 -0.5790751 0.4489057 -0.5587534 0.8293173 -0.005236923 -0.6304401 0.7734203 -0.06607842 -0.6232864 0.7819261 -0.01027661 -0.623549 0.7816022 -0.01687884 -0.5816628 0.8124368 0.04018729 -0.5819034 0.8114953 0.05351597 -0.5660057 0.8204912 0.08019912 -0.5820396 0.8125507 0.03148519 -0.5772521 0.8084248 0.1150189 -0.543753 0.8255069 0.151232 -0.5412144 0.8206725 0.1832586 -0.4846063 0.8395687 0.2455226 -0.5106934 0.8274896 0.2333521 -0.4737957 0.816018 0.331108 -0.404368 0.8535255 0.3286046 -0.396876 0.8348733 0.3814132 -0.3206833 0.854772 0.4080774 -0.3302968 0.8481132 0.414256 -0.2594676 0.8268337 0.4990217 -0.2167969 0.8626586 0.4569675 2.42425e-4 -1 -3.1378e-5 -0.001078903 -0.9998143 0.01923918 -0.2663823 -0.9281535 0.2599455 -0.2226714 -0.9283232 0.2977141 0.09301239 0.9914765 -0.09123075 0.1393746 0.9861056 -0.09039115 0.1375457 0.9871777 -0.08100396 0.1494137 0.987223 -0.05537319 0.06819623 0.9915381 -0.1104608 0.07177007 0.99107 -0.1123802 0 1 -1.44674e-6 0 1 1.09329e-6 0 1 0 0 1 -1.00674e-6 0 1 5.00188e-7 0 1 5.85516e-7 0 1 5.62786e-7 -9.45881e-4 0.9999995 -2.75818e-4 -0.008570671 -0.9999616 0.001845955 -0.00804609 -0.9999645 0.002516567 -0.007454335 -0.9999672 0.003172397 -0.006781578 -0.9999697 0.003813266 -0.006014287 -0.9999721 0.004433631 -0.005139946 -0.9999743 0.005015254 -0.004145205 -0.9999762 0.005542516 -0.003020942 -0.9999776 0.005984425 0.3253078 0.86088 0.3912294 0.3353339 0.8403869 0.4257947 0.2328538 0.8649786 0.4445123 0.2502915 0.8126863 0.5262085 0.1764569 0.8381875 0.5160472 0.108153 0.8436713 0.5258532 0.111874 0.8617501 0.4948445 2.93952e-4 0.8386349 0.544694 -0.009138107 -0.9999578 0.001010715 -0.006300806 -0.9999618 0.006074786 0.1039827 -0.9435236 0.3145646 0.07082712 -0.9362 0.3442571 -0.005549609 -0.9507325 0.3099626 0.04523348 -0.9048653 0.4232882 0.144534 -0.9396931 0.309979 0.1445415 -0.9396914 0.3099805 0.1273764 -0.9415367 0.3119037 0.1891373 -0.9183689 0.3475999 0.3039665 0.342953 0.8888125 0.2804162 0.2789188 0.9184613 0.1553155 -0.6371626 0.7549178 0.2523761 -0.5058105 0.8249012 0.1803314 0.445826 0.8767666 0.02352964 0.3836897 0.9231623 0 -0.5819071 0.8132553 0.4301446 -0.5448245 0.7198209 0.3903565 -0.607702 0.6916069 0.5324332 0.4040622 0.7438069 0.4447464 0.03826415 0.8948388 0.4621932 0.5201581 0.7182013 0.2946085 -0.6401373 0.7095282 1.71358e-4 0.9474422 0.3199272 0.1941332 0.9599966 0.2017894 0.1373166 0.9475201 0.2887035 0.1705607 0.9612523 0.2165713 0.171053 0.9616236 0.2145248 0.214577 0.961078 0.1740285 0.2147515 0.9619804 0.1687477 0.05806607 -0.9880314 0.1429067 0.1169387 -0.9522553 0.28202 0.032947 0.9525757 0.302513 0.07027965 0.9478498 0.3108724 0.09367543 0.9526427 0.2893038 0 1 4.53124e-7 0 1 -6.00837e-7 -0.04460245 0.9908387 -0.1274728 -0.02095264 0.9922768 -0.1222616 0.02095055 0.9922778 -0.1222537 0.04459178 0.9908378 -0.1274845 0.04751849 0.9919002 -0.1177966 -0.1672664 -0.9285652 0.3313437 -0.2199037 -0.9266219 0.3049826 -0.03233152 0.9524945 0.3028351 -0.07020843 0.947472 0.3120378 -0.09560763 0.9524616 0.2892684 -0.232196 -0.6087536 0.7586198 -0.2873092 0.2939853 0.9116063 -0.1316278 0.4609094 0.8776313 -0.01399791 -0.6233049 0.7818536 0 0.316581 0.9485655 9.45796e-4 0.9999995 -2.75429e-4 -0.105062 -0.942558 0.3170908 -0.09282618 -0.9347623 0.3429328 -0.03533959 -0.9430731 0.3307028 -0.1682182 0.8287444 0.5337466 -0.1321681 0.7983899 0.5874565 -0.06548124 0.8972908 0.4365563 0.01265799 0.8676803 0.4969617 0 -1 -2.4102e-7 0.04879629 -0.9986239 0.01921701 -0.2765444 -0.5929449 0.7562668 -0.2212658 -0.6100214 0.760865 0.889209 -0.2822818 0.3600338 0.1199291 0.9925267 0.02253824 -0.5501474 -0.6272983 0.5512121 0.8536071 0.2229846 0.470779 0.7894631 0.3702331 0.4895667 0.1710899 -0.9322401 0.3188365 0.1746863 -0.9329746 0.3147113 0.2767109 0.9606188 0.02534931 0.263171 0.9632381 0.05397689 0.2677149 0.9606305 0.074283 0.2457146 0.9626218 0.1139464 0.2470988 0.9609021 0.1249375 0.3688555 -0.8658204 0.338084 0.4026026 -0.8445747 0.3529942 0.308172 -0.8786218 0.3647655 0.7923155 -0.4864156 0.3682882 0.7305853 -0.558312 0.3931067 0.9395707 -0.146551 0.3094022 0.928402 0.290261 0.2319882 0.9281877 0.2916604 0.2310886 0.6097099 0.4163735 0.6744531 0.4500975 -0.6295736 0.6332847 0.5276497 -0.5685282 0.6311589 0.5146833 -0.5832202 0.6284548 0.6990765 0.2892658 0.6539245 0.6960498 0.2586018 0.6698059 0.7332493 0.3929696 0.5549058 0.5154395 -0.6392898 0.5706407 0.7147256 -0.4433333 0.5409463 0.5036937 -0.6912699 0.5181106 0.6269823 -0.5819169 0.5179439 0.5468725 -0.6432143 0.5359159 0.8545992 0.2362191 0.462451 0.8735074 0.3251897 0.3622661 0.7715933 0.6347557 0.04158359 0.1448653 -0.9397484 0.3096565 0.1440095 -0.939971 0.3093798 0.1439254 -0.9399907 0.3093592 0.1436942 -0.9400355 0.3093305 0.1435336 -0.9400599 0.3093309 0.1434216 -0.9400692 0.3093546 0.1033853 -0.93946 0.32669 0.4052484 0.8371889 0.3672718 0.4044098 0.8537505 0.3279677 0.4530866 0.8312945 0.3219658 0.4888369 0.8366282 0.2471675 0.4901078 0.8324457 0.2585124 0.5333601 0.82041 0.2060447 0.5503028 0.8208827 0.1527036 0.5477409 0.8253573 0.136986 0.5793785 0.809996 0.09070283 0.5819945 0.8114432 0.05331397 0.5820823 0.8113909 0.05315387 0.6388975 0.768046 -0.04376792 0.5823343 0.8117543 0.04406726 -0.6297601 -0.6157538 0.47355 -0.6271269 -0.61181 0.4820793 -0.6740816 -0.6303635 0.3850401 -0.7233169 -0.6162534 0.3115198 -0.7775487 -0.5790694 0.2451464 -0.694438 -0.6441196 0.320727 1 9.2081e-5 0 1 1.42916e-6 0 1 2.5156e-6 0 0.1012263 0.9936183 0.04976046 0.2418722 0.9669444 -0.08072465 0.3517644 0.8901475 -0.2896541 0.319589 0.9434137 -0.08850628 0.3643679 0.9312353 0.0060817 0.4288873 0.9010788 -0.06412988 0.341588 0.9306011 -0.1315265 0.358623 0.9302885 -0.07715469 0.4497612 0.8931353 0.004944205 0.439339 0.8979295 0.02652955 0.5673882 0.8141484 -0.1234225 0.542482 0.8392208 -0.03771036 0.1955649 -0.8704745 0.4516953 0.2745296 -0.7721582 0.5730665 0.3052283 -0.6570864 0.6892555 0.9903784 0.1327756 -0.03900408 0.9073752 0.4119837 0.08330512 0.9103932 0.3720301 0.1810463 0.8285985 0.5490783 -0.1092599 0.7531706 0.6424418 -0.1414313 0.7841973 0.6195065 -0.0353055 0.9006777 -0.3103618 0.3040649 0.7987238 -0.5374888 0.2704553 0.7540262 -0.4613333 0.4675641 -0.2270545 -0.8699207 0.4378176 0.8582275 -0.4431359 0.2589904 0.9269313 -0.3494888 0.1365875 0.8458942 -0.475709 0.2411722 0.8216131 -0.5431307 0.1730923 -0.2034394 -0.8764474 0.4364084 0.2270879 0.9730886 -0.03911292 0.2774384 0.9607207 0.006608605 0.2238214 0.9730706 -0.05511504 0.2000846 0.9797757 0.002401053 0.1887501 0.9813428 -0.03660351 0.2663174 0.9637076 -0.01851803 0.2754459 0.9612826 -0.008094966 -0.264955 -0.9269971 0.2654719 -0.2992184 -0.9272764 0.2250044 -0.299843 -0.9280349 0.2210106 -0.3246496 -0.9274773 0.1854414 -0.3248423 -0.927956 0.1826887 -0.3430609 -0.9276205 0.1477481 -0.3430402 -0.9279051 0.1459987 -0.3559868 -0.9277263 0.1122379 -0.3559244 -0.9278636 0.1112971 0.920683 0.3750211 -0.1081768 -0.6946235 -0.6997585 0.1668421 -0.1926451 -0.86351 0.4660886 0.1259085 -0.5479866 0.8269569 0.1832948 -0.6922963 0.6979463 0.2395914 -0.7246619 0.6461124 0.3299832 -0.7194402 0.6111603 0.04363238 -0.7846601 0.6183888 -0.3957124 -0.9000076 0.1827509 -0.4031019 -0.9021133 0.1539502 -0.3804691 -0.9247195 -0.0117188 0.2491165 -0.6247045 0.7400577 0.337868 -0.8061593 0.4857493 0.7485523 -0.5875532 0.3073284 0.4964398 -0.681161 0.5381146 0.9643658 -0.1841035 0.1900117 0.9985206 -0.05405253 0.00590527 0.9406658 -0.09922194 0.3245044 0.9400354 -0.09055203 0.328837 0.4867979 -0.5134408 0.706687 0.8262438 -0.3874569 0.4088991 -0.3666161 -0.9272913 0.07565391 -0.3647415 -0.9277921 0.07852095 0.2002123 -0.5680648 0.798259 0.1786817 -0.9140068 0.3642312 -0.1870584 -0.7481064 0.6366679 0.8344709 -0.2208986 0.5048388 0.8941393 -0.2304596 0.3839313 0.9409665 0.3361978 -0.03941136 0.9936861 0.1094021 -0.02488267 0.990553 0.1364832 -0.01331132 1 -3.75782e-6 0 0.9998699 0.007268965 0.0144034 -0.704915 -0.6942662 0.1452219 0.9614057 0.2549124 0.1035314 0.9998137 0.00684899 0.01804786 0.9902083 0.1392028 -0.01050209 0.9922821 0.1211351 -0.0265069 0.7042466 -0.0613535 0.7072994 0.7239768 -0.08033579 0.6851305 0.6983557 -0.06705397 0.712603 0.7075556 -0.1746252 0.6847416 0.6875693 -0.2029396 0.6971829 0.6896845 -0.356697 0.6301608 0.660139 -0.289966 0.6929187 0.7391296 -0.2969395 0.6045779 0.6596161 -0.2923703 0.6924061 0.7135635 -0.4679442 0.5213977 0.5224345 -0.7449344 0.4148916 0.5623597 -0.6221847 0.5446446 0.538944 -0.6397623 0.547945 -0.1649883 -0.6948317 0.6999912 -0.1721705 -0.7020137 0.6910384 -0.2965725 -0.6659905 0.6844717 -0.3183978 -0.6728961 0.6677079 -0.4518458 -0.6214222 0.6400547 -0.458203 -0.6214787 0.6354638 -0.662901 -0.3759033 0.6475023 -0.534205 -0.5139482 0.6711797 -0.4940853 -0.6083303 0.6211394 -0.6978292 -0.07750886 0.7120581 -0.9061196 -0.3123853 -0.2852414 -0.7172483 -0.1574019 0.6788075 -0.573997 -0.0708096 0.8157901 -0.6710348 -0.1832863 0.7184138 -0.6809132 -0.2819246 0.675926 -0.6374452 -0.3846929 0.667589 -0.7220264 -0.4327795 0.5397961 0.11515 0.9931567 -0.0194981 0.1239584 0.9922873 -6.71187e-4 -0.07000869 0.9917712 -0.1071853 -0.06792056 0.9915012 -0.1109606 -0.04278177 0.9915738 -0.1222749 -0.04209768 0.9915068 -0.123053 -0.01461929 0.9915618 -0.1288074 -0.01424247 0.9915309 -0.1290883 0.01421999 0.9915563 -0.1288954 0.01463288 0.9915258 -0.1290836 0.0420947 0.9915072 -0.1230506 0.04277223 0.9915734 -0.1222822 0.06837439 0.9914932 -0.1107526 0.2103151 0.9718128 -0.1065243 0.04527276 0.9962331 -0.07396137 -0.1653163 0.9857091 -0.03237485 -0.1740418 0.9846469 -0.01341986 0.1215348 -0.4375799 0.8909283 -0.782398 -0.2745555 0.5589927 0.507017 -0.2129967 0.8352043 0.4329984 -0.2010579 0.8786855 -0.8757907 -0.1192685 0.467724 -0.9418939 -0.02902787 0.3346541 -0.9712263 0.01020473 0.2379399 -0.7445427 -0.1339634 0.6539955 -0.3532124 -0.2099426 0.9116827 -0.3567031 0.1562505 0.9210585 0.1107167 -3.82819e-6 0.9938521 0.5562118 -0.07181781 0.8279317 0.3572989 0.1460975 0.9224929 0.7510437 0.02514708 0.6597735 0.971076 -0.02064311 0.2378768 0.8484025 -0.1308491 0.5129248 0.867828 -0.1354771 0.4780381 -0.4048523 -0.2260404 0.8860025 -0.7133276 -0.06060302 0.6982057 -0.5534284 -0.1223115 0.8238671 -0.1083685 -0.205918 0.9725503 -0.2138177 -0.3760483 0.901593 0.7823982 -0.2746399 0.5589509 -0.01554936 0.9904477 -0.1370099 0.01553106 0.9904451 -0.1370303 -0.09152954 -0.9255641 0.3673599 -0.09961837 -0.9288844 0.3567214 -0.1623419 -0.9261419 0.3404501 -0.9997832 -0.01466858 0.01477938 0.7275558 0 0.6860486 0.726333 -6.4839e-5 0.6873431 0.695419 3.81278e-4 0.7186044 0.7154067 0.002270877 0.6987046 0.6999158 2.7339e-6 0.7142254 0.6315467 -0.002501487 0.7753339 0.6148269 -0.006632447 0.7886343 0.5668371 0.001422405 0.8238286 0.4715737 0.008822381 0.8817825 0.4264562 -0.001268088 0.9045074 0.4857826 -0.001645624 0.8740781 0.4415702 -0.03337681 0.8966058 0.4167212 -0.06069684 0.9070057 0.4557999 -5.20191e-4 0.8900822 0.3554891 8.1172e-5 0.9346804 0.3657844 0.03910851 0.9298777 0.3227239 -0.009049594 0.9464499 0.272421 -0.04836589 0.9609619 0.2800182 -0.03618645 0.9593125 0.1562021 0.02802324 0.9873275 0.09442484 -0.04775547 0.994386 0 0.03384745 0.999427 -0.09442532 -0.04775494 0.994386 -0.1562021 0.02802312 0.9873275 -0.2684181 -0.03007429 0.962833 -0.3746107 -0.1566021 0.9138613 -0.2801716 -0.0140649 0.959847 -0.3741421 0.002497851 0.9273681 -0.4835739 0 0.8753036 -0.471597 0.008808493 0.8817701 -0.4280844 -0.01025849 0.9036805 -0.4896432 -0.001502633 0.8719217 -0.4556691 -0.02415341 0.8898215 -0.5389022 3.45079e-4 0.8423684 -0.6557434 -0.02015328 0.7547149 -0.61484 -0.003781557 0.7886428 -0.6950601 3.79004e-4 0.7189515 -0.7273829 -8.18578e-5 0.6862319 -0.7262931 0 0.6873852 0 1 -2.5572e-6 0 1 1.99401e-6 0 1 1.46476e-6 0 -1 6.31455e-6 0 -1 3.61023e-6 -0.3275542 0 0.9448325 -0.3275166 3.14031e-6 0.9448455 -0.079584 -6.96924e-6 0.9968281 -0.07951372 6.65685e-6 0.9968338 0.1735915 1.56966e-6 0.9848178 0.1736273 5.96455e-6 0.9848114 0.4152699 -6.28131e-7 0.9096983 0.4152849 0 0.9096914 0.6303395 -4.3969e-6 0.7763196 0.6303293 -6.28118e-7 0.776328 0.8050481 -6.90664e-6 0.5932096 0.805091 5.02203e-6 0.5931515 0.9283191 -9.39685e-6 0.3717847 0.9283614 1.0022e-5 0.371679 0.9919638 -1.06784e-5 0.1265224 0.9919716 0 0.1264611 0.07958567 0 0.996828 0.07962554 0 0.9968249 -0.1735882 0 0.9848183 -0.1735882 0 0.9848183 -0.4153034 0 0.909683 -0.4152699 0 0.9096983 -0.6303153 0 0.7763394 -0.928317 0 0.3717895 -0.9919639 0 0.126522 -0.9919652 0 0.1265119 0.3232129 0.1619913 0.9323585 0.1810334 0.3289432 0.9268351 0.1843685 0.3297115 0.9259042 0.07847672 0.1685379 0.9825663 -0.1594553 0.3951826 0.9046573 -0.04530256 0.9315405 0.3608049 -0.1745921 0.8633985 0.4733505 -0.4005588 0.2640538 0.8773986 -0.3237463 0.3519926 0.8782309 -0.2226099 0.9204897 0.3211598 -0.5800693 0.3912622 0.7144463 -0.7805877 0.2446452 0.5751796 -0.6942772 0.3619237 0.6220855 -0.2604727 0.9344747 0.242716 -0.2706985 0.9316072 0.2425498 -0.3349857 0.9210135 0.1987932 -0.8562477 0.3863131 0.3429316 -0.3237419 0.9400024 0.1076421 -0.3640635 0.9269708 0.09046024 -0.9669712 0.2230653 0.1233235 -0.975466 0.1940402 0.1039932 -0.814288 0.5440617 0.2023164 -0.5472692 0.8189932 -0.1724727 -0.195034 0.9805734 0.02092117 -0.07827651 0.1788819 0.9807518 -0.1834024 0.3286129 0.9264866 -0.1848071 0.3284284 0.9262727 0.1593245 0.3968477 0.9039512 0.3865703 0.365348 0.8468083 0.3285778 0.3081328 0.8927994 0.03931337 0.9309094 0.3631283 0.1814485 0.860272 0.4764542 0.2225834 0.9205057 0.3211323 0.5802356 0.3906853 0.714627 0.2666 0.9312444 0.2484118 0.2664145 0.9335919 0.2396448 0.7469216 0.3730925 0.5503727 0.7082537 0.30412 0.6370932 0.3350259 0.9209917 0.1988269 0.8563952 0.3859448 0.342978 0.3222717 0.946016 0.03456628 0.1943064 0.9768201 -0.0898199 0.5503183 0.8236184 0.1371226 0.9246596 0.3031837 0.2304003 0.9731979 0.1935951 0.1241243 0.3273853 0.03110522 0.9443789 0.07822334 -0.184395 0.9797345 0.02498716 -0.1189292 0.9925884 -0.1961209 -0.2753205 0.9411351 -0.382672 -0.3884676 0.8382453 -0.6123628 -0.2370278 0.7542079 -0.64667 -0.3296828 0.6878424 -0.107399 -0.9363885 0.3341289 -0.2087744 -0.923874 0.3207341 -0.2957119 -0.8938205 0.3371047 -0.3453072 -0.8654537 0.3629781 -0.3200513 -0.9223791 0.2162961 -0.7414494 -0.3895579 0.5463494 -0.3466411 -0.9248383 0.1565696 -0.3362544 -0.9377009 0.08746469 -0.2987666 -0.953988 0.02540689 -0.1945877 -0.9782515 -0.07183074 -0.5490854 -0.821721 0.1525779 -0.9094669 -0.2004783 0.3642506 -0.9021546 -0.3511012 0.250689 -0.8166614 -0.5456555 -0.1879477 -0.9731969 -0.1936026 0.1241207 0.557637 0 0.830085 0.557637 0 0.8300849 0.1108072 0 0.993842 0.1107439 0 0.993849 -0.3611987 0 0.9324889 -0.3611429 0 0.9325106 -0.7512952 0 0.6599664 -0.7512953 1.28376e-6 0.6599663 -0.9712764 4.69684e-7 0.2379544 -0.97128 0 0.2379395 -0.5576308 0 0.8300892 -0.5576162 5.00963e-7 0.8300991 -0.1108706 -1.50291e-6 0.9938349 -0.1108117 2.19185e-6 0.9938415 0.3611447 1.00193e-6 0.9325098 0.3612005 1.00191e-6 0.9324883 0.7512809 -5.00929e-7 0.6599826 0.7512688 0 0.6599965 0.9712767 0 0.2379532 0.9712802 0 0.2379386 -0.5202017 -0.2587888 0.813891 -0.5562989 -0.06916588 0.8280989 -0.5763384 -0.1463436 0.804001 -0.572912 -0.1417641 0.8072638 -0.5029056 -0.1015917 0.8583503 -0.5349144 -0.1696742 0.8276939 -0.3679513 -0.4636304 0.806014 -0.4224026 -0.4853973 0.7654839 -0.2873507 -0.5379293 0.7925035 -0.2108275 -0.4659639 0.8593192 -0.1088839 -0.1910625 0.9755201 0.04712581 -0.2458041 0.9681733 -0.07672715 -0.5207356 0.8502632 -0.3118354 -0.7055594 0.6363526 0.03120064 -0.8383007 0.5443148 0.2198807 -0.6633926 0.7152362 0.3478292 -0.2695976 0.89796 0.5071625 -0.6845974 0.5235579 0.6574988 -0.325842 0.6793544 0.008528828 -0.9368424 0.3496479 -0.01762491 -0.7925555 0.6095452 -0.1933858 -0.8588144 0.4743835 -0.06005418 -0.9436043 0.3255833 0.7144359 -0.309176 0.6276875 0.6160334 -0.7054083 0.3505739 0.4061858 -0.8900607 0.2068941 0.3385329 -0.939684 0.04888141 0.4446725 -0.8874277 0.1214028 0.9410023 -0.2477176 0.2305449 0.8154081 -0.5788119 -0.009303331 0.9582853 -0.244593 0.1478638 0.1180189 -0.9657322 0.2311553 0.471534 -0.01438546 0.8817307 0.4123391 -0.3059462 0.8581221 0.2931734 -0.7044092 0.6464187 0.1430543 -0.9533349 0.2658724 0.3391726 -0.3852264 0.8582323 0.1304484 -0.909453 0.3948144 0.07104367 -0.9424967 0.3265776 0.05431014 -0.7523046 0.6565731 0.03996342 -0.7316474 0.6805109 0.01607513 -0.988026 0.1534482 -0.03997993 -0.7315849 0.6805771 -0.01607787 -0.9880257 0.15345 -0.07104831 -0.9424923 0.3265894 -0.130474 -0.9094444 0.3948258 -0.4424555 -0.1168809 0.8891412 -0.1419815 -0.9500072 0.2780786 -0.1384984 -0.9539638 0.266029 -0.293165 -0.7044141 0.6464171 -0.4555923 -0.2584289 0.8518511 0.5563261 -0.06905138 0.8280901 0.5464122 -0.07520806 0.8341329 0.5759911 -0.1381884 0.8056913 0.4918567 -0.3073551 0.8146227 0.5331567 -0.232103 0.8135553 0.5242867 -0.2285747 0.8202909 0.4919223 -0.2657617 0.8290858 0.4866643 -0.2608736 0.8337284 0.2261926 -0.4301855 0.8739436 0.1192962 -0.1963214 0.9732555 0.1085587 -0.196945 0.9743858 0.2952591 -0.7045558 0.6453087 0.3609427 -0.6371008 0.6810455 0.2607129 -0.597975 0.7579279 0.008454144 -0.5754375 0.8178021 0.1316787 -0.6925271 0.7092722 -0.2890246 -0.2736105 0.9173888 -0.1371398 -0.6223405 0.7706393 -0.3474874 -0.2725124 0.8972121 3.25673e-4 -0.9541056 0.2994701 -0.06953895 -0.8381013 0.5410645 0.1195502 -0.9101141 0.396737 -0.3796343 -0.7014837 0.6031571 -0.2014111 -0.8733103 0.4435794 -0.647301 -0.3049226 0.6985868 -0.4819368 -0.6994639 0.5277189 -0.2138976 -0.9764416 -0.02845561 -0.4322295 -0.891519 0.1355419 -0.7187423 -0.2910736 0.6314157 -0.6910426 -0.6792786 0.2470641 -0.4514073 -0.8852436 0.1121389 -0.9365185 -0.2651449 0.2294149 -0.9238845 -0.2623777 0.2785599 -0.775507 -0.6209349 0.1141441 0.08395129 -0.4719866 0.8775995 0.07372015 -0.3143983 0.9464244 0.03183549 -0.7180106 0.6953037 0.05569869 -0.9124084 0.4054734 0.06149965 -0.8951033 0.4415969 0.06956493 -0.9881619 0.1367365 0.01245504 -0.9194358 0.3930431 0 -1 4.95681e-7 0 -1 1.70304e-7 0 -1 -7.57151e-7 3.42246e-5 0 1 -5.35299e-6 0 1 2.29107e-6 0 1 -1.65208e-5 0 1 -1.21978e-5 -5.22733e-6 1 -2.79659e-7 1.53617e-6 1 7.06608e-6 1.84159e-6 1 0 1.2207e-6 1 2.43332e-6 2.02777e-7 1 -5.4755e-6 3.86866e-7 1 -1.33034e-6 4.36484e-7 1 1.33317e-6 2.71858e-7 1 -1.37195e-6 0 1 0 3.8147e-6 1 0 0.8944273 0.4472137 0.04409027 -0.7186179 0.6940062 -0.04408603 -0.7186174 0.6940069 0.1970221 -0.3283001 0.9237973 -0.1148504 -0.9055458 0.4084069 0.3531439 -0.8725538 0.337549 0.1973829 -0.8019864 0.5637888 -0.1888831 -0.6710043 0.7169913 -0.252723 -0.650116 0.7165755 0.1260042 -0.6533969 0.7464553 -0.2126852 -0.2951408 0.9314811 -0.2042579 -0.3007022 0.9315884 0.1040016 -0.3002238 0.9481822 -6.97161e-5 -0.1876338 0.9822391 0.2625852 -0.1267624 0.956546 0.2700747 -0.1371648 0.9530192 -0.2703428 -0.1375379 0.9528893 -0.2625852 -0.1267632 0.956546 6.97161e-5 -0.1876333 0.9822393 -0.1040025 -0.3002275 0.9481809 0.204261 -0.3007043 0.9315871 0.2126826 -0.295147 0.9314798 -0.1260036 -0.6533979 0.7464545 0.2527327 -0.6501175 0.7165706 0.1888768 -0.6709983 0.7169985 -0.1973849 -0.8019881 0.5637858 -0.3531457 -0.8725546 0.3375452 0.1148532 -0.905546 0.4084059 -0.1970812 -0.3274851 0.9240739 -0.01244688 -0.9194329 0.3930503 -0.06952106 -0.9881661 0.1367288 -0.06146043 -0.8951025 0.4416044 -0.05566418 -0.9124081 0.4054787 -0.03181576 -0.7180101 0.6953052 -0.07368171 -0.3143135 0.9464555 -0.08391422 -0.471988 0.8776024 -0.2046118 -0.3709434 0.905834 -0.05429369 -0.7522509 0.6566359 -0.3395856 -0.3843429 0.8584651 0.9732077 -0.1935811 0.1240701 0.8165884 -0.5456888 -0.1881682 0.902351 -0.3499484 0.2515926 0.9094901 -0.2006197 0.3641147 0.5490403 -0.8216574 0.153082 0.194595 -0.9782633 -0.07165002 0.2984515 -0.9540874 0.0253781 0.3363723 -0.9375854 0.08824759 0.3466402 -0.9248383 0.1565716 0.7418172 -0.3885865 0.5465417 0.3200529 -0.9223789 0.2162948 0.3452972 -0.8654603 0.3629718 0.2957256 -0.8938149 0.3371075 0.208764 -0.9238781 0.3207286 0.1074017 -0.9363893 0.3341258 0.6468898 -0.3287492 0.6880826 0.6125271 -0.2361273 0.754357 0.3827768 -0.3879485 0.8384377 0.1960151 -0.2749744 0.9412583 0.1666672 -0.2794893 0.9455727 -0.02492839 -0.1190558 0.9925746 -0.07813555 -0.1847251 0.9796794 -0.327387 0.02955615 0.944428 -0.3660877 0.03954648 0.9297397 -0.3923583 0.003088593 0.9198074 -0.4278048 -9.71403e-4 0.9038707 -0.7175288 0.002583503 0.6965241 -0.6999363 0 0.7142053 0 -1 9.88534e-7 -0.9997617 -0.02029365 0.008054614 0.009287655 0.9989368 0.04515784 -0.07535886 0.9953441 -0.06009387 0.04501003 0.9983416 -0.03589278 -0.0772376 0.9952924 -0.05854499 0.04527163 0.9983852 -0.03431504 0 1 1.17901e-6 0 1 -3.96071e-6 0 1 1.76805e-6 -1 3.62144e-7 0 -0.5430648 0.8396907 4.82393e-4 -0.8264437 0.5630194 3.2729e-4 -0.9801915 0.1980522 0 -0.9803733 0.1953104 0.02687388 0.4829632 0.8755002 -0.01568531 0.552717 0.8333691 -1.38812e-4 0.8264399 0.5630251 3.24843e-4 0.9800156 0.1989206 1.63328e-4 0.965921 -0.2588375 0 0.7070809 -0.7071163 0.004823923 0.2588038 -0.9659232 0.003612518 -0.7070981 -0.7070991 0.004823923 -0.9659167 -0.2588282 0.003612577 0 1 -9.59354e-7 0 1 1.90647e-6 0 1 -9.52167e-7 0 1 -2.04591e-7 0 1 2.19793e-6 -0.8263129 0.5629014 -0.018687 -0.8509929 0.5205147 0.06982499 -0.9828234 0.1844959 -0.004392027 0.6048265 0.7911542 0.09088516 0.8263018 0.5629194 -0.01863598 0.85099 0.5205044 0.06993812 0.9800146 0.1989226 -0.001185834 -0.3826095 0.9238328 0.01196295 -0.6055045 0.792051 -0.07758653 -0.9824225 0.1831277 0.03620064 -0.843442 0.5313928 -0.07891297 -0.9204106 0.381335 -0.08618521 -0.3511083 0.9344614 0.05920231 -0.7671368 0.4246712 0.4807865 -0.308559 0.923425 0.2282058 -0.3523127 0.9094608 0.2208097 -0.7682725 0.3935126 0.5048813 -0.1669071 0.9277224 0.3338763 -0.2949511 0.413254 0.8615249 -0.3026888 0.4024366 0.8639586 -0.1389601 0.9074052 0.3966183 0.002532839 0.934964 0.3547337 0.2963958 0.4032707 0.8657496 0.3009995 0.4138633 0.859137 0.1392869 0.9069462 0.3975523 0.1703251 0.9286412 0.329568 0.7682695 0.3935213 0.5048791 0.3494669 0.9026612 0.2511488 0.3348155 0.9186205 0.2098455 0.7671328 0.4246703 0.4807937 0.3527268 0.934 0.05681604 0.9204775 0.3834838 -0.07524281 0.6135864 0.7808443 0.1174479 0.9823466 0.1835634 0.03605121 0.8434485 0.5313822 -0.07891601 0.6050687 0.7903822 0.09585458 0.4783692 0.8781291 -0.007226943 -0.9996244 3.63717e-4 0.02740442 0.9978135 0 -0.06609231 0.997798 -1.22723e-4 -0.06632727 -0.8357018 0 0.5491836 -0.3238794 0 0.9460985 -0.3239053 0 0.9460896 0.3238773 0 0.9460991 0.3239032 0 0.9460903 0.8357015 0 0.549184 -0.9970437 0.00522834 -0.07665872 -0.9977977 0 -0.06633126 -0.9644887 -0.2584411 -0.05449753 -0.6995587 -0.6995517 0.1457571 -0.6235508 -0.6657857 0.4097731 -0.2085139 -0.7652241 0.60906 0 -0.8450086 0.5347527 0.208513 -0.7652225 0.6090624 0.6235525 -0.6657827 0.4097754 0.9644863 -0.2584495 -0.05449831 0.699537 -0.6995701 0.1457728 0 1 1.3991e-6 -0.1872099 0.9823199 -4.94085e-4 -0.6798563 -0.7150568 0.1627552 -0.2588235 -0.9659247 0 0.2588042 -0.9659299 0 0.6798601 -0.7150551 0.1627472 0.6806184 -0.4674172 0.564163 0.6841571 -0.4691831 0.5583873 -0.06979542 0.991136 -0.1130405 -0.170021 0.9853904 0.0099442 0.4937721 -0.5547935 0.6696218 -0.8891666 -0.2823334 0.3600981 -0.06967383 0.9911669 -0.1128442 -0.04752177 0.9918993 -0.1178029 -0.8314865 0.5555451 -1.62699e-4 -0.9807845 0.1950942 1.69045e-4 0.1950907 0.980781 0.002891421 0.5555733 0.8314675 -3.22302e-4 0.8314709 0.5555682 -1.64222e-4 0.9807817 0.1951087 -5.13936e-5 0.9807748 -0.195084 0.004795312 0.831456 -0.5555855 -0.002417981 0.5555829 -0.8314577 -0.002417564 0.1950916 -0.9807851 0 -0.831469 -0.555566 -0.002418279 -0.9807803 -0.1951156 0 -0.1950764 0.9807881 0 -0.4398789 0.8976876 0.02576094 -0.3430815 0.9296283 -0.1344856 -0.1209136 0.9899572 -0.07324492 -0.9531871 0.2032362 0.2238964 -0.9473301 0.2911785 0.133345 0.1918165 -0.8630225 0.4673315 -0.1259078 -0.5479939 0.8269522 -0.1824597 -0.6903181 0.7001211 -0.2695391 -0.7382368 0.6183487 -0.04402703 -0.7844842 0.6185842 0.3448621 -0.8710698 0.3497253 -0.2489994 -0.6207612 0.7434076 -0.5327304 -0.676858 0.5079978 -0.4866414 -0.6858492 0.5411018 -0.9643545 -0.1841418 0.1900324 -0.9393264 -0.2294046 0.2550288 -0.9744618 0.2097287 0.08023798 -0.9417777 -0.1188724 0.314522 -0.4720259 -0.5159732 0.714817 -0.5530023 -0.4998726 0.6665703 -0.1070439 -0.9371827 0.3320096 -0.0836271 -0.9754928 0.2035198 -0.9561884 0.2784951 0.09024542 0.818395 -0.5591341 0.1326606 0.2641258 -0.938436 0.2226552 0.3083111 -0.9294101 0.2028331 0.333342 -0.9270864 0.1714472 0.342742 -0.9316172 0.1209029 0.4158316 -0.9039108 0.1001474 -0.0201013 -0.9983823 0.05318653 -0.2465068 0.9682106 -0.0424571 -0.2326041 0.9725052 -0.01136684 -0.2238128 0.9730725 -0.05511569 -0.2000837 0.979776 0.002407371 -0.1797862 0.9814465 -0.06663262 -0.16469 0.9861021 -0.02191048 -0.1375573 0.987178 -0.08097976 -0.1393817 0.9861038 -0.09039956 -0.09302842 0.9914764 -0.0912162 -0.1179175 0.9614136 0.2485546 -0.2802109 0.9171363 0.2834487 -0.1703953 0.961222 0.2168358 -0.1709771 0.9616602 0.2144219 -0.2144709 0.961053 0.1742969 -0.2146719 0.9620078 0.1686921 -0.2470595 0.9608822 0.1251685 -0.2456666 0.9626367 0.1139232 -0.2677062 0.9606199 0.0744512 -0.2631598 0.9632415 0.05397272 -0.2767134 0.9606155 0.02544689 -0.2688917 0.963138 -0.007902383 -0.2554127 0.9665963 0.02135539 -0.06977152 0.9915631 -0.1092455 -0.3400524 -0.6262983 0.7015091 -0.2235329 -0.5177233 0.8258303 -0.276458 0.3216184 0.9056118 -0.6454427 -0.570711 0.5076345 -0.6437433 -0.5742677 0.5057778 -0.8400915 0.2612005 0.4754162 -0.6797545 0.6453481 0.3485107 -0.883956 0.08795714 0.4592226 -0.8141481 0.3264027 0.4802335 -0.7574682 0.3963346 0.5188073 -0.5314234 -0.562009 0.6338257 -0.4964349 -0.6743631 0.5466141 -0.6934512 0.3280935 0.6414672 -0.6976175 0.315371 0.6433281 -0.452671 -0.6393336 0.6215639 -0.5941925 0.4217058 0.6849085 -0.4963485 0.3667766 0.7868375 -0.5515128 0.1910685 0.8119893 -0.4038659 0.4439213 0.7998914 -0.4172113 -0.5408415 0.7303597 -0.4119712 -0.606406 0.6801115 -0.7042384 -0.6028205 0.375041 -0.5508819 -0.70644 0.4443778 -0.9400364 -0.1471368 0.3077053 -0.9538562 0.1967629 0.2268096 -0.7761428 0.6075046 0.1689394 -0.8967276 0.4056945 0.1768947 0.3300494 -0.8072372 0.4893216 -0.2002112 -0.5680697 0.7982558 -0.1971077 -0.7726777 0.6034218 -0.5600557 -0.4294327 0.7084668 -0.7705113 -0.5968967 0.2236668 -0.8949348 -0.391108 0.2147701 -0.8690293 -0.315653 0.3809874 0.4041029 -0.5643869 0.719839 0.3379974 -0.8513121 0.4012802 0.5200824 -0.7874175 0.3308898 0.1497552 -0.7814211 0.6057678 -0.6730771 -0.6537163 0.3458647 -0.7948719 -0.5232999 0.3071419 -0.9916676 0.1243183 -0.03376781 -0.9546826 0.2962529 0.02855819 -0.9338624 0.3528826 -0.0580936 -0.9701182 0.2232418 -0.09504586 -0.8466302 0.5286223 -0.06144857 -0.779831 0.6256838 -0.01958274 -0.7979555 0.60053 -0.05129343 -0.7679895 0.6403132 -0.01382827 -0.8011807 0.5893276 -0.103936 -0.7627715 0.6444351 -0.05369585 -0.7271135 0.6860024 0.02658373 -0.718687 0.6953335 -6.80152e-4 -0.6762196 0.7332058 0.07166862 -0.193817 -0.8716135 0.4502499 -0.3348465 -0.6711634 0.6613755 -0.1441255 -0.9396889 0.310182 -0.1445419 -0.939689 0.3099874 -0.1214922 -0.9360873 0.3301218 -0.1497813 -0.9392885 0.3087114 -0.1491957 -0.9378121 0.3134471 -0.1485684 -0.9376184 0.3143234 -0.1064905 -0.9430905 0.3150243 -0.1650259 -0.9329177 0.3200489 -0.1735466 -0.932642 0.3163236 0 1 1.50206e-7 0 1 1.66698e-7 0 1 -1.00676e-6 0 1 7.00748e-7 0 1 2.18866e-7 0 1 -7.22511e-7 -0.1431156 -0.9386841 0.3136721 -0.5999617 0.7818661 -0.169504 -0.3586164 0.930291 -0.07715588 -0.3416075 0.9305926 -0.1315361 -0.47585 0.8778105 -0.05491495 -0.3378196 0.9405917 0.03413587 -0.3705795 0.9288002 -9.95159e-4 -0.2694837 0.9591629 -0.0859366 -0.1514496 0.9877588 0.03735685 -0.9987608 0.02242535 0.04443085 -1 -2.50843e-7 0 -1 2.62583e-7 0 -0.001180827 -0.9999988 -0.001035869 0.6689747 -0.7179054 0.1925743 0.7136602 -0.6457897 0.271376 0.674607 -0.6515443 0.3469805 0.6488716 -0.6298773 0.4268727 0.6481469 -0.6266615 0.4326674 0.5822712 -0.6480963 0.4908477 0.6805528 -0.5790771 0.4489071 -0.5587522 0.8293181 -0.005236923 -0.6304372 0.773424 -0.06606334 -0.6232882 0.7819248 -0.01027661 -0.623547 0.7816037 -0.01687878 -0.5816592 0.8124393 0.04018914 -0.5819067 0.8114929 0.05351477 -0.5659896 0.8205019 0.08020216 -0.5820434 0.8125481 0.03148502 -0.5772616 0.8084186 0.1150153 -0.543751 0.8255084 0.1512314 -0.5412147 0.8206719 0.1832607 -0.4846062 0.8395693 0.2455201 -0.5106773 0.8274986 0.2333558 -0.4738001 0.8160095 0.3311226 -0.4043673 0.8535189 0.3286226 -0.3968949 0.8348726 0.3813952 -0.3206884 0.8547692 0.4080792 -0.3302846 0.8481233 0.4142452 -0.2594663 0.8268334 0.4990229 -0.2167983 0.8626586 0.4569668 2.42425e-4 -1 -3.15289e-5 -0.001078963 -0.9998143 0.01923942 -0.2663819 -0.9281533 0.2599466 -0.222671 -0.9283233 0.2977136 0.09301203 0.9914766 -0.09123039 0.1393747 0.9861055 -0.09039163 0.1375457 0.9871779 -0.08100134 0.1494139 0.987223 -0.05537438 0.06819599 0.9915383 -0.1104595 0.07177025 0.99107 -0.1123805 0 1 -4.82248e-7 0 1 4.37318e-7 0 1 0 0 1 -1.00674e-6 0 1 5.00188e-7 0 1 5.62787e-7 -9.4588e-4 0.9999995 -2.75452e-4 -0.008570671 -0.9999616 0.001845836 -0.00804603 -0.9999645 0.002515852 -0.007454335 -0.9999673 0.003172576 -0.006781578 -0.9999697 0.003813266 -0.006014466 -0.9999722 0.004433631 -0.005139946 -0.9999743 0.005016148 -0.004145085 -0.9999762 0.005542099 -0.003021001 -0.9999775 0.005984246 0.3253084 0.8608779 0.3912339 0.3353385 0.840382 0.4258006 0.2502911 0.8126868 0.5262077 0.1764573 0.8381868 0.5160483 0.1081532 0.8436708 0.5258542 0.1118735 0.8617494 0.4948459 2.93952e-4 0.8386355 0.5446932 -0.009138107 -0.9999577 0.001010835 -0.006300628 -0.9999618 0.006075322 0.1039825 -0.9435236 0.3145648 0.070827 -0.9362003 0.3442566 -0.005549609 -0.9507325 0.3099629 0.04523396 -0.904865 0.4232887 0.2568375 -0.8716255 0.4174968 0.1445357 -0.9396909 0.3099847 0.144414 -0.9397076 0.3099909 0.1445428 -0.9396924 0.3099766 0.1333982 -0.9358229 0.3262525 0.3039713 0.3429644 0.8888064 0.2804105 0.2789251 0.9184611 0.2523728 -0.5058087 0.8249034 0.1803315 0.4458271 0.876766 0.0235297 0.3836901 0.9231621 0 -0.581907 0.8132554 0.4301447 -0.5448142 0.7198285 0.390359 -0.6076956 0.6916112 0.5324343 0.404063 0.7438057 0.4447454 0.03827071 0.894839 0.4621867 0.5201783 0.7181909 0.2946103 -0.640128 0.7095357 1.71358e-4 0.9474426 0.3199259 0.1373168 0.9475201 0.2887039 0.1941308 0.959995 0.2017992 0.1705669 0.9612503 0.2165753 0.1710501 0.9616259 0.2145165 0.2145826 0.961078 0.1740215 0.2147532 0.9619787 0.168755 0.05806541 -0.9880315 0.1429067 0.06865459 -0.9834027 0.1679461 0.03294676 0.9525756 0.3025133 0.07027977 0.9478501 0.3108715 0.09367614 0.952643 0.2893027 0.09771275 -0.9210393 0.3770131 0 1 4.53123e-7 0 1 -1.12655e-6 -0.04460245 0.9908383 -0.1274763 0.02095049 0.9922776 -0.1222549 0.04459178 0.9908378 -0.1274842 0.04751855 0.9919002 -0.1177967 -0.1672669 -0.9285647 0.3313447 -0.2199034 -0.926622 0.3049822 -0.03233146 0.9524942 0.3028358 -0.0702086 0.9474718 0.3120387 -0.09560775 0.9524615 0.2892688 -0.2321969 -0.6087498 0.7586227 -0.2873108 0.2939787 0.911608 -0.1316283 0.460908 0.8776319 -0.01399797 -0.6233045 0.781854 0 0.3165808 0.9485656 9.45798e-4 0.9999995 -2.7543e-4 -0.1050618 -0.9425587 0.3170887 -0.09282618 -0.9347618 0.3429341 -0.03533941 -0.9430727 0.3307038 -0.1682195 0.8287449 0.5337454 -0.1321688 0.7983937 0.5874513 -0.06548088 0.8972885 0.4365614 0.01265799 0.86768 0.4969621 0 -1 -2.41021e-7 0.04879736 -0.9986238 0.01921683 -0.6231691 0.7820751 -0.004350244 -0.7938039 0.6081632 -0.003591895 -0.7201286 0.6938405 -4.0072e-4 -0.5626685 0.8266338 -0.00899285 0.129077 -0.9916344 -6.45319e-4 0.1248509 -0.9921747 -0.001281738 0.3668264 -0.9302869 -0.002200245 0.3816626 -0.9243018 1.56751e-4 0.5131084 -0.8583085 -0.00514692 0.6088515 -0.7930525 0.01917397 0.8109589 -0.5850596 0.007145762 0.7930005 -0.6092143 0.00286287 0.9242299 -0.381829 -0.002386391 0.9914898 -0.1291405 0.0164563 0.9756928 -0.2191429 -1.41413e-4 -0.1352024 -0.9908149 0.002499163 -0.1931217 -0.9811079 0.01146376 -0.3865935 -0.9222501 -5.65866e-4 -0.5070083 -0.8618882 0.00956428 -0.7072537 -0.7067853 -0.0157091 -0.8111367 -0.5848126 0.007181942 -0.9242291 -0.3818314 -0.00231707 -0.9916318 -0.129099 -1.84976e-5 -0.9753018 -0.220657 0.009857714 3.28566e-4 -0.9999998 -6.43411e-4 -0.00366652 -0.9999911 0.002090811 1 0 -2.47578e-5 1 2.89659e-5 -2.94772e-5 1 0 -3.52414e-5 1 5.37577e-5 -1.19856e-4 1 2.12807e-5 -6.03893e-5 1 0 -4.59341e-5 1 0 -4.15393e-5 -1 3.09405e-5 2.46086e-5 -1 -3.75432e-5 2.17251e-5 -1 -2.30673e-5 2.57528e-5 -1 -1.38441e-5 2.88632e-5 -1 -7.95959e-6 3.30116e-5 -1 -3.55304e-6 3.76716e-5 -1 0 4.12765e-5 -1 0 4.12765e-5 0.9938653 0.1105988 5.65232e-6 0.993991 0.1094625 -5.69874e-5 0.9496613 0.3132788 1.16469e-4 0.9443236 0.3290176 -6.40189e-4 0.8767707 0.4809086 5.92133e-4 0.8463136 0.5326835 -0.001255393 0.7072225 0.7069866 0.002527058 0.4787645 0.877938 -0.00309509 0.5328802 0.8461908 3.42442e-4 0.3865119 0.9222844 1.7967e-4 0.3065028 0.9518678 -0.002002656 0.2614942 0.9651941 -0.004630804 0.2211157 0.9752425 -0.003179252 0.1246716 0.9921977 -8.57262e-4 0.03863555 0.9992535 1.76838e-4 -0.9939972 0.1094059 5.44798e-5 -0.9938629 0.1106193 -9.36668e-6 -0.9496678 0.3132589 1.6209e-4 -0.941152 0.3379822 -0.001030325 -0.8767781 0.4808948 6.19274e-4 -0.844413 0.5356916 0.001153945 -0.7071433 0.707043 0.006224691 -0.4769447 0.8789277 -0.003162264 -0.5338333 0.8455649 0.006508231 -0.3969817 0.9177913 -0.008063077 -0.3090421 0.9510445 -0.002742946 -0.2317181 0.9727829 4.57865e-4 -0.12067 0.9924733 -0.02087718 -0.1740253 0.9846501 -0.0134015 -0.237044 0.9714721 -0.007217466 2.81785e-4 1 4.6035e-4 6.2819e-5 0.9999999 5.69168e-4 1.69007e-4 1 4.93775e-4 0.5373366 0.8433674 -9.22213e-4 0.6653172 0.7465601 -0.001019656 0.7972739 0.6036175 4.83258e-4 -0.2332267 0.9724024 -0.006232798 -0.1693604 0.9854786 -0.01221376 -0.1154012 0.9931274 -0.01950681 -0.2225384 0.9749239 4.5799e-4 -0.3061909 0.9519681 -0.001999139 -0.5326671 0.8463008 0.006385266 0.2143282 -0.976655 -0.01444053 0.2611925 -0.9652869 0 0.5131276 -0.8582968 -0.005175113 0.6086885 -0.793179 0.01911449 0.8109914 -0.5850161 0.00701791 0.7938222 -0.6081431 0.002908229 0.9241245 -0.382084 -0.002408564 0.9482622 -0.3174778 0.002587735 0.9916281 -0.1290963 -0.002799093 0.9954479 -0.09530782 -8.50438e-5 -0.1467857 -0.9891591 0.004287362 -0.1263885 -0.9919803 -0.0010885 -0.1931204 -0.9811082 0.01146352 -0.3864818 -0.922297 -5.59516e-4 -0.506996 -0.861895 0.009595513 -0.608959 -0.7931973 -0.002657949 -0.7930048 -0.6092082 0.002955973 -0.8111071 -0.5848525 0.007278203 -0.9242252 -0.381841 -0.002314388 -0.9916264 -0.1291407 -1.85343e-5 -0.9753022 -0.2206549 0.009855568 -2.53244e-4 -1 -9.0733e-5 1.20489e-4 -1 -3.64696e-4 3.36168e-5 -1 -3.20651e-4 -3.36119e-5 -1 -3.20721e-4 -1.20463e-4 -1 -3.64222e-4 -5.82992e-4 -0.9999992 -0.001109302 1.48022e-4 -1 -1.6804e-4 -0.002981603 -0.9999899 0.003380656 1 -1.50218e-4 0 1 2.63366e-5 -2.89774e-5 1 0 -3.02485e-5 1 1.90184e-4 -2.17667e-4 1 0 -3.50881e-5 1 3.90593e-5 -9.22453e-5 1 1.49627e-5 -5.81192e-5 1 1.22007e-5 -5.48812e-5 1 0 -4.13586e-5 -1 2.07935e-5 1.46001e-5 -1 -2.33887e-5 1.35343e-5 -1 -1.23631e-5 1.49953e-5 -1 -7.7869e-6 1.59994e-5 -1 -4.24185e-6 1.71972e-5 -1 -3.16016e-6 1.83818e-5 -1 0 1.92001e-5 -1 2.18265e-5 4.12863e-5 0.9703965 0.2415179 0 0.9931328 0.1160387 -0.01491671 0.9491825 0.3147183 -0.002289235 0.8440755 0.5362229 0.001284658 0.8754612 0.4832826 -0.002410113 0.707156 0.7070502 0.003238499 0.7919594 0.6105471 -0.005725562 0.6669138 0.7451331 0.001653492 0.5440167 0.8390741 -7.95128e-4 0.5360404 0.8441923 -5.51505e-4 0.4661409 0.8847106 4.27561e-4 0.340917 0.9400933 -5.49652e-4 0.4022942 0.9155015 -0.004060268 0.3001999 0.9538763 -3.5995e-4 0.110633 0.9938601 0.001595199 0.240801 0.9705395 -0.008251249 0.1300229 0.9915086 -0.002224743 0.03753817 0.9992952 4.58538e-4 -0.9939971 0.1094069 3.2328e-5 -0.9938503 0.1107324 -9.09638e-6 -0.9496659 0.3132648 1.64047e-4 -0.9442877 0.3291208 -5.99689e-4 -0.8767982 0.4808582 6.35005e-4 -0.8461852 0.5328877 0.001174211 -0.7933847 0.6087073 -0.004050731 -0.7201671 0.6938006 -3.95679e-4 -0.7069916 0.7071947 0.006211638 -0.5626358 0.8266561 -0.008982479 -0.623164 0.7820793 -0.004340171 -0.4769105 0.8789462 -0.003154873 -0.5326532 0.8463096 0.006383776 -0.3969376 0.9178103 -0.00805217 -0.3061936 0.9519672 -0.001999735 -0.222546 0.9749221 4.5799e-4 -0.1154013 0.9931275 -0.019508 -0.1693698 0.9854769 -0.01221483 -0.2332298 0.9724017 -0.006233334 2.81785e-4 0.9999999 4.6035e-4 0 1 5.44372e-4 -2.81797e-4 1 4.60455e-4 -4.30319e-4 0.9999991 0.001257956 -8.11354e-5 0.9999998 7.35909e-4 6.2819e-5 0.9999999 5.69168e-4 1.69007e-4 1 4.94331e-4 0.1248509 -0.9921747 -0.001281321 0.3668352 -0.9302834 -0.002198457 0.3816663 -0.9243003 1.57396e-4 0.5131085 -0.8583084 -0.005146682 0.6088515 -0.7930525 0.01917606 0.8109568 -0.5850623 0.007145762 0.7929961 -0.60922 0.002863764 0.9242299 -0.381829 -0.002387046 0.9482654 -0.3174684 0.002587258 0.9916201 -0.1291583 -0.0028041 0.9954479 -0.09530764 -8.49718e-5 -0.1263745 -0.9919819 0.001138925 -0.1931228 -0.9811077 0.0114637 -0.3864809 -0.9222972 -5.58473e-4 -0.5069879 -0.8618998 0.009595513 -0.6089608 -0.7931959 -0.002658665 -0.7929977 -0.6092175 0.002954483 -0.8111104 -0.5848479 0.007278978 -0.9242249 -0.3818418 -0.002313077 -0.9916273 -0.1291338 -1.84283e-5 -0.9753021 -0.2206554 0.009856939 3.28565e-4 -0.9999998 -6.43409e-4 7.11595e-4 -0.9999997 -5.06464e-4 0 -1 4.82655e-7 -7.11486e-4 -0.9999997 -5.06146e-4 -0.004351794 -0.9999903 7.98798e-4 1 0 -2.46011e-5 1 2.81614e-5 -2.92906e-5 1 0 -3.50183e-5 1 6.04839e-5 -1.1911e-4 1 1.59602e-5 -6.00064e-5 1 3.48588e-6 -4.5643e-5 1 0 -4.12765e-5 -1 2.68334e-5 2.46674e-5 -1 -3.69566e-5 2.1777e-5 -1 -2.13632e-5 2.58143e-5 -1 -1.42386e-5 2.8932e-5 -1 -8.42851e-6 3.30906e-5 -1 -3.40688e-6 3.77617e-5 -1 0 4.13751e-5 -1 0 4.13752e-5 0.9938629 0.1106192 5.91644e-6 0.9939911 0.1094614 -5.86029e-5 0.9496549 0.3132981 1.17983e-4 0.9442846 0.3291297 -6.43575e-4 0.8767825 0.4808869 5.94599e-4 0.8461948 0.5328724 -0.001257836 0.7972459 0.6036546 4.82543e-4 0.6653295 0.7465493 -0.00100702 0.7069923 0.7072167 0.002515137 0.5373126 0.8433827 -9.15531e-4 0.4787251 0.8779594 -0.00308448 0.5326772 0.8463184 3.37685e-4 0.3865384 0.9222733 1.82131e-4 0.3064589 0.9518819 -0.001998722 0.2225327 0.9749011 -0.006859004 0.2407992 0.97054 -0.008251667 0.1300224 0.9915086 -0.002224743 0.03753745 0.9992951 4.5853e-4 -0.9939974 0.1094041 5.45394e-5 -0.9938623 0.1106249 -9.86928e-6 -0.9496611 0.3132792 1.63597e-4 -0.944291 0.3291113 -5.98789e-4 -0.8767977 0.4808591 6.36103e-4 -0.8461889 0.5328819 0.001174211 -0.79341 0.6086742 -0.004048168 -0.7201431 0.6938255 -3.96113e-4 -0.7069793 0.707207 0.006211519 -0.562636 0.826656 -0.008982121 -0.6231654 0.7820781 -0.004339635 -0.4768999 0.8789521 -0.003155589 -0.3969455 0.9178069 -0.008051574 2.81785e-4 1 4.60421e-4 0 0.9999999 5.44579e-4 -2.81798e-4 0.9999999 4.60528e-4 -4.30319e-4 0.9999991 0.001257956 -8.11348e-5 0.9999998 7.36297e-4 6.28193e-5 0.9999999 5.69475e-4 1.69007e-4 0.9999999 4.94053e-4 -0.2225382 0.9749212 -0.002338051 -0.2652899 0.9641222 -0.009481191 -0.5312964 0.8471861 -1.50181e-4 -0.5326779 0.8463181 1.23777e-4 -1 0 -1.52528e-4 -1 3.8151e-5 0 -0.2652935 0.9641649 -0.002329587 -0.2357423 0.9716097 0.02000755 -0.625132 -0.7788618 0.05083727 -0.3018028 -0.9530544 0.02454334 -0.3301534 -0.9439162 0.004615485 -0.3295322 -0.9441348 -0.004258632 -8.49062e-5 -0.9999994 -0.001111805 5.59778e-4 -0.9999999 3.28077e-5 -0.1263882 -0.9919809 -1.09236e-6 -0.1263767 -0.9919824 0 -0.2736922 -0.9589906 -0.07368582 -0.3858768 -0.9209901 -0.05363303 -0.5434745 -0.8359996 -0.07576513 -0.6082919 -0.7923274 -0.04688727 -0.7930028 -0.609218 5.44223e-4 -0.9242249 -0.381841 -0.00241959 -0.9160988 -0.4009481 0.001935839 -0.9904294 -0.1380206 0 -0.9916253 -0.129135 -0.001856327 0.5985463 -0.7799643 0.1827514 0.7851468 -0.6014923 0.1474844 0.2639735 -0.9611311 0.08090245 0.2603494 -0.9620193 0.08208018 0.7517033 -0.6367184 0.1718482 0.904082 -0.3738056 0.2071357 0.9911794 -0.1290387 0.03020977 0.9288848 -0.274271 0.248895 0.5199322 -0.7468302 0.4146264 0.7598346 -0.2355769 0.6059331 0.772805 -0.2259913 0.5930434 0.5864064 -0.2685676 0.7641984 0.1279677 -0.9704073 0.2047783 0.2270326 -0.9462998 0.2301585 0.3979119 -0.6599752 0.6372589 0.4227526 -0.2252903 0.8777952 0.370681 -0.2484229 0.8949199 0.3066824 -0.7074066 0.6368061 0.08815091 -0.9653817 0.245495 0.03413552 -0.6918567 0.7212275 0.01226896 -0.9657358 0.2592371 -0.01021254 -0.9713129 0.2375858 0.03891921 -0.9659032 0.2559617 0.1259428 -0.2625573 0.956662 0 -0.2218374 0.9750837 0 -0.7098814 0.7043213 -0.1259452 -0.262558 0.9566615 -0.06132078 -0.9652315 0.2541024 -0.09605556 -0.9673879 0.2343802 -0.1020579 -0.9696502 0.2221772 -0.2744494 -0.6900975 0.669659 -0.3045977 -0.7121627 0.6324907 -0.4208787 -0.2432441 0.8738956 -0.3740081 -0.2115663 0.9029715 -0.5864073 -0.2685641 0.764199 -0.1535176 -0.9649147 0.2130068 -0.1830023 -0.9684808 0.1689825 -0.182753 -0.9681568 0.1710965 -0.5328546 -0.6884574 0.492029 -0.5472106 -0.7142357 0.4363805 -0.7609418 -0.2295922 0.6068402 -0.7705006 -0.2382378 0.591246 -0.2224743 -0.9649689 0.139069 -0.245252 -0.9614925 0.124031 -0.2384098 -0.9668871 0.09105014 -0.6326425 -0.7051153 0.3202748 -0.8904528 -0.2665571 0.3688377 -0.6073523 -0.784718 0.1238579 -0.9457821 -0.2272621 0.2320522 -0.3018279 -0.9519221 0.05238604 -0.9821153 -0.1368619 0.1292997 -0.8739315 -0.3831439 -0.2990729 0.1290758 -0.9916347 3.33593e-4 0.3816635 -0.9242979 0.002521812 0.6081067 -0.7920832 -0.0530132 0.6982085 -0.7158532 -0.007696032 0.793 -0.6092138 -0.003106176 0.9242318 -0.3818309 9.88361e-4 0.915481 -0.4023481 -0.003269672 0.9909467 -0.1342528 -9.95982e-4 0.9916234 -0.1291631 0 0.6774284 -0.7106199 0.1900268 0.8867164 -0.38979 0.2485918 0.9858306 -0.133561 0.1014869 0.9794272 -0.1552268 0.1289461 0.1090447 -0.9940155 0.006524562 0.2876167 -0.9576415 -0.01412796 0.6853936 -0.6950594 0.21709 0.2473377 -0.9672542 0.05695009 0.2029162 -0.9761706 0.07691532 0.8929699 -0.2565014 0.369881 0.2228595 -0.9649136 0.1388361 0.4958158 -0.7129814 0.4958065 0.51918 -0.70066 0.4894157 0.6846059 -0.2503171 0.6845846 0.7837223 -0.1552311 0.6014007 0.5884026 -0.2565084 0.7668023 0.18134 -0.9684495 0.1709428 0.1825512 -0.9682609 0.170722 0.1533647 -0.9649432 0.2129879 0.2670729 -0.6875563 0.6752322 0.09074652 -0.9690868 0.2294252 0.10609 -0.9669688 0.2317678 0.3699086 -0.2565091 0.8929563 0.1779043 -0.7262874 0.6639704 0.2531371 -0.2083964 0.9447183 0.1261535 -0.2564983 0.9582765 0.06061547 -0.9653428 0.2538485 0.01024764 -0.9659534 0.2585132 0 -1 -1.3154e-5 0 -1 -7.17001e-6 -1.55498e-6 -1 -1.62717e-4 0 -1 3.16456e-6 0 -1 -1.43998e-6 1.76921e-4 -1 -1.68624e-4 0 -1 2.71459e-6 0 -1 -2.61615e-6 5.19923e-5 -0.9999993 -0.001195847 -2.7702e-4 -1 -1.42449e-6 -5.58569e-4 -1 8.18299e-6 -5.56901e-4 -1 -8.3661e-6 5.56213e-4 -1 2.03089e-6 -5.56597e-4 -1 0 -0.2452715 0.9682754 0.04779791 -0.2282696 0.9717563 0.05985605 -0.5267138 0.8398235 0.1314126 -0.7031312 0.7031294 0.1059045 -0.8432829 0.5371094 -0.01968157 -0.6844264 0.7018835 0.1972821 -0.9174895 0.3451434 0.1977092 -0.9938359 0.1107787 0.004289388 -0.9498568 0.2411993 0.198985 -0.2378441 0.965083 0.1097502 -0.5599566 0.697885 0.4465481 -0.2044416 0.9652057 0.1630387 -0.1639249 0.9725712 0.1650274 -0.208741 0.9670078 0.1460244 -0.5599454 0.6978913 0.4465525 -0.7586141 0.2418795 0.6049785 -0.7841817 0.2199489 0.5802428 -0.148227 0.9654339 0.214397 -0.1083347 0.9683286 0.2249521 -0.1022337 0.9693092 0.2235799 -0.3107614 0.6978862 0.6452768 -0.3107564 0.6978859 0.6452796 -0.4190116 0.2597001 0.870049 -0.5030179 0.1975403 0.8413981 -0.06555408 0.9651415 0.2533864 -0.1799161 0.2665369 0.9468834 0 0.9659085 0.258884 0.02339667 0.9720072 0.2337835 -0.01964509 0.9667126 0.2551095 0 0.6978855 0.7162094 0 0.2095644 0.9777949 0 0.6978866 0.7162083 0.1832787 0.2683007 0.9457398 0.07118129 0.965284 0.2513171 0.1077889 0.968651 0.2238231 0.1082217 0.9687908 0.223008 0.3107567 0.6978845 0.645281 0.3107632 0.6978883 0.6452738 0.423744 0.2150648 0.8798796 0.508274 0.2576521 0.8217501 0.1535161 0.9652343 0.2115551 0.1929849 0.9690569 0.1539014 0.1941048 0.9663287 0.1689148 0.5599554 0.6978867 0.446547 0.7612237 0.2281213 0.6070414 0.7724136 0.2399384 0.5880536 0.5599544 0.6978898 0.4465435 0.6896296 0.7005511 0.1834102 0.3402868 0.938207 0.06302905 0.1097323 0.985755 -0.1274597 0.2234852 0.9746094 0.01381415 0.2379807 0.9702363 0.04479783 0.2442579 0.965713 0.08795714 0.8264533 0.5252715 0.2026447 0.7048761 0.7047727 0.08028095 0.5358645 0.8261544 -0.1741215 0.9514753 0.2402932 0.1922341 0.9512569 0.2367905 0.1975864 -0.2357891 0.9718043 0 -0.7071065 0.7071072 -1.23862e-4 -0.7069937 0.7072198 -1.50536e-4 -0.8461899 0.5328815 1.49052e-4 -0.843488 0.5371472 9.96185e-4 -0.944291 0.3291119 2.2644e-4 -0.936171 0.3515248 -0.003780484 -0.9938451 0.1107783 -2.24597e-4 -0.9938622 0.110625 -1.98899e-4 0.1668414 0.9859838 0 0.2225278 0.974879 0.009609758 0.3113011 0.9502949 -0.005592405 0.5326783 0.8463174 8.95596e-4 0.53728 0.843404 1.19358e-4 0.7071139 0.7070997 -1.50123e-4 0.706993 0.7072206 -1.22085e-4 0.8461977 0.5328692 1.49962e-4 0.8483656 0.5294108 -5.35515e-4 0.9442745 0.3291203 -0.005048453 0.9658445 0.2590525 0.006040215 0.9927561 0.1104986 -0.047176 0 0.9667528 0.255713 0.01834553 0.9712025 0.2375485 0 0.2095643 0.9777949 0 0.697885 0.7162098 0.1832832 0.2683003 0.945739 0.06562757 0.9651408 0.2533698 0.3107574 0.6978856 0.6452794 0.1072144 0.9689907 0.2226255 0.1042047 0.9681391 0.2277015 0.310761 0.6978868 0.6452763 0.42374 0.2150684 0.8798807 0.5082675 0.2576551 0.8217532 0.1482546 0.9654361 0.2143685 0.1986084 0.9671962 0.1583864 0.1969158 0.9706819 0.137844 0.1822648 0.9659683 0.1835346 0.559955 0.6978842 0.4465515 0.5599543 0.6978883 0.4465458 0.7612228 0.228128 0.6070401 0.7726202 0.2401776 0.5876844 0.2378416 0.9650793 0.1097883 0.6901725 0.7004004 0.1819377 0.3105177 0.9486364 0.06056278 0.1665622 0.9843248 -0.05798166 0.2278265 0.9735088 0.01938384 0.2434371 0.9678102 0.06389111 0.8300043 0.5181775 0.2063613 0.704804 0.7047931 0.08073502 0.5272727 0.8292859 -0.185118 0.9517843 0.2384747 0.192968 0.9503403 0.2215198 0.2185913 -0.9914448 3.7848e-5 0.1305265 -0.9786565 -0.002442538 0.2054886 -0.9238765 0.001921355 0.382686 -0.793349 3.12625e-4 0.608767 -0.803758 -3.59585e-4 0.5949562 -0.6087708 0.001903831 0.7933439 -0.5134404 -0.001185655 0.8581245 -0.3826521 0.001846909 0.9238908 -0.1863344 -6.3698e-4 0.9824863 -0.130551 0.001205742 0.991441 0.1305485 0.001150906 0.9914413 0.190133 -8.42167e-4 0.981758 0.3826685 0.002029895 0.9238835 0.5260806 -9.64971e-4 0.8504341 0.6087705 0.001681447 0.7933446 0.793357 -2.12318e-4 0.6087567 0.7957606 -4.61992e-5 0.6056113 0.9659256 0 0.2588198 0.9659249 0 0.2588227 0.9773253 0.003582715 0.2117132 0.130537 0.001150429 0.9914427 0.1901181 -8.43579e-4 0.9817609 0.3827049 0.002028703 0.9238685 0.5260743 -9.65935e-4 0.8504381 0.6087693 0.001680672 0.7933456 0.7933558 -2.35463e-4 0.6087583 0.796032 -5.02225e-5 0.6052547 0.9238752 0.002184748 0.382688 0.9741204 -0.00170958 0.2260235 0.991445 0 0.130526 0.9924661 3.00905e-4 0.12252 0.9790756 -2.28704e-4 0.2034971 0.9999062 -0.01225125 0.006125628 -2.73316e-5 1 -2.70099e-4 0 1 0 0.002390384 -0.9999971 9.49515e-5 -8.05278e-4 -0.9999967 0.002437651 -2.24676e-4 -0.9999977 0.002144098 2.24643e-4 -0.9999977 0.002144277 8.0512e-4 -0.9999968 0.002437353 -9.75495e-4 -0.9999989 0.00113213 1 0 -1.91766e-5 0.1290761 -0.9916345 6.55101e-4 0.2638501 -0.9643493 -0.02033817 -0.04512012 -0.6800225 0.7318016 -0.01599919 -0.9656132 0.2594904 -0.03665977 -0.9714599 0.2343538 -0.126173 -0.256511 0.9582706 -0.1764255 -0.7316542 0.65845 -0.2531365 -0.208406 0.9447163 -0.08960133 -0.9652557 0.2454649 -0.3698862 -0.2565128 0.8929645 -0.4071354 -0.6562027 0.6353257 -0.2883681 -0.845251 0.4498829 -0.1736642 -0.978681 0.1096563 -0.1624994 -0.9716547 0.1717014 -0.4966858 -0.7117726 0.496672 -0.684592 -0.2503267 0.684595 -0.6013834 -0.1552246 0.7837368 -0.7668192 -0.2564963 0.5883859 -0.8929696 -0.2565026 0.3698808 -0.6949734 -0.6945185 0.1861619 -0.7352178 -0.5948907 0.3248996 -0.9444826 -0.2086727 0.2537882 -0.9832879 -0.1280099 0.129455 -0.8930937 -0.3689596 -0.257396 -0.3812087 -0.9089608 0.1687313 -0.2608523 -0.9626127 0.07302725 -0.1323925 -0.9893963 0.05972814 0.3816633 -0.9242977 -0.002624511 0.5984002 -0.8011815 -0.005046844 0.6089544 -0.7932004 -0.002782762 0.7064949 -0.7077178 -6.78513e-4 0.7928581 -0.6091169 0.01878601 0.9240667 -0.3817658 0.01886451 0.9916266 -0.1291387 -1.84762e-4 0.979529 -0.201074 -0.009603083 0.9999988 -0.001573503 -4.35569e-4 -1.66325e-5 -0.9999998 -6.95287e-4 -2.02984e-5 -1 1.26465e-4 -2.06476e-5 -1 5.72482e-5 -2.15789e-5 -1 2.19127e-5 -0.002101957 -0.9999972 0.001108884 -4.83557e-4 -0.9999862 -0.005236983 0.002395093 -0.9999972 7.80011e-5 -0.001855075 -0.999996 -0.002125442 -0.2316784 0.9726876 0.01428282 -0.5294724 0.8380821 0.1314445 -0.7032117 0.7031061 0.1055242 -0.8442716 0.535526 -0.02043521 -0.3655189 0.9280483 0.07157039 -0.1122282 0.9887061 0.09932452 -0.2363772 0.971364 0.02403903 -0.219406 0.9747619 0.04123717 -0.9247313 0.3314515 0.1871153 -0.9938578 0.1106168 0.003287434 -0.9784321 0.1786922 0.1036339 -0.6800279 0.7028621 0.2086793 -0.8626525 0.2691712 0.4282261 -0.5599555 0.6978864 0.4465473 -0.2016932 0.9661513 0.1608468 -0.3262218 0.9336315 0.1480253 -0.5599522 0.6978868 0.4465509 -0.7642102 0.2111435 0.609427 -0.6594612 0.2606201 0.7051158 -0.1534435 0.9652345 0.211607 -0.107634 0.9687434 0.2234978 -0.1083887 0.9686284 0.2236316 -0.3107616 0.6978862 0.6452767 -0.4205459 0.2459834 0.8732888 -0.492914 0.2003042 0.8467078 -0.3107532 0.6978877 0.6452793 -0.07108342 0.9652831 0.2513478 -0.1799148 0.2665371 0.9468836 0 0.6978856 0.7162093 -0.02557474 0.966261 0.2562922 -0.9943342 0 0.1062993 -0.9943343 0 0.1062982 -0.9943345 0 0.1062964 -0.9914444 8.34443e-4 0.1305273 -0.923878 0.001211643 0.3826853 -0.8956499 -9.26938e-4 0.4447588 -0.7933666 0.002134442 0.6087404 -0.6842283 -6.37026e-4 0.7292676 -0.6087584 0.001067399 0.7933549 -0.5023187 -9.1768e-4 0.8646821 -0.3826972 0.001846611 0.923872 -0.1863318 -6.3722e-4 0.9824867 -0.1305289 0.001206219 0.9914439 -0.112559 0.9895226 0.09041821 -0.3771478 -0.4977047 0.7810567 -0.5938155 -0.6883011 0.416683 -0.4531128 -0.8043228 0.3843876 0.7434602 0.3355858 -0.5784887 0.7512954 0.3323918 -0.57015 0.3633313 0.4563143 -0.8122609 0.3741158 0.4557352 -0.8076775 0.3790548 0.4560446 -0.8051962 0.05928039 0.3714098 -0.9265747 0.2494852 0.5346788 -0.8073883 0.1360694 0.4019794 -0.9054821 0.8389613 0 -0.5441911 0.5105388 0.8598548 0 -0.6741006 0.257412 0.6923348 -0.6843224 0.229991 0.6919589 -0.6436331 0.4204518 0.6394973 -0.6303927 0.4477756 0.6341152 -0.5824812 0.5708336 0.5786751 -0.5677219 0.5929023 0.5711031 -0.5038743 0.7040554 0.5004166 -0.4885634 0.7208648 0.491589 -0.4101598 0.8161256 0.4070724 -0.3952291 0.8279414 0.3978782 -0.2904149 0.9110461 0.2926677 -0.8902586 0.08335781 -0.4477626 -0.9869892 0.09845042 0.1271218 -0.8390633 0.09969222 -0.5348218 2.7081e-4 0.72315 -0.6906911 -7.52627e-4 0.7950972 -0.6064816 -0.009415149 0.780221 -0.6254333 0.002680897 0.8353554 -0.549704 -1.5277e-4 0.884904 -0.4657737 0.001182556 0.8875786 -0.460655 -0.001135289 0.9500544 -0.3120824 -0.001067578 0.9501392 -0.3118243 9.51006e-4 0.9859774 -0.1668764 -0.002914965 0.988727 -0.1497011 0.07723903 0.9970127 -1.1221e-4 0.02791786 0.9994846 -0.01585006 0.01220434 0.9995191 -0.02850878 0.0027498 0.9991238 -0.04176449 0.00147289 0.9990198 -0.04424238 -0.008354187 0.9998231 0.01685363 -0.003001928 0.9999099 -0.01309162 -0.01646089 0.9996851 -0.0189464 0.001255512 0.9975304 0.07022547 -0.05103343 0.9930328 0.1062155 0.4226028 0.8139204 -0.3986736 0.473546 0.8179398 -0.3266936 0.9325067 0.3520213 -0.08069819 0.3686162 0.8832325 -0.2898663 0.9292338 0.3578174 -0.09214812 0.4314796 0.8918259 -0.1359112 0.3975144 0.9047292 -0.1531255 0.910652 0.4084586 -0.06224715 0.9255003 0.3766523 -0.03977662 0.3363329 0.9417428 8.75299e-4 0.5509508 0.833641 0.03867852 0.2786143 0.9599183 -0.03051108 0.920066 0.3909726 0.02488011 0.9101961 0.4138187 0.01723855 0.9876722 0.1537647 0.0293284 0.9026346 0.4303784 -0.00502634 0.4517914 0.02711701 0.8917115 0.460098 0.01347011 0.887766 -0.1891884 0.08439064 0.9783078 0.007497847 0.1390455 0.9902576 0.5096908 0.0656957 0.8578458 -0.4943362 0.2784597 0.8234634 0.5064991 0.117649 0.8541765 0.5090385 0.1129382 0.8533024 0.04395335 0.3068457 0.9507439 -0.3845657 0.4099982 0.8270494 -0.4010248 0.4286856 0.8095726 0.043949 0.3068507 0.9507425 0.5365477 0.1450437 0.8313117 -0.3833342 0.5756236 0.7222967 0.1274873 0.481359 0.8672027 0.5434232 0.1799464 0.8199455 0.536799 0.1986386 0.8199936 -0.2620797 0.6403601 0.7219788 -0.2899719 0.696212 0.6566621 0.1274884 0.4813555 0.8672046 0.5785382 0.209509 0.7882891 -0.2018024 0.8002145 0.5647411 0.5807597 0.2387432 0.7782801 0.2435359 0.6135582 0.7511569 -0.1071608 0.8160356 0.5679811 0.2435371 0.6135595 0.7511554 0.6056722 0.2319532 0.7611564 -0.1125308 0.8841904 0.4533696 0.6352382 0.2674841 0.7245168 0.632637 0.25378 0.7316872 0.3818923 0.6918341 0.6128 0.3818919 0.6918337 0.6128008 0.04978328 0.9313733 0.360646 0.0623511 0.9148168 0.3990271 0.1080878 0.9686424 0.2237163 -0.6572673 0.5402966 -0.5254325 -0.624855 0.5441068 -0.5599145 -0.5524313 0.5898724 -0.5889571 -0.4776741 0.6212202 -0.6212189 -0.4348464 0.6179786 -0.6549895 -0.5026471 0.6091389 -0.6134296 -0.3003395 0.6744622 -0.6744605 -0.3104793 0.6735184 -0.6708022 -0.1327344 0.6998506 -0.7018481 -0.08938032 0.707036 -0.7015065 0.04632556 0.7042871 -0.7084022 0.1590789 0.7031884 -0.692979 0.2262287 0.6893938 -0.6881548 0.3289839 0.671754 -0.663714 0.4073334 0.6437223 -0.6478434 0.5384637 0.5982347 -0.593441 0.5258163 0.6050944 -0.5978111 0.7053032 0.5095769 -0.4928274 0.7646628 0.4558568 -0.4555057 0.8193933 0.4045076 -0.4061629 0.8488252 0.3790981 -0.368484 0.9453508 0.2308415 -0.2302699 0.9509572 0.2168191 -0.2206127 0.9953019 0.06845957 -0.06846696 0.9930554 0.08515626 -0.08117526 0.1306185 -0.8720973 -0.4715774 -0.2886868 0.939889 0.1823972 0.07548344 -0.8667988 -0.4929119 0.07969188 -0.8636419 -0.497767 0.1279236 -0.7852202 -0.6058588 0.08530372 -0.7467164 -0.65965 0.1112099 -0.6749705 -0.7294157 0.07329982 -0.6352249 -0.768841 0.09116035 -0.5454369 -0.8331797 0.05995398 -0.5093207 -0.8584858 0.06785207 -0.4008651 -0.913621 0.04496335 -0.3725648 -0.9269163 0.0426582 -0.2453954 -0.9684841 0.02877289 -0.2276608 -0.9733154 0.01186519 -0.08263629 -0.9965092 0.01505935 -0.07612735 -0.9969844 9.35715e-5 -5.81744e-5 -1 -1.49612e-7 0 -1 -0.00415039 0.003829538 -0.9999841 0.4519554 0 0.8920406 0.7067568 0.005009591 0.7074388 0.7060443 0.005374193 0.7081473 0.7052096 0.005628347 0.7089765 0.7042238 0.005725562 0.709955 0.6984286 0 0.7156798 0.698594 0.001042783 0.7155176 0.6994475 0.002879798 0.7146782 0.7005989 0.004240572 0.7135428 0.7018715 0.005129754 0.7122851 0.7030957 0.005588769 0.7110733 0.002337396 0.004740536 -0.9999861 -0.05594265 -0.8215866 -0.5673322 0.1841984 -0.7910799 -0.5833211 0.01475805 -0.8591935 -0.511438 -0.02639675 -0.8127173 -0.58206 -0.003294229 -0.7900847 -0.612989 0.05581611 -0.749934 -0.6591537 -0.03087157 -0.6789569 -0.7335289 -0.02185475 -0.6694396 -0.742545 0.02602875 -0.6692037 -0.742623 0.04196757 -0.6387615 -0.7682594 -0.0232461 -0.5037534 -0.8635346 0.02718001 -0.4954181 -0.8682293 0.01391708 -0.5145488 -0.8573482 -0.01630628 -0.4957451 -0.868315 0.03194385 -0.3741891 -0.9268021 -0.0144909 -0.3066127 -0.9517241 -0.001477003 -0.3014047 -0.9534952 -0.01018053 -0.3014394 -0.953431 0.02323681 -0.2283673 -0.9732977 0.001066982 -0.1024205 -0.9947407 -0.005247771 -0.1005085 -0.9949223 -0.007656157 -0.1005616 -0.9949014 -0.005274832 -0.1005383 -0.9949193 0.004743158 -0.07745271 -0.9969847 -0.04889899 -0.8888797 -0.4555239 0.03656172 -0.8803262 -0.4729579 -0.003386557 -0.9113426 -0.4116351 -0.0723406 -0.8835468 -0.4627222 0.06737059 -0.8947737 -0.4414082 0.1392434 -0.88713 -0.4400134 -0.06006246 -0.9188514 -0.390006 0.03747391 -0.9078493 -0.4176188 -0.07677996 -0.9160442 -0.3936597 0.1820166 -0.9055491 -0.3832112 0.06209367 -0.9310846 -0.3594802 0.1892503 -0.8998785 -0.3929416 -0.0569511 -0.945517 -0.3205532 -0.1729782 -0.9447917 -0.2782935 0.06639808 -0.9290549 -0.3639346 -0.06605398 -0.944503 -0.3217935 -0.1954647 -0.9470937 -0.2545725 0.2296618 -0.9066499 -0.3538948 0.231958 -0.9044478 -0.3580079 0.09473073 -0.9470679 -0.3067389 -0.04324483 -0.9675459 -0.2489674 -0.0401563 -0.9666828 -0.2528082 -0.1699603 -0.9670357 -0.1896195 0.09834474 -0.9451784 -0.3113939 -0.2975556 -0.9478172 -0.1144699 -0.1825266 -0.9677875 -0.1734114 -0.3195262 -0.9438383 -0.08409792 0.2707759 -0.9062064 -0.3247622 0.12917 -0.9577383 -0.257007 0.2712092 -0.9057574 -0.3256519 0.2707762 -0.9062088 -0.3247552 -0.01230341 -0.9826731 -0.1849385 0.1220201 -0.899999 -0.4184652 0.1215417 -0.8996283 -0.4194002 0.1273263 -0.908676 -0.3976131 0.1304464 -0.9216029 -0.365557 0.1286338 -0.9563322 -0.2624542 0.2274439 -0.8957888 -0.3818792 0.1005201 -0.9854596 -0.1369861 0.1912815 -0.9359201 -0.2957447 0.206274 -0.9257832 -0.3168224 0.1360763 -0.9180184 -0.3724588 0.1981372 -0.8652434 -0.4605383 0.1607044 -0.9383504 -0.3060598 0.2087543 -0.9241911 -0.319832 0.2101308 -0.9235985 -0.3206412 0.2563297 -0.9157437 -0.3093684 0.2411032 -0.9030527 -0.3554787 0.2606135 -0.8791193 -0.3990361 0.2725011 -0.8916178 -0.3616086 0.2606132 -0.879115 -0.3990461 0.3032559 -0.9022665 -0.3065147 0.3092437 -0.8849613 -0.3481552 0.2916394 -0.8928928 -0.3430581 0.3003532 -0.8767207 -0.3756976 0.3003521 -0.8767194 -0.3757015 0.3392358 -0.878213 -0.3371368 0.3334041 -0.8813056 -0.3348765 0.3345062 -0.8741335 -0.3521311 0.3345066 -0.8741351 -0.3521266 0.365529 -0.8712196 -0.3276662 0.365792 -0.8716266 -0.3262873 0.9999955 -0.003008186 3.31879e-5 1 8.33568e-5 3.34822e-4 0.9999641 -0.003407955 -0.007767379 0.9989812 0.04512751 -4.02687e-4 1 3.18097e-6 0 1 -4.10959e-6 0 0.8379758 -0.5448291 -0.03094977 1 -6.79506e-6 0 1 1.34438e-5 0 1 -2.00195e-5 0 -0.7169734 0.05797815 0.6946853 -0.554971 0.2137233 0.8039463 -0.8072304 0.5272586 0.2652876 -0.7212954 0.5976719 0.3500305 -0.7829425 0.61492 0.09420466 0.8831481 -0.4435193 0.1527743 0.8672657 -0.466992 0.1725364 0.9850745 -0.1274706 0.1156699 0.9523313 -0.1859377 0.2418517 0.8115993 -0.07581377 0.5792744 -0.06885635 0.1345952 0.9885054 0.9073557 -0.09318494 0.4099053 0.9999291 -0.007989108 0.008831083 0.9495443 -0.03318291 0.3118726 0.9979124 -0.00455445 0.06442272 0.9400027 -0.005737125 0.3411189 0.9998195 0.001581311 0.01893723 0.8120155 0.03160804 0.5827794 0.9828572 0.04224348 0.1794639 0.9811263 0.05167436 0.1863362 0.3059343 -0.9059434 -0.2926957 0.4717551 -0.8814688 0.02144956 0.4968281 -0.8626452 0.09489524 0.6975289 -0.7161151 0.02515166 0.6933256 -0.7204994 0.01342827 0.3783665 -0.8715115 -0.3119399 0.9997844 0.01108682 -0.01755666 -0.3252865 0.1585435 -0.9322299 -0.9276869 0.0933333 -0.3615051 -0.4257484 0.404133 -0.809577 -0.5642621 0.3349891 -0.7545798 -0.8919276 0.2019551 -0.4045732 -0.9167748 0.1632171 -0.364533 -0.3417892 0.5188846 -0.7835426 -0.9300447 0.204182 -0.3054941 -0.4618717 0.618493 -0.6357209 -0.5175392 0.5845273 -0.6248849 -0.897227 0.3079181 -0.3164969 -0.907122 0.2892009 -0.3057654 -0.3348663 0.749191 -0.5714697 -0.930866 0.2920597 -0.2195212 -0.4885497 0.7696746 -0.410999 -0.8925576 0.4008065 -0.2066283 -0.01301449 0.6830748 -0.7302325 0.9641014 -0.2528634 -0.08104687 0.6462064 -0.7304705 -0.2209757 0.652409 -0.724308 -0.2230257 0.9632922 -0.2550059 -0.08390617 0.6579053 -0.7126973 -0.2433584 0.6563068 -0.7135252 -0.2452411 0.8965461 -0.4188794 -0.1440325 0.9825614 -0.1659482 -0.08387202 0.9631556 -0.2556755 -0.08343541 0.664126 -0.7048932 -0.2491229 0.3392137 -0.8892906 -0.3067515 0.3536769 -0.8817612 -0.3121057 0.3657767 -0.8783157 -0.3078457 0.3577999 -0.8828725 -0.3041638 0.3911018 -0.8757024 -0.2831692 0.3912124 -0.8756377 -0.2832168 0.3633454 -0.8725322 -0.3266006 0.3842945 -0.8703666 -0.3078633 0.3798308 -0.8731902 -0.3053976 0.3974111 -0.8689829 -0.2948446 0.3826029 -0.8687322 -0.3145148 0.3914965 -0.8670657 -0.3081033 0.3906881 -0.8676319 -0.3075351 1 -1.45594e-6 0 0.9999477 -0.007441937 0.00701934 0.999961 0.00838536 -0.002759397 1 4.20238e-6 0 0.01280051 0.005337238 -0.9999039 0.04313379 0.03422349 -0.998483 -8.24405e-5 3.26281e-4 -1 -0.2648477 -0.01101124 -0.9642274 -0.4029927 -1.34009e-4 -0.9152032 -0.6087464 7.6092e-4 -0.7933646 -0.7933165 0.00263822 -0.6088038 -0.9590357 -0.003581225 -0.2832628 -0.9470306 -0.00119102 -0.3211416 -0.8891438 0.07034194 -0.4521896 -0.2607533 0.174937 -0.9494234 -0.604173 0.1224911 -0.7873824 -0.7834984 0.1568573 -0.6012705 -0.9585772 0.03104162 -0.2831363 0.01279819 0.1651923 -0.9861784 0.002169191 -0.9999946 -0.002475082 1 -3.91906e-7 0 0.0826016 -0.8260163 -0.557561 -0.473027 0.779642 -0.4103705 -0.9045962 0.3760166 -0.2007917 -0.3369748 0.8944904 -0.2938284 -0.9300392 0.3502094 -0.1112678 -0.5068891 0.847804 -0.1558591 -0.4324777 0.8914842 -0.1349787 -0.9130982 0.4010199 -0.0737214 -0.8713573 0.4858902 -0.06817138 -0.3480546 0.9373412 0.01579988 -0.9276394 0.3733227 0.0107482 -0.9220491 0.3839629 0.0489701 -0.8396537 0.5326473 0.1061539 -0.5176714 0.848705 0.1082419 -0.3974717 0.9021294 0.1678661 -0.3677316 0.8732 0.3198364 -0.9235251 0.3583346 0.1367404 -0.7781924 0.5687875 0.2662661 -0.5976586 0.7359775 0.3180271 -0.3448134 0.8848772 0.3132032 -0.8938057 0.4080261 0.1860811 -0.9401327 0.2935919 0.1730734 -0.9932257 0.08879643 0.07495313 -0.9411617 0.3050418 0.1454796 -0.002855479 0.98312 0.18294 0.0144419 0.9623745 0.2713429 -0.04489737 0.9380477 0.3435853 0.9798713 -0.009259939 -0.1994156 0.8351706 -0.06883072 -0.5456669 0.3927136 -0.03281903 -0.9190751 0.5214909 -0.1081427 -0.846376 0.2021932 -0.2011665 -0.9584624 0.9830816 -0.04580318 -0.1773494 0.9803977 -0.06234812 -0.1869043 0.8346403 -0.174293 -0.5224919 0.5686165 -0.2603399 -0.7803195 0.8346127 -0.1743311 -0.5225233 0.5009738 -0.3190675 -0.8045007 0.2960548 -0.3521385 -0.8878908 0.3952938 -0.3059073 -0.8661199 0.9832931 -0.07453441 -0.1660702 0.980495 -0.1018169 -0.1681163 0.8345359 -0.2854113 -0.4712646 0.5823139 -0.4211835 -0.6953524 0.8344978 -0.2854725 -0.471295 0.2211773 -0.4735667 -0.8525347 0.4092233 -0.5454488 -0.7314519 0.391007 -0.554566 -0.7345544 0.4885603 -0.5215927 -0.6994641 0.9827491 -0.103533 -0.1532489 0.8344125 -0.3857802 -0.3936107 0.9811226 -0.1353658 -0.1381109 0.9815413 -0.1328969 -0.1375331 0.5879799 -0.566228 -0.5776379 0.8343735 -0.385847 -0.393628 0.2447941 -0.7031913 -0.6675313 0.3773239 -0.7937089 -0.4771299 0.6684799 -0.621816 -0.408019 0.3652368 -0.8297475 -0.422044 0.9829686 -0.1488209 -0.1078195 0.8342893 -0.4681679 -0.2911704 0.9801588 -0.1683186 -0.1046796 0.5273244 -0.7483755 -0.4023221 0.7689965 -0.5705307 -0.288339 0.9832546 -0.1641283 -0.07919907 0.9841111 -0.1671201 -0.05996942 0.9793814 -0.1945212 -0.05453193 0.792079 -0.5893573 -0.1589617 0.5484709 -0.8178105 -0.1742576 0.8375391 -0.5094164 -0.1975429 0.241163 -0.9067862 -0.3458023 0.2375695 -0.9098817 -0.340112 0.2824472 -0.8943927 -0.3468216 0.2118482 -0.8748407 -0.4356306 0.3511077 -0.7704287 -0.5321306 0.232459 -0.8299633 -0.5070738 0.366066 -0.7643359 -0.5308356 0.2980045 -0.8520066 -0.4304394 0.1512646 -0.8521116 -0.5010238 0.2663684 -0.8341907 -0.4828807 0.3598143 -0.7699436 -0.5269921 0.3396801 -0.6784154 -0.6514369 0.1553544 -0.6927188 -0.7042768 0.2285069 -0.5321836 -0.8152087 0.1273328 -0.6121675 -0.7804085 0.1914125 -0.5443819 -0.8167067 0.1535153 -0.6128446 -0.7751481 0.1411277 -0.505691 -0.8510933 0.1797662 -0.4803889 -0.8584349 0.1666155 -0.3367291 -0.9267432 0.1356553 -0.3689977 -0.9194773 0.09008049 -0.3619101 -0.9278505 0.09373366 -0.3565605 -0.9295583 0.03520065 -0.2255817 -0.9735881 0.08755058 -0.2146376 -0.9727619 0.152049 -0.07548326 -0.9854864 0.01351892 -0.1281173 -0.9916669 0.0257917 -0.07398718 -0.9969257 -0.9973791 0.05116158 -0.05116266 -0.9989907 0.04470539 -0.00437361 -0.9845536 0.12134 -0.1262171 -0.9756032 0.1722715 -0.1360923 -0.9577188 0.2004516 -0.2063833 -0.9299393 0.2693272 -0.250351 -0.9373143 0.2690706 -0.2214562 -0.8970142 0.3118559 -0.3132278 -0.8614809 0.3651812 -0.3528364 -0.8497461 0.3646922 -0.3806984 -0.7709907 0.4575126 -0.4430074 -0.7493137 0.4599667 -0.4764029 0.9844859 -0.1717435 -0.03594112 0.8655419 -0.5006891 0.01215672 0.5810279 -0.7915049 -0.1895437 0.4533263 -0.8726853 -0.1814269 0.711342 -0.6668606 -0.2220125 0.6608183 -0.7234095 -0.1999949 0.9526451 -0.2903081 -0.09049093 0.9608675 -0.2685312 -0.06800651 0.9609282 -0.2654742 -0.07836276 0.2336835 -0.9208079 -0.3122579 0.3177284 -0.9114137 -0.2614837 0.2729938 -0.9280538 -0.2533586 0.2764288 -0.9084844 -0.3134377 0.3275251 -0.903297 -0.2770956 0.3086735 -0.9130226 -0.2666651 0.391942 -0.8758842 -0.2814397 0.3151012 -0.9210598 -0.2288236 0.3171176 -0.9131181 -0.2562261 0.3546198 -0.8782312 -0.3208656 -1 2.81594e-5 -1.00174e-4 -0.9999993 0.001195013 -1.55113e-5 -1 -3.42215e-6 0 -1 3.91011e-6 0 -1 5.84609e-6 0 -1 -1.58208e-5 0 -1 -2.87228e-6 0 -1 -4.32788e-6 0 -1 5.59386e-6 0 1 1.59008e-7 0 1 -3.41841e-7 0 1 -6.56388e-7 0 1 5.06396e-7 0 1 7.63867e-7 0 1 -1.32972e-6 0 -0.9999998 7.19153e-4 -1.07949e-4 -0.9999995 -0.001043856 5.90098e-5 -1 8.5599e-5 -1.88159e-5 -1 4.67023e-5 -1.74634e-5 -1 2.83077e-5 -1.62974e-5 -1 2.08523e-5 -1.52462e-5 -1 3.98774e-6 -1.42758e-5 -1 6.96199e-6 -1.33639e-5 -1 7.31263e-6 -1.24939e-5 -1 4.22351e-6 -1.16522e-5 -1 2.04503e-6 -1.08269e-5 -1 -1.39463e-4 5.90143e-5 -1 2.4555e-4 -2.07856e-5 -0.002139687 0.07474064 -0.9972007 0 0.07844948 -0.9969182 0.001940488 0.2226194 -0.9749035 -0.003848135 0.233428 -0.9723665 0.003648638 0.3655376 -0.9307895 -0.005474627 0.3826521 -0.9238764 0.005172431 0.5001814 -0.8659052 -0.006927251 0.5224548 -0.8526389 0.00651437 0.6235849 -0.7817286 -0.008185923 0.6493989 -0.7604039 0.007663547 0.7330715 -0.6801085 -0.009219646 0.7603511 -0.6494469 -0.02101194 0.9236682 -0.3826169 -0.01644933 0.9722355 -0.2334258 0 0.9982421 -0.05926978 0.3572145 0.1721246 -0.9180256 0.1116613 0.07427316 -0.9909669 0.9603779 0.02415013 -0.277653 0.9878751 0.1082264 -0.1113103 0.9324972 0.04988521 -0.3577159 0.6954702 0.078673 -0.7142351 0.8290961 0.1833785 -0.5281782 0.7014632 0.1259256 -0.7014928 0.5298852 0.1107677 -0.8408045 0.3147926 0.1324383 -0.9398755 0.2480992 0.2156604 -0.9444244 0.9672077 0.06550782 -0.2453939 0.9656521 0.1096204 -0.2355834 0.9625334 0.1037701 -0.2505221 0.7094444 0.2697033 -0.6511136 0.2713506 0.3518237 -0.8958733 0.3129349 0.3807169 -0.8701302 0.6932175 0.2889031 -0.6602913 0.2421434 0.4853014 -0.8401484 0.9657092 0.1487578 -0.2127839 0.714321 0.4260214 -0.555204 0.962507 0.1651319 -0.2152017 0.6887317 0.4600478 -0.5603613 0.2881979 0.5971384 -0.7485772 0.3055509 0.6041898 -0.7359303 0.9672052 0.1794922 -0.1797127 0.2399594 0.7116745 -0.6602567 0.7185348 0.5517703 -0.423388 0.9656643 0.2127342 -0.14912 0.9625293 0.2151396 -0.1650835 0.594534 0.7006126 -0.3945521 0.343833 0.8196363 -0.4582307 0.3245199 0.8220254 -0.4679331 0.9656971 0.2352957 -0.1098415 0.684109 0.6738597 -0.2791202 0.9625121 0.2505924 -0.1037986 0.9672056 0.2453187 -0.06581979 0.3518749 0.9090262 -0.2232835 0.3477931 0.9188788 -0.1862841 0.7014545 0.70149 -0.1259903 0.8450642 0.5309299 -0.06308567 0.9653713 0.2554905 -0.05275529 0.933696 0.3307452 -0.1371842 0.9936645 0.111959 -0.009812653 0.02595931 -0.07363975 -0.996947 0.027188 -0.07262027 -0.9969891 0.1141648 -0.1502323 -0.9820371 0.3358852 -0.1108185 -0.9353612 0.5627717 -0.08353137 -0.822381 0.8414813 -0.06212443 -0.5367027 0.9396344 -0.1202303 -0.3203623 0.9937229 -0.009413003 -0.1114739 1.85779e-6 0 -1 -4.51701e-7 0 -1 0.002134203 -0.002418816 -0.9999948 0 6.41014e-4 -0.9999999 0.9937669 0 -0.1114786 0.9937118 3.13093e-4 -0.1119678 0.9463921 -2.65123e-4 -0.3230201 0.9334436 0.01976442 -0.3581794 0.8427929 -0.02596616 -0.5376115 0.8436014 -0.02714461 -0.5362835 0.7068773 0.02457982 -0.706909 0.5640779 -0.05169218 -0.8241021 0.532926 -0.02365112 -0.8458312 0.3377405 0.02282607 -0.9409625 0.3627134 0.002918541 -0.9318962 0.1154714 -0.00229156 -0.9933083 0.1119697 0 -0.9937117 0.5306671 0.8313473 -0.1650885 0.6379931 0.7513809 -0.1684982 0.111774 0.9919868 -0.05889815 0.4088394 0.8973245 -0.1663107 -0.01167392 0.9968492 -0.07845658 -0.01643747 0.9722406 -0.2334057 0.04465347 0.8710399 -0.4891785 0.01656317 0.8525095 -0.5224493 1 3.10351e-7 0 6.5167e-4 0.9999998 5.29619e-5 0.9999966 0.001384198 -0.002208054 1 -5.70506e-4 -7.43023e-5 0.961086 -0.1840682 0.205992 -0.5362554 -0.007166206 0.8440253 -0.5504496 -0.01512283 0.8347315 -0.5472633 -0.01161706 0.83688 -0.543847 -4.66592e-4 0.8391844 0 -1 0 0.3776602 -0.8640482 -0.3328568 0.2368711 -0.1000133 0.9663796 0.4539434 -0.462877 0.7613675 0.5200549 -0.4869199 0.7017492 0.540436 -0.6388316 0.5475613 0.01391738 0.5844959 0.8112774 0.281876 -0.102458 0.9539645 0.1757532 0.03600156 0.9837757 0.3483712 -0.1124808 0.9305835 0.4815795 -0.02410346 0.8760709 0.4910525 -0.03749573 0.8703227 0.4554896 -0.4619738 0.7609923 0.5929015 -0.3527636 0.7238963 0.4971065 -0.665467 0.5568114 0.4847894 -0.6409465 0.5951193 0.652553 -0.5413008 0.530253 0.6161574 -0.7085257 0.3440079 0.5454206 -0.837594 -0.03086584 0.4653367 -0.8693268 -0.1665315 0.3553192 -0.9340108 -0.03704398 0.6188419 -0.7150431 0.3251893 0.4530512 -0.8885421 -0.07237243 0.401898 -0.9070776 -0.1252533 0.6277956 -0.7016445 0.3369981 0.6444604 -0.3422868 0.6837475 0.6469035 -0.3190512 0.6926199 0.4957444 -0.01489186 0.8683408 0.3104243 -0.9035879 -0.2952381 0.1971139 -0.9421263 -0.2711902 0.3059458 -0.9047393 -0.2963849 0.2562024 0.08328598 0.9630285 0.3544101 0.05971103 0.9331818 0.6558814 0.07864439 0.750756 0.3323323 -0.07304048 0.9403299 0.7050172 -0.07075542 0.7056518 0.1856285 -0.1332911 0.9735378 0.5935947 -0.1371243 0.7929957 0.2614477 -0.2291522 0.9376217 0.09384083 -0.3045476 0.9478632 0.6470505 -0.2060917 0.7340654 0.5062759 -0.3062883 0.8061466 0.9208592 -0.1161531 0.3721921 0.2041416 -0.392111 0.8969812 0.853789 -0.2250663 0.4694566 0.9941435 -0.02715778 0.1046006 0.03057163 -0.4550173 0.8899577 0.5837455 -0.3522214 0.7315608 0.9861252 -0.08229124 0.144171 0.3807926 -0.495814 0.7804907 0.497214 -0.4468709 0.7436966 0.8715755 -0.2325186 0.431615 0.9816727 -0.08870482 0.1686726 0.7329768 -0.4172288 0.5372758 -0.4978063 4.92779e-4 0.8672881 -0.5350548 -0.006736338 0.8447906 0.06064909 -0.4010703 0.9140374 -0.003353774 -0.251598 0.9678261 0.01576977 -0.09440422 0.9954091 0.06213581 -0.01976609 0.997872 0.09037846 0.06707292 0.9936463 0.09116744 0.07841539 0.9927435 0.194193 0.2960969 0.935209 0.1344234 0.1859015 0.9733299 0.1086314 0.1694635 0.9795313 0.1153102 0.1785046 0.977159 0.1175344 0.1078433 0.9871959 0.1712553 0.0853886 0.9815195 0.1237934 0.06446164 0.990212 0.2467819 -0.07473063 0.9661853 0.3504899 0.032076 0.9360171 0.39219 0.05271083 0.9183728 0.3678779 -0.04794323 0.9286374 0.7897607 -0.09106856 0.6066175 0.66966 -0.3006506 0.6790911 0.7231866 -0.2860631 0.6286247 0.3758314 0.296083 0.8781149 0.4605287 0.1928144 0.8664503 0.3948699 0.2972266 0.8693296 0.322137 0.2883487 0.901711 0.3822845 0.1526339 0.9113515 0.340965 0.2912679 0.8938155 0.3191721 0.2459022 0.9152384 0.2437549 0.2802867 0.928452 0.2842794 0.1267594 0.9503248 0.2139113 0.2091978 0.9541898 0.2097261 0.1696964 0.9629217 0.1626902 0.227898 0.9599972 0.1532691 0.09098947 0.9839866 0.1791455 0.02928829 0.9833866 0.1670357 0.07722926 0.9829216 0.1331938 0.1255831 0.9831014 -0.724617 0.6671788 -0.1726348 -0.6476532 0.4092508 -0.6426969 -0.7253689 0.6658846 -0.1744641 -0.5572745 0.8212862 0.122205 -0.7246153 0.6671814 -0.1726316 -0.5506164 0.7971789 0.2476436 -0.7811428 0.6123464 -0.1218515 -0.7337259 0.5925793 0.3324096 -0.7240674 0.3981922 0.563178 -0.09459418 0.02775603 0.9951289 -0.3720337 0.2184861 0.9021391 -0.4756997 0.3210244 0.8189342 -0.4001361 0.7468502 0.5311366 -0.605444 0.5395126 0.5851185 -0.7773556 0.6232603 -0.08523511 -0.1925814 0.7445091 0.6392329 -0.3248364 0.001050889 0.9457697 -0.5623628 0.1437552 0.8142989 -0.6403983 -2.75398e-4 -0.7680431 -0.4927611 0.002374589 -0.8701615 -0.4171549 0.005316793 -0.9088199 -0.3399441 0.002449393 -0.9404425 -0.1374762 -0.001425623 -0.9905041 0.08637279 2.49695e-4 -0.9962629 0.2553984 0.007820427 -0.9668043 0.319364 0.004260659 -0.9476225 0.5456354 -0.00105375 -0.8380221 0.7122352 0.02560454 -0.7014738 0.9316018 -8.03547e-4 -0.3634797 -0.3041583 0.9036665 0.3014544 -0.1890541 0.9640443 0.1867545 -0.1771622 0.9677659 0.1790049 -0.06827867 0.995454 0.06640398 -0.05876928 0.9964561 0.06017881 0.05451798 0.996944 -0.05595141 0.06133568 0.9962894 -0.06037753 0.1756668 0.9684722 -0.1766433 0.1796801 0.9672673 -0.17919 0.2917768 0.9108977 -0.2917733 -0.7067435 1.78016e-4 -0.7074699 -0.7061063 0.004922449 -0.7080888 -0.6119597 0.1686864 -0.7726904 -0.468113 0.3843582 -0.7957004 -0.4436371 0.4103727 -0.7967311 -0.6920805 0.03288418 -0.721071 -0.4801709 0.3866037 -0.7873842 -0.4034767 0.473141 -0.7831629 -0.3814563 0.4980608 -0.7787341 -0.3970223 0.4797436 -0.7824445 -0.4409829 0.4329608 -0.78618 -0.4022779 0.5065561 -0.7626097 -0.3429994 0.5387044 -0.7695122 -0.2432358 0.6246196 -0.7420827 -0.1983163 0.6618924 -0.7228894 -0.04254239 0.7614476 -0.646829 0.1082051 0.8284441 -0.5495198 0.2735553 0.8669303 -0.4166529 -0.4472646 0.8826857 0.1442926 -0.754242 0.3957766 -0.5239083 -0.3663402 0.9287732 -0.05634981 -0.3560209 0.9344417 0.008245348 -0.5741702 0.7522953 -0.3230799 -0.574168 0.7523019 -0.3230682 -0.6934132 0.4873071 -0.5307635 -0.6941183 0.4903302 -0.5270446 -0.2076989 0.9752555 -0.07574957 -0.6409539 0.4787076 -0.6000144 -0.1477187 0.9601676 -0.2371867 -0.1551241 0.9528726 -0.2607114 -0.4126851 0.7712969 -0.4845535 -0.412685 0.7712969 -0.4845539 -0.5455379 0.5850832 -0.6000552 -0.5546634 0.5438347 -0.6297558 0.02742677 0.9478965 -0.3173959 -0.5027874 0.5062291 -0.7006689 -0.2469331 0.7194184 -0.6492006 0.01821643 0.8902195 -0.4551676 0.143426 0.9481597 -0.2835883 0.02092045 0.851215 -0.5244001 -0.4318569 0.5257264 -0.7328789 -0.2768213 0.7199547 -0.6364238 -0.1701346 0.8470757 -0.5035048 -0.1966278 0.7393109 -0.6440164 -0.4539805 -0.8470877 0.2763046 -0.4533604 -0.848363 0.273395 -0.4522265 -0.8622987 0.2278861 -0.3093813 -0.8458716 0.4344936 -0.3163899 -0.8510039 0.4191538 -0.3273567 -0.8542048 0.4039453 -0.1925182 -0.8433929 0.5016226 -0.2101692 -0.8212646 0.5304276 0.09594672 -0.7045931 0.7030952 0.2792406 -0.5346295 0.7976191 0.3361161 -0.58741 0.7361899 0.5099868 -0.3193511 0.7987041 0.733245 -0.1144878 0.6702569 0.6976909 -0.07378655 0.7125891 0.710013 0.09333074 0.6979764 0.7134165 0.1114984 0.6918129 0.4465981 0.2848923 0.8481666 0.4257016 0.3456322 0.8362516 0.4930779 0.3589311 0.7924914 0.4719185 0.3397439 0.813552 0.4885823 0.3554179 0.7968472 0.5040731 0.3040662 0.8083651 0.5413032 0.3531867 0.7630532 0.5159114 0.3437187 0.7846612 0.5494706 0.3572877 0.7552667 0.5575377 0.3109859 0.769701 0.591749 0.3431873 0.7294215 0.5667667 0.3431259 0.7490262 0.6133757 0.3486296 0.7086802 0.615197 0.3111583 0.724371 0.6236216 0.3302645 0.7085348 0.6427235 0.3284323 0.6921263 0.6668816 0.3003149 0.6819678 0.668949 0.329252 0.6664086 0.673443 0.3098803 0.6711549 0.6873942 0.3079509 0.6577656 0.7139731 0.3024111 0.6314983 0.7095375 0.2794122 0.6469046 0.7122894 0.2819702 0.6427571 0.6883561 0.3482038 0.6363334 0.7484955 0.2538752 0.612619 0.7514767 0.2630101 0.6050691 0.8008257 0.2947502 0.5213449 0.7568158 0.259699 0.5998219 0.7844568 0.2281603 0.5766891 0.7800489 0.2070798 0.5904589 0.7911553 0.2045117 0.5764099 0.791697 0.2313679 0.5654068 0.8041592 0.1867533 0.564315 0.810909 0.1596022 0.5629865 0.822303 0.152372 0.5482705 0.8324447 0.1912182 0.5200688 0.8267803 0.1150134 0.5506415 0.8317025 0.08125221 0.5492441 0.8480792 -0.01668649 0.5296069 0.1309141 -0.9567632 -0.2597422 -0.1489591 -0.9831051 -0.1063742 -0.01483452 -0.983344 -0.1811482 -0.157014 -0.9831088 -0.09404176 -0.2850607 -0.9583344 -0.01832276 -0.2986577 -0.9543526 0.00386399 -0.4305515 -0.8984192 0.08642065 -0.4341226 -0.8952089 0.1006914 0.1649684 -0.9644543 -0.20643 0.02009177 -0.9922361 -0.1227352 0.09740692 -0.9812533 -0.1662945 0.1538771 -0.9648271 -0.2131441 -0.03211128 -0.996072 -0.08251976 0.03310126 -0.9890071 -0.1441156 -0.1173545 -0.9926416 -0.02984511 -0.2559156 -0.9640985 0.07086223 -0.1627967 -0.9866204 0.008806109 -0.101218 -0.9931936 -0.0576319 -0.3905496 -0.9016283 0.1858432 -0.3375369 -0.9310195 0.1388224 -0.2815854 -0.9552078 0.09103715 -0.2339371 -0.971796 0.02976554 -0.4134761 -0.8927356 0.1790552 -0.4475362 -0.8655835 0.22467 -0.4091256 -0.898095 0.1613749 0.5149334 0.1353662 0.8464748 0.5446342 0.1177519 0.8303663 0.609116 -0.3574458 0.707962 0.5471408 0.1032153 0.8306525 0.5465114 0.1220452 0.8285109 0.6069376 -0.365236 0.7058537 0.5168855 -0.7590422 0.395834 0.5123671 -0.7644433 0.3912883 0.3393955 -0.9385729 0.06238275 0.3359303 -0.9399943 0.05967992 0.2363325 -0.9710448 0.03491389 0.5694711 0.1051251 0.8152617 0.5641799 -0.3738059 0.7361863 0.5722686 0.1190496 0.811379 0.5623487 -0.377904 0.7354948 0.4067869 -0.7857065 0.4660364 0.1629788 -0.981235 0.103033 0.2621039 -0.9469704 0.1858724 0.4038135 -0.7885184 0.463868 0.1204777 -0.9844543 0.1278077 0.5950385 0.09131306 0.798493 0.5288107 -0.3773037 0.7602639 0.6095115 0.1208391 0.7835137 0.305981 -0.7867974 0.5360276 0.5274409 -0.3794801 0.7601323 0.3041718 -0.7881531 0.5350649 0.01436418 -0.9826554 0.1848838 0.1715607 -0.9370491 0.3041481 0.004896938 -0.9743567 0.224956 0.6228352 0.08588939 0.7776243 -0.06247884 -0.9667105 0.2481273 0.6408137 0.1040457 0.7606132 0.4895374 -0.3701714 0.7895103 0.2041695 -0.763458 0.612737 0.4879917 -0.3719904 0.7896122 -0.0653547 -0.9336504 0.352173 -0.06812214 -0.9340104 0.3506907 0.2022971 -0.7645498 0.6119964 0.6441358 0.08124589 0.7605842 -0.1773179 -0.9252502 0.3353663 0.4417296 -0.3487561 0.8265859 0.6896401 0.1308606 0.7122303 0.6629344 0.08756345 0.7435393 0.4928792 -0.3056233 0.814656 0.101081 -0.7136439 0.6931775 -0.2111451 -0.8786945 0.4281516 -0.1489601 -0.8729726 0.4644673 0.1056499 -0.7117836 0.6944079 -0.2880908 -0.8620641 0.4169524 0.9148553 -0.2015232 0.3498975 0.9031133 -0.1593846 0.3987268 0.8885876 -0.1125301 0.44469 0.8701869 -0.05657875 0.4894626 0.8524698 0.006777524 0.5227328 0.8021779 0.1295281 0.5828663 -1.44951e-4 -0.9999205 -0.0126118 -6.70002e-4 -0.9998919 -0.01469069 0 -0.9999574 -0.009231984 -0.4189233 -0.9034371 0.09113085 -0.4513366 -0.8922941 -0.01031994 -0.4237365 -0.9057359 -0.009479165 -0.3229871 -0.9301205 -0.1748005 -0.4440127 -0.8882246 -0.117941 -0.3960765 -0.9111062 -0.1140574 0.707355 0.004577517 0.7068437 0.7078469 0.004104912 0.706354 0.7082546 0.003603219 0.7059479 0.7090581 0.002358198 0.7051463 0.7071077 1.48968e-6 0.707106 0.7071048 2.49381e-6 0.7071089 0.7141139 -0.005651712 0.7000068 0.7089964 2.76803e-4 0.7052121 0.6787242 7.41029e-4 0.7343929 -0.2020025 -0.8484395 0.4892294 -0.4705632 -0.8393442 0.2721611 -0.473387 -0.8340765 0.2832335 -0.4162015 -0.8776567 0.2376872 -0.4561776 -0.8447028 0.2799631 -0.4694327 -0.8343262 0.2890204 -0.4522299 -0.8622989 0.2278788 -0.4151757 -0.8777239 0.2392278 -0.4663877 -0.8348957 0.2922869 -0.4155336 -0.8706414 0.263278 -0.4643027 -0.8646032 0.192053 -0.4801806 -0.8535674 0.2021126 -0.481458 -0.8666383 0.1309058 -0.4647725 -0.8599386 0.2109312 -0.4683038 -0.8644235 0.182931 -0.4704764 -0.8629807 0.1841642 -0.4860926 -0.8572657 0.1697345 -0.4900521 -0.8609444 0.1364691 -0.4861276 -0.8655043 0.1207573 -0.4610552 -0.8809291 0.1067338 -0.4962244 -0.8676235 0.03147923 -0.4632857 -0.8801629 0.1033431 -0.4963526 -0.8589547 0.1258216 -0.4939816 -0.8610604 0.1206532 -0.493997 -0.866242 0.07477986 -0.462496 -0.8860082 0.03297209 -0.4802328 -0.8761584 0.04150992 -0.4906924 -0.8685565 -0.06950241 -0.480872 -0.8764255 0.0253095 -0.4716266 -0.881496 0.02309173 -0.4290171 -0.9018104 0.05179274 -0.4402624 -0.8968452 -0.04287058 -0.4436563 -0.8952342 -0.04153299 -0.4381151 -0.8988739 -0.009003639 -0.9999876 0.002013564 0.004572629 -1 -5.39082e-5 3.98456e-4 -1 -3.74985e-4 2.15369e-5 6.50333e-5 -4.24583e-4 1 -5.06079e-4 -5.59717e-5 1 -0.3866693 0.005125522 0.9222042 -0.4907721 -0.01192599 0.8712064 -0.9137964 0.0114395 0.4060117 -0.9404833 0.001508772 0.3398367 0.7815409 0 -0.6238541 0.7818362 -3.9468e-5 -0.623484 0.8991082 3.73172e-5 -0.4377265 0.9009643 -3.05201e-4 -0.433893 0.9725509 2.96983e-4 -0.2326905 0.9749268 -5.20467e-4 -0.2225252 0.9998937 5.14272e-4 -0.01457464 0.9999999 -6.1295e-4 0 0.9779866 6.22995e-4 0.2086668 0.9749271 -4.91809e-4 0.2225241 0.9051734 5.0537e-4 0.4250423 0.9009674 -2.841e-4 0.4338869 0.7840216 2.93386e-4 0.6207337 0.7574181 -0.003181219 0.6529224 0.7835043 0.03640604 0.6203191 0.8094606 0.08876705 0.5804256 0.7949306 0.05166721 0.6044964 0.7886002 0.1922282 0.5840874 0.8077305 0.09172278 0.5823732 0.8285039 0.2440603 0.504 0.9021776 0.08131206 0.423632 0.9646988 0.1642861 0.205831 0.965075 0.1678408 0.2011458 0.8773846 0.3659671 0.3102651 0.8706684 0.3939211 0.2945554 0.84607 0.5108379 0.1523495 0.9830855 0.182586 -0.01432961 0.940811 0.253387 -0.2250993 0.9552413 0.2291569 -0.1870862 0.8006203 0.5968629 -0.05255329 0.8098816 0.5852063 -0.04031652 0.6977439 0.6778292 -0.2317349 0.8720388 0.2435303 -0.4245486 0.6747517 0.6823436 -0.2812783 0.7464115 0.2964394 -0.5958135 0.9540874 0.09459674 -0.2841983 0.8288258 0.3057972 -0.4685466 0.721512 0.5009825 -0.477951 0.7578341 0.6213868 -0.1989122 0.4881312 0.8096939 -0.3257668 0.4235047 0.866217 -0.265164 0.4259545 0.8657706 -0.2626865 0.5695811 0.817996 -0.0803743 0.5655918 0.8202447 -0.08546644 0.6715647 0.7358602 0.08666449 0.6756845 0.7312198 0.09363776 0.7447523 0.616601 0.2552399 0.7488847 0.6071465 0.265603 0.7826386 0.4659016 0.4128106 0.7840834 0.4558948 0.4211569 0.7825797 0.3015406 0.5446488 0.7814826 0.2843788 0.5553501 0.7414415 0.09761834 0.663879 0.7413328 0.09719735 0.664062 0.4609431 0.8871734 0.02132809 0.369863 0.9045552 -0.2120883 0.6576377 0.5467707 0.5182225 0.6573826 0.6755391 0.333909 0.5922223 0.7895867 0.1607033 0.4596391 0.8880764 -0.007225751 0.7613793 0.2650636 0.5916442 0.6766765 0.1457223 0.7217159 0.7459275 0.3292196 0.5789703 0.6873157 0.6590932 0.305276 0.344111 0.9389194 -0.0042423 0.7285835 0.2467918 0.6389522 0.2611839 0.9543986 0.1445901 0.2660969 0.9474036 0.1778172 0.5303927 0.7093008 0.4643017 0.6950469 0.2734687 0.6649246 0.6934548 0.2690451 0.6683826 0.5303921 0.7093014 0.4643014 0.6667519 0.2527706 0.7011056 0.265514 0.8662636 -0.4231902 0.09697586 0.8238956 -0.5583832 -0.07391184 0.7423495 -0.6659236 -0.5468373 0.2954072 -0.7833924 0.7071075 0 -0.7071061 0.7071071 0 -0.7071065 0.4096584 0.8150839 -0.4096564 0.4105514 0.8140231 -0.4108698 0.5209229 0.6764619 -0.5206137 0.5232887 0.6720031 -0.5240046 0.6091818 0.5085818 -0.6084753 0.6114826 0.501312 -0.612189 0.6711772 0.3162326 -0.6704612 0.6720027 0.3105002 -0.672311 0.703176 0.1074113 -0.702856 0.7031539 0.1056006 -0.7031522 0.346513 0.8716984 -0.346512 0.3465135 0.8716986 -0.3465114 0.2925519 0.9102368 -0.293057 -0.2678399 -0.9621656 0.04999279 -0.3982558 -0.912675 0.09174168 -0.4276668 -0.8978684 0.1045632 -0.2519304 -0.9662386 0.05398416 -0.3096126 -0.9474257 0.08077543 -0.3494175 -0.9321954 0.09444266 -0.4345346 -0.8933826 0.1142257 -0.280151 -0.9559341 0.08778226 -0.08963286 -0.9955469 0.02919584 -0.4012507 -0.9057256 0.1365985 -0.2556677 -0.9617177 0.09865641 -0.427843 -0.8886474 0.1650946 -0.08917099 -0.9953272 0.03704524 -0.08508962 -0.9956766 0.03725343 -0.2684402 -0.9561001 0.1175266 -0.3924307 -0.902892 0.1754549 -0.08595442 -0.9952327 0.04608476 -0.2418359 -0.9618641 0.1278001 -0.4102364 -0.8858371 0.2167922 -0.3791043 -0.899583 0.2168653 -0.2532933 -0.9559711 0.1481958 0 -0.001597702 -0.9999988 -0.09886491 0.001510381 -0.9950997 -0.2393283 -0.001431763 -0.9709377 -0.3225793 9.85645e-4 -0.946542 -0.4647574 -0.001201629 -0.8854373 -0.513181 6.6851e-4 -0.8582803 -0.6631585 -5.31175e-4 -0.7484788 -0.6801328 3.99355e-4 -0.7330888 -0.8275149 -7.27179e-5 -0.5614439 -0.8230035 -4.12378e-4 -0.5680362 -0.9705158 1.58771e-4 -0.2410378 -0.9349754 0.01068174 -0.3545518 -0.9927102 0 -0.1205261 0.7083307 -0.006050109 0.7058548 0.2152365 -0.5630365 0.7979118 -0.116904 -0.001859664 -0.9931415 -0.1411381 -0.126115 -0.9819242 -0.1023715 0.3830919 -0.91802 -0.02680301 0.5798056 -0.814314 -0.01268023 0.7776266 -0.6285986 -0.00903517 0.7349285 -0.6780844 6.76478e-4 0.8060946 -0.5917865 -0.001083076 0.8526382 -0.5225006 0.01510781 0.9102824 -0.413712 0.01390153 0.92379 -0.3826472 0.02031373 0.9433811 -0.3310884 0.01342141 0.9722836 -0.2334191 0.02135747 0.9899111 -0.1400707 0.01795202 0.9967567 -0.07844686 0.02255636 0.999266 -0.03096526 -0.00253874 0.02714651 -0.9996283 0.7002778 -0.2541831 -0.6670847 0.8518192 0.376347 -0.3643722 0.4903462 -0.1436392 -0.8596094 0.3366999 -0.1316734 -0.9323601 0.2727416 -0.3670957 -0.889299 -0.1718104 -0.1699352 -0.9703624 0.880852 -0.2154452 -0.421525 0.5265473 -0.3589505 -0.7706508 0.4399925 -0.2661986 -0.8576392 0.831632 -0.169717 -0.5287573 0.6470477 -0.2984358 -0.7016164 0.6459695 -0.293848 -0.7045401 -0.9997085 0.009312331 0.02228057 0.8435385 0.4415805 -0.3056949 0.8523254 0.4236877 -0.3066433 0.8454534 0.3922232 -0.3624497 0.9999922 -0.00153613 0.003636598 1 -4.40956e-5 2.50424e-4 1 3.81855e-5 -2.15945e-4 0.9999846 -8.01703e-5 0.005550563 0.9999982 -0.001665532 0.001028537 0.9999847 -0.001161873 -0.005423545 1 1.33553e-7 0 1 -1.7308e-7 0 -0.9999848 0.001047372 -0.005425035 -0.9999829 4.0838e-4 -0.005849599 -0.9515623 -0.2171742 0.2176341 -0.9713482 -0.1540328 -0.1809878 -0.1102127 -0.3669086 -0.9237052 -0.110212 -0.3774144 -0.9194628 -0.2887054 -0.9407582 -0.1778299 -0.2737306 -0.9393494 -0.2066264 -0.2643916 -0.9237189 -0.2772013 -0.2641182 -0.9020748 -0.3413252 -0.2502977 -0.8845947 -0.3935015 -0.2439798 -0.8332548 -0.4961456 -0.2302222 -0.8122005 -0.5360301 -0.2164828 -0.7395884 -0.6372945 -0.2044018 -0.7190129 -0.6642593 -0.1861287 -0.6226618 -0.7600318 -0.1848658 -0.6344809 -0.7505056 -0.194454 -0.6345547 -0.748016 -0.1570996 -0.5516017 -0.8191798 -0.1586355 -0.6123098 -0.7745395 -0.190328 -0.6460444 -0.7391901 -0.1475515 -0.4868354 -0.8609414 -0.1367073 -0.4775584 -0.8678992 -0.1008981 -0.3363657 -0.9363107 -0.1080862 -0.3424044 -0.9333149 -0.008674979 -0.201533 -0.9794433 -0.05391848 -0.2044529 -0.9773904 -0.06813019 -0.1746635 -0.9822683 -0.003753602 0 -0.999993 -0.003177762 1.88114e-4 -0.9999949 -0.924865 0.0145747 -0.3800164 -0.840346 -0.009421348 -0.5419687 -0.4192137 0.008547782 -0.9078475 -0.3581739 1.38414e-4 -0.9336549 -5.61768e-4 -0.9999996 8.61526e-4 -0.05785393 -0.9983251 2.03282e-4 0.01407217 -0.9998986 -0.002243757 0.006702721 -0.9999766 -0.001414 -0.1145749 -0.9928461 0.03360468 0.01814156 -0.9998317 -0.002762138 -1 2.4553e-6 9.37157e-6 -1 3.471e-6 6.26154e-6 -1 3.7072e-6 4.56118e-6 -0.9999936 1.87408e-4 0.003590404 -0.9999987 0.001240789 0.001069128 -0.9999988 0.001306474 7.77942e-4 -0.9999991 0.001323223 5.06233e-4 -0.9999728 -4.82474e-4 -0.007373869 -0.9999992 0.001300036 2.45736e-4 -1 -1.84774e-4 -1.34456e-5 -0.9999991 -5.24427e-4 0.0012331 -0.9820407 -0.05352365 -0.1809182 -0.9995699 -0.01029503 -0.02745991 -0.9998227 -0.002960801 0.01859796 -1 -3.72739e-4 -1.38769e-4 -1 -1.77812e-4 -1.78148e-6 -0.268144 -0.9182851 -0.2912929 -0.3769391 -0.9068272 -0.1886302 -0.2701635 -0.9432855 -0.192936 -0.2694007 -0.9578105 -0.1001126 -0.3814453 -0.9167324 -0.1187486 -0.3789718 -0.9229676 -0.06716555 -0.3788593 -0.9039307 -0.1984311 -0.4489918 -0.8880225 -0.09910857 -0.3817814 -0.9164614 -0.1197565 -0.4380425 -0.8985005 -0.02856105 -0.3745914 -0.926162 -0.04364895 -0.02661353 -0.004262447 -0.9996367 0.04035472 0.04176372 -0.9983123 0.01030802 -0.005361795 -0.9999326 -0.8478515 0.4617443 -0.2606533 -0.1318634 0.8672449 -0.4801025 -0.2381291 0.7980723 -0.5535117 -0.9999969 0.002278864 0.001057028 -0.9999166 0.008903384 0.009352862 -0.9999995 6.26034e-4 8.82795e-4 -0.9999924 0.003165483 0.002286016 -0.9999995 1.41934e-5 0.001077771 -0.9999748 0.003959 0.005900263 -0.9999958 0.00228101 0.001818239 -0.9995821 0.02850633 0.004820764 -0.9999895 -0.003032743 0.003450095 -0.9999885 -0.004141032 0.002423942 -0.9999749 -0.00464183 -0.005358994 -0.9999969 0.001284539 -0.002148747 -0.9999857 7.17588e-5 -0.00536549 -0.9999889 0.001848459 -0.004346787 -0.9998855 -0.0143578 0.004785716 -0.9995179 0.01269304 0.02833378 -0.9996761 -0.02527791 0.002978086 -0.9994114 0.01254117 0.03193277 -0.2049688 -0.896389 -0.3930326 -0.1773713 -0.8467383 -0.5015712 -0.1210752 -0.8553029 -0.5037833 -0.1893836 -0.823015 -0.5355187 -0.08551704 -0.818138 -0.5686273 -0.1608434 -0.7333628 -0.6605365 -0.15808 -0.7313078 -0.6634755 -0.1088457 -0.7426179 -0.6608111 -0.06638288 -0.6762052 -0.7337166 -0.1413075 -0.6168398 -0.7743003 -0.09200024 -0.6003286 -0.7944443 -0.1260766 -0.6019378 -0.7885276 -0.03267478 -0.5030416 -0.8636445 0.01233673 -0.4837051 -0.8751442 -0.08330184 -0.5792713 -0.8108673 0.004136621 -0.3080316 -0.9513671 -0.05414754 -0.3484262 -0.9357709 -0.03686916 -0.1281383 -0.9910708 -0.1125457 -0.8871731 -0.4475013 -0.1599214 -0.8984308 -0.4089589 -0.2550567 -0.8911059 -0.375335 -0.1993896 -0.9065436 -0.3720518 -0.3353774 -0.900687 -0.2761976 -0.151363 -0.9177034 -0.3673008 -0.1897391 -0.9227646 -0.3354171 -0.2407427 -0.9162504 -0.3202002 -0.3324269 -0.9079114 -0.2553218 -0.4054808 -0.8943605 -0.1889564 -0.3016276 -0.9156136 -0.2658432 -0.2854925 -0.9334266 -0.2172763 0.001473486 -0.9999989 0 0.005607068 -0.9999683 0.005659341 0.0150122 -0.999831 0.0106157 0.09285223 -0.9952319 0.02986824 -0.01021814 -0.9861576 -0.1654961 -0.001252889 0.004385948 -0.9999896 -1 -3.07588e-4 -2.61775e-4 -1 1.82076e-4 -1.48305e-4 -0.9999998 7.82143e-4 1.38939e-4 -0.9999911 -0.002938926 -0.00305736 -0.919341 0.2809095 -0.2755032 -0.6221987 0.5905657 -0.5139076 -0.756809 0.5196202 -0.3965287 -0.7566589 0.5420821 -0.3655331 -0.690002 0.563445 -0.4543424 -0.6915109 0.646816 -0.3216236 -0.592689 0.682546 -0.4276105 -0.6344888 0.7677957 -0.08895921 -0.6615512 0.7496544 0.01919561 -0.4701437 0.863682 -0.18171 -0.4673519 0.864352 -0.1856825 -0.2423684 0.9696425 -0.03241991 -0.2656977 0.9622778 0.05853426 -0.9989492 -0.02723044 -0.03686493 -0.9539238 0.299892 -0.009709715 -0.9998636 0.01640158 -0.002003967 -0.6887392 0.6979256 -0.1963115 -0.6244903 0.7433002 -0.2398265 -0.6851564 0.7212867 -0.1015195 -0.5584479 0.8267541 -0.06792527 -0.1061056 0.9943397 0.005492329 -0.3220087 0.9467312 -0.003268539 -0.5527118 0.821884 -0.1379006 -0.4947187 0.8673378 -0.05457812 -0.9999946 0.001167833 -0.003091156 -0.9999359 0.01132225 4.71741e-4 -1 -7.94338e-5 2.14296e-4 -1 -2.04081e-4 1.31795e-4 0 1 0 0 1 0 0.001496374 0.9999989 1.30483e-4 0.02107715 0.9997777 6.08222e-4 -0.9093911 0.3380467 -0.2423477 -0.2822736 0.8794949 -0.3831586 -0.8813602 0.4281744 -0.1996769 -0.216539 0.9147156 -0.3411837 -0.8915888 0.424292 -0.1582587 -0.8936868 0.4196648 -0.1587622 -0.8327754 0.5508205 -0.05551427 -0.2426601 0.914548 -0.323602 -0.09216773 0.9737858 -0.2079577 -0.7833909 0.6076484 -0.1306221 -0.1685231 0.97171 -0.1654686 -0.01020032 0.9999002 -0.009778916 -0.9997458 0.02213084 -0.004313528 -0.9996268 0.02649706 -0.006659209 -0.998517 -0.008014261 -0.05384755 -0.9999911 -0.001081705 -0.00407958 -0.9999971 4.84433e-4 -0.002406001 -0.9999889 0.001256763 0.004557549 -0.9977688 0.03906857 0.05414134 -0.9996494 0.02639657 -0.002122759 -0.4188753 0.8940788 -0.1586395 0.006332933 -0.05714911 -0.9983456 -0.9267018 0.2310745 -0.2963589 -0.9033287 0.240117 -0.3554452 -0.9207648 0.2057509 -0.3314496 -0.4789333 0.4942929 -0.7254635 -0.5234429 0.4641446 -0.7145469 -0.3489233 0.4490349 -0.8225693 -0.9256725 0.1601115 -0.3427753 -0.4704908 0.310767 -0.8258707 -0.4432406 0.3249691 -0.8354238 -0.9004537 0.1531818 -0.4070854 -0.9173166 0.1272207 -0.3772867 -0.356484 0.2324959 -0.9049115 -0.9265884 0.08252972 -0.3669099 -0.2781873 0.1961504 -0.9402856 -0.4348198 0.127923 -0.8913851 -0.9397397 0.1050327 -0.3253574 0.002019226 0.9766474 -0.2148395 0.00341916 0.9261009 -0.3772609 0.002323269 0.1679984 -0.9857845 -0.9980025 0.05698579 -0.02726864 -0.9865032 -0.07302439 -0.1465567 -0.999157 0.006472051 0.04053902 -1 8.35988e-7 0 -1 4.29562e-7 0 -0.9999999 1.42017e-5 5.53611e-4 -1 6.204e-5 -2.3457e-5 -1 3.27814e-5 -2.61019e-4 -1 -1.84652e-4 -1.70201e-6 -0.9999247 0.001418232 0.01219159 -0.9999998 3.43512e-5 6.25155e-4 3.5936e-4 0.9999997 -8.50457e-4 -7.40406e-4 -0.9999868 0.005084753 -0.006421625 -0.999781 -0.01991832 -0.0062626 -0.9996674 0.02502143 -4.43714e-4 -0.9999997 7.56921e-4 0.06325995 0.9530309 -0.2961934 1.25687e-4 -1 -1.33376e-4 5.63398e-5 -0.9999976 -0.002221465 0 -1 0 0 -1 0 0 -1 0 -7.14057e-4 0.9999998 0 -6.58427e-4 0.9999998 2.28456e-4 0.9999979 -0.002053201 -2.09145e-4 1 -2.08662e-6 0 1 1.1923e-5 -4.75464e-5 1 2.06879e-5 -4.63189e-5 1 2.83237e-5 -4.43978e-5 1 3.43781e-5 -4.16779e-5 1 4.43815e-5 -3.80006e-5 0.9999709 -0.006778717 -0.003507316 0.9999767 0.005830824 -0.003573298 0.9999594 0.008340716 -0.00345385 0.9999153 0.01266342 -0.003040134 0.9997536 0.02213245 -0.001742243 0.9994719 0.03249943 0 -0.003580212 0.01693403 -0.9998503 0.004159033 0.07844877 -0.9969095 -0.00170207 0.1420554 -0.9898573 0.003893315 0.2488425 -0.9685362 5.62959e-4 0.2334299 -0.9723735 -4.43083e-4 0.3625256 -0.9319737 0.003127932 0.3826562 -0.9238855 -0.002499163 0.4791488 -0.8777301 0.004077374 0.5224629 -0.8526523 -0.002746105 0.5885288 -0.8084717 0.009340643 0.6493924 -0.7603963 8.39495e-4 0.7543671 -0.6564523 0.002449274 0.7603818 -0.6494718 -0.001861274 0.8291113 -0.5590806 0.003916323 0.8526196 -0.5225175 -0.002659559 0.8927369 -0.4505707 0.003834605 0.9238658 -0.3826974 -0.006707966 0.9526135 -0.3041092 0.00412631 0.972359 -0.2334549 -0.004819989 0.9951824 -0.0979225 -6.43227e-4 0.996917 -0.07846164 0.7960914 0.05508351 -0.6026644 -0.003608047 0.004158914 -0.9999849 0.8287035 0.005043327 -0.5596652 1 0 -2.10932e-4 0 -1 0 -2.75147e-4 -1 2.19419e-4 -2.51305e-4 -1 1.21024e-4 -2.32415e-4 -1 5.30488e-5 -2.15541e-4 -1 0 -1.99076e-4 -1 -4.54391e-5 -1.76186e-4 -1 -1.01368e-4 -0.002018272 -0.9999904 0.003917336 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 4.31231e-4 0.9999994 -0.001103878 -0.07286357 0.9819766 -0.174393 0.09330511 0.9900184 0.1056305 -7.14978e-6 1 -1.71598e-5 -0.005053281 -0.001902341 -0.9999855 -3.0353e-4 0.002226948 -0.9999976 0.003479897 0.02061891 -0.9997814 -4.1924e-5 -0.005414128 -0.9999854 -0.001603662 0.2653653 -0.9641466 -0.002326369 0.6270264 -0.7789947 -3.30502e-4 0.8686488 -0.4954283 0.002951383 0.9821726 -0.1879587 0.01462584 -0.858115 -0.5132493 0.009435951 -0.3456978 -0.9382985 -0.008150696 0.2374205 -0.9713729 0.01098859 0.928408 -0.3713999 0.0137149 0.7779062 -0.6282308 0.9369826 -0.01281577 -0.3491408 0.9405003 -0.01829624 -0.3393001 0.3653695 0.01784718 -0.9306915 0.4224374 -0.009571671 -0.9063416 0.336315 0.1219647 -0.9338185 0.9430256 0.1321551 -0.3053489 0.9098356 0.06163299 -0.4103666 0.405523 0.2063769 -0.890483 0.9031061 0.2048665 -0.3773981 0.3568853 0.3739794 -0.8560212 0.5325916 0.5304426 -0.6595278 0.4165644 0.828377 -0.3745209 0.4164859 0.828327 -0.3747187 -0.9999765 0.004486918 -0.005196928 -1.08337e-5 0.9999998 8.26257e-4 -0.003672838 0.9999915 -0.001937747 0.04137194 0.9989054 0.02182757 -0.005012035 0.9999724 0.00551325 0.279649 0.8268695 -0.4879378 0.046036 0.9904432 -0.1300119 -0.007558941 0.9999521 0.006216526 0.364331 0.8298283 -0.4226678 0.7074095 -6.98707e-4 0.7068036 1 1.37355e-7 0 0.8558652 0.4400526 -0.2717511 0.8356484 0.4838561 -0.2599521 0.8914898 0.4130164 -0.186182 0.8625032 0.4843688 -0.1465446 0.8659469 0.4789409 -0.1440542 0.8894212 0.4488893 -0.08618885 0.9688904 0.2464345 -0.02283304 0.018386 0.974377 -0.2241683 -6.72768e-4 0.007193684 -0.9999739 0.1884723 0.9642542 -0.1862586 0.3229725 0.8809741 -0.3457939 0.7049357 -6.64896e-4 0.7092709 -0.908913 0.01398503 -0.4167514 -0.8437783 -0.03306895 -0.5356723 -0.4072045 -0.02035832 -0.9131101 -0.2515867 -0.06225973 -0.9658302 -0.7649502 0.5974295 -0.240685 -0.7288851 0.5546277 -0.4013909 -0.64508 0.5945251 -0.4800124 -0.5304828 0.6080412 -0.5906555 -0.3042625 0.6476627 -0.6985396 -0.3062797 0.4931384 -0.8142527 -0.008366346 0.7124717 -0.7016509 0.9928977 0.05152982 -0.1072329 0.9985327 0.004922807 -0.05392879 0.948361 0.004379987 -0.317163 0.9999083 -0.01321697 0.002993822 0.9997985 0.0191459 -0.006029903 1 3.53775e-4 -1.09141e-4 0.9999999 -4.81745e-4 1.90219e-4 1 -1.59972e-6 -2.49136e-7 1 -4.14841e-6 0 0.9999588 0.007681846 -0.004833638 0.9999839 -0.003909945 0.004124104 -0.3255857 0.9092779 -0.2592448 -0.1336529 0.9147942 -0.3811675 0.359624 0.5876311 -0.7248175 -0.2118139 0.1687 -0.9626398 -0.2590512 0.194341 -0.9461101 -0.7488935 0.08450263 -0.6572806 -0.8339812 0.1485991 -0.5314072 0.927399 -0.3737809 -0.01480239 0.9298827 -0.3676535 -0.01221442 0.619563 -0.7844023 0.0292387 0.5544282 -0.8321262 0.01324939 0.3554904 -0.9331609 0.05326741 -0.06802839 -0.9976542 0.007637262 -0.1239227 -0.9919637 0.02551847 0.9902527 -0.0966559 0.1002869 0.9195506 -0.2222741 0.3240694 0.9503159 -0.2368006 0.2020526 0.9611477 -0.2175061 0.1699591 0.5934503 -0.6296308 0.50138 -0.2910826 -0.795597 0.5313157 0.560897 -0.6416718 0.5231176 0.1312969 -0.8026034 0.5818841 0.08355575 -0.8017702 0.5917628 0.9401589 -0.2953581 0.1698967 0.9463987 -0.2951787 0.1311457 0.9562072 -0.2717004 0.1088433 0.4956529 -0.7937101 0.3526366 -0.1879935 -0.9060434 0.3791356 -0.1217802 -0.9296506 0.3477349 0.5404254 -0.7761765 0.3247932 0.9413361 -0.3277946 0.08023113 0.9286494 -0.365149 0.06539589 0.961643 -0.2735056 0.02092009 0.507673 -0.8523334 0.1256826 -0.1156812 -0.9704195 0.2119055 0.5530733 -0.8265057 0.1048734 -0.1980081 -0.9683348 0.1520547 -0.06289684 -0.9965847 0.05350768 -0.2745485 -0.9611018 0.03011047 -0.3367016 -0.7377874 0.5850656 -0.3022667 -0.7344393 0.6076462 -0.3970602 -0.7189812 0.5704467 -0.2626711 -0.6725482 0.6918691 -0.4060206 -0.7579737 0.5105128 -0.4200506 -0.8499844 0.3179374 -0.3257352 -0.8443655 0.4253745 -0.383799 -0.8129539 0.4379547 -0.3632602 -0.9102383 0.198767 -0.2801457 -0.9154125 0.2890301 -0.3581888 -0.9128196 0.1961153 -0.3138513 -0.9461466 0.07939928 -0.3856433 -0.9094269 0.1556345 -0.3279863 -0.9446426 -0.008694589 -0.427953 -0.9033969 0.02702939 -0.2539839 -0.9609709 -0.109668 0.9937127 0.1119608 -1.26434e-7 0.9426114 0.3338918 1.18998e-5 0.8467497 0.5319916 -3.61206e-7 0.7070948 0.7071188 -5.93583e-6 0.5373346 0.8433692 7.16338e-6 0.3546353 0.9350048 -2.16994e-4 -0.9254779 -0.1788794 -0.3339054 -0.8985208 -0.09204894 -0.4291705 -0.9743472 0.04967176 -0.2194998 0.002589523 0.7814381 -0.6239776 0.001488924 0.7070907 -0.7071213 0.002418816 0.4763811 -0.8792357 1 -6.98387e-6 0 -7.97776e-4 -0.999953 -0.009672939 -0.002029955 -0.9999897 0.004080832 -0.03005772 -0.9965494 0.07736903 -0.003503561 -0.9995632 -0.02934688 -0.02316039 -0.9993519 -0.02755749 1 -7.54539e-5 3.83553e-5 1 1.95094e-6 0 1 -2.45063e-6 0 1 -8.57932e-7 0 1 2.25101e-4 -5.17223e-5 1 -2.05414e-4 3.16624e-5 1 2.65882e-6 0 1 -1.72558e-6 0 1 3.78805e-6 0 1 1.0671e-6 0 0.9999998 8.27771e-4 -7.31935e-5 1 -4.35883e-5 -1.89105e-6 0.9999979 -0.002070128 1.34167e-4 1 6.83156e-5 -1.43043e-7 0.1415971 0.9899244 2.81365e-5 0.1085429 0.9940918 -3.38015e-5 0.2140609 0.9768198 0.001014351 0.5328855 0.8461874 4.48019e-5 0.7072293 0.7069843 -7.50871e-6 0.8463197 0.5326755 6.46216e-6 0.9443244 0.3290158 -3.28754e-5 0.993865 0.1106007 -1.1726e-5 0.1760877 -0.9063529 -0.3840803 0.09975576 -0.9386106 -0.3302407 0.1526376 -0.9216807 -0.3566601 0.1807117 -0.9037523 -0.38804 0.2034283 -0.8985968 -0.3887683 0.1517844 -0.9223296 -0.3553445 0.2045128 -0.8979811 -0.389621 0.1649219 -0.9223594 -0.3493623 0.2273359 -0.8935042 -0.3872578 0.2255572 -0.8945084 -0.3859778 0.2231776 -0.8960372 -0.3838087 0.2207193 -0.8979066 -0.3808501 0.2123157 -0.9059875 -0.3662087 0.2285431 -0.9219208 -0.3127782 0.2369599 -0.9159456 -0.3238729 0.1874396 -0.9391138 -0.2879788 0.2739867 -0.9338153 -0.2300445 0.2413733 -0.9499744 -0.1982114 0.2129999 -0.9592269 -0.185782 0.3897479 -0.8952633 -0.2158708 0.2372152 -0.899676 -0.3664863 0.1294394 -0.9553148 -0.2657429 0.2702637 -0.91424 -0.3018655 0.2598927 -0.9169959 -0.3026125 0.2548688 -0.9439575 -0.2097288 0.2616177 -0.9163236 -0.3031622 -0.2802768 -0.9591352 -0.03879255 -0.1052476 -0.9894365 -0.09969222 -0.03191983 -0.9734483 -0.2266705 -0.02945131 -0.9637354 -0.2652298 4.13872e-4 -0.9551025 -0.2962756 -0.04267185 -0.9766634 -0.2104943 0.1775664 -0.9051184 -0.3863043 0.1196913 -0.927413 -0.3543718 -0.1617613 -0.975425 -0.1495974 -0.281467 -0.9587406 -0.03991204 -0.3051204 -0.9314032 -0.1984683 -0.2764685 -0.943381 -0.1832969 -0.2720334 -0.9455534 -0.1786801 0.5017039 -0.8382288 -0.2136954 0.1614738 -0.9473162 -0.2766194 -0.123639 -0.9910038 -0.05123317 0.02714645 -0.9987475 -0.04203009 0.3227751 -0.9163478 -0.2369031 0.3590193 -0.9024697 -0.2380201 0.3594515 -0.9318961 -0.04862475 0.3544587 -0.9338448 -0.047885 0.7632202 -0.6257334 -0.1610989 0.6172836 -0.7851406 -0.05015242 0.7631555 -0.6258116 -0.161101 0.7628613 -0.6460998 -0.02445119 0.9400089 -0.3270505 -0.09706383 0.9458875 -0.3238125 -0.02103495 0.9867432 -0.1582716 -0.03588891 0.9274069 -0.3737763 -0.0144149 0.9999996 -9.17838e-4 -2.27767e-4 1 -4.28147e-4 -1.50951e-4 0.331036 -0.8797073 -0.3413654 0.3289586 -0.8802478 -0.3419799 0.3250807 -0.8809494 -0.343876 0.394799 -0.8588338 -0.3264019 0.7653114 -0.5993843 -0.2345997 0.7943932 -0.5678073 -0.215718 0.9870088 -0.1490936 -0.05987393 0.9900225 -0.1313964 -0.05089843 0.9906854 -0.1272195 -0.04855513 0.9999996 -9.87542e-4 -2.79771e-4 0.1294597 -0.6409711 -0.7565689 0.1100846 -0.8002188 -0.5895178 0.1579405 -0.6826351 -0.7134873 0.1673113 -0.7614156 -0.6263013 0.1915856 -0.7975618 -0.5720055 0.1797449 -0.7140406 -0.6766372 0.2087545 -0.7859613 -0.5819678 0.2087785 -0.7836321 -0.5850917 0.2189413 -0.8235958 -0.5232158 0.2829174 -0.7827305 -0.5543383 0.2532968 -0.8631847 -0.4367528 0.2529317 -0.8737236 -0.4154908 0.2547158 -0.9441244 -0.2091628 0.9410039 -0.3218023 -0.1046664 0.9371364 -0.3334425 -0.102916 0.9219451 -0.3727718 -0.1051592 0.9376876 -0.3328194 -0.0998665 0.5865759 -0.7795065 -0.219769 0.6552885 -0.7211241 -0.2248937 0.6751486 -0.702938 -0.2237244 0.4822707 -0.842445 -0.2402119 0.9468972 -0.311807 -0.07850086 0.5543984 -0.8077327 -0.2005255 0.9431468 -0.3247797 -0.07065665 0.9445284 -0.3207141 -0.07077223 0.9250382 -0.3721839 -0.07605046 0.6514732 -0.7442591 -0.1471771 0.6790699 -0.7182093 -0.1517875 0.6141547 -0.7746479 -0.1507805 -0.6515077 -0.5922797 -0.4740701 0.2983582 -0.7588099 -0.5789559 0.4743295 -0.6923699 -0.5437237 0.4932813 -0.7235894 -0.4827961 0.6180689 -0.6309403 -0.4689405 0.6272727 -0.6254295 -0.4640764 0.7773426 -0.5031926 -0.3775391 0.7745686 -0.6067619 -0.1785598 0.8311404 -0.4504856 -0.3259884 0.9231412 -0.3639666 -0.1238499 0.8511587 -0.4265249 -0.3059502 0.969431 -0.199123 -0.1433655 0.9708631 -0.2302814 -0.06629961 0.9781036 -0.1713885 -0.1180644 0.2213925 -0.6612526 -0.7167499 0.1979601 -0.6884124 -0.6977823 0.3015044 -0.6507887 -0.696828 0.3922005 -0.8019897 -0.4505456 0.2343123 -0.8909326 -0.3890205 0.6222372 -0.5655772 -0.5412424 0.2120811 -0.9425153 -0.2582378 0.6318533 -0.5640163 -0.5316457 0.6980609 -0.5647023 -0.4402526 0.590187 -0.7511847 -0.2956365 0.8333127 -0.4261968 -0.3520601 0.8532586 -0.4038364 -0.3299489 0.6121371 -0.7613176 -0.2137373 0.9731557 -0.2195509 -0.06903213 0.04483354 -0.9568561 -0.2870826 0.1242132 -0.7776114 -0.6163535 0.05319547 -0.9818876 -0.1818436 0.1450359 -0.8415976 -0.5202675 0.04814887 -0.9834967 -0.1744017 0.3857413 -0.8689323 -0.3100977 0.4760893 -0.8328139 -0.2824183 0.7946657 -0.5658835 -0.2197324 0.9397612 -0.3314501 -0.08360534 0.9904782 -0.1295601 -0.04655432 0.9907284 -0.1274753 -0.04698431 1 -7.63032e-7 -4.63851e-7 1 -8.55687e-6 -4.98491e-7 1 1.34337e-5 -5.12035e-7 1 -8.08992e-6 -5.13496e-7 1 -1.03492e-5 -5.14218e-7 1 1.38018e-5 -5.14443e-7 1 -1.61781e-5 -5.14375e-7 1 5.23183e-6 -5.14167e-7 1 1.16989e-6 -5.13937e-7 1 -1.88309e-5 -5.13782e-7 0.2570858 -0.9147795 -0.3115853 7.75979e-6 1 1.09455e-5 -1.85183e-4 1 9.8128e-5 0 1 7.09662e-7 0 1 -2.98879e-7 0 1 -1.00155e-6 2.61636e-5 1 0 -1 5.34251e-7 0 -1 1.14108e-6 0 -1 -1.48358e-6 0 -0.9953162 0.09667277 3.32156e-4 -0.9938519 0.1107189 -8.74835e-6 -0.9564408 0.2919265 -2.64973e-4 -0.9442882 0.3291193 4.82949e-4 -0.8753363 0.4835146 -4.41924e-4 -0.8461895 0.532882 5.55476e-4 -0.749931 0.661516 -5.46582e-4 -0.7070015 0.7072119 5.18649e-4 -0.5326669 0.8463245 -9.26646e-4 -0.5787569 0.8154997 7.57585e-4 -0.3676887 0.9299489 -5.17529e-4 -0.1229472 0.9924028 0.004548311 -0.2225453 0.9749224 0 -0.6145356 0.6681406 0.4194452 -0.6699659 0.5685433 0.4773932 -0.6955999 0.5392723 0.4746854 -0.726719 0.4522794 0.5170328 -0.7579405 0.3955738 0.5186979 -0.7692406 0.3343254 0.544514 -0.7994202 0.218225 0.5597367 -0.7989186 0.2414311 0.5508541 -0.814423 0.1072092 0.5702821 -0.8201908 0.08089411 0.5663421 -0.8172328 -0.002174139 0.5763037 -0.8202547 -0.08187979 0.5661076 -0.8137095 -0.111968 0.5703859 -0.8041676 -0.2206366 0.5519366 -0.7951281 -0.2425445 0.555827 -0.7677845 -0.339664 0.5432635 -0.7576175 -0.3967864 0.5182434 -0.7246111 -0.4570474 0.5157971 -0.6953606 -0.5403892 0.4737648 -0.6676818 -0.5720394 0.4764159 -0.614748 -0.6684996 0.4185611 -0.0668801 0.9965814 0.04850238 -0.2002549 0.9693779 0.1421428 -0.3273844 0.9157119 0.233005 -0.4010217 0.873254 0.2767834 -0.4474981 0.8370589 0.3147663 -0.4963673 0.7955765 0.347387 -0.5841711 0.7003335 0.4102159 -0.5565637 0.7355448 0.3862782 -0.5970784 0.6872137 0.4138053 -0.6456247 0.6139581 0.4541193 -0.6946043 0.5318456 0.4844226 -0.719582 0.4756093 0.5059621 -0.7552493 0.3899239 0.5268376 -0.5735784 8.76742e-7 -0.8191507 -0.596748 0.02602171 -0.8020067 -0.5698591 -0.0140872 -0.8216217 -0.5698394 0.01636141 -0.8215933 -0.5735771 0 -0.8191516 -0.5735771 5.23585e-7 -0.8191517 -0.5735672 -5.67146e-6 -0.8191586 -0.5735774 3.77233e-6 -0.8191514 -0.57358 -5.24715e-7 -0.8191497 -0.5735659 -4.41491e-6 -0.8191596 -0.5735852 -2.43034e-6 -0.819146 -0.5735686 1.42376e-6 -0.8191576 -0.5735719 5.24574e-6 -0.8191552 -0.5735785 -4.78774e-7 -0.8191507 -0.5735708 -2.1479e-6 -0.819156 -0.5735775 -2.06499e-6 -0.8191514 -0.5735899 1.08269e-5 -0.8191427 -0.5735756 0 -0.8191527 -0.5735734 -1.65242e-6 -0.8191542 -0.5735774 1.5844e-7 -0.8191514 -0.573563 0 -0.8191615 -0.5735871 -1.04712e-6 -0.8191447 -0.5735957 -1.05184e-6 -0.8191387 -0.5735523 -2.32144e-7 -0.8191689 -0.4673458 -5.29141e-5 -0.8840747 -0.4673458 -5.29492e-5 -0.8840747 -0.4673458 -5.29248e-5 -0.8840747 -0.4782204 -4.52959e-6 -0.8782399 -0.5784782 -4.11403e-6 -0.8156979 -0.5784758 -4.05922e-6 -0.8156995 -0.573583 -5.92388e-7 -0.8191475 -0.5735934 1.14611e-6 -0.8191401 -0.5735886 1.04006e-6 -0.8191435 0.5451903 -0.001592993 0.838311 0.5814579 0.005036711 0.8135609 0.5735809 -4.22789e-6 0.8191491 0.5735707 -7.15342e-7 0.8191562 0.573575 -3.53788e-7 0.8191532 0.5735769 2.4586e-7 0.8191518 0.5730837 -6.01709e-4 0.8194968 0.576574 -6.03849e-4 0.8170447 0.5735765 -3.83947e-7 0.8191521 0.5735775 0 0.8191514 0.5735677 4.05024e-6 0.8191582 0.5735793 0 0.81915 0.5735747 0 0.8191533 0.5735728 -1.91475e-7 0.8191547 0.5735787 9.57364e-7 0.8191505 0.5640264 0.006244063 0.8257333 0.5721818 -0.001323938 0.8201258 0.5735749 7.65882e-7 0.8191531 0.5750188 -0.001310944 0.8181392 0.5745356 -0.001262247 0.8184786 0.5689357 -0.001260995 0.8223811 0.5756536 -0.001978397 0.8176913 0.5202558 -0.001649141 0.854009 -0.3737808 -0.8890925 0.2642018 -0.3830875 -0.8839068 0.2682403 -0.4659548 -0.8231451 0.3245278 -0.48598 -0.8035161 0.343781 -0.5489001 -0.7437035 0.3815938 -0.5791238 -0.7048527 0.409632 -0.6157022 -0.6607896 0.4292646 -0.65792 -0.5901657 0.4678095 -0.69672 -0.527899 0.4856994 -0.7249998 -0.4620863 0.5107363 -0.7377006 -0.4362507 0.5152506 -0.7706735 -0.3363095 0.5412563 -0.7731431 -0.3299044 0.5416761 -0.7964227 -0.2378594 0.5559983 -0.8117133 -0.1416938 0.5666079 -0.8013283 -0.1987025 0.564261 -0.8151633 -0.08812069 0.572489 -0.8136717 -0.09843355 0.5729305 0 -1 0 -8.20801e-6 -1 -1.41044e-4 6.22223e-4 -0.9999976 0.002142488 -5.3329e-4 -0.9999995 -8.69812e-4 -4.23781e-4 -0.9999998 -6.60052e-4 1.02974e-4 -1 1.2552e-4 0 -1 1.25367e-6 0 -1 0 0 -1 0 0 -1 6.58043e-7 2.4876e-5 -1 -2.1379e-5 5.7119e-6 -1 4.06404e-5 5.82966e-4 -0.9999997 4.64723e-4 8.29458e-5 -1 -1.86727e-4 -0.9958125 -0.09141987 -4.17653e-6 -0.9916259 -0.1291418 7.52289e-4 -0.9611123 -0.2761576 -4.79903e-4 -0.9242274 -0.3818414 9.40583e-4 -0.8923055 -0.4514318 -2.88279e-4 -0.7930085 -0.6092107 4.36165e-4 -0.7969281 -0.6040741 5.92197e-4 -0.6828801 -0.7305305 -3.0857e-4 -0.6089604 -0.7932002 8.8924e-4 -0.5533295 -0.8329625 -1.51997e-4 -0.3864821 -0.922297 2.46224e-4 -0.4080954 -0.9129389 8.44022e-4 -0.2498838 -0.9682758 -4.79412e-4 -0.08251857 -0.996589 0.001163482 -0.1263754 -0.9919826 0 -0.07920688 -0.9957805 0.04634213 -0.08133816 -0.9951571 0.0551964 -0.2231199 -0.961896 0.1580313 -0.3785265 -0.8859114 0.2681024 -0.2323501 -0.9560111 0.1790422 -0.07235914 -0.9958189 0.05575758 -0.07481259 -0.995135 0.06410485 -0.9113505 3.7258e-4 0.4116311 -0.6326649 0.006780564 0.7743961 -0.4284642 -0.001967251 0.9035567 -0.177915 0.002121746 0.9840435 0.1312291 -0.006550073 0.9913305 0.3513884 0.001372754 0.9362289 -0.03705424 -0.009188771 0.999271 -0.02604758 -0.01111447 0.9995989 -0.4297068 0.04045569 -0.9020619 -0.1441454 0.1977762 -0.969591 -0.6375281 -0.06058651 -0.7680412 -0.407925 0.05693882 -0.9112383 -0.5887272 -0.02189135 -0.8080353 -9.38921e-4 -0.9999993 -7.46211e-4 3.74548e-5 -1 -2.06066e-4 1.49649e-4 -1 -1.82447e-4 4.65845e-5 -1 -1.78874e-4 -0.8191178 0 0.5736254 -0.8191519 6.70926e-5 0.5735766 -0.8189911 0.01982569 0.5734637 -0.8174414 0.01111662 0.5759046 0.1308051 -0.1086903 0.9854321 -0.4283635 -0.006014406 0.9035865 -1 2.35072e-6 0 -1 -1.94983e-6 0 -1 -3.31192e-7 0 -1 9.72851e-7 0 -1 1.16886e-6 0 -1 -2.28419e-7 0 -1 2.35815e-6 0 -1 -2.02953e-6 0 0 0.9965911 -0.08250045 0.06911551 0.9804314 -0.1843297 0.02892476 0.9690525 -0.2451544 0.0317645 0.9154687 -0.4011336 0.0799272 0.8824906 -0.4634892 0.008345842 0.8374333 -0.546476 0.370607 0.8964493 -0.2429594 -1.88177e-4 0.9827821 -0.1847681 0.8780164 0.3767946 -0.2951492 -0.9946448 1.84568e-5 -0.1033527 -0.928736 -0.03123027 -0.3694241 -0.4240022 -0.002488791 -0.9056577 -0.4016724 -0.007183134 -0.9157553 -0.9476478 0.007473647 -0.3192304 -0.9291578 -0.003299117 -0.3696687 -0.4239902 0.005134165 -0.9056524 -0.3221305 0.1621387 -0.9327074 -0.9478265 0.0126487 -0.3185359 -0.9126432 0.1132107 -0.3927668 -0.4581097 0.3230206 -0.8281264 -0.3790972 0.4294726 -0.8196576 -0.9159575 0.2138344 -0.339554 -0.01607769 0.9635441 -0.2670662 -0.5356388 0.5537267 -0.6375561 -0.009805262 0.9999512 0.0012753 0.0913279 0.8551701 -0.5102385 0.5117732 0.8484938 -0.1347095 0.1016802 0.3071302 -0.94622 0.3689035 0.3944309 -0.8416261 0.2211357 0.6097297 -0.7611365 0.09709531 0.5856058 -0.8047599 0.2888512 0.3260384 -0.9001466 0.5551017 0.8052276 -0.2084962 0.4777543 0.6929338 -0.5399941 0.6171597 0.4671949 -0.6331214 0.5836918 0.4221096 -0.6936335 0.6541047 0.4721958 -0.5909131 0.7935695 0.4930948 -0.3565177 0.6211341 0.7436351 -0.2473851 0.8989672 0.4319052 -0.07291066 0.06064009 0.008268475 -0.9981254 0.1898587 0.01736611 -0.9816579 0.3144188 0.06473422 -0.9470746 0.3685191 0.05476391 -0.9280057 0.6977537 0.08162367 -0.7116723 0.768581 0.1165354 -0.6290492 0.7837703 0.1100592 -0.611221 0.9246709 0.1036547 -0.3663871 0.9797675 0.135512 -0.1472829 0.9747995 0.1037114 -0.1975095 0.4188417 -0.004719018 -0.908047 0.3152425 0.02584499 -0.9486592 0.7737935 -0.01777899 -0.6331884 0.9188041 0.01693844 -0.3943504 0.9798122 -0.007395327 -0.1997834 -0.003050327 0.2629845 -0.9647953 0.01788187 0.787659 -0.6158519 -0.00582534 0.9642863 -0.2647983 0.4269151 0.8879566 -0.1711042 0 1 -1.88224e-7 4.84643e-4 1 1.49723e-4 0.6559137 0.7316635 -0.185596 0.4223848 0.8785116 -0.2231783 0.9611114 0.2666363 -0.07190257 0.906399 0.3705635 -0.2027896 0.9952076 0.09552538 -0.02090531 0.6556635 0.7319176 -0.1854776 0.9672288 0.2342543 -0.0979461 0.5402349 0.7039797 -0.4610412 0.9612367 0.2306609 -0.1510621 0.9615778 0.2301017 -0.1497381 0.6400693 0.6627621 -0.3886616 0.336782 0.8162149 -0.4694373 0.4384587 0.7956957 -0.4178788 0.9672638 0.1843381 -0.174414 0.2427803 0.7008503 -0.670721 0.9625434 0.1663325 -0.2141118 0.9587322 0.1680014 -0.2293648 0.7290444 0.4199087 -0.5405284 0.2887509 0.5497648 -0.783825 0.3446028 0.5650439 -0.7496495 0.6871017 0.4172092 -0.5948343 0.2389392 0.4522023 -0.8593145 0.9669207 0.1112571 -0.2295352 0.9641485 0.0859763 -0.2510494 0.9549828 0.0792663 -0.2858758 0.7198964 0.2248793 -0.656642 0.6975048 0.2159202 -0.6832756 0.3005535 0.2873897 -0.9094366 0.3263987 0.2999854 -0.8963665 0.2370513 0.1561917 -0.9588592 0.9661811 0.02308201 -0.2568294 0.9595911 -1.60644e-4 -0.2813985 0.7082721 -4.0201e-4 -0.7059395 0.3103312 4.80773e-4 -0.9506284 6.5404e-4 0.08508771 -0.9963732 -0.006361961 0.2263588 -0.9740233 5.39893e-4 0.463678 -0.8860037 0.002649366 0.4166054 -0.9090837 0.003751516 0.6552975 -0.7553617 -0.01024723 0.7875786 -0.616129 1.73446e-4 1 3.12265e-4 -0.006394386 0.7361789 -0.6767567 0.005308449 0.7224558 -0.6913968 -0.005446672 0.6148737 -0.7886069 0.004332542 0.6019061 -0.7985552 -0.004440844 0.4768109 -0.8789948 0.003296315 0.4656894 -0.8849421 -0.003381669 0.3257777 -0.9454404 0.002203047 0.3173666 -0.9483004 -0.002267897 0.1658715 -0.9861448 0.001059412 0.1607745 -0.9869907 -0.001107633 0 -0.9999994 -0.00178337 0.00533092 -0.9999843 5.60904e-4 0.002031564 -0.9999978 -0.981355 -6.78631e-4 -0.1922031 -0.9547787 0.005409359 0.2972679 6.95189e-4 -0.005326747 -0.9999856 -1.64421e-4 0.01316905 -0.9999133 0.001481711 -0.004424214 -0.9999892 -1.31833e-5 1.70224e-4 -1 -1 -5.56023e-5 -1.01938e-4 -1 -1.63698e-5 -6.26694e-5 -1 1.91721e-7 0 -1 -1.9982e-7 0 -1 2.20573e-7 0 -1 -3.66957e-7 0 -1 -5.90653e-7 0 0 1 3.07766e-5 -3.22887e-5 1 -8.761e-5 0.002125442 0.9999445 0.01032942 1 -1.49479e-6 0 1 1.49152e-6 0 0.9999997 -7.90194e-4 -5.36022e-4 0.9999995 5.91535e-4 -8.07801e-4 0.9999994 8.55641e-4 -8.08263e-4 0.9999992 0.001136243 -7.39887e-4 0.9999989 0.001393258 -5.81919e-4 0.9999988 0.001550436 -3.39324e-4 0.9999068 0.01260364 0.005259156 0.9999236 0.01036888 0.006735622 0.9999417 0.007849693 0.007413506 0.9999572 0.00547719 0.007458925 0.9999601 -0.007295846 0.005170047 -1 5.97977e-7 0 -1 -2.36604e-7 0 -1 0 0 0.9994336 -0.004753708 0.03331792 0.06021386 -0.9614261 -0.2683916 -0.03233987 -0.9988745 -0.03469848 0 -0.9965766 -0.08267515 0.07446533 -0.9666551 -0.245016 0.0858162 -0.9122486 -0.4005475 -0.006096184 -0.7352719 -0.6777449 0.004936993 -0.7224559 -0.6913996 -0.005070388 -0.6135418 -0.789646 0.003815054 -0.6019042 -0.7985593 -0.003908514 -0.4750596 -0.879945 0.002688229 -0.465701 -0.8849381 -0.002764582 -0.3236512 -0.9461725 0.001474738 -0.3173598 -0.9483041 -0.001520395 -0.1633164 -0.9865726 1.69604e-4 -0.1607686 -0.9869922 -1.71931e-4 0.001393139 -0.9999991 0.3194913 -0.9396712 -0.122244 0.209841 -0.9771463 -0.03394126 0.6593334 -0.7364569 -0.1513628 0.4536312 -0.8782142 -0.1515212 0.3850248 -0.8889108 -0.2481807 0.20208 -0.9608408 -0.1896013 0.7056624 -0.6878014 -0.1702053 0.9568101 -0.2851912 -0.05639654 0.9452171 -0.323097 -0.04661786 0.9672303 -0.2343196 -0.09777539 0.674718 -0.6893954 -0.2636089 0.7343981 -0.5682116 -0.3712075 0.9611237 -0.2315596 -0.150404 0.961441 -0.230235 -0.1504097 0.6770417 -0.5849289 -0.4466238 0.1695755 -0.8895326 -0.4242357 -0.0284757 -0.9336646 -0.3570148 0.3298851 -0.7504199 -0.5727529 0.2430607 -0.7007983 -0.6706738 0.967261 -0.1845206 -0.1742365 0.9633613 -0.1587324 -0.2161924 0.9604315 -0.1711154 -0.2197518 0.7297238 -0.4200769 -0.53948 0.2807964 -0.5776919 -0.7664369 0.3239842 -0.542477 -0.7750826 0.6862874 -0.4170543 -0.5958821 0.239112 -0.452193 -0.8592712 0.9669205 -0.1115496 -0.229394 0.9650139 -0.07041132 -0.2525678 0.9598044 -0.09123736 -0.2654268 0.7207741 -0.2253285 -0.6555242 0.6965609 -0.2155159 -0.6843654 0.2943909 -0.3032962 -0.9062811 0.3181255 -0.2847677 -0.9042696 0.2370921 -0.1561846 -0.9588503 0.9661915 -0.02346968 -0.2567551 0.3096097 0 -0.9508638 0.7093663 3.56237e-4 -0.7048399 0.06717389 -0.8450867 -0.5303925 -0.008420288 -0.7120541 -0.7020742 -0.002616405 -0.2134634 -0.9769476 -0.1159188 -0.9922445 -0.04487502 -0.01912593 -0.9996887 -0.01602381 0.004272639 -0.9999896 -0.001626551 5.02594e-7 0 1 2.67644e-4 -0.9999973 -0.002327382 -0.001648843 -0.9999987 -6.06001e-5 0.007037043 -0.9999753 0 0 -0.9998682 0.01623815 -2.13303e-4 -0.9999998 7.11689e-4 -0.01884585 -0.9998186 0.002763986 0.06188428 -0.9980834 1.64161e-4 0 0 -1 -0.0257321 0.01376366 -0.9995742 1.18103e-4 -0.001168906 -0.9999993 -0.001138687 0.004076957 -0.9999911 1.72211e-4 1.3247e-4 -1 1.98764e-4 0 -1 0.99989 -0.001582205 0.0147497 1 -2.22881e-4 2.3199e-5 1 -1.46311e-4 -2.28958e-5 1 -9.7248e-5 -4.94865e-5 1 -6.44529e-5 -6.49377e-5 1 -3.87177e-5 -7.56603e-5 1 -1.31637e-5 -8.40488e-5 1 0 -8.75213e-5 0.3469863 0.00122565 0.9378695 0.400728 0.009061098 0.9161523 0.8401724 -0.009489834 0.5422366 0.9262058 0.01501661 0.3767194 -0.002370595 -0.1991147 -0.9799734 -4.51754e-5 -0.1547338 -0.9879562 0.002064943 -0.4531015 -0.8914566 -0.001380801 -0.5453383 -0.8382149 0.003058671 -0.7072941 -0.7069129 -3.77845e-4 -0.8030017 -0.5959766 9.11265e-4 -0.8916413 -0.4527418 -4.06847e-4 -0.9075418 -0.4199615 0.002854824 -0.9879705 -0.1546159 0.2732821 -0.9515416 -0.1410167 0.449171 -0.8881703 -0.09694778 0.6632948 -0.3869379 -0.6405615 0.469652 -0.7935276 -0.3869642 0.7026602 -0.4497786 -0.5513329 0.44405 -0.770565 -0.457219 0.4102657 -0.3960632 -0.8214719 0.1931111 -0.7286277 -0.6571224 0.2827868 -0.4098826 -0.8671955 0.8776828 -0.1424724 -0.4575748 0.4447392 -0.03172421 -0.8950982 0.4111306 -0.00213021 -0.911574 0.874166 0.0112794 -0.4854962 0.8668503 0.007018983 -0.4985191 0.443984 0.0242235 -0.8957074 0.1957103 -0.02095705 -0.9804378 0.1084851 -0.8972765 -0.4279323 0.007833182 -0.8368299 -0.5474071 0.2290926 -0.9608433 -0.155874 0.2715668 -0.9124262 -0.3061538 0.2563239 -0.9157137 -0.3094618 0 1 7.55274e-5 -0.004107058 0.9999384 -0.01030761 0.01770657 0.9997271 0.01523762 6.61101e-4 0.9999999 -1.04788e-4 -1 -9.24796e-7 0 -1 -6.37225e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 5.48251e-7 0 -1 -3.69006e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.35052e-7 0 -1 2.20279e-7 0 -1 -2.03432e-7 0 -1 3.51244e-7 0 -0.9999865 0.004831016 0.001937687 -0.9999998 -8.12147e-4 -4.55294e-5 -1 -8.35031e-5 0 1 3.24671e-5 -1.07969e-4 1 2.51967e-7 -4.2614e-5 1 0 0 1 0 0 1 1.77824e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.78249e-7 0 1 3.33461e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 3.78746e-7 0 1.23536e-5 -8.07357e-5 -1 4.05288e-4 7.36185e-5 -1 3.61392e-5 -6.36628e-5 -1 0 -0.9889355 -0.1483462 -0.07778793 -0.993562 -0.08236414 0.01710331 -0.9692338 -0.2455474 0.01202851 -0.9156532 -0.4017891 -0.09268277 -0.8334745 -0.5447295 -0.01339972 -0.8704398 -0.4920928 0.00603336 -0.735584 -0.6774068 -0.004918277 -0.72119 -0.6927199 0.005062699 -0.6140148 -0.7892783 -0.003912031 -0.600738 -0.7994364 0.004022598 -0.4756636 -0.8796182 -0.002827346 -0.4647267 -0.8854497 0.002913296 -0.3243296 -0.9459397 -0.001684546 -0.3166665 -0.9485355 0.001740455 -0.1641752 -0.9864296 -4.91779e-4 -0.1604045 -0.9870513 4.99934e-4 0 -0.9999999 7.62953e-4 4.39921e-4 -0.9999997 -7.37704e-4 0.1604154 -0.9870494 0.001959562 0.1649976 -0.986292 -0.001907765 0.3166675 -0.9485347 0.003094434 0.3250458 -0.9456933 -0.003009259 0.4647203 -0.8854525 0.004164159 0.4762236 -0.8793144 -0.00404787 0.6007375 -0.7994362 0.005167424 0.6144201 -0.7889622 -0.005022227 0.7211955 -0.6927134 0.006109714 0.7358713 -0.6770939 -0.0188232 0.8990198 -0.4375034 -0.1662803 0.8256093 -0.5391849 -0.07077836 0.9135302 -0.4005659 -0.07078123 0.9669888 -0.2447915 -0.05539655 0.9612935 -0.2699 0.02930742 0.9989862 -0.0341745 0 0.9965866 -0.08255422 -0.04440712 0.9985281 0.03113979 -0.1272888 0.9879079 0.08851873 -0.1919764 0.971996 0.1355324 -0.237507 0.9568552 0.1673877 -0.4085989 0.8679904 0.282205 -0.5896056 -0.7101616 0.3847541 -0.4204149 -0.8533859 0.3081947 -0.4159412 -0.86902 0.2679504 -0.2518877 -0.933171 0.2564067 -0.05191326 -0.9949969 0.08535987 -0.106732 -0.989756 0.09482264 -0.8520151 0.4021583 -0.3351702 -0.6970461 0.2062797 -0.6867136 -0.7521197 0.5012068 -0.427911 -0.7300593 0.5107627 -0.4540208 -0.7447735 0.6386939 -0.193346 -0.7245594 0.6334912 0.2714824 -0.7306236 0.6177512 0.2908141 -0.7661489 0.6351892 0.09772688 -0.8107617 0.5825802 -0.05714786 -0.7849943 0.5232927 0.3315855 -0.8829498 0.3022508 -0.3592272 -0.7564446 0.08608323 -0.6483683 -0.7207499 0.1159441 -0.6834301 -0.8846095 0.3006407 -0.3564846 -0.9079273 0.4174535 -0.03742659 -0.9261304 0.3767489 0.01851725 -0.8493233 0.3828601 0.3634119 -0.8432897 0.4291871 0.3235135 -0.8864958 0.2340625 0.3991742 -0.9158614 0.1479565 0.3732386 -0.9904037 0.1288712 0.04992645 -0.9887133 0.1463827 0.0319103 -0.9085032 0.07862311 0.4104148 -0.942945 0.1044725 -0.3161337 -0.9426978 0.1050564 -0.3166767 -0.755189 0.04330933 -0.6540749 -0.9332692 -0.07755625 0.3507046 -0.9015103 -0.1478 0.4067364 -0.9905307 -0.1277857 0.05019873 -0.8863739 -0.2341295 0.3994054 -0.943093 -0.1040602 -0.3158278 -0.9888131 -0.1457326 0.03179198 -0.7553094 -0.04352122 -0.6539219 -0.9425181 -0.1054196 -0.3170903 -0.7440542 -0.06877928 -0.6645697 -0.9265168 -0.3757778 0.01891422 -0.8689177 -0.3788201 0.3185551 -0.8324289 -0.4305317 0.3488621 -0.7848837 -0.523364 0.3317344 -0.8852242 -0.4557114 -0.09330278 -0.8617193 -0.353088 -0.3643745 -0.7489871 -0.1418223 -0.6472285 -0.8933722 -0.3237349 -0.3115798 -0.7159297 -0.6467757 0.2629181 -0.8209927 -0.5617519 -0.1020096 -0.7608877 -0.6279163 -0.1636193 -0.8089194 -0.4513398 -0.376752 -0.7703467 -0.466975 -0.4341664 -0.7113638 -0.2204344 -0.6673607 -0.8217526 -0.4064046 -0.3994472 -0.996408 0.01263606 -0.08373463 -0.9944046 0.01900696 -0.1039152 -0.9990923 0.0227127 -0.03603744 -0.9990969 0.01164025 -0.04086524 -0.9894008 0.009796202 -0.14488 -0.9947921 0.02021545 -0.09990125 -0.994392 0.04069286 -0.09761393 -0.9594226 0.02106994 -0.281184 -0.9828487 0.1044596 -0.1519761 -0.9822808 0.06087076 -0.1772548 -0.9700506 0.08807164 -0.226374 -0.9707147 0.02645146 -0.2387748 -0.9412925 0.032148 -0.336058 -0.9258497 0.2543582 -0.2794716 -0.9481039 0.03658169 -0.3158493 -0.9471427 0.112491 -0.3004437 -0.9443778 0.1134435 -0.3086766 -0.9444873 0.2107847 -0.2520193 -0.9023398 0.03338575 -0.4297305 -0.9011236 0.1544615 -0.4051148 -0.9579957 0.2267187 -0.1756215 -0.8543987 0.05021345 -0.5171864 -0.8876013 0.1591364 -0.4322496 -0.8875283 0.2983527 -0.3511117 -0.8868735 0.3987759 -0.2333096 -0.8862825 0.2994717 -0.353299 -0.8607461 0.178979 -0.4765319 -0.8628278 0.05416858 -0.5025873 -0.8733252 0.4180639 -0.2500514 -0.7855408 0.585107 -0.2014337 -0.844719 0.3467761 -0.4076718 -0.8446934 0.1833282 -0.5028755 -0.8424605 0.3483155 -0.411019 -0.8426245 0.4686604 -0.2652199 -0.8769378 0.4692035 -0.1040589 -0.7962025 0.04933249 -0.6030158 -0.7939663 0.2149806 -0.5686836 -0.808227 0.5111253 -0.292438 -0.8082408 0.5803766 -0.09954905 -0.7506155 0.06643128 -0.6573913 -0.7634159 0.216939 -0.6083862 -0.7638848 0.4178681 -0.4917992 -0.8204135 0.3880577 -0.4199202 -0.7766782 0.5528714 -0.3018349 -0.7155137 0.6889013 0.1159964 -0.6725213 0.7364091 0.07359898 -0.6812862 0.7182174 -0.1414671 -0.8020722 0.07690471 -0.5922549 -0.8019977 0.1995236 -0.5630187 -0.7122604 0.1981002 -0.6733806 -0.7527995 0.4451657 -0.4848922 -0.7656359 0.5644668 -0.3085107 -0.8179035 0.5551498 -0.151138 -0.6993778 0.6522798 0.292236 -0.9092212 -0.3766145 -0.1774214 -0.9913836 -0.1305 -0.01132673 -0.949055 -0.3044831 -0.08114677 -0.9649092 -0.2586047 -0.04554009 -0.5966526 -0.777577 -0.1984434 -0.7891349 -0.6048989 -0.1065998 -0.9657943 -0.235155 -0.1092869 -0.9490864 -0.2582734 -0.1803608 -0.9649135 -0.2273905 -0.1312841 -0.3877626 -0.8024071 -0.4536331 -0.2385869 -0.7003719 -0.6727225 -0.9657933 -0.1835868 -0.1831372 -0.7385994 -0.4333303 -0.516426 -0.9490706 -0.1810172 -0.2578715 -0.9649195 -0.1687619 -0.201121 -0.3305876 -0.5669633 -0.7544963 -0.3050023 -0.5594328 -0.7707197 -0.6805779 -0.4303903 -0.5929401 -0.2377073 -0.4514084 -0.8600731 -0.9657891 -0.1098628 -0.2349078 -0.9490526 -0.08189117 -0.3042908 -0.9649252 -0.0897904 -0.2466925 -0.7275053 -0.2346612 -0.6447249 -0.322265 -0.2997724 -0.897932 -0.3098672 -0.2936034 -0.9043115 -0.6946948 -0.2221216 -0.68415 -0.2372568 -0.1558241 -0.9588681 -0.9657868 -0.0228762 -0.2583266 -0.3142737 0 -0.9493324 -0.31426 8.74341e-6 -0.949337 -0.9490262 0.02717965 -0.3140232 -0.9649398 0 -0.2624714 -0.7117421 5.30173e-6 -0.7024409 -0.7117519 0 -0.702431 -0.2372613 0.1558347 -0.9588653 -0.9657777 0.06694763 -0.2505825 -0.3066231 0.3014162 -0.9028459 -0.3182151 0.2927598 -0.9016822 -0.694701 0.2221306 -0.6841408 -0.9489522 0.1331467 -0.2859402 -0.9649646 0.08974051 -0.2465564 -0.7275002 0.2346638 -0.6447297 -0.2376979 0.4514032 -0.8600785 -0.9657641 0.1487216 -0.2125602 -0.6805854 0.4303969 -0.5929267 -0.2993382 0.5731975 -0.7627853 -0.3217291 0.5562056 -0.7662413 -0.7385926 0.4333356 -0.5164313 -0.9488759 0.2231664 -0.2232298 -0.964989 0.1685978 -0.2009255 -0.2385858 0.700378 -0.6727166 -0.9657475 0.2125681 -0.148817 -0.2939365 0.8594491 -0.4182687 -0.3936309 0.8054496 -0.4430642 -0.615529 0.6905264 -0.3798651 -0.9588282 0.2459397 -0.1419935 -0.5820078 0.7042377 -0.4065909 -0.9657585 0.2351608 -0.1095905 -0.9657359 0.2507134 -0.06705999 -0.9487726 0.3147652 -0.0274471 -0.9896426 0.1114978 -0.09042066 -0.9374392 0.3416635 -0.06688767 -0.5873391 0.8006835 -0.1180628 -0.8226501 0.5219266 -0.2254763 -0.6924756 0.6924636 -0.2024151 -0.5147524 0.831374 -0.2093971 -0.3524112 0.9010128 -0.2529473 -0.3123171 0.9193571 -0.2392503 -0.3528842 0.9005162 -0.254054 -0.1119046 0.9931381 -0.03397244 -0.1119699 0.9937116 -1.78406e-4 -0.1946955 0.9808569 0.003682971 -0.3651767 0.9309352 -0.00240159 -0.5260813 0.8504334 0.001280069 -0.4889855 0.872291 -0.00127381 -0.7143178 0.6998209 9.17657e-4 -0.707122 0.7070901 0.001479625 -0.8595867 0.5109899 -5.67055e-4 -0.8447405 0.5351755 9.53597e-4 -0.9587785 0.2841482 -0.001939833 -0.9394835 0.3425897 0.001776456 -0.9954783 0.09498715 -7.97928e-4 -0.9937124 0.1119639 0 -0.7133834 0.6985089 -0.05629914 -0.5625953 0.8205677 -0.1007737 -0.8549636 0.508279 -0.1033917 -0.8415546 0.5292949 -0.1078557 -0.9490778 0.2814462 -0.1415614 -0.9878228 0.09500938 -0.1232047 -0.406057 0.9138467 0.001397609 -0.3324879 0.943072 -0.008196532 -0.2558831 0.9652795 -0.05252945 -0.7110176 0.6436711 0.283093 -0.5436429 0.7803342 0.3090808 -0.3353622 0.9420609 0.007323265 -0.6103575 0.7843998 0.1103666 -0.6920753 0.7032364 0.1627585 -0.5170993 0.8547837 -0.04419523 -0.5763878 0.8033123 0.1498892 -0.6578716 0.749139 0.07743287 -0.6678611 0.7414907 0.06444466 -0.6164978 0.7814478 -0.09627938 -0.5726468 0.8176057 -0.05997097 -0.8166515 0.5724842 -0.07309085 -0.8004091 0.5814624 -0.1457626 -0.8559814 0.4787226 -0.1952455 -0.8365836 0.5312302 -0.1338753 0.9487577 -1.5082e-4 -0.3160046 0.9326866 0.001193046 -0.360686 0.4537588 -0.00118494 -0.8911238 0.4353505 -4.55056e-4 -0.900261 -7.93739e-5 -1 2.98774e-5 -3.86575e-5 -1 8.15107e-5 0 -1 1.77169e-7 -1.47704e-4 -1 -3.08984e-5 -0.9964498 -0.01178532 -0.08336162 -0.9983762 -0.02492457 -0.05122333 -0.998402 -0.01889759 -0.05325752 -0.9983075 -0.02478682 -0.05261021 -0.9960803 -0.03421962 -0.08156597 -0.9962339 -0.01169383 -0.0859152 -0.9892727 -0.01950609 -0.144772 -0.9822662 -0.01710367 -0.1867101 -0.9819517 -0.06726473 -0.1767666 -0.9591674 -0.03072613 -0.2811654 -0.9905112 -0.07150346 -0.1173669 -0.9788526 -0.1252843 -0.161714 -0.9785422 -0.06961661 -0.1939297 -0.9627919 -0.1621823 -0.2161684 -0.9592568 -0.1722732 -0.2239382 -0.9586429 -0.0961523 -0.267878 -0.9413122 -0.03120034 -0.3360924 -0.9472403 -0.03591889 -0.3185055 -0.9460272 -0.1175846 -0.302004 -0.9425166 -0.2767438 -0.1872845 -0.9054799 -0.1446663 -0.3989711 -0.9062985 -0.2631977 -0.3306813 -0.9178807 -0.2522543 -0.3063708 -0.9216434 -0.3316446 -0.201458 -0.8855422 -0.1666429 -0.4336419 -0.8871166 -0.0363301 -0.4601134 -0.8538761 -0.05461061 -0.5176036 -0.9337716 -0.3099125 -0.1789554 -0.8434594 -0.3523581 -0.4054874 -0.8440992 -0.18374 -0.5037223 -0.7847732 -0.552006 -0.2818163 -0.8232899 -0.04665136 -0.5657009 -0.8211603 -0.2026797 -0.5334947 -0.8080378 -0.5168795 -0.2826845 -0.8082885 -0.3758358 -0.4532298 -0.750651 -0.06076163 -0.6578992 -0.8160256 -0.5458183 -0.1902227 -0.7501133 -0.22158 -0.6230831 -0.7450543 -0.437609 -0.5033811 -0.7673738 -0.210667 -0.6056045 -0.7670268 -0.06712132 -0.6380947 -0.784841 -0.5459694 -0.2931591 -0.8126369 -0.3939298 -0.4294656 -0.6989669 -0.6212382 -0.3542716 -0.7312147 -0.6573439 -0.182275 -0.684179 -0.5085508 -0.5227574 -0.7260631 -0.215768 -0.6528986 -0.7226821 -0.678829 0.130084 -0.7277319 -0.5936058 -0.3435674 -0.264388 -0.95913 0.1008402 -0.4320181 -0.8969509 -0.09401935 -0.6050702 -0.7832266 0.142991 -0.3751323 -0.9266769 0.02336347 -0.4584776 -0.8885427 -0.01703929 -0.6055442 -0.7930687 -0.0660187 -0.6529601 -0.7511695 0.09688997 -0.6542546 -0.7504227 0.09389841 -0.7925587 -0.5891061 -0.1574957 -0.6224873 -0.7787278 -0.07805567 -0.7948885 -0.5878264 -0.1503739 -0.8105062 -0.5620998 -0.1646923 -0.8098721 -0.5634237 -0.1632822 -0.8986508 -0.392256 -0.1963722 -0.1193391 -0.9927923 -0.01103776 -0.0144087 -0.9994608 -0.02950733 -0.001143455 -0.9999994 -2.23502e-4 -0.3521888 -0.9358712 -0.01041001 -0.131658 -0.9912229 -0.01197606 -0.2374448 -0.9700775 -0.05069363 -0.2377125 -0.9700925 -0.04912614 -0.2733497 -0.9605963 -0.05034786 -0.4170451 -0.9047861 -0.08623045 -0.424819 -0.9044398 -0.03895831 -0.4455932 -0.8913614 -0.08319658 -0.5952562 -0.8006581 -0.06794643 -0.5963745 -0.799857 -0.06757283 -0.5880718 -0.8001113 -0.118294 -0.6166662 -0.7797056 -0.1085458 -0.8064756 -0.5864192 -0.07556146 -0.8082581 -0.5840689 -0.07471626 -0.7971332 -0.5849951 -0.1495316 -0.9189757 -0.3791266 -0.1083826 -0.8150715 -0.5633074 -0.1354375 -0.9674891 -0.2398635 -0.08019047 -0.9115308 -0.3776317 -0.1628059 -0.9430138 -0.2613939 -0.2059085 -0.9927644 -0.04472106 -0.11144 -0.989093 -0.1273361 -0.07403099 -0.9299391 -0.2990081 -0.2140272 -0.1305209 -0.9914456 -1.69666e-7 -0.1192955 -0.9928587 -6.1726e-4 -0.3826858 -0.9238786 -4.11445e-4 -0.3522574 -0.9359026 0.001012384 -0.6087589 -0.7933542 0.001346826 -0.5964696 -0.8026325 0.002293169 -0.8090472 -0.5877434 -6.7648e-4 -0.7936529 -0.6083704 8.1415e-4 -0.9243702 -0.3814969 -7.03132e-5 -0.9238857 -0.3826686 -1.70008e-7 -0.9916466 -0.1289844 0 -0.9914461 -0.1305167 8.35663e-5 -0.1291008 -0.9806596 -0.1471053 -0.3755054 -0.9065418 -0.1928151 -0.4680989 -0.8530529 -0.2306171 -0.4515169 -0.7878483 -0.4188406 -0.5465849 -0.7252127 -0.4187024 -0.6082782 -0.7008405 -0.372586 -0.5721026 -0.7917593 -0.2140467 -0.4746628 0.8510899 0.2243682 -0.4577124 0.8535903 0.2487632 -0.3598774 0.9262133 0.1123266 -0.5492996 0.8211207 0.1550191 -0.4882165 0.870643 -0.06021147 -0.194683 0.9808581 -0.004012584 -0.2049255 0.9787381 -0.008794546 -0.2408218 0.9699551 -0.03452485 -0.2553867 0.9652409 -0.05556869 -0.9999711 0.007605195 1.21785e-4 -0.9999952 -0.002997696 8.54734e-4 -0.9999939 -0.003353118 9.78871e-4 -0.9999994 0 -0.001186072 -0.8862363 -0.4370459 -0.1535461 -0.8596947 -0.4913477 -0.1396511 -0.7213765 -0.640836 0.2625741 -0.687279 -0.6679332 0.2855045 -0.5379254 -0.8254376 0.1711407 -0.089634 -0.9955468 0.02919554 -0.09554094 -0.9951177 0.02475494 -0.1069311 -0.9932101 0.04582095 -0.1259351 -0.9920355 0.002433717 -0.1173849 -0.9810523 -0.1541333 -0.9991533 -0.04114508 1.00893e-4 -0.04763281 -0.9988645 -8.5677e-4 1 -3.01314e-5 1.96228e-4 1 1.99712e-4 -5.40625e-5 1 0 -2.22524e-6 0.2393013 0.01659196 -0.9708037 0.340554 0.004552781 -0.940214 0.4647546 0.001059055 -0.8854389 0.6631556 -0.002519607 -0.7484775 0.8229896 0.006064116 -0.5680243 0.9347048 0.02630251 -0.3544504 0.9927123 0 -0.1205085 0.9927189 -2.88792e-5 -0.1204546 0.9040649 0.01585537 -0.4271011 3.95195e-5 -0.9999998 -6.03869e-4 -2.46076e-5 -1 1.03468e-4 -2.52e-5 -1 2.31361e-4 4.41908e-7 -1 -4.49938e-6 1.29983e-7 -1 -2.30838e-6 3.28781e-7 -1 6.8647e-7 0 -1 -6.07353e-7 1.03811e-5 -1 -8.06934e-5 0 -1 -2.9669e-7 1.10848e-5 -1 1.22027e-5 -0.947209 -0.01689749 -0.3201715 -0.1633957 -0.02333933 -0.9862846 -0.4521208 -2.54416e-4 -0.8919568 -0.9946249 -0.00928992 -0.1031258 -0.1635607 -0.01427954 -0.9864299 0 -1 0 0 -1 0 0 -1 0 0 -0.9701426 0.2425356 0.815125 -0.05270439 0.5768826 0.8986712 0 -0.438623 0.9044824 -0.006862699 -0.426456 0.9393242 0.004310369 -0.3430036 0.9545444 -0.009238779 -0.2979258 0.9694658 0.004599153 -0.2451834 0.9866577 -9.10171e-4 -0.1628062 0.9898295 -0.009415447 -0.141947 -0.02275341 0.02489012 -0.9994313 0.1193639 -0.02614277 -0.9925064 0.2252363 0.01381814 -0.9742063 0.3575754 -0.009148716 -0.9338395 0.4524347 0.01231402 -0.8917125 0.5349345 -0.006917893 -0.8448653 0.6521134 0.008543729 -0.7580733 0.6912466 -0.003481268 -0.7226107 0.8106769 0.004049777 -0.5854799 0.8202673 0 -0.5719806 -0.09965127 -0.001815855 -0.9950208 -0.06235259 -0.9957591 0.06764686 -0.2023846 -0.9591159 0.1978318 -0.06164848 -0.9959497 0.06545031 -0.3453996 -0.8805637 0.32451 -0.3388894 -0.890093 0.3047761 -0.1991704 -0.9617902 0.1878585 -0.3668327 -0.8914704 0.2659214 0.636735 -0.6006257 0.4835467 0.2391135 -0.8473774 0.474106 -0.2736889 -0.8272328 0.4906939 0.08862429 -0.9032942 0.4197685 0.6647042 -0.6040238 0.4396858 0.6847661 -0.5922917 0.4246011 0.6514908 -0.6602333 0.3737001 0.1170858 -0.9446147 0.3065844 0.2397288 -0.9332714 0.2674601 0.6956524 -0.6429955 0.3203508 0.687515 -0.6494031 0.3249595 0.6645329 -0.6935549 0.2781682 0.7263695 -0.6447274 0.2381473 0.6908797 -0.6795063 0.2468938 0.2417125 -0.9505735 0.194898 0.3729038 -0.9153248 0.1520641 0.4021362 -0.9113624 0.0877785 0.3472985 -0.9325497 0.09866535 0.3556221 -0.9313089 0.07871842 0.3150433 -0.948167 0.04155969 0.1168699 -0.9930276 0.0154156 0.4402564 -0.8978334 -0.00833708 0.3215475 -0.9466273 0.02245247 -0.6497644 0.09072828 -0.7547018 -0.572444 0.08332252 -0.8156992 -0.5177595 0.03186547 -0.8549327 -0.6212211 0.09206408 -0.7782086 -0.5780669 0.1097511 -0.808575 -0.4363012 0.08042347 -0.8961995 -0.4955585 0.2551012 -0.8302682 -0.1986352 0.1620711 -0.96658 -0.2292832 0.1702265 -0.9583592 -0.2924733 0.3886293 -0.8737429 -0.2980372 0.3872548 -0.8724721 -0.01434177 0.1772688 -0.984058 -0.1274458 0.5253184 -0.8413075 0.03705573 0.591821 -0.8052173 0.08401024 0.594484 -0.7997068 0.1842445 0.2372651 -0.9538131 0.2028936 0.2333935 -0.9509793 0.4125484 0.240747 -0.878547 0.2440397 0.6798533 -0.691552 0.4809156 0.4938198 -0.7244738 0.3262248 0.6498309 -0.6865109 0.02677047 0.7169066 -0.696655 0.4363033 0.6820588 -0.5868861 0.549539 0.2822183 -0.7863587 0.6172878 0.1049025 -0.7797123 0.337953 0.285218 -0.896905 -0.08532345 0.3475857 -0.933758 -0.623868 0 -0.7815298 -0.6234945 -3.99086e-5 -0.7818279 -0.4377225 3.64117e-5 -0.8991103 -0.4338716 -3.05726e-4 -0.9009748 -0.2326863 2.96529e-4 -0.9725519 -0.2225331 -5.20208e-4 -0.9749251 -0.01456749 5.14326e-4 -0.9998938 0 -6.11776e-4 -0.9999998 0.2086611 6.24165e-4 -0.9779879 0.222522 -4.92212e-4 -0.9749276 0.4250473 5.04517e-4 -0.9051711 0.4338807 -2.83749e-4 -0.9009703 0.6207231 2.93722e-4 -0.7840299 0.623473 0 -0.781845 -0.7070778 0 -0.7071359 -0.707079 -2.35906e-6 -0.7071346 -0.7104141 -0.00923711 -0.7037233 -0.7046067 0.01245743 -0.7094888 -0.661574 0.1000357 -0.7431775 -0.4219263 -0.8521161 0.3096395 -0.4038802 -0.8363662 0.3706381 -0.4013476 -0.8437567 0.3563635 -0.2014473 -0.84829 0.4897173 0.1538095 -0.757456 0.6345101 0.4889825 -0.4556807 0.7438086 0.7088915 -0.1785257 0.6823499 -0.1675468 -0.8655346 0.4719939 -0.2499654 -0.8760294 0.4124197 -0.1294784 -0.8392081 0.5281714 -0.2039812 -0.8563758 0.4743547 0.1536067 -0.7572695 0.6347818 0.3293162 -0.6767236 0.6584802 0.491304 -0.4580534 0.7408155 0.354331 -0.709137 0.609569 0.220324 -0.8119357 0.5405718 0.5934155 -0.5175992 0.6164002 0.7374612 -0.209017 0.6422328 0.8160329 -0.3085777 0.4887436 0.7259456 -0.3590474 0.5865902 0.7405961 -0.2001601 0.6414464 0.1168556 -0.9931485 -0.001008868 0.1501712 -0.9882257 -0.0293008 0.1360949 -0.988255 -0.06950169 0.1833649 -0.9819478 -0.04643225 0.1919435 -0.9812871 0.01527905 0.1068691 -0.9921252 -0.06532013 0.4402417 -0.8977922 -0.01251453 0.1109331 -0.9889203 -0.09864336 0.1121163 -0.9886544 -0.0999614 0.1090295 -0.9886416 -0.1034424 0.2499032 -0.9296916 -0.2705954 0.1828768 -0.9455833 -0.2691254 0.2156059 -0.9133102 -0.3455122 0.1611708 -0.9472076 -0.2771676 0.1785748 -0.9074363 -0.380356 0.03253912 -0.9983173 -0.04799997 0.04872357 -0.9940711 -0.09720379 0.04951423 -0.9920257 -0.115903 0.1734674 -0.8360562 -0.5204991 0.1712641 -0.8500947 -0.4980036 0.1757156 -0.9089293 -0.3781159 0.04759436 -0.9923745 -0.1136998 0.05362218 -0.9869092 -0.1521018 0.2535678 -0.9447028 -0.2079422 0.2840492 -0.8643484 -0.4149917 0.2602985 -0.8956975 -0.3605148 0.2666859 -0.8230801 -0.5014158 0.2478 -0.7843751 -0.5686395 -6.56949e-5 -0.9999994 -0.001131415 -2.05054e-4 -0.9999998 6.86732e-4 -2.0504e-4 -0.9999998 6.86062e-4 -1.68216e-5 -1 1.06803e-5 -2.07044e-4 -0.9999999 5.55598e-4 2.25611e-4 -0.9999998 -6.05423e-4 -2.95175e-5 -1 4.35961e-5 -1.22186e-5 -1 2.78497e-6 0 -1 4.036e-7 -4.91502e-5 -1 4.56323e-4 0 -1 4.41363e-6 0.3525553 -0.8555891 -0.3790411 0.3116161 -0.8804436 -0.3573716 0.3061493 -0.910061 -0.2793951 0.3423857 -0.9190624 -0.1951834 0.2929202 -0.9164159 -0.2727267 0.2386974 -0.9456217 -0.2209595 0.2381839 -0.9469295 -0.2158546 0.2469198 -0.9477921 -0.2017945 0.2470577 -0.94852 -0.1981722 0.2674833 -0.9185493 -0.2910668 0.2569962 -0.9456889 -0.1990618 0.2777743 -0.9156069 -0.2906985 0.3134286 -0.86365 -0.3948054 0.256459 -0.9482637 -0.187149 0.2863978 -0.9431062 -0.1688995 0.2216923 -0.9559361 -0.1924548 0.3077291 -0.8655282 -0.3951758 0.3023807 -0.9104925 -0.2820807 0.2564381 -0.9490117 -0.1833474 0.2560515 -0.8881105 -0.3817031 0.2650578 -0.9465113 -0.1840127 0.2565774 -0.9478963 -0.1888403 0.25937 -0.9140505 -0.3118314 0.2356683 -0.9201387 -0.3127386 0.2905758 -0.9386476 -0.185759 0.228971 -0.8909945 -0.3920472 0.2026887 -0.8984285 -0.3895427 0.3008745 -0.9391363 -0.1658239 0.260475 -0.9274561 -0.2682876 0.3878899 -0.8987562 -0.2043988 0.3247321 -0.8801459 -0.3462547 0.3460811 -0.925378 -0.1546077 0.2665843 -0.8656461 -0.4237803 0.2790189 -0.8544856 -0.4381812 0.4687653 -0.8755775 -0.1167182 0.4902011 -0.8681079 -0.07804828 0.4814864 -0.8716093 -0.09202271 0.4902051 -0.8678818 -0.0805 0.4474827 -0.8914318 -0.07147413 0.5005638 -0.8656895 -0.004193425 0.4995087 -0.8662844 -0.00653398 0.6005955 -0.7889509 -0.1297757 0.5074489 -0.8594309 -0.0622428 0.7013735 -0.7049167 0.1056779 0.6956553 -0.7094041 0.1131802 0.6289874 -0.762393 -0.1520922 0.664568 -0.7442901 -0.06619393 0.5952162 -0.7993766 0.08194464 0.6265507 -0.761123 0.1677084 0.6269951 -0.7671248 0.135635 0.6911711 -0.7164413 0.09483975 0.7182928 -0.6952803 0.0253154 0.7580253 -0.6227501 0.1938552 0.7604596 -0.5803706 0.2913271 0.7575163 -0.5975437 0.2628894 0.7544999 -0.6070907 0.2493409 0.7991358 -0.5859143 0.1344864 0.790567 -0.6058165 0.08938848 0.8215386 -0.5405208 0.1814157 0.8207837 -0.4692702 0.3257293 0.835345 -0.3997552 0.3773519 0.8150735 -0.3789454 0.4382415 0.8246665 -0.4032723 0.3966066 0.8262979 -0.4337514 0.3592935 0.8732556 -0.3672801 0.3202035 0.8743069 -0.4323125 0.2206662 0.8756905 -0.4198485 0.2385237 0.8797497 -0.372007 0.2960597 0.8811836 -0.3304143 0.3381449 0.8816385 -0.2787825 0.3807807 0.8599933 -0.2211823 0.4598806 0.8817104 -0.2316821 0.4109869 0.8767298 -0.1035447 0.4697057 0.7611622 -0.1840569 0.6218965 0.830002 -0.1669018 0.5322036 0.8491138 0.0220589 0.5277491 8.00675e-4 0.9999955 -0.002914607 1.9192e-4 -1 -4.49039e-7 0.04146766 -0.9978154 -0.0514279 -0.007111132 -0.9999207 0.01039892 0.003337204 -0.9999825 -0.00488013 -8.85215e-4 -0.9999996 2.76288e-4 -9.95798e-4 -0.9999994 4.69509e-4 -0.001082301 -0.9999991 7.54711e-4 -0.001183986 -0.9999986 0.00123775 -0.001281738 -0.9999972 0.002024412 -0.002108991 -0.9999896 0.004053294 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.001348614 -0.999993 0.003522038 0.002055346 -0.9910548 0.1334401 0.2772106 -0.546256 0.7904167 -0.1166644 0.03638851 0.9925045 -0.604407 0.2074012 0.7692056 -0.7454774 -0.1872649 0.6396838 -0.4285294 -0.1607231 0.8891178 0.9962196 0.04058206 -0.0768094 0.9986143 0.03368157 -0.04043662 -0.2765302 -0.5929502 0.756268 -0.2212674 -0.610017 0.7608678 0.8892003 -0.2822961 0.3600443 0.119928 0.9925268 0.02254009 -0.5501428 -0.6272999 0.5512149 0.8536086 0.2230147 0.470762 0.7894388 0.3703002 0.4895551 0.1710877 -0.9322435 0.3188278 0.1746862 -0.9329741 0.3147128 0.2767142 0.9606179 0.02535039 0.2631711 0.9632378 0.05398029 0.2677219 0.9606288 0.07427906 0.2457112 0.962623 0.1139428 0.2470989 0.9609029 0.1249308 0.4025743 -0.8445901 0.3529898 0.3081626 -0.8786294 0.364755 0.7923493 -0.4863711 0.3682739 0.7305898 -0.5583207 0.3930861 0.9395618 -0.146577 0.3094171 0.9284021 0.2902551 0.2319945 0.9281854 0.2916861 0.2310658 0.4500841 -0.6295917 0.6332762 0.5276674 -0.5684834 0.6311845 0.5146169 -0.5832913 0.6284432 0.6990584 0.2892754 0.6539397 0.6960245 0.2585659 0.6698459 0.7332835 0.3930097 0.5548322 0.5154247 -0.6393544 0.5705817 0.7147649 -0.4432713 0.5409453 0.5036952 -0.691275 0.5181024 0.6268921 -0.5820151 0.5179428 0.5468484 -0.6432545 0.5358923 0.8545953 0.2361623 0.4624871 0.8735178 0.3251657 0.3622626 0.7715947 0.6347539 0.04158365 0.1448652 -0.9397484 0.3096566 0.1440281 -0.9399671 0.3093829 0.1438862 -0.9399999 0.3093492 0.143729 -0.9400287 0.3093351 0.1435254 -0.9400616 0.3093297 0.1433923 -0.9400712 0.3093619 0.1033968 -0.9394602 0.3266857 0.4052397 0.8371928 0.3672726 0.4044088 0.8537462 0.3279804 0.4530766 0.8312925 0.321985 0.4888494 0.8366226 0.2471617 0.4901289 0.8324376 0.2584983 0.5333691 0.8204042 0.2060449 0.5503007 0.8208852 0.1526988 0.5477446 0.8253548 0.1369865 0.5793759 0.8099972 0.0907095 0.5819862 0.8114492 0.05331397 0.5820849 0.811389 0.05315369 0.6388921 0.7680506 -0.04376411 0.5823409 0.811749 0.04407769 -0.6297558 -0.6157594 0.4735484 -0.6271258 -0.6118091 0.482082 -0.6740891 -0.630357 0.3850376 -0.723318 -0.6162527 0.3115186 -0.7775484 -0.5790691 0.2451478 -0.6944273 -0.6441287 0.3207319 1 -1.13442e-5 0 1 5.63126e-6 0 0.101216 0.9936187 0.04977393 0.2418761 0.9669432 -0.08072793 0.3517692 0.8901457 -0.2896535 0.31959 0.943414 -0.08850127 0.3643687 0.931235 0.006072521 0.4288782 0.9010828 -0.0641359 0.3415879 0.9306011 -0.1315277 0.3586279 0.9302865 -0.07715725 0.449767 0.8931323 0.004947423 0.4393381 0.89793 0.02652996 0.5673802 0.8141534 -0.1234261 0.5424739 0.8392261 -0.03770589 0.1955621 -0.8704785 0.4516888 0.274533 -0.7721518 0.5730736 0.3052313 -0.6570793 0.689261 0.9903775 0.1327829 -0.03900474 0.9073838 0.4119579 0.08333945 0.910393 0.3720346 0.181038 0.8286109 0.5490599 -0.1092581 0.7531545 0.6424612 -0.1414283 0.784201 0.6195023 -0.03529936 0.8274941 -0.507332 0.2405576 0.754019 -0.4613307 0.4675784 -0.2270602 -0.8699226 0.4378109 0.85823 -0.4431261 0.2589995 0.9197178 -0.361854 0.1522533 0.8714846 -0.4373522 0.2218957 0.8436255 -0.50055 0.1942832 -0.2034449 -0.8764452 0.4364104 0.2774363 0.9607213 0.006606578 0.22382 0.973071 -0.05511474 0.2000837 0.9797759 0.002401053 0.1887516 0.9813424 -0.03660464 0.2663145 0.9637085 -0.01851433 0.2754479 0.961282 -0.008096873 -0.2649534 -0.9269971 0.2654737 -0.2992206 -0.9272763 0.2250022 -0.2998444 -0.9280352 0.2210069 -0.3246492 -0.9274775 0.1854411 -0.324842 -0.9279549 0.1826956 -0.3430623 -0.9276202 0.147747 -0.3430413 -0.9279056 0.1459932 -0.3559871 -0.927726 0.1122397 -0.3559255 -0.9278632 0.1112974 0.9206955 0.3749945 -0.1081624 -0.6946241 -0.6997562 0.1668493 -0.1926552 -0.8635072 0.4660895 0.1259099 -0.5479894 0.8269549 0.1832878 -0.6922945 0.6979498 0.2395914 -0.7246621 0.6461121 0.3299891 -0.7194282 0.6111713 0.04363244 -0.7846608 0.618388 -0.1494648 -0.8515264 0.5025566 -0.3957157 -0.9000049 0.1827576 -0.4030988 -0.9021148 0.153949 -0.3804587 -0.9247238 -0.01171422 0.2491181 -0.6247086 0.7400537 0.3378735 -0.8061549 0.4857529 0.748552 -0.5875605 0.3073152 0.964355 -0.1841309 0.1900404 0.9985203 -0.05406308 0.005875289 0.9406669 -0.09922677 0.3244997 0.9360032 -0.05074065 0.3483154 0.4868026 -0.513422 0.7066973 0.6986375 -0.4543292 0.5527121 -0.366618 -0.9272905 0.07565355 0.9591944 -0.03705906 0.2803084 0.9970114 -0.05994063 0.04874032 -0.3647406 -0.9277924 0.07852077 0.2002142 -0.568073 0.7982528 0.1787045 -0.9140034 0.3642288 -0.1870661 -0.7481045 0.6366679 0.7113925 -0.332099 0.6193796 0.9002285 0.05974829 0.431299 0.9730402 -0.2282612 0.03301316 0.94095 0.3362436 -0.03941237 0.9844909 0.1730127 -0.02905684 0.9928647 0.1133084 -0.03716182 -0.7048978 -0.6942834 0.1452228 0.9613913 0.2549741 0.1035134 0.999779 0.0126211 0.01681411 0.9902083 0.1392028 -0.0104978 0.9922839 0.1211212 -0.02650296 0.7042478 -0.06135284 0.7072983 0.7239521 -0.08034116 0.685156 0.6983569 -0.06705141 0.7126021 0.7075543 -0.1746249 0.6847431 0.6875606 -0.2029415 0.6971909 0.6896713 -0.3566929 0.6301776 0.660143 -0.2899693 0.6929134 0.7391242 -0.2969423 0.6045832 0.659618 -0.292375 0.6924024 0.7135634 -0.467945 0.5213969 0.5224366 -0.7449336 0.4148904 0.562367 -0.622181 0.5446413 0.5389438 -0.6397625 0.5479448 -0.1650041 -0.6948294 0.6999899 -0.1721704 -0.7020143 0.6910379 -0.296572 -0.6659918 0.6844707 -0.3183932 -0.6728965 0.6677097 -0.4518482 -0.6214181 0.6400569 -0.4581964 -0.6214816 0.6354659 -0.6628969 -0.3759046 0.6475055 -0.5342051 -0.5139497 0.6711787 -0.4940941 -0.6083242 0.6211383 -0.697804 -0.07751375 0.7120823 -0.9061352 -0.3123813 -0.2851964 -0.7172728 -0.1574089 0.6787799 -0.5739915 -0.07081013 0.8157939 -0.6710349 -0.1832858 0.7184139 -0.6374457 -0.3846909 0.6675896 -0.7220277 -0.4327798 0.5397941 0.1151524 0.9931565 -0.01949805 0.1239578 0.9922873 -6.73406e-4 -0.07000857 0.9917713 -0.1071851 -0.0679205 0.991501 -0.1109617 -0.04278165 0.9915738 -0.1222754 -0.04209762 0.991507 -0.1230517 -0.01424241 0.9915308 -0.1290884 0.01422011 0.9915562 -0.1288958 0.01463288 0.9915258 -0.1290833 0.04209452 0.9915074 -0.1230499 0.04277229 0.9915734 -0.1222823 0.06837427 0.9914932 -0.1107528 0.2103157 0.9718128 -0.1065233 0.04527235 0.9962331 -0.07396161 -0.1653037 0.9857109 -0.03238445 -0.1740404 0.9846473 -0.01340448 0.1215655 -0.4375817 0.8909232 -0.7824028 -0.2745493 0.5589889 0.5069887 -0.2129981 0.8352211 0.4330044 -0.2010571 0.8786827 -0.875782 -0.1192691 0.4677402 -0.9418965 -0.02902972 0.3346465 -0.9712265 0.01020163 0.237939 -0.7445402 -0.1339588 0.6539992 -0.3530753 -0.2099598 0.9117317 -0.356702 0.1562464 0.9210597 0.110721 -4.31915e-6 0.9938516 0.5562127 -0.07181793 0.8279311 0.3573098 0.1461005 0.9224882 0.7510414 0.025141 0.6597764 0.9710683 -0.02064198 0.2379083 0.8484088 -0.1308462 0.5129153 0.8678233 -0.1354776 0.4780468 -0.4048344 -0.2260442 0.8860098 -0.7133364 -0.060602 0.6981968 -0.5534311 -0.1223077 0.8238659 -0.1083631 -0.2059153 0.9725515 -0.2137928 -0.3760545 0.9015962 0.782373 -0.2746481 0.558982 0.015531 0.9904449 -0.1370318 -0.09152913 -0.9255646 0.367359 -0.09961742 -0.9288843 0.3567219 -0.162343 -0.9261409 0.3404524 -0.9997835 -0.01465904 0.01476764 0.7275759 7.39232e-7 0.6860272 0.7263327 -6.49982e-5 0.6873434 0.6954023 3.81417e-4 0.7186205 0.7153871 0.002266645 0.6987247 0.6999038 4.60439e-6 0.7142372 0.6315554 -0.002503454 0.7753267 0.6148208 -0.006632685 0.788639 0.5668371 0.001422405 0.8238287 0.4715675 0.008821845 0.8817859 0.4264562 -0.001268327 0.9045074 0.4857826 -0.001645982 0.8740782 0.4918571 0 0.8706759 0.4415683 -0.03337556 0.8966068 0.4167242 -0.06069928 0.9070042 0.4558042 -5.24582e-4 0.89008 0.3554621 7.62318e-5 0.9346908 0.3920073 0.002701163 0.9199582 0.3657767 0.03910827 0.9298807 0.322727 -0.009053826 0.9464488 0.2724107 -0.04837489 0.9609643 0.2800182 -0.03618669 0.9593125 0.1562021 0.02802312 0.9873275 0.09442484 -0.04776018 0.9943857 0 0.03383982 0.9994273 -0.09442496 -0.04775863 0.9943858 -0.1562018 0.02802222 0.9873276 -0.2684122 -0.03007036 0.9628348 -0.3746393 -0.1566197 0.9138466 -0.2801734 -0.01406919 0.9598463 -0.3741711 0.002496123 0.9273563 -0.4835759 0 0.8753026 -0.4715933 0.008809924 0.8817722 -0.4280501 -0.01026046 0.9036969 -0.4896407 -0.001503765 0.871923 -0.4556706 -0.02415466 0.8898207 -0.5389024 3.43773e-4 0.8423682 -0.6557487 -0.02015483 0.7547103 -0.6148345 -0.003781855 0.7886472 -0.6950608 3.79409e-4 0.7189509 -0.7273753 -8.15432e-5 0.6862399 -0.7263069 0 0.6873706 -1.95194e-6 1 -2.48458e-5 -1.95193e-6 1 2.03044e-6 -2.45848e-6 1 -2.5572e-6 -2.45837e-6 1 1.99401e-6 0 1 2.03182e-5 0 1 -1.3574e-6 0 1 1.46475e-6 0 -1 6.31453e-6 -0.3275347 0 0.9448391 -0.3275162 3.14031e-6 0.9448456 -0.07958555 -6.73445e-6 0.9968281 -0.07951301 6.7351e-6 0.9968339 0.1735875 6.27848e-7 0.9848185 0.1736083 6.27851e-6 0.9848148 0.4153171 1.25622e-6 0.9096767 0.4152984 -6.28144e-7 0.9096853 0.6303045 -5.02523e-6 0.7763481 0.6303653 0 0.7762988 0.8050445 -2.51149e-6 0.5932145 0.8050652 5.02211e-6 0.5931865 0.9283186 -1.00233e-5 0.3717857 0.9283615 1.0022e-5 0.3716786 0.9919646 -1.00499e-5 0.126516 0.9919711 0 0.1264653 0.327549 0 0.9448342 0.327513 0 0.9448466 0.07960546 0 0.9968265 -0.415295 -1.25628e-6 0.9096868 -0.6303404 -1.25626e-6 0.7763189 -0.6302809 0 0.7763673 -0.8050472 0 0.5932108 -0.8050472 0 0.5932108 -0.9919634 0 0.1265257 -0.9919646 0 0.1265156 0.3232126 0.1619968 0.9323576 0.1810331 0.3289416 0.9268358 0.184368 0.3297136 0.9259036 0.07847672 0.1685382 0.9825662 -0.159455 0.3951819 0.9046576 -0.04530227 0.9315398 0.3608065 -0.174589 0.8633994 0.4733501 -0.4005866 0.2640361 0.8773912 -0.3237472 0.352005 0.8782256 -0.2226132 0.9204893 0.3211584 -0.5800468 0.3912677 0.7144616 -0.7805791 0.244649 0.5751898 -0.6942726 0.3619258 0.6220894 -0.2604711 0.9344742 0.2427198 -0.2706961 0.9316076 0.2425511 -0.3349846 0.9210141 0.1987925 -0.8562552 0.3863052 0.3429216 -0.3237393 0.9400035 0.1076404 -0.3640657 0.9269699 0.09046077 -0.9669717 0.2230598 0.1233299 -0.9754656 0.1940457 0.103987 -0.8142781 0.5440774 0.2023139 -0.5472675 0.8189943 -0.1724721 -0.1950362 0.9805729 0.0209214 -0.3232564 0.1610867 0.9325001 -0.07827818 0.1788802 0.9807519 -0.1833869 0.3286159 0.9264885 -0.1849232 0.3284342 0.9262475 0.1593427 0.3968459 0.9039488 0.3865718 0.3653618 0.8468017 0.3285615 0.3081375 0.8928039 0.03931218 0.930907 0.3631347 0.1814484 0.8602703 0.4764572 0.2225986 0.920499 0.3211412 0.580243 0.3906866 0.7146202 0.2665967 0.9312395 0.2484336 0.2664141 0.9335923 0.2396434 0.7469158 0.3730921 0.550381 0.7082531 0.3041261 0.6370911 0.3350259 0.9209915 0.1988278 0.8563929 0.3859483 0.34298 0.3567547 0.9266382 0.1186075 0.3222737 0.9460151 0.03456979 0.5503025 0.8236308 0.137112 0.9246653 0.3031751 0.230389 0.8166505 0.5456643 -0.1879696 0.9731957 0.1936072 0.1241229 0.3273859 0.03110289 0.9443788 0.07822322 -0.1843942 0.9797347 0.02498722 -0.1189305 0.9925881 -0.1666514 -0.2797943 0.9454853 -0.1961208 -0.2753227 0.9411345 -0.3827057 -0.3884672 0.83823 -0.6123507 -0.2370259 0.7542185 -0.6466637 -0.3296902 0.6878447 -0.1073997 -0.9363869 0.3341331 -0.2087697 -0.9238782 0.3207247 -0.2957175 -0.8938161 0.3371111 -0.345305 -0.8654537 0.36298 -0.3200525 -0.922379 0.2162945 -0.7414488 -0.3895595 0.5463489 -0.3466394 -0.9248387 0.1565713 -0.3362553 -0.9377008 0.0874626 -0.2987656 -0.9539883 0.02540749 -0.1945886 -0.9782513 -0.07183104 -0.5490779 -0.8217259 0.1525779 -0.9094717 -0.2004799 0.3642377 -0.9021558 -0.3510975 0.2506904 -0.8166311 -0.5456895 -0.1879807 -0.9732011 -0.1935793 0.1241236 0.5576379 7.51474e-7 0.8300844 0.557638 7.51474e-7 0.8300844 0.1108116 1.25248e-7 0.9938415 -0.3611443 0 0.93251 -0.7513202 0 0.6599379 -0.7512923 1.00196e-6 0.6599697 -0.5576122 0 0.8301017 -0.5576199 -1.00193e-6 0.8300965 -0.110875 -1.62822e-6 0.9938344 -0.1108064 2.25436e-6 0.9938421 0.361142 5.00963e-7 0.9325108 0.3611582 -2.50493e-7 0.9325046 0.7512848 -1.00186e-6 0.6599782 0.7512966 0 0.6599647 0.9712749 0 0.2379607 0.9712747 0 0.237961 -0.5562368 -0.06918132 0.8281392 -0.5763472 -0.146318 0.8039994 -0.5728635 -0.14177 0.8072972 -0.5029347 -0.1015777 0.8583348 -0.5349435 -0.1696748 0.8276751 -0.3679262 -0.4636331 0.806024 -0.4224179 -0.4853927 0.7654783 -0.2873509 -0.5379242 0.7925068 -0.1088883 -0.1910635 0.9755194 0.04712641 -0.2458049 0.9681731 -0.0766834 -0.5207398 0.8502645 -0.3118429 -0.7055487 0.636361 0.03120106 -0.8382958 0.5443221 0.2198841 -0.6633877 0.7152397 0.3478258 -0.2696009 0.8979602 0.6574984 -0.3258451 0.6793534 0.008529186 -0.9368405 0.3496529 -0.01760828 -0.7925553 0.609546 -0.1933844 -0.8588166 0.4743801 -0.06004387 -0.9436027 0.3255898 0.7144407 -0.3091722 0.6276839 0.6160475 -0.7053889 0.3505883 0.4061797 -0.890061 0.2069048 0.3384894 -0.9396987 0.04890048 0.4446636 -0.8874267 0.1214423 0.9409967 -0.2477312 0.2305526 0.815414 -0.5788037 -0.00930339 0.9582869 -0.2445883 0.1478614 0.118026 -0.965727 0.2311738 0.4715322 -0.01438325 0.8817316 0.412339 -0.3059516 0.8581201 0.2931747 -0.7044059 0.6464217 0.1430625 -0.9533309 0.2658821 0.3391804 -0.3852117 0.8582358 0.1304555 -0.9094468 0.3948265 0.07104367 -0.9424946 0.3265838 0.0543124 -0.7523027 0.6565752 0.2044921 -0.3714818 0.9056403 0.03996741 -0.7316387 0.68052 0.01607573 -0.9880259 0.1534491 -0.03997969 -0.7315848 0.6805772 -0.01607775 -0.9880258 0.1534489 -0.07104778 -0.9424942 0.3265836 -0.1304734 -0.909444 0.394827 -0.4424511 -0.1168897 0.8891422 -0.1419802 -0.950008 0.2780762 -0.1385004 -0.9539611 0.2660372 -0.2931624 -0.7044206 0.6464112 -0.4555909 -0.2584397 0.8518486 0.5562838 -0.06906259 0.8281176 0.5464311 -0.07520049 0.8341212 0.5760222 -0.1381741 0.8056714 0.491858 -0.3073638 0.8146185 0.5331549 -0.2320942 0.8135589 0.5242691 -0.2285705 0.8203033 0.4866642 -0.2608661 0.8337307 0.226194 -0.4301882 0.8739418 0.1192969 -0.1963207 0.9732556 0.1085587 -0.1969413 0.9743866 0.2952621 -0.7045485 0.6453152 0.3609424 -0.637109 0.681038 0.2607138 -0.5979807 0.7579233 0.008400857 -0.5754423 0.8177993 -0.2890245 -0.2736122 0.9173884 -0.1371408 -0.6223332 0.7706451 -0.3474891 -0.2725104 0.8972121 3.39265e-4 -0.9540952 0.2995033 -0.06953859 -0.8381032 0.5410615 0.1195395 -0.9101155 0.3967369 -0.379635 -0.7014769 0.6031645 -0.2014105 -0.8733112 0.4435782 -0.6472467 -0.3049449 0.6986275 -0.4819357 -0.6994797 0.5276989 -0.2139152 -0.9764378 -0.02845585 -0.4322341 -0.8915166 0.1355434 -0.7187637 -0.2910695 0.6313932 -0.6910665 -0.679261 0.2470458 -0.4514328 -0.8852335 0.1121171 -0.9365108 -0.2651551 0.2294348 -0.9238849 -0.2623649 0.2785705 -0.7754824 -0.6209607 0.1141712 0.08395135 -0.4719861 0.8775998 0.07371973 -0.3143962 0.9464252 0.03183543 -0.7180108 0.6953036 0.05569863 -0.9124087 0.4054726 0.06149959 -0.8951037 0.4415962 0.06956887 -0.9881621 0.1367331 0.0124498 -0.9194352 0.3930448 3.90352e-6 -1 9.41801e-6 5.20875e-7 -1 -2.04363e-6 6.27698e-7 -1 -1.19883e-6 6.63163e-7 -1 -7.93599e-7 -4.10701e-5 0 1 1.6059e-5 0 1 -6.87323e-6 0 1 9.01135e-6 0 1 -1.5586e-5 -7.84104e-6 1 -3.63556e-6 2.30426e-6 1 7.9493e-6 2.76238e-6 1 0 1.83106e-6 1 -4.86664e-6 3.04165e-7 1 -3.65032e-6 5.80305e-7 1 3.99102e-6 6.54716e-7 1 -2.66633e-6 4.07785e-7 1 -4.11585e-6 1.41935e-7 1 0 5.72204e-6 1 0.04408562 -0.7186193 0.6940049 -0.04408627 -0.7186175 0.6940068 0.1970235 -0.3283075 0.9237944 -0.1148472 -0.9055498 0.4083991 0.3531469 -0.8725537 0.3375462 0.1973826 -0.8019873 0.5637878 -0.1888833 -0.6710017 0.7169936 -0.2527742 -0.650106 0.7165665 0.1260037 -0.6533983 0.7464541 -0.2126874 -0.2951406 0.9314806 -0.2042734 -0.3007056 0.931584 0.1040272 -0.3002272 0.9481782 -5.57729e-5 -0.1876331 0.9822393 0.2625852 -0.1267632 0.956546 0.2700747 -0.137165 0.9530192 -0.2703427 -0.1375407 0.952889 5.57729e-5 -0.1876352 0.9822388 -0.1040279 -0.3002293 0.9481775 0.2042766 -0.3006989 0.9315853 0.2126827 -0.2951478 0.9314795 -0.1260026 -0.6533963 0.7464561 0.2527777 -0.6501016 0.7165693 0.1888809 -0.6710066 0.7169897 -0.1973828 -0.8019837 0.5637928 -0.3531537 -0.8725557 0.3375337 0.1148489 -0.9055485 0.4084015 -0.1970813 -0.3274838 0.9240744 -0.01244151 -0.919433 0.3930501 -0.06952518 -0.9881662 0.1367257 -0.06146055 -0.8951021 0.4416051 -0.05566406 -0.9124087 0.4054775 -0.03181552 -0.7180086 0.6953067 -0.07368135 -0.3143103 0.9464566 -0.2046101 -0.3709416 0.905835 -0.05429589 -0.7522495 0.6566374 -0.3395892 -0.3843276 0.8584704 0.9732064 -0.1935856 0.1240735 0.8166108 -0.5456638 -0.188143 0.9023569 -0.3499321 0.2515942 0.9094913 -0.2006037 0.3641209 0.5490273 -0.8216667 0.1530783 0.1945943 -0.9782637 -0.0716477 0.2984476 -0.9540886 0.02538162 0.3363667 -0.9375879 0.08824169 0.3466362 -0.9248397 0.1565722 0.7418124 -0.3885729 0.5465579 0.3200497 -0.9223806 0.2162926 0.3452997 -0.8654575 0.3629759 0.2957094 -0.8938256 0.3370933 0.208776 -0.9238727 0.3207365 0.1073966 -0.9363908 0.3341233 0.6468907 -0.3287454 0.6880835 0.6125394 -0.2361295 0.7543464 0.3827741 -0.3879532 0.8384369 0.1960179 -0.2749704 0.941259 0.1666682 -0.279492 0.9455718 -0.02492833 -0.1190567 0.9925745 -0.07813513 -0.1847241 0.9796796 -0.3273875 0.02956396 0.9444276 -0.366091 0.03954058 0.9297386 -0.3923577 0.003085732 0.9198076 -0.4278044 -9.70372e-4 0.9038708 -0.7175811 0.002586185 0.6964702 -0.6999162 0 0.7142251 -0.9997621 -0.02027523 0.008047997 -0.1050825 0.9935915 0.04163748 0.009287655 0.9989368 0.04515779 -0.07535785 0.9953442 -0.0600931 0.04501128 0.9983414 -0.03589534 -0.07723855 0.9952924 -0.05854493 0.04527288 0.9983851 -0.03431439 0 1 -3.96134e-6 0 1 1.76811e-6 1 -1.23874e-4 0 -0.543058 0.839695 4.81564e-4 -0.8264393 0.563026 3.26399e-4 -0.9801963 0.1980285 0 -0.9803798 0.1952774 0.02687489 0.4829752 0.8754935 -0.01568573 0.552717 0.8333691 -1.38711e-4 0.8264394 0.5630257 3.26037e-4 0.9800179 0.1989096 1.65037e-4 0.9659219 -0.2588335 0 0.7070871 -0.7071101 0.004824459 0.2587996 -0.9659243 0.003612041 -0.2588242 -0.9659245 0 -0.7070856 -0.7071117 0.004823327 -0.9659214 -0.2588106 0.003612875 -0.5393827 0.8339684 0.1164609 -0.8263171 0.5628948 -0.01869899 -0.8509969 0.5205001 0.06988495 -0.9828308 0.1844589 -0.004311978 0.6048113 0.7911733 0.09082007 0.8263233 0.5628854 -0.0187093 0.8509936 0.5205033 0.069902 0.9800152 0.1989188 -0.001196682 -0.3826013 0.9238361 0.01196557 -0.6054936 0.7920593 -0.07758605 -0.982422 0.1831318 0.03619015 -0.8434682 0.5313514 -0.07891225 -0.9204171 0.3813195 -0.08618438 -0.3511031 0.9344635 0.05920141 -0.7671253 0.4246752 0.4808014 -0.30855 0.9234274 0.2282076 -0.3523108 0.909461 0.2208118 -0.768274 0.3935215 0.5048722 -0.1669273 0.9277191 0.333875 -0.2949079 0.4132785 0.8615279 -0.3027046 0.4024117 0.8639647 -0.1389532 0.9074012 0.3966298 0.002523839 0.9349589 0.3547472 0.2963587 0.4032523 0.8657708 0.3010104 0.4138914 0.8591198 0.1392916 0.9069396 0.3975657 0.1703311 0.928636 0.3295797 0.7682684 0.3935372 0.5048685 0.349474 0.9026596 0.2511447 0.7671205 0.4246799 0.4808049 0.3527261 0.9340001 0.05681711 0.9204785 0.383482 -0.07523989 0.6135499 0.7808734 0.1174457 0.4356908 0.8971719 -0.07250112 0.9823441 0.1835767 0.03605121 0.8434673 0.5313539 -0.07890462 0.6050399 0.7904077 0.09582602 0.4783669 0.8781304 -0.007226884 0.9978135 0 -0.06609296 0.997798 -1.25194e-4 -0.06632816 -0.8357062 0 0.5491769 -0.323853 0 0.9461075 -0.3238531 0 0.9461074 0.3238514 0 0.946108 -0.9970437 0.005227029 -0.07665872 -0.9977977 0 -0.06633216 -0.9644939 -0.258421 -0.05449843 -0.6995447 -0.6995636 0.1457675 -0.6235514 -0.6657878 0.4097685 -0.2084822 -0.765229 0.6090648 0.2084813 -0.7652282 0.6090662 0.623553 -0.6657857 0.4097695 0.9644863 -0.2584495 -0.05449891 0.6995447 -0.6995636 0.1457672 0 1 1.39909e-6 -0.1872045 0.9823209 -4.94347e-4 -0.6798595 -0.715054 0.1627544 0.2588017 -0.9659305 0 0.6798594 -0.7150544 0.1627527 0.680618 -0.4674216 0.5641598 0.684151 -0.4691834 0.5583946 -0.06979513 0.991136 -0.11304 0.4937724 -0.5547939 0.6696213 -0.8891696 -0.2823281 0.3600952 -0.06967383 0.9911667 -0.112846 1 0 -5.2395e-5 -0.5555935 0.8314541 -3.21888e-4 -0.8314814 0.5555528 -1.63858e-4 -0.9807841 0.1950969 1.67725e-4 0.1950917 0.9807808 0.002891421 0.5555554 0.8314796 -3.21513e-4 0.8314709 0.5555682 -1.62751e-4 0.9807818 0.1951081 -5.13732e-5 0.9807748 -0.195084 0.004795193 0.8314688 -0.5555663 -0.002417623 0.5555701 -0.8314662 -0.002418398 0.1950905 -0.9807853 0 -0.1950844 -0.9807748 0.004794239 -0.5555857 -0.8314559 -0.002417564 -0.8314639 -0.5555737 -0.002418637 -0.9807841 -0.1950969 0 -0.1950758 0.9807882 0 -0.4398642 0.8976948 0.02575904 -0.3430797 0.9296294 -0.1344832 -0.1209133 0.9899573 -0.07324415 -0.9531854 0.2032546 0.2238866 -0.9473337 0.2911731 0.1333307 0.1918236 -0.8630234 0.4673269 -0.1259078 -0.5479844 0.8269586 -0.1824608 -0.6903202 0.7001187 -0.2695353 -0.7382375 0.6183496 -0.04402703 -0.7844851 0.6185829 0.3448712 -0.8710669 0.3497232 -0.2490481 -0.6207319 0.7434158 -0.5327387 -0.6768707 0.5079721 -0.4865656 -0.6858842 0.5411255 -0.9643621 -0.1841322 0.1900032 -0.9393294 -0.2293927 0.2550281 -0.9744558 0.2097574 0.0802353 -0.9417713 -0.1188889 0.3145352 -0.471988 -0.5159836 0.7148344 -0.5530089 -0.4998648 0.6665707 -0.107047 -0.9371785 0.3320203 -0.08362579 -0.9754936 0.2035164 -0.9561833 0.278514 0.09024131 0.8183959 -0.5591328 0.1326608 0.2641203 -0.9384379 0.2226537 0.3083098 -0.9294108 0.2028322 0.3333425 -0.9270871 0.1714425 0.4158322 -0.9039104 0.100148 -0.0201013 -0.9983823 0.05318695 -0.2465073 0.9682106 -0.04245507 -0.2326105 0.9725036 -0.01136696 -0.2238139 0.9730722 -0.05511879 -0.179786 0.9814466 -0.06663066 -0.09303051 0.9914761 -0.09121805 -0.1322363 0.9512194 0.278739 -0.1913794 0.9384491 0.2875542 -0.2423986 0.9549323 0.171311 -0.1703892 0.9612234 0.2168343 -0.170974 0.9616594 0.2144276 -0.214473 0.9610535 0.174292 -0.2146787 0.9620076 0.1686846 -0.2470538 0.9608834 0.1251707 -0.245663 0.9626376 0.1139242 -0.26771 0.9606189 0.07445025 -0.2631568 0.9632421 0.05397623 -0.2767165 0.9606146 0.02544921 -0.2688905 0.9631384 -0.007906079 -0.2554128 0.9665963 0.02135545 -0.06977128 0.9915631 -0.1092462 -0.3400449 -0.6262983 0.7015125 -0.2235368 -0.5177174 0.8258329 -0.2764627 0.3216268 0.9056074 -0.6454439 -0.570694 0.507652 -0.6437101 -0.5743148 0.5057665 -0.8400881 0.2612391 0.475401 -0.6797994 0.6452875 0.3485353 -0.8839502 0.08803063 0.4592198 -0.8141434 0.3264344 0.4802199 -0.7574713 0.3963568 0.5187858 -0.5314271 -0.5620051 0.6338263 -0.49642 -0.6743949 0.5465882 -0.6976424 0.3153098 0.6433311 -0.452665 -0.639333 0.6215688 -0.4963524 0.3667766 0.786835 -0.5515167 0.1910752 0.8119851 -0.4038561 0.4439343 0.7998891 -0.4172129 -0.5408358 0.7303631 -0.7042384 -0.60282 0.3750419 -0.5508995 -0.7064279 0.4443755 -0.9400338 -0.1471344 0.3077144 -0.9538579 0.1967604 0.226805 -0.7761563 0.6074858 0.1689454 -0.8967693 0.4055957 0.1769102 0.3300452 -0.8072382 0.4893227 -0.2001935 -0.568071 0.7982594 -0.1971307 -0.7726789 0.6034126 -0.5600999 -0.4294062 0.708448 -0.7705115 -0.5968961 0.2236676 -0.8949335 -0.3911104 0.214771 -0.8690226 -0.3156638 0.380994 0.4041016 -0.5643867 0.7198401 0.3380058 -0.8513108 0.4012756 0.5200937 -0.7874122 0.3308845 0.1497383 -0.7814201 0.6057733 -0.6730825 -0.653711 0.3458641 -0.7948731 -0.5232976 0.3071425 -0.9338671 0.3528715 -0.05808728 -0.846621 0.5286373 -0.06144428 -0.7798327 0.6256815 -0.01958215 -0.7979602 0.6005228 -0.05130398 -0.7679969 0.6403045 -0.0138157 -0.8011792 0.5893303 -0.1039317 -0.7627705 0.644436 -0.05369722 -0.7271161 0.6859998 0.02658385 -0.7186803 0.6953403 -6.99698e-4 -0.6761894 0.7332347 0.07165735 -0.1938138 -0.8716314 0.4502167 -0.3348661 -0.6711363 0.6613931 -0.1441256 -0.939689 0.3101811 -0.1445418 -0.9396896 0.3099858 -0.1497857 -0.939287 0.3087141 -0.1492024 -0.9378128 0.3134419 -0.148566 -0.937618 0.3143259 -0.1064831 -0.9430903 0.3150271 -0.1649997 -0.9329211 0.3200522 0 1 6.04166e-7 0 1 -5.00094e-7 0 1 1.1898e-6 0 1 -2.00214e-7 0 1 2.18865e-7 0 1 -7.22525e-7 -0.1431156 -0.9386841 0.3136722 -0.5999657 0.7818635 -0.1695013 -0.3586198 0.9302898 -0.07715541 -0.341605 0.9305937 -0.1315351 -0.4758468 0.8778123 -0.05491286 -0.3378086 0.9405955 0.0341413 -0.3705793 0.9288004 -9.99339e-4 -0.2694854 0.9591626 -0.08593559 -0.9987608 0.02242249 0.04443156 -1 2.00674e-6 0 -1 2.10068e-6 0 -0.001180827 -0.9999988 -0.001035928 0.6689701 -0.7179104 0.1925714 0.7136576 -0.6457921 0.271377 0.6746108 -0.6515443 0.3469732 0.6488735 -0.6298767 0.4268708 0.6481448 -0.6266615 0.4326704 0.5822682 -0.648095 0.490853 0.6805571 -0.5790713 0.4489082 -0.5587527 0.8293179 -0.005236923 -0.6304171 0.7734392 -0.0660777 -0.6232809 0.7819285 -0.01042681 -0.6235331 0.781615 -0.01686447 -0.5816636 0.8124362 0.04018729 -0.5818997 0.8114981 0.0535137 -0.5660055 0.8204928 0.08018398 -0.5820387 0.8125513 0.03148514 -0.5772525 0.8084238 0.115024 -0.5437502 0.8255088 0.1512322 -0.5412142 0.8206722 0.1832606 -0.4846042 0.8395704 0.2455208 -0.5106952 0.8274887 0.233352 -0.4737935 0.8160199 0.3311064 -0.4043738 0.8535223 0.3286055 -0.3968793 0.8348701 0.3814169 -0.3206759 0.8547791 0.4080683 -0.3303018 0.84811 0.4142587 -0.2594583 0.826846 0.4990063 -0.2167979 0.862659 0.4569661 2.42425e-4 -1 -3.1378e-5 -0.001078903 -0.9998143 0.01923877 -0.2663807 -0.9281532 0.2599482 -0.2226713 -0.9283232 0.297714 0.09301066 0.9914767 -0.09123086 0.1393759 0.9861054 -0.09039157 0.1375467 0.9871779 -0.08099925 0.1494146 0.9872229 -0.05537468 0.06819528 0.9915382 -0.1104601 0.07177078 0.9910705 -0.1123766 0 1 -1.44673e-6 0 1 1.0933e-6 0 1 0 0 1 -6.40653e-7 0 1 1.6673e-7 0 1 5.85521e-7 0 1 -5.62779e-7 -0.008570611 -0.9999616 0.001845777 -0.00804603 -0.9999645 0.002516269 -0.007454454 -0.9999673 0.003172993 -0.006781458 -0.9999697 0.003813982 -0.006014466 -0.9999721 0.004433333 -0.005139827 -0.9999743 0.005015671 -0.004145205 -0.9999762 0.005542099 -0.003020942 -0.9999776 0.005984306 0.3253074 0.8608788 0.3912326 0.3353319 0.840389 0.4257922 0.2328515 0.8649798 0.4445111 0.2502908 0.8126875 0.526207 0.1764578 0.8381843 0.5160521 0.1081538 0.843666 0.5258616 0.1118743 0.8617493 0.4948459 2.93948e-4 0.8386362 0.5446921 -0.009138107 -0.9999578 0.001009166 -0.006300747 -0.9999617 0.006076276 0.1039838 -0.9435226 0.3145671 0.07082647 -0.9362012 0.3442546 -0.005549609 -0.9507322 0.3099638 0.0452339 -0.9048654 0.423288 0.2568309 -0.8716326 0.417486 0.1445409 -0.9396916 0.30998 0.1273748 -0.941538 0.3119006 0.189134 -0.9183688 0.3476018 0.3039706 0.3429703 0.8888044 0.2804107 0.2789239 0.9184614 0.1553157 -0.6371582 0.7549216 0.2523795 -0.5058095 0.8249008 0.1803311 0.4458267 0.8767665 0.02352958 0.3836879 0.9231631 0 -0.5819066 0.8132557 0.4301431 -0.544819 0.7198258 0.3903653 -0.6076905 0.6916121 0.532432 0.4040668 0.7438052 0.4447466 0.03825753 0.8948391 0.4621858 0.5201829 0.7181881 0.2946108 -0.6401264 0.709537 1.71357e-4 0.9474398 0.3199343 0.1638165 0.9545846 0.2488626 0.1373203 0.9475179 0.2887093 0.2419497 0.9550979 0.1710216 0.1705617 0.9612518 0.2165725 0.1710535 0.961623 0.2145273 0.2145774 0.9610776 0.1740304 0.2147516 0.9619802 0.1687477 0.05806726 -0.9880309 0.1429097 0.06865692 -0.9834015 0.1679516 0.03294652 0.9525738 0.3025193 0.07027983 0.9478479 0.3108783 0.09368062 0.9526406 0.2893094 0.09771579 -0.9210404 0.3770098 0 1 3.02083e-7 0 1 0 -0.04460233 0.9908385 -0.1274741 0.02095043 0.9922779 -0.1222524 0.04459172 0.9908376 -0.1274852 0.04751843 0.9919 -0.1177978 -0.1672682 -0.9285652 0.3313428 -0.03233128 0.9524927 0.3028405 -0.07020837 0.9474694 0.3120462 -0.09561145 0.9524602 0.289272 -0.2322027 -0.6087521 0.7586191 -0.131628 0.4609077 0.8776322 -0.01399797 -0.6233036 0.7818546 0 0.3165827 0.948565 9.45799e-4 0.9999995 -2.75796e-4 -0.105062 -0.942558 0.3170905 -0.0928263 -0.9347615 0.3429346 -0.03533929 -0.9430724 0.3307045 -0.1682178 0.8287453 0.5337454 -0.1321673 0.7983928 0.5874528 -0.06548112 0.8972913 0.4365556 0.01265805 0.8676763 0.4969684 0.04879575 -0.9986239 0.01921677 0.5249837 -0.6555281 0.5428399 0.1279134 -0.6148375 0.7782114 -0.8030136 -0.2009384 0.5610642 0 1 -8.31664e-7 0 1 -9.83897e-7 0 1 0 0 1 7.65709e-7 0 1 -7.57987e-7 -3.01003e-5 1 -1.88166e-5 1.63584e-4 1 4.54989e-5 4.78764e-4 0.9999999 8.98074e-5 7.1691e-5 1 -5.39712e-6 5.06954e-5 1 -9.53093e-6 -0.001268386 0.9999992 -3.54914e-4 -1.60798e-5 1 1.45829e-4 -5.2518e-5 1 1.53517e-4 -1.03263e-4 1 1.6907e-4 -1.27595e-4 1 1.77463e-4 3.25689e-5 1 -3.72173e-5 0 1 0 2.84776e-6 1 -2.85893e-5 2.17876e-5 1 -1.35249e-5 7.19316e-6 1 -2.50632e-5 1.11396e-5 1 -2.28981e-5 1.51282e-5 1 -1.96002e-5 0 -1 0 3.2689e-4 -1 1.88933e-4 -3.01921e-5 -1 -2.04903e-4 1.37127e-4 1 -7.66889e-5 2.13542e-4 1 -1.98559e-4 0 1 1.34263e-6 5.76875e-5 1 9.98095e-5 1.45004e-4 1 7.02342e-5 -0.0011065 0.9999994 2.04763e-4 -6.36644e-6 1 -1.73212e-5 -7.17073e-6 1 -1.70257e-5 -7.13223e-6 1 0 -6.94155e-6 1 7.56691e-6 -7.38992e-6 1 7.46295e-6 0.1119688 0.9937118 1.68058e-5 0.111816 0.9937289 8.69787e-6 3.66604e-4 1 1.40831e-4 0 1 4.09e-5 3.94434e-4 1 7.33121e-5 0 1 1.78667e-7 2.00161e-5 1 -1.12762e-5 4.4736e-7 1 0 1.78804e-5 1 -1.23145e-5 1.46971e-5 1 -3.01984e-5 0 1 9.08734e-7 -4.44284e-4 0.9999995 9.59907e-4 1.71729e-5 1 -1.4339e-5 1.71315e-5 1 -1.41936e-5 -7.9937e-4 0.9999997 -3.51273e-5 0.001091003 0.9999983 -0.00155431 2.13319e-5 1 -2.31298e-5 0.8296459 0 0.5582902 -0.8980236 -0.2616399 0.3536926 -0.9494912 -0.1210009 0.2895259 -0.8980271 -0.2616347 0.3536873 -0.949492 -0.1209999 0.2895236 -0.8980311 -0.2616292 0.353681 -0.9494931 -0.1209968 0.2895216 -0.06814444 -0.9965406 0.04757255 -0.1110144 -0.9912123 0.07193052 -0.1983147 -0.9699551 0.1409199 -0.2912737 -0.9351806 0.2014865 -0.3265832 -0.9166823 0.2302979 -0.4278199 -0.85344 0.2976753 -0.4369035 -0.8460813 0.3053884 -0.5801893 -0.7071943 0.4040504 -0.5580003 -0.7372873 0.3808454 -0.6899606 -0.5318908 0.4909651 -0.6509934 -0.6135658 0.4469279 -0.7514291 -0.3899708 0.532238 -0.7348878 -0.446139 0.5107837 -0.7939811 -0.2380669 0.559391 -0.7883638 -0.2750521 0.5502989 -0.8158121 -0.08005833 0.5727491 -0.815621 -0.09274435 0.5711051 -0.8165264 0.08000856 0.5717371 -0.8107988 0.1233395 0.5721825 -0.7965629 0.2380096 0.5557328 -0.7738796 0.3242682 0.5440226 -1.32173e-5 4.68658e-4 -0.9999999 -4.40064e-5 4.3556e-4 -1 0.4188722 0.003536522 -0.9080383 0.2125791 -0.01145368 -0.9770768 0.8668085 -0.006250202 -0.4986021 0.9189638 4.36298e-4 -0.3943418 0.9014806 0.005701541 -0.4327822 -0.9197242 -4.96325e-4 -0.3925648 -0.9988456 -0.03721529 -0.03037142 -0.9955021 -0.04019302 0.08579266 0.05326783 -8.75462e-5 -0.9985803 -0.4010694 -0.05433034 -0.9144352 0.01734858 0.01334506 -0.9997605 0.009241819 0.01646214 -0.9998218 -0.001242101 -0.002269923 -0.9999967 0.01311069 0.001632452 -0.9999128 0.4267706 0.01191771 -0.9042814 0.6719533 0.04612934 -0.7391555 0.9406457 -3.25418e-4 -0.3393899 -0.3213763 0.03813886 -0.9461833 -0.4072002 -0.01936894 -0.9131336 -0.007701277 -0.04993236 -0.998723 0 1 -1.21517e-6 0.01046025 0.9999229 0.006704032 -5.27824e-4 0.9999986 0.001597166 -1.78713e-4 0.9999986 0.001674294 1.82334e-4 0.9999986 0.001673996 5.18477e-4 0.9999986 0.001601278 -0.01046025 0.9999229 0.006702721 0 1 9.14827e-7 0 1 -3.03799e-7 0.0361911 -0.9402177 0.3386456 0.102649 -0.945005 0.3105301 0.11094 -0.943374 0.3126304 0.1227717 -0.9486521 0.2915241 -0.03619098 -0.9402182 0.3386442 -0.1028522 -0.9450126 0.3104398 -0.1226226 -0.9485899 0.2917895 -0.1109283 -0.9433678 0.3126535 -0.1109333 -0.9433687 0.312649 -0.1226149 -0.948591 0.2917889 -0.1028583 -0.9450126 0.3104372 -0.03618699 -0.9402191 0.3386423 0.1227702 -0.9486532 0.2915214 0.1109382 -0.9433727 0.3126351 0.1026554 -0.9450048 0.3105282 0.03618752 -0.9402189 0.3386429 -0.1445484 -0.9396907 0.3099794 0 1 6.07609e-7 0 1 -3.04934e-7 -0.01046061 0.9999228 0.006703138 5.18481e-4 0.9999986 0.001601278 1.82333e-4 0.9999986 0.001674294 -1.78713e-4 0.9999986 0.001673996 -5.27824e-4 0.9999986 0.001597166 0.01046055 0.9999228 0.006704151 0 1 -1.21972e-6 0.01044809 0.9999231 0.006694853 -5.27214e-4 0.9999986 0.001595616 -1.78503e-4 0.9999986 0.001672208 1.82117e-4 0.9999986 0.001672387 5.17885e-4 0.9999986 0.001599192 -0.01044785 0.9999231 0.006695449 0 1 -3.04942e-7 0 1 -6.07595e-7 -0.1109365 -0.9433688 0.3126475 -0.1226224 -0.9485902 0.2917882 -0.03619074 -0.9402182 0.3386445 0.1227715 -0.948652 0.2915245 0.1109402 -0.9433745 0.3126291 0.1026494 -0.9450047 0.310531 0.03619146 -0.9402177 0.3386458 0.1445331 -0.9396932 0.309979 -0.1214787 -0.9360836 0.3301371 -0.144547 -0.9396919 0.3099763 0 1 1.09897e-6 0 1 -1.09901e-6 0 1 2.19793e-6 0 1 -9.5241e-7 0 1 -9.52156e-7 0 1 9.59339e-7 -0.5736157 -4.58335e-7 -0.8191246 -0.573571 0 -0.8191559 -0.5735622 5.72753e-7 -0.8191621 -0.5735751 -9.35991e-7 -0.819153 0.6826881 -0.04833006 0.72911 0.5759342 8.1355e-4 0.8174957 0.58895 -0.01023763 0.8081047 0.5331689 -0.008830964 0.8459628 0 -0.920579 0.3905566 0 -0.9206038 0.3904983 0 -0.9206254 0.3904469 0 -0.9206275 0.390442 0 -0.9206291 0.3904386 0 -0.9206352 0.3904241 0 -0.9206277 0.3904418 0 -0.9206271 0.3904433 0 -0.9206248 0.3904484 0 -0.9206337 0.3904275 0 1 8.75091e-7 0 1 -4.10727e-6 0 1 -2.45366e-6 0 1 2.03994e-6 0 1 -7.99362e-7 0 1 4.31867e-6 0 1 -6.93178e-7 0 1 1.51088e-6 1 0 0 1 -1.99881e-7 0 1 -1.86259e-7 0 1 0 0 1 1.38721e-7 0 1 -1.24541e-7 0 1 2.07847e-7 0 1 -1.26333e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 6.51112e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.67476e-7 0 1 -2.08167e-7 0 1 2.35828e-7 0 1 -2.70312e-7 0 1 -4.43117e-7 0 1 4.3766e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.37803e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.85363e-7 0 -1 1.38721e-7 0 -1 -2.43752e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.08167e-7 0 -1 2.51215e-7 0 -1 0 0 -1 0 0 -1 1.35157e-7 0 -1 6.51115e-7 0 -1.90104e-5 -0.3749045 0.9270635 3.53855e-6 -0.37489 0.9270693 0 -0.3748994 0.9270656 0 0.7071075 0.7071061 0 0.7071063 0.7071073 0 0.8365738 0.5478542 0 0.8365731 0.5478554 0 0.898551 0.4388694 0 0.9561426 0.2929018 0 0.9901912 0.1397194 0 0.9998573 -0.01689833 0 0.9998572 -0.01690053 0 0.9849037 -0.173103 0 0.984904 -0.173102 0 0.9456979 -0.3250472 0 0.9456982 -0.3250463 0 0.8832074 -0.4689828 0 0.7989683 -0.6013732 0 0.7989673 -0.6013746 0 0.6950564 -0.7189553 0 0.6950558 -0.7189558 0 0.5740295 -0.8188347 0 0.4388695 -0.8985508 0 0.2929012 -0.9561427 0 0.2929012 -0.9561428 0 0.1397201 -0.9901911 0 0.1397201 -0.9901911 0 -0.01689922 -0.9998573 0 -0.01689922 -0.9998573 0 -0.1731035 -0.9849037 0 -0.325046 -0.9456983 0 -0.3250458 -0.9456983 0 -0.4689828 -0.8832073 0 -0.601374 -0.7989677 0 -0.718954 -0.6950578 0 -0.8188356 -0.5740282 0 -0.8188362 -0.5740275 0 -0.898551 -0.4388694 0 -0.9561426 -0.2929017 0 -0.9901912 -0.1397194 0 -0.9998573 0.01689833 0 -0.9998572 0.01690053 0 -0.9849037 0.173103 0 -0.9849039 0.173102 0 -0.9456978 0.3250473 0 -0.9456982 0.3250463 0 -0.8832074 0.4689828 0 -0.7989655 0.6013768 0 -0.7989665 0.6013757 0 -0.6371554 0.7707355 0 -0.637155 0.7707358 -0.8910075 0 0.4539886 -0.891008 0 0.4539879 -0.7071043 0 0.7071092 -0.7071043 0 0.7071093 0.7071043 0 0.7071093 0.7071043 0 0.7071092 0.891008 0 0.4539879 0.8910075 0 0.4539886 0.9876884 0 0.1564343 0.9876883 0 0.1564348 -0.9876883 0 0.1564348 -0.9876884 0 0.1564343 -0.4539912 0 0.8910062 -0.4539892 0 0.8910072 -0.4539963 0 0.8910036 0.453992 0 0.8910058 0.4539846 0 0.8910096 0.4539942 0 0.8910046 -0.1564362 0 0.9876881 -0.1564289 0 0.9876893 0.15643 0 0.9876891 0.1564352 0 0.9876883 -0.2631011 -0.9002954 -0.3467652 -0.1796959 -0.906349 -0.3824149 0.334348 -0.8925247 -0.3026732 0.3349564 -0.8920447 -0.3034148 0.9835327 0.1801463 -0.01452398 0.6210286 0.7509599 -0.224461 -0.8998233 0.4325617 -0.05664354 -0.9667052 0.2456487 -0.07167977 0.3670322 -0.8866896 -0.2811921 0.3622159 -0.8894866 -0.2785917 -0.5605934 0.8190392 -0.1221058 -0.04968655 0.9980979 -0.03649336 -0.05698674 0.9765571 -0.2075784 0.16266 0.9844366 -0.06652981 -0.03361511 0.968647 -0.2461568 0.004083454 0.9815452 0.1911867 -0.08374708 0.9277295 -0.3637368 -0.07776176 0.9594801 -0.2708344 -0.06404066 0.9668525 -0.247174 -0.07747 0.9280424 -0.3643293 -0.01831763 0.9874434 -0.1569078 -0.02893555 0.9682158 -0.2484369 -0.00332719 0.9913552 -0.1311637 -0.006734549 0.987677 -0.1563609 0.2011198 0.9709574 -0.1295869 0.1716023 0.9763332 -0.1316294 0.173201 0.8229305 -0.5410978 0.001363396 0.1353878 -0.9907917 0.1497246 0.9839175 -0.09741157 -0.405629 0.9095177 -0.09079104 -0.316255 -0.7470064 -0.5847771 -0.3020465 -0.677889 -0.6702495 -0.06273508 -0.80231 -0.5936017 -0.0675047 -0.8108865 -0.581297 -0.01102149 -0.7962208 -0.6049057 -0.0158571 -0.8094701 -0.5869469 -0.001671433 -0.7905492 -0.6123963 -0.003700077 -0.7970896 -0.6038498 1.70641e-4 -0.7930918 -0.6091021 8.59998e-4 -0.7907761 -0.6121049 3.34939e-4 -0.7952235 -0.6063164 0.001003265 -0.793096 -0.609096 -0.002143561 -0.7944436 -0.6073343 -0.002468287 -0.7953861 -0.6060981 -0.01412522 -0.8018981 -0.5972939 -0.01160174 -0.7952094 -0.606224 -0.03387957 -0.822739 -0.5674089 -0.02379816 -0.8020758 -0.5967479 0.003752768 -0.9964701 -0.08386564 -0.00537616 -0.9975541 -0.06969141 0.006298243 -0.9929191 -0.1186258 -0.002072274 -0.9963544 -0.08528655 0.02330636 -0.9880397 -0.1524287 0.01559203 -0.9929572 -0.1174432 0.167618 -0.9396044 -0.2984088 0.1417362 -0.9620317 -0.2332508 0.1322016 -0.915322 -0.3804059 0.1119063 -0.949243 -0.2939642 0.1266257 -0.900209 -0.416641 0.1169542 -0.9175869 -0.379942 0.1727983 -0.8943608 -0.4126254 0.1732788 -0.8935391 -0.4142009 0.2314541 -0.8948121 -0.3817599 0.2379328 -0.8833972 -0.4037296 0.271546 -0.898977 -0.3436616 0.2801473 -0.8849685 -0.3719521 0.3021169 -0.900515 -0.3127269 0.3104805 -0.8898628 -0.3342844 0.3523783 -0.8875541 -0.2967784 0.3325268 -0.9006499 -0.2797425 0.3331861 -0.8850267 -0.3251382 0.3120599 -0.9013831 -0.3002122 0.3038468 -0.8832855 -0.3570489 0.2832205 -0.9005038 -0.3299686 0.254615 -0.8890826 -0.3803989 0.2408921 -0.9004493 -0.362163 0.1707873 -0.909079 -0.3800094 0.174545 -0.9062883 -0.3849359 0.08180826 -0.9410387 -0.3282588 0.1169403 -0.9170857 -0.3811545 0.04369992 -0.9754717 -0.2157435 0.1121444 -0.9372021 -0.3302665 0.03673708 -0.9990152 -0.02488321 0.06412231 -0.9962092 -0.05878603 0.006486654 -0.9999597 -0.00622791 0.01685124 -0.9995406 -0.02518945 -0.006411135 -0.9999747 0.003084719 3.941e-4 -0.9999712 -0.007583916 -0.01820814 -0.9031013 -0.4290413 -0.03382843 -0.9080421 -0.417511 -0.02090251 -0.8992483 -0.436939 -0.02527123 -0.90266 -0.4296118 -0.02544122 -0.9101434 -0.4135116 -0.0144596 -0.8992779 -0.4371388 -0.02406436 -0.9255183 -0.3779374 -0.007837831 -0.9096472 -0.4153078 -0.01015609 -0.9325473 -0.3609051 -0.002408087 -0.9253288 -0.379158 -1.95964e-4 -0.9331931 -0.3593754 2.69207e-4 -0.9327709 -0.3604698 2.45261e-4 -0.9319823 -0.3625037 -0.001120448 -0.933146 -0.3594958 -0.005510628 -0.9300172 -0.3674748 -0.007530868 -0.9314656 -0.3637515 -0.05347251 -0.9293251 -0.3653705 -0.04481071 -0.9262985 -0.3741165 -0.01270705 -0.9952268 0.0967592 -0.03157055 -0.9962677 0.08033758 -0.01775789 -0.9994752 0.0270946 -0.02328169 -0.9993767 0.02653986 -0.002181887 -0.9999975 -5.30424e-4 -0.01532971 -0.9998383 -0.009405374 -0.01314747 -0.9998692 -0.009429931 -0.03922861 -0.9988954 -0.025873 0.9165164 0.3692579 -0.1537739 0.3680654 0.9170877 0.1532258 0.987372 0.1566114 0.02386635 0.9664543 0.2495845 0.06060969 0.9891315 0.1419847 0.0382027 0.9873234 0.1529161 0.04253619 0.9894106 0.139044 0.04163742 0.9890294 0.1414406 0.04260665 0.9859603 0.1590346 0.05089563 0.9893913 0.138907 0.04253971 0.9491924 0.2986972 0.09906506 0.9860555 0.1602815 0.04477125 -0.2099127 0.9215956 0.3264939 0.954777 0.2888276 0.07056701 -0.9183346 0.3623638 0.1592294 0.158396 0.9537277 0.2555667 0.9562438 0.2925073 0.006112396 0.7768988 -0.5968516 -0.2004906 0.6856722 0.7048334 0.1818339 0.9978555 0.06544679 0.001051008 0.6570678 0.7254196 0.2050083 0.7049594 0.6827739 0.191969 0.7314615 0.6522355 0.1988794 0.6550024 0.7223555 0.2217531 0.7080669 0.6716321 0.2180637 0.7211474 0.6589841 0.2137439 -0.03964489 0.9448269 0.3251627 0.6934807 0.6836228 0.2274737 -0.8301616 0.5209454 0.1986145 -0.1216284 0.9356269 0.3313742 -0.9250524 0.344706 0.1595491 -0.8879563 0.4208752 0.1854664 -0.1087345 0.7297829 0.6749769 -0.1007312 0.9945974 0.02508699 -0.1083323 0.6740674 0.7306827 -0.1149891 0.8354136 0.5374586 -0.0270465 0.9907785 0.1327644 -0.03387826 0.9513012 0.3063959 -0.03683108 0.07128745 0.9967757 -0.0372495 0.619345 0.7842348 0.2061033 0.9772589 -0.04986548 0.2048478 0.9649795 -0.1638655 -0.01687055 -0.06198197 0.9979347 0.1713996 0.801404 0.5730393 0.371371 0.9271211 -0.05030208 0.3663611 0.9167321 -0.1593171 0.2172067 0.9726887 -0.0818423 0.2051789 0.9754435 -0.08007252 -0.001041054 0.9940989 -0.1084736 -0.003308773 0.9966055 -0.08226031 -0.007456183 0.9653831 -0.2607296 -0.01832818 0.9938445 -0.1092582 -0.02517014 0.8004436 -0.5988795 -0.06486183 0.9829284 -0.1721766 -0.26073 0.9646807 -0.03756356 -0.00714904 0.9983414 -0.05712723 -0.2793248 0.9596197 0.03328484 -0.2575873 0.9657527 0.03115463 -0.3380373 0.9344004 0.1123686 -0.334851 0.93557 0.1121767 -0.29172 0.9490829 0.1189166 -0.3467069 0.9300773 0.1214521 -0.1508471 0.9853612 0.07942557 -0.2811547 0.9551535 0.09291988 -0.06495279 0.9971046 0.03954356 -0.1520716 0.9866089 0.05896723 -0.6539103 0.75623 -0.02274864 -0.5363406 0.8430492 -0.04008746 -0.6937384 0.7195252 0.0317896 -0.6647983 0.7465315 0.02709347 -0.6388481 0.7643798 0.08715945 -0.7076966 0.700562 0.09153437 -0.4240108 0.9005413 0.09612768 -0.6376151 0.7632569 0.1043363 -0.2088628 0.9758827 0.06347751 -0.4211513 0.9028652 0.08640545 -0.1316061 0.9905225 0.03930819 -0.2027762 0.9776013 0.0563696 -0.1687934 0.9833432 0.06741708 -0.1478809 0.987251 0.05888038 -0.3022449 0.9347101 0.1869895 -0.2656577 0.9498472 0.1649745 -0.4811589 0.7952733 0.3688179 -0.490535 0.7863144 0.3756128 -0.7822627 0.02323788 0.6225152 -0.6620627 0.4947527 0.5629323 -0.6363098 0.5326976 0.5579813 -0.6569643 0.4890578 0.5737774 -0.05849879 -0.9901745 -0.1270133 -0.04657799 -0.992348 -0.1143513 -0.1087211 -0.988952 0.100766 -0.08806014 -0.9881938 0.1253734 -0.121807 -0.9516453 0.2820187 -0.1287865 -0.9530123 0.2741929 -0.1187016 -0.9268659 0.3561316 -0.1258957 -0.9287317 0.3487231 -0.1281728 -0.9075279 0.3999561 -0.1222209 -0.9054318 0.4065163 -0.1518524 -0.8802543 0.4495477 -0.1368208 -0.8723182 0.4694052 -0.1854301 -0.8438335 0.5035482 -0.1668558 -0.8305785 0.5313178 -0.2157816 -0.8081929 0.5479624 -0.1999549 -0.7959153 0.5714341 -0.2343256 -0.7878445 0.5695548 -0.2236571 -0.7783299 0.5866687 -0.2505379 -0.7746306 0.5806705 -0.2406616 -0.7634437 0.5993628 -0.2719075 -0.7732284 0.5728736 -0.2567475 -0.7553393 0.6029457 -0.2964558 -0.7916272 0.5342662 -0.2729541 -0.7711161 0.5752182 -0.3241026 -0.7951514 0.5125349 -0.3039461 -0.7822549 0.5437777 -0.4674369 -0.7655708 0.4420455 -0.4277171 -0.693318 0.5799727 1.62555e-4 -0.99239 -0.1231338 -4.454e-4 -0.9922635 -0.1241489 -0.01786136 -0.9970011 0.07529902 -0.009236633 -0.9955982 0.09326833 -0.0290811 -0.9622901 0.2704662 -0.0283907 -0.9619107 0.271886 -0.03630965 -0.9392845 0.341213 -0.0321505 -0.9367811 0.3484359 -0.05368155 -0.9284565 0.3675419 -0.03930968 -0.919007 0.3922767 -0.08282434 -0.9128272 0.3998582 -0.06212288 -0.8951259 0.4414638 -0.1223578 -0.888369 0.442526 -0.1005167 -0.8630478 0.4950202 -0.1656263 -0.8548939 0.4916549 -0.146372 -0.8282511 0.5409024 -0.1990116 -0.8265146 0.5265626 -0.1839694 -0.8045661 0.5646492 -0.2245538 -0.8104489 0.5410622 -0.2108803 -0.7902959 0.5752929 -0.2506961 -0.8125854 0.5261716 -0.231398 -0.7912847 0.5659713 -0.2883771 -0.8323338 0.473349 -0.2510946 -0.8117685 0.5272415 -0.3777623 -0.8278912 0.4145984 -0.3092835 -0.8016744 0.5115291 -0.3678145 -0.8718828 0.3233155 -0.3596819 -0.8483156 0.3885738 0.00380969 -0.9927618 -0.1200394 0.002223312 -0.9924011 -0.1230244 -0.00117892 -0.9976446 0.06858605 0.001006722 -0.997274 0.07378119 -0.005440354 -0.9637541 0.2667368 -0.005083382 -0.9635149 0.2676069 -0.01040655 -0.9433721 0.3315733 -0.006754457 -0.9408096 0.3388685 -0.02198988 -0.9385021 0.3445725 -0.01162081 -0.9313164 0.3640258 -0.04189741 -0.9314734 0.3613891 -0.02606952 -0.91876 0.3939549 -0.0708093 -0.9186089 0.3887725 -0.05294889 -0.8997594 0.4331622 -0.1082811 -0.8970576 0.4284424 -0.0921489 -0.8724011 0.4800261 -0.1458427 -0.8712775 0.4686208 -0.1321532 -0.8466291 0.5155141 -0.1775322 -0.8545945 0.4880068 -0.1628262 -0.8323583 0.5297805 -0.2066265 -0.8551701 0.4753836 -0.1856676 -0.8366829 0.5152566 -0.2349788 -0.8743482 0.4246177 -0.2021975 -0.863227 0.4625532 -0.2769287 -0.8938221 0.3526936 -0.2245646 -0.8895547 0.397823 -0.286087 -0.9221708 0.2602985 -0.2508547 -0.92304 0.2916661 -0.2588828 -0.9481678 0.1842762 -0.2451546 -0.9498822 0.1939668 -0.001115202 -0.9927926 -0.1198406 -0.001373708 -0.9927291 -0.1203626 -4.31406e-4 -0.9974354 0.07157254 -0.001604318 -0.9976426 0.06860578 -9.96879e-4 -0.963804 0.2666103 -0.001111268 -0.9638839 0.2663205 -0.003372192 -0.9449178 0.3272906 -0.001464903 -0.943578 0.3311474 -0.008992433 -0.9425209 0.3340262 -0.003744542 -0.9391115 0.3435924 -0.01963895 -0.939665 0.3415319 -0.01033329 -0.9333599 0.3587934 -0.03659808 -0.9332597 0.3573332 -0.02419185 -0.9233288 0.3832475 -0.06109613 -0.9219124 0.3825505 -0.04824209 -0.9062507 0.4199792 -0.09108692 -0.9051283 0.4152662 -0.07999479 -0.8850877 0.4584982 -0.1204772 -0.8924518 0.4347585 -0.1072379 -0.8731166 0.4755706 -0.149046 -0.8928827 0.4249068 -0.1283816 -0.8771401 0.4627565 -0.1736768 -0.9064158 0.3850283 -0.146165 -0.8978921 0.4152418 -0.1951467 -0.9270857 0.3200468 -0.164241 -0.9242676 0.3446075 -0.2091919 -0.949301 0.2346626 -0.1885398 -0.9497689 0.249784 -0.2156877 -0.9626919 0.1634116 -0.2051464 -0.9633556 0.1728036 -0.01539355 -0.9920959 -0.1245346 -0.01349508 -0.9926062 -0.1206272 -0.005075752 -0.9959926 0.08929187 -0.01226449 -0.9973861 0.07120877 -6.10513e-4 -0.9628424 0.2700635 -0.001982033 -0.9637942 0.2666399 -0.001452505 -0.9456673 0.3251327 -3.90316e-4 -0.9449427 0.3272357 -0.003869593 -0.9440714 0.3297187 -0.001524984 -0.9426484 0.3337838 -0.009425222 -0.9433106 0.3317774 -0.004087984 -0.9402304 0.3405148 -0.01903098 -0.9400506 0.3405036 -0.01028394 -0.9349334 0.3546741 -0.03271865 -0.9336017 0.3568158 -0.02181088 -0.9253616 0.3784578 -0.05093616 -0.9236692 0.3797906 -0.03983187 -0.9108921 0.4107179 -0.07145917 -0.915445 0.3960478 -0.0592705 -0.9019277 0.427801 -0.09230935 -0.917373 0.3871768 -0.07519423 -0.9063799 0.415718 -0.1124851 -0.9279098 0.3554302 -0.09090507 -0.9210083 0.3787877 -0.1217584 -0.9428753 0.3100987 -0.1111251 -0.9413234 0.3186874 -0.1166425 -0.9615637 0.2485758 -0.1330533 -0.9624934 0.2364392 -0.1845719 -0.9742549 0.1294629 -0.1400011 -0.9756156 0.1690382 -0.03357875 -0.9902786 -0.1349853 -0.02885818 -0.9917282 -0.1250699 -0.01031672 -0.9924562 0.122165 -0.02508687 -0.9958774 0.08717191 2.02784e-5 -0.9603943 0.2786449 -0.003788948 -0.9628802 0.2699025 0.001011669 -0.9455811 0.325385 8.95669e-4 -0.9456581 0.3251618 0.001152932 -0.9440325 0.3298507 0.001031696 -0.944103 0.3296493 -0.001415908 -0.9449092 0.3273298 0.001153349 -0.9435181 0.331319 -0.007828235 -0.94402 0.3297954 -0.001329362 -0.9407445 0.3391136 -0.01340121 -0.9383229 0.3455007 -0.006956815 -0.9348891 0.3548718 -0.01836442 -0.9296718 0.3679311 -0.01203417 -0.9254337 0.3787186 -0.02582556 -0.92381 0.3819794 -0.01826208 -0.9184849 0.3950344 -0.03508096 -0.9276236 0.3718654 -0.02592515 -0.9227159 0.384608 -0.04808253 -0.9389357 0.3407167 -0.03496021 -0.9342483 0.3549056 -0.04934751 -0.9481624 0.3139311 -0.05119699 -0.9486075 0.3122862 -0.0264241 -0.9575935 0.2869088 -0.05942821 -0.9652028 0.2546605 -0.03295439 -0.9885956 -0.1469451 -0.02692645 -0.9904987 -0.1348602 -0.006857633 -0.9892424 0.1461248 -0.01902258 -0.9924796 0.1209229 0.002483189 -0.9593338 0.2822634 6.53523e-4 -0.9603777 0.2787014 0.005449295 -0.9445413 0.3283475 0.003774344 -0.9455249 0.3255282 0.009856641 -0.9417383 0.3362022 0.005480408 -0.9440274 0.3298216 0.01298218 -0.9432498 0.3318303 0.009667396 -0.9449287 0.3271339 0.01438122 -0.9434383 0.3312363 0.01290923 -0.9441687 0.3292095 0.0231772 -0.9345523 0.3550701 0.01542264 -0.938467 0.3450245 0.03411948 -0.9238003 0.3813515 0.02497869 -0.9288896 0.3695136 0.03664201 -0.920814 0.3882766 0.03461545 -0.9219602 0.3857349 0.02125483 -0.933562 0.3577851 0.03580951 -0.9263222 0.3750265 -0.01474481 -0.9537724 0.300168 0.02063971 -0.9397221 0.3413159 -0.03884756 -0.9584812 0.2824975 -0.01489889 -0.9501361 0.3114795 -0.04746854 -0.9611147 0.2720394 -0.0396794 -0.9566681 0.2884642 -0.02074038 -0.9890523 -0.1461005 -0.02088248 -0.9890125 -0.1463496 -0.002547562 -0.9874338 0.1580131 -0.009852766 -0.9892765 0.1457222 0.00403285 -0.9587582 0.2841942 0.002746939 -0.9593255 0.2822889 0.01048433 -0.9421501 0.3350272 0.005305528 -0.944547 0.3283336 0.02098399 -0.9376354 0.3469864 0.01052474 -0.9417358 0.3361892 0.03229558 -0.9382975 0.3443182 0.02028739 -0.943121 0.33183 0.047544 -0.9355036 0.3501036 0.03156405 -0.9426965 0.3321553 0.07747834 -0.9184339 0.3879128 0.0483663 -0.9327742 0.3572018 0.099128 -0.9078845 0.407332 0.07716941 -0.9192597 0.3860139 0.08744251 -0.9186288 0.3853248 0.0970025 -0.9140895 0.3937398 0.03309822 -0.9492779 0.3126916 0.08534693 -0.9301686 0.3570747 -0.01305973 -0.9697352 0.2438102 0.03528505 -0.9570091 0.2879039 -0.04898607 -0.9688077 0.2429239 -0.02077484 -0.9607847 0.2765163 -0.07789456 -0.9666159 0.2441029 -0.05826067 -0.9596332 0.2751545 -0.116576 -0.9703214 0.2118644 -0.07889693 -0.9656985 0.2473896 -0.1462917 -0.9786096 0.1446443 -0.1075395 -0.9771014 0.183598 -0.08890759 -0.9924809 0.08412528 -0.1529265 -0.9869042 0.05132007 -0.07700663 -0.9966485 0.027601 -0.110571 -0.9938538 0.005373775 -0.07016968 -0.9972484 -0.02391874 -0.09712934 -0.9945459 -0.03800743 -0.03857135 -0.9989684 -0.02397173 -0.07703882 -0.9961389 -0.04209995 -0.0121662 -0.9900795 -0.139981 -0.01782935 -0.989164 -0.1457284 -4.77836e-4 -0.9867408 0.1623035 -0.005513846 -0.9874926 0.1575695 0.00408709 -0.9585096 0.2850312 0.002860248 -0.9588051 0.2840504 0.01339596 -0.9402577 0.3402001 0.00520271 -0.9424573 0.3342861 0.0287761 -0.9347981 0.3540121 0.01370948 -0.9376468 0.3473193 0.04617923 -0.9343739 0.3532888 0.02803337 -0.9384443 0.3442913 0.07410007 -0.926756 0.3682832 0.04577976 -0.9356821 0.3498619 0.1220742 -0.9014343 0.4153482 0.07794636 -0.9183604 0.3879933 0.1364986 -0.8976323 0.4190757 0.1210457 -0.9037194 0.4106569 0.07874178 -0.9276164 0.3651404 0.1311731 -0.9124247 0.3876531 0.003532946 -0.9583346 0.2856265 0.07899963 -0.9498705 0.3024982 -0.02254229 -0.9744564 0.223443 0.01859986 -0.9741588 0.2250972 -0.05497771 -0.9744327 0.2178501 -0.02511829 -0.9728032 0.2302675 -0.09922909 -0.9728563 0.2090561 -0.06332623 -0.9685288 0.240711 -0.1427408 -0.9750505 0.1700048 -0.09956932 -0.9725298 0.2104083 -0.1483584 -0.9793462 0.137371 -0.1391316 -0.9794886 0.1457554 -0.1027218 -0.9889315 0.1070648 -0.145233 -0.986348 0.07762092 -0.07570189 -0.9958933 0.0496571 -0.1188637 -0.9927104 0.01994264 -0.04851901 -0.9988212 0.001515924 -0.09631311 -0.9950402 -0.02487421 -0.01394379 -0.9998971 -0.003408551 -0.05691254 -0.9980829 -0.02432256 0.003607273 -0.9174987 0.3977226 0.02924668 -0.9141625 0.4042915 -0.1510202 -0.9289819 0.3379135 -0.08088296 -0.9457136 0.3147758 -0.2606998 -0.9177302 0.2996783 -0.1381313 -0.9448303 0.297011 -0.3289278 -0.9205938 0.210508 -0.2508915 -0.940634 0.228607 -0.3114387 -0.9373372 0.1562207 -0.334613 -0.9303674 0.1498357 -0.284116 -0.9497955 0.1310214 -0.319757 -0.9398432 0.1202095 -0.2599349 -0.9569814 0.1289208 -0.2874674 -0.950303 0.1195275 -0.238751 -0.961342 0.1371846 -0.2597995 -0.9569575 0.1293704 -0.2177584 -0.9646015 0.1487463 -0.2376469 -0.9610656 0.140986 -0.1911525 -0.9682489 0.1611055 -0.217104 -0.9643827 0.1511022 -0.1467893 -0.9747797 0.1681002 -0.19348 -0.9692962 0.1517581 -0.07680797 -0.9860469 0.1476892 -0.1536054 -0.9798154 0.1279353 -0.0336039 -0.9964625 0.07702744 -0.07822501 -0.9942929 0.07254481 -0.01010572 -0.9967551 0.07985788 -0.002608358 -0.9956992 0.09260934 -0.04164993 -0.9893239 0.1396555 -0.009988307 -0.98127 0.1923782 -0.1027618 -0.981338 0.16253 -0.04912716 -0.9654346 0.2559739 -0.1871368 -0.9651074 0.1831601 -0.120002 -0.9460636 0.3009372 -0.2975788 -0.9297912 0.2166455 -0.2126623 -0.9192447 0.3313064 -0.3808824 -0.9022576 0.2021386 -0.3120838 -0.9053252 0.2880798 -0.4423471 -0.8800659 0.1726654 -0.3865721 -0.8913981 0.2365833 -0.4717832 -0.867524 0.1575527 -0.4436373 -0.8752173 0.1928233 -0.4726864 -0.8634982 0.1758938 -0.471771 -0.8637475 0.177123 -0.463172 -0.8618176 0.2067417 -0.4721069 -0.8597815 0.1946564 -0.4492775 -0.8604624 0.2403209 -0.4622853 -0.8582687 0.2228609 -0.4252495 -0.8606886 0.2799609 -0.4486672 -0.8582208 0.2493092 -0.379113 -0.8692668 0.3172519 -0.4264356 -0.8672805 0.2568607 -0.3088476 -0.8953292 0.3209345 -0.3788098 -0.8971799 0.2270937 -0.2351873 -0.9282256 0.2882434 -0.2944836 -0.9342887 0.2009578 -0.1479108 -0.9331585 0.3276241 -0.2121821 -0.950579 0.226668 -0.04785007 -0.9298108 0.3649141 -0.1048603 -0.9603418 0.2583561 0.02382493 -0.9753916 0.2191886 0.03319519 -0.9701474 0.2402339 -0.02064818 -0.9895939 0.1423996 0.03184854 -0.978735 0.2026409 -0.03148257 -0.9902101 0.1359887 -0.02083963 -0.9894362 0.1434642 -0.01769852 -0.9989737 0.04169583 0.006563305 -0.9966027 0.082098 -0.07403022 -0.9958949 0.05208563 -0.02403265 -0.9899134 0.1396208 -0.1484543 -0.9881569 0.03882288 -0.08923524 -0.982918 0.1609641 -0.2366583 -0.9705002 0.04606807 -0.1754068 -0.967779 0.1806557 -0.3426154 -0.9359303 0.08154255 -0.2688565 -0.9407066 0.2068508 -0.4258928 -0.8989551 0.1024465 -0.361768 -0.9111391 0.1973561 -0.4695585 -0.8749225 0.1184294 -0.4321885 -0.8853747 0.1712453 -0.4781778 -0.8660174 0.1461508 -0.4703391 -0.868308 0.1575518 -0.472018 -0.8622187 0.1837885 -0.4776822 -0.8608284 0.175483 -0.4612378 -0.8595123 0.2202236 -0.4710811 -0.8577069 0.2059651 -0.4474452 -0.8566786 0.2566996 -0.4599195 -0.8551291 0.2392245 -0.4195684 -0.8529383 0.3105782 -0.4454105 -0.8512617 0.2774221 -0.3440933 -0.8524129 0.3936905 -0.4195569 -0.8529067 0.3106806 -0.2195584 -0.8719235 0.4376569 -0.3489512 -0.8839473 0.3112397 -0.1381626 -0.9273834 0.3476654 -0.1754538 -0.9349129 0.3084701 -0.07196295 -0.9092487 0.4099859 -0.1262324 -0.9336003 0.3353444 0.05849009 -0.8487957 0.5254759 -0.04410564 -0.9296048 0.3659095 0.1659846 -0.9478328 0.2721439 0.1687093 -0.9446262 0.2814582 0.08440703 -0.9959347 -0.03145694 0.2116005 -0.9625803 0.1693059 -0.0439558 -0.9971852 0.06074357 0.07517546 -0.9877122 0.1370158 -0.02109426 -0.9997123 -0.0114209 0.03241521 -0.9987572 0.03786134 -0.1040779 -0.9942011 -0.02705907 -0.0300619 -0.9985306 0.04508841 -0.1913193 -0.980052 -0.05380696 -0.1167341 -0.9926164 0.03295248 -0.2830911 -0.9579406 -0.04700428 -0.212444 -0.9762881 0.04158234 -0.3805463 -0.9247469 -0.005280435 -0.3068634 -0.9488868 0.07381677 -0.4481738 -0.892869 0.04387879 -0.3941637 -0.9137958 0.09804159 -0.4738011 -0.87538 0.09603345 -0.4524126 -0.8840299 0.117533 -0.4759207 -0.8675483 0.1444282 -0.4741758 -0.8682005 0.1462374 -0.4702761 -0.8621138 0.1886806 -0.4750846 -0.8605682 0.1836223 -0.4609203 -0.8576577 0.2279818 -0.4687283 -0.8555727 0.2197487 -0.4467709 -0.853662 0.2676885 -0.4584532 -0.8511856 0.2555459 -0.3804675 -0.8508052 0.3624572 -0.4404979 -0.8440069 0.3059639 -0.07080835 -0.8096985 0.5825587 -0.3745061 -0.843906 0.3841456 0.2787301 -0.7425549 0.6090337 -0.07954066 -0.8773459 0.4732205 0.4500086 -0.7690104 0.4539991 0.7591634 -0.6137473 0.2167607 0.4777904 -0.7565971 0.4464047 0.6573375 -0.09650772 0.7473914 0.6524212 -0.3798012 0.6558184 0.701017 -0.6691093 0.2467142 0.7070004 -0.6630272 0.2460595 -0.02685779 -0.955734 -0.2930036 0.0431087 -0.9771355 -0.2082016 -0.08456408 -0.959464 -0.2688457 -0.03393882 -0.9774513 -0.2084161 -0.1215369 -0.9651021 -0.2319628 -0.08917117 -0.9773392 -0.1919809 -0.1548199 -0.9709963 -0.1822009 -0.1255424 -0.9813666 -0.1454604 -0.1894145 -0.9736717 -0.1268289 -0.1586859 -0.9833948 -0.08805453 -0.224695 -0.972095 -0.06740731 -0.1931546 -0.9807834 -0.02748662 -0.2568457 -0.966451 0.001690983 -0.2280729 -0.9729038 0.03796178 -0.2652636 -0.9592018 0.09781223 -0.2582654 -0.9601933 0.1064324 -0.231668 -0.9482851 0.2169917 -0.2632316 -0.9476919 0.1805251 0.04400914 -0.8492078 0.5262217 -0.2273704 -0.9323149 0.2812322 0.06710749 -0.8783374 0.4733077 -0.002916336 -0.9125801 0.4088876 0.4986566 -0.4102755 0.7635548 0.2264113 -0.6726326 0.7044879 0.04405516 -0.9350239 -0.3518374 0.08037412 -0.9503359 -0.3006691 0.01243215 -0.9488232 -0.3155629 0.03931069 -0.9607104 -0.2747551 -0.01548987 -0.9614794 -0.2744404 0.008359551 -0.9715441 -0.2367116 -0.04612028 -0.9720939 -0.2300142 -0.01947104 -0.9821233 -0.1872292 -0.08030313 -0.9802235 -0.1808682 -0.05019074 -0.9899595 -0.1321408 -0.1133915 -0.9862391 -0.1203115 -0.08386802 -0.993838 -0.07247382 -0.115957 -0.9932471 -0.003763914 -0.1143466 -0.9934402 -0.001208782 -0.004684746 -0.9658284 0.2591401 -0.1098337 -0.9882717 0.1060925 0.1768505 -0.8474303 0.5005856 -0.003850579 -0.9641318 0.2653962 0.4618275 -0.357388 0.8117816 0.1777524 -0.8513656 0.4935393 0.1602572 -0.9175868 -0.3638026 0.1705614 -0.9210762 -0.3500393 0.1445141 -0.9299921 -0.3379802 0.1588349 -0.9353651 -0.3160121 0.1233884 -0.9429051 -0.3093631 0.1422917 -0.9498609 -0.2784195 0.09576982 -0.9561018 -0.2769432 0.1204474 -0.9643397 -0.2356724 0.06300705 -0.9696723 -0.2361476 0.09264004 -0.9781497 -0.1861211 0.04305183 -0.9870175 -0.1547356 0.06231802 -0.9905381 -0.1222729 0.1268629 -0.9844191 0.1217581 0.05350404 -0.9985676 5.14949e-4 0.3688575 -0.7146466 0.5943269 0.1567848 -0.94762 0.2782716 0.2627719 -0.8988674 -0.3506969 0.2552517 -0.8970924 -0.3606548 0.2612134 -0.9034488 -0.3399235 0.2627648 -0.9038912 -0.3375434 0.2518296 -0.9110326 -0.3264991 0.260816 -0.913657 -0.3117787 0.2338293 -0.921862 -0.3090215 0.2511246 -0.9265117 -0.2802008 0.2104268 -0.9375397 -0.2770195 0.234278 -0.9428681 -0.2368829 0.2143054 -0.9633898 -0.1611001 0.2194745 -0.9636617 -0.1522731 0.3773422 -0.8689006 0.3203511 0.257076 -0.961385 0.098239 0.321874 -0.8890856 -0.3254597 0.304214 -0.8864717 -0.3487433 0.3307398 -0.8860231 -0.324922 0.3216696 -0.8841766 -0.3387633 0.3334272 -0.8863095 -0.3213752 0.3307275 -0.885716 -0.325771 0.3302997 -0.8905838 -0.3126702 0.3339422 -0.8913277 -0.3066229 0.3267956 -0.9021637 -0.2816121 0.3344202 -0.9033596 -0.268523 0.3712083 -0.9213786 -0.115178 0.350391 -0.9239446 -0.1534681 0.3530907 -0.8859348 -0.3007431 0.3332039 -0.8851429 -0.3248034 0.3649188 -0.8792266 -0.3062597 0.3520921 -0.8780269 -0.3241915 0.372405 -0.875664 -0.3074528 0.3642023 -0.8746291 -0.3199698 0.3783023 -0.8762077 -0.2985755 0.3723157 -0.8753572 -0.308433 0.3950734 -0.885181 -0.2457066 0.3837535 -0.884059 -0.2667831 0.3703563 -0.8842005 -0.2846503 0.3520493 -0.8863282 -0.3008052 0.3814013 -0.8768782 -0.2926055 0.3681349 -0.8779432 -0.3060924 0.3908459 -0.8722438 -0.2939901 0.3798918 -0.8726605 -0.3068321 0.4157016 -0.8719616 -0.2586026 0.3905991 -0.8716923 -0.2959474 0.5256429 -0.8486955 0.05844318 0.4198812 -0.8787821 -0.2268084 -0.2981425 -0.9463537 -0.124602 -0.250445 -0.9629549 -0.09997653 -0.3588903 -0.9240681 0.1315139 -0.3394881 -0.9298589 0.1418116 -0.3374437 -0.8991185 0.278779 -0.3701665 -0.89135 0.2616716 -0.3018149 -0.8865624 0.3505924 -0.3359785 -0.8811157 0.3327965 -0.2789433 -0.8696776 0.4072489 -0.2997879 -0.8681238 0.3955861 -0.2674852 -0.8417421 0.4689586 -0.2783275 -0.8419778 0.4621766 -0.2662963 -0.8049308 0.5302575 -0.2689719 -0.8051808 0.5285244 -0.2669155 -0.7768815 0.5702732 -0.2677655 -0.7769832 0.5697357 -0.2682585 -0.7645944 0.5860316 -0.2677389 -0.7644934 0.5864008 -0.2756551 -0.7499877 0.6012759 -0.2708677 -0.7484297 0.6053791 -0.2962054 -0.7355141 0.6093288 -0.2819513 -0.7291761 0.623543 -0.3300297 -0.7384307 0.5880481 -0.3031701 -0.721925 0.6220227 -0.345941 -0.7564878 0.5550236 -0.3443217 -0.7204875 0.6019472 0.3830988 -0.8807353 -0.2784613 0.3656868 -0.8860617 -0.2848994 0.3926033 -0.8740262 -0.2862535 0.3784056 -0.878098 -0.2928365 0.4015061 -0.8695096 -0.2876562 0.3902235 -0.8724954 -0.2940707 0.4049007 -0.8750514 -0.2652179 0.4086202 -0.8743851 -0.2616877 0.4324645 -0.89414 -0.1161376 0.4632499 -0.8846732 -0.05246698 0.5314753 -0.6819683 0.5024473 0.5468911 -0.5998479 0.5840315 0.5273544 -0.323993 0.7854463 0.5270299 -0.3813111 0.7595007 0.5140514 -0.2055852 0.8327581 0.514366 -0.2161346 0.8298876 0.9969195 0.07333236 -0.02781873 0.9855659 0.1659177 0.03363275 0.9983174 0.05681353 0.01160448 0.9976966 0.06576222 0.01664543 0.9984027 0.05451732 0.01483136 0.9982836 0.05638438 0.01583194 0.9983437 0.05514407 0.0164051 0.9983929 0.05436271 0.0160067 0.9975799 0.06649398 0.02032119 0.9983482 0.05550181 0.01485359 0.9916025 0.1245479 0.03482049 0.9975156 0.06930518 0.0126248 0.9134302 0.3954344 0.09631699 0.9914086 0.1301031 0.01349842 0.1079776 0.960331 0.2571096 0.9316424 0.3605664 0.04510378 -0.9122866 0.4088726 -0.02358841 -0.9116509 0.4102807 -0.02371853 -0.9368572 0.3491795 0.01929688 -0.9214891 0.3880601 0.01634818 -0.9076097 0.4173257 0.04564946 -0.9337636 0.3549227 0.04599469 -0.7654519 0.6411647 0.0546925 -0.9027928 0.4266725 0.05399966 -0.487511 0.8720195 0.04376178 -0.7607584 0.6460343 0.06234097 -0.3620433 0.9306724 0.05266344 -0.5000511 0.8624858 0.07789319 -0.441965 0.8856626 0.1423687 -0.4299385 0.8922588 0.1379391 -0.5513123 0.7779781 0.3013384 -0.5821598 0.7479455 0.3188535 -0.6521663 0.6016824 0.4611481 -0.6915682 0.5328287 0.4876753 -0.7612283 -0.2998391 0.5750026 -0.7217844 0.4300535 0.5422926 -0.4480584 -0.5958563 0.6664825 -0.5802089 -0.4424502 0.6838096 -0.3212727 -0.7183685 0.6170337 -0.5438646 -0.499606 0.6742442 -0.3502233 -0.7061768 0.615352 -0.5563187 -0.4910098 0.6703872 -0.750343 -0.09660112 0.6539523 -0.5905084 -0.4330709 0.6809916 -0.7692191 0.01311933 0.6388505 -0.5651587 0.8077204 0.1678792 -0.4826873 -0.6051719 0.6330719 -0.3989727 -0.6417772 0.6549373 -0.6221145 -0.3989896 0.6736326 -0.4386854 -0.5984956 0.6703419 -0.5640923 -0.4599831 0.6857227 -0.5076067 -0.5248436 0.6832823 -0.4428157 -0.5942549 0.6713981 -0.5301041 -0.5021556 0.6832492 -0.4276117 -0.6157957 0.6617732 -0.5615618 -0.4674891 0.6827168 -0.5462624 -0.4882979 0.6805606 -0.5974673 -0.4172917 0.6847631 -0.7919336 0.110805 0.6004695 -0.6336002 -0.3469631 0.6914966 -0.3877336 -0.6655932 0.63769 -0.3330432 -0.6861893 0.6467044 -0.4903249 -0.5650799 0.6635257 -0.3803079 -0.6482318 0.6596677 -0.5857186 -0.4547212 0.6709414 -0.4494474 -0.5864338 0.673864 -0.5495627 -0.4850839 0.6802018 -0.4967207 -0.5383223 0.680792 -0.5542817 -0.4743251 0.68395 -0.5292655 -0.501487 0.6843895 -0.5875568 -0.4282884 0.6865465 -0.5564983 -0.4667216 0.6873724 -0.6471123 -0.3314251 0.6865881 -0.598624 -0.4034936 0.6919844 -0.6602657 -0.298543 0.6891455 -0.632691 -0.3394673 0.6960345 -0.669453 -0.2718579 0.691322 -0.6550215 -0.2948625 0.6957033 -0.6867761 -0.2295817 0.6896601 -0.6853862 -0.232171 0.6901757 -0.7191492 -0.1473455 0.6790536 -0.7246865 -0.1355869 0.6756078 -0.7406019 -0.08274555 0.6668299 -0.7477329 -0.06696319 0.6606146 -0.7548255 -0.03274589 0.6551077 -0.7597565 -0.02228933 0.6498256 -0.7614818 -0.007521569 0.6481428 -0.763462 -0.003721415 0.6458423 -0.7636702 0.004563331 0.6455906 -0.7637954 0.004837989 0.6454403 -0.763007 0.02062457 0.6460611 -0.7625888 0.01892608 0.6466066 -0.7541403 0.09694558 0.6495183 -0.7555869 0.04297626 0.6536371 -0.7537529 -0.02981907 0.6564812 -0.754633 0.03297358 0.6553182 -0.7515385 0.06094336 0.6568682 -0.7520145 0.08335471 0.653855 -0.3324094 -0.7035362 0.6281249 -0.3197003 -0.7069787 0.6308509 -0.4899126 -0.601859 0.6306753 -0.3711182 -0.6730466 0.6397497 -0.6753524 -0.4132667 0.6108272 -0.4296944 -0.6256802 0.651066 -0.6491266 -0.4209277 0.6336045 -0.4883868 -0.5704364 0.6603642 -0.6408561 -0.4131167 0.6470225 -0.5188636 -0.5338523 0.6676694 -0.6511867 -0.3824551 0.6555028 -0.5397394 -0.5040593 0.6742445 -0.6757441 -0.3263311 0.6609675 -0.5813748 -0.4464549 0.6802069 -0.6772581 -0.3043613 0.66984 -0.6280619 -0.3732488 0.6828057 -0.7020027 -0.2444107 0.6689212 -0.6671172 -0.3012749 0.6813134 -0.7225013 -0.1861031 0.6658511 -0.7051877 -0.2195751 0.6741641 -0.7467151 -0.1092854 0.6561046 -0.7437987 -0.1160936 0.6582444 -0.7595466 -0.0576387 0.6478943 -0.7646076 -0.04496383 0.6429259 -0.7689764 -0.0185126 0.6390092 -0.7712669 -0.01274055 0.6363844 -0.7720171 -0.002317547 0.6355976 -0.7716404 -0.003231227 0.6360508 -0.7716339 0.005549907 0.6360428 -0.7701557 0.001197934 0.6378548 -0.7693028 0.01912403 0.638598 -0.768426 0.01406663 0.6397841 -0.7664817 0.04526841 0.6406689 -0.7661781 0.03355324 0.6417517 -0.7263296 0.282603 0.6265627 -0.7598763 0.06625652 0.6466825 -0.7641523 0.01708662 0.6448097 -0.7628232 0.06831836 0.6429879 -0.7636073 0.05805218 0.6430661 -0.7602575 0.1145405 0.6394445 -0.3307473 -0.7258607 0.6031023 -0.3289766 -0.7262389 0.6036154 -0.5375238 -0.6174771 0.5742738 -0.3978523 -0.6894889 0.6052426 -0.7398698 -0.4234209 0.5227882 -0.437937 -0.6569843 0.6136634 -0.7280085 -0.4070432 0.5516517 -0.4872086 -0.6119347 0.6230279 -0.7042954 -0.4085004 0.5805991 -0.5268531 -0.5680259 0.6322757 -0.6969254 -0.3923949 0.6002677 -0.5606222 -0.5254431 0.6400097 -0.7270305 -0.3251212 0.6047503 -0.6096876 -0.4611596 0.6446805 -0.7425336 -0.2721804 0.6120144 -0.656997 -0.3872655 0.6468232 -0.7621389 -0.2056363 0.6138877 -0.6986409 -0.3076492 0.6459512 -0.775751 -0.1442811 0.6143236 -0.745104 -0.2040372 0.6349716 -0.7915068 -0.07254976 0.6068391 -0.7826893 -0.09308552 0.6154125 -0.7980499 -0.02756899 0.6019604 -0.7981888 -0.02721613 0.6017924 -0.8009758 -0.005525946 0.5986713 -0.8003035 -0.007037162 0.599554 -0.8005563 -8.22485e-4 0.5992571 -0.7978127 -0.006774842 0.6028674 -0.7976331 0.001977562 0.6031398 -0.7933365 -0.009403109 0.6087107 -0.7921603 0.01380747 0.610157 -0.7895534 -8.0203e-4 0.6136815 -0.7878671 0.03277677 0.6149725 -0.787348 0.018736 0.6162242 -0.7843058 0.06950825 0.6164683 -0.785018 0.04686486 0.6176977 -0.7854052 0.04032474 0.6176671 -0.7847077 0.06408226 0.6165448 -0.7876063 0.005852699 0.6161511 -0.7856134 0.0958752 0.6112443 -0.3466414 -0.7387918 0.5779502 -0.3541514 -0.7371208 0.5755257 -0.531435 -0.653795 0.5386363 -0.4661351 -0.6854542 0.5593484 -0.6879862 -0.5338779 0.4915785 -0.5108394 -0.6537458 0.5582648 -0.7345422 -0.4729012 0.4866337 -0.5338587 -0.6286071 0.5655511 -0.7472919 -0.4375165 0.5001341 -0.5725453 -0.5872453 0.572132 -0.7594305 -0.3978356 0.514774 -0.6193035 -0.5328561 0.5766521 -0.7905977 -0.3256418 0.518568 -0.6727656 -0.4617062 0.5781123 -0.8059587 -0.268011 0.5278264 -0.7155255 -0.3896352 0.5798344 -0.8255115 -0.1937305 0.5300936 -0.7645033 -0.2944704 0.57343 -0.8430662 -0.1124946 0.5259129 -0.8169991 -0.1676648 0.5517255 -0.8535715 -0.04277116 0.5192171 -0.843783 -0.06704348 0.5324805 -0.854088 -0.008510947 0.5200591 -0.8500135 -0.01808112 0.5264505 -0.8515688 -5.19528e-5 0.5242429 -0.8489077 -0.005662918 0.5285109 -0.8489139 -0.005278825 0.5285049 -0.8457677 -0.01158517 0.5334256 -0.8457624 -0.01144647 0.5334371 -0.8409094 -0.02322256 0.5406775 -0.8404399 -0.005432665 0.5418776 -0.836827 -0.02355766 0.5469602 -0.8360401 0.01266658 0.5485222 -0.8350375 -0.005661249 0.5501639 -0.8331696 0.04479908 0.5512002 -0.8333347 0.03227722 0.5518257 -0.8315553 0.06154233 0.5520222 -0.8312191 0.06943732 0.5515918 -0.8228412 0.1431905 0.5499352 -0.8156901 0.1956571 0.5443969 -0.3696606 -0.7431785 0.5577068 -0.3855344 -0.7390329 0.5524433 -0.5424593 -0.6632934 0.5155384 -0.5424256 -0.6633322 0.5155239 -0.6549718 -0.5872504 0.4755512 -0.6139659 -0.6154407 0.4942457 -0.7104743 -0.5370333 0.4547764 -0.6386222 -0.5932444 0.4901254 -0.7616907 -0.4786687 0.4366962 -0.6721437 -0.5588839 0.4856662 -0.8085825 -0.4100632 0.4219511 -0.712331 -0.5105498 0.4815843 -0.8485634 -0.3313658 0.4124764 -0.7549608 -0.4484732 0.4784414 -0.8662657 -0.2723929 0.4187911 -0.7940707 -0.3784648 0.475622 -0.8928453 -0.1813418 0.4122409 -0.8527575 -0.2585198 0.4538416 -0.9136732 -0.08065581 0.3983666 -0.8975142 -0.1237448 0.4232676 -0.917779 -0.02239787 0.3964593 -0.9106289 -0.04447066 0.4108253 -0.9148839 -0.003174543 0.403705 -0.911033 -0.0138697 0.4121002 -0.9114969 -9.57742e-4 0.4113061 -0.9083225 -0.008637845 0.4181814 -0.9083598 -0.01145088 0.4180328 -0.9056295 -0.01785951 0.4236937 -0.9060296 -0.02800846 0.4222865 -0.9039883 -0.0342887 0.4261803 -0.9039888 -0.03435844 0.4261732 -0.9020722 -0.04573678 0.4291552 -0.9023046 -0.02070355 0.4306019 -0.9015337 -0.03203964 0.4315211 -0.90086 0.02437144 0.4334251 -0.9008329 0.01339727 0.4339594 -0.8974744 0.0734896 0.4349011 -0.8978423 0.06625902 0.4353035 -0.8550516 0.296731 0.4252498 -0.8597924 0.2784306 0.428058 -0.4227815 -0.7494265 0.5095252 -0.4226645 -0.7494615 0.5095707 -0.633476 -0.6273328 0.452948 -0.5959448 -0.6512542 0.4698062 -0.7128875 -0.5595632 0.4227063 -0.6820752 -0.5844532 0.4395316 -0.7397852 -0.531799 0.4121987 -0.7296366 -0.5409854 0.4182885 -0.7816229 -0.4863839 0.3905078 -0.7780069 -0.4901573 0.3930029 -0.8320365 -0.4224522 0.359513 -0.8212385 -0.4357327 0.368381 -0.8795191 -0.3464021 0.3262696 -0.8596933 -0.37606 0.3456968 -0.9163228 -0.2668296 0.2985872 -0.9027903 -0.2928914 0.3149356 -0.9538103 -0.1511859 0.2595937 -0.9457995 -0.1743454 0.2739835 -0.9708599 -0.05088019 0.2341847 -0.9647674 -0.07774811 0.2513547 -0.9716686 -0.006868779 0.2362479 -0.9678928 -0.0268107 0.2499296 -0.9689186 -0.001322209 0.2473766 -0.9668747 -0.01078444 0.2550237 -0.9669141 -0.006538569 0.2550189 -0.9648507 -0.0144481 0.2624014 -0.9649102 -0.0202943 0.2617945 -0.9632173 -0.0265159 0.2674124 -0.9634336 -0.04089975 0.2648074 -0.963873 -0.03852188 0.2635622 -0.9635529 -0.05799543 0.2611558 -0.9644284 -0.04978883 0.2596127 -0.9645398 -0.04655063 0.2598001 -0.9650755 -0.03784924 0.2592236 -0.9653988 0.009047508 0.2606213 -0.9653319 9.35555e-4 0.261024 -0.9622361 0.07334882 0.2621482 -0.9626939 0.06526666 0.262604 -0.8914119 0.3767369 0.2519015 -0.8898065 0.3809157 0.2512923 -0.4749339 -0.7632098 0.4381193 -0.4735478 -0.7637625 0.4386566 -0.7142307 -0.5940507 0.3701058 -0.653169 -0.6425659 0.400599 -0.7897285 -0.5097976 0.3412265 -0.7381673 -0.5617389 0.3735754 -0.8155009 -0.4739255 0.3321942 -0.7980448 -0.4940713 0.3449902 -0.8472231 -0.4288432 0.3135389 -0.8569853 -0.4154891 0.3048686 -0.882063 -0.3750085 0.2851905 -0.906349 -0.3344023 0.2582764 -0.9173787 -0.3118169 0.2473593 -0.9465979 -0.2488654 0.204984 -0.9571648 -0.2178009 0.1907836 -0.9789032 -0.145493 0.1434585 -0.9859362 -0.1067102 0.1286196 -0.9917826 -0.07118946 0.106299 -0.9946725 -0.03494572 0.09698128 -0.9949293 -0.03215599 0.09529805 -0.9957791 -0.002901792 0.09173643 -0.9951712 -0.01234591 0.09737586 -0.9952705 -0.002259314 0.09711641 -0.9947716 -0.009067893 0.1017215 -0.9947239 -0.01430535 0.1015864 -0.9942135 -0.01933014 0.1056692 -0.9940195 -0.03019833 0.1049446 -0.9935865 -0.03379911 0.1079051 -0.993245 -0.0453906 0.1067906 -0.9934708 -0.04290646 0.1057115 -0.9928584 -0.05700379 0.1047987 -0.9938972 -0.04054224 0.1025899 -0.9939089 -0.04023545 0.1025983 -0.9947079 -0.01661241 0.1013914 -0.9948164 0.001853883 0.1016709 -0.9948172 0.006339132 0.1014821 -0.9925333 0.06694197 0.1019633 -0.9924028 0.06898647 0.1018706 -0.8959277 0.4335656 0.09661608 -0.9182796 0.3828784 0.1008311 -0.5164613 -0.7722924 0.3699083 -0.5274303 -0.7669137 0.3655967 -0.7504533 -0.5873996 0.302955 -0.7155514 -0.6204559 0.3209685 -0.8332241 -0.4831755 0.2688477 -0.8054581 -0.5181154 0.2877392 -0.8721951 -0.4210612 0.2489643 -0.8663032 -0.4301216 0.2539967 -0.9081182 -0.3544931 0.2228366 -0.9181567 -0.3350481 0.2114974 -0.9387003 -0.2868121 0.1912606 -0.9621306 -0.2248981 0.1540315 -0.9650903 -0.2148174 0.1498479 -0.9886353 -0.1198027 0.09081715 -0.9888156 -0.1186397 0.09037929 -0.9977223 -0.04824513 0.047145 -0.9975131 -0.05159562 0.04801815 -0.9993953 -0.01884114 0.02922749 -0.9993777 -0.0196079 0.02932494 -0.999696 -0.007952392 0.02334022 -0.9997222 -0.003825485 0.02325993 -0.9997298 -0.003294408 0.02301359 -0.9997241 -0.005032002 0.02294719 -0.9997087 -0.005947172 0.02339577 -0.9995629 -0.01887297 0.02275806 -0.9995821 -0.01827824 0.0223993 -0.9991226 -0.03579592 0.0217452 -0.9991021 -0.03620028 0.02201288 -0.998536 -0.04955661 0.02168357 -0.9981054 -0.05656051 0.02422219 -0.9983171 -0.05264133 0.02432572 -0.9977132 -0.06265467 0.02535575 -0.9992347 -0.02897477 0.02627921 -0.9994605 -0.02000689 0.02604568 -0.9996491 -0.001081287 0.0264703 -0.9993997 0.02289009 0.0260083 -0.9979075 0.05891263 0.02664524 -0.996985 0.07298344 0.02635234 -0.9273402 0.3729141 0.03123039 -0.9638559 0.2642542 0.03393334 -0.5595997 -0.769652 0.3073828 -0.5874429 -0.7530227 0.2964249 -0.779965 -0.5762336 0.2441505 -0.7743851 -0.5824761 0.2470818 -0.8644531 -0.4579088 0.207462 -0.8630266 -0.4601255 0.2084938 -0.9087629 -0.3761649 0.1806932 -0.9189426 -0.3555107 0.1707533 -0.9448224 -0.2917054 0.1490592 -0.9625385 -0.2413029 0.1236636 -0.974687 -0.1956877 0.1081284 -0.9901238 -0.1219034 0.069242 -0.9921141 -0.1073447 0.06470525 -0.9984959 -0.04565286 0.03036117 -0.9986234 -0.04317927 0.0297805 -0.9998203 -0.0138235 0.01297712 -0.9997759 -0.01645392 0.01332366 -0.9999691 -0.004250884 0.006620824 -0.9999556 -0.006615102 0.006722688 -0.9999905 -0.001401841 0.00413531 -0.9999896 -0.00196737 0.004126071 -0.9999937 -5.65569e-4 0.003518998 -0.999983 -0.004836499 0.003304362 -0.9999936 -0.002689659 0.002383112 -0.9998405 -0.01779288 0.001575231 -0.9999176 -0.01280814 -9.51156e-4 -0.9993348 -0.03643912 -0.00155127 -0.9994183 -0.03397977 -0.002928197 -0.9982602 -0.0588985 -0.002761363 -0.9976549 -0.06844484 5.38125e-4 -0.9975061 -0.07057976 5.16106e-4 -0.996081 -0.08841121 0.002469539 -0.9993359 -0.03618359 0.004327476 -0.999026 -0.04390621 0.004398167 -0.9999294 0.009740114 0.00681132 -0.9996145 0.02686834 0.007009863 -0.9981513 0.06015902 0.008658707 -0.998465 0.05471932 0.008580029 -0.968502 0.2482039 0.01996958 -0.9879699 0.1535312 0.01853901 -0.6136374 -0.7531092 0.237225 -0.6522855 -0.7248139 0.2217396 -0.8188014 -0.5452118 0.1797457 -0.8311383 -0.5284429 0.1730821 -0.8984308 -0.4146264 0.1445929 -0.9097597 -0.3922669 0.1358827 -0.9407095 -0.3184637 0.1168186 -0.9560043 -0.2759395 0.09956634 -0.9725864 -0.2167433 0.08425128 -0.9865165 -0.1533246 0.05724388 -0.9927303 -0.1108429 0.04691058 -0.9980382 -0.05827623 0.02288269 -0.9988955 -0.04259335 0.01984149 -0.9998583 -0.01566839 0.006177127 -0.9998984 -0.01298922 0.005863845 -0.9999958 -0.002880156 2.84149e-4 -0.9999917 -0.004057109 3.41506e-4 -0.9999974 -0.002139687 -7.27109e-4 -0.9999988 -0.001370012 -7.33676e-4 -0.9999991 -0.001119613 -8.59393e-4 -0.9999996 -4.52978e-4 -8.49553e-4 -0.9999995 -6.14345e-4 -7.64016e-4 -0.9999964 -0.002555429 -8.35718e-4 -0.9999979 -0.001722693 -0.00120157 -0.9999168 -0.01278859 -0.0017367 -0.9999528 -0.009070217 -0.003499925 -0.9994142 -0.03396815 -0.00417453 -0.9994921 -0.03139358 -0.005483865 -0.9976329 -0.06857639 -0.005091607 -0.9972838 -0.07358074 -0.003309071 -0.9958829 -0.09058803 -0.003351688 -0.99551 -0.09461665 -0.002759754 -0.998625 -0.05241149 -0.001183032 -0.9985892 -0.05308824 -0.001168966 -0.9997816 0.02061665 0.003410696 -0.9998696 0.0158106 0.003301799 -0.998641 0.05175322 0.006165504 -0.9991548 0.0406993 0.005789399 -0.988549 0.1500432 0.01606333 -0.9933951 0.1137582 0.01500773 -0.6766434 -0.7264527 0.1200844 -0.6965627 -0.7086723 0.1121788 -0.8698862 -0.4866961 0.08015549 -0.8827802 -0.4640562 0.07315051 -0.9371579 -0.3445312 0.05507558 -0.9475908 -0.3160787 0.04654055 -0.9701579 -0.2399441 0.03493773 -0.9787942 -0.2034979 0.02346503 -0.9910831 -0.1325945 0.01315993 -0.9953943 -0.09586358 6.33547e-4 -0.9987811 -0.04909557 -0.005099117 -0.9995477 -0.02665704 -0.01392716 -0.9998125 -0.01222461 -0.01502496 -0.9997912 -6.97131e-4 -0.02042633 -0.9997893 -0.002151906 -0.02041751 -0.9997414 0.002183139 -0.02263718 -0.9997339 -0.00253278 -0.02292943 -0.9997643 -0.0092929 -0.01962327 -0.9998198 -0.001567363 -0.01892125 -0.9998371 -0.00990808 -0.01509779 -0.9998976 -7.10218e-4 -0.01429605 -0.9999087 -0.007227659 -0.01142287 -0.9999386 -0.001612186 -0.01097184 -0.9999341 -0.007996678 -0.008233487 -0.9999251 -0.008985817 -0.008306145 -0.9998922 -0.01319497 -0.006447374 -0.9994829 -0.03130155 -0.007364153 -0.9994252 -0.03327763 -0.006471931 -0.9972856 -0.07331264 -0.006834745 -0.997254 -0.07375627 -0.006677567 -0.995348 -0.09610766 -0.006753802 -0.9958378 -0.09080857 -0.007804334 -0.9979722 -0.06325817 -0.007068693 -0.9982231 -0.05912756 -0.007404088 -0.9999883 0.00233376 -0.004252493 -0.9999908 -0.001146554 -0.004152297 -0.9993594 0.03575205 -0.001643478 -0.9994017 0.03454953 -0.001626968 -0.9938094 0.1110259 0.00403738 -0.9929242 0.1186865 0.003872036 -0.6958391 -0.7094154 -0.1119727 -0.7271418 -0.6755708 -0.1219382 -0.9018576 -0.4151976 -0.119432 -0.9097008 -0.3968892 -0.1221617 -0.958012 -0.2614044 -0.1178175 -0.9574258 -0.2636783 -0.1175152 -0.9800291 -0.1631616 -0.1136727 -0.9789507 -0.170241 -0.1125761 -0.9915753 -0.07047009 -0.1086852 -0.9912776 -0.07626032 -0.1074852 -0.9944267 -0.011684 -0.1047815 -0.9944003 -0.01046729 -0.1051598 -0.9945682 0.005885839 -0.103921 -0.9942812 0.01130235 -0.1061943 -0.9941664 0.002351105 -0.107831 -0.994093 0.003859996 -0.1084637 -0.9934371 -0.01210021 -0.1137381 -0.9936016 -0.02909028 -0.1091311 -0.9946436 -0.01307064 -0.1025345 -0.9941844 -0.04551404 -0.09760075 -0.9964663 -0.009337604 -0.08347308 -0.9959154 -0.04580831 -0.07780891 -0.9977748 -0.008844316 -0.0660867 -0.9971703 -0.04858654 -0.05736464 -0.9987272 -0.0124967 -0.04886788 -0.9981651 -0.04633826 -0.03897911 -0.9988781 -0.03012645 -0.03653657 -0.9980366 -0.05612397 -0.0278055 -0.9972307 -0.06863945 -0.02862602 -0.9963366 -0.08184331 -0.02480322 -0.9954 -0.09248262 -0.02501952 -0.9964434 -0.07962965 -0.02756273 -0.9963259 -0.08108079 -0.02758419 -0.9978941 -0.05725049 -0.03049194 -0.9992069 -0.02637827 -0.02983105 -0.9994459 -0.01213365 -0.03099656 -0.9987327 0.04053664 -0.0298292 -0.9987874 0.03922861 -0.02974635 -0.9886998 0.1472782 -0.027965 -0.9909774 0.131296 -0.02692759 0.9922385 0.01694869 0.1231893 0.3610363 0.472621 0.8039168 0.9334124 0.1231616 0.337005 0.832801 0.2277678 0.5045438 0.1171876 0.9430172 0.3114253 0.9472963 0.2830352 0.15007 0.284264 0.8623394 0.4190046 0.9809333 0.1353674 0.1394474 0.9951396 0.05544143 0.08138513 0.4216659 0.6447656 0.6375541 0.990906 0.06129008 0.1197868 0.5530551 0.526145 0.6459888 0.9848278 0.06754386 0.1598499 0.4954792 0.5082241 0.7044208 0.9821166 0.05437082 0.1802516 0.6366192 0.3997702 0.6594693 0.9819818 0.02693057 0.1870466 0.7613335 0.2680106 0.5903742 0.9786376 0.001426994 0.2055881 0.728545 0.2258998 0.6466772 0.9377101 0.02587467 0.346454 0.6098994 0.2318683 0.7577993 0.9568146 -0.1054208 0.2709102 -0.008726298 0.2977958 0.9545898 0.720126 -0.05217647 0.6918787 0.3442754 -0.0677073 0.9364241 0.5558897 -0.3574309 -0.7504864 0.8027731 -0.5725299 -0.1666287 -0.512602 0.2045431 -0.8339074 -0.5062216 0.2006464 -0.8387377 0.4684029 -0.1415563 0.8721013 0.4422192 -0.1318929 0.8871564 0.4985944 -0.1806817 0.8477959 0.4479873 -0.1685491 0.8780084 0.4416127 -0.1659128 0.8817319 0.4354328 -0.165652 0.8848491 0.4879717 -0.1720115 0.8557427 0.7775681 -0.165948 0.6065058 0.8388403 0.5401907 0.06738764 0.828824 0.555147 0.06973427 0.9975638 0.06471925 0.02603596 0.8050048 0.565414 0.1796508 0.9981937 0.04831218 0.03571188 0.9380564 0.3098253 0.1551083 0.9982253 0.03528445 0.0479716 0.8677959 0.4155796 0.272441 0.9980763 0.01673448 0.05969786 0.8445525 0.3985276 0.3576408 0.9974742 -0.00322622 0.07095718 0.8399999 0.3373364 0.4249756 0.9957209 -0.0205366 0.09010034 0.8133597 0.2806024 0.5096158 0.9882016 -0.01791703 0.1521071 0.8261394 0.2063723 0.5243131 0.9758718 -0.03371089 0.2157264 0.8490946 0.1347146 0.5107743 0.9711777 -0.1922843 0.140857 0.7004516 0.1187188 0.7037566 0.8925943 -0.4344278 0.1206156 0.5011943 -0.0407018 0.8643772 0.5977277 -0.1579748 0.7859807 0.5549535 -0.265666 0.78832 0.3285688 0.2574416 0.9087169 0.6447187 -0.08378434 0.7598145 0.6298237 -0.1073188 0.7692885 0.6226931 -0.1012504 0.7758876 0.6096577 -0.1261109 0.7825686 0.6512797 -0.1504661 0.7437706 0.6656053 -0.1815133 0.723894 0.7060117 -0.1881099 0.6827607 0.7060735 -0.2407282 0.6659656 0.5863736 -0.2080927 0.7828561 0.5449742 -0.2287675 0.8066404 0.5308211 -0.2119294 0.8205577 0.4989507 -0.2275882 0.8362128 0.5002738 -0.21329 0.8391863 0.8626689 0.5034355 0.04853147 0.9919242 0.1267474 0.004648387 0.7575211 0.6526394 0.01495695 0.9872793 0.158985 0.001832306 0.9938409 0.1107941 0.002245426 0.995375 0.09604746 0.001844346 0.9971238 0.07575184 0.002421855 0.9938689 0.1105065 0.00361073 0.9982797 0.0584079 0.005131602 0.9793879 0.2016255 0.01210659 0.9995116 0.02907007 0.01147466 0.9563994 0.2890057 0.04214197 0.9997566 0.00803411 0.02054983 0.9420425 0.3202147 0.1000933 0.9994011 -0.008578062 0.03352606 0.9485577 0.2668308 0.17041 0.9983662 -0.01870083 0.0539931 0.9770163 0.1289033 0.1697736 0.9964401 -0.03161102 0.07815307 0.9861313 0.05002075 0.15825 0.992633 -0.04606753 0.1120603 0.9865003 0.009027779 0.1635102 0.9776512 -0.1064014 0.1813204 0.9738554 -0.02551633 0.2257316 0.9053387 -0.17351 0.3876289 0.9217279 -0.06922918 0.3816084 0.9912917 0.1315181 -0.006625413 0.9723212 -0.04612171 0.2290508 0.8414676 -0.1487172 0.5194379 0.830216 -0.1547439 0.5355331 0.7780103 -0.1766271 0.6029121 0.7966139 -0.1672998 0.5808762 0.7026411 -0.1981692 0.6833919 0.7001085 -0.1997921 0.6855154 0.5958032 -0.2256354 0.7707836 0.6001424 -0.2404283 0.7629046 0.5278955 -0.274621 0.8036851 0.5303364 -0.318149 0.7858274 0.9887645 0.1471641 0.02621906 0.9986592 0.05150586 0.005195975 0.9545958 0.2966856 0.02691888 0.9992721 0.03811502 0.001674771 0.9948261 0.1015419 0.003237187 0.9994674 0.032633 -2.06764e-6 0.9956579 0.09307634 -0.001503825 0.998959 0.04558688 -0.001726567 0.9930357 0.1176574 -0.006060063 0.9971643 0.07511335 -0.004632711 0.9954675 0.09489309 -0.006309807 0.9951161 0.09849816 -0.0064978 0.9982858 0.05848032 -0.002376079 0.9922916 0.1238135 -0.005258798 0.999634 0.0266661 0.004588484 0.9866287 0.162899 0.005283832 0.9999105 -5.17386e-4 0.01337158 0.9949153 0.09743392 0.02550387 0.9996215 -0.01872807 0.02015626 0.9993109 0.01979517 0.03140121 0.9994214 -0.01854056 0.02851992 0.9991228 0.009453356 0.04079759 0.9987245 -0.02004659 0.04634392 0.9986313 -0.005126416 0.05205082 0.9967411 -0.02465683 0.07680815 0.9966375 -0.02673089 0.07745581 0.9261048 -0.184127 0.3292828 0.9618712 -0.1259201 0.2427921 0.9654572 -0.1199533 0.231309 0.9504873 -0.1488904 0.2727737 0.9586853 -0.1376197 0.2489645 0.9266917 -0.2004906 0.3178774 0.857621 -0.2621828 0.4424325 0.8245148 -0.3625504 0.4344338 0.6146445 -0.5102741 0.6015252 0.5988092 -0.6057528 0.5239191 0.9983826 0.05491852 0.01470208 0.9991933 0.03913307 0.00902456 0.9982805 0.05719065 0.0128653 0.999517 0.0304706 0.006120204 0.9983882 0.05576169 0.01056128 0.9996023 0.02780586 0.004716098 0.9960664 0.0876221 0.01320111 0.9994729 0.03221863 0.003979682 0.9823002 0.1863054 0.01941305 0.9992904 0.03759038 0.002415955 0.9817836 0.1897723 0.00935626 0.9992152 0.03961235 7.52277e-5 0.9895191 0.1443924 -0.001681506 0.9989974 0.044703 -0.002437651 0.9946377 0.1031996 -0.006766319 0.9986617 0.0515024 -0.004723548 0.9996255 0.02727633 -0.002272546 0.9998727 -0.01595383 -4.83799e-4 0.9999466 -0.01029741 -8.698e-4 0.9998136 -0.01925981 -0.001386404 0.9999986 3.26718e-4 -0.001695215 0.9997586 0.02158635 0.00410068 0.9999746 -0.00440967 0.005600273 0.9999031 0.008526682 0.01100629 0.9998525 -0.01055371 0.01355773 0.9998558 -0.005441844 0.01608872 0.9995807 -0.02185171 0.01900005 0.9995504 -0.02383148 0.01819866 0.9977586 -0.06195223 0.02529442 0.996922 -0.07470786 0.0237782 0.9778981 -0.2013779 0.05623364 0.9826961 -0.1773135 0.05355799 0.985092 -0.164938 0.04887968 0.9682603 -0.24382 0.05498927 0.9813032 -0.1893382 0.03457188 0.9424948 -0.3330913 0.02745485 0.9199637 -0.389805 0.04145866 0.8581174 -0.5134515 0.001533448 0.5734261 -0.8191126 -0.01540094 0.5848711 -0.8111255 -0.001217782 0.9991274 0.04003489 0.01190423 0.9991979 0.03843605 0.01123392 0.9993135 0.03554844 0.01043659 0.9994333 0.03232669 0.009385049 0.9992817 0.03642672 0.01045542 0.9994607 0.03159952 0.008932769 0.9988309 0.04666346 0.01263105 0.9994298 0.03265553 0.00859487 0.9980993 0.05986016 0.01464694 0.9994307 0.03288769 0.007528781 0.9978558 0.06406533 0.01339703 0.9994889 0.03144323 0.005788803 0.9972438 0.07324904 0.01181793 0.9996047 0.02792477 0.003258943 0.9951121 0.09825408 0.009901702 0.9999964 0.002008438 -0.001841723 0.9969925 -0.07726293 -0.006048619 0.9759742 -0.2174201 -0.01424807 0.9994282 -0.03297281 -0.007497549 0.9997024 -0.02347141 -0.006659924 0.9998086 0.01857662 -0.006141483 0.9995175 0.03091603 -0.003007173 0.9999665 0.007761478 -0.002593457 0.9998683 0.01622408 5.25245e-4 0.9999856 -0.005341053 6.04627e-4 0.9999651 -0.008332669 -7.38372e-4 0.9996827 -0.0251255 -0.00183022 0.9986819 -0.04971539 -0.01276665 0.995936 -0.08815735 -0.01843863 0.9876872 -0.1509149 -0.04121595 0.9651239 -0.2548503 -0.05989396 0.944156 -0.3198345 -0.07921773 0.9437646 -0.3209395 -0.0794112 0.8815746 -0.4563645 -0.1206562 0.9126932 -0.3939355 -0.1086556 0.8044745 -0.5702915 -0.1660981 0.8034489 -0.5716508 -0.1663889 0.6905524 -0.6920866 -0.2101274 0.4996498 -0.8313134 -0.2434507 0.4866195 -0.8375034 -0.2485749 0.9992054 0.03833866 0.01089709 0.9991427 0.03976821 0.01151353 0.9994229 0.03259068 0.009586513 0.9993814 0.03371661 0.01000744 0.9994217 0.03260046 0.009678363 0.9993965 0.03328818 0.009928524 0.9993347 0.03497302 0.01035529 0.999387 0.03357321 0.009927332 0.9992678 0.03673368 0.01070106 0.9994297 0.03244763 0.009361088 0.9992858 0.03635942 0.01028466 0.9995498 0.02893894 0.007929444 0.9993696 0.03431189 0.009119808 0.999839 0.01748615 0.004062652 0.9999601 0.008635759 0.00227648 0.9994316 -0.03271377 -0.0081501 0.3669002 -0.9155066 -0.1650209 0.9954616 -0.09393781 -0.01523524 0.9997127 -0.02308702 -0.006443262 0.9997947 0.02020978 0.001506984 0.9994809 0.03217303 0.001733601 0.9995052 0.03141802 0.001531422 0.9998645 0.01637393 0.001719474 0.9999686 0.007874906 -9.94781e-4 0.9999632 -0.008428156 -0.001618802 0.9993263 -0.03486371 -0.01146942 0.9986653 -0.04986667 -0.0134536 0.992162 -0.1183956 -0.03996551 0.9868176 -0.1546115 -0.04781645 0.955454 -0.2798055 -0.0938965 0.9310008 -0.3476387 -0.1112882 0.8714293 -0.4660623 -0.152961 0.8552768 -0.4928265 -0.1600745 0.7724211 -0.6031818 -0.1988402 0.7757647 -0.5992299 -0.1977696 0.6856095 -0.6906423 -0.2301148 0.6601263 -0.7130447 -0.2362216 0.5841764 -0.7699203 -0.2568283 0.4649254 -0.8412266 -0.2760115 0.4336438 -0.8552218 -0.2838113 0.9991763 0.0393458 0.009938538 0.9991068 0.04090064 0.01062417 0.9994382 0.03242313 0.008491337 0.9994523 0.03202694 0.008332967 0.9994763 0.03131556 0.008150517 0.9995014 0.03056448 0.007923483 0.9994617 0.03176391 0.008215129 0.9995339 0.02958893 0.007514595 0.9994884 0.03100663 0.00786215 0.9996904 0.02423387 0.005649209 0.999598 0.02761524 0.006424963 0.9998926 0.01451236 0.002084374 0.9998676 0.01609313 0.002435564 0.9999124 -0.01151722 -0.006534278 0.9992092 -0.03779488 -0.01235765 0.9949831 -0.09567999 -0.02922445 0.9910269 -0.1285526 -0.03660446 0.9960319 -0.08544862 -0.02488005 0.9998509 0.01623284 -0.005898594 0.9996911 0.02467596 -0.002980053 0.9995273 0.03064942 -0.00239551 0.999706 0.02372157 -0.005028307 0.9999564 0.006831467 -0.006365299 0.9998146 -0.01357817 -0.01365816 0.9992095 -0.03622919 -0.01636773 0.9951789 -0.09129947 -0.03582638 0.9920653 -0.1188681 -0.04094851 0.9680094 -0.2370058 -0.0823785 0.9559985 -0.2785078 -0.09219729 0.8934907 -0.4257388 -0.1429018 0.8711531 -0.4664361 -0.1533943 0.7933958 -0.5778994 -0.1911949 0.773895 -0.601737 -0.1974824 0.6913544 -0.6862459 -0.2260436 0.6912111 -0.68638 -0.2260748 0.6071314 -0.7545895 -0.2489704 0.5929352 -0.7648954 -0.25172 0.5179877 -0.812343 -0.267932 0.4394592 -0.8540175 -0.278442 0.4104715 -0.8663476 -0.2845263 0.9991951 0.03996115 0.003521502 0.9988301 0.04775333 0.007618606 0.9995951 0.0283569 0.002353608 0.9998074 0.01958996 -0.001175701 0.9997186 0.02372634 -3.92962e-5 0.9998677 0.01600152 -0.002954304 0.9997506 0.02230179 -0.00122559 0.9999477 0.007738113 -0.00669074 0.9998518 0.01666426 -0.00432372 0.9998595 -0.009077787 -0.01409447 0.9999292 0.005582809 -0.01051735 0.9992534 -0.0303418 -0.02391993 0.9994637 -0.02375119 -0.02254527 0.9972167 -0.06516551 -0.03622668 0.9927124 -0.1122916 -0.04373514 0.9959896 -0.08176219 -0.03632682 0.9944632 -0.09798228 -0.03798115 0.99656 -0.07583534 -0.0334261 0.9994179 0.01884019 -0.02844464 0.9992609 -0.00861746 -0.03746151 0.9991605 0.01958298 -0.03598517 0.9986016 -0.0172196 -0.04998391 0.998471 -0.02246785 -0.05050569 0.9944092 -0.07873696 -0.07036268 0.9913498 -0.107883 -0.07474625 0.9699255 -0.2170602 -0.1101337 0.9578935 -0.2615169 -0.118529 0.8943184 -0.4157478 -0.1653742 0.8752183 -0.4518769 -0.1726277 0.7924991 -0.5734613 -0.2075746 0.7724574 -0.5984664 -0.2124801 0.6945613 -0.6800729 -0.2347033 0.674932 -0.6984179 -0.2380745 0.6052265 -0.7549286 -0.2525547 0.5996313 -0.7591404 -0.2532751 0.5364427 -0.8017702 -0.2634275 0.524696 -0.809144 -0.2645376 0.4700214 -0.8398526 -0.271528 0.4217999 -0.8641839 -0.2743558 0.3969467 -0.8747502 -0.2779311 -0.3950266 0.8874415 -0.2374904 -0.3970353 0.8821412 -0.2533571 -0.2800031 0.6618061 -0.6954214 -0.3017365 0.737964 -0.603626 -0.15338 0.4457573 -0.8819156 -0.1942383 0.5638419 -0.8027166 -0.04955548 0.2711204 -0.961269 -0.07590341 0.3570296 -0.9310041 0.02879804 0.1370697 -0.9901428 0.02614367 0.1490735 -0.9884805 0.06662809 0.05871933 -0.9960486 0.07205551 0.02282267 -0.9971395 0.07862973 0.007169425 -0.9968782 0.08429628 -0.03746283 -0.9957363 0.06930446 3.85849e-4 -0.9975956 0.07580178 -0.03598845 -0.9964733 0.06326091 -0.002051591 -0.997995 0.06727242 -0.02320402 -0.9974648 0.05857789 0.002637743 -0.9982793 0.061926 -0.01913088 -0.9978975 0.05947071 -0.01075947 -0.9981722 0.06130164 -0.02518767 -0.9978014 0.06952959 -0.05676674 -0.9959635 0.06794762 -0.04486507 -0.9966797 0.09074002 -0.1357237 -0.9865827 0.08134573 -0.0774191 -0.9936746 0.1295092 -0.2640558 -0.9557729 0.1056743 -0.1413347 -0.9843056 0.1804739 -0.4233552 -0.8878061 0.1438693 -0.2513628 -0.9571408 0.2275367 -0.5692784 -0.790031 0.2013943 -0.4441009 -0.8730492 0.2539913 -0.658222 -0.7086834 0.2415915 -0.5926731 -0.7683568 0.2701753 -0.7214037 -0.6376378 0.2622606 -0.6737638 -0.6908414 0.2874675 -0.8048941 -0.5191416 0.2852092 -0.7825726 -0.5533858 0.2987076 -0.8834556 -0.3609431 0.3001827 -0.8751201 -0.3795462 -0.4142082 0.8788367 -0.2368076 -0.3132119 0.7111186 -0.6294512 -0.3329005 0.7418507 -0.5820953 -0.2995467 0.6783817 -0.6708726 -0.2441898 0.5800489 -0.7771193 -0.1918784 0.4697254 -0.8617081 -0.1495214 0.38678 -0.9099695 -0.1133801 0.3015547 -0.9466836 -0.05999845 0.1888658 -0.9801684 -0.04137003 0.1377632 -0.9896008 -0.0162971 0.07973295 -0.9966831 -0.006279408 0.04652166 -0.9988976 -0.001248538 0.03350132 -0.999438 0.003135621 0.01536506 -0.9998771 1.97778e-4 0.02396708 -0.9997128 0.002675592 0.01266056 -0.9999163 7.26634e-5 0.02115595 -0.9997762 0.001624226 0.01352828 -0.9999072 0.001249551 0.01486563 -0.9998888 0.002066373 0.0102995 -0.9999449 0.003181755 0.005958437 -0.9999772 0.003239333 0.005591273 -0.9999791 0.006595969 -0.008494675 -0.9999422 0.005478858 -8.94823e-4 -0.9999847 0.01142454 -0.02676773 -0.9995765 0.008840858 -0.009634017 -0.9999145 0.02101868 -0.06191575 -0.9978601 0.01470935 -0.02495604 -0.9995804 0.04022938 -0.1272927 -0.9910491 0.0246486 -0.05046874 -0.9984214 0.08245158 -0.2603778 -0.9619798 0.05163973 -0.1339844 -0.9896371 0.1273435 -0.3972527 -0.9088311 0.1027644 -0.3031144 -0.947397 0.1564546 -0.4898786 -0.8576368 0.1473235 -0.4550052 -0.8782176 0.2140355 -0.6917728 -0.689666 0.2118632 -0.6826863 -0.6993236 0.2625869 -0.8722061 -0.4126797 0.2622082 -0.8603054 -0.4371744 -0.2155211 0.6944181 -0.6865378 -0.1063167 0.3924245 -0.9136192 -0.1865938 0.5985813 -0.7790271 -0.1162481 0.3989411 -0.9095782 -0.118077 0.4038887 -0.9071559 -0.04040032 0.1672087 -0.9850934 -0.07747024 0.2713068 -0.9593701 -0.02751755 0.10868 -0.9936959 -0.03605717 0.133567 -0.9903836 -0.01515519 0.05890774 -0.9981485 -0.01307022 0.05243068 -0.9985391 -0.007592558 0.03010892 -0.9995179 -0.005921006 0.02440547 -0.9996846 -0.005420982 0.02197229 -0.9997439 -0.004895627 0.01994937 -0.999789 -0.005313992 0.0222451 -0.9997385 -0.004513561 0.018821 -0.9998127 -0.005042612 0.02202987 -0.9997447 -0.003423333 0.01449763 -0.9998891 -0.004051804 0.01883316 -0.9998145 -0.002195835 0.009474515 -0.9999528 -0.002848982 0.0147224 -0.9998877 -7.95374e-4 0.003441214 -0.9999939 -0.001461386 0.009775876 -0.9999512 8.74364e-4 -0.004212379 -0.9999908 2.07721e-4 0.003295719 -0.9999946 0.003495216 -0.01740652 -0.9998424 0.002426385 -0.004380702 -0.9999875 0.00846374 -0.03888756 -0.9992077 0.005817532 -0.0130009 -0.9998986 0.02577543 -0.104248 -0.9942173 0.01526576 -0.04340499 -0.9989409 0.06379115 -0.2391091 -0.9688951 0.04302763 -0.1446715 -0.9885438 0.09990966 -0.3678582 -0.924499 0.08921253 -0.3215292 -0.9426877 0.1617823 -0.6100721 -0.7756537 0.1624189 -0.6130124 -0.7731986 0.2209299 -0.8548135 -0.4695573 0.2205251 -0.8457006 -0.4859621 -0.07107532 0.3845958 -0.9203448 -0.04432928 0.2487981 -0.9675404 -0.06250405 0.332354 -0.9410814 -0.03311091 0.182161 -0.9827111 -0.02666091 0.1522247 -0.9879863 -0.01131141 0.06920808 -0.9975382 -0.01758837 0.09813159 -0.9950181 -0.007498323 0.04149878 -0.9991105 -0.01005983 0.05346065 -0.9985193 -0.006038963 0.02964454 -0.9995422 -0.005705118 0.02801287 -0.9995913 -0.005629301 0.02752047 -0.9996054 -0.004332244 0.02066892 -0.999777 -0.005470037 0.02919739 -0.9995588 -0.004035711 0.02071797 -0.9997773 -0.005372643 0.03219056 -0.9994673 -0.003610312 0.02047145 -0.999784 -0.004910588 0.03352463 -0.9994259 -0.002828955 0.01777768 -0.9998381 -0.003864705 0.03084808 -0.9995166 -0.001968622 0.01407408 -0.999899 -0.002602934 0.02537745 -0.9996746 -0.001133382 0.009549856 -0.9999538 -0.00137782 0.01743936 -0.999847 -3.65778e-4 0.003633856 -0.9999934 -3.74972e-4 0.007407248 -0.9999725 3.28241e-4 -0.003610134 -0.9999935 4.45866e-4 3.50885e-4 -1 0.001488685 -0.01191449 -0.9999279 0.001737236 -0.003910779 -0.9999909 0.006561815 -0.03904056 -0.9992161 0.005167663 -0.01588553 -0.9998605 0.0242359 -0.1233825 -0.9920632 0.01569092 -0.06200963 -0.9979523 0.05312317 -0.2582787 -0.9646088 0.04170292 -0.1893585 -0.9810221 0.1059658 -0.5281794 -0.842495 0.1027666 -0.5078788 -0.8552767 0.1630544 -0.8386547 -0.5196841 0.1630011 -0.8338826 -0.5273239 -0.03263121 0.2546755 -0.9664759 -0.04309445 0.3681374 -0.9287723 -0.02000212 0.1773624 -0.9839424 -0.01942586 0.1716713 -0.9849628 -0.007094204 0.06901812 -0.9975902 -0.005407094 0.05022084 -0.9987236 -0.004213452 0.04005372 -0.9991887 -0.003666579 0.0333454 -0.9994372 -0.002969324 0.02698701 -0.9996315 -0.003441691 0.03362506 -0.9994287 -0.002491176 0.02381449 -0.9997134 -0.00329262 0.03803628 -0.999271 -0.002188742 0.02441358 -0.9996996 -0.002844929 0.04167085 -0.9991274 -0.001890301 0.0266422 -0.9996433 -0.002263545 0.04437029 -0.9990127 -0.001520156 0.02863383 -0.9995889 -0.001631736 0.04631698 -0.9989256 -0.001045644 0.02831023 -0.9995987 -9.22332e-4 0.04440855 -0.9990131 -5.38138e-4 0.02428084 -0.9997051 -2.63217e-4 0.03638762 -0.9993378 -1.38432e-4 0.01693135 -0.9998567 9.21381e-5 0.02263408 -0.9997438 3.16682e-5 0.007294416 -0.9999734 7.02859e-5 0.007845461 -0.9999693 3.63062e-5 3.87425e-4 -1 1.31029e-4 0.00115019 -0.9999994 2.00031e-4 -0.003887772 -0.9999924 5.74303e-4 -0.001488149 -0.9999988 0.001255154 -0.01549381 -0.9998792 0.001817047 -0.007184207 -0.9999727 0.006228327 -0.05737775 -0.9983332 0.005166947 -0.02761018 -0.9996055 0.02029478 -0.1589868 -0.9870722 0.01404398 -0.08847838 -0.9959792 0.06002384 -0.4467689 -0.8926337 0.04719841 -0.3209461 -0.9459208 0.1153655 -0.8313847 -0.5435903 0.1153717 -0.8053381 -0.5814808 0.008145332 0.4643359 -0.8856217 -0.008332669 0.1674225 -0.98585 -0.009497702 0.1889375 -0.9819433 -0.009382545 0.1839948 -0.9828824 -0.002526044 0.05637568 -0.9984065 -0.002759754 0.07639968 -0.9970734 -0.001289665 0.03653955 -0.9993314 -0.001205503 0.05653649 -0.9983999 -7.75236e-4 0.03439474 -0.999408 -3.14611e-4 0.0588864 -0.9982647 -2.28474e-4 0.03627693 -0.9993419 6.12649e-4 0.06086361 -0.998146 3.72026e-4 0.0379185 -0.9992808 0.001500725 0.06017357 -0.9981869 0.001005947 0.03977108 -0.9992084 0.002180397 0.05764156 -0.998335 0.001623988 0.04224824 -0.9991059 0.002507269 0.05374175 -0.9985518 0.002006292 0.04244709 -0.9990968 0.002427399 0.0474717 -0.9988697 0.001851379 0.03565466 -0.9993625 0.001882791 0.03600341 -0.99935 0.001197218 0.02230495 -0.9997505 0.00101155 0.02045589 -0.9997903 4.14254e-4 0.007764875 -0.9999698 2.93641e-4 0.006870388 -0.9999765 7.71484e-5 0.00115478 -0.9999994 1.128e-4 0.001320719 -0.9999992 3.39785e-5 -0.001485943 -0.999999 2.85106e-4 -5.84918e-4 -0.9999998 1.9482e-4 -0.007122337 -0.9999746 8.59795e-4 -0.003776788 -0.9999926 0.00157845 -0.02654951 -0.9996463 0.002346396 -0.01434463 -0.9998944 0.008132398 -0.08237916 -0.9965679 0.006767094 -0.04603046 -0.9989171 0.03841829 -0.3096374 -0.9500784 0.02796018 -0.1862344 -0.9821074 0.1131812 -0.8051996 -0.5821027 0.1121867 -0.752125 -0.6494014 0.01095384 0.2121556 -0.9771745 0.005570411 0.1526415 -0.988266 0.002454996 0.2092097 -0.9778677 9.47624e-4 0.1791352 -0.983824 8.4122e-4 0.08444696 -0.9964277 0.002763092 0.1102762 -0.9938972 0.00128895 0.05982524 -0.9982081 0.00322467 0.08039164 -0.9967582 0.002293765 0.05960702 -0.9982194 0.003599703 0.07182729 -0.9974107 0.002947151 0.05973941 -0.9982097 0.004132568 0.06968343 -0.9975606 0.003436326 0.05843085 -0.9982857 0.004377722 0.06545066 -0.9978462 0.003733277 0.05603772 -0.9984217 0.004407525 0.06058281 -0.9981535 0.003808617 0.05247849 -0.9986149 0.003694355 0.05176907 -0.9986523 0.003332138 0.04680013 -0.9988988 0.002704262 0.04298126 -0.9990723 0.002227604 0.03575766 -0.9993581 0.001389026 0.03078913 -0.999525 8.72716e-4 0.02056449 -0.9997882 2.9886e-4 0.01745432 -0.9998477 3.05099e-5 0.007031977 -0.9999753 -6.99414e-5 0.006645023 -0.999978 -9.03959e-5 0.001379609 -0.9999991 4.26937e-6 0.001604676 -0.9999988 -1.5542e-5 -5.50987e-4 -1 1.82272e-4 -1.96304e-4 -1 1.05677e-4 -0.00367707 -0.9999933 7.19493e-4 -0.002426564 -0.9999969 0.001044332 -0.01385533 -0.9999035 0.002268314 -0.009581565 -0.9999516 0.006194353 -0.04549944 -0.9989452 0.007009148 -0.03417545 -0.9993914 0.03193473 -0.1913905 -0.9809944 0.0302146 -0.1541172 -0.9875905 0.136123 -0.7594749 -0.6361355 0.1371716 -0.730114 -0.6694159 0.180921 0.4092182 -0.89432 0.127281 0.2898656 -0.9485661 0.04257559 0.09848141 -0.9942277 0.02657431 0.06297028 -0.9976616 0.009892582 0.02489274 -0.9996412 0.003828823 0.01172107 -0.999924 0.003404796 0.01071178 -0.9999369 8.89729e-4 0.005470156 -0.9999847 0.002049803 0.008630156 -0.9999607 5.11934e-4 0.005372881 -0.9999855 0.001590251 0.009305238 -0.9999555 2.58511e-4 0.005738019 -0.9999835 0.001248776 0.01086515 -0.9999403 -2.49588e-4 0.005361795 -0.9999857 4.08751e-4 0.01004803 -0.9999495 -0.001629233 7.46348e-4 -0.9999985 -0.001185059 0.006948649 -0.9999752 -0.002920925 -0.003415584 -0.9999899 -0.003628194 0.01268839 -0.999913 -0.004116296 0.001540064 -0.9999904 -0.006158292 0.01964432 -0.9997881 -0.006101608 0.01779693 -0.999823 -0.006217956 0.01873314 -0.9998052 -0.006515324 0.02634048 -0.9996318 -0.004360854 0.008446872 -0.9999549 -0.004434525 0.01628941 -0.9998576 -0.003063321 0.002325952 -0.9999926 -0.002650856 0.00815767 -0.9999633 -0.002028405 -0.00161308 -0.9999967 -0.001242995 0.003961622 -0.9999915 -3.70995e-4 -0.01689213 -0.9998573 -2.34477e-4 -0.01570576 -0.9998767 0.002818107 -0.1065128 -0.9943073 0.002190351 -0.1183 -0.9929755 0.02019178 -0.7225213 -0.6910538 0.01613408 -0.7786192 -0.6272894 -0.002553343 0.002095997 -0.9999946 -0.005334377 -0.007269978 -0.9999594 -0.004320859 0.01740896 -0.9998391 -0.00568819 0.007801711 -0.9999534 -0.005579113 0.02605807 -0.9996449 -0.005927443 0.02246111 -0.9997302 -0.005855083 0.01655703 -0.9998458 -0.005751729 0.01778137 -0.9998254 -0.005499243 0.008096039 -0.9999521 -0.004574775 0.01604831 -0.9998608 -0.004208326 0.003350198 -0.9999856 -0.002460241 0.01422256 -0.9998959 -0.00163114 -0.01626098 -0.9998666 -0.001015245 -0.01133364 -0.9999353 0.00104773 -0.1190513 -0.9928876 -8.7517e-4 -0.148725 -0.9888783 0.00783807 -0.7803811 -0.6252551 7.50378e-4 -0.8476032 -0.5306302 -0.004567265 0.008312046 -0.9999551 -0.006807386 0.002036392 -0.9999747 -0.005254149 0.02251982 -0.9997326 -0.006014108 0.01990669 -0.9997838 -0.006121158 0.01776552 -0.9998235 -0.006275415 0.01719045 -0.9998326 -0.006303846 0.01566022 -0.9998576 -0.005216479 0.01940608 -0.9997981 -0.00518161 0.01298183 -0.9999024 -0.002704203 0.02062565 -0.9997836 -0.002053737 -0.0121814 -0.9999237 -9.0745e-4 -0.007125973 -0.9999743 0.001045763 -0.1456943 -0.9893292 -0.001199305 -0.1648719 -0.9863144 0.005262315 -0.8454909 -0.5339639 -0.001510739 -0.8723549 -0.4888709 0.1655127 0.95173 -0.2584872 0.1537296 0.9532095 -0.2603055 0.1168994 0.6825095 -0.7214675 0.1266121 0.6844844 -0.7179489 0.04575848 0.1527031 -0.9872123 0.0528959 0.1558824 -0.9863584 0.03118199 0.03669559 -0.99884 0.0351141 0.03689736 -0.998702 0.02164471 -0.01954251 -0.9995747 0.01636099 -0.01311057 -0.9997802 0.01092928 -0.02386748 -0.9996554 5.91924e-4 -0.007943511 -0.9999683 0.004404783 -0.004240453 -0.9999814 -0.002340495 -0.002082824 -0.9999952 0.00105977 6.0428e-4 -0.9999994 -0.002235054 -1.97011e-4 -0.9999975 -8.45105e-4 8.56508e-4 -0.9999993 0.001509726 0.001688778 -0.9999975 1.82854e-4 6.15832e-4 -0.9999999 0.008881866 0.002727806 -0.9999569 0.00633645 -1.42788e-4 -0.9999799 0.01992332 0.001194834 -0.9998008 0.01901215 -0.002712666 -0.9998157 0.01698946 -0.002957224 -0.9998514 -0.006695866 0.9639707 -0.2659246 -0.01060634 0.9475626 -0.3193944 -0.007875859 0.6583371 -0.752682 -0.01054221 0.5355414 -0.8444433 -0.002953648 0.133403 -0.9910575 -0.003121674 0.0885033 -0.9960711 -0.001585781 0.04202258 -0.9991155 -0.001455903 0.02266454 -0.9997421 -0.001389801 0.02148443 -0.9997683 -0.001089155 0.01084363 -0.9999407 -4.14206e-4 0.002954661 -0.9999957 -4.21359e-4 0.00308156 -0.9999952 4.36788e-4 -0.004523158 -0.9999898 3.67493e-4 -0.002714037 -0.9999963 1.69153e-4 -0.001111865 -0.9999995 1.2331e-4 -0.001416921 -0.999999 -2.48228e-5 4.91376e-4 -0.9999999 -1.48314e-4 2.46163e-4 -1 -1.38816e-4 7.68193e-4 -0.9999998 -1.23701e-4 7.92131e-4 -0.9999997 -1.33704e-4 4.50486e-4 -0.9999999 -5.2805e-5 6.10413e-4 -0.9999998 -5.66409e-5 1.31503e-5 -1 1.11962e-5 1.82521e-4 -1 9.10126e-6 -7.35691e-4 -0.9999998 1.32932e-4 -4.03223e-4 -1 9.54018e-5 -0.004877269 -0.9999881 6.11879e-4 -0.003461539 -0.9999939 3.03001e-4 -0.0205177 -0.9997895 0.00149405 -0.01697564 -0.9998549 9.019e-5 -0.05299925 -0.9985947 -2.92299e-4 -0.05444252 -0.9985169 -0.00415647 -0.1120484 -0.9936941 -0.0086959 -0.1361519 -0.9906499 -0.01573199 -0.2335034 -0.9722288 -0.01788741 -0.2474098 -0.9687458 -0.02464669 -0.3666192 -0.9300445 -0.02241659 -0.3498601 -0.9365338 -0.03441315 -0.6484425 -0.7604855 -0.0286169 -0.614359 -0.7885076 -0.02856868 0.9472978 -0.3190782 -0.03728038 0.882243 -0.469316 -0.0242328 0.5372803 -0.8430556 -0.02307659 0.392988 -0.9192541 -0.006301164 0.08838748 -0.9960663 -0.00585401 0.06981211 -0.997543 -0.002325236 0.02267926 -0.9997402 -0.002099692 0.01584124 -0.9998723 -0.001577854 0.01089799 -0.9999395 -0.001350164 0.006934404 -0.9999751 -7.90695e-4 0.003091394 -0.9999949 -8.18791e-4 0.003376126 -0.999994 3.40117e-4 -0.002713799 -0.9999963 -3.66458e-5 4.2114e-4 -1 4.16477e-4 -0.001424849 -0.9999989 3.53492e-4 -3.60161e-4 -1 1.89582e-4 2.43596e-4 -1 1.77863e-4 1.53136e-4 -1 4.25905e-5 7.89984e-4 -0.9999998 -2.11994e-6 6.2729e-4 -0.9999999 0 6.09603e-4 -0.9999999 -2.58686e-5 5.11788e-4 -1 -5.85903e-6 1.83239e-4 -1 -3.58395e-6 1.92748e-4 -1 7.27839e-6 -3.91691e-4 -1 3.06014e-5 -2.95916e-4 -1 3.25202e-5 -0.00342375 -0.9999942 1.99958e-4 -0.002744376 -0.9999963 1.29252e-4 -0.01703876 -0.9998549 6.73534e-4 -0.01464027 -0.9998926 1.62486e-4 -0.05432283 -0.9985234 1.31643e-4 -0.05449974 -0.9985138 -0.002019703 -0.1341006 -0.9909657 -0.003833413 -0.1488214 -0.9888567 -0.006792962 -0.2457981 -0.9692973 -0.007514655 -0.2523077 -0.9676179 -0.009783804 -0.3488773 -0.9371175 -0.008982717 -0.3407041 -0.9401277 -0.01364922 -0.6136145 -0.7894878 -0.01090699 -0.5925325 -0.8054728 -0.07436728 0.8808874 -0.4674475 -0.07970046 0.7989874 -0.5960429 -0.04248702 0.3980551 -0.9163771 -0.04171812 0.3805212 -0.9238308 -0.009640812 0.06989353 -0.9975079 -0.01047801 0.08820712 -0.9960471 -0.002982974 0.01602023 -0.9998673 -0.003103613 0.02137345 -0.9997668 -0.001610755 0.00699079 -0.9999744 -0.001622617 0.008088648 -0.999966 -0.00110656 0.003383874 -0.9999938 -0.001109302 0.003541886 -0.9999932 -6.7789e-4 3.81749e-4 -0.9999997 -6.8596e-4 0.001101791 -0.9999992 -3.86122e-4 -3.11451e-4 -1 -3.76462e-4 5.73083e-4 -0.9999998 -2.71099e-4 2.0044e-4 -1 -2.42942e-4 5.72633e-4 -0.9999998 -2.6377e-4 6.49766e-4 -0.9999998 -2.4063e-4 8.24875e-4 -0.9999997 -1.84236e-4 5.18993e-4 -0.9999998 -1.46378e-4 8.03521e-4 -0.9999997 -8.80019e-5 1.93474e-4 -1 -4.6203e-5 4.72453e-4 -1 -2.00542e-5 -2.96057e-4 -1 -5.75524e-6 -2.21939e-4 -1 1.37346e-5 -0.00274676 -0.9999963 2.42424e-5 -0.002697706 -0.9999964 4.85043e-5 -0.01465487 -0.9998927 1.63233e-4 -0.01407164 -0.9999011 1.63199e-4 -0.05449795 -0.9985139 1.36261e-4 -0.05468863 -0.9985035 -3.54683e-4 -0.1485441 -0.9889058 -8.5382e-4 -0.1537947 -0.9881025 -0.001531243 -0.2522079 -0.9676719 -0.001627564 -0.2532544 -0.9673984 -0.00206995 -0.3407292 -0.9401592 -0.00111711 -0.3292386 -0.9442461 -0.002354681 -0.5920104 -0.8059269 8.03863e-4 -0.5641639 -0.8256624 -0.06584596 0.8033311 -0.5918815 -0.06646978 0.7875679 -0.6126325 -0.03257888 0.3788847 -0.9248704 -0.03408092 0.435101 -0.8997364 -0.006968855 0.08614838 -0.996258 -0.00734651 0.1071718 -0.9942134 -0.002020359 0.02014774 -0.999795 -0.001945495 0.02353888 -0.9997211 -0.001253664 0.007872879 -0.9999682 -0.001210212 0.008929729 -0.9999594 -0.001011431 0.003548145 -0.9999933 -0.001065969 0.00253576 -0.9999963 -9.58698e-4 0.001051485 -0.9999991 -9.79879e-4 7.84668e-4 -0.9999992 -9.57151e-4 6.50588e-4 -0.9999994 -9.20079e-4 0.001095235 -0.9999991 -8.36905e-4 7.47017e-4 -0.9999995 -7.69412e-4 0.001529037 -0.9999986 -6.32688e-4 9.23612e-4 -0.9999994 -5.54505e-4 0.00195074 -0.999998 -3.81954e-4 8.35591e-4 -0.9999997 -2.87863e-4 0.002200663 -0.9999976 -1.56736e-4 4.73466e-4 -0.9999999 -7.47669e-5 0.001240193 -0.9999992 -4.01301e-5 -2.23326e-4 -1 -2.56978e-5 -1.41129e-4 -1 -1.19214e-5 -0.002698957 -0.9999964 -2.74659e-5 -0.002773463 -0.9999963 1.16851e-5 -0.01407253 -0.999901 7.97847e-6 -0.01409196 -0.9999007 1.33341e-4 -0.05468869 -0.9985035 6.25418e-5 -0.05522418 -0.9984741 1.20755e-4 -0.153792 -0.9881033 -8.24307e-5 -0.1561097 -0.9877398 -1.31985e-4 -0.2532567 -0.9673991 -2.01529e-4 -0.2540545 -0.96719 -2.26955e-4 -0.3292586 -0.9442398 -3.16159e-5 -0.3267608 -0.9451071 -1.38047e-4 -0.5642037 -0.8256357 0.001371324 -0.5492802 -0.8356372 0.006668031 0.8681855 -0.4961952 -0.00172615 0.7718011 -0.6358617 1.53034e-5 0.4477876 -0.8941401 -0.00384736 0.3120425 -0.9500604 -8.36752e-4 0.08677023 -0.996228 -0.001231014 0.07011431 -0.9975383 -5.54869e-4 0.01779347 -0.9998416 -5.24331e-4 0.01843494 -0.99983 -4.501e-4 0.007674753 -0.9999705 -4.22791e-4 0.008158683 -0.9999667 -3.87065e-4 0.002733528 -0.9999963 -4.20324e-4 0.002337574 -0.9999973 -3.79019e-4 0.001051247 -0.9999995 -3.84471e-4 0.001010358 -0.9999995 -3.90263e-4 0.001085698 -0.9999994 -3.52941e-4 0.00132811 -0.9999991 -3.57891e-4 0.001385152 -0.9999991 -2.75924e-4 0.001874387 -0.9999983 -2.75174e-4 0.001861691 -0.9999983 -2.03869e-4 0.002350807 -0.9999973 -1.98981e-4 0.00218743 -0.9999976 -1.94563e-4 0.002228319 -0.9999976 -1.86279e-4 0.001237213 -0.9999992 -1.84637e-4 0.001250803 -0.9999993 -1.86045e-4 -1.49699e-4 -1 -2.18201e-4 -3.25801e-4 -1 -2.19194e-4 -0.002778649 -0.9999962 -2.70469e-4 -0.003018736 -0.9999954 -2.42304e-4 -0.01408791 -0.9999008 -2.8061e-4 -0.01428616 -0.999898 -1.59626e-4 -0.05520951 -0.9984748 -2.36373e-4 -0.05579471 -0.9984423 -1.17935e-4 -0.1561093 -0.9877398 -2.54907e-4 -0.1576901 -0.9874887 -2.13684e-4 -0.2540605 -0.9671884 -2.40922e-4 -0.2543721 -0.9671064 -2.20755e-4 -0.3267694 -0.9451041 -2.47691e-4 -0.3271089 -0.9449867 -1.73266e-4 -0.5492953 -0.8356283 1.18473e-4 -0.54629 -0.8375961 0.06088507 0.8177351 -0.5723656 0.03719121 0.6445609 -0.763648 0.01875829 0.3155964 -0.9487082 0.009347081 0.2055163 -0.9786091 0.002789497 0.04686033 -0.9988976 0.001711487 0.03330391 -0.9994438 7.74126e-4 0.008558273 -0.9999632 9.44447e-4 0.01007616 -0.9999488 7.0775e-4 0.005099356 -0.9999868 9.11602e-4 0.006557941 -0.9999782 6.62363e-4 0.002768218 -0.999996 7.67279e-4 0.003265798 -0.9999945 6.19823e-4 0.001718282 -0.9999984 7.14354e-4 0.002017736 -0.9999977 6.66927e-4 0.001681089 -0.9999985 5.03444e-4 0.001249909 -0.9999992 6.2255e-4 0.00190258 -0.999998 2.21836e-4 9.12673e-4 -0.9999996 5.26082e-4 0.002473294 -0.9999969 -4.81004e-4 -3.4645e-4 -0.9999999 -5.89089e-5 0.002263545 -0.9999975 -0.001535475 -0.003179907 -0.9999938 -0.001068234 0.001122474 -0.9999989 -0.001811563 -0.002128303 -0.9999961 -0.001703798 -4.05685e-4 -0.9999985 -0.002188861 -0.002343595 -0.9999949 -0.002210855 -0.003039777 -0.999993 -0.002611875 -0.004604041 -0.9999861 -0.002718985 -0.01419353 -0.9998956 -0.00283277 -0.01472103 -0.9998877 -0.002875149 -0.05552399 -0.9984533 -0.002911329 -0.0557841 -0.9984387 -0.002777218 -0.1575548 -0.9875063 -0.002829074 -0.1581355 -0.9874134 -0.002618849 -0.2543962 -0.9670966 -0.002585768 -0.2540206 -0.9671953 -0.002447843 -0.3271271 -0.9449772 -0.002720773 -0.330568 -0.9437783 -0.002179503 -0.5461701 -0.8376716 -0.003128945 -0.5557308 -0.8313565 -0.02355355 0.6272415 -0.7784686 0.1364328 0.9345695 -0.3285815 -0.00301063 0.2009731 -0.9795922 0.09581845 0.6101549 -0.7864667 -0.001294374 0.04003512 -0.9991974 0.01729643 0.1158133 -0.9931205 -9.35811e-4 0.01902997 -0.9998186 -4.8434e-4 0.02036935 -0.9997924 -0.002416789 0.01208543 -0.9999241 -0.006887257 4.93425e-4 -0.9999762 -0.00717622 -6.21395e-4 -0.9999741 -0.006576478 7.38711e-4 -0.9999781 -0.007891416 -0.00400716 -0.9999608 -0.002992212 0.005156457 -0.9999822 -0.005139827 -0.001202285 -0.9999862 -0.004938125 -8.78429e-4 -0.9999875 -0.004844665 -6.47529e-4 -0.9999881 -0.007173955 -0.004042148 -0.9999662 -0.006889998 -0.00340259 -0.9999706 -0.01140242 -0.01021271 -0.9998829 -0.009954273 -0.006818473 -0.9999272 -0.01566791 -0.01636481 -0.9997434 -0.01120716 -0.004075825 -0.999929 -0.015823 -0.01246494 -0.9997972 -0.01321375 -0.002971708 -0.9999083 -0.01736652 -0.01074379 -0.9997915 -0.01627719 -0.004560887 -0.9998572 -0.01923501 -0.0108152 -0.9997566 -0.01948326 -0.01384192 -0.9997144 -0.02026325 -0.01611602 -0.9996649 -0.02111583 -0.05354237 -0.9983423 -0.0209555 -0.05271142 -0.9983899 -0.02079117 -0.15678 -0.9874148 -0.02039718 -0.1531339 -0.987995 -0.01928502 -0.2542073 -0.9669575 -0.01907622 -0.2520439 -0.9675278 -0.01811635 -0.3309874 -0.9434612 -0.01913827 -0.3428924 -0.9391797 -0.01559174 -0.5550633 -0.8316621 -0.01822137 -0.5794825 -0.814781 0.09671258 0.9343786 -0.3429043 0.2035953 0.9583477 -0.2002961 0.0120601 0.584613 -0.8112227 0.1392323 0.7784862 -0.6120242 -0.0932613 0.1518313 -0.9839968 -0.05597877 0.2316237 -0.9711935 -0.09227412 0.1280811 -0.9874618 -0.1355059 0.05663508 -0.9891566 -0.1500513 0.02123028 -0.9884503 -0.1996188 -0.05135041 -0.9785273 -0.2198271 -0.09842157 -0.9705613 -0.1636104 -0.02293038 -0.9862585 -0.2070688 -0.1168715 -0.9713206 -0.09858399 0.01671904 -0.9949883 -0.1383403 -0.05526226 -0.9888418 -0.1039093 -0.0180068 -0.9944238 -0.1170768 -0.03776806 -0.9924045 -0.1251797 -0.04540228 -0.9910948 -0.1339963 -0.0565564 -0.9893667 -0.1440253 -0.06545233 -0.9874072 -0.1287668 -0.04773062 -0.9905257 -0.1423975 -0.05913138 -0.9880418 -0.1138852 -0.02594769 -0.9931551 -0.1317721 -0.03993314 -0.9904755 -0.1124373 -0.01455438 -0.9935523 -0.1308276 -0.02820861 -0.9910038 -0.120524 -0.009238839 -0.9926674 -0.1328502 -0.01941764 -0.9909459 -0.1304631 -0.01041615 -0.9913985 -0.1352241 -0.01626825 -0.9906815 -0.1369934 -0.04089009 -0.9897277 -0.1387273 -0.04523164 -0.9892972 -0.136692 -0.1451739 -0.9799184 -0.1364087 -0.1435321 -0.9801996 -0.1295292 -0.2527368 -0.9588255 -0.1290967 -0.2488993 -0.9598872 -0.121615 -0.3448845 -0.9307333 -0.1222299 -0.3521453 -0.9279298 -0.09883797 -0.5727162 -0.8137735 -0.09942054 -0.5784344 -0.8096476 -0.3236444 0.9133862 -0.2469416 -0.4405691 0.8548496 -0.2741006 -0.8760561 0.2575578 -0.4076637 -0.79539 0.438779 -0.4181241 -0.9066249 0.05919373 -0.4177649 -0.8716073 0.2036283 -0.4459104 -0.8847464 0.1462595 -0.442529 -0.9150521 0.01463389 -0.4030705 -0.9190197 -0.09446203 -0.3827267 -0.9194064 -0.09831064 -0.380824 -0.9064663 -0.2547513 -0.3367798 -0.8798831 -0.054448 -0.4720607 -0.861716 -0.3534609 -0.3640207 -0.7667322 -9.86673e-4 -0.6419664 -0.7925124 -0.2784352 -0.5425846 -0.6954214 -0.05351567 -0.7166067 -0.7163292 -0.22261 -0.6612997 -0.6620897 -0.115899 -0.7404084 -0.6745055 -0.2296168 -0.701654 -0.6277887 -0.1443779 -0.7648768 -0.6294449 -0.1545936 -0.7615116 -0.6077158 -0.122477 -0.7846535 -0.599121 -0.08277863 -0.796368 -0.6041365 -0.08822959 -0.7919815 -0.5923665 -0.0364952 -0.8048416 -0.6116999 -0.0518161 -0.7893912 -0.6042213 -0.005677223 -0.7967963 -0.6197016 -0.01692664 -0.784655 -0.6188043 0.006218433 -0.7855206 -0.6262716 -0.001463174 -0.7796037 -0.6255691 -0.01260137 -0.780067 -0.631559 -0.02621835 -0.7748844 -0.6179202 -0.1135846 -0.7779931 -0.619109 -0.1261413 -0.775108 -0.5927473 -0.23053 -0.7716907 -0.5926319 -0.2327548 -0.7711113 -0.56128 -0.3289026 -0.7594655 -0.5627815 -0.3183125 -0.7628592 -0.481257 -0.5086802 -0.7138881 -0.4935665 -0.4501266 -0.7441627 0.997475 0.05350142 -0.04670494 0.996669 0.06725281 -0.04613 0.997133 0.005372464 -0.07547843 0.9965032 -0.01871246 -0.08143222 0.9957719 -0.01674616 -0.09032112 0.9946967 -0.03691989 -0.09599727 0.9942934 -0.02978986 -0.1024369 0.9926834 -0.05452513 -0.1077349 0.9916946 -0.04741919 -0.1195546 0.989616 -0.0765962 -0.1216273 0.9854586 -0.07375884 -0.1530721 0.9796994 -0.1359167 -0.147363 0.9720646 -0.1230596 -0.1998671 0.9606583 -0.2115911 -0.1799024 0.9644458 -0.1636571 -0.2075108 0.9628753 -0.1768299 -0.2039669 0.9671707 -0.1486003 -0.2061522 0.9676102 -0.1431839 -0.2079157 0.9717541 -0.03254288 -0.2337411 0.9734583 -0.09066885 -0.2101384 0.9659364 -0.03820013 -0.2559447 0.9665703 -0.1086004 -0.2322668 0.9515461 -0.1265286 -0.280269 0.9410768 -0.2153503 -0.260766 0.902107 -0.3005409 -0.3096418 0.8574303 -0.4264695 -0.2879884 0.7957006 -0.5097812 -0.3270835 0.7232064 -0.6203822 -0.3034775 0.6848516 -0.6511195 -0.3271417 0.6239699 -0.717988 -0.308472 0.5949426 -0.7371963 -0.3202888 0.5505003 -0.7765118 -0.3065599 0.5219591 -0.7943911 -0.310647 0.4933096 -0.8159168 -0.3015383 0.4697557 -0.8296211 -0.3017591 0.4522172 -0.8413371 -0.29606 0.4300076 -0.8536691 -0.2938408 0.4195398 -0.8600627 -0.2903078 0.390114 -0.8755856 -0.2848878 0.3855265 -0.8781988 -0.2830833 -0.6579256 -0.6430068 -0.3920156 -0.8110395 -0.4740761 -0.3427347 -0.835586 -0.3905466 -0.3863539 -0.859709 -0.3475309 -0.37433 -0.889751 -0.2645023 -0.371997 -0.8929191 -0.2570198 -0.3696437 -0.9175299 -0.1748788 -0.3571503 -0.9160625 -0.1792646 -0.3587393 -0.9372618 -0.07907408 -0.3395403 -0.9363877 -0.08258908 -0.3411117 -0.9445792 -0.006872475 -0.328212 -0.9455919 -0.002624332 -0.3253446 -0.9452157 0.01272529 -0.3261986 -0.9462619 0.01568192 -0.3230209 -0.9429944 -0.001078009 -0.3328073 -0.9437336 4.27599e-4 -0.3307062 -0.9386265 -0.03621947 -0.3430286 -0.9326323 -0.04658728 -0.3578079 -0.9438456 -0.0529353 -0.3261185 -0.9177579 -0.09916108 -0.3845617 -0.9579408 -0.0523169 -0.2821568 -0.9093493 -0.1492052 -0.3883575 -0.9727549 -0.05192434 -0.2259463 -0.9155175 -0.1874945 -0.3559127 -0.9841225 -0.04318553 -0.1721569 -0.947167 -0.1676454 -0.2734403 -0.9913618 -0.04106593 -0.1245614 -0.967257 -0.1565811 -0.1997403 -0.9942869 -0.05982506 -0.08839988 -0.9771596 -0.1641363 -0.1349759 -0.9942907 -0.07143247 -0.07926982 -0.989561 -0.113694 -0.08855879 -0.9934677 -0.07938277 -0.08197808 -0.9951997 -0.05706155 -0.0795086 -0.9961637 -0.02187174 -0.08473205 -0.9965223 -0.003372907 -0.08325874 -0.9936878 0.07798969 -0.08063691 -0.9963011 0.01111924 -0.08520907 -0.9806062 0.1824488 -0.07158219 -0.9955904 0.04842585 -0.08034187 0.4641222 0.5700562 -0.6779577 0.6712378 0.6273335 -0.3948324 0.5763779 0.2057179 -0.7908658 0.689565 0.3523634 -0.6327244 0.6111265 0.04785621 -0.790085 0.6838164 0.1673388 -0.7102063 0.6415122 -0.008646428 -0.7670642 0.679149 0.05425965 -0.7319922 0.6627486 -0.04072749 -0.7477337 0.6627944 -0.04065352 -0.7476971 0.658638 -0.09083145 -0.7469577 0.6156804 -0.158191 -0.7719542 0.6156632 -0.1537694 -0.7728608 0.5632864 -0.2512788 -0.787126 0.5535908 -0.1509249 -0.8189988 0.5379225 -0.2118225 -0.8159478 0.5260961 -0.1396563 -0.8388797 0.5241246 -0.1542167 -0.8375623 0.5053321 -0.06352418 -0.8605837 0.4976349 -0.114586 -0.8597847 0.4915723 -0.07844734 -0.8672963 0.482727 -0.1303263 -0.8660194 0.488761 -0.1955571 -0.8502178 0.4835026 -0.2254511 -0.8458114 0.4826586 -0.401921 -0.7781391 0.4839119 -0.3964089 -0.7801854 0.4589185 -0.5983663 -0.6567736 0.4651492 -0.5802081 -0.6685767 0.4333367 -0.7058175 -0.5603936 0.4349013 -0.7024518 -0.5634026 0.4097662 -0.7689758 -0.4906809 0.4059364 -0.7755668 -0.4834374 0.3883669 -0.8113944 -0.4368185 0.3871521 -0.8132066 -0.4345208 0.3713741 -0.8404308 -0.3946611 0.3738621 -0.8371087 -0.3993447 0.3580943 -0.8610847 -0.360973 0.3604599 -0.8582782 -0.3652769 0.3436011 -0.8809779 -0.3252945 0.3420537 -0.8824991 -0.3227921 -0.7392538 -0.07059282 0.6697168 -0.7142847 0.0132988 0.6997289 -0.6782106 -0.006291389 0.7348408 -0.7263168 -0.04284644 0.6860234 -0.66205 -0.2899598 0.6910957 -0.6099271 -0.3206478 0.7246889 0.1657058 -0.7172631 0.6768127 -0.6536967 -0.01389634 0.7566291 -0.6686353 -0.02775883 0.7430723 -0.6914887 -0.2154459 0.6895118 -0.6899006 -0.06604135 0.7208855 -0.6995837 -0.1212775 0.7041836 -0.7151927 -0.1647824 0.6792247 -0.5350872 -0.4980502 0.6823692 -0.4705199 -0.6237894 0.6240977 -0.5987427 -0.4993056 0.6262597 -0.60255 -0.4116976 0.6836948 0.5050661 -0.3901878 0.7698453 0.5050656 -0.3901814 0.7698489 -0.3651484 -0.1825742 -0.912871 0.5050643 -0.3901911 0.7698447 0.4038575 -0.6613951 0.632025 0.4988614 -0.410766 0.763157 0.364162 -0.7336733 0.5736808 0.459129 -0.5334061 0.7104073 0.4374569 -0.8614361 0.257991 0.4148644 -0.7252271 0.5494845 0.467944 -0.8789368 0.09218841 0.4704262 -0.8802521 -0.06209385 -0.04962563 -0.6714565 -0.7393805 -0.04277276 -0.6491881 -0.7594244 -0.06576246 -0.6815472 -0.7288132 -0.05993127 -0.6727235 -0.7374627 -0.07803273 -0.6876108 -0.7218742 -0.07304883 -0.6824503 -0.7272727 -0.08138239 -0.6926142 -0.7167025 -0.07601863 -0.6873849 -0.7223041 -0.08321088 -0.6980603 -0.7111876 -0.0771529 -0.6921446 -0.7176235 -0.03654396 -0.3843548 -0.9224619 -0.03344053 -0.3694362 -0.9286543 -0.04883635 -0.3951128 -0.9173336 -0.0468468 -0.3896002 -0.9197919 -0.05688381 -0.3998676 -0.9148061 -0.05680948 -0.3997139 -0.9148778 -0.05831193 -0.3997353 -0.9147741 -0.05897706 -0.40116 -0.9141075 -0.05832654 -0.3980926 -0.9154892 -0.05942487 -0.4004464 -0.9143913 -0.02231472 -0.2253614 -0.9740197 -0.0253241 -0.238124 -0.9709046 -0.03010493 -0.2230926 -0.9743323 -0.03429937 -0.2343279 -0.9715524 -0.03489553 -0.2197585 -0.97493 -0.04040795 -0.2320829 -0.9718564 -0.0347566 -0.211994 -0.9766528 -0.04067754 -0.2252277 -0.9734566 -0.0335676 -0.203337 -0.9785333 -0.03943938 -0.2167333 -0.975434 -0.005798697 -0.09883671 -0.9950868 -0.01151591 -0.117013 -0.9930636 -0.01040273 -0.09561836 -0.9953638 -0.01700347 -0.1088089 -0.9939172 -0.01455348 -0.09441089 -0.995427 -0.02173638 -0.1067407 -0.9940493 -0.01465284 -0.08955401 -0.9958742 -0.02200639 -0.102135 -0.9945271 -0.01222079 -0.08132898 -0.9966124 -0.02078449 -0.09616696 -0.9951483 -0.004772543 -0.06456077 -0.9979024 -0.01779425 -0.08740353 -0.9960141 -5.02629e-4 -0.05164957 -0.9986652 -0.001559853 -0.05383765 -0.9985486 -0.002563893 -0.05082309 -0.9987044 -0.006049931 -0.05527228 -0.9984531 -0.00420773 -0.04950392 -0.9987651 -0.010495 -0.05658417 -0.9983427 -0.003330051 -0.04603391 -0.9989344 -0.01092183 -0.05470412 -0.998443 0.002413094 -0.03745901 -0.9992953 -0.008191704 -0.04996061 -0.9987176 0.01574748 -0.02010619 -0.9996739 3.60892e-4 -0.03912425 -0.9992344 1.32577e-4 -0.02192986 -0.9997596 0.001208901 -0.02043706 -0.9997904 -2.45632e-4 -0.02172118 -0.9997641 -7.51322e-4 -0.02203738 -0.9997569 -2.51782e-4 -0.02102422 -0.999779 -0.002399504 -0.02203226 -0.9997544 8.68181e-4 -0.02012336 -0.9997971 -0.001432776 -0.02121311 -0.999774 0.00699532 -0.0184617 -0.9998052 0.005229353 -0.01939272 -0.9997984 0.01823627 -0.01573574 -0.99971 0.01675552 -0.01673334 -0.9997196 0.02369016 -0.01340687 -0.9996295 0.02172827 -0.01502817 -0.999651 9.00437e-5 -0.005481302 -0.999985 5.73287e-4 -0.004962027 -0.9999876 1.69892e-4 -0.005558431 -0.9999846 2.89569e-4 -0.005531013 -0.9999847 2.79569e-4 -0.00559926 -0.9999844 3.11381e-4 -0.005598425 -0.9999844 5.08424e-4 -0.006008744 -0.9999818 0.001602768 -0.006007075 -0.9999808 0.003207802 -0.008909463 -0.9999552 0.008623182 -0.008692979 -0.9999251 0.01055216 -0.01551091 -0.9998241 0.01896268 -0.01370257 -0.9997264 0.01535677 -0.02002441 -0.9996816 0.02202957 -0.01720041 -0.9996094 3.03041e-5 -8.91172e-4 -0.9999997 1.49825e-4 -7.69424e-4 -0.9999998 8.79866e-5 -9.89328e-4 -0.9999996 2.4887e-4 -9.6642e-4 -0.9999996 1.1181e-4 -0.001073896 -0.9999995 3.47402e-4 -0.001093387 -0.9999994 9.3614e-5 -0.001214861 -0.9999994 5.61815e-4 -0.001271545 -0.9999991 4.80815e-4 -0.002458989 -0.999997 0.003573238 -0.002833068 -0.9999896 0.003383994 -0.007439613 -0.9999666 0.01225709 -0.007804751 -0.9998944 0.008782923 -0.01324886 -0.9998738 0.01810801 -0.01227086 -0.9997608 0.005554676 -0.01453405 -0.999879 0.01127439 -0.01350444 -0.9998453 0.00308305 -0.01443547 -0.9998911 0.001764118 -0.01474207 -0.9998899 -6.86171e-5 -1.10529e-4 -1 3.51103e-5 2.45801e-6 -1 -4.71525e-6 -1.69038e-4 -1 9.08064e-5 -1.38339e-4 -1 3.37888e-5 -2.02906e-4 -1 1.12758e-4 -1.93413e-4 -1 3.6013e-5 -2.20782e-4 -1 9.06395e-5 -2.15965e-4 -1 5.43768e-5 -3.60988e-4 -1 4.87477e-4 -3.30272e-4 -0.9999998 5.28602e-4 -0.001402795 -0.9999989 0.003750085 -0.00125122 -0.9999923 0.003136515 -0.003647923 -0.9999885 0.0105741 -0.003379166 -0.9999385 0.004304409 -0.004143595 -0.9999822 0.006944954 -0.004023015 -0.9999679 0.008662223 -0.003741323 -0.9999555 0.003227055 -0.004121661 -0.9999863 0.01578313 -0.003024041 -0.9998709 0.007000803 -0.00378859 -0.9999684 -2.45914e-4 2.64968e-4 -1 -5.50589e-5 4.48695e-4 -1 -1.45568e-4 1.97711e-4 -1 -9.0939e-7 2.57958e-4 -1 3.14892e-5 1.92381e-4 -1 3.3557e-5 1.92936e-4 -1 8.44392e-5 2.05399e-4 -1 3.53127e-5 1.92301e-4 -1 1.36384e-4 2.27307e-4 -1 5.36703e-5 2.05744e-4 -1 3.52173e-4 1.87913e-4 -1 5.37248e-4 2.28193e-4 -0.9999999 0.001653671 1.3098e-5 -0.9999987 0.003315687 2.54423e-4 -0.9999945 0.00589168 3.03448e-4 -0.9999826 0.004496991 1.50815e-4 -0.9999899 0.01239979 8.85421e-4 -0.9999228 0.008615374 4.86058e-4 -0.9999628 0.01023131 5.59808e-4 -0.9999476 0.01569527 0.001135528 -0.9998763 -3.31037e-4 6.66961e-4 -0.9999998 -1.94299e-4 7.6758e-4 -0.9999998 -2.28171e-4 6.33046e-4 -0.9999998 -1.11728e-4 6.7498e-4 -0.9999998 1.84028e-4 6.94626e-4 -0.9999998 3.64609e-5 6.51628e-4 -0.9999999 4.2342e-4 7.91357e-4 -0.9999997 8.4982e-5 6.83767e-4 -0.9999998 6.24429e-4 9.16199e-4 -0.9999995 1.37229e-4 7.47914e-4 -0.9999997 0.001176595 0.001143276 -0.9999987 3.53726e-4 8.64052e-4 -0.9999997 0.003291666 0.001737117 -0.9999931 0.001663625 0.001252651 -0.9999979 0.009245991 0.003267168 -0.999952 0.005927503 0.002367436 -0.9999796 0.01053589 0.003531157 -0.9999383 0.01272124 0.004108428 -0.9999107 0.003415942 0.001621723 -0.9999929 0.01212728 0.003905236 -0.9999189 -1.42244e-4 6.45017e-4 -0.9999999 -3.61621e-4 4.83859e-4 -0.9999998 5.60884e-5 7.28987e-4 -0.9999998 -2.26847e-4 6.40962e-4 -0.9999998 7.51667e-4 8.77616e-4 -0.9999994 1.86367e-4 7.40062e-4 -0.9999997 0.001512527 0.001137495 -0.9999983 4.23864e-4 8.32855e-4 -0.9999996 0.002376079 0.001537561 -0.999996 6.24799e-4 9.63527e-4 -0.9999994 0.004102826 0.002266466 -0.9999891 0.001177549 0.001232743 -0.9999986 0.009217321 0.004092335 -0.9999492 0.003297328 0.002025842 -0.9999926 0.01534664 0.00619173 -0.9998631 0.009321331 0.004125475 -0.9999481 0.01023548 0.004526197 -0.9999374 0.0113179 0.004899024 -0.999924 0.001897156 0.0018 -0.9999967 0.004682064 0.002788305 -0.9999852 1.29645e-5 -7.40262e-4 -0.9999998 -2.20232e-4 -0.001093864 -0.9999995 8.43365e-5 -6.83266e-4 -0.9999998 -4.8363e-5 -7.35157e-4 -0.9999998 4.62141e-4 -7.79887e-4 -0.9999997 6.95556e-4 -7.56869e-4 -0.9999995 0.001136958 -9.29747e-4 -0.999999 0.001455664 -9.2003e-4 -0.9999986 0.002249658 -0.001093447 -0.999997 0.002291023 -0.001093089 -0.9999968 0.004818022 -0.001314222 -0.9999876 0.003944754 -0.001304209 -0.9999914 0.0114817 -0.001792907 -0.9999325 0.008719027 -0.001699805 -0.9999606 0.01788288 -0.002070248 -0.999838 0.01283085 -0.001905024 -0.9999159 0.01231688 -0.001048505 -0.9999236 0.005171 -0.001165628 -0.9999861 0.003274142 3.55299e-5 -0.9999946 -9.97649e-4 -5.56058e-4 -0.9999994 1.85876e-4 -0.004441201 -0.9999902 1.804e-4 -0.004487335 -0.9999899 4.52838e-5 -0.00452876 -0.9999898 1.1012e-4 -0.004415392 -0.9999903 5.96391e-5 -0.004866719 -0.9999883 4.04275e-4 -0.00475794 -0.9999886 1.89198e-4 -0.005555152 -0.9999846 9.96178e-4 -0.00582832 -0.9999825 4.91217e-4 -0.006783962 -0.9999769 0.001951217 -0.0080958 -0.9999654 0.00127542 -0.009192287 -0.999957 0.003951728 -0.01298964 -0.9999079 0.003986418 -0.01568758 -0.9998691 0.008451998 -0.02359223 -0.999686 0.009255647 -0.02700018 -0.9995926 0.01093512 -0.03012615 -0.9994864 0.01123136 -0.0273844 -0.999562 0.003132879 -0.01442396 -0.9998912 0.005802452 -0.01086568 -0.9999242 -0.001710712 -0.004366636 -0.9999891 -2.05459e-4 0.002831459 -0.999996 -2.04585e-4 0.002936065 -0.9999957 -8.16469e-5 0.002541363 -0.9999968 -5.43742e-5 0.002780139 -0.9999961 -2.84946e-5 0.001936972 -0.9999982 8.92085e-5 0.002402484 -0.9999971 7.25895e-6 9.28646e-4 -0.9999996 2.54146e-4 0.001482069 -0.9999989 9.34942e-5 -8.36695e-4 -0.9999997 5.93674e-4 -6.24485e-4 -0.9999997 3.55489e-4 -0.003951847 -0.9999922 0.001403808 -0.005762934 -0.9999824 0.001506984 -0.01178306 -0.9999295 0.003645896 -0.01919966 -0.9998091 0.004401326 -0.02831941 -0.9995893 0.006955206 -0.03890353 -0.9992188 0.007892668 -0.04474264 -0.9989674 0.006799638 -0.04033082 -0.9991633 0.01005017 -0.03932613 -0.9991759 0.001799106 -0.01606965 -0.9998694 -8.11553e-4 0.02900183 -0.999579 -9.42415e-4 0.02146387 -0.9997693 -2.39443e-4 0.0301336 -0.9995459 -3.46022e-4 0.02897882 -0.99958 -5.00834e-5 0.02990359 -0.9995528 -1.91715e-5 0.03010171 -0.9995469 -2.95867e-5 0.02934032 -0.9995695 6.52602e-5 0.02985966 -0.9995541 4.55531e-5 0.02831387 -0.9995992 2.37411e-4 0.02913683 -0.9995754 3.25702e-4 0.0263518 -0.9996528 7.87111e-4 0.02732944 -0.9996263 0.001804292 0.0215637 -0.9997659 0.00298953 0.02126497 -0.9997695 0.0066275 0.00941646 -0.9999337 0.008750915 0.006602585 -0.9999399 0.0129863 -0.005815744 -0.9998989 0.01517277 -0.009209871 -0.9998425 0.01771074 -0.01583421 -0.9997178 0.01748788 -0.01550221 -0.9997269 -7.6842e-4 0.0543226 -0.9985232 -0.001129925 0.04202616 -0.9991159 -1.98047e-4 0.05630064 -0.9984139 -3.86894e-4 0.054322 -0.9985234 -4.9523e-5 0.05634957 -0.9984112 -5.70241e-5 0.05629968 -0.9984139 -4.08095e-5 0.05621773 -0.9984186 -1.97319e-5 0.05634981 -0.9984112 4.56564e-5 0.05595636 -0.9984332 9.04012e-5 0.0562058 -0.9984193 4.12936e-4 0.05542433 -0.9984629 5.24001e-4 0.0558604 -0.9984385 0.002374827 0.05410051 -0.9985327 0.002710342 0.05462259 -0.9985034 0.008857309 0.05047273 -0.9986863 0.01022398 0.05101752 -0.9986455 0.01804357 0.04531604 -0.9988098 0.02099633 0.04566031 -0.9987364 0.0250678 0.04083907 -0.9988512 0.02873462 0.04106384 -0.9987433 -9.63954e-4 0.1568993 -0.9876142 -0.001763761 0.1334202 -0.9910581 -1.64773e-4 0.1602293 -0.9870798 -4.74148e-4 0.1569014 -0.9876142 -3.56658e-5 0.1604241 -0.9870483 -6.30925e-5 0.1602282 -0.98708 -2.02415e-5 0.1604416 -0.9870454 -2.36248e-5 0.1604254 -0.987048 1.66029e-4 0.1604691 -0.9870409 1.61024e-4 0.1604412 -0.9870454 0.001039624 0.160681 -0.9870059 9.90575e-4 0.1604589 -0.9870421 0.005141258 0.1609517 -0.9869489 0.00498116 0.1606267 -0.9870027 0.01675939 0.1607913 -0.9868462 0.01707601 0.1610641 -0.9867962 0.02870219 0.1589367 -0.9868716 0.03268778 0.1611106 -0.986395 0.03654748 0.1557546 -0.9871196 0.04360622 0.1591209 -0.9862957 -0.001789748 0.6872127 -0.7264541 -0.003675282 0.6582481 -0.7527921 -1.97677e-4 0.6893174 -0.7244595 -5.43966e-4 0.6872006 -0.7264676 -2.37668e-5 0.6893004 -0.7244757 -2.22039e-5 0.6893078 -0.7244687 7.95491e-5 0.6893299 -0.7244476 7.05838e-5 0.6893065 -0.7244699 8.12641e-4 0.6894781 -0.7243061 7.69956e-4 0.6893544 -0.7244238 0.004257202 0.6900691 -0.723731 0.004033386 0.6894969 -0.7242774 0.01940858 0.6912434 -0.7223613 0.01843732 0.6900959 -0.7234832 0.0569064 0.6921318 -0.7195243 0.05495357 0.6912478 -0.7205253 0.08311128 0.6901146 -0.718912 0.08843183 0.6916547 -0.716794 0.09464269 0.6861686 -0.7212597 0.1075913 0.6892727 -0.7164688 -0.001401066 0.9656627 -0.2597959 -0.002297282 0.9640136 -0.2658431 -2.07907e-4 0.9656757 -0.2597507 -2.23205e-4 0.9656639 -0.2597945 -3.44014e-5 0.9656616 -0.2598034 -8.52466e-6 0.9656757 -0.259751 1.04776e-4 0.9656462 -0.2598605 1.37749e-4 0.9656645 -0.2597926 0.001000463 0.965593 -0.2600558 0.001121938 0.965648 -0.2598513 0.005072712 0.9653752 -0.2608164 0.005713403 0.9655795 -0.2600456 0.02338641 0.9647853 -0.2619974 0.0257517 0.9650753 -0.260704 0.07150804 0.9623841 -0.2621133 0.07463192 0.9623461 -0.2613811 0.1110988 0.9587923 -0.2614853 0.1124944 0.9586999 -0.2612274 0.1327751 0.9562337 -0.2607449 0.1312497 0.9563775 -0.2609896 -0.02064353 -0.9973844 0.06926953 -0.0783807 -0.9948765 0.06385385 -0.02355378 -0.9979041 0.06027328 -0.08275002 -0.995077 0.05453699 -0.02605426 -0.9983885 0.05041325 -0.08265364 -0.9955902 0.04436933 -0.02424234 -0.998909 0.03991478 -0.07704448 -0.9964414 0.0341894 -0.01782411 -0.9994083 0.02941894 -0.0604518 -0.9978595 0.02494317 -0.009629487 -0.9997465 0.02035164 -0.03594726 -0.9992033 0.01733744 -0.005613803 -0.9998782 0.01456576 -0.02087759 -0.9997047 0.01244151 -0.004201769 -0.9999276 0.01127785 -0.01803278 -0.9997981 0.008869051 -0.004294931 -0.9999557 0.008381843 -0.0233308 -0.999719 0.004227817 -0.003900885 -0.9999826 0.004446804 -0.03011429 -0.9995366 -0.004424929 -0.07665342 -0.9875652 0.1372563 -0.1607911 -0.9801521 0.1159669 -0.08277535 -0.9887444 0.124631 -0.1683861 -0.9803321 0.1029326 -0.08638334 -0.9900289 0.1112694 -0.1732808 -0.9808515 0.08890503 -0.08311462 -0.9917524 0.09756678 -0.170345 -0.9825299 0.0749498 -0.06754416 -0.9941461 0.0843293 -0.1496847 -0.9867452 0.0626769 -0.04575216 -0.9963902 0.07150691 -0.1189413 -0.9915599 0.05159324 -0.03167569 -0.997731 0.05941206 -0.09818083 -0.9943431 0.04052513 -0.02705979 -0.9984496 0.04864531 -0.09668141 -0.9949537 0.02683317 -0.02899736 -0.9989065 0.03667569 -0.1080124 -0.9941024 0.009682059 -0.02895182 -0.9993289 0.02244228 -0.09682095 -0.9952868 -0.005468487 -0.1531909 -0.9750348 0.1607475 -0.2024911 -0.9687368 0.1433405 -0.1599027 -0.9752219 0.1528834 -0.2117125 -0.9680761 0.1341882 -0.1649097 -0.9756158 0.1448399 -0.220375 -0.9674602 0.1243211 -0.1628693 -0.9769964 0.137665 -0.2253915 -0.9675663 0.1140801 -0.1450306 -0.9804435 0.1330289 -0.221211 -0.9697248 0.1034397 -0.1199806 -0.984525 0.1277311 -0.215541 -0.9723612 0.08975529 -0.1031022 -0.9876726 0.1177831 -0.2208055 -0.9727385 0.07088571 -0.1013631 -0.9895682 0.1023742 -0.2339193 -0.9710912 0.04758024 -0.1057972 -0.9909179 0.08299767 -0.2305894 -0.9726299 0.02863359 -0.08247131 -0.9941998 0.0690307 -0.1662166 -0.9857164 0.02711713 -0.1992796 -0.9674779 0.1558017 -0.2261668 -0.9631978 0.1452541 -0.2075269 -0.9666114 0.1503168 -0.2347323 -0.9620186 0.1393598 -0.2150637 -0.965794 0.1448781 -0.2436073 -0.9607032 0.1330601 -0.2186163 -0.9656722 0.1403009 -0.252678 -0.9593265 0.1258833 -0.2128971 -0.9673059 0.1378191 -0.2589596 -0.9586912 0.117691 -0.2059655 -0.9693021 0.1342827 -0.2675978 -0.9576077 0.1066727 -0.2089422 -0.9698028 0.1258001 -0.2844052 -0.9542828 0.09196794 -0.2188238 -0.9691102 0.1137611 -0.3042007 -0.949656 0.07493799 -0.209688 -0.9719695 0.1063315 -0.2994622 -0.9519473 0.06417667 -0.1430078 -0.9831063 0.1142407 -0.2166891 -0.9732876 0.07587605 -0.2265374 -0.9632985 0.1440035 -0.2470607 -0.9594295 0.1358538 -0.2347383 -0.9620216 0.1393282 -0.2556957 -0.9578723 0.1307684 -0.2431713 -0.9606194 0.134455 -0.2651577 -0.9560465 0.1251661 -0.2515551 -0.959157 0.1293752 -0.2753717 -0.9539401 0.1190333 -0.2565438 -0.9583991 0.1251264 -0.2834156 -0.9523069 0.1130807 -0.263255 -0.9572441 0.1199194 -0.2941713 -0.9498959 0.1056466 -0.277724 -0.9541712 0.1114755 -0.3109618 -0.9455783 0.09583616 -0.2949782 -0.9500823 0.1016449 -0.3270947 -0.9410542 0.08617502 -0.2878745 -0.9523835 0.1004691 -0.3248591 -0.9422026 0.08198124 -0.2096529 -0.9700133 0.122964 -0.2245832 -0.9677226 0.1143481 -0.2481384 -0.9596392 0.1323632 -0.2689402 -0.9550742 0.1245172 -0.2566649 -0.9580152 0.1277892 -0.2777576 -0.9531714 0.1196461 -0.2659229 -0.9561224 0.1229438 -0.2883027 -0.9507237 0.1140446 -0.2758331 -0.95397 0.1177182 -0.2970988 -0.9486058 0.1089932 -0.2833587 -0.9523036 0.1132515 -0.3003175 -0.9479234 0.1060698 -0.29318 -0.9498951 0.1083734 -0.3155413 -0.9437742 0.09861093 -0.3091354 -0.9456639 0.1007735 -0.3205071 -0.9424036 0.09565937 -0.324105 -0.9412971 0.09442341 -0.3024072 -0.9474506 0.1043419 -0.3193858 -0.9424667 0.0987392 -0.2948808 -0.9491732 0.1100704 -0.2228503 -0.9658105 0.1324689 -0.1621425 -0.9726861 0.1661075 -0.2691934 -0.9551068 0.1237177 -0.2901526 -0.9498617 0.1165084 -0.2778352 -0.9531788 0.1194065 -0.2951207 -0.948706 0.1134056 -0.2878999 -0.9507144 0.1151348 -0.3035225 -0.9464879 0.109704 -0.2961447 -0.9486123 0.1115038 -0.3011218 -0.9472464 0.1097728 -0.29873 -0.9479355 0.1103577 -0.2722074 -0.9547812 0.1195665 -0.3111189 -0.9439422 0.1103551 -0.2997965 -0.9471381 0.1142429 -0.3152279 -0.9425516 0.11058 -0.2376276 -0.9616507 0.1369708 -0.2962056 -0.9468253 0.1256352 -0.172033 -0.9712958 0.1642836 -0.2841914 -0.9465286 0.1527054 -0.1635975 -0.9697201 0.181325 -0.1632451 -0.9697776 0.1813353 -0.08568668 -0.9744116 0.2077978 -0.2871825 -0.9495325 0.1261516 -0.3130571 -0.9423079 0.1185376 -0.2922621 -0.9484886 0.1222794 -0.3035149 -0.9453647 0.1190148 -0.3000127 -0.9464052 0.1196224 -0.2705815 -0.954184 0.1277447 -0.2960137 -0.9470934 0.1240561 -0.2128748 -0.966363 0.1443154 -0.2661975 -0.9537871 0.1393887 -0.1421879 -0.9761801 0.1638755 -0.2828555 -0.9451516 0.1633441 -0.163999 -0.9705221 0.1766104 -0.2293624 -0.9563743 0.180945 -0.1128141 -0.9755178 0.1887801 -0.1720763 -0.9644171 0.2007222 -0.07841503 -0.9768533 0.1990193 -0.1669384 -0.9580021 0.2331598 -0.07768648 -0.9739106 0.213221 -0.0892924 -0.9716292 0.219006 -0.04295605 -0.9765109 0.211143 -0.3037911 -0.9402699 0.1536349 -0.3309412 -0.9321151 0.1471034 -0.2947288 -0.9435956 0.1508718 -0.2540135 -0.9539366 0.1596313 -0.2626069 -0.9516682 0.1592658 -0.1559904 -0.9718542 0.1765406 -0.206546 -0.9614937 0.1812971 -0.09217262 -0.9781776 0.1862064 -0.1416267 -0.969685 0.1991308 -0.04904061 -0.9803605 0.1910194 -0.1596389 -0.9574486 0.2404326 -0.06499552 -0.9749847 0.2125573 -0.1197372 -0.9624798 0.2435074 -0.06453561 -0.9724452 0.2240211 -0.08925998 -0.9665367 0.2404987 -0.05287849 -0.9724718 0.2269418 -0.08956658 -0.962755 0.255109 -0.04633963 -0.9718268 0.2310963 -0.05254578 -0.9702961 0.2361451 -0.01141172 -0.9765774 0.2148634 -0.3180227 -0.919954 0.2292299 -0.2524222 -0.9380728 0.2372819 -0.246886 -0.939675 0.2367662 -0.1608223 -0.9569439 0.2416498 -0.1587297 -0.9574282 0.2411145 -0.0907315 -0.9668221 0.2387949 -0.1003474 -0.964697 0.243496 -0.05216598 -0.9713166 0.2319975 -0.05993181 -0.969612 0.2371935 -0.02227437 -0.9745338 0.2231317 -0.07555079 -0.9612655 0.2650678 -0.02041864 -0.9720503 0.2338829 -0.08036112 -0.9557298 0.2830598 -0.03055572 -0.966311 0.2555574 -0.07352209 -0.954693 0.2883676 -0.03965538 -0.9603016 0.2761313 -0.06545782 -0.9539421 0.2927625 -0.01334059 -0.9614349 0.2747091 -0.03143078 -0.9581302 0.2846028 0.05841445 -0.9634113 0.2615847 -0.2617369 -0.9004954 0.347278 -0.1417111 -0.9370487 0.3191516 -0.177407 -0.9243012 0.3379261 -0.1083927 -0.9418059 0.3182023 -0.1112599 -0.9408609 0.320003 -0.07477229 -0.9474711 0.3109788 -0.07469141 -0.9474971 0.310919 -0.04924619 -0.9518687 0.3025242 -0.04682421 -0.9525427 0.3007823 -0.0219919 -0.95561 0.2938127 -0.03911995 -0.951689 0.3045618 0.01090633 -0.9574258 0.2884731 -0.04515993 -0.9470585 0.3178694 0.04893124 -0.9548906 0.292899 -0.05648177 -0.9406229 0.3347215 0.02754491 -0.942813 0.3321822 -0.02635663 -0.9390227 0.3428435 0.08880323 -0.9332997 0.3479452 0.05612134 -0.9347574 0.3508263 0.1614041 -0.9180149 0.362212 -0.1563692 -0.9153668 0.3710152 -0.07402437 -0.941654 0.3283417 -0.1217426 -0.9228788 0.3653401 -0.05828428 -0.9407413 0.3340791 -0.0887165 -0.9303237 0.3558471 -0.04886096 -0.9370437 0.3457772 -0.06491935 -0.9326416 0.3549156 -0.01864111 -0.9370003 0.3488308 -0.04025763 -0.9331716 0.3571699 0.02185189 -0.9328899 0.3594983 -0.001906991 -0.9315655 0.3635687 0.1002615 -0.9230141 0.3714736 0.05037331 -0.9259835 0.3741888 0.1777545 -0.9053248 0.3857339 0.02675414 -0.922752 0.3844645 0.1633206 -0.8968458 0.411089 0.1038154 -0.9080823 0.4057203 0.2163529 -0.8772796 0.4284532 0.1809566 -0.8871502 0.4245225 0.186987 -0.8851395 0.4261032 -0.08101677 -0.9337819 0.3485509 -0.01405686 -0.9442995 0.3287872 -0.06346297 -0.9333411 0.3533369 0.03264921 -0.9425666 0.3324186 -0.05325615 -0.9303456 0.3627961 0.02219229 -0.9298588 0.3672469 -0.02281731 -0.9276608 0.3727263 0.07777839 -0.9168272 0.3916359 0.01994353 -0.9212285 0.3885104 0.1364609 -0.8966009 0.42129 0.1108477 -0.9020457 0.4171646 0.188969 -0.8782855 0.43921 0.2095575 -0.8717716 0.4428318 0.2007529 -0.8750041 0.4405293 0.1777316 -0.8821085 0.4362292 0.1772041 -0.8822928 0.4360713 0.2328947 -0.8640663 0.4462618 0.1924319 -0.8791006 0.4360644 0.1924989 -0.8790771 0.4360821 0.1398445 -0.8971914 0.4189165 -0.02175241 -0.934526 0.3552294 0.05368357 -0.9295996 0.3646404 0.03045743 -0.930387 0.3653115 0.1243769 -0.9170116 0.3789726 0.0222879 -0.9275318 0.3730792 0.1167006 -0.9092975 0.3994487 0.07800424 -0.9164398 0.3924964 0.13885 -0.9005663 0.4119476 0.1312757 -0.9025179 0.4101561 0.1243055 -0.9046075 0.4077173 0.1765919 -0.8896048 0.4212111 0.1158509 -0.9091653 0.3999963 0.1835826 -0.8900464 0.4172709 0.1121463 -0.9127283 0.3928743 0.1587428 -0.9007658 0.4042548 0.1059724 -0.9162613 0.3863098 0.1598255 -0.9032998 0.3981274 0.1053065 -0.9183006 0.381621 0.1190014 -0.9154757 0.3843734 0.07246071 -0.9270067 0.3679782 0.05081957 -0.9125728 0.4057442 0.03358054 -0.9150846 0.4018615 0.1330659 -0.9039034 0.4065122 0.05166381 -0.9171606 0.3951549 0.1153542 -0.910658 0.396731 0.06923514 -0.9177055 0.3911817 0.1263765 -0.9107999 0.3930299 0.06251436 -0.9205988 0.3854737 0.111919 -0.9150508 0.3875 0.05429738 -0.9235826 0.3795355 0.1041715 -0.918461 0.3815464 0.05225771 -0.9259678 0.3739692 0.1024503 -0.9211117 0.3755759 0.05416816 -0.9279727 0.3686904 0.1011943 -0.9236029 0.3697532 0.05787163 -0.9297549 0.3636024 0.09671342 -0.9262997 0.364164 0.0549184 -0.9318248 0.358729 0.06845694 -0.9308821 0.3588486 0.03867858 -0.93473 0.3532475 0.03377598 -0.9139826 0.4043452 0.004675567 -0.9193675 0.3933721 0.0524311 -0.9154403 0.399024 0.008274734 -0.9212998 0.3887651 0.06904923 -0.9179408 0.3906624 0.01483732 -0.9230515 0.3843901 0.06180483 -0.9214781 0.3834819 0.01554894 -0.924623 0.3805662 0.05398643 -0.924018 0.3785185 0.0172258 -0.9261856 0.3766742 0.05230236 -0.9259127 0.3740994 0.01855868 -0.9278455 0.3725026 0.05443459 -0.9276064 0.3695719 0.02079278 -0.9295694 0.3680604 0.05803328 -0.9292206 0.3649401 0.02341014 -0.9313845 0.3632836 0.05538016 -0.9310426 0.3606839 0.0224719 -0.9330847 0.3589541 0.03979158 -0.9330198 0.3576184 0.01704281 -0.93478 0.3548184 0.01259112 -0.9335917 0.3581175 0.002155005 -0.9359934 0.3520108 0.01364737 -0.9340889 0.3567799 0.002328634 -0.9364571 0.3507745 0.01559782 -0.9344776 0.3556804 0.002668976 -0.9370061 0.349303 0.01683109 -0.9350939 0.3540003 0.002742171 -0.9376809 0.3474867 0.01913154 -0.9356414 0.3524332 0.00340557 -0.9383605 0.3456417 0.02285689 -0.9361132 0.3509554 0.004296362 -0.9391915 0.343367 0.02151274 -0.9373638 0.3476871 0.004127383 -0.9400854 0.3409142 0.01587587 -0.9390004 0.3435495 0.004012882 -0.9409793 0.3384405 0.001656055 -0.9576259 0.2880102 2.73028e-5 -0.9578462 0.2872818 0.002043843 -0.9576871 0.2878044 -2.5688e-4 -0.9579881 0.286808 0.002049446 -0.957821 0.2873584 -3.54641e-4 -0.9581184 0.286372 0.002365469 -0.9579351 0.2869753 -2.86726e-4 -0.9582518 0.2859258 0.003773629 -0.9579952 0.2867593 -1.84797e-4 -0.9584506 0.2852586 0.003285646 -0.9582502 0.2859122 1.16976e-4 -0.9586054 0.2847379 0.002788484 -0.9584663 0.2851924 0.001577436 -0.9586279 0.2846579 -5.0609e-4 -0.9856995 0.1685123 -0.004593849 -0.9859749 0.166831 -5.33145e-4 -0.9858523 0.1676162 -0.004759669 -0.9861333 0.1658869 -6.0929e-4 -0.986012 0.1666734 -0.004842698 -0.986288 0.1649625 -4.69933e-4 -0.9861649 0.1657664 -0.00513935 -0.9864652 0.1638908 -3.52512e-4 -0.9863348 0.1647535 -0.004877746 -0.9866297 0.1629052 1.6541e-5 -0.9865 0.1637616 -0.004006803 -0.9868294 0.161715 -0.007552027 -0.9933592 -0.114807 -0.028297 -0.9919368 -0.123534 -0.007676959 -0.9927822 -0.1196848 -0.02841436 -0.9913147 -0.1284049 -0.007913708 -0.9921771 -0.1245875 -0.02908033 -0.9906213 -0.1335054 -0.00755465 -0.9915496 -0.1295078 -0.02716296 -0.9900574 -0.1380168 -0.007556676 -0.990896 -0.1344177 -0.02023452 -0.9897497 -0.1413723 -1.43343e-4 0.9967818 -0.08016216 -5.11433e-4 0.9969504 -0.07803708 -1.11195e-4 0.996963 -0.07787686 -9.20664e-5 0.9969584 -0.07793527 -8.20846e-5 0.9969592 -0.07792645 -5.91743e-5 0.9969567 -0.07795929 -1.24156e-5 0.9969564 -0.07796192 2.47825e-6 0.9969545 -0.07798528 3.91352e-4 0.9969547 -0.07798099 4.7693e-4 0.9969453 -0.07810199 0.002453386 0.9969486 -0.07802319 0.003100216 0.9968953 -0.07867765 0.01241111 0.996865 -0.07814121 0.01621389 0.996665 -0.07997447 0.04961079 0.9956279 -0.07914561 0.06015926 0.994861 -0.08144122 0.1159128 0.9899088 -0.08151668 0.1197487 0.9894011 -0.08213216 0.1704475 0.9819071 -0.08249938 0.1636168 0.9831583 -0.08142054 -0.005437076 -0.999706 0.02363014 -0.01849865 -0.9995775 0.02242118 -0.004365563 -0.9997894 0.02005481 -0.01992356 -0.9996303 0.01850503 -0.00509119 -0.9998607 0.01590114 -0.01974534 -0.9997029 0.01429617 -0.004630506 -0.9999237 0.01145595 -0.01796448 -0.9997871 0.0101602 -0.003318309 -0.9999682 0.007252573 -0.01331466 -0.9998908 0.006413638 -0.001544356 -0.9999909 0.003998458 -0.005766808 -0.9999772 0.00354278 -9.12265e-4 -0.9999964 0.002534985 -0.002380013 -0.9999946 0.002317488 -7.27445e-4 -0.9999979 0.001979112 -0.00184524 -0.9999967 0.001781702 -7.51241e-4 -0.9999985 0.001573145 -0.002428412 -0.9999964 0.001136779 -4.3817e-4 -0.9999996 8.73781e-4 -0.003217637 -0.9999947 -4.96201e-4 -0.03230369 -0.918861 -0.3932569 -0.06615471 -0.917981 -0.3910685 -0.0327304 -0.9156157 -0.4007201 -0.0664035 -0.9147713 -0.3984773 -0.03041547 -0.912521 -0.4078977 -0.06273019 -0.9120466 -0.4052605 -0.02206331 -0.9091497 -0.4158846 -0.04785096 -0.9105942 -0.4105222 -0.04852366 -0.8370241 -0.5450103 -0.0333243 -0.8227728 -0.5673928 -0.06614607 -0.8426692 -0.5343534 -0.04800951 -0.8370707 -0.5449843 -0.08039391 -0.8456689 -0.5276182 -0.06252861 -0.843062 -0.5341691 -0.08358532 -0.8495258 -0.5208835 -0.06602114 -0.8473522 -0.5269114 -0.08466273 -0.8538625 -0.5135671 -0.06595313 -0.8516128 -0.5200057 -5.2252e-4 0.991814 -0.12769 -0.001393795 0.9913876 -0.1309534 -9.58155e-5 0.9918377 -0.1275067 -2.02779e-4 0.9918159 -0.1276761 -5.98129e-5 0.991833 -0.1275439 -3.01473e-5 0.9918379 -0.1275061 1.04754e-5 0.991822 -0.1276291 1.06913e-4 0.9918334 -0.1275406 5.25927e-4 0.99177 -0.1280311 9.85749e-4 0.9918219 -0.1276267 0.00328499 0.991621 -0.12914 0.005016028 0.99176 -0.1280122 0.01680034 0.9912438 -0.1309711 0.02325248 0.9913682 -0.1290286 0.06069827 0.9893347 -0.1324113 0.07199525 0.9887605 -0.1310318 0.116609 0.9842872 -0.1325937 0.1162581 0.9843244 -0.1326262 0.1574459 0.9787304 -0.1315206 0.1418261 0.9809536 -0.1327233 -0.3140181 -0.8617738 -0.3984201 -0.1097932 -0.5745246 -0.8110901 -0.2323036 -0.8970369 -0.3759788 -0.05464375 -0.6512854 -0.756863 -0.1585096 -0.9240205 -0.3479378 -0.02796262 -0.7537855 -0.6565254 -0.06631976 -0.9080393 -0.4136018 -0.008727431 -0.8309255 -0.5563152 -0.01168924 -0.8815106 -0.4720197 2.16817e-4 -0.8642054 -0.5031393 0.002272367 -0.8701037 -0.4928634 5.36298e-4 -0.8733404 -0.4871103 -0.1559794 -0.3290249 -0.9313502 -0.04868769 -0.1222134 -0.991309 -0.2289204 -0.5461923 -0.8057726 -0.03738212 -0.1325518 -0.990471 -0.109579 -0.3935926 -0.9127308 -0.02159708 -0.1528242 -0.9880174 -0.02092218 -0.2131422 -0.9767972 -0.007968008 -0.1666517 -0.9859837 -0.001748442 -0.1660606 -0.986114 -0.002431631 -0.169351 -0.9855528 -0.03157132 -0.03555458 -0.998869 -0.02368205 -0.02346533 -0.9994442 -0.01154613 -0.01640892 -0.9997988 -0.007470965 -0.009270668 -0.9999292 -0.003197431 -0.009480178 -0.99995 -0.00155735 -0.005603432 -0.9999831 -0.005578458 0.02079516 -0.9997683 -0.007099509 0.01903504 -0.9997936 -0.004797577 0.01944458 -0.9997994 -0.002825617 0.02245712 -0.9997438 -0.004919767 0.02041995 -0.9997794 -0.005714178 0.01961618 -0.9997913 -0.005557596 0.01930791 -0.9997981 -0.004759609 0.02046936 -0.9997792 -0.004784703 0.01751095 -0.9998353 -0.005368471 0.01695644 -0.9998419 -0.005831837 0.01722288 -0.9998348 -0.005688726 0.01742964 -0.999832 -0.002768874 0.02036702 -0.9997888 -0.006002902 0.01563596 -0.9998598 0.01688754 -3.50639e-4 -0.9998574 0.0286377 6.82075e-4 -0.9995896 0.03386801 8.32161e-4 -0.999426 0.02906918 2.14677e-4 -0.9995774 0.004482865 7.00354e-4 -0.9999898 0.01904714 0.003166794 -0.9998136 0.0237016 0.002105474 -0.9997169 0.03465837 0.003434062 -0.9993934 0.05168366 0.004826605 -0.9986519 0.0409764 0.003623545 -0.9991536 0.05809605 0.005868494 -0.9982938 0.04140847 0.003867626 -0.9991348 0.04166972 0.004818737 -0.9991198 0.03028106 0.003041386 -0.9995369 0.002290427 0.00138843 -0.9999965 0.006763696 0.002700209 -0.9999735 0.01779639 0.004383385 -0.9998321 0.02675139 0.006472766 -0.9996213 0.05469119 0.01169681 -0.9984349 0.05220746 0.01116693 -0.9985738 0.05371093 0.0114293 -0.9984911 0.05842524 0.01243376 -0.9982144 0.02277117 0.004891753 -0.9997288 0.04425448 0.009579539 -0.9989744 0.01068007 0.001991748 -0.999941 0.02877765 0.005973696 -0.999568 0.01396489 0.001883864 -0.9999008 0.02791422 0.004589915 -0.9995998 0.007545709 0.002131998 -0.9999693 0.00132817 6.39801e-4 -0.999999 0.03117305 0.006876826 -0.9994904 0.01724171 0.003864407 -0.9998439 0.05475395 0.01139605 -0.9984349 0.05450898 0.01134544 -0.9984489 0.03387063 0.007077276 -0.9994012 0.05353164 0.01116299 -0.9985038 0.01183634 0.00267291 -0.9999264 0.02301788 0.005105733 -0.9997221 0.005205929 0.001232504 -0.9999857 0.0114367 0.002609968 -0.9999312 0.009932279 0.001525998 -0.9999495 0.01434206 0.002339482 -0.9998944 0.02134937 0.00296235 -0.9997678 0.01749396 0.002308011 -0.9998443 0.01562947 -0.006049096 -0.9998596 0.001624643 -0.002852857 -0.9999946 0.03980809 -0.01196956 -0.9991357 0.01954823 -0.007261514 -0.9997826 0.04931074 -0.01430159 -0.9986812 0.04300975 -0.0128442 -0.9989921 0.03296416 -0.008976578 -0.9994163 0.02072793 -0.006656408 -0.999763 0.01280778 -0.002834975 -0.9999141 0.005379617 -0.002310633 -0.999983 0.00757426 -7.82259e-4 -0.9999711 0.002121508 -0.001024961 -0.9999973 0.01761257 -2.02555e-4 -0.999845 0.007230937 -7.55832e-4 -0.9999737 0.04468995 0.001143276 -0.9990003 0.01932638 -2.3159e-4 -0.9998133 0.0590552 0.004470944 -0.9982447 0.02185291 6.9498e-4 -0.9997611 0.02163761 -0.03600507 -0.9991174 0.007071971 -0.01657849 -0.9998376 0.02949523 -0.04756945 -0.9984325 0.02699744 -0.04423278 -0.9986564 0.0329408 -0.05313712 -0.9980438 0.03521531 -0.05617928 -0.9977995 0.03255909 -0.04810374 -0.9983116 0.01776033 -0.03030276 -0.999383 0.02169972 -0.02270305 -0.9995068 0.004652976 -0.009852051 -0.9999406 0.01720613 -0.009711623 -0.9998048 0.002556562 -0.004624068 -0.9999861 0.03479218 -0.01285868 -0.9993119 0.01055878 -0.00626558 -0.9999247 0.06115347 -0.01999157 -0.9979282 0.03555583 -0.01313436 -0.9992814 0.07299578 -0.02155786 -0.9970993 0.04798251 -0.01573741 -0.9987243 0.02613574 -0.02660846 -0.9993043 0.02525222 -0.0255686 -0.9993541 0.02960628 -0.03333604 -0.9990057 0.03253608 -0.03681087 -0.9987925 0.03275114 -0.03960162 -0.9986788 0.03586626 -0.04332655 -0.998417 0.03577607 -0.04395419 -0.9983928 0.03465902 -0.04265505 -0.9984886 0.03834253 -0.0370723 -0.9985768 0.02189207 -0.02243942 -0.9995085 0.03897023 -0.02175748 -0.9990035 0.01643192 -0.01050174 -0.9998099 0.05124592 -0.02484571 -0.998377 0.03200525 -0.01655936 -0.9993506 0.05848312 -0.02910757 -0.997864 0.05761033 -0.02872741 -0.9979258 0.06326347 -0.03285574 -0.997456 0.06790065 -0.03474342 -0.997087 0.03691071 0.03304839 -0.998772 0.04058468 0.03320604 -0.9986242 0.04192233 0.0296489 -0.998681 0.04589945 0.02979737 -0.9985015 0.04652768 0.02633625 -0.9985698 0.05089986 0.02647012 -0.998353 0.05124872 0.02305394 -0.9984199 0.05565983 0.02315521 -0.9981814 0.05533421 0.02028775 -0.9982618 0.05901771 0.02038526 -0.9980488 0.05950474 0.01914262 -0.9980446 0.05901783 0.01911216 -0.9980741 0.06338965 0.01703757 -0.9978435 0.06712418 0.01726293 -0.9975954 0.06755006 0.01451367 -0.9976104 0.0730946 0.01479816 -0.9972153 0.05535423 0.1501505 -0.9871124 0.06172627 0.152891 -0.9863135 0.06150555 0.1471278 -0.9872034 0.0693832 0.1504452 -0.9861807 0.06769531 0.1439706 -0.9872639 0.07643997 0.1475807 -0.9860918 0.0732575 0.1402602 -0.987401 0.08393496 0.1445821 -0.9859265 0.08022952 0.1371409 -0.9872972 0.08996421 0.1410011 -0.9859134 0.08731311 0.1344059 -0.9870722 0.09638249 0.1379481 -0.9857388 0.09225982 0.132248 -0.9869137 0.09977883 0.1351307 -0.985791 0.09702581 0.129989 -0.9867568 0.1051456 0.1330426 -0.9855173 0.1412748 0.6796106 -0.719841 0.146111 0.6804746 -0.718057 0.1521754 0.6761198 -0.7209055 0.1628196 0.6778959 -0.716901 0.1612198 0.6708664 -0.7238414 0.1797654 0.6737798 -0.7167323 0.1742152 0.6644158 -0.7267742 0.1967096 0.667759 -0.7179159 0.1955497 0.6588327 -0.7264296 0.211262 0.6609876 -0.7200443 0.2212712 0.6556715 -0.7218961 0.2240568 0.6560141 -0.7207248 0.234357 0.6537722 -0.7194851 0.2366814 0.6540471 -0.7184736 0.241095 0.6514856 -0.7193329 0.2481697 0.6522706 -0.7162088 0.2011111 0.9458982 -0.2546191 0.176595 0.9497991 -0.2582552 0.2240991 0.9418341 -0.2504562 0.1949091 0.9471556 -0.254768 0.2403114 0.9388067 -0.2467643 0.2136356 0.94418 -0.2507666 0.2610193 0.9342134 -0.2431345 0.2365198 0.9397372 -0.2468856 0.2877776 0.9275084 -0.2385628 0.2580196 0.9350206 -0.2432333 0.3214539 0.9180555 -0.2320381 0.2795859 0.9299226 -0.2389054 0.3474711 0.9103897 -0.2246207 0.2969347 0.9259526 -0.2333271 0.3639155 0.9057464 -0.2172302 0.3097288 0.9233329 -0.22699 -0.02861231 -0.9892185 0.1436253 -0.04441422 -0.9894692 0.1377609 -0.01444935 -0.9903631 0.1377393 -0.0623331 -0.9896238 0.1294587 -0.01189506 -0.9914705 0.1297875 -0.08663606 -0.9889009 0.1207027 -0.01776456 -0.9925236 0.1207529 -0.100425 -0.9886311 0.1119083 -0.02114701 -0.9935687 0.1112388 -0.1051575 -0.9890819 0.1032423 -0.02729076 -0.9944201 0.1019014 -0.1095386 -0.9894419 0.09490048 -0.04972726 -0.9943906 0.09335237 -0.1158676 -0.9893651 0.08792853 -0.09669518 -0.9914793 0.08728647 -0.1257601 -0.9884595 0.08445304 -0.123199 -0.9887905 0.08435297 -0.1262226 -0.9884409 0.08397895 -0.08195757 -0.9932509 0.08207213 -0.09788399 -0.9919612 0.08019846 -0.0528196 -0.9795411 0.194189 -0.03849625 -0.9787344 0.2014871 -0.0624327 -0.9781224 0.198441 -0.0919466 -0.9775524 0.1895712 -0.07222074 -0.9786677 0.1923378 -0.1206641 -0.9763059 0.17963 -0.08005964 -0.9793936 0.1854152 -0.1310807 -0.9762789 0.1723299 -0.08542799 -0.9801806 0.1787407 -0.1373935 -0.9765673 0.1656485 -0.09350675 -0.9807124 0.1716382 -0.1436991 -0.9767395 0.1591556 -0.1029902 -0.9809954 0.164442 -0.1498687 -0.9768162 0.1528704 -0.1207155 -0.9802718 0.1565083 -0.1548539 -0.976818 0.1478072 -0.1321411 -0.9797111 0.150682 -0.1554987 -0.97723 0.1443662 -0.1003144 -0.9833345 0.1516257 -0.1510578 -0.9788308 0.1381011 -0.04525804 -0.9743624 0.2203853 -0.040582 -0.9738025 0.2237451 -0.0928176 -0.9727427 0.2125011 -0.1074689 -0.9724724 0.2067558 -0.1148899 -0.9719609 0.205164 -0.1433027 -0.9701822 0.1954759 -0.1234458 -0.9720344 0.1997757 -0.1525657 -0.9698543 0.1900171 -0.1300033 -0.972173 0.1948817 -0.1595199 -0.9696994 0.1850309 -0.1368976 -0.9722179 0.1898722 -0.1647469 -0.9696723 0.1805388 -0.1423189 -0.9723193 0.1853125 -0.1698464 -0.9696223 0.1760253 -0.1461032 -0.972549 0.181114 -0.1761146 -0.9694278 0.1708612 -0.1475145 -0.9730706 0.1771249 -0.1797664 -0.9696172 0.1659113 -0.1436038 -0.9742168 0.1740109 -0.1851679 -0.9696791 0.1594847 -0.06551963 -0.9606878 0.2697892 -0.1395702 -0.9679173 0.2089412 -0.1085796 -0.9700552 0.2172631 -0.164291 -0.9676148 0.1916506 -0.1429199 -0.9698968 0.1971656 -0.1707343 -0.9675337 0.1863557 -0.1522982 -0.969699 0.1910213 -0.1747294 -0.9675458 0.1825512 -0.1591602 -0.9694902 0.1864322 -0.1819225 -0.9670855 0.1779047 -0.1643018 -0.9694299 0.1822382 -0.1870477 -0.9668622 0.1737551 -0.1692714 -0.9693433 0.1781039 -0.1912021 -0.9667258 0.1699498 -0.1752192 -0.9690524 0.1738845 -0.1972092 -0.9662553 0.1657084 -0.1784565 -0.9690856 0.1703716 -0.2026118 -0.9658777 0.161334 -0.1833896 -0.96889 0.1661947 -0.2087181 -0.9653604 0.1565763 -0.156508 -0.9562173 0.2472931 -0.2316765 -0.9562374 0.1787071 -0.1647657 -0.9659514 0.1994746 -0.2217223 -0.9601984 0.1698773 -0.1712681 -0.9679045 0.183924 -0.201466 -0.9643955 0.171327 -0.175834 -0.96816 0.1781817 -0.1992688 -0.9653013 0.1687762 -0.1831448 -0.9677447 0.1729978 -0.2049906 -0.9648702 0.1643306 -0.1883656 -0.9675222 0.1685803 -0.2089763 -0.964653 0.1605415 -0.1926649 -0.9673534 0.1646445 -0.2117148 -0.9645811 0.1573538 -0.1986418 -0.96682 0.1606258 -0.2161606 -0.9641374 0.1539922 -0.2038137 -0.9663215 0.1571081 -0.2225884 -0.9633061 0.1499861 -0.2096317 -0.9656862 0.1533135 -0.2296532 -0.9623178 0.1456158 -0.2386661 -0.9461085 0.2188997 -0.2996547 -0.940342 0.1611332 -0.2209489 -0.9580338 0.1826274 -0.2725917 -0.9494695 0.1555688 -0.2009097 -0.9640823 0.173726 -0.2375093 -0.9583063 0.1588663 -0.1994169 -0.9653847 0.1681232 -0.2308294 -0.9604171 0.1559383 -0.2055283 -0.9651656 0.1619058 -0.2332874 -0.9605678 0.1512832 -0.2098606 -0.9650992 0.1566591 -0.2326589 -0.9612079 0.1481525 -0.212877 -0.9650831 0.1526366 -0.2312704 -0.9618799 0.1459485 -0.2174491 -0.964617 0.149097 -0.2338898 -0.9616608 0.1431929 -0.223819 -0.963704 0.1455325 -0.2418878 -0.9602939 0.1390175 -0.230758 -0.9626419 0.1416737 -0.2518886 -0.9584422 0.1339426 -0.3046048 -0.9213777 0.2414109 -0.3739285 -0.9097005 0.1806169 -0.2695378 -0.9416853 0.2014403 -0.3472426 -0.9232689 0.1643087 -0.2319275 -0.9544615 0.1876509 -0.3044355 -0.9388379 0.1609424 -0.2267857 -0.9578385 0.1763911 -0.289788 -0.9446359 0.1539028 -0.2306231 -0.9588345 0.165679 -0.2856248 -0.9471586 0.1459767 -0.2309001 -0.9602354 0.1569497 -0.2752581 -0.9509174 0.1413828 -0.2302173 -0.961427 0.1505266 -0.2635485 -0.9545594 0.1391354 -0.2333416 -0.9614682 0.1453639 -0.2614111 -0.9556114 0.1359093 -0.2415905 -0.9602157 0.1400711 -0.2702026 -0.953926 0.1304452 -0.2517528 -0.9584103 0.1344254 -0.2828904 -0.951126 0.1238242 -0.3754178 -0.888549 0.2637087 -0.4281718 -0.8762825 0.2209028 -0.3433907 -0.9094052 0.2346594 -0.4177362 -0.8859508 0.2014641 -0.2956605 -0.9290058 0.2225606 -0.3928684 -0.9000587 0.1885443 -0.2817087 -0.9366126 0.2083199 -0.3820012 -0.9076964 0.1736732 -0.2789535 -0.9407391 0.1928603 -0.371811 -0.9143902 0.1601472 -0.2687305 -0.946258 0.179944 -0.352398 -0.9235785 0.1510583 -0.2572454 -0.9513599 0.1695267 -0.3308629 -0.9324734 0.1449936 -0.2558783 -0.9534465 0.1595812 -0.3220702 -0.9366039 0.1380003 -0.2653554 -0.9525574 0.1490668 -0.3262575 -0.9363714 0.1294791 -0.2789008 -0.9502524 0.1386896 -0.3305058 -0.93585 0.1222736 -0.4270246 -0.8683381 0.2522682 -0.4520213 -0.8612089 0.2323709 -0.4153237 -0.8778643 0.2384549 -0.4517318 -0.864014 0.2223023 -0.3889901 -0.8912032 0.2333319 -0.444611 -0.8698838 0.2135959 -0.3774147 -0.8980928 0.2258044 -0.4403883 -0.8743799 0.2037595 -0.3669838 -0.9044038 0.2176616 -0.4350434 -0.8794164 0.1932985 -0.3457942 -0.9143412 0.2107291 -0.4257645 -0.8862512 0.1824377 -0.3222113 -0.924713 0.2026967 -0.414608 -0.8937711 0.1710954 -0.3127928 -0.9304755 0.1907248 -0.4064496 -0.8996258 0.1596 -0.3168176 -0.9319304 0.1764433 -0.3991884 -0.9045443 0.1498275 -0.322082 -0.9324808 0.1635324 -0.3797337 -0.9135697 0.1455781 -0.4525139 -0.863101 0.2242494 -0.4637666 -0.8593713 0.2154106 -0.4520173 -0.8651105 0.217404 -0.4636173 -0.8602185 0.2123284 -0.4445168 -0.8693903 0.2157901 -0.4599573 -0.8626801 0.2102909 -0.4398238 -0.8722061 0.2140366 -0.4588168 -0.863986 0.2074019 -0.434059 -0.8755688 0.212066 -0.459716 -0.8645511 0.2030089 -0.4239994 -0.8810301 0.2097871 -0.4609326 -0.865332 0.1968289 -0.411733 -0.8876905 0.2061108 -0.4574372 -0.868619 0.1904006 -0.4029256 -0.8930065 0.2004759 -0.4367409 -0.8794715 0.1891751 -0.3944692 -0.8976548 0.1964944 -0.3990906 -0.8959317 0.1950207 -0.3746179 -0.9056444 0.1986692 -0.337573 -0.9176417 0.2097103 -0.4646891 -0.8635883 0.1956512 -0.4692648 -0.8618943 0.1921693 -0.4643326 -0.8644001 0.1928933 -0.4680053 -0.8627467 0.1914139 -0.4603363 -0.8666043 0.1925815 -0.4651368 -0.8643793 0.1910396 -0.4592695 -0.8673116 0.1919434 -0.4636817 -0.8652679 0.1905542 -0.4600965 -0.8670592 0.1911011 -0.4634568 -0.8655008 0.1900431 -0.4612193 -0.8666214 0.1903789 -0.4588365 -0.8677212 0.1911258 -0.4573907 -0.868438 0.1913357 -0.4276549 -0.8814896 0.2002188 -0.4365964 -0.8773452 0.1991205 -0.3253692 -0.9176529 0.2281406 -0.3979338 -0.8895127 0.224535 -0.2227664 -0.9402744 0.2574089 -0.3398362 -0.9021622 0.2657344 -0.1820228 -0.9420243 0.2818828 -0.4695201 -0.8649368 0.1772996 -0.450783 -0.8721295 0.1902233 -0.4680334 -0.8631644 0.1894518 -0.439919 -0.8760758 0.1973897 -0.4650765 -0.8631359 0.1967241 -0.4479102 -0.8714451 0.1999003 -0.4635744 -0.8633021 0.1995201 -0.4485384 -0.8705943 0.2021856 -0.4632691 -0.8629304 0.2018245 -0.4352341 -0.8762488 0.2067836 -0.4585694 -0.8643721 0.2063374 -0.3975531 -0.8916543 0.2165738 -0.4289236 -0.8769634 0.2167016 -0.3007408 -0.9244331 0.2344751 -0.3270781 -0.914914 0.2365424 -0.1503898 -0.9563724 0.2504692 -0.223745 -0.9369049 0.2686026 -0.07104182 -0.9629085 0.2603082 -0.1890068 -0.9297903 0.3158582 -0.07848566 -0.9533591 0.291456 -0.4509127 -0.8713545 0.1934405 -0.391093 -0.8928025 0.2234952 -0.4413383 -0.8667086 0.2324581 -0.3464225 -0.9080842 0.2353177 -0.4474104 -0.8564728 0.2574458 -0.3472269 -0.9042881 0.2483877 -0.4470945 -0.8525926 0.2705412 -0.3482263 -0.900465 0.2605788 -0.4345052 -0.8562322 0.2794133 -0.3142949 -0.9108732 0.2674487 -0.404879 -0.867803 0.2880814 -0.2684419 -0.9235616 0.2738117 -0.3234429 -0.9013849 0.2879062 -0.1806442 -0.945242 0.2718185 -0.1563385 -0.9518402 0.2637395 -0.06131809 -0.9647735 0.2558364 -0.3938174 -0.8877297 0.2384198 -0.3240782 -0.9085542 0.2636338 -0.3556077 -0.8935372 0.2741068 -0.2444145 -0.9342288 0.2597656 -0.3525967 -0.8866477 0.299218 -0.1707199 -0.9528316 0.2509319 -0.3496319 -0.8814324 0.3175445 -0.1371514 -0.9564726 0.2575842 -0.3181158 -0.8905496 0.3251521 -0.1133344 -0.9564987 0.2688229 -0.2856727 -0.8983034 0.3338296 -0.09937977 -0.9533934 0.2848941 -0.2155242 -0.9188641 0.3305118 -0.07715392 -0.9507254 0.3002806 -0.3343209 -0.8951122 0.2949643 -0.2665789 -0.9060332 0.3286938 -0.2744014 -0.9028241 0.3310781 -0.1872546 -0.9251666 0.3301554 -0.1933642 -0.9232497 0.3319947 -0.06929433 -0.9481618 0.3101415 -0.1460102 -0.9310449 0.3344197 -0.02327072 -0.9507137 0.309196 -0.1199506 -0.9325316 0.3405829 -0.0144124 -0.9472075 0.3202973 -0.2746024 -0.8935168 0.3552766 -0.1626288 -0.8984994 0.4077388 -0.2210721 -0.875557 0.4295662 -0.08217114 -0.9036738 0.4202638 -0.09000265 -0.9014223 0.4234825 -0.0116207 -0.9151622 0.4029182 -0.1449185 -0.9411655 0.3052968 -0.06941306 -0.9300122 0.3609142 -0.0745992 -0.9293619 0.3615542 -0.02057284 -0.9274455 0.373392 -0.06105685 -0.964639 0.2564055 -0.02011257 -0.9569482 0.2895613 -0.01782339 -0.956994 0.2895597 -0.004005849 -0.9557563 0.2941327 -0.01787066 -0.9813346 0.1914762 -0.002803087 -0.9786632 0.2054522 -0.003720104 -0.9786902 0.2053093 -7.9438e-4 -0.9783955 0.2067406 -0.00581789 -0.9957712 0.0916844 -0.005813717 -0.9957712 0.09168416 -0.003611624 -0.9957095 0.09246438 -0.005304396 -0.9958105 0.09128808 -0.002392768 -0.9957201 0.09239041 -0.003067791 -0.9957562 0.09197926 0.2673676 0.9602189 -0.08058857 0.2500185 0.965074 -0.07825052 0.3196767 0.9442378 -0.07887858 0.2958415 0.9522346 -0.07567936 0.3635489 0.9284403 -0.07635909 0.33417 0.9397423 -0.072214 0.3973968 0.9147412 -0.07296723 0.3655038 0.9282965 -0.06835722 0.4255244 0.9022998 -0.06916874 0.3901607 0.9184955 -0.06434786 0.4604024 0.8853054 -0.06530028 0.4209679 0.9050567 -0.06048589 0.5049233 0.8609783 -0.06139093 0.4601888 0.8860424 -0.05617105 -0.002020061 -0.9968935 0.0787357 -0.02274274 -0.9973006 0.06981688 0.01017051 -0.9977778 0.06584823 -0.01820844 -0.9978905 0.06231349 0.0128858 -0.9981862 0.05880653 -0.03094047 -0.9978985 0.05693346 0.008742213 -0.9985849 0.05245751 -0.0411427 -0.9978374 0.05126345 0.005008995 -0.9989395 0.04577136 -0.04301959 -0.9980537 0.04514664 -0.002011954 -0.9991961 0.04004073 -0.04398769 -0.9982393 0.0397945 -0.02270257 -0.9990549 0.03706806 -0.05187135 -0.9979789 0.03670907 -0.05739331 -0.9976496 0.03743404 -0.07116079 -0.9967882 0.03673672 -0.07428932 -0.9965439 0.03716939 -0.07830685 -0.9962543 0.03668141 -0.04817664 -0.9983209 0.03216278 -0.0489692 -0.9982857 0.03206104 -0.01072931 -0.99991 0.00805974 -0.002512931 -0.9999858 0.004728376 -0.009558141 -0.9998847 0.01180952 4.80674e-4 -0.9999007 0.01408964 -0.005845606 -0.9998567 0.01589584 0.003653526 -0.9997991 0.01971095 -0.004976093 -0.9998263 0.01796358 0.003287553 -0.9997586 0.02172893 -0.005133032 -0.9998063 0.01900279 0.001118779 -0.9997552 0.02209991 -0.2368042 -0.9426324 -0.2353041 -0.06480956 -0.9614343 -0.2672901 -0.1597874 -0.974552 -0.1572151 -0.02676314 -0.9861691 -0.1635675 -0.06557571 -0.9931739 -0.09646451 -0.006261885 -0.9953239 -0.09639048 -0.02475655 -0.9971781 -0.0708732 -0.00135827 -0.9974787 -0.07095414 -0.001605689 -0.9981367 -0.06099742 0.001102924 -0.9981334 -0.06106281 0.006919026 -0.9981547 -0.06032854 0.001494586 -0.9982032 -0.05990374 0.005873262 -0.9977876 -0.06622356 -0.002161204 -0.9979885 -0.06336015 0.2490474 0.9601668 -0.1267088 0.2028549 0.9705943 -0.1296022 0.2920433 0.9484947 -0.1227539 0.2295451 0.9650385 -0.1265292 0.3254756 0.9381576 -0.1180092 0.252089 0.959933 -0.1223918 0.3546879 0.9281383 -0.1129427 0.276605 0.9537739 -0.1174947 0.3823519 0.9177188 -0.1077001 0.2992697 0.9475437 -0.1122444 0.4179155 0.9027302 -0.1021021 0.3260052 0.9392891 -0.1070365 0.4571546 0.8842362 -0.09558296 0.3525129 0.9302707 -0.1016433 0.4902426 0.867132 -0.08800232 0.3729351 0.9229343 -0.09545493 0.5461017 -0.6541648 0.5232986 0.5174307 -0.4872983 0.7034243 0.5484551 -0.5971296 0.5853489 0.5162255 -0.4326077 0.739163 0.5142561 -0.4258543 0.7444387 0.5427455 -0.3046531 0.7826965 0.5196405 -0.180809 0.8350341 -0.6367401 0.1592943 -0.7544451 -0.5881579 0.2316814 -0.774851 0.4970697 -0.2174758 0.8400155 0.4930441 -0.2003297 0.8466261 0.4823232 -0.1889359 0.8553757 0.4618089 -0.4861234 0.7419007 0.5121636 -0.1919625 0.8371612 -0.006671786 0.5709244 -0.8209756 0.5811213 -0.2274345 0.7813908 -0.5052621 -0.3612315 -0.7837232 -0.5589112 0.2056093 -0.8033325 0.1604309 -0.878484 0.4500312 0.6214066 -0.074961 0.7798941 -0.4658992 0.5006154 -0.7296042 -0.5321246 0.4584201 -0.7118248 0.9981634 -0.01520824 0.05864071 0.9963281 -0.02829557 0.08080714 0.991503 -0.05557447 0.1176164 0.9910577 -0.05702984 0.1206328 0.9615234 -0.06538969 0.2668278 0.9793174 -0.03544408 0.1992016 0.05837339 -0.7067965 -0.7050045 0.05666047 -0.7293177 -0.6818249 0.009202957 -0.1129373 -0.9935595 0.009496986 -0.1074507 -0.9941651 0.00143218 -0.01940608 -0.9998107 0.001840233 -0.01692348 -0.9998551 -3.26401e-4 -0.003940224 -0.9999922 2.04387e-4 -0.001702308 -0.9999986 -0.001221597 -1.48807e-4 -0.9999993 -8.948e-4 0.001946866 -0.9999978 -0.002522468 0.002729237 -0.9999931 -0.002544522 0.007568717 -0.9999682 -0.005396127 0.009806334 -0.9999374 -0.006555855 0.01903653 -0.9997974 -0.008432328 0.01901644 -0.9997836 -0.009117007 0.02303111 -0.9996932 -0.008746147 0.0239011 -0.9996761 -0.007529556 0.01581209 -0.9998466 -0.005912721 0.02229064 -0.9997341 -0.004959225 0.008194684 -0.9999542 -0.004783391 0.02685719 -0.999628 -0.004539787 0.01339942 -0.9999 -0.00272119 0.02612227 -0.9996551 -0.003518879 0.0131756 -0.9999071 3.04213e-4 0.01973801 -0.9998052 -0.002474188 0.007741987 -0.999967 0.002487421 0.01633232 -0.9998636 -0.001744687 0.005924403 -0.999981 0.007423579 0.02510094 -0.9996575 -1.00115e-4 0.00845474 -0.9999643 0.01735311 0.04699259 -0.9987446 0.006944656 0.02393114 -0.9996896 0.03550922 0.08952492 -0.9953514 0.03827363 0.09575045 -0.9946694 0.090792 0.219956 -0.9712756 0.1378673 0.3268269 -0.9349743 0.2219635 0.5258931 -0.8210778 0.276497 0.647291 -0.7103267 0.1661344 0.420444 -0.8919788 0.3665575 0.8483854 -0.3819398 0.8393103 -0.4377179 0.3224302 0.8880364 -0.343626 0.3054713 0.8716561 -0.2113796 0.4421926 0.6434513 -0.5349869 0.547503 0.6688813 -0.3545304 0.6533805 -0.1882743 -0.81468 0.5484974 -0.2375774 -0.8495243 0.471026 -0.4241737 -0.8363656 0.3472309 -0.441555 -0.8537193 0.2760304 -0.4549963 -0.8496828 0.266491 -0.4584885 -0.8580884 0.2312414 -0.4637479 -0.8561698 0.2278403 -0.4656172 -0.864481 0.1894024 -0.4666412 -0.8640662 0.1887746 -0.4674575 -0.8727056 0.1409555 -0.4614055 -0.8753507 0.1444513 -0.4606819 -0.8835175 0.08467125 -0.4416921 -0.8921357 0.09487849 -0.4384061 -0.8985448 0.02042871 -0.3996286 -0.9157928 0.04025691 -0.3925464 -0.9188569 -0.0401172 -0.3343604 -0.942387 -0.01048368 -0.3227646 -0.9420839 -0.09111016 -0.2484953 -0.9672672 -0.05142152 -0.2371072 -0.9652233 -0.1101105 -0.1394114 -0.9881967 -0.06349712 -0.1343251 -0.9873474 -0.08427423 -0.02662682 -0.9985938 -0.04584342 -0.02250999 -0.9978003 -0.0623539 0.07463204 -0.9966436 -0.03363966 0.07911032 -0.9950137 -0.060741 0.1442641 -0.983151 -0.112259 0.07494509 -0.9809725 -0.1790986 0.06479114 -0.9866378 -0.1494926 -0.6713226 0.3909963 -0.6296411 0.0932126 -0.9905596 -0.1005154 0.1905476 -0.9664313 -0.1723436 -0.03581398 -0.9931648 -0.1110907 0.09278732 -0.9908122 -0.09839636 -0.1582694 -0.9788484 -0.1296401 -0.03627437 -0.9933627 -0.1091551 -0.2468801 -0.9579666 -0.146117 -0.1596931 -0.9796412 -0.1216601 -0.3026103 -0.9462965 -0.1137983 -0.2520667 -0.9628251 -0.09710925 -0.3427066 -0.9376611 -0.05782592 -0.3074835 -0.9504379 -0.0460633 -0.3788966 -0.9254309 0.003880023 -0.3466303 -0.9378863 0.01472342 -0.4116128 -0.9086249 0.07054013 -0.3822023 -0.9205385 0.08081012 -0.4338741 -0.891273 0.131855 -0.4133427 -0.8998041 0.139644 -0.4436206 -0.8768402 0.1853438 -0.4335172 -0.8809832 0.1895558 -0.438822 -0.8677758 0.2332388 -0.4411566 -0.8668827 0.2321536 -0.4596669 -0.8486621 0.2616847 -0.43239 -0.8578116 0.2778456 -0.5319104 -0.7897275 0.3056174 -0.4047513 -0.8209935 0.4026736 -0.1947484 -0.7466548 0.6360659 -0.5315816 -0.6738115 0.5132243 0.1363974 -0.7302384 -0.6694383 0.1343318 -0.7424106 -0.6563394 0.02610772 -0.1374105 -0.9901701 0.02703571 -0.1259031 -0.9916741 0.004881024 -0.0259307 -0.9996519 0.006376504 -0.02108412 -0.9997574 0.001054406 -0.006390273 -0.9999791 0.002118647 -0.004370212 -0.9999882 -1.26303e-4 -0.001390457 -0.9999991 3.54455e-4 -4.59059e-4 -0.9999998 -0.001214206 6.86924e-4 -0.9999991 -8.09828e-4 0.0020141 -0.9999977 -0.003801047 0.005093514 -0.9999798 -0.003760218 0.008347511 -0.9999582 -0.01010757 0.01926565 -0.9997633 -0.01056897 0.02186393 -0.9997051 -0.01754862 0.0402587 -0.9990352 -0.01627576 0.0345844 -0.9992693 -0.01764553 0.04871124 -0.9986571 -0.01502639 0.03336662 -0.9993302 -0.01696872 0.05587977 -0.9982933 -0.01522982 0.04062384 -0.9990585 -0.01287961 0.05747741 -0.9982637 -0.01256042 0.03758889 -0.9992144 -0.001786053 0.05037945 -0.9987286 -0.007211744 0.02126324 -0.9997479 0.008360087 0.04188281 -0.9990876 -0.003497064 0.01361483 -0.9999012 0.01554375 0.05025255 -0.9986157 0.003060996 0.02422899 -0.9997018 0.0193153 0.05774754 -0.9981443 0.01488655 0.04857468 -0.9987087 0.02603036 0.07608199 -0.9967618 0.03276044 0.09064882 -0.995344 0.04407262 0.12496 -0.9911825 0.06976717 0.1840063 -0.9804459 0.08459722 0.2277247 -0.9700437 0.1019662 0.268099 -0.9579802 0.1562141 0.3983687 -0.9038249 0.1616339 0.4106726 -0.897342 0.1663753 -0.9651133 -0.2021771 0.1467697 -0.9738689 -0.1733152 0.5628829 -0.3437236 0.7516762 0.3762471 -0.5467758 0.7479802 0.3426187 -0.6278476 0.6988704 -0.1847994 -0.858963 0.4775267 -0.2489892 -0.9084677 0.3356946 -0.305915 -0.9043515 0.2975975 -0.3116348 -0.9098233 0.2740534 -0.3709966 -0.897787 0.2373604 -0.3747271 -0.9102243 0.1762707 -0.3611523 -0.9139972 0.1848735 -0.3612767 -0.925984 0.1096948 -0.3325003 -0.9344356 0.127568 -0.3301958 -0.942918 0.04331779 -0.2966315 -0.9528558 0.06384128 -0.2935068 -0.9556939 -0.02243071 -0.2617039 -0.9651436 -0.00298345 -0.2586132 -0.9623643 -0.08351248 -0.2269534 -0.9717926 -0.06412059 -0.2237514 -0.9644196 -0.1408205 -0.1903871 -0.9742687 -0.1206376 -0.1871758 -0.9648174 -0.1846418 -0.1397866 -0.9774906 -0.1580253 -0.1370514 -0.971688 -0.1924559 -0.0536313 -0.9867117 -0.1533746 -0.04940974 -0.9812355 -0.1863755 0.05376523 -0.9886828 -0.1400563 0.05310362 -0.9894512 -0.1347825 0.1418415 -0.9611767 -0.2366862 0.1875861 -0.7542073 -0.6292718 0.186987 -0.7565711 -0.6266068 0.04321187 -0.1701282 -0.9844741 0.04439687 -0.1571148 -0.986582 0.008212268 -0.03512698 -0.9993491 0.01050114 -0.02929019 -0.9995158 0.001662254 -0.009371459 -0.9999548 0.003447949 -0.007030308 -0.9999694 2.76244e-4 -0.002350449 -0.9999973 9.85819e-4 -0.001591444 -0.9999983 -3.18864e-4 -9.00402e-5 -1 3.79583e-5 3.11447e-4 -1 -0.001355111 0.00231117 -0.9999964 -9.00837e-4 0.003026902 -0.9999951 -0.00372523 0.01041573 -0.9999389 -0.003532111 0.01097387 -0.9999336 -0.006690979 0.02656328 -0.9996249 -0.00707668 0.02451741 -0.9996743 -0.007356107 0.04107588 -0.9991289 -0.008365333 0.03559881 -0.9993312 -0.006009221 0.05174422 -0.9986423 -0.007734715 0.04410761 -0.9989969 -0.003030896 0.05844736 -0.998286 -0.005827188 0.04906284 -0.9987787 0.001171648 0.06367564 -0.99797 -0.002977192 0.05142241 -0.9986726 0.007500171 0.06280565 -0.9979977 2.39499e-5 0.04419821 -0.9990228 0.009802818 0.06481951 -0.9978489 0.006530761 0.05682271 -0.998363 0.01027989 0.06729096 -0.9976805 0.01028347 0.06730473 -0.9976795 0.0109319 0.07827919 -0.9968715 0.0143038 0.08739423 -0.9960712 0.01838994 0.1166785 -0.9929995 0.01850247 0.1170341 -0.9929555 0.07884037 0.2763314 -0.9578232 0.01107925 0.08112889 -0.9966421 0.2196707 0.6018743 -0.767784 0.03032219 0.1167664 -0.9926964 0.2204855 -0.9465005 -0.2356332 0.1923058 -0.9605542 -0.2008839 0.6360942 0.2868405 0.7163147 -0.8172233 -0.2154514 -0.5345344 0.39036 -0.7807201 0.48795 -0.5030611 -0.8464038 0.174729 -0.2691748 -0.9630914 2.35858e-5 -0.09761983 -0.5550746 -0.8260524 -0.8172222 -0.215453 -0.5345352 -0.835546 -0.0229842 -0.5489398 0.5590077 -0.515052 0.6497939 0.6769667 -0.4858 0.5529146 0.5590022 -0.5150571 0.6497945 0.9032881 -0.3382036 0.2639868 0.4874141 -0.4244721 0.7630538 0.5799763 -0.3992679 0.7100793 0.3559157 -0.5903168 0.7244654 0.4392999 -0.7456811 0.5009745 0.8695285 -0.3058853 0.3877556 0.6669508 0.2694315 0.6946823 0.7452138 -0.265241 0.6118037 -0.1188148 -0.9870657 0.1076307 0.3878984 0.8889915 -0.2433702 0.404703 0.9055659 -0.1271458 0.4004274 0.9111043 -0.0977078 0.005157768 -0.9340878 0.3570061 0.02939635 -0.9125102 0.4079964 0.007327437 -0.9171352 0.3985089 0.01950651 -0.9152573 0.4023975 -0.04489064 -0.9376425 0.3446903 0.009068787 -0.9367597 0.3498558 -0.04490035 -0.9376428 0.3446885 -0.0962069 -0.9288639 0.3577097 -0.03069239 -0.9552332 0.2942577 -0.03069102 -0.9552355 0.2942504 0.7719478 0.2618046 -0.5792711 -0.7248072 0.2043684 0.6579424 0.9709165 0.23221 0.05830818 -0.6528772 0.7530159 0.08196747 0.4058708 0.9078236 -0.1054769 0.4028531 0.9034301 -0.146709 0.3780879 0.8486393 -0.3699471 0.3389185 0.7641746 -0.5487908 0.3433082 0.7737518 -0.5323981 0.3695538 0.8158997 -0.4446771 0.1553163 0.3310751 -0.9307342 0.1376323 0.2954667 -0.9453871 0.03556692 0.06650626 -0.997152 0.03269886 0.06117087 -0.9975916 0.01261353 0.01641786 -0.9997857 0.01115322 0.01430046 -0.9998356 0.0100218 0.01184582 -0.9998797 0.00801593 0.00948137 -0.9999229 0.009212851 0.01196867 -0.999886 0.006606876 0.008826255 -0.9999393 0.007215023 0.01006644 -0.9999234 0.004374027 0.006031095 -0.9999723 0.004606246 0.006522834 -0.9999682 0.001549482 0.001587152 -0.9999976 0.001598536 0.001702964 -0.9999973 -0.001816213 -0.004351615 -0.999989 -0.001195251 -0.002442061 -0.9999964 -0.004377961 -0.009162724 -0.9999485 -0.003901422 -0.008143365 -0.9999593 -0.004896879 -0.00956434 -0.9999424 -0.004910051 -0.009612679 -0.9999418 -0.006596744 -0.008245885 -0.9999443 -0.004910051 -0.009611189 -0.9999418 0.01447796 -0.011101 -0.9998336 0.006926953 -0.01198935 -0.9999042 -0.08516162 -0.6982831 -0.7107378 -0.07921051 -0.7002906 -0.7094497 -0.05874627 -0.3983646 -0.9153439 -0.05953043 -0.3974671 -0.9156835 -0.03380042 -0.2035859 -0.9784736 -0.03712385 -0.2005067 -0.9789888 -0.0371471 -0.2005324 -0.9789826 -0.03371888 -0.1968896 -0.9798457 -3.09834e-4 -0.06007647 -0.9981938 -0.01005136 -0.05355262 -0.9985145 0.02139723 -0.01594144 -0.999644 0.0124576 -0.01050037 -0.9998673 0.01247334 -0.01049053 -0.9998672 0.01545661 -0.008899807 -0.999841 0.01524609 -0.01552772 -0.9997632 0.01381582 -0.01491415 -0.9997934 0.01328831 -0.02136856 -0.9996834 0.009466469 -0.02056062 -0.9997438 0.01328915 -0.02137124 -0.9996833 0.001007556 -0.02441978 -0.9997014 8.15477e-4 -0.02442467 -0.9997014 -0.001466989 -0.02521562 -0.999681 -0.001001358 -0.01461338 -0.9998927 0.007394313 -0.01377725 -0.9998778 -9.41409e-4 -0.01461607 -0.9998928 0.002474546 -0.9349777 0.3546983 -7.62599e-4 -0.9351385 0.3542816 0.006108462 -0.9343177 0.3563894 3.09442e-4 -0.9357872 0.3525653 0.00234282 -0.9353604 0.3536883 -0.001122415 -0.957821 0.2873633 3.82071e-4 -0.9576893 0.287804 0.001175582 -0.957666 0.2878792 -1.70301e-4 -0.9577177 0.2877098 -7.07995e-4 -0.9855293 0.1695044 -3.18051e-4 -0.9855121 0.169605 -0.00409168 -0.9858109 0.1678098 -4.74386e-4 -0.9856815 0.1686174 -0.007864534 -0.9939119 -0.1098973 -0.02884501 -0.9930834 -0.1138131 -0.007651627 -0.9933558 -0.1148298 -0.02891206 -0.9930813 -0.113815 -0.03322356 -0.9250739 -0.3783314 -0.03213965 -0.9251806 -0.3781641 -0.06695121 -0.9178719 -0.391189 -0.04056733 -0.9223778 -0.3841531 -0.06666201 -0.8559994 -0.512661 -0.08709526 -0.8560647 -0.509478 -0.2151373 -0.5752058 -0.7892112 -0.2015632 -0.5583333 -0.8047586 -0.2214472 -0.6215286 -0.7514409 -0.311172 -0.777746 -0.5461531 -0.1552679 -0.5425193 -0.8255695 -0.2443853 -0.6927196 -0.6785393 -0.09776937 -0.1864994 -0.9775782 -0.1169336 -0.2274838 -0.9667357 -0.07769024 -0.1557744 -0.9847328 -0.09696239 -0.1957061 -0.9758574 -0.04210531 -0.04771834 -0.997973 -0.03974074 -0.04083311 -0.9983754 -0.03577005 -0.03970736 -0.9985709 -0.04185348 -0.04388177 -0.9981597 -0.04012459 -0.04129093 -0.9983412 -0.04114246 -0.04286772 -0.9982334 -0.0214889 0.005543112 -0.9997537 -0.009553492 0.01744794 -0.9998021 -0.01773452 0.00818938 -0.9998093 -0.01337456 0.0132991 -0.9998222 -0.006063699 0.01949918 -0.9997916 -0.009612858 0.0171799 -0.9998062 -0.005970537 0.01687139 -0.9998399 -0.006542682 0.01664632 -0.9998401 -0.007707238 0.007662653 -0.999941 0.002478182 0.0176559 -0.9998411 -0.006501317 0.008147716 -0.9999457 -0.004625797 0.01088845 -0.9999301 0.0189132 -0.008285343 -0.9997868 -0.00388807 -0.002244472 -0.99999 0.0010944 0.006905615 -0.9999756 -0.007020294 -0.004464089 -0.9999654 -0.004438161 -5.65854e-4 -0.99999 0.02308309 -0.002358794 -0.9997308 0.02770435 -0.001342475 -0.9996153 0.02464365 -0.002129793 -0.9996941 0.02811956 -0.001269042 -0.9996038 0.02465271 -0.001355469 -0.9996951 0.02433365 -0.001451551 -0.9997029 -0.004550516 -0.009315133 -0.9999463 0.0250324 3.58967e-4 -0.9996866 0.04098719 0.001527905 -0.9991586 0.02504163 3.58642e-4 -0.9996864 0.04133129 0.00252664 -0.9991424 0.02363806 8.98066e-4 -0.9997202 0.02970069 0.001974701 -0.999557 0.007038652 0.001949787 -0.9999734 0.001404106 0.002602756 -0.9999957 0.02621841 0.002814054 -0.9996523 0.02378278 0.002616822 -0.9997138 0.02733713 0.003277003 -0.999621 0.0229063 0.002938687 -0.9997334 0.01942908 0.002102732 -0.9998091 0.0196101 0.002463161 -0.9998047 0.01750236 0.002337515 -0.9998442 0.0195989 0.002464175 -0.9998049 0.01595687 0.001919567 -0.9998708 0.01647007 0.002899706 -0.9998602 0.02340477 0.003201305 -0.9997211 0.01647627 0.002884984 -0.9998601 0.009436607 0.001830101 -0.9999539 0.02087771 0.001892924 -0.9997802 0.01088452 0.003775358 -0.9999337 0.03184992 -0.00952661 -0.9994474 0.01821035 -0.002028942 -0.9998322 0.03015798 -0.01285082 -0.9994626 0.04297697 -0.01281249 -0.9989939 0.07651865 0.01243269 -0.9969906 0.08110094 0.0114156 -0.9966406 0.07926464 0.01143115 -0.9967882 0.05666744 0.01716852 -0.9982455 0.1159859 0.1312087 -0.9845464 0.118008 0.1308676 -0.9843515 0.2789522 0.6471045 -0.7095361 0.2816416 0.646139 -0.7093536 0.3938911 0.8937044 -0.2148072 0.3490485 0.9123662 -0.2138999 -0.007843315 -0.9676845 0.2520427 -0.07111579 -0.9627965 0.2607021 -0.007843852 -0.9676868 0.2520337 -0.08904623 -0.9376187 0.3360683 -0.03402876 -0.9622433 0.2700552 -0.02764213 -0.9526703 0.3027463 -0.08189266 -0.9496622 0.3023829 -0.02766984 -0.9526726 0.3027367 -0.01472938 -0.955101 0.295914 0.02178192 -0.9481003 0.3172246 -0.00541085 -0.9483502 0.3171793 -0.1142189 -0.9208498 0.3728134 -0.04167813 -0.9415274 0.3343492 -0.09719777 -0.9250903 0.3670975 -0.0140978 -0.9309554 0.364861 -0.0442323 -0.9246633 0.3782083 0.03433591 -0.9175523 0.3961299 0.02329105 -0.9183011 0.395197 -7.63401e-4 -0.9174624 0.3978219 -0.03134268 -0.9081346 0.4175036 -0.009770929 -0.9154905 0.4022212 -0.02012139 -0.9093433 0.4155598 -0.0129618 -0.9127334 0.4083503 -0.009643733 -0.9119703 0.4101431 0.0352776 -0.9116479 0.4094554 -0.001002192 -0.9278457 0.3729631 -0.01026505 -0.9281108 0.3721625 -0.0010311 -0.9278474 0.3729589 -1.22792e-4 -0.9278925 0.372848 -5.8515e-4 -0.9557564 0.2941589 -1.57063e-4 -0.9557721 0.2941085 -6.94641e-4 -0.9784016 0.2067121 -4.95466e-4 -0.9783853 0.20679 -6.29922e-4 -0.9783937 0.2067493 -7.76992e-4 -0.9784045 0.2066983 -0.002614438 -0.9957465 0.09209883 -0.002384424 -0.9957322 0.09225994 -0.002460479 -0.9957348 0.09222865 -0.002757608 -0.9957535 0.09201931 -0.002726614 -0.9957497 0.09206002 -0.002277851 -0.9957353 0.09222918 0.5179673 0.8535224 -0.05665385 0.4961314 0.8667712 -0.05060952 0.5333036 0.8443923 -0.05088251 0.5333036 0.8443923 -0.05088245 0.5333036 0.8443923 -0.05088245 -0.00475198 -0.9998032 0.01926368 -0.004750251 -0.9997969 0.01958435 -0.003086745 -0.9997828 0.02061378 -0.02221703 -0.9997504 0.002375543 -0.01127785 -0.9998291 0.01465666 -0.05961406 -0.9974498 -0.03924578 -0.04200077 -0.9990295 -0.01326674 -0.1485518 -0.9825477 -0.1119491 -0.3020734 -0.8720507 -0.3850705 -0.29045 -0.8756162 -0.3859214 -0.1489724 -0.946423 -0.2865151 -0.2853861 -0.8801665 -0.3792909 0.52523 0.8464373 -0.08762091 0.4037052 0.9107466 -0.08696448 0.5228875 -0.2164052 0.8244741 0.4519396 -0.2010204 0.8691039 -0.3427015 -0.3470915 -0.8729738 0.7401359 -0.0218665 -0.6721018 0.9940571 0.04003751 -0.1012304 -0.03907757 0.1377179 -0.9897004 0.6283962 0.04932564 -0.776328 -0.01864558 -0.007212221 -0.9998002 -0.122974 -0.003693997 -0.992403 -0.02056914 0.006317973 -0.9997685 -0.6964497 0.07476443 -0.7137003 -0.0205608 0.006317973 -0.9997687 -0.9937607 0.00528866 -0.1114081 -0.05677872 0.2658283 -0.962347 -0.8768789 -0.1443179 0.4585366 0.06015312 -0.9406965 0.3338741 0.9999525 0.008953988 -0.00385338 0.999949 0.008047401 0.00610429 0.9999516 0.008988857 -0.003999173 0.9999672 0.005345165 0.006093502 0.9999749 0.00663799 -0.002537012 0.9999996 -8.98076e-4 0 0.9999996 -8.97983e-4 0 0.9999996 -8.9789e-4 0 0.9999724 0.004261732 0.006088793 0.9999749 0.006633639 -0.002511739 0.9999873 0.004830837 -0.001449286 0.9999938 0.003377676 -0.001015007 0.9999739 0.003902256 0.006087243 0.9999942 0.003372251 -5.77009e-4 0.9999785 0.002476751 0.0060817 0.9999976 0.002164959 2.48113e-4 0.9987782 0 -0.04941868 0.99998 0.001793563 0.006078481 -0.7525767 0 0.6585046 0.99998 0.001793861 0.006078422 0.9999976 0.002164602 2.39328e-4 0.9999986 4.75561e-5 0.001651823 0.9999919 -7.13571e-6 0.004036605 0.9999841 0.001706302 0.005387961 0.9999994 0.001080989 4.47012e-4 1 4.98325e-6 0 0.9999994 9.60149e-4 7.65397e-4 1 -1.64046e-6 0 0.9999987 2.46012e-5 0.001652359 0.9999991 2.87319e-4 0.001425743 1 -1.77006e-6 0 0.9999986 4.06531e-5 0.001644372 0.9999986 4.02378e-5 0.001651227 0.9999986 3.64907e-5 0.001651108 0.9999965 0.001317143 0.002312719 0.9999918 2.18887e-5 0.004053592 -0.9999672 1.82905e-5 -0.00811249 1 -7.38704e-6 0 1 4.50256e-5 0 0.9946324 0.01399707 0.102522 0.9999672 -3.03744e-5 0.008099615 0.9999666 1.65487e-5 0.008185148 0.9999954 -0.003044247 2.68633e-4 1 1.40543e-6 0 0.9999915 -0.002006828 0.003613293 -1 5.53234e-7 0 -1 0 0 -1 5.67086e-5 0 -1 -2.19552e-7 0 -1 -3.04314e-7 0 -1 0 0 -1 9.03969e-7 0 -1 -6.32253e-7 0 -1 0 0 -1 -5.95968e-7 0 -1 1.39153e-6 0 -1 1.03398e-5 0 -1 -9.16337e-7 0 -1 2.39789e-6 0 -0.6110162 0.2271704 -0.7583225 -0.7896494 0.0176739 -0.6133037 -0.5462286 0.3662254 -0.7533348 -0.7452912 0.1701958 -0.6446507 -0.4817775 0.47648 -0.73543 -0.6878117 0.305402 -0.6585171 -0.5982013 0.2577606 -0.7587588 -0.5414443 0.3260763 -0.7749274 -0.6134775 0.2210775 -0.758136 -0.5593448 0.2917323 -0.7759032 -0.6261638 0.1884177 -0.756583 -0.574791 0.2603446 -0.775781 -0.8917185 -0.04560673 -0.4502869 -0.8127122 -0.09015727 -0.5756479 -0.812707 -0.09016466 -0.5756542 -0.5809443 0.468021 -0.6659281 -0.79658 0.2466412 -0.5519317 -0.7795476 -0.2818812 -0.5593287 -0.7795452 -0.2818711 -0.5593371 -0.7795504 -0.2818796 -0.5593255 -0.5809383 0.4680345 -0.6659238 0.8141095 0.07346433 0.5760458 0.894159 0.1694083 0.4144642 0 0.8479983 -0.529999 0.891953 0.4459765 0.07432937 0 -0.3162278 0.9486834 -0.8126994 -0.09011876 -0.575672 -0.1611782 0.9131802 -0.3743309 -0.8540712 -0.1820275 -0.4872664 -0.612577 -0.6921572 0.3816648 -0.6125808 -0.6921617 0.3816503 -0.6125687 -0.6921695 0.3816556 -0.3210265 -0.7969595 0.5116617 -0.8524331 0.04312527 -0.5210547 -0.841789 0.05741018 -0.5367453 -0.8417911 0.05741196 -0.5367417 -0.8417893 0.05741196 -0.5367445 -0.9920295 -0.04563826 -0.1174509 -0.9920298 -0.04563415 -0.1174501 -0.8842 -0.04168379 -0.4652451 -0.8841884 -0.0416696 -0.4652684 -0.4814717 0.1477566 -0.8639174 0.8581808 0.1938771 0.4753288 0.7976446 0.1510681 0.5839021 + + + + + + + + + + + + + + +

0 0 1 0 2 0 1 1 3 1 2 1 1 2 0 2 4 2 0 3 5 3 4 3 6 4 7 4 8 4 9 5 10 5 11 5 12 6 13 6 14 6 12 7 15 7 13 7 16 8 17 8 18 8 19 9 17 9 16 9 20 10 21 10 22 10 22 11 23 11 20 11 24 12 20 12 23 12 23 13 25 13 24 13 26 14 24 14 25 14 27 15 17 15 19 15 27 16 28 16 17 16 28 17 18 17 17 17 14 18 28 18 27 18 27 19 29 19 14 19 29 20 30 20 14 20 31 21 14 21 30 21 30 22 32 22 31 22 33 23 34 23 35 23 36 24 37 24 35 24 13 25 35 25 38 25 35 26 37 26 38 26 35 27 13 27 33 27 13 28 39 28 33 28 15 29 39 29 13 29 38 30 40 30 13 30 13 31 28 31 14 31 18 32 28 32 13 32 13 33 41 33 18 33 13 34 40 34 41 34 14 35 42 35 12 35 42 36 14 36 31 36 32 37 43 37 31 37 44 38 36 38 45 38 44 39 37 39 36 39 44 40 38 40 37 40 44 41 40 41 38 41 44 42 41 42 40 42 44 43 18 43 41 43 18 44 44 44 16 44 34 45 33 45 46 45 26 46 46 46 33 46 33 47 39 47 26 47 24 48 26 48 15 48 26 49 39 49 15 49 15 50 12 50 24 50 20 51 24 51 42 51 24 52 12 52 42 52 42 53 31 53 20 53 21 54 20 54 31 54 31 55 43 55 21 55 43 56 47 56 48 56 21 57 43 57 48 57 3 58 49 58 9 58 11 59 3 59 9 59 50 60 49 60 3 60 51 61 50 61 3 61 52 62 51 62 3 62 52 63 3 63 53 63 54 64 55 64 56 64 54 64 56 64 57 64 54 65 57 65 4 65 54 64 58 64 55 64 59 64 55 64 58 64 60 66 6 66 8 66 60 67 8 67 61 67 60 68 61 68 62 68 63 69 60 69 62 69 64 70 60 70 63 70 63 71 65 71 64 71 63 72 62 72 66 72 65 73 63 73 66 73 67 74 64 74 65 74 48 75 67 75 65 75 65 76 68 76 48 76 48 77 68 77 21 77 69 78 19 78 16 78 16 79 70 79 69 79 70 80 71 80 69 80 58 81 54 81 72 81 72 82 73 82 74 82 72 83 74 83 47 83 75 84 72 84 47 84 43 85 32 85 75 85 47 86 43 86 75 86 76 87 59 87 77 87 78 88 59 88 76 88 4 89 57 89 1 89 1 90 78 90 3 90 1 91 57 91 56 91 1 92 56 92 55 92 1 93 55 93 78 93 59 94 78 94 55 94 3 95 78 95 53 95 65 96 79 96 80 96 65 97 80 97 68 97 81 98 79 98 65 98 65 99 66 99 81 99 81 100 66 100 62 100 22 101 21 101 68 101 22 102 68 102 80 102 10 103 9 103 82 103 9 104 49 104 83 104 84 105 83 105 49 105 49 106 50 106 84 106 85 107 84 107 50 107 50 108 51 108 85 108 86 109 85 109 51 109 51 110 52 110 86 110 87 111 86 111 52 111 88 112 73 112 72 112 53 113 89 113 90 113 53 114 91 114 89 114 92 115 89 115 91 115 71 116 89 116 92 116 71 117 70 117 89 117 70 118 16 118 89 118 44 119 89 119 16 119 93 120 89 120 44 120 94 121 89 121 93 121 95 122 89 122 94 122 90 123 89 123 95 123 71 124 92 124 69 124 69 125 27 125 19 125 69 126 29 126 27 126 69 127 96 127 29 127 30 128 29 128 96 128 75 129 30 129 96 129 97 130 75 130 96 130 97 131 96 131 98 131 92 132 96 132 69 132 92 133 98 133 96 133 95 134 52 134 90 134 97 135 98 135 99 135 52 136 95 136 87 136 76 137 92 137 91 137 91 138 53 138 76 138 76 139 53 139 78 139 92 140 76 140 98 140 76 141 77 141 98 141 72 142 75 142 97 142 72 143 97 143 99 143 72 144 99 144 98 144 72 145 98 145 100 145 100 64 98 64 77 64 59 146 100 146 77 146 90 147 52 147 53 147 75 148 32 148 30 148 58 149 100 149 59 149 58 150 72 150 100 150 88 151 72 151 54 151 101 152 102 152 103 152 101 153 103 153 104 153 105 154 101 154 104 154 106 155 102 155 101 155 101 156 107 156 106 156 106 157 107 157 108 157 109 158 106 158 108 158 109 159 110 159 106 159 108 160 111 160 109 160 112 161 109 161 111 161 113 162 112 162 111 162 113 163 114 163 115 163 112 164 113 164 115 164 116 165 117 165 118 165 119 166 118 166 117 166 117 167 120 167 119 167 121 168 119 168 120 168 120 169 122 169 121 169 10 170 121 170 122 170 123 171 124 171 11 171 11 172 122 172 123 172 122 173 11 173 10 173 125 174 126 174 127 174 124 175 125 175 127 175 124 176 127 176 128 176 124 177 128 177 129 177 124 178 129 178 130 178 2 179 124 179 130 179 124 180 2 180 11 180 11 181 2 181 3 181 131 182 132 182 133 182 134 183 135 183 8 183 7 184 134 184 8 184 136 185 137 185 138 185 139 186 137 186 136 186 136 187 140 187 139 187 141 188 139 188 140 188 140 189 142 189 141 189 143 190 141 190 142 190 144 191 145 191 143 191 142 192 144 192 143 192 146 193 145 193 144 193 144 194 147 194 146 194 146 195 147 195 61 195 146 196 61 196 8 196 135 197 146 197 8 197 137 198 148 198 138 198 148 199 149 199 138 199 150 200 106 200 110 200 151 201 152 201 150 201 153 202 102 202 106 202 150 203 153 203 106 203 150 204 152 204 154 204 150 205 154 205 155 205 150 206 155 206 156 206 150 207 156 207 157 207 153 208 150 208 157 208 102 209 153 209 158 209 103 210 102 210 158 210 159 211 160 211 161 211 159 212 161 212 162 212 163 213 159 213 162 213 160 214 159 214 164 214 0 215 160 215 164 215 0 216 130 216 129 216 0 217 129 217 128 217 0 218 128 218 165 218 0 219 165 219 160 219 2 220 130 220 0 220 0 221 164 221 5 221 142 222 140 222 166 222 144 223 142 223 166 223 119 224 167 224 118 224 168 225 167 225 119 225 119 226 121 226 168 226 116 227 118 227 169 227 131 64 114 64 113 64 131 228 113 228 111 228 133 64 114 64 131 64 103 229 170 229 171 229 104 230 103 230 171 230 171 231 172 231 104 231 104 232 172 232 173 232 105 233 104 233 173 233 173 234 172 234 174 234 175 235 173 235 174 235 174 236 176 236 175 236 176 237 177 237 178 237 179 238 178 238 177 238 175 239 176 239 178 239 175 240 178 240 180 240 175 241 180 241 181 241 175 242 181 242 182 242 183 243 175 243 182 243 182 244 184 244 183 244 185 245 179 245 177 245 177 246 186 246 185 246 183 247 184 247 187 247 183 248 187 248 188 248 189 249 183 249 188 249 188 250 190 250 189 250 191 251 189 251 190 251 190 252 192 252 191 252 193 253 191 253 192 253 192 254 194 254 193 254 193 255 194 255 195 255 193 256 195 256 196 256 197 257 193 257 196 257 196 258 198 258 197 258 199 259 200 259 201 259 202 260 199 260 201 260 197 261 198 261 200 261 200 262 199 262 203 262 203 263 197 263 200 263 199 264 204 264 203 264 203 265 204 265 205 265 206 266 203 266 205 266 205 267 207 267 127 267 127 268 207 268 208 268 128 269 127 269 208 269 190 270 188 270 192 270 194 270 192 270 188 270 188 270 209 270 194 270 210 270 194 270 209 270 209 270 211 270 210 270 212 270 210 270 211 270 211 270 213 270 212 270 214 271 212 271 213 271 213 270 215 270 214 270 216 272 214 272 215 272 215 270 217 270 216 270 218 270 216 270 217 270 219 182 220 182 221 182 222 273 221 273 220 273 220 182 223 182 222 182 224 182 222 182 223 182 223 182 225 182 224 182 224 182 225 182 226 182 227 182 224 182 226 182 226 274 228 274 227 274 229 182 227 182 228 182 200 275 230 275 201 275 231 276 201 276 230 276 230 277 232 277 231 277 233 278 231 278 232 278 232 279 234 279 233 279 235 280 233 280 234 280 234 281 236 281 235 281 237 282 235 282 236 282 236 283 238 283 237 283 239 284 237 284 238 284 238 285 240 285 239 285 241 286 239 286 240 286 240 287 242 287 241 287 243 288 241 288 242 288 242 289 244 289 243 289 245 290 243 290 244 290 178 291 246 291 180 291 247 292 180 292 246 292 246 293 248 293 247 293 249 293 247 293 248 293 248 294 250 294 249 294 251 295 249 295 250 295 250 296 252 296 251 296 253 297 251 297 252 297 252 298 254 298 253 298 255 299 253 299 254 299 254 300 256 300 255 300 257 301 255 301 256 301 256 302 258 302 257 302 259 302 257 302 258 302 258 303 260 303 259 303 261 304 259 304 260 304 247 305 181 305 180 305 249 306 184 306 182 306 249 307 182 307 181 307 247 308 249 308 181 308 249 309 251 309 184 309 262 310 188 310 187 310 262 311 187 311 184 311 184 312 251 312 253 312 262 313 184 313 253 313 209 314 188 314 262 314 253 315 255 315 262 315 262 316 255 316 257 316 263 317 262 317 257 317 263 318 211 318 209 318 262 319 263 319 209 319 213 320 211 320 263 320 257 321 259 321 263 321 264 322 215 322 213 322 263 323 264 323 213 323 263 324 259 324 261 324 263 325 261 325 265 325 264 326 263 326 265 326 215 327 264 327 266 327 217 328 215 328 266 328 200 329 198 329 230 329 232 330 230 330 198 330 198 331 196 331 232 331 232 332 196 332 267 332 234 333 232 333 267 333 268 334 236 334 234 334 267 335 268 335 234 335 195 336 194 336 268 336 268 337 267 337 195 337 194 338 210 338 268 338 238 339 236 339 268 339 268 340 210 340 212 340 269 341 268 341 212 341 269 342 240 342 238 342 268 343 269 343 238 343 212 344 214 344 269 344 242 345 240 345 269 345 269 346 214 346 216 346 216 347 218 347 269 347 269 348 218 348 270 348 271 349 269 349 270 349 269 350 271 350 242 350 242 351 271 351 272 351 244 352 242 352 272 352 178 353 273 353 246 353 248 354 246 354 273 354 273 355 274 355 248 355 250 356 248 356 274 356 274 357 275 357 250 357 252 358 250 358 275 358 276 359 254 359 252 359 275 360 276 360 252 360 277 361 221 361 276 361 278 362 277 362 276 362 279 363 278 363 276 363 276 364 275 364 279 364 221 365 222 365 276 365 256 366 254 366 276 366 276 367 222 367 224 367 276 368 224 368 227 368 276 369 227 369 229 369 276 370 229 370 280 370 281 371 276 371 280 371 281 372 258 372 256 372 276 373 281 373 256 373 258 374 281 374 282 374 260 375 258 375 282 375 103 376 158 376 170 376 283 377 170 377 158 377 158 378 153 378 283 378 284 379 283 379 153 379 153 380 157 380 284 380 285 380 284 380 157 380 157 381 156 381 285 381 286 382 285 382 156 382 156 383 155 383 286 383 287 384 286 384 155 384 208 385 288 385 128 385 165 386 128 386 288 386 288 387 289 387 165 387 160 388 165 388 289 388 289 389 290 389 160 389 161 390 160 390 290 390 290 391 291 391 161 391 162 392 161 392 291 392 291 393 292 393 162 393 163 394 162 394 292 394 199 395 293 395 204 395 288 396 208 396 207 396 294 397 205 397 204 397 205 398 294 398 207 398 207 399 295 399 288 399 295 400 207 400 294 400 204 401 296 401 294 401 296 402 204 402 293 402 297 403 294 403 296 403 294 404 297 404 295 404 289 405 288 405 295 405 295 406 298 406 289 406 298 407 295 407 297 407 293 408 299 408 296 408 300 409 297 409 296 409 297 410 300 410 298 410 290 411 289 411 298 411 301 412 298 412 300 412 298 413 301 413 290 413 299 414 302 414 296 414 296 415 303 415 300 415 303 416 296 416 302 416 291 417 290 417 301 417 300 418 304 418 301 418 304 419 300 419 303 419 305 420 303 420 302 420 303 421 305 421 304 421 292 422 291 422 301 422 304 423 306 423 301 423 301 424 306 424 292 424 307 425 308 425 309 425 310 426 177 426 176 426 310 427 176 427 311 427 309 428 310 428 311 428 310 429 309 429 308 429 186 430 177 430 310 430 308 431 312 431 310 431 313 432 310 432 312 432 313 433 314 433 315 433 315 434 186 434 310 434 316 435 313 435 312 435 312 436 317 436 316 436 318 437 319 437 316 437 317 438 318 438 316 438 320 439 319 439 318 439 318 440 321 440 320 440 320 441 293 441 202 441 320 442 321 442 302 442 320 443 302 443 299 443 293 444 320 444 299 444 199 445 202 445 293 445 170 446 283 446 171 446 322 447 171 447 283 447 171 448 322 448 172 448 311 449 176 449 174 449 174 450 323 450 311 450 323 451 174 451 172 451 172 452 324 452 323 452 324 453 172 453 322 453 322 454 325 454 324 454 325 455 322 455 283 455 283 456 284 456 325 456 309 457 311 457 323 457 323 458 326 458 309 458 326 459 323 459 324 459 327 460 324 460 325 460 324 461 327 461 326 461 328 462 325 462 284 462 325 463 328 463 327 463 284 464 285 464 328 464 307 465 309 465 326 465 329 466 326 466 327 466 326 467 329 467 307 467 330 468 327 468 328 468 327 469 330 469 329 469 331 470 328 470 285 470 328 471 331 471 330 471 332 472 307 472 329 472 332 473 329 473 330 473 285 474 286 474 331 474 333 475 330 475 331 475 330 476 333 476 332 476 286 477 287 477 331 477 334 478 331 478 287 478 331 479 334 479 333 479 335 480 315 480 314 480 336 481 315 481 335 481 335 482 337 482 336 482 338 483 336 483 337 483 337 484 339 484 338 484 338 485 339 485 219 485 338 486 219 486 221 486 173 182 175 182 183 182 173 182 183 182 189 182 173 182 189 182 191 182 173 182 191 182 193 182 173 487 193 487 197 487 173 488 197 488 203 488 206 182 173 182 203 182 206 489 125 489 124 489 206 490 124 490 123 490 206 491 123 491 122 491 206 492 122 492 120 492 206 493 120 493 117 493 206 494 117 494 116 494 116 495 169 495 132 495 206 496 116 496 132 496 206 497 132 497 131 497 206 498 131 498 111 498 206 499 111 499 108 499 206 500 108 500 107 500 206 501 107 501 101 501 206 502 101 502 105 502 173 503 206 503 105 503 126 495 125 495 206 495 196 270 195 270 267 270 314 504 313 504 316 504 316 505 319 505 314 505 310 506 313 506 315 506 221 507 277 507 338 507 315 508 336 508 338 508 277 509 315 509 338 509 277 510 278 510 315 510 278 511 279 511 315 511 186 512 315 512 279 512 186 513 279 513 275 513 186 514 275 514 274 514 185 515 186 515 274 515 185 516 274 516 273 516 179 517 185 517 273 517 178 518 179 518 273 518 201 519 340 519 341 519 341 520 340 520 342 520 342 521 340 521 343 521 342 522 343 522 344 522 344 523 343 523 345 523 344 524 345 524 346 524 344 525 346 525 347 525 348 526 347 526 346 526 349 527 347 527 348 527 349 528 350 528 347 528 347 529 350 529 351 529 352 530 350 530 349 530 320 531 347 531 319 531 350 532 352 532 219 532 350 533 219 533 339 533 337 534 350 534 339 534 350 535 337 535 351 535 335 536 351 536 337 536 351 537 335 537 347 537 335 538 314 538 347 538 347 539 320 539 344 539 319 540 347 540 314 540 344 541 320 541 202 541 245 542 353 542 243 542 243 543 353 543 354 543 355 544 241 544 354 544 354 545 241 545 243 545 354 546 356 546 355 546 355 547 356 547 228 547 355 548 228 548 226 548 355 549 226 549 357 549 355 550 357 550 358 550 241 551 355 551 239 551 352 552 355 552 358 552 355 553 346 553 345 553 346 554 355 554 348 554 348 555 355 555 349 555 349 556 355 556 352 556 345 557 237 557 355 557 355 558 237 558 239 558 237 559 345 559 235 559 343 560 235 560 345 560 235 561 343 561 233 561 340 562 233 562 343 562 233 563 340 563 231 563 201 564 231 564 340 564 223 182 357 182 225 182 357 182 223 182 358 182 220 182 358 182 223 182 358 182 220 182 352 182 219 182 352 182 220 182 202 565 342 565 344 565 342 566 202 566 341 566 341 567 202 567 201 567 225 182 357 182 226 182 127 568 206 568 205 568 126 569 206 569 127 569 169 182 167 182 132 182 169 570 118 570 167 570 359 270 218 270 360 270 361 270 359 270 360 270 362 270 363 270 360 270 364 270 365 270 361 270 360 571 366 571 362 571 367 572 361 572 365 572 368 573 362 573 366 573 365 574 369 574 367 574 366 575 370 575 368 575 371 576 367 576 369 576 372 270 368 270 370 270 369 270 373 270 371 270 374 270 371 270 373 270 370 270 375 270 372 270 373 270 376 270 374 270 377 577 372 577 375 577 374 578 376 578 378 578 379 270 374 270 378 270 380 270 381 270 377 270 375 270 380 270 377 270 382 270 381 270 380 270 378 270 382 270 379 270 383 270 379 270 382 270 384 270 383 270 382 270 380 579 384 579 382 579 385 580 245 580 386 580 387 581 388 581 261 581 389 582 366 582 266 582 390 583 389 583 264 583 390 584 261 584 388 584 391 585 390 585 388 585 361 270 218 270 359 270 218 586 361 586 392 586 392 587 393 587 270 587 393 588 394 588 271 588 394 589 386 589 272 589 385 590 395 590 245 590 395 591 396 591 354 591 396 592 397 592 356 592 398 593 399 593 229 593 399 594 400 594 281 594 400 595 387 595 282 595 401 596 376 596 373 596 378 597 376 597 401 597 382 598 378 598 401 598 381 599 382 599 401 599 377 600 381 600 401 600 372 270 377 270 401 270 401 601 368 601 372 601 362 602 368 602 401 602 363 270 362 270 401 270 364 270 363 270 401 270 365 603 364 603 401 603 369 604 365 604 401 604 373 270 369 270 401 270 402 605 366 605 389 605 389 606 390 606 402 606 403 607 402 607 390 607 390 608 391 608 403 608 392 609 404 609 393 609 394 610 393 610 404 610 404 611 405 611 394 611 394 612 405 612 386 612 406 613 370 613 366 613 402 614 406 614 366 614 403 615 391 615 406 615 402 616 403 616 406 616 391 617 407 617 406 617 375 618 370 618 406 618 408 619 406 619 407 619 408 620 380 620 375 620 406 621 408 621 375 621 407 622 409 622 408 622 384 623 380 623 408 623 408 624 409 624 410 624 411 625 408 625 410 625 408 626 411 626 384 626 383 627 384 627 411 627 410 628 412 628 411 628 413 629 411 629 412 629 411 630 413 630 383 630 379 631 383 631 413 631 412 632 414 632 413 632 415 633 374 633 379 633 413 634 415 634 379 634 415 635 413 635 414 635 371 636 374 636 415 636 414 637 386 637 415 637 404 638 367 638 371 638 415 639 404 639 371 639 415 640 386 640 405 640 415 641 405 641 404 641 392 642 367 642 404 642 367 643 392 643 361 643 229 182 397 182 398 182 398 182 416 182 417 182 397 182 416 182 398 182 391 644 388 644 387 644 386 645 414 645 418 645 418 646 385 646 386 646 409 647 407 647 419 647 419 648 420 648 409 648 410 649 409 649 420 649 420 650 421 650 410 650 421 651 422 651 412 651 412 652 410 652 421 652 422 653 418 653 414 653 414 654 412 654 422 654 407 655 391 655 387 655 387 656 419 656 407 656 400 657 419 657 387 657 399 658 419 658 400 658 417 659 420 659 419 659 417 660 421 660 420 660 417 661 416 661 421 661 416 662 422 662 421 662 418 663 422 663 416 663 395 664 385 664 418 664 395 665 418 665 396 665 360 666 364 666 361 666 360 270 363 270 364 270 360 667 266 667 366 667 399 668 417 668 419 668 398 669 417 669 399 669 397 670 396 670 416 670 396 671 418 671 416 671 112 672 423 672 110 672 109 673 112 673 110 673 424 182 133 182 132 182 425 674 136 674 138 674 149 675 426 675 138 675 150 676 110 676 423 676 150 677 427 677 151 677 136 678 425 678 428 678 428 679 429 679 136 679 115 680 114 680 133 680 244 681 386 681 245 681 228 182 397 182 229 182 260 581 387 581 261 581 266 682 264 682 389 682 264 683 265 683 390 683 390 684 265 684 261 684 270 685 218 685 392 685 271 686 270 686 393 686 272 687 271 687 394 687 244 688 272 688 386 688 395 689 353 689 245 689 354 690 353 690 395 690 356 691 354 691 396 691 228 692 356 692 397 692 399 693 280 693 229 693 281 694 280 694 399 694 282 695 281 695 400 695 260 696 282 696 387 696 360 270 218 270 217 270 217 697 266 697 360 697 430 698 431 698 432 698 138 699 433 699 434 699 425 700 138 700 434 700 435 701 436 701 437 701 435 702 438 702 436 702 439 703 440 703 441 703 441 704 440 704 442 704 442 705 440 705 443 705 443 706 440 706 444 706 444 707 440 707 445 707 445 708 440 708 446 708 443 709 447 709 442 709 448 710 449 710 447 710 447 711 449 711 450 711 436 712 450 712 449 712 451 713 450 713 436 713 452 714 451 714 436 714 451 715 453 715 450 715 442 716 447 716 450 716 442 717 450 717 453 717 454 718 455 718 456 718 445 719 455 719 454 719 436 720 438 720 452 720 424 721 115 721 133 721 457 722 115 722 424 722 458 723 457 723 424 723 459 724 458 724 424 724 424 725 446 725 459 725 440 726 459 726 446 726 455 727 445 727 446 727 460 728 461 728 462 728 432 729 461 729 460 729 460 730 463 730 432 730 464 731 432 731 463 731 463 732 465 732 464 732 465 733 434 733 464 733 465 734 466 734 434 734 425 735 434 735 466 735 467 736 425 736 466 736 468 737 469 737 470 737 469 738 471 738 470 738 472 739 468 739 470 739 470 740 473 740 472 740 474 741 472 741 473 741 473 742 475 742 474 742 476 743 474 743 475 743 475 744 477 744 476 744 478 745 476 745 477 745 477 746 479 746 478 746 480 747 478 747 479 747 479 748 462 748 480 748 480 749 462 749 461 749 428 750 425 750 467 750 481 751 482 751 483 751 482 752 481 752 484 752 485 753 486 753 482 753 487 754 488 754 489 754 490 755 489 755 488 755 490 756 437 756 489 756 490 757 491 757 437 757 490 758 492 758 491 758 490 759 493 759 492 759 494 760 493 760 490 760 495 761 490 761 496 761 490 762 488 762 496 762 490 763 495 763 494 763 495 764 497 764 494 764 496 765 498 765 495 765 499 766 497 766 495 766 495 767 482 767 499 767 482 768 500 768 499 768 482 769 486 769 500 769 495 770 483 770 482 770 495 771 498 771 483 771 489 772 448 772 487 772 449 773 448 773 489 773 436 774 449 774 489 774 489 775 437 775 436 775 437 776 491 776 501 776 501 777 435 777 437 777 502 778 439 778 441 778 503 779 441 779 442 779 441 780 503 780 502 780 442 781 453 781 503 781 503 782 504 782 502 782 502 783 504 783 505 783 427 784 506 784 151 784 427 785 150 785 423 785 427 786 439 786 502 786 427 787 507 787 439 787 427 788 423 788 507 788 427 789 502 789 506 789 502 790 505 790 506 790 508 791 509 791 510 791 511 792 510 792 509 792 511 793 451 793 452 793 511 794 509 794 451 794 452 795 512 795 511 795 452 796 513 796 512 796 452 797 514 797 513 797 515 798 514 798 438 798 514 799 452 799 438 799 438 800 435 800 515 800 516 801 515 801 435 801 435 802 501 802 516 802 491 803 516 803 501 803 448 804 447 804 444 804 443 805 444 805 447 805 517 806 518 806 483 806 483 807 498 807 517 807 498 808 456 808 517 808 498 809 454 809 456 809 445 810 454 810 488 810 454 811 496 811 488 811 454 812 498 812 496 812 445 813 488 813 444 813 488 814 487 814 444 814 448 815 444 815 487 815 519 816 477 816 475 816 519 817 479 817 477 817 462 270 479 270 519 270 519 818 460 818 462 818 519 819 463 819 460 819 519 270 465 270 463 270 519 820 466 820 465 820 519 821 467 821 466 821 481 822 483 822 518 822 432 823 431 823 461 823 433 824 432 824 464 824 464 825 434 825 433 825 432 826 433 826 430 826 433 827 520 827 430 827 521 828 520 828 433 828 521 829 433 829 138 829 426 830 521 830 138 830 509 831 504 831 451 831 505 832 504 832 509 832 509 581 508 581 505 581 446 833 424 833 132 833 439 834 459 834 440 834 459 835 439 835 507 835 459 836 507 836 458 836 507 837 457 837 458 837 112 838 457 838 507 838 457 839 112 839 115 839 507 840 423 840 112 840 461 841 431 841 480 841 513 842 514 842 522 842 431 843 522 843 514 843 514 844 515 844 431 844 515 845 480 845 431 845 478 846 480 846 491 846 480 847 516 847 491 847 480 848 515 848 516 848 491 849 492 849 478 849 476 850 478 850 492 850 492 851 493 851 476 851 474 852 476 852 494 852 476 853 493 853 494 853 494 854 497 854 474 854 472 855 474 855 497 855 497 856 499 856 472 856 468 857 472 857 500 857 472 858 499 858 500 858 500 859 486 859 468 859 469 860 468 860 486 860 523 861 446 861 132 861 446 862 523 862 455 862 83 863 82 863 9 863 82 864 524 864 10 864 525 865 61 865 526 865 62 866 61 866 525 866 525 867 527 867 62 867 527 868 81 868 62 868 147 869 526 869 61 869 147 870 528 870 526 870 22 270 80 270 519 270 519 871 525 871 526 871 519 872 527 872 525 872 519 873 81 873 527 873 519 874 79 874 81 874 519 875 80 875 79 875 526 876 528 876 519 876 528 877 529 877 519 877 166 878 519 878 529 878 455 879 87 879 95 879 455 880 86 880 87 880 455 881 85 881 86 881 455 882 84 882 85 882 455 883 83 883 84 883 455 884 82 884 83 884 455 885 524 885 82 885 455 886 168 886 524 886 530 887 531 887 34 887 46 888 530 888 34 888 532 889 533 889 531 889 530 890 532 890 531 890 534 891 533 891 532 891 535 892 536 892 534 892 532 893 535 893 534 893 535 894 537 894 536 894 455 895 95 895 94 895 455 896 94 896 93 896 538 897 539 897 540 897 540 898 541 898 538 898 538 899 541 899 484 899 542 900 538 900 484 900 543 901 45 901 36 901 36 902 544 902 543 902 544 903 540 903 543 903 539 904 543 904 540 904 545 905 533 905 534 905 546 906 545 906 534 906 546 907 541 907 540 907 546 908 540 908 545 908 534 909 536 909 546 909 546 910 536 910 547 910 546 911 485 911 541 911 545 912 544 912 36 912 35 913 545 913 36 913 35 914 34 914 531 914 35 915 531 915 533 915 35 916 533 916 545 916 544 917 545 917 540 917 537 918 535 918 548 918 530 919 549 919 550 919 532 920 530 920 550 920 530 921 46 921 549 921 551 922 549 922 46 922 46 923 26 923 551 923 25 924 551 924 26 924 93 925 44 925 455 925 455 926 44 926 45 926 535 927 552 927 548 927 532 928 552 928 535 928 532 929 550 929 552 929 519 930 25 930 23 930 519 931 23 931 22 931 140 932 136 932 429 932 429 933 166 933 140 933 166 934 529 934 144 934 147 935 144 935 529 935 529 936 528 936 147 936 524 937 168 937 121 937 121 938 10 938 524 938 548 939 553 939 537 939 469 940 537 940 553 940 471 941 469 941 553 941 485 942 482 942 484 942 485 943 554 943 486 943 485 944 547 944 554 944 485 945 484 945 541 945 485 946 546 946 547 946 428 270 467 270 519 270 429 270 428 270 519 270 519 947 166 947 429 947 518 948 555 948 481 948 484 949 481 949 555 949 555 950 542 950 484 950 554 951 469 951 486 951 537 952 469 952 547 952 469 953 554 953 547 953 537 954 547 954 536 954 523 182 132 182 167 182 523 955 167 955 168 955 523 956 168 956 455 956 556 957 557 957 558 957 557 958 559 958 558 958 557 959 556 959 560 959 561 960 562 960 563 960 564 961 565 961 566 961 567 962 568 962 569 962 567 963 570 963 568 963 571 964 572 964 573 964 574 965 572 965 571 965 575 966 576 966 577 966 577 967 578 967 575 967 579 968 575 968 578 968 578 969 580 969 579 969 581 970 579 970 580 970 582 971 572 971 574 971 582 972 583 972 572 972 583 973 573 973 572 973 569 974 583 974 582 974 582 975 584 975 569 975 584 976 585 976 569 976 586 977 569 977 585 977 585 978 587 978 586 978 588 979 589 979 590 979 591 980 592 980 590 980 568 981 590 981 593 981 590 982 592 982 593 982 590 983 568 983 588 983 568 984 594 984 588 984 570 985 594 985 568 985 593 986 595 986 568 986 568 987 583 987 569 987 573 988 583 988 568 988 568 989 596 989 573 989 568 990 595 990 596 990 569 991 597 991 567 991 597 992 569 992 586 992 587 993 598 993 586 993 599 994 591 994 600 994 599 995 592 995 591 995 599 996 593 996 592 996 599 997 595 997 593 997 599 998 596 998 595 998 599 999 573 999 596 999 573 1000 599 1000 571 1000 589 1001 588 1001 601 1001 581 1002 601 1002 588 1002 588 1003 594 1003 581 1003 579 1004 581 1004 570 1004 581 1005 594 1005 570 1005 570 1006 567 1006 579 1006 575 1007 579 1007 597 1007 579 1008 567 1008 597 1008 597 1009 586 1009 575 1009 576 1010 575 1010 586 1010 586 1011 598 1011 576 1011 598 1012 602 1012 603 1012 576 1013 598 1013 603 1013 559 1014 604 1014 564 1014 566 1015 559 1015 564 1015 605 1016 604 1016 559 1016 606 1017 605 1017 559 1017 607 1018 606 1018 559 1018 607 1019 559 1019 608 1019 609 64 610 64 611 64 609 64 611 64 612 64 609 1020 612 1020 560 1020 609 1021 613 1021 610 1021 614 1022 610 1022 613 1022 615 1023 561 1023 563 1023 615 1024 563 1024 616 1024 615 1025 616 1025 617 1025 618 1026 615 1026 617 1026 619 1027 615 1027 618 1027 618 1028 620 1028 619 1028 618 1029 617 1029 621 1029 620 1030 618 1030 621 1030 622 1031 619 1031 620 1031 603 1032 622 1032 620 1032 620 1033 623 1033 603 1033 603 1034 623 1034 576 1034 624 1035 574 1035 571 1035 571 1036 625 1036 624 1036 625 1037 626 1037 624 1037 613 1038 609 1038 627 1038 627 1039 628 1039 629 1039 627 1040 629 1040 602 1040 630 1041 627 1041 602 1041 598 1042 587 1042 630 1042 602 1043 598 1043 630 1043 631 1044 632 1044 614 1044 633 1045 614 1045 632 1045 560 1046 612 1046 557 1046 557 1047 633 1047 559 1047 557 1048 612 1048 611 1048 557 1049 611 1049 610 1049 557 1050 610 1050 633 1050 614 1051 633 1051 610 1051 559 1052 633 1052 608 1052 620 1053 634 1053 635 1053 620 1054 635 1054 623 1054 636 1055 634 1055 620 1055 620 1056 621 1056 636 1056 636 1057 621 1057 617 1057 577 1058 576 1058 623 1058 577 1059 623 1059 635 1059 565 1060 564 1060 637 1060 564 1061 604 1061 638 1061 639 1062 638 1062 604 1062 604 1063 605 1063 639 1063 640 1064 639 1064 605 1064 605 1065 606 1065 640 1065 641 1066 640 1066 606 1066 606 1067 607 1067 641 1067 642 1068 641 1068 607 1068 643 1069 628 1069 627 1069 608 1070 644 1070 645 1070 608 1071 646 1071 644 1071 647 1072 644 1072 646 1072 626 1073 644 1073 647 1073 626 1074 625 1074 644 1074 625 1075 571 1075 644 1075 599 1076 644 1076 571 1076 648 120 644 120 599 120 649 1077 644 1077 648 1077 650 1078 644 1078 649 1078 645 1079 644 1079 650 1079 626 1080 647 1080 624 1080 624 1081 582 1081 574 1081 624 1082 584 1082 582 1082 624 1083 651 1083 584 1083 585 1084 584 1084 651 1084 630 1085 585 1085 651 1085 652 1086 630 1086 651 1086 652 1087 651 1087 653 1087 647 1088 651 1088 624 1088 647 1089 653 1089 651 1089 650 1090 607 1090 645 1090 607 1091 650 1091 642 1091 632 1092 647 1092 646 1092 646 1093 608 1093 632 1093 632 1094 608 1094 633 1094 647 1095 632 1095 653 1095 632 1096 631 1096 653 1096 627 1097 630 1097 652 1097 627 1098 652 1098 653 1098 627 1099 653 1099 654 1099 654 1100 653 1100 631 1100 654 1101 631 1101 614 1101 645 1102 607 1102 608 1102 630 1103 587 1103 585 1103 613 1104 654 1104 614 1104 613 1105 627 1105 654 1105 643 1106 627 1106 609 1106 655 1107 656 1107 657 1107 655 1108 657 1108 658 1108 659 1109 655 1109 658 1109 660 1110 656 1110 655 1110 655 1111 661 1111 660 1111 660 1112 661 1112 662 1112 663 1113 660 1113 662 1113 663 1114 664 1114 660 1114 662 1115 665 1115 663 1115 666 1116 663 1116 665 1116 667 1117 666 1117 665 1117 667 1118 668 1118 669 1118 666 1119 667 1119 669 1119 670 1120 671 1120 672 1120 673 1121 672 1121 671 1121 671 1122 674 1122 673 1122 675 1123 673 1123 674 1123 674 1124 676 1124 675 1124 565 1125 675 1125 676 1125 677 1126 678 1126 566 1126 566 1127 676 1127 677 1127 676 1128 566 1128 565 1128 679 1129 680 1129 681 1129 678 1130 679 1130 681 1130 678 1131 681 1131 682 1131 678 1132 682 1132 683 1132 678 1133 683 1133 684 1133 558 1134 678 1134 684 1134 678 1135 558 1135 566 1135 566 1136 558 1136 559 1136 685 182 686 182 687 182 688 1137 689 1137 563 1137 562 1138 688 1138 563 1138 690 1139 691 1139 692 1139 693 1140 691 1140 690 1140 690 1141 694 1141 693 1141 695 1142 693 1142 694 1142 694 1143 696 1143 695 1143 697 1144 695 1144 696 1144 698 1145 699 1145 697 1145 696 1146 698 1146 697 1146 700 1147 699 1147 698 1147 698 1148 701 1148 700 1148 700 1149 701 1149 616 1149 700 1150 616 1150 563 1150 689 1151 700 1151 563 1151 691 1152 702 1152 692 1152 702 1153 703 1153 692 1153 704 1154 660 1154 664 1154 705 1155 706 1155 704 1155 707 1156 656 1156 660 1156 704 1157 707 1157 660 1157 704 1158 706 1158 708 1158 704 1159 708 1159 709 1159 704 1160 709 1160 710 1160 704 1161 710 1161 711 1161 707 1162 704 1162 711 1162 656 1163 707 1163 712 1163 656 1164 712 1164 713 1164 657 1165 656 1165 713 1165 714 1166 715 1166 716 1166 714 1167 716 1167 717 1167 718 1168 714 1168 717 1168 715 1169 714 1169 719 1169 556 1170 715 1170 719 1170 556 1171 684 1171 683 1171 556 1172 683 1172 682 1172 556 1173 682 1173 720 1173 556 1174 720 1174 715 1174 558 1175 684 1175 556 1175 556 1176 719 1176 560 1176 696 1177 694 1177 721 1177 698 1178 696 1178 721 1178 673 1179 722 1179 672 1179 723 1180 722 1180 673 1180 673 1181 675 1181 723 1181 670 1182 672 1182 724 1182 685 64 668 64 667 64 685 228 667 228 665 228 687 64 668 64 685 64 657 1183 725 1183 726 1183 658 1184 657 1184 726 1184 726 1185 727 1185 658 1185 658 1186 727 1186 728 1186 659 1187 658 1187 728 1187 728 1188 727 1188 729 1188 730 1189 728 1189 729 1189 729 1190 731 1190 730 1190 731 1191 732 1191 733 1191 734 1192 733 1192 732 1192 730 1193 731 1193 733 1193 730 240 733 240 735 240 730 1194 735 1194 736 1194 730 1195 736 1195 737 1195 738 1196 730 1196 737 1196 737 1197 739 1197 738 1197 740 245 734 245 732 245 732 1198 741 1198 740 1198 738 1199 739 1199 742 1199 738 1200 742 1200 743 1200 744 1201 738 1201 743 1201 743 1202 745 1202 744 1202 746 1203 744 1203 745 1203 745 1204 747 1204 746 1204 748 1205 746 1205 747 1205 747 1206 749 1206 748 1206 748 1207 749 1207 750 1207 748 1208 750 1208 751 1208 752 1209 748 1209 751 1209 751 1210 753 1210 752 1210 754 1211 755 1211 756 1211 757 1212 754 1212 756 1212 752 1213 753 1213 755 1213 755 1214 754 1214 758 1214 758 1215 752 1215 755 1215 754 1216 759 1216 758 1216 758 1217 759 1217 760 1217 761 1218 758 1218 760 1218 760 1219 762 1219 681 1219 681 1220 762 1220 763 1220 682 1221 681 1221 763 1221 745 270 743 270 747 270 749 270 747 270 743 270 743 270 764 270 749 270 765 1222 749 1222 764 1222 764 1223 766 1223 765 1223 767 270 765 270 766 270 766 270 768 270 767 270 769 271 767 271 768 271 768 270 770 270 769 270 771 1224 769 1224 770 1224 770 270 772 270 771 270 773 270 771 270 772 270 774 182 775 182 776 182 777 1225 776 1225 775 1225 775 182 778 182 777 182 779 182 777 182 778 182 778 182 780 182 779 182 779 182 780 182 781 182 782 182 779 182 781 182 781 1226 783 1226 782 1226 784 182 782 182 783 182 755 1227 785 1227 756 1227 786 1228 756 1228 785 1228 785 1229 787 1229 786 1229 788 1230 786 1230 787 1230 787 1231 789 1231 788 1231 790 1232 788 1232 789 1232 789 1233 791 1233 790 1233 792 1234 790 1234 791 1234 791 1235 793 1235 792 1235 794 1236 792 1236 793 1236 793 1237 795 1237 794 1237 796 1238 794 1238 795 1238 795 1239 797 1239 796 1239 798 1240 796 1240 797 1240 797 1241 799 1241 798 1241 800 1242 798 1242 799 1242 733 291 801 291 735 291 802 292 735 292 801 292 801 1243 803 1243 802 1243 804 1244 802 1244 803 1244 803 1245 805 1245 804 1245 806 1246 804 1246 805 1246 805 1247 807 1247 806 1247 808 1248 806 1248 807 1248 807 298 809 298 808 298 810 1249 808 1249 809 1249 809 300 811 300 810 300 812 301 810 301 811 301 811 1250 813 1250 812 1250 814 1250 812 1250 813 1250 813 1251 815 1251 814 1251 816 1252 814 1252 815 1252 802 1253 736 1253 735 1253 804 1254 739 1254 737 1254 804 1255 737 1255 736 1255 802 1256 804 1256 736 1256 804 1257 806 1257 739 1257 817 1258 743 1258 742 1258 817 1259 742 1259 739 1259 739 1260 806 1260 808 1260 817 1261 739 1261 808 1261 764 1262 743 1262 817 1262 808 1263 810 1263 817 1263 817 1264 810 1264 812 1264 818 1265 817 1265 812 1265 818 1266 766 1266 764 1266 817 1267 818 1267 764 1267 768 1268 766 1268 818 1268 812 1269 814 1269 818 1269 819 1270 770 1270 768 1270 818 1271 819 1271 768 1271 818 1272 814 1272 816 1272 818 1273 816 1273 820 1273 819 1274 818 1274 820 1274 770 1275 819 1275 821 1275 772 1276 770 1276 821 1276 755 329 753 329 785 329 787 1277 785 1277 753 1277 753 1278 751 1278 787 1278 787 1279 751 1279 822 1279 789 1280 787 1280 822 1280 823 1281 791 1281 789 1281 822 1282 823 1282 789 1282 750 1283 749 1283 823 1283 823 1284 822 1284 750 1284 749 1285 765 1285 823 1285 793 1286 791 1286 823 1286 823 1287 765 1287 767 1287 824 1288 823 1288 767 1288 824 1289 795 1289 793 1289 823 1290 824 1290 793 1290 767 1291 769 1291 824 1291 797 1292 795 1292 824 1292 824 346 769 346 771 346 771 1293 773 1293 824 1293 824 1294 773 1294 825 1294 826 1295 824 1295 825 1295 824 1296 826 1296 797 1296 797 351 826 351 827 351 799 1297 797 1297 827 1297 733 1298 828 1298 801 1298 803 1299 801 1299 828 1299 828 1300 829 1300 803 1300 805 356 803 356 829 356 829 1301 830 1301 805 1301 807 1302 805 1302 830 1302 831 1303 809 1303 807 1303 830 1304 831 1304 807 1304 832 1305 776 1305 831 1305 833 1306 832 1306 831 1306 834 1307 833 1307 831 1307 831 1308 830 1308 834 1308 776 1309 777 1309 831 1309 811 1310 809 1310 831 1310 831 1311 777 1311 779 1311 831 1312 779 1312 782 1312 831 1313 782 1313 784 1313 831 1314 784 1314 835 1314 836 1315 831 1315 835 1315 836 1316 813 1316 811 1316 831 1317 836 1317 811 1317 813 1318 836 1318 837 1318 815 1319 813 1319 837 1319 657 1320 713 1320 725 1320 838 1321 725 1321 713 1321 713 1322 712 1322 838 1322 839 1323 838 1323 712 1323 712 1324 711 1324 839 1324 840 1325 839 1325 711 1325 711 1326 710 1326 840 1326 841 1327 840 1327 710 1327 710 1328 709 1328 841 1328 842 1329 841 1329 709 1329 763 1330 843 1330 682 1330 720 1331 682 1331 843 1331 843 1332 844 1332 720 1332 715 1333 720 1333 844 1333 844 1334 845 1334 715 1334 716 1335 715 1335 845 1335 845 1336 846 1336 716 1336 717 1337 716 1337 846 1337 846 1338 847 1338 717 1338 718 1339 717 1339 847 1339 754 1340 848 1340 759 1340 843 1341 763 1341 762 1341 849 1342 760 1342 759 1342 760 1343 849 1343 762 1343 762 1344 850 1344 843 1344 850 1345 762 1345 849 1345 759 1346 851 1346 849 1346 851 1347 759 1347 848 1347 852 1348 849 1348 851 1348 849 1349 852 1349 850 1349 844 1350 843 1350 850 1350 850 1351 853 1351 844 1351 853 1352 850 1352 852 1352 848 1353 854 1353 851 1353 855 1354 852 1354 851 1354 852 1355 855 1355 853 1355 845 1356 844 1356 853 1356 856 1357 853 1357 855 1357 853 1358 856 1358 845 1358 854 1359 857 1359 851 1359 851 1360 858 1360 855 1360 858 1361 851 1361 857 1361 857 1362 859 1362 858 1362 846 1363 845 1363 856 1363 855 1364 860 1364 856 1364 860 1365 855 1365 858 1365 861 1366 858 1366 859 1366 858 1367 861 1367 860 1367 847 1368 846 1368 856 1368 860 1369 862 1369 856 1369 856 1370 862 1370 847 1370 863 1371 864 1371 865 1371 866 1372 732 1372 731 1372 866 1373 731 1373 867 1373 865 1374 866 1374 867 1374 866 1375 865 1375 864 1375 741 1376 732 1376 866 1376 864 1377 868 1377 866 1377 869 1378 866 1378 868 1378 869 1379 870 1379 871 1379 871 434 741 434 866 434 872 1380 869 1380 868 1380 868 1381 873 1381 872 1381 874 1382 875 1382 872 1382 873 1383 874 1383 872 1383 876 1384 875 1384 874 1384 874 1385 877 1385 876 1385 876 1386 848 1386 757 1386 876 1387 877 1387 857 1387 876 1388 857 1388 854 1388 848 1389 876 1389 854 1389 754 1390 757 1390 848 1390 725 1391 838 1391 726 1391 878 1392 726 1392 838 1392 726 1393 878 1393 727 1393 867 1394 731 1394 729 1394 729 1395 879 1395 867 1395 879 1396 729 1396 727 1396 727 1397 880 1397 879 1397 880 1398 727 1398 878 1398 878 1399 881 1399 880 1399 881 1400 878 1400 838 1400 838 1401 839 1401 881 1401 865 1402 867 1402 879 1402 879 1403 882 1403 865 1403 882 1404 879 1404 880 1404 883 1405 880 1405 881 1405 880 1406 883 1406 882 1406 884 1407 881 1407 839 1407 881 1408 884 1408 883 1408 839 1409 840 1409 884 1409 863 1410 865 1410 882 1410 885 1411 882 1411 883 1411 882 1412 885 1412 863 1412 886 1413 883 1413 884 1413 883 1414 886 1414 885 1414 887 1415 884 1415 840 1415 884 1416 887 1416 886 1416 888 1417 863 1417 885 1417 888 1418 885 1418 886 1418 840 1419 841 1419 887 1419 889 1420 886 1420 887 1420 886 1421 889 1421 888 1421 841 1422 842 1422 887 1422 890 1423 887 1423 842 1423 887 1424 890 1424 889 1424 891 1425 871 1425 870 1425 892 1426 871 1426 891 1426 891 1427 893 1427 892 1427 894 1428 892 1428 893 1428 893 1429 895 1429 894 1429 894 1430 895 1430 774 1430 894 1431 774 1431 776 1431 728 182 730 182 738 182 728 182 738 182 744 182 728 182 744 182 746 182 728 1432 746 1432 748 1432 728 1433 748 1433 752 1433 728 1434 752 1434 758 1434 761 182 728 182 758 182 761 1435 679 1435 678 1435 761 1436 678 1436 677 1436 761 1437 677 1437 676 1437 761 1438 676 1438 674 1438 761 1439 674 1439 671 1439 761 1440 671 1440 670 1440 670 495 724 495 686 495 761 1441 670 1441 686 1441 761 1442 686 1442 685 1442 761 1443 685 1443 665 1443 761 1444 665 1444 662 1444 761 1445 662 1445 661 1445 761 1446 661 1446 655 1446 761 1447 655 1447 659 1447 728 1448 761 1448 659 1448 680 495 679 495 761 495 707 182 711 182 712 182 751 1449 750 1449 822 1449 870 1450 869 1450 872 1450 872 1451 875 1451 870 1451 866 1452 869 1452 871 1452 776 1453 832 1453 894 1453 871 1454 892 1454 894 1454 832 1455 871 1455 894 1455 832 1456 833 1456 871 1456 833 1457 834 1457 871 1457 741 1458 871 1458 834 1458 741 1459 834 1459 830 1459 741 1460 830 1460 829 1460 740 1461 741 1461 829 1461 740 1462 829 1462 828 1462 734 1463 740 1463 828 1463 733 1464 734 1464 828 1464 756 1465 896 1465 897 1465 897 1466 896 1466 898 1466 898 1467 896 1467 899 1467 898 1468 899 1468 900 1468 900 1469 899 1469 901 1469 900 1470 901 1470 902 1470 900 1471 902 1471 903 1471 904 1472 903 1472 902 1472 905 1473 903 1473 904 1473 905 1474 906 1474 903 1474 903 1475 906 1475 907 1475 908 1476 906 1476 905 1476 876 1477 903 1477 875 1477 906 1478 908 1478 774 1478 906 1479 774 1479 895 1479 893 1480 906 1480 895 1480 906 1481 893 1481 907 1481 891 1482 907 1482 893 1482 907 1483 891 1483 903 1483 891 1484 870 1484 903 1484 903 1485 876 1485 900 1485 875 1486 903 1486 870 1486 900 1487 876 1487 757 1487 800 1488 909 1488 798 1488 798 1489 909 1489 910 1489 911 1490 796 1490 910 1490 910 1491 796 1491 798 1491 910 1492 912 1492 911 1492 911 1493 912 1493 783 1493 911 1494 783 1494 781 1494 911 1495 781 1495 913 1495 911 1496 913 1496 914 1496 796 1497 911 1497 794 1497 908 1498 911 1498 914 1498 911 1499 902 1499 901 1499 902 1500 911 1500 904 1500 904 1501 911 1501 905 1501 905 1502 911 1502 908 1502 901 1503 792 1503 911 1503 911 1504 792 1504 794 1504 792 1505 901 1505 790 1505 899 1506 790 1506 901 1506 790 1507 899 1507 788 1507 896 1508 788 1508 899 1508 788 1509 896 1509 786 1509 756 1510 786 1510 896 1510 778 182 913 182 780 182 913 182 778 182 914 182 775 182 914 182 778 182 914 182 775 182 908 182 774 182 908 182 775 182 757 1511 898 1511 900 1511 898 1512 757 1512 897 1512 897 1513 757 1513 756 1513 780 182 913 182 781 182 681 1514 761 1514 760 1514 680 1515 761 1515 681 1515 724 1516 722 1516 686 1516 724 1517 672 1517 722 1517 915 270 773 270 916 270 917 270 915 270 916 270 918 270 919 270 916 270 920 270 921 270 917 270 916 571 922 571 918 571 923 1518 917 1518 921 1518 924 1519 918 1519 922 1519 921 1520 925 1520 923 1520 922 1521 926 1521 924 1521 927 1522 923 1522 925 1522 928 270 924 270 926 270 925 270 929 270 927 270 930 270 927 270 929 270 926 270 931 270 928 270 929 270 932 270 930 270 933 1523 928 1523 931 1523 930 1524 932 1524 934 1524 935 270 930 270 934 270 936 270 937 270 933 270 931 270 936 270 933 270 938 270 937 270 936 270 934 270 938 270 935 270 939 270 935 270 938 270 940 270 939 270 938 270 936 1525 940 1525 938 1525 941 580 800 580 942 580 943 1526 944 1526 816 1526 945 1527 922 1527 821 1527 946 1528 945 1528 819 1528 946 1529 816 1529 944 1529 947 1530 946 1530 944 1530 917 270 773 270 915 270 773 1531 917 1531 948 1531 948 1532 949 1532 825 1532 949 1533 950 1533 826 1533 950 1534 942 1534 827 1534 941 1535 951 1535 800 1535 951 1536 952 1536 910 1536 952 1537 953 1537 912 1537 954 593 955 593 784 593 955 1538 956 1538 836 1538 956 1539 943 1539 837 1539 957 1540 932 1540 929 1540 934 1541 932 1541 957 1541 938 1542 934 1542 957 1542 937 1543 938 1543 957 1543 933 600 937 600 957 600 928 270 933 270 957 270 957 601 924 601 928 601 918 1544 924 1544 957 1544 919 270 918 270 957 270 920 270 919 270 957 270 921 603 920 603 957 603 925 604 921 604 957 604 929 270 925 270 957 270 958 605 922 605 945 605 945 1545 946 1545 958 1545 959 1546 958 1546 946 1546 946 1547 947 1547 959 1547 948 1548 960 1548 949 1548 950 1549 949 1549 960 1549 960 1550 961 1550 950 1550 950 1551 961 1551 942 1551 962 1552 926 1552 922 1552 958 1553 962 1553 922 1553 959 1554 947 1554 962 1554 958 1555 959 1555 962 1555 947 1556 963 1556 962 1556 931 1557 926 1557 962 1557 964 1558 962 1558 963 1558 964 1559 936 1559 931 1559 962 1560 964 1560 931 1560 963 1561 965 1561 964 1561 940 1562 936 1562 964 1562 964 1563 965 1563 966 1563 967 1564 964 1564 966 1564 964 1565 967 1565 940 1565 939 1566 940 1566 967 1566 966 1567 968 1567 967 1567 969 1568 967 1568 968 1568 967 1569 969 1569 939 1569 935 1570 939 1570 969 1570 968 1571 970 1571 969 1571 971 1572 930 1572 935 1572 969 1573 971 1573 935 1573 971 1574 969 1574 970 1574 927 1575 930 1575 971 1575 970 1576 942 1576 971 1576 960 1577 923 1577 927 1577 971 639 960 639 927 639 971 1578 942 1578 961 1578 971 1579 961 1579 960 1579 948 1580 923 1580 960 1580 923 1581 948 1581 917 1581 784 182 953 182 954 182 954 182 972 182 973 182 953 182 972 182 954 182 947 1582 944 1582 943 1582 942 1583 970 1583 974 1583 974 1584 941 1584 942 1584 965 1585 963 1585 975 1585 975 1585 976 1585 965 1585 966 1586 965 1586 976 1586 976 1587 977 1587 966 1587 977 1588 978 1588 968 1588 968 1589 966 1589 977 1589 978 1590 974 1590 970 1590 970 1590 968 1590 978 1590 963 1591 947 1591 943 1591 943 1592 975 1592 963 1592 956 1593 975 1593 943 1593 955 1594 975 1594 956 1594 973 1595 976 1595 975 1595 973 1596 977 1596 976 1596 973 1597 972 1597 977 1597 972 1598 978 1598 977 1598 974 1599 978 1599 972 1599 951 1600 941 1600 974 1600 951 1601 974 1601 952 1601 916 1602 920 1602 917 1602 916 270 919 270 920 270 916 1603 821 1603 922 1603 955 1604 973 1604 975 1604 954 1605 973 1605 955 1605 953 1606 952 1606 972 1606 952 1607 974 1607 972 1607 666 1608 979 1608 664 1608 663 1609 666 1609 664 1609 980 182 687 182 686 182 981 1610 690 1610 692 1610 703 1611 982 1611 692 1611 704 1612 664 1612 979 1612 704 1613 983 1613 705 1613 690 1614 981 1614 984 1614 984 1615 985 1615 690 1615 799 681 942 681 800 681 783 182 953 182 784 182 815 581 943 581 816 581 821 682 819 682 945 682 819 1616 820 1616 946 1616 946 1617 820 1617 816 1617 825 1618 773 1618 948 1618 826 1619 825 1619 949 1619 827 1620 826 1620 950 1620 799 1621 827 1621 942 1621 951 1622 909 1622 800 1622 910 1623 909 1623 951 1623 912 1624 910 1624 952 1624 783 1625 912 1625 953 1625 955 693 835 693 784 693 836 694 835 694 955 694 837 1626 836 1626 956 1626 815 1627 837 1627 943 1627 916 270 773 270 772 270 772 1628 821 1628 916 1628 986 1629 987 1629 988 1629 692 1630 989 1630 990 1630 981 1631 692 1631 990 1631 991 1632 992 1632 993 1632 991 1633 994 1633 992 1633 995 1634 996 1634 997 1634 997 1635 996 1635 998 1635 998 1636 996 1636 999 1636 999 1637 996 1637 1000 1637 1000 1638 996 1638 1001 1638 1001 1639 996 1639 1002 1639 999 1640 1003 1640 998 1640 1004 1641 1005 1641 1003 1641 1003 1642 1005 1642 1006 1642 992 1643 1006 1643 1005 1643 1007 1644 1006 1644 992 1644 1008 1645 1007 1645 992 1645 1007 1646 1009 1646 1006 1646 998 1647 1003 1647 1006 1647 998 1648 1006 1648 1009 1648 1010 1649 1011 1649 1012 1649 1001 1650 1011 1650 1010 1650 992 1651 994 1651 1008 1651 980 1652 669 1652 687 1652 1013 1653 669 1653 980 1653 1014 1654 1013 1654 980 1654 1015 1655 1014 1655 980 1655 980 1656 1002 1656 1015 1656 996 1657 1015 1657 1002 1657 1011 1658 1001 1658 1002 1658 1016 1659 1017 1659 1018 1659 988 1660 1017 1660 1016 1660 1016 1661 1019 1661 988 1661 1020 1662 988 1662 1019 1662 1019 1663 1021 1663 1020 1663 1021 1664 990 1664 1020 1664 1021 1665 1022 1665 990 1665 981 1666 990 1666 1022 1666 1023 1667 981 1667 1022 1667 1024 1668 1025 1668 1026 1668 1025 1669 1027 1669 1026 1669 1028 1670 1024 1670 1026 1670 1026 1671 1029 1671 1028 1671 1030 1672 1028 1672 1029 1672 1029 1673 1031 1673 1030 1673 1032 1674 1030 1674 1031 1674 1031 1675 1033 1675 1032 1675 1034 1676 1032 1676 1033 1676 1033 1677 1035 1677 1034 1677 1036 1678 1034 1678 1035 1678 1035 1679 1018 1679 1036 1679 1036 1680 1018 1680 1017 1680 984 1681 981 1681 1023 1681 1037 1682 1038 1682 1039 1682 1038 1683 1037 1683 1040 1683 1041 1684 1042 1684 1038 1684 1043 1685 1044 1685 1045 1685 1046 1686 1045 1686 1044 1686 1046 1687 993 1687 1045 1687 1046 1688 1047 1688 993 1688 1046 1689 1048 1689 1047 1689 1046 1690 1049 1690 1048 1690 1050 1691 1049 1691 1046 1691 1051 1692 1046 1692 1052 1692 1046 1693 1044 1693 1052 1693 1046 1694 1051 1694 1050 1694 1051 1695 1053 1695 1050 1695 1052 1696 1054 1696 1051 1696 1055 1697 1053 1697 1051 1697 1051 1698 1038 1698 1055 1698 1038 1699 1056 1699 1055 1699 1038 1700 1042 1700 1056 1700 1051 1701 1039 1701 1038 1701 1051 1702 1054 1702 1039 1702 1045 1703 1004 1703 1043 1703 1005 1704 1004 1704 1045 1704 992 1705 1005 1705 1045 1705 1045 1706 993 1706 992 1706 993 1707 1047 1707 1057 1707 1057 1708 991 1708 993 1708 1058 1709 995 1709 997 1709 1059 1710 997 1710 998 1710 997 1711 1059 1711 1058 1711 998 1712 1009 1712 1059 1712 1060 1713 1058 1713 1059 1713 1059 1714 1061 1714 1060 1714 983 1715 1062 1715 705 1715 983 1716 704 1716 979 1716 983 1717 995 1717 1058 1717 983 1718 1063 1718 995 1718 983 1719 979 1719 1063 1719 983 1720 1058 1720 1062 1720 1058 1721 1060 1721 1062 1721 1064 1722 1065 1722 1066 1722 1067 1723 1066 1723 1065 1723 1067 1724 1007 1724 1008 1724 1067 1725 1065 1725 1007 1725 1008 1726 1068 1726 1067 1726 1008 1727 1069 1727 1068 1727 1008 1728 1070 1728 1069 1728 1071 1729 1070 1729 994 1729 1070 1730 1008 1730 994 1730 994 1731 991 1731 1071 1731 1072 1732 1071 1732 991 1732 991 1733 1057 1733 1072 1733 1047 1734 1072 1734 1057 1734 1004 1735 1003 1735 1000 1735 999 1736 1000 1736 1003 1736 1073 1737 1074 1737 1039 1737 1039 1738 1054 1738 1073 1738 1054 1739 1010 1739 1012 1739 1001 1740 1010 1740 1044 1740 1010 1741 1052 1741 1044 1741 1010 1742 1054 1742 1052 1742 1001 1743 1044 1743 1000 1743 1044 1744 1043 1744 1000 1744 1004 1745 1000 1745 1043 1745 1075 270 1033 270 1031 270 1075 1746 1035 1746 1033 1746 1018 270 1035 270 1075 270 1075 1747 1016 1747 1018 1747 1075 1748 1019 1748 1016 1748 1075 1749 1021 1749 1019 1749 1075 1750 1022 1750 1021 1750 1075 1751 1023 1751 1022 1751 1037 1752 1039 1752 1074 1752 988 1753 987 1753 1017 1753 989 1754 988 1754 1020 1754 1020 1755 990 1755 989 1755 988 1756 989 1756 986 1756 989 1757 1076 1757 986 1757 1077 1758 1076 1758 989 1758 1077 1759 989 1759 692 1759 982 1760 1077 1760 692 1760 1065 1761 1061 1761 1007 1761 1060 1762 1061 1762 1065 1762 1065 1763 1064 1763 1060 1763 1002 1764 980 1764 686 1764 995 1765 1015 1765 996 1765 1015 1766 995 1766 1063 1766 1015 1767 1063 1767 1014 1767 1063 1768 1013 1768 1014 1768 666 1769 1013 1769 1063 1769 1013 1770 666 1770 669 1770 666 1771 1063 1771 979 1771 1017 1772 987 1772 1036 1772 1069 1773 1070 1773 1078 1773 987 1774 1078 1774 1070 1774 1070 1775 1071 1775 987 1775 1071 1776 1036 1776 987 1776 1034 1777 1036 1777 1047 1777 1036 1778 1072 1778 1047 1778 1036 1779 1071 1779 1072 1779 1047 1780 1048 1780 1034 1780 1032 1781 1034 1781 1048 1781 1048 1782 1049 1782 1032 1782 1030 1783 1032 1783 1050 1783 1032 1784 1049 1784 1050 1784 1050 1785 1053 1785 1030 1785 1028 1786 1030 1786 1053 1786 1053 1787 1055 1787 1028 1787 1024 1788 1028 1788 1056 1788 1028 1789 1055 1789 1056 1789 1056 1790 1042 1790 1024 1790 1025 1791 1024 1791 1042 1791 1079 1792 1002 1792 686 1792 1002 1793 1079 1793 1011 1793 638 1794 637 1794 564 1794 637 1795 1080 1795 565 1795 1081 1796 616 1796 1082 1796 617 1797 616 1797 1081 1797 1081 1798 1083 1798 617 1798 1083 1799 636 1799 617 1799 701 1800 1082 1800 616 1800 701 1801 1084 1801 1082 1801 577 270 635 270 1075 270 1075 1802 1081 1802 1082 1802 1075 1803 1083 1803 1081 1803 1075 1804 636 1804 1083 1804 1075 1805 634 1805 636 1805 1075 1806 635 1806 634 1806 1082 876 1084 876 1075 876 1084 1807 1085 1807 1075 1807 721 1808 1075 1808 1085 1808 1011 1809 642 1809 650 1809 1011 1810 641 1810 642 1810 1011 1811 640 1811 641 1811 1011 1812 639 1812 640 1812 1011 1813 638 1813 639 1813 1011 1814 637 1814 638 1814 1011 1815 1080 1815 637 1815 1011 1816 723 1816 1080 1816 1086 1817 1087 1817 589 1817 601 1818 1086 1818 589 1818 1088 889 1089 889 1087 889 1086 1819 1088 1819 1087 1819 1090 1820 1089 1820 1088 1820 1091 1821 1092 1821 1090 1821 1088 1822 1091 1822 1090 1822 1091 1823 1093 1823 1092 1823 1011 1824 650 1824 649 1824 1011 1825 649 1825 648 1825 1094 1826 1095 1826 1096 1826 1096 1827 1097 1827 1094 1827 1094 1828 1097 1828 1040 1828 1098 1829 1094 1829 1040 1829 1099 1830 599 1830 600 1830 1100 1831 600 1831 591 1831 1101 1832 1095 1832 1100 1832 591 1833 1101 1833 1100 1833 1101 1834 1096 1834 1095 1834 1102 1835 1089 1835 1090 1835 1103 1836 1102 1836 1090 1836 1103 907 1097 907 1096 907 1103 1837 1096 1837 1102 1837 1090 1838 1092 1838 1103 1838 1103 1839 1092 1839 1104 1839 1103 1840 1041 1840 1097 1840 1102 1841 1101 1841 591 1841 590 1842 1102 1842 591 1842 590 1843 589 1843 1087 1843 590 1844 1087 1844 1089 1844 590 1845 1089 1845 1102 1845 1101 1846 1102 1846 1096 1846 1093 1847 1091 1847 1105 1847 1088 1848 1086 1848 1106 1848 1107 1849 1106 1849 1086 1849 1086 1850 601 1850 1107 1850 1108 1851 1107 1851 601 1851 601 1852 581 1852 1108 1852 580 1853 1108 1853 581 1853 648 1854 599 1854 1011 1854 1011 1855 599 1855 1099 1855 1091 1856 1109 1856 1105 1856 1088 1857 1109 1857 1091 1857 1088 1858 1106 1858 1109 1858 600 1859 1011 1859 1099 1859 1075 1860 580 1860 578 1860 1075 1861 578 1861 577 1861 694 1862 690 1862 985 1862 985 933 721 933 694 933 721 1863 1085 1863 698 1863 701 1864 698 1864 1085 1864 1085 1865 1084 1865 701 1865 1080 1866 723 1866 675 1866 675 1867 565 1867 1080 1867 1105 1868 1110 1868 1093 1868 1025 1869 1093 1869 1110 1869 1027 1870 1025 1870 1110 1870 1041 1871 1038 1871 1040 1871 1041 1872 1111 1872 1042 1872 1041 1873 1104 1873 1111 1873 1041 1874 1040 1874 1097 1874 1041 1875 1103 1875 1104 1875 984 270 1023 270 1075 270 985 270 984 270 1075 270 1075 1876 721 1876 985 1876 1074 1877 1112 1877 1037 1877 1040 1878 1037 1878 1112 1878 1112 1879 1098 1879 1040 1879 1111 1880 1025 1880 1042 1880 1093 1881 1025 1881 1104 1881 1025 1882 1111 1882 1104 1882 1093 1883 1104 1883 1092 1883 1079 182 686 182 722 182 1079 1884 722 1884 723 1884 1079 1885 723 1885 1011 1885 1113 1886 1114 1886 1115 1886 1116 1887 1117 1887 1118 1887 1118 1888 1114 1888 1113 1888 1113 1889 1115 1889 1119 1889 1120 1890 1121 1890 1122 1890 1123 1891 1122 1891 1121 1891 1124 1892 1123 1892 1125 1892 1123 1893 1121 1893 1125 1893 1126 1894 1124 1894 1127 1894 1124 1895 1125 1895 1127 1895 1128 1896 1126 1896 1129 1896 1126 1897 1127 1897 1129 1897 1130 1898 1128 1898 1129 1898 1130 1899 1131 1899 1128 1899 1132 1900 1128 1900 1131 1900 1133 1901 1134 1901 1135 1901 1133 1902 1136 1902 1134 1902 1136 1903 1137 1903 1134 1903 1136 1904 1138 1904 1137 1904 1138 1905 1139 1905 1137 1905 1138 1906 1140 1906 1139 1906 1139 1907 1140 1907 1141 1907 1142 1908 1141 1908 1143 1908 1141 1909 1140 1909 1143 1909 1122 1910 1144 1910 1120 1910 1145 1911 1133 1911 1135 1911 1146 1912 1147 1912 1148 1912 1147 1913 1149 1913 1148 1913 1149 1914 1131 1914 1148 1914 1149 1915 1150 1915 1131 1915 1150 1916 1151 1916 1131 1916 1151 1917 1152 1917 1131 1917 1132 1918 1131 1918 1152 1918 1153 1919 1154 1919 1155 1919 1156 1920 1154 1920 1153 1920 1153 1921 1157 1921 1156 1921 1153 1922 1158 1922 1157 1922 1153 1923 1159 1923 1158 1923 1153 1924 1160 1924 1159 1924 1153 1925 1143 1925 1160 1925 1142 1926 1143 1926 1161 1926 1143 1926 1162 1926 1161 1926 1143 1926 1153 1926 1162 1926 1146 1927 1163 1927 1147 1927 1163 1928 1164 1928 1147 1928 1165 1929 1164 1929 1163 1929 1163 1930 1166 1930 1165 1930 1167 1931 1165 1931 1166 1931 1166 1932 1168 1932 1167 1932 1168 1933 1169 1933 1170 1933 1171 1934 1172 1934 1169 1934 1169 1935 1173 1935 1171 1935 1173 1936 1174 1936 1171 1936 1175 1937 1174 1937 1173 1937 1173 1938 1176 1938 1175 1938 1176 1939 1177 1939 1175 1939 1176 1940 1178 1940 1177 1940 1179 1941 1178 1941 1176 1941 1155 1942 1180 1942 1153 1942 1181 1943 1153 1943 1180 1943 1180 1944 1182 1944 1181 1944 1116 1945 1181 1945 1182 1945 1182 1946 1117 1946 1116 1946 1113 1947 1116 1947 1118 1947 1183 1948 1113 1948 1119 1948 1119 1949 1184 1949 1183 1949 1185 1950 1183 1950 1186 1950 1183 1951 1184 1951 1186 1951 1186 1952 1187 1952 1185 1952 1188 1953 1185 1953 1189 1953 1185 1954 1190 1954 1189 1954 1185 1955 1191 1955 1190 1955 1185 1956 1187 1956 1191 1956 1192 1957 1188 1957 1189 1957 1188 1958 1193 1958 1194 1958 1188 1959 1192 1959 1193 1959 1169 1960 1172 1960 1170 1960 1170 1961 1195 1961 1168 1961 1168 1962 1195 1962 1167 1962 1196 1963 982 1963 703 1963 1196 1964 703 1964 702 1964 1196 1965 702 1965 691 1965 1197 1966 1196 1966 691 1966 982 1967 1196 1967 1077 1967 1196 1968 1198 1968 1077 1968 305 1969 302 1969 1199 1969 302 1970 1200 1970 1199 1970 304 1971 305 1971 1201 1971 305 1972 1199 1972 1201 1972 306 1973 304 1973 1202 1973 304 1974 1201 1974 1202 1974 1203 1975 306 1975 1202 1975 1204 1976 306 1976 1203 1976 1203 1977 1205 1977 1204 1977 292 1978 1204 1978 1205 1978 307 1979 1206 1979 1207 1979 1207 1980 1206 1980 1208 1980 307 1981 332 1981 1206 1981 332 1982 1209 1982 1206 1982 332 1983 333 1983 1209 1983 333 1984 1210 1984 1209 1984 333 1985 1211 1985 1210 1985 333 1986 334 1986 1211 1986 1211 1987 334 1987 1212 1987 1213 1988 1212 1988 287 1988 1212 1989 334 1989 287 1989 302 182 321 182 1200 182 1200 1990 321 1990 1214 1990 321 1991 318 1991 1214 1991 318 1992 317 1992 1214 1992 317 1993 312 1993 1214 1993 312 1994 308 1994 1214 1994 1208 1995 1214 1995 1207 1995 1214 1996 308 1996 1207 1996 308 1997 307 1997 1207 1997 1215 1998 54 1998 1216 1998 54 1999 4 1999 1216 1999 4 2000 1217 2000 1216 2000 4 2001 5 2001 1217 2001 5 2002 1205 2002 1217 2002 5 2003 164 2003 1205 2003 164 2004 159 2004 1205 2004 159 2005 163 2005 1205 2005 292 2006 1205 2006 163 2006 508 2007 1218 2007 505 2007 1218 2008 506 2008 505 2008 1218 2009 151 2009 506 2009 1218 2010 152 2010 151 2010 1218 2011 154 2011 152 2011 1218 2012 155 2012 154 2012 1218 2013 287 2013 155 2013 287 2014 1218 2014 1213 2014 1215 2015 1219 2015 54 2015 1219 2016 88 2016 54 2016 73 2017 88 2017 1219 2017 1219 2018 1220 2018 73 2018 74 2019 73 2019 1220 2019 1220 2020 1221 2020 74 2020 1221 2021 47 2021 74 2021 48 2022 47 2022 1221 2022 1221 2023 1222 2023 48 2023 1222 2024 67 2024 48 2024 64 2025 67 2025 1222 2025 1222 2026 1223 2026 64 2026 1223 2027 60 2027 64 2027 6 2028 60 2028 1223 2028 1223 2029 1224 2029 6 2029 1224 2030 7 2030 6 2030 1224 2031 134 2031 7 2031 135 2032 134 2032 1224 2032 508 2033 510 2033 1218 2033 1225 2034 1218 2034 510 2034 510 2035 511 2035 1225 2035 1226 2036 1225 2036 511 2036 511 2037 512 2037 1226 2037 1227 2038 1226 2038 513 2038 1226 2039 512 2039 513 2039 513 2040 522 2040 1227 2040 1228 2041 1227 2041 430 2041 1227 2042 431 2042 430 2042 1227 2043 522 2043 431 2043 430 2044 520 2044 1228 2044 1229 2045 1228 2045 521 2045 1228 2046 520 2046 521 2046 521 2047 426 2047 1229 2047 1230 2048 1229 2048 137 2048 1229 2049 148 2049 137 2049 1229 2050 149 2050 148 2050 1229 2051 426 2051 149 2051 139 2052 1230 2052 137 2052 1224 2053 1230 2053 146 2053 146 2054 135 2054 1224 2054 1230 2055 145 2055 146 2055 1230 2056 143 2056 145 2056 1230 2057 141 2057 143 2057 1230 2058 139 2058 141 2058 1231 1890 1232 1890 857 1890 859 2059 857 2059 1232 2059 861 2060 859 2060 1233 2060 859 2061 1232 2061 1233 2061 860 2062 861 2062 1234 2062 861 2063 1233 2063 1234 2063 862 2064 860 2064 1235 2064 860 2065 1234 2065 1235 2065 1236 2066 862 2066 1235 2066 1237 2067 862 2067 1236 2067 1236 2068 1238 2068 1237 2068 847 2069 1237 2069 1238 2069 863 2070 1239 2070 1240 2070 863 2071 888 2071 1239 2071 888 2072 1241 2072 1239 2072 888 2073 889 2073 1241 2073 889 2074 1242 2074 1241 2074 889 2075 1243 2075 1242 2075 889 2076 890 2076 1243 2076 1243 2077 890 2077 1244 2077 1245 2078 1244 2078 842 2078 1244 2079 890 2079 842 2079 857 2080 877 2080 1231 2080 1231 2081 877 2081 1246 2081 877 2082 874 2082 1246 2082 874 182 873 182 1246 182 873 182 868 182 1246 182 868 182 864 182 1246 182 1246 2083 864 2083 1240 2083 864 2084 863 2084 1240 2084 1247 2085 609 2085 1248 2085 609 2086 560 2086 1248 2086 560 2087 1238 2087 1248 2087 560 2088 719 2088 1238 2088 719 2089 714 2089 1238 2089 714 2090 718 2090 1238 2090 847 2091 1238 2091 718 2091 1064 2092 1249 2092 1060 2092 1249 2093 1062 2093 1060 2093 1249 2094 705 2094 1062 2094 1249 2095 706 2095 705 2095 1249 2096 708 2096 706 2096 1249 2097 709 2097 708 2097 1249 2098 842 2098 709 2098 842 2099 1249 2099 1245 2099 1247 2100 1250 2100 609 2100 1250 2101 643 2101 609 2101 628 2102 643 2102 1250 2102 1250 2103 1251 2103 628 2103 629 2104 628 2104 1251 2104 1251 2105 1252 2105 629 2105 1252 2106 602 2106 629 2106 603 2107 602 2107 1252 2107 1252 2108 1253 2108 603 2108 1253 2109 622 2109 603 2109 619 2110 622 2110 1253 2110 1253 2111 1254 2111 619 2111 1254 2112 615 2112 619 2112 561 2113 615 2113 1254 2113 1254 2114 1255 2114 561 2114 1255 2115 562 2115 561 2115 1255 2116 688 2116 562 2116 689 2117 688 2117 1255 2117 1064 2118 1066 2118 1249 2118 1256 2119 1249 2119 1066 2119 1066 2120 1067 2120 1256 2120 1257 2121 1256 2121 1067 2121 1067 2122 1068 2122 1257 2122 1258 2123 1257 2123 1069 2123 1257 2124 1068 2124 1069 2124 1069 2125 1078 2125 1258 2125 1198 2126 1258 2126 986 2126 1258 2127 987 2127 986 2127 1258 2128 1078 2128 987 2128 986 2129 1076 2129 1198 2129 1198 2130 1076 2130 1077 2130 693 2131 1197 2131 691 2131 1255 2132 1197 2132 700 2132 700 2133 689 2133 1255 2133 1197 2134 699 2134 700 2134 1197 2135 697 2135 699 2135 1197 2136 695 2136 697 2136 1197 2137 693 2137 695 2137 1259 2138 1196 2138 1197 2138 1260 2139 1196 2139 1259 2139 1261 2140 1196 2140 1260 2140 1198 2141 1196 2141 1261 2141 1238 64 1262 64 1248 64 1263 64 1248 64 1262 64 1249 2142 1264 2142 1245 2142 1265 2143 1245 2143 1264 2143 1266 2144 1260 2144 1259 2144 1266 2145 1259 2145 1267 2145 1268 2146 1269 2146 1270 2146 1271 2147 1269 2147 1268 2147 1272 2148 1269 2148 1271 2148 1273 2149 1269 2149 1272 2149 1246 2150 1271 2150 1274 2150 1275 2151 1246 2151 1274 2151 1208 2152 1206 2152 1276 2152 1240 2153 1239 2153 1273 2153 1239 2154 1269 2154 1273 2154 1239 2155 1241 2155 1269 2155 1270 2156 1269 2156 1241 2156 1241 2157 1242 2157 1270 2157 1242 2158 1243 2158 1270 2158 1243 2159 1244 2159 1270 2159 1244 2160 1277 2160 1270 2160 1265 2161 1277 2161 1245 2161 1277 2162 1244 2162 1245 2162 1199 2163 1278 2163 1201 2163 1278 2164 1202 2164 1201 2164 1199 2165 1279 2165 1278 2165 1199 2166 1200 2166 1279 2166 1280 2167 1202 2167 1278 2167 1202 2168 1280 2168 1203 2168 1280 2169 1205 2169 1203 2169 1280 2170 1281 2170 1205 2170 1282 2171 1280 2171 1278 2171 1280 2172 1282 2172 1281 2172 1282 2173 1283 2173 1281 2173 1284 2174 1283 2174 1282 2174 1278 2175 1285 2175 1286 2175 1278 2176 1279 2176 1285 2176 1278 2177 1286 2177 1282 2177 1282 2178 1287 2178 1284 2178 1287 2179 1288 2179 1284 2179 1287 2180 1282 2180 1286 2180 1285 2181 1289 2181 1286 2181 1286 2182 1290 2182 1287 2182 1290 2183 1286 2183 1291 2183 1286 2184 1292 2184 1291 2184 1286 2185 1289 2185 1292 2185 1293 2186 1288 2186 1287 2186 1287 2187 1294 2187 1293 2187 1294 2188 1287 2188 1290 2188 1295 2189 1293 2189 1294 2189 1291 2190 1296 2190 1290 2190 1297 2191 1290 2191 1298 2191 1290 2192 1296 2192 1298 2192 1290 2193 1297 2193 1294 2193 1299 2194 1294 2194 1297 2194 1294 2195 1299 2195 1295 2195 1299 2196 1300 2196 1295 2196 1301 2197 1300 2197 1299 2197 1298 2198 1302 2198 1297 2198 1303 2199 1297 2199 1304 2199 1297 2200 1302 2200 1304 2200 1297 2201 1303 2201 1299 2201 1305 2202 1299 2202 1303 2202 1299 2203 1305 2203 1301 2203 1305 2204 1306 2204 1301 2204 1304 2205 1307 2205 1303 2205 1303 2206 1308 2206 1268 2206 1303 2207 1307 2207 1308 2207 1303 2208 1268 2208 1305 2208 1309 2209 1306 2209 1305 2209 1305 2210 1268 2210 1270 2210 1305 2211 1270 2211 1309 2211 1308 2212 1271 2212 1268 2212 1265 2213 1309 2213 1277 2213 1309 2214 1270 2214 1277 2214 1275 2215 1232 2215 1231 2215 1233 2216 1232 2216 1310 2216 1234 2217 1233 2217 1311 2217 1233 2218 1310 2218 1311 2218 1235 2219 1234 2219 1311 2219 1236 2220 1235 2220 1312 2220 1235 2221 1311 2221 1312 2221 1312 2222 1262 2222 1236 2222 1238 2223 1236 2223 1262 2223 1313 2224 1311 2224 1310 2224 1311 2225 1313 2225 1312 2225 1313 2226 1262 2226 1312 2226 1313 2227 1314 2227 1262 2227 1275 2228 1274 2228 1232 2228 1274 2229 1310 2229 1232 2229 1310 2230 1315 2230 1313 2230 1315 2231 1310 2231 1316 2231 1310 2232 1274 2232 1316 2232 1317 2233 1314 2233 1313 2233 1316 2234 1318 2234 1315 2234 1319 2235 1313 2235 1320 2235 1313 2236 1315 2236 1320 2236 1313 2237 1319 2237 1317 2237 1319 2238 1321 2238 1317 2238 1319 2239 1322 2239 1321 2239 1320 2240 1315 2240 1323 2240 1315 2241 1318 2241 1323 2241 1323 2242 1324 2242 1320 2242 1320 2243 1325 2243 1319 2243 1325 2244 1320 2244 1326 2244 1320 2245 1324 2245 1326 2245 1327 2246 1322 2246 1319 2246 1328 2247 1319 2247 1325 2247 1319 2248 1328 2248 1327 2248 1328 2249 1329 2249 1327 2249 1326 2250 1330 2250 1325 2250 1325 2251 1330 2251 1331 2251 1331 182 1292 182 1332 182 1291 182 1292 182 1330 182 1292 2252 1331 2252 1330 2252 1330 182 1326 182 1291 182 1296 2253 1291 2253 1326 2253 1326 182 1324 182 1296 182 1298 182 1296 182 1324 182 1279 2254 1333 2254 1285 2254 1324 2255 1323 2255 1298 2255 1302 182 1298 182 1323 182 1323 182 1318 182 1302 182 1318 2256 1304 2256 1302 2256 1333 2257 1279 2257 1214 2257 1307 182 1304 182 1318 182 1318 182 1316 182 1307 182 1308 182 1307 182 1316 182 1316 2258 1274 2258 1308 2258 1271 2259 1308 2259 1274 2259 1279 2260 1200 2260 1214 2260 1208 2261 1276 2261 1214 2261 1272 2262 1271 2262 1246 2262 1273 2263 1272 2263 1246 2263 1275 2264 1231 2264 1246 2264 1240 2265 1273 2265 1246 2265 1334 2266 1260 2266 1335 2266 1260 2267 1266 2267 1335 2267 1260 2268 1334 2268 1261 2268 1334 2269 1336 2269 1261 2269 1334 2270 1337 2270 1336 2270 1338 2271 1337 2271 1334 2271 1338 2272 1339 2272 1337 2272 1338 2273 1264 2273 1339 2273 1338 2274 1340 2274 1264 2274 1335 2275 1341 2275 1334 2275 1334 2276 1342 2276 1338 2276 1342 2277 1334 2277 1343 2277 1334 2278 1344 2278 1343 2278 1334 2279 1341 2279 1344 2279 1345 2280 1338 2280 1342 2280 1338 2281 1345 2281 1340 2281 1345 2282 1346 2282 1340 2282 1343 2283 1347 2283 1342 2283 1348 2284 1342 2284 1349 2284 1342 2285 1347 2285 1349 2285 1342 2286 1348 2286 1345 2286 1350 2287 1345 2287 1348 2287 1345 2288 1350 2288 1346 2288 1350 2289 1351 2289 1346 2289 1349 2290 1352 2290 1348 2290 1353 2291 1351 2291 1350 2291 1354 2292 1348 2292 1355 2292 1348 2293 1356 2293 1355 2293 1352 2294 1356 2294 1348 2294 1348 2295 1354 2295 1350 2295 1350 2296 1357 2296 1353 2296 1357 2297 1350 2297 1354 2297 1358 2298 1353 2298 1357 2298 1355 2299 1359 2299 1354 2299 1360 2300 1354 2300 1361 2300 1354 2301 1359 2301 1361 2301 1354 2302 1360 2302 1357 2302 1362 2303 1357 2303 1360 2303 1357 2304 1362 2304 1358 2304 1362 2305 1363 2305 1358 2305 1361 2306 1364 2306 1360 2306 1365 2307 1360 2307 1366 2307 1360 2308 1364 2308 1366 2308 1360 2309 1365 2309 1362 2309 1362 2310 1367 2310 1363 2310 1367 2311 1368 2311 1363 2311 1367 2312 1362 2312 1365 2312 1365 2313 1222 2313 1367 2313 1365 2314 1223 2314 1222 2314 1365 2315 1224 2315 1223 2315 1365 2316 1369 2316 1224 2316 1365 2317 1370 2317 1369 2317 1365 2318 1366 2318 1370 2318 1219 2319 1367 2319 1220 2319 1367 2320 1221 2320 1220 2320 1367 2321 1222 2321 1221 2321 1367 2322 1219 2322 1368 2322 1368 2323 1219 2323 1215 2323 1267 2324 1259 2324 1197 2324 1261 2325 1336 2325 1198 2325 1336 2326 1258 2326 1198 2326 1257 2327 1258 2327 1336 2327 1336 2328 1337 2328 1257 2328 1256 2329 1257 2329 1339 2329 1257 2330 1337 2330 1339 2330 1339 2331 1264 2331 1256 2331 1249 2332 1256 2332 1264 2332 1255 2333 1371 2333 1372 2333 1255 2334 1254 2334 1371 2334 1254 2335 1373 2335 1371 2335 1254 2336 1253 2336 1373 2336 1253 2337 1374 2337 1373 2337 1375 2338 1374 2338 1252 2338 1374 2339 1253 2339 1252 2339 1252 2340 1251 2340 1375 2340 1376 2341 1375 2341 1251 2341 1251 2342 1250 2342 1376 2342 1377 2343 1376 2343 1247 2343 1376 2344 1250 2344 1247 2344 1378 2345 1379 2345 1380 2345 1379 2346 1381 2346 1380 2346 1382 2347 1383 2347 1384 2347 1383 2348 1382 2348 1378 2348 1385 2349 1384 2349 1383 2349 1380 2350 1386 2350 1378 2350 1378 2351 1387 2351 1383 2351 1387 2352 1378 2352 1388 2352 1378 2353 1386 2353 1388 2353 1389 2354 1383 2354 1387 2354 1383 2355 1389 2355 1385 2355 1389 2356 1390 2356 1385 2356 1388 2357 1391 2357 1387 2357 1392 2358 1387 2358 1393 2358 1387 2359 1394 2359 1393 2359 1387 2360 1391 2360 1394 2360 1387 2361 1392 2361 1389 2361 1395 2362 1389 2362 1392 2362 1389 2363 1395 2363 1390 2363 1395 2364 1396 2364 1390 2364 1393 2365 1397 2365 1392 2365 1392 2366 1373 2366 1395 2366 1392 2367 1371 2367 1373 2367 1392 2368 1372 2368 1371 2368 1392 2369 1398 2369 1372 2369 1392 2370 1397 2370 1398 2370 1376 2371 1395 2371 1375 2371 1395 2372 1374 2372 1375 2372 1395 2373 1373 2373 1374 2373 1395 2374 1376 2374 1396 2374 1376 2375 1377 2375 1396 2375 1309 2376 1265 2376 1264 2376 1264 2377 1340 2377 1309 2377 1306 2378 1309 2378 1340 2378 1301 2379 1306 2379 1346 2379 1306 2380 1340 2380 1346 2380 1300 2381 1301 2381 1346 2381 1346 2382 1351 2382 1300 2382 1295 2383 1300 2383 1351 2383 1351 2384 1353 2384 1295 2384 1293 2385 1295 2385 1353 2385 1288 2386 1293 2386 1353 2386 1353 2387 1358 2387 1288 2387 1284 2388 1288 2388 1358 2388 1358 2389 1363 2389 1284 2389 1283 2390 1284 2390 1363 2390 1281 2391 1283 2391 1368 2391 1283 2392 1363 2392 1368 2392 1205 2393 1281 2393 1217 2393 1281 2394 1216 2394 1217 2394 1281 2395 1368 2395 1216 2395 1327 2396 1329 2396 1384 2396 1384 2397 1385 2397 1327 2397 1322 2398 1327 2398 1385 2398 1385 2399 1390 2399 1322 2399 1321 2400 1322 2400 1390 2400 1317 2401 1321 2401 1396 2401 1321 2402 1390 2402 1396 2402 1314 2403 1317 2403 1396 2403 1396 2404 1377 2404 1314 2404 1314 2405 1263 2405 1262 2405 1314 2406 1377 2406 1263 2406 1368 2407 1215 2407 1216 2407 1377 2408 1247 2408 1263 2408 1248 64 1263 64 1247 64 1255 270 1372 270 1197 270 1267 270 1197 270 1372 270 1224 270 1369 270 1230 270 1230 2409 1370 2409 1366 2409 1230 2410 1369 2410 1370 2410 1120 2411 1144 2411 1399 2411 1144 2412 1400 2412 1399 2412 1400 2413 1401 2413 1399 2413 1401 2414 1402 2414 1399 2414 1402 2415 1145 2415 1399 2415 1399 2416 1145 2416 1135 2416 1131 2417 1403 2417 1148 2417 1120 2418 1404 2418 1121 2418 1405 2419 1121 2419 1404 2419 1325 2420 1406 2420 1328 2420 1406 2421 1325 2421 1407 2421 1325 2422 1331 2422 1407 2422 1408 2423 1329 2423 1328 2423 1409 2424 1328 2424 1406 2424 1328 2425 1409 2425 1408 2425 1407 2426 1410 2426 1406 2426 1411 2427 1408 2427 1409 2427 1406 2428 1412 2428 1409 2428 1412 2429 1406 2429 1413 2429 1406 2430 1414 2430 1413 2430 1406 2431 1410 2431 1414 2431 1415 2432 1409 2432 1412 2432 1409 2433 1415 2433 1411 2433 1415 2434 1416 2434 1411 2434 1415 2435 1417 2435 1416 2435 1418 2436 1417 2436 1415 2436 1415 2437 1137 2437 1139 2437 1415 2438 1412 2438 1137 2438 1415 2439 1139 2439 1418 2439 1142 2440 1418 2440 1141 2440 1418 2441 1139 2441 1141 2441 1137 2442 1412 2442 1134 2442 1412 2443 1413 2443 1134 2443 1413 2444 1135 2444 1134 2444 1405 2445 1125 2445 1121 2445 1405 2446 1419 2446 1125 2446 1127 2447 1125 2447 1419 2447 1419 2448 1420 2448 1127 2448 1420 2449 1129 2449 1127 2449 1129 2450 1420 2450 1130 2450 1131 2451 1130 2451 1421 2451 1130 2452 1420 2452 1421 2452 1131 2453 1421 2453 1422 2453 1332 2454 1404 2454 1331 2454 1404 2455 1407 2455 1331 2455 1410 2456 1407 2456 1404 2456 1414 2457 1410 2457 1404 2457 1413 2458 1414 2458 1399 2458 1414 2459 1404 2459 1399 2459 1404 2460 1120 2460 1399 2460 1399 2461 1135 2461 1413 2461 1423 2462 1185 2462 1188 2462 1185 2463 1424 2463 1183 2463 1424 2464 1113 2464 1183 2464 1424 2465 1116 2465 1113 2465 1424 2466 1185 2466 1425 2466 1185 2467 1426 2467 1425 2467 1185 2468 1427 2468 1426 2468 1185 2469 1423 2469 1427 2469 1181 2470 1116 2470 1428 2470 1428 2471 1153 2471 1181 2471 1428 2472 1429 2472 1153 2472 1428 2473 1116 2473 1424 2473 1430 2474 1429 2474 1428 2474 1424 2475 1431 2475 1428 2475 1431 2476 1424 2476 1432 2476 1424 2477 1425 2477 1432 2477 1433 2478 1428 2478 1431 2478 1428 2479 1433 2479 1430 2479 1434 2480 1430 2480 1433 2480 1432 2481 1435 2481 1431 2481 1379 2482 1431 2482 1436 2482 1431 2483 1435 2483 1436 2483 1431 2484 1379 2484 1433 2484 1433 2485 1382 2485 1434 2485 1382 2486 1437 2486 1434 2486 1382 2487 1433 2487 1379 2487 1436 2488 1438 2488 1379 2488 1384 2489 1437 2489 1382 2489 1379 2490 1378 2490 1382 2490 1438 2491 1381 2491 1379 2491 1153 2492 1429 2492 1162 2492 1429 2493 1161 2493 1162 2493 1429 2494 1142 2494 1161 2494 1418 2495 1142 2495 1429 2495 1417 2496 1418 2496 1429 2496 1429 2497 1430 2497 1417 2497 1416 2498 1417 2498 1430 2498 1430 2499 1434 2499 1416 2499 1411 2500 1416 2500 1434 2500 1434 2501 1437 2501 1411 2501 1408 2502 1411 2502 1437 2502 1437 2503 1384 2503 1408 2503 1329 2504 1408 2504 1384 2504 1425 2505 1426 2505 1432 2505 1439 2506 1440 2506 1441 2506 1442 2507 1443 2507 1439 2507 1443 2508 1440 2508 1439 2508 1444 2509 1445 2509 1446 2509 1444 2510 1447 2510 1445 2510 1447 2511 1448 2511 1445 2511 1447 2512 1449 2512 1448 2512 1447 2513 1450 2513 1449 2513 1447 2514 1451 2514 1450 2514 1447 2515 1452 2515 1451 2515 1447 2516 1453 2516 1452 2516 1454 2517 1455 2517 1456 2517 1457 2518 1458 2518 1455 2518 1459 2519 1440 2519 1443 2519 1443 2520 1460 2520 1459 2520 1461 2521 1459 2521 1460 2521 1460 2522 1462 2522 1461 2522 1463 2523 1461 2523 1462 2523 1462 2524 1464 2524 1463 2524 1465 2525 1463 2525 1464 2525 1464 2526 1466 2526 1465 2526 1467 2527 1465 2527 1466 2527 1466 2528 1468 2528 1467 2528 1468 2529 1469 2529 1470 2529 1440 2530 1459 2530 1441 2530 1471 2531 1441 2531 1461 2531 1441 2532 1459 2532 1461 2532 1449 2533 1450 2533 1472 2533 1472 2534 1473 2534 1449 2534 1473 2535 1448 2535 1449 2535 1445 2536 1448 2536 1473 2536 1473 2537 1474 2537 1445 2537 1475 2538 1445 2538 1474 2538 1474 2539 1476 2539 1475 2539 1476 2540 1477 2540 1475 2540 1478 2541 1477 2541 1476 2541 1476 2542 1479 2542 1478 2542 1480 2543 1478 2543 1481 2543 1478 2544 1482 2544 1481 2544 1478 2545 1483 2545 1482 2545 1478 2546 1484 2546 1483 2546 1478 2547 1479 2547 1484 2547 1479 2548 1485 2548 1486 2548 1486 2549 1484 2549 1479 2549 1485 2550 1487 2550 1486 2550 1488 2551 1487 2551 1485 2551 1489 2552 1490 2552 1488 2552 1445 2553 1475 2553 1446 2553 1491 2554 1446 2554 1475 2554 1491 2555 1492 2555 1446 2555 1475 2556 1477 2556 1491 2556 1493 2557 1492 2557 1491 2557 1494 2558 1491 2558 1478 2558 1491 2559 1477 2559 1478 2559 1491 2560 1494 2560 1493 2560 1495 2561 1493 2561 1494 2561 1478 2562 1480 2562 1494 2562 1494 2563 1496 2563 1497 2563 1494 2564 1480 2564 1496 2564 1494 2565 1497 2565 1495 2565 1497 2566 1498 2566 1495 2566 1499 2567 1498 2567 1500 2567 1498 2568 1497 2568 1500 2568 1501 2569 1502 2569 1442 2569 1503 2570 1442 2570 1502 2570 1504 2571 1443 2571 1442 2571 1504 2572 1442 2572 1503 2572 1502 2573 1505 2573 1503 2573 1460 2574 1443 2574 1504 2574 1506 2575 1503 2575 1507 2575 1503 2576 1505 2576 1507 2576 1503 2577 1506 2577 1504 2577 1504 2578 1508 2578 1460 2578 1508 2579 1462 2579 1460 2579 1508 2580 1504 2580 1506 2580 1507 2581 1509 2581 1506 2581 1464 2582 1462 2582 1508 2582 1506 2583 1510 2583 1508 2583 1510 2584 1506 2584 1511 2584 1506 2585 1509 2585 1511 2585 1508 2586 1512 2586 1464 2586 1512 2587 1466 2587 1464 2587 1512 2588 1508 2588 1510 2588 1511 2589 1513 2589 1510 2589 1468 2590 1466 2590 1512 2590 1514 2591 1510 2591 1513 2591 1510 2592 1514 2592 1512 2592 1512 2593 1515 2593 1468 2593 1515 2594 1512 2594 1514 2594 1513 2595 1516 2595 1514 2595 1469 2596 1468 2596 1515 2596 1517 2597 1514 2597 1518 2597 1514 2598 1516 2598 1518 2598 1514 2599 1517 2599 1515 2599 1519 2600 1515 2600 1517 2600 1515 2601 1519 2601 1469 2601 1519 2602 1520 2602 1469 2602 1521 2603 1520 2603 1519 2603 1522 2604 1523 2604 1490 2604 1488 2605 1490 2605 1523 2605 1523 2606 1524 2606 1488 2606 1487 2607 1488 2607 1525 2607 1488 2608 1526 2608 1525 2608 1488 2609 1524 2609 1526 2609 1525 2610 1527 2610 1487 2610 1527 2611 1486 2611 1487 2611 1484 2612 1486 2612 1527 2612 1527 2613 1528 2613 1484 2613 1483 2614 1484 2614 1528 2614 1528 2615 1529 2615 1483 2615 1482 2616 1483 2616 1529 2616 1529 2617 1530 2617 1482 2617 1481 2618 1482 2618 1530 2618 1530 2619 1531 2619 1481 2619 1480 2620 1481 2620 1531 2620 1531 2621 1532 2621 1480 2621 1532 2622 1496 2622 1480 2622 1497 2623 1496 2623 1532 2623 1532 2624 1533 2624 1497 2624 1533 2625 1534 2625 1497 2625 1500 2626 1497 2626 1534 2626 1499 2627 1500 2627 1535 2627 1500 2628 1534 2628 1535 2628 1534 2629 1533 2629 1536 2629 1536 2630 1537 2630 1534 2630 1537 2631 1538 2631 1534 2631 1538 2632 1535 2632 1534 2632 1539 2633 1535 2633 1538 2633 1538 2634 1540 2634 1539 2634 1541 2635 1539 2635 1540 2635 1540 2636 1542 2636 1541 2636 1543 2637 1541 2637 1542 2637 1542 2638 1544 2638 1543 2638 1545 2639 1543 2639 1544 2639 1544 2640 1546 2640 1545 2640 1547 2641 1545 2641 1546 2641 1546 2642 1548 2642 1547 2642 1547 2643 1549 2643 1550 2643 1547 2644 1548 2644 1549 2644 1551 2645 1549 2645 1552 2645 1551 2646 1550 2646 1549 2646 1552 2647 1553 2647 1554 2647 1501 2648 1442 2648 1555 2648 1556 2649 1518 2649 1557 2649 1518 2650 1516 2650 1557 2650 1516 2651 1513 2651 1557 2651 1513 2652 1511 2652 1557 2652 1555 2653 1557 2653 1501 2653 1557 2654 1502 2654 1501 2654 1557 2655 1505 2655 1502 2655 1557 2656 1507 2656 1505 2656 1557 2657 1509 2657 1507 2657 1557 2658 1511 2658 1509 2658 1553 2659 1558 2659 1554 2659 1559 2660 1560 2660 1561 2660 1562 2661 1563 2661 1537 2661 1563 2662 1538 2662 1537 2662 1563 2663 1562 2663 1559 2663 1562 2664 1560 2664 1559 2664 1540 2665 1538 2665 1563 2665 1559 2666 1564 2666 1563 2666 1565 2667 1563 2667 1564 2667 1563 2668 1565 2668 1540 2668 1542 2669 1540 2669 1565 2669 1564 2670 1566 2670 1565 2670 1565 2671 1567 2671 1542 2671 1567 2672 1544 2672 1542 2672 1567 2673 1565 2673 1566 2673 1546 2674 1544 2674 1567 2674 1566 2675 1568 2675 1567 2675 1567 2676 1569 2676 1546 2676 1569 2677 1567 2677 1568 2677 1548 2678 1546 2678 1569 2678 1568 2679 1570 2679 1553 2679 1553 2680 1569 2680 1568 2680 1569 2681 1552 2681 1548 2681 1569 2682 1553 2682 1552 2682 1548 2683 1552 2683 1549 2683 1571 2684 1561 2684 1560 2684 1572 2685 1560 2685 1537 2685 1560 2686 1562 2686 1537 2686 1560 2687 1572 2687 1571 2687 1537 2688 1573 2688 1572 2688 1573 2689 1537 2689 1456 2689 1574 2690 1571 2690 1572 2690 1575 2691 1572 2691 1573 2691 1572 2692 1575 2692 1574 2692 1456 2693 1455 2693 1573 2693 1573 2694 1576 2694 1575 2694 1576 2695 1573 2695 1455 2695 1577 2696 1574 2696 1575 2696 1574 2697 1577 2697 1578 2697 1579 2698 1575 2698 1576 2698 1575 2699 1579 2699 1577 2699 1580 2700 1578 2700 1577 2700 1455 2701 1458 2701 1576 2701 1581 2702 1576 2702 1458 2702 1576 2703 1581 2703 1579 2703 1582 2704 1577 2704 1583 2704 1577 2705 1579 2705 1583 2705 1577 2706 1582 2706 1580 2706 1583 2707 1579 2707 1581 2707 1580 2708 1584 2708 1585 2708 1584 2709 1580 2709 1582 2709 1586 2710 1585 2710 1584 2710 1458 2711 1587 2711 1581 2711 1581 2712 1588 2712 1583 2712 1588 2713 1581 2713 1589 2713 1581 2714 1587 2714 1589 2714 1583 2715 1590 2715 1582 2715 1536 2716 1533 2716 1537 2716 1533 2717 1532 2717 1537 2717 1532 2718 1531 2718 1537 2718 1531 2719 1530 2719 1537 2719 1530 2720 1529 2720 1537 2720 1591 2721 1529 2721 1592 2721 1529 2722 1528 2722 1592 2722 1528 2723 1527 2723 1592 2723 1527 2724 1525 2724 1592 2724 1529 2725 1591 2725 1537 2725 1456 2726 1537 2726 1591 2726 1523 2727 1592 2727 1524 2727 1592 2728 1526 2728 1524 2728 1592 2729 1525 2729 1526 2729 1592 2730 1593 2730 1591 2730 1591 2731 1594 2731 1456 2731 1594 2732 1454 2732 1456 2732 1594 2733 1591 2733 1593 2733 1455 2734 1454 2734 1594 2734 1593 2735 1595 2735 1594 2735 1596 2736 1594 2736 1595 2736 1594 2737 1596 2737 1455 2737 1596 2738 1457 2738 1455 2738 1458 2739 1457 2739 1596 2739 1597 2740 1596 2740 1598 2740 1596 2741 1597 2741 1458 2741 1597 2742 1587 2742 1458 2742 1589 2743 1587 2743 1597 2743 1597 2744 1599 2744 1589 2744 1600 2745 1589 2745 1599 2745 1601 64 1550 64 1551 64 1547 64 1550 64 1601 64 1601 2746 1602 2746 1547 2746 1545 2747 1547 2747 1602 2747 1543 2748 1545 2748 1446 2748 1545 2749 1602 2749 1446 2749 1541 2750 1543 2750 1499 2750 1543 2751 1492 2751 1499 2751 1543 2752 1446 2752 1492 2752 1492 2753 1493 2753 1499 2753 1498 2754 1499 2754 1493 2754 1499 64 1535 64 1541 64 1535 64 1539 64 1541 64 1493 2755 1495 2755 1498 2755 1603 2756 1604 2756 1605 2756 1441 2757 1471 2757 1606 2757 1461 2758 1463 2758 1471 2758 1607 2759 1471 2759 1465 2759 1471 2760 1463 2760 1465 2760 1608 2761 1609 2761 1610 2761 1609 2762 1611 2762 1610 2762 1609 2763 1608 2763 1612 2763 1608 2764 1603 2764 1612 2764 1612 2765 1613 2765 1609 2765 1614 2766 1615 2766 1616 2766 1617 2767 1618 2767 1619 2767 1617 2768 1620 2768 1618 2768 1619 2769 1621 2769 1617 2769 1604 2770 1620 2770 1617 2770 1605 2771 1617 2771 1621 2771 1617 2772 1605 2772 1604 2772 1621 2773 1613 2773 1612 2773 1621 2774 1612 2774 1605 2774 1603 2775 1605 2775 1612 2775 1589 2776 1600 2776 1588 2776 1622 2777 1623 2777 1624 2777 1624 2778 1625 2778 1622 2778 1625 2779 1624 2779 1610 2779 1610 2780 1611 2780 1625 2780 1599 2781 1623 2781 1600 2781 1626 64 1627 64 1628 64 1627 64 1629 64 1630 64 1629 2782 1618 2782 1630 2782 1631 2783 1453 2783 1632 2783 1633 2784 1634 2784 1631 2784 1631 2785 1635 2785 1453 2785 1635 2786 1452 2786 1453 2786 1635 2787 1631 2787 1636 2787 1631 2788 1634 2788 1636 2788 1451 2789 1452 2789 1635 2789 1636 2790 1637 2790 1635 2790 1635 2791 1638 2791 1451 2791 1638 2792 1472 2792 1451 2792 1638 2793 1635 2793 1639 2793 1635 2794 1637 2794 1639 2794 1473 2795 1472 2795 1638 2795 1639 2796 1640 2796 1638 2796 1638 2797 1641 2797 1473 2797 1638 2798 1640 2798 1642 2798 1451 2799 1472 2799 1450 2799 1643 2800 1644 2800 1628 2800 1644 2801 1643 2801 1645 2801 1643 2802 1646 2802 1645 2802 1628 2803 1630 2803 1643 2803 1647 2804 1646 2804 1643 2804 1643 2805 1610 2805 1647 2805 1610 2806 1643 2806 1608 2806 1643 2807 1603 2807 1608 2807 1643 2808 1630 2808 1603 2808 1647 2809 1610 2809 1624 2809 1595 2810 1598 2810 1596 2810 1598 2811 1595 2811 1648 2811 1598 2812 1649 2812 1597 2812 1649 2813 1598 2813 1648 2813 1648 2814 1646 2814 1649 2814 1645 2815 1646 2815 1648 2815 1599 2816 1597 2816 1649 2816 1649 2817 1650 2817 1599 2817 1650 2818 1649 2818 1646 2818 1646 2819 1647 2819 1650 2819 1623 2820 1599 2820 1650 2820 1650 2821 1624 2821 1623 2821 1624 2822 1650 2822 1647 2822 1626 64 1628 64 1651 64 1627 2823 1630 2823 1628 2823 1618 2824 1620 2824 1630 2824 1620 64 1604 64 1630 64 1630 2825 1604 2825 1603 2825 1652 2826 1653 2826 1654 2826 1447 2827 1655 2827 1632 2827 1632 2828 1655 2828 1656 2828 1657 2829 1632 2829 1656 2829 1658 2830 1659 2830 1632 2830 1657 2831 1658 2831 1632 2831 1660 2832 1659 2832 1658 2832 1661 2833 1660 2833 1658 2833 1662 2834 1661 2834 1658 2834 1658 2835 1663 2835 1662 2835 1631 2836 1660 2836 1633 2836 1631 2837 1632 2837 1659 2837 1660 2838 1631 2838 1659 2838 1633 2839 1660 2839 1661 2839 1633 2840 1661 2840 1662 2840 1632 2841 1453 2841 1447 2841 1664 2842 1665 2842 1666 2842 1653 64 1667 64 1654 64 1667 64 1626 64 1654 64 1651 2843 1654 2843 1626 2843 1668 2844 1669 2844 1670 2844 1641 2845 1474 2845 1473 2845 1641 2846 1638 2846 1642 2846 1476 2847 1474 2847 1641 2847 1642 2848 1671 2848 1641 2848 1641 2849 1672 2849 1476 2849 1672 2850 1479 2850 1476 2850 1672 2851 1641 2851 1673 2851 1641 2852 1671 2852 1673 2852 1485 2853 1479 2853 1672 2853 1673 2854 1674 2854 1672 2854 1675 2855 1672 2855 1676 2855 1672 2856 1674 2856 1676 2856 1672 2857 1675 2857 1485 2857 1675 2858 1489 2858 1485 2858 1677 2859 1489 2859 1675 2859 1676 2860 1678 2860 1675 2860 1679 2861 1680 2861 1675 2861 1680 2862 1681 2862 1675 2862 1681 2863 1677 2863 1675 2863 1679 2864 1675 2864 1678 2864 1678 2865 1682 2865 1679 2865 1682 2866 1683 2866 1684 2866 1684 2867 1679 2867 1682 2867 1485 2868 1489 2868 1488 2868 1685 2869 1490 2869 1489 2869 1489 2870 1677 2870 1685 2870 1686 2871 1687 2871 1688 2871 1689 2872 1690 2872 1686 2872 1691 2873 1692 2873 1693 2873 1691 2874 1694 2874 1689 2874 1695 2875 1692 2875 1691 2875 1688 2876 1696 2876 1686 2876 1697 2877 1686 2877 1696 2877 1686 2878 1697 2878 1689 2878 1689 2879 1698 2879 1691 2879 1698 2880 1689 2880 1697 2880 1699 2881 1691 2881 1698 2881 1691 2882 1699 2882 1695 2882 1699 2883 1700 2883 1695 2883 1696 2884 1701 2884 1697 2884 1702 2885 1697 2885 1701 2885 1697 2886 1702 2886 1698 2886 1698 2887 1703 2887 1699 2887 1703 2888 1698 2888 1702 2888 1704 2889 1700 2889 1699 2889 1699 2890 1705 2890 1704 2890 1705 2891 1706 2891 1704 2891 1705 2892 1699 2892 1703 2892 1701 2893 1707 2893 1702 2893 1702 2894 1708 2894 1703 2894 1708 2895 1702 2895 1709 2895 1702 2896 1707 2896 1709 2896 1703 2897 1710 2897 1705 2897 1710 2898 1703 2898 1708 2898 1711 2899 1706 2899 1705 2899 1712 2900 1705 2900 1710 2900 1705 2901 1712 2901 1711 2901 1712 2902 1713 2902 1711 2902 1709 2903 1714 2903 1708 2903 1708 2904 1715 2904 1710 2904 1715 2905 1708 2905 1714 2905 1710 2906 1716 2906 1712 2906 1716 2907 1710 2907 1715 2907 1714 2908 1717 2908 1715 2908 1715 2909 1718 2909 1719 2909 1715 2910 1717 2910 1718 2910 1715 2911 1719 2911 1716 2911 1712 2912 1716 2912 1720 2912 1716 2913 1719 2913 1720 2913 1721 2914 1722 2914 1522 2914 1722 2915 1523 2915 1522 2915 1722 2916 1721 2916 1723 2916 1522 2917 1724 2917 1721 2917 1670 2918 1721 2918 1668 2918 1721 2919 1724 2919 1668 2919 1721 2920 1670 2920 1723 2920 1713 2921 1723 2921 1711 2921 1723 2922 1725 2922 1711 2922 1725 2923 1723 2923 1669 2923 1723 2924 1670 2924 1669 2924 1706 2925 1711 2925 1725 2925 1669 2926 1726 2926 1725 2926 1725 2927 1727 2927 1706 2927 1727 2928 1704 2928 1706 2928 1727 2929 1725 2929 1728 2929 1725 2930 1726 2930 1728 2930 1728 2931 1729 2931 1727 2931 1700 2932 1704 2932 1727 2932 1730 2933 1727 2933 1731 2933 1727 2934 1729 2934 1731 2934 1727 2935 1730 2935 1700 2935 1730 2936 1695 2936 1700 2936 1731 2937 1732 2937 1730 2937 1692 2938 1695 2938 1730 2938 1730 2939 1732 2939 1733 2939 1730 2940 1733 2940 1692 2940 1692 2941 1733 2941 1734 2941 1728 2942 1726 2942 1683 2942 1726 2943 1684 2943 1683 2943 1679 2944 1684 2944 1726 2944 1726 2945 1669 2945 1679 2945 1680 2946 1679 2946 1669 2946 1669 2947 1668 2947 1680 2947 1668 2948 1681 2948 1680 2948 1677 2949 1681 2949 1668 2949 1668 2950 1724 2950 1677 2950 1685 2951 1677 2951 1724 2951 1724 2952 1522 2952 1685 2952 1490 2953 1685 2953 1522 2953 1718 2954 1735 2954 1719 2954 1735 2955 1720 2955 1719 2955 1644 2956 1712 2956 1720 2956 1644 2957 1713 2957 1712 2957 1644 2958 1736 2958 1713 2958 1644 2959 1645 2959 1736 2959 1644 2960 1720 2960 1735 2960 1735 2961 1651 2961 1644 2961 1644 2962 1651 2962 1628 2962 1592 2963 1523 2963 1722 2963 1737 2964 1722 2964 1723 2964 1722 2965 1737 2965 1592 2965 1593 2966 1592 2966 1737 2966 1713 2967 1736 2967 1723 2967 1736 2968 1737 2968 1723 2968 1737 2969 1645 2969 1648 2969 1737 2970 1736 2970 1645 2970 1737 2971 1648 2971 1593 2971 1595 2972 1593 2972 1648 2972 1634 2973 1633 2973 1733 2973 1733 2974 1732 2974 1634 2974 1636 581 1634 581 1732 581 1732 2975 1731 2975 1636 2975 1637 581 1636 581 1731 581 1731 2976 1729 2976 1637 2976 1639 2977 1637 2977 1683 2977 1637 2978 1729 2978 1683 2978 1729 2979 1728 2979 1683 2979 1683 581 1682 581 1639 581 1640 2980 1639 2980 1682 2980 1682 2981 1678 2981 1640 2981 1642 581 1640 581 1678 581 1678 581 1676 581 1642 581 1671 581 1642 581 1676 581 1676 581 1674 581 1671 581 1673 581 1671 581 1674 581 1707 64 1701 64 1738 64 1709 64 1707 64 1739 64 1714 64 1709 64 1740 64 1717 64 1714 64 1741 64 1742 64 1718 64 1717 64 1735 2982 1718 2982 1654 2982 1718 64 1742 64 1654 64 1741 2983 1742 2983 1717 2983 1740 64 1741 64 1714 64 1739 64 1740 64 1709 64 1738 2984 1739 2984 1707 2984 1743 2985 1738 2985 1701 2985 1701 64 1696 64 1743 64 1744 64 1743 64 1696 64 1696 2986 1688 2986 1744 2986 1745 2987 1744 2987 1688 2987 1688 64 1746 64 1745 64 1747 64 1745 64 1746 64 1733 2988 1633 2988 1662 2988 1748 2989 1733 2989 1662 2989 1663 2990 1749 2990 1750 2990 1663 2991 1750 2991 1751 2991 1663 2992 1751 2992 1752 2992 1663 2993 1752 2993 1753 2993 1663 2994 1753 2994 1754 2994 1663 2995 1754 2995 1755 2995 1663 2996 1755 2996 1756 2996 1663 2997 1756 2997 1757 2997 1663 2998 1757 2998 1748 2998 1662 2999 1663 2999 1748 2999 1758 3000 1749 3000 1663 3000 1757 3001 1759 3001 1760 3001 1748 3002 1757 3002 1760 3002 1761 3003 1759 3003 1757 3003 1757 3004 1756 3004 1761 3004 1762 3005 1761 3005 1756 3005 1756 3006 1755 3006 1762 3006 1763 3007 1762 3007 1755 3007 1755 3008 1754 3008 1763 3008 1764 3009 1763 3009 1754 3009 1754 3010 1753 3010 1764 3010 1765 3011 1764 3011 1753 3011 1753 3012 1752 3012 1765 3012 1751 3013 1750 3013 1766 3013 1750 3014 1749 3014 1766 3014 1767 3015 1768 3015 1758 3015 1759 3016 1769 3016 1770 3016 1760 3017 1759 3017 1770 3017 1771 3018 1745 3018 1747 3018 1771 3019 1747 3019 1772 3019 1771 3020 1772 3020 1773 3020 1774 3021 1771 3021 1773 3021 1774 3022 1773 3022 1775 3022 1774 3023 1775 3023 1776 3023 1769 3024 1774 3024 1776 3024 1774 3025 1769 3025 1759 3025 1759 3026 1761 3026 1774 3026 1744 3027 1745 3027 1771 3027 1777 3028 1743 3028 1744 3028 1771 3029 1777 3029 1744 3029 1777 3030 1771 3030 1774 3030 1774 3031 1761 3031 1762 3031 1778 3032 1774 3032 1762 3032 1774 3033 1778 3033 1777 3033 1762 3034 1763 3034 1778 3034 1738 3035 1743 3035 1777 3035 1779 3036 1777 3036 1778 3036 1777 3037 1779 3037 1738 3037 1778 3038 1780 3038 1779 3038 1778 3039 1763 3039 1764 3039 1780 3040 1778 3040 1764 3040 1739 3041 1738 3041 1779 3041 1764 3042 1765 3042 1780 3042 1781 3043 1779 3043 1780 3043 1781 3044 1740 3044 1739 3044 1779 3045 1781 3045 1739 3045 1780 3046 1782 3046 1781 3046 1780 3047 1765 3047 1766 3047 1780 3048 1766 3048 1782 3048 1741 3049 1740 3049 1781 3049 1783 3050 1781 3050 1782 3050 1781 3051 1783 3051 1741 3051 1742 3052 1741 3052 1783 3052 1782 3053 1766 3053 1768 3053 1782 3054 1784 3054 1785 3054 1783 3055 1786 3055 1787 3055 1788 3056 1783 3056 1787 3056 1783 3057 1788 3057 1742 3057 1742 3058 1788 3058 1789 3058 1654 3059 1742 3059 1789 3059 1692 3060 1734 3060 1790 3060 1693 3061 1692 3061 1790 3061 1691 3062 1693 3062 1791 3062 1694 3063 1691 3063 1791 3063 1689 3064 1694 3064 1690 3064 1686 3065 1690 3065 1687 3065 1688 3066 1687 3066 1792 3066 1746 3067 1688 3067 1792 3067 1693 3068 1790 3068 1760 3068 1760 3069 1790 3069 1734 3069 1760 3070 1734 3070 1733 3070 1748 3071 1760 3071 1733 3071 1746 3072 1792 3072 1747 3072 1772 3073 1747 3073 1792 3073 1792 3074 1687 3074 1772 3074 1773 3075 1772 3075 1687 3075 1687 3076 1690 3076 1773 3076 1775 3077 1773 3077 1690 3077 1776 3078 1775 3078 1690 3078 1690 3079 1694 3079 1776 3079 1769 3080 1776 3080 1694 3080 1694 3081 1791 3081 1769 3081 1770 3082 1769 3082 1791 3082 1791 3083 1693 3083 1770 3083 1760 3084 1770 3084 1693 3084 1786 3085 1782 3085 1785 3085 1786 3086 1783 3086 1782 3086 1767 3087 1784 3087 1768 3087 1768 3088 1784 3088 1782 3088 1758 3089 1768 3089 1749 3089 1749 3090 1768 3090 1766 3090 1751 3091 1766 3091 1765 3091 1751 3092 1765 3092 1752 3092 1651 3093 1735 3093 1654 3093 1793 3094 1663 3094 1658 3094 1794 3095 1627 3095 1626 3095 1795 64 1796 64 1654 64 1797 3096 1795 3096 1654 3096 1627 3097 1794 3097 1798 3097 1664 3098 1799 3098 1800 3098 1664 3099 1800 3099 1798 3099 1798 3100 1794 3100 1664 3100 1664 3101 1794 3101 1626 3101 1664 182 1626 182 1801 182 1801 3102 1802 3102 1803 3102 1801 182 1626 182 1802 182 1796 64 1652 64 1654 64 1623 3103 1804 3103 1600 3103 1805 3104 1614 3104 1806 3104 1806 3105 1807 3105 1805 3105 1611 3106 1805 3106 1807 3106 1807 3107 1625 3107 1611 3107 1808 3108 1809 3108 1810 3108 1811 3109 1806 3109 1614 3109 1811 3110 1614 3110 1812 3110 1811 3111 1812 3111 1809 3111 1809 3112 1808 3112 1813 3112 1811 3113 1809 3113 1813 3113 1807 3114 1806 3114 1811 3114 1813 3115 1814 3115 1811 3115 1622 3116 1625 3116 1807 3116 1811 3117 1622 3117 1807 3117 1622 3118 1811 3118 1814 3118 1814 3119 1815 3119 1622 3119 1623 3120 1622 3120 1815 3120 1815 3121 1804 3121 1623 3121 1816 3122 1817 3122 1818 3122 1818 3123 1815 3123 1819 3123 1818 3124 1817 3124 1804 3124 1818 3125 1804 3125 1815 3125 1819 3126 1815 3126 1814 3126 1819 3127 1814 3127 1820 3127 1820 3128 1814 3128 1813 3128 1821 3129 1813 3129 1808 3129 1600 3130 1804 3130 1817 3130 1590 3131 1817 3131 1816 3131 1588 3132 1600 3132 1817 3132 1822 3133 1823 3133 1616 3133 1822 3134 1616 3134 1613 3134 1621 3135 1822 3135 1613 3135 1824 3136 1823 3136 1822 3136 1825 3137 1822 3137 1621 3137 1822 3138 1825 3138 1824 3138 1621 3139 1619 3139 1825 3139 1826 3140 1824 3140 1825 3140 1825 3141 1827 3141 1826 3141 1827 3142 1825 3142 1619 3142 1619 3143 1828 3143 1827 3143 1828 3144 1619 3144 1618 3144 1829 3145 1826 3145 1827 3145 1618 3146 1830 3146 1828 3146 1830 3147 1618 3147 1629 3147 1831 3148 1829 3148 1827 3148 1831 3149 1827 3149 1828 3149 1629 3150 1627 3150 1830 3150 1799 3151 1831 3151 1828 3151 1828 3152 1800 3152 1799 3152 1800 3153 1828 3153 1830 3153 1798 3154 1830 3154 1627 3154 1830 3155 1798 3155 1800 3155 1664 3156 1829 3156 1831 3156 1664 3157 1831 3157 1799 3157 1829 3158 1606 3158 1826 3158 1824 3159 1826 3159 1606 3159 1823 3160 1824 3160 1606 3160 1606 3161 1832 3161 1823 3161 1823 3162 1832 3162 1833 3162 1616 3163 1823 3163 1833 3163 1834 3164 1616 3164 1833 3164 1835 3165 1834 3165 1833 3165 1833 3166 1836 3166 1835 3166 1835 3167 1836 3167 1837 3167 1834 3168 1835 3168 1838 3168 1838 3169 1614 3169 1834 3169 1616 3170 1834 3170 1614 3170 1614 3171 1805 3171 1615 3171 1839 3172 1613 3172 1616 3172 1839 3173 1616 3173 1615 3173 1839 3174 1615 3174 1805 3174 1839 3175 1609 3175 1613 3175 1839 3176 1805 3176 1611 3176 1609 3177 1839 3177 1611 3177 1840 3178 1841 3178 1821 3178 1842 3179 1821 3179 1808 3179 1821 3180 1842 3180 1840 3180 1808 3181 1810 3181 1842 3181 1843 3182 1842 3182 1810 3182 1843 3183 1844 3183 1840 3183 1842 3184 1843 3184 1840 3184 1810 3185 1809 3185 1843 3185 1845 3186 1843 3186 1809 3186 1843 3187 1845 3187 1844 3187 1809 3188 1812 3188 1845 3188 1838 3189 1837 3189 1844 3189 1845 3190 1838 3190 1844 3190 1845 3191 1812 3191 1614 3191 1845 3192 1614 3192 1838 3192 1837 3193 1838 3193 1835 3193 1846 3194 1847 3194 1848 3194 1846 3195 1841 3195 1840 3195 1847 3196 1846 3196 1840 3196 1848 3197 1607 3197 1467 3197 1607 3198 1848 3198 1847 3198 1465 3199 1467 3199 1607 3199 1847 3200 1849 3200 1607 3200 1471 3201 1607 3201 1849 3201 1849 3202 1606 3202 1471 3202 1832 3203 1606 3203 1849 3203 1833 3204 1832 3204 1849 3204 1849 3205 1836 3205 1833 3205 1849 3206 1844 3206 1837 3206 1849 3207 1837 3207 1836 3207 1840 3208 1849 3208 1847 3208 1840 3209 1844 3209 1849 3209 1664 3210 1606 3210 1829 3210 1664 3211 1441 3211 1606 3211 1850 3212 1851 3212 1852 3212 1853 3213 1851 3213 1850 3213 1850 3214 1854 3214 1853 3214 1854 3215 1855 3215 1853 3215 1856 3216 1855 3216 1854 3216 1857 3217 1856 3217 1854 3217 1854 3218 1858 3218 1857 3218 1859 3219 1857 3219 1858 3219 1860 3220 1859 3220 1858 3220 1861 3221 1862 3221 1860 3221 1863 3222 1862 3222 1861 3222 1470 3223 1467 3223 1468 3223 1864 3224 1470 3224 1469 3224 1469 3225 1520 3225 1864 3225 1865 3226 1864 3226 1520 3226 1520 3227 1521 3227 1865 3227 1866 3228 1865 3228 1521 3228 1521 3229 1867 3229 1866 3229 1868 3230 1866 3230 1867 3230 1867 3231 1869 3231 1868 3231 1870 3232 1868 3232 1871 3232 1852 3233 1872 3233 1850 3233 1873 3234 1874 3234 1852 3234 1874 3235 1873 3235 1875 3235 1876 3236 1877 3236 1878 3236 1876 3237 1879 3237 1877 3237 1876 3238 1875 3238 1879 3238 1878 3239 1880 3239 1881 3239 1882 3240 1881 3240 1883 3240 1883 3241 1884 3241 1882 3241 1881 3242 1885 3242 1883 3242 1881 3243 1880 3243 1885 3243 1886 3244 1887 3244 1884 3244 1887 3245 1882 3245 1884 3245 1888 3246 1882 3246 1887 3246 1887 3247 1889 3247 1888 3247 1889 3248 1890 3248 1891 3248 1890 3249 1892 3249 1893 3249 1893 3250 1892 3250 1870 3250 1467 3251 1470 3251 1848 3251 1894 3252 1841 3252 1846 3252 1895 3253 1848 3253 1864 3253 1848 3254 1470 3254 1864 3254 1848 3255 1895 3255 1846 3255 1896 3256 1846 3256 1895 3256 1846 3257 1896 3257 1894 3257 1896 3258 1897 3258 1894 3258 1864 3259 1865 3259 1895 3259 1898 3260 1897 3260 1896 3260 1899 3261 1895 3261 1866 3261 1895 3262 1865 3262 1866 3262 1895 3263 1899 3263 1896 3263 1900 3264 1896 3264 1899 3264 1896 3265 1900 3265 1898 3265 1900 3266 1901 3266 1898 3266 1866 3267 1868 3267 1899 3267 1902 3268 1901 3268 1900 3268 1899 3269 1890 3269 1900 3269 1899 3270 1892 3270 1890 3270 1899 3271 1870 3271 1892 3271 1899 3272 1868 3272 1870 3272 1886 3273 1900 3273 1887 3273 1900 3274 1889 3274 1887 3274 1900 3275 1890 3275 1889 3275 1900 3276 1886 3276 1902 3276 1903 3277 1904 3277 1905 3277 1903 3278 1906 3278 1904 3278 1903 3279 1907 3279 1906 3279 1906 3280 1908 3280 1904 3280 1908 3281 1905 3281 1904 3281 1908 3282 1909 3282 1905 3282 1910 3283 1911 3283 1909 3283 1910 3284 1909 3284 1908 3284 1908 3285 1912 3285 1910 3285 1913 3286 1910 3286 1912 3286 1910 3287 1913 3287 1914 3287 1912 3288 1915 3288 1913 3288 1913 3289 1916 3289 1917 3289 1913 3290 1918 3290 1916 3290 1913 3291 1919 3291 1918 3291 1913 3292 1915 3292 1919 3292 1920 3293 1921 3293 1821 3293 1920 3294 1821 3294 1841 3294 1841 3295 1894 3295 1920 3295 1922 3296 1921 3296 1920 3296 1923 3297 1920 3297 1894 3297 1920 3298 1923 3298 1922 3298 1894 3299 1897 3299 1923 3299 1924 3300 1922 3300 1923 3300 1925 3301 1923 3301 1897 3301 1923 3302 1925 3302 1924 3302 1897 3303 1898 3303 1925 3303 1926 3304 1924 3304 1925 3304 1927 3305 1925 3305 1898 3305 1925 3306 1927 3306 1926 3306 1928 3307 1926 3307 1927 3307 1898 3308 1901 3308 1927 3308 1927 3309 1929 3309 1928 3309 1929 3310 1927 3310 1901 3310 1930 3311 1928 3311 1929 3311 1901 3312 1902 3312 1929 3312 1931 3313 1929 3313 1902 3313 1929 3314 1931 3314 1930 3314 1919 3315 1930 3315 1931 3315 1902 3316 1886 3316 1931 3316 1931 3317 1932 3317 1919 3317 1932 3318 1931 3318 1884 3318 1931 3319 1886 3319 1884 3319 1918 3320 1919 3320 1932 3320 1884 3321 1883 3321 1932 3321 1932 3322 1933 3322 1918 3322 1933 3323 1916 3323 1918 3323 1933 3324 1932 3324 1883 3324 1883 3325 1885 3325 1933 3325 1933 3326 1880 3326 1916 3326 1880 3327 1934 3327 1916 3327 1933 3328 1885 3328 1880 3328 1880 3329 1878 3329 1934 3329 1878 3330 1877 3330 1934 3330 1877 3331 1879 3331 1934 3331 1590 3332 1583 3332 1588 3332 1582 3333 1935 3333 1584 3333 1935 3334 1582 3334 1590 3334 1936 3335 1584 3335 1935 3335 1584 3336 1936 3336 1586 3336 1937 3337 1586 3337 1936 3337 1586 3338 1937 3338 1938 3338 1937 3339 1939 3339 1938 3339 1588 3340 1817 3340 1590 3340 1590 3341 1940 3341 1935 3341 1940 3342 1590 3342 1941 3342 1590 3343 1816 3343 1941 3343 1942 3344 1935 3344 1943 3344 1935 3345 1940 3345 1943 3345 1935 3346 1942 3346 1936 3346 1936 3347 1944 3347 1937 3347 1936 3348 1945 3348 1944 3348 1936 3349 1942 3349 1945 3349 1907 3350 1939 3350 1937 3350 1946 3351 1937 3351 1947 3351 1937 3352 1948 3352 1947 3352 1937 3353 1944 3353 1948 3353 1937 3354 1946 3354 1907 3354 1906 3355 1907 3355 1949 3355 1907 3356 1946 3356 1949 3356 1820 3357 1813 3357 1821 3357 1821 3358 1921 3358 1820 3358 1820 3359 1950 3359 1819 3359 1950 3360 1820 3360 1922 3360 1820 3361 1921 3361 1922 3361 1951 3362 1819 3362 1950 3362 1819 3363 1951 3363 1818 3363 1952 3364 1818 3364 1951 3364 1818 3365 1952 3365 1816 3365 1952 3366 1941 3366 1816 3366 1940 3367 1941 3367 1952 3367 1922 3368 1924 3368 1950 3368 1950 3369 1953 3369 1951 3369 1953 3370 1950 3370 1924 3370 1954 3371 1951 3371 1953 3371 1951 3372 1954 3372 1952 3372 1952 3373 1955 3373 1940 3373 1955 3374 1943 3374 1940 3374 1955 3375 1952 3375 1954 3375 1942 3376 1943 3376 1955 3376 1924 3377 1926 3377 1953 3377 1953 3378 1956 3378 1954 3378 1956 3379 1953 3379 1926 3379 1954 3380 1957 3380 1955 3380 1957 3381 1954 3381 1956 3381 1958 3382 1955 3382 1957 3382 1955 3383 1958 3383 1942 3383 1958 3384 1945 3384 1942 3384 1958 3385 1944 3385 1945 3385 1926 3386 1928 3386 1956 3386 1948 3387 1944 3387 1958 3387 1959 3388 1956 3388 1928 3388 1956 3389 1959 3389 1957 3389 1957 3390 1960 3390 1958 3390 1960 3391 1957 3391 1959 3391 1958 3392 1961 3392 1948 3392 1961 3393 1947 3393 1948 3393 1961 3394 1958 3394 1960 3394 1928 3395 1930 3395 1959 3395 1946 3396 1947 3396 1961 3396 1959 3397 1915 3397 1960 3397 1959 3398 1919 3398 1915 3398 1959 3399 1930 3399 1919 3399 1960 3400 1915 3400 1912 3400 1960 3401 1912 3401 1961 3401 1961 3402 1908 3402 1946 3402 1908 3403 1949 3403 1946 3403 1961 3404 1912 3404 1908 3404 1906 3405 1949 3405 1908 3405 1962 3406 1853 3406 1855 3406 1962 3407 1851 3407 1853 3407 1962 3408 1852 3408 1851 3408 1962 3409 1873 3409 1852 3409 1962 3410 1875 3410 1873 3410 1934 3411 1879 3411 1875 3411 1963 3412 1964 3412 1965 3412 1963 3413 1965 3413 1966 3413 1967 3414 1963 3414 1966 3414 1938 3415 1968 3415 1586 3415 1585 3416 1586 3416 1968 3416 1968 3417 1969 3417 1585 3417 1585 3418 1970 3418 1580 3418 1970 3419 1585 3419 1969 3419 1969 3420 1971 3420 1970 3420 1972 3421 1556 3421 1557 3421 1973 3422 1972 3422 1557 3422 1974 3423 1973 3423 1557 3423 1974 3424 1557 3424 1975 3424 1976 3425 1974 3425 1975 3425 1977 3426 1976 3426 1975 3426 1978 3427 1977 3427 1975 3427 1979 3428 1978 3428 1975 3428 1980 3429 1978 3429 1979 3429 1910 3430 1981 3430 1911 3430 1982 3431 1909 3431 1911 3431 1982 3432 1911 3432 1981 3432 1982 3433 1981 3433 1983 3433 1909 3434 1903 3434 1905 3434 1903 3435 1909 3435 1982 3435 1939 3436 1907 3436 1903 3436 1983 3437 1984 3437 1982 3437 1982 3438 1985 3438 1903 3438 1985 3439 1982 3439 1984 3439 1986 3440 1903 3440 1985 3440 1903 3441 1986 3441 1939 3441 1938 3442 1939 3442 1986 3442 1984 3443 1987 3443 1985 3443 1988 3444 1985 3444 1987 3444 1985 3445 1988 3445 1986 3445 1987 3446 1989 3446 1988 3446 1990 3447 1968 3447 1938 3447 1986 3448 1990 3448 1938 3448 1990 3449 1986 3449 1988 3449 1969 3450 1968 3450 1990 3450 1988 3451 1991 3451 1990 3451 1988 3452 1989 3452 1992 3452 1991 3453 1988 3453 1992 3453 1992 3454 1993 3454 1991 3454 1994 3455 1990 3455 1991 3455 1990 3456 1994 3456 1969 3456 1971 3457 1969 3457 1994 3457 1995 3458 1991 3458 1993 3458 1991 3459 1995 3459 1994 3459 1993 3460 1996 3460 1995 3460 1994 3461 1997 3461 1971 3461 1997 3462 1994 3462 1995 3462 1995 3463 1996 3463 1998 3463 1999 581 1993 581 2000 581 1993 581 1999 581 1967 581 1993 3464 1967 3464 1966 3464 1993 3465 1966 3465 2001 3465 1996 3466 1993 3466 2001 3466 2002 3467 1964 3467 2003 3467 2004 3468 2003 3468 1964 3468 2002 3469 2005 3469 1964 3469 1965 3470 1964 3470 2005 3470 2005 3471 2001 3471 1965 3471 1966 3472 1965 3472 2001 3472 2006 3473 2007 3473 2008 3473 2009 3474 2008 3474 2007 3474 2007 3475 2010 3475 2009 3475 2011 3476 2009 3476 2010 3476 2010 3477 2012 3477 2011 3477 2013 3478 2011 3478 2012 3478 2012 3479 2014 3479 2013 3479 2015 3480 2013 3480 2014 3480 2014 3481 2016 3481 2015 3481 2017 3482 2015 3482 2016 3482 2016 3483 2018 3483 2017 3483 2019 3484 2017 3484 2018 3484 2018 3485 1980 3485 2019 3485 1979 3486 2019 3486 1980 3486 1980 3487 2018 3487 1978 3487 2020 3488 1978 3488 2018 3488 2020 3489 2021 3489 1976 3489 2020 3490 1976 3490 1977 3490 1978 3491 2020 3491 1977 3491 2022 3492 2021 3492 2020 3492 2018 3493 2016 3493 2020 3493 2020 3494 2016 3494 2014 3494 2023 3495 2020 3495 2014 3495 2023 3496 2024 3496 2022 3496 2020 3497 2023 3497 2022 3497 2025 3498 2024 3498 2023 3498 2014 3499 2012 3499 2023 3499 2023 3500 2012 3500 2010 3500 2026 3501 2023 3501 2010 3501 2026 3502 2027 3502 2025 3502 2023 3503 2026 3503 2025 3503 2028 3504 2027 3504 2026 3504 2010 3505 2007 3505 2026 3505 2026 3506 2029 3506 2028 3506 2026 3507 2007 3507 2006 3507 2026 3508 2006 3508 2030 3508 2026 3509 2030 3509 2031 3509 2029 3510 2026 3510 2031 3510 2028 3511 2029 3511 2032 3511 2033 3512 2028 3512 2032 3512 1871 3513 2034 3513 2033 3513 2028 3514 2033 3514 2034 3514 2034 3515 2035 3515 2028 3515 2027 3516 2028 3516 2035 3516 2035 3517 2036 3517 2027 3517 2025 3518 2027 3518 2036 3518 2036 3519 2037 3519 2025 3519 2024 3520 2025 3520 2037 3520 2037 3521 2038 3521 2024 3521 2022 3522 2024 3522 2038 3522 2038 3523 2039 3523 2022 3523 2021 3524 2022 3524 2039 3524 2039 3525 1974 3525 2021 3525 1976 3526 2021 3526 1974 3526 1869 3527 2035 3527 2034 3527 1871 3528 1869 3528 2034 3528 2040 3529 2038 3529 2037 3529 2040 3530 2037 3530 2036 3530 2035 3531 2040 3531 2036 3531 2040 3532 2035 3532 1869 3532 2041 3533 1973 3533 1974 3533 2041 3534 1974 3534 2039 3534 2041 3535 2039 3535 2038 3535 2041 3536 2038 3536 2040 3536 1869 3537 1867 3537 2040 3537 1972 3538 1973 3538 2041 3538 2040 3539 1867 3539 1521 3539 1519 3540 2040 3540 1521 3540 2040 3541 1519 3541 2041 3541 1517 3542 1556 3542 1972 3542 2041 3543 1517 3543 1972 3543 1517 3544 2041 3544 1519 3544 1518 3545 1556 3545 1517 3545 2042 3546 1893 3546 1870 3546 1893 3547 1891 3547 1890 3547 1891 3548 1888 3548 1889 3548 1881 3549 1876 3549 1878 3549 2006 3550 2043 3550 2044 3550 2008 3551 2043 3551 2006 3551 2033 3552 2032 3552 2042 3552 2045 3553 2042 3553 2032 3553 2032 3554 2029 3554 2045 3554 2046 3555 2045 3555 2029 3555 2029 3556 2031 3556 2046 3556 2047 3557 2046 3557 2031 3557 2031 3558 2030 3558 2047 3558 2048 3559 2047 3559 2030 3559 2030 3560 2006 3560 2048 3560 2044 3561 2048 3561 2006 3561 2042 3562 1870 3562 2033 3562 1871 3563 2033 3563 1870 3563 1868 3564 1869 3564 1871 3564 2049 3565 2050 3565 2051 3565 1989 3566 2052 3566 2053 3566 1992 3567 1989 3567 2053 3567 2054 3568 2049 3568 2051 3568 2054 3569 2051 3569 2055 3569 2052 3570 2054 3570 2055 3570 2054 3571 2052 3571 1989 3571 2056 3572 2049 3572 2054 3572 2056 3573 2057 3573 2049 3573 1989 3574 1987 3574 2054 3574 2054 3575 2058 3575 2056 3575 2058 3576 2054 3576 1987 3576 2059 3577 2057 3577 2056 3577 2056 3578 2060 3578 2059 3578 2060 3579 2056 3579 2058 3579 1987 3580 1984 3580 2058 3580 2061 3581 2059 3581 2060 3581 2058 3582 2062 3582 2060 3582 2062 3583 2058 3583 1984 3583 1984 3584 1983 3584 2062 3584 2063 3585 2060 3585 2062 3585 2064 3586 2065 3586 2050 3586 2051 3587 2050 3587 2065 3587 2065 3588 2066 3588 2051 3588 2055 3589 2051 3589 2066 3589 2066 3590 2067 3590 2055 3590 2052 3591 2055 3591 2067 3591 2067 3592 2068 3592 2052 3592 2053 3593 2052 3593 2068 3593 2069 3594 1992 3594 2053 3594 2068 3595 2069 3595 2053 3595 1993 3596 1992 3596 2069 3596 2069 3597 2070 3597 1993 3597 2070 3598 2071 3598 1993 3598 1993 581 2071 581 2000 581 1801 3599 1975 3599 1557 3599 1801 3600 1557 3600 2072 3600 2073 3601 2074 3601 2075 3601 2075 3602 2074 3602 2076 3602 2076 3603 2074 3603 2077 3603 2078 3604 2076 3604 2077 3604 2079 3605 2078 3605 2077 3605 2079 3606 2077 3606 2080 3606 2081 3607 2079 3607 2080 3607 2081 3608 2080 3608 2082 3608 2083 3609 2081 3609 2082 3609 2083 3610 2082 3610 2084 3610 2085 3611 2083 3611 2084 3611 2085 3612 2084 3612 2086 3612 2087 3613 2085 3613 2086 3613 2087 3614 2086 3614 2088 3614 2087 3615 2088 3615 2089 3615 2090 3616 2089 3616 2088 3616 2091 3617 2092 3617 2093 3617 2094 64 2095 64 2096 64 2097 64 2096 64 2095 64 2074 3618 2098 3618 2077 3618 2099 3619 2100 3619 2098 3619 2098 3620 2074 3620 2099 3620 2074 3621 2101 3621 2099 3621 2074 3622 2073 3622 2101 3622 2100 3623 2091 3623 2093 3623 2093 3624 2098 3624 2100 3624 2093 3625 2102 3625 2103 3625 2093 3626 2092 3626 2102 3626 2104 3627 2093 3627 2103 3627 2093 3628 2104 3628 2098 3628 2104 3629 2105 3629 2098 3629 2106 3630 2107 3630 2108 3630 2108 3631 2103 3631 2106 3631 2103 3632 2102 3632 2106 3632 2103 3633 2108 3633 2104 3633 2108 3634 2105 3634 2104 3634 2108 3635 2098 3635 2105 3635 2077 3636 2098 3636 2108 3636 2108 3637 2109 3637 2077 3637 2080 3638 2077 3638 2109 3638 2109 3639 2110 3639 2080 3639 2082 64 2080 64 2110 64 2084 3640 2082 3640 2111 3640 2112 64 2086 64 2084 64 2088 64 2086 64 2112 64 2078 3641 2113 3641 1570 3641 1570 3642 2114 3642 2078 3642 2114 3643 2076 3643 2078 3643 2076 3644 2114 3644 2115 3644 2075 3645 2116 3645 2117 3645 2076 3646 2116 3646 2075 3646 2118 3647 2119 3647 2120 3647 2119 3648 2121 3648 2120 3648 2122 3649 2121 3649 2119 3649 2119 3650 2123 3650 2122 3650 2124 3651 2122 3651 2123 3651 2123 3652 2125 3652 2124 3652 2126 3653 2124 3653 2125 3653 2125 3654 2127 3654 2126 3654 2128 3655 2126 3655 2127 3655 2127 3656 2129 3656 2101 3656 2101 3657 2128 3657 2127 3657 2129 3658 2099 3658 2101 3658 2129 3659 2100 3659 2099 3659 2128 3660 2073 3660 2075 3660 2128 3661 2101 3661 2073 3661 2129 3662 2130 3662 2100 3662 2091 3663 2100 3663 2130 3663 2130 3664 2131 3664 2091 3664 2131 3665 2092 3665 2091 3665 2102 3666 2092 3666 2106 3666 2092 3667 2131 3667 2106 3667 2132 3668 2106 3668 2131 3668 2096 3669 2097 3669 2133 3669 2134 3670 2133 3670 2097 3670 2135 3671 2136 3671 2137 3671 2138 3672 2137 3672 2136 3672 2136 3673 2133 3673 2138 3673 2134 3674 2138 3674 2133 3674 2139 3675 2096 3675 2002 3675 2001 3676 2136 3676 2135 3676 2001 3677 2133 3677 2136 3677 2001 3678 2096 3678 2133 3678 2001 3679 2005 3679 2096 3679 2005 3680 2002 3680 2096 3680 2140 3681 2132 3681 2130 3681 2132 581 2131 581 2130 581 2130 3682 2129 3682 2140 3682 2129 3683 2127 3683 2140 3683 2141 3684 2140 3684 2127 3684 2127 3685 2125 3685 2141 3685 2141 3686 2125 3686 2123 3686 2123 3687 2119 3687 2141 3687 2141 3688 2118 3688 2142 3688 2141 3689 2119 3689 2118 3689 2118 3690 1998 3690 2135 3690 2135 3691 2142 3691 2118 3691 2135 3692 2143 3692 2142 3692 2135 3693 2144 3693 2143 3693 2137 3694 2144 3694 2135 3694 2001 3695 2135 3695 1996 3695 2135 3696 1998 3696 1996 3696 2122 3697 2145 3697 2121 3697 2146 3698 2121 3698 2145 3698 2121 3699 2146 3699 2120 3699 2120 3700 2147 3700 2118 3700 2147 3701 2120 3701 2146 3701 1998 3702 2118 3702 2147 3702 2145 3703 1971 3703 2146 3703 1971 3704 1997 3704 2146 3704 2146 3705 1997 3705 2147 3705 1995 3706 2147 3706 1997 3706 2147 3707 1995 3707 1998 3707 1553 3708 2148 3708 1558 3708 1553 3709 2149 3709 2148 3709 1553 3710 1570 3710 2149 3710 2150 3711 1558 3711 2148 3711 2150 3712 2148 3712 2151 3712 2148 3713 2149 3713 2151 3713 2079 3714 2113 3714 2078 3714 2151 3715 2149 3715 2113 3715 2152 3716 2113 3716 2081 3716 2113 3717 2079 3717 2081 3717 2113 3718 2152 3718 2151 3718 2081 3719 2083 3719 2152 3719 2152 3720 2153 3720 2151 3720 2153 3721 2154 3721 2151 3721 2153 3722 2152 3722 2083 3722 2155 3723 2153 3723 2083 3723 2083 3724 2085 3724 2155 3724 2156 3725 2155 3725 2085 3725 2085 3726 2087 3726 2156 3726 2157 3727 2156 3727 2087 3727 2090 3728 2157 3728 2089 3728 2157 3729 2087 3729 2089 3729 2113 3730 2149 3730 1570 3730 1570 3731 2115 3731 2114 3731 2122 3732 2124 3732 2158 3732 2159 3733 2158 3733 2124 3733 2159 3734 1561 3734 2158 3734 2124 3735 2126 3735 2159 3735 1559 3736 1561 3736 2159 3736 2160 3737 2159 3737 2128 3737 2159 3738 2126 3738 2128 3738 2159 3739 2160 3739 1559 3739 1564 3740 1559 3740 2160 3740 2128 3741 2075 3741 2160 3741 2160 3742 2117 3742 1564 3742 2160 3743 2075 3743 2117 3743 1566 3744 1564 3744 2076 3744 1564 3745 2116 3745 2076 3745 1564 3746 2117 3746 2116 3746 1568 3747 1566 3747 2115 3747 1566 3748 2076 3748 2115 3748 1568 3749 2115 3749 1570 3749 1561 3750 1571 3750 2158 3750 2161 3751 2158 3751 1571 3751 2162 3752 2158 3752 2161 3752 2162 3753 2122 3753 2158 3753 2145 3754 2122 3754 2162 3754 1571 3755 1574 3755 2161 3755 1578 3756 2161 3756 1574 3756 2161 3757 1578 3757 2162 3757 2162 3758 1970 3758 2145 3758 1970 3759 1971 3759 2145 3759 1970 3760 2162 3760 1578 3760 1578 3761 1580 3761 1970 3761 2095 3762 2144 3762 2097 3762 2144 3763 2134 3763 2097 3763 2144 3764 2138 3764 2134 3764 2144 3765 2137 3765 2138 3765 2163 3766 2144 3766 2095 3766 2164 3767 2090 3767 2112 3767 2165 3768 2166 3768 2167 3768 2168 3769 2166 3769 2165 3769 2165 3770 2169 3770 2168 3770 2165 3771 2170 3771 2169 3771 2171 3772 2167 3772 2166 3772 2172 3773 2171 3773 2173 3773 2173 3774 2171 3774 2166 3774 2174 3775 2173 3775 2166 3775 2168 3776 2174 3776 2166 3776 2174 3777 2168 3777 2175 3777 2175 3778 2168 3778 2176 3778 2177 3779 2178 3779 2179 3779 2180 3780 2179 3780 2178 3780 2178 3781 2181 3781 2180 3781 2182 3782 2180 3782 2181 3782 2183 3783 2180 3783 2182 3783 2184 3784 2183 3784 2182 3784 2170 3785 2185 3785 2186 3785 2186 3786 2185 3786 2177 3786 2186 3787 2176 3787 2187 3787 2186 3788 2188 3788 2176 3788 2188 3789 2175 3789 2176 3789 2188 3790 2186 3790 2177 3790 2177 3791 2189 3791 2188 3791 2189 3792 2183 3792 2184 3792 2189 3793 2180 3793 2183 3793 2189 3794 2177 3794 2179 3794 2179 3795 2180 3795 2189 3795 2169 3796 2170 3796 2187 3796 2170 3797 2186 3797 2187 3797 2187 3798 2176 3798 2169 3798 2176 3799 2168 3799 2169 3799 2190 3800 2191 3800 2192 3800 2192 3801 2193 3801 2190 3801 2192 3802 2194 3802 2193 3802 2194 3803 2164 3803 2193 3803 2150 3804 2195 3804 1558 3804 2151 3805 2154 3805 2150 3805 2196 3806 2195 3806 2150 3806 2197 3807 2150 3807 2154 3807 2150 3808 2197 3808 2196 3808 2197 3809 2191 3809 2196 3809 2197 3810 2192 3810 2191 3810 2154 3811 2198 3811 2197 3811 2194 3812 2197 3812 2198 3812 2197 3813 2194 3813 2192 3813 2198 3814 2199 3814 2194 3814 2164 3815 2194 3815 2199 3815 2155 3816 2154 3816 2153 3816 2155 3817 2156 3817 2198 3817 2200 3818 2198 3818 2156 3818 2156 3819 2157 3819 2200 3819 2157 3820 2199 3820 2200 3820 2157 3821 2090 3821 2199 3821 2164 3822 2199 3822 2090 3822 2154 3823 2155 3823 2198 3823 2199 3824 2198 3824 2200 3824 2201 3825 2202 3825 2203 3825 2167 3826 2171 3826 2204 3826 2205 3827 2204 3827 2171 3827 2205 3828 2206 3828 2204 3828 2205 3829 2171 3829 2207 3829 2171 3830 2172 3830 2207 3830 2207 3831 2208 3831 2205 3831 2209 3832 2206 3832 2205 3832 2210 3833 2205 3833 2211 3833 2205 3834 2208 3834 2211 3834 2205 3835 2210 3835 2209 3835 2210 3836 2212 3836 2209 3836 2211 3837 2213 3837 2210 3837 2214 3838 2212 3838 2210 3838 2210 3839 2215 3839 1554 3839 2210 3840 2213 3840 2215 3840 2210 3841 1554 3841 2214 3841 2184 3842 2182 3842 2216 3842 2217 3843 2182 3843 2218 3843 2219 3844 2220 3844 2201 3844 1558 3845 2195 3845 1554 3845 2195 3846 2221 3846 1554 3846 2195 3847 2214 3847 2221 3847 2195 3848 2212 3848 2214 3848 2209 581 2212 581 2195 581 2195 581 2196 581 2209 581 2196 581 2206 581 2209 581 2196 3849 2204 3849 2206 3849 2167 3850 2204 3850 2196 3850 2196 3851 2191 3851 2167 3851 2165 3852 2167 3852 2191 3852 2191 3853 2190 3853 2165 3853 2190 3854 2222 3854 2165 3854 2190 3855 2223 3855 2222 3855 1656 3856 2184 3856 2216 3856 2072 3857 1665 3857 1664 3857 1665 3858 2072 3858 2224 3858 2008 3859 1854 3859 1850 3859 2008 3860 1850 3860 1872 3860 1858 3861 1854 3861 2008 3861 1858 3862 1979 3862 2225 3862 1979 3863 2226 3863 2225 3863 2227 3864 2225 3864 2226 3864 1801 3865 1803 3865 2227 3865 2226 182 1801 182 2227 182 1801 3866 2072 3866 1664 3866 2184 3867 1656 3867 2228 3867 2189 3868 2184 3868 2228 3868 2229 64 1601 64 1551 64 2230 3869 1444 3869 2229 3869 1551 3870 2230 3870 2229 3870 1444 3871 2230 3871 2231 3871 1444 3872 2231 3872 2232 3872 1444 3873 2232 3873 2233 3873 1444 3874 2233 3874 2234 3874 1444 3875 2234 3875 2235 3875 1655 3876 1444 3876 2235 3876 2235 3877 2236 3877 1655 3877 1655 3878 2236 3878 2237 3878 1655 3879 2237 3879 2238 3879 1655 3880 2238 3880 2228 3880 1656 3881 1655 3881 2228 3881 2215 3882 1551 3882 1554 3882 2230 3883 1551 3883 2215 3883 2215 3884 2213 3884 2230 3884 2230 3885 2213 3885 2211 3885 2231 3886 2230 3886 2211 3886 2211 3887 2208 3887 2231 3887 2232 3888 2231 3888 2208 3888 2208 3889 2207 3889 2232 3889 2233 3890 2232 3890 2207 3890 2172 3891 2233 3891 2207 3891 2234 3892 2233 3892 2172 3892 2234 3893 2172 3893 2173 3893 2235 3894 2234 3894 2173 3894 2173 3895 2174 3895 2235 3895 2236 3896 2235 3896 2174 3896 2236 3897 2174 3897 2175 3897 2236 3898 2175 3898 2237 3898 2188 3899 2237 3899 2175 3899 2238 3900 2237 3900 2188 3900 2238 3901 2188 3901 2189 3901 2228 3902 2238 3902 2189 3902 1447 3903 1444 3903 1655 3903 1554 3904 1551 3904 1552 3904 1858 3905 1861 3905 1860 3905 1444 3906 1601 3906 2229 3906 2043 3907 2008 3907 1872 3907 1858 3908 2008 3908 2009 3908 1858 3909 2009 3909 2011 3909 1858 3910 2011 3910 2013 3910 1858 3911 2013 3911 2015 3911 1858 3912 2015 3912 2017 3912 1858 3913 2017 3913 2019 3913 1858 3914 2019 3914 1979 3914 2071 182 2070 182 1999 182 1999 3915 2070 3915 2069 3915 1999 3916 2069 3916 2068 3916 1999 3917 2068 3917 2067 3917 1999 3918 2067 3918 2066 3918 1999 3919 2066 3919 2065 3919 1999 3920 2065 3920 2064 3920 1999 3921 2064 3921 2239 3921 1999 3922 2239 3922 2240 3922 1999 3923 2240 3923 2241 3923 1999 3924 2241 3924 2242 3924 2243 3925 2244 3925 2245 3925 2243 3926 2216 3926 2217 3926 2244 3927 2243 3927 2217 3927 2243 3928 1656 3928 2216 3928 2246 3929 2247 3929 2142 3929 2248 3930 2247 3930 2246 3930 2249 3931 2250 3931 2248 3931 2219 3932 2201 3932 2203 3932 2219 3933 2251 3933 2220 3933 2251 3934 2252 3934 2253 3934 2252 3935 2217 3935 2218 3935 2217 3936 2216 3936 2182 3936 2143 3937 2144 3937 2163 3937 2142 3938 2143 3938 2254 3938 1999 495 2255 495 1967 495 2256 3939 2257 3939 2250 3939 2244 3940 2258 3940 2259 3940 2257 3941 2259 3941 2258 3941 2250 3942 2260 3942 2248 3942 2261 3943 2248 3943 2260 3943 2260 3944 2219 3944 2261 3944 2203 3945 2261 3945 2219 3945 2262 3946 2219 3946 2260 3946 2260 3947 2250 3947 2257 3947 2262 3948 2260 3948 2257 3948 2251 3949 2219 3949 2262 3949 2257 3950 2258 3950 2262 3950 2262 3951 2258 3951 2251 3951 2252 3952 2251 3952 2258 3952 2258 3953 2244 3953 2252 3953 2217 3954 2252 3954 2244 3954 2071 581 1999 581 2000 581 2247 3955 2141 3955 2142 3955 2112 3956 2263 3956 2264 3956 2263 3957 2265 3957 2264 3957 2265 3958 2266 3958 2264 3958 2247 3959 2264 3959 2141 3959 2140 3960 2107 3960 2106 3960 2141 3961 2266 3961 2140 3961 2141 3962 2264 3962 2266 3962 2140 3963 2106 3963 2132 3963 2226 3964 1979 3964 1975 3964 2111 64 2112 64 2084 64 2110 3965 2111 3965 2082 3965 2109 3966 2108 3966 2107 3966 2107 3967 2267 3967 2109 3967 2110 3968 2109 3968 2267 3968 2265 3969 2111 3969 2110 3969 2267 3970 2265 3970 2110 3970 2111 3971 2265 3971 2263 3971 2112 3972 2111 3972 2263 3972 2265 3973 2267 3973 2266 3973 2090 3974 2088 3974 2112 3974 2140 3975 2266 3975 2267 3975 2140 3976 2267 3976 2107 3976 2226 3977 1975 3977 1801 3977 2165 3978 2268 3978 2170 3978 2268 3979 2269 3979 2170 3979 2202 3980 2269 3980 2268 3980 2201 3981 2269 3981 2202 3981 2177 3982 2270 3982 2178 3982 2185 3983 2270 3983 2177 3983 2270 3984 2181 3984 2178 3984 2271 3985 2181 3985 2270 3985 2272 3986 2271 3986 2270 3986 2220 3987 2253 3987 2270 3987 2253 3988 2272 3988 2270 3988 2225 3989 2227 3989 2273 3989 2227 3990 2274 3990 2273 3990 2227 3991 1803 3991 2274 3991 2225 3992 2275 3992 2276 3992 2225 3993 2277 3993 2275 3993 2225 3994 2278 3994 2277 3994 2225 3995 2279 3995 2278 3995 2225 3996 2280 3996 2279 3996 2225 3997 2281 3997 2280 3997 2225 3998 2282 3998 2281 3998 2225 3999 2283 3999 2282 3999 2225 64 2273 64 2283 64 2181 4000 2271 4000 2182 4000 2271 4001 2272 4001 2182 4001 2218 4002 2182 4002 2272 4002 2270 4003 2201 4003 2220 4003 2270 4004 2269 4004 2201 4004 2270 4005 2185 4005 2269 4005 2170 4006 2269 4006 2185 4006 2284 4007 2285 4007 1797 4007 2286 4008 1797 4008 2285 4008 2285 4009 2287 4009 2286 4009 2288 4010 2286 4010 2287 4010 2287 4011 2289 4011 2288 4011 2290 4012 2288 4012 2289 4012 2289 4013 2291 4013 2290 4013 1802 4014 1667 4014 2292 4014 1667 4015 2293 4015 2292 4015 2294 4016 2293 4016 1653 4016 2293 4017 1667 4017 1653 4017 2294 4018 2295 4018 2293 4018 2296 4019 2297 4019 2298 4019 2299 4020 2295 4020 2294 4020 2299 4021 2298 4021 2295 4021 2299 4022 2296 4022 2298 4022 1653 4023 1652 4023 2294 4023 2300 4024 2294 4024 1796 4024 2294 4025 1652 4025 1796 4025 2294 4026 2300 4026 2299 4026 2299 4027 2301 4027 2296 4027 2301 4028 2302 4028 2296 4028 2301 4029 2299 4029 2300 4029 1796 4030 1795 4030 2300 4030 2300 4031 1797 4031 2286 4031 2300 4032 1795 4032 1797 4032 2300 4033 2286 4033 2301 4033 2303 4034 2302 4034 2301 4034 2301 4035 2286 4035 2288 4035 2301 4036 2288 4036 2303 4036 2303 4037 2288 4037 2290 4037 2290 4038 2291 4038 2304 4038 2297 4039 2273 4039 2305 4039 2273 4040 2306 4040 2305 4040 2273 4041 2274 4041 2306 4041 2274 4042 1803 4042 2306 4042 2273 4043 2297 4043 2296 4043 2307 4044 2296 4044 2302 4044 2296 4045 2307 4045 2273 4045 2283 4046 2273 4046 2307 4046 2302 4047 2303 4047 2307 4047 2282 4048 2283 4048 2307 4048 2282 4049 2307 4049 2303 4049 2303 4050 2290 4050 2282 4050 2281 4051 2282 4051 2290 4051 2290 4052 2304 4052 2281 4052 2280 4053 2281 4053 2304 4053 2279 4054 2280 4054 2304 4054 1654 4055 1789 4055 1146 4055 1163 4056 1789 4056 1788 4056 1788 4057 1787 4057 1166 4057 1786 4058 1168 4058 1787 4058 1169 4059 1786 4059 1785 4059 1785 4060 1784 4060 1173 4060 2268 4061 2222 4061 2223 4061 2222 4062 2268 4062 2165 4062 1554 4063 2221 4063 2214 4063 2252 4064 2218 4064 2272 4064 2272 4065 2253 4065 2252 4065 2251 4066 2253 4066 2220 4066 1667 4067 1802 4067 1626 4067 1802 182 2292 182 1803 182 2306 182 1803 182 2292 182 2292 4068 2293 4068 2306 4068 2305 4069 2306 4069 2293 4069 2297 4070 2305 4070 2295 4070 2305 4071 2293 4071 2295 4071 2298 4072 2297 4072 2295 4072 1403 4073 2308 4073 1148 4073 1148 4074 2308 4074 2309 4074 1148 4075 2309 4075 2310 4075 1148 4076 2310 4076 2311 4076 1148 64 2311 64 2312 64 1148 4077 2312 4077 2313 4077 1148 4078 2313 4078 2314 4078 1148 4079 2314 4079 2315 4079 1146 64 1148 64 2315 64 1146 4080 2315 4080 2316 4080 1146 4081 2316 4081 2317 4081 1146 4082 2317 4082 2318 4082 1146 64 2318 64 2319 64 1146 4083 2319 4083 2320 4083 1146 4084 2320 4084 2284 4084 1146 4085 2284 4085 1797 4085 1654 4086 1146 4086 1797 4086 2321 4087 1176 4087 1793 4087 1784 4088 1793 4088 1176 4088 1176 4089 1173 4089 1784 4089 1169 4090 1785 4090 1173 4090 1169 4091 1168 4091 1786 4091 1168 4092 1166 4092 1787 4092 1166 4093 1163 4093 1788 4093 1789 4094 1163 4094 1146 4094 2322 4095 2323 4095 2324 4095 2322 4096 2324 4096 2325 4096 2326 4097 2322 4097 2325 4097 2327 4098 2323 4098 2322 4098 2328 4099 2329 4099 2327 4099 2322 4100 2328 4100 2327 4100 2330 4101 2329 4101 2328 4101 2328 4102 2331 4102 2330 4102 2332 4103 2330 4103 2331 4103 2333 4104 2332 4104 2331 4104 2334 4105 2333 4105 2331 4105 2331 4106 2335 4106 2334 4106 2336 4107 2335 4107 2331 4107 2337 4108 2338 4108 2336 4108 2331 4109 2337 4109 2336 4109 2338 4110 2339 4110 2336 4110 2340 4111 2341 4111 2342 4111 2341 4112 2343 4112 2342 4112 2343 4113 2344 4113 2342 4113 2342 4114 2344 4114 2345 4114 2346 4115 2335 4115 2336 4115 2336 4116 2339 4116 2340 4116 2336 4117 2340 4117 2342 4117 2346 4118 2336 4118 2342 4118 2342 4119 2345 4119 2347 4119 2346 4120 2342 4120 2348 4120 2291 4121 2349 4121 2350 4121 2275 4122 2350 4122 2349 4122 2276 4123 2275 4123 2349 4123 2349 4124 2351 4124 2276 4124 2352 4125 2276 4125 2351 4125 2351 4126 2326 4126 2352 4126 2352 4127 2326 4127 2325 4127 2324 4128 2352 4128 2325 4128 2304 4129 2350 4129 2275 4129 2350 4130 2304 4130 2291 4130 2275 4131 2277 4131 2304 4131 2277 4132 2278 4132 2304 4132 2278 4133 2279 4133 2304 4133 2353 4134 2326 4134 2351 4134 2353 4135 2351 4135 2349 4135 2349 4136 2291 4136 2289 4136 2353 4137 2349 4137 2289 4137 2354 4138 2326 4138 2353 4138 2353 4139 2355 4139 2354 4139 2355 4140 2353 4140 2289 4140 2289 4141 2287 4141 2355 4141 2356 4142 2354 4142 2355 4142 2287 4143 2285 4143 2355 4143 2355 4144 2357 4144 2356 4144 2357 4145 2355 4145 2285 4145 2357 4146 2320 4146 2356 4146 2320 4147 2357 4147 2285 4147 2317 4148 2356 4148 2320 4148 2285 4149 2284 4149 2320 4149 2320 4150 2319 4150 2318 4150 2320 4151 2318 4151 2317 4151 2354 4152 2331 4152 2328 4152 2354 4153 2328 4153 2322 4153 2326 4154 2354 4154 2322 4154 2358 4155 2331 4155 2354 4155 2354 4156 2356 4156 2358 4156 2359 4157 2358 4157 2356 4157 2356 4158 2317 4158 2359 4158 2359 4159 2317 4159 2316 4159 2359 4160 2316 4160 2315 4160 1131 4161 1422 4161 1403 4161 2360 4162 2361 4162 2362 4162 2363 4163 2360 4163 2362 4163 2364 4164 2365 4164 2361 4164 2360 4165 2364 4165 2361 4165 2365 4166 2364 4166 2366 4166 2367 4167 2365 4167 2366 4167 2368 4168 2369 4168 2367 4168 2366 4169 2368 4169 2367 4169 2370 4170 2369 4170 2368 4170 2344 4171 2370 4171 2345 4171 2371 4172 2345 4172 2370 4172 2368 4173 2371 4173 2370 4173 2345 4174 2371 4174 2347 4174 2372 4175 2313 4175 2312 4175 2372 4176 2312 4176 2311 4176 2372 4177 2311 4177 2310 4177 2373 4178 2372 4178 2310 4178 2373 4179 2340 4179 2339 4179 2373 4180 2339 4180 2338 4180 2373 4181 2338 4181 2337 4181 2373 4182 2337 4182 2372 4182 2310 4183 2309 4183 2373 4183 2341 4184 2340 4184 2373 4184 2373 4185 2309 4185 2308 4185 2373 4186 2308 4186 1403 4186 2373 4187 1403 4187 2374 4187 2374 4188 2344 4188 2343 4188 2374 4189 2343 4189 2341 4189 2373 4190 2374 4190 2341 4190 2370 4191 2367 4191 2369 4191 2375 4192 2365 4192 2370 4192 2370 4193 2376 4193 2375 4193 2376 4194 2370 4194 2344 4194 2377 4195 2375 4195 2376 4195 2378 4196 2377 4196 2376 4196 2376 4197 2379 4197 2378 4197 2379 4198 2376 4198 2374 4198 2380 4199 2378 4199 2379 4199 2379 4200 2374 4200 1403 4200 2381 4201 2380 4201 2379 4201 2379 4202 1422 4202 2381 4202 1422 4203 2379 4203 1403 4203 1421 4204 2381 4204 1422 4204 2361 4205 2382 4205 2362 4205 2382 4206 2361 4206 2365 4206 2365 4207 2375 4207 2382 4207 1405 4208 2362 4208 2382 4208 2362 4209 1405 4209 2363 4209 2375 4210 2377 4210 2382 4210 1404 4211 2363 4211 1405 4211 2377 4212 2378 4212 2382 4212 1420 4213 2382 4213 2378 4213 2382 4214 1420 4214 1405 4214 2378 4215 2380 4215 1420 4215 2380 4216 2381 4216 1420 4216 1419 4217 1405 4217 1420 4217 2381 4218 1421 4218 1420 4218 1332 4219 2363 4219 1404 4219 2383 4220 2360 4220 2363 4220 2383 4221 2363 4221 1332 4221 2364 4222 2360 4222 2383 4222 1332 4223 2384 4223 2383 4223 2331 4224 2358 4224 2337 4224 2372 4225 2337 4225 2358 4225 2358 4226 2359 4226 2372 4226 2313 4227 2372 4227 2359 4227 2314 4228 2313 4228 2359 4228 2359 4229 2315 4229 2314 4229 2225 4230 2276 4230 2352 4230 2225 4231 2352 4231 2324 4231 2225 4232 2324 4232 2323 4232 2225 4233 2323 4233 2327 4233 2225 4234 2327 4234 2329 4234 2225 4235 2329 4235 2330 4235 2225 4236 2330 4236 2332 4236 2225 4237 2332 4237 2333 4237 2225 4238 2333 4238 2334 4238 2335 4239 2225 4239 2334 4239 2344 4240 2374 4240 2376 4240 2385 4241 2386 4241 2387 4241 2388 4242 1366 4242 1364 4242 2388 4243 1364 4243 1361 4243 2388 4244 1361 4244 1359 4244 2388 4245 1359 4245 1355 4245 2388 4246 1230 4246 1366 4246 1213 4247 2389 4247 2390 4247 1213 4248 2390 4248 2391 4248 1213 4249 2391 4249 2392 4249 2393 581 1213 581 2392 581 1225 4250 2394 4250 2395 4250 1218 4251 1225 4251 2395 4251 2396 4252 2394 4252 1225 4252 1225 4253 1226 4253 2396 4253 2397 4254 2396 4254 1226 4254 1226 4255 1227 4255 2397 4255 2398 4256 2397 4256 1227 4256 1227 4257 1228 4257 2398 4257 2398 4258 1228 4258 1229 4258 2399 4259 2398 4259 1229 4259 2400 4260 2399 4260 1229 4260 2388 4261 2400 4261 1229 4261 1230 4262 2388 4262 1229 4262 2395 4263 2401 4263 2402 4263 2403 4264 2402 4264 2401 4264 2401 4265 2404 4265 2403 4265 2405 4266 2403 4266 2404 4266 2404 4267 2406 4267 2405 4267 2407 4268 2405 4268 2406 4268 2408 4269 2409 4269 2407 4269 2406 4270 2408 4270 2407 4270 2410 4271 2409 4271 2408 4271 2408 4272 2411 4272 2410 4272 2412 4273 2410 4273 2411 4273 2411 4274 2413 4274 2412 4274 2414 4275 2412 4275 2413 4275 2415 4276 2389 4276 2414 4276 2413 4277 2415 4277 2414 4277 2390 4278 2389 4278 2415 4278 2415 4279 2416 4279 2390 4279 2391 4280 2390 4280 2416 4280 2416 4281 2417 4281 2391 4281 2392 4282 2391 4282 2417 4282 2417 4283 2393 4283 2392 4283 2386 4284 2418 4284 2419 4284 2420 4285 2419 4285 2421 4285 2422 4286 2420 4286 2423 4286 2422 4287 2424 4287 2425 4287 2426 4288 2422 4288 2425 4288 2425 4289 2427 4289 2426 4289 2426 4290 2427 4290 2428 4290 2429 4291 2426 4291 2428 4291 2429 4292 2428 4292 2430 4292 2431 4293 2429 4293 2430 4293 2430 4294 2432 4294 2431 4294 2433 4295 2431 4295 2432 4295 2432 4296 2434 4296 2433 4296 2435 4297 2436 4297 2437 4297 2437 4298 2436 4298 2438 4298 2437 4299 2438 4299 2439 4299 2437 4300 2439 4300 2440 4300 2437 4301 2440 4301 2441 4301 2441 4302 2442 4302 2437 4302 2437 4303 2442 4303 2443 4303 2437 4304 2443 4304 2444 4304 2437 4305 2444 4305 2445 4305 2437 4306 2445 4306 2446 4306 2437 4307 2398 4307 2399 4307 2437 4308 2399 4308 2400 4308 2437 4309 2400 4309 2388 4309 2437 4310 2388 4310 2447 4310 2437 4311 2447 4311 2448 4311 2437 4312 2448 4312 2435 4312 2446 4313 2449 4313 2437 4313 2437 4314 2449 4314 2397 4314 2397 4315 2398 4315 2437 4315 2449 4316 2450 4316 2397 4316 2396 4317 2397 4317 2450 4317 2450 4318 2451 4318 2396 4318 2394 4319 2396 4319 2451 4319 2451 4320 2452 4320 2394 4320 2394 4321 2452 4322 2393 4323 2395 4324 2394 4324 2393 4324 2393 4325 2417 4325 2395 4325 2401 4326 2395 4326 2417 4326 2417 4327 2416 4327 2401 4327 2404 4328 2401 4328 2416 4328 2416 4329 2415 4329 2404 4329 2453 4330 2454 4330 2455 4330 2455 4331 2454 4331 2456 4331 2457 4332 2458 4332 2459 4332 2453 4333 2455 4333 2460 4333 2453 4334 2460 4334 2457 4334 2453 4335 2457 4335 2459 4335 2461 4336 2453 4336 2459 4336 2462 4337 2461 4337 2459 4337 2463 4338 2462 4338 2459 4338 2464 4339 2463 4339 2459 4339 2459 4340 2458 4340 2387 4340 2459 4341 2387 4341 2386 4341 2459 4342 2386 4342 2419 4342 2459 4343 2419 4343 2420 4343 2459 4344 2420 4344 2422 4344 2465 4345 2464 4345 2459 4345 2426 4346 2465 4346 2459 4346 2422 4347 2426 4347 2459 4347 2466 4348 2465 4348 2426 4348 2426 4349 2429 4349 2466 4349 2467 4350 2466 4350 2429 4350 2429 4351 2431 4351 2467 4351 2468 4352 2467 4352 2431 4352 2458 4353 2448 4353 2447 4353 2387 4354 2458 4354 2447 4354 2435 4355 2448 4355 2458 4355 2458 4356 2457 4356 2435 4356 2436 4357 2435 4357 2457 4357 2457 4358 2460 4358 2436 4358 2438 4359 2436 4359 2460 4359 2460 4360 2455 4360 2438 4360 2469 4361 2438 4361 2455 4361 2455 4362 2456 4362 2469 4362 2470 4363 2469 4363 2456 4363 2471 4364 2472 4364 2470 4364 2456 4365 2471 4365 2470 4365 2473 4366 2472 4366 2471 4366 2474 4367 2475 4367 2473 4367 2471 4368 2474 4368 2473 4368 2474 4369 2476 4369 2475 4369 2439 4370 2475 4370 2476 4370 1276 4371 2477 4371 2478 4371 2479 4372 2480 4372 2477 4372 2481 4373 2479 4373 2477 4373 2482 4374 2481 4374 2477 4374 1276 182 2442 182 2477 182 2483 4375 2482 4375 2477 4375 2484 4376 2483 4376 2477 4376 2485 4377 2484 4377 2477 4377 2486 182 2485 182 2477 182 2441 4378 2486 4378 2477 4378 2442 4379 2441 4379 2477 4379 2487 4380 2486 4380 2441 4380 2488 4381 2489 4381 2487 4381 2441 4382 2488 4382 2487 4382 2453 4383 2461 4383 2490 4383 2061 182 2489 182 2490 182 2059 182 2061 182 2490 182 2461 4384 2491 4384 2490 4384 2393 4385 2452 4385 1213 4385 1212 4386 1213 4386 2452 4386 2452 4387 2451 4387 1212 4387 1212 4388 2451 4388 1211 4388 2451 4389 2450 4389 1211 4389 1210 4390 1211 4390 2450 4390 2450 4391 2449 4391 1210 4391 2449 4392 2446 4392 1210 4392 1209 4393 1210 4393 2446 4393 2446 4394 2445 4394 1209 4394 1206 4395 1209 4395 2445 4395 2444 4396 1206 4396 2445 4396 2443 4397 1206 4397 2444 4397 2442 4398 1206 4398 2443 4398 1276 4399 1206 4399 2442 4399 2060 4400 2063 4400 2061 4400 2489 4401 2061 4401 2063 4401 2062 4402 2492 4402 2063 4402 2492 4403 2062 4403 1983 4403 2493 4404 2063 4404 2492 4404 2063 4405 2493 4405 2489 4405 2487 4406 2489 4406 2493 4406 2476 4407 2488 4407 2494 4407 2495 4408 2488 4408 2476 4408 2476 4409 2496 4409 2495 4409 2497 4410 2495 4410 2496 4410 2496 4411 2454 4411 2497 4411 2497 4412 2454 4412 2453 4412 2454 4413 2474 4413 2471 4413 2456 4414 2454 4414 2471 4414 2438 4415 2469 4415 2470 4415 2438 4416 2470 4416 2472 4416 2438 4417 2472 4417 2473 4417 2438 4418 2473 4418 2475 4418 2438 4419 2475 4419 2439 4419 2453 4420 2490 4420 2497 4420 2490 4421 2495 4421 2497 4421 2488 4422 2495 4422 2490 4422 2488 4423 2490 4423 2489 4423 2440 4424 2488 4424 2441 4424 2440 4425 2494 4425 2488 4425 2439 4426 2494 4426 2440 4426 2476 4427 2494 4427 2439 4427 2454 4428 2496 4428 2474 4428 2496 4429 2476 4429 2474 4429 1218 4430 2395 4430 2402 4430 1218 4431 2402 4431 2403 4431 1218 4432 2403 4432 2405 4432 1218 4433 2405 4433 2407 4433 1218 4434 2407 4434 2409 4434 1218 4435 2409 4435 1213 4435 2410 581 1213 581 2409 581 2410 4436 2412 4436 1213 4436 2412 581 2414 581 1213 581 2414 4437 2389 4437 1213 4437 2498 4438 2499 4438 2500 4438 2498 4439 2501 4439 2499 4439 2502 4440 2499 4440 2501 4440 2503 4441 2502 4441 2501 4441 2503 4442 2501 4442 2504 4442 2505 4443 2503 4443 2504 4443 2501 4444 2506 4444 2507 4444 2498 4445 2506 4445 2501 4445 2508 4446 2509 4446 2510 4446 2511 4447 2512 4447 2513 4447 2514 4448 2515 4448 2246 4448 2516 4449 2517 4449 2518 4449 2515 4450 2518 4450 2517 4450 2517 4451 2249 4451 2515 4451 2246 4452 2515 4452 2249 4452 2519 4453 2517 4453 2516 4453 2520 4454 2517 4454 2519 4454 2520 4455 2249 4455 2517 4455 2520 4456 2256 4456 2249 4456 2259 4457 2520 4457 2521 4457 2520 4458 2519 4458 2521 4458 2520 4459 2259 4459 2256 4459 2522 4460 2259 4460 2523 4460 2259 4461 2521 4461 2523 4461 2523 4462 2245 4462 2522 4462 2524 4463 2525 4463 2526 4463 2525 4464 2527 4464 2526 4464 2528 4465 2529 4465 2530 4465 2531 4466 2530 4466 2529 4466 2530 4467 2531 4467 2524 4467 2525 4468 2524 4468 2531 4468 2529 4469 2532 4469 2531 4469 2527 4470 2525 4470 2531 4470 2531 4471 2533 4471 2527 4471 2533 4472 2531 4472 2532 4472 2532 4473 2534 4473 2533 4473 2534 4474 2535 4474 2533 4474 2535 4475 2508 4475 2533 4475 2533 4476 2510 4476 2527 4476 2510 4477 2533 4477 2508 4477 2536 4478 2528 4478 2537 4478 2529 4479 2528 4479 2536 4479 2536 4480 2538 4480 2529 4480 2532 4481 2529 4481 2538 4481 2534 4482 2532 4482 2538 4482 2538 4483 2539 4483 2534 4483 2535 4484 2534 4484 2539 4484 2508 4485 2535 4485 2539 4485 2509 4486 2508 4486 2539 4486 2539 4487 2540 4487 2509 4487 2541 4488 2542 4488 2536 4488 2538 4489 2536 4489 2542 4489 2539 4490 2538 4490 2542 4490 2542 4491 2543 4491 2539 4491 2540 4492 2539 4492 2543 4492 2249 4493 2256 4493 2250 4493 2256 4494 2259 4494 2257 4494 2244 4495 2259 4495 2522 4495 2526 4496 2527 4496 2506 4496 2513 4497 2526 4497 2506 4497 2506 4498 2498 4498 2513 4498 2507 4499 2527 4499 2510 4499 2507 4500 2506 4500 2527 4500 2544 4501 2510 4501 2545 4501 2510 4502 2509 4502 2545 4502 2509 4503 2540 4503 2545 4503 2510 4504 2544 4504 2507 4504 2545 4505 2546 4505 2544 4505 2544 4506 2547 4506 2507 4506 2547 4507 2544 4507 2548 4507 2544 4508 2546 4508 2548 4508 2549 4509 2507 4509 2547 4509 2549 4510 2501 4510 2507 4510 2549 4511 2504 4511 2501 4511 2548 4512 2550 4512 2547 4512 2551 4513 2504 4513 2549 4513 2552 4514 2547 4514 2553 4514 2547 4515 2550 4515 2553 4515 2547 4516 2552 4516 2549 4516 2549 4517 2554 4517 2551 4517 2554 4518 2555 4518 2551 4518 2554 4519 2549 4519 2552 4519 2556 4520 2555 4520 2554 4520 2553 4521 2557 4521 2552 4521 2558 4522 2552 4522 2559 4522 2552 4523 2557 4523 2559 4523 2552 4524 2558 4524 2554 4524 2560 4525 2554 4525 2558 4525 2554 4526 2560 4526 2556 4526 2560 4527 2561 4527 2556 4527 2562 4528 2561 4528 2560 4528 2559 4529 2563 4529 2558 4529 2564 4530 2558 4530 2563 4530 2558 4531 2564 4531 2560 4531 2560 4532 2565 4532 2562 4532 2519 4533 2516 4533 2528 4533 2528 4534 2530 4534 2519 4534 2521 4535 2519 4535 2530 4535 2530 4536 2524 4536 2521 4536 2523 4537 2521 4537 2524 4537 2524 4538 2526 4538 2523 4538 2526 270 2513 270 2523 270 2245 4539 2523 4539 2513 4539 2566 4540 2505 4540 2504 4540 2504 4541 2551 4541 2566 4541 2567 4542 2566 4542 2551 4542 2551 4543 2555 4543 2567 4543 2568 4544 2567 4544 2555 4544 2555 4545 2556 4545 2568 4545 2569 4546 2568 4546 2556 4546 2556 4547 2561 4547 2569 4547 2570 4548 2569 4548 2561 4548 2561 4549 2562 4549 2570 4549 2570 4550 2562 4550 2571 4550 2246 4551 2249 4551 2248 4551 2572 4552 2246 4552 2142 4552 2572 4553 2254 4553 2246 4553 2254 4554 2514 4554 2246 4554 2528 4555 2516 4555 2537 4555 2516 4556 2536 4556 2537 4556 2516 4557 2541 4557 2536 4557 2518 4558 2541 4558 2516 4558 2573 4559 2511 4559 2500 4559 2513 4560 2500 4560 2511 4560 2500 4561 2499 4561 2574 4561 2499 4562 2502 4562 2575 4562 2502 4563 2503 4563 2576 4563 2503 581 2505 581 2577 581 2505 581 2566 581 2578 581 2566 581 2567 581 2579 581 2567 4564 2568 4564 2580 4564 2568 581 2569 581 2581 581 2569 4565 2570 4565 2582 4565 2513 4566 2498 4566 2500 4566 2513 4567 2243 4567 2245 4567 2522 4568 2245 4568 2244 4568 2563 4569 2559 4569 2583 4569 2559 4570 2557 4570 2583 4570 2557 64 2553 64 2583 64 2553 4571 2543 4571 2583 4571 2553 4572 2550 4572 2543 4572 2550 4573 2548 4573 2543 4573 2548 4574 2546 4574 2543 4574 2546 4575 2545 4575 2543 4575 2545 4576 2540 4576 2543 4576 2584 4577 2585 4577 2586 4577 2587 4578 2585 4578 2584 4578 2588 4579 2585 4579 2587 4579 2589 4580 2585 4580 2588 4580 2589 4581 2583 4581 2585 4581 2590 64 2583 64 2589 64 2591 64 2583 64 2590 64 2563 64 2583 64 2591 64 2592 581 2582 581 2570 581 2582 4582 2581 4582 2569 4582 2581 581 2580 581 2568 581 2580 581 2579 581 2567 581 2579 581 2578 581 2566 581 2578 581 2577 581 2505 581 2577 4583 2576 4583 2503 4583 2576 581 2575 581 2502 581 2575 581 2574 581 2499 581 2574 4584 2573 4584 2500 4584 2593 4585 2586 4585 2585 4585 2575 4586 2594 4586 2595 4586 2575 4587 2595 4587 2596 4587 2574 4588 2575 4588 2596 4588 2575 4589 2576 4589 2594 4589 2576 4590 2577 4590 2594 4590 2578 4591 2579 4591 2597 4591 2598 4592 2597 4592 2579 4592 2579 4593 2580 4593 2598 4593 2599 4594 2598 4594 2580 4594 2580 4595 2581 4595 2599 4595 2600 4596 2599 4596 2581 4596 2581 4597 2582 4597 2600 4597 2601 4598 2600 4598 2582 4598 2582 4599 2592 4599 2601 4599 2571 4600 2601 4600 2592 4600 2592 4601 2570 4601 2571 4601 2595 4602 2602 4602 2603 4602 2596 4603 2595 4603 2603 4603 2604 4604 2605 4604 2606 4604 2602 4605 2604 4605 2606 4605 2602 4606 2595 4606 2594 4606 2602 4607 2594 4607 2604 4607 2607 4608 2605 4608 2604 4608 2607 4609 2586 4609 2593 4609 2607 4610 2593 4610 2605 4610 2584 4611 2586 4611 2607 4611 2607 4612 2604 4612 2608 4612 2609 4613 2607 4613 2608 4613 2609 4614 2587 4614 2584 4614 2607 4615 2609 4615 2584 4615 2608 4616 2610 4616 2609 4616 2604 4617 2594 4617 2597 4617 2608 4618 2604 4618 2597 4618 2610 4619 2608 4619 2597 4619 2597 4620 2598 4620 2610 4620 2588 4621 2587 4621 2609 4621 2611 4622 2589 4622 2588 4622 2609 4623 2611 4623 2588 4623 2611 4624 2609 4624 2610 4624 2610 4625 2598 4625 2599 4625 2612 4626 2610 4626 2599 4626 2610 4627 2612 4627 2611 4627 2599 4628 2600 4628 2612 4628 2590 4629 2589 4629 2611 4629 2564 4630 2591 4630 2590 4630 2611 4631 2564 4631 2590 4631 2564 4632 2611 4632 2612 4632 2612 4633 2565 4633 2564 4633 2612 4634 2600 4634 2601 4634 2565 4635 2612 4635 2601 4635 2601 4636 2571 4636 2565 4636 2563 4637 2591 4637 2564 4637 2565 4638 2571 4638 2562 4638 2564 4639 2565 4639 2560 4639 2613 4640 2163 4640 2095 4640 2163 4641 2254 4641 2143 4641 2254 4642 2572 4642 2142 4642 1963 4643 2614 4643 2615 4643 1963 4644 2615 4644 2004 4644 1963 4645 2004 4645 1964 4645 1967 4646 2255 4646 2616 4646 1963 495 1967 495 2616 495 2617 4647 2573 4647 2618 4647 2619 4648 2617 4648 2618 4648 2573 4649 2574 4649 2618 4649 2596 4650 2618 4650 2574 4650 2094 182 2096 182 2139 182 2139 4651 2002 4651 2003 4651 2139 4652 2003 4652 2620 4652 2139 4653 2620 4653 2621 4653 2094 4654 2139 4654 2095 4654 2095 4655 2139 4655 2613 4655 2622 4656 2623 4656 2624 4656 2625 4657 2624 4657 2623 4657 2625 4658 2623 4658 2139 4658 2626 4659 2625 4659 2139 4659 2614 4660 1963 4660 2621 4660 2617 4661 2619 4661 2621 4661 2621 4662 2619 4662 2627 4662 2621 4663 2627 4663 2628 4663 2621 4664 2628 4664 2629 4664 2621 4665 2629 4665 2630 4665 2621 4666 2630 4666 2626 4666 2139 4667 2621 4667 2626 4667 2004 4668 2615 4668 2003 4668 2620 4669 2003 4669 2615 4669 2615 4670 2614 4670 2620 4670 2621 4671 2620 4671 2614 4671 2630 4672 2631 4672 2625 4672 2626 4673 2630 4673 2625 4673 2630 4674 2629 4674 2631 4674 2632 4675 2631 4675 2629 4675 2629 4676 2628 4676 2632 4676 2633 4677 2632 4677 2628 4677 2628 4678 2627 4678 2633 4678 2618 4679 2633 4679 2627 4679 2627 4680 2619 4680 2618 4680 2596 4681 2603 4681 2618 4681 2602 4682 2606 4682 2603 4682 2593 4683 2634 4683 2605 4683 2605 4684 2635 4684 2606 4684 2635 4685 2605 4685 2634 4685 2632 4686 2606 4686 2635 4686 2631 4687 2635 4687 2634 4687 2635 4688 2631 4688 2632 4688 2634 4689 2625 4689 2631 4689 2634 4690 2593 4690 2636 4690 2636 4691 2624 4691 2634 4691 2625 4692 2634 4692 2624 4692 2585 4693 2636 4693 2593 4693 2585 4694 2637 4694 2636 4694 2624 4695 2636 4695 2637 4695 2624 4696 2637 4696 2622 4696 2577 4697 2597 4697 2594 4697 2578 4698 2597 4698 2577 4698 2603 4699 2633 4699 2618 4699 2603 4700 2606 4700 2633 4700 2606 4701 2632 4701 2633 4701 2638 4702 2639 4702 2640 4702 2641 4703 2642 4703 2643 4703 2641 4704 2643 4704 2638 4704 2640 4705 2641 4705 2638 4705 2644 4706 2645 4706 2646 4706 2647 4707 2646 4707 2645 4707 2645 4708 2648 4708 2647 4708 2649 4709 2647 4709 2648 4709 2648 4710 2650 4710 2649 4710 2651 4711 2649 4711 2650 4711 2650 4712 2652 4712 2651 4712 2653 4713 2651 4713 2652 4713 2652 4714 2654 4714 2653 4714 2655 4715 2653 4715 2654 4715 2654 4716 2656 4716 2655 4716 2657 4717 2655 4717 2656 4717 2656 4718 2658 4718 2657 4718 2659 4719 2657 4719 2658 4719 2658 4720 2660 4720 2659 4720 2659 4721 2660 4721 2661 4721 2662 581 2659 581 2661 581 2662 4722 2663 4722 2664 4722 2662 4723 2664 4723 2665 4723 2666 4724 2662 4724 2665 4724 2667 4725 2668 4725 2638 4725 2639 4726 2638 4726 2668 4726 2669 64 2670 64 2639 64 2668 64 2669 64 2639 64 2671 4727 2670 4727 2669 4727 2669 4728 2672 4728 2671 4728 2673 4729 2671 4729 2672 4729 2672 4730 2674 4730 2673 4730 2675 4731 2673 4731 2674 4731 2674 4732 2676 4732 2675 4732 2677 4733 2675 4733 2676 4733 2676 4734 2678 4734 2677 4734 2679 4735 2677 4735 2678 4735 2678 4736 2680 4736 2679 4736 2681 4737 2679 4737 2680 4737 2680 4738 2682 4738 2681 4738 2683 4739 2681 4739 2682 4739 2682 4740 2684 4740 2683 4740 2683 64 2684 64 2685 64 2686 64 2683 64 2685 64 2642 4741 2687 4741 2573 4741 2688 4742 2642 4742 2573 4742 2689 4743 2687 4743 2642 4743 2668 4744 2690 4744 2691 4744 2669 4745 2668 4745 2691 4745 2672 4746 2669 4746 2691 4746 2674 4747 2672 4747 2691 4747 2676 4748 2674 4748 2691 4748 2691 4749 2692 4749 2676 4749 2678 4750 2676 4750 2692 4750 2692 4751 2693 4751 2678 4751 2680 4752 2678 4752 2693 4752 2693 4753 2694 4753 2680 4753 2682 4754 2680 4754 2694 4754 2694 4755 2695 4755 2682 4755 2684 4756 2682 4756 2695 4756 2695 4757 2696 4757 2684 4757 2685 4758 2684 4758 2696 4758 2696 4759 2697 4759 2685 4759 2685 4760 2697 4760 2698 4760 2686 4761 2685 4761 2698 4761 2698 4762 2699 4762 2686 4762 2683 4763 2686 4763 2699 4763 2699 4764 2700 4764 2683 4764 2681 4765 2683 4765 2700 4765 2700 4766 2701 4766 2681 4766 2679 4767 2681 4767 2701 4767 2701 4768 2702 4768 2679 4768 2677 4769 2679 4769 2702 4769 2702 4770 2703 4770 2677 4770 2675 4771 2677 4771 2703 4771 2703 4772 2704 4772 2675 4772 2673 4773 2675 4773 2704 4773 2673 4774 2704 4774 2671 4774 2670 4775 2671 4775 2704 4775 2670 4776 2704 4776 2705 4776 2670 4777 2705 4777 2640 4777 2639 4778 2670 4778 2640 4778 2385 4779 2418 4779 2386 4779 2418 4780 2706 4780 2419 4780 2706 4781 2421 4781 2419 4781 2421 4782 2423 4782 2420 4782 2423 4783 2424 4783 2422 4783 2707 4784 2708 4784 2709 4784 2710 4785 2707 4785 2709 4785 2709 4786 2711 4786 2710 4786 2712 4787 2710 4787 2711 4787 2711 4788 2713 4788 2712 4788 2491 4789 2712 4789 2713 4789 2714 4790 2715 4790 2716 4790 2717 4791 2716 4791 2718 4791 2716 4792 2717 4792 2714 4792 2719 4793 2714 4793 2717 4793 2719 4794 2720 4794 2714 4794 2721 4795 2430 4795 2428 4795 2721 4796 2428 4796 2722 4796 2721 4797 2722 4797 2720 4797 2721 4798 2720 4798 2719 4798 2432 4799 2430 4799 2721 4799 2717 4800 2723 4800 2719 4800 2717 4801 2718 4801 2724 4801 2723 4802 2717 4802 2724 4802 2725 4803 2719 4803 2723 4803 2719 4804 2725 4804 2721 4804 2726 4805 2721 4805 2725 4805 2726 4806 2434 4806 2432 4806 2721 4807 2726 4807 2432 4807 2727 4808 2434 4808 2726 4808 2726 4809 2728 4809 2727 4809 2729 4810 2728 4810 2726 4810 2725 4811 2729 4811 2726 4811 2730 4812 2727 4812 2728 4812 2731 4813 2729 4813 2725 4813 2723 4814 2731 4814 2725 4814 2731 4815 2723 4815 2724 4815 2732 4816 2733 4816 2730 4816 2728 4817 2732 4817 2730 4817 2732 4818 2728 4818 2729 4818 2734 4819 2733 4819 2732 4819 2735 4820 2729 4820 2731 4820 2729 4821 2735 4821 2732 4821 2736 4822 2731 4822 2724 4822 2731 4823 2736 4823 2735 4823 2724 4824 2737 4824 2736 4824 2738 4825 2732 4825 2735 4825 2738 4826 2739 4826 2734 4826 2732 4827 2738 4827 2734 4827 2708 4828 2739 4828 2738 4828 2735 4829 2740 4829 2738 4829 2740 4830 2735 4830 2736 4830 2741 4831 2736 4831 2737 4831 2736 4832 2741 4832 2740 4832 2738 4833 2742 4833 2708 4833 2742 4834 2738 4834 2740 4834 2740 4835 2743 4835 2742 4835 2743 4836 2740 4836 2741 4836 2741 4837 2744 4837 2743 4837 2741 4838 2737 4838 2744 4838 2745 4839 2743 4839 2744 4839 2663 4840 2746 4840 2664 4840 2747 4841 2748 4841 2666 4841 2665 4842 2747 4842 2666 4842 2747 4843 2665 4843 2664 4843 2664 4844 2746 4844 2749 4844 2750 4845 2664 4845 2749 4845 2664 4846 2750 4846 2747 4846 2749 4847 2751 4847 2750 4847 2747 4848 2752 4848 2748 4848 2752 4849 2747 4849 2750 4849 2750 4850 2753 4850 2752 4850 2753 4851 2750 4851 2751 4851 2751 4852 2754 4852 2753 4852 2755 4853 2748 4853 2752 4853 2756 4854 2753 4854 2754 4854 2753 4855 2756 4855 2752 4855 2757 4856 2752 4856 2756 4856 2752 4857 2757 4857 2755 4857 2758 4858 2756 4858 2754 4858 2756 4859 2758 4859 2757 4859 2759 4860 2748 4860 2755 4860 2754 4861 2760 4861 2758 4861 2761 4862 2757 4862 2758 4862 2757 4863 2761 4863 2755 4863 2755 4864 2762 4864 2759 4864 2762 4865 2755 4865 2761 4865 2758 4866 2763 4866 2761 4866 2763 4867 2758 4867 2760 4867 2764 4868 2759 4868 2762 4868 2759 4869 2764 4869 2765 4869 2761 4870 2766 4870 2762 4870 2766 4871 2761 4871 2763 4871 2767 4872 2762 4872 2766 4872 2762 4873 2767 4873 2764 4873 2764 4874 2768 4874 2765 4874 2769 4875 2763 4875 2760 4875 2763 4876 2769 4876 2766 4876 2770 4877 2764 4877 2767 4877 2764 4878 2770 4878 2768 4878 2760 4879 2724 4879 2769 4879 2771 4880 2766 4880 2769 4880 2766 4881 2771 4881 2767 4881 2715 4882 2767 4882 2771 4882 2767 4883 2715 4883 2770 4883 2720 4884 2722 4884 2772 4884 2768 4885 2720 4885 2772 4885 2720 4886 2768 4886 2770 4886 2769 4887 2724 4887 2718 4887 2771 4888 2769 4888 2718 4888 2771 4889 2718 4889 2716 4889 2771 4890 2716 4890 2715 4890 2770 4891 2715 4891 2714 4891 2770 4892 2714 4892 2720 4892 2773 4893 2722 4893 2428 4893 2660 4894 2774 4894 2775 4894 2661 4895 2660 4895 2775 4895 2774 4896 2660 4896 2658 4896 2776 4897 2774 4897 2658 4897 2776 4898 2777 4898 2778 4898 2774 4899 2776 4899 2778 4899 2658 4900 2656 4900 2776 4900 2776 4901 2656 4901 2654 4901 2779 4902 2776 4902 2654 4902 2780 4903 2692 4903 2691 4903 2693 4904 2692 4904 2780 4904 2654 4905 2652 4905 2779 4905 2779 4906 2781 4906 2780 4906 2779 4907 2652 4907 2650 4907 2781 4908 2779 4908 2650 4908 2782 4909 2694 4909 2693 4909 2780 4910 2782 4910 2693 4910 2782 4911 2780 4911 2781 4911 2695 4912 2694 4912 2782 4912 2650 4913 2648 4913 2781 4913 2781 4914 2648 4914 2645 4914 2783 4915 2781 4915 2645 4915 2781 4916 2783 4916 2782 4916 2784 4917 2696 4917 2695 4917 2782 4918 2784 4918 2695 4918 2784 4919 2782 4919 2783 4919 2697 4920 2696 4920 2784 4920 2645 4921 2644 4921 2783 4921 2785 4922 2698 4922 2697 4922 2784 4923 2785 4923 2697 4923 2783 4924 2644 4924 2646 4924 2786 4925 2783 4925 2646 4925 2786 4926 2785 4926 2784 4926 2783 4927 2786 4927 2784 4927 2699 4928 2698 4928 2785 4928 2646 4929 2647 4929 2786 4929 2787 4930 2700 4930 2699 4930 2785 4931 2787 4931 2699 4931 2787 4932 2785 4932 2786 4932 2786 4933 2647 4933 2649 4933 2788 4934 2786 4934 2649 4934 2786 4935 2788 4935 2787 4935 2701 4936 2700 4936 2787 4936 2649 4937 2651 4937 2788 4937 2789 4938 2787 4938 2788 4938 2789 4939 2702 4939 2701 4939 2787 4940 2789 4940 2701 4940 2788 4941 2790 4941 2789 4941 2788 4942 2651 4942 2653 4942 2790 4943 2788 4943 2653 4943 2703 4944 2702 4944 2789 4944 2653 4945 2655 4945 2790 4945 2791 4946 2704 4946 2703 4946 2789 4947 2791 4947 2703 4947 2791 4948 2789 4948 2790 4948 2792 4949 2790 4949 2655 4949 2790 4950 2792 4950 2791 4950 2655 4951 2657 4951 2792 4951 2792 4952 2657 4952 2659 4952 2792 4953 2659 4953 2662 4953 2792 4954 2662 4954 2793 4954 2792 4955 2793 4955 2794 4955 2792 4956 2794 4956 2791 4956 2791 4957 2794 4957 2795 4957 2791 4958 2795 4958 2796 4958 2797 4959 2791 4959 2796 4959 2797 4960 2705 4960 2704 4960 2797 4961 2704 4961 2791 4961 2705 4962 2797 4962 2798 4962 2640 4963 2705 4963 2798 4963 2640 4964 2798 4964 2641 4964 2799 4965 2641 4965 2798 4965 2799 4966 2798 4966 2797 4966 2797 4967 2796 4967 2799 4967 2800 4968 2799 4968 2796 4968 2801 4969 2800 4969 2796 4969 2795 4970 2801 4970 2796 4970 2802 4971 2801 4971 2795 4971 2795 4972 2794 4972 2802 4972 2803 4973 2802 4973 2794 4973 2794 4974 2793 4974 2803 4974 2666 4975 2803 4975 2793 4975 2793 4976 2662 4976 2666 4976 2800 4977 2801 4977 2804 4977 2805 4978 2804 4978 2801 4978 2801 4979 2802 4979 2805 4979 2748 4980 2805 4980 2802 4980 2802 4981 2803 4981 2748 4981 2803 4982 2666 4982 2748 4982 2804 4983 2421 4983 2706 4983 2804 4984 2706 4984 2418 4984 2385 4985 2804 4985 2418 4985 2773 4986 2428 4986 2427 4986 2773 4987 2427 4987 2425 4987 2806 4988 2421 4988 2804 4988 2772 4989 2773 4989 2806 4989 2773 4990 2772 4990 2722 4990 2807 4991 2806 4991 2804 4991 2806 4992 2807 4992 2772 4992 2768 4993 2772 4993 2807 4993 2807 4994 2808 4994 2768 4994 2808 4995 2807 4995 2804 4995 2804 4996 2805 4996 2808 4996 2808 4997 2765 4997 2768 4997 2765 4998 2808 4998 2805 4998 2759 4999 2765 4999 2805 4999 2805 5000 2748 5000 2759 5000 2638 5001 2643 5001 2667 5001 2809 5002 2667 5002 2643 5002 2643 5003 2642 5003 2809 5003 2688 5004 2809 5004 2642 5004 2810 5005 2667 5005 2809 5005 2809 5006 2688 5006 2810 5006 2810 5007 2690 5007 2668 5007 2668 5008 2667 5008 2810 5008 2746 5009 2663 5009 2811 5009 2812 5010 2813 5010 2814 5010 2813 5011 2812 5011 2811 5011 2814 5012 2815 5012 2812 5012 2816 5013 2811 5013 2812 5013 2811 5014 2816 5014 2746 5014 2749 5015 2746 5015 2816 5015 2816 5016 2817 5016 2749 5016 2817 5017 2816 5017 2812 5017 2751 5018 2749 5018 2817 5018 2815 5019 2818 5019 2812 5019 2819 5020 2812 5020 2818 5020 2812 5021 2819 5021 2817 5021 2818 5022 2820 5022 2819 5022 2821 5023 2819 5023 2820 5023 2819 5024 2821 5024 2817 5024 2754 5025 2751 5025 2817 5025 2817 5026 2822 5026 2754 5026 2822 5027 2817 5027 2821 5027 2823 5028 2824 5028 2820 5028 2821 5029 2825 5029 2822 5029 2825 5030 2821 5030 2820 5030 2820 5031 2826 5031 2825 5031 2826 5032 2820 5032 2824 5032 2827 5033 2822 5033 2825 5033 2822 5034 2827 5034 2754 5034 2760 5035 2754 5035 2827 5035 2824 5036 2828 5036 2826 5036 2829 5037 2825 5037 2826 5037 2825 5038 2829 5038 2827 5038 2828 5039 2830 5039 2826 5039 2827 5040 2831 5040 2760 5040 2831 5041 2827 5041 2829 5041 2832 5042 2826 5042 2830 5042 2826 5043 2832 5043 2829 5043 2724 5044 2760 5044 2831 5044 2828 5045 2833 5045 2830 5045 2829 5046 2834 5046 2831 5046 2834 5047 2829 5047 2832 5047 2737 5048 2831 5048 2834 5048 2831 5049 2737 5049 2724 5049 2745 5050 2832 5050 2830 5050 2832 5051 2745 5051 2834 5051 2830 5052 2835 5052 2745 5052 2835 5053 2830 5053 2833 5053 2744 5054 2834 5054 2745 5054 2834 5055 2744 5055 2737 5055 2833 5056 2836 5056 2742 5056 2745 5057 2835 5057 2743 5057 2837 5058 2838 5058 2713 5058 2837 5059 2713 5059 2711 5059 2709 5060 2836 5060 2837 5060 2837 5061 2839 5061 2838 5061 2840 5062 2839 5062 2837 5062 2837 5063 2841 5063 2840 5063 2837 5064 2836 5064 2833 5064 2841 5065 2837 5065 2833 5065 2833 5066 2828 5066 2841 5066 2842 5067 2840 5067 2841 5067 2841 5068 2828 5068 2842 5068 2828 5069 2824 5069 2842 5069 2843 5070 2842 5070 2824 5070 2824 5071 2823 5071 2843 5071 2844 5072 2810 5072 2845 5072 2845 5073 2846 5073 2844 5073 2845 5074 2713 5074 2846 5074 2847 5075 2844 5075 2846 5075 2846 5076 2713 5076 2838 5076 2848 5077 2846 5077 2838 5077 2846 5078 2848 5078 2847 5078 2848 5079 2838 5079 2839 5079 2849 5080 2848 5080 2839 5080 2848 5081 2849 5081 2847 5081 2839 5082 2840 5082 2849 5082 2850 5083 2847 5083 2849 5083 2849 5084 2851 5084 2850 5084 2851 5085 2849 5085 2840 5085 2851 5086 2840 5086 2842 5086 2852 5087 2850 5087 2851 5087 2851 5088 2853 5088 2852 5088 2853 5089 2851 5089 2842 5089 2854 5090 2852 5090 2853 5090 2853 5091 2842 5091 2843 5091 2853 5092 2818 5092 2854 5092 2853 5093 2843 5093 2823 5093 2818 5094 2853 5094 2823 5094 2854 5095 2818 5095 2815 5095 2814 5096 2854 5096 2815 5096 2823 5097 2820 5097 2818 5097 2810 5098 2855 5098 2690 5098 2844 5099 2855 5099 2810 5099 2847 5100 2777 5100 2855 5100 2844 5101 2847 5101 2855 5101 2850 5102 2778 5102 2777 5102 2847 5103 2850 5103 2777 5103 2850 5104 2852 5104 2778 5104 2774 5105 2778 5105 2852 5105 2852 5106 2854 5106 2774 5106 2775 5107 2774 5107 2854 5107 2854 5108 2814 5108 2775 5108 2661 5109 2775 5109 2814 5109 2690 5110 2855 5110 2691 5110 2691 5111 2855 5111 2777 5111 2777 5112 2856 5112 2691 5112 2856 5113 2780 5113 2691 5113 2779 5114 2856 5114 2776 5114 2780 5115 2856 5115 2779 5115 2776 5116 2856 5116 2777 5116 2424 5117 2773 5117 2425 5117 2423 5118 2773 5118 2424 5118 2421 5119 2806 5119 2423 5119 2423 5120 2806 5120 2773 5120 2799 5121 2800 5121 2804 5121 2641 5122 2799 5122 2804 5122 2641 5123 2804 5123 2857 5123 2857 5124 2804 5124 2858 5124 2385 5125 2858 5125 2804 5125 2661 5126 2814 5126 2813 5126 2661 5127 2813 5127 2811 5127 2661 5128 2811 5128 2663 5128 2661 5129 2663 5129 2662 5129 2742 5130 2743 5130 2835 5130 2742 5131 2835 5131 2833 5131 2708 5132 2742 5132 2836 5132 2708 5133 2836 5133 2709 5133 2711 5134 2709 5134 2837 5134 2859 5135 2049 5135 2057 5135 2859 5136 2860 5136 2049 5136 2050 5137 2049 5137 2860 5137 2860 5138 2861 5138 2050 5138 2861 5139 2862 5139 2050 5139 2617 5140 2861 5140 2860 5140 2862 5141 2861 5141 2617 5141 2621 5142 2863 5142 2617 5142 2621 5143 1963 5143 2863 5143 2616 5144 2863 5144 1963 5144 2239 5145 2064 5145 2862 5145 2064 5146 2050 5146 2862 5146 2240 5147 2239 5147 2862 5147 2241 5148 2240 5148 2862 5148 2242 5149 2241 5149 2862 5149 2864 5150 2242 5150 2862 5150 2865 5151 2864 5151 2863 5151 2864 5152 2617 5152 2863 5152 2864 5153 2862 5153 2617 5153 2617 5154 2688 5154 2573 5154 2617 5155 2810 5155 2688 5155 2617 5156 2860 5156 2810 5156 2810 5157 2860 5157 2845 5157 2860 5158 2859 5158 2713 5158 2713 5159 2845 5159 2860 5159 2859 5160 2057 5160 2713 5160 2057 5161 2491 5161 2713 5161 2057 5162 2059 5162 2490 5162 2490 5163 2491 5163 2057 5163 2866 5164 2513 5164 2512 5164 2512 5165 2687 5165 2866 5165 2689 5166 2866 5166 2687 5166 2512 5167 2511 5167 2573 5167 2512 5168 2573 5168 2687 5168 2255 5169 1999 5169 2865 5169 1999 5170 2864 5170 2865 5170 1999 5171 2242 5171 2864 5171 2046 5172 2047 5172 2867 5172 1934 5173 1962 5173 2868 5173 2869 5174 2870 5174 2871 5174 2872 5175 2871 5175 2870 5175 2870 5176 2873 5176 2872 5176 2874 5177 2872 5177 2873 5177 2873 5178 2875 5178 2874 5178 1861 5179 2874 5179 1863 5179 2874 5180 2875 5180 1863 5180 2876 5181 2877 5181 2878 5181 2879 5182 2878 5182 2877 5182 2877 5183 2880 5183 2879 5183 2881 5184 2879 5184 2880 5184 2880 5185 2882 5185 2881 5185 2883 5186 2881 5186 2882 5186 2882 5187 2884 5187 2883 5187 2885 5188 2883 5188 2884 5188 2884 5189 2869 5189 2885 5189 2871 5190 2885 5190 2869 5190 2878 5191 2886 5191 2876 5191 2487 5192 2887 5192 2486 5192 2493 5193 2888 5193 2887 5193 2493 5194 2887 5194 2487 5194 2492 5195 2889 5195 2888 5195 2492 5196 2890 5196 2889 5196 2888 5197 2493 5197 2492 5197 1983 5198 2890 5198 2492 5198 2891 5199 2892 5199 2893 5199 2892 5200 2894 5200 2895 5200 2894 5201 2889 5201 2895 5201 2894 5202 2888 5202 2889 5202 2894 5203 2892 5203 2896 5203 2892 5204 2891 5204 2896 5204 2896 5205 2897 5205 2894 5205 2894 5206 2898 5206 2888 5206 2898 5207 2887 5207 2888 5207 2898 5208 2894 5208 2899 5208 2894 5209 2897 5209 2899 5209 2899 5210 2900 5210 2898 5210 2898 5211 2901 5211 2902 5211 2898 5212 2900 5212 2901 5212 2898 5213 2902 5213 2887 5213 2902 5214 2486 5214 2887 5214 2903 5215 2486 5215 2902 5215 2903 5216 2485 5216 2486 5216 2484 5217 2485 5217 2903 5217 2903 5218 2904 5218 2484 5218 2483 5219 2484 5219 2905 5219 2484 5220 2906 5220 2905 5220 2484 5221 2904 5221 2906 5221 1874 5222 1876 5222 2907 5222 2907 5223 2908 5223 2909 5223 2908 5224 2910 5224 2909 5224 2908 5225 2911 5225 2910 5225 2908 5226 2907 5226 1876 5226 2912 5227 2911 5227 2908 5227 1876 5228 1881 5228 2908 5228 2908 5229 2913 5229 2912 5229 2913 5230 2914 5230 2912 5230 2913 5231 2908 5231 1882 5231 2908 5232 1881 5232 1882 5232 2915 5233 2914 5233 2913 5233 1882 5234 1888 5234 2913 5234 2916 5235 2913 5235 1891 5235 2913 5236 1888 5236 1891 5236 2913 5237 2916 5237 2915 5237 2916 5238 2917 5238 2915 5238 2918 5239 2917 5239 2916 5239 1891 5240 1893 5240 2916 5240 2867 5241 2916 5241 2046 5241 2916 5242 2045 5242 2046 5242 2916 5243 2042 5243 2045 5243 2916 5244 1893 5244 2042 5244 2916 5245 2867 5245 2918 5245 2044 5246 2918 5246 2048 5246 2918 5247 2047 5247 2048 5247 2918 5248 2867 5248 2047 5248 2910 5249 2911 5249 1872 5249 2919 5250 1872 5250 2911 5250 2911 5251 2912 5251 2919 5251 2920 5252 2919 5252 2912 5252 2912 5253 2914 5253 2920 5253 2921 5254 2920 5254 2914 5254 2914 5255 2915 5255 2921 5255 2922 5256 2921 5256 2915 5256 2915 5257 2917 5257 2922 5257 2923 5258 2922 5258 2917 5258 2917 5259 2918 5259 2923 5259 2924 5260 2923 5260 2918 5260 2918 5261 2044 5261 2924 5261 2043 5262 2924 5262 2044 5262 1852 5263 2910 5263 1872 5263 1852 5264 2909 5264 2910 5264 1852 5265 2907 5265 2909 5265 1852 5266 1874 5266 2907 5266 1876 5267 1874 5267 1875 5267 1981 5268 2890 5268 1983 5268 2889 5269 2890 5269 2925 5269 2890 5270 1981 5270 2925 5270 1914 5271 1981 5271 1910 5271 1913 5272 2926 5272 1914 5272 1917 5273 2926 5273 1913 5273 1916 5274 1934 5274 1917 5274 2927 5275 2889 5275 2925 5275 2927 5276 2895 5276 2889 5276 2927 5277 2925 5277 1914 5277 2925 5278 1981 5278 1914 5278 1914 5279 2926 5279 2927 5279 2928 5280 2927 5280 1917 5280 2927 5281 2926 5281 1917 5281 2927 5282 2928 5282 2895 5282 2928 5283 2892 5283 2895 5283 2893 5284 2892 5284 2928 5284 1917 5285 1934 5285 2928 5285 2928 5286 2929 5286 2893 5286 2929 5287 2928 5287 2868 5287 2928 5288 1934 5288 2868 5288 2483 5289 2905 5289 2482 5289 2930 5290 2481 5290 2482 5290 2481 5291 2930 5291 2479 5291 2482 5292 2931 5292 2930 5292 2931 5293 2482 5293 2905 5293 2932 5294 2479 5294 2930 5294 2905 5295 2906 5295 2931 5295 2933 5296 2479 5296 2932 5296 2480 5297 2479 5297 2933 5297 2933 5298 2934 5298 2480 5298 2935 5299 2936 5299 2937 5299 2938 5300 2937 5300 2939 5300 2937 5301 2936 5301 2939 5301 2939 5302 2940 5302 2938 5302 2941 5303 2938 5303 2940 5303 2938 5304 2941 5304 2942 5304 2941 5305 2943 5305 2942 5305 2944 5306 2943 5306 2941 5306 2383 5307 2941 5307 2364 5307 2941 5308 2366 5308 2364 5308 2941 5309 2940 5309 2366 5309 2941 5310 2383 5310 2944 5310 2383 5311 2384 5311 2944 5311 2371 5312 2936 5312 2347 5312 2371 5313 2368 5313 2936 5313 2368 5314 2939 5314 2936 5314 2940 5315 2939 5315 2368 5315 2368 5316 2366 5316 2940 5316 2480 5317 2934 5317 2477 5317 2934 5318 2945 5318 2477 5318 2945 5319 2946 5319 2477 5319 2946 5320 2947 5320 2477 5320 2947 5321 2935 5321 2477 5321 2935 5322 2937 5322 2477 5322 2937 5323 2938 5323 2477 5323 2938 5324 2478 5324 2477 5324 2478 182 1332 182 1292 182 2478 5325 2384 5325 1332 5325 2938 5326 2942 5326 2478 5326 2942 182 2943 182 2478 182 2943 182 2944 182 2478 182 2944 5327 2384 5327 2478 5327 2948 5328 2949 5328 2886 5328 2949 5329 2948 5329 2950 5329 2948 5330 2951 5330 2950 5330 2948 5331 2952 5331 2951 5331 2948 5332 2953 5332 2952 5332 2953 5333 2932 5333 2952 5333 2933 5334 2932 5334 2953 5334 2934 5335 2933 5335 2953 5335 2954 5336 2945 5336 2953 5336 2954 5337 2953 5337 2948 5337 2945 5338 2934 5338 2953 5338 2948 5339 2955 5339 2954 5339 2955 5340 2948 5340 2886 5340 2946 5341 2945 5341 2954 5341 2947 5342 2946 5342 2954 5342 2935 5343 2947 5343 2954 5343 2955 5344 2886 5344 2956 5344 2955 5345 2956 5345 2954 5345 2936 5346 2935 5346 2954 5346 2886 5347 2957 5347 2956 5347 2348 5348 2936 5348 2954 5348 2348 5349 2347 5349 2936 5349 2348 5350 2954 5350 2956 5350 2956 5351 2346 5351 2348 5351 2348 5352 2342 5352 2347 5352 2957 5353 2346 5353 2956 5353 2346 5354 2957 5354 2335 5354 2932 5355 2930 5355 2952 5355 2930 5356 2951 5356 2952 5356 2951 5357 2958 5357 2950 5357 2958 5358 2949 5358 2950 5358 2958 5359 2951 5359 2930 5359 2959 5360 2949 5360 2958 5360 2959 5361 2886 5361 2949 5361 2959 5362 2876 5362 2886 5362 2959 5363 2877 5363 2876 5363 2959 5364 2880 5364 2877 5364 2959 5365 2882 5365 2880 5365 2930 5366 2931 5366 2958 5366 2960 5367 2958 5367 2906 5367 2958 5368 2931 5368 2906 5368 2958 5369 2960 5369 2959 5369 2884 5370 2882 5370 2959 5370 2961 5371 2959 5371 2960 5371 2959 5372 2961 5372 2884 5372 2961 5373 2869 5373 2884 5373 2961 5374 2870 5374 2869 5374 2906 5375 2904 5375 2960 5375 2902 5376 2960 5376 2903 5376 2960 5377 2904 5377 2903 5377 2960 5378 2902 5378 2961 5378 2873 5379 2870 5379 2961 5379 2962 5380 2961 5380 2899 5380 2961 5381 2900 5381 2899 5381 2961 5382 2901 5382 2900 5382 2961 5383 2902 5383 2901 5383 2961 5384 2962 5384 2873 5384 2962 5385 2875 5385 2873 5385 2962 5386 1863 5386 2875 5386 2899 5387 2897 5387 2962 5387 2963 5388 2962 5388 2893 5388 2962 5389 2891 5389 2893 5389 2962 5390 2896 5390 2891 5390 2962 5391 2897 5391 2896 5391 2962 5392 2963 5392 1863 5392 2963 5393 1862 5393 1863 5393 2963 5394 1860 5394 1862 5394 2963 5395 1859 5395 1860 5395 2963 5396 1857 5396 1859 5396 2963 5397 1856 5397 1857 5397 2893 5398 2929 5398 2963 5398 1855 5399 1856 5399 2963 5399 2963 5400 1962 5400 1855 5400 1962 5401 2963 5401 2868 5401 2963 5402 2929 5402 2868 5402 1962 5403 1934 5403 1875 5403 2321 5404 1793 5404 2964 5404 2225 5405 2335 5405 1858 5405 2335 5406 1861 5406 1858 5406 2335 5407 2874 5407 1861 5407 2335 5408 2886 5408 2874 5408 2886 5409 2872 5409 2874 5409 2886 5410 2871 5410 2872 5410 2886 5411 2885 5411 2871 5411 2886 5412 2883 5412 2885 5412 2886 5413 2881 5413 2883 5413 2335 5414 2957 5414 2886 5414 2919 5415 2043 5415 1872 5415 2924 5416 2043 5416 2919 5416 2919 5417 2920 5417 2924 5417 2923 5418 2924 5418 2920 5418 2920 182 2921 182 2923 182 2922 182 2923 182 2921 182 2879 5419 2881 5419 2886 5419 2879 5420 2886 5420 2878 5420 1557 5421 2224 5421 2072 5421 1441 5422 1666 5422 1665 5422 1441 5423 1664 5423 1666 5423 1665 5424 2224 5424 1439 5424 1441 5425 1665 5425 1439 5425 1601 5426 1446 5426 1602 5426 1601 5427 1444 5427 1446 5427 2965 5428 2966 5428 2967 5428 2966 5429 2968 5429 2967 5429 2966 5430 2965 5430 1149 5430 1175 5431 1177 5431 2969 5431 2970 5432 2971 5432 2972 5432 2973 5433 2974 5433 2975 5433 2973 5434 2976 5434 2974 5434 2977 5435 2978 5435 2979 5435 2980 5436 2978 5436 2977 5436 2981 5437 2982 5437 2983 5437 2983 5438 2984 5438 2981 5438 2985 5439 2981 5439 2984 5439 2984 5440 2986 5440 2985 5440 2987 5441 2985 5441 2986 5441 2988 971 2978 971 2980 971 2988 5442 2989 5442 2978 5442 2989 5443 2979 5443 2978 5443 2975 5444 2989 5444 2988 5444 2988 5445 2990 5445 2975 5445 2990 5446 2991 5446 2975 5446 2992 5447 2975 5447 2991 5447 2991 5448 2993 5448 2992 5448 2994 979 2995 979 2996 979 2997 5449 2998 5449 2996 5449 2974 5450 2996 5450 2999 5450 2996 5451 2998 5451 2999 5451 2996 5452 2974 5452 2994 5452 2974 5453 3000 5453 2994 5453 2976 5454 3000 5454 2974 5454 2999 5455 3001 5455 2974 5455 2974 5456 2989 5456 2975 5456 2979 5457 2989 5457 2974 5457 2974 5458 3002 5458 2979 5458 2974 5459 3001 5459 3002 5459 2975 5460 3003 5460 2973 5460 3003 5461 2975 5461 2992 5461 2993 5462 3004 5462 2992 5462 3005 5463 2997 5463 3006 5463 3005 5464 2998 5464 2997 5464 3005 5465 2999 5465 2998 5465 3005 5466 3001 5466 2999 5466 3005 5467 3002 5467 3001 5467 3005 5468 2979 5468 3002 5468 2979 5469 3005 5469 2977 5469 2995 5470 2994 5470 3007 5470 2987 5471 3007 5471 2994 5471 2994 5472 3000 5472 2987 5472 2985 5473 2987 5473 2976 5473 2987 5474 3000 5474 2976 5474 2976 5475 2973 5475 2985 5475 2981 5476 2985 5476 3003 5476 2985 5477 2973 5477 3003 5477 3003 5478 2992 5478 2981 5478 2982 5479 2981 5479 2992 5479 2992 5480 3004 5480 2982 5480 3004 5481 1195 5481 1170 5481 2982 5482 3004 5482 1170 5482 2968 5483 3008 5483 2970 5483 2972 5484 2968 5484 2970 5484 3009 5485 3008 5485 2968 5485 3010 5486 3009 5486 2968 5486 3011 5487 3010 5487 2968 5487 3011 5488 2968 5488 3012 5488 1147 64 3013 64 3014 64 1147 5489 3014 5489 3015 5489 1147 64 3015 64 1149 64 1147 5490 3016 5490 3013 5490 3017 64 3013 64 3016 64 1174 5491 1175 5491 2969 5491 1174 5492 2969 5492 3018 5492 1174 5493 3018 5493 3019 5493 3020 5494 1174 5494 3019 5494 1171 5495 1174 5495 3020 5495 3020 5496 3021 5496 1171 5496 3020 5497 3019 5497 3022 5497 3021 5498 3020 5498 3022 5498 1172 5499 1171 5499 3021 5499 1170 5500 1172 5500 3021 5500 3021 5501 3023 5501 1170 5501 1170 5502 3023 5502 2982 5502 3024 5503 2980 5503 2977 5503 2977 5504 3025 5504 3024 5504 3025 5505 3026 5505 3024 5505 3016 5506 1147 5506 3027 5506 3027 5507 1165 5507 1167 5507 3027 5508 1167 5508 1195 5508 3028 5509 3027 5509 1195 5509 3004 5510 2993 5510 3028 5510 1195 5511 3004 5511 3028 5511 3029 5512 3017 5512 3030 5512 1149 5513 3015 5513 2966 5513 2966 5514 3029 5514 2968 5514 2966 5515 3015 5515 3014 5515 2966 5516 3014 5516 3013 5516 2966 5517 3013 5517 3029 5517 3017 5518 3029 5518 3013 5518 2968 5519 3029 5519 3012 5519 3021 1053 3031 1053 3032 1053 3021 5520 3032 5520 3023 5520 3033 5521 3031 5521 3021 5521 3021 5522 3022 5522 3033 5522 3033 5523 3022 5523 3019 5523 2983 5524 2982 5524 3023 5524 2983 5525 3023 5525 3032 5525 2971 5526 2970 5526 3034 5526 2970 5527 3008 5527 3035 5527 3036 5528 3035 5528 3008 5528 3008 5529 3009 5529 3036 5529 3037 5530 3036 5530 3009 5530 3009 5531 3010 5531 3037 5531 3038 5532 3037 5532 3010 5532 3010 5533 3011 5533 3038 5533 3039 5534 3038 5534 3011 5534 1164 5535 1165 5535 3027 5535 3012 5536 3040 5536 3041 5536 3012 5537 3042 5537 3040 5537 3043 5538 3040 5538 3042 5538 3026 5539 3040 5539 3043 5539 3026 5540 3025 5540 3040 5540 3025 5541 2977 5541 3040 5541 3005 5542 3040 5542 2977 5542 3044 5543 3040 5543 3005 5543 3045 5544 3040 5544 3044 5544 3046 5545 3040 5545 3045 5545 3041 5546 3040 5546 3046 5546 3026 5547 3043 5547 3024 5547 3024 5548 2988 5548 2980 5548 3024 5549 2990 5549 2988 5549 3024 1083 3047 1083 2990 1083 2991 5550 2990 5550 3047 5550 3028 5551 2991 5551 3047 5551 3048 5552 3028 5552 3047 5552 3048 5553 3047 5553 3049 5553 3043 5554 3047 5554 3024 5554 3043 5555 3049 5555 3047 5555 3046 5556 3011 5556 3041 5556 3048 5557 3049 5557 3050 5557 3050 5558 3049 5558 3051 5558 3011 5559 3046 5559 3039 5559 3030 5560 3043 5560 3042 5560 3042 5561 3012 5561 3030 5561 3030 5562 3012 5562 3029 5562 3043 5563 3030 5563 3049 5563 3030 5564 3017 5564 3051 5564 3030 5565 3051 5565 3049 5565 3027 5566 3028 5566 3048 5566 3027 5567 3048 5567 3050 5567 3027 5568 3050 5568 3051 5568 3041 5569 3011 5569 3012 5569 3028 5570 2993 5570 2991 5570 3016 5571 3051 5571 3017 5571 3016 5572 3027 5572 3051 5572 1164 5573 3027 5573 1147 5573 3052 5574 3053 5574 3054 5574 3052 5575 3054 5575 3055 5575 3056 5576 3052 5576 3055 5576 3057 5577 3053 5577 3052 5577 3052 5578 3058 5578 3057 5578 3057 5579 3058 5579 3059 5579 3060 5580 3057 5580 3059 5580 3060 5581 3061 5581 3057 5581 3059 5582 3062 5582 3060 5582 3063 5583 3060 5583 3062 5583 3064 5584 3063 5584 3062 5584 3064 5585 3065 5585 3066 5585 3063 5586 3064 5586 3066 5586 3067 5587 3068 5587 3069 5587 3070 5588 3068 5588 3067 5588 3067 5589 3071 5589 3070 5589 3072 5590 3070 5590 3071 5590 3071 5591 3073 5591 3072 5591 2971 5592 3072 5592 3073 5592 3074 5593 3075 5593 2972 5593 2972 5594 3073 5594 3074 5594 3073 5595 2972 5595 2971 5595 3076 5596 3077 5596 3078 5596 3075 5597 3076 5597 3078 5597 3075 5598 3078 5598 3079 5598 3075 5599 3079 5599 3080 5599 3075 5600 3080 5600 3081 5600 2967 1134 3075 1134 3081 1134 3075 5601 2967 5601 2972 5601 2972 5602 2967 5602 2968 5602 3082 182 3083 182 3084 182 1178 5603 1179 5603 2969 5603 1177 5604 1178 5604 2969 5604 3085 5605 1189 5605 3086 5605 1192 5606 1189 5606 3085 5606 3085 5607 3087 5607 1192 5607 1193 5608 1192 5608 3087 5608 3087 1143 3088 1143 1193 1143 1194 5609 1193 5609 3088 5609 3089 5610 3090 5610 1194 5610 3088 5611 3089 5611 1194 5611 3091 5612 3090 5612 3089 5612 3089 5613 3092 5613 3091 5613 3091 5614 3092 5614 3018 5614 3091 5615 3018 5615 2969 5615 1179 5616 3091 5616 2969 5616 1189 5617 1190 5617 3086 5617 1190 5618 1191 5618 3086 5618 3093 5619 3057 5619 3061 5619 1157 5620 1158 5620 3093 5620 3094 5621 3053 5621 3057 5621 3093 5622 3094 5622 3057 5622 3093 5623 1158 5623 1159 5623 3093 5624 1159 5624 1160 5624 3093 5625 1160 5625 3095 5625 3093 5626 3095 5626 3096 5626 3094 5627 3093 5627 3096 5627 3053 5628 3094 5628 3097 5628 3053 5629 3097 5629 3098 5629 3054 5630 3053 5630 3098 5630 1151 5631 3099 5631 3100 5631 1151 5632 3100 5632 3101 5632 1152 5633 1151 5633 3101 5633 3099 5634 1151 5634 1150 5634 2965 5635 3099 5635 1150 5635 2965 5636 3081 5636 3080 5636 2965 5637 3080 5637 3079 5637 2965 5638 3079 5638 3102 5638 2965 5639 3102 5639 3099 5639 2967 5640 3081 5640 2965 5640 2965 5641 1150 5641 1149 5641 3088 222 3087 222 3103 222 3089 5642 3088 5642 3103 5642 3070 5643 3104 5643 3068 5643 3105 5644 3104 5644 3070 5644 3070 5645 3072 5645 3105 5645 3069 5646 3068 5646 3106 5646 3082 64 3065 64 3064 64 3082 228 3064 228 3062 228 3084 64 3065 64 3082 64 3054 5647 3107 5647 3108 5647 3055 5648 3054 5648 3108 5648 3108 5649 3109 5649 3055 5649 3055 5650 3109 5650 3110 5650 3056 5651 3055 5651 3110 5651 3110 5652 3109 5652 3111 5652 3112 5653 3110 5653 3111 5653 3111 5654 3113 5654 3112 5654 3113 5655 3114 5655 3115 5655 3116 5656 3115 5656 3114 5656 3112 5657 3113 5657 3115 5657 3112 5658 3115 5658 3117 5658 3112 5659 3117 5659 3118 5659 3112 5660 3118 5660 3119 5660 3120 5661 3112 5661 3119 5661 3119 5662 3121 5662 3120 5662 3122 5663 3116 5663 3114 5663 3114 5664 3123 5664 3122 5664 3120 5665 3121 5665 3124 5665 3120 5666 3124 5666 3125 5666 3126 5667 3120 5667 3125 5667 3125 5668 3127 5668 3126 5668 3128 5669 3126 5669 3127 5669 3127 5670 3129 5670 3128 5670 3130 5671 3128 5671 3129 5671 3129 5672 3131 5672 3130 5672 3130 5673 3131 5673 3132 5673 3130 5674 3132 5674 3133 5674 3134 5675 3130 5675 3133 5675 3133 5676 3135 5676 3134 5676 3136 5677 3137 5677 3138 5677 3139 5678 3136 5678 3138 5678 3134 5679 3135 5679 3137 5679 3137 5680 3136 5680 3140 5680 3140 5681 3134 5681 3137 5681 3136 5682 3141 5682 3140 5682 3140 5683 3141 5683 3142 5683 3143 5684 3140 5684 3142 5684 3142 5685 3144 5685 3078 5685 3078 5686 3144 5686 3145 5686 3079 5687 3078 5687 3145 5687 3127 270 3125 270 3129 270 3131 5688 3129 5688 3125 5688 3125 5689 3146 5689 3131 5689 3147 5690 3131 5690 3146 5690 3146 5691 3148 5691 3147 5691 3149 5692 3147 5692 3148 5692 3148 270 3150 270 3149 270 3151 5693 3149 5693 3150 5693 3150 270 3152 270 3151 270 3153 5694 3151 5694 3152 5694 3152 270 3154 270 3153 270 3155 270 3153 270 3154 270 3156 182 3157 182 3158 182 3159 5695 3158 5695 3157 5695 3157 182 3160 182 3159 182 3161 182 3159 182 3160 182 3160 182 3162 182 3161 182 3161 182 3162 182 3163 182 3164 182 3161 182 3163 182 3163 1226 3165 1226 3164 1226 3166 182 3164 182 3165 182 3137 5696 3167 5696 3138 5696 3168 5697 3138 5697 3167 5697 3167 5698 3169 5698 3168 5698 3170 5699 3168 5699 3169 5699 3169 5700 3171 5700 3170 5700 3172 5701 3170 5701 3171 5701 3171 5702 3173 5702 3172 5702 3174 5703 3172 5703 3173 5703 3173 5704 3175 5704 3174 5704 3176 5705 3174 5705 3175 5705 3175 5706 3177 5706 3176 5706 3178 5707 3176 5707 3177 5707 3177 5708 3179 5708 3178 5708 3180 5709 3178 5709 3179 5709 3179 5710 3181 5710 3180 5710 3182 5711 3180 5711 3181 5711 3115 5712 3183 5712 3117 5712 3184 5713 3117 5713 3183 5713 3183 5714 3185 5714 3184 5714 3186 5714 3184 5714 3185 5714 3185 294 3187 294 3186 294 3188 295 3186 295 3187 295 3187 296 3189 296 3188 296 3190 5715 3188 5715 3189 5715 3189 5716 3191 5716 3190 5716 3192 5717 3190 5717 3191 5717 3191 5718 3193 5718 3192 5718 3194 5719 3192 5719 3193 5719 3193 302 3195 302 3194 302 3196 302 3194 302 3195 302 3195 5720 3197 5720 3196 5720 3198 5721 3196 5721 3197 5721 3184 5722 3118 5722 3117 5722 3186 5723 3121 5723 3119 5723 3186 5724 3119 5724 3118 5724 3184 5725 3186 5725 3118 5725 3186 5726 3188 5726 3121 5726 3199 5727 3125 5727 3124 5727 3199 5728 3124 5728 3121 5728 3121 5729 3188 5729 3190 5729 3199 5730 3121 5730 3190 5730 3146 5731 3125 5731 3199 5731 3190 5732 3192 5732 3199 5732 3199 5733 3192 5733 3194 5733 3200 5734 3199 5734 3194 5734 3200 5735 3148 5735 3146 5735 3199 5736 3200 5736 3146 5736 3150 5737 3148 5737 3200 5737 3194 5738 3196 5738 3200 5738 3201 5739 3152 5739 3150 5739 3200 5740 3201 5740 3150 5740 3200 5741 3196 5741 3198 5741 3200 5742 3198 5742 3202 5742 3201 5743 3200 5743 3202 5743 3152 5744 3201 5744 3203 5744 3154 5745 3152 5745 3203 5745 3137 5746 3135 5746 3167 5746 3169 5747 3167 5747 3135 5747 3135 5748 3133 5748 3169 5748 3169 5749 3133 5749 3204 5749 3171 5750 3169 5750 3204 5750 3205 5751 3173 5751 3171 5751 3204 5752 3205 5752 3171 5752 3132 5753 3131 5753 3205 5753 3205 5754 3204 5754 3132 5754 3131 5755 3147 5755 3205 5755 3175 5756 3173 5756 3205 5756 3205 5757 3147 5757 3149 5757 3206 5758 3205 5758 3149 5758 3206 5759 3177 5759 3175 5759 3205 5760 3206 5760 3175 5760 3149 5761 3151 5761 3206 5761 3179 5762 3177 5762 3206 5762 3206 5763 3151 5763 3153 5763 3153 5764 3155 5764 3206 5764 3206 348 3155 348 3207 348 3208 5765 3206 5765 3207 5765 3206 5766 3208 5766 3179 5766 3179 5767 3208 5767 3209 5767 3181 5768 3179 5768 3209 5768 3115 5769 3210 5769 3183 5769 3185 5770 3183 5770 3210 5770 3210 5771 3211 5771 3185 5771 3187 5772 3185 5772 3211 5772 3211 5773 3212 5773 3187 5773 3189 5774 3187 5774 3212 5774 3213 5775 3191 5775 3189 5775 3212 5776 3213 5776 3189 5776 3214 5777 3158 5777 3213 5777 3215 5778 3214 5778 3213 5778 3216 5779 3215 5779 3213 5779 3213 5780 3212 5780 3216 5780 3158 5781 3159 5781 3213 5781 3193 5782 3191 5782 3213 5782 3213 5783 3159 5783 3161 5783 3213 5784 3161 5784 3164 5784 3213 5785 3164 5785 3166 5785 3213 5786 3166 5786 3217 5786 3218 5787 3213 5787 3217 5787 3218 5788 3195 5788 3193 5788 3213 5789 3218 5789 3193 5789 3195 5790 3218 5790 3219 5790 3197 5791 3195 5791 3219 5791 3054 5792 3098 5792 3107 5792 3220 5793 3107 5793 3098 5793 3098 5794 3097 5794 3220 5794 3221 379 3220 379 3097 379 3097 5795 3096 5795 3221 5795 3222 5795 3221 5795 3096 5795 3096 5796 3095 5796 3222 5796 3223 5797 3222 5797 3095 5797 3095 383 1160 383 3223 383 1143 384 3223 384 1160 384 3145 5798 3224 5798 3079 5798 3102 5799 3079 5799 3224 5799 3224 5800 3225 5800 3102 5800 3099 5801 3102 5801 3225 5801 3225 5802 3226 5802 3099 5802 3100 5803 3099 5803 3226 5803 3226 5804 3227 5804 3100 5804 3101 5805 3100 5805 3227 5805 3227 5806 1132 5806 3101 5806 1152 5807 3101 5807 1132 5807 3136 1340 3228 1340 3141 1340 3224 5808 3145 5808 3144 5808 3229 5809 3142 5809 3141 5809 3142 5810 3229 5810 3144 5810 3144 5811 3230 5811 3224 5811 3230 5812 3144 5812 3229 5812 3141 5813 3231 5813 3229 5813 3231 5814 3141 5814 3228 5814 3232 5815 3229 5815 3231 5815 3229 1349 3232 1349 3230 1349 3225 5816 3224 5816 3230 5816 3230 5817 3233 5817 3225 5817 3233 5818 3230 5818 3232 5818 3228 5819 3234 5819 3231 5819 3235 5820 3232 5820 3231 5820 3232 5821 3235 5821 3233 5821 3226 5822 3225 5822 3233 5822 3236 1357 3233 1357 3235 1357 3233 5823 3236 5823 3226 5823 3234 5824 1122 5824 3231 5824 3231 5825 3237 5825 3235 5825 3237 5826 3231 5826 1122 5826 1122 5827 1123 5827 3237 5827 3227 5828 3226 5828 3236 5828 3235 5829 1126 5829 3236 5829 1126 5830 3235 5830 3237 5830 1124 5831 3237 5831 1123 5831 3237 5832 1124 5832 1126 5832 1132 5833 3227 5833 3236 5833 1126 5834 1128 5834 3236 5834 3236 5835 1128 5835 1132 5835 1133 5836 1145 5836 3238 5836 3239 5837 3114 5837 3113 5837 3239 5838 3113 5838 3240 5838 3238 5839 3239 5839 3240 5839 3239 5840 3238 5840 1145 5840 3123 5841 3114 5841 3239 5841 1145 5842 1402 5842 3239 5842 3241 5843 3239 5843 1402 5843 3241 5844 3242 5844 3243 5844 3243 5845 3123 5845 3239 5845 3244 5846 3241 5846 1402 5846 1402 5847 1401 5847 3244 5847 1400 5848 3245 5848 3244 5848 1401 5849 1400 5849 3244 5849 3246 5850 3245 5850 1400 5850 1400 5851 1144 5851 3246 5851 3246 5852 3228 5852 3139 5852 3246 5853 1144 5853 1122 5853 3246 5854 1122 5854 3234 5854 3228 5855 3246 5855 3234 5855 3136 5856 3139 5856 3228 5856 3107 5857 3220 5857 3108 5857 3247 5858 3108 5858 3220 5858 3108 5859 3247 5859 3109 5859 3240 5860 3113 5860 3111 5860 3111 5861 3248 5861 3240 5861 3248 5862 3111 5862 3109 5862 3109 452 3249 452 3248 452 3249 5863 3109 5863 3247 5863 3247 5864 3250 5864 3249 5864 3250 5865 3247 5865 3220 5865 3220 5866 3221 5866 3250 5866 3238 5867 3240 5867 3248 5867 3248 5868 3251 5868 3238 5868 3251 5869 3248 5869 3249 5869 3252 5870 3249 5870 3250 5870 3249 461 3252 461 3251 461 3253 5871 3250 5871 3221 5871 3250 5872 3253 5872 3252 5872 3221 5873 3222 5873 3253 5873 1133 5874 3238 5874 3251 5874 3254 5875 3251 5875 3252 5875 3251 5876 3254 5876 1133 5876 3255 5877 3252 5877 3253 5877 3252 5878 3255 5878 3254 5878 3256 5879 3253 5879 3222 5879 3253 5880 3256 5880 3255 5880 1136 5881 1133 5881 3254 5881 1136 5882 3254 5882 3255 5882 3222 5883 3223 5883 3256 5883 1138 5884 3255 5884 3256 5884 3255 5885 1138 5885 1136 5885 3223 5886 1143 5886 3256 5886 1140 5887 3256 5887 1143 5887 3256 5888 1140 5888 1138 5888 3257 5889 3243 5889 3242 5889 3258 5890 3243 5890 3257 5890 3257 5891 3259 5891 3258 5891 3260 5892 3258 5892 3259 5892 3259 5893 3261 5893 3260 5893 3260 5894 3261 5894 3156 5894 3260 5895 3156 5895 3158 5895 3110 182 3112 182 3120 182 3110 182 3120 182 3126 182 3110 182 3126 182 3128 182 3110 5896 3128 5896 3130 5896 3110 5897 3130 5897 3134 5897 3110 5898 3134 5898 3140 5898 3143 5899 3110 5899 3140 5899 3143 5900 3076 5900 3075 5900 3143 5901 3075 5901 3074 5901 3143 5902 3074 5902 3073 5902 3143 5903 3073 5903 3071 5903 3143 5904 3071 5904 3067 5904 3143 5905 3067 5905 3069 5905 3069 495 3106 495 3083 495 3143 5906 3069 5906 3083 5906 3143 5907 3083 5907 3082 5907 3143 5908 3082 5908 3062 5908 3143 5909 3062 5909 3059 5909 3143 5910 3059 5910 3058 5910 3143 5911 3058 5911 3052 5911 3143 5912 3052 5912 3056 5912 3110 5913 3143 5913 3056 5913 3077 495 3076 495 3143 495 3094 495 3096 495 3097 495 3133 270 3132 270 3204 270 3242 5914 3241 5914 3244 5914 3244 5915 3245 5915 3242 5915 3239 5916 3241 5916 3243 5916 3158 5917 3214 5917 3260 5917 3243 5918 3258 5918 3260 5918 3214 5919 3243 5919 3260 5919 3214 5920 3215 5920 3243 5920 3215 5921 3216 5921 3243 5921 3123 5922 3243 5922 3216 5922 3123 5923 3216 5923 3212 5923 3123 5924 3212 5924 3211 5924 3122 5925 3123 5925 3211 5925 3122 5926 3211 5926 3210 5926 3116 5927 3122 5927 3210 5927 3115 5928 3116 5928 3210 5928 3138 5929 3262 5929 3263 5929 3263 1466 3262 1466 3264 1466 3264 5930 3262 5930 3265 5930 3264 5931 3265 5931 3266 5931 3266 5932 3265 5932 3267 5932 3266 5933 3267 5933 3268 5933 3266 5934 3268 5934 3269 5934 3270 5935 3269 5935 3268 5935 3271 5936 3269 5936 3270 5936 3271 5937 3272 5937 3269 5937 3269 5938 3272 5938 3273 5938 3274 5939 3272 5939 3271 5939 3246 5940 3269 5940 3245 5940 3272 5941 3274 5941 3156 5941 3272 5942 3156 5942 3261 5942 3259 5943 3272 5943 3261 5943 3272 5944 3259 5944 3273 5944 3257 5945 3273 5945 3259 5945 3273 5946 3257 5946 3269 5946 3257 1484 3242 1484 3269 1484 3269 5947 3246 5947 3266 5947 3245 5948 3269 5948 3242 5948 3266 5949 3246 5949 3139 5949 3182 5950 3275 5950 3180 5950 3180 5951 3275 5951 3276 5951 3277 5952 3178 5952 3276 5952 3276 5953 3178 5953 3180 5953 3276 5954 3278 5954 3277 5954 3277 5955 3278 5955 3165 5955 3277 5956 3165 5956 3163 5956 3277 5957 3163 5957 3279 5957 3277 5958 3279 5958 3280 5958 3178 5959 3277 5959 3176 5959 3274 5960 3277 5960 3280 5960 3277 5961 3268 5961 3267 5961 3268 5962 3277 5962 3270 5962 3270 5963 3277 5963 3271 5963 3271 5964 3277 5964 3274 5964 3267 5965 3174 5965 3277 5965 3277 5966 3174 5966 3176 5966 3174 5967 3267 5967 3172 5967 3265 5968 3172 5968 3267 5968 3172 5969 3265 5969 3170 5969 3262 5970 3170 5970 3265 5970 3170 5971 3262 5971 3168 5971 3138 5972 3168 5972 3262 5972 3160 182 3279 182 3162 182 3279 182 3160 182 3280 182 3157 182 3280 182 3160 182 3280 182 3157 182 3274 182 3156 182 3274 182 3157 182 3139 5973 3264 5973 3266 5973 3264 5974 3139 5974 3263 5974 3263 5975 3139 5975 3138 5975 3162 182 3279 182 3163 182 3078 5976 3143 5976 3142 5976 3077 5977 3143 5977 3078 5977 3106 182 3104 182 3083 182 3106 5978 3068 5978 3104 5978 3281 270 3155 270 3282 270 3283 270 3281 270 3282 270 3284 270 3285 270 3282 270 3286 270 3287 270 3283 270 3282 5979 3288 5979 3284 5979 3289 5980 3283 5980 3287 5980 3290 5981 3284 5981 3288 5981 3287 5982 3291 5982 3289 5982 3288 5983 3292 5983 3290 5983 3293 5984 3289 5984 3291 5984 3294 270 3290 270 3292 270 3291 270 3295 270 3293 270 3296 270 3293 270 3295 270 3292 270 3297 270 3294 270 3295 270 3298 270 3296 270 3299 577 3294 577 3297 577 3296 5985 3298 5985 3300 5985 3301 270 3296 270 3300 270 3302 270 3303 270 3299 270 3297 270 3302 270 3299 270 3304 270 3303 270 3302 270 3300 270 3304 270 3301 270 3305 270 3301 270 3304 270 3306 270 3305 270 3304 270 3302 5986 3306 5986 3304 5986 3307 5987 3182 5987 3308 5987 3309 581 3310 581 3198 581 3311 5988 3288 5988 3203 5988 3312 5989 3311 5989 3201 5989 3312 5990 3198 5990 3310 5990 3313 5991 3312 5991 3310 5991 3283 270 3155 270 3281 270 3155 5992 3283 5992 3314 5992 3314 5993 3315 5993 3207 5993 3315 5994 3316 5994 3208 5994 3316 5995 3308 5995 3209 5995 3307 5996 3317 5996 3182 5996 3317 5997 3318 5997 3276 5997 3318 5998 3319 5998 3278 5998 3320 5999 3321 5999 3166 5999 3321 6000 3322 6000 3218 6000 3322 6001 3309 6001 3219 6001 3323 6002 3288 6002 3311 6002 3311 6003 3312 6003 3323 6003 3324 6004 3323 6004 3312 6004 3312 6005 3313 6005 3324 6005 3314 6006 3325 6006 3315 6006 3316 6007 3315 6007 3325 6007 3325 6008 3326 6008 3316 6008 3316 6009 3326 6009 3308 6009 3327 6010 3292 6010 3288 6010 3323 6011 3327 6011 3288 6011 3324 6012 3313 6012 3327 6012 3323 6013 3324 6013 3327 6013 3313 6014 3328 6014 3327 6014 3297 6015 3292 6015 3327 6015 3329 6016 3327 6016 3328 6016 3329 6017 3302 6017 3297 6017 3327 6018 3329 6018 3297 6018 3328 6019 3330 6019 3329 6019 3306 6020 3302 6020 3329 6020 3329 6021 3330 6021 3331 6021 3332 6022 3329 6022 3331 6022 3329 6023 3332 6023 3306 6023 3305 6024 3306 6024 3332 6024 3331 6025 3333 6025 3332 6025 3334 6026 3332 6026 3333 6026 3332 6027 3334 6027 3305 6027 3301 6028 3305 6028 3334 6028 3333 6029 3335 6029 3334 6029 3336 6030 3296 6030 3301 6030 3334 634 3336 634 3301 634 3336 6031 3334 6031 3335 6031 3293 6032 3296 6032 3336 6032 3335 6033 3308 6033 3336 6033 3325 6034 3289 6034 3293 6034 3336 6035 3325 6035 3293 6035 3336 6036 3308 6036 3326 6036 3336 6037 3326 6037 3325 6037 3314 6038 3289 6038 3325 6038 3289 6039 3314 6039 3283 6039 3166 182 3319 182 3320 182 3320 182 3337 182 3338 182 3319 182 3337 182 3320 182 3313 1582 3310 1582 3309 1582 3308 6040 3335 6040 3339 6040 3339 6041 3307 6041 3308 6041 3330 6042 3328 6042 3340 6042 3340 1585 3341 1585 3330 1585 3331 6043 3330 6043 3341 6043 3341 6044 3342 6044 3331 6044 3342 6045 3343 6045 3333 6045 3333 6045 3331 6045 3342 6045 3343 653 3339 653 3335 653 3335 654 3333 654 3343 654 3328 6046 3313 6046 3309 6046 3309 6047 3340 6047 3328 6047 3322 6048 3340 6048 3309 6048 3321 6049 3340 6049 3322 6049 3338 6050 3341 6050 3340 6050 3338 6051 3342 6051 3341 6051 3338 661 3337 661 3342 661 3337 6052 3343 6052 3342 6052 3339 6053 3343 6053 3337 6053 3317 6054 3307 6054 3339 6054 3317 6055 3339 6055 3318 6055 3282 6056 3286 6056 3283 6056 3282 270 3285 270 3286 270 3282 6057 3203 6057 3288 6057 3321 6058 3338 6058 3340 6058 3320 1605 3338 1605 3321 1605 3319 6059 3318 6059 3337 6059 3318 6060 3339 6060 3337 6060 3063 6061 3344 6061 3061 6061 3060 6062 3063 6062 3061 6062 3345 182 3084 182 3083 182 3346 6063 3085 6063 3086 6063 1191 675 1187 675 3086 675 3093 6064 3061 6064 3344 6064 3093 6065 3347 6065 1157 6065 3085 6066 3346 6066 3348 6066 3348 679 3349 679 3085 679 3066 680 3065 680 3084 680 3181 6067 3308 6067 3182 6067 3165 182 3319 182 3166 182 3197 581 3309 581 3198 581 3203 6068 3201 6068 3311 6068 3201 6069 3202 6069 3312 6069 3312 6070 3202 6070 3198 6070 3207 6071 3155 6071 3314 6071 3208 6072 3207 6072 3315 6072 3209 6073 3208 6073 3316 6073 3181 6074 3209 6074 3308 6074 3317 6075 3275 6075 3182 6075 3276 6076 3275 6076 3317 6076 3278 6077 3276 6077 3318 6077 3165 6078 3278 6078 3319 6078 3321 6079 3217 6079 3166 6079 3218 6080 3217 6080 3321 6080 3219 6081 3218 6081 3322 6081 3197 6082 3219 6082 3309 6082 3282 270 3155 270 3154 270 3154 6083 3203 6083 3282 6083 1119 6084 1115 6084 3350 6084 3086 6085 3351 6085 3352 6085 3346 6086 3086 6086 3352 6086 3353 6087 3354 6087 3355 6087 3353 6088 3356 6088 3354 6088 3357 6089 3358 6089 3359 6089 3359 6090 3358 6090 3360 6090 3360 6091 3358 6091 3361 6091 3361 6092 3358 6092 3362 6092 3362 6093 3358 6093 3363 6093 3363 6094 3358 6094 3364 6094 3361 6095 3365 6095 3360 6095 3366 6096 3367 6096 3365 6096 3365 6097 3367 6097 3368 6097 3354 6098 3368 6098 3367 6098 3369 6099 3368 6099 3354 6099 3370 6100 3369 6100 3354 6100 3369 6101 3371 6101 3368 6101 3360 6102 3365 6102 3368 6102 3360 6103 3368 6103 3371 6103 3372 6104 3373 6104 3374 6104 3363 6105 3373 6105 3372 6105 3354 6106 3356 6106 3370 6106 3345 6107 3066 6107 3084 6107 3375 6108 3066 6108 3345 6108 3376 6109 3375 6109 3345 6109 3377 6110 3376 6110 3345 6110 3345 725 3364 725 3377 725 3358 6111 3377 6111 3364 6111 3373 6112 3363 6112 3364 6112 3378 6113 3379 6113 3380 6113 3350 6114 3379 6114 3378 6114 3378 6115 3381 6115 3350 6115 3382 731 3350 731 3381 731 3381 6116 3383 6116 3382 6116 3383 733 3352 733 3382 733 3383 734 3384 734 3352 734 3346 735 3352 735 3384 735 3385 6117 3346 6117 3384 6117 3386 6118 3387 6118 3388 6118 3387 6119 3389 6119 3388 6119 3388 6120 3390 6120 3386 6120 3391 6121 3386 6121 3390 6121 3390 6122 3392 6122 3391 6122 3393 6123 3391 6123 3392 6123 3392 6124 3394 6124 3393 6124 3395 6125 3393 6125 3394 6125 3394 6126 3396 6126 3395 6126 3397 6127 3395 6127 3396 6127 3396 6128 3398 6128 3397 6128 3399 6129 3397 6129 3398 6129 3398 6130 3380 6130 3399 6130 3399 6131 3380 6131 3379 6131 3348 6132 3346 6132 3385 6132 3400 6133 3401 6133 3402 6133 3401 6134 3400 6134 3403 6134 3404 6135 3405 6135 3401 6135 3406 6136 3407 6136 3408 6136 3409 6137 3408 6137 3407 6137 3409 6138 3355 6138 3408 6138 3409 6139 3410 6139 3355 6139 3409 6140 3411 6140 3410 6140 3409 6141 3412 6141 3411 6141 3413 6142 3412 6142 3409 6142 3414 6143 3409 6143 3415 6143 3409 6144 3407 6144 3415 6144 3409 763 3414 763 3413 763 3414 6145 3416 6145 3413 6145 3415 6146 3417 6146 3414 6146 3418 766 3416 766 3414 766 3414 6147 3401 6147 3418 6147 3401 6148 3419 6148 3418 6148 3401 6149 3405 6149 3419 6149 3414 6150 3402 6150 3401 6150 3414 1702 3417 1702 3402 1702 3408 6151 3366 6151 3406 6151 3367 6152 3366 6152 3408 6152 3354 6153 3367 6153 3408 6153 3408 6154 3355 6154 3354 6154 3355 6155 3410 6155 3420 6155 3420 6156 3353 6156 3355 6156 3421 6157 3357 6157 3359 6157 3422 6158 3359 6158 3360 6158 3359 6159 3422 6159 3421 6159 3360 6160 3371 6160 3422 6160 1154 6161 3421 6161 3422 6161 3422 6162 3423 6162 1154 6162 3347 6163 1156 6163 1157 6163 3347 6164 3093 6164 3344 6164 3347 6165 3357 6165 3421 6165 3347 6166 3424 6166 3357 6166 3347 6167 3344 6167 3424 6167 3347 6168 3421 6168 1156 6168 3421 6169 1154 6169 1156 6169 1155 791 3425 791 1180 791 1182 792 1180 792 3425 792 1182 6170 3369 6170 3370 6170 1182 794 3425 794 3369 794 3370 6171 1117 6171 1182 6171 3370 6172 1118 6172 1117 6172 3370 6173 3426 6173 1118 6173 3427 6174 3426 6174 3356 6174 3426 6175 3370 6175 3356 6175 3356 6176 3353 6176 3427 6176 3428 6177 3427 6177 3353 6177 3353 6178 3420 6178 3428 6178 3410 6179 3428 6179 3420 6179 3366 6180 3365 6180 3362 6180 3361 6181 3362 6181 3365 6181 3429 6182 3430 6182 3402 6182 3402 6183 3417 6183 3429 6183 3363 6184 3372 6184 3407 6184 3372 6185 3415 6185 3407 6185 3372 6186 3417 6186 3415 6186 3363 6187 3407 6187 3362 6187 3407 6188 3406 6188 3362 6188 3366 815 3362 815 3406 815 3431 6189 3396 6189 3394 6189 3431 817 3398 817 3396 817 3380 270 3398 270 3431 270 3431 6190 3378 6190 3380 6190 3431 6191 3381 6191 3378 6191 3431 6192 3383 6192 3381 6192 3431 6193 3384 6193 3383 6193 3431 6194 3385 6194 3384 6194 3400 6195 3402 6195 3430 6195 3350 6196 1115 6196 3379 6196 3351 6197 3350 6197 3382 6197 3382 6198 3352 6198 3351 6198 3350 6199 3351 6199 1119 6199 3351 6200 1184 6200 1119 6200 1186 6201 1184 6201 3351 6201 1186 6202 3351 6202 3086 6202 1187 830 1186 830 3086 830 3425 6203 3423 6203 3369 6203 1154 6204 3423 6204 3425 6204 3425 6205 1155 6205 1154 6205 3364 6206 3345 6206 3083 6206 3357 6207 3377 6207 3358 6207 3377 6208 3357 6208 3424 6208 3377 6209 3424 6209 3376 6209 3424 6210 3375 6210 3376 6210 3063 6211 3375 6211 3424 6211 3375 6212 3063 6212 3066 6212 3424 6213 3344 6213 3063 6213 3379 6214 1115 6214 3399 6214 1118 6215 3426 6215 1114 6215 1115 6216 1114 6216 3426 6216 3426 6217 3427 6217 1115 6217 3427 6218 3399 6218 1115 6218 3397 6219 3399 6219 3410 6219 3399 6220 3428 6220 3410 6220 3399 6221 3427 6221 3428 6221 3410 6222 3411 6222 3397 6222 3395 6223 3397 6223 3411 6223 3411 6224 3412 6224 3395 6224 3393 6225 3395 6225 3413 6225 3395 6226 3412 6226 3413 6226 3413 6227 3416 6227 3393 6227 3391 6228 3393 6228 3416 6228 3416 6229 3418 6229 3391 6229 3386 6230 3391 6230 3419 6230 3391 6231 3418 6231 3419 6231 3419 6232 3405 6232 3386 6232 3387 6233 3386 6233 3405 6233 3432 6234 3364 6234 3083 6234 3364 6235 3432 6235 3373 6235 3035 6236 3034 6236 2970 6236 3034 6237 3433 6237 2971 6237 3434 6238 3018 6238 3435 6238 3019 6239 3018 6239 3434 6239 3434 6240 3436 6240 3019 6240 3436 6241 3033 6241 3019 6241 3092 6242 3435 6242 3018 6242 3092 6243 3437 6243 3435 6243 2983 270 3032 270 3431 270 3431 6244 3434 6244 3435 6244 3431 6245 3436 6245 3434 6245 3431 6246 3033 6246 3436 6246 3431 6247 3031 6247 3033 6247 3431 6248 3032 6248 3031 6248 3435 6249 3437 6249 3431 6249 3437 6250 3438 6250 3431 6250 3103 1808 3431 1808 3438 1808 3373 6251 3039 6251 3046 6251 3373 6252 3038 6252 3039 6252 3373 6253 3037 6253 3038 6253 3373 6254 3036 6254 3037 6254 3373 6255 3035 6255 3036 6255 3373 6256 3034 6256 3035 6256 3373 6257 3433 6257 3034 6257 3373 6258 3105 6258 3433 6258 3439 6259 3440 6259 2995 6259 3007 6260 3439 6260 2995 6260 3441 6261 3442 6261 3440 6261 3439 6262 3441 6262 3440 6262 3443 6263 3442 6263 3441 6263 3444 6264 3445 6264 3443 6264 3441 6265 3444 6265 3443 6265 3444 6266 3446 6266 3445 6266 3373 6267 3046 6267 3045 6267 3373 6268 3045 6268 3044 6268 3447 6269 3448 6269 3449 6269 3449 6270 3450 6270 3447 6270 3447 6271 3450 6271 3403 6271 3451 6272 3447 6272 3403 6272 3452 6273 3005 6273 3006 6273 2997 6274 3453 6274 3454 6274 3453 6275 3449 6275 3454 6275 3448 6276 3454 6276 3449 6276 3455 6277 3442 6277 3443 6277 3456 6278 3455 6278 3443 6278 3456 6279 3450 6279 3449 6279 3456 6280 3449 6280 3455 6280 3443 6281 3445 6281 3456 6281 3456 6282 3445 6282 3457 6282 3456 6283 3404 6283 3450 6283 3455 6284 3453 6284 2997 6284 2996 6285 3455 6285 2997 6285 2996 6286 2995 6286 3440 6286 2996 6287 3440 6287 3442 6287 2996 6288 3442 6288 3455 6288 3453 6289 3455 6289 3449 6289 3446 6290 3444 6290 3458 6290 3439 6291 3459 6291 3460 6291 3441 6292 3439 6292 3460 6292 3461 6293 3459 6293 3439 6293 3439 6294 3007 6294 3461 6294 3462 6295 3461 6295 3007 6295 3007 6296 2987 6296 3462 6296 2986 6297 3462 6297 2987 6297 3044 6298 3005 6298 3373 6298 3373 6299 3005 6299 3452 6299 3444 6300 3463 6300 3458 6300 3441 6301 3463 6301 3444 6301 3441 6302 3460 6302 3463 6302 3006 6303 3373 6303 3452 6303 3431 6304 2986 6304 2984 6304 3431 6305 2984 6305 2983 6305 3087 6306 3085 6306 3349 6306 3349 933 3103 933 3087 933 3103 6307 3438 6307 3089 6307 3092 6308 3089 6308 3438 6308 3438 6309 3437 6309 3092 6309 3433 6310 3105 6310 3072 6310 3072 1867 2971 1867 3433 1867 3458 6311 3464 6311 3446 6311 3387 6312 3446 6312 3464 6312 3389 6313 3387 6313 3464 6313 3404 6314 3401 6314 3403 6314 3404 943 3465 943 3405 943 3404 6315 3457 6315 3465 6315 3404 6316 3403 6316 3450 6316 3404 6317 3456 6317 3457 6317 3348 270 3385 270 3431 270 3349 270 3348 270 3431 270 3431 6318 3103 6318 3349 6318 3430 6319 3466 6319 3400 6319 3403 6320 3400 6320 3466 6320 3466 6321 3451 6321 3403 6321 3465 6322 3387 6322 3405 6322 3446 6323 3387 6323 3457 6323 3387 6324 3465 6324 3457 6324 3446 6325 3457 6325 3445 6325 3432 182 3083 182 3104 182 3432 182 3104 182 3105 182 3432 6326 3105 6326 3373 6326 1555 6327 2224 6327 1557 6327 1442 6328 2224 6328 1555 6328 1439 6329 2224 6329 1442 6329 1352 6330 3467 6330 1356 6330 1349 270 3467 270 1352 270 1347 270 3467 270 1349 270 1343 270 3467 270 1347 270 1344 270 3467 270 1343 270 1341 6331 3467 6331 1344 6331 1335 270 3467 270 1341 270 1266 270 3467 270 1335 270 1267 270 3467 270 1266 270 1372 6332 3467 6332 1267 6332 1372 270 1398 270 3467 270 1398 270 1397 270 3467 270 1397 270 1393 270 3467 270 1393 270 1394 270 3467 270 1394 270 1391 270 3467 270 1391 6333 1388 6333 3467 6333 1388 6334 1386 6334 3467 6334 1386 270 1380 270 3467 270 1380 270 1381 270 3467 270 2321 6335 3468 6335 1176 6335 1426 6336 3468 6336 1432 6336 1194 6337 3468 6337 1188 6337 1188 6338 3468 6338 1423 6338 1423 6339 3468 6339 1427 6339 1427 6340 3468 6340 1426 6340 3090 6341 3468 6341 1194 6341 3091 6342 3468 6342 3090 6342 1179 6343 3468 6343 3091 6343 1179 6344 1176 6344 3468 6344 2964 6345 3467 6345 3468 6345 2321 6346 2964 6346 3468 6346 1381 6347 1438 6347 3468 6347 1381 6348 3468 6348 3467 6348 1436 6349 3468 6349 1438 6349 1435 6350 3468 6350 1436 6350 1435 6351 1432 6351 3468 6351 1289 6352 2478 6352 1292 6352 1289 182 1285 182 2478 182 1285 182 1333 182 2478 182 1214 6353 2478 6353 1333 6353 1214 6354 1276 6354 2478 6354 3469 6355 2964 6355 1793 6355 2387 6356 2858 6356 2385 6356 2689 6357 3469 6357 2866 6357 1656 6358 3469 6358 1793 6358 1656 6359 1793 6359 1657 6359 1793 6360 1658 6360 1657 6360 2513 6361 3470 6361 2243 6361 3470 6362 1656 6362 2243 6362 2866 6363 3470 6363 2513 6363 1656 6364 3470 6364 3469 6364 3470 6365 2866 6365 3469 6365 1767 6366 3471 6366 1784 6366 3471 6367 1793 6367 1784 6367 1663 6368 3471 6368 1767 6368 1663 6369 1767 6369 1758 6369 1663 6370 1793 6370 3471 6370 1355 6371 2447 6371 2388 6371 2447 6372 2964 6372 3469 6372 2858 6373 2387 6373 2857 6373 2447 6374 3469 6374 2387 6374 2447 6375 3467 6375 2964 6375 1355 270 3467 270 2447 270 1355 6376 1356 6376 3467 6376 2857 6377 3472 6377 2641 6377 3469 6378 3472 6378 2387 6378 3472 6379 2857 6379 2387 6379 2689 6380 2642 6380 3472 6380 2641 6381 3472 6381 2642 6381 2689 6382 3472 6382 3469 6382 668 6383 687 6383 669 6383 3422 6384 3371 6384 3423 6384 3371 6385 3369 6385 3423 6385 1059 6386 1009 6386 1061 6386 1009 6387 1007 6387 1061 6387 503 6388 453 6388 504 6388 453 6389 451 6389 504 6389 2462 6390 2491 6390 2461 6390 2462 6391 2712 6391 2491 6391 2463 6392 2712 6392 2462 6392 2463 6393 2710 6393 2712 6393 2464 6394 2710 6394 2463 6394 2464 6395 2707 6395 2710 6395 2465 6396 2707 6396 2464 6396 2465 6397 2708 6397 2707 6397 2466 6398 2708 6398 2465 6398 2466 6399 2739 6399 2708 6399 2467 6400 2739 6400 2466 6400 2467 6401 2734 6401 2739 6401 2468 6402 2734 6402 2467 6402 2468 6403 2733 6403 2734 6403 3473 6404 2733 6404 2468 6404 3473 6405 2730 6405 2733 6405 3474 6406 2730 6406 3473 6406 3474 6407 2727 6407 2730 6407 3475 6408 2727 6408 3474 6408 2434 6409 2727 6409 3475 6409 2433 6410 2434 6410 3475 6410 2541 6411 2518 6411 2623 6411 2541 6412 2623 6412 2622 6412 2542 6413 2541 6413 2622 6413 2542 6414 2622 6414 2637 6414 2583 6415 2637 6415 2585 6415 2542 6416 2583 6416 2543 6416 2542 6417 2637 6417 2583 6417 2254 6418 2515 6418 2514 6418 2163 6419 2515 6419 2254 6419 2163 6420 2613 6420 2515 6420 2518 6421 2613 6421 2623 6421 2515 6422 2613 6422 2518 6422 2139 6423 2623 6423 2613 6423 2164 6424 2203 6424 2202 6424 2112 6425 2203 6425 2164 6425 2112 6426 2264 6426 2203 6426 2203 6427 2264 6427 2261 6427 2247 6428 2261 6428 2264 6428 2247 6429 2248 6429 2261 6429 2164 6430 2202 6430 2223 6430 2202 6431 2268 6431 2223 6431 2164 6432 2223 6432 2190 6432 473 6433 519 6433 475 6433 470 270 519 270 473 270 470 6434 471 6434 519 6434 519 6435 471 6435 553 6435 519 6436 553 6436 548 6436 519 6437 548 6437 552 6437 519 6438 552 6438 550 6438 519 6439 550 6439 549 6439 519 6440 549 6440 551 6440 519 6441 551 6441 25 6441 538 6442 542 6442 455 6442 539 6443 538 6443 455 6443 45 6444 543 6444 455 6444 539 6445 455 6445 543 6445 542 6446 555 6446 455 6446 455 6447 555 6447 518 6447 517 6448 455 6448 518 6448 456 6449 455 6449 517 6449 1012 6450 1011 6450 1073 6450 1073 6451 1011 6451 1074 6451 1011 6452 1112 6452 1074 6452 1098 6453 1112 6453 1011 6453 1095 6454 1011 6454 1100 6454 600 6455 1100 6455 1011 6455 1095 6456 1094 6456 1011 6456 1094 6457 1098 6457 1011 6457 1054 6458 1012 6458 1073 6458 1075 6459 1108 6459 580 6459 1075 6460 1107 6460 1108 6460 1075 6461 1106 6461 1107 6461 1075 6462 1109 6462 1106 6462 1075 6463 1105 6463 1109 6463 1075 6464 1110 6464 1105 6464 1075 6465 1027 6465 1110 6465 1026 6466 1027 6466 1075 6466 1026 6467 1075 6467 1029 6467 1029 270 1075 270 1031 270 3392 270 3431 270 3394 270 3390 270 3431 270 3392 270 3390 6468 3389 6468 3431 6468 3431 6469 3389 6469 3464 6469 3431 6470 3464 6470 3458 6470 3431 6471 3458 6471 3463 6471 3431 6472 3463 6472 3460 6472 3431 6473 3460 6473 3461 6473 3431 6474 3461 6474 3462 6474 3431 6475 3462 6475 2986 6475 3374 6476 3373 6476 3429 6476 3429 6477 3373 6477 3430 6477 3373 6447 3466 6447 3430 6447 3451 6478 3466 6478 3373 6478 3448 6479 3373 6479 3454 6479 3006 6480 3454 6480 3373 6480 3448 6481 3447 6481 3373 6481 3447 6482 3451 6482 3373 6482 3454 6483 3006 6483 2997 6483 3417 6484 3372 6484 3374 6484 3417 6485 3374 6485 3429 6485 3295 270 3291 270 3476 270 3291 6486 3287 6486 3476 6486 3287 603 3286 603 3476 603 3286 270 3285 270 3476 270 3285 6487 3284 6487 3476 6487 3284 6488 3290 6488 3476 6488 3476 601 3290 601 3294 601 3294 270 3299 270 3476 270 3299 6489 3303 6489 3476 6489 3303 1543 3304 1543 3476 1543 3304 6490 3300 6490 3476 6490 3300 270 3298 270 3476 270 3476 6491 3298 6491 3295 6491 2413 6492 2411 6492 2408 6492 2408 6493 2406 6493 2404 6493 2404 6494 2415 6494 2413 6494 2408 6495 2404 6495 2413 6495 2433 6496 3475 6496 3474 6496 3474 6497 3473 6497 2468 6497 2468 6498 2431 6498 2433 6498 3474 6499 2468 6499 2433 6499 3477 6500 3478 6500 3479 6500 3479 6501 3480 6501 3477 6501 3477 6502 3480 6502 3481 6502 3477 6503 3481 6503 3482 6503 3482 6504 3481 6504 3483 6504 3484 6505 3485 6505 3486 6505 3481 6506 3487 6506 3483 6506 3483 6507 3487 6507 3484 6507 3483 6508 3484 6508 3488 6508 3488 6509 3484 6509 3486 6509 3489 270 3490 270 3491 270 3491 270 3490 270 3492 270 3491 6510 3492 6510 3493 6510 3494 6511 3495 6511 3496 6511 3496 270 3495 270 3497 270 3493 6512 3498 6512 3491 6512 3491 6513 3498 6513 3499 6513 3491 6514 3499 6514 3495 6514 3494 6515 3500 6515 3495 6515 3495 6516 3500 6516 3501 6516 3495 6517 3501 6517 3491 6517 3502 64 3503 64 3504 64 3505 64 3506 64 3504 64 3507 6518 3504 6518 3508 6518 3508 6519 3504 6519 3489 6519 3508 64 3489 64 3509 64 3491 64 3480 64 3489 64 3489 6520 3480 6520 3479 6520 3504 6521 3506 6521 3502 6521 3502 6522 3506 6522 3510 6522 3502 6523 3510 6523 3511 6523 3511 6524 3512 6524 3502 6524 3502 6525 3512 6525 3513 6525 3502 6526 3513 6526 3514 6526 3507 64 3515 64 3504 64 3504 6527 3515 6527 3516 6527 3504 6528 3516 6528 3517 6528 3479 6529 3518 6529 3489 6529 3489 64 3518 64 3519 64 3489 64 3519 64 3520 64 3521 6530 3522 6530 3523 6530 3517 64 3524 64 3504 64 3504 6531 3524 6531 3525 6531 3504 6532 3525 6532 3505 6532 3520 64 3526 64 3489 64 3489 6533 3526 6533 3527 6533 3489 6534 3527 6534 3509 6534 3514 6535 3528 6535 3502 6535 3502 6536 3528 6536 3529 6536 3502 6537 3529 6537 3530 6537 3530 64 3531 64 3502 64 3502 6538 3531 6538 3521 6538 3502 6539 3521 6539 3532 6539 3532 6540 3521 6540 3523 6540 3477 581 3492 581 3478 581 3478 581 3492 581 3490 581 3478 6541 3490 6541 3533 6541 3534 581 3535 581 3490 581 3490 6542 3535 6542 3536 6542 3490 6543 3536 6543 3537 6543 3538 6544 3539 6544 3490 6544 3540 6545 3541 6545 3542 6545 3542 6546 3541 6546 3543 6546 3537 6547 3544 6547 3490 6547 3490 581 3544 581 3545 581 3490 581 3545 581 3533 581 3538 581 3490 581 3546 581 3539 581 3547 581 3490 581 3490 6548 3547 6548 3548 6548 3490 6549 3548 6549 3534 6549 3543 6550 3549 6550 3542 6550 3542 6551 3549 6551 3550 6551 3542 6552 3550 6552 3551 6552 3551 581 3550 581 3552 581 3552 6553 3550 6553 3553 6553 3552 581 3553 581 3490 581 3490 6554 3553 6554 3554 6554 3490 6555 3554 6555 3546 6555 3555 6556 3556 6556 3542 6556 3542 6557 3556 6557 3557 6557 3542 6558 3557 6558 3540 6558 3542 581 3558 581 3555 581 3555 6559 3558 6559 3559 6559 3555 6560 3559 6560 3560 6560 3560 581 3561 581 3555 581 3555 581 3561 581 3562 581 3555 6561 3562 6561 3563 6561 3564 6562 3565 6562 3485 6562 3485 6563 3565 6563 3566 6563 3485 6564 3566 6564 3486 6564 3490 6565 3489 6565 3552 6565 3552 6566 3489 6566 3504 6566 3552 495 3504 495 3551 495 3551 495 3504 495 3503 495 3551 6567 3503 6567 3542 6567 3542 6568 3503 6568 3502 6568 3542 6569 3502 6569 3558 6569 3558 6569 3502 6569 3532 6569 3558 6570 3532 6570 3559 6570 3559 6570 3532 6570 3523 6570 3559 6571 3523 6571 3560 6571 3560 6571 3523 6571 3522 6571 3560 6572 3522 6572 3561 6572 3561 6573 3522 6573 3521 6573 3561 6574 3521 6574 3562 6574 3562 6575 3521 6575 3531 6575 3562 6576 3531 6576 3563 6576 3563 6577 3531 6577 3530 6577 3563 6578 3530 6578 3555 6578 3555 6578 3530 6578 3529 6578 3555 6579 3529 6579 3556 6579 3556 6580 3529 6580 3528 6580 3556 6581 3528 6581 3557 6581 3557 6582 3528 6582 3514 6582 3557 6583 3514 6583 3540 6583 3540 6583 3514 6583 3513 6583 3540 6584 3513 6584 3541 6584 3541 6584 3513 6584 3512 6584 3541 6585 3512 6585 3543 6585 3543 6586 3512 6586 3511 6586 3543 6587 3511 6587 3549 6587 3549 6588 3511 6588 3510 6588 3549 6589 3510 6589 3550 6589 3550 6590 3510 6590 3506 6590 3550 6591 3506 6591 3553 6591 3553 6591 3506 6591 3505 6591 3553 6592 3505 6592 3554 6592 3554 6593 3505 6593 3525 6593 3554 6594 3525 6594 3546 6594 3546 6594 3525 6594 3524 6594 3546 6595 3524 6595 3538 6595 3538 6595 3524 6595 3517 6595 3538 6596 3517 6596 3539 6596 3539 6596 3517 6596 3516 6596 3539 6597 3516 6597 3547 6597 3547 6598 3516 6598 3515 6598 3547 6599 3515 6599 3548 6599 3548 6599 3515 6599 3507 6599 3548 6600 3507 6600 3534 6600 3534 6600 3507 6600 3508 6600 3534 6601 3508 6601 3535 6601 3535 6601 3508 6601 3509 6601 3535 6602 3509 6602 3536 6602 3536 6603 3509 6603 3527 6603 3536 6604 3527 6604 3537 6604 3537 6605 3527 6605 3526 6605 3537 6606 3526 6606 3544 6606 3544 6607 3526 6607 3520 6607 3544 6608 3520 6608 3545 6608 3545 6608 3520 6608 3519 6608 3545 6609 3519 6609 3533 6609 3533 6610 3519 6610 3518 6610 3518 6611 3479 6611 3533 6611 3533 6612 3479 6612 3478 6612 3498 6613 3493 6613 3483 6613 3483 6614 3493 6614 3482 6614 3499 6615 3498 6615 3488 6615 3488 6616 3498 6616 3483 6616 3500 6617 3494 6617 3487 6617 3487 6618 3494 6618 3484 6618 3501 6619 3500 6619 3481 6619 3481 6620 3500 6620 3487 6620 3491 6621 3501 6621 3480 6621 3480 6622 3501 6622 3481 6622 3493 6623 3492 6623 3482 6623 3482 6624 3492 6624 3477 6624 3566 6625 3495 6625 3486 6625 3486 6626 3495 6626 3499 6626 3486 6627 3499 6627 3488 6627 3496 6628 3564 6628 3494 6628 3494 6629 3564 6629 3485 6629 3494 6630 3485 6630 3484 6630 3495 6631 3566 6631 3567 6631 3567 6632 3566 6632 3568 6632 3569 6633 3570 6633 3496 6633 3496 6634 3570 6634 3564 6634 3571 6635 3572 6635 3573 6635 3571 6636 3573 6636 3574 6636 3575 6637 3576 6637 3577 6637 3575 6638 3577 6638 3578 6638 3579 6639 3580 6639 3581 6639 3579 6640 3581 6640 3582 6640 3583 6641 3584 6641 3585 6641 3583 6642 3585 6642 3586 6642 3587 6643 3588 6643 3577 6643 3587 6644 3577 6644 3576 6644 3584 6645 3589 6645 3590 6645 3584 6646 3590 6646 3585 6646 3589 6647 3591 6647 3592 6647 3589 6648 3592 6648 3590 6648 3593 6649 3594 6649 3595 6649 3593 6650 3595 6650 3596 6650 3594 6651 3597 6651 3598 6651 3594 6652 3598 6652 3595 6652 3597 6653 3599 6653 3600 6653 3597 6654 3600 6654 3598 6654 3599 6655 3601 6655 3602 6655 3599 6656 3602 6656 3600 6656 3601 6657 3603 6657 3604 6657 3601 6658 3604 6658 3602 6658 3605 6659 3606 6659 3607 6659 3605 6660 3607 6660 3608 6660 3609 6661 3610 6661 3611 6661 3609 6662 3611 6662 3612 6662 3613 6663 3579 6663 3582 6663 3613 6664 3582 6664 3614 6664 3615 6665 3616 6665 3574 6665 3615 6666 3574 6666 3573 6666 3616 6667 3617 6667 3618 6667 3616 6668 3618 6668 3574 6668 3617 6669 3619 6669 3620 6669 3617 6670 3620 6670 3618 6670 3619 6671 3621 6671 3622 6671 3619 6672 3622 6672 3620 6672 3621 6673 3623 6673 3624 6673 3621 6674 3624 6674 3622 6674 3623 6675 3625 6675 3626 6675 3623 6676 3626 6676 3624 6676 3625 6677 3627 6677 3628 6677 3625 6678 3628 6678 3626 6678 3627 6679 3629 6679 3630 6679 3627 6680 3630 6680 3628 6680 3629 6681 3631 6681 3632 6681 3629 6682 3632 6682 3630 6682 3633 6683 3634 6683 3635 6683 3633 6684 3635 6684 3636 6684 3634 6685 3637 6685 3638 6685 3634 6686 3638 6686 3635 6686 3637 6687 3639 6687 3640 6687 3637 6688 3640 6688 3638 6688 3641 6689 3642 6689 3643 6689 3641 6690 3643 6690 3644 6690 3642 6691 3645 6691 3646 6691 3642 6692 3646 6692 3643 6692 3645 6693 3647 6693 3648 6693 3645 6694 3648 6694 3646 6694 3647 6695 3649 6695 3650 6695 3647 6696 3650 6696 3648 6696 3649 6697 3651 6697 3652 6697 3649 6698 3652 6698 3650 6698 3651 6699 3653 6699 3654 6699 3651 6700 3654 6700 3652 6700 3653 6701 3575 6701 3578 6701 3653 6702 3578 6702 3654 6702 3588 6703 3655 6703 3578 6703 3588 6704 3578 6704 3577 6704 3655 6705 3656 6705 3654 6705 3655 6706 3654 6706 3578 6706 3656 6707 3657 6707 3652 6707 3656 6708 3652 6708 3654 6708 3657 6709 3658 6709 3650 6709 3657 6710 3650 6710 3652 6710 3658 6711 3659 6711 3648 6711 3658 6712 3648 6712 3650 6712 3659 6713 3660 6713 3646 6713 3659 6714 3646 6714 3648 6714 3660 6715 3661 6715 3643 6715 3660 6716 3643 6716 3646 6716 3662 6717 3663 6717 3640 6717 3662 6718 3640 6718 3664 6718 3663 6719 3665 6719 3638 6719 3663 6720 3638 6720 3640 6720 3665 6721 3666 6721 3635 6721 3665 6722 3635 6722 3638 6722 3667 6723 3668 6723 3632 6723 3667 6724 3632 6724 3669 6724 3668 6725 3670 6725 3630 6725 3668 6726 3630 6726 3632 6726 3670 6727 3671 6727 3628 6727 3670 6728 3628 6728 3630 6728 3671 6729 3672 6729 3626 6729 3671 6730 3626 6730 3628 6730 3672 6731 3673 6731 3624 6731 3672 6732 3624 6732 3626 6732 3673 6733 3674 6733 3622 6733 3673 6734 3622 6734 3624 6734 3674 6735 3675 6735 3620 6735 3674 6736 3620 6736 3622 6736 3675 6737 3676 6737 3618 6737 3675 6738 3618 6738 3620 6738 3676 6739 3571 6739 3574 6739 3676 6740 3574 6740 3618 6740 3677 6741 3678 6741 3679 6741 3677 6742 3679 6742 3680 6742 3681 6743 3682 6743 3683 6743 3681 6744 3683 6744 3684 6744 3685 6745 3686 6745 3687 6745 3685 6746 3687 6746 3688 6746 3688 6747 3687 6747 3689 6747 3688 6748 3689 6748 3690 6748 3613 6749 3691 6749 3692 6749 3613 6750 3692 6750 3579 6750 3691 6751 3693 6751 3694 6751 3691 6752 3694 6752 3692 6752 3693 6753 3695 6753 3696 6753 3693 6754 3696 6754 3694 6754 3695 6755 3697 6755 3698 6755 3695 6756 3698 6756 3696 6756 3697 6757 3699 6757 3700 6757 3697 6758 3700 6758 3698 6758 3699 6759 3701 6759 3702 6759 3699 6760 3702 6760 3700 6760 3701 6761 3703 6761 3704 6761 3701 6762 3704 6762 3702 6762 3703 6763 3705 6763 3706 6763 3703 6764 3706 6764 3704 6764 3707 6765 3708 6765 3691 6765 3707 6766 3691 6766 3613 6766 3708 6767 3709 6767 3693 6767 3708 6768 3693 6768 3691 6768 3709 6769 3710 6769 3695 6769 3709 6770 3695 6770 3693 6770 3710 6771 3711 6771 3697 6771 3710 6772 3697 6772 3695 6772 3711 6773 3712 6773 3699 6773 3711 6774 3699 6774 3697 6774 3712 6775 3713 6775 3701 6775 3712 6776 3701 6776 3699 6776 3713 6777 3714 6777 3703 6777 3713 6778 3703 6778 3701 6778 3714 6779 3715 6779 3705 6779 3714 6780 3705 6780 3703 6780 3716 6781 3717 6781 3718 6781 3716 6782 3718 6782 3719 6782 3717 6783 3720 6783 3721 6783 3717 6784 3721 6784 3718 6784 3610 6785 3722 6785 3717 6785 3610 6786 3717 6786 3716 6786 3722 6787 3723 6787 3720 6787 3722 6788 3720 6788 3717 6788 3609 6789 3724 6789 3722 6789 3609 6790 3722 6790 3610 6790 3724 6791 3725 6791 3723 6791 3724 6792 3723 6792 3722 6792 3726 6793 3727 6793 3724 6793 3726 6794 3724 6794 3609 6794 3605 6795 3728 6795 3729 6795 3605 6796 3729 6796 3606 6796 3601 6797 3730 6797 3731 6797 3601 6798 3731 6798 3603 6798 3599 6799 3732 6799 3730 6799 3599 6800 3730 6800 3601 6800 3597 6801 3733 6801 3732 6801 3597 6802 3732 6802 3599 6802 3589 6803 3734 6803 3735 6803 3589 6804 3735 6804 3591 6804 3734 6805 3736 6805 3737 6805 3734 6806 3737 6806 3735 6806 3736 6807 3738 6807 3739 6807 3736 6808 3739 6808 3737 6808 3738 6809 3740 6809 3741 6809 3738 6810 3741 6810 3739 6810 3740 6811 3742 6811 3743 6811 3740 6812 3743 6812 3741 6812 3742 6813 3744 6813 3745 6813 3742 6814 3745 6814 3743 6814 3584 6815 3746 6815 3734 6815 3584 6816 3734 6816 3589 6816 3746 6817 3747 6817 3736 6817 3746 6818 3736 6818 3734 6818 3747 6819 3748 6819 3738 6819 3747 6820 3738 6820 3736 6820 3748 6821 3749 6821 3740 6821 3748 6822 3740 6822 3738 6822 3749 6823 3750 6823 3742 6823 3749 6824 3742 6824 3740 6824 3750 6825 3751 6825 3744 6825 3750 6826 3744 6826 3742 6826 3751 6827 3752 6827 3753 6827 3751 6828 3753 6828 3744 6828 3752 6829 3754 6829 3755 6829 3752 6830 3755 6830 3753 6830 3754 6831 3756 6831 3757 6831 3754 6832 3757 6832 3755 6832 3758 6833 3759 6833 3757 6833 3757 6834 3756 6834 3760 6834 3760 6835 3761 6835 3758 6835 3757 6836 3760 6836 3758 6836 3676 6837 3762 6837 3763 6837 3676 6838 3763 6838 3571 6838 3762 6839 3764 6839 3765 6839 3762 6840 3765 6840 3763 6840 3764 6841 3766 6841 3767 6841 3764 6842 3767 6842 3765 6842 3766 6843 3768 6843 3769 6843 3766 6844 3769 6844 3767 6844 3768 6845 3770 6845 3771 6845 3768 6846 3771 6846 3769 6846 3770 6847 3772 6847 3773 6847 3770 6848 3773 6848 3771 6848 3772 6849 3774 6849 3775 6849 3772 6850 3775 6850 3773 6850 3774 6851 3776 6851 3777 6851 3774 6852 3777 6852 3775 6852 3776 6853 3778 6853 3779 6853 3776 6854 3779 6854 3777 6854 3778 6855 3780 6855 3781 6855 3778 6856 3781 6856 3779 6856 3780 6857 3782 6857 3783 6857 3780 6858 3783 6858 3781 6858 3782 6859 3784 6859 3785 6859 3782 6860 3785 6860 3783 6860 3784 6861 3786 6861 3787 6861 3784 6862 3787 6862 3785 6862 3786 6863 3788 6863 3789 6863 3786 6864 3789 6864 3787 6864 3675 6865 3790 6865 3762 6865 3675 6866 3762 6866 3676 6866 3790 6867 3791 6867 3764 6867 3790 6868 3764 6868 3762 6868 3791 6869 3792 6869 3766 6869 3791 6870 3766 6870 3764 6870 3792 6871 3793 6871 3768 6871 3792 6872 3768 6872 3766 6872 3793 6873 3794 6873 3770 6873 3793 6874 3770 6874 3768 6874 3794 6875 3795 6875 3772 6875 3794 6876 3772 6876 3770 6876 3795 6877 3796 6877 3774 6877 3795 6878 3774 6878 3772 6878 3796 6879 3797 6879 3776 6879 3796 6880 3776 6880 3774 6880 3797 6881 3798 6881 3778 6881 3797 6882 3778 6882 3776 6882 3798 6883 3799 6883 3780 6883 3798 6884 3780 6884 3778 6884 3799 6885 3800 6885 3782 6885 3799 6886 3782 6886 3780 6886 3800 6887 3801 6887 3784 6887 3800 6888 3784 6888 3782 6888 3801 6889 3802 6889 3786 6889 3801 6890 3786 6890 3784 6890 3802 6891 3803 6891 3788 6891 3802 6892 3788 6892 3786 6892 3674 6893 3804 6893 3790 6893 3674 6894 3790 6894 3675 6894 3804 6895 3805 6895 3791 6895 3804 6896 3791 6896 3790 6896 3805 6897 3806 6897 3792 6897 3805 6898 3792 6898 3791 6898 3806 6899 3807 6899 3793 6899 3806 6900 3793 6900 3792 6900 3807 6901 3808 6901 3794 6901 3807 6902 3794 6902 3793 6902 3808 6903 3809 6903 3795 6903 3808 6904 3795 6904 3794 6904 3809 6905 3810 6905 3796 6905 3809 6906 3796 6906 3795 6906 3810 6907 3811 6907 3797 6907 3810 6908 3797 6908 3796 6908 3811 6909 3812 6909 3798 6909 3811 6910 3798 6910 3797 6910 3812 6911 3813 6911 3799 6911 3812 6912 3799 6912 3798 6912 3813 6913 3814 6913 3800 6913 3813 6914 3800 6914 3799 6914 3814 6915 3815 6915 3801 6915 3814 6916 3801 6916 3800 6916 3815 6917 3816 6917 3802 6917 3815 6918 3802 6918 3801 6918 3816 6919 3817 6919 3803 6919 3816 6920 3803 6920 3802 6920 3817 6921 3818 6921 3819 6921 3817 6922 3819 6922 3803 6922 3673 6923 3820 6923 3804 6923 3673 6924 3804 6924 3674 6924 3820 6925 3821 6925 3805 6925 3820 6926 3805 6926 3804 6926 3821 6927 3822 6927 3806 6927 3821 6928 3806 6928 3805 6928 3822 6929 3823 6929 3807 6929 3822 6930 3807 6930 3806 6930 3823 6931 3824 6931 3808 6931 3823 6932 3808 6932 3807 6932 3824 6933 3825 6933 3809 6933 3824 6934 3809 6934 3808 6934 3825 6935 3826 6935 3810 6935 3825 6936 3810 6936 3809 6936 3826 6937 3827 6937 3811 6937 3826 6938 3811 6938 3810 6938 3827 6939 3828 6939 3812 6939 3827 6940 3812 6940 3811 6940 3828 6941 3829 6941 3813 6941 3828 6942 3813 6942 3812 6942 3829 6943 3830 6943 3814 6943 3829 6944 3814 6944 3813 6944 3830 6945 3831 6945 3815 6945 3830 6946 3815 6946 3814 6946 3831 6947 3832 6947 3816 6947 3831 6948 3816 6948 3815 6948 3832 6949 3833 6949 3817 6949 3832 6950 3817 6950 3816 6950 3833 6951 3834 6951 3818 6951 3833 6952 3818 6952 3817 6952 3672 6953 3835 6953 3820 6953 3672 6954 3820 6954 3673 6954 3835 6955 3836 6955 3821 6955 3835 6956 3821 6956 3820 6956 3836 6957 3837 6957 3822 6957 3836 6958 3822 6958 3821 6958 3837 6959 3838 6959 3823 6959 3837 6960 3823 6960 3822 6960 3838 6961 3839 6961 3824 6961 3838 6962 3824 6962 3823 6962 3839 6963 3840 6963 3825 6963 3839 6964 3825 6964 3824 6964 3840 6965 3841 6965 3826 6965 3840 6966 3826 6966 3825 6966 3841 6967 3842 6967 3827 6967 3841 6968 3827 6968 3826 6968 3842 6969 3843 6969 3828 6969 3842 6970 3828 6970 3827 6970 3843 6971 3844 6971 3829 6971 3843 6972 3829 6972 3828 6972 3844 6973 3845 6973 3830 6973 3844 6974 3830 6974 3829 6974 3845 6975 3846 6975 3831 6975 3845 6976 3831 6976 3830 6976 3846 6977 3847 6977 3832 6977 3846 6978 3832 6978 3831 6978 3847 6979 3848 6979 3833 6979 3847 6980 3833 6980 3832 6980 3848 6981 3849 6981 3834 6981 3848 6982 3834 6982 3833 6982 3671 6983 3850 6983 3835 6983 3671 6984 3835 6984 3672 6984 3850 6985 3851 6985 3836 6985 3850 6986 3836 6986 3835 6986 3851 6987 3852 6987 3837 6987 3851 6988 3837 6988 3836 6988 3852 6989 3853 6989 3838 6989 3852 6990 3838 6990 3837 6990 3853 6991 3854 6991 3839 6991 3853 6992 3839 6992 3838 6992 3854 6993 3855 6993 3840 6993 3854 6994 3840 6994 3839 6994 3855 6995 3856 6995 3841 6995 3855 6996 3841 6996 3840 6996 3856 6997 3857 6997 3842 6997 3856 6998 3842 6998 3841 6998 3857 6999 3858 6999 3843 6999 3857 7000 3843 7000 3842 7000 3858 7001 3859 7001 3844 7001 3858 7002 3844 7002 3843 7002 3859 7003 3860 7003 3845 7003 3859 7004 3845 7004 3844 7004 3860 7005 3861 7005 3846 7005 3860 7006 3846 7006 3845 7006 3861 7007 3862 7007 3847 7007 3861 7008 3847 7008 3846 7008 3862 7009 3863 7009 3848 7009 3862 7010 3848 7010 3847 7010 3670 7011 3864 7011 3850 7011 3670 7012 3850 7012 3671 7012 3864 7013 3865 7013 3851 7013 3864 7014 3851 7014 3850 7014 3865 7015 3866 7015 3852 7015 3865 7016 3852 7016 3851 7016 3866 7017 3867 7017 3853 7017 3866 7018 3853 7018 3852 7018 3867 7019 3868 7019 3854 7019 3867 7020 3854 7020 3853 7020 3868 7021 3869 7021 3855 7021 3868 7022 3855 7022 3854 7022 3869 7023 3870 7023 3856 7023 3869 7024 3856 7024 3855 7024 3870 7025 3871 7025 3857 7025 3870 7026 3857 7026 3856 7026 3871 7027 3872 7027 3858 7027 3871 7028 3858 7028 3857 7028 3872 7029 3873 7029 3859 7029 3872 7030 3859 7030 3858 7030 3873 7031 3874 7031 3860 7031 3873 7032 3860 7032 3859 7032 3874 7033 3875 7033 3861 7033 3874 7034 3861 7034 3860 7034 3875 7035 3876 7035 3862 7035 3875 7036 3862 7036 3861 7036 3876 7037 3877 7037 3863 7037 3876 7038 3863 7038 3862 7038 3668 7039 3878 7039 3864 7039 3668 7040 3864 7040 3670 7040 3878 7041 3879 7041 3865 7041 3878 7042 3865 7042 3864 7042 3879 7043 3880 7043 3866 7043 3879 7044 3866 7044 3865 7044 3880 7045 3881 7045 3867 7045 3880 7046 3867 7046 3866 7046 3881 7047 3882 7047 3868 7047 3881 7048 3868 7048 3867 7048 3882 7049 3883 7049 3869 7049 3882 7050 3869 7050 3868 7050 3883 7051 3884 7051 3870 7051 3883 7052 3870 7052 3869 7052 3884 7053 3885 7053 3871 7053 3884 7054 3871 7054 3870 7054 3885 7055 3886 7055 3872 7055 3885 7056 3872 7056 3871 7056 3886 7057 3887 7057 3873 7057 3886 7058 3873 7058 3872 7058 3887 7059 3888 7059 3874 7059 3887 7060 3874 7060 3873 7060 3888 7061 3889 7061 3875 7061 3888 7062 3875 7062 3874 7062 3889 7063 3890 7063 3876 7063 3889 7064 3876 7064 3875 7064 3890 7065 3891 7065 3877 7065 3890 7066 3877 7066 3876 7066 3891 7067 3892 7067 3893 7067 3891 7068 3893 7068 3877 7068 3892 7069 3894 7069 3895 7069 3892 7070 3895 7070 3893 7070 3894 7071 3896 7071 3897 7071 3894 7072 3897 7072 3898 7072 3896 7073 3899 7073 3900 7073 3896 7074 3900 7074 3897 7074 3899 7075 3901 7075 3902 7075 3899 7076 3902 7076 3900 7076 3901 7077 3688 7077 3690 7077 3901 7078 3690 7078 3902 7078 3667 7079 3903 7079 3878 7079 3667 7080 3878 7080 3668 7080 3903 7081 3904 7081 3879 7081 3903 7082 3879 7082 3878 7082 3904 7083 3905 7083 3880 7083 3904 7084 3880 7084 3879 7084 3905 7085 3906 7085 3881 7085 3905 7086 3881 7086 3880 7086 3906 7087 3907 7087 3882 7087 3906 7088 3882 7088 3881 7088 3907 7089 3908 7089 3883 7089 3907 7090 3883 7090 3882 7090 3908 7091 3909 7091 3884 7091 3908 7092 3884 7092 3883 7092 3909 7093 3910 7093 3885 7093 3909 7094 3885 7094 3884 7094 3910 7095 3911 7095 3886 7095 3910 7096 3886 7096 3885 7096 3911 7097 3912 7097 3887 7097 3911 7098 3887 7098 3886 7098 3912 7099 3913 7099 3888 7099 3912 7100 3888 7100 3887 7100 3913 7101 3914 7101 3889 7101 3913 7102 3889 7102 3888 7102 3914 7103 3915 7103 3890 7103 3914 7104 3890 7104 3889 7104 3915 7105 3916 7105 3891 7105 3915 7106 3891 7106 3890 7106 3916 7107 3917 7107 3892 7107 3916 7108 3892 7108 3891 7108 3917 7109 3918 7109 3894 7109 3917 7110 3894 7110 3892 7110 3918 7111 3919 7111 3896 7111 3918 7112 3896 7112 3894 7112 3919 7113 3920 7113 3899 7113 3919 7114 3899 7114 3896 7114 3920 7115 3921 7115 3901 7115 3920 7116 3901 7116 3899 7116 3921 7117 3685 7117 3688 7117 3921 7118 3688 7118 3901 7118 3922 7119 3923 7119 3924 7119 3922 7120 3924 7120 3925 7120 3926 7121 3927 7121 3928 7121 3926 7122 3928 7122 3929 7122 3927 7123 3930 7123 3931 7123 3927 7124 3931 7124 3928 7124 3930 7125 3932 7125 3933 7125 3930 7126 3933 7126 3931 7126 3932 7127 3934 7127 3935 7127 3932 7128 3935 7128 3933 7128 3934 7129 3936 7129 3937 7129 3934 7130 3937 7130 3935 7130 3936 7131 3938 7131 3939 7131 3936 7132 3939 7132 3937 7132 3938 7133 3940 7133 3941 7133 3938 7134 3941 7134 3939 7134 3940 7135 3942 7135 3943 7135 3940 7136 3943 7136 3941 7136 3942 7137 3944 7137 3945 7137 3942 7138 3945 7138 3943 7138 3944 7139 3946 7139 3947 7139 3944 7140 3947 7140 3945 7140 3946 7141 3948 7141 3949 7141 3946 7142 3949 7142 3947 7142 3948 7143 3681 7143 3684 7143 3948 7144 3684 7144 3949 7144 3665 7145 3950 7145 3951 7145 3665 7146 3951 7146 3666 7146 3950 7147 3952 7147 3953 7147 3950 7148 3953 7148 3951 7148 3952 7149 3954 7149 3955 7149 3952 7150 3955 7150 3953 7150 3954 7151 3956 7151 3957 7151 3954 7152 3957 7152 3955 7152 3956 7153 3958 7153 3959 7153 3956 7154 3959 7154 3957 7154 3958 7155 3960 7155 3961 7155 3958 7156 3961 7156 3959 7156 3960 7157 3962 7157 3963 7157 3960 7158 3963 7158 3961 7158 3962 7159 3964 7159 3965 7159 3962 7160 3965 7160 3963 7160 3964 7161 3966 7161 3967 7161 3964 7162 3967 7162 3965 7162 3966 7163 3968 7163 3969 7163 3966 7164 3969 7164 3967 7164 3968 7165 3970 7165 3971 7165 3968 7166 3971 7166 3969 7166 3970 7167 3972 7167 3973 7167 3970 7168 3973 7168 3971 7168 3972 7169 3974 7169 3975 7169 3972 7170 3975 7170 3973 7170 3974 7171 3976 7171 3977 7171 3974 7172 3977 7172 3975 7172 3976 7173 3978 7173 3979 7173 3976 7174 3979 7174 3977 7174 3978 7175 3980 7175 3981 7175 3978 7176 3981 7176 3979 7176 3980 7177 3982 7177 3983 7177 3980 7178 3983 7178 3981 7178 3982 7179 3984 7179 3985 7179 3982 7180 3985 7180 3983 7180 3984 7181 3986 7181 3987 7181 3984 7182 3987 7182 3985 7182 3986 7183 3677 7183 3680 7183 3986 7184 3680 7184 3987 7184 3663 7185 3988 7185 3950 7185 3663 7186 3950 7186 3665 7186 3988 7187 3989 7187 3952 7187 3988 7188 3952 7188 3950 7188 3989 7189 3990 7189 3954 7189 3989 7190 3954 7190 3952 7190 3990 7191 3991 7191 3956 7191 3990 7192 3956 7192 3954 7192 3991 7193 3992 7193 3958 7193 3991 7194 3958 7194 3956 7194 3992 7195 3993 7195 3960 7195 3992 7196 3960 7196 3958 7196 3993 7197 3994 7197 3962 7197 3993 7198 3962 7198 3960 7198 3994 7199 3995 7199 3964 7199 3994 7200 3964 7200 3962 7200 3995 7201 3996 7201 3966 7201 3995 7202 3966 7202 3964 7202 3996 7203 3997 7203 3968 7203 3996 7204 3968 7204 3966 7204 3997 7205 3998 7205 3970 7205 3997 7206 3970 7206 3968 7206 3998 7207 3999 7207 3972 7207 3998 7208 3972 7208 3970 7208 3999 7209 4000 7209 3974 7209 3999 7210 3974 7210 3972 7210 4000 7211 4001 7211 3976 7211 4000 7212 3976 7212 3974 7212 4001 7213 4002 7213 3978 7213 4001 7214 3978 7214 3976 7214 4002 7215 4003 7215 3980 7215 4002 7216 3980 7216 3978 7216 4003 7217 4004 7217 3982 7217 4003 7218 3982 7218 3980 7218 4004 7219 4005 7219 3984 7219 4004 7220 3984 7220 3982 7220 4005 7221 4006 7221 3986 7221 4005 7222 3986 7222 3984 7222 4006 7223 4007 7223 3677 7223 4006 7224 3677 7224 3986 7224 3662 7225 4008 7225 3988 7225 3662 7226 3988 7226 3663 7226 4008 7227 4009 7227 3989 7227 4008 7228 3989 7228 3988 7228 4009 7229 4010 7229 3990 7229 4009 7230 3990 7230 3989 7230 4010 7231 4011 7231 3991 7231 4010 7232 3991 7232 3990 7232 4011 7233 4012 7233 3992 7233 4011 7234 3992 7234 3991 7234 4012 7235 4013 7235 3993 7235 4012 7236 3993 7236 3992 7236 4013 7237 4014 7237 3994 7237 4013 7238 3994 7238 3993 7238 4014 7239 4015 7239 3995 7239 4014 7240 3995 7240 3994 7240 4015 7241 4016 7241 3996 7241 4015 7242 3996 7242 3995 7242 4016 7243 4017 7243 3997 7243 4016 7244 3997 7244 3996 7244 4017 7245 4018 7245 3998 7245 4017 7246 3998 7246 3997 7246 4018 7247 4019 7247 3999 7247 4018 7248 3999 7248 3998 7248 4019 7249 4020 7249 4000 7249 4019 7250 4000 7250 3999 7250 4020 7251 4021 7251 4001 7251 4020 7252 4001 7252 4000 7252 4001 7253 4021 7253 4022 7253 4022 7254 4023 7254 4002 7254 4022 7255 4002 7255 4001 7255 4024 7256 4025 7256 4005 7256 4024 7257 4005 7257 4004 7257 4025 7258 4026 7258 4005 7258 4026 7259 4006 7259 4005 7259 3660 7260 4027 7260 4028 7260 3660 7261 4028 7261 3661 7261 4027 7262 4029 7262 4030 7262 4027 7263 4030 7263 4028 7263 4029 7264 4031 7264 4032 7264 4029 7265 4032 7265 4030 7265 4031 7266 4033 7266 4034 7266 4031 7267 4034 7267 4032 7267 4033 7268 4035 7268 4036 7268 4033 7269 4036 7269 4034 7269 4035 7270 4037 7270 4038 7270 4035 7271 4038 7271 4036 7271 4037 7272 4039 7272 4040 7272 4037 7273 4040 7273 4038 7273 4039 7274 4041 7274 4042 7274 4039 7275 4042 7275 4040 7275 4041 7276 4043 7276 4044 7276 4041 7277 4044 7277 4042 7277 4043 7278 4045 7278 4046 7278 4043 7279 4046 7279 4044 7279 4045 7280 4047 7280 4048 7280 4045 7281 4048 7281 4046 7281 4047 7282 4049 7282 4050 7282 4047 7283 4050 7283 4048 7283 3659 7284 4051 7284 4027 7284 3659 7285 4027 7285 3660 7285 4051 7286 4052 7286 4029 7286 4051 7287 4029 7287 4027 7287 4052 7288 4053 7288 4031 7288 4052 7289 4031 7289 4029 7289 4053 7290 4054 7290 4033 7290 4053 7291 4033 7291 4031 7291 4054 7292 4055 7292 4035 7292 4054 7293 4035 7293 4033 7293 4055 7294 4056 7294 4037 7294 4055 7295 4037 7295 4035 7295 4056 7296 4057 7296 4039 7296 4056 7297 4039 7297 4037 7297 4057 7298 4058 7298 4041 7298 4057 7299 4041 7299 4039 7299 4058 7300 4059 7300 4043 7300 4058 7301 4043 7301 4041 7301 4059 7302 4060 7302 4045 7302 4059 7303 4045 7303 4043 7303 3658 7304 4061 7304 4051 7304 3658 7305 4051 7305 3659 7305 4061 7306 4062 7306 4052 7306 4061 7307 4052 7307 4051 7307 4062 7308 4063 7308 4053 7308 4062 7309 4053 7309 4052 7309 4063 7310 4064 7310 4054 7310 4063 7311 4054 7311 4053 7311 4064 7312 4065 7312 4055 7312 4064 7313 4055 7313 4054 7313 4065 7314 4066 7314 4056 7314 4065 7315 4056 7315 4055 7315 4066 7316 4067 7316 4057 7316 4066 7317 4057 7317 4056 7317 4067 7318 4068 7318 4058 7318 4067 7319 4058 7319 4057 7319 3657 7320 4069 7320 4061 7320 3657 7321 4061 7321 3658 7321 4069 7322 4070 7322 4062 7322 4069 7323 4062 7323 4061 7323 4070 7324 4071 7324 4063 7324 4070 7325 4063 7325 4062 7325 4071 7326 4072 7326 4064 7326 4071 7327 4064 7327 4063 7327 4072 7328 4073 7328 4065 7328 4072 7329 4065 7329 4064 7329 4073 7330 4074 7330 4066 7330 4073 7331 4066 7331 4065 7331 4074 7332 4075 7332 4067 7332 4074 7333 4067 7333 4066 7333 3656 7334 4076 7334 4069 7334 3656 7335 4069 7335 3657 7335 4076 7336 4077 7336 4070 7336 4076 7337 4070 7337 4069 7337 4077 7338 4078 7338 4071 7338 4077 7339 4071 7339 4070 7339 4078 7340 4079 7340 4072 7340 4078 7341 4072 7341 4071 7341 4079 7342 4080 7342 4073 7342 4079 7343 4073 7343 4072 7343 4080 7344 4081 7344 4074 7344 4080 7345 4074 7345 4073 7345 3655 7346 4082 7346 4076 7346 3655 7347 4076 7347 3656 7347 4082 7348 4083 7348 4077 7348 4082 7349 4077 7349 4076 7349 4083 7350 4084 7350 4078 7350 4083 7351 4078 7351 4077 7351 4084 7352 4085 7352 4079 7352 4084 7353 4079 7353 4078 7353 4085 7354 4086 7354 4080 7354 4085 7355 4080 7355 4079 7355 3588 7356 4087 7356 4082 7356 3588 7357 4082 7357 3655 7357 4087 7358 4088 7358 4083 7358 4087 7359 4083 7359 4082 7359 4088 7360 4089 7360 4084 7360 4088 7361 4084 7361 4083 7361 4089 7362 4090 7362 4085 7362 4089 7363 4085 7363 4084 7363 4090 7364 4091 7364 4086 7364 4090 7365 4086 7365 4085 7365 3571 7366 3763 7366 4092 7366 3571 7367 4092 7367 3572 7367 3763 7368 3765 7368 4093 7368 3763 7369 4093 7369 4092 7369 3765 7370 3767 7370 4094 7370 3765 7371 4094 7371 4093 7371 3767 7372 3769 7372 4095 7372 3767 7373 4095 7373 4094 7373 3769 7374 3771 7374 4096 7374 3769 7375 4096 7375 4095 7375 3771 7376 3773 7376 4097 7376 3771 7377 4097 7377 4096 7377 3773 7378 3775 7378 4098 7378 3773 7379 4098 7379 4097 7379 3775 7380 3777 7380 4099 7380 3775 7381 4099 7381 4098 7381 3777 7382 3779 7382 4100 7382 3777 7383 4100 7383 4099 7383 3779 7384 3781 7384 4101 7384 3779 7385 4101 7385 4100 7385 3781 7386 3783 7386 4102 7386 3781 7387 4102 7387 4101 7387 3783 7388 3785 7388 4103 7388 3783 7389 4103 7389 4102 7389 3785 7390 3787 7390 4104 7390 3785 7391 4104 7391 4103 7391 3587 7392 4105 7392 4087 7392 3587 7393 4087 7393 3588 7393 4105 7394 4106 7394 4088 7394 4105 7395 4088 7395 4087 7395 4106 7396 4107 7396 4089 7396 4106 7397 4089 7397 4088 7397 4107 7398 4108 7398 4090 7398 4107 7399 4090 7399 4089 7399 4108 7400 4109 7400 4091 7400 4108 7401 4091 7401 4090 7401 4109 7402 4110 7402 4111 7402 4109 7403 4111 7403 4091 7403 4110 7404 4112 7404 4113 7404 4110 7405 4113 7405 4111 7405 4112 7406 4114 7406 4115 7406 4112 7407 4115 7407 4113 7407 3579 7408 3692 7408 4116 7408 3579 7409 4116 7409 3580 7409 3692 7410 3694 7410 4117 7410 3692 7411 4117 7411 4116 7411 3694 7412 3696 7412 4118 7412 3694 7413 4118 7413 4117 7413 3696 7414 3698 7414 4119 7414 3696 7415 4119 7415 4118 7415 3698 7416 3700 7416 4120 7416 3698 7417 4120 7417 4119 7417 3700 7418 3702 7418 4121 7418 3700 7419 4121 7419 4120 7419 3702 7420 3704 7420 4122 7420 3702 7421 4122 7421 4121 7421 3704 7422 3706 7422 4123 7422 3704 7423 4123 7423 4122 7423 3583 7424 4124 7424 3746 7424 3583 7425 3746 7425 3584 7425 4124 7426 4125 7426 3747 7426 4124 7427 3747 7427 3746 7427 4125 7428 4126 7428 3748 7428 4125 7429 3748 7429 3747 7429 4126 7430 4127 7430 3749 7430 4126 7431 3749 7431 3748 7431 4127 7432 4128 7432 3750 7432 4127 7433 3750 7433 3749 7433 4128 7434 4129 7434 3751 7434 4128 7435 3751 7435 3750 7435 4129 7436 4130 7436 3752 7436 4129 7437 3752 7437 3751 7437 4130 7438 4131 7438 3754 7438 4130 7439 3754 7439 3752 7439 4131 7440 4132 7440 3756 7440 4131 7441 3756 7441 3754 7441 4132 7442 3760 7442 4133 7442 4132 7443 4133 7443 3756 7443 4134 7444 4135 7444 4136 7444 4134 7445 4136 7445 4137 7445 4137 7446 4136 7446 4138 7446 4137 7447 4138 7447 4139 7447 4139 7448 4138 7448 4140 7448 4139 7449 4140 7449 4141 7449 4141 7450 4140 7450 4142 7450 4141 7451 4142 7451 4143 7451 4143 7452 4142 7452 4144 7452 4142 7453 4145 7453 4144 7453 4103 7454 4104 7454 4146 7454 4103 7455 4146 7455 4147 7455 4147 7456 4146 7456 4134 7456 4147 7457 4134 7457 4148 7457 4148 7458 4134 7458 4137 7458 4148 7459 4137 7459 4149 7459 4149 7460 4137 7460 4139 7460 4149 7461 4139 7461 4150 7461 4150 7462 4139 7462 4141 7462 4150 7463 4141 7463 4151 7463 4151 7464 4141 7464 4143 7464 4151 7465 4143 7465 4152 7465 4152 7466 4143 7466 4144 7466 4152 7467 4144 7467 4153 7467 4102 7468 4103 7468 4147 7468 4102 7469 4147 7469 4154 7469 4154 7470 4147 7470 4148 7470 4154 7471 4148 7471 4155 7471 4155 7472 4148 7472 4149 7472 4155 7473 4149 7473 4156 7473 4156 7474 4149 7474 4150 7474 4156 7475 4150 7475 4157 7475 4157 7476 4150 7476 4151 7476 4157 7477 4151 7477 4158 7477 4158 7478 4151 7478 4152 7478 4158 7479 4152 7479 4159 7479 4159 7480 4152 7480 4153 7480 4159 7481 4153 7481 4160 7481 4160 7482 4153 7482 4161 7482 4160 7483 4161 7483 4162 7483 4162 7484 4161 7484 4163 7484 4162 7485 4163 7485 4164 7485 4164 7486 4163 7486 4165 7486 4164 7487 4165 7487 4166 7487 4166 7488 4165 7488 4167 7488 4166 7489 4167 7489 4168 7489 4168 7490 4167 7490 4169 7490 4168 7491 4169 7491 4170 7491 4170 7492 4169 7492 4171 7492 4170 7493 4171 7493 4172 7493 4172 7494 4171 7494 4173 7494 4172 7495 4173 7495 4174 7495 4174 7496 4173 7496 4175 7496 4174 7497 4175 7497 4176 7497 4176 7498 4175 7498 4177 7498 4176 7499 4177 7499 4178 7499 4178 7500 4177 7500 4179 7500 4178 7501 4179 7501 4180 7501 4181 7502 4182 7502 4183 7502 4181 7503 4183 7503 4184 7503 4184 7504 4183 7504 3758 7504 4184 7505 3758 7505 3761 7505 4101 7506 4102 7506 4154 7506 4101 7507 4154 7507 4185 7507 4185 7508 4154 7508 4155 7508 4185 7509 4155 7509 4186 7509 4186 7510 4155 7510 4156 7510 4186 7511 4156 7511 4187 7511 4187 7512 4156 7512 4157 7512 4187 7513 4157 7513 4188 7513 4188 7514 4157 7514 4158 7514 4188 7515 4158 7515 4189 7515 4189 7516 4158 7516 4159 7516 4189 7517 4159 7517 4190 7517 4190 7518 4159 7518 4160 7518 4190 7519 4160 7519 4191 7519 4191 7520 4160 7520 4162 7520 4191 7521 4162 7521 4192 7521 4192 7522 4162 7522 4164 7522 4192 7523 4164 7523 4193 7523 4193 7524 4164 7524 4166 7524 4193 7525 4166 7525 4194 7525 4194 7526 4166 7526 4168 7526 4194 7527 4168 7527 4195 7527 4195 7528 4168 7528 4170 7528 4195 7529 4170 7529 4196 7529 4196 7530 4170 7530 4172 7530 4196 7531 4172 7531 4197 7531 4197 7532 4172 7532 4174 7532 4197 7533 4174 7533 4198 7533 4198 7534 4174 7534 4176 7534 4198 7535 4176 7535 4199 7535 4199 7536 4176 7536 4178 7536 4199 7537 4178 7537 4200 7537 4200 7538 4178 7538 4180 7538 4200 7539 4180 7539 4201 7539 4201 7540 4180 7540 4181 7540 4201 7541 4181 7541 4202 7541 4202 7542 4181 7542 4184 7542 4202 7543 4184 7543 4203 7543 4203 7544 4184 7544 3761 7544 4203 7545 3761 7545 3760 7545 4100 7546 4101 7546 4185 7546 4100 7547 4185 7547 4204 7547 4204 7548 4185 7548 4186 7548 4204 7549 4186 7549 4205 7549 4205 7550 4186 7550 4187 7550 4205 7551 4187 7551 4206 7551 4206 7552 4187 7552 4188 7552 4206 7553 4188 7553 4207 7553 4207 7554 4188 7554 4189 7554 4207 7555 4189 7555 4208 7555 4208 7556 4189 7556 4190 7556 4208 7557 4190 7557 4209 7557 4209 7558 4190 7558 4191 7558 4209 7559 4191 7559 4210 7559 4210 7560 4191 7560 4192 7560 4210 7561 4192 7561 4211 7561 4211 7562 4192 7562 4193 7562 4211 7563 4193 7563 4212 7563 4212 7564 4193 7564 4194 7564 4212 7565 4194 7565 4213 7565 4213 7566 4194 7566 4195 7566 4213 7567 4195 7567 4214 7567 4214 7568 4195 7568 4196 7568 4214 7569 4196 7569 4215 7569 4215 7570 4196 7570 4197 7570 4215 7571 4197 7571 4216 7571 4216 7572 4197 7572 4198 7572 4216 7573 4198 7573 4217 7573 4217 7574 4198 7574 4199 7574 4217 7575 4199 7575 4218 7575 4218 7576 4199 7576 4200 7576 4218 7577 4200 7577 4219 7577 4219 7578 4200 7578 4201 7578 4219 7579 4201 7579 4220 7579 4220 7580 4201 7580 4202 7580 4220 7581 4202 7581 4221 7581 4221 7582 4202 7582 4203 7582 4221 7583 4203 7583 4222 7583 4222 7584 4203 7584 3760 7584 4222 7585 3760 7585 4132 7585 4099 7586 4100 7586 4204 7586 4099 7587 4204 7587 4223 7587 4223 7588 4204 7588 4205 7588 4223 7589 4205 7589 4224 7589 4224 7590 4205 7590 4206 7590 4224 7591 4206 7591 4225 7591 4225 7592 4206 7592 4207 7592 4225 7593 4207 7593 4226 7593 4226 7594 4207 7594 4208 7594 4226 7595 4208 7595 4227 7595 4227 7596 4208 7596 4209 7596 4227 7597 4209 7597 4228 7597 4228 7598 4209 7598 4210 7598 4228 7599 4210 7599 4229 7599 4229 7600 4210 7600 4211 7600 4229 7601 4211 7601 4230 7601 4230 7602 4211 7602 4212 7602 4230 7603 4212 7603 4231 7603 4231 7604 4212 7604 4213 7604 4231 7605 4213 7605 4232 7605 4232 7606 4213 7606 4214 7606 4232 7607 4214 7607 4233 7607 4233 7608 4214 7608 4215 7608 4233 7609 4215 7609 4234 7609 4234 7610 4215 7610 4216 7610 4234 7611 4216 7611 4235 7611 4235 7612 4216 7612 4217 7612 4235 7613 4217 7613 4236 7613 4236 7614 4217 7614 4218 7614 4236 7615 4218 7615 4237 7615 4237 7616 4218 7616 4219 7616 4237 7617 4219 7617 4238 7617 4238 7618 4219 7618 4220 7618 4238 7619 4220 7619 4239 7619 4239 7620 4220 7620 4221 7620 4239 7621 4221 7621 4240 7621 4240 7622 4221 7622 4222 7622 4240 7623 4222 7623 4241 7623 4241 7624 4222 7624 4132 7624 4241 7625 4132 7625 4131 7625 4098 7626 4099 7626 4223 7626 4098 7627 4223 7627 4242 7627 4242 7628 4223 7628 4224 7628 4242 7629 4224 7629 4243 7629 4243 7630 4224 7630 4225 7630 4243 7631 4225 7631 4244 7631 4244 7632 4225 7632 4226 7632 4244 7633 4226 7633 4245 7633 4245 7634 4226 7634 4227 7634 4245 7635 4227 7635 4246 7635 4246 7636 4227 7636 4228 7636 4246 7637 4228 7637 4247 7637 4247 7638 4228 7638 4229 7638 4247 7639 4229 7639 4248 7639 4248 7640 4229 7640 4230 7640 4248 7641 4230 7641 4249 7641 4249 7642 4230 7642 4231 7642 4249 7643 4231 7643 4250 7643 4250 7644 4231 7644 4232 7644 4250 7645 4232 7645 4251 7645 4251 7646 4232 7646 4233 7646 4251 7647 4233 7647 4252 7647 4252 7648 4233 7648 4234 7648 4252 7649 4234 7649 4253 7649 4253 7650 4234 7650 4235 7650 4253 7651 4235 7651 4254 7651 4254 7652 4235 7652 4236 7652 4254 7653 4236 7653 4255 7653 4255 7654 4236 7654 4237 7654 4255 7655 4237 7655 4256 7655 4256 7656 4237 7656 4238 7656 4256 7657 4238 7657 4257 7657 4257 7658 4238 7658 4239 7658 4257 7659 4239 7659 4258 7659 4258 7660 4239 7660 4240 7660 4258 7661 4240 7661 4259 7661 4259 7662 4240 7662 4241 7662 4259 7663 4241 7663 4260 7663 4260 7664 4241 7664 4131 7664 4260 7665 4131 7665 4130 7665 4097 7666 4098 7666 4242 7666 4097 7667 4242 7667 4261 7667 4261 7668 4242 7668 4243 7668 4261 7669 4243 7669 4262 7669 4262 7670 4243 7670 4244 7670 4262 7671 4244 7671 4263 7671 4263 7672 4244 7672 4245 7672 4263 7673 4245 7673 4264 7673 4264 7674 4245 7674 4246 7674 4264 7675 4246 7675 4265 7675 4265 7676 4246 7676 4247 7676 4265 7677 4247 7677 4266 7677 4266 7678 4247 7678 4248 7678 4266 7679 4248 7679 4267 7679 4267 7680 4248 7680 4249 7680 4267 7681 4249 7681 4268 7681 4268 7682 4249 7682 4250 7682 4268 7683 4250 7683 4269 7683 4269 7684 4250 7684 4251 7684 4269 7685 4251 7685 4270 7685 4270 7686 4251 7686 4252 7686 4270 7687 4252 7687 4271 7687 4271 7688 4252 7688 4253 7688 4271 7689 4253 7689 4272 7689 4272 7690 4253 7690 4254 7690 4272 7691 4254 7691 4273 7691 4273 7692 4254 7692 4255 7692 4273 7693 4255 7693 4274 7693 4274 7694 4255 7694 4256 7694 4274 7695 4256 7695 4275 7695 4275 7696 4256 7696 4257 7696 4275 7697 4257 7697 4276 7697 4276 7698 4257 7698 4258 7698 4276 7699 4258 7699 4277 7699 4277 7700 4258 7700 4259 7700 4277 7701 4259 7701 4278 7701 4278 7702 4259 7702 4260 7702 4278 7703 4260 7703 4279 7703 4279 7704 4260 7704 4130 7704 4279 7705 4130 7705 4129 7705 4096 7706 4097 7706 4261 7706 4096 7707 4261 7707 4280 7707 4280 7708 4261 7708 4262 7708 4280 7709 4262 7709 4281 7709 4281 7710 4262 7710 4263 7710 4281 7711 4263 7711 4282 7711 4282 7712 4263 7712 4264 7712 4282 7713 4264 7713 4283 7713 4283 7714 4264 7714 4265 7714 4283 7715 4265 7715 4284 7715 4284 7716 4265 7716 4266 7716 4284 7717 4266 7717 4285 7717 4285 7718 4266 7718 4267 7718 4285 7719 4267 7719 4286 7719 4286 7720 4267 7720 4268 7720 4286 7721 4268 7721 4287 7721 4287 7722 4268 7722 4269 7722 4287 7723 4269 7723 4288 7723 4288 7724 4269 7724 4270 7724 4288 7725 4270 7725 4289 7725 4289 7726 4270 7726 4271 7726 4289 7727 4271 7727 4290 7727 4290 7728 4271 7728 4272 7728 4290 7729 4272 7729 4291 7729 4291 7730 4272 7730 4273 7730 4291 7731 4273 7731 4292 7731 4292 7732 4273 7732 4274 7732 4292 7733 4274 7733 4293 7733 4293 7734 4274 7734 4275 7734 4293 7735 4275 7735 4294 7735 4294 7736 4275 7736 4276 7736 4294 7737 4276 7737 4295 7737 4295 7738 4276 7738 4277 7738 4295 7739 4277 7739 4296 7739 4296 7740 4277 7740 4278 7740 4296 7741 4278 7741 4297 7741 4297 7742 4278 7742 4279 7742 4297 7743 4279 7743 4298 7743 4298 7744 4279 7744 4129 7744 4298 7745 4129 7745 4128 7745 4095 7746 4096 7746 4280 7746 4095 7747 4280 7747 4299 7747 4299 7748 4280 7748 4281 7748 4299 7749 4281 7749 4300 7749 4300 7750 4281 7750 4282 7750 4300 7751 4282 7751 4301 7751 4301 7752 4282 7752 4283 7752 4301 7753 4283 7753 4302 7753 4302 7754 4283 7754 4284 7754 4302 7755 4284 7755 4303 7755 4303 7756 4284 7756 4285 7756 4303 7757 4285 7757 4304 7757 4304 7758 4285 7758 4286 7758 4304 7759 4286 7759 4305 7759 4305 7760 4286 7760 4287 7760 4305 7761 4287 7761 4306 7761 4306 7762 4287 7762 4288 7762 4306 7763 4288 7763 4307 7763 4307 7764 4288 7764 4289 7764 4307 7765 4289 7765 4308 7765 4308 7766 4289 7766 4290 7766 4308 7767 4290 7767 4309 7767 4309 7768 4290 7768 4291 7768 4309 7769 4291 7769 4310 7769 4310 7770 4291 7770 4292 7770 4310 7771 4292 7771 4311 7771 4311 7772 4292 7772 4293 7772 4311 7773 4293 7773 4312 7773 4312 7774 4293 7774 4294 7774 4312 7775 4294 7775 4313 7775 4313 7776 4294 7776 4295 7776 4313 7777 4295 7777 4314 7777 4314 7778 4295 7778 4296 7778 4314 7779 4296 7779 4315 7779 4315 7780 4296 7780 4297 7780 4315 7781 4297 7781 4316 7781 4316 7782 4297 7782 4298 7782 4316 7783 4298 7783 4317 7783 4317 7784 4298 7784 4128 7784 4317 7785 4128 7785 4127 7785 4094 7786 4095 7786 4299 7786 4094 7787 4299 7787 4318 7787 4318 7788 4299 7788 4300 7788 4318 7789 4300 7789 4319 7789 4319 7790 4300 7790 4301 7790 4319 7791 4301 7791 4320 7791 4320 7792 4301 7792 4302 7792 4320 7793 4302 7793 4321 7793 4321 7794 4302 7794 4303 7794 4321 7795 4303 7795 4322 7795 4322 7796 4303 7796 4304 7796 4322 7797 4304 7797 4323 7797 4323 7798 4304 7798 4305 7798 4323 7799 4305 7799 4324 7799 4324 7800 4305 7800 4306 7800 4324 7801 4306 7801 4325 7801 4325 7802 4306 7802 4307 7802 4325 7803 4307 7803 4326 7803 4326 7804 4307 7804 4308 7804 4326 7805 4308 7805 4327 7805 4327 7806 4308 7806 4309 7806 4327 7807 4309 7807 4328 7807 4328 7808 4309 7808 4310 7808 4328 7809 4310 7809 4329 7809 4329 7810 4310 7810 4311 7810 4329 7811 4311 7811 4330 7811 4330 7812 4311 7812 4312 7812 4330 7813 4312 7813 4331 7813 4331 7814 4312 7814 4313 7814 4331 7815 4313 7815 4332 7815 4332 7816 4313 7816 4314 7816 4332 7817 4314 7817 4333 7817 4333 7818 4314 7818 4315 7818 4333 7819 4315 7819 4334 7819 4334 7820 4315 7820 4316 7820 4334 7821 4316 7821 4335 7821 4335 7822 4316 7822 4317 7822 4335 7823 4317 7823 4336 7823 4336 7824 4317 7824 4127 7824 4336 7825 4127 7825 4126 7825 4093 7826 4094 7826 4318 7826 4093 7827 4318 7827 4337 7827 4337 7828 4318 7828 4319 7828 4337 7829 4319 7829 4338 7829 4338 7830 4319 7830 4320 7830 4338 7831 4320 7831 4339 7831 4339 7832 4320 7832 4321 7832 4339 7833 4321 7833 4340 7833 4340 7834 4321 7834 4322 7834 4340 7835 4322 7835 4341 7835 4341 7836 4322 7836 4323 7836 4341 7837 4323 7837 4342 7837 4342 7838 4323 7838 4324 7838 4342 7839 4324 7839 4343 7839 4343 7840 4324 7840 4325 7840 4343 7841 4325 7841 4344 7841 4344 7842 4325 7842 4326 7842 4344 7843 4326 7843 4345 7843 4345 7844 4326 7844 4327 7844 4345 7845 4327 7845 4346 7845 4346 7846 4327 7846 4328 7846 4346 7847 4328 7847 4347 7847 4347 7848 4328 7848 4329 7848 4347 7849 4329 7849 4348 7849 4348 7850 4329 7850 4330 7850 4348 7851 4330 7851 4349 7851 4349 7852 4330 7852 4331 7852 4349 7853 4331 7853 4350 7853 4350 7854 4331 7854 4332 7854 4350 7855 4332 7855 4351 7855 4351 7856 4332 7856 4333 7856 4351 7857 4333 7857 4352 7857 4352 7858 4333 7858 4334 7858 4352 7859 4334 7859 4353 7859 4353 7860 4334 7860 4335 7860 4353 7861 4335 7861 4354 7861 4354 7862 4335 7862 4336 7862 4354 7863 4336 7863 4355 7863 4355 7864 4336 7864 4126 7864 4355 7865 4126 7865 4125 7865 4092 7866 4093 7866 4337 7866 4092 7867 4337 7867 4356 7867 4356 7868 4337 7868 4338 7868 4356 7869 4338 7869 4357 7869 4357 7870 4338 7870 4339 7870 4357 7871 4339 7871 4358 7871 4358 7872 4339 7872 4340 7872 4358 7873 4340 7873 4359 7873 4359 7874 4340 7874 4341 7874 4359 7875 4341 7875 4360 7875 4360 7876 4341 7876 4342 7876 4360 7877 4342 7877 4361 7877 4361 7878 4342 7878 4343 7878 4361 7879 4343 7879 4362 7879 4362 7880 4343 7880 4344 7880 4362 7881 4344 7881 4363 7881 4363 7882 4344 7882 4345 7882 4363 7883 4345 7883 4364 7883 4364 7884 4345 7884 4346 7884 4364 7885 4346 7885 4365 7885 4365 7886 4346 7886 4347 7886 4365 7887 4347 7887 4366 7887 4366 7888 4347 7888 4348 7888 4366 7889 4348 7889 4367 7889 4367 7890 4348 7890 4349 7890 4367 7891 4349 7891 4368 7891 4368 7892 4349 7892 4350 7892 4368 7893 4350 7893 4369 7893 4369 7894 4350 7894 4351 7894 4369 7895 4351 7895 4370 7895 4370 7896 4351 7896 4352 7896 4370 7897 4352 7897 4371 7897 4371 7898 4352 7898 4353 7898 4371 7899 4353 7899 4372 7899 4372 7900 4353 7900 4354 7900 4372 7901 4354 7901 4373 7901 4373 7902 4354 7902 4355 7902 4373 7903 4355 7903 4374 7903 4374 7904 4355 7904 4125 7904 4374 7905 4125 7905 4124 7905 3572 7906 4092 7906 4356 7906 3572 7907 4356 7907 4375 7907 4375 7908 4356 7908 4357 7908 4375 7909 4357 7909 4376 7909 4376 7910 4357 7910 4358 7910 4376 7911 4358 7911 4377 7911 4377 7912 4358 7912 4359 7912 4377 7913 4359 7913 4378 7913 4378 7914 4359 7914 4360 7914 4378 7915 4360 7915 4379 7915 4379 7916 4360 7916 4361 7916 4379 7917 4361 7917 4380 7917 4380 7918 4361 7918 4362 7918 4380 7919 4362 7919 4381 7919 4381 7920 4362 7920 4363 7920 4381 7921 4363 7921 4382 7921 4382 7922 4363 7922 4364 7922 4382 7923 4364 7923 4383 7923 4383 7924 4364 7924 4365 7924 4383 7925 4365 7925 4384 7925 4384 7926 4365 7926 4366 7926 4384 7927 4366 7927 4385 7927 4385 7928 4366 7928 4367 7928 4385 7929 4367 7929 4386 7929 4386 7930 4367 7930 4368 7930 4386 7931 4368 7931 4387 7931 4387 7932 4368 7932 4369 7932 4387 7933 4369 7933 4388 7933 4388 7934 4369 7934 4370 7934 4388 7935 4370 7935 4389 7935 4389 7936 4370 7936 4371 7936 4389 7937 4371 7937 4390 7937 4390 7938 4371 7938 4372 7938 4390 7939 4372 7939 4391 7939 4391 7940 4372 7940 4373 7940 4391 7941 4373 7941 4392 7941 4392 7942 4373 7942 4374 7942 4392 7943 4374 7943 4393 7943 4393 7944 4374 7944 4124 7944 4393 7945 4124 7945 3583 7945 4394 7946 4395 7946 4396 7946 4394 7947 4396 7947 4397 7947 4397 7948 4396 7948 4398 7948 4397 7949 4398 7949 4399 7949 4123 7950 4400 7950 4401 7950 4400 7951 4402 7951 4401 7951 4401 7952 4402 7952 4403 7952 4402 7953 4404 7953 4403 7953 4403 7954 4404 7954 4405 7954 4403 7955 4405 7955 4406 7955 4406 7956 4405 7956 4394 7956 4406 7957 4394 7957 4407 7957 4407 7958 4394 7958 4397 7958 4407 7959 4397 7959 4408 7959 4408 7960 4397 7960 4399 7960 4408 7961 4399 7961 4409 7961 4409 7962 4399 7962 4410 7962 4409 7963 4410 7963 4411 7963 4411 7964 4410 7964 4412 7964 4411 7965 4412 7965 4413 7965 4413 7966 4412 7966 4414 7966 4413 7967 4414 7967 4415 7967 4415 7968 4414 7968 4416 7968 4415 7969 4416 7969 4417 7969 4417 7970 4416 7970 4418 7970 4416 7971 4419 7971 4418 7971 4418 7972 4419 7972 4420 7972 4419 7973 4421 7973 4420 7973 4420 7974 4421 7974 4422 7974 4421 7975 4423 7975 4422 7975 4422 7976 4423 7976 4424 7976 4422 7977 4424 7977 4425 7977 4425 7978 4424 7978 4426 7978 4425 7979 4426 7979 4427 7979 4427 7980 4426 7980 4428 7980 4427 7981 4428 7981 4429 7981 4429 7982 4428 7982 4430 7982 4429 7983 4430 7983 4431 7983 4122 7984 4123 7984 4401 7984 4122 7985 4401 7985 4432 7985 4433 7986 4403 7986 4406 7986 4433 7987 4406 7987 4434 7987 4434 7988 4406 7988 4407 7988 4434 7989 4407 7989 4435 7989 4435 7990 4407 7990 4408 7990 4435 7991 4408 7991 4436 7991 4436 7992 4408 7992 4409 7992 4436 7993 4409 7993 4437 7993 4437 7994 4409 7994 4411 7994 4437 7995 4411 7995 4438 7995 4438 7996 4411 7996 4413 7996 4438 7997 4413 7997 4439 7997 4439 7998 4413 7998 4415 7998 4439 7999 4415 7999 4440 7999 4440 8000 4415 8000 4417 8000 4440 8001 4417 8001 4441 8001 4441 8002 4417 8002 4418 8002 4441 8003 4418 8003 4442 8003 4442 8004 4418 8004 4420 8004 4442 8005 4420 8005 4443 8005 4443 8006 4420 8006 4444 8006 4420 8007 4422 8007 4444 8007 4444 8008 4422 8008 4425 8008 4444 8009 4425 8009 4445 8009 4445 8010 4425 8010 4427 8010 4445 8011 4427 8011 4446 8011 4446 8012 4427 8012 4429 8012 4446 8013 4429 8013 4447 8013 4447 8014 4429 8014 4431 8014 4447 8015 4431 8015 4448 8015 4448 8016 4431 8016 4449 8016 4448 8017 4449 8017 4450 8017 4450 8018 4449 8018 4451 8018 4450 8019 4451 8019 4452 8019 4452 8020 4451 8020 4114 8020 4452 8021 4114 8021 4112 8021 4121 8022 4122 8022 4432 8022 4121 8023 4432 8023 4453 8023 4453 8024 4432 8024 4433 8024 4453 8025 4433 8025 4454 8025 4454 8026 4433 8026 4434 8026 4454 8027 4434 8027 4455 8027 4455 8028 4434 8028 4435 8028 4455 8029 4435 8029 4456 8029 4456 8030 4435 8030 4436 8030 4456 8031 4436 8031 4457 8031 4457 8032 4436 8032 4437 8032 4457 8033 4437 8033 4458 8033 4458 8034 4437 8034 4438 8034 4458 8035 4438 8035 4459 8035 4459 8036 4438 8036 4439 8036 4459 8037 4439 8037 4460 8037 4460 8038 4439 8038 4440 8038 4460 8039 4440 8039 4461 8039 4461 8040 4440 8040 4441 8040 4461 8041 4441 8041 4462 8041 4462 8042 4441 8042 4442 8042 4462 8043 4442 8043 4463 8043 4463 8044 4442 8044 4443 8044 4463 8045 4443 8045 4464 8045 4464 8046 4443 8046 4444 8046 4464 8047 4444 8047 4465 8047 4465 8048 4444 8048 4445 8048 4465 8049 4445 8049 4466 8049 4467 8050 4446 8050 4447 8050 4467 8051 4447 8051 4468 8051 4468 8052 4447 8052 4448 8052 4468 8053 4448 8053 4469 8053 4469 8054 4448 8054 4450 8054 4469 8055 4450 8055 4470 8055 4470 8056 4450 8056 4452 8056 4470 8057 4452 8057 4471 8057 4471 8058 4452 8058 4112 8058 4471 8059 4112 8059 4110 8059 4120 8060 4121 8060 4453 8060 4120 8061 4453 8061 4472 8061 4472 8062 4453 8062 4454 8062 4472 8063 4454 8063 4473 8063 4473 8064 4454 8064 4455 8064 4473 8065 4455 8065 4474 8065 4474 8066 4455 8066 4456 8066 4474 8067 4456 8067 4475 8067 4475 8068 4456 8068 4457 8068 4475 8069 4457 8069 4476 8069 4476 8070 4457 8070 4458 8070 4476 8071 4458 8071 4477 8071 4477 8072 4458 8072 4459 8072 4477 8073 4459 8073 4478 8073 4478 8074 4459 8074 4460 8074 4478 8075 4460 8075 4479 8075 4479 8076 4460 8076 4461 8076 4479 8077 4461 8077 4480 8077 4480 8078 4461 8078 4462 8078 4480 8079 4462 8079 4481 8079 4481 8080 4462 8080 4463 8080 4481 8081 4463 8081 4482 8081 4482 8082 4463 8082 4464 8082 4482 8083 4464 8083 4483 8083 4484 8084 4465 8084 4466 8084 4484 8085 4466 8085 4485 8085 4486 8086 4467 8086 4468 8086 4486 8087 4468 8087 4487 8087 4487 8088 4468 8088 4469 8088 4487 8089 4469 8089 4488 8089 4488 8090 4469 8090 4470 8090 4488 8091 4470 8091 4489 8091 4489 8092 4470 8092 4471 8092 4489 8093 4471 8093 4490 8093 4490 8094 4471 8094 4110 8094 4490 8095 4110 8095 4109 8095 4119 8096 4120 8096 4472 8096 4119 8097 4472 8097 4491 8097 4491 8098 4472 8098 4473 8098 4491 8099 4473 8099 4492 8099 4492 8100 4473 8100 4474 8100 4492 8101 4474 8101 4493 8101 4493 8102 4474 8102 4475 8102 4493 8103 4475 8103 4494 8103 4494 8104 4475 8104 4476 8104 4494 8105 4476 8105 4495 8105 4495 8106 4476 8106 4477 8106 4495 8107 4477 8107 4496 8107 4496 8108 4477 8108 4478 8108 4496 8109 4478 8109 4497 8109 4497 8110 4478 8110 4479 8110 4497 8111 4479 8111 4498 8111 4498 8112 4479 8112 4480 8112 4498 8113 4480 8113 4499 8113 4499 8114 4480 8114 4481 8114 4499 8115 4481 8115 4500 8115 4500 8116 4481 8116 4482 8116 4500 8117 4482 8117 4501 8117 4501 8118 4482 8118 4483 8118 4501 8119 4483 8119 4502 8119 4502 8120 4483 8120 4484 8120 4502 8121 4484 8121 4503 8121 4503 8122 4484 8122 4485 8122 4503 8123 4485 8123 4504 8123 4504 8124 4485 8124 4486 8124 4504 8125 4486 8125 4505 8125 4505 8126 4486 8126 4487 8126 4505 8127 4487 8127 4506 8127 4506 8128 4487 8128 4488 8128 4506 8129 4488 8129 4507 8129 4507 8130 4488 8130 4489 8130 4507 8131 4489 8131 4508 8131 4508 8132 4489 8132 4490 8132 4508 8133 4490 8133 4509 8133 4509 8134 4490 8134 4109 8134 4509 8135 4109 8135 4108 8135 4118 8136 4119 8136 4491 8136 4118 8137 4491 8137 4510 8137 4510 8138 4491 8138 4492 8138 4510 8139 4492 8139 4511 8139 4511 8140 4492 8140 4493 8140 4511 8141 4493 8141 4512 8141 4512 8142 4493 8142 4494 8142 4512 8143 4494 8143 4513 8143 4513 8144 4494 8144 4495 8144 4513 8145 4495 8145 4514 8145 4514 8146 4495 8146 4496 8146 4514 8147 4496 8147 4515 8147 4515 8148 4496 8148 4497 8148 4515 8149 4497 8149 4516 8149 4516 8150 4497 8150 4498 8150 4516 8151 4498 8151 4517 8151 4517 8152 4498 8152 4499 8152 4517 8153 4499 8153 4518 8153 4518 8154 4499 8154 4500 8154 4518 8155 4500 8155 4519 8155 4519 8156 4500 8156 4501 8156 4519 8157 4501 8157 4520 8157 4520 8158 4501 8158 4502 8158 4520 8159 4502 8159 4521 8159 4521 8160 4502 8160 4503 8160 4521 8161 4503 8161 4522 8161 4522 8162 4503 8162 4504 8162 4522 8163 4504 8163 4523 8163 4523 8164 4504 8164 4505 8164 4523 8165 4505 8165 4524 8165 4524 8166 4505 8166 4506 8166 4524 8167 4506 8167 4525 8167 4525 8168 4506 8168 4507 8168 4525 8169 4507 8169 4526 8169 4526 8170 4507 8170 4508 8170 4526 8171 4508 8171 4527 8171 4527 8172 4508 8172 4509 8172 4527 8173 4509 8173 4528 8173 4528 8174 4509 8174 4108 8174 4528 8175 4108 8175 4107 8175 4117 8176 4118 8176 4510 8176 4117 8177 4510 8177 4529 8177 4529 8178 4510 8178 4511 8178 4529 8179 4511 8179 4530 8179 4530 8180 4511 8180 4512 8180 4530 8181 4512 8181 4531 8181 4531 8182 4512 8182 4513 8182 4531 8183 4513 8183 4532 8183 4532 8184 4513 8184 4514 8184 4532 8185 4514 8185 4533 8185 4533 8186 4514 8186 4515 8186 4533 8187 4515 8187 4534 8187 4534 8188 4515 8188 4516 8188 4534 8189 4516 8189 4535 8189 4535 8190 4516 8190 4517 8190 4535 8191 4517 8191 4536 8191 4536 8192 4517 8192 4518 8192 4536 8193 4518 8193 4537 8193 4537 8194 4518 8194 4519 8194 4537 8195 4519 8195 4538 8195 4538 8196 4519 8196 4520 8196 4538 8197 4520 8197 4539 8197 4539 8198 4520 8198 4521 8198 4539 8199 4521 8199 4540 8199 4540 8200 4521 8200 4522 8200 4540 8201 4522 8201 4541 8201 4541 8202 4522 8202 4523 8202 4541 8203 4523 8203 4542 8203 4542 8204 4523 8204 4524 8204 4542 8205 4524 8205 4543 8205 4543 8206 4524 8206 4525 8206 4543 8207 4525 8207 4544 8207 4544 8208 4525 8208 4526 8208 4544 8209 4526 8209 4545 8209 4545 8210 4526 8210 4527 8210 4545 8211 4527 8211 4546 8211 4546 8212 4527 8212 4528 8212 4546 8213 4528 8213 4547 8213 4547 8214 4528 8214 4107 8214 4547 8215 4107 8215 4106 8215 4116 8216 4117 8216 4529 8216 4116 8217 4529 8217 4548 8217 4548 8218 4529 8218 4530 8218 4548 8219 4530 8219 4549 8219 4549 8220 4530 8220 4531 8220 4549 8221 4531 8221 4550 8221 4550 8222 4531 8222 4532 8222 4550 8223 4532 8223 4551 8223 4551 8224 4532 8224 4533 8224 4551 8225 4533 8225 4552 8225 4552 8226 4533 8226 4534 8226 4552 8227 4534 8227 4553 8227 4553 8228 4534 8228 4535 8228 4553 8229 4535 8229 4554 8229 4554 8230 4535 8230 4536 8230 4554 8231 4536 8231 4555 8231 4555 8232 4536 8232 4537 8232 4555 8233 4537 8233 4556 8233 4556 8234 4537 8234 4538 8234 4556 8235 4538 8235 4557 8235 4557 8236 4538 8236 4539 8236 4557 8237 4539 8237 4558 8237 4558 8238 4539 8238 4540 8238 4558 8239 4540 8239 4559 8239 4559 8240 4540 8240 4541 8240 4559 8241 4541 8241 4560 8241 4560 8242 4541 8242 4542 8242 4560 8243 4542 8243 4561 8243 4561 8244 4542 8244 4543 8244 4561 8245 4543 8245 4562 8245 4562 8246 4543 8246 4544 8246 4562 8247 4544 8247 4563 8247 4563 8248 4544 8248 4545 8248 4563 8249 4545 8249 4564 8249 4564 8250 4545 8250 4546 8250 4564 8251 4546 8251 4565 8251 4565 8252 4546 8252 4547 8252 4565 8253 4547 8253 4566 8253 4566 8254 4547 8254 4106 8254 4566 8255 4106 8255 4105 8255 3580 8256 4116 8256 4548 8256 3580 8257 4548 8257 4567 8257 4567 8258 4548 8258 4549 8258 4567 8259 4549 8259 4568 8259 4568 8260 4549 8260 4550 8260 4568 8261 4550 8261 4569 8261 4569 8262 4550 8262 4551 8262 4569 8263 4551 8263 4570 8263 4570 8264 4551 8264 4552 8264 4570 8265 4552 8265 4571 8265 4571 8266 4552 8266 4553 8266 4571 8267 4553 8267 4572 8267 4572 8268 4553 8268 4554 8268 4572 8269 4554 8269 4573 8269 4573 8270 4554 8270 4555 8270 4573 8271 4555 8271 4574 8271 4574 8272 4555 8272 4556 8272 4574 8273 4556 8273 4575 8273 4575 8274 4556 8274 4557 8274 4575 8275 4557 8275 4576 8275 4576 8276 4557 8276 4558 8276 4576 8277 4558 8277 4577 8277 4577 8278 4558 8278 4559 8278 4577 8279 4559 8279 4578 8279 4578 8280 4559 8280 4560 8280 4578 8281 4560 8281 4579 8281 4579 8282 4560 8282 4561 8282 4579 8283 4561 8283 4580 8283 4580 8284 4561 8284 4562 8284 4580 8285 4562 8285 4581 8285 4581 8286 4562 8286 4563 8286 4581 8287 4563 8287 4582 8287 4582 8288 4563 8288 4564 8288 4582 8289 4564 8289 4583 8289 4583 8290 4564 8290 4565 8290 4583 8291 4565 8291 4584 8291 4584 8292 4565 8292 4566 8292 4584 8293 4566 8293 4585 8293 4585 8294 4566 8294 4105 8294 4585 8295 4105 8295 3587 8295 3614 8296 3582 8296 4586 8296 3614 8297 4586 8297 4587 8297 4587 8298 4586 8298 4588 8298 4587 8299 4588 8299 4589 8299 4589 8300 4588 8300 4590 8300 4589 8301 4590 8301 4591 8301 4591 8302 4590 8302 4592 8302 4591 8303 4592 8303 4593 8303 4593 8304 4592 8304 4594 8304 4593 8305 4594 8305 4595 8305 4595 8306 4594 8306 4596 8306 4595 8307 4596 8307 4597 8307 4597 8308 4596 8308 4598 8308 4597 8309 4598 8309 4599 8309 4599 8310 4598 8310 4600 8310 4599 8311 4600 8311 4601 8311 4601 8312 4600 8312 4602 8312 4601 8313 4602 8313 4603 8313 4603 8314 4602 8314 4604 8314 4603 8315 4604 8315 4605 8315 4605 8316 4604 8316 4606 8316 4605 8317 4606 8317 4607 8317 4607 8318 4606 8318 4608 8318 4607 8319 4608 8319 4609 8319 4609 8320 4608 8320 4610 8320 4609 8321 4610 8321 4611 8321 4611 8322 4610 8322 4612 8322 4611 8323 4612 8323 4613 8323 4613 8324 4612 8324 4614 8324 4613 8325 4614 8325 4615 8325 4615 8326 4614 8326 4616 8326 4615 8327 4616 8327 4617 8327 4617 8328 4616 8328 4618 8328 4617 8329 4618 8329 4619 8329 4619 8330 4618 8330 4620 8330 4619 8331 4620 8331 4621 8331 4621 8332 4620 8332 4622 8332 4621 8333 4622 8333 4623 8333 4623 8334 4622 8334 3575 8334 4623 8335 3575 8335 3653 8335 4624 8336 3614 8336 4587 8336 4624 8337 4587 8337 4625 8337 4625 8338 4587 8338 4589 8338 4625 8339 4589 8339 4626 8339 4626 8340 4589 8340 4591 8340 4626 8341 4591 8341 4627 8341 4627 8342 4591 8342 4593 8342 4627 8343 4593 8343 4628 8343 4628 8344 4593 8344 4595 8344 4628 8345 4595 8345 4629 8345 4629 8346 4595 8346 4597 8346 4629 8347 4597 8347 4630 8347 4630 8348 4597 8348 4599 8348 4630 8349 4599 8349 4631 8349 4631 8350 4599 8350 4601 8350 4631 8351 4601 8351 4632 8351 4632 8352 4601 8352 4603 8352 4632 8353 4603 8353 4633 8353 4633 8354 4603 8354 4605 8354 4633 8355 4605 8355 4634 8355 4634 8356 4605 8356 4607 8356 4634 8357 4607 8357 4635 8357 4635 8358 4607 8358 4609 8358 4635 8359 4609 8359 4636 8359 4636 8360 4609 8360 4611 8360 4636 8361 4611 8361 4637 8361 4637 8362 4611 8362 4613 8362 4637 8363 4613 8363 4638 8363 4638 8364 4613 8364 4615 8364 4638 8365 4615 8365 4639 8365 4639 8366 4615 8366 4617 8366 4639 8367 4617 8367 4640 8367 4640 8368 4617 8368 4619 8368 4640 8369 4619 8369 4641 8369 4641 8370 4619 8370 4621 8370 4641 8371 4621 8371 4642 8371 4642 8372 4621 8372 4623 8372 4642 8373 4623 8373 4643 8373 4643 8374 4623 8374 3653 8374 4643 8375 3653 8375 3651 8375 4644 8376 4624 8376 4625 8376 4644 8377 4625 8377 4645 8377 4645 8378 4625 8378 4626 8378 4645 8379 4626 8379 4646 8379 4646 8380 4626 8380 4627 8380 4646 8381 4627 8381 4647 8381 4647 8382 4627 8382 4628 8382 4647 8383 4628 8383 4648 8383 4648 8384 4628 8384 4629 8384 4648 8385 4629 8385 4649 8385 4649 8386 4629 8386 4630 8386 4649 8387 4630 8387 4650 8387 4650 8388 4630 8388 4631 8388 4650 8389 4631 8389 4651 8389 4651 8390 4631 8390 4632 8390 4651 8391 4632 8391 4652 8391 4652 8392 4632 8392 4633 8392 4652 8393 4633 8393 4653 8393 4653 8394 4633 8394 4634 8394 4653 8395 4634 8395 4654 8395 4654 8396 4634 8396 4635 8396 4654 8397 4635 8397 4655 8397 4655 8398 4635 8398 4636 8398 4655 8399 4636 8399 4656 8399 4656 8400 4636 8400 4637 8400 4656 8401 4637 8401 4657 8401 4657 8402 4637 8402 4638 8402 4657 8403 4638 8403 4658 8403 4658 8404 4638 8404 4639 8404 4658 8405 4639 8405 4659 8405 4659 8406 4639 8406 4640 8406 4659 8407 4640 8407 4660 8407 4660 8408 4640 8408 4641 8408 4660 8409 4641 8409 4661 8409 4661 8410 4641 8410 4642 8410 4661 8411 4642 8411 4662 8411 4662 8412 4642 8412 4643 8412 4662 8413 4643 8413 4663 8413 4663 8414 4643 8414 3651 8414 4663 8415 3651 8415 3649 8415 4664 8416 4644 8416 4645 8416 4664 8417 4645 8417 4665 8417 4665 8418 4645 8418 4646 8418 4665 8419 4646 8419 4666 8419 4666 8420 4646 8420 4647 8420 4666 8421 4647 8421 4667 8421 4667 8422 4647 8422 4648 8422 4667 8423 4648 8423 4668 8423 4668 8424 4648 8424 4649 8424 4668 8425 4649 8425 4669 8425 4669 8426 4649 8426 4650 8426 4669 8427 4650 8427 4670 8427 4670 8428 4650 8428 4651 8428 4670 8429 4651 8429 4671 8429 4671 8430 4651 8430 4652 8430 4671 8431 4652 8431 4672 8431 4672 8432 4652 8432 4653 8432 4672 8433 4653 8433 4673 8433 4673 8434 4653 8434 4654 8434 4673 8435 4654 8435 4674 8435 4674 8436 4654 8436 4655 8436 4674 8437 4655 8437 4675 8437 4675 8438 4655 8438 4656 8438 4675 8439 4656 8439 4676 8439 4676 8440 4656 8440 4657 8440 4676 8441 4657 8441 4677 8441 4677 8442 4657 8442 4658 8442 4677 8443 4658 8443 4678 8443 4678 8444 4658 8444 4659 8444 4678 8445 4659 8445 4679 8445 4679 8446 4659 8446 4660 8446 4679 8447 4660 8447 4680 8447 4680 8448 4660 8448 4661 8448 4680 8449 4661 8449 4681 8449 4681 8450 4661 8450 4662 8450 4681 8451 4662 8451 4682 8451 4682 8452 4662 8452 4663 8452 4682 8453 4663 8453 4683 8453 4683 8454 4663 8454 3649 8454 4683 8455 3649 8455 3647 8455 3611 8456 4664 8456 4665 8456 3611 8457 4665 8457 4684 8457 4684 8458 4665 8458 4666 8458 4684 8459 4666 8459 4685 8459 4685 8460 4666 8460 4667 8460 4685 8461 4667 8461 4686 8461 4686 8462 4667 8462 4668 8462 4686 8463 4668 8463 4687 8463 4687 8464 4668 8464 4669 8464 4687 8465 4669 8465 4688 8465 4688 8466 4669 8466 4670 8466 4688 8467 4670 8467 4689 8467 4689 8468 4670 8468 4671 8468 4689 8469 4671 8469 4690 8469 4690 8470 4671 8470 4672 8470 4690 8471 4672 8471 4691 8471 4691 8472 4672 8472 4673 8472 4691 8473 4673 8473 4692 8473 4692 8474 4673 8474 4674 8474 4692 8475 4674 8475 4693 8475 4693 8476 4674 8476 4675 8476 4693 8477 4675 8477 4694 8477 4694 8478 4675 8478 4676 8478 4694 8479 4676 8479 4695 8479 4695 8480 4676 8480 4677 8480 4695 8481 4677 8481 4696 8481 4696 8482 4677 8482 4678 8482 4696 8483 4678 8483 4697 8483 4697 8484 4678 8484 4679 8484 4697 8485 4679 8485 4698 8485 4698 8486 4679 8486 4680 8486 4698 8487 4680 8487 4699 8487 4699 8488 4680 8488 4681 8488 4699 8489 4681 8489 4700 8489 4700 8490 4681 8490 4682 8490 4700 8491 4682 8491 4701 8491 4701 8492 4682 8492 4683 8492 4701 8493 4683 8493 4702 8493 4702 8494 4683 8494 3647 8494 4702 8495 3647 8495 3645 8495 3612 8496 3611 8496 4684 8496 3612 8497 4684 8497 4703 8497 4703 8498 4684 8498 4685 8498 4703 8499 4685 8499 4704 8499 4704 8500 4685 8500 4686 8500 4704 8501 4686 8501 4705 8501 4705 8502 4686 8502 4687 8502 4705 8503 4687 8503 4706 8503 4706 8504 4687 8504 4688 8504 4706 8505 4688 8505 4707 8505 4707 8506 4688 8506 4689 8506 4707 8507 4689 8507 4708 8507 4708 8508 4689 8508 4690 8508 4708 8509 4690 8509 4709 8509 4709 8510 4690 8510 4691 8510 4709 8511 4691 8511 4710 8511 4710 8512 4691 8512 4692 8512 4710 8513 4692 8513 4711 8513 4711 8514 4692 8514 4693 8514 4711 8515 4693 8515 4712 8515 4712 8516 4693 8516 4694 8516 4712 8517 4694 8517 4713 8517 4713 8518 4694 8518 4695 8518 4713 8519 4695 8519 4714 8519 4714 8520 4695 8520 4696 8520 4714 8521 4696 8521 4715 8521 4715 8522 4696 8522 4697 8522 4715 8523 4697 8523 4716 8523 4716 8524 4697 8524 4698 8524 4716 8525 4698 8525 4717 8525 4717 8526 4698 8526 4699 8526 4717 8527 4699 8527 4718 8527 4718 8528 4699 8528 4700 8528 4718 8529 4700 8529 4719 8529 4719 8530 4700 8530 4701 8530 4719 8531 4701 8531 4720 8531 4720 8532 4701 8532 4702 8532 4720 8533 4702 8533 4721 8533 4721 8534 4702 8534 3645 8534 4721 8535 3645 8535 3642 8535 4722 8536 3612 8536 4703 8536 4722 8537 4703 8537 4723 8537 4723 8538 4703 8538 4704 8538 4723 8539 4704 8539 4724 8539 4724 8540 4704 8540 4705 8540 4724 8541 4705 8541 4725 8541 4725 8542 4705 8542 4706 8542 4725 8543 4706 8543 4726 8543 4726 8544 4706 8544 4707 8544 4726 8545 4707 8545 4727 8545 4727 8546 4707 8546 4708 8546 4727 8547 4708 8547 4728 8547 4728 8548 4708 8548 4709 8548 4728 8549 4709 8549 4729 8549 4729 8550 4709 8550 4710 8550 4729 8551 4710 8551 4730 8551 4730 8552 4710 8552 4711 8552 4730 8553 4711 8553 4731 8553 4731 8554 4711 8554 4712 8554 4731 8555 4712 8555 4732 8555 4732 8556 4712 8556 4713 8556 4732 8557 4713 8557 4733 8557 4733 8558 4713 8558 4714 8558 4733 8559 4714 8559 4734 8559 4734 8560 4714 8560 4715 8560 4734 8561 4715 8561 4735 8561 4735 8562 4715 8562 4716 8562 4735 8563 4716 8563 4736 8563 4736 8564 4716 8564 4717 8564 4736 8565 4717 8565 4737 8565 4737 8566 4717 8566 4718 8566 4737 8567 4718 8567 4738 8567 4738 8568 4718 8568 4719 8568 4738 8569 4719 8569 4739 8569 4739 8570 4719 8570 4720 8570 4739 8571 4720 8571 4740 8571 4740 8572 4720 8572 4721 8572 4740 8573 4721 8573 4741 8573 4741 8574 4721 8574 3642 8574 4741 8575 3642 8575 3641 8575 4742 8576 4743 8576 4744 8576 4742 8577 4744 8577 4745 8577 4745 8578 4744 8578 4746 8578 4745 8579 4746 8579 4747 8579 4747 8580 4746 8580 4748 8580 4747 8581 4748 8581 4749 8581 4749 8582 4748 8582 4750 8582 4749 8583 4750 8583 4751 8583 4751 8584 4750 8584 4752 8584 4751 8585 4752 8585 4753 8585 4753 8586 4752 8586 4754 8586 4753 8587 4754 8587 4755 8587 4755 8588 4754 8588 4756 8588 4755 8589 4756 8589 4757 8589 4757 8590 4756 8590 4758 8590 4757 8591 4758 8591 4759 8591 4759 8592 4758 8592 4760 8592 4759 8593 4760 8593 4761 8593 4761 8594 4760 8594 4762 8594 4761 8595 4762 8595 4763 8595 4763 8596 4762 8596 4764 8596 4763 8597 4764 8597 4765 8597 4765 8598 4764 8598 4766 8598 4765 8599 4766 8599 4767 8599 4767 8600 4766 8600 4768 8600 4767 8601 4768 8601 4769 8601 4769 8602 4768 8602 4770 8602 4769 8603 4770 8603 4771 8603 4771 8604 4770 8604 4772 8604 4771 8605 4772 8605 4773 8605 4773 8606 4772 8606 4774 8606 4773 8607 4774 8607 4775 8607 4775 8608 4774 8608 4776 8608 4775 8609 4776 8609 4777 8609 4777 8610 4776 8610 3639 8610 4777 8611 3639 8611 3637 8611 4778 8612 4761 8612 4763 8612 4778 8613 4763 8613 4779 8613 4779 8614 4763 8614 4765 8614 4779 8615 4765 8615 4780 8615 4780 8616 4765 8616 4767 8616 4780 8617 4767 8617 4781 8617 4781 8618 4767 8618 4769 8618 4781 8619 4769 8619 4782 8619 4782 8620 4769 8620 4771 8620 4782 8621 4771 8621 4783 8621 4783 8622 4771 8622 4773 8622 4783 8623 4773 8623 4784 8623 4784 8624 4773 8624 4775 8624 4784 8625 4775 8625 4785 8625 4785 8626 4775 8626 4777 8626 4785 8627 4777 8627 4786 8627 4786 8628 4777 8628 3637 8628 4786 8629 3637 8629 3634 8629 4787 8630 4779 8630 4780 8630 4787 8631 4780 8631 4788 8631 4788 8632 4780 8632 4781 8632 4788 8633 4781 8633 4789 8633 4789 8634 4781 8634 4782 8634 4789 8635 4782 8635 4790 8635 4790 8636 4782 8636 4783 8636 4790 8637 4783 8637 4791 8637 4791 8638 4783 8638 4784 8638 4791 8639 4784 8639 4792 8639 4792 8640 4784 8640 4785 8640 4792 8641 4785 8641 4793 8641 4793 8642 4785 8642 4786 8642 4793 8643 4786 8643 4794 8643 4794 8644 4786 8644 3634 8644 4794 8645 3634 8645 3633 8645 3608 8646 3607 8646 4795 8646 3608 8647 4795 8647 4796 8647 4796 8648 4795 8648 4797 8648 4796 8649 4797 8649 4798 8649 4798 8650 4797 8650 4799 8650 4798 8651 4799 8651 4800 8651 4800 8652 4799 8652 4801 8652 4800 8653 4801 8653 4802 8653 4802 8654 4801 8654 4803 8654 4802 8655 4803 8655 4804 8655 4804 8656 4803 8656 4805 8656 4804 8657 4805 8657 4806 8657 4806 8658 4805 8658 4807 8658 4806 8659 4807 8659 4808 8659 4808 8660 4807 8660 4809 8660 4808 8661 4809 8661 4810 8661 4810 8662 4809 8662 4811 8662 4810 8663 4811 8663 4812 8663 4812 8664 4811 8664 4813 8664 4812 8665 4813 8665 4814 8665 4814 8666 4813 8666 4815 8666 4814 8667 4815 8667 4816 8667 4816 8668 4815 8668 4817 8668 4816 8669 4817 8669 4818 8669 3602 8670 3604 8670 4819 8670 3602 8671 4819 8671 4820 8671 4820 8672 4819 8672 4821 8672 4820 8673 4821 8673 4822 8673 4822 8674 4821 8674 4823 8674 4822 8675 4823 8675 4824 8675 4824 8676 4823 8676 4825 8676 4824 8677 4825 8677 4826 8677 4826 8678 4825 8678 4827 8678 4826 8679 4827 8679 4828 8679 4828 8680 4827 8680 4829 8680 4828 8681 4829 8681 4830 8681 4830 8682 4829 8682 4831 8682 4830 8683 4831 8683 4832 8683 4832 8684 4831 8684 4833 8684 4832 8685 4833 8685 4834 8685 4834 8686 4833 8686 4835 8686 4834 8687 4835 8687 4836 8687 4836 8688 4835 8688 4837 8688 4836 8689 4837 8689 4838 8689 4838 8690 4837 8690 4839 8690 4838 8691 4839 8691 4840 8691 4840 8692 4839 8692 4841 8692 4840 8693 4841 8693 4842 8693 4842 8694 4841 8694 4843 8694 4842 8695 4843 8695 4844 8695 4844 8696 4843 8696 4845 8696 4844 8697 4845 8697 4846 8697 4846 8698 4845 8698 4847 8698 4846 8699 4847 8699 4848 8699 4848 8700 4847 8700 4849 8700 4848 8701 4849 8701 4850 8701 4850 8702 4849 8702 4851 8702 4850 8703 4851 8703 4852 8703 4852 8704 4851 8704 4853 8704 4852 8705 4853 8705 4854 8705 4854 8706 4853 8706 4855 8706 4854 8707 4855 8707 4856 8707 4856 8708 4855 8708 3631 8708 4856 8709 3631 8709 3629 8709 3600 8710 3602 8710 4820 8710 3600 8711 4820 8711 4857 8711 4857 8712 4820 8712 4822 8712 4857 8713 4822 8713 4858 8713 4858 8714 4822 8714 4824 8714 4858 8715 4824 8715 4859 8715 4859 8716 4824 8716 4826 8716 4859 8717 4826 8717 4860 8717 4860 8718 4826 8718 4828 8718 4860 8719 4828 8719 4861 8719 4861 8720 4828 8720 4830 8720 4861 8721 4830 8721 4862 8721 4862 8722 4830 8722 4832 8722 4862 8723 4832 8723 4863 8723 4863 8724 4832 8724 4834 8724 4863 8725 4834 8725 4864 8725 4864 8726 4834 8726 4836 8726 4864 8727 4836 8727 4865 8727 4865 8728 4836 8728 4838 8728 4865 8729 4838 8729 4866 8729 4866 8730 4838 8730 4840 8730 4866 8731 4840 8731 4867 8731 4867 8732 4840 8732 4842 8732 4867 8733 4842 8733 4868 8733 4868 8734 4842 8734 4844 8734 4868 8735 4844 8735 4869 8735 4869 8736 4844 8736 4846 8736 4869 8737 4846 8737 4870 8737 4870 8738 4846 8738 4848 8738 4870 8739 4848 8739 4871 8739 4871 8740 4848 8740 4850 8740 4871 8741 4850 8741 4872 8741 4872 8742 4850 8742 4852 8742 4872 8743 4852 8743 4873 8743 4873 8744 4852 8744 4854 8744 4873 8745 4854 8745 4874 8745 4874 8746 4854 8746 4856 8746 4874 8747 4856 8747 4875 8747 4875 8748 4856 8748 3629 8748 4875 8749 3629 8749 3627 8749 3598 8750 3600 8750 4857 8750 3598 8751 4857 8751 4876 8751 4876 8752 4857 8752 4858 8752 4876 8753 4858 8753 4877 8753 4877 8754 4858 8754 4859 8754 4877 8755 4859 8755 4878 8755 4878 8756 4859 8756 4860 8756 4878 8757 4860 8757 4879 8757 4879 8758 4860 8758 4861 8758 4879 8759 4861 8759 4880 8759 4880 8760 4861 8760 4862 8760 4880 8761 4862 8761 4881 8761 4881 8762 4862 8762 4863 8762 4881 8763 4863 8763 4882 8763 4882 8764 4863 8764 4864 8764 4882 8765 4864 8765 4883 8765 4883 8766 4864 8766 4865 8766 4883 8767 4865 8767 4884 8767 4884 8768 4865 8768 4866 8768 4884 8769 4866 8769 4885 8769 4885 8770 4866 8770 4867 8770 4885 8771 4867 8771 4886 8771 4886 8772 4867 8772 4868 8772 4886 8773 4868 8773 4887 8773 4887 8774 4868 8774 4869 8774 4887 8775 4869 8775 4888 8775 4888 8776 4869 8776 4870 8776 4888 8777 4870 8777 4889 8777 4889 8778 4870 8778 4871 8778 4889 8779 4871 8779 4890 8779 4890 8780 4871 8780 4872 8780 4890 8781 4872 8781 4891 8781 4891 8782 4872 8782 4873 8782 4891 8783 4873 8783 4892 8783 4892 8784 4873 8784 4874 8784 4892 8785 4874 8785 4893 8785 4893 8786 4874 8786 4875 8786 4893 8787 4875 8787 4894 8787 4894 8788 4875 8788 3627 8788 4894 8789 3627 8789 3625 8789 3595 8790 3598 8790 4876 8790 3595 8791 4876 8791 4895 8791 4895 8792 4876 8792 4877 8792 4895 8793 4877 8793 4896 8793 4896 8794 4877 8794 4878 8794 4896 8795 4878 8795 4897 8795 4897 8796 4878 8796 4879 8796 4897 8797 4879 8797 4898 8797 4898 8798 4879 8798 4880 8798 4898 8799 4880 8799 4899 8799 4899 8800 4880 8800 4881 8800 4899 8801 4881 8801 4900 8801 4900 8802 4881 8802 4882 8802 4900 8803 4882 8803 4901 8803 4901 8804 4882 8804 4883 8804 4901 8805 4883 8805 4902 8805 4902 8806 4883 8806 4884 8806 4902 8807 4884 8807 4903 8807 4903 8808 4884 8808 4885 8808 4903 8809 4885 8809 4904 8809 4904 8810 4885 8810 4886 8810 4904 8811 4886 8811 4905 8811 4905 8812 4886 8812 4887 8812 4905 8813 4887 8813 4906 8813 4906 8814 4887 8814 4888 8814 4906 8815 4888 8815 4907 8815 4907 8816 4888 8816 4889 8816 4907 8817 4889 8817 4908 8817 4908 8818 4889 8818 4890 8818 4908 8819 4890 8819 4909 8819 4909 8820 4890 8820 4891 8820 4909 8821 4891 8821 4910 8821 4910 8822 4891 8822 4892 8822 4910 8823 4892 8823 4911 8823 4911 8824 4892 8824 4893 8824 4911 8825 4893 8825 4912 8825 4912 8826 4893 8826 4894 8826 4912 8827 4894 8827 4913 8827 4913 8828 4894 8828 3625 8828 4913 8829 3625 8829 3623 8829 3596 8830 3595 8830 4895 8830 3596 8831 4895 8831 4914 8831 4914 8832 4895 8832 4896 8832 4914 8833 4896 8833 4915 8833 4915 8834 4896 8834 4897 8834 4915 8835 4897 8835 4916 8835 4916 8836 4897 8836 4898 8836 4916 8837 4898 8837 4917 8837 4917 8838 4898 8838 4899 8838 4917 8839 4899 8839 4918 8839 4918 8840 4899 8840 4900 8840 4918 8841 4900 8841 4919 8841 4919 8842 4900 8842 4901 8842 4919 8843 4901 8843 4920 8843 4920 8844 4901 8844 4902 8844 4920 8845 4902 8845 4921 8845 4921 8846 4902 8846 4903 8846 4921 8847 4903 8847 4922 8847 4922 8848 4903 8848 4904 8848 4922 8849 4904 8849 4923 8849 4923 8850 4904 8850 4905 8850 4923 8851 4905 8851 4924 8851 4924 8852 4905 8852 4906 8852 4924 8853 4906 8853 4925 8853 4925 8854 4906 8854 4907 8854 4925 8855 4907 8855 4926 8855 4926 8856 4907 8856 4908 8856 4926 8857 4908 8857 4927 8857 4927 8858 4908 8858 4909 8858 4927 8859 4909 8859 4928 8859 4928 8860 4909 8860 4910 8860 4928 8861 4910 8861 4929 8861 4929 8862 4910 8862 4911 8862 4929 8863 4911 8863 4930 8863 4930 8864 4911 8864 4912 8864 4930 8865 4912 8865 4931 8865 4931 8866 4912 8866 4913 8866 4931 8867 4913 8867 4932 8867 4932 8868 4913 8868 3623 8868 4932 8869 3623 8869 3621 8869 4933 8870 3596 8870 4914 8870 4933 8871 4914 8871 4934 8871 4934 8872 4914 8872 4915 8872 4934 8873 4915 8873 4935 8873 4935 8874 4915 8874 4916 8874 4935 8875 4916 8875 4936 8875 4936 8876 4916 8876 4917 8876 4936 8877 4917 8877 4937 8877 4937 8878 4917 8878 4918 8878 4937 8879 4918 8879 4938 8879 4938 8880 4918 8880 4919 8880 4938 8881 4919 8881 4939 8881 4939 8882 4919 8882 4920 8882 4939 8883 4920 8883 4940 8883 4940 8884 4920 8884 4921 8884 4940 8885 4921 8885 4941 8885 4941 8886 4921 8886 4922 8886 4941 8887 4922 8887 4942 8887 4942 8888 4922 8888 4923 8888 4942 8889 4923 8889 4943 8889 4943 8890 4923 8890 4924 8890 4943 8891 4924 8891 4944 8891 4944 8892 4924 8892 4925 8892 4944 8893 4925 8893 4945 8893 4945 8894 4925 8894 4926 8894 4945 8895 4926 8895 4946 8895 4946 8896 4926 8896 4927 8896 4946 8897 4927 8897 4947 8897 4947 8898 4927 8898 4928 8898 4947 8899 4928 8899 4948 8899 4948 8900 4928 8900 4929 8900 4948 8901 4929 8901 4949 8901 4949 8902 4929 8902 4930 8902 4949 8903 4930 8903 4950 8903 4950 8904 4930 8904 4931 8904 4950 8905 4931 8905 4951 8905 4951 8906 4931 8906 4932 8906 4951 8907 4932 8907 4952 8907 4952 8908 4932 8908 3621 8908 4952 8909 3621 8909 3619 8909 3592 8910 4933 8910 4934 8910 3592 8911 4934 8911 4953 8911 4953 8912 4934 8912 4935 8912 4953 8913 4935 8913 4954 8913 4954 8914 4935 8914 4936 8914 4954 8915 4936 8915 4955 8915 4955 8916 4936 8916 4937 8916 4955 8917 4937 8917 4956 8917 4956 8918 4937 8918 4938 8918 4956 8919 4938 8919 4957 8919 4957 8920 4938 8920 4939 8920 4957 8921 4939 8921 4958 8921 4958 8922 4939 8922 4940 8922 4958 8923 4940 8923 4959 8923 4959 8924 4940 8924 4941 8924 4959 8925 4941 8925 4960 8925 4960 8926 4941 8926 4942 8926 4960 8927 4942 8927 4961 8927 4961 8928 4942 8928 4943 8928 4961 8929 4943 8929 4962 8929 4962 8930 4943 8930 4944 8930 4962 8931 4944 8931 4963 8931 4963 8932 4944 8932 4945 8932 4963 8933 4945 8933 4964 8933 4964 8934 4945 8934 4946 8934 4964 8935 4946 8935 4965 8935 4965 8936 4946 8936 4947 8936 4965 8937 4947 8937 4966 8937 4966 8938 4947 8938 4948 8938 4966 8939 4948 8939 4967 8939 4967 8940 4948 8940 4949 8940 4967 8941 4949 8941 4968 8941 4968 8942 4949 8942 4950 8942 4968 8943 4950 8943 4969 8943 4969 8944 4950 8944 4951 8944 4969 8945 4951 8945 4970 8945 4970 8946 4951 8946 4952 8946 4970 8947 4952 8947 4971 8947 4971 8948 4952 8948 3619 8948 4971 8949 3619 8949 3617 8949 3590 8950 3592 8950 4953 8950 3590 8951 4953 8951 4972 8951 4972 8952 4953 8952 4954 8952 4972 8953 4954 8953 4973 8953 4973 8954 4954 8954 4955 8954 4973 8955 4955 8955 4974 8955 4974 8956 4955 8956 4956 8956 4974 8957 4956 8957 4975 8957 4975 8958 4956 8958 4957 8958 4975 8959 4957 8959 4976 8959 4976 8960 4957 8960 4958 8960 4976 8961 4958 8961 4977 8961 4977 8962 4958 8962 4959 8962 4977 8963 4959 8963 4978 8963 4978 8964 4959 8964 4960 8964 4978 8965 4960 8965 4979 8965 4979 8966 4960 8966 4961 8966 4979 8967 4961 8967 4980 8967 4980 8968 4961 8968 4962 8968 4980 8969 4962 8969 4981 8969 4981 8970 4962 8970 4963 8970 4981 8971 4963 8971 4982 8971 4982 8972 4963 8972 4964 8972 4982 8973 4964 8973 4983 8973 4983 8974 4964 8974 4965 8974 4983 8975 4965 8975 4984 8975 4984 8976 4965 8976 4966 8976 4984 8977 4966 8977 4985 8977 4985 8978 4966 8978 4967 8978 4985 8979 4967 8979 4986 8979 4986 8980 4967 8980 4968 8980 4986 8981 4968 8981 4987 8981 4987 8982 4968 8982 4969 8982 4987 8983 4969 8983 4988 8983 4988 8984 4969 8984 4970 8984 4988 8985 4970 8985 4989 8985 4989 8986 4970 8986 4971 8986 4989 8987 4971 8987 4990 8987 4990 8988 4971 8988 3617 8988 4990 8989 3617 8989 3616 8989 3585 8990 3590 8990 4972 8990 3585 8991 4972 8991 3586 8991 3586 8992 4972 8992 4973 8992 3586 8993 4973 8993 4991 8993 4991 8994 4973 8994 4974 8994 4991 8995 4974 8995 4992 8995 4992 8996 4974 8996 4975 8996 4992 8997 4975 8997 4993 8997 4993 8998 4975 8998 4976 8998 4993 8999 4976 8999 4994 8999 4994 9000 4976 9000 4977 9000 4994 9001 4977 9001 4995 9001 4995 9002 4977 9002 4978 9002 4995 9003 4978 9003 4996 9003 4996 9004 4978 9004 4979 9004 4996 9005 4979 9005 4997 9005 4997 9006 4979 9006 4980 9006 4997 9007 4980 9007 4998 9007 4998 9008 4980 9008 4981 9008 4998 9009 4981 9009 4999 9009 4999 9010 4981 9010 4982 9010 4999 9011 4982 9011 5000 9011 5000 9012 4982 9012 4983 9012 5000 9013 4983 9013 5001 9013 5001 9014 4983 9014 4984 9014 5001 9015 4984 9015 5002 9015 5002 9016 4984 9016 4985 9016 5002 9017 4985 9017 5003 9017 5003 9018 4985 9018 4986 9018 5003 9019 4986 9019 5004 9019 5004 9020 4986 9020 4987 9020 5004 9021 4987 9021 5005 9021 5005 9022 4987 9022 4988 9022 5005 9023 4988 9023 5006 9023 5006 9024 4988 9024 4989 9024 5006 9025 4989 9025 5007 9025 5007 9026 4989 9026 4990 9026 5007 9027 4990 9027 5008 9027 5008 9028 4990 9028 3616 9028 5008 9029 3616 9029 3615 9029 3580 9030 4567 9030 5009 9030 3580 9031 5009 9031 3581 9031 4567 9032 4568 9032 5010 9032 4567 9033 5010 9033 5009 9033 4568 9034 4569 9034 5011 9034 4568 9035 5011 9035 5010 9035 4569 9036 4570 9036 5012 9036 4569 9037 5012 9037 5011 9037 4570 9038 4571 9038 5013 9038 4570 9039 5013 9039 5012 9039 4571 9040 4572 9040 5014 9040 4571 9041 5014 9041 5013 9041 4572 9042 4573 9042 5015 9042 4572 9043 5015 9043 5014 9043 4573 9044 4574 9044 5016 9044 4573 9045 5016 9045 5015 9045 4574 9046 4575 9046 5017 9046 4574 9047 5017 9047 5016 9047 4575 9048 4576 9048 5018 9048 4575 9049 5018 9049 5017 9049 4576 9050 4577 9050 5019 9050 4576 9051 5019 9051 5018 9051 4577 9052 4578 9052 5020 9052 4577 9053 5020 9053 5019 9053 4578 9054 4579 9054 5021 9054 4578 9055 5021 9055 5020 9055 4579 9056 4580 9056 5022 9056 4579 9057 5022 9057 5021 9057 4580 9058 4581 9058 5023 9058 4580 9059 5023 9059 5022 9059 4581 9060 4582 9060 5024 9060 4581 9061 5024 9061 5023 9061 4582 9062 4583 9062 5025 9062 4582 9063 5025 9063 5024 9063 4583 9064 4584 9064 5026 9064 4583 9065 5026 9065 5025 9065 4584 9066 4585 9066 5027 9066 4584 9067 5027 9067 5026 9067 4585 9068 3587 9068 3576 9068 4585 9069 3576 9069 5027 9069 3572 9070 4375 9070 3615 9070 3572 9071 3615 9071 3573 9071 4375 9072 4376 9072 5008 9072 4375 9073 5008 9073 3615 9073 4376 9074 4377 9074 5007 9074 4376 9075 5007 9075 5008 9075 4377 9076 4378 9076 5006 9076 4377 9077 5006 9077 5007 9077 4378 9078 4379 9078 5005 9078 4378 9079 5005 9079 5006 9079 4379 9080 4380 9080 5004 9080 4379 9081 5004 9081 5005 9081 4380 9082 4381 9082 5003 9082 4380 9083 5003 9083 5004 9083 4381 9084 4382 9084 5002 9084 4381 9085 5002 9085 5003 9085 4382 9086 4383 9086 5001 9086 4382 9087 5001 9087 5002 9087 4383 9088 4384 9088 5000 9088 4383 9089 5000 9089 5001 9089 4384 9090 4385 9090 4999 9090 4384 9091 4999 9091 5000 9091 4385 9092 4386 9092 4998 9092 4385 9093 4998 9093 4999 9093 4386 9094 4387 9094 4997 9094 4386 9095 4997 9095 4998 9095 4387 9096 4388 9096 4996 9096 4387 9097 4996 9097 4997 9097 4388 9098 4389 9098 4995 9098 4388 9099 4995 9099 4996 9099 4389 9100 4390 9100 4994 9100 4389 9101 4994 9101 4995 9101 4390 9102 4391 9102 4993 9102 4390 9103 4993 9103 4994 9103 4391 9104 4392 9104 4992 9104 4391 9105 4992 9105 4993 9105 4392 9106 4393 9106 4991 9106 4392 9107 4991 9107 4992 9107 4393 9108 3583 9108 3586 9108 4393 9109 3586 9109 4991 9109 3582 9110 3581 9110 5009 9110 3582 9111 5009 9111 4586 9111 4586 9112 5009 9112 5010 9112 4586 9113 5010 9113 4588 9113 4588 9114 5010 9114 5011 9114 4588 9115 5011 9115 4590 9115 4590 9116 5011 9116 5012 9116 4590 9117 5012 9117 4592 9117 4592 9118 5012 9118 5013 9118 4592 9119 5013 9119 4594 9119 4594 9120 5013 9120 5014 9120 4594 9121 5014 9121 4596 9121 4596 9122 5014 9122 5015 9122 4596 9123 5015 9123 4598 9123 4598 9124 5015 9124 5016 9124 4598 9125 5016 9125 4600 9125 4600 9126 5016 9126 5017 9126 4600 9127 5017 9127 4602 9127 4602 9128 5017 9128 5018 9128 4602 9129 5018 9129 4604 9129 4604 9130 5018 9130 5019 9130 4604 9131 5019 9131 4606 9131 4606 9132 5019 9132 5020 9132 4606 9133 5020 9133 4608 9133 4608 9134 5020 9134 5021 9134 4608 9135 5021 9135 4610 9135 4610 9136 5021 9136 5022 9136 4610 9137 5022 9137 4612 9137 4612 9138 5022 9138 5023 9138 4612 9139 5023 9139 4614 9139 4614 9140 5023 9140 5024 9140 4614 9141 5024 9141 4616 9141 4616 9142 5024 9142 5025 9142 4616 9143 5025 9143 4618 9143 4618 9144 5025 9144 5026 9144 4618 9145 5026 9145 4620 9145 4620 9146 5026 9146 5027 9146 4620 9147 5027 9147 4622 9147 4622 9148 5027 9148 3576 9148 4622 9149 3576 9149 3575 9149 4145 9150 4182 9150 4179 9150 4179 9151 4177 9151 4175 9151 4179 9152 4175 9152 4173 9152 4144 9153 4145 9153 4179 9153 4161 9154 4153 9154 4144 9154 4165 9155 4163 9155 4161 9155 4167 9156 4165 9156 4161 9156 4144 9157 4179 9157 4173 9157 4144 9158 4173 9158 4171 9158 4167 9159 4161 9159 4144 9159 4144 9160 4171 9160 4169 9160 4169 9161 4167 9161 4144 9161 3789 9162 4145 9162 4135 9162 4135 9163 4134 9163 4146 9163 4146 9164 4104 9164 3787 9164 3787 9165 3789 9165 4135 9165 4135 9166 4146 9166 3787 9166 5028 9167 5029 9167 4050 9167 4050 9168 4049 9168 5030 9168 5030 9169 5031 9169 5028 9169 4050 9170 5030 9170 5028 9170 4047 9171 4045 9171 4060 9171 4047 9172 4060 9172 4049 9172 4059 9173 4058 9173 4068 9173 4059 9174 4068 9174 4060 9174 4075 9175 4074 9175 4081 9175 4068 9176 4067 9176 4075 9176 4080 9177 4086 9177 4091 9177 4080 9178 4091 9178 4081 9178 4855 9179 5032 9179 5033 9179 4855 9180 5033 9180 3631 9180 5032 9181 5034 9181 5035 9181 5032 9182 5035 9182 5033 9182 5034 9183 5036 9183 5037 9183 5034 9184 5037 9184 5035 9184 5036 9185 5038 9185 5039 9185 5036 9186 5039 9186 5037 9186 5038 9187 5040 9187 5041 9187 5038 9188 5041 9188 5039 9188 4853 9189 5042 9189 5032 9189 4853 9190 5032 9190 4855 9190 5042 9191 5043 9191 5034 9191 5042 9192 5034 9192 5032 9192 5043 9193 5044 9193 5036 9193 5043 9194 5036 9194 5034 9194 5044 9195 5045 9195 5038 9195 5044 9196 5038 9196 5036 9196 5045 9197 5046 9197 5040 9197 5045 9198 5040 9198 5038 9198 4851 9199 5047 9199 5042 9199 4851 9200 5042 9200 4853 9200 5047 9201 5048 9201 5043 9201 5047 9202 5043 9202 5042 9202 5048 9203 5049 9203 5044 9203 5048 9204 5044 9204 5043 9204 5049 9205 5050 9205 5045 9205 5049 9206 5045 9206 5044 9206 5050 9207 5051 9207 5046 9207 5050 9208 5046 9208 5045 9208 4849 9209 5052 9209 5047 9209 4849 9210 5047 9210 4851 9210 5052 9211 5053 9211 5048 9211 5052 9212 5048 9212 5047 9212 5053 9213 5054 9213 5049 9213 5053 9214 5049 9214 5048 9214 5054 9215 5055 9215 5050 9215 5054 9216 5050 9216 5049 9216 5055 9217 5056 9217 5051 9217 5055 9218 5051 9218 5050 9218 5056 9219 5057 9219 5058 9219 5056 9220 5058 9220 5051 9220 4847 9221 5059 9221 5052 9221 4847 9222 5052 9222 4849 9222 5059 9223 5060 9223 5053 9223 5059 9224 5053 9224 5052 9224 5060 9225 5061 9225 5054 9225 5060 9226 5054 9226 5053 9226 5061 9227 5062 9227 5055 9227 5061 9228 5055 9228 5054 9228 5062 9229 5063 9229 5056 9229 5062 9230 5056 9230 5055 9230 5063 9231 5064 9231 5057 9231 5063 9232 5057 9232 5056 9232 4845 9233 5065 9233 5059 9233 4845 9234 5059 9234 4847 9234 5065 9235 5066 9235 5060 9235 5065 9236 5060 9236 5059 9236 5066 9237 5067 9237 5061 9237 5066 9238 5061 9238 5060 9238 5067 9239 5068 9239 5062 9239 5067 9240 5062 9240 5061 9240 5068 9241 5069 9241 5063 9241 5068 9242 5063 9242 5062 9242 5069 9243 5070 9243 5064 9243 5069 9244 5064 9244 5063 9244 5070 9245 5071 9245 5072 9245 5070 9246 5072 9246 5064 9246 4843 9247 5073 9247 5065 9247 4843 9248 5065 9248 4845 9248 5073 9249 5074 9249 5066 9249 5073 9250 5066 9250 5065 9250 5074 9251 5075 9251 5067 9251 5074 9252 5067 9252 5066 9252 5075 9253 5076 9253 5068 9253 5075 9254 5068 9254 5067 9254 5076 9255 5077 9255 5069 9255 5076 9256 5069 9256 5068 9256 5077 9257 5078 9257 5070 9257 5077 9258 5070 9258 5069 9258 5078 9259 5079 9259 5071 9259 5078 9260 5071 9260 5070 9260 4841 9261 5080 9261 5073 9261 4841 9262 5073 9262 4843 9262 5080 9263 5081 9263 5074 9263 5080 9264 5074 9264 5073 9264 5081 9265 5082 9265 5075 9265 5081 9266 5075 9266 5074 9266 5082 9267 5083 9267 5076 9267 5082 9268 5076 9268 5075 9268 5083 9269 5084 9269 5077 9269 5083 9270 5077 9270 5076 9270 5084 9271 5085 9271 5078 9271 5084 9272 5078 9272 5077 9272 5085 9273 5086 9273 5079 9273 5085 9274 5079 9274 5078 9274 5086 9275 5087 9275 5088 9275 5086 9276 5088 9276 5079 9276 5087 9277 5089 9277 5090 9277 5087 9278 5090 9278 5088 9278 4839 9279 5091 9279 5080 9279 4839 9280 5080 9280 4841 9280 5091 9281 5092 9281 5081 9281 5091 9282 5081 9282 5080 9282 5092 9283 5093 9283 5082 9283 5092 9284 5082 9284 5081 9284 5093 9285 5094 9285 5083 9285 5093 9286 5083 9286 5082 9286 5094 9287 5095 9287 5084 9287 5094 9288 5084 9288 5083 9288 5095 9289 5096 9289 5085 9289 5095 9290 5085 9290 5084 9290 5096 9291 5097 9291 5086 9291 5096 9292 5086 9292 5085 9292 5097 9293 5098 9293 5087 9293 5097 9294 5087 9294 5086 9294 5098 9295 5099 9295 5089 9295 5098 9296 5089 9296 5087 9296 5099 9297 4816 9297 4818 9297 5099 9298 4818 9298 5089 9298 4837 9299 5100 9299 5091 9299 4837 9300 5091 9300 4839 9300 5100 9301 5101 9301 5092 9301 5100 9302 5092 9302 5091 9302 5101 9303 5102 9303 5093 9303 5101 9304 5093 9304 5092 9304 5102 9305 5103 9305 5094 9305 5102 9306 5094 9306 5093 9306 5103 9307 5104 9307 5095 9307 5103 9308 5095 9308 5094 9308 5104 9309 5105 9309 5096 9309 5104 9310 5096 9310 5095 9310 5105 9311 5106 9311 5097 9311 5105 9312 5097 9312 5096 9312 5106 9313 5107 9313 5098 9313 5106 9314 5098 9314 5097 9314 5107 9315 5108 9315 5099 9315 5107 9316 5099 9316 5098 9316 5108 9317 4814 9317 4816 9317 5108 9318 4816 9318 5099 9318 4835 9319 5109 9319 5100 9319 4835 9320 5100 9320 4837 9320 5109 9321 5110 9321 5101 9321 5109 9322 5101 9322 5100 9322 5110 9323 5111 9323 5102 9323 5110 9324 5102 9324 5101 9324 5111 9325 5112 9325 5103 9325 5111 9326 5103 9326 5102 9326 5112 9327 5113 9327 5104 9327 5112 9328 5104 9328 5103 9328 5113 9329 5114 9329 5105 9329 5113 9330 5105 9330 5104 9330 5114 9331 5115 9331 5106 9331 5114 9332 5106 9332 5105 9332 5115 9333 5116 9333 5107 9333 5115 9334 5107 9334 5106 9334 5116 9335 5117 9335 5108 9335 5116 9336 5108 9336 5107 9336 5117 9337 4812 9337 4814 9337 5117 9338 4814 9338 5108 9338 4833 9339 5118 9339 5109 9339 4833 9340 5109 9340 4835 9340 5118 9341 5119 9341 5110 9341 5118 9342 5110 9342 5109 9342 5119 9343 5120 9343 5111 9343 5119 9344 5111 9344 5110 9344 5120 9345 5121 9345 5112 9345 5120 9346 5112 9346 5111 9346 5121 9347 5122 9347 5113 9347 5121 9348 5113 9348 5112 9348 5122 9349 5123 9349 5114 9349 5122 9350 5114 9350 5113 9350 5123 9351 5124 9351 5115 9351 5123 9352 5115 9352 5114 9352 5124 9353 5125 9353 5116 9353 5124 9354 5116 9354 5115 9354 5125 9355 5126 9355 5117 9355 5125 9356 5117 9356 5116 9356 5126 9357 4810 9357 4812 9357 5126 9358 4812 9358 5117 9358 4831 9359 5127 9359 5118 9359 4831 9360 5118 9360 4833 9360 5127 9361 5128 9361 5119 9361 5127 9362 5119 9362 5118 9362 5128 9363 5129 9363 5120 9363 5128 9364 5120 9364 5119 9364 5129 9365 5130 9365 5121 9365 5129 9366 5121 9366 5120 9366 5130 9367 5131 9367 5122 9367 5130 9368 5122 9368 5121 9368 5131 9369 5132 9369 5123 9369 5131 9370 5123 9370 5122 9370 5132 9371 5133 9371 5124 9371 5132 9372 5124 9372 5123 9372 5133 9373 5134 9373 5125 9373 5133 9374 5125 9374 5124 9374 5134 9375 5135 9375 5126 9375 5134 9376 5126 9376 5125 9376 5135 9377 4808 9377 4810 9377 5135 9378 4810 9378 5126 9378 4829 9379 5136 9379 5127 9379 4829 9380 5127 9380 4831 9380 5136 9381 5137 9381 5128 9381 5136 9382 5128 9382 5127 9382 5137 9383 5138 9383 5129 9383 5137 9384 5129 9384 5128 9384 5138 9385 5139 9385 5130 9385 5138 9386 5130 9386 5129 9386 5139 9387 5140 9387 5131 9387 5139 9388 5131 9388 5130 9388 5140 9389 5141 9389 5132 9389 5140 9390 5132 9390 5131 9390 5141 9391 5142 9391 5133 9391 5141 9392 5133 9392 5132 9392 5142 9393 5143 9393 5134 9393 5142 9394 5134 9394 5133 9394 5143 9395 5144 9395 5135 9395 5143 9396 5135 9396 5134 9396 5144 9397 4806 9397 4808 9397 5144 9398 4808 9398 5135 9398 4827 9399 5145 9399 5136 9399 4827 9400 5136 9400 4829 9400 5145 9401 5146 9401 5137 9401 5145 9402 5137 9402 5136 9402 5146 9403 5147 9403 5138 9403 5146 9404 5138 9404 5137 9404 5147 9405 5148 9405 5139 9405 5147 9406 5139 9406 5138 9406 5148 9407 5149 9407 5140 9407 5148 9408 5140 9408 5139 9408 5149 9409 5150 9409 5141 9409 5149 9410 5141 9410 5140 9410 5150 9411 5151 9411 5142 9411 5150 9412 5142 9412 5141 9412 5151 9413 5152 9413 5143 9413 5151 9414 5143 9414 5142 9414 5152 9415 5153 9415 5144 9415 5152 9416 5144 9416 5143 9416 5153 9417 4804 9417 4806 9417 5153 9418 4806 9418 5144 9418 4825 9419 5154 9419 5145 9419 4825 9420 5145 9420 4827 9420 5154 9421 5155 9421 5146 9421 5154 9422 5146 9422 5145 9422 5155 9423 5156 9423 5147 9423 5155 9424 5147 9424 5146 9424 5156 9425 5157 9425 5148 9425 5156 9426 5148 9426 5147 9426 5157 9427 5158 9427 5149 9427 5157 9428 5149 9428 5148 9428 5158 9429 5159 9429 5150 9429 5158 9430 5150 9430 5149 9430 5159 9431 5160 9431 5151 9431 5159 9432 5151 9432 5150 9432 5160 9433 5161 9433 5152 9433 5160 9434 5152 9434 5151 9434 5161 9435 5162 9435 5153 9435 5161 9436 5153 9436 5152 9436 5162 9437 4802 9437 4804 9437 5162 9438 4804 9438 5153 9438 4823 9439 5163 9439 5154 9439 4823 9440 5154 9440 4825 9440 5163 9441 5164 9441 5155 9441 5163 9442 5155 9442 5154 9442 5164 9443 5165 9443 5156 9443 5164 9444 5156 9444 5155 9444 5165 9445 5166 9445 5157 9445 5165 9446 5157 9446 5156 9446 5166 9447 5167 9447 5158 9447 5166 9448 5158 9448 5157 9448 5167 9449 5168 9449 5159 9449 5167 9450 5159 9450 5158 9450 5168 9451 5169 9451 5160 9451 5168 9452 5160 9452 5159 9452 5169 9453 5170 9453 5161 9453 5169 9454 5161 9454 5160 9454 5170 9455 5171 9455 5162 9455 5170 9456 5162 9456 5161 9456 5171 9457 4800 9457 4802 9457 5171 9458 4802 9458 5162 9458 4821 9459 5172 9459 5163 9459 4821 9460 5163 9460 4823 9460 5172 9461 5173 9461 5164 9461 5172 9462 5164 9462 5163 9462 5173 9463 5174 9463 5165 9463 5173 9464 5165 9464 5164 9464 5174 9465 5175 9465 5166 9465 5174 9466 5166 9466 5165 9466 5175 9467 5176 9467 5167 9467 5175 9468 5167 9468 5166 9468 5176 9469 5177 9469 5168 9469 5176 9470 5168 9470 5167 9470 5177 9471 5178 9471 5169 9471 5177 9472 5169 9472 5168 9472 5178 9473 5179 9473 5170 9473 5178 9474 5170 9474 5169 9474 5179 9475 5180 9475 5171 9475 5179 9476 5171 9476 5170 9476 5180 9477 4798 9477 4800 9477 5180 9478 4800 9478 5171 9478 4819 9479 5181 9479 5172 9479 4819 9480 5172 9480 4821 9480 5181 9481 5182 9481 5173 9481 5181 9482 5173 9482 5172 9482 5182 9483 5183 9483 5174 9483 5182 9484 5174 9484 5173 9484 5183 9485 5184 9485 5175 9485 5183 9486 5175 9486 5174 9486 5184 9487 5185 9487 5176 9487 5184 9488 5176 9488 5175 9488 5185 9489 5186 9489 5177 9489 5185 9490 5177 9490 5176 9490 5186 9491 5187 9491 5178 9491 5186 9492 5178 9492 5177 9492 5187 9493 5188 9493 5179 9493 5187 9494 5179 9494 5178 9494 5188 9495 5189 9495 5180 9495 5188 9496 5180 9496 5179 9496 5189 9497 4796 9497 4798 9497 5189 9498 4798 9498 5180 9498 3604 9499 5190 9499 5181 9499 3604 9500 5181 9500 4819 9500 5190 9501 5191 9501 5182 9501 5190 9502 5182 9502 5181 9502 5191 9503 5192 9503 5183 9503 5191 9504 5183 9504 5182 9504 5192 9505 5193 9505 5184 9505 5192 9506 5184 9506 5183 9506 5193 9507 5194 9507 5185 9507 5193 9508 5185 9508 5184 9508 5194 9509 5195 9509 5186 9509 5194 9510 5186 9510 5185 9510 5195 9511 5196 9511 5187 9511 5195 9512 5187 9512 5186 9512 5196 9513 5197 9513 5188 9513 5196 9514 5188 9514 5187 9514 5197 9515 5198 9515 5189 9515 5197 9516 5189 9516 5188 9516 5198 9517 3608 9517 4796 9517 5198 9518 4796 9518 5189 9518 3949 9519 3684 9519 5199 9519 3949 9520 5199 9520 5200 9520 5200 9521 5199 9521 5201 9521 5200 9522 5201 9522 5202 9522 5202 9523 5201 9523 5203 9523 5202 9524 5203 9524 5204 9524 5204 9525 5203 9525 5205 9525 5204 9526 5205 9526 5206 9526 5206 9527 5205 9527 5207 9527 5206 9528 5207 9528 5208 9528 5208 9529 5207 9529 5209 9529 5208 9530 5209 9530 5210 9530 5210 9531 5209 9531 5211 9531 5210 9532 5211 9532 5212 9532 5212 9533 5211 9533 5213 9533 5212 9534 5213 9534 5214 9534 5214 9535 5213 9535 5215 9535 5214 9536 5215 9536 5216 9536 5216 9537 5215 9537 3685 9537 5216 9538 3685 9538 3921 9538 3947 9539 3949 9539 5200 9539 3947 9540 5200 9540 5217 9540 5217 9541 5200 9541 5202 9541 5217 9542 5202 9542 5218 9542 5218 9543 5202 9543 5204 9543 5218 9544 5204 9544 5219 9544 5219 9545 5204 9545 5206 9545 5219 9546 5206 9546 5220 9546 5220 9547 5206 9547 5208 9547 5220 9548 5208 9548 5221 9548 5221 9549 5208 9549 5210 9549 5221 9550 5210 9550 5222 9550 5222 9551 5210 9551 5212 9551 5222 9552 5212 9552 5223 9552 5223 9553 5212 9553 5214 9553 5223 9554 5214 9554 5224 9554 5224 9555 5214 9555 5216 9555 5224 9556 5216 9556 5225 9556 5225 9557 5216 9557 3921 9557 5225 9558 3921 9558 3920 9558 3945 9559 3947 9559 5217 9559 3945 9560 5217 9560 5226 9560 5226 9561 5217 9561 5218 9561 5226 9562 5218 9562 5227 9562 5227 9563 5218 9563 5219 9563 5227 9564 5219 9564 5228 9564 5228 9565 5219 9565 5220 9565 5228 9566 5220 9566 5229 9566 5229 9567 5220 9567 5221 9567 5229 9568 5221 9568 5230 9568 5230 9569 5221 9569 5222 9569 5230 9570 5222 9570 5231 9570 5231 9571 5222 9571 5223 9571 5231 9572 5223 9572 5232 9572 5232 9573 5223 9573 5224 9573 5232 9574 5224 9574 5233 9574 5233 9575 5224 9575 5225 9575 5233 9576 5225 9576 5234 9576 5234 9577 5225 9577 3920 9577 5234 9578 3920 9578 3919 9578 3943 9579 3945 9579 5226 9579 3943 9580 5226 9580 5235 9580 5235 9581 5226 9581 5227 9581 5235 9582 5227 9582 5236 9582 5236 9583 5227 9583 5228 9583 5236 9584 5228 9584 5237 9584 5237 9585 5228 9585 5229 9585 5237 9586 5229 9586 5238 9586 5238 9587 5229 9587 5230 9587 5238 9588 5230 9588 5239 9588 5239 9589 5230 9589 5231 9589 5239 9590 5231 9590 5240 9590 5240 9591 5231 9591 5232 9591 5240 9592 5232 9592 5241 9592 5241 9593 5232 9593 5233 9593 5241 9594 5233 9594 5242 9594 5242 9595 5233 9595 5234 9595 5242 9596 5234 9596 5243 9596 5243 9597 5234 9597 3919 9597 5243 9598 3919 9598 3918 9598 3941 9599 3943 9599 5235 9599 3941 9600 5235 9600 5244 9600 5244 9601 5235 9601 5236 9601 5244 9602 5236 9602 5245 9602 5245 9603 5236 9603 5237 9603 5245 9604 5237 9604 5246 9604 5246 9605 5237 9605 5238 9605 5246 9606 5238 9606 5247 9606 5247 9607 5238 9607 5239 9607 5247 9608 5239 9608 5248 9608 5248 9609 5239 9609 5240 9609 5248 9610 5240 9610 5249 9610 5249 9611 5240 9611 5241 9611 5249 9612 5241 9612 5250 9612 5250 9613 5241 9613 5242 9613 5250 9614 5242 9614 5251 9614 5251 9615 5242 9615 5243 9615 5251 9616 5243 9616 5252 9616 5252 9617 5243 9617 3918 9617 5252 9618 3918 9618 3917 9618 3939 9619 3941 9619 5244 9619 3939 9620 5244 9620 5253 9620 5253 9621 5244 9621 5245 9621 5253 9622 5245 9622 5254 9622 5254 9623 5245 9623 5246 9623 5254 9624 5246 9624 5255 9624 5255 9625 5246 9625 5247 9625 5255 9626 5247 9626 5256 9626 5256 9627 5247 9627 5248 9627 5256 9628 5248 9628 5257 9628 5257 9629 5248 9629 5249 9629 5257 9630 5249 9630 5258 9630 5258 9631 5249 9631 5250 9631 5258 9632 5250 9632 5259 9632 5259 9633 5250 9633 5251 9633 5259 9634 5251 9634 5260 9634 5260 9635 5251 9635 5252 9635 5260 9636 5252 9636 5261 9636 5261 9637 5252 9637 3917 9637 5261 9638 3917 9638 3916 9638 3937 9639 3939 9639 5253 9639 3937 9640 5253 9640 5262 9640 5262 9641 5253 9641 5254 9641 5262 9642 5254 9642 5263 9642 5263 9643 5254 9643 5255 9643 5263 9644 5255 9644 5264 9644 5264 9645 5255 9645 5256 9645 5264 9646 5256 9646 5265 9646 5265 9647 5256 9647 5257 9647 5265 9648 5257 9648 5266 9648 5266 9649 5257 9649 5258 9649 5266 9650 5258 9650 5267 9650 5267 9651 5258 9651 5259 9651 5267 9652 5259 9652 5268 9652 5268 9653 5259 9653 5260 9653 5268 9654 5260 9654 5269 9654 5269 9655 5260 9655 5261 9655 5269 9656 5261 9656 5270 9656 5270 9657 5261 9657 3916 9657 5270 9658 3916 9658 3915 9658 3935 9659 3937 9659 5262 9659 3935 9660 5262 9660 5271 9660 5271 9661 5262 9661 5263 9661 5271 9662 5263 9662 5272 9662 5272 9663 5263 9663 5264 9663 5272 9664 5264 9664 5273 9664 5273 9665 5264 9665 5265 9665 5273 9666 5265 9666 5274 9666 5274 9667 5265 9667 5266 9667 5274 9668 5266 9668 5275 9668 5275 9669 5266 9669 5267 9669 5275 9670 5267 9670 5276 9670 5276 9671 5267 9671 5268 9671 5276 9672 5268 9672 5277 9672 5277 9673 5268 9673 5269 9673 5277 9674 5269 9674 5278 9674 5278 9675 5269 9675 5270 9675 5278 9676 5270 9676 5279 9676 5279 9677 5270 9677 3915 9677 5279 9678 3915 9678 3914 9678 3933 9679 3935 9679 5271 9679 3933 9680 5271 9680 5280 9680 5280 9681 5271 9681 5272 9681 5280 9682 5272 9682 5281 9682 5281 9683 5272 9683 5273 9683 5281 9684 5273 9684 5282 9684 5282 9685 5273 9685 5274 9685 5282 9686 5274 9686 5283 9686 5283 9687 5274 9687 5275 9687 5283 9688 5275 9688 5284 9688 5284 9689 5275 9689 5276 9689 5284 9690 5276 9690 5285 9690 5285 9691 5276 9691 5277 9691 5285 9692 5277 9692 5286 9692 5286 9693 5277 9693 5278 9693 5286 9694 5278 9694 5287 9694 5287 9695 5278 9695 5279 9695 5287 9696 5279 9696 5288 9696 5288 9697 5279 9697 3914 9697 5288 9698 3914 9698 3913 9698 3931 9699 3933 9699 5280 9699 3931 9700 5280 9700 5289 9700 5289 9701 5280 9701 5281 9701 5289 9702 5281 9702 5290 9702 5290 9703 5281 9703 5282 9703 5290 9704 5282 9704 5291 9704 5291 9705 5282 9705 5283 9705 5291 9706 5283 9706 5292 9706 5292 9707 5283 9707 5284 9707 5292 9708 5284 9708 5293 9708 5293 9709 5284 9709 5285 9709 5293 9710 5285 9710 5294 9710 5294 9711 5285 9711 5286 9711 5294 9712 5286 9712 5295 9712 5295 9713 5286 9713 5287 9713 5295 9714 5287 9714 5296 9714 5296 9715 5287 9715 5288 9715 5296 9716 5288 9716 5297 9716 5297 9717 5288 9717 3913 9717 5297 9718 3913 9718 3912 9718 3928 9719 3931 9719 5289 9719 3928 9720 5289 9720 5298 9720 5298 9721 5289 9721 5290 9721 5298 9722 5290 9722 5299 9722 5299 9723 5290 9723 5291 9723 5299 9724 5291 9724 5300 9724 5300 9725 5291 9725 5292 9725 5300 9726 5292 9726 5301 9726 5301 9727 5292 9727 5293 9727 5301 9728 5293 9728 5302 9728 5302 9729 5293 9729 5294 9729 5302 9730 5294 9730 5303 9730 5303 9731 5294 9731 5295 9731 5303 9732 5295 9732 5304 9732 5304 9733 5295 9733 5296 9733 5304 9734 5296 9734 5305 9734 5305 9735 5296 9735 5297 9735 5305 9736 5297 9736 5306 9736 5306 9737 5297 9737 3912 9737 5306 9738 3912 9738 3911 9738 3929 9739 3928 9739 5298 9739 3929 9740 5298 9740 5307 9740 5307 9741 5298 9741 5299 9741 5307 9742 5299 9742 5308 9742 5308 9743 5299 9743 5300 9743 5308 9744 5300 9744 5309 9744 5309 9745 5300 9745 5301 9745 5309 9746 5301 9746 5310 9746 5310 9747 5301 9747 5302 9747 5310 9748 5302 9748 5311 9748 5311 9749 5302 9749 5303 9749 5311 9750 5303 9750 5312 9750 5312 9751 5303 9751 5304 9751 5312 9752 5304 9752 5313 9752 5313 9753 5304 9753 5305 9753 5313 9754 5305 9754 5314 9754 5314 9755 5305 9755 5306 9755 5314 9756 5306 9756 5315 9756 5315 9757 5306 9757 3911 9757 5315 9758 3911 9758 3910 9758 5316 9759 3929 9759 5307 9759 5316 9760 5307 9760 5317 9760 5317 9761 5307 9761 5308 9761 5317 9762 5308 9762 5318 9762 5318 9763 5308 9763 5309 9763 5318 9764 5309 9764 5319 9764 5319 9765 5309 9765 5310 9765 5319 9766 5310 9766 5320 9766 5320 9767 5310 9767 5311 9767 5320 9768 5311 9768 5321 9768 5321 9769 5311 9769 5312 9769 5321 9770 5312 9770 5322 9770 5322 9771 5312 9771 5313 9771 5322 9772 5313 9772 5323 9772 5323 9773 5313 9773 5314 9773 5323 9774 5314 9774 5324 9774 5324 9775 5314 9775 5315 9775 5324 9776 5315 9776 5325 9776 5325 9777 5315 9777 3910 9777 5325 9778 3910 9778 3909 9778 3924 9779 5316 9779 5317 9779 3924 9780 5317 9780 5326 9780 5326 9781 5317 9781 5318 9781 5326 9782 5318 9782 5327 9782 5327 9783 5318 9783 5319 9783 5327 9784 5319 9784 5328 9784 5328 9785 5319 9785 5320 9785 5328 9786 5320 9786 5329 9786 5329 9787 5320 9787 5321 9787 5329 9788 5321 9788 5330 9788 5330 9789 5321 9789 5322 9789 5330 9790 5322 9790 5331 9790 5331 9791 5322 9791 5323 9791 5331 9792 5323 9792 5332 9792 5332 9793 5323 9793 5324 9793 5332 9794 5324 9794 5333 9794 5333 9795 5324 9795 5325 9795 5333 9796 5325 9796 5334 9796 5334 9797 5325 9797 3909 9797 5334 9798 3909 9798 3908 9798 3925 9799 3924 9799 5326 9799 3925 9800 5326 9800 5335 9800 5335 9801 5326 9801 5327 9801 5335 9802 5327 9802 5336 9802 5336 9803 5327 9803 5328 9803 5336 9804 5328 9804 5337 9804 5337 9805 5328 9805 5329 9805 5337 9806 5329 9806 5338 9806 5338 9807 5329 9807 5330 9807 5338 9808 5330 9808 5339 9808 5339 9809 5330 9809 5331 9809 5339 9810 5331 9810 5340 9810 5340 9811 5331 9811 5332 9811 5340 9812 5332 9812 5341 9812 5341 9813 5332 9813 5333 9813 5341 9814 5333 9814 5342 9814 5342 9815 5333 9815 5334 9815 5342 9816 5334 9816 5343 9816 5343 9817 5334 9817 3908 9817 5343 9818 3908 9818 3907 9818 5344 9819 3925 9819 5335 9819 5344 9820 5335 9820 5345 9820 5345 9821 5335 9821 5336 9821 5345 9822 5336 9822 5346 9822 5346 9823 5336 9823 5337 9823 5346 9824 5337 9824 5347 9824 5347 9825 5337 9825 5338 9825 5347 9826 5338 9826 5348 9826 5348 9827 5338 9827 5339 9827 5348 9828 5339 9828 5349 9828 5349 9829 5339 9829 5340 9829 5349 9830 5340 9830 5350 9830 5350 9831 5340 9831 5341 9831 5350 9832 5341 9832 5351 9832 5351 9833 5341 9833 5342 9833 5351 9834 5342 9834 5352 9834 5352 9835 5342 9835 5343 9835 5352 9836 5343 9836 5353 9836 5353 9837 5343 9837 3907 9837 5353 9838 3907 9838 3906 9838 5354 9839 5346 9839 5347 9839 5354 9840 5347 9840 5355 9840 5355 9841 5347 9841 5348 9841 5355 9842 5348 9842 5356 9842 5356 9843 5348 9843 5349 9843 5356 9844 5349 9844 5357 9844 5357 9845 5349 9845 5350 9845 5357 9846 5350 9846 5358 9846 5358 9847 5350 9847 5351 9847 5358 9848 5351 9848 5359 9848 5359 9849 5351 9849 5352 9849 5359 9850 5352 9850 5360 9850 5360 9851 5352 9851 5353 9851 5360 9852 5353 9852 5361 9852 5361 9853 5353 9853 3906 9853 5361 9854 3906 9854 3905 9854 5362 9855 5355 9855 5356 9855 5362 9856 5356 9856 5363 9856 5363 9857 5356 9857 5357 9857 5363 9858 5357 9858 5364 9858 5364 9859 5357 9859 5358 9859 5364 9860 5358 9860 5365 9860 5365 9861 5358 9861 5359 9861 5365 9862 5359 9862 5366 9862 5366 9863 5359 9863 5360 9863 5366 9864 5360 9864 5367 9864 5367 9865 5360 9865 5361 9865 5367 9866 5361 9866 5368 9866 5368 9867 5361 9867 3905 9867 5368 9868 3905 9868 3904 9868 5369 9869 5363 9869 5364 9869 5369 9870 5364 9870 5370 9870 5370 9871 5364 9871 5365 9871 5370 9872 5365 9872 5371 9872 5371 9873 5365 9873 5366 9873 5371 9874 5366 9874 5372 9874 5372 9875 5366 9875 5367 9875 5372 9876 5367 9876 5373 9876 5373 9877 5367 9877 5368 9877 5373 9878 5368 9878 5374 9878 5374 9879 5368 9879 3904 9879 5374 9880 3904 9880 3903 9880 5375 9881 5370 9881 5371 9881 5375 9882 5371 9882 5376 9882 5376 9883 5371 9883 5372 9883 5376 9884 5372 9884 5377 9884 5377 9885 5372 9885 5373 9885 5377 9886 5373 9886 5378 9886 5378 9887 5373 9887 5374 9887 5378 9888 5374 9888 5379 9888 5379 9889 5374 9889 3903 9889 5379 9890 3903 9890 3667 9890 3603 9891 3731 9891 5380 9891 3603 9892 5380 9892 5381 9892 5381 9893 5380 9893 5382 9893 5381 9894 5382 9894 5383 9894 5383 9895 5382 9895 5384 9895 5383 9896 5384 9896 5385 9896 5385 9897 5384 9897 5386 9897 5385 9898 5386 9898 5387 9898 5387 9899 5386 9899 5388 9899 5387 9900 5388 9900 5389 9900 5389 9901 5388 9901 5390 9901 5389 9902 5390 9902 5391 9902 5391 9903 5390 9903 5392 9903 5391 9904 5392 9904 5393 9904 5393 9905 5392 9905 5394 9905 5393 9906 5394 9906 5395 9906 5395 9907 5394 9907 5396 9907 5395 9908 5396 9908 5397 9908 5397 9909 5396 9909 3728 9909 5397 9910 3728 9910 3605 9910 3684 9911 3683 9911 5398 9911 3684 9912 5398 9912 5199 9912 5199 9913 5398 9913 5399 9913 5199 9914 5399 9914 5201 9914 5201 9915 5399 9915 5400 9915 5201 9916 5400 9916 5203 9916 5203 9917 5400 9917 5401 9917 5203 9918 5401 9918 5205 9918 5205 9919 5401 9919 5402 9919 5205 9920 5402 9920 5207 9920 5207 9921 5402 9921 5403 9921 5207 9922 5403 9922 5209 9922 5209 9923 5403 9923 5404 9923 5209 9924 5404 9924 5211 9924 5211 9925 5404 9925 5405 9925 5211 9926 5405 9926 5213 9926 5213 9927 5405 9927 5406 9927 5213 9928 5406 9928 5215 9928 5215 9929 5406 9929 3686 9929 5215 9930 3686 9930 3685 9930 5376 9931 5377 9931 5407 9931 5376 9932 5407 9932 5408 9932 5377 9933 5378 9933 5409 9933 5377 9934 5409 9934 5407 9934 5378 9935 5379 9935 5410 9935 5378 9936 5410 9936 5409 9936 5379 9937 3667 9937 3669 9937 5379 9938 3669 9938 5410 9938 3631 9939 5033 9939 3669 9939 3631 9940 3669 9940 3632 9940 5033 9941 5035 9941 5410 9941 5033 9942 5410 9942 3669 9942 5035 9943 5037 9943 5409 9943 5035 9944 5409 9944 5410 9944 5037 9945 5039 9945 5407 9945 5037 9946 5407 9946 5409 9946 5039 9947 5041 9947 5408 9947 5039 9948 5408 9948 5407 9948 3603 9949 5381 9949 5190 9949 3603 9950 5190 9950 3604 9950 5381 9951 5383 9951 5191 9951 5381 9952 5191 9952 5190 9952 5383 9953 5385 9953 5192 9953 5383 9954 5192 9954 5191 9954 5385 9955 5387 9955 5193 9955 5385 9956 5193 9956 5192 9956 5387 9957 5389 9957 5194 9957 5387 9958 5194 9958 5193 9958 5389 9959 5391 9959 5195 9959 5389 9960 5195 9960 5194 9960 5391 9961 5393 9961 5196 9961 5391 9962 5196 9962 5195 9962 5393 9963 5395 9963 5197 9963 5393 9964 5197 9964 5196 9964 5395 9965 5397 9965 5198 9965 5395 9966 5198 9966 5197 9966 5397 9967 3605 9967 3608 9967 5397 9968 3608 9968 5198 9968 5411 9969 5412 9969 5413 9969 5411 9970 5413 9970 5414 9970 5412 9971 5415 9971 5416 9971 5412 9972 5416 9972 5413 9972 5415 9973 5417 9973 5418 9973 5415 9974 5418 9974 5416 9974 5417 9975 5419 9975 5420 9975 5417 9976 5420 9976 5418 9976 5419 9977 5421 9977 5422 9977 5419 9978 5422 9978 5420 9978 5421 9979 4794 9979 3633 9979 5421 9980 3633 9980 5422 9980 5423 9981 5424 9981 5415 9981 5423 9982 5415 9982 5412 9982 5424 9983 5425 9983 5417 9983 5424 9984 5417 9984 5415 9984 5425 9985 5426 9985 5419 9985 5425 9986 5419 9986 5417 9986 5426 9987 5427 9987 5421 9987 5426 9988 5421 9988 5419 9988 5427 9989 4793 9989 4794 9989 5427 9990 4794 9990 5421 9990 5428 9991 5429 9991 5426 9991 5428 9992 5426 9992 5425 9992 5429 9993 5430 9993 5427 9993 5429 9994 5427 9994 5426 9994 5430 9995 4792 9995 4793 9995 5430 9996 4793 9996 5427 9996 5431 9997 5432 9997 5430 9997 5431 9998 5430 9998 5429 9998 5432 9999 4791 9999 4792 9999 5432 10000 4792 10000 5430 10000 5433 10001 5434 10001 5432 10001 5433 10002 5432 10002 5431 10002 5434 10003 4790 10003 4791 10003 5434 10004 4791 10004 5432 10004 5435 10005 5436 10005 5434 10005 5435 10006 5434 10006 5433 10006 5436 10007 4789 10007 4790 10007 5436 10008 4790 10008 5434 10008 5437 10009 4788 10009 4789 10009 5437 10010 4789 10010 5436 10010 4813 10011 5438 10011 5439 10011 4813 10012 5439 10012 4815 10012 5438 10013 5440 10013 5441 10013 5438 10014 5441 10014 5439 10014 4811 10015 5442 10015 5438 10015 4811 10016 5438 10016 4813 10016 5442 10017 5443 10017 5440 10017 5442 10018 5440 10018 5438 10018 5443 10019 5444 10019 5445 10019 5443 10020 5445 10020 5440 10020 5444 10021 5446 10021 5447 10021 5444 10022 5447 10022 5445 10022 5446 10023 5448 10023 5449 10023 5446 10024 5449 10024 5447 10024 4809 10025 5450 10025 5442 10025 4809 10026 5442 10026 4811 10026 5450 10027 5451 10027 5443 10027 5450 10028 5443 10028 5442 10028 5451 10029 5452 10029 5444 10029 5451 10030 5444 10030 5443 10030 5452 10031 5453 10031 5446 10031 5452 10032 5446 10032 5444 10032 5453 10033 5454 10033 5448 10033 5453 10034 5448 10034 5446 10034 5454 10035 5455 10035 5456 10035 5454 10036 5456 10036 5448 10036 5455 10037 5457 10037 5458 10037 5455 10038 5458 10038 5456 10038 4807 10039 5459 10039 5450 10039 4807 10040 5450 10040 4809 10040 5459 10041 5460 10041 5451 10041 5459 10042 5451 10042 5450 10042 5460 10043 5461 10043 5452 10043 5460 10044 5452 10044 5451 10044 5461 10045 5462 10045 5453 10045 5461 10046 5453 10046 5452 10046 5462 10047 5463 10047 5454 10047 5462 10048 5454 10048 5453 10048 5463 10049 5464 10049 5455 10049 5463 10050 5455 10050 5454 10050 5464 10051 5465 10051 5457 10051 5464 10052 5457 10052 5455 10052 5465 10053 5466 10053 5467 10053 5465 10054 5467 10054 5457 10054 4805 10055 5468 10055 5459 10055 4805 10056 5459 10056 4807 10056 5468 10057 5469 10057 5460 10057 5468 10058 5460 10058 5459 10058 5469 10059 5470 10059 5461 10059 5469 10060 5461 10060 5460 10060 5470 10061 5471 10061 5462 10061 5470 10062 5462 10062 5461 10062 5471 10063 5472 10063 5463 10063 5471 10064 5463 10064 5462 10064 5472 10065 5473 10065 5464 10065 5472 10066 5464 10066 5463 10066 5473 10067 5474 10067 5465 10067 5473 10068 5465 10068 5464 10068 5474 10069 5475 10069 5466 10069 5474 10070 5466 10070 5465 10070 5475 10071 5476 10071 5477 10071 5475 10072 5477 10072 5466 10072 4803 10073 5478 10073 5468 10073 4803 10074 5468 10074 4805 10074 5478 10075 5479 10075 5469 10075 5478 10076 5469 10076 5468 10076 5479 10077 5480 10077 5470 10077 5479 10078 5470 10078 5469 10078 5480 10079 5481 10079 5471 10079 5480 10080 5471 10080 5470 10080 5481 10081 5482 10081 5472 10081 5481 10082 5472 10082 5471 10082 5482 10083 5483 10083 5473 10083 5482 10084 5473 10084 5472 10084 5483 10085 5484 10085 5474 10085 5483 10086 5474 10086 5473 10086 5484 10087 5485 10087 5475 10087 5484 10088 5475 10088 5474 10088 5485 10089 5486 10089 5476 10089 5485 10090 5476 10090 5475 10090 4801 10091 5487 10091 5478 10091 4801 10092 5478 10092 4803 10092 5487 10093 5488 10093 5479 10093 5487 10094 5479 10094 5478 10094 5488 10095 5489 10095 5480 10095 5488 10096 5480 10096 5479 10096 5489 10097 5490 10097 5481 10097 5489 10098 5481 10098 5480 10098 5490 10099 5491 10099 5482 10099 5490 10100 5482 10100 5481 10100 5491 10101 5492 10101 5483 10101 5491 10102 5483 10102 5482 10102 5492 10103 5493 10103 5484 10103 5492 10104 5484 10104 5483 10104 5493 10105 5494 10105 5485 10105 5493 10106 5485 10106 5484 10106 5494 10107 5495 10107 5486 10107 5494 10108 5486 10108 5485 10108 4799 10109 5496 10109 5487 10109 4799 10110 5487 10110 4801 10110 5496 10111 5497 10111 5488 10111 5496 10112 5488 10112 5487 10112 5497 10113 5498 10113 5489 10113 5497 10114 5489 10114 5488 10114 5498 10115 5499 10115 5490 10115 5498 10116 5490 10116 5489 10116 5499 10117 5500 10117 5491 10117 5499 10118 5491 10118 5490 10118 5500 10119 5501 10119 5492 10119 5500 10120 5492 10120 5491 10120 5501 10121 5502 10121 5493 10121 5501 10122 5493 10122 5492 10122 5502 10123 5503 10123 5494 10123 5502 10124 5494 10124 5493 10124 4797 10125 5504 10125 5496 10125 4797 10126 5496 10126 4799 10126 5504 10127 5505 10127 5497 10127 5504 10128 5497 10128 5496 10128 5505 10129 5506 10129 5498 10129 5505 10130 5498 10130 5497 10130 5506 10131 5507 10131 5499 10131 5506 10132 5499 10132 5498 10132 5507 10133 5508 10133 5500 10133 5507 10134 5500 10134 5499 10134 5508 10135 5509 10135 5501 10135 5508 10136 5501 10136 5500 10136 5509 10137 5510 10137 5502 10137 5509 10138 5502 10138 5501 10138 5510 10139 5511 10139 5503 10139 5510 10140 5503 10140 5502 10140 4795 10141 5512 10141 5504 10141 4795 10142 5504 10142 4797 10142 5512 10143 5513 10143 5505 10143 5512 10144 5505 10144 5504 10144 5513 10145 5514 10145 5506 10145 5513 10146 5506 10146 5505 10146 5514 10147 5515 10147 5507 10147 5514 10148 5507 10148 5506 10148 5515 10149 5516 10149 5508 10149 5515 10150 5508 10150 5507 10150 5516 10151 5517 10151 5509 10151 5516 10152 5509 10152 5508 10152 5517 10153 5518 10153 5510 10153 5517 10154 5510 10154 5509 10154 5518 10155 5519 10155 5511 10155 5518 10156 5511 10156 5510 10156 3607 10157 5520 10157 5512 10157 3607 10158 5512 10158 4795 10158 5520 10159 5521 10159 5513 10159 5520 10160 5513 10160 5512 10160 5521 10161 5522 10161 5514 10161 5521 10162 5514 10162 5513 10162 5522 10163 5523 10163 5515 10163 5522 10164 5515 10164 5514 10164 5523 10165 5524 10165 5516 10165 5523 10166 5516 10166 5515 10166 5524 10167 5525 10167 5517 10167 5524 10168 5517 10168 5516 10168 5525 10169 5526 10169 5518 10169 5525 10170 5518 10170 5517 10170 5526 10171 5527 10171 5519 10171 5526 10172 5519 10172 5518 10172 3987 10173 3680 10173 5528 10173 3987 10174 5528 10174 5529 10174 5529 10175 5528 10175 5530 10175 5529 10176 5530 10176 5531 10176 5531 10177 5530 10177 5532 10177 5531 10178 5532 10178 5533 10178 5533 10179 5532 10179 5534 10179 5533 10180 5534 10180 5535 10180 5535 10181 5534 10181 5536 10181 5535 10182 5536 10182 5537 10182 5537 10183 5536 10183 5538 10183 5537 10184 5538 10184 5539 10184 5539 10185 5538 10185 5540 10185 5539 10186 5540 10186 5541 10186 5541 10187 5540 10187 5542 10187 5541 10188 5542 10188 5543 10188 5543 10189 5542 10189 5544 10189 5543 10190 5544 10190 5545 10190 5545 10191 5544 10191 3681 10191 5545 10192 3681 10192 3948 10192 3985 10193 3987 10193 5529 10193 3985 10194 5529 10194 5546 10194 5546 10195 5529 10195 5531 10195 5546 10196 5531 10196 5547 10196 5547 10197 5531 10197 5533 10197 5547 10198 5533 10198 5548 10198 5548 10199 5533 10199 5535 10199 5548 10200 5535 10200 5549 10200 5549 10201 5535 10201 5537 10201 5549 10202 5537 10202 5550 10202 5550 10203 5537 10203 5539 10203 5550 10204 5539 10204 5551 10204 5551 10205 5539 10205 5541 10205 5551 10206 5541 10206 5552 10206 5552 10207 5541 10207 5543 10207 5552 10208 5543 10208 5553 10208 5553 10209 5543 10209 5545 10209 5553 10210 5545 10210 5554 10210 5554 10211 5545 10211 3948 10211 5554 10212 3948 10212 3946 10212 3983 10213 3985 10213 5546 10213 3983 10214 5546 10214 5555 10214 5555 10215 5546 10215 5547 10215 5555 10216 5547 10216 5556 10216 5556 10217 5547 10217 5548 10217 5556 10218 5548 10218 5557 10218 5557 10219 5548 10219 5549 10219 5557 10220 5549 10220 5558 10220 5558 10221 5549 10221 5550 10221 5558 10222 5550 10222 5559 10222 5559 10223 5550 10223 5551 10223 5559 10224 5551 10224 5560 10224 5560 10225 5551 10225 5552 10225 5560 10226 5552 10226 5561 10226 5561 10227 5552 10227 5553 10227 5561 10228 5553 10228 5562 10228 5562 10229 5553 10229 5554 10229 5562 10230 5554 10230 5563 10230 5563 10231 5554 10231 3946 10231 5563 10232 3946 10232 3944 10232 3981 10233 3983 10233 5555 10233 3981 10234 5555 10234 5564 10234 5564 10235 5555 10235 5556 10235 5564 10236 5556 10236 5565 10236 5565 10237 5556 10237 5557 10237 5565 10238 5557 10238 5566 10238 5566 10239 5557 10239 5558 10239 5566 10240 5558 10240 5567 10240 5567 10241 5558 10241 5559 10241 5567 10242 5559 10242 5568 10242 5568 10243 5559 10243 5560 10243 5568 10244 5560 10244 5569 10244 5569 10245 5560 10245 5561 10245 5569 10246 5561 10246 5570 10246 5570 10247 5561 10247 5562 10247 5570 10248 5562 10248 5571 10248 5571 10249 5562 10249 5563 10249 5571 10250 5563 10250 5572 10250 5572 10251 5563 10251 3944 10251 5572 10252 3944 10252 3942 10252 3979 10253 3981 10253 5564 10253 3979 10254 5564 10254 5573 10254 5573 10255 5564 10255 5565 10255 5573 10256 5565 10256 5574 10256 5574 10257 5565 10257 5566 10257 5574 10258 5566 10258 5575 10258 5575 10259 5566 10259 5567 10259 5575 10260 5567 10260 5576 10260 5576 10261 5567 10261 5568 10261 5576 10262 5568 10262 5577 10262 5577 10263 5568 10263 5569 10263 5577 10264 5569 10264 5578 10264 5578 10265 5569 10265 5570 10265 5578 10266 5570 10266 5579 10266 5579 10267 5570 10267 5571 10267 5579 10268 5571 10268 5580 10268 5580 10269 5571 10269 5572 10269 5580 10270 5572 10270 5581 10270 5581 10271 5572 10271 3942 10271 5581 10272 3942 10272 3940 10272 3977 10273 3979 10273 5573 10273 3977 10274 5573 10274 5582 10274 5582 10275 5573 10275 5574 10275 5582 10276 5574 10276 5583 10276 5583 10277 5574 10277 5575 10277 5583 10278 5575 10278 5584 10278 5584 10279 5575 10279 5576 10279 5584 10280 5576 10280 5585 10280 5585 10281 5576 10281 5577 10281 5585 10282 5577 10282 5586 10282 5586 10283 5577 10283 5578 10283 5586 10284 5578 10284 5587 10284 5587 10285 5578 10285 5579 10285 5587 10286 5579 10286 5588 10286 5588 10287 5579 10287 5580 10287 5588 10288 5580 10288 5589 10288 5589 10289 5580 10289 5581 10289 5589 10290 5581 10290 5590 10290 5590 10291 5581 10291 3940 10291 5590 10292 3940 10292 3938 10292 3975 10293 3977 10293 5582 10293 3975 10294 5582 10294 5591 10294 5591 10295 5582 10295 5583 10295 5591 10296 5583 10296 5592 10296 5592 10297 5583 10297 5584 10297 5592 10298 5584 10298 5593 10298 5593 10299 5584 10299 5585 10299 5593 10300 5585 10300 5594 10300 5594 10301 5585 10301 5586 10301 5594 10302 5586 10302 5595 10302 5595 10303 5586 10303 5587 10303 5595 10304 5587 10304 5596 10304 5596 10305 5587 10305 5588 10305 5596 10306 5588 10306 5597 10306 5597 10307 5588 10307 5589 10307 5597 10308 5589 10308 5598 10308 5598 10309 5589 10309 5590 10309 5598 10310 5590 10310 5599 10310 5599 10311 5590 10311 3938 10311 5599 10312 3938 10312 3936 10312 3973 10313 3975 10313 5591 10313 3973 10314 5591 10314 5600 10314 5600 10315 5591 10315 5592 10315 5600 10316 5592 10316 5601 10316 5601 10317 5592 10317 5593 10317 5601 10318 5593 10318 5602 10318 5602 10319 5593 10319 5594 10319 5602 10320 5594 10320 5603 10320 5603 10321 5594 10321 5595 10321 5603 10322 5595 10322 5604 10322 5604 10323 5595 10323 5596 10323 5604 10324 5596 10324 5605 10324 5605 10325 5596 10325 5597 10325 5605 10326 5597 10326 5606 10326 5606 10327 5597 10327 5598 10327 5606 10328 5598 10328 5607 10328 5607 10329 5598 10329 5599 10329 5607 10330 5599 10330 5608 10330 5608 10331 5599 10331 3936 10331 5608 10332 3936 10332 3934 10332 3971 10333 3973 10333 5600 10333 3971 10334 5600 10334 5609 10334 5609 10335 5600 10335 5601 10335 5609 10336 5601 10336 5610 10336 5610 10337 5601 10337 5602 10337 5610 10338 5602 10338 5611 10338 5611 10339 5602 10339 5603 10339 5611 10340 5603 10340 5612 10340 5612 10341 5603 10341 5604 10341 5612 10342 5604 10342 5613 10342 5613 10343 5604 10343 5605 10343 5613 10344 5605 10344 5614 10344 5614 10345 5605 10345 5606 10345 5614 10346 5606 10346 5615 10346 5615 10347 5606 10347 5607 10347 5615 10348 5607 10348 5616 10348 5616 10349 5607 10349 5608 10349 5616 10350 5608 10350 5617 10350 5617 10351 5608 10351 3934 10351 5617 10352 3934 10352 3932 10352 3969 10353 3971 10353 5609 10353 3969 10354 5609 10354 5618 10354 5618 10355 5609 10355 5610 10355 5618 10356 5610 10356 5619 10356 5619 10357 5610 10357 5611 10357 5619 10358 5611 10358 5620 10358 5620 10359 5611 10359 5612 10359 5620 10360 5612 10360 5621 10360 5621 10361 5612 10361 5613 10361 5621 10362 5613 10362 5622 10362 5622 10363 5613 10363 5614 10363 5622 10364 5614 10364 5623 10364 5623 10365 5614 10365 5615 10365 5623 10366 5615 10366 5624 10366 5624 10367 5615 10367 5616 10367 5624 10368 5616 10368 5625 10368 5625 10369 5616 10369 5617 10369 5625 10370 5617 10370 5626 10370 5626 10371 5617 10371 3932 10371 5626 10372 3932 10372 3930 10372 3967 10373 3969 10373 5618 10373 3967 10374 5618 10374 5627 10374 5627 10375 5618 10375 5619 10375 5627 10376 5619 10376 5628 10376 5628 10377 5619 10377 5620 10377 5628 10378 5620 10378 5629 10378 5629 10379 5620 10379 5621 10379 5629 10380 5621 10380 5630 10380 5630 10381 5621 10381 5622 10381 5630 10382 5622 10382 5631 10382 5631 10383 5622 10383 5623 10383 5631 10384 5623 10384 5632 10384 5632 10385 5623 10385 5624 10385 5632 10386 5624 10386 5633 10386 5633 10387 5624 10387 5625 10387 5633 10388 5625 10388 5634 10388 5634 10389 5625 10389 5626 10389 5634 10390 5626 10390 5635 10390 5635 10391 5626 10391 3930 10391 5635 10392 3930 10392 3927 10392 3965 10393 3967 10393 5627 10393 3965 10394 5627 10394 5636 10394 5636 10395 5627 10395 5628 10395 5636 10396 5628 10396 5637 10396 5637 10397 5628 10397 5629 10397 5637 10398 5629 10398 5638 10398 5638 10399 5629 10399 5630 10399 5638 10400 5630 10400 5639 10400 5639 10401 5630 10401 5631 10401 5639 10402 5631 10402 5640 10402 5640 10403 5631 10403 5632 10403 5640 10404 5632 10404 5641 10404 5641 10405 5632 10405 5633 10405 5641 10406 5633 10406 5642 10406 5642 10407 5633 10407 5634 10407 5642 10408 5634 10408 5643 10408 5643 10409 5634 10409 5635 10409 5643 10410 5635 10410 5644 10410 5644 10411 5635 10411 3927 10411 5644 10412 3927 10412 3926 10412 3963 10413 3965 10413 5636 10413 3963 10414 5636 10414 5645 10414 5645 10415 5636 10415 5637 10415 5645 10416 5637 10416 5646 10416 5646 10417 5637 10417 5638 10417 5646 10418 5638 10418 5647 10418 5647 10419 5638 10419 5639 10419 5647 10420 5639 10420 5648 10420 5648 10421 5639 10421 5640 10421 5648 10422 5640 10422 5649 10422 5649 10423 5640 10423 5641 10423 5649 10424 5641 10424 5650 10424 5650 10425 5641 10425 5642 10425 5650 10426 5642 10426 5651 10426 5651 10427 5642 10427 5643 10427 5651 10428 5643 10428 5652 10428 3961 10429 3963 10429 5645 10429 3961 10430 5645 10430 5653 10430 5653 10431 5645 10431 5646 10431 5653 10432 5646 10432 5654 10432 5654 10433 5646 10433 5647 10433 5654 10434 5647 10434 5655 10434 5655 10435 5647 10435 5648 10435 5655 10436 5648 10436 5656 10436 5656 10437 5648 10437 5649 10437 5656 10438 5649 10438 5657 10438 5657 10439 5649 10439 5650 10439 5657 10440 5650 10440 5658 10440 5658 10441 5650 10441 5651 10441 5658 10442 5651 10442 5659 10442 3959 10443 3961 10443 5653 10443 3959 10444 5653 10444 5660 10444 5660 10445 5653 10445 5654 10445 5660 10446 5654 10446 5661 10446 5661 10447 5654 10447 5655 10447 5661 10448 5655 10448 5662 10448 5662 10449 5655 10449 5656 10449 5662 10450 5656 10450 5663 10450 5663 10451 5656 10451 5657 10451 5663 10452 5657 10452 5664 10452 3957 10453 3959 10453 5660 10453 3957 10454 5660 10454 5665 10454 5665 10455 5660 10455 5661 10455 5665 10456 5661 10456 5666 10456 5666 10457 5661 10457 5662 10457 5666 10458 5662 10458 5667 10458 3955 10459 3957 10459 5665 10459 3955 10460 5665 10460 5668 10460 5668 10461 5665 10461 5666 10461 5668 10462 5666 10462 5669 10462 3953 10463 3955 10463 5668 10463 3953 10464 5668 10464 5670 10464 5670 10465 5668 10465 5669 10465 5670 10466 5669 10466 5671 10466 3951 10467 3953 10467 5670 10467 3951 10468 5670 10468 5672 10468 5672 10469 5670 10469 5671 10469 5672 10470 5671 10470 5673 10470 3666 10471 3951 10471 5672 10471 3666 10472 5672 10472 5674 10472 5674 10473 5672 10473 5673 10473 5674 10474 5673 10474 5675 10474 5675 10475 5673 10475 5676 10475 5675 10476 5676 10476 5677 10476 3606 10477 3729 10477 5678 10477 3606 10478 5678 10478 5679 10478 5679 10479 5678 10479 5680 10479 5679 10480 5680 10480 5681 10480 5681 10481 5680 10481 5682 10481 5681 10482 5682 10482 5683 10482 5683 10483 5682 10483 5684 10483 5683 10484 5684 10484 5685 10484 5685 10485 5684 10485 5686 10485 5685 10486 5686 10486 5687 10486 5687 10487 5686 10487 5688 10487 5687 10488 5688 10488 5689 10488 5689 10489 5688 10489 5690 10489 5689 10490 5690 10490 5691 10490 3680 10491 3679 10491 5692 10491 3680 10492 5692 10492 5528 10492 5528 10493 5692 10493 5693 10493 5528 10494 5693 10494 5530 10494 5530 10495 5693 10495 5694 10495 5530 10496 5694 10496 5532 10496 5532 10497 5694 10497 5695 10497 5532 10498 5695 10498 5534 10498 5534 10499 5695 10499 5696 10499 5534 10500 5696 10500 5536 10500 5536 10501 5696 10501 5697 10501 5536 10502 5697 10502 5538 10502 5538 10503 5697 10503 5698 10503 5538 10504 5698 10504 5540 10504 5540 10505 5698 10505 5699 10505 5540 10506 5699 10506 5542 10506 5542 10507 5699 10507 5700 10507 5542 10508 5700 10508 5544 10508 5544 10509 5700 10509 3682 10509 5544 10510 3682 10510 3681 10510 3666 10511 5674 10511 3636 10511 3666 10512 3636 10512 3635 10512 5674 10513 5675 10513 5701 10513 5674 10514 5701 10514 3636 10514 5675 10515 5677 10515 5702 10515 5675 10516 5702 10516 5701 10516 5677 10517 5703 10517 5704 10517 5677 10518 5704 10518 5702 10518 5703 10519 5705 10519 5706 10519 5703 10520 5706 10520 5704 10520 5707 10521 5414 10521 5708 10521 5707 10522 5708 10522 5709 10522 5414 10523 5413 10523 5710 10523 5414 10524 5710 10524 5708 10524 5413 10525 5416 10525 5706 10525 5413 10526 5706 10526 5710 10526 5416 10527 5418 10527 5704 10527 5416 10528 5704 10528 5706 10528 5418 10529 5420 10529 5702 10529 5418 10530 5702 10530 5704 10530 5420 10531 5422 10531 5701 10531 5420 10532 5701 10532 5702 10532 5422 10533 3633 10533 3636 10533 5422 10534 3636 10534 5701 10534 3606 10535 5679 10535 5520 10535 3606 10536 5520 10536 3607 10536 5679 10537 5681 10537 5521 10537 5679 10538 5521 10538 5520 10538 5681 10539 5683 10539 5522 10539 5681 10540 5522 10540 5521 10540 5683 10541 5685 10541 5523 10541 5683 10542 5523 10542 5522 10542 5685 10543 5687 10543 5524 10543 5685 10544 5524 10544 5523 10544 5687 10545 5689 10545 5525 10545 5687 10546 5525 10546 5524 10546 5689 10547 5691 10547 5526 10547 5689 10548 5526 10548 5525 10548 5691 10549 5711 10549 5527 10549 5691 10550 5527 10550 5526 10550 4081 10551 4091 10551 4075 10551 4111 10552 4068 10552 4075 10552 4111 10553 4075 10553 4091 10553 4113 10554 4060 10554 4068 10554 4113 10555 4068 10555 4111 10555 4115 10556 4049 10556 4060 10556 4115 10557 4060 10557 4113 10557 5712 10558 5713 10558 4049 10558 5712 10559 4049 10559 5030 10559 4114 10560 4451 10560 4426 10560 4424 10561 4423 10561 4114 10561 4424 10562 4114 10562 4426 10562 4060 10563 4049 10563 4059 10563 4115 10564 4114 10564 4423 10564 5714 10565 5029 10565 5715 10565 5716 10566 5713 10566 4049 10566 4115 10567 4049 10567 5717 10567 4049 10568 5716 10568 5717 10568 4002 10569 4023 10569 4003 10569 5716 10570 5718 10570 5713 10570 5719 10571 5715 10571 5714 10571 5719 10572 5714 10572 5720 10572 4484 10573 4483 10573 4464 10573 4484 10574 4464 10574 4465 10574 4486 10575 4485 10575 4466 10575 4486 10576 4466 10576 4467 10576 4446 10577 4467 10577 4466 10577 4446 10578 4466 10578 4445 10578 4776 10579 5721 10579 5722 10579 4776 10580 5722 10580 3639 10580 4774 10581 5723 10581 5721 10581 4774 10582 5721 10582 4776 10582 4772 10583 5724 10583 5723 10583 4772 10584 5723 10584 4774 10584 4770 10585 5725 10585 5724 10585 4770 10586 5724 10586 4772 10586 4768 10587 5726 10587 5725 10587 4768 10588 5725 10588 4770 10588 4766 10589 5727 10589 5726 10589 4766 10590 5726 10590 4768 10590 4764 10591 5728 10591 5727 10591 4764 10592 5727 10592 4766 10592 4762 10593 5729 10593 5728 10593 4762 10594 5728 10594 4764 10594 4760 10595 5730 10595 5729 10595 4760 10596 5729 10596 4762 10596 4758 10597 5731 10597 5730 10597 4758 10598 5730 10598 4760 10598 4756 10599 5732 10599 5731 10599 4756 10600 5731 10600 4758 10600 4754 10601 5733 10601 5732 10601 4754 10602 5732 10602 4756 10602 4752 10603 5734 10603 5733 10603 4752 10604 5733 10604 4754 10604 4750 10605 5735 10605 5734 10605 4750 10606 5734 10606 4752 10606 4748 10607 5736 10607 5735 10607 4748 10608 5735 10608 4750 10608 4746 10609 5737 10609 5736 10609 4746 10610 5736 10610 4748 10610 4744 10611 5738 10611 5737 10611 4744 10612 5737 10612 4746 10612 4743 10613 5739 10613 5738 10613 4743 10614 5738 10614 4744 10614 5740 10615 5741 10615 5739 10615 5740 10616 5739 10616 4743 10616 5742 10617 5743 10617 5741 10617 5742 10618 5741 10618 5740 10618 5744 10619 5745 10619 4022 10619 5744 10620 4022 10620 4021 10620 5746 10621 5744 10621 4021 10621 5746 10622 4021 10622 4020 10622 5747 10623 5746 10623 4020 10623 5747 10624 4020 10624 4019 10624 5748 10625 5747 10625 4019 10625 5748 10626 4019 10626 4018 10626 5749 10627 5748 10627 4018 10627 5749 10628 4018 10628 4017 10628 5750 10629 5749 10629 4017 10629 5750 10630 4017 10630 4016 10630 5751 10631 5750 10631 4016 10631 5751 10632 4016 10632 4015 10632 5752 10633 5751 10633 4015 10633 5752 10634 4015 10634 4014 10634 5753 10635 5752 10635 4014 10635 5753 10636 4014 10636 4013 10636 5754 10637 5753 10637 4013 10637 5754 10638 4013 10638 4012 10638 5755 10639 5754 10639 4012 10639 5755 10640 4012 10640 4011 10640 5756 10641 5755 10641 4011 10641 5756 10642 4011 10642 4010 10642 5757 10643 5756 10643 4010 10643 5757 10644 4010 10644 4009 10644 5758 10645 5757 10645 4009 10645 5758 10646 4009 10646 4008 10646 5759 10647 5758 10647 4008 10647 5759 10648 4008 10648 3662 10648 5759 10649 3662 10649 3664 10649 5759 10650 3664 10650 5760 10650 3639 10651 5722 10651 3664 10651 3639 10652 3664 10652 3640 10652 4024 10653 4022 10653 4004 10653 5761 10654 5759 10654 5760 10654 5761 10655 5760 10655 3644 10655 5761 10656 5762 10656 5758 10656 5761 10657 5758 10657 5759 10657 5762 10658 5763 10658 5757 10658 5762 10659 5757 10659 5758 10659 5763 10660 5764 10660 5756 10660 5763 10661 5756 10661 5757 10661 5764 10662 5765 10662 5755 10662 5764 10663 5755 10663 5756 10663 5765 10664 5766 10664 5754 10664 5765 10665 5754 10665 5755 10665 5766 10666 5767 10666 5753 10666 5766 10667 5753 10667 5754 10667 5767 10668 5768 10668 5752 10668 5767 10669 5752 10669 5753 10669 5768 10670 5769 10670 5751 10670 5768 10671 5751 10671 5752 10671 5769 10672 5770 10672 5750 10672 5769 10673 5750 10673 5751 10673 5770 10674 5771 10674 5749 10674 5770 10675 5749 10675 5750 10675 5771 10676 5772 10676 5748 10676 5771 10677 5748 10677 5749 10677 5772 10678 5773 10678 5747 10678 5772 10679 5747 10679 5748 10679 5773 10680 5774 10680 5747 10680 5774 10681 5746 10681 5747 10681 5721 10682 5775 10682 5776 10682 5721 10683 5776 10683 5722 10683 5723 10684 5777 10684 5775 10684 5723 10685 5775 10685 5721 10685 5724 10686 5778 10686 5777 10686 5724 10687 5777 10687 5723 10687 5725 10688 5779 10688 5778 10688 5725 10689 5778 10689 5724 10689 5726 10690 5780 10690 5779 10690 5726 10691 5779 10691 5725 10691 5727 10692 5781 10692 5780 10692 5727 10693 5780 10693 5726 10693 5728 10694 5782 10694 5781 10694 5728 10695 5781 10695 5727 10695 5729 10696 5783 10696 5782 10696 5729 10697 5782 10697 5728 10697 5730 10698 5784 10698 5783 10698 5730 10699 5783 10699 5729 10699 5731 10700 5785 10700 5784 10700 5731 10701 5784 10701 5730 10701 5732 10702 5786 10702 5785 10702 5732 10703 5785 10703 5731 10703 5733 10704 5787 10704 5786 10704 5733 10705 5786 10705 5732 10705 5734 10706 5788 10706 5787 10706 5734 10707 5787 10707 5733 10707 5735 10708 5789 10708 5788 10708 5735 10709 5788 10709 5734 10709 5736 10710 5790 10710 5789 10710 5736 10711 5789 10711 5735 10711 5737 10712 5791 10712 5790 10712 5737 10713 5790 10713 5736 10713 5738 10714 5792 10714 5791 10714 5738 10715 5791 10715 5737 10715 5739 10716 5793 10716 5792 10716 5739 10717 5792 10717 5738 10717 5741 10718 5794 10718 5793 10718 5741 10719 5793 10719 5739 10719 5743 10720 5795 10720 5794 10720 5743 10721 5794 10721 5741 10721 5722 10722 5776 10722 5760 10722 5722 10723 5760 10723 3664 10723 4050 10724 5029 10724 5774 10724 4050 10725 5774 10725 5773 10725 4048 10726 4050 10726 5773 10726 4048 10727 5773 10727 5772 10727 4046 10728 4048 10728 5772 10728 4046 10729 5772 10729 5771 10729 4044 10730 4046 10730 5771 10730 4044 10731 5771 10731 5770 10731 4042 10732 4044 10732 5770 10732 4042 10733 5770 10733 5769 10733 4040 10734 4042 10734 5769 10734 4040 10735 5769 10735 5768 10735 4038 10736 4040 10736 5768 10736 4038 10737 5768 10737 5767 10737 4036 10738 4038 10738 5767 10738 4036 10739 5767 10739 5766 10739 4034 10740 4036 10740 5766 10740 4034 10741 5766 10741 5765 10741 4032 10742 4034 10742 5765 10742 4032 10743 5765 10743 5764 10743 4030 10744 4032 10744 5764 10744 4030 10745 5764 10745 5763 10745 4028 10746 4030 10746 5763 10746 4028 10747 5763 10747 5762 10747 3661 10748 4028 10748 5762 10748 3661 10749 5762 10749 5761 10749 3661 10750 5761 10750 3644 10750 3661 10751 3644 10751 3643 10751 5775 10752 4741 10752 3641 10752 5775 10753 3641 10753 5776 10753 5777 10754 4740 10754 4741 10754 5777 10755 4741 10755 5775 10755 5778 10756 4739 10756 4740 10756 5778 10757 4740 10757 5777 10757 5779 10758 4738 10758 4739 10758 5779 10759 4739 10759 5778 10759 5780 10760 4737 10760 4738 10760 5780 10761 4738 10761 5779 10761 5781 10762 4736 10762 4737 10762 5781 10763 4737 10763 5780 10763 5782 10764 4735 10764 4736 10764 5782 10765 4736 10765 5781 10765 5783 10766 4734 10766 4735 10766 5783 10767 4735 10767 5782 10767 5784 10768 4733 10768 4734 10768 5784 10769 4734 10769 5783 10769 5785 10770 4732 10770 4733 10770 5785 10771 4733 10771 5784 10771 5786 10772 4731 10772 4732 10772 5786 10773 4732 10773 5785 10773 5787 10774 4730 10774 4731 10774 5787 10775 4731 10775 5786 10775 5788 10776 4729 10776 4730 10776 5788 10777 4730 10777 5787 10777 5789 10778 4728 10778 4729 10778 5789 10779 4729 10779 5788 10779 5790 10780 4727 10780 4728 10780 5790 10781 4728 10781 5789 10781 5791 10782 4726 10782 4727 10782 5791 10783 4727 10783 5790 10783 5792 10784 4725 10784 4726 10784 5792 10785 4726 10785 5791 10785 5793 10786 4724 10786 4725 10786 5793 10787 4725 10787 5792 10787 5794 10788 4723 10788 4724 10788 5794 10789 4724 10789 5793 10789 5795 10790 4722 10790 4723 10790 5795 10791 4723 10791 5794 10791 5776 10792 3641 10792 3644 10792 5776 10793 3644 10793 5760 10793 4024 10794 5796 10794 4025 10794 5797 10795 5718 10795 5798 10795 5798 10796 5799 10796 5720 10796 5720 10797 5714 10797 5800 10797 5801 10798 5802 10798 5797 10798 5720 10799 5800 10799 5801 10799 5797 10800 5798 10800 5720 10800 5720 10801 5801 10801 5797 10801 5803 10802 5744 10802 5746 10802 5746 10803 5714 10803 5804 10803 5804 4654 5805 4654 5803 4654 5746 10804 5804 10804 5803 10804 5744 10805 5806 10805 5745 10805 5714 10806 5746 10806 5774 10806 5714 10807 5774 10807 5029 10807 4003 10808 4023 10808 4022 10808 4003 10809 4022 10809 4004 10809 4022 10810 5745 10810 5807 10810 5807 10811 5796 10811 4024 10811 5807 10812 4024 10812 4022 10812 3895 10813 3894 10813 3898 10813 5808 10814 3726 10814 5742 10814 5808 10815 5742 10815 5809 10815 3727 10816 3726 10816 5808 10816 5344 10817 5810 10817 5811 10817 5812 10818 3922 10818 3925 10818 3925 10819 5344 10819 5811 10819 3925 10820 5811 10820 5812 10820 5813 10821 5814 10821 5316 10821 5316 10822 3924 10822 3923 10822 5316 10823 3923 10823 5813 10823 3926 10824 3929 10824 5316 10824 5316 10825 5814 10825 5815 10825 5316 10826 5815 10826 3926 10826 4179 10827 4182 10827 4181 10827 4180 10828 4179 10828 4181 10828 4401 10829 4403 10829 4433 10829 4432 10830 4401 10830 4433 10830 5809 10831 5742 10831 5740 10831 5809 10832 5740 10832 5816 10832 5816 10833 5740 10833 4743 10833 4743 10834 4742 10834 5817 10834 4743 10835 5817 10835 5816 10835 5817 10836 4742 10836 5818 10836 5818 10837 4742 10837 4745 10837 5818 10838 4745 10838 5819 10838 5819 10839 4745 10839 4747 10839 5819 10840 4747 10840 5820 10840 5820 10841 4747 10841 4749 10841 5820 10842 4749 10842 5821 10842 5821 10843 4749 10843 4751 10843 5821 10844 4751 10844 5822 10844 5822 10845 4751 10845 4753 10845 5822 10846 4753 10846 5823 10846 5823 10847 4753 10847 4755 10847 5823 10848 4755 10848 5824 10848 5824 10849 4755 10849 4757 10849 5824 10850 4757 10850 5825 10850 5825 10851 4757 10851 4759 10851 5825 10852 4759 10852 5826 10852 5826 10853 4759 10853 4761 10853 4761 10854 4778 10854 5827 10854 4761 10855 5827 10855 5826 10855 5827 10856 4778 10856 5828 10856 5829 10857 5828 10857 4778 10857 4778 10858 4779 10858 4787 10858 4778 10859 4787 10859 5829 10859 5830 10860 4818 10860 4817 10860 5830 10861 4817 10861 5831 10861 5041 10862 5040 10862 5832 10862 5041 10863 5832 10863 5833 10863 5040 10864 5046 10864 5834 10864 5040 10865 5834 10865 5832 10865 5046 10866 5051 10866 5058 10866 5058 10867 5835 10867 5834 10867 5058 10868 5834 10868 5046 10868 5058 10869 5836 10869 5835 10869 5058 10870 5057 10870 5837 10870 5058 10871 5837 10871 5836 10871 5057 10872 5064 10872 5072 10872 5072 10873 5838 10873 5837 10873 5072 10874 5837 10874 5057 10874 5072 10875 5839 10875 5838 10875 5072 10876 5071 10876 5840 10876 5072 10877 5840 10877 5839 10877 5841 10878 5840 10878 5071 10878 5071 10879 5079 10879 5088 10879 5071 10880 5088 10880 5841 10880 5841 10881 5088 10881 5090 10881 5841 10882 5090 10882 5842 10882 5090 10883 5843 10883 5842 10883 5830 10884 5843 10884 5090 10884 5090 10885 5089 10885 4818 10885 5090 10886 4818 10886 5830 10886 5344 10887 5345 10887 5844 10887 5344 10888 5844 10888 5810 10888 5844 10889 5345 10889 5346 10889 5346 10890 5354 10890 5845 10890 5346 10891 5845 10891 5844 10891 5354 10892 5846 10892 5845 10892 5847 10893 5846 10893 5354 10893 5354 10894 5355 10894 5362 10894 5354 10895 5362 10895 5847 10895 5362 10896 5848 10896 5847 10896 5848 10897 5362 10897 5363 10897 5363 10898 5369 10898 5849 10898 5363 10899 5849 10899 5848 10899 5369 10900 5850 10900 5849 10900 5851 10901 5850 10901 5369 10901 5369 10902 5370 10902 5375 10902 5369 10903 5375 10903 5851 10903 5375 10904 5852 10904 5851 10904 5852 10905 5375 10905 5376 10905 5376 10906 5408 10906 5853 10906 5376 10907 5853 10907 5852 10907 5853 10908 5408 10908 5041 10908 5853 10909 5041 10909 5833 10909 5854 10910 5855 10910 5856 10910 5707 10911 5856 10911 5855 10911 5707 10912 5855 10912 5857 10912 5858 10913 5411 10913 5414 10913 5414 10914 5707 10914 5857 10914 5414 10915 5857 10915 5858 10915 5859 10916 5411 10916 5858 10916 5860 10917 5423 10917 5412 10917 5412 10918 5411 10918 5859 10918 5412 10919 5859 10919 5860 10919 5861 10920 5423 10920 5860 10920 5862 10921 5424 10921 5423 10921 5862 10922 5423 10922 5861 10922 5863 10923 5428 10923 5425 10923 5425 10924 5424 10924 5862 10924 5425 10925 5862 10925 5863 10925 5864 10926 5428 10926 5863 10926 5865 10927 5431 10927 5429 10927 5429 10928 5428 10928 5864 10928 5429 10929 5864 10929 5865 10929 5866 10930 5433 10930 5431 10930 5866 10931 5431 10931 5865 10931 5867 10932 5435 10932 5433 10932 5867 10933 5433 10933 5866 10933 5868 10934 5435 10934 5867 10934 5869 10935 5437 10935 5436 10935 5436 10936 5435 10936 5868 10936 5436 10937 5868 10937 5869 10937 4817 10938 5870 10938 5831 10938 5871 10939 5437 10939 5869 10939 5872 10940 4787 10940 4788 10940 4788 10941 5437 10941 5871 10941 4788 10942 5871 10942 5872 10942 5870 10943 4817 10943 4815 10943 4815 10944 5439 10944 5873 10944 4815 10945 5873 10945 5870 10945 5873 10946 5439 10946 5441 10946 5873 10947 5441 10947 5874 10947 5441 10948 5875 10948 5874 10948 5829 10949 4787 10949 5872 10949 5876 10950 5875 10950 5441 10950 5441 10951 5440 10951 5445 10951 5441 10952 5445 10952 5876 10952 5876 10953 5445 10953 5447 10953 5876 10954 5447 10954 5877 10954 5877 10955 5447 10955 5449 10955 5877 10956 5449 10956 5878 10956 5449 4654 5879 4654 5878 4654 5880 10957 5879 10957 5449 10957 5449 10958 5448 10958 5456 10958 5449 10959 5456 10959 5880 10959 5880 10960 5456 10960 5458 10960 5880 10961 5458 10961 5881 10961 5458 10962 5882 10962 5881 10962 5883 10963 5882 10963 5458 10963 5458 10964 5457 10964 5467 10964 5458 10965 5467 10965 5883 10965 5467 10966 5884 10966 5883 10966 5885 10967 5884 10967 5467 10967 5467 10968 5466 10968 5477 10968 5467 10969 5477 10969 5885 10969 5477 10970 5886 10970 5885 10970 5477 10971 5476 10971 5887 10971 5477 10972 5887 10972 5886 10972 5476 10973 5486 10973 5888 10973 5476 10974 5888 10974 5887 10974 5888 10975 5486 10975 5495 10975 5888 10976 5495 10976 5889 10976 5494 10977 5503 10977 5890 10977 5890 10978 5891 10978 5495 10978 5890 10979 5495 10979 5494 10979 5495 10980 5891 10980 5889 10980 5503 10981 5511 10981 5892 10981 5503 10982 5892 10982 5890 10982 5511 10983 5519 10983 5893 10983 5511 10984 5893 10984 5892 10984 5519 10985 5527 10985 5894 10985 5519 10986 5894 10986 5893 10986 5895 10987 5896 10987 5652 10987 5652 10988 5643 10988 5644 10988 5652 10989 5644 10989 5895 10989 5644 10990 3926 10990 5815 10990 5644 10991 5815 10991 5895 10991 5897 10992 5898 10992 5659 10992 5659 10993 5651 10993 5652 10993 5659 10994 5652 10994 5897 10994 5897 10995 5652 10995 5896 10995 3923 10996 5899 10996 5813 10996 5900 10997 5664 10997 5657 10997 5657 10998 5658 10998 5901 10998 5657 10999 5901 10999 5900 10999 5901 11000 5658 11000 5659 11000 5901 11001 5659 11001 5902 11001 5898 11002 5902 11002 5659 11002 3923 11003 3922 11003 5903 11003 3923 11004 5903 11004 5899 11004 5904 11005 5667 11005 5662 11005 5662 11006 5663 11006 5905 11006 5662 11007 5905 11007 5904 11007 5663 11008 5664 11008 5906 11008 5663 11009 5906 11009 5905 11009 5664 11010 5900 11010 5906 11010 3922 11011 5812 11011 5903 11011 5907 11012 5908 11012 5669 11012 5669 11013 5666 11013 5667 11013 5669 11014 5667 11014 5907 11014 5904 11015 5907 11015 5667 11015 5909 11016 5671 11016 5669 11016 5909 11017 5669 11017 5908 11017 5910 11018 5676 11018 5673 11018 5673 11019 5671 11019 5909 11019 5673 11020 5909 11020 5910 11020 5910 11021 5911 11021 5676 11021 5912 11022 5703 11022 5677 11022 5677 11023 5676 11023 5911 11023 5677 11024 5911 11024 5912 11024 5913 11025 5705 11025 5703 11025 5913 11026 5703 11026 5912 11026 5913 11027 5914 11027 5705 11027 5691 11028 5690 11028 5915 11028 5691 11029 5915 11029 5711 11029 5711 11030 5915 11031 5916 11032 5706 11033 5705 11033 5914 11033 5914 11034 5917 11034 5710 11034 5914 11035 5710 11035 5706 11035 5918 11036 5708 11036 5710 11036 5918 11037 5710 11037 5917 11037 5919 11038 5709 11038 5708 11038 5919 11039 5708 11039 5918 11039 5709 11040 5919 11040 5920 11040 5854 11041 5856 11041 5921 11041 5921 11042 5856 11042 5707 11042 5707 11043 5709 11043 5920 11043 5707 11044 5920 11044 5921 11044 5527 11045 5711 11045 5916 11045 5527 11046 5916 11046 5894 11046 4426 11047 4451 11047 4449 11047 4430 11048 4428 11048 4426 11048 4426 11049 4449 11049 4430 11049 4449 11050 4431 11050 4430 11050 5814 11051 5813 11051 5922 11051 5814 11052 5922 11052 5923 11052 5815 11053 5814 11053 5923 11053 5815 11054 5923 11054 5924 11054 5895 11055 5815 11055 5924 11055 5895 11056 5924 11056 5925 11056 5926 11057 5897 11057 5895 11057 5926 11058 5895 11058 5925 11058 5898 11059 5897 11059 5926 11059 5898 11060 5926 11060 5927 11060 5922 11061 3923 11061 5813 11061 5895 11062 5897 11062 5896 11062 5899 11063 5903 11063 5928 11063 5899 11064 5928 11064 5922 11064 5812 64 5811 64 5903 64 5928 11065 5903 11065 5811 11065 5928 11066 5811 11066 5929 11066 5929 11067 5811 11067 5810 11067 5810 11068 5844 11069 5845 11070 5845 11071 5930 11071 5929 11071 5810 11072 5845 11072 5929 11072 5930 11073 5845 11073 5846 11073 5846 11074 5847 11074 5931 11074 5846 11075 5931 11075 5930 11075 5847 64 5848 64 5849 64 5847 11076 5849 11076 5931 11076 5932 11077 5931 11077 5849 11077 5932 11078 5850 11078 5851 11078 5851 11079 5933 11079 5934 11079 5935 11080 5690 11080 5932 11080 5851 11081 5934 11081 5935 11081 5851 11082 5935 11082 5932 11082 5849 11083 5850 11083 5932 11083 5843 11084 5933 11084 5842 11084 5878 11085 5934 11085 5877 11085 5935 11086 5934 11086 5879 11086 5933 11087 5851 11087 5853 11087 5833 11088 5832 11088 5834 11088 5834 11089 5933 11089 5853 11089 5834 11090 5853 11090 5833 11090 5839 11091 5840 11091 5933 11091 5933 11092 5834 11092 5836 11092 5836 11093 5838 11093 5839 11093 5839 11094 5933 11094 5836 11094 5841 11095 5842 11095 5933 11095 5841 11096 5933 11096 5840 11096 5934 11097 5933 11097 5843 11097 5934 11098 5843 11098 5877 11098 5886 11099 5878 11099 5935 11099 5888 64 5889 64 5891 64 5891 64 5890 64 5892 64 5892 11100 5893 11100 5894 11100 5894 11101 5916 11101 5915 11101 5915 11102 5690 11102 5935 11102 5935 11103 5886 11103 5887 11103 5888 64 5891 64 5892 64 5935 11104 5887 11104 5888 11104 5894 11105 5915 11105 5935 11105 5888 11106 5892 11106 5894 11106 5888 11107 5894 11107 5935 11107 5900 581 5901 581 5902 581 5902 11108 5898 11108 5927 11108 5927 11109 5936 11109 5904 11109 5904 581 5905 581 5906 581 5900 581 5902 581 5927 581 5904 11110 5906 11110 5900 11110 5900 11111 5927 11111 5904 11111 5908 581 5904 581 5936 581 5908 581 5936 581 5909 581 5909 581 5936 581 5937 581 5909 11112 5869 11112 5911 11112 5909 11113 5937 11113 5869 11113 5867 11114 5866 11114 5914 11114 5913 581 5912 581 5911 581 5867 11115 5914 11115 5913 11115 5869 581 5868 581 5867 581 5913 581 5911 581 5869 581 5913 11116 5869 11116 5867 11116 5863 581 5862 581 5920 581 5920 581 5919 581 5918 581 5918 581 5917 581 5914 581 5914 11117 5866 11117 5864 11117 5864 11118 5863 11118 5920 11118 5920 11119 5918 11119 5914 11119 5920 581 5914 581 5864 581 5859 581 5858 581 5920 581 5920 11120 5862 11120 5860 11120 5920 11121 5860 11121 5859 11121 5854 581 5920 581 5858 581 5869 581 5937 581 5819 581 5713 11122 5712 11122 5798 11122 5713 11123 5798 11123 5718 11123 5712 11124 5938 11124 5799 11124 5712 11125 5799 11125 5798 11125 5938 11126 5719 11126 5720 11126 5938 11127 5720 11127 5799 11127 5715 11128 5719 11128 5028 11128 5715 11129 5028 11129 5029 11129 5719 11130 5938 11130 5031 11130 5719 11131 5031 11131 5028 11131 5938 11132 5712 11132 5030 11132 5938 11133 5030 11133 5031 11133 5939 11134 5802 11134 5801 11134 5801 11135 5940 11135 5941 11135 5801 11136 5941 11136 5939 11136 5942 11137 5797 11137 5802 11137 5942 11138 5802 11138 5939 11138 5941 11139 5940 11139 5943 11139 5941 11140 5943 11140 5939 11140 5942 11141 5939 11141 5943 11141 5942 11142 5943 11142 5944 11142 5940 11143 5944 11143 5714 11143 5714 11144 5944 11144 5806 11144 5806 11145 5945 11145 5946 11145 5946 11146 5947 11146 5714 11146 5806 11147 5946 11147 5714 11147 5714 11148 5940 11148 5801 11148 5714 11149 5801 11149 5800 11149 5744 11150 5806 11150 5948 11150 5806 11151 5949 11151 5948 11151 5949 11152 5950 11152 5948 11152 5950 11153 5951 11153 5948 11153 5951 11154 5714 11154 5948 11154 5714 11155 5804 11155 5948 11155 5804 11156 5805 11156 5948 11156 5805 11157 5803 11157 5948 11157 5803 11158 5744 11158 5948 11158 5806 11159 5745 11159 5952 11159 5806 11160 5952 11160 5953 11160 5714 11161 5948 11161 5954 11161 5714 11162 5954 11162 5955 11162 5956 11163 5953 11163 5954 11163 5953 11164 5806 11164 5948 11164 5953 11165 5948 11165 5954 11165

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/palm/palm_E4.dae b/URDFs/sr_description/meshes/components/palm/palm_E4.dae new file mode 100644 index 0000000..94aaf6e --- /dev/null +++ b/URDFs/sr_description/meshes/components/palm/palm_E4.dae @@ -0,0 +1,122 @@ + + + + + + Blender User + Blender 3.4.1 commit date:2022-12-19, commit time:17:00, hash:55485cb379f7 + + 2023-01-25T12:00:19 + 2023-01-25T12:00:19 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.04392 0.04392 0.04392 1 + + + 0.21961 0.21961 0.21961 1 + + + 0.45000 0.45000 0.45000 1 + + + 32 + + + 1 + + + + + + + + + + + + + + + + + -15.63157 -11.1671 37.04457 -9.852789 -10 45.29752 -15.63157 -8 37.04456 -9.852787 11 45.29753 -15.63157 11 37.04456 -9.996184 -11.77947 45.09273 -9.891212 -11.52065 45.24265 -10.06535 -11.85011 44.99395 -9.852788 -11.1671 45.29752 -10.13958 -11.8742 44.88795 -15.34478 -11.8742 37.45414 -15.40073 -11.86062 37.37424 -15.60974 -11.43769 37.07574 -15.45453 -11.82038 37.2974 -15.54757 -11.6671 37.16453 -31.1548 -10.12936 23.44643 -31.1388 -10.08775 23.46907 -31.16969 -10.12923 23.45685 -31.15277 -10.08763 23.47886 -31.95926 -10.03408 24.04204 -31.92028 -10.03701 24.01628 -32.41716 -9.957194 24.3642 -31.98354 -10.03125 24.05877 -32.47746 -9.947364 24.40462 -32.90916 -9.840753 24.7087 -32.96633 -9.827264 24.74693 -33.39448 -9.688118 25.04852 -33.44838 -9.671392 25.08446 -33.87133 -9.499844 25.38242 -33.92185 -9.480317 25.41599 -34.49449 -9.192632 25.81876 -34.54041 -9.169998 25.84911 -35.09515 -8.824612 26.23935 -35.1364 -8.799649 26.26643 -35.66933 -8.398223 26.64139 -35.70591 -8.371691 26.66521 -36.21322 -7.916285 27.02223 -36.24522 -7.888926 27.04283 -37.19599 -6.798859 27.71037 -37.21931 -6.771961 27.7249 -38.01751 -5.501849 28.28561 -38.03321 -5.477952 28.2948 -39.09484 -2.509955 29.03996 -39.10009 -2.49787 29.04183 -39.3547 0 29.22192 -39.35736 0 29.22198 -30.78843 -10.05235 23.96456 -30.78843 -10.43288 23.96456 -30.79248 -10.03783 23.95903 -30.85965 -10.63651 23.86774 -30.85965 -9.891713 23.86774 -32.96586 -11 21.29985 -32.05224 -8.99898 22.362 -31.15277 -11 23.47886 -34.24037 -9.000475 19.82587 -33.95288 -9.000055 20.16607 -34.5319 -11 19.47051 -33.91099 -9 20.215 -33.86153 -8.999938 20.27262 -34.99076 -9.001958 18.87805 -34.99763 -10.9425 18.86878 -35.32338 -9.002824 18.40917 -35.30551 -10.83623 18.43552 -35.69787 -10.6041 17.81547 -35.88157 -9.004629 17.48455 -35.98874 -10.33803 17.27374 -36.05147 -9.005281 17.1426 -36.42349 -9.006922 16.16142 -36.14739 -10.14442 16.9283 -36.58259 -9.007765 15.47798 -36.5671 -9.299139 15.56322 -36.60354 -9.007891 15.35041 -30.78225 -10.40598 23.9733 -30.78459 -10.40598 23.97494 -30.81714 -10.52709 23.92844 -30.79408 -10.03987 23.96137 -30.76762 -10.22121 23.99917 -30.76519 -10.22008 23.99742 24 0 85.41296 24 0 78.70024 23.95033 0 78.79646 23.975 0 78.70024 23.88242 0 78.86894 23.78801 0 78.89982 22.51415 0 85.41296 23.69038 0 78.88146 21.38016 0 85.63554 20.41444 0 86.27025 20.64093 0 78.53271 20.45454 0 78.73052 20 0 86.77617 20.37647 0 78.78839 20.28034 0 78.80261 20.1 0 78.60358 20 0 78.60358 20.12361 0 78.69785 20.18886 0 78.76985 23.61364 0 78.8184 23.32196 0 78.4992 22.46058 0 78.05376 21.49091 0 78.06588 20.37647 6 78.78839 20.45454 6 78.73052 20.11047 6 79.3445 20 6 80 20 6 78.60358 20.1 6 78.60358 20.12361 6 78.69785 20.18886 6 78.76985 20.28034 6 78.80261 20 2.537532 91.58148 20.00008 0.9425158 91.2116 20.00001 0.5039723 90.86651 19.99998 -0.04999852 90.76329 20.00001 -0.4555604 90.84561 20 4.02107 92.27953 20 8 96.07158 20 6.05 80 20 8 80 19.99998 0.04999887 90.76329 20 -8 86.77617 20 -8 90.96275 20 -7.992074 91.15404 20.00001 -0.8922592 91.15404 20 7.522194 97.05182 20 7.070023 95.73551 20 6.245589 94.3183 20 5.141971 93.10694 20 7.674408 97.32546 20 8.29283 97.78427 20 8.347739 97.80921 19.99999 8.419126 97.84249 23.61364 6 78.8184 23.69038 6 78.88146 23.87255 6 79.29747 23.78801 6 78.89982 23.88242 6 78.86894 23.975 6 78.70024 24 6 78.70024 23.95033 6 78.79646 23.99938 6 79.95001 24 -8 85.41296 24 -8 86.96275 24 8.347738 93.80921 24.00001 8.419132 93.8425 24 8 92.07158 23.99985 -0.89226 87.15404 24 -7.992074 87.15404 24.00001 -0.5667624 86.89865 24.00001 -0.1227943 86.76594 24.00001 -0.04999911 86.76329 24.00004 0.05000001 86.76329 23.99999 0.5197654 86.87382 24.00003 0.8052727 87.06809 24 6.965666 91.51197 24 6.096521 90.12173 23.99938 8 79.95001 24 5.14197 89.10693 24 7.737691 93.39491 24 7.534903 93.09442 24 7.522194 93.05182 23.99992 0.9425114 87.2116 24 2.30319 87.50439 24 3.808211 88.15484 -1.975 0 78.70024 -2 0 78.70024 -1.950333 0 78.79646 -2 0 85.41296 -1.882417 0 78.86894 -1.788005 0 78.89982 0.619842 0 85.63554 1.585566 0 86.27025 -1.690385 0 78.88146 2 0 86.77617 -1.613636 0 78.8184 2 0 78.60358 1.9 0 78.60358 1.876393 0 78.69785 1.811144 0 78.76985 1.719657 0 78.80261 -0.5141522 0 85.41296 1.623529 0 78.78839 1.545454 0 78.73052 1.0144 0 78.27635 0.02500194 0 78.00016 -0.9709919 0 78.25153 -1.690385 6 78.88146 -1.613636 6 78.8184 -1.710841 6 78.96414 -1.788005 6 78.89982 -2 6 79.95001 -1.882417 6 78.86894 -1.950333 6 78.79646 -2 6 78.70024 -1.975 6 78.70024 -2 2.537532 87.58148 -1.99992 0.9425158 87.2116 -1.999988 0.5039723 86.86651 -2 4.02107 88.27953 -2.000019 -0.04999852 86.76329 -1.999992 -0.4555604 86.84561 -2.000022 0.04999887 86.76329 -2 -8 85.41296 -2 -8 86.96275 -2 -7.992074 87.15404 -1.999991 -0.8922592 87.15404 -2.000013 8.419126 93.84249 -2 8.347739 93.80921 -2 8 92.07158 -2 8.29283 93.78427 -2 8 79.95001 -2 5.141971 89.10693 -2 6.245589 90.3183 -2 7.070023 91.73551 -2 7.522194 93.05182 -2 7.674408 93.32546 1.736203 6 79.00723 1.545454 6 78.73052 1.623529 6 78.78839 1.9 6 78.60358 2 6 78.60358 1.876393 6 78.69785 2 6 80 1.811144 6 78.76985 1.719657 6 78.80261 2.000027 0.8052727 91.06809 1.99992 0.9425114 91.2116 2 2.30319 91.50439 2.000001 8.347738 97.80921 2.000011 8.419132 97.8425 2 8 96.07158 2.000036 0.05000001 90.76329 1.999987 0.5197654 90.87382 2 8 80 2 -7.992074 91.15404 1.999853 -0.89226 91.15404 2 -8 90.96275 2.000011 -0.5667624 90.89865 2 -8 86.77617 2 6.965666 95.51197 2 6.096521 94.12173 2 5.14197 93.10694 2.000011 -0.04999911 90.76329 2 3.808211 92.15484 2 7.737691 97.39491 2 7.534903 97.09442 2 7.522194 97.05182 2.000009 -0.1227943 90.76594 -20 -8 86.96275 -20 -7.992074 87.15404 -20.00015 -0.89226 87.15404 -20 0 58.35442 -20 0 67.6 -20 2.783452 57.72694 -20 8 92.07158 -20 5.383815 55.88576 -20 8.347738 93.80921 -19.99999 8.419132 93.8425 -20 -8 81.1 -20 7.627752 52.56674 -20 8 52.48383 -20 7.558959 52.49385 -20 7.545219 52.48383 -20 7.672248 52.67604 -20 7.674957 52.79312 -20 7.593864 53.01306 -20 6.096521 90.12173 -20 6.965666 91.51197 -19.99999 -0.5667624 86.89865 -20 -4.633975 79.45001 -20 5.14197 89.10693 -20 -7.425 80.10408 -20 -7.845929 80.525 -20 -6.85 79.95001 -20 -5.5 79.95001 -20 -5 79.81603 -20 2.30319 87.50439 -20 3.808211 88.15484 -20 -4.5 78.95 -20 -4.5 67.6 -19.99999 -0.1227943 86.76594 -19.99999 -0.04999911 86.76329 -19.99996 0.05000001 86.76329 -20 7.737691 93.39491 -20 7.534903 93.09442 -20 7.522194 93.05182 -20.00001 0.5197654 86.87382 -19.99997 0.8052727 87.06809 -20.00008 0.9425114 87.2116 -21.03607 -10.80751 40.82883 -23.04069 -10.11431 42.23248 -22.19614 -9.342291 39.11337 -23.60113 -7.547463 37.00945 -25.42057 -8.338501 43.89889 -27.0014 -3.675825 33.71841 -26.11347 -4.226118 33.09667 -27.23835 -5.755874 45.17171 -27.89103 -2.607348 34.34133 -27.28798 -3.406847 33.91907 -28.57801 0 46.10976 -28.57801 0 34.82236 -28.31813 -2.616324 45.92778 -28.43525 -1.236314 34.7224 -28.03067 -2.351668 34.43911 -28.62173 0 46.14036 -28.29854 2.9196 45.91407 -40.2508 0 29.53233 -40.54878 1.631817 28.89457 -40.64908 0 28.9648 -39.27928 6.357625 27.39223 -39.36458 5.65907 28.06538 -26.96404 6.358095 44.97964 -40.2399 3.274823 28.67828 -40.3253 2.9196 28.73808 -39.25498 6.5 27.24815 -38.90707 6.5 27.74502 -38.8604 6.577053 27.71235 -24.74977 9.035862 43.42919 -38.49341 7.373648 27.09542 -37.77354 8.604277 25.8405 -21.92066 10.63251 41.44823 -36.96957 9.610816 24.36953 -37.45719 9.039074 25.27304 -34.37295 11 18.74884 -34.38207 10.99998 18.77241 -19.61105 11 39.83102 -35.23461 10.83611 20.81647 -36.06531 10.39656 22.59659 -31.1388 0 23.46907 -26.0733 0 30.63266 -40.02836 0 29.69362 -27.31667 0 31.51188 -28.24811 0 33.04089 -40.21281 0 29.57542 -19.65201 -10.81303 39.85971 -20.79119 -9.407652 38.23279 -21.92945 -8 36.60719 -21.87542 -8 36.56926 -22.24273 -7.548001 36.04982 -24.92514 -4.226118 32.25638 -19.67317 -10.63638 39.5695 -19.57219 -10.69731 39.60398 -19.41918 -10.76541 39.61444 -19.37218 -10.78082 39.60814 -19.17522 -10.81303 39.52585 -19.87025 -10.46113 39.40496 -19.74299 -10.58511 39.52986 -19.67192 -12.7621 39.57008 -19.87025 -12.7621 39.40496 -19.41766 -12.7621 39.61431 -19.17522 -12.7621 39.52585 -19.06016 -13.88552 39.44528 -18.96522 -14.2698 39.37881 -18.72177 -14.93952 39.20834 -23.82293 -8 33.81547 -23.87537 -7.93422 33.74095 -25.06324 -4.03637 32.06108 -31.1388 -10.02759 23.46907 -31.12284 -10.04614 23.49175 -21.79245 -13.15199 36.68659 -27.36366 -14.10366 28.80784 -23.87537 -8 33.74095 -25.79657 -2.358274 31.024 -32.2769 -14.63108 21.85956 -35.85406 -14.7551 16.80078 -31.9534 -9.019498 22.31707 -35.85406 -8 16.80078 -32.48834 -8 21.56055 44.99998 -0.1914873 9.003568 45 -0.186048 9.033534 45.00831 -0.25 9.033459 44.99996 -0.1999999 8.982865 44.99984 -0.2538716 8.946176 44.99984 -0.2483009 8.946512 44.99985 -0.2319718 8.951368 44.99989 -0.2136166 8.964616 -21.175 0 0.1246222 -30.825 0 0.0992316 -21.175 0 11 -30.825 0 11 -21.6875 0 11.88768 -21.31233 0 11.5125 -22.2 0 12.025 -29.8 0 12.025 -30.3125 0 11.88768 -30.68768 0 11.5125 -38.99057 0 16.84909 -39.93136 0 17.74325 -40.04502 0 17.87049 -40.066 0 17.89478 -42.16515 0 22.38991 -42.1957 0 22.59775 -42.19385 0 22.5881 -40.10243 0 29.74549 -40.75143 0 28.81413 -40.76856 0 28.78981 -40.85209 0 28.66065 -40.88351 0 28.61267 -40.95032 0 28.50396 -40.99395 0 28.4334 -41.04599 0 28.34411 -41.09994 0 28.25202 -41.13899 0 28.18113 -41.20148 0 28.06854 -41.22919 0 28.0151 -41.29861 0 27.88296 -41.40068 0 27.67407 -41.39133 0 27.6953 -41.47965 0 27.50556 -41.48172 0 27.49921 -41.52101 0 27.41073 -41.54755 0 27.35132 -41.55947 0 27.32157 -41.61258 0 27.19573 -41.6338 0 27.14121 -41.67476 0 27.03879 -41.7046 0 26.95823 -41.73406 0 26.88048 -42.21768 0 22.77828 -42.22145 0 22.80673 -42.23745 0 22.96887 -42.24235 0 23.01686 -42.25316 0 23.15975 -42.27182 0 24.0804 -42.26582 0 24.24524 -42.26436 0 24.26202 -42.25595 0 24.41359 -42.25326 0 24.44312 -42.24294 0 24.5816 -42.23855 0 24.62358 -42.2224 0 24.78989 -42.22026 0 24.80329 -42.19702 0 24.99766 -42.17309 0 25.16007 -42.16679 0 25.20492 -42.14429 0 25.33693 -42.25836 0 23.22814 -42.26764 0 23.3985 -42.26479 0 23.35079 -42.27367 0 23.56852 -42.2757 0 23.71599 -42.27648 0 23.73821 -42.2756 0 23.89835 -42.27611 0 23.90755 -42.27254 0 24.07656 -42.25948 0 23.25526 -42.25097 0 23.12236 -41.73864 0 26.86579 -41.77175 0 26.77273 -41.79048 0 26.72081 -41.83515 0 26.58481 -41.84399 0 26.55976 -41.8654 0 26.48997 -41.89457 0 26.39733 -41.89468 0 26.39457 -41.94221 0 26.2335 -41.95023 0 26.20213 -41.99703 0 26.02883 -42.03765 0 25.86024 -42.04686 0 25.82363 -42.07651 0 25.68711 -42.09174 0 25.61791 -42.11209 0 25.51264 -42.11234 0 25.51485 -42.12861 0 25.42494 -42.13171 0 25.41167 -42.14986 0 25.30836 -41.80093 0 20.91644 -41.85612 0 21.08345 -41.85998 0 21.09716 -41.90561 0 21.24484 -41.9153 0 21.27941 -41.95202 0 21.40697 -41.96683 0 21.46308 -41.99535 0 21.56982 -42.01452 0 21.64805 -42.02072 0 21.67135 -42.03691 0 21.74098 -42.04492 0 21.77316 -42.05831 0 21.8342 -42.06792 0 21.87525 -42.07874 0 21.92768 -42.08974 0 21.97762 -42.09818 0 22.0214 -42.11037 0 22.08027 -42.11663 0 22.11536 -42.12982 0 22.1832 -42.13407 0 22.20954 -42.16598 0 22.39848 -41.19649 0 19.52743 -41.29412 0 19.71344 -41.28742 0 19.7011 -41.34137 0 19.80744 -41.37102 0 19.86867 -41.38758 0 19.90212 -41.4116 0 19.95331 -41.43275 0 19.99746 -41.45137 0 20.03851 -41.47686 0 20.09348 -41.4903 0 20.12425 -41.51991 0 20.19017 -41.52838 0 20.21052 -41.56191 0 20.28755 -41.56562 0 20.29732 -41.59488 0 20.3663 -41.60199 0 20.38462 -41.62705 0 20.44524 -41.67187 0 20.56007 -41.68902 0 20.60368 -41.7382 0 20.73738 -41.74784 0 20.76286 -41.80353 0 20.92279 -41.20068 0 19.53589 -41.15615 0 19.45419 -41.14612 0 19.43541 -41.11087 0 19.37312 -41.09473 0 19.34406 -41.06484 0 19.29267 -41.04231 0 19.25337 -41.01809 0 19.21287 -40.98886 0 19.16334 -40.97061 0 19.13371 -40.93438 0 19.07396 -40.92243 0 19.05521 -40.87888 0 18.98524 -40.87356 0 18.97738 -40.82236 0 18.89718 -40.82401 0 18.90022 -40.77379 0 18.82374 -40.76481 0 18.80977 -40.72291 0 18.74796 -40.71774 0 18.73989 -40.67139 0 18.67287 -40.10083 0 17.93477 -40.15594 0 17.99949 -40.18094 0 18.02955 -40.21038 0 18.06464 -40.23766 0 18.09807 -40.26414 0 18.13023 -40.29385 0 18.16735 -40.31722 0 18.19625 -40.3495 0 18.23737 -40.36963 0 18.2627 -40.4046 0 18.30813 -40.42137 0 18.32959 -40.45914 0 18.37963 -40.47243 0 18.3969 -40.51311 0 18.45186 -40.52283 0 18.46464 -40.56647 0 18.52481 -40.57256 0 18.53281 -40.61924 0 18.59848 -40.62162 0 18.60141 -40.67001 0 18.67044 36.025 0 11 36.025 0 0.2128129 36.01972 0 0.2127943 26.375 0 0.2127943 26.375 0 11 35 0 12.025 26.51233 0 11.5125 26.8875 0 11.88768 27.4 0 12.025 35.72478 0 11.72478 35.94697 0 11.39225 35.39225 0 11.94698 30.29696 0 41.90764 30.17015 0 41.87215 32.35895 0 43.04232 32.13755 0 42.28835 38.72033 0 46.38016 39.07643 0 46.40801 38.87948 0 46.22781 37.32806 0 45.08153 36.90866 0 44.83335 36.03378 0 44.90519 34.55941 0 43.56946 32.2069 0 42.31118 38.01823 0 45.5457 42.2084 0 70.21218 42.2084 0 67.41297 42 0 67.6 40.4084 0 67.41297 39.25 4.46464e-4 67.6 40.4084 0 64.86296 42 0 85.28413 42.2084 0 85.22474 42.2084 0 81.409 39.2 0 67.59917 39.2 0 64.95001 39.32807 0 62.82043 40.49411 0 63.19118 39.72287 0 60.45989 41.28963 0 58.99728 40.34708 0 57.9257 41.5599 0 53.48676 42.84017 0 53.39157 41.79266 0 52.39184 42.34719 0 52.68526 41.86008 0 51.98737 42.2084 0 78.6098 42.2084 0 75.81059 42.2084 0 73.01139 40.38591 0 16.65846 39.84885 0 16.71328 40.47975 0 17.04018 41.18298 0 16.56071 40.91244 0 17.12517 41.77449 0 16.84374 40.78535 0 17.13699 42.62542 0 16.53031 42.92301 0 16.38492 43.24047 0 16.16123 40.64711 0 17.11091 21.73325 0 27.90483 33.00025 0 16.72511 21.82053 0 27.17433 31.82762 0 16.87757 28.90793 0 17.78647 26.30217 0 19.38668 22.64576 0 24.22991 24.17099 0 21.57956 35.0206 -3.004986 14.7204 35.0206 -0.1999999 14.7204 34.865 -3.09243 14.8748 33.00025 -0.1999999 16.72511 34.75521 -3.270671 14.98374 34.71567 -3.5 15.02297 21.73325 -0.1999999 27.90483 32.68898 -15.62669 17.03397 34.71567 -8 15.02297 34.71568 -8.500018 15.02297 22.88341 -17.09272 26.76358 23.05256 -17.2312 26.59574 20.50851 -6.935604 29.12008 34.04998 -12.79883 15.6835 34.46316 -11.18647 15.27353 34.68121 -9.500018 15.05717 20.51299 -6.856955 29.11564 26.06361 -18.65373 23.60801 27.2232 -18.82072 22.45741 24.16536 -17.96583 25.49156 25.40324 -18.47016 24.26327 25.73501 -18.5647 23.93406 33.4531 -14.29263 16.27577 23.0902 -17.26098 26.55839 28.43778 -18.71653 21.25224 29.62338 -18.33073 20.07582 30.74735 -17.67394 18.96056 20.50064 -0.1999999 29.12789 20.51153 -0.2651532 29.11709 20.51299 -0.3 29.11564 31.77869 -16.76424 17.93721 20.43466 -7.851187 29.19336 20.42846 -8 29.19951 20.42289 -8.809835 29.20504 20.45463 -9.808921 29.17354 22.43283 -16.68443 27.21067 20.59263 -11.75032 29.03661 20.8652 -13.48861 28.76616 20.93198 -13.77596 28.6999 22.23045 -16.47351 27.41148 21.33128 -15.01103 28.30369 21.59716 -15.56776 28.03986 2.873557 -8 0 3.008885 -8 -0.02341377 2.873557 -10 0 3.008885 -13.98923 -0.02341377 2.855663 -10 0.006895124 2.855663 -13.98923 0.006895124 2.725729 -13.98923 0.09357196 2.725729 -10 0.09357196 2.638895 -13.98923 0.2234006 2.638895 -10 0.2234006 2.608401 -13.98923 0.376586 2.608401 -10 0.376586 2.608401 -13.98923 1.889674 2.608401 -10 1.889674 -2.491599 -20.78648 3.585449 -2.491599 -10 3.585449 -2.220439 -10 3.903858 -2.462367 -20.95924 3.627262 -2.485485 -20.87298 3.594389 -2.422348 -21.02638 3.680959 -1.941632 -21.44697 4.12157 -1.889135 -21.48167 4.154058 -1.370787 -10 4.371359 -0.2981954 -10 4.405178 -0.449914 -22.11895 4.427219 -0.5221658 -22.09625 4.434953 -1.239677 -21.82565 4.401827 -1.266123 -21.81391 4.396362 -1.330402 -21.78474 4.38167 1.286473 -10 3.709312 1.286477 -22.40365 3.709309 1.27947 -22.40393 3.714409 1.221374 -22.40559 3.755912 0.9473126 -22.39879 3.933704 0.4733356 -22.34176 4.175066 0.3544617 -22.32056 4.22323 0.2310722 -22.29603 4.268287 -0.299643 -22.16378 4.405387 2.411623 -10 2.479053 2.413721 -21.87829 2.475016 2.122184 -22.17202 2.911698 1.943293 -22.26877 3.121548 1.591412 -22.37195 3.465745 1.382857 -22.3979 3.63701 2.107333 -22.18167 2.930315 2.557765 -14.0726 2.139996 2.524711 -14.16257 2.235364 2.482391 -21.754 2.336817 2.449433 -21.81858 2.406234 2.508401 -14.28923 2.276518 2.512882 -14.22244 2.265506 2.490362 -21.73441 2.318933 2.508401 -21.60413 2.276518 2.504278 -21.67333 2.286472 42.0042 3 64.95001 42 3 67.41297 42.0084 3 67.41297 42.00007 3 64.90646 42.00434 3 64.86294 42.07752 3 63.43943 42.02238 3 64.15135 42.02624 3 64.15138 40.6 0.3751289 67.41297 40.4084 0.2741799 67.41297 42 2.8 67.41297 42.2084 -0.00605905 67.41297 42.44091 -0.02946698 67.41297 42.27122 0.03687548 67.41297 42.0084 0.5014023 67.41297 41.62487 1.4 67.41297 42.04205 0.313437 67.41297 42.13307 0.1556454 67.41297 40.25677 -7.998615 85.409 40.01424 -7.980129 85.409 40.01424 -12.89295 85.409 41.00834 -11.60555 85.409 41.00834 -8 85.409 40.34308 -8 85.409 2.239719 -8 87.22291 2.239719 -14.5 87.22291 2.411329 -8.000001 87.55995 2.920334 -14.5 88.2012 3.928124 -14.5 88.8373 3.49623 -8.000505 88.63247 2.713616 -8.000174 87.98267 5.223824 -7.829246 89.02402 4.92409 -7.9114 89.03207 5.104053 -14.5 89.03084 4.361419 -8.000147 88.9314 3.928124 -8.000659 88.8373 6.015515 -7.619611 88.85345 6.262549 -14.5 88.75128 6.262549 -7.616895 88.75128 18.14124 -8.000664 88.80995 17.64021 -8.000156 88.93104 16.89595 -14.5 89.03084 17.07583 -7.911381 89.03207 18.07188 -14.5 88.8373 19.07967 -14.5 88.2012 19.00399 -8.000318 88.27111 19.58742 -8.000005 87.56206 19.76028 -14.5 87.22291 19.76028 -8 87.22291 16.77618 -7.829246 89.02402 15.98447 -7.619609 88.85345 15.73745 -14.5 88.75128 15.8184 -7.609794 88.78762 15.73745 -7.616895 88.75128 -2.491599 -14.64784 0.369324 -2.529601 -14.64784 0.1781221 -2.491599 -10 0.369324 -2.558485 -10 0.1194986 -2.74125 -14.64784 -0.06348675 -2.654553 -10 0 -2.637832 -14.64784 0.01598435 -2.558485 -14.64784 0.1194986 -2.990994 -14.64784 -0.1306756 -2.990994 -8.5 -0.1306756 -2.799838 -14.64784 -0.09244203 -2.809539 -8.5 -0.09635215 -2.74125 -8.5 -0.06348675 -2.654553 -8.5 0 -15.0916 -8.308312 -0.1071169 -15.0916 -8.147577 0 -2.991152 -8.162956 0 -2.991035 -8.318221 -0.09646111 -15.0916 -8.5 -0.1453216 35.86429 -0.1999999 15.74215 35.86356 -0.25 15.74715 38.17945 -0.25 16.30034 40.35894 -0.25 17.25905 39.34029 -0.1999999 16.74701 38.18106 -0.1999999 16.29555 39.53608 -0.05155014 16.73362 39.43817 -0.09859555 16.74049 40.36814 -0.1543291 17.24239 39.37197 -0.1523826 16.74494 39.35631 -0.1718685 16.74597 40.39433 -0.07322329 17.19494 40.43352 -0.01903009 17.12394 39.65826 -0.01766139 16.72455 43.41786 0.04970836 51.69968 42.44479 -0.6659969 50.95619 42.18235 -0.4169142 50.02568 43.56813 0.4887732 50.97877 43.38594 0.3277283 50.77126 42.86136 0.1001518 49.80036 42.15724 -0.1999999 49.3445 41.94675 -0.2220842 49.08925 41.9178 -0.1999999 48.96374 42.26153 2.80043e-4 48.628 42.57225 0.02982401 49.28041 42.22278 -0.01270037 48.61678 44.34759 2.054254 53.39269 44.07014 0.9883826 52.5395 44.22304 1.39941 52.56538 44.19361 1.322106 52.45764 43.76765 0.6688865 51.3702 43.98228 0.8120055 52.38923 39.48776 -0.3619644 46.40192 39.63323 -0.3871483 46.56661 39.5942 -0.4497938 46.56394 39.3591 -0.06147515 46.43012 39.45329 -0.1254867 46.43749 39.45417 -0.1292854 46.43455 39.51163 -0.1999999 46.44205 39.48817 -0.2407957 46.40152 39.64665 -0.3461493 46.56753 39.64935 -0.2683004 46.56771 39.62717 -0.1999999 46.5662 39.29936 -0.4467367 46.2592 39.45301 -0.4730244 46.43568 39.55305 -0.4908408 46.56114 39.3244 -0.3370082 46.23328 39.32599 -0.2971841 46.23164 39.31879 -0.2217944 46.23909 39.28335 -0.1181721 46.27577 39.22332 -0.04149967 46.33789 39.15 -0.003661394 46.41377 39.06424 -0.4107237 46.019 39.07709 -0.2673093 46.00447 38.97255 -0.03490632 46.12263 39.04396 -0.1315023 46.04192 38.19139 -0.3 45.30072 38.17821 -0.1851949 45.31937 38.16819 -0.15 45.33354 38.08449 -0.02283608 45.45195 38.1048 -0.04019236 45.42321 38.14067 -0.08786791 45.37247 32.17473 -0.1851949 42.01369 32.17779 -0.3 41.99106 30.37795 -0.3 41.61879 28.93964 -0.1999999 41.1434 29.08623 -0.1392406 41.23401 30.3671 -0.15 41.65748 29.40391 -0.06414371 41.42659 29.56533 -0.0395264 41.52258 30.33745 -0.04019236 41.76322 32.15295 -0.02283608 42.17458 32.1724 -0.15 42.03089 32.166 -0.08786791 42.07814 32.15767 -0.04019236 42.1397 28.64693 -0.3 41.00105 28.64006 -0.1999999 41.01677 27.01803 -0.3 40.14974 27.00905 -0.1999999 40.16436 25.52261 -0.3 39.08122 25.51169 -0.1999999 39.09446 24.18941 -0.3 37.81607 24.17677 -0.1999999 37.82767 23.0441 -0.3 36.37861 23.02997 -0.1999999 36.38835 22.10871 -0.3 34.7965 22.09337 -0.1999999 34.80419 21.40122 -0.3 33.10018 21.38497 -0.1999999 33.10567 20.93526 -0.3 31.32229 20.91841 -0.1999999 31.32548 20.71979 -0.3 29.49703 20.70266 -0.1999999 29.49785 -15.0916 -7.5 0 -15.0916 -7.5 -0.1453216 25.82394 -12.32839 85.41296 26.0149 -12.52185 85.41296 26.0149 -7.975761 85.41296 22.51415 -10.81118 85.41296 23.52254 -11.0008 85.41296 25.65181 -8 85.41296 24.29824 -11.28796 85.41296 25.18703 -11.80067 85.41296 1.287322 -11.5916 86.01406 1.588286 -12.24217 86.27292 1.878748 -13.1408 86.60353 2.089341 -14.13635 86.92237 2.119318 -14.32817 86.976 2.143555 -14.5 87.02133 2.143555 -8 87.02133 0.005724668 -10.36776 85.45835 -0.3779382 -10.33141 85.41605 -0.4460897 -10.33883 85.41372 -0.5141522 -10.35042 85.41296 0.3133202 -10.49479 85.52933 0.6909502 -10.78023 85.66564 0.9201455 -11.03263 85.77803 21.48743 -11.06003 85.59412 21.76619 -10.89984 85.50769 22.1599 -10.79342 85.43395 22.43445 -10.79789 85.41401 21.10788 -11.40642 85.76297 21.02392 -11.50591 85.80927 19.89054 -14.5 86.95808 20.043 -13.73087 86.71195 20.33497 -12.76933 86.35112 20.65467 -12.06576 86.05874 -4.064463 -12.11764 85.41296 -3.663353 -11.72122 85.41296 -4.064463 -7.968719 85.41296 -2.837289 -11.11275 85.41296 -3.805429 -7.995624 85.41296 -3.651809 -8 85.41296 -2.09568 -10.73989 85.41296 -1.116672 -10.44032 85.41296 42.2084 -2.99 85.22474 42 -8 85.28413 42.5282 -10.88028 85.109 43.38656 -10.34772 84.62522 43.6509 -2.99 84.41181 43.84131 -9.999867 84.23287 44.55062 -9.260519 83.26702 44.65321 -2.99 83.05669 45.00834 -8 81.409 45.00834 -2.99 81.409 45.00827 -8.015653 81.43267 44.7047 -9.02808 82.93768 -2.491599 -20.90245 3.401225 -2.491599 -20.71905 3.173046 -2.491599 -17.29977 0.8190304 -2.491599 -16.17909 0.5163338 -2.491599 -19.6524 2.125362 -2.491599 -18.68116 1.455931 -2.821997 -8.318221 -0.0644865 -2.699634 -8.331606 0 -2.822818 -8.208259 0 36.025 -8 0.2128129 36.025 -8 0.01654875 36.01972 -8 0.2127943 36.01911 -8 0.01653993 26.375 -8 0.2127943 26.375 -8 0.004867196 -31.7739 -7 -0.2784677 -30.825 -7 -0.2773193 -30.825 -7 -0.1643643 -31.76574 -7 -0.1655029 -33.69125 -7 0.2176032 -33.9705 -7 0.2053292 -35.32083 -7 1.312516 -35.75731 -7 1.571519 -36.40324 -7 2.950429 -36.8 -7 3.564489 -36.78481 -7 4.864673 -36.78311 -8 15.25509 -36.85488 -8 15.36589 -36.8 -8 14.35429 -36.46846 -8 16.4475 -36.5367 -8 15.42854 -36.7716 -8 13.914 -36.7858 -8 8.050001 -35.25089 -8 18.54635 -35.77054 -8 17.80753 -36.18895 -8 17.07934 -33.16252 -8 20.97763 -32.58888 -8 21.6329 -32.22562 -8.712735 22.13568 -39.8159 -2.752025 29.54485 -38.62839 -6.029355 28.71335 -36.64101 -8.666837 27.32177 -34.06467 -10.38458 25.51779 -31.84206 -10.96247 23.9615 -31.67816 -11 23.84674 -30.825 11 11 -30.825 11 0 -30.825 10.33062 -3.778672 -30.825 8.403935 -7.097455 -30.825 -10.9965 -0.2773193 -30.825 -10.38369 -3.630282 -30.825 -8.504755 -6.976329 -30.825 -5.590736 -9.473314 -30.825 -7 0.0992316 -30.825 5.454443 -9.552437 -30.825 1.841113 -10.84483 -30.825 -1.996292 -10.81734 -36.8 -4.059227 12.6019 -36.8 -2.09037 12.29491 -36.8 -7.158224 7.000737 -36.8 -8 3.564489 -36.8 -8 -0.04996067 -36.8 3.226537 -7.320482 -36.8 -5.760751 13.13765 -36.8 -7.369039 13.94107 -36.8 8 11 -36.7858 -7 6.635787 -36.8 -7.040527 6.832978 -36.8 -4.930331 -6.300146 -36.8 -6.324011 -4.899682 -36.8 -7.331962 -3.200365 -36.80003 8 14.35487 -36.8 6.323191 13.38157 -36.8 4.536248 12.72431 -36.8 2.514578 12.33802 -36.8 0 12.21355 -36.8 -7.333333 7.107191 -36.8 -7.683552 7.320099 -36.8 -7.918946 7.655617 -36.8 1.34005 -7.886969 -36.8 0 -8 -36.8 -7.892704 -1.305844 -36.8 -1.344153 -7.88627 -36.8 -3.235929 -7.316336 -36.8 8 0 -36.8 7.886969 -1.34005 -36.8 7.320482 -3.226537 -36.8 6.310221 -4.917428 -36.8 4.917429 -6.310222 -31.7739 -10.99647 -0.2784677 -33.8 -10.38369 -3.630282 -33.03819 -10.9993 -0.1240092 -33.8 -10.85247 -1.795536 -33.30476 -10.99989 -0.04996067 -33.84737 -10.99913 -0.04996067 -33.8 8.403935 -7.097455 -33.8 8.676554 -6.761465 -33.8 10.06566 -4.436489 -33.8 10.33062 -3.778672 -33.8 10.84458 -1.842568 -33.8 11 0 -33.8 6.761465 -8.676554 -33.8 5.454443 -9.552437 -33.8 4.436489 -10.06566 -33.8 1.842568 -10.84458 -33.8 -4.449402 -10.05996 -33.8 -1.84821 -10.84362 -33.8 0 -11 -33.8 -6.779205 -8.662701 -33.8 -5.590736 -9.473314 -33.8 -10.08145 -4.400503 -33.8 -8.695515 -6.737062 -33.8 -8.504755 -6.976329 -36.75905 -8.331245 15.2857 -36.60806 -8.995011 15.34819 -36.7019 -8.667995 15.30545 -31.84264 -11 23.61181 -34.58244 -11 19.69899 -34.61785 -10.9996 19.65036 -34.63477 -10.99927 19.62792 -34.84316 -10.98184 19.35059 -35.25437 -10.87692 18.7975 -35.45339 -10.78916 18.51328 -36.29978 -10.26094 18.32885 -36.6335 -9.630109 17.24514 -36.70282 -9.82072 18.24103 -36.92342 -9.479011 18.19297 -36.83929 -8.218725 15.38347 -36.82837 -8.337017 15.38486 -36.86109 -8.279238 15.65517 -36.77154 -8.676156 15.40277 -36.67847 -9.005521 15.44309 -36.62184 -9.161471 15.48659 -36.89535 -8.360342 16.01038 -37.04026 -8.631823 17.16682 -37.10973 -8.745037 17.64838 -37.18205 -8.857699 18.13663 -34.78084 -10.9624 19.76447 -39.17504 -6.029355 27.93265 -38.86058 -6.577975 27.71248 -39.96082 -4.216639 28.48287 -40.36255 -2.752025 28.76416 -36.56306 -10.00648 23.58888 -35.66645 -10.64152 21.76241 -38.23591 -7.857988 26.65407 -37.72815 -8.669953 25.76202 -37.44307 -9.058033 25.2476 -34.84634 -10.96191 19.64333 -37.27032 -9.411594 19.65095 -37.5504 -9.174956 20.40674 -37.38026 -9.084086 19.39775 -37.77455 -9.165685 21.68707 -37.3122 -9.714802 21.31856 -37.85725 -9.125651 22.15164 -37.91339 -9.104361 22.64842 -37.98789 -9.020464 22.88069 -37.19299 -9.769972 23.14676 -37.87092 -9.000868 24.46589 -38.02116 -8.985171 23.06568 -38.62675 -7.614321 26.42286 -38.48486 -8.078951 25.63742 -38.33836 -8.457077 24.8251 -35.81246 -10.71782 20.17951 -36.50033 -10.34322 21.71396 -37.6955 -9.185369 21.23974 -36.70692 -10.15118 19.88081 -37.19042 -8.585906 17.81177 -36.81494 -1.25354e-7 12.63672 -36.85742 -7.343797 14.90762 -38.80732 -7.567835 26.1159 -38.80179 -7.646891 25.9363 -38.788 -7.823812 25.47622 -38.78639 -7.842635 25.42105 -38.73314 -8.206122 23.45326 -38.72037 -8.206205 22.93115 -37.84289 -9.066388 21.71215 -37.82737 -8.760194 20.58793 -37.81484 -8.283812 19.52601 -37.1884 -7.675853 16.81881 -38.72102 -3.522624 17.0112 -38.77141 -2.843359 16.88723 -37.92713 -2.621569 15.8852 -38.86776 -1.849929 16.82413 -38.07326 1.38296e-7 15.90917 -38.96991 -0.689181 16.8411 -37.86127 -3.809265 16.06044 -37.82483 -4.922519 16.4293 -38.67382 -4.495684 17.3361 -37.80786 -5.946931 16.9814 -38.65175 -5.384617 17.81621 -37.80309 -6.861699 17.69712 -38.64629 -6.48536 18.74323 -38.71925 -8.204245 22.88423 -38.7149 -8.193396 22.70001 -38.69725 -8.090636 21.9201 -38.68671 -7.975021 21.42297 -37.80625 -7.646471 18.55362 -38.66083 -7.409017 20.02025 -38.67649 -7.811461 20.90931 -37.43933 0 14.90854 -36.93684 0 13.48765 -37.26931 -2.809127 14.72579 -36.88996 -3.01532 13.45119 -37.22596 -4.151842 14.92416 -36.8713 -4.526565 13.68125 -37.20235 -5.430839 15.34936 -36.8617 -5.985293 14.17141 -37.19145 -6.615503 15.98884 -34.11541 -10.98318 -0.04996067 -34.83836 -10.81447 -0.04996067 -34.83835 -10.66953 -1.765269 -35.49274 -10.47605 -0.04996067 -35.92133 -10.12118 -0.04996067 -35.92132 -9.985573 -1.652108 -36.29565 0 -9.664842 -35.92208 0 -10.12056 -35.92132 -1.700575 -9.977434 -35.46913 0 -10.49279 -34.83835 0 -10.81457 -34.83835 -1.817055 -10.66083 -36.74252 0 -8.584457 -36.61457 0 -9.038352 -36.61457 -1.518616 -8.90986 -36.57164 0 -9.148036 -36.61457 -3.655933 -8.265952 -36.61457 -5.570258 -7.117866 -36.61457 -7.144829 -5.53563 -36.61457 -8.283606 -3.615754 -36.61457 -8.917129 -1.475335 -36.45386 -9.398735 -0.04996067 -34.83835 -9.911506 -4.326324 -34.83835 -8.548936 -6.623497 -34.83835 -6.664929 -8.516674 -34.83835 -4.374399 -9.890381 -35.92132 -4.093984 -9.256373 -35.92132 -6.237683 -7.970724 -35.92132 -8.000918 -6.198906 -35.92132 -9.276142 -4.04899 -41.98481 -2.078503 22.43569 -39.44185 -3.833254 17.89891 -40.02994 -5.647982 26.93356 -40.58638 -5.49103 25.68693 -39.15869 -7.663368 24.68725 -39.59449 -7.313885 23.48236 -39.04639 -7.674705 21.66119 -39.88644 -6.824322 22.24941 -40.01577 -6.219707 21.05695 -39.78789 -4.697836 18.84578 -39.9837 -5.508764 19.91776 -40.65538 -1.280998 18.74864 -39.84402 -0.9638202 17.68589 -41.72768 -1.84092 21.13891 -41.27513 -1.569924 19.88716 -42.0469 -2.280554 23.76217 -41.58477 -2.560947 26.38602 -41.90993 -2.444156 25.10365 -41.05687 -2.634146 27.65263 -40.63912 -4.179968 27.36011 -41.17863 -4.063812 26.10163 -40.95706 -5.240615 24.43645 -41.5223 -3.878484 24.83224 -41.15782 -4.889829 23.13963 -41.68522 -3.618874 23.50892 -41.1745 -4.456604 21.86831 -41.65518 -3.298252 22.20488 -41.00999 -3.947192 20.63637 -41.43572 -2.921246 20.93448 -39.46828 -2.066566 17.42278 -40.15599 -2.74664 18.39895 -40.6631 -3.366139 19.45861 -27.12697 -2.613918 32.25586 -26.90366 -2.672033 31.99987 -26.47272 -3.67709 32.59236 -26.99839 -2.358243 31.8738 -27.75959 -1.854113 32.69883 -27.19101 -1.481944 31.63452 -28.1466 -0.8791561 32.96981 -27.30254 -0.4847767 31.5226 -36.7716 -7.333333 7.107191 -36.7716 -7.158224 7.000737 -36.7716 -7.040527 6.832978 -36.7716 -7.918946 7.655617 -36.7716 -7.683552 7.320099 -33.48769 -10.99989 0.009863734 -34.43727 -10.93142 0.4516338 -34.55667 -10.90292 0.5248018 -35.36021 -10.56168 1.150119 -35.49441 -10.4749 1.282217 -35.7167 -10.30738 1.523895 -36.78528 -8.296994 3.511177 -36.71945 -8.690351 3.295559 -36.42116 -9.459094 2.576025 -36.32208 -9.624401 2.389479 42.2084 -0.00605905 67.61297 42.2084 -0.006046772 67.69438 42.2084 -0.006046772 70.21218 42.2084 -0.006046772 73.01139 42.2084 -0.006046772 75.81059 42.2084 -0.006046772 78.6098 42.2084 -0.006046772 81.409 35.26108 -0.1999999 14.93363 35.26108 -3.002625 14.93363 -21.175 -7 0.1246222 42.26996 -15.96091 2.591812 42.2418 -10.80809 2.564061 42.94095 -15.90305 3.335416 42.45528 -10.73917 2.780819 43.82124 -15.64559 4.654077 42.8282 -10.59167 3.198189 44.1791 -15.47413 5.388258 43.4322 -10.27125 4.007743 44.85776 -15.01485 7.969048 44.73938 -15.10979 7.190607 44.90643 -13.73623 8.7322 44.9065 -13.53729 8.735527 44.89004 -14.84519 8.346134 44.87709 -14.96024 8.17136 44.89999 -14.61382 8.531104 44.90359 -14.40311 8.625903 44.02095 -9.83583 5.042522 44.17881 -9.690975 5.38759 44.31122 -15.39957 5.711511 44.37328 -9.490029 5.87718 44.55042 -9.279051 6.417969 44.83416 -8.856748 7.769877 44.9065 -8.73472 8.735527 37.75388 -15.96091 0.1893878 36.025 -11 0.01654875 39.42168 -15.96091 0.6971006 39.37984 -11 0.6798507 40.93771 -15.96091 1.506319 40.95137 -11 1.51542 42.00563 -10.87177 2.340635 36.01911 -15.96091 0.01653993 26.375 -11 0.004867196 17.75 -8 -0.005571961 17.91905 -8.992829 -0.005367517 20.11266 -14.02943 -0.002712309 19.96266 -13.98923 -0.002893924 20.09125 -10.92678 -0.002738416 20.75 -11 -0.001941204 22.35372 -11 0 20.22247 -14.13923 -0.002579629 20.26266 -14.28923 -0.002530753 20.26266 -15.96091 -0.002530753 18.40727 -9.873923 -0.004776597 19.15961 -10.54375 -0.003865778 19.60195 -10.77164 -0.003330707 -15.5 -7.008462 -0.1458156 -15.5 -7.008462 0 -15.29043 -7.100879 0 -15.29043 -7.100879 -0.1455623 -15.14406 -7.277048 0 -15.14406 -7.277048 -0.1453849 42.44091 -0.03003782 67.52523 42.44074 -0.03001469 67.6126 42.61596 -0.06369072 66.94857 42.38147 0.02783721 66.94766 42.54245 0.02789902 66.27999 42.25202 0.3160369 66.27259 42.17943 0.2026 66.94609 42.04985 0.4361968 66.94404 42.0084 0.6844804 66.94189 42.20593 0.6245077 64.92555 42.0084 1.488927 64.86296 42.0084 1.484822 65.12069 42.08016 0.8870278 65.58515 42.06774 0.6812511 66.26322 42.0084 1.395701 65.5318 42.0084 1.124832 66.14482 43.13632 -0.3062471 64.99293 42.89285 -0.1485887 66.27673 42.75253 -0.06355708 64.97536 42.68138 -0.003515601 64.97101 42.2084 -0.7428959 84.13938 42.72481 -0.4566686 83.35946 42.2084 -0.3043623 83.39956 42.2084 -2.376936 85.15809 43.40394 -1.542342 84.13118 42.2084 -1.541951 84.83062 42.2084 -1.488909 84.79873 44.31258 -1.542342 82.9027 43.37585 -0.4566686 82.47924 42.2084 -0.05039918 82.4005 44.63452 -1.542342 81.409 43.60652 -0.4566686 81.409 45.00834 -2.99 67.69438 44.83602 -1.989627 67.69438 43.62177 -0.4662894 67.69438 44.18947 -0.9342128 67.69438 44.63887 -1.550235 67.69438 43.17089 -0.2310664 67.69438 44.05178 -0.9342128 65.40015 43.20976 -0.4286482 64.10177 43.28587 -0.6069733 63.2256 43.87161 -1.218743 63.08239 44.69368 -1.989627 65.32282 44.31162 -2.124072 62.97481 44.86476 -2.99 65.30221 44.43609 -2.99 62.94438 20.64352 -0.1999999 29.28851 20.65856 -0.3 29.28025 34.86748 -3.090774 14.87396 34.75691 -3.269396 14.98452 35.15885 -3.083438 15.15014 35.17027 -3.263644 15.39358 35.16619 -0.2506735 15.37931 35.27579 -3.471454 15.58194 35.27579 -0.4857268 15.58194 35.27489 -0.4756341 15.58092 35.26951 -0.4619381 15.57476 35.27445 -0.4736123 15.58043 35.1602 -0.1999999 15.14369 35.15398 -0.1999999 15.31986 35.19823 -3.028241 15.0327 -8.129328 -8.008399 84.11455 -8.568182 -8.177098 84.00794 -8.885489 -8.53534 83.94242 -5.887493 -7.551508 84.97338 -6.037596 -7.55091 84.89793 -5.887493 -12.38038 84.97338 -6.075965 -7.551275 84.87909 -6.202408 -7.559607 84.8183 -7.944966 -7.986277 84.16498 -6.285313 -13.14293 84.7795 -7.110949 -7.802872 84.43647 -7.017931 -7.773761 84.47129 -6.520378 -13.78921 84.67391 -8.261513 -14.5 84.08046 -6.69331 -14.5 84.60031 -9 -9 83.9211 -9 -9.004487 83.9211 -9.143492 -9.506356 83.89613 -9.355443 -9.743202 83.86274 -9.127268 -9.479436 83.89886 -9.023364 -9.214381 83.9169 -9.475065 -9.82379 83.84574 -9.635213 -9.895741 83.82501 -10.22995 -14.5 83.76849 -9.95 -9.946413 83.79111 -12.22251 -14.5 83.81034 -12.05 -9.946559 83.79262 -12.22251 -9.932393 83.81034 -4.82851 -12.22445 85.3393 -4.997925 -7.732981 85.30251 27.85792 -7.584428 84.96306 26.95826 -7.753763 85.30012 27.85792 -13.66095 84.96306 26.60054 -7.853807 85.36985 27.18596 -13.19915 85.23769 26.1646 -12.60126 85.41016 26.02907 -12.52929 85.41293 37.41506 -7.687186 84.60243 37.18038 -7.750659 84.5054 35 -9 83.88007 36.96423 -7.812143 84.42147 36.89205 -7.832218 84.39457 35.90687 -8.004347 84.08225 35.45209 -8.163466 83.97098 35.12025 -8.52456 83.90236 36.03851 -7.993303 84.11825 38.17322 -13.32326 84.96015 38.17322 -7.607247 84.96015 37.98005 -7.606793 84.86236 34.94721 -9.31339 83.87071 34.87273 -9.47564 83.85794 37.49997 -13.94716 84.63909 34.79433 -9.590256 83.84506 28.07238 -14.5 84.85463 30.105 -14.5 84.08892 27.96892 -14.07838 84.90622 31.23619 -14.5 83.84607 31.23619 -9.627076 83.84607 31.06087 -9.336281 83.87576 31 -9 83.88674 30.88113 -8.527134 83.90917 30.5528 -8.166684 83.97812 30.10181 -8.005197 84.08979 29.95742 -7.991806 84.12976 29.61917 -7.946952 84.23166 29.13884 -7.831814 84.39674 28.4777 -7.643493 84.6651 28.0272 -7.584778 84.877 34.52494 -9.819937 83.80516 34.52318 -14.5 83.80492 36.63711 -14.5 84.30409 34.46323 -9.851952 83.79695 34.05 -9.942454 83.75098 32.29991 -14.5 83.72644 31.95 -9.942801 83.75444 31.5585 -9.862354 83.79892 39.63344 -12.98848 85.39083 39.38456 -7.85418 85.35913 39.29956 -13.0693 85.34464 39.07001 -7.769585 85.29595 8.879969 -8.524969 87.90248 8.54869 -8.163974 87.97155 9 -9 87.88002 8.094512 -8.004477 88.08344 7.960781 -7.993054 88.12024 8.545011 -14.5 87.97237 9.375262 -9.754577 87.81848 9.098804 -9.422699 87.86254 7.167241 -7.84624 88.37622 12.62474 -14.5 87.81848 12.62474 -9.754577 87.81848 12.52494 -9.819853 87.8043 12.35303 -9.895667 87.78203 12.05 -9.942288 87.74933 11 -14.5 87.7 9.95 -9.942288 87.74933 9.646702 -9.895579 87.78206 14.8561 -7.839867 88.38475 13 -9 87.88002 15.13143 -7.761275 88.48986 13.90549 -8.004477 88.08344 13.45131 -8.163974 87.97155 13.12003 -8.524969 87.90248 14.03922 -7.993054 88.12024 12.90133 -9.422439 87.86257 12.8727 -9.475665 87.85767 13.45499 -14.5 87.97237 -15.66726 -8.986545 -0.1460182 -15.5 -7.998672 -0.1458156 -31.76574 -11.23341 -0.1655029 -30.14191 -11.24566 -0.1635373 -28.73779 -11.26834 -0.1618381 -22.37895 -11.53332 -0.1541417 -17.83622 -10.92463 -0.1486431 -17.46165 -10.81356 -0.14819 -16.51943 -12.06233 -0.1470496 -16.90525 -10.53998 -0.1475167 -13.22441 -12.50407 -0.1430617 -16.15401 -9.868755 -0.1466073 -21.175 -7 -0.1526846 -21.175 -10.99894 -0.1526846 -18.5 -10.99898 -0.1494469 -3.098868 -14.61885 -0.130806 -8.132303 -13.41876 -0.1368982 -2.678354 -21.01803 2.92307 -2.679745 -21.21174 3.162299 -2.880135 -21.28817 3.103244 -2.540699 -20.88482 3.034448 -2.541084 -21.07409 3.268642 -3.102588 -21.28825 3.103165 -2.87753 -21.09252 2.860787 -3.099109 -21.09367 2.859831 -2.862714 -19.95586 1.749463 -3.086498 -20.38189 2.107574 -2.670482 -19.89314 1.827155 -2.849693 -18.92278 1.041825 -2.663623 -18.87136 1.129959 -2.831888 -17.45613 0.3717673 -2.654328 -17.42158 0.4705909 -2.818018 -16.26831 0.05599772 -2.647152 -16.24805 0.1605238 -3.079135 -19.96162 1.742325 -3.061326 -18.93068 1.028287 -3.036592 -17.4641 0.3489559 -3.017025 -16.2741 0.02610367 -2.538522 -19.78524 1.960817 -2.536633 -18.78567 1.276812 -2.534086 -17.36633 0.6286317 -2.53213 -16.21661 0.322735 -2.484989 -20.94001 3.493706 -2.525234 -21.12104 3.357928 -2.661231 -21.27831 3.259957 -2.864244 -21.37858 3.220498 -3.091374 -21.40068 3.247887 -3.056401 -21.50593 3.379773 -2.830385 -21.46183 3.324698 -2.629295 -21.33847 3.344927 -2.498226 -21.16353 3.435925 -2.46657 -20.97624 3.577283 -2.997817 -21.60845 3.503349 -2.779433 -21.54129 3.419528 -2.585149 -21.39472 3.420245 -2.460991 -21.20348 3.505332 -2.436375 -21.01287 3.65463 -2.970405 -21.6451 3.545924 -2.756715 -21.56925 3.451474 -2.566287 -21.41422 3.44507 -2.44508 -21.21743 3.528258 2.618624 -21.84832 1.95892 2.698559 -21.8984 1.897486 2.558445 -21.78822 2.032658 2.536761 -21.75534 2.072993 2.508401 -21.65046 2.201661 2.843231 -22.21306 2.056718 2.900663 -21.96051 1.824486 2.744704 -21.91886 1.872385 2.900697 -21.95895 1.823202 2.516859 -21.9271 2.185225 2.571104 -22.01296 2.12685 2.646496 -22.09202 2.084596 -1.37538 -21.98071 4.227842 -1.287173 -22.02131 4.248744 -0.5154262 -22.31147 4.288125 1.338355 -22.57678 3.542745 1.926852 -22.43286 3.028637 2.801346 -22.29721 2.146037 2.651383 -22.20634 2.153684 2.534075 -22.0861 2.204535 2.463875 -21.95132 2.292324 2.100603 -22.33864 2.834279 2.148122 -22.50717 2.777271 2.243444 -22.6644 2.767024 2.373641 -22.78899 2.804929 1.96421 -22.6121 2.980578 2.050013 -22.78078 2.984258 2.171963 -22.91474 3.039151 1.343498 -22.78166 3.513355 1.397407 -22.9774 3.553878 1.490837 -23.13045 3.657366 1.170732 -22.58699 3.659164 1.167592 -22.79706 3.63285 1.212517 -22.99813 3.681689 1.297452 -23.15413 3.796921 0.4105648 -23.13488 4.278409 0.2715672 -23.11719 4.332113 0.3702644 -22.97383 4.118236 0.2389746 -22.95641 4.166438 0.368407 -22.75683 4.04002 0.2439736 -22.73803 4.084945 0.4053879 -22.53004 4.06041 0.2854775 -22.50951 4.105355 -0.5832153 -22.54694 4.262548 -0.6368222 -22.76822 4.3567 -0.6632313 -22.92156 4.547721 -1.376478 -22.25484 4.210499 -1.484741 -22.46647 4.296882 -1.584257 -22.60206 4.485785 -1.466985 -22.21326 4.187665 -1.581734 -22.4228 4.271439 -1.690211 -22.55559 4.457687 -1.970938 -21.64347 3.967689 -2.078696 -21.86307 3.910066 -2.237683 -22.05027 3.963257 -2.407738 -22.1578 4.113824 2.508401 -16.46593 0.376586 2.508401 -14.28923 0.376586 2.546519 -14.28923 0.1851046 2.546519 -16.46593 0.1851046 2.655062 -14.28923 0.02281886 2.655062 -16.46593 0.02281886 2.817479 -14.28923 -0.08552742 2.817479 -16.46593 -0.08552742 3.009006 -14.28923 -0.1234136 3.009006 -16.46593 -0.1234136 2.536778 -21.74589 2.065237 2.508401 -21.64117 2.194103 2.618689 -21.83872 1.950999 2.744835 -21.90912 1.864355 2.508401 -20.60731 1.481948 2.538692 -20.69316 1.333613 2.508401 -19.20863 0.8406422 2.541307 -19.26743 0.6722204 2.508401 -18.02553 0.5236023 2.543541 -18.05995 0.3427152 2.625897 -20.76861 1.203251 2.635692 -19.31848 0.5259659 2.64402 -18.08953 0.1872532 2.759447 -20.82452 1.106657 2.779134 -19.35508 0.4211302 2.795716 -18.11011 0.07906752 2.900898 -21.94912 1.81514 2.923162 -20.85411 1.055536 2.952753 -19.3724 0.3715116 2.977307 -18.11881 0.03336519 35.33865 -0.3259933 15.60175 35.4318 -0.1999999 15.59769 40.61427 -0.02794003 17.22096 40.58876 -0.105515 17.30641 40.5763 -0.2153852 17.34816 40.57568 -0.2391419 17.35024 40.57967 -0.3329926 17.33688 40.77825 -0.02347695 17.24252 40.77248 -0.08949851 17.32823 40.76914 -0.1856647 17.37803 40.76883 -0.2939141 17.38255 40.77163 -0.3939158 17.34095 40.94675 -0.02924382 17.23737 40.97304 -0.1101337 17.32332 40.98515 -0.2237454 17.36292 40.98025 -0.3434994 17.34689 40.95948 -0.4413791 17.27899 41.82615 -0.4441947 16.99246 42.68152 -0.4464862 16.67434 41.85012 -0.3467714 17.06149 42.70866 -0.3494732 16.74403 41.85615 -0.2263858 17.07884 42.71582 -0.2285801 16.7624 41.8428 -0.1116035 17.04041 42.70128 -0.1128292 16.72506 41.81324 -0.02966034 16.95531 42.66852 -0.03000825 16.64097 43.44428 -0.01858437 16.10777 42.98229 -0.02889764 16.48542 43.47566 -0.02550166 16.09931 43.02786 -0.1089101 16.56269 43.61559 -0.07773274 16.06072 43.69541 -0.1378139 16.03809 43.0492 -0.2215399 16.59886 43.73492 -0.1989506 16.02672 43.88441 -0.1999999 15.85323 43.75872 -0.1999999 16.00076 43.75694 -0.3105185 15.99917 43.04136 -0.3407492 16.58557 44.18159 -0.1999999 15.43725 44.18389 -0.2840637 15.4387 44.50806 -0.1999999 14.82902 44.69516 -0.2387607 14.37367 44.64751 -0.1999999 14.49135 44.84915 -0.2182716 13.84517 44.84216 -0.1999999 13.86101 45.00834 -0.25 12.55014 45 -0.1859726 12.55014 45 -0.1999999 12.73567 44.99933 -0.1999999 12.7705 44.96152 -0.1999999 13.21555 44.84451 -0.3078771 13.84405 43.00616 -0.4389789 16.52589 43.71891 -0.4107344 15.96506 44.15317 -0.3835474 15.41931 44.68217 -0.3325425 14.36914 45.00834 -0.25 9.037966 45 -0.1859726 9.037966 35.25503 -3.5 15.56233 -13.15986 -15.74962 47.5486 -13.14167 -15.51994 47.56034 -13.11733 -15.75921 47.44137 -13.0773 -15.57538 47.40028 -13.1006 -15.76709 47.32711 -13.16911 -15.24431 47.61963 -13.25912 -15.45611 47.68266 -13.31194 -15.72746 47.71965 -13.0268 -15.49705 47.16542 -13.07448 -15.61516 47.22353 -13.10224 -15.77026 47.26924 -13.01369 -15.43586 47.34332 -13.06349 -15.34742 47.50226 -13.06049 -15.08298 47.54358 -12.97149 -15.21828 47.4348 -12.95411 -15.25976 47.38731 -12.9397 -15.33298 47.28022 -12.95307 -15.38916 47.16317 -12.96996 -15.40962 47.10339 -13.1467 -15.77618 47.10201 -13.13953 -15.6693 47.06794 -13.13357 -15.63405 47.05328 -13.10095 -15.52229 46.99387 -13.05767 -15.43653 46.93122 -12.93749 -16.24127 47.67783 -12.91634 -16.25548 47.67643 -13.5442 -15.95438 48.06979 -12.45331 -16.45223 47.64696 -13.48348 -16.05172 48.23362 -12.45816 -16.45108 47.64728 -12.66025 -16.38753 47.66029 -13.51012 -15.62611 47.85841 -13.55358 -15.80452 47.93767 -13.25525 -15.90117 47.70578 -13.22997 -15.94555 47.70232 -13.20109 -15.98899 47.69898 -13.13033 -16.0758 47.69217 -13.75444 -15.47602 48.02949 -13.8078 -15.63837 48.11052 -13.8125 -15.77748 48.23855 -14.48956 -15.20331 48.80451 -13.76785 -15.87347 48.39528 -14.37461 -14.9137 48.46374 -14.45115 -15.0249 48.54832 -14.47594 -15.07695 48.60366 -14.49081 -15.12482 48.66588 -18.22279 -10.64587 51.41854 -18.20917 -10.51951 51.21769 -18.10785 -10.35626 51.07778 -18.48319 -9.852977 51.34059 -18.59531 -9.997874 51.48582 -18.62022 -10.11109 51.68885 -18.81428 -9.313855 51.57242 -18.93611 -9.439803 51.72283 -18.97078 -9.538883 51.92853 -19.55131 -8.150999 52.23411 -19.51984 -8.090434 52.13013 -19.27073 -8.754106 51.95605 -19.40097 -7.961926 51.98328 -19.39664 -7.958164 51.9802 -19.13904 -8.650714 51.79982 -19.49905 -8.06227 52.09051 -19.31464 -8.83581 52.16542 -19.55724 -8.195265 52.33436 -19.55594 -8.168488 52.27045 -21.1712 -5.768577 53.83314 -21.6794 -4.611959 54.18899 -21.76084 -4.596002 54.01243 -20.78508 -6.559434 53.13117 -19.55854 -8.209064 52.40989 -20.76278 -6.624938 53.31358 -20.74139 -6.4614 52.96826 -20.63834 -6.34576 52.84965 -19.62574 -8.065868 52.751 -20.67787 -6.64794 53.48771 -19.60902 -8.108878 52.68918 -19.57099 -8.193512 52.51308 -21.77328 -4.550559 53.82312 -21.71481 -4.482549 53.64987 -21.59435 -4.402325 53.51905 -22.29962 -2.361005 54.62327 -22.37892 -2.352836 54.44522 -22.38524 -2.329573 54.25162 -22.31763 -2.294756 54.07196 -22.18638 -2.253687 53.93359 -22.50962 0 54.77032 -22.58819 0 54.59175 -22.59245 0 54.39671 -22.52174 0 54.21488 -22.38683 0 54.07395 20.65782 -6.856955 29.27892 20.71979 -6.856955 29.49703 -36.7716 -14.7551 13.914 -36.5367 -14.7551 15.42854 43.28486 -0.5619027 57.7513 43.4029 -1.189164 57.33206 43.82482 0.4184012 55.83083 44.26805 2.535291 54.14696 42.79891 2.526927 59.55366 44.28099 2.536665 54.09416 43.15459 -0.06732791 58.21892 42.11055 2.705733 63.11965 42.11397 1.621373 63.09025 42.16381 1.59356 62.69122 42.3012 2.600369 61.818 42.19924 1.544924 62.44176 42.20822 1.529776 62.3819 42.48917 2.560585 60.86584 42.49144 1.18977 60.85537 42.72605 0.8905816 59.84473 43.06317 0.2049341 58.55205 42.05657 1.584454 63.68113 42.07946 2.775875 63.41903 42.07775 2.791752 63.43705 42.07756 2.797111 63.43914 42.07752 2.8 63.43943 39.8465 -0.200366 46.58117 -19.9916 -6.040742 55.21584 -19.9916 -5.768575 55.51778 -19.9916 -2.997754 57.64052 -19.9916 0 58.36642 37.4078 -0.04019236 44.95449 37.46618 -0.15 44.86148 37.48755 -0.3 44.82744 37.05389 -0.3 44.57085 36.98128 -0.04019236 44.7021 37.03443 -0.15 44.60601 34.62957 -0.04019236 43.43687 32.27903 -0.04019236 42.17967 34.68092 -0.15 43.33982 34.69972 -0.3 43.30429 32.35116 -0.3 42.04815 32.34018 -0.1851949 42.06817 32.33184 -0.15 42.08339 32.30891 -0.08786791 42.12519 25.31009 -13.91546 85.10625 25.07016 -14.11526 84.94741 24.84135 -14.6215 84.62564 23.92757 -15.73171 81.92294 23.94872 -15.70635 82.35065 23.79293 -15.38862 81.92885 23.96575 -15.69384 82.48696 24.12604 -15.58868 83.1659 24.2165 -15.17545 83.67212 24.15361 -15.56961 83.24679 24.29829 -15.44419 83.61587 25.93498 -12.70817 85.40805 26.00748 -12.53956 85.41291 24.61423 -13.583 84.94818 24.31674 -15.41661 83.66334 24.51745 -15.08431 84.12118 24.02587 -14.85573 83.67461 24.17965 -13.22178 84.94868 23.57271 -12.87068 84.94917 23.04271 -12.67398 84.94944 22.35349 -12.54407 84.94961 23.7258 -14.5044 83.67728 23.43953 -14.26587 83.67904 23.03947 -14.03395 83.68073 22.68997 -13.90399 83.68166 22.23537 -13.81814 83.68227 23.63789 -15.13084 81.93317 23.39462 -14.84787 81.93779 23.16302 -14.65595 81.94086 22.83982 -14.46948 81.94379 22.55775 -14.36504 81.94541 22.19106 -14.29608 81.94647 42.81844 -0.1990125 63.03818 42.35768 0.420894 63.89526 42.12657 0.9923382 63.78349 42.46059 0.3263666 62.83307 45.00834 -8 72.62341 45.00834 -7.267217 71.76062 45.00834 -4.643889 67.69438 45.00834 -5.335476 68.86626 45.00834 -6.043648 70.0282 44.43609 -3.010334 62.94438 44.82151 -3.598796 64.96705 44.99671 -4.35573 67.01271 44.4243 -2.99 62.89589 44.28771 -2.08412 62.92892 43.89077 -1.263393 63.02492 43.28354 -0.6149333 63.17178 3.140771 -16.97496 86.72658 3.146765 -17.16127 86.30033 3.921063 -17.62916 86.25558 3.774612 -17.67214 85.8021 4.134766 -17.74303 86.11998 3.994978 -17.79065 85.61312 5.214877 -17.99993 85.39155 4.876981 -18 84.78174 5.233865 -18 85.3781 2.143132 -14.52963 87.02027 2.29367 -15.14924 87.19464 2.305052 -15.69053 86.88069 2.536274 -15.994 87.06523 2.363098 -15.86918 86.84045 3.035754 -16.84809 86.78707 2.613427 -16.42733 86.6741 2.943857 -16.92594 86.44831 19.89096 -14.53065 86.95705 19.36524 -16.21084 87.01165 18.90134 -16.92556 86.75092 19.07884 -16.95024 86.36247 18.75215 -17.09246 86.6642 18.54734 -17.48276 85.95076 17.93604 -17.70787 86.16522 18.16463 -17.73564 85.62638 17.71847 -17.80818 86.02522 17.18677 -18 84.68885 16.78512 -17.99993 85.39155 16.76613 -18 85.3781 19.73511 -15.67555 86.81979 19.38074 -16.50734 86.57467 19.68778 -15.82698 86.78576 19.65287 -15.41239 87.16645 19.68949 -15.24274 87.18579 20.38981 -14.89806 85.4027 20.16724 -15.31966 85.92815 20.10826 -15.73044 85.27861 20.32126 -14.33448 86.10295 20.15942 -15.22742 86.06013 19.9019 -14.51923 86.93732 22.31564 -12.53661 84.95272 22.18456 -12.52705 84.9672 21.97657 -12.56015 85.00273 21.80073 -12.6255 85.04696 21.50852 -12.79378 85.15293 21.43473 -12.84709 85.18642 21.06926 -13.17681 85.39508 20.69971 -13.64212 85.68831 20.74784 -14.41986 84.83571 21.0943 -14.12036 84.4174 21.43224 -13.93038 84.09926 21.49967 -13.90283 84.04507 21.76268 -13.82698 83.86239 21.91679 -13.80629 83.77822 22.09397 -13.80443 83.70862 22.20367 -13.81402 83.68555 20.24408 -15.3842 84.65765 20.47412 -15.01785 83.88618 20.72601 -14.75417 83.2731 21.01693 -14.54749 82.75682 21.08309 -14.51108 82.66162 21.38213 -14.38512 82.31582 21.60176 -14.32738 82.13959 21.91195 -14.28938 81.98943 22.12827 -14.29123 81.9487 -18.22279 -14.63382 68.20404 -19.60862 -14.0946 77.87761 -19.47812 -14.54135 78.03184 -19.9916 -11.1813 76.85272 -19.99159 -11.20033 76.85946 -19.95595 -12.07945 77.17071 -19.09129 -15.48933 78.01091 -19.20011 -15.31759 78.29632 -18.98738 -15.59399 77.55313 -18.92258 -15.58031 76.96311 -18.22616 -14.63817 68.242 45.00834 -3.349422 10.45429 45.00834 -4.98431 9.800368 45.00834 -19.82881 10.18105 45.00834 -19.80031 8.916534 45.00834 -15.23914 9.60569 45.00834 -14.49959 8.916534 45.00834 -1.509681 11.54434 45.00834 -1.793861 11.34865 45.00834 -6.813476 9.375516 45.00834 -8.5 9.250606 45.00834 -13.53729 9.037966 45.00834 -13.73154 9.035059 45.00834 -10.83782 9.295021 36.01923 -20.74515 -0.08346033 36.01923 -16.26091 -0.08346033 38.15645 -20.5235 0.1766473 37.7735 -16.26091 0.09133023 39.30113 -20.40313 0.5405234 39.46004 -16.26091 0.6047474 41.06392 -20.21543 1.470659 40.9931 -16.26091 1.423058 42.21906 -20.09109 2.402939 42.34032 -16.26091 2.520748 44.98661 -15.2332 8.29144 44.96013 -15.31363 7.986285 44.94683 -19.80261 7.866156 44.83015 -15.41907 7.134517 44.72018 -19.82363 6.657365 44.43606 -15.68795 5.758437 44.45148 -19.85111 5.799926 44.32445 -15.75213 5.475271 44.32426 -19.86444 5.474811 43.72294 -16.02319 4.281348 43.8652 -19.91332 4.526814 43.27195 -16.15471 3.602412 43.33364 -19.97059 3.687778 42.37608 -20.07413 2.556353 45.00096 -15.06376 8.552131 45.0071 -14.81001 8.767326 35.25503 -4.583749 15.56233 35.14734 -4.985863 15.45464 34.8232 -6.737305 15.1305 26.36712 -18.87793 23.96982 27.25794 -22.42061 25.78207 28.05429 -22.58152 24.98593 26.85251 -18.98093 23.48444 28.85087 -22.6513 24.18955 28.12403 -19.03614 22.21291 29.64641 -22.63131 23.39421 28.14748 -19.03428 22.18946 30.43966 -22.52178 22.60117 28.73871 -18.95239 21.59823 30.61875 -22.48449 22.42213 28.87219 -18.92454 21.46475 31.40793 -22.26357 21.63314 29.35433 -18.79452 20.98261 32.17601 -21.95652 20.86526 30.5671 -18.2514 19.76984 32.92208 -21.56525 20.11938 30.58877 -18.23867 19.74817 33.64501 -21.09055 19.39662 31.1275 -17.88465 19.20944 33.80529 -20.97152 19.23639 31.24693 -17.79589 19.09 34.49831 -20.39358 18.54354 31.67148 -17.44748 18.66545 35.15124 -19.74426 17.89077 32.68877 -16.36727 17.64817 35.76368 -19.02575 17.27848 32.70621 -16.34516 17.63073 36.33475 -18.23934 16.70755 33.13171 -15.75891 17.20523 36.45812 -18.05198 16.5842 33.22363 -15.61924 17.1133 36.97678 -17.18215 16.06567 33.54273 -15.09169 16.79419 37.44089 -16.26373 15.60167 34.24985 -13.59617 16.08708 37.85058 -15.29898 15.19206 34.2611 -13.56721 16.07583 38.20533 -14.28952 14.83739 34.5254 -12.81484 15.81153 38.27788 -14.05496 14.76486 34.57946 -12.64002 15.75748 38.56365 -12.99133 14.47915 34.75712 -11.99274 15.57981 38.78654 -11.9074 14.2563 35.07433 -10.25052 15.2626 38.94725 -10.80522 14.09562 35.07816 -10.21802 15.25877 39.04563 -9.686591 13.99725 35.15147 -9.384343 15.18546 39.05917 -9.431286 13.98371 35.16156 -9.194072 15.17537 39.08084 -8.5 13.96203 35.17772 -8.500014 15.15921 35.37907 -4.643628 15.64894 35.3553 -5.067792 15.57235 35.42746 -4.662819 15.66806 35.46167 -4.675325 15.67785 35.60041 -5.128809 15.56977 35.70618 -4.7433 15.67248 35.622 -4.723937 15.68853 35.53728 -4.700206 15.68977 35.53425 -4.699279 15.68953 35.47406 -4.679655 15.68069 35.03504 -6.778033 15.25471 35.20218 -7.678764 15.18297 35.282 -6.808668 15.26051 34.99439 -8.500014 15.16497 34.93015 -8.500014 15.15068 34.82132 -8.500015 15.10423 25.77718 -22.81509 27.83946 25.35977 -21.96792 27.79455 25.25861 -22.49146 28.25839 26.34669 -23.18228 27.35809 25.85288 -22.55584 27.5841 25.81615 -22.83979 27.80713 25.96272 -22.05028 27.11644 26.03737 -18.7879 24.29943 25.7061 -18.69254 24.63028 25.69553 -19.27469 25.21681 26.35901 -23.14483 27.32055 26.48135 -22.83465 26.98082 26.07783 -21.53801 26.61509 26.63915 -22.58014 26.62675 26.2071 -20.97981 26.03592 26.67044 -22.54552 26.56629 26.23028 -20.88041 25.92936 27.01824 -22.38858 26.04431 26.44136 -19.95026 24.88933 25.688 -19.43348 25.37547 25.61814 -20.274 26.20421 25.52647 -20.97765 26.88001 25.42197 -21.62291 27.48127 24.45836 -18.19291 25.88882 22.93315 -21.07082 30.32813 22.44664 -17.86128 28.91454 21.63132 -20.22158 31.65688 23.35831 -17.47875 26.99855 24.07106 -19.97682 28.02493 23.32003 -17.44867 27.03718 23.14795 -17.3087 27.21079 22.6893 -16.89546 27.67355 20.39912 -12.59302 33.30105 19.65663 -15.29375 35.90433 19.83859 -16.93935 34.30306 19.82005 -17.14949 47.95089 19.23017 -17.08262 46.47637 20.63511 -14.46988 43.80186 18.79305 -17.07585 44.88592 18.59879 -17.1082 43.84672 19.44741 -15.48261 42.16003 21.28484 -16.1118 30.12786 21.15297 -13.93118 29.18985 20.85601 -12.28536 29.45212 20.59074 -14.32586 31.61488 22.03274 -16.09364 28.33447 21.74965 -15.59919 28.61536 21.29589 -14.4511 29.05566 20.49776 -18.63537 32.89089 20.06759 -19.2182 33.88676 20.89022 -19.77906 32.57682 18.4571 -17.6025 39.45761 18.69453 -17.96638 37.78201 19.10285 -18.4124 36.17472 19.40841 -18.69283 35.30922 22.18832 -13.7776 45.29858 20.30943 -17.22329 48.87704 22.32803 -6.135391 35.2708 23.34745 -5.725086 36.86993 22.80775 -8.542918 38.68467 24.46816 -5.426536 38.18765 20.63183 -8.762168 29.63873 20.9979 -6.942741 31.69564 21.01526 -8.295202 32.79648 21.02988 -6.861322 31.79556 20.66675 -9.917212 29.57964 20.6673 -10.02454 30.84142 21.944 -11.44754 41.01692 20.7364 -12.47723 39.3476 21.53614 -9.627192 36.92685 21.90175 -6.804566 34.77791 22.03101 -6.289783 34.68844 21.3386 -6.718351 32.94001 23.52321 -10.74366 42.53871 24.47069 -7.801724 40.28713 25.00666 -5.323956 38.71146 18.41345 -17.23418 42.07569 18.68477 -16.76499 40.45541 19.96099 -13.78109 37.61443 20.71962 -11.00018 35.1018 18.4017 -17.45935 40.29419 20.63004 -8.813689 29.58482 35.38842 -0.4191205 15.6577 35.38887 -4.583749 15.65792 35.54847 -4.583749 15.70515 35.54847 -0.3457587 15.70515 35.50718 -0.2914057 15.69032 35.48452 -0.260052 15.67218 35.44449 -0.1999999 15.60957 22.87397 -23.38581 -0.09937059 19.75243 -22.56079 -0.1031485 19.96278 -16.26091 -0.1028938 15.51323 -21.12326 -0.1082792 19.96278 -14.28923 -0.1028938 9.788833 -18.93657 -0.1152077 4.335438 -16.9189 -0.121808 28.85976 -23.93467 -0.09212535 26.98562 -23.95988 -0.09439408 24.87412 -23.7548 -0.09694963 34.82164 -21.74061 -0.08490949 33.57513 -22.55003 -0.08641821 32.73496 -22.9758 -0.08743524 31.41181 -23.4718 -0.08903664 30.02107 -23.7947 -0.09071999 -8.196562 -15.83939 83.82208 -6.497401 -15.77304 84.42274 -6.548411 -15.5405 84.48957 -6.691272 -14.52533 84.60107 -6.188889 -16.74026 83.9338 -8.011596 -16.97488 83.08627 -6.11402 -16.9089 83.80287 -5.768739 -17.49299 83.16303 -7.734775 -17.73358 81.98505 -5.38741 -17.86478 82.40133 -5.32133 -17.90477 82.26376 -7.408243 -18 80.68607 -4.981596 -18 81.52742 -12.60706 -18 80.33153 -9.991816 -18 80.2766 -12.4599 -17.73358 81.66281 -10.08294 -17.73358 81.61289 -12.33514 -16.97488 82.79141 -10.1602 -16.97488 82.74574 -12.25179 -15.83939 83.54553 -10.21182 -15.83939 83.50269 -2.390463 -15.52002 82.95135 -2.265957 -15.52339 82.68991 -2.380539 -15.45503 82.96014 -2.002961 -15.50115 81.69477 -1.966059 -15.40087 81.3109 -1.99062 -15.49481 81.56384 -1.980605 -15.47994 81.30221 -3.507437 -15.33127 84.2288 -2.765193 -15.49132 83.52268 -2.669643 -15.50053 83.39808 -4.434458 -15.20997 84.6768 -4.227816 -15.25541 84.60283 -3.42908 -15.40378 84.16036 -6.671529 -14.50908 84.60927 -4.960833 -14.44808 84.89855 -5.734604 -14.85367 84.83073 -5.501206 -14.92715 84.84116 -1.867011 -15.07113 81.39294 -2.319721 -15.17566 83.03637 -3.439901 -14.95007 84.30565 -5.079253 -15.04903 84.818 -4.831083 -14.01701 84.9926 -3.372889 -14.68244 84.39671 -2.258821 -14.98037 83.13404 -1.75482 -14.83968 81.50603 -4.616466 -13.50395 85.15687 -3.268402 -14.36047 84.55631 -2.163709 -14.74636 83.31439 -1.56495 -14.5699 81.72634 -3.675942 -13.21404 85.22586 -2.615065 -14.01617 84.48309 -1.846847 -14.47888 83.2517 -1.516815 -14.51453 81.76496 -3.051062 -13.04304 85.13268 -2.199963 -13.82024 84.33675 -1.647477 -14.32476 83.15263 -1.482085 -14.47579 81.76997 -19.57156 -14.00078 78.91812 -19.42741 -14.39608 79.2649 -19.26918 -13.59358 79.94968 -19.25147 -15.21874 78.41186 -19.42635 -14.49433 79.17178 -19.99159 -11.19712 76.86435 -19.96288 -11.92852 77.40215 -19.67965 -13.62008 78.64114 -19.99158 -11.19391 76.86925 -19.94802 -11.77664 77.63259 -19.52351 -13.11181 79.36949 -19.36401 -13.4076 79.74968 -19.26221 -13.57512 79.96389 -19.14468 -14.80048 79.71609 -19.09453 -13.65617 80.28117 -18.78181 -15.7924 78.99798 -15.1282 -14.48259 83.51867 -15.55338 -14.45739 83.36711 -15.60314 -16.16343 82.86106 -16.26661 -14.38818 83.03934 -16.37894 -16.03002 82.49405 -17.36197 -14.20693 82.3208 -17.51641 -15.69956 81.71941 -17.83918 -14.09401 81.90257 -17.98715 -15.50426 81.28743 -18.77558 -13.79208 80.79551 -18.86209 -15.01139 80.19955 -18.92007 -15.58398 76.96962 -18.64511 -15.93229 77.50559 -18.05423 -16.49986 78.22248 -17.74097 -16.74148 78.50598 -18.49895 -16.04661 79.39593 -16.84735 -17.27824 79.13238 -17.63355 -16.63946 80.29983 -16.40139 -17.47898 79.37701 -17.17171 -16.87375 80.66302 -15.39338 -17.8012 79.81513 -16.06194 -17.26903 81.32359 -14.7461 -17.92425 80.0288 -15.30865 -17.42811 81.64327 -13.67572 -18 80.2852 -14.01779 -17.53109 82.00144 -14.15947 -16.97488 82.71234 -14.35985 -14.5 83.7177 -14.30777 -15.83939 83.45641 -14.26819 -16.25 83.25782 26.01467 -12.53613 85.41294 26.01151 -12.67258 85.41112 25.92664 -13.69834 85.30268 25.80265 -14.38553 85.1328 26.02187 -12.53271 85.41294 26.08806 -12.63693 85.41183 26.56291 -13.45537 85.34725 26.85646 -14.04997 85.25067 27.05648 -14.83279 85.12844 26.76956 -14.52078 85.19166 26.70142 -14.93582 85.13082 25.99879 -15.12055 85.00102 25.54101 -14.87884 84.91223 25.34147 -15.26773 84.69944 25.04241 -15.32435 84.48957 2.980246 -15.31737 88.1197 3.229153 -16.28721 87.79201 3.671821 -17.10902 87.24209 4.340935 -17.73401 86.44921 4.490883 -17.81727 86.27261 5.221189 -17.99995 85.39379 5.227501 -17.99995 85.39604 4.858341 -17.84216 86.41396 4.780504 -17.76925 86.62331 4.412605 -17.19824 87.59278 4.139502 -16.38908 88.29711 3.970693 -15.37638 88.72873 5.233814 -17.99995 85.39827 5.230784 -17.81727 86.5416 5.228793 -17.73401 86.77356 5.202161 -17.10902 87.81266 5.156641 -16.28721 88.51914 5.115854 -15.31737 88.93003 5.240126 -17.99993 85.40052 5.601773 -17.74303 86.65332 5.674604 -17.62916 86.89618 5.980859 -16.84809 87.88511 6.156901 -15.994 88.43109 6.243266 -15.14924 88.69325 11 -15.83939 87.43358 15.878 -16.21084 88.32412 13.51339 -15.83939 87.71244 13.67969 -16.97488 86.97218 7.777826 -18 84.5575 8.071414 -17.73358 85.86431 8.320308 -16.97488 86.97218 8.486612 -15.83939 87.71244 15.76275 -15.24274 88.67512 15.77581 -15.41239 88.63565 13.92859 -17.73358 85.86431 16.09318 -17.09246 87.65068 16.04115 -16.92556 87.81574 16.75988 -17.99993 85.40052 14.22217 -18 84.5575 16.448 -17.80818 86.48559 16.37414 -17.70787 86.73397 11 -18 84.2 11 -17.73358 85.53939 11 -16.97488 86.67488 16.77881 -17.99995 85.39379 17.40769 -17.8642 86.15274 17.55848 -17.79173 86.3308 18.15817 -17.31592 87.0382 18.27689 -17.17586 87.18027 18.67742 -16.51132 87.67294 18.96221 -15.6345 88.04244 19.00144 -15.43136 88.09502 16.7725 -17.99995 85.39604 17.08961 -17.88295 86.27298 17.16716 -17.81987 86.48272 17.48981 -17.39194 87.33842 17.55759 -17.26131 87.51527 17.80021 -16.61533 88.1424 17.98915 -15.71226 88.62625 18.01646 -15.4975 88.69594 16.76619 -17.99995 85.39827 16.76833 -17.8642 86.38442 16.76977 -17.79173 86.618 16.78736 -17.31592 87.54676 16.79434 -17.17586 87.73221 16.83115 -16.51132 88.36782 16.87357 -15.6345 88.83393 16.8807 -15.43136 88.89937 -14.29218 -19.52702 4.174715 -14.42198 -20.3628 6.946236 -17.45128 -19.93299 6.756376 -3.870463 -17.49476 0.4429725 3.337863 -19.78473 0.4747334 -31.77968 -13.25838 0.09501314 -31.77696 -11.94655 -0.1336642 -30.1747 -13.91832 0.2961421 -31.78201 -14.31301 0.4509935 -31.77276 -11.54679 -0.1593701 -31.76973 -11.40466 -0.1636742 -31.76643 -11.26253 -0.1654507 -31.77701 -11.87333 -0.1398789 -31.77554 -11.71011 -0.1512974 -30.20483 -16.28382 1.622427 -31.78756 -16.58338 1.886583 -31.78531 -15.70604 1.201583 -30.22885 -18.07028 3.662889 -31.79248 -18.25059 3.992759 -31.79057 -17.64944 3.055961 -31.78602 -19.05369 6.148299 -31.7866 -19.04683 6.116806 -30.24398 -19.07238 6.183017 -31.79026 -18.99841 5.909777 -31.79325 -18.94449 5.704025 -31.79481 -18.88515 5.499876 -31.79483 -18.86947 5.449086 7.758882 -24.19012 2.199836 8.692049 -21.7771 0.4854921 -2.97349 -22.2485 4.620941 1.912609 -23.86734 4.732393 7.129778 -25.81244 4.769803 -4.990111 -21.65311 4.55574 -4.532588 -19.95745 2.083735 -21.33272 -19.52094 6.535034 -22.8982 -19.39514 6.455852 -22.83337 -18.44684 3.845181 -28.90484 -19.10134 6.219707 -28.88152 -18.10602 3.687466 -17.34456 -19.0514 4.046625 -28.79287 -13.94909 0.3008117 -22.55709 -14.26367 0.328085 -16.84702 -14.84912 0.3607633 -13.65135 -15.32179 0.3812161 -8.72928 -16.27506 0.4134896 -9.245342 -18.73783 1.990266 -14.02355 -17.76984 1.886296 -17.13423 -17.28183 1.820474 -22.71491 -16.6647 1.717033 -28.84271 -16.31972 1.635373 -9.609386 -20.46775 4.376186 -11.73032 -20.83137 7.119089 -9.771255 -21.22648 7.242525 -5.177294 -22.3381 7.503815 -3.169701 -22.90545 7.597918 1.697916 -24.47402 7.757259 6.899423 -26.3999 7.808595 12.9788 -28.01286 4.704373 12.74809 -28.63156 7.710525 17.63742 -29.52532 4.57075 17.42691 -30.20864 7.513058 20.05778 -30.92649 7.367105 21.32032 -30.42564 4.428304 21.15154 -31.17733 7.301626 23.83602 -30.83469 4.322892 23.71579 -31.63546 7.144222 14.47188 -23.95866 0.4825216 18.8899 -25.40636 0.4688339 22.24551 -26.24054 0.4529633 24.45698 -26.61001 0.44102 26.86107 -26.80276 0.4286465 29.07213 -26.74437 0.4207959 30.48559 -26.56534 0.4193691 32.22201 -26.16629 0.4231349 33.90403 -25.55802 0.4330754 34.97349 -25.03902 0.4421418 36.54011 -24.0653 0.4579207 38.00708 -22.89412 0.4739683 13.58322 -26.37438 2.169997 18.14954 -27.84429 2.104927 21.7026 -28.70053 2.035111 24.09469 -29.08084 1.983517 26.75156 -29.2738 1.929654 29.25604 -29.19396 1.893305 30.8897 -28.98305 1.883535 32.92743 -28.51644 1.892232 34.92014 -27.80513 1.924227 36.18638 -27.20018 1.954816 38.02497 -26.07572 2.008867 39.71775 -24.74492 2.064094 26.67138 -31.04979 4.212302 29.38792 -30.9695 4.136676 31.18194 -30.73987 4.115269 33.43792 -30.22189 4.130508 35.65141 -29.42552 4.192506 37.05406 -28.74883 4.252359 39.07546 -27.50008 4.358261 40.91389 -26.04072 4.466278 24.93279 -31.78136 7.07146 26.63105 -31.89844 6.978024 29.45086 -31.8434 6.863386 31.32506 -31.61199 6.83029 33.68824 -31.0647 6.851917 36.00294 -30.20891 6.943552 37.46222 -29.48099 7.032145 39.54958 -28.14584 7.188493 41.42953 -26.60174 7.347203 -36.33746 -11.62373 2.803467 -36.51115 -11.6725 3.254428 -36.56675 -11.6568 3.429729 -36.76844 -11.47416 4.651502 -36.77167 -11.50335 4.862359 -36.7716 -11.47976 4.878816 -36.7716 -11.51152 4.868662 -36.7716 -11.49644 4.876293 -36.7716 -11.52305 4.856094 -36.7716 -11.52832 4.842084 -36.7716 -11.52872 4.839007 -36.76819 -11.54561 4.655234 -35.96903 -11.77127 2.135875 -33.35611 -11.9364 0.1213728 -33.86452 -11.92202 0.3214927 -33.64591 -11.83897 0.219795 -34.48169 -11.89582 0.6586133 -34.83467 -11.87567 0.9071926 -35.24356 -11.75153 1.250926 -35.71849 -11.80165 1.785016 -31.94958 -11.94782 -0.1307133 -33.18074 -11.94001 0.06672281 -31.84521 -11.25799 -0.1649376 -32.23511 -11.37878 -0.1429439 -32.63381 -11.5033 -0.08694905 -33.11545 -11.65729 0.02789741 -34.35726 -11.5865 0.5600579 -33.46914 -11.45525 0.1331894 -32.69647 -11.3522 -0.07878232 -31.92397 -11.25345 -0.1631769 -35.40966 -11.50294 1.406067 -34.25364 -11.40407 0.4944285 -33.14978 -11.32514 0.02824944 -32.00269 -11.24891 -0.1601687 -36.19532 -11.41275 2.503741 -34.96372 -11.3513 0.985908 -33.59107 -11.29784 0.1772164 -32.08136 -11.24436 -0.155914 -36.39157 -12.47877 3.074677 -33.68986 -13.16237 0.4619519 -35.30939 -12.8886 1.508298 -36.7716 -11.99529 4.922507 -33.69147 -14.16674 0.8016714 -33.69376 -15.49308 1.517398 -33.69532 -16.32822 2.170262 -33.6974 -17.34274 3.284382 -33.69873 -17.91468 4.176663 -33.70035 -18.50329 5.563476 -34.28423 -18.22715 5.649739 -35.3102 -13.75033 1.800033 -35.31137 -14.88819 2.414451 -35.31217 -15.60457 2.974785 -35.31323 -16.47474 3.930852 -35.31391 -16.96524 4.696458 -35.31474 -17.46997 5.886273 -36.3918 -13.12716 3.294103 -36.39211 -13.98336 3.756301 -36.39233 -14.52245 4.177855 -36.39261 -15.17728 4.897175 -36.39279 -15.54641 5.473228 -36.10527 -16.48434 6.194171 -36.7716 -12.3921 5.056446 -36.7716 -12.91623 5.338857 -36.7716 -13.24633 5.596589 -36.7716 -13.64744 6.036569 -36.7716 -13.87362 6.38904 -36.7716 -14.10648 6.936984 -36.09458 -17.2441 12.61531 -36.59954 -16.04732 13.2776 -36.39046 -16.51683 10.21775 -33.06447 -19.46428 10.53683 -34.2668 -19.00946 11.24017 -35.30513 -18.13422 10.08521 -35.30302 -18.24844 11.93839 -36.39233 -16.04418 6.850329 -36.39253 -15.98086 6.566195 -35.78059 -17.04277 6.372925 -36.7716 -14.17578 7.247684 -36.72184 -14.79636 6.797105 -33.6811 -19.21409 9.996719 -31.76645 -19.58083 9.834491 -33.68401 -19.11679 8.987488 -31.77014 -19.49473 8.946203 -33.69472 -18.69018 6.287596 -31.78561 -19.06639 6.207589 -32.10155 -19.03972 6.13513 -35.30662 -18.03944 9.105177 -35.31209 -17.62912 6.513254 -34.11052 -18.46092 6.156137 -36.39086 -16.42673 9.281348 -36.7716 -14.75317 13.71336 -36.7716 -14.60851 10.37413 -36.7716 -14.5243 9.489169 35.65713 -0.2854154 15.71877 35.55444 -0.1999999 15.67382 35.6294 -0.2031753 15.69921 35.71082 -0.1999999 15.71659 35.5192 -0.1999999 15.65835 37.18444 -2.981839 16.0085 36.57424 -3.568674 15.87041 38.87057 -1.455837 16.55436 40.37289 -0.854007 16.97776 40.81064 -0.5442534 17.19872 40.68782 -0.4504545 17.29597 39.04278 -1.862702 16.42248 39.16335 -1.767373 16.46611 39.0634 -1.680542 16.53664 35.60128 -4.63862 15.7057 35.65426 -4.692218 15.69473 36.71088 -3.711547 15.85793 38.56918 -2.244141 16.2632 37.87341 -2.823539 16.06272 37.33786 -3.145942 15.99482 37.41413 -3.217413 15.95121 36.77831 -3.775877 15.82297 36.64194 -3.641555 15.87395 37.25996 -3.066051 16.01425 38.96279 -1.573484 16.56697 -13.08702 -15.90705 47.35809 -13.11137 -15.94127 47.16561 -13.09228 -15.98361 47.1887 -13.1231 -15.93387 47.55013 -13.07497 -15.94718 47.37062 -13.1376 -15.89295 47.54797 -13.20025 -15.37608 46.62219 -13.33125 -15.58196 46.64584 -13.28269 -16.04219 46.53722 -13.36113 -15.82334 46.61505 -13.11481 -16.1859 46.43106 -12.83555 -16.31262 47.00545 -13.013 -16.17269 47.11254 -13.0049 -16.18347 47.10667 -13.56289 -15.25698 45.89665 -13.68545 -15.45831 45.93247 -13.7143 -15.69426 45.91405 -13.64288 -15.91117 45.84556 -14.57584 -15.86355 44.03929 -13.86465 -15.96766 45.10991 -13.48742 -16.05972 45.74258 -15.94326 -15.68088 42.45545 -14.69868 -15.70469 44.12563 -15.98288 -15.48765 42.47156 -14.752 -15.49702 44.16819 -15.9613 -15.29368 42.43877 -14.72561 -15.28023 44.15884 -15.88192 -15.12935 42.3622 -14.62455 -15.09576 44.09935 -15.84867 -15.84309 42.39296 -13.0161 -16.07001 47.40975 -12.63118 -16.39426 47.53742 -12.45752 -16.45122 47.64444 -12.63942 -16.38876 47.57849 -12.64913 -16.38651 47.61954 -12.89916 -16.23109 47.58192 -13.05495 -16.05974 47.55862 -12.87402 -16.23731 47.48142 -12.80659 -16.30038 47.42086 -12.86315 -16.25967 47.38066 -13.01747 -16.10562 47.25973 -14.70539 -15.88562 60.3252 -15.11964 -15.80883 60.38386 -14.41465 -16.01734 57.00908 -12.25406 -16.49721 46.13861 -11.74219 -16.61557 45.36865 -11.67181 -16.48061 48.64528 -11.21267 -16.70074 44.56369 -10.66613 -16.75345 43.72284 -10.65812 -16.75398 43.71043 -12.38649 -16.46018 46.33666 -12.65176 -16.39233 47.33134 -12.69 -16.39837 48.43601 -15.75577 -15.57921 60.4788 -16.12104 -15.37518 60.53646 -15.34973 -15.58626 56.78392 -16.64329 -14.95867 60.62431 -16.07707 -14.84978 56.58517 -16.92592 -14.64274 60.67576 -16.97044 -14.58443 60.68423 -13.38725 -16.08981 57.23288 -14.03342 -15.89874 60.23485 -16.96996 -14.60991 60.78873 -16.96818 -14.63382 60.87897 -16.97048 -14.58764 60.698 20.95838 -6.809269 31.44152 21.03322 -6.800097 31.79325 21.34117 -6.625187 32.91804 27.92776 -4.254246 40.66053 26.41745 -4.75973 39.75791 25.02339 -5.091895 38.64799 24.48235 -5.203797 38.12536 23.35642 -5.529885 36.81283 22.33281 -5.97912 35.22408 22.0348 -6.148746 34.64668 29.96795 -3.369038 41.49665 28.29277 -4.112174 40.83997 32.06391 -2.204347 41.97514 31.8506 -2.363739 41.9426 31.8013 -2.392319 41.93457 32.17779 -1.980768 41.99106 32.17076 -2.03404 41.9901 32.13276 -2.119052 41.98488 20.71114 -6.921062 29.45013 20.71635 -6.916133 29.49851 20.69296 -6.927685 29.37391 20.65973 -6.932921 29.2948 20.65436 -6.933445 29.28484 20.95502 -6.870165 31.44371 -36.31805 -16.26247 15.34846 -36.3895 -16.67207 13.89861 -35.3016 -18.29604 13.88557 -35.64537 -17.67539 15.12471 -34.65768 -18.30328 15.93415 -35.54576 -16.67679 16.5716 -31.75598 -19.75492 13.87386 -33.32624 -19.38469 14.98638 -33.24433 -19.51348 14.34863 -34.58548 -18.79641 14.77995 -33.67418 -19.37882 13.87688 -19.73395 -14.0086 39.3274 -19.35012 -15.17808 39.0752 -19.6256 -14.43497 39.25759 -21.37669 -15.00374 36.65049 -18.42761 -16.01981 39.26088 -20.43247 -16.5886 36.20354 -18.18639 -16.04862 39.49536 -17.21911 -15.97168 40.6872 -17.0184 -15.94739 40.94549 -18.70776 -15.89704 39.0965 -18.98405 -15.68868 39.01675 -19.2155 -15.4175 39.02076 -13.09591 -16.72521 43.03446 -13.29911 -16.6969 42.98102 -15.85076 -17.05483 39.87976 -14.0446 -16.55207 42.79089 -14.71696 -16.35776 42.62962 -15.33103 -16.11385 42.49424 -10.67023 -16.75513 43.70697 -14.28876 -17.4646 38.83583 -11.50029 -16.8046 43.47142 -12.31041 -16.7945 43.24622 -26.98675 -15.95027 28.72443 -31.93434 -16.5062 21.71087 -26.08232 -17.534 28.24194 -31.04491 -18.10713 21.16181 -19.09587 -17.67816 35.41014 -24.77912 -18.62939 27.42904 -29.73869 -19.1998 20.29267 -16.03929 -17.81687 36.46591 -17.55953 -18.11539 34.38467 -23.26267 -19.08049 26.40147 -28.20667 -19.62441 19.23053 -19.43037 -14.4105 39.41464 -19.15914 -15.14147 39.23067 -19.18993 -14.35036 39.45878 -18.93081 -15.05479 39.27904 -19.53717 -13.99075 39.48598 -19.29155 -13.94589 39.52895 -18.74545 -15.37635 39.24869 -18.88847 -15.54919 39.17958 -18.67893 -15.71369 39.24511 -19.06198 -15.33252 39.1836 -18.86839 -15.20683 39.24709 -18.58653 -15.20824 39.20885 -18.64176 -15.13709 39.19819 -18.67909 -15.06925 39.19665 -18.59003 -15.50078 39.30261 -18.46742 -15.80762 39.37653 -18.42992 -15.56727 39.40488 -18.26989 -15.88707 39.54927 -18.28659 -15.82634 39.55788 -18.30153 -15.70036 39.56012 -18.29123 -15.57515 39.54238 -18.27675 -15.51537 39.52633 -18.46115 -15.30648 39.25597 -18.32411 -15.35641 39.33913 -18.19913 -15.35871 39.45277 -17.11996 -15.40585 40.98357 -17.04153 -15.24536 40.90838 -17.10745 -15.78537 41.00363 -17.14309 -15.59534 41.01699 44.31935 2.486668 53.90983 44.30227 2.52796 54.00159 43.87546 0.05116349 55.41389 43.41401 -1.825567 56.70668 44.32298 2.467779 53.88446 43.80357 -0.2977847 54.98455 43.44801 -1.476264 55.5573 43.11184 -2.386834 56.0671 42.82004 -0.2072498 62.98239 42.46575 0.3165112 62.77561 42.99997 -0.6060224 61.40828 43.35269 -0.9372917 61.98371 43.50585 -1.549507 60.8917 43.09524 -0.9904503 59.41571 43.25604 -1.805878 58.78031 43.41097 -2.724593 59.25613 43.33953 -2.460127 58.85881 43.29228 -1.995732 58.19379 43.30382 -1.77109 57.91163 43.6569 -3.12922 60.16943 43.57575 -3.258531 59.93744 43.63559 -2.756693 60.12583 43.45958 -2.871706 59.46794 43.59724 -2.241487 60.27931 43.66493 -3.279299 60.2262 43.61101 -3.419019 60.10905 43.59967 -3.363567 60.04986 43.70095 -3.982691 60.84486 43.69963 -3.973021 60.82899 43.63803 -3.565779 60.27191 42.72985 -0.08842933 61.05252 43.54731 -1.803108 60.60868 42.90957 -0.4432439 60.20478 43.86239 -4.952772 62.43458 42.54133 -6.556286 62.22093 42.12691 -5.722215 59.9909 43.72369 -0.1141545 53.57924 43.6948 -3.987039 60.83003 43.50783 -4.129261 60.42148 43.3527 -4.187708 60.0383 44.01157 -3.631162 61.56031 41.91975 -4.737287 57.75704 42.79888 -4.063142 58.29885 42.9384 -4.205479 58.91072 42.79654 -3.297625 56.87025 41.90533 -3.587775 55.52129 42.74125 -3.595089 57.28698 41.95402 -3.054473 54.58579 42.20541 -1.616392 52.30656 41.62821 -0.1999999 48.5434 41.08825 -0.6631572 48.91889 41.7776 -0.6647678 49.93495 42.25553 1.87567e-4 48.61454 42.22737 0 48.56586 40.59171 -0.1999999 47.27003 41.31992 -0.1999999 48.10464 40.43368 -0.3655185 47.39191 40.50765 -0.2170613 47.20848 40.35194 -0.1999999 47.0358 39.24964 -0.6583599 46.43988 39.28921 -0.5163654 46.30966 38.52504 -0.8910132 45.91891 38.59407 -0.571184 45.6879 37.79373 -1.106314 45.3978 37.8538 -0.786851 45.16345 37.09178 -1.331379 44.95614 37.11846 -1.013871 44.7016 37.8186 -0.4062722 45.04301 37.05389 -0.633031 44.57085 32.35116 -1.980768 42.04815 34.28525 -1.515915 43.08502 32.2671 -1.980768 42.01163 23.58901 -15.25737 77.62563 22.21062 -14.57886 76.52814 22.1376 -14.30111 81.32678 22.97161 -14.73012 77.58552 23.93606 -15.76396 81.75148 23.93755 -15.77034 81.68941 23.93846 -15.77542 81.5791 23.88413 -16.02726 75.09446 23.59614 -15.41437 75.92512 23.81241 -16.27636 71.74938 23.61846 -16.16022 70.32091 23.63739 -16.70996 67.17178 22.9882 -14.88804 75.87386 22.29287 -15.25833 70.96628 23.0403 -15.6382 70.24047 22.35642 -16.0627 66.18595 23.0732 -16.33556 66.23564 23.59156 -16.8 66.32023 25.30476 -17.20736 83.09816 26.41852 -17.44618 83.44797 26.55592 -17.14388 83.89667 24.42836 -16.60415 82.5616 25.42775 -16.96488 83.60501 24.51152 -16.4597 83.0617 26.60573 -17.0243 84.03732 25.47678 -16.86738 83.76281 26.88364 -16.18353 84.70402 25.77792 -16.18179 84.50457 26.91798 -16.04184 84.7782 25.81808 -16.06772 84.58713 27.05192 -15.07529 85.0932 25.98805 -15.30686 84.9522 28.07642 -14.77188 84.84086 27.99931 -15.82864 84.5987 27.9757 -15.97876 84.53707 27.76403 -16.8469 83.99991 27.7218 -16.96906 83.89163 27.59391 -17.28292 83.55583 24.54958 -16.4001 83.2183 24.81363 -15.97378 83.96672 24.85201 -15.90269 84.05194 25.02728 -15.43557 84.43675 28.42998 -18 64.82235 31.79198 -18 69.47966 26.08366 -18 66.86878 26.83649 -18 81.56642 26.70059 -18 74.98365 29.19456 -18 80.70941 26.52127 -18 71.5677 32.0754 -18 80.23364 35.00834 -18 72.70595 35.00834 -18 80.33868 34.87493 -18 72.60038 34.99343 -18 80.33665 33.21689 -18 71.11179 25.96907 -18 65.99246 25.95128 -18 65.8636 25.93485 -18 65.17181 25.9794 -18 64.85986 26.18617 -18 64.20893 26.3353 -18 63.92037 26.74116 -18 63.38365 26.9847 -18 63.15646 27.19303 -18 62.99827 44.44211 -7.317793 67.67798 44.43409 -8.021047 68.80238 42.8717 -8.85114 66.75883 42.84324 -9.544236 67.85813 44.4498 -6.629245 66.54035 42.89898 -8.171045 65.64416 42.9017 -7.886852 65.15603 44.42384 -6.333463 65.95233 42.80258 -7.138977 63.68506 44.23017 -5.55655 64.18581 43.74713 -1.598157 61.63265 44.05279 -2.590412 61.54903 -0.1234524 -14.10104 66.25225 -0.1206011 -13.76487 71.8245 -1.00224 -14.0269 71.83485 -0.1062179 -13.67568 77.18727 -1.98842 -15.40226 75.90038 -1.670153 -14.56313 77.17977 -0.08374363 -13.82265 81.7124 -0.1374387 -13.82519 81.70785 -0.1910637 -13.82937 81.70666 -0.410162 -13.86225 81.70981 -0.7661648 -13.97181 81.72038 -0.9935509 -13.93374 77.18509 -1.035841 -14.10819 81.73363 -1.336227 -14.33076 81.75552 -1.673269 -14.65552 71.85964 -0.9505984 -14.33373 66.27056 -1.603413 -14.89101 66.31445 -1.958011 -15.65488 66.3746 0.8521837 -14.29077 66.26726 1.615694 -14.92531 66.31722 1.616232 -14.608 71.46456 1.228285 -14.3368 83.00322 0.9389925 -14.10937 82.48884 0.8750532 -13.9966 81.18402 0.7584132 -14.00705 82.24572 0.4608853 -13.89127 81.95264 0.2185366 -13.83919 81.80117 1.694263 -14.97393 84.31412 1.629619 -14.85325 84.08029 1.623955 -14.63262 81.15046 1.465411 -14.60325 83.57373 1.939143 -15.64416 85.06671 1.929915 -15.62635 85.24208 1.883808 -15.46472 85.17268 1.925767 -15.61619 85.29245 1.916982 -15.59227 85.36331 1.941436 -15.64665 85.00015 1.860188 -15.3857 85.0466 1.94694 -15.6406 84.71475 1.968399 -15.47366 81.10713 1.61897 -14.50429 76.41282 1.975491 -15.40195 76.59456 1.969208 -15.46562 71.50025 1.944917 -15.65487 66.37466 0.861189 -13.86761 76.41338 0.853618 -13.97204 71.43751 1.870133 -15.28288 85.90876 2.051039 -15.91594 85.81893 2.137852 -14.52347 87.01024 2.049061 -15.44856 86.49038 2.06099 -15.59438 86.39249 2.286062 -16.19774 86.26126 2.132621 -14.51731 87.00019 1.877059 -15.18268 86.0707 3.567382 -17.6989 84.7518 2.520664 -16.85604 84.72786 3.058403 -17.33744 85.44593 2.344527 -16.59212 85.23284 2.935673 -17.21173 85.59621 2.588867 -16.75849 85.98177 2.475718 -16.5718 86.09348 2.301338 -16.51087 85.34207 2.174425 -16.23572 85.62135 2.130336 -16.12747 85.70136 11.31194 -18 64.99493 15.46385 -18 64.6163 16.60707 -18 64.45978 4.88003 -18 66.16831 4.872113 -18 66.32307 4.948441 -18 76.59562 5.354199 -18 65.38217 5.645069 -18 65.2328 17.17771 -18 83.65095 17.27644 -18 75.98117 17.53605 -18 70.93581 4.890697 -18 66.09849 4.987464 -18 65.80767 5.018236 -18 65.74981 5.711044 -18 65.21164 6.044265 -18 65.16266 5.208477 -18 65.50332 5.281401 -18 65.43766 18.04404 -18 65.9924 18.06145 -18 65.86597 16.76819 -18 64.443 18.07003 -18 65.78192 16.80577 -18 64.44116 17.11184 -18 64.47174 17.1947 -18 64.49479 17.48966 -18 64.63476 17.54402 -18 64.67211 17.83379 -18 64.9644 17.99599 -18 65.27127 18.02261 -18 65.35233 17.79227 -18 64.9095 18.07265 -18 65.68665 19.71337 -16.29905 86.1672 19.95878 -16.03698 85.73 19.53563 -16.63094 86.00988 19.88145 -16.22558 85.62129 19.23395 -17.06825 85.69755 19.0179 -17.30984 85.44482 18.44787 -17.72202 84.67405 19.76179 -16.48538 85.3992 19.68099 -16.63823 85.21766 19.47526 -16.93961 84.66201 20.0996 -15.75374 85.21545 20.08936 -15.77996 85.07913 20.08447 -15.79114 84.96869 20.07856 -15.79775 84.65493 19.97362 -15.58872 86.37362 19.89645 -14.52494 86.9472 19.98342 -15.46212 86.45388 21.62777 -16.06797 66.18691 20.46724 -15.01962 81.3413 20.11446 -15.96795 76.07434 20.48725 -15.26495 76.58929 20.21833 -16.32922 71.13212 20.51032 -15.90354 71.06159 20.42154 -16.8 66.32021 20.07494 -15.7783 83.63395 20.07487 -15.77784 81.35678 21.21603 -14.45959 81.32998 21.31929 -15.35841 70.98107 21.3625 -16.13717 66.19951 20.9494 -16.3297 66.23457 21.2642 -14.71074 76.53989 -12.34904 -17.88404 64.50019 -11.00375 -18 64.68484 -12.94462 -17.75516 64.38252 -14.05368 -17.37136 64.07833 -16.73995 -15.1175 61.75142 -16.93706 -14.71996 61.06494 -15.48529 -16.51916 63.38376 -14.6922 -17.0506 63.82845 -16.32313 -15.70972 62.54963 -15.90367 -16.15798 63.04289 43.74314 -24.13818 11.17635 42.94431 -25.17204 11.66498 42.95254 -25.18302 10.2095 44.88654 -21.21969 10.36199 44.66697 -22.14042 10.54816 44.47673 -22.69654 10.21598 44.47568 -22.69771 10.68977 44.13015 -23.46879 10.9265 44.47202 -22.6775 8.7933 44.87311 -21.26364 8.853857 43.81861 -23.9941 8.736908 42.93498 -25.16892 8.68659 42.92217 -25.1768 8.5473 43.79551 -24.00227 8.347805 44.43721 -22.68454 8.163722 44.8254 -21.26857 8.001327 44.66343 -21.30165 7.015131 44.47353 -21.34409 6.308771 44.05875 -21.44017 5.242366 43.68004 -21.52935 4.522278 42.88238 -25.21246 8.384694 43.7276 -24.04572 7.894709 42.83675 -25.256 8.267551 43.65016 -24.10011 7.567045 42.73859 -25.35187 8.090203 43.48247 -24.22205 7.065082 42.65016 -25.43889 7.97054 43.32941 -24.33465 6.719378 42.46517 -25.62059 7.781414 43.00175 -24.5752 6.153031 42.27333 -25.80729 7.637544 42.65003 -24.83046 5.694301 41.9797 -26.0887 7.483128 42.08455 -25.23307 5.146211 41.78832 -26.26918 7.415294 41.69565 -25.50476 4.863322 44.32853 -22.7262 7.432614 44.20291 -22.77902 6.905545 43.92923 -22.89829 6.101343 43.6786 -23.00906 5.55019 43.14119 -23.24729 4.653166 42.56387 -23.50229 3.933381 41.63583 -23.90921 3.084576 40.99806 -24.1873 2.653536 42.8747 -21.72052 3.376319 42.0214 -21.9239 2.488843 40.67704 -22.24547 1.49808 39.77299 -22.46307 1.031275 40.79205 -18.03504 14.20721 41.85727 -15.04719 13.14199 43.64122 -19.46543 12.67137 39.353 -20.69114 15.64626 42.41375 -22.71106 14.03961 42.90358 -22.09357 13.58916 43.13878 -21.6898 13.35836 43.45957 -20.88254 13.00823 43.58525 -20.31963 12.83611 37.87976 -25.82486 18.03802 39.30178 -25.19001 16.80312 37.59019 -22.92308 17.40907 40.67808 -24.28474 15.58667 41.48599 -23.6133 14.867 35.35808 -26.27976 20.15354 36.83907 -26.10993 18.92332 35.56494 -24.65322 19.43432 31.82088 -25.76299 22.96668 33.34772 -25.82135 21.65153 33.60019 -26.16735 21.57029 33.81862 -26.19799 21.39656 30.00098 -25.10092 24.37901 28.16521 -24.2234 25.82904 42.5116 -11.83155 12.48766 42.73226 -8.5 12.267 43.52978 -14.97974 12.17822 43.46042 -10.73868 11.91831 43.44998 -8.5 11.88151 25.00221 -23.71715 28.81708 25.56431 -24.06285 28.34633 24.91963 -25.25879 28.41094 24.35755 -24.92551 28.88409 24.01464 -26.18176 27.98768 23.45932 -25.8641 28.44541 23.03536 -26.64204 27.16354 22.49516 -26.33683 27.59269 26.09738 -24.40085 27.87444 25.45615 -25.58372 27.93187 24.55221 -26.49254 27.5188 23.56774 -26.94415 26.71847 22.63171 -22.28871 30.88938 21.30316 -21.43041 32.19366 21.91586 -23.4586 30.97894 20.5592 -22.5691 32.27726 20.93585 -24.33494 30.57801 19.55293 -23.4027 31.89042 19.89741 -24.73378 29.77074 18.49201 -23.75919 31.11296 25.02502 -5.211453 38.66946 39.96835 -1.597521 48.91754 39.78326 -1.750751 48.91732 39.09951 -1.749935 47.98867 37.28578 -3.792854 48.91429 20.321 -17.22361 48.89376 20.31363 -17.229 48.89375 25.21312 -7.550062 40.85112 26.42446 -5.007457 39.84712 26.51995 -6.989776 41.65451 27.96581 -4.522791 40.77809 27.86103 -6.273131 42.25041 28.33931 -4.385945 40.96438 29.20182 -5.41858 42.62348 30.05849 -3.666316 41.65169 21.58794 -16.288 48.8953 22.12876 -15.88372 48.89595 23.52122 -13.32587 46.31114 24.32874 -14.20709 48.89861 25.86739 -12.31998 47.75348 26.12991 -12.7971 48.90079 28.27505 -11.03338 48.82331 29.23429 -10.30741 48.90455 31.80533 -6.143017 45.93681 32.52752 -7.636491 48.90853 33.50309 -4.686956 45.8059 36.12334 -4.732814 48.91289 40.18013 -0.6607427 47.64999 37.13234 -3.917164 48.91411 35.06326 -3.143657 45.35452 31.74537 -3.38675 42.66869 32.00024 -2.684512 42.12862 34.29893 -2.194664 43.41433 36.42025 -1.560854 44.57951 30.50781 -4.448124 42.76412 31.94927 -2.712534 42.11985 30.01369 -7.47435 45.74388 28.1743 -8.646679 45.23208 26.33453 -9.629818 44.41458 24.54173 -10.39845 43.31244 18.05608 -17.99964 48.89117 18.61536 -17.91648 48.65697 19.10745 -17.82328 48.89229 16.93794 -17.87894 48.88968 16.9227 -17.87493 48.88965 16.374 -17.93293 47.75283 20.16501 -17.33171 48.8935 19.26349 -17.62735 48.27955 20.28523 -17.24932 48.89346 17.15228 -18.0704 47.43105 17.92874 -17.96571 47.09296 15.6995 -18.102 45.9451 16.56401 -18.23658 45.70072 15.37486 -18.26217 44.77306 16.29105 -18.39168 44.58154 15.00784 -18.62808 42.78891 16.00427 -18.74177 42.69404 14.86388 -19.12288 40.80371 15.93 -19.20862 40.81766 14.87566 -19.40268 39.87412 15.96982 -19.46994 39.94401 15.0641 -20.06452 38.00352 16.20308 -20.08233 38.19723 15.48122 -20.8306 36.19602 16.64495 -20.78356 36.52388 15.81893 -21.29837 35.21965 16.98627 -21.20824 35.62583 16.58291 -22.15691 33.61438 17.7366 -21.98122 34.15801 17.57527 -23.05634 32.14132 18.68763 -22.78231 32.81995 17.41866 -18.09796 45.42586 17.19159 -18.22704 44.34751 16.97438 -18.52534 42.53029 16.95863 -18.92929 40.72782 17.02132 -19.15677 39.89052 17.29003 -19.69123 38.22321 17.74981 -20.30312 36.63535 18.09235 -20.67299 35.78669 18.82782 -21.34409 34.40433 19.74041 -22.03607 33.14823 18.64057 -17.62733 46.76592 18.1851 -17.69885 45.14569 17.98714 -17.78458 44.0942 17.8088 -18.00318 42.31612 17.81899 -18.3204 40.54561 17.8892 -18.50518 39.7208 18.16372 -18.94922 38.07761 18.61608 -19.46742 36.51229 18.94842 -19.78395 35.67479 19.65563 -20.36285 34.30801 20.52621 -20.96463 33.06149 -8.606752 -18 64.82243 -4.941845 -18 81.32876 -4.94293 -18 81.36627 -4.944545 -18 81.38504 -6.208713 -18 64.94049 -6.202927 -18 64.94076 -5.843776 -18 65.00698 -5.291138 -18 65.34287 -5.065467 -18 65.63421 -5.022187 -18 65.71516 -5.756924 -18 65.03841 -5.431131 -18 65.222 -5.359753 -18 65.27958 -4.908126 -18 66.05574 -4.892989 -18 66.15634 -4.885207 -18 66.32305 -4.961329 -18 75.89874 -6.67812 -14.5145 84.60655 -6.016474 -15.09071 84.76178 -5.846463 -15.22416 84.76947 -6.684701 -14.51991 84.60382 -6.28916 -15.32085 84.64747 -6.181163 -15.50836 84.62888 -5.615604 -16.33426 84.38745 -5.488101 -16.49032 84.30503 -4.915392 -17.07881 83.82039 -4.308651 -17.5104 83.07924 -4.208809 -17.56041 82.92838 -5.015244 -15.81059 84.6417 -4.839695 -15.92191 84.58002 -4.095039 -16.34626 84.17008 -3.374042 -16.66445 83.47891 -3.261853 -16.70182 83.33345 -2.770301 -16.7928 82.47401 -3.744517 -17.68127 82.05698 -3.591662 -17.67692 81.4567 -3.58313 -17.67465 81.31658 -2.531439 -16.77727 81.52765 -2.519122 -16.76916 81.30704 -3.599603 -17.67789 81.52666 -2.543476 -16.78072 81.63786 24.3754 -16.69701 81.87747 24.53792 -16.92782 81.57647 25.10989 -17.41772 82.04151 25.00979 -17.37973 81.57441 26.05241 -17.84552 82.16169 25.56832 -17.71877 81.57196 27.08924 -17.92879 82.22355 24.39229 -16.69523 82.05178 25.1643 -17.40374 82.31183 26.1521 -17.79771 82.49796 27.22776 -17.82613 82.58603 -35.85234 -16.88381 6.151394 -34.68392 -18.07139 6.049215 -33.37187 -18.76158 6.04558 -31.99665 -19.04425 6.12855 -31.89165 -19.04662 6.122441 -32.59168 -18.94231 5.962741 -33.31134 -18.72603 5.818956 -34.07868 -18.35572 5.684412 -31.75999 -19.70707 11.86667 -33.67697 -19.33012 11.88216 -13.38039 -16.2227 44.89272 -12.80784 -16.44921 44.6402 -12.64815 -16.49979 44.57107 -12.01918 -16.65198 44.30106 -11.35602 -16.73851 44.01609 -10.66818 -16.75429 43.7149 -14.71267 -15.94883 60.9162 -14.02965 -15.93895 60.84449 -14.00921 -16.15689 61.40715 -16.94309 -14.62308 60.68973 -16.76916 -14.84493 60.72603 -16.60384 -15.02524 60.76212 -16.27516 -15.31942 60.83494 -16.14708 -15.41584 60.8636 -15.78601 -15.64481 60.94598 -15.5482 -15.7665 61.00179 -15.13848 -15.88442 60.96232 -15.14919 -15.92777 61.09878 -15.13757 -15.93174 61.10168 -16.79534 -14.83763 60.81857 32.35033 -2.084603 42.05371 32.26369 -2.059827 42.01264 32.31565 -2.245983 42.06715 32.22891 -2.184384 42.01266 32.24253 -2.403115 42.08531 32.16038 -2.308162 42.01062 31.93946 -2.538724 41.99914 31.8893 -2.566882 41.99104 30.02621 -3.527543 41.54767 28.32783 -4.255874 40.88277 27.95831 -4.3948 40.70123 26.43149 -4.888127 39.7891 43.69724 -3.979992 60.8295 43.51114 -3.783246 60.03322 43.29826 -3.491966 59.05227 43.23526 -2.579695 57.37812 43.20189 -2.840097 57.71924 43.22627 -3.297238 58.54653 22.73941 -17.35062 52.58916 41.67761 -1.441781 51.16355 37.97235 -5.572081 52.98579 41.75863 -6.905205 61.65071 39.92561 -3.525788 52.23655 38.73382 -9.719602 62.23917 33.59878 -9.412514 53.46741 35.85129 -7.545596 53.39844 24.06598 -15.21301 50.371 26.44583 -14.06616 51.62995 28.85541 -12.70097 52.57553 31.25343 -11.14084 53.19153 25.06268 -17.48251 56.29931 25.70577 -17.50531 57.31375 26.66799 -17.52425 58.80411 27.93067 -17.51783 60.69013 28.80577 -17.4905 61.9394 28.75712 -17.0716 61.06563 29.65212 -17.44513 63.09668 32.17689 -14.84673 61.94411 40.83269 -11.36602 68.17037 36.96556 -14.57117 68.28879 35.52156 -12.38198 62.33753 33.77449 -16.95287 67.96208 31.88959 -17.23312 65.89598 34.32996 -1.882369 43.19229 23.58453 -16.81422 66.19082 23.04367 -16.34114 66.10297 22.3579 -16.08686 66.055 24.52074 -17.05934 75.06942 24.64 -17.68328 66.17568 24.29881 -17.40113 67.08985 25.14306 -17.84635 66.98529 25.41904 -17.7892 71.64163 25.51366 -17.75482 75.03036 24.47171 -17.18641 71.70516 24.63018 -17.68725 66.04625 26.93523 -17.96559 62.62568 26.68335 -17.86314 62.26164 26.63969 -17.95108 62.74164 26.30593 -17.80593 62.34035 26.27063 -17.9285 62.93368 25.82253 -17.71742 62.50516 25.58537 -17.871 63.47881 24.89993 -17.49508 63.07522 25.30355 -17.8397 63.81256 24.51525 -17.37591 63.45855 24.85542 -17.77272 64.63923 23.90175 -17.12534 64.45204 24.72603 -17.74352 65.06276 23.72391 -17.01791 64.97236 23.58281 -16.83742 66.03164 32.86815 -17.72695 68.65587 31.89743 -17.39268 66.32215 32.85891 -17.19164 67.17996 33.47824 -17.03544 67.71172 33.73074 -16.96585 67.92597 27.49728 -17.98008 62.78253 27.75724 -17.92873 62.57786 29.50518 -17.74779 64.08357 27.90397 -17.88369 62.45182 27.93028 -17.87425 62.42826 30.07472 -17.67018 64.59372 -2.508 -16.72661 75.9001 -3.57927 -17.66269 75.89949 -2.534682 -16.86368 66.36444 -3.579855 -17.70102 66.34604 -6.069957 -16.26064 62.22174 -6.087413 -16.2621 62.22159 -6.149001 -15.62129 61.7442 -3.268181 -15.38906 62.90318 -3.732769 -16.02286 62.97047 -3.782584 -15.47901 62.5478 -4.726723 -16.13518 62.45963 -4.58048 -15.60338 62.17646 -4.9888 -16.16178 62.37652 -5.184482 -15.68797 62.01141 -2.575958 -15.85208 64.19327 -3.296923 -15.96586 63.32043 -3.511409 -15.99468 63.13616 -2.636093 -15.26263 63.52154 -2.270518 -15.17614 64.02685 -2.433928 -15.8244 64.44187 -2.047474 -15.72152 65.5116 -1.703188 -14.98434 65.42945 -1.880116 -15.05992 64.8235 -1.992434 -15.69497 65.83417 -5.082021 -15.13895 61.26633 -6.183866 -15.25854 61.16044 -6.18816 -15.21385 61.03846 -1.060977 -14.42806 65.24709 -0.2418137 -14.2053 65.06136 -1.262101 -14.50442 64.54533 -0.4684032 -14.28943 64.24247 -1.709479 -14.62181 63.62121 -0.9794574 -14.41832 63.16051 -2.130254 -14.70915 63.03394 -1.463775 -14.514 62.47031 -2.860008 -14.83683 62.31362 -2.308293 -14.65378 61.61989 -3.455274 -14.92769 61.89832 -3.000156 -14.75344 61.12668 -4.380414 -15.05339 61.46216 -4.07962 -14.89198 60.60414 -4.90136 -14.98693 60.3656 -6.197099 -15.12084 60.22798 6.054425 -14.69024 61.14408 6.036028 -15.25113 61.92988 5.154184 -15.21756 62.01371 1.54536 -14.84044 66.20567 1.982141 -15.69283 65.81871 1.662931 -14.91948 65.34315 2.02453 -15.70934 65.56752 1.845862 -14.97026 64.7593 2.389467 -15.77349 64.52231 2.241317 -15.03453 63.98415 2.503071 -15.78535 64.31552 2.607589 -15.07406 63.49196 3.190502 -15.83318 63.44575 3.239372 -15.12307 62.88763 3.448044 -15.84565 63.21872 3.751062 -15.15343 62.54081 3.702184 -15.85644 63.02901 4.552798 -15.19234 62.17466 4.693521 -15.89071 62.53072 4.914302 -15.89745 62.46213 6.013778 -15.92955 62.31046 0.8001773 -14.27591 66.14403 -0.121674 -14.11223 66.10954 0.02662521 -14.20141 64.92322 0.9332807 -14.3558 65.13827 0.2715115 -14.25788 64.11756 1.1449 -14.40702 64.45677 0.81068 -14.32786 63.0458 1.605584 -14.4717 63.55141 1.314345 -14.36987 62.36469 2.033738 -14.51137 62.97639 2.186598 -14.42085 61.52829 2.773572 -14.56048 62.27029 2.894176 -14.45226 61.04797 3.373294 -14.59091 61.86484 4.003359 -14.49357 60.53895 4.31336 -14.63009 61.43589 4.835855 -14.52187 60.3124 5.018853 -14.65569 61.24611 6.058608 -14.56268 60.18694 2.521587 -16.86368 66.3645 2.494993 -16.72644 76.59474 3.56629 -17.66264 76.59513 3.566759 -17.70102 66.34607 18.44496 -17.71919 83.64351 19.47498 -16.92934 83.63747 18.48286 -17.74645 76.02078 18.61965 -17.79634 71.01512 19.48535 -17.02865 76.05368 19.55612 -17.21302 71.08366 19.76644 -17.44478 66.22988 19.3731 -17.68328 66.17565 18.94808 -17.85783 66.11705 2.562165 -16.88396 65.88869 3.59549 -17.70665 66.01335 2.602089 -16.89276 65.67452 2.926462 -16.9268 64.78799 3.02532 -16.93306 64.61334 3.61712 -16.95827 63.88074 3.837413 -16.96482 63.68998 4.054421 -16.97048 63.53075 4.898915 -16.98843 63.11397 5.08669 -16.99195 63.05704 6.020448 -17.00869 62.93452 3.623512 -17.70908 65.86373 3.850251 -17.71849 65.24503 3.91929 -17.72022 65.12313 4.333195 -17.72716 64.61087 4.487699 -17.72896 64.47703 4.640172 -17.73052 64.36511 5.23591 -17.73544 64.07093 5.368796 -17.73641 64.03057 6.031231 -17.74099 63.94332 16.40398 -17.66121 63.08983 15.14593 -16.58948 62.09192 16.24676 -16.72134 62.02931 15.22962 -17.34225 62.75645 15.33973 -17.83079 63.63079 11.14738 -16.184 62.24337 11.1864 -17.13964 62.89583 11.24412 -17.77659 63.86093 16.62523 -16.78535 62.03632 16.71474 -16.8 62.04289 16.68815 -17.67918 63.09556 16.75489 -17.68328 63.10049 19.38268 -17.68724 66.04785 20.42843 -16.81418 66.19181 19.37878 -17.69806 65.86931 19.36111 -17.70918 65.67164 19.1969 -17.7393 65.00982 19.13345 -17.7446 64.85494 18.79529 -17.75727 64.27664 18.71434 -17.7581 64.17284 18.24332 -17.75396 63.70946 18.14067 -17.75151 63.63208 17.57111 -17.73058 63.31061 17.40479 -17.72243 63.24595 20.4241 -16.85301 65.93911 20.39976 -16.89309 65.65953 20.16709 -17.0025 64.72684 20.07725 -17.0219 64.5095 19.60119 -17.06834 63.70017 19.48771 -17.07142 63.55498 18.82791 -17.05619 62.90471 18.68384 -17.04721 62.7955 17.87991 -16.9707 62.33913 17.64353 -16.94109 62.24699 21.58053 -16.10107 66.05926 20.86751 -16.40584 66.11638 -16.63084 -15.04458 60.94364 -16.01963 -15.65245 61.38731 -15.26808 -16.19693 61.87516 -13.7886 -16.25707 61.59187 -14.93441 -16.4584 62.20584 -13.55635 -16.33463 61.71632 -14.59977 -16.67472 62.43129 -13.09873 -16.4419 61.8725 -13.96099 -17.00156 62.71764 -12.72026 -16.50053 61.95545 -13.44243 -17.20376 62.8722 -12.04945 -16.55756 62.04814 -12.53254 -17.45096 63.05057 -11.68396 -16.56824 62.07984 -12.03925 -17.53539 63.11564 -10.8477 -16.54721 62.11933 -10.88838 -17.32145 62.78811 -10.91412 -17.61167 63.21135 -10.9425 -17.82527 63.67782 43.1619 -24.53051 12.68083 42.97471 -23.66224 13.51863 43.83063 -23.57611 12.17183 43.53645 -22.85969 13.01726 44.15087 -22.96518 11.91285 44.5881 -21.76307 11.52235 44.76122 -20.93496 11.3313 44.84476 -19.68773 11.14791 43.80468 -22.34396 12.76206 44.16858 -21.32601 12.37712 44.31015 -20.62296 12.18892 44.37186 -19.56203 12.00933 42.12487 -25.12884 14.01406 41.90972 -24.3846 14.54268 41.07093 -25.10574 15.29545 42.11043 -25.7733 13.33282 39.63077 -26.09487 16.57902 38.12981 -26.81048 17.89601 37.02583 -27.14748 18.84733 35.45291 -27.37743 20.17551 33.82326 -27.3406 21.51991 33.59287 -27.31504 21.70772 31.72614 -26.94247 23.2147 29.83665 -26.30009 24.73099 27.95022 -25.43456 26.2735 41.24897 -25.89731 14.79057 39.73411 -26.96557 16.12249 38.14257 -27.75675 17.49785 36.96646 -28.14228 18.49519 35.28849 -28.42902 19.89005 33.55391 -28.43636 21.30183 33.30933 -28.41602 21.49891 31.33501 -28.07832 23.07846 29.35025 -27.46107 24.66425 27.38075 -26.61199 26.27261 41.19414 -26.57914 14.12328 39.60058 -27.70758 15.4831 37.91653 -28.55286 16.89018 36.66833 -28.97084 17.91061 34.887 -29.29264 19.33568 33.05011 -29.32447 20.77433 32.79168 -29.30683 20.97486 30.71104 -28.98605 22.58011 28.62766 -28.37889 24.19057 26.56502 -27.53191 25.82652 41.86779 -26.25497 12.56552 40.91199 -27.08204 13.36127 39.24469 -28.24032 14.73028 37.47819 -29.10554 16.14417 36.16845 -29.53034 17.16614 34.30262 -29.85175 18.58719 32.38579 -29.87458 20.01482 32.11675 -29.85522 20.21336 29.95555 -29.51825 21.80056 27.79644 -28.89152 23.39357 25.65808 -28.01946 25.02004 26.38546 -17.77924 59.03084 26.83276 -17.86228 61.39475 26.71791 -17.85316 61.34732 24.57769 -17.94086 58.98142 26.04675 -17.94004 59.2935 29.73302 -17.64197 63.8708 28.12782 -17.81811 62.18907 27.90976 -17.83831 61.98931 27.84463 -17.84402 61.93861 27.46038 -17.86941 61.6919 27.33487 -17.87344 61.62479 27.02443 -17.87205 61.47668 26.871 -17.86481 61.41064 29.74676 -17.64023 63.88518 31.97185 -17.3075 66.18857 30.22471 -17.57741 64.38479 33.73253 -16.96098 67.92032 33.48697 -17.01475 67.68658 32.89035 -17.13776 67.10769 19.78063 -17.66497 49.23799 23.08342 -17.775 54.15614 19.17441 -17.92807 49.65564 22.55963 -18.00682 54.52237 18.5347 -17.99206 50.09975 22.00349 -18.06624 54.9089 22.11491 -17.96288 56.08022 17.9251 -17.86069 50.52602 -8.549957 -17.80619 63.76315 -8.464771 -16.40272 62.17437 -8.5005 -17.2498 62.84074 -6.15926 -17.78726 63.83201 -6.11682 -17.17922 62.88074 -3.607701 -17.70697 66.01358 -2.573504 -16.8851 65.89871 -3.64579 -17.71088 65.81562 -3.898046 -17.72589 65.16213 -3.988751 -17.72989 65.011 -4.443154 -17.74615 64.48288 -4.57711 -17.75023 64.372 -4.71494 -17.7542 64.27254 -5.329425 -17.76986 63.9683 -5.490316 -17.77353 63.91951 -6.148705 -17.78706 63.832 -2.626767 -16.89923 65.62179 -2.979331 -16.95365 64.71018 -3.105923 -16.9682 64.50002 -3.738676 -17.02757 63.76844 -3.924788 -17.04251 63.61554 -4.116109 -17.05707 63.47867 -4.967516 -17.11475 63.06238 -5.190222 -17.12832 62.99622 -6.10218 -17.17848 62.88064 26.46297 -17.76782 61.81138 26.57887 -17.82752 61.34946 26.576 -17.80566 61.60562 26.61361 -17.83404 61.34853 26.6658 -17.84368 61.3477 26.66129 -17.8342 61.45039 26.42253 -17.75428 61.88498 26.16498 -17.74402 61.38344 26.44029 -17.80077 61.3561 25.72829 -17.6442 61.46628 25.74155 -17.64741 61.46303 25.74526 -17.64519 61.47684 25.98279 -17.70384 61.41201 26.02921 -17.67632 61.65166 26.26754 -17.78225 62.28804 26.02656 -17.67078 61.95055 23.23162 -16.49782 65.95251 23.32318 -16.66204 65.05377 23.50843 -16.80507 64.39585 23.88261 -17.0033 63.62482 24.24012 -17.15237 63.13325 24.83612 -17.35774 62.56552 25.28048 -17.48736 62.27148 26.50924 -17.77522 61.93774 26.80736 -17.87041 62.20467 26.80212 -17.87211 62.2159 26.70916 -17.84811 62.17792 26.78848 -17.87303 62.22931 26.80857 -17.86807 62.19316 26.79741 -17.85967 62.16157 26.73529 -17.83693 62.09454 26.74917 -17.87091 62.24731 25.04249 -17.4626 61.70149 24.50105 -17.296 61.99184 23.75486 -17.02536 62.59201 23.29356 -16.82481 63.13547 22.79247 -16.55382 64.01434 22.52765 -16.35579 64.78138 22.3651 -16.12642 65.84643 16.85782 -16.3434 61.54592 16.98496 -16.07236 60.86203 17.93899 -16.2435 61.0667 19.45386 -16.6505 62.69406 19.01016 -16.62809 62.34287 18.22174 -16.56072 61.91462 17.68327 -16.4999 61.73532 20.85163 -16.49486 65.41286 20.7268 -16.56432 64.75707 20.39895 -16.62923 63.91967 20.06893 -16.65237 63.38224 18.54795 -16.32976 61.2838 19.43445 -16.42357 61.78305 19.93253 -16.45407 62.18432 20.62615 -16.45534 62.9622 21.00306 -16.42221 63.56705 21.38733 -16.32985 64.51115 21.54382 -16.23029 65.25492 22.29114 -16.24534 65.13102 22.09366 -16.36676 64.28424 21.64019 -16.4792 63.21641 21.20741 -16.51994 62.5336 20.42166 -16.52018 61.65147 19.86018 -16.48475 61.19121 18.85908 -16.3733 60.60631 18.16718 -16.26933 60.34181 17.066 -16.06991 60.11989 16.7401 -16.00446 60.09713 16.69784 -16.01492 60.83719 16.60525 -16.28931 61.51963 16.41113 -15.93609 60.09185 16.39651 -16.00594 61.02326 16.34909 -16.23247 61.50662 16.29681 -16.4822 61.82067 12.31466 -15.74617 61.83424 8.407433 -15.28921 61.84564 8.446093 -14.79704 61.07712 12.40614 -15.1756 60.13368 8.453962 -14.69687 60.16925 12.39232 -15.26179 61.05247 -10.07696 -16.01572 61.74552 -10.11835 -15.60814 61.04097 -10.1279 -15.51404 60.23148 26.49706 -17.7722 61.93008 27.77071 -17.88846 62.32262 27.28394 -17.90797 62.20622 27.3943 -17.90834 62.21977 27.41021 -17.91761 62.26909 27.71906 -17.89271 62.30023 26.83485 -17.86825 62.17473 26.86936 -17.87467 62.18141 27.00712 -17.89196 62.18798 26.57073 -17.79079 61.97629 26.71286 -17.82999 62.07578 27.35461 -17.93034 62.32399 27.2731 -17.94484 62.39589 27.12191 -17.96103 62.50951 42.04496 0.0090245 52.25225 42.84017 0.282193 53.39157 42.16152 0.02427983 52.41926 40.59029 0.2682285 62.38774 41.14378 0.2642874 59.57926 41.22208 0.2639759 59.26297 42.73371 0.2740778 53.77291 40.4084 0.2740623 64.86296 40.4084 0.2741799 64.95001 -0.1822794 -13.62311 83.11024 -0.1547312 -13.62069 83.11404 -0.2573706 -12.88226 84.3165 -0.23627 -12.8789 84.31967 -0.350394 -11.72417 85.12875 -0.3149782 -11.71902 85.1314 -0.2099534 -13.62597 83.10806 -0.2786484 -12.88628 84.31378 -0.3859013 -11.7314 85.12644 1.940542 -14.63032 86.55998 1.84041 -14.92515 86.11347 1.821345 -15.20555 85.64728 1.782543 -15.10423 85.54321 1.519974 -14.59632 84.94626 1.898693 -14.47098 86.49397 1.614424 -13.65781 86.11835 1.250123 -12.9553 85.7641 0.9088857 -12.47809 85.52033 0.5462636 -12.10208 85.33363 0.3505901 -11.94754 85.26005 0.07667034 -11.7898 85.18637 -0.1095907 -11.72901 85.1539 1.795495 -14.79655 86.03005 1.49294 -14.15067 85.55718 1.112865 -13.61709 85.1122 0.767907 -13.27971 84.80593 0.4198866 -13.04223 84.57131 0.2444434 -12.95829 84.47898 0.02161848 -12.88917 84.38697 -0.1094717 -12.87258 84.3469 1.186392 -14.17991 84.36412 0.8778833 -13.91971 83.93923 0.5562933 -13.73942 83.58323 0.3867462 -13.67692 83.42717 0.1564816 -13.6268 83.2519 0.006062626 -13.61558 83.16639 -0.8363823 -11.79788 85.12675 -0.601933 -12.93342 84.31494 -0.4516677 -13.66122 83.11028 -1.569243 -12.01961 85.12779 -2.125699 -12.29598 85.12911 -2.747746 -12.74795 85.13126 -1.128588 -13.09079 84.31878 -1.52953 -13.28728 84.3236 -1.979521 -13.6094 84.33153 -0.8455203 -13.7789 83.11773 -1.145479 -13.92588 83.12707 -1.482338 -14.16692 83.14248 35.04648 -17.99982 72.69026 35.27907 -17.99065 72.59275 35.85982 -17.62383 71.36682 36.73428 -17.58684 71.93637 36.63299 -16.57619 70.3984 38.15291 -16.39297 71.33394 34.26055 -17.67746 70.08004 35.11186 -16.76929 69.23845 35.04111 -17.99992 72.70236 35.24143 -17.99586 72.67939 36.53332 -17.8168 72.49932 37.96208 -17.26937 72.28353 35.03574 -17.99996 72.71447 35.20368 -17.99809 72.76613 36.30419 -17.91568 73.08914 37.54837 -17.67203 73.45524 38.74948 -16.16127 71.53462 38.46001 -17.38541 73.70526 38.72378 -16.99557 72.51048 38.83288 -17.23975 73.78878 39.80029 -16.47509 72.72875 39.74189 -16.80872 73.94641 40.5515 -16.00482 72.80679 40.63018 -16.27012 74.03368 41.50496 -15.25082 72.80339 41.74699 -15.38854 74.03285 39.59627 -15.73163 71.7272 40.19022 -15.35009 71.79553 40.94871 -14.74604 71.79103 41.43854 -14.26875 71.72009 42.11624 -14.64931 72.72489 42.05567 -13.53388 71.52302 42.87954 -13.71624 72.50513 42.07991 -15.07057 74.00308 42.45399 -14.6755 73.94921 43.3211 -13.55859 73.71208 43.93963 -12.19812 72.52133 45.00828 -8.031661 72.63027 45.00827 -8.0335 72.6243 45.0082 -8.05296 72.63486 45.00816 -8.056031 72.62489 44.99117 -8.585703 72.74562 44.98701 -8.617725 72.63317 44.92024 -9.324405 72.88816 44.89914 -9.390848 72.62766 44.53322 -11.04575 73.19532 44.41971 -11.16861 72.56589 44.24708 -11.82695 73.33678 44.14906 -12.05551 73.38006 45.00825 -8.035341 72.61834 45.00809 -8.059102 72.61491 44.97829 -8.649432 72.5209 44.85418 -9.453543 72.36927 44.17688 -11.24262 71.96612 43.50461 -12.21967 71.73909 44.72028 -8.574408 70.71717 44.68849 -9.944083 72.11431 42.12168 -13.15964 71.27186 42.37005 -11.81234 70.23845 43.7699 -11.02691 71.02709 42.61118 -10.60368 69.09731 43.88932 -9.730982 69.79393 37.53981 -15.58876 70.17387 40.78607 -12.93717 70.13732 44.35823 -11.08358 83.14398 44.42913 -11.35389 82.21305 44.84487 -9.800741 81.87351 44.83164 -9.62968 82.35669 45.00831 -8.022361 81.41491 45.00831 -8.020125 81.42083 45.0083 -8.017889 81.42675 44.73259 -9.447835 82.82575 43.99811 -10.73603 83.97718 43.41993 -11.39961 84.47941 43.9818 -11.83463 83.50149 42.29405 -12.37817 85.00708 42.82661 -12.6982 84.53032 43.23526 -12.94376 83.90901 43.38402 -13.03316 83.55706 44.24743 -11.82611 82.29306 44.12258 -12.11469 82.334 43.57977 -13.15079 82.409 41.99632 -14.8303 83.55706 42.15963 -14.98992 82.409 41.53126 -14.37573 84.53032 40.83525 -13.69542 85.18064 42.07939 -15.07109 82.40742 42.02363 -15.12641 82.40446 41.79183 -15.00668 83.5959 41.25049 -14.55338 84.5904 40.48908 -13.84142 85.2236 41.90438 -15.24186 82.39291 41.60512 -15.16073 83.61547 40.99308 -14.70993 84.62193 40.17644 -13.96914 85.2344 41.50212 -15.60465 82.29679 40.91424 -15.68143 83.55722 40.03312 -15.24985 84.54594 39.04871 -14.40293 85.04978 38.83567 -17.23859 81.49294 40.28271 -16.49594 81.88973 39.74575 -16.48409 83.10267 39.00441 -15.97621 84.07846 38.20363 -15.07161 84.6263 38.71987 -17.28571 81.46499 38.27646 -17.17852 82.63825 37.71507 -16.59972 83.60494 37.13455 -15.65121 84.19484 35.92736 -16.97617 83.02805 35.75028 -17.38291 82.48495 35.95975 -17.61757 82.10992 35.5219 -17.73388 81.77867 35.19186 -17.97052 80.8235 35.23271 -17.98183 80.7279 35.02308 -17.99993 80.36367 35.02055 -17.99988 80.36988 35.02561 -17.99996 80.35746 35.02814 -17.99997 80.35125 35.03067 -17.99998 80.34504 35.27359 -17.98952 80.63194 35.31443 -17.99357 80.53575 35.3552 -17.99398 80.43946 36.17338 -17.78019 81.70064 36.38547 -17.86646 81.26802 36.59038 -17.87406 80.82356 36.08258 -16.51795 83.46643 36.41792 -17.06523 83.02908 36.77331 -17.45989 82.46234 37.12492 -17.67548 81.80419 37.44918 -17.69754 81.09877 36.33447 -15.62308 84.01192 36.75595 -16.46495 83.65571 37.22315 -17.10366 83.03357 37.68347 -17.4673 82.21556 38.08509 -17.51491 81.29376 30.03569 -15.83939 83.83168 34.55898 -15.83939 83.54092 29.83834 -16.97488 83.09909 29.54297 -17.73358 82.00269 34.66091 -16.97488 82.78909 34.81348 -17.73358 81.6639 32.28283 -15.83939 83.46056 32.23416 -16.97488 82.70342 32.16131 -17.73358 81.57028 2.534059 -14.13112 0.376586 2.570221 -14.13112 0.1949306 2.673194 -14.13112 0.0409727 2.827276 -14.13112 -0.06181311 3.008975 -14.13112 -0.09775519 34.3299 -30.00265 17.92329 24.56618 -29.18305 21.47299 19.42585 -24.93422 28.97465 23.57031 -17.72076 59.00402 14.17341 -15.58395 59.47192 9.794281 -14.88432 59.67037 1.786134 -15.32861 52.27017 -20.89557 -19.98082 12.51873 41.2237 -26.92485 10.5714 36.77192 -30.02786 10.41557 39.02755 -28.68 10.49069 24.92302 -31.86158 8.183105 29.75404 -31.95034 8.29618 5.861208 -25.94569 9.636059 -2.860336 -22.99702 9.364696 -21.15818 -19.81008 8.765906 -11.57289 -20.97378 9.071703 -20.18539 -18.88029 28.19099 -10.51933 -18.90727 28.46138 -10.36325 -17.60773 36.43695 -10.35182 -17.06866 40.43827 -10.59791 -16.16302 52.37734 -2.195471 -15.46571 52.32373 5.767182 -15.42995 52.18724 14.21896 -16.7208 51.90044 14.40069 -19.10135 40.4385 14.3228 -18.09668 44.26433 14.72481 -23.47018 28.97491 14.49712 -20.38905 36.61437 19.715 -28.06869 21.4088 29.55693 -30.74043 17.80438 31.9583 -30.52035 17.86069 38.99681 -28.45665 14.31244 1.902045 -16.20676 44.48109 -2.023294 -16.77758 40.5406 -2.04868 -16.19869 44.48416 -10.38735 -16.67228 44.43577 -6.088829 -17.50838 36.52088 -2.669334 -22.72907 13.17107 9.868777 -15.86078 52.06632 5.8652 -16.47343 44.44873 1.929724 -16.8945 40.56511 -2.030217 -17.55411 36.59271 -6.230774 -19.08926 28.59207 -10.83679 -20.15547 20.57957 -20.46909 -19.65554 20.24902 -11.29612 -20.94121 12.85249 -6.919521 -21.72381 13.01463 -6.513784 -20.65048 20.73984 -2.353266 -21.35221 20.89179 -2.135908 -19.44936 28.7122 1.892236 -20.03691 28.81609 1.937164 -17.8082 36.64514 5.937801 -18.33374 36.67086 5.904551 -17.27736 40.56128 29.42971 -29.60733 21.54808 27.00131 -29.50016 21.50834 24.70273 -30.43503 17.70535 24.89711 -31.84925 10.09981 27.32348 -32.02724 10.1573 29.73259 -31.96813 10.21693 32.116 -31.63789 10.27939 34.46525 -31.00248 10.34537 19.94961 -30.37707 13.80949 24.81591 -31.36905 13.91589 36.72949 -29.76373 14.23245 34.41167 -30.69452 14.15935 32.05239 -31.28474 14.09215 29.66065 -31.57009 14.02984 27.24548 -31.58629 13.97142 19.84314 -29.38097 17.61559 14.95476 -26.56361 21.34226 15.054 -27.87281 17.52449 15.13393 -28.87985 13.70263 20.02636 -30.91815 9.988451 20.05108 -30.95929 8.074886 15.18789 -29.44712 9.87731 10.23499 -22.05909 28.95251 5.978571 -23.505 21.15572 5.956581 -24.61431 17.30104 5.918068 -25.46952 13.45933 1.769482 -22.29318 21.03166 5.980283 -20.90071 28.89808 10.09077 -19.18557 36.66254 10.02381 -17.99535 40.52119 9.9649 -17.07866 44.37871 44.75586 -0.843139 13.64019 42.74718 -0.7280515 16.27799 43.93702 -0.4397252 15.66457 44.04092 -1.527383 14.372 42.78541 -0.902197 16.04643 42.98387 -1.957977 14.83253 43.14828 -3.112498 13.80962 44.12552 -2.737332 13.2794 43.17446 -3.332237 13.64508 44.13887 -2.969351 13.10337 43.29308 -4.533118 12.8932 44.19898 -4.244363 12.29824 43.37873 -5.793116 12.34357 44.24198 -5.591269 11.70888 43.43385 -7.201682 11.98649 44.2695 -7.103428 11.32566 44.27753 -8.5 11.21295 44.77886 -2.174349 12.48373 44.78247 -2.429461 12.29745 44.79867 -3.830516 11.44554 44.81021 -5.30925 10.8221 44.81756 -6.968297 10.41681 44.8197 -8.5 10.29761 44.82109 -10.79842 10.33756 44.28271 -10.76394 11.24995 44.83024 -15.13698 10.61883 44.31707 -15.04695 11.51168 20.12081 -14.13842 -0.05244028 19.96275 -14.13112 -0.0772354 20.12081 -14.28923 -0.07706356 20.569 -8.810261 29.3702 20.58905 -8.810724 29.41101 20.63478 -9.910614 29.39923 20.48959 -8.809633 29.26267 20.53996 -9.907855 29.24234 20.76139 -12.24966 29.08592 21.07653 -13.855 28.81253 21.222 -14.35643 28.67844 21.66886 -15.45381 28.24999 21.94077 -15.92429 27.98122 22.56472 -16.69317 27.3511 20.84468 -12.26163 29.2603 21.15292 -13.88204 28.99569 21.29734 -14.39048 28.86286 21.74659 -15.50715 28.43212 22.02261 -15.98662 28.15923 22.65847 -16.76715 27.51721 36.0192 -16.1028 -0.05780196 20.11702 -16.10665 -0.07831341 42.32205 -16.10188 2.539199 40.97888 -16.1028 1.444422 39.45019 -16.1028 0.6284435 37.76846 -16.1028 0.1164899 44.97952 -13.72615 8.867868 44.98188 -13.53729 8.87748 44.96741 -14.43717 8.728493 44.97386 -14.72078 8.619923 44.96217 -14.93175 8.430149 44.94514 -15.065 8.214112 44.92118 -15.12484 7.97272 26.18729 -18.66775 23.73534 26.66427 -18.76922 23.2613 27.91011 -18.82332 22.01546 29.11556 -18.58658 20.81001 30.30383 -18.05443 19.62174 31.38591 -17.26675 18.53965 32.38264 -16.20836 17.54291 33.21936 -14.95855 16.70619 33.91219 -13.49323 16.01336 34.40922 -11.92219 15.51633 34.72002 -10.21516 15.20553 26.2949 -18.7458 23.86325 26.77467 -18.84812 23.38471 29.24479 -18.66407 20.91458 28.03008 -18.90263 22.12929 31.53258 -17.33411 18.62678 30.44219 -18.12784 19.71718 33.38013 -15.00817 16.77924 32.53697 -16.26758 17.62239 34.57912 -11.94848 15.58024 34.07827 -13.53159 16.08109 34.89231 -10.22834 15.26705 25.85975 -18.57846 24.06269 25.51667 -18.47925 24.37932 25.96654 -18.65622 24.19142 25.63092 -18.55579 24.51565 24.29662 -17.97995 25.61324 23.22286 -17.27173 26.69954 24.40128 -18.05756 25.75938 23.31822 -17.34816 26.85528 23.27963 -17.31692 26.89137 23.18238 -17.24082 26.73325 23.01467 -17.10242 26.90305 23.11035 -17.17811 27.06274 44.77167 -15.19906 7.10982 44.37722 -15.48373 5.732123 43.67279 -15.838 4.269625 43.23063 -15.97881 3.601225 42.38498 -2.06537 15.00969 39.09371 -7.744481 13.98615 39.28273 -5.538837 14.33952 39.19499 -6.263092 14.17552 41.36745 -6.197128 13.24727 39.13192 -6.998589 14.0576 39.81265 -3.018727 15.33044 39.63864 -3.669376 15.00498 41.75751 -4.014317 13.92288 39.48649 -4.347151 14.72046 39.35675 -5.05165 14.4779 40.15383 -1.987384 15.96882 40.00817 -2.395873 15.69623 40.63434 -0.879701 16.86847 40.38531 -1.413837 16.40213 17.75 -8 0 -19.75012 9.282606 52.22771 -18.76643 10.45214 51.53892 -20.03813 8 52.42937 -17.03813 11 50.32875 -20.03813 7.187853 52.42937 -22.0915 2.720362 53.86716 -21.22588 5.25289 53.26105 -19.33343 -5 79.81603 -12.53002 -9.820047 83.83748 -12.78049 -9.607796 83.84954 -13.5013 -8.499462 83.83413 -13.50073 -8.133553 83.83418 -13.67147 -8.055504 83.81962 -13.13436 -8.499328 83.85126 -13.02591 -8.773854 83.85263 -13 -8.998924 83.85272 -13.15502 -8.465194 83.85081 -13.37805 -8.216938 83.84204 -12.94338 -9.322487 83.85255 -15.12788 -8 83.51877 -13.99998 -8 83.7797 -15.73451 -7.999833 83.29296 -17.0709 -7.996808 82.54124 -17.66153 -7.996282 82.06729 -18.17384 -7.99605 81.5585 -18.56849 -7.999944 81.09384 -18.95099 -7.845929 80.525 -19.08877 -7.667719 80.2914 -19.19069 -7.425 80.10408 -19.24919 -7.150698 79.99002 -19.26909 -6.85 79.95001 -19.26909 -5.5 79.95001 -19.28614 -5.238478 79.9152 -19.9916 -4.5 76.85272 -19.67003 -4.5 78.95 -19.49192 -4.633975 79.45001 -19.9916 -4.5 67.6 -19.9916 0 67.6 44.9793 -8.346832 8.870056 44.99984 -8 8.946176 43.17281 -9.5 -0.5407877 43.56593 -8 -0.624448 44.40542 -8 3.539999 40.63164 -11 0 42.09878 -10.59808 -0.3122239 44.00985 -9.5 3.611209 44.9972 -8 8.69508 44.79846 -8 6.07959 44.79636 -8 6.062592 41.66331 -0.2351384 -9.683796 41.66273 -0.1999999 -9.687094 41.89669 -0.1999999 -9.277047 40.58488 -0.2623777 -10.64873 40.58559 -0.1999999 -10.65144 41.18207 -0.1999999 -10.23606 39.18235 -0.275 -10.99656 39.18214 -0.1999999 -10.99909 40.14959 -0.1999999 -10.8397 40.55559 -10.98903 -0.4911733 42.0149 -10.57828 -0.783462 43.0877 -9.482539 -0.9628561 43.20824 -7.817915 -2.31229 43.38127 -7.952596 -1.492497 43.48985 -7.992021 -0.9818416 40.27199 -10.74963 -2.333529 41.70443 -10.31564 -2.53943 40.19071 -10.61914 -2.869472 41.42717 -9.7895 -4.160581 40.0151 -10.2274 -4.049726 39.77973 -9.404109 -5.706378 41.17753 -8.983589 -5.714834 39.70476 -9.044546 -6.260687 40.97784 -7.962766 -7.077631 39.58735 -8.345894 -7.165617 39.43231 -7.034022 -8.4571 40.82122 -6.707039 -8.280981 39.37992 -6.424726 -8.928768 40.711 -5.280932 -9.255839 42.77357 -9.248149 -2.531697 42.49438 -8.777339 -3.974628 42.95611 -7.43811 -3.53728 42.2444 -8.055422 -5.352837 42.72776 -6.839351 -4.706092 42.04574 -7.140457 -6.55667 42.5433 -6.069741 -5.723596 41.89114 -6.01457 -7.615592 42.39635 -5.115653 -6.613751 41.78336 -4.735718 -8.47027 42.29058 -4.028229 -7.327242 41.71383 -3.311891 -9.115478 42.21952 -2.816476 -7.861939 41.6759 -1.80761 -9.521874 42.17906 -1.536777 -8.196611 42.16362 -0.1999999 -8.332178 39.31948 -5.538814 -9.503765 39.24294 -3.872655 -10.29575 40.63914 -3.693221 -9.9942 39.19903 -2.113069 -10.79514 40.59952 -2.015765 -10.46045 44.79636 8 6.062592 44.99994 8 9.003568 44.99994 0 9.003568 44.99992 8 8.983509 44.40542 8 3.539999 43.56593 8 -0.624448 43.50486 7.994863 -0.9113237 43.38129 7.952606 -1.492405 43.22221 7.832268 -2.245628 42.67709 -4.076298 -4.977373 42.16349 0 -8.333323 42.16419 0.3307868 -8.327054 42.18186 1.664896 -8.172566 42.2251 2.940395 -7.817756 42.2994 4.141479 -7.264505 42.3972 5.122584 -6.608313 42.54447 6.075864 -5.716789 42.73583 6.866046 -4.663351 42.96564 7.457124 -3.489964 36.025 -11 0 36.025 -3.062392 -10.56512 36.025 -10.61905 -2.869793 36.025 -9.044273 -6.26108 36.025 -6.424487 -8.928941 36.025 -0.1999999 -10.99909 36.025 11 11 36.025 11 0 36.025 10.46162 -3.399187 36.025 8.899188 -6.465638 36.025 6.465638 -8.899188 36.025 3.399187 -10.46162 36.025 0 -11 -18.5 10.82065 1.978268 -21.175 10.82065 1.978268 -21.175 11 3 26.375 11 3 26.375 10.82065 1.978268 20.75 10.82065 1.978268 20.05867 10.76414 1.833999 18.63004 10.08733 0.8452252 -15.90685 9.5 0.401924 18.72146 10.16809 0.9264994 -16.47273 10.16915 0.927616 19.45 10.59808 1.5 -17.2 10.59808 1.5 -17.80663 10.76378 1.83317 17.85858 8.799146 0.1083972 17.75 8 0 -15.5 8 0 18.15685 9.5 0.401924 -15.60911 8.801056 0.1089262 42.21895 -0.1999999 48.65937 42.28141 -0.1999999 47.96597 39.85355 -0.1999999 46.4688 40.38549 -0.1999999 46.64968 41.45685 -0.1999999 47.3726 27.45289 -0.1999999 40.14933 27.83639 0 40.4205 29.96534 0 41.75547 25.95978 0 38.96857 24.96159 -0.1999999 38.03841 24.96588 0 38.0427 24.96159 0 38.03841 24.33072 -0.1999999 37.33955 24.33072 0 37.33955 24.64615 2.40028e-5 37.68898 22.51754 0 33.97518 22.51754 -0.1999999 33.97518 22.04279 0 32.2047 21.74617 -0.1999999 30.23132 21.74617 0 30.23132 22.53558 0 34.02817 22.82957 0 34.80249 23.8754 -0.1999999 36.73232 23.53734 0 36.20714 44.07508 -0.1999999 15.92404 44.07508 -1.2299e-5 15.92404 43.29472 0 16.14709 45 0 12.77053 44.94065 -0.1999999 13.58718 44.76366 0 14.40416 44.76366 -0.1999999 14.40416 40.25254 0 -10.80252 39.18207 0 -11 41.84829 0 -9.375223 41.18207 0 -10.23606 42.28141 0 47.96597 40.6 0.3751289 67.6 41.62487 1.4 67.6 42 2.8 67.6 -39.24811 6.5 27.20958 44.52726 2.8 53.00334 44.69887 2.8 51.89873 44.56245 3 52.80884 44.52726 3 53.00334 44.28023 3 54.14993 44.28023 2.8 54.14993 42.50464 0.01007306 48.13273 42.50464 0.06371182 48.13273 42.52906 0.01240372 48.15113 42.52906 0.06397241 48.15113 43.24439 0.1939953 48.69036 43.38637 0.4592789 48.79738 44.10743 1.155077 49.34093 43.96454 0.6469119 49.23322 43.59406 0.3728185 48.95394 44.79364 1.962608 49.8582 44.56021 1.397777 49.68225 44.47695 1.254793 49.61948 44.71686 2.260506 49.80032 44.91413 3.0052 49.94902 44.91413 2.8 49.94902 44.6288 2.039643 49.73394 44.91386 2.760485 49.94882 42.30847 0.06408381 47.98604 41.19042 0.06652599 47.188 40.38549 0.06859594 46.64968 39.63935 0.02821397 46.45204 39.85355 0.04339271 46.4688 40.21927 0.06573867 46.56009 -36.61457 1.51398 -8.910649 -35.92132 1.695384 -9.978317 -34.83835 1.811508 -10.66177 -34.83835 4.361703 -9.895987 -34.83835 6.647487 -8.530295 -34.83835 8.530295 -6.647487 -34.83835 9.895987 -4.361703 -34.83835 10.66178 -1.811508 -34.83835 10.81457 0 -35.3 10.59808 0 -36.39807 9.5 0 -35.92132 10.12132 0 -35.92132 9.978317 -1.695384 -36.61457 8.910649 -1.51398 -36.61457 9.038352 0 -36.61457 8.270637 -3.645322 -36.61457 7.12925 -5.555681 -36.61457 5.555681 -7.12925 -36.61457 3.645322 -8.270637 -35.92132 9.261619 -4.082102 -35.92132 7.983471 -6.221359 -35.92132 6.221359 -7.983471 -35.92132 4.082102 -9.261619 -33.8 11 11 -34.83835 10.81457 11 -35.3 10.59808 11 -35.92132 10.12132 11 -36.39807 9.5 11 -36.61457 9.038351 11 24.07248 8.658164 79.95001 24.13864 8.90329 79.95001 24.17916 9.022792 79.95001 24.18543 9.038352 79.95001 24.22459 9.140276 79.95001 24.24557 9.188741 79.95001 24.24914 9.198266 79.95001 24.27866 9.262662 79.95001 24.27492 9.255751 79.95001 24.93672 10.17781 79.95001 24.93403 10.17567 79.95001 24.8887 10.13172 79.95001 25.96165 10.81457 79.95001 25.9332 10.80404 79.95001 25.92375 10.8003 79.95001 25.90494 10.79312 79.95001 24.4555 9.590002 79.95001 24.47335 9.617416 79.95001 24.48987 9.643708 79.95001 24.51793 9.685032 79.95001 24.52527 9.696506 79.95001 24.56432 9.75142 79.95001 25.4214 10.55131 79.95001 25.45138 10.56939 79.95001 25.47279 10.58239 79.95001 25.4862 10.59006 79.95001 25.52477 10.61242 79.95001 25.52131 10.61026 79.95001 25.63046 10.66933 79.95001 25.66434 10.68626 79.95001 25.68418 10.6962 79.95001 25.70072 10.70405 79.95001 25.73734 10.72134 79.95001 25.79338 10.74679 79.95001 25.81126 10.75443 79.95001 25.82105 10.75878 79.95001 25.82988 10.76239 79.95001 25.84855 10.77023 79.95001 25.87683 10.78194 79.95001 25.88605 10.78552 79.95001 24.30191 9.312732 79.95001 24.31374 9.335664 79.95001 24.33015 9.369209 79.95001 24.87868 10.12132 79.95001 24.84436 10.08689 79.95001 24.76728 10.00374 79.95001 24.75864 9.99458 79.95001 24.74044 9.973421 79.95001 24.71727 9.947109 79.95001 24.71401 9.94274 79.95001 24.67688 9.898757 79.95001 24.6624 9.880322 79.95001 24.63748 9.849525 79.95001 24.61249 9.816534 79.95001 24.59908 9.799408 79.95001 24.56167 9.748404 79.95001 24.33201 9.371804 79.95001 24.35077 9.407693 79.95001 24.35961 9.425178 79.95001 24.37002 9.443325 79.95001 24.39032 9.480635 79.95001 24.38974 9.478695 79.95001 24.42228 9.535577 79.95001 24.43061 9.54862 79.95001 24.45175 9.583162 79.95001 24.98036 10.21873 79.95001 24.99626 10.23272 79.95001 25.0277 10.26089 79.95001 25.05726 10.28599 79.95001 25.07604 10.30216 79.95001 25.0883 10.31201 79.95001 25.12541 10.34252 79.95001 25.11968 10.3376 79.95001 25.17325 10.38001 79.95001 25.18347 10.38751 79.95001 25.2217 10.41641 79.95001 25.21586 10.41181 79.95001 25.24858 10.43568 79.95001 25.27074 10.45173 79.95001 25.28162 10.4591 79.95001 25.32037 10.48598 79.95001 25.31497 10.48207 79.95001 25.37059 10.51917 79.95001 25.38259 10.52665 79.95001 25.41684 10.54825 79.95001 11.72588 -9.258679 98.14145 11.90933 -9.025 97.4 11.54336 -9.398475 98.0016 11.525 -9.409328 97.4 11.27078 -9.514483 97.88589 11.8872 -9.061576 98.33866 11.91034 -9.023241 98.37699 12.05 -8.5 97.4 11.99853 -8.824703 98.57533 12.0497 -8.525 98.875 11 -9.55 97.4 10.475 -9.409328 97.4 10.7467 -9.51899 97.88156 10.88233 -9.543387 97.85675 11.00042 -9.55 97.84976 11.19421 -9.531883 97.86824 10.08988 -9.023629 98.37659 10.10791 -9.053791 98.34643 10.09067 -9.025 97.4 10.28745 -9.27122 98.12892 10.48033 -9.412385 97.98764 10.00783 -8.843651 98.55625 9.95 -8.5 97.4 9.950299 -8.525 98.875 10.09067 -7.975 98.9 10.09067 -7.975 97.4 10.475 -7.590673 98.9 10.475 -7.590673 97.4 11 -7.45 98.9 11 -7.45 97.4 11.525 -7.590673 98.9 11.525 -7.590673 97.4 11.90933 -7.975 98.9 11.90933 -7.975 97.4 12.01422 -8.22824 98.9 12.05 -8.5 98.9 12.0497 -8.525 98.9 9.950299 -8.525 98.9 9.95 -8.5 98.9 9.958983 -8.362949 98.9 9.985778 -8.22824 98.9 16.525 0.04999995 87.65311 16.525 0 87.65311 17.38448 0.04999995 88.91714 17.45112 0 88.99973 18.63169 0.04999995 90.21912 17.45112 -0.04999995 88.99973 18.26127 -0.04999995 89.87972 19.61024 -0.05000019 90.97061 19.61024 0.04999995 90.97061 5.475 0 87.65311 5.475 0.04999995 87.65311 4.548877 0 88.99973 4.615538 0.04999995 88.91712 4.122714 0.04999995 89.48887 2.389772 0.05000001 90.97063 2.389753 -0.04999995 90.9706 3.368342 0.04999995 90.21909 3.740081 -0.04999995 89.87841 4.548877 -0.04999995 88.99973 16.525 2.920343 89.84761 16.525 4.5 90.52 16.525 4.5 83.95001 16.525 0 83.95001 16.525 0.05588293 87.65315 16.525 0.2271351 87.68482 16.525 0.4156218 87.79087 16.525 1.052269 89.28337 16.525 1.063253 89.31496 16.525 1.253013 89.47109 16.525 1.07093 89.33208 16.525 0.6216115 88.00473 16.525 0.8309162 88.37018 16.525 1.040888 89.22087 16.525 1.113824 89.39595 16.525 1.131512 89.41367 16.525 1.200338 89.45713 16.5 4.5 90.50357 12.1 4.5 88.92303 9.525001 4.5 83.95001 13.41069 4.5 89.15636 14.93606 4.5 89.66651 10.33184 4.5 88.88484 9.9 4.5 88.92303 9.525001 4.5 88.97154 9.525001 6 83.95001 9.525001 5.267948 89.35678 9.525001 6 89.79921 5.475 0 83.95001 5.475 1.040888 89.22087 5.475 0.9268653 88.62847 5.475 6 83.95001 5.475 0.6425546 88.03333 5.475 0.4778812 87.84371 5.475 0.2731142 87.70359 5.475 6 91.51933 5.475 5.763355 91.33309 5.475 4.303596 90.41747 5.475 2.936981 89.85299 5.475 1.253273 89.47113 5.475 1.052361 89.28369 5.475 1.20348 89.45837 5.475 1.170739 89.44255 5.475 1.065431 89.32012 5.475 1.135859 89.41751 5.475 1.097699 89.37628 9.003727 8.4 98.77796 9.003727 8.5 98.77796 9.28049 8.4 98.55516 9.28049 8.5 98.55516 9.461881 8.4 98.24965 9.461881 8.5 98.24965 9.525001 8.4 97.9 9.525001 8.5 97.9 9.525001 8.5 97.54931 9.525001 8.4 97.54931 9 -9.050001 90.767 9 -9 90.83775 9 -9.050001 88.9 13 -9.050001 88.9 13 -9 90.83775 13 -9.050001 90.767 13 -9 97.9 13.00001 -6.301752 97.91022 13 -6 90.83775 13 -6.227205 97.9 13 -6 97.86019 13.83894 -1.284456 88.27266 13.69878 -1.252911 88.23622 13.00169 -5.1 88.08366 13.31073 -1.059956 88.14544 13.1364 -0.9017933 88.10946 14.78053 -5.30759 88.56984 15.25272 -5.568563 88.75517 16.0008 -1.3 89.10246 14.03111 -1.3 88.32587 14.2414 -5.1 88.38842 14.77446 -5.304682 88.56762 15.88888 -7 89.04613 16.73993 -7 89.51634 15.88889 -6 89.04614 15.40564 -5.66539 88.82048 12.80889 0 88.04975 9.191111 0 88.04975 12.80889 -0.04999995 88.04972 9.191105 -0.04999995 88.04972 9.158153 -0.338993 88.05531 8.944957 -0.8026482 88.09368 12.98267 -0.6927235 88.08015 12.92569 -0.58349 88.06987 6.111111 -6 89.04614 6.611826 -5.654841 88.81317 5.405203 -1.264313 89.42909 6.74354 -5.571221 88.7569 7.190725 -5.321292 88.5802 8.998311 -5.1 88.08366 8.533525 -1.158682 88.18012 7.758602 -5.1 88.38842 7.96889 -1.3 88.32587 5.999196 -1.3 89.10246 6.111111 -7 89.04614 5.260067 -7 89.51634 4.176049 -7 90.27251 5.131926 -1.231151 89.59593 4.74322 -1.177315 89.85275 2.869491 -1.175788 91.49076 2.869565 -7 91.49082 3.961088 -1.096133 90.44697 4.3221 -1.124149 90.15897 17.3718 -1.161583 89.93339 17.8132 -7 90.26402 18.50654 -1.099363 90.85938 19.13043 -7 91.49082 19.13043 -1.175788 91.49082 17.13864 -1.193938 89.77218 16.86814 -1.23122 89.59597 16.58267 -1.265658 89.42193 12 -10 90.83775 12.05015 -10 90.29071 12.49713 -9.888198 90.40189 12.34114 -9.940012 90.83775 12.72206 -9.721445 90.46941 12.70705 -9.707159 90.83775 12.85062 -9.561365 90.52208 12.93996 -9.34128 90.83775 12.94223 -9.376236 90.58302 12.98665 -9.208695 90.65068 12.99992 -9.061986 90.75175 9.005198 -9.149256 90.68246 9.057496 -9.375482 90.58329 9.060037 -9.341276 90.83775 9.133975 -9.5 90.83775 9.114307 -9.501788 90.54115 9.292938 -9.707152 90.83775 9.277892 -9.721395 90.46943 9.5 -9.866025 90.83775 9.418658 -9.837512 90.42524 9.658842 -9.940007 90.83775 9.949879 -10 90.29098 10 -10 90.83775 9.8532 -9.99507 90.3143 9.621228 -9.941298 90.3712 9 -6 90.83775 8.999991 -8.994227 90.83115 8.989774 -8.752775 90.63575 8.439874 -7.370632 89.44966 8.493509 -7.431004 89.50754 8.747597 -6 89.86517 8.749513 -7.83306 89.86862 8.880521 -6 90.15683 8.785354 -7.911786 89.93635 8.852055 -8.084345 90.08283 8.086535 -7.10175 89.15863 8.397741 -6 89.40725 8.037576 -7.078943 89.12793 8.054093 -6 89.13807 7.666666 -7 88.95212 7.637173 -6 88.94195 7.094532 -7 88.83998 6.749975 -6 88.85343 7.094532 -6 88.83998 9.95 -10 88.9 10.45618 -10 97.71924 10.01211 -9.999983 98.05502 10 -10 97.9 12.05 -10 88.9 11 -10 97.60003 11.54382 -10 97.71924 12 -10 97.9 11.98791 -9.999927 98.055 10.3875 -3.15 97.83912 11.6125 -3.15 99.96089 12.06088 -3.15 99.5125 9.93912 -3.15 98.2875 9.775 -3.15 98.9 11.6125 -3.15 97.83912 11 -3.15 97.67501 12.06088 -3.15 98.2875 12.225 -3.15 98.9 11 -3.15 100.125 10.3875 -3.15 99.96089 9.93912 -3.15 99.5125 9.809215 -5 98.2125 9.742846 -5 98.34306 9.625 -3.3 98.9 9.723166 -5.020742 98.38979 9.658512 -5.020742 98.59828 9.809215 -3.3 98.2125 10.3125 -3.3 97.70922 10.3125 -5 97.70922 11 -3.3 97.525 11 -5 97.525 11.6875 -3.3 97.70922 11.6875 -5 97.70922 12.19079 -3.3 98.2125 12.19079 -5 98.2125 12.3416 -5.020742 98.59877 12.27684 -5.020742 98.38979 12.25716 -5 98.34306 12.375 -3.3 98.9 12.19079 -3.3 99.5875 12.31716 -5.020742 99.29461 12.375 -5.020742 98.9 11.6875 -3.3 100.0908 11.95497 -5.020742 99.88927 12.19079 -5.020742 99.5875 11 -3.3 100.275 11.3479 -5.020742 100.2303 11.6875 -5.020742 100.0908 10.3125 -3.3 100.0908 10.65162 -5.020742 100.2301 11 -5.020742 100.275 9.809215 -3.3 99.5875 10.04468 -5.020742 99.88893 10.3125 -5.020742 100.0908 9.625 -5.020742 98.9 9.682702 -5.020742 99.29415 9.809215 -5.020742 99.5875 9.818057 -5.151254 100.1235 9.568352 -5.107384 98.13504 9.488845 -5.150352 98.12187 9.34028 -5.151254 98.52671 12.88914 -5.555395 98.05845 12.84106 -5.470862 98.06657 12.97233 -5.471708 98.45714 12.81777 -5.435908 98.07051 12.58789 -5.201189 98.10908 12.65985 -5.151254 98.52731 12.43162 -5.107371 98.13506 12.37584 -5.079031 98.16043 12.32773 -5.051606 98.22497 12.99003 -5.900344 98.04128 13.05841 -6.110832 98.22512 13.05617 -6 98.199 13.064 -6.22993 98.31398 13.11477 -5.9006 98.42516 13.07625 -5.9006 99.52203 13.06439 -6.356179 98.47943 13.06564 -6.323883 98.42983 12.85683 -6.642856 99.45629 12.91865 -6.642857 99.17576 13.02044 -6.349895 99.50531 13.00605 -6.55226 98.9 13.0595 -6.405199 98.56475 12.63535 -6.642854 99.94064 12.46487 -6.349895 100.4175 12.34624 -6.642852 100.2946 11.53366 -6.349895 100.9405 11.49045 -6.642848 100.7753 12.06141 -6.642851 100.5219 9.534594 -6.349895 100.417 9.760156 -6.642842 100.39 10.46561 -6.349895 100.9404 10.48365 -6.642845 100.7683 11.30014 -6.642848 100.815 8.979341 -6.349895 99.5046 9.280398 -6.642839 99.79459 9.653255 -6.642842 100.2941 8.993952 -6.552258 98.9 8.936739 -6.372003 98.50564 8.935355 -6.351727 98.47229 9.081323 -6.642837 99.17571 9.142961 -6.642838 99.45564 9.058588 -5.679071 98.04963 9.012384 -5.878861 98.0417 8.885396 -5.9006 98.4244 9.004933 -6 98.04039 8.94383 -6 98.199 8.941594 -6.110831 98.22512 8.93927 -6.16162 98.25527 8.934825 -6.262164 98.34905 9.607116 -5.088003 98.14871 9.66431 -5.056387 98.2099 9.370209 -5.151254 99.38764 10.56898 -5.151254 100.5457 11.43043 -5.151254 100.5458 12.18151 -5.151254 100.124 12.62962 -5.151254 99.38822 9.181074 -5.437565 98.07031 9.027822 -5.471708 98.45644 9.063385 -5.471708 99.47945 9.595544 -5.471708 100.3539 10.48784 -5.471708 100.8555 11.51146 -5.471708 100.8557 12.40394 -5.471708 100.3544 12.93641 -5.471708 99.48014 8.923527 -5.9006 99.5213 9.494117 -5.9006 100.4589 10.45085 -5.9006 100.9967 11.5484 -5.9006 100.9969 12.50533 -5.9006 100.4594 12.99507 -6 98.04039 8.934401 -6.326043 98.43299 11.32931 -7.363168 99.73629 11.74215 -7.195647 99.93025 11.25592 -7.264546 100.0075 11.78098 -7.179602 99.93679 11.83398 -7.157603 99.94299 11.94381 -7.111667 99.94605 12.10568 -7.043078 99.92648 12.24181 -6.984648 99.88651 12.6038 -6.828299 99.63746 12.7778 -6.741575 99.4146 10.20597 -7.174181 99.93864 10.64782 -7.353991 99.75461 10.74405 -7.264546 100.0075 10.9061 -7.457777 99.4401 11.06838 -7.468299 99.38399 10.99903 -7.498518 99.08433 11 -7.49948 99.04977 9.993097 -7.084999 99.94198 9.775164 -6.992025 99.89264 9.443437 -6.84847 99.68663 9.396225 -6.82827 99.63745 10.17371 -7.160788 99.94232 9.216632 -6.738239 99.40651 9.286767 -6.777135 99.50449 9.679464 -7.01647 99.73749 9.453755 -6.864865 99.66917 9.526664 -7.039707 99.51348 10.33336 -7.269131 99.82433 9.952228 -7.231753 99.69901 10.07134 -7.344212 99.63395 10.61391 -7.551449 99.21464 10.6135 -7.573191 99.0513 9.953261 -8.132639 99.2191 9.910025 -8.455853 99.20715 9.972042 -8.207195 99.16957 9.943185 -8.529528 99.12952 9.981597 -8.258778 99.1205 9.95 -8.549263 99.07154 10.02372 -8.162842 99.06352 9.832092 -8.289469 99.28379 9.874403 -8.379746 99.25066 9.877703 -8.386798 99.24739 9.678812 -7.956234 99.32064 9.776186 -8.169442 99.30965 9.834675 -7.824126 99.34141 9.780548 -8.178977 99.30821 9.882887 -7.932943 99.30914 9.923759 -8.039802 99.26661 9.67754 -7.953423 99.32053 9.777729 -7.710232 99.36357 9.596931 -7.772179 99.2993 9.719212 -7.604649 99.37248 9.65624 -7.501065 99.36799 10.45711 -7.366322 99.68009 10.54193 -7.447352 99.52381 10.59178 -7.509815 99.36597 9.525283 -7.171008 99.38873 9.694419 -7.187157 99.56212 9.561137 -7.361258 99.33145 9.514282 -7.584464 99.2389 10.25754 -7.806956 99.05615 10.30554 -7.742834 99.14823 10.30108 -7.698507 99.23943 10.28078 -7.632773 99.34064 10.23711 -7.548548 99.44659 10.16532 -7.448741 99.54932 10.13928 -7.948007 99.05907 10.14277 -7.924562 99.12395 10.14157 -7.877679 99.1888 10.1293 -7.808838 99.26212 10.0999 -7.72158 99.34007 10.04948 -7.619289 99.41664 9.982005 -7.513249 99.48047 9.895339 -7.400285 99.53027 9.80081 -7.29368 99.55776 12.43127 -7.709235 99.2843 12.48571 -7.58443 99.2389 12.35395 -7.347208 99.41812 12.46259 -7.379713 99.29716 12.46907 -7.213155 99.36735 12.41701 -7.741687 99.29247 12.28274 -7.441043 99.42592 12.39163 -7.798947 99.30414 12.21648 -7.537508 99.41856 12.34955 -7.893075 99.31658 12.15561 -7.636309 99.3983 12.29542 -8.012877 99.3215 12.10323 -7.732593 99.368 12.26054 -8.089064 99.31841 12.21869 -8.180674 99.30795 12.0497 -7.848978 99.31871 12.20527 -8.209673 99.3029 12.01195 -7.953299 99.26273 12.15366 -8.319835 99.27423 11.98871 -8.042631 99.20401 12.10464 -8.42458 99.22753 11.97802 -8.110161 99.14789 12.07418 -8.490302 99.1788 11.97573 -8.141011 99.11294 12.05974 -8.522743 99.14064 11.97578 -8.159037 99.08003 12.05032 -8.547314 99.0841 11.97628 -8.162852 99.06352 12.05 -8.549271 99.07154 11.38548 -7.569951 99.10176 11.3865 -7.573192 99.0513 11.74247 -7.806961 99.05615 11.39995 -7.529678 99.30545 11.44009 -7.472164 99.46768 11.78773 -7.187556 99.91512 11.63117 -7.297863 99.78461 11.51607 -7.393321 99.63217 11.74117 -7.803498 99.08193 11.73904 -7.787477 99.13398 11.73951 -7.759815 99.19061 11.75121 -7.698329 99.28464 11.78419 -7.615329 99.38664 11.84343 -7.516356 99.48685 11.93196 -7.40364 99.57754 12.02115 -7.308665 99.63498 12.12671 -7.209578 99.67518 12.24327 -7.111155 99.69251 12.36992 -7.013665 99.68259 12.47443 -7.172865 99.38775 9.95 -8.550001 99 10.00892 -8.203207 99 11 -7.5 99 10.74344 -7.531826 99 10.2916 -7.774975 99 11.99108 -8.203207 99 12.05 -8.550001 99 11.7084 -7.774975 99 11.25656 -7.531826 99 9.95 -8.550001 98.9 9.955459 -8.443077 98.9 12.05 -8.550001 98.9 11.99108 -8.203207 98.9 11.8763 -7.971558 98.9 11.7084 -7.774975 98.9 11.25656 -7.531826 98.9 9.967003 -8.361807 98.9 10.00892 -8.203207 98.9 10.2916 -7.774975 98.9 10.74344 -7.531826 98.9 12.05 -9 99.07154 12.05 -9.034406 99.07036 12.05 -9.211328 99.02565 12.04996 -9.390825 98.9 12.06506 -9.451295 98.96039 12.08633 -9.482668 98.99172 12.08633 -9.264457 99.14406 12.4404 -9.295998 99.21437 12.4404 -9.048569 99.27672 12.37535 -9.050728 99.30817 12.4404 -9.537191 99.04617 12.37535 -9.308901 99.24314 12.29588 -9.313645 99.2537 12.35185 -9.563876 99.07282 12.37535 -9.559496 99.06844 12.29588 -9.051522 99.31974 12.21229 -9.050436 99.30392 12.21229 -9.307154 99.23924 12.17951 -9.545824 99.05479 12.21229 -9.556478 99.06543 12.26409 -9.56589 99.07482 12.29588 -9.567699 99.07663 12.13876 -9.526015 99.03501 12.13876 -9.289532 99.19996 12.13876 -9.047489 99.26097 12.08633 -9.043293 99.19985 12.11923 -9 99.24423 12.21036 -9 99.30491 12.31867 -9 99.32084 12.4234 -9 99.28896 12.48571 -9 99.2389 12.47843 -9.355033 99.14817 12.46923 -9.521179 99.03018 12.05802 -9.435276 98.94439 12.05802 -9.237042 99.08296 12.05802 -9.038707 99.13303 12.06278 -9 99.15044 9.861239 -9.526015 99.03501 9.861239 -9.471044 99.08547 9.787714 -9.498726 99.11843 9.559598 -9.257676 99.2303 9.515912 -9.174027 99.21783 9.530876 -9.5211 99.0301 9.57388 -9 99.2874 9.514286 -9 99.2389 9.559598 -9.537191 99.04617 9.559598 -9.481201 99.09756 9.62465 -9.559496 99.06844 9.62465 -9.501469 99.12171 9.646118 -9.563566 99.0725 9.704122 -9.508922 99.13058 9.704122 -9.567699 99.07663 9.722538 -9.567003 99.07594 9.787714 -9.556477 99.06543 9.62465 -9.268963 99.25974 9.704122 -9.273114 99.27056 9.787714 -9.267436 99.25575 9.861239 -9.25202 99.21556 9.624649 -9 99.30992 9.678866 -9 99.32064 9.787952 -9 99.30555 9.879972 -9 99.24507 9.913665 -9.482668 98.99172 9.941979 -9.435276 98.94439 9.913665 -9.431657 99.03855 9.941979 -9.388591 98.98725 9.913665 -9.230085 99.15835 9.941979 -9.206103 99.09582 9.95 -9.183609 99.03717 9.95 -9.3482 98.93914 9.95 -9.390825 98.9 9.93707 -9 99.1509 9.95 -9 99.07154 9.638736 -9.699225 98.90526 9.65294 -9.806904 98.72328 9.727143 -9.811209 98.7417 9.953845 -9.4864 98.81024 9.76841 -9.951728 98.33737 9.815502 -9.943811 98.41733 9.740926 -9.937585 98.3808 9.687966 -9.882285 98.55451 9.713086 -9.920287 98.4286 9.595624 -9.787303 98.70063 9.656911 -9.872871 98.5404 9.590881 -9.778019 98.71582 9.575194 -9.67939 98.88465 9.535425 -9.570299 98.98289 9.548441 -9.651947 98.89221 9.551848 -9.6671 98.87353 10.1457 -9.874311 98.23313 10.16789 -9.809807 98.24735 10.03525 -9.76208 98.46656 9.96056 -9.64456 98.70318 9.928578 -9.701764 98.72686 10.00445 -9.82446 98.47052 9.875694 -9.754546 98.74363 9.95436 -9.882019 98.46405 9.80535 -9.793406 98.74916 9.888365 -9.924396 98.44567 9.990514 -9.997722 98.11711 9.966005 -9.998608 98.09786 10.05228 -9.977646 98.16477 10.10643 -9.933827 98.20522 10.07654 -9.985174 98.11013 10.14579 -9.927609 98.16937 10.19019 -9.837027 98.20734 10.20208 -9.75 98.21751 10.03293 -9.689511 98.49103 11.8481 -9.746126 98.28113 11.79789 -9.75 98.21754 11.80981 -9.837027 98.20734 12.22047 -9.956727 98.32082 12.23165 -9.951685 98.3376 12.15276 -9.954818 98.37822 12.37521 -9.834509 98.61721 12.43605 -9.711852 98.81417 12.36767 -9.705039 98.89299 12.4391 -9.702023 98.82761 12.442 -9.677424 98.86558 12.04603 -9.676257 98.69644 12.00361 -9.641942 98.59137 12.17105 -9.79571 98.72914 12.09893 -9.74638 98.72039 12.35929 -9.706657 98.89502 12.27201 -9.709021 98.90605 12.35 -9.816774 98.69847 12.34188 -9.818538 98.70127 12.25649 -9.821117 98.72244 11.95848 -9.796837 98.4354 12.00768 -9.873312 98.43048 12.07426 -9.92711 98.41078 12.2516 -9.941665 98.3689 11.85421 -9.927609 98.16937 11.92346 -9.985174 98.11013 12.08684 -9.993285 98.15214 10.75154 -9.75 97.87982 10.52001 -9.75 97.96614 10.29547 -9.75 98.12145 11.71908 -9.75 98.13488 11.47999 -9.75 97.96614 11.26765 -9.75 97.88468 11 -9.75 97.85 12.93365 -6.690876 98.80213 12.78259 -6.955661 98.97019 12.88625 -6.869753 98.69171 12.78006 -7.317301 98.8118 12.88945 -7.138579 98.55567 12.8775 -6.983185 98.63063 12.62781 -7.257876 99.1011 12.63783 -7.469259 99.04783 12.64622 -7.053874 99.1969 12.93997 -9.34125 97.9 12.81097 -9.34125 98.59562 12.92656 -9.376144 97.9 12.59359 -9.707108 98.51212 12.70711 -9.707108 97.9 12.34125 -9.939973 97.9 12.86701 -9 98.61714 9.767628 -5.000012 97.99293 9.633977 -5.069402 97.9 12.23238 -5.000014 97.99292 12.36602 -5.0694 97.9 13.00038 -6 97.89997 9.228517 -7.018667 98.93914 9.221294 -7.321883 98.81444 9.35187 -7.459646 99.03299 9.208996 -6.917225 98.99238 9.353387 -7.052024 99.19787 9.106183 -6.825238 98.71823 9.121994 -6.964532 98.63985 9.111351 -7.128067 98.55799 9.14119 -9.132231 98.61399 9.633719 -9.886041 98.42481 9.299098 -9.569395 98.55334 9.5 -9.866025 97.9 9 -9 97.9 9.008782 -9.132231 97.9 9.132994 -9 98.61714 9.133975 -9.5 97.9 9.177936 -9.569395 97.9 8.985044 -6 98.03699 8.999618 -6 97.89998 9.019205 -6.76355 98.17649 9.034343 -6.869681 98.26905 9.049763 -6.947753 98.34337 9.054231 -6.962121 98.36258 9 -6.227223 97.90001 9.000246 -6.330717 97.93131 9.000257 -6.319462 97.95272 9.003962 -6.538232 98.02583 9.004267 -6.480894 98.08923 9.020076 -6.627499 98.28667 11.5555 -9.985174 97.81922 11 -9.985174 97.68482 10.4445 -9.985174 97.81922 10.51286 -9.837027 97.95223 11 -9.837027 97.83436 11.48713 -9.837027 97.95223 11.51384 -9.927609 97.90026 11 -9.927609 97.77594 10.48616 -9.927609 97.90026 12.97082 -6.67067 98.3531 12.95847 -6.906963 98.30543 12.97167 -6.831212 98.23543 12.96985 -6.813028 98.2475 12.97975 -6.770859 98.18389 12.99765 -6.434971 98.03704 12.99816 -6.47411 97.98577 9.381387 -5.218513 98.03119 9.098912 -5.566365 97.9 9.179525 -5.436984 98.04756 9.296263 -5.28954 97.9 9.402709 -5.197976 97.9 9.999992 -5 97.16774 9.864711 -5 97.56899 11 -4.999992 96.9 10.21154 -4.999992 97.06198 11.78846 -4.999992 97.06198 11.99984 -5 97.16768 12.13533 -5 97.56896 12.33501 -5.057784 97.79937 12.82048 -5.436984 98.04756 12.96499 -5.737719 97.89999 12.61861 -5.218513 98.0312 12.73336 -5.320165 97.9 12.82645 -5.436984 97.9 9 -6 97.86019 9.56411 -5.1 97.50781 9.56411 -5.1 90.83775 9.27874 -5.307336 90.83775 9.062212 -5.652791 90.83775 10.21154 -5.1 97.06198 11 -5.1 96.9 11.78846 -5.1 97.06198 12.43589 -5.1 97.50781 12.93779 -5.652791 90.83775 12.72126 -5.307336 90.83775 12.43589 -5.1 90.83775 13.25333 -7.827156 89.86351 13.50649 -7.431004 89.50754 13.25538 -6 89.85984 13.56013 -7.370632 89.44966 13.60226 -6 89.40725 13.91347 -7.10175 89.15863 13.95629 -6 89.13169 13.96242 -7.078943 89.12793 14.36283 -6 88.94195 14.33333 -7 88.95212 14.92373 -6 88.83921 14.92373 -7 88.83921 15.25003 -6 88.85343 13.00001 -8.994227 90.83115 13.01023 -8.752775 90.63575 13.14795 -8.084345 90.08283 13.21465 -7.911786 89.93635 13.11948 -6 90.15683 15.2578 -5.652791 88.79171 13.55878 -5.652791 89.36275 14.34301 -5.652791 88.88299 13.06098 -5.652791 90.13565 12.58907 -5.1 89.96478 14.27402 -5.307336 88.67774 12.85739 -5.307336 90.06193 13.40746 -5.307336 89.20788 13.20802 -5.1 89.00377 14.18311 -5.1 88.40724 7.816891 -5.1 88.40724 8.79198 -5.1 89.00377 9.410932 -5.1 89.96478 7.725975 -5.307336 88.67774 8.592543 -5.307336 89.20788 7.656993 -5.652791 88.88299 8.939017 -5.652791 90.13565 8.441219 -5.652791 89.36275 6.742197 -5.652791 88.79171 9.142609 -5.307336 90.06193 7.913778 -1.054999 88.13361 7.926749 -1.069616 88.17886 8.193234 -1.021616 88.0765 9.026883 -0.4741105 88.06306 9.083895 -0.04999995 88.04425 8.804026 -0.8457012 88.10768 8.658584 -0.9857968 88.13969 8.281131 -1.193545 88.23319 7.964939 -1.216566 88.31209 8.522912 -0.85109 87.98071 8.521834 -0.8505192 87.97761 8.461206 -0.8932336 87.99154 8.690512 -0.7554785 88.02449 8.651172 -0.7327879 87.94907 8.630571 -0.7544527 87.95351 8.560203 -0.8789338 88.05693 8.976194 -0.04999995 87.98286 8.95933 -0.04999995 87.96485 8.890306 -0.426408 87.97927 8.917546 -0.04999959 87.8953 8.862497 -0.379056 87.90586 8.849254 -0.4151946 87.90845 8.703981 -0.670724 87.93787 7.950116 -1.12847 88.26038 8.222942 -1.05971 88.15162 8.365487 -0.951784 88.02449 8.399433 -0.9848648 88.10018 7.95914 -1.171793 88.29186 8.25188 -1.116484 88.20301 8.604945 -0.9234341 88.10907 9.021751 -0.04999995 88.01776 8.949712 -0.4460386 88.03206 8.741082 -0.7928433 88.07691 8.158233 -1.025037 88.06652 8.917598 0 87.8953 8.976194 0 87.98286 9.083895 0 88.04425 12.91476 0 88.04462 12.91476 -0.04999995 88.04462 12.9298 -0.04999995 88.04008 13.02334 0 87.9833 13.02334 -0.04999995 87.9833 13.0824 0 87.8953 13.06387 -0.04999995 87.93261 13.08245 -0.04999977 87.8953 12.92496 -0.4932844 88.06729 13.30768 -1.025144 88.14341 14.03506 -1.216566 88.31209 13.72794 -1.161043 88.22412 13.08887 -0.1634691 87.89652 13.13224 -0.4203064 87.94712 13.615 -0.9660341 88.06811 13.61963 -0.940514 88.01067 13.45648 -0.8623629 88.02471 13.34928 -0.7332874 87.94916 13.32988 -0.7433295 87.99264 13.25546 -0.6151112 87.92945 13.15091 -0.4156274 87.90847 14.08622 -1.054972 88.13361 13.81063 -1.016727 88.0584 14.07325 -1.069616 88.17886 13.78887 -1.038839 88.11973 14.06432 -1.086148 88.21002 14.04988 -1.12847 88.26038 13.75989 -1.086825 88.1807 13.41544 -0.8990758 88.08657 13.36107 -0.9583711 88.13063 13.2219 -0.8242291 88.09911 13.00483 -0.4628769 88.05435 13.2846 -0.7740201 88.05483 13.08045 -0.4363043 88.00975 16.01933 -1.163197 89.06616 16.03178 -1.128471 89.04177 16.09378 -1.054174 88.9203 16.10679 -1.050571 88.89481 15.73745 -1.055051 88.75128 16.07033 -1.069616 88.96624 16.05227 -1.090751 89.00163 16.0027 -1.254509 89.09873 16.00732 -1.216566 89.08969 16.00879 -1.207976 89.08683 2.852027 -1.090845 91.4877 2.838203 -1.057169 91.4802 2.717831 -1.040775 91.55757 2.161168 -0.7204724 91.31249 2.10529 -0.7423923 91.29227 2.13662 -0.8135201 91.3868 2.025554 -0.9660782 91.31183 2.075659 -1.017191 91.41849 2.026763 -0.9276655 91.30904 2.224552 -1.093937 91.57132 2.230462 -1.096047 91.57517 2.23721 -1.083187 91.57891 2.271391 -0.7091577 91.32292 2.304567 -0.7694419 91.38236 2.349922 -0.7237922 91.30943 2.36656 -0.8128817 91.40848 2.693729 -0.9787024 91.50414 2.631582 -0.9490539 91.48503 2.59327 -0.9673613 91.54013 2.515808 -0.9229715 91.50121 2.492644 -0.9414625 91.54298 2.426128 -0.8780741 91.47243 2.406373 -0.9008815 91.51531 2.34232 -0.8459314 91.4628 2.745924 -0.9506376 91.41223 2.793693 -0.9902547 91.44977 2.806188 -1.005101 91.4589 2.677625 -1.176285 91.62142 2.860819 -1.120725 91.49118 2.730319 -1.124545 91.59114 2.574748 -1.107466 91.64112 2.539999 -1.163745 91.65243 2.447909 -1.150172 91.65132 2.418756 -1.068112 91.63593 2.38778 -1.138796 91.64128 2.321962 -1.123616 91.62126 2.287435 -1.006661 91.58473 2.31398 -1.121546 91.61814 2.138797 -1.056906 91.49977 2.131491 -0.9911025 91.48374 2.068207 -0.8661974 91.35578 2.028463 -0.8070735 91.23262 2.001072 -0.9075111 91.18676 2.094578 -0.7483041 91.28681 2.059003 -0.7736669 91.26343 2.192434 -0.9248337 91.50144 2.587811 -1.026518 91.60144 2.457706 -0.9937679 91.60063 2.347676 -0.942568 91.56118 2.267574 -0.8739933 91.4931 2.220856 -0.7799501 91.39541 2.216527 -0.7101369 91.32202 19.15294 -1.077446 91.48519 19.1965 -1.144767 91.54843 19.26688 -1.144155 91.59368 19.70623 -0.7113268 91.32093 19.65009 -0.7238042 91.30941 19.62881 -0.8208937 91.41684 19.84102 -0.7210968 91.31191 19.76372 -0.7087639 91.32328 19.75858 -0.7784787 91.39725 19.87901 -0.8272652 91.38572 19.88137 -0.7358992 91.29826 19.82053 -0.7969099 91.39763 19.9561 -0.7882291 91.24999 19.93758 -0.770759 91.2661 19.92753 -0.8669204 91.36216 19.90542 -0.7483089 91.28681 19.68826 -1.115435 91.60134 19.64957 -1.125812 91.61701 19.67507 -1.118973 91.60668 19.79394 -1.087089 91.5585 19.8407 -1.067137 91.52 19.82089 -1.033609 91.53378 19.89082 -1.040176 91.4659 19.89852 -1.035329 91.456 19.8239 -0.9360741 91.49765 19.78082 -0.9809741 91.54408 19.86293 -1.056047 91.49797 19.4348 -1.166705 91.64976 19.3449 -1.1383 91.62658 19.34869 -1.174527 91.63059 19.33987 -1.175127 91.6277 19.14217 -1.176678 91.50325 19.76866 -1.093869 91.56875 19.76171 -1.078126 91.57921 19.6614 -1.05703 91.6178 19.58773 -1.086584 91.64007 19.60663 -1.137332 91.63442 19.50874 -1.109761 91.64963 19.57057 -1.147002 91.64904 19.46495 -1.163131 91.6528 19.98071 -0.9564232 91.29158 19.96166 -0.9113526 91.32994 19.97969 -0.8196772 91.22098 19.96849 -0.8029307 91.23643 19.93701 -0.9747087 91.39406 19.85816 -0.8828273 91.44258 19.77149 -0.8944233 91.49845 19.68342 -0.9710536 91.57553 19.72581 -1.021948 91.5853 19.9491 -0.9957025 91.37384 19.55973 -1.028537 91.62195 19.41542 -1.064446 91.62406 19.42642 -1.126974 91.6453 19.71593 -0.8638052 91.48609 19.6218 -0.8314024 91.42771 19.63922 -0.9303699 91.5517 19.54453 -0.8965955 91.48725 19.53234 -0.9800114 91.58919 19.49174 -0.920289 91.50044 19.40832 -1.011003 91.5884 19.38921 -0.9461196 91.49167 19.28529 -1.024252 91.54575 19.27823 -0.9527381 91.43393 19.27239 -1.079749 91.57626 19.18169 -1.021989 91.46739 19.25408 -0.9506341 91.41223 19.19381 -1.005102 91.45891 2.20232 -0.1053122 91.01065 2.273365 -0.1050692 91.01414 2.305844 -0.04999995 91.00697 2.378635 -0.4205834 91.06372 2.383644 -0.3264159 91.02165 2.333301 -0.2616652 91.02729 2.385962 -0.2684018 91.00227 2.389499 -0.1079662 90.9728 2.325122 -0.4101784 91.08544 2.311123 -0.570613 91.18806 2.016726 -0.04999995 90.8532 2.121132 -0.4206516 91.06359 2.189758 -0.4083731 91.08921 2.175744 -0.572845 91.18511 2.004154 -0.4936304 90.91131 2.030253 -0.1141268 90.88474 2.072717 -0.1101409 90.94167 2.083869 -0.04999995 90.95011 2.132325 -0.1070464 90.98587 2.187958 -0.04999995 91.00547 2.269133 -0.2581462 91.04036 2.26053 -0.4052832 91.09565 2.245981 -0.5660703 91.19409 2.063881 -0.4411011 91.02093 2.024408 -0.466675 90.96756 2.140495 -7.889184 91.50154 2.092683 -7.923341 91.44403 2.024547 -7.969582 91.30877 2.340899 -7.721494 91.62805 2.18981 -7.851704 91.54618 2.545746 -7.503365 91.65194 2.643575 -7.378187 91.63298 2.867133 -7.005202 91.49346 2.754488 -7.213155 91.58443 19.2508 -7.221737 91.58751 19.13287 -7.005202 91.49346 19.6591 -7.721494 91.62805 19.35643 -7.378187 91.63298 19.45425 -7.503365 91.65194 19.86109 -7.890347 91.4999 19.81019 -7.851704 91.54618 19.97546 -7.969582 91.30877 19.90732 -7.923341 91.44403 19.97561 -0.4667882 90.96759 19.86767 -0.1071043 90.98588 19.81327 -0.04999995 91.00515 19.79767 -0.1053687 91.01067 19.91761 -0.04999995 90.94879 19.99586 -0.4937537 90.91133 19.98423 -0.04999995 90.85068 19.96974 -0.1141927 90.88474 19.87888 -0.420747 91.06363 19.93614 -0.4412043 91.02095 19.92728 -0.1102021 90.94168 19.69469 -0.04999995 91.0071 19.72662 -0.1051263 91.01416 19.61049 -0.1080283 90.9728 19.66669 -0.2617524 91.02731 19.61403 -0.2684867 91.00229 19.62041 -0.4048455 91.05573 19.67487 -0.4102752 91.08548 19.73086 -0.2582363 91.04039 19.75401 -0.5660954 91.19412 19.82425 -0.5728724 91.18514 19.68886 -0.5706378 91.18807 19.73947 -0.4053757 91.0957 19.81025 -0.4084649 91.08926 19.69469 0.04999995 91.0071 19.98423 0.04999995 90.85068 19.91761 0.04999995 90.94879 19.86735 0.04999995 90.98404 19.81327 0.04999995 91.00515 2.016726 0.05000001 90.8532 2.305844 0.05000001 91.00697 2.273736 0.05000001 91.01216 2.187958 0.05000001 91.00547 2.132676 0.05000001 90.98406 2.083869 0.05000001 90.95011 12.87272 -9.525001 88.9 12.525 -9.872725 88.9 12.72175 -9.721752 88.9 9.072315 -9.41355 88.9 9.278249 -9.721752 88.9 9.586451 -9.927686 88.9 13.16098 -8.455893 89.48565 13.11096 -8.542173 89.70538 13.00001 -8.996537 90.82926 13.00767 -8.876387 90.53476 13.42009 -8.185317 88.75563 13.37987 -8.215502 88.84244 13.72182 -8.039472 88.27304 13.6851 -8.050876 88.31906 8.579906 -8.185317 88.75563 8.314901 -8.050876 88.31906 8.278182 -8.039472 88.27304 8.620131 -8.215502 88.84244 8.839016 -8.455893 89.48565 8.999995 -8.996537 90.82926 8.992331 -8.876387 90.53476 8.889041 -8.542173 89.70538 13.56773 -7.745383 89.34075 13.52361 -8.018767 89.10897 13.57379 -7.988337 89.03895 13.01135 -8.835378 90.56856 13.16136 -8.400229 89.83827 13.23201 -8.293065 89.64829 13.0122 -8.794136 90.60225 13.17386 -8.245539 89.96581 13.25025 -8.108119 89.80148 13.91234 -7.868884 88.6684 13.87479 -7.875457 88.70216 13.62279 -7.703214 89.28186 13.95675 -7.53484 89.00346 13.99894 -7.523157 88.97611 14.16667 -7.866025 88.48072 14.18722 -7.827358 88.53887 14.28868 -7.5 88.82582 14.29455 -7.468149 88.84243 15.94059 -7.468149 88.9419 14.9193 -7.468149 88.72293 7.70545 -7.468149 88.84243 7.711325 -7.5 88.82582 8.001062 -7.523157 88.97611 7.812776 -7.827358 88.53887 7.833333 -7.866025 88.48072 8.087663 -7.868884 88.6684 8.987799 -8.794136 90.60225 8.826141 -8.245539 89.96581 8.749749 -8.108119 89.80148 8.432268 -7.745383 89.34075 8.988652 -8.835378 90.56856 8.838638 -8.400229 89.83827 8.767989 -8.293065 89.64829 8.476394 -8.018767 89.10897 8.426215 -7.988337 89.03895 8.125206 -7.875457 88.70216 8.377206 -7.703214 89.28186 8.043251 -7.53484 89.00346 19.91963 8.689736 96.38453 19.77164 9.148051 80 18.14805 10.77164 80 19.27273 9.958243 97.71873 19.12132 10.12132 80 19.61923 9.462752 96.96124 19.80458 9.065065 96.61929 17 11 80 17 11 91.15404 17.47922 10.96148 93.04126 17.94216 10.84822 94.94868 18.8 10.4 98.9 18.04157 10.81338 95.37368 17.96154 10.84173 95.03101 19.27273 9.971097 97.83267 19.80907 9.285041 97.90611 19.92409 9.004234 98.20426 19.92475 9.001721 98.20187 19.93818 8.947532 98.15267 19.97141 8.778544 98.02308 19.99896 8.487301 97.86834 19.27273 9.947851 100.1658 19.68796 9.55513 99.13549 19.75155 9.4507 98.86997 19.84479 9.248688 98.48961 19.93563 8.250217 98.03442 19.98016 8.32453 97.95166 19.91739 8.267148 98.07478 19.81724 8.220183 98.17555 19.76805 8.180013 98.19653 19.69466 8.18889 98.2427 19.69671 8.16507 98.23104 19.97949 8.355715 97.96926 19.91607 8.295081 98.09049 19.81539 8.245558 98.18949 19.69246 8.212679 98.25522 19.76884 1.108734 91.66001 19.86481 1.077025 91.57472 19.86395 2.346608 91.87863 19.9762 4.233979 92.59642 19.68056 6.581723 95.78952 19.58541 7.043313 97.16944 19.46189 6.552531 95.80332 19.44746 7.038862 97.17054 19.25067 6.611432 95.77548 19.34266 7.060859 97.16515 19.26789 7.09171 97.15756 19.86395 6.693301 95.7368 19.7881 7.124944 97.14938 19.68075 7.069033 97.16312 19.99958 7.50224 97.05672 19.93998 7.291264 97.10853 19.9762 6.86546 95.65544 19.86415 7.18912 97.13362 19.80574 7.137607 97.14627 19.9762 5.756629 93.94793 19.9762 2.406965 91.69804 19.9516 1.027787 91.4391 19.95608 1.02401 91.42881 19.97641 1.003122 91.37234 19.99854 0.958072 91.25204 19.92539 1.046477 91.49033 19.4622 1.161122 91.74623 19.54686 1.150737 91.74377 19.68056 2.30749 91.99568 19.6815 1.128814 91.70797 19.70871 1.1232 91.69542 19.46189 2.297255 92.0263 19.25067 2.317905 91.96452 19.32057 1.174489 91.71611 19.13042 1.806905 91.71451 19.13044 1.184357 91.58605 19.13035 7.195083 97.13219 19.13045 6.647323 95.62755 19.13044 5.787574 94.274 19.86395 4.127807 92.75448 19.68056 4.058996 92.85693 19.46189 4.040993 92.88374 19.25067 4.077318 92.82965 19.13043 3.309217 92.27088 19.86395 5.612276 94.07211 19.68056 5.518718 94.15259 19.46189 5.494241 94.17365 19.25067 5.543629 94.13117 19.13043 4.657988 93.13813 19.69104 0.1338604 91.01071 19.74144 0.7499325 91.37073 19.72193 0.6062481 91.22402 19.81088 0.6100675 91.21945 19.63798 0.6221893 91.20484 19.6184 0.3685107 91.03882 19.66505 0.7612884 91.36135 19.65578 0.7640079 91.3591 19.8947 0.6347926 91.1898 19.89266 0.7842686 91.34236 19.78199 0.7514027 91.36952 19.98484 0.8763912 91.26624 19.97187 0.8536854 91.28501 19.95729 0.6758547 91.14051 19.94081 0.8179988 91.31449 19.91023 0.7945907 91.33383 19.61083 0.1375815 90.97563 19.78004 0.133305 91.0159 19.86803 0.1362346 90.98825 19.93817 0.1421158 90.93276 19.98516 0.1505244 90.85343 19.87262 0.2965917 91.01881 19.78521 0.2878236 91.04712 19.69611 0.2888016 91.04389 19.9975 0.915212 91.23416 19.98976 0.5176127 90.95185 19.94754 0.4793457 91.02481 19.8808 0.4515573 91.0778 19.79458 0.4362587 91.10697 19.70542 0.4362582 91.10697 2.87868 10.12132 80 3.960494 10.81415 95.36478 3.85195 10.77164 80 4.031146 10.83925 95.06217 4.038734 10.84183 95.02986 4.119446 10.86786 94.68843 5 11 91.15404 5 11 80 2.727273 9.958243 97.71873 3.200001 10.4 98.9 3.597251 10.65185 96.98032 2.466682 9.606954 97.1261 2.133587 8.885254 96.49893 2.228361 9.148051 80 9 6 89.9 7.422643 6 90.4028 6.917739 6 90.63349 9.5 6 89.8033 17.91192 10.85833 94.98857 16.88666 11.27843 95.82453 17.7762 11.05001 97.90985 17.79358 11.04076 97.92588 16.72955 11.14794 94.014 16.03461 11.37363 94.49263 16.05132 11.10042 92.37878 15.11851 11.4 93.58303 19.7883 9.363243 98.90268 19.36837 9.815316 100.2444 19.63781 9.567469 99.59197 19.40996 9.589716 100.3221 19.65697 9.430231 99.6367 19.38941 9.468083 100.344 19.63318 9.28393 99.67203 19.34472 9.358374 100.3516 19.56675 9.148318 99.69239 19.18794 9.175562 100.3261 19.46911 9.04036 99.6961 19.5902 8.825829 99.03335 19.61403 8.843555 99.03191 19.71422 8.948119 99.01672 19.7826 9.081138 98.98759 19.80743 9.226062 98.9476 19.38592 8.739488 99.02572 19.24636 8.929163 99.6658 19.02682 9.095395 100.2721 17.84815 11.05001 98.89146 4.153476 11.05001 98.75046 4.223803 11.05001 97.90984 3.958033 10.42331 102.1811 4.24737 10.97421 100.623 2.727273 9.947851 100.1658 17.75263 10.97421 100.623 18.04197 10.42331 102.1811 2.727273 9.971098 97.83267 4.446931 11.05001 100.8886 5.39123 11.05001 102.8292 5.921521 10.76396 104.1294 6.892584 11.05001 104.3796 7.979533 10.85909 105.3774 8.801883 11.05001 105.3858 9.964168 10.85909 105.9716 10.9295 11.05001 105.7478 12.03583 10.85909 105.9716 13.06411 11.05001 105.4297 14.02047 10.85909 105.3774 14.99372 11.05001 104.463 16.07848 10.76396 104.1294 16.52668 11.05001 102.9439 17.51074 11.05001 101.0231 19.65434 8.780303 98.84611 19.78126 8.61693 98.484 19.83365 8.491841 98.31934 19.90814 8.563808 98.25151 19.45553 8.681855 98.85077 19.52537 8.606416 98.6859 19.71906 8.712232 98.66299 19.9282 8.989221 98.21267 19.88761 9.115652 98.45644 19.88987 9.009678 98.52043 19.97534 8.732233 98.07418 19.95739 8.646467 98.1673 19.64835 8.395926 98.39484 19.61365 8.472312 98.48031 19.59217 8.51077 98.53101 19.80645 8.97072 98.79188 19.74139 8.865866 98.82538 19.80146 8.798075 98.62876 19.86072 8.9003 98.57989 19.7749 0.9937691 91.61257 19.85011 0.8957426 91.49278 19.91596 0.9553516 91.47009 19.76857 0.8555395 91.49336 19.83121 1.065692 91.60491 19.17235 1.066357 91.56508 19.18411 1.048577 91.55713 19.28337 1.05721 91.64077 19.65617 0.7668761 91.36288 19.68712 0.8397367 91.47401 19.6358 0.9069462 91.55621 19.63755 0.8573679 91.47795 19.57653 0.917934 91.54986 19.22597 1.003452 91.52639 19.26355 0.9790189 91.4966 19.31222 1.001041 91.58361 19.37561 0.9783393 91.569 19.39148 0.9948791 91.61524 19.48923 0.9564898 91.58248 19.48648 0.9771258 91.62329 19.56714 0.9492103 91.60295 19.13614 1.155007 91.58499 19.54364 1.100602 91.73067 19.39118 1.127835 91.72637 19.26512 1.137104 91.68011 19.67065 1.057567 91.6899 19.38761 1.04948 91.68048 19.51309 1.026922 91.68707 19.61814 0.9913363 91.65655 19.70527 0.9381936 91.59441 18.59713 0.9190438 90.84957 18.46773 0.7110046 90.40734 18.59731 0.3692809 90.25859 17.34357 0.3692809 88.94979 17.18939 0.7110046 89.07286 17.23204 0.9803331 89.71993 16.94389 0.949814 89.26881 17.94671 0.920407 90.28142 2.023801 5.756629 93.94793 2.749337 6.611435 95.77548 2.869559 6.341961 95.06915 2.869551 7.017164 96.52194 2.023801 6.865461 95.65543 2.136056 6.6933 95.7368 2.064243 7.283825 97.11036 2.13586 7.189112 97.13362 2.31944 6.581721 95.78952 2.319296 7.069025 97.16313 2.23183 7.111984 97.15257 2.869647 7.195086 97.13219 2.855265 7.180184 97.13585 2.732112 7.091717 97.15756 2.665061 7.063425 97.16452 2.538113 6.552531 95.80332 2.460063 7.037733 97.17082 2.377343 7.051028 97.16754 2.749337 2.317903 91.96451 2.869581 2.728104 92.01133 2.869574 4.146322 92.75963 2.869566 1.184357 91.58604 2.839852 1.183693 91.61634 2.653506 1.172383 91.72505 2.538113 2.297252 92.0263 2.31944 2.307486 91.99568 2.430889 1.147643 91.74064 2.537746 1.161122 91.74623 2.044634 1.024869 91.43051 2.070086 1.043685 91.48239 2.023801 2.406962 91.69804 2.13509 1.076982 91.5746 2.136056 2.346604 91.87863 2.236083 1.110035 91.66335 2.320415 1.129189 91.70879 2.023801 4.233977 92.59642 2.136056 5.612274 94.07211 2.31944 5.518716 94.15259 2.538113 5.49424 94.17365 2.749337 5.543631 94.13116 2.86956 6.229709 94.88919 2.136056 4.127804 92.75448 2.31944 4.058992 92.85693 2.538113 4.040991 92.88374 2.749337 4.077318 92.82965 2.869566 5.369221 93.79437 2.305342 8.188876 98.24269 2.182766 8.220167 98.17555 2.303291 8.16504 98.23103 2.211904 8.185323 98.18421 2.012098 8.304291 97.90953 2.019843 8.324509 97.95165 2.113832 8.22151 98.10066 2.082612 8.26713 98.07477 2.020513 8.355715 97.96926 2.184616 8.245559 98.18949 2.126818 8.27026 98.14011 2.083931 8.295081 98.09049 2.307542 8.212679 98.25522 2.171387 9.288738 98.55007 2.243365 9.441286 98.84654 2.190932 9.285041 97.90611 2.624676 9.87877 99.97737 2.248456 9.450699 98.86996 2.001044 8.487422 97.8684 2.017031 8.696295 97.97143 2.061975 8.9482 98.15325 2.074261 8.997894 98.19824 2.303088 0.6415332 91.24919 2.358513 0.6543256 91.23503 2.344217 0.764006 91.3591 2.317197 0.5092888 91.14342 2.379533 0.4059969 91.05633 2.328244 0.3627617 91.06333 2.335212 0.2092344 91.01422 2.049422 0.7053512 91.17869 2.102122 0.6702207 91.21752 2.116595 0.7795366 91.34626 2.059185 0.817999 91.31448 2.040443 0.8374139 91.29844 2.015519 0.7473144 91.1323 2.030372 0.8504354 91.28767 2.015166 0.8763864 91.26623 2.167883 0.6470296 91.24315 2.237722 0.6379178 91.25321 2.153253 0.7648242 91.35842 2.230093 0.7504258 91.37032 2.263781 0.358168 91.0746 2.271138 0.2064711 91.02802 2.192893 0.3605412 91.06883 2.123876 0.3709756 91.04335 2.065999 0.3886229 91.00023 2.02576 0.4108422 90.94593 2.004711 0.4343597 90.88842 2.252254 0.504335 91.15117 8.662785 7.944444 91.65961 9.20522 6.622629 90.30236 10.99993 6.861519 90.30236 6.527851 7.645157 92.37686 15.12326 7.944507 92.50598 15.472 7.645246 92.37686 16.31687 7.944535 93.45801 18.63331 7.794329 97.49246 18.50052 7.944618 97.62526 18.30657 7.183207 94.89805 18.0957 7.944598 96.15512 17.35101 7.944567 94.71091 17.31602 6.209383 92.37686 18.72028 4.341181 92.37686 18.0021 1.106109 90.48887 17.14398 1.192677 89.88995 17.86035 1.120409 90.38994 17.65226 1.681632 90.30236 17.97378 1.108967 90.4691 16.98082 3.363069 90.30236 16.63954 1.243563 89.53789 15.89296 4.810346 90.30236 12.79465 6.622664 90.30236 14.46441 5.922695 90.30236 4.683856 6.209258 92.37686 5.236474 1.231642 89.61212 4.347706 1.681499 90.30236 5.019112 3.362949 90.30236 4.023871 1.107235 90.46747 4.132921 1.113291 90.37921 4.892246 1.192329 89.82952 3.99065 1.105806 90.49487 3.279635 4.341027 92.37686 3.693289 7.183063 94.89805 4.703597 7.944498 94.62914 3.940332 7.944567 96.06365 3.430627 7.86729 97.55454 3.499486 7.944628 97.62528 5.5 7.944444 93.64302 6.551599 7.944444 92.72769 13.67145 7.944476 91.77619 12.1 7.944444 91.37167 10.99999 7.944444 91.29174 5.123087 11.28008 95.80598 5.235127 11.14213 94.04239 5.948684 11.10042 92.37878 6.881489 11.4 93.58303 6.106579 11.38174 94.32252 5.923489 11.37086 94.54552 13.86586 11.4 92.81567 14.1775 11.10042 91.2878 11.98331 11.4 92.24678 12.08414 11.10042 90.72279 10.01668 11.4 92.24678 9.915863 11.10042 90.72279 8.134138 11.4 92.81567 7.822498 11.10042 91.2878 14.77427 11 89.85816 12.28775 11 89.18703 9.712252 11 89.18703 7.225733 11 89.85816 15.96502 11.38531 94.45552 16.67042 11.38531 96.20222 17.02541 11.38531 98.01955 14.64814 11.5 94.19028 15.26159 11.5 94.88072 15.74859 11.5 95.97338 16.17315 11.5 97.87876 16.21247 11.5 98.13834 7.347674 11.38531 103.7725 8.491992 11.49455 103.7371 8.39558 11.49981 103.5177 8.677126 11.4955 103.8854 9.045428 11.38531 104.6672 9.234614 11.491 104.109 10.93731 11.38531 104.9891 10.94338 11.491 104.3997 12.83541 11.38531 104.7062 12.65776 11.491 104.1442 13.60979 11.5 103.4759 13.53346 11.49571 103.7008 14.55123 11.38531 103.8467 13.35956 11.49112 103.8665 13.32287 11.4955 103.8854 14.0721 11.5 103.1793 15.91434 11.38531 102.4958 15.2513 11.5 102.0107 16.78936 11.38531 100.7879 16.00827 11.5 100.5332 17.0894 11.38531 98.89241 16.26782 11.5 98.89344 6.012665 11.38531 102.3939 5.172993 11.38531 100.6683 4.912051 11.38531 98.76702 5.733429 11.5 98.78497 5.787528 11.5 98.13834 4.974578 11.38531 98.01955 5.959164 11.5 100.4297 6.68555 11.5 101.9225 7.840441 11.5 103.1151 8.390213 11.5 103.4759 18.12817 10.29442 102.2752 18.16889 10.06916 102.3542 18.1163 9.832924 102.363 17.98274 9.641145 102.2995 16.06002 9.974726 104.2074 15.95542 9.880118 104.0832 17.84339 9.552564 102.2099 14.05338 10.0871 105.448 13.97657 9.97159 105.2833 16.15656 10.17293 104.3076 14.10349 10.27459 105.5555 14.11439 10.49493 105.5788 16.18895 10.41267 104.3188 14.11369 10.5086 105.5773 16.1496 10.63769 104.2384 14.08393 10.70473 105.5135 12.0576 10.70473 106.1202 12.04712 10.0871 106.0486 12.02078 9.97159 105.8688 9.952879 10.0871 106.0486 9.979223 9.97159 105.8688 11 9.97159 105.9432 12.06804 10.49493 106.1915 12.06431 10.27459 106.166 7.923932 10.73264 105.4967 9.942402 10.70473 106.1202 9.931957 10.49493 106.1915 9.935694 10.27459 106.166 8.023433 9.97159 105.2833 7.956994 10.06424 105.4258 7.946616 10.0871 105.448 7.898133 10.26409 105.552 7.886167 10.50603 105.5776 7.916066 10.70473 105.5135 5.85006 10.63677 104.239 5.811018 10.41011 104.3192 5.844563 10.16917 104.3066 5.942734 9.971138 104.2042 4.020989 9.637723 102.2974 4.156606 9.552564 102.2099 6.044575 9.880118 104.0832 2.973183 9.095395 100.2721 2.816394 9.172376 100.3249 3.885314 9.829247 102.3625 2.631195 9.814373 100.2449 3.871441 10.29349 102.2757 2.590173 9.587201 100.3226 3.831182 10.06661 102.3547 2.610592 9.468082 100.344 2.65721 9.354817 100.3516 17.8673 1.11187 90.3792 17.19015 1.032522 89.79237 17.17616 1.067247 89.81972 18.44385 1.108687 90.87754 18.46362 1.020549 90.86113 18.50327 0.9479164 90.82263 17.16646 1.106962 89.84155 17.1614 1.149847 89.85697 17.16098 1.193899 89.86564 17.88029 1.024054 90.35579 17.91233 0.9520404 90.30979 17.2075 1.004589 89.76123 2.433338 0.9239552 91.55622 2.36405 0.8599888 91.48121 3.42424 0.9180271 90.82995 3.5323 0.7110046 90.40731 4.053294 0.9204065 90.28141 2.523612 0.960171 91.58372 2.736445 0.9790191 91.4966 2.633693 0.97921 91.56549 5.05612 0.9498139 89.26879 4.810628 0.7110046 89.07284 4.656444 0.3692808 88.94977 3.402721 0.3692808 90.25856 4.726714 0.9761614 89.7507 2.178297 1.073574 91.61479 2.084523 0.9564331 91.47136 2.150312 0.896705 91.49392 2.231786 0.8563552 91.49434 2.313174 0.8404068 91.47484 2.233604 1.00075 91.62124 2.353441 1.067753 91.70124 2.489581 1.10832 91.73428 2.644532 1.131597 91.7176 2.786765 1.137413 91.64707 2.864635 1.158462 91.5852 2.862429 1.149476 91.58447 2.8278 1.066654 91.56517 2.721035 1.001254 91.56231 2.77424 1.00364 91.52654 2.301877 0.9440349 91.60152 2.369919 0.9116304 91.56174 2.401854 0.9997708 91.66532 2.448346 0.9558445 91.60913 2.514266 1.033304 91.68929 2.534295 0.982132 91.62424 2.641832 1.05261 91.67269 2.630821 0.9973615 91.6088 2.759877 1.057471 91.61317 2.81746 1.050826 91.5582 2.380538 8.460948 98.46638 2.190313 8.557074 98.39762 2.152578 8.443392 98.26985 2.330484 8.585347 98.5656 2.237175 8.649281 98.53798 2.588712 8.720318 98.9602 2.614076 8.739487 99.02572 2.51192 8.769891 99.03341 2.083847 9.033066 98.28696 2.139222 9.173767 98.61323 2.519594 8.657227 98.79122 2.336782 8.353923 98.35531 2.014853 8.667213 98.00733 2.03126 8.587402 98.10588 2.079153 8.510441 98.19607 2.157782 8.732919 98.49291 2.217401 9.081137 98.98759 2.174332 8.949305 98.71679 2.285778 8.948118 99.01672 2.237283 8.844974 98.75554 2.385967 8.843555 99.03191 2.322651 8.758917 98.78076 2.420113 8.69622 98.79204 2.077358 8.934225 98.36124 2.102304 8.830869 98.43227 2.211698 9.363241 98.90268 2.192804 9.247939 98.9409 2.192575 9.226061 98.9476 2.361044 9.566286 99.58785 2.341878 9.429047 99.63258 2.752593 8.928083 99.66204 2.52979 9.039229 99.69216 2.432128 9.147164 99.68836 2.36568 9.282758 99.66794 5.387992 8.357628 94.77312 4.391601 8.357628 96.69664 4.128383 8.355965 97.73209 4.957223 8.5 97.40512 4.863085 8.5 97.85691 6.927097 8.357628 93.24871 5.985034 8.5 95.21217 5.475 8.5 96.03219 9.9 8.5 92.77301 9.087733 8.5 92.97605 8.860074 8.357628 92.27079 9 8.5 93.00509 7.360399 8.5 93.84992 10.99999 8.5 92.67505 10.99999 8.357628 91.93395 12.1 8.5 92.77301 13.13991 8.357628 92.27079 13.5037 8.5 93.20056 15.07289 8.357628 93.2487 14.68429 8.5 93.88185 16.612 8.357628 94.77311 15.77236 8.5 94.90277 16.5578 8.5 96.0963 17.6084 8.357628 96.69662 17.04366 8.5 97.40804 17.87162 8.355962 97.73207 17.13692 8.5 97.85691 13.53855 11.5 93.51055 11.87101 11.5 93.00663 11.67428 11.5 92.9809 11.33811 11.49627 92.80241 10.12899 11.5 93.00663 10.32572 11.5 92.9809 10.80384 11.49468 92.76713 8.461444 11.5 93.51055 7.351858 11.5 94.19028 7.293538 11.5 94.23704 6.649846 11.5 95.02996 6.183833 11.5 96.19513 5.470488 11.38531 95.71788 13.56567 9.366894 103.6417 13.60979 9.318982 103.4759 15.38263 9.046358 101.8228 17.95937 8.560328 99.14781 17.96491 8.561372 99.14839 18.22884 8.739486 99.56527 18.207 8.675528 99.38146 13.46589 9.398838 103.7851 13.32287 9.409926 103.8854 16.15389 8.56032 99.9897 18.08798 8.592896 99.18658 18.15911 8.6262 99.25432 8.533811 9.532044 104.1888 11 9.409926 104.4 8.675601 9.409925 103.8847 3.771158 8.739486 99.56527 5.84611 8.560318 99.98969 6.617371 9.046358 101.8228 3.91637 8.591715 99.18481 4.040637 8.560323 99.1478 3.831266 8.632414 99.26885 3.792936 8.675964 99.38285 8.534851 9.39897 103.7859 8.435207 9.367385 103.6436 8.390213 9.318982 103.4759 18.41025 8.202855 98.27964 18.35398 8.170079 98.09488 18.40682 8.195223 98.25537 17.81277 8.388828 97.88395 17.76799 8.449958 98.38932 18.4172 8.038136 97.74221 18.22396 8.32901 98.43063 18.01884 8.42428 98.59688 17.44428 8.5 98.7231 17.59535 8.5 98.94012 18.49598 7.951324 97.64017 18.45001 8.026434 97.81234 18.41186 8.112875 98.02538 5.213439 1.090434 89.55004 4.08782 0.952255 90.30997 4.119805 1.024362 90.35592 5.233023 1.167804 89.59544 4.891637 1.153125 89.82086 5.179535 1.036128 89.48497 4.844858 1.009312 89.72321 4.876413 1.071063 89.78258 17.94949 8.554957 99.13571 17.80379 8.516889 99.04485 16.22379 8.5 99.57968 18.31309 8.42724 98.76656 18.35736 8.455332 98.87706 18.33361 8.431356 98.78234 18.40692 8.382739 98.71077 18.30608 8.530426 99.04908 18.25774 8.601222 99.21125 18.41707 8.367884 98.67675 18.41488 8.371092 98.6841 18.42776 8.352224 98.64088 18.22322 8.651783 99.32707 18.3264 8.50067 98.98092 18.33673 8.485536 98.94626 18.3553 8.458345 98.88397 3.613655 8.479188 98.90225 3.599746 8.44904 98.83966 3.640652 8.437804 98.80424 3.579904 8.388618 98.71583 3.568176 8.298502 98.52592 3.772883 8.327207 98.42807 3.56892 8.279341 98.48265 3.58976 8.202863 98.27964 3.589083 8.4202 98.78045 3.681859 8.428194 98.77038 3.981182 8.424287 98.5969 3.624379 8.498843 98.94373 3.61569 8.483117 98.91049 4.052092 8.554214 99.13407 3.739218 8.633299 99.25989 3.67662 8.570812 99.10353 4.091715 8.539834 99.1025 4.220495 8.513184 99.03282 4.404645 8.5 98.94012 5.776205 8.5 99.57968 3.588115 8.112804 98.02519 3.579397 8.088348 97.96298 3.633391 8.131237 97.98484 3.54829 8.023335 97.80503 4.19015 8.470419 98.65641 4.23205 8.433513 98.227 4.542073 8.5 98.74633 3.64585 8.224975 98.26665 3.595494 8.187191 98.23081 3.595619 8.144192 98.10848 18.56559 7.985476 97.94601 19.26996 7.355421 97.63544 19.28886 7.383107 97.67987 19.15888 7.48743 97.70639 19.46835 7.680656 97.99874 19.55637 7.850891 98.10895 19.42906 7.926337 98.17524 18.69913 8.203955 98.46259 18.5499 8.18525 98.36601 18.52102 8.541767 99.02569 18.34914 8.502466 98.94716 18.84835 8.247836 98.54031 18.67897 8.608129 99.08317 18.66307 8.61355 99.09888 18.93284 8.514904 98.84305 19.01321 8.324601 98.60499 19.16146 8.420734 98.64287 19.13696 8.090984 98.34494 19.4404 8.293511 98.41815 19.62367 7.992305 98.17529 19.40077 7.561666 97.89628 19.42113 7.596707 97.92909 19.13805 7.786908 98.03654 19.44848 7.644831 97.97045 19.22829 7.297145 97.52498 18.65063 7.783852 97.5231 18.94524 7.481684 97.42347 19.18464 7.242253 97.3833 18.86067 7.735708 97.80469 18.84181 7.987963 98.18479 19.3976 7.556281 97.89102 2.710845 7.383547 97.68055 3.090778 7.694948 97.78565 2.957907 7.711924 97.9102 3.301596 7.73442 97.5033 3.49982 8.122793 98.18967 3.016183 8.494707 98.79713 2.839626 8.421184 98.64377 2.894487 8.280365 98.53455 3.33545 8.344257 98.67936 3.606244 8.480696 98.90688 3.277916 8.593173 99.041 3.531033 8.675383 99.29757 3.057965 8.197619 98.47387 3.206445 8.147405 98.39861 3.355449 8.121463 98.30335 3.207281 7.703168 97.64695 2.729544 7.356136 97.63664 2.768136 7.301971 97.53526 2.785949 7.278398 97.48236 2.805068 7.254463 97.41997 2.363183 8.020673 98.18609 2.369181 8.00712 98.18095 2.371379 8.008738 98.18246 2.443359 7.850263 98.10852 2.523095 7.898868 98.15016 2.510999 7.719446 98.02717 2.666818 7.817526 98.09578 2.578711 7.596982 97.92934 2.81338 7.75396 98.0156 2.61817 7.529383 97.86386 2.647046 7.482301 97.81196 10.2625 8.4 97.62261 9.722613 8.4 98.1625 9.525001 8.4 98.9 10.37084 8.4 97.00154 11 8.4 97.42501 11.3764 8.4 96.93574 11.7375 8.4 97.62261 12.28641 8.4 97.36861 12.27739 8.4 98.1625 12.86983 8.4 98.19026 12.475 8.4 98.9 12.97855 8.4 99.1921 12.27739 8.4 99.6375 12.58498 8.4 100.1198 11.7375 8.4 100.1774 11.78901 8.4 100.7378 11 8.4 100.375 10.79274 8.4 100.8892 10.2625 8.4 100.1774 9.849091 8.4 100.5357 9.722613 8.4 99.6375 9.197621 8.4 99.76685 19.62266 7.560337 97.8883 19.7881 7.608641 97.82955 19.44746 7.552392 97.89796 19.9663 7.447067 97.32124 19.91238 7.360826 97.37625 19.7881 7.254662 97.44397 19.62266 7.19053 97.4849 19.44746 7.179982 97.49163 19.26789 7.225826 97.46238 19.9663 7.753557 97.65326 19.91238 7.688601 97.73227 2.732112 7.251549 97.50122 2.552537 7.522727 97.87319 2.0337 7.727891 97.63182 2.211904 7.580093 97.8057 2.377343 7.530829 97.86365 2.087621 7.661645 97.70975 2.552537 7.2068 97.53213 2.377343 7.217096 97.52502 2.211904 7.279697 97.48178 2.0337 7.467507 97.35208 2.087621 7.383326 97.41022 9.525001 6.5 98.9 9.722613 6.5 98.1625 10.2625 6.5 97.62261 11 6.5 97.42501 11.7375 6.5 97.62261 12.27739 6.5 98.1625 12.475 6.5 98.9 12.27739 6.5 99.6375 11.7375 6.5 100.1774 11 6.5 100.375 10.2625 6.5 100.1774 9.722613 6.5 99.6375 11 6.5 98.9 8.390213 8.5 103.4759 6.617371 8.5 101.8228 8.534851 8.5 103.7859 8.435207 8.5 103.6436 9.197621 8.5 99.76685 12.86983 8.5 98.19026 12.28641 8.5 97.36861 11.3764 8.5 96.93574 10.37084 8.5 97.00154 12.97855 8.5 99.1921 12.58498 8.5 100.1198 15.38263 8.5 101.8228 11.78901 8.5 100.7378 13.60979 8.5 103.4759 10.79274 8.5 100.8892 9.849091 8.5 100.5357 13.46589 8.5 103.7851 13.32287 8.5 103.8854 11 8.5 104.4 13.56567 8.5 103.6417 8.677126 8.5 103.8854 11 -8.5 97.4 -4.102882 10.86282 79.95001 -4.348168 10.92839 79.95001 -4.999813 11 79.95001 -2.430607 9.54862 79.95001 -2.389739 9.478695 79.95001 -2.442612 9.569198 79.95001 -2.87868 10.12132 79.95001 -2.822188 10.06328 79.95001 -2.828661 10.07056 79.95001 -2.473348 9.617416 79.95001 -2.122844 8.849693 79.95001 -2.104779 8.785937 79.95001 -2.130834 8.878211 79.95001 -2.214482 9.113952 79.95001 -2.240225 9.177592 79.95001 -2.245568 9.188741 79.95001 -2.265659 9.235475 79.95001 -2.313738 9.335664 79.95001 -2.32002 9.349293 79.95001 -2.379008 9.460533 79.95001 -2.785493 10.02434 79.95001 -2.767284 10.00374 79.95001 -2.743216 9.977116 79.95001 -2.000183 8.033134 79.95001 -2.000063 8.064223 79.95001 -2.000732 8.066263 79.95001 -2.002117 8.128211 79.95001 -2.002927 8.132493 79.95001 -2.010277 8.255493 79.95001 -2.872714 10.11577 79.95001 -2.917648 10.16 79.95001 -2.936717 10.17781 79.95001 -2.963461 10.20323 79.95001 -2.996259 10.23272 79.95001 -3.010151 10.24547 79.95001 -3.02658 10.25956 79.95001 -3.057716 10.28673 79.95001 -3.106158 10.32699 79.95001 -3.119678 10.3376 79.95001 -3.155479 10.36626 79.95001 -3.183467 10.38751 79.95001 -3.205681 10.40454 79.95001 -3.248579 10.43568 79.95001 -3.256768 10.44182 79.95001 -3.314968 10.48207 79.95001 -2.740439 9.973421 79.95001 -2.714007 9.94274 79.95001 -2.701837 9.928879 79.95001 -2.687991 9.911705 79.95001 -2.662396 9.880322 79.95001 -2.510843 9.675285 79.95001 -2.476147 9.622565 79.95001 -3.308746 10.47809 79.95001 -3.361621 10.51335 79.95001 -3.382585 10.52665 79.95001 -3.416839 10.54825 79.95001 -2.09609 8.755493 79.95001 -2.072894 8.657304 79.95001 -2.06669 8.631856 79.95001 -2.04672 8.527389 79.95001 -2.042593 8.50731 79.95001 -2.035792 8.46203 79.95001 -2.032527 8.444697 79.95001 -2.03087 8.429265 79.95001 -2.023784 8.381857 79.95001 -2.02631 8.396446 79.95001 -2.018279 8.330667 79.95001 -2.016366 8.318789 79.95001 -2.014809 8.297716 79.95001 -2.011703 8.264727 79.95001 -3.983283 10.82257 79.95001 -3.961649 10.81457 79.95001 -3.953696 10.81175 79.95001 -3.924235 10.80061 79.95001 -2.142314 8.913035 79.95001 -2.150233 8.939223 79.95001 -2.163178 8.975931 79.95001 -2.170997 9 79.95001 -2.185426 9.038352 79.95001 -2.192885 9.059861 79.95001 -2.215964 9.119055 79.95001 -3.894899 10.78917 79.95001 -3.886049 10.78552 79.95001 -3.865688 10.77742 79.95001 -3.848549 10.77023 79.95001 -3.836601 10.76537 79.95001 -3.829878 10.76239 79.95001 -3.807639 10.75301 79.95001 -3.81126 10.75443 79.95001 -3.750091 10.72737 79.95001 -3.737338 10.72134 79.95001 -3.693044 10.70051 79.95001 -3.664708 10.68662 79.95001 -3.646236 10.67719 79.95001 -3.636499 10.67241 79.95001 -3.628197 10.66799 79.95001 -3.592308 10.64923 79.95001 -3.580459 10.64308 79.95001 -3.556675 10.62998 79.95001 -3.552629 10.62795 79.95001 -3.538957 10.62018 79.95001 -3.524927 10.61251 79.95001 -3.521306 10.61026 79.95001 -3.469906 10.58068 79.95001 -3.451381 10.56939 79.95001 44.6102 9.478695 9.003568 44.62221 9.457291 9.003568 44.598 9.5 8.983983 44.62815 9.446552 9.003568 44.63404 9.435789 9.003568 44.63989 9.425002 9.003568 44.6457 9.414191 9.003568 44.69055 9.326867 9.003568 44.69596 9.315849 9.003568 44.70663 9.293748 9.003568 44.70132 9.30481 9.003568 44.75728 9.181977 9.003568 44.76209 9.170687 9.003568 44.76685 9.159379 9.003568 44.77157 9.148051 9.003568 44.71191 9.282666 9.003568 44.73253 9.238121 9.003568 44.73757 9.226934 9.003568 44.74256 9.215724 9.003568 44.75242 9.193245 9.003568 44.89771 8.776457 9.003568 44.90397 8.752724 9.003568 44.91003 8.728941 9.003568 44.92157 8.681229 9.003568 44.92704 8.657304 9.003568 44.93232 8.633336 9.003568 44.9374 8.609323 9.003568 44.94229 8.585272 9.003568 44.97427 8.391579 9.003568 44.97737 8.367233 9.003568 44.98028 8.342862 9.003568 44.98299 8.318468 9.003568 44.98549 8.294052 9.003568 44.99351 8.19621 9.003568 44.99502 8.171712 9.003568 44.99633 8.147204 9.003568 44.99833 8.098157 9.003568 44.99903 8.073624 9.003568 44.99953 8.049085 9.003568 44.99984 8.024544 9.003568 43.64619 10.50796 9.003568 43.65643 10.50121 9.003568 43.63591 10.51467 9.003568 43.5317 10.57947 9.003568 43.54224 10.57319 9.003568 43.49993 10.59808 8.985277 43.58414 10.54761 9.003568 43.59455 10.5411 9.003568 43.60493 10.53456 9.003568 43.62561 10.52134 9.003568 43.87451 10.34221 9.003568 43.88408 10.33452 9.003568 43.89361 10.3268 9.003568 43.90311 10.31903 9.003568 43.66664 10.49441 9.003568 43.82622 10.38006 9.003568 43.83594 10.37257 9.003568 43.84563 10.36504 9.003568 43.86492 10.34986 9.003568 44.10383 10.1386 9.003568 44.11256 10.12998 9.003568 44.12126 10.12132 9.003568 43.97797 10.25552 9.003568 43.98719 10.24741 9.003568 43.99636 10.23926 9.003568 44.0055 10.23108 9.003568 44.01461 10.22285 9.003568 44.05071 10.18959 9.003568 44.59801 9.5 9.003568 44.09506 10.14719 9.003568 44.08626 10.15574 9.003568 44.06856 10.17274 9.003568 44.05965 10.18118 9.003568 41.99997 11 9.003568 43.49993 10.59808 9.003568 43.52114 10.58572 9.003568 41.99993 11 8.987045 41.99997 11 9.221344 44.3975 9.5 6.112143 44.00985 9.5 3.611209 43.17281 9.5 -0.5407877 42.7065 10.12132 -0.4415511 43.3078 10.59808 6.247515 42.92915 10.59808 3.805759 42.09878 10.59808 -0.3122239 41.81924 11 6.432437 41.45288 11 4.07152 40.63164 11 0 42.41564 2.8 61.26302 42.48083 2.8 60.95261 42.48083 8 60.95261 44.58328 3.448722 52.79433 44.77061 3.770995 51.75038 44.54322 8 52.9901 44.82143 8 51.40904 45 3.669722 49 45 8 49 44.99303 3.615221 49.45573 44.86763 3.829289 51.0587 43.04892 2.8 58.66058 44.24975 8 54.27413 44.5432 3.385737 52.99066 43.02904 8 58.73381 42 8 64.95001 42.10369 8 63.19303 42.44761 8 61.10871 40.03318 3.939808 28.17742 40.72212 3.671412 28.97665 41.02895 3.675734 32.35592 41.29512 3.417842 35.74123 40.80213 3.466688 35.91257 37.6314 2.563193 39.08329 39.02676 3.183561 37.68794 42.16956 1.727367 43.13401 41.88554 2.306812 41.27316 41.34966 3.333343 36.39018 41.35535 3.324101 36.45606 41.69674 2.686151 39.81808 40.00536 3.951022 28.14552 38.49895 4.582697 29.65194 36.51378 4.862227 31.6371 36.42191 4.860747 31.72897 34.53137 4.546082 33.61951 33.5997 4.182533 34.55118 32.97329 3.853368 35.17759 -1.884672 8 79.33067 1.878716 8 79.31413 1.736203 8 79.00723 1.529575 8 78.71144 0.994921 8 78.26502 0.3395994 8 78.02904 0.02500194 8 78.00016 -0.3569101 8 78.03211 -1.010132 8 78.27384 -1.540842 8 78.72492 -1.710841 8 78.96414 36.77426 11 85.85816 39 11 87.15404 39 11 64.95001 26.375 11 11 -21.175 11 11 -17 11 50.38321 -2.525331 11 75.6846 18.17606 11 76.77859 19.5127 11 75.66257 4.696791 11 78.28531 -17 11 87.15404 -14.77427 11 85.85816 -12.28775 11 85.18704 -0.8922752 11 75.08026 0.8489986 11 75.07261 41.33725 11 53.55486 17.30321 11 78.28531 21.151 11 75.07261 22.89228 11 75.08026 24.52533 11 75.6846 -21.31233 11 11.5125 -21.6875 11 11.88768 -22.2 11 12.025 -29.8 11 12.025 -30.3125 11 11.88768 -30.68768 11 11.5125 -33.8 10.99997 14.35487 -33.89511 11.00003 16.01221 42 11 49 41.99993 11 9.520451 35.94697 11 11.39225 35.72478 11 11.72478 35.39225 11 11.94698 35 11 12.025 3.823937 11 76.77859 39.12274 11 62.85554 39.51165 11 60.49215 -4.71168 11 78.32666 -3.852104 11 76.81233 2.487303 11 75.66257 40.13344 11 57.94927 26.51233 11 11.5125 26.8875 11 11.88768 27.4 11 12.025 41.85069 11 50.99105 25.8521 11 76.81233 26.71168 11 78.32666 26.99981 11 79.95001 -5 11 87.15404 -7.225733 11 85.85816 -9.712252 11 85.18704 27 11 87.15404 29.22573 11 85.85816 31.71225 11 85.18704 34.28775 11 85.18704 45 6.327876 28.02471 45 5.965644 24.84254 45 0.4124416 13.15892 45 4.289943 46.6902 45 5.175963 21.34926 45 4.671211 19.86154 45 3.923815 18.12157 45 2.849726 16.18872 45 2.185285 15.21321 45 4.943964 44.34032 45 6.009005 40.62665 45 6.211642 39.53195 45 6.53226 36.80147 45 6.627478 34.46321 45 6.376598 28.7553 31.5251 3.190818 36.00158 32.13812 3.435829 35.77436 36.15528 1.052706 41.84077 42.04816 0.8481366 45.42818 37.83142 1.847471 40.7913 32.6872 3.696182 35.43057 26.18765 0.5518227 36.81235 28.01691 2.464837 34.9831 26.19155 0.5518226 36.81626 28.32376 2.473762 35.25934 27.09119 0.5457129 37.66611 28.90155 2.529102 35.64735 29.53433 2.633103 35.92346 28.78878 0.5099603 39.04477 30.19884 2.781943 36.07753 30.75391 0.4525856 40.38113 30.87066 2.970154 36.10389 33.03188 0.3885297 41.72801 34.28483 0.3581465 42.42369 36.6474 0.3113536 43.72424 40.03767 0.2652374 45.73113 41.93184 0.2481039 47.00854 23.88467 8 79.33067 23.54084 8 78.72492 23.32196 8 78.4992 23.01013 8 78.27384 22.35691 8 78.03211 21.6604 8 78.02904 20.12129 8 79.31413 20.47043 8 78.71144 20.64093 8 78.53271 21.00508 8 78.26502 21.49091 8 78.06588 -40.90886 3.246996 27.56734 -38.80218 7.658305 25.90358 -38.88824 7.471623 26.15249 -38.81533 7.46268 26.33189 -38.74573 8.167943 23.95245 -38.73102 8.20798 23.35308 -39.28478 7.513591 22.06581 -38.87295 1.774088 16.82135 -38.93585 1.840618 16.88315 -38.79925 2.540331 16.85589 -40.15491 3.194036 18.56193 -38.74524 3.215174 16.94893 -38.66241 4.86925 17.51456 -38.66948 4.631129 17.39754 -39.21597 4.415881 17.90448 -38.68183 4.302002 17.25725 -38.66739 7.596756 20.39369 -39.48751 6.889032 20.91747 -38.64938 6.881505 19.21051 -39.54253 6.147931 19.81982 -38.64563 6.495517 18.75399 -38.64641 5.823754 18.1336 -38.70479 8.131296 22.17198 -38.69708 8.065855 21.81158 -39.47167 7.268867 24.94336 -38.77191 7.993633 24.9056 -38.75905 8.093419 24.45399 -42.1443 1.301581 22.77778 -42.18244 1.419583 24.09478 -41.91352 1.161561 21.48 -41.7354 1.574044 26.52845 -40.14086 6.55557 22.66524 -40.29387 6.02596 25.51907 -39.73337 6.194047 26.74426 -41.21512 1.617951 27.78178 -38.95581 0.8604274 16.83482 -39.28516 0.9648748 17.12774 -40.76107 1.674353 18.98636 -41.69365 2.331088 21.32605 -40.27242 6.010645 21.46707 -40.24301 5.364038 20.31029 -40.41424 4.76994 27.22101 -41.43746 3.158883 26.31982 -40.95626 4.640499 25.98288 -41.47976 4.185125 23.60275 -40.88237 5.43463 23.18446 -41.50003 3.837241 22.32665 -40.9523 4.982882 21.94313 -41.33855 3.424442 21.0774 -40.84975 4.446839 20.73513 -41.89793 2.612088 22.60527 -41.91374 2.8489 23.90663 -37.85078 4.688513 16.36582 -37.83278 5.553548 16.77719 -37.20718 6.161077 15.7506 -37.82878 9.141086 21.99315 -37.86769 9.085597 22.00605 -38.14189 8.825594 23.73651 -36.89415 3.113212 13.49162 -36.87753 4.414692 13.68929 -37.19652 8.879454 18.23491 -37.20143 8.078536 17.2678 -37.19975 8.884393 18.25674 -37.20494 8.87341 18.26449 -37.20554 8.893167 18.29581 -37.18286 8.858471 18.14266 -37.18197 8.857271 18.13688 -36.91363 8.39924 16.17953 -37.54266 9.172064 20.36231 -37.46833 9.141455 19.92625 -37.83908 8.440616 19.89989 -37.64037 9.188021 20.92631 -38.42844 8.235046 25.32458 -38.18966 8.748974 24.00143 -38.17552 8.772505 23.92301 -38.68129 7.403955 26.72577 -38.54846 7.882889 25.98924 -38.4428 8.196501 25.40416 -38.4383 8.20868 25.37923 -37.94269 2.69964 15.92019 -37.2017 7.177649 16.43598 -36.86119 7.992682 15.41843 -36.86338 6.824615 14.62938 -36.86809 5.679324 14.08086 -37.21883 5.161745 15.27447 -37.24143 4.052178 14.935 -37.27935 2.896445 14.76452 -37.40795 9.104564 19.56612 -37.82931 7.893059 18.94523 -37.82386 7.207656 18.08542 -37.82777 9.203487 22.48488 -37.24059 9.777152 21.17753 -37.83555 9.085 24.21179 -35.87269 10.6924 20.08148 -36.51261 10.3479 21.52291 -37.17995 9.80843 22.92006 -36.12248 10.41074 18.39116 -36.73632 9.840538 18.47013 -36.67641 9.855335 18.24702 -36.44984 10.11703 18.29638 -35.7669 10.63907 18.44516 -35.26352 10.85984 18.57954 -35.25526 10.86087 18.55663 -17.46165 10.75501 1.133513 -15.68543 8.925634 -1.422974 -15.5 7.937254 -1 -16.37868 9.995098 -1.593474 -17.46165 10.6797 -1.702618 -18.5 10.93941 1.152948 -17.46165 9.869385 -4.421567 -18.5 10.80406 -2.066943 -18.5 10.86282 -1.731811 -17.46165 8.379814 -6.836207 -18.5 9.326336 -5.832621 -18.5 10.0386 -4.49738 -18.5 2.957435 -10.59498 -18.5 3.87806 -10.29372 -17.46165 3.812687 -10.1202 -18.5 6.421762 -8.9309 -17.46165 6.313511 -8.780353 -18.5 6.587319 -8.809497 -18.5 8.523493 -6.953421 -18.5 1.067453 -10.94808 -17.46165 1.04946 -10.76353 -18.5 -1.072411 -10.9476 -17.46165 -1.785996 -10.66608 -18.5 -1.816619 -10.84896 -17.46165 -4.498532 -9.834543 -18.5 -4.575664 -10.00316 -18.5 -4.957225 -9.81967 -17.46165 -6.901462 -8.326153 -18.5 -7.019794 -8.468914 -18.5 -8.171626 -7.363731 -17.46165 -8.829406 -6.244726 -18.5 -8.980794 -6.351798 -17.46165 -10.7714 -0.9653428 -18.5 -10.2809 -3.911923 -17.46165 -10.14967 -3.733512 -18.5 -10.3237 -3.797526 -18.5 -10.95609 -0.9818942 -15.5 -7.968064 -0.714105 -15.68543 -1.492658 -8.914246 -15.5 -3.327756 -7.275029 -15.68543 -3.759678 -8.219284 -15.5 -5.105305 -6.15921 -15.68543 -5.767942 -6.958637 -15.5 -6.531487 -4.619489 -15.68543 -7.379234 -5.219071 -15.5 -7.508146 -2.761837 -15.68543 -8.482658 -3.120307 -15.68543 -9.002271 -0.8067916 -15.5 7.900231 -1.259499 -15.5 7.300803 -3.270822 -15.68543 8.248403 -3.695354 -15.5 6.198904 -5.057033 -15.68543 7.003484 -5.713405 -15.5 4.670372 -6.4952 -15.68543 5.276558 -7.338237 -15.5 2.820407 -7.486341 -15.68543 3.186479 -8.458024 -15.5 0.7763298 -7.962243 -15.68543 0.8770927 -8.995694 -15.5 0 -8.000006 -15.5 -1.321177 -7.890151 -16.37868 9.236721 -4.138129 -16.37868 7.842637 -6.397982 -16.37868 5.908792 -8.2175 -16.37868 3.56828 -9.471458 -16.37868 0.9821854 -10.07355 -16.37868 -1.671507 -9.982344 -16.37868 -4.21016 -9.204113 -16.37868 -6.459053 -7.792417 -16.37868 -8.26341 -5.844416 -16.37868 -9.499045 -3.49418 -16.37868 -10.08092 -0.9034606 39.22797 3.399272 -10.46159 39.20208 2.289232 -10.75916 39.18283 0.4548318 -10.99059 39.38315 6.465842 -8.899039 39.32893 5.694534 -9.411285 39.24898 4.043044 -10.23004 39.67766 8.899511 -6.465193 39.58858 8.354314 -7.155798 39.43322 7.043553 -8.449164 40.57062 10.99294 -0.3941347 40.28614 10.76937 -2.240693 40.02487 10.25354 -3.983066 39.7881 9.440814 -5.645444 -36.61457 9.038351 14.35487 -35.77213 10.38481 16.3433 -36.311 9.641609 14.35487 -36.21762 9.961236 16.27939 -36.58938 9.104257 14.35487 -36.56151 9.465703 16.23004 -34.9043 10.78936 14.35487 -35.92133 10.1213 14.35487 -34.68632 10.91156 16.49907 -35.25018 10.70718 16.41818 -34.83835 10.81457 14.35487 -21.175 -10.2809 -3.911923 -21.175 6.587319 -8.809497 -21.175 2.957435 -10.59498 -21.175 10.80406 -2.066943 -21.175 9.326336 -5.832621 -21.175 -8.171626 -7.363731 -21.175 -4.957225 -9.81967 -21.175 -1.072411 -10.9476 30.26643 4.304041 32.73357 31.37604 3.414024 35.55693 30.66456 3.176466 35.66014 32.02869 3.68392 35.28399 32.58458 3.970469 34.85717 29.93559 2.985053 35.58761 29.23151 2.850909 35.34356 28.59321 2.78183 34.94218 28.05782 2.78183 34.40678 27.71601 3.68392 30.97131 28.14283 3.970469 30.41543 27.44307 3.414024 31.62396 27.33986 3.176466 32.33544 30.06285 4.764472 29.61246 30.79181 4.955884 29.68499 29.35136 4.526914 29.71566 28.69871 4.257018 29.98861 33.28433 4.526914 33.64863 33.01139 4.257018 34.30129 33.38754 4.764472 32.93716 23.98898 0.9525223 27.49938 24.90591 1.405268 25.68252 26.3244 2.987132 28.02353 29.81453 0.9525223 19.78294 28.18522 1.252132 21.06863 27.67271 0.9525223 21.09825 39.85216 3.97087 27.56749 39.95882 3.95716 27.93506 38.6766 4.533651 28.7246 37.55501 4.72668 26.94104 38.92924 4.052052 25.8423 39.30685 4.03348 26.43646 39.48266 4.014645 26.73138 39.67013 3.993148 27.1044 39.82302 3.974531 27.48311 38.49735 4.022426 25.15485 36.05896 4.72668 25.44499 38.06952 3.938231 24.46658 34.27539 4.533651 24.3234 37.22683 3.604291 23.0927 37.64593 3.79913 23.77879 35.63146 2.263669 20.43821 36.00261 2.670855 21.06123 35.6806 3.220276 21.81438 36.38637 3.026844 21.70208 36.78241 3.331608 22.35969 35.27339 1.804889 19.83429 33.21974 2.751428 20.9614 35.02758 1.447614 19.41817 34.72433 0.9525223 18.90309 24.66729 0.9525223 25.07918 25.92096 0.9525223 22.9007 26.45922 2.205972 24.48987 28.28292 2.960142 23.72718 30.27101 3.623948 23.43879 27.65644 2.850909 33.7685 27.41239 2.985053 33.06441 26.49057 2.291598 33.35573 25.10808 1.776741 31.67298 36.39928 4.90662 31.51565 33.31501 4.955884 32.20819 35.9239 5.167918 30.14416 33.07096 5.090028 31.5041 35.14205 5.302478 28.90084 32.66958 5.159108 30.86581 34.09916 5.302478 27.85795 31.48435 4.90662 26.60072 30.0644 4.533767 26.45944 28.67851 4.07103 26.66047 27.40721 3.5453 27.19214 24.96134 1.903235 30.37763 25.49301 2.428964 29.10634 31.4959 5.090028 29.92903 32.21439 0.9525223 19.03587 30.67193 2.08242 20.70791 32.30797 4.158812 23.64146 32.85584 5.167918 27.07609 32.13418 5.159108 30.33042 23.92786 0.9525223 30.01209 24.04862 0.8077043 31.79179 24.54876 0.649254 34.08253 24.34794 0.6914616 33.4069 25.87261 0.554039 36.47258 25.75071 0.5562255 36.32625 25.06654 0.587813 35.28903 43.14803 10.77165 9.003568 44.4944 9.666721 9.003568 44.57318 9.542318 9.003568 44.59191 9.510624 9.003568 44.87082 8.870861 9.003568 44.89133 8.800144 9.003568 44.60113 9.494692 9.003568 44.68789 9.332375 9.003568 44.67967 9.348843 9.003568 44.9727 8.403745 9.003568 43.97341 10.25957 9.003568 44.90093 8.764603 9.003568 44.91882 8.69318 9.003568 44.61928 9.462659 9.003568 44.99797 8.110424 9.003568 44.99435 8.183964 9.003568 44.99187 8.220695 9.003568 44.98172 8.33067 9.003568 43.81652 10.38752 9.003568 43.83113 10.37633 9.003568 43.86016 10.35368 9.003568 44.93495 8.621338 9.003568 44.96753 8.440196 9.003568 44.76454 9.165042 9.003568 44.75003 9.198881 9.003568 44.73511 9.232538 9.003568 44.7275 9.249298 9.003568 44.70404 9.29929 9.003568 43.8889 10.33068 9.003568 43.95951 10.27164 9.003568 43.41417 10.64577 9.003568 43.47867 10.61027 9.003568 43.49466 10.60115 9.003568 43.5106 10.59193 9.003568 43.52647 10.58261 9.003568 43.57375 10.55408 9.003568 43.58939 10.54437 9.003568 43.6205 10.52468 9.003568 44.99977 8.036815 9.003568 44.63703 9.430407 9.003568 44.10825 10.13431 9.003568 44.0819 10.16002 9.003568 44.05524 10.1854 9.003568 44.04179 10.19797 9.003568 44.00099 10.23518 9.003568 43.65135 10.5046 9.003568 43.78708 10.40963 9.003568 43.14803 10.77165 49 44.12131 10.12133 49 43.5 10.59808 49 44.77163 9.148058 49 44.59807 9.5 49 41.12132 10.12132 64.95001 41.59808 9.5 64.95001 41.70432 9.5 63.14782 40.61322 10.59808 63.02429 40.5 10.59808 64.95001 42.05426 9.5 61.02611 42.6411 9.5 58.6287 40.97962 10.59808 60.80043 41.58124 10.59808 58.34154 43.85955 9.5 54.17776 42.7935 10.59808 53.9145 44.42343 9.5 51.35304 43.33606 10.59808 51.20004 -2.099865 9.148051 79.25424 -2.712684 10.12132 79.0366 -3.629831 10.77164 78.71088 -2.967622 10.77164 77.54425 -1.945489 10.77164 76.67546 -0.6873998 10.77164 76.20989 -2.217795 10.12132 78.16474 -1.453924 10.12132 77.51547 -0.5137149 10.12132 77.16754 3.61836 10.77164 78.67903 2.704111 10.12132 79.0128 2.09323 9.148051 79.23581 2.945923 10.77164 77.51826 1.916193 10.77164 76.65849 2.201578 10.12132 78.14532 1.432029 10.12132 77.50279 1.704223 9.148051 78.56431 1.108522 9.148051 78.06693 0.65406 10.77164 76.20399 0.4887989 10.12132 77.16312 0.3783751 9.148051 77.804 -1.716776 9.148051 78.57934 -1.12547 9.148051 78.07675 -0.3976623 9.148051 77.80741 23.12547 9.148051 78.07675 23.45392 10.12132 77.51547 22.51372 10.12132 77.16754 23.94549 10.77164 76.67546 22.6874 10.77164 76.20989 24.71268 10.12132 79.0366 25.62983 10.77164 78.71088 24.09987 9.148051 79.25424 21.34594 10.77164 76.20399 20.08381 10.77164 76.65849 19.05408 10.77164 77.51826 18.38164 10.77164 78.67903 21.5112 10.12132 77.16312 20.56797 10.12132 77.50279 19.79842 10.12132 78.14532 19.29589 10.12132 79.0128 24.96762 10.77164 77.54425 24.2178 10.12132 78.16474 23.71678 9.148051 78.57934 22.39766 9.148051 77.80741 21.62162 9.148051 77.804 20.89148 9.148051 78.06693 20.29578 9.148051 78.56431 19.90677 9.148051 79.23581 37.71731 0.7317537 18.76999 41.02202 3.163848 25.28242 41.126 3.016624 24.62024 40.20923 2.667485 22.48151 41.44198 2.497807 22.69905 40.47655 2.835138 23.1564 41.28919 2.762512 23.61274 40.74819 2.955729 23.83684 41.14289 2.991639 24.51423 41.024 3.029275 24.52199 38.96354 1.120571 19.26435 42.17921 0.7733224 18.55228 39.18957 1.511712 19.85759 42.0401 1.166726 19.31187 39.42502 1.860706 20.4708 41.90044 1.525664 20.08248 39.66979 2.167421 21.10343 41.74886 1.87948 20.93079 39.94646 2.452306 21.81294 41.66915 2.052017 21.38282 41.60036 2.193989 21.77675 42.28264 0.4539195 17.99095 41.41347 0.4987869 18.20107 40.56697 0.5467174 18.37561 38.74711 0.6870274 18.69186 40.05915 3.925131 28.14538 40.76704 3.59657 28.16532 40.79413 3.554024 27.69503 40.83346 3.490716 27.1806 40.84406 3.473356 27.05732 40.89852 3.382036 26.47388 40.96309 3.269674 25.83909 43.27526 9.137041 -0.903393 42.63774 10.10696 -0.8024461 42.96448 8.928763 -2.419689 42.68424 8.483449 -3.831885 42.43578 7.798531 -5.164206 42.32016 9.866993 -2.47971 42.03364 9.367293 -4.043988 41.77964 8.605607 -5.522711 41.68848 10.75834 -0.623708 41.38225 10.51154 -2.417029 41.10417 9.985954 -4.096827 40.85566 9.178727 -5.690654 40.64986 8.113412 -7.133489 41.57142 7.604269 -6.857194 42.23195 6.893915 -6.363286 42.07833 5.80947 -7.382411 41.4148 6.406852 -7.995253 40.49306 6.836892 -8.366983 41.97903 4.696478 -8.136455 41.90607 3.335008 -8.775747 41.31387 5.179268 -8.840322 41.24007 3.67809 -9.559316 40.39046 5.527036 -9.28453 40.31406 3.924843 -10.06614 41.86517 1.888785 -9.187864 41.84893 0.3753224 -9.367907 41.19895 2.083289 -10.02426 41.18271 0.4139953 -10.22779 40.27064 2.222878 -10.57199 40.25322 0.4417148 -10.79351 43.34797 0.4571265 48.58606 43.12213 0.4703742 47.87717 44.14027 1.331874 48.17952 44.81589 2.471333 49.39089 44.79135 2.46664 48.57777 44.71432 3 51.76988 44.87656 3 50.32487 44.8991 3 50.11582 42.39552 0.1262366 47.77672 42.38817 0.1299771 47.75775 41.96914 0.2360489 47.06887 43.18946 1.275421 45.58485 42.30941 0.1457901 47.62744 44.17031 2.080491 45.88005 44.79883 3.151922 46.27291 44.80654 3.869524 43.93738 44.20125 2.860094 43.55881 43.25887 2.110705 43.27777 44.76925 4.808746 40.33458 41.35452 3.456619 28.99421 41.98216 3.317029 36.38808 42.92328 2.951826 39.88272 42.64878 3.434509 36.40319 43.30575 3.702116 36.43759 44.03933 3.699087 40.06456 43.90191 4.116617 36.49089 44.73875 5.266026 36.63867 44.31869 4.683385 32.80506 44.71054 5.311452 32.81828 44.23109 4.377727 28.91885 44.67627 5.025543 28.86584 43.60722 3.851888 28.96187 43.76987 4.153203 32.79389 42.86414 3.513317 28.98957 43.10746 3.774306 32.78591 42.08644 3.387831 28.99984 42.39485 3.573421 32.78168 41.69672 3.545118 32.78109 42.1261 3.334491 28.17881 42.89533 3.468379 28.17192 43.62805 3.811397 28.15426 44.24232 4.33752 28.12718 44.68067 4.982821 28.09395 44.30368 4.067163 25.1406 44.70105 4.675948 25.04502 44.70497 4.683977 25.04376 43.74156 3.552465 25.22141 43.06577 3.195273 25.27748 42.34469 3.021574 25.30475 41.61764 3.026117 25.30404 44.82432 1.368585 15.81005 44.78816 2.927204 18.60421 44.11705 2.010768 19.04802 43.45713 0.06779432 16.76012 44.27371 0.6051774 16.36797 43.09731 1.410871 19.33854 42.53834 1.267601 19.40792 42.09225 2.305416 22.21612 42.72595 2.389409 22.19075 43.35681 2.614563 22.12276 43.63581 1.660476 19.21766 43.93348 2.980079 22.01238 44.74668 4.020952 21.69805 43.32263 0.09698009 16.92052 42.35139 0.4235439 17.92772 37.69884 0 16.80665 40.48142 0.1416254 17.56431 34.79521 0.2513826 17.91507 37.70875 0.1911485 17.86033 41.30404 0.1289343 17.42229 34.88123 0 16.71603 32.03846 0.2484156 18.05415 29.40216 0.2484156 18.87483 27.04931 0.2484156 20.31973 25.12497 0.2484156 22.29977 23.74778 0.2484156 24.69288 23.00264 0.2484156 27.35153 22.9355 0.2484156 30.11181 42.26153 0.1259029 47.65146 42.45075 0.07571387 48.02477 -9.95 -10 84.9 -12.05 -10 84.9 -11.525 -7.590673 93.4 -11.90933 -7.975 93.4 -11 -8.5 93.4 -12.05 -8.5 93.4 -11.90933 -9.025 93.4 -10.09067 -7.975 93.4 -10.475 -7.590673 93.4 -11 -7.45 93.4 -10.475 -9.409328 93.4 -10.09067 -9.025 93.4 -9.95 -8.5 93.4 -11.525 -9.409328 93.4 -11 -9.55 93.4 -12.475 6 79.95001 -16.525 6 79.95001 -12.475 4.5 79.95001 -16.525 0 79.95001 -5.475 4.5 79.95001 -5.475 0 79.95001 -8.677126 8.5 99.8854 -8.677126 9.409926 99.8854 -11 9.409926 100.4 -11 8.5 100.4 -13.3244 9.409925 99.8847 -13.32287 8.5 99.8854 -8.534111 8.5 99.78511 -8.534111 9.398838 99.78511 -8.434326 8.5 99.64173 -8.434326 9.366894 99.64173 -8.390213 8.5 99.47592 -8.390213 9.318982 99.47592 -13.60979 9.318982 99.47592 -13.60979 8.5 99.47592 -13.56479 8.5 99.64363 -13.56479 9.367385 99.64363 -13.46515 8.5 99.78585 -13.46515 9.39897 99.78585 -6.617371 8.5 97.82277 -5.776206 8.5 95.57968 -5.846113 8.56032 95.9897 -6.617371 9.046358 97.82277 -16.15389 8.560318 95.98969 -16.22379 8.5 95.57968 -15.38263 8.5 97.82277 -15.38263 9.046358 97.82277 -12.99627 8.5 94.77796 -12.99627 8.4 94.77796 -12.80238 8.4 95.76685 -12.80238 8.5 95.76685 -12.15091 8.4 96.53567 -12.15091 8.5 96.53567 -11.20726 8.4 96.88923 -11.20726 8.5 96.88923 -10.21098 8.4 96.73779 -10.21098 8.5 96.73779 -9.415024 8.4 96.11978 -9.415024 8.5 96.11978 -9.021446 8.4 95.1921 -9.021446 8.5 95.1921 -9.130168 8.4 94.19026 -9.130168 8.5 94.19026 -9.71359 8.4 93.36861 -9.71359 8.5 93.36861 -10.6236 8.4 92.93574 -10.6236 8.5 92.93574 -11.62916 8.4 93.00154 -11.62916 8.5 93.00154 -12.475 8.4 93.54931 -12.475 8.5 93.54931 -12.71951 8.5 94.55516 -17.04278 8.5 93.40512 -17.59535 8.5 94.94012 -17.45793 8.5 94.74633 -12.475 8.5 93.9 -16.525 8.5 92.03219 -12.53812 8.5 94.24965 -17.13692 8.5 93.85691 -6.227636 8.5 90.90277 -8.496297 8.5 89.20056 -7.315706 8.5 89.88185 -16.01497 8.5 91.21217 -14.6396 8.5 89.84992 -13 8.5 89.00509 -12.91227 8.5 88.97605 -5.442203 8.5 92.0963 -4.956336 8.5 93.40804 -4.863084 8.5 93.85691 -4.555724 8.5 94.7231 -4.404645 8.5 94.94012 -12.1 8.5 88.77301 -11.00001 8.5 88.67505 -9.9 8.5 88.77301 -10.2625 6.5 93.62261 -9.722613 6.5 94.1625 -11 6.5 94.9 -9.525001 6.5 94.9 -9.722613 6.5 95.6375 -12.27739 6.5 94.1625 -11.7375 6.5 93.62261 -11 6.5 93.42501 -11.7375 6.5 96.17739 -12.27739 6.5 95.6375 -12.475 6.5 94.9 -10.2625 6.5 96.17739 -11 6.5 96.375 -12.27739 8.4 94.1625 -11.7375 8.4 93.62261 -11 8.4 93.42501 -10.2625 8.4 93.62261 -9.722613 8.4 94.1625 -9.525001 8.4 94.9 -9.722613 8.4 95.6375 -10.2625 8.4 96.17739 -11 8.4 96.375 -11.7375 8.4 96.17739 -12.27739 8.4 95.6375 -12.475 8.4 94.9 -19.38593 8.739487 95.02572 -19.41129 8.720318 94.9602 -18.94026 8.511985 94.83631 -18.72208 8.593173 95.041 -18.46897 8.675383 95.29756 -18.22884 8.739486 95.56527 -19.69466 8.188876 94.24269 -19.69671 8.16504 94.23102 -19.16037 8.421184 94.64377 -19.61946 8.460948 94.46638 -19.66322 8.353923 94.35531 -19.69246 8.212679 94.25522 -19.48041 8.657227 94.79122 -18.98382 8.494707 94.79713 -19.19493 7.254463 93.41997 -19.21405 7.278398 93.48236 -19.26789 7.251549 93.50122 -19.42129 7.596982 93.92934 -19.44746 7.522727 93.87319 -19.38183 7.529383 93.86386 -19.9663 7.727891 93.63182 -19.9879 8.304291 93.90953 -19.63682 8.020673 94.1861 -19.7881 7.580093 93.80569 -19.63082 8.00712 94.18095 -19.62266 7.530829 93.86365 -19.55664 7.850263 94.10852 -19.91238 7.661645 93.70975 -19.88617 8.22151 94.10066 -19.7881 8.185323 94.18421 -19.489 7.719446 94.02717 -19.23186 7.301971 93.53526 -19.27046 7.356136 93.63664 -19.44746 7.2068 93.53214 -19.28915 7.383547 93.68055 -19.35295 7.482301 93.81196 -19.62266 7.217096 93.52502 -19.53994 7.037733 93.17082 -19.33494 7.063425 93.16452 -19.26789 7.091717 93.15756 -19.14473 7.180184 93.13585 -19.13035 7.195086 93.13219 -19.7881 7.279697 93.48178 -19.6807 7.069025 93.16313 -19.62266 7.051028 93.16754 -19.9663 7.467507 93.35207 -19.93576 7.283825 93.11036 -19.91238 7.383326 93.41022 -19.86414 7.189112 93.13362 -19.76817 7.111984 93.15257 -2.37633 7.992305 94.17529 -2.377343 7.560337 93.8883 -2.211904 7.608641 93.82954 -2.599233 7.561666 93.89627 -2.602404 7.556281 93.89102 -2.552537 7.552392 93.89796 -2.000418 7.50224 93.05672 -2.060021 7.291264 93.10853 -2.0337 7.447067 93.32123 -2.087621 7.360826 93.37625 -2.135846 7.18912 93.13362 -2.211904 7.254662 93.44397 -2.194257 7.137607 93.14627 -2.211904 7.124944 93.14938 -2.31925 7.069033 93.16312 -2.377343 7.19053 93.4849 -2.414586 7.043313 93.16944 -2.552537 7.179982 93.49162 -2.552537 7.038862 93.17053 -2.657337 7.060859 93.16514 -2.732112 7.225826 93.46237 -2.732112 7.09171 93.15756 -2.869647 7.195083 93.13219 -2.815358 7.242253 93.3833 -2.771715 7.297145 93.52498 -2.730042 7.355421 93.63544 -2.711146 7.383107 93.67988 -2.578867 7.596707 93.92909 -2.443635 7.850891 94.10895 -2.531651 7.680656 93.99874 -2.551525 7.644831 93.97045 -2.0337 7.753557 93.65326 -2.064372 8.250217 94.03442 -2.087621 7.688601 93.73227 -2.23195 8.180013 94.19653 -2.303287 8.16507 94.23104 -3.771158 8.739486 95.56527 -3.336935 8.61355 95.09887 -2.614079 8.739488 95.02572 -3.32103 8.608129 95.08318 -2.544471 8.681855 94.85077 -3.067156 8.514904 94.84305 -2.474632 8.606416 94.6859 -2.407834 8.51077 94.53102 -2.838542 8.420734 94.64287 -2.559598 8.293511 94.41815 -2.305341 8.18889 94.2427 -2.307541 8.212679 94.25522 -2.351653 8.395926 94.39484 -2.386354 8.472312 94.48032 -12.475 8.4 93.9 -12.71951 8.4 94.55516 -12.53812 8.4 94.24965 -18.90922 7.694948 93.78565 -19.04209 7.711924 93.9102 -18.56937 7.86729 93.55454 -18.69841 7.73442 93.5033 -18.41189 8.112804 94.02519 -18.40438 8.144192 94.10848 -18.50018 8.122793 94.18968 -19.10551 8.280365 94.53455 -18.66455 8.344257 94.67936 -18.39376 8.480696 94.90688 -18.38431 8.483117 94.91049 -18.37562 8.498843 94.94373 -18.32338 8.570812 95.10353 -18.20706 8.675964 95.38285 -18.26078 8.633299 95.25989 -18.27673 8.618904 95.22182 -18.43108 8.279341 94.48265 -18.43182 8.298502 94.52592 -18.4201 8.388618 94.71582 -18.41092 8.4202 94.78045 -18.40025 8.44904 94.83966 -18.38635 8.479188 94.90225 -18.94203 8.197619 94.47387 -18.79356 8.147405 94.39861 -18.64455 8.121463 94.30335 -18.41024 8.202863 94.27964 -18.40451 8.187191 94.23081 -18.79272 7.703168 93.64695 -18.45171 8.023335 93.80503 -18.50052 7.944628 93.62528 -19.62862 8.008738 94.18246 -19.47691 7.898868 94.15016 -19.33318 7.817526 94.09578 -19.18662 7.75396 94.0156 -18.4206 8.088348 93.96298 -3.549992 8.026434 93.81234 -3.434408 7.985476 93.94601 -3.588136 8.112875 94.02538 -2.841115 7.48743 93.70639 -2.57094 7.926337 94.17525 -3.585124 8.371092 94.6841 -3.582933 8.367884 94.67675 -3.300865 8.203955 94.46259 -3.57224 8.352224 94.64088 -3.450104 8.18525 94.36601 -3.589752 8.202855 94.27964 -3.478979 8.541767 95.02569 -3.650857 8.502466 94.94716 -3.15165 8.247836 94.54031 -3.663268 8.485536 94.94626 -3.644701 8.458345 94.88397 -3.642644 8.455332 94.87706 -3.593076 8.382739 94.71077 -3.776783 8.651783 95.32707 -3.742259 8.601222 95.21125 -3.693918 8.530426 95.04908 -3.673601 8.50067 94.98092 -3.792997 8.675528 95.38146 -2.986795 8.324601 94.60499 -2.863037 8.090984 94.34494 -2.861956 7.786908 94.03654 -3.504022 7.951324 93.64017 -3.49948 7.944618 93.62526 -3.349373 7.783852 93.5231 -3.366688 7.794329 93.49247 -3.054758 7.481684 93.42347 -3.139334 7.735708 93.80469 -3.593179 8.195223 94.25537 -3.158187 7.987963 94.18479 -18.36661 8.131237 93.98484 -17.87162 8.355965 93.73209 -18.01882 8.424287 94.5969 -17.80985 8.470419 94.65641 -17.76795 8.433513 94.227 -18.22712 8.327206 94.42807 -18.35415 8.224975 94.26665 -17.95936 8.560323 95.1478 -17.94791 8.554214 95.13407 -17.77951 8.513184 95.03282 -17.90829 8.539834 95.1025 -18.16873 8.632414 95.26885 -18.35935 8.437804 94.80424 -18.31814 8.428194 94.77038 -18.08363 8.591715 95.18481 -4.050513 8.554957 95.13572 -4.196212 8.516889 95.04485 -3.686913 8.42724 94.76657 -3.66639 8.431356 94.78234 -4.035095 8.561372 95.14839 -4.040626 8.560328 95.14781 -3.912016 8.592896 95.18658 -3.981164 8.42428 94.59688 -3.77604 8.32901 94.43063 -3.840896 8.6262 95.25431 -16.525 1.065431 85.32013 -16.525 1.097699 85.37628 -16.78656 1.090434 85.55004 -19.18254 1.050826 87.55821 -19.22576 1.00364 87.52654 -17.91218 0.952255 86.30997 -19.1722 1.066654 87.56517 -17.97613 1.107235 86.46747 -18.00935 1.105806 86.49487 -17.8802 1.024362 86.35592 -19.13043 1.184357 87.58605 -19.13537 1.158462 87.58519 -16.525 1.135859 85.41751 -16.525 1.170739 85.44255 -16.76698 1.167804 85.59545 -16.525 1.20348 85.45837 -17.86708 1.113291 86.37921 -17.10836 1.153125 85.82086 -17.10775 1.192329 85.82952 -16.76353 1.231642 85.61212 -16.525 1.253273 85.47113 -16.525 1.040888 85.22087 -16.525 1.052361 85.28369 -16.82047 1.036128 85.48497 -17.15514 1.009312 85.72321 -17.12359 1.071063 85.78258 -19.13757 1.149476 87.58447 -17.27329 0.9761614 85.7507 -17.94671 0.9204065 86.28141 -18.57576 0.9180271 86.82995 -19.26355 0.9790191 87.4966 -3.646018 8.170079 94.09488 -4.187231 8.388828 93.88395 -4.232015 8.449958 94.38932 -3.582806 8.038136 93.74221 -4.128379 8.355962 93.73207 -17.84339 9.552564 98.20986 -19.02682 9.095395 96.27211 -19.24741 8.928083 95.66204 -15.95542 9.880118 100.0832 -13.46619 9.532044 100.1888 -13.97657 9.97159 101.2833 -12.02078 9.97159 101.8688 -11 9.97159 101.9432 -8.023433 9.97159 101.2833 -9.979223 9.97159 101.8688 -6.044576 9.880118 100.0832 -2.753644 8.929163 95.66581 -2.973183 9.095395 96.27211 -4.156607 9.552564 98.20986 -10.66189 11.49627 88.8024 -10.32572 11.5 88.9809 -10.12899 11.5 89.00663 -13.86586 11.4 88.81567 -15.11851 11.4 89.58303 -14.64814 11.5 90.19028 -13.53856 11.5 89.51055 -11.87101 11.5 89.00663 -11.98332 11.4 88.24678 -11.67428 11.5 88.9809 -11.19616 11.49468 88.76713 -10.01669 11.4 88.24678 -8.461447 11.5 89.51055 -8.134141 11.4 88.81567 -7.351861 11.5 90.19028 -6.881489 11.4 89.58303 -14.70646 11.5 90.23703 -16.52951 11.38531 91.71788 -15.81617 11.5 92.19513 -15.35015 11.5 91.02996 -16.21247 11.5 94.13834 -17.02542 11.38531 94.01955 -17.7762 11.05001 93.90984 -16.87691 11.28008 91.80598 -15.89342 11.38174 90.32252 -16.07651 11.37086 90.54552 -13.60979 11.5 99.47592 -8.466541 11.49571 99.70079 -8.390213 11.5 99.47592 -8.640438 11.49112 99.8665 -8.677126 11.4955 99.8854 -5.732177 11.5 94.89344 -5.787528 11.5 94.13834 -5.826847 11.5 93.87876 -6.251409 11.5 91.97337 -16.26657 11.5 94.78497 -13.60442 11.49981 99.51767 -5.991729 11.5 96.53317 -6.748696 11.5 98.0107 -7.927898 11.5 99.17928 -12.76539 11.491 100.109 -11.05662 11.491 100.3997 -9.342239 11.491 100.1442 -16.04084 11.5 96.4297 -15.31445 11.5 97.9225 -14.15956 11.5 99.11511 -13.50801 11.49455 99.73709 -13.32287 11.4955 99.8854 -6.738407 11.5 90.88072 -16.5 7.944444 89.64302 -16.61201 8.357628 90.77313 -17.2964 7.944498 90.62914 -17.6084 8.357628 92.69664 -18.05967 7.944567 92.06364 -15.0729 8.357628 89.24871 -13.13993 8.357628 88.27079 -11.00001 8.357628 87.93395 -8.860089 8.357628 88.27079 -6.92711 8.357628 89.2487 -5.388002 8.357628 90.77311 -4.391606 8.357628 92.69662 -3.904297 7.944598 92.15512 -6.876737 7.944507 88.50598 -5.683129 7.944535 89.45802 -4.648991 7.944567 90.71091 -15.4484 7.944444 88.72768 -13.33722 7.944444 87.65961 -11.00001 7.944444 87.29174 -9.9 7.944444 87.37167 -8.328549 7.944476 87.77619 -19.63896 9.566286 95.58785 -19.37532 9.87877 95.97737 -19.75154 9.450699 94.86997 -19.36881 9.814373 96.24488 -19.27273 9.947851 96.1658 -19.7883 9.363241 94.90268 -19.8072 9.247939 94.9409 -19.65812 9.429047 95.63258 -19.48808 8.769891 95.03341 -19.47021 9.039229 95.69216 -19.61403 8.843555 95.03191 -19.56787 9.147164 95.68836 -19.71422 8.948118 95.01672 -19.63432 9.282758 95.66794 -19.7826 9.081137 94.98759 -19.80743 9.226061 94.9476 -19.40983 9.587201 96.32264 -19.38941 9.468082 96.34396 -19.34279 9.354817 96.35162 -19.18361 9.172376 96.32495 -19.80969 8.557074 94.39761 -19.84742 8.443392 94.26985 -19.66952 8.585347 94.5656 -19.76283 8.649281 94.53798 -19.91615 9.033066 94.28696 -19.86078 9.173767 94.61323 -19.82861 9.288738 94.55007 -19.99896 8.487422 93.8684 -19.97949 8.355715 93.96926 -19.87318 8.27026 94.14011 -19.81538 8.245559 94.18949 -19.93803 8.9482 94.15325 -19.98297 8.696295 93.97143 -19.98515 8.667213 94.00733 -19.96874 8.587402 94.10588 -19.92085 8.510441 94.19606 -19.91607 8.295081 94.09049 -19.84222 8.732919 94.49291 -19.82567 8.949305 94.71679 -19.76272 8.844974 94.75554 -19.67735 8.758917 94.78076 -19.57989 8.69622 94.79204 -19.92574 8.997894 94.19824 -19.92264 8.934225 94.36124 -19.8977 8.830869 94.43226 -19.75664 9.441286 94.84654 -19.86491 1.076982 87.5746 -19.8217 1.073574 87.61479 -19.76392 1.110035 87.66336 -19.98484 0.8763864 87.26623 -19.95537 1.024869 87.43051 -19.76991 0.7504258 87.37032 -19.65578 0.764006 87.3591 -19.63595 0.8599888 87.48121 -19.91548 0.9564331 87.47136 -19.88341 0.7795366 87.34626 -19.84969 0.896705 87.49392 -19.84675 0.7648242 87.35842 -19.76821 0.8563552 87.49435 -19.68683 0.8404068 87.47484 -19.56666 0.9239552 87.55622 -19.96963 0.8504354 87.28767 -19.95956 0.8374139 87.29844 -19.94081 0.817999 87.31448 -19.92992 1.043685 87.48239 -19.7664 1.00075 87.62124 -19.64656 1.067753 87.70124 -19.67959 1.129189 87.70879 -19.51042 1.10832 87.73427 -19.3465 1.172383 87.72505 -19.46225 1.161122 87.74623 -19.56911 1.147643 87.74063 -19.35547 1.131597 87.7176 -19.21324 1.137413 87.64707 -19.16015 1.183693 87.61634 -19.36631 0.97921 87.56548 -19.27897 1.001254 87.5623 -19.69812 0.9440349 87.60152 -19.63008 0.9116304 87.56174 -19.59815 0.9997708 87.66532 -19.55165 0.9558445 87.60913 -19.48574 1.033304 87.68929 -19.46571 0.982132 87.62424 -19.35817 1.05261 87.67269 -19.36918 0.9973615 87.6088 -19.24012 1.057471 87.61316 -19.47639 0.960171 87.58372 -18.4677 0.7110046 86.40731 -16.94388 0.9498139 85.26879 -16.525 0.9268653 84.62847 -17.18937 0.7110046 85.07284 -16.525 0.6425546 84.03333 -16.525 0.4778812 83.84371 -17.34356 0.3692808 84.94977 -16.525 0.2731142 83.70359 -17.38446 0.04999995 84.91712 -16.525 0.04999995 83.65311 -19.61023 0.05000001 86.97063 -18.63166 0.04999995 86.21909 -19.62047 0.4059969 87.05633 -18.59728 0.3692808 86.25856 -19.64149 0.6543256 87.23503 -4.139648 1.120409 86.38994 -4.132701 1.11187 86.3792 -4.026223 1.108967 86.4691 -5.475 1.07093 85.33209 -4.809847 1.032522 85.79237 -4.82384 1.067247 85.81972 -2.869559 1.184357 87.58605 -3.556156 1.108687 86.87754 -2.863858 1.155007 87.58499 -3.536378 1.020549 86.86113 -2.827651 1.066357 87.56508 -2.815888 1.048577 87.55713 -3.496726 0.9479164 86.82263 -2.774029 1.003452 87.52638 -5.475 1.040888 85.22087 -4.767956 0.9803331 85.71994 -5.475 1.052269 85.28337 -5.475 1.113824 85.39595 -4.833543 1.106962 85.84154 -5.475 1.131512 85.41366 -4.838603 1.149847 85.85697 -4.839016 1.193899 85.86564 -5.475 1.200338 85.45713 -5.360457 1.243563 85.5379 -5.475 1.253013 85.47109 -3.997898 1.106109 86.48887 -4.119711 1.024054 86.35579 -4.087671 0.9520404 86.30979 -2.736445 0.9790189 87.4966 -3.402874 0.9190438 86.84957 -4.053287 0.920407 86.28142 -4.792505 1.004589 85.76123 -5.475 1.063253 85.31497 -4.856027 1.192677 85.88995 -16.14994 10.63677 100.239 -16.07848 10.76396 100.1294 -18.04197 10.42331 98.18107 -14.02047 10.85909 101.3774 -14.07607 10.73264 101.4967 -14.08393 10.70473 101.5135 -16.18898 10.41011 100.3192 -14.11383 10.50603 101.5776 -16.15544 10.16917 100.3066 -14.10187 10.26409 101.552 -14.05338 10.0871 101.448 -16.05727 9.971138 100.2042 -14.04301 10.06424 101.4258 -17.97901 9.637723 98.29736 -18.11469 9.829247 98.36253 -18.12856 10.29349 98.27568 -18.16882 10.06661 98.35469 -9.942402 10.70473 102.1202 -9.964168 10.85909 101.9716 -12.03583 10.85909 101.9716 -9.952879 10.0871 102.0486 -12.04712 10.0871 102.0486 -7.979533 10.85909 101.3774 -7.916066 10.70473 101.5135 -7.88631 10.5086 101.5773 -9.931957 10.49493 102.1915 -7.885608 10.49493 101.5788 -9.935694 10.27459 102.166 -7.896506 10.27459 101.5555 -7.946616 10.0871 101.448 -12.0576 10.70473 102.1202 -12.06804 10.49493 102.1915 -12.06431 10.27459 102.166 -3.871836 10.29442 98.27517 -3.831111 10.06916 98.3542 -2.631627 9.815316 96.24444 -2.590037 9.589716 96.32205 -2.610592 9.468083 96.34396 -3.8837 9.832924 98.36301 -2.655286 9.358375 96.35159 -4.017266 9.641145 98.29953 -2.812066 9.175562 96.32612 -5.939976 9.974726 100.2074 -5.843445 10.17293 100.3076 -5.811052 10.41267 100.3188 -5.850398 10.63769 100.2384 -2.727272 9.947851 96.1658 -3.958033 10.42331 98.18107 -5.921521 10.76396 100.1294 -14.65233 11.38531 99.7725 -12.95457 11.38531 100.6672 -11.06269 11.38531 100.9891 -9.164587 11.38531 100.7062 -7.448771 11.38531 99.84667 -6.08566 11.38531 98.49584 -5.210636 11.38531 96.78787 -4.910604 11.38531 94.89241 -4.151848 11.05001 94.89146 -4.223802 11.05001 93.90985 -4.974587 11.38531 94.01955 -4.489265 11.05001 97.0231 -5.47332 11.05001 98.9439 -7.006278 11.05001 100.463 -8.935889 11.05001 101.4297 -11.0705 11.05001 101.7478 -13.19812 11.05001 101.3858 -15.10741 11.05001 100.3796 -15.98733 11.38531 98.39389 -16.60877 11.05001 98.82925 -16.82701 11.38531 96.66828 -17.55307 11.05001 96.8886 -17.08795 11.38531 94.76702 -17.84653 11.05001 94.75045 -6.034978 11.38531 90.45552 -5.965394 11.37363 90.49263 -5.329577 11.38531 92.20222 -5.113342 11.27843 91.82453 -5.948684 11.10042 88.37878 -7.822498 11.10042 87.28781 -9.915863 11.10042 86.72279 -12.08414 11.10042 86.72279 -14.1775 11.10042 87.28781 -16.05132 11.10042 88.37878 -18.03951 10.81415 91.36478 -18.40275 10.65185 92.98032 -18.8 10.4 94.9 -17.96127 10.84183 91.02986 -16.76487 11.14213 90.04239 -17.88055 10.86786 90.68843 -17.96885 10.83925 91.06217 -12.79478 6.622629 86.30236 -11.00007 6.861519 86.30236 -15.08226 6 86.63349 -14.57736 6 86.4028 -15.47215 7.645157 88.37686 -6.528003 7.645246 88.37686 -3.693432 7.183207 90.89805 -2.869566 4.657988 89.13813 -2.86956 5.787574 90.274 -2.869553 6.647323 91.62755 -4.68398 6.209383 88.37686 -3.279722 4.341181 88.37686 -2.869573 3.309217 88.27088 -2.86958 1.806905 87.71451 -4.34774 1.681632 86.30236 -5.475 4.5 86.52 -5.475 2.920343 85.8476 -5.019179 3.363069 86.30236 -5.5 4.5 86.50357 -6.107044 4.810346 86.30236 -7.063942 4.5 85.66651 -12.5 6 85.8033 -12.475 6 85.79921 -12.475 5.267948 85.35678 -12.475 4.5 84.97154 -12.1 4.5 84.92303 -11.66816 4.5 84.88484 -9.9 4.5 84.92303 -9.205351 6.622664 86.30236 -8.589306 4.5 85.15636 -7.535589 5.922695 86.30236 -16.525 6 87.51933 -17.31614 6.209258 88.37686 -16.525 5.763355 87.33309 -17.65229 1.681499 86.30236 -16.525 2.936981 85.85298 -16.98089 3.362949 86.30236 -16.525 4.303596 86.41747 -19.13042 2.728104 88.01133 -18.72036 4.341027 88.37686 -19.13045 7.017164 92.52194 -18.30671 7.183063 90.89805 -19.13044 6.341961 91.06915 -19.13044 6.229709 90.88919 -19.13043 5.369221 89.79437 -19.13043 4.146322 88.75963 -13 6 85.9 -19.69691 0.6415332 87.24919 -19.6828 0.5092888 87.14342 -19.67176 0.3627617 87.06333 -19.66479 0.2092344 87.01422 -19.69416 0.05000001 87.00698 -19.95058 0.7053512 87.17869 -19.89788 0.6702207 87.21752 -19.98448 0.7473144 87.1323 -19.83212 0.6470296 87.24314 -19.76228 0.6379178 87.25321 -19.73622 0.358168 87.0746 -19.72886 0.2064711 87.02802 -19.72626 0.05000001 87.01216 -19.86733 0.05000001 86.98405 -19.81204 0.05000001 87.00547 -19.80711 0.3605412 87.06884 -19.87612 0.3709756 87.04335 -19.934 0.3886229 87.00023 -19.97424 0.4108422 86.94592 -19.99529 0.4343597 86.88842 -19.74775 0.504335 87.15117 -19.98327 0.05000001 86.8532 -19.91613 0.05000001 86.95011 -19.80907 9.285041 93.90612 -19.27273 9.971098 93.83267 -19.86641 8.885254 92.49893 -19.27273 9.958243 93.71873 -19.53332 9.606954 93.1261 -19.81723 8.220167 94.17555 -19.98016 8.324509 93.95165 -19.91739 8.26713 94.07478 -19.9762 5.756629 89.94793 -19.25066 6.611435 91.77548 -19.9762 6.865461 91.65544 -19.86395 6.6933 91.7368 -19.68056 6.581721 91.78952 -19.46189 6.552531 91.80332 -19.25066 2.317903 87.96451 -19.46189 2.297252 88.0263 -19.68056 2.307486 87.99568 -19.9762 2.406962 87.69803 -19.86395 2.346604 87.87863 -19.9762 4.233977 88.59641 -19.86395 5.612274 90.07211 -19.68056 5.518716 90.15259 -19.46189 5.49424 90.17365 -19.25066 5.543631 90.13116 -19.86395 4.127804 88.75448 -19.68056 4.058992 88.85693 -19.46189 4.040991 88.88374 -19.25066 4.077318 88.82965 -5.475 0.05588293 83.65315 -5.475 0.04999995 83.65311 -4.615526 0.04999995 84.91713 -2.510773 0.9564898 87.58248 -2.624387 0.9783393 87.56899 -3.532267 0.7110046 86.40734 -2.344216 0.7640079 87.3591 -2.423465 0.917934 87.54986 -2.362456 0.8573679 87.47795 -2.343827 0.7668761 87.36288 -3.402688 0.3692809 86.25859 -3.36831 0.04999995 86.21912 -2.389761 0.04999995 86.97061 -2.389174 0.1375815 86.97563 -2.381602 0.3685107 87.03882 -2.362021 0.6221893 87.20484 -5.475 0.2271351 83.68482 -4.656432 0.3692809 84.94979 -5.475 0.4156218 83.79087 -4.810616 0.7110046 85.07286 -5.475 0.6216115 84.00473 -5.056107 0.949814 85.26881 -5.475 0.8309162 84.37019 -2.225106 0.9937691 87.61257 -2.149889 0.8957426 87.49278 -2.084036 0.9553516 87.47009 -2.258557 0.7499325 87.37073 -2.218006 0.7514027 87.36952 -2.231433 0.8555395 87.49336 -2.074609 1.046477 87.49033 -2.135195 1.077025 87.57472 -2.16879 1.065692 87.6049 -2.231163 1.108734 87.66001 -2.716631 1.05721 87.64077 -2.334955 0.7612884 87.36135 -2.312886 0.8397367 87.47401 -2.364198 0.9069462 87.55621 -2.687785 1.001041 87.5836 -2.608525 0.9948791 87.61524 -2.513519 0.9771258 87.62329 -2.432861 0.9492103 87.60295 -2.679429 1.174489 87.71611 -2.456357 1.100602 87.73067 -2.537804 1.161122 87.74623 -2.608822 1.127835 87.72638 -2.734881 1.137104 87.68011 -2.329352 1.057567 87.6899 -2.318498 1.128814 87.70797 -2.453141 1.150737 87.74377 -2.043923 1.02401 87.42881 -2.048399 1.027787 87.4391 -2.001463 0.958072 87.25203 -2.002502 0.915212 87.23416 -2.023588 1.003122 87.37234 -2.015163 0.8763912 87.26624 -2.028132 0.8536854 87.28501 -2.05919 0.8179988 87.31449 -2.089772 0.7945907 87.33383 -2.107336 0.7842686 87.34236 -2.291294 1.1232 87.69542 -2.612392 1.04948 87.68048 -2.486905 1.026922 87.68707 -2.38186 0.9913363 87.65655 -2.294731 0.9381936 87.5944 -2.345664 8.780303 94.84611 -2.409796 8.825829 95.03335 -2.218741 8.61693 94.484 -2.166356 8.491841 94.31935 -2.091864 8.563808 94.25151 -2.28094 8.712232 94.66299 -2.248455 9.4507 94.86997 -2.211697 9.363243 94.90268 -2.155215 9.248688 94.48962 -2.192573 9.226062 94.9476 -2.075256 9.001721 94.20187 -2.075913 9.004234 94.20426 -2.071796 8.989221 94.21267 -2.112394 9.115652 94.45644 -2.11013 9.009678 94.52043 -2.02466 8.732233 94.07418 -2.028589 8.778544 94.02308 -2.061818 8.947532 94.15267 -2.020514 8.355715 93.96927 -2.00104 8.487301 93.86834 -2.042609 8.646467 94.1673 -2.08393 8.295081 94.09049 -2.184613 8.245558 94.18949 -2.217399 9.081138 94.98759 -2.193547 8.97072 94.79188 -2.258606 8.865866 94.82538 -2.285777 8.948119 95.01672 -2.385967 8.843555 95.03191 -2.198536 8.798075 94.62876 -2.139284 8.9003 94.57989 -4.206422 11.04076 93.92588 -17.75263 10.97421 96.62297 -4.24737 10.97421 96.62297 -2.727273 9.971097 93.83267 -2.727273 9.958243 93.71873 -2.879335 10.12188 94.12384 -3.2 10.4 94.9 -2.31204 9.55513 95.13549 -2.362194 9.567469 95.59197 -2.343027 9.430231 95.6367 -2.366819 9.28393 95.67203 -2.433249 9.148318 95.69239 -2.530889 9.04036 95.69611 -3.958427 10.81338 91.37368 -4.038463 10.84173 91.03101 -4.088079 10.85833 90.98857 -5.27045 11.14794 90.014 -4.057839 10.84822 90.94868 -4.520786 10.96148 89.04126 -18.0251 10.81943 51.10099 -18.7283 10.45214 51.59337 -19.10929 10.13329 51.86014 -19.712 9.282606 52.28216 -2.30896 0.1338604 87.01071 -2.305306 0.04999995 87.0071 -2.186732 0.04999995 87.00515 -2.278067 0.6062481 87.22402 -2.18912 0.6100675 87.21945 -2.105304 0.6347926 87.1898 -2.042707 0.6758547 87.14052 -2.219965 0.133305 87.01591 -2.132649 0.04999995 86.98404 -2.131968 0.1362346 86.98825 -2.082394 0.04999995 86.94879 -2.061827 0.1421158 86.93276 -2.015771 0.04999995 86.85068 -2.014843 0.1505244 86.85343 -2.127379 0.2965917 87.01881 -2.214793 0.2878236 87.04712 -2.303895 0.2888016 87.04389 -2.010245 0.5176127 86.95185 -2.052461 0.4793457 87.02481 -2.119206 0.4515573 87.0778 -2.205421 0.4362587 87.10697 -2.294579 0.4362582 87.10697 -2.136055 2.346608 87.87863 -2.023802 4.233979 88.59642 -2.319437 6.581723 91.78952 -2.538107 6.552531 91.80332 -2.74933 6.611432 91.77548 -2.136055 6.693301 91.7368 -2.023802 6.86546 91.65544 -2.023802 5.756629 89.94793 -2.023802 2.406965 87.69803 -2.319437 2.30749 87.99568 -2.538107 2.297255 88.02631 -2.74933 2.317905 87.96452 -2.136055 4.127807 88.75448 -2.319437 4.058996 88.85693 -2.538107 4.040993 88.88374 -2.74933 4.077318 88.82965 -2.136055 5.612276 90.07211 -2.319437 5.518718 90.15259 -2.538107 5.494241 90.17365 -2.74933 5.543629 90.13117 -2.01984 8.32453 93.95166 -2.082609 8.267148 94.07478 -2.182764 8.220183 94.17555 -2.380771 9.462752 92.96124 -2.190932 9.285041 93.90611 -2.191529 9.054746 92.61192 -2.080366 8.689736 92.38454 -19.85951 -7.889184 87.50154 -19.90732 -7.923341 87.44403 -18.22959 -7.938191 85.75965 -16.94695 -7.971325 84.75282 -16.26334 -7.987675 84.29141 -16.17951 -7.938191 84.46038 -18.44431 -8 85.48818 -17.63148 -7.999892 84.89883 -19.97546 -7.969582 87.30877 -19.81019 -7.851704 87.54618 -18.00565 -7.707107 86.04278 -19.6591 -7.721494 87.62805 -16.73993 -7 85.51634 -17.82395 -7 86.27251 -17.86229 -7.346117 86.22402 -19.13043 -7 87.49082 -19.13287 -7.005202 87.49346 -19.24551 -7.213155 87.58443 -19.32978 -7.341098 87.62417 -19.45425 -7.503365 87.65193 -15.88889 -7 85.04614 -15.91636 -7.346117 84.99076 -16.01906 -7.707107 84.78376 -16.04746 -7.999783 84.02655 -15.18097 -8 83.84321 -15.16009 -7.938191 84.18869 -14 -8 84.00932 -15.13831 -7.707107 84.54902 -15.12437 -7.346117 84.77969 -14.33333 -7 84.95212 -14.90547 -7 84.83998 -15.12064 -7 84.84139 -14.16667 -7.866025 84.48072 -14.2357 -7.707107 84.67598 -14.28868 -7.5 84.82582 -14.31273 -7.346117 84.89385 -13.91234 -7.868884 84.6684 -13.99894 -7.523157 84.97611 -13.00001 -8.996537 86.82926 -13.01135 -8.835378 86.56856 -13.00767 -8.876387 86.53476 -13.16136 -8.400229 85.83827 -13.11096 -8.542173 85.70538 -13.00001 -8.994227 86.83114 -13.01023 -8.752775 86.63575 -13.0122 -8.794136 86.60225 -13.14795 -8.084345 86.08283 -13.17386 -8.245539 85.96581 -13.21465 -7.911786 85.93635 -13.25025 -8.108119 85.80148 -13.25049 -7.83306 85.86862 -13.56773 -7.745383 85.34075 -13.13376 -8.50037 85.59937 -13.23201 -8.293065 85.64828 -13.16098 -8.455893 85.48565 -13.52361 -8.018767 85.10897 -13.37987 -8.215502 84.84244 -13.57379 -7.988337 85.03896 -13.42009 -8.185317 84.75563 -13.50649 -7.431004 85.50754 -13.56013 -7.370632 85.44966 -13.62279 -7.703214 85.28186 -13.91347 -7.10175 85.15863 -13.95675 -7.53484 85.00346 -13.96242 -7.078943 85.12794 -13 -9 86.83775 -13.87479 -7.875457 84.70216 -13.49424 -8.137325 84.61203 -13.6851 -8.050876 84.31906 -13.72182 -8.039472 84.27304 -2.867133 -7.005202 87.49346 -2.869565 -7 87.49082 -4.186796 -7 86.26402 -4.005383 -7.707107 86.03407 -2.545746 -7.503365 87.65193 -4.139648 -7.382683 86.20426 -2.643575 -7.378187 87.63298 -2.749197 -7.221737 87.58751 -2.092683 -7.923341 87.44403 -2.138914 -7.890347 87.4999 -3.804441 -7.92388 85.77937 -2.18981 -7.851704 87.54618 -2.340899 -7.721494 87.62805 -2.024547 -7.969582 87.30877 -3.567414 -8 85.47892 -6.062705 -7.453886 84.94854 -5.260067 -7 85.51634 -6.111122 -7 85.04613 -7.080421 -7.453886 84.73034 -7.711325 -7.5 84.82582 -7.804008 -7.808878 84.56366 -7.833333 -7.866025 84.48072 -7.076267 -7 84.83921 -7.666666 -7 84.95212 -7.70298 -7.453886 84.84941 -8.432268 -7.745383 85.34075 -8.476394 -8.018767 85.10897 -8.426215 -7.988337 85.03896 -8.278182 -8.039472 84.27304 -8.999995 -8.996537 86.82926 -8.992331 -8.876387 86.53476 -8.988652 -8.835378 86.56856 -8.889041 -8.542173 85.70538 -8.838638 -8.400229 85.83827 -8.839016 -8.455893 85.48565 -8.767989 -8.293065 85.64828 -9 -9 86.83775 -8.999991 -8.994227 86.83114 -8.987799 -8.794136 86.60225 -8.826141 -8.245539 85.96581 -8.749749 -8.108119 85.80148 -8.852055 -8.084345 86.08283 -8.989774 -8.752775 86.63575 -8.493509 -7.431004 85.50754 -8.746675 -7.827156 85.86351 -8.785354 -7.911786 85.93635 -8.087663 -7.868884 84.6684 -8.125206 -7.875457 84.70216 -8.314901 -8.050876 84.31906 -8.579906 -8.185317 84.75563 -8.620131 -8.215502 84.84244 -8.377206 -7.703214 85.28186 -8.043251 -7.53484 85.00346 -8.001062 -7.523157 84.97611 -8.439874 -7.370632 85.44966 -8.086535 -7.10175 85.15863 -8.037576 -7.078943 85.12794 -14 -8 83.87409 -13.5 -8.133975 83.87409 -13.13397 -8.5 83.87409 -13 -9 83.87409 -12.41355 -9.927686 84.9 -12.72175 -9.721752 84.9 -12.92769 -9.41355 84.9 -13 -9.050001 84.9 -12.05012 -10 86.29098 -12.1468 -9.99507 86.3143 -12.72211 -9.721395 86.46943 -12.88569 -9.501788 86.54115 -12.9425 -9.375482 86.58329 -12.9948 -9.149256 86.68246 -13 -9.050001 86.767 -12.37877 -9.941298 86.3712 -12.58134 -9.837512 86.42524 -9.475001 -9.872725 84.9 -9.278249 -9.721752 84.9 -9.127277 -9.525001 84.9 -9 -9.050001 84.9 -9 -9.050001 86.767 -9.000076 -9.061986 86.75175 -9.013349 -9.208695 86.65068 -9.949854 -10 86.29071 -9.502872 -9.888198 86.40189 -9.057771 -9.376236 86.58302 -9.149375 -9.561365 86.52208 -9.277941 -9.721445 86.46942 -11 -3.15 93.67501 -11 -3.3 93.525 -11.6875 -3.3 93.70922 -11.6125 -3.15 93.83912 -12.19079 -3.3 94.2125 -12.06088 -3.15 94.2875 -12.375 -3.3 94.9 -12.225 -3.15 94.9 -12.19079 -3.3 95.5875 -12.06088 -3.15 95.5125 -11.6875 -3.3 96.09078 -11.6125 -3.15 95.96089 -11 -3.3 96.275 -11 -3.15 96.125 -10.3125 -3.3 96.09078 -10.3875 -3.15 95.96089 -9.809215 -3.3 95.5875 -9.93912 -3.15 95.5125 -9.625 -3.3 94.9 -9.775 -3.15 94.9 -9.809215 -3.3 94.2125 -9.93912 -3.15 94.2875 -10.3125 -3.3 93.70922 -10.3875 -3.15 93.83912 -19.69416 -0.04999995 87.00698 -19.61025 -0.04999995 86.97061 -19.81204 -0.04999995 87.00547 -19.91613 -0.04999995 86.95011 -19.98327 -0.04999995 86.8532 -2.389759 -0.05000019 86.97061 -2.015771 -0.04999995 86.85068 -2.082394 -0.04999995 86.94879 -2.186732 -0.04999995 87.00515 -2.305306 -0.04999995 87.0071 -2.031507 -0.8029307 87.23643 -2.02031 -0.8196772 87.22098 -2.024393 -0.4667882 86.96759 -2.13233 -0.1071043 86.98588 -2.20233 -0.1053687 87.01067 -2.004144 -0.4937537 86.91133 -2.030255 -0.1141927 86.88474 -2.121119 -0.420747 87.06363 -2.063865 -0.4412043 87.02095 -2.072719 -0.1102021 86.94168 -2.273379 -0.1051263 87.01416 -2.389512 -0.1080283 86.9728 -2.33331 -0.2617524 87.0273 -2.385969 -0.2684867 87.00229 -2.379591 -0.4048455 87.05573 -2.269135 -0.2582363 87.04039 -2.325129 -0.4102752 87.08547 -2.374776 -0.4780363 87.09632 -2.043897 -0.7882291 87.24999 -2.293771 -0.7113268 87.32093 -2.236277 -0.7087639 87.32328 -2.245995 -0.5660954 87.19412 -2.158977 -0.7210968 87.31191 -2.175753 -0.5728724 87.18514 -2.118627 -0.7358992 87.29826 -2.094576 -0.7483089 87.28681 -2.06242 -0.770759 87.2661 -2.349915 -0.7238042 87.30941 -2.311139 -0.5706378 87.18807 -2.260531 -0.4053757 87.0957 -2.189751 -0.4084649 87.08926 -2.857835 -1.176678 87.50325 -2.869565 -1.175788 87.49082 -2.660127 -1.175127 87.6277 -2.535047 -1.163131 87.65281 -2.5652 -1.166705 87.64977 -2.65131 -1.174527 87.63059 -2.318542 -1.122748 87.61994 -2.344547 -1.129236 87.62926 -2.429427 -1.147002 87.64904 -2.389869 -1.139326 87.64176 -2.159305 -1.067137 87.52 -2.206061 -1.087089 87.5585 -2.228753 -1.095482 87.57406 -2.305349 -1.119242 87.61459 -2.050904 -0.9957025 87.37384 -2.10148 -1.035329 87.456 -2.109177 -1.040176 87.4659 -2.137076 -1.056047 87.49797 -2.019291 -0.9564232 87.29158 -19.77545 -1.093937 87.57132 -19.8612 -1.056906 87.49977 -19.92434 -1.017191 87.41849 -19.97445 -0.9660782 87.31183 -19.99893 -0.9075111 87.18676 -19.46 -1.163745 87.65243 -19.55209 -1.150172 87.65131 -19.61222 -1.138796 87.64128 -19.67804 -1.123616 87.62126 -19.68602 -1.121546 87.61814 -19.76954 -1.096047 87.57517 -19.32238 -1.176285 87.62142 -19.13051 -1.175788 87.49076 -19.79768 -0.1053122 87.01065 -19.72664 -0.1050692 87.01414 -19.62137 -0.4205834 87.06372 -19.61636 -0.3264159 87.02165 -19.6667 -0.2616652 87.02728 -19.61404 -0.2684018 87.00227 -19.6105 -0.1079662 86.9728 -19.67488 -0.4101784 87.08544 -19.68888 -0.570613 87.18806 -19.65008 -0.7237922 87.30943 -19.72861 -0.7091577 87.32292 -19.87887 -0.4206516 87.06359 -19.81024 -0.4083731 87.08922 -19.90542 -0.7483041 87.28682 -19.89471 -0.7423923 87.29227 -19.82426 -0.572845 87.18511 -19.83883 -0.7204724 87.31249 -19.99585 -0.4936304 86.91131 -19.96975 -0.1141268 86.88474 -19.92728 -0.1101409 86.94167 -19.86768 -0.1070464 86.98587 -19.73087 -0.2581462 87.04036 -19.73947 -0.4052832 87.09565 -19.75402 -0.5660703 87.19409 -19.78347 -0.7101369 87.32202 -19.941 -0.7736669 87.26343 -19.93612 -0.4411011 87.02092 -19.97154 -0.8070735 87.23262 -19.97559 -0.466675 86.96756 -2.847061 -1.077446 87.4852 -2.803505 -1.144767 87.54843 -2.733125 -1.144155 87.59368 -2.371187 -0.8208937 87.41684 -2.241417 -0.7784787 87.39725 -2.120993 -0.8272652 87.38573 -2.179469 -0.7969099 87.39762 -2.072468 -0.8669204 87.36216 -2.17911 -1.033609 87.53378 -2.1761 -0.9360741 87.49765 -2.219182 -0.9809741 87.54408 -2.655102 -1.1383 87.62658 -2.238288 -1.078126 87.57921 -2.338598 -1.05703 87.6178 -2.412266 -1.086584 87.64007 -2.491264 -1.109761 87.64963 -2.038338 -0.9113526 87.32994 -2.06299 -0.9747087 87.39406 -2.141843 -0.8828273 87.44258 -2.22851 -0.8944233 87.49845 -2.316578 -0.9710536 87.57553 -2.274193 -1.021948 87.5853 -2.440276 -1.028537 87.62195 -2.584584 -1.064446 87.62406 -2.573581 -1.126974 87.6453 -2.284071 -0.8638052 87.48609 -2.378203 -0.8314024 87.42771 -2.360783 -0.9303699 87.5517 -2.455474 -0.8965955 87.48725 -2.467657 -0.9800114 87.5892 -2.508262 -0.920289 87.50044 -2.591682 -1.011003 87.5884 -2.610793 -0.9461196 87.49167 -2.714707 -1.024252 87.54575 -2.721774 -0.9527381 87.43393 -2.727608 -1.079749 87.57626 -2.818311 -1.021989 87.46739 -2.745924 -0.9506341 87.41223 -2.80619 -1.005102 87.45891 -19.14797 -1.090845 87.4877 -19.1618 -1.057169 87.4802 -19.28217 -1.040775 87.55757 -19.86338 -0.8135201 87.3868 -19.97324 -0.9276655 87.30904 -19.76279 -1.083187 87.57891 -19.69543 -0.7694419 87.38236 -19.63344 -0.8128817 87.40848 -19.30627 -0.9787024 87.50413 -19.36842 -0.9490539 87.48503 -19.40673 -0.9673613 87.54013 -19.48419 -0.9229715 87.50121 -19.50736 -0.9414625 87.54298 -19.57387 -0.8780741 87.47243 -19.59363 -0.9008815 87.51531 -19.65768 -0.8459314 87.46279 -19.25408 -0.9506376 87.41223 -19.20631 -0.9902547 87.44976 -19.19381 -1.005101 87.4589 -19.13918 -1.120725 87.49118 -19.26968 -1.124545 87.59114 -19.42525 -1.107466 87.64112 -19.58124 -1.068112 87.63593 -19.71257 -1.006661 87.58473 -19.86851 -0.9911025 87.48374 -19.93179 -0.8661974 87.35578 -19.80757 -0.9248337 87.50144 -19.41219 -1.026518 87.60144 -19.54229 -0.9937679 87.60063 -19.65233 -0.942568 87.56118 -19.73243 -0.8739933 87.4931 -19.77915 -0.7799501 87.3954 -17.71803 -0.935837 86.08109 -17.73882 -0.9092849 86.05027 -18.48525 -0.8854146 86.6864 -18.87049 -1.067318 87.20212 -18.90943 -0.9775598 87.17549 -17.25678 -1.177315 85.85275 -16.86684 -1.216041 85.59458 -16.86662 -1.166575 85.58477 -16.86808 -1.231151 85.59593 -16.5948 -1.264313 85.42909 -16.0027 -1.254509 85.09873 -16.00783 -1.213471 85.08869 -16.0008 -1.3 85.10245 -18.03891 -1.096133 86.44697 -17.6779 -1.124149 86.15897 -17.6774 -1.112192 86.15823 -18.40973 -1.043631 86.76305 -16.11446 -1.05 84.87978 -16.93816 -0.9951457 85.43614 -16.09378 -1.054174 84.9203 -16.91744 -1.0131 85.47268 -16.07512 -1.065452 84.95685 -16.89855 -1.040076 85.50817 -16.05227 -1.090751 85.00164 -16.88298 -1.075791 85.54019 -16.03409 -1.123223 85.03723 -16.87206 -1.118793 85.56634 -16.01933 -1.163198 85.06616 -18.43867 -0.9505965 86.73496 -17.70008 -0.9708256 86.10933 -18.96439 -0.9173031 87.1294 -17.67878 -1.061449 86.14953 -17.68657 -1.013366 86.13281 -5.887493 -1.064437 84.97338 -5.92385 -1.064631 84.95484 -5.927376 -1.067553 84.96174 -5.417335 -1.265658 85.42192 -5.997298 -1.254509 85.09873 -5.999196 -1.3 85.10245 -3.493458 -1.099363 86.85938 -4.322661 -1.112204 86.15818 -4.628198 -1.161583 85.93339 -5.133406 -1.166574 85.58475 -5.131862 -1.23122 85.59597 -4.861361 -1.193938 85.77218 -5.061864 -0.9951477 85.43611 -5.446044 -1.031719 85.16678 -5.082584 -1.013101 85.47266 -5.700592 -1.056442 85.06303 -5.101476 -1.040076 85.50815 -5.990623 -1.204749 85.08566 -5.980669 -1.163197 85.06616 -5.961106 -1.11326 85.02783 -5.117045 -1.075791 85.54017 -5.127969 -1.118792 85.56632 -4.299978 -0.9708371 86.10929 -4.313496 -1.013377 86.13275 -4.321282 -1.061461 86.14949 -4.052699 -0.8942893 86.22168 -4.282028 -0.9358491 86.08103 -7.963693 -1.204749 84.30773 -7.96889 -1.3 84.32586 -6.374783 -1.065044 84.73854 -7.924438 -1.066206 84.1708 -7.945802 -1.11326 84.24533 -7.959665 -1.175031 84.29369 -8.757117 -0.6284799 83.96778 -8.866845 -0.4207266 83.94599 -8.890417 -0.4276567 83.97998 -8.689268 -1.059956 84.14544 -8.161063 -1.284456 84.27266 -8.288581 -1.19644 84.23251 -8.667265 -0.9853018 84.13934 -8.80631 -0.8508683 84.1089 -9.01733 -0.6927235 84.08016 -9.031214 -0.4771553 84.06405 -9.074315 -0.58349 84.06987 -9.098063 -0.04999995 84.0477 -9.191105 -0.04999995 84.04972 -8.998476 -0.04999995 84.002 -8.929008 -0.1710672 83.93417 -8.936205 -0.04999983 83.93283 -8.391421 -0.9523758 84.04863 -8.228437 -1.058508 84.15067 -8.205227 -1.026793 84.09477 -8.258656 -1.117648 84.2033 -8.404945 -0.9825189 84.09937 -8.61226 -0.9216458 84.1097 -8.565498 -0.8753709 84.05629 -8.742176 -0.7965068 84.07912 -8.689585 -0.7573415 84.02544 -8.952341 -0.4482534 84.03404 -9.098063 0 84.0477 -9.191111 0 84.04975 -8.93625 0 83.93281 -8.998476 0 84.002 -14.1 -1.049952 84.08554 -14.07616 -1.065452 84.16873 -14.05129 -1.123223 84.25548 -14.04086 -1.171794 84.29186 -14.03537 -1.213471 84.31101 -14.03111 -1.3 84.32586 -14.18311 -5.1 84.40724 -14.27402 -5.307336 84.67774 -13.40746 -5.307336 85.20788 -14.90547 -6 84.83998 -14.36283 -6 84.94196 -14.34301 -5.652791 84.88299 -12.93779 -5.652791 86.83775 -13.06098 -5.652791 86.13565 -13 -6 86.83775 -13.11948 -6 86.15683 -13.55878 -5.652791 85.36275 -13.94591 -6 85.13807 -13.60226 -6 85.40725 -13.2524 -6 85.86517 -15.2578 -5.652791 84.79171 -15.25003 -6 84.85343 -15.88889 -6 85.04614 -15.38817 -5.654841 84.81317 -15.25646 -5.571221 84.7569 -14.80927 -5.321292 84.5802 -13.20802 -5.1 85.00377 -12.85739 -5.307336 86.06193 -12.58907 -5.1 85.96478 -12.72126 -5.307336 86.83775 -12.43589 -5.1 86.83775 -14.2414 -5.1 84.38842 -7.816891 -5.1 84.40724 -7.758602 -5.1 84.38842 -8.998311 -5.1 84.08366 -10.21154 -5.1 93.06198 -9.56411 -5.1 93.50781 -9.56411 -5.1 86.83775 -12.43589 -5.1 93.50781 -11.78846 -5.1 93.06198 -13.00169 -5.1 84.08366 -11 -5.1 92.9 -9.410932 -5.1 85.96478 -8.79198 -5.1 85.00377 -6.111111 -6 85.04614 -6.594362 -5.66539 84.82048 -6.742197 -5.652791 84.79171 -7.637173 -6 84.94196 -7.076267 -6 84.83921 -6.749975 -6 84.85343 -8.441219 -5.652791 85.36275 -8.397741 -6 85.40725 -8.043715 -6 85.13169 -7.656993 -5.652791 84.88299 -8.744625 -6 85.85985 -8.939017 -5.652791 86.13565 -8.880521 -6 86.15683 -9.062212 -5.652791 86.83775 -9 -6 86.83775 -9.27874 -5.307336 86.83775 -7.725975 -5.307336 84.67774 -7.219474 -5.30759 84.56984 -7.225537 -5.304682 84.56762 -9.142609 -5.307336 86.06193 -8.592543 -5.307336 85.20788 -6.747278 -5.568563 84.75517 -13 -6 93.86019 -13 -6.227223 93.90001 -13 -9 93.9 -9.664994 -5.057784 93.79937 -10.00016 -5 93.16767 -9 -6 93.86019 -9.035009 -5.737719 93.9 -8.999623 -6 93.89997 -9.266635 -5.320165 93.9 -9.633976 -5.0694 93.9 -12.00001 -5 93.16774 -11.78846 -4.999992 93.06198 -11 -4.999992 92.9 -10.21154 -4.999992 93.06198 -13.00038 -6 93.89998 -12.90109 -5.566365 93.9 -12.70374 -5.28954 93.9 -12.59729 -5.197976 93.9 -12.36602 -5.069402 93.9 -13.05841 -6.110831 94.22512 -13.05617 -6 94.199 -13.01496 -6 94.03699 -12.77871 -7.321883 94.81444 -12.88865 -7.128067 94.55799 -12.86701 -9 94.61714 -12.94577 -6.962121 94.36259 -12.95024 -6.947753 94.34338 -12.96566 -6.869681 94.26905 -12.9808 -6.76355 94.17649 -12.99604 -6.538232 94.02583 -12.99975 -6.330717 93.93131 -12.48571 -9 95.2389 -12.48572 -7.584464 95.2389 -12.64813 -7.459646 95.03299 -12 -10 86.83775 -12 -10 93.9 -12.34116 -9.940007 86.83775 -12.5 -9.866025 93.9 -12.99122 -9.132231 93.9 -12.93996 -9.341276 86.83775 -12.86603 -9.5 93.9 -12.86603 -9.5 86.83775 -12.82206 -9.569395 93.9 -12.70706 -9.707152 86.83775 -12.5 -9.866025 86.83775 -8.94383 -6 94.199 -8.941594 -6.110832 94.22512 -9 -6.227205 93.9 -9.009968 -5.900344 94.04128 -9.004933 -6 94.04039 -9.381388 -5.218513 94.0312 -9.179525 -5.436984 94.04756 -9.050041 -5.705057 94.04818 -9.110857 -5.555395 94.05845 -9.182226 -5.435908 94.0705 -9.412111 -5.201189 94.10909 -9.568378 -5.107371 94.13506 -9.864669 -5 93.56896 -9.767623 -5.000014 93.99291 -11.6875 -5 93.70922 -11 -5 93.525 -10.3125 -5 93.70922 -9.809215 -5 94.2125 -9.742844 -5 94.34306 -12.13529 -5 93.56899 -12.19079 -5 94.2125 -12.23237 -5.000012 93.99292 -12.25715 -5 94.34306 -12.61861 -5.218513 94.03119 -12.43165 -5.107384 94.13504 -12.99507 -6 94.04039 -12.98762 -5.878861 94.0417 -12.82048 -5.436984 94.04756 -12.94141 -5.679071 94.04963 -12.81893 -5.437565 94.07031 -12.51115 -5.150352 94.12187 -9 -9 93.9 -9.060028 -9.34125 93.9 -9.060039 -9.34128 86.83775 -9.073438 -9.376144 93.9 -9.292894 -9.707108 93.9 -9.292946 -9.707159 86.83775 -9.658753 -9.939973 93.9 -9.658861 -9.940012 86.83775 -10 -10 93.9 -10 -10 86.83775 -9.514289 -7.58443 95.2389 -9.514286 -9 95.2389 -9.362173 -7.469259 95.04784 -9.132994 -9 94.61714 -9.219943 -7.317301 94.8118 -8.999994 -6.301752 93.91022 -9.00184 -6.47411 93.98577 -9.020251 -6.770859 94.18389 -9.028329 -6.831212 94.23543 -9.041526 -6.906963 94.30543 -9.110547 -7.138579 94.55567 -8.935606 -6.356179 94.47943 -8.9405 -6.405199 94.56475 -9.029179 -6.67067 94.35309 -9.030148 -6.813028 94.2475 -8.935996 -6.22993 94.31398 -9.00235 -6.434971 94.03704 -9.122505 -6.983185 94.63064 -9.113749 -6.869753 94.69171 -9.066353 -6.690876 94.80213 -8.993953 -6.55226 94.9 -8.934358 -6.323883 94.42983 -11.70453 -9.75 94.12145 -11.79792 -9.75 94.21751 -11.80981 -9.837027 94.20734 -10.01209 -9.999927 94.055 -10.07654 -9.985174 94.11013 -10.4445 -9.985174 93.81922 -10.45618 -10 93.71924 -11 -9.985174 93.68482 -11 -10 93.60003 -11.5555 -9.985174 93.81922 -11.54382 -10 93.71924 -11.92346 -9.985174 94.11013 -11.98789 -9.999983 94.05502 -11.47999 -9.75 93.96614 -11.48714 -9.837027 93.95223 -11.24846 -9.75 93.87982 -11 -9.837027 93.83436 -11 -9.75 93.85 -10.73235 -9.75 93.88468 -10.51286 -9.837027 93.95223 -10.52001 -9.75 93.96614 -10.28092 -9.75 94.13488 -10.19019 -9.837027 94.20734 -10.20211 -9.75 94.21754 -10.14579 -9.927609 94.16936 -10.48616 -9.927609 93.90026 -11 -9.927609 93.77594 -11.51384 -9.927609 93.90026 -11.85421 -9.927609 94.16936 -12.89382 -6.825238 94.71823 -12.878 -6.964532 94.63985 -12.99974 -6.319462 93.95272 -12.99573 -6.480894 94.08923 -12.97992 -6.627499 94.28666 -13.00605 -6.552258 94.9 -13.06326 -6.372003 94.50564 -13.06073 -6.16162 94.25527 -13.06517 -6.262164 94.34905 -13.0656 -6.326043 94.43299 -13.06464 -6.351727 94.47229 -12.40307 -7.772179 95.2993 -12.42612 -9 95.28739 -12.37535 -9 95.30992 -12.32246 -7.953423 95.32053 -12.32119 -7.956234 95.32064 -12.21945 -8.178977 95.30821 -12.22381 -8.169442 95.30964 -12.21205 -9 95.30555 -12.32113 -9 95.32064 -12.05681 -8.529528 95.12952 -12.08998 -8.455853 95.20715 -12.12003 -9 95.24507 -12.1223 -8.386798 95.24739 -12.1256 -8.379746 95.25066 -12.16791 -8.289469 95.28379 -12.06293 -9 95.1509 -12.05 -9 95.07154 -12.05 -8.549263 95.07154 -12.46912 -9.5211 95.0301 -12.48409 -9.174027 95.21783 -12.85881 -9.132231 94.61399 -12.46458 -9.570299 94.98289 -12.28691 -9.920287 94.42861 -12.34309 -9.872871 94.5404 -12.36628 -9.886041 94.42481 -12.40438 -9.787303 94.70063 -12.40912 -9.778019 94.71581 -12.44815 -9.6671 94.87353 -12.45156 -9.651947 94.89221 -12.7009 -9.569395 94.55334 -12.034 -9.998608 94.09786 -12.23159 -9.951728 94.33737 -12.25907 -9.937585 94.38081 -12.91868 -6.642837 95.17571 -12.791 -6.917225 94.99237 -12.77148 -7.018667 94.93914 -12.64661 -7.052024 95.19787 -12.47472 -7.171008 95.38873 -12.78337 -6.738239 95.40651 -12.71323 -6.777135 95.50449 -12.60377 -6.82827 95.63745 -9.723165 -5.020742 94.38979 -9.624165 -5.079031 94.16043 -9.672272 -5.051606 94.22497 -12.27683 -5.020742 94.38979 -12.33569 -5.056387 94.2099 -12.39288 -5.088003 94.14871 -9.18903 -9.34125 94.59562 -9.406411 -9.707108 94.51212 -9.624793 -9.834509 94.61721 -9.748396 -9.941665 94.3689 -9.768353 -9.951685 94.3376 -9.913163 -9.993285 94.15214 -9.779525 -9.956727 94.32082 -9.521567 -9.355033 95.14816 -9.530773 -9.521179 95.03018 -9.560896 -9.702023 94.82761 -9.563953 -9.711852 94.81417 -9.95 -8.549271 95.07154 -9.95 -9 95.07154 -9.949685 -8.547314 95.0841 -9.937224 -9 95.15044 -9.940261 -8.522743 95.14064 -9.925824 -8.490302 95.1788 -9.880765 -9 95.24423 -9.895365 -8.42458 95.22753 -9.846343 -8.319835 95.27423 -9.789643 -9 95.30491 -9.794734 -8.209673 95.3029 -9.681329 -9 95.32084 -9.739457 -8.089064 95.31841 -9.781311 -8.180674 95.30795 -9.582988 -7.741687 95.29246 -9.608368 -7.798947 95.30414 -9.576596 -9 95.28896 -9.650449 -7.893075 95.31658 -9.704585 -8.012877 95.3215 -9.568734 -7.709235 95.2843 -9.372194 -7.257876 95.1011 -9.217406 -6.955661 94.97019 -9.353775 -7.053874 95.1969 -9.222201 -6.741575 95.4146 -9.396202 -6.828299 95.63746 -9.081349 -6.642857 95.17577 -9.537413 -7.379713 95.29716 -9.530934 -7.213155 95.36735 -9.52557 -7.172865 95.38775 -9.95 -8.550001 94.9 -9.950299 -8.525 94.875 -10.00147 -8.824703 94.57533 -12.04615 -9.4864 94.81023 -11.96707 -9.689511 94.49103 -11.99217 -8.843651 94.55625 -12.0497 -8.525 94.875 -12.05 -8.550001 94.9 -12.05 -9.390825 94.9 -11.2533 -9.51899 93.88156 -11.51967 -9.412385 93.98764 -11.71255 -9.27122 94.12892 -11.89208 -9.053791 94.34642 -11.91012 -9.023629 94.37659 -10.27412 -9.258679 94.14145 -10.45664 -9.398475 94.0016 -10.72922 -9.514483 93.88589 -10.80579 -9.531883 93.86824 -10.99958 -9.55 93.84976 -11.11767 -9.543387 93.85675 -10.1519 -9.746126 94.28113 -10.11279 -9.061576 94.33866 -9.996387 -9.641942 94.59137 -10.08966 -9.023241 94.37699 -9.950036 -9.390825 94.9 -9.847243 -9.954818 94.37821 -9.63233 -9.705039 94.89299 -9.557996 -9.677424 94.86559 -9.95397 -9.676257 94.69644 -9.941979 -9.435276 94.94439 -9.828946 -9.79571 94.72914 -9.861239 -9.526015 95.03501 -9.901073 -9.74638 94.72039 -9.913665 -9.482668 94.99172 -9.934941 -9.451295 94.96039 -9.559597 -9.537191 95.04617 -9.624649 -9.559496 95.06844 -9.648146 -9.563876 95.07281 -9.640706 -9.706657 94.89503 -9.704122 -9.567699 95.07663 -9.727988 -9.709021 94.90605 -9.735906 -9.56589 95.07482 -9.787714 -9.556478 95.06543 -9.649998 -9.816774 94.69847 -9.658119 -9.818538 94.70127 -9.743506 -9.821117 94.72244 -9.820487 -9.545824 95.05479 -10.04152 -9.796837 94.4354 -9.992321 -9.873312 94.43048 -9.925744 -9.92711 94.41078 -12.36126 -9.699225 94.90526 -12.34706 -9.806904 94.72328 -12.27286 -9.811209 94.7417 -12.05802 -9.435276 94.94439 -12.1845 -9.943811 94.41733 -12.31203 -9.882285 94.55451 -12.42481 -9.67939 94.88465 -12.21229 -9.556477 95.06543 -12.27746 -9.567003 95.07595 -11.8543 -9.874311 94.23313 -11.83211 -9.809807 94.24735 -11.96475 -9.76208 94.46656 -12.03944 -9.64456 94.70318 -12.07142 -9.701764 94.72686 -11.99555 -9.82446 94.47052 -12.12431 -9.754546 94.74363 -12.04564 -9.882019 94.46404 -12.19465 -9.793406 94.74916 -12.11163 -9.924396 94.44567 -12.00949 -9.997722 94.11711 -11.94772 -9.977646 94.16477 -11.89357 -9.933827 94.20522 -12.4404 -9.537191 95.04617 -12.37535 -9.559496 95.06844 -12.35388 -9.563566 95.0725 -12.29588 -9.567699 95.07663 -12.13876 -9.526015 95.03501 -12.08633 -9.482668 94.99172 -12.05 -8.550001 95 -12.05 -9.183609 95.03717 -12.05 -9.3482 94.93914 -12.13876 -9.471044 95.08547 -12.21229 -9.498726 95.11843 -12.4404 -9.257676 95.2303 -12.4404 -9.481201 95.09756 -12.37535 -9.501469 95.12171 -12.29588 -9.508922 95.13058 -12.37535 -9.268963 95.25973 -12.29588 -9.273114 95.27056 -12.21229 -9.267436 95.25575 -12.13876 -9.25202 95.21555 -12.08633 -9.431657 95.03855 -12.05802 -9.388591 94.98725 -12.08633 -9.230085 95.15835 -12.05802 -9.206103 95.09582 -9.913665 -9.264457 95.14406 -9.559597 -9.295998 95.21437 -9.559597 -9.048569 95.27672 -9.624649 -9.050728 95.30817 -9.624649 -9.308901 95.24314 -9.704122 -9.313645 95.2537 -9.704122 -9.051522 95.31974 -9.787714 -9.050436 95.30391 -9.787714 -9.307154 95.23924 -9.861239 -9.289532 95.19995 -9.861239 -9.047489 95.26097 -9.913665 -9.043293 95.19985 -9.941979 -9.237042 95.08296 -9.941979 -9.038707 95.13303 -9.95 -9.211328 95.02565 -9.95 -9.034406 95.07036 -9.95 -8.550001 95 -9.95 -8.5 94.9 -9.950299 -8.525 94.9 -10.00892 -8.203207 94.9 -11.7084 -7.774975 94.9 -11.99108 -8.203207 94.9 -12.01422 -8.22824 94.9 -12.04102 -8.362949 94.9 -11.90933 -7.975 94.9 -11.525 -7.590673 94.9 -11.25656 -7.531826 94.9 -11 -7.45 94.9 -10.74344 -7.531826 94.9 -10.475 -7.590673 94.9 -10.2916 -7.774975 94.9 -10.09067 -7.975 94.9 -10.1237 -7.971558 94.9 -9.985778 -8.22824 94.9 -12.0497 -8.525 94.9 -12.05 -8.5 94.9 -12.04454 -8.443077 94.9 -12.033 -8.361807 94.9 -11.99108 -8.203207 95 -10.00892 -8.203207 95 -10.2916 -7.774975 95 -11.7084 -7.774975 95 -11.25656 -7.531826 95 -11 -7.5 95 -10.74344 -7.531826 95 -10.02372 -8.162852 95.06352 -10.25753 -7.806961 95.05615 -10.6135 -7.573192 95.0513 -11 -7.49948 95.04977 -11.3865 -7.573191 95.0513 -11.74246 -7.806956 95.05615 -11.86072 -7.948007 95.05907 -11.97628 -8.162842 95.06352 -9.646055 -7.347208 95.41812 -9.717258 -7.441043 95.42592 -9.783523 -7.537508 95.41856 -9.844386 -7.636309 95.3983 -9.896766 -7.732593 95.368 -9.950303 -7.848978 95.31872 -9.988053 -7.953299 95.26273 -10.01128 -8.042631 95.20401 -10.02198 -8.110161 95.14789 -10.02427 -8.141011 95.11294 -10.02422 -8.159037 95.08003 -10.61452 -7.569951 95.10176 -10.60005 -7.529678 95.30545 -10.93162 -7.468299 95.38399 -10.55991 -7.472164 95.46768 -10.67069 -7.363168 95.73629 -10.16602 -7.157603 95.94299 -10.21902 -7.179602 95.9368 -10.21227 -7.187556 95.91512 -10.25785 -7.195647 95.93025 -10.36883 -7.297863 95.78461 -10.48392 -7.393321 95.63217 -10.25883 -7.803498 95.08193 -10.26096 -7.787477 95.13398 -10.26049 -7.759815 95.19061 -10.24879 -7.698329 95.28464 -10.21581 -7.615329 95.38665 -10.15657 -7.516356 95.48685 -10.06804 -7.40364 95.57754 -9.978854 -7.308665 95.63498 -10.05619 -7.111667 95.94604 -9.873291 -7.209578 95.67518 -9.894316 -7.043078 95.92648 -9.756728 -7.111155 95.69251 -9.758188 -6.984648 95.88652 -9.630077 -7.013665 95.68259 -12.32054 -7.01647 95.73749 -12.54624 -6.864865 95.66916 -12.47334 -7.039707 95.51348 -11.82629 -7.160788 95.94232 -11.66664 -7.269131 95.82433 -11.79403 -7.174181 95.93864 -12.0069 -7.084999 95.94198 -12.04777 -7.231753 95.69901 -11.92866 -7.344212 95.63395 -11.0939 -7.457777 95.4401 -11.38609 -7.551449 95.21464 -11.00096 -7.498518 95.08433 -12.04674 -8.132639 95.2191 -12.02796 -8.207195 95.16957 -12.0184 -8.258778 95.1205 -12.16532 -7.824126 95.34141 -12.11711 -7.932943 95.30914 -12.07624 -8.039802 95.26661 -12.22227 -7.710232 95.36357 -12.28079 -7.604649 95.37248 -12.34376 -7.501065 95.36799 -11.35218 -7.353991 95.75461 -11.54289 -7.366322 95.68009 -11.45807 -7.447352 95.52381 -11.40822 -7.509815 95.36598 -12.55656 -6.84847 95.68663 -12.22484 -6.992025 95.89263 -12.30558 -7.187157 95.56213 -12.43886 -7.361258 95.33145 -11.69446 -7.742834 95.14823 -11.69892 -7.698507 95.23943 -11.71922 -7.632773 95.34064 -11.76289 -7.548548 95.44659 -11.83468 -7.448741 95.54931 -11.85723 -7.924562 95.12395 -11.85843 -7.877679 95.1888 -11.8707 -7.808838 95.26213 -11.9001 -7.72158 95.34008 -11.95052 -7.619289 95.41664 -12.018 -7.513249 95.48047 -12.10466 -7.400285 95.53027 -12.19919 -7.29368 95.55776 -10.74408 -7.264546 96.00752 -9.938589 -6.642851 96.52194 -9.653758 -6.642852 96.2946 -9.364654 -6.642854 95.94064 -9.143174 -6.642856 95.45629 -11.25595 -7.264546 96.0075 -12.23984 -6.642842 96.39 -12.34675 -6.642842 96.29413 -12.7196 -6.642839 95.7946 -11.51635 -6.642845 96.76834 -12.85704 -6.642838 95.45564 -10.50955 -6.642848 96.7753 -10.69986 -6.642848 96.815 -11.6875 -5.020742 96.09078 -11.95532 -5.020742 95.88893 -12.18194 -5.151254 96.12353 -12.65972 -5.151254 94.52671 -9.027665 -5.471708 94.45714 -9.340147 -5.151254 94.5273 -8.885227 -5.9006 94.42516 -8.923748 -5.9006 95.52203 -8.979556 -6.349895 95.50531 -9.535134 -6.349895 96.41748 -10.46634 -6.349895 96.94054 -12.46541 -6.349895 96.41696 -11.53439 -6.349895 96.94036 -13.02066 -6.349895 95.5046 -13.1146 -5.9006 94.4244 -12.34149 -5.020742 94.59828 -12.62979 -5.151254 95.38764 -12.19079 -5.020742 95.5875 -12.3173 -5.020742 95.29415 -12.375 -5.020742 94.9 -11.34838 -5.020742 96.23014 -11.43102 -5.151254 96.54567 -11 -5.020742 96.275 -10.56957 -5.151254 96.54583 -10.6521 -5.020742 96.23026 -10.3125 -5.020742 96.09078 -9.818491 -5.151254 96.12395 -10.04503 -5.020742 95.88928 -9.809215 -5.020742 95.5875 -9.370383 -5.151254 95.38822 -9.682842 -5.020742 95.29462 -9.625 -5.020742 94.9 -9.658404 -5.020742 94.59877 -12.97218 -5.471708 94.45644 -12.93661 -5.471708 95.47945 -12.40446 -5.471708 96.35388 -11.51216 -5.471708 96.85549 -10.48853 -5.471708 96.85567 -9.596061 -5.471708 96.35437 -9.063591 -5.471708 95.48014 -13.07647 -5.9006 95.5213 -12.50588 -5.9006 96.45886 -11.54915 -5.9006 96.99671 -10.4516 -5.9006 96.99691 -9.494672 -5.9006 96.45941 -12.80889 0 84.04975 -12.80889 -0.04999995 84.04972 -12.84185 -0.338993 84.05531 -13.05504 -0.8026482 84.09368 -13.46648 -1.158682 84.18012 -19.22909 -8 81.60631 -18.9101 -8 84.49237 -18.16328 -8 84.849 -19.62458 -8 82.34901 -19.69488 -8 83.0644 -19.45047 -8 83.87406 -16.525 0 83.65311 -5.475 0 83.65311 -4.194513 0 85.41084 -4.194513 -0.04999995 85.41084 -3.594703 -0.04999995 86.01576 -15.29455 -1.05 83.46305 -14.1 -1.05 83.76441 34.05 -10 84.9 31.95 -10 84.9 32.475 -7.590673 93.4 32.09067 -7.975 93.4 33 -8.5 93.4 31.95 -8.5 93.4 32.09067 -9.025 93.4 33.90933 -7.975 93.4 33.525 -7.590673 93.4 33 -7.45 93.4 33.525 -9.409328 93.4 33.90933 -9.025 93.4 34.05 -8.5 93.4 32.475 -9.409328 93.4 33 -9.55 93.4 31.525 6 79.95001 27.475 6 79.95001 31.525 4.5 79.95001 27.475 0 79.95001 38.525 4.5 79.95001 38.525 0 79.95001 35.32287 8.5 99.8854 35.32287 9.409926 99.8854 33 9.409925 100.4 33 8.5 100.4 30.6756 9.409925 99.8847 30.67712 8.5 99.8854 35.46589 8.5 99.78511 35.46589 9.398838 99.78511 35.56567 8.5 99.64173 35.56567 9.366894 99.64173 35.60979 8.5 99.47592 35.60979 9.318982 99.47592 30.39021 9.318982 99.47592 30.39021 8.5 99.47592 30.43521 8.5 99.64363 30.43521 9.367385 99.64363 30.53485 8.5 99.78585 30.53485 9.39897 99.78585 37.38263 8.5 97.82277 38.2238 8.5 95.57968 38.15388 8.56032 95.9897 37.38263 9.046358 97.82277 27.84611 8.560318 95.98969 27.77621 8.5 95.57968 28.61737 8.5 97.82277 28.61737 9.046358 97.82277 31.00373 8.5 94.77796 31.00373 8.4 94.77796 31.19762 8.4 95.76685 31.19762 8.5 95.76685 31.84909 8.4 96.53567 31.84909 8.5 96.53567 32.79274 8.4 96.88923 32.79274 8.5 96.88923 33.78902 8.4 96.73779 33.78902 8.5 96.73779 34.58498 8.4 96.11978 34.58498 8.5 96.11978 34.97855 8.4 95.1921 34.97855 8.5 95.1921 34.86983 8.4 94.19026 34.86983 8.5 94.19026 34.28641 8.4 93.36861 34.28641 8.5 93.36861 33.3764 8.4 92.93574 33.3764 8.5 92.93574 32.37084 8.4 93.00154 32.37084 8.5 93.00154 31.525 8.4 93.54931 31.525 8.5 93.54931 26.40465 8.5 94.94012 26.54207 8.5 94.74633 31.28049 8.5 94.55516 31.46188 8.5 94.24965 26.95722 8.5 93.40512 31.525 8.5 93.9 27.475 8.5 92.03219 26.86309 8.5 93.85691 37.77236 8.5 90.90277 35.5037 8.5 89.20056 36.68429 8.5 89.88185 27.98504 8.5 91.21217 29.3604 8.5 89.84992 31 8.5 89.00509 31.08773 8.5 88.97605 38.5578 8.5 92.0963 39.04366 8.5 93.40804 39.13692 8.5 93.85691 39.44427 8.5 94.7231 39.59535 8.5 94.94012 31.9 8.5 88.77301 32.99999 8.5 88.67505 34.1 8.5 88.77301 33.7375 6.5 93.62261 34.27738 6.5 94.1625 33 6.5 94.9 34.475 6.5 94.9 34.27738 6.5 95.6375 31.72261 6.5 94.1625 32.2625 6.5 93.62261 33 6.5 93.42501 32.2625 6.5 96.17739 31.72261 6.5 95.6375 31.525 6.5 94.9 33.7375 6.5 96.17739 33 6.5 96.375 31.72261 8.4 94.1625 32.2625 8.4 93.62261 33 8.4 93.42501 33.7375 8.4 93.62261 34.27738 8.4 94.1625 34.475 8.4 94.9 34.27738 8.4 95.6375 33.7375 8.4 96.17739 33 8.4 96.375 32.2625 8.4 96.17739 31.72261 8.4 95.6375 31.525 8.4 94.9 24.61408 8.739487 95.02572 24.58871 8.720318 94.9602 25.05974 8.511985 94.83631 25.27792 8.593173 95.041 25.53103 8.675383 95.29756 25.77116 8.739486 95.56527 24.30534 8.188876 94.24269 24.30329 8.16504 94.23102 24.83963 8.421184 94.64377 24.38054 8.460948 94.46638 24.33678 8.353923 94.35531 24.30754 8.212679 94.25522 24.51959 8.657227 94.79122 25.01618 8.494707 94.79713 24.80507 7.254463 93.41997 24.78595 7.278398 93.48236 24.73211 7.251549 93.50122 24.57871 7.596982 93.92934 24.55254 7.522727 93.87319 24.61817 7.529383 93.86386 24.0337 7.727891 93.63182 24.0121 8.304291 93.90953 24.36318 8.020673 94.1861 24.21191 7.580093 93.80569 24.36918 8.00712 94.18095 24.37734 7.530829 93.86365 24.44336 7.850263 94.10852 24.08762 7.661645 93.70975 24.11383 8.221511 94.10066 24.21191 8.185323 94.18421 24.511 7.719446 94.02717 24.76814 7.301971 93.53526 24.72954 7.356136 93.63664 24.55254 7.2068 93.53214 24.71085 7.383547 93.68055 24.64705 7.482301 93.81196 24.37734 7.217096 93.52502 24.46006 7.037733 93.17082 24.66506 7.063425 93.16452 24.73211 7.091717 93.15756 24.85527 7.180184 93.13585 24.86965 7.195086 93.13219 24.21191 7.279697 93.48178 24.31929 7.069025 93.16313 24.37734 7.051028 93.16754 24.0337 7.467507 93.35207 24.06424 7.283825 93.11036 24.08762 7.383326 93.41022 24.13586 7.189112 93.13362 24.23183 7.111984 93.15257 41.62367 7.992305 94.17529 41.62266 7.560337 93.8883 41.7881 7.608641 93.82954 41.40077 7.561666 93.89627 41.39759 7.556281 93.89102 41.44746 7.552392 93.89796 41.99958 7.50224 93.05672 42 7.522194 93.05182 42 7.674408 93.32546 41.93997 7.291264 93.10853 41.9663 7.447067 93.32123 41.91238 7.360826 93.37625 41.86415 7.18912 93.13362 41.7881 7.254662 93.44397 41.80574 7.137607 93.14627 41.7881 7.124944 93.14938 41.68075 7.069033 93.16312 41.62266 7.19053 93.4849 41.58541 7.043313 93.16944 41.44746 7.179982 93.49162 41.44746 7.038862 93.17053 41.34266 7.060859 93.16514 41.26789 7.225826 93.46237 41.26789 7.09171 93.15756 41.13035 7.195083 93.13219 41.18464 7.242253 93.3833 41.22828 7.297145 93.52498 41.26996 7.355421 93.63544 41.28885 7.383107 93.67988 41.42113 7.596707 93.92909 41.55636 7.850891 94.10895 41.46835 7.680656 93.99874 41.44847 7.644831 93.97045 41.9663 7.753557 93.65326 41.93563 8.250217 94.03442 41.91238 7.688601 93.73227 41.76805 8.180013 94.19653 41.69671 8.16507 94.23104 42 8.29283 93.78427 42 8.347739 93.80921 40.22884 8.739486 95.56527 40.66306 8.61355 95.09887 41.38592 8.739488 95.02572 40.67897 8.608129 95.08318 41.45553 8.681855 94.85077 40.93284 8.514904 94.84305 41.52537 8.606416 94.6859 41.59217 8.51077 94.53102 41.16146 8.420734 94.64287 41.4404 8.293511 94.41815 41.69466 8.18889 94.2427 41.69246 8.212679 94.25522 41.64834 8.395926 94.39484 41.61365 8.472312 94.48032 31.525 8.4 93.9 31.28049 8.4 94.55516 31.46188 8.4 94.24965 25.09078 7.694948 93.78565 24.95791 7.711924 93.9102 25.43063 7.86729 93.55454 25.3016 7.73442 93.5033 25.58812 8.112804 94.02519 25.59562 8.144192 94.10848 25.49982 8.122793 94.18968 24.89449 8.280365 94.53455 25.33545 8.344257 94.67936 25.60625 8.480696 94.90688 25.61569 8.483117 94.91049 25.62438 8.498843 94.94373 25.67662 8.570812 95.10353 25.79294 8.675964 95.38285 25.73922 8.633299 95.25989 25.72327 8.618904 95.22182 25.56892 8.279341 94.48265 25.56818 8.298502 94.52592 25.5799 8.388618 94.71582 25.58908 8.4202 94.78045 25.59975 8.44904 94.83966 25.61366 8.479188 94.90225 25.05797 8.197619 94.47387 25.20645 8.147405 94.39861 25.35545 8.121463 94.30335 25.58976 8.202863 94.27964 25.59549 8.187191 94.23081 25.20728 7.703168 93.64695 25.54829 8.023335 93.80503 25.49949 7.944628 93.62528 24.37138 8.008738 94.18246 24.52309 7.898868 94.15016 24.66682 7.817526 94.09578 24.81338 7.75396 94.0156 25.5794 8.088348 93.96298 40.45001 8.026434 93.81234 40.56559 7.985476 93.94601 40.41186 8.112875 94.02538 41.15888 7.48743 93.70639 41.42906 7.926337 94.17525 40.41488 8.371092 94.6841 40.41707 8.367884 94.67675 40.69913 8.203955 94.46259 40.42776 8.352224 94.64088 40.5499 8.18525 94.36601 40.41025 8.202855 94.27964 40.52102 8.541767 95.02569 40.34914 8.502466 94.94716 40.84835 8.247836 94.54031 40.33673 8.485536 94.94626 40.3553 8.458345 94.88397 40.35735 8.455332 94.87706 40.40692 8.382739 94.71077 40.22322 8.651783 95.32707 40.25774 8.601222 95.21125 40.30608 8.530426 95.04908 40.3264 8.50067 94.98092 40.207 8.675528 95.38146 41.0132 8.324601 94.60499 41.13696 8.090984 94.34494 41.13805 7.786908 94.03654 40.49597 7.951324 93.64017 40.50052 7.944618 93.62526 40.65062 7.783852 93.5231 40.63331 7.794329 93.49247 40.94524 7.481684 93.42347 40.86067 7.735708 93.80469 40.40682 8.195223 94.25537 40.84181 7.987963 94.18479 25.63339 8.131237 93.98484 26.12838 8.355965 93.73209 25.98118 8.424287 94.5969 26.19015 8.470419 94.65641 26.23205 8.433513 94.227 25.77288 8.327207 94.42807 25.64585 8.224975 94.26665 26.04064 8.560323 95.1478 26.05209 8.554214 95.13407 26.2205 8.513184 95.03282 26.09172 8.539834 95.1025 25.83127 8.632414 95.26885 25.64065 8.437804 94.80424 25.68186 8.428194 94.77038 25.91637 8.591715 95.18481 39.94949 8.554957 95.13572 39.80379 8.516889 95.04485 40.31309 8.42724 94.76657 40.33361 8.431356 94.78234 39.9649 8.561372 95.14839 39.95937 8.560328 95.14781 40.08798 8.592896 95.18658 40.01884 8.42428 94.59688 40.22396 8.32901 94.43063 40.1591 8.6262 95.25431 27.475 1.065431 85.32013 27.475 1.097699 85.37628 27.21344 1.090434 85.55004 24.81746 1.050826 87.55821 24.77424 1.00364 87.52654 26.08782 0.952255 86.30997 24.8278 1.066654 87.56517 26.02387 1.107235 86.46747 25.99065 1.105806 86.49487 26.11981 1.024362 86.35592 24.86957 1.184357 87.58605 24.86463 1.158462 87.58519 27.475 1.135859 85.41751 27.475 1.170739 85.44255 27.23302 1.167804 85.59545 27.475 1.20348 85.45837 26.13292 1.113291 86.37921 26.89164 1.153125 85.82086 26.89225 1.192329 85.82952 27.23648 1.231642 85.61212 27.475 1.253273 85.47113 27.475 1.040888 85.22087 27.475 1.052361 85.28369 27.17954 1.036128 85.48497 26.84486 1.009312 85.72321 26.87641 1.071063 85.78258 24.86243 1.149476 87.58447 26.72671 0.9761614 85.7507 26.0533 0.9204065 86.28141 25.42424 0.9180271 86.82995 24.73645 0.9790191 87.4966 40.35398 8.170079 94.09488 39.81277 8.388828 93.88395 39.76798 8.449958 94.38932 40.41719 8.038136 93.74221 39.87162 8.355962 93.73207 26.15661 9.552564 98.20986 24.97318 9.095395 96.27211 24.75259 8.928083 95.66204 28.04458 9.880118 100.0832 30.53381 9.532044 100.1888 30.02343 9.97159 101.2833 31.97922 9.97159 101.8688 33 9.97159 101.9432 35.97657 9.97159 101.2833 34.02078 9.97159 101.8688 37.95542 9.880118 100.0832 41.24635 8.929163 95.66581 41.02682 9.095395 96.27211 39.84339 9.552564 98.20986 33.33811 11.49627 88.8024 33.67428 11.5 88.9809 33.87101 11.5 89.00663 30.13414 11.4 88.81567 28.88149 11.4 89.58303 29.35186 11.5 90.19028 30.46144 11.5 89.51055 32.12899 11.5 89.00663 32.01668 11.4 88.24678 32.32571 11.5 88.9809 32.80384 11.49468 88.76713 33.98331 11.4 88.24678 35.53855 11.5 89.51055 35.86586 11.4 88.81567 36.64814 11.5 90.19028 37.11851 11.4 89.58303 29.29354 11.5 90.23703 27.47049 11.38531 91.71788 28.18383 11.5 92.19513 28.64985 11.5 91.02996 27.78753 11.5 94.13834 26.97458 11.38531 94.01955 26.2238 11.05001 93.90984 27.12309 11.28008 91.80598 28.10658 11.38174 90.32252 27.92349 11.37086 90.54552 30.39021 11.5 99.47592 35.53346 11.49571 99.70079 35.60979 11.5 99.47592 35.35956 11.49112 99.8665 35.32287 11.4955 99.8854 38.26782 11.5 94.89344 38.21247 11.5 94.13834 38.17315 11.5 93.87876 37.74859 11.5 91.97337 27.73343 11.5 94.78497 30.39558 11.49981 99.51767 38.00827 11.5 96.53317 37.2513 11.5 98.0107 36.0721 11.5 99.17928 31.23461 11.491 100.109 32.94337 11.491 100.3997 34.65776 11.491 100.1442 27.95916 11.5 96.4297 28.68555 11.5 97.9225 29.84044 11.5 99.11511 30.49199 11.49455 99.73709 30.67712 11.4955 99.8854 37.26159 11.5 90.88072 27.5 7.944444 89.64302 27.38799 8.357628 90.77313 26.7036 7.944498 90.62914 26.3916 8.357628 92.69664 25.94033 7.944567 92.06364 28.9271 8.357628 89.24871 30.86007 8.357628 88.27079 32.99999 8.357628 87.93395 35.13991 8.357628 88.27079 37.07289 8.357628 89.2487 38.61199 8.357628 90.77311 39.60839 8.357628 92.69662 40.0957 7.944598 92.15512 37.12326 7.944507 88.50598 38.31687 7.944535 89.45802 39.35101 7.944567 90.71091 28.5516 7.944444 88.72768 30.66279 7.944444 87.65961 32.99999 7.944444 87.29174 34.1 7.944444 87.37167 35.67145 7.944476 87.77619 24.36104 9.566286 95.58785 24.62468 9.87877 95.97737 24.24846 9.450699 94.86997 24.6312 9.814373 96.24488 24.72727 9.947851 96.1658 24.2117 9.363241 94.90268 24.19281 9.247939 94.9409 24.34188 9.429047 95.63258 24.51192 8.769891 95.03341 24.52979 9.039229 95.69216 24.38597 8.843555 95.03191 24.43213 9.147164 95.68836 24.28578 8.948118 95.01672 24.36568 9.282758 95.66794 24.2174 9.081137 94.98759 24.19258 9.226061 94.9476 24.59017 9.587201 96.32264 24.61059 9.468082 96.34396 24.65721 9.354817 96.35162 24.8164 9.172376 96.32495 24.19031 8.557074 94.39761 24.15258 8.443392 94.26985 24.33049 8.585347 94.5656 24.23718 8.649281 94.53798 24.08385 9.033066 94.28696 24.13922 9.173767 94.61323 24.17139 9.288738 94.55007 24.00104 8.487422 93.8684 24.02051 8.355715 93.96926 24.12682 8.27026 94.14011 24.18462 8.245559 94.18949 24.06198 8.9482 94.15325 24.01703 8.696295 93.97143 24.01485 8.667213 94.00733 24.03126 8.587402 94.10588 24.07915 8.510441 94.19606 24.08393 8.295081 94.09049 24.15778 8.732919 94.49291 24.17433 8.949305 94.71679 24.23728 8.844974 94.75554 24.32265 8.758917 94.78076 24.42011 8.69622 94.79204 24.07426 8.997894 94.19824 24.07736 8.934225 94.36124 24.10231 8.830869 94.43226 24.24337 9.441286 94.84654 24.13509 1.076982 87.5746 24.1783 1.073574 87.61479 24.23608 1.110035 87.66336 24.01517 0.8763864 87.26623 24.04463 1.024869 87.43051 24.23009 0.7504258 87.37032 24.34422 0.764006 87.3591 24.36405 0.8599888 87.48121 24.08452 0.9564331 87.47136 24.1166 0.7795366 87.34626 24.15031 0.896705 87.49392 24.15325 0.7648242 87.35842 24.23179 0.8563552 87.49435 24.31317 0.8404068 87.47484 24.43334 0.9239552 87.55622 24.03037 0.8504354 87.28767 24.04044 0.8374139 87.29844 24.05919 0.817999 87.31448 24.07009 1.043685 87.48239 24.23361 1.00075 87.62124 24.35344 1.067753 87.70124 24.32042 1.129189 87.70879 24.48958 1.10832 87.73427 24.65351 1.172383 87.72505 24.53775 1.161122 87.74623 24.43089 1.147643 87.74063 24.64453 1.131597 87.7176 24.78676 1.137413 87.64707 24.83985 1.183693 87.61634 24.63369 0.97921 87.56548 24.72104 1.001254 87.5623 24.30188 0.9440349 87.60152 24.36992 0.9116304 87.56174 24.40185 0.9997708 87.66532 24.44835 0.9558445 87.60913 24.51427 1.033304 87.68929 24.53429 0.982132 87.62424 24.64183 1.05261 87.67269 24.63082 0.9973615 87.6088 24.75988 1.057471 87.61316 24.52361 0.960171 87.58372 25.5323 0.7110046 86.40731 27.05612 0.9498139 85.26879 27.475 0.9268653 84.62847 26.81063 0.7110046 85.07284 27.475 0.6425546 84.03333 27.475 0.4778812 83.84371 26.65645 0.3692808 84.94977 27.475 0.2731142 83.70359 27.475 0.04999995 83.65311 26.61554 0.04999995 84.91712 26.12271 0.04999995 85.48887 25.36834 0.04999995 86.21909 24.37953 0.4059969 87.05633 25.40272 0.3692808 86.25856 24.35851 0.6543256 87.23503 24.38977 0.05000001 86.97063 39.86035 1.120409 86.38994 39.8673 1.11187 86.3792 39.97378 1.108967 86.4691 38.525 1.07093 85.33209 39.19015 1.032522 85.79237 39.17616 1.067247 85.81972 41.13044 1.184357 87.58605 40.44384 1.108687 86.87754 41.13614 1.155007 87.58499 40.46362 1.020549 86.86113 41.17235 1.066357 87.56508 41.18411 1.048577 87.55713 40.50327 0.9479164 86.82263 41.22597 1.003452 87.52638 38.525 1.040888 85.22087 39.23204 0.9803331 85.71994 38.525 1.052269 85.28337 38.525 1.113824 85.39595 39.16646 1.106962 85.84154 38.525 1.131512 85.41366 39.16139 1.149847 85.85697 39.16098 1.193899 85.86564 38.525 1.200338 85.45713 38.63954 1.243563 85.5379 38.525 1.253013 85.47109 40.0021 1.106109 86.48887 39.88029 1.024054 86.35579 39.91233 0.9520404 86.30979 41.26355 0.9790189 87.4966 40.59712 0.9190438 86.84957 39.94671 0.920407 86.28142 39.2075 1.004589 85.76123 38.525 1.063253 85.31497 39.14397 1.192677 85.88995 27.85006 10.63677 100.239 27.92152 10.76396 100.1294 25.95803 10.42331 98.18107 29.97953 10.85909 101.3774 29.92393 10.73264 101.4967 29.91607 10.70473 101.5135 27.81102 10.41011 100.3192 29.88617 10.50603 101.5776 27.84456 10.16917 100.3066 29.89813 10.26409 101.552 29.94662 10.0871 101.448 27.94273 9.971138 100.2042 29.95699 10.06424 101.4258 26.02099 9.637723 98.29736 25.88531 9.829247 98.36253 25.87144 10.29349 98.27568 25.83118 10.06661 98.35469 34.0576 10.70473 102.1202 34.03583 10.85909 101.9716 31.96417 10.85909 101.9716 34.04712 10.0871 102.0486 31.95288 10.0871 102.0486 36.02046 10.85909 101.3774 36.08393 10.70473 101.5135 36.11369 10.5086 101.5773 34.06804 10.49493 102.1915 36.11439 10.49493 101.5788 34.0643 10.27459 102.166 36.10349 10.27459 101.5555 36.05339 10.0871 101.448 31.9424 10.70473 102.1202 31.93196 10.49493 102.1915 31.9357 10.27459 102.166 40.12816 10.29442 98.27517 40.16889 10.06916 98.3542 41.36837 9.815316 96.24444 41.40996 9.589716 96.32205 41.38941 9.468083 96.34396 40.1163 9.832924 98.36301 41.34471 9.358375 96.35159 39.98273 9.641145 98.29953 41.18793 9.175562 96.32612 38.06002 9.974726 100.2074 38.15655 10.17293 100.3076 38.18895 10.41267 100.3188 38.1496 10.63769 100.2384 41.27272 9.947851 96.1658 40.04197 10.42331 98.18107 38.07848 10.76396 100.1294 29.34768 11.38531 99.7725 31.04543 11.38531 100.6672 32.9373 11.38531 100.9891 34.83541 11.38531 100.7062 36.55123 11.38531 99.84667 37.91434 11.38531 98.49584 38.78936 11.38531 96.78787 39.0894 11.38531 94.89241 39.84815 11.05001 94.89146 39.7762 11.05001 93.90985 39.02541 11.38531 94.01955 39.51073 11.05001 97.0231 38.52668 11.05001 98.9439 36.99372 11.05001 100.463 35.06411 11.05001 101.4297 32.9295 11.05001 101.7478 30.80188 11.05001 101.3858 28.89258 11.05001 100.3796 28.01267 11.38531 98.39389 27.39123 11.05001 98.82925 27.17299 11.38531 96.66828 26.44693 11.05001 96.8886 26.91205 11.38531 94.76702 26.15348 11.05001 94.75045 37.96502 11.38531 90.45552 38.03461 11.37363 90.49263 38.67042 11.38531 92.20222 38.88666 11.27843 91.82453 38.05131 11.10042 88.37878 36.1775 11.10042 87.28781 34.08414 11.10042 86.72279 31.91586 11.10042 86.72279 29.8225 11.10042 87.28781 27.94869 11.10042 88.37878 25.59725 10.65185 92.98032 25.2 10.4 94.9 26.03874 10.84183 91.02986 27.23513 11.14213 90.04239 26.11945 10.86786 90.68843 26.03115 10.83925 91.06217 31.20522 6.622629 86.30236 32.99993 6.861519 86.30236 28.91774 6 86.63349 29.42264 6 86.4028 28.52785 7.645157 88.37686 37.472 7.645246 88.37686 40.30657 7.183207 90.89805 41.13043 4.657988 89.13813 41.13044 5.787574 90.274 41.13045 6.647323 91.62755 39.31602 6.209383 88.37686 40.72027 4.341181 88.37686 41.13043 3.309217 88.27088 41.13042 1.806905 87.71451 39.65226 1.681632 86.30236 38.525 4.5 86.52 38.525 2.920343 85.8476 38.98082 3.363069 86.30236 38.5 4.5 86.50357 37.89295 4.810346 86.30236 36.93605 4.5 85.66651 31.5 6 85.8033 31.525 6 85.79921 31.525 5.267948 85.35678 31.525 4.5 84.97154 31.9 4.5 84.92303 32.33184 4.5 84.88484 34.1 4.5 84.92303 34.79465 6.622664 86.30236 35.41069 4.5 85.15636 36.46441 5.922695 86.30236 27.475 6 87.51933 26.68386 6.209258 88.37686 27.475 5.763355 87.33309 26.34771 1.681499 86.30236 27.475 2.936981 85.85298 27.01911 3.362949 86.30236 27.475 4.303596 86.41747 24.86958 2.728104 88.01133 25.27964 4.341027 88.37686 24.86955 7.017164 92.52194 25.69329 7.183063 90.89805 24.86956 6.341961 91.06915 24.86956 6.229709 90.88919 24.86957 5.369221 89.79437 24.86957 4.146322 88.75963 31 6 85.9 24.30309 0.6415332 87.24919 24.3172 0.5092888 87.14342 24.32824 0.3627617 87.06333 24.33521 0.2092344 87.01422 24.30585 0.05000001 87.00698 24.04942 0.7053512 87.17869 24.10212 0.6702207 87.21752 24.01552 0.7473144 87.1323 24.16789 0.6470296 87.24314 24.23772 0.6379178 87.25321 24.26378 0.358168 87.0746 24.27114 0.2064711 87.02802 24.27374 0.05000001 87.01216 24.13268 0.05000001 86.98405 24.18796 0.05000001 87.00547 24.19289 0.3605412 87.06884 24.12388 0.3709756 87.04335 24.066 0.3886229 87.00023 24.02576 0.4108422 86.94592 24.00471 0.4343597 86.88842 24.25226 0.504335 87.15117 24.01673 0.05000001 86.8532 24.08387 0.05000001 86.95011 24.19093 9.285041 93.90612 24.72727 9.971098 93.83267 24.13359 8.885254 92.49893 24.72727 9.958243 93.71873 24.46668 9.606954 93.1261 24.18277 8.220167 94.17555 24.01984 8.324509 93.95165 24.08261 8.26713 94.07478 24.0238 5.756629 89.94793 24.74934 6.611435 91.77548 24.0238 6.865461 91.65544 24.13606 6.6933 91.7368 24.31944 6.581721 91.78952 24.53811 6.552531 91.80332 24.74934 2.317903 87.96451 24.53811 2.297252 88.0263 24.31944 2.307486 87.99568 24.0238 2.406962 87.69803 24.13606 2.346604 87.87863 24.0238 4.233977 88.59641 24.13606 5.612274 90.07211 24.31944 5.518716 90.15259 24.53811 5.49424 90.17365 24.74934 5.543631 90.13116 24.13606 4.127804 88.75448 24.31944 4.058992 88.85693 24.53811 4.040991 88.88374 24.74934 4.077318 88.82965 38.525 0.05588293 83.65315 38.525 0.04999995 83.65311 39.38447 0.04999995 84.91713 41.48923 0.9564898 87.58248 41.37561 0.9783393 87.56899 40.46773 0.7110046 86.40734 41.65578 0.7640079 87.3591 41.57653 0.917934 87.54986 41.63754 0.8573679 87.47795 41.65617 0.7668761 87.36288 40.59731 0.3692809 86.25859 40.63169 0.04999995 86.21912 41.61024 0.04999995 86.97061 41.61082 0.1375815 86.97563 41.6184 0.3685107 87.03882 41.63798 0.6221893 87.20484 38.525 0.2271351 83.68482 39.34357 0.3692809 84.94979 38.525 0.4156218 83.79087 39.18938 0.7110046 85.07286 38.525 0.6216115 84.00473 38.94389 0.949814 85.26881 38.525 0.8309162 84.37019 41.77489 0.9937691 87.61257 41.85011 0.8957426 87.49278 41.91596 0.9553516 87.47009 41.74144 0.7499325 87.37073 41.78199 0.7514027 87.36952 41.76856 0.8555395 87.49336 41.92539 1.046477 87.49033 41.8648 1.077025 87.57472 41.83121 1.065692 87.6049 41.76884 1.108734 87.66001 41.28337 1.05721 87.64077 41.66504 0.7612884 87.36135 41.68711 0.8397367 87.47401 41.6358 0.9069462 87.55621 41.31221 1.001041 87.5836 41.39147 0.9948791 87.61524 41.48648 0.9771258 87.62329 41.56714 0.9492103 87.60295 41.32057 1.174489 87.71611 41.54364 1.100602 87.73067 41.46219 1.161122 87.74623 41.39118 1.127835 87.72638 41.26512 1.137104 87.68011 41.67065 1.057567 87.6899 41.6815 1.128814 87.70797 41.54686 1.150737 87.74377 41.95608 1.02401 87.42881 41.9516 1.027787 87.4391 42.00008 0.9425158 87.2116 41.99853 0.958072 87.25203 41.9975 0.915212 87.23416 41.97641 1.003122 87.37234 41.98484 0.8763912 87.26624 41.97187 0.8536854 87.28501 41.94081 0.8179988 87.31449 41.91023 0.7945907 87.33383 41.89266 0.7842686 87.34236 41.7087 1.1232 87.69542 41.38761 1.04948 87.68048 41.51309 1.026922 87.68707 41.61814 0.9913363 87.65655 41.70527 0.9381936 87.5944 41.65434 8.780303 94.84611 41.5902 8.825829 95.03335 41.78126 8.61693 94.484 41.83364 8.491841 94.31935 41.90814 8.563808 94.25151 41.71906 8.712232 94.66299 41.75154 9.4507 94.86997 41.7883 9.363243 94.90268 41.84478 9.248688 94.48962 41.80743 9.226062 94.9476 41.92474 9.001721 94.20187 41.92408 9.004234 94.20426 41.9282 8.989221 94.21267 41.88761 9.115652 94.45644 41.88987 9.009678 94.52043 41.97534 8.732233 94.07418 41.97141 8.778544 94.02308 41.93818 8.947532 94.15267 41.97949 8.355715 93.96927 41.99999 8.419126 93.84249 41.99896 8.487301 93.86834 41.95739 8.646467 94.1673 41.91607 8.295081 94.09049 41.81538 8.245558 94.18949 41.7826 9.081138 94.98759 41.80645 8.97072 94.79188 41.74139 8.865866 94.82538 41.71422 8.948119 95.01672 41.61403 8.843555 95.03191 41.80146 8.798075 94.62876 41.86071 8.9003 94.57989 39.79357 11.04076 93.92588 26.24737 10.97421 96.62297 39.75263 10.97421 96.62297 41.27272 9.971097 93.83267 41.27272 9.958243 93.71873 40.8 10.4 94.9 24.87868 10.12132 94.12431 41.68796 9.55513 95.13549 41.63781 9.567469 95.59197 41.65697 9.430231 95.6367 41.63318 9.28393 95.67203 41.56675 9.148318 95.69239 41.46911 9.04036 95.69611 40.04157 10.81338 91.37368 39.96154 10.84173 91.03101 39.91192 10.85833 90.98857 38.72955 11.14794 90.014 39.94216 10.84822 90.94868 39.47921 10.96148 89.04126 41.69104 0.1338604 87.01071 41.69469 0.04999995 87.0071 41.81327 0.04999995 87.00515 41.72193 0.6062481 87.22402 41.81088 0.6100675 87.21945 41.89469 0.6347926 87.1898 41.95729 0.6758547 87.14052 41.78004 0.133305 87.01591 41.86735 0.04999995 86.98404 41.86803 0.1362346 86.98825 41.91761 0.04999995 86.94879 41.93817 0.1421158 86.93276 41.98423 0.04999995 86.85068 41.98516 0.1505244 86.85343 41.99998 0.04999887 86.76329 42.00001 0.5039723 86.86651 41.87262 0.2965917 87.01881 41.7852 0.2878236 87.04712 41.6961 0.2888016 87.04389 41.98975 0.5176127 86.95185 41.94754 0.4793457 87.02481 41.88079 0.4515573 87.0778 41.79458 0.4362587 87.10697 41.70542 0.4362582 87.10697 41.86394 2.346608 87.87863 41.9762 4.233979 88.59642 42 4.02107 88.27953 42 5.141971 89.10693 41.68056 6.581723 91.78952 41.46189 6.552531 91.80332 41.25067 6.611432 91.77548 41.86394 6.693301 91.7368 41.9762 6.86546 91.65544 41.9762 5.756629 89.94793 42 6.245589 90.3183 42 7.070023 91.73551 41.9762 2.406965 87.69803 42 2.537532 87.58148 41.68056 2.30749 87.99568 41.46189 2.297255 88.02631 41.25067 2.317905 87.96452 41.86394 4.127807 88.75448 41.68056 4.058996 88.85693 41.46189 4.040993 88.88374 41.25067 4.077318 88.82965 41.86394 5.612276 90.07211 41.68056 5.518718 90.15259 41.46189 5.494241 90.17365 41.25067 5.543629 90.13117 41.98016 8.32453 93.95166 41.91739 8.267148 94.07478 41.81724 8.220183 94.17555 41.61923 9.462752 92.96124 41.80907 9.285041 93.90611 41.80457 9.065065 92.61929 41.91963 8.689736 92.38454 42 8 92.07158 28.05157 -7.5 84.92611 25.55569 -8 85.48818 24.09268 -7.923341 87.44403 24.02455 -7.969582 87.30877 25.86587 -7.866025 85.88034 24.3409 -7.721494 87.62805 24.18981 -7.851704 87.54618 24.17114 -7.866175 87.53067 27.26007 -7 85.51634 26.17605 -7 86.27251 26.09294 -7.5 86.16742 24.86956 -7 87.49082 24.86713 -7.005202 87.49346 24.75449 -7.213155 87.58443 24.54871 -7.499804 87.65165 24.54575 -7.503365 87.65193 28.06011 -7.465131 84.94333 28.11111 -7 85.04614 29.70492 -7.465131 84.84394 29.66667 -7 84.95212 29.09453 -7 84.83998 29.09996 -7.465131 84.72535 29.83333 -7.866025 84.48072 29.8109 -7.823506 84.54418 29.71133 -7.5 84.82582 30.00106 -7.523157 84.97611 30.08766 -7.868884 84.6684 30.99999 -8.994227 86.83114 30.98977 -8.752775 86.63575 30.9878 -8.794136 86.60225 30.85206 -8.084345 86.08283 30.82614 -8.245539 85.96581 30.78536 -7.911786 85.93635 30.74975 -8.108119 85.80148 30.74951 -7.83306 85.86862 30.43227 -7.745383 85.34075 31 -8.996537 86.82926 30.98865 -8.835378 86.56856 30.99233 -8.876387 86.53476 30.83864 -8.400229 85.83827 30.88904 -8.542173 85.70538 30.76799 -8.293065 85.64828 30.83902 -8.455893 85.48565 30.47639 -8.018767 85.10897 30.62013 -8.215502 84.84244 30.42621 -7.988337 85.03896 30.57991 -8.185317 84.75563 30.12521 -7.875457 84.70216 30.3149 -8.050876 84.31906 30.27818 -8.039472 84.27304 30.49351 -7.431004 85.50754 30.43988 -7.370632 85.44966 30.37721 -7.703214 85.28186 30.08654 -7.10175 85.15863 30.04325 -7.53484 85.00346 30.03758 -7.078943 85.12794 31 -9 86.83775 41.13286 -7.005202 87.49346 41.13043 -7 87.49082 39.8132 -7 86.26402 40.1229 -7.866025 85.87147 41.82886 -7.866175 87.53067 41.81019 -7.851704 87.54618 41.6591 -7.721494 87.62805 41.45425 -7.503365 87.65193 39.89619 -7.5 86.15883 41.45129 -7.499804 87.65165 41.2508 -7.221737 87.58751 40.43259 -8 85.47892 42 -8 86.96275 42 -7.992074 87.15404 41.97545 -7.969582 87.30877 41.90732 -7.923341 87.44403 37.94842 -7.5 84.92611 38.73993 -7 85.51634 37.94074 -7.46878 84.94159 37.88888 -7 85.04613 36.91928 -7.46878 84.7226 36.16667 -7.866025 84.48072 36.18683 -7.828161 84.53775 36.28867 -7.5 84.82582 36.92373 -7 84.83921 36.33333 -7 84.95212 36.29444 -7.46878 84.84211 35.56773 -7.745383 85.34075 35.52361 -8.018767 85.10897 35.57378 -7.988337 85.03896 35.72182 -8.039472 84.27304 35.00001 -8.996537 86.82926 35.00767 -8.876387 86.53476 35.01135 -8.835378 86.56856 35.11096 -8.542173 85.70538 35.16136 -8.400229 85.83827 35.16098 -8.455893 85.48565 35.23201 -8.293065 85.64828 35 -9 86.83775 35.00001 -8.994227 86.83114 35.0122 -8.794136 86.60225 35.17386 -8.245539 85.96581 35.25025 -8.108119 85.80148 35.14794 -8.084345 86.08283 35.01023 -8.752775 86.63575 35.50649 -7.431004 85.50754 35.25333 -7.827156 85.86351 35.21464 -7.911786 85.93635 35.91234 -7.868884 84.6684 35.87479 -7.875457 84.70216 35.6851 -8.050876 84.31906 35.42009 -8.185317 84.75563 35.37987 -8.215502 84.84244 35.62279 -7.703214 85.28186 35.95675 -7.53484 85.00346 35.99894 -7.523157 84.97611 35.56013 -7.370632 85.44966 35.91347 -7.10175 85.15863 35.96242 -7.078943 85.12794 31.58645 -9.927686 84.9 31.27825 -9.721752 84.9 31.07232 -9.41355 84.9 31 -9.050001 84.9 31.94988 -10 86.29098 31.8532 -9.99507 86.3143 31.27789 -9.721395 86.46943 31.11431 -9.501788 86.54115 31.0575 -9.375482 86.58329 31.0052 -9.149256 86.68246 31 -9.050001 86.767 31.62123 -9.941298 86.3712 31.41866 -9.837512 86.42524 35 -9.050001 84.9 34.87273 -9.525001 84.9 34.525 -9.872725 84.9 34.72175 -9.721752 84.9 35 -9.050001 86.767 34.99993 -9.061986 86.75175 34.98665 -9.208695 86.65068 34.05014 -10 86.29071 34.49713 -9.888198 86.40189 34.94223 -9.376236 86.58302 34.85062 -9.561365 86.52208 34.72206 -9.721445 86.46942 33 -3.15 93.67501 33 -3.3 93.525 32.3125 -3.3 93.70922 32.3875 -3.15 93.83912 31.80921 -3.3 94.2125 31.93912 -3.15 94.2875 31.625 -3.3 94.9 31.775 -3.15 94.9 31.80921 -3.3 95.5875 31.93912 -3.15 95.5125 32.3125 -3.3 96.09078 32.3875 -3.15 95.96089 33 -3.3 96.275 33 -3.15 96.125 33.6875 -3.3 96.09078 33.6125 -3.15 95.96089 34.19078 -3.3 95.5875 34.06088 -3.15 95.5125 34.375 -3.3 94.9 34.225 -3.15 94.9 34.19078 -3.3 94.2125 34.06088 -3.15 94.2875 33.6875 -3.3 93.70922 33.6125 -3.15 93.83912 24.30585 -0.04999995 87.00698 24.38975 -0.04999995 86.97061 24.18796 -0.04999995 87.00547 24.08387 -0.04999995 86.95011 24.01673 -0.04999995 86.8532 41.61024 -0.05000019 86.97061 41.98423 -0.04999995 86.85068 41.99998 -0.04999852 86.76329 41.91761 -0.04999995 86.94879 41.81327 -0.04999995 87.00515 41.69469 -0.04999995 87.0071 41.96849 -0.8029307 87.23643 41.97969 -0.8196772 87.22098 41.9756 -0.4667882 86.96759 41.86767 -0.1071043 86.98588 41.79767 -0.1053687 87.01067 42.00001 -0.4555604 86.84561 41.99586 -0.4937537 86.91133 42.00001 -0.8922592 87.15404 41.96974 -0.1141927 86.88474 41.87888 -0.420747 87.06363 41.93614 -0.4412043 87.02095 41.92728 -0.1102021 86.94168 41.72662 -0.1051263 87.01416 41.61048 -0.1080283 86.9728 41.66669 -0.2617524 87.0273 41.61403 -0.2684867 87.00229 41.62041 -0.4048455 87.05573 41.67487 -0.4102752 87.08547 41.73086 -0.2582363 87.04039 41.9561 -0.7882291 87.24999 41.70623 -0.7113268 87.32093 41.76372 -0.7087639 87.32328 41.754 -0.5660954 87.19412 41.84102 -0.7210968 87.31191 41.82425 -0.5728724 87.18514 41.88137 -0.7358992 87.29826 41.90542 -0.7483089 87.28681 41.93758 -0.770759 87.2661 41.65008 -0.7238042 87.30941 41.68886 -0.5706378 87.18807 41.73947 -0.4053757 87.0957 41.81025 -0.4084649 87.08926 41.14216 -1.176678 87.50325 41.13043 -1.175788 87.49082 41.33987 -1.175127 87.6277 41.46495 -1.163131 87.65281 41.4348 -1.166705 87.64977 41.34869 -1.174527 87.63059 41.68146 -1.122748 87.61994 41.65545 -1.129236 87.62926 41.57057 -1.147002 87.64904 41.61013 -1.139326 87.64176 41.84069 -1.067137 87.52 41.79394 -1.087089 87.5585 41.77125 -1.095482 87.57406 41.69465 -1.119242 87.61459 41.9491 -0.9957025 87.37384 41.89852 -1.035329 87.456 41.89082 -1.040176 87.4659 41.86292 -1.056047 87.49797 41.98071 -0.9564232 87.29158 24.22455 -1.093937 87.57132 24.1388 -1.056906 87.49977 24.07566 -1.017191 87.41849 24.02556 -0.9660782 87.31183 24.00107 -0.9075111 87.18676 24.54 -1.163745 87.65243 24.44791 -1.150172 87.65131 24.38778 -1.138796 87.64128 24.32196 -1.123616 87.62126 24.31398 -1.121546 87.61814 24.23046 -1.096047 87.57517 24.67763 -1.176285 87.62142 24.86949 -1.175788 87.49076 24.3333 -0.2616652 87.02728 24.38596 -0.2684018 87.00227 24.3895 -0.1079662 86.9728 24.20232 -0.1053122 87.01065 24.27337 -0.1050692 87.01414 24.27139 -0.7091577 87.32292 24.34992 -0.7237922 87.30943 24.31112 -0.570613 87.18806 24.374 -0.4884308 87.10285 24.32512 -0.4101784 87.08544 24.37864 -0.4205834 87.06372 24.38364 -0.3264159 87.02165 24.12113 -0.4206516 87.06359 24.18976 -0.4083731 87.08922 24.09458 -0.7483041 87.28682 24.10529 -0.7423923 87.29227 24.17575 -0.572845 87.18511 24.16117 -0.7204724 87.31249 24.00415 -0.4936304 86.91131 24.03025 -0.1141268 86.88474 24.07272 -0.1101409 86.94167 24.13232 -0.1070464 86.98587 24.26914 -0.2581462 87.04036 24.26053 -0.4052832 87.09565 24.24598 -0.5660703 87.19409 24.21653 -0.7101369 87.32202 24.059 -0.7736669 87.26343 24.06388 -0.4411011 87.02092 24.02846 -0.8070735 87.23262 24.02441 -0.466675 86.96756 41.15294 -1.077446 87.4852 41.19649 -1.144767 87.54843 41.26687 -1.144155 87.59368 41.62881 -0.8208937 87.41684 41.75858 -0.7784787 87.39725 41.879 -0.8272652 87.38573 41.82053 -0.7969099 87.39762 41.92753 -0.8669204 87.36216 41.82089 -1.033609 87.53378 41.8239 -0.9360741 87.49765 41.78082 -0.9809741 87.54408 41.3449 -1.1383 87.62658 41.76171 -1.078126 87.57921 41.6614 -1.05703 87.6178 41.58773 -1.086584 87.64007 41.50873 -1.109761 87.64963 41.96166 -0.9113526 87.32994 41.93701 -0.9747087 87.39406 41.85815 -0.8828273 87.44258 41.77149 -0.8944233 87.49845 41.68342 -0.9710536 87.57553 41.72581 -1.021948 87.5853 41.55973 -1.028537 87.62195 41.41542 -1.064446 87.62406 41.42642 -1.126974 87.6453 41.71593 -0.8638052 87.48609 41.62179 -0.8314024 87.42771 41.63922 -0.9303699 87.5517 41.54452 -0.8965955 87.48725 41.53234 -0.9800114 87.5892 41.49174 -0.920289 87.50044 41.40832 -1.011003 87.5884 41.38921 -0.9461196 87.49167 41.28529 -1.024252 87.54575 41.27822 -0.9527381 87.43393 41.27239 -1.079749 87.57626 41.18169 -1.021989 87.46739 41.25408 -0.9506341 87.41223 41.19381 -1.005102 87.45891 24.85203 -1.090845 87.4877 24.8382 -1.057169 87.4802 24.71783 -1.040775 87.55757 24.13662 -0.8135201 87.3868 24.02676 -0.9276655 87.30904 24.23721 -1.083187 87.57891 24.30457 -0.7694419 87.38236 24.36656 -0.8128817 87.40848 24.69373 -0.9787024 87.50413 24.63158 -0.9490539 87.48503 24.59327 -0.9673613 87.54013 24.51581 -0.9229715 87.50121 24.49264 -0.9414625 87.54298 24.42613 -0.8780741 87.47243 24.40637 -0.9008815 87.51531 24.34232 -0.8459314 87.46279 24.74592 -0.9506376 87.41223 24.79369 -0.9902547 87.44976 24.80619 -1.005101 87.4589 24.86082 -1.120725 87.49118 24.73032 -1.124545 87.59114 24.57475 -1.107466 87.64112 24.41876 -1.068112 87.63593 24.28743 -1.006661 87.58473 24.13149 -0.9911025 87.48374 24.06821 -0.8661974 87.35578 24.19244 -0.9248337 87.50144 24.58781 -1.026518 87.60144 24.45771 -0.9937679 87.60063 24.34768 -0.942568 87.56118 24.26758 -0.8739933 87.4931 24.22086 -0.7799501 87.3954 38.58266 -1.265658 85.42192 38.0027 -1.254509 85.09873 38.0008 -1.3 85.10245 40.50654 -1.099363 86.85938 39.67734 -1.112204 86.15818 39.3718 -1.161583 85.93339 38.8666 -1.166574 85.58475 38.86814 -1.23122 85.59597 39.13864 -1.193938 85.77218 38.91741 -1.013101 85.47266 38.93813 -0.9951477 85.43611 38.42306 -1.040521 85.0789 38.00878 -1.207976 85.08683 38.01179 -1.192793 85.08094 38.04894 -1.095725 85.00815 38.87203 -1.118792 85.56632 38.88296 -1.075791 85.54017 38.07262 -1.067553 84.96174 38.89852 -1.040076 85.50815 38.09416 -1.054021 84.91956 38.17322 -1.053253 84.96015 39.70002 -0.9708371 86.10929 39.6865 -1.013377 86.13275 39.67872 -1.061461 86.14949 39.88504 -0.8982012 86.16999 39.71797 -0.9358491 86.08103 36.03111 -1.3 84.32586 36.03776 -1.192793 84.30265 36.04703 -1.140165 84.27033 36.06028 -1.095725 84.22409 36.08672 -1.054635 84.13187 36.06475 -1.085199 84.20851 37.64339 -1.054168 84.70291 34.98267 -0.6927235 84.08016 35.13634 -0.9017297 84.10945 34.92484 -0.493286 84.06729 35.31073 -1.059956 84.14544 35.30781 -1.02539 84.14346 35.69898 -1.252971 84.23626 35.72809 -1.161207 84.22421 34.91479 -0.04999995 84.04461 34.80889 -0.04999995 84.04972 34.92568 -0.58349 84.06987 35.08248 -0.04999977 83.89521 35.06483 -0.04999995 83.93102 35.08891 -0.1633976 83.89642 35.13315 -0.420019 83.94552 35.61589 -0.9654099 84.0666 35.61989 -0.940301 84.00969 35.45744 -0.8618904 84.02318 35.34943 -0.7331584 83.94863 35.33069 -0.7427794 83.99105 35.25553 -0.6149687 83.92908 35.15098 -0.4155792 83.90827 35.8112 -1.016515 84.05717 35.78966 -1.038072 84.11824 35.76006 -1.086883 84.18076 35.41561 -0.8992136 84.08662 35.83893 -1.284456 84.27266 35.36118 -0.9586004 84.13071 35.22177 -0.8242394 84.09913 35.00471 -0.462878 84.05438 34.92969 -0.04999995 84.04011 35.28455 -0.7739653 84.05481 35.08044 -0.4362709 84.00975 35.02339 -0.04999995 83.98326 34.91479 0 84.04461 34.80889 0 84.04975 35.02339 0 83.98326 35.08243 0 83.89521 30.97962 0 83.98611 30.92022 0 83.90165 30.92017 -0.04999959 83.90167 31.19111 -0.04999995 84.04972 31.19111 0 84.04975 31.08601 -0.04999995 84.04483 31.08601 0 84.04483 31.02175 -0.04999995 84.01776 30.97962 -0.04999995 83.98611 30.36625 -0.9513881 84.02427 30.19399 -1.021387 84.07627 30.22372 -1.05946 84.15138 30.46288 -0.8951597 83.9988 30.56096 -0.8783322 84.05673 30.6903 -0.7557193 84.02453 30.15953 -1.027014 84.07438 29.91607 -1.056843 84.1416 29.94184 -1.1014 84.23152 30.94496 -0.8026482 84.09368 31.15815 -0.338993 84.05531 31.02682 -0.4742746 84.06307 29.96771 -1.253852 84.32173 29.96889 -1.3 84.32586 30.282 -1.193252 84.23295 30.53352 -1.158682 84.18012 30.65942 -0.9851121 84.1395 30.80379 -0.8459738 84.10773 30.70613 -0.6722382 83.94465 30.89025 -0.4265536 83.97928 30.865 -0.3798661 83.91233 30.40022 -0.9844451 84.09996 30.2527 -1.116214 84.20278 30.60573 -0.9227964 84.10888 30.94965 -0.4461918 84.03208 30.74086 -0.7930976 84.07695 29.96275 -1.196823 84.30445 27.9973 -1.254509 85.09873 27.9992 -1.3 85.10245 29.43873 -1.057074 84.29083 27.98907 -1.196823 85.08261 27.95458 -1.1014 85.01502 27.92738 -1.067553 84.96175 27.91344 -1.057648 84.93444 29.81689 -5.1 84.40724 29.72598 -5.307336 84.67774 30.59254 -5.307336 85.20788 29.09453 -6 84.83998 29.63717 -6 84.94196 29.65699 -5.652791 84.88299 31.06221 -5.652791 86.83775 30.93902 -5.652791 86.13565 31 -6 86.83775 30.88052 -6 86.15683 30.44122 -5.652791 85.36275 30.05409 -6 85.13807 30.39774 -6 85.40725 30.7476 -6 85.86517 28.7422 -5.652791 84.79171 28.74998 -6 84.85343 28.11111 -6 85.04614 28.61183 -5.654841 84.81317 28.74354 -5.571221 84.7569 29.19073 -5.321292 84.5802 30.79198 -5.1 85.00377 31.14261 -5.307336 86.06193 31.41093 -5.1 85.96478 31.27874 -5.307336 86.83775 31.56411 -5.1 86.83775 29.7586 -5.1 84.38842 36.18311 -5.1 84.40724 36.2414 -5.1 84.38842 35.00168 -5.1 84.08366 33.78845 -5.1 93.06198 34.43589 -5.1 93.50781 34.43589 -5.1 86.83775 31.56411 -5.1 93.50781 32.21154 -5.1 93.06198 30.99831 -5.1 84.08366 33 -5.1 92.9 34.58906 -5.1 85.96478 35.20802 -5.1 85.00377 37.88889 -6 85.04614 37.40564 -5.66539 84.82048 37.2578 -5.652791 84.79171 36.36283 -6 84.94196 36.92373 -6 84.83921 37.25003 -6 84.85343 35.95629 -6 85.13169 36.34301 -5.652791 84.88299 35.60226 -6 85.40725 35.55878 -5.652791 85.36275 35.25537 -6 85.85985 35.06098 -5.652791 86.13565 35.11948 -6 86.15683 34.93778 -5.652791 86.83775 35 -6 86.83775 34.72126 -5.307336 86.83775 36.27402 -5.307336 84.67774 36.78052 -5.30759 84.56984 36.77446 -5.304682 84.56762 34.85739 -5.307336 86.06193 35.40746 -5.307336 85.20788 37.25272 -5.568563 84.75517 31 -6 93.86019 31 -6.227223 93.90001 31 -9 93.9 34.33501 -5.057784 93.79937 33.99983 -5 93.16767 35 -6 93.86019 34.96499 -5.737719 93.9 35.00038 -6 93.89997 34.73337 -5.320165 93.9 34.36602 -5.0694 93.9 31.99999 -5 93.16774 32.21154 -4.999992 93.06198 33 -4.999992 92.9 33.78845 -4.999992 93.06198 30.99962 -6 93.89998 31.09891 -5.566365 93.9 31.29627 -5.28954 93.9 31.40271 -5.197976 93.9 31.63398 -5.069402 93.9 30.9416 -6.110831 94.22512 30.94383 -6 94.199 30.98504 -6 94.03699 31.22129 -7.321883 94.81444 31.11135 -7.128067 94.55799 31.13299 -9 94.61714 31.05423 -6.962121 94.36259 31.04977 -6.947753 94.34338 31.03434 -6.869681 94.26905 31.0192 -6.76355 94.17649 31.00396 -6.538232 94.02583 31.00025 -6.330717 93.93131 31.51429 -9 95.2389 31.51428 -7.584464 95.2389 31.35187 -7.459646 95.03299 32 -10 86.83775 32 -10 93.9 31.65884 -9.940007 86.83775 31.5 -9.866025 93.9 31.00878 -9.132231 93.9 31.06004 -9.341276 86.83775 31.13397 -9.5 93.9 31.13397 -9.5 86.83775 31.17794 -9.569395 93.9 31.29294 -9.707152 86.83775 31.5 -9.866025 86.83775 35.05617 -6 94.199 35.05841 -6.110832 94.22512 35 -6.227205 93.9 34.99003 -5.900344 94.04128 34.99507 -6 94.04039 34.61861 -5.218513 94.0312 34.82048 -5.436984 94.04756 34.94996 -5.705057 94.04818 34.88914 -5.555395 94.05845 34.81777 -5.435908 94.0705 34.58789 -5.201189 94.10909 34.43162 -5.107371 94.13506 34.13533 -5 93.56896 34.23237 -5.000014 93.99291 32.3125 -5 93.70922 33 -5 93.525 33.6875 -5 93.70922 34.19078 -5 94.2125 34.25716 -5 94.34306 31.86471 -5 93.56899 31.80921 -5 94.2125 31.76763 -5.000012 93.99292 31.74285 -5 94.34306 31.38139 -5.218513 94.03119 31.56835 -5.107384 94.13504 31.00494 -6 94.04039 31.01239 -5.878861 94.0417 31.17952 -5.436984 94.04756 31.05859 -5.679071 94.04963 31.18107 -5.437565 94.07031 31.48885 -5.150352 94.12187 35 -9 93.9 34.93997 -9.34125 93.9 34.93996 -9.34128 86.83775 34.92656 -9.376144 93.9 34.70711 -9.707108 93.9 34.70705 -9.707159 86.83775 34.34125 -9.939973 93.9 34.34114 -9.940012 86.83775 34 -10 93.9 34 -10 86.83775 34.48571 -7.58443 95.2389 34.48571 -9 95.2389 34.63783 -7.469259 95.04784 34.86701 -9 94.61714 34.78006 -7.317301 94.8118 35.00001 -6.301752 93.91022 34.99816 -6.47411 93.98577 34.97975 -6.770859 94.18389 34.97167 -6.831212 94.23543 34.95847 -6.906963 94.30543 34.88945 -7.138579 94.55567 35.06439 -6.356179 94.47943 35.0595 -6.405199 94.56475 34.97082 -6.67067 94.35309 34.96985 -6.813028 94.2475 35.064 -6.22993 94.31398 34.99765 -6.434971 94.03704 34.8775 -6.983185 94.63064 34.88625 -6.869753 94.69171 34.93365 -6.690876 94.80213 35.00605 -6.55226 94.9 35.06564 -6.323883 94.42983 32.29546 -9.75 94.12145 32.20207 -9.75 94.21751 32.19018 -9.837027 94.20734 33.98791 -9.999927 94.055 33.92346 -9.985174 94.11013 33.5555 -9.985174 93.81922 33.54382 -10 93.71924 33 -9.985174 93.68482 33 -10 93.60003 32.4445 -9.985174 93.81922 32.45618 -10 93.71924 32.07654 -9.985174 94.11013 32.01211 -9.999983 94.05502 32.52001 -9.75 93.96614 32.51287 -9.837027 93.95223 32.75154 -9.75 93.87982 33 -9.837027 93.83436 33 -9.75 93.85 33.26765 -9.75 93.88468 33.48713 -9.837027 93.95223 33.47999 -9.75 93.96614 33.71908 -9.75 94.13488 33.80981 -9.837027 94.20734 33.79789 -9.75 94.21754 33.85421 -9.927609 94.16936 33.51384 -9.927609 93.90026 33 -9.927609 93.77594 32.48616 -9.927609 93.90026 32.14579 -9.927609 94.16936 31.10618 -6.825238 94.71823 31.122 -6.964532 94.63985 31.00026 -6.319462 93.95272 31.00427 -6.480894 94.08923 31.02008 -6.627499 94.28666 30.99395 -6.552258 94.9 30.93674 -6.372003 94.50564 30.93927 -6.16162 94.25527 30.93483 -6.262164 94.34905 30.9344 -6.326043 94.43299 30.93535 -6.351727 94.47229 31.59693 -7.772179 95.2993 31.57388 -9 95.28739 31.62465 -9 95.30992 31.67754 -7.953423 95.32053 31.67881 -7.956234 95.32064 31.78055 -8.178977 95.30821 31.77619 -8.169442 95.30964 31.78795 -9 95.30555 31.67887 -9 95.32064 31.94318 -8.529528 95.12952 31.91003 -8.455853 95.20715 31.87997 -9 95.24507 31.87771 -8.386798 95.24739 31.8744 -8.379746 95.25066 31.83209 -8.289469 95.28379 31.93707 -9 95.1509 31.95 -9 95.07154 31.95 -8.549263 95.07154 31.53088 -9.5211 95.0301 31.51591 -9.174027 95.21783 31.14119 -9.132231 94.61399 31.53543 -9.570299 94.98289 31.71309 -9.920287 94.42861 31.65691 -9.872871 94.5404 31.63372 -9.886041 94.42481 31.59563 -9.787303 94.70063 31.59088 -9.778019 94.71581 31.55185 -9.6671 94.87353 31.54844 -9.651947 94.89221 31.2991 -9.569395 94.55334 31.96601 -9.998608 94.09786 31.76841 -9.951728 94.33737 31.74093 -9.937585 94.38081 31.08132 -6.642837 95.17571 31.209 -6.917225 94.99237 31.22852 -7.018667 94.93914 31.35339 -7.052024 95.19787 31.52528 -7.171008 95.38873 31.21663 -6.738239 95.40651 31.28677 -6.777135 95.50449 31.39623 -6.82827 95.63745 34.27684 -5.020742 94.38979 34.37583 -5.079031 94.16043 34.32773 -5.051606 94.22497 31.72316 -5.020742 94.38979 31.66431 -5.056387 94.2099 31.60711 -5.088003 94.14871 34.81097 -9.34125 94.59562 34.59359 -9.707108 94.51212 34.3752 -9.834509 94.61721 34.2516 -9.941665 94.3689 34.23165 -9.951685 94.3376 34.08684 -9.993285 94.15214 34.22047 -9.956727 94.32082 34.47843 -9.355033 95.14816 34.46923 -9.521179 95.03018 34.4391 -9.702023 94.82761 34.43605 -9.711852 94.81417 34.05 -8.549271 95.07154 34.05 -9 95.07154 34.05031 -8.547314 95.0841 34.06278 -9 95.15044 34.05974 -8.522743 95.14064 34.07418 -8.490302 95.1788 34.11923 -9 95.24423 34.10463 -8.42458 95.22753 34.15366 -8.319835 95.27423 34.21036 -9 95.30491 34.20526 -8.209673 95.3029 34.31867 -9 95.32084 34.26054 -8.089064 95.31841 34.21869 -8.180674 95.30795 34.41701 -7.741687 95.29246 34.39163 -7.798947 95.30414 34.4234 -9 95.28896 34.34955 -7.893075 95.31658 34.29542 -8.012877 95.3215 34.43127 -7.709235 95.2843 34.62781 -7.257876 95.1011 34.7826 -6.955661 94.97019 34.64622 -7.053874 95.1969 34.7778 -6.741575 95.4146 34.6038 -6.828299 95.63746 34.91865 -6.642857 95.17577 34.46258 -7.379713 95.29716 34.46906 -7.213155 95.36735 34.47443 -7.172865 95.38775 34.05 -8.550001 94.9 34.0497 -8.525 94.875 33.99853 -8.824703 94.57533 31.95385 -9.4864 94.81023 32.03292 -9.689511 94.49103 32.00783 -8.843651 94.55625 31.9503 -8.525 94.875 31.95 -8.550001 94.9 31.95 -9.390825 94.9 32.7467 -9.51899 93.88156 32.48033 -9.412385 93.98764 32.28746 -9.27122 94.12892 32.10791 -9.053791 94.34642 32.08988 -9.023629 94.37659 33.72588 -9.258679 94.14145 33.54336 -9.398475 94.0016 33.27078 -9.514483 93.88589 33.19421 -9.531883 93.86824 33.00041 -9.55 93.84976 32.88233 -9.543387 93.85675 33.8481 -9.746126 94.28113 33.8872 -9.061576 94.33866 34.00362 -9.641942 94.59137 33.91034 -9.023241 94.37699 34.04996 -9.390825 94.9 34.15275 -9.954818 94.37821 34.36767 -9.705039 94.89299 34.442 -9.677424 94.86559 34.04603 -9.676257 94.69644 34.05802 -9.435276 94.94439 34.17105 -9.79571 94.72914 34.13876 -9.526015 95.03501 34.09893 -9.74638 94.72039 34.08633 -9.482668 94.99172 34.06506 -9.451295 94.96039 34.4404 -9.537191 95.04617 34.37535 -9.559496 95.06844 34.35186 -9.563876 95.07281 34.35929 -9.706657 94.89503 34.29588 -9.567699 95.07663 34.27201 -9.709021 94.90605 34.26409 -9.56589 95.07482 34.21229 -9.556478 95.06543 34.35 -9.816774 94.69847 34.34188 -9.818538 94.70127 34.2565 -9.821117 94.72244 34.17951 -9.545824 95.05479 33.95848 -9.796837 94.4354 34.00768 -9.873312 94.43048 34.07426 -9.92711 94.41078 31.63874 -9.699225 94.90526 31.65294 -9.806904 94.72328 31.72714 -9.811209 94.7417 31.94198 -9.435276 94.94439 31.8155 -9.943811 94.41733 31.68796 -9.882285 94.55451 31.5752 -9.67939 94.88465 31.78771 -9.556477 95.06543 31.72254 -9.567003 95.07595 32.1457 -9.874311 94.23313 32.16789 -9.809807 94.24735 32.03525 -9.76208 94.46656 31.96056 -9.64456 94.70318 31.92858 -9.701764 94.72686 32.00445 -9.82446 94.47052 31.87569 -9.754546 94.74363 31.95436 -9.882019 94.46404 31.80535 -9.793406 94.74916 31.88837 -9.924396 94.44567 31.99051 -9.997722 94.11711 32.05228 -9.977646 94.16477 32.10643 -9.933827 94.20522 31.5596 -9.537191 95.04617 31.62465 -9.559496 95.06844 31.64612 -9.563566 95.0725 31.70412 -9.567699 95.07663 31.86124 -9.526015 95.03501 31.91366 -9.482668 94.99172 31.95 -8.550001 95 31.95 -9.183609 95.03717 31.95 -9.3482 94.93914 31.86124 -9.471044 95.08547 31.78771 -9.498726 95.11843 31.5596 -9.257676 95.2303 31.5596 -9.481201 95.09756 31.62465 -9.501469 95.12171 31.70412 -9.508922 95.13058 31.62465 -9.268963 95.25973 31.70412 -9.273114 95.27056 31.78771 -9.267436 95.25575 31.86124 -9.25202 95.21555 31.91366 -9.431657 95.03855 31.94198 -9.388591 94.98725 31.91366 -9.230085 95.15835 31.94198 -9.206103 95.09582 34.08633 -9.264457 95.14406 34.4404 -9.295998 95.21437 34.4404 -9.048569 95.27672 34.37535 -9.050728 95.30817 34.37535 -9.308901 95.24314 34.29588 -9.313645 95.2537 34.29588 -9.051522 95.31974 34.21229 -9.050436 95.30391 34.21229 -9.307154 95.23924 34.13876 -9.289532 95.19995 34.13876 -9.047489 95.26097 34.08633 -9.043293 95.19985 34.05802 -9.237042 95.08296 34.05802 -9.038707 95.13303 34.05 -9.211328 95.02565 34.05 -9.034406 95.07036 34.05 -8.550001 95 34.05 -8.5 94.9 34.0497 -8.525 94.9 33.99108 -8.203207 94.9 32.29159 -7.774975 94.9 32.00892 -8.203207 94.9 31.98578 -8.22824 94.9 31.95898 -8.362949 94.9 32.09067 -7.975 94.9 32.475 -7.590673 94.9 32.74344 -7.531826 94.9 33 -7.45 94.9 33.25656 -7.531826 94.9 33.525 -7.590673 94.9 33.7084 -7.774975 94.9 33.90933 -7.975 94.9 33.8763 -7.971558 94.9 34.01422 -8.22824 94.9 31.9503 -8.525 94.9 31.95 -8.5 94.9 31.95546 -8.443077 94.9 31.967 -8.361807 94.9 32.00892 -8.203207 95 33.99108 -8.203207 95 33.7084 -7.774975 95 32.29159 -7.774975 95 32.74344 -7.531826 95 33 -7.5 95 33.25656 -7.531826 95 33.97628 -8.162852 95.06352 33.74246 -7.806961 95.05615 33.3865 -7.573192 95.0513 33 -7.49948 95.04977 32.6135 -7.573191 95.0513 32.25754 -7.806956 95.05615 32.13928 -7.948007 95.05907 32.02372 -8.162842 95.06352 34.35395 -7.347208 95.41812 34.28274 -7.441043 95.42592 34.21648 -7.537508 95.41856 34.15561 -7.636309 95.3983 34.10323 -7.732593 95.368 34.0497 -7.848978 95.31872 34.01195 -7.953299 95.26273 33.98871 -8.042631 95.20401 33.97801 -8.110161 95.14789 33.97573 -8.141011 95.11294 33.97578 -8.159037 95.08003 33.38548 -7.569951 95.10176 33.39995 -7.529678 95.30545 33.06838 -7.468299 95.38399 33.44009 -7.472164 95.46768 33.32931 -7.363168 95.73629 33.83398 -7.157603 95.94299 33.78097 -7.179602 95.9368 33.78773 -7.187556 95.91512 33.74215 -7.195647 95.93025 33.63117 -7.297863 95.78461 33.51607 -7.393321 95.63217 33.74117 -7.803498 95.08193 33.73904 -7.787477 95.13398 33.7395 -7.759815 95.19061 33.75121 -7.698329 95.28464 33.78419 -7.615329 95.38665 33.84343 -7.516356 95.48685 33.93196 -7.40364 95.57754 34.02114 -7.308665 95.63498 33.9438 -7.111667 95.94604 34.12671 -7.209578 95.67518 34.10569 -7.043078 95.92648 34.24327 -7.111155 95.69251 34.24181 -6.984648 95.88652 34.36992 -7.013665 95.68259 31.67946 -7.01647 95.73749 31.45376 -6.864865 95.66916 31.52666 -7.039707 95.51348 32.17371 -7.160788 95.94232 32.33335 -7.269131 95.82433 32.20597 -7.174181 95.93864 31.9931 -7.084999 95.94198 31.95223 -7.231753 95.69901 32.07134 -7.344212 95.63395 32.9061 -7.457777 95.4401 32.61391 -7.551449 95.21464 32.99903 -7.498518 95.08433 31.95326 -8.132639 95.2191 31.97204 -8.207195 95.16957 31.9816 -8.258778 95.1205 31.83468 -7.824126 95.34141 31.88289 -7.932943 95.30914 31.92376 -8.039802 95.26661 31.77773 -7.710232 95.36357 31.71921 -7.604649 95.37248 31.65624 -7.501065 95.36799 32.64782 -7.353991 95.75461 32.45711 -7.366322 95.68009 32.54193 -7.447352 95.52381 32.59178 -7.509815 95.36598 31.44344 -6.84847 95.68663 31.77517 -6.992025 95.89263 31.69442 -7.187157 95.56213 31.56114 -7.361258 95.33145 32.30554 -7.742834 95.14823 32.30108 -7.698507 95.23943 32.28078 -7.632773 95.34064 32.23711 -7.548548 95.44659 32.16532 -7.448741 95.54931 32.14277 -7.924562 95.12395 32.14157 -7.877679 95.1888 32.1293 -7.808838 95.26213 32.0999 -7.72158 95.34008 32.04948 -7.619289 95.41664 31.982 -7.513249 95.48047 31.89534 -7.400285 95.53027 31.80081 -7.29368 95.55776 33.25592 -7.264546 96.00752 34.06141 -6.642851 96.52194 34.34624 -6.642852 96.2946 34.63534 -6.642854 95.94064 34.85683 -6.642856 95.45629 32.74405 -7.264546 96.0075 31.76016 -6.642842 96.39 31.65326 -6.642842 96.29413 31.2804 -6.642839 95.7946 32.48365 -6.642845 96.76834 31.14296 -6.642838 95.45564 33.49044 -6.642848 96.7753 33.30014 -6.642848 96.815 32.3125 -5.020742 96.09078 32.04468 -5.020742 95.88893 31.81805 -5.151254 96.12353 31.34028 -5.151254 94.52671 34.97233 -5.471708 94.45714 34.65985 -5.151254 94.5273 35.11477 -5.9006 94.42516 35.07625 -5.9006 95.52203 35.02044 -6.349895 95.50531 34.46487 -6.349895 96.41748 33.53366 -6.349895 96.94054 31.53459 -6.349895 96.41696 32.46561 -6.349895 96.94036 30.97934 -6.349895 95.5046 30.8854 -5.9006 94.4244 31.65851 -5.020742 94.59828 31.37021 -5.151254 95.38764 31.80921 -5.020742 95.5875 31.6827 -5.020742 95.29415 31.625 -5.020742 94.9 32.65163 -5.020742 96.23014 32.56898 -5.151254 96.54567 33 -5.020742 96.275 33.43043 -5.151254 96.54583 33.3479 -5.020742 96.23026 33.6875 -5.020742 96.09078 34.18151 -5.151254 96.12395 33.95497 -5.020742 95.88928 34.19078 -5.020742 95.5875 34.62961 -5.151254 95.38822 34.31716 -5.020742 95.29462 34.375 -5.020742 94.9 34.34159 -5.020742 94.59877 31.02782 -5.471708 94.45644 31.06339 -5.471708 95.47945 31.59554 -5.471708 96.35388 32.48784 -5.471708 96.85549 33.51146 -5.471708 96.85567 34.40394 -5.471708 96.35437 34.93641 -5.471708 95.48014 30.92353 -5.9006 95.5213 31.49412 -5.9006 96.45886 32.45085 -5.9006 96.99671 33.5484 -5.9006 96.99691 34.50533 -5.9006 96.45941 27.4052 -1.264313 85.42909 27.13193 -1.231151 85.59593 26.74322 -1.177315 85.85275 25.96109 -1.096133 86.44697 26.3221 -1.124149 86.15897 27.475 0 83.65311 38.525 0 83.65311 26.19634 0 85.40884 25.62152 -0.04999995 85.99085 26.19634 -0.04999995 85.40884 39.79852 0 85.40318 39.79852 -0.04999995 85.40318 40.35518 -0.04999995 85.96903 39.72364 0.0670588 46.24539 36.34887 0.07887524 44.29877 25.60491 0.1412824 37.39509 30.37539 0.1153646 41.04082 28.33421 0.1303206 39.7014 26.55311 0.1396799 38.28554 25.609 0.1412824 37.39917 32.70687 0.09875792 42.3628 23.12089 0.2092217 31.98277 24.34239 0.1507403 35.7238 25.11744 0.1424378 36.85766 25.25393 0.141864 37.01896 23.73982 0.1669594 34.4213 23.49897 0.1781553 33.69792 26.375 -11 0 26.375 9.334449 -5.819627 26.375 10.8055 -2.05942 26.375 -10.25895 -3.96913 26.375 -8.135639 -7.403471 26.375 -4.916159 -9.840294 26.375 6.605706 -8.795718 26.375 2.986932 -10.5867 26.375 -1.034292 -10.95127 17.75 7.986611 -0.4626535 17.75 -7.772853 -1.892814 17.75 -0.3104059 -7.993976 17.75 -2.344545 -7.648732 17.75 7.602675 -2.489845 17.75 6.713053 -4.351428 17.75 5.376917 -5.923577 17.75 3.683139 -7.101725 17.75 -4.222738 -6.794739 17.75 -5.820059 -5.488799 17.75 -7.030263 -3.817775 17.75 1.744379 -7.807505 34.88123 -0.1999999 16.71603 37.38357 -0.1999999 16.80893 -17.86531 -7.997167 82.97203 -18.10161 -7.997594 83.07537 -12.89557 -0.04999995 84.04897 -13.09519 0 83.85195 -13.09525 -0.04999947 83.85195 -13.08532 -0.04999995 83.88755 -13.06499 0 83.93075 -12.89557 0 84.04897 -12.99306 0 84.00818 -12.99306 -0.04999995 84.00818 -13.06499 -0.04999995 83.93075 -13.81176 -1.02311 84.07808 -12.97271 -0.4730225 84.06298 -13.19439 -0.8438977 84.10735 -13.34698 -0.9903015 84.14096 -13.72462 -1.195456 84.23472 -13.65556 -0.9457876 83.94152 -13.48198 -0.8548734 83.98201 -13.50221 -0.8516258 83.89875 -13.34787 -0.7310742 83.94752 -13.29359 -0.641323 83.8462 -13.15275 -0.4137671 83.90203 -13.16572 -0.4125506 83.85056 -13.13603 -0.3277608 83.85123 -13.78219 -1.06134 84.15318 -13.7535 -1.118252 84.20455 -13.83503 -1.014258 83.99601 -13.63958 -0.9543805 84.02597 -13.60575 -0.9876182 84.10163 -13.40027 -0.9276301 84.11035 -13.44478 -0.8828918 84.05821 -13.30807 -0.7538858 84.02414 -13.10933 -0.4254429 83.97919 -13.0499 -0.4450228 84.03199 -13.25744 -0.7911612 84.07657 -17.08444 -0.04999995 84.52149 -16.21419 -0.04999995 83.06681 -16.21419 0 83.06681 -18.4464 -0.04999995 86.05361 -16.54821 -0.9906947 84.90755 -16.84403 -0.7604314 84.69458 -18.24633 -0.7604314 86.27209 -19.45924 -0.8517897 87.35362 -18.40416 -0.398106 86.09974 -16.07061 -0.5937921 83.13919 -16.15853 -0.3981055 83.09535 -17.03368 -0.398106 84.55803 -16.18902 -0.2862781 83.0798 -15.94838 -0.7604385 83.1976 -15.86648 -0.8395361 83.23513 -15.59529 -0.9976264 83.35047 -13.64543 -0.9407109 83.82212 19.60195 10.75361 -0.622942 20.75 10.98159 -0.6361486 17.97836 -8.888307 -2.164445 18.62868 -9.833944 -2.394722 19.60195 -10.4658 -2.548589 19.60195 10.23666 -3.352465 20.75 10.8055 -2.05942 20.75 10.45368 -3.423538 20.75 9.334449 -5.819627 19.60195 9.038824 -5.859001 20.75 9.230448 -5.983213 20.75 7.39326 -8.144919 19.60195 7.239776 -7.975829 20.75 6.605706 -8.795718 19.60195 4.95918 -9.562151 20.75 5.064316 -9.764871 20.75 2.986932 -10.5867 19.60195 2.348728 -10.51245 20.75 2.398522 -10.73532 20.75 -0.4268081 -10.99172 19.60195 -0.4179475 -10.76353 20.75 -1.034292 -10.95127 19.60195 -3.156824 -10.29867 20.75 -3.223749 -10.51701 19.60195 -5.685726 -9.14881 20.75 -4.916159 -9.840294 20.75 -5.806265 -9.342766 20.75 -8.002581 -7.547098 19.60195 -7.836447 -7.39042 20.75 -8.135639 -7.403471 19.60195 -9.465931 -5.140461 20.75 -10.68767 -2.602619 20.75 -10.25895 -3.96913 20.75 -9.666612 -5.249441 18.62868 -8.894443 -4.830115 18.62868 -7.363335 -6.944236 18.62868 -5.342461 -8.596467 18.62868 -2.966236 -9.676909 18.62868 -0.3927147 -10.1137 18.62868 2.206928 -9.877783 18.62868 4.659779 -8.984854 18.62868 6.802687 -7.494302 18.62868 8.493121 -5.505274 18.62868 9.618639 -3.150065 18.62868 10.10438 -0.5853329 17.97836 -8.03915 -4.365649 17.97836 -6.655274 -6.276476 17.97836 -4.828728 -7.769827 17.97836 -2.681002 -8.746374 17.97836 -0.3549512 -9.141162 17.97836 1.994709 -8.927932 17.97836 4.211693 -8.120867 17.97836 6.148538 -6.773648 17.97836 7.676418 -4.975885 17.97836 8.693708 -2.847155 17.97836 9.13274 -0.529047 18.43259 -8 89.47892 3.55569 -8 89.48818 44.82174 2.44762 50.58581 44.48014 1.4 50.47461 44.87646 2.8 50.32464 44.87638 2.777199 50.32447 44.87353 2.69804 50.33348 44.87194 2.67663 50.33959 44.84444 2.486835 50.44276 44.83523 2.455887 50.48719 44.8269 2.442913 50.54039 43.46329 0.3751289 50.34667 18.21922 -0.3928334 89.92335 19.45924 -0.851789 91.35362 18.06184 -0.7515894 90.08668 17.76386 -0.9072189 90.0706 16.73537 -0.9560475 89.0206 16.93814 -0.9951477 89.43611 16.24802 -1.046932 88.93543 16.16749 -1.049693 88.91319 17.40098 -0.3412906 89.00681 17.25811 -0.5992912 89.0223 17.10627 -0.7531332 89.03121 17.03578 -0.8059881 89.03273 17.67872 -1.061461 90.14949 17.67734 -1.112204 90.15818 16.8666 -1.166574 89.58475 16.87203 -1.118792 89.56632 16.88296 -1.075791 89.54017 16.89852 -1.040076 89.50814 16.91742 -1.013101 89.47266 17.68651 -1.013377 90.13276 17.70002 -0.9708371 90.10929 17.71797 -0.9358491 90.08103 17.86035 -7.382683 90.20426 17.99462 -7.707107 90.03407 18.19556 -7.92388 89.77937 6.262549 -1.055051 88.75128 5.893211 -1.05057 88.89481 5.906222 -1.054174 88.92031 5.929673 -1.069616 88.96624 5.947734 -1.090751 89.00164 5.968224 -1.12847 89.04177 5.980669 -1.163198 89.06616 5.991216 -1.207976 89.08683 5.997298 -1.254509 89.09873 5.99268 -1.216566 89.08969 7.100031 -7.468149 88.72377 6.0594 -7.468149 88.9419 3.502165 -0.8857862 90.69766 4.236092 -0.9072052 90.07065 3.939553 -0.7515902 90.08535 2.540755 -0.8517897 91.35362 3.782141 -0.3928339 89.92204 4.593685 -0.3257692 89.0061 4.894826 -0.7540283 89.03125 4.761369 -0.6231864 89.02388 5.021308 -0.8428159 89.03275 5.394692 -0.99485 89.00594 5.061837 -0.9951457 89.43614 5.832519 -1.049693 88.91319 5.082557 -1.0131 89.47267 5.133378 -1.166575 89.58477 5.13316 -1.216041 89.59458 4.322598 -1.112192 90.15823 3.129515 -1.067318 91.20213 5.101449 -1.040076 89.50817 5.117017 -1.075791 89.54019 5.127941 -1.118793 89.56634 3.090571 -0.9775598 91.17549 3.561327 -0.9505965 90.73496 3.590271 -1.043631 90.76305 4.299919 -0.9708256 90.10933 4.28197 -0.935837 90.08109 4.32122 -1.061449 90.14953 4.313435 -1.013366 90.1328 3.793091 -7.92388 89.78833 4.128827 -7.382683 90.21281 3.99435 -7.707107 90.04279 40.31949 -0.3686949 86.00705 40.18494 -0.7099729 86.15036 38.92451 -0.9537629 85.2577 39.36495 -0.7585376 85.35595 39.62233 -0.5290173 85.38976 39.7513 -0.3051672 85.40035 26.08406 -0.8962015 86.1956 25.42588 -0.8886124 86.76639 25.56133 -0.9505965 86.73496 25.12952 -1.067318 87.20212 27.85792 -1.057298 84.96306 27.13316 -1.216041 85.59458 26.3226 -1.112192 86.15823 25.59027 -1.043631 86.76305 27.10145 -1.040076 85.50817 27.08256 -1.0131 85.47268 27.51212 -1.036461 85.12217 27.11702 -1.075791 85.54019 27.12794 -1.118793 85.56634 27.13338 -1.166575 85.58477 25.09057 -0.9775598 87.17549 26.32122 -1.061449 86.14953 26.31344 -1.013366 86.13281 26.29992 -0.9708256 86.10933 26.28197 -0.935837 86.08109 27.06184 -0.9951457 85.43614 25.91609 -0.8729123 86.30661 25.68881 -0.4830723 86.06298 26.24008 -0.2966951 85.40661 26.99965 -0.9341793 85.28984 26.84611 -0.8761371 85.32563 26.63069 -0.7612471 85.36528 26.37356 -0.5319862 85.39684 -3.659246 -0.4753884 86.08546 -3.877921 -0.8623436 86.32159 -2.559685 -0.8963338 87.41896 -4.815495 -0.8669411 85.34181 -5.067279 -0.9587647 85.28521 -4.242069 -0.3084982 85.40901 -4.372437 -0.5355522 85.40108 -4.630535 -0.7658675 85.37269 -5.887493 0 84.97338 -8.42756 -0.5581032 84.04006 -15.76146 -0.55 83.28139 44.78398 3 51.63153 44.85869 2.903034 51.1089 44.85831 3 51.11178 44.91973 2.777199 50.58483 44.91973 3 50.58483 44.86734 2.606443 50.70095 44.87224 2.58302 50.63324 44.6864 2.97945 52.16585 44.69511 3 52.13785 44.6642 3 52.29616 44.8951 2.622569 50.48309 44.91164 2.687489 50.48359 44.92023 2.731501 50.53071 44.91541 2.777199 50.45095 44.91541 3 50.45095 6.262549 0 88.75128 5.424028 0 89.00183 16.57597 0 89.00183 15.73745 0 88.75128 13.58708 -0.5524861 88.00289 38.17322 0 84.96015 35.58733 -0.5523176 84.00196 27.85792 0 84.96306 30.41535 -0.5534214 84.01006 -20.03731 7.242537 52.43054 -21.33952 5.349134 53.38708 -21.39219 5.430727 53.55628 -21.37589 5.485245 53.74288 -21.29309 5.504388 53.91849 -22.20014 2.850607 54.55362 -22.27979 2.840694 54.37581 -22.28712 2.81246 54.18291 -22.221 2.770205 54.0043 13.35 0 68.65 14.35 0 68.65 13.35 0 67.6 14.35 0 67.6 14.35 3.5 68.65 14.35 3.5 67.6 14.21603 4 67.6 13.85 4.366025 67.6 13.35 4.5 67.6 13.35 4.5 68.65 13.85 4.366025 68.65 14.21603 4 68.65 16.03841 0 70.90145 15.99715 0 70.92485 16.55073 0 71.41286 16.53841 0 71.42047 17.25 0 71.60001 17.25 4 71.60001 16.55073 4 71.41286 16.03841 4 70.90145 15.99715 4 70.92485 16.53841 4 71.42047 6.002849 0 70.92485 5.961595 0 70.90145 5.461594 0 71.42047 5.449273 0 71.41286 4.75 0 71.60001 5.961595 4 70.90145 5.449273 4 71.41286 4.75 4 71.60001 5.461594 4 71.42047 6.002849 4 70.92485 20.1 4 75.95001 20 4 75.51412 20 4 75.95001 20 6 75.95001 20.1 6 75.95001 20 6 75.51412 -2 4.5 71.95001 -1.975 4.5 71.95001 -2 4 71.95001 -1.975 4 71.95001 -2 4 71.7278 -2 4.5 71.7278 1.9 0 71.60001 1.9 4 71.60001 3.9 0 71.60001 3.9 4 71.60001 2.033974 4 71.1 3.4 4 70.73398 3.766025 4 71.1 2.9 4 70.6 2.4 4 70.73398 2.033974 0 71.1 2.4 0 70.73398 2.9 0 70.6 3.4 0 70.73398 3.766025 0 71.1 2 4 75.51412 1.9 4 75.95001 2 4 75.95001 2 6 75.95001 1.9 6 75.95001 2 6 75.51412 -40.575 -0.5 21.5 -40.675 -0.4 21.5 -40.47739 -0.4 20.7625 -40.39078 -0.5 20.8125 -39.9375 -0.4 20.22261 -39.8875 -0.5 20.30922 -39.2 -0.4 20.025 -39.2 -0.5 20.125 -38.4625 -0.4 20.22261 -38.5125 -0.5 20.30922 -37.92261 -0.4 20.7625 -38.00922 -0.5 20.8125 -37.725 -0.4 21.5 -37.825 -0.5 21.5 -37.92261 -0.4 22.2375 -38.00922 -0.5 22.1875 -38.4625 -0.4 22.77739 -38.5125 -0.5 22.69079 -39.2 -0.4 22.975 -39.2 -0.5 22.875 -39.9375 -0.4 22.77739 -39.8875 -0.5 22.69079 -40.47739 -0.4 22.2375 -40.39078 -0.5 22.1875 -37.92261 0 22.2375 -38.4625 0 22.77739 -39.2 0 22.975 -39.9375 0 22.77739 -40.47739 0 22.2375 -40.675 0 21.5 -40.47739 0 20.7625 -39.9375 0 20.22261 -39.2 0 20.025 -38.4625 0 20.22261 -37.92261 0 20.7625 -37.725 0 21.5 -40.54234 0 20.725 -39.975 0 20.15766 -39.2 0 19.95 -38.425 0 20.15766 -37.85766 0 20.725 -37.65 0 21.5 -37.85766 0 22.275 -38.425 0 22.84234 -39.2 0 23.05 -39.975 0 22.84234 -40.54234 0 22.275 -40.75 0 21.5 -40.49904 -0.5 22.25 -39.95 -0.5 22.79904 -39.2 -0.5 23 -38.45 -0.5 22.79904 -37.90096 -0.5 22.25 -37.7 -0.5 21.5 -37.90096 -0.5 20.75 -38.45 -0.5 20.20096 -39.2 -0.5 20 -39.95 -0.5 20.20096 -40.49904 -0.5 20.75 -40.7 -0.5 21.5 -40.7 -0.0866025 21.5 -40.49904 -0.0866025 22.25 -39.95 -0.0866025 22.79904 -39.2 -0.0866025 23 -38.45 -0.0866025 22.79904 -37.90096 -0.0866025 22.25 -37.7 -0.0866025 21.5 -37.90096 -0.0866025 20.75 -38.45 -0.0866025 20.20096 -39.2 -0.0866025 20 -39.95 -0.0866025 20.20096 -40.49904 -0.0866025 20.75 -33.65704 0 19.90779 -34.27294 0 20.22576 -33.71062 0 19.83202 -33.71062 -0.7611421 19.83202 -33.68999 -0.4497478 19.86119 -33.66559 -0.1482408 19.89569 -34.19855 -0.3615938 20.17367 -33.99301 -0.6373495 20.02975 42.2084 -12.4746 83.02506 42.2084 -12.4746 73.21286 42.23523 -12.4746 82.80922 42.23523 -12.4746 73.42666 42.2084 -12.50446 82.93309 42.2084 -12.51764 82.81538 42.2084 -12.51764 73.43614 35.4535 -28.67636 14.28793 35.4535 -14.35754 14.28793 35.61182 -15.23121 14.44746 35.86505 -16.55913 14.70261 36.12701 -17.90912 14.96657 37.22636 -23.92482 16.07429 37.54417 -25.92879 16.39452 37.56209 -26.47425 16.41257 37.54259 -26.63727 16.39293 37.45666 -26.99173 16.30633 37.33153 -27.28117 16.18026 36.94976 -27.72728 15.79558 37.24696 -27.41979 16.09504 41.82282 -23.35718 12.60193 41.56604 -22.93638 12.8228 41.68348 -22.80633 12.71715 41.79517 -22.67262 12.61532 41.85027 -22.7627 12.5886 41.8832 -22.88918 12.57257 39.16473 -19.74985 13.7489 41.50252 -24.0533 12.75527 40.95181 -24.85381 13.00944 39.16473 -26.5384 13.7489 39.55747 -26.23881 13.59782 40.6356 -25.2282 13.14989 36.64868 -17.49437 14.59033 36.64868 -28.06672 14.59033 37.36546 -27.69854 14.35062 37.99253 -18.50484 14.14092 38.59598 -25.38729 15.47185 40.63083 -23.86056 13.6597 36.95178 -20.78357 15.3491 38.63876 -22.50108 14.72801 40.03899 -24.37203 14.18907 36.53269 -17.17028 14.56098 37.52185 -27.4757 15.32054 38.58637 -26.89769 14.4255 40.89089 -24.37361 13.4197 40.33279 -25.39711 13.56597 38.7966 -25.9825 15.29 38.79318 -26.52002 14.91763 40.28388 -24.90909 13.96405 35.84322 -15.34428 14.38654 -21.175 0 15.48078 -21.175 0.3272668 15.48078 -21.175 0 14.85628 -21.175 0.3272668 14.85628 -19.90023 0.3272668 15.48078 -19.90023 0 15.48078 -19.9 0 15.5 -21.39282 4.5 15.1 -21.1 4.5 14.80718 -21.1 0.3272668 14.80718 -20.7 4.5 14.7 -20.7 0.3272668 14.7 -20.3 4.5 14.80718 -20.3 0.3272668 14.80718 -20.00718 4.5 15.1 -20.00718 0.3272668 15.1 -19.9 4.5 15.5 -20.00718 4.5 15.9 -20.00718 0 15.9 -20.3 4.5 16.19282 -20.3 0 16.19282 -20.7 4.5 16.3 -20.7 0 16.3 -21.1 4.5 16.19282 -21.1 0 16.19282 -21.39282 4.5 15.9 -21.39282 0 15.9 -21.5 4.5 15.5 -21.5 0 15.5 -21.39282 0 15.1 -20.7 4.5 15.5 7.65 0 67.6 8.650001 0 67.6 7.65 3.5 67.6 8.650001 4.5 67.6 7.783975 4 67.6 8.150001 4.366025 67.6 8.650001 0 68.65 7.65 0 68.65 8.650001 4.5 68.65 8.150001 4.366025 68.65 7.783975 4 68.65 7.65 3.5 68.65 -10.13397 9.600001 74 -10.5 9.600001 74.36602 -11 9.600001 74.5 -11.86603 9.600001 73 -11.5 9.600001 72.63397 -11 9.600001 72.5 -12 9.600001 73.5 -11.86603 9.600001 74 -11.5 9.600001 74.36602 -10 9.600001 73.5 -10.13397 9.600001 73 -10.5 9.600001 72.63397 -10 9.050001 73.5 -10.13397 9.050001 74 -10.5 9.050001 74.36602 -11 9.050001 74.5 -11.5 9.050001 74.36602 -11.86603 9.050001 74 -12 9.050001 73.5 -11.86603 9.050001 73 -11.5 9.050001 72.63397 -11 9.050001 72.5 -10.5 9.050001 72.63397 -10.13397 9.050001 73 -11 9.050001 73.5 11.59772 9.600001 72.40171 10.40228 9.600001 72.40171 11.59772 9.050001 72.40171 10.40228 9.050001 72.40171 11.21193 9.600001 72.57729 10.78807 9.600001 72.57729 11.21193 9.050001 72.57729 10.78807 9.050001 72.57729 33 9.600001 74.5 32.5 9.600001 74.36602 32.13397 9.600001 74 33 9.600001 72.5 33.5 9.600001 72.63397 33.86602 9.600001 73 33.86602 9.600001 74 33.5 9.600001 74.36602 34 9.600001 73.5 32 9.600001 73.5 32.5 9.600001 72.63397 32.13397 9.600001 73 34 9.050001 73.5 33.86602 9.050001 74 33.5 9.050001 74.36602 33 9.050001 74.5 32.5 9.050001 74.36602 32.13397 9.050001 74 32 9.050001 73.5 32.13397 9.050001 73 32.5 9.050001 72.63397 33 9.050001 72.5 33.5 9.050001 72.63397 33.86602 9.050001 73 33 9.050001 73.5 39.8567 8 66.46176 39.36585 8 66.50459 38.94858 8 66.7666 39.36585 8 68.49542 39.8567 8 68.53824 40.31304 8 68.35245 40.63439 8 67.02104 40.31304 8 66.64756 40.75 8 67.5 40.63439 8 67.97896 38.94858 8 68.2334 40.31304 8.75 68.35245 40.225 8.75 68.40933 39.7 9.380905 67.5 39.36585 8.75 66.50459 39.7 8.75 66.45001 39.8567 8.75 66.46176 40.225 8.75 66.59067 40.60932 8.75 66.975 40.75 8.75 67.5 40.60932 8.75 68.025 40.31304 8.75 66.64756 38.94858 8.929409 67.5 38.94858 8.843377 67.98548 38.94858 8.843377 67.01454 38.94858 8.75 66.7666 39.175 8.75 66.59067 39.7 8.75 68.55001 39.36585 8.75 68.49542 39.175 8.75 68.40933 39.8567 8.75 68.53824 38.94858 8.75 68.2334 3.9 6.05 73.30718 3.60718 6.05 73.6 4.3 6.05 74 3.5 6.05 74 3.60718 6.05 74.4 4.99282 6.05 73.6 4.7 6.05 73.30718 4.3 6.05 73.2 4.7 6.05 74.69282 4.99282 6.05 74.4 5.1 6.05 74 3.9 6.05 74.69282 4.3 6.05 74.8 5.1 10 74 4.99282 10 74.4 4.7 10 74.69282 4.3 10 74.8 3.9 10 74.69282 3.60718 10 74.4 3.5 10 74 3.60718 10 73.6 3.9 10 73.30718 4.3 10 73.2 4.7 10 73.30718 4.99282 10 73.6 4.3 10.48069 74 17.3 6.05 73.30718 17.00718 6.05 73.6 17.7 6.05 74 16.9 6.05 74 17.00718 6.05 74.4 18.39282 6.05 73.6 18.1 6.05 73.30718 17.7 6.05 73.2 18.1 6.05 74.69282 18.39282 6.05 74.4 18.5 6.05 74 17.3 6.05 74.69282 17.7 6.05 74.8 17.7 10.48069 74 18.39282 10 74.4 18.1 10 74.69282 18.5 10 74 17.3 10 74.69282 17.00718 10 74.4 17.7 10 74.8 17.00718 10 73.6 17.3 10 73.30718 16.9 10 74 18.1 10 73.30718 18.39282 10 73.6 17.7 10 73.2 17.7 10.6309 81.5 18.60933 10 82.025 18.225 10 82.40933 18.75 10 81.5 17.175 10 82.40933 16.79067 10 82.025 17.7 10 82.55001 16.79067 10 80.975 17.175 10 80.59067 16.65 10 81.5 18.225 10 80.59067 18.60933 10 80.975 17.7 10 80.45001 18.75 6.15 81.5 18.60933 6.15 82.025 18.225 6.15 82.40933 17.7 6.15 82.55001 17.175 6.15 82.40933 16.79067 6.15 82.025 16.65 6.15 81.5 16.79067 6.15 80.975 17.175 6.15 80.59067 17.7 6.15 80.45001 18.225 6.15 80.59067 18.60933 6.15 80.975 18.69593 6.05 82.075 18.275 6.05 82.49594 17.7 6.05 82.65 17.125 6.05 82.49594 16.70407 6.05 82.075 16.55 6.05 81.5 16.70407 6.05 80.92501 17.125 6.05 80.50408 17.7 6.05 80.35 18.275 6.05 80.50408 18.69593 6.05 80.92501 18.85 6.05 81.5 17.7 6.05 81.5 4.3 10.6309 81.5 5.209327 10 82.025 4.825 10 82.40933 5.35 10 81.5 3.775 10 82.40933 3.390673 10 82.025 4.3 10 82.55001 3.390673 10 80.975 3.775 10 80.59067 3.25 10 81.5 4.825 10 80.59067 5.209327 10 80.975 4.3 10 80.45001 5.35 6.15 81.5 5.209327 6.15 82.025 4.825 6.15 82.40933 4.3 6.15 82.55001 3.775 6.15 82.40933 3.390673 6.15 82.025 3.25 6.15 81.5 3.390673 6.15 80.975 3.775 6.15 80.59067 4.3 6.15 80.45001 4.825 6.15 80.59067 5.209327 6.15 80.975 5.295929 6.05 82.075 4.875 6.05 82.49594 4.3 6.05 82.65 3.725 6.05 82.49594 3.304071 6.05 82.075 3.15 6.05 81.5 3.304071 6.05 80.92501 3.725 6.05 80.50408 4.3 6.05 80.35 4.875 6.05 80.50408 5.295929 6.05 80.92501 5.45 6.05 81.5 4.3 6.05 81.5 -17.92859 8 68.21432 -17.55488 8 66.76418 -17.92859 8 66.78569 -17.21732 8 68.07404 -17 8 67.76926 -17 8 67.23075 -18.42627 8 67.68717 -18.24535 8 68.01486 -18.42627 8 67.31284 -18.24535 8 66.98513 -17.55488 8 68.23583 -17.21732 8 66.92596 -18.24535 8.800001 66.98513 -17.92859 8.800001 66.78569 -17.55488 8.800001 66.76418 -17.21732 8.800001 68.07404 -17.55488 8.800001 68.23583 -17.92859 8.800001 68.21432 -18.24535 8.800001 68.01486 -18.42627 8.800001 67.68717 -18.42627 8.800001 67.31284 -17.21732 8.800001 66.92596 -17 8.800001 67.76926 -17 8.800001 67.23075 24 4 71.7278 23.975 4 71.95001 24 4 71.95001 24 6 71.95001 23.975 6 71.95001 24 6 71.7278 20.1 0 71.60001 18.1 0 71.60001 20.1 4 71.60001 18.1 4 71.60001 18.23398 4 71.1 18.6 4 70.73398 19.1 4 70.6 19.96603 4 71.1 19.6 4 70.73398 18.23398 0 71.1 18.6 0 70.73398 19.1 0 70.6 19.6 0 70.73398 19.96603 0 71.1 + + + + + + + + + + -0.8191521 4.78204e-7 0.5735765 -0.819152 0 0.5735766 -0.819152 0 0.5735765 -0.8191413 0 0.5735919 -0.8191632 2.79601e-6 0.5735605 -0.8191609 0 0.5735639 -0.8191487 -1.63427e-6 0.5735813 -0.8191517 -8.97132e-7 0.573577 -0.8191523 -1.9797e-6 0.5735761 -0.8191224 1.53382e-5 0.5736188 -0.8191567 -1.01138e-5 0.57357 -0.8191531 -3.81392e-5 0.573575 -0.819176 0 0.5735424 0.4743768 -0.5544894 0.6837456 0.4740293 -0.5546649 0.6838445 0.4947394 -0.3620432 0.7900366 0.5341092 -0.2275975 0.8142033 -0.009038746 -0.9748764 0.2225631 0.4885717 -0.3283032 0.8084025 -0.02839404 -0.9547664 0.2959983 0.4702967 -0.3277554 0.8193885 -0.04645311 -0.93085 0.3624368 0.4518113 -0.3279275 0.8296567 -0.06264501 -0.9000734 0.4312117 0.4523546 -0.2829622 0.8457587 -0.3176444 -0.9252257 0.2075078 0.4291021 -0.2809479 0.8584519 -0.3209813 -0.8880451 0.3291611 0.40501 -0.2763057 0.8715631 -0.3163273 -0.8369595 0.4465826 0.3795838 -0.2699262 0.8849046 -0.3067801 -0.7749835 0.5525275 0.420696 -0.1772359 0.8897204 -0.7687585 -0.6371052 -0.05574452 0.3771175 -0.1650956 0.9113319 -0.7103558 -0.6048686 0.3599007 0.4059546 -0.08285784 0.9101293 -0.7157916 -0.3985863 0.573386 0.2428954 -0.04517483 0.9690001 0.02291369 -0.06937527 0.9973275 -0.4500369 0.5046722 -0.7367312 0.8071457 0 -0.5903522 0.8055949 -3.90241e-5 -0.592467 0.8054358 0 -0.5926831 0.7686483 -0.0114603 -0.6395691 0.7781702 -7.54518e-4 -0.6280531 0.7927852 0 -0.6095013 0.763788 0.003354489 -0.6454585 0.7596757 0.00624305 -0.6502721 0.7596448 0.006239652 -0.6503084 0.7587551 0.005279719 -0.6513547 0.7559565 0.002326369 -0.6546179 0.7840247 -0.003993749 -0.6207169 0.7908104 1.29115e-4 -0.6120615 0.8156208 -1.19684e-4 -0.5785868 0.8151085 -3.7711e-4 -0.5793083 0.8451173 5.58846e-4 -0.5345805 0.8560683 -0.008598327 -0.5167913 0.8817846 0.003694593 -0.4716381 0.8955541 -0.001631915 -0.4449496 0.9350007 0.00911951 -0.3545288 0.8833582 -0.09502893 -0.4589638 0.9705591 0.08317822 -0.2260457 0.9472793 -0.04249429 -0.3175784 0.986768 0.005087316 -0.1620594 0.5327048 -0.3695729 0.7613419 0.01300185 -0.3613435 0.9323421 0.8935862 -0.1050923 -0.4364166 0.3106754 0.6021742 0.7354367 0.5293061 0.4260775 0.7336847 -0.1494902 0.1811901 0.97202 0.4992142 0.2321997 0.8347865 0.627141 -0.157635 0.7627879 0.5665621 -0.15707 0.8089106 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 1 1.27744e-4 -3.6478e-4 1 6.6223e-5 5.62375e-6 1 0 0 1 9.58753e-6 -4.25752e-6 1 -8.507e-5 6.76085e-6 1 3.82713e-5 5.26216e-6 1 -9.95739e-7 -1.99148e-6 1 -6.60341e-7 0 1 -1.3065e-6 -8.08575e-6 1 2.71334e-4 -4.12798e-5 -1 0 0 -1 2.03473e-4 -3.53774e-5 -1 0 -5.00586e-4 -1 -1.04563e-4 0 -1 -3.38194e-4 -2.58322e-4 -1 -1.76354e-5 -9.36503e-5 -1 -2.03645e-5 8.57123e-7 -0.9999955 0.002140283 0.002132952 -1 2.88662e-5 1.22116e-4 -1 6.37115e-5 1.20671e-4 -1 2.68769e-4 3.13703e-4 -1 -1.1135e-4 4.10724e-6 -1 4.92288e-5 1.29646e-4 -1 -5.29058e-5 5.16113e-5 -1 -5.50522e-5 5.1299e-5 -0.9999999 -4.96155e-4 -2.70193e-4 -1 3.70169e-5 1.00989e-4 -1 0 8.28142e-5 -1 -2.63171e-5 6.24584e-5 -1 -4.08694e-5 5.58726e-5 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 1.34804e-4 -3.66059e-4 1 7.01853e-5 1.69104e-5 1 1.02879e-5 -1.20041e-5 1 -8.09461e-5 1.95911e-5 1 3.17819e-5 1.54491e-5 1 -1.15272e-6 -5.85229e-6 1 -9.90596e-7 0 1 -1.25209e-6 -4.441e-6 1 2.07754e-4 -4.05452e-5 -0.9999995 2.7748e-4 -0.001011431 -1 1.65321e-4 -3.27124e-5 -1 -1.0622e-4 1.03015e-5 -1 -2.07163e-5 8.58607e-7 -0.9999999 -3.93617e-6 -6.23853e-4 -1 1.47097e-6 0 -1 2.43974e-4 5.88999e-6 -1 1.55237e-4 -2.27729e-5 -1 -2.07521e-5 1.01194e-5 -1 2.40126e-6 -1.46085e-6 -1 4.09707e-7 2.8583e-7 -1 0 2.66037e-6 -1 -3.90564e-6 2.15842e-6 -1 3.30557e-5 3.18155e-6 -1 -2.03652e-5 8.5715e-7 -1 -2.05057e-5 0 -1 3.43667e-4 -1.84845e-4 -1 -6.54632e-6 -1.57521e-5 -1 -7.23275e-6 -1.74038e-5 -1 -1.45688e-5 -1.28314e-5 -1 -7.93349e-6 3.33753e-6 -1 5.61494e-5 -1.45256e-5 -1 2.50387e-4 -1.53862e-4 -1 -1.35966e-4 8.54423e-5 -1 2.97625e-4 -1.88002e-4 -1 -2.4902e-5 2.04957e-5 -0.9999995 2.76725e-4 -0.001008033 -0.508394 -0.7936705 -0.3341001 -0.5109567 -0.7919142 -0.334358 -0.6768431 -0.7033988 -0.217057 -0.6329014 -0.7300925 -0.2576837 -0.5246126 -0.7849944 -0.3294929 -0.8369395 -0.5369967 -0.1056742 -0.8221686 -0.55623 -0.121025 -0.7378796 -0.6496579 -0.1829707 -0.9951031 -0.09884321 0 -0.9934267 -0.1144111 -0.003706037 -0.9473801 -0.3187623 -0.02935463 -0.9423484 -0.3326959 -0.03595858 -0.8872765 -0.4544817 -0.0786572 -0.8117741 0.1339133 0.5684102 -0.811941 0.077838 0.5785267 -0.8162513 0.07482039 0.5728315 -0.6859498 0.5466052 0.4803079 -0.7439259 0.4089754 0.5285011 -0.7386821 0.4281632 0.5206007 -0.7859969 0.2816237 0.5503607 -0.8013663 0.2072525 0.5611227 -0.6646794 0.5844562 0.4654163 -0.6646787 0.5844606 0.4654119 -0.6586481 0.5944426 0.4613249 -0.5752997 0.71043 0.4053634 -0.6195101 0.6387705 0.4562671 -0.5580661 0.7295754 0.3953253 -0.340315 0.9076793 0.2455685 -0.4331554 0.8487504 0.303314 -0.4888569 0.8024064 0.3422909 -7.07609e-4 0.9999998 4.52182e-4 -0.07140374 0.9961893 0.05008399 -0.1039534 0.9916074 0.07686752 -0.2063638 0.9680107 0.1427214 -0.3303839 0.9137481 0.2364549 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.3334925 -0.8163009 -0.4716308 -0.3335708 -0.8162732 -0.4716237 -0.3340283 -0.8156394 -0.4723955 -0.3344266 -0.8154958 -0.4723616 -0.334752 -0.8127353 -0.4768672 -0.3343952 -0.8151971 -0.4728993 -0.3358014 -0.8134602 -0.4748894 -0.3358028 -0.8134601 -0.4748886 -0.3311876 -0.8165243 -0.4728668 -0.3311117 -0.8165432 -0.4728873 -0.331152 -0.816556 -0.4728367 -0.3310951 -0.8165578 -0.4728735 -0.332485 -0.8156074 -0.4735382 -0.3201451 -0.8158098 -0.4816241 -0.3334663 -0.8162884 -0.471671 -0.3313494 -0.8164834 -0.472824 -0.3311851 -0.8165257 -0.472866 -0.6398228 -1.68627e-4 0.7685225 -0.5047751 -0.02000826 0.8630191 -0.7004513 0 0.7137002 0.3427302 0 0.9394339 0.3846468 -0.005957424 0.9230446 0.1330148 3.44717e-5 0.9911141 -0.1713637 -1.95947e-4 0.9852079 -0.0738632 -0.0128082 0.9971862 -0.3231272 6.78198e-5 0.9463557 0.5736259 9.18017e-6 0.8191174 0.5735775 5.56856e-7 0.8191514 0.5735769 0 0.8191519 0.5735771 4.64052e-6 0.8191516 0.573578 0 0.819151 0.5735737 -4.95813e-7 0.819154 0.573574 -2.22231e-6 0.8191538 0.5735771 0 0.8191516 0.5735753 1.43993e-7 0.8191528 0.5735895 0 0.8191429 0.5735725 2.07005e-7 0.8191548 0.5735754 0 0.8191529 0.5735741 0 0.8191537 0.5735783 -1.13062e-6 0.8191508 0.5735785 -5.04593e-7 0.8191506 0.5735743 0 0.8191536 0.5735769 2.49204e-7 0.8191519 0.5735757 0 0.8191527 0.5735787 0 0.8191505 -0.8164565 8.54753e-5 0.5774069 -0.8164561 8.63264e-5 0.5774074 -0.816708 0.002655684 0.577045 -0.8164935 -1.36385e-6 0.5773546 -0.8164787 8.79866e-6 0.5773756 -0.8164916 0 0.5773574 -0.8163855 0.003710985 0.5774955 -0.8164278 0 0.5774476 -0.8168777 -0.001126289 0.5768101 -0.8164865 -3.42378e-6 0.5773645 -0.8164922 0 0.5773565 -0.816481 -2.52257e-5 0.5773725 -0.8164904 -3.79594e-5 0.5773591 -0.8178237 0.002231776 0.5754644 -0.8164923 0 0.5773565 -0.8164925 1.47495e-6 0.5773561 -0.8164924 1.45786e-7 0.5773561 -0.8164923 -1.25682e-6 0.5773565 -0.8164916 -2.12718e-6 0.5773575 -0.8164923 0 0.5773563 -0.8165027 0 0.5773416 -0.8164932 2.52222e-5 0.5773552 -0.8164783 -1.53422e-4 0.5773764 -0.8164925 -4.44002e-7 0.5773561 -0.816493 2.21361e-6 0.5773554 -0.8164922 0 0.5773566 -0.8164929 -4.94396e-7 0.5773556 -0.8164923 0 0.5773564 -0.8164932 1.28372e-6 0.5773552 0.9913578 0.1289892 -0.02390944 0.9920158 0.1161809 -0.04905778 0.9952743 0.0060938 -0.09691345 0.9949554 0.02757531 -0.09645402 0.9941035 0.06218445 -0.08883327 0.9930655 0.09247875 -0.07258504 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -3.58226e-7 1 -3.20014e-7 -2.94304e-7 1 -2.54043e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.62347e-4 0.9999991 -0.001381516 3.85415e-4 1 0 0 1 0 -0.008929669 0.9999602 0 -1.21194e-5 1 -1.68248e-4 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.7043661 0 0.7098369 0.7043523 1.85352e-6 0.7098506 0.7043557 2.49975e-5 0.7098473 0.7043512 0 0.7098517 0.7043555 0 0.7098475 0.7043521 2.88113e-7 0.7098509 0.7043522 0 0.7098508 0.7043521 -7.01571e-7 0.7098509 0.7043527 1.40589e-7 0.7098501 0.7043439 0 0.7098589 0.7043393 0 0.7098634 0.7043497 -1.96097e-6 0.7098532 0.704351 -1.0617e-6 0.7098519 0.7043526 -9.09485e-7 0.7098504 0.7043496 3.99305e-7 0.7098532 0.7043534 3.20251e-6 0.7098495 0.7043504 0 0.7098526 0.7043575 -1.33802e-6 0.7098454 0.7043519 -2.63902e-6 0.709851 0.7043741 0 0.7098289 0.7043526 -9.94365e-6 0.7098503 0.7043531 0 0.7098498 0.7043527 1.42238e-6 0.7098503 0.7043527 -6.32746e-7 0.7098502 0.7043515 1.43427e-6 0.7098515 0.7043521 -3.37183e-5 0.7098508 0.7043517 8.3667e-5 0.7098513 0.7043517 0 0.7098512 0.7043521 0 0.7098508 0.7043522 1.98435e-6 0.7098508 0.7043518 -2.11694e-6 0.7098511 0.7042526 0 0.7099495 0.704347 1.79616e-7 0.7098559 0.7043582 0 0.7098448 0.7043467 -1.27203e-6 0.7098562 0.7043537 0 0.7098492 0.7043552 2.34109e-7 0.7098476 0.7043504 0 0.7098525 0.7043542 -1.28517e-5 0.7098487 0.7043545 0 0.7098485 0.704349 2.57122e-6 0.709854 0.704354 6.05833e-6 0.7098489 -0.1704822 0 -0.9853608 -0.1704823 0 -0.9853608 -0.3595615 -0.006721019 -0.9330973 -0.1940504 0 -0.9809916 -0.5549405 0 -0.83189 -0.5549407 0 -0.83189 -0.8312177 0 -0.5559473 -0.9807559 0 -0.1952381 -0.9807559 0 -0.1952381 0.7613346 0 -0.6483592 0.7869436 -0.02407449 -0.6165552 0.8040148 -0.004628419 -0.5945914 0.5991793 -0.1408175 -0.7881336 0.7001686 0.003474414 -0.7139692 0.5245871 -0.003414571 -0.85135 0.4820646 -0.005181729 -0.8761204 -0.1065741 -4.7415e-4 -0.9943047 0.04487985 -0.003289997 -0.998987 0.1958413 -0.0153141 -0.980516 0.03151392 -0.001836061 -0.9995017 0.2227866 -8.9507e-5 -0.9748673 0.3774924 4.83445e-4 -0.9260125 -0.5885481 0 -0.8084622 -0.5812842 -6.23414e-6 -0.8137006 -0.5442447 -2.95435e-4 -0.8389264 -0.4541293 -0.003701508 -0.8909282 -0.3770495 -0.01010912 -0.9261379 -0.3452584 -0.01302558 -0.9384174 -0.4020563 -0.00711286 -0.9155874 -0.2501171 1.31023e-5 -0.9682157 -0.1437824 0 -0.9896094 -0.8316982 4.1774e-5 -0.5552279 -0.6987842 -0.003140747 -0.7153257 -0.6346017 -4.26521e-4 -0.7728394 -0.6000705 0 -0.7999471 -0.7379111 -0.006440758 -0.6748673 -0.7785516 -0.01233732 -0.6274594 -0.7568991 -0.009215474 -0.6534668 -0.9485296 0 -0.3166886 -0.9787959 -0.01813668 -0.2040337 -0.9430302 -0.006145954 -0.3326504 -0.9032328 -3.19389e-4 -0.4291509 -0.9284991 -0.003487408 -0.3713183 -0.9210927 -0.00239706 -0.3893361 -0.9023913 -1.29487e-5 -0.4309176 -0.8871519 -0.001002192 -0.4614765 -0.9133461 -1.0687e-4 -0.4071844 -0.9202338 0 -0.3913693 -0.9173031 -0.002625942 -0.398181 0 1 0 0 0 1 0.001453995 0 0.999999 -1.74579e-5 0 1 6.18113e-6 0 1 -2.10671e-6 0 1 0 0 1 -4.69751e-4 0 0.9999999 -5.12259e-5 0 1 3.35178e-5 0 1 -0.8911275 0 0.4537531 -0.8208537 -0.007939815 0.5710833 -0.533728 -0.008818149 0.8456102 -0.6387894 0.005550384 0.7693617 -0.8134076 -0.006313443 0.5816599 0.02661812 5.42806e-4 0.9996456 -0.1753281 -0.004973232 0.9844976 -0.1624084 -0.003459095 0.9867176 -0.2122291 0 0.9772199 -0.4285092 0 0.9035374 0.2113368 -0.002794802 0.9774094 0.2345728 -0.006012916 0.97208 0.3822451 0 0.924061 0.2349253 -0.01197177 0.9719398 0.1754283 -0.00497353 0.9844797 0.1623909 0.0024181 0.9867236 0.5337572 -0.002138376 0.8456351 0.5297414 -0.002954661 0.8481541 0.7721946 0.002156496 0.6353826 0.8208488 -0.007967591 0.5710901 0.8909449 0 0.4541115 -0.02668637 5.42673e-4 0.9996438 -0.211328 -0.002794802 0.9774113 -0.2345724 -0.006013333 0.9720801 -0.3685175 -5.73919e-4 0.9296207 -0.4096652 0 0.912236 0.9808147 0 -0.1949427 0.9659745 0.002740979 -0.2586229 0.6093202 -5.34804e-4 -0.7929242 0.7793741 6.49212e-4 -0.6265587 0.79366 0 -0.6083617 0.8970304 0 -0.4419689 0.1961279 0 -0.9805784 0.1858612 -3.31653e-4 -0.982576 0.4430607 1.28992e-4 -0.8964916 0.4336583 0 -0.9010774 0.5908159 0 -0.8068064 7.04808e-4 0.5545557 -0.8321464 0.001180112 0.5277199 -0.8494177 0.001016855 0.1849704 -0.9827436 0.001186966 0.1954627 -0.9807104 -0.2311634 0.1001073 0.9677511 -0.2615166 0.7603649 0.5945203 -0.3610637 0.1004953 0.9271105 -0.2311624 0.1001327 0.9677487 -0.2987678 0.7142707 0.6328943 -0.3784137 0.528598 0.7598599 -0.4378755 0.1949645 0.8776412 -0.4010428 0.3665739 0.8395167 -0.4214543 0.2722582 0.8650155 -0.3827851 0.555424 0.7382275 -0.2467883 0.8312149 0.4981741 -0.2138441 0.8828632 0.4181187 -0.08803069 0.9807607 0.1742384 -0.08185327 0.9840443 0.1579772 0.7157593 -0.5973399 -0.3617648 0.8047906 -0.5016825 -0.3172174 0.3917844 -0.8864554 -0.2463777 0.347092 -0.9297013 -0.1232182 0.4544062 -0.8717041 -0.1834313 0.4294237 -0.8558273 -0.2883663 0.4378761 -0.8518627 -0.2873926 0.9250982 -0.3529422 0.1400896 0.9373539 -0.3483258 -0.006072998 0.9179199 -0.3728831 -0.1355783 0.9298654 -0.33656 -0.1485853 0.8416377 -0.5301651 -0.102815 0.5517049 -0.8104032 -0.1971508 0.5755457 -0.8087072 -0.1214084 0.6154411 -0.7489899 -0.2454515 0.7697532 -0.6037528 -0.2072747 0.8188496 -0.5499961 -0.1642857 0.6617898 -0.3847962 -0.6434021 0.4624919 0.6067771 -0.6464696 0.7088899 0.5265655 -0.4692591 0.5723664 0.388416 -0.7221702 0.7144137 -0.2191272 -0.6645272 0.7218354 -0.004698514 -0.6920488 0.7156968 -0.02325797 -0.6980239 0.7164719 0.2391846 -0.6553311 0.7145302 0.2172281 -0.6650253 0.6609536 -0.3998869 -0.6350048 0.6514874 -0.3998628 -0.644728 0.6032449 -0.566429 -0.5614748 0.6589137 -0.3120476 -0.6844407 0.7128567 -0.05713009 -0.698979 0.7240837 -0.00472486 -0.689696 0.6936092 0.1361512 -0.7073678 0.6594639 0.3912148 -0.6419178 0.6260747 0.4416607 -0.6426246 0.5160798 0.6904637 -0.5068745 0.4448919 0.7476798 -0.4929972 0.275654 0.9397392 -0.2022502 0.6551342 -0.3120541 -0.6880563 0.07592082 0.9196684 -0.3852872 0.67674 0.1360046 -0.7235509 0.6692946 -0.05703806 -0.7408046 0.1628371 0.9704676 -0.1779803 0.1843135 0.9652704 -0.185153 0.4459341 0.7446194 -0.4966737 0.4423233 0.7476184 -0.4953957 0.6523658 -0.1340322 -0.7459586 0.6195235 -0.1338691 -0.773479 0.6057589 0.1948336 -0.7714247 0.5690934 0.441378 -0.6937711 0.5858249 0.3451432 -0.7332704 0.6193097 0.3455232 -0.7050314 0.6142436 0.4416334 -0.6539608 0.1212989 0.9807292 -0.1531561 0.1537027 0.9704426 -0.1860557 0.2745394 0.8966324 -0.347388 0.4164111 0.7442102 -0.5222576 0.3873543 0.7925403 -0.4709953 0.4913519 0.6082909 -0.6233424 0.1986747 0.1946627 -0.9605388 0.2679764 0.5416133 -0.7967709 0.2202885 0.7292919 -0.6477703 0.2041983 0.8092213 -0.5508757 0.2109842 0.7069536 -0.6750573 0.03960788 0.9806947 -0.1914923 0.04857468 0.9656887 -0.2551196 0.06978076 0.9659247 -0.249239 0.07581639 0.9676593 -0.240598 0.1608349 0.6078367 -0.7776033 0.1380341 0.7060546 -0.6945744 0.1234933 0.79262 -0.5970787 0.08974707 0.8964723 -0.4339158 0.181747 0.4414525 -0.8786853 0.1916204 0.2581377 -0.9469143 0.3193118 0.2583044 -0.9117669 0.3165498 0.3361219 -0.8870278 0.3837319 0.1690657 -0.9078363 0.4565533 0.1686751 -0.8735605 0.4565498 0.1686861 -0.8735601 0.5730313 0.1687149 -0.8019792 0.5730307 0.1687017 -0.8019823 0.6784867 0.1687151 -0.7149763 0.678487 0.1687176 -0.7149754 0.7708877 0.1687352 -0.6142155 0.7708938 0.1687005 -0.6142174 0.8484675 0.1686951 -0.5016423 0.848461 0.1687376 -0.5016388 0.9097112 0.1687347 -0.379413 0.9097181 0.1686948 -0.3794141 0.9534596 0.1687347 -0.2498872 0.9534702 0.168668 -0.2498915 0.9788783 0.1686546 -0.1155542 0.9788667 0.1687226 -0.1155544 1 -2.57125e-6 0 1.89977e-6 0 1 3.6721e-6 0 1 -2.59578e-6 0 1 5.25706e-5 0 1 -1.5961e-5 0 1 5.31111e-6 0 1 -0.652054 2.04996e-5 0.7581726 -0.925985 -0.07753688 0.3695131 -0.9046553 -0.02241456 0.4255541 -0.9024845 -0.01370531 0.4305045 -0.7735829 0 0.633695 -0.773853 -3.37815e-5 0.6333652 -0.862704 0.02380037 0.5051489 -0.7678028 -0.01250922 0.6405642 -0.9025053 0.01149708 0.4305254 -0.8639796 0 0.5035269 -0.1105174 -0.01043659 0.9938195 -0.1925938 -0.002245903 0.981276 -0.034258 -1.50787e-4 0.999413 -0.01126235 0 0.9999366 -0.2261261 -0.003253161 0.9740927 -0.3393002 3.89146e-4 0.9406781 -0.5492308 -0.001289069 0.8356698 -0.4513707 -0.01258283 0.8922478 -0.5455588 -0.004485249 0.8380606 0.2965039 -7.00806e-4 0.9550315 0.1853551 -0.004959702 0.9826592 0.1926174 -0.004413366 0.9812641 0.07239151 -4.37208e-4 0.9973763 0.01314485 0 0.9999136 0.4060974 5.16117e-4 0.9138298 0.5492348 -0.003774344 0.8356596 0.490849 -0.008901059 0.8711993 0.7735829 0 0.6336953 0.8973375 0 0.4413451 0.8555864 -0.003944873 0.5176451 0.8811486 0.001312911 0.4728379 0.778928 -0.001183509 0.6271124 0.7804937 -8.97925e-4 0.6251631 0.6743131 4.80455e-4 0.7384455 0.5632157 -0.003270685 0.8263036 2.2816e-6 0 1 4.3811e-6 0 1 -2.87499e-6 0 1 4.92299e-6 0 1 0.2740325 0 0.9617204 0.2740561 0 0.9617137 0.1249419 0 0.9921641 0.2037542 -0.02214395 0.9787716 0.3073165 -0.001502752 0.9516062 0.4877077 0.006961941 0.8729793 0.4909451 0.007629632 0.8711571 0.6539057 -0.001549899 0.7565745 0.8035554 0.0066334 0.5951929 0.8039601 0.006792128 0.5946445 0.9999954 0 0.00306189 0.9775521 9.79923e-4 0.2106915 0.9796712 0.004399657 0.2005622 0.9059414 -6.2048e-4 0.4234028 1 0 0 1 0 0 1 0 0 1 0 0 0.4262173 0.184455 -0.8856158 0.5835602 0.1562265 -0.7969008 0.4737775 0.205745 -0.8562732 0.45388 0.4532772 -0.7671589 0.1827609 0.1818963 -0.9661844 0.18276 0.1818961 -0.9661846 0.1609404 0.5001708 -0.8508393 0.1406325 0.5225501 -0.8409305 -0.4406116 -0.6565089 -0.6122562 -0.2872462 -0.6634015 -0.6909328 -0.4094734 -0.7054318 -0.5785304 -0.3860481 -0.7795962 -0.4931498 -0.3640155 -0.7788811 -0.510722 0.5736142 0 0.8191257 0.5734857 0 0.8192155 0.5735735 0 0.8191542 0.5750502 2.27163e-4 0.8181182 0.5749215 1.54601e-4 0.8182086 0.5748026 6.54341e-4 0.8182919 0.5748247 6.73327e-4 0.8182764 0.5746293 9.83511e-4 0.8184133 0.5735773 -1.23809e-6 0.8191515 0.573578 0 0.8191511 0.5735746 0 0.8191534 0.5748646 0.001688122 0.8182468 0.5745872 0.001133143 0.8184427 0.5743572 0.00130409 0.8186038 0.5735778 -9.29298e-7 0.8191511 0.5735747 9.25715e-7 0.8191533 0.5735758 -6.94013e-7 0.8191526 0.5735763 0 0.8191521 0.573576 6.93431e-7 0.8191525 0.5735807 3.09729e-7 0.8191491 0.5739876 0.001531183 0.8188626 0.5740821 0.001505672 0.8187964 0.5743104 0.001642465 0.8186361 0.5743452 0.001828908 0.8186113 0.5743241 0.001478195 0.8186267 0.5735769 0 0.8191518 0.5735766 4.71534e-7 0.8191519 0.5735769 4.64946e-7 0.8191517 0.5735644 -2.62595e-6 0.8191605 0.5735756 0 0.8191527 0.5735751 2.14956e-6 0.819153 0.5735771 0 0.8191517 0.557542 -0.002010047 0.8301463 0.5737612 0.001621127 0.8190211 0.5738775 0.001736462 0.8189394 0.5738675 0.001776933 0.8189463 0.5739319 0.001601457 0.8189015 -0.8178063 0 0.5754937 1 -3.66518e-7 0 1 -8.65894e-7 0 1 6.55492e-7 0 1 1.80921e-6 0 1 -1.6439e-7 0 1 9.1906e-7 0 -1 0 6.26968e-7 -1 -1.2756e-6 0 -0.9999968 -0.001143455 -0.002287685 -0.9999965 -0.001473009 -0.002252101 -0.9975094 0.01884192 -0.06797248 -1 -1.08498e-5 -9.09651e-6 -1 0 1.49426e-7 -1 -1.04565e-5 2.33565e-6 -1 0 1.0368e-6 -1 2.07139e-5 3.04745e-7 -1 -1.2909e-6 6.74617e-7 -1 -2.26104e-7 7.58076e-7 -1 -2.32833e-5 9.529e-6 -1 -9.46786e-7 0 -0.9979222 -0.05995339 0.02360403 -1 -1.56777e-6 0 -1 5.06251e-6 0 -1 -3.50114e-6 0 -1 -2.09905e-6 0 -1 2.71339e-6 0 -0.9999996 -7.84572e-4 -5.59998e-4 -0.9999995 -0.001012802 0 -0.9999279 0.002775669 0.01168221 -1 -3.72099e-7 0 -1 2.51364e-7 0 -1 -5.30985e-7 0 1.87876e-4 -0.9837052 -0.179789 0 -0.9836958 -0.1798406 -0.01844549 -0.9854419 -0.1690094 0.3357252 -0.9126423 -0.2331795 -0.01964479 -0.9967125 -0.07860261 -0.001394033 -0.9964849 -0.08376109 0 0.7765353 -0.6300737 0.02073502 0.8582641 -0.5127893 0.03397303 0.8643296 -0.501777 0 0.9275849 -0.3736127 0 0.9846693 -0.1744317 0.107786 0.960893 -0.2550818 0 0.9964615 -0.08405065 0 0.6930632 -0.7208768 0.05468946 0.6387763 -0.7674465 0 0.5566944 -0.8307174 0 0.450192 -0.8929318 0.04714703 0.3364042 -0.9405368 6.24309e-5 0.2875998 -0.9577507 0.05027407 -0.3497911 -0.9354779 -0.005899786 -0.2884575 -0.9574747 0.008476078 -0.007162868 -0.9999384 0.103591 -0.08385717 -0.9910787 -4.23e-5 0.08405089 -0.9964615 0.05295813 -0.6497662 -0.7582871 0 -0.5634757 -0.8261327 0 -0.4571487 -0.8893904 0 -0.9308922 -0.3652944 0.04465436 -0.8592224 -0.5096498 0.01652884 -0.871814 -0.4895581 0 -0.7819098 -0.6233916 0 -0.6989415 -0.7151789 0.965853 0.04658496 -0.2548685 0.9403675 0.302931 -0.1547312 0.9538816 0.252507 -0.1623275 0.9188221 0.1341537 -0.3711724 0.9568747 0.1861923 -0.2229871 0.9544763 0.1201892 -0.2730014 0.9256091 0.1411158 -0.3511899 0.9100116 0.09911936 -0.4025597 0.8915132 0.09403795 -0.4431266 0.8652691 0.0642001 -0.4971799 0.8538465 0.07138746 -0.5156064 0.8177893 0.01956629 -0.5751851 0.7499547 -0.08089983 -0.6565235 0.7577382 -0.07253992 -0.6485144 0.7614147 -0.07966053 -0.6433522 0.7568705 -0.06698328 -0.6501235 0.7840297 -0.001945257 -0.6207203 0.8154376 0.02018904 -0.5784929 0.7568814 -0.07102346 -0.6496816 0.754858 -0.06772661 -0.6523823 0.7546295 -0.05956381 -0.653442 1.90738e-6 -1 0 1.19136e-6 -1 0 1.92412e-6 -1 -1.96699e-6 3.87458e-6 -1 0 -0.008774876 -0.9999597 -0.001943826 -0.01369106 -0.9998972 -0.004267692 -0.04797399 -0.9984916 -0.02670341 -0.03059458 -0.9969649 -0.07158839 -0.2475581 -0.968873 2.7058e-4 -0.2265905 -0.9709317 -0.07712632 -0.3308731 -0.9418221 -0.05911374 -0.3579341 -0.9259815 -0.1201736 -0.5222059 -0.8517382 -0.04293048 -0.6266404 -0.7418061 -0.2388423 -0.7073513 -0.6835429 -0.1800645 -0.8184157 -0.5511813 -0.1624655 -0.7636195 -0.6271404 -0.1535582 -0.7379875 -0.6737067 -0.03865182 -0.7389834 -0.6703284 0.06755256 -0.9906559 -0.09260332 -0.1001281 -0.9821395 -0.1689672 -0.08277738 -0.9620851 -0.2630078 0.07224476 -0.9392929 -0.2898222 0.1836627 -0.9615028 -0.2328659 -0.1458972 -0.9364146 -0.348187 0.04351454 -0.9522452 -0.2483542 -0.1776211 -0.917216 -0.3824762 -0.111476 -0.8973616 -0.3828539 -0.2194654 -0.8975984 -0.3859193 -0.2130343 -0.8927136 -0.3917865 -0.2226337 -0.1510012 -0.9828641 0.1057205 -0.1509894 -0.9828655 0.1057239 -0.1512879 -0.9827991 0.1059142 -0.1523567 -0.9829643 0.102805 -0.6711692 -0.5732981 0.4699589 -0.5470032 -0.6740776 0.496394 -0.7240229 -0.4677323 0.5069687 -0.6550533 -0.3999918 0.6410241 -0.776759 -0.3175238 0.5438972 -0.8126124 -0.1260907 0.5690011 -0.8126142 -0.1260915 0.5689983 -0.2034151 -0.9764362 0.07207363 -0.210476 -0.9508154 0.2272664 -0.1384483 -0.9856154 0.09692472 -0.5487737 -0.675286 0.4927843 -0.5396859 -0.7524033 0.3776621 -0.3924105 -0.8776358 0.2752622 -0.3599296 -0.8297749 0.426526 -0.3690611 -0.8775866 0.3059998 -0.6687332 -0.6993744 0.2523318 -0.1533839 -0.982966 0.1012493 -0.1671205 -0.9821452 0.08638113 -0.1689052 -0.9834793 0.06511175 -0.3227313 -0.9445376 0.06077229 -0.8782021 -0.439917 -0.187708 -0.8620829 -0.4576511 -0.217643 -0.8989268 -0.3919296 -0.1957595 -0.8170709 -0.5512371 -0.1689172 -0.7904144 -0.6061506 -0.08846879 -0.7738566 -0.6304708 -0.06043529 -0.835376 -0.5450683 -0.07104516 -0.6897419 -0.721048 0.0659241 -0.6441038 -0.6490548 0.4047939 -0.6280555 -0.7141799 0.3090201 -0.6165476 -0.7243934 0.3084207 -0.6220064 -0.7467785 0.2354358 -0.6146803 -0.7548552 0.2288271 -0.3397776 -0.9373874 0.07652539 -0.3407285 -0.9272732 0.1551409 -0.4353694 -0.8884962 0.1450107 -0.4793799 -0.8469461 0.2299508 -0.5129929 -0.829695 0.2201015 -0.6237225 -0.7265568 0.2882457 -0.7327508 -0.6767795 0.07103502 -0.2515975 -0.9677476 -0.01278567 -0.1914506 -0.9764394 0.09956347 -0.2049763 -0.9765406 0.06597858 -0.7964686 -0.5937158 -0.114627 -0.791015 -0.5943127 -0.1452171 -0.7865672 -0.5991916 -0.1492695 -0.7777559 -0.6215565 -0.09361267 -0.7619376 -0.6287242 -0.1554255 -0.7249273 -0.6824139 -0.09376394 -0.6885139 -0.7250782 0.01449888 -0.6922745 -0.7206196 0.03825539 -0.668659 -0.7431168 -0.02593404 -0.6314505 -0.7723351 0.06905734 -0.5897811 -0.8047001 -0.06794148 -0.5414048 -0.8403243 0.02713084 -0.5157593 -0.8534792 -0.07460391 -0.5161303 -0.8532149 -0.07505941 -0.9414263 -0.2701827 -0.2017869 -0.9993762 -0.001374781 -0.03528833 -0.9921704 -0.0785306 -0.09711325 -0.9953618 -0.05764424 -0.07702165 -0.9978585 -0.02922874 -0.05851531 -0.9975714 -0.03816562 -0.05826526 -0.9976649 -0.0416575 -0.05412608 -0.731924 -0.5897852 0.3412343 -0.6623663 -0.6929853 0.2846795 -0.6674267 -0.6875101 0.2861319 -0.6965454 -0.676449 0.2392516 -0.690831 -0.6951003 0.1989682 -0.6734962 -0.7053894 0.2209723 -0.7558177 -0.647239 0.09910249 -0.7159336 -0.6936691 0.07913416 -0.7425055 -0.6695968 -0.01805067 -0.7436427 -0.6685486 -0.006193518 -0.8312499 -0.5466707 -0.1008704 -0.8316503 -0.5327625 -0.1565948 -0.8705052 -0.473853 -0.1329823 -0.8514857 -0.501074 -0.1545871 -0.8528795 -0.47254 -0.2220419 -0.8754644 -0.4453289 -0.1877353 -0.9412779 -0.2721823 -0.1997818 -0.9528793 -0.2226701 -0.2060077 -0.9625353 -0.2111128 -0.1701684 -0.7336863 -0.1742813 -0.6567575 -0.7471637 -0.1140516 -0.6547815 -0.7198103 -0.03378009 -0.6933484 -0.7004659 -0.05124074 -0.7118441 -0.7155976 -0.01335358 -0.6983851 -0.7548934 -0.1365138 -0.6414827 -0.7553744 -0.2282494 -0.6142571 -0.7623877 -0.2379258 -0.6017944 -0.7622138 -0.3168461 -0.564481 -0.7654905 -0.3203891 -0.5580099 -0.7653866 -0.3990456 -0.5049219 -0.7769986 -0.4077541 -0.4795932 -0.7440631 -0.666552 -0.04559153 -0.7436851 -0.6661114 -0.05681663 -0.7464238 -0.6643912 -0.03789293 -0.7612016 -0.6405043 -0.1016192 -0.75932 -0.6411342 -0.111267 -0.7592626 -0.6301345 -0.1626374 -0.7538822 -0.6312052 -0.1823229 -0.7599415 -0.4778439 -0.4406294 -0.7866978 -0.5131093 -0.3432573 -0.7625502 -0.5200304 -0.3848187 -0.763943 -0.5853423 -0.2715982 -0.7606029 -0.5863082 -0.2787938 -0.7628042 -0.611607 -0.2099207 -0.9421944 -0.03534877 -0.3331973 -0.9588938 -0.01148098 -0.2835327 -0.9591029 -0.0714271 -0.2738979 -0.9643282 -0.05143576 -0.2596641 -0.9643623 -0.09932786 -0.2452334 -0.9671677 -0.08664643 -0.2389121 -0.9672027 -0.127484 -0.2196972 -0.9601888 -0.2376356 -0.1468567 -0.9691052 -0.1537462 -0.1928659 -0.9685602 -0.1529763 -0.1961872 -0.9684872 -0.1210157 -0.2176873 -0.9968647 -0.04010641 -0.06820785 -0.9974242 -0.02866071 -0.06575542 -0.9968004 -0.02400636 -0.07624113 -0.996806 -0.02391088 -0.07619845 -0.995978 -0.01380467 -0.08852851 -0.9959266 -0.01441037 -0.08900982 -0.9897655 0.0161128 -0.1417906 -0.8721552 -0.4390208 -0.2158846 -0.8927542 -0.3731606 -0.2524704 -0.8892124 -0.3619081 -0.2798641 -0.8886467 -0.3364837 -0.311586 -0.8890847 -0.3365526 -0.3102592 -0.8891276 -0.2848772 -0.3581862 -0.8884649 -0.2844622 -0.3601547 -0.8885416 -0.2289827 -0.3975687 -0.8861922 -0.2263662 -0.4042546 -0.8863167 -0.1715391 -0.4301361 -0.8812643 -0.1636675 -0.4433805 -0.8814396 -0.1164123 -0.4577255 -0.8722748 -0.09891217 -0.4789083 -0.8719564 -0.04414552 -0.4875892 -0.8446319 -0.0163089 -0.5350993 -0.2264988 -0.9705529 -0.08200949 -0.6363977 -0.7686122 -0.06506443 -0.772251 -0.05362707 -0.6330503 -0.4531394 -0.07515764 -0.8882657 -0.1751874 -0.0830059 -0.9810298 -0.9622387 -0.02295041 -0.2712377 -0.93077 -0.03082311 -0.3643038 -0.9951646 -0.008282542 -0.09787195 -0.9842824 -0.04641562 -0.1703931 -0.9841915 -0.05108898 -0.1695796 -0.9841914 -0.05108678 -0.1695801 -0.9841911 -0.09109497 -0.1518873 -0.9841915 -0.09109002 -0.1518872 -0.9841912 -0.1255396 -0.1249303 -0.9841912 -0.125539 -0.1249303 -0.9841908 -0.152332 -0.09035325 -0.9841915 -0.152327 -0.09035331 -0.9841907 -0.16983 -0.05026513 -0.984192 -0.1698222 -0.05026525 -0.9814577 -0.1855837 0.04795414 -0.9705145 -0.2401678 -0.02051877 -0.05915719 -0.9946086 -0.08517146 -0.1755185 -0.9788588 -0.105018 -0.1751639 -0.9538964 -0.24372 -0.2386936 -0.9311642 -0.2756061 -0.1756758 -0.9164153 -0.3596123 -0.1744919 -0.8468853 -0.5023325 -0.2050766 -0.6937566 -0.690395 -0.1757788 -0.7697379 -0.6136819 -0.1744899 -0.846888 -0.5023289 -0.1751894 -0.08300632 -0.9810295 -0.1744912 -0.284038 -0.9428019 -0.1744923 -0.2840369 -0.942802 -0.1755082 -0.4500518 -0.8755857 -0.2498415 -0.4980143 -0.8303982 -0.1754313 -0.5547389 -0.8133196 -0.1747692 -0.6881833 -0.704173 -0.8810432 -0.04887878 -0.4705038 -0.8422138 -0.08760666 -0.5319784 -0.8403283 -0.1563684 -0.5190352 -0.840329 -0.1563691 -0.5190336 -0.8403288 -0.2788056 -0.464882 -0.8403293 -0.2788019 -0.4648832 -0.8403282 -0.3842374 -0.3823746 -0.8403288 -0.3842361 -0.3823745 -0.8403301 -0.4662273 -0.2765457 -0.8403269 -0.4662339 -0.2765442 -0.8403276 -0.519789 -0.1538472 -0.8403296 -0.5197856 -0.1538478 -0.842213 -0.5324133 -0.0849325 -0.8039358 -0.5925967 -0.05016463 -0.6335592 -0.06517022 -0.7709447 -0.5388609 -0.1098221 -0.8352054 -0.5362012 -0.2434876 -0.8082093 -0.5362006 -0.2434887 -0.8082092 -0.536201 -0.4341393 -0.7238865 -0.5362011 -0.4341396 -0.7238863 -0.5362013 -0.598309 -0.5954113 -0.5362007 -0.5983105 -0.5954104 -0.5362039 -0.7259833 -0.4306199 -0.536203 -0.7259845 -0.4306194 -0.5362022 -0.8093809 -0.2395617 -0.5362018 -0.8093813 -0.2395611 -0.5389509 -0.8349342 -0.1114312 -0.4580815 -0.8857535 -0.07484668 -0.9883975 -0.09078943 -0.1217686 -0.7336922 -0.1742904 -0.6567485 -0.7185592 -0.5711248 0.3968493 -0.7148377 -0.6047626 0.3510974 -0.7707062 -0.5915982 0.2366927 -0.7579015 -0.5969443 0.2631404 -0.7648102 -0.6086732 0.2111452 -0.6210235 -0.7735828 0.1260934 -0.8080335 -0.5888082 -0.01966518 -0.6992511 -0.7133954 0.04598873 -0.7276172 -0.6844436 -0.04593652 -0.7282494 -0.6771125 -0.1056952 -0.6970785 -0.6949582 -0.1763936 -0.7309461 -0.6800229 -0.05732947 -0.7423636 -0.6642004 -0.08794379 -0.7404904 -0.6651977 -0.09584385 -0.7661533 -0.6028785 -0.2225905 -0.7228371 -0.6135766 -0.3178527 -0.704985 -0.2551506 -0.6617359 -0.7286491 -0.3393874 -0.5948839 -0.736144 -0.343839 -0.582981 -0.7343941 -0.4393411 -0.517344 -0.7517253 -0.4525724 -0.4796741 -0.742722 -0.538508 -0.3979614 -0.755839 -0.5456972 -0.3618317 -0.7462418 -0.6014019 -0.2853753 -0.7574201 -0.6176418 -0.2117391 -0.8233453 -0.04394382 -0.565837 -0.8180041 -0.04434281 -0.5735006 -0.812551 -0.0453788 -0.5811212 -0.8069753 -0.04700773 -0.5887116 -0.8013648 -0.04924643 -0.5961452 -0.7956297 -0.05209165 -0.6035395 -0.7897295 -0.05559295 -0.6109312 -0.7838364 -0.05956828 -0.6181038 -0.7777232 -0.06435859 -0.6253037 -0.7850922 -0.05792194 -0.6166646 -0.7726085 -0.0447883 -0.633301 -0.7667855 -0.03969359 -0.6406751 -0.7608411 -0.03538525 -0.6479728 -0.7547483 -0.0318796 -0.6552395 -0.7454706 -0.02791422 -0.6659538 -0.9476793 -0.07545715 -0.310178 -0.941544 -0.07729279 -0.3279036 -0.9349384 -0.08081519 -0.3454841 -0.927845 -0.08603435 -0.3629074 -0.9201692 -0.06984668 -0.3852406 -0.9162137 -0.06658363 -0.3951192 -0.9116775 -0.06380987 -0.4059218 -0.9069632 -0.06177628 -0.4166553 -0.9948189 -0.1003184 -0.016483 -0.9941733 -0.1018537 -0.03528791 -0.9930286 -0.1047376 -0.05407816 -0.9917168 -0.1081662 -0.06926882 -0.9923502 -0.1063756 -0.06265437 -0.9916614 -0.1002021 -0.08103841 -0.9905705 -0.09519654 -0.09852862 -0.9536828 -0.1165896 0.2773013 -0.9591283 -0.1185613 0.2569361 -0.9644323 -0.1225878 0.2341849 -0.9645959 -0.1227954 0.2334014 -0.9703434 -0.1167177 0.2116856 -0.9742773 -0.1134477 0.1947138 -0.9766774 -0.111725 0.1833547 -0.8192611 -0.1260789 0.5593883 -0.8319894 -0.1277766 0.5398766 -0.8440394 -0.1311502 0.5199973 -0.846915 -0.1324167 0.5149765 -0.856324 -0.1278473 0.5003644 -0.8682481 -0.1235283 0.4805061 -0.7519593 -0.4671399 0.4651213 -0.7705023 -0.4507058 0.4507665 -0.8389905 -0.4408408 0.3189898 -0.8389931 -0.4408398 0.3189846 -0.8891468 -0.4210531 0.1792548 -0.8891496 -0.4210459 0.1792577 -0.9192485 -0.3920035 0.03627145 -0.9192521 -0.391995 0.03627008 -0.928947 -0.3539773 -0.1084328 -0.9289485 -0.3539729 -0.1084335 -0.917866 -0.3082334 -0.2500284 -0.9178674 -0.3082295 -0.2500281 -0.8692263 -0.2341791 -0.4354375 -0.902071 -0.06054472 -0.42732 -0.8970341 -0.06008219 -0.4378587 -0.8918222 -0.06039553 -0.4483367 -0.883755 -0.06201046 -0.4638233 -0.8752803 -0.06593549 -0.4791 -0.8694361 -0.06930971 -0.4891596 -0.8406363 -0.04701787 -0.5395554 -0.8343526 -0.04505985 -0.5493865 -0.8286069 -0.04414308 -0.558088 -0.8634325 -0.07342749 -0.4990919 -0.8572439 -0.0783264 -0.5089183 -0.8690034 -0.06753808 -0.4901755 -0.8526709 -0.05373579 -0.5196778 -0.8467299 -0.04989206 -0.5296785 -0.7728527 -0.1144201 -0.6241849 -0.7728531 -0.1144102 -0.6241863 -0.8471788 -0.1684358 -0.5039023 -0.8471786 -0.168442 -0.5039004 -0.9017134 -0.2181972 -0.3732331 -0.9761825 -0.09252506 -0.1962318 -0.9854691 -0.0886926 -0.1448602 -0.9818067 -0.08888387 -0.1677956 -0.9785565 -0.09074407 -0.1849129 -0.9736241 -0.09488719 -0.2074909 -0.9708591 -0.09780406 -0.2187854 -0.9729774 -0.09519094 -0.210366 -0.969161 -0.08766436 -0.2303085 -0.966737 -0.08403062 -0.241575 -0.9632732 -0.08005821 -0.2563117 -0.9585429 -0.07685554 -0.2743882 -0.9533437 -0.07532143 -0.2923398 -0.9788773 -0.1104993 0.1720156 -0.9809098 -0.1097373 0.160542 -0.9836015 -0.1093142 0.1434524 -0.9865256 -0.1106436 0.1205213 -0.9886998 -0.1138913 0.0974763 -0.9894152 -0.1162554 0.08684754 -0.990657 -0.112734 0.07674473 -0.9924896 -0.1076071 0.05818122 -0.9938111 -0.1037843 0.03960126 -0.9946351 -0.1012994 0.02096796 -0.9949709 -0.1001408 0.002218902 -0.7215307 -0.6614903 0.2045091 -0.7597585 -0.6068076 0.2335628 -0.8030069 -0.5835184 0.1211869 -0.8030085 -0.5835164 0.1211855 -0.8391581 -0.5436174 -0.01714205 -0.8391571 -0.5436191 -0.01714038 -0.8568808 -0.4912908 -0.1561689 -0.8568833 -0.491286 -0.1561701 -0.8554644 -0.4281696 -0.291293 -0.8554613 -0.4281778 -0.2912899 -0.8347687 -0.3549007 -0.4209596 -0.8347688 -0.3549009 -0.4209591 -0.7953552 -0.2738757 -0.5407423 -0.7953569 -0.2738747 -0.5407403 -0.7313445 -0.1776267 -0.658471 -0.7285796 -0.2024888 -0.6543472 -0.6810047 -0.1120103 -0.7236618 -0.6927299 -0.06466776 -0.718292 -0.685954 -0.04975545 -0.7259418 -0.691599 -0.01968884 -0.7220134 -0.6888651 -0.01224696 -0.7247862 -0.879482 -0.1209644 0.4603032 -0.8900453 -0.1201332 0.4397584 -0.8999183 -0.1210497 0.4189202 -0.9082474 -0.1234573 0.3998063 -0.9152027 -0.126722 0.3825517 -0.9179922 -0.1285884 0.375174 -0.9223403 -0.1255633 0.3654071 -0.9295257 -0.1214033 0.3482002 -0.9362384 -0.1184491 0.3307983 -0.9425152 -0.1166375 0.3131466 -0.9483253 -0.1160273 0.2953246 -0.8164169 -0.3166788 0.4828853 -0.8202314 -0.3123467 0.4792286 -0.8850162 -0.305628 0.351195 -0.8850128 -0.3056342 0.3511981 -0.9331039 -0.2919107 0.2100127 -0.933103 -0.2919133 0.2100129 -0.9601721 -0.2717688 0.06489485 -0.9601739 -0.2717618 0.06489616 -0.9658966 -0.245403 -0.08259129 -0.9658957 -0.2454057 -0.08259308 -0.9500351 -0.2136915 -0.2275289 -0.9500343 -0.2136965 -0.2275272 -0.9127138 -0.1769688 -0.3682875 -0.9313464 -0.08271014 -0.3546166 -0.9235618 -0.07321536 -0.376395 -0.6805678 -0.5660555 -0.4651976 -0.7254752 -0.4337065 -0.5344011 -0.7849678 -0.3593561 -0.5046668 -0.7856981 -0.3176566 -0.5308229 -0.8369577 -0.1895349 -0.513399 -0.8350079 -0.1527239 -0.5286182 -0.8534516 -0.03637641 -0.5199011 -0.8555439 -0.0571835 -0.5145627 -0.9785172 -0.0983355 -0.1812019 -0.978517 -0.09833341 -0.1812048 -0.9347136 -0.285197 -0.2120687 -0.9246787 -0.3029402 -0.2306442 -0.8868511 -0.3889959 -0.2493537 -0.8315712 -0.4766454 -0.2851292 -0.811596 -0.4929344 -0.3135725 -0.759018 -0.5560989 -0.3385938 -0.7447651 -0.5687746 -0.3490278 -0.6461156 -0.700706 -0.3025657 0 -0.5193854 -0.8545401 0 -0.5195749 -0.854425 0 -0.8185949 -0.5743713 0 -0.8186442 -0.5743011 0 -0.97952 -0.2013472 0 -0.9795179 -0.2013577 0 -0.8186839 -0.5742445 0 -0.8185757 -0.5743986 0 -0.5195637 -0.8544318 0 -0.5193843 -0.8545409 -0.4444903 -0.5641082 -0.6958523 -0.712249 -0.4162778 -0.5651676 -0.7308383 -0.3569443 -0.5817785 -0.7542758 -0.2854897 -0.5912392 -0.7653496 -0.2944035 -0.5723344 -0.7956576 -0.1641494 -0.5830814 -0.8029946 -0.1697777 -0.5712926 -0.8145605 -0.08199876 -0.5742539 -0.8270446 -0.1109961 -0.5510691 -0.8348362 -0.1029192 -0.5407923 -0.00139898 -0.9999899 -0.004274487 -0.02041363 -0.993709 0.1101173 -0.05924797 -0.9961391 0.06478291 -0.2270327 -0.9728337 -0.04528748 -0.2480063 -0.9683688 -0.02747303 -0.4575819 -0.8847925 0.08809691 -0.4043307 -0.9143811 -0.0205909 -0.5429617 -0.8397575 3.81229e-5 -0.637745 -0.7702476 -1.3766e-4 -0.6115214 -0.7911025 -0.01408284 -0.8044721 -0.592991 0.03444355 -0.952512 0.007466852 -0.3044097 -0.993262 -0.1158912 0 -0.9446572 -0.3250508 -0.04432904 -0.9706989 -0.2402094 0.006566047 -0.8582572 -0.5132187 -0.001108646 -0.7600582 -0.6495765 -0.01903027 0.1212688 0 0.9926197 0.2149941 -0.03026521 0.9761463 0.2676439 -0.01694077 0.9633691 0.6070005 -0.026147 0.7942712 0.5210215 -0.008387207 0.8535024 0.4222012 0.006664872 0.9064778 0.3108163 -0.008924722 0.9504281 0.8699074 -0.03384351 0.4920527 0.820145 0.001830518 0.5721529 0.607392 -0.003982245 0.7943924 0.7017322 -0.08866941 0.7069015 0.6765936 -0.06952953 0.7330667 0.8860594 0 0.463572 0.8928481 -0.03631818 0.4488912 0.9021241 -0.08130484 0.4237471 0.8964339 -0.0627911 0.4387068 -0.001210093 0 0.9999993 -0.001210153 0 0.9999994 0 0 -1 -0.6634345 0 0.7482345 -0.6634389 0 0.7482306 0.003538727 0 -0.9999938 0.003527462 0 -0.9999939 0.002631127 0 -0.9999966 0.002631127 0 -0.9999966 0.7424067 4.4772e-4 -0.6699493 0.7137507 -0.0080868 -0.7003532 0.8299262 0.01817345 -0.5575772 0.7523065 -0.04158836 -0.6574994 0.8935519 0.04695492 -0.4464979 0.8083538 -0.03980565 -0.5873497 0.9860423 0.05604994 -0.1567769 0.9940372 0.001455903 -0.1090322 0.9947778 0.03407043 -0.09621 0.9931856 0.04567104 -0.1072224 0.9954314 0.02450799 -0.09228134 0.9969945 0.008034348 -0.07705473 0.870197 -0.005803287 -0.4926698 0.9093686 -2.60736e-6 -0.4159916 0.9256649 2.83326e-6 -0.3783448 0.9292797 5.94958e-4 -0.3693763 0.9606812 -0.002306878 -0.2776442 0.9514137 -0.009945034 -0.3077551 0.9922295 0.0158022 -0.1234145 0.9799345 -0.02563631 -0.1976649 0.9972062 0 -0.07469809 0.290551 0.06800454 -0.95444 0.1939595 -0.001775383 -0.9810079 0.4708923 9.03869e-4 -0.8821903 0.4694612 3.2748e-4 -0.8829531 0.631658 -3.16801e-4 -0.7752472 0.6168712 -0.006803989 -0.7870348 0.6872503 -1.56884e-4 -0.7264208 0.09914612 -1.15934e-4 -0.9950729 0.001502513 0 -0.9999989 0.001501917 0 -0.9999989 0.001210331 0 -0.9999993 0.001210331 0 -0.9999994 0.001210331 0 -0.9999993 0.001210272 1.70696e-7 -0.9999993 0.001210689 0 -0.9999994 0.001210153 0 -0.9999994 0.00121051 -1.25752e-7 -0.9999993 0.001209318 7.33812e-7 -0.9999994 0.001210331 0 -0.9999993 0.001211047 -1.44884e-6 -0.9999994 0.001210331 0 -0.9999993 0.001210331 0 -0.9999993 0.001210331 0 -0.9999993 0.001210391 -2.87794e-7 -0.9999993 0.001210331 0 -0.9999993 0.001209437 -1.61114e-7 -0.9999993 0.00121051 0 -0.9999993 0.4034974 0.9149808 0 0.4034904 0.9149839 0 0.769158 0.6390587 0 0.7691407 0.6390796 0 0.973419 0.2290315 0 0.9734159 0.2290446 0 0.1001737 0.9949572 0.005059242 0.1025835 0.9947245 0 0.1025626 0.9947265 -7.10091e-5 0.1891376 0.9819507 9.48346e-5 0.6922595 0.7020648 0.1669785 0.645531 0.750863 0.1396226 0.8660151 0.4816054 0.1344406 0.857231 0.4944739 0.1437034 0.9845148 0.1648787 0.05954456 0.9820518 0.175797 0.06833511 0.9748062 0.2230257 0.003552794 0.8808053 0.4483508 0.1521964 0.9873431 0.1458288 0.0623492 0.9865307 0.1496208 0.06611233 0.4495346 0.8929296 -0.02440345 0.4480125 0.8874678 0.1081011 0.3633157 0.931114 0.03207188 0.5333847 0.8454539 0.02662122 0.6423448 0.7647949 0.04982089 0.7024023 0.7094523 0.05752074 0.7884107 0.6049495 0.1115567 0.9403313 0.3372634 0.04506075 0.9741034 0.1995491 0.1063149 0.9892671 0.1428012 0.03096151 0.9843065 0.1544647 0.08533066 0.9826434 0.1648151 0.08513557 0.8756793 0.4465688 0.1837447 0.8605788 0.4788882 0.1734076 0.6409069 0.742659 0.1941546 0.6472524 0.7495316 0.1388047 0.3625346 0.9294977 0.06784528 0.3632991 0.9291533 0.0684697 0.2045298 0.9788477 0.004977166 0.9999965 0.002683699 4.27895e-5 0.9999943 0.002949655 0.001621186 0.9999958 0.002843499 6.15924e-4 0.9999966 0.002000331 -0.001705229 1 1.85799e-6 0 0.2814489 0.8254566 0.4892932 0.4887744 0.09429204 0.8672997 0.526104 0.2474681 0.8136179 0.4783886 0.320621 0.8175247 0.4634931 0.6873952 0.559162 0.408827 0.6043757 0.683806 0.4483225 0.4606178 0.7660537 0.7795258 0.2447504 0.5765735 0.7795268 0.2447562 0.5765696 0.5900179 0.6792864 0.4364045 0.5900262 0.6792805 0.4364024 0.2915978 0.9319083 0.21568 0.3053368 0.9228934 0.2346006 0.9478215 0.2447497 0.2042839 0.9478209 0.2447521 0.2042838 0.7173973 0.6792884 0.1546234 0.7173997 0.679287 0.1546186 0.3236628 0.9435975 0.06975835 0.3064882 0.9509236 0.04253727 0.9854865 0.1697542 0 0.9682219 0.2500195 0.006071925 0.636025 0.7716686 1.65791e-4 0.7261168 0.6875365 0.006924092 0.8078727 0.5893571 -8.27674e-5 0.9123678 0.4093716 5.39654e-5 0.2276495 0.9737432 0 0.2276477 0.9737436 0 0.4620512 0.8856511 0.04615974 0.3096312 0.9508568 0 0.3079461 0.9514039 -3.25048e-4 0.3067655 0.9517852 0 0.306766 0.951785 0 0.4245184 0.9049017 -0.03061527 0.1025573 0.9947271 -1.50028e-4 0.2140949 0.9157679 0.3399009 0.2632745 0.9645019 0.02055794 0.2903326 0.956925 -0.001269519 0.4623242 0.8861836 -0.03057831 0.5817239 0.8114243 -0.05646288 0.5834842 0.8096672 -0.06312865 0.6243005 0.7743159 -0.1033627 0.6985195 0.7016752 -0.1404362 0.8429315 0.5221717 -0.1296272 0.8785097 0.4470046 -0.1685456 0.9711467 0.1695309 -0.1677309 0.9733106 0.1461282 -0.1769552 0.9837682 0.1694521 -0.05904543 0.9837668 0.1694595 -0.05904608 0.9109976 0.4087712 -0.05467808 0.8493198 0.5222146 -0.07712334 0.8069344 0.5886521 -0.04843181 0.6355658 0.7711039 -0.03814643 0.7273409 0.2288371 -0.6469999 0.7478176 0.05895841 -0.6612812 0.7499612 0.1656901 -0.6403944 0.9491707 0.1648795 -0.2681227 0.9491698 0.1648938 -0.2681168 -0.5823246 0.802215 -0.1317161 -0.09798705 0.5638025 0.8200765 -0.6596614 0.6451437 0.3855339 -0.540937 0.2319918 0.8084349 -0.9989411 -0.001134276 0.04599595 -0.8718926 0.001139938 0.4896959 -0.8795775 0 0.4757558 -0.8956165 -0.03549051 0.4434092 -0.939513 -0.2846065 0.1905638 -0.7621527 -0.01090204 0.6473056 -0.9014474 0 -0.4328889 -0.9815647 -0.01288056 0.190696 -0.9993761 3.86517e-4 -0.03531765 -0.9480871 -2.68632e-4 -0.3180109 -0.8455146 0.009583234 -0.5338665 -0.2528846 0.04724252 0.9663423 -0.4490293 0 0.8935171 -0.4407864 3.26453e-4 0.897612 -0.4333863 6.83192e-4 0.901208 -0.3120391 0.01277887 0.9499834 -0.4260314 -0.007754683 0.9046752 -0.3546727 0.01485431 0.9348726 -0.3923965 0.003953695 0.9197878 -0.2669361 0.02887326 0.9632817 -0.2462545 0.03698831 0.9684991 -0.3483858 -0.02637368 0.9369801 -0.3184295 -0.01137381 0.9478783 -0.3145831 -0.02171844 0.9489815 -0.1869026 0 0.9823785 -0.1637665 0.007490932 0.9864708 -0.1743973 0.005465567 0.9846602 -0.1929649 0.00252068 0.9812024 -0.1956827 0.002160549 0.9806649 -0.1816392 0.004252493 0.9833561 -0.1481457 0.01119643 0.9889022 -0.1348256 0.01474446 0.9907596 -0.1565285 0.008093833 0.9876404 -0.1073458 0.001660823 0.9942204 0.02098953 -0.006257414 0.9997602 7.22854e-4 0.003863275 0.9999923 0.1021556 0 0.9947685 -0.3266125 0 0.9451584 -0.3479629 -0.005444824 0.9374925 -0.09655559 0.004511237 0.9953175 -0.1175197 0 0.9930706 0.3508487 0 0.9364323 0.1981438 -0.0257259 0.9798353 0.3899536 0.01994723 0.9206185 0.1627733 -0.006567895 0.9866417 0.0733906 0 0.9973034 0.006692349 0.008411109 0.9999423 0.02382218 0.006305396 0.9996964 -0.4370433 0.3474102 0.8296381 -0.4183712 0.3013958 0.8568116 -0.4001517 0.2610622 0.878479 -0.2536799 0.04956179 0.9660177 -0.3253182 0.1135043 0.9387678 -0.2672345 0.0479784 0.9624364 -0.2309682 0.01279246 0.9728773 -0.3222193 0 0.9466652 -0.4275667 0.3180049 0.8462032 -0.4327111 0.3355805 0.8367478 -0.295988 0.02132672 0.9549536 -0.2668896 0.04679906 0.9625902 -0.3814233 -0.06298941 0.9222519 -0.2199643 0.04098546 0.9746466 0.3523887 -0.02798956 0.9354351 0.1613744 -0.6395067 0.7516578 0.3025078 -0.0491681 0.9518779 0.3139245 0 0.9494481 0.254063 0.05460542 0.965645 0.3214541 0 0.9469252 0.3360028 0.03008723 0.9413803 0.2129852 0.007194519 0.977029 0.2496134 0.02781367 0.9679461 0.2707427 0.04811698 0.9614485 0.2970216 0.077735 0.9517014 0.355762 0.1651479 0.9198694 0.4335019 0.3235444 0.8410679 0.4366119 0.3319983 0.8361502 0.4309498 0.3129909 0.8463563 -0.1465404 5.05244e-6 0.9892047 -0.2298066 0.004733502 0.9732248 -0.3395297 -0.03956961 0.9397627 -0.1318035 -6.139e-7 0.991276 -0.1106371 2.76055e-4 0.9938609 -0.03527516 0.008164763 0.9993443 0.001643359 -0.006018877 0.9999806 0.1117683 0.002474308 0.9937313 0.1133362 0.002224385 0.9935543 0.1447572 0 0.9894673 -0.04761195 0 0.998866 -0.07850378 0.00235176 0.9969111 -0.1368951 -5.2004e-4 0.9905855 -0.3235986 0.002645194 0.9461908 -0.2036146 -0.02629607 0.978698 -0.3506876 0 0.9364925 0.211588 0.00731194 0.9773316 0.2484192 0.02807974 0.9682456 0.268804 0.04796755 0.9619998 0.3228653 -0.02580577 0.9460932 0.2157024 0.05019855 0.975168 0.2990091 0 0.9542503 0.3193494 0.03548139 0.9469726 0.4310853 0.3223574 0.842764 0.323459 0.1096147 0.9398718 -0.1406384 0 0.9900611 -0.1286351 2.61939e-4 0.991692 -0.1074703 0.001524567 0.9942072 -0.07273358 0.00595963 0.9973337 0 -0.01082313 0.9999415 0.1102579 0.01464414 0.9937952 0.1095573 0.01486814 0.9938694 0.1370598 0.008133947 0.9905294 -0.4111401 0.280471 0.8673523 -0.4401082 0.3502324 0.8268265 -0.2551574 0.04946428 0.9656335 -0.3249841 0.1113521 0.9391412 -0.268804 0.04796892 0.9619997 -0.2325423 0.01278877 0.9725022 -0.3032826 0 0.9529007 -0.2633813 0.02167445 0.9644483 -0.2363345 0.03785282 0.9709342 -0.1561138 0 0.9877391 -0.1822489 0.001324534 0.9832516 -0.3229307 -0.015823 0.9462903 0.001209914 1.6245e-7 -0.9999993 0.001208782 0 -0.9999993 0.001210391 0 -0.9999993 0.001210212 0 -0.9999994 0.001210093 0 -0.9999993 0.001210331 0 -0.9999994 0.001209676 -4.23022e-7 -0.9999993 0.001210212 0 -0.9999994 0.001210272 0 -0.9999993 0.001210391 1.77949e-7 -0.9999994 0.001209795 0 -0.9999994 0.001210153 -3.32168e-7 -0.9999994 0.001214444 1.63235e-6 -0.9999993 0.001210331 0 -0.9999993 0.001210212 0 -0.9999993 0.001210272 -1.93772e-7 -0.9999994 0.001210331 0 -0.9999994 0.001210749 7.09611e-7 -0.9999994 0.001208722 0 -0.9999993 0.001210331 0 -0.9999994 0.001210331 0 -0.9999993 0.001210331 0 -0.9999993 0.001210212 0 -0.9999993 0.001210033 0 -0.9999994 0.4341219 -0.701346 -0.5653778 0.781894 -0.4854884 -0.3910792 0.9749346 -0.1734184 -0.1393864 4.91939e-4 -0.7782333 -0.6279752 0.006720244 -0.7810226 -0.6244667 0.006690025 -0.6991212 -0.7149719 0.2801211 -0.6996404 -0.6572942 0.4381282 -0.7018522 -0.5616468 0.4365849 -0.6318502 -0.6404366 0.4592843 -0.621514 -0.6346483 0.459976 -0.5057227 -0.7298402 0.4798308 -0.4966988 -0.7232239 0.4792124 -0.3695334 -0.7961159 0.5062231 -0.3597232 -0.7837969 0.506969 -0.2269756 -0.8315435 0.5279056 -0.2199703 -0.8203223 0.04232752 -0.6558028 -0.7537447 0.04224383 -0.5693593 -0.8210028 0.07366687 -0.564212 -0.8223369 0.07354331 -0.4201898 -0.9044512 0.1167301 -0.4138786 -0.9028171 0.1169561 -0.2618322 -0.9580007 0.1508891 -0.2556207 -0.9549297 0.1506137 -0.09725362 -0.9837974 0.1953028 -0.09163677 -0.9764525 0.4413903 -0.08676397 -0.8931107 0.5273625 -0.0872994 -0.8451435 0.6076061 -0.0749588 -0.7906934 0.7922553 -0.05946785 -0.6072851 0.78356 -0.4850886 -0.3882303 0.7822345 -0.43753 -0.4434827 0.7916563 -0.4276328 -0.4363605 0.7922315 -0.347557 -0.5015709 0.8004022 -0.339568 -0.494014 0.7999303 -0.2526806 -0.5443016 0.8109917 -0.2442409 -0.531638 0.8115514 -0.1538873 -0.5636516 0.8200428 -0.1484522 -0.5527133 0.8197148 -0.0600236 -0.5696182 0.8962332 -0.0421496 -0.4415764 0.9751293 -0.173164 -0.1383374 0.9749249 -0.1564497 -0.1582555 0.976039 -0.1524772 -0.1552379 0.9761373 -0.1238883 -0.1783469 0.9770984 -0.1207587 -0.1752036 0.9770348 -0.08996444 -0.1931564 0.978334 -0.08668392 -0.1880123 0.9784276 -0.05467092 -0.199225 0.9794206 -0.05262809 -0.1948482 0.9793569 -0.02011966 -0.2011352 0.980643 -0.01871246 -0.1949083 0.9843294 -0.127288 -0.1220392 0.9683924 -0.104115 -0.2266634 0.8033455 -0.4563515 -0.3825958 0.7791124 -0.4393479 -0.4471661 0.4519486 -0.6948958 -0.5593411 0.4337458 -0.6841834 -0.5863086 0.003353416 -0.7917054 -0.6108938 4.91264e-4 -0.7896915 -0.6135041 5.01294e-4 -0.7815417 -0.6238529 7.14684e-4 -0.7811825 -0.6243023 0.4465919 -0.6226544 -0.6425397 0.4403713 -0.6463407 -0.6231508 0.789951 -0.3196756 -0.5232448 0.7887812 -0.3822203 -0.4813853 0.9531285 0.06236314 -0.2960693 0.9717479 -0.04180508 -0.2322899 -0.007087767 -0.7712619 -0.6364786 -0.006133735 -0.7680961 -0.6403053 0.4291542 -0.5654276 -0.7043568 0.4283647 -0.5854389 -0.6883059 0.7600098 -0.2215901 -0.610969 0.7702654 -0.2787305 -0.5735857 0.9062866 0.1818134 -0.3815606 0.9412794 0.08711576 -0.3261962 -0.01514458 -0.7625685 -0.6467301 -0.01692718 -0.7583038 -0.6516817 0.4036352 -0.5267112 -0.7481003 0.4098374 -0.5396794 -0.7353771 0.7216087 -0.1596533 -0.6736407 0.7440319 -0.1993125 -0.6377235 0.8600923 0.2521128 -0.4434868 0.9035801 0.185724 -0.3860697 -4.20539e-5 -0.7751168 0.6318181 -2.24531e-4 -0.7751078 0.6318292 -0.4282232 -0.5569904 -0.7116085 -0.03077328 -0.8017734 0.5968354 -0.3770024 -0.5831134 -0.7196165 -0.9791863 -0.01792776 -0.2021701 -0.9616243 -0.01311784 -0.274056 -0.8605845 -0.2373417 -0.4506254 -0.7717356 -0.2823032 -0.5698501 -0.7194485 -0.372831 -0.5859957 -0.4430047 -0.5585488 -0.7012633 0.5337288 0.4429648 -0.7203582 0.3850649 0.5088913 -0.7699058 0.08905702 0.5632332 -0.8214848 -0.5405279 0.493533 -0.6813625 -0.6973063 0.4047877 -0.5915326 -0.436182 -0.5438547 -0.7169152 -0.3416821 -0.4967681 -0.7977938 -0.722373 -0.3800363 -0.5777109 -0.6590445 -0.3648437 -0.657685 -0.8270334 -0.1551659 -0.5403143 -0.872045 -0.1509624 -0.4655619 -0.8976019 0.1754215 -0.4043989 -0.8731491 0.3200733 -0.367646 -0.9281194 0.1791 -0.3263705 -0.9406476 0.1562073 -0.3012996 -0.8139759 0.3281494 -0.4793343 -0.8778383 0.2906011 -0.3807242 -0.8178847 -0.03637039 -0.5742316 -0.8127889 -0.04502362 -0.5808159 -0.6415635 -0.3442975 -0.68546 -0.6454524 -0.3405928 -0.6836576 -0.3751814 -0.6055813 -0.7017908 -0.3957052 -0.5941279 -0.7003067 -0.7823398 0.364386 -0.5051409 -0.7760435 0.3530086 -0.5226293 -0.7503511 0.02076828 -0.6607131 -0.7454062 0.01525205 -0.666436 -0.6109671 -0.3265075 -0.721188 -0.6132004 -0.3248471 -0.7200415 -0.3838276 -0.6271416 -0.6777682 -0.397474 -0.6209169 -0.6756306 -0.5898482 0.4864226 -0.6445714 -0.6193646 0.557327 -0.5529686 -0.6675807 0.08927869 -0.7391653 -0.6598878 0.06320893 -0.7487007 -0.5675736 -0.3138855 -0.7611413 -0.5715238 -0.3073114 -0.7608681 -0.3677266 -0.6644129 -0.6506403 -0.399428 -0.6346908 -0.6615322 -0.5181767 0.5140852 -0.6835272 -0.5109691 0.5115132 -0.6908436 -0.5714825 0.1104016 -0.8131539 -0.5650936 0.1032385 -0.818542 -0.5156847 -0.3092994 -0.7990013 -0.5174404 -0.3077992 -0.7984455 -0.3676433 -0.6736819 -0.6410859 -0.3810883 -0.6661351 -0.6411207 -0.2658267 0.6804814 -0.6828479 -0.4576551 0.5145112 -0.7251414 -0.5091845 0.5113644 -0.6922699 -0.3317173 -0.7056853 -0.6260766 -0.3237811 -0.7100264 -0.6253226 -0.3636523 -0.3186135 -0.8753527 -0.3640853 -0.3182851 -0.8752923 -0.3181387 0.136231 -0.9382052 -0.3258796 0.1426614 -0.9345856 -0.3639544 -0.6734325 -0.6434485 -0.3426199 -0.7042177 -0.6218433 -0.4452836 -0.3040601 -0.8421817 -0.4442495 -0.3071413 -0.8416097 -0.4460808 0.117802 -0.8872061 -0.4499669 0.1524863 -0.8799306 -0.3455826 0.5758929 -0.7408914 -0.2042877 0.5618667 -0.8016062 -0.05826145 0.5962473 -0.800684 -0.1806765 0.5671964 -0.8035199 -0.2180771 0.5726079 -0.7902928 0.05214476 0.5731409 -0.8177961 -0.01802408 0.6377418 -0.7700394 -0.1824112 0.1579178 -0.9704578 -0.1817821 0.1201854 -0.9759666 -0.2691344 -0.3211452 -0.9079827 -0.2677624 -0.331458 -0.9046761 -0.2913413 -0.7259343 -0.6230086 -0.2957926 -0.713968 -0.6346309 0.2473876 0.5590905 -0.7913389 0.2479122 0.5512644 -0.7966476 0.09720993 0.1245371 -0.9874416 0.09474486 0.08049607 -0.9922418 -0.06664925 -0.3476417 -0.9352558 -0.06878703 -0.376451 -0.9238794 -0.216458 -0.7355273 -0.6419855 -0.2166323 -0.7464674 -0.6291717 0.4037442 0.5057583 -0.7623643 0.4109727 0.5005866 -0.7619151 0.2582454 0.06480312 -0.9639036 0.2679553 0.05504989 -0.9618573 0.05032867 -0.3944042 -0.9175578 0.05830752 -0.4026759 -0.9134836 -0.1717742 -0.7521243 -0.6362411 -0.1651425 -0.7579579 -0.6310529 0.6588238 0.400453 -0.6368584 0.5656151 0.4835259 -0.6680437 0.4162434 0.03416883 -0.908611 0.4111241 -0.004459619 -0.9115686 0.1758309 -0.4043443 -0.8975462 0.163322 -0.4420679 -0.8819875 -0.1129283 -0.7438273 -0.6587627 -0.1281627 -0.7707206 -0.6241507 0.7786548 0.3325915 -0.5320523 0.7808244 0.3088314 -0.5430805 0.641991 -0.0727691 -0.7632511 0.6318408 -0.108671 -0.7674424 0.3498667 -0.463396 -0.8141606 0.3240544 -0.5028778 -0.8013131 -0.03106188 -0.7438415 -0.667634 -0.06881535 -0.7734553 -0.6301043 -0.9807558 0 -0.1952387 -0.9807558 0 -0.1952389 -0.8312178 0 -0.5559471 -0.8312172 0 -0.5559478 -0.5549428 0 -0.8318886 -0.5549423 0 -0.8318889 -0.1940504 0 -0.9809916 -0.1940505 0 -0.9809916 -0.9230448 -0.2429898 -0.2982354 -0.9857201 -0.1063061 -0.130595 -0.7041147 -0.4489697 -0.5501351 -0.8450812 -0.3367608 -0.415247 -0.5744786 -0.516102 -0.6353055 -0.3767789 -0.5862415 -0.717188 -0.9857057 -0.1058103 -0.1311052 -0.9856212 -0.09585082 -0.1391528 -0.9846554 -0.09838259 -0.1441341 -0.9846033 -0.07285529 -0.1588978 -0.9832794 -0.07514649 -0.1658758 -0.9833206 -0.04707801 -0.1756825 -0.9821906 -0.04776984 -0.1817135 -0.9821197 -0.017668 -0.1874272 -0.9806061 -0.01746964 -0.1952087 -0.7767621 0.08290779 -0.6243131 -0.8731984 -0.2770645 -0.4009488 -0.8647944 -0.2836813 -0.4143134 -0.8644723 -0.2102333 -0.4566067 -0.853008 -0.2161107 -0.4750511 -0.8533647 -0.1357716 -0.5033238 -0.843601 -0.1373543 -0.5191062 -0.8431672 -0.05134236 -0.5351945 -0.8301537 -0.05058759 -0.5552349 -0.5916441 -0.07160782 -0.8030129 -0.6616341 -0.4264873 -0.6167244 -0.6401577 -0.434147 -0.6338095 -0.6396192 -0.3217375 -0.6981205 -0.6105363 -0.3281031 -0.7208285 -0.6111416 -0.2064588 -0.764121 -0.5865144 -0.2073106 -0.782958 -0.5858501 -0.0777148 -0.8066847 -0.5533508 -0.0757156 -0.8295 -0.3764929 -0.5827506 -0.720177 -0.3754919 -0.5273772 -0.7621543 -0.3385151 -0.5316736 -0.7763575 -0.3380911 -0.3941593 -0.8545951 -0.2886165 -0.3965446 -0.8714659 -0.2890405 -0.2500491 -0.9240839 -0.2475991 -0.2478001 -0.9366375 -0.2472015 -0.09327816 -0.9644639 -0.1932813 -0.0889737 -0.9771009 -0.7257359 0.2411774 0.6443144 -0.6117031 0.4727227 0.6343128 -0.5903543 0.5504242 0.5903518 -0.0925526 0.9713281 0.2189882 -0.05492132 0.9797995 0.1922933 -0.283393 0.750628 0.5968635 -0.1704278 0.826397 0.5366773 -0.4170377 0.3638474 0.8328834 -0.2459377 0.5473412 0.7999577 -0.4300764 0.09008091 0.8982872 -0.3886923 0.1942317 0.9006621 -0.3774119 -0.146246 0.9144247 -0.04044121 0.9759127 0.2143807 -0.05665481 0.9715959 0.2297646 -0.100791 0.7914767 0.6028315 -0.1419411 0.7536004 0.6418249 -0.1441538 0.4589712 0.8766786 -0.1974108 0.3677085 0.9087462 -0.1591551 0.04165691 0.9863744 -0.1394818 0.09004962 0.9861217 -0.2558842 -0.3773733 0.8900072 -0.06643134 -0.1433804 0.9874356 0.02285212 0.9691018 0.2456007 0.04007112 0.9747777 0.2195512 0.0458374 0.7344291 0.6771358 0.0957967 0.7854481 0.611469 0.05743122 0.334007 0.9408194 0.1412113 0.4513052 0.881126 0.04556214 -0.1343496 0.989886 0.1754456 0.04060226 0.9836516 0.004668593 -0.5706565 0.8211756 0.2050328 -0.3710061 0.9057131 0.2774807 -0.5998979 0.7504179 0.2730031 -0.610463 0.7435081 0.3424317 -0.1508496 0.9273538 0.3405625 -0.1609705 0.92634 0.3263434 0.3340352 0.8842627 0.3262513 0.3270877 0.88689 0.2329649 0.7396885 0.6313385 0.2335278 0.7367267 0.6345854 0.08438289 0.9698746 0.2285232 0.08468842 0.9695176 0.2299212 0.2523857 -0.5871006 0.7691648 0.2473764 -0.5999222 0.7608536 0.3082631 -0.1385948 0.9411512 0.3061097 -0.1508409 0.9399701 0.2922714 0.34236 0.8929542 0.2920677 0.3340387 0.8961666 0.2080789 0.7432415 0.6358422 0.2086195 0.7396946 0.6397889 0.07529371 0.970304 0.2298717 0.07560068 0.9698761 0.2315706 0.1408531 0.9696401 0.1998959 0.1392853 0.9704809 0.1968924 0.2969828 0.8728724 0.3871628 0.4088371 0.7436828 0.52895 0.4209601 0.7301414 0.5382251 0.5545377 0.4808709 0.6791548 0.5889183 0.3461258 0.7303233 0.6139302 0.2580224 0.7459989 0.7610124 -0.02158206 0.6483783 0.7365101 -0.02167814 0.6760792 0.637947 -0.1266633 0.7595921 0.6341357 -0.06513416 0.7704735 0.8020598 -0.1684423 0.5729984 0.7943301 0.03224724 0.6066301 0.8806409 0.03225982 0.472685 0.8158962 -0.4419022 0.372875 0.9240348 -0.02289235 0.3816223 0.9177755 0.2831864 0.2783769 0.9497891 0.1090121 0.2932866 0.9915804 0.1291236 0.009764254 0.9953086 0.09483021 0.01918411 0.9782272 -0.190169 0.08311092 0.9011437 -0.422942 0.09518468 0.3412836 -0.6095215 0.7155482 0.1058313 0.9705001 0.216632 0.1063404 0.9693605 0.2214319 0.294018 0.7452964 0.5984034 0.2944195 0.735741 0.60992 0.4139413 0.3484608 0.8409684 0.4107637 0.3262522 0.8513711 0.438979 -0.1279901 0.8893346 0.4278692 -0.1605407 0.8894688 0.3639566 -0.5753503 0.7324669 0.521229 -0.5717088 0.6336162 0.5771094 -0.4507505 0.6810058 0.7084466 -0.4530434 0.541161 0.7551727 -0.3421851 0.5591276 0.846083 -0.3411049 0.4096231 0.8944331 -0.1444416 0.4232331 0.9471647 -0.1451668 0.2860172 0.9592754 -0.05310887 0.2774352 0.9833211 -0.05310398 0.1739532 0.9606624 0.2134719 0.1776444 0.9916374 0.1290563 0 0.9916201 0.1291886 0 0.9916158 0.129123 -0.005035042 0.9916441 0.1289857 -0.002194166 -0.7811626 0.152197 0.6054926 -0.1493505 0.9761382 0.1576353 -0.287315 0.9291622 0.2326106 -0.3194401 0.8943309 0.3132579 -0.5263002 0.6586498 0.5377627 -0.525806 0.671689 0.5218831 -0.6849684 0.2373617 0.6888235 -0.6857886 0.243711 0.6857835 -0.9227431 0.09220969 -0.3742228 -0.9088788 0.1078421 -0.4028767 -0.9719884 0.1770926 -0.1545214 -0.6965138 0.08395296 -0.7126153 -0.6940274 0.09145092 -0.7141168 -0.7427758 0.05362176 -0.6673896 -0.9381121 0.3343724 -0.09022659 -0.9855688 0.1610929 -0.0519942 -0.9934291 0.1122951 0.02210593 -0.9178763 0.3911837 -0.06692332 -0.8750036 0.2236455 -0.4293618 -0.8728488 0.2556025 -0.415695 -0.7041497 0.08163613 -0.705343 -0.6830776 0.1202939 -0.720371 -0.6906072 0.1192842 -0.7133253 -0.7933703 0.2839018 -0.5384825 -0.7972165 0.385718 -0.4644002 -0.846405 0.3796615 -0.3734381 -0.839495 0.529859 -0.1204065 -0.8149616 0.5532544 -0.172474 -0.8245975 0.5643106 0.03990793 -0.9576602 0.1436869 0.2494817 -0.9208472 0.2524285 0.2971878 -0.9173411 0.2749375 0.2879145 -0.8515759 0.4639258 0.2441138 -0.8560813 0.4142421 0.3090771 -0.7365607 0.6380293 0.224493 -0.7519698 0.5917161 0.2905402 -0.5491279 -0.7905741 -0.2710192 -0.2031994 -0.9378436 0.2813531 -0.2888323 -0.947088 0.1400014 -0.6253093 -0.1845456 -0.7582421 -0.6363282 -0.1471968 -0.7572448 -0.644024 -0.3125429 -0.6982479 -0.6466078 -0.3789515 -0.662038 -0.6481572 -0.5260079 -0.5506433 -0.6606189 -0.4941552 -0.5651491 -0.6016115 -0.6624296 -0.446375 -0.6329017 -0.1690649 -0.7555478 -0.6312072 -0.1812853 -0.7541307 -0.6857319 -0.4802407 -0.5469375 -0.6732021 -0.5122665 -0.5332748 -0.7248705 -0.6599147 -0.1976751 -0.6402328 -0.7227502 -0.2602579 -0.6067621 -0.7616043 -0.2275937 -0.5478607 -0.7925416 -0.2678181 -0.4605796 -0.875059 -0.1487894 -0.6447073 -0.1292442 -0.7534244 -0.6527929 -0.1554834 -0.7414084 -0.7203953 -0.314301 -0.6182602 -0.7424948 -0.439889 -0.5051724 -0.7408969 -0.4349628 -0.5117413 -0.7537445 -0.5747678 -0.3186084 -0.8151125 -0.5072384 -0.2798234 -0.814287 -0.4648408 -0.3476492 -0.7936272 -0.37557 -0.4786473 -0.6947988 -0.1680669 -0.6992911 -0.6602376 -0.1105567 -0.7428752 -0.7538801 -0.2753314 -0.596538 -0.6994017 -0.1575592 -0.6971459 -0.7004539 -0.1611191 -0.6952733 -0.8304021 -0.4370415 -0.3455824 -0.8292356 -0.4460061 -0.3368188 -0.7095566 -0.138679 -0.6908673 -0.7105385 -0.1411405 -0.6893581 -0.8613548 -0.3855055 -0.3308377 -0.861082 -0.3917815 -0.3241066 -0.88721 -0.2278177 -0.4011953 -0.5791981 -0.002739429 -0.8151823 -0.7289295 -0.09580922 -0.6778514 -0.7974471 -0.2080286 -0.5663941 -0.6990303 -0.07647776 -0.7109908 -0.9162949 -0.2686833 -0.2970066 -0.9187602 -0.3571555 -0.168285 -0.915432 -0.3045057 -0.2631741 -0.7195167 -0.1176826 -0.6844316 -0.7203803 -0.1191422 -0.6832697 -0.8908299 -0.3276929 -0.3147056 -0.8911518 -0.3314498 -0.3098218 -0.8197554 -0.4636274 0.3362305 -0.8207156 -0.5593705 -0.1163218 -0.8191923 -0.5642898 -0.1024753 -0.7617578 -0.2676438 -0.5899931 -0.8077583 -0.3692603 -0.459536 -0.8116024 -0.3781949 -0.4452756 -0.8272969 -0.4577181 -0.32569 -0.8288145 -0.5098696 -0.2304333 -0.6794898 -0.1343665 -0.7212761 -0.5852912 0.009710371 -0.8107651 -0.6728304 -0.1220836 -0.7296539 -0.700801 -0.6603445 0.2698576 -0.7071878 -0.6583205 0.2578753 -0.7495458 -0.6451542 0.1481795 -0.797578 -0.6031923 -0.005324363 -0.7746424 -0.5542412 0.3045423 -0.8891062 -0.4548709 0.05082142 -0.9023315 -0.428826 -0.04366141 -0.9023276 -0.4288348 -0.04365366 -0.8677854 -0.2871728 -0.4055616 -0.8677719 -0.2871837 -0.4055828 -0.7002353 -0.1010059 -0.7067308 -0.7001948 -0.1010046 -0.706771 -0.8729296 -0.3127599 0.3743998 -0.8729217 -0.3127603 0.3744179 -0.9640918 -0.2655689 -4.05581e-4 -0.9640966 -0.2655519 -4.15322e-4 -0.909132 -0.1778481 -0.3766286 -0.9091408 -0.1778422 -0.3766104 -0.7147501 -0.06255555 -0.6965768 -0.7147742 -0.06254637 -0.6965529 -0.9101659 -0.1058957 0.4004803 -0.910161 -0.105898 0.4004908 -0.9957121 -0.08991914 0.02172559 -0.9957123 -0.08991807 0.02172309 -0.9303139 -0.06021618 -0.3617876 -0.9303138 -0.06021851 -0.3617872 -0.7222065 -0.02118247 -0.6913531 -0.7222078 -0.0211811 -0.6913518 0.7491195 0 -0.6624349 0.7481163 5.00931e-5 -0.6635676 0.9623417 -5.29469e-5 -0.2718427 0.9619265 0 -0.2733084 -0.9881852 0 0.1532647 -0.9881852 0 0.1532645 -0.8953338 0 0.4453961 -0.8953346 0 0.4453943 0.9626483 1.90929e-4 0.270755 0.964986 0.006535708 0.2622202 0.9712209 -0.01407957 0.2377644 0.9628832 -0.001596271 0.2699136 0.9922881 -2.27884e-4 0.1239534 0.9893051 -0.008712708 0.1456007 0.9896972 -0.01126348 0.1427332 0.9886559 -0.006835103 0.1500427 0.9810622 0.01643806 0.1929943 0.9832299 2.36998e-4 0.1823704 0.9732517 -1.4451e-4 0.2297416 0.9738975 -0.002996265 0.2269688 0.9646255 0.003933489 0.2635948 0.9631645 -0.03019988 0.2672121 0.963094 -0.00589317 0.269101 0.9953119 5.14657e-4 0.096717 0.9947252 0.003454923 0.1025177 0.9991498 -0.01042282 0.0398876 0.9970954 0.02565783 0.07171064 0.9986937 0.00268054 0.05102777 0.9986379 0.01844918 0.04880601 0.9892053 0.1433407 0.03043991 0.9974799 0.00231111 0.07091301 0.9974152 0 0.07185471 0.0680741 -7.94357e-6 -0.9976803 0.06813925 -2.35288e-5 -0.9976758 0.08398091 -0.005248785 -0.9964535 0.06777578 7.34564e-5 -0.9977006 0.06803315 1.07255e-5 -0.9976831 -0.5779739 -0.6705296 0.4651198 -0.8143652 -0.1079487 0.570225 -0.6792909 -0.5650388 0.4682896 -0.6911005 -0.5368459 0.4839178 -0.7218628 -0.4726865 0.5054519 -0.7214043 -0.4211525 0.5497332 -0.7840955 -0.3187874 0.5325119 -0.8004664 -0.1410611 0.5825422 -0.8143237 -0.1081069 0.5702542 0.2469079 0.8967918 -0.3671524 0.4918789 0.258731 -0.8313323 0.1318596 0.9658992 -0.2228273 0.1088997 0.9807763 -0.161922 0.1367607 0.9659254 -0.2197375 0.1318504 0.9659029 -0.2228161 0.3601778 0.7069451 -0.6086877 0.3397594 0.7932842 -0.5052365 0.3844857 0.7070784 -0.5934737 0.3601285 0.7070097 -0.6086419 0.4919093 0.2586986 -0.8313244 0.5472893 0.1950007 -0.8139098 0.5314825 0.2587619 -0.8065785 0.5004931 0.442195 -0.7442919 0.4427466 0.6086596 -0.658414 0.1220666 0.9659267 -0.2282227 0.122076 0.9659219 -0.2282375 0.4555611 0.258837 -0.8517438 0.4659289 0.1951249 -0.8630391 0.4230202 0.4421889 -0.7909001 0.3335065 0.7070888 -0.6235375 0.3808512 0.6087823 -0.6959429 0.2871194 0.7933461 -0.5368095 0.4576527 0.2587512 -0.850648 0.4576408 0.2588419 -0.8506268 0.3350247 0.7070926 -0.6227188 0.33503 0.7070806 -0.6227295 0.1226318 0.9659219 -0.2279395 0.1226266 0.9659246 -0.2279307 0.3069278 0.1919416 -0.932177 0.3069646 0.1919582 -0.9321614 0.2814524 0.4362285 -0.8546867 0.2813924 0.4362872 -0.8546765 0.2496736 0.6023042 -0.7582168 0.2496663 0.6022371 -0.7582725 0.1924378 0.7883201 -0.5843965 0.1924421 0.7883338 -0.5843765 0.1401906 0.8939017 -0.4257774 0.1412115 0.9741321 -0.1764261 0.08224433 0.9648118 -0.2497485 -0.1841147 -0.4666041 0.865091 -0.9283641 -0.3654729 0.06759983 -0.9506037 -0.2749956 0.1439794 -0.9668267 -0.08391106 0.2412574 -0.8968608 -0.2503641 0.3646347 -0.8282982 -0.3445783 0.4418008 -0.2796459 -0.09411805 0.955479 -0.02213287 -0.01937723 0.9995673 -0.001534163 -0.001814603 0.9999972 -0.3437711 -0.2957478 0.8912659 -0.788712 -0.3463937 0.5078827 -0.7507059 -0.332833 0.5706689 -0.7087299 -0.4269411 0.5616256 -0.7106731 -0.2280746 0.6655267 -0.2653302 -0.09942281 0.9590178 -0.1648446 -0.1989429 0.9660477 -0.1643633 -0.1991044 0.9660964 -0.1292201 -0.2239941 0.965986 -0.1288056 -0.2240287 0.9660333 -0.08961266 -0.2420335 0.9661208 -0.08930909 -0.2420335 0.966149 -0.04775464 -0.2539309 0.9660428 -0.04759979 -0.2538975 0.9660593 -0.7464483 -0.08232319 0.6603316 -0.5361236 -0.4602556 0.7076273 -0.5342196 -0.4616572 0.708154 -0.4505476 -0.5430053 0.708627 -0.4488475 -0.543954 0.7089782 -0.3529946 -0.6112015 0.7083979 -0.3515879 -0.6116346 0.7087236 -0.2449624 -0.66105 0.7092294 -0.2440115 -0.6612136 0.7094047 -0.1304784 -0.6931923 0.7088441 -0.1299449 -0.6931695 0.7089644 -0.9644692 -0.09610444 0.246096 -0.8280552 -0.4957588 0.2618167 -0.824879 -0.5004893 0.2628405 -0.7327675 -0.6278363 0.2624375 -0.729349 -0.6313505 0.2635272 -0.6165034 -0.7418248 0.2638553 -0.6132324 -0.7442734 0.2645812 -0.4828873 -0.8348827 0.2641795 -0.4800891 -0.8362759 0.2648721 -0.3354319 -0.903961 0.265217 -0.3333958 -0.9046016 0.2655998 -0.1785691 -0.9475125 0.2652043 -0.1774518 -0.9476517 0.2654567 0.6751796 0.7320997 -0.09034752 0.6371201 0.7629792 0.1092732 0.7973582 0.6035037 -0.001826882 0.9747962 0.2230594 0.004098594 0.9212818 0.3842784 0.05975025 0.9218449 0.3836132 0.05516445 0.757972 0.6521056 0.01539731 0.8284287 0.5599873 -0.01096904 0.5353327 0.8436565 -0.04077529 0.616213 0.7855058 -0.05711621 0.9672853 0.2367322 0.09119719 0.9657217 0.2378178 0.10404 0.9582307 0.2202496 0.1824391 0.9854295 0.134481 0.1041323 0.9907589 0.1258597 0.05055946 1 2.83605e-6 0 0.9823266 0 -0.1871757 0.9834703 0.02856123 -0.1788027 0.9955092 -0.01976948 -0.09257751 0.9979751 0.02140355 -0.05989849 0.9998548 0 -0.01704877 0.9612101 0.1463955 -0.2337599 0.9245796 0.1521521 -0.3492884 0.8935266 0.4416295 -0.08107799 0.8964992 0.440891 -0.04363912 0.6565799 0.6858128 -0.3139486 0.6999142 0.7015312 -0.1340677 -0.4700437 -0.8111642 0.3479537 -0.4921553 -0.8372578 0.2382912 -0.357668 -0.9117571 0.2019222 -0.3410887 -0.9224916 0.1807423 -0.1442795 -0.9807025 0.1319321 -0.1534318 -0.9844851 0.08513486 -0.00275135 -0.9999949 0.001656055 -0.9025515 -0.002635359 0.4305739 -0.8933853 -0.09337735 0.4394809 -0.9554537 -0.1628565 0.2461422 -0.8070461 -0.3088721 0.5032641 -0.8244347 -0.3652207 0.432344 -0.7800645 -0.5520941 0.2944341 -0.631306 -0.4675626 0.6187391 -0.7180066 -0.6750775 0.1695197 -0.685411 -0.6241099 0.3750981 -0.6160271 -0.7249268 0.3082074 0.8973253 -0.002635598 0.441362 0.7147243 -0.596903 0.3645216 0.6141844 -0.7185456 0.3262971 0.576333 -0.7752134 0.2586205 0.427119 -0.8392459 0.3365053 0.4034403 -0.8889096 0.2169692 0.3133538 -0.9322305 0.1809856 0.209474 -0.9761651 0.05676698 0.1458522 -0.9857791 0.08346742 0.002735018 -0.9999948 0.001704156 0.8758329 -0.1732255 0.4504551 0.6182909 -0.6400032 0.4561933 0.8083902 -0.4733818 0.3498784 0.7890868 -0.378102 0.4841292 0.8106453 -0.3575336 0.4637069 0.8896274 -0.2365875 0.3906273 0.9643658 -0.1040599 0.243249 0.9337264 -0.3347362 0.1269131 0.9652349 -0.1838787 0.1857696 0.8710607 -0.01553851 0.4909295 0.06570589 -0.2600741 0.9633506 0.0875777 -0.2578174 0.9622164 0.2428549 -0.2489671 0.9375697 0.2028985 -0.2613075 0.94369 0.4017587 -0.2194827 0.8890541 0.3236424 -0.2538303 0.9114964 0.5335077 -0.1819243 0.8259983 0.4525651 -0.2461663 0.8570805 0.6160263 -0.1611413 0.7710675 0.5297207 -0.2183933 0.8195734 0.6802029 -0.1269242 0.7219517 0.6237495 -0.2159655 0.751196 0.7713503 -0.08861088 0.6302117 0.7411184 -0.1812093 0.6464572 0.8425694 -0.05477941 0.5357949 0.8385629 -0.1436445 0.525527 0.8959609 -0.03376632 0.4428477 0.8941736 -0.1816978 0.4091938 0.9495126 -0.1924113 0.2477979 0.9004729 -0.2915089 0.3227555 0.8984493 -0.2979511 0.3225125 0.8265708 -0.3918046 0.4040668 0.822923 -0.3981385 0.4053193 0.7285872 -0.4834426 0.4852257 0.7216505 -0.4911952 0.4877989 0.6504372 -0.5387945 0.5353803 0.6397633 -0.5457118 0.5412039 0.5701839 -0.5828671 0.5789268 0.5536534 -0.593479 0.5841665 0.4328284 -0.6398163 0.635055 0.4035835 -0.6510547 0.6428438 0.2740076 -0.6807285 0.6793589 0.2272039 -0.691618 0.6855968 0.08716487 -0.7023152 0.7065095 0.02688252 -0.7051852 0.7085134 0.9457588 -0.3238033 0.02630507 0.9128804 -0.3998379 0.08233523 0.8449144 -0.5275056 0.08864229 0.8300845 -0.5475577 0.1055485 0.7347038 -0.6654035 0.1320925 0.7259057 -0.6735153 0.1394211 0.6011815 -0.7802323 0.1726805 0.6351351 -0.7573611 0.1516823 0.5109819 -0.832951 0.2123446 0.5575931 -0.8086317 0.1876291 0.4079973 -0.8862205 0.2194346 0.4087542 -0.8859433 0.2191452 0.2601441 -0.9334869 0.2468345 0.2372533 -0.9380099 0.2526827 0.1117143 -0.9594465 0.2588095 0.04203993 -0.9627451 0.2671226 -0.02833002 -0.9635649 0.2659704 -0.0647459 -0.961517 0.2670076 -0.09694212 -0.9589446 0.26651 -0.01800495 -0.7033192 0.7106462 -0.07945364 -0.6993026 0.7103964 0.02827352 -0.2581619 0.9656879 -0.02985966 -0.2556078 0.9663194 -0.8261799 -0.5481486 -0.1302304 -0.9504446 -0.30246 -0.07192271 -0.9583184 -0.2780625 -0.06562966 -0.955321 -0.2876242 -0.06807392 -0.9999997 -8.09061e-4 -2.07951e-4 -0.9897964 -0.1386061 -0.033041 -0.9986155 -0.04805552 -0.02140283 -0.9818593 -0.184529 -0.04360586 -0.9172458 -0.3793383 -0.121502 -0.9197931 -0.3719851 -0.1249307 -0.9190504 -0.378562 -0.1097142 -0.9524602 -0.2964487 -0.07027071 -0.9511361 -0.3004401 -0.07124674 -0.9149521 -0.392439 -0.09409713 -0.9389501 -0.3354646 -0.07639491 -0.8572139 -0.5001814 -0.1224866 -0.8366586 -0.5308455 -0.1349281 -0.9062021 -0.4136219 -0.08783394 -0.8675351 -0.4846378 -0.1118444 1 6.59145e-7 0 1 3.44892e-6 0 1 -3.97874e-6 0 1 -5.60008e-7 0 1 -1.37304e-6 0 1 -2.35363e-5 0 1 9.68185e-7 0 1 2.64598e-6 0 0.1208126 0 -0.9926754 0.09914058 -0.01100862 -0.9950126 0.3021661 0.008067727 -0.9532213 0.2912232 0.003660798 -0.9566482 0.4670154 -0.00420612 -0.8842393 0.4708908 -0.00218594 -0.8821889 0.6279208 0.001878559 -0.778275 0.6316533 0.003846704 -0.7752415 0.9963883 -0.006838679 -0.08463877 0.9982894 -0.001394033 -0.05845129 0.9885352 0.001114189 -0.1509865 0.9828749 -0.004587411 -0.184217 0.961027 0.00594449 -0.2763907 0.9542393 5.56603e-4 -0.2990437 0.9303611 -2.05759e-4 -0.3666445 0.9312387 -5.31407e-6 -0.3644099 0.8930603 6.93889e-6 -0.4499372 0.8999072 0.005398154 -0.436048 0.8333611 -0.004397332 -0.5527116 0.8446888 0.001682162 -0.5352551 0.7578103 -0.002345263 -0.6524708 0.7632663 0.00112605 -0.646083 0.6988612 -1.25193e-4 -0.7152574 0.9985744 -0.002544343 -0.05331647 0.9996118 -5.84802e-4 -0.0278564 0.9999657 0 -0.008283138 -0.7071043 0 0.7071093 -0.7071108 0 0.7071028 -0.7071088 1.63456e-6 0.7071048 -0.7071048 1.68067e-6 0.7071089 -0.7070128 -1.77076e-5 0.7072009 0.671346 0.4643161 0.5776722 0.6735176 0.4645608 0.5749413 0.6451791 0.4673839 0.6043974 0.6361353 0.4646812 0.6159572 0.6184936 0.4690539 0.6304397 0.6060445 0.4679335 0.6432327 0.5922034 0.4667683 0.6568276 0.5921964 0.4667632 0.6568376 0.576265 0.4637059 0.6729751 0.5762307 0.4637017 0.6730075 0.5600348 0.4600515 0.6889948 0.5620216 0.4614307 0.68645 0.5346412 0.4505678 0.7149459 0.5268146 0.4431955 0.7252891 0.5090544 0.4398021 0.7398904 0.4975091 0.4328836 0.751729 0.4847871 0.4253192 0.7642546 0.4847755 0.4253085 0.7642681 0.4704664 0.4149098 0.7787883 0.4704384 0.4149041 0.7788084 0.4560006 0.4039223 0.7930387 0.4575366 0.4062821 0.7909457 0.4342789 0.3829564 0.8153198 0.4286833 0.3717489 0.8234279 0.4126358 0.3609693 0.8363211 0.4034285 0.3489721 0.8458511 0.393122 0.3359203 0.855928 0.3931208 0.3359108 0.8559324 0.3820454 0.3193501 0.8672122 0.382044 0.3193415 0.8672159 0.3709704 0.3022552 0.878079 0.3718534 0.3053411 0.8766368 0.3553907 0.2721762 0.8942134 0.3528094 0.2583953 0.8993095 0.340095 0.2414478 0.9088665 0.3342293 0.2256854 0.9150722 0.3275509 0.2086589 0.9215053 0.3275522 0.2086519 0.9215064 0.3209874 0.1877885 0.9282794 0.3209734 0.1877581 0.9282904 0.3145267 0.1665232 0.9345283 0.3146194 0.1699755 0.9338753 0.3068813 0.1307147 0.9427289 0.307738 0.1159164 0.9443839 0.2996187 0.09471064 0.9493464 0.2977342 0.07703953 0.9515352 0.2954602 0.0578739 0.9536005 0.2954599 0.05787318 0.9536007 0.2941514 0.03504842 0.955116 0.2941507 0.03506374 0.9551157 0.2932046 0.01542633 0.9559254 0.2932025 0.01542884 0.955926 -0.5900777 -0.05761843 0.8052879 -0.4113714 -0.1395666 0.9007192 -0.3258124 -0.1620935 0.9314355 0.1158561 -0.2852939 0.951412 -0.1460179 -0.234058 0.9611949 -0.2069901 -0.2037671 0.9568877 -0.2787489 -0.1781332 0.9436989 -0.5250245 -0.1226411 0.8422045 -0.5106082 -0.06418484 0.8574146 -0.5137529 -0.06271499 0.8556429 -0.03399133 -0.08561027 0.9957487 -0.04452663 -0.1727142 0.9839651 -0.0335626 -0.176425 0.9837418 -0.05912834 -0.2780752 0.9587378 -0.0631057 -0.2751851 0.9593179 0.03138798 -0.02984392 0.9990617 -0.2170717 0.03353166 0.9755796 0.07760667 -0.06482899 0.9948741 -0.3923327 -0.03164649 0.9192789 -0.5075246 -0.0122953 0.8615496 -0.6096752 -0.01116245 0.7925727 0.7132276 0.3825501 0.5873346 0.727326 0.3632513 0.5822762 0.7317162 0.3703528 0.5722153 0.6745454 0.5178453 0.5261415 0.7093209 0.3688363 0.6006861 0.7142026 0.3694459 0.5944951 0.7311109 0.3861661 0.5624523 0.7061796 0.3870024 0.5929078 0.73277 0.4008404 0.5498865 0.6953144 0.4065265 0.5926838 0.7427853 0.4013324 0.5359126 0.6976939 0.4093276 0.5879406 0.7351053 0.4243591 0.528715 0.6899424 0.4366881 0.5773067 0.8035258 0.4185654 0.4232605 0.6747036 0.5068184 0.5365727 0.6867032 0.5043572 0.5235098 0.677044 0.4749458 0.5621725 0.7303069 0.4652133 0.5002285 0.6614423 0.4712516 0.5834519 0.7085967 0.4646725 0.5310087 0.6898154 0.438205 0.5763083 0.7098875 0.4375715 0.5518976 0.69982 0.4130783 0.5827679 0.7108935 0.4143795 0.5682606 0.7068601 0.3914404 0.5891717 0.7159211 0.3941916 0.5762553 0.7064335 0.3784075 0.5981299 0.7214848 0.3859422 0.5748985 0.7071864 0.4954022 0.5044445 0.7334248 0.3658646 0.5729147 0.7711356 0.350875 0.5312597 0.7651506 0.4191248 0.4887526 0.7869727 0.4129071 0.458456 0.7911772 0.4117246 0.4522405 0.7313135 0.3815193 0.5653527 0.7241944 0.4115915 0.5532947 0.7602148 0.3549051 0.5441654 0.7876418 0.412231 0.4579148 0.8039952 0.3827387 0.4550854 0.7209854 0.4062994 0.5613384 0.7219876 0.4280402 0.5436136 0.7077305 0.4738284 0.5240269 0.6996676 0.4712988 0.5369756 0.7049469 0.4843152 0.5181589 0.9775246 -0.08121627 0.1945499 0.6765339 -0.6720323 -0.3011222 0.8142194 -0.5647336 -0.1346209 0.8517948 0.2442373 0.4634587 0.9603025 0.1343066 0.2445017 0.8398012 0.3364573 0.426064 0.8718311 0.3245289 0.3668676 0.8810942 0.2940422 0.3704218 0.9080615 0.2229012 0.3545975 0.865603 0.1674507 0.4719023 0.9589492 -0.2166795 0.1829383 0.948816 -0.144114 0.281033 0.9544865 -0.1469854 0.2595204 0.938928 -0.03384917 0.3424448 0.5964038 -0.7113671 -0.3718324 0.8105976 -0.4188367 -0.4092767 0.7231433 -0.4665249 -0.5093313 0.9911153 -0.07608175 -0.1090967 0.9705317 -0.1445139 -0.1928322 0.7995162 0.1123276 0.590048 0.85018 0.2450426 0.4659914 0.9367936 0.08059996 0.3404724 0.9538685 0.1583387 0.255076 0.947857 0.1956205 0.2515944 0.9968286 0.07932901 0.006307661 0.9928854 0.009958088 0.1186571 0.9930604 -0.004542648 0.1175181 0.977525 -0.08121591 0.1945481 0.9367938 0.08059912 0.3404719 0.9115906 0.01214581 0.4109199 0.9110867 0.03001976 0.4111203 0.7550188 -0.6211141 -0.2101519 0.7679798 -0.61592 -0.1756406 0.7965089 -0.5584614 -0.2317208 0.7965077 -0.5584629 -0.2317212 0.8232844 -0.4835424 -0.2973042 0.8232851 -0.4835419 -0.2973029 0.845701 -0.3728632 -0.381789 0.8891344 -0.3445138 -0.3012479 0.8820976 -0.2864838 -0.3739397 0.913986 -0.2804626 -0.2932075 0.6308 -0.7024068 -0.3297215 0.6602865 -0.6432002 -0.3877052 0.6602863 -0.6432009 -0.3877044 0.6883367 -0.5674872 -0.4518305 0.6883351 -0.5674886 -0.4518313 0.7131924 -0.4638134 -0.5255796 0.6499972 -0.5029071 -0.5697263 0.8610306 -0.5056633 -0.05413895 0.8612143 -0.5082336 -0.002961218 0.8934403 -0.4443948 -0.06540399 0.8934395 -0.4443966 -0.06540352 0.9193112 -0.3705403 -0.1325395 0.919311 -0.3705406 -0.1325403 0.9370492 -0.2801151 -0.2085053 0.9370507 -0.2801117 -0.2085033 0.9406592 -0.1659462 -0.2960106 0.9559355 -0.174532 -0.2360637 0.921661 -0.385644 0.0426594 0.9075428 -0.3998132 0.128513 0.9391472 -0.3366587 0.06828927 0.9419167 -0.3165061 0.1123241 0.9715978 -0.2341546 0.03419673 0.9715979 -0.2341543 0.0341975 0.9880716 -0.147027 -0.04580175 0.9880715 -0.1470268 -0.04580211 0.9911153 -0.07608288 -0.1090962 0.9995443 0.03011304 0.002120137 0.9973256 0.03346955 -0.06497418 -0.5581162 0 0.8297628 -0.6866167 0 0.7270196 -0.5811945 -0.003500521 0.8137572 -0.5578337 -1.589e-5 0.8299529 -0.2837717 1.99494e-5 0.958892 -0.2842324 0 0.9587555 -0.5860643 0.1397681 0.7981188 -0.2982516 0.03369277 0.9538925 -0.6538357 0.2920917 0.6979838 -0.5419897 0.4241486 0.7254965 -0.4599388 0.07220464 0.8850101 -0.5044283 0.1294383 0.8536967 -0.4907813 0.1028126 0.8651956 -0.6428905 0.4371867 0.6289354 -0.5705819 0.0317682 0.8206261 0.001210272 0 -0.9999994 0.001210272 0 -0.9999994 0.001210272 0 -0.9999994 0.001210331 0 -0.9999993 0.001210331 0 -0.9999994 0.001210212 0 -0.9999993 0.001210451 0 -0.9999994 0.00121051 2.08122e-7 -0.9999994 0.001210272 0 -0.9999994 0.001210391 0 -0.9999993 0.001210272 0 -0.9999993 0.001210212 -2.56796e-7 -0.9999993 0.001210331 0 -0.9999994 0.001210391 1.33818e-7 -0.9999994 0.001210272 0 -0.9999993 0.001210391 0 -0.9999993 0.001210153 -1.90723e-7 -0.9999994 -0.3040112 -0.3241667 0.8958199 -0.3378167 -0.1940509 0.9209908 -0.313411 -0.1471421 0.9381486 -0.3146443 0.003005683 0.9492049 -0.2708289 -0.5016889 0.8215595 -0.291647 -0.5531817 0.7803412 -0.2451788 -0.6601178 0.7100225 -0.1995338 -0.774929 0.599726 -0.2092605 -0.8290308 0.5185731 -0.1196542 -0.9145056 0.3864746 -0.09576302 -0.9672259 0.2351672 -0.09009677 -0.9798396 0.1783168 -0.03838872 -0.9931095 0.1107243 0.004113078 -0.9806365 0.1957933 0.004112601 -0.9806364 0.1957942 0.01169908 -0.8304451 0.5569776 0.01169896 -0.830449 0.556972 0.01747936 -0.5540447 0.8323034 0.01748448 -0.5540462 0.8323023 0.02059853 -0.1943455 0.9807169 0.02058947 -0.194343 0.9807175 -0.03065586 -0.9806361 0.1934244 -0.0306555 -0.9806365 0.1934224 -0.08720672 -0.8304471 0.5502297 -0.08720797 -0.8304479 0.5502283 -0.1303209 -0.5540463 0.8222221 -0.130309 -0.5540423 0.8222268 -0.1535449 -0.1943438 0.9688419 -0.153541 -0.194347 0.9688419 0.8850092 -0.192456 0.4239332 0.8411259 0.487982 0.2331973 0.8067404 0.5481256 0.2207447 0.9955898 -0.008798599 0.09340101 0.9826013 -0.1837285 0.02717691 0.5609876 0.7078301 0.4292663 0.728881 0.4374146 0.5266887 0.8274419 -0.1974435 0.5256958 0.3606185 0.7602662 0.5403236 0.3988003 -0.3637023 0.8418307 0.6959569 0.07829886 0.713802 -0.3814495 -0.002927005 0.9243851 -0.1646209 -0.05386471 0.9848851 -0.1701359 0.1620565 0.9720039 -0.06064063 -0.05105501 0.9968532 0.9178816 -0.3304085 0.2198269 0.9329106 -0.2685592 0.2399038 0.6906479 -0.3264493 0.6453189 0.7011271 -0.2582094 0.6646418 0.3949607 -0.2482939 0.884509 0.3555291 -0.02630537 0.934295 0.171774 -0.1640629 0.971379 0.01514357 -0.135783 0.9906229 -0.1961427 -0.08822011 0.9765989 -0.2027938 -0.1500765 0.9676527 0.2518969 -0.278059 0.9269472 0.231209 -0.3647629 0.9019371 0.6446858 -0.3859356 0.6598743 0.6037598 -0.4991422 0.6215555 0.8861321 -0.3964049 0.240069 0.8400437 -0.50458 0.1993134 -0.2432194 -0.1179018 0.9627791 -0.2563905 -0.1958029 0.9465332 0.1748326 -0.3658065 0.9141222 0.1380874 -0.4754771 0.8688231 0.5599659 -0.5066689 0.6555342 0.4883697 -0.648506 0.5838966 0.8149549 -0.5232431 0.2491291 0.7347325 -0.6565227 0.1707226 -0.248607 -0.3911307 0.8861215 -0.09115481 0.05921578 0.9940746 0.1209785 -0.583566 0.8030037 0.2453001 -0.26731 0.9318655 0.4383865 -0.7164403 0.5427067 0.5588418 -0.5084801 0.6550908 0.6550621 -0.7377611 0.1631016 0.6785369 -0.7130176 0.1766171 -0.04413133 -0.3335602 0.9416954 0.1354615 0.04430514 0.9897916 0.2655198 -0.5323761 0.8037878 0.4237149 -0.2466896 0.8715561 0.5075264 -0.6815388 0.527183 0.6570885 -0.4723781 0.5874468 0.6520699 -0.7413043 0.158974 0.7215152 -0.6696001 0.1762143 -0.9484008 -0.07573616 0.3078963 -0.9256238 -0.3652623 -0.09901666 -0.9558003 -0.2887665 0.05531519 -0.9999997 -7.78614e-4 -2.06059e-4 -0.9992424 -0.03284144 0.02088481 -0.999139 -0.04138469 -0.002930223 -0.9869362 -0.1468691 0.06623119 -0.9871213 -0.1597992 0.007477819 -0.9637814 -0.2572795 0.07023262 -0.969186 -0.2420953 0.04548108 -0.9651477 -0.2559919 0.05438774 -0.9642864 -0.1875938 0.1869767 -0.9999991 2.5974e-4 0.001372218 -0.9995046 -0.02552688 0.01841485 -0.9981297 0.005173683 0.06091368 -0.9899173 -0.08027166 0.1167054 -0.9746454 -0.01995855 0.2228638 -0.9613325 -0.08159494 0.2630252 -0.943876 -0.1075547 0.3122984 -0.9369379 -0.1280603 0.3251891 -0.9011955 0.006352245 0.4333664 -0.906032 -0.2962141 0.3022636 -0.8767499 -0.4324483 0.2104715 -0.886222 -0.0220462 0.462736 -0.822007 -0.558308 0.1122359 -0.7928705 -0.6061802 0.06246685 -0.3379512 -0.2585729 0.904947 -0.4243464 -0.2461047 0.8714142 -0.4489384 -0.2538275 0.8567531 -0.5601819 -0.2263242 0.7968524 -0.5934494 -0.2472079 0.7659675 -0.6719527 -0.2158985 0.7084261 -0.7074729 -0.2188863 0.6719902 -0.7746554 -0.1827844 0.6053916 -0.8062266 -0.2126355 0.5520732 -0.856742 -0.176133 0.4847374 -0.8814014 -0.1775298 0.4377383 -0.8843035 -0.1750019 0.4328761 -0.8966588 -0.171491 0.4081591 -0.7332792 -0.6731026 -0.09609735 -0.7064307 -0.7015756 -0.0935266 -0.7027304 -0.7114493 0.00314325 -0.6988815 -0.7151702 0.009819507 -0.6977634 -0.7163274 -0.001169204 -0.6516733 -0.754584 0.07697433 -0.6724388 -0.7401347 0.005160868 -0.5782797 -0.80449 0.1356041 -0.5931479 -0.8040739 0.04050779 -0.4747325 -0.8664814 0.1543989 -0.5098329 -0.8547984 0.09690314 -0.3762495 -0.904595 0.2003601 -0.4048399 -0.9037016 0.1393852 -0.251984 -0.942223 0.2207262 -0.2799532 -0.9407118 0.1915401 -0.1278855 -0.959673 0.2503462 -0.1417912 -0.9617199 0.2345 -0.8531672 -0.4723513 0.2213369 -0.8251109 -0.4967246 0.2691783 -0.826166 -0.4965242 0.2662959 -0.7542562 -0.5467681 0.3635137 -0.755428 -0.5479121 0.3593341 -0.6600908 -0.5994483 0.4527053 -0.6618527 -0.5993657 0.4502354 -0.5477504 -0.6426988 0.5356377 -0.5496441 -0.6436805 0.5325101 -0.4032714 -0.6808034 0.6114564 -0.4054706 -0.681285 0.6094624 -0.2419249 -0.7016635 0.6701797 -0.3759041 -0.7646928 0.5233939 -0.2500964 -0.1947461 0.9484334 -0.3508692 -0.2535371 0.9014487 -0.2819727 -0.4396168 0.852777 -0.2626326 -0.6050252 0.751644 -0.04249078 -0.1928843 0.9803012 -0.04248827 -0.1928915 0.9802998 -0.03892576 -0.4380994 0.8980834 -0.006299495 -0.5529066 0.8332195 -0.03450059 -0.6042327 0.7960607 -0.0265581 -0.7898609 0.6127108 0.0130949 -0.8305036 0.5568595 -0.07125037 -0.9657116 0.2496486 -0.008547067 -0.9803392 0.1971349 0.01184833 -0.03452676 0.9993336 -0.03423076 -0.01250207 0.9993358 0.09535443 -0.287657 0.9529748 -0.2774993 -0.07827162 0.9575322 -0.08746749 -0.5202286 0.8495362 -0.4345316 -0.1414795 0.8894751 0.001752555 -0.00159794 0.9999972 0.003927886 -0.01344084 0.999902 -0.003089845 -0.01278972 0.9999135 0.04114973 -0.1084259 0.9932525 -0.03250432 -0.09735035 0.9947193 0.02536034 -0.244207 0.9693915 -0.05102115 -0.1846032 0.9814879 0.001168549 -3.48059e-5 0.9999994 0.003905117 -0.007173418 0.9999668 0.02111023 0.001401484 0.9997762 0.04590857 -0.05200874 0.9975909 0.1704443 0.006911158 0.9853432 0.1973491 -0.06149363 0.9784028 0.3124996 -0.1066196 0.9439155 -0.004674077 -0.001561045 0.999988 0.2751442 -0.04996305 0.9601039 0.2273688 0.01180905 0.9737371 0.05102092 -0.1530359 0.9869027 -0.1499831 -0.1192431 0.9814714 -0.2105264 -0.0399183 0.9767729 -0.337336 -0.3127364 0.8879191 -0.544268 -0.1702218 0.8214603 -0.5983645 -0.08605891 0.7965888 -0.6413206 -0.4593867 0.6145502 -0.2304259 -0.6388198 0.734039 -0.6069995 -0.03307729 0.7940136 0.03323411 -0.4226081 0.905703 -0.1970261 -0.08604747 0.9766149 0.3347972 -0.1777884 0.9253661 0.253377 -0.06406426 0.9652439 -0.8173494 -0.09267812 0.5686394 -0.8075394 -0.116835 0.5781261 -0.7898891 -0.3080719 0.5302519 -0.7415108 -0.377677 0.5545465 -0.7021608 -0.5556356 0.4452407 -0.6025663 -0.6418955 0.4742195 -0.5869665 -0.6887502 0.4255511 -0.4706021 -0.8412944 0.266003 -0.4040265 -0.8005391 0.4426056 -0.3363347 -0.9117969 0.2355961 -0.2822618 -0.9377323 0.2024511 -0.2146823 -0.9763381 0.02599358 -0.05898106 -0.9859735 0.1561331 -0.003513574 -0.9999938 4.67505e-4 -0.001879036 -0.9999966 0.001869916 -0.04971092 -0.9895339 0.1354688 -0.1105051 -0.987383 0.1134173 -0.1674232 -0.9487193 0.2681437 -0.1878179 -0.9402953 0.2838469 -0.2380861 -0.8736873 0.4242469 -0.3018721 -0.8558927 0.4199059 -0.3799507 -0.6769491 0.6303789 -0.4229583 -0.6501764 0.6311712 -0.4770813 -0.4106863 0.7770009 -0.4991322 -0.389622 0.7739908 -0.5249601 -0.1297072 0.8411855 -0.5297431 -0.1225084 0.839264 2.70392e-4 -0.9999967 0.002572357 -0.05467736 -0.9860159 0.1574264 0.01204538 -0.9874554 0.1574387 -0.05266338 -0.9400442 0.3369623 -0.03209769 -0.9475338 0.3180403 -0.1040704 -0.853458 0.5106651 -0.04003441 -0.867528 0.4957746 -0.1347374 -0.6502341 0.7476908 -0.09323734 -0.6714147 0.7351933 -0.1587513 -0.3908028 0.9066815 -0.1376671 -0.407679 0.9026881 -0.1656543 -0.123077 0.9784737 -0.1610443 -0.1290367 0.9784755 0.002382218 -0.9999936 0.002689123 -0.07474088 -0.9724158 0.220956 0.1483035 -0.9764934 0.1564182 0.05896985 -0.9105263 0.4092241 0.1270394 -0.9332339 0.3360588 0.01545244 -0.7869783 0.6167871 0.2314074 -0.8310443 0.5057826 0.1077111 -0.5511385 0.8274326 0.2480561 -0.623583 0.7413586 0.1726384 -0.307993 0.9355942 0.2434492 -0.3696599 0.8967074 0.2179578 -0.09330558 0.9714878 0.2329993 -0.1157292 0.9655662 -0.07133233 -0.1945912 0.9782872 -0.2890373 -0.5521643 0.7820308 9.81981e-4 -0.9999949 0.003068327 0.06177192 -0.9805992 0.1860359 0.06228333 -0.9810991 0.1832088 0.1278758 -0.9121789 0.3893296 0.190023 -0.8294162 0.5253191 0.1809148 -0.7982839 0.5744674 0.2767361 -0.5529116 0.7859427 0.2782817 -0.5573986 0.7822188 0.298956 -0.3105757 0.9023126 0.3424862 -0.1933609 0.9194101 0.3215444 -0.09376859 0.9422402 -0.3210991 -0.1074141 0.9409345 -0.3422383 -0.1933683 0.9195007 -0.3281302 -0.2379754 0.9141653 -0.2871389 -0.3798387 0.87936 -0.188231 -0.8295219 0.5257971 -0.2201573 -0.719754 0.6583958 -0.2584123 -0.5984159 0.7583677 -9.81996e-4 -0.9999948 0.003068387 -0.05280244 -0.9858598 0.1590354 -0.07419788 -0.980275 0.1831821 -0.1122539 -0.9325206 0.3432265 -0.1731562 -0.8414633 0.5118169 0.02164095 -0.9805558 0.1950438 0.02164 -0.9805555 0.1950454 0.06152325 -0.8298938 0.5545189 0.06152343 -0.8298956 0.5545164 0.09185957 -0.5532228 0.8279531 0.0918554 -0.5532224 0.827954 0.1081755 -0.193939 0.9750312 0.1081743 -0.1939432 0.9750305 -0.1787494 -0.1949502 0.9643875 -0.1090239 -0.1501286 0.9826369 -0.09185528 -0.5532237 0.827953 -0.09185969 -0.5532218 0.8279538 -0.06152361 -0.8298946 0.5545178 -0.06152307 -0.8298949 0.5545174 -0.02164006 -0.9805554 0.1950458 -0.02164095 -0.9805555 0.195045 0.003515183 -0.9999937 5.84655e-4 0.07110798 -0.9789611 0.191256 0.2694834 -0.9305323 0.2479688 0.2771565 -0.9488136 0.1514502 0.3684681 -0.8292829 0.420144 0.452956 -0.868734 0.2003299 0.5448994 -0.7148064 0.4383336 0.5349147 -0.7808204 0.3227782 0.6048282 -0.5883527 0.5366788 0.6475815 -0.6654815 0.3711773 0.7225326 -0.3731259 0.5819998 0.7539224 -0.447547 0.4809396 0.7913587 -0.235171 0.5643103 0.7908485 -0.2919428 0.5378923 0.80338 -0.1058602 0.5859814 0.8136006 -0.1328614 0.5660405 0.09534043 -0.9906394 0.09769356 0.1537597 -0.9538324 0.2579959 0.1584275 -0.9601556 0.2302219 0.2219355 -0.8857722 0.4076181 0.2602124 -0.8992583 0.3516021 0.3215861 -0.7947382 0.5147561 0.3206471 -0.8164566 0.4801916 0.3722485 -0.6870134 0.6240543 0.3950946 -0.7119696 0.5805168 0.4595746 -0.4674975 0.7551406 0.4768046 -0.490558 0.7293903 0.5076199 -0.3064417 0.8052425 0.5085279 -0.3235806 0.7979318 0.5225088 -0.1397745 0.8410992 0.527893 -0.1478462 0.8363436 -2.70546e-4 -0.9999967 0.002573788 0.04062277 -0.992227 0.1176242 -0.01052081 -0.9906007 0.1363807 0.03912204 -0.9607861 0.2745172 0.03315514 -0.9546235 0.2959641 0.07960021 -0.903239 0.4216908 0.03868681 -0.8896359 0.4550292 0.08126682 -0.816323 0.5718501 0.08099019 -0.7968189 0.5987656 0.1163172 -0.7139748 0.6904422 0.09262597 -0.6909036 0.7169886 0.1470701 -0.4908699 0.85873 0.1297246 -0.4703158 0.8729116 0.1514684 -0.3224594 0.9343861 0.1503449 -0.3079138 0.9394603 0.1660724 -0.1474 0.9750351 0.1607856 -0.1405351 0.9769329 -0.002381622 -0.9999936 0.002688467 0.04512262 -0.9896705 0.1360754 -0.1286213 -0.9822408 0.1366006 -0.07308018 -0.9524053 0.2959451 -0.09561532 -0.9325324 0.348197 -0.05460244 -0.8882578 0.4560887 -0.1951545 -0.8409344 0.5047219 -0.1628829 -0.7843543 0.5985463 -0.1640402 -0.7190292 0.6753428 -0.1460848 -0.679543 0.718944 -0.2238831 -0.5983334 0.7693331 -0.1832351 -0.4545226 0.8716846 -0.2382503 -0.3793209 0.8940651 -0.2268339 -0.2913965 0.9293195 -0.2294018 -0.2373076 0.9439597 -0.2164487 -0.1329852 0.9671944 -0.2332337 -0.1070445 0.966511 0.1859423 -0.9823223 0.02164298 0.0489732 -0.989502 0.1359691 0.001876413 -0.9999965 0.001869142 -0.1164187 -0.9493832 -0.2917506 -0.09880465 -0.2590437 -0.9607987 -0.1974818 -0.4076318 -0.8915365 -0.0308268 -0.09379744 -0.995114 0.05557769 -0.1715762 -0.983602 -0.01275563 -0.3197631 -0.9474118 0.003047108 -0.03033572 -0.9995352 0.001307785 -0.01252746 -0.9999207 0.001196742 -0.00181967 -0.9999977 0.01804101 -0.08454763 -0.9962561 0.01239711 -0.06989175 -0.9974775 0.00658375 -0.04947811 -0.9987536 -0.01507693 -0.6153154 -0.7881368 -0.01688826 -0.8414826 -0.5400202 -0.007058024 -0.9770944 -0.2126893 -0.006361365 -0.9737327 -0.2276056 -0.001480758 -0.9673401 -0.2534781 0.007038235 -0.9602165 -0.2791682 0.0146051 -0.9554085 -0.294926 0.1209197 -0.2607296 -0.9578093 -0.255338 -0.688034 -0.679273 -0.2396075 -0.6480804 -0.722897 -0.1515451 -0.650168 -0.7445238 -0.1572526 -0.6251024 -0.7645382 -0.1812777 -0.4917536 -0.8516553 0.6453829 -0.492188 -0.5841506 0.3179662 -0.5447545 -0.7759768 -0.2615621 -0.8564826 -0.4449977 -0.2706293 -0.8430533 -0.4647807 -0.2615351 -0.8605057 -0.4371838 -0.2602591 -0.8419056 -0.4727157 -0.2458693 -0.7815768 -0.5733115 -0.2805314 -0.8507945 -0.4443545 -0.280228 -0.8505309 -0.4450499 -0.231915 -0.7596564 -0.607567 -0.2989127 -0.8114041 -0.5022694 -0.1898733 -0.8429759 -0.5033286 -0.2442026 -0.8418754 -0.48126 -0.3759429 -0.6699417 -0.6401914 -0.31537 -0.7389446 -0.5954013 -0.2924521 -0.7660275 -0.5724278 -0.2768091 -0.7855095 -0.5534905 -0.2660582 -0.8001092 -0.5376229 -0.2342237 -0.8458157 -0.4793068 -0.3742651 -0.8081897 -0.4547032 -0.2869798 -0.8349927 -0.4694996 -0.3410409 -0.3903677 -0.8551632 -0.1914901 -0.5566018 -0.8084096 -0.1767125 -0.6438789 -0.7444412 -0.05805933 -0.9378644 -0.3421105 -0.03249335 -0.939158 -0.3419451 -0.04285073 -0.929698 -0.3658218 -0.01009905 -0.9306086 -0.3658766 -0.01790738 -0.9290441 -0.3695357 0.05306434 -0.9280301 -0.3687063 0.02362114 -0.9201005 -0.3909695 -0.08099311 -0.9403867 -0.3303225 -0.09274154 -0.9457603 -0.3113464 -0.1335389 -0.9408632 -0.3113579 0.05345189 -0.1698989 -0.9840109 -0.001545429 -0.1694858 -0.9855315 -4.55935e-4 -0.1700596 -0.9854338 -0.005889058 -0.1699481 -0.9854355 -0.004452586 -0.173642 -0.9847988 -0.01442641 -0.1729945 -0.9848172 -0.01260071 -0.1778219 -0.9839821 -0.0224933 -0.1766649 -0.984014 -0.02031666 -0.1799107 -0.9834732 -0.03084081 -0.1783192 -0.9834893 -0.02905201 -0.1832742 -0.9826325 -0.04187023 -0.1806011 -0.9826648 -0.04049116 -0.1850372 -0.981897 -0.04798966 -0.1830352 -0.9819344 -0.3364856 -0.0850259 -0.9378423 -0.0747894 -0.5389003 -0.8390431 -0.1199458 -0.5279188 -0.8407824 -0.1244826 -0.5163745 -0.8472672 -0.08772444 -0.5240192 -0.8471768 -0.09338551 -0.5111111 -0.8544265 -0.06283318 -0.5157571 -0.8544277 -0.06952697 -0.5072242 -0.8590051 -0.04054027 -0.5105705 -0.8588798 -0.04609626 -0.497928 -0.8659924 -0.01660037 -0.4998457 -0.8659554 -0.02091413 -0.4901216 -0.8714031 -0.004646658 -0.4904828 -0.8714386 -0.007938146 -0.4889608 -0.8722697 0.05313575 -0.4888784 -0.8707322 0.03166592 -0.4741642 -0.8798668 -0.2207835 -0.7847495 -0.5791572 -0.1814937 -0.7949544 -0.5788849 -0.190256 -0.7807789 -0.5951362 -0.1336128 -0.7925317 -0.5950137 -0.143993 -0.7766475 -0.6132575 -0.09641957 -0.7839551 -0.6132845 -0.1080835 -0.7732276 -0.6248497 -0.06280583 -0.7783682 -0.6246588 -0.07242596 -0.7626789 -0.6427096 -0.02638936 -0.7656894 -0.642669 -0.03367221 -0.7535223 -0.6565595 -0.008030414 -0.7541672 -0.6566335 -0.01356822 -0.7522351 -0.6587551 0.05295872 -0.7516361 -0.6574487 0.02743542 -0.7387595 -0.6734106 -0.1458114 -0.9452731 -0.2918866 -0.179031 -0.9477405 -0.2640753 -0.1749991 -0.9492989 -0.2611647 -0.230398 -0.9374012 -0.2611435 -0.2160686 -0.9479303 -0.2339714 -0.2683158 -0.9344401 -0.2341551 -0.2552629 -0.9404792 -0.2243656 -0.301868 -0.9265715 -0.224368 -0.2938343 -0.9329565 -0.207975 -0.3403827 -0.916976 -0.208074 -0.3382038 -0.9188575 -0.2032712 -0.3467471 -0.9156612 -0.2033002 -0.3513354 -0.9113398 -0.2145305 -0.3071703 -0.9271883 -0.2144023 -0.3193175 -0.9177923 -0.2359954 -0.2679603 -0.934054 -0.2360945 -0.2387238 -0.9350976 -0.2619228 -0.2306097 -0.9379636 -0.2589278 -0.1655808 -0.9516631 -0.2586897 -0.185436 -0.9432138 -0.2756109 0.03211855 -0.214388 -0.9762204 -0.06589382 -0.1813096 -0.981216 -0.06578111 -0.182074 -0.981082 -0.06803238 -0.181206 -0.9810892 -0.06822979 -0.1794319 -0.9814016 -0.06060665 -0.182228 -0.9813867 -0.06160259 -0.1787117 -0.9819712 -0.04719841 -0.1830762 -0.9819651 -0.04921293 -0.1792729 -0.9825678 -0.03256016 -0.1829426 -0.9825842 -0.03538906 -0.1800482 -0.983021 -0.01656448 -0.1827962 -0.9830113 -0.01950079 -0.1800847 -0.9834578 0.003627181 -0.1810984 -0.9834583 0.001247465 -0.1794936 -0.9837583 0.02263027 -0.1778838 -0.9837913 0.02149331 -0.1775346 -0.9838798 0.0416249 -0.1741508 -0.9838389 0.04219222 -0.1743119 -0.9837862 0.06406557 -0.1677286 -0.9837493 0.0666027 -0.1680979 -0.9835178 0.0826863 -0.1608166 -0.9835146 0.08617353 -0.1603972 -0.9832837 0.1002115 -0.152492 -0.983211 0.104516 -0.1522305 -0.9828034 0.1188869 -0.1415959 -0.9827597 0.1231971 -0.1408511 -0.9823357 -0.1851092 -0.5205817 -0.8335043 -0.1954353 -0.5166519 -0.8335921 -0.1962839 -0.511968 -0.8362784 -0.1731216 -0.5204184 -0.836178 -0.1764765 -0.5109883 -0.841277 -0.134188 -0.5237884 -0.8412131 -0.1403753 -0.5134755 -0.8465445 -0.09214341 -0.5241678 -0.8466154 -0.1004207 -0.5162468 -0.8505321 -0.04639786 -0.5240868 -0.8504002 -0.05484211 -0.5166056 -0.8544655 0.0106858 -0.5194817 -0.8544149 0.003974854 -0.5149797 -0.8571932 0.06381082 -0.5106286 -0.8574302 0.06066089 -0.5096214 -0.8582578 0.1167917 -0.5001128 -0.8580483 0.1182857 -0.5005731 -0.8575751 0.1794379 -0.4821727 -0.8575032 0.1862769 -0.4833768 -0.8553642 0.2318825 -0.4628796 -0.8555543 0.2413082 -0.4619367 -0.8534547 0.2815433 -0.4391494 -0.8531597 0.293273 -0.4386937 -0.8494344 0.3349341 -0.4078834 -0.8493824 0.3467431 -0.4059711 -0.8455511 -0.2669603 -0.7840822 -0.5603103 -0.2932845 -0.7743859 -0.5606341 -0.2954987 -0.7686092 -0.5673804 -0.2596701 -0.7815641 -0.5672116 -0.266533 -0.7697107 -0.5800912 -0.2016074 -0.7893014 -0.5799636 -0.2127082 -0.7762155 -0.5935022 -0.138832 -0.7927041 -0.5935875 -0.1525388 -0.7825784 -0.6035752 -0.06992787 -0.7944252 -0.6033231 -0.08349603 -0.7850728 -0.6137502 0.01625853 -0.789424 -0.613633 0.005889117 -0.7839443 -0.6208034 0.09668558 -0.777677 -0.6211848 0.09195721 -0.7765366 -0.6233258 0.1771296 -0.761923 -0.6229757 0.1792461 -0.7623975 -0.6217885 0.2721521 -0.7344595 -0.6216931 0.2818463 -0.7354139 -0.6162217 0.3514658 -0.7044917 -0.6165738 0.3649124 -0.7023261 -0.6112095 0.4261165 -0.6673743 -0.6107671 0.4425213 -0.6653459 -0.6012402 0.5058984 -0.6185518 -0.6012158 0.5223594 -0.6142665 -0.5914537 -0.1306505 -0.9522799 -0.2758505 -0.08370572 -0.9519847 -0.2944802 -0.08181107 -0.9524661 -0.2934541 0.02009701 -0.9558957 -0.2930181 0.006172776 -0.9522269 -0.3053293 0.1173022 -0.9449215 -0.3055546 0.1111539 -0.9444648 -0.3092426 0.2148122 -0.9265056 -0.308939 0.2173933 -0.9265653 -0.3069478 0.3298044 -0.8927961 -0.3068296 0.3414124 -0.891584 -0.2975161 0.425089 -0.8547853 -0.2977275 0.4413518 -0.8496598 -0.2885946 0.5141389 -0.8078157 -0.2882623 0.532887 -0.8012493 -0.2720865 0.6080409 -0.7458435 -0.2720364 0.6264246 -0.7364105 -0.2555226 -0.8982406 0.3089555 -0.3125866 -0.999826 0.01280641 -0.01356309 -0.99996 -0.002630114 0.00855416 -0.9999993 0.001251518 0 -0.9999719 -0.006362915 0.0039649 -0.9999939 -0.003474414 4.5297e-4 -0.9998546 0.009800076 -0.01395797 -0.9998256 -0.004451453 -0.01813852 -0.9868623 -0.01189595 -0.1611255 -0.8304349 -0.4206063 -0.3653332 -0.3654364 -0.1607699 -0.9168475 -0.4672143 0.1666212 -0.8683019 -0.5071823 0.4173475 -0.7540472 -0.6536684 -0.4314262 -0.6217631 -0.6226043 0.6045095 -0.4969227 -0.01640981 -0.08457082 -0.9962824 -0.1524556 0.2350817 -0.9599447 -0.006608426 -0.001633226 -0.9999769 -0.007223427 -0.01232933 -0.9998979 -0.04627627 -0.03241568 -0.9984026 -0.04610592 -0.02925837 -0.9985081 -0.09048837 -0.1528089 -0.9841044 -0.08610808 -0.0477184 -0.9951425 -0.1380866 -0.2772257 -0.9508302 -0.1348796 -0.06793814 -0.9885302 -0.1790935 -0.4178663 -0.8906815 -0.1466042 0.5602076 -0.815276 -0.294848 0.084472 -0.9518031 -0.3891897 0.6449419 -0.6577091 -0.5085124 -0.4187361 -0.7523797 -0.381945 0.1523636 -0.9115391 -0.3945297 -0.2265598 -0.8905151 -0.2508564 0.06423491 -0.9658908 -0.2573873 -0.05459451 -0.9647648 -0.1379488 -0.003678321 -0.9904326 -0.1271188 0.1574626 -0.9793091 -0.02756857 -0.09223675 -0.9953555 -0.01993805 0.04148852 -0.9989401 -0.5928751 0.6528533 -0.4714676 -0.8092727 -0.1948972 -0.5541596 -0.6214665 0.07162094 -0.7801602 -0.6214021 0.07230323 -0.7801486 -0.421323 -0.0854988 -0.9028716 -0.3919217 0.2472484 -0.8861522 -0.2363256 -0.1887096 -0.9531732 -0.1729742 0.4874673 -0.8558363 -0.05623042 -0.3569619 -0.932425 -0.03059661 0.1264726 -0.9914981 -0.6923375 0.688124 -0.2171503 -0.9281159 0.2850149 -0.2395152 -0.7977787 -0.2451412 -0.5508675 -0.6716544 0.5239582 -0.5237826 -0.5336412 -0.43696 -0.7240808 -0.4194576 0.6107418 -0.6716024 -0.3031296 -0.5110582 -0.8043209 -0.1660289 0.7580047 -0.6307641 -0.07855123 -0.6615151 -0.7458067 -0.03801983 0.2481268 -0.9679812 -0.9524126 -0.07540142 -0.2953386 -0.01557743 -0.1716729 -0.9850309 -0.1566975 -0.1873346 -0.9697173 -0.296033 -0.1800042 -0.9380634 -0.5687736 -0.2331119 -0.7887684 -0.478197 -0.1650189 -0.8626102 -0.3656191 -0.1554046 -0.9176994 -0.870661 -0.2914594 -0.3962334 -0.8097235 -0.1611086 -0.5642623 -0.7056905 -0.08658641 -0.7032096 -0.9998281 -0.003260314 -0.01825398 -0.9844491 -0.08419787 -0.1541774 -0.1947149 -0.2274026 -0.9541353 -0.1943117 -0.3133324 -0.9295514 -0.1947103 -0.3139962 -0.929244 -0.1942477 -0.46495 -0.8637647 -0.194812 -0.4655349 -0.8633224 -0.1952784 -0.6032483 -0.7732775 -0.1956633 -0.6037555 -0.7727842 -0.1951993 -0.7245355 -0.6610186 -0.1957118 -0.7249033 -0.6604636 -0.1961801 -0.8250839 -0.5298586 -0.1965056 -0.8253481 -0.5293262 -0.1960373 -0.9023713 -0.383791 -0.19644 -0.9024973 -0.3832885 -0.4422226 -0.8254299 -0.3508628 -0.5553603 -0.2162502 -0.8030011 -0.5544483 -0.2658532 -0.7886123 -0.5546903 -0.2663437 -0.7882765 -0.5537416 -0.3946982 -0.733201 -0.5540807 -0.3950912 -0.732733 -0.5550345 -0.511665 -0.6558474 -0.5552664 -0.512006 -0.6553847 -0.5543164 -0.6148779 -0.5609444 -0.5546291 -0.6150714 -0.5604229 -0.5555804 -0.69963 -0.4492753 -0.5557783 -0.6997705 -0.4488117 -0.556546 -0.739777 -0.3781358 -0.6081087 -0.7306637 -0.310378 -0.8221179 0.004984021 -0.5692954 -0.8307751 -0.1777774 -0.5274544 -0.8308675 -0.1781193 -0.5271933 -0.8302322 -0.2641866 -0.4908359 -0.8303698 -0.2644522 -0.49046 -0.8310086 -0.3421362 -0.4385975 -0.8311025 -0.342368 -0.4382383 -0.8304656 -0.4115247 -0.3754655 -0.8305886 -0.411641 -0.3750658 -0.8312277 -0.4677695 -0.3004204 -0.8313062 -0.4678542 -0.3000708 -0.8306711 -0.5123434 -0.2179214 -0.7798725 -0.5138348 -0.3574532 -0.976741 -0.1368588 -0.1650663 -0.9806876 -0.06238663 -0.1853637 -0.9806968 -0.06253832 -0.1852644 -0.9806063 -0.09282243 -0.1726133 -0.9806196 -0.09293383 -0.1724779 -0.9807145 -0.1201556 -0.1541488 -0.9807241 -0.1202469 -0.1540159 -0.9806332 -0.1446347 -0.1320585 -0.9806449 -0.1446937 -0.1319074 -0.9807398 -0.1643096 -0.1056017 -0.9807484 -0.1643463 -0.1054657 -0.9661998 -0.2509967 0.05880987 -0.9657216 -0.2389025 -0.1015258 -0.9220495 -0.3870551 -0.003615975 -0.4608733 -0.855971 -0.2343276 -0.612043 -0.7893695 -0.04795151 -0.7966203 -0.6033905 -0.03627872 -0.8697597 -0.4817931 -0.1067404 -0.9975097 -0.06883823 -0.01535236 -0.2011927 -0.9560752 -0.2131709 -0.1949402 -0.9763424 -0.09356302 -0.1948258 -0.9763398 -0.09382653 -0.1946319 -0.9689751 -0.1523344 -0.1972025 -0.968756 -0.1504095 -0.1636829 -0.9110983 0.3782961 -0.03455525 -0.9772914 -0.2090636 -0.5305554 -0.8165574 0.2274757 -0.5549468 -0.8281022 -0.07925176 -0.5553789 -0.827911 -0.07821691 -0.554998 -0.8218008 -0.1289217 -0.5564366 -0.8210454 -0.1275261 -0.5196112 -0.8327182 0.1912714 -0.2249543 -0.7586189 -0.611468 -0.8310747 -0.5523512 -0.06498652 -0.8312107 -0.5534358 -0.05289465 -0.8313817 -0.5532398 -0.05225217 -0.831133 -0.5493912 -0.08594977 -0.831656 -0.54873 -0.08510959 -0.7880124 -0.5806244 0.2047241 -0.5780187 -0.5953812 -0.5580465 -0.9913316 -0.1313781 -0.00126475 -0.9915072 -0.1299299 -0.005628585 -0.980531 -0.1927658 -0.03742229 -0.9807547 -0.1943663 -0.01849579 -0.9807734 -0.1942928 -0.01827478 -0.9807404 -0.192997 -0.03000855 -0.9807932 -0.1927703 -0.02973902 -0.9442066 -0.2396969 0.2258747 -0.964707 -0.2571668 -0.05661952 -0.189677 0.1217514 0.9742686 -0.1473119 0.829582 0.5386028 -0.1524342 0.1005223 0.9831882 -0.1629503 0.1273466 0.9783813 -0.2120034 0.1577849 0.9644473 -0.1901935 0.1659209 0.9676243 -0.2926227 0.3143529 0.9030804 -0.2903259 0.313312 0.9041828 -0.3674096 0.40491 0.8372923 -0.4873403 0.4532485 0.7463681 -0.2064568 -0.01554483 0.9783322 -0.1590553 0 0.9872697 -0.141439 0.03143393 0.9894479 -0.1401178 0.02694082 0.9897683 -0.2322875 -0.01928126 0.9724561 -0.3207586 0.01566088 0.9470315 -0.4023575 -0.03791451 0.9146972 0.08876359 -0.6585299 0.7473015 0.1225368 -0.5369013 0.8346986 0.01824885 -0.1832309 0.9829006 0.153676 -0.53715 0.8293694 0.3093983 -0.6207967 0.7203361 0.2537645 -0.5839158 0.771133 0.1321741 -0.4096601 0.9026122 0.153614 -0.3900107 0.9079067 0.1323376 -0.3625043 0.9225386 0.164676 -0.331994 0.9287959 0.1251704 -0.2864983 0.949869 0.029082 -0.1957484 0.9802228 -0.006093859 -0.2288447 0.9734439 -2.87708e-4 -0.2365672 0.9716151 -0.05621701 -0.287338 0.9561781 -0.03978258 -0.3067799 0.9509488 -0.3204206 -0.1509994 0.935163 -0.2381335 -0.0830174 0.967678 -0.2088708 -0.1210575 0.9704217 -0.1544436 -0.07127112 0.9854277 -0.1439426 -0.08576869 0.9858623 -0.1082177 -0.05226778 0.9927523 -0.0885412 -0.0752002 0.9932299 -0.3641377 -0.1000792 0.9259524 -0.1371257 -0.3871386 0.9117677 -0.1084221 -0.4145731 0.9035341 0.06383746 -0.5838916 0.809318 0.2697505 -0.7171868 0.6425557 -0.1629489 -0.4549989 0.8754563 0.0633018 -0.6771711 0.7330977 0.07131397 -0.6756732 0.7337439 -0.9298208 -0.3236547 0.1751595 -0.742907 -0.3803216 -0.5508581 -0.9156206 -0.3361501 -0.2205494 -0.7574754 -0.2990383 -0.5803509 -0.7791498 -0.2070342 -0.5916608 -0.7497435 -0.1135685 -0.6519103 -0.9244129 -0.1420132 -0.3539678 -0.965839 -0.05537176 -0.2531582 -0.9139157 -0.342383 -0.2180188 -0.9595282 -0.2442328 0.1401997 -0.9600885 -0.1057049 0.2589527 -0.991178 -0.02587634 0.1299871 -0.9954565 -0.08924096 0.03320384 -0.982859 -0.1252819 -0.1352506 -0.6466326 0.6350399 0.4225998 -0.7491677 0.5233409 0.4060322 -0.7755948 0.4576009 0.4348037 -0.8588077 -0.4147251 0.3007532 -0.9131037 -0.03904539 0.4058536 -0.9156239 0.06266373 0.3971226 -0.8762149 0.198661 0.4390688 -0.8333365 0.3264393 0.4460804 -0.6015607 -0.7900388 0.1181678 -0.9173411 -0.3969298 0.03053194 -0.8507677 -0.4307131 0.3011325 -0.7309485 -0.6542435 0.1941128 -0.5745922 -0.814698 0.07817423 -0.7294796 0.5157729 0.4492636 -0.7248597 0.5213763 0.4502724 -0.8907654 0.05266821 0.4514015 -0.885297 0.07238823 0.4593575 -0.8381851 -0.4228677 0.3444254 -0.8439245 -0.3931508 0.3649985 -0.5847201 -0.7965621 0.1535944 -0.424149 -0.8841787 0.1957697 -0.5850983 -0.7758706 0.2359765 -0.6100312 -0.7694772 0.1891216 -0.7854749 -0.2095774 0.5823286 -0.7699002 -0.311775 0.5568215 -0.7948029 0.186042 0.5776478 -0.8064283 0.1231179 0.5783731 -0.6787006 0.553027 0.4832461 -0.6892144 0.5350999 0.48852 -0.7149628 0.5186612 0.4688485 -0.7036802 0.5359258 0.4664952 -0.8579103 0.06510251 0.5096583 -0.8465486 0.1253802 0.5173347 -0.8061922 -0.4024139 0.4337247 -0.8266979 -0.3086604 0.4704249 -0.6566787 -0.6823486 0.3212066 -0.5874518 -0.6868412 0.4279599 -0.6523586 -0.5719855 0.4972533 -0.8587692 -0.4737599 -0.195108 -0.7199178 -0.4371662 -0.5390771 -0.3426156 -0.9377568 0.05680495 -0.2312287 -0.9728932 -0.003465056 -0.3012098 -0.9533292 -0.02088385 -0.3056017 -0.9461271 -0.1070097 -0.4605908 -0.8752747 -0.1474802 -0.4707654 -0.8297765 -0.2997517 -0.5452937 -0.7823225 -0.3010421 -0.6294298 -0.7051782 -0.3264077 -0.6357624 -0.6373214 -0.4354627 -0.704724 -0.5380837 -0.4624177 -0.725104 -0.4289134 -0.5387555 -0.8577594 -0.4772645 -0.1909644 -0.7227098 -0.6764111 -0.1419814 -0.7244976 -0.6750209 -0.1394634 -0.5179767 -0.8519365 -0.07684111 -0.5184238 -0.8517347 -0.07605803 -0.3172101 -0.9480757 -0.02302825 -0.482424 -0.8756977 0.02051013 -0.5840994 -0.7925789 0.1750622 -0.6283876 -0.7710151 0.1032708 -0.7728622 -0.6320233 0.05683863 -0.7567428 -0.634461 0.1574794 -0.909375 -0.4027932 0.1038979 -0.8812373 -0.4402668 0.1720057 -0.1790164 -0.9835685 0.02337229 -0.1616603 -0.9858616 0.04407799 -0.0946123 -0.9945853 0.04299795 -0.0162577 -0.9985136 0.05202311 0.02977544 -0.997678 0.0612545 -0.3522381 -0.9354255 -0.03012508 -0.2768626 -0.9608738 -0.008285343 -0.3882414 -0.9199938 -0.05366623 -0.3919034 -0.9192219 -0.03798472 -0.5527069 -0.8315331 -0.05538904 -0.4933002 -0.8682703 -0.05255299 -0.6300139 -0.7717984 -0.08608031 -0.6908563 -0.7136119 -0.1160846 -0.749516 -0.6505332 -0.1226068 -0.7968621 -0.5887574 -0.1355565 -0.3412353 -0.939885 -0.01321339 -0.4096543 -0.9112136 -0.04328048 -0.409075 -0.9113438 -0.04593861 -0.6929925 -0.71307 -0.1062667 -0.7097954 -0.6952477 -0.113231 -0.2810307 -0.9596612 -0.00850743 -0.06352025 -0.997752 0.02135974 -0.08886384 -0.9951884 0.04127317 -0.08621203 -0.9958806 0.02809906 -0.07659602 -0.9966437 0.02888798 -0.08027869 -0.995706 0.04609704 -0.01433366 -0.9991586 0.03842961 -0.8034641 -0.5792338 -0.1375995 -0.8034659 -0.5792278 -0.1376147 -0.8034648 -0.5792294 -0.137615 -0.803467 -0.5792263 -0.1376149 -0.8028845 -0.5800402 -0.1375861 -0.8034617 -0.5792331 -0.1376172 0.9925565 0 -0.1217851 0.9931034 0.001379966 -0.1172339 0.9781066 -3.38005e-4 -0.2081043 0.9673226 -0.003791391 -0.2535207 0.9645652 -0.001560747 -0.2638402 0.4631775 -0.007921576 -0.8862302 0.5113561 0.006636798 -0.8593434 0.5813516 -0.006806671 -0.813624 0.621989 0.005993187 -0.7830031 0.6883406 -0.006131291 -0.7253618 0.6951601 -0.003811657 -0.7188448 0.7820817 0.007416784 -0.6231319 0.7600227 -0.008566915 -0.6498401 0.860768 0.009150385 -0.5089152 0.8415664 -0.007455468 -0.5401023 0.9229195 0.007439196 -0.3849214 0.8911535 -0.02327138 -0.4531047 0.9278876 0.001926541 -0.3728553 0.3360931 -0.007419586 -0.9417997 0.362783 0.005672693 -0.9318564 0.4421405 -0.003176152 -0.8969402 0.1732514 -0.03083914 -0.9843947 0.1765424 -0.02837324 -0.9838841 0.2281488 0.008265852 -0.9735913 0.2025483 0 -0.9792724 0.1949703 -0.008199036 -0.9807749 0.1829521 -0.02138155 -0.9828893 0.1751785 -0.02904462 -0.9841083 0.993093 -0.06037735 -0.1006032 0.8582342 0.3414979 -0.3831623 0.9710811 0.04098451 -0.2352058 0.7468967 -0.07983922 -0.6601296 0.7454163 -0.08489197 -0.6611717 0.8794741 -0.07614523 -0.4698165 0.9614017 -0.03303629 -0.2731584 0.9989386 -0.04497665 0.009941101 0.991235 -0.05452394 -0.1203345 0.9854853 -0.0065068 -0.1696364 0.9702435 -0.131779 -0.2031301 -0.9770382 -0.1497778 0.1515361 -0.9753106 -0.1952298 0.103221 -0.8141953 -0.5469883 0.1946532 -0.7088481 -0.5567675 0.433064 -0.09970694 -0.9777353 0.1846411 -0.5904157 -0.8024791 0.08623552 -0.3520832 -0.8684573 0.3490263 -0.6605935 -0.7044144 0.2596471 -0.8784907 -0.1930583 0.4370157 -0.8581451 -0.1505572 0.4908357 -0.8170337 -0.4467141 0.3645582 -0.9045731 -0.4245967 -0.03827762 -0.6921144 -0.7037245 0.1604667 -0.5538784 -0.8323028 -0.02215486 -0.4317789 -0.891199 0.1390371 -0.1915154 -0.9759556 -0.1040801 -0.8017122 -0.1240472 0.5846965 -0.7156766 -0.4049686 0.5690408 -0.5561367 -0.6715602 0.489611 -0.5352811 -0.695495 0.4793338 -0.5627118 -0.6588523 0.4992685 -0.5762706 -0.6477008 0.4983933 -0.6072807 -0.6108109 0.5080554 -0.6488512 -0.5613903 0.5136468 -0.6803485 -0.5036422 0.5324195 -0.2034274 -0.939441 0.2758041 -0.2582906 -0.9122954 0.3178101 -0.3376531 -0.8698257 0.3597133 -0.4125998 -0.8278741 0.3799816 -0.4860171 -0.7870652 0.3798893 -0.4160324 -0.8189758 0.3952163 0.06796675 -0.9932607 0.0938822 0.02294999 -0.9915893 0.1273743 -0.06138944 -0.9823323 0.1767896 -0.7982055 -0.2893419 0.528346 -0.7953759 -0.1898043 0.5756314 -0.7908872 -0.1889243 0.5820696 -0.7910028 -0.1877496 0.5822926 -0.7950877 -0.1883232 0.5765156 -0.7949243 -0.1908943 0.5758948 -0.7992134 -0.1911968 0.569826 -0.7992494 -0.195985 0.5681465 -0.6661453 -0.5415046 0.5128579 -0.6555008 -0.5395504 0.5283977 -0.6568369 -0.5365184 0.5298238 -0.6680762 -0.5380952 0.5139337 -0.6653631 -0.544721 0.5104616 -0.6770797 -0.5455506 0.4939005 -0.6728433 -0.5578195 0.4859212 -0.4132987 -0.8189311 0.3981662 -0.4083632 -0.8179509 0.405211 -0.4147117 -0.8102718 0.4140941 -0.4256695 -0.8123871 0.3985382 -0.4291306 -0.8088608 0.401984 -0.4459336 -0.8112244 0.3782305 -0.4386054 -0.8188557 0.3702713 -0.4558995 -0.8200929 0.3458368 -0.4432887 -0.8339139 0.3287593 -0.1421204 -0.9671653 0.210697 -0.1181172 -0.9716776 0.2046732 -0.1057691 -0.9692481 0.2221962 -0.1207938 -0.9673949 0.222612 -0.1226245 -0.9658826 0.22811 -0.1345534 -0.968137 0.2112019 -0.1403108 -0.9660304 0.2170211 -0.1602613 -0.968847 0.1888173 -0.1478816 -0.9732589 0.1757791 -0.1679028 -0.9747092 0.1474813 -0.1460113 -0.9818962 0.1206678 -0.5485747 -0.3854565 0.7419496 -0.5360739 -0.3876685 0.7498919 -0.105337 -0.2793033 0.9544076 -0.09641414 -0.279224 0.9553734 0.3656884 -0.1015546 0.9251804 0.3683868 -0.1013011 0.9241371 -0.5882878 -0.2740429 0.760801 -0.5807423 -0.277804 0.7652212 -0.1335658 -0.1989541 0.9708643 -0.1280524 -0.2006913 0.9712496 0.3557379 -0.07227373 0.9317871 0.3574568 -0.07276052 0.931091 -0.6354235 -0.1169734 0.7632525 -0.616231 -0.120854 0.7782376 -0.1707061 -0.08591341 0.9815693 -0.1561769 -0.08757382 0.9838392 0.3425635 -0.03120642 0.9389764 0.3471817 -0.03166019 0.9372634 -0.3539962 -0.07967442 0.931847 -0.5091106 -0.4527142 0.7320221 -0.5238094 -0.4452666 0.7261966 -0.09465086 -0.2832443 0.9543657 -0.1443929 -0.2599291 0.9547709 0.346756 -0.05444407 0.936374 0.1315205 0.2459421 0.9603202 0.1745285 0.1181433 0.9775388 0.2587172 -0.001878798 0.9659513 -0.3873831 -0.08611041 0.9178887 -0.530162 -0.007580876 0.8478625 -0.5425166 -0.01442205 0.8399214 -0.6271325 -0.5182322 0.5814983 -0.684409 -0.4437411 0.5785139 -0.6069491 -0.465116 0.6444222 -0.5903704 -0.4501869 0.6699213 -0.5731013 -0.4597513 0.6783685 -0.5446169 -0.4517011 0.7066531 -0.6933874 -0.2844264 0.662054 -0.7097916 -0.09657102 0.6977607 -0.752869 0.03996586 0.656956 -0.6907976 0.1568626 0.7058278 -0.652327 0.3398312 0.6774839 -0.5183882 -0.4531694 0.7251974 -0.5460349 -0.4504068 0.706385 -0.2001686 -0.1782279 0.9634144 -0.2510419 -0.1730729 0.952378 0.1341855 0.1066117 0.9852047 -0.08485692 0.3050397 0.9485516 -0.1168211 0.3043904 0.9453568 -0.3510707 0.4322175 0.8306247 -0.346821 0.4333987 0.8317938 -0.6354129 0.5018308 0.5868699 -0.5505402 0.5624359 0.6169048 -0.6705234 0.5571708 0.4898564 -0.6469177 -0.5204138 0.5573751 -0.6357123 -0.545414 0.5462542 -0.7377631 -0.2893048 0.609925 -0.7587981 -0.1861877 0.624147 -0.6685486 0.5606524 0.4885813 -0.7501214 0.3347122 0.5703383 -0.771656 0.2006709 0.6035546 -0.779074 0.1503528 0.6086362 -0.774924 -0.1029818 0.6236085 -0.6719574 0.553732 0.4917866 -0.6700015 0.5572242 0.4905093 -0.7753549 0.1881409 0.6028497 -0.7730752 0.2005376 0.6017802 -0.757327 -0.206902 0.6193928 -0.7599053 -0.1862962 0.6227663 -0.6207588 -0.5695528 0.5387654 -0.632435 -0.5450912 0.550365 0.9773989 -0.05151212 0.2050315 0.9788478 -0.1344439 0.1542135 0.9730833 -0.03811186 0.2272807 0.9819208 -0.06602156 0.1774055 0.978641 -0.0800457 0.1893529 0.9722648 -0.09820526 0.2122662 0.9823127 -0.1868213 -0.01262837 0.9629129 -0.2644178 0.05368536 0.9602068 -0.2738564 -0.05482316 0.9165162 -0.3894515 -0.09124487 0.9681363 0.2352901 0.08573621 0.6818268 0.718791 -0.1358374 0.6780149 0.7297279 -0.08827817 0.8352984 0.5468603 -0.05675059 0.8319151 0.5545278 -0.0204069 0.9736592 0.2226213 0.04926896 0.8184326 0.5425057 -0.1893562 0.9867794 0.08911794 0.1353681 0.9882565 0.1138905 -0.101873 0.9914697 0.128865 0.01953929 0.998276 0.01865768 0.05565196 0.9916149 -0.1192619 0.04976481 0.9859266 0.09239697 0.1393256 0.9412984 0.01439207 -0.3372687 0.9666853 -0.01946109 -0.255227 0.9474348 0.1540661 -0.2804123 0.9376818 -0.07795321 -0.3386389 0.9575048 -0.09493321 -0.272346 0.9545064 -0.08771985 -0.2849963 0.9926661 -0.04751342 -0.1111598 0.9726167 -0.1228238 -0.1973094 0.9511426 -0.1336749 -0.2783144 0.8835822 0.4681642 0.01023679 0.6871523 0.7102791 -0.1527264 0.749275 0.6573024 -0.08087354 0.8353639 0.5479866 -0.04333555 0.8796774 0.4750048 0.02319568 0.9795652 0.0398429 -0.1971414 0.9769346 0.05835622 -0.2054103 0.9621668 0.2250255 -0.1536186 0.9411244 0.3027701 -0.1503832 0.9390236 0.312824 -0.1427437 0.8984933 0.4302843 -0.08697819 0.8826909 0.4698576 -0.009523153 0.9617205 0.2443714 0.1240016 0.9748379 0.197716 0.1029536 0.9650089 0.2051782 0.1632779 0.975952 0.1708315 0.1354048 0.9712436 0.1767039 0.1595669 0.9815089 0.1286969 0.1416953 0.9781245 0.1384175 0.1552839 0.9819805 0.1229364 0.1435306 0.7451981 -0.5672176 -0.3506338 0.8617059 -0.4738283 -0.1815203 0.980525 -0.1233652 0.1528126 0.9389606 -0.3302069 -0.09652245 0.9109793 -0.2456331 -0.3313323 0.9620983 -0.0703144 -0.2634823 0.954199 -0.2323669 -0.1884409 0.9233726 -0.2788162 -0.2639029 0.6955171 -0.6314122 -0.3428916 0.7298741 -0.6100866 -0.3083474 0.7347615 -0.5736265 -0.3620474 0.7029794 -0.6306506 -0.3287855 0.6778836 -0.6379221 -0.3654167 0.6945461 -0.637088 -0.3342523 0.9160184 -0.3877562 -0.1027396 0.9214648 -0.3760662 -0.09735041 0.9711904 -0.2375407 -0.01907044 0.7376101 -0.6024064 -0.3050212 0.7770026 -0.5005635 -0.381711 0.7768579 -0.5676646 -0.2724865 0.7828381 -0.5580649 -0.2751872 0.7806738 -0.5677416 -0.2611857 0.6654362 -0.7264608 -0.1716083 0.7566339 -0.5961142 -0.2686133 0.7658388 -0.6050356 -0.217768 0.7510909 -0.5540915 -0.3589501 0.8958829 -0.3330672 -0.2940411 0.9060337 -0.3141539 -0.2835672 0.47415 -0.8176027 -0.3266614 0.4815565 -0.8374381 -0.2584589 0.4823821 -0.8120063 -0.3285627 0.5461746 -0.7820584 -0.3001301 0.5447092 -0.758948 -0.3567774 0.3530984 -0.9233112 -0.1510569 0.3473664 -0.9167255 -0.1973603 0.4815464 -0.7691419 -0.4201595 0.5567585 -0.6113091 -0.5624245 0.567415 -0.5297649 -0.6303883 0.5291517 -0.6531288 -0.5416837 0.4721086 -0.7685942 -0.4317134 0.499279 -0.7608743 -0.4144766 0.5631412 -0.6598933 -0.4974061 0.5619402 -0.6288248 -0.5374036 0.5691029 -0.6362461 -0.5208771 0.6020873 -0.5241975 -0.6022525 0.5751604 -0.6341504 -0.5167629 0.5607181 -0.5379056 -0.6294863 0.5850943 -0.554023 -0.5922191 0.5838029 -0.5487411 -0.5983791 0.5631603 -0.5550145 -0.6122168 0.5599028 -0.5463777 -0.6228807 0.5767752 -0.5154595 -0.6337444 0.5981427 -0.5500465 -0.5828158 0.6083328 -0.1950811 -0.769334 0.6046826 -0.2020684 -0.7704072 0.5945355 -0.1921036 -0.7807841 0.5647647 -0.2010683 -0.8003827 0.5553401 -0.1842688 -0.8109515 0.5571634 0.0549134 -0.8285853 0.5346595 -0.04607939 -0.8438104 0.5092229 0 -0.8606348 0.4716338 0 -0.8817945 0.4729195 -0.002318024 -0.8811026 0.4737918 -0.002699196 -0.8806328 0.4728742 0 -0.88113 0.2244554 0 -0.9744844 0.3127406 0.00499612 -0.9498255 0.3984925 0 -0.9171717 -0.8565071 -0.515536 0.02486407 -0.3463101 -0.9362538 0.05914551 -0.1844446 -0.9815416 0.05056089 -0.439745 -0.8969833 0.04522591 -0.07644438 -0.9969657 0.014692 -0.6372113 -0.7695921 0.04111051 -0.9305087 -0.3655678 0.02266633 -0.9319208 -0.3623602 0.01479429 -0.9332529 -0.3591108 0.008858025 -0.9254654 -0.3774489 0.03234356 -0.9044054 -0.4259918 0.02412122 -0.8826683 -0.468331 0.03953313 -0.8730678 -0.4845101 0.05479776 -0.8357112 -0.5447947 0.06917929 -0.8719385 -0.4831824 0.07910805 -0.4991551 -0.865736 0.0366804 -0.2607877 -0.9641124 0.04977166 -0.3059339 -0.9482929 0.08452963 -0.2842613 -0.9521687 0.1121183 -0.3545498 -0.9272792 0.1201995 -0.3259322 -0.9329866 0.1526577 -0.3608377 -0.9192998 0.157112 -0.7577718 -0.6519294 0.02775073 -0.6504161 -0.7583773 0.04269772 -0.6504646 -0.7565651 0.06711935 -0.6562662 -0.7518937 0.06301224 -0.6561094 -0.7484071 0.09699076 -0.6743273 -0.7327617 0.09134048 -0.674437 -0.7280097 0.1230317 -0.6798306 -0.723421 0.1203847 -0.6732072 -0.7306932 0.1134891 -0.3427377 -0.7271302 0.5948215 -0.6763883 -0.5869608 0.4449449 -0.9073955 -0.3387618 0.2487449 -0.2550734 -0.8466879 0.466966 -0.2828835 -0.6789819 0.6774663 -0.2466365 -0.788313 0.5636781 -0.2689231 -0.5422992 0.7959851 -0.1274833 -0.702039 0.700635 -0.1611815 -0.4268379 0.8898484 -0.130253 -0.5508186 0.8243986 -0.1574416 -0.2861999 0.9451465 -0.02669882 -0.4275861 0.9035804 0.2514964 -0.04523587 0.9668006 0.3173843 -0.3333083 0.887791 0.2037475 -0.2327783 0.9509475 0.2363842 -0.4950392 0.8360974 0.2112752 -0.399467 0.89207 0.232487 -0.6503229 0.7232081 0.1099442 -0.5422303 0.8330058 0.1389852 -0.7782078 0.6124343 0.1050511 -0.679726 0.7259042 0.1282673 -0.8402514 0.5268066 0.0405972 -0.737635 0.6739781 0.3008889 -0.1427155 0.9429201 0.04858243 -0.1445627 0.9883023 -0.04441094 -0.3627283 0.9308362 -0.1132163 -0.2457387 0.9627017 -0.366792 -0.2159704 0.904887 -0.5941078 -0.7410537 0.3128507 -0.6287522 -0.5588919 0.5406575 -0.5905862 -0.6960099 0.4083849 -0.60944 -0.4434024 0.6572498 -0.4596812 -0.6921409 0.5564479 -0.5118278 -0.3780929 0.7714132 -0.4725761 -0.5603734 0.6801865 -0.5013578 -0.2806974 0.8184434 -0.3513328 -0.5132352 0.7830422 -0.3296853 -0.5657765 0.7557807 -0.5050793 -0.3132812 0.8042076 -0.8310953 -0.5512123 0.07379561 -0.8785376 -0.3346281 0.3408752 -0.8336414 -0.5307376 0.1528393 -0.8598309 -0.2494803 0.4454779 -0.6885691 -0.6742299 0.2669959 -0.7907176 -0.2454766 0.5608092 -0.7178177 -0.5821911 0.3818262 -0.7794964 -0.1972799 0.5945302 -0.4947137 -0.7452003 0.4471409 -0.7299943 -0.2096733 0.6504963 -0.5700727 -0.5945246 0.5670605 0.9712752 -0.2031939 -0.1238421 0.9708508 -0.2062661 -0.1220783 0.7512717 -0.5619577 -0.3461132 0.7478072 -0.570172 -0.34013 0.9716712 -0.2035365 -0.1201168 0.9712647 -0.2064634 -0.1183967 0.754567 -0.5636485 -0.3360493 0.7512476 -0.5714452 -0.3302687 0.971676 0 -0.2363173 0.7545847 -0.5689134 -0.3270164 0.9713923 -0.192153 -0.1395498 0.753467 -0.5734082 -0.3216997 0.7530023 -0.5646744 -0.3378322 0.7500678 -0.5711596 -0.3334292 0.7470135 -0.5610827 -0.3565911 0.744921 -0.5668186 -0.3518657 0.9688955 -0.2215859 -0.110187 0.9659723 -0.1804729 -0.1852755 0.9604436 -0.224173 -0.165211 0.9478489 -0.1818439 -0.2617542 0.9457844 -0.2155773 -0.2429368 0.928547 0.2847208 -0.2381901 0.8680542 0.4261623 -0.2546916 0.7832631 0.5826625 -0.2168028 0.9783974 0.1224493 -0.1665678 0.9040879 0.3038313 -0.3005192 0.9587098 0.02163946 -0.283562 0.9648277 -0.04627752 -0.2587778 0.9643616 -0.0410313 -0.2613871 0.9300179 -0.2147085 -0.2982736 0.9213916 0.1519724 -0.3576899 0.9873636 -0.04076677 -0.153138 0.8425114 0.4432747 -0.3060754 0.9377207 0.3031572 -0.1696342 0.6818463 0.6921204 -0.2367594 0.8298968 0.5487724 -0.1005998 0.2850411 -0.9567845 0.05757766 0.285024 -0.9584004 0.01517349 0.9835689 -0.1804888 -0.004018783 0.9368972 -0.3495846 -0.00378257 0.957008 -0.2898976 0.009761214 0.901717 -0.4322119 -0.009981155 0.8251951 -0.564496 -0.01993477 0.7546408 -0.655879 -0.01843816 0.7415757 -0.6699226 0.03562754 0.04990446 -0.9982196 -0.03266847 0.07841885 -0.9963936 -0.03241121 0.2934508 -0.9557039 -0.02273476 0.4499062 -0.8925701 -0.03004926 0.681033 -0.73193 -0.0217396 0.5952188 -0.8035594 -0.002630949 0.7042288 -0.7098073 -0.01534628 0.9320542 -0.3622734 0.005744934 0.6838577 -0.7295123 0.01226747 0.6810069 -0.7321845 0.01164275 0.2791765 -0.9601021 0.01626449 0.2792382 -0.9599959 -0.0208348 0.1478812 -0.9885242 -0.03084039 0.2715267 -0.9608291 0.05550402 0.6503745 -0.7581058 0.04784095 0.6839118 -0.7284917 0.0395534 0.9075235 -0.4189834 0.029226 0.94262 -0.333657 0.01185768 -0.6402767 -0.766685 0.04732942 -0.5689876 -0.8212164 -0.04309374 -0.4335793 -0.8993437 -0.05648034 -0.323608 -0.9451277 -0.04484927 -0.2193223 -0.975529 0.01551985 -0.8482387 -0.5282393 -0.03813916 -0.79137 -0.6097244 -0.04438483 -0.9589111 -0.282873 -0.02173686 -0.9588929 -0.2829246 -0.02186554 -0.958607 -0.2837964 -0.02307134 -0.9590086 -0.282486 -0.02245593 -0.955103 -0.2961984 -0.006706476 -0.9557377 -0.293186 -0.02464693 -0.9386648 -0.3443024 0.01908534 -0.9303029 -0.366103 -0.02247524 -0.9255744 -0.3780258 -0.02021378 -0.9255263 -0.3785697 -0.009280443 -0.928845 -0.3703958 -0.007345497 -0.9299197 -0.3676707 0.008220255 -0.9248102 -0.3803833 0.005894958 -0.9248284 -0.379658 0.02350091 -0.911893 -0.4099669 0.01945847 -0.09720516 -0.9842534 0.1476365 -0.194874 -0.9803424 -0.03087222 -0.2143332 -0.9764204 -0.0257796 -0.1815909 -0.98323 0.01683831 -0.2000221 -0.9795693 0.02086311 -0.1850537 -0.9809392 0.05927503 -0.1914348 -0.9796424 0.06044578 -0.640723 -0.7663065 0.04741859 -0.6407142 -0.7675895 0.01708465 -0.6431889 -0.765532 0.01639997 -0.6431748 -0.7654879 -0.01882988 -0.6477143 -0.7616223 -0.01994848 -0.6476687 -0.7617393 -0.01669198 -0.7051974 -0.7080157 -0.03755486 -0.9554673 -0.2842739 0.07918745 -0.8856768 -0.004099905 0.4642843 -0.9085502 -0.1350191 0.3953561 -0.8696923 -0.1767209 0.4608743 -0.8708701 -0.3210753 0.3721506 -0.8607345 -0.360595 0.3593153 -0.8559937 -0.3924886 0.336493 -0.7999984 -0.46997 0.3730025 -0.8876321 -0.002140402 0.4605482 -0.9128755 -0.1687796 0.3717148 -0.9406054 -0.09317815 0.326465 -0.9381631 -0.275014 0.2102796 -0.9467916 -0.2291628 0.2259868 -0.9385358 -0.2938916 0.1810477 -0.8941805 -0.3837257 0.2306424 -0.2242323 -0.9745067 0.007513701 -0.6255502 -0.7783563 -0.05337011 -0.9001498 -0.4258851 -0.09139007 -0.4505583 -0.8832918 0.129588 -0.4418244 -0.8958911 0.04659003 -0.5130508 -0.8166957 0.2641726 -0.5096882 -0.8336911 0.2125493 -0.6561163 -0.7128213 0.2477849 -0.6548168 -0.7162731 0.24118 -0.7136666 -0.6235263 0.3192099 -0.7145454 -0.6201549 0.3237791 -0.7799248 -0.5384996 0.3189603 -0.7324565 -0.6739081 0.09672409 -0.7208632 -0.6930189 -0.009007036 -0.7603283 -0.627862 0.1664038 -0.7540981 -0.6509807 0.08694958 -0.8243141 -0.5429566 0.1603257 -0.8162099 -0.5655044 0.1183472 -0.8500881 -0.4896147 0.1939786 -0.8454754 -0.5056629 0.1716871 -0.8798938 -0.4354928 0.1900866 -0.9172403 -0.3974777 -0.02611213 -0.9127575 -0.404015 -0.06038123 -0.9206089 -0.3901113 -0.01709896 -0.9188438 -0.3934875 -0.02989494 -0.9257841 -0.3779114 -0.01033902 -0.9271752 -0.3746053 -0.004117965 -0.9281226 -0.3722725 -0.001286745 -0.9330153 -0.3594169 0.01737928 -0.9287229 -0.370641 0.009947955 0 -1 1.0538e-6 0 -1 -1.40009e-5 0 -1 1.27596e-7 0 -1 -1.08115e-6 0 -1 1.04363e-5 0 -1 -2.8959e-7 0 -1 -4.37545e-6 0 -1 5.66587e-6 0.728592 -0.6278378 0.2738127 0.8378009 -0.5229803 0.1567843 0.9174969 -0.3962213 0.03475916 0.7127193 -0.5732771 0.4042086 0.6406469 -0.7535173 0.147591 0.5775033 -0.6992909 0.4212865 0.5271371 -0.8488465 0.03982675 0.4768007 -0.8022358 0.3592755 0.4096134 -0.8953633 -0.1747609 0.2063519 -0.9181063 0.3383783 0.8404707 -0.484496 0.2426373 0.793935 -0.6030448 0.0774877 0.778021 -0.5749044 0.253315 0.7425832 -0.6697323 0.005377948 0.7303479 -0.6468315 0.2195472 0.6851514 -0.7179822 -0.1227567 0.5949047 -0.7780649 0.2017509 0.9148876 -0.4030413 0.02320104 0.9079821 -0.4190081 9.26781e-4 0.9089657 -0.4167032 0.01183873 0.9002173 -0.4340131 -0.0352351 0.9032216 -0.4291608 0.003477871 0.8894542 -0.4488897 -0.08584553 0.8841373 -0.4671775 -0.006814658 0.8811194 -0.3973393 0.2564178 0.8764813 -0.002368867 0.4814302 0.8989193 -0.1357743 0.4165447 0.9293861 -0.1015824 0.3548557 0.9312216 -0.2438312 0.2708744 0.9321216 -0.268542 0.2429701 0.9232427 -0.3249419 0.2050265 0.9465129 -0.3045321 0.106647 0.8746498 -0.004229426 0.484737 0.8990114 -0.1709503 0.4031807 0.8590091 -0.1737775 0.4815651 0.8569815 -0.3523651 0.3760607 0.8547955 -0.3234695 0.4058232 0.8293395 -0.4686475 0.3042461 0.7965277 -0.4186103 0.4362443 0.007350206 -0.9860944 0.1660244 0.874253 -0.4846215 0.02870124 0.8650313 -0.4987344 0.05463689 0.8279491 -0.5566934 0.06776905 0.8281837 -0.5533276 0.08910965 0.9313621 -0.3640943 4.09955e-5 0.9334964 -0.3585621 0.004225969 0.9299227 -0.3677341 -0.003929018 0.9283824 -0.3715007 -0.009661138 0.923563 -0.3703014 0.09954094 0.8869851 -0.4616439 -0.01193928 0.8857064 -0.4642415 -0.002072334 0.8881254 -0.4596012 -1.21787e-4 0.8880828 -0.4590989 0.02317923 0.5502659 -0.832535 0.06397503 0.6103631 -0.7916609 0.02702236 0.7213692 -0.6925492 -0.001468837 0.1610755 -0.9833734 0.08385443 0.2739943 -0.9613673 0.02645975 0.2562755 -0.9536636 0.1576344 0.4280771 -0.8913674 0.1490442 0.1033568 -0.9829415 0.1521297 0.103331 -0.9871217 0.1221209 0.1384889 -0.9835507 0.1159687 0.1384866 -0.9885858 0.05932754 0.1694188 -0.9841019 0.05329996 0.169511 -0.9853603 0.01820093 0.03254902 -0.9755318 0.2174357 0.3916355 -0.9201138 0.0035187 0.5989611 -0.8002583 0.02884846 0.5987009 -0.7995368 0.0479409 0.5820103 -0.8119702 0.04437011 0.5820125 -0.8070327 0.09979814 0.5628086 -0.8208549 0.09717977 0.5629637 -0.8172239 0.1233573 0.6712443 -0.7305256 0.125553 -0.08390891 -0.9963698 -0.01437175 -0.2851012 -0.9572901 -0.04809355 -0.2046884 -0.978187 -0.03539663 -0.1771414 -0.9837314 -0.02989238 -0.06748825 -0.9976354 -0.01300054 -0.5470114 -0.830698 -0.1035337 -0.3170403 -0.9475827 -0.0396561 -0.4633299 -0.8811753 -0.09410279 -0.3772926 -0.923447 -0.06997084 -0.7776095 -0.6145994 -0.1326317 -0.7996535 -0.5846339 -0.1369583 -0.6935364 -0.7082577 -0.1318271 -0.6188493 -0.7783078 -0.1061253 -0.5196031 -0.8497754 -0.08885008 -0.4274027 -0.9016978 -0.06532949 -0.7306321 -0.6725873 -0.1174867 -0.6769422 -0.7307093 -0.08839225 -0.7431412 -0.6541676 -0.1407335 -0.6273807 -0.7768966 -0.0531519 -0.7087095 -0.6931438 -0.1314632 -0.6792082 -0.723752 -0.1218987 0.793348 -0.6087008 0.009082794 0.959215 -0.2538797 -0.1243053 0.9459307 -0.3243663 0.001295685 0.8525695 -0.5226136 6.01822e-4 0.8421254 -0.4625025 -0.277338 0.8406256 -0.5291455 -0.1155582 0.9620921 -0.2726398 -0.00683093 0.7611028 -0.1487806 -0.6313374 0.9789898 -0.1803224 0.09520012 0.9957636 -0.09192788 -0.002071559 0.8958709 -0.4442251 -0.008906662 0.8498095 -0.5211283 0.07905274 0.7993942 -0.6006253 -0.01477813 0.7993688 -0.5995339 -0.03960615 0.8956403 -0.4426088 -0.04388618 0.9613897 -0.2705864 -0.05012863 0.9944559 -0.08953863 -0.05513983 0.9944525 -0.08772617 -0.05803787 0.9827333 -0.09599345 -0.1581789 0.9798382 -0.08174145 -0.1823062 0.9625089 -0.09816014 -0.2528663 0.9514464 -0.08662247 -0.2953749 0.9272478 -0.1084479 -0.3584001 0.9300096 -0.104739 -0.3522953 0.8983176 -0.08786761 -0.4304707 0.885666 -0.1002079 -0.453381 0.8438296 -0.09520232 -0.5280988 0.7991397 -0.6001341 -0.0348553 0.7957776 -0.6023453 -0.06259781 0.7958437 -0.6023687 -0.0615198 0.7903723 -0.6070798 -0.08225518 0.7895926 -0.6076107 -0.08574861 0.7833482 -0.6131369 -0.1021213 0.780608 -0.6150177 -0.1113759 0.7748395 -0.6203801 -0.1214594 0.7676858 -0.6262432 -0.1359344 0.7635407 -0.6300535 -0.1415568 0.7512859 -0.639532 -0.1629987 0.7487345 -0.6419112 -0.1653682 0.7271482 -0.6595026 -0.1905568 0.7294518 -0.6573892 -0.1890491 0.6976088 -0.6823396 -0.2185286 0.7092977 -0.6716139 -0.214083 0.6660637 -0.7075345 -0.2361233 0.6845524 -0.6911046 -0.2318674 0.631618 -0.7319393 -0.255585 0.8957005 -0.442418 -0.04457587 0.8903178 -0.4462261 -0.09064561 0.8901545 -0.4428953 -0.1070924 0.8832749 -0.4492468 -0.1341741 0.8780148 -0.4495868 -0.1642002 0.8718451 -0.455244 -0.1806631 0.8614121 -0.4550154 -0.2256773 0.8584846 -0.4578818 -0.2309734 0.8347592 -0.4711832 -0.2848924 0.8356502 -0.4703357 -0.2836776 0.8020142 -0.4822668 -0.3524088 0.8045957 -0.479749 -0.3499526 0.7502107 -0.5097181 -0.4211552 0.7592388 -0.5011872 -0.4151721 0.6857286 -0.535416 -0.4930579 0.7096967 -0.5124006 -0.483504 0.6149605 -0.5766128 -0.5379045 0.6458086 -0.5486384 -0.5309681 0.5350447 -0.6030093 -0.5916984 0.9615544 -0.2695972 -0.05225598 0.9529583 -0.2756935 -0.1259506 0.9523244 -0.2670921 -0.1474454 0.940184 -0.2785222 -0.1961618 0.9329066 -0.2734089 -0.234378 0.9193093 -0.2858639 -0.270467 0.9046047 -0.2731347 -0.3272429 0.892886 -0.284786 -0.348786 0.8612499 -0.2904869 -0.4169725 0.8513696 -0.2998358 -0.4304282 0.8047827 -0.2918038 -0.5168901 0.7928722 -0.3035296 -0.5284161 0.7187069 -0.318602 -0.6180236 0.7119038 -0.325056 -0.6225205 0.6096649 -0.3340941 -0.7188114 0.6224665 -0.3216484 -0.7134969 0.4949298 -0.3824471 -0.7802428 0.5155752 -0.3636485 -0.7758492 0.36249 -0.3915724 -0.8457376 0.7600578 -0.1672843 -0.6279555 0.8204402 -0.03571659 -0.5706157 0.6997871 -0.1371761 -0.7010568 0.7289589 -0.1102836 -0.6756156 0.6313934 -0.104111 -0.7684422 0.6079301 -0.1264473 -0.7838572 0.472706 -0.1019124 -0.8753074 0.4753072 -0.09938597 -0.8741885 0.31388 -0.1514055 -0.9373131 0.3285379 -0.137888 -0.9343713 0.1331989 -0.1315941 -0.9823142 0.4562353 0.1765468 0.87217 0.5165075 0.1182135 0.8480835 0.5382586 0.1569958 0.8280278 0.550044 0.1613942 0.8193922 0.5420249 0.1562578 0.8257073 0.5334348 0.149142 0.8325889 0.5257644 0.139193 0.8391647 0.5198798 0.1288108 0.8444719 0.5786079 0.2275038 0.7832337 0.5645806 0.2131317 0.7973856 0.5605019 0.1933217 0.8052729 0.5585951 0.1925944 0.8067708 0.5490121 0.1832798 0.8154718 0.5995063 0.2586687 0.7574185 0.5885662 0.2444759 0.7705981 0.6207256 0.3420826 0.7054638 0.6306943 0.291296 0.7192853 0.6072606 0.2674166 0.7481464 0.6247857 0.2382142 0.7435704 0.6160522 0.2516971 0.7464102 0.6142641 0.3432517 0.7105335 0.6264455 0.3457276 0.6985975 0.6503877 0.3530071 0.6725933 0.6330919 0.3634333 0.6834551 0.6553363 0.3590819 0.6645259 0.6782745 0.3676599 0.6362153 0.6719509 0.3737189 0.6393873 0.6940084 0.3654286 0.6203341 0.7074087 0.3716641 0.6011978 0.7142926 0.3773624 0.5893928 0.7151462 0.3790876 0.5872465 0.7143058 0.377199 0.5894813 0.7129152 0.3707516 0.595227 0.7127017 0.3656739 0.5986142 0.5505117 0.3049018 0.7771562 0.562031 0.3109883 0.7664253 0.5764074 0.3272036 0.7487939 0.5767762 0.327147 0.7485347 0.5981994 0.3299267 0.7302779 0.5847283 0.2271496 0.7787785 0.5347248 0.2991645 0.7902975 0.5379977 0.2994918 0.7879487 0.4862036 0.2340958 0.8419058 0.4937188 0.2468472 0.8338513 0.4972842 0.2607824 0.8274667 0.5078619 0.2654749 0.8195117 0.5245282 0.280638 0.8038113 0.4684973 0.2109759 0.8579041 0.4570977 0.206126 0.8652017 0.4777054 0.2218942 0.8500357 0.4407949 0.1556853 0.8840035 0.4424746 0.1570281 0.8829261 0.4404751 0.1380791 0.8870828 0.4252952 0.09657013 0.8998879 0.4259456 0.09734618 0.8994966 0.4376527 0.1217133 0.8908682 0.4210309 0.01131397 0.9069758 0.4178473 0.02599847 0.9081453 0.4160117 0.03263902 0.9087734 0.42102 0.04264682 0.9060482 0.4267256 0.06923615 0.9017271 0.4931563 0.1071621 0.8633152 0.4964903 0.06118476 0.8658834 0.4290311 0.0954768 0.8982297 0.5003738 0.01656103 0.8656511 0.472997 0.02700191 0.8806502 -0.02165019 -0.1288633 0.9914261 0.1119946 -0.298941 0.9476768 -0.1794227 -0.1100478 0.9775976 -0.2428648 -0.05861461 0.9682878 -0.2815431 -0.01908767 0.9593588 -0.5809792 -0.02695924 0.8134719 -0.3916381 -0.07349413 0.9171796 -0.2837384 -0.01550561 0.9587764 0.004731476 -0.1961864 0.9805552 -0.2726457 -0.2530072 0.9282519 -0.1128339 -0.1196428 0.9863845 0.6835615 0.1794872 0.70748 0.6902474 0.1681519 0.7037639 0.6915019 0.1674803 0.7026917 0.530975 -0.2423626 0.811989 0.5370297 -0.2416861 0.8081998 0.2694218 -0.6070212 0.747621 0.2691035 -0.6070194 0.7477371 -0.0477724 -0.8468245 0.5297226 -0.05547827 -0.8453268 0.5313612 0.6947287 0.1554439 0.7022745 0.7086255 0.1573202 0.6878229 0.5444431 -0.2563644 0.7986609 0.5532811 -0.2554156 0.7928701 0.283336 -0.6159307 0.7350851 0.2846202 -0.6159437 0.7345778 -0.03528624 -0.851167 0.5237076 -0.04286146 -0.8497131 0.5255004 0.7458673 0.117533 0.6556432 0.7297159 0.1021266 0.6760805 0.5689498 -0.2892036 0.7698426 0.5487501 -0.3012737 0.7798125 0.2735354 -0.6360169 0.7215685 0.253756 -0.6420481 0.7234516 -0.07854771 -0.849951 0.5209736 -0.09430134 -0.8499253 0.518396 0.7098118 0.1637907 0.6850839 0.7000916 0.1485781 0.6984242 0.5484164 -0.2483002 0.7984902 0.5318632 -0.2638418 0.8046795 0.2728735 -0.6091649 0.7446195 0.2513522 -0.6208144 0.7425709 -0.05926787 -0.8431327 0.5344293 -0.08267593 -0.8471429 0.5248939 0.6865865 -0.3499585 -0.6372817 0.7023906 -0.1165068 -0.7021921 0.6863577 -0.2360822 -0.6878796 0.7672826 -0.2175636 -0.6032775 0.7671412 -0.2123214 -0.6053216 0.8495709 -0.1836675 -0.4944648 0.8494518 -0.1748106 -0.4978683 0.8962069 -0.1519826 -0.4167907 0.8958814 -0.1481263 -0.4188736 0.9325527 -0.1253034 -0.3385922 0.9325902 -0.1069554 -0.3447265 0.9645941 -0.08538264 -0.2495355 0.9650583 -0.06217128 -0.2545527 0.5773152 -0.6967752 -0.4256895 0.5738446 -0.7011848 -0.423134 0.5438053 -0.7428286 -0.3904889 0.6230139 -0.5112437 -0.5920167 0.6005433 -0.5244427 -0.6035791 0.5976709 -0.5242607 -0.6065809 0.5520704 -0.5470938 -0.6292113 0.566565 -0.5500281 -0.6135743 0.524578 -0.5662056 -0.6357902 0.5346554 -0.5642198 -0.6291262 0.5004497 -0.5939841 -0.6298674 0.5465724 -0.7398203 -0.3923323 0.5399139 -0.7298548 -0.4192913 0.5445113 -0.7277253 -0.4170413 0.5575325 -0.720398 -0.4125342 0.5509865 -0.7223082 -0.4179531 0.5628465 -0.7128272 -0.4184273 0.5585164 -0.7128108 -0.4242174 0.5661192 -0.7071544 -0.4236056 0.5767181 -0.7185105 -0.3887659 0.5538303 -0.6821603 -0.4774196 0.5527728 -0.6838219 -0.4762666 0.5822727 -0.6972804 -0.4180416 0.5744452 -0.7012209 -0.4222583 0.5625894 -0.6966075 -0.4452317 0.5331446 -0.7392569 -0.4114077 0.5530496 -0.6834384 -0.4764956 0.5486646 -0.6919144 -0.4692777 0.5554132 -0.6848728 -0.4716625 0.5377199 -0.7039003 -0.4640923 0.5499988 -0.6968579 -0.4603155 0.5137214 -0.735558 -0.4416389 0.5302523 -0.7208563 -0.4463168 0.5386829 -0.6277058 -0.5619665 0.4608108 -0.6866768 -0.5622529 0.5128675 -0.6739866 -0.531704 0.496863 -0.686146 -0.5313482 0.5185433 -0.6910941 -0.5034897 0.5503547 -0.6846738 -0.4778404 0.5149439 -0.6506096 -0.5581577 0.5149457 -0.6506075 -0.5581586 0.49732 -0.6331897 -0.5930799 0.4581335 -0.6403846 -0.6164587 0.5515417 -0.6234153 -0.5542159 0.5515409 -0.6234151 -0.5542169 0.5704497 -0.6123367 -0.5473856 0.5704489 -0.6123384 -0.5473845 0.5891182 -0.6033346 -0.5375194 0.5891178 -0.6033346 -0.5375199 0.6034178 -0.5980362 -0.5274844 0.6034092 -0.5980398 -0.52749 0.5781762 -0.6734306 -0.4606556 0.5781841 -0.6734272 -0.4606505 0.5742452 -0.6748932 -0.463424 0.5742453 -0.6748936 -0.4634233 0.5691022 -0.6773736 -0.4661412 0.5691034 -0.6773726 -0.4661414 0.5575578 -0.6840834 -0.4702758 0.5636956 -0.6793037 -0.4698872 0.5576002 -0.6817577 -0.4735912 0.5328781 -0.6362833 -0.5578393 0.5328803 -0.6362823 -0.5578382 0.508638 -0.5942136 -0.6230552 0.4690608 -0.6222223 -0.6267547 0.1652175 -0.985242 0.04473751 -0.2513423 -0.9528751 0.1698713 0.4148225 -0.8920064 -0.1795745 0.632645 -0.6701748 -0.3881057 0.5474535 -0.7598394 -0.3506264 0.5306841 -0.7746429 -0.3439517 -0.1067753 -0.9877307 0.1139611 0.135419 -0.9903849 -0.02827799 -0.1284022 -0.9855474 0.1104958 -0.1175844 -0.9837227 0.1358811 -0.1154056 -0.9842708 0.1337635 -0.1064521 -0.9807811 0.1635126 -0.1049313 -0.9812653 0.1615795 -0.09655064 -0.9754848 0.1977559 -0.09281986 -0.9763612 0.1952012 -0.08662617 -0.965175 0.2468465 -0.0809192 -0.9664781 0.2436643 -0.0805332 -0.9547348 0.2863497 -0.07681679 -0.956185 0.282506 -0.07870751 -0.9422757 0.3254561 -0.06949406 -0.9442652 0.321767 -0.07801783 -0.9242519 0.373727 -0.06694692 -0.9264022 0.3705362 -0.07834696 -0.9093614 0.4085628 -0.07033383 -0.9118463 0.404462 -0.08358335 -0.8947166 0.4387435 -0.06928288 -0.8968479 0.4368796 -0.09003305 -0.8758438 0.4741221 -0.07278388 -0.8776652 0.4737155 -0.09496116 -0.8592704 0.50263 -0.07838839 -0.8613528 0.5019229 0.1218637 -0.9921699 -0.02735209 0.1519385 -0.9874465 0.04317706 0.168388 -0.9853606 0.0266456 0.1875332 -0.9781437 0.08981251 0.1982203 -0.9772651 0.07524472 0.2146154 -0.9656488 0.1465019 0.236723 -0.9628728 0.1297627 0.2481511 -0.9423176 0.2246302 0.2732207 -0.9391747 0.20809 0.2743089 -0.9178084 0.2870233 0.2873886 -0.9186457 0.2711049 0.283646 -0.892473 0.3507662 0.3118728 -0.8890177 0.3352359 0.2957092 -0.8507034 0.4345801 0.325761 -0.8467332 0.4206218 0.3027408 -0.8119798 0.4990358 0.3229112 -0.812934 0.4846305 0.2940248 -0.7755055 0.5586957 0.3262452 -0.7704933 0.5476352 0.2796034 -0.7230898 0.6316354 0.3138064 -0.7166889 0.6228022 0.2611058 -0.6728613 0.692157 0.291529 -0.6691328 0.6835731 0.28435 -0.9318171 -0.2255264 0.3443189 -0.930911 -0.1218574 0.3669506 -0.9178973 -0.1510362 0.4088397 -0.9110766 -0.05281764 0.4362066 -0.8960044 -0.08306509 0.4642211 -0.8856809 0.008260488 0.4812902 -0.876352 -0.01915889 0.5040078 -0.8599006 0.08091396 0.5388907 -0.8409298 0.04933583 0.5543693 -0.813147 0.1773886 0.5918831 -0.7927927 0.1454452 0.5940274 -0.7639447 0.252032 0.6128224 -0.7583765 0.222067 0.6072281 -0.7229363 0.3296016 0.6463109 -0.7025542 0.2978252 0.6246351 -0.6507773 0.431648 0.6649392 -0.6302449 0.4008083 0.6338209 -0.5819891 0.5094703 0.6612706 -0.5762986 0.4802097 0.6201473 -0.5236242 0.5841534 0.6615803 -0.5035868 0.5556185 0.5961156 -0.4367716 0.6737039 0.6388471 -0.4161444 0.6470689 0.5640159 -0.3532236 0.7464041 0.6023041 -0.3405097 0.7219992 0.4918743 -0.8035002 -0.3353317 0.5533998 -0.80117 -0.227762 0.5799723 -0.7696649 -0.2669237 0.6323745 -0.7611297 -0.1441668 0.6635186 -0.7248129 -0.1854434 0.6982929 -0.7120381 -0.07340866 0.7161931 -0.688786 -0.1124338 0.7430907 -0.669146 0.007734537 0.7798787 -0.6248261 -0.03717005 0.797798 -0.592662 0.1107707 0.8350195 -0.5465358 0.06357002 0.8380717 -0.512794 0.1862214 0.8559826 -0.4971905 0.141759 0.8490732 -0.4568275 0.2652986 0.884867 -0.4132 0.2151195 0.8603972 -0.3545922 0.3660346 0.8962136 -0.3128755 0.3144999 0.8610865 -0.2568954 0.4387881 0.887378 -0.2427798 0.3919416 0.839554 -0.1824955 0.5117075 0.8759177 -0.1460127 0.4598354 0.8016477 -0.07002836 0.5936809 0.8393079 -0.03593581 0.5424674 0.754184 0.03646546 0.65565 0.7905464 0.05618858 0.6098192 0 -1 2.02234e-7 0 -1 0 0 -1 4.02662e-5 0 -1 -5.06361e-6 0 -1 0 0 -1 -4.17167e-5 0 -1 6.65192e-7 0 -1 -2.70361e-6 0 -1 3.53144e-7 0 -1 1.42551e-7 -0.3802704 -6.39208e-4 0.9248752 -0.3088718 -0.0991646 0.94592 -0.2323421 -0.00662887 0.9726116 -0.1390557 -0.1205555 0.9829191 -0.3846572 -0.003370761 0.9230534 -0.2765434 -0.1437337 0.9501919 -0.4142476 -0.1557036 0.8967471 -0.278969 -0.3212956 0.9049561 -0.3432746 -0.2864432 0.8944903 -0.1554291 -0.4846929 0.8607639 -0.3244793 -0.4632717 0.8246773 -0.1380386 -0.6449188 0.7516816 -0.2247542 -0.5922514 0.7737724 -0.03317916 -0.7469919 0.6640048 -0.169515 -0.7195574 0.6734254 0.06963711 -0.8822953 0.4655169 -0.02154827 -0.8715261 0.4898754 0.1053333 -0.940205 0.3239126 0.07436996 -0.9308457 0.3577645 -0.3816844 -0.002170383 0.9242902 -0.311178 -0.1010873 0.9449602 -0.310321 -0.1017438 0.9451715 -0.2149859 -0.218178 0.9519346 -0.2144992 -0.2183866 0.9519966 -0.1014872 -0.3425207 0.9340128 -0.09754955 -0.3419259 0.9346502 0.01932841 -0.4545378 0.8905178 0.02296519 -0.4565349 0.8894091 0.1325117 -0.5500716 0.8245375 0.139976 -0.5498482 0.8234524 0.3239771 -0.6778568 0.6599614 0.3314805 -0.6767756 0.6573396 0.4339683 -0.7293224 0.5289238 0.4374435 -0.7301232 0.5249413 0.7673197 -0.4050047 0.4971839 0.7183173 -0.3852807 0.5792918 0.6835293 -0.3780832 0.6243724 0.6244562 -0.3501328 0.6981844 0.5476257 -0.3792462 0.7458407 0.4221386 -0.2894216 0.8590891 0.3121721 -0.3172459 0.8954907 0.2688053 -0.2783685 0.9220926 0.1859114 -0.2354669 0.9539352 0.1588327 -0.2099705 0.96472 -0.009939491 -0.2263074 0.9740053 -0.01082909 -0.2227265 0.9748209 -0.08716708 -0.1368497 0.9867492 0.8268952 -0.3963808 0.3989068 0.7714441 -0.4120609 0.4848504 0.5279825 -0.7583625 0.3822575 0.5242571 -0.7597104 0.384701 0.1556034 -0.9637843 0.2165811 0.1753206 -0.9628442 0.2054112 0.2320982 -0.9726693 0.006721079 0.2328599 -0.9725091 -0.001579284 0.645694 -0.7631205 0.02695268 0.6481045 -0.761507 0.008221387 0.9204188 -0.3891702 0.03709042 0.9226685 -0.3853605 0.01342773 0.2309165 -0.972772 0.01981365 0.2316989 -0.9727032 0.01281589 0.6424719 -0.7637658 0.0623846 0.6444508 -0.7632318 0.04648095 0.9162243 -0.3909197 0.08783572 0.918596 -0.3893511 0.06772953 0.2254403 -0.9724888 0.05867207 0.2269877 -0.9722961 0.05582946 0.6248028 -0.7629618 0.1658639 0.6292893 -0.7605829 0.1597148 0.8888135 -0.3931721 0.2354283 0.8933752 -0.3874939 0.2274413 -0.9050142 -0.4252084 0.0121392 -0.8803755 -0.4576746 -0.1243914 -0.7092777 -0.6896741 0.1458591 -0.6887273 -0.7195288 0.08906745 -0.4148278 -0.909778 0.01490437 -0.5036661 -0.8313974 0.2347314 -0.06994622 -0.9855315 -0.1543872 -0.2119688 -0.9595093 0.1855024 -0.9006453 -0.433952 0.02288722 -0.9074018 -0.4100437 0.09212052 -0.687719 -0.7221938 0.07401823 -0.7091651 -0.682191 0.1780461 -0.3878366 -0.9131693 0.1253194 -0.4264482 -0.8692739 0.2500101 -0.0385285 -0.9876579 0.1518135 -0.09429609 -0.9478435 0.3044686 -0.8803001 -0.4722574 0.04522073 -0.9063086 -0.4002624 0.1356275 -0.629986 -0.7555651 0.1795524 -0.6983423 -0.6551137 0.2883471 -0.2844918 -0.916934 0.2798151 -0.4034463 -0.8155237 0.4149125 0.1014502 -0.9419355 0.320102 -0.06416016 -0.8601374 0.5060112 -0.1973617 -0.936751 -0.2890433 -0.6364967 -0.02668988 -0.7708175 -0.8697426 -0.4886672 -0.06893533 -0.7005707 -0.6675701 -0.2520932 -0.5660873 -0.7262627 0.3899843 -0.3797461 -0.7188343 -0.5822973 -0.2076405 -0.7437775 0.6353585 -0.07589745 -0.6024867 -0.7945122 -0.0438289 -0.9989899 -0.009919583 -0.0307452 -0.9890397 -0.144414 -0.0610063 -0.5427203 -0.837695 -0.1955527 -0.9520476 0.2352968 -0.1742422 -0.3263447 -0.9290527 -0.336537 -0.848941 0.4074828 -0.2298322 -0.1432994 -0.9626227 -0.437995 -0.7048275 0.5580132 -0.543699 -0.809349 0.222139 -0.3318116 -0.6242299 0.7072752 -0.7117726 -0.3879535 -0.5855526 -0.6078621 -0.4545869 0.6510412 -0.4612113 0.1442508 -0.8754861 -0.4401575 -0.80885 -0.3899014 -0.1470059 -0.8245765 0.5463177 -0.2168802 -0.697526 -0.6829498 -0.157292 -0.9486287 -0.2745229 -0.1604107 -0.8580781 -0.4878221 -0.08411759 -0.9642037 -0.2514668 -0.0844466 -0.9623377 -0.2584085 -0.01411139 -0.973684 -0.2274653 -0.01331657 -0.9770492 -0.2125974 -0.9718235 -0.1947718 0.1327526 -0.1930578 -0.9793376 -0.06022077 -0.5494628 -0.8306645 0.08992809 -0.3981004 -0.9128952 -0.09021371 -0.04735666 -0.9958482 0.07774186 -0.8016489 -0.5348778 -0.2669546 -0.8728888 -0.4593498 0.1645085 -0.7900128 -0.612921 -0.01441055 -0.5538948 -0.8323479 -0.01994526 -0.5542296 -0.8321344 -0.01954311 -0.1923843 -0.9810339 -0.02368462 -0.1930683 -0.9809158 -0.02299702 -0.4201069 -0.8995583 0.1196035 -0.4865483 -0.7931554 0.3662995 -0.4108388 -0.8467454 0.337985 -0.5891959 -0.742263 0.3192085 -0.3243713 -0.9109825 0.2547432 -0.358972 -0.8980734 0.2541719 -0.2406125 -0.9444125 0.2240332 -0.2731139 -0.9363354 0.2206465 -0.186334 -0.9621621 0.1988059 -0.2148301 -0.9553733 0.2027558 -0.1350432 -0.9739388 0.1822267 -0.1597803 -0.9714511 0.1753656 -0.05350494 -0.987509 0.1482001 -0.06948167 -0.9879521 0.1382865 0.0270214 -0.9931861 0.1133638 0.02125698 -0.9947158 0.1004424 0.06986051 -0.9936832 0.0878247 0.06914424 -0.993783 0.08726137 0.04655253 -0.9945821 0.09294867 0.006498098 -0.9977247 0.06710702 -0.03990721 -0.9960644 0.07913959 -0.1034513 -0.9927808 0.06069839 -0.1280611 -0.9895023 0.06697553 -0.2124552 -0.9756208 0.0550177 -0.1971818 -0.9790301 0.05118113 -0.2766658 -0.9589309 0.0625118 -0.2393656 -0.9694721 0.05317872 -0.3482791 -0.9360579 0.04997336 -0.610255 -0.7824289 0.1240725 -0.4873394 -0.8668923 0.1048722 -0.5433759 -0.83551 -0.08164399 -0.8813672 -0.4394351 0.1734614 -0.686053 -0.6697136 0.2842797 -0.772933 -0.5889205 0.2361088 -0.5771055 -0.8134562 0.07237601 -0.5159052 -0.8526722 0.08241319 -0.1980252 -0.9783122 -0.06075769 -0.3246629 -0.9455364 0.02355933 -0.4925406 -0.8693216 0.04103481 -0.02434349 -0.9325163 -0.3603066 -0.7958595 -0.585406 -0.1546204 -0.7781559 -0.6230111 -0.07956641 -0.7449468 -0.6311907 -0.2159924 -0.7187736 -0.6839755 -0.1246677 -0.6330143 -0.7523767 -0.1822698 -0.6315829 -0.7527951 -0.1854793 -0.5739958 -0.8057637 -0.1458561 -0.4999065 -0.8536992 -0.1459147 -0.5043478 -0.8500171 -0.1520006 -0.2904151 -0.9051816 -0.3103312 -0.1749494 -0.9343329 -0.3105073 -0.2080397 -0.8952586 -0.3939945 -0.1339462 -0.9667615 -0.2177857 -0.4215431 -0.8938442 -0.1527882 -0.3580104 -0.9150829 -0.1856124 -0.28595 -0.9489253 -0.1333165 -0.1988654 -0.9709112 -0.1333572 -0.1600152 -0.9813061 -0.1069277 -0.03374022 -0.9937191 -0.1066971 0.007511317 -0.9977998 -0.06587308 -0.7754607 -0.6139522 -0.1473895 -0.7140328 -0.6842824 -0.1480365 -0.7711497 -0.6136022 -0.1697662 -0.7705816 -0.6247427 -0.1260989 -0.798861 -0.5852226 -0.1390523 -0.7989975 -0.5850678 -0.1389207 0.3980675 -0.05230075 -0.9158641 0.2244136 -0.02215719 -0.9742422 0.4211698 -0.02973401 -0.9064944 0.3856073 -0.1585512 -0.9089381 0.4604077 -0.1287142 -0.8783266 0.36541 -0.272864 -0.8899556 0.4769951 -0.2501471 -0.842557 0.3149408 -0.4033758 -0.8591277 0.5042008 -0.4463599 -0.7392865 0.2320432 -0.01319503 -0.972616 0.2191447 -0.06135362 -0.9737615 0.2454227 -0.05027782 -0.9681116 0.2120012 -0.1013086 -0.9720042 0.2527664 -0.09408557 -0.962942 0.2009334 -0.1443429 -0.9689123 0.2707306 -0.1687875 -0.9477425 0.4083604 -0.5050324 -0.7603843 0.2536989 -0.1783428 -0.9507002 0.4068366 -0.5055003 -0.76089 0.4342552 -0.4897966 -0.7559906 0.4282556 -0.4760968 -0.7680683 0.4872701 -0.4483557 -0.7493632 0.4836936 -0.4341853 -0.7599498 0.5235595 -0.4192143 -0.7417175 0.5221799 -0.4163856 -0.7442791 0.5627016 -0.4011141 -0.722824 0.5618394 -0.388288 -0.7304581 0.6297904 -0.3693638 -0.6833261 0.630347 -0.3597141 -0.6879451 0.2575307 -0.177429 -0.9498405 0.3022862 -0.1519885 -0.9410221 0.3191522 -0.1820634 -0.930051 0.4119585 -0.138477 -0.9006189 0.4218538 -0.1627105 -0.8919444 0.4787771 -0.1412369 -0.8665014 0.4815015 -0.1455746 -0.8642711 0.5381957 -0.1243726 -0.8335928 0.5423461 -0.141808 -0.828101 0.6348116 -0.1160871 -0.7638967 0.6362276 -0.1279469 -0.7608181 0.9765918 -0.06103271 -0.2062609 0.97659 -0.06131142 -0.2061868 0.9909959 -0.05899065 -0.1201975 0.9908995 -0.06079542 -0.1200932 0.9027555 -0.3299362 -0.2759976 0.8828941 -0.3267259 -0.3372659 0.9306742 -0.23938 -0.2766637 0.9278112 -0.1872189 -0.3226695 0.9528118 -0.163981 -0.2554603 0.9150665 -0.1786761 -0.3615636 0.9208353 -0.1805773 -0.3456219 0.99271 -0.07520902 0.09418261 0.9843629 -0.1472544 0.09667545 0.9971743 -0.07308298 -0.01738935 0.9935718 -0.1126489 0.01119244 0.9934219 -0.04787003 -0.1040272 0.9910749 -0.1021509 -0.08565026 0.9760302 -0.05334728 -0.2109957 0.9794747 -0.09690195 -0.1767468 0.9606534 -0.06969422 -0.268864 0.9568706 -0.05808782 -0.2846482 0.901422 -0.3333776 -0.2762209 0.8932113 -0.3331939 -0.3019195 0.8885295 -0.3517692 -0.294574 0.8813098 -0.3492425 -0.3183127 0.8737853 -0.3806564 -0.3026551 0.8765276 -0.3846798 -0.2893456 0.8743078 -0.3980617 -0.2777277 0.8785967 -0.4124119 -0.2407997 0.8836489 -0.3982475 -0.2460966 0.8827104 -0.4298982 -0.1897628 0.8935547 -0.3947193 -0.2139085 0.8870092 -0.4374417 -0.1478498 0.9291362 -0.3430483 -0.1379279 0.5486647 -0.7423371 -0.3845813 0.6026875 -0.6989208 -0.3850684 0.6006104 -0.708055 -0.371383 0.591982 -0.7125889 -0.3765295 0.5955348 -0.7042248 -0.3865304 0.5997136 -0.7019712 -0.3841615 0.6012625 -0.704042 -0.3778997 0.5974229 -0.7096573 -0.3734601 0.5985676 -0.7083408 -0.3741258 0.5973961 -0.7116265 -0.3697372 0.5970338 -0.7121319 -0.3693494 0.5878415 -0.7039915 -0.3985455 0.5858414 -0.7056321 -0.398589 0.5994088 -0.697642 -0.3924346 0.5856766 -0.7068371 -0.3966918 0.5893235 -0.7016428 -0.4004938 0.5794682 -0.7080888 -0.4035183 0.5864874 -0.7212349 -0.3685823 0.5743057 -0.7081019 -0.4108098 0.5733081 -0.7093515 -0.4100468 0.5561451 -0.7291113 -0.3988725 0.5670387 -0.7237485 -0.3932623 0.561192 -0.7237722 -0.4015191 0.5739863 -0.7150986 -0.3989659 0.5660066 -0.7160833 -0.4084866 0.5692864 -0.7143258 -0.4070034 0.5528985 -0.7390012 -0.3849421 0.5499195 -0.741053 -0.3852648 0.5596397 -0.7381823 -0.3766834 0.5563038 -0.7405279 -0.3770207 0.5625113 -0.7377813 -0.3731752 0.5630835 -0.7374771 -0.3729135 0.5638267 -0.7370104 -0.3727132 0.5621513 -0.7377154 -0.3738476 0.5625422 -0.7328781 -0.3826698 0.5707581 -0.7253182 -0.3849009 0.5770871 -0.7111132 -0.4016073 0.5738012 -0.7136835 -0.4017564 0.5733572 -0.7138749 -0.4020498 0.5496963 -0.7321819 -0.4021737 0.5643931 -0.7241747 -0.3962721 0.5880371 -0.7043023 -0.3977069 0.5900233 -0.6991718 -0.4037714 0.5924111 -0.6940981 -0.4089953 0.5879855 -0.7121442 -0.383567 0.5934888 -0.7150868 -0.3693537 0.5934889 -0.7150868 -0.3693534 0.578086 -0.7066232 -0.4080445 0.5807717 -0.7040205 -0.4087291 0.5763008 -0.7123168 -0.4006024 0.5769066 -0.7114854 -0.4012073 0.5673549 -0.7297933 -0.3814581 0.5661884 -0.7355167 -0.3720833 0.5715324 -0.7322553 -0.3703415 0.5715317 -0.7322561 -0.3703413 0.5791269 -0.7269902 -0.368914 0.5751991 -0.7086108 -0.4086768 0.571659 -0.7101398 -0.4109838 0.5791261 -0.7269909 -0.3689136 0.5864863 -0.7212355 -0.3685826 0.5770865 -0.7111135 -0.401608 0.587224 -0.7021382 -0.4027034 0.5695441 -0.7018715 -0.4277802 0.4711142 -0.817605 -0.331019 0.4647511 -0.8199613 -0.3341705 0.4784049 -0.7738037 -0.4151589 0.5032728 -0.7718706 -0.3885 0.481324 -0.05076205 -0.8750718 0.5051303 -0.3273568 -0.7985494 0.5042011 -0.1786947 -0.8448962 0.5040868 -0.1853966 -0.8435193 0.50968 -0.1838349 -0.8404945 0.5137576 -0.1993678 -0.8344494 0.496692 -0.5330817 -0.6849241 0.4960733 -0.5353334 -0.683615 0.5246519 -0.5273191 -0.6683375 0.5260395 -0.5215383 -0.6717741 0.5433207 -0.5524324 -0.6321559 -0.6645199 -0.7380229 0.117199 -0.6725956 -0.7178065 0.1799138 -0.3524381 -0.9284271 0.1175189 -0.3608925 -0.9178454 0.165277 -0.691541 -0.7221506 0.01642209 -0.6446714 -0.7644456 -0.004667818 -0.1594095 -0.9871009 0.0148462 -0.1863017 -0.9822211 0.02309805 -0.1872022 -0.9822723 0.009826719 -0.2016851 -0.9793267 0.0155673 -0.2021384 -0.9793481 0.004172742 -0.2164644 -0.9762641 0.0071882 -0.2278186 -0.9732478 0.02979046 -0.1715167 -0.9809685 -0.09101021 -0.4538626 -0.88501 0.1037597 -0.4624069 -0.8858411 0.03827941 -0.5330648 -0.8439984 0.05923634 -0.5355638 -0.8441672 0.02351826 -0.5722218 -0.8191578 0.03927892 -0.57343 -0.8192017 0.009306073 -0.5189074 -0.854825 -0.003090441 -0.7113254 -0.6939368 0.1116599 -0.717705 -0.6938292 0.05916661 -0.8047934 -0.5872339 0.08639627 -0.8085665 -0.5874233 0.03397148 -0.849092 -0.5251273 0.05730807 -0.8509015 -0.5251681 0.0128616 -0.8868421 -0.461377 0.02534806 -0.6301245 -0.7673903 0.1185552 -0.633425 -0.7704757 0.07169389 -0.2254539 -0.9731204 0.04698288 -0.226144 -0.9735936 0.03121441 -0.04584175 -0.9971232 -0.06036609 -0.1222097 -0.9742281 -0.1895902 -0.1863654 -0.9632531 -0.1934207 -0.1676959 -0.9634283 -0.209007 -0.2449424 -0.946497 -0.2101117 -0.2458214 -0.9464771 -0.2091723 -0.3601655 -0.9040087 -0.2303241 -0.3645264 -0.9040934 -0.2230151 -0.4419972 -0.8808135 -0.1697233 -0.4425132 -0.8807845 -0.1685254 -0.5405564 -0.8321303 -0.1239275 -0.5436218 -0.832264 -0.1086825 -0.5842611 -0.8109243 -0.03226387 -0.07158446 -0.9957531 -0.05789244 -0.06168931 -0.9959022 -0.06613087 -0.09259724 -0.9938274 -0.06109821 -0.08764666 -0.9939447 -0.06627357 -0.1330834 -0.9891042 -0.06294304 -0.1304529 -0.9891592 -0.06742566 -0.1599873 -0.9861993 -0.04260462 -0.1567798 -0.9863771 -0.049802 -0.1933498 -0.9808022 -0.02535605 -0.1929192 -0.9808279 -0.02754873 -0.2078933 -0.9781436 0.003943502 -0.2079839 -0.9781198 0.004940867 -0.225821 -0.9735864 0.03368318 -0.5889259 -0.8060387 0.05888915 -0.6298418 -0.7765383 -0.01696115 -0.6266111 -0.7701926 0.1190053 0.1601983 -0.9802875 -0.1156424 0.4493815 -0.8389021 -0.3070827 0.469745 -0.8289528 -0.3036069 0.4788762 -0.826511 -0.2959009 0.4839058 -0.82586 -0.2894657 0.1506639 -0.9869806 -0.05630135 0.1998302 -0.973052 -0.1150552 0.222698 -0.9650602 -0.1380745 0.3964949 -0.8636482 -0.3112936 0.04414236 -0.9985767 -0.02993345 0.1701831 -0.9815289 -0.08740127 0.1550289 -0.9818172 -0.1095497 0.3495281 -0.9021294 -0.2529679 0.4105453 -0.8630135 -0.2943814 0.9308992 -0.3652167 -0.006599426 0.9227334 -0.3854373 -0.001135408 0.6579889 -0.7530139 -0.004573345 0.6480895 -0.7615632 -0.001219213 0.2371045 -0.9714822 -0.001975476 0.2328649 -0.9725088 -8.36184e-4 0.9024171 -0.430626 0.01430082 0.930916 -0.3652241 0.002645254 0.6251125 -0.7804773 0.009469926 0.6579915 -0.7530196 0.002981305 0.2231905 -0.9747671 0.003897726 0.2371031 -0.9714828 0.001884818 0.05597823 -0.5930368 -0.8032272 0.5541901 -0.4785522 -0.6810735 0.4347489 -0.5274583 -0.7299185 0.4265345 -0.5136904 -0.7444398 0.3064512 -0.5116793 -0.8026655 0.2926031 -0.5049105 -0.8120645 0.7234212 -0.427962 -0.5417661 0.6062472 -0.4857366 -0.6297018 0.563077 -0.4838677 -0.6699376 0.637747 -0.5497404 -0.5395038 0.7559628 -0.4569926 -0.4686984 0.7931143 -0.4574031 -0.4021846 0.874336 -0.3981048 -0.2775772 0.6495112 -0.7603204 0.006950855 0.9038229 -0.4240695 -0.05717742 0.7922277 -0.5246064 -0.3117107 0.8784421 -0.4328206 -0.2024995 0.8947361 -0.4309405 -0.1172078 0.9198226 -0.391219 -0.02956402 0.1339921 -0.9289684 -0.3450564 0.1416432 -0.8369863 -0.5285748 0.2739562 -0.9600625 0.05681788 0.2681924 -0.9629607 0.02792358 0.269966 -0.962566 0.0241881 0.2602607 -0.9655327 -0.003351688 0.2630388 -0.9647404 -0.009316265 0.2483897 -0.9680635 -0.03399413 0.2490075 -0.9676505 -0.04059225 0.2314803 -0.9708352 -0.06241732 0.2322844 -0.9700366 -0.0712248 0.210813 -0.9734481 -0.08920061 0.208965 -0.9731502 -0.09650075 0.185136 -0.976391 -0.1112892 0.1830396 -0.9758265 -0.1194114 0.1556069 -0.9792709 -0.1296726 0.1522434 -0.9791193 -0.1347131 0.09688037 -0.9844238 -0.1467105 0.1141539 -0.9868425 -0.1145021 0.2715433 -0.9606012 0.0592423 0.6545721 -0.755999 -9.21687e-4 0.6353642 -0.7658723 -0.09875279 0.6422345 -0.760893 -0.09261119 0.6055925 -0.7714686 -0.1951768 0.6166765 -0.7637473 -0.1907883 0.5607367 -0.7769546 -0.2862097 0.5716642 -0.7706189 -0.2816854 0.5010578 -0.7828751 -0.3688465 0.5151194 -0.7739515 -0.3683085 0.4284696 -0.7882416 -0.441689 0.4413158 -0.7815158 -0.4409915 0.3440281 -0.7942416 -0.5008244 0.3574422 -0.7857149 -0.5048636 0.2498667 -0.7997792 -0.5458203 0.2612181 -0.793904 -0.5490736 0.1050158 -0.8074403 -0.5805274 0.1875074 -0.5497989 -0.8139793 0.167225 -0.5766338 -0.7997058 -0.08599025 -0.8099537 -0.5801557 -0.8949463 -0.4451958 -0.02952742 -0.9017868 -0.4239242 -0.08407706 -0.8891054 -0.4414117 -0.1210265 -0.8587662 -0.4582411 -0.2292069 -0.8334464 -0.4870202 -0.2611101 -0.8144268 -0.4393367 -0.3790677 -0.7908276 -0.4559156 -0.408329 -0.724355 -0.473629 -0.5009844 -0.6925391 -0.5001436 -0.519852 -0.6353688 -0.4496763 -0.6277722 -0.5962965 -0.470292 -0.6505813 -0.5127093 -0.4755877 -0.7148046 -0.545837 -0.4519936 -0.7055239 -0.3776326 -0.5103014 -0.7726489 -0.4074731 -0.4786402 -0.7777336 -0.2456084 -0.4791347 -0.8426782 -0.2763097 -0.4593188 -0.8442034 -0.1003746 -0.5228831 -0.8464741 -0.1335471 -0.481541 -0.8661891 -0.1901883 -0.9810106 -0.03803449 -0.6358416 -0.7510655 0.1777814 -0.177031 -0.9813659 0.07470631 -0.1764684 -0.9829405 0.05183684 -0.180087 -0.9821577 0.05417567 -0.1717176 -0.9850023 0.01683956 -0.175624 -0.9842654 0.01944059 -0.1618818 -0.9866637 -0.01700508 -0.1685587 -0.9855719 -0.01536262 -0.147911 -0.9878128 -0.04846131 -0.1543258 -0.9869105 -0.04681098 -0.130226 -0.9886022 -0.07554358 -0.1383946 -0.9874312 -0.07633262 -0.1107493 -0.9889563 -0.09848928 -0.1170948 -0.9881696 -0.09904456 -0.08974432 -0.9892719 -0.1152698 -0.09488999 -0.9885098 -0.1176621 -0.0682128 -0.9895493 -0.1270403 -0.07034051 -0.9892764 -0.1280019 -0.04666537 -0.99005 -0.1327533 -0.0460487 -0.990159 -0.1321541 -0.08408451 -0.8110783 -0.5788626 -0.1800216 -0.8086032 -0.5601368 -0.1830677 -0.8099936 -0.5571325 -0.2731431 -0.8060985 -0.5249746 -0.2762326 -0.809002 -0.5188559 -0.3588854 -0.8062115 -0.4703447 -0.3622052 -0.8086231 -0.4636121 -0.4375739 -0.8040353 -0.4025623 -0.4388681 -0.8079153 -0.3932783 -0.5021975 -0.8039757 -0.3184664 -0.5033206 -0.8066701 -0.3097609 -0.5553086 -0.8005235 -0.2253769 -0.5533977 -0.8045246 -0.2156185 -0.5888808 -0.798834 -0.1228152 -0.5870637 -0.80144 -0.1142387 -0.6081926 -0.7935976 -0.01745504 -0.6033456 -0.7974271 -0.009169936 -0.5746459 -0.7841582 -0.2342605 -0.8853074 -0.3782451 0.2704836 -0.9023074 -0.4306209 0.02017581 -0.9309261 -0.3651354 -0.007265031 -0.2371203 -0.9714781 -0.002069652 -0.223977 -0.974585 -0.004301726 -0.6580307 -0.7529841 -0.003259181 -0.6270027 -0.7789472 -0.01043295 -0.9258067 -0.3779847 -0.003100633 -0.9039236 -0.4269546 -0.02513474 -0.2232296 -0.9747646 0.001658856 -0.2371205 -0.9714735 0.003626883 -0.6252088 -0.7804522 0.002894341 -0.6580125 -0.7529602 0.008390486 -0.9266926 -0.3758112 0.002632617 -0.9309358 -0.3651387 0.005711793 0.2152321 -0.9765612 -0.001881062 0.2163203 -0.9763169 -0.003290891 0.6058328 -0.7955827 -0.003892481 0.6084734 -0.7935329 -0.008123517 0.8841528 -0.4671719 -0.004925906 0.9039496 -0.4270653 0.02214503 0.8867707 -0.4622098 -1.22519e-4 0.8866904 -0.4622094 -0.0119493 0.5814775 -0.8132085 0.02399611 0.5262538 -0.8494327 0.03900235 0.1833483 -0.9828675 0.01884061 0.1836447 -0.9828811 0.01481556 0.2053322 -0.9786354 0.01056504 0.5110884 -0.8572107 0.06307619 0.5244403 -0.8492008 0.06181108 0.3752791 -0.9261814 0.03678989 0.1522716 -0.98808 0.02261352 0.2163535 -0.9763112 0.002784729 0.205531 -0.9786402 0.004521131 0.6085258 -0.7935125 0.005862891 0.5818777 -0.8131959 0.01144456 0.8600043 -0.5102264 0.007857799 0.8594132 -0.5103307 0.03116816 0.7972047 -0.6006537 0.06066191 0.797011 -0.6006475 0.06321489 0.6910218 -0.7159902 0.09923255 -0.9022244 -0.4301485 -0.03104048 -0.6253414 -0.7800929 -0.02008163 -0.2233009 -0.9747456 -0.002804815 -0.8962281 -0.4398267 -0.0576871 -0.8896288 -0.4403127 -0.1211838 -0.8837031 -0.4445322 -0.1464931 -0.8550474 -0.4418419 -0.2714217 -0.8403328 -0.4580496 -0.2898818 -0.7886742 -0.4609387 -0.4068518 -0.7779623 -0.4639453 -0.423709 -0.7083604 -0.4610187 -0.5344974 -0.6932243 -0.4730817 -0.5437223 -0.5944215 -0.4759853 -0.6481522 -0.5826917 -0.4791259 -0.6564365 -0.5380082 -0.4791914 -0.6934861 -0.5265063 -0.4819074 -0.7003973 -0.4073869 -0.4789977 -0.7775585 -0.3946813 -0.4876223 -0.7787498 -0.2721425 -0.4907132 -0.8277314 -0.2610371 -0.4924046 -0.8302996 -0.1331794 -0.4894086 -0.8618251 -0.1216244 -0.4974583 -0.8589196 -0.6193684 -0.7840689 -0.04023337 -0.6146484 -0.7844898 -0.08236056 -0.609607 -0.7861944 -0.1013799 -0.5920421 -0.7840263 -0.1865181 -0.5786434 -0.7906691 -0.2000361 -0.5419196 -0.7930096 -0.2783145 -0.5335096 -0.7942097 -0.2908582 -0.4880251 -0.7919296 -0.3669868 -0.4751714 -0.7968566 -0.3731377 -0.4069268 -0.79914 -0.4424771 -0.3978027 -0.8004055 -0.4484463 -0.3679928 -0.8004716 -0.4731034 -0.359131 -0.8015515 -0.4780588 -0.2794939 -0.7993412 -0.531918 -0.2693005 -0.8028515 -0.5318898 -0.1858179 -0.8052138 -0.5631185 -0.1774371 -0.8058879 -0.5648548 -0.09156095 -0.8036473 -0.5880203 -0.08261948 -0.8069121 -0.584865 -0.2213317 -0.9751328 -0.01132601 -0.2196568 -0.9752499 -0.0252695 -0.2177763 -0.9754323 -0.03324919 -0.2122251 -0.9751914 -0.06294602 -0.2074058 -0.9758177 -0.06901282 -0.1941096 -0.9762614 -0.09610021 -0.1907632 -0.9763751 -0.1014947 -0.1752853 -0.976109 -0.1283991 -0.1703466 -0.9765728 -0.1314826 -0.1460407 -0.976989 -0.1554498 -0.1423323 -0.9771125 -0.1580911 -0.1321772 -0.977144 -0.1664901 -0.1285693 -0.9772495 -0.1686816 -0.1009178 -0.9769694 -0.1880071 -0.09678244 -0.9773023 -0.1884502 -0.06748181 -0.977701 -0.1988644 -0.06403207 -0.9777705 -0.1996623 -0.03419798 -0.977479 -0.2082435 -0.03048503 -0.9777874 -0.2073705 -0.03223699 -0.9713535 -0.2354425 -0.1215318 -0.6644566 -0.7373788 -0.01565808 -0.7494575 -0.6618673 -0.102385 -0.8738136 -0.4753603 0.06651848 -0.9819644 -0.1769787 -0.08830094 -0.5641164 -0.8209603 -0.05897468 -0.6643311 -0.7451082 -0.06069749 -0.8347398 -0.5472893 -0.03875011 -0.8743809 -0.4836905 -0.02376532 -0.9811325 -0.1918703 -0.01525992 -0.9857819 -0.1673356 -0.03611022 -0.5004518 -0.865011 -0.02048444 -0.5643129 -0.8253068 -0.02490574 -0.8091353 -0.5870946 -0.01439642 -0.8349218 -0.5501802 -0.009961426 -0.97815 -0.2076617 -0.006143569 -0.9811915 -0.1929395 -0.07806801 -0.7641896 -0.6402497 8.3197e-5 -0.767534 -0.6410083 -0.04284745 -0.9724798 -0.2290137 -0.01117908 -0.973247 -0.2294895 -0.1151285 -0.7518322 -0.6492255 -0.03542029 -0.7648164 -0.6432738 -0.05676025 -0.9711192 -0.2317453 -0.02397203 -0.9728473 -0.2302032 0.2272251 -0.9735663 0.02318418 0.6378442 -0.7694705 0.03271299 0.2210637 -0.9737536 0.05417537 0.2243883 -0.9744803 0.006160259 0.2204469 -0.9747665 0.03511983 0.219693 -0.975015 -0.03287464 0.2142953 -0.9767299 -0.008722364 0.1981447 -0.9780089 -0.06509447 0.2016654 -0.9782236 -0.04909008 0.1840279 -0.978097 -0.09726262 0.185052 -0.9788897 -0.08677995 0.1604646 -0.9795532 -0.1213532 0.1622186 -0.9796023 -0.1185939 0.1399717 -0.9792767 -0.1463736 0.138536 -0.9789963 -0.1495792 0.1147107 -0.9792702 -0.1669472 0.1071469 -0.9790615 -0.1730844 0.08798974 -0.9787116 -0.1854226 0.07594585 -0.9772164 -0.1981934 0.05682688 -0.9772584 -0.2042959 0.03488981 -0.9764801 -0.212766 0.02156949 -0.9761785 -0.215894 -0.007224082 -0.9732481 -0.2296428 0.6205917 -0.7765656 0.1086827 0.6291091 -0.7772158 -0.01255434 0.6171637 -0.7846373 0.05876523 0.6127901 -0.781616 -0.1164685 0.5938749 -0.8027437 -0.05399316 0.5550157 -0.8075184 -0.1996792 0.5625103 -0.811134 -0.1601369 0.5153939 -0.8086417 -0.2836684 0.5155637 -0.8176084 -0.2563413 0.4535486 -0.8208898 -0.3470355 0.4575927 -0.8214901 -0.3402394 0.3982805 -0.8194365 -0.4121853 0.395618 -0.8164729 -0.4205455 0.3331578 -0.8186437 -0.4677909 0.3152755 -0.8168731 -0.483032 0.2615792 -0.8153131 -0.5165665 0.2365306 -0.8003798 -0.5508589 0.1820461 -0.8017474 -0.5692631 0.1307606 -0.7958425 -0.591216 0.08662009 -0.7946544 -0.6008507 0.02446895 -0.7668381 -0.6413741 0.6179802 -0.6732286 -0.4060342 0.6885281 -0.7158729 0.1159967 0.1524856 -0.9880822 0.0210185 0.2638772 -0.8540866 -0.4482244 0.3725982 -0.9262644 0.05661386 0.5108491 -0.8572207 0.06485414 0.018965 -0.9831894 0.1816019 0.6711779 -0.7320278 0.1168576 0.6809783 -0.7323036 -3.6079e-5 0.4258247 -0.8657969 0.2628102 0.3883188 -0.8356205 0.3885191 0.2562685 -0.9544718 0.1526766 0.007330834 -0.968608 0.2484852 -0.6767066 -0.7265428 0.1191805 -0.7684943 -0.638248 -0.04534453 -0.638627 -0.7003537 -0.3188422 -0.6339489 -0.7560902 -0.1625935 -0.5526149 -0.801725 -0.2277145 -0.4726163 -0.8405644 -0.2647363 -0.4007637 -0.8874854 -0.2275044 -0.3410339 -0.929247 -0.142113 -0.3138718 -0.9485526 -0.04162347 -0.2407941 -0.9522781 0.1875755 -0.1920987 -0.7885676 -0.584174 -0.7478212 -0.6412709 -0.1718583 -0.719215 -0.6936061 0.04050165 -0.6525929 -0.7217681 -0.2305936 -0.5920312 -0.8058153 0.01268315 -0.5491085 -0.7824217 -0.2937625 -0.1084786 -0.9223973 -0.3706963 -0.4996778 -0.8498122 -0.1677539 -0.1350413 -0.8389877 -0.5271278 -0.07125514 -0.9007953 -0.428358 -0.1324859 -0.8060815 -0.5767843 -0.04219156 -0.8769524 -0.4787217 -0.1136506 -0.7710523 -0.6265478 -0.00665158 -0.8306055 -0.5568218 -0.0980814 -0.7508072 -0.6531989 0.01511651 -0.7990724 -0.6010448 -0.06461191 -0.7293114 -0.6811242 0.03483253 -0.7543655 -0.65553 -0.03327733 -0.7247868 -0.6881691 0.05207973 -0.6543642 -0.7543841 -0.06356632 -0.7184662 -0.6926513 -0.007766485 -0.8244827 -0.5658339 -0.02606099 -0.9082962 -0.4175151 -0.5091732 -0.8066548 -0.3000848 -0.4381506 -0.8781142 -0.1921972 -0.4701994 -0.8293922 -0.3016971 -0.3738997 -0.905716 -0.1996939 -0.4060103 -0.8613671 -0.3052911 -0.2921403 -0.9274923 -0.233264 -0.3346858 -0.8952884 -0.294014 -0.2107847 -0.9479801 -0.238545 -0.2421607 -0.9269345 -0.2866193 -0.129698 -0.9571997 -0.2587419 -0.1516046 -0.9499541 -0.273136 -0.1160676 -0.9567129 -0.2668874 -0.06080144 -0.982827 -0.174225 0.8172025 -0.5499961 0.1722924 0.8126354 -0.3043508 0.4969851 0.6726409 -0.008575022 0.7399194 0.8493987 -0.4880203 0.2008933 0.8792757 -0.4436902 0.173243 0.9005166 -0.394633 0.1825785 0.9179781 -0.3607295 0.164896 0.9410114 -0.28105 0.1884372 0.9431403 -0.2770389 0.1836732 0.9675221 -0.1992859 0.1555193 0.9712525 -0.163037 0.173458 0.9867988 -0.06724214 0.147332 0.984186 -0.04056847 0.1724299 0.8224926 -0.2595214 0.506117 0.8402294 -0.2328525 0.4896882 0.8483468 -0.1983022 0.4909014 0.8666966 -0.1619744 0.4718067 0.8640791 -0.1244578 0.4877271 0.8793711 -0.07537126 0.4701337 0.8766522 -0.04837781 0.4786862 0.8863174 0.008708536 0.4629966 0.8780322 0.02978605 0.4776738 0.6736263 0.004765868 0.7390568 0.6778556 0.01120328 0.7351098 0.6795354 0.02331173 0.7332723 0.6836732 0.03132104 0.7291159 0.6803465 0.04686278 0.7313908 0.6835004 0.0571739 0.7277076 0.680678 0.07094955 0.729139 0.6828263 0.08314818 0.7258338 0.6753069 0.0967825 0.7311593 0.7506365 -0.2243925 0.6214441 0.7965435 -0.5734424 0.1915265 0.6478819 0.03598308 0.7608904 0.6479755 0.04026418 0.7605963 0.6470218 0.03949987 0.7614477 0.64663 0.04653972 0.7613827 0.6435614 0.04475057 0.7640852 0.6440796 0.05345177 0.7630888 0.6388699 0.05148333 0.7675904 0.6411761 0.05937659 0.7650933 0.633992 0.05763942 0.7711887 0.6375299 0.07043713 0.7671991 0.6289302 0.0698418 0.7743185 0.6351836 0.08544224 0.7676207 0.627516 0.086084 0.7738303 0.6352384 0.08782988 0.7673058 0.6273332 0.08864343 0.7736896 0.6374897 0.1091691 0.7626854 0.6340389 0.1100196 0.7654349 0.6472753 0.1316761 0.750797 0.6520764 0.1298871 0.7469443 0.6661622 0.1498644 0.7305948 0.6833104 0.1415648 0.7162725 0.6941418 0.1557754 0.7027812 0.7500721 -0.2273941 0.6210346 0.7327495 -0.2410702 0.6363673 0.7320752 -0.2461618 0.6351932 0.7040836 -0.2624115 0.6598534 0.7027332 -0.2678524 0.6591064 0.6743359 -0.278647 0.6838326 0.6726052 -0.2822826 0.6840459 0.6418734 -0.289637 0.7100063 0.6403228 -0.2928695 0.7100805 0.6039916 -0.2953748 0.740235 0.6037645 -0.2957416 0.7402738 0.5840713 -0.2941306 0.7565369 0.5847672 -0.2939801 0.7560575 0.5648552 -0.2918558 0.7718543 0.5677316 -0.2879897 0.7711956 0.5406338 -0.2812606 0.7928478 0.5466774 -0.2745096 0.7910678 0.5325796 -0.2692527 0.8024102 0.5402003 -0.2618821 0.7997508 0.5425718 -0.2630254 0.7977679 0.5478975 -0.2583865 0.7956411 0.671085 -0.0102517 0.7413096 0.6712231 0.058021 0.7389812 0.7618578 -0.3571657 0.5403754 0.8128451 -0.1623387 0.5594006 0.7907314 -0.4529884 0.4117588 0.7797834 -0.4629662 0.4214264 0.7760156 -0.471922 0.4184369 0.7436279 -0.4972354 0.4469616 0.7378712 -0.5118681 0.4399287 0.6875103 -0.5410695 0.4843279 0.6789762 -0.5574455 0.4777509 0.6302052 -0.5761788 0.5204416 0.6205855 -0.5887271 0.5179519 0.5692342 -0.6008034 0.5612555 0.5568237 -0.6163247 0.5568584 0.4966161 -0.620481 0.6069399 0.4839791 -0.6332628 0.6039392 0.4541828 -0.6311278 0.6288051 0.4475851 -0.6321755 0.6324728 0.4174561 -0.6286134 0.6561827 0.4061585 -0.6382372 0.6539791 0.3583215 -0.6263791 0.6922824 0.3500149 -0.6322743 0.691172 0.318017 -0.6203781 0.7169353 0.311966 -0.624036 0.7164191 0.2979472 -0.6172914 0.7281338 0.2914422 -0.6207022 0.7278669 0.7618223 -0.6291971 0.1540707 0.7326815 -0.656259 0.1802836 0.7230615 -0.6686282 0.1735473 0.6789389 -0.70279 0.2124341 0.6633798 -0.7218296 0.1972036 0.5961804 -0.7607671 0.2565197 0.5755324 -0.7815168 0.2408193 0.5121846 -0.8061501 0.2962923 0.4912719 -0.8220463 0.2879092 0.4258213 -0.8371765 0.3432375 0.3980427 -0.8563681 0.3289313 0.3220897 -0.8616574 0.3921795 0.2930052 -0.8776246 0.3793719 0.2574998 -0.8755012 0.4088907 0.2434549 -0.8764596 0.4153894 0.2078419 -0.8717908 0.4436016 0.1785236 -0.8845739 0.4308809 0.1174635 -0.8694962 0.4797694 0.09146028 -0.8781998 0.4694682 0.04692816 -0.8616759 0.5052846 0.02430969 -0.8673924 0.4970307 -0.003562927 -0.8539916 0.5202748 -0.02399271 -0.8577412 0.5135216 0.4800447 -0.8166763 -0.3203076 -0.1474119 -0.9744399 0.169519 0.2540941 -0.9566485 -0.1423375 0.1559222 -0.9852454 -0.07056879 0.1250822 -0.9909368 -0.04897832 0.07565528 -0.9970177 -0.01523911 0.02385604 -0.999597 0.0153892 -0.02455151 -0.9988116 0.04210317 -0.07474625 -0.9951167 0.06446516 0.3890703 -0.8822844 -0.2649505 0.4089044 -0.8733134 -0.2648037 0.3902439 -0.8842024 -0.2567021 0.3843732 -0.8887397 -0.2497979 0.5044668 -0.7922894 -0.3432067 0.4171741 -0.8664038 -0.2744274 0.3928 -0.8805996 -0.2650519 0.5006181 -0.792237 -0.3489156 0.493773 -0.7994958 -0.3420449 0.5871016 -0.6630621 -0.4643927 0.5880448 -0.6615694 -0.4653271 0.4582635 -0.8267763 -0.3262444 0.5443659 -0.7553464 -0.3648529 0.4729505 -0.8215934 -0.3182802 0.4626132 -0.8290584 -0.3140878 0.4735018 -0.8184033 -0.3255952 0.4523971 -0.8307587 -0.3243099 0.5455666 -0.7454754 -0.3829147 0.05968272 -0.9965519 -0.05764049 0.06377738 -0.9960757 -0.06136643 -0.09570479 -0.9927628 0.07254588 -0.007928729 -0.9991706 0.03994286 -0.002860069 -0.9998667 0.01608449 -0.01816517 -0.9995703 0.02300834 0.1554163 -0.9852104 0.07215511 -0.1588628 -0.9820414 0.1017714 -0.1481226 -0.9847133 0.09164977 0.2691593 -0.9415749 -0.2024602 0.2731021 -0.9400122 -0.2044323 0.2814388 -0.9400643 -0.1925396 0.2909352 -0.9360534 -0.1978905 0.3235772 -0.9335426 -0.1542597 0.4808895 -0.8166195 -0.3191834 0.557519 -0.8135827 -0.1650929 0.3908523 -0.839944 -0.3764687 0.3011346 -0.9408068 -0.155566 0.004426896 -0.9906461 -0.1363844 0.1652103 -0.9844767 -0.05925691 -0.1627114 -0.9841438 0.07061219 -0.1071172 -0.9913623 0.07567542 0.01029974 -0.9837164 -0.1794326 0.05709183 -0.6543345 -0.754047 0.03585916 -0.6188188 -0.7847149 0.03718113 -0.8252152 -0.5635935 0.04948282 -0.8564075 -0.5139239 0.02206152 -0.9094921 -0.4151354 0.01392692 -0.9853259 -0.1701151 0.009258449 -0.9821116 -0.1880724 0.01295322 -0.9837102 -0.1792945 0.02216154 -0.8428217 -0.5377365 0.03400814 -0.8565964 -0.5148653 0.03090929 -0.5839945 -0.811169 0.05217373 -0.6187987 -0.7838152 0.2234383 -0.9746624 -0.01042205 0.625187 -0.7795285 -0.03842759 0.9013495 -0.4295374 -0.05537861 0.2221631 -0.9750089 -0.001190066 0.2187051 -0.9752359 -0.03290903 0.2190494 -0.9754461 -0.02285444 0.2099766 -0.9751744 -0.07031893 0.2093005 -0.976108 -0.0583676 0.1886049 -0.9768625 -0.1008357 0.193013 -0.9770603 -0.08999562 0.1691926 -0.9768304 -0.1310589 0.172631 -0.9778428 -0.1184144 0.1395507 -0.9785909 -0.1512793 0.1474632 -0.9787915 -0.1422036 0.1281926 -0.9789414 -0.1588725 0.136694 -0.979134 -0.1503708 0.1002193 -0.9789428 -0.1778404 0.1079612 -0.9799229 -0.167617 0.06668978 -0.9806119 -0.1842629 0.07676106 -0.9807937 -0.1793087 0.03552651 -0.9806191 -0.1926761 0.04492872 -0.9814667 -0.1862918 0.00903362 -0.9820832 -0.1882314 0.0184102 -0.9820664 -0.1876344 0.6210052 -0.7836488 -0.01572436 0.6119221 -0.7842821 -0.1022403 0.6120714 -0.7869891 -0.07756859 0.5849343 -0.7840145 -0.2077811 0.580733 -0.7945815 -0.1771708 0.5258896 -0.7979464 -0.2944857 0.5360167 -0.8007177 -0.2674651 0.4689816 -0.7977801 -0.3789502 0.4752264 -0.8092554 -0.3453488 0.3861212 -0.8126008 -0.4365667 0.4051184 -0.8154064 -0.4135114 0.3539057 -0.8155552 -0.4578434 0.3743256 -0.8182985 -0.4361971 0.2733042 -0.8155818 -0.5100308 0.2913795 -0.8266564 -0.481391 0.1792216 -0.8298192 -0.5284695 0.2038227 -0.8323441 -0.5154219 0.0902304 -0.829876 -0.5506039 0.1135305 -0.8394532 -0.5314408 0.01558798 -0.8426544 -0.5382293 0.03833204 -0.8427278 -0.5369735 0.8978212 -0.4396745 -0.02456849 0.8855454 -0.4403946 -0.1478579 0.8871292 -0.4470728 -0.1145773 0.8445314 -0.4434866 -0.3001444 0.8439566 -0.4693253 -0.2597519 0.7686113 -0.4734464 -0.4302155 0.783511 -0.4803676 -0.3941543 0.6837113 -0.4765406 -0.5526735 0.6966668 -0.5049086 -0.5096299 0.570333 -0.5092576 -0.6444976 0.5969029 -0.5164047 -0.6140304 0.5238654 -0.5165394 -0.6773125 0.5522782 -0.5235111 -0.6487873 0.4034548 -0.5196213 -0.7531387 0.4306455 -0.547393 -0.7175692 0.2681982 -0.551819 -0.7896616 0.3017467 -0.5583504 -0.7727832 0.1345722 -0.5545547 -0.8211939 0.1671978 -0.5788317 -0.7981221 0.02379167 -0.5835732 -0.811712 0.05495667 -0.5839151 -0.8099524 -0.1794641 -0.9803661 0.08170133 -0.1816434 -0.9799708 0.0816276 -0.1798061 -0.9802853 0.08191889 -0.1776635 -0.9806084 0.08272176 -0.1776768 -0.9806025 0.08276432 -0.1882648 -0.9791223 0.07665526 -0.1935649 -0.9777861 0.08041822 -0.1852478 -0.9794207 0.08011615 -0.1826309 -0.9618955 0.2034779 -0.1821179 -0.9620468 0.2032217 -0.1983154 -0.968643 0.1496729 -0.190733 -0.9703633 0.1483775 -0.429485 -0.9030126 0.01053804 0.0543363 -0.9973536 -0.04830533 -0.1194864 -0.9926846 0.01732939 -0.434544 -0.9005592 0.01283818 -0.6550714 -0.7548817 -0.03217178 -0.7036252 -0.7020194 0.1099114 -0.700735 -0.7110172 0.05852514 -0.6589068 -0.7511487 0.04021853 -0.6667253 -0.744857 -0.02579426 -0.6259372 -0.7780501 -0.05329871 -0.6195456 -0.7784986 -0.1005152 -0.5115782 -0.8516669 -0.1138047 -0.5363098 -0.835378 -0.1204807 -0.4755139 -0.85931 -0.1883422 -0.449834 -0.8749021 -0.1794315 -0.3906281 -0.8999614 -0.1935957 -0.3251424 -0.9315296 -0.1628963 -0.1581149 -0.9789942 -0.1287251 -0.1587313 -0.9625393 -0.2198244 -0.1563214 -0.9616979 -0.2251684 -0.1331841 -0.9683598 -0.2110483 -0.1640505 -0.9654141 -0.2026403 -0.1605808 -0.970395 -0.1804093 -0.143997 -0.9738617 -0.1756658 -0.1313447 -0.9842182 0.1185879 -0.2090384 -0.9752935 0.07145428 -0.3117098 -0.9303886 -0.1929103 -0.2189584 -0.9622804 -0.1614737 -0.2530596 -0.9375368 -0.2387167 -0.2839727 -0.9344933 -0.214667 -0.1814803 -0.9693548 -0.1655789 -0.1055474 -0.9725727 -0.2072732 -0.161785 -0.9613898 -0.2226104 -0.1555487 -0.9615559 -0.2263071 -0.2372792 -0.9697716 0.05693662 -0.243092 -0.9681808 0.05943477 -0.2676976 -0.9620547 0.05280917 -0.275644 -0.9595247 0.05773091 -0.3047437 -0.95112 0.05002307 -0.3139032 -0.9476166 0.05905604 -0.3359913 -0.9398469 0.06162458 -0.3445704 -0.9358869 0.07339632 -0.3664193 -0.9272592 0.07698917 -0.3743642 -0.9223906 0.09511661 -0.3877686 -0.916027 0.1026176 -0.3937383 -0.910511 0.126254 -0.4041743 -0.904931 0.1332034 -0.4040374 -0.8376278 0.367605 -0.3529986 -0.9213933 0.1625622 -0.08357071 -0.920984 -0.380532 0.34739 -0.7995646 -0.489915 0.2421392 -0.7927119 -0.5594431 0.2406623 -0.7877762 -0.5670014 0.1468238 -0.7679641 -0.6234373 0.1283258 -0.7559916 -0.6418796 0.02801084 -0.7581173 -0.6515164 0.6747094 -0.7365939 0.04686719 0.6380489 -0.7668787 -0.06921595 0.6172223 -0.7860436 -0.0342378 0.6120108 -0.7690598 -0.1843636 0.6113728 -0.7706897 -0.1796131 0.5194563 -0.8143575 -0.2588186 0.5212292 -0.8042641 -0.285446 0.4752708 -0.8053017 -0.3544104 0.4519473 -0.7942504 -0.406091 0.3915789 -0.8204653 -0.4165365 0.3390665 -0.789113 -0.5121862 0.6867473 -0.7201374 0.09889578 0.6930369 -0.7169822 0.0750761 0.3980094 -0.9112002 0.1063138 0.01470154 -0.738402 -0.6742006 -0.08582752 -0.9188404 -0.3851833 0.01220846 -0.9351834 -0.3539535 -0.008806049 -0.9375227 -0.3478127 0.08403199 -0.948963 -0.3039867 0.06669825 -0.9524209 -0.2973984 0.1431481 -0.9596357 -0.2420909 0.1363 -0.9606087 -0.2421848 0.2009482 -0.962507 -0.1822097 0.2027386 -0.9621053 -0.1823472 0.2534838 -0.9605619 -0.1143103 0.2632595 -0.9582522 -0.1115668 0.3008258 -0.9526669 -0.04392659 0.321574 -0.9461086 -0.03832489 0.3454129 -0.9378501 0.03357255 0.3660497 -0.9293882 0.04738372 0.3797147 -0.9159489 0.1298252 0.01891142 -0.9872981 0.15775 0.008083641 -0.9856725 0.1684764 0.001968681 -0.9912127 0.1322638 -0.005707621 -0.9896715 0.1432405 -0.01832044 -0.994331 0.1047403 -0.02534717 -0.9930049 0.1153203 -0.0439617 -0.9956685 0.08192563 -0.045529 -0.9950591 0.08822929 -0.06750637 -0.9959987 0.05856251 -0.06816273 -0.9958087 0.06098455 -0.09219628 -0.9949839 0.03882098 -0.09253793 -0.9950475 0.03629446 -0.1159309 -0.9930705 0.01926225 -0.1165726 -0.9931289 0.01028466 -0.1400266 -0.9901475 -6.80514e-4 -0.1447384 -0.9894164 -0.01030457 -0.1725301 -0.9848169 -0.01921468 -0.1738106 -0.9845283 -0.02222973 -0.1951766 -0.9804493 -0.02500641 -0.1940818 -0.9806813 -0.02442657 -0.1487146 -0.9103485 -0.3861992 -0.1540654 -0.9084115 -0.3886546 -0.08261924 -0.7205025 -0.6885132 -0.06835198 -0.7247868 -0.6855742 -0.2016932 -0.9764649 -0.07639414 -0.03990167 -0.999069 -0.01640218 -0.2905555 -0.8551571 -0.4292832 -0.1808438 -0.9037784 -0.3879179 -0.1375149 -0.7639838 -0.6304114 -0.212894 -0.7089326 -0.672377 -0.09467607 -0.6431463 -0.759868 -0.08696269 -0.5464808 -0.8329443 -0.03591012 -0.4956717 -0.8677673 -0.03881072 -0.4879217 -0.8720242 -0.03268837 -0.8409174 -0.5401756 -0.05253666 -0.8122172 -0.5809847 -0.1204952 -0.986612 -0.1098994 -0.04741501 -0.9928056 -0.1099499 -0.05641639 -0.9896255 -0.1321306 -0.069691 -0.5755622 -0.8147829 -0.09931182 -0.8356769 -0.540168 -0.1023659 -0.8410111 -0.5312454 -0.1170201 -0.9886225 -0.09450948 -0.1866721 -0.977862 -0.09454864 -0.1197105 -0.6383593 -0.7603728 -0.1202399 -0.6364635 -0.7618771 -0.143153 -0.7628924 -0.630478 -0.1437826 -0.8347696 -0.5314944 -0.1678462 -0.8862163 -0.4317967 -0.1827179 -0.9801944 -0.07637476 -0.1240561 -0.9267998 -0.3544749 0.04987913 -0.6192193 -0.7836323 0.05373072 -0.6288086 -0.7757015 0.05211156 -0.8010028 -0.5963882 0.08308649 -0.8604794 -0.5026649 0.07117152 -0.7125701 -0.6979818 0.06169557 -0.6604179 -0.7483595 0.05284404 -0.6344189 -0.7711811 0.05598258 -0.6274243 -0.7766626 0.0525012 -0.6243186 -0.7794036 0.09775292 -0.9930123 -0.06611472 0.09736853 -0.9040432 -0.4162034 0.08949571 -0.9892044 -0.1160402 0.09875971 -0.9883213 -0.11605 0.09909272 -0.9884667 -0.1145172 0.09346318 -0.9337813 -0.3454233 0.09164458 -0.8596101 -0.5026647 0.08457791 -0.8440489 -0.5295547 0.05924546 -0.5927082 -0.8032354 -0.04170966 -0.9488953 -0.3128226 0.1968728 -0.9660453 -0.1673251 0.02018666 -0.981404 -0.1908894 0.09996086 -0.9715383 -0.2147588 -0.1429396 -0.9704924 -0.1941983 -0.1209514 -0.9902681 -0.06884747 -0.5329518 -0.3391511 0.7752026 -0.05702596 -0.9537601 -0.2951096 -0.0913096 -0.9647716 -0.2467352 -0.4037955 -0.9022307 0.1514233 -0.1584253 -0.9703466 -0.1825618 -0.1499335 -0.9673553 -0.2043128 0.07980448 -0.9967952 0.005553126 0.08854359 -0.9945746 -0.05460214 0.1109175 -0.9869675 -0.1165877 0.1285107 -0.9718158 -0.1976342 0.07575839 -0.9906069 -0.1138375 0.08520984 -0.986572 -0.1393385 0.02672082 -0.9939936 -0.1061266 0.00806266 -0.9967104 -0.08064395 -0.02302521 -0.9968315 -0.07613623 -0.08458405 -0.824335 0.5597475 -0.08407878 -0.9963282 0.01615035 -0.05472439 -0.9774358 -0.2040212 -0.04643434 -0.9617152 -0.2700883 -0.06818246 -0.9812203 -0.1804384 -0.05214041 -0.9658377 -0.2538487 -0.0906428 -0.9829616 -0.1599076 -0.06613153 -0.9717658 -0.2264901 -0.1254359 -0.9793882 -0.1583182 -0.09809029 -0.9756979 -0.1959385 -0.1516325 -0.9738568 -0.1691467 0.5641077 -0.7052022 -0.4295026 0.5608991 -0.7068969 -0.4309166 0.5490154 -0.7288441 -0.4091069 0.5405393 -0.732045 -0.4146413 0.5104181 -0.780897 -0.3601016 0.4949522 -0.7859432 -0.3705614 0.4470307 -0.8460283 -0.2905164 0.4222182 -0.8524238 -0.3083921 0.1775825 -0.980561 -0.08345502 0.2817424 -0.944305 -0.1700275 0.3092076 -0.9332963 -0.1826168 0.3164988 -0.9302155 -0.1858157 0.3267489 -0.928277 -0.1775869 -0.264355 -0.9638364 0.03370445 -0.2550344 -0.9662016 0.03757697 -0.2550318 -0.9662026 0.03756767 -0.255013 -0.9662079 0.03755944 -0.2549836 -0.9662132 0.03762269 -0.2842455 -0.9583278 0.02850598 -0.09189188 -0.9952856 0.03102284 -0.294457 -0.9556425 -0.00652486 -0.06280875 -0.9979977 -0.007471919 -0.1805008 -0.9834892 -0.01297867 -0.04163759 -0.9990497 -0.01288634 -0.1229861 -0.991932 -0.03074955 0.008771538 -0.9995762 -0.02775943 -0.05344444 -0.9965266 -0.06386435 0.0607993 -0.9966953 -0.05387133 0.005635738 -0.9973275 -0.07284271 0.1042201 -0.9927331 -0.06016105 0.07437211 -0.9914013 -0.1076682 0.1493276 -0.9854781 -0.08083456 0.1234947 -0.987587 -0.09706294 0.1639434 -0.9832594 -0.07952153 0.155252 -0.9825568 -0.1023665 -0.8200134 4.96672e-4 0.5723441 -0.8200123 0 0.572346 -0.8200126 -6.78453e-5 0.5723454 -0.8200114 -3.85576e-4 0.5723472 -0.9746257 -0.1152074 -0.1919174 -0.9706814 -0.0065701 -0.2402802 -0.9635841 0.02166056 -0.2665266 -0.9641065 -0.005109906 -0.2654668 -0.9631738 0 -0.2688797 -0.9622853 -0.2017166 -0.1825304 -0.978397 0.2005568 -0.05016267 -0.9973111 0 -0.07328432 -1 -2.18244e-5 0 0.03452783 -0.98903 0.1436235 0.0666278 -0.9870961 0.1456091 0.002521395 -0.8520433 0.5234653 0.05668866 -0.8486225 0.5259528 -0.03073191 -0.5756037 0.8171511 0.02171099 -0.5722503 0.8197916 -0.04336184 -0.204186 0.9779714 -0.01163709 -0.2014374 0.9794323 0.07376158 -0.9867925 0.1442213 0.09042179 -0.9853108 0.1448675 0.04683709 -0.850264 0.5242685 0.09254842 -0.8458805 0.5252819 0.00449264 -0.5752125 0.8179917 0.06253051 -0.569715 0.8194601 -0.02181577 -0.2050581 0.9785067 0.02303111 -0.1999039 0.9795449 -0.9205082 0.1324363 0.367594 -0.9022478 -0.1924964 0.3858681 -0.9785346 -0.1538932 0.1370657 -0.978088 -0.2056198 0.03262591 -0.9331281 -0.3527042 0.06979888 -0.9480198 -0.3147083 0.04708808 -0.960929 -0.2767165 0.006588578 -0.9191753 -0.3865672 0.0753836 -0.9175078 -0.3974131 -0.01556742 -0.9128707 -0.0212028 0.407698 -0.9110608 -0.02736812 0.4113629 -0.8962848 -0.05301499 0.440299 -0.8975509 -0.0495451 0.4381184 -0.8505843 -0.05582153 0.5228675 -0.8404155 -0.07413452 0.5368481 -0.7723993 -0.08301597 0.6296886 -0.7610073 -0.09682208 0.6414777 -0.6784982 -0.1144972 0.7256243 -0.6650491 -0.1260493 0.7360851 -0.5645774 -0.1406011 0.8133165 -0.5589493 -0.1439329 0.8166145 -0.4607294 -0.1684489 0.8714088 -0.4480991 -0.1740333 0.8768806 -0.3504985 -0.1793798 0.9192246 -0.2958464 -0.1936589 0.9353989 -0.2295669 -0.193869 0.9537892 -0.1265004 -0.2062854 0.9702804 -0.1163994 -0.2046498 0.9718898 -0.7900032 -0.4150657 0.4512377 -0.9469101 -0.1262064 0.2956914 -0.9436211 -0.1329033 0.3031765 -0.9286555 -0.1731094 0.3280735 -0.9199413 -0.1735353 0.3515588 -0.8779421 -0.2491124 0.4088531 -0.863834 -0.2510696 0.4367553 -0.8057239 -0.3223494 0.4968904 -0.786104 -0.3284109 0.5236285 -0.7098289 -0.3949463 0.5832328 -0.6843382 -0.401533 0.6086482 -0.6036785 -0.4515787 0.657 -0.5759385 -0.4611479 0.6750092 -0.4825874 -0.503259 0.7168263 -0.4586229 -0.5074756 0.729475 -0.3140524 -0.5480182 0.7752723 -0.3070822 -0.5487444 0.7775474 -0.1166941 -0.5726498 0.8114522 -0.1445249 -0.5739219 0.8060561 -0.9772099 -0.1618744 0.1373231 -0.959369 -0.222737 0.173204 -0.9653678 -0.2081779 0.1572482 -0.9354085 -0.2871149 0.2063395 -0.9424086 -0.2886922 0.1688876 -0.8755947 -0.4078769 0.2587864 -0.8874758 -0.4059363 0.21818 -0.7917375 -0.5229868 0.3156529 -0.8127409 -0.5131943 0.2758334 -0.681824 -0.6271391 0.3765803 -0.7147396 -0.6141263 0.3346585 -0.56259 -0.7100961 0.4233865 -0.6115457 -0.6893859 0.3882771 -0.4323534 -0.7706967 0.4680782 -0.4932084 -0.7550286 0.432062 -0.2584814 -0.8237478 0.5046058 -0.3327831 -0.8124281 0.4787653 -0.07079607 -0.84731 0.5263589 -0.1397498 -0.8475335 0.5120128 -0.8957418 -0.4441949 0.01837581 -0.8208537 -0.5674914 0.06444203 -0.8353745 -0.5496811 -4.85296e-4 -0.7242929 -0.680828 0.1089628 -0.7560594 -0.6544467 0.008597195 -0.5922131 -0.7948166 0.1324778 -0.6497285 -0.7595909 0.02956992 -0.4528838 -0.8806179 0.1393145 -0.5512431 -0.832246 0.05914312 -0.3238248 -0.932703 0.1587534 -0.4306077 -0.8988004 0.08206582 -0.1635273 -0.9735026 0.1598482 -0.275948 -0.9544612 0.1133866 -0.02024894 -0.9871451 0.1585386 -0.09426504 -0.9860332 0.1373047 0.02990776 -0.2003977 0.9792581 0.08438909 -0.5681681 0.8185742 0.1247101 -0.8425436 0.5239923 0.1440775 -0.9790275 0.1440375 0.03020828 -0.2002172 0.9792857 0.05940818 -0.1941672 0.9791679 0.05996298 -0.193548 0.9792567 0.09091341 -0.1808227 0.9793048 0.09161794 -0.1798502 0.9794183 0.1199323 -0.1628149 0.9793404 0.1205655 -0.1612485 0.9795218 0.1411855 -0.1428655 0.9796204 0.141956 -0.1412392 0.9797449 0.08573478 -0.5676672 0.8187818 0.1676216 -0.5502118 0.8180282 0.1698734 -0.548469 0.8187336 0.2567332 -0.5130074 0.8190919 0.2598164 -0.5100442 0.8199697 0.3386878 -0.46224 0.8195272 0.3418449 -0.4573126 0.8209795 0.3994186 -0.4065974 0.8216712 0.4030727 -0.4010542 0.8226106 0.1275662 -0.8418049 0.5244917 0.2474577 -0.8153305 0.523451 0.2527682 -0.8126145 0.5251342 0.3794422 -0.761391 0.5256496 0.3869174 -0.7561499 0.5277617 0.5007596 -0.6865543 0.5271462 0.5091538 -0.6776378 0.5306312 0.5919938 -0.6057876 0.5315682 0.6011758 -0.5946401 0.5338454 0.148855 -0.9781959 0.1448279 0.2858101 -0.9473357 0.144457 0.2949291 -0.9441304 0.1470869 0.438906 -0.8863789 0.1472892 0.4520174 -0.8792054 0.1505933 0.579851 -0.8007234 0.1503834 0.5953822 -0.7881861 0.1558299 0.6874579 -0.7092271 0.1562004 0.7039301 -0.6920602 0.1597973 0.003158211 -0.9999871 -0.003972828 0.02234339 -0.9989255 -0.04060488 0.1745483 -0.9629765 -0.2054488 0.4101545 -0.7495477 -0.5195686 0.3750178 -0.7631855 -0.5262221 0.4202133 -0.7634714 -0.4904407 0.4271922 -0.7966719 -0.4275754 0.4459732 -0.7964662 -0.4083499 0.442802 -0.8276168 -0.3449302 0.01693922 -0.9600697 -0.2792477 0.1551111 -0.9726727 -0.1727674 0.1534913 -0.9766889 -0.1500642 0.1619994 -0.9766032 -0.1414302 0.1571707 -0.9803026 -0.1196008 0.001584112 -0.9999673 -0.007935583 0.04399573 -0.9989687 0.01121968 0.01402962 -0.998445 -0.05395358 0.2964988 -0.9523511 0.07152664 0.08014416 -0.9324594 -0.3522734 0.6156021 -0.7817424 -0.09956353 0.1861187 -0.7403743 -0.6459147 0.002171099 -0.9999948 -0.002407968 0.02094274 -0.999765 0.00559163 0.01678401 -0.9996903 -0.01837676 0.1421767 -0.9891697 0.03645831 0.1098736 -0.9863443 -0.1226894 0.3552587 -0.9345811 -0.01869589 0.2525899 -0.9389784 -0.2334909 0.4566611 -0.6976115 -0.552086 0.3471106 -0.9114693 -0.2207668 0.3794094 -0.9079365 -0.1780446 0.3956262 -0.8952908 -0.2047789 0.459366 -0.8644271 -0.2043252 0.4486711 -0.8671807 -0.2160829 0.5347638 -0.8211526 -0.1993395 0.5218186 -0.8262599 -0.2121317 0.6066703 -0.7680695 -0.2049888 0.6062873 -0.7682582 -0.2054147 0.4230517 -0.6941869 -0.5823504 0.4717829 -0.676275 -0.5657501 0.4452041 -0.6732049 -0.5904139 0.4856549 -0.6516538 -0.582655 0.4709944 -0.6541615 -0.5918083 0.5011397 -0.6336885 -0.58932 0.4993097 -0.6340469 -0.5904867 0.5167077 -0.6183084 -0.5922061 0.5276666 -0.6129928 -0.5880543 0.533674 -0.6062853 -0.5895848 0.5588969 -0.5935736 -0.579055 0.6651729 -0.7162059 -0.2111734 0.6708451 -0.7097918 -0.2148549 0.6962043 -0.687423 -0.2067591 0.7303848 -0.6481993 -0.2153502 0.7544762 -0.6269592 -0.1941335 0.8008568 -0.5568808 -0.220255 0.9999971 -0.002075552 -0.001313745 0.9999921 -0.003954231 -6.07558e-4 0.9999858 -0.004997909 -0.001914024 0.9995111 -0.03068673 0.006011903 0.9989355 -0.03800261 -0.02614885 0.995212 -0.09731388 -0.009122133 0.9923153 -0.1124081 -0.05171811 0.9745575 -0.2230499 -0.02205538 0.9592037 -0.2543994 -0.123326 0.9286698 -0.3578295 -0.09762537 0.8983954 -0.4124081 -0.1510139 0.8979745 -0.4135737 -0.1503286 0.8568993 -0.4998527 -0.1259803 0.9999933 -0.001774609 -0.003213286 0.9999856 -0.00484997 -0.002310454 0.9999704 -0.00578624 -0.005079925 0.9992833 -0.03756409 0.004686236 0.9970169 -0.03979414 -0.06613576 0.9926214 -0.112488 -0.04526817 0.9821393 -0.1250858 -0.1405564 0.9610552 -0.2555338 -0.1052411 0.9042202 -0.2672492 -0.3331121 0.8685716 -0.3919085 -0.3033001 0.7884597 -0.4434456 -0.426248 0.7520574 -0.5208477 -0.4038902 0.5870541 -0.5494935 -0.594495 0.9854786 -0.1294218 -0.1099185 0.9876798 0.01975977 -0.1552358 0.9879246 0.01589566 -0.1541187 0.9893977 -0.02722609 -0.1426572 0.9815409 -0.124054 -0.1455616 0.9554803 -0.2212685 -0.1951865 0.917786 -0.3761367 0.127241 0.5702199 -0.5247607 -0.6320408 0.580452 -0.5602553 -0.5909227 0.6206939 -0.4990386 -0.6047309 0.6208692 -0.6000827 -0.5044029 0.6567791 -0.5507068 -0.5151343 0.6563969 -0.629715 -0.4154541 0.7424628 -0.4969987 -0.4491562 0.9707629 -0.1960694 -0.1384792 0.9821216 -0.08064627 -0.1700983 0.8699875 -0.4235525 -0.2524381 0.8713862 -0.3600983 -0.3331897 0.8571135 -0.3943551 -0.3314222 0.8533142 -0.286482 -0.4356408 0.784175 -0.4372534 -0.4403169 0.4749453 -0.5855486 -0.6569322 0.554723 -0.6768599 -0.4838836 0.462708 -0.575135 -0.6746267 0.4561137 -0.5777848 -0.6768493 0.4499655 -0.5786026 -0.6802574 0.4654124 -0.5790196 -0.6694235 0.4545408 -0.6013621 -0.6570817 0.4545803 -0.6013113 -0.6571009 0.432278 -0.5538283 -0.7116249 0.4771063 -0.5656836 -0.6725858 0.4623715 -0.5917379 -0.6603476 0.4960196 -0.6463674 -0.5798049 0.5454212 -0.6847807 -0.4833126 0.5499387 -0.6588824 -0.5132654 0.5374112 -0.6650825 -0.518512 0.5348762 -0.6646229 -0.5217125 0.5679646 -0.6394398 -0.5182016 0.5048657 -0.6640309 -0.5515194 0.963747 -0.227476 0.1394508 0.9955013 -0.07739287 0.05465656 0.9890304 -0.137293 0.05449426 0.9999891 0.001636624 0.004391252 0.9891675 -0.1355381 0.0563656 0.9788104 0.01052439 0.2044981 0.9166669 -0.04498285 0.3971127 0.9999969 0 0.002526342 0.8957126 -0.1308847 0.4249331 0.9193086 -0.2603986 0.2950669 0.9791788 0.01040059 0.2027333 0.9953549 -0.09013056 0.03383976 0.9999996 -8.1833e-4 4.10164e-4 0.815486 -0.02710723 0.5781417 0.6928693 -0.1004276 0.7140354 0.6011278 -0.2936672 0.7432395 0.8252124 -0.1550881 0.5431135 0.9612118 -0.2506656 0.1150599 0.905247 -0.06762307 0.4194701 0.8066685 -0.3336436 0.4878196 0.6037873 0.07458221 0.7936488 0.3588535 -0.4039449 0.8414586 0.3505496 0.09887295 0.9313105 0.5692025 -0.2291142 0.7896299 0.7523539 -0.321196 0.5751496 0.7469065 -0.2813711 0.6024626 0.8113498 -0.384235 0.4405395 0.9294055 -0.3294027 0.1664313 0.9108108 -0.3624279 0.1976609 0.9096116 -0.3655817 0.1973751 0.8789785 -0.4287027 0.2088324 0.8745799 -0.444111 0.1946163 0.7764902 -0.5995807 0.1938195 0.7764881 -0.5995826 0.1938219 0.7108241 -0.5488606 0.4398651 0.6446594 -0.5267282 0.5540502 0.6295077 -0.4860953 0.6061613 0.4838918 -0.3736535 0.7913482 0.4241595 -0.3602673 0.8308407 0.227207 -0.1243564 0.965874 0.1554251 -0.1200124 0.9805305 0.6955668 -0.6914697 0.1950808 0.6841238 -0.7004058 0.2034855 0.6614754 -0.7230218 0.1992236 0.5930964 -0.5602645 0.5782218 0.5267257 -0.6454352 0.5531488 0.3957961 -0.3366212 0.8544189 0.3036646 -0.4774684 0.8245071 0.1435902 -0.04972529 0.9883872 0.01823991 -0.2563621 0.9664087 0.6692829 -0.7123843 0.2111141 0.6360051 -0.7456737 0.1986667 0.5472522 -0.5876257 0.595996 0.4778192 -0.6716277 0.5662201 0.3268439 -0.361603 0.8731646 0.2316733 -0.4963272 0.8366522 0.06028974 -0.06329697 0.9961721 -0.07038313 -0.2595198 0.9631697 0.6172153 -0.7485651 0.2422715 0.5798916 -0.7911473 0.1944522 0.4211203 -0.6315653 0.6509861 0.3726117 -0.7410861 0.5585267 0.1412188 -0.3797567 0.914244 0.08813494 -0.5752189 0.8132377 -0.1473993 -0.03746116 0.9883674 -0.2342913 -0.3398895 0.9108144 0.4069002 -0.8937353 0.1888637 0.5200114 -0.8202666 0.2382249 0.5065351 -0.8421491 0.1849518 0.2797176 -0.7480297 0.6018387 0.2766747 -0.7656124 0.5807657 -0.01402068 -0.5270224 0.8497358 -0.01348912 -0.5227631 0.8523713 -0.3061893 -0.2021864 0.9302521 -0.2974398 -0.1630977 0.9407066 0.3254395 -0.9225662 0.20727 0.3582351 -0.9067398 0.2224648 0.1891891 -0.7901594 0.5829716 0.1845963 -0.8073549 0.5604484 -0.04292535 -0.5464456 0.8363938 -0.04257941 -0.5448608 0.8374449 -0.268501 -0.2053321 0.9411408 -0.2584595 -0.1725589 0.9504853 0.1132106 -0.8126217 0.57169 0.1622315 -0.9694229 0.1841203 -0.004706621 -0.9999734 0.005585312 -0.001950085 -0.9999892 0.004237234 -3.22009e-4 -0.9999963 0.002696394 9.17878e-4 -0.9999994 7.70416e-4 -0.06626236 -0.9937929 0.0893588 0.0428 -0.9987751 0.02483218 -0.03032141 -0.9972922 0.06700056 0.02524262 -0.9995651 0.01524889 -0.003087878 -0.999163 0.04079157 0.01635563 -0.9998272 0.008843302 0.01540464 -0.9998229 0.0108143 0.01647561 -0.9998418 0.006707549 -0.1272248 -0.8712453 0.4740732 0.1071533 -0.9738543 0.2003147 -0.1202911 -0.9425325 0.3117089 0.09027719 -0.9889371 0.1177005 -0.002594113 -0.9809338 0.1943252 0.0693075 -0.9950398 0.07135993 0.08095401 -0.9952346 0.05435746 0.08427733 -0.9956433 0.03989779 -0.1221534 -0.6642135 0.7374952 -0.1487974 -0.8130974 0.5627895 -0.07114869 -0.8389248 0.5395768 0.01639193 -0.9262353 0.3765894 0.06589502 -0.9373015 0.3422334 0.08127057 -0.9690582 0.2330693 0.1729425 -0.9787575 0.1101126 0.1709317 -0.9806355 0.09558492 -0.2050987 -0.466692 0.86031 -0.1509227 -0.6719241 0.7250796 -0.03785425 -0.7113273 0.7018409 -0.04280263 -0.832267 0.5527204 0.1169134 -0.8814319 0.4576125 0.08791083 -0.9317895 0.3521932 0.2426409 -0.9576238 0.155184 0.2341569 -0.9623931 0.1377322 -0.2251774 -0.1880227 0.9560035 -0.212476 -0.4690747 0.8572181 -0.03164225 -0.5417573 0.8399391 -0.06461966 -0.7201462 0.6908066 0.1579566 -0.8040632 0.5731772 0.1074003 -0.88466 0.4536981 0.3088852 -0.9294759 0.2016544 0.2920199 -0.9401167 0.1757981 0.2058796 -0.1948381 0.9589847 -0.2254416 -0.1942014 0.9547052 0.2185387 -0.828997 0.5147864 0.1464585 -0.8856003 0.4407516 0.08433747 -0.9801902 0.1792055 0.1287078 -0.9659631 0.2243874 0.03437632 -0.9949231 0.09458553 0.3208228 -0.4024569 0.8573805 0.3030424 -0.5537656 0.7755702 0.3028582 -0.5532849 0.7759851 0.2524149 -0.6892246 0.6791584 0.2288809 -0.753139 0.616762 0.3416575 -0.2335385 0.9103462 0.3637078 -0.193811 0.9111279 0.3522152 -0.04213106 0.9349703 -0.2068237 -0.5529808 0.807116 -0.170491 -0.4774398 0.8619652 -0.2306628 -0.1862952 0.9550334 -0.1603991 -0.8283321 0.5367851 -0.1177111 -0.7760511 0.6195878 -0.1400477 -0.6592975 0.7387242 -0.02618175 -0.980795 0.1932762 -0.3406526 -0.9301618 0.136949 -0.2506517 -0.9553446 0.1564942 -0.04151695 -0.9663757 0.2537608 -0.07541596 -0.8830453 0.4631883 0.1096268 -0.1948794 0.9746815 0.1609802 -0.1547635 0.9747481 0.1356912 -0.5536676 0.8216083 0.1356858 -0.5536639 0.8216116 0.0908426 -0.8301952 0.5500214 0.09083181 -0.8301965 0.5500212 0.03193974 -0.9805995 0.1934027 0.03194141 -0.9805989 0.1934052 -0.006915152 -0.9805997 0.1958992 -0.006915688 -0.9805992 0.1959018 -0.01966834 -0.8301944 0.5571272 -0.01966679 -0.8301956 0.5571254 -0.02937406 -0.5536659 0.8322207 -0.02938657 -0.5536707 0.8322171 -0.03461724 -0.1941645 0.980358 -0.03460168 -0.1941573 0.98036 0.8842906 -0.4657164 -0.03373986 0.7914871 -0.611167 0.004824459 0.7261039 -0.687585 -2.905e-4 0.7924875 -0.6092286 0.02835905 0.8758484 -0.482586 -5.98786e-4 0.9177835 -0.3970811 9.04433e-5 0.919053 -0.3941341 9.63373e-7 0.9332946 -0.3591119 -2.84102e-6 0.9389379 -0.3440856 -9.19791e-4 0.9954947 -0.0947135 0.00443083 0.9999441 -0.004110813 -0.009750306 0.9762535 -0.2154268 0.02281314 0.9950382 -0.0970754 -0.02180659 0.9661183 -0.258089 0.00233221 0.9994904 -0.03192126 1.76536e-4 0.9999921 -0.003998875 8.76788e-6 0.9999988 -0.001619696 0 0.7111377 -0.7030528 5.55368e-7 0.7042984 -0.7099041 -7.22339e-7 0.6906905 -0.7231505 -1.79862e-4 0.001391649 -0.9999991 0 0.1861137 -0.9822983 0.02125364 0.004201054 -0.9999324 -0.01084446 0.07418781 -0.997243 0.001662373 0.01111894 -0.9999383 3.48734e-5 0.6956012 -0.718428 -4.91251e-4 0.6696765 -0.7426529 4.22049e-4 0.6195932 -0.7849202 -0.002167344 0.5894708 -0.8077847 0.002852499 0.5185847 -0.8550248 -0.001640617 0.4557201 -0.8901142 0.004021406 0.4284531 -0.9035642 -1.90291e-5 0.3769182 -0.9262466 3.21806e-6 0.3397596 -0.9405121 -6.30342e-4 0.2781484 -0.9605089 -0.007502317 0.3618966 -0.9321632 0.0101251 0.2053858 -0.9785917 -0.01323246 0.2968068 -0.9548569 0.01240795 0.1009801 -0.9947879 -0.01414674 0.02917551 -0.9988936 -0.03688299 -1 0 0 -1 1.46339e-7 0 -1 0 0 -1 -1.06912e-5 0 -0.8857803 0.4641051 0 -0.9662051 0.2284883 -0.1193357 -0.8982337 0.4395086 0.002918004 -0.9811962 0.1930064 -0.00166887 -0.9870831 0.160175 -0.003322243 -0.997757 0.0669406 0 -0.9685663 0.1571716 -0.1928124 -0.8723227 0.4570547 -0.1736502 -0.8723226 0.4570541 -0.1736518 -0.7393188 0.4570534 -0.4944795 -0.7393171 0.4570502 -0.4944849 -0.4935849 0.4570525 -0.7399169 -0.493585 0.4570518 -0.7399173 -0.1725975 0.4570571 -0.8725302 -0.1725956 0.4570521 -0.8725333 -0.9685655 0.1571785 -0.1928106 -0.8208833 0.1571751 -0.5490416 -0.8208872 0.157177 -0.5490351 -0.5480372 0.157172 -0.8215548 -0.5480507 0.1571787 -0.8215445 -0.1916376 0.1571755 -0.9687987 -0.1916413 0.1571793 -0.9687973 -0.9979363 0.05460399 -0.03378939 -0.9732009 0.2294944 0.01457542 -0.756264 0.581502 0.299867 0.9966919 0.06877917 -0.04329842 0.9970186 0.06640583 -0.0392971 0.971604 0.199142 -0.1277825 0.9677731 0.202142 -0.1501792 0.9179673 0.3455379 -0.1947814 0.9012185 0.2598212 -0.3468405 0.327431 -0.9183787 0.2221927 -0.1817128 -0.9164278 0.3565678 -0.2574715 -0.8898915 0.3765657 -0.2059847 -0.9614522 0.1821539 -0.1910074 -0.9617744 0.1962301 -0.2027873 -0.961431 0.1858168 -0.1196392 -0.9915013 0.05110484 0.03396975 -0.9947949 0.09606945 0.05777764 -0.9941602 0.09114378 -0.0237559 -0.999435 -0.02377986 -0.007141709 -0.9778109 -0.2093678 0.6908232 -0.7225374 -0.02651536 0.6980021 -0.7157289 -0.02291899 0.7043414 -0.7096252 -0.01831501 0.7082901 -0.7057671 -0.01476705 0.7100737 -0.7040115 -0.01277458 0.7102192 -0.7038679 -0.01260375 0.7090839 -0.7049809 -0.01421296 0.7066997 -0.7072896 -0.01780474 0.7026861 -0.7110811 -0.02441251 0.7081437 -0.7059153 -0.01470077 0.5135148 -0.8561648 -0.05731159 0.6357422 -0.7715191 -0.02429699 -0.01847147 -0.9998197 0.004403114 0.01629179 -0.9968321 -0.07784813 0.1202123 -0.987784 -0.09915614 -0.1764194 -0.9842719 -0.009224951 -0.1229861 -0.9897559 -0.07251 -0.07256418 -0.9947305 -0.07242715 -0.3038392 -0.9500805 -0.07091552 -0.3473067 -0.9370757 0.03559827 -0.3558992 -0.934044 0.02996301 -0.2318629 -0.9711814 -0.05519402 -0.1143904 -0.9818992 -0.1509595 -0.1332748 -0.9855386 -0.1046493 -0.1675797 -0.9841354 -0.05826389 -0.04262977 -0.9884486 -0.1454384 -0.07333421 -0.9897499 -0.1225455 -0.09800732 -0.9878791 -0.1203721 -0.006306767 -0.9879736 -0.1544941 -0.01695156 -0.9869376 -0.1602092 -0.03222543 -0.9838937 -0.175826 -0.03120023 -0.9948628 -0.09630471 -0.02779483 -0.9976961 -0.06188774 -0.01639211 -0.9992457 0.03520661 -0.008900165 -0.9919552 0.1262763 -0.006270468 -0.9921142 0.1251811 0.005029439 -0.9903669 0.1383769 0.03716236 -0.9864173 0.1599997 0.03716677 -0.9920767 0.1200103 0.04533201 -0.990045 0.1332515 0.0587663 -0.9931479 0.101014 0.1055938 -0.9915308 0.07560861 0.09774953 -0.9916464 0.08415824 0.08049917 -0.9928894 0.08769601 0.08475214 -0.9925038 0.08805334 0.08881437 -0.9920687 0.08894765 0.0928896 -0.9915742 0.09028851 0.0562005 -0.9940615 0.09318405 0.08139926 -0.9935551 0.07888197 0.05699974 -0.9946276 0.08641237 0.05956399 -0.9943561 0.08779579 0.05653178 -0.9950385 0.08186942 -0.006036698 -0.9947584 0.1020759 0.008062422 -0.9951211 0.09833216 0.02143698 -0.9950885 0.09664082 -0.05479019 -0.9924654 0.1095922 -0.1873149 -0.9625103 0.1961817 -0.1753398 -0.9645112 0.1974192 -0.1290258 -0.9700296 0.2059003 -0.1648845 -0.9700571 0.1783325 -0.1854275 -0.9660766 0.1797572 -0.1553241 -0.9673023 0.200501 -0.2114363 -0.9593609 0.1868728 -0.2060425 -0.9601958 0.1886014 -0.2066769 -0.9601215 0.1882854 -0.2091522 -0.9599216 0.1865635 -0.2113546 -0.9599444 0.1839455 -0.2128882 -0.9600838 0.1814325 -0.2132673 -0.9601901 0.1804221 -0.2114051 -0.9593449 0.1869899 -0.1741257 -0.9655712 0.1932685 -0.1752233 -0.9651724 0.194266 -0.1757938 -0.9649738 0.1947361 -0.1768394 -0.9646025 0.1956274 -0.1790866 -0.9638423 0.1973223 -0.1812463 -0.963154 0.1987066 -0.1829595 -0.9626371 0.1996389 -0.1837655 -0.9624105 0.199991 -0.2042797 -0.9563916 0.2087698 -0.1881096 -0.9626371 0.1947937 -0.1907591 -0.9618375 0.1961618 -0.2309715 -0.9596408 0.1604431 -0.2141269 -0.9619231 0.1698635 -0.2066009 -0.9557003 0.20965 -0.2071047 -0.9561358 0.2071527 -0.2092558 -0.9604514 0.1836987 -0.2273552 -0.963217 0.1432578 -0.2354999 -0.9586116 0.1600117 -0.2378395 -0.9590126 0.1540367 -0.2515908 -0.954101 0.162461 -0.2348775 -0.9413132 0.2424091 -0.1959087 -0.9480845 0.2505106 -0.2548352 -0.9414482 0.2207584 -0.2746344 -0.8901637 0.363572 -0.2719416 -0.8918848 0.3613713 -0.2578653 -0.8976594 0.3573698 -0.2593505 -0.9028782 0.3428533 -0.2701157 -0.907312 0.3222151 -0.2203428 -0.9260874 0.3062863 -0.2249903 -0.9254688 0.3047739 -0.2600654 -0.925518 0.275286 -0.2432435 -0.8966869 0.3698452 -0.2472439 -0.8984758 0.3627834 -0.2286201 -0.9058974 0.3564866 -0.1195319 -0.9318844 0.3424965 0.08178913 -0.9604879 0.2660332 0.2021334 -0.953172 0.2249564 0.1945578 -0.9495312 0.2460442 0.1245856 -0.9569498 0.2621556 0.5896356 -0.8074122 0.02038693 0.710683 -0.7034505 0.009327292 0.7117181 -0.7024388 0.006086885 0.6695614 -0.7420232 0.03300267 -0.02296531 -0.9934806 0.1116641 -0.02303838 -0.9938205 0.1085826 -0.02208602 -0.9938974 0.1080749 -0.001906156 -0.989397 0.1452244 -0.001940667 -0.9937061 0.1120024 0.03552186 -0.9949674 0.09369242 0.03554636 -0.9947332 0.09613764 0.05992633 -0.9943539 0.08757418 0.05663114 -0.9930564 0.1031119 0.05334395 -0.9924808 0.1101649 0.05648964 -0.9935724 0.09809756 0.05525922 -0.9878341 0.1453629 0.0559076 -0.9940028 0.09398347 0.08294165 -0.9943689 0.06596422 0.08294314 -0.992896 0.08531183 0.09931236 -0.992147 0.07603603 0.01978826 -0.9868521 0.1604102 0.01981174 -0.9870146 0.1594045 0.03298026 -0.99052 0.1333506 0.03354364 -0.9945306 0.09891396 0.0350573 -0.9944775 0.09892225 0.1201747 -0.9905094 0.06670349 0.05998754 -0.9959149 0.06749087 0.08079361 -0.9948372 0.06141191 -0.2718502 -0.962337 -0.00227487 -0.3204687 -0.9472332 0.007022559 -0.3214913 -0.9433085 0.08253759 -0.09126508 -0.9878289 0.1259565 -0.1000269 -0.9871858 0.1243342 -0.09971171 -0.9862586 0.1317253 -0.06546586 -0.9890145 0.1325309 -0.06473332 -0.9829378 0.1721716 -0.03018999 -0.9845131 0.1726923 -0.03020405 -0.9807416 0.1929603 -0.01447135 -0.9810917 0.193002 -0.01451432 -0.9805436 0.1957649 -0.04754078 -0.9794242 0.1961334 -0.04667383 -0.9863229 0.1580789 -0.007139384 -0.9876217 0.1566923 -0.0549634 -0.9935733 0.09895014 0.008427262 -0.9952633 0.09685045 -0.01534599 -0.9961648 0.08614051 -0.02253401 -0.9987835 -0.04386317 -0.1192806 -0.9921787 -0.03679358 -0.1000837 -0.9948521 0.01589578 -0.1767499 -0.9840229 0.02141314 -0.1793602 -0.9730956 0.1446203 -0.1696968 -0.9748661 0.1443584 -0.1699839 -0.9564146 0.2374379 -0.1461967 -0.9602701 0.2377141 -0.1457629 -0.9512954 0.2716438 -0.1270466 -0.9538026 0.2722498 -0.1274416 -0.9574611 0.2588958 -0.009622454 -0.9990472 0.04256939 -0.1010686 -0.9937501 0.04739212 -0.05511689 -0.9930225 0.1042531 -0.1170325 -0.9873089 0.1073535 -0.1187493 -0.9730347 0.1977428 -0.09162229 -0.9760397 0.1973623 -0.09197878 -0.9678745 0.2340061 -0.06521654 -0.9700081 0.2341603 -0.06523227 -0.9718477 0.2263999 -0.09318321 -0.969696 0.2258464 -0.0937336 -0.9751553 0.200714 -0.04683959 -0.9630933 0.2650616 -0.07328528 -0.9972963 0.005423426 -0.0168522 -0.9978562 -0.06323796 0.02474933 -0.9996534 -0.008981406 0.2044826 -0.9788467 -0.006782472 0.1381469 -0.9896392 -0.0391103 0.2257391 -0.9723955 -0.05906754 0.2619462 -0.9642074 -0.04108929 0.3482505 -0.9354279 -0.06079739 0.3899109 -0.9200524 -0.03838056 0.4483107 -0.8923194 -0.05276107 0.5400279 -0.8412517 -0.02579432 -0.1992379 -0.9528415 0.2289047 -0.06581783 -0.9692917 0.2369425 -0.06598079 -0.9556534 0.2870074 0.056432 -0.955061 0.290988 0.6005722 -0.7975628 0.05662786 0.5182161 -0.8452809 0.1302009 0.4939944 -0.8632535 0.1037455 0.4088665 -0.900214 0.1498098 0.3649407 -0.9199863 0.1429806 0.3130627 -0.9328503 0.1782754 0.2338477 -0.9553364 0.1806866 0.203953 -0.9584386 0.1994957 0.1109223 -0.9734518 0.2002193 0.08408272 -0.9727394 0.2161208 0.001357793 -0.9766758 0.214715 -0.09187984 -0.9592784 0.2671011 -0.2165825 -0.9248503 0.3126403 -0.2142074 -0.9124363 0.3486764 -0.2209374 -0.9092102 0.3528789 0.03937143 -0.9652006 0.2585303 -0.0110535 -0.9355307 0.3530725 -0.04700189 -0.9446175 0.3247904 -0.1258742 -0.9273191 0.3524699 -0.1272323 -0.9426365 0.3086236 -0.2074146 -0.9305654 0.3017072 -0.209938 -0.9472814 0.2420412 -0.2765496 -0.8880673 0.3672288 -0.2781183 -0.8931002 0.3535851 -0.2860959 -0.8890546 0.3573951 -0.2910994 -0.9072576 0.3035536 -0.2914149 -0.9070253 0.303945 -0.2958777 -0.9252045 0.2375986 -0.2933571 -0.9268324 0.2343577 -0.1878447 -0.9821915 0.003784179 -0.1824756 -0.9830311 0.01877695 -0.1824529 -0.9830582 0.01753848 -0.2259682 -0.9729887 -0.04723781 -0.2968799 -0.9451842 0.1359753 -0.2911722 -0.9480157 0.128394 -0.2007529 -0.9705171 0.1333978 -0.1890525 -0.9747739 0.1186391 -0.09116631 -0.988282 0.1224235 -0.0753526 -0.9907341 0.1129965 0.003883481 -0.9933668 0.114923 0.02181661 -0.9943161 0.1042101 0.1151026 -0.9877582 0.1052863 0.1342364 -0.9865177 0.09361302 0.2391182 -0.9664776 0.09350776 0.2580956 -0.9626878 0.08135664 0.369291 -0.9258685 0.07994771 0.3865519 -0.9197614 0.06794571 0.4966359 -0.8654906 0.06541335 0.5108643 -0.8579481 0.05424886 0.6223727 -0.7810803 0.05065381 0.6247109 -0.7799174 -0.03828006 0.6824977 -0.7302875 -0.02961575 -0.2442904 -0.9018177 0.3564367 -0.2822806 -0.8925851 0.3515814 -0.2821225 -0.8920585 0.3530418 -0.3101894 -0.8899301 0.3343754 -0.3131965 -0.9008038 0.3007665 -0.3310695 -0.9062992 0.2627066 -0.3329434 -0.9135165 0.2337442 -0.344321 -0.915682 0.2072913 -0.3470588 -0.9283963 0.1327801 -0.2653744 -0.9629919 -0.04715114 -0.2783566 -0.9603266 0.01705098 -0.3165006 -0.9466266 0.06103909 -0.2900155 -0.9564378 -0.03343302 -0.3521303 -0.9348871 0.04461562 -0.3516317 -0.9283059 0.1208446 -0.3054618 -0.9443366 0.1221543 -0.3036331 -0.9293738 0.209932 -0.310177 -0.9233384 0.2263552 -0.2738608 -0.9238411 0.2674287 -0.2716583 -0.9121546 0.306881 -0.2535592 -0.9168249 0.3084478 -0.2515975 -0.9084243 0.3338623 -0.2448849 -0.9099958 0.334573 -0.2499608 -0.9264534 0.2814317 -0.2278426 -0.9245092 0.305566 -0.2349821 -0.9464657 0.2213282 -0.2145284 -0.9457523 0.2439885 -0.2199299 -0.9605736 0.1700866 -0.2325609 -0.9577157 0.1693997 -0.1754193 -0.9677431 0.1808352 -0.1940123 -0.9794117 -0.05578517 -0.2226631 -0.9711701 -0.08514565 -0.228091 -0.9699501 0.08468437 -0.232219 -0.9693769 0.07989287 -0.2326813 -0.9557569 0.1799678 -0.2246833 -0.9576659 0.1799821 -0.2228079 -0.9353802 0.2746281 -0.2040202 -0.9394024 0.275498 -0.2026841 -0.9301784 0.3060839 -0.1906436 -0.9324522 0.3069009 -0.1937679 -0.9471827 0.2555367 -0.1616978 -0.9437856 0.2883104 -0.1664399 -0.9659525 0.1980746 -0.1384385 -0.9640117 0.2269721 -0.1417617 -0.9779804 0.1531598 -0.1861438 -0.9707776 0.1514641 -0.1879367 -0.9744129 0.1232859 -0.1496226 -0.9779146 0.1459324 -0.1449973 -0.9670021 0.2094824 -0.1842961 -0.9766426 0.1104724 0.9264159 -0.2578989 0.2743025 0.2855028 -0.7583326 0.5860205 0.7404583 -0.3535639 0.5715891 0.6960943 -0.5207914 0.4941954 0.812443 -0.4350907 0.3881143 0.4081125 -0.7768496 0.47953 0.4159559 -0.6924896 0.5894394 0.4532457 -0.7937728 0.4055774 0.4604446 -0.631149 0.6242129 0.510949 -0.6370581 0.5771379 0.5107125 -0.5282598 0.6783174 0.5521748 -0.5371705 0.6376134 0.5532858 -0.4560518 0.6970592 0.5599448 -0.4800677 0.6752755 0.5586214 -0.3998098 0.7267009 0.5883183 -0.4117374 0.6959555 0.5882058 -0.2894273 0.7551463 0.6095529 -0.301373 0.7332255 0.6093304 -0.1723532 0.7739579 0.623026 -0.1814834 0.7608565 0.623329 -0.05532866 0.7799999 0.6273326 -0.05906468 0.7765084 0.8128274 -0.4352939 0.3870803 0.812883 -0.3580136 0.459399 0.8298273 -0.3577224 0.4282773 0.8304995 -0.3055364 0.4657446 0.8332152 -0.3183328 0.4521247 0.8323137 -0.2673777 0.4855547 0.8443042 -0.2712399 0.4621465 0.8441731 -0.1920439 0.5004906 0.8527307 -0.1972659 0.4836698 0.8525519 -0.1137632 0.5101112 0.8580145 -0.1182959 0.4998173 0.8581632 -0.03639441 0.5120853 0.8597566 -0.03843408 0.509256 0.9722295 -0.2044102 0.1139567 0.9794588 -0.1223335 0.1602969 0.9806275 -0.1222201 0.1530753 0.9806535 -0.1062184 0.1644275 0.9809927 -0.110059 0.1598135 0.9808338 -0.09282052 0.1713168 0.982288 -0.09339743 0.162442 0.9822311 -0.06635111 0.1755552 0.9832644 -0.06766206 0.1691541 0.9832139 -0.03917354 0.1782023 0.9838712 -0.04047131 0.1742401 0.9838789 -0.01250189 0.1783985 0.9840704 -0.01312536 0.1772944 0.9842666 0.00335592 0.1766585 0.9841486 0.003669261 0.1773085 0.8613601 0.009344935 0.5079089 0.8603462 0.01030385 0.5096061 0.6309294 0.01412564 0.7757117 0.6283501 0.01571398 0.7777721 0.9850335 0.01213568 0.1719353 0.9842488 0.01350575 0.1762722 0.8679752 0.03394967 0.4954457 0.8612512 0.03787666 0.506766 0.6478523 0.05164039 0.7600136 0.6307464 0.05773955 0.7738379 0.9862688 0.02054208 0.1638652 0.9850304 0.02300816 0.1708388 0.8786627 0.05790084 0.4739192 0.8679872 0.06479907 0.4923409 0.6752312 0.08889698 0.7322296 0.6478843 0.09912782 0.7552613 0.4053534 0.4043687 -0.8198626 0.1595563 0.4196118 -0.8935702 0.1244742 0.4605436 -0.8788663 0.4380873 0.1170862 -0.8912746 0.4603384 0.1430426 -0.8761436 0.1601725 0.1590558 -0.97419 0.1592838 0.1581671 -0.9744803 0.8969678 0.0420013 -0.4400962 0.6530184 0.04394203 -0.7560663 0.6579193 0.04461103 -0.751766 0.6920183 0.09961467 -0.7149739 0.5591031 0.1077805 -0.8220627 0.7958446 0.2129669 -0.5668127 0.5960415 0.2471243 -0.7639792 0.6841212 0.3111029 -0.6596917 0.6882531 0.3670092 -0.6257891 0.7763653 0.4057317 -0.4823265 0.5275962 0.4866768 -0.6962672 0.6464859 0.556208 -0.5221959 0.5631493 0.6305699 -0.5340828 0.6531926 0.6831932 -0.326476 0.4004472 0.7529414 -0.5222272 0.4587349 0.8028036 -0.3808791 0.9728779 0.03343439 -0.2288907 0.804078 0.03240346 -0.5936402 0.98403 0.04276752 -0.1727888 0.9814224 0.08762353 -0.1706819 0.9946646 0.09160786 -0.04743933 0.9824894 0.1829187 -0.03543084 0.9827088 0.1795616 0.04517918 0.9663539 0.2494167 0.06286191 0.9640551 0.2513029 0.08628147 0.9380639 0.3284248 0.1103333 0.9360288 0.3204966 0.1453693 0.894617 0.4051023 0.1885544 0.8939031 0.4037098 0.194822 0.8395563 0.4839081 0.2469381 0.8393952 0.4894908 0.2362511 0.8551906 0.04877477 -0.5160136 0.8518035 0.106361 -0.5129504 0.8995441 0.1132329 -0.4218993 0.8833815 0.2343168 -0.4058729 0.9086046 0.2369419 -0.3439421 0.8860877 0.3353016 -0.3200334 0.8911324 0.339132 -0.3014509 0.8541841 0.446456 -0.2665457 0.8634297 0.4446404 -0.2382941 0.8054913 0.5651603 -0.1782633 0.806698 0.5650649 -0.173032 0.7301 0.6761413 -0.09892946 0.7267524 0.6783466 -0.1080602 0.001072049 0.4641032 -0.8857805 0.001033544 0.4605492 -0.8876336 0.001234412 0.1601843 -0.9870864 0.00119543 0.1561854 -0.9877271 0.1613151 0 -0.986903 0.1570395 3.51617e-4 -0.9875923 0.4651267 -3.60216e-4 -0.8852441 0.461583 0 -0.8870971 0.001072049 0.4641079 -0.885778 0.001072049 0.4640994 -0.8857825 0.001194655 0.1601808 -0.987087 0.001194655 0.1601822 -0.9870868 0.6234651 0.1604405 -0.7652126 0.5597181 0.4632542 -0.6871036 0.6236473 0.1594724 -0.7652664 0.464867 0.1594815 -0.8708986 0.4648652 0.1594648 -0.8709026 0.2875002 0.1594077 -0.944422 0.2874964 0.1594561 -0.9444149 0.09787809 0.1594312 -0.9823449 0.09787827 0.1594419 -0.9823433 0.5600855 0.462368 -0.6874011 0.4175308 0.4623746 -0.7822262 0.4175219 0.4624295 -0.7821985 0.2582291 0.4623471 -0.8482647 0.2582302 0.4623494 -0.8482631 0.08791399 0.4623501 -0.8823285 0.0879119 0.462349 -0.8823292 0.9217435 -0.05841922 -0.383375 0.6537067 -0.009672462 -0.7566862 0.9714267 -0.05814445 -0.2301078 0.972207 -0.05780041 -0.2268759 0.9935634 -0.04981631 -0.1017355 0.2985703 -0.05179572 -0.9529811 -0.0557717 -0.07518833 -0.9956085 0.803121 -0.05326175 -0.5934305 0.7476476 -0.06406676 -0.6609981 0.8956125 -0.06077891 -0.4406635 0.8801152 -0.06223577 -0.4706635 0.8801012 0.00762844 -0.4747251 0.8831178 0.0128172 -0.4689762 0.9854437 -0.003654778 -0.169963 0.9866775 0.002444922 -0.1626704 0.8578959 0.07731616 -0.5079734 0.8751754 0.0786553 -0.4773693 0.9784441 0.02354711 -0.2051649 0.985275 0.02608102 -0.1689763 0.8603978 0.1991509 -0.4690997 0.8577467 0.1986584 -0.4741367 0.8782235 0.2920528 -0.3787198 0.8544861 0.3014664 -0.4230506 0.8569962 0.4056596 -0.3178015 0.8467106 0.413437 -0.3348898 0.8569052 0.4740068 -0.2025614 0.8497518 0.4828717 -0.2115581 0.9790749 0.08497679 -0.1849089 0.9818093 0.0869351 -0.1687982 0.9818237 0.1083453 -0.1558319 0.9757521 0.1140189 -0.1868358 0.9774585 0.1483468 -0.1502274 0.971657 0.1591804 -0.1747691 0.974844 0.1796523 -0.1319251 0.9712237 0.1900617 -0.1435316 0.03139543 0.02253103 0.9992531 0.1615592 0.9856737 -0.04843467 0.2495011 0.9618925 0.1118575 -0.06718009 0.9916343 -0.1102201 0.1614933 0.9558807 0.2453814 -0.1800009 0.9835785 0.01316088 0.06030339 0.9288943 0.3654025 -0.3045758 0.94507 0.1186431 -0.03494 0.8761536 0.4807641 -0.4085953 0.8822985 0.2336647 -0.1232893 0.8001353 0.5870122 -0.5182868 0.7919884 0.3226968 -0.2017986 0.7029823 0.6819775 -0.6007484 0.6817287 0.4175494 -0.2685311 0.5876118 0.7632846 -0.683548 0.5500533 0.4797954 -0.3234493 0.4576097 0.8282354 -0.733885 0.4047738 0.5455008 -0.3629977 0.3159145 0.8766019 -0.780816 0.2466751 0.5740016 -0.3904218 0.1666461 0.905428 -0.7920216 0.08250534 0.6048922 -0.6090081 0.04807186 0.791706 0.5867542 0.6779195 0.4428825 0.3989861 0.8928 0.209089 0.4963175 0.6050171 0.622594 0.510812 0.5887655 0.6264393 0.5869851 0.6771868 0.4436966 0.5294663 0.6855401 0.4997002 0.5294786 0.6855406 0.4996865 0.4882335 0.6834362 0.5427184 0.4707689 0.6778935 0.5646567 0.3582358 0.5413948 0.7606305 0.3762654 0.5285115 0.7609863 0.4246398 0.6726268 0.606015 0.3681683 0.6538677 0.6609911 0.368181 0.6538665 0.6609852 0.3297801 0.6321838 0.701134 0.3147479 0.6177212 0.7206624 0.2429012 0.4166663 0.876007 0.2633959 0.408688 0.8738403 0.2723223 0.5922493 0.7583413 0.2233718 0.5484859 0.8057718 0.2233815 0.5484575 0.8057885 0.1923103 0.5096951 0.8385867 0.1815738 0.4878918 0.8538106 0.1632383 0.2450035 0.9556812 0.1849455 0.2427586 0.9522938 0.1473916 0.4451229 0.8832561 0.1113812 0.3812515 0.9177372 0.1114144 0.3812302 0.9177421 0.09120517 0.3296525 0.9396867 0.08631575 0.3030782 0.9490486 0.06395071 0.2477921 0.9667003 0.04490584 0.1710234 0.9842431 0.04490065 0.1710311 0.9842421 0.0379799 0.1124748 0.9929286 0.03966224 0.08406674 0.9956705 -0.2166048 0.07031124 0.9737242 0.1497395 0.04947751 0.9874868 0.1282905 0.04574024 0.9906813 0.4002841 0.8915526 0.2119117 0.3248991 0.9015454 0.2857561 0.3248991 0.9015508 0.2857391 0.2176454 0.8933687 0.3930942 0.2176399 0.8933675 0.3930997 0.1127815 0.8598834 0.4978765 0.1127674 0.859897 0.4978561 0.01348119 0.8019387 0.5972542 0.01346194 0.8019564 0.597231 -0.07763636 0.7212941 0.6882641 -0.07764947 0.7212959 0.6882608 -0.1577822 0.6201133 0.7684819 -0.1577687 0.6201108 0.7684866 -0.2248672 0.5013701 0.8355016 -0.2248718 0.5013758 0.8354969 -0.2768185 0.3683633 0.8875135 -0.2768198 0.3683501 0.8875185 -0.312346 0.2249153 0.9229589 -0.3123475 0.224918 0.9229578 -0.3306343 0.07060128 0.9411144 -0.3913499 0.07727092 0.9169922 0.1947681 0.9772186 -0.08431547 0.1856474 0.9769963 -0.1049442 0.425099 0.8864848 0.1828543 0.4166798 0.8959491 0.1537959 0.6082828 0.6727026 0.4212639 0.6071838 0.6792963 0.4121704 0.1895065 0.9789097 -0.07630938 0.1886696 0.9789186 -0.07824462 0.4249237 0.8864589 0.1833863 0.4248459 0.8865553 0.1831008 0.6065968 0.6729639 0.4232729 0.6065674 0.6731768 0.4229764 0.3370103 0.9053201 -0.2584953 0.3418586 0.9052521 -0.2522925 0.569916 0.8212273 0.0279569 0.5788897 0.814159 0.04507678 0.7239667 0.6112002 0.319854 0.7284251 0.5954438 0.3388858 0.2362062 0.9591379 -0.1557598 0.241476 0.9588623 -0.14924 0.4649543 0.8792111 0.1039489 0.4759611 0.8710111 0.1216588 0.6460593 0.6666963 0.3716499 0.6533737 0.6487113 0.3902262 0.759925 0.5729078 0.3070678 0.7567925 0.5744665 0.3118549 0.6245413 0.7809479 -0.008291006 0.6132602 0.7897886 0.01208633 0.3968757 0.8623687 -0.3143406 0.390337 0.8702311 -0.3005577 0.4234294 0.8396766 -0.3400746 0.4213481 0.8393253 -0.3435096 0.6539587 0.7557832 -0.03361266 0.654226 0.7555903 -0.03273987 0.7857635 0.5490655 0.2847856 0.7858825 0.5449402 0.2922826 0.395828 0.8632352 -0.3132815 0.3959933 0.8633996 -0.3126189 0.6288435 0.7774299 -0.01259475 0.6289544 0.777397 -0.008399009 0.7676809 0.5666409 0.2993063 0.7667093 0.5654319 0.3040454 0.8533068 0.4857028 -0.1896325 0.8563657 0.480601 -0.18884 0.7495167 0.5722245 -0.3328421 0.7803316 0.5312325 -0.3299618 0.7600925 0.4922558 -0.424198 0.8323864 0.2912917 -0.4714677 0.8231782 0.3122728 -0.4741976 0.6148132 0.5842269 -0.5297961 0.6353334 0.5586307 -0.5331824 0.6751394 0.3945291 -0.6233246 0.6390343 0.4648818 -0.612797 0.9673414 0.1872884 -0.1708034 0.9546468 0.2329391 -0.1854423 0.9277194 0.21214 -0.3071375 0.9231766 0.2259 -0.310989 0.8935558 0.2060378 -0.3988815 0.8340293 0.2869325 -0.4712376 0.8555912 0.2015447 -0.4768055 0.8026142 0.1813303 -0.5682692 0.8013998 0.1844068 -0.5689927 0.7385175 0.1690751 -0.6526911 0.7406963 0.1608054 -0.6523118 0.3163672 -0.6895673 0.6514667 0.4207828 -0.03609317 0.9064432 0.3869999 -0.2479829 0.8881078 0.3911938 -0.1782995 0.9028714 0.3726121 -0.1073881 0.9217528 0.3313122 -0.4914761 0.805409 0.3546546 -0.4284803 0.8310384 0.3555259 -0.3337478 0.8730486 0.3285159 -0.3610049 0.8727845 0.3645302 -0.3052539 0.8797374 0.2978003 -0.60109 0.7416238 0.3013705 -0.5514339 0.7778795 0.1996171 -0.7657967 0.6113172 0.2032614 -0.7390865 0.6422119 0.21989 -0.771668 0.5968056 0.281509 -0.6481662 0.7075545 0.2479178 -0.690767 0.6792479 0.2484588 -0.7002062 0.6693127 0.2248156 -0.7605651 0.6090967 0.2203903 -0.7775756 0.5889009 0.2972465 -0.5362321 0.7899999 0.4107683 -0.5413479 0.7336293 0.3239054 -0.6011439 0.7305555 0.4351268 -0.2052091 0.876672 0.4413086 -0.3334223 0.8331124 0.4434387 -0.3363782 0.8307899 0.3800777 -0.4635869 0.8003926 0.3981276 -0.5189843 0.7564058 0.3966336 -0.150414 0.9055702 0.4710687 -0.09415829 0.8770567 0.4969941 -0.06380331 0.8654052 0.2930535 -0.03548419 0.9554374 0.2932034 -0.03637874 0.9553577 0.290668 -0.105987 0.9509358 0.2913643 -0.1113882 0.9501051 0.1970078 -0.7384386 0.6449003 0.2229909 -0.6842483 0.6943194 0.237632 -0.6993525 0.6741195 0.219163 -0.6214172 0.7522022 0.2262901 -0.6436622 0.7310895 0.2391973 -0.6118268 0.753958 0.2389892 -0.5965139 0.7661954 0.2486083 -0.5696173 0.7834094 0.2469217 -0.5471916 0.799757 0.2536956 -0.5256951 0.8119627 0.2564677 -0.4863839 0.8352575 0.2571319 -0.4847165 0.8360223 0.2636613 -0.4230965 0.866875 0.2626743 -0.4258013 0.8658496 0.2631264 -0.357041 0.8962624 0.2707639 -0.3164919 0.9091314 0.2718797 -0.3009238 0.9140713 0.2860086 -0.2256619 0.9312765 0.2906048 -0.2446724 0.9250321 0.2857008 -0.1755425 0.9421041 0 1 4.38073e-5 -0.5735744 -2.40809e-7 -0.8191536 -0.5735715 0 -0.8191556 -0.5735782 3.37868e-6 -0.8191508 -0.5735692 -1.76479e-6 -0.8191571 -0.5735789 0 -0.8191504 -0.5735768 4.56318e-7 -0.8191518 -0.5735753 0 -0.8191528 -0.5735779 6.65852e-7 -0.8191511 -0.5735774 2.72933e-7 -0.8191515 -0.573576 0 -0.8191523 -0.5735812 9.86285e-6 -0.8191487 -0.5735774 0 -0.8191514 -0.5735882 -1.09611e-5 -0.8191439 -0.5735802 -4.40141e-6 -0.8191495 -0.5735647 1.41212e-5 -0.8191603 -0.5736044 -6.11805e-6 -0.8191326 -0.5735522 1.3764e-5 -0.819169 -0.5735754 -1.62073e-6 -0.8191528 -0.5735769 2.49168e-6 -0.8191518 -0.5735744 -2.05846e-6 -0.8191534 -0.5735767 1.87095e-7 -0.8191519 -0.5735766 -1.70256e-7 -0.8191519 -0.5735701 0 -0.8191565 -0.573576 0 -0.8191525 -0.6491074 0.701088 0.295187 -0.6790266 0.6947038 0.2372962 -0.7741497 0.6329991 0.002141892 -0.8123713 0.5564796 -0.1743085 -0.8151639 0.4999916 -0.292432 -0.7546357 0.6532814 0.06122583 -0.6755668 0.1379549 -0.7242775 -0.7062868 0.1829027 -0.68389 -0.7706015 0.3127232 -0.5553175 -0.8076515 0.430477 -0.4029746 -0.4752032 0.6971719 0.5367806 -0.5187528 0.705315 0.4831422 -0.3880198 0.6764412 0.6259937 -0.1616427 0.5885552 0.792133 -0.2313485 0.6173303 0.7519185 0.4495517 0.1379559 0.882537 0.496056 0.08538919 0.8640817 0.3640527 0.2207458 0.9048408 0.1551737 0.3928509 0.9064157 0.2394789 0.3230409 0.9155843 0.04021221 0.4734514 0.8799015 -0.5792264 0.7071071 0.4055816 -0.5792275 0.7071073 0.4055797 -0.5792282 0.7071064 0.4055801 -0.5792275 0.707107 0.4055801 -0.5792263 0.7071084 0.4055794 -0.5792304 0.7071062 0.4055774 -0.5792381 0.7070993 0.4055786 -0.9220577 2.99522e-4 0.3870522 -0.04330438 0 0.999062 0.06881678 -0.05239903 0.9962523 -0.2485617 0.07246321 0.9659018 -0.00666666 -0.06452447 0.9978939 -0.0850194 8.07411e-6 0.9963794 -0.04659324 -0.01342105 0.9988239 -0.0414381 -0.004394829 0.9991315 -0.04660964 -0.01504546 0.9987999 -0.0473811 -0.007272422 0.9988504 -0.06390053 -2.51514e-5 0.9979563 -0.1687545 -0.03003275 0.9852005 -0.2490522 -0.2148349 0.9443617 -0.2238011 -0.1180369 0.9674608 -0.1230516 -0.01473683 0.9922909 -0.05428326 -0.04155284 0.9976607 -0.1510448 -7.72207e-6 0.9885269 -0.3358112 1.95542e-6 0.9419293 -0.3488364 9.75376e-4 0.9371832 -0.4176579 -0.001283168 0.9086036 -0.4902532 0.006231129 0.8715578 -0.54895 -0.003940343 0.835846 -0.6585372 0.004153072 0.7525368 -0.6258645 -0.002835273 0.7799267 -0.7046617 0.001361548 0.7095421 -0.7642343 -0.005554676 0.6449149 -0.7621462 -0.006093621 0.6473763 -0.8494805 0.003196239 0.5276107 -0.8824851 0.01452612 0.4701162 -0.8309702 -0.009337663 0.5562387 -0.9011916 0.00651133 0.4333721 -0.8634097 -0.00620979 0.5044654 -0.8798298 -0.002662599 0.4752816 -0.8908818 -0.001099467 0.4542341 -0.896915 -5.24044e-4 0.4422029 -0.9020988 -1.23969e-4 0.4315295 -0.9014289 0 0.4329272 -0.9048444 -0.002298772 0.4257361 -0.9884486 0 0.1515564 -0.9987927 0.03848975 0.03052431 -0.9451489 -0.05469834 0.3220276 -0.9373722 -0.06335133 0.3425202 -0.9932477 0.05764031 0.100681 -0.9696964 0.009283483 0.2441367 -1 -3.69802e-7 0 -1 9.91318e-7 0 -1 2.29774e-6 0 0.9684383 -0.0026443 -0.2492399 0.9953177 0 -0.09665811 0.9999866 -0.001043021 -0.005076348 0.9957405 0 -0.09220051 0.9866802 2.57346e-4 -0.1626725 0.8831959 -2.32059e-4 -0.4690045 0.8794723 0 -0.4759504 0.9468843 -0.2587972 -0.1908774 0.144102 -0.9890957 -0.03040283 0.2450631 -0.9652292 -0.09097623 0.3336814 -0.9388332 -0.08514124 0.7026935 -0.6612862 -0.2625307 0.8558955 -0.4991965 -0.1350775 0.8162797 -0.5609461 -0.1379394 0.7502211 -0.6423884 -0.1565426 0.9983304 -0.05680501 -0.0104801 0.9791512 -0.1294903 -0.1565092 0.9891451 -0.1262651 -0.07516157 0.9943832 -0.08443993 -0.06381338 0.9728386 -0.1977661 -0.1203066 0.9657565 -0.2226876 -0.1331344 0.9460804 -0.2418034 -0.215553 0.9560467 -0.2530259 -0.1481644 0.953927 -0.2587713 -0.1518578 0.9468882 -0.2587717 -0.1908929 0.697924 -0.7022145 -0.1407021 0.6925836 -0.7070981 -0.1426193 0.4542737 -0.8860183 -0.09277433 0.3843001 -0.9191733 -0.0862208 0.868123 -0.03217738 -0.495305 0.5709574 -0.04211449 -0.8198989 0.1624724 -0.03280586 -0.9861677 0.2517245 -0.9659029 -0.06055033 0.6904557 -0.7070944 -0.1526054 0.9447384 -0.2588171 -0.2012045 0.9345082 -0.2625169 -0.2403733 0.9411261 -0.2567254 -0.2199405 0.943964 -0.2573229 -0.2066812 0.2540035 -0.9634007 -0.08568197 0.2373893 -0.9579762 -0.1610217 0.2600079 -0.9471986 -0.1876454 0.2446647 -0.9329028 -0.2642568 0.2552776 -0.9059795 -0.3376899 0.2543613 -0.905923 -0.3385323 0.2300555 -0.8580742 -0.4591115 0.2505484 -0.8424074 -0.4770485 0.2373464 -0.8000102 -0.5510449 0.2548997 -0.7556325 -0.603362 0.245817 -0.7515673 -0.6121445 0.2290756 -0.6690081 -0.7070733 0.2448207 -0.6547434 -0.7151041 0.2357264 -0.5821292 -0.7781766 0.2584632 -0.5314621 -0.8066876 0.9411401 -0.2513555 -0.2259997 0.9341817 -0.2439674 -0.2603544 0.934883 -0.2356225 -0.2654731 0.9304869 -0.2268742 -0.2876148 0.9318773 -0.2149996 -0.2921985 0.9287546 -0.204844 -0.308956 0.9308885 -0.1896551 -0.3122138 0.9286261 -0.1784318 -0.3252936 0.9317044 -0.1605024 -0.3258315 0.9299264 -0.146933 -0.3371164 0.9335345 -0.1287175 -0.3345823 0.9320384 -0.1108219 -0.3449972 0.935653 -0.09509944 -0.3398669 0.9344454 -0.07072508 -0.3490126 0.9372105 -0.06021803 -0.3435264 0.9364257 -0.02851092 -0.3497056 0.9377421 -0.02430373 -0.3464809 0.2834454 -0.9556395 -0.08007562 0.2420641 -0.5165596 -0.8213228 0.2329678 -0.4087432 -0.8824143 0.2423151 -0.4000722 -0.8838697 0.2356536 -0.2598906 -0.9364424 0.2414693 -0.2545778 -0.9364202 0.2379848 -0.1036689 -0.9657205 0.2403301 -0.1016499 -0.9653543 0.1597132 -0.7713848 -0.6160011 0.3960269 -0.04441481 -0.9171641 0.6904363 -0.7035363 -0.1683279 0.6776657 -0.7002467 -0.2245525 0.6867749 -0.686098 -0.2400206 0.6680264 -0.6666599 -0.3306136 0.6771106 -0.6508567 -0.3433758 0.6604291 -0.6179944 -0.4265166 0.6703236 -0.6004111 -0.436088 0.6561705 -0.5546773 -0.5116381 0.6660235 -0.536822 -0.5179139 0.6543333 -0.4790741 -0.5850949 0.6643461 -0.4616378 -0.5878221 0.6551476 -0.3911901 -0.6463375 0.6643538 -0.3757947 -0.6460747 0.6574947 -0.2930423 -0.6941376 0.6652763 -0.2809669 -0.6917117 0.6607021 -0.186497 -0.7271118 0.6660396 -0.178844 -0.7241589 0.6635283 -0.07439196 -0.7444435 0.6661103 -0.07112389 -0.7424544 0.3284054 -0.8803758 -0.3421819 0.7514475 -0.04933595 -0.6579458 0.9995602 0.01599669 -0.02497136 0.9999997 0 -7.60673e-4 0.9975804 -1.71974e-4 -0.06952309 0.9996763 0.01852369 -0.01743954 0.9985395 0.005659401 -0.05373126 0.9999991 2.40558e-4 -0.001388072 0.9999449 0 -0.01049721 0.9971233 0.002116978 -0.07576787 0.9964854 0.004550158 -0.08364474 0.9991593 0.01084613 -0.03953599 0.9975315 5.62489e-5 -0.07022106 0.9882034 -3.32498e-5 -0.1531478 0.9924285 0.004955708 -0.1227241 0.9882034 0 -0.1531478 0.9802809 0 -0.1976097 0.9780864 0 -0.2081999 0.9780862 0 -0.2082 0.9781268 -8.03571e-7 -0.2080095 0.9781312 4.59398e-7 -0.2079887 0.9784178 6.23091e-7 -0.2066364 0.9876989 -0.004446148 -0.1563047 0.9866503 -0.01065379 -0.1625047 0.9866008 -0.01387119 -0.1625626 0.9868376 -0.01099842 -0.1613406 0.9790933 -0.005839943 -0.2033281 0.9813609 -8.70885e-4 -0.192172 0.9840371 5.74039e-4 -0.1779628 0.9859877 -0.003745436 -0.166776 0.9884496 -1.81031e-4 -0.1515498 0.7517011 -0.3601464 -0.5524853 0.9780917 -0.009285032 -0.2079677 0.9847624 0.001221477 -0.1739015 0.9857972 0.006374537 -0.167819 0.986903 0.01130634 -0.1609189 0.98716 0.01229685 -0.1592608 0.9865986 0.01054626 -0.1628253 0.9853033 0.007386445 -0.1706543 0.9833627 0.003970682 -0.1816094 0.9812159 0.001458525 -0.1929072 0.9793833 2.30266e-4 -0.2020109 0.01185566 -0.2727307 -0.9620175 -2.20491e-6 -0.9716144 -0.2365707 -0.01386249 -0.991209 -0.1315768 -0.01138013 -0.9918215 -0.1271249 0 -0.9997507 -0.02233088 6.39867e-6 -0.7915437 -0.6111127 -4.11872e-6 -0.8389549 -0.544201 -0.02469253 -0.9067063 -0.4210391 -0.04201537 -0.897088 -0.43985 4.28026e-6 -0.949087 -0.315014 -0.04224205 -0.7034521 -0.7094864 -0.03059959 -0.7131727 -0.7003202 -3.399e-6 -0.6121363 -0.7907524 -0.03489357 -0.4373216 -0.8986281 -0.04158681 -0.4304923 -0.9016357 4.30638e-6 -0.544425 -0.8388097 -0.03931766 -0.1092015 -0.9932419 -0.002768933 -0.1498979 -0.9886977 0 -0.03369003 -0.9994324 -1 1.77105e-6 0 -1 0 0 -1 -2.60093e-7 0 -1 -4.0449e-7 0 -1 6.0163e-7 0 -1 -7.09195e-7 0 -1 5.48163e-7 0 -1 -3.36222e-6 0 -1 6.51646e-6 0 -1 5.29437e-5 0 -1 1.71137e-5 0 -1 -8.11238e-5 0 -0.9993438 0.01524436 -0.03285676 -0.9999955 -0.00295031 -5.59994e-4 -1 1.35157e-6 0 -0.9999963 -0.001297771 0.002421855 -0.9999976 -0.002225637 -2.11585e-4 -0.9999963 -0.001693785 -0.002168357 -0.9999968 -0.001896679 -0.001730203 -0.9999971 -0.002047717 -0.001313269 -1 -4.01372e-6 0 -0.9999999 4.90076e-4 0 -1 -3.75918e-6 0 -1 1.1698e-6 0 -1 -3.63225e-6 0 -0.9999973 -0.002158522 -9.17299e-4 -0.9999974 -0.002235352 -4.98501e-4 -0.9999975 -0.002254903 -3.50476e-4 -1 -9.78407e-6 0 -0.9974066 -0.02899307 0.06587523 -0.9998983 -0.002993047 -0.0139507 -0.9806909 0.005727291 -0.1954805 -0.9658728 -0.01936495 -0.2582923 -0.8341711 0.0164985 -0.5512591 -0.776094 -0.01637762 -0.6304045 -0.5576269 0.01652967 -0.8299272 -0.5074927 -0.003732085 -0.861648 -0.2156131 0.004150032 -0.9764701 -0.1951237 0.01229381 -0.9807017 -0.03036743 0 -0.9995388 1 -3.06268e-5 0 1 -2.93544e-6 0 1 1.58688e-4 0 0 0.984941 -0.1728912 0 0.9849407 -0.1728929 0 0.9849405 -0.1728939 -0.004425704 0.9381203 -0.3462811 8.04873e-4 0.9852972 -0.1708477 -0.003067851 0.7110787 -0.7031057 -6.21768e-6 0.6177673 -0.7863611 5.22612e-6 0.8000856 -0.5998861 0 0.8002454 -0.5996727 0 0.8954337 -0.4451948 1.45518e-6 0.8953717 -0.4453195 -6.43852e-7 0.93105 -0.3648918 0 0.1344106 -0.9909257 0 0.6024364 -0.7981669 0 0.3863007 -0.922373 7.4888e-6 0.3866084 -0.922244 -7.97158e-6 0.1347369 -0.9908815 -0.001782 -0.9999971 0.001659154 2.53568e-4 -0.9999948 -0.003241539 0.003458738 -0.9999894 -0.003040373 0 -1 0 0.5529876 -0.1009004 -0.8270574 0.5231806 -0.2017424 -0.8279989 0.4958573 -0.3589028 -0.7907682 0.4919783 0.1097298 -0.8636648 0.5338775 -0.1077288 -0.8386713 0.5497863 0.07391637 -0.8320285 0.6088332 -0.1004948 -0.7869073 0.6153738 0.3063712 -0.7262588 0.6816173 0.001075506 -0.7317081 0.7071068 0 -0.7071068 0.7422906 0 -0.6700782 0.7422953 4.05075e-5 -0.670073 0.7422859 0 -0.6700834 0.9658781 0 -0.2589972 0.8623377 0.4741376 -0.177672 0.9888913 0 -0.1486405 0.9466502 0 -0.3222631 0.9348417 0.009717583 -0.354932 0.8247467 0.3934618 -0.4061782 0.8485876 0.3115507 -0.4275922 0.8129355 -0.121479 -0.5695427 0.800065 0 -0.5999133 0.9999846 0 -0.005552649 0.2889823 0 0.9573345 0.2789303 0.03846681 0.9595406 0.2828444 0.01449978 0.9590563 0.2855991 0.006322801 0.9583283 0.2764705 0.08233767 0.9574888 0.2706092 0.1745886 0.9467257 0.252182 -0.01727348 0.9675257 0.9974231 -0.003307819 0.0716682 0.9503003 0.2793341 0.1374835 0.9773284 0 0.2117291 0.910879 0 0.4126735 0.9108791 0 0.4126736 0.180701 0.08910369 -0.9794936 0.1625591 -0.004435181 -0.9866889 0.9571589 -0.00100249 -0.2895613 0.9576175 0.09889173 -0.2705352 0.8680973 -0.03311127 -0.4952888 0.7722495 0.2154902 -0.5976578 0.7523635 0 -0.6587482 0.5203811 0 -0.8539342 0.542396 0.3148648 -0.7788883 0.3961998 -0.03333652 -0.917559 0 -0.004553735 -0.9999896 0 -0.004553735 -0.9999896 0.9959682 -1.48036e-5 0.08970791 0.9959635 0 0.08976024 0.9959684 0 0.08970546 0.9959684 0 0.0897057 0.2212675 -0.9752049 -0.004010498 0.2299711 -0.9731975 0 0.2596712 -0.9356595 0.2389819 0.4661549 -0.8847032 0 0.7071279 -0.7070857 0 0.7070963 -0.7071174 0 0.9659271 -0.2588144 0 0.9659242 -0.2588252 0 0 -1 1.62024e-4 0 -1 -1.67808e-5 0 -1 5.90744e-6 0 -1 -1.3424e-5 0 -1 1.05683e-6 0 -1 -3.72573e-6 0 -1 3.11446e-6 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.9844379 -0.009575068 -0.1754719 -0.9444922 -0.1608756 -0.2864499 0.9878497 -0.02452844 0.153465 0.9840275 0 0.1780172 0.9775683 0 0.2106189 0.9775682 0 0.2106194 0.6020952 0 -0.7984244 0.6019644 0 -0.798523 0.6019606 0 -0.7985258 0.6019445 1.77822e-5 -0.798538 0.6019561 -1.14089e-5 -0.7985292 0.6019448 3.42423e-5 -0.7985377 0.6019457 2.26066e-5 -0.798537 0.601968 7.64987e-6 -0.7985203 0.601939 -3.42021e-5 -0.7985421 0.6019644 0 -0.7985229 0.6019896 0 -0.7985039 0.6019486 -1.63799e-5 -0.7985349 0.6019501 0 -0.7985338 0.6019357 -7.84506e-6 -0.7985447 0.6019659 9.95314e-5 -0.7985218 0.5841083 0 -0.8116759 0.5988482 0 -0.8008626 0.598511 -0.001796543 -0.8011126 0.5809557 0.009697437 -0.8138775 0.5812119 0.01750928 -0.813564 0.5592753 -0.01499253 -0.8288464 0.5559068 0 -0.8312447 0.07801574 0 -0.9969521 0.07798743 2.71994e-5 -0.9969543 0.07801872 -1.07731e-4 -0.9969519 0.07800084 2.36581e-5 -0.9969533 0.07797181 -1.80157e-5 -0.9969556 0.07799452 -6.30616e-6 -0.9969539 0.07797604 1.8659e-5 -0.9969553 0.3219282 0 -0.9467642 0.2483658 -0.1663513 -0.9542756 0.4744481 0 -0.8802835 -0.9307734 0.03073036 -0.3643028 -0.96224 0.02287793 -0.2712395 -0.7722579 0.05346095 -0.6330557 -0.4531447 0.07492655 -0.8882825 -0.1755667 0.4431994 -0.8790624 -0.1745 0.2831867 -0.9430562 -0.1744997 0.2831868 -0.9430564 -0.1751928 0.08275121 -0.9810504 -0.1751943 0.08275043 -0.9810501 -0.296972 0.5315807 -0.7932401 -0.1744992 0.5050293 -0.8452785 -0.1748799 0.6823832 -0.7097677 -0.2152103 0.6905377 -0.6905377 -0.175763 0.7644465 -0.6202653 -0.1744993 0.8452785 -0.505029 -0.1744996 0.845278 -0.5050297 -0.1744992 0.943056 -0.2831881 -0.2520835 0.9353115 -0.2482868 -0.1757068 0.9131541 -0.3677998 -0.1751942 0.9810501 -0.08275145 -0.1751916 0.9810508 -0.08274924 -0.4233629 0.9027546 -0.07614612 -0.792311 0.6079586 -0.05128031 -0.6074064 0.7915803 -0.06677007 -0.9048033 0.4243231 -0.03579163 -0.9843184 0.1757769 -0.01482647 -0.9843181 0.1757789 -0.01482647 -0.9841929 0.1696178 -0.05093401 -0.984193 0.1696174 -0.05093383 -0.9841925 0.1520336 -0.09083473 -0.9841926 0.1520338 -0.09083479 -0.9841924 0.1252322 -0.1252289 -0.9841933 0.1252255 -0.1252288 -0.9841928 0.09083396 -0.1520318 -0.9841926 0.09083694 -0.1520316 -0.9841929 0.0509327 -0.169618 -0.984193 0.05093073 -0.1696183 -0.9842799 0.04647195 -0.1703921 -0.9951649 0.008254587 -0.09787219 -0.8422125 0.5321278 -0.08670717 -0.840344 0.5191515 -0.1558964 -0.8403371 0.519163 -0.1558952 -0.8403421 0.4653269 -0.2780222 -0.8403405 0.4653296 -0.2780222 -0.8403396 0.3832956 -0.3832935 -0.8403409 0.3832927 -0.3832937 -0.840341 0.2780194 -0.4653303 -0.8403397 0.2780238 -0.4653298 -0.8403409 0.1558945 -0.5191574 -0.8403401 0.1558949 -0.5191582 -0.842215 0.08759725 -0.5319783 -0.8810469 0.04878389 -0.4705069 -0.5388323 0.8354692 -0.1079403 -0.5362183 0.8084179 -0.242756 -0.5362192 0.8084172 -0.2427562 -0.536219 0.7245984 -0.4329277 -0.5362199 0.7245981 -0.4329272 -0.5362185 0.5968554 -0.5968529 -0.5362198 0.5968537 -0.5968534 -0.5362206 0.4329252 -0.7245988 -0.5362187 0.4329285 -0.7245982 -0.5362194 0.2427568 -0.808417 -0.536219 0.2427561 -0.8084175 -0.5388678 0.109725 -0.8352137 -0.6335642 0.06496685 -0.7709578 -0.1757985 0.9844263 -1.64392e-7 -0.1757968 0.9844265 0 -0.4245932 0.9053843 0 -0.4245849 0.9053882 0 -0.6087619 0.7933531 0 -0.6087645 0.793351 0 -0.793356 0.608758 0 -0.7933564 0.6087574 0 -0.9053803 0.4246017 0 -0.9053841 0.4245935 0 -0.9844267 0.1757953 0 -0.9844268 0.1757952 0 0.004493057 0 0.99999 -0.01871013 0 0.999825 0.009603381 0 0.999954 -0.008968234 0 0.9999599 -0.0487225 0 0.9988124 -0.01738864 0 0.9998489 0.0937035 0 0.9956002 0.01769632 0 0.9998434 -0.02082878 0 0.999783 -0.07387167 0 0.9972678 0.03553307 0 0.9993686 0.0233854 0 0.9997266 -0.006349027 0 0.9999799 0.03976947 0 0.9992089 0.07743668 0 0.9969974 0.02713489 0 0.9996319 -0.0100308 0 0.9999497 -0.06490349 0 0.9978916 0.03416806 0 0.9994161 -0.002967894 0 0.9999957 0.01154321 0 0.9999334 -0.01929676 0 0.9998139 0.02383822 0 0.9997159 -0.03191983 0 0.9994905 0.02380275 0 0.9997168 -0.03601264 0 0.9993513 0.0232495 0 0.9997297 -0.01532381 0 0.9998826 -0.008574128 0 0.9999634 -0.05361402 0 0.9985618 -0.0439136 0 0.9990354 -0.6441627 0.7606557 0.08035808 -0.7070807 0.7070778 0.008825361 -0.3898997 0.9208453 -0.004709482 -0.7768785 0.6296198 0.006226241 -0.856146 0.5167341 -4.16307e-5 -0.9659265 0.2588163 5.36095e-4 -0.9324769 0.3565945 0.05768209 -0.986163 0.1657586 0.00260967 0.2581068 0.9632984 0.07373648 0.1827502 0.9826104 0.03285205 0.05591231 0.9984357 -5.37856e-5 -0.2588198 0.9659257 2.4188e-4 -0.1085087 0.9777995 0.17926 -0.2391918 0.9673159 0.08418732 0.8582899 0.5131652 -2.60868e-5 0.773613 0.6336371 0.005182623 0.7063022 0.7062878 0.04790401 0.5900461 0.8073688 -0.001152276 0.3720698 0.9282037 0.001451015 0.909957 0.4147027 1.54507e-4 0.9655303 0.2587146 0.02860242 0.984567 0.1749866 0.002766668 0.707108 -0.7071056 0 0.7071033 -0.7071103 0 0.2588211 -0.9659253 0 0.2588195 -0.9659258 0 -0.2588205 -0.9659255 0 -0.2588195 -0.9659258 0 -0.7071092 -0.7071045 0 -0.7071021 -0.7071115 0 -0.9238814 -0.382679 0 -0.9656511 -0.2587459 0.02384531 -0.9914444 -0.1305305 0 -0.999928 0.01200288 0 -0.9999292 0.01190841 0 0.9999297 0.01186078 0 0.999928 0.01200288 0 0.9978592 -0.0654 0 0.9657717 -0.258778 0.01786082 0.9801633 -0.194963 0.03562742 0.9238781 -0.3826869 0 -0.8269478 0 0.5622788 -0.8133218 -0.1600816 0.5593582 -0.7107014 0.1772042 0.6808099 -0.7357001 0 0.6773074 -0.6843436 0.3325034 0.6489339 -0.60064 -0.2959564 0.7427257 -0.6090814 -1.54589e-5 0.7931078 0.8239477 0 0.566666 0.8147776 -0.1709322 0.5540033 0.7556604 0.06870669 0.6513499 0.6090927 -3.55544e-4 0.7930991 0.6005036 -0.2969818 0.7424266 0.6890073 0.1363855 0.7118062 0.724489 -0.1744111 0.6668557 0.7539632 0 0.6569167 -1 3.50232e-4 0 -1 -7.16309e-6 0 -1 4.12094e-7 0 -1 -2.90613e-5 0 -1 2.60275e-7 0 -1 1.29996e-6 0 -1 -2.82687e-6 0 -1 -2.29048e-5 0 -1 4.20592e-5 0 -1 -5.2367e-5 0 0 -1 6.4467e-7 0 -1 0 -1 3.22614e-7 0 -1 -1.11361e-6 0 1 -1.078e-6 0 1 -9.88467e-7 0 1 2.61155e-6 0 1 1.3749e-6 0 1 -2.12964e-6 0 1 -2.92059e-7 0 1 1.81599e-7 0 1 4.48157e-6 0 1 -3.64751e-5 0 1 3.66784e-5 0 -0.6270752 0 -0.7789589 -0.6271012 0 -0.7789379 -0.859868 0 -0.5105164 -0.8598541 0 -0.51054 -0.9840939 0 -0.1776497 1 -3.20299e-6 0 1 0 -9.43902e-7 1 1.16446e-4 2.89373e-6 1 0 -1.35804e-7 -0.2502828 0.006941139 0.9681479 -0.2266163 0.002441048 0.9739812 -0.2018269 4.53258e-4 0.9794212 -0.3704661 -0.01064956 0.928785 -0.2659224 0.01062595 0.963936 -0.2387338 0.002774357 0.9710811 -0.3667802 -0.004983305 0.9302943 -0.3274753 -0.02586853 0.9445056 -0.3480898 -0.01759034 0.9372963 -0.4836029 -9.80827e-7 0.8752875 -0.4826921 9.98973e-4 0.8757897 -0.4235301 -7.70095e-4 0.9058818 -0.3956167 -0.005375862 0.9184 0 -7.6294e-4 0.9999998 -5.27214e-6 -7.62939e-4 0.9999998 0 0.01934748 0.9998129 0.001108467 0.08196389 0.9966347 0.00230652 0.09486025 0.9954879 -0.001431345 0.03744268 0.9992979 0.4271764 -0.009436666 0.9041191 0.4024119 -0.01783233 0.9152851 0.3799861 -0.0262202 0.9246206 -0.1872017 -2.61769e-5 0.9823215 0.003326833 8.10658e-4 0.9999942 0 -0.002331018 0.9999974 0.2053404 2.68649e-4 0.9786907 0.2387363 0.004386186 0.9710746 0.2494528 0.002137124 0.9683847 0.320683 -0.002155363 0.9471841 0.3667538 -0.01214009 0.9302389 0.4830197 0.02945572 0.8751139 0.4835959 0 0.8752915 0.4825879 0.001111567 0.8758468 0.572119 -0.002000689 0.8201682 0.5222215 0.01347118 0.8527035 0.5518486 0.006364703 0.8339201 0.6911008 1.62624e-5 0.7227584 0.6819874 0.003219842 0.7313569 0.6236087 -3.94756e-4 0.7817366 0.5882098 0.001006722 0.8087078 -0.6321077 -0.00390917 0.7748708 -0.6815338 0.006247639 0.73176 -0.7113431 0 0.702845 -0.5689878 0.003546118 0.8223384 -0.5465726 0.007440149 0.8373787 -0.5716111 0.00137633 0.8205236 -0.5204967 -2.18647e-4 0.8538636 -0.4813439 0.001229822 0.8765311 0.2374853 -0.9711472 0.02176797 0.1729357 -0.9833959 -0.05500817 0.5710471 -0.8138325 0.1076191 0.5360773 -0.8424072 0.05450922 0.7693889 -0.6363195 0.0560196 0.8359234 -0.5321295 0.1344258 0.8844972 -0.4610893 0.0711432 0.9608067 -0.2733651 0.04606705 0.9774698 -0.1723708 0.1218242 0.9769566 -0.1701293 0.1288874 0.9775791 -0.1719575 0.1215314 -0.8560658 -0.3604047 0.3704862 -0.9775795 -0.1719548 0.1215314 -0.9804657 -0.1934065 0.03579217 -0.9045231 -0.4213377 0.06567049 -0.9022591 -0.4266539 0.06240975 -0.7920749 -0.6078324 0.05618989 -0.7918872 -0.6081066 0.05586868 -0.6078049 -0.7921473 0.05546116 -0.6219009 -0.7800757 0.068713 -0.4221128 -0.9063093 0.02059775 -0.04983156 -0.9987473 0.004565775 -0.1730678 -0.9841269 0.03926479 -0.2209836 -0.9750617 0.02051597 -0.4474567 -0.8934746 0.03854429 -0.9999991 0 0.001442253 -0.9986428 -1.1243e-4 0.05208224 -0.7496441 -0.03212738 0.661061 -0.8156411 2.35541e-4 0.5785582 -0.9099553 -1.71243e-4 0.4147065 -0.8880226 -0.008808016 0.4597154 -0.9845359 0.02908402 0.1727518 -0.9337037 -0.0614795 0.3527292 -0.9738503 -0.01302522 0.2268174 -0.6672956 -0.07482248 0.7410252 -0.7916045 0.08711588 0.604792 -0.542695 -0.03602927 0.8391568 -0.616673 0.002039968 0.7872168 -0.4286544 -0.001928687 0.9034666 -0.425632 -0.003351628 0.9048902 -0.1923612 0.004307031 0.9813148 0.2887831 0 0.9573946 0.2048385 0.05742818 0.9771097 0.03902977 0 0.9992381 -0.1846898 0 0.982797 4.2562e-5 -1 1.07512e-4 -1.82108e-4 -1 4.56898e-4 0 1 3.17757e-7 0 1 -5.92945e-7 0 1 -8.68143e-7 -0.8880801 0.08635252 -0.4515053 -0.9287958 0.05565696 -0.3663887 -0.9545998 0.03331524 -0.2960228 -0.9659268 0 -0.258816 -0.7071091 0 -0.7071046 -0.7071092 0 -0.7071045 -0.2587999 0 -0.965931 -0.2588235 0 -0.9659246 0.2588235 0 -0.9659247 0.2588 0 -0.9659309 0.7071091 0 -0.7071046 0.7071092 0 -0.7071045 0.9289531 0.2327237 -0.2878994 0.8914298 0 -0.4531589 0.9657714 0.01783221 -0.2587811 0.9498174 0.03596097 -0.3107311 0.9655774 0.02687466 0.2587243 0.9894273 0 0.1450299 0.9939079 0 -0.110214 0.7068361 0.0270937 0.7068583 0.7879603 0 0.6157262 0.9181727 0 0.3961805 0.2587227 0.0272057 0.9655685 0.3799402 0 0.9250112 0.6017621 0 0.7986754 -0.2587227 0.02720403 0.9655686 -0.1277423 0 0.9918074 0.127565 0 0.9918302 -0.7068484 0.02710062 0.7068458 -0.6018638 0 0.7985989 -0.3801038 0 0.9249439 -0.9938882 0 -0.110392 -0.9894544 0 0.1448451 -0.9655754 0.02688503 0.2587305 -0.9182396 0 0.3960255 -0.7880738 0 0.6155809 -0.225041 0.9274713 0.2985862 -0.4481568 0.8790611 -0.162503 0.8238561 0.4951484 -0.2758428 0.683052 0.7020647 -0.2013583 0.4829881 0.8557978 -0.1852909 0.4006889 0.9066979 -0.1317096 0.3764165 0.9198604 -0.1103067 0.9252329 0.2831768 -0.2524974 0.9985896 0.007774949 -0.05252081 0.9728366 -0.0761674 -0.2186037 0.9937817 -0.1057353 0.0349009 0.9920046 -0.1157149 -0.0503683 0.9873983 -0.1158003 -0.1078662 0.8442556 -0.5026115 0.1860486 0.8817738 -0.453245 0.1305525 0.9716224 -0.2303172 0.05388838 0.7875378 -0.5000951 0.3601238 0.8061819 -0.3300993 0.4910247 0.6702757 -0.5010347 0.5474438 0.4265639 -0.4912589 0.759413 0.3950373 -0.2266228 0.890274 0.5395002 -0.5020102 0.6759626 -0.4456167 -0.416068 0.7926621 -0.4062385 -0.4811434 0.7768342 -1.47189e-4 -0.506345 0.862331 -0.05326902 -0.3571463 0.9325284 0.1763839 -0.5032005 0.8459775 -0.8029111 -0.3414248 0.4886338 -0.694601 -0.4987393 0.5184483 -0.5768668 -0.5034077 0.6432772 -0.9768627 -0.2088 0.04628044 -0.9990921 0.001724839 0.04256802 -0.8817144 -0.453391 0.1304467 -0.8442834 -0.5026218 0.1858954 -0.8014883 -0.501991 0.3249949 -0.9282405 0.2263836 -0.2951614 -0.9483416 0.06171751 -0.31119 -0.901656 0.2576199 -0.3473451 -0.97112 -0.03599721 -0.2358605 -0.9773634 -0.07313799 -0.1985238 -0.982526 -0.1018645 -0.1557762 -0.4272775 0.9016773 -0.06642407 -0.3885307 0.9130584 -0.1239688 -0.3449451 0.9358125 -0.07257986 -0.355799 0.9280277 -0.1103252 -0.3264812 0.9240836 0.198695 -0.3981518 0.862991 0.3110011 -0.3431088 0.9275664 0.1479765 -0.3819683 0.92408 0.01327824 -0.4921315 0.8675346 0.07204514 -0.3711478 0.9276582 -0.04122686 -0.1951056 0.8582162 0.4747619 -0.1872893 0.9240816 0.3331606 -0.04778826 0.9273771 0.3710637 -8.10323e-5 0.9008056 0.4342228 0.04771286 0.9273809 0.3710636 0.1422495 0.9272744 0.3463056 0.212592 0.9008688 0.3784706 0.2249682 0.9274801 0.2986136 0.2951893 0.9271752 0.2306717 0.3704316 0.9010428 0.2256157 0.3430716 0.9275708 0.1480352 0.3709337 0.9270664 0.05437064 0.4328562 0.9013349 0.01520156 0.3711649 0.9276545 -0.04115772 0.3605085 0.9284006 -0.09003299 0.2885563 0.953279 -0.08941256 -0.6420768 0.7300562 -0.2339985 -0.67754 0.7059061 -0.2064857 -0.7184946 0.6950839 0.02497786 -0.71849 0.6950888 0.02497702 -0.6141275 0.695092 0.3737573 -0.6141376 0.6950882 0.373748 -0.3522968 0.695092 0.626685 -0.3522946 0.6950959 0.626682 -1.39082e-4 0.695097 0.718916 -1.17049e-4 0.6950809 0.7189315 0.3520827 0.6950803 0.6268183 0.352064 0.6950922 0.6268156 0.6140111 0.6950815 0.3739683 0.6140074 0.6950839 0.3739696 0.7184781 0.6950918 0.0252335 0.7184875 0.6950821 0.02523195 0.6777729 0.7059452 -0.2055853 0.7887923 0.555114 -0.2639229 -0.8419905 0.4522225 -0.2941883 -0.9174318 0.3221177 -0.2335788 -0.9492586 0.3127606 0.03299957 -0.949257 0.3127654 0.03299915 -0.8113877 0.3127648 0.4937897 -0.8113874 0.3127527 0.4937979 -0.4654587 0.3127515 0.8279703 -0.4654534 0.3127513 0.8279733 -1.65063e-4 0.312747 0.9498366 -1.69339e-4 0.3127674 0.9498298 0.4651607 0.3127674 0.8281317 0.4651474 0.3127698 0.8281383 0.8112089 0.31277 0.4940802 0.8112099 0.312765 0.4940816 0.9492484 0.312756 0.0333352 0.9492457 0.3127641 0.03333741 0.9007849 0.3209773 -0.2925067 0.9416044 0.1408153 -0.3058631 0.9319513 0.05030351 -0.3590771 -0.9889059 -0.1157525 -0.09309369 -0.9920046 -0.1153141 -0.051279 -0.9937255 -0.1063781 0.03454488 -0.9912828 -0.1247225 0.04246044 -0.8475974 -0.1244615 0.5158371 -0.8476003 -0.1244701 0.5158305 -0.4862228 -0.1244686 0.8649249 -0.4862388 -0.1244505 0.8649184 -1.68864e-4 -0.1244511 0.9922258 -1.73528e-4 -0.1244732 0.992223 0.4859272 -0.1244714 0.8650906 0.4859006 -0.1244705 0.8651056 0.8474208 -0.1244696 0.5161253 0.8474114 -0.1244606 0.5161431 0.9912479 -0.1247349 0.04322981 0.9987657 -0.02496302 0.04294097 0.1887304 -0.9054033 0.3802968 0.2512668 -0.7702574 0.5861472 0.305617 -0.7680027 0.5628234 0.3836557 -0.7529866 0.5346211 0.4209162 -0.7380548 0.5273563 0.4613611 -0.7347304 0.4973099 0.5498538 -0.7042411 0.4491163 0.5753772 -0.7230031 0.3823711 0.6982008 -0.6407613 0.3192816 0.6893012 -0.6691061 0.2777785 0.7357788 -0.6575209 0.1621599 -0.2010462 -0.8969665 0.3937405 0.01860862 -0.9448136 0.3270797 0.05525648 -0.9402478 0.3359773 -0.02757698 -0.9939184 0.1066105 0.2709768 -0.9619737 0.03432279 -0.4326673 -0.7439509 0.5092507 -0.4515334 -0.7366066 0.503516 -0.5708852 -0.697426 0.4332289 -0.5811671 -0.6885374 0.4337756 -0.6439082 -0.687301 0.3361539 -0.3167329 -0.7522673 0.577732 -0.2334571 -0.7355923 0.635926 -0.305333 -0.7522163 0.5839028 -0.2065551 -0.7911089 0.5757446 0 -0.7743604 0.6327448 -1.13611e-5 -0.9505358 0.3106151 -0.06082761 -0.9432286 0.3265272 -0.7386433 -0.6541802 0.1626482 -0.6856955 -0.6726919 0.2780418 -0.7299219 -0.6262606 0.2738827 -0.6760965 -0.6741884 0.2972603 0.2165283 -0.7689073 0.6015788 0.2580503 -0.7715 0.5815478 0.2037901 -0.7903742 0.5777354 0.1253697 -0.7894176 0.6009179 -0.03491377 -0.7909529 0.6108802 -0.5859251 -0.6613508 0.4683022 -0.3206573 -0.8728213 0.3679154 -0.4188065 -0.7444111 0.5200513 0.187321 -0.9691945 0.1599155 0.1778501 -0.9755126 0.1294004 0.187375 -0.9817487 0.032561 0.8444258 -0.1321479 0.5191165 0.856533 -0.1384295 0.4971806 0.9417151 -0.1232246 0.3130311 0.9779899 -0.1334344 0.1604091 0.9051372 -0.1644896 0.3920075 0.5307915 -0.06144094 0.8452724 0.599871 -0.08926796 0.7951013 0.6671044 -0.1164494 0.7358065 -0.06437081 -0.08061271 0.9946648 0.09331548 -0.1069106 0.98988 0.3197569 -0.1364797 0.9376188 0.2376896 -0.1025336 0.9659143 0.5238342 -0.1344167 0.841148 0.635801 -0.1818521 0.7501247 -0.1248871 -0.01404976 0.9920716 0.01900464 -0.181833 0.9831458 -0.3245248 -0.03362458 0.9452794 -0.2580136 -0.2223102 0.9402166 -0.3332176 -0.1623933 0.9287596 -0.09261447 -0.8142537 0.5730737 -0.1294357 -0.8702486 0.475304 -0.1029931 -0.9047851 0.4132267 0.05437755 -0.9340835 0.35289 0.06191855 -0.921202 0.3841267 0.09303855 -0.9564305 0.2767394 -0.388678 -0.6325004 0.6699798 -0.6406996 -0.6420444 0.42105 -0.6251411 -0.7183817 0.3051663 -0.5931849 -0.7314195 0.3363884 -0.578151 -0.672181 0.4625087 -0.4321648 -0.7379131 0.5183802 -0.5189245 -0.7353259 0.4359051 -0.4373634 -0.6627928 0.6077985 -0.6485752 -0.5723478 0.5017651 -0.5874319 -0.4454698 0.6756335 -0.9234065 -0.2592294 0.2830559 -0.2594264 -0.3229104 0.9101795 0.5294223 -0.8003593 0.2813134 0.5063555 -0.8549512 0.1125283 0.4139359 -0.8105894 0.4142487 0.4253454 -0.8547849 0.2973618 0.2641275 -0.7838103 0.5620304 0.3010708 -0.8503403 0.4315994 0.08999973 -0.7612098 0.6422303 0.1486552 -0.8426295 0.5175685 -0.08668196 -0.7441254 0.6623924 -0.01173722 -0.8338918 0.5518034 -0.2483705 -0.7345471 0.6314688 -0.1582938 -0.8246383 0.5430606 -0.3212739 -0.7631942 0.5606405 0.8694573 -0.4707338 -0.1498459 0.8950282 -0.4326842 0.1082085 0.7574386 -0.3708173 0.5373837 0.8287654 -0.446086 0.3378688 0.582715 -0.3427608 0.7368571 0.7039527 -0.4552104 0.5451918 0.3811443 -0.3223628 0.8664938 0.5305989 -0.4582577 0.7130671 0.1672115 -0.3086908 0.9363495 0.3276857 -0.4573406 0.8267174 -0.04522293 -0.3023636 0.9521193 0.1229851 -0.4532199 0.882874 -0.239481 -0.2995429 0.9235383 -0.07533383 -0.4500071 0.8898418 -0.4163205 -0.303043 0.8572295 -0.2526103 -0.4454936 0.8589084 -0.5629398 -0.3090263 0.7665519 -0.7444324 -0.1162959 0.657492 -0.494018 -0.110474 0.8624046 -0.7025486 -0.3105404 0.6403048 -0.4107675 -0.4428917 0.7969424 -0.4719341 -0.5009428 0.7254891 -0.429044 -0.5626742 0.7066252 -0.2194967 -0.6522761 0.7255048 -0.2811433 -0.5594143 0.7797526 -0.05177348 -0.6561598 0.7528438 -0.1096124 -0.5629007 0.8192241 0.1322597 -0.6631063 0.7367479 0.08451259 -0.5700835 0.8172286 0.3266225 -0.6696497 0.6669986 0.2841712 -0.5837172 0.7606058 0.5044322 -0.6744248 0.5391656 0.4718049 -0.6020163 0.6441867 0.6441001 -0.6751095 0.3596698 0.6284413 -0.6247964 0.4633477 0.7367997 -0.6709768 0.0831654 0.7547057 -0.6289442 0.1866773 0.745777 -0.08495908 0.6607562 0.7241801 -0.1118508 0.6804798 0.6634073 -0.3123581 0.6799436 0.6841796 -0.119718 0.7194206 0.3906339 -0.2220905 0.8933539 0.5856571 -0.0956428 0.8048965 0.2495796 -0.2430035 0.9373684 0.4527673 -0.08508628 0.8875597 0.07973664 -0.2471387 0.9656939 0.284017 -0.08922111 0.9546591 -0.1165487 -0.2398346 0.9637925 0.1085833 -0.08983349 0.99002 0.02734249 -0.1258102 0.9916775 -0.3652574 -0.2154841 0.9056234 -0.1428938 -0.1050129 0.9841513 -0.5102686 -0.2560132 0.8210257 -0.3212597 -0.09464609 0.9422496 -0.7054197 -0.2519969 0.6624807 -0.5459146 -0.1145544 0.8299727 -0.8633057 -0.2345243 0.4468801 -0.7472312 -0.1361007 0.6504785 -0.9424211 -0.2177658 0.2538121 -0.8716219 -0.1580802 0.4639893 -0.9722083 -0.2059574 0.1113222 -0.9543904 -0.1807277 0.2376481 -0.9820165 -0.1882887 0.01381605 -0.9810115 -0.186358 0.05373322 -0.5487885 -0.8348793 0.04251956 -0.1872169 -0.9805341 0.0591855 -0.2025862 -0.9578297 0.2037674 -0.1524704 -0.9806638 0.1226838 -0.08902597 -0.9316444 0.3522969 -0.08708745 -0.9350955 0.3435292 0.3080463 -0.8580798 0.4108608 0.2890588 -0.86604 0.4079459 0.2860772 -0.8730961 0.3947951 0.100484 -0.8487986 0.5190801 0.1160849 -0.8788775 0.462708 0.0767225 -0.9124598 0.4019092 -0.5437417 -0.8349558 0.08481812 -0.5249461 -0.8192998 0.2306068 -0.5265818 -0.8260873 0.2007274 -0.4166746 -0.8154325 0.4018111 -0.4207316 -0.8172464 0.393819 -0.2535098 -0.7948618 0.5512962 -0.2825545 -0.8076046 0.5176271 -0.04890382 -0.7668982 0.6399028 -0.1200913 -0.798088 0.590452 0.1451565 -0.7454984 0.6505089 0.04603403 -0.7894578 0.6120762 0.3146546 -0.7326965 0.6034471 0.16596 -0.7968248 0.5809713 0.3846755 -0.7146201 0.5842457 0.3056682 -0.7682172 0.5625029 0.4468903 -0.7013829 0.5552937 0.3840821 -0.7545644 0.5320841 0.5123718 -0.6955282 0.5037019 0.4613535 -0.7415741 0.4870533 0.5656653 -0.6887909 0.4534203 0.6021493 -0.64529 0.4701244 0.5854874 -0.6082379 0.5359583 -0.8354607 -0.5486367 0.03167641 -0.8303228 -0.5479486 0.1015694 -0.8267931 -0.5462633 0.1342002 -0.7853526 -0.5434459 0.296459 -0.7917169 -0.5462668 0.2734538 -0.6816238 -0.5259108 0.5087308 -0.7151352 -0.5409132 0.4427127 -0.4959752 -0.5071331 0.704858 -0.5688967 -0.5381515 0.6218919 -0.2604447 -0.4821593 0.8364754 -0.3827614 -0.5341839 0.7537515 -0.02808767 -0.4647664 0.8849878 -0.1765269 -0.5290849 0.8300045 0.1893988 -0.4554897 0.8698605 0.01857626 -0.5302225 0.847655 0.3510502 -0.4493929 0.8214682 0.1782293 -0.5270718 0.8309211 0.4854428 -0.4524856 0.7480656 0.3268236 -0.525341 0.7856228 0.5965439 -0.4600523 0.6576377 0.459754 -0.5242496 0.7167906 0.6841156 -0.4730088 0.5552014 0.7509839 -0.4319698 0.4994249 0.7117861 -0.3904346 0.5838848 0.9858614 -0.1675543 0.001731812 0.1873497 -0.9822396 0.01027572 0.1106334 -0.8916996 -0.4388988 0.4472334 -0.6688227 0.5938507 0.4634221 -0.8610429 -0.2093929 0.7635054 -0.6380582 0.09970647 0.7348729 -0.485069 0.4739935 0.8775467 -0.4701344 0.09426391 0.9761623 -0.1884554 -0.107666 -0.9858665 -0.1675248 0.001710176 -0.9761812 -0.1883895 -0.1076088 -0.8276398 -0.5406536 0.1506851 -0.8195579 -0.5409274 0.1890048 -0.5419332 -0.8281638 -0.1430146 -0.4255144 -0.7906494 0.4402401 -0.1772027 -0.9355463 -0.305536 -0.1231026 -0.9923398 0.01037681 0.9999296 -0.01186984 0 0.9999285 -0.01196748 0 0.9979417 -0.06285053 -0.01273745 0.9782232 -0.166207 -0.1243173 -0.999929 -0.01191753 0 -0.9999278 -0.0120151 0 -0.9829406 -0.1791005 -0.04184329 -0.9858741 -0.1674885 0 -0.8960299 -0.4439938 0 -0.6427934 -0.5491176 -0.5341224 -0.8345786 -0.550889 0 -0.4738169 -0.8806235 0 0.9723103 -0.1380966 -0.1885263 0.9667901 -0.2555717 0 0.8345829 -0.5508825 0 0.8345786 -0.550889 0 0.4739322 -0.8805614 0 0.4738169 -0.8806235 0 0.1231186 -0.992392 0 0 -0.9529009 0.3032819 -0.1231186 -0.992392 0 -0.4739322 -0.8805614 0 -0.00117731 0 -0.9999994 2.46548e-5 0 -1 -2.7772e-4 0 -1 2.7772e-4 0 -1 1.41098e-4 0 -1 -9.10003e-4 0 -0.9999996 -1 -3.33369e-6 0 -1 8.15643e-6 2.66107e-4 -1 4.5372e-5 0 -0.8988547 -0.2508466 0.3593555 0.4302737 -0.2206004 0.8753286 0.4300279 -0.5164245 0.740528 0.1419785 -0.558847 0.8170264 0.2509512 -0.5535905 0.7940788 0.4304875 -0.5161691 0.7404391 0.4309149 -0.2204141 0.87506 0.1421616 -0.2417883 0.9598586 0.1418517 -0.2418081 0.9598995 -0.1833977 -0.2401385 0.953257 -0.1835095 -0.2401732 0.9532268 -0.4118138 -0.5211365 0.7475468 -0.2450833 -0.5544305 0.7953245 -0.1835857 -0.5531412 0.8126076 -0.07907533 -0.569986 0.8178405 0.09458541 -0.569228 0.816721 -0.5603619 -0.4738472 0.679311 -0.4995371 -0.485724 0.7173109 -0.499501 -0.2117201 0.8400438 -0.4992315 -0.2117011 0.8402086 -0.7546704 -0.375575 0.537974 -0.7540341 -0.3757739 0.5387271 -0.7548726 -0.160436 0.6359463 -0.7545136 -0.1603987 0.6363817 -0.7590558 -0.08474344 0.6454866 -0.4991011 0.09817647 0.8609643 -0.5538734 -0.03752768 0.8317547 -0.185982 -0.02643883 0.9821974 -0.1454375 0.04308897 0.9884288 0.1442878 -0.08502018 0.9858766 0.2901554 0.08609706 0.9530988 0.4359429 -0.07338476 0.8969775 0.626075 0.02273482 0.7794315 0.7311252 -0.1667218 0.6615587 0.7817113 -0.1694163 0.600188 0.4749112 -0.5033924 0.7218418 0.6140462 -0.479328 0.6270502 -0.9535128 -0.1726638 0.2469829 -0.9191945 -0.2178665 0.3280483 -0.9189621 -0.09652405 0.3823503 -0.918816 -0.09654295 0.3826967 -0.9205178 -0.06047582 0.3859917 -0.8504739 0.1214606 0.511802 -0.9916219 -0.07394248 0.1059184 -0.9916592 -0.07384222 0.1056384 -0.9916967 -0.03150367 0.1246808 -0.9916768 -0.03152304 0.1248342 -0.9919317 -0.004323661 0.1267006 -0.9859402 0.04932582 0.1596524 0.5048919 -0.583711 0.6358975 -0.7767673 -0.3251937 0.5393345 -0.628006 -0.09932368 0.7718442 -0.6202676 -0.5303974 0.5778813 -0.4356441 -0.6086472 0.6631461 -0.4358606 -0.6086471 0.663004 -0.2590598 -0.6531941 0.7114953 -0.1442372 -0.6447005 0.7507043 -0.100264 -0.6727837 0.7330138 0.05356258 -0.6752101 0.7356782 0.1863875 -0.6412264 0.7443712 0.2221796 -0.6592587 0.7183413 0.5049667 -0.58362 0.6359217 -0.794731 -0.3099234 0.5218717 -0.4315002 -0.460631 0.775646 -0.4310984 -0.4606226 0.7758743 -0.1424311 -0.5052767 0.8511222 -0.1420763 -0.5052698 0.8511855 0.1840068 -0.5017314 0.8452261 0.1836163 -0.501818 0.8452596 0.5002173 -0.4420406 0.7445688 0.4998964 -0.4422821 0.744641 -0.5338261 -0.1546434 0.8313335 -0.4307187 -0.1724272 0.8858613 -0.399534 -0.1681286 0.9011689 -0.1420601 -0.1815373 0.973069 -0.1901593 -0.194103 0.9623739 0.1827251 -0.1609684 0.9698973 0.1347612 -0.1815273 0.9741085 0.4989644 -0.1590903 0.8518948 0.544066 -0.1373695 0.8277209 0.9209579 -0.263493 0.2870678 0.9209228 -0.2635924 0.2870893 0.9192149 -0.2011843 0.3384804 0.9190115 -0.2015653 0.3388057 0.9917077 -0.06576025 0.1104146 0.9917345 -0.06559354 0.1102738 0.9919336 -0.08572286 0.09337782 0.991931 -0.08574753 0.09338366 0.7594329 -0.4399461 0.4792798 0.7594053 -0.4399525 0.4793179 0.7555645 -0.3345122 0.5632264 0.7551257 -0.3349573 0.5635502 0.7554153 -0.1313225 0.6419518 0.9135576 -0.01931846 0.4062504 0.8491898 -0.1173675 0.5148802 0.9912934 -0.01145529 0.1311721 0.9865339 -0.03009051 0.1607654 -0.1715823 -0.8536717 0.491736 0.9914031 -0.06613272 0.1129008 -0.1786319 -0.9632487 0.2006058 -0.1979088 -0.949862 0.2420626 -0.1494839 -0.9544659 0.2581659 -0.4128372 -0.8595994 0.3010885 -0.4278699 -0.824474 0.3703649 -0.4223012 -0.7941735 0.4369785 -0.3939076 -0.8091265 0.4360633 -0.5342438 -0.6649314 0.5219672 -0.5744974 -0.6837207 0.4499764 -0.5655663 -0.7339098 0.3761798 0.2199475 -0.7862195 0.5774791 0.7534673 -0.3777744 0.5381204 0.8593696 -0.3131554 0.4042494 0.6943348 -0.5471975 0.4674122 0.6435728 -0.6117359 0.4599928 0.4543336 -0.7553659 0.4722325 0.3891725 -0.8022513 0.4527006 0.08081227 -0.9068939 0.4135373 0.1528095 -0.9533655 0.260276 -0.06794792 -0.9881216 0.1378366 -0.07052969 -0.9882929 0.1352875 0.005916714 -0.999243 0.03845131 0.2264471 -0.9673313 0.1139822 0.1184481 -0.9606567 0.2512152 0.3889892 -0.8366597 0.3856009 0.411432 -0.8164396 0.4051545 0.6090025 -0.6286503 0.4836475 0.6254919 -0.6003837 0.4982963 0.7719847 -0.3474274 0.5322911 0.8147231 -0.3741674 0.4429731 -0.6205344 -0.5720522 0.5363705 -0.5021916 -0.6725336 0.5436011 -0.434339 -0.6964691 0.5712096 -0.4077845 -0.7106443 0.5733207 -0.2577535 -0.7447819 0.6155186 0.16636 -0.7693924 0.6167332 -0.09900385 -0.8080582 0.580724 0.05346834 -0.8059611 0.589549 0.694945 -0.5486526 0.4647923 0.503499 -0.6675301 0.5485366 0.435156 -0.7087764 0.5552254 0.1230366 -0.7909562 0.599375 0.1648309 -0.8964362 0.4113792 -0.1388243 -0.9293572 0.3420866 -0.002291977 -0.9132373 0.4074218 -0.4001916 -0.8648049 0.3032477 -0.3668223 -0.9083217 0.2009804 0.07977962 -0.9820848 0.1707187 0.4365866 -0.8444787 0.3102387 0.4328246 -0.8390684 0.3295865 0.6111744 -0.5415868 0.5771912 0.7112216 -0.6223847 0.3268046 0.5986287 -0.1731566 0.7820872 0.8868215 -0.3671518 0.2806196 0.8148585 -0.1930299 0.546576 0.8301257 -0.1541111 0.5358556 0.9586722 -0.06288141 0.2774773 0.8896576 -0.2294331 0.3948036 0.9950194 -0.02338099 0.09690058 0.8698852 -0.3374211 0.3597873 0.9210858 -0.2729617 0.2776559 0.7594523 -0.4796432 0.4395166 -0.7671297 -0.1773746 0.6164821 0.1404752 -0.9700855 0.1979925 0.3799684 -0.8332741 0.4015948 0.451115 -0.7662066 0.4576273 0.4532676 -0.7635012 0.4600157 0.9531084 -0.2820176 0.1097742 -0.9032101 0.1329863 0.4080765 -0.923031 -0.2526312 0.2901574 -0.9866417 -0.01702129 0.1620143 -0.5206742 -0.6668968 0.5330545 -0.759311 -0.4839072 0.4350639 -0.7904945 -0.4571403 0.4076043 -0.9014954 -0.2951416 0.3165398 -0.9545513 -0.1893451 0.2301747 0.6148553 -0.6202227 0.4871107 0.4335291 -0.7098894 0.5550762 0.4615958 -0.692593 0.5542961 0.2530807 -0.7500274 0.6110723 0.2911145 -0.7399957 0.6063488 0.09561383 -0.7741683 0.6257168 0.1001332 -0.7730163 0.6264337 -0.08016341 -0.7620686 0.6425149 -0.2475775 -0.7446126 0.6198851 0.6229959 -0.701398 0.3462902 0.2748619 -0.8442429 0.4601138 0.3342768 -0.8288701 0.4485906 0.08571588 -0.8661193 0.492433 0.1510013 -0.849357 0.5057582 -0.5303918 -0.7028914 0.4739498 -0.1888621 -0.7890959 0.5845159 -0.4147979 -0.7166453 0.5606803 -0.5637448 -0.6481196 0.511989 -0.8053627 -0.387111 0.4489279 -0.7264586 -0.497901 0.4736589 -0.7829292 -0.4405055 0.4392914 -0.464366 -0.7482511 0.4737979 -0.5394719 -0.7077593 0.4561217 -0.1449651 -0.8982758 0.4148324 -0.229892 -0.8818022 0.4117944 0.1935342 -0.9328131 0.303981 0.1061549 -0.9436949 0.3133227 -0.12589 -0.9185715 0.374671 0.2901493 -0.9203916 0.2620931 0.2450865 -0.9285802 0.2786962 -0.8247212 -0.1039257 0.5559087 -0.6572772 -0.5417512 0.5239203 -0.7050582 -0.4868478 0.515628 -0.366948 -0.8439907 0.3911892 -0.5016484 -0.7671614 0.3997655 -0.04357528 -0.9766309 0.2104598 -0.2292085 -0.9411856 0.2482605 -0.1357197 -0.9694123 0.2044991 0.09172642 -0.9857513 0.1409992 -0.9927582 0.07879132 0.09068191 0.9721832 0.01080304 0.2339727 0.991923 0.08358001 0.09541088 0.9861428 0 0.165899 0.994597 -0.04694783 0.09258931 0.3493193 2.65231e-4 0.9370037 0.3642654 -0.01649105 0.9311492 0.5688021 0.01448535 0.8223469 0.5896217 -0.002733826 0.807675 0.7169932 0.001122474 0.6970794 0.762937 -0.01648068 0.6462628 0.8522 0.01842045 0.5228919 0.8636752 0.012694 0.503889 0.9075348 -0.005454361 0.4199417 -0.6071209 -0.002233386 0.7946065 -0.576487 0.02153021 0.8168227 -0.3818548 -0.02436137 0.9239013 -0.3581558 -7.58083e-6 0.9336619 -0.2240369 -0.001999855 0.9745786 -0.1285039 0.03147017 0.9912096 -0.0950911 0.001414 0.9954677 0.1192067 9.63458e-4 0.992869 0.06280076 0.07133549 0.9954735 0.1793431 -0.00364989 0.9837799 -0.7237711 7.83955e-4 0.6900398 -0.7841346 -0.0188623 0.6203042 -0.7691721 -0.009759664 0.6389672 -0.8957352 0.01382511 0.444373 -0.8718222 0.03778815 0.4883628 -0.9145521 0.002256929 0.4044619 -0.9885224 -0.003178417 0.1510413 -0.9876734 4.31289e-5 0.1565291 0.8510579 -0.5153847 0.1003949 0.8891392 -0.4480326 0.09326452 0.9008464 -0.3743724 0.2198205 0.9421113 -0.1400329 0.3046593 0.9602491 -0.0578593 0.2730823 0.9341524 -0.2224011 0.2791004 0.7687471 -0.121777 0.6278523 0.8900617 -0.188103 0.41522 0.7428112 -0.5642063 0.3604204 0.8104969 -0.5242357 0.261289 0.8109969 -0.5236115 0.2609887 0.8722562 -0.2701812 0.4076412 0.8023027 -0.07779753 0.591826 0.793321 -0.1131371 0.5981989 0.81158 -0.2534192 0.5264189 0.7900153 -0.3176078 0.5244054 0.7940854 -0.355355 0.4931038 0.7643507 -0.5411122 0.3506649 -0.9996843 0 0.02512538 -0.987132 -0.00374639 0.1598643 -0.9861911 -0.00287652 0.1655867 -0.9356288 0.001294493 0.3529832 -0.8567514 -0.009526848 0.5156416 -0.8444258 -0.005876898 0.5356403 -0.6935148 0.003318428 0.7204348 -0.5541296 -0.008664667 0.8323854 -0.4840453 -8.87062e-4 0.8750424 -0.1455034 -0.006641745 0.9893355 -0.2403635 -0.001156091 0.9706823 -0.3531583 1.14056e-4 0.9355636 0.4186735 -4.07185e-4 0.9081369 0.2924345 -0.004351496 0.9562757 0.2912362 -0.004444301 0.9566409 0.08742821 0.001395106 0.9961699 -0.08234572 -0.002608537 0.9966005 0.4975482 1.02592e-4 0.8674364 0.626251 -0.001002967 0.779621 0.6404486 1.18792e-6 0.7680011 0.9197562 -0.3534911 0.1705661 0.8309875 -0.5313394 0.1647371 0.8236439 -0.5461491 0.1527485 0.5367103 -0.8378756 0.09953296 0.5330396 -0.840469 0.09736961 0.5343004 -0.8394635 0.09911698 0.3630349 -0.9294298 0.06607651 0.06181919 -0.9980733 0.005304753 0.1731458 -0.984329 -0.03342354 0.231169 -0.9725213 0.0276302 0.3357777 -0.9400976 0.05890601 0.7973024 -0.3782165 0.4703842 0.7554492 -0.5405626 0.3702549 0.7552475 -0.5351378 0.3784556 0.6649649 -0.6668404 0.3363715 0.582878 -0.7582288 0.2921342 0.9688523 -0.1704226 0.1796708 0.9688522 -0.170416 0.1796766 0.8460913 -0.1707658 0.5049442 0.842908 -0.1493893 0.5169035 -0.467464 0.8839265 0.01231354 -0.6499335 0.7574136 0.06253886 -0.5392661 0.8412685 -0.03820127 -0.4821683 0.8760765 -0.001968145 -0.4561228 0.889326 0.032422 0.7837365 0.61861 -0.05548751 0.4584663 0.8885751 0.01558685 0.4689375 0.8831043 0.01499104 0.4884344 0.872575 -0.006703019 0.4945794 0.8690748 -0.01001673 -0.8881838 -0.1565015 0.4320149 -0.8580549 -0.3582676 0.3679485 -0.8966054 -0.163181 0.4116681 -0.7898328 -0.2274488 0.5695887 -0.821806 -0.1746634 0.5423355 -0.8042003 -0.5400416 0.2482278 -0.8221076 -0.516933 0.2385784 -0.7658966 -0.5524687 0.3289088 -0.7588739 -0.558157 0.3355162 -0.7329711 -0.5581901 0.3888152 -0.8683315 -0.4820391 0.1167855 -0.8673131 -0.4685252 0.1680837 -0.9208906 -0.3047665 0.2430594 -0.923008 -0.2628774 0.2809836 -0.9430461 -0.09778952 0.3179643 -0.9408584 -0.1094514 0.3206339 -0.8198711 -0.299341 0.4880639 -0.8236673 -0.4304264 0.3691956 -0.3968635 -0.8996233 0.1821466 -0.5721343 -0.7940642 0.2052426 -0.8200107 -0.5654236 0.0887618 -0.9567568 -0.2889429 -0.03359574 -0.9837578 3.24316e-4 -0.1795006 -0.607344 -0.7491517 0.2643959 -0.2587704 -0.9657255 0.02030479 -0.1971915 -0.9634728 -0.1812064 -0.2625812 -0.9645078 -0.02785599 -0.3853706 -0.9210582 0.0560472 -0.9811456 -0.06515508 0.1819567 -0.9811477 -0.06514358 0.1819496 -0.8506611 -0.06512427 0.5216652 -0.8497341 -0.07118272 0.5223839 -0.9323958 -0.3173974 0.1729078 -0.9139617 -0.3569208 0.1930842 -0.8184129 -0.3579794 0.4495009 -0.727057 -0.5588627 0.3988242 -0.8345804 -0.5286964 0.1547765 -0.6721858 -0.7298132 0.1246555 -0.6523376 -0.7452985 0.1377893 -0.4089464 -0.9099085 0.06949353 -0.3981903 -0.9120454 0.09806966 -0.5900889 -2.46792e-6 0.8073383 -0.631157 0.004333496 0.7756431 -0.4054578 -0.001250326 0.914113 -0.2487068 0.002754271 0.968575 -0.1025439 -0.004996955 0.9947159 0.3137125 -2.43879e-4 0.949518 0.1049021 -0.003421127 0.9944767 0.1369976 7.00047e-6 0.9905714 -0.1941474 -9.81565e-6 0.9809724 0.911766 -0.02178215 0.4101321 0.779957 5.20985e-4 0.6258329 0.706114 -7.88449e-5 0.7080982 0.549245 -0.002602279 0.8356574 0.5994222 -0.01273542 0.8003318 0.4296578 9.55815e-4 0.9029914 0.8550262 0.01244467 0.5184356 0.986972 -0.005520701 0.1607978 0.9931574 0 0.1167839 -0.9874023 -0.002909362 0.1582031 -0.9859919 -0.04076641 0.1617348 -0.9821872 -0.07494372 0.1723133 -0.9444567 -0.2359321 0.2287739 -0.9700327 -0.05530983 0.2365955 -0.999997 -0.001902699 0.001534938 -0.9998664 -0.0142498 0.008017539 -0.9998113 -0.01176702 0.01545697 -0.9983526 -0.04008567 0.04105317 -0.9979375 -0.03641927 0.05286169 -0.9831292 -0.1112613 0.1451827 -0.9230029 -0.3847124 0.00788182 -0.9513931 -0.3079669 -0.002742588 -0.9859703 -0.04952394 -0.1594059 -0.9843626 -0.08944481 -0.1517563 -0.9842827 -0.09522134 -0.1487295 -0.9795536 -0.1435346 -0.1409699 -0.978914 -0.1601437 -0.1268121 -0.9687013 -0.2300469 -0.09325432 -0.9687778 -0.2176613 -0.1187149 -0.9680017 -0.2302459 -0.09979754 0.7056635 -0.1766172 0.6861818 -0.1082612 -0.9846463 0.1369351 -0.1203287 -0.9798577 0.1593736 -0.03647768 -0.9878966 0.1507641 -0.03773152 -0.9843496 0.172141 0.04164099 -0.9841983 0.1721041 0.03296458 -0.9880757 0.150399 0.1264752 -0.9789876 0.1599605 0.1061433 -0.9843846 0.14043 0.5645973 0.1225073 0.8162242 0.6107822 -0.173619 0.7725293 0.3439412 -0.1756542 0.9224154 0.2320453 0.1615945 0.9591884 0.1173452 -0.1756622 0.9774318 -0.1265568 -0.1754596 0.9763183 -0.2321789 0.1591643 0.9595623 -0.3525267 -0.1758424 0.9191324 -0.5676748 -0.1751909 0.8043965 -0.6201878 0.006606757 0.7844256 -0.7122787 -0.1772167 0.6791563 -0.3357164 -0.8408206 0.4246354 -0.3357301 -0.8408135 0.4246388 -0.1281572 -0.8384639 0.5296734 -0.128149 -0.838476 0.5296564 0.1281415 -0.8384663 0.5296736 0.1281658 -0.8384742 0.5296552 0.3357076 -0.8408176 0.4246484 0.3357353 -0.840816 0.4246295 -0.5240818 -0.5347439 0.662863 -0.5240713 -0.534766 0.6628534 -0.1992382 -0.5311626 0.8235111 -0.1992753 -0.531116 0.8235323 0.1992772 -0.5311136 0.8235332 0.199234 -0.5311676 0.8235089 0.5240668 -0.5347695 0.6628542 0.5240903 -0.5347313 0.6628665 0.9638867 -0.2510191 -0.08894836 0.9852831 -0.01443248 0.1703206 0.9883383 -0.00226289 0.1522577 0.9859213 -0.0677241 -0.1528813 0.9998964 -0.004749655 0.01359462 0.9986082 -0.03664946 0.03792858 0.9974787 -0.02394253 0.06680631 0.9916177 -0.08125776 0.1004568 0.9717184 -0.03769248 0.2331152 0.9676647 0.03669971 0.249556 0.9732431 -0.1625576 0.1623982 0.9772167 -0.1307039 0.1672241 0.9537566 -0.2932983 0.06576037 0.9311171 -0.3595997 0.06090229 0.8988238 -0.4356943 -0.04781424 0.9997572 0.003063797 0.02182549 0.9819575 -0.111739 -0.1525579 0.9741614 -0.212705 -0.07593584 0.9567372 -0.2192202 -0.1913022 0.9634241 -0.2350186 -0.1287644 0.7823472 1.37924e-6 0.6228426 0.852309 -0.01945567 0.5226766 0.8605117 -0.01444637 0.509226 0.999707 -9.27166e-5 0.02421104 0.9960195 -0.002299308 0.0891059 0.9895161 -0.009368896 0.144119 0.9851674 -0.01358741 0.1710576 0.983112 -0.01581144 0.1823211 0.9646921 -0.002935886 0.2633641 0.9191439 0.001923263 0.3939175 0.9848784 -0.1732474 0 0.9848768 -0.1732565 -8.53576e-7 0.933434 -0.3587493 0 0.8334276 -0.5526277 -0.001146793 0.8435829 -0.5369992 -2.26807e-6 0.5369514 -0.8436132 2.49102e-6 0.536872 -0.8436638 -3.67962e-6 0.1732454 -0.9848787 2.92302e-6 0.1731879 -0.9848888 0 -0.5096243 0.860391 -0.003245115 -0.9974278 0.06092923 0.03775399 -0.8126046 0.5792895 -0.06401294 -0.7265824 0.6791959 0.1037834 -0.6520532 0.758067 0.0126903 -0.4850834 0.872559 0.05774867 -0.9696482 0.2220129 -0.1024347 -0.9695748 0.2277649 -0.08970957 -0.8901556 0.4454995 0.09567284 -0.8919458 0.4463496 0.07214605 -0.7307097 0.6793931 0.06699573 -0.6775141 0.6727328 0.2973303 -0.456092 0.8815288 -0.1220133 -0.4962934 0.8518788 -0.167319 -0.4069664 0.9086785 -0.09317731 9.54913e-5 1 -4.61859e-5 2.66431e-6 1 1.35469e-5 3.22118e-6 1 1.1829e-5 -2.66431e-6 1 1.35469e-5 -3.22118e-6 1 1.23433e-5 3.18575e-5 1 1.61656e-5 -3.18284e-5 1 1.61528e-5 3.36612e-7 1 0 -2.04851e-4 1 -1.83652e-5 -8.09107e-5 1 -4.09733e-5 5.29462e-5 1 -5.0787e-5 9.53169e-6 1 2.87072e-5 -3.36578e-7 1 0 0.4240177 0.8942651 -0.1431747 0.3646751 0.9273887 -0.08344119 0.4423913 0.8962181 -0.03291243 0.8658689 0.4976715 -0.05093342 0.990327 0.1336006 0.03746175 0.8337978 0.5472869 0.07251566 0.7312324 0.6799693 0.05423212 0.7189093 0.6824889 0.1318269 0.5141577 0.8576815 -0.004926621 0.5054539 0.8628212 0.007485449 0.5578226 0.8171564 -0.1452221 0.7260557 0.6789543 0.1089231 0.781696 0.6228573 0.03162455 0.8631601 0.503722 0.03491395 0.9072621 0.417971 -0.04664719 0.9517701 0.2711935 0.1434854 0.9918227 0.05116075 -0.1169213 0.9827657 -0.02338838 -0.1833706 0.9843469 -0.001664638 -0.1762344 0.9999536 -0.001675188 -0.009494423 -0.1731942 -0.9848877 0 -0.2588177 -0.9659167 0.004297554 -0.997802 -0.06626671 0 -0.9848749 -0.1732555 -0.002019405 -0.9466494 -0.3222544 0.002668321 -0.9064746 -0.4222605 0 -0.844763 -0.5351406 0 -0.7933348 -0.6087849 -0.001043736 -0.6774625 -0.7355499 0.003315985 -0.6087352 -0.7933734 0 -0.4222118 -0.9064974 0 -0.9185964 0.001868903 0.3951928 -0.9832199 -0.005605995 0.1823383 -0.9663659 -0.03220063 0.2551474 -0.9772257 -0.02187579 0.2110718 -0.9823263 -0.01646482 0.1864513 -0.9886088 -0.01007771 0.1501705 -0.9953975 -0.003292381 0.09577548 -0.9992586 -3.59918e-4 0.03849756 -0.9999694 0 0.007832467 -0.8524719 -3.69483e-6 0.5227732 -0.7983504 -0.04860526 0.6002284 -0.8622552 -0.01415252 0.5062766 -0.9852728 -0.02014374 -0.1697994 -0.9656559 0.0845474 -0.2456837 -0.9943886 -0.001690566 -0.1057755 -0.9999527 -0.00168693 -0.009582936 -0.9747198 0.2232356 -0.009349465 -0.5877897 0.8090139 0 -0.6501052 0.7557542 -0.07873392 -0.4858274 0.8738617 0.01836919 -0.2468534 0.968538 -0.03158777 -0.5782477 0.8158611 -6.21316e-4 -0.8473158 0.5310888 7.6403e-4 -0.8142575 0.580497 -0.002872407 -0.9843201 0.1763668 0.002956688 -0.9749585 0.2223871 0 -0.5387792 -0.3122748 -0.782433 -0.4472015 0 -0.8944333 -0.20121 0 -0.9795482 -0.2012339 0 -0.9795433 0.2012327 0 -0.9795435 0.2012111 0 -0.9795479 0.4472399 0 -0.8944141 0.538876 -0.311868 -0.7825287 0.2599117 0.9643529 -0.04969465 0.9843248 0.1763661 -1.44374e-7 0.9909757 0.1337115 -0.009409248 0.9911614 0.1326433 -0.002222836 0.9082494 0.4184265 0.001533269 0.8473142 0.5310842 -0.002870142 0.7820893 0.6231665 -2.08287e-4 0.3695631 0.9291819 -0.006664872 0.5634194 0.8253875 0.0359745 0.5949014 0.8037988 0 0.5877897 0.8090137 4.62129e-4 -1 0 -1.35804e-7 0.8148012 2.50243e-4 0.5797405 0.7491602 -0.03140234 0.6616441 0.7936923 -0.005573868 0.608294 0.6337434 0.004452168 0.7735306 0.6142101 -0.0045771 0.7891293 0.5312893 7.34131e-5 0.8471905 0.4229115 -7.45714e-4 0.9061707 0.4289147 -0.003463864 0.9033383 0.1801899 0.004689753 0.9836207 0.1878469 0 0.9821983 -0.04354286 0 0.9990516 -0.209338 0.05440813 0.9763286 -0.2887626 -3.8904e-6 0.9574007 0.999999 0 0.001441121 0.9986428 -1.12024e-4 0.05208224 0.9738503 -0.01302582 0.2268174 0.9337038 -0.06147748 0.3527292 0.8831844 -4.91715e-5 0.469026 0.9093204 -0.002721726 0.4160878 0.9845359 0.02908402 0.1727518 -0.1411429 0.405157 0.9032865 0.1800293 -0.03878456 0.9828963 -0.04285168 0.1757904 0.9834945 -0.2843853 0.173965 0.9427945 0.6047141 0.175301 0.776911 0.5216129 0.02975177 0.8526635 0.7815087 0.1746281 0.5989568 0.8400203 0.04052805 0.5410391 0.8951715 0.1757884 0.4095931 0.9699626 0.1737958 0.1701993 0.9699628 0.1737973 0.1701962 0.584693 0.8047415 0.1025943 0.1349248 0.7636505 0.6313741 0.5846868 0.8047459 0.1025935 0.5023995 0.8018054 0.3235781 0.5024039 0.8018019 0.3235801 0.3118475 0.8018063 0.5097625 0.3118594 0.8018036 0.5097597 0.1227889 0.807162 0.5774189 0.1604558 0.8528584 0.4968768 -0.1443917 0.386523 0.9109067 0.09095913 0.4009924 0.9115544 0.09780603 0.1720353 0.9802234 0.4163783 0.175261 0.8921394 0.04929059 0.6360646 0.7700599 0.1771399 0.5286039 0.8301804 0.4453116 0.5213938 0.7279053 0.4452986 0.5213941 0.727913 0.7174016 0.5213907 0.4620463 0.7173905 0.5214 0.462053 0.8381032 0.5253155 0.1470608 0.8381031 0.525316 0.1470593 0 1 1.90263e-7 0 1 -1.1145e-6 0 1 -3.30245e-6 0 1 7.47317e-6 -0.3118458 0.8018072 0.5097623 -0.1818568 0.1747031 0.9676812 -0.9699642 0.1737906 0.170195 -0.9699612 0.1738014 0.170201 -0.5140638 0.1720408 0.8403217 -0.4230897 -0.1102709 0.8993529 -0.6070675 0.175366 0.7750587 -0.8281824 0.1720671 0.5333918 -0.7941392 -0.03484207 0.6067365 -0.89578 0.175823 0.408246 0.03842377 0.1757262 0.983689 0.2816009 0.2216266 0.9335859 0.1571722 0.1762572 0.9717152 0.1439088 0.3864435 0.911017 -0.09921658 0.0375387 0.9943576 -0.07869535 0.6097207 0.7887001 0.1440406 0.3864361 0.9109992 -0.3118607 0.8018026 0.5097602 -0.5024063 0.8018018 0.3235769 -0.5023977 0.8018051 0.3235816 -0.584688 0.804745 0.1025941 -0.584693 0.8047415 0.1025943 -0.8381032 0.5253155 0.1470603 -0.8381016 0.525318 0.1470606 -0.7173878 0.5214058 0.4620506 -0.717403 0.5213863 0.4620491 -0.4453052 0.5213921 0.7279105 -0.4453037 0.5213962 0.7279085 -0.1655775 0.5279587 0.832973 -0.126115 0.8073481 0.5764408 -0.1619169 0.8499501 0.5013659 -0.04773736 0.9464126 0.3194125 -0.04934555 0.1048492 0.9932632 0.04415589 0.01428079 0.9989227 -0.05073827 0.05105972 0.997406 0.07641905 0.07362949 0.9943535 0.04254132 0.1802751 0.9826958 0.0202353 0.213766 0.9766753 0.1932288 0.08874017 0.9771324 0.1377366 0.3888044 0.9109665 0.2270561 0.1691346 0.9590824 -0.4954147 0.8071845 0.3209637 -0.5761986 0.649576 0.4960304 -0.5778176 0.7424639 0.338931 -0.5036285 0.7024297 0.5029422 -0.5431435 0.6965628 0.4688235 -0.7209529 0.1580094 0.6747296 -0.8440247 0.174232 0.5072136 -0.8836687 0.1619159 0.4392188 -0.7940796 0.3275082 0.5120314 -0.7124923 0.5001423 0.4921509 -0.7932647 0.492268 0.3583345 -0.6113166 0.6110984 0.5028427 0.07158482 0.818331 0.5702719 -0.03810197 0.8850671 0.4639014 -0.1901032 0.84325 0.5027825 -0.2235528 0.8523185 0.4728398 0.1601429 0.6018555 0.7823837 0.08659809 0.6924521 0.7162478 -0.05739456 0.6537643 0.7545185 -0.2519442 0.755223 0.6051137 -0.6021839 0.1379675 0.7863458 -0.6323501 0.1370083 0.762471 -0.5253869 0.4122476 0.7443256 -0.4954329 0.4063776 0.7677263 -0.3604459 0.5594674 0.7463746 -0.3357892 0.5545595 0.7613865 -0.2227155 0.6388605 0.7363798 -0.3899226 0.7869285 0.47823 -0.3612422 0.7840829 0.504696 -0.5713133 0.7559884 -0.3195038 0.210005 0.1964433 0.957762 -0.2290672 0.8224555 0.520668 -0.1097276 0.9929857 0.0440393 0.188434 0.4246133 0.8855485 0.1909182 0.419867 0.8872779 0.03974717 0.37739 0.9252011 -0.0136941 0.4310838 0.9022081 -0.1192607 0.35297 0.9280028 -0.1463798 0.3620167 0.9206067 -0.2363035 0.2631537 0.9353668 -0.2714779 0.2734555 0.9227794 -0.3407384 0.09578305 0.9352663 -0.390524 0.09310525 0.9158725 -0.857235 9.6959e-4 0.5149247 -0.8283933 0.07971477 0.5544458 -0.05099296 -7.55123e-4 0.9986988 -0.05116748 0 0.9986901 -0.3919266 0 0.9199966 -0.4895132 0.1532769 0.858419 -0.6079745 0 0.7939566 -0.7302262 0 0.6832055 0.04840552 -7.54843e-4 0.9988275 0.04822862 0 0.9988364 0.2889459 0 0.9573455 0.4905859 0.0687049 0.8686802 0.5187769 0 0.8549097 0.8303479 0 0.5572454 0.7691616 0.1739512 0.614924 0.8952166 9.437e-4 0.4456303 -0.1674631 0.01508659 0.9857629 -0.1641817 0.04306399 0.9854897 -0.209428 0.03863668 0.9770605 -0.2429564 0.1692465 0.9551585 0.04800117 0.05212622 0.9974862 -0.04355728 0.02819722 0.9986529 -0.1259592 0.0273258 0.9916591 0.8938382 0.05534899 0.4449607 0.9779844 0.1843543 0.09777516 0.4242617 0.8143609 0.3960033 0.3803332 0.6817221 0.6249814 0.5645475 0.7126244 0.4164763 0.6676347 0.602741 0.4369979 0.8458024 0.5281198 0.0755499 0.7794568 0.4540055 0.4316552 0.8638076 0.2339417 0.4462151 0.04424947 0.9466972 0.3190713 0.02906894 0.9370053 0.3481037 -0.001794576 0.8836056 0.4682286 -0.06256675 0.7727768 0.6315866 -0.05951106 0.7979996 0.5997126 0.2095714 0.7175073 0.6642765 -0.2733374 -0.1116225 0.9554199 -0.2290445 0.198142 0.9530364 -0.1323371 0.1705453 0.9764226 -0.09930551 0.2630158 0.9596673 -0.03742629 0.2165919 0.9755446 -0.04661148 0.1824601 0.9821078 0.01853281 0.112158 0.9935176 0.09171545 0.1764073 0.9800352 0.1396053 0.05378913 0.9887452 0.2882564 0.08528316 0.9537479 -0.1473196 0.5190244 0.8419682 -0.1481208 0.5461117 0.8245134 0.0481103 0.488867 0.8710308 0.07299381 0.5508251 0.8314226 0.2260918 0.438888 0.8696321 0.2341354 0.4620651 0.855381 0.3587652 0.3239692 0.8754037 0.3833726 0.3460731 0.8563054 0.473937 0.1163009 0.8728448 0.5142139 0.1340197 0.8471262 0.2494839 0.8793584 0.4055696 0.2460379 0.8782609 0.4100283 0.32816 0.9237712 0.1973776 0.2995041 0.7200039 0.6260126 0.433036 0.6193503 0.6548932 0.4384416 0.6372122 0.6338215 0.6006593 0.4511787 0.660035 0.6188319 0.4676232 0.63117 0.7416455 0.154365 0.652789 0.7702339 0.1662831 0.6157027 -0.2885515 0.6173239 0.7318806 -0.05552619 0.992165 0.1119173 -0.124852 0.9579776 0.2582458 -0.2311594 0.7764087 0.5863062 -0.2365342 0.7654419 0.5984566 -0.1726308 0.8819178 0.4386569 -0.1672373 0.8900048 0.4241735 -0.06742179 0.982961 0.1710029 -0.1043229 0.9546037 0.2790139 -0.3615422 0.1685504 0.916994 -0.368167 0.09109729 0.9252861 -0.354411 0.2575181 0.8989313 -0.3134381 0.5193948 0.7949753 -0.3521414 0.349206 0.8683615 -0.3295828 0.4585346 0.8253008 0.5352163 0.3869875 0.7508558 -0.4705386 0.6230906 0.6247813 -0.891919 0.06066596 0.4481074 -0.535171 0.03604388 0.8439745 0.2453979 0.7457265 0.6194126 0.2561617 0.7396968 0.622278 0.2615734 0.8467619 0.4632211 0.2559004 0.8500708 0.4603203 0.2293752 0.8365682 0.4975348 0.2512798 0.8257666 0.5049437 0.2137491 0.818221 0.5336908 0.2764365 0.7897976 0.5475425 0.2082561 0.791579 0.5744842 0.2834529 0.7578815 0.5875969 0.3122366 0.8241717 0.4724929 0.3038583 0.8769186 0.3724029 0.401836 0.7006754 0.5895607 0.5608724 0.08193385 0.8238381 0.6033881 -0.1568602 0.7818681 0.3200101 0.2143245 0.9228535 0.2244235 0.0570476 0.9728205 0.01565331 0.1876996 0.9821017 0.01510477 0.1894915 0.9817662 -0.1384478 0.1348547 0.9811456 -0.2475721 0.1806048 0.9518876 -0.2656793 0.2150826 0.9397627 -0.3106003 0.1982551 0.9296356 -0.5963774 0.1450167 0.7894961 -0.6012326 0.1254901 0.7891589 -0.7713391 0.06846803 0.6327306 -0.7826552 0.2054259 0.5875808 -0.8387657 0.1730272 0.516269 -0.9699791 0.2045732 0.1314929 -0.6937787 0.4729691 0.5431126 -0.8273097 0.3534492 0.4366148 -0.8693844 0.2731997 0.4117437 -0.9607889 0.1579611 0.227888 -0.9760178 0.04620534 0.2127311 -0.5982831 0.5322616 0.5989616 -0.6435318 0.488572 0.5892064 -0.6141997 0.3954057 0.6829445 -0.619018 0.3866826 0.6835885 -0.5090486 0.2480144 0.8242321 -0.5045205 0.2686823 0.8205296 -0.3762286 0.1775504 0.9093558 -0.4614471 -0.01582032 0.8870267 0.4972154 0.5723351 0.6520808 0.4050472 0.6817529 0.6092206 0.2988866 0.68661 0.662747 0.3165889 0.6683701 0.6730921 0.1721764 0.7011789 0.6918841 0.1918805 0.6661677 0.7206959 0.08202505 0.7128628 0.6964902 0.08619832 0.6798792 0.7282405 0.02891266 0.7210363 0.6922938 0.0229116 0.704537 0.7092974 0.008853077 0.7225189 0.6912946 0.01547145 0.7282178 0.6851711 0.01627933 0.724951 0.6886081 -0.02421069 0.6950451 0.7185585 0.582117 0.2611474 0.7700272 0.5349629 0.381718 0.7537283 0.3200116 0.3930803 0.8620212 0.3331826 0.3710476 0.8667832 0.07815909 0.4285399 0.9001359 0.09173017 0.3874831 0.9173018 -0.1173188 0.475487 0.8718649 -0.1163766 0.4371675 0.8918189 -0.2503706 0.5324859 0.8085627 -0.2563571 0.5134102 0.8189574 -0.3217505 0.5961924 0.7355483 -0.3154665 0.6037467 0.7321004 -0.3263683 0.6409613 0.6947319 -0.246048 0.6950024 0.6755976 -0.498003 0.4003423 0.7692329 -0.2890971 0.7379939 0.6097442 0.211946 0.7037686 0.6780773 0.4500941 0.6113702 0.6508777 0.7859521 0.3939632 0.4765213 0.5736004 0.5587217 0.5990099 0.7043607 0.7043607 0.08804506 0.6232019 0.04708147 0.7806426 0.7017382 0.2479428 0.6678981 0.631469 0.1754428 0.7552927 0.6626682 0.3782182 0.6463915 0.6930049 0.1876888 0.6960728 0.6753716 0.09850674 0.7308691 -0.2237724 0.08415353 0.9710016 -0.3916876 0.06070291 0.9180936 -0.3173574 0.255878 0.9131324 -0.5092344 -0.3255001 0.7966994 -0.5093011 -0.2834862 0.8125564 -0.6935946 0.2011712 0.6917057 -0.7045818 0.2005832 0.6806841 0.4316934 -0.3592336 0.8274009 0.3369847 -0.1087048 0.9352138 0.3922624 -0.07794284 0.9165453 0.31249 -0.06457918 0.9477233 0.367852 0.03352141 0.92928 0.1370943 -0.05901789 0.9887983 0.2495537 0.4006998 0.8815683 0.03033363 0.03448611 0.9989448 0.9511043 0.2064635 0.2297245 0.9730685 0.06976914 0.2197043 0.8935502 0.2596601 0.3662579 0.8458472 0.3168384 0.429134 0.8373637 0.3237948 0.4404307 0.809766 0.2308852 0.5394174 0.7059007 0.2573343 0.6599116 0.6863277 0.476862 0.5491421 0.6690511 0.4833599 0.5645653 0.6478186 0.4123428 0.6405501 0.4342997 0.5594655 0.705962 0.3966677 0.5558474 0.7305399 0.3407135 0.4428476 0.8293373 0.9212345 0.06247442 0.3839585 0.8945791 0.09400385 0.4369115 0.8538058 -0.01006841 0.5204944 0.6983069 0.2441084 0.6728883 0.6996234 0.2442733 0.6714594 0.4169393 0.5099988 0.7523716 0.3801605 0.4630732 0.8006504 0.2764202 0.4712733 0.837552 0.4856005 0.2033982 0.850189 -0.06356453 0.3110594 0.9482625 -0.1103398 0.08775281 0.9900124 -0.07751792 0.1225092 0.9894354 -0.1298042 0.3918614 0.9108213 0.02425217 0.3086528 0.9508656 0.1718988 0.368135 0.9137437 0.1057492 0.416861 0.9027979 0.2457582 0.3762586 0.8933265 0.3816681 0.1450107 0.9128534 0.4854131 0.2185179 0.8465366 0.6786996 -0.1743348 0.7134244 0.2968885 0.2730031 0.9150556 -0.06027251 0.7284832 0.6824071 -0.1232779 0.7015795 0.7018468 -0.1465619 0.7476628 0.6477037 -0.1378539 0.7548979 0.6411907 -0.1266545 0.7665137 0.6296154 -0.1569992 0.7610057 0.6294614 -0.1433894 0.7742639 0.6164049 -0.1940705 0.7704682 0.6072193 -0.1960724 0.7696278 0.6076419 -0.2459861 0.781782 0.5729815 -0.2813762 0.7702889 0.5722609 -0.3200826 0.7888023 0.5247268 -0.2312511 0.06006973 0.9710379 -0.2508088 0.271554 0.9291681 -0.3822128 0.3934116 0.8361464 -0.3310983 0.2727573 0.9033147 -0.5825047 0.2584088 0.7706576 0.4455575 0.6151092 0.6504762 0.206544 0.7078925 0.6754464 0.1907845 0.6574859 0.7289127 0.2002906 0.656849 0.7269341 0.1588145 0.6034576 0.7814198 0.1395171 0.6089136 0.780871 0.05707448 0.5500239 0.8331965 0.02419769 0.5687368 0.8221636 -0.1145836 0.5106143 0.8521406 -0.1394159 0.5366561 0.832204 -0.3225975 0.4952612 0.8066271 -0.3300104 0.5125339 0.7927183 -0.5183865 0.5013715 0.6927497 -0.5180928 0.4928303 0.6990696 -0.3940463 0.7628222 0.5126695 -0.321032 0.7955942 0.5137786 -0.455263 0.6385982 0.6204256 -0.0491451 0.1573755 0.9863153 0.510954 0.3278366 0.7946379 0.4410023 0.2684469 0.856419 0.4398856 0.1528698 0.8849472 0.4088022 0.3131327 0.8572216 0.4092111 0.4660736 0.7844245 0.04040515 0.6267737 0.7781531 0.2445402 0.6394504 0.7289056 -0.9831327 0.006680011 0.1827715 -0.3773545 0.2470242 0.8925148 -0.5950488 0.4848211 0.6409879 -0.3806552 0.4897419 0.7843818 -0.1714526 0.5763478 0.7990165 -0.4698134 0.6028276 0.6448833 -0.9922521 0.03557807 0.1190379 -0.9671506 0.0833314 0.2401573 -0.9645736 -0.07984429 0.2514412 -0.7998254 0.1205341 0.5880057 -0.8198214 0.0723263 0.5680335 -0.5956646 -0.002282261 0.8032302 -0.4640073 0.1527166 0.872568 0.2064599 0.2590042 0.9435524 0.2059924 0.3336492 0.919916 0.1719562 0.3509348 0.9204759 0.1721046 0.5029913 0.8469828 0.1146157 0.5281718 0.8413667 0.1150313 0.6463144 0.7543512 -0.02446073 0.7008858 0.712854 0.3975337 0.03301823 0.9169933 0.3328114 -0.07386827 0.9400959 0.3349983 0.1500824 0.9301889 -0.04926425 0.1699522 0.9842202 0.3260206 0.3157801 0.8910632 -0.09875804 0.2535524 0.9622671 -0.09990984 0.5260989 0.8445343 -0.157131 0.5073988 0.8472641 -0.1574875 0.6734755 0.7222385 -0.2449541 0.6471351 0.7219514 -0.6912303 0.4442979 0.5699125 -0.6298378 0.4636464 0.6231665 -0.8259606 0.3399932 0.4496597 -0.8266561 0.3395479 0.448717 -0.9696986 0.1427972 0.198226 -0.9972101 0.04637914 0.05849117 -0.9503709 0.1692249 0.2610709 -0.9498303 0.08636778 0.3006048 -0.8271216 0.141496 0.5439198 -0.7964991 0.1608509 0.5828518 -0.6300271 0.1967343 0.75124 -0.5889841 0.2141592 0.7792519 -0.3294333 0.2382048 0.9136368 -0.3336334 0.001490712 0.9427018 -0.01267176 0.08985269 0.9958745 -0.6407224 3.97718e-5 0.7677727 -0.7689274 -2.54559e-5 0.6393362 -0.7895663 3.22238e-4 0.6136652 -0.893011 -5.37254e-4 0.4500347 -0.9051274 -5.55959e-5 0.4251407 -0.9876513 7.35574e-5 0.1566684 -0.9814406 -7.37168e-4 0.1917651 -0.9993069 -2.07036e-5 0.03722709 -0.01267659 -0.003335833 0.9999142 -0.1649488 -8.08177e-4 0.9863019 -0.2908704 1.48656e-4 0.9567625 -0.4760025 -4.6246e-4 0.8794438 -0.3663458 -0.003222405 0.9304732 -0.6729536 0.004509449 0.7396711 -0.4584801 -0.003561794 0.8886977 -0.5445442 -0.001854896 0.8387302 -0.1156637 -1.81347e-4 0.9932884 0.1902862 9.67844e-5 0.9817287 0.2197731 6.09979e-4 0.9755508 0.7355049 1.65226e-5 0.6775195 0.5629235 1.56275e-4 0.826509 0.6246643 0.003169059 0.780887 0.4016174 -4.99122e-4 0.9158076 -0.7271932 0 0.6864328 -0.532732 -7.3397e-4 0.8462837 -0.09948748 -0.007202565 0.9950128 -0.7232831 0.01000726 0.6904792 -0.6191701 0.003899276 0.7852473 -0.3114306 -0.001729071 0.9502673 -0.2168049 -0.003443062 0.9762089 0.3747031 0.00209254 0.9271425 -0.3904895 0.00388205 0.9205992 -0.1900851 1.87339e-4 0.9817677 0.03571444 -1.9613e-4 0.9993621 0.1141598 -0.001634538 0.9934611 0.3748905 0.002091944 0.9270668 0.3753179 0.002092182 0.9268938 0.6355397 -3.74e-4 0.7720682 0.3767053 -0.004264175 0.9263234 0.3766794 -0.004263401 0.9263339 0.3757272 0.002092301 0.9267279 0.4772863 0.001446187 0.8787468 0.6753699 0.0061872 0.7374533 0.851951 -0.001664996 0.5236189 0.8931132 3.58415e-4 0.4498319 0.7893294 -5.89762e-5 0.6139701 0.7703468 -1.80416e-4 0.6376252 0.7545229 -1.76462e-5 0.6562739 0.7041072 1.11449e-5 0.7100937 0.9334225 1.80533e-4 0.358779 0.9876406 -3.55766e-4 0.1567352 0.9902962 -1.45081e-6 0.1389735 0.8944904 0.2676082 0.3581517 0.3339679 -1.40353e-4 0.9425845 0.4696124 0.1540502 0.869329 0.9915077 0.0749889 0.1062508 0.9761949 -0.1267958 0.175973 0.6302525 0.196744 0.7510484 0.9617887 0.05451524 0.2683107 0.9774525 0.06357163 0.2013589 0.9410208 0.2632958 0.2124977 0.9492318 0.1906333 0.250236 0.9783113 0.1151028 0.1722158 -0.3941242 -0.1114723 0.9122719 -0.3360288 0.03405612 0.9412358 -0.3328158 0.204672 0.9205124 -0.4396718 0.1529363 0.885042 -0.4401825 0.3096911 0.8428114 -0.4322237 0.3081176 0.8474942 -0.2052156 0.3471115 0.9150957 -0.2054892 0.1597196 0.9655382 0.04884248 0.1699671 0.9842386 0.0488708 0.1546774 0.9867556 0.01633858 0.09456592 0.9953845 0.7991829 0.1309485 0.5866509 0.7965958 0.1608473 0.5827208 0.8270366 0.1416046 0.544021 0.8263493 0.3425775 0.446976 0.8462651 0.3216835 0.4246822 -0.06003206 0.6677067 0.742 0.2114924 0.6638359 0.7173514 0.1576837 0.6520595 0.7415891 0.4452129 0.6106254 0.6549215 0.1176977 0.5936227 0.79609 0.5681801 0.4942771 0.6579222 0.6291205 0.4718404 0.6177169 0.6825312 0.4381364 0.5849682 0.7838955 0.3727399 0.4965612 -0.2881942 0.638372 0.7137404 -0.1146655 0.6745254 0.7292923 -0.1145691 0.5112436 0.8517653 0.1576226 0.5260151 0.8357413 0.1001046 0.5075806 0.8557693 0.3803817 0.4898508 0.7844463 0.8254025 0.06651324 0.5606127 0.5957539 8.60916e-4 0.8031667 0.5888009 0.2142587 0.779363 0.3293921 0.2382606 0.9136371 0.3775562 0.2470602 0.8924196 -0.1302962 0.2437784 0.9610385 0.1000042 0.3552411 0.92941 -0.1721128 0.3378016 0.9253472 -0.1716941 0.5202088 0.8366027 -0.3856248 0.4731133 0.792122 -0.007063329 0.6220632 0.7829353 -0.3964344 0 0.9180631 0.9841347 0 0.1774232 0.9841482 0 0.1773486 0.8273018 0 0.5617579 0.5742212 0 0.8187002 0.4741911 -0.0711497 0.8775423 -0.3966175 0 0.917984 0.01640516 0 0.9998654 0.01640516 0 0.9998655 0.3633784 0 0.9316416 -0.9831969 2.3795e-4 0.1825485 0.3975492 -3.54365e-4 0.9175809 0.3974742 0 0.9176134 0.159509 0 0.9871966 -0.01259922 -0.05593669 0.9983549 -0.07781106 0 0.9969682 -0.3612874 0 0.9324546 -0.4684742 -0.07036489 0.8806707 -0.9831554 0 0.1827722 -0.821944 0 0.5695684 -0.8219964 0 0.5694927 -0.5710438 0 0.8209196 0.1861525 0.6947504 0.694744 0.186163 0.6947326 0.694759 0.5086075 0.6947302 0.5085946 0.5085915 0.6947456 0.5085896 0.6947333 0.694759 0.1861606 0.694761 0.6947322 0.1861568 0.6947529 0.69474 -0.1861582 0.6947401 0.6947536 -0.1861554 0.5086029 0.6947368 -0.5085901 0.508567 0.6947597 -0.5085948 0.1861649 0.6947488 -0.6947423 0.1861445 0.6947519 -0.6947447 -0.1861401 0.694752 -0.6947456 -0.1861723 0.6947494 -0.6947397 -0.5085793 0.6947526 -0.5085921 -0.5085927 0.6947437 -0.5085909 -0.6947466 0.6947466 -0.1861573 -0.6947466 0.6947466 -0.1861568 -0.6947493 0.6947429 0.1861606 -0.694747 0.6947461 0.1861573 -0.5085934 0.6947414 0.5085934 -0.508608 0.6947314 0.5085924 -0.1861687 0.6947338 0.6947563 -0.1861445 0.6947519 0.6947447 0.9999802 -0.006307244 0 0.9959661 -0.08972835 -5.40277e-4 0.9658005 -0.2587864 -0.01609438 0.2426575 -0.9701121 -2.53019e-5 0.2588181 -0.9659124 -0.005148112 0.6087603 -0.7933481 0.003122329 0.9682159 -0.2494722 -0.01793426 0.8959789 -0.4440909 0.002251863 0.793357 -0.6087501 -0.002838313 0.7796767 -0.6261824 -3.03387e-5 0.5955401 -0.8033256 4.01518e-5 0.9738288 -0.2270101 -0.01112824 0.9659257 -0.2588177 0.001043975 0.8813076 -0.4720137 -0.02236443 0.7930238 -0.6085085 -0.02882289 0.7498162 -0.6599584 -0.04722893 0.6084733 -0.7929877 -0.03051251 0.550958 -0.8335617 -0.04025274 0.4078708 -0.9119776 -0.04402714 0.258768 -0.9657327 -0.01998829 0.1570889 -0.9863446 -0.04947096 -0.05093395 -0.9987021 -4.42662e-6 -0.8314648 -0.5555775 -6.42287e-5 -0.8036943 -0.5949329 -0.01142275 -0.9118379 -0.4105485 0.001256942 -0.9807765 -0.1950891 -0.004222452 -0.975166 -0.2212726 -0.009478211 -0.9986314 -0.05230152 0 -0.1950793 -0.9807372 -0.009933829 -0.2266644 -0.9739661 -0.003652989 -0.5555666 -0.8314543 0.005440354 -0.461095 -0.8870021 -0.02487385 -0.636334 -0.7714138 3.0805e-5 -0.1948544 -0.9796007 -0.04913341 -0.155981 -0.9870761 -0.03675317 -0.5547658 -0.8302689 -0.05374634 -0.4624657 -0.8865174 -0.014575 -0.8300827 -0.5546551 -0.05762511 -0.7691857 -0.6388719 -0.01400393 -0.9805186 -0.1950376 -0.02331602 -0.9737941 -0.2271592 -0.01113528 0.8646182 -0.5024295 -4.43711e-4 0.999999 -0.0014894 0 0.9694947 -0.2450994 0.002539753 0.9620472 -0.2727031 0.00991863 0.9979826 -0.06348937 7.26043e-5 0.7356973 -0.6772235 0.01085531 0.6739879 -0.7366024 0.05618989 0.7516807 -0.6594613 0.009329259 0.3028057 -0.9456189 0.1188005 0.3626345 -0.9300754 0.05878841 0.443553 -0.8962229 -0.006733059 -0.443553 -0.8962229 -0.006733059 -0.3626345 -0.9300754 0.05878841 -0.3027967 -0.9456216 0.1188024 -0.6034075 -0.7974296 0.002318084 -0.734701 -0.6780918 0.02014905 -0.75168 -0.6594621 0.009329378 -0.999999 -0.0014894 0 -0.9979833 -0.0634787 7.26043e-5 -0.9693944 -0.2453572 0.008623898 -0.9568275 -0.2906496 0.00204122 -0.86462 -0.5024262 -4.43795e-4 0.8060827 -0.452984 0.380836 0.1065872 -0.9911051 -0.07968658 0.9965255 -0.08291375 -0.007888615 0.9876058 -0.142619 0.06553506 0.943447 -0.3315026 -0.003734946 0.9218212 -0.3830256 0.05947387 0.8861793 -0.4578208 0.0713188 0.9999986 -0.001712322 2.78699e-7 0.9993 -0.02466756 0.02812826 0.9990894 -0.03741538 0.02051091 0.9839252 -0.1247506 0.1277835 0.9803951 -0.166317 0.1056601 0.94511 -0.2499157 0.2104977 0.9395975 -0.2685012 0.212282 0.93204 -0.10249 0.3475589 0.9731744 -0.01040434 0.2298333 0.9811203 -0.09125822 0.1705137 0.9984523 0.002709329 0.0555489 0.8660973 -0.1167867 0.4860417 0.9203654 -0.09389746 0.3796195 0.9357648 -0.06798702 0.3460087 0.2657891 -0.9251315 0.2710865 0.3566487 -0.907994 0.2198833 0.4726932 -0.866109 0.1625313 0.4902194 -0.8585281 0.1503814 0.6485463 -0.7431127 0.1648369 0.6599334 -0.735512 0.1533299 0.7307558 -0.674676 0.1039637 0.786666 -0.4731177 0.3966313 0.7160812 -0.5198947 0.4657654 0.6756331 -0.5729522 0.4639461 0.5856152 -0.6115459 0.5320399 0.5370557 -0.6319041 0.5588098 0.2030692 -0.943796 0.2607915 0.3325066 -0.8352718 0.4379048 0.3986248 -0.6634302 0.6332131 0.3821251 -0.6732808 0.6329877 0.434189 -0.4782944 0.7633574 0.8651404 -0.4889375 0.1116791 0.753699 -0.6528748 0.0754491 0.8884337 -0.3415747 0.3066146 0.8725278 -0.3901527 0.2940682 0.8550977 -0.1030052 0.5081318 0.7775999 -0.1697072 0.6054238 0.796858 -0.1457191 0.5863305 0.6876248 -0.2196155 0.6920558 0.7024356 -0.1768068 0.6894373 0.5730182 -0.2250399 0.7880401 0.5893618 -0.2175112 0.7780371 0.4375279 -0.258401 0.8612772 0.4569545 -0.2386251 0.8568843 0.07864397 -0.9486233 0.3064785 -0.3364399 -0.5457083 0.7674703 -0.2913323 -0.5785174 0.7618682 -0.09549552 -0.6609457 0.7443329 0.1514849 -0.6791502 0.7181974 0.1530157 -0.6777991 0.7191485 0.1050868 -0.844803 0.5246568 0.1824302 -0.2386251 0.9538226 0.1824536 -0.2385957 0.9538254 0.164838 -0.4799412 0.8616756 -0.1483636 -0.6790385 0.7189541 -0.1507158 -0.6950682 0.7029687 -0.2038087 -0.2341635 0.9505943 -0.2038192 -0.2341456 0.9505965 -0.4341774 -0.4783117 0.7633532 -0.332507 -0.8352727 0.4379027 -0.2030781 -0.9437931 0.2607948 -0.9984523 0.002720415 0.05555099 -0.9852914 -0.07666188 0.1527218 -0.9719645 -0.01413428 0.2347024 -0.9410755 -0.08613991 0.3270429 -0.9280781 -0.08133834 0.363394 -0.920766 -0.09326058 0.378804 -0.8595273 -0.121885 0.4963436 -0.9965255 -0.08291375 -0.007888615 -0.9803194 -0.1702746 0.09990257 -0.9459779 -0.3239808 -0.01274269 -0.9037134 -0.4159396 0.1014711 -0.9020931 -0.4299925 0.03653359 -0.8265221 -0.5350942 0.1747437 -0.7837833 -0.6200481 0.03498989 -0.672663 -0.7203953 0.1689828 -0.7167843 -0.6912306 0.09176301 -0.5657122 -0.7884991 0.2413275 -0.5681505 -0.8176442 0.09307473 -0.3658609 -0.901408 0.2315374 -0.4633343 -0.872818 0.1533307 -0.2657905 -0.9251307 0.2710879 -0.1065855 -0.9911054 -0.07968527 -0.8600909 -0.09805166 0.5006293 -0.7992736 -0.1526999 0.5812438 -0.7759415 -0.1614671 0.6097895 -0.7106382 -0.2055852 0.6728507 -0.6826375 -0.1850555 0.7069374 -0.5896372 -0.2195554 0.7772538 -0.5729842 -0.2224925 0.7887878 -0.45784 -0.2535963 0.8520984 -0.43667 -0.2393615 0.8671941 -0.9999986 -0.001712322 2.78699e-7 -0.9991863 -0.02676391 0.03017497 -0.9990959 -0.03730231 0.02039849 -0.9819304 -0.131492 0.1360977 -0.980931 -0.1645352 0.1034541 -0.9404131 -0.258293 0.2211513 -0.9435255 -0.261524 0.2033834 -0.8766762 -0.3552054 0.3244508 -0.8803812 -0.3812566 0.2820857 -0.7875394 -0.4675208 0.4015049 -0.8044139 -0.4592685 0.3768166 -0.6830139 -0.5381366 0.4938634 -0.7025583 -0.5588049 0.4406233 -0.5385406 -0.6272335 0.5626299 -0.5831417 -0.6167439 0.5287464 -0.3849246 -0.6655405 0.6394443 -0.3963895 -0.6715729 0.6259915 0.9932801 0.1157355 0 0.9807798 0.1950884 -0.003401875 0.5555658 0.8314675 0.002905189 0.8182767 0.5748223 -0.001701593 0.8314647 0.5555703 -0.002836704 0.9064982 0.4222097 3.11768e-4 0.9560085 0.2933387 -4.29874e-4 0.1950902 0.9807853 0 0.1138229 0.9934636 -0.008624255 0.2438946 0.9698004 -0.001608908 0.6233442 0.7807899 -0.04253578 0.5682843 0.8228306 0.001701653 0.3348062 0.942287 -2.39748e-4 0.3190804 0.9477276 -4.61376e-4 0.76179 0.6437399 -0.07263064 0.7893264 0.6124377 -0.04340374 0.8730751 0.4800986 -0.08511894 0.9434693 0.3261574 -0.05905127 0.9467697 0.3143174 -0.06951248 0.948807 0.3060899 -0.07793891 0.9532145 0.2781646 -0.1183495 0.991124 0.1293687 -0.03061175 0.9762433 0.2162458 -0.01366651 0.8100049 0.2185168 -0.5441899 0.9319347 0.2349282 -0.2762363 0.6964321 0.7175872 0.007150113 0.7860759 0.6157724 -0.05393528 0.7894991 0.6110148 -0.05789709 0.8882893 0.4585592 -0.02580201 0.9375611 0.3459699 -0.03583461 0.8780599 -0.4764595 0.04469072 0.9899584 -0.05958557 0.1281877 0.9001895 -0.05891364 0.4314952 0.729967 -0.4467352 0.5172774 0.6732063 -0.5957449 0.4380428 0.5077162 -0.1820898 0.8420616 0.4662717 -0.3561208 0.8097956 0.9896408 -0.05380249 0.133104 0.9057501 -0.1933383 0.3771435 0.9077641 -0.1722562 0.3824815 0.7398316 -0.3029208 0.6007398 0.7429888 -0.2798617 0.6079844 0.5129907 -0.3842538 0.7675869 0.5171977 -0.3606883 0.7761511 0.6188355 -0.1824815 0.7640309 0.9832772 -0.1081613 0.1465166 0.1452311 -0.9352389 0.3228562 0.03303223 -0.9415452 0.3352634 -0.293294 -0.9017084 0.3176487 -0.2104911 -0.9259968 0.3134062 -0.3894464 -0.8684987 0.3066622 0.5559783 -0.7861015 0.2700607 0.4708025 -0.8314825 0.2949271 0.2664251 -0.9083971 0.3222303 0.963778 -0.2485018 0.09684532 0.8103581 -0.5565322 0.1832805 0.8603166 -0.4804351 0.1704043 0.670464 -0.6992259 0.2481152 0.5924569 -0.7610044 0.2643244 0.99497 -0.08658933 0.05036979 0.9781616 -0.1536495 0.1399703 0.9892531 -0.06225705 0.1322969 0.9000214 -0.095802 0.4251863 0.9270523 -0.08461385 0.3652597 0.9864209 -0.03696793 0.1600224 0.979751 -0.04174888 0.195819 0.9990786 -0.009654402 0.04181843 0.8605691 -0.1180213 0.4954714 0.7847908 -0.1220686 0.6076207 0.8688725 -0.1062847 0.4834917 0.002251505 -0.2130306 0.977043 0.2146084 -0.2314411 0.9488827 0.5568937 -0.1965372 0.8069961 0.3805895 -0.1839438 0.9062651 0.4642896 -0.1885055 0.8653906 0.1456067 -0.2367658 0.9605939 -0.2938775 -0.2288522 0.9280425 -0.2226901 -0.2199503 0.9497532 -0.6627727 -0.1974406 0.7223224 -0.5625534 -0.1671018 0.8096979 -0.6100137 -0.7460992 0.2668697 -0.5742283 -0.7693148 0.2800302 -0.6737141 -0.6237909 0.3962252 0.9922791 -0.05472409 0.1112998 0.8594238 -0.2256 0.4587979 0.8594261 -0.2255967 0.4587953 0.5548641 -0.367095 0.7465703 0.5547485 -0.3671396 0.7466342 0.1448571 -0.4366032 0.8879156 0.1447597 -0.4366153 0.8879256 -0.292257 -0.4219973 0.8581984 -0.2923235 -0.4219769 0.8581855 -0.8038477 -0.2624806 0.5337913 -0.4281908 -0.3138419 0.8474408 0.9942472 -0.07109951 0.08010989 0.8594331 -0.3393806 0.3823555 0.8594077 -0.3394089 0.3823874 0.5548713 -0.5522606 0.6221947 0.5548443 -0.5522818 0.6221998 0.1447835 -0.6568298 0.7400084 0.1447598 -0.6568378 0.740006 -0.292312 -0.6348378 0.7152166 -0.2922584 -0.6348446 0.7152324 -0.7896866 -0.4072628 0.4588379 -0.413411 -0.4924433 0.7658923 0.9997922 -0.01927822 0.006628572 0.9902551 -0.1322691 0.04358559 0.9831339 -0.1533843 0.09960556 0.8594267 -0.4287837 0.2784429 0.859425 -0.4287847 0.2784467 0.55485 -0.6977351 0.4531085 0.5548211 -0.6977558 0.4531119 0.1447545 -0.8298481 0.5388864 0.1447954 -0.8298377 0.5388911 -0.2922902 -0.8020539 0.5208417 -0.2922919 -0.8020498 0.5208471 -0.7256844 -0.5770313 0.3747227 -0.5151674 -0.6077339 0.6043693 0.01638329 -0.04227268 0.9989718 0.06636744 -0.7172743 0.693623 -0.2824074 -0.50999 0.8125001 -0.2839341 -0.6658894 0.6899078 -0.1888867 -0.7175349 0.670422 -0.3556688 -0.6673069 0.654371 0.4167371 -0.6465191 0.6390175 0.3573113 -0.6446036 0.6758809 0.04680627 -0.7226235 0.6896554 0.9149388 -0.2970649 0.2732028 0.8290422 -0.3919905 0.398789 0.7133454 -0.508059 0.4827158 0.7036933 -0.5122058 0.4924033 0.6045194 -0.5649787 0.5615651 -0.3961303 -0.04982656 0.9168414 -0.4020659 -0.05686098 0.9138434 -0.3990143 -0.2298245 0.8876758 0.3008834 -0.04879772 0.9524117 0.5738688 -0.04438078 0.8177439 0.6206126 -0.002093434 0.7841147 0.8241662 -0.08664786 0.5596806 0.86122 -0.02188253 0.5077611 0.9840412 -0.01397174 0.1773916 0.9754118 -0.04893803 0.2148879 0.6204172 -0.1639366 0.7669469 0.3195753 -0.1862334 0.9290795 0.2999438 -0.1985539 0.9330649 -0.03774189 -0.1966895 0.9797391 0.9972331 -0.04603141 0.05837202 0.9837336 -0.1163535 0.1368576 0.9908828 -0.04632157 0.1265133 0.8861973 -0.1303296 0.4445995 0.8568907 -0.1577428 0.4907704 0.6606473 -0.2146911 0.7193419 0.3245568 -0.3514137 0.8781636 0.3552136 -0.3488945 0.8672347 0.3196523 -0.3715685 0.8716418 -8.01245e-5 -0.3739383 0.9274537 -0.03762233 -0.3909991 0.9196218 0.9686111 -0.1561484 0.1934175 0.7822514 -0.4044709 0.4737996 0.8883313 -0.2649282 0.3750742 0.7132312 -0.3815715 0.5879665 0.6646609 -0.4257459 0.613976 0.4160172 -0.4970102 0.7615185 0.3546494 -0.5312272 0.7694293 0.06635284 -0.5465151 0.8348165 0 -0.5671355 0.8236245 -0.2174538 -0.5390948 0.8136895 -0.4026499 -0.3384094 0.8505012 -0.2606291 -0.1940132 0.9457438 -0.05832171 -0.2072089 0.9765568 -0.05866426 -0.150699 0.9868375 0.3636585 0.02482289 0.9312016 -0.5555694 0.8314688 0.001624464 -0.3356441 0.941989 -2.3475e-4 -0.3233692 0.9462728 -4.01084e-4 -0.3092822 0.9509702 -5.97336e-4 -0.1621681 0.9867569 -0.003510892 -0.1950901 0.9807853 0 -0.639286 0.7683238 -0.03149408 -0.6588422 0.7487394 -0.0729146 -0.5666322 0.8239665 0.002741634 -0.8020478 0.5972585 -0.001356482 -0.9049256 0.4254749 -0.008990705 -0.8314631 0.5555651 0.004072904 -0.9807823 0.1950895 -0.002526462 -0.9888051 0.1492129 0 0 -1 -1.70946e-7 0 -1 2.3433e-5 0.3130586 0.9497181 0.005474984 0.3562808 0.9330523 -0.04977542 0.4910723 0.8706071 -0.02985292 0.5511624 0.8341398 -0.02075761 0.3682873 0.9295831 -0.01548504 0.3100692 0.9459473 -0.09508371 0.2502294 0.9638832 -0.09118396 0.2288923 0.96565 -0.1229984 0.1528137 0.9802553 -0.1254892 0.3172255 0.9483501 0 0.2984285 0.9543018 -0.01576399 0.2392559 0.9709551 -0.001734018 0.2026116 0.9787534 -0.03147017 0.04441118 0.9978873 -0.0474196 0.9122221 0.4054284 0.05898141 0.7820222 0.6169214 0.0885961 0.9224092 0.2662788 0.2797447 0.9324893 0.2228925 0.2842227 0.9296078 -0.09288257 0.356654 0.9321332 -0.06556075 0.3561314 0.8583169 -0.3218716 0.3996133 0.8460469 -0.3547016 0.3979842 0.6588669 -0.6236522 0.420657 0.6768111 -0.5973414 0.4302441 0.5735195 -0.7428901 0.3452389 0.7034811 -0.6248495 0.3386406 0.7035732 -0.6247327 0.3386647 0.8727804 -0.3821154 0.3037143 0.8728469 -0.3819521 0.3037289 0.9656519 -0.09913325 0.2401854 0.9656585 -0.09907555 0.2401828 0.9699106 0.1864798 0.1565204 0.969913 0.1864709 0.1565167 0.9236772 0.3721036 0.09142976 0.7685821 0.6362075 0.06724345 0.3560031 -0.8719849 0.3360121 0.3806757 -0.8571308 0.3470059 0.3744877 -0.8507114 0.3688485 0.3270719 -0.8834162 0.3355588 0.4956075 0.8677864 -0.03633224 -0.5677232 0.8218483 -0.04749643 -0.586165 0.791908 0.1711506 0.5861645 0.7919085 0.1711497 0.5637437 0.8249922 -0.03976428 -0.5441378 0.8337056 -0.09406983 -0.6809116 0.7323293 0.007296621 -0.5512677 0.8294167 0.09039884 -0.5712094 0.8184767 0.06177264 -0.4207293 0.9053466 0.0577442 -0.5537317 0.8120453 0.1842923 -0.4757584 0.8485649 0.2314984 -0.5090479 0.7733958 0.3777952 -0.3444751 0.8775319 0.3335786 -0.3629057 0.7589986 0.5405746 -0.2110885 0.8916242 0.4005597 -0.1842054 0.7664566 0.615315 -0.074907 0.8947486 0.440243 0 0.7607574 0.6490364 0.06556534 0.8956215 0.4399584 0.1859354 0.7613781 0.621073 0.200397 0.8943223 0.400036 0.3667541 0.7522063 0.5474278 0.3360176 0.8787056 0.3390705 0.5101599 0.7719926 0.3791626 0.4723601 0.8475341 0.2419958 0.5567529 0.8102479 0.183097 0.3900029 0.9187419 0.06173413 0.5721491 0.8173803 0.06734341 0.5614163 0.8232193 0.08439117 0.6809081 0.7323326 0.007296562 0.5440168 0.8337855 -0.09406155 0.3563173 -0.8725557 0.3341925 0.7911274 -0.33893 0.5091602 0.4555173 -0.7206311 0.5226804 0.9194969 0.392738 0.01680755 0.982186 0.1658672 0.08831179 0.965429 0.2605447 -0.00795263 0.9615122 0.274163 0.0181424 0.9888699 0.0918343 0.1170594 0.9870908 0.1488935 0.05901134 0.9893003 -0.03844881 0.1407364 0.9958282 0.09105449 0.005941212 0.9869822 -0.03647387 0.1566388 0.9878336 -0.02899938 0.1527878 0.9153164 -0.1768759 0.3618159 0.9057117 -0.1978847 0.3748707 0.7845984 -0.3014549 0.5417844 0.7383413 -0.3565573 0.5724676 0.5121976 -0.4391229 0.7381225 0.5221058 -0.4277146 0.7378793 0.5373715 -0.5085828 0.6727374 0.5056794 -0.6018857 0.6180793 0.4886795 -0.5828993 0.6491692 0.9521094 0.3057462 0.002636551 0.9543431 0.2842275 0.09189212 0.9850354 0.1040275 0.1374181 0.9662978 -0.1000564 0.2371867 0.9360086 -0.2452678 0.2524513 0.8443163 -0.4160732 0.3376584 0.8754501 -0.3863444 0.2903878 0.6953166 -0.61917 0.3649156 0.6988671 -0.61708 0.3616588 0.5680515 -0.7336208 0.3729852 0.4091117 -0.8057672 0.4282135 0.4065176 -0.800101 0.4411144 0.6770601 -0.5788168 0.4544898 0.7340388 -0.5408304 0.4107183 0.8331261 -0.3923677 0.3898059 0.8752183 -0.345316 0.3387474 0.954856 -0.1030247 0.2786321 0.4365731 -0.6690573 0.6014702 0.5107552 -0.6725337 0.5355628 0.7140941 -0.4839187 0.5058581 0.7184698 -0.4813749 0.502075 0.8565247 -0.2935442 0.4244965 0.9187612 -0.2017321 0.3393849 0.9534938 -0.09942543 0.2845423 0.9820549 -7.74376e-4 0.1885939 0.9862254 0.1189551 0.1149319 0.9870871 0.1479752 0.06133919 0.9671106 0.2538761 -0.0156272 0.5975686 -0.3944879 0.6980624 0.04703879 -0.7619851 0.6458841 0.687199 -0.3678839 0.6264337 0.6663387 0.01089918 0.7455697 -0.4826734 -0.6031389 0.6350197 -0.3549019 -0.7264697 0.5884611 -0.2509124 -0.8202127 0.5140956 -0.209213 -0.8281377 0.5200172 -0.2752922 -0.8840258 0.3777732 -0.2391951 -0.9010227 0.3618618 -0.2273891 -0.8896132 0.3960844 -0.2185408 -0.8926777 0.3941656 -0.2008532 -0.8796133 0.4312059 -0.2271419 -0.8751751 0.4271711 -0.1778882 -0.8613323 0.4758809 -0.2093266 -0.8582828 0.4685437 -0.5640488 -0.1389828 0.8139612 -0.09069085 -0.3604741 0.9283499 -0.2170867 -0.1151539 0.9693364 -0.346452 -0.3312592 0.8776323 -0.5833108 0.08767706 0.8075032 0.2100796 -0.2703328 0.9395674 0.208374 -0.259759 0.942924 -0.00256133 -0.2526338 0.9675586 0.8595418 -0.2278299 0.4574731 0.9972602 -0.04784458 0.05641919 0.9682614 -0.1158857 0.2214511 0.9654383 -0.1265577 0.2278425 0.8597707 -0.2930262 0.4182466 0.9065671 -0.2200191 0.3601773 0.8734238 -0.2643072 0.4089901 0.8246903 -0.3521807 0.4425547 0.700601 -0.4757108 0.5318436 0.6514824 -0.5039188 0.5671302 0.6033374 -0.5495337 0.5779247 -0.1889842 -0.7230272 0.6644673 0.8411896 -0.1987258 0.5029 0.735489 -0.2185494 0.6413206 0.5979717 -0.3937762 0.6981191 0.502294 -0.3070938 0.808328 0.4265547 -0.3257094 0.8437799 0.4233521 -0.3170079 0.8486925 0.3534678 -0.2803076 0.8924619 -0.3954633 -0.7387787 0.5457243 -0.3811956 -0.7482877 0.5429139 -0.2827296 -0.7516501 0.5958909 -0.2979888 -0.7406184 0.6022351 -0.1696624 -0.7606317 0.6266212 -0.1922844 -0.7329515 0.6525403 -0.07686918 -0.7700489 0.6333371 -0.08821332 -0.7405902 0.6661416 -0.02277982 -0.7753602 0.6311085 -0.01983332 -0.7559242 0.6543588 -7.8216e-5 -0.7740452 0.6331304 -1.92075e-4 -0.7742047 0.6329354 0.02465969 -0.8226476 0.5680166 -0.2299278 -0.7769396 0.5860871 -0.3831057 -0.7553277 0.5317049 0.3592132 -0.6947371 0.6231423 0.3505876 -0.7022421 0.6196325 0.3149369 -0.6284494 0.7112427 0.3153816 -0.6277414 0.7116708 0.2329574 -0.5532495 0.7997787 0.2289852 -0.5764752 0.7843738 0.08156853 -0.4990621 0.8627188 0.08878892 -0.5342922 0.8406239 -0.1294919 -0.4646681 0.8759655 -0.1131899 -0.4983498 0.8595554 -0.3453122 -0.4625939 0.8165577 -0.3335634 -0.476659 0.813346 -0.5234631 -0.4695898 0.7109655 -0.5799268 -0.396643 0.7115893 -0.8269422 -0.003817856 0.562274 -0.2069434 -0.9313904 0.2994769 -0.2155864 -0.9207544 0.3251677 -0.3491221 -0.8044511 0.4805958 -0.1512781 -0.815705 0.5583371 -0.2948567 -0.8663257 0.4031617 -0.3692063 -0.7586262 0.5368176 -0.3851961 -0.7154667 0.5828649 -0.6010875 -0.1614721 0.7827009 -0.5835123 -0.04250717 0.8109912 -0.5957392 -0.1937634 0.7794554 -0.5263324 -0.4992122 0.6883033 -0.5292336 -0.4356507 0.7280937 -0.4731735 -0.6206576 0.6252127 -0.8227307 -0.10339 0.5589497 -0.8202039 -0.1612146 0.5488857 -0.7836965 -0.304555 0.541356 -0.7171917 -0.4988404 0.4866151 -0.7135202 -0.5046232 0.4860499 -0.2307128 -0.9497313 0.211618 -0.232005 -0.9443725 0.2330973 -0.6340209 -0.6710512 0.3843277 -0.4818813 -0.7959774 0.3663474 -0.4422819 -0.7951288 0.4149182 -0.2581723 -0.938709 0.2284133 -0.4245206 -0.7651029 0.4841488 -0.4235679 -0.8099101 0.4057536 -0.6260307 -0.498446 0.5996977 -0.6260336 -0.4984372 0.5997018 -0.7126947 -0.1611294 0.6827179 -0.712697 -0.1611251 0.6827164 -0.9832734 -0.1326679 0.1247906 0.4054934 -0.8289431 0.3852639 -0.8599429 -0.4836689 0.1629807 -0.8046026 -0.559641 0.1985364 -0.5563679 -0.7831343 0.2777689 -0.4501938 -0.8475326 0.2810947 -0.6356491 -0.7275356 0.2581515 0.7292931 -0.6568849 0.1913999 0.59445 -0.7736591 0.2192735 0.7282071 -0.6445175 0.2330485 0.396831 -0.8654869 0.3057083 0.2931479 -0.9037709 0.3118698 0.1272462 -0.932464 0.3381114 -0.1452351 -0.9350273 0.323467 -0.1625571 -0.9319139 0.3242094 -0.3027662 -0.8982259 0.3186267 0.780259 -0.2918717 0.553179 0.7032014 -0.1888471 0.6854522 0.447007 -0.2297168 0.8645317 0.5016536 -0.217024 0.8374034 0.2936473 -0.2190726 0.9304722 -0.1454186 -0.2257881 0.9632617 -0.02063351 -0.2392928 0.9707282 0.1970025 -0.2347205 0.9518909 -0.8774985 -0.1038557 0.4681991 -0.7900349 -0.1218569 0.6008294 -0.8605391 -0.1180042 0.4955276 -0.6143907 -0.183298 0.7674151 -0.5565719 -0.1859815 0.8097153 -0.4250105 -0.2144683 0.8794143 -0.233925 -0.2301855 0.944613 -0.9949716 -0.03973436 0.09193861 -0.9781628 -0.1207547 0.1691625 -0.9667937 -0.2372113 0.09508329 -0.9864296 -0.1544098 0.0558061 -0.9892502 -0.1239957 0.07751888 -0.9922775 -0.1040282 0.06755554 -0.8594238 -0.4287852 0.2784493 -0.8594318 -0.428775 0.2784405 -0.5548095 -0.6977618 0.453117 -0.554843 -0.6977421 0.4531064 -0.1447818 -0.8298416 0.5388889 -0.144758 -0.8298437 0.5388919 0.2923079 -0.8020479 0.5208409 0.29232 -0.8020433 0.5208414 0.8040061 -0.4986954 0.3238475 0.7702077 -0.5411497 0.337546 -0.9942476 -0.07109999 0.08010298 -0.8594249 -0.3393896 0.3823658 -0.8594227 -0.3393938 0.382367 -0.5548223 -0.5522844 0.6222172 -0.5548427 -0.5522757 0.6222068 -0.1447682 -0.656836 0.7400059 -0.1448277 -0.6568269 0.7400024 0.2923386 -0.6348277 0.7152146 0.2922549 -0.6348447 0.7152338 0.749481 -0.4394708 0.4951199 0.5084182 -0.6770235 0.5321187 -0.9751307 -0.04656893 0.2166829 -0.9885768 -0.0428707 0.1444926 -0.9831421 -0.08068162 0.1640791 -0.8594152 -0.2256054 0.4588114 -0.8594229 -0.2256013 0.4587987 -0.554828 -0.3671138 0.7465879 -0.5548429 -0.3671081 0.7465795 -0.1447791 -0.4366113 0.8879243 -0.1448273 -0.4366092 0.8879175 0.2923338 -0.4219865 0.8581774 0.2923184 -0.4219871 0.8581824 0.6129169 -0.3486607 0.7090618 0.6319571 -0.5005986 0.5916345 -0.51728 -0.339904 0.7854214 -0.4806817 -0.1891648 0.8562487 -0.9865351 0.06839799 0.1485608 -0.8838018 -0.3371587 0.3243741 -0.8586996 -0.4614394 0.2229545 -0.9076892 -0.1913347 0.3734856 -0.9902231 -0.05182516 0.1295082 -0.9896942 -0.0603972 0.1298371 -0.655074 -0.5903372 0.471572 -0.7912012 -0.2709405 0.5482629 -0.9056316 -0.1745745 0.3864651 -0.6517601 -0.01581281 0.7582604 -0.7233822 -0.4820879 0.4942769 -0.7430516 -0.2796779 0.6079924 -0.5170721 -0.3826506 0.7656468 -0.5130922 -0.3621476 0.7781939 -0.8806916 0.4727743 -0.02944487 -0.5688109 0.8224276 0.008194804 -0.9886288 0.1503571 -0.002429246 -0.7894609 0.6099324 -0.06880557 -0.7849075 0.619225 -0.0219205 -0.865624 0.4898005 -0.1038784 -0.7895062 0.6110428 -0.05750364 -0.7976898 0.5992788 -0.06749844 -0.7424784 0.6698368 -0.006682336 -0.9744302 0.2186519 -0.05174279 -0.810336 0.2184065 -0.5437409 -0.9142664 0.2333471 -0.3311588 -0.9543248 0.2670156 -0.1340407 -0.9488653 0.3057615 -0.07851451 -0.9364344 0.3495208 -0.03042912 0.324486 -0.6898039 0.647209 0.1915686 -0.5625564 0.8042586 0.4482256 -0.402504 0.7981756 0.3505535 -0.2708272 0.8965293 0.1022925 -0.2300497 0.9677879 0.3947572 -0.1143372 0.9116435 -0.7043938 -0.5000472 0.5037682 -0.6555705 -0.5573495 0.5094988 -0.8013024 -0.4308597 0.4150596 -0.8783396 -0.3525027 0.3228958 -0.8589066 -0.3850307 0.3376845 -0.910874 -0.2983608 0.2851132 -0.1904978 -0.6985876 0.6897 -0.2356302 -0.7084609 0.6652531 0.1845825 -0.4606428 0.8681806 0.1843932 -0.2802907 0.9420384 0.2134104 -0.2888135 0.9332968 0.2133225 -0.09497636 0.9723544 0.1593846 -0.07423418 0.9844216 -0.3551687 -0.1814416 0.9170246 -0.4611541 -0.6492053 0.6048715 -0.4639774 -0.6488566 0.6030838 -0.4596812 -0.4714422 0.752619 -0.7009702 -0.3961284 0.5930625 -0.6220514 -0.408817 0.667773 -0.8772656 -0.2696573 0.3971021 -0.8214866 -0.2952217 0.4878567 -0.9452083 -0.1797339 0.2725383 -0.9465607 -0.08937299 0.3098956 -0.9845089 -0.1275409 0.1203143 -0.9842414 -0.1281616 0.1218343 -0.9835599 -0.08863562 0.1573337 -0.996918 -0.04403752 0.06492525 -0.9903782 -0.03179186 0.1346864 0.3245403 -0.569456 0.7552441 0.1396147 -0.6093717 0.780496 0.1396355 -0.4508578 0.8816061 -0.08717745 -0.4676887 0.8795838 -0.08735769 -0.2962633 0.9511029 0.1131829 -0.2003352 0.9731678 -0.07737708 -0.1017745 0.9917938 -0.9829553 -0.02228486 0.182489 -0.8155956 -0.124777 0.5650084 -0.8209813 -0.1257702 0.5569304 -0.5644935 -0.1499494 0.8117034 -0.6205978 -0.1588637 0.7678677 -0.3644191 -0.1788193 0.9139051 -0.365021 -0.5069872 0.7808482 0.06134676 -0.5149298 0.8550345 -0.1903671 -0.608904 0.7700626 0.08195608 -0.5993229 0.7963011 0.08203899 -0.7160224 0.69324 0.1516396 -0.6878961 0.7097918 0.09245747 -0.6946071 0.7134231 0.3142454 -0.6543677 0.6877884 -0.427043 -0.7286633 0.535429 -0.6023332 -0.7567192 0.2541079 -0.7878543 -0.576384 0.2169498 -0.6627296 -0.7036935 0.2561348 -0.6732212 -0.6963246 0.2488081 -0.7153704 -0.5898194 0.3746443 -0.5549099 -0.5898767 0.586618 -0.6275752 -0.7081101 0.3236194 -0.601709 -0.6366456 0.4823161 -0.677532 -0.5563347 0.4810843 -0.6607921 -0.4966903 0.5627191 -0.7527361 -0.3560443 0.5537337 -0.6842525 -0.1473936 0.7141945 -0.5760421 -0.08674031 0.8128049 -0.5760139 -0.08673429 0.8128255 -0.5763684 -0.08670639 0.8125772 -0.4735017 -0.3449656 0.810429 -0.6046579 -0.1754415 0.776923 -0.5271046 -0.2104837 0.8233211 -0.501281 -0.2736448 0.8208752 -0.5760324 -0.08675169 0.8128105 -0.672229 -0.1755425 0.7192308 -0.6548298 -0.2624744 0.708735 -0.6553826 -0.2617079 0.7085074 -0.6427616 -0.326622 0.6929471 -0.6135316 -0.3786371 0.692974 -0.5960346 -0.4480196 0.6663492 -0.4595754 -0.5472444 0.6995099 -0.4967926 -0.5223601 0.6930636 -0.4452034 -0.3315163 0.8317998 0.07987952 -0.6001227 0.7959097 0.1228914 -0.6488642 0.7509148 0.01017117 -0.5172151 0.855795 0.1147954 -0.4454321 0.8879259 0.07820844 -0.4610771 0.8839069 0.009172856 -0.5165435 0.8562119 -0.01855754 -0.5107029 0.859557 -0.07017695 -0.5272837 0.8467863 -0.1514574 -0.5032654 0.8507553 -0.2144104 -0.511476 0.8321182 0.4127639 -0.6145677 0.6722593 0.489312 -0.6283643 0.6047579 0.5669142 -0.5094512 0.6473546 0.5090141 -0.2555045 0.8219624 0.5361061 -0.1867123 0.823243 0.5679727 -0.2267872 0.7911856 0.4848347 -0.3338918 0.8083635 0.6279364 -0.1336584 0.7667018 0.5903335 -0.1150836 0.7989131 0.5396466 -0.1917005 0.8197759 0.6769543 -0.1954939 0.7095879 0.6332238 -0.4112607 0.6556618 0.5920705 -0.4450163 0.6718728 0.6119197 -0.3813651 0.6929033 0.6456662 -0.3211513 0.6928038 0.6468014 -0.2582681 0.7175972 0.6831139 -0.1876749 0.7057858 0.6335294 -0.1384862 0.7612241 0.5973942 -0.7699185 0.2243788 0.7118337 -0.6369186 0.2960194 0.6985933 -0.607096 0.3786844 0.6607998 -0.5754369 0.481888 0.6462459 -0.5999876 0.4715732 0.6649971 -0.4998326 0.5549292 0.7138282 -0.4523579 0.534623 0.7232118 -0.3222839 0.6108174 0.6225408 -0.709016 0.3312693 0.6615945 -0.7077646 0.2477136 0.7652606 -0.6010462 0.2304773 0.6456272 -0.7415778 0.1822857 0.6044189 -0.6295709 0.4881786 0.6028794 -0.6355223 0.4823359 0.497974 -0.6516962 0.5721136 0.5194752 -0.6671189 0.5339456 0.3064291 -0.7343235 0.6056982 0.3222856 -0.6502376 0.6879848 0.2631645 -0.6364661 0.725021 0.2469524 -0.5820486 0.7747477 0.1557804 -0.5718325 0.805444 -0.3054257 -0.6543934 0.6917257 -0.3460051 -0.6375174 0.6883692 -0.2656857 -0.6337753 0.7264572 -0.1839613 -0.674839 0.7146681 -0.08701044 -0.6538052 0.7516435 -0.05357122 -0.6735309 0.7372152 0.1154297 -0.6699956 0.7333362 -0.2803626 -0.4676063 0.8382966 -0.3728414 -0.4788281 0.7948037 -0.444628 -0.5710214 0.6901018 -0.4446278 -0.5710219 0.6901016 -0.5036656 -0.6468337 0.5726493 -0.5903108 -0.6435196 0.4872532 -0.3552235 0.9334562 -0.04975825 -0.5068652 0.8615897 -0.02740842 -0.5361371 0.8441309 -2.02277e-4 -0.2274955 0.9735643 0.02045649 -0.322987 0.9324494 -0.161918 -0.1158237 0.9932353 0.008278906 -0.1471333 0.9805416 -0.1299614 -0.2266572 0.9663728 -0.1214505 -0.2220426 0.9656196 -0.1351886 -0.2818056 0.9581663 -0.05003088 -0.2968125 0.9473339 -0.1202538 -0.3671564 0.9300821 -0.011985 -0.3690193 0.9293775 -0.009076416 0.1013866 0.9809843 -0.1655012 0.1000065 0.9800484 -0.1717671 0.05480092 0.9818911 -0.1813476 0.05111473 0.9805732 -0.1893768 0 0.9812214 -0.1928848 0 0.9812212 -0.1928858 -0.05709409 0.9803293 -0.1889306 -0.04925638 0.9819718 -0.182497 -0.1046138 0.9797421 -0.1707671 -0.09791082 0.9808836 -0.1681692 0.03283029 0.9978691 -0.05638754 0.03283041 0.997869 -0.05638915 0.01700294 0.9978691 -0.06299465 0.01700246 0.997869 -0.06299591 0 0.9978691 -0.06524884 0 0.997869 -0.06524974 -0.01700234 0.9978692 -0.06299346 -0.01700294 0.997869 -0.06299597 -0.03283077 0.9978691 -0.05638736 -0.03282999 0.9978691 -0.05638837 0.3005337 0.9128918 -0.2762397 0.2789283 0.9539617 -0.1102545 0.3450113 0.9361761 -0.06739097 0.3982705 0.9146154 -0.06970959 0.1031123 0.9911711 -0.08335328 0.1050237 0.9900821 -0.09331393 0.1271907 0.9902571 -0.05668723 0.2083936 0.9744166 -0.0841701 0.136767 0.9890624 -0.05523198 0.1296096 0.9912418 -0.02532011 0.1383057 0.9899101 -0.03081732 0.1367014 0.990396 -0.02070355 -0.0928446 0.9935805 0.06463426 -0.09118163 0.9900201 0.1074534 -0.09665882 0.9782708 0.1834212 -0.05880844 0.9842969 0.1664367 -0.0299685 0.9839091 0.1761384 -0.02996933 0.9839099 0.1761339 0.02633434 0.9839095 0.1767163 0.02633655 0.9839094 0.1767165 0.1001733 0.9935587 0.05297672 0.08978819 0.9885094 0.1216031 0.08996796 0.9796176 0.1795973 0.2522023 0.9279803 0.2743111 0.05821716 0.9842858 0.1667106 0.0747708 0.9903704 0.1165152 0.09852647 0.9901555 0.09942162 0.09852588 0.9901555 0.09942185 0.1245743 0.9901555 0.06382334 0.1245743 0.9901556 0.06382107 0.1382509 0.9901555 0.02188342 0.1382512 0.9901554 0.02188366 0.4039972 0.914281 -0.02961075 0.1382366 0.9903475 -0.01013237 0.1382371 0.9903473 -0.01013499 0.4039846 0.9142863 -0.02961426 0.4034442 0.9127731 0.06386101 0.4034373 0.9127761 0.06386041 0.3635361 0.912773 0.1862443 0.3635303 0.9127754 0.1862438 0.2875187 0.9127742 0.2901316 0.2875211 0.9127736 0.2901309 0.1829466 0.9127755 0.3652008 0.1829469 0.912775 0.3652018 0.06020885 0.9127762 0.403998 0.06020462 0.9127733 0.4040054 -0.06851506 0.9127749 0.4026756 -0.06851124 0.9127749 0.4026767 -0.1904292 0.9127755 0.3613554 -0.1904229 0.9127757 0.3613581 -0.2934308 0.9127748 0.2841491 -0.2934281 0.9127757 0.2841488 -0.3672884 0.9127751 0.17872 -0.3672903 0.9127745 0.1787196 -0.4046747 0.9127725 0.05553996 -0.4046667 0.9127761 0.05554062 -0.1380274 0.9903611 -0.0115481 -0.4034364 0.9143851 -0.0337516 -0.4034408 0.9143833 -0.03374797 -0.1380355 0.99036 -0.0115472 -0.1386718 0.9901555 0.01903289 -0.1386713 0.9901556 0.01903158 -0.125862 0.9901556 0.06124371 -0.1258639 0.9901553 0.06124371 -0.100553 0.9901556 0.09737133 -0.1005538 0.9901555 0.09737157 -0.08095288 0.9903934 0.1121066 -0.003241896 0.9999826 0.00494343 0.8426406 0.3074295 0.4420905 0.8426398 0.3074344 0.4420886 0.8473785 -0.04796999 0.5288181 0.8211503 -0.1623877 0.5471221 0.7874946 -0.2827405 0.5476406 0.6135079 -0.5979903 0.5157672 0.6134886 -0.5980072 0.5157704 0.2736046 -0.8621273 0.4264707 0.249292 -0.843719 0.4753861 0.234277 -0.8582425 0.4566555 0.4116184 -0.5628844 0.7167506 0.4199833 -0.5331732 0.734398 0.5117318 -0.1156041 0.8513322 0.5128425 -0.1092159 0.8515071 0.5188367 0.1196833 0.846454 0.494556 0.3678273 0.7874754 0.5026886 0.3354775 0.7967177 0.6978393 0.6635677 0.2696264 0.6978396 0.6635674 0.2696262 0.5611668 0.6989676 0.443324 0.3967783 0.6934309 0.6014323 0.3824035 0.7178683 0.5817497 0.5611453 0.6989896 0.4433166 0.6901603 0.347465 0.634781 0.6901558 0.34746 0.6347886 0.6875758 -0.1264121 0.7150242 0.6875733 -0.1263985 0.715029 0.5246657 -0.5735982 0.6290556 0.5246679 -0.5736139 0.6290395 0.273591 -0.8621217 0.4264907 0.3021876 -0.8699179 0.3897763 0.3021817 -0.8699128 0.3897923 0 0.6934962 0.7204604 0.1549944 -0.8414003 0.5177088 -0.03904706 -0.8433449 0.5359522 0.2066321 0.6935032 0.6901859 0.2066245 0.6935021 0.6901892 0.270264 0.3347063 0.9027342 0.2702602 0.3218511 0.9073982 0.2847583 0.1192668 0.951151 0.2849001 -0.1150236 0.9516311 0.2848899 -0.1150245 0.9516339 0.2431272 -0.5304432 0.8121079 0.2431234 -0.5304448 0.812108 0.1549947 -0.8413845 0.5177344 -0.1998418 0.7172831 0.6675091 -0.2038026 0.6937133 0.6908158 0 0.6934987 0.7204579 0 0.3217888 0.9468115 0 0.321786 0.9468125 0 -0.1150241 0.9933628 0 -0.1150234 0.9933628 0 -0.5304423 0.8477211 0 -0.5304434 0.8477204 0 -0.6743113 0.7384472 0.03904706 -0.8433449 0.5359522 -0.1467757 -0.8591303 0.4902571 -0.1521017 -0.8415864 0.5182638 -0.1965326 -0.7282934 0.6564783 -0.2431318 -0.5304468 0.8121042 -0.2403323 -0.5397558 0.8067862 -0.2860613 -0.1150035 0.951285 -0.2860537 -0.1150626 0.9512802 -0.2704947 0.3218375 0.9073331 -0.2705067 0.3322778 0.9035583 -0.239385 0.5507136 0.7996309 -0.5616372 0.6981993 0.4439387 -0.3853499 0.7170798 0.5807772 -0.3853562 0.7170738 0.5807803 -0.4510999 0.5513066 0.7018334 -0.4976042 0.3642929 0.7871982 -0.5001231 0.3331784 0.799293 -0.5111512 -0.115633 0.851677 -0.5111424 -0.1156325 0.8516823 -0.4170951 -0.5425655 0.7291464 -0.4088984 -0.5708321 0.7120062 -0.3287196 -0.731167 0.5977778 -0.2699655 -0.8648412 0.4232828 -0.2977289 -0.8724019 0.3876499 -0.2977012 -0.8724132 0.387646 -0.6077166 -0.6053997 0.5139765 -0.6983867 0.6627723 0.2701647 -0.8432591 0.3040026 0.4432794 -0.843261 0.3040175 0.4432656 -0.8469982 -0.05049234 0.5291925 -0.8194793 -0.1687839 0.5476913 -0.7861067 -0.2864987 0.5476815 -0.6077238 -0.6053926 0.5139763 -0.2337519 -0.8613101 0.4511155 -0.2337615 -0.8613054 0.4511194 -0.2699733 -0.8648393 0.4232819 -0.520056 -0.5813401 0.625768 -0.5200669 -0.5813419 0.6257572 -0.6863861 -0.1328995 0.7149908 -0.6863903 -0.1329056 0.7149857 -0.69076 0.3440462 0.6359897 -0.6907549 0.3440726 0.635981 -0.5616542 0.6981717 0.4439606 -0.6984183 0.6627401 0.2701622 -0.374292 -0.8285082 0.4165091 -0.454289 -0.6569819 0.6016614 -0.7000737 -0.1610943 0.695662 -0.6772086 -0.2787047 0.6809642 -0.6306525 -0.406051 0.6613623 -0.5360055 -0.6138277 0.5795807 -0.5409114 -0.604988 0.5842983 -0.4339995 -0.7463448 0.5045927 -0.2061535 -0.9626936 0.1752766 -0.3889484 -0.7647968 0.5136196 -0.4949978 -0.5082711 0.7047252 -0.4460774 -0.6333581 0.6323548 -0.5339748 -0.1680724 0.8286269 -0.5364817 -0.1349225 0.8330567 -0.5048311 -0.2212994 0.8343694 -0.4422161 -0.739508 0.5075164 -0.6416515 -0.2327274 0.730836 -0.6302115 -0.2764273 0.7255492 -0.5199161 -0.6120347 0.5959033 -0.5246404 -0.6042656 0.5996795 -0.2809652 -0.8849335 0.3714181 -0.3782393 -0.8077703 0.452153 -0.3757091 -0.8219102 0.428143 -0.3857832 -0.8119956 0.4379894 -0.3999716 -0.8134477 0.4222864 -0.3225806 -0.887355 0.3294584 -0.3021415 -0.8894866 0.3428181 -0.283796 -0.9056792 0.3149684 -0.5551415 -0.3776761 0.741066 -0.6227157 -0.2861918 0.7282304 -0.5793747 -0.2888659 0.7621557 -0.3602334 -0.8296 0.4266096 -0.6028299 -0.1594885 0.781767 -0.04400247 -0.9957534 -0.08086508 -0.0439701 -0.9957548 -0.08086341 -0.4975602 -0.4631177 0.7334548 -0.5305523 -0.3416164 0.7757658 -0.5759487 -0.3359936 0.7452459 -0.5430139 -0.5024879 0.6727867 -0.5020391 -0.613053 0.6100187 -0.4878563 -0.6529386 0.5793682 -0.4200142 -0.7793086 0.4650444 -0.3836276 -0.7833954 0.4890006 -0.3269454 -0.862337 0.3866284 0.3121839 -0.8456891 0.4328407 0.3405075 -0.807066 0.482389 0.4245132 -0.7655086 0.4835134 0.2535911 -0.9004664 0.3533439 0.2036001 -0.9334087 0.2954574 0.2126442 -0.9233267 0.319766 0.2288931 -0.9559054 0.1839916 0.4935045 -0.7956134 0.3513583 0.5026768 -0.7800378 0.3726357 0.6880383 -0.5479038 0.4758201 0.7194249 -0.4987056 0.4834465 0.7655987 -0.363291 0.5309221 0.8203321 -0.1262083 0.5577874 0.8191282 -0.1612423 0.5504816 0.7474812 -0.1616649 0.6443107 0.6946269 0.05047911 0.717597 0.5344636 -0.4634086 0.7068248 0.5154523 -0.4987801 0.6967979 0.4649869 -0.6360255 0.61584 0.3901671 -0.7536096 0.5290014 0.2305672 -0.9502228 0.2095599 0.2564015 -0.9396252 0.2266341 0.4422966 -0.7951188 0.4149216 0.4235767 -0.8099049 0.4057548 0.6260345 -0.4984427 0.5996963 0.6260307 -0.4984451 0.5996983 0.7126975 -0.161132 0.6827144 0.6032011 -0.161498 0.7810679 0.6001313 -0.1708598 0.7814406 -0.6741978 0.09289932 0.7326849 -0.9752047 -0.04597765 0.2164765 0.152401 -0.7888833 0.5953462 -0.6550789 -0.5118418 0.5557786 -0.4609603 -0.6409113 0.6137983 -0.3388997 -0.6778689 0.6524116 -0.2361942 -0.7372862 0.6329467 0.006444871 -0.7604249 0.6493939 0.253257 -0.823567 0.5075417 0.2644177 -0.840619 0.4726978 -0.8512687 -0.3050705 0.4269353 -0.7966048 -0.3835824 0.4672103 -0.6526278 -0.5127564 0.5578153 -0.9025048 -0.2262765 0.3664481 -0.8730913 -0.2641968 0.4097703 -0.8481851 -0.2022595 0.4895642 -0.7640333 -0.2037973 0.6121438 -0.4937931 -0.3028663 0.8151322 -0.3942072 -0.3226219 0.8605324 -0.3928872 -0.3173543 0.8630909 -0.1709939 -0.2102539 0.962577 0.2023028 -0.3879587 0.8992005 -0.02624952 -0.1977652 0.9798979 -0.1857069 -0.4208563 0.887915 0.1353459 -0.2066919 0.9689995 0.4380589 -0.2538281 0.8623664 0.5041025 -0.004798769 0.8636305 0.7067162 -0.1569556 0.6898675 0.6427842 -0.2585079 0.7211118 0.6426304 -0.2175613 0.7346382 0.6185354 -0.4141545 0.66775 0.2405201 -0.9009171 0.3612458 0.2861109 -0.8852633 0.3666737 0.01365751 -0.7635943 0.645552 0.04686051 -0.7678048 0.6389678 0.0839582 -0.7501422 0.6559253 0.1210417 -0.7617119 0.6365091 0.1956843 -0.7405755 0.6428497 0.2180025 -0.75652 0.6165651 0.3258538 -0.7422171 0.5856049 0.5128924 -0.6038416 0.6101776 0.5495627 -0.4759718 0.6866089 0.4128687 -0.4697301 0.7803162 0.4091587 -0.4615006 0.7871509 0.1850479 -0.4904727 0.8515831 0.1636716 -0.4672231 0.8688579 -0.02654093 -0.5205975 0.8533896 -0.06081199 -0.4997894 0.8640096 -0.1973074 -0.5640676 0.8018091 -0.2268334 -0.5521094 0.8023228 -0.660814 -0.3087259 0.6841149 -0.5937548 -0.3878422 0.7050061 -0.5933408 -0.388089 0.7052189 -0.3130158 -0.6247348 0.7153514 -0.3124867 -0.6248557 0.7154771 7.31583e-5 -0.7740098 0.6331738 0.001626133 -0.7739381 0.6332592 0.205838 -0.8184525 0.5364386 0.2076814 -0.8627645 0.4609837 0.205526 -0.8628882 0.4617177 0.1950821 -0.8829006 0.4271176 0.2215798 -0.880614 0.4188334 0.2040351 -0.8979847 0.389863 0.2388141 -0.8898527 0.3887547 0.329068 -0.7483562 0.5759143 0.3910812 -0.7512552 0.5316684 0.4192334 -0.7383512 0.5282812 -0.5167684 -0.5581254 0.6491891 -0.5848191 -0.6364719 0.502882 -0.2415552 -0.9021549 0.3574461 -0.9567274 0.2884989 0.03796112 -0.9892909 -0.03843152 0.1408069 -0.1860617 -0.8931024 0.409572 -0.6900577 -0.3654771 0.6246975 -0.5504477 -0.4822314 0.6815133 -0.5367394 -0.3906976 0.7478411 -0.5127164 -0.4232143 0.7470018 -0.9889591 0.1386473 0.05231499 -0.9971192 0.07584482 9.42612e-4 -0.9897559 -0.03157705 0.1392335 -0.9891881 -0.03768366 0.1417281 -0.9223141 -0.1636409 0.3500837 -0.905668 -0.2026728 0.3724101 -0.5244287 -0.6207215 0.5828202 -0.7406741 -0.4208389 0.5237332 -0.6692339 -0.4459079 0.5943839 -0.8689616 -0.3763058 0.3214029 -0.8594217 -0.4005321 0.3177551 -0.6966972 -0.6135708 0.3716773 -0.7101134 -0.593373 0.3790088 -0.4691484 -0.7943102 0.3859679 -0.5240197 -0.7382763 0.4246781 -0.3334442 -0.8588017 0.3889404 -0.9305865 0.3634727 -0.04354739 -0.9738184 0.2268171 0.01522612 -0.9886366 0.1262469 0.08160597 -0.9889885 0.1235651 0.08144593 -0.9703502 -0.07667386 0.2292199 -0.9813423 0.03226721 0.1895424 -0.884243 -0.2610943 0.3872262 -0.9209004 -0.1529056 0.3585562 -0.8037726 -0.3539622 0.4781845 -0.7956335 -0.2808104 0.5367615 -0.7910408 -0.2870887 0.5402172 -0.9160014 0.3993142 0.03859919 -0.920552 0.3899511 0.02284967 -0.9800602 0.1848059 0.07299935 -0.9466038 0.3111672 0.08435755 -0.9872883 0.05588656 0.1487902 -0.9877225 0.03650939 0.1518929 -0.9745013 -0.1135216 0.1935465 -0.9663802 0.1919792 0.1710358 -0.934184 -0.2389905 0.2649221 -0.9629849 -0.05046325 0.2647899 -0.8495892 -0.3748066 0.3711039 -0.8855081 -0.2654788 0.3813089 -0.6965817 -0.5592496 0.4494596 -0.7521926 -0.4594794 0.4723188 -0.5094788 -0.7026663 0.4966805 -0.5801559 -0.6169928 0.5317321 -0.3092927 -0.7999895 0.5141545 -0.4593589 -0.6594516 0.5950739 -0.7765536 0.6297211 0.02039515 -0.7481524 0.6407196 0.1724717 -0.908655 0.4104959 0.07641553 -0.9667319 0.2078324 0.1491149 -0.9691873 0.1874465 0.1598116 -0.2473134 -0.9130046 0.3244358 -0.377246 -0.8536006 0.3592377 -0.4771838 -0.8088304 0.3436408 -0.7036255 -0.6247912 0.3384485 -0.7035096 -0.6249037 0.3384813 -0.8728966 -0.3820697 0.3034375 -0.8728289 -0.3821908 0.3034799 -0.9657287 -0.09915328 0.2398681 -0.9657129 -0.09922647 0.2399017 -0.9787896 0.06926906 0.1928027 -0.8386092 0.5246017 0.1467235 -0.9279774 0.2261378 0.2961752 -0.925884 0.2607702 0.2733821 -0.9338321 -0.06701034 0.3513792 -0.9274712 -0.09422963 0.3618262 -0.8444327 -0.3531591 0.4027555 -0.8590508 -0.3269311 0.3938882 -0.6805494 -0.6010023 0.4191046 -0.6496568 -0.6292221 0.4266446 -0.3793109 -0.8557509 0.3518716 -0.3130022 -0.8809961 0.3547896 0.4299927 -0.8333569 0.3473076 0.4640679 -0.8525575 0.240389 0.4506624 -0.8598753 0.2398291 0.5236458 -0.8390074 0.1478575 0.554777 -0.8201855 0.1397086 0.1887723 -0.9809236 0.04641163 0.1858994 -0.981805 0.03873467 0.3487612 -0.8685478 0.3521229 0.1343366 -0.9816098 0.1356317 0.1695061 -0.98161 0.08780485 0.2061018 -0.9700977 0.1281898 0.1681684 -0.983716 0.0634219 0.04584968 -0.9819628 0.183431 0.05932277 -0.9820395 0.1791068 0.08775687 -0.9809224 0.1734651 0.08734494 -0.9816496 0.169514 0.1343411 -0.981609 0.1356332 0.02072483 -0.972322 0.232724 0.02968221 -0.9816098 0.1885769 -0.01679825 -0.9819039 0.1886336 -0.03289079 -0.9773706 0.2089617 -0.05209714 -0.9838857 0.1710407 -0.09444886 -0.9778677 0.1866929 -0.09411072 -0.9821143 0.1630792 -0.1359058 -0.9811735 0.137216 -0.1424135 -0.9781005 0.1517819 -0.1690802 -0.9836106 0.06262731 -0.1888169 -0.9809145 0.04642051 -0.1859178 -0.9818058 0.03862661 -0.5243551 -0.8391672 0.1443958 -0.5468994 -0.8257958 0.1377036 -0.4600876 -0.8552886 0.2383291 -0.1881214 -0.9772993 0.09744966 -0.1513763 -0.9834439 0.09961599 -0.2330174 -0.8564782 0.4605953 -0.3488374 -0.8288621 0.4373786 -0.3477663 -0.8693526 0.3511193 -0.4326433 -0.8278192 0.3571208 -0.4587963 -0.8564637 0.236592 0.3562893 -0.8399462 0.4093267 0.2463608 -0.8379552 0.4869677 0.246363 -0.8379557 0.4869658 0.08485007 -0.8379558 0.5391017 0.0848639 -0.8379498 0.5391088 -0.03928709 -0.8403333 0.5406445 -0.07687163 -0.8692477 0.4883638 -0.1395484 -0.8285932 0.5421805 -0.2330407 -0.8548324 0.463631 -0.009518444 0.9999503 -0.002977669 -0.01211512 0.9998142 0.01499414 0.190159 0.9711483 0.1439113 0 1 2.4603e-6 0 1 8.51352e-7 0 1 0 0 1 9.67353e-7 0 0.9999898 0.004538655 0 1 -4.92738e-6 0.003809869 0.9999925 7.02848e-4 -0.001161158 0.9996215 -0.02749186 -0.001111388 0.9999781 0.006532788 0.002546846 0.9998508 0.01709097 -0.003419518 0.9999573 0.008588314 0 1 -8.08074e-7 0 1 7.66622e-7 0 1 -1.76564e-6 1.55289e-4 0.999714 0.02391612 -0.001310169 0.9999877 -0.004796624 6.28008e-4 0.9998278 0.01855182 0 1 -3.80822e-7 0 1 1.31027e-7 0 1 -3.19824e-7 -0.08078235 0.991627 -0.1007474 -0.1256682 0.9907984 -0.05026119 -0.1356762 0.9903669 -0.02767026 -0.139093 0.9898258 -0.02996885 -0.395878 0.9143335 -0.0852943 -0.2948275 0.9553076 -0.02154839 -0.1050716 0.9907998 -0.08529925 -0.1046963 0.9908446 -0.08524054 -0.1330411 0.9890947 -0.06318122 -0.1389195 0.9881113 -0.0658605 -0.3183547 0.9383704 -0.1345787 0.0036273 0.9996086 -0.02773952 -0.0678367 0.9915319 -0.1107371 -0.06783658 0.9915322 -0.1107348 -0.03774404 0.9914515 -0.1248982 -0.0377435 0.9914513 -0.1248999 -0.01674467 0.9916298 -0.1280243 -0.04155987 0.9921847 -0.1176535 0 0.9838476 -0.1790089 0.007761299 0.9867676 -0.1619551 0.04074716 0.9913895 -0.1244451 0.03774404 0.9914515 -0.1248982 0.03774356 0.9914513 -0.1249001 0.0678364 0.9915322 -0.1107345 0.06783646 0.9915319 -0.1107384 0.144569 -0.9396826 0.3099946 0.1450121 -0.939558 0.3101649 0.144544 -0.9396932 0.3099738 0.1445362 -0.9396932 0.3099777 0.1445435 -0.9396928 0.3099755 0.1445469 -0.9396919 0.3099765 0.1442479 -0.9397769 0.3098582 0.1445387 -0.9397007 0.3099535 0.1445477 -0.9396919 0.3099761 0.1445098 -0.9396921 0.3099933 0.1445434 -0.9396925 0.3099764 0.1445528 -0.9396912 0.3099759 0.1445436 -0.9396928 0.3099752 0.1444988 -0.9397037 0.3099631 0.144714 -0.9396414 0.3100516 0.1447064 -0.9396495 0.3100306 -0.09901279 -0.938517 0.33073 -0.01958066 -0.9629976 0.2687978 0.09902536 -0.9384986 0.3307785 0.06951904 -0.9469416 0.3137972 0.02490609 -0.939401 0.3419144 -0.07560515 -0.937003 0.3410415 -0.07562136 -0.9369994 0.3410478 -0.1445434 -0.939693 0.3099747 -0.1445311 -0.9396939 0.3099778 -0.1445423 -0.9396942 0.3099716 -0.1445469 -0.9396916 0.3099772 -0.1445426 -0.9396931 0.3099747 -0.1445446 -0.9396923 0.3099762 -0.1459371 -0.940254 0.3076114 -0.1444646 -0.9397603 0.3098072 -0.1446304 -0.9395653 0.3103213 -0.1445445 -0.9396998 0.3099535 -0.144553 -0.9396892 0.309982 -0.1445088 -0.9396929 0.309991 -0.1445216 -0.9396975 0.3099713 -0.1445465 -0.9396924 0.3099753 -0.1445243 -0.9396959 0.309975 -0.1445453 -0.9396923 0.3099763 -0.6101512 -0.7270692 0.3147793 -0.1654821 -0.9807176 0.1039656 -0.4826856 -0.8187959 0.3107862 -0.2683205 -0.9406224 0.2079271 -0.1123726 -0.9928659 0.03987258 -0.124587 -0.9918174 0.02786427 -0.1132085 -0.9904403 0.07881563 -0.6438948 -0.7518834 0.141672 -0.6256712 -0.7623242 0.1655218 -0.632139 -0.7560711 0.1695787 -0.5224551 -0.8186044 0.2385949 -0.4765051 -0.8309799 0.2870808 -0.1662703 -0.9751222 0.1465983 -0.5032947 -0.8640779 -0.00799787 -0.4899879 -0.869539 0.06175583 -0.2903733 -0.9121603 0.289218 -0.2698715 -0.9065296 0.3246126 -0.3784515 -0.8846887 0.2722142 0.3346071 -0.8170604 0.4695216 0.439571 -0.7421405 0.5059692 0.5322433 -0.6074908 0.5896372 0.618824 -0.2744392 0.7360299 0.6837051 -0.1533084 0.7134732 0.4615866 -0.5173231 0.7206349 0.4979144 -0.3773614 0.7808198 0.5889183 -0.1830236 0.7871961 0.5467265 -0.1886698 0.8157781 0.5378074 -0.2402074 0.8081235 0.5049612 -0.2436235 0.828047 0.5114169 -0.2132682 0.8324478 0.1737223 -0.9687741 0.1769107 0.2711881 -0.905984 0.3250385 0.3504066 -0.800813 0.4857097 0.3917338 -0.7964932 0.4605903 0.4149935 -0.7318229 0.5405698 0.4539452 -0.7271274 0.5149949 0.5012572 -0.6121029 0.6116138 0.5306103 -0.6102463 0.588262 0.6705505 -0.1689893 0.7223604 0.623658 -0.4150745 0.6623926 0.6727679 -0.2226452 0.7055582 0.4265293 -0.6637884 0.614376 0.4542039 -0.5335633 0.7134487 0.5024596 -0.5286072 0.6841848 0.5079504 -0.4397306 0.7406911 0.5612118 -0.4331008 0.7053121 0.5777334 -0.2854955 0.7646676 0.612708 -0.2835838 0.7376782 0.3148763 -0.8875681 0.3362678 0.3291942 -0.8711063 0.3644243 0.3239315 -0.8912491 0.3174013 0.3941732 -0.8124734 0.4295519 0.3857187 -0.8115866 0.4388034 0.421021 -0.7652727 0.4869283 0.281832 -0.8845471 0.3716816 -0.02897399 -0.9044389 0.4256183 0.1113358 -0.9646778 0.2387495 0.03068757 -0.994583 0.09931254 0.07339316 -0.9848057 0.1573897 0.02639186 -0.9363872 0.3499752 -0.3020026 -0.9034164 0.3043573 0.1471766 -0.9428503 0.2989525 -0.01267713 -0.9177827 0.3968808 -0.2393391 -0.9140148 0.3275571 -0.1986683 -0.9185082 0.3418681 -0.1964586 -0.9354897 0.2937061 -0.2894615 -0.8795199 0.3776996 -0.2020694 -0.9082916 0.3662983 -0.08403509 -0.9830591 0.1628897 -0.01805877 -0.9808159 0.1940986 -0.02352905 -0.8871907 0.4608026 -0.06633126 -0.9215626 0.3825214 -0.06638216 -0.9215589 0.3825215 -0.01261496 -0.9177751 0.3969002 0.07520973 -0.8744069 0.4793288 0.03647541 -0.9118052 0.4089999 -0.2383922 -0.9140841 0.328054 -0.1593804 -0.8847861 0.4378944 -0.03569561 -0.9547557 0.2952412 -0.06953704 -0.9627938 0.2611375 0.03941828 -0.9100318 0.4126602 0.03675276 -0.9120249 0.4084848 0.03618049 -0.9118841 0.40885 0.1080374 -0.9048395 0.4118174 0.3089201 -0.8665085 0.3920861 0.308054 -0.8679109 0.3896582 0.3038555 -0.8808414 0.3630292 0.1147872 -0.9010578 0.418233 0.1116366 -0.8989861 0.423511 0.1289729 -0.9015803 0.4129397 0.1870162 -0.9276032 0.3233841 0.1738272 -0.9310289 0.3208883 -0.08192199 -0.8924434 0.4436596 -0.04245817 -0.9379944 0.3440407 -0.04660987 -0.9210376 0.3866748 -0.05263197 -0.9186428 0.391568 -0.0664497 -0.9014718 0.4277069 -0.08994752 -0.8879565 0.4510463 -0.0464192 -0.926382 0.3737133 -0.08282101 -0.8914423 0.4455012 -0.04208636 -0.924526 0.3787881 -0.03797698 -0.9265117 0.3743447 0.02039986 -0.9550084 0.2958768 -0.01413619 -0.9423811 0.3342426 0.07852119 -0.984371 0.1576333 0.02388477 -0.9820406 0.1871522 -0.1408696 -0.9428476 0.3019837 -0.0343132 -0.9966986 0.07358443 -0.06311494 -0.9857729 0.1557831 -0.09156024 -0.9747695 0.2035712 -0.1275107 -0.9531888 0.2741755 0.5421171 -0.8051444 0.2405235 0.5057865 -0.8322325 0.2270887 0.2358672 -0.9687029 -0.07733994 0.02136701 -0.9959194 0.08768123 0.09730887 -0.9928585 0.06901448 -0.0727232 -0.9828881 0.1692412 0.1812576 -0.9812574 0.06541937 0.4039006 -0.882443 0.2411611 0.4108821 -0.8529391 0.3219795 0.451959 -0.8522352 0.2634925 0.6073577 -0.7492756 0.2640128 0.5485185 -0.7975385 0.2511175 0.07943117 -0.9033461 0.4214934 -0.005031764 -0.8430128 0.53787 0.3398079 -0.9336339 0.1133951 0.3383864 -0.8972868 0.2834981 0.4339548 -0.8995433 0.0500527 0.5166297 -0.8025228 0.298414 0.5053923 -0.8284208 0.2414491 -0.5487345 -0.8042829 0.2280781 -0.4216858 -0.6782062 0.6018452 0.08565706 -0.5722652 0.815583 -0.2945833 -0.9047146 0.3077535 -0.2920348 -0.9053934 0.3081858 -0.1818369 -0.8741904 0.4502515 -0.3397603 -0.8632126 0.3733993 -0.03175252 -0.8642899 0.5019907 0.4604622 -0.3799759 0.8022424 -0.1428117 -0.9219883 0.3599202 -0.1437142 -0.9218488 0.3599183 -0.142757 -0.9219917 0.3599332 0.09348654 -0.9019417 0.4216179 0.09349799 -0.9019524 0.4215923 0.08246397 -0.9516578 0.295884 0.7091846 -0.5436682 0.4488676 0.7091387 -0.5438008 0.4487795 0.1845619 -0.8564179 0.4821673 0.09339064 -0.9019652 0.4215888 0.1833226 -0.8558664 0.4836173 0.07013195 -0.9446899 0.3203789 0.2858134 -0.6991332 0.6553804 0.2463753 -0.6597366 0.7099626 0.2682735 -0.6567191 0.7048045 0.1676627 -0.54753 0.8198172 0.1629979 -0.4815472 0.8611295 0.118394 -0.3499593 0.9292532 0.3094768 -0.5312906 0.788641 -0.1364769 -0.6335753 0.7615488 -0.1124406 -0.6101989 0.7842286 -0.4746009 -0.6918807 0.5441096 -0.6903086 -0.7149075 0.1112719 -0.678989 -0.7212233 0.1371534 -0.684801 -0.714639 0.142614 -0.6461588 -0.7077063 0.2857109 -0.6567057 -0.7026237 0.2739664 -0.5580753 -0.794596 0.2391004 -0.5637571 -0.8015698 0.1991578 -0.5830468 -0.7525017 0.3062639 -0.5572231 -0.7809752 0.2820999 -0.5655069 -0.6968255 0.4411759 -0.5946341 -0.6577245 0.4623947 -0.5957056 -0.6699539 0.4430538 -0.3134055 -0.8922994 0.3249291 -0.3488937 -0.859438 0.373684 -0.2331134 -0.8220852 0.5194557 -0.07045924 -0.8046876 0.5895029 -0.04896986 -0.8265344 0.5607521 -0.1428008 -0.9219596 0.359998 -0.3581854 -0.6229798 0.6954132 -0.4488485 -0.4753694 0.7566763 -0.3274264 -0.6607363 0.6754403 -0.3380253 -0.7490561 0.5697843 -0.3474417 -0.7378838 0.5786293 -0.3559617 -0.8345561 0.4204847 -0.4033125 -0.7823263 0.4746627 -0.3685219 -0.8777461 0.3061919 -0.09540128 -0.5837539 0.8063064 -0.09848248 -0.5909646 0.8006635 -0.0551694 -0.6439491 0.7630766 -0.07101029 -0.7742229 0.6289169 -0.03876036 -0.8063662 0.5901451 0.06925219 -0.7255161 0.6847121 0.1443331 -0.8003039 0.5819638 0.2435472 -0.7158192 0.654437 0.1701064 -0.8445664 0.5077121 0.4297736 -0.711835 0.5555047 0.6055543 -0.7192023 0.3406642 0.431784 -0.8561819 0.2837519 -0.32097 -0.6553594 0.6837269 -0.1082414 -0.7449652 0.6582635 -0.1340247 -0.7713736 0.6221096 -0.108193 -0.8760892 0.4698534 -0.02616178 -0.7970155 0.603392 -0.1151202 -0.8859482 0.4492697 -0.118891 -0.8901919 0.4397992 -0.1141986 -0.9078097 0.4035349 -0.1097915 -0.9070568 0.4064404 -0.1189024 -0.9208043 0.3714588 -0.1009281 -0.9432429 0.3163961 0.08781093 -0.9102538 0.4046323 0.1006805 -0.9012482 0.4214443 0.09969604 -0.8994907 0.4254143 0.1021859 -0.9014365 0.4206786 0.1064218 -0.9034827 0.4152031 0.0776031 -0.9047912 0.418725 0.07366746 -0.9072711 0.414044 -0.1168885 -0.7270097 0.6766048 0.01145893 -0.8212063 0.5705164 0.189999 -0.8427787 0.5036115 0.1846019 -0.8361677 0.5164743 0.338367 -0.8686187 0.3619522 0.3356908 -0.8449329 0.4164136 0.4297405 -0.8438535 0.3213011 0.4415096 -0.8463402 0.2979561 0.6395534 -0.7224478 0.2627559 0.4836947 -0.6820472 0.548499 0.5180535 -0.7027414 0.4876219 0.6341344 -0.7289816 0.2577976 0.5846973 -0.6812512 0.4404839 0.6394237 -0.7119126 0.2903751 0.4001082 -0.6912051 0.6017882 0.5321421 -0.7446359 0.4029172 0.5243258 -0.7539399 0.3957992 0.6291801 -0.7570545 0.1760709 0.6763669 -0.7243623 0.1335184 -0.262708 -0.442157 0.8576024 -0.2244922 -0.4911847 0.84163 -0.1607868 -0.476389 0.8644079 -0.08962404 -0.55899 0.8243165 -0.007700443 -0.5650171 0.8250434 0.03675401 -0.6112754 0.7905641 0.1426039 -0.6319184 0.7618027 0.1518933 -0.6405365 0.7527559 0.2820236 -0.6932706 0.6632034 0.2479131 -0.6449162 0.7229261 0.2987727 -0.6875901 0.6617816 0.5631192 -0.7973005 0.217276 0.5561991 -0.7970201 0.2353753 0.3893497 -0.760927 0.5190349 0.4713669 -0.8281217 0.3033609 0.2402761 -0.7423316 0.6254687 0.3424184 -0.8378916 0.4250734 0.0904836 -0.693246 0.7149984 0.2001549 -0.8198866 0.5363992 -0.05718445 -0.6227399 0.7803365 0.05480569 -0.7772862 0.6267556 -0.205442 -0.5262724 0.8251248 -0.1005581 -0.7098901 0.697097 -0.3138883 -0.4671089 0.8266096 -0.1730752 -0.6448406 0.7444633 -0.4168576 -0.4233136 0.8043851 0 -1 -9.59792e-7 0 -1 2.04657e-6 0 -1 -2.18414e-6 0 -1 -1.09564e-6 0 -1 -8.93761e-7 0 -1 -1.26089e-6 0 -1 -9.69545e-7 0 -1 3.18068e-6 0.1968975 -0.8848397 0.4222443 0.1975515 -0.8476492 0.4924065 0.1987319 -0.9046088 0.3770789 0.2436839 -0.7890154 0.5639796 0.2585803 -0.8322762 0.4903598 0.273508 -0.7612159 0.5879999 0.3147448 -0.6684227 0.6739042 0.3162429 -0.6018732 0.733307 0.4200503 -0.3695062 0.8288686 0.4053407 -0.3959676 0.8239591 0.3421398 -0.5159772 0.7853077 0.3779761 -0.6087656 0.6975232 0.4162951 -0.6308121 0.6548089 0.4160146 -0.5038949 0.756982 -0.1547771 -0.6425161 0.7504779 0.9997776 -0.0184347 0.01024198 0.9605718 -0.2347822 0.1489271 0.9891152 -0.1463539 -0.01522064 0.8830997 -0.4238703 0.201169 0.808053 -0.5445379 0.2247867 0.7093474 -0.6341233 0.3077565 0.6661095 -0.6798215 0.3068241 0.5883107 -0.7400715 0.3258599 0.4670913 -0.8092346 0.3563219 0.4149059 -0.8239271 0.386002 0.2642472 -0.8855513 0.3820635 0.07052803 -0.9070876 0.4149917 0.03278082 -0.9149882 0.4021468 -0.4350017 -0.7182433 0.5430472 -0.5595869 -0.7000638 0.4435914 -0.208197 -0.8954198 0.3935448 -0.2876402 -0.8662885 0.4084209 -0.3861545 -0.8443112 0.3715148 -0.4906893 -0.797551 0.3509078 -0.609759 -0.7445638 0.2716962 -0.2362675 -0.7763742 0.5843122 -0.2889479 -0.7623108 0.5791299 -0.1390153 -0.7293793 0.6698363 -0.1521102 -0.6270058 0.7640198 0.3246853 -0.5239406 0.7874425 0.1206828 -0.582746 0.8036436 0.07124495 -0.6233685 0.7786759 -0.008336067 -0.6170255 0.786899 -0.1057481 -0.6128719 0.7830744 0.8830726 -0.2501504 0.3969983 0.7229043 -0.3503273 0.5955503 0.7078482 -0.3639814 0.6053664 0.4624699 -0.4675987 0.7533082 0.5017443 -0.4504548 0.7384735 -0.1498517 -0.7288808 0.6680399 0.07021993 -0.7353965 0.6739891 0.07048743 -0.7352959 0.6740708 0.4125603 -0.6714792 0.6155565 0.4143266 -0.6704441 0.6154984 0.706323 -0.5214687 0.4787257 0.7083305 -0.5193051 0.4781111 0.8815945 -0.3472488 0.3197022 0.8827546 -0.3452386 0.3186766 0.9795761 -0.1477514 0.1363826 0.9940142 -0.02091109 0.1072311 0.9618406 -0.1630231 0.2197414 0.9672746 -0.1049122 0.2310266 0.5195525 -0.732364 0.440123 0.171513 -0.6319638 0.7557811 -0.972474 -0.1931433 0.1303458 -0.993719 -0.06286859 0.09257531 -0.4576941 -0.4855622 0.7448124 -0.4156621 -0.509181 0.7536311 -0.3486545 -0.5237654 0.7772452 -0.9854065 -0.1024345 0.1359462 -0.8809698 -0.2317705 0.4125225 -0.8972303 -0.2237772 0.3806595 -0.7085701 -0.3813633 0.5937092 -0.6762763 -0.3906009 0.6245649 -0.5066525 -0.4571495 0.7309703 -0.4849891 -0.4370224 0.7574939 -0.07106143 -0.5855999 0.8074795 -0.04159325 -0.6375213 0.7693092 -0.1597636 -0.5795661 0.7991112 0.5203511 -0.7010018 0.4876794 0.4596753 -0.6986199 0.5482963 0.2894243 -0.7548936 0.5885317 0.2859733 -0.7534235 0.5920915 0.2070414 -0.7312029 0.6499817 -0.07042223 -0.8964558 0.4375016 0.1261944 -0.9105149 0.3937484 0.2869347 -0.8594738 0.4230524 0.3922209 -0.8340744 0.387921 0.4514142 -0.8090903 0.3762952 0.5908726 -0.748847 0.3001631 0.7231062 -0.6262224 0.2914841 -0.4140204 -0.8172794 0.4008012 -0.2988846 -0.865458 0.4020578 -0.1603184 -0.8951832 0.4158667 -0.8826149 -0.4212794 0.2086016 -0.8014588 -0.5461421 0.2437061 -0.7084899 -0.6297159 0.3185907 -0.6308935 -0.7061123 0.3215258 -0.4438744 -0.8090311 0.3852846 -0.9673667 -0.2428035 0.07244461 -0.9678254 -0.2436456 0.06285619 -0.9889569 -0.1084826 0.1009739 -0.8825978 -0.344127 0.3203091 -0.8832786 -0.343464 0.3191419 -0.7080683 -0.5172986 0.4806677 -0.7092646 -0.5168798 0.4793527 -0.4143097 -0.6673328 0.6188817 -0.4152292 -0.6673322 0.6182658 -0.07051724 -0.7317336 0.6779332 -0.0706861 -0.7317818 0.6778635 0.1253306 -0.7278331 0.6742042 0.1703354 -0.6808694 0.7123222 -0.3157839 -0.8707323 0.3769696 -0.1931581 -0.8201913 0.5384946 -0.200075 -0.8583781 0.4723948 -0.1747635 -0.9104873 0.3747943 -0.4550735 -0.3595588 0.8146322 -0.4407087 -0.3858338 0.8104988 -0.2846669 -0.8540748 0.4353402 -0.2599188 -0.7731994 0.5784505 -0.3209477 -0.6553931 0.6837049 -0.3308191 -0.6110641 0.719138 -0.3880465 -0.4780367 0.7879726 -0.9659259 0 -0.2588189 -0.7071071 0 -0.7071065 -0.7071074 0 -0.7071061 -0.2588152 0 -0.9659269 0.2588152 0 -0.9659269 0.7071081 0 -0.7071055 0.7071078 0 -0.7071058 0.9659255 0 -0.2588201 0.965927 0 0.2588149 0.9659242 0 0.2588254 0.7071081 0 0.7071055 0.7071183 0 0.7070953 0.2588152 0 0.9659269 -0.2588152 0 0.9659269 -0.7071177 0 0.707096 -0.7071074 0 0.7071061 -0.9659245 0 0.2588244 -0.9659273 0 0.2588136 -0.9659259 0 -0.2588191 0 -1 8.76695e-7 0 -1 -8.76686e-7 0 -1 8.76685e-7 -1.72454e-6 -1 0 0 -1 -4.68536e-6 2.0782e-7 -1 0 2.20784e-7 -1 7.19126e-7 0 -1 2.4361e-7 0 -1 3.05574e-7 0 -1 9.31578e-7 0 -1 2.37328e-7 0 -1 -8.84095e-7 0 -1 2.47364e-7 0 -1 1.23727e-7 0 -1 2.42533e-7 0 -1 1.27001e-6 0 -1 -3.25763e-7 0 -1 2.21313e-7 0 -1 -3.04138e-6 0 -1 9.10413e-7 0 -1 -3.75154e-7 0 -1 -1.10193e-6 0 -1 1.34903e-6 -0.9813141 0 0.1924133 -0.9813154 0 0.1924062 -0.7629346 0 0.6464758 -0.7629266 0 0.6464852 -0.3508589 0 0.9364283 -0.3508756 0 0.9364221 0.1503033 0 0.98864 0.1502847 0 0.9886428 0.613282 0 0.7898641 0.9205788 0 0.3905571 0.9205741 0 0.3905678 0.9941629 0 -0.1078898 0.9941627 0 -0.107891 0.8153551 0 -0.5789612 0.8153659 0 -0.5789459 0.4295434 0 -0.9030462 0.4295552 0 -0.9030407 -0.06528031 0 -0.9978671 -0.06529915 0 -0.9978658 -0.5435742 0 -0.8393613 -0.5704599 -0.7929767 0.2139239 -0.9217382 0 0.3878129 -0.6819888 0 0.7313626 -0.6819867 0 0.7313646 0.6819908 0 0.7313607 0.5704616 -0.7929752 0.2139251 0.921736 0 0.3878179 0.6819865 0 0.7313648 -0.9658411 0 0.2591356 -0.9658411 0 0.2591351 -0.8189725 0 0.5738329 -0.8190259 0 0.5737565 -0.5746807 0 0.8183778 -0.5732666 -3.22167e-4 0.8193688 0.5741791 0 0.8187299 0.5741061 0 0.8187809 0.8207583 0 0.5712757 0.8207954 0 0.5712225 0.9663913 0 0.2570756 0.9663821 0 0.2571105 0.2162912 0 0.9763289 0.2162916 0 0.9763288 -0.2164373 0 0.9762966 -0.2162986 3.98482e-4 0.9763273 0 0 1 1.38402e-5 0 1 6.92007e-6 0 1 -6.92009e-6 0 1 -2.76803e-5 0 1 1.03801e-5 0 1 -1.03801e-5 0 1 0 -0.9987447 -0.05009299 -3.78917e-5 0 1 0.496139 0 0.8682432 0.01699709 0 0.9998556 0.07353311 0 0.9972928 0.03211194 0 0.9994844 -0.02040386 0 0.9997918 -0.00566262 0 0.999984 -0.001345813 0 0.9999991 0.02794277 0 0.9996096 -0.02100497 0 0.9997794 0.00549817 0 0.9999849 -0.01055347 0 0.9999444 0.01705509 0 0.9998546 0.007866024 0 0.9999691 -0.06237828 0 0.9980526 0.005755245 0 0.9999834 0.09950369 0 0.9950373 -0.003968179 0 0.9999922 -0.01769632 0 0.9998434 -0.09594088 0 0.995387 0.02689391 0 0.9996383 -0.02045607 0 0.9997908 0.003152072 0 0.9999951 -0.1102424 0 0.9939048 0.01298063 0 0.9999158 0.050628 0 0.9987176 -0.03949481 0 0.9992198 0.007961869 0 0.9999683 -0.02200287 0 0.999758 0.01548326 0 0.9998802 -0.01944917 0 0.9998109 0.018314 0 0.9998323 -0.01602995 0 0.9998716 9.68805e-5 0 1 -4.4405e-4 0 1 -0.03612095 0 0.9993475 0.0382952 0 0.9992665 -0.015585 0 0.9998786 -0.02221673 0 0.9997532 -0.05121475 0 0.9986878 -0.01999598 0 0.9998001 0.01895391 0 0.9998204 -0.05349469 0 0.9985682 0.006308972 0 0.9999801 0.03224128 0 0.9994802 -0.03172999 0 0.9994965 0.8720866 0.4892314 -0.01084834 0.87476 0.483857 -0.02602714 0.8763557 0.4801067 -0.03870826 0.8776787 0.4760879 -0.05495941 0.8788225 0.4718045 -0.07121574 0.8777366 0.4507974 -0.162358 0.84761 0.415959 -0.3294472 0.06080937 0.02929073 -0.9977197 0.05971574 0.02902132 -0.9977936 0.07612532 0.03261935 -0.9965646 0.07849496 0.03297907 -0.9963689 0.0800119 0.03330117 -0.9962375 0.06182837 0.02954834 -0.9976494 0.06530559 0.03028738 -0.9974056 0.06892937 0.0310353 -0.9971387 0.0704168 0.03136676 -0.9970244 0.07278323 0.03179168 -0.996841 0.07462632 0.03229004 -0.9966887 0.1232443 0.04184037 -0.991494 0.1917861 0.0505799 -0.9801325 0.20435 0.05206465 -0.9775124 0.2260297 0.05465006 -0.9725862 0.2503479 0.05723655 -0.9664626 0.2679814 0.05911231 -0.9616089 0.2885738 0.06107193 -0.955508 0.3100339 0.06288766 -0.9486433 0.4562592 0.07532936 -0.8866528 0.6346179 0.08072161 -0.7685989 0.6839332 0.0819301 -0.7249296 0.7349629 0.08129942 -0.6732161 0.783878 0.08033412 -0.6156963 0.8983898 0.07371991 -0.432968 0.9607996 0.0589683 -0.2709004 0.9768497 0.05187439 -0.207542 0.9920205 0.04062551 -0.1193525 0.9977157 0.02875816 -0.06112623 0.9993308 0.0203278 -0.0304104 0.999863 0.01234847 -0.01103001 0.9999912 0.004116177 -7.60435e-4 0.0337429 0.05143958 -0.998106 0.0331282 0.05062258 -0.9981684 0.5123922 0.8585888 -0.01672571 0.5205845 0.8526736 -0.04403972 0.5272249 0.8440353 -0.09817588 0.5293577 0.83938 -0.1233762 0.5313928 0.8314148 -0.1623918 0.5314471 0.8210765 -0.2083202 0.06018728 0.07485324 -0.9953765 0.06179571 0.07611984 -0.995182 0.0636686 0.07759279 -0.9949502 0.03429549 0.05215775 -0.9980499 0.04282122 0.05972784 -0.9972959 0.05277878 0.0683946 -0.9962613 0.05386316 0.06960242 -0.9961196 0.05620741 0.07146292 -0.9958584 0.05855703 0.07342034 -0.9955806 0.02380275 0 -0.9997168 0.07193905 0.08481389 -0.9937965 0.08166438 0.092727 -0.992337 0.08399742 0.09476631 -0.9919495 0.08662265 0.09687042 -0.9915205 0.08908635 0.0989151 -0.9911002 0.09648358 0.1045783 -0.9898255 0.1168181 0.1207239 -0.9857887 0.7933792 0.6087278 -4.35205e-4 0.867953 0.4966461 -5.26896e-4 0.02499216 0 -0.9996877 0.2588118 0.9659278 -2.15912e-4 0.5035161 0.863986 -1.99136e-4 0.5088121 0.8608317 -0.008895039 0.3727446 0.1001709 -0.9225115 0.9637399 0.2582524 -0.06716465 0.9636731 0.2584715 -0.06728106 0.9545592 0.2587131 -0.1479339 0.954546 0.2587493 -0.147955 0.9468945 0.2587584 -0.1908795 0.9468777 0.2588117 -0.1908908 0.7777283 0.6087327 -0.1567906 0.3133614 0.314423 -0.8960709 0.706219 0.7062745 -0.04930633 0.7058754 0.7066018 -0.04953634 0.6989262 0.7069414 -0.1083336 0.6988567 0.7070039 -0.1083736 0.697571 0.707074 -0.1159362 0.5967702 0.7933379 -0.1203343 0.258827 0.9659236 -5.94663e-4 0.2587561 0.9657721 -0.01815855 0.2585133 0.9658347 -0.01828408 0.2558712 0.9658963 -0.03967893 0.2558267 0.9659072 -0.03969854 0.2537649 0.9659116 -0.05116993 0.253722 0.9659224 -0.05117642 0.978654 0 0.2055151 0.9842228 0.001052737 0.1769303 0.984866 0.002152562 0.1733042 0.9998832 0 0.01528292 0.9972455 0.006100714 0.07392066 0.9969906 0.004541337 0.07739025 0.9903126 -6.93728e-4 0.1388545 0.9647026 0 0.263342 0.9748639 4.07784e-4 0.2228013 0.9752202 2.5038e-5 0.2212365 0.9797927 2.26928e-5 0.2000158 0.9706301 0 0.2405768 0.9647676 -0.01047861 0.2628949 0.9705496 0.02302706 0.2397987 0.9645196 -6.81017e-4 0.2640107 0.9955312 8.3596e-4 -0.09442967 0.9952149 -8.37488e-4 0.09770691 0.9996788 4.25507e-4 0.02534288 0.9982508 -0.004942476 0.05891633 0.9970125 -0.001411378 0.07722783 0.9866551 0.002860307 0.1627991 0.977798 0.0246399 0.2080965 0.9871031 0 0.1600856 0.9881413 -0.003222763 0.1535135 -0.4002332 -0.9156453 0.03751057 -0.1210476 -0.9904545 -0.06593424 0.1060339 -0.9436477 -0.3135058 0.09805369 -0.9458346 -0.3094873 -0.1379315 -0.9835694 -0.1164748 -0.1288996 -0.9835132 -0.1268329 -0.04982662 -0.9773482 -0.2056885 -0.03732204 -0.9824718 -0.1826367 0.02338796 -0.9666484 -0.2550371 -0.3807327 -0.924659 0.006959795 -0.3634963 -0.9311816 0.0277751 -0.2376668 -0.9660141 -0.1016429 -0.242697 -0.9674015 -0.0723381 -0.1509498 -0.9743941 -0.1666448 -0.08217364 -0.9681344 -0.2365659 -0.07747161 -0.9680249 -0.2385918 0.0246852 -0.9394167 -0.3418877 0.04287588 -0.9281347 -0.3697671 0.0812993 -0.9134666 -0.3987095 0.66152 0 0.7499275 0.983101 0 0.1830644 0.9590913 0.03180646 0.2813047 -0.9847232 0 0.1741273 -0.9660435 0.02944767 0.2566961 -0.9069818 0 0.4211699 -0.8197864 0 0.5726694 -0.8233252 -0.001119911 0.5675688 -0.6409165 0.002237498 0.7676075 -0.6456664 0 0.7636197 -0.6499565 -5.0706e-4 0.7599712 -0.3387975 5.06576e-4 0.9408593 -0.2688718 0.007095396 0.9631499 -0.09143078 0 0.9958115 0.08337169 0 0.9965186 0.2447034 0.00780946 0.9695665 0.3470562 -9.17236e-4 0.9378439 0.6677379 0.001191198 0.7443957 0.6475952 0.01203852 0.7618894 0.8319196 -0.004345953 0.5548794 0.8151279 0 0.5792812 0.9035363 0 0.4285116 0 1 2.34225e-6 0 1 5.44955e-6 0 1 0 0 1 2.82298e-7 0 1 1.46921e-7 0 1 0 0 1 -1.60667e-6 0 1 -7.25844e-7 -1.49023e-7 1 0 0 1 2.98599e-7 0 1 0 -1.45109e-6 1 8.76821e-6 -4.9648e-6 1 6.83009e-6 -3.68398e-5 1 -4.11887e-5 3.02401e-5 1 1.83834e-5 0 1 6.84788e-6 0 1 -4.26915e-6 0 1 -6.86727e-6 0 1 -5.58848e-7 0 1 1.92767e-6 0 1 -5.28181e-7 0 1 5.86803e-7 0 1 6.71158e-7 0 1 -4.96976e-7 0 1 -3.13936e-7 0 1 5.24565e-6 0 1 0 0 1 0 0 1 -2.03067e-7 0 1 3.92094e-7 0 1 6.33525e-7 0 1 -4.80794e-7 0 1 -2.37906e-7 0 1 1.86882e-7 0 1 0 0 1 0 0 1 -1.4638e-7 0 1 1.46684e-7 0 1 -1.44101e-6 0 1 2.93368e-7 0.9999999 2.49294e-4 -5.52581e-4 1 1.99935e-5 -1.81056e-6 1 1.96425e-5 -1.62027e-5 1 0 -1.46883e-5 0.9998087 -0.003353416 0.01927208 1 4.35622e-5 -1.62028e-5 1 3.27056e-4 0 1 2.88309e-4 -5.56835e-6 1 6.22353e-6 -2.4573e-6 1 1.60882e-5 -2.95293e-6 1 7.68031e-6 -3.28014e-6 1 6.90749e-6 -3.70963e-6 1 4.67187e-6 -4.13891e-6 1 5.31808e-6 -4.71406e-6 1 1.77893e-5 -1.52601e-6 1 8.58348e-6 -1.07671e-6 1 5.68195e-5 -1.38421e-6 0.1775355 -0.8702827 -0.4594445 0.1611201 -0.924392 -0.3457453 0.1902422 -0.8973158 -0.398287 0.08063715 -0.9158939 -0.3932381 0.1122118 -0.8959339 -0.4297804 0.4194059 -0.8044343 -0.4206951 0.4106067 -0.803979 -0.4301395 0.4060474 -0.8033498 -0.4356086 0.380558 -0.8069947 -0.451592 0.34327 -0.8053108 -0.4833635 0.3600878 -0.8091335 -0.4643703 0.29694 -0.8210468 -0.487554 0.304814 -0.8205812 -0.4834614 0.2534409 -0.8366708 -0.4855408 0.2627582 -0.8346339 -0.4840915 0.2138363 -0.8540521 -0.4742038 0.2445813 -0.8439809 -0.4773638 0.1793034 -0.8693572 -0.460509 0.2049524 -0.8913289 -0.4043853 0.2293779 -0.8837893 -0.4078019 0.1428288 -0.8853748 -0.442393 0.142826 -0.8853771 -0.4423894 0.1936985 -0.9058731 -0.3766627 0.2042537 -0.9020844 -0.3801636 0.2160239 -0.9179792 -0.3326378 0.2588189 0 -0.9659259 0.2588238 0 -0.9659246 0.7071062 0 -0.7071075 0.7071088 0 -0.7071049 0.9659251 0 -0.2588222 0.9659254 0 -0.2588208 -0.9807861 0 -0.1950867 -0.9807859 0 -0.1950873 -0.8314717 0 -0.5555672 -0.8314706 0 -0.5555688 -0.5555708 0 -0.8314694 -0.1950878 0 -0.9807859 -0.1950945 0 -0.9807845 0.9860947 0 0.1661842 0.7278122 0 0.6857766 -0.9816322 0 0.190783 -0.7382221 0 0.6745578 -0.983275 0.002936899 0.1821035 -0.8696638 -0.00292319 0.4936358 -0.8796943 -0.009799301 0.4754387 -0.7178882 0.00640732 0.696129 -0.7382167 0 0.6745637 -0.5857449 0 0.8104955 -0.4593353 0.007118105 0.8882344 -0.3470552 -0.001959025 0.9378427 -0.004403293 0.002649426 0.9999869 0.01249337 0.004339993 0.9999126 0.9847228 0 0.1741293 0.986055 -0.002801418 0.1663966 0.8652897 0.002932786 0.5012636 0.8723574 -0.002260088 0.4888637 0.7235432 8.41653e-4 0.6902787 0.5922914 0 0.8057239 0.4813827 0.007415592 0.8764792 0.3792738 0 0.9252846 0.2124547 0 0.977171 -0.8252858 0.28087 0.4899138 -0.6501419 0.6984899 0.299044 -0.7998018 0.5999158 0.02044939 -0.6439794 0.09615528 -0.7589762 -0.7537703 0.1220074 -0.6457126 -0.7455074 0.1492241 -0.6495775 -0.7086544 0.328013 -0.6246731 -0.7096156 0.2986268 -0.6381754 -0.7161318 0.6583959 -0.2316681 -0.7306675 0.5792888 -0.3613163 -0.7263449 0.5859875 -0.3592239 -0.7298223 0.5190848 -0.4448713 -0.7504439 0.4488841 -0.4851154 -0.7224286 0.6887705 -0.06076294 -0.7095999 0.6904466 -0.1405404 -0.7175303 0.6566583 -0.2322717 -0.7208771 0.6506478 0.2387333 -0.6980665 0.6848688 0.2089449 -0.7095785 0.6920158 0.1327123 -0.9931041 0.05594789 -0.1030244 -0.9948853 0.05918532 -0.08185607 -0.9957764 0.06392425 -0.06590181 -0.9978574 0.06542444 5.42719e-4 -0.9965518 0.07496064 -0.0355758 -0.9964204 0.07911801 -0.02977782 -0.9961583 0.06784486 -0.05536997 -0.9732495 0.05315595 -0.223517 -0.975389 0.05657553 -0.2131092 -0.9773425 0.06088268 -0.2027193 -0.9807162 0.07104611 -0.1820665 -0.9783561 0.07696235 -0.192084 -0.9807428 0.07161229 -0.1817012 -0.9839705 0.06479972 -0.1661415 -0.9876589 0.05874902 -0.1451843 -0.9906941 0.05580359 -0.1241418 -0.9771354 0.1220074 0.1741284 -0.9978224 0.06260645 0.02076244 -0.997214 0.06236457 0.04092526 -0.9960388 0.06466519 0.06103402 -0.9942854 0.06948477 0.08104693 -0.9919206 0.07681751 0.1009585 -0.9872184 0.0914461 0.1305279 -0.9762018 0.1149044 0.1839212 -0.9744269 0.1049786 0.1986749 -0.9713951 0.09396976 0.2180857 -0.9656807 0.08060455 0.2469086 -0.9581747 0.0734263 0.2766044 -0.9535487 0.07160276 0.2926054 -0.752183 0.6587908 0.01467943 -0.8189852 0.5704602 0.06195515 -0.7467436 0.6132498 0.2574853 -0.7467473 0.6132451 0.2574858 -0.7144706 0.6214978 0.3213602 -0.7098091 0.6214454 0.3316274 -0.6451829 0.6524636 0.3975303 -0.6784454 0.59412 0.4321265 -0.844488 0.08107477 0.5294023 -0.8337651 0.07658445 0.5467821 -0.8248646 0.07481926 0.5603575 -0.8547301 0.0878604 0.511583 -0.8550881 0.08819395 0.5109269 -0.8656684 0.08120411 0.493988 -0.950287 0.07106751 0.303157 -0.9451281 0.07130938 0.3188228 -0.9395755 0.07358783 0.3343391 -0.9357017 0.07577949 0.3445575 -0.9296364 0.08000504 0.3596882 -0.921074 0.0881958 0.3792681 -0.9209651 0.088032 0.3795705 -0.915116 0.08249831 0.3946602 -0.9110496 0.0794692 0.4045657 -0.9046639 0.075841 0.4193226 -0.8910641 0.07236099 0.4480723 -0.8761522 0.07625055 0.4759658 -0.6619746 0.0143128 -0.7493897 -0.6971113 -0.005793154 -0.7169396 -0.759249 0.1036809 -0.6424884 -0.7565347 0.1066121 -0.6452048 -0.7666816 0.09701102 -0.6346561 -0.773432 0.09101295 -0.6273114 -0.7799817 0.08557933 -0.6199232 -0.7864335 0.08065944 -0.6123859 -0.7927783 0.07616549 -0.6047325 -0.7990115 0.07222467 -0.5969627 -0.8051958 0.0688095 -0.5890035 -0.8112149 0.06588059 -0.5810253 -0.8171664 0.06348991 -0.5728946 -0.8229805 0.06164985 -0.5647145 -0.8287573 0.06033498 -0.5563462 -0.834379 0.05956387 -0.5479636 -0.8399354 0.05932879 -0.5394339 -0.8453935 0.05965304 -0.5308026 -0.8507138 0.06051963 -0.5221337 -0.8559384 0.06194174 -0.5133544 -0.8610761 0.06393724 -0.5044402 -0.8660389 0.06649267 -0.4955355 -0.8709497 0.06958407 -0.4864204 -0.8756805 0.07328677 -0.4772974 -0.8825671 0.0796265 -0.4633951 -0.9107529 0.1172905 -0.3959447 -0.8842532 0.1533613 -0.4411087 -0.8923069 0.1440182 -0.4278404 -0.8974786 0.1380816 -0.4188863 -0.9024894 0.1325705 -0.4098027 -0.9073759 0.1273394 -0.400567 -0.9120656 0.1226107 -0.3912838 -0.9166207 0.1181449 -0.381901 -0.9231687 0.1121972 -0.3676567 -0.9313419 0.105785 -0.3484419 -0.9389463 0.101009 -0.328903 -0.9459707 0.09785223 -0.309135 -0.9617131 0.04807209 -0.2698095 -0.9672233 0.04802453 -0.2493451 -0.9709414 0.05060058 -0.2339072 -0.781742 0.619515 0.07127958 -0.7502053 0.6610368 -0.01492023 -0.7870132 0.5895676 -0.1817149 -0.7870156 0.589564 -0.1817166 -0.7970547 0.5182846 -0.3099756 -0.7970568 0.5182827 -0.3099736 -0.7801225 0.3920575 -0.4875448 -0.7779211 0.3943307 -0.4892261 -0.7211496 0.3854326 -0.5756605 -0.7866364 0.4079325 0.4634591 -0.7519052 0.3685203 0.5466548 -0.8679654 0.3597564 0.3423618 -0.8679655 0.3597556 0.3423622 -0.9317463 0.3346556 0.140906 -0.8826957 0.4577005 0.1065772 -0.9101301 0.4031769 -0.09545475 -0.9101287 0.40318 -0.0954566 -0.9052903 0.3544424 -0.2341372 -0.9052935 0.3544365 -0.2341336 -0.86201 0.2681238 -0.4301727 -0.9524368 0.09634846 -0.2891043 -0.8491308 0.09114503 -0.5202592 -0.9692339 0.15729 -0.1893296 -0.9692332 0.157294 -0.1893297 -0.9828581 0.1789146 -0.04449445 -0.9828575 0.1789172 -0.04449373 -0.965253 0.2031111 0.1644163 -0.9774928 0.1224702 0.1717823 -0.9781616 0.1335395 0.159271 -0.7316257 0.2252248 -0.6434265 -0.73579 0.2209752 -0.640143 -0.8006224 0.355871 -0.4820371 -0.8246839 0.3341705 -0.4563187 -0.8559482 0.4417637 -0.268696 -0.8559471 0.441767 -0.268694 -0.854007 0.5025039 -0.1347666 -0.8540018 0.5025129 -0.1347656 -0.8189825 0.5704643 0.06195467 -0.8826974 0.4576973 0.1065775 -0.815238 0.4920225 0.3054519 -0.8152392 0.4920211 0.305451 -0.7420286 0.503086 0.4430553 -0.7581843 0.5137012 0.4015815 -0.6724563 0.05010104 -0.7384392 -0.6547372 0.0505194 -0.7541666 -0.7544363 0.1207297 -0.6451746 -0.7544374 0.1207327 -0.6451727 -0.8728826 0.2276285 -0.43158 -0.8907375 0.196033 -0.4100707 -0.9432716 0.2591484 -0.2075595 -0.9432713 0.25915 -0.2075586 -0.9533334 0.2947911 -0.06522035 -0.9533321 0.2947948 -0.06522172 -0.9317477 0.3346514 0.1409066 -0.9652535 0.2031076 0.1644173 -0.9039853 0.218339 0.3676123 -0.9039853 0.2183354 0.3676143 -0.8461772 0.2228043 0.4840891 -0.8405498 0.2067174 0.5007433 -0.8853127 0.2145953 -0.4125169 -0.8228296 0.5664829 -0.04526203 -0.9898003 0.01375436 -0.1417964 -0.9993757 0.001748323 -0.03528779 -0.9968264 -0.003523945 -0.07952982 -0.9950752 0.02718222 -0.09532284 -0.996825 0.01494514 -0.07820969 -0.95034 0.24247 -0.1950956 -0.9326441 0.2804381 -0.2270013 -0.932909 0.2962042 -0.2048026 -0.9502755 0.2421429 -0.1958147 -0.9499053 0.2423429 -0.1973574 -0.9554383 0.230154 -0.1848431 -0.8666235 0.4652171 -0.1803796 -0.8247256 0.5375111 -0.1758112 -0.8929876 0.4281221 -0.1388699 -0.8736696 0.4579332 -0.1643131 -0.6780628 0.7215224 0.14013 -0.6934801 0.7049691 0.148674 -0.723456 0.685409 0.08261913 -0.7235605 0.6861275 0.07542747 -0.726507 0.6865869 0.02803611 -0.7399462 0.6702153 0.05736875 -0.7028359 0.7086783 -0.06161993 -0.7533764 0.6572662 -0.02062064 -0.7497282 0.567843 0.3397971 -0.6558958 0.6814 0.3247997 -0.6874862 0.6683043 0.284134 -0.6876491 0.6843052 0.2426212 -0.7173536 0.6667067 0.2022526 -0.7144749 0.6708562 0.19869 -0.7127984 0.6733494 0.1962628 -0.7064768 0.480622 -0.5195123 -0.7567113 0.2935332 -0.5841458 -0.7606588 0.3043634 -0.5733771 -0.7676604 0.3577122 -0.5317326 -0.7423462 0.1012594 -0.6623206 -0.7418692 0.1494997 -0.6536666 -0.7291682 0.1815317 -0.6598183 -0.7592139 0.2182427 -0.6131595 -0.7597503 0.2788722 -0.5873754 -0.7225944 0.05537468 -0.6890509 -0.705844 0.03702431 -0.7073991 -0.7155516 0.0173282 -0.6983449 -0.9673689 0.1430681 -0.2091149 -0.9970099 0.02666962 -0.07252573 -0.996612 0.03103315 -0.0761674 -0.9653048 0.08377897 -0.2473211 -0.9625993 0.09700292 -0.2529688 -0.9625712 0.0526759 -0.2658609 -0.957974 0.07237607 -0.2775744 -0.9576817 0.0134989 -0.287513 -0.9421903 0.03547066 -0.3331956 -0.8643918 0.4645015 -0.1925237 -0.8648937 0.4543274 -0.2134145 -0.8859527 0.3983296 -0.2375319 -0.8860177 0.3843241 -0.25936 -0.8855347 0.3605204 -0.2930077 -0.8862911 0.3605527 -0.2906715 -0.8863521 0.3142458 -0.3400434 -0.962195 0.1849228 -0.199961 -0.9665949 0.1923841 -0.1693595 -0.9981219 -0.02100372 -0.05754566 -0.9975499 0.04043531 -0.05709046 -0.966722 0.1465728 -0.2096785 -0.8851646 0.2633722 -0.3835608 -0.8974866 0.2765606 -0.343558 -0.76196 0.4042662 -0.5059505 -0.764324 0.5018572 -0.4049053 -0.7537009 0.4988073 -0.4279325 -0.7752278 0.5444919 -0.3202352 -0.7628549 0.5481171 -0.3429579 -0.7553434 0.6236624 -0.2012501 -0.7338603 0.6401901 -0.2271691 -0.756445 0.6404997 -0.1324809 -0.9970812 0.03830808 -0.06604266 -0.9972816 0.03513032 -0.06477123 -0.9667309 0.1137153 -0.2291296 -0.9653457 0.1213454 -0.2310477 -0.8828164 0.210383 -0.4199692 -0.8825541 0.1539121 -0.4443075 -0.8871474 0.1395601 -0.4398778 -0.8702014 0.09972286 -0.4824987 -0.8696659 0.04407024 -0.4916696 -0.8445733 0.02003955 -0.5350649 -0.7794432 0.6216872 -0.07728779 -0.6785033 0.6189681 0.3956157 -0.6011181 0.7599678 0.2471964 -0.5353293 0.8138265 0.2260728 -0.5298732 0.84182 0.1028276 -0.5936321 0.7193695 0.3607059 -0.597903 0.7164011 0.3595576 -0.6254227 0.7291291 0.2778798 -0.7110387 0.6984298 0.08136212 -0.7226657 0.6782736 0.1330379 -0.6152348 0.7494314 0.2446195 -0.6170228 0.7465633 0.2488496 -0.6180422 0.7445998 0.2521806 -0.2097314 0.9777168 -0.009090125 -0.3131825 0.9457014 0.08698099 -0.3129117 0.9457428 0.08750361 -0.4303225 0.8919313 0.1388565 -0.3754196 0.8767864 0.3005091 -0.6915269 0.7204396 0.0525099 -0.7076284 0.7028567 0.07248806 -0.6840156 0.7210463 -0.1105214 -0.859051 0.4648995 -0.2142423 -0.8538792 0.4657258 -0.2323571 -0.8541837 0.4655398 -0.2316097 -0.8542358 0.4656545 -0.2311864 -0.8505969 0.4892206 -0.1927385 -0.8421958 0.508503 -0.1792513 -0.8012849 0.5827131 -0.1356024 -0.7861452 0.5987701 -0.1531347 -0.7984969 0.5909088 -0.1150203 -0.8581336 0.4599323 -0.2281868 -0.8645441 0.4603401 -0.2016197 -0.7326933 0.663191 -0.152769 -0.6756652 0.7350992 0.05572974 -0.1688356 0.4680939 -0.8673999 -0.409027 0.4491146 0.7943507 -0.3784565 0.9207239 -0.09507024 -0.1534121 0.9881033 -0.01080363 -0.8595789 0.5071548 -0.06259608 -0.6966373 0.7162276 0.04140657 -0.6863456 0.7271949 0.01083028 -0.6191667 0.7852243 0.007450759 -0.5985919 0.7989125 -0.05853801 -0.5645825 0.8236211 -0.05380612 -0.4475414 0.8904736 -0.08224147 -0.1659411 0.985218 0.04253262 -0.1449774 0.9878941 -0.05519795 0.258818 0 -0.9659262 0.2588229 0 -0.9659248 0.7071043 0 -0.7071093 0.707107 0 -0.7071066 0.9659259 0 -0.2588188 0.9659262 0 -0.2588175 -0.9659262 0 -0.2588175 -0.9659259 0 -0.2588188 -0.7071088 0 -0.7071049 -0.7071062 0 -0.7071075 -0.2588238 0 -0.9659246 -0.2588189 0 -0.9659259 0.3388367 0.9279187 0.1554241 0.5102915 0.8599926 0.003934264 0.9178755 0.39664 -0.01346921 0.9894358 0.1399273 -0.03791058 0.9836545 0.1797128 -0.0112769 0.7568873 0.6533278 -0.01687049 0.5060249 0.862215 -0.02289295 0.1743243 0.9843415 -0.02613449 0.1757231 0.9816299 0.0743255 0.1103038 0.983765 0.1415609 0.2101857 0.936937 -0.2792328 0.175776 0.9696412 -0.1699966 0.1743246 0.9843413 -0.02613592 0.2591973 0.8219993 -0.5070837 0.1753916 0.8686378 -0.4633643 0.1746485 0.9391542 -0.2957826 0.1756313 0.3061724 -0.9356347 0.174324 0.4650242 -0.8679654 0.1743233 0.4650227 -0.8679662 0.1757881 0.58214 -0.7938588 0.1971899 0.671795 -0.7140083 0.1745256 0.6813973 -0.7108013 0.1754617 0.8003417 -0.5732944 0.2857618 0.1759934 -0.9420014 0.1743243 0.2232827 -0.9590391 0.1749883 -2.22492e-4 -0.9845705 0.2401203 -0.03334438 -0.9701704 0.175697 -0.1293521 -0.9759091 0.1743243 -0.2886022 -0.9414457 0.1743229 -0.2886039 -0.9414454 0.1757628 -0.4266478 -0.8871749 0.2174037 -0.5189422 -0.8267011 0.1747223 -0.5394352 -0.8237002 0.1753472 -0.6816174 -0.710388 0.2584811 -0.708706 -0.6564476 0.1755 -0.7688893 -0.6148244 0.2840099 -0.9575482 -0.04939681 0.1744447 -0.8689957 -0.4630501 0.1883829 -0.8692772 -0.4570221 0.1757946 -0.9220052 -0.3449677 0.1743249 -0.9607536 -0.2157853 0.174323 -0.9607542 -0.2157844 0.175776 -0.97902 -0.103066 0.1112295 -0.992478 -0.05114281 0.9859274 -0.1669326 -0.008990883 0.9841605 -0.05195999 -0.1694945 0.9841606 -0.09425103 -0.150149 0.9841603 -0.09425395 -0.1501489 0.9841607 -0.1300576 -0.120469 0.9841604 -0.13006 -0.1204692 0.9841608 -0.1569132 -0.08249807 0.9841603 -0.1569163 -0.08249789 0.9841604 -0.1729717 -0.03884917 0.9841605 -0.1729714 -0.03884917 0.9844007 -0.1744445 -0.02290344 0.8755102 -0.4830363 -0.01256728 0.9844225 0.1740575 -0.02482932 0.9841607 0.1698942 -0.05063343 0.9841605 0.1698951 -0.05063354 0.9841606 0.1508796 -0.093077 0.9841603 0.1508823 -0.09307694 0.9841604 0.1214818 -0.1291145 0.9841603 0.1214826 -0.1291146 0.9841604 0.08372199 -0.1562659 0.9841605 0.08372092 -0.156266 0.9841604 0.0401988 -0.1726624 0.9841604 0.04019886 -0.1726624 0.9843907 0.008549869 -0.1757892 0.982034 -0.006481826 -0.1885929 0.9843215 -0.01461511 -0.1757774 0.9841605 -0.05195832 -0.1694952 0.5366995 0.8429096 -0.03817373 0.5358204 0.8091619 -0.2411505 0.5358229 0.8091598 -0.2411524 0.5358213 0.7185989 -0.4432959 0.5358228 0.7185966 -0.4432978 0.5358211 0.5785797 -0.614932 0.5358227 0.5785782 -0.6149321 0.5358218 0.3987393 -0.7442459 0.5358213 0.3987385 -0.7442468 0.5358228 0.1914573 -0.822337 0.5358213 0.1914562 -0.8223383 0.5358204 -0.02900302 -0.8438337 0.5358234 -0.02900224 -0.8438318 0.535822 -0.2474656 -0.8072519 0.5358234 -0.247465 -0.807251 0.5358222 -0.448897 -0.7151128 0.5358217 -0.4488973 -0.7151129 0.5358204 -0.619436 -0.5737558 0.5358227 -0.6194327 -0.5737572 0.5358211 -0.7473392 -0.392912 0.5358223 -0.7473375 -0.3929139 0.5358207 -0.8238094 -0.1850253 0.5358233 -0.8238074 -0.1850272 0.8420677 0.5352814 -0.06630194 0.8400818 0.5198639 -0.1549334 0.8400819 0.5198636 -0.1549336 0.8400821 0.4616795 -0.2848058 0.8400821 0.4616789 -0.2848066 0.840082 0.3717206 -0.3950773 0.8400821 0.3717208 -0.3950771 0.8400815 0.2561794 -0.4781583 0.8400822 0.2561784 -0.4781574 0.8400819 0.1230057 -0.5283294 0.8400819 0.1230064 -0.5283293 0.8400824 -0.01863342 -0.5421389 0.8400819 -0.01863288 -0.5421395 0.8400809 -0.1589905 -0.5186389 0.8400818 -0.1589902 -0.5186374 0.8400817 -0.2884047 -0.4594406 0.8400818 -0.2884035 -0.459441 0.840082 -0.3979689 -0.3686231 0.8400822 -0.3979687 -0.3686231 0.840082 -0.4801442 -0.2524356 0.8400811 -0.4801461 -0.2524352 0.8400816 -0.5292747 -0.1188747 0.8400818 -0.5292746 -0.1188741 0.8410408 -0.5315226 -0.1006686 0.5327955 -0.8426373 0.07804787 0.647681 -0.7245646 -0.2356173 0.4408096 -0.8964087 -0.04624295 1.5545e-6 0.2589223 -0.9658982 -0.037817 0.1563229 -0.9869819 -0.01509428 0.1253144 -0.9920023 0 0.02068012 -0.9997861 3.37384e-6 0.5532345 -0.8330256 -0.03212922 0.4537557 -0.8905467 -0.02456849 0.4449999 -0.8951935 -8.70418e-7 0.3384515 -0.9409838 6.23156e-6 0.7848929 -0.6196315 -0.02881681 0.7068133 -0.706813 -0.02556079 0.7036705 -0.7100666 -2.3271e-6 0.6144028 -0.7889926 0 0.9998396 -0.01791459 -0.008763194 0.9928724 -0.1188604 -0.02878987 0.9872791 -0.1563689 0.008259475 0.9584928 -0.284997 -0.01991617 0.8908298 -0.4539006 -0.03470396 0.8997818 -0.434958 -6.77757e-6 0.8344846 -0.5510313 -0.8588765 0.4599323 -0.225374 -0.9795595 0.1749552 -0.09926694 -0.6797285 0.7281715 -0.08795171 -0.8874378 0.4597237 -0.03329354 -0.8129072 0.5739939 -0.09855473 -0.9327141 0.3564178 -0.05487221 -0.5476932 0.8337961 -0.06939983 -0.7759395 0.6302996 -0.02530664 -0.1151562 0.9933252 -0.006647169 -0.5192062 0.8530003 -0.05306243 -0.3382834 0.9408477 -0.01923435 -0.3570775 0.9339215 -0.01692432 -0.1756796 0.9839256 -0.03205102 -0.9479805 0.3151326 -0.04499393 -0.9416778 0.316346 -0.1147531 -0.8040307 0.5735934 -0.1566055 -0.7361767 0.6629903 -0.1359695 -0.6727324 0.7277126 -0.1336622 -0.5913347 0.8007639 -0.09539693 -0.5121096 0.8528552 -0.1018923 -0.3845078 0.9206811 -0.06708341 -0.3312961 0.9410428 -0.06842225 -0.1519744 0.9882264 -0.01767623 -0.1242642 0.9920122 -0.02168428 -0.984427 0.1757937 -8.96098e-6 -0.9844219 0.1758232 0 -0.9340409 0.3571662 0 -0.9053872 0.4245843 -0.001541435 -0.1757703 0.9844312 8.62417e-6 -0.1757969 0.9844265 0 -0.3571285 0.9340553 0 -0.4245929 0.9053831 -0.001540899 -0.548936 0.8356896 0.01709824 -0.6087664 0.7933496 2.17786e-6 -0.7933498 0.6087662 0 -0.776169 0.6304918 -0.006468117 -0.887915 0.4599932 0.003629386 -1 -1.42295e-6 0 -1 6.90578e-7 0 -1 4.02302e-7 0 -1 1.74422e-7 0 -1 -1.73079e-7 0 -1 -3.87321e-7 0 -1 -6.69362e-7 0 4.59097e-5 -0.998675 -0.051463 -0.0423851 -0.98136 -0.1874465 -0.006240367 -0.9756744 -0.2191358 0 -0.9365872 -0.3504348 0 -0.8825277 -0.4702605 -0.06075543 -0.8517236 -0.5204571 0 -0.7810106 -0.6245177 0 -0.1313953 -0.9913302 -0.04623562 -0.2927779 -0.9550621 -0.02609461 -0.2787334 -0.9600139 0 -0.4333935 -0.9012048 0 -0.6071177 -0.7946119 -0.109071 -0.5445923 -0.8315786 0 -0.692345 -0.7215667 0 -2.25955e-4 -1 -0.06974065 0.08695667 -0.993768 0 0.1836516 -0.9829914 -0.01340603 0.4413375 -0.8972411 -0.06313306 0.4713128 -0.8797037 0 0.3110061 -0.9504081 -0.06271058 0.7344464 -0.6757632 0 0.6920174 -0.7218808 0 0.5913441 -0.8064194 -0.06538498 0.928898 -0.364518 0 0.8823146 -0.47066 0 0.8129536 -0.5823286 0 0.9898051 0.1424291 -0.05249762 0.9982693 -0.02650457 -0.02144628 0.9997616 -0.004098892 0 0.984975 -0.1726971 0 0.9538136 -0.3003994 0.2435727 -0.8934546 -0.3773744 0.2184291 -0.9028088 -0.3704389 0.1961457 -0.9130676 -0.3575392 0.296548 -0.8795456 -0.3721005 0.3429353 -0.8745242 -0.3429328 0.3575379 -0.9130679 -0.1961476 0.3704387 -0.9028099 -0.2184254 0.3773709 -0.8934549 -0.2435769 0.2654375 -0.951155 -0.1576297 0.2919954 -0.9432458 -0.1581969 0.3171411 -0.933892 -0.1651286 0.1651288 -0.9338925 -0.3171393 0.158196 -0.9432458 -0.2919957 0.1780303 -0.9236327 -0.3394231 -0.05592322 -0.9743247 -0.2180917 0.41554 -0.809109 -0.4155347 0.6344791 -0.7618686 0.1303561 0.4064596 -0.629853 0.661873 -0.3711382 -0.9256905 0.07316797 -0.3799323 -0.9232509 0.05709058 -0.3187609 -0.9318283 0.1734574 -0.3300762 -0.9339427 0.1371158 -0.3333547 -0.935932 0.1136045 -0.3331829 -0.9366389 0.1081519 -0.3506443 -0.9315996 0.09576392 -0.3613977 -0.9285745 0.08450466 -0.2836942 -0.9336963 0.2184693 -0.2424601 -0.9393755 0.2424597 -0.2387402 -0.934858 0.2627614 -0.134288 -0.9186125 0.3716421 -0.1603834 -0.9194242 0.3590771 -0.2091498 -0.9254302 0.3159675 -0.06074178 -0.8185768 0.5711765 -0.1402919 -0.8274877 0.5436748 -0.1566282 -0.8567451 0.4913814 0.005921483 -0.7604297 0.6493933 0.04852735 -0.7342323 0.6771618 0.7274867 -0.6551269 0.2038917 0.5768278 -0.7463759 0.3319529 0.6245864 -0.7020117 0.3421571 0.4610017 -0.765993 0.4480315 0.4956483 -0.7419233 0.4515336 0.4664741 -0.7518852 0.4659084 0.3386753 -0.7972223 0.4997358 0.3721026 -0.8795437 -0.296551 0.5002778 -0.8020637 -0.3262147 0.5474545 -0.8122774 -0.2012435 0.3212949 -0.8757981 -0.3602045 0.3766601 -0.8036953 -0.4606531 0.4112453 -0.8032674 -0.4308582 0.2701323 -0.885545 -0.3779401 0.1538286 -0.8614413 -0.4839997 0.2076112 -0.8445696 -0.4935586 0.2109997 -0.8452381 -0.4909701 0.2515648 -0.8276853 -0.5016496 0.2667774 -0.8311257 -0.4879139 0.2978646 -0.8145681 -0.4977505 0.3208189 -0.8192756 -0.4752503 0.3428028 -0.8063924 -0.4818897 0.3781969 -0.8103163 -0.4476099 0.007210791 -0.948814 -0.3157534 0.00598526 -0.9335827 -0.3583123 0.03868865 -0.9290186 -0.368005 0.06153255 -0.9075662 -0.4153763 0.06870603 -0.9072592 -0.4149221 0.09725832 -0.8909364 -0.4435911 0.1156736 -0.8878283 -0.4453995 0.1207844 -0.8746511 -0.4694644 0.1692335 -0.8637007 -0.4747433 -0.2505199 -0.9612361 -0.1151741 -0.173792 -0.9664046 -0.1893637 -0.06132847 -0.9771277 -0.2036185 -0.06770944 -0.9666267 -0.2470797 0.157629 -0.9511554 -0.265437 -0.0185967 -0.9952064 -0.09601324 -0.0185973 -0.9952062 -0.0960142 0.03227543 -0.9989578 -0.03227519 0.2467342 -0.9664906 0.07083904 0.2467333 -0.9664908 0.07083898 0.3249593 -0.9431949 0.06917279 0.3249592 -0.9431949 0.06917423 0.3990367 -0.9156383 0.0487461 0.3990364 -0.9156385 0.04874593 0.4646706 -0.8854184 0.01074475 0.3779382 -0.8855469 -0.2701287 0.5673531 -0.7808562 -0.2614845 0.5612686 -0.8060634 -0.1877215 0.5661641 -0.8117232 -0.143401 0.5560368 -0.8240783 -0.1082498 0.5560365 -0.8240783 -0.1082514 0.518034 -0.8542975 -0.04262119 0.5024305 -0.7721472 -0.3890402 0.5078207 -0.7620126 -0.4018148 0.3602077 -0.8757964 -0.3212959 -0.2111808 -0.9770726 0.02705574 -0.2111814 -0.9770725 0.02705568 -0.1294527 -0.9830992 0.1294524 -0.1294529 -0.9830992 0.1294529 -0.02705574 -0.9770724 0.2111811 0.5652062 -0.8006955 0.1985669 0.565207 -0.8006948 0.1985675 0.4597678 -0.849242 0.2596182 0.4597681 -0.8492421 0.2596176 0.3407574 -0.8935135 0.292435 0.3407555 -0.8935143 0.2924343 0.2150846 -0.9309396 0.2951106 0.1689109 -0.9841703 0.05364704 0.239018 -0.957157 -0.1634657 -0.02616035 -0.7884826 0.6145005 -0.04184466 -0.819688 0.5712798 0.006726741 -0.8843856 0.4667088 -0.1119515 -0.9047746 0.4109134 -0.1155418 -0.9060439 0.4071054 0.03062319 -0.8148344 0.5788845 0.1153598 -0.7046217 0.7001432 0.1722739 -0.8467773 0.5032793 0.006727159 -0.8843856 0.4667088 0.09005928 -0.9593423 0.2674914 -0.02705633 -0.9770725 0.2111808 0.09601229 -0.9952065 0.01859658 0.03227543 -0.9989578 -0.03227502 0.1926346 -0.9621765 -0.1926354 0.1753638 -0.9609032 -0.2142725 -0.4126424 -0.9103689 -0.03090202 -0.1281997 -0.9913567 0.02787125 -0.2674924 -0.9593421 -0.09005904 -0.05364757 -0.9841704 -0.1689106 -0.0536465 -0.9841704 -0.1689104 0.1634675 -0.9571562 -0.2390198 0.1111201 -0.9274881 0.356957 0.3129628 -0.6276289 0.7128368 0.3386757 -0.7972227 0.4997349 0.1722728 -0.8467774 0.5032794 0.2150846 -0.9309394 0.2951112 0.09005939 -0.9593421 0.2674926 0.1689107 -0.9841704 0.05364692 0.09601426 -0.9952062 0.01859718 0.2142761 -0.9609022 -0.1753648 0.6973686 -0.7013733 -0.1474878 0.6737859 -0.7387449 0.01639014 0.7013344 -0.7128309 -0.001478672 0.6408063 -0.7612107 0.09962791 0.5180337 -0.8542978 -0.04262101 0.4646671 -0.8854204 0.01074582 0.339421 -0.9236334 -0.17803 0.6647089 -0.7396463 -0.1052883 0.5756399 -0.7837679 -0.2331237 0.5925508 -0.7736296 -0.2244566 0.6538925 -0.736266 -0.1741755 0.4335308 -0.8038967 -0.4071871 0.4493315 -0.8054761 -0.3864058 0.4701662 -0.8080522 -0.3549585 0.4881647 -0.8010659 -0.346394 0.5571427 -0.7821693 -0.2789324 4.01001e-6 0 -1 -7.16974e-4 0 -0.9999998 8.93975e-5 0 -1 0.01941376 0 -0.9998115 0.01723879 0 -0.9998515 3.462e-4 0 -1 -0.003903985 0 -0.9999924 -0.0499376 0 -0.9987524 -4.36279e-4 0 -1 0.1203314 0 -0.9927338 -0.004496812 0 -0.9999899 0.1366374 0 0.9906212 -0.01231938 0 -0.9999242 -0.1267148 0 0.9919393 0.008781194 0 -0.9999615 0.063115 0 0.9980063 0.01355803 0 -0.9999082 0.04415577 0 0.9990248 -0.01413285 0 -0.9999002 9.20132e-4 0 -0.9999997 -0.0144912 0 -0.9998951 0.07124704 0 -0.9974587 0.00526303 0 -0.9999862 0.006908297 0 -0.9999762 -0.01514977 0 -0.9998853 -0.01886457 0 -0.999822 0.02939903 0 -0.9995678 -0.01418292 0 -0.9998995 0.01709151 0 -0.999854 0.0192272 0 -0.9998152 0.009132027 0 -0.9999583 -0.01550197 0 -0.9998798 -0.01960402 0 -0.9998079 0.0338788 0 -0.999426 -0.01298588 0 -0.9999158 0.001373589 0 -0.9999991 -8.96338e-5 0 -1 0.008196413 0 -0.9999665 -0.09950369 0 -0.9950373 0.002747237 0 -0.9999963 -0.1269641 0 0.9919073 0.01550197 0 -0.9998798 0.01999598 0 -0.9998001 -0.03701162 0 -0.9993149 -6.31273e-5 0 -1 -0.02499216 0 -0.9996877 -0.0475651 0 -0.9988682 0.02563256 0 -0.9996715 -0.02701711 0 -0.999635 -3.55366e-4 0 -1 0.1950864 0.980786 -3.30195e-7 0.1950741 0.9807886 0 0.1950849 0.9807865 2.17913e-5 0.1950807 0.9807872 0 0.6900724 0.7237228 0.005043625 0.6888524 0.7248844 0.005001664 0.6828529 0.7305403 0.004781961 0.6752436 0.7375811 0.004509389 0.6710639 0.7413867 0.004362761 0.6630651 0.7485505 0.004102289 0.6616101 0.7498371 0.004054963 0.6555804 0.7551156 0.003858864 0.6434015 0.7655211 0.003483116 0.633518 0.7737213 0.003210425 0.6256767 0.7800768 0.002987504 0.6241436 0.7813042 0.002944707 0.6159307 0.7877956 0.002737224 0.6143178 0.7890542 0.002695381 0.6081783 0.7937965 0.002536118 0.6006332 0.7995213 0.002359509 0.5755943 0.8177334 0.001795291 0.5545566 0.8321449 0.001424908 0.5463789 0.8375371 0.001284062 0.5442178 0.8389431 0.001249432 0.5362009 0.8440898 0.001118838 0.5339906 0.8454898 0.001087486 0.5272789 0.8496918 9.89166e-4 0.5185651 0.8550378 8.68158e-4 0.5128043 0.8585052 7.96546e-4 0.5062844 0.8623664 7.13281e-4 0.5007523 0.8655905 6.51298e-4 0.4956346 0.868531 5.92654e-4 0.4821956 0.8760635 4.51609e-4 0.4275501 0.9039917 0 0.9140965 0.4054657 0.005020916 0.9143168 0.4049684 0.005028367 0.9104866 0.4135112 0.004781007 0.9059228 0.4234188 0.004498839 0.9037402 0.4280588 0.004378557 0.8989282 0.4380769 0.004083216 0.8985897 0.4387711 0.004074752 0.8945448 0.4469615 0.003859698 0.8873103 0.4611598 0.003479838 0.8819168 0.471394 0.003225088 0.8760312 0.4822454 0.002967953 0.8759813 0.482336 0.002965569 0.8701183 0.4928353 0.002717494 0.8700283 0.4929944 0.002714216 0.8655803 0.5007638 0.002535641 0.8607879 0.5089587 0.002359151 0.8448472 0.5350049 0.001799523 0.7729602 0.6344546 -1.19599e-6 0.6087609 0.7933537 -1.00474e-6 0.7065445 0.7076641 0.002539575 0.4422879 0.8968656 -0.003673315 0.698758 0.7153379 0.005382418 0.6979388 0.7161375 0.005342483 0.980785 0.1950921 -1.49719e-6 0.9999745 0.004476606 0.005579888 0.9997856 0.02006125 0.005144476 0.999567 0.0290153 0.004903495 0.998995 0.04459822 0.004497408 0.9985646 0.05339127 0.004269063 0.9977016 0.06764727 0.003929674 0.9962347 0.08662772 0.003477215 0.9947476 0.1023102 0.003130733 0.9929861 0.1181983 0.00280416 0.9919176 0.126857 0.002626299 0.9900872 0.1404346 0.002360641 0.9851993 0.1714038 0.00179249 0.9799273 0.1993511 0.001373887 0.9766184 0.2149773 0.001158833 0.9747275 0.2233952 0.001046478 0.9711737 0.2383718 8.6056e-4 0.9688637 0.2475934 7.60261e-4 0.9654315 0.2606565 6.20419e-4 0.9604227 0.2785463 4.5142e-4 0.9414799 0.3370692 -1.41726e-6 0.8968685 0.4422973 -1.36716e-6 0.9237655 0.3829582 6.40514e-4 0.7933562 0.6087552 -0.001796305 0.919009 0.3942001 0.005359053 0.9192329 0.3936779 0.005365431 0.7924786 0.6081078 0.04671835 0.9643605 0.2583975 0.05691581 0.6083725 0.7928453 0.03576815 0.2587884 0.9658142 0.01521503 0.964345 0.2584702 0.05685043 0.9531226 0.2585051 0.1572657 0.9531101 0.2585926 0.1571978 0.944763 0.2588286 0.2010738 0.9390121 0.2557805 0.2298537 0.7100333 0.7040475 -0.01303619 0.6981293 0.7066522 0.1151443 0.6980345 0.7067678 0.1150095 0.6870199 0.7069106 0.16817 0.6869513 0.7069998 0.168075 0.682016 0.7071041 0.1867032 0.6821068 0.7069956 0.1867823 0.6937816 0.706744 0.1384923 0.6939597 0.7065269 0.1387073 0.9782034 0.194578 0.07250905 0.960407 0.2586902 0.1034303 0.9513474 0.2586771 0.1674047 0.9413515 0.2802609 0.187913 0.9416557 0.2587819 0.2152128 0.9316678 0.2587407 0.2550458 0.9316538 0.2588226 0.2550142 0.9377429 0.2587599 0.2316927 0.894888 0.4413205 0.06642037 0.7919833 0.6077065 0.05878293 0.7004539 0.7071051 0.09678125 0.6081379 0.792537 0.04531675 0.4420379 0.8963915 0.03293913 0.2587301 0.9658308 0.01516193 0.2556793 0.9658434 0.04212623 0.2556132 0.9658637 0.04206258 0.2515301 0.965891 0.06154125 0.2514843 0.965906 0.06149405 0.2496295 0.9659258 0.06835627 0.2496958 0.9659054 0.06840193 0.2540374 0.9658607 0.05077546 0.2541766 0.9658175 0.05090248 0.253652 0.9657582 0.05451536 0.1950666 0.9806809 0.01462835 0.9686749 0 0.2483324 0.9686686 0 0.248357 0.7297576 0 0.6837061 0.7297097 0 0.6837572 0.310906 0 0.9504407 0.3108135 0 0.950471 -0.1848458 0 0.9827677 -0.6348391 0 0.7726444 0.595421 0 0.803414 0.1463466 0 0.9892334 -0.3370844 0 0.9414745 -0.3369916 0 0.9415076 -0.7410374 0 0.6714637 -0.7409902 0 0.6715158 -0.9700455 0 0.2429235 0.9700452 0 0.2429247 0.7409982 0 0.6715071 0.7410454 0 0.671455 0.3369882 0 0.941509 0.3370809 0 0.9414757 -0.146348 0 0.9892331 -0.5954151 0 0.8034183 0.6348367 0 0.7726464 0.184849 0 0.9827671 -0.3108121 0 0.9504715 -0.3109046 0 0.9504413 -0.7297043 0 0.6837629 -0.7297522 0 0.6837118 -0.9686712 0 0.2483469 -0.9686775 0 0.2483223 0.9517472 0.2694581 0.146866 0.9260407 0.3386032 0.1667226 0.9335886 0.3189656 0.1633201 0.9410372 0.299186 0.1579135 0.9774184 0.1890993 0.09431248 0.9800835 0.1575801 0.1208517 0.9812287 0.1365141 0.1362136 0.9820137 0.1155021 0.1493604 0.9825364 0.09451508 0.1602778 0.9828459 0.06301516 0.1733297 0.9831771 0.03156119 0.1799077 0.9831001 9.60542e-4 0.1830664 0.7703548 0.6257021 0.1226807 0.7528311 0.6458215 0.1271227 0.7103232 0.6920194 0.1286475 0.7246377 0.6768289 0.1296264 0.7388237 0.661413 0.1291216 0.79913 0.5906618 0.1118476 0.832419 0.5478081 0.08357715 0.844537 0.5307584 0.07108414 0.8569609 0.5015665 0.1185287 0.8744446 0.4637042 0.1425662 0.8909095 0.4255043 0.1588284 0.9029188 0.3967502 0.165309 0.9107201 0.3774497 0.1676926 0.9184178 0.3580864 0.1681759 0.6663078 0.7364562 0.1169031 0.6811766 0.7218351 0.122281 0.6958407 0.7070201 0.1262075 0.6202583 0.7790086 0.0917887 0.6359207 0.7650291 0.1016635 0.6512162 0.7508753 0.110018 0.5716578 0.8192047 0.04594802 0.5890284 0.807241 0.03751844 0.6061153 0.7948831 0.02802026 0.5203306 0.8515579 0.06407183 0.5333185 0.843753 0.06043398 0.5540332 0.8307898 0.05325227 0.3915154 0.9175081 0.06996327 0.4058752 0.911093 0.07193744 0.4248865 0.9022607 0.07346546 0.4390246 0.895439 0.07380008 0.4484149 0.8907784 0.07374292 0.4624591 0.8836101 0.07324481 0.4764705 0.8762434 0.07192677 0.4857109 0.8712504 0.07076561 0.4995538 0.8635619 0.06860631 0.1092074 0.99383 0.01938331 0.2582423 0.9659604 -0.01521831 0.3184856 0.9465034 0.05194598 0.3430786 0.9374322 0.05931341 0.3528999 0.9336031 0.06202536 0.3625932 0.9297186 0.06441706 0.3722751 0.9257352 0.06652438 0.3819152 0.9216619 0.06841218 0.2044771 0.9788528 0.006034076 0.1721941 0.9802019 0.09774202 0.1721934 0.9802022 0.09774041 0.1282296 0.9802027 0.1508635 0.1282315 0.9802023 0.1508648 0.06871771 0.9802024 0.1856914 0.06871658 0.9802024 0.1856915 0.5649912 0.8233874 0.05308705 0.4883006 0.8274881 0.2771754 0.4883066 0.8274847 0.277175 0.3636338 0.8274883 0.4278243 0.3636443 0.8274839 0.427824 0.1948738 0.827483 0.5265892 0.1948711 0.8274871 0.5265836 -0.1949734 0.9802024 0.03447794 -0.1949757 0.980202 0.03447741 -0.5529117 0.8274838 0.09777134 -0.5529043 0.8274888 0.09777194 -0.822629 0.549656 0.1454647 -0.8226246 0.5496625 0.1454651 -0.9663599 0.19222 0.1708804 -0.1269007 0.9802022 0.1519864 -0.1269008 0.9802024 0.1519856 -0.3598672 0.8274852 0.4310034 -0.3598676 0.8274853 0.4310031 -0.5354176 0.5496594 0.6412508 -0.5354133 0.5496606 0.6412534 -0.06708317 0.9802023 0.1862884 -0.06708109 0.9802025 0.1862882 -0.190231 0.8274863 0.5282789 -0.1902471 0.8274827 0.5282788 -0.2830342 0.5496608 0.7859801 -0.2830542 0.5496588 0.7859742 0.8350068 0.5440958 0.08199715 0.7265099 0.5496578 0.4123831 0.7265029 0.5496629 0.4123885 0.5410336 0.5496567 0.636522 0.541034 0.5496597 0.636519 0.2899257 0.5496625 0.7834631 0.2899205 0.5496612 0.7834659 -0.8117784 0.1395362 0.5670499 -0.8896617 0.1944301 0.4131577 -0.9663603 0.1922184 0.1708797 -0.3324823 0.1922193 0.9233133 -0.6289735 0.1922174 0.7532894 -0.6289727 0.1922172 0.7532902 -0.8491509 0.1922216 0.4919285 -0.7228597 0.5496559 0.4187508 -0.7228468 0.5496671 0.4187585 -0.4858475 0.8274871 0.2814557 -0.4858498 0.8274862 0.2814548 -0.1713279 0.9802021 0.09925049 -0.1713253 0.9802026 0.09925043 0.08251285 0.1431175 0.9862602 -0.08975589 0.1945018 0.976787 -0.3324699 0.1922215 0.9233172 8.68053e-4 0.9802025 0.1979959 8.72814e-4 0.9802022 0.1979971 0.002474844 0.8274835 0.5614848 0.002463936 0.8274876 0.5614786 0.003697097 0.5496609 0.8353797 0.003679096 0.5496608 0.8353798 0.004319429 0.1922189 0.9813426 0.3406128 0.1922169 0.9203454 0.3405777 0.192218 0.9203582 0.635565 0.1922173 0.7477363 0.6355449 0.1922208 0.7477526 0.9653306 0.2295496 0.1242743 0.977383 0.1894587 0.09395766 0.8534443 0.192224 0.4844408 0.8937663 0.1466897 0.4238679 0.7995479 0.1945821 0.5682086 -0.2899202 0.5496646 0.7834637 -0.1948714 0.8274855 0.5265862 -0.06871652 0.9802026 0.1856905 -0.70512 0.6974492 0.1279472 -0.3688521 0.9271545 0.0658245 -0.1757408 0.9839422 0.03119248 -0.1998363 0.9796339 0.01957046 -0.3466941 0.9360311 0.06040745 -0.359401 0.9310091 0.06366336 -0.6905936 0.7123649 0.1249673 -0.6758385 0.7271303 0.1205151 -0.6607892 0.7417804 0.114541 -0.6454818 0.7562357 0.107055 -0.629935 0.7704358 0.0980339 -0.564333 0.8236781 0.05552232 -0.6166449 0.7869477 0.02150934 -0.6003918 0.7990921 0.03133314 -0.5839771 0.8107791 0.04010087 -0.5673493 0.8220881 0.04781448 -0.5505473 0.8330206 0.05453866 -0.533559 0.8436137 0.06025624 -0.5163994 0.8538799 0.0649687 -0.4991062 0.8638153 0.06867432 -0.4728089 0.8781568 0.07274913 -0.4462168 0.8918713 0.07386684 -0.4263231 0.9015732 0.07358306 -0.4124234 0.9080911 0.07264691 -0.3964219 0.9153445 0.07066959 -0.3835152 0.9209728 0.06874006 -0.3818098 0.9217036 0.06843703 -0.9001207 0.4035927 0.1639997 -0.892204 0.4227088 0.1590268 -0.8840304 0.441983 0.1521234 -0.8757902 0.4609286 0.1433056 -0.8671084 0.4801813 0.1324737 -0.8339961 0.5447468 0.0877583 -0.8634054 0.5022627 0.04757523 -0.8518596 0.5200125 0.06262987 -0.8398352 0.5374684 0.07618761 -0.8273862 0.5546668 0.08818626 -0.8146535 0.5715014 0.09862017 -0.8017066 0.5879707 0.1075038 -0.7884848 0.6042296 0.1148843 -0.7750852 0.6202128 0.1207444 -0.7614219 0.6360638 0.1251391 -0.7476496 0.6516343 0.1280354 -0.7265707 0.6746482 0.1301721 -0.9648408 0.1927487 0.1786903 -0.9931474 0.1103147 0.03858667 -0.9554049 0.2578433 0.143939 -0.9342733 0.316854 0.1635144 -0.9193193 0.3554835 0.1687706 -0.9079572 0.3843264 0.1670543 -0.06871753 0.9802025 0.1856904 -8.69952e-4 0.9802021 0.1979977 -8.70351e-4 0.9802021 0.1979979 0.06708121 0.9802027 0.1862874 0.06708353 0.980202 0.1862901 0.1269007 0.9802025 0.1519849 0.1269009 0.9802021 0.1519869 0.1713255 0.9802025 0.09925049 0.1713276 0.9802021 0.09925031 0.1949734 0.9802024 0.03447794 0.1949757 0.980202 0.03447741 -0.1948725 0.8274856 0.5265855 -0.002465009 0.8274862 0.5614807 -0.002477109 0.8274836 0.5614845 0.190237 0.8274838 0.5282807 0.1902396 0.8274863 0.5282759 0.3598666 0.8274856 0.431003 0.3598684 0.8274857 0.4310015 0.4858493 0.8274863 0.2814551 0.4858468 0.8274877 0.2814553 0.5529046 0.8274885 0.09777152 0.5529127 0.8274832 0.09777104 -0.1721938 0.9802021 0.09774059 -0.1721942 0.980202 0.09774082 -0.4883019 0.8274877 0.2771742 -0.4883073 0.8274847 0.2771738 -0.7265117 0.5496555 0.4123829 -0.7264993 0.5496675 0.4123888 -0.853444 0.1922215 0.4844424 -0.2899265 0.5496584 0.7834655 -0.003697097 0.5496611 0.8353797 -0.003679096 0.5496603 0.8353801 0.283046 0.5496599 0.7859765 0.2830398 0.5496585 0.7859798 0.5354188 0.549657 0.6412518 0.5354128 0.5496631 0.6412518 0.7228519 0.5496639 0.4187539 0.7228539 0.5496591 0.4187567 0.822629 0.5496561 0.1454639 0.8226237 0.5496633 0.145466 -0.5796803 0.1433751 0.8021311 -0.7041894 0.1945068 0.6828502 -0.8534539 0.1922149 0.4844275 0.2082693 0.1949143 0.9584531 -0.004288315 0.1922202 0.9813424 -0.004319429 0.1922184 0.9813427 -0.3405939 0.1922184 0.9203521 -0.3405979 0.1922176 0.9203507 -0.6355647 0.1922156 0.7477371 -0.5410317 0.5496599 0.6365208 -0.5410345 0.5496567 0.6365212 -0.3636465 0.8274824 0.427825 -0.3636352 0.8274871 0.4278255 -0.1282318 0.9802022 0.1508651 -0.12823 0.9802026 0.150864 0.3740343 0.1655731 0.9125152 0.3324825 0.192218 0.9233135 0.5810858 0.1938791 0.7904115 0.6316751 0.1690914 0.7565677 0.7097159 0.1947226 0.6770425 0.8491507 0.1922257 0.4919273 0.8491534 0.1922231 0.4919236 0.96636 0.192219 0.1708805 0.9663601 0.1922187 0.1708806 -0.02159464 -0.714405 0.6993992 -0.3407449 -0.9212164 0.1877589 -0.3519468 -0.9238991 0.1501466 -0.1824133 -0.9348865 0.3044877 -0.2180981 -0.9465247 0.2377483 -0.2285748 -0.9388179 0.2576327 -0.2554657 -0.9461141 0.1990112 -0.2820843 -0.9352306 0.2139447 -0.286573 -0.9417013 0.1762804 0.02943307 -0.8396217 0.5423735 -0.02015888 -0.8892955 0.4568885 -0.009754478 -0.8674491 0.4974305 -0.05826371 -0.9089483 0.4128176 -0.04980683 -0.8910067 0.4512498 -0.09747809 -0.9246137 0.3682222 -0.0927844 -0.9109493 0.4019485 -0.1338339 -0.9334829 0.3327136 -0.1284763 -0.9281849 0.3492375 -0.1622018 -0.9370076 0.3093663 -0.1792137 -0.9431505 0.2799103 0.07738554 -0.8603463 0.5038013 0.03618478 -0.8240964 0.5652927 0.09173876 -0.7529268 0.6516789 0.04111349 -0.8039436 0.5932828 -0.03872734 -0.7467302 0.6639987 -0.3181002 -0.9242206 0.2112548 -0.305113 -0.9237508 0.2314968 -0.3076804 -0.9249538 0.2231445 -0.2714573 -0.9204145 0.2813327 -0.2740958 -0.9221822 0.2728581 -0.2380912 -0.912999 0.3312787 -0.2407669 -0.9153506 0.3227455 -0.2050261 -0.901454 0.3812414 -0.2077013 -0.9044006 0.3727196 -0.1711282 -0.8850085 0.432984 -0.1735983 -0.888629 0.4245023 -0.1380406 -0.8642914 0.4836789 -0.1406228 -0.868434 0.4754446 -0.1073226 -0.8404603 0.5311387 -0.1098067 -0.8451377 0.523149 -0.07754808 -0.8127731 0.5773963 -0.07989019 -0.8179373 0.5697336 -0.04874545 -0.7812095 0.622363 -0.05090838 -0.7868067 0.6150965 0.02692633 -0.6723487 0.7397447 -0.0163989 -0.9455242 0.3251388 -0.4325055 -0.8989545 0.06942665 -0.4216388 -0.904547 0.06336915 -0.4204281 -0.90549 0.05769002 -0.4128825 -0.9067161 0.08598887 -0.4124249 -0.9074593 0.08014708 -0.405065 -0.9087538 0.100444 -0.4072173 -0.9085891 0.09295147 -0.3982397 -0.9099116 0.1160436 -0.3990817 -0.9108474 0.1053132 -0.3826474 -0.9132741 0.1396829 -0.3861923 -0.914242 0.1225439 -0.3654801 -0.9170864 0.1593009 -0.3744688 -0.9173948 0.1347597 -0.421637 -0.9047693 0.06012338 -0.4278689 -0.9014189 0.06612318 -0.432733 -0.8994413 0.06121784 0.9438065 0.2588126 -0.205537 0.7042542 0.5913096 -0.392911 0.5915892 0.7932255 -0.1442767 0.9773495 0.1959188 0.08002364 0.9566164 0.1938192 -0.2175296 0.9549389 0.1962307 -0.2226774 0.9545564 0.1876084 -0.2315713 0.9503623 0.1834955 -0.2512788 0.9526292 0.1793768 -0.2456045 0.9475412 0.1695261 -0.2709733 0.9507876 0.1651107 -0.2621862 0.8138837 0.5533868 -0.177078 0.7996982 0.5505529 -0.2395298 0.808948 0.5407902 -0.2305412 0.7900714 0.5220103 -0.3213912 0.7995631 0.5140007 -0.3106482 0.7828701 0.4818043 -0.3936738 0.7929607 0.4753876 -0.3810773 0.513846 0.8189457 -0.2555197 0.5241914 0.8234716 -0.2170667 0.5450102 0.8129942 -0.2049501 0.5158327 0.7841604 -0.3449771 0.5357264 0.7765324 -0.3316545 0.5095726 0.7261494 -0.4615658 0.528686 0.7211608 -0.447681 0.1753222 0.8105301 -0.5588409 0.1944086 0.8700319 -0.453045 0.1663235 0.8689846 -0.4660496 0.1986826 0.9312385 -0.3054834 0.1679436 0.9325562 -0.3195844 0.2037248 0.9676932 -0.1485465 0.1705034 0.9718058 -0.1628563 0.195733 0.9794893 -0.04784864 0.2850219 0.9516934 0.1142033 0.1855042 0.759493 -0.6235052 0.2115392 0.771611 -0.5998896 0.5237694 0.6478955 -0.5530796 0.5062118 0.6500381 -0.5667452 0.7890622 0.425909 -0.4426991 0.7786559 0.4301016 -0.4568455 0.9506656 0.1475205 -0.2728969 0.946407 0.1512524 -0.2853709 0.9469173 0.1290734 -0.2944278 0.9517964 0.1273896 -0.2790262 0.7774797 0.3686862 -0.5095055 0.7876075 0.3672366 -0.4947845 0.5057331 0.5586423 -0.6573835 0.5209721 0.5591776 -0.6449097 0.1681614 0.6742295 -0.7191219 0.2161737 0.5295573 -0.8202672 0.1768321 0.595137 -0.7839276 0.1873892 0.678586 -0.7102157 0.9509406 0.07896244 -0.2991271 0.9552228 0.08226752 -0.2842208 0.7812181 0.230541 -0.5801286 0.7889602 0.2334317 -0.5683762 0.5099752 0.3510495 -0.785296 0.5198579 0.3543971 -0.7772713 0.9488232 0.10469 -0.2979509 0.953333 0.1063748 -0.2825607 0.7792439 0.3023814 -0.5489486 0.7876876 0.3040845 -0.5357993 0.5081781 0.45962 -0.7283574 0.5197272 0.4624759 -0.7183313 0.1843699 0.5541723 -0.8117271 0.1731671 0.4251439 -0.8884064 0.2234917 0.2475031 -0.9427586 0.1791234 0.3278005 -0.9276108 0.1837257 0.4294618 -0.8841987 0.9557471 0.02131724 -0.2934165 0.9570701 0.02409636 -0.2888531 0.7878104 0.064417 -0.61254 0.7901917 0.06659144 -0.6092313 0.5166491 0.09866672 -0.8504931 0.5194638 0.1004544 -0.8485673 0.5203089 0.01661092 -0.8538166 0.5201949 0.0162689 -0.8538928 0.7907808 0.01100373 -0.6120005 0.7906847 0.0106076 -0.6121318 0.957152 0.004014909 -0.2895585 0.9570977 0.003454148 -0.289745 0.9535952 0.05025982 -0.2968674 0.9565725 0.05454081 -0.2863464 0.7847097 0.1492517 -0.6016266 0.7900159 0.1527352 -0.5937566 0.5135151 0.2279365 -0.8272528 0.5199525 0.231142 -0.8223277 0.182429 0.2758365 -0.9437341 0.1784964 0.1197149 -0.9766308 0.1811819 0.1212297 -0.975949 0.1812808 0.01976919 -0.9832327 0.1813853 0.02003258 -0.9832081 0.6674689 -0.7095439 -0.2259048 0.9770212 -0.03345441 0.2105009 0.9813181 -0.03432089 0.1893063 0.9832448 -0.03990131 0.17787 0.9855698 -0.04045265 0.1643645 0.9882417 -0.152867 -0.003175735 0.9865363 -0.1609776 -0.02884912 0.9871664 -0.06840342 0.1443033 0.9913494 -0.06955862 0.111302 0.9861004 -0.1040281 0.1295536 0.9907364 -0.08383673 0.1068319 0.994517 -0.05980253 0.0857889 0.9944707 -0.05762279 0.08779448 0.9880503 -0.1513547 -0.02912628 0.9579101 -0.2720558 0.09161895 0.886065 -0.4629357 -0.02407342 0.9294509 -0.3689041 -0.005566358 0.8742889 -0.482258 -0.0551936 0.8699822 -0.490534 -0.05007463 0.7239292 -0.684769 -0.08377259 0.7069674 -0.6967546 -0.121368 0.4637644 -0.8827546 -0.07527887 0.5001732 -0.8480172 -0.1751968 0.4419245 -0.8460005 -0.2983053 0.4409899 -0.8327333 -0.3347885 0.2375409 -0.9138057 -0.3294444 0.3703705 -0.8759935 -0.3089678 0.3308191 -0.8789367 -0.3435534 0.3638566 -0.8726181 -0.3258007 0.4410679 -0.8507437 -0.2858223 0.6579024 -0.7163921 -0.2322646 0.6674132 -0.7106294 -0.2226333 0.8755774 -0.4625985 -0.1391655 0.8791005 -0.4576426 -0.1332131 0.9868007 -0.1563994 -0.04199695 0.986418 -0.1582905 -0.04386121 0.9864205 -0.1582262 -0.0440374 0.9859994 -0.1602814 -0.04599201 0.8755788 -0.4625746 -0.1392363 0.8716189 -0.4680665 -0.1455826 0.6579042 -0.7165157 -0.2318779 0.6470978 -0.7228935 -0.2422591 0.3703608 -0.8769171 -0.3063483 0.3517886 -0.880156 -0.3187008 0.9829705 -0.1766427 -0.05066019 -0.3222129 -0.946177 0.03046584 -0.02599287 -0.9902779 -0.1366537 -0.03096652 -0.9825688 -0.183302 0.2170032 -0.9631201 -0.1590896 0.2173819 -0.937263 -0.2725494 0.1748912 -0.9732774 -0.1488094 0.379612 -0.9118236 -0.1564368 0.5655435 -0.8166519 -0.1150668 0.8107071 -0.5801693 -0.07847046 0.8083739 -0.5886688 8.89004e-4 0.8484711 -0.5290929 -0.0125572 0.8479829 -0.5295445 0.02253502 0.8249748 -0.5641667 0.03365731 0.4156778 -0.9079225 0.05374759 0.4960696 -0.8678355 0.02786737 0.1597726 -0.9854773 0.05750846 0.2710992 -0.9622238 0.02511185 -0.0938521 -0.9939855 0.05643272 0.0404824 -0.9989863 0.01968747 -0.2177643 -0.9750772 0.04246628 -0.1527182 -0.9862518 -0.06312453 0.5739808 -0.8105006 -0.1167681 0.8421208 -0.5309592 -0.09441822 0.8424782 -0.5191147 -0.1440501 0.9860564 -0.1582553 -0.05145907 0.8717734 -0.4656659 -0.1522059 0.6459711 -0.7349309 -0.206393 0.5664754 -0.7850839 -0.2504974 0.3508275 -0.9002779 -0.2577204 0.158712 -0.935545 -0.3155411 0.9725931 -0.2323629 0.008375108 0.9739212 -0.2266678 0.009962618 0.9790711 -0.2032894 -0.009647607 0.9795482 -0.2010433 -0.008186757 0.9796739 -0.1979345 -0.03257393 0.9846043 -0.1736052 -0.0203855 0.9829463 -0.1808212 -0.03347212 -0.02599728 -0.9915714 -0.1269267 -0.09365969 -0.994059 -0.05544823 0.1747248 -0.9816873 -0.07590401 0.04050827 -0.9983322 -0.04113417 0.3792924 -0.9231969 -0.06200665 0.2713583 -0.9618865 -0.03375107 0.5730707 -0.8181402 -0.0472927 0.4965759 -0.8675941 -0.02632117 0.6947756 -0.7185178 -0.03192454 0.6942468 -0.7192273 0.02708631 0.645646 -0.762286 0.0454027 -0.3225613 -0.9440137 0.06922757 -0.09230625 -0.990512 -0.1018121 -0.189589 -0.9803481 0.05453258 0.1716581 -0.982513 0.07212394 0.1597802 -0.9853125 0.06024682 0.4243644 -0.9030961 0.06582146 0.4156962 -0.9077636 0.05623149 0.6509303 -0.7571607 0.05474835 0.6456741 -0.7621118 0.04786235 0.8274794 -0.560057 0.04017728 0.8249912 -0.5640026 0.03592467 0.9730076 -0.2300475 0.01828652 0.9726414 -0.2317973 0.01545792 0.9729276 -0.2296272 0.02613967 0.840169 -0.5390104 0.05986499 0.9007225 -0.4315685 0.04947274 0.9750909 -0.2198616 0.02930641 0.8269097 -0.558266 0.06752395 0.6504199 -0.7551656 0.08172494 0.6795887 -0.7279807 0.09057217 0.423919 -0.9006068 0.09591728 0.4715904 -0.8748895 0.1103217 0.1714646 -0.9798385 0.1025498 0.2368032 -0.9637479 0.1229395 -0.006316304 -0.994157 0.1077592 -0.1986517 -0.9744577 0.104737 -0.1895198 -0.9788035 0.07762771 -0.2089976 -0.970683 0.1187206 -0.2192056 -0.966862 0.1308693 -0.2389146 -0.9601161 0.1452479 -0.2381684 -0.9602265 0.145743 -0.2279026 -0.9606956 0.1585065 0.8342537 -0.4768665 0.276802 0.6300378 -0.5830496 0.5129382 0.7804925 -0.5155578 0.3535982 0.2737714 -0.8781271 0.3923546 0.04137295 -0.9195045 0.3908963 0.09746611 -0.8952959 0.4346789 0.08702516 -0.8780092 0.4706662 -0.2278293 -0.9574606 0.1770964 -0.2405751 -0.9526046 0.1861941 -0.08851623 -0.9605929 0.2634885 -0.05583596 -0.9511224 0.3037246 -0.07773995 -0.942178 0.3259712 -0.1060826 -0.9350715 0.3382126 -0.08415484 -0.9389398 0.3336316 0.136705 -0.9219294 0.3624335 0.2729661 -0.8984962 0.3437939 0.3482753 -0.8718141 0.3444483 0.4564928 -0.831385 0.3168808 0.5506967 -0.7759161 0.3077133 0.6273792 -0.727839 0.2768499 0.7993264 -0.5547639 0.230899 0.8338863 -0.5167679 0.1938676 0.9808216 -0.1336181 0.141899 0.9763885 -0.1743278 0.1275748 0.8633135 -0.3797309 0.3324068 0.8637741 -0.4237055 0.272705 0.6295013 -0.6723642 0.3894284 0.6277688 -0.6732554 0.3906834 0.400038 -0.7821194 0.4777646 0.456434 -0.7632646 0.4572693 0.2137966 -0.8498504 0.4817109 0.146883 -0.8452116 0.5138511 0.08429884 -0.8593013 0.5044749 0.9785588 -0.2008984 0.04541516 0.9748939 -0.2157913 0.05492001 0.900361 -0.4245746 0.09532368 0.8399985 -0.5302156 0.1152133 0.7991225 -0.5908756 0.1107678 0.6787339 -0.7148855 0.1681044 0.550898 -0.8152888 0.1783698 0.4707291 -0.8589507 0.2015387 0.3484054 -0.9156095 0.2006812 0.2362942 -0.9462109 0.2210208 0.1367552 -0.9674049 0.2131336 -0.006306707 -0.9740231 0.226361 -0.2135302 -0.9581236 0.1907991 -0.260581 -0.9449546 0.1978849 0.9851568 -0.129954 0.1121524 0.9852355 -0.1415002 0.09637922 0.985935 -0.1402055 0.09096497 0.9821332 -0.1644947 0.09141087 0.9821532 -0.1728034 0.07425713 0.9821401 -0.172878 0.07425802 0.9786407 -0.1946781 0.06605291 0.006910979 -0.9872297 0.1591538 0.01560306 -0.9881273 0.152843 0.01870489 -0.988124 0.1525161 -0.005995512 -0.8157088 0.5784319 -0.04063189 -0.858771 0.510746 0.03631198 -0.9046815 0.4245384 0.07564663 -0.8642017 0.4974263 0.05058121 -0.9048894 0.422631 0.07867199 -0.9235557 0.3753077 0.0622518 -0.8955466 0.4405918 0.01005178 -0.9891432 0.1466113 0.02042466 -0.9891971 0.1451619 0.02409362 -0.9919779 0.1240938 -0.0566852 -0.9895583 0.132519 0.02681106 -0.9943342 0.1028619 0.02920418 -0.9943326 0.1022252 0.003676593 -0.8948228 0.4464063 0.0391283 -0.8591517 0.5102229 0.001480937 -0.9839421 0.1784819 -0.01698219 -0.9837707 0.1786252 -0.006584405 -0.9787952 0.2047352 0.03013068 -0.8141277 0.5799037 0.03062438 -0.8148168 0.578909 0.1723114 -0.8148151 0.5535208 0.1723099 -0.8148154 0.5535208 0.3033722 -0.8148149 0.4940062 0.3033716 -0.8148159 0.4940047 0.4157288 -0.8148167 0.4040338 0.4157308 -0.8148152 0.4040349 0.5024604 -0.8148145 0.2891554 0.5024573 -0.8148167 0.2891546 0.5582123 -0.8148145 0.1564495 0.5582091 -0.814817 0.1564483 0.2021249 -0.979062 0.02415025 0.1973899 -0.9787629 0.05532205 0.1973904 -0.9787628 0.05532228 0.1776761 -0.9787627 0.102249 0.1776757 -0.9787628 0.1022489 0.1470074 -0.9787628 0.1428715 0.1470073 -0.9787628 0.1428717 0.1072757 -0.9787629 0.1746858 0.1072762 -0.9787628 0.1746869 0.0609309 -0.9787628 0.1957317 0.06093138 -0.9787627 0.1957318 0.02626454 -0.9790329 0.2020022 0.01070171 -0.9814929 0.1911994 9.9066e-4 -0.9787073 0.205259 0.2043498 -0.9788973 -0.001134693 0.1940321 -0.9809838 0.004719972 0.5795489 -0.8148157 0.01409804 0.5795493 -0.8148154 0.01409775 0.2370467 -0.9259337 -0.2940335 0.2530236 -0.930225 -0.2658203 0.2693456 -0.9197034 -0.2856546 0.2295839 -0.9424465 -0.2430761 0.2603104 -0.9331274 -0.2480157 0.1473262 -0.9722699 -0.1816216 0 -0.9988343 -0.0482707 3.52273e-5 -0.9988377 -0.04820233 -2.76803e-5 0 1 2.07603e-5 0 1 -2.07602e-5 0 1 -3.46004e-6 0 1 3.46005e-6 0 1 -0.216434 0 0.9762973 -0.2162919 3.90475e-4 0.9763287 0.9663899 0 0.2570808 0.9663879 0 0.2570887 -0.9658425 0 0.2591301 -0.9658493 0 0.2591049 -0.8189703 0 0.573836 -0.818991 0 0.5738065 -0.5746836 0 0.8183758 -0.5733343 -3.30449e-4 0.8193215 0.570447 -0.7929872 0.2139196 0.6819812 0 0.7313698 -0.570449 -0.7929857 0.2139198 -0.9217379 0 0.3878137 -0.6819834 0 0.7313677 -0.6819908 0 0.7313607 0.4295398 0 -0.903048 0.4295589 0 -0.9030389 -0.5435609 0 -0.8393698 0 -1 3.68772e-7 -1.7245e-6 -1 0 0 -1 -3.51402e-6 0 -1 1.24711e-6 2.07814e-7 -1 0 2.2079e-7 -1 9.58843e-7 0 -1 9.31577e-7 0 -1 2.37329e-7 0 -1 -2.47363e-7 0 -1 2.47454e-7 0 -1 2.42534e-7 0 -1 -6.51525e-7 0 -1 1.7882e-6 0 -1 9.57955e-7 0 -1 -4.81269e-7 0 -1 3.61116e-7 0 -1 3.10007e-7 0 -1 9.10417e-7 0 -1 -3.75155e-7 0 -1 -8.7669e-7 -0.965927 0 -0.2588149 -0.7071081 0 -0.7071055 -0.7070972 0 -0.7071163 -0.2588348 0 -0.9659217 -0.2587956 0 -0.9659322 0.2587956 0 -0.9659322 0.2588348 0 -0.9659217 0.7070966 0 -0.707117 0.7071074 0 -0.7071061 0.9659273 0 -0.2588138 0.9659259 0 -0.2588189 0.9659259 0 0.2588191 0.9659259 0 0.2588189 0.7071071 0 0.7071065 0.7071074 0 0.7071061 0.2588348 0 0.9659217 0.2587956 0 0.9659322 -0.2587956 0 0.9659322 -0.2588348 0 0.9659217 -0.7071081 0 0.7071055 -0.7071078 0 0.7071058 -0.9659255 0 0.2588201 -0.9659255 0 -0.2588201 -0.2922909 -0.8814336 0.3709998 -0.1937509 -0.823515 0.5331826 -0.2000657 -0.8583732 0.4724077 -0.1747548 -0.9104965 0.3747758 -0.4549981 -0.3598161 0.8145608 -0.330812 -0.6110565 0.7191478 -0.3880484 -0.478039 0.7879704 -0.4407114 -0.3858223 0.8105027 -0.2676658 -0.8616365 0.431205 -0.2565346 -0.7747216 0.5779244 -0.2962013 -0.7076545 0.6414747 -0.320941 -0.6553946 0.6837068 0.519527 -0.7323863 0.440116 0.171675 -0.6319529 0.7557534 -0.9724721 -0.193152 0.1303467 -0.9937175 -0.06287896 0.09258395 -0.4576518 -0.4856497 0.7447814 -0.4156375 -0.5091823 0.7536438 -0.3486443 -0.5237936 0.7772307 -0.9854092 -0.102414 0.1359414 -0.8809574 -0.2317872 0.4125395 -0.8972389 -0.2237756 0.38064 -0.7085362 -0.3813896 0.5937328 -0.6762683 -0.3906164 0.6245638 -0.5066994 -0.4571425 0.7309423 -0.4850218 -0.4369237 0.75753 -0.0710597 -0.5855873 0.8074888 -0.04159337 -0.6375223 0.7693083 -0.1597655 -0.5795658 0.7991112 0.5203481 -0.701006 0.4876766 0.4596636 -0.6986188 0.5483075 0.2894235 -0.7548951 0.5885301 0.2859718 -0.7534413 0.5920697 0.2070417 -0.7311995 0.6499855 -0.07047498 -0.8964548 0.4374954 0.1261919 -0.9105173 0.3937435 0.2869852 -0.8594613 0.4230437 0.3922264 -0.8340734 0.3879178 0.4514144 -0.8090866 0.376303 0.5908645 -0.7488517 0.3001669 0.7230657 -0.6262812 0.2914583 -0.4140213 -0.817281 0.400797 -0.2989646 -0.8654348 0.4020484 -0.1602656 -0.8951885 0.4158757 -0.8826199 -0.4212602 0.208619 -0.8014558 -0.546147 0.2437052 -0.7084824 -0.629725 0.3185892 -0.630898 -0.7061073 0.3215281 -0.4438697 -0.8090326 0.3852872 -0.9673665 -0.2428041 0.07244455 -0.9678234 -0.2436533 0.06285786 -0.9889576 -0.1084759 0.1009753 -0.8825809 -0.3441585 0.3203215 -0.8833034 -0.3434167 0.3191242 -0.7080646 -0.517306 0.4806653 -0.7092663 -0.5168764 0.4793539 -0.4142001 -0.6673609 0.6189247 -0.4153481 -0.6672901 0.6182313 -0.07051527 -0.7317352 0.6779316 -0.0707792 -0.7317707 0.6778658 0.1255027 -0.7277995 0.6742084 0.170345 -0.680811 0.7123756 0.4159782 -0.5039026 0.7569969 -0.1542763 -0.6420478 0.7509816 0.999777 -0.01845955 0.01026272 0.9605613 -0.2348183 0.1489376 0.9891182 -0.1463349 -0.01520836 0.8831321 -0.4238089 0.2011563 0.8080132 -0.5445891 0.2248051 0.7093583 -0.6341077 0.3077635 0.666069 -0.67987 0.3068043 0.5883526 -0.7400393 0.3258576 0.4670926 -0.8092306 0.3563289 0.4149032 -0.8239296 0.3859995 0.2642524 -0.8855479 0.3820675 0.07049489 -0.907092 0.4149877 0.0327419 -0.9149883 0.4021498 -0.2081968 -0.8954187 0.3935475 -0.287668 -0.8662787 0.4084218 -0.3859598 -0.8443931 0.3715314 -0.6097601 -0.7445651 0.27169 -0.490692 -0.7975432 0.350922 -0.5595236 -0.7001122 0.4435947 -0.4350824 -0.7182146 0.5430203 -0.2362471 -0.7764238 0.5842546 -0.2889669 -0.7623287 0.5790968 -0.1389135 -0.7293897 0.6698461 -0.1520994 -0.6270295 0.7640025 0.3247768 -0.5239045 0.7874289 0.1206855 -0.5827421 0.8036459 0.07124507 -0.6233851 0.7786626 -0.008334636 -0.6169797 0.7869351 -0.1057462 -0.6128896 0.7830609 0.8830584 -0.2501564 0.3970261 0.7229078 -0.3503259 0.595547 0.7078784 -0.3639683 0.6053391 0.4624537 -0.4676212 0.7533041 0.5017502 -0.4504444 0.7384759 -0.1498454 -0.7288925 0.6680285 0.07014328 -0.7354022 0.6739908 0.07040804 -0.7353058 0.6740683 0.4125877 -0.6714709 0.6155472 0.4143959 -0.6704115 0.6154873 0.7062885 -0.521484 0.4787599 0.7083031 -0.5193318 0.4781228 0.8815996 -0.3472443 0.3196932 0.8827634 -0.3452237 0.3186683 0.9795755 -0.1477522 0.1363865 0.9940132 -0.02091407 0.1072407 0.9618358 -0.163036 0.2197526 0.9672733 -0.1049082 0.2310341 0.1968928 -0.8848468 0.4222314 0.1975481 -0.8473759 0.4928781 0.1987263 -0.9046089 0.3770819 0.2436803 -0.7890288 0.5639624 0.2586131 -0.8322702 0.4903526 0.2735021 -0.761198 0.5880258 0.3147417 -0.668436 0.6738925 0.3162406 -0.6018808 0.7333017 0.4197906 -0.3697527 0.8288902 0.4053151 -0.3961024 0.823907 0.3421423 -0.5159732 0.7853091 0.3780843 -0.6087687 0.6974619 0.4160851 -0.6308915 0.6548658 0 -1 -1.91958e-6 0 -1 -2.78319e-6 0 -1 2.04659e-6 0 -1 -2.18417e-6 0 -1 -4.46882e-7 0 -1 1.10522e-6 0 -1 1.00354e-6 0 -1 5.7226e-7 0 -1 -1.95468e-6 0 -1 1.15529e-6 0.4297751 -0.7118306 0.5555094 0.6053906 -0.7193142 0.3407187 0.431776 -0.8561838 0.2837585 -0.3209688 -0.655364 0.683723 -0.1082496 -0.7449588 0.6582694 -0.1776633 -0.8121535 0.555736 -0.1957485 -0.8220571 0.5347006 -0.05430066 -0.8265305 0.5602669 -0.02616149 -0.7970837 0.6033018 -0.1151207 -0.8859473 0.4492715 -0.1188907 -0.8901916 0.4397999 -0.1142029 -0.9078058 0.4035423 -0.002021253 -0.9444554 0.3286337 -0.1274546 -0.9326168 0.3376112 -0.1134143 -0.9126738 0.3926371 -0.104786 -0.9061725 0.4097214 0.08781105 -0.9102439 0.4046546 0.1007203 -0.9012412 0.4214498 0.09979414 -0.8994926 0.4253872 0.102187 -0.9014449 0.4206603 0.1064254 -0.9034696 0.4152308 0.07764065 -0.9047179 0.4188764 0.07365053 -0.9072064 0.4141886 -0.1168605 -0.7270169 0.6766018 0.01145911 -0.821204 0.5705197 0.1899978 -0.8427783 0.5036127 0.184603 -0.8361708 0.516469 0.3384032 -0.8686023 0.3619577 0.3356218 -0.8449431 0.4164484 0.4300041 -0.8437376 0.3212531 0.4415079 -0.8463414 0.2979549 0.6395139 -0.7224826 0.2627565 0.4836935 -0.682049 0.5484977 0.5180516 -0.7027454 0.4876183 0.634181 -0.7289463 0.2577823 0.584591 -0.6813164 0.4405241 0.6394276 -0.7119083 0.2903777 0.4001155 -0.6912066 0.6017815 0.5321415 -0.7446337 0.402922 0.5243598 -0.7539231 0.3957864 0.6291877 -0.7570478 0.1760724 0.676401 -0.7243311 0.1335154 -0.2674756 -0.4418354 0.8562934 -0.2245278 -0.4909389 0.8417637 -0.1607881 -0.4763993 0.8644021 -0.08962529 -0.5589835 0.8243209 -0.007700264 -0.5650143 0.8250453 0.03675377 -0.6112736 0.7905656 0.142603 -0.6319245 0.7617978 0.1518535 -0.640569 0.7527363 0.2820227 -0.6932804 0.6631934 0.2479266 -0.6448581 0.7229734 0.2987739 -0.6875919 0.6617791 0.5631181 -0.7973014 0.2172756 0.5562024 -0.7970175 0.2353767 0.3893479 -0.7609241 0.5190403 0.4713931 -0.8281132 0.3033432 0.2402217 -0.7423474 0.6254709 0.3424292 -0.8378804 0.4250867 0.2001857 -0.8198818 0.536395 -0.05721646 -0.6227469 0.7803286 0.05480641 -0.7772816 0.6267612 -0.2054417 -0.5262745 0.8251236 -0.1005645 -0.7098879 0.6970984 -0.3138337 -0.4673999 0.8264659 -0.1730749 -0.6448459 0.7444589 -0.4168732 -0.4232571 0.8044068 -0.5487444 -0.8042732 0.2280886 -0.4216687 -0.6782383 0.6018208 0.08563017 -0.5722759 0.8155782 -0.2919003 -0.905389 0.3083264 -0.2923892 -0.9053173 0.3080735 -0.1818054 -0.8741928 0.4502596 -0.3397878 -0.8632054 0.3733909 -0.03175222 -0.8642929 0.5019859 0.4604533 -0.3799191 0.8022744 -0.1428045 -0.9219964 0.3599022 -0.1437156 -0.9218581 0.3598939 -0.142758 -0.9219929 0.3599298 0.09348946 -0.9019434 0.4216133 0.09349882 -0.9019446 0.4216089 0.08246487 -0.9516575 0.2958846 0.7090221 -0.5439186 0.448821 0.7091495 -0.5437354 0.4488416 0.1841886 -0.8563478 0.4824346 0.09338742 -0.9019722 0.4215744 0.1833573 -0.8558569 0.4836208 0.07013279 -0.9446885 0.3203827 0.285814 -0.6991317 0.6553817 0.2463721 -0.6597442 0.7099567 0.2682728 -0.6567173 0.7048064 0.1676922 -0.5475148 0.8198212 0.1630319 -0.4815656 0.8611128 0.1183937 -0.3499248 0.9292662 0.3094952 -0.5312758 0.7886436 -0.1366745 -0.6336201 0.7614761 -0.1124427 -0.6102018 0.7842261 -0.4746122 -0.6918755 0.5441063 -0.6907269 -0.7144971 0.1113115 -0.6788527 -0.721335 0.1372402 -0.6848323 -0.7146035 0.1426417 -0.6461197 -0.707735 0.2857285 -0.6567122 -0.7026171 0.2739678 -0.5580711 -0.7945997 0.2390986 -0.5637608 -0.8015668 0.1991591 -0.5830315 -0.752517 0.3062558 -0.5572133 -0.7809827 0.2820985 -0.5655107 -0.6968206 0.4411789 -0.5946365 -0.6577172 0.462402 -0.595705 -0.6699577 0.4430489 -0.3134199 -0.8922889 0.324944 -0.3488928 -0.8594387 0.3736829 -0.2331108 -0.822085 0.5194571 -0.07046025 -0.804688 0.589502 -0.04897081 -0.8265365 0.5607489 -0.1427958 -0.9219487 0.3600277 -0.3581973 -0.6229636 0.6954215 -0.449007 -0.4747644 0.7569621 -0.3274348 -0.6607303 0.675442 -0.3379937 -0.7490714 0.5697829 -0.3474417 -0.7378787 0.5786358 -0.3559654 -0.8345559 0.420482 -0.403309 -0.7823306 0.4746586 -0.3685208 -0.8777468 0.306191 -0.09539633 -0.5837365 0.8063197 -0.09848088 -0.5909853 0.8006485 -0.0551905 -0.6439607 0.7630653 -0.07102668 -0.7742132 0.6289269 -0.0387603 -0.8063672 0.5901438 0.06925177 -0.7255168 0.6847114 0.1443338 -0.8003018 0.5819664 0.2435459 -0.7158247 0.6544315 0.1700699 -0.8445796 0.5077024 0.5421155 -0.8051457 0.2405228 0.5057434 -0.8322607 0.2270811 0.2358661 -0.9687035 -0.07733464 0.02136707 -0.9959195 0.08767974 0.09730923 -0.9928582 0.0690183 -0.07270449 -0.9828898 0.1692391 0.1812557 -0.9812577 0.06541961 0.4037684 -0.8825062 0.2411514 0.4108389 -0.8529638 0.3219694 0.4519131 -0.8522668 0.2634693 0.6074343 -0.7492051 0.2640368 0.5485236 -0.7975342 0.2511197 0.07935464 -0.9033558 0.421487 -0.004989802 -0.8430123 0.5378713 0.3398071 -0.9336337 0.1133984 0.3383877 -0.8972887 0.2834906 0.4339543 -0.8995435 0.05005264 0.5166398 -0.8025273 0.2983846 0.5054159 -0.8284053 0.2414532 -0.1408651 -0.942844 0.3019973 -0.03431296 -0.9966986 0.07358402 -0.06311482 -0.9857727 0.1557846 -0.09156137 -0.9747709 0.2035636 -0.1275065 -0.9531962 0.2741518 -0.04251062 -0.937999 0.3440213 0.1080391 -0.9048362 0.4118239 0.3088956 -0.8665028 0.3921178 0.3080582 -0.8678964 0.3896872 0.3038702 -0.8808419 0.363016 0.1147838 -0.9010642 0.4182204 0.1116283 -0.8990139 0.4234538 0.1289614 -0.9015988 0.4129028 0.1870299 -0.9276055 0.3233695 0.1738263 -0.931028 0.3208917 -0.08192014 -0.8924486 0.4436494 -0.04641705 -0.9263669 0.373751 -0.08995801 -0.8879604 0.4510366 -0.0664491 -0.9014669 0.4277172 -0.04723519 -0.9169709 0.3961483 -0.05865061 -0.9253933 0.3744429 -0.05359846 -0.9174775 0.3941602 -0.08283346 -0.8914076 0.4455685 -0.04208713 -0.9245254 0.3787896 -0.03797465 -0.9265142 0.3743387 0.02040016 -0.9550077 0.2958788 -0.01413607 -0.9423821 0.3342396 0.07852154 -0.9843704 0.1576367 0.02388465 -0.9820424 0.1871425 0.02637052 -0.9363914 0.3499653 -0.3020145 -0.9034084 0.3043693 0.1470289 -0.9428227 0.2991119 -0.01267695 -0.9177851 0.3968752 -0.2382262 -0.9140974 0.3281375 -0.198631 -0.9185401 0.3418039 -0.1964573 -0.9354895 0.2937071 -0.2894595 -0.8795216 0.377697 -0.2020874 -0.9082888 0.3662952 -0.08403414 -0.9830604 0.1628823 -0.01805895 -0.9808153 0.194101 -0.02348834 -0.8871639 0.4608563 -0.06641685 -0.9215563 0.3825216 -0.0663827 -0.9215551 0.3825306 -0.01261538 -0.9177694 0.3969134 0.07520931 -0.874405 0.4793325 0.03647702 -0.9118152 0.4089776 -0.2383461 -0.9141189 0.3279905 -0.1593974 -0.8847599 0.4379411 -0.03556388 -0.9547372 0.2953172 -0.069579 -0.9627901 0.2611398 0.03961765 -0.9099979 0.4127156 0.03675901 -0.911978 0.4085891 0.03617984 -0.911889 0.4088393 -0.02997368 -0.9045197 0.4253771 0.1113318 -0.9646804 0.2387408 0.03068739 -0.9945836 0.099307 0.07339376 -0.9848051 0.1573927 0.3346319 -0.8170282 0.4695597 0.4395611 -0.742166 0.5059405 0.5324391 -0.607102 0.5898608 0.618855 -0.2743315 0.736044 0.6836488 -0.1537115 0.7134404 0.4615938 -0.5173051 0.7206433 0.4979136 -0.3773652 0.7808185 0.5889124 -0.183072 0.7871893 0.5467312 -0.1886423 0.8157814 0.537817 -0.2401406 0.8081371 0.5049747 -0.2435205 0.828069 0.5114006 -0.2134108 0.8324214 0.1737343 -0.9687714 0.1769133 0.2711462 -0.9060146 0.3249883 0.3503934 -0.800818 0.4857108 0.3917304 -0.796499 0.4605831 0.4149928 -0.7318216 0.5405721 0.4539654 -0.727114 0.5149958 0.5012523 -0.6120994 0.6116213 0.530598 -0.6102576 0.5882615 0.6705515 -0.1689913 0.7223591 0.6236382 -0.4151268 0.6623784 0.6729151 -0.2219817 0.7056271 0.4265741 -0.6637815 0.6143523 0.4541739 -0.5336148 0.7134293 0.5024377 -0.5286666 0.6841549 0.5079699 -0.4397255 0.7406809 0.5612059 -0.4331182 0.7053061 0.5777343 -0.2854905 0.7646688 0.612748 -0.2835776 0.7376474 0.3292134 -0.8710913 0.3644428 0.3238895 -0.8912731 0.3173766 0.394185 -0.8124607 0.4295647 0.3857138 -0.811592 0.4387978 0.4210134 -0.7652824 0.4869195 0.2818326 -0.8845421 0.3716931 -0.6103726 -0.7268595 0.3148343 -0.3784338 -0.8846958 0.2722156 -0.1654825 -0.9807173 0.1039674 -0.4826831 -0.8187933 0.3107967 -0.1123719 -0.9928659 0.0398736 -0.1245879 -0.9918174 0.02786129 -0.1132079 -0.9904402 0.0788185 -0.6436085 -0.7521166 0.1417351 -0.6256716 -0.7623248 0.1655169 -0.6321288 -0.7560815 0.1695704 -0.5224582 -0.8185991 0.2386064 -0.4765124 -0.8309773 0.2870761 -0.1662707 -0.9751235 0.1465886 -0.5032948 -0.8640777 -0.008007764 -0.4900076 -0.8695277 0.06175827 -0.2903703 -0.9121626 0.2892138 -0.3075416 -0.9157786 0.2583948 -0.1076254 -0.9140687 0.3910183 -0.1445431 -0.9396932 0.3099744 -0.1445313 -0.9396938 0.3099784 -0.1445428 -0.9396934 0.3099738 -0.144543 -0.9396926 0.3099762 -0.1445452 -0.9396929 0.3099744 -0.144537 -0.9396933 0.3099768 -0.1459332 -0.9402673 0.3075724 -0.1444652 -0.9397583 0.309813 -0.1446235 -0.9395757 0.3102925 -0.14455 -0.9396952 0.3099653 -0.1445529 -0.9396888 0.309983 -0.1445102 -0.9396932 0.3099896 -0.144519 -0.939697 0.3099739 -0.1445466 -0.9396923 0.3099754 -0.1445351 -0.9396958 0.3099702 -0.1445455 -0.939692 0.3099766 0.06951904 -0.9469416 0.3137974 0.02490609 -0.9394012 0.341914 -0.07562261 -0.9369972 0.3410536 0.1445096 -0.9396939 0.3099879 0.1441169 -0.9396578 0.3102798 0.1445426 -0.9396944 0.3099709 0.1445322 -0.9396933 0.3099789 0.1445434 -0.939693 0.3099745 0.1445453 -0.9396921 0.3099767 0.1442748 -0.939771 0.3098632 0.1445386 -0.9397009 0.3099533 0.1445477 -0.9396919 0.309976 0.1445089 -0.9396929 0.3099914 0.1445463 -0.939692 0.3099763 0.14455 -0.9396919 0.3099753 0.1445437 -0.9396924 0.309976 0.1445186 -0.9397014 0.3099606 0.1447159 -0.9396426 0.310047 0.1447018 -0.9396525 0.3100236 0.003624856 0.9996087 -0.02773803 -0.0678386 0.9915318 -0.1107375 -0.06783676 0.991532 -0.110737 -0.03774356 0.9914513 -0.1248999 -0.01674455 0.9916298 -0.1280235 -0.04155987 0.9921844 -0.1176558 0 0.9838476 -0.1790087 0.007755637 0.9867674 -0.1619569 0.04075163 0.9913893 -0.1244454 0.03774398 0.9914515 -0.1248981 0.06783664 0.9915321 -0.1107349 0.06783831 0.9915318 -0.1107379 -0.08075231 0.9916291 -0.1007509 -0.1256681 0.9907984 -0.05026203 -0.1356765 0.9903668 -0.02766919 -0.1390928 0.9898258 -0.02996879 -0.395879 0.9143329 -0.08529549 -0.2948299 0.9553068 -0.02155065 -0.1050751 0.9907994 -0.08529943 -0.1046951 0.9908446 -0.08524125 -0.1330413 0.9890947 -0.06318134 -0.1389177 0.9881114 -0.06586331 -0.3183569 0.9383695 -0.1345796 0 1 -3.97115e-7 -0.009518444 0.9999503 -0.002977609 -0.01211446 0.9998143 0.0149933 0.1901533 0.9711495 0.1439115 0 1 -2.12837e-6 0 1 0 0 1 9.67353e-7 0 0.9999898 0.004533469 0 1 -1.89328e-6 0.003809869 0.9999925 7.02849e-4 -0.001161158 0.9996213 -0.02749264 -0.001111328 0.9999781 0.006529569 0.002546608 0.9998508 0.01709061 -0.003419697 0.9999574 0.008578538 0 1 0 0 1 1.61614e-6 0 1 1.53323e-6 0 1 -1.1771e-6 1.55392e-4 0.999714 0.02391606 -0.001310229 0.9999877 -0.004796624 6.28051e-4 0.9998276 0.01855677 0 1 2.85617e-7 0 1 -1.31027e-7 0 1 -1.59913e-7 0 1 -1.32955e-7 0.4299841 -0.8333615 0.3473072 0.4640656 -0.8525587 0.2403889 0.4506615 -0.859876 0.2398283 0.5236504 -0.8390045 0.1478573 0.5547707 -0.8201895 0.1397101 0.1887726 -0.9809235 0.04641169 0.1858996 -0.9818049 0.0387361 0.3487589 -0.8685496 0.3521206 0.1343371 -0.9816097 0.1356322 0.1695077 -0.9816095 0.08780568 0.2061021 -0.9700976 0.1281901 0.1681683 -0.9837161 0.06342107 0.04584974 -0.9819628 0.1834312 0.05932116 -0.9820405 0.179102 0.08775699 -0.9809224 0.1734654 0.08734524 -0.9816499 0.1695118 0.1343395 -0.9816092 0.1356328 -0.01679825 -0.9819038 0.188634 -0.03289073 -0.9773707 0.2089614 -0.09444892 -0.9778677 0.186693 -0.09411072 -0.9821142 0.1630796 -0.1359056 -0.9811736 0.1372158 -0.1424133 -0.9781005 0.1517827 -0.1690794 -0.9836108 0.06262618 -0.1888176 -0.9809144 0.04642128 -0.1859171 -0.9818059 0.03862643 -0.5243503 -0.8391702 0.1443961 -0.5469057 -0.825792 0.1377028 -0.4600903 -0.8552869 0.2383306 -0.1881208 -0.9772995 0.09744936 -0.1513759 -0.9834441 0.09961491 -0.2330175 -0.8564781 0.4605953 -0.3488439 -0.8288597 0.4373782 -0.3477691 -0.86935 0.3511229 -0.4326369 -0.8278221 0.3571219 -0.4587952 -0.8564645 0.2365922 0.3562927 -0.8399469 0.4093224 0.24636 -0.8379565 0.486966 0.2463623 -0.8379568 0.4869641 0.08484995 -0.837956 0.5391012 0.08486396 -0.8379494 0.5391094 -0.03928703 -0.8403337 0.5406441 -0.0768758 -0.8692474 0.4883637 -0.1395422 -0.8285938 0.5421811 -0.2330433 -0.854832 0.4636304 -0.7765779 0.6296912 0.02039492 -0.7481788 0.6406902 0.1724666 -0.9086311 0.4105502 0.07640701 -0.9667407 0.2077873 0.14912 -0.9691833 0.1874704 0.1598087 -0.2473082 -0.9130085 0.324429 -0.3772496 -0.8535987 0.3592384 -0.4771776 -0.8088361 0.3436363 -0.7036303 -0.6247837 0.338452 -0.703507 -0.6249061 0.3384824 -0.8728992 -0.3820684 0.3034318 -0.8728339 -0.3821779 0.3034816 -0.965727 -0.09916633 0.2398698 -0.9657156 -0.0992096 0.239898 -0.9787985 0.06909835 0.1928187 -0.8386106 0.5245989 0.1467252 -0.9279713 0.2261482 0.2961866 -0.9258829 0.2607836 0.273373 -0.9338315 -0.06701004 0.3513811 -0.8444396 -0.3531607 0.4027395 -0.8590444 -0.326958 0.39388 -0.6805582 -0.6009879 0.4191113 -0.6496556 -0.6292238 0.4266439 -0.3793146 -0.8557502 0.3518697 -0.3130001 -0.8809978 0.3547872 -0.5167817 -0.5580938 0.6492058 -0.5848193 -0.6364659 0.5028893 -0.2415491 -0.9021601 0.3574372 -0.9567236 0.2885125 0.03795486 -0.9892907 -0.03843724 0.1408069 -0.1860704 -0.8930909 0.4095933 -0.6900554 -0.3654732 0.6247023 -0.5504447 -0.4822304 0.6815163 -0.5367425 -0.3906773 0.7478494 -0.5127208 -0.4232143 0.7469987 -0.9889658 0.1386009 0.05231356 -0.9971214 0.07581669 9.45445e-4 -0.9897558 -0.03155654 0.1392397 -0.9891871 -0.03768861 0.1417343 -0.922306 -0.1636313 0.3501092 -0.9056655 -0.2026981 0.3724024 -0.5244188 -0.620743 0.5828062 -0.7407455 -0.4208069 0.523658 -0.6689826 -0.4460433 0.5945652 -0.8689612 -0.3763134 0.321395 -0.8594208 -0.4005321 0.317758 -0.696695 -0.6135774 0.3716704 -0.7101284 -0.5933476 0.3790203 -0.4691395 -0.7943191 0.3859605 -0.5240219 -0.7382715 0.4246838 -0.3334394 -0.8588062 0.3889347 -0.9305653 0.3635243 -0.04356908 -0.9737193 0.227245 0.01517838 -0.9886402 0.126214 0.08161282 -0.9889864 0.1235765 0.08145451 -0.9703436 -0.07670778 0.2292361 -0.9813417 0.03226715 0.1895446 -0.8842697 -0.2610335 0.3872063 -0.9209036 -0.1529074 0.3585472 -0.8037638 -0.3539788 0.4781871 -0.7956781 -0.2807867 0.5367078 -0.7910435 -0.2870706 0.540223 -0.915992 0.3993332 0.03862196 -0.9205572 0.3899394 0.02284288 -0.9800628 0.184793 0.07299685 -0.9465978 0.3111865 0.08435434 -0.9872861 0.05588638 0.1488053 -0.9877209 0.03650546 0.1519045 -0.9744986 -0.1135415 0.1935482 -0.9663833 0.1919605 0.1710399 -0.9341928 -0.2389563 0.264922 -0.9629854 -0.05046105 0.2647885 -0.849577 -0.3748396 0.3710986 -0.8855114 -0.2654587 0.3813152 -0.6965894 -0.5592361 0.4494645 -0.7521837 -0.4594922 0.4723203 -0.5094729 -0.7026693 0.4966822 -0.5801631 -0.6169872 0.5317308 -0.3092896 -0.7999941 0.5141493 -0.4593638 -0.6594436 0.595079 -0.6741978 0.09280073 0.7326973 -0.9752125 -0.04591828 0.2164537 0.1526074 -0.7888615 0.5953223 -0.6550915 -0.5118175 0.555786 -0.4609493 -0.6409178 0.6137998 -0.3389991 -0.6778519 0.6523776 -0.2361196 -0.7373125 0.6329438 0.006587862 -0.7604377 0.6493776 0.2532772 -0.823561 0.5075412 0.2646649 -0.8405606 0.4726631 -0.8513177 -0.3049445 0.4269277 -0.7966789 -0.3835106 0.4671431 -0.6525692 -0.5127948 0.5578486 -0.9024927 -0.2263168 0.3664531 -0.8730513 -0.2642699 0.4098085 -0.8481851 -0.202288 0.4895524 -0.7640318 -0.2037702 0.6121545 -0.4939687 -0.3028774 0.8150216 -0.3940423 -0.3226824 0.8605851 -0.3928976 -0.3173223 0.8630981 -0.1709479 -0.2102319 0.96259 0.2022932 -0.3880847 0.8991484 -0.02638912 -0.1978482 0.9798774 -0.1856755 -0.4207931 0.8879514 0.1353471 -0.2066832 0.9690012 0.4380616 -0.2538207 0.8623673 0.5040267 -0.004760503 0.8636751 0.7066601 -0.1573456 0.6898362 0.6427549 -0.25863 0.7210941 0.6425666 -0.21696 0.7348718 0.6184481 -0.4142405 0.6677775 0.2405057 -0.9009056 0.3612841 0.2862839 -0.8851935 0.3667071 0.01365756 -0.7636001 0.6455451 0.0467503 -0.7677935 0.6389895 0.08386164 -0.7501575 0.65592 0.1211657 -0.7617002 0.6364996 0.1955989 -0.740578 0.6428728 0.217998 -0.7565258 0.6165595 0.3259232 -0.7422064 0.5855798 0.5130072 -0.6034462 0.6104723 0.5496456 -0.4759657 0.6865467 0.4129188 -0.4697712 0.7802649 0.4091577 -0.4615079 0.7871471 0.1850457 -0.4904645 0.8515883 0.1636118 -0.4671829 0.8688909 -0.02671808 -0.5205417 0.8534181 -0.06077647 -0.499763 0.8640273 -0.197157 -0.564068 0.8018457 -0.226894 -0.5521123 0.8023037 -0.6608012 -0.3087578 0.684113 -0.5937272 -0.3878509 0.7050246 -0.5933436 -0.3880802 0.7052214 -0.3131234 -0.6247011 0.7153338 -0.3122485 -0.6248737 0.7155655 -3.65793e-5 -0.7740041 0.6331807 0.001716434 -0.7739468 0.6332485 0.2057078 -0.818476 0.5364527 0.2078028 -0.8627347 0.4609845 0.20552 -0.8629015 0.4616954 0.1949645 -0.882918 0.4271355 0.2216628 -0.8805968 0.4188255 0.2040039 -0.8980161 0.3898069 0.2387287 -0.8898978 0.3887035 0.3290654 -0.7483642 0.5759054 0.3910875 -0.7512536 0.531666 0.4189805 -0.7384363 0.5283629 0.3121779 -0.8456957 0.4328325 0.3405005 -0.8070677 0.4823912 0.4245249 -0.7655032 0.4835116 0.2535901 -0.9004673 0.3533424 0.2036105 -0.9334067 0.2954568 0.2126967 -0.9232848 0.3198522 0.228886 -0.9559077 0.1839885 0.4935133 -0.7956089 0.351356 0.502684 -0.78003 0.3726419 0.6880348 -0.5479093 0.4758189 0.7194221 -0.4987108 0.4834455 0.765595 -0.3632951 0.5309249 0.8191263 -0.1612434 0.550484 0.8203356 -0.1262072 0.5577826 0.6001262 -0.170857 0.7814453 0.6032065 -0.1614968 0.7810639 0.5344678 -0.4633963 0.7068296 0.5154528 -0.4987793 0.6967982 0.4649837 -0.6360325 0.6158351 0.3901768 -0.7535955 0.529014 0.7126991 -0.161131 0.6827129 0.7126939 -0.1611397 0.6827161 0.6260346 -0.498443 0.5996961 0.6260351 -0.4984412 0.5996969 0.4235751 -0.8099065 0.4057531 0.4422991 -0.7951166 0.4149232 0.2564008 -0.9396256 0.2266331 0.2305669 -0.950223 0.2095597 -0.3742768 -0.8285305 0.4164783 -0.4542962 -0.6569669 0.6016723 -0.7000576 -0.1612678 0.695638 -0.6772146 -0.2786986 0.6809608 -0.6306439 -0.4060748 0.6613558 -0.5360246 -0.6137865 0.5796066 -0.5409091 -0.6049907 0.5842977 -0.43393 -0.7464172 0.5045456 -0.2061554 -0.9626923 0.1752809 -0.3889842 -0.7647625 0.5136437 -0.4950132 -0.5081756 0.7047834 -0.4461249 -0.6331821 0.6324976 -0.5339758 -0.1680445 0.8286319 -0.5364716 -0.1350818 0.8330373 -0.5048936 -0.2212659 0.8343403 -0.4422304 -0.7395024 0.5075123 -0.6416545 -0.2327163 0.730837 -0.6302079 -0.2764459 0.7255451 -0.519918 -0.6120191 0.5959178 -0.5246437 -0.604265 0.5996773 -0.2810016 -0.8849113 0.3714433 -0.3782762 -0.8077393 0.4521774 -0.3757096 -0.8219112 0.4281408 -0.385758 -0.8120214 0.4379636 -0.3999912 -0.8134379 0.4222864 -0.3225801 -0.8873488 0.3294757 -0.3021839 -0.889464 0.3428394 -0.2837762 -0.9057086 0.3149019 -0.5551416 -0.3776266 0.7410911 -0.6227191 -0.286198 0.728225 -0.5793744 -0.2888599 0.7621583 -0.3601702 -0.8296663 0.4265342 -0.6028319 -0.1594527 0.7817727 -0.04400324 -0.9957531 -0.08086657 -0.04396897 -0.9957547 -0.08086782 -0.4975461 -0.4631686 0.7334321 -0.5305389 -0.3417794 0.7757033 -0.5759035 -0.3361458 0.7452121 -0.5430597 -0.5023609 0.6728446 -0.5020142 -0.6130749 0.6100171 -0.4878815 -0.6529184 0.5793697 -0.4200276 -0.7792899 0.4650636 -0.3836211 -0.7833831 0.4890254 -0.3269385 -0.8623387 0.3866307 -0.5616309 0.6982027 0.4439413 -0.3853486 0.7170819 0.5807754 -0.3853578 0.7170685 0.5807858 -0.497606 0.3642908 0.7871978 -0.5001224 0.3331816 0.799292 -0.5111516 -0.115633 0.8516767 -0.5111442 -0.1156036 0.8516851 -0.4170919 -0.5425931 0.7291277 -0.4088981 -0.5708335 0.7120053 -0.32871 -0.7311458 0.597809 -0.2699556 -0.8648399 0.4232918 -0.2977242 -0.8724063 0.3876438 -0.297709 -0.8724067 0.3876545 -0.6077287 -0.6053888 0.5139751 -0.6983947 0.6627627 0.2701679 -0.8432629 0.3040153 0.4432634 -0.843263 0.3039904 0.4432802 -0.8469972 -0.05046021 0.5291972 -0.8194714 -0.1687898 0.5477012 -0.7861061 -0.2865178 0.5476723 -0.6077157 -0.605396 0.5139818 -0.2337519 -0.8613148 0.4511065 -0.2337616 -0.86131 0.4511106 -0.2699725 -0.8648364 0.4232882 -0.5200551 -0.5813478 0.6257616 -0.5200685 -0.5813323 0.6257647 -0.6863893 -0.1328916 0.7149893 -0.6863924 -0.132915 0.7149819 -0.6907594 0.3440433 0.6359919 -0.6907555 0.3440617 0.6359862 -0.5616497 0.6981774 0.4439572 -0.6984193 0.6627389 0.2701626 0 0.6934916 0.7204648 0.206628 0.6935038 0.6901865 0.206628 0.6935002 0.6901901 0.2702606 0.3218538 0.9073971 0.2847617 0.1191709 0.951162 0.2849001 -0.1150215 0.9516312 0.1549945 -0.8413851 0.5177335 -0.1998431 0.7172879 0.6675034 -0.2038011 0.6937103 0.6908192 0 0.6935033 0.7204536 0 0.3217898 0.9468111 0 0.3217858 0.9468125 -0.1467748 -0.8591263 0.4902644 -0.1521021 -0.8415855 0.5182653 -0.1965377 -0.7283259 0.6564407 -0.2431321 -0.5304453 0.8121051 -0.2403195 -0.5397827 0.8067721 -0.2860547 -0.1150318 0.9512836 -0.2704943 0.3218348 0.9073342 -0.2705066 0.3322797 0.9035577 0.8426373 0.3074384 0.4420905 0.8473813 -0.04797017 0.5288136 0.8211501 -0.1623942 0.5471203 0.7874969 -0.2827312 0.5476422 0.6135058 -0.5979934 0.515766 0.6134988 -0.597999 0.5157678 0.2736082 -0.8621233 0.4264762 0.2492927 -0.8437179 0.4753877 0.2342787 -0.8582401 0.4566589 0.4116181 -0.5628852 0.7167502 0.5128415 -0.1092124 0.8515082 0.5187831 0.1197279 0.8464806 0.4945592 0.3678228 0.7874755 0.5026873 0.3354842 0.7967157 0.6978302 0.6635786 0.2696229 0.6978418 0.663563 0.2696314 0.5611643 0.6989757 0.4433144 0.3967793 0.6934289 0.6014338 0.5611478 0.6989815 0.4433261 0.6901612 0.3474742 0.6347749 0.6901533 0.3474588 0.634792 0.6875732 -0.1264229 0.7150248 0.6875711 -0.1263888 0.7150328 0.5246656 -0.5735985 0.6290555 0.5246641 -0.5736097 0.6290465 0.2735875 -0.8621293 0.4264777 0.3021894 -0.8699163 0.3897785 0.3021835 -0.8699111 0.3897946 -0.09285205 0.9935795 0.06464171 -0.09118247 0.9900199 0.1074543 -0.09665924 0.9782713 0.1834182 -0.02996855 0.9839091 0.1761387 -0.02996748 0.9839097 0.1761349 0.0263344 0.9839101 0.1767131 0.02633464 0.9839095 0.1767165 0.1001778 0.9935588 0.05296701 0.08978837 0.9885094 0.1216034 0.2522026 0.9279802 0.2743114 0.07476723 0.9903703 0.1165183 0.09852635 0.9901555 0.0994215 0.09852606 0.9901556 0.09942203 0.1245751 0.9901555 0.06382262 0.124574 0.9901556 0.06382095 0.1382516 0.9901554 0.02188348 0.138251 0.9901555 0.0218836 0.4039918 0.9142832 -0.02961307 0.1382369 0.9903475 -0.01013237 0.4039865 0.9142855 -0.02961444 0.4034416 0.9127742 0.06386059 0.4034405 0.9127747 0.06386089 0.3635354 0.9127734 0.1862438 0.3635304 0.912775 0.1862455 0.2875191 0.912774 0.2901319 0.2875207 0.912774 0.2901304 0.1829443 0.9127741 0.3652053 0.06020939 0.9127746 0.4040019 0.06020838 0.9127745 0.4040024 -0.06851452 0.9127764 0.4026726 -0.1904286 0.9127752 0.3613567 -0.1904259 0.9127762 0.3613554 -0.2934252 0.9127773 0.2841472 -0.2934277 0.9127758 0.2841489 -0.3672901 0.9127746 0.1787196 -0.3672931 0.9127733 0.1787199 -0.4046725 0.9127736 0.05553972 -0.4046702 0.9127746 0.05553942 -0.1380276 0.9903611 -0.0115481 -0.4034349 0.9143857 -0.03375196 -0.4034351 0.9143857 -0.03374803 -0.138035 0.9903601 -0.01154714 -0.1386719 0.9901556 0.01903164 -0.1258621 0.9901555 0.06124496 -0.1258636 0.9901555 0.06124216 -0.1005533 0.9901554 0.09737288 -0.1005516 0.9901556 0.09737151 -0.08095544 0.9903932 0.1121056 -0.003241181 0.9999825 0.004942357 0.3004791 0.9129295 -0.276174 0.2789282 0.9539623 -0.1102504 0.3450047 0.9361786 -0.06739139 0.3982734 0.914614 -0.06970971 0.1031114 0.9911711 -0.08335417 0.1050241 0.9900822 -0.09331303 0.1271895 0.9902572 -0.05668854 0.2083975 0.9744155 -0.08417165 0.1367673 0.9890623 -0.05523312 0.1296121 0.9912416 -0.02531796 0.1383045 0.9899102 -0.03081709 0.1367011 0.9903959 -0.0207079 0.1013891 0.9809843 -0.1654999 0.1000058 0.9800484 -0.1717679 0.05480247 0.9818907 -0.1813485 0.05111461 0.980573 -0.1893776 0 0.9812214 -0.1928849 -0.04925769 0.9819719 -0.1824966 -0.104614 0.9797421 -0.1707674 -0.09791195 0.9808834 -0.1681702 0.03283041 0.9978691 -0.05638653 0.03282976 0.997869 -0.05638885 0.01700341 0.9978691 -0.06299316 0.01700252 0.997869 -0.0629962 0 0.997869 -0.06524908 0 0.997869 -0.06525009 -0.01700299 0.9978691 -0.06299489 -0.01700288 0.997869 -0.06299573 -0.03283071 0.9978691 -0.05638724 -0.03282999 0.9978691 -0.05638837 -0.3552221 0.9334568 -0.04975819 -0.5068675 0.8615882 -0.02740913 -0.5361365 0.8441314 -2.01763e-4 -0.2274907 0.9735653 0.02046275 -0.3229876 0.9324497 -0.1619159 -0.1158224 0.9932355 0.008277595 -0.1471285 0.9805424 -0.129961 -0.2266585 0.9663724 -0.121451 -0.2220421 0.9656192 -0.135192 -0.2818089 0.9581651 -0.05003386 -0.2968087 0.9473354 -0.1202518 -0.3672534 0.9300442 -0.01195031 0.09245961 -0.6946079 0.7134222 0.314269 -0.6543627 0.6877824 -0.4270393 -0.7286699 0.5354229 -0.7878589 -0.5763782 0.2169482 -0.5549095 -0.5898781 0.5866169 -0.7153749 -0.5898154 0.3746419 -0.6746781 -0.6935948 0.2524594 -0.6663575 -0.7026725 0.2494376 -0.6023244 -0.7567264 0.2541074 -0.6275749 -0.7081101 0.3236199 -0.6017091 -0.6366457 0.4823158 -0.6775314 -0.556336 0.4810839 -0.6607916 -0.4966902 0.5627197 -0.7527361 -0.3560432 0.5537344 -0.6842566 -0.1473875 0.7141917 -0.5760524 -0.08673739 0.8127977 -0.5760849 -0.08672893 0.8127757 -0.5761505 -0.08671087 0.8127311 -0.4735019 -0.3449689 0.8104274 -0.6046589 -0.1754384 0.7769228 -0.5271067 -0.2104831 0.8233199 -0.5012509 -0.273572 0.8209178 -0.5760293 -0.08676064 0.8128117 -0.6722292 -0.1755425 0.7192307 -0.6548417 -0.262467 0.7087266 -0.6553797 -0.2617094 0.7085095 -0.6427614 -0.3266233 0.6929467 -0.6135341 -0.378637 0.6929719 -0.5960379 -0.4480185 0.666347 -0.4595861 -0.5471947 0.6995418 -0.496792 -0.5223615 0.6930629 -0.4452025 -0.3315173 0.8317999 0.01017713 -0.5172218 0.855791 0.1148422 -0.4454226 0.8879246 0.07816827 -0.4610726 0.8839128 0.009172916 -0.5165426 0.8562125 -0.2144142 -0.5114756 0.8321173 0.4127637 -0.6145676 0.6722595 0.4893034 -0.6283669 0.6047623 0.5669085 -0.5094658 0.647348 0.5090084 -0.255545 0.8219532 0.5361066 -0.1867048 0.8232443 0.5679756 -0.2267889 0.791183 0.4848025 -0.3339043 0.8083777 0.6279317 -0.1336476 0.7667074 0.5903329 -0.1150802 0.7989141 0.5396487 -0.1917008 0.8197746 0.6769582 -0.1954888 0.7095857 0.6332243 -0.4112588 0.6556624 0.5920708 -0.4450157 0.6718729 0.6119225 -0.3813655 0.6929007 0.6456624 -0.3211526 0.6928066 0.6467993 -0.2582701 0.7175983 0.6831235 -0.1876716 0.7057774 0.6335145 -0.1385225 0.7612299 0.5973985 -0.7699145 0.2243814 0.711834 -0.6369185 0.296019 0.6986018 -0.6070898 0.3786788 0.6608024 -0.5754343 0.4818876 0.6462436 -0.5999888 0.4715747 0.6649973 -0.4998323 0.5549291 0.71382 -0.452362 0.5346304 0.7232111 -0.3222826 0.6108189 0.6225335 -0.709021 0.3312723 0.6615957 -0.707764 0.2477122 0.7652665 -0.6010392 0.2304761 0.6456226 -0.7415817 0.1822855 0.6028788 -0.6355233 0.4823353 0.4979805 -0.6516944 0.5721101 0.51947 -0.6671175 0.5339524 0.3064289 -0.734318 0.605705 0.3222807 -0.6502385 0.6879863 0.2631682 -0.6364654 0.7250202 0.2469466 -0.58205 0.7747486 0.1557997 -0.5718308 0.8054416 -0.305403 -0.6544008 0.6917287 -0.3460124 -0.6375151 0.6883677 -0.2656784 -0.6337767 0.7264587 -0.1839641 -0.6748391 0.7146674 -0.08701556 -0.6538049 0.7516433 -0.0535618 -0.6735313 0.7372156 0.1154253 -0.6699949 0.7333375 -0.2803625 -0.4676072 0.8382962 -0.3728435 -0.4788271 0.7948033 -0.444628 -0.5710215 0.6901018 -0.444628 -0.5710214 0.6901019 -0.5036714 -0.6468333 0.5726447 -0.5903065 -0.6435213 0.4872563 0.3243186 -0.6898425 0.6472518 0.1915706 -0.5625513 0.8042616 0.4482519 -0.4025143 0.7981557 0.3505443 -0.27083 0.8965321 0.1021859 -0.2300609 0.9677965 0.3947597 -0.1143013 0.9116469 -0.7044813 -0.4999717 0.5037208 -0.6555824 -0.5573374 0.5094966 -0.8012711 -0.4308697 0.4151095 -0.8783323 -0.352497 0.3229216 -0.8588967 -0.3850886 0.3376438 -0.9108754 -0.2983242 0.2851471 -0.1906466 -0.6985905 0.6896559 -0.235632 -0.7084572 0.6652563 0.1847105 -0.4606183 0.8681665 0.1845702 -0.2802771 0.9420077 0.2132873 -0.2888195 0.9333231 0.2133285 -0.09497761 0.9723529 0.1593857 -0.07414394 0.9844283 -0.3553432 -0.181441 0.9169571 -0.4609077 -0.6493203 0.6049359 -0.4637405 -0.6489385 0.6031779 -0.4596771 -0.4714497 0.7526169 -0.7008982 -0.3961859 0.5931092 -0.622142 -0.4087837 0.667709 -0.8772606 -0.2696515 0.397117 -0.8214285 -0.2952948 0.4879099 -0.9452223 -0.1797077 0.2725068 -0.9465273 -0.0894038 0.3099889 -0.9844992 -0.1275923 0.1203401 -0.9842482 -0.1281276 0.1218152 -0.9835616 -0.08863234 0.1573243 -0.9969172 -0.04403412 0.06494021 -0.9903877 -0.03176099 0.1346237 0.324369 -0.5695161 0.7552723 0.1397873 -0.609313 0.780511 0.1396348 -0.4508417 0.8816144 -0.08733779 -0.4676957 0.879564 -0.08702224 -0.296277 0.9511294 0.1131808 -0.2003534 0.9731643 -0.07751637 -0.1017667 0.9917837 -0.9829538 -0.02229386 0.1824966 -0.8156045 -0.1247637 0.5649985 -0.8210285 -0.1257666 0.5568618 -0.5646201 -0.1499245 0.8116199 -0.6205999 -0.1588866 0.7678613 -0.3644201 -0.1788519 0.9138983 -0.3648993 -0.506985 0.7809064 0.06134843 -0.5148818 0.8550632 -0.1903609 -0.6089314 0.7700424 0.08195501 -0.5993176 0.7963051 0.08221459 -0.7160195 0.6932221 0.1517323 -0.6879156 0.709753 -0.8807005 0.4727574 -0.02944731 -0.5688216 0.8224201 0.008195757 -0.988629 0.1503559 -0.002428531 -0.78952 0.6098557 -0.068807 -0.7849123 0.6192191 -0.02191871 -0.8656273 0.489795 -0.1038762 -0.7894989 0.6110522 -0.05750513 -0.7975094 0.5995233 -0.06745982 -0.7424793 0.6698358 -0.006682336 -0.9744307 0.2186492 -0.05174261 -0.8100966 0.2185236 -0.5440506 -0.9142651 0.2333486 -0.3311613 -0.9543224 0.2670195 -0.1340495 -0.9488825 0.3057212 -0.07846373 -0.9364359 0.3495165 -0.03043097 -0.4874429 -0.3498643 0.7999966 -0.511413 -0.2212901 0.8303537 -0.674172 -0.4114567 0.6133478 -0.9896917 -0.06041884 0.129846 -0.9902207 -0.05185061 0.1295171 -0.9076551 -0.1913247 0.3735737 -0.6551252 -0.590167 0.471714 -0.7912368 -0.2708399 0.5482611 -0.905662 -0.1743876 0.3864781 -0.9865352 0.06836372 0.1485761 -0.8837977 -0.3371571 0.3243868 -0.8588312 -0.4612526 0.2228342 -0.7314141 -0.1197767 0.6713323 -0.7429937 -0.2799179 0.6079527 -0.5171281 -0.3827508 0.7655591 -0.5128936 -0.3622295 0.7782865 -0.9832724 -0.132673 0.1247931 0.4054846 -0.8289476 0.3852639 -0.8599395 -0.4836742 0.1629825 -0.8046325 -0.5596024 0.1985242 -0.556348 -0.7831471 0.277773 -0.4502165 -0.8475255 0.2810793 -0.6356382 -0.7275419 0.2581607 0.729277 -0.656906 0.191389 0.5944358 -0.7736704 0.2192719 0.7281992 -0.644526 0.2330499 0.3968712 -0.8654699 0.3057045 0.2931503 -0.9037697 0.3118705 0.1272326 -0.9324659 0.3381116 -0.1452113 -0.9350315 0.3234654 -0.1626263 -0.9318976 0.3242217 -0.3027625 -0.8982309 0.3186161 0.7802382 -0.2918778 0.5532051 0.7027302 -0.1889585 0.6859045 0.4470949 -0.2297077 0.8644886 0.5016539 -0.2170256 0.8374027 0.2936417 -0.2190693 0.9304748 -0.145476 -0.2257964 0.9632511 -0.02055525 -0.2392898 0.9707306 0.1970118 -0.2347228 0.9518885 -0.877508 -0.1038513 0.4681823 -0.7899617 -0.121871 0.6009227 -0.8605963 -0.1179834 0.4954332 -0.6144186 -0.1832968 0.7673931 -0.5564536 -0.1860032 0.8097915 -0.4251898 -0.2144427 0.8793339 -0.2337927 -0.2301988 0.9446426 -0.9949715 -0.03973555 0.09194046 -0.9781679 -0.1207466 0.1691386 -0.9667955 -0.2372043 0.09508359 -0.986429 -0.1544138 0.05580705 -0.9892488 -0.1240063 0.07752043 -0.9922775 -0.1040278 0.06755417 -0.8594204 -0.4287928 0.2784483 -0.8594341 -0.4287717 0.2784383 -0.5548104 -0.6977629 0.4531143 -0.5548434 -0.6977393 0.45311 -0.1447578 -0.8298415 0.5388954 -0.1447929 -0.8298414 0.5388863 0.2923011 -0.8020495 0.5208424 0.2922869 -0.8020535 0.5208441 0.8040176 -0.4986811 0.3238409 0.7701898 -0.54117 0.3375543 -0.9942479 -0.07109475 0.08010458 -0.8594182 -0.3394017 0.3823701 -0.8594285 -0.3393808 0.3823655 -0.5548469 -0.5522782 0.6222007 -0.5548422 -0.5522709 0.6222114 -0.1446998 -0.6568419 0.740014 -0.1447589 -0.6568338 0.7400096 0.292299 -0.6348353 0.715224 0.2923196 -0.6348333 0.7152175 0.7494537 -0.4394919 0.4951422 0.5084673 -0.6770015 0.5320996 -0.9751307 -0.04657119 0.2166824 -0.988578 -0.04286509 0.1444863 -0.9831382 -0.08068537 0.164101 -0.8594427 -0.2255874 0.4587687 -0.8594442 -0.2255831 0.4587679 -0.5548091 -0.3671197 0.746599 -0.5547932 -0.3671133 0.7466139 -0.144832 -0.4366056 0.8879185 -0.1447585 -0.436612 0.8879274 0.2923055 -0.4219951 0.8581828 0.2923203 -0.421981 0.8581848 0.612976 -0.3486474 0.7090172 0.6319139 -0.5006284 0.5916554 -0.8269433 -0.003605723 0.5622739 -0.2069422 -0.9313893 0.2994813 -0.2156648 -0.9207131 0.3252324 -0.349124 -0.8044502 0.4805961 -0.1516457 -0.8156172 0.5583659 -0.294859 -0.8663245 0.4031626 -0.3692007 -0.7586352 0.5368086 -0.3852702 -0.7153352 0.5829771 -0.6010934 -0.1614711 0.7826966 -0.5835132 -0.04250723 0.8109905 -0.5957382 -0.193764 0.779456 -0.5263327 -0.4992088 0.6883056 -0.5292309 -0.4356593 0.7280905 -0.4731758 -0.6206523 0.6252163 -0.8227313 -0.10339 0.5589489 -0.8202055 -0.1612209 0.5488812 -0.7836945 -0.304561 0.5413553 -0.717191 -0.4988417 0.4866151 -0.7135144 -0.5046244 0.4860571 -0.2307077 -0.9497338 0.211612 -0.231996 -0.9443745 0.2330986 -0.6340036 -0.6710673 0.3843281 -0.4818802 -0.7959761 0.366352 -0.442291 -0.7951227 0.4149202 -0.2581515 -0.9387178 0.2284005 -0.4245193 -0.7651048 0.4841468 -0.4235689 -0.8099091 0.4057546 -0.6260312 -0.4984451 0.599698 -0.6260327 -0.4984406 0.5997 -0.7126917 -0.1611334 0.68272 -0.7126959 -0.1611334 0.6827157 0.5976415 -0.3944809 0.698004 0.04645931 -0.7620154 0.6458902 0.6870589 -0.3680875 0.6264677 0.6662507 0.01072496 0.7456508 -0.4826483 -0.6031989 0.6349817 -0.3549246 -0.7264764 0.5884392 -0.2508977 -0.8202279 0.5140784 -0.2092062 -0.8281452 0.5200082 -0.2753179 -0.8840076 0.3777973 -0.2392445 -0.9010013 0.3618823 -0.2272397 -0.889666 0.3960512 -0.218476 -0.8927161 0.3941144 -0.2008448 -0.8796205 0.4311952 -0.2270347 -0.8751873 0.4272029 -0.1779841 -0.8613169 0.4758728 -0.209331 -0.858273 0.4685596 -0.5639882 -0.1391689 0.8139714 -0.09063112 -0.360403 0.9283834 -0.2169354 -0.1149919 0.9693895 -0.3465251 -0.3312225 0.8776172 -0.5833092 0.08766853 0.8075051 0.2100781 -0.2703464 0.9395638 0.2083407 -0.2597481 0.9429343 -0.00256133 -0.2526235 0.9675614 0.8595165 -0.2277304 0.4575702 0.9972683 -0.04769176 0.05640625 0.9682879 -0.1157712 0.2213951 0.9654327 -0.1265886 0.2278491 0.859821 -0.2929422 0.4182017 0.9065555 -0.2200497 0.3601881 0.8734157 -0.2643278 0.4089936 0.8247574 -0.3520883 0.4425035 0.7006143 -0.4757265 0.5318118 0.6514527 -0.5039347 0.5671503 0.6039391 -0.5491583 0.5776529 -0.1889855 -0.7230182 0.6644768 0.8412932 -0.1986693 0.5027486 0.7354676 -0.2185521 0.6413444 0.5979955 -0.3936952 0.6981443 0.5023005 -0.3070838 0.8083279 0.4266086 -0.3256986 0.8437568 0.4233517 -0.3169963 0.8486971 0.3534982 -0.2803124 0.8924484 -0.3955191 -0.7388032 0.5456506 -0.3811845 -0.7483169 0.5428814 -0.2827076 -0.7516927 0.5958478 -0.2979497 -0.7406162 0.6022571 -0.1697051 -0.7606254 0.6266173 -0.1923364 -0.7329496 0.6525271 -0.07682186 -0.7700458 0.6333466 -0.088279 -0.7405855 0.6661381 -0.02282643 -0.7753702 0.6310945 -0.01983439 -0.7558954 0.6543918 1.56443e-4 -0.774012 0.6331709 -1.92073e-4 -0.7742053 0.6329346 0.02474904 -0.8226429 0.5680196 -0.2299736 -0.7769616 0.5860401 -0.3837854 -0.7550562 0.5316003 0.3593137 -0.6946834 0.6231443 0.3504946 -0.7022646 0.6196597 0.3148554 -0.6284186 0.711306 0.3152662 -0.6277803 0.7116876 0.2329843 -0.5533343 0.7997122 0.2289144 -0.5764945 0.7843802 0.08161598 -0.4990599 0.8627155 0.08878964 -0.5342884 0.8406261 -0.1131518 -0.4984157 0.8595222 -0.3453004 -0.4626494 0.8165313 -0.3336392 -0.4766573 0.8133159 -0.5234569 -0.4696184 0.710951 -0.5798932 -0.3966277 0.7116252 0.3563156 -0.872559 0.3341856 0.7911185 -0.3389235 0.5091784 0.4555168 -0.7206277 0.5226855 0.9194871 0.3927609 0.01680821 0.982191 0.1658355 0.08831405 0.9655065 0.2602499 -0.008205771 0.9615827 0.2739161 0.01813161 0.9888707 0.09181874 0.1170648 0.9870953 0.1488627 0.05901598 0.9893006 -0.03845888 0.1407313 0.9958298 0.09103584 0.005949318 0.9869819 -0.03646808 0.1566423 0.9878337 -0.02899515 0.1527873 0.915318 -0.1768668 0.3618165 0.9057102 -0.1978793 0.3748772 0.784608 -0.3014552 0.5417705 0.7383794 -0.3565401 0.5724291 0.5122076 -0.4391114 0.7381224 0.5220531 -0.4277541 0.7378936 0.5373473 -0.5086607 0.6726978 0.5057291 -0.6018389 0.6180843 0.4885841 -0.5829108 0.6492308 0.9520848 0.305823 0.002625405 0.9543358 0.2842527 0.0918889 0.9850344 0.1040313 0.1374219 0.9662982 -0.1000704 0.2371788 0.9360092 -0.2452596 0.2524575 0.8443111 -0.4160768 0.3376666 0.8754381 -0.3863663 0.290395 0.6953612 -0.6191261 0.3649051 0.6988441 -0.6170957 0.3616766 0.5680599 -0.7336014 0.3730107 0.4090663 -0.8057878 0.4282183 0.4065208 -0.8001033 0.4411073 0.6770628 -0.5788214 0.4544797 0.7340343 -0.540835 0.4107203 0.8331277 -0.3923663 0.3898037 0.8752073 -0.3453444 0.3387473 0.9548566 -0.1030372 0.278626 0.4365819 -0.6690456 0.6014768 0.5107609 -0.6725247 0.5355688 0.714094 -0.483914 0.5058627 0.7184742 -0.4813705 0.5020731 0.8565567 -0.2935186 0.4244496 0.9187526 -0.2017441 0.3394011 0.953474 -0.09945231 0.284599 0.9820581 -7.80678e-4 0.1885771 0.9862246 0.1189565 0.1149372 0.9870841 0.1480053 0.06131464 0.9670711 0.2540218 -0.01569855 0.4955622 0.8678127 -0.03632247 -0.5677222 0.8218489 -0.04749715 -0.5861642 0.7919088 0.1711497 0.586165 0.7919082 0.1711497 0.6104615 0.7870543 -0.08878374 0.7108201 0.7033389 0.007008016 0.5637431 0.8249926 -0.03976422 0.6728433 0.739672 0.01293224 0.5614126 0.8232218 0.08439075 0.5721493 0.8173799 0.06734406 0.3899995 0.9187433 0.06173533 0.5567443 0.8102536 0.1830976 0.4723579 0.8475354 0.2419958 0.5101624 0.7719913 0.3791624 0.3360193 0.8787042 0.3390722 0.3667538 0.7522067 0.5474274 0.2003915 0.8943247 0.4000334 0.1859382 0.7613891 0.6210585 0.06556475 0.8956225 0.4399564 -0.07490694 0.8947489 0.4402426 -0.1842054 0.7664569 0.6153149 -0.2110882 0.8916244 0.4005593 -0.3629043 0.759 0.5405735 -0.344475 0.8775315 0.3335799 -0.50905 0.7733951 0.3777939 -0.4757538 0.848568 0.2314969 -0.5537288 0.812047 0.1842937 -0.4207249 0.9053487 0.05774414 -0.5712071 0.8184782 0.06177294 -0.5512676 0.8294167 0.09039926 -0.6809104 0.7323305 0.007296562 -0.5440387 0.8337715 -0.09405833 0.9122205 0.4054318 0.05898129 0.7820225 0.6169217 0.08859264 0.9224067 0.266288 0.2797439 0.932493 0.2228758 0.2842239 0.9296107 -0.09287029 0.3566499 0.9321293 -0.06557744 0.3561385 0.8583116 -0.3218829 0.3996155 0.846046 -0.3546947 0.3979923 0.658864 -0.6236565 0.4206552 0.676833 -0.5973066 0.430258 0.5734122 -0.7429521 0.3452835 0.7034904 -0.6248434 0.3386327 0.7036127 -0.6246876 0.3386662 0.8727809 -0.3821213 0.3037051 0.872838 -0.3819761 0.3037237 0.9656514 -0.09913939 0.2401853 0.965662 -0.09903967 0.2401836 0.9699144 0.1864603 0.1565204 0.9699129 0.1864731 0.1565145 0.9236745 0.3721103 0.09143084 0.7685797 0.63621 0.06724762 0.3806697 -0.857135 0.3470019 0.3745042 -0.8507069 0.368842 0.3270959 -0.8834066 0.335561 0.313084 0.9497097 0.005475461 0.3562812 0.9330521 -0.04977577 0.4910579 0.8706154 -0.02985203 0.5511617 0.8341404 -0.02075815 0.3682855 0.9295838 -0.01548498 0.2502296 0.9638831 -0.09118473 0.228894 0.9656494 -0.1229993 0.1528105 0.9802558 -0.1254896 0.317236 0.9483467 -1.73258e-5 0.2984352 0.9542995 -0.01577627 0.2392556 0.9709552 -0.001734018 0.2026114 0.9787535 -0.03146964 0.0444113 0.9978873 -0.04741895 -0.1484022 0.9889272 0 -0.3220126 0.9467273 -0.003931283 -0.3382815 0.941035 -0.004340589 -0.1736459 0.9848082 -2.43979e-4 -0.3347383 0.9423112 3.81648e-6 -0.4629926 0.8863623 -4.94222e-5 -0.6401031 0.7682781 0.004092752 -0.63929 0.7683206 -0.0314939 -0.658837 0.7487437 -0.07291513 -0.5685983 0.8226144 0.001219868 -0.8026296 0.5964775 -6.39622e-4 -0.9066476 0.4218705 -0.003935337 -0.8153518 0.5789602 0.002589583 -0.9757561 0.2188553 -0.001584172 -0.9888049 0.1492143 0 0.0162875 -0.04227387 0.9989733 0.06641888 -0.717265 0.6936279 -0.2824155 -0.5099641 0.8125136 -0.2840346 -0.665869 0.6898861 -0.1888867 -0.7175534 0.6704021 -0.3553202 -0.6673414 0.6545251 0.4167389 -0.646537 0.6389982 0.3572885 -0.6446201 0.6758771 0.0466932 -0.7226807 0.689603 0.915029 -0.2968817 0.2730993 0.8290254 -0.39199 0.3988243 0.7132773 -0.5081241 0.4827478 0.7035474 -0.5123106 0.4925028 0.6049884 -0.5647097 0.5613305 -0.3961257 -0.04982042 0.9168437 -0.402056 -0.05685222 0.9138484 -0.3990034 -0.2298339 0.8876783 0.3008753 -0.04880368 0.9524139 0.5738722 -0.04438948 0.817741 0.6206219 -0.002091646 0.7841072 0.8241057 -0.08663535 0.5597716 0.8612717 -0.02185696 0.5076745 0.9840447 -0.01394075 0.1773748 0.9753983 -0.04894667 0.2149474 0.6203459 -0.1639462 0.7670024 0.3196664 -0.1862192 0.9290511 0.2998191 -0.1985222 0.9331117 -0.03774136 -0.1966401 0.9797491 0.9972317 -0.04608058 0.05835777 0.9837446 -0.1163058 0.1368201 0.9908853 -0.04632461 0.126493 0.886211 -0.1303016 0.4445801 0.8568868 -0.1577643 0.4907704 0.6606665 -0.2147001 0.7193217 0.324293 -0.3514503 0.8782464 0.355232 -0.3488718 0.8672363 0.3197697 -0.3715792 0.8715941 -9.68337e-5 -0.3739256 0.9274588 -0.03762114 -0.3910159 0.9196147 0.9686128 -0.1561771 0.1933856 0.7823288 -0.4043963 0.4737357 0.8883716 -0.2648921 0.3750044 0.7131315 -0.3816521 0.588035 0.6647211 -0.4256886 0.6139504 0.4159834 -0.4970337 0.7615218 0.3546524 -0.5312239 0.7694303 0.06630074 -0.5465085 0.834825 1.03653e-4 -0.567129 0.8236292 -0.2174505 -0.5391399 0.8136606 -0.4026048 -0.3384066 0.8505236 -0.2606421 -0.194007 0.9457415 -0.05828154 -0.2072193 0.976557 -0.05866521 -0.1508228 0.9868186 0.3636677 0.02475422 0.9311999 0.6187798 -0.1824874 0.7640746 0.9832783 -0.1081536 0.1465153 0.1452081 -0.9352418 0.3228585 0.03305113 -0.9415447 0.3352632 -0.2932935 -0.9017083 0.3176496 -0.2105364 -0.9259862 0.3134073 -0.3893789 -0.8685271 0.3066676 0.5559634 -0.7861108 0.2700642 0.4708082 -0.8314815 0.2949206 0.266431 -0.9083941 0.3222342 0.9637794 -0.2484978 0.09684073 0.8103616 -0.5565278 0.183279 0.8603208 -0.4804273 0.170405 0.6703919 -0.6992936 0.2481194 0.5926856 -0.7608345 0.2643004 0.9949698 -0.08659029 0.05037122 0.978164 -0.1536359 0.1399692 0.9892538 -0.06224906 0.1322956 0.8995705 -0.09603166 0.4260879 0.9270579 -0.08459675 0.3652495 0.9864212 -0.03697425 0.1600197 0.9797575 -0.04174673 0.1957871 0.9990773 -0.009654581 0.04185146 0.8605816 -0.1180197 0.4954501 0.7847608 -0.1220784 0.6076573 0.8689479 -0.1062452 0.4833648 0.00240159 -0.2130337 0.9770419 0.2145354 -0.2314522 0.9488965 0.5569334 -0.196536 0.8069689 0.3804255 -0.1839683 0.9063289 0.4643738 -0.1884937 0.8653481 0.1455485 -0.2367708 0.9606015 -0.2938482 -0.2288635 0.928049 -0.2226903 -0.219947 0.9497538 -0.6627928 -0.1974352 0.7223054 -0.5625227 -0.1670955 0.8097205 -0.6100229 -0.7460917 0.2668695 -0.5742323 -0.769312 0.2800295 -0.6737149 -0.6237918 0.3962223 0.9922766 -0.05473566 0.111316 0.8594537 -0.2255784 0.4587522 0.8594249 -0.2255986 0.4587966 0.5547912 -0.3671219 0.7466111 0.5548002 -0.3671185 0.7466062 0.1449002 -0.4365996 0.8879104 0.1447596 -0.4366118 0.8879272 -0.2922967 -0.421988 0.8581892 -0.2923855 -0.4219756 0.8581652 -0.8038492 -0.2624756 0.5337913 -0.4280771 -0.3138568 0.8474928 0.9942476 -0.07109999 0.08010369 0.8594161 -0.3394004 0.382376 0.8594245 -0.3393912 0.3823652 0.5548408 -0.5522766 0.6222077 0.5548485 -0.5522738 0.6222032 0.144817 -0.6568313 0.7400005 0.1447599 -0.6568352 0.7400082 -0.2923283 -0.63483 0.7152168 -0.2922561 -0.6348473 0.715231 -0.7896921 -0.4072619 0.4588294 -0.4133532 -0.4924693 0.7659066 0.9997907 -0.01935034 0.006641685 0.9902547 -0.132273 0.04358583 0.9831345 -0.1533808 0.0996046 0.8594279 -0.4287802 0.2784443 0.8594242 -0.4287854 0.2784478 0.55484 -0.6977444 0.4531064 0.5548236 -0.6977535 0.4531123 0.1447902 -0.8298402 0.5388889 0.1447599 -0.8298434 0.5388922 -0.2922891 -0.8020533 0.5208433 -0.2922894 -0.8020519 0.5208454 -0.7256661 -0.5770494 0.3747301 -0.5151255 -0.6077497 0.604389 0.8780498 -0.4764782 0.04469019 0.9899584 -0.05958557 0.1281873 0.9001975 -0.05889588 0.4314808 0.7299729 -0.4467207 0.5172816 0.6732221 -0.5957429 0.4380212 0.5077196 -0.1820539 0.8420673 0.4662405 -0.3563517 0.8097118 0.9896451 -0.05381226 0.133067 0.9057238 -0.1934831 0.3771325 0.9077671 -0.1722038 0.3824983 0.7398357 -0.3029038 0.6007432 0.742994 -0.2798137 0.6080003 0.5129666 -0.384243 0.7676085 0.5172047 -0.3606555 0.7761617 0.7893276 0.6124364 -0.04340261 0.873867 0.4785767 -0.08556276 0.9443583 0.3237564 -0.05804681 0.9468643 0.3140306 -0.0695194 0.9488149 0.3060656 -0.07793861 0.9532099 0.2781808 -0.1183483 0.9911236 0.1293721 -0.03061151 0.9762429 0.2162479 -0.01366627 0.809779 0.2186387 -0.5444771 0.9319413 0.2349149 -0.2762255 0.6964294 0.7175897 0.007149338 0.7860813 0.6157656 -0.05393642 0.7895015 0.6110117 -0.05789774 0.8882848 0.4585677 -0.02580195 0.937561 0.34597 -0.03583443 0.9932803 0.1157337 0 0.9999659 0.00550884 0.006156861 0.9998471 0.01658284 0.00557208 0.99944 0.0331279 0.004739463 0.9977998 0.06622028 0.003246545 0.9955946 0.09373503 0.002293229 0.9944992 0.1047275 0.001941144 0.9926277 0.1211947 0.001456737 0.9904854 0.1376141 0.00105983 0.988904 0.1485536 8.24497e-4 0.9863088 0.1649085 5.15668e-4 0.980303 0.1974998 7.395e-5 0.9706253 0.2405966 -4.42543e-5 0.9621216 0.272621 2.20085e-4 0.9558632 0.2938119 5.14093e-4 0.9491417 0.3148481 9.25626e-4 0.9419557 0.3357341 0.001453816 0.9566351 0.2912889 8.39385e-5 0.9334357 0.358745 -1.46758e-5 0.9234102 0.3838147 1.20719e-4 0.9073573 0.42036 5.76045e-4 0.9071123 0.4208886 5.62332e-4 0.8830749 0.469232 -3.37136e-5 0.8633555 0.5045963 2.31903e-5 0.8494186 0.5277196 2.29356e-4 0.8118921 0.5838063 0.001162946 0.7749444 0.6320197 0.003509402 0.7663504 0.6424099 0.00407195 0.757596 0.652707 0.004674494 0.748717 0.6628684 0.005321145 0.7351398 0.6778858 0.006346583 0.7165645 0.6974763 0.007882356 0.6974936 0.7165911 4.24465e-6 0.7325406 0.6807234 7.15449e-6 0.8179278 0.5753167 -0.002180159 0.6031642 0.7967897 -0.0363211 0.6779009 0.7351533 1.56805e-4 0.6628865 0.7487199 3.86912e-4 0.534741 0.8450119 0.00265336 0.6573341 0.7534056 0.01709067 0.6345157 0.7727759 0.0144025 0.6161556 0.7875263 0.01244008 0.5946815 0.8038945 0.01037418 0.572768 0.8196736 0.008489847 0.5504473 0.8348424 0.006791472 0.5334311 0.8458246 0.005658924 0.5219813 0.8529427 0.004951834 0.5045899 0.8633502 0.003958046 0.489938 0.8717514 0.003240466 0.4841046 0.875005 0.002978622 0.475158 0.8798967 0.002585053 0.4632672 0.8862162 0.002111673 0.4542982 0.8908479 0.001797258 0.4546614 0.8906626 0.001807212 0.4313274 0.9021948 0.001078307 0.4086011 0.9127131 5.54155e-4 0.3931498 0.9194744 3.19537e-4 0.3869148 0.9221155 2.39129e-4 0.3775852 0.9259749 1.33477e-4 0.1758274 0.9844211 4.77005e-6 0.1151642 0.993306 -0.008967936 0.2409917 0.9705268 -8.61128e-4 0.3675292 0.9300121 6.02321e-5 0.3496669 0.9368741 -1.04525e-6 0.3338743 0.9426177 4.06066e-6 0.3177547 0.9481729 -1.21704e-4 0.2911013 -0.9091108 0.2979561 0.1258959 -0.9671635 0.220783 0.1033619 -0.9844012 0.1423754 0.03920972 -0.9983744 0.04136854 0.1271985 -0.9841626 0.1234683 0.1267997 -0.9842783 0.1229556 0.211517 -0.9525031 0.2190856 0.3463289 -0.8709469 0.3485798 0.3850626 -0.8404107 0.3813618 0.4337591 -0.7832958 0.44531 0.5632388 -0.1755021 0.8074412 0.6714442 -0.1752517 0.7200344 0.709887 0.02588891 0.7038397 0.6965611 -0.06472849 0.7145718 0.6724151 -0.2237067 0.7055589 0.5811294 -0.5375509 0.6110056 0.6575081 -0.394563 0.6418748 0.5611877 -0.5905207 0.5799602 0.4760829 -0.1756395 0.8616819 0.5352871 -0.008859574 0.8446238 0.4515659 -0.5370526 0.7125046 0.4515566 -0.5370559 0.712508 0.28972 -0.8408824 0.4571424 0.2897267 -0.8408753 0.4571511 0.1061245 -0.9801528 0.1674463 0.06633239 -0.9909009 0.1171135 0.03653901 -0.9840939 0.1738511 -0.02496695 -0.9838009 0.1775174 0.1817737 -0.9643663 0.1922393 0.04065752 -0.987457 0.1525637 0.1408259 -0.8372286 0.5284094 0.1408352 -0.8372243 0.5284137 0.2181469 -0.5314441 0.8185225 0.2181433 -0.5314445 0.8185233 0.2536765 -0.1724091 0.9518001 -0.1921326 -0.04921495 0.9801342 0.006403803 -0.1755579 0.9844483 0.253678 -0.1724014 0.951801 -0.009510397 -0.9627422 0.270254 -0.1192793 -0.7902777 0.6010273 -0.07617175 -0.8372255 0.5415269 -0.1113391 -0.6010398 0.7914258 -0.1435623 -0.5289261 0.8364372 -0.126564 -0.4176127 0.8997673 -0.1371969 -0.1723724 0.9754306 -0.3779719 -0.7789664 0.5003485 -0.4441993 -0.4194635 0.7916674 -0.9803159 -0.1702949 0.09990221 -0.94598 -0.3239746 -0.01274096 -0.998453 0.002690374 0.05553793 -0.9719628 -0.01412642 0.2347099 -0.9410669 -0.0861364 0.3270684 -0.9280688 -0.08133929 0.3634176 -0.859533 -0.1218827 0.4963343 -0.9252038 -0.3760648 0.05072891 -0.8929084 -0.442638 0.08237922 -0.8986559 -0.4363973 0.04444181 -0.8265225 -0.535092 0.1747488 -0.7837843 -0.6200469 0.03498995 -0.6726166 -0.7204345 0.1690005 -0.7167778 -0.6912376 0.09176218 -0.8600863 -0.09805089 0.5006372 -0.7992349 -0.1527114 0.5812941 -0.7759866 -0.1614465 0.6097376 -0.7106288 -0.205588 0.6728599 -0.6826373 -0.1850576 0.7069371 -0.5895543 -0.2195806 0.7773097 -0.5729716 -0.222517 0.7887901 -0.457854 -0.2536042 0.8520883 -0.3412085 -0.1757588 0.9234099 -0.9991934 -0.02635002 0.03030252 -0.9819276 -0.1315127 0.1360974 -0.9809306 -0.1645393 0.1034507 -0.9404112 -0.2583029 0.2211482 -0.9435328 -0.2615058 0.2033733 -0.876677 -0.355208 0.3244453 -0.8803781 -0.3812622 0.2820879 -0.7875387 -0.4675222 0.4015045 -0.8044242 -0.4592464 0.3768215 -0.6829842 -0.5381509 0.4938889 -0.7025839 -0.5587868 0.4406055 -0.5385304 -0.6272404 0.5626318 -0.5831433 -0.6167455 0.5287428 -0.3849257 -0.6655409 0.6394431 -0.2870574 -0.6086019 0.739731 -0.6921328 -0.7118148 0.1194651 -0.5252064 -0.829149 0.1914954 -0.5455643 -0.8307829 0.11027 -0.3659257 -0.9013845 0.231526 -0.4632999 -0.8728341 0.1533429 -0.225986 -0.9293134 0.2920741 -0.2903583 -0.9425479 0.1652138 -0.680603 0.05360144 0.7306891 -0.5825799 -0.5533838 0.5952873 -0.6339432 -0.3947116 0.6650706 -0.6687228 -0.2477495 0.7010207 -0.2893381 -0.9097153 0.2978281 -0.3436934 -0.8715451 0.3496914 -0.394784 -0.8296853 0.3946745 -0.4335357 -0.7832283 0.4456458 -0.5609238 -0.5903322 0.5804072 -0.4942082 -0.8680304 0.04776465 -0.1702753 -0.9696594 0.1754053 -0.06913399 -0.9967521 0.04130303 -0.1346437 -0.9806337 0.1422277 -0.02845627 -0.9989319 0.03640615 -0.07116943 -0.9788396 0.1918543 -0.1014045 -0.9762548 0.1914253 -0.4031405 -0.8290323 0.3875349 -0.2686088 -0.8783122 0.395496 -0.4840546 -0.5551562 0.6763821 -0.3706606 -0.6905753 0.6210609 -0.4259791 -0.5900788 0.6858199 -0.3896284 -0.5032248 0.7713329 -0.6992373 -0.07192516 0.7112622 -0.6690618 -0.1944463 0.7173194 -0.5312725 -0.1942327 0.8246352 -0.5715407 -0.01565581 0.8204244 -0.4702748 -0.2331684 0.8511605 -0.1083933 -0.7117439 0.6940257 -0.3440243 -0.5136831 0.785988 -0.3767488 -0.503254 0.7776862 0.1602561 -0.6439684 0.7480793 0.1404169 -0.6648294 0.7336791 0.1060658 -0.8359374 0.5384783 0.1020187 -0.9411066 0.3223516 0.1827847 -0.2308862 0.9556576 0.1827617 -0.2308744 0.9556648 0.1655403 -0.4728291 0.8654646 -0.08724486 -0.6371859 0.7657563 -0.1610916 -0.6399427 0.7513474 -0.204185 -0.2265524 0.9523563 -0.2041787 -0.2265431 0.9523599 0.8060854 -0.4529783 0.3808373 0.1365418 -0.9884619 -0.06556934 0.9876116 -0.1425783 0.06553548 0.9434431 -0.3315138 -0.003736674 0.9218249 -0.3830168 0.05947279 0.886183 -0.457814 0.07131689 0.999297 -0.02471941 0.02818739 0.9990902 -0.03739041 0.02051335 0.9803954 -0.1663129 0.1056635 0.9451193 -0.2498914 0.2104853 0.9396022 -0.2684926 0.2122719 0.9320351 -0.1024888 0.3475726 0.9731745 -0.0103988 0.2298334 0.9984531 0.002693951 0.05553585 0.8660969 -0.11679 0.4860415 0.9357606 -0.06798917 0.3460198 0.2404307 -0.9280189 0.2845594 0.3566421 -0.9079976 0.2198792 0.4726858 -0.8661135 0.1625287 0.4902184 -0.8585287 0.1503811 0.6485519 -0.7431087 0.1648333 0.659887 -0.7355504 0.1533452 0.7307489 -0.6746836 0.1039628 0.7866711 -0.4731069 0.3966339 0.7160863 -0.5198845 0.4657687 0.5856301 -0.6115199 0.5320534 0.5370602 -0.6319094 0.5587997 0.2168118 -0.9353263 0.2795663 0.3405491 -0.8261745 0.4488453 0.3781937 -0.6665228 0.6424305 0.3863158 -0.6614827 0.642807 0.4354923 -0.4712753 0.766972 0.8651399 -0.488938 0.1116819 0.7536891 -0.652886 0.07545131 0.8884283 -0.3415905 0.3066127 0.872524 -0.3901581 0.2940723 0.855102 -0.1030039 0.5081248 0.7775987 -0.169716 0.6054229 0.6876252 -0.219613 0.6920562 0.7024356 -0.1768057 0.6894374 0.5731338 -0.2250212 0.7879614 0.589189 -0.2175608 0.778154 0.4282703 -0.2605417 0.8652761 0.4564726 -0.2309517 0.8592404 -0.1404777 -0.9900838 0 -0.25789 -0.9624629 0.08460432 -0.3368297 -0.9408923 0.03560155 -0.7469209 -0.6648887 0.005680143 -0.665782 -0.744493 0.0496447 -0.7069244 -0.7069181 0.02290749 -0.5439335 -0.8391284 4.34345e-4 -0.4114282 -0.9114418 -9.27611e-4 -0.999999 -0.001490771 0 -0.9979828 -0.0634855 7.24593e-5 -0.9620342 -0.2727498 0.009898662 -0.9659071 -0.2588153 0.00617963 -0.8779001 -0.4788438 6.17033e-6 -0.8528986 -0.5220767 -5.63434e-6 0.864885 -0.5019702 -2.03108e-4 0.9999989 -0.001510381 0 0.9709382 -0.2393283 0.001028835 0.9621356 -0.2723857 0.01005905 0.997983 -0.06348198 7.3627e-5 0.748174 -0.6634877 0.00443834 0.6787397 -0.7319247 0.05998933 0.7539802 -0.6568034 0.01110768 0.3291857 -0.9358586 0.1257197 0.3747248 -0.9244961 0.06991684 0.4487716 -0.8936423 -0.002783834 -0.08664906 -0.995081 -0.04802131 -0.9850078 -0.1722895 -0.008721947 -0.3434565 -0.9391606 -0.003893494 -0.1945011 -0.9778169 -0.077739 -0.5554161 -0.8312456 -0.02332425 -0.6471145 -0.7609815 -0.04636949 -0.8313908 -0.5555177 -0.01377242 -0.8681694 -0.4953573 -0.03005409 -0.9807837 -0.1950858 -0.002262473 -0.9849969 -0.1723679 -0.008400559 -0.8314648 -0.5555775 -6.35018e-5 -0.8037003 -0.5949248 -0.01142287 -0.9118381 -0.4105483 0.001256942 -0.9751651 -0.2212769 -0.009478211 -0.1950799 -0.980737 -0.009933888 -0.226662 -0.9739667 -0.003652989 -0.5555682 -0.8314532 0.005439519 -0.4610908 -0.8870043 -0.02487361 -0.6363372 -0.771411 3.08051e-5 0.5620676 -0.8262003 -0.03838396 0.608507 -0.7930226 -0.02888607 0.7474596 -0.6629836 -0.04191672 0.7931229 -0.6085841 -0.02411371 0.8573043 -0.5142782 -0.02340108 0.965859 -0.2588008 -0.01177054 0.9293884 -0.3670074 0.03927928 0.9938601 -0.1105245 -0.005138635 0.4139893 -0.9093017 -0.0422306 0.2587763 -0.9657716 -0.01789158 0.1637409 -0.9853534 -0.04761898 0.9959668 -0.08972185 -5.40277e-4 0.9657995 -0.2587906 -0.01609438 0.2426582 -0.9701119 -2.5302e-5 0.2588174 -0.9659126 -0.005148112 0.6087653 -0.7933444 0.003122389 0.9682176 -0.2494658 -0.01793432 0.8959835 -0.4440818 0.002251505 0.7933501 -0.6087591 -0.00283885 0.779673 -0.6261869 -3.10785e-5 0.5955435 -0.8033231 4.01514e-5 -2.59967e-4 -1 -4.12298e-5 -2.60064e-4 -1 -4.56738e-5 -0.1861479 0.6947687 -0.694727 -0.508594 0.6947419 -0.5085922 -0.6947462 0.6947462 0.1861598 0.6947363 0.6947556 0.1861614 0.6947498 0.6947433 -0.1861574 0.6947435 0.6947498 -0.1861564 0.1861769 0.6947488 -0.6947391 0.1861399 0.6947705 -0.6947273 -0.9831955 2.3469e-4 0.182556 0.3977267 -2.82457e-4 0.9175039 0.3974751 0 0.917613 -0.01276069 -0.05588108 0.998356 -0.07781016 0 0.9969682 -0.3612847 0 0.9324556 -0.4684738 -0.07029926 0.8806761 -0.9831535 0 0.1827823 -0.822004 0 0.5694817 -0.5708256 0 0.8210714 -0.3966044 -8.09846e-6 0.9179896 0.9841371 3.35672e-5 0.1774102 0.9841424 0 0.1773808 0.8272952 0 0.5617675 0.8272445 0 0.5618422 0.5744331 0 0.8185516 0.4740738 -0.07114487 0.8776062 -0.3966128 0 0.917986 0.01656597 0 0.9998628 0.01624441 0 0.9998682 0.3636718 0 0.9315271 0.8944391 0.2676211 0.3582706 0.3337631 -1.24618e-4 0.942657 0.469621 0.1540248 0.8693287 0.9914965 0.07507425 0.1062952 0.9761827 -0.1269109 0.1759575 0.6302463 0.1967385 0.751055 0.9617982 0.05451953 0.2682759 0.977449 0.063564 0.201378 0.9410201 0.2633173 0.2124739 0.9492126 0.1906864 0.2502687 0.9783222 0.1150623 0.1721816 -0.393962 -0.1114763 0.9123416 -0.3360279 0.03408539 0.9412351 -0.3328182 0.2046323 0.9205204 -0.4396815 0.1529304 0.8850381 -0.4401896 0.3097065 0.8428019 0.01633858 0.09456342 0.9953848 0.04887086 0.1546737 0.9867562 0.04867029 0.1699692 0.9842468 -0.2056612 0.1597057 0.9655038 -0.2057332 0.3470692 0.9149956 -0.43206 0.3081662 0.8475598 -0.4012489 0.423959 0.8119472 0.7991897 0.130975 0.5866357 0.7965753 0.1608741 0.5827414 0.8270688 0.1415701 0.5439808 0.8264052 0.3425086 0.4469254 0.8462945 0.3216936 0.4246164 -0.06020611 0.6676808 0.7420092 0.2114862 0.6638506 0.7173395 0.1576805 0.6520846 0.7415677 0.4452818 0.6105634 0.6549324 0.1178681 0.5935981 0.7960832 0.5679715 0.4943847 0.6580215 0.6290287 0.4718969 0.6177671 0.6827329 0.4380164 0.5848227 0.7836854 0.3729537 0.496732 -0.288491 0.638323 0.7136643 -0.1145174 0.6745252 0.7293159 -0.1147215 0.5112163 0.8517612 0.157657 0.5260251 0.8357285 0.09996259 0.5075874 0.8557819 0.3803846 0.4898671 0.7844348 0.8253986 0.06646811 0.560624 0.595621 8.64398e-4 0.8032652 0.5889111 0.2142384 0.7792855 0.3293697 0.2382661 0.9136438 0.3777057 0.247045 0.8923605 -0.1303785 0.2437769 0.9610277 0.1001706 0.3552313 0.9293958 -0.1721132 0.3377979 0.9253484 -0.1718375 0.5202369 0.8365557 -0.4500686 0.4530674 0.7695248 -0.1593253 0.6374797 0.7538139 -0.727235 0 0.6863886 -0.532761 -7.34167e-4 0.8462656 -0.09948122 -0.007203876 0.9950134 -0.7247514 0.01000016 0.688938 -0.6191573 0.003899276 0.7852573 -0.3114612 -0.001727342 0.9502574 -0.2170255 -0.003441452 0.9761599 0.3369908 1.33989e-5 0.941508 -0.390345 0.003881156 0.9206604 -0.1902016 1.84782e-4 0.9817451 0.03589683 -1.9864e-4 0.9993555 0.1141285 -0.001635015 0.9934647 0.1804988 -7.0128e-4 0.9835751 0.2661997 -3.02914e-5 0.9639179 0.6357078 -3.7407e-4 0.7719298 0.5658381 -0.001518607 0.824515 0.4683436 -0.003448665 0.8835398 0.3769759 -1.36863e-4 0.9262232 0.4758318 -7.69554e-4 0.879536 0.6746715 0.00407356 0.7381069 0.8519953 -0.001664757 0.5235468 0.8931177 3.58435e-4 0.449823 0.7889735 -5.94479e-5 0.6144273 0.7703421 -1.80116e-4 0.6376309 0.7546812 -1.75389e-5 0.6560918 0.7038877 1.12183e-5 0.7103114 0.9334026 1.79976e-4 0.358831 0.987642 -3.56e-4 0.1567265 0.9902967 -1.14856e-6 0.1389693 -0.640628 3.98625e-5 0.7678514 -0.7690376 -2.51893e-5 0.6392037 -0.7895787 3.21934e-4 0.6136492 -0.8929829 -5.37279e-4 0.4500905 -0.9051377 -5.60272e-5 0.4251185 -0.9876525 7.4318e-5 0.1566609 -0.981438 -7.36796e-4 0.1917786 -0.999307 -2.10296e-5 0.03722226 -0.01267659 -0.00333321 0.9999142 -0.1646571 -8.09182e-4 0.9863506 -0.2909157 1.48488e-4 0.9567488 -0.4759991 -4.6243e-4 0.8794457 -0.3650591 -0.003223001 0.9309788 -0.6730972 0.004508554 0.7395403 -0.458464 -0.003561794 0.8887059 -0.5459012 -0.001855194 0.8378475 -0.115572 -1.82522e-4 0.9932991 0.2175263 1.20764e-4 0.9760545 0.2199102 1.71817e-4 0.9755201 0.7366752 1.59948e-5 0.6762468 0.5628609 1.56107e-4 0.8265516 0.6247548 0.003169715 0.7808147 0.4264854 -1.08268e-4 0.9044946 -0.04938662 0.1572393 0.9863249 0.5107342 0.3278928 0.794756 0.440998 0.2684921 0.8564069 0.4395675 0.1528697 0.8851053 0.4086633 0.3131894 0.857267 0.4090581 0.466124 0.7844744 0.04040461 0.6267541 0.778169 0.2445383 0.6394569 0.7289005 -0.9831311 0.006652176 0.1827815 -0.3774891 0.2470315 0.8924559 -0.5951007 0.4847159 0.6410192 -0.3806565 0.4897183 0.7843958 -0.1714486 0.5763511 0.7990149 -0.4697663 0.602851 0.6448956 -0.9922471 0.03559172 0.119076 -0.9671486 0.08333188 0.240166 -0.9645718 -0.07983684 0.2514505 -0.7998421 0.120507 0.5879886 -0.8198295 0.07231444 0.5680232 -0.5955762 -0.002265572 0.8032957 -0.4640035 0.152735 0.8725669 0.2066706 0.258921 0.9435292 0.2059904 0.3336462 0.9199175 0.1722671 0.3509473 0.920413 0.1721091 0.5029829 0.8469868 0.1146578 0.5281609 0.8413677 0.1150362 0.6463042 0.7543591 -0.02441596 0.700897 0.7128444 0.397386 0.03288322 0.9170622 0.3329291 -0.0739938 0.9400443 0.3349965 0.1500827 0.9301896 -0.04919975 0.1699589 0.9842223 0.32603 0.3157557 0.8910684 -0.09841769 0.2535886 0.9622925 -0.09962701 0.526133 0.8445465 -0.1574113 0.5073379 0.8472485 -0.1574867 0.6734851 0.7222298 -0.244956 0.6471079 0.721975 -0.6912436 0.4443002 0.5698945 -0.6300477 0.463546 0.6230289 -0.8258333 0.3401197 0.4497978 -0.8266831 0.3395266 0.4486835 -0.9696885 0.1428284 0.1982532 -0.9972122 0.04634797 0.05848032 -0.9503642 0.1692609 0.2610726 -0.9498128 0.08639138 0.3006529 -0.827048 0.1415252 0.5440241 -0.7966356 0.1607958 0.5826804 -0.6300446 0.1967142 0.7512305 -0.5888776 0.214187 0.7793248 -0.3294302 0.2381933 0.9136409 -0.3338344 0.001495957 0.9426306 -0.0126717 0.08983534 0.995876 -0.4981424 0.4002536 0.7691887 -0.2888812 0.7380502 0.6097784 0.2119391 0.7037829 0.6780645 0.4497798 0.6115359 0.6509394 0.7859697 0.3939067 0.4765388 0.573474 0.5587282 0.5991248 -0.1297981 0.9382614 0.3206527 0.6231964 0.04707217 0.7806475 0.7022894 0.2477732 0.6673816 0.6313511 0.1754634 0.7553862 0.6626717 0.378211 0.6463921 0.6930682 0.1877112 0.6960036 0.6751783 0.09852558 0.7310452 -0.2239153 0.08413362 0.9709703 -0.3916807 0.06070661 0.9180964 -0.3173843 0.2560284 0.9130809 -0.5092396 -0.3255248 0.7966861 -0.5093035 -0.2834487 0.8125681 -0.6935294 0.201133 0.6917822 -0.7051906 0.200349 0.6801224 0.4688368 -0.004567861 0.8832731 0.3833914 0.1578532 0.9099964 0.3203794 0.1226806 0.9393117 0.2373801 0.133143 0.9622493 0.2365248 0.1311144 0.9627383 0.09846854 0.07355946 0.9924178 0.1369215 0.2119006 0.9676522 0.03033381 0.03457838 0.9989416 0.9511075 0.2064215 0.2297498 0.973066 0.06977373 0.2197144 0.8935688 0.2595751 0.3662727 0.8460007 0.3166836 0.4289457 0.8373325 0.3238238 0.4404684 0.809888 0.2307879 0.5392757 0.7059311 0.2573462 0.6598744 0.6865047 0.4767262 0.5490386 0.6692393 0.4832602 0.5644276 0.6479503 0.4121916 0.6405143 0.4339416 0.5595473 0.7061173 0.396656 0.5558919 0.7305123 0.3407223 0.4428175 0.8293499 0.9212568 0.06257766 0.383888 0.8945667 0.09411418 0.436913 0.8537966 -0.01009851 0.5205088 0.698302 0.2441055 0.6728945 0.6997129 0.2442683 0.6713679 0.4168834 0.5099707 0.7524216 0.3803209 0.4630128 0.8006093 0.2764164 0.4713054 0.8375353 0.4856034 0.2033464 0.8501996 -0.06346845 0.311051 0.9482717 -0.1099523 0.08793658 0.9900392 -0.07725918 0.1226832 0.9894341 -0.1298046 0.3918743 0.9108158 0.02425223 0.3086503 0.9508664 0.1718965 0.3681549 0.9137361 0.1057484 0.4168401 0.9028077 0.2457603 0.3762786 0.8933175 0.3816699 0.1450141 0.9128522 0.485471 0.218548 0.8464956 0.5725212 0.07225787 0.8166997 0.5298753 0.1205851 0.8394591 -0.06043577 0.7284776 0.6823986 -0.1232811 0.7015687 0.701857 -0.1465602 0.7476726 0.6476928 -0.1378433 0.7549164 0.6411713 -0.1266543 0.7665171 0.6296113 -0.1570649 0.7609924 0.6294611 -0.1433115 0.7742919 0.6163878 -0.1942039 0.7704609 0.6071862 -0.196259 0.7696169 0.6075955 -0.2458788 0.7818094 0.5729904 -0.2814345 0.7702773 0.5722478 -0.3200175 0.7888236 0.5247345 -0.2315093 0.06026643 0.9709642 -0.2509646 0.2715442 0.929129 -0.382205 0.3934153 0.8361481 -0.3311001 0.2727588 0.9033136 -0.582445 0.2584233 0.7706979 0.4455899 0.6150385 0.6505209 0.2065486 0.7078728 0.6754657 0.1911652 0.657462 0.7288346 0.2004068 0.6568074 0.7269396 0.1588117 0.6034805 0.7814028 0.1395236 0.6088922 0.7808864 0.0570749 0.5500186 0.8331999 0.02443808 0.5686802 0.8221957 -0.1145907 0.5105287 0.8521909 -0.1395314 0.5366412 0.8321942 -0.3225977 0.4952654 0.8066245 -0.33001 0.5125299 0.7927211 -0.5183905 0.5013599 0.6927551 -0.51798 0.4929577 0.6990633 -0.3941088 0.7627471 0.5127331 -0.3211742 0.7955582 0.5137456 -0.4552987 0.6385338 0.6204658 0.5352201 0.3869377 0.7508787 -0.470336 0.6231728 0.6248518 -0.8919317 0.06066679 0.4480819 -0.5352185 0.03623872 0.8439361 0.2453993 0.7457221 0.6194173 0.2562123 0.7397087 0.622243 0.261551 0.8467375 0.4632782 0.2558937 0.8500759 0.4603148 0.2293765 0.8365638 0.4975414 0.2514467 0.8257231 0.5049317 0.2136212 0.8182535 0.533692 0.2766237 0.7897685 0.54749 0.2079694 0.7916026 0.5745555 0.2833963 0.7578616 0.5876499 0.3122088 0.8241641 0.4725244 0.3039658 0.8768671 0.3724365 0.4015823 0.7008807 0.5894896 0.5608222 0.08194667 0.8238709 0.6034446 -0.1569786 0.7818008 0.31993 0.2142046 0.9229091 0.2245301 0.05701488 0.9727979 0.01565319 0.1877402 0.9820941 0.01510506 0.1893964 0.9817846 -0.1384524 0.1347992 0.9811525 -0.24757 0.1806047 0.9518882 -0.2656781 0.2150848 0.9397627 -0.3124326 0.1982251 0.9290278 -0.5963977 0.1449709 0.7894892 -0.6012377 0.1254575 0.7891601 -0.7713702 0.06846386 0.6326932 -0.782651 0.205441 0.5875811 -0.8387562 0.1730608 0.5162734 -0.9699688 0.2046209 0.1314952 -0.693961 0.4728381 0.542994 -0.8273169 0.3534634 0.4365897 -0.869385 0.2731974 0.4117439 -0.9607878 0.1579805 0.2278794 -0.9760288 0.04604285 0.2127155 -0.5982411 0.5323562 0.5989195 -0.6434425 0.4886004 0.5892804 -0.6141995 0.3953979 0.6829491 -0.6190168 0.3866785 0.683592 -0.5090737 0.2480227 0.8242141 -0.5046138 0.2686761 0.8204743 -0.3761318 0.1775606 0.9093939 -0.4614382 -0.01585716 0.8870307 0.4972036 0.5723553 0.6520721 0.405067 0.6817736 0.6091845 0.2987974 0.6866697 0.6627254 0.3167119 0.668326 0.673078 0.1721754 0.7011855 0.6918777 0.1918814 0.6661676 0.7206957 0.08202481 0.7128675 0.6964854 0.0861997 0.6798684 0.7282505 0.02891218 0.7210406 0.6922895 0.02302378 0.7046027 0.7092284 0.009010493 0.7225601 0.6912494 0.01537644 0.7281721 0.6852219 0.01628047 0.7249013 0.6886604 -0.02400606 0.6950486 0.7185618 0.5820923 0.2612647 0.7700061 0.5349689 0.3817095 0.7537282 0.3200094 0.3930858 0.8620195 0.3331843 0.371058 0.866778 0.07815909 0.4285441 0.900134 0.09173029 0.3874737 0.9173058 -0.1173182 0.4754798 0.871869 -0.1163757 0.437164 0.8918209 -0.2503719 0.532482 0.8085647 -0.2563548 0.5134294 0.818946 -0.3217509 0.5961911 0.7355491 -0.3154512 0.6037934 0.7320684 -0.3265379 0.6409146 0.6946953 -0.2460447 0.694998 0.6756033 0.3944979 0.8107665 0.4324686 0.6379995 0.4073092 0.6534951 0.4592093 0.7128124 0.5301182 0.5559332 0.1593787 0.8158044 0.5538001 0.02899265 0.8321448 0.4665053 0.2647758 0.8439589 0.4840491 0.09126722 0.8702684 0.6244811 0.02240133 0.7807188 0.6381941 0.3353213 0.6930137 0.649995 0.299896 0.6982614 0.7181671 0.1078067 0.6874691 0.6772059 0.2787685 0.6809408 0.1006033 0.9936188 0.05099838 0.2521477 0.9174438 0.3077634 0.184019 0.961765 0.2028425 0.3294451 0.8278709 0.4539778 0.2715603 0.8906877 0.3645964 0.3959144 0.7026662 0.5911954 0.3543258 0.773828 0.5250176 0.449773 0.5447543 0.7077761 0.4175071 0.6288055 0.6559662 0.4855698 0.3621529 0.7956552 0.4652834 0.4485729 0.7630817 0.5000265 0.1663298 0.8498871 0.5054852 -0.09233856 0.8578801 0.5237504 0.03331536 0.8512201 0.545052 0.5819929 0.603492 0.6220303 0.4582296 0.6349048 0.5945532 0.4546704 0.6631602 0.6222931 0.3972916 0.6744708 0.4806766 0.6867611 0.5452607 0.4596547 0.7179104 0.5228025 0.4534118 0.7177271 0.5284749 0.4130108 0.7602691 0.5014112 0.4220595 0.7614089 0.4920593 0.3385603 0.829322 0.4445247 0.5610176 -0.4003252 0.7245682 0.6380164 0.1469041 0.7558798 0.5958952 0.3963028 0.6984649 0.6036006 0.3472749 0.7176814 0.5565183 0.5299676 0.6398607 0.3074784 0.9114213 0.2734377 0.4023635 0.810019 0.4265828 0.3938947 0.8205813 0.4141175 0.4727901 0.6875157 0.5511732 0.4693934 0.6940371 0.5458777 0.5287547 0.5326333 0.6608482 0.5278881 0.5352033 0.6594632 0.5648069 0.3512294 0.746747 0.5646517 0.3521068 0.7464511 0.5774641 0.1531258 0.8019276 0.5607057 -0.1749175 0.8093287 0.5900417 0.02549958 0.8069701 -0.164451 0.9356788 0.3121876 -0.4834239 0.09128057 0.8706144 -0.685409 0.1968759 0.7010381 -0.1097146 -0.9829221 0.1477394 -0.5651926 0.4958386 0.6593189 -0.553704 0.129584 0.8225691 -0.2875215 0.9140686 0.2860248 -0.1381324 0.9849202 0.1041725 -0.3504469 0.8260906 0.4413177 -0.4627416 0.2828581 0.8401557 -0.5109052 -0.08720552 0.8552024 -0.441416 0.4657119 0.7669841 -0.5169258 0.1344254 0.8454098 -0.3940503 0.6517653 0.6480173 -0.07064324 0.9957867 0.05846673 -0.1119631 0.9864798 0.1196745 -0.4093229 0.7014859 0.5834144 -0.3009858 0.8492735 0.4337538 -0.4527872 0.5443758 0.7061436 -0.5047103 0.3600981 0.7845998 -0.5022925 0.6481133 0.5724084 -0.5633807 0.5290854 0.6345636 -0.5733373 0.5045155 0.6455606 -0.6282944 0.3444681 0.6975585 -0.6635929 0.1438524 0.7341328 -0.3846565 0.808018 0.4462581 -0.4633415 0.7012913 0.5417612 -0.4658765 0.6881545 0.5562396 -0.567901 -0.008349537 0.8230545 -0.5496968 -0.2405819 0.7999711 -0.5558601 0.3534797 0.7523774 -0.5861227 0.152326 0.7957745 -0.5191396 0.5364462 0.6653718 -0.5733366 0.3505412 0.7405444 -0.4607525 0.6953401 0.5515518 -0.537029 0.5318624 0.6547689 -0.3855667 0.8218484 0.4194087 -0.4806275 0.6868242 0.5452244 -0.2996087 0.9125365 0.2784093 -0.3976972 0.8231983 0.4051932 -0.359877 0.193347 0.9127462 -0.1794011 0.8542478 0.4879305 -0.3696495 0.09094744 0.9247097 -0.351929 0.2817827 0.8926056 -0.3294585 0.439568 0.8356059 -0.324425 0.4644557 0.8240324 -0.2857396 0.6296994 0.7223792 -0.2784 0.6510617 0.7061247 -0.1393455 0.9250211 0.3534384 -0.2303434 0.8513774 0.4712734 -0.1532817 0.9356906 0.3177859 0.6989906 0.4290636 0.5721159 -0.1170524 0.267026 0.9565542 -0.2618131 0.06013947 0.9632431 -0.2166 0.1939114 0.9568087 -0.1682351 0.1294801 0.9772062 -0.1074985 0.1124426 0.9878263 -0.009103953 0.1672645 0.98587 -0.08373934 0.06887167 0.9941049 -0.04236578 0.07172667 0.9965242 0.02896136 0.04280525 0.9986636 0.02163487 0.04247409 0.9988633 0.7877752 0.1913244 0.5854959 0.8572521 0.2350967 0.4580923 0.742176 0.05154496 0.6682201 0.1919739 0.817247 0.5433723 0.002809882 0.8692551 0.4943559 -0.02409434 0.84842 0.528775 0.2497484 0.7455368 0.6179002 0.2225318 0.6319178 0.7424012 0.3411048 0.5418295 0.7681591 0.3477311 0.5618329 0.7506178 0.4933226 0.3978334 0.7735383 -0.191797 0.4405051 0.8770229 -0.1926059 0.4046075 0.8939776 -0.03023362 0.3575688 0.9333974 -0.004149019 0.4249771 0.9051946 0.1178822 0.3336508 0.9352973 0.1266736 0.3575564 0.9252606 0.2261896 0.2491325 0.9416853 0.253023 0.2729438 0.92816 0.3265394 0.08707875 0.9411638 -0.1122446 0.62807 0.7700191 -0.105812 0.6906703 0.715387 0.05755734 0.6470896 0.7602384 0.1961023 0.8191847 0.5389626 0.3589345 0.7572814 0.5456107 0.2559121 0.4961277 0.8296784 0.2860354 0.512179 0.8098496 0.8180699 0.5293393 0.2248597 0.5151159 0.4169687 0.748861 0.6260462 0.1342902 0.7681357 0.4138134 0.1205536 0.9023444 0.02192813 -7.60417e-4 0.9997593 0.7432491 8.53642e-4 0.6690143 0.7434878 0 0.6687495 0.4170758 0 0.9088717 0.02172464 0 0.999764 0.03364729 0.9957787 0.08539634 0.06669276 0.9841579 0.1642722 0.09761726 0.9639341 0.2475923 0.1654794 0.8924462 0.41971 0.2009872 0.840954 0.5023949 0.2319278 0.7747098 0.5882468 0.2852278 0.62874 0.7234163 0.2903062 0.6127947 0.7349864 0.3307144 0.429673 0.8402436 0.3652689 0.09091418 0.9264521 0.362826 0.1749819 0.9152806 0.3538081 0.2637346 0.897365 0.3279378 0.4479057 0.8317676 -0.3118519 0.8018113 0.5097519 -0.1818749 0.174725 0.9676738 -0.5140621 0.1720594 0.8403189 -0.4230693 -0.110291 0.89936 -0.8281826 0.1720701 0.5333905 -0.7941365 -0.03485381 0.6067392 0.03842377 0.1757255 0.9836891 0.2816013 0.2216272 0.9335857 0.157173 0.1762568 0.9717152 0.1439102 0.3864471 0.9110152 -0.09921628 0.03753823 0.9943576 -0.07869547 0.6097213 0.7886996 0.1440412 0.3864259 0.9110035 -0.3118596 0.8018027 0.5097607 -0.5024073 0.8018007 0.3235776 -0.5023976 0.8018054 0.3235816 -0.5846864 0.8047463 0.102593 -0.8381061 0.5253108 0.1470609 -0.8381004 0.5253203 0.1470593 -0.4453055 0.5213911 0.7279109 -0.4453039 0.5213987 0.7279065 -0.1655777 0.5279604 0.8329718 -0.1260929 0.8073578 0.5764322 -0.1619399 0.8498995 0.5014442 0 1 -3.30237e-6 -0.1411363 0.4052363 0.903252 0.1800479 -0.03879767 0.9828924 -0.04285168 0.1757916 0.9834944 -0.2843846 0.1739667 0.9427943 0.521613 0.02974879 0.8526635 0.7815093 0.1746283 0.598956 0.8400267 0.0405451 0.5410279 0.895159 0.1757948 0.4096177 0.1349068 0.7635704 0.6314749 0.5846882 0.8047448 0.1025937 0.5024037 0.8018021 0.3235799 0.3118464 0.8018062 0.5097634 0.3118641 0.8018076 0.5097506 0.122766 0.807173 0.5774084 0.1604789 0.8528124 0.4969484 -0.1443915 0.3865226 0.910907 0.09780591 0.1720573 0.9802196 0.4163569 0.1752818 0.8921453 0.04929059 0.6360624 0.7700617 0.1771401 0.5286065 0.8301787 0.4453111 0.5213934 0.7279059 0.4452992 0.5213925 0.7279139 0.8381017 0.5253181 0.1470602 0.8147947 2.47852e-4 0.5797496 0.7492204 -0.03140211 0.661576 0.7936931 -0.005574643 0.6082929 0.6337319 0.004453778 0.77354 0.6142284 -0.00457704 0.7891151 0.5312428 7.91363e-5 0.8472197 0.4229115 -7.39804e-4 0.9061707 0.4289067 -0.003471493 0.9033423 0.18019 0.004681646 0.9836207 0.1878472 0 0.9821982 -0.2093378 0.05440807 0.9763286 -0.288762 -3.89041e-6 0.9574009 0.9999991 0 0.001442253 0.998643 -1.12424e-4 0.05207955 0.9738512 -0.01302498 0.2268134 0.9336904 -0.06148946 0.3527627 0.8832291 -5.07486e-5 0.4689419 0.909312 -0.002722561 0.4161064 0.9845359 0.02908474 0.1727518 0.2599096 0.9643535 -0.04969424 0.9843241 0.176369 0 0.9909707 0.1337484 -0.009409844 0.9911625 0.1326349 -0.002222895 0.8473136 0.5310838 0.003122806 0.874465 0.4850884 -6.17684e-4 0.3696108 0.9291628 -0.006664872 0.5634181 0.8253884 0.03597444 0.5877897 0.8090137 4.62033e-4 -0.5387816 -0.3122762 -0.7824308 0.447236 0 -0.894416 0.538863 -0.3119238 -0.7825155 -0.9747205 0.2232323 -0.00934273 -0.5877882 0.809015 0 -0.6501092 0.7557502 -0.07873868 -0.4858255 0.8738629 0.01836913 -0.2468522 0.9685382 -0.03158766 -0.5782446 0.8158633 -6.21274e-4 -0.8473178 0.5310856 7.64199e-4 -0.8142604 0.5804927 -0.002872347 -0.9843185 0.176376 0.002956867 -0.9749591 0.2223848 -1.52666e-7 -0.9852738 -0.02013021 -0.1697947 -0.9656582 0.08453512 -0.2456788 -0.9943879 -0.001690566 -0.1057821 -0.9185776 0.00187093 0.3952362 -0.9832206 -0.005604505 0.1823343 -0.9663627 -0.0322045 0.2551589 -0.9772443 -0.02186703 0.2109868 -0.9823263 -0.01645982 0.1864513 -0.9886086 -0.01007771 0.1501716 -0.9953981 -0.003292977 0.0957697 -0.9992588 -3.59913e-4 0.03849697 -0.9999694 0 0.007835865 -0.8524719 -2.77112e-6 0.5227732 -0.7983461 -0.0486024 0.6002345 -0.8622728 -0.01414948 0.5062465 -0.9978026 -0.0662586 0 -0.9848744 -0.1732585 -0.002019405 -0.9466494 -0.3222544 0.002668201 -0.9064794 -0.4222503 0 -0.7933307 -0.6087901 -0.001043617 -0.6774622 -0.7355502 0.003315985 0.9827647 -0.02338838 -0.1833757 0.9843463 -0.00165832 -0.1762375 0.9999536 -0.001662015 -0.009494364 0.9980308 0.05009877 0.03774464 0.5578207 0.8171578 -0.1452217 0.7260586 0.6789513 0.1089236 0.8669153 0.4809174 -0.1310594 0.9765766 0.2029054 -0.07160741 0.9885307 0.1333551 0.07087641 0.9266643 0.3757242 0.01117217 0.8614449 0.4861271 -0.146947 0.8591267 0.5058518 0.07755947 0.7310883 0.6801217 0.05426263 0.7189501 0.6824523 0.1317943 0.5054867 0.862802 0.007480561 0.5141264 0.8577002 -0.00492537 0.4240078 0.8942703 -0.1431713 0.3646675 0.9273915 -0.08344268 0.4424386 0.8961947 -0.03291201 3.22118e-6 1 1.23433e-5 9.53185e-6 1 2.81218e-5 5.29467e-5 1 -5.07857e-5 9.54831e-5 1 -4.7673e-5 3.36613e-7 1 0 -2.04841e-4 1 -1.83643e-5 -8.09185e-5 1 -4.09714e-5 -3.36572e-7 1 0 3.18579e-5 1 1.61657e-5 -3.22118e-6 1 1.13147e-5 -2.66458e-6 1 1.35471e-5 2.66458e-6 1 1.35471e-5 -0.4069663 0.9086781 -0.09318035 -0.5096234 0.8603916 -0.003249168 -0.9974276 0.06092911 0.03776055 -0.8126065 0.5792862 -0.06401783 -0.7265807 0.6791986 0.1037773 -0.6520597 0.7580615 0.01269447 -0.4850803 0.8725604 0.05775517 -0.9696426 0.2220329 -0.1024433 -0.9695761 0.2277576 -0.08971536 -0.8901588 0.4454951 0.09566432 -0.8919433 0.4463483 0.0721845 -0.7307019 0.6793946 0.06706517 -0.677515 0.6727284 0.2973379 -0.456094 0.8815327 -0.1219776 0.8334271 -0.5526283 -0.001146972 0.8435832 -0.5369986 -2.26807e-6 0.536872 -0.8436638 -3.56135e-6 0.7823129 2.069e-6 0.6228856 0.852309 -0.0194565 0.5226766 0.8605117 -0.01444256 0.509226 0.9997068 -9.38894e-5 0.02421462 0.9960191 -0.002299785 0.08911103 0.9895183 -0.009361743 0.1441039 0.9851686 -0.0135895 0.1710504 0.9831126 -0.01581019 0.1823175 0.9646887 -0.002934992 0.2633765 0.919145 0.00192517 0.3939147 0.9638851 -0.2510256 -0.08894824 0.9883258 -0.002264201 0.1523386 0.9859211 -0.06772649 -0.1528818 0.9998965 -0.004769861 0.01358056 0.9986082 -0.03665983 0.03791755 0.9974784 -0.02395045 0.06680774 0.9916242 -0.08122658 0.1004187 0.9717199 -0.03769946 0.2331076 0.9676737 0.03669464 0.2495219 0.9732412 -0.162563 0.1624036 0.9772188 -0.130689 0.1672245 0.9537564 -0.2932991 0.06576055 0.9311146 -0.359606 0.06090211 0.8988184 -0.4357058 -0.04781395 0.9997573 0.003093302 0.02181679 0.9819588 -0.1117282 -0.1525574 0.9741591 -0.2127147 -0.07593739 0.9567307 -0.2192363 -0.1913164 0.963449 -0.2349423 -0.1287178 0.7056583 -0.1766083 0.6861894 -0.0364775 -0.9878966 0.1507634 -0.03773152 -0.9843495 0.1721407 0.5646078 0.1224897 0.8162196 0.6107761 -0.1736173 0.7725347 0.3438711 -0.1756631 0.9224398 0.2320896 0.1615036 0.959193 0.1173452 -0.1756635 0.9774316 -0.2321785 0.1591748 0.9595606 -0.3525344 -0.1758462 0.9191287 -0.5676757 -0.175182 0.8043977 -0.7122758 -0.1772057 0.6791623 -0.3357353 -0.840801 0.4246593 -0.3357118 -0.8408194 0.4246417 -0.1281564 -0.8384664 0.52967 -0.1281479 -0.8384685 0.5296687 0.1281419 -0.8384651 0.5296754 0.3357103 -0.8408148 0.4246518 0.3357359 -0.8408073 0.4246461 -0.5240674 -0.5347805 0.6628448 -0.1992405 -0.531173 0.8235037 -0.1992757 -0.5311127 0.8235342 0.5240696 -0.5347622 0.6628578 0.5240683 -0.5347737 0.6628495 -0.987402 -0.002909362 0.1582053 -0.9859924 -0.04075419 0.1617349 -0.9821821 -0.0749036 0.1723601 -0.9444509 -0.2359542 0.2287757 -0.9700325 -0.05530476 0.236598 -0.9998661 -0.01427143 0.008017539 -0.9983527 -0.04008567 0.04105055 -0.997938 -0.03640711 0.05286127 -0.9831285 -0.111267 0.1451826 -0.9230018 -0.3847148 0.00788325 -0.9513907 -0.3079745 -0.002741396 -0.985969 -0.04954731 -0.1594057 -0.9843615 -0.08945763 -0.1517561 -0.9842837 -0.09521108 -0.1487296 -0.9795528 -0.143541 -0.1409698 -0.9789192 -0.1601178 -0.1268061 -0.9686985 -0.230057 -0.0932576 -0.968777 -0.2176611 -0.1187222 -0.9680188 -0.2301822 -0.09977883 -0.631145 0.004325807 0.775653 -0.4054704 -0.001253426 0.9141073 -0.2485592 0.002754509 0.9686128 -0.1126739 -0.005001485 0.9936195 0.3136488 -2.61965e-4 0.949539 0.1049022 -0.00341016 0.9944768 0.7799655 5.20991e-4 0.6258223 0.7061133 -8.1473e-5 0.7080989 0.5492458 -0.002602338 0.8356569 0.5994135 -0.01273804 0.8003383 0.4297991 9.53167e-4 0.902924 0.8550184 0.01244741 0.5184483 0.9869758 -0.005520701 0.1607747 0.9931614 0 0.1167502 -0.8236703 -0.430428 0.3691869 -0.3968152 -0.8996447 0.1821461 -0.5721502 -0.7940512 0.2052483 -0.8206612 -0.5644868 0.08871293 -0.9567564 -0.2889428 -0.03360319 -0.9837689 -2.16213e-5 -0.1794405 -0.6073462 -0.7491495 0.2643969 -0.197193 -0.9634722 -0.1812078 -0.3853741 -0.9210571 0.05604237 -0.9811464 -0.06516242 0.1819496 -0.9811458 -0.06515467 0.1819553 -0.8506556 -0.0651648 0.521669 -0.9323975 -0.3173912 0.1729099 -0.9139615 -0.3569207 0.1930856 -0.8184123 -0.3579791 0.4495026 -0.7270581 -0.5588537 0.3988347 -0.834565 -0.5287216 0.1547737 -0.6523413 -0.7452954 0.1377891 -0.40894 -0.9099113 0.06949478 -0.3983454 -0.9119735 0.0981087 -0.868312 -0.4820727 0.1167925 -0.8673169 -0.4685182 0.1680844 -0.9208982 -0.3047421 0.2430614 -0.9230069 -0.2628867 0.2809785 -0.943048 -0.09777498 0.3179636 -0.9408619 -0.1094521 0.3206231 -0.8881902 -0.1565006 0.432002 -0.8580793 -0.3582242 0.3679339 -0.8966061 -0.1631821 0.4116665 -0.7898437 -0.2274469 0.5695743 -0.8217979 -0.1746681 0.5423463 -0.8041942 -0.5400516 0.248226 -0.822115 -0.5169247 0.2385707 -0.7588869 -0.5581446 0.3355075 0.7837464 0.6185976 -0.05548638 0.468919 0.883114 0.01499116 0.4945909 0.8690683 -0.01001662 -0.4674862 0.8839146 0.01231497 -0.5392602 0.8412724 -0.03820085 -0.4821588 0.8760817 -0.001968085 -0.4561127 0.8893322 0.03239554 0.9197797 -0.3534278 0.1705704 0.8309872 -0.5313392 0.1647387 0.823647 -0.5461448 0.1527462 0.5343005 -0.8394637 0.09911525 0.3630461 -0.929426 0.06606775 0.06182092 -0.9980732 0.005304872 0.2311717 -0.9725206 0.02762752 0.335693 -0.9401268 0.05892443 0.797297 -0.3782131 0.4703961 0.7554512 -0.5405592 0.3702558 0.7552502 -0.5351334 0.3784569 0.5828796 -0.7582272 0.292135 0.9688513 -0.1704263 0.1796725 0.9688524 -0.170422 0.1796701 0.8460801 -0.1707875 0.5049557 0.8429066 -0.1494 0.5169026 -0.9996852 0 0.02509158 -0.987132 -0.003749668 0.1598643 -0.9861835 -0.002877295 0.1656318 -0.9356211 0.001291453 0.3530036 -0.8567515 -0.009524703 0.5156416 -0.8444387 -0.005881309 0.53562 -0.6933149 0.003320634 0.7206272 -0.4842925 -8.86924e-4 0.8749058 0.4183311 -3.99727e-4 0.9082946 0.2923775 -0.004350066 0.9562931 0.2913491 -0.004444658 0.9566066 0.08735799 0.001395165 0.996176 -0.08234769 -0.002608597 0.9966003 0.4964233 1.06582e-4 0.8680806 0.6263465 -0.00100404 0.7795442 0.6404486 1.78187e-6 0.7680011 0.7686923 -0.1217665 0.6279212 0.8900746 -0.1880964 0.4151952 0.8104855 -0.5242494 0.2612964 0.8109982 -0.5236082 0.2609913 0.8722674 -0.2701736 0.4076223 0.8022789 -0.0778017 0.5918577 0.7933228 -0.1131166 0.5982003 0.8115671 -0.2534269 0.5264348 0.790039 -0.3175894 0.5243811 0.7940747 -0.3553877 0.4930972 0.764338 -0.5411248 0.3506731 0.8510684 -0.5153684 0.10039 0.8891385 -0.4480343 0.09326344 0.9008468 -0.3743726 0.2198188 0.9421104 -0.1400439 0.3046571 0.9602478 -0.05785691 0.2730877 0.934152 -0.2223853 0.2791148 0.9721832 0.01080125 0.2339727 0.9919255 0.08355051 0.09541112 0.9945971 -0.0469464 0.09258931 0.3492579 2.94473e-4 0.9370267 0.3642295 -0.01648873 0.9311633 0.5896437 -0.002733767 0.807659 0.7169932 0.001118779 0.6970794 0.8521804 0.01842713 0.5229236 0.8638221 0.01267671 0.5036377 0.9075348 -0.005455911 0.4199417 -0.6071199 -0.002231299 0.7946071 -0.3581572 -9.77166e-6 0.9336614 -0.2240383 -0.002001464 0.9745783 -0.1285034 0.03147053 0.9912096 -0.0950911 0.001414775 0.9954677 0.1192067 9.62267e-4 0.992869 0.0629509 0.07136934 0.9954615 0.1793431 -0.003617942 0.98378 -0.7237668 7.81826e-4 0.6900442 -0.7841405 -0.01885652 0.620297 -0.769213 -0.009760439 0.6389179 -0.8718162 0.0378009 0.4883725 -0.9145676 0.002252817 0.4044268 -0.9885218 -0.003178477 0.1510457 -0.7671359 -0.177374 0.6164746 0.1404441 -0.9700989 0.1979488 0.3799632 -0.833279 0.4015893 0.4511585 -0.7662018 0.4575927 0.4533184 -0.7635167 0.45994 0.9530435 -0.28224 0.1097667 -0.7593201 -0.4838955 0.4350613 -0.7904998 -0.4571285 0.407607 -0.9014766 -0.2951915 0.3165472 0.4335424 -0.7098679 0.5550932 0.4616094 -0.692576 0.5543061 0.2530679 -0.7500533 0.6110456 0.2911012 -0.7399621 0.6063961 0.09561723 -0.7741348 0.6257576 0.1001313 -0.7730254 0.6264228 -0.08017086 -0.7620387 0.6425493 -0.2475738 -0.7446215 0.6198758 0.6230306 -0.7013579 0.3463094 0.275671 -0.8441082 0.4598771 0.3342545 -0.8289365 0.4484845 0.08562314 -0.8661257 0.4924378 0.1510008 -0.8493542 0.5057629 -0.5303779 -0.7029103 0.4739373 -0.4147976 -0.7166457 0.5606799 -0.1449643 -0.8982769 0.4148302 -0.2298892 -0.8818053 0.4117894 0.1935384 -0.9328101 0.3039875 0.1061043 -0.9436973 0.3133325 -0.125409 -0.9186975 0.3745231 0.2902315 -0.9203551 0.2621302 -0.6572633 -0.5417787 0.5239093 -0.705041 -0.4868595 0.5156404 -0.3670055 -0.8439682 0.3911837 -0.5016545 -0.7671548 0.3997703 -0.04357314 -0.9766332 0.2104494 -0.2291777 -0.9411935 0.2482588 -0.1357264 -0.9694094 0.2045091 0.09168094 -0.9857547 0.141005 -0.1715863 -0.8536641 0.4917476 0.9914001 -0.06615459 0.1129136 -0.1786203 -0.9632536 0.2005927 -0.1978618 -0.9498676 0.2420795 -0.412836 -0.8595969 0.3010973 -0.4279985 -0.8243573 0.3704761 -0.4222774 -0.7941951 0.4369622 -0.3940263 -0.8090859 0.4360315 -0.534227 -0.6649445 0.5219678 -0.5744946 -0.6837174 0.449985 -0.565564 -0.7339069 0.3761889 0.2200699 -0.7862154 0.5774381 0.8593717 -0.3131561 0.4042445 0.6943417 -0.5471804 0.4674221 0.6435977 -0.6117433 0.459948 0.4543564 -0.7553523 0.4722322 0.389178 -0.802245 0.452707 0.08087992 -0.9068949 0.4135217 0.1528092 -0.9533634 0.2602838 -0.06794905 -0.9881212 0.1378389 -0.0705263 -0.9882941 0.135281 0.2264367 -0.9673343 0.1139769 0.1184483 -0.9606587 0.2512066 0.4114517 -0.81642 0.405174 0.6090105 -0.6286377 0.4836539 0.6254786 -0.6004157 0.4982746 0.7719781 -0.347449 0.5322867 0.8147106 -0.3741872 0.4429791 -0.5021972 -0.6725246 0.5436072 -0.4343436 -0.6964613 0.5712158 -0.4077869 -0.7106466 0.5733162 -0.2577434 -0.7448027 0.6154977 0.1663533 -0.7693956 0.6167311 -0.09900397 -0.8080588 0.5807232 0.05297261 -0.8059588 0.5895969 0.6949425 -0.5486506 0.4647982 0.4352653 -0.7087251 0.5552053 0.1229206 -0.7909603 0.5993935 0.1648263 -0.8964443 0.4113637 -0.1388242 -0.9293556 0.3420907 -0.002291917 -0.9132416 0.4074121 -0.4001904 -0.8648023 0.3032569 -0.3668392 -0.9083129 0.2009897 0.4367185 -0.8444163 0.3102228 0.4327886 -0.8390976 0.329559 0.6111393 -0.5416394 0.577179 0.7112365 -0.6223813 0.3267785 0.598644 -0.1731678 0.7820731 0.9586899 -0.06284427 0.2774243 0.8896451 -0.229439 0.3948284 0.9950215 -0.02336174 0.09688317 0.9210883 -0.2729649 0.2776446 0.75945 -0.479644 0.4395196 1 2.08445e-6 0 1 3.76279e-6 0 0.5048837 -0.5837295 0.6358871 -0.7767626 -0.3252102 0.5393313 -0.6279931 -0.0993216 0.7718549 -0.2590655 -0.6531746 0.7115111 0.05355447 -0.6751802 0.7357063 0.186397 -0.6411797 0.744409 0.2221804 -0.6592555 0.718344 0.504972 -0.5836083 0.6359283 -0.7947358 -0.3099059 0.5218749 -0.4311032 -0.4606034 0.7758831 -0.1422613 -0.5052648 0.8511576 -0.1422461 -0.5052573 0.8511646 0.1840117 -0.501731 0.8452253 0.500215 -0.442049 0.7445654 0.4999085 -0.4422378 0.7446591 -0.5338238 -0.1546268 0.8313379 -0.4305581 -0.1724148 0.8859418 -0.399755 -0.1681432 0.9010682 -0.1420621 -0.1815609 0.9730643 0.4990965 -0.1590739 0.8518205 0.5440639 -0.1373966 0.8277177 0.9209669 -0.2634719 0.2870587 0.920926 -0.2635804 0.2870903 0.9192234 -0.2011579 0.338473 0.9190152 -0.2015661 0.3387954 0.9919364 -0.08569049 0.09337806 0.9919271 -0.08579182 0.09338331 0.7594227 -0.43996 0.4792832 0.7594123 -0.4399353 0.4793224 0.7554793 -0.3345573 0.563314 0.7551216 -0.3349555 0.5635568 0.755407 -0.131333 0.6419596 0.9135625 -0.01931858 0.4062394 0.8491806 -0.1173819 0.514892 0.9912884 -0.01145005 0.1312115 0.9865449 -0.03007489 0.1607009 -0.898837 -0.250897 0.3593645 0.1419728 -0.5588731 0.8170096 0.2509738 -0.5535663 0.7940886 0.1421601 -0.241785 0.9598597 0.142022 -0.2418318 0.9598683 -0.1835587 -0.2401592 0.9532208 -0.1835128 -0.2401457 0.9532331 -0.1835889 -0.5531327 0.8126127 -0.07907581 -0.5700133 0.8178215 0.09458231 -0.5692272 0.816722 -0.5601907 -0.4738795 0.6794296 -0.4996481 -0.4856945 0.7172536 -0.4996332 -0.2117266 0.8399634 -0.4992344 -0.2116758 0.8402134 -0.7546803 -0.3755575 0.5379726 -0.7540412 -0.3757671 0.5387218 -0.7548794 -0.1604335 0.635939 -0.754434 -0.1604344 0.636467 -0.7590625 -0.08476012 0.6454764 -0.49892 0.09821778 0.8610645 -0.5539904 -0.03765434 0.8316711 -0.1861959 -0.02658349 0.982153 -0.1454389 0.04323393 0.9884222 0.1445149 -0.08491355 0.9858525 0.2901556 0.08608645 0.9530997 0.6260823 0.02275043 0.7794252 0.781708 -0.1694412 0.6001853 0.4751482 -0.5033066 0.7217457 -0.9535741 -0.1725527 0.246824 -0.9191606 -0.2178957 0.3281239 -0.9189185 -0.09653455 0.3824524 -0.9188103 -0.09654968 0.3827089 -0.9205153 -0.06045508 0.3860009 -0.9916964 -0.03151154 0.1246808 -0.9916818 -0.03150904 0.1247971 -0.9919387 -0.004321813 0.1266456 -0.9859384 0.04936426 0.1596521 -1 3.33298e-6 0 -1 9.51583e-6 2.66107e-4 -1 4.25363e-5 0 0.001513719 0 -0.9999989 -1.27582e-4 0 -1 2.46545e-5 0 -1 5.83335e-4 0 -0.9999998 0.999929 -0.01191753 0 0.9999278 -0.0120151 0 -0.9999296 -0.01186984 0 -0.9999285 -0.01196748 0 -0.9829399 -0.179104 -0.04184323 -0.9858747 -0.1674852 0 -0.8346237 -0.5508206 0 0.9722958 -0.1381413 -0.1885677 0.9667919 -0.2555649 0 0.8346279 -0.5508141 0 0.8345335 -0.5509573 0 -0.9858696 -0.1675064 0.001710176 -0.9761671 -0.1884446 -0.1076403 -0.8275529 -0.540777 0.1507195 0.9858645 -0.1675359 0.001731812 0.7348219 -0.4851085 0.4740322 0.8775422 -0.4701396 0.09427857 0.9761645 -0.1884487 -0.1076569 0.7457777 -0.08494842 0.6607568 0.7241795 -0.1118582 0.6804792 0.6634866 -0.3123287 0.6798797 0.6841593 -0.1197592 0.719433 0.3906306 -0.2221137 0.8933495 0.5856754 -0.09558314 0.8048902 0.4527704 -0.08508688 0.8875581 0.284012 -0.08921957 0.9546607 -0.1166579 -0.2398315 0.9637799 0.1085853 -0.08983522 0.9900196 0.02760022 -0.1258093 0.9916705 -0.3651824 -0.2154726 0.9056563 -0.1436799 -0.1050133 0.9840368 -0.5102274 -0.2560582 0.8210374 -0.321073 -0.09465241 0.9423127 -0.7054769 -0.251971 0.6624298 -0.5460544 -0.1145391 0.8298829 -0.8633074 -0.2345247 0.4468765 -0.7472413 -0.1361068 0.6504656 -0.8716138 -0.1580787 0.4640051 -0.9810479 -0.1861899 0.05365103 0.3083781 -0.8580229 0.4107308 0.2891848 -0.866069 0.4077949 0.1160838 -0.8788799 0.4627038 0.07672244 -0.9124587 0.4019115 -0.5249457 -0.8192991 0.2306106 -0.5265806 -0.8260881 0.2007269 -0.4166767 -0.8154314 0.4018111 -0.2535104 -0.7948607 0.5512976 -0.2825536 -0.8076022 0.5176314 -0.04892361 -0.7669106 0.6398866 -0.120137 -0.7980771 0.5904575 0.1451942 -0.7454863 0.6505144 0.04599362 -0.7894594 0.6120774 0.314652 -0.7326967 0.6034483 0.1659604 -0.796827 0.5809681 0.3846784 -0.7146167 0.5842479 0.3056787 -0.7682008 0.5625194 0.4468955 -0.7013726 0.5553025 0.3840456 -0.7545807 0.5320875 0.5124095 -0.6955075 0.5036923 0.4613474 -0.7415843 0.4870435 0.5656548 -0.688805 0.4534119 0.6021772 -0.6452817 0.4701004 0.5855112 -0.608225 0.535947 -0.8356698 -0.548319 0.03165805 -0.8267943 -0.5462588 0.1342111 -0.7917211 -0.5462648 0.2734456 -0.7151331 -0.5409173 0.4427113 -0.5688835 -0.538182 0.6218776 -0.2605466 -0.4821421 0.8364536 -0.3826496 -0.5341994 0.7537974 -0.02823573 -0.4647911 0.8849701 -0.1765255 -0.5290808 0.8300074 0.1894885 -0.4554542 0.8698596 0.01871824 -0.5302188 0.8476543 0.350959 -0.4494093 0.8214982 0.4855184 -0.4524638 0.7480297 0.4596594 -0.5242784 0.7168301 0.6841662 -0.4729781 0.5551652 0.7119262 -0.3903557 0.5837668 -0.5859336 -0.6613369 0.4683111 -0.4188062 -0.7444077 0.5200564 0.8444263 -0.1321446 0.5191168 0.9780074 -0.1333947 0.1603349 0.9050805 -0.1645485 0.3921135 0.5307891 -0.06143498 0.8452743 0.5998713 -0.08926367 0.7951015 0.6671125 -0.1164508 0.7357991 -0.06420671 -0.08063912 0.9946733 0.09324592 -0.1067025 0.989909 0.319482 -0.1364928 0.9377105 0.2376942 -0.102532 0.9659135 0.5238233 -0.1344127 0.8411555 0.6358063 -0.1818537 0.7501196 0.01900476 -0.1818327 0.9831458 -0.2580822 -0.2223592 0.9401862 -0.3332186 -0.1623747 0.9287625 0.05437874 -0.9340834 0.35289 0.06190448 -0.9211966 0.3841416 0.09307157 -0.9564307 0.2767274 -0.3885534 -0.6325364 0.670018 -0.6407239 -0.6420008 0.4210795 -0.624956 -0.7185578 0.3051307 -0.5930621 -0.7315684 0.3362812 -0.5781667 -0.6721589 0.4625212 -0.432167 -0.7379099 0.5183828 -0.5189375 -0.7353101 0.4359161 -0.4373279 -0.6627933 0.6078235 -0.6485819 -0.5723357 0.5017703 -0.5874304 -0.445472 0.6756331 -0.9234088 -0.2592301 0.283048 -0.2598137 -0.3228817 0.9100793 0.4139348 -0.8105905 0.4142476 0.4253708 -0.8547789 0.297343 0.264039 -0.7838324 0.5620411 0.301079 -0.8503313 0.4316112 0.09000009 -0.7612076 0.6422328 -0.08671975 -0.744109 0.6624058 -0.0117917 -0.8338954 0.5517967 -0.2483 -0.7345759 0.6314629 -0.158295 -0.8246352 0.543065 -0.3212713 -0.7632011 0.5606327 0.8694537 -0.4707406 -0.1498453 0.8950267 -0.4326835 0.1082233 0.757444 -0.3708171 0.5373764 0.8287693 -0.4460833 0.3378628 0.5826159 -0.3427926 0.7369206 0.7039849 -0.4552209 0.5451416 0.3811463 -0.322369 0.8664904 0.5305604 -0.4582787 0.7130823 0.1671008 -0.3087041 0.936365 0.3276473 -0.4573241 0.8267418 -0.04511398 -0.3023589 0.952126 -0.2395792 -0.2995315 0.9235165 -0.07533407 -0.4500072 0.8898419 -0.4162253 -0.3030852 0.8572607 -0.2526127 -0.4454764 0.8589166 -0.5628743 -0.3090149 0.7666046 -0.7444348 -0.1162934 0.6574898 -0.4939412 -0.1104784 0.862448 -0.7025429 -0.3105552 0.6403039 -0.4108313 -0.4428932 0.7969086 -0.4718797 -0.50098 0.725499 -0.4290459 -0.5626689 0.7066282 -0.2194947 -0.6522767 0.7255048 -0.2811422 -0.559414 0.7797533 -0.05177277 -0.656172 0.7528333 -0.1096134 -0.5628895 0.8192316 0.1323215 -0.6630764 0.7367638 0.0845831 -0.5700455 0.8172478 0.3265652 -0.6696589 0.6670174 0.2843178 -0.5836845 0.760576 0.5043779 -0.6744468 0.5391888 0.4718955 -0.6020175 0.6441194 0.6441025 -0.6751065 0.3596711 0.6284394 -0.6248016 0.4633433 0.7367968 -0.67098 0.08316504 0.7547044 -0.6289432 0.1866865 0.1887335 -0.9054059 0.3802893 0.2512571 -0.7702778 0.5861245 0.3056126 -0.7680147 0.5628094 0.3836345 -0.752992 0.5346286 0.4209461 -0.7380433 0.5273485 0.4613298 -0.7347406 0.4973239 0.5498821 -0.7042222 0.4491112 0.5753524 -0.7230192 0.3823781 0.735785 -0.6575137 0.1621612 -0.02758598 -0.9939181 0.1066104 -0.4326624 -0.7439554 0.5092481 -0.4514882 -0.7366296 0.5035229 -0.5708802 -0.6974324 0.4332252 -0.5811485 -0.6885517 0.4337778 -0.6440086 -0.6872324 0.336102 -0.3167358 -0.7522653 0.5777329 -0.2332518 -0.7356295 0.6359583 0 -0.7743619 0.632743 -2.27222e-5 -0.9505364 0.3106134 -0.06078892 -0.9432337 0.3265194 -0.6857077 -0.6726843 0.2780303 -0.7298887 -0.6262953 0.2738916 -0.6760898 -0.6741964 0.2972573 0.2162781 -0.7689111 0.6016641 0.2580568 -0.771499 0.5815464 0.2037911 -0.7903723 0.5777378 0.1253503 -0.789418 0.6009215 -0.03491395 -0.7909503 0.6108835 -0.2250411 0.9274718 0.2985844 -0.448152 0.8790638 -0.1625012 0.8123238 0.5131161 -0.2772038 0.4830029 0.8557875 -0.1852996 0.4006736 0.9067038 -0.1317149 0.3763956 0.9198688 -0.1103078 0.886956 0.3785788 -0.2645512 0.9985911 0.007810294 -0.05248832 0.931953 0.05031764 -0.3590707 0.9416013 0.1408184 -0.3058712 0.9728367 -0.07616555 -0.2186037 0.9920018 -0.1157358 -0.05037736 0.9873977 -0.1158051 -0.1078662 0.8442506 -0.5026171 0.1860562 0.8817772 -0.4532389 0.1305508 0.9716231 -0.2303144 0.05388844 0.8061835 -0.3300942 0.4910256 0.6702673 -0.5010315 0.5474571 0.3950405 -0.2265992 0.8902786 0.5395273 -0.5019873 0.6759578 0.1763835 -0.5031977 0.8459794 -0.8029068 -0.3414185 0.4886451 -0.6946026 -0.4987359 0.5184494 -0.8817046 -0.4534092 0.1304497 -0.8442854 -0.5026181 0.1858958 -0.8015056 -0.5019748 0.3249769 -0.9282393 0.2263891 -0.295161 -0.9483422 0.06170779 -0.31119 -0.9016539 0.2576193 -0.3473511 -0.977361 -0.07313781 -0.1985353 -0.4272505 0.9016879 -0.06645363 -0.3885337 0.9130575 -0.1239658 -0.3264811 0.9240833 0.1986966 -0.3981559 0.8629879 0.3110044 -0.3431074 0.927567 0.1479759 -0.3819672 0.9240805 0.01327818 0.04771149 0.9273853 0.3710529 0.1422474 0.9272764 0.3463007 0.224975 0.9274755 0.2986226 0.3704327 0.9010421 0.2256164 0.3430814 0.9275664 0.1480394 0.370929 0.9270683 0.05436998 0.4328533 0.9013362 0.0152015 0.3605214 0.9283957 -0.09003251 0.2885534 0.9532799 -0.08941161 -0.6420764 0.7300558 -0.2340011 -0.6775439 0.7059025 -0.206485 -0.7184971 0.6950814 0.02497732 -0.718492 0.6950866 0.02497762 -0.6141291 0.6950914 0.3737558 -0.3522967 0.6950923 0.6266847 0.352074 0.6950827 0.6268205 0.352079 0.6950891 0.6268106 0.6140027 0.6950882 0.3739693 0.718478 0.695092 0.02523314 0.7184834 0.6950863 0.02523249 0.6789507 0.7060951 -0.2011362 0.6816034 0.7016828 -0.2075045 -0.8420011 0.4522098 -0.2941776 -0.9174339 0.3221163 -0.2335726 -0.9492562 0.3127681 0.03299951 -0.9492556 0.31277 0.03299987 -0.8113867 0.3127685 0.4937891 -0.8113927 0.3127488 0.4937917 -1.48557e-4 0.312747 0.9498366 -1.69339e-4 0.3127679 0.9498296 0.4651473 0.3127674 0.8281393 0.4651592 0.3127694 0.8281318 0.9492468 0.3127608 0.03333652 0.91734 0.3220926 -0.2339738 0.9315093 0.2018446 -0.3025713 -0.9889112 -0.115731 -0.09306561 -0.9920014 -0.1153368 -0.05129069 -0.9937251 -0.1063818 0.03454482 -0.9912826 -0.1247235 0.04245972 -0.8476017 -0.1244599 0.5158304 -0.8475958 -0.1244717 0.5158374 -0.4862345 -0.1244677 0.8649184 -0.4862268 -0.1244515 0.8649252 -1.84216e-4 -0.1244511 0.9922258 -1.73528e-4 -0.124473 0.992223 0.4859117 -0.1244851 0.8650974 0.8474157 -0.1244788 0.5161315 0.8474158 -0.1244589 0.5161361 -0.9288172 0.05564951 -0.3663357 -0.7070965 0 -0.7071171 -0.7071218 0 -0.7070918 -0.2588235 0 -0.9659247 0.2588235 0 -0.9659246 0.7071217 0 -0.7070919 0.7070966 0 -0.7071171 0.9498238 0.03595876 -0.310712 0.9655773 0.02687662 0.2587243 0.7068485 0.02709674 0.7068458 0.2586995 0.02720159 0.9655748 0.6017283 0 0.7987009 -0.2586995 0.02720421 0.9655748 -0.127792 0 0.9918011 0.1276147 0 0.9918238 -0.7068359 0.02710109 0.7068582 -0.6018989 0 0.7985724 -0.9894535 0 0.1448515 -0.9655754 0.02688425 0.2587305 -0.9182483 0 0.3960053 -0.7880725 0 0.6155824 -0.9336899 -0.06148761 0.3527643 -0.888008 -0.008810698 0.4597436 -0.9099643 -1.71235e-4 0.4146869 -0.815638 2.35543e-4 0.5785626 -0.9738512 -0.01302498 0.2268134 -0.9986431 -1.12017e-4 0.0520789 -0.9999991 0 0.001442253 0.2887836 0 0.9573944 0.2574582 0.02167409 0.9660464 0.03902876 -0.00698769 0.9992137 0.006594717 0 0.9999783 -0.1923611 0.004299044 0.9813148 -0.425632 -0.003357291 0.9048902 -0.4286811 -0.001921713 0.9034539 -0.6166539 0.002047061 0.7872318 -0.5427675 -0.03605848 0.8391086 -0.7915952 0.087116 0.604804 -0.6672981 -0.07482159 0.741023 -0.7496201 -0.03212958 0.6610881 -0.8560589 -0.3604239 0.3704833 -0.9804669 -0.1934006 0.03579223 -0.9045272 -0.4213289 0.06567078 -0.9022588 -0.4266552 0.06240683 -0.792072 -0.6078364 0.05618661 -0.6218979 -0.7800781 0.06871265 -0.4221154 -0.9063081 0.02059787 -0.2209836 -0.9750617 0.02051705 -0.4474565 -0.8934745 0.0385487 0.5710233 -0.8138492 0.10762 0.5360841 -0.8424029 0.05450987 0.7693951 -0.636312 0.05602002 0.8359134 -0.5321441 0.1344304 0.8845048 -0.4610745 0.0711438 0.9774708 -0.1723653 0.1218243 0.9769529 -0.1701507 0.1288869 -0.2329915 0.002949476 0.9724743 -0.3704215 -0.01064854 0.9288027 -0.2659964 0.01061773 0.9639156 -0.2387219 0.002776443 0.971084 -0.3667865 -0.004981756 0.9302919 -0.3274768 -0.02586686 0.9445052 -0.3482263 -0.01751053 0.9372469 -0.4836033 -1.47124e-6 0.8752874 -0.4826824 0.001000761 0.875795 -0.4235888 -7.68294e-4 0.9058543 -0.3955515 -0.005382061 0.9184281 0 -7.62939e-4 0.9999998 0 -7.6294e-4 0.9999998 0 0.01934748 0.9998129 0.001106381 0.08196479 0.9966347 0.002311229 0.0949316 0.9954811 -0.001431345 0.03744268 0.9992979 0.4271762 -0.009436488 0.9041191 0.4023627 -0.01783287 0.9153068 0.380001 -0.02621996 0.9246144 -0.1951996 -6.3181e-5 0.9807636 0.003326714 8.08918e-4 0.9999942 0 -0.002331018 0.9999974 0.2053384 2.68714e-4 0.9786911 0.2387363 0.004386126 0.9710746 0.2494046 0.002140223 0.968397 0.3207079 -0.002153396 0.9471758 0.3667666 -0.01213812 0.9302338 0.4829937 0.02946078 0.8751282 0.482605 0.001112282 0.8758374 0.5721187 -0.001999676 0.8201685 0.5222118 0.01347213 0.8527094 0.5518402 0.006364881 0.8339257 0.691101 1.64792e-5 0.7227583 0.6819847 0.003219842 0.7313594 0.6236229 -3.94619e-4 0.7817253 0.5882084 0.001006662 0.8087087 -0.6321122 -0.003908514 0.7748671 -0.6815337 0.006247699 0.7317602 -0.7113313 0 0.702857 -0.56901 0.003546297 0.8223231 -0.5465408 0.007440328 0.8373994 -0.5716109 0.001377284 0.8205237 -0.5204926 -2.17099e-4 0.8538662 -0.4813616 0.001231908 0.8765212 1 -2.80261e-6 0 1 0 -9.43905e-7 1 1.0189e-4 2.89373e-6 3.90484e-5 -1 -5.88254e-5 1.94621e-4 -1 8.6227e-5 1 -4.31183e-6 0 1 5.93082e-6 0 1 -2.61154e-6 0 1 1.44726e-6 0 1 1.86343e-6 0 1 5.84113e-7 0 1 2.9056e-7 0 1 -2.80269e-6 0 1 -1.79263e-5 0 1 1.459e-4 0 1 -1.468e-4 0 -1 -1.29046e-6 0 -1 2.44994e-6 0 0 -1 0 0 -1 0 0 -1 0 -1 -7.35128e-7 0 -1 -1.22526e-6 0 -1 3.09075e-7 0 -1 7.26491e-6 0 -1 -4.20851e-7 0 -1 2.60276e-7 0 -1 6.49989e-7 0 -1 7.06662e-7 0 -1 5.72679e-6 0 -1 -1.05219e-5 0 -1 2.62109e-5 0 -1 -2.24336e-5 0 -0.7101083 0 0.7040925 -0.8269445 0 0.5622838 -0.5738846 -0.704185 0.418067 -0.5777199 0.5999701 0.5534218 -0.6961895 0.1475797 0.7025244 -0.610419 -0.1844869 0.7702942 -0.6090812 -1.15942e-5 0.7931081 -3.1162e-5 1 -1.76426e-5 3.8021e-5 1 -1.51025e-4 -0.6441815 0.7606397 0.0803582 -0.7070807 0.7070778 0.008828282 -0.7768822 0.6296151 0.006226301 -0.856146 0.5167341 -4.09482e-5 -0.9659255 0.2588196 5.36992e-4 -0.9324787 0.3565899 0.05768144 -0.9861636 0.1657546 0.00260967 0.2581059 0.9632987 0.07373625 0.1827531 0.98261 0.03284859 0.0559113 0.9984357 -4.93025e-5 -0.2588207 0.9659254 2.41881e-4 -0.1085086 0.9777986 0.1792647 -0.2391921 0.9673169 0.08417361 0.8583107 0.5131304 -2.60878e-5 0.7736148 0.6336351 0.005182683 0.7063023 0.7062879 0.04790222 0.9845656 0.1749942 0.002766668 0.7071021 -0.7071115 0 0.7071092 -0.7071045 0 0.2588217 -0.9659252 0 0.2588183 -0.9659261 0 -0.2588217 -0.9659252 0 -0.2588189 -0.9659259 0 -0.7071033 -0.7071103 0 -0.707108 -0.7071056 0 -0.9238781 -0.3826869 0 -0.965651 -0.258746 0.02384555 -0.9999297 0.01186078 0 0.9999292 0.01190841 0 0.9657706 -0.2587826 0.017861 0.9801641 -0.1949595 0.03562676 0.9238814 -0.382679 0 0 -0.9987482 -0.0500214 8.27506e-5 -0.9987558 -0.04986888 1.38402e-5 0 1 2.07602e-5 0 1 -2.07602e-5 0 1 -3.46003e-6 0 1 3.46003e-6 0 1 0.2162943 0 0.9763283 -0.2164382 0 0.9762964 -0.2162916 3.91355e-4 0.9763288 0.574184 0 0.8187263 0.5741112 0 0.8187775 0.8207608 0 0.5712721 0.8207983 0 0.5712183 0.9663845 0 0.2571014 0.9663823 0 0.2571097 -0.9658438 0 0.2591251 -0.9658506 0 0.2590998 -0.8189677 0 0.5738398 -0.8189885 0 0.5738101 -0.5746778 0 0.8183798 -0.57334 -3.28944e-4 0.8193175 0.6819913 0 0.7313603 0.9217363 0 0.3878172 -0.9217385 0 0.3878121 -0.6819827 0 0.7313684 -0.6819903 0 0.7313613 -0.3508558 0 0.9364295 0.1502819 0 0.9886432 0.6132866 0 0.7898606 0.8153597 0 -0.5789549 -0.5435652 0 -0.839367 0 -1 7.37546e-7 -1.72451e-6 -1 0 0 -1 2.92203e-7 2.07814e-7 -1 0 2.20789e-7 -1 4.79421e-7 0 -1 -2.37329e-7 0 -1 8.84098e-7 0 -1 -2.47364e-7 0 -1 -6.51525e-7 0 -1 -3.04139e-6 0 -1 4.55209e-7 0 -1 -3.75154e-7 0 -1 4.40753e-6 -0.9659277 0 -0.2588126 -0.7071065 0 -0.7071071 -0.7070963 0 -0.7071173 -0.258835 0 -0.9659216 -0.2587959 0 -0.9659321 0.2587957 0 -0.9659321 0.2588351 0 -0.9659215 0.7070976 0 -0.707116 0.965927 0 -0.2588149 0.9659255 0 0.2588201 0.7071078 0 0.7071058 0.258835 0 0.9659216 0.2587959 0 0.9659321 -0.2587957 0 0.9659321 -0.2588351 0 0.9659215 -0.7071065 0 0.7071071 -0.7071068 0 0.7071068 -0.9659262 0 0.2588177 -0.9659262 0 0.2588179 -0.9659262 0 -0.2588177 -0.2922877 -0.8814364 0.3709958 -0.1937514 -0.8235141 0.5331839 -0.3308092 -0.611065 0.7191418 -0.3880459 -0.4780495 0.7879652 -0.4407333 -0.3857128 0.810543 -0.2676678 -0.8616387 0.4311992 -0.2961609 -0.7077509 0.6413872 -0.3209444 -0.6553854 0.6837139 0.5195691 -0.7323437 0.4401371 -0.4576467 -0.485493 0.7448866 -0.4156329 -0.509195 0.7536378 -0.3486559 -0.5237676 0.777243 -0.8972305 -0.2237796 0.3806578 -0.708533 -0.3813979 0.5937312 -0.6762689 -0.3906167 0.624563 -0.5066975 -0.4571485 0.7309397 -0.04159349 -0.6375239 0.769307 -0.1597617 -0.5795711 0.799108 0.5203682 -0.7009665 0.4877121 0.45967 -0.6986286 0.5482899 0.2894267 -0.7548887 0.5885366 0.2859697 -0.7534452 0.5920656 0.2070425 -0.7311907 0.6499952 -0.07047414 -0.8964574 0.4374901 0.2869781 -0.8594663 0.4230382 0.3922251 -0.8340696 0.3879273 0.4514044 -0.8090997 0.3762871 0.5908856 -0.7488351 0.3001671 0.7231339 -0.6261897 0.2914857 -0.4140209 -0.8172802 0.4007991 -0.2989531 -0.8654401 0.4020454 -0.8014565 -0.5461459 0.2437054 -0.7084895 -0.6297155 0.3185924 -0.6308886 -0.7061178 0.3215233 -0.4438809 -0.8090264 0.3852869 -0.7092708 -0.5168675 0.4793568 -0.4141997 -0.6673616 0.6189242 -0.415345 -0.6672964 0.6182267 -0.07051652 -0.7317243 0.6779432 -0.0707786 -0.7317761 0.67786 0.1255019 -0.7278163 0.6741905 0.1703518 -0.6807864 0.7123975 0.4159756 -0.5039117 0.7569922 -0.1542685 -0.6420947 0.7509432 0.999777 -0.01844036 0.01029187 0.9605577 -0.234834 0.1489362 0.9891217 -0.1463094 -0.0152294 0.883128 -0.4238226 0.2011455 0.8080081 -0.5446055 0.2247838 0.7093616 -0.6341043 0.3077626 0.6660916 -0.6798411 0.3068194 0.5883172 -0.7400797 0.3258295 0.4670893 -0.809231 0.3563325 0.4149104 -0.8239226 0.3860062 0.2642551 -0.88555 0.382061 0.07049679 -0.9070867 0.4149987 0.03274148 -0.9149894 0.4021474 -0.2082057 -0.8954064 0.3935707 -0.2876629 -0.8662821 0.4084182 -0.3859505 -0.8443992 0.3715268 -0.6097689 -0.7445545 0.2716993 -0.4907042 -0.7975369 0.3509195 -0.5595369 -0.7001013 0.4435952 -0.4351313 -0.7181234 0.5431019 -0.2362786 -0.7764106 0.5842595 -0.2889636 -0.7623279 0.5790995 -0.1389094 -0.7294035 0.6698319 -0.152095 -0.6270425 0.7639929 0.3247708 -0.5239109 0.787427 0.1206853 -0.5827371 0.8036496 0.07124578 -0.6233674 0.7786765 -0.008332729 -0.6171438 0.7868063 -0.1057674 -0.6127579 0.7831609 0.8830564 -0.2501624 0.3970268 0.7229121 -0.3503187 0.5955459 0.707882 -0.3639582 0.6053408 0.4624413 -0.4676551 0.7532906 0.501767 -0.4504159 0.7384819 -0.1498391 -0.7288879 0.668035 0.07014375 -0.7353978 0.6739956 0.07040774 -0.7353128 0.6740607 0.412596 -0.6714544 0.6155596 0.4143918 -0.6704198 0.6154811 0.70629 -0.5214822 0.4787596 0.7082917 -0.5193542 0.4781151 0.8816134 -0.3472045 0.3196983 0.8827579 -0.3452399 0.3186662 0.9795771 -0.1477447 0.1363827 0.994014 -0.02089798 0.1072363 0.9618362 -0.1630295 0.2197559 0.9672648 -0.1049735 0.2310399 0.1968929 -0.8848494 0.4222261 0.1975533 -0.8473657 0.4928935 0.198725 -0.9046102 0.3770795 0.2436822 -0.7890273 0.5639637 0.2586135 -0.8322697 0.4903532 0.273497 -0.7612082 0.5880148 0.3147403 -0.6684343 0.6738948 0.3162385 -0.6018824 0.7333014 0.4197958 -0.3697234 0.8289006 0.405321 -0.3960708 0.8239192 0.3421464 -0.5159761 0.7853053 0.3780855 -0.6087727 0.6974576 0.4160929 -0.6308736 0.6548781 0 -1 -9.59789e-7 0 -1 1.09564e-6 0 -1 -2.03451e-6 0 -1 4.12505e-7 0 -1 -1.26087e-6 0 -1 2.23636e-6 0 -1 -1.96936e-6 0 -1 3.73413e-6 0 -1 -1.39161e-6 0.6054105 -0.7193112 0.3406899 0.4317935 -0.8561711 0.2837701 -0.1776665 -0.812146 0.5557458 -0.1957454 -0.8220618 0.5346946 -0.1151224 -0.8859436 0.4492782 -0.1188914 -0.8901901 0.4398027 0.0878188 -0.910237 0.4046685 0.1007194 -0.9012429 0.4214462 0.09979289 -0.8994953 0.4253818 0.1021885 -0.9014419 0.4206661 -0.1168611 -0.7270137 0.6766052 0.01145905 -0.8212065 0.5705161 0.1899964 -0.8427808 0.5036089 0.1846045 -0.8361652 0.5164777 0.3383932 -0.8686107 0.361947 0.3356205 -0.84494 0.4164556 0.4300069 -0.8437431 0.3212347 0.4415208 -0.8463315 0.2979636 0.6341808 -0.7289466 0.2577822 0.584593 -0.6813137 0.4405255 0.6394239 -0.7119134 0.2903731 0.6763992 -0.7243292 0.1335344 -0.2676344 -0.4416937 0.8563169 -0.2246572 -0.4907895 0.8418164 -0.08962458 -0.5589933 0.8243143 -0.007700324 -0.5650078 0.8250498 0.03675407 -0.6112789 0.7905614 0.1426053 -0.6319153 0.761805 0.1518551 -0.6405594 0.7527442 0.2820208 -0.6932855 0.6631889 0.2479313 -0.644858 0.7229718 0.2987688 -0.6875941 0.6617791 0.2402213 -0.7423424 0.625477 0.0904839 -0.6932519 0.7149927 0.2001854 -0.8198825 0.5363941 -0.100565 -0.7098841 0.6971021 -0.5487723 -0.8042544 0.2280873 -0.4216923 -0.6782166 0.6018287 0.08563077 -0.5722729 0.8155803 -0.2920604 -0.9052797 0.3084956 -0.2923654 -0.9053264 0.3080691 -0.1818085 -0.8741902 0.4502635 -0.3397849 -0.8632064 0.3733914 -0.03175228 -0.8642919 0.5019875 0.4603459 -0.380275 0.8021675 -0.1428212 -0.9219775 0.3599442 -0.1437144 -0.9218704 0.3598628 -0.1427595 -0.9219942 0.3599259 0.09348583 -0.9019348 0.4216325 0.0934953 -0.9019517 0.4215944 0.0824638 -0.9516562 0.295889 0.7089752 -0.5439577 0.4488476 0.7091604 -0.54367 0.4489039 0.1841359 -0.8563733 0.4824092 0.1833605 -0.8558545 0.4836238 0.2463687 -0.6597479 0.7099543 0.2682718 -0.6567168 0.7048073 0.1676917 -0.5475132 0.8198224 0.1630306 -0.4815628 0.8611147 0.1183922 -0.3499155 0.9292699 0.3094943 -0.5312856 0.7886374 -0.1366717 -0.6336074 0.7614872 -0.1124455 -0.610206 0.7842223 -0.4745866 -0.6919032 0.5440933 -0.6909076 -0.7143477 0.1111485 -0.6788694 -0.7213392 0.1371355 -0.6848385 -0.71461 0.1425796 -0.6461209 -0.7077319 0.2857334 -0.6566995 -0.7026278 0.2739706 -0.5580733 -0.7945999 0.2390927 -0.563759 -0.801567 0.1991639 -0.5830237 -0.7525193 0.3062649 -0.5572121 -0.7809812 0.282105 -0.5655125 -0.6968181 0.4411803 -0.5946351 -0.657723 0.4623955 -0.595705 -0.6699666 0.4430354 -0.313521 -0.8922153 0.3250488 -0.3488886 -0.8594394 0.3736855 -0.2331066 -0.8220897 0.5194514 -0.07046258 -0.8046814 0.5895107 -0.04897069 -0.8265421 0.5607407 -0.1428118 -0.921947 0.3600261 -0.3581978 -0.6229621 0.6954226 -0.4491061 -0.4746908 0.7569495 -0.3274336 -0.6607254 0.6754474 -0.3379956 -0.749068 0.5697861 -0.347437 -0.7378819 0.5786345 -0.3559633 -0.8345527 0.4204902 -0.4033093 -0.7823264 0.4746653 -0.3685188 -0.8777512 0.306181 -0.09539473 -0.5837552 0.8063062 -0.09848076 -0.590984 0.8006494 -0.05519068 -0.6439664 0.7630606 -0.07102674 -0.7742128 0.6289274 -0.03876072 -0.8063654 0.5901462 0.06925183 -0.7255127 0.6847157 0.1443349 -0.8002984 0.5819708 0.2435477 -0.7158206 0.6544352 0.1700744 -0.8445752 0.5077082 0.505741 -0.8322586 0.2270947 0.2358707 -0.9687023 -0.07733613 0.02136665 -0.9959197 0.08767873 0.09730923 -0.9928584 0.06901472 -0.07270449 -0.98289 0.169238 0.1812562 -0.9812577 0.06541979 0.4038981 -0.8824486 0.2411448 0.4108694 -0.8529508 0.3219647 0.5485031 -0.7975512 0.2511104 0.0794301 -0.9033576 0.421469 -0.005031704 -0.8430025 0.5378861 0.3398081 -0.9336338 0.1133952 0.4339542 -0.8995434 0.0500558 0.5054176 -0.8284039 0.2414541 -0.1408789 -0.9428305 0.3020328 -0.03431326 -0.9966986 0.07358455 -0.06311494 -0.9857727 0.1557846 -0.09156209 -0.9747706 0.2035652 -0.1275016 -0.9531998 0.2741413 -0.04251223 -0.9379941 0.3440347 0.108046 -0.9048234 0.4118503 0.3088976 -0.8665034 0.3921152 0.3080726 -0.8678898 0.3896907 0.3038569 -0.8808428 0.363025 0.1147857 -0.9010605 0.4182276 0.1289668 -0.9015986 0.4129012 0.1870047 -0.9276126 0.3233641 0.1738282 -0.9310281 0.3208903 -0.04641801 -0.926386 0.3737038 -0.08995783 -0.8879584 0.4510408 -0.06644833 -0.9014692 0.4277124 -0.04723566 -0.9169801 0.3961265 -0.04208767 -0.9245235 0.3787943 -0.03797346 -0.9265189 0.374327 0.02040016 -0.95501 0.2958712 -0.01413625 -0.9423807 0.3342436 0.07852071 -0.9843708 0.157635 0.02637076 -0.9363902 0.3499687 -0.3020173 -0.9034107 0.3043597 0.1467946 -0.9431554 0.2981765 -0.01267677 -0.9177882 0.3968681 -0.2381426 -0.9141606 0.3280223 -0.1986326 -0.9185386 0.3418067 -0.2894535 -0.8795257 0.3776921 -0.2020882 -0.908288 0.3662968 -0.08403277 -0.98306 0.1628852 -0.01805931 -0.9808146 0.1941047 -0.02348858 -0.8871617 0.4608608 -0.06641876 -0.9215493 0.382538 -0.06637191 -0.9215817 0.3824684 -0.01261597 -0.917777 0.3968961 0.07521146 -0.874394 0.479352 0.03647601 -0.9118202 0.4089663 -0.2382729 -0.9141553 0.3279426 -0.159403 -0.8847512 0.4379566 -0.03556364 -0.9547483 0.2952812 -0.06958144 -0.9627898 0.2611407 0.03961509 -0.9100102 0.412689 0.03673905 -0.9120627 0.4084016 0.03618127 -0.9118804 0.4088583 -0.02995193 -0.9045485 0.4253175 0.1113302 -0.9646813 0.2387375 0.03068691 -0.9945837 0.09930545 0.0733956 -0.984804 0.1573982 0.3346469 -0.8170119 0.4695776 0.5324412 -0.6071044 0.5898565 0.6188136 -0.2744346 0.7360403 0.6836467 -0.153711 0.7134425 0.4615972 -0.5173088 0.7206384 0.4979169 -0.3773618 0.7808179 0.5049774 -0.2435218 0.828067 0.5114083 -0.2133764 0.8324254 0.1737344 -0.968772 0.1769104 0.271127 -0.9060305 0.3249602 0.3503894 -0.8008243 0.4857034 0.3917264 -0.7965036 0.4605784 0.4149844 -0.7318322 0.5405642 0.4539651 -0.7271135 0.5149968 0.5012527 -0.6120999 0.6116204 0.4265834 -0.6637666 0.614362 0.4541746 -0.5336156 0.7134282 0.5024423 -0.5286461 0.6841675 0.5079677 -0.4397363 0.7406761 0.561207 -0.433119 0.7053046 0.6127569 -0.2835633 0.7376455 0.3148766 -0.8875688 0.3362655 0.281832 -0.8845403 0.371698 -0.611026 -0.7262156 0.3150529 -0.3784258 -0.884704 0.2722 -0.165483 -0.9807173 0.103967 -0.4826831 -0.8187978 0.3107846 -0.1245867 -0.9918174 0.02786415 -0.1132071 -0.9904406 0.07881456 -0.6439293 -0.7519236 0.141301 -0.6257103 -0.76229 0.1655322 -0.6321169 -0.7560896 0.1695784 -0.5223855 -0.8186566 0.2385682 -0.4765579 -0.8309497 0.2870806 -0.5032927 -0.8640791 -0.007987976 -0.4900074 -0.8695285 0.06174993 -0.29037 -0.9121593 0.2892245 -0.3075407 -0.9157778 0.2583985 -0.1076228 -0.9140748 0.3910045 -0.1445427 -0.9396934 0.3099737 -0.144531 -0.9396939 0.3099775 -0.1445424 -0.9396938 0.3099731 -0.1445431 -0.9396928 0.3099755 -0.1445451 -0.9396927 0.3099751 -0.144537 -0.9396937 0.3099757 -0.1459318 -0.9402586 0.3076003 -0.144464 -0.9397595 0.3098104 -0.1446225 -0.9395766 0.3102905 -0.1445506 -0.9396945 0.3099666 -0.1445571 -0.9396843 0.3099948 -0.1445136 -0.9396889 0.3100013 -0.1445462 -0.9396923 0.3099754 -0.1445369 -0.9396943 0.3099738 -0.1445453 -0.9396924 0.3099759 -0.09901291 -0.9385171 0.3307298 -0.01958054 -0.9629988 0.2687939 0.09902578 -0.9384981 0.3307797 0.06952083 -0.9469415 0.3137972 0.02490597 -0.9394009 0.3419148 -0.07560718 -0.9370021 0.3410435 -0.07562232 -0.9369965 0.3410556 0.1445125 -0.9396967 0.309978 0.1438955 -0.9398491 0.309803 0.1445428 -0.9396943 0.3099713 0.1445327 -0.9396932 0.3099792 0.1445431 -0.939693 0.3099747 0.1445451 -0.9396921 0.3099763 0.144282 -0.9397625 0.3098856 0.144537 -0.9396991 0.3099592 0.1445043 -0.9396967 0.3099815 0.144546 -0.9396924 0.3099752 0.1445508 -0.9396916 0.3099759 0.1445441 -0.9396922 0.3099771 0.144522 -0.9396969 0.309973 0.144711 -0.9396474 0.310035 0.1447058 -0.9396501 0.3100293 0.003624558 0.9996088 -0.02773612 -0.06783872 0.9915317 -0.1107385 -0.06783652 0.9915322 -0.1107347 -0.03774404 0.9914518 -0.1248954 -0.03774344 0.9914515 -0.1248981 -0.01674562 0.9916287 -0.1280313 -0.04155951 0.9921848 -0.1176524 0 0.9838478 -0.1790069 0.007755577 0.9867666 -0.1619623 0.04075139 0.9913896 -0.1244429 0.03774416 0.9914514 -0.1248986 0.03774344 0.9914515 -0.1248979 0.06783676 0.9915321 -0.1107351 0.06783825 0.9915316 -0.1107394 -0.1256685 0.9907982 -0.0502631 -0.1390931 0.9898258 -0.02996784 -0.2948299 0.9553067 -0.02155065 -0.1050757 0.9907993 -0.08529925 -0.1046943 0.9908447 -0.08524054 -0.1330405 0.9890947 -0.06318169 -0.1389228 0.9881107 -0.06586158 0 1 3.97114e-7 -0.009518325 0.9999503 -0.002977609 -0.0121147 0.9998142 0.0149936 0.1901711 0.9711439 0.143925 0 1 1.70272e-6 0 1 6.65127e-7 0 1 9.67339e-7 0 0.9999898 0.00453782 0 1 -7.66835e-7 0.003809869 0.9999926 7.02104e-4 -0.001161158 0.9996214 -0.02749246 -0.001111328 0.9999781 0.006531238 -0.003419697 0.9999574 0.008583247 0 1 0 0 1 7.66617e-7 0 1 -1.1771e-6 1.55393e-4 0.999714 0.02391612 -0.001310229 0.9999877 -0.004788398 6.28048e-4 0.9998278 0.01855307 0 1 -1.30486e-6 0 1 -3.80819e-7 0 1 2.62055e-7 0 1 6.39645e-7 0 1 -5.31825e-7 0.4640657 -0.852559 0.2403878 0.4506598 -0.859877 0.2398277 0.5236477 -0.8390065 0.1478558 0.5547729 -0.8201878 0.1397107 0.1887722 -0.9809237 0.04641163 0.1859001 -0.9818048 0.03873622 0.2061035 -0.9700973 0.1281909 0.1681694 -0.9837158 0.06342142 0.05931967 -0.9820414 0.1790974 0.08775693 -0.9809224 0.1734652 0.08734548 -0.9816498 0.1695123 0.1343391 -0.9816094 0.1356325 0.02072483 -0.9723221 0.2327237 0.02968221 -0.9816098 0.1885771 -0.01679831 -0.9819037 0.1886345 -0.03289067 -0.9773708 0.2089608 -0.05209702 -0.9838855 0.1710417 -0.09444928 -0.977868 0.1866911 -0.09411054 -0.9821144 0.1630784 -0.1359048 -0.981174 0.1372138 -0.1424142 -0.9781002 0.1517836 -0.1690788 -0.9836109 0.06262677 -0.1888169 -0.9809145 0.04642111 -0.1859186 -0.9818057 0.03862398 -0.5243517 -0.839169 0.1443975 -0.5469041 -0.8257932 0.1377011 -0.4600875 -0.8552884 0.2383302 -0.1881211 -0.9772993 0.09744954 -0.2330174 -0.8564772 0.4605973 -0.3488405 -0.8288634 0.4373739 -0.347772 -0.8693479 0.3511254 -0.4587917 -0.8564669 0.2365897 0.3562922 -0.8399474 0.4093218 0.2463602 -0.8379561 0.4869664 0.08485001 -0.837956 0.5391015 0.08486396 -0.8379496 0.5391092 -0.03928703 -0.8403351 0.5406419 -0.0768758 -0.869247 0.4883645 -0.1395424 -0.8285934 0.5421817 -0.2330429 -0.8548325 0.4636295 -0.7765697 0.6297011 0.02039474 -0.9086408 0.4105286 0.07640784 -0.9667363 0.2078063 0.1491222 -0.9691901 0.1874358 0.1598076 -0.703499 -0.6249172 0.3384785 -0.8729051 -0.3820534 0.3034338 -0.8728396 -0.3821631 0.3034836 -0.9787935 0.06921219 0.1928035 -0.8386172 0.5245883 0.1467263 -0.9279676 0.2261648 0.2961854 -0.9258874 0.2607639 0.273377 -0.93383 -0.06700992 0.3513848 -0.9274765 -0.09418833 0.361823 -0.8590564 -0.3269199 0.3938854 -0.6805509 -0.6009993 0.4191067 -0.5167746 -0.5581107 0.6491969 -0.5848246 -0.6364575 0.5028939 -0.2415559 -0.9021542 0.3574472 -0.1860713 -0.8930951 0.4095835 -0.512723 -0.4232064 0.7470017 -0.9889611 0.1386331 0.05231738 -0.9897547 -0.03158926 0.1392396 -0.9222984 -0.163658 0.3501168 -0.9056669 -0.2026851 0.3724063 -0.5244155 -0.620739 0.5828135 -0.7407438 -0.4208115 0.5236568 -0.6690112 -0.4460075 0.5945598 -0.8594298 -0.40051 0.3177613 -0.6966935 -0.6135761 0.3716753 -0.7101171 -0.5933648 0.3790143 -0.9305598 0.3635386 -0.04356884 -0.9737372 0.227167 0.01520437 -0.9886471 0.1261666 0.08160281 -0.9889851 0.1235919 0.08144658 -0.9813417 0.03227186 0.1895446 -0.8842739 -0.2610167 0.3872082 -0.9208957 -0.152947 0.3585505 -0.8037733 -0.3539671 0.4781796 -0.7956892 -0.2807576 0.5367065 -0.7910453 -0.2870633 0.5402242 -0.9205473 0.3899629 0.02284264 -0.9800586 0.1848137 0.07299989 -0.9466036 0.3111671 0.08436024 -0.9872951 0.05576407 0.1487913 -0.9341975 -0.2389367 0.2649233 -0.8495883 -0.374821 0.3710917 -0.8855064 -0.2654831 0.3813098 -0.752185 -0.4594895 0.4723211 -0.4593622 -0.6594465 0.595077 -0.6742009 0.09275186 0.7327007 -0.9752116 -0.04596722 0.216447 0.1526108 -0.7888523 0.5953337 -0.6550824 -0.5118376 0.5557783 -0.4609481 -0.6409201 0.6137983 -0.2361192 -0.7373135 0.6329427 0.006587922 -0.7604449 0.6493691 0.2532518 -0.8235605 0.5075544 0.2646417 -0.8405464 0.4727016 -0.8512878 -0.3050486 0.4269127 -0.7967163 -0.3834475 0.467131 -0.6525517 -0.5128107 0.5578545 -0.9024946 -0.2263173 0.3664481 -0.8730589 -0.264223 0.4098225 -0.8481642 -0.202324 0.489574 -0.7640244 -0.2038157 0.6121485 -0.4939711 -0.3028632 0.8150255 -0.3928997 -0.3173063 0.8631029 -0.02638912 -0.1978425 0.9798786 0.7066498 -0.1574506 0.6898227 0.6427717 -0.2586022 0.7210892 0.6425587 -0.2169574 0.7348796 0.6184342 -0.4142856 0.6677625 0.2404976 -0.900913 0.3612711 0.2862736 -0.8851976 0.3667052 0.04674977 -0.7677993 0.6389828 0.08385962 -0.7501636 0.6559132 0.121169 -0.7616901 0.6365111 0.195599 -0.7405896 0.6428593 0.5130273 -0.6033956 0.6105055 0.5496538 -0.4759413 0.6865571 0.1850478 -0.4904698 0.8515849 0.1636119 -0.4671745 0.8688954 -0.02671766 -0.5205338 0.8534229 -0.1971547 -0.5640817 0.8018366 -0.2268962 -0.5521006 0.8023111 -0.593728 -0.3878482 0.7050255 -3.65796e-5 -0.7740108 0.6331725 0.001716494 -0.7739255 0.6332744 0.2057045 -0.8184962 0.5364231 0.2078155 -0.8627276 0.4609921 0.19497 -0.882911 0.4271475 0.2216699 -0.8805913 0.4188333 0.2039998 -0.8980235 0.3897924 0.2387223 -0.8899041 0.3886932 0.3290619 -0.7483704 0.5758994 0.3910896 -0.7512359 0.5316894 0.4189705 -0.7384396 0.5283661 0.3121882 -0.8456845 0.4328466 0.3404983 -0.8070707 0.4823876 0.2535857 -0.9004704 0.3533375 0.2036147 -0.933404 0.2954628 0.2126892 -0.9232912 0.3198387 0.2288893 -0.9559066 0.1839902 0.4935086 -0.7956141 0.3513511 0.5026813 -0.7800334 0.3726388 0.6880414 -0.547898 0.4758222 0.7194252 -0.4987061 0.4834457 0.7655959 -0.3632956 0.530923 0.8203361 -0.1262072 0.5577817 0.819126 -0.1612454 0.5504842 0.7474868 -0.1616685 0.6443033 0.6946267 0.05048477 0.7175967 0.5344619 -0.4634124 0.7068235 0.2305695 -0.9502224 0.2095599 0.2564008 -0.9396255 0.2266334 0.4422973 -0.7951185 0.4149215 0.6260362 -0.4984388 0.599698 0.6260359 -0.4984387 0.5996983 0.7126939 -0.1611358 0.6827172 0.6032067 -0.1615014 0.7810629 0.6001278 -0.1708479 0.7814458 -0.3741881 -0.8286132 0.4163935 -0.454266 -0.6570281 0.6016283 -0.7000538 -0.1612831 0.6956382 -0.677221 -0.2786636 0.6809687 -0.6306325 -0.4061164 0.6613413 -0.5360039 -0.6138258 0.5795841 -0.5409182 -0.6049735 0.584307 -0.4339237 -0.7464269 0.5045365 -0.2061492 -0.9626946 0.1752756 -0.3889798 -0.7647715 0.5136336 -0.4950352 -0.5081068 0.7048175 -0.4460949 -0.6332458 0.632455 -0.5339798 -0.1680176 0.8286348 -0.5364645 -0.1351996 0.8330228 -0.5049034 -0.221229 0.8343443 -0.4422245 -0.7395117 0.5075037 -0.6416547 -0.2327188 0.730836 -0.6302099 -0.2764266 0.7255508 -0.519924 -0.6120041 0.5959279 -0.5246193 -0.6043138 0.5996494 -0.2810211 -0.8848963 0.3714643 -0.3782733 -0.8077415 0.452176 -0.3857827 -0.8119946 0.4379916 -0.4000012 -0.8134288 0.4222945 -0.3225858 -0.8873445 0.3294816 -0.3021725 -0.8894728 0.3428265 -0.2837917 -0.9056977 0.314919 -0.5551952 -0.3774481 0.7411419 -0.6227185 -0.2861745 0.7282348 -0.5793734 -0.2888653 0.762157 -0.3601489 -0.8296836 0.4265186 -0.04399925 -0.9957532 -0.0808683 -0.0439701 -0.9957538 -0.08087635 -0.4975469 -0.4631693 0.7334312 -0.5305584 -0.341684 0.7757318 -0.5758924 -0.3362098 0.7451919 -0.5430841 -0.5022893 0.6728783 -0.502007 -0.6130896 0.6100083 -0.4878929 -0.6529077 0.5793722 -0.4200133 -0.7793068 0.4650481 -0.3836439 -0.7833517 0.4890578 -0.3268992 -0.8623746 0.3865841 -0.385351 0.7170776 0.580779 -0.3853559 0.7170649 0.5807915 -0.4510914 0.5513899 0.7017733 -0.4976035 0.3642958 0.7871972 -0.5001237 0.333175 0.7992939 -0.5111524 -0.1156333 0.8516761 -0.5111438 -0.11561 0.8516845 -0.4170936 -0.5425878 0.7291307 -0.408898 -0.5708338 0.7120051 -0.269962 -0.8648291 0.4233099 -0.6077233 -0.6053967 0.5139722 -0.8432655 0.3040034 0.4432668 -0.8432597 0.3040021 0.4432784 -0.8469998 -0.05046039 0.5291929 -0.8194748 -0.1687775 0.5477002 -0.7861033 -0.2865168 0.5476768 -0.6077167 -0.6053971 0.5139794 -0.2337556 -0.86131 0.4511135 -0.2337579 -0.8613146 0.4511036 -0.2699688 -0.8648403 0.4232825 -0.5200552 -0.5813476 0.6257617 -0.5200651 -0.5813398 0.6257606 -0.6863884 -0.1328914 0.7149901 -0.6907581 0.3440534 0.6359879 0 0.6934965 0.7204601 0.1549938 -0.8414016 0.5177069 -0.03904712 -0.843344 0.5359537 0.2066282 0.6935029 0.6901874 0.2702642 0.3347044 0.9027349 0.2702584 0.321847 0.9074002 0.2847561 0.1193307 0.9511436 0.2848995 -0.1150296 0.9516305 0.2848899 -0.1150225 0.9516342 0.2431281 -0.5304426 0.812108 0.243124 -0.5304418 0.8121098 -0.1998428 0.7172892 0.6675022 -0.2038017 0.6937081 0.6908212 0 0.6935024 0.7204543 0 0.3217881 0.9468118 0 0.3217862 0.9468123 0 -0.1150243 0.9933627 0 -0.1150223 0.993363 0 -0.5304449 0.8477196 0 -0.5304446 0.8477197 0.039047 -0.8433452 0.5359517 -0.1467742 -0.8591277 0.4902622 -0.1521025 -0.8415848 0.5182665 -0.1965416 -0.7283131 0.6564537 -0.2431296 -0.5304465 0.812105 -0.2403212 -0.5397863 0.8067691 -0.2860598 -0.1150113 0.9512846 -0.2860549 -0.1150282 0.9512839 -0.2704953 0.321838 0.9073327 -0.270505 0.3322714 0.9035612 -0.2393814 0.5507324 0.799619 0.8426339 0.307453 0.442087 0.842642 0.3074222 0.442093 0.8211486 -0.1624004 0.5471209 0.7875035 -0.2827169 0.5476401 0.6134954 -0.5980116 0.5157573 0.6135058 -0.597984 0.515777 0.2736118 -0.8621194 0.4264819 0.2492936 -0.8437168 0.4753892 0.4116166 -0.5628895 0.7167477 0.4199882 -0.5331578 0.7344065 0.5117309 -0.1156182 0.8513307 0.5128406 -0.1092155 0.8515085 0.5188438 0.1195708 0.8464656 0.4945561 0.3678399 0.7874693 0.697824 0.6635879 0.2696162 0.6978468 0.6635569 0.2696334 0.5611827 0.698942 0.4433442 0.3967781 0.6934377 0.6014245 0.3824058 0.7178641 0.5817533 0.6901628 0.3474666 0.6347774 0.690156 0.347449 0.6347944 0.687575 -0.126412 0.715025 0.6875702 -0.126366 0.7150377 0.5246591 -0.5736131 0.6290477 0.5246695 -0.5736041 0.6290472 0.2735857 -0.8621349 0.4264674 0.3021882 -0.8699193 0.3897727 0.3021863 -0.8699085 0.3897983 -0.09285211 0.9935798 0.06463521 -0.09118306 0.9900198 0.107455 -0.09665977 0.9782711 0.1834192 -0.05880796 0.9842968 0.1664381 -0.0299685 0.9839097 0.1761351 -0.02996772 0.9839093 0.1761373 0.02633416 0.9839103 0.1767117 0.02633464 0.9839094 0.1767169 0.1001762 0.9935585 0.0529741 0.08996802 0.9796181 0.1795945 0.2522814 0.9279326 0.2743998 0.05821651 0.9842858 0.1667109 0.07476752 0.9903702 0.1165188 0.098526 0.9901555 0.09942239 0.09852617 0.9901556 0.09942144 0.1245748 0.9901556 0.06382125 0.1245754 0.9901553 0.0638231 0.1382513 0.9901554 0.02188372 0.1382504 0.9901556 0.02188354 0.4039936 0.9142824 -0.02961319 0.1382369 0.9903474 -0.01013243 0.1382356 0.9903476 -0.01013487 0.4039846 0.9142863 -0.02961689 0.403446 0.9127722 0.0638622 0.403437 0.9127762 0.06386035 0.3635354 0.9127737 0.1862427 0.3635311 0.9127748 0.1862459 0.2875201 0.9127737 0.2901318 0.2875214 0.9127735 0.2901312 0.1829468 0.9127753 0.3652011 0.1829437 0.9127739 0.3652061 0.06020933 0.9127737 0.4040039 0.06020849 0.9127746 0.4040017 -0.06851434 0.9127758 0.4026738 -0.06851136 0.9127749 0.4026762 -0.1904281 0.9127765 0.3613533 -0.1904256 0.9127761 0.3613556 -0.2934263 0.912776 0.2841495 -0.2934283 0.9127761 0.2841474 -0.367291 0.9127741 0.17872 -0.4046717 0.9127738 0.05554068 -0.1380271 0.9903612 -0.0115481 -0.4034369 0.9143849 -0.03375214 -0.1386721 0.9901555 0.01903295 -0.1386712 0.9901556 0.01903152 -0.1258624 0.9901555 0.06124514 -0.1258637 0.9901554 0.06124293 -0.1005529 0.9901554 0.0973736 -0.1005515 0.9901556 0.09737205 -0.0809555 0.9903932 0.1121057 -0.003241479 0.9999825 0.004942774 0.300432 0.9129581 -0.2761307 0.2789307 0.9539614 -0.1102514 0.3450112 0.9361761 -0.06739264 0.398271 0.9146153 -0.0697093 0.103111 0.9911712 -0.08335387 0.1050238 0.9900824 -0.09331142 0.1271902 0.9902571 -0.0566889 0.1367663 0.9890624 -0.0552327 0.1296138 0.9912412 -0.02531951 0.1383028 0.9899105 -0.03081667 0.1367008 0.990396 -0.02070349 0.101389 0.9809846 -0.165498 0.1000059 0.9800481 -0.1717692 0.05480229 0.9818909 -0.181348 0.05111461 0.9805733 -0.1893763 0 0.9812213 -0.1928857 0 0.9812211 -0.1928863 -0.05709427 0.980329 -0.1889324 -0.04925769 0.9819719 -0.1824966 -0.104614 0.9797422 -0.1707665 -0.09791189 0.9808834 -0.1681702 0.03283035 0.9978691 -0.05638766 0.03282982 0.9978691 -0.05638808 0.01700341 0.9978691 -0.0629943 0.01700258 0.997869 -0.06299638 0 0.997869 -0.06524908 -0.01700299 0.997869 -0.06299495 -0.01700288 0.997869 -0.06299561 -0.03282994 0.9978691 -0.05638623 -0.03283005 0.997869 -0.05638939 -0.4369461 0.8950852 -0.08888679 -0.2274894 0.9735655 0.02046263 -0.3229852 0.9324505 -0.1619158 -0.1158238 0.9932354 0.008278071 -0.1471281 0.9805426 -0.1299606 -0.2266576 0.9663726 -0.1214507 -0.2220422 0.9656198 -0.1351884 -0.2968089 0.9473353 -0.120252 -0.3672524 0.9300444 -0.01196414 -0.3773506 0.9260564 0.005114614 0.09245955 -0.6946076 0.7134225 0.3142693 -0.6543634 0.6877815 -0.4270411 -0.728666 0.5354267 -0.7878512 -0.5763893 0.2169474 -0.5549074 -0.5898788 0.5866183 -0.7153722 -0.5898203 0.3746396 -0.6746764 -0.6935968 0.2524582 -0.6663579 -0.7026722 0.2494373 -0.602333 -0.7567191 0.2541087 -0.6275791 -0.7081058 0.3236215 -0.6017084 -0.6366471 0.482315 -0.6775314 -0.5563362 0.4810836 -0.6607913 -0.496687 0.5627229 -0.752732 -0.3560476 0.5537371 -0.6842554 -0.1473906 0.7141923 -0.5760509 -0.08672767 0.8127999 -0.5760807 -0.0867449 0.8127769 -0.5761656 -0.08666801 0.812725 -0.4735043 -0.3449674 0.8104267 -0.6046612 -0.1754404 0.7769206 -0.5271056 -0.2104837 0.8233204 -0.501255 -0.273575 0.8209143 -0.5760315 -0.08674108 0.8128123 -0.6722308 -0.1755368 0.7192305 -0.6548426 -0.2624669 0.7087259 -0.6553791 -0.2617101 0.7085098 -0.642761 -0.3266237 0.6929469 -0.6135345 -0.3786383 0.6929707 -0.5960381 -0.4480195 0.6663462 -0.4596809 -0.5468704 0.699733 -0.4967901 -0.5223656 0.6930612 -0.4452041 -0.3315038 0.8318044 0.07987946 -0.6001235 0.795909 0.1228801 -0.64887 0.7509116 0.01017719 -0.5172197 0.8557923 0.1148424 -0.4454258 0.887923 0.07816857 -0.4610692 0.8839145 0.009172916 -0.516544 0.8562116 -0.0185576 -0.5107017 0.8595577 -0.07017695 -0.5272845 0.8467859 -0.1514574 -0.503264 0.8507563 -0.2144136 -0.5114771 0.8321166 0.4127634 -0.6145673 0.6722599 0.489302 -0.6283689 0.6047613 0.5090137 -0.2555229 0.8219569 0.5361073 -0.186705 0.8232438 0.5679765 -0.22679 0.7911821 0.4848043 -0.3339031 0.808377 0.6279373 -0.1336608 0.7667005 0.5396488 -0.1916988 0.8197748 0.6332232 -0.4112625 0.6556612 0.5920714 -0.4450148 0.671873 0.6119234 -0.3813636 0.6929008 0.6456627 -0.3211517 0.6928068 0.6831233 -0.1876738 0.7057771 0.6334971 -0.1384748 0.7612531 0.5973955 -0.7699165 0.2243818 0.6608009 -0.5754373 0.481886 0.6462445 -0.5999874 0.4715752 0.6649975 -0.4998315 0.5549297 0.7138199 -0.4523619 0.5346307 0.7232106 -0.3222844 0.6108185 0.6225342 -0.7090197 0.3312738 0.661594 -0.7077655 0.2477124 0.6456326 -0.7415729 0.1822858 0.6044178 -0.6295727 0.4881777 0.6028799 -0.6355217 0.4823361 0.4979798 -0.6516951 0.5721099 0.5194697 -0.667118 0.5339521 0.3064284 -0.7343189 0.6057042 0.3222802 -0.6502397 0.6879854 0.2631686 -0.6364653 0.7250202 0.2469469 -0.582049 0.7747492 0.1557999 -0.5718291 0.8054426 -0.3054012 -0.6544028 0.6917276 -0.3460116 -0.6375164 0.6883667 -0.2656777 -0.633777 0.7264586 -0.183964 -0.674838 0.7146685 -0.05356198 -0.6735311 0.7372157 0.1154254 -0.6699956 0.7333369 -0.2803633 -0.4676052 0.838297 -0.3728429 -0.4788274 0.7948036 -0.4446291 -0.5710192 0.690103 -0.4446281 -0.5710211 0.6901021 -0.5036723 -0.6468331 0.5726441 -0.5903055 -0.6435229 0.4872555 0.324303 -0.6898587 0.6472423 0.1915732 -0.562559 0.8042557 0.4482613 -0.4025257 0.7981447 0.350552 -0.2708621 0.8965195 0.1021884 -0.2300277 0.9678041 0.3947593 -0.1143093 0.911646 -0.6555659 -0.5573589 0.5094944 -0.8013122 -0.4308165 0.4150854 -0.878338 -0.3524993 0.3229037 -0.8588985 -0.3850894 0.3376384 -0.9108772 -0.2983248 0.2851403 -0.1906493 -0.6986006 0.6896449 0.1845697 -0.2802879 0.9420047 0.2132822 -0.2888069 0.9333281 0.2133225 -0.09496921 0.9723551 0.1593858 -0.07413822 0.9844287 -0.3553535 -0.1814463 0.9169521 -0.4609086 -0.6493216 0.6049338 -0.4637358 -0.648932 0.6031885 -0.4596647 -0.4714557 0.7526207 -0.7008972 -0.3961853 0.5931107 -0.6221602 -0.4087604 0.6677062 -0.8772646 -0.2696715 0.3970949 -0.8214364 -0.2952627 0.4879162 -0.9452219 -0.1797076 0.2725084 -0.9465258 -0.08942174 0.3099884 -0.9845019 -0.127578 0.1203327 -0.9842395 -0.1281813 0.1218292 -0.9835585 -0.08863204 0.1573441 -0.9969161 -0.04405701 0.06494015 0.324371 -0.5694716 0.7553051 0.1397872 -0.6093124 0.7805113 -0.08702188 -0.2962864 0.9511265 0.1131834 -0.2003579 0.973163 -0.07751631 -0.1017754 0.9917828 -0.9829541 -0.02227944 0.1824967 -0.8155965 -0.1247681 0.5650091 -0.8210288 -0.1257717 0.5568602 -0.5646206 -0.1499188 0.8116205 -0.6206133 -0.15889 0.7678498 -0.3644122 -0.178848 0.9139022 -0.3648823 -0.5070185 0.7808926 0.06134998 -0.5148649 0.8550733 -0.1903687 -0.6089163 0.7700525 0.0819565 -0.5993288 0.7962966 0.08221572 -0.7160293 0.6932119 0.1517351 -0.6879031 0.7097646 -0.9886295 0.1503525 -0.002428531 -0.7895177 0.6098586 -0.06880676 -0.7849139 0.6192171 -0.02191871 -0.8656246 0.4898 -0.1038759 -0.9543256 0.267013 -0.1340408 -0.948881 0.3057207 -0.0784837 -0.9364343 0.3495207 -0.03043097 -0.67421 -0.4114374 0.613319 -0.9076399 -0.1913214 0.3736121 -0.7912254 -0.2708891 0.5482532 -0.9865359 0.0683943 0.1485571 -0.8837847 -0.3372095 0.3243678 -0.8587839 -0.4613337 0.2228487 -0.731483 -0.1197637 0.6712595 -0.5128922 -0.3622363 0.7782843 0.4054906 -0.828942 0.3852697 -0.8599348 -0.483683 0.1629816 -0.804623 -0.5596171 0.1985218 -0.556348 -0.7831472 0.2777723 -0.4502373 -0.8475122 0.2810866 -0.6356478 -0.7275322 0.2581646 0.7292767 -0.6569057 0.1913912 0.5944542 -0.7736558 0.2192738 0.7281997 -0.6445264 0.2330471 0.3968824 -0.8654589 0.3057209 0.2931472 -0.9037719 0.3118672 0.1272341 -0.9324642 0.3381156 -0.145213 -0.93503 0.323469 -0.1626216 -0.9319017 0.3242123 -0.3027497 -0.8982362 0.3186134 0.7802353 -0.2918891 0.5532032 0.7027321 -0.1889448 0.6859063 0.4470954 -0.2297032 0.8644896 0.501653 -0.2170327 0.8374013 -0.02055525 -0.2392899 0.9707306 -0.877494 -0.1038497 0.4682089 -0.7899619 -0.1218695 0.6009228 -0.860596 -0.1179866 0.4954329 -0.556454 -0.1859998 0.809792 -0.4251897 -0.2144438 0.8793337 -0.9667977 -0.2371948 0.09508383 -0.9864241 -0.1544451 0.05580681 -0.9892505 -0.1239922 0.0775206 -0.8594235 -0.4287858 0.2784493 -0.1447919 -0.8298441 0.5388823 0.2923011 -0.8020493 0.5208425 0.8040137 -0.4986883 0.3238393 0.7494568 -0.4394937 0.4951362 0.5084691 -0.6770039 0.5320949 -0.9751328 -0.04656785 0.2166736 -0.988578 -0.04286903 0.1444854 -0.8594428 -0.2255864 0.4587688 0.6129775 -0.3486418 0.7090188 0.6319185 -0.5006167 0.5916604 -0.8269451 -0.00339365 0.5622726 -0.2069454 -0.9313868 0.2994871 -0.215679 -0.9206994 0.325262 -0.349126 -0.8044479 0.4805982 -0.1516312 -0.8156525 0.5583181 -0.2948565 -0.8663274 0.4031581 -0.3692005 -0.7586365 0.5368071 -0.3852698 -0.7152447 0.5830886 -0.6010938 -0.161476 0.7826952 -0.5835133 -0.04248982 0.8109912 -0.5957378 -0.1937629 0.7794564 -0.5263334 -0.4992057 0.6883072 -0.5292289 -0.4356665 0.7280877 -0.4731709 -0.6206631 0.6252093 -0.8227313 -0.1034045 0.5589463 -0.8202117 -0.1611791 0.5488846 -0.7836894 -0.304579 0.5413525 -0.7171863 -0.4988511 0.4866122 -0.7135173 -0.5046196 0.486058 -0.2307105 -0.9497326 0.2116145 -0.2319988 -0.944373 0.2331012 -0.6340038 -0.6710675 0.3843274 -0.4818815 -0.795975 0.3663523 -0.4422971 -0.7951166 0.4149254 -0.2581455 -0.9387209 0.2283945 -0.4245184 -0.7651057 0.484146 -0.423564 -0.8099143 0.4057494 -0.6260327 -0.4984424 0.5996986 -0.6260295 -0.4984493 0.5996961 -0.712691 -0.161143 0.6827185 -0.7126979 -0.1611092 0.6827192 0.5976392 -0.3944731 0.6980103 0.04646277 -0.7619901 0.6459198 0.6871777 -0.3677042 0.6265624 0.6662622 0.01090061 0.7456379 -0.4826467 -0.6031866 0.6349947 -0.3548113 -0.7264429 0.5885488 -0.2509095 -0.8202034 0.5141118 -0.2092154 -0.8281443 0.5200058 -0.2753159 -0.8840124 0.3777875 -0.2392419 -0.9010002 0.361887 -0.2272294 -0.8896803 0.396025 -0.2184906 -0.8927081 0.3941248 -0.2008393 -0.8796064 0.4312265 -0.2270243 -0.875185 0.4272134 -0.1779875 -0.8613271 0.475853 -0.2093444 -0.8582643 0.4685697 -0.5639991 -0.1391795 0.813962 -0.09063142 -0.3604258 0.9283745 -0.2169374 -0.1149981 0.9693883 -0.3465172 -0.3312649 0.8776044 -0.5833186 0.08767819 0.8074974 0.210079 -0.270332 0.9395678 0.2083393 -0.2597567 0.9429323 -0.002561211 -0.2526074 0.9675655 0.8594089 -0.2279433 0.4576661 0.997264 -0.04772222 0.05645501 0.9683053 -0.1156407 0.2213866 0.9654206 -0.1266678 0.2278561 0.8599361 -0.2926258 0.4181869 0.906543 -0.2200801 0.3602007 0.8734128 -0.2643715 0.4089719 0.824753 -0.3520966 0.4425049 0.7006568 -0.4756957 0.5317836 0.6514574 -0.5039238 0.5671544 0.6038124 -0.549359 0.5775945 -0.1889701 -0.7230491 0.6644474 0.8413162 -0.1986675 0.5027109 0.7354609 -0.2185916 0.6413385 0.5979889 -0.3937013 0.6981467 0.5022983 -0.3070685 0.808335 0.4266036 -0.3257111 0.8437545 0.4233592 -0.3169457 0.8487122 0.3535028 -0.2803542 0.8924334 -0.3955225 -0.7387961 0.5456577 -0.3811802 -0.7483322 0.5428634 -0.2826935 -0.7517305 0.5958068 -0.2979488 -0.7406266 0.6022449 -0.1697037 -0.7606188 0.6266257 -0.1923268 -0.7329528 0.6525263 -0.07682555 -0.7700403 0.6333528 -0.08828145 -0.7405926 0.6661298 -0.02282601 -0.775383 0.6310786 -0.01983493 -0.7558771 0.654413 1.56447e-4 -0.7739843 0.6332049 -1.92067e-4 -0.7742224 0.6329136 0.02475118 -0.8226181 0.5680553 -0.229951 -0.7769953 0.5860042 -0.3839921 -0.7549184 0.5316469 0.3593267 -0.6946653 0.6231569 0.3504843 -0.7022816 0.6196461 0.3148434 -0.6284449 0.711288 0.3152566 -0.6277998 0.7116747 0.2329803 -0.5533317 0.7997151 0.2289142 -0.5764802 0.7843909 0.08161717 -0.4990621 0.8627141 0.08879101 -0.5342862 0.8406275 -0.1294892 -0.4646896 0.8759545 -0.1131526 -0.4984013 0.8595305 -0.3452979 -0.4626934 0.8165073 -0.3336421 -0.476626 0.813333 -0.5234499 -0.4696169 0.7109572 -0.5798963 -0.3966338 0.7116193 0.3563166 -0.8725562 0.3341919 0.791109 -0.3389195 0.5091955 0.455509 -0.7206392 0.5226765 0.9194743 0.3927911 0.01680248 0.9822008 0.1657801 0.08831113 0.9651775 0.2614864 -0.007571995 0.9616166 0.2738044 0.01802301 0.9888777 0.09173774 0.1170691 0.9870867 0.1489056 0.05905169 0.9893007 -0.03839939 0.1407464 0.9958279 0.09105449 0.005984306 0.9869815 -0.03649711 0.1566386 0.9878358 -0.02897393 0.1527776 0.9153318 -0.1768201 0.3618046 0.9056988 -0.1979227 0.374882 0.7845872 -0.3014786 0.5417876 0.7383769 -0.3565303 0.5724385 0.5122125 -0.4391064 0.738122 0.5220584 -0.4277524 0.7378909 0.5373481 -0.5086707 0.6726896 0.5057382 -0.6018342 0.6180813 0.4885803 -0.5829195 0.6492259 0.9520738 0.3058575 0.002598762 0.9543039 0.2843612 0.09188491 0.985037 0.1039959 0.1374302 0.9663004 -0.1000784 0.2371662 0.9360085 -0.2452683 0.2524514 0.8443151 -0.4160726 0.3376621 0.8754131 -0.386418 0.2904017 0.6953951 -0.6190829 0.3649137 0.6988378 -0.6170975 0.3616856 0.5679772 -0.7336855 0.3729714 0.4090679 -0.8057803 0.4282311 0.4065263 -0.8000971 0.4411133 0.6770765 -0.578812 0.4544713 0.7340158 -0.5408681 0.4107099 0.8331252 -0.3923673 0.3898085 0.8752107 -0.3453546 0.3387278 0.9548652 -0.1029841 0.278616 0.4365859 -0.6690432 0.6014766 0.5107638 -0.6725243 0.5355666 0.714111 -0.4838753 0.5058758 0.7184438 -0.4814172 0.5020717 0.8565614 -0.2935121 0.4244448 0.9187672 -0.2016881 0.3393946 0.9534689 -0.09947818 0.2846069 0.9820591 -7.45069e-4 0.1885722 0.9862267 0.1189367 0.114939 0.9870793 0.1480228 0.06135094 0.9671096 0.2538759 -0.01568716 0.4956942 0.8677366 -0.03633862 -0.5677214 0.8218497 -0.04749482 -0.5861628 0.7919098 0.1711493 0.5861658 0.7919078 0.1711484 0.5440655 0.8337535 -0.09406298 0.5637388 0.8249952 -0.03976732 -0.7110699 0.7030866 0.007005333 -0.610006 0.7874022 -0.08882862 0.6809167 0.7323246 0.007296621 0.5614138 0.8232204 0.08439618 0.5721482 0.8173807 0.06734454 0.3900061 0.9187404 0.06173634 0.5567445 0.810254 0.183096 0.4723566 0.8475362 0.2419952 0.5101597 0.7719943 0.3791594 0.336017 0.8787071 0.339067 0.3667545 0.7522026 0.5474326 0.2003923 0.8943238 0.4000349 0.1859384 0.7613863 0.6210619 0.06556469 0.8956227 0.439956 0 0.7607566 0.6490374 -0.1842056 0.7664562 0.6153156 -0.211089 0.8916235 0.4005607 -0.362905 0.7590003 0.5405724 -0.3444741 0.8775322 0.3335791 -0.5090508 0.7733943 0.3777945 -0.5537346 0.8120433 0.1842926 -0.4207249 0.9053488 0.05774289 -0.5712066 0.8184787 0.06177341 -0.5512663 0.8294175 0.09040039 -0.6728094 0.7397025 0.01295399 0.9122346 0.4054013 0.05897402 0.7820298 0.6169133 0.08858644 0.9223972 0.2663176 0.279747 0.9324907 0.2228753 0.284232 0.9296084 -0.09288197 0.3566529 0.9321307 -0.0655775 0.3561347 0.858317 -0.321858 0.3996242 0.8460455 -0.3547011 0.3979878 0.6588619 -0.6236578 0.4206566 0.6768174 -0.5973281 0.4302528 0.5733568 -0.7430051 0.3452615 0.7035003 -0.6248309 0.3386351 0.7035997 -0.6247056 0.33866 0.8727666 -0.3821539 0.3037056 0.8728474 -0.3819523 0.3037269 0.9656506 -0.09915137 0.2401829 0.9656677 -0.09899121 0.2401807 0.9699199 0.1864302 0.1565219 0.9699198 0.1864366 0.1565156 0.9236775 0.3721038 0.0914272 0.7685651 0.6362287 0.06723755 0.3560028 -0.8719841 0.3360149 0.3806677 -0.8571344 0.3470054 0.3745025 -0.8507059 0.3688461 0.3271057 -0.8834006 0.3355674 0.3130363 0.9497255 0.005457997 0.35628 0.9330525 -0.04977607 0.4912497 0.8705072 -0.02984869 0.5511603 0.8341413 -0.02075755 0.3682922 0.9295812 -0.01548171 0.3100684 0.9459475 -0.09508347 0.2502292 0.9638832 -0.09118455 0.2288929 0.9656497 -0.1229993 0.1528117 0.9802554 -0.1254907 0.3171942 0.9483606 0 0.2984557 0.9542933 -0.01576542 0.2026112 0.9787535 -0.03147006 0.04441124 0.9978873 -0.04741966 -0.1758274 0.9844211 4.51899e-6 -0.1584849 0.9873582 -0.002570629 -0.6194975 0.7845921 -0.02526229 -0.6712079 0.7369584 -0.07982683 -0.307758 0.9514647 -1.98979e-4 -0.3524532 0.9358294 1.50257e-4 -0.3227058 0.9464994 -2.00547e-4 -0.3563725 0.9343441 1.7085e-4 -0.5241084 0.8516482 0.002417564 -0.373416 0.9275097 0.01692622 -0.3775246 0.9258517 0.01655095 -0.3868691 0.9220004 0.0157352 -0.3931462 0.9193501 0.0152105 -0.4085646 0.9126239 0.01388263 -0.4269517 0.9041893 0.01240867 -0.4391503 0.8983405 0.01146686 -0.4692106 0.8830385 0.009186744 -0.4987355 0.8667236 0.00728625 -0.510443 0.8598867 0.006560504 -0.5219296 0.8529683 0.005872964 -0.5334665 0.8458051 0.005222141 -0.5504481 0.8348584 0.004304945 -0.5673065 0.8234994 0.003498494 -0.5782271 0.8158704 0.003002583 -0.5892882 0.807919 0.002539932 -0.600105 0.7999185 0.002117097 -0.6162199 0.7875728 0.001541018 -0.6319757 0.7749875 0.001079738 -0.6424755 0.7663058 8.09202e-4 -0.6577769 0.7532127 4.62684e-4 -0.6779088 0.7351461 1.5431e-4 -0.6974985 0.7165863 0 -0.7574924 0.6525387 0.01995837 -0.770523 0.6371566 0.01805114 -0.7875224 0.6160869 0.01566898 -0.8038482 0.5946825 0.01345282 -0.8196485 0.5727534 0.0113998 -0.8348016 0.5504688 0.009512424 -0.8458924 0.5332902 0.00822097 -0.8528889 0.5220401 0.007404506 -0.8633257 0.5046084 0.006240129 -0.8733832 0.487006 0.00520277 -0.8798983 0.4751403 0.004553794 -0.8862266 0.4632351 0.003948748 -0.8924044 0.451224 0.003384888 -0.9013439 0.4330964 0.002604663 -0.9127101 0.4086041 0.001737594 -0.7485705 0.6627143 0.02126514 -0.9053133 0.4246715 -0.007864952 -0.7259296 0.6877566 0.004149556 -0.8017374 0.597674 -0.001737415 -0.7328356 0.6804058 0 -0.9285091 0.3713091 6.94392e-4 -0.9843216 0.176373 -0.001914501 -0.9888087 0.1491892 5.10358e-5 0.01628726 -0.04227209 0.9989734 0.06641721 -0.7172504 0.693643 -0.2824172 -0.5099718 0.812508 -0.2840396 -0.6658606 0.6898922 -0.1888778 -0.7175611 0.6703965 -0.3553217 -0.6672936 0.654573 0.4167618 -0.6465089 0.6390117 0.3573021 -0.6445931 0.6758956 0.04669022 -0.7227416 0.6895395 0.9150456 -0.2967965 0.2731364 0.8289905 -0.3920495 0.3988384 0.7132759 -0.5081021 0.4827731 0.7035593 -0.5123404 0.4924548 0.6049339 -0.564733 0.561366 -0.3961158 -0.04979521 0.9168494 -0.4020495 -0.05687695 0.9138497 -0.3989985 -0.2298211 0.8876838 0.300883 -0.04882758 0.9524103 0.5738682 -0.04440325 0.8177431 0.6206027 -0.002122879 0.7841224 0.8241045 -0.08663797 0.5597729 0.8612822 -0.02182918 0.5076579 0.9840475 -0.01394414 0.1773592 0.9754035 -0.04890412 0.2149336 0.6203284 -0.1639313 0.7670198 0.3196669 -0.1862234 0.92905 0.2998294 -0.198483 0.9331168 -0.03774219 -0.1966497 0.9797471 0.9972356 -0.0459823 0.05836945 0.9837345 -0.1163865 0.136824 0.9908849 -0.04632359 0.1264966 0.8862215 -0.1303014 0.4445594 0.8568971 -0.1577588 0.4907541 0.6606592 -0.2147107 0.7193253 0.324277 -0.35141 0.8782684 0.3552308 -0.3488726 0.8672366 0.3197715 -0.3715732 0.871596 -9.68331e-5 -0.3739383 0.9274537 -0.03762185 -0.3910274 0.9196098 0.9686154 -0.1561629 0.1933842 0.7823464 -0.4043925 0.4737098 0.8883706 -0.2649313 0.374979 0.7131329 -0.3816131 0.5880587 0.6647285 -0.4256517 0.6139681 0.4160008 -0.4970121 0.7615264 0.3546409 -0.5312643 0.7694076 0.06629753 -0.5465104 0.834824 1.03656e-4 -0.5671004 0.8236488 -0.2174527 -0.5391487 0.8136542 -0.402612 -0.3384013 0.8505223 -0.2606443 -0.1939973 0.9457429 -0.05828064 -0.2072309 0.9765545 -0.05866444 -0.1508247 0.9868184 0.3636813 0.0247628 0.9311943 0.6187841 -0.1824886 0.7640709 0.9832767 -0.1081822 0.1465048 0.145206 -0.935242 0.3228588 0.0330519 -0.9415423 0.3352696 -0.2932968 -0.9017051 0.3176555 -0.2105296 -0.9259899 0.3134011 -0.3893743 -0.8685292 0.306667 0.5559625 -0.7861124 0.2700611 0.4708176 -0.8314711 0.2949352 0.2664326 -0.9083964 0.3222262 0.9637739 -0.2485173 0.09684509 0.8103745 -0.5565096 0.1832765 0.8603211 -0.480426 0.170407 0.6703861 -0.6992996 0.2481182 0.5925604 -0.7609534 0.2642391 0.994969 -0.08660244 0.05036777 0.9781602 -0.1536696 0.1399588 0.9892545 -0.06225717 0.1322864 0.899467 -0.09622323 0.4262633 0.9270774 -0.08456707 0.3652067 0.9864234 -0.03697258 0.1600064 0.9797563 -0.04175269 0.1957916 0.9990747 -0.009652018 0.04191267 0.860578 -0.1180285 0.4954541 0.7847486 -0.122087 0.6076714 0.8689704 -0.1062188 0.4833303 0.002401471 -0.2130214 0.9770447 0.2145354 -0.2314587 0.9488949 0.5569366 -0.196534 0.8069673 0.3804383 -0.1839401 0.9063294 0.4643748 -0.1884986 0.8653464 0.1455466 -0.236764 0.9606035 -0.2938467 -0.2288724 0.9280472 -0.2226904 -0.219945 0.9497544 -0.6628008 -0.1974276 0.7223002 -0.5625342 -0.1670953 0.8097126 -0.6100277 -0.7460864 0.2668735 -0.5742584 -0.7692902 0.2800357 -0.6737297 -0.6237761 0.3962217 0.9922782 -0.0547229 0.1113084 0.8594513 -0.225579 0.4587566 0.8594213 -0.2256042 0.4588006 0.554795 -0.3671175 0.7466105 0.5548027 -0.3671196 0.7466038 0.1448984 -0.4365943 0.8879132 0.1447571 -0.4366165 0.8879253 -0.292295 -0.421993 0.8581874 -0.2923861 -0.4219654 0.8581699 -0.8038578 -0.2624694 0.5337813 -0.4280837 -0.3138684 0.8474851 0.9942497 -0.07107806 0.08009821 0.8594147 -0.339399 0.3823805 0.8594213 -0.3393954 0.3823687 0.5548406 -0.5522826 0.6222025 0.5548546 -0.5522655 0.6222051 0.1448151 -0.6568303 0.7400018 0.1447584 -0.6568316 0.7400118 -0.2923252 -0.6348375 0.7152115 -0.2922587 -0.6348363 0.7152397 -0.7897003 -0.40726 0.4588168 -0.413367 -0.4924588 0.765906 0.9997867 -0.01955109 0.00666058 0.9902595 -0.1322376 0.04358392 0.9831389 -0.1533563 0.0995981 0.8594375 -0.4287566 0.2784512 0.8594174 -0.4287984 0.2784488 0.5548313 -0.697758 0.453096 0.5548361 -0.6977393 0.4531192 0.1447883 -0.8298395 0.5388903 0.144761 -0.8298351 0.5389046 -0.2922872 -0.8020551 0.5208415 -0.2922871 -0.8020542 0.5208429 -0.7256838 -0.5770329 0.3747215 -0.5151453 -0.607737 0.6043849 0.8779995 -0.4765717 0.0446816 0.989959 -0.05958563 0.1281822 0.9002078 -0.05906116 0.431437 0.7300168 -0.446669 0.5172644 0.673115 -0.5959268 0.4379356 0.5077053 -0.1822045 0.8420434 0.4662531 -0.3562183 0.8097633 0.989646 -0.05384576 0.1330469 0.9057189 -0.1935098 0.3771304 0.9077955 -0.1719506 0.3825446 0.7397871 -0.3030021 0.6007535 0.743014 -0.2796506 0.6080508 0.5129567 -0.3841708 0.7676512 0.5172165 -0.3606007 0.7761794 0.7893261 0.6124384 -0.04340255 0.8730816 0.4800869 -0.08511865 0.9434705 0.3261546 -0.05904924 0.9467906 0.3143243 -0.06919586 0.9488061 0.3060972 -0.07792091 0.9532158 0.2781605 -0.118349 0.9911231 0.1293746 -0.03061336 0.9762428 0.2162483 -0.01366829 0.8098239 0.2186636 -0.5444002 0.9319364 0.2349127 -0.2762438 0.6964222 0.7175968 0.007149994 0.7860817 0.6157648 -0.05393868 0.7895069 0.6110047 -0.05789953 0.8882658 0.4586046 -0.02580136 0.937562 0.3459674 -0.03583371 0.9932816 0.1157231 0 0.9659207 0.2588124 -0.003677248 0.6087576 0.7933553 0.001293301 0.8187366 0.5741684 -0.001054108 0.7933489 0.6087674 2.10537e-4 0.9063585 0.4225096 -1.22497e-4 0.9556362 0.2945392 -0.002502202 0.2588188 0.965926 0 0.1189432 0.9928514 -0.009936809 0.252723 0.9675309 -0.003886342 0.6233453 0.7807889 -0.04253762 0.5664666 0.8240788 0.003112912 0.3405404 0.9402283 -0.001753449 0.325443 0.9455593 -0.00211507 0.3796462 -0.5430303 0.7489906 0.03921073 -0.9983743 0.04136961 0.4941896 -0.8680409 0.04776644 0.1822902 -0.9682211 0.1712259 0.1885334 -0.9653069 0.1806596 0.1595222 -0.9659225 0.2038294 0.4346434 -0.7835198 0.4440519 0.3587341 -0.8577191 0.3682767 0.3067207 -0.8982014 0.3148914 0.5526867 -0.2583985 0.7923179 0.658902 -0.2580258 0.706591 0.7349124 9.33388e-4 0.6781614 0.7157721 -0.08447784 0.6932055 0.6583541 -0.3119876 0.6850064 0.4910831 -0.7054659 0.5110336 0.6471445 -0.4916148 0.5826826 0.5764265 -0.6018442 0.5527352 0.06452929 -0.966723 0.2475535 0.215503 -0.9331285 0.2878013 0.4116247 -0.7066898 0.5754604 0.3226596 -0.7719102 0.5477643 0.3530673 -0.7423279 0.5694671 0.4062436 -0.6512244 0.6409937 0.5294163 -0.1480362 0.8353465 0.3082343 -0.4808645 0.8208294 0.4695414 -0.2393273 0.8498548 -0.186866 -0.2371049 0.9533427 0.1158259 -0.6560586 0.7457691 -0.02602148 -0.9439371 0.3290985 0.2990828 -0.5412316 0.7858867 0.1496833 -0.7427107 0.6526682 0.1810106 -0.4707638 0.863491 -0.09106904 -0.9214352 0.3777082 -0.1053122 -0.8429704 0.5275513 -0.1514672 -0.6685488 0.7280799 -0.156929 -0.6755093 0.7204585 -0.1688741 -0.4787185 0.8615744 -0.1868833 -0.2371147 0.9533369 0.199569 -0.2322675 0.951958 0.1995658 -0.2322871 0.951954 -0.4344503 -0.4769071 0.7640763 -0.3342218 -0.8333705 0.4402152 -0.2059963 -0.9420463 0.2647914 -0.9984537 0.002649843 0.05552601 -0.9852952 -0.07664144 0.1527068 -0.9719622 -0.0141111 0.2347136 -0.9280681 -0.08135229 0.3634163 -0.9207684 -0.09323328 0.3788051 -0.8595318 -0.1218826 0.4963364 -0.9965257 -0.08291375 -0.007874786 -0.9803069 -0.1703352 0.09992223 -0.9459753 -0.3239883 -0.01274752 -0.9037282 -0.4159116 0.101455 -0.9020797 -0.4300199 0.03653877 -0.8265352 -0.5350704 0.1747545 -0.7837797 -0.620053 0.03498482 -0.6726139 -0.7204389 0.1689925 -0.7167698 -0.6912432 0.09178113 -0.5657185 -0.7884966 0.2413209 -0.5681504 -0.8176442 0.09307581 -0.365955 -0.9013739 0.2315213 -0.4632703 -0.8728499 0.1533421 -0.260036 -0.9258584 0.2741671 -0.1130563 -0.9906399 -0.07649147 -0.860084 -0.09805065 0.5006413 -0.7992345 -0.1527079 0.5812955 -0.7759814 -0.1614732 0.6097371 -0.7106279 -0.2055854 0.6728615 -0.6826338 -0.1850634 0.7069391 -0.5895482 -0.2195658 0.7773184 -0.5729871 -0.222523 0.7887771 -0.4578532 -0.253611 0.8520868 -0.4343566 -0.2377932 0.8687859 -0.9999994 -0.001141548 2.78699e-7 -0.9990953 -0.0373317 0.02037507 -0.9819251 -0.1315541 0.136076 -0.9809321 -0.164527 0.103457 -0.9404188 -0.2582737 0.22115 -0.9435332 -0.2615146 0.2033603 -0.8766779 -0.3552083 0.3244426 -0.8803758 -0.3812651 0.2820911 -0.7875441 -0.4675109 0.4015073 -0.8044165 -0.45927 0.3768091 -0.6829851 -0.5381515 0.4938868 -0.7025861 -0.558784 0.4406057 -0.5385253 -0.6272744 0.5625989 -0.5831318 -0.616774 0.5287222 -0.3849281 -0.6655327 0.6394503 -0.39268 -0.6696463 0.6303779 -0.6805992 0.05370289 0.7306851 -0.3584298 -0.8577662 0.3684633 -0.4344171 -0.783459 0.4443803 -0.5760959 -0.6016188 0.5533249 -0.4912052 -0.7054118 0.510991 -0.614813 -0.4602088 0.6404787 -0.6570413 -0.3158563 0.6844937 -0.1786069 -0.9656625 0.1886677 -0.09495455 -0.994628 0.04121559 -0.1474592 -0.9818437 0.1193274 -0.2197386 -0.9516496 0.2146577 -0.3065286 -0.8981996 0.3150838 -0.0160405 -0.9996613 0.02049553 -0.1053463 -0.9635838 0.2457811 -0.07348126 -0.9641101 0.2551321 -0.2095717 -0.9367398 0.2803542 -0.3141916 -0.8447383 0.4332446 -0.3884919 -0.7057426 0.5924537 -0.3473125 -0.747591 0.5661111 -0.4068951 -0.6489142 0.6429205 -0.3769111 -0.5545213 0.7419193 -0.7143151 -0.0874986 0.6943327 -0.6591205 -0.2579956 0.7063983 -0.5167484 -0.2575299 0.8164861 -0.5704509 -0.06361109 0.8188648 -0.3069214 -0.4824146 0.8204118 -0.4693107 -0.2413315 0.8494155 -0.09922719 -0.6634256 0.7416337 -0.1196775 -0.6731389 0.729768 -0.1812059 -0.7568417 0.627977 0.08042567 -0.9490139 0.3048023 0.1017338 -0.8449684 0.5250511 -0.09241861 -0.6633078 0.742618 0.1522583 -0.6684695 0.7279876 0.1425874 -0.6775842 0.7214906 0.1824063 -0.2389646 0.9537421 0.1824114 -0.2389491 0.953745 0.1647962 -0.4801625 0.8615604 -0.1787406 -0.5428107 0.8206146 -0.1847276 -0.4727283 0.8616285 -0.203787 -0.2345033 0.9505152 -0.2037834 -0.2345116 0.9505139 0.806131 -0.4529085 0.380824 0.1051623 -0.9911926 -0.08048737 0.9965257 -0.08291375 -0.007874786 0.9876167 -0.1425374 0.06554621 0.9434387 -0.3315262 -0.00373733 0.9218394 -0.3829816 0.05947631 0.8861794 -0.4578209 0.07131659 0.9999974 -0.002283096 1.68613e-4 0.9992839 -0.02524507 0.02818703 0.9990926 -0.03731691 0.0205276 0.983938 -0.1246265 0.1278061 0.9803932 -0.1663264 0.1056632 0.9451234 -0.2498767 0.2104836 0.9395937 -0.268525 0.2122689 0.9320359 -0.1024784 0.3475736 0.973175 -0.01040434 0.2298307 0.9811264 -0.09125488 0.1704804 0.9984558 0.002590894 0.0554918 0.8661031 -0.1167759 0.4860338 0.9203598 -0.09389263 0.3796343 0.9357584 -0.06802332 0.346019 0.2670179 -0.9249718 0.2704235 0.3567006 -0.9079635 0.2199255 0.4726035 -0.866162 0.1625095 0.4902173 -0.858529 0.1503831 0.6485576 -0.7431028 0.1648372 0.659906 -0.7355365 0.1533303 0.7307005 -0.674736 0.1039628 0.7866526 -0.4731236 0.3966506 0.7160832 -0.5198906 0.4657667 0.6756372 -0.5729468 0.4639467 0.5856112 -0.6115417 0.5320492 0.537029 -0.6319513 0.5587821 0.2024472 -0.9441614 0.2599509 0.3321846 -0.8356583 0.4374113 0.3995931 -0.6632674 0.6327732 0.3819561 -0.6737906 0.6325472 0.4341539 -0.4786025 0.7631842 0.8651372 -0.4889422 0.111683 0.753692 -0.6528826 0.07544958 0.8884183 -0.3416166 0.3066123 0.8725326 -0.3901342 0.2940789 0.8551025 -0.1030138 0.5081222 0.7775741 -0.1697741 0.6054381 0.7968421 -0.1457032 0.586356 0.6876257 -0.2196104 0.6920566 0.702435 -0.1768146 0.6894358 0.5731257 -0.2250193 0.7879678 0.5891956 -0.2175633 0.7781483 0.4379583 -0.2583193 0.8610829 0.4570129 -0.2389707 0.8567569 -0.4445822 -0.8957182 -0.00596112 -0.3649419 -0.9290349 0.06092274 -0.308187 -0.9437147 0.1200969 -0.6027565 -0.797923 0.001897335 -0.7372906 -0.6753001 0.01929813 -0.7521376 -0.6589351 0.009682893 -0.999999 -0.001492798 0 -0.9979829 -0.06348389 7.27699e-5 -0.9696961 -0.2441634 0.008589267 -0.9566442 -0.2912538 0.001773118 -0.864662 -0.5023542 -3.99604e-4 0.8645987 -0.5024629 -4.52255e-4 0.9999989 -0.0014894 0 0.9694403 -0.2453138 0.002600014 0.9620477 -0.2727011 0.009917914 0.9979812 -0.06351172 7.19776e-5 0.7352163 -0.6777417 0.01110446 0.6739105 -0.7366805 0.05609369 0.7515966 -0.659558 0.009269356 0.3019227 -0.945916 0.1186827 0.3622169 -0.9302583 0.05846726 0.4433562 -0.8963192 -0.006881117 -0.1948563 -0.9796115 -0.04891258 -0.2067431 -0.9769737 -0.05272227 -0.5552247 -0.8309549 -0.03521001 -0.5935285 -0.8033515 -0.04847991 -0.8313418 -0.5555101 -0.01672136 -0.8573514 -0.5139036 -0.02918761 -0.9807789 -0.1950867 -0.003755629 -0.9840229 -0.1778259 -0.008774816 -0.05093395 -0.9987021 -4.42662e-6 -0.8314648 -0.5555775 -6.45456e-5 -0.8036962 -0.5949302 -0.01142412 -0.911832 -0.4105616 0.001255869 -0.9807765 -0.1950891 -0.004223048 -0.9986326 -0.05227977 0 -0.1950772 -0.9807376 -0.009934663 -0.2266619 -0.9739667 -0.003652989 -0.5555714 -0.831451 0.005440413 -0.4611036 -0.8869978 -0.02487295 -0.6363242 -0.7714219 2.91394e-5 0.9861154 -0.1658626 -0.008131206 0.9657961 -0.2587653 0.01668852 0.2585147 -0.964798 -0.04832112 0.2170755 -0.9756774 -0.03052866 0.4645553 -0.8845155 -0.04266983 0.6083254 -0.7927653 -0.03825592 0.65223 -0.7564091 -0.04941248 0.793178 -0.6086174 -0.02129751 0.8264831 -0.5623311 -0.02663826 0.9092144 -0.4158622 -0.01969897 0.9999812 -0.006136775 0 0.9959626 -0.08976805 -5.41961e-4 0.9658016 -0.2587823 -0.01609438 0.2426589 -0.9701118 -2.53021e-5 0.2588194 -0.9659121 -0.005148172 0.6087504 -0.7933557 0.00312227 0.9682224 -0.2494467 -0.01793354 0.8959832 -0.4440824 0.002253651 0.7933341 -0.60878 -0.002837061 0.7796991 -0.6261545 -3.03395e-5 0.5955353 -0.8033292 4.01509e-5 -0.1861719 0.6947482 -0.694741 -0.5085771 0.6947559 -0.5085899 -0.5085921 0.6947456 -0.5085889 -0.6947402 0.6947531 -0.1861564 -0.6947398 0.6947543 -0.1861536 -0.694746 0.694746 0.1861614 -0.6947503 0.694743 0.1861564 -0.5085866 0.6947514 0.5085866 -0.5086131 0.6947257 0.5085951 -0.1861695 0.6947305 0.6947594 -0.1861431 0.6947556 0.6947412 0.1861529 0.6947487 0.6947455 0.1861622 0.694737 0.6947548 0.5086143 0.6947202 0.5086014 0.5085865 0.6947524 0.5085852 0.6947517 0.6947389 0.1861664 0.694733 0.6947619 0.1861501 0.694765 0.6947265 -0.186163 0.6947222 0.6947727 -0.1861507 0.5086056 0.694734 -0.5085911 0.5085648 0.6947621 -0.5085939 0.1861399 0.6947723 -0.6947255 -0.9831954 2.08613e-4 0.182556 -0.01276069 -0.05588358 0.9983558 -0.3612955 0 0.9324515 -0.4684805 -0.07030028 0.8806725 -0.8219965 0 0.5694927 -0.3965941 0 0.9179941 0.9841384 0 0.1774024 0.9841452 0 0.1773652 0.8272943 0 0.5617688 0.8272435 0 0.5618435 0.5744295 0 0.8185541 0.474082 -0.07110226 0.8776052 -0.39661 0 0.9179872 0.01656574 0 0.9998628 0.01624411 0 0.9998682 0.3636857 0 0.9315217 0.8945063 0.2673662 0.3582932 0.333779 -7.91833e-5 0.9426513 0.4696292 0.1540036 0.8693282 0.9915132 0.07491135 0.1062548 0.9761883 -0.1268779 0.1759504 0.630244 0.1967318 0.7510588 0.9617996 0.05450594 0.2682735 0.9774463 0.0635659 0.2013905 0.9409868 0.263426 0.2124869 0.9491832 0.1907865 0.2503032 0.9783179 0.1150782 0.1721947 -0.3939569 -0.1115245 0.9123378 -0.3360143 0.03408998 0.9412398 -0.3328044 0.2046284 0.9205263 -0.4396581 0.152944 0.8850474 -0.4401664 0.3097075 0.8428137 -0.4320849 0.3081368 0.8475579 -0.2057344 0.3470742 0.9149934 -0.2056623 0.1597204 0.9655011 0.04867041 0.1699581 0.9842486 0.01633828 0.09456443 0.9953848 0.799186 0.1309366 0.5866494 0.796568 0.1608713 0.5827519 0.8270999 0.1415554 0.5439373 0.826433 0.3424938 0.4468855 0.8462937 0.3217229 0.4245957 -0.06021088 0.6676528 0.742034 0.2114763 0.6638794 0.7173158 0.1576848 0.6520295 0.7416151 0.4452781 0.6105924 0.654908 0.1178794 0.5935392 0.7961255 0.5678648 0.4944999 0.6580269 0.6290341 0.4718726 0.6177803 0.6827673 0.4379763 0.5848126 0.7836688 0.3729372 0.4967707 -0.2884802 0.6383462 0.7136479 -0.1145076 0.6745564 0.7292886 -0.1147209 0.5111557 0.8517975 0.1576468 0.5260683 0.8357032 0.09996217 0.5075545 0.8558014 0.3803691 0.489902 0.7844204 0.8253986 0.06645041 0.5606261 0.5956143 8.61025e-4 0.8032702 0.5889039 0.2142482 0.7792881 0.3293865 0.2382547 0.9136407 0.3776975 0.2470448 0.892364 -0.1303765 0.2438049 0.9610209 0.1001691 0.3551995 0.9294082 -0.1721118 0.3378226 0.9253396 -0.1718359 0.5202512 0.8365472 -0.3853777 0.4732067 0.7921866 -0.007063925 0.6220702 0.7829297 -0.727249 0 0.6863738 -0.5327605 -7.33948e-4 0.8462659 -0.0994749 -0.007205545 0.9950141 -0.7250955 0.009994149 0.6885758 -0.6191571 0.003899812 0.7852575 -0.3114914 -0.001722991 0.9502475 -0.2170279 -0.003441154 0.9761594 0.3369963 1.30923e-5 0.941506 -0.3040814 4.81504e-4 0.952646 -0.09530752 2.22818e-5 0.9954479 0.03589642 -1.98653e-4 0.9993556 0.1141268 -0.001635015 0.9934648 0.1804967 -7.01918e-4 0.9835754 0.2662139 -2.9973e-5 0.963914 0.6356933 1.04866e-4 0.7719418 0.5656992 -4.72022e-4 0.8246116 0.4679233 -0.001681268 0.8837676 0.3769232 -1.35812e-4 0.9262446 0.4758428 -7.69206e-4 0.8795301 0.6406952 0.003190577 0.7677887 0.8519833 -0.001663982 0.5235664 0.8931234 3.58848e-4 0.4498116 0.7890656 -5.86782e-5 0.6143091 0.7410674 -3.56949e-4 0.6714307 0.7546874 -6.22498e-4 0.6560843 0.7042761 -1.09851e-4 0.7099263 0.9334043 1.79022e-4 0.3588262 0.9876413 -3.56596e-4 0.156731 0.9902943 -9.67205e-7 0.1389868 -0.6406509 4.41856e-4 0.7678322 -0.7410714 -4.73311e-4 0.6714262 -0.9814407 -7.36798e-4 0.1917643 -0.9993049 -2.10296e-5 0.03728044 -0.1646571 -8.08885e-4 0.9863506 -0.4760037 -4.62644e-4 0.8794432 -0.6407809 0.003614187 0.7677153 -0.4579253 -0.001830339 0.8889888 -0.5460294 -7.27004e-4 0.8377658 -0.115572 -1.82613e-4 0.9932991 0.09540528 8.04348e-6 0.9954385 0.2196307 1.82337e-4 0.9755831 0.7369393 1.63561e-5 0.675959 0.5628647 1.5646e-4 0.8265491 0.6247487 0.003169655 0.7808195 0.3128899 -0.001836359 0.9497877 0.244538 0.6394561 0.7289013 0.1797049 0.638487 0.7483586 0.4508994 0.4527155 0.7692453 0.4099462 0.4345024 0.8019676 0.4087278 0.3131739 0.857242 0.5108425 0.3278803 0.7946915 -0.3774988 0.2470275 0.8924528 -0.5951015 0.4847137 0.6410201 -0.3806625 0.4897261 0.784388 -0.9671528 0.08332204 0.240152 -0.9645804 -0.07977926 0.2514358 -0.7998088 0.120603 0.5880144 -0.8198221 0.07231378 0.568034 -0.5955886 -0.002265632 0.8032865 -0.46401 0.1527372 0.8725631 0.2066769 0.2589122 0.9435302 0.2059955 0.3336543 0.9199135 0.1721075 0.5029973 0.8469786 0.1146531 0.5281796 0.8413566 0.1150344 0.6462935 0.7543686 0.3349962 0.1500888 0.9301886 -0.04919975 0.1699588 0.9842223 0.3260186 0.3157258 0.8910831 -0.09841477 0.2536024 0.9622892 -0.09962505 0.5261227 0.8445531 -0.1574127 0.5073243 0.8472563 -0.9498131 0.08638113 0.3006552 -0.8270484 0.1415159 0.5440261 -0.7966088 0.1608102 0.582713 -0.6300454 0.1967144 0.7512299 -0.5888903 0.2141817 0.7793167 -0.3338344 0.001499593 0.9426306 -0.0126717 0.08983308 0.9958763 -0.4981353 0.400325 0.7691562 -0.2889122 0.7379822 0.609846 0.2119307 0.7038069 0.6780422 0.4498077 0.6114771 0.6509754 0.7859535 0.3939058 0.4765661 0.5733982 0.5587747 0.5991539 -0.1292893 0.9390491 0.3185452 0.6232011 0.04698657 0.780649 0.7023618 0.2478342 0.6672827 0.6313456 0.175486 0.7553856 0.6626964 0.3781554 0.6463993 0.6930857 0.1876118 0.6960131 0.6752058 0.09853523 0.7310185 -0.2239187 0.08406138 0.9709759 -0.3916686 0.06077682 0.918097 -0.3174475 0.2556071 0.913177 -0.5092376 -0.3255876 0.7966617 -0.5093075 -0.283412 0.8125783 -0.6935314 0.2011581 0.6917729 -0.7051948 0.2004085 0.6801006 0.4688296 -0.004601657 0.8832767 0.3833967 0.1578946 0.909987 0.3203685 0.1226637 0.9393177 0.2373782 0.1331406 0.9622501 0.2365339 0.1311366 0.962733 0.09846699 0.07355988 0.9924179 0.1369189 0.2119185 0.9676486 0.03033328 0.0345717 0.9989418 0.9511024 0.2064335 0.2297592 0.9730697 0.06967484 0.2197291 0.8935738 0.2595519 0.3662768 0.8459863 0.316749 0.4289256 0.8373284 0.3238222 0.4404775 0.8098843 0.2308091 0.5392723 0.705921 0.2573322 0.6598907 0.6865321 0.4767058 0.5490222 0.6692038 0.4833139 0.5644236 0.6479077 0.4122892 0.6404945 0.433937 0.5595515 0.7061167 0.3967008 0.5558054 0.7305539 0.3407334 0.4428191 0.8293442 0.9212555 0.06263285 0.3838822 0.894585 0.09400445 0.4368991 0.8537928 -0.01014882 0.5205141 0.6982819 0.24409 0.672921 0.6997408 0.2442753 0.6713363 0.4168913 0.5100017 0.7523961 0.3803091 0.463053 0.8005916 0.2764282 0.4712479 0.8375637 0.4855992 0.203353 0.8502006 -0.06346768 0.3110375 0.9482761 -0.1099463 0.08793783 0.9900398 -0.07726186 0.1226986 0.989432 -0.1298078 0.3919285 0.9107919 0.02425271 0.308616 0.9508776 0.1718927 0.3682212 0.9137101 0.1057501 0.4168078 0.9028224 0.2457743 0.3762161 0.8933401 0.3816759 0.1450136 0.9128497 0.4854679 0.2185056 0.8465083 0.5724837 0.07228142 0.8167238 0.5299401 0.1204225 0.8394414 -0.06044024 0.72846 0.6824171 -0.123279 0.70157 0.701856 -0.1465595 0.7476671 0.6476992 -0.1378147 0.75506 0.6410082 -0.1266552 0.7665183 0.6296096 -0.1570641 0.7609888 0.6294656 -0.1433043 0.7743102 0.6163665 -0.1942153 0.7704402 0.6072087 -0.1962592 0.7696238 0.6075866 -0.245889 0.7818045 0.5729926 -0.2814339 0.7702822 0.5722416 -0.3200218 0.7888067 0.5247572 -0.2315048 0.06030648 0.9709627 -0.2509532 0.271569 0.9291248 -0.3822022 0.393382 0.8361651 -0.3311011 0.2727478 0.9033165 -0.5824496 0.2583777 0.7707099 0.4455893 0.6150609 0.6505 0.2065598 0.7078517 0.6754844 0.1911677 0.657477 0.7288203 0.2003902 0.6568284 0.7269252 0.1588035 0.6034965 0.7813921 0.1395279 0.6088381 0.7809278 0.05707335 0.5500134 0.8332035 0.02443659 0.5686904 0.8221886 -0.1145872 0.5105288 0.8521915 -0.1395319 0.5366445 0.832192 -0.322598 0.4952588 0.8066283 -0.3300127 0.5125234 0.792724 -0.517975 0.4929421 0.699078 -0.3940205 0.762915 0.5125512 -0.3211849 0.7955374 0.5137709 -0.4552881 0.6385397 0.6204675 0.5352198 0.3869842 0.7508549 0.2562105 0.7397034 0.6222501 0.2514431 0.8257337 0.5049161 0.2136316 0.8182241 0.5337329 0.2765983 0.7897949 0.5474646 0.2079738 0.7915796 0.5745856 0.2833821 0.7578688 0.5876473 0.5608271 0.08191037 0.8238713 0.6034469 -0.1570077 0.7817931 0.2245301 0.05701136 0.9727981 0.01565313 0.1877502 0.9820922 -0.7826523 0.2054413 0.5875791 -0.838752 0.1730508 0.5162835 -0.9699809 0.2045364 0.1315371 -0.6939462 0.4728647 0.5429897 -0.8273232 0.3534328 0.4366024 -0.8693733 0.2732138 0.4117578 -0.9607942 0.1579642 0.227864 -0.9760277 0.04614311 0.2126988 -0.5982891 0.5322481 0.5989676 -0.6434532 0.4885876 0.5892794 -0.6142056 0.3954018 0.6829414 -0.6190201 0.3866805 0.6835878 0.4972069 0.5723592 0.6520663 0.4050555 0.6817998 0.6091627 0.2987961 0.6866667 0.662729 0.3167062 0.6683408 0.673066 0.1918815 0.6661671 0.7206962 0.08619886 0.6798762 0.7282432 0.0289123 0.7210379 0.6922922 0.009010612 0.7225507 0.6912592 0.5821214 0.2611377 0.7700272 0.5349664 0.3817077 0.753731 0.3200089 0.3930851 0.86202 0.3331826 0.3710368 0.8667879 -0.3154442 0.6038167 0.7320522 -0.3265429 0.6409007 0.6947059 -0.4834205 0.09138911 0.8706048 -0.6854113 0.1968554 0.7010417 -0.1097085 -0.9829245 0.1477276 -0.5651669 0.4959094 0.6592878 -0.5537037 0.129623 0.8225631 -0.2815157 0.9147555 0.2897782 -0.4638164 0.2759752 0.8418504 -0.5091908 -0.09959685 0.8548715 -0.4595268 0.3984393 0.7937766 -0.506139 0.1358082 0.8516922 -0.4035204 0.6427426 0.6511937 -0.5170108 0.3586108 0.7772376 -0.4605564 0.5436826 0.7016388 -0.2722836 0.8778804 0.3939386 -0.409344 0.7014508 0.5834418 -0.1761506 0.9599232 0.2179871 -0.3413122 0.8269429 0.4468462 0.1154045 0.9631293 -0.2430307 -0.04425936 0.998922 -0.01400065 -0.5022425 0.6481977 0.5723568 -0.5633982 0.5290462 0.6345807 -0.5733423 0.5045051 0.6455643 -0.6282787 0.3445259 0.6975441 -0.6635923 0.1438702 0.7341299 -0.3846547 0.8080193 0.4462572 -0.4548965 0.714556 0.5314877 -0.4555084 0.6889572 0.563782 -0.5679019 -0.008168637 0.8230558 -0.5496977 -0.2405823 0.7999705 -0.5558673 0.3534376 0.7523919 -0.5861221 0.1523087 0.7957783 -0.5191404 0.536447 0.6653705 -0.5733402 0.3505234 0.7405501 -0.4607646 0.6953206 0.5515664 -0.5370295 0.5318604 0.6547701 -0.3855698 0.8218453 0.4194121 -0.4806034 0.686865 0.5451943 -0.2996282 0.912523 0.2784326 -0.4040737 0.8158927 0.4135741 -0.357896 0.2188094 0.9077627 -0.371485 0.0909065 0.9239779 -0.3535826 0.2750445 0.8940525 -0.3365886 0.3973318 0.8537187 -0.3095287 0.5365261 0.785068 -0.2776203 0.642108 0.7145798 -0.2495229 0.7329344 0.6328867 -0.1238135 0.9334173 0.3367528 -0.1778385 0.838442 0.5151588 -0.1077539 0.9558725 0.2733074 -0.2252025 0.8796226 0.4189844 -0.1192922 0.9615018 0.2475554 -0.1677504 0.01499217 0.9857155 -0.1644631 0.04267764 0.9854596 -0.2093252 0.03834241 0.9770941 -0.2184902 0.2194673 0.9508397 0.04798543 0.05212694 0.997487 -0.04457837 0.02814483 0.9986094 -0.126643 0.02716451 0.9915764 0.8954578 0.05549269 0.4416742 0.9797635 0.1840047 0.07877796 0.4262991 0.8161419 0.3901047 0.3808859 0.6813988 0.6249973 0.5663837 0.7137331 0.4120615 0.6695744 0.6036165 0.4328017 0.8476622 0.5272233 0.05919945 0.7813435 0.4542727 0.4279472 0.8658307 0.2339652 0.4422643 0.02603894 0.9259557 0.3767334 0.04654961 0.9366884 0.3470565 -0.03827947 0.8331725 0.5516867 -0.07657909 0.729758 0.6794034 -0.06238186 0.8008154 0.5956535 0.2111207 0.7194648 0.6616634 -0.2734549 -0.1109808 0.955461 -0.2291257 0.1978735 0.9530727 -0.1325858 0.1703204 0.9764283 -0.09951382 0.2626881 0.9597354 -0.03762507 0.2162089 0.9756219 -0.04666006 0.1823421 0.9821274 0.01840221 0.1120809 0.9935287 0.09129798 0.1762244 0.980107 0.1392048 0.05375301 0.9888038 0.2896562 0.08527123 0.9533248 -0.1553276 0.5365605 0.8294434 -0.1549971 0.5474612 0.8223516 0.04785561 0.4886927 0.8711426 0.07281029 0.5506536 0.8315524 0.2258183 0.4387564 0.8697695 0.2339218 0.4620295 0.8554585 0.3587108 0.3238322 0.8754767 0.3832575 0.3459011 0.8564265 0.4734417 0.1162826 0.873116 0.5141282 0.1340401 0.847175 0.2517709 0.8812975 0.399908 0.2474053 0.8799034 0.4056609 0.3255106 0.9233313 0.2037209 0.300844 0.7219445 0.6231285 0.4350801 0.6208347 0.652127 0.4403308 0.638763 0.6309444 0.6028731 0.4521477 0.6573482 0.6210286 0.4686672 0.6282313 0.7442402 0.1544703 0.6498042 0.7724782 0.1666451 0.6127862 0.04821127 -7.60241e-4 0.9988369 0.04839247 0 0.9988285 0.2891911 0 0.9572714 0.4907755 0.06800222 0.8686283 0.5186412 0 0.8549921 0.8305861 0 0.5568902 0.7724699 0.166889 0.6127302 0.8969065 9.55534e-4 0.4422194 -0.8179557 0.001025855 0.5752803 -0.04641085 -7.53497e-4 0.9989222 -0.04695105 0 0.9988972 -0.3881574 0 0.9215931 -0.4780117 0.1454379 0.8662291 -0.6008048 0 0.7993958 -0.8176497 0 0.575716 -0.1907948 0.8430332 0.5028842 -0.4661279 0.6495197 0.6007072 0.01188111 0.8973147 0.4412315 -0.04947191 0.1048886 0.9932528 0.04447919 0.01427918 0.9989083 -0.04646134 0.04937207 0.9976993 0.2542189 0.09265512 0.9626983 0.1379572 0.388113 0.9112278 0.1930022 0.0886293 0.9771873 0.01989704 0.2141039 0.9766083 0.04249274 0.1802836 0.9826964 0.07637852 0.07365107 0.994355 -0.4688178 0.6554532 0.5921072 -0.7627668 0.5166909 0.3888666 -0.6945432 0.4403106 0.5689784 -0.8642022 0.1967056 0.4631 -0.8079369 0.1535267 0.5689178 -0.2243881 0.8520939 0.4728488 -0.05802053 0.6537492 0.7544837 -0.2527779 0.7550457 0.6049869 -0.5948699 0.1369165 0.7920757 -0.6325856 0.1362956 0.7624034 -0.5252886 0.4123963 0.7443127 -0.4953457 0.4065138 0.7677104 -0.3603765 0.5593318 0.7465098 -0.3361117 0.554481 0.7613013 -0.2235609 0.638621 0.7363312 -0.4034766 0.7954629 0.4521565 -0.3337455 0.7997211 0.4990593 0.2011877 0.09542417 0.9748937 -0.1637079 0.8152987 0.5554167 -0.1690093 0.9606018 0.2206357 -0.003735542 0.8913276 0.4533448 0.1278765 0.6198025 0.7742689 0.06257683 0.6873723 0.7236046 0.2401371 0.3006912 0.9229947 0.1721816 0.4152945 0.8932436 0.03941327 0.377299 0.9252525 -0.01428496 0.4309801 0.9022484 -0.1196491 0.3529505 0.9279602 -0.1460427 0.3619056 0.920704 -0.2362024 0.2632175 0.9353743 -0.2709997 0.2735497 0.9228921 -0.3406237 0.09581404 0.9353049 -0.3866548 0.09337013 0.9174858 0.3652706 0.09091454 0.9264513 0.127952 0.9027647 0.4106631 0.3652573 0.09217846 0.9263316 0.3499105 0.2995023 0.8876153 0.3500941 0.2982594 0.8879615 0.2876249 0.6205515 0.729512 0.2876121 0.6205897 0.7294846 0.1188954 0.9460042 0.3015624 0.1950885 0.8698746 0.4530548 0.1194961 0.9513392 0.2840327 -0.3118546 0.8018075 0.5097563 -0.1818748 0.1747249 0.9676739 -0.969964 0.1737865 0.1702 -0.5140618 0.1720622 0.8403185 -0.4230697 -0.1102823 0.8993609 -0.6070693 0.1753634 0.7750578 -0.8281818 0.1720758 0.53339 -0.7941367 -0.0348491 0.6067394 -0.8957825 0.1758024 0.4082492 0.03842395 0.1757264 0.983689 0.2816008 0.2216247 0.9335864 0.1571719 0.1762557 0.9717155 0.143908 0.3864414 0.9110179 -0.09921658 0.03753912 0.9943576 -0.07869529 0.6097201 0.7887006 0.1440431 0.3864548 0.9109909 -0.3118585 0.8018049 0.5097579 -0.5024139 0.801795 0.3235818 -0.5023915 0.8018105 0.3235782 -0.5846831 0.8047486 0.1025937 -0.584693 0.8047415 0.1025928 -0.8381056 0.5253116 0.1470613 -0.7173887 0.5214065 0.4620485 -0.7174013 0.5213897 0.462048 -0.4453061 0.5213893 0.727912 -0.4453045 0.5213971 0.7279074 -0.1655768 0.5279608 0.8329716 -0.1260919 0.8073611 0.5764278 -0.1619396 0.8499003 0.5014432 0 1 1.90263e-7 0 1 0 0 1 1.10073e-6 0 1 -7.47518e-6 0 1 6.21044e-7 -0.1411321 0.4052367 0.9032525 0.1800485 -0.038796 0.9828923 -0.04285138 0.1757894 0.9834947 -0.2843854 0.1739631 0.9427947 0.6099265 -0.1180652 0.7836136 0.51406 0.1720675 0.8403185 0.7815057 0.1746417 0.5989568 0.840027 0.04053914 0.541028 0.8951608 0.1757667 0.4096257 0.9699598 0.1738104 0.1701998 0.9699662 0.1737822 0.1701922 0.5846931 0.8047417 0.1025913 0.134957 0.7633937 0.6316777 0.5846806 0.8047505 0.1025933 0.5023968 0.8018067 0.3235791 0.5024057 0.8017999 0.3235824 0.3118439 0.8018133 0.5097538 0.311864 0.8018061 0.5097528 0.1227655 0.8071729 0.5774086 0.1604857 0.8527988 0.4969694 -0.1443903 0.3865019 0.910916 0.09095919 0.4009901 0.9115555 0.09780627 0.1720542 0.98022 0.4163582 0.1752808 0.892145 0.04929083 0.636065 0.7700597 0.1771403 0.5286049 0.8301796 0.4453099 0.5213919 0.7279077 0.4453002 0.5213891 0.7279157 0.7173849 0.5214098 0.4620506 0.838109 0.525306 0.1470612 0.8381003 0.5253202 0.1470596 0.8147984 2.46656e-4 0.5797445 0.7491998 -0.03141796 0.6615986 0.7936916 -0.005574166 0.6082949 0.6337307 0.004451453 0.773541 0.6142274 -0.004575073 0.7891158 0.5312501 8.00908e-5 0.8472151 0.422913 -7.38821e-4 0.9061701 0.428909 -0.003470897 0.9033411 0.1801902 0.004680991 0.9836207 -0.04354262 0 0.9990516 -0.2093375 0.05440855 0.9763286 -0.2887626 -3.17587e-6 0.9574007 0.9999985 0 0.00173068 0.9986432 -1.08771e-4 0.0520755 0.9738514 -0.01302951 0.2268122 0.9336922 -0.06147933 0.3527593 0.8832191 -4.75763e-5 0.4689608 0.9093097 -0.002721786 0.4161112 0.9845365 0.02908694 0.1727477 0.259906 0.9643544 -0.04969358 0.9843258 0.1763601 0 0.9909647 0.1337929 -0.009412586 0.9911561 0.1326829 -0.002222597 0.8473207 0.5310724 0.003122925 0.8744708 0.485078 -6.18073e-4 0.3696029 0.929166 -0.006664752 0.5634092 0.8253946 0.03597247 0.5948925 0.8038053 0 0.5877897 0.8090137 4.61788e-4 -0.5387836 -0.3122658 -0.7824337 -0.4472056 0 -0.8944313 -0.2012088 0 -0.9795485 -0.2012327 0 -0.9795435 0.5388619 -0.311929 -0.782514 -0.9747191 0.2232387 -0.009349465 -0.6501173 0.7557424 -0.07874614 -0.4858294 0.8738607 0.01836699 -0.2468545 0.9685376 -0.03158795 -0.5782477 0.8158611 -6.2113e-4 -0.8473155 0.5310895 7.64197e-4 -0.8142604 0.5804927 -0.002872526 -0.9843195 0.17637 0.002956688 -0.9749602 0.2223801 0 -0.9852741 -0.02014076 -0.1697917 -0.9656592 0.08454144 -0.2456728 -0.9943872 -0.001705825 -0.1057887 -0.9185786 0.001867711 0.3952341 -0.9832211 -0.005607306 0.1823318 -0.9663619 -0.03219962 0.2551622 -0.9772713 -0.02180528 0.2108687 -0.9823241 -0.01647478 0.1864619 -0.9886074 -0.01007568 0.1501802 -0.9953981 -0.003296494 0.0957697 -0.9992591 -3.58993e-4 0.03848791 -0.9999691 0 0.007866382 -0.8524707 -3.69483e-6 0.5227752 -0.798343 -0.04860532 0.6002384 -0.8622758 -0.01414644 0.5062415 -0.1731964 -0.9848874 0 -0.2588177 -0.9659167 0.004297316 -0.9848755 -0.1732525 -0.002019345 -0.9466494 -0.3222544 0.00266838 -0.8447154 -0.5352157 0 -0.7933387 -0.6087797 -0.001043498 -0.6774622 -0.7355502 0.003316104 -0.6087392 -0.7933704 0 -0.4222022 -0.9065017 0 0.9827637 -0.02341663 -0.1833773 0.9843463 -0.001651942 -0.1762375 0.9999536 -0.001688361 -0.009494364 0.9980325 0.05006486 0.03774476 0.5578172 0.8171606 -0.1452187 0.7260495 0.6789593 0.1089336 0.8669264 0.4808967 -0.1310611 0.976573 0.202922 -0.07160931 0.9885326 0.1333493 0.07086217 0.9266679 0.3757155 0.01115453 0.861448 0.4861288 -0.1469228 0.8591402 0.5058315 0.07754188 0.7310711 0.6801403 0.05426132 0.7189521 0.6824494 0.1317983 0.5055094 0.8627888 0.007480919 0.5141265 0.8577004 -0.004921376 0.3646628 0.9273934 -0.08344161 0.4424232 0.8962026 -0.03290432 3.22117e-6 1 1.23433e-5 9.53192e-6 1 2.8122e-5 5.29459e-5 1 -5.0785e-5 9.54796e-5 1 -4.76713e-5 3.36611e-7 1 0 -8.09224e-5 1 -4.09733e-5 -2.6646e-6 1 1.35472e-5 2.66457e-6 1 1.3547e-5 -0.4963005 0.8518741 -0.1673215 -0.4069665 0.9086785 -0.09317708 -0.5096269 0.8603895 -0.003247201 -0.9974327 0.06084531 0.03776073 -0.8126087 0.5792829 -0.06402039 -0.7265772 0.6792026 0.1037768 -0.6520724 0.7580504 0.01270037 -0.4850743 0.8725633 0.05776125 -0.9696391 0.2220509 -0.1024373 -0.9695739 0.2277712 -0.08970385 -0.8901625 0.4454855 0.09567356 -0.8919483 0.4463412 0.0721656 -0.7306906 0.6794104 0.06702905 -0.6775134 0.6727304 0.2973372 -0.4561242 0.8815185 -0.1219675 0.9848794 -0.1732414 0 0.98488 -0.1732383 -8.53579e-7 0.9333372 -0.3590011 0 0.8334347 -0.552617 -0.001146316 0.8435809 -0.5370022 -2.39706e-6 0.5369582 -0.8436089 2.17967e-6 0.5368652 -0.8436681 -3.76053e-6 0.1732434 -0.9848791 2.72812e-6 0.173189 -0.9848886 0 0.7823092 2.75865e-6 0.6228903 0.8523079 -0.01945817 0.5226785 0.8605102 -0.01444542 0.5092285 0.9997068 -9.50485e-5 0.02421385 0.9960179 -0.00229752 0.08912414 0.989525 -0.009361803 0.1440578 0.9851648 -0.0135861 0.1710727 0.9831131 -0.01581054 0.1823151 0.9646895 -0.002933979 0.2633738 0.9191473 0.001927018 0.3939093 0.963871 -0.2510707 -0.08897477 0.9852727 -0.01462048 0.1703642 0.9883248 -0.00212264 0.1523473 0.9859198 -0.06775754 -0.1528767 0.9998963 -0.004769861 0.01359462 0.998606 -0.03670126 0.03793495 0.9974787 -0.02395713 0.06680154 0.9916255 -0.0812354 0.1003986 0.9717235 -0.03769141 0.2330941 0.9676781 0.03666836 0.2495087 0.9732306 -0.1626302 0.1623997 0.9772267 -0.1306312 0.1672225 0.9537626 -0.2932789 0.06576097 0.9311135 -0.3596091 0.06090205 0.8988131 -0.4357173 -0.04780662 0.9997564 0.003181636 0.02184116 0.9819607 -0.1117175 -0.1525536 0.9741597 -0.2127135 -0.07593387 0.9567309 -0.2192171 -0.1913374 0.9634585 -0.23493 -0.1286684 0.7056628 -0.1766522 0.6861736 -0.1082624 -0.9846459 0.1369368 -0.1203267 -0.9798586 0.1593695 -0.03647714 -0.9878944 0.1507791 0.03296399 -0.9880761 0.1503961 0.126477 -0.978987 0.1599627 0.1061417 -0.9843851 0.1404279 0.5645986 0.1224877 0.8162263 0.6107684 -0.1736282 0.7725381 0.343872 -0.1756471 0.9224424 0.2320846 0.1615055 0.9591938 -0.1265566 -0.1754645 0.9763174 -0.3525308 -0.1758355 0.9191321 -0.5676795 -0.1752293 0.8043847 -0.6201748 0.006606638 0.7844359 -0.7122827 -0.1772207 0.6791512 -0.3357273 -0.8408094 0.4246491 -0.3357089 -0.8408223 0.424638 -0.1281481 -0.8384785 0.5296526 0.1281421 -0.8384645 0.5296763 0.1281648 -0.8384768 0.5296515 0.3357023 -0.8408329 0.4246225 0.3357374 -0.8408007 0.4246583 -0.5240668 -0.5347695 0.6628542 -0.5240865 -0.5347274 0.6628725 -0.1992422 -0.531161 0.8235112 0.1992781 -0.5311076 0.8235369 0.1992364 -0.5311785 0.8235012 0.5240574 -0.5347805 0.6628527 -0.9859917 -0.04077869 0.1617332 -0.9821886 -0.07491165 0.1723187 -0.9444544 -0.2359319 0.2287839 -0.9700314 -0.05529451 0.2366041 -0.9999973 -0.001856267 0.00146228 -0.9998679 -0.01418495 0.007944583 -0.9998115 -0.01174724 0.01545989 -0.9983531 -0.0400753 0.04105055 -0.9831299 -0.1112555 0.1451828 -0.9229968 -0.384727 0.007883191 -0.9513926 -0.3079687 -0.002741456 -0.9859713 -0.04950046 -0.1594061 -0.9843612 -0.08946084 -0.1517557 -0.9842864 -0.09519058 -0.1487249 -0.9795542 -0.1435347 -0.1409661 -0.9789179 -0.1601176 -0.1268159 -0.9686996 -0.2300516 -0.09325987 -0.9687833 -0.2176329 -0.118723 -0.9680047 -0.2302501 -0.09975957 -0.5900718 -3.29046e-6 0.8073509 -0.6311447 0.004328012 0.7756531 -0.4054639 -0.001253426 0.9141103 -0.2485669 0.002755522 0.9686108 -0.1128264 -0.00500822 0.9936022 0.3136476 -2.49873e-4 0.9495394 0.1048998 -0.003410458 0.994477 0.1370012 7.77851e-6 0.9905709 -0.1941441 -1.03321e-5 0.980973 0.9117716 -0.02177387 0.4101201 0.7799738 5.21233e-4 0.6258119 0.7059077 -8.40767e-5 0.7083039 0.5492377 -0.002604007 0.8356621 0.5994275 -0.01274394 0.8003277 0.4297906 9.51851e-4 0.9029281 0.8550257 0.01243948 0.5184366 0.9931575 0 0.1167824 -0.8198702 -0.2993443 0.4880635 -0.8236775 -0.4304115 0.3691901 -0.3968228 -0.8996382 0.1821613 -0.5721104 -0.7940836 0.2052341 -0.8206439 -0.5644979 0.08880323 -0.9567896 -0.2888331 -0.03360438 -0.9837949 6.919e-4 -0.1792966 -0.6073392 -0.7491554 0.2643962 -0.2625789 -0.9645085 -0.02785265 -0.3853974 -0.9210479 0.05603182 -0.9811469 -0.06516242 0.1819472 -0.9811476 -0.06513494 0.1819532 -0.8506535 -0.06516462 0.5216726 -0.8497323 -0.07121312 0.5223827 -0.9324018 -0.3173791 0.1729093 -0.9139563 -0.3569367 0.1930808 -0.8184112 -0.3579745 0.4495082 -0.834581 -0.5286967 0.1547722 -0.6721893 -0.7298104 0.1246528 -0.652336 -0.7453004 0.1377871 -0.4089348 -0.9099137 0.06949388 -0.3983364 -0.9119807 0.0980786 -0.8683077 -0.4820815 0.1167874 -0.8673187 -0.4685147 0.1680848 -0.9208936 -0.304754 0.2430635 -0.9230129 -0.2628692 0.2809755 -0.9430491 -0.09778773 0.317956 -0.9408644 -0.1094347 0.3206218 -0.8881927 -0.156501 0.4319969 -0.8580859 -0.3581978 0.3679441 -0.8966034 -0.1631778 0.4116739 -0.7898406 -0.2274538 0.5695759 -0.8217942 -0.1746635 0.5423533 -0.8041944 -0.5400518 0.2482246 -0.8221131 -0.5169278 0.2385702 -0.7658858 -0.5524798 0.3289148 -0.7588921 -0.5581362 0.3355098 -0.7329748 -0.5581869 0.3888127 0.783603 0.6187801 -0.05547624 0.4584897 0.888563 0.01558768 0.4689215 0.8831127 0.01499128 0.4884036 0.8725921 -0.006705582 0.4946167 0.8690535 -0.01001995 -0.4674769 0.8839196 0.01231753 -0.6499344 0.7574146 0.0625174 -0.5392602 0.8412723 -0.03820252 -0.4821541 0.8760843 -0.001973628 -0.4561445 0.8893169 0.03237199 0.9197326 -0.3535543 0.1705617 0.8309817 -0.5313491 0.1647344 0.8236488 -0.5461421 0.1527475 0.5367223 -0.8378679 0.09953188 0.5330435 -0.8404659 0.09737384 0.5343043 -0.8394604 0.0991218 0.3630246 -0.9294348 0.06606155 0.0618245 -0.9980729 0.005305171 0.1731467 -0.9843289 -0.03341829 0.2311636 -0.9725226 0.02762651 0.797298 -0.3782054 0.4704007 0.7554484 -0.5405651 0.3702529 0.7552475 -0.5351347 0.3784603 0.6648733 -0.6669641 0.3363072 0.5828732 -0.7582299 0.292141 0.9688513 -0.1704224 0.1796764 0.9688547 -0.1704111 0.1796686 0.8460776 -0.1707913 0.5049586 0.8429045 -0.1494033 0.516905 -0.9996833 0 0.02516734 -0.9871262 -0.003756284 0.1598992 -0.9861756 -0.002867579 0.1656793 -0.9356445 0.001300573 0.3529418 -0.8567708 -0.009527027 0.5156095 -0.8444539 -0.005864977 0.535596 -0.6932817 0.003321945 0.7206591 -0.5541177 -0.008664488 0.8323934 -0.4843183 -8.84764e-4 0.8748914 -0.1455022 -0.006641685 0.9893357 -0.353136 1.14049e-4 0.935572 0.4183941 -3.95597e-4 0.9082656 0.2923395 -0.00435537 0.9563047 0.2913514 -0.004441678 0.9566059 0.08736544 0.001395165 0.9961754 -0.08234351 -0.002608478 0.9966007 0.4963976 1.05507e-4 0.8680953 0.6263465 -0.001002907 0.7795442 0.6404545 0 0.7679961 0.7686919 -0.1217497 0.627925 0.8900752 -0.1880888 0.4151974 0.7428156 -0.5642017 0.3604186 0.810483 -0.5242559 0.2612916 0.8109936 -0.5236135 0.260995 0.8722633 -0.2701798 0.4076269 0.8022724 -0.07780945 0.5918654 0.7933198 -0.1131093 0.5982058 0.811563 -0.2534162 0.5264463 0.7900297 -0.3175931 0.5243929 0.7940789 -0.355427 0.4930623 0.7643292 -0.5411415 0.3506662 0.8510496 -0.5154001 0.1003856 0.8891456 -0.44802 0.09326416 0.900844 -0.3743786 0.2198199 0.9421103 -0.140055 0.3046524 0.960245 -0.05788379 0.2730914 0.9341536 -0.2223766 0.2791159 -0.9927645 0.07872861 0.09066665 0.9721847 0.01079851 0.2339667 0.9919177 0.08366852 0.09538811 0.9861437 0 0.1658939 0.9945972 -0.04694932 0.09258645 0.3492634 2.84035e-4 0.9370247 0.3642242 -0.01649111 0.9311653 0.5687997 0.01448273 0.8223487 0.5896487 -0.002744376 0.8076553 0.7169969 0.001122534 0.6970756 0.7629304 -0.01648646 0.6462705 0.8638219 0.01269423 0.5036376 -0.6071178 -0.002237677 0.7946088 -0.5764848 0.02153009 0.8168243 -0.381853 -0.02436125 0.923902 -0.358157 -7.51131e-6 0.9336614 -0.2240383 -0.002003073 0.9745783 -0.1285034 0.03147006 0.9912096 -0.0950911 0.001411676 0.9954677 0.1192045 9.67012e-4 0.9928693 0.0629521 0.0713678 0.9954616 0.1793444 -0.003621697 0.9837797 -0.7237753 7.73337e-4 0.6900354 -0.7841463 -0.01885074 0.6202898 -0.769214 -0.009766399 0.6389168 -0.8957307 0.01382499 0.4443821 -0.8717893 0.03777366 0.4884225 -0.9145674 0.002254784 0.4044275 -0.9885229 -0.003178477 0.1510381 -0.9876746 4.14038e-5 0.1565215 -0.7671447 -0.1773406 0.6164734 0.1404511 -0.9700826 0.1980238 0.37999 -0.8332507 0.4016231 0.4510996 -0.7662396 0.4575871 0.4532742 -0.7635676 0.459899 0.9532018 -0.2818036 0.1095131 -0.9031972 0.133114 0.4080632 -0.923036 -0.2526456 0.290129 -0.9866504 -0.01695054 0.1619684 -0.5206639 -0.666912 0.5330457 -0.7593155 -0.4839102 0.4350528 -0.7904974 -0.4571272 0.4076133 -0.9014804 -0.2951893 0.3165381 -0.9545159 -0.1894035 0.2302733 0.6148586 -0.6202261 0.4871022 0.433519 -0.7098945 0.5550777 0.4616085 -0.6925624 0.5543239 0.2531127 -0.7500114 0.6110785 0.2911792 -0.7399209 0.6064089 0.09561324 -0.7741412 0.6257504 0.1001266 -0.7730376 0.6264085 -0.08017295 -0.7620244 0.6425662 -0.2475837 -0.7445935 0.6199057 0.6229548 -0.7014572 0.3462443 0.2758544 -0.843935 0.4600849 0.334311 -0.8289549 0.4484081 0.08561927 -0.866132 0.4924274 0.1509971 -0.8493586 0.5057567 -0.5304136 -0.7028954 0.4739194 -0.1888643 -0.7890794 0.5845375 -0.4147779 -0.7166431 0.5606977 -0.5637071 -0.6481795 0.5119548 -0.8053491 -0.3871407 0.4489264 -0.726475 -0.4978944 0.4736405 -0.7829278 -0.4405047 0.4392946 -0.4643609 -0.7482577 0.4737927 -0.53947 -0.7077568 0.4561277 -0.1449728 -0.8982679 0.4148465 -0.22988 -0.881812 0.4117799 0.1935363 -0.9328069 0.3039983 0.1061016 -0.9437003 0.3133245 -0.1253761 -0.9187157 0.3744896 0.2903195 -0.9203365 0.2620981 0.245076 -0.9285947 0.2786571 -0.8247179 -0.1039032 0.5559176 -0.7050234 -0.4868986 0.5156275 -0.3670285 -0.8439435 0.3912157 -0.5016377 -0.767177 0.3997491 -0.04357302 -0.9766343 0.2104445 -0.2291686 -0.9412002 0.2482417 -0.1357371 -0.969406 0.204518 0.09167772 -0.9857574 0.1409878 -0.171586 -0.8536605 0.491754 0.9914014 -0.06615465 0.1129029 -0.1786282 -0.9632559 0.2005745 -0.1978711 -0.9498666 0.2420757 -0.1494985 -0.9544601 0.2581787 -0.4128522 -0.8595918 0.3010898 -0.4280118 -0.8243452 0.3704876 -0.422279 -0.794198 0.4369555 -0.3940389 -0.8090768 0.4360367 -0.5342237 -0.6649363 0.5219817 -0.5744243 -0.6838057 0.4499406 0.2200781 -0.78621 0.5774422 0.7534826 -0.3777287 0.5381312 0.8593551 -0.3131967 0.4042484 0.6943214 -0.5472268 0.4673979 0.6436199 -0.6117042 0.4599689 0.4543647 -0.7553479 0.4722314 0.3891693 -0.8022623 0.4526835 0.08088237 -0.9068867 0.4135391 0.1528166 -0.9533588 0.2602965 -0.06795036 -0.9881198 0.1378479 -0.07052338 -0.9883018 0.1352267 0.005915641 -0.9992433 0.03844422 0.1184522 -0.9606539 0.251224 0.3889749 -0.8366813 0.3855684 0.4114583 -0.8164135 0.4051804 0.6089993 -0.6286494 0.4836527 0.6254836 -0.6003981 0.4982897 0.7719402 -0.3475546 0.5322728 0.8147216 -0.3741412 0.4429978 -0.6205204 -0.5721347 0.5362988 -0.5021795 -0.6725665 0.5435716 -0.4343334 -0.6964755 0.5712061 -0.4077998 -0.7106373 0.5733184 -0.2577581 -0.7447454 0.6155608 0.1663509 -0.7694076 0.6167166 -0.0990051 -0.808068 0.5807101 0.05296629 -0.8059877 0.5895579 0.694936 -0.5486627 0.4647939 0.5034814 -0.6675466 0.5485326 0.4352634 -0.7087372 0.5551914 0.1229172 -0.7909533 0.5994033 0.1648136 -0.8964574 0.4113402 -0.1388285 -0.929351 0.3421013 -0.002291798 -0.9132443 0.4074063 -0.4001926 -0.8648073 0.3032395 -0.3668241 -0.9083264 0.200956 0.07978332 -0.982082 0.1707327 0.4367114 -0.8444218 0.3102177 0.4327898 -0.8390857 0.3295882 0.6111359 -0.5416467 0.5771757 0.7112668 -0.6223913 0.3266937 0.5986758 -0.1731771 0.7820467 0.8868401 -0.3671023 0.2806255 0.8148719 -0.1929475 0.546585 0.8301257 -0.154138 0.5358478 0.9587029 -0.06279492 0.2773904 0.8896344 -0.229496 0.3948194 0.9950238 -0.02331662 0.09687113 0.8698726 -0.3374384 0.3598014 0.9210701 -0.272993 0.2776775 0.7594725 -0.4796063 0.4395219 1 -8.33778e-6 0 -0.7767741 -0.3251965 0.5393231 -0.6279937 -0.09931284 0.7718556 -0.6202471 -0.5304655 0.5778407 -0.4356378 -0.6086385 0.6631583 -0.259047 -0.6532002 0.7114943 -0.1442409 -0.6446986 0.7507053 -0.1002693 -0.6727683 0.7330273 0.05355083 -0.6752135 0.7356759 0.1863991 -0.6411694 0.7444174 0.2221899 -0.6592438 0.7183519 0.5049583 -0.5836193 0.635929 -0.7947643 -0.3098588 0.5218596 -0.4314959 -0.4606264 0.775651 -0.4311088 -0.4605605 0.7759055 -0.1422619 -0.5052777 0.8511498 -0.142246 -0.5052677 0.8511584 0.1840151 -0.501721 0.8452305 0.183618 -0.5018224 0.8452566 0.5002076 -0.442032 0.7445805 0.4998874 -0.4422963 0.7446386 -0.5338283 -0.154628 0.8313349 -0.4305527 -0.172422 0.8859431 -0.3997499 -0.1681253 0.9010737 -0.1420642 -0.181569 0.9730625 -0.1901561 -0.1940919 0.9623768 0.1827265 -0.1609823 0.9698947 0.1347651 -0.1815205 0.9741092 0.4990835 -0.1590955 0.8518241 0.5440571 -0.1373842 0.8277243 0.9209575 -0.2634692 0.2870914 0.9209066 -0.2636266 0.2871101 0.9192028 -0.2011816 0.3385149 0.9189931 -0.2016081 0.3388302 0.9917066 -0.06580001 0.110402 0.991736 -0.06559365 0.1102605 0.9919264 -0.0858199 0.09336495 0.9919382 -0.08567386 0.09337323 0.7594336 -0.4399663 0.4792603 0.7594233 -0.4399203 0.4793186 0.7554879 -0.3345612 0.5633 0.7551407 -0.3349258 0.5635488 0.7554174 -0.1313468 0.6419445 0.9135442 -0.01931154 0.4062809 0.8491907 -0.1173729 0.5148775 0.9912901 -0.01142346 0.1312006 0.9865412 -0.03007078 0.1607245 -0.8988714 -0.2507774 0.3593621 0.4302673 -0.2206133 0.8753286 0.4300212 -0.5164306 0.7405277 0.1419779 -0.5588642 0.8170148 0.2509883 -0.5536324 0.7940379 0.4304876 -0.516153 0.7404502 0.4309115 -0.2203999 0.8750653 0.1421627 -0.2417764 0.9598614 0.1420241 -0.2418628 0.9598602 -0.1835584 -0.2401653 0.9532193 -0.1835135 -0.2401307 0.9532366 -0.4117749 -0.5211745 0.7475417 -0.2450876 -0.5544089 0.7953383 -0.07907474 -0.5700299 0.81781 0.09458136 -0.5692202 0.8167269 -0.560213 -0.4738144 0.6794567 -0.4996228 -0.485736 0.7172431 -0.4996186 -0.2117246 0.8399726 -0.4992176 -0.2116793 0.8402224 -0.7546701 -0.3756085 0.5379513 -0.7540531 -0.3757418 0.5387226 -0.7548848 -0.1604412 0.6359304 -0.7544426 -0.1604123 0.6364623 -0.7590588 -0.08487957 0.6454652 -0.4989101 0.09815603 0.8610773 -0.5539854 -0.03761053 0.8316764 -0.1861959 -0.02659046 0.9821528 -0.1454359 0.04322773 0.9884229 0.1445192 -0.08490526 0.9858527 0.2901594 0.08605551 0.9531013 0.4359292 -0.07339924 0.8969829 0.6260827 0.02271974 0.7794256 0.731126 -0.1667149 0.6615595 0.7817217 -0.1694134 0.6001754 0.4751475 -0.5033622 0.7217072 0.6140816 -0.4792671 0.6270622 -0.9535077 -0.1727516 0.2469412 -0.9191281 -0.2180079 0.3281406 -0.9189062 -0.09652715 0.3824838 -0.9187961 -0.09654819 0.3827431 -0.9204982 -0.06043338 0.3860452 -0.8504955 0.1214137 0.5117775 -0.9916262 -0.0739603 0.1058655 -0.9916655 -0.07381099 0.1056014 -0.9917022 -0.03149861 0.1246383 -0.991688 -0.03149521 0.1247523 -0.9919436 -0.00437653 0.1266052 -0.9859274 0.04948878 0.1596816 -1 -1.33319e-5 0 -1 1.63129e-5 2.58916e-4 0.001513898 0 -0.9999989 -1.27586e-4 0 -1 2.46542e-5 0 -1 -2.77739e-4 0 -1 2.77739e-4 0 -1 1.41102e-4 0 -1 5.83322e-4 0 -0.9999998 0.9999302 -0.01182216 0 0.9979452 -0.06279271 -0.01274478 0.9782211 -0.1662066 -0.1243339 -0.9999302 -0.01182216 0 -0.9829402 -0.1791005 -0.0418542 -0.9858763 -0.1674754 0 -0.8960372 -0.4439789 0 -0.6427689 -0.5491357 -0.5341332 -0.8346301 -0.5508109 0 -0.4738188 -0.8806223 0 0.9722985 -0.1381417 -0.188554 0.8346216 -0.5508239 0 0.8345398 -0.5509476 0 0.4739342 -0.8805604 0 0.473811 -0.8806266 0 0.123122 -0.9923916 0 0 -0.9529026 0.3032768 -0.123122 -0.9923916 0 -0.4739264 -0.8805645 0 -0.9858711 -0.1674972 0.001710176 -0.9761756 -0.1884228 -0.1076026 -0.827546 -0.5407762 0.1507613 -0.8195586 -0.5409359 0.1889765 -0.5419375 -0.8281608 -0.1430157 -0.4255152 -0.7906551 0.4402288 -0.1772046 -0.935545 -0.3055393 -0.1231003 -0.99234 0.01037663 0.9858661 -0.1675267 0.001731812 0.1106366 -0.8917009 -0.4388953 0.4472362 -0.6688495 0.5938183 0.4634236 -0.8610414 -0.2093955 0.7635121 -0.6380536 0.09968411 0.8775309 -0.4701534 0.09431517 0.9761704 -0.1884312 -0.1076342 0.7457803 -0.08497017 0.6607511 0.7241933 -0.111815 0.6804715 0.663489 -0.312352 0.6798666 0.6841465 -0.1197793 0.7194418 0.3906261 -0.2221119 0.8933519 0.5857122 -0.09556406 0.8048657 0.2495865 -0.2429902 0.9373699 0.4527472 -0.08512103 0.8875666 0.07973372 -0.2471362 0.9656947 0.284021 -0.08919787 0.9546601 -0.1166589 -0.2398404 0.9637777 0.1085812 -0.089827 0.9900208 0.0276001 -0.1258127 0.99167 -0.3651845 -0.2154782 0.9056542 -0.1436762 -0.105023 0.9840363 -0.5102282 -0.256052 0.8210387 -0.3210807 -0.09466195 0.9423091 -0.7054764 -0.2519931 0.6624218 -0.5460396 -0.1145167 0.8298957 -0.8633079 -0.2344981 0.4468896 -0.7472545 -0.1361244 0.6504468 -0.9424155 -0.2177645 0.2538343 -0.8716359 -0.1580995 0.4639565 -0.9722064 -0.2059615 0.1113308 -0.9543761 -0.1807398 0.2376962 -0.9820197 -0.1882894 0.01358479 -0.981048 -0.1861689 0.05372309 -0.5487983 -0.8348717 0.04254245 -0.1872137 -0.9805347 0.05918443 -0.2025838 -0.9578304 0.2037663 -0.1524689 -0.9806642 0.1226826 -0.089024 -0.9316475 0.3522893 -0.08708614 -0.9350972 0.3435248 0.3083614 -0.8580191 0.4107513 0.2892209 -0.8660604 0.4077875 0.286094 -0.8730972 0.3947806 0.100482 -0.8487922 0.5190908 0.116084 -0.8788766 0.46271 0.07672476 -0.912453 0.4019239 -0.5437248 -0.8349625 0.08485901 -0.5249438 -0.8193015 0.2306058 -0.4166862 -0.8154349 0.4017944 -0.4207372 -0.8172442 0.3938177 -0.2534933 -0.7948703 0.5512916 -0.2825572 -0.8076005 0.517632 -0.0489245 -0.7669139 0.6398825 -0.1201379 -0.7980718 0.5904645 0.1451877 -0.7455078 0.6504911 0.04599487 -0.7894509 0.6120881 0.3146468 -0.7326987 0.6034485 0.1659493 -0.7968508 0.5809386 0.3846836 -0.7146219 0.584238 0.4469009 -0.7013622 0.5553114 0.3840342 -0.7545943 0.5320763 0.5123898 -0.695534 0.5036758 0.4613456 -0.7415883 0.4870391 0.5656566 -0.6888071 0.4534066 0.6021797 -0.6452779 0.4701023 0.5855075 -0.6082257 0.5359503 -0.8356713 -0.5483118 0.03174471 -0.830347 -0.5479561 0.101331 -0.8268027 -0.5462483 0.1342018 -0.7853454 -0.5434576 0.2964563 -0.7917358 -0.5462604 0.2734118 -0.6816121 -0.5259056 0.5087518 -0.7151188 -0.5409065 0.4427475 -0.4959746 -0.5071282 0.7048619 -0.5688948 -0.5381782 0.6218706 -0.2605459 -0.4821585 0.8364443 -0.3826493 -0.5341823 0.7538096 -0.02823555 -0.4648033 0.8849637 -0.1765269 -0.52907 0.8300141 0.1894915 -0.4554613 0.8698552 0.01871907 -0.5301979 0.8476673 0.3509551 -0.4494466 0.8214793 0.1782277 -0.5270752 0.8309192 0.4854896 -0.4524865 0.7480347 0.3268149 -0.5253429 0.7856253 0.5965733 -0.4600266 0.657629 0.459662 -0.5242964 0.7168154 0.6841536 -0.4729804 0.5551788 0.7509872 -0.4319653 0.4994239 0.7119754 -0.3903648 0.5837005 -0.5859307 -0.6613414 0.4683087 -0.3205878 -0.872826 0.3679649 -0.4188207 -0.7443829 0.5200801 0.177854 -0.9755113 0.129405 0.1873719 -0.9817504 0.03252542 0.8444026 -0.1321443 0.5191555 0.8565329 -0.1384387 0.4971783 0.9417222 -0.1232367 0.3130049 0.978002 -0.1333939 0.1603689 0.9050921 -0.1645455 0.3920881 0.5307963 -0.06145298 0.8452686 0.5997357 -0.08913987 0.7952177 0.6671216 -0.1164589 0.7357895 -0.06420505 -0.08063703 0.9946736 0.09324532 -0.1067591 0.989903 0.3194925 -0.1364924 0.9377071 0.2376931 -0.1025315 0.9659138 0.5238205 -0.1344195 0.8411561 0.6358076 -0.1818428 0.7501212 -0.1249354 -0.01405519 0.9920654 0.01900434 -0.1818312 0.9831461 -0.3245322 -0.03362536 0.9452769 -0.2580854 -0.2223584 0.9401856 -0.3332194 -0.1623891 0.9287598 -0.09261292 -0.8142507 0.5730783 -0.1294348 -0.8702536 0.4752949 -0.1029922 -0.9047884 0.4132198 0.05437725 -0.9340836 0.3528897 0.06190425 -0.9211968 0.384141 0.09306693 -0.9564339 0.2767182 -0.3885536 -0.6325552 0.6700001 -0.6407387 -0.6419885 0.4210757 -0.6249415 -0.7185734 0.3051236 -0.5930947 -0.7315335 0.3362997 -0.57816 -0.6721612 0.462526 -0.432164 -0.7379118 0.5183827 -0.5189321 -0.73531 0.4359229 -0.4373263 -0.6627976 0.60782 -0.6485785 -0.5723417 0.5017677 -0.5874307 -0.4454657 0.6756372 -0.9234139 -0.2592315 0.28303 -0.2598105 -0.3228648 0.9100863 0.5294196 -0.8003493 0.2813466 0.5063434 -0.854959 0.1125236 0.4139394 -0.8105928 0.4142386 0.4253802 -0.8547673 0.2973626 0.2640418 -0.7838274 0.5620468 0.3010812 -0.8503335 0.4316053 0.09000027 -0.7612066 0.642234 0.1486585 -0.8426255 0.5175741 -0.08671897 -0.7441066 0.6624087 -0.01179134 -0.8338966 0.5517948 -0.2483029 -0.7345759 0.6314617 -0.1582992 -0.8246313 0.5430697 -0.3212654 -0.7632134 0.5606192 0.8694432 -0.4707437 -0.1498961 0.8950316 -0.4326809 0.1081939 0.7574575 -0.3708238 0.5373526 0.8287795 -0.4460743 0.3378496 0.5826008 -0.3427791 0.7369389 0.7039784 -0.455237 0.5451365 0.3811438 -0.3223668 0.8664925 0.5305543 -0.4582597 0.7130991 0.1670983 -0.3087047 0.9363651 0.3276486 -0.4573258 0.8267403 -0.04511481 -0.3023679 0.9521231 0.1229868 -0.4532176 0.8828749 -0.2395731 -0.2995302 0.9235185 -0.07533425 -0.4500134 0.8898386 -0.4162237 -0.3030973 0.8572573 -0.2526075 -0.4454928 0.8589097 -0.5628709 -0.309 0.766613 -0.7444213 -0.1162928 0.6575052 -0.4939536 -0.1104782 0.862441 -0.7025429 -0.3105639 0.6402996 -0.4108347 -0.4428868 0.7969103 -0.471876 -0.5009914 0.7254934 -0.4290431 -0.5626671 0.7066313 -0.281145 -0.5594121 0.7797536 -0.05177348 -0.656177 0.7528289 -0.1096146 -0.562883 0.819236 0.1323195 -0.663081 0.73676 0.08458262 -0.5700426 0.81725 0.3265689 -0.669658 0.6670166 0.2843157 -0.5836753 0.7605839 0.5043683 -0.6744623 0.5391785 0.4719073 -0.6020034 0.6441238 0.6441064 -0.6751133 0.3596515 0.6284416 -0.6248108 0.463328 0.7368018 -0.670973 0.0831772 0.7547118 -0.6289395 0.1866694 0.1887327 -0.9054054 0.3802911 0.251265 -0.7702518 0.5861555 0.3056193 -0.7680084 0.5628145 0.3836281 -0.752995 0.5346291 0.4209508 -0.7380404 0.5273488 0.4613235 -0.7347512 0.4973142 0.5498914 -0.7042102 0.4491187 0.575345 -0.7230246 0.382379 0.698217 -0.640739 0.3192908 0.6893131 -0.669092 0.2777833 0.7357972 -0.6574994 0.162164 -0.2010471 -0.8969674 0.3937382 0.01860922 -0.94481 0.3270899 0.05525803 -0.9402483 0.3359758 -0.02758675 -0.993918 0.1066111 0.2710881 -0.9619419 0.03433686 -0.4326646 -0.7439528 0.5092501 -0.4514936 -0.7366222 0.5035288 -0.5708727 -0.6974401 0.4332227 -0.5811571 -0.6885403 0.4337842 -0.6440321 -0.6872075 0.336108 -0.3167409 -0.7522596 0.5777376 -0.2332024 -0.735691 0.6359052 -0.3053317 -0.752216 0.5839039 -0.2065558 -0.7911091 0.575744 0 -0.7743589 0.6327466 -0.06078946 -0.9432334 0.3265202 -0.7386425 -0.6541795 0.1626546 -0.6857259 -0.6726617 0.2780402 -0.7298964 -0.6262806 0.2739052 0.2162662 -0.769009 0.6015431 0.2580555 -0.7714987 0.5815471 0.203791 -0.79037 0.5777409 0.125353 -0.7894152 0.6009246 -0.03491407 -0.7909505 0.6108833 -0.2250391 0.9274719 0.2985858 -0.4481711 0.8790522 -0.1625112 0.8123278 0.5131103 -0.2772031 0.4830031 0.8557881 -0.1852967 0.4006853 0.9066979 -0.1317207 0.376381 0.9198759 -0.1102974 0.8869644 0.3785536 -0.264559 0.998593 0.007651269 -0.05247378 0.93195 0.05033159 -0.3590766 0.941599 0.1408416 -0.3058675 0.9728397 -0.07616031 -0.2185925 0.9937809 -0.105743 0.03489995 0.9920054 -0.1157305 -0.05031621 0.987397 -0.1157905 -0.1078874 0.844261 -0.5025988 0.1860585 0.8817864 -0.4532209 0.1305512 0.9716289 -0.2302893 0.05389171 0.787537 -0.5000946 0.3601261 0.806187 -0.3300842 0.4910264 0.6702589 -0.5010483 0.5474518 0.4265621 -0.4912649 0.75941 0.3950389 -0.2265958 0.8902801 0.5395295 -0.5019894 0.6759547 -0.4456152 -0.4160695 0.7926622 -0.4062358 -0.4811542 0.776829 -1.47189e-4 -0.5063471 0.8623298 -0.05326938 -0.3571483 0.9325275 0.1763877 -0.5031925 0.8459815 -0.8029066 -0.3414212 0.4886436 -0.6946002 -0.4987433 0.5184454 -0.5768682 -0.5034041 0.6432788 -0.9768627 -0.2088 0.04628163 -0.9990919 0.001815617 0.04256802 -0.8817077 -0.4534032 0.1304501 -0.8442887 -0.5026103 0.1859021 -0.801499 -0.501986 0.3249762 -0.9282357 0.2263998 -0.2951642 -0.9483411 0.06172734 -0.3111897 -0.9016728 0.2575429 -0.3473584 -0.9711191 -0.03599721 -0.2358645 -0.9773598 -0.07314479 -0.1985386 -0.9825256 -0.1018645 -0.155779 -0.4273055 0.9016686 -0.06636077 -0.3885223 0.9130623 -0.1239661 -0.3449441 0.9358129 -0.07257968 -0.3981549 0.8629905 0.3109987 -0.3431086 0.9275658 0.1479807 -0.3819649 0.9240815 0.01327735 -0.3711493 0.9276576 -0.04122817 -0.1951055 0.8582107 0.4747718 -0.1872881 0.9240821 0.3331601 -0.04778784 0.92738 0.3710563 -8.10326e-5 0.900803 0.434228 0.04771208 0.9273855 0.3710523 0.1422445 0.9272795 0.3462936 0.2125968 0.9008633 0.378481 0.2249765 0.9274733 0.2986286 0.2951797 0.9271807 0.2306622 0.370434 0.9010414 0.2256172 0.3430833 0.927566 0.1480381 0.3709195 0.9270721 0.05437028 0.3711706 0.9276521 -0.04115837 0.3605276 0.9283933 -0.09003221 0.2885563 0.9532791 -0.08940988 -0.6420732 0.7300575 -0.2340045 -0.6775439 0.7059026 -0.2064843 -0.7184971 0.6950814 0.02497667 -0.7184942 0.6950845 0.02497678 -0.6141313 0.6950889 0.373757 -0.6141356 0.6950901 0.3737478 -0.3522959 0.6950895 0.6266883 -0.3522936 0.6950981 0.6266801 -1.39082e-4 0.6951014 0.7189117 -1.1705e-4 0.6950787 0.7189337 0.3520699 0.6950893 0.6268156 0.3520792 0.6950871 0.6268128 0.6140077 0.6950839 0.3739692 0.6140054 0.6950858 0.3739694 0.718473 0.6950971 0.02523297 0.7184855 0.6950842 0.02523255 0.6789546 0.7060917 -0.2011349 0.6816005 0.7016867 -0.207501 -0.8420078 0.4521963 -0.2941792 -0.917435 0.3221115 -0.2335749 -0.9492537 0.3127755 0.03299838 -0.9492556 0.31277 0.03299963 -0.8113881 0.312765 0.4937889 -0.8113909 0.312752 0.4937926 -0.4654594 0.3127478 0.8279713 -0.4654555 0.3127488 0.8279731 -1.48557e-4 0.3127457 0.949837 -1.69339e-4 0.3127685 0.9498294 0.465147 0.3127692 0.8281387 0.8112032 0.3127884 0.4940778 0.8112132 0.3127546 0.4940826 0.9492529 0.3127422 0.03333675 0.9492434 0.3127711 0.03333652 0.9173423 0.3220856 -0.233975 0.9315078 0.2018561 -0.3025679 -0.9889097 -0.1157286 -0.09308391 -0.9920006 -0.1153439 -0.05129063 -0.9937242 -0.1063894 0.03454482 -0.9912821 -0.1247275 0.04246163 -0.8476014 -0.1244599 0.5158312 -0.8475967 -0.1244679 0.515837 -0.4862353 -0.1244679 0.8649179 -1.84215e-4 -0.1244515 0.9922258 -1.73528e-4 -0.1244723 0.9922232 0.4859277 -0.1244754 0.8650896 0.485911 -0.1244829 0.8650981 0.8474173 -0.1244676 0.5161315 0.8474142 -0.1244823 0.5161332 0.991251 -0.1247106 0.04322993 0.9987639 -0.02503794 0.04294085 -0.8880836 0.08634144 -0.4515004 -0.9288044 0.05567795 -0.3663638 -0.9546037 0.03330522 -0.296011 -0.9659264 0 -0.2588172 -0.7070956 0 -0.7071179 -0.7071212 0 -0.7070925 0.7071225 0 -0.7070912 0.7070971 0 -0.7071164 0.9289084 0.2329424 -0.2878664 0.8914272 0 -0.4531641 0.965771 0.01783537 -0.2587823 0.9498258 0.03595781 -0.3107058 0.9655769 0.02687776 0.2587255 0.989427 0 0.1450322 0.9939072 0 -0.1102203 0.7068491 0.02709871 0.7068451 0.7879652 0 0.6157199 0.2586995 0.02720081 0.9655748 0.3799384 0 0.9250119 0.6017244 0 0.7987039 -0.2586995 0.02720415 0.9655748 -0.1277926 0 0.991801 0.1276154 0 0.9918238 -0.7068352 0.0270999 0.706859 -0.6018961 0 0.7985745 -0.380102 0 0.9249446 -0.9938871 0 -0.1104013 -0.965575 0.02688622 0.2587317 -0.9182472 0 0.3960077 0 1 -3.17759e-7 0 1 4.34065e-7 0 1 -1.00243e-6 0 1 7.33839e-7 4.25621e-5 -1 1.07512e-4 -1.82109e-4 -1 4.56901e-4 -0.9986427 -1.10395e-4 0.05208444 -0.7496439 -0.03213423 0.6610608 -0.8156383 2.35543e-4 0.5785622 -0.909963 -1.688e-4 0.4146894 -0.8880031 -0.008816659 0.459753 -0.9845362 0.02908694 0.1727504 -0.9336917 -0.06148952 0.3527591 -0.9738515 -0.01302498 0.2268122 -0.6672942 -0.07482731 0.741026 -0.7915948 0.08711898 0.6048043 -0.542688 -0.03608125 0.8391591 -0.6166544 0.002049088 0.7872315 -0.4286825 -0.00192064 0.9034533 -0.1923614 0.004299461 0.9813147 0.2887828 0 0.9573947 0.2048383 0.05742835 0.9771096 0.03902983 0 0.9992381 -0.8560522 -0.360443 0.3704804 -0.9775812 -0.1719454 0.1215316 -0.980467 -0.1934006 0.03578919 -0.9045316 -0.4213203 0.06566578 -0.902262 -0.426648 0.06240993 -0.792066 -0.607844 0.05618929 -0.7918768 -0.6081199 0.05587029 -0.6078145 -0.79214 0.05546206 -0.6218981 -0.7800782 0.06870967 -0.4221053 -0.9063128 0.02059739 -0.04983067 -0.9987473 0.004565715 -0.1730714 -0.9841262 0.03926819 -0.2209799 -0.9750625 0.02051824 -0.4474601 -0.8934727 0.038549 0.2374817 -0.9711481 0.02176767 0.1729335 -0.9833962 -0.05501067 0.5710285 -0.8138468 0.1076102 0.536088 -0.8424002 0.05451422 0.7693921 -0.6363158 0.05601984 0.8359154 -0.5321419 0.1344264 0.8844957 -0.4610932 0.07113605 0.9608101 -0.2733547 0.04605865 0.9774705 -0.1723766 0.12181 0.9769445 -0.1700776 0.1290469 0.9775835 -0.171939 0.1215223 -0.2502403 0.00695163 0.9681588 -0.2266392 0.002441346 0.9739758 -0.2016535 4.50944e-4 0.9794568 -0.3704223 -0.01064854 0.9288025 -0.2659907 0.01061564 0.9639172 -0.2387214 0.002776145 0.9710842 -0.3667868 -0.00498116 0.9302918 -0.3274762 -0.0258668 0.9445054 -0.3482887 -0.01746553 0.9372246 -0.4836033 0 0.8752874 -0.4826825 0.001000583 0.8757949 -0.4235897 -7.6708e-4 0.9058538 -0.3955438 -0.005384385 0.9184314 0 -7.62941e-4 0.9999998 0 -7.62939e-4 0.9999998 0 0.01934748 0.9998129 0.001106381 0.08196479 0.9966346 0.002311229 0.0949316 0.9954811 -0.001431345 0.03744268 0.9992979 0.4271765 -0.009435892 0.904119 0.4023557 -0.01783502 0.9153096 0.3800029 -0.02622008 0.9246137 -0.1872712 -2.7915e-5 0.9823083 0.003326714 8.08914e-4 0.9999942 0 -0.002331018 0.9999974 0.2053382 2.68975e-4 0.9786911 0.2387362 0.004386007 0.9710746 0.2494055 0.002140462 0.9683969 0.3207073 -0.002153158 0.9471759 0.3667665 -0.01213836 0.930234 0.4829936 0.02946114 0.8751282 0.4835963 0 0.8752912 0.4826055 0.001112461 0.8758372 0.5222118 0.01347088 0.8527094 0.5518383 0.006366193 0.8339269 0.6911003 1.60456e-5 0.722759 0.6819842 0.003219842 0.7313599 0.6236229 -3.94444e-4 0.7817253 0.5882103 0.001006066 0.8087075 -0.6321126 -0.003909587 0.7748668 -0.6815338 0.006246924 0.73176 -0.7113303 0 0.7028579 -0.5690062 0.003545999 0.8223257 -0.5465422 0.007439076 0.8373985 -0.5716104 0.001377522 0.820524 -0.5204926 -2.17161e-4 0.8538662 -0.4813626 0.00123161 0.8765208 1 -1.60149e-6 0 1 0 -1.07875e-6 1 5.82229e-5 3.30714e-6 1 -9.15974e-5 1.81697e-5 1 5.15803e-5 1.41842e-5 1 6.64306e-5 1.52249e-5 1 -1.30115e-6 -5.20461e-6 1 -1.32079e-6 0 1 -8.71022e-7 -1.46504e-5 1 1.37656e-6 0 1 2.71352e-4 -3.5385e-5 1 1.12521e-6 0 0.9999982 8.38842e-4 0.001705229 1 1.27742e-4 -3.72609e-4 1 1.60194e-5 -1.01624e-5 -0.6270686 0 -0.7789641 -0.859857 0 -0.510535 -0.9840933 0 -0.1776529 -0.9840927 0 -0.1776561 1 8.62366e-6 0 1 -3.50833e-6 0 1 5.6484e-6 0 1 -1.37106e-5 0 1 1.15781e-6 0 1 1.59723e-6 0 1 1.94704e-7 0 1 1.07558e-4 0 1 7.29501e-5 0 -1 2.15076e-6 0 -1 -1.33633e-6 0 -1 4.52405e-6 0 -1 -1.31872e-5 0 -1 1.74358e-4 0 -1 1.83332e-5 0 -1 -4.20851e-6 0 -1 -1.0411e-6 0 -1 5.19991e-6 0 -1 -4.58143e-5 0 -1 -8.41751e-5 0 0.7555878 0.07007384 0.6512886 0.5751219 -0.7027096 0.4188485 0.8269484 0 0.5622777 0.6090837 -3.09172e-4 0.793106 0.609194 -0.2057343 0.7658695 0.6904781 0.1200274 0.7133256 0.7109593 -0.03851395 0.7021777 0.7358786 0 0.6771135 -0.8269456 0 0.5622821 -0.578656 -0.6984612 0.421081 -0.5792042 0.5972182 0.554845 -0.712886 0 0.7012801 -0.6943722 0.1733343 0.6984286 -0.6078863 -0.2241602 0.761726 -0.6090822 0 0.7931072 -0.6441837 0.7606378 0.08035844 -0.7070792 0.7070792 0.008825361 -0.3899075 0.9208421 -0.004714965 -0.7768747 0.6296245 0.006221771 -0.8561073 0.5167981 -4.16288e-5 -0.9324809 0.356584 0.05768305 -0.9861647 0.1657485 0.002610087 0.2581033 0.9632996 0.07373362 0.182753 0.9826098 0.03285658 0.05591732 0.9984355 -4.93078e-5 -0.2588168 0.9659265 2.37976e-4 -0.1085105 0.977797 0.1792727 -0.2391763 0.9673203 0.0841791 0.8582617 0.5132124 -2.34777e-5 0.7736285 0.6336184 0.005185365 0.7063023 0.7062879 0.04790097 0.5900437 0.8073707 -0.001152276 0.3720673 0.9282046 0.001448154 0.9099496 0.4147191 1.57596e-4 0.9655318 0.2587088 0.02860438 0.9845656 0.1749942 0.002767264 0.7071068 -0.7071068 0 0.7071115 -0.7071021 0 0.2588172 -0.9659264 0 -0.2588194 -0.9659258 0 -0.7071068 -0.7071068 0 -0.9238748 -0.3826949 0 -0.9656516 -0.2587439 0.02384471 -0.9914479 -0.1305032 0 -0.9999304 0.01179945 0 -0.9999303 0.01181316 0 0.9999303 0.01181316 0 0.9999304 0.01179945 0 0.9978616 -0.0653631 0 0.9657682 -0.2587913 0.01786124 0.9801641 -0.1949595 0.03562623 0.1266207 -0.9769566 -0.1718233 0.08168762 -0.9850232 -0.151844 0.1005259 -0.9815852 -0.1624353 0.1333022 -0.9710704 -0.1981239 0.1398097 -0.9700084 -0.198839 0.1665888 -0.9502327 -0.2632604 0.1781539 -0.9462273 -0.2700281 0.1689129 -0.9498375 -0.263206 0.1613384 -0.9438356 -0.2883478 0.1584774 -0.9514921 -0.2637192 0.1656739 -0.9499365 -0.264902 0.1536871 -0.9498863 -0.2722063 0.08366435 -0.9849832 -0.1510249 0.03681576 -0.9961391 -0.07969611 0.3156964 -0.8949599 -0.31525 0.0758925 -0.9890338 -0.1266992 0.09030902 -0.9890502 -0.1167228 0.09195882 -0.9882346 -0.1222131 0.1040614 -0.9882776 -0.111708 0.1042147 -0.9881385 -0.1127908 0.1085363 -0.988154 -0.1084976 0.1084604 -0.9881553 -0.1085613 0.0551933 -0.993402 -0.1005307 0.05184412 -0.9934048 -0.1022711 0.05596959 -0.9917321 -0.1154767 0.06049704 -0.9917334 -0.1131592 0.06218189 -0.9905669 -0.1221098 0.06863749 -0.9903394 -0.1204861 0.07372051 -0.990325 -0.1175658 0.3150008 -0.8951902 -0.315292 0.3031511 -0.8949553 -0.3273447 0.3029253 -0.8961464 -0.3242807 0.2685762 -0.8958761 -0.3539391 0.2646027 -0.9028735 -0.3388289 0.2234329 -0.9028573 -0.3673235 0.2178662 -0.9140134 -0.3422192 0.1870901 -0.9140427 -0.3598934 0.1807202 -0.9263924 -0.3303597 0.1653391 -0.9264194 -0.3382459 0.1656664 -0.9323979 -0.3212304 0.1485127 -0.9411379 -0.3036502 0.1626116 -0.9411412 -0.2963289 0.2004036 -0.9788816 -0.04036426 0.1229859 -0.9881994 -0.09130436 0.1163905 -0.9879519 -0.1020017 0.1155827 -0.9878102 -0.1042681 0.1140146 -0.9881263 -0.1029916 0.1128087 -0.987861 -0.1067937 0.3254507 -0.8949913 -0.3050777 0.1301298 -0.9872966 -0.09116888 0.1419277 -0.9872904 -0.07151484 0.1471691 -0.9858415 -0.08036047 0.1560369 -0.985973 -0.0592432 0.1587944 -0.9849593 -0.06811535 0.1631224 -0.985042 -0.05552697 0.1635857 -0.9850555 -0.05390173 0.1806668 -0.9823505 -0.04844522 0.1849198 -0.9823605 -0.02779531 0.3248378 -0.8945524 -0.3070123 0.3394911 -0.8946377 -0.2904639 0.3372747 -0.8942033 -0.2943576 0.3675532 -0.8935614 -0.2577844 0.3720223 -0.8873499 -0.2724142 0.4140081 -0.8874448 -0.2025812 0.4265547 -0.8753476 -0.2276349 0.4533838 -0.8760014 -0.1645134 0.4592142 -0.8676163 -0.1906946 0.4825523 -0.8673176 -0.1220807 0.5126324 -0.8443588 -0.1557763 0.5305011 -0.8447672 -0.0702641 0.5684306 -0.8160074 -0.1049696 1 -5.73323e-7 0 1 -3.49462e-7 0 1 9.42132e-7 0 1 -1.26202e-6 0 1 1.81797e-7 0 1 -6.48463e-7 0 -1 -1.09554e-6 0 -1 3.50388e-6 0 -1 8.39122e-7 0 -1 -6.8365e-7 0 -1 5.85547e-7 0 -1 -3.9254e-7 0 -1 2.42987e-7 0 -1 2.77995e-6 0 -1 -1.74554e-6 0 1 0 -9.53674e-7 1 -5.70972e-7 0 1 2.61608e-7 0 1 1.24091e-7 0 1 0 3.63129e-6 1 -1.34422e-5 0 1 2.86385e-7 0 1 3.23399e-7 0 1 -4.38068e-6 0 1 -4.75204e-7 0 1 6.45255e-7 0 0 -1 0 0 -1 0 0 -1 1.28773e-7 0 -1 0 0 -1 5.61193e-7 0 -1 -6.32284e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0125879 -0.9985727 0.05190569 0 -1 0 0 -1 -1.37682e-7 0 -1 -1.32469e-7 0 0 -1 0 -1 0 0 -1 0 4.24657e-4 -0.9999996 -8.83573e-4 0.01453012 -0.9998867 -0.003959357 8.49824e-4 -0.9999992 9.84929e-4 0.002107441 -0.9999976 6.88276e-4 0.00112766 -0.9999983 -0.001550912 3.28672e-4 -0.9999991 -0.001345396 0.001506865 -0.9999988 4.81703e-4 0.001513242 -0.9999988 -4.5634e-4 0.001001119 -0.9999987 -0.00132209 -8.90258e-5 -0.9999995 -9.99111e-4 -8.80644e-4 -0.9999966 -0.00245881 -0.001185059 -0.9999992 -4.37696e-4 -0.01896917 -0.9993633 0.0302236 -0.01047354 -0.999747 0.0199092 0.0403518 -0.9991656 -0.006309807 0 -0.965925 -0.2588219 -0.001084566 -0.9654282 -0.260667 0 -0.2588133 -0.9659274 -0.0994178 -0.1376993 -0.985472 0 -0.3839479 -0.9233548 0 -0.7071048 -0.7071088 -0.07537257 -0.6288882 -0.7738338 0 -0.7950621 -0.6065281 -0.8555082 -0.5177888 -8.08227e-4 -0.930044 -0.3674151 0.004935324 -0.5210976 -0.1395797 -0.8420065 -0.9934106 -0.114463 -0.005802273 -0.6983448 -0.6385055 -0.3234586 -0.5361516 -0.5361625 -0.651975 -0.5622324 -0.8269782 0.001436889 -0.4156534 -0.9095206 -0.00210309 -0.2241848 -0.8367378 -0.499611 -0.1666053 -0.9860237 -4.54874e-5 -0.008582234 -7.61927e-4 0.9999629 -0.9632683 0.001096189 0.2685385 -0.931418 0.07040309 0.3570773 -0.009021699 0 0.9999593 -0.3860408 0 0.9224818 -0.3858871 0 0.922546 -0.7326156 0 0.6806427 -0.7326992 0 0.6805527 -0.9047622 0 0.4259172 0.05196559 0.8380253 0.5431512 -0.04922223 0.1047808 0.9932765 0.0440368 0.01433056 0.9989271 -0.00876826 0.03466314 0.9993607 0.07575649 0.07369631 0.9943993 0.04291009 0.1809524 0.9825553 0.02244848 0.2112741 0.977169 0.1938098 0.08958458 0.9769404 0.1362956 0.3929949 0.9093837 0.2251039 0.1756005 0.9583803 -0.4860789 0.8606468 0.1517054 -0.6406016 0.745324 0.1847208 -0.6443601 0.7100998 0.2838279 -0.8512659 0.5246621 0.008735656 -0.852211 0.4719033 0.2259287 -0.9464721 0.185903 0.2638761 -0.9862667 0.1449998 -0.07907634 -0.9171165 0.3192354 0.2387179 -0.02812081 0.8863071 0.4622433 0.1534845 0.6132582 0.774827 0.08889865 0.6917343 0.7166594 -0.06393831 0.9776053 0.2004991 -0.110499 0.984319 0.1375004 -0.3139958 0.9303427 0.1893913 -0.1848996 0.8444443 0.5027186 -0.2185964 0.8536748 0.4727104 -0.05302673 0.65429 0.7543823 -0.2465052 0.7562644 0.6060523 -0.5115123 0.6950021 0.5052993 -0.533782 0.6935623 0.4837853 -0.6972122 0.5021105 0.5116447 -0.7195212 0.5011889 0.4807274 -0.8460207 0.1768738 0.502956 -0.8931928 0.1596965 0.4203615 -0.7249251 0.1449081 0.6734131 -0.6220421 0.1720029 0.7638578 -0.5259694 0.4112378 0.7444728 -0.4964013 0.4054197 0.7676071 -0.3594442 0.5607957 0.7458606 -0.3342812 0.5551691 0.7616058 -0.2182407 0.640705 0.7361169 -0.3846673 0.7895703 0.4781317 -0.356019 0.7865302 0.5045997 -0.4889767 0.8536467 0.1794136 -0.3109406 0.9378232 0.1542844 0.1878756 0.4304398 0.8828502 0.1935563 0.4189966 0.8871178 0.0429567 0.377513 0.9250075 -0.01054149 0.4316546 0.9019775 -0.11785 0.3531407 0.9281181 -0.1456919 0.3630456 0.9203107 -0.2369514 0.2625685 0.9353673 -0.271561 0.2727643 0.9229595 -0.3374392 0.1049388 0.9354799 -0.3839283 0.1004215 0.917886 0 -0.1319245 -0.9912598 0.04768067 -0.2585341 -0.9648247 0 -0.3839856 -0.9233392 0 -0.7071027 -0.707111 0 -0.7070977 -0.7071158 0 -0.9659267 -0.258816 0 -0.9659269 -0.2588152 0.7078261 -0.5653922 0.4234548 0.8835263 0 0.4683819 0.6090829 -3.40088e-4 0.7931065 0.6117396 -0.1514695 0.7764225 0.7090334 0.1896268 0.6792006 0.6972194 -0.3602231 0.6197778 0.8010311 0.248392 0.5446566 0.8406444 0 0.5415875 0.1416911 0.9834622 0.1128084 0.2486662 0.9494814 0.1914427 0.4001767 0.8441253 0.356807 0.4036728 0.8415967 0.3588361 0.4334844 0.7626557 0.4800497 0.3683762 0.8097677 0.4567006 0.1908275 0.7706671 0.6079943 0.3281238 0.827949 0.4547914 0.3488553 0.7251861 0.5936373 0.5904797 0.02791082 0.8065699 0.6017563 0.1314382 0.7877902 0.5974436 0.2324609 0.7674784 0.588074 0.3036416 0.749647 0.5310172 0.5025725 0.6822329 0.7673708 0.4475898 0.4591355 0.8206967 0.2921134 0.4910467 0.6091783 0.1763791 0.7731703 0.7357367 0.1759434 0.6540148 0.7357336 0.1759365 0.6540201 0.848884 0.1761049 0.4983804 0.8520789 0.1187949 0.5097543 0.6670325 0.629123 0.3990889 0.5681111 0.7494771 0.3399028 0.4655058 0.8441111 0.2660465 0.4080153 0.879267 0.2457907 0.140127 0.9867848 0.08136492 0.1412274 0.9865976 0.08173102 0.7290983 0.540066 0.4204101 0.6290574 0.539996 0.559188 0.6290568 0.5399981 0.5591866 0.5091307 0.5404155 0.6698784 0.3493871 0.8252883 0.4436531 0.3585934 0.7338229 0.5769877 0.2990422 0.8626362 0.4079616 0.2776805 0.8460944 0.454992 0.2534312 0.8901382 0.3787172 -0.6219282 0.703048 0.3448609 -0.1335524 0.9910418 -1.50641e-4 -0.2478286 0.959281 0.1355032 -0.3538882 0.9352371 0.009730517 -0.5249781 0.8510747 -0.008363783 -0.5226581 0.8521751 0.0250225 -0.09399551 0.9936917 0.0611698 -0.9908174 0.1351507 -0.003910839 -0.9852004 -0.1677564 -0.03518605 -0.6630911 -0.7448828 -0.07389134 -0.871219 -0.482798 -0.08879005 -0.3001555 -0.9470773 -0.1138033 -0.4552913 -0.8839836 -0.1062204 -0.288048 0.9563385 0.04944765 -0.1943228 0.9804181 0.03192234 -0.1935224 0.9639598 -0.182567 -0.3332388 0.9357081 -0.1157689 -0.1947062 0.949782 -0.2449564 -0.1937301 0.8888647 -0.4151968 -0.2125754 0.881645 -0.4213239 -0.1950837 0.8276793 -0.5262028 -0.1935224 0.7475797 -0.6353533 -0.1935225 0.7475808 -0.6353518 -0.194889 0.624788 -0.7560809 -0.2614769 0.5511556 -0.7923746 -0.1944469 0.5221225 -0.8304087 -0.1941182 0.3608691 -0.9121906 -0.2433875 0.3317894 -0.9114156 -0.1950183 0.2401857 -0.9509357 -0.1935222 0.08866882 -0.9770809 -0.1935237 0.088669 -0.9770807 -0.1950173 -0.06516146 -0.9786329 -0.2435014 -0.1622954 -0.9562256 -0.194121 -0.19085 -0.9622336 -0.1935225 -0.4060869 -0.8931084 -0.2964351 -0.354584 -0.88679 -0.1948882 -0.4785523 -0.8561579 -0.1935223 -0.6209938 -0.7595497 -0.193521 -0.6209957 -0.7595486 -0.1950807 -0.7194849 -0.6665471 -0.2127515 -0.7913652 -0.5731301 -0.1095479 -0.9868903 -0.1185197 -0.1942036 -0.9711319 -0.1385209 -0.1946922 -0.9358849 -0.2936227 -0.267166 -0.8990711 -0.3468335 -0.1947049 -0.8902056 -0.4118544 -0.193732 -0.7996532 -0.5683509 -0.5539289 -0.823648 -0.1215187 -0.5523502 -0.7777476 -0.3000304 -0.5523512 -0.7777464 -0.3000311 -0.5523514 -0.6751475 -0.4889622 -0.5523509 -0.6751486 -0.4889612 -0.5523525 -0.5276411 -0.6453694 -0.5523509 -0.5276421 -0.6453699 -0.552349 -0.3450418 -0.7588524 -0.5523523 -0.345041 -0.7588502 -0.5523499 -0.1394894 -0.8218592 -0.5523506 -0.1394889 -0.8218587 -0.5523508 0.07533931 -0.8302003 -0.5523501 0.07534098 -0.8302007 -0.5523506 0.2851593 -0.7833217 -0.5523512 0.2851582 -0.7833218 -0.552351 0.4760093 -0.6843417 -0.5523499 0.4760109 -0.6843415 -0.5523512 0.6351992 -0.5398427 -0.5523518 0.6351983 -0.5398433 -0.5523506 0.7521402 -0.3594358 -0.5523512 0.7521395 -0.3594362 -0.5523506 0.8190519 -0.1551223 -0.552351 0.8190516 -0.1551223 -0.554618 0.8320396 0.0104441 -0.62816 0.7754543 -0.0639199 -0.8285566 -0.5576899 -0.0497592 -0.8293091 -0.5213425 -0.2011182 -0.8293088 -0.521343 -0.2011185 -0.8293095 -0.4525667 -0.3277639 -0.8293079 -0.4525699 -0.3277636 -0.8293084 -0.3536922 -0.4326078 -0.8293079 -0.3536928 -0.4326081 -0.8293079 -0.2312904 -0.5086779 -0.8293089 -0.231289 -0.508677 -0.8293079 -0.09350383 -0.5509133 -0.8293085 -0.09350258 -0.5509126 -0.829308 0.05050146 -0.5565051 -0.8293085 0.05050331 -0.5565041 -0.829308 0.1911492 -0.5250813 -0.8293084 0.1911479 -0.525081 -0.829308 0.319083 -0.4587312 -0.8293084 0.3190811 -0.4587318 -0.8293089 0.4257891 -0.3618705 -0.8293077 0.4257921 -0.3618702 -0.8293092 0.5041768 -0.2409399 -0.8293086 0.5041779 -0.2409396 -0.8293095 0.5490297 -0.1039824 -0.8293076 0.5490325 -0.1039828 -0.9805186 -0.1950195 -0.02347242 -0.9804697 -0.1834912 -0.07078444 -0.9804698 -0.1834899 -0.07078474 -0.9804697 -0.1592852 -0.1153581 -0.98047 -0.1592836 -0.1153579 -0.9804699 -0.1244835 -0.1522586 -0.9804699 -0.1244834 -0.1522585 -0.98047 -0.08140361 -0.1790316 -0.98047 -0.08140289 -0.1790315 -0.98047 -0.03290855 -0.1938962 -0.98047 -0.03290843 -0.1938964 -0.98047 0.0177741 -0.1958644 -0.9804699 0.01777493 -0.1958643 -0.9804699 0.06727576 -0.1848047 -0.98047 0.06727617 -0.1848047 -0.9804699 0.1123023 -0.1614528 -0.98047 0.1123014 -0.161453 -0.98047 0.1498585 -0.127362 -0.9804699 0.1498593 -0.127362 -0.9804691 0.1774529 -0.08479964 -0.9804702 0.1774469 -0.08479976 -0.980469 0.193239 -0.03659713 -0.9804704 0.1932321 -0.03659713 -0.9781512 0.1900082 -0.08436465 -0.8194897 0.5564258 0.1372118 -0.8845775 0.4405636 -0.1530569 -0.7816936 0.6236091 0.008176147 3.85785e-4 -1 -2.53519e-5 -0.001598238 -0.9999973 0.00168991 -7.00968e-4 -0.999999 0.001297473 4.68742e-4 -0.9999999 -5.55047e-5 2.45034e-5 -1 -9.828e-7 -4.93584e-6 -1 0 -4.88798e-4 -1 -5.86878e-5 -3.93055e-4 -1 -3.51322e-5 5.24281e-4 -0.9999998 5.52064e-4 -6.59006e-4 -0.9999996 6.35074e-4 8.5568e-4 -0.9999985 0.001500844 0.2212619 -0.9752137 0.001318275 0.2224178 -0.9747733 0.01864117 0.212029 -0.9771802 0.01275122 0.2197656 -0.97486 0.03675597 0.2080155 -0.9772076 0.04236686 0.2141064 -0.9753857 0.05273729 0.2124903 -0.9756941 0.05356329 0.2078208 -0.9765175 0.05678164 0.2137943 -0.9752103 0.05707174 0.9778568 -0.04034352 0.2053499 0.9717622 -0.04973834 0.2306611 0.9656359 -0.1013113 0.2393393 0.9646923 -0.02603387 0.2620896 0.9636231 -0.04729741 0.2630467 0.988135 -0.004923462 0.1535089 0.9956016 0 0.09368854 0.9943048 -0.01150149 0.1059516 0.9727023 -0.1763036 0.1508881 0.9790863 -0.1327722 0.1541478 0.9806678 -0.02144116 0.1945017 0.28092 -0.957975 0.05803519 0.2047766 -0.9743571 0.09324628 0.06465905 -0.9978128 0.01374524 0.0620771 -0.996929 0.04774129 0.03937113 -0.9992032 0.006562173 0.9771629 -0.05305862 0.2057605 0.9769475 -0.03562849 0.2104859 0.9726399 -0.04546022 0.227827 0.970417 -0.04730683 0.236755 0.9772728 -0.07730174 0.197389 0.9744599 -0.1454604 0.1710827 0.9760478 -0.1560092 0.1516312 0.9549043 -0.2853396 0.08209294 0.9554821 -0.2500937 0.1565482 0.9406784 -0.319005 0.1155858 0.9949814 -0.00741589 0.09978538 0.9950337 -0.003989934 0.09945935 0.9946579 -0.02431774 0.100321 0.9845122 -0.1571605 0.07769495 0.995719 -0.08491826 -0.03650856 0.9913565 -0.1280271 0.02866077 0.832712 -0.4462349 0.3278189 0.9645579 -0.2633533 0.01652866 0.9430961 -0.318301 0.09619933 0.9452289 -0.3187458 0.07030886 0.936953 -0.3203371 0.1396539 0.5669476 -0.8219425 0.05459892 0.6940728 -0.7061413 0.140098 0.723159 -0.6813746 0.1130034 0.8438513 -0.5295158 0.08676367 0.386616 -0.9214646 0.03783112 0.3060044 -0.9511252 -0.04150146 0.3575686 -0.9216164 0.1508908 0.1961396 -0.9793478 -0.04906356 0.1976494 -0.9768857 -0.08141946 0.1854749 -0.9790806 0.08366781 0.02583974 -0.9996045 -0.01109552 0.07597148 -0.9967852 0.02544939 0.04223966 -0.9991003 0.003804445 0.8705338 -0.480354 0.1069153 0.7637262 -0.6398914 0.08521479 0.7104265 -0.7037102 -0.009286582 0.631537 -0.7745779 0.03449833 0.3245505 -0.9388561 0.1149625 0.9959675 0 0.08971619 0.9941282 -0.01478493 0.107195 0.9950083 -5.97174e-4 0.09979146 0.03815817 0.01531147 0.9991545 0.03880244 0.0216217 0.999013 0.03988802 0.03356099 0.9986405 0.04132175 0.05969649 0.997361 0.04260808 0.1120812 0.9927852 0.04277789 0.1666768 0.9850832 0.0316056 -0.03841763 0.9987619 -0.03208291 0.06196105 0.9975628 -0.03709858 0 0.9993117 -0.6285842 0.02666682 0.7772844 -0.6154483 0.1733538 0.768877 -0.6138935 0.1295474 0.7786863 -0.6045407 0.2659627 0.7508625 -0.3990485 0.7680347 0.5008824 -0.3207008 0.8173056 0.4787092 -0.3394736 0.776139 0.5313813 -0.3519579 0.7280516 0.5882743 -0.2966049 0.8608188 0.4135417 -0.3019128 0.8647144 0.4013949 -0.4231792 0.759132 0.4946088 -0.2801464 0.8528505 0.4406406 -0.2539819 0.853757 0.4545243 -0.2673529 0.8491984 0.4553951 -0.2683435 0.9380487 0.219218 -0.2124882 0.9577502 0.1938131 -0.009214937 0.9958699 -0.09032338 -0.6944714 0.4196663 0.5844568 -0.5875117 0.6106295 0.5310006 -0.4414087 0.8039854 0.3984546 -0.5316076 0.7217036 0.4433254 -0.4257586 0.8217212 0.3788194 -0.5356154 0.4945662 0.6844856 -0.5291439 0.5327931 0.6604077 -0.615604 0.5339363 0.5796067 -0.7297807 0.1736763 0.6612539 -0.7282795 0.1416544 0.6704797 -0.04922735 0.9921289 0.1151397 -0.6635922 0.1438711 0.7341298 -0.6854027 0.1969165 0.7010329 -0.1097208 -0.9829202 0.1477477 -0.5651621 0.4959222 0.6592822 -0.5537047 0.1295562 0.8225731 -0.470462 0.3499713 0.8100529 -0.5041275 -0.1333867 0.8532664 -0.4664364 0.2585793 0.8459161 -0.4834054 0.09138971 0.8706132 -0.06191813 0.9979985 -0.01285547 -0.4434737 0.4595997 0.7694799 -0.5169283 0.1344117 0.8454105 -0.4086343 0.6180166 0.6716201 -0.4968131 0.361007 0.789209 -0.3471313 0.7653677 0.5419522 -0.4635398 0.543364 0.6999189 -0.2683026 0.8811404 0.3893654 -0.4074411 0.7017241 0.5844443 -0.1832216 0.9562922 0.2278929 -0.3410625 0.8269311 0.4470584 -0.2521109 0.9174604 0.3077444 -0.628314 0.3443571 0.6975957 -0.5733512 0.5044708 0.6455832 -0.5633615 0.5291254 0.6345473 -0.5022962 0.6481053 0.5724143 -0.4783874 0.6870489 0.5469089 -0.3817663 0.8075926 0.4494984 -0.3918859 0.7961484 0.4610566 -0.5679009 -0.008375406 0.8230543 -0.5496934 -0.240613 0.7999642 -0.5558546 0.3535042 0.75237 -0.5861111 0.152309 0.7957862 -0.5191301 0.5364735 0.6653572 -0.5733666 0.3504123 0.7405823 -0.4607303 0.6953919 0.5515049 -0.5369899 0.5319576 0.6547236 -0.3856072 0.8218068 0.4194528 -0.48062 0.686827 0.5452278 -0.2996173 0.9125313 0.2784172 -0.409452 0.8095554 0.420677 -0.4693409 -0.2409688 0.8495019 -0.6690621 -0.1944472 0.7173188 -0.6992375 -0.07192099 0.7112625 -0.5825821 -0.5533816 0.5952873 -0.633946 -0.3946889 0.6650814 -0.6687229 -0.2477438 0.7010226 -0.2893421 -0.9097127 0.2978322 -0.3436904 -0.8715475 0.3496884 -0.3947847 -0.8296837 0.3946773 -0.4335363 -0.7832295 0.4456434 -0.5609177 -0.5903484 0.5803965 -0.4941897 -0.8680411 0.04776287 -0.170275 -0.9696595 0.175405 -0.06913352 -0.996752 0.04130274 -0.1346431 -0.9806339 0.142227 -0.1219935 -0.9766733 0.1767116 -0.1158092 -0.9807652 0.1571241 -0.2550358 -0.8945026 0.367181 -0.3038927 -0.8303991 0.4669975 -0.319967 -0.8142101 0.4844409 -0.4396713 -0.5531598 0.707604 -0.4438425 -0.5443258 0.711838 -0.5328996 -0.1942706 0.8235758 -0.5713412 -0.03079366 0.8201348 0.1041645 0.9547564 0.27855 0.05552017 0.992168 0.1118945 0.1248673 0.9579656 0.2582831 0.06742262 0.9829611 0.1710022 0.1728685 0.8819683 0.4384616 0.2121372 0.8201782 0.5313243 0.2360612 0.7653652 0.5987414 0.2930907 0.6012173 0.7433947 0.2890393 0.617334 0.7316797 0.3256345 0.4583753 0.8269549 0.3325442 0.4238073 0.8424974 0.3652682 0.09106069 0.9264379 0.3631115 0.1685331 0.9163769 0.3544135 0.2575075 0.8989333 0.3437287 0.3489307 0.8718361 0.1409105 -0.6562915 0.7412326 -0.186805 -0.2387492 0.9529443 -0.1867726 -0.2387509 0.9529502 -0.07637202 -0.9485578 0.307255 -0.1073065 -0.8449455 0.5239776 -0.1595298 -0.6832932 0.712503 -0.1552707 -0.6779505 0.7185223 -0.1687223 -0.4801681 0.8607971 0.1994822 -0.2338721 0.9515833 0.199468 -0.2339017 0.951579 0.1469645 -0.6977715 0.7010823 0.325447 -0.5453973 0.7724158 0.4274497 0.7697871 0.4740408 0.2533993 0.8901495 0.3787118 0.1908335 0.7706686 0.6079906 0.3281229 0.8279529 0.4547851 0.3489231 0.7251689 0.5936185 0.6056532 0.027493 0.7952536 0.6139699 0.129496 0.7786346 0.6083032 0.2294998 0.7598007 0.5983833 0.3000574 0.7429018 0.5413348 0.4978321 0.6775839 0.6193444 0.1734199 0.7657272 0.7307546 0.1736561 0.6601828 0.7291272 0.1339768 0.6711362 0.5808774 0.6220791 0.5249752 0.277682 0.8460934 0.454993 0.3029145 0.8654145 0.3991249 0.3860762 0.7573929 0.5265941 0.3453732 0.8343784 0.4295699 0.522276 0.5324041 0.6661636 0.6365979 0.5330228 0.5573419 0.6664834 0.4128698 0.6207564 0.5071406 0.7301553 0.4579102 0.4436207 0.8089252 0.385799 0.3756548 0.8630263 0.337741 0.2503517 0.9484459 0.1943568 0.1473471 0.9824134 0.114686 0.2674262 0.9161641 0.2985408 0.5559331 0.1593636 0.8158074 0.5537053 0.02912831 0.832203 0.5237523 0.03331238 0.8512191 0.6244822 0.0223152 0.7807202 0.6379685 0.4074022 0.6534675 0.6772247 0.2787061 0.6809476 0.7181876 0.107768 0.6874538 0.04925167 0.9921291 0.1151274 0.0593121 0.9981381 0.01422762 0.1959435 0.955357 0.2211316 0.3273466 0.8280659 0.4551385 0.2813766 0.8802624 0.3820541 0.3959023 0.7027001 0.5911632 0.3603181 0.7645096 0.5345053 0.4485805 0.5447526 0.7085339 0.4216736 0.6174078 0.6640776 0.4855633 0.3621861 0.7956441 0.4624748 0.4590364 0.758553 0.5010205 0.1662533 0.8493165 0.474643 0.349893 0.8076441 0.5038282 -0.1015422 0.8578149 0.4674135 0.2585107 0.8453976 0.4840324 0.09141325 0.8702622 0.3435897 0.8302111 0.4389712 0.4648715 0.7048317 0.5358234 0.4592941 0.7127116 0.5301803 0.5450658 0.5819633 0.6035082 0.6223049 0.3972648 0.6744756 0.650012 0.2998357 0.6982714 0.6381871 0.3353331 0.6930144 0.4806862 0.6867511 0.5452648 0.6219944 0.4582739 0.6349079 0.5945338 0.4547249 0.6631402 0.4533361 0.7178538 0.5283677 0.4588039 0.7191166 0.5218912 0.4006273 0.8028553 0.4414991 0.5610387 -0.4002342 0.7246021 0.6380304 0.1468735 0.7558741 0.5959103 0.3962898 0.6984594 0.603562 0.3474364 0.7176356 0.5565601 0.529852 0.6399201 0.3072902 0.9114363 0.2735995 0.4052281 0.8063396 0.4308211 0.3938543 0.8206245 0.4140701 0.4728028 0.6874935 0.5511899 0.4693651 0.6940802 0.5458471 0.5287502 0.5325894 0.6608872 0.5278972 0.5351203 0.6595233 0.5647925 0.3512933 0.746728 0.5646118 0.3521981 0.7464383 0.5774624 0.1531348 0.801927 0.5606999 -0.1749607 0.8093234 0.5900434 0.02538585 0.8069725 0.1110156 -0.9807059 0.1609085 0.03920984 -0.9983743 0.04136866 0.141456 -0.9804515 0.1367667 0.1305724 -0.9838665 0.1223021 0.3448004 -0.8708918 0.350229 0.2904031 -0.9091405 0.2985459 0.2125017 -0.9524065 0.2185515 0.5611692 -0.1947467 0.8044643 0.668975 -0.1944668 0.7173947 0.7152495 0.02109885 0.6985507 0.7004837 -0.06870585 0.7103534 0.6698415 -0.2438806 0.7013093 0.5745021 -0.5539312 0.6025842 0.6507015 -0.4118768 0.6379225 0.561177 -0.5905374 0.5799536 0.1239386 -0.9777551 0.1692166 0.3155884 -0.8309103 0.458249 0.3950423 -0.8297047 0.3943754 0.4337648 -0.7832872 0.4453193 0.4693437 -0.2409836 0.849496 0.544603 -0.09289109 0.833534 0.4443247 -0.5442931 0.7115621 0.4401586 -0.5531385 0.7073177 0.3199337 -0.814621 0.4837716 0.2514503 -0.8773717 0.4086464 -0.6235381 0.026847 0.7813319 -0.6118406 0.1609054 0.7744422 -0.610623 0.1300944 0.7811627 -0.6002342 0.2673055 0.7538346 -0.202545 0.7802188 0.5918058 -0.2872712 0.8223017 0.4912181 -0.256232 0.8863865 0.3855701 -0.2367591 0.9058334 0.3512992 -0.4213059 0.7277051 0.5412455 -0.3609084 0.8261888 0.4326168 -0.2641356 0.74101 0.6173627 -0.2747502 0.7737013 0.5708753 -0.2470179 0.9396267 0.2368202 -0.2790681 0.9305247 0.23716 -0.4444129 0.7914138 0.4197158 -0.4603065 0.778011 0.4275708 -0.5869953 0.5741382 0.5707907 -0.7004643 0.3748463 0.607322 -0.5365031 0.4941666 0.6840788 -0.5359261 0.4976582 0.6819967 -0.6058451 0.4990199 0.6196216 -0.7118384 0.1612659 0.6835784 -0.7074482 0.1232254 0.6959401 0.4528411 0.7296133 0.5124445 0.637966 0.4074167 0.6534609 0.4840536 0.0912674 0.8702657 0.1455817 0.9515647 0.2707963 0.4610922 0.2993749 0.8353254 0.5135794 -0.04361432 0.8569329 0.5237488 0.03341257 0.8512173 0.6244813 0.02235198 0.7807199 0.7181677 0.1077638 0.6874751 0.6772413 0.2786303 0.6809621 0.2941604 0.8675686 0.4009919 0.1470625 0.9738238 0.1733199 0.3410131 0.8269251 0.4471073 0.06767344 0.9975718 0.01646161 0.3931712 0.7028487 0.5928071 0.4576216 0.5440005 0.7033107 0.4261097 0.6203562 0.6584746 0.4811856 0.3626554 0.7980862 0.5034736 0.1659502 0.8479239 0.5559287 0.1594127 0.8158008 0.5537962 0.02899247 0.8321473 0.3424466 0.8300003 0.4402612 0.451751 0.719992 0.5268136 0.4618072 0.7092236 0.5326688 0.4592188 0.7127961 0.5301319 0.6380228 0.1469106 0.7558732 0.5958962 0.3963034 0.6984636 0.6222885 0.3972935 0.6744739 0.6220358 0.458227 0.6349013 0.6035964 0.3472857 0.7176796 0.5565078 0.5299956 0.6398468 0.4566919 0.7248796 0.5157346 0.4616914 0.6883616 0.5594635 0.4011403 0.8192776 0.4097203 0.2846198 0.9144017 0.2878565 0.299661 0.912516 0.2784207 0.4728018 0.6874936 0.5511906 0.4693928 0.6940361 0.5458793 0.5287448 0.5326623 0.6608328 0.5278872 0.5352025 0.6594645 0.564828 0.3511322 0.7467768 0.5646315 0.3522058 0.7464197 0.5774642 0.1531264 0.8019274 0.5607051 -0.1749172 0.8093293 0.5900417 0.02519577 0.8069796 0.2562026 0.8296701 0.4959919 0.4214566 0.7720545 0.4757165 0.1366808 0.9743089 0.1789987 0.2713519 0.8881115 0.3709802 0.2747194 0.868496 0.4126064 0.1174373 0.748073 0.6531427 0.4053003 0.7509753 0.5213137 0.4876724 0.5471917 0.6802623 0.4706367 0.6483839 0.5984141 0.6222803 0.02686357 0.7823335 0.5939493 0.1326733 0.7934873 0.5936673 0.2334898 0.7700921 0.5874146 0.303847 0.7500807 0.5729097 0.379765 0.7263285 0.6014334 0.2213001 0.7676615 0.7148227 0.221534 0.6632883 0.7064417 0.1189596 0.6977026 0.2724454 0.9237561 0.2691624 0.2939244 0.9201978 0.2585433 0.4028444 0.8361913 0.3721567 0.326779 0.8938954 0.306866 0.4827685 0.7481315 0.4552295 0.5675203 0.6481877 0.507714 0.5879746 0.5820966 0.561649 0.6658306 0.3503702 0.6587188 -0.6208605 0.02691239 0.7834591 -0.5911369 0.2701682 0.759978 -0.5746412 0.3677324 0.7311365 -0.525082 0.5265719 0.6685888 -0.4583525 0.6371461 0.6196433 -0.4257946 0.7116283 0.5588238 -0.2025229 0.7802652 0.5917522 -0.3853586 0.7750499 0.5007957 -0.3240949 0.8498224 0.4156497 -0.3202709 0.834913 0.4476012 -0.2561378 0.8840311 0.3910021 -0.2631145 0.8679527 0.4212232 -0.2708867 0.881379 0.3870294 -0.2733796 0.89357 0.3560848 -0.4245164 0.7537639 0.5016235 -0.3487894 0.8773137 0.3296465 -0.3378773 0.884966 0.320428 -0.3786292 0.8965784 0.2297548 -0.2542431 0.9380807 0.2352977 -0.6930697 0.2177423 0.6871991 -0.5933808 0.217025 0.7751126 -0.6127879 0.1297265 0.7795269 -0.7349596 0.1305007 0.6654352 -0.6622036 0.3572283 0.6586915 -0.5602048 0.638561 0.5276463 -0.5951648 0.6012427 0.533185 -0.4837585 0.7449169 0.4594309 0.03032284 -0.9825617 -0.1834481 0 -0.9928764 -0.1191495 1.44332e-4 -0.9928658 -0.1192373 0 -0.8150951 -0.5793272 0.03011167 -0.8501799 -0.5256306 0 -0.9075756 -0.4198888 0 -0.9541429 -0.2993515 0 -0.7335783 -0.679605 0.004795253 -0.6329521 -0.7741761 0.02496784 -0.6033272 -0.7971029 0 -0.1945508 -0.9808925 0.03285843 -0.2750002 -0.9608826 0 -0.3712723 -0.9285241 0 -0.4879079 -0.8728952 0 -0.0664376 -0.9977906 0.01691937 0.09036409 -0.9957651 0.0168662 0.09027701 -0.9957739 0 0.5322818 -0.8465673 0.03285169 0.443324 -0.8957593 0 0.3678677 -0.9298782 0 0.2448878 -0.9695515 0 0.637004 -0.7708606 0.03174406 0.7616008 -0.6472686 0.006026148 0.7370597 -0.6758008 0 0.8438897 -0.5365168 0 0.9060302 -0.423213 0.03009241 0.9308492 -0.3641625 0 0.9981107 0.06144243 0.03034144 0.9995326 -0.003750741 0 0.9924332 -0.1227862 0 0.9683139 -0.2497364 0.004826605 0 0.9999884 0.004824101 0 0.9999884 -0.2501845 0 0.9681982 -0.432537 0 0.9016162 -0.3783625 0.0116052 0.9255847 -0.3063241 0.04714357 0.9507592 -0.2520288 0.09754884 0.9627906 -0.07110804 0.006021916 0.9974505 -0.2475762 0.07129961 0.9662414 -0.2252648 0.1334808 0.9651107 -0.2298949 0.1258745 0.965041 -0.2409184 -9.86486e-4 0.9705449 -0.2112538 -0.006311297 0.9774109 -0.2122875 -0.009664297 0.9771595 -0.2145327 0.001555621 0.9767156 -0.2078183 -0.001501739 0.9781664 -0.3188695 -0.1208043 0.9400684 -0.3230099 5.92081e-6 0.9463956 -0.2629232 -0.01213353 0.9647405 -0.3422617 -0.09847712 0.9344298 -0.3337433 -0.0548076 0.9410694 -0.4324799 -9.31411e-4 0.9016432 -0.4542663 0 0.8908661 -0.3302921 0.1168668 0.9366158 -0.4241012 0.004623472 0.905603 -0.4206209 0.01149654 0.9071637 -0.4196304 0.01477634 0.9075748 -0.419126 0.01078069 0.9078641 -0.1476271 0.0943368 0.9845339 -0.1268224 0.05202794 0.9905601 -0.2385194 0.2218103 0.9454674 -0.2192524 0.1457512 0.9647202 -0.3741315 -0.01247131 0.9272919 -0.4131545 0.004339814 0.9106506 -0.2171351 0.06832867 0.9737473 -0.2143521 0.02894973 0.9763273 -0.2395997 0.1915373 0.9517906 -0.2441201 2.96521e-4 0.969745 -0.2441133 0 0.9697467 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.9899262 -3.044e-4 0.141584 0.9932971 4.50611e-4 0.1155882 0.9932766 0 0.1157656 0.9692817 -0.2021602 0.1400874 0.9689925 -0.1896511 0.1583855 0.9601813 -0.2158923 0.1773204 0.9661735 -0.1948508 0.1689432 0.9690264 -0.1790611 0.1700736 0.9698648 -0.1532562 0.1894067 0.965614 -0.2466932 0.0820496 0.9982752 0.04909294 -0.03219747 0.9453012 -0.145923 -0.2917397 0.9911609 -0.0800938 -0.1057599 0.9623425 -0.2626745 0.06999468 0.9659059 -0.193355 0.1721615 0.9408269 -0.2377786 -0.2414669 0.9567801 -0.1434192 -0.2529875 0.9662469 -0.0631535 -0.2497572 0.9287407 -0.2716699 -0.2522624 0.9856497 -0.1106879 0.1274476 0.9358744 -0.3522005 0.009702861 0.9396994 -0.3124181 0.1391411 0.9305842 -0.3631733 0.04602581 0.955657 -1.80708e-4 -0.294482 0.9555371 -0.001102209 -0.2948691 0.9555879 0 -0.2947065 0.9994802 0 -0.03223931 0.9994803 0 -0.03223723 0.891674 -0.4039441 0.20432 0.886856 -0.4095815 0.2138444 0.9857476 -0.1147312 0.1230387 0.952886 -0.2293254 0.1985404 0.958601 -0.2118733 0.1902471 0.29172 -0.09128278 0.9521381 0.3503485 0 0.9366194 0.2768426 -0.1246336 0.9527983 0.2839682 -0.1110341 0.9523831 0.2886991 -0.09924089 0.9522627 0.293847 -0.08431529 0.9521265 0.2953119 -0.0795086 0.9520869 0.300341 -0.06115555 0.9518694 0.3032658 -0.04300785 0.9519351 0.306433 -0.02072447 0.9516666 0.3068467 -1.79951e-4 0.951759 0.2861598 0.0304858 0.9576969 0.2900249 0.02870577 0.9565885 0.3622447 0 0.932083 -0.002397358 0 0.9999972 -0.003695011 0.02249526 0.9997402 -0.01494222 0.05124157 0.9985745 -0.01015013 0.0460447 0.9988879 0.01039129 0.03167933 0.9994441 0.07242524 0.00197947 0.997372 0.2070156 -0.002067446 0.9783356 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.002397358 0 0.9999972 0.09322065 0.008155941 0.9956121 0.004650294 0.03941673 0.9992122 0.01127904 0.04685217 0.9988381 -0.005263686 0.03543472 0.9993581 -0.3622534 0 0.9320797 -0.2901266 0.02871519 0.9565574 -0.2672884 0.0390293 0.9628259 -0.2861779 0.02889859 0.9577407 -0.1704955 -0.00908482 0.9853166 -0.04625606 0.01189351 0.9988589 -0.2211866 0.001011908 0.975231 -0.2427403 -9.10519e-4 0.9700909 -0.2648268 -0.01223468 0.9642185 -0.2099795 -0.001426696 0.9777048 -0.2133578 -0.006184875 0.9769546 -0.2144728 -0.009670615 0.9766821 -0.2148171 -0.007681787 0.9766241 -0.3484722 -0.103805 0.9315534 -0.3286884 0 0.9444385 -0.3035033 -0.1019735 0.947358 -0.3068459 -1.64096e-4 0.9517592 -0.2629942 0 0.9647975 -0.4292989 0 0.9031625 -0.3397096 0.02573996 0.9401781 -0.09215694 0.006020128 0.9957264 -0.2603952 0.06879448 0.9630481 -0.2392281 0.126473 0.9626913 -0.2575164 0.09709924 0.9613829 -0.2411907 -9.1756e-4 0.9704774 -0.2194907 0.00101149 0.9756141 -0.2117677 -0.00618118 0.9773005 -0.2127912 -0.009635746 0.9770502 -0.2131345 -0.007696032 0.9769926 -0.2083014 -0.00138992 0.9780638 -0.3214699 -0.1235843 0.9388206 -0.3257569 -1.40028e-4 0.9454536 -0.2631655 -0.01222407 0.9646732 -0.3426812 -0.09908342 0.9342121 -0.3353583 -0.0608502 0.9401234 -0.4331784 -0.002210795 0.9013054 -0.4566029 0 0.8896707 0.4581966 0 0.8888508 0.3274778 -0.00838387 0.9448217 0.210328 7.3955e-5 0.9776309 0.2166407 -0.007098793 0.9762256 0.2036428 -0.002435445 0.9790422 0.2629907 -0.05303227 0.9633398 0.2239109 0.01142632 0.9745426 0.2676075 -0.01373022 0.9634302 0.5839165 -0.3937096 0.7099538 0.2977431 -0.06669825 0.9523133 0.3808667 -0.2015327 0.9023997 0.2411959 0.1199776 0.9630317 0.2591255 0 0.9658436 0.2579089 0.03701329 0.9654601 0.246059 0.09955137 0.964129 0.2346785 0.1305996 0.9632601 0.2605397 0.09672582 0.9606057 0.3178082 0.03939312 0.9473364 0.4180082 0 0.9084433 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.4950678 -0.1984619 -0.8458846 -0.5391275 -0.1532548 -0.8281635 -0.5770028 -0.03486001 -0.8159979 -0.4344399 -0.5883243 -0.6820092 -0.5159223 -0.4488807 -0.7296097 -0.5449656 -0.3302366 -0.7706857 -0.4113815 -0.6024662 -0.6839589 -0.3840062 -0.7830594 -0.4892416 -0.3830476 -0.7482224 -0.5416991 -0.6014198 0.02605253 -0.7985083 -0.6920153 0.1159595 -0.7125085 -0.753974 0.2029403 -0.6247707 -0.8339251 0.3251975 -0.4458875 -0.8401352 0.3377189 -0.4244043 -0.8531662 0.3793672 -0.3580337 -0.8657251 0.4635787 -0.1887192 -0.8597687 0.5055015 -0.07256823 -0.8490406 0.5281863 -0.01222026 -0.7494202 0.5959815 0.2884017 -0.7865821 0.5793601 0.2136135 -0.9076745 0.1289016 0.3993889 -0.9076749 0.1289032 0.3993873 -0.9937462 0.109537 0.02168118 -0.9937467 0.1095319 0.02168983 -0.929487 0.073435 -0.3614712 -0.9294921 0.07343149 -0.3614586 -0.7221345 0.02584904 -0.6912696 -0.7221425 0.02584981 -0.6912612 -0.852679 0.377788 0.360853 -0.8526468 0.377826 0.3608891 -0.9470034 0.321034 -0.0110408 -0.9470002 0.321043 -0.01105296 -0.8981549 0.2152303 -0.3833977 -0.8981525 0.2152331 -0.3834018 -0.7110921 0.07576555 -0.6990048 -0.7111088 0.07575231 -0.6989892 -0.649312 0.6027793 0.4637359 -0.7601983 0.3850705 0.5232775 -0.7572677 0.3774041 0.5330215 -0.8133727 0.1313856 0.5667123 -0.8123882 0.1282342 0.5688422 -0.8190929 -4.29114e-6 0.5736611 -0.8191524 0 0.5735761 -0.8191411 -5.2938e-6 0.5735923 -0.8191505 0 0.5735786 -0.8178227 0 0.5754704 -0.7900024 0.2643734 0.5531754 -0.7900024 0.2643706 0.5531767 -0.6195289 0.6541994 0.4338284 -0.7968763 0.4075978 -0.4459286 -0.1169844 0.9897491 0.08192306 -0.6064063 0.4157679 -0.6777968 -0.3222106 0.9193881 0.2256239 -0.4632166 0.8247738 0.3243126 -0.8192076 0 0.5734972 -0.8191449 0 0.5735866 -0.8189222 0 0.5739045 0 1 0 0 1 0 -5.21097e-6 0 1 -0.258819 -0.9659259 0 -0.7071033 -0.7071103 0 -0.7071086 -0.7071051 0 -0.9659253 -0.2588207 0 -0.9659272 -0.2588139 0 1.42366e-5 0 -1 0 1 0 0 1 0 0 1 0 -0.258535 0 0.966002 -0.7064781 0 0.707735 -0.7064676 0 0.7077455 0.6753323 0 -0.7375136 0.2446533 0 -0.9696107 0.2446337 0 -0.9696156 0.4932516 0 0.8698868 0 1 0 0 1 0 0 1 0 0.7064685 0 0.7077445 0.7064791 0 0.7077339 0.2585349 0 0.966002 -0.2446337 0 -0.9696156 -0.2446533 0 -0.9696107 -0.6753323 0 -0.7375136 -0.4932429 0 0.8698917 -0.9746794 0 0.2236071 -0.9746811 0 0.2235997 -0.99373 0 0.111807 -0.9937309 0 0.1117994 0.9659259 0 0.2588188 0.965928 0 0.2588114 0.7070941 0 0.7071195 0.7071089 0 0.7071048 0.2588148 0 0.965927 0.2588423 0 0.9659197 -0.2588421 0 0.9659197 -0.2588145 0 0.9659271 -0.7071093 0 0.7071043 -0.7070946 0 0.707119 -0.9659278 0 0.2588116 -0.9659259 0 0.258819 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.9746804 0 0.223603 0.9746787 0 0.2236104 -0.6947141 -0.6947814 -0.1861482 -0.6947744 -0.6947166 -0.186165 -0.5086089 -0.6947239 -0.5086019 -0.50859 -0.6947413 -0.5085968 -0.1861614 -0.6947398 -0.6947522 -0.1861523 -0.6947514 -0.694743 0.1861504 -0.6947503 -0.6947447 0.1861636 -0.6947383 -0.6947531 0.5085895 -0.6947456 -0.5085915 0.508605 -0.6947293 -0.5085984 0.6947488 -0.6947442 -0.1861577 0.6947721 -0.6947191 -0.1861643 0.6947314 -0.6947629 0.1861529 0.6947814 -0.6947091 0.1861669 0.5085929 -0.6947441 0.5085904 0.5085963 -0.6947385 0.5085945 0.1861637 -0.6947302 0.6947611 0.1861506 -0.6947547 0.6947402 -0.1861559 -0.694745 0.6947484 -0.1861582 -0.6947457 0.6947471 -0.5085927 -0.6947439 0.5085905 -0.5086055 -0.6947222 0.5086074 -0.6947141 -0.6947814 0.1861484 -0.6947721 -0.6947191 0.1861643 0.9659259 0 0.2588193 0.7071056 0 0.707108 0.7071087 0 0.7071049 0.2588231 0 0.9659247 0.2588173 0 0.9659263 -0.2588173 0 0.9659263 -0.2588231 0 0.9659247 -0.7071087 0 0.7071049 -0.7071056 0 0.707108 -0.9659259 0 0.2588193 -0.9659259 0 -0.2588193 -0.7071056 0 -0.707108 -0.7071087 0 -0.7071049 -0.2588231 0 -0.9659247 -0.2588173 0 -0.9659263 0.2588173 0 -0.9659263 0.2588231 0 -0.9659247 0.7071087 0 -0.7071049 0.7071056 0 -0.707108 0.9659259 0 -0.2588193 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.965926 0 -0.2588185 0.9659256 0 -0.25882 0.707104 0 -0.7071096 0.2588239 0 -0.9659245 0.2588183 0 -0.9659261 -0.2588171 0 -0.9659264 -0.2588226 0 -0.9659249 -0.9659257 0 -0.25882 -0.965926 0 -0.2588185 -0.9659257 0 0.25882 -0.965926 0 0.2588185 -0.2588171 0 0.9659264 -0.2588226 0 0.9659249 0.2588239 0 0.9659245 0.2588183 0 0.9659261 0.707104 0 0.7071096 0.965926 0 0.2588185 0.9659256 0 0.25882 0.6175526 0.4870809 -0.6175604 0.6175806 0.4870184 -0.6175819 0.2260425 0.4870828 -0.8435965 0.2260478 0.4870383 -0.8436208 -0.2260472 0.4870433 -0.8436182 -0.2260417 0.4870731 -0.8436024 -0.6175413 0.4871191 -0.6175416 -0.6175643 0.4870558 -0.6175686 -0.8435978 0.4870812 -0.2260416 -0.8435936 0.4870913 -0.2260352 -0.8435978 0.4870812 0.2260416 -0.8435927 0.4870925 0.2260358 -0.6175543 0.4870823 0.6175577 -0.6175411 0.4871263 0.6175363 -0.2260372 0.4870722 0.8436041 -0.2260475 0.4870725 0.8436012 0.2260511 0.4870633 0.8436055 0.2260369 0.4870755 0.8436023 0.6175584 0.4870783 0.6175569 0.6175788 0.4870193 0.617583 0.8435978 0.4870812 0.2260416 0.8436117 0.4870555 0.2260451 0.8435987 0.4870799 -0.226041 0.8436117 0.4870555 -0.2260451 0 -1 0 -0.8164608 0 0.5774009 -0.8165107 -1.60132e-5 0.5773302 -0.816501 6.06587e-5 0.5773441 0.5735781 0 0.8191509 0.573574 -7.48029e-6 0.8191538 0.5735805 0 0.8191493 -0.5358682 0.1138807 -0.8365862 -0.5145601 0.06278234 -0.8551529 -0.5009691 0.138289 -0.8543455 -0.4716407 0.02992981 -0.8812828 -0.4565151 0.09847676 -0.884249 1 -3.61245e-5 0 -0.9276526 0.3551953 -0.1153132 -0.8509248 0.5220258 -0.05844837 -0.8333916 0.5426977 0.1045842 -0.8486858 0.5288976 0 -0.8486589 0.5289406 0 0.7097811 0 -0.7044223 0.709782 0 -0.7044215 0.7097831 -7.20453e-7 -0.7044204 0.7097818 3.38249e-7 -0.7044217 0.7097826 0 -0.7044209 0.7097815 2.61182e-6 -0.704422 0.7097885 -5.30413e-5 -0.7044149 0.7097828 0 -0.7044206 0.7097907 1.2744e-5 -0.7044127 0.7097764 8.80523e-6 -0.7044271 0.7097216 1.10535e-4 -0.7044823 -0.6621474 -0.01076871 -0.7492963 -0.5859876 -0.1207928 -0.8012663 -0.6004232 -0.05519014 -0.7977758 -0.5797447 0.02370607 -0.8144533 0.4026916 0.007420301 0.9153057 0.4068731 0.01012301 0.9134286 0.4296792 0.001181542 0.9029809 0.4348537 -8.58889e-4 0.9005008 0.4350938 -9.68221e-4 0.9003847 0.3590301 0 0.933326 0.3823742 0.001630127 0.9240062 0.3990789 0.006889164 0.9168907 0.3171585 0 0.9483726 0.3171595 0 0.9483723 0.3171599 0 0.9483721 0.3171597 -2.78533e-7 0.9483722 -0.5780504 -0.2173585 -0.7865197 -0.5440701 -0.1710748 -0.8214141 -0.5458476 -0.1730892 -0.8198113 -0.5518385 -0.1791408 -0.8144832 -0.4650772 -0.2394614 -0.8522683 -0.5054298 -0.2125548 -0.8362783 -0.5111595 -0.1997753 -0.8359461 -0.5580725 -0.1814674 -0.8097065 -0.5602777 -0.1868641 -0.8069515 -0.4383909 -0.2354498 -0.8673967 -0.4348769 -0.2402722 -0.8678429 -0.4273456 -0.2386661 -0.8720173 -0.5367416 -0.2340591 -0.8106324 -0.5641856 -0.198202 -0.8015053 -0.5702688 -0.1970723 -0.7974686 -0.4195619 0.8956725 -0.1474405 -0.485569 0.8655769 -0.1224716 -0.4823912 0.8674855 -0.121523 -0.5409897 0.8345124 -0.1044952 -0.5473157 0.8365936 -0.02359628 -0.6335997 0.7613782 -0.1373131 -0.7683225 0.2212273 -0.6006155 -0.7665838 0.358124 -0.5330071 -0.7771185 0.3489007 -0.5237895 -0.6613621 -0.009911537 -0.7500014 -0.7145463 0.3246275 -0.6197101 -0.6989455 0.1673485 -0.6953199 -0.7759715 0.5232154 -0.3522979 -0.7156076 0.6494463 -0.2571486 -0.7123382 0.6457481 -0.2749247 -0.678878 0.6919192 -0.2457087 -0.6273556 0.7224154 -0.2907594 -0.6381848 0.7083642 -0.3015634 -0.7206715 0.6245791 -0.300888 -0.558957 0.7889028 -0.255342 -0.6975911 0.5174391 -0.4956042 -0.7252532 0.3951863 -0.5637692 -0.7510636 0.3792074 -0.5404676 -0.7525897 0.3692886 -0.5451925 -0.7773056 0.3490492 -0.5234128 -0.6663093 0.01104229 -0.7455938 -0.6709299 0.00677824 -0.7414898 -0.6695004 0.005927801 -0.742788 -0.6682462 0.006965994 -0.7439077 -0.6657852 0.003547847 -0.7461351 -0.6726242 -6.29958e-4 -0.739984 -0.6451225 -0.04643195 -0.7626671 -0.3511003 -0.2293841 -0.9078059 -0.3467407 -0.2180725 -0.9122583 -0.4122288 -0.2471062 -0.8769299 -0.415684 -0.2515574 -0.8740285 -0.2452833 0 0.9694516 -0.2452844 0 0.9694513 -0.2452564 -2.74439e-7 0.9694584 -0.245288 0 0.9694504 -0.9999279 0 0.01200979 0.7070987 -0.00438857 0.7071013 0.5477378 0 0.83665 0.2588208 0 0.9659253 0.2588167 0 0.9659265 -0.2588167 0 0.9659265 -0.2588208 0 0.9659253 -0.7071032 0 0.7071104 -0.7071055 0 0.7071082 -0.9659258 0 0.2588194 -0.9627473 -0.001192808 0.2704001 -0.9999279 0 0.01201009 -0.9659261 0 -0.2588186 -0.707104 0 -0.7071096 -0.2588226 0 -0.965925 0.2588226 0 -0.965925 0.7071063 0 -0.7071073 0.9659261 0 -0.2588186 0.9659261 0 0.2588186 0.7456129 0 0.6663793 0.7456154 0 0.6663765 0 1 0 0 1 1.31444e-7 0 1 -1.22791e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.42366e-5 0 1 0 1 0 0.258819 -0.9659259 0 0.7071068 -0.7071068 0 0.7071051 -0.7071086 0 0.9659264 -0.2588173 0 0.9659253 -0.2588207 0 -5.69463e-5 0 -1 5.21097e-6 0 -1 -0.9659266 0 -0.2588165 -0.9659246 0 -0.2588239 -0.7071118 0 -0.7071018 -0.7070968 0 -0.7071169 -0.25884 0 -0.9659203 -0.2588142 0 -0.9659272 0.258815 0 -0.965927 0.2588391 0 -0.9659205 0.7070984 0 -0.7071152 0.7071101 0 -0.7071034 0.9659248 0 -0.2588232 0.9659263 0 -0.2588172 0.9659266 0 0.2588165 0.9659263 0 0.2588172 0.7071118 0 0.7071018 0.7070968 0 0.7071169 0.258815 0 0.965927 0.2588142 0 0.9659272 -0.258815 0 0.965927 -0.2588142 0 0.9659272 -0.7070984 0 0.7071152 -0.7071101 0 0.7071034 -0.9659266 0 0.2588165 -0.9659263 0 0.2588172 0 1 4.76837e-7 0 1 -4.76837e-7 0 1 -1.90734e-6 0 1 1.90736e-6 0 -1 2.27174e-6 -0.4142487 0 -0.9101638 -0.4142472 0 -0.9101645 0.4142487 0 -0.9101638 0.414248 0 -0.9101642 0 -1 -7.11855e-6 0 -1 7.11825e-6 0 -1 1.50428e-6 -0.9659255 0 -0.2588204 -0.9659237 0 -0.258827 -0.7071135 0 -0.7071001 -0.7070993 0 -0.7071143 0.7071001 0 -0.7071135 0.7071126 0 -0.7071009 0.9659237 0 -0.258827 0.9659255 0 -0.2588204 0.9659255 0 0.2588204 0.7071135 0 0.7071001 0.7070993 0 0.7071143 -0.7071001 0 0.7071135 -0.7071126 0 0.7071009 -0.9659255 0 0.2588204 0 1 9.53674e-7 0 1 -9.53674e-7 0 1 -1.90733e-6 -0.2797425 -0.8568898 -0.4329943 0.08380484 -0.8541522 0.5132259 -0.1723493 -0.8531295 0.4924083 -0.5101974 -0.8491225 0.1367099 -0.5102051 -0.8491176 -0.136712 -0.388274 -0.85195 0.3513185 0.5092027 -0.8474424 -0.1501798 0.4040381 -0.8560427 0.322404 0.3182097 -0.8550151 0.4095017 0.5092066 -0.84744 0.1501809 -0.2797425 -0.8568898 0.4329943 -0.03856486 -0.8565297 0.5146548 0.2125499 -0.8560219 0.471221 0.08384066 -0.8541537 -0.5132178 0.2125499 -0.8560219 -0.471221 -0.0386455 -0.8565166 -0.5146708 0.2641516 -0.902587 -0.3399422 0.3623611 -0.8506269 -0.3809575 -0.1723494 -0.8531297 -0.4924079 -0.388267 -0.8519564 -0.3513104 0.6135805 0 0.7896323 0.5314066 0.03809463 0.84626 0.4110959 0 0.9115921 0.1612226 0 0.9869182 0.08684998 0.03375715 0.9956493 -0.07476943 0 0.9972009 -0.3303552 0 0.9438568 -0.3769484 0.02597141 0.9258701 -0.5426672 0 0.8399478 -0.7580398 0 0.6522083 -0.7414014 0.01640194 0.6708614 -0.9719278 -0.01809269 0.2345832 -0.9659245 0 0.258824 -0.9720857 0 -0.2346263 -0.9657933 -0.01640516 -0.2587939 -0.7579579 0.01469838 -0.6521378 -0.7415219 0 -0.6709287 -0.5426672 0 -0.8399478 -0.3769484 0.02597141 -0.9258701 -0.3303552 0 -0.9438568 -0.07483381 0 -0.9971961 0.08687049 0.0337674 -0.9956472 0.1612226 0 -0.9869182 0.4110959 0 -0.9115921 0.5314066 0.03809463 -0.84626 0.6135805 0 -0.7896323 0 1 1.86264e-6 0 1 -1.86267e-6 0 1 -1.4901e-6 0 1 -2.2352e-6 0 1 2.23516e-6 0 1 1.49011e-6 -0.9659237 0 -0.2588268 -0.9659263 0 -0.2588173 -0.7070993 0 -0.7071144 -0.707118 0 -0.7070956 -0.2588079 0 -0.9659289 -0.258808 0 -0.9659288 0.2588074 0 -0.965929 0.2588075 0 -0.9659289 0.7071182 0 -0.7070955 0.7070997 0 -0.7071139 0.9659266 0 -0.2588164 0.9659242 0 -0.2588257 0.9659242 0 0.2588257 0.965929 0 0.258807 0.7071182 0 0.7070955 0.7070997 0 0.7071139 0.2588074 0 0.965929 0.2588075 0 0.9659289 -0.2588079 0 0.9659289 -0.258808 0 0.9659288 -0.7070993 0 0.7071144 -0.707118 0 0.7070956 -0.9659288 0 0.2588081 -0.9659239 0 0.2588267 -0.3734924 -0.8491201 -0.373495 -0.5101937 -0.8491244 -0.1367118 0.373492 -0.8491205 -0.3734946 0.136712 -0.8491173 -0.5102055 -0.1367122 -0.8491169 -0.5102061 0.3735076 -0.8491156 0.3734899 0.5102021 -0.8491199 0.1367086 0.5101941 -0.8491238 -0.1367144 -0.373508 -0.8491153 0.3734903 -0.1367112 -0.8491195 0.5102022 0.1367112 -0.8491195 0.5102022 -0.5102017 -0.8491198 0.136711 0 1 1.86265e-6 0 1 -1.86268e-6 0 1 1.1176e-6 0 1 -1.11758e-6 -0.373492 -0.8491205 -0.3734946 -0.5101937 -0.8491249 -0.1367092 0.3734917 -0.8491196 -0.3734967 0.136713 -0.8491166 -0.5102064 -0.1367114 -0.8491172 -0.5102058 0.3735067 -0.8491154 0.3734915 0.5102051 -0.8491179 0.1367094 0.5101955 -0.849123 -0.1367148 -0.3735079 -0.8491155 0.3734901 -0.1367102 -0.8491201 0.5102014 0.1367118 -0.8491194 0.510202 -0.5102009 -0.849121 0.1367058 -0.9659242 0 -0.2588257 -0.9659266 0 -0.2588163 -0.7070998 0 -0.7071138 -0.7071186 0 -0.707095 -0.2588068 0 -0.9659292 -0.2588068 0 -0.9659291 0.258809 0 -0.9659286 0.2588092 0 -0.9659286 0.7071161 0 -0.7070975 0.7070977 0 -0.7071159 0.7071161 0 0.7070975 0.7070977 0 0.7071159 0.258809 0 0.9659286 0.2588092 0 0.9659286 -0.2588068 0 0.9659292 -0.2588068 0 0.9659291 -0.7070998 0 0.7071138 -0.7071186 0 0.707095 -0.965929 0 0.2588071 -0.9659242 0 0.2588257 -0.3735085 -0.8491155 -0.3734894 -0.5101951 -0.8491235 -0.1367124 0.3735089 -0.8491151 -0.3734899 0.1366988 -0.8491203 -0.5102041 -0.1366988 -0.8491203 -0.5102041 0.3735071 -0.8491168 0.373488 0.5102002 -0.8491212 0.1367077 0.5101978 -0.8491222 -0.1367102 -0.3735067 -0.8491172 0.3734875 -0.1366879 -0.8491201 0.5102074 0.1366886 -0.8491184 0.51021 -0.5102 -0.8491209 0.1367106 -0.965925 0 -0.2588224 -0.9659249 0 -0.2588225 -0.7071107 0 -0.7071029 -0.7071108 0 -0.7071028 -0.258807 0 -0.965929 -0.2588342 0 -0.9659218 0.2588342 0 -0.9659218 0.258807 0 -0.965929 0.7071107 0 -0.7071029 0.7071108 0 -0.7071028 0.9659268 0 -0.2588159 0.9659268 0 -0.2588158 0.9659268 0 0.2588159 0.9659268 0 0.2588158 0.7071107 0 0.7071029 0.7071108 0 0.7071028 0.258807 0 0.965929 -0.258807 0 0.965929 -0.7071107 0 0.7071029 -0.965925 0 0.2588224 -0.9659249 0 0.2588225 -0.5085862 -0.6947565 -0.5085799 -0.5085735 -0.6947747 -0.5085678 -0.1861429 -0.69478 -0.6947169 -0.1861865 -0.6947369 -0.6947484 0.1861763 -0.6947408 -0.6947472 0.1861568 -0.6947696 -0.6947236 0.5085675 -0.6947655 -0.5085865 0.5086043 -0.6947507 -0.5085697 0.694734 -0.6947593 -0.1861565 0.6947466 -0.6947466 -0.1861574 0.694759 -0.6947337 0.1861588 0.6947587 -0.6947356 0.186153 0.5085996 -0.6947369 0.5085933 0.5085946 -0.6947312 0.5086061 0.1861584 -0.694718 0.6947748 0.1861575 -0.6947667 0.6947264 -0.1861437 -0.6947767 0.69472 -0.1861687 -0.6947219 0.694768 -0.5085942 -0.6947262 0.5086132 -0.5085858 -0.6947568 0.50858 -0.6947343 -0.6947595 0.1861545 -0.6947585 -0.6947354 0.1861544 -0.6947333 -0.6947585 -0.1861618 -0.6947463 -0.6947463 -0.1861588 0 1 7.21122e-7 0 1 -7.21122e-7 0 1 7.21114e-7 0 1 -1.44221e-6 0 1 7.21118e-7 0 1 -7.21118e-7 -0.3735094 -0.8491147 -0.3734903 -0.5101957 -0.8491231 -0.1367126 0.3735089 -0.8491145 -0.3734912 0.1366987 -0.8491206 -0.5102037 -0.1366986 -0.8491208 -0.5102034 0.3735075 -0.8491158 0.3734899 0.5101993 -0.8491213 0.1367105 0.5101961 -0.8491234 -0.1367098 -0.373508 -0.8491159 0.3734889 -0.1366878 -0.8491205 0.5102068 0.1366879 -0.8491201 0.5102074 -0.510199 -0.8491215 0.1367104 -0.9659255 0 -0.2588208 -0.7071111 0 -0.7071025 -0.7071112 0 -0.7071023 -0.2588068 0 -0.9659292 -0.258834 0 -0.9659219 0.258834 0 -0.9659218 0.2588068 0 -0.9659292 0.7071109 0 -0.7071027 0.707111 0 -0.7071025 0.9659255 0 -0.2588203 0.9659255 0 -0.2588204 0.9659255 0 0.2588203 0.9659255 0 0.2588204 0.7071109 0 0.7071027 0.707111 0 0.7071025 0.2588068 0 0.9659292 0.2588068 0 0.9659292 -0.2588068 0 0.9659292 -0.2588068 0 0.9659292 -0.7071111 0 0.7071025 -0.7071112 0 0.7071023 -0.9659255 0 0.2588208 -0.5085878 -0.6947588 -0.5085752 -0.5085796 -0.6947658 -0.5085739 -0.1861428 -0.6947741 -0.6947228 -0.186187 -0.6947404 -0.6947447 0.1861748 -0.6947402 -0.6947482 0.5085647 -0.6947742 -0.5085773 0.5086028 -0.6947486 -0.508574 0.6947306 -0.6947621 -0.1861587 0.6947448 -0.6947476 -0.1861598 0.6947418 -0.6947513 0.1861573 0.6947597 -0.6947337 0.1861562 0.5086018 -0.6947336 0.5085955 0.5085935 -0.6947327 0.5086051 0.1861568 -0.6947119 0.6947813 0.186158 -0.6947709 0.694722 -0.1861437 -0.6947705 0.6947262 -0.1861709 -0.6947188 0.6947706 -0.5085898 -0.6947328 0.5086087 -0.5086035 -0.694735 0.508592 -0.6947495 -0.6947432 0.1861586 -0.6947527 -0.6947412 0.1861543 -0.6947394 -0.694752 -0.1861634 -0.6947352 -0.6947582 -0.1861558 0 1 -7.21119e-7 0 1 7.21119e-7 0 1 7.21117e-7 0 1 -1.44222e-6 0 1 5.40839e-7 0 1 -5.40839e-7 0 1 -7.21108e-7 0 -1 -1.46185e-6 -0.8142076 0 0.580574 -0.814224 0 0.5805509 -0.4322161 0 0.9017701 -0.432174 0 0.9017903 0.0574761 0 0.9983469 0.05742526 0 0.9983499 0.5328267 0 0.8462244 0.5328077 0 0.8462364 0.8754576 0 0.483295 0.8754394 0 0.483328 0.8754398 0 -0.4833274 0.8754454 0 -0.4833172 0.5328449 0 -0.8462129 0.532826 0 -0.8462249 0.05742532 0 -0.9983498 0.05747604 0 -0.998347 -0.4322161 0 -0.9017701 -0.4322155 0 -0.9017705 -0.8142076 0 -0.580574 -0.8142068 0 -0.5805751 0.9937312 0 0.1117973 0.9937303 0 0.1118049 0.9659262 0 0.2588181 0.9659281 0 0.2588107 0.7070939 0 0.7071197 0.7071086 0 0.7071049 0.2588156 0 0.9659268 0.2588431 0 0.9659194 -0.2588413 0 0.96592 -0.2588137 0 0.9659273 -0.7071105 0 0.7071031 -0.7070958 0 0.7071179 -0.9659281 0 0.2588107 -0.9659262 0 0.2588181 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 2 1 1 1 3 1 2 2 3 2 4 2 5 3 6 3 7 3 7 4 6 4 8 4 7 5 8 5 9 5 9 6 8 6 1 6 9 7 1 7 10 7 10 8 1 8 0 8 10 9 0 9 11 9 11 10 0 10 12 10 11 11 12 11 13 11 13 12 12 12 14 12 15 13 16 13 17 13 17 14 16 14 18 14 19 15 20 15 21 15 19 16 21 16 22 16 22 17 21 17 23 17 23 18 21 18 24 18 23 19 24 19 25 19 25 20 24 20 26 20 25 21 26 21 27 21 27 22 26 22 28 22 27 23 28 23 29 23 29 24 28 24 30 24 29 25 30 25 31 25 31 26 30 26 32 26 31 27 32 27 33 27 33 28 32 28 34 28 33 29 34 29 35 29 35 30 34 30 36 30 35 31 36 31 37 31 37 32 36 32 38 32 37 33 38 33 39 33 39 34 38 34 40 34 39 35 40 35 41 35 41 36 40 36 42 36 41 37 42 37 43 37 43 38 42 38 44 38 43 39 44 39 45 39 19 40 22 40 20 40 46 41 47 41 48 41 48 42 47 42 49 42 48 43 49 43 50 43 51 44 52 44 53 44 53 45 52 45 17 45 53 46 17 46 18 46 54 47 55 47 56 47 56 48 55 48 57 48 56 49 57 49 51 49 51 50 57 50 58 50 51 51 58 51 52 51 54 52 56 52 59 52 59 53 56 53 60 53 59 54 60 54 61 54 60 55 62 55 61 55 61 56 62 56 63 56 61 57 63 57 64 57 64 58 63 58 65 58 64 59 65 59 66 59 66 60 65 60 67 60 67 61 65 61 68 61 67 62 68 62 69 62 69 63 68 63 70 63 69 64 70 64 71 64 72 65 73 65 47 65 47 66 73 66 74 66 47 67 74 67 49 67 50 68 75 68 48 68 48 69 75 69 46 69 46 70 75 70 76 70 46 71 76 71 77 71 77 72 76 72 73 72 77 73 73 73 72 73 78 74 79 74 80 74 80 75 79 75 81 75 80 76 82 76 78 76 78 77 82 77 83 77 78 78 83 78 84 78 84 79 83 79 85 79 84 80 85 80 86 80 86 81 85 81 87 81 88 82 89 82 90 82 90 83 89 83 91 83 90 84 91 84 92 84 93 85 94 85 95 85 95 86 94 86 90 86 95 87 90 87 96 87 96 88 90 88 92 88 87 89 85 89 90 89 90 90 85 90 97 90 90 91 97 91 98 91 98 92 99 92 90 92 90 93 99 93 100 93 90 94 100 94 88 94 101 95 102 95 103 95 104 95 105 95 106 95 106 95 107 95 104 95 104 95 107 95 108 95 104 95 108 95 103 95 103 95 108 95 109 95 103 95 109 95 101 95 110 96 111 96 112 96 113 97 114 97 90 97 115 98 110 98 90 98 94 98 105 98 90 98 90 98 105 98 104 98 90 98 104 98 116 98 116 98 104 98 117 98 116 98 117 98 118 98 110 99 112 99 90 99 90 100 112 100 119 100 90 101 119 101 113 101 120 98 90 98 121 98 121 102 90 102 114 102 121 103 114 103 122 103 122 104 114 104 123 104 124 98 125 98 116 98 116 98 125 98 126 98 116 98 126 98 90 98 90 98 126 98 127 98 90 98 127 98 115 98 128 98 124 98 129 98 129 98 124 98 116 98 129 98 116 98 130 98 130 105 116 105 131 105 132 95 133 95 134 95 134 95 133 95 135 95 134 95 135 95 136 95 137 95 138 95 139 95 139 95 138 95 140 95 140 95 134 95 136 95 140 95 136 95 139 95 78 106 141 106 142 106 143 107 144 107 145 107 138 108 79 108 140 108 140 109 79 109 78 109 140 110 78 110 146 110 146 111 78 111 142 111 146 112 142 112 147 112 146 113 148 113 140 113 140 114 148 114 149 114 140 115 149 115 150 115 150 116 151 116 140 116 140 117 151 117 152 117 140 118 152 118 153 118 154 106 145 106 155 106 155 119 145 119 156 119 155 120 156 120 157 120 158 106 143 106 159 106 159 106 143 106 145 106 159 106 145 106 160 106 160 106 145 106 154 106 153 121 161 121 140 121 140 122 161 122 162 122 140 123 162 123 156 123 156 124 162 124 163 124 156 125 163 125 157 125 164 126 165 126 166 126 166 127 165 127 167 127 166 128 167 128 168 128 168 129 167 129 169 129 170 130 171 130 172 130 172 131 171 131 173 131 172 132 173 132 174 132 175 133 176 133 177 133 175 134 177 134 173 134 173 135 177 135 178 135 173 136 178 136 179 136 169 137 167 137 172 137 172 138 167 138 180 138 172 139 180 139 170 139 179 140 181 140 173 140 173 141 181 141 182 141 173 142 182 142 183 142 183 143 184 143 173 143 173 144 184 144 185 144 173 145 185 145 174 145 186 95 187 95 188 95 186 95 188 95 189 95 189 95 188 95 190 95 189 95 190 95 191 95 191 95 190 95 192 95 192 95 190 95 193 95 192 95 193 95 194 95 195 146 196 146 197 146 167 98 198 98 195 98 199 147 200 147 167 147 195 148 197 148 167 148 167 149 197 149 201 149 167 150 201 150 199 150 202 98 167 98 203 98 203 151 167 151 200 151 203 152 200 152 204 152 204 153 200 153 205 153 206 154 207 154 208 154 208 98 207 98 209 98 165 98 193 98 167 98 167 98 193 98 190 98 167 98 190 98 198 98 198 98 190 98 210 98 198 98 210 98 211 98 211 98 210 98 212 98 212 98 210 98 213 98 213 98 210 98 208 98 213 98 208 98 214 98 214 98 208 98 209 98 214 98 209 98 215 98 216 95 217 95 218 95 219 95 220 95 221 95 221 95 220 95 222 95 221 95 222 95 223 95 223 95 222 95 216 95 223 95 216 95 224 95 224 95 216 95 218 95 225 155 226 155 227 155 228 156 229 156 230 156 231 157 232 157 173 157 220 106 175 106 222 106 222 106 175 106 173 106 222 106 173 106 233 106 234 158 235 158 236 158 236 159 235 159 237 159 236 160 237 160 238 160 239 106 230 106 240 106 240 106 230 106 233 106 240 106 233 106 241 106 231 161 173 161 242 161 232 162 225 162 173 162 173 163 225 163 227 163 173 106 227 106 233 106 233 106 227 106 243 106 233 106 243 106 241 106 244 164 228 164 245 164 245 165 228 165 230 165 245 106 230 106 246 106 246 106 230 106 239 106 238 166 237 166 173 166 173 167 237 167 247 167 173 168 247 168 242 168 248 169 249 169 250 169 251 106 252 106 253 106 253 106 252 106 254 106 253 106 254 106 255 106 256 107 257 107 254 107 248 170 250 170 258 170 259 106 260 106 261 106 261 106 260 106 262 106 259 106 263 106 260 106 260 106 263 106 264 106 260 106 264 106 254 106 254 106 264 106 265 106 254 106 265 106 255 106 266 106 267 106 254 106 250 171 268 171 269 171 266 106 254 106 270 106 271 106 272 106 273 106 273 106 272 106 258 106 273 106 258 106 274 106 274 172 258 172 250 172 274 173 250 173 275 173 275 174 250 174 269 174 276 106 277 106 269 106 269 106 277 106 270 106 269 106 270 106 278 106 278 106 270 106 254 106 278 106 254 106 279 106 279 106 254 106 252 106 268 175 280 175 269 175 269 176 280 176 281 176 269 177 281 177 282 177 283 106 256 106 284 106 284 106 256 106 254 106 284 106 254 106 285 106 285 106 254 106 267 106 282 178 286 178 269 178 269 179 286 179 287 179 269 180 287 180 276 180 276 181 287 181 288 181 289 182 290 182 291 182 291 183 290 183 292 183 293 184 294 184 290 184 290 185 294 185 295 185 290 186 295 186 292 186 296 187 297 187 293 187 293 188 297 188 298 188 293 189 298 189 294 189 299 190 300 190 301 190 301 191 300 191 302 191 301 192 302 192 296 192 296 193 302 193 303 193 296 194 303 194 297 194 304 195 305 195 306 195 306 196 305 196 307 196 306 197 307 197 308 197 309 198 310 198 311 198 311 199 310 199 312 199 311 200 312 200 305 200 305 201 312 201 313 201 305 202 313 202 307 202 314 203 309 203 315 203 315 204 309 204 311 204 315 205 311 205 316 205 316 206 311 206 317 206 316 207 317 207 318 207 318 208 317 208 319 208 320 209 321 209 317 209 317 210 321 210 322 210 317 211 322 211 319 211 323 212 324 212 325 212 325 213 324 213 326 213 325 214 326 214 320 214 320 215 326 215 327 215 320 216 327 216 321 216 44 217 328 217 329 217 45 218 44 218 329 218 45 219 329 219 330 219 330 220 329 220 331 220 330 221 331 221 332 221 332 222 300 222 330 222 330 223 300 223 299 223 330 224 299 224 333 224 333 225 299 225 304 225 333 226 304 226 306 226 334 227 289 227 335 227 335 228 289 228 291 228 335 229 291 229 336 229 336 230 291 230 292 230 336 231 292 231 337 231 337 232 292 232 338 232 338 233 292 233 295 233 338 234 295 234 339 234 340 235 341 235 334 235 341 236 342 236 334 236 334 237 342 237 343 237 334 238 343 238 344 238 336 239 337 239 335 239 335 240 337 240 345 240 335 241 345 241 334 241 334 242 345 242 346 242 334 243 346 243 340 243 347 244 340 244 348 244 348 245 340 245 346 245 348 246 346 246 345 246 349 247 350 247 344 247 344 248 343 248 349 248 349 249 343 249 342 249 349 250 342 250 347 250 347 251 342 251 341 251 347 252 341 252 340 252 305 253 304 253 299 253 2 254 344 254 0 254 0 255 344 255 350 255 320 256 317 256 311 256 350 257 351 257 0 257 0 258 351 258 352 258 0 259 352 259 353 259 2 260 4 260 344 260 344 261 4 261 325 261 344 262 325 262 334 262 334 263 325 263 289 263 311 264 305 264 320 264 320 265 305 265 299 265 320 266 299 266 325 266 325 267 299 267 301 267 325 268 301 268 296 268 296 269 293 269 325 269 325 270 293 270 290 270 325 271 290 271 289 271 345 272 337 272 354 272 354 273 337 273 338 273 354 274 338 274 355 274 355 275 338 275 339 275 355 276 339 276 356 276 328 277 357 277 46 277 46 278 357 278 358 278 46 279 358 279 47 279 47 280 358 280 16 280 47 281 16 281 15 281 348 282 345 282 359 282 359 283 345 283 354 283 359 284 354 284 360 284 360 285 354 285 361 285 360 286 361 286 77 286 329 287 328 287 362 287 362 288 328 288 46 288 362 289 46 289 356 289 356 290 46 290 77 290 356 291 77 291 355 291 355 292 77 292 361 292 77 293 72 293 360 293 360 294 72 294 47 294 360 295 47 295 363 295 363 296 47 296 15 296 363 297 15 297 364 297 364 298 15 298 365 298 364 299 365 299 366 299 366 300 365 300 367 300 368 301 369 301 370 301 368 302 370 302 371 302 370 303 372 303 373 303 373 304 374 304 370 304 370 305 374 305 375 305 370 306 375 306 371 306 376 307 377 307 378 307 378 308 377 308 379 308 380 309 381 309 382 309 382 310 381 310 378 310 382 311 378 311 383 311 383 312 378 312 379 312 383 313 379 313 384 313 384 314 379 314 385 314 386 315 387 315 388 315 386 316 388 316 389 316 390 317 391 317 392 317 330 318 333 318 393 318 393 319 333 319 306 319 393 320 306 320 308 320 308 321 394 321 395 321 395 322 394 322 396 322 395 323 396 323 397 323 397 324 396 324 398 324 397 325 398 325 399 325 399 326 398 326 400 326 399 327 400 327 401 327 401 328 400 328 402 328 401 329 402 329 403 329 403 330 402 330 404 330 403 331 404 331 405 331 405 332 404 332 406 332 405 333 406 333 407 333 407 334 406 334 408 334 406 335 409 335 408 335 408 336 409 336 410 336 408 337 410 337 411 337 411 338 410 338 412 338 411 339 412 339 413 339 413 340 412 340 414 340 413 341 414 341 415 341 415 342 414 342 416 342 415 343 416 343 417 343 392 344 391 344 418 344 418 345 391 345 419 345 418 346 419 346 420 346 420 347 419 347 421 347 420 348 421 348 422 348 423 349 424 349 425 349 425 350 424 350 426 350 425 351 426 351 427 351 427 352 426 352 428 352 427 353 428 353 429 353 429 354 428 354 430 354 429 355 430 355 431 355 431 356 430 356 432 356 431 357 432 357 433 357 433 358 432 358 434 358 433 359 434 359 435 359 436 360 437 360 438 360 438 361 437 361 439 361 438 362 439 362 440 362 440 363 439 363 441 363 440 364 441 364 442 364 442 365 441 365 443 365 442 366 443 366 423 366 423 367 443 367 444 367 423 368 444 368 424 368 438 369 445 369 436 369 436 370 445 370 422 370 436 371 422 371 446 371 446 372 422 372 421 372 416 373 447 373 417 373 417 374 447 374 448 374 417 375 448 375 449 375 449 376 448 376 450 376 449 377 450 377 451 377 451 378 450 378 452 378 451 379 452 379 453 379 453 380 452 380 454 380 453 381 454 381 455 381 455 382 454 382 456 382 455 383 456 383 457 383 457 384 456 384 458 384 457 385 458 385 459 385 459 386 458 386 460 386 459 387 460 387 461 387 461 388 460 388 462 388 461 389 462 389 463 389 463 390 462 390 464 390 463 391 464 391 465 391 465 392 464 392 435 392 465 393 435 393 466 393 466 394 435 394 434 394 467 395 468 395 469 395 469 396 468 396 470 396 469 397 470 397 471 397 471 398 470 398 472 398 471 399 472 399 473 399 473 400 472 400 474 400 473 401 474 401 475 401 475 402 474 402 476 402 475 403 476 403 477 403 477 404 476 404 478 404 477 405 478 405 479 405 479 406 478 406 480 406 479 407 480 407 481 407 481 408 480 408 482 408 481 409 482 409 483 409 483 410 482 410 484 410 483 411 484 411 485 411 485 412 484 412 486 412 485 413 486 413 487 413 487 414 486 414 390 414 487 415 390 415 488 415 488 416 390 416 392 416 489 417 490 417 491 417 491 418 490 418 492 418 491 419 492 419 493 419 493 420 492 420 494 420 493 421 494 421 495 421 495 422 494 422 496 422 495 423 496 423 497 423 497 424 496 424 498 424 497 425 498 425 499 425 499 426 498 426 500 426 499 427 500 427 501 427 501 428 500 428 502 428 501 429 502 429 503 429 503 430 502 430 504 430 503 431 504 431 505 431 505 432 504 432 506 432 505 433 506 433 507 433 507 434 506 434 508 434 507 435 508 435 509 435 509 436 508 436 510 436 509 437 510 437 467 437 467 438 510 438 511 438 467 439 511 439 468 439 491 440 512 440 489 440 489 441 512 441 513 441 489 442 513 442 514 442 514 443 513 443 515 443 514 444 515 444 516 444 516 445 515 445 517 445 516 446 517 446 518 446 518 447 517 447 519 447 518 448 519 448 520 448 520 449 519 449 521 449 520 450 521 450 522 450 522 451 521 451 523 451 522 452 523 452 524 452 524 453 523 453 525 453 524 454 525 454 526 454 525 455 527 455 526 455 526 456 527 456 528 456 526 457 528 457 529 457 529 458 528 458 530 458 529 459 530 459 531 459 531 460 530 460 532 460 388 461 533 461 389 461 389 462 533 462 534 462 389 463 534 463 535 463 535 464 534 464 536 464 535 465 536 465 537 465 537 466 536 466 538 466 537 467 538 467 539 467 539 468 538 468 540 468 539 469 540 469 541 469 541 470 540 470 542 470 541 471 542 471 543 471 543 472 542 472 544 472 543 473 544 473 545 473 545 474 544 474 546 474 545 475 546 475 547 475 547 476 546 476 548 476 547 477 548 477 549 477 549 478 548 478 550 478 549 479 550 479 551 479 551 480 550 480 552 480 551 481 552 481 532 481 532 482 552 482 553 482 532 483 553 483 531 483 554 484 555 484 556 484 557 485 558 485 559 485 560 486 561 486 558 486 558 487 561 487 562 487 558 311 562 311 559 311 563 488 564 488 565 488 565 489 564 489 554 489 565 490 554 490 559 490 559 491 554 491 556 491 559 492 556 492 557 492 566 493 567 493 568 493 566 494 568 494 569 494 570 495 571 495 572 495 573 496 574 496 575 496 575 497 574 497 576 497 575 498 576 498 568 498 568 499 576 499 577 499 568 500 577 500 569 500 570 501 572 501 575 501 575 502 572 502 578 502 575 503 578 503 573 503 579 504 580 504 581 504 581 505 580 505 582 505 581 506 582 506 583 506 583 507 582 507 584 507 585 508 586 508 587 508 588 509 583 509 589 509 589 510 583 510 584 510 589 511 584 511 590 511 590 512 584 512 591 512 590 513 591 513 592 513 592 514 591 514 593 514 592 515 593 515 594 515 594 516 593 516 595 516 595 517 593 517 596 517 595 518 596 518 597 518 597 519 596 519 598 519 597 520 598 520 599 520 587 521 600 521 585 521 585 522 600 522 601 522 585 523 601 523 581 523 581 524 601 524 602 524 581 525 602 525 579 525 603 526 604 526 605 526 606 527 607 527 608 527 607 528 606 528 609 528 608 529 610 529 606 529 606 530 610 530 611 530 606 531 611 531 612 531 603 532 605 532 606 532 606 533 605 533 613 533 606 534 613 534 609 534 614 535 615 535 616 535 616 536 615 536 617 536 617 537 618 537 616 537 616 538 618 538 619 538 616 539 619 539 620 539 620 540 619 540 621 540 622 541 623 541 624 541 624 542 623 542 625 542 624 543 625 543 626 543 626 544 625 544 627 544 628 545 629 545 614 545 614 546 629 546 625 546 614 547 625 547 615 547 627 548 625 548 630 548 630 549 625 549 629 549 630 550 629 550 631 550 632 551 633 551 634 551 635 552 636 552 637 552 638 553 639 553 640 553 641 554 642 554 638 554 638 555 642 555 643 555 638 556 643 556 639 556 631 557 629 557 637 557 637 558 629 558 644 558 637 559 644 559 635 559 634 560 633 560 638 560 638 561 633 561 645 561 638 562 645 562 641 562 640 563 646 563 638 563 638 564 646 564 647 564 638 565 647 565 648 565 649 566 650 566 628 566 628 567 650 567 651 567 628 568 651 568 629 568 629 569 651 569 638 569 629 570 638 570 652 570 652 571 638 571 648 571 653 572 654 572 634 572 634 573 654 573 655 573 634 574 655 574 632 574 632 575 655 575 656 575 632 576 656 576 657 576 657 577 656 577 658 577 658 578 659 578 657 578 657 579 659 579 660 579 657 580 660 580 661 580 661 581 660 581 662 581 661 582 662 582 663 582 664 583 665 583 666 583 666 584 665 584 667 584 666 585 667 585 668 585 667 586 669 586 668 586 668 587 669 587 670 587 668 588 670 588 671 588 671 589 670 589 672 589 671 589 672 589 673 589 673 590 672 590 674 590 673 591 674 591 675 591 674 106 676 106 675 106 675 106 676 106 677 106 678 592 679 592 680 592 681 593 682 593 683 593 683 594 682 594 678 594 683 595 678 595 684 595 684 596 678 596 680 596 684 597 680 597 685 597 685 598 680 598 686 598 687 599 688 599 689 599 689 600 690 600 687 600 687 601 690 601 691 601 687 602 691 602 686 602 686 603 691 603 692 603 686 604 692 604 685 604 693 605 694 605 695 605 695 606 696 606 693 606 693 607 696 607 697 607 693 608 697 608 698 608 698 609 699 609 693 609 693 610 699 610 700 610 693 611 700 611 687 611 687 612 700 612 701 612 687 613 701 613 688 613 702 614 703 614 704 614 705 615 706 615 693 615 693 616 706 616 707 616 693 617 707 617 694 617 702 618 704 618 693 618 693 619 704 619 708 619 693 620 708 620 705 620 677 621 676 621 702 621 702 622 676 622 709 622 702 623 709 623 710 623 711 624 712 624 713 624 710 625 714 625 702 625 702 626 714 626 713 626 702 627 713 627 703 627 703 628 713 628 712 628 711 629 713 629 715 629 715 630 713 630 716 630 715 631 716 631 717 631 718 632 719 632 720 632 721 632 718 632 722 632 723 632 724 632 725 632 725 632 724 632 722 632 726 633 727 633 582 633 720 633 719 633 728 633 729 633 730 633 731 633 720 634 728 634 732 634 732 635 728 635 733 635 732 633 733 633 734 633 734 633 733 633 726 633 734 633 726 633 735 633 735 636 726 636 582 636 735 637 582 637 731 637 731 638 582 638 580 638 731 639 580 639 729 639 736 640 737 640 738 640 739 633 740 633 738 633 738 633 740 633 741 633 738 641 741 641 736 641 742 642 743 642 744 642 744 643 743 643 745 643 746 644 747 644 745 644 745 645 747 645 748 645 745 646 748 646 744 646 749 647 750 647 751 647 751 648 750 648 752 648 751 649 752 649 746 649 746 650 752 650 753 650 746 651 753 651 747 651 749 652 751 652 754 652 754 653 751 653 755 653 754 654 755 654 756 654 757 655 758 655 759 655 759 656 758 656 760 656 759 657 761 657 757 657 757 658 761 658 762 658 757 659 762 659 763 659 763 660 762 660 764 660 764 661 762 661 765 661 764 662 765 662 766 662 760 663 767 663 759 663 759 664 767 664 768 664 759 665 768 665 769 665 769 666 768 666 770 666 769 667 770 667 771 667 772 668 773 668 774 668 774 669 773 669 775 669 776 670 777 670 778 670 778 671 777 671 775 671 778 672 775 672 779 672 779 673 775 673 773 673 780 674 781 674 782 674 782 675 781 675 783 675 782 676 783 676 776 676 776 677 783 677 784 677 776 678 784 678 777 678 777 678 784 678 785 678 786 679 787 679 788 679 788 680 789 680 786 680 786 681 789 681 781 681 786 682 781 682 790 682 791 683 792 683 793 683 794 684 795 684 793 684 793 685 795 685 796 685 793 686 796 686 791 686 797 687 798 687 799 687 799 688 798 688 800 688 799 689 800 689 794 689 794 690 800 690 801 690 794 691 801 691 795 691 799 692 802 692 797 692 797 693 802 693 803 693 797 694 803 694 804 694 804 695 803 695 605 695 804 696 605 696 604 696 805 697 806 697 807 697 808 698 809 698 810 698 811 699 812 699 813 699 814 700 815 700 816 700 816 701 815 701 811 701 811 702 815 702 807 702 811 703 807 703 812 703 817 704 818 704 819 704 819 705 818 705 820 705 820 706 818 706 821 706 821 707 818 707 822 707 821 708 822 708 805 708 815 709 810 709 807 709 807 710 810 710 809 710 807 711 809 711 805 711 805 712 809 712 808 712 805 713 808 713 821 713 823 714 824 714 825 714 826 715 827 715 828 715 828 716 827 716 829 716 828 717 829 717 830 717 824 718 823 718 831 718 831 719 823 719 830 719 831 720 830 720 832 720 832 721 830 721 829 721 832 722 829 722 833 722 834 723 823 723 835 723 835 724 823 724 825 724 835 725 825 725 836 725 834 726 837 726 823 726 823 727 837 727 838 727 823 728 838 728 830 728 830 729 838 729 839 729 830 730 839 730 828 730 828 731 839 731 840 731 828 732 840 732 826 732 826 733 840 733 841 733 826 734 841 734 842 734 837 735 834 735 843 735 571 736 842 736 841 736 839 737 838 737 844 737 844 738 838 738 837 738 572 739 571 739 845 739 845 740 571 740 841 740 845 741 841 741 846 741 846 742 841 742 840 742 837 743 843 743 844 743 844 744 843 744 847 744 844 745 847 745 848 745 848 746 849 746 844 746 844 747 849 747 846 747 844 748 846 748 839 748 839 749 846 749 840 749 578 750 572 750 850 750 850 751 572 751 845 751 850 752 845 752 851 752 851 753 845 753 846 753 851 754 846 754 852 754 852 755 846 755 849 755 853 756 854 756 855 756 856 757 857 757 858 757 857 758 859 758 858 758 858 759 859 759 860 759 858 760 860 760 861 760 569 761 862 761 566 761 566 762 862 762 861 762 566 763 861 763 567 763 567 764 861 764 860 764 863 765 858 765 864 765 864 766 858 766 861 766 864 767 861 767 865 767 865 768 861 768 862 768 863 769 853 769 858 769 858 770 853 770 855 770 858 771 855 771 856 771 856 772 855 772 866 772 856 773 866 773 867 773 867 774 866 774 868 774 867 775 868 775 869 775 869 776 868 776 870 776 869 777 870 777 871 777 871 778 870 778 872 778 871 779 872 779 873 779 873 780 872 780 874 780 873 781 874 781 875 781 875 782 874 782 876 782 875 783 876 783 877 783 877 784 876 784 878 784 877 785 878 785 879 785 879 786 878 786 880 786 879 787 880 787 881 787 881 788 880 788 882 788 881 789 882 789 883 789 884 98 787 98 885 98 885 790 787 790 786 790 885 98 786 98 790 98 141 633 78 633 84 633 886 633 887 633 888 633 84 791 889 791 141 791 141 792 889 792 890 792 141 633 890 633 891 633 891 793 890 793 892 793 891 794 892 794 888 794 888 795 892 795 893 795 888 796 893 796 886 796 894 797 895 797 171 797 896 798 897 798 743 798 743 799 897 799 898 799 743 800 898 800 899 800 173 801 171 801 238 801 238 802 171 802 895 802 238 803 895 803 900 803 900 804 895 804 896 804 900 805 896 805 742 805 742 806 896 806 743 806 901 807 170 807 902 807 902 808 170 808 180 808 902 809 180 809 903 809 903 810 180 810 904 810 901 811 905 811 170 811 170 812 905 812 906 812 170 813 906 813 171 813 171 814 906 814 907 814 171 815 907 815 894 815 908 816 909 816 86 816 86 817 909 817 910 817 86 818 910 818 84 818 84 819 910 819 911 819 84 820 911 820 889 820 908 821 86 821 912 821 912 822 86 822 87 822 912 823 87 823 913 823 87 824 90 824 120 824 765 825 914 825 766 825 766 826 914 826 915 826 766 827 915 827 120 827 120 828 915 828 916 828 120 829 916 829 87 829 87 830 916 830 917 830 87 831 917 831 913 831 180 633 167 633 904 633 904 633 167 633 202 633 918 633 919 633 920 633 920 832 919 832 921 832 920 633 921 633 922 633 922 633 921 633 923 633 923 833 921 833 924 833 923 633 924 633 202 633 202 834 924 834 925 834 202 835 925 835 904 835 586 836 585 836 926 836 926 837 585 837 927 837 740 838 739 838 927 838 927 839 739 839 928 839 927 840 928 840 926 840 926 841 928 841 929 841 926 842 929 842 930 842 929 843 931 843 930 843 930 844 931 844 932 844 930 845 932 845 933 845 934 846 935 846 936 846 936 847 935 847 933 847 936 848 933 848 937 848 937 849 933 849 932 849 678 98 938 98 679 98 679 850 938 850 939 850 940 98 941 98 679 98 679 851 941 851 772 851 679 98 772 98 774 98 939 852 942 852 679 852 679 98 942 98 943 98 679 853 943 853 940 853 784 854 783 854 944 854 785 855 784 855 945 855 945 856 784 856 944 856 945 857 944 857 946 857 783 858 781 858 944 858 944 859 781 859 789 859 944 860 789 860 946 860 946 861 789 861 788 861 947 632 948 632 949 632 949 632 948 632 950 632 949 632 950 632 951 632 951 632 950 632 952 632 953 95 954 95 955 95 955 95 956 95 953 95 953 95 956 95 957 95 953 95 957 95 958 95 958 95 957 95 959 95 958 95 959 95 960 95 960 95 959 95 961 95 960 95 961 95 962 95 962 95 961 95 963 95 964 95 965 95 966 95 366 95 967 95 968 95 968 95 967 95 964 95 968 95 964 95 969 95 969 95 964 95 966 95 969 95 966 95 970 95 971 95 972 95 366 95 366 95 972 95 973 95 366 95 973 95 967 95 971 95 366 95 974 95 974 95 366 95 367 95 974 95 367 95 975 95 975 862 367 862 976 862 976 863 367 863 365 863 976 864 365 864 52 864 52 865 365 865 15 865 52 866 15 866 17 866 330 867 393 867 977 867 18 868 16 868 357 868 26 869 24 869 328 869 45 870 330 870 43 870 43 871 330 871 977 871 43 872 977 872 41 872 41 873 977 873 978 873 41 874 978 874 39 874 24 875 21 875 328 875 328 876 21 876 20 876 328 877 20 877 357 877 39 878 978 878 37 878 37 879 978 879 979 879 37 880 979 880 35 880 38 881 36 881 328 881 328 882 36 882 34 882 328 883 34 883 32 883 32 884 30 884 328 884 328 885 30 885 28 885 328 886 28 886 26 886 27 887 29 887 980 887 980 888 29 888 31 888 980 889 31 889 979 889 979 890 31 890 33 890 979 891 33 891 35 891 44 892 42 892 328 892 328 893 42 893 40 893 328 894 40 894 38 894 20 895 981 895 982 895 357 896 20 896 18 896 18 897 20 897 982 897 18 898 982 898 53 898 20 899 22 899 981 899 981 900 22 900 23 900 981 901 23 901 980 901 980 902 23 902 25 902 980 903 25 903 27 903 355 904 361 904 354 904 983 98 379 98 984 98 984 98 379 98 377 98 984 905 377 905 985 905 985 98 377 98 986 98 987 98 988 98 954 98 954 906 988 906 989 906 954 907 989 907 990 907 991 98 955 98 377 98 377 908 955 908 954 908 986 98 377 98 992 98 992 909 377 909 954 909 992 98 954 98 993 98 993 910 954 910 990 910 993 98 990 98 994 98 995 911 996 911 997 911 998 106 962 106 999 106 999 912 962 912 1000 912 1001 913 970 913 1002 913 1002 914 970 914 966 914 1003 915 1004 915 1005 915 1006 106 1007 106 1008 106 1009 916 1003 916 1010 916 1010 917 1003 917 1005 917 1010 918 1005 918 1011 918 1011 919 1005 919 1012 919 997 920 996 920 1005 920 1005 921 996 921 1013 921 1005 922 1013 922 1012 922 997 923 1014 923 995 923 995 106 1014 106 1015 106 995 106 1015 106 1001 106 1001 924 1015 924 1016 924 1001 925 1016 925 970 925 1000 106 1017 106 999 106 999 926 1017 926 1018 926 999 106 1018 106 1019 106 1019 927 1018 927 1020 927 1019 928 1020 928 1008 928 1008 929 1020 929 1021 929 1008 930 1021 930 1006 930 1004 931 1003 931 963 931 963 932 1003 932 1022 932 963 933 1022 933 962 933 962 934 1022 934 1023 934 962 106 1023 106 1024 106 1024 106 1025 106 962 106 962 935 1025 935 1026 935 962 936 1026 936 1000 936 988 937 987 937 1027 937 988 938 1027 938 1028 938 1028 939 1027 939 1029 939 1028 940 1029 940 1030 940 1030 941 1029 941 1031 941 1030 942 1031 942 1032 942 1033 943 1034 943 986 943 986 944 1034 944 1035 944 986 945 1035 945 985 945 985 946 1035 946 1036 946 985 947 1036 947 984 947 984 948 1036 948 1037 948 984 949 1037 949 1038 949 1033 950 986 950 1039 950 1039 951 986 951 992 951 1039 952 992 952 1040 952 1040 953 992 953 1041 953 1041 954 992 954 993 954 1041 955 993 955 1042 955 990 956 1043 956 994 956 994 957 1043 957 1044 957 994 958 1044 958 993 958 993 959 1044 959 1045 959 993 960 1045 960 1042 960 989 961 1046 961 990 961 990 962 1046 962 1047 962 990 963 1047 963 1043 963 1028 964 1048 964 988 964 988 965 1048 965 1049 965 988 966 1049 966 989 966 989 967 1049 967 1050 967 989 968 1050 968 1046 968 1051 969 964 969 967 969 69 970 71 970 1052 970 1052 971 1053 971 69 971 69 972 1053 972 1051 972 69 973 1051 973 67 973 67 974 1051 974 967 974 67 975 967 975 66 975 66 976 967 976 973 976 66 977 973 977 64 977 64 978 973 978 972 978 64 979 972 979 61 979 61 980 972 980 971 980 974 981 975 981 976 981 57 982 55 982 974 982 974 983 55 983 54 983 974 984 54 984 971 984 971 985 54 985 59 985 971 986 59 986 61 986 57 987 974 987 58 987 58 988 974 988 976 988 58 989 976 989 52 989 53 990 982 990 1054 990 53 991 1054 991 51 991 51 992 1054 992 1055 992 51 993 1055 993 56 993 56 994 1055 994 1056 994 1056 995 1057 995 56 995 56 996 1057 996 1058 996 56 997 1058 997 60 997 60 998 1058 998 1059 998 60 999 1059 999 62 999 62 1000 1059 1000 1060 1000 62 1001 1060 1001 63 1001 63 1002 1060 1002 1061 1002 63 1003 1061 1003 1062 1003 1062 1004 1061 1004 1063 1004 1062 1005 1063 1005 1064 1005 70 1006 68 1006 1062 1006 1062 1007 68 1007 65 1007 1062 1008 65 1008 63 1008 1065 1009 1066 1009 1067 1009 1067 1010 1066 1010 1068 1010 1068 1011 1069 1011 1067 1011 1067 1012 1069 1012 1070 1012 1067 1013 1070 1013 1071 1013 1071 1014 1070 1014 70 1014 1071 1015 70 1015 1072 1015 1072 1016 70 1016 1062 1016 1072 1017 1062 1017 1073 1017 1073 1018 1062 1018 1064 1018 1073 1019 1064 1019 1074 1019 1054 1020 982 1020 981 1020 1054 1021 981 1021 1055 1021 1055 1022 981 1022 1075 1022 1055 1023 1075 1023 1056 1023 978 1024 1076 1024 1077 1024 978 1025 1077 1025 979 1025 1076 1026 978 1026 1078 1026 1078 1027 978 1027 977 1027 1078 1028 977 1028 1079 1028 1079 1029 977 1029 393 1029 1079 1030 393 1030 308 1030 980 1031 1080 1031 981 1031 981 1032 1080 1032 1081 1032 981 1033 1081 1033 1075 1033 1077 1034 1082 1034 979 1034 979 1035 1082 1035 1083 1035 979 1036 1083 1036 980 1036 980 1037 1083 1037 1084 1037 980 1038 1084 1038 1080 1038 1085 1039 1060 1039 1059 1039 1056 1040 1075 1040 1057 1040 1057 1041 1075 1041 1085 1041 1057 1042 1085 1042 1058 1042 1058 1043 1085 1043 1059 1043 1086 1044 1087 1044 1088 1044 1088 1045 1074 1045 1086 1045 1086 1046 1074 1046 1064 1046 1086 1047 1064 1047 1063 1047 1089 1048 1090 1048 1091 1048 1091 1049 1090 1049 1092 1049 1091 1050 1092 1050 1093 1050 1094 1051 1095 1051 1096 1051 1077 1052 1097 1052 1082 1052 1082 1053 1097 1053 1098 1053 1082 1054 1098 1054 1083 1054 1083 1055 1098 1055 1099 1055 1083 1056 1099 1056 1084 1056 1100 1057 1081 1057 1101 1057 1101 1058 1081 1058 1080 1058 1101 1059 1080 1059 1094 1059 1094 1060 1080 1060 1084 1060 1094 1061 1084 1061 1095 1061 1095 1062 1084 1062 1099 1062 1095 1063 1099 1063 1096 1063 1060 1064 1085 1064 1100 1064 1100 1065 1085 1065 1075 1065 1100 1066 1075 1066 1081 1066 1089 1067 1102 1067 1090 1067 1090 1068 1102 1068 1087 1068 1090 1069 1087 1069 1103 1069 1103 1070 1087 1070 1086 1070 1103 1071 1086 1071 1061 1071 1061 1072 1086 1072 1063 1072 1096 1073 1093 1073 1094 1073 1094 1074 1093 1074 1092 1074 1094 1075 1092 1075 1101 1075 1101 1076 1092 1076 1090 1076 1101 1077 1090 1077 1100 1077 1100 1078 1090 1078 1103 1078 1100 1079 1103 1079 1060 1079 1060 1080 1103 1080 1061 1080 1074 1081 1104 1081 1073 1081 1105 1082 1013 1082 996 1082 1065 1083 1067 1083 965 1083 965 1084 1067 1084 1106 1084 1001 1085 1002 1085 1106 1085 1106 1086 1002 1086 966 1086 1106 1087 966 1087 965 1087 1077 1088 1107 1088 1097 1088 1097 1089 1107 1089 1108 1089 1097 1090 1108 1090 1098 1090 1098 1091 1108 1091 1109 1091 1098 1092 1109 1092 1099 1092 1109 1093 1110 1093 1099 1093 1099 1094 1110 1094 1111 1094 1099 1095 1111 1095 1096 1095 1096 1096 1111 1096 1112 1096 1096 1097 1112 1097 1093 1097 1091 1098 1113 1098 1089 1098 1089 1099 1113 1099 1114 1099 1089 1100 1114 1100 1102 1100 1102 1101 1114 1101 1087 1101 1087 1102 1114 1102 1115 1102 1087 1103 1115 1103 1088 1103 1073 1104 1104 1104 1072 1104 1072 1105 1104 1105 1116 1105 1072 1106 1116 1106 1071 1106 1117 1107 1118 1107 1119 1107 1119 1108 1118 1108 1120 1108 1119 1109 1120 1109 1121 1109 1121 1110 1120 1110 1122 1110 1121 1111 1122 1111 386 1111 1119 1112 1123 1112 1117 1112 1117 1113 1123 1113 1124 1113 1117 1114 1124 1114 1125 1114 1125 1115 1124 1115 1126 1115 1125 1116 1126 1116 1127 1116 1127 1117 1126 1117 1128 1117 1127 1118 1128 1118 1129 1118 1112 1119 1130 1119 1093 1119 1093 1120 1130 1120 1131 1120 1093 1121 1131 1121 1091 1121 1091 1122 1131 1122 1132 1122 1091 1123 1132 1123 1113 1123 1113 1124 1132 1124 1133 1124 1113 1125 1133 1125 1114 1125 1128 1126 1134 1126 1129 1126 1129 1127 1134 1127 1115 1127 1129 1128 1115 1128 1135 1128 1135 1129 1115 1129 1114 1129 1135 1130 1114 1130 1136 1130 1136 1131 1114 1131 1133 1131 1137 1132 1138 1132 1139 1132 1139 1133 1138 1133 1140 1133 1139 1134 1140 1134 1141 1134 1141 1135 1140 1135 1142 1135 1141 1136 1142 1136 1143 1136 1143 1137 1142 1137 1144 1137 1143 1138 1144 1138 1145 1138 1071 1139 1116 1139 1067 1139 1067 1140 1116 1140 1145 1140 1067 1141 1145 1141 1106 1141 1106 1142 1145 1142 1144 1142 1106 1143 1144 1143 1001 1143 1001 1144 1144 1144 1142 1144 1001 1145 1142 1145 995 1145 995 1146 1142 1146 1140 1146 995 1147 1140 1147 996 1147 996 1148 1140 1148 1138 1148 996 1149 1138 1149 1105 1149 1088 1150 1115 1150 1074 1150 1074 1151 1115 1151 1134 1151 1074 1152 1134 1152 1104 1152 1104 1153 1134 1153 1128 1153 1104 1154 1128 1154 1116 1154 1116 1155 1128 1155 1126 1155 1116 1156 1126 1156 1145 1156 1145 1157 1126 1157 1124 1157 1145 1158 1124 1158 1143 1158 1143 1159 1124 1159 1123 1159 1143 1160 1123 1160 1141 1160 1141 1161 1123 1161 1119 1161 1141 1162 1119 1162 1139 1162 1139 1163 1119 1163 1121 1163 1139 1164 1121 1164 1137 1164 1146 1165 1147 1165 1148 1165 1149 1166 1150 1166 1151 1166 1152 1167 1153 1167 1154 1167 1155 1168 1156 1168 1157 1168 1157 1169 1156 1169 1045 1169 1158 1170 1159 1170 1160 1170 1160 1171 1159 1171 1161 1171 1020 1172 1018 1172 1158 1172 1158 1173 1160 1173 1020 1173 1020 1174 1160 1174 1162 1174 1020 1175 1162 1175 1021 1175 1021 1176 1162 1176 1163 1176 1021 1177 1163 1177 1006 1177 1006 1178 1163 1178 1164 1178 1006 1179 1164 1179 1007 1179 1007 1180 1164 1180 1165 1180 1007 1181 1165 1181 1008 1181 1008 1182 1165 1182 1166 1182 1008 1183 1166 1183 1019 1183 1019 1184 1166 1184 1167 1184 1019 1185 1167 1185 999 1185 1032 1186 1146 1186 1030 1186 1030 1187 1146 1187 1148 1187 1030 1188 1148 1188 1028 1188 1028 1189 1148 1189 1168 1189 1028 1190 1168 1190 1048 1190 1048 1191 1168 1191 1169 1191 1170 1192 1050 1192 1169 1192 1169 1193 1050 1193 1049 1193 1169 1194 1049 1194 1048 1194 1045 1195 1044 1195 1157 1195 1157 1196 1044 1196 1043 1196 1157 1197 1043 1197 1171 1197 1171 1198 1043 1198 1047 1198 1171 1199 1047 1199 1170 1199 1170 1200 1047 1200 1046 1200 1170 1201 1046 1201 1050 1201 1161 1202 1152 1202 1160 1202 1160 1203 1152 1203 1154 1203 1160 1204 1154 1204 1162 1204 1162 1205 1154 1205 1172 1205 1162 1206 1172 1206 1163 1206 1163 1207 1172 1207 1173 1207 1163 1208 1173 1208 1164 1208 1164 1209 1173 1209 1174 1209 1164 1210 1174 1210 1165 1210 1165 1211 1174 1211 1175 1211 1165 1212 1175 1212 1166 1212 1166 1213 1175 1213 1151 1213 1166 1214 1151 1214 1167 1214 1167 1215 1151 1215 1150 1215 1153 1216 1155 1216 1154 1216 1154 1217 1155 1217 1157 1217 1154 1218 1157 1218 1172 1218 1172 1219 1157 1219 1171 1219 1172 1220 1171 1220 1173 1220 1173 1221 1171 1221 1170 1221 1173 1222 1170 1222 1174 1222 1174 1223 1170 1223 1169 1223 1174 1224 1169 1224 1175 1224 1175 1225 1169 1225 1168 1225 1175 1226 1168 1226 1151 1226 1151 1227 1168 1227 1148 1227 1151 1228 1148 1228 1149 1228 1149 1229 1148 1229 1147 1229 419 1230 391 1230 1176 1230 1118 1231 1117 1231 1177 1231 1076 1232 1178 1232 1077 1232 1077 1233 1178 1233 1107 1233 1107 1234 1178 1234 1108 1234 1108 1235 1178 1235 1179 1235 1108 1236 1179 1236 1109 1236 1180 1237 1111 1237 1110 1237 1111 1238 1180 1238 1112 1238 1112 1239 1180 1239 1181 1239 1112 1240 1181 1240 1130 1240 1131 1241 1182 1241 1132 1241 1132 1242 1182 1242 1133 1242 1130 1243 1181 1243 1131 1243 1131 1244 1181 1244 1183 1244 1131 1245 1183 1245 1182 1245 1182 1246 1183 1246 1184 1246 1182 1247 1184 1247 1133 1247 1117 1248 1125 1248 1177 1248 1177 1249 1125 1249 1127 1249 1177 1250 1127 1250 1185 1250 1185 1251 1127 1251 1129 1251 1185 1252 1129 1252 1186 1252 1186 1253 1129 1253 1135 1253 1186 1254 1135 1254 1184 1254 1184 1255 1135 1255 1136 1255 1184 1256 1136 1256 1133 1256 1187 1257 531 1257 553 1257 553 1258 552 1258 1187 1258 1187 1259 552 1259 550 1259 1187 1260 550 1260 548 1260 548 1261 546 1261 1187 1261 1187 1262 546 1262 544 1262 1187 1263 544 1263 542 1263 542 1264 540 1264 1187 1264 1187 1265 540 1265 538 1265 1187 1266 538 1266 1188 1266 1188 1267 538 1267 536 1267 1188 1268 536 1268 534 1268 534 1269 533 1269 1188 1269 1188 1270 533 1270 388 1270 1188 1271 388 1271 387 1271 1189 1272 468 1272 511 1272 511 1273 510 1273 1189 1273 1189 1274 510 1274 508 1274 1189 1275 508 1275 506 1275 1190 1276 504 1276 502 1276 502 1277 500 1277 1190 1277 1190 1278 500 1278 498 1278 1190 1279 498 1279 496 1279 441 1280 439 1280 1191 1280 1191 1281 439 1281 437 1281 437 1282 436 1282 1191 1282 1191 1283 436 1283 446 1283 1191 1284 446 1284 1176 1284 1176 1285 446 1285 421 1285 1176 1286 421 1286 419 1286 1192 1287 453 1287 455 1287 455 1288 457 1288 1192 1288 1192 1289 457 1289 459 1289 1192 1290 459 1290 1193 1290 459 1291 461 1291 1193 1291 1193 1292 461 1292 463 1292 1193 1293 463 1293 465 1293 1079 1294 308 1294 395 1294 395 1295 397 1295 1079 1295 1079 1296 397 1296 399 1296 1079 1297 399 1297 1194 1297 1194 1298 399 1298 401 1298 1194 1299 401 1299 403 1299 1076 1300 1078 1300 1178 1300 1178 1301 1078 1301 1195 1301 1178 1302 1195 1302 1179 1302 1179 1303 1195 1303 1196 1303 1179 1304 1196 1304 1197 1304 1197 1305 1196 1305 1198 1305 1197 1306 1198 1306 1199 1306 1199 1307 1198 1307 1200 1307 1199 1308 1200 1308 1201 1308 1201 1309 1200 1309 1202 1309 1201 1310 1202 1310 1203 1310 1203 1311 1202 1311 1204 1311 1203 1312 1204 1312 1190 1312 496 1313 494 1313 1190 1313 1190 1314 494 1314 492 1314 1190 1315 492 1315 490 1315 490 1316 489 1316 1190 1316 1190 1317 489 1317 514 1317 1190 1318 514 1318 516 1318 524 1319 526 1319 1187 1319 1187 1320 526 1320 529 1320 1187 1321 529 1321 531 1321 516 1322 518 1322 1190 1322 1190 1323 518 1323 520 1323 1190 1324 520 1324 1187 1324 1187 1325 520 1325 522 1325 1187 1326 522 1326 524 1326 1188 1327 1205 1327 1187 1327 1187 1328 1205 1328 1206 1328 1187 1329 1206 1329 1190 1329 1190 1330 1206 1330 1207 1330 1190 1331 1207 1331 1203 1331 484 1332 482 1332 1176 1332 391 1333 390 1333 1176 1333 1176 1334 390 1334 486 1334 1176 1335 486 1335 484 1335 482 1336 480 1336 1176 1336 1176 1337 480 1337 478 1337 1176 1338 478 1338 1189 1338 1189 1339 478 1339 476 1339 1189 1340 476 1340 474 1340 474 1341 472 1341 1189 1341 1189 1342 472 1342 470 1342 1189 1343 470 1343 468 1343 465 1344 466 1344 1193 1344 1193 1345 466 1345 434 1345 1193 1346 434 1346 432 1346 432 1347 430 1347 1193 1347 1193 1348 430 1348 428 1348 1193 1349 428 1349 1191 1349 1191 1350 428 1350 426 1350 1191 1351 426 1351 424 1351 424 1352 444 1352 1191 1352 1191 1353 444 1353 443 1353 1191 1354 443 1354 441 1354 1110 1355 1109 1355 1180 1355 1180 1356 1109 1356 1179 1356 1180 1357 1179 1357 1181 1357 1181 1358 1179 1358 1197 1358 1181 1359 1197 1359 1183 1359 1183 1360 1197 1360 1199 1360 1183 1361 1199 1361 1184 1361 1184 1362 1199 1362 1201 1362 1184 1363 1201 1363 1186 1363 1186 1364 1201 1364 1203 1364 1186 1365 1203 1365 1185 1365 1185 1366 1203 1366 1207 1366 1185 1367 1207 1367 1177 1367 1177 1368 1207 1368 1206 1368 1177 1369 1206 1369 1118 1369 1118 1370 1206 1370 1205 1370 1118 1371 1205 1371 1120 1371 1120 1372 1205 1372 1188 1372 1120 1373 1188 1373 1122 1373 1122 1374 1188 1374 387 1374 1122 1375 387 1375 386 1375 403 1376 405 1376 1194 1376 1194 1377 405 1377 407 1377 1194 1378 407 1378 408 1378 408 1379 411 1379 1194 1379 1194 1380 411 1380 413 1380 1194 1381 413 1381 1192 1381 1192 1382 413 1382 415 1382 1192 1383 415 1383 417 1383 417 1384 449 1384 1192 1384 1192 1385 449 1385 451 1385 1192 1386 451 1386 453 1386 1078 1387 1079 1387 1195 1387 1195 1388 1079 1388 1194 1388 1195 1389 1194 1389 1196 1389 1196 1390 1194 1390 1192 1390 1196 1391 1192 1391 1198 1391 1198 1392 1192 1392 1193 1392 1198 1393 1193 1393 1200 1393 1200 1394 1193 1394 1191 1394 1200 1395 1191 1395 1202 1395 1202 1396 1191 1396 1176 1396 1202 1397 1176 1397 1204 1397 1204 1398 1176 1398 1189 1398 1204 1399 1189 1399 1190 1399 1190 1400 1189 1400 506 1400 1190 1401 506 1401 504 1401 1208 1402 1209 1402 1210 1402 1209 1403 1208 1403 1211 1403 1211 1404 1208 1404 1212 1404 1211 1405 1212 1405 1213 1405 1213 1406 1212 1406 1214 1406 1213 1407 1214 1407 1215 1407 331 1408 1215 1408 332 1408 332 1409 1215 1409 1214 1409 332 1410 1214 1410 300 1410 300 1411 1214 1411 302 1411 302 1412 1214 1412 303 1412 303 1413 1214 1413 1212 1413 303 1414 1212 1414 297 1414 297 1415 1212 1415 298 1415 298 1416 1212 1416 1208 1416 298 1417 1208 1417 294 1417 294 1418 1208 1418 1210 1418 294 1419 1210 1419 295 1419 1216 1420 1014 1420 1217 1420 1217 1421 1014 1421 997 1421 1217 1422 997 1422 1218 1422 1218 1423 997 1423 1005 1423 1218 1424 1005 1424 1004 1424 970 1425 1016 1425 1219 1425 1219 1426 1016 1426 1015 1426 1219 1427 1015 1427 1220 1427 1220 1428 1015 1428 1014 1428 1220 1429 1014 1429 1216 1429 70 1430 1070 1430 71 1430 71 1431 1070 1431 1069 1431 71 1432 1069 1432 1052 1432 1052 1433 1069 1433 1068 1433 1052 1434 1068 1434 1053 1434 1053 1435 1068 1435 1066 1435 1053 1436 1066 1436 1051 1436 1051 1437 1066 1437 1065 1437 1051 1438 1065 1438 964 1438 964 1439 1065 1439 965 1439 1031 1440 1221 1440 1032 1440 1032 1441 1221 1441 1222 1441 1032 1442 1222 1442 1146 1442 1146 1443 1222 1443 1147 1443 1147 1444 1222 1444 1223 1444 1147 1445 1223 1445 1149 1445 1223 1446 1224 1446 1149 1446 1149 1447 1224 1447 1225 1447 1149 1448 1225 1448 1150 1448 1150 1449 1225 1449 1226 1449 1150 1450 1226 1450 1167 1450 1227 1451 998 1451 1228 1451 1228 1452 998 1452 999 1452 1228 1453 999 1453 1229 1453 1229 1454 999 1454 1167 1454 1229 1455 1167 1455 1230 1455 1230 1456 1167 1456 1226 1456 1027 1457 953 1457 1029 1457 1029 1458 953 1458 958 1458 1029 1459 958 1459 1031 1459 958 1460 1224 1460 1223 1460 1223 1461 1222 1461 958 1461 958 1462 1222 1462 1221 1462 958 1463 1221 1463 1031 1463 1229 1464 1230 1464 960 1464 960 1465 1230 1465 1226 1465 960 1466 1226 1466 958 1466 958 1467 1226 1467 1225 1467 958 1468 1225 1468 1224 1468 960 1469 962 1469 998 1469 998 1470 1227 1470 960 1470 960 1471 1227 1471 1228 1471 960 1472 1228 1472 1229 1472 987 1473 954 1473 1027 1473 1027 1474 954 1474 953 1474 1231 98 729 98 580 98 1231 98 580 98 1232 98 1232 98 580 98 579 98 1232 98 579 98 1233 98 1233 98 579 98 602 98 1233 98 602 98 1234 98 1234 98 602 98 601 98 1234 98 601 98 1235 98 1235 98 601 98 600 98 1235 98 600 98 1236 98 1236 98 600 98 587 98 1236 98 587 98 1237 98 556 1475 949 1475 557 1475 557 1475 949 1475 951 1475 623 1476 622 1476 1238 1476 1238 1477 622 1477 1239 1477 556 1478 555 1478 949 1478 949 1479 555 1479 947 1479 991 1480 377 1480 1240 1480 1240 1481 377 1481 376 1481 1241 1482 1242 1482 1243 1482 1243 1483 1242 1483 1244 1483 1243 1484 1244 1484 1245 1484 1245 1485 1244 1485 1246 1485 1245 1486 1246 1486 1247 1486 1247 1487 1246 1487 1248 1487 1249 1488 1250 1488 1251 1488 1251 1489 1250 1489 1252 1489 1253 1490 1254 1490 1255 1490 1255 1491 1254 1491 1249 1491 1255 1492 1249 1492 1256 1492 1256 1493 1249 1493 1251 1493 1248 1494 1257 1494 1247 1494 1247 1495 1257 1495 1258 1495 1247 1496 1258 1496 1259 1496 1259 1497 1258 1497 1260 1497 1259 1498 1260 1498 1250 1498 1250 1499 1260 1499 1261 1499 1250 1500 1261 1500 1252 1500 1252 1501 1261 1501 1262 1501 1252 1502 1262 1502 1263 1502 1264 1503 1265 1503 1266 1503 1266 1504 1265 1504 1267 1504 1266 1505 1267 1505 1268 1505 1268 1506 1267 1506 1269 1506 1268 1507 1269 1507 1241 1507 1241 1508 1269 1508 1270 1508 1241 1509 1270 1509 1242 1509 1264 1510 1271 1510 1265 1510 1265 1511 1271 1511 950 1511 1265 1512 950 1512 948 1512 952 1513 950 1513 1272 1513 1272 1514 950 1514 1271 1514 665 1515 1273 1515 667 1515 667 1516 1273 1516 1274 1516 1275 1517 1276 1517 1277 1517 1277 1518 1278 1518 1275 1518 1275 1519 1278 1519 1279 1519 1275 1520 1279 1520 1280 1520 1280 1521 1279 1521 1272 1521 1280 1522 1272 1522 1281 1522 1281 1523 1272 1523 1271 1523 1281 1524 1271 1524 1282 1524 1274 1525 1283 1525 667 1525 667 1526 1283 1526 1284 1526 667 1527 1284 1527 1276 1527 1276 1528 1284 1528 1285 1528 1276 1529 1285 1529 1277 1529 1286 1530 1287 1530 1288 1530 1286 1531 1288 1531 1289 1531 1289 1532 1288 1532 1290 1532 1289 1533 1290 1533 1291 1533 1291 1534 1290 1534 884 1534 1291 1535 884 1535 885 1535 730 1536 729 1536 1292 1536 1292 1537 729 1537 1231 1537 1292 1538 1231 1538 1293 1538 1292 1539 1293 1539 1294 1539 1295 1540 1296 1540 1297 1540 731 1541 1298 1541 735 1541 735 1542 1298 1542 1299 1542 735 1543 1299 1543 734 1543 734 1544 1299 1544 1300 1544 734 1545 1300 1545 732 1545 1301 1546 1302 1546 1303 1546 1297 1547 1304 1547 1305 1547 1305 1548 1304 1548 1306 1548 1305 1549 1306 1549 1307 1549 1308 1550 1296 1550 1309 1550 1309 1551 1296 1551 1295 1551 1309 1552 1295 1552 1294 1552 1308 1553 1310 1553 1296 1553 1296 1554 1310 1554 1311 1554 1296 1555 1311 1555 1297 1555 1297 1556 1311 1556 1301 1556 1297 1557 1301 1557 1304 1557 1304 1558 1301 1558 1303 1558 1304 1559 1303 1559 1306 1559 1307 1560 1300 1560 1305 1560 1305 1561 1300 1561 1299 1561 1305 1562 1299 1562 1297 1562 1297 1563 1299 1563 1298 1563 1297 1564 1298 1564 1295 1564 1295 1565 1298 1565 731 1565 1295 1566 731 1566 1294 1566 1294 1567 731 1567 730 1567 1294 1568 730 1568 1292 1568 720 98 732 98 1300 98 1302 1569 722 1569 1303 1569 1303 1570 722 1570 718 1570 1303 1571 718 1571 1306 1571 1306 1572 718 1572 720 1572 1306 98 720 98 1307 98 1307 1573 720 1573 1300 1573 1312 1574 1313 1574 1314 1574 926 1575 930 1575 1315 1575 1315 1576 930 1576 1316 1576 1315 1577 1316 1577 1317 1577 1313 1578 1312 1578 1316 1578 1316 1579 1312 1579 1318 1579 1316 1580 1318 1580 1317 1580 930 1581 933 1581 1316 1581 1316 1582 933 1582 1319 1582 1316 1583 1319 1583 1313 1583 1313 1584 1319 1584 1320 1584 1313 1585 1320 1585 1314 1585 1314 1586 1320 1586 1321 1586 933 1587 935 1587 1319 1587 1319 1588 935 1588 1322 1588 1319 1589 1322 1589 1320 1589 1320 1590 1322 1590 1323 1590 1320 1591 1323 1591 1321 1591 1321 1592 1323 1592 1237 1592 1324 1593 1325 1593 935 1593 935 1594 1325 1594 1322 1594 1326 1595 1323 1595 1327 1595 1327 1596 1323 1596 1322 1596 1327 1597 1322 1597 1328 1597 1328 1598 1322 1598 1325 1598 1232 1599 1233 1599 1329 1599 1329 1600 1233 1600 1234 1600 1329 1601 1234 1601 1326 1601 1326 1602 1234 1602 1235 1602 1326 1603 1235 1603 1323 1603 1323 1604 1235 1604 1236 1604 1323 1605 1236 1605 1237 1605 1329 1606 1308 1606 1309 1606 1231 1607 1232 1607 1293 1607 1293 1608 1232 1608 1329 1608 1293 1609 1329 1609 1294 1609 1294 1610 1329 1610 1309 1610 1329 1611 1326 1611 1308 1611 1308 1612 1326 1612 1330 1612 1308 1613 1330 1613 1331 1613 1331 1614 1330 1614 1332 1614 1332 1615 1330 1615 1333 1615 1333 1616 1330 1616 1334 1616 1333 1617 1334 1617 1335 1617 1335 1618 1334 1618 1336 1618 1335 1619 1336 1619 1337 1619 1324 1620 1336 1620 1325 1620 1325 1621 1336 1621 1334 1621 1325 1622 1334 1622 1328 1622 1328 1623 1334 1623 1330 1623 1328 1624 1330 1624 1327 1624 1327 1625 1330 1625 1326 1625 650 1626 649 1626 1338 1626 1339 1627 651 1627 650 1627 650 1628 1338 1628 1339 1628 1339 1629 1338 1629 883 1629 1339 1630 883 1630 882 1630 622 1631 624 1631 1340 1631 1340 1632 624 1632 626 1632 1340 1633 626 1633 1341 1633 1341 1634 626 1634 627 1634 1342 1635 1343 1635 1344 1635 1344 1636 1343 1636 1345 1636 1345 1637 1346 1637 1344 1637 1344 1638 1346 1638 1347 1638 1344 1639 1347 1639 1348 1639 1348 1640 1347 1640 1349 1640 1350 1641 1238 1641 1239 1641 1344 1642 1351 1642 1342 1642 1342 1643 1351 1643 1350 1643 1342 1644 1350 1644 1352 1644 1352 1645 1350 1645 1239 1645 1353 1646 1354 1646 1355 1646 1356 1647 1357 1647 1358 1647 1358 1648 1357 1648 1359 1648 1358 1649 1359 1649 1360 1649 1361 1650 1362 1650 1363 1650 1363 1651 1362 1651 1358 1651 1363 1652 1358 1652 1364 1652 1364 1653 1358 1653 1360 1653 1361 1654 1353 1654 1362 1654 1362 1655 1353 1655 1355 1655 1362 1656 1355 1656 1365 1656 1365 1657 1355 1657 1366 1657 1365 1658 1366 1658 1367 1658 1355 1659 1368 1659 1369 1659 1370 1660 1371 1660 1366 1660 1370 1661 1366 1661 1372 1661 1355 1662 1369 1662 1366 1662 1366 1663 1369 1663 1373 1663 1366 1664 1373 1664 1372 1664 1371 1665 1374 1665 1366 1665 1366 1666 1374 1666 1375 1666 1366 1667 1375 1667 1376 1667 1376 1668 1375 1668 1377 1668 1376 1669 1377 1669 1378 1669 1378 1670 1377 1670 1379 1670 1378 1671 1379 1671 1380 1671 1356 1672 1358 1672 1381 1672 1356 1673 1381 1673 1382 1673 1382 1674 1381 1674 918 1674 1382 1675 918 1675 920 1675 1383 1676 1384 1676 1385 1676 1385 1677 1384 1677 1386 1677 1385 1678 1386 1678 1387 1678 1387 1679 1386 1679 1388 1679 888 1680 887 1680 1386 1680 1386 1681 887 1681 1389 1681 1386 1682 1389 1682 1388 1682 1390 1683 1391 1683 1392 1683 1392 1684 1391 1684 1393 1684 1392 1685 1393 1685 1394 1685 1395 1686 1396 1686 1397 1686 1394 1687 1398 1687 1392 1687 1392 1688 1398 1688 1395 1688 1392 1689 1395 1689 1397 1689 1399 1690 1400 1690 1392 1690 1392 1691 1400 1691 1401 1691 1392 1692 1401 1692 1390 1692 1392 1693 1402 1693 1399 1693 1399 1694 1402 1694 1403 1694 1399 1695 1403 1695 1404 1695 1404 1696 1403 1696 1405 1696 1406 1697 1407 1697 1408 1697 1408 1698 1407 1698 1409 1698 1408 1699 1409 1699 1385 1699 1409 1700 1410 1700 1385 1700 1385 1701 1410 1701 1411 1701 1385 1702 1411 1702 1383 1702 1383 1703 1411 1703 1412 1703 1413 1704 1414 1704 1412 1704 1412 1705 1414 1705 1415 1705 1415 1706 1416 1706 1412 1706 1412 1707 1416 1707 1417 1707 1412 1708 1417 1708 1418 1708 1418 1709 1419 1709 1412 1709 1412 1710 1419 1710 1420 1710 1412 1711 1420 1711 1383 1711 1421 1712 1422 1712 1405 1712 1405 1713 1422 1713 1423 1713 1405 1714 1423 1714 1404 1714 1421 1715 1424 1715 1422 1715 1422 1716 1424 1716 1425 1716 1422 1717 1425 1717 1426 1717 1426 1718 1425 1718 1427 1718 1426 1719 1427 1719 1409 1719 1409 1720 1427 1720 1428 1720 1409 1721 1428 1721 1410 1721 738 1722 737 1722 1429 1722 1429 1723 737 1723 1430 1723 1429 1724 1430 1724 1431 1724 1431 1725 1430 1725 1399 1725 1399 1726 1430 1726 1432 1726 1399 1727 1432 1727 1400 1727 1433 1728 1434 1728 1435 1728 1435 1729 1434 1729 1436 1729 1435 1730 1436 1730 1437 1730 1438 1731 1439 1731 755 1731 755 1732 1439 1732 1440 1732 755 1733 1440 1733 756 1733 756 1734 1440 1734 1435 1734 756 1735 1435 1735 1441 1735 1441 1736 1435 1736 1437 1736 1442 1737 1443 1737 1444 1737 1444 1738 1445 1738 1442 1738 1442 1739 1445 1739 1446 1739 1442 1740 1446 1740 1447 1740 1447 1741 1446 1741 1448 1741 1447 1742 1448 1742 1438 1742 1438 1743 1448 1743 1449 1743 1438 1744 1449 1744 1439 1744 1450 1745 1451 1745 1452 1745 1452 1746 1451 1746 771 1746 1453 1747 1454 1747 1455 1747 1450 1748 1456 1748 1451 1748 1451 1749 1456 1749 1453 1749 1451 1750 1453 1750 1455 1750 771 1751 1451 1751 769 1751 769 1752 1451 1752 1457 1752 769 1753 1457 1753 1458 1753 1443 1754 1442 1754 1458 1754 1458 1755 1442 1755 1459 1755 1458 1756 1459 1756 769 1756 790 1757 1460 1757 1461 1757 1461 1758 1286 1758 1289 1758 1462 1759 956 1759 1463 1759 1463 1760 956 1760 955 1760 1463 1761 955 1761 1464 1761 1464 1762 955 1762 1465 1762 1466 1763 1467 1763 1468 1763 1468 1764 1467 1764 1469 1764 1468 1765 1469 1765 1470 1765 1470 1766 1469 1766 1471 1766 790 1767 1461 1767 885 1767 885 1768 1461 1768 1289 1768 885 1769 1289 1769 1291 1769 955 1770 1472 1770 1465 1770 1465 1771 1472 1771 1473 1771 1465 1772 1473 1772 1468 1772 1468 1773 1473 1773 1474 1773 1468 1774 1474 1774 1466 1774 781 1775 780 1775 1475 1775 1475 1776 1476 1776 781 1776 781 1777 1476 1777 1470 1777 781 1778 1470 1778 790 1778 790 1779 1470 1779 1471 1779 790 1780 1471 1780 1460 1780 1477 1781 1478 1781 1479 1781 1480 1782 1481 1782 1478 1782 939 1783 938 1783 1481 1783 1479 1784 1482 1784 1483 1784 1483 1785 1482 1785 1484 1785 1483 1786 1484 1786 1485 1786 1485 1787 1484 1787 1486 1787 1479 1788 1483 1788 1477 1788 1477 1789 1483 1789 1485 1789 1477 1790 1485 1790 1487 1790 1487 1791 1485 1791 1488 1791 1487 1792 1488 1792 1489 1792 1489 1793 1488 1793 1490 1793 1489 1794 1490 1794 1491 1794 1491 1795 1490 1795 1492 1795 1491 1796 1492 1796 1493 1796 1486 1797 1494 1797 1485 1797 1485 1798 1494 1798 1495 1798 1485 1799 1495 1799 1488 1799 1488 1800 1495 1800 1496 1800 1488 1801 1496 1801 1490 1801 1490 1802 1496 1802 1497 1802 1490 1803 1497 1803 1492 1803 1492 1804 1497 1804 780 1804 780 1805 782 1805 1492 1805 1492 1806 782 1806 776 1806 1492 1807 776 1807 1493 1807 1493 1808 776 1808 778 1808 1493 1809 778 1809 779 1809 1478 1810 1477 1810 1480 1810 1480 1811 1477 1811 1487 1811 1480 1812 1487 1812 1498 1812 1498 1813 1487 1813 1489 1813 1498 1814 1489 1814 1499 1814 1499 1815 1489 1815 1491 1815 1499 1816 1491 1816 1500 1816 1500 1817 1491 1817 1493 1817 1500 1818 1493 1818 1501 1818 1501 1819 1493 1819 779 1819 1501 1820 779 1820 773 1820 1481 1821 1480 1821 939 1821 939 1822 1480 1822 1498 1822 939 1823 1498 1823 942 1823 942 1824 1498 1824 1499 1824 942 1825 1499 1825 943 1825 943 1826 1499 1826 1500 1826 943 1827 1500 1827 940 1827 940 1828 1500 1828 1501 1828 940 1829 1501 1829 941 1829 941 1830 1501 1830 773 1830 941 1831 773 1831 772 1831 938 1832 1502 1832 1503 1832 938 1833 1503 1833 1481 1833 1481 1834 1503 1834 1504 1834 1481 1835 1504 1835 1478 1835 1478 1836 1504 1836 1505 1836 1478 1837 1505 1837 1479 1837 1479 1838 1505 1838 1506 1838 1479 1839 1506 1839 1482 1839 1507 1840 1506 1840 1508 1840 1508 1841 1506 1841 1505 1841 1508 1842 1505 1842 1509 1842 1509 1843 1505 1843 1504 1843 1509 1844 1504 1844 1510 1844 1510 1845 1504 1845 1503 1845 1510 1846 1503 1846 1511 1846 1511 1847 1503 1847 1502 1847 1512 1848 1507 1848 1513 1848 1513 1849 1507 1849 1508 1849 1513 1850 1508 1850 1514 1850 1514 1851 1508 1851 1509 1851 1514 1852 1509 1852 1515 1852 1515 1853 1509 1853 1510 1853 1515 1854 1510 1854 1516 1854 1516 1855 1510 1855 1511 1855 1517 1856 1512 1856 1518 1856 1518 1857 1512 1857 1513 1857 1518 1858 1513 1858 1519 1858 1519 1859 1513 1859 1514 1859 1519 1860 1514 1860 1520 1860 1520 1861 1514 1861 1515 1861 1520 1862 1515 1862 683 1862 683 1863 1515 1863 1516 1863 1521 1864 1522 1864 1523 1864 1524 1865 1523 1865 1525 1865 1526 1866 1522 1866 1527 1866 1527 1867 1522 1867 1528 1867 1527 1868 1528 1868 1529 1868 711 1869 1525 1869 1530 1869 1530 1870 1525 1870 1523 1870 1530 1871 1523 1871 1531 1871 1531 1872 1523 1872 1522 1872 1531 1873 1522 1873 1532 1873 1532 1874 1522 1874 1526 1874 685 1875 692 1875 1533 1875 691 1876 690 1876 1534 1876 689 1877 688 1877 1535 1877 694 1878 707 1878 1536 1878 706 1879 705 1879 1537 1879 1526 1880 1538 1880 1532 1880 1532 1881 1538 1881 1539 1881 1532 1882 1539 1882 1531 1882 1531 1883 1539 1883 1540 1883 1531 1884 1540 1884 1530 1884 1530 1885 1540 1885 1541 1885 1530 1886 1541 1886 711 1886 704 1887 703 1887 1541 1887 1541 1888 703 1888 712 1888 1541 1889 712 1889 711 1889 708 1890 704 1890 1542 1890 1542 1891 704 1891 1541 1891 1542 1892 1541 1892 1543 1892 1543 1893 1541 1893 1540 1893 1543 1894 1540 1894 1544 1894 1544 1895 1540 1895 1539 1895 1544 1896 1539 1896 1545 1896 1545 1897 1539 1897 1538 1897 705 1898 708 1898 1537 1898 1537 1899 708 1899 1542 1899 1537 1900 1542 1900 1546 1900 1546 1901 1542 1901 1543 1901 1546 1902 1543 1902 1547 1902 1547 1903 1543 1903 1544 1903 1547 1904 1544 1904 1548 1904 1548 1905 1544 1905 1545 1905 707 1906 706 1906 1536 1906 1536 1907 706 1907 1537 1907 1536 1908 1537 1908 1549 1908 1549 1909 1537 1909 1546 1909 1549 1910 1546 1910 1550 1910 1550 1911 1546 1911 1547 1911 1550 1912 1547 1912 1551 1912 1551 1913 1547 1913 1548 1913 695 1914 694 1914 1552 1914 1552 1915 694 1915 1536 1915 1552 1916 1536 1916 1553 1916 1553 1917 1536 1917 1549 1917 1553 1918 1549 1918 1554 1918 1554 1919 1549 1919 1550 1919 1554 1920 1550 1920 1555 1920 1555 1921 1550 1921 1551 1921 698 1922 697 1922 1552 1922 1552 1923 697 1923 696 1923 1552 1924 696 1924 695 1924 1556 1925 1557 1925 1558 1925 1558 1926 1557 1926 1559 1926 1558 1927 1559 1927 1560 1927 1560 1928 1559 1928 1561 1928 1560 1929 1561 1929 1562 1929 1562 1930 1561 1930 1563 1930 1555 1931 1556 1931 1554 1931 1554 1932 1556 1932 1558 1932 1554 1933 1558 1933 1553 1933 1553 1934 1558 1934 1560 1934 1553 1935 1560 1935 1552 1935 1552 1936 1560 1936 1562 1936 1552 1937 1562 1937 698 1937 698 1938 1562 1938 1563 1938 701 1939 700 1939 1563 1939 1563 1940 700 1940 699 1940 1563 1941 699 1941 698 1941 688 1942 701 1942 1535 1942 1535 1943 701 1943 1563 1943 1535 1944 1563 1944 1564 1944 1564 1945 1563 1945 1561 1945 1564 1946 1561 1946 1565 1946 1565 1947 1561 1947 1559 1947 1565 1948 1559 1948 1566 1948 1566 1949 1559 1949 1557 1949 690 1950 689 1950 1534 1950 1534 1951 689 1951 1535 1951 1534 1952 1535 1952 1567 1952 1567 1953 1535 1953 1564 1953 1567 1954 1564 1954 1568 1954 1568 1955 1564 1955 1565 1955 1568 1956 1565 1956 1569 1956 1569 1957 1565 1957 1566 1957 692 1958 691 1958 1533 1958 1533 1959 691 1959 1534 1959 1533 1960 1534 1960 1570 1960 1570 1961 1534 1961 1567 1961 1570 1962 1567 1962 1571 1962 1571 1963 1567 1963 1568 1963 1571 1964 1568 1964 1572 1964 1572 1965 1568 1965 1569 1965 684 1966 685 1966 1573 1966 1573 1967 685 1967 1533 1967 1573 1968 1533 1968 1574 1968 1574 1969 1533 1969 1570 1969 1574 1970 1570 1970 1575 1970 1575 1971 1570 1971 1571 1971 1575 1972 1571 1972 1576 1972 1576 1973 1571 1973 1572 1973 683 1974 684 1974 1520 1974 1520 1975 684 1975 1573 1975 1520 1976 1573 1976 1519 1976 1519 1977 1573 1977 1574 1977 1519 1978 1574 1978 1518 1978 1518 1979 1574 1979 1575 1979 1518 1980 1575 1980 1517 1980 1517 1981 1575 1981 1576 1981 1577 1982 1578 1982 1579 1982 1577 1983 1579 1983 1580 1983 1580 1984 1579 1984 1581 1984 1580 1985 1581 1985 1582 1985 1582 1986 1581 1986 1583 1986 1582 1987 1583 1987 1584 1987 1584 1988 1583 1988 1585 1988 1584 1989 1585 1989 1586 1989 1523 1990 1524 1990 1587 1990 1524 1991 1525 1991 1588 1991 1522 1992 1521 1992 1589 1992 1589 1993 1521 1993 1523 1993 1590 1994 1528 1994 1522 1994 1528 1995 1590 1995 1529 1995 1524 1996 1588 1996 1587 1996 1587 1997 1588 1997 1591 1997 1587 1998 1591 1998 1592 1998 1592 1999 1591 1999 1593 1999 1592 2000 1593 2000 1594 2000 1594 2001 1593 2001 1595 2001 1594 2002 1595 2002 1596 2002 1596 2003 1595 2003 1577 2003 1596 2004 1577 2004 1580 2004 1523 2005 1587 2005 1589 2005 1589 2006 1587 2006 1592 2006 1589 2007 1592 2007 1597 2007 1597 2008 1592 2008 1594 2008 1597 2009 1594 2009 1598 2009 1598 2010 1594 2010 1596 2010 1598 2011 1596 2011 1599 2011 1599 2012 1596 2012 1580 2012 1599 2013 1580 2013 1582 2013 1522 2014 1589 2014 1590 2014 1590 2015 1589 2015 1597 2015 1590 2016 1597 2016 1600 2016 1600 2017 1597 2017 1598 2017 1600 2018 1598 2018 1601 2018 1601 2019 1598 2019 1599 2019 1601 2020 1599 2020 1602 2020 1602 2021 1599 2021 1582 2021 1602 2022 1582 2022 1584 2022 1529 2023 1590 2023 1603 2023 1603 2024 1590 2024 1600 2024 1603 2025 1600 2025 1604 2025 1604 2026 1600 2026 1601 2026 1604 2027 1601 2027 1605 2027 1605 2028 1601 2028 1602 2028 1605 2029 1602 2029 1606 2029 1606 2030 1602 2030 1584 2030 1606 2031 1584 2031 1586 2031 1348 2032 1607 2032 1344 2032 1344 2033 1607 2033 1608 2033 1344 2034 1608 2034 1351 2034 613 2035 605 2035 1609 2035 1609 2036 605 2036 803 2036 1609 2037 803 2037 1610 2037 1610 2038 803 2038 802 2038 1610 2039 802 2039 1611 2039 1611 2040 802 2040 799 2040 1611 2041 799 2041 1612 2041 1612 2042 799 2042 794 2042 1612 2043 794 2043 1613 2043 609 2044 613 2044 1614 2044 1614 2045 613 2045 1609 2045 1614 2046 1609 2046 1615 2046 1615 2047 1609 2047 1610 2047 1615 2048 1610 2048 1616 2048 1616 2049 1610 2049 1611 2049 1616 2050 1611 2050 1617 2050 1617 2051 1611 2051 1612 2051 1617 2052 1612 2052 1618 2052 1618 2053 1612 2053 1613 2053 607 2054 609 2054 1619 2054 1619 2055 609 2055 1614 2055 1619 2056 1614 2056 1620 2056 1620 2057 1614 2057 1615 2057 1620 2058 1615 2058 1621 2058 1621 2059 1615 2059 1616 2059 1621 2060 1616 2060 1622 2060 1622 2061 1616 2061 1617 2061 1622 2062 1617 2062 1623 2062 1623 2063 1617 2063 1618 2063 1624 2064 1625 2064 1626 2064 1626 2065 1625 2065 1627 2065 1626 2066 1627 2066 1628 2066 1628 2067 1627 2067 1629 2067 1628 2068 1629 2068 1630 2068 1630 2069 1629 2069 1631 2069 1630 2070 1631 2070 1632 2070 1632 2071 1631 2071 1633 2071 1632 2072 1633 2072 608 2072 608 2073 1633 2073 610 2073 1623 2074 1624 2074 1622 2074 1622 2075 1624 2075 1626 2075 1622 2076 1626 2076 1621 2076 1621 2077 1626 2077 1628 2077 1621 2078 1628 2078 1620 2078 1620 2079 1628 2079 1630 2079 1620 2080 1630 2080 1619 2080 1619 2081 1630 2081 1632 2081 1619 2082 1632 2082 607 2082 607 2083 1632 2083 608 2083 612 2084 611 2084 1634 2084 1634 2085 611 2085 1635 2085 1634 2086 1635 2086 1636 2086 1636 2087 1635 2087 1637 2087 1636 2088 1637 2088 1638 2088 1638 2089 1637 2089 1639 2089 1639 2090 1637 2090 1640 2090 1639 2091 1640 2091 1641 2091 1642 2092 1643 2092 1644 2092 1644 2093 1643 2093 1641 2093 1641 2094 1640 2094 1645 2094 1641 2095 1645 2095 1644 2095 1642 2096 1644 2096 1646 2096 1646 2097 1644 2097 1647 2097 1646 2098 1647 2098 1648 2098 1648 2099 1647 2099 1649 2099 1648 2100 1649 2100 1650 2100 1650 2101 1649 2101 1651 2101 1650 2102 1651 2102 1652 2102 1653 2103 1654 2103 1655 2103 1655 2104 1656 2104 1653 2104 1653 2105 1656 2105 1657 2105 1653 2106 1657 2106 1658 2106 1627 2107 1625 2107 1659 2107 611 2108 610 2108 1635 2108 1635 2109 610 2109 1633 2109 1635 2110 1633 2110 1637 2110 1637 2111 1633 2111 1631 2111 1637 2112 1631 2112 1640 2112 1640 2113 1631 2113 1629 2113 1640 2114 1629 2114 1645 2114 1645 2115 1629 2115 1627 2115 1627 2116 1659 2116 1645 2116 1645 2117 1659 2117 1660 2117 1645 2118 1660 2118 1644 2118 1644 2119 1660 2119 1661 2119 1644 2120 1661 2120 1647 2120 1647 2121 1661 2121 1662 2121 1647 2122 1662 2122 1649 2122 1649 2123 1662 2123 1658 2123 1649 2124 1658 2124 1651 2124 1651 2125 1658 2125 1657 2125 1651 2126 1657 2126 1652 2126 1663 2127 1664 2127 1653 2127 1653 2128 1664 2128 1654 2128 1663 2129 370 2129 1664 2129 1664 2130 370 2130 369 2130 1665 2131 1345 2131 1343 2131 1239 2132 622 2132 1352 2132 1352 2133 622 2133 1340 2133 1352 2134 1340 2134 1342 2134 1342 2135 1340 2135 1341 2135 1342 2136 1341 2136 1343 2136 1343 2137 1341 2137 627 2137 1343 2138 627 2138 1665 2138 1666 2139 1667 2139 1668 2139 1668 2140 1667 2140 1669 2140 1668 2141 1669 2141 1670 2141 1671 2142 1667 2142 1672 2142 1672 2143 1667 2143 1666 2143 1672 2144 1666 2144 1673 2144 1674 2145 1675 2145 1669 2145 1669 2146 1675 2146 1676 2146 1669 2147 1676 2147 1670 2147 1674 2148 1669 2148 1677 2148 1677 2149 1669 2149 1667 2149 1677 2150 1667 2150 1678 2150 1678 2151 1667 2151 1671 2151 1678 2152 1671 2152 1679 2152 1679 2153 1680 2153 1678 2153 1678 2154 1680 2154 1681 2154 1678 2155 1681 2155 1677 2155 1677 2156 1681 2156 1682 2156 1677 2157 1682 2157 1674 2157 1674 2158 1682 2158 1683 2158 1674 2159 1683 2159 1684 2159 1685 2160 1676 2160 1686 2160 1686 2161 1676 2161 1675 2161 1686 2162 1675 2162 1687 2162 1687 2163 1675 2163 1674 2163 1687 2164 1674 2164 1688 2164 1688 2165 1674 2165 1684 2165 1688 2166 1684 2166 1689 2166 1690 2167 1691 2167 1692 2167 1693 2168 1694 2168 1695 2168 1695 2169 1694 2169 1696 2169 1697 2170 1673 2170 1698 2170 1698 2171 1673 2171 1699 2171 1699 2172 1700 2172 1698 2172 1698 2173 1700 2173 1701 2173 1698 2174 1701 2174 1692 2174 1692 2175 1701 2175 1702 2175 1692 2176 1702 2176 1690 2176 1703 2177 1697 2177 1704 2177 1704 2178 1697 2178 1698 2178 1704 2179 1698 2179 1705 2179 1705 2180 1698 2180 1692 2180 1706 2181 1705 2181 1707 2181 1707 2182 1705 2182 1692 2182 1707 2183 1692 2183 1694 2183 1694 2184 1692 2184 1691 2184 1694 2185 1691 2185 1696 2185 1708 2186 1703 2186 1709 2186 1709 2187 1703 2187 1704 2187 1709 2188 1704 2188 1710 2188 1710 2189 1704 2189 1705 2189 1710 2190 1705 2190 1711 2190 1711 2191 1705 2191 1706 2191 1706 2192 1712 2192 1711 2192 1711 2193 1712 2193 1713 2193 1711 2194 1713 2194 1710 2194 1714 2195 1708 2195 1713 2195 1713 2196 1708 2196 1709 2196 1713 2197 1709 2197 1710 2197 1715 2198 1714 2198 1716 2198 1716 2199 1714 2199 1713 2199 1716 2200 1713 2200 1717 2200 1717 2201 1713 2201 1712 2201 1718 2202 1715 2202 1719 2202 1719 2203 1715 2203 1716 2203 1719 2204 1716 2204 1720 2204 1720 2205 1716 2205 1717 2205 1721 2206 1722 2206 1723 2206 1724 2207 1725 2207 1726 2207 1723 2208 1722 2208 1726 2208 1726 2209 1722 2209 1727 2209 1726 2210 1727 2210 1724 2210 1728 2211 1729 2211 1723 2211 1723 2212 1729 2212 1730 2212 1723 2213 1730 2213 1721 2213 1726 2214 1718 2214 1723 2214 1723 2215 1718 2215 1719 2215 1723 2216 1719 2216 1728 2216 1728 2217 1719 2217 1720 2217 1731 2218 1732 2218 1733 2218 1734 2219 1729 2219 1735 2219 1734 2220 1735 2220 1736 2220 1727 2221 1722 2221 1737 2221 1737 2222 1722 2222 1721 2222 1737 2223 1721 2223 1734 2223 1734 2224 1721 2224 1730 2224 1734 2225 1730 2225 1729 2225 1738 2226 1725 2226 1737 2226 1737 2227 1725 2227 1724 2227 1737 2228 1724 2228 1727 2228 1739 2229 1740 2229 1741 2229 1741 2230 1740 2230 1736 2230 1741 2231 1736 2231 1742 2231 1742 2232 1736 2232 1735 2232 1740 2233 1731 2233 1736 2233 1736 2234 1731 2234 1733 2234 1736 2235 1733 2235 1734 2235 1734 2236 1733 2236 1743 2236 1734 2237 1743 2237 1737 2237 1737 2238 1743 2238 1744 2238 1737 2239 1744 2239 1738 2239 1738 2240 1744 2240 1745 2240 1732 2241 1746 2241 1733 2241 1733 2242 1746 2242 1747 2242 1733 2243 1747 2243 1743 2243 1743 2244 1747 2244 1748 2244 1743 2245 1748 2245 1744 2245 1744 2246 1748 2246 1749 2246 1744 2247 1749 2247 1745 2247 1745 2248 1749 2248 1750 2248 1746 2249 1751 2249 1747 2249 1747 2250 1751 2250 1752 2250 1747 2251 1752 2251 1748 2251 1748 2252 1752 2252 1753 2252 1748 2253 1753 2253 1749 2253 1749 2254 1753 2254 1754 2254 1749 2255 1754 2255 1750 2255 1750 2256 1754 2256 1755 2256 638 2257 651 2257 1339 2257 638 2258 1339 2258 1756 2258 1756 2259 1339 2259 882 2259 1756 2260 882 2260 1757 2260 969 2261 1758 2261 1759 2261 969 2262 1759 2262 968 2262 968 2263 1759 2263 364 2263 968 2264 364 2264 366 2264 1760 2265 1761 2265 1762 2265 1763 2266 1764 2266 1762 2266 1763 2267 1762 2267 1765 2267 1760 2268 1762 2268 1766 2268 1767 2269 1768 2269 1769 2269 1767 2270 1769 2270 1770 2270 1769 2271 1771 2271 1770 2271 1770 2272 1771 2272 1772 2272 1770 2273 1772 2273 1773 2273 1773 2274 1772 2274 1774 2274 1773 2275 1774 2275 1764 2275 1764 2276 1774 2276 1775 2276 1764 2277 1775 2277 1762 2277 1762 2278 1775 2278 1776 2278 1762 2279 1776 2279 1766 2279 1768 2280 1767 2280 1777 2280 1777 2281 1767 2281 1778 2281 1777 2282 1778 2282 1302 2282 1302 2283 1778 2283 1779 2283 1302 2284 1779 2284 722 2284 722 2285 1779 2285 1780 2285 722 2286 1780 2286 725 2286 725 2287 1780 2287 1781 2287 725 2288 1781 2288 723 2288 832 2289 833 2289 1782 2289 832 2290 1782 2290 831 2290 836 2291 825 2291 1782 2291 1782 2292 825 2292 824 2292 1782 2293 824 2293 831 2293 1740 2294 1739 2294 1783 2294 251 2295 1751 2295 1746 2295 1740 2296 1783 2296 1731 2296 1731 2297 1783 2297 1784 2297 1731 2298 1784 2298 1732 2298 1732 2299 1784 2299 1785 2299 1732 2300 1785 2300 1746 2300 1746 2301 1785 2301 1786 2301 1746 2302 1786 2302 251 2302 850 2303 851 2303 1787 2303 1788 2304 1789 2304 1790 2304 1791 2305 574 2305 573 2305 578 2306 850 2306 573 2306 573 2307 850 2307 1787 2307 573 2308 1787 2308 1791 2308 1791 2309 1787 2309 1792 2309 851 2310 852 2310 1787 2310 1787 2311 852 2311 1788 2311 1787 2312 1788 2312 1792 2312 1792 2313 1788 2313 1790 2313 847 2314 1789 2314 848 2314 848 2315 1789 2315 1788 2315 848 2316 1788 2316 849 2316 849 2317 1788 2317 852 2317 1793 2318 1794 2318 576 2318 576 2319 1794 2319 577 2319 1795 2320 1796 2320 1797 2320 1797 2321 1798 2321 1795 2321 1795 2322 1798 2322 1799 2322 1795 2323 1799 2323 1793 2323 1793 2324 1799 2324 1800 2324 1793 2325 1800 2325 1794 2325 1790 2326 1796 2326 1792 2326 1792 2327 1796 2327 1795 2327 1792 2328 1795 2328 1791 2328 1791 2329 1795 2329 1793 2329 1791 2330 1793 2330 574 2330 574 2331 1793 2331 576 2331 1797 2332 854 2332 1798 2332 1798 2333 854 2333 853 2333 1798 2334 853 2334 1799 2334 1799 2335 853 2335 863 2335 1799 2336 863 2336 1800 2336 863 2337 864 2337 1800 2337 1800 2338 864 2338 865 2338 1800 2339 865 2339 1794 2339 865 2340 862 2340 1794 2340 1794 2341 862 2341 569 2341 1794 2342 569 2342 577 2342 1801 2343 1802 2343 1803 2343 1804 2344 1805 2344 1806 2344 1806 2345 1805 2345 1807 2345 1807 2346 1808 2346 1809 2346 1809 2347 1808 2347 1810 2347 1809 2348 1810 2348 1811 2348 1801 2349 1812 2349 886 2349 886 2350 1812 2350 1813 2350 886 2351 1813 2351 887 2351 1802 2352 1801 2352 1814 2352 1811 2353 1815 2353 1809 2353 1809 2354 1815 2354 1816 2354 1809 2355 1816 2355 1817 2355 1817 2356 1816 2356 1803 2356 1801 2357 886 2357 1814 2357 1814 2358 886 2358 893 2358 1814 2359 893 2359 1818 2359 1818 2360 893 2360 892 2360 1818 2361 892 2361 1819 2361 1819 2362 892 2362 890 2362 1819 2363 890 2363 1820 2363 1820 2364 890 2364 889 2364 1820 2365 889 2365 1821 2365 1803 2366 1802 2366 1817 2366 1817 2367 1802 2367 1814 2367 1817 2368 1814 2368 1822 2368 1822 2369 1814 2369 1818 2369 1822 2370 1818 2370 1823 2370 1823 2371 1818 2371 1819 2371 1823 2372 1819 2372 1824 2372 1824 2373 1819 2373 1820 2373 1824 2374 1820 2374 1825 2374 1825 2375 1820 2375 1821 2375 1825 2376 1821 2376 1826 2376 1807 2377 1809 2377 1806 2377 1806 2378 1809 2378 1817 2378 1806 2379 1817 2379 1827 2379 1827 2380 1817 2380 1822 2380 1827 2381 1822 2381 1828 2381 1828 2382 1822 2382 1823 2382 1828 2383 1823 2383 1829 2383 1829 2384 1823 2384 1824 2384 1829 2385 1824 2385 1830 2385 1830 2386 1824 2386 1825 2386 1830 2387 1825 2387 1831 2387 1831 2388 1825 2388 1826 2388 1831 2389 1826 2389 1832 2389 1331 2390 1332 2390 1833 2390 1310 2391 1834 2391 1311 2391 1311 2392 1834 2392 1301 2392 1302 2393 1301 2393 1835 2393 1835 2394 1301 2394 1834 2394 1835 2395 1834 2395 1836 2395 1836 2396 1834 2396 1310 2396 1836 2397 1310 2397 1833 2397 1833 2398 1310 2398 1308 2398 1833 2399 1308 2399 1331 2399 1771 2400 1769 2400 1836 2400 1836 2401 1769 2401 1768 2401 1836 2402 1768 2402 1835 2402 1835 2403 1768 2403 1777 2403 1835 2404 1777 2404 1302 2404 934 98 1837 98 935 98 935 2405 1837 2405 1838 2405 1839 98 1324 98 1840 98 1840 98 1324 98 935 98 1840 98 935 98 1841 98 1841 98 935 98 1838 98 1842 2406 1337 2406 1843 2406 1843 2407 1337 2407 1336 2407 1843 2408 1336 2408 1844 2408 1844 2409 1336 2409 1324 2409 1844 2410 1324 2410 1839 2410 1335 2411 1337 2411 1845 2411 1845 2412 1846 2412 1335 2412 1335 2413 1846 2413 1847 2413 1335 2414 1847 2414 1333 2414 1333 2415 1847 2415 1848 2415 1333 2416 1848 2416 1332 2416 1849 2417 1850 2417 1851 2417 1851 2418 1850 2418 1852 2418 1851 2419 1852 2419 1853 2419 1853 2420 1852 2420 1854 2420 1853 2421 1854 2421 1855 2421 1855 2422 1854 2422 1856 2422 1855 2423 1856 2423 1857 2423 743 2424 899 2424 1858 2424 743 2425 1858 2425 1859 2425 1859 2426 1858 2426 1860 2426 1859 2427 1860 2427 1861 2427 1861 2428 1860 2428 1862 2428 1861 2429 1862 2429 1863 2429 1863 2430 1862 2430 1864 2430 1863 2431 1864 2431 1849 2431 1849 2432 1864 2432 1865 2432 1849 2433 1865 2433 1850 2433 1866 2434 914 2434 765 2434 1867 2435 1868 2435 1869 2435 1869 2436 1868 2436 1870 2436 1869 2437 1870 2437 1871 2437 1871 2438 1870 2438 1872 2438 1871 2439 1872 2439 1873 2439 1873 2440 1872 2440 1874 2440 1873 2441 1874 2441 1875 2441 1875 2442 1874 2442 1876 2442 1875 2443 1876 2443 1877 2443 1866 2444 765 2444 1878 2444 1869 2445 1879 2445 1867 2445 1867 2446 1879 2446 1880 2446 1867 2447 1880 2447 1881 2447 1881 2448 1880 2448 1878 2448 1881 2449 1878 2449 1882 2449 1882 2450 1878 2450 765 2450 1883 2451 1884 2451 1885 2451 1886 2452 1887 2452 1884 2452 915 2453 914 2453 1888 2453 1889 2454 911 2454 910 2454 1889 2455 910 2455 1890 2455 1890 2456 910 2456 909 2456 1890 2457 909 2457 1891 2457 1891 2458 909 2458 908 2458 1891 2459 908 2459 1892 2459 1892 2460 908 2460 912 2460 1892 2461 912 2461 1893 2461 1893 2462 912 2462 913 2462 1893 2463 913 2463 1894 2463 1894 2464 913 2464 917 2464 1894 2465 917 2465 1895 2465 1895 2466 917 2466 916 2466 1895 2467 916 2467 1896 2467 1896 2468 916 2468 915 2468 1896 2469 915 2469 1886 2469 1886 2470 915 2470 1888 2470 1886 2471 1888 2471 1887 2471 1884 2472 1883 2472 1886 2472 1886 2473 1883 2473 1897 2473 1886 2474 1897 2474 1896 2474 1896 2475 1897 2475 1898 2475 1896 2476 1898 2476 1895 2476 1895 2477 1898 2477 1899 2477 1895 2478 1899 2478 1894 2478 1894 2479 1899 2479 1900 2479 1894 2480 1900 2480 1893 2480 1893 2481 1900 2481 1901 2481 1893 2482 1901 2482 1892 2482 1892 2483 1901 2483 1902 2483 1892 2484 1902 2484 1891 2484 1891 2485 1902 2485 1903 2485 1891 2486 1903 2486 1890 2486 1890 2487 1903 2487 1904 2487 1890 2488 1904 2488 1889 2488 1885 2489 1905 2489 1883 2489 1883 2490 1905 2490 1906 2490 1883 2491 1906 2491 1897 2491 1897 2492 1906 2492 1907 2492 1897 2493 1907 2493 1898 2493 1898 2494 1907 2494 1908 2494 1898 2495 1908 2495 1899 2495 1899 2496 1908 2496 1909 2496 1899 2497 1909 2497 1900 2497 1900 2498 1909 2498 1910 2498 1900 2499 1910 2499 1901 2499 1901 2500 1910 2500 1911 2500 1901 2501 1911 2501 1902 2501 1902 2502 1911 2502 1912 2502 1902 2503 1912 2503 1903 2503 1903 2504 1912 2504 1913 2504 1903 2505 1913 2505 1904 2505 1913 2506 1832 2506 1904 2506 1904 2507 1832 2507 1826 2507 1904 2508 1826 2508 1889 2508 1889 2509 1826 2509 1821 2509 1889 2510 1821 2510 911 2510 911 2511 1821 2511 889 2511 1717 2512 1712 2512 1914 2512 1915 2513 1739 2513 1916 2513 1916 2514 1739 2514 1741 2514 1916 2515 1741 2515 1742 2515 1917 2516 1783 2516 1918 2516 1918 2517 1783 2517 1739 2517 1918 2518 1739 2518 1919 2518 1919 2519 1739 2519 1915 2519 1920 2520 1921 2520 1922 2520 1922 2521 1921 2521 1916 2521 1922 2522 1916 2522 1923 2522 1742 2523 1735 2523 1916 2523 1916 2524 1735 2524 1729 2524 1916 2525 1729 2525 1923 2525 1923 2526 1729 2526 1728 2526 1923 2527 1728 2527 1924 2527 1924 2528 1728 2528 1914 2528 1914 2529 1728 2529 1720 2529 1914 2530 1720 2530 1717 2530 1925 98 1926 98 1663 98 1927 2531 1928 2531 1929 2531 1929 98 1928 98 1930 98 1653 2532 1931 2532 1663 2532 1663 2533 1931 2533 1932 2533 1663 98 1932 98 1925 98 1926 2534 1933 2534 1663 2534 1663 2535 1933 2535 1934 2535 1663 98 1934 98 1935 98 1930 98 1936 98 1929 98 1929 2536 1936 2536 1935 2536 1929 2537 1935 2537 1937 2537 1937 2538 1935 2538 1934 2538 1938 2539 1939 2539 1940 2539 1940 2540 1939 2540 1941 2540 1940 2541 1941 2541 1942 2541 1942 2542 1941 2542 1943 2542 1942 2543 1943 2543 1944 2543 1944 2544 1943 2544 1945 2544 1944 2545 1945 2545 1946 2545 1946 2546 1945 2546 1947 2546 1948 2547 1928 2547 1949 2547 1949 2548 1928 2548 1950 2548 1949 2549 1950 2549 1951 2549 1951 2550 1950 2550 1952 2550 1951 2551 1952 2551 1953 2551 1953 2552 1952 2552 1954 2552 1953 2553 1954 2553 1955 2553 1955 2554 1954 2554 1956 2554 1955 2555 1956 2555 1957 2555 1957 2556 1956 2556 1958 2556 1957 2557 1958 2557 1959 2557 1959 2558 1958 2558 1960 2558 1959 2559 1960 2559 1947 2559 1947 2560 1960 2560 1961 2560 1947 2561 1961 2561 1946 2561 1948 2562 1962 2562 1928 2562 1928 2563 1962 2563 1963 2563 1928 2564 1963 2564 1930 2564 1964 2565 1665 2565 1965 2565 1965 2566 1665 2566 627 2566 1965 2567 627 2567 1966 2567 1966 2568 627 2568 630 2568 1966 2569 630 2569 631 2569 1967 2570 1968 2570 1969 2570 1967 2571 1969 2571 1970 2571 1970 2572 1969 2572 1971 2572 1970 2573 1971 2573 1972 2573 1972 2574 1971 2574 1973 2574 1972 2575 1973 2575 1974 2575 1974 2576 1973 2576 1975 2576 1974 2577 1975 2577 1976 2577 1976 2578 1975 2578 1977 2578 1976 2579 1977 2579 1978 2579 1978 2580 1977 2580 1979 2580 1978 2581 1979 2581 1980 2581 1980 2582 1979 2582 1981 2582 1980 2583 1981 2583 1982 2583 1982 2584 1981 2584 1983 2584 1982 2585 1983 2585 1984 2585 1984 2586 1983 2586 1985 2586 1984 2587 1985 2587 1986 2587 1986 2588 1985 2588 1987 2588 1986 2589 1987 2589 1988 2589 1988 2590 1987 2590 1989 2590 1988 2591 1989 2591 1990 2591 1990 2592 1989 2592 1991 2592 1990 2593 1991 2593 1992 2593 1992 2594 1991 2594 1993 2594 1992 2595 1993 2595 1994 2595 1994 2596 1993 2596 1995 2596 1994 2597 1995 2597 1996 2597 1996 2598 1995 2598 1997 2598 1996 2599 1997 2599 1998 2599 1998 2600 1997 2600 1999 2600 1998 2601 1999 2601 2000 2601 2000 2602 1999 2602 2001 2602 2000 2603 2001 2603 2002 2603 2002 2604 2001 2604 2003 2604 2002 2605 2003 2605 2004 2605 2004 2606 2003 2606 2005 2606 2004 2607 2005 2607 2006 2607 2006 2608 2005 2608 2007 2608 2006 2609 2007 2609 2008 2609 2008 2610 2007 2610 2009 2610 2008 2611 2009 2611 2010 2611 2010 2612 2009 2612 2011 2612 2010 2613 2011 2613 2012 2613 2012 2614 2011 2614 2013 2614 2012 2615 2013 2615 2014 2615 2014 2616 2013 2616 2015 2616 2014 2617 2015 2617 2016 2617 2016 2618 2015 2618 2017 2618 2016 2619 2017 2619 2018 2619 2018 2620 2017 2620 2019 2620 2018 2621 2019 2621 2020 2621 2021 2622 1964 2622 1965 2622 2021 2623 2022 2623 2023 2623 2023 2624 2022 2624 2024 2624 2025 2625 2026 2625 2027 2625 2028 2626 2029 2626 2022 2626 2022 2627 2029 2627 2030 2627 2022 2628 2030 2628 2024 2628 2021 2629 1965 2629 2022 2629 2022 2630 1965 2630 1966 2630 2022 2631 1966 2631 2031 2631 2032 2632 2033 2632 2031 2632 2031 2633 2033 2633 2025 2633 2031 2634 2025 2634 2022 2634 2022 2635 2025 2635 2027 2635 2022 2636 2027 2636 2028 2636 2034 2637 2020 2637 2032 2637 2034 2638 2032 2638 2035 2638 2035 2639 2032 2639 2031 2639 2035 2640 2031 2640 2036 2640 2036 2641 2031 2641 1966 2641 2036 2642 1966 2642 631 2642 2037 2643 2038 2643 2039 2643 2040 2644 2041 2644 2042 2644 2041 2645 2040 2645 2043 2645 2044 2646 2045 2646 2046 2646 2040 2647 2047 2647 2043 2647 2043 2648 2047 2648 2048 2648 2043 2649 2048 2649 2049 2649 2049 2650 2048 2650 2050 2650 2049 2651 2050 2651 2051 2651 2051 2652 2050 2652 2052 2652 2051 2653 2052 2653 2053 2653 2053 2654 2052 2654 2054 2654 2053 2655 2054 2655 2055 2655 2055 2656 2054 2656 1968 2656 2055 2657 1968 2657 1967 2657 1967 2658 2044 2658 2055 2658 2055 2659 2044 2659 2046 2659 2055 2660 2046 2660 2053 2660 2053 2661 2046 2661 2056 2661 2053 2662 2056 2662 2051 2662 2051 2663 2056 2663 2057 2663 2051 2664 2057 2664 2049 2664 2049 2665 2057 2665 2058 2665 2049 2666 2058 2666 2043 2666 2043 2667 2058 2667 2059 2667 2043 2668 2059 2668 2041 2668 2041 2669 2059 2669 2038 2669 2041 2670 2038 2670 2042 2670 2042 2671 2038 2671 2037 2671 2046 2672 2045 2672 2060 2672 2061 2673 2039 2673 2038 2673 2062 2674 2063 2674 2061 2674 2060 2675 2064 2675 2065 2675 2065 2676 2064 2676 2066 2676 2065 2677 2066 2677 2067 2677 2038 2678 2059 2678 2061 2678 2061 2679 2059 2679 2065 2679 2061 2680 2065 2680 2062 2680 2062 2681 2065 2681 2067 2681 2062 2682 2067 2682 2068 2682 2059 2683 2058 2683 2065 2683 2065 2684 2058 2684 2057 2684 2065 2685 2057 2685 2060 2685 2060 2686 2057 2686 2056 2686 2060 2687 2056 2687 2046 2687 2069 2688 2070 2688 2071 2688 2072 2689 2073 2689 2074 2689 2075 2690 2076 2690 2077 2690 2063 2691 2062 2691 2078 2691 2079 2692 2080 2692 2081 2692 2062 2693 2068 2693 2082 2693 2062 2694 2082 2694 2078 2694 2078 2695 2082 2695 2083 2695 2078 2696 2083 2696 2084 2696 2085 2697 2086 2697 2087 2697 2088 2698 2089 2698 2070 2698 2070 2699 2089 2699 2090 2699 2070 2700 2090 2700 2071 2700 2071 2701 2090 2701 2091 2701 2092 2702 2093 2702 2072 2702 2094 2703 2095 2703 2096 2703 2096 2704 2095 2704 2097 2704 2098 2705 2099 2705 2100 2705 2100 2706 2099 2706 2101 2706 2087 2707 2063 2707 2085 2707 2085 2708 2063 2708 2078 2708 2085 2709 2078 2709 2081 2709 2081 2710 2078 2710 2084 2710 2081 2711 2084 2711 2079 2711 2102 2712 2103 2712 2080 2712 2080 2713 2103 2713 2069 2713 2080 2714 2069 2714 2081 2714 2081 2715 2069 2715 2071 2715 2081 2716 2071 2716 2085 2716 2085 2717 2071 2717 2091 2717 2085 2718 2091 2718 2086 2718 2073 2719 2075 2719 2074 2719 2074 2720 2075 2720 2077 2720 2074 2721 2077 2721 2104 2721 2104 2722 2077 2722 2105 2722 2104 2723 2105 2723 2096 2723 2096 2724 2105 2724 2106 2724 2096 2725 2106 2725 2094 2725 2094 2726 2106 2726 2107 2726 2094 2727 2107 2727 2108 2727 2108 2728 2107 2728 2109 2728 2072 2729 2074 2729 2092 2729 2092 2730 2074 2730 2104 2730 2092 2731 2104 2731 2110 2731 2110 2732 2104 2732 2096 2732 2110 2733 2096 2733 2111 2733 2111 2734 2096 2734 2097 2734 2111 2735 2097 2735 2112 2735 2076 2736 2113 2736 2077 2736 2077 2737 2113 2737 2114 2737 2077 2738 2114 2738 2105 2738 2105 2739 2114 2739 2115 2739 2105 2740 2115 2740 2106 2740 2106 2741 2115 2741 2116 2741 2106 2742 2116 2742 2107 2742 2107 2743 2116 2743 2100 2743 2107 2744 2100 2744 2109 2744 2109 2745 2100 2745 2101 2745 2113 2746 2117 2746 2114 2746 2114 2747 2117 2747 2088 2747 2114 2748 2088 2748 2115 2748 2115 2749 2088 2749 2070 2749 2115 2750 2070 2750 2116 2750 2116 2751 2070 2751 2069 2751 2116 2752 2069 2752 2100 2752 2100 2753 2069 2753 2103 2753 2100 2754 2103 2754 2098 2754 2098 2755 2103 2755 2102 2755 2098 2756 2102 2756 2118 2756 2119 2757 1346 2757 1345 2757 1665 2758 1964 2758 1345 2758 1345 2759 1964 2759 2120 2759 1345 2760 2120 2760 2119 2760 2119 2761 2120 2761 2121 2761 2119 2762 2121 2762 2122 2762 1607 2763 1348 2763 1349 2763 2119 2764 2122 2764 2123 2764 2124 2765 2125 2765 1608 2765 1608 2766 1607 2766 2124 2766 2124 2767 1607 2767 1349 2767 2124 2768 1349 2768 2123 2768 2123 2769 1349 2769 1347 2769 2123 2770 1347 2770 2119 2770 2119 2771 1347 2771 1346 2771 2126 2772 2127 2772 2128 2772 2128 2773 2127 2773 2129 2773 2128 2774 2129 2774 2130 2774 2130 2775 2129 2775 2131 2775 2130 2776 2131 2776 1585 2776 1585 2777 2131 2777 2132 2777 1585 2778 2132 2778 1586 2778 2133 2779 2134 2779 2128 2779 2128 2780 2134 2780 2135 2780 2128 2781 2135 2781 2126 2781 2128 2782 1939 2782 1938 2782 1938 2783 2136 2783 2128 2783 2128 2784 2136 2784 2137 2784 2128 2785 2137 2785 2138 2785 2138 2786 2139 2786 2128 2786 2128 2787 2139 2787 2140 2787 2128 2788 2140 2788 2133 2788 2141 2789 2142 2789 2143 2789 2141 2790 2143 2790 1366 2790 1366 2791 2143 2791 2144 2791 1366 2792 2144 2792 1367 2792 2142 2793 2141 2793 2145 2793 2145 2794 2141 2794 2146 2794 2145 2795 2146 2795 2147 2795 2147 2796 2146 2796 2148 2796 2148 2797 2146 2797 2149 2797 2148 2798 2149 2798 2150 2798 2150 2799 2149 2799 2151 2799 2151 2800 2149 2800 2152 2800 2151 2801 2152 2801 2153 2801 2154 2802 2155 2802 2156 2802 2156 2803 2155 2803 2157 2803 2156 2804 2157 2804 2158 2804 2158 2805 2157 2805 2159 2805 2158 2806 2159 2806 2160 2806 2160 2807 2159 2807 2161 2807 2160 2808 2161 2808 1378 2808 1378 2809 2161 2809 1376 2809 2155 2810 2152 2810 2157 2810 2157 2811 2152 2811 2149 2811 2157 2812 2149 2812 2159 2812 2159 2813 2149 2813 2146 2813 2159 2814 2146 2814 2161 2814 2161 2815 2146 2815 2141 2815 2161 2816 2141 2816 1376 2816 1376 2817 2141 2817 1366 2817 2162 2818 2163 2818 2164 2818 2164 2819 2163 2819 2165 2819 2164 2820 2165 2820 2166 2820 2166 2821 2165 2821 2167 2821 2166 2822 2167 2822 2168 2822 2169 2823 2170 2823 2164 2823 2164 2824 2170 2824 2171 2824 2164 2825 2171 2825 2162 2825 2172 2826 2173 2826 2169 2826 2169 2827 2173 2827 2174 2827 2169 2828 2174 2828 2170 2828 1365 2829 1367 2829 2175 2829 1365 2830 2175 2830 2176 2830 2176 2831 2175 2831 2177 2831 2176 2832 2177 2832 2178 2832 2166 2833 2179 2833 2164 2833 2164 2834 2179 2834 2180 2834 2164 2835 2180 2835 2169 2835 2169 2836 2180 2836 2181 2836 2169 2837 2181 2837 2172 2837 2172 2838 2181 2838 2176 2838 2172 2839 2176 2839 2182 2839 2182 2840 2176 2840 2178 2840 1362 2841 1365 2841 2183 2841 2183 2842 1365 2842 2176 2842 2183 2843 2176 2843 2184 2843 2184 2844 2176 2844 2181 2844 2184 2845 2181 2845 2185 2845 2185 2846 2181 2846 2180 2846 2185 2847 2180 2847 2186 2847 2186 2848 2180 2848 2179 2848 1358 2849 1362 2849 2187 2849 2187 2850 1362 2850 2183 2850 2187 2851 2183 2851 2188 2851 2188 2852 2183 2852 2184 2852 2188 2853 2184 2853 2189 2853 2189 2854 2184 2854 2185 2854 2189 2855 2185 2855 2190 2855 2190 2856 2185 2856 2186 2856 1381 2857 1358 2857 2191 2857 2191 2858 1358 2858 2187 2858 2191 2859 2187 2859 2192 2859 2192 2860 2187 2860 2188 2860 2192 2861 2188 2861 2193 2861 2193 2862 2188 2862 2189 2862 2193 2863 2189 2863 2194 2863 2194 2864 2189 2864 2190 2864 918 2865 1381 2865 2195 2865 2195 2866 1381 2866 2191 2866 2195 2867 2191 2867 2196 2867 2196 2868 2191 2868 2192 2868 2196 2869 2192 2869 2197 2869 2197 2870 2192 2870 2193 2870 2197 2871 2193 2871 2198 2871 2198 2872 2193 2872 2194 2872 2199 2873 2200 2873 2201 2873 1921 2874 2202 2874 1916 2874 1916 2875 2202 2875 2203 2875 1917 2876 1918 2876 2204 2876 2204 2877 1918 2877 1919 2877 2204 2878 1919 2878 2205 2878 2205 2879 1919 2879 1915 2879 2205 2880 1915 2880 2206 2880 2206 2881 1915 2881 1916 2881 2206 2882 1916 2882 2199 2882 2199 2883 1916 2883 2203 2883 2199 2884 2203 2884 2200 2884 1917 2885 2204 2885 2207 2885 2207 2886 2204 2886 2205 2886 2207 2887 2205 2887 2208 2887 2208 2888 2205 2888 2206 2888 2208 2889 2206 2889 2209 2889 2209 2890 2206 2890 2199 2890 2209 2891 2199 2891 2210 2891 2210 2892 2199 2892 2201 2892 2210 2893 2201 2893 2211 2893 2200 2894 2203 2894 2212 2894 2212 2895 2203 2895 2202 2895 2213 2896 2211 2896 2201 2896 2202 2897 1921 2897 2214 2897 2214 2898 1921 2898 1920 2898 2215 2899 2216 2899 2217 2899 2217 2900 2216 2900 2218 2900 2217 2901 2218 2901 2219 2901 2219 2902 2218 2902 2220 2902 2219 2903 2220 2903 2221 2903 2221 2904 2220 2904 2222 2904 2221 2905 2222 2905 2223 2905 2223 2906 2222 2906 2224 2906 2223 2907 2224 2907 2225 2907 2225 2908 2224 2908 2213 2908 2225 2909 2213 2909 2212 2909 2212 2910 2213 2910 2201 2910 2212 2911 2201 2911 2200 2911 1923 2912 2226 2912 1922 2912 1922 2913 2226 2913 2227 2913 1922 2914 2227 2914 1920 2914 1920 2915 2227 2915 2228 2915 1920 2916 2228 2916 2214 2916 2214 2917 2228 2917 2229 2917 2214 2918 2229 2918 2230 2918 2230 2919 2229 2919 2231 2919 2230 2920 2231 2920 2232 2920 2232 2921 2231 2921 2233 2921 2232 2922 2233 2922 2234 2922 2234 2923 2233 2923 2235 2923 2234 2924 2235 2924 2236 2924 2236 2925 2235 2925 2237 2925 2236 2926 2237 2926 2238 2926 2238 2927 2237 2927 2239 2927 2238 2928 2239 2928 2240 2928 2202 2929 2214 2929 2212 2929 2212 2930 2214 2930 2230 2930 2212 2931 2230 2931 2225 2931 2225 2932 2230 2932 2232 2932 2225 2933 2232 2933 2223 2933 2223 2934 2232 2934 2234 2934 2223 2935 2234 2935 2221 2935 2221 2936 2234 2936 2236 2936 2221 2937 2236 2937 2219 2937 2219 2938 2236 2938 2238 2938 2219 2939 2238 2939 2217 2939 2217 2940 2238 2940 2240 2940 2217 2941 2240 2941 2241 2941 2242 2942 2215 2942 2243 2942 2243 2943 2215 2943 2217 2943 2243 2944 2217 2944 2244 2944 2244 2945 2217 2945 2241 2945 2160 2946 1378 2946 2242 2946 2242 2947 2243 2947 2160 2947 2160 2948 2243 2948 2244 2948 2160 2949 2244 2949 2158 2949 2244 2950 2241 2950 2158 2950 2158 2951 2241 2951 2240 2951 2158 2952 2240 2952 2156 2952 2156 2953 2240 2953 2239 2953 2156 2954 2239 2954 2154 2954 2245 2955 1813 2955 1812 2955 2245 2956 1812 2956 2246 2956 2246 2957 1812 2957 1801 2957 2246 2958 1801 2958 2247 2958 2247 2959 1801 2959 1803 2959 2247 2960 1803 2960 2248 2960 887 2961 2245 2961 2249 2961 2249 2962 2245 2962 2246 2962 2249 2963 2246 2963 2250 2963 2250 2964 2246 2964 2247 2964 2250 2965 2247 2965 2251 2965 2251 2966 2247 2966 2248 2966 2251 2967 2248 2967 2252 2967 887 2968 2249 2968 1389 2968 1389 2969 2249 2969 2250 2969 1389 2970 2250 2970 1388 2970 1388 2971 2250 2971 2251 2971 1388 2972 2251 2972 1387 2972 1387 2973 2251 2973 2252 2973 1387 2974 2252 2974 1385 2974 1813 2975 2245 2975 887 2975 1406 2976 1408 2976 2253 2976 2253 2977 1408 2977 2254 2977 2253 2978 2254 2978 2255 2978 2255 2979 2254 2979 2256 2979 2256 2980 2254 2980 2257 2980 2256 2981 2257 2981 2258 2981 2258 2982 2257 2982 2259 2982 2259 2983 2257 2983 1816 2983 2259 2984 1816 2984 1815 2984 1803 2985 1816 2985 2248 2985 2248 2986 1816 2986 2257 2986 2248 2987 2257 2987 2252 2987 2252 2988 2257 2988 2254 2988 2252 2989 2254 2989 1385 2989 1385 2990 2254 2990 1408 2990 745 2991 743 2991 1859 2991 745 2992 1859 2992 2260 2992 2260 2993 1859 2993 1861 2993 2260 2994 1861 2994 2261 2994 2261 2995 1861 2995 1863 2995 2261 2996 1863 2996 2262 2996 2262 2997 1863 2997 1849 2997 2262 2998 1849 2998 2263 2998 1849 2999 1851 2999 2263 2999 2263 3000 1851 3000 1853 3000 2263 3001 1853 3001 2264 3001 2264 3002 1853 3002 1855 3002 2264 3003 1855 3003 2265 3003 2265 3004 1855 3004 1857 3004 1857 3005 2266 3005 2265 3005 2265 3006 2266 3006 2267 3006 2265 3007 2267 3007 2264 3007 2264 3008 2267 3008 2268 3008 2264 3009 2268 3009 2263 3009 2263 3010 2268 3010 2269 3010 2263 3011 2269 3011 2262 3011 2262 3012 2269 3012 2270 3012 2262 3013 2270 3013 2261 3013 2261 3014 2270 3014 2271 3014 2261 3015 2271 3015 2260 3015 2260 3016 2271 3016 746 3016 2260 3017 746 3017 745 3017 1857 3018 2272 3018 2266 3018 2266 3019 2272 3019 2273 3019 2266 3020 2273 3020 2267 3020 2267 3021 2273 3021 2274 3021 2267 3022 2274 3022 2268 3022 2268 3023 2274 3023 2275 3023 2268 3024 2275 3024 2269 3024 2269 3025 2275 3025 2276 3025 2269 3026 2276 3026 2270 3026 2270 3027 2276 3027 2277 3027 2270 3028 2277 3028 2271 3028 2271 3029 2277 3029 751 3029 2271 3030 751 3030 746 3030 1857 3031 2278 3031 2272 3031 2272 3032 2278 3032 2279 3032 2272 3033 2279 3033 2273 3033 2273 3034 2279 3034 2280 3034 2273 3035 2280 3035 2274 3035 2274 3036 2280 3036 2281 3036 2274 3037 2281 3037 2275 3037 2275 3038 2281 3038 2282 3038 2275 3039 2282 3039 2276 3039 2276 3040 2282 3040 2283 3040 2276 3041 2283 3041 2277 3041 2277 3042 2283 3042 755 3042 2277 3043 755 3043 751 3043 1442 3044 1447 3044 2284 3044 2285 3045 2286 3045 2287 3045 1857 3046 2288 3046 2278 3046 2278 3047 2288 3047 2289 3047 2278 3048 2289 3048 2279 3048 2279 3049 2289 3049 2280 3049 2280 3050 2289 3050 2290 3050 2280 3051 2290 3051 2281 3051 2281 3052 2290 3052 2291 3052 2281 3053 2291 3053 2282 3053 2282 3054 2291 3054 2283 3054 2283 3055 2291 3055 1438 3055 2283 3056 1438 3056 755 3056 769 3057 1459 3057 2292 3057 2292 3058 1459 3058 2286 3058 2292 3059 2286 3059 2293 3059 2293 3060 2286 3060 2285 3060 2294 3061 2295 3061 2287 3061 2287 3062 2295 3062 2296 3062 2287 3063 2296 3063 2285 3063 1877 3064 2297 3064 2298 3064 2298 3065 2297 3065 2299 3065 2298 3066 2299 3066 2294 3066 2294 3067 2299 3067 2300 3067 2294 3068 2300 3068 2295 3068 2288 3069 2301 3069 2289 3069 2289 3070 2301 3070 2302 3070 2289 3071 2302 3071 2290 3071 2290 3072 2302 3072 2303 3072 2290 3073 2303 3073 2291 3073 2291 3074 2303 3074 2284 3074 2291 3075 2284 3075 1438 3075 1438 3076 2284 3076 1447 3076 1459 3077 1442 3077 2286 3077 2286 3078 1442 3078 2284 3078 2286 3079 2284 3079 2287 3079 2287 3080 2284 3080 2303 3080 2287 3081 2303 3081 2294 3081 2294 3082 2303 3082 2302 3082 2294 3083 2302 3083 2298 3083 2298 3084 2302 3084 2301 3084 1877 3085 1876 3085 2304 3085 2304 3086 1876 3086 1874 3086 2305 3087 1874 3087 1872 3087 2305 3088 1872 3088 2306 3088 2306 3089 1872 3089 1870 3089 2306 3090 1870 3090 2307 3090 2307 3091 1870 3091 1868 3091 2307 3092 1868 3092 2308 3092 2308 3093 1868 3093 1867 3093 2308 3094 1867 3094 2309 3094 2309 3095 1867 3095 1881 3095 2309 3096 1881 3096 2310 3096 2310 3097 1881 3097 1882 3097 2310 3098 1882 3098 2311 3098 2311 3099 1882 3099 765 3099 2311 3100 765 3100 762 3100 2312 3101 2305 3101 2313 3101 2313 3102 2305 3102 2306 3102 2313 3103 2306 3103 2314 3103 2314 3104 2306 3104 2307 3104 2314 3105 2307 3105 2315 3105 2315 3106 2307 3106 2308 3106 2315 3107 2308 3107 2316 3107 2316 3108 2308 3108 2309 3108 2316 3109 2309 3109 2317 3109 2317 3110 2309 3110 2310 3110 2317 3111 2310 3111 2318 3111 2318 3112 2310 3112 2311 3112 2318 3113 2311 3113 2319 3113 2319 3114 2311 3114 762 3114 2319 3115 762 3115 761 3115 1877 3116 2312 3116 2320 3116 2320 3117 2312 3117 2313 3117 2320 3118 2313 3118 2321 3118 2321 3119 2313 3119 2314 3119 2321 3120 2314 3120 2322 3120 2322 3121 2314 3121 2315 3121 2322 3122 2315 3122 2323 3122 2323 3123 2315 3123 2316 3123 2323 3124 2316 3124 2324 3124 2324 3125 2316 3125 2317 3125 2324 3126 2317 3126 2325 3126 2325 3127 2317 3127 2318 3127 2325 3128 2318 3128 2326 3128 2326 3129 2318 3129 2319 3129 2326 3130 2319 3130 2327 3130 2327 3131 2319 3131 761 3131 2327 3132 761 3132 759 3132 1877 3133 2320 3133 2297 3133 2297 3134 2320 3134 2321 3134 2297 3135 2321 3135 2299 3135 2299 3136 2321 3136 2322 3136 2299 3137 2322 3137 2300 3137 2300 3138 2322 3138 2323 3138 2300 3139 2323 3139 2295 3139 2295 3140 2323 3140 2324 3140 2295 3141 2324 3141 2296 3141 2296 3142 2324 3142 2325 3142 2296 3143 2325 3143 2285 3143 2285 3144 2325 3144 2326 3144 2285 3145 2326 3145 2293 3145 2293 3146 2326 3146 2327 3146 2293 3147 2327 3147 2292 3147 2292 3148 2327 3148 759 3148 2292 3149 759 3149 769 3149 1874 3150 2305 3150 2304 3150 2304 3151 2305 3151 2312 3151 2304 3152 2312 3152 1877 3152 2328 3153 2329 3153 2330 3153 1497 3154 1496 3154 2331 3154 1605 3155 2332 3155 1604 3155 1606 3156 1586 3156 2132 3156 2333 3157 2334 3157 1463 3157 2335 3158 2336 3158 2333 3158 2337 3159 2338 3159 1463 3159 1463 3160 2338 3160 2339 3160 1463 3161 2339 3161 1462 3161 2334 3162 2340 3162 1463 3162 1463 3163 2340 3163 2341 3163 1463 3164 2341 3164 2337 3164 2342 3165 2343 3165 2344 3165 2345 3166 2346 3166 2347 3166 2348 3167 2349 3167 2350 3167 2350 3168 2349 3168 2351 3168 2351 3169 2352 3169 2350 3169 2350 3170 2352 3170 2353 3170 2350 3171 2353 3171 2354 3171 1606 3172 2132 3172 1605 3172 1545 3173 1538 3173 2355 3173 2355 3174 1538 3174 1526 3174 1526 3175 1527 3175 2356 3175 2356 3176 1527 3176 1529 3176 2356 3177 1529 3177 2332 3177 2332 3178 1529 3178 1603 3178 2332 3179 1603 3179 1604 3179 2357 3180 1576 3180 1572 3180 1556 3181 1555 3181 2358 3181 1572 3182 1569 3182 2357 3182 2357 3183 1569 3183 1566 3183 2357 3184 1566 3184 2358 3184 2358 3185 1566 3185 1557 3185 2358 3186 1557 3186 1556 3186 1545 3187 2359 3187 1548 3187 1548 3188 2359 3188 2358 3188 1548 3189 2358 3189 1551 3189 1551 3190 2358 3190 1555 3190 1486 3191 1484 3191 2360 3191 2360 3192 1484 3192 1482 3192 2360 3193 1482 3193 1506 3193 1506 3194 1507 3194 2360 3194 2360 3195 1507 3195 1512 3195 2360 3196 1512 3196 2357 3196 2357 3197 1512 3197 1517 3197 2357 3198 1517 3198 1576 3198 1496 3199 1495 3199 2361 3199 2361 3200 1495 3200 1494 3200 2361 3201 1494 3201 1486 3201 2362 3202 2363 3202 2364 3202 2364 3203 2363 3203 2365 3203 2364 3204 2365 3204 2366 3204 2366 3205 2365 3205 2350 3205 2366 3206 2350 3206 2345 3206 2345 3207 2350 3207 2354 3207 2345 3208 2354 3208 2346 3208 2362 3209 2364 3209 2330 3209 2330 3210 2364 3210 2367 3210 2330 3211 2367 3211 2328 3211 2333 3212 1463 3212 2335 3212 2335 3213 1463 3213 1464 3213 2335 3214 1464 3214 2368 3214 2368 3215 1464 3215 1465 3215 2368 3216 1465 3216 2369 3216 2369 3217 1465 3217 1468 3217 2369 3218 1468 3218 2370 3218 2370 3219 1468 3219 1470 3219 2370 3220 1470 3220 2371 3220 2371 3221 1470 3221 1476 3221 2371 3222 1476 3222 2372 3222 2372 3223 1476 3223 1475 3223 2372 3224 1475 3224 2331 3224 2331 3225 1475 3225 780 3225 2331 3226 780 3226 1497 3226 1496 3227 2361 3227 2331 3227 2331 3228 2361 3228 2373 3228 2331 3229 2373 3229 2372 3229 2372 3230 2373 3230 2374 3230 2372 3231 2374 3231 2371 3231 2371 3232 2374 3232 2375 3232 2371 3233 2375 3233 2370 3233 2370 3234 2375 3234 2376 3234 2370 3235 2376 3235 2369 3235 2369 3236 2376 3236 2377 3236 2369 3237 2377 3237 2368 3237 2368 3238 2377 3238 2342 3238 2368 3239 2342 3239 2335 3239 2335 3240 2342 3240 2344 3240 2335 3241 2344 3241 2336 3241 1486 3242 2360 3242 2361 3242 2361 3243 2360 3243 2378 3243 2361 3244 2378 3244 2373 3244 2373 3245 2378 3245 2328 3245 2373 3246 2328 3246 2374 3246 2374 3247 2328 3247 2367 3247 2374 3248 2367 3248 2375 3248 2375 3249 2367 3249 2364 3249 2375 3250 2364 3250 2376 3250 2376 3251 2364 3251 2366 3251 2376 3252 2366 3252 2377 3252 2377 3253 2366 3253 2345 3253 2377 3254 2345 3254 2342 3254 2342 3255 2345 3255 2347 3255 2342 3256 2347 3256 2343 3256 2329 3257 2328 3257 2379 3257 2379 3258 2328 3258 2378 3258 2379 3259 2378 3259 2380 3259 2380 3260 2378 3260 2360 3260 2380 3261 2360 3261 2381 3261 2381 3262 2360 3262 2357 3262 2381 3263 2357 3263 2382 3263 2382 3264 2357 3264 2358 3264 2382 3265 2358 3265 2383 3265 2383 3266 2358 3266 2359 3266 2383 3267 2359 3267 2384 3267 2384 3268 2359 3268 2385 3268 2384 3269 2385 3269 2386 3269 2386 3270 2385 3270 2387 3270 2386 3271 2387 3271 2388 3271 2388 3272 2387 3272 2389 3272 2389 3273 2387 3273 2390 3273 2389 3274 2390 3274 2391 3274 2391 3275 2390 3275 2392 3275 2391 3276 2392 3276 2393 3276 1605 3277 2132 3277 2332 3277 2332 3278 2132 3278 2131 3278 2332 3279 2131 3279 2356 3279 2356 3280 2131 3280 2129 3280 2356 3281 2129 3281 2394 3281 2394 3282 2129 3282 2127 3282 2394 3283 2127 3283 2395 3283 2395 3284 2127 3284 2126 3284 2395 3285 2126 3285 2396 3285 2396 3286 2126 3286 2135 3286 2396 3287 2135 3287 2397 3287 2397 3288 2135 3288 2134 3288 2397 3289 2134 3289 2398 3289 2398 3290 2134 3290 2133 3290 2398 3291 2133 3291 2399 3291 2399 3292 2133 3292 2140 3292 2399 3293 2140 3293 2400 3293 2400 3294 2140 3294 2139 3294 2400 3295 2139 3295 2401 3295 2401 3296 2139 3296 2138 3296 2401 3297 2138 3297 2402 3297 2402 3298 2138 3298 2137 3298 2402 3299 2137 3299 2403 3299 2403 3300 2137 3300 2136 3300 2403 3301 2136 3301 2404 3301 2404 3302 2136 3302 1938 3302 2404 3303 1938 3303 2405 3303 1526 3304 2356 3304 2355 3304 2355 3305 2356 3305 2394 3305 2355 3306 2394 3306 2406 3306 2406 3307 2394 3307 2395 3307 2406 3308 2395 3308 2407 3308 2407 3309 2395 3309 2396 3309 2407 3310 2396 3310 2408 3310 2408 3311 2396 3311 2397 3311 2408 3312 2397 3312 2409 3312 2409 3313 2397 3313 2398 3313 2409 3314 2398 3314 2410 3314 2410 3315 2398 3315 2399 3315 2410 3316 2399 3316 2411 3316 2411 3317 2399 3317 2400 3317 2411 3318 2400 3318 2412 3318 2412 3319 2400 3319 2401 3319 2412 3320 2401 3320 2413 3320 2413 3321 2401 3321 2402 3321 2413 3322 2402 3322 2414 3322 2414 3323 2402 3323 2403 3323 2414 3324 2403 3324 2415 3324 2415 3325 2403 3325 2404 3325 2415 3326 2404 3326 2416 3326 2416 3327 2404 3327 2405 3327 2416 3328 2405 3328 2417 3328 1545 3329 2355 3329 2359 3329 2359 3330 2355 3330 2406 3330 2359 3331 2406 3331 2385 3331 2385 3332 2406 3332 2407 3332 2385 3333 2407 3333 2387 3333 2387 3334 2407 3334 2408 3334 2387 3335 2408 3335 2390 3335 2390 3336 2408 3336 2409 3336 2390 3337 2409 3337 2392 3337 2392 3338 2409 3338 2410 3338 2392 3339 2410 3339 2418 3339 2418 3340 2410 3340 2411 3340 2418 3341 2411 3341 2419 3341 2419 3342 2411 3342 2412 3342 2419 3343 2412 3343 2420 3343 2420 3344 2412 3344 2413 3344 2420 3345 2413 3345 2421 3345 2421 3346 2413 3346 2414 3346 2421 3347 2414 3347 2422 3347 2422 3348 2414 3348 2415 3348 2422 3349 2415 3349 2423 3349 2423 3350 2415 3350 2416 3350 2423 3351 2416 3351 2424 3351 2424 3352 2416 3352 2417 3352 2424 3353 2417 3353 2425 3353 2393 3354 2392 3354 2426 3354 2426 3355 2392 3355 2418 3355 2426 3356 2418 3356 2427 3356 2427 3357 2418 3357 2419 3357 2427 3358 2419 3358 2428 3358 2428 3359 2419 3359 2420 3359 2428 3360 2420 3360 2429 3360 2429 3361 2420 3361 2421 3361 2429 3362 2421 3362 2430 3362 2430 3363 2421 3363 2422 3363 2430 3364 2422 3364 2431 3364 2431 3365 2422 3365 2423 3365 2431 3366 2423 3366 2432 3366 2432 3367 2423 3367 2424 3367 2432 3368 2424 3368 2433 3368 2433 3369 2424 3369 2425 3369 2433 3370 2425 3370 2434 3370 2435 3371 2436 3371 2437 3371 2438 3372 2439 3372 2440 3372 2440 3373 2439 3373 2441 3373 2440 106 2441 106 2442 106 2443 3374 2441 3374 2444 3374 2444 3375 2441 3375 2439 3375 2444 3376 2439 3376 2445 3376 2445 3377 2439 3377 2438 3377 2445 3378 2438 3378 2446 3378 2446 3379 2438 3379 2437 3379 2436 3380 2435 3380 2447 3380 2448 3381 2449 3381 2450 3381 2450 3382 2449 3382 2451 3382 2451 3383 2452 3383 2453 3383 2453 3384 2452 3384 2454 3384 2453 3385 2454 3385 2447 3385 2334 3386 2455 3386 2340 3386 2340 3387 2455 3387 2456 3387 1462 3388 2339 3388 2457 3388 2457 3389 2339 3389 2338 3389 2457 3390 2338 3390 2458 3390 2458 3391 2338 3391 2337 3391 2458 3392 2337 3392 2459 3392 2459 3393 2337 3393 2341 3393 2459 3394 2341 3394 2460 3394 2460 3395 2341 3395 2340 3395 2460 3396 2340 3396 2450 3396 2450 3397 2340 3397 2456 3397 2450 3398 2456 3398 2448 3398 2451 3399 2453 3399 2450 3399 2450 3400 2453 3400 2461 3400 2450 3401 2461 3401 2460 3401 2460 3402 2461 3402 2462 3402 2460 3403 2462 3403 2459 3403 2459 3404 2462 3404 2463 3404 2459 3405 2463 3405 2458 3405 2458 3406 2463 3406 2464 3406 2458 3407 2464 3407 2457 3407 2457 3408 2464 3408 1462 3408 2447 3409 2435 3409 2453 3409 2453 3410 2435 3410 2465 3410 2453 3411 2465 3411 2461 3411 2461 3412 2465 3412 2466 3412 2461 3413 2466 3413 2462 3413 2462 3414 2466 3414 2467 3414 2462 3415 2467 3415 2463 3415 2463 3416 2467 3416 2468 3416 2463 3417 2468 3417 2464 3417 2464 3418 2468 3418 1462 3418 2437 3419 2438 3419 2435 3419 2435 3420 2438 3420 2469 3420 2435 3421 2469 3421 2465 3421 2465 3422 2469 3422 2470 3422 2465 3423 2470 3423 2466 3423 2466 3424 2470 3424 2471 3424 2466 3425 2471 3425 2467 3425 2467 3426 2471 3426 2472 3426 2467 3427 2472 3427 2468 3427 2468 3428 2472 3428 1462 3428 2437 3429 2436 3429 2473 3429 2455 3430 2334 3430 2333 3430 2455 3431 2333 3431 2456 3431 2474 3432 2448 3432 2456 3432 2452 3433 2451 3433 2474 3433 2474 3434 2451 3434 2449 3434 2474 3435 2449 3435 2448 3435 2436 3436 2447 3436 2475 3436 2475 3437 2447 3437 2454 3437 2475 3438 2454 3438 2452 3438 2445 3439 2446 3439 2476 3439 2476 3440 2446 3440 2437 3440 2456 3441 2333 3441 2474 3441 2474 3442 2333 3442 2336 3442 2474 3443 2336 3443 2477 3443 2477 3444 2336 3444 2344 3444 2477 3445 2344 3445 2478 3445 2478 3446 2344 3446 2343 3446 2478 3447 2343 3447 2479 3447 2479 3448 2343 3448 2347 3448 2479 3449 2347 3449 2480 3449 2480 3450 2347 3450 2346 3450 2480 3451 2346 3451 2481 3451 2346 3452 2354 3452 2481 3452 2481 3453 2354 3453 2482 3453 2481 3454 2482 3454 2483 3454 2452 3455 2474 3455 2475 3455 2475 3456 2474 3456 2477 3456 2475 3457 2477 3457 2484 3457 2484 3458 2477 3458 2478 3458 2484 3459 2478 3459 2485 3459 2485 3460 2478 3460 2479 3460 2485 3461 2479 3461 2486 3461 2486 3462 2479 3462 2480 3462 2486 3463 2480 3463 2487 3463 2487 3464 2480 3464 2481 3464 2487 3465 2481 3465 2488 3465 2488 3466 2481 3466 2483 3466 2488 3467 2483 3467 2489 3467 2436 3468 2475 3468 2473 3468 2473 3469 2475 3469 2484 3469 2473 3470 2484 3470 2490 3470 2490 3471 2484 3471 2485 3471 2490 3472 2485 3472 2491 3472 2491 3473 2485 3473 2486 3473 2491 3474 2486 3474 2492 3474 2492 3475 2486 3475 2487 3475 2492 3476 2487 3476 2493 3476 2493 3477 2487 3477 2488 3477 2493 3478 2488 3478 2494 3478 2494 3479 2488 3479 2489 3479 2494 3480 2489 3480 2495 3480 2437 3481 2473 3481 2476 3481 2476 3482 2473 3482 2490 3482 2476 3483 2490 3483 2496 3483 2496 3484 2490 3484 2491 3484 2496 3485 2491 3485 2497 3485 2497 3486 2491 3486 2492 3486 2497 3487 2492 3487 2498 3487 2498 3488 2492 3488 2493 3488 2498 3489 2493 3489 2499 3489 2499 3490 2493 3490 2494 3490 2499 3491 2494 3491 2500 3491 2500 3492 2494 3492 2495 3492 2500 3493 2495 3493 2501 3493 2502 3494 2503 3494 2504 3494 2505 3495 2506 3495 2507 3495 2507 3496 2506 3496 2508 3496 2507 3497 2508 3497 2502 3497 2509 3498 2510 3498 2511 3498 2512 3499 2501 3499 2513 3499 2505 3500 2514 3500 2515 3500 2515 3501 2514 3501 2516 3501 2515 3502 2516 3502 2517 3502 2517 3503 2516 3503 2518 3503 2517 3504 2518 3504 2519 3504 2519 3505 2518 3505 2520 3505 2519 3506 2520 3506 2348 3506 2505 3507 2507 3507 2514 3507 2514 3508 2507 3508 2521 3508 2514 3509 2521 3509 2516 3509 2516 3510 2521 3510 2522 3510 2516 3511 2522 3511 2518 3511 2518 3512 2522 3512 2523 3512 2518 3513 2523 3513 2520 3513 2502 3514 2504 3514 2507 3514 2507 3515 2504 3515 2524 3515 2507 3516 2524 3516 2521 3516 2521 3517 2524 3517 2509 3517 2521 3518 2509 3518 2522 3518 2522 3519 2509 3519 2511 3519 2522 3520 2511 3520 2523 3520 1758 3521 2525 3521 2503 3521 2503 3522 2525 3522 2526 3522 2503 3523 2526 3523 2504 3523 2504 3524 2526 3524 2527 3524 2504 3525 2527 3525 2524 3525 2524 3526 2527 3526 2512 3526 2524 3527 2512 3527 2509 3527 2509 3528 2512 3528 2513 3528 2509 3529 2513 3529 2510 3529 2123 3530 2122 3530 2528 3530 2529 3531 2530 3531 2531 3531 2528 3532 792 3532 791 3532 791 3533 2531 3533 2528 3533 2528 3534 2531 3534 2530 3534 2528 3535 2530 3535 2123 3535 2123 3536 2530 3536 2529 3536 2123 3537 2529 3537 2124 3537 2124 3538 2529 3538 2532 3538 2124 3539 2532 3539 2125 3539 2533 3540 2122 3540 2534 3540 2534 3541 2122 3541 2121 3541 2528 3542 2122 3542 792 3542 792 3543 2122 3543 2533 3543 792 3544 2533 3544 793 3544 793 3545 2533 3545 2535 3545 793 3546 2535 3546 794 3546 2536 3547 2537 3547 2538 3547 2539 3548 2540 3548 2541 3548 2542 3549 2543 3549 2544 3549 2539 3550 2541 3550 2545 3550 2545 3551 2541 3551 2546 3551 2546 3552 2541 3552 2547 3552 2546 3553 2547 3553 2548 3553 2548 3554 2547 3554 2544 3554 2548 3555 2544 3555 2549 3555 2549 3556 2544 3556 2543 3556 2549 3557 2543 3557 2026 3557 2542 3558 2544 3558 2550 3558 2550 3559 2544 3559 2547 3559 2550 3560 2547 3560 2551 3560 2551 3561 2547 3561 2541 3561 2551 3562 2541 3562 2552 3562 794 3563 2535 3563 2552 3563 2552 3564 2535 3564 2533 3564 2552 3565 2533 3565 2551 3565 2551 3566 2533 3566 2534 3566 2551 3567 2534 3567 2550 3567 2550 3568 2534 3568 2121 3568 2550 3569 2121 3569 2542 3569 794 3570 2552 3570 1613 3570 1613 3571 2552 3571 2541 3571 1613 3572 2541 3572 2538 3572 2538 3573 2541 3573 2540 3573 2538 3574 2540 3574 2536 3574 1613 3575 2538 3575 1618 3575 1618 3576 2538 3576 2537 3576 1618 3577 2537 3577 1623 3577 2553 3578 2554 3578 2555 3578 2556 3579 1700 3579 1699 3579 2557 3580 2556 3580 2558 3580 2556 3581 1699 3581 2558 3581 2558 3582 1699 3582 1673 3582 2558 3583 1673 3583 1666 3583 1666 3584 1668 3584 2558 3584 2558 3585 1668 3585 2553 3585 2558 3586 2553 3586 2557 3586 2557 3587 2553 3587 2555 3587 1685 3588 2554 3588 1676 3588 1676 3589 2554 3589 2553 3589 1676 3590 2553 3590 1670 3590 1670 3591 2553 3591 1668 3591 1689 3592 2559 3592 1688 3592 1688 3593 2559 3593 2560 3593 1688 3594 2560 3594 1687 3594 2561 3595 2554 3595 2562 3595 2562 3596 2554 3596 1685 3596 2562 3597 1685 3597 2560 3597 2560 3598 1685 3598 1686 3598 2560 3599 1686 3599 1687 3599 2561 3600 2563 3600 2564 3600 2555 3601 2554 3601 2565 3601 2565 3602 2554 3602 2561 3602 2565 3603 2561 3603 2566 3603 2566 3604 2561 3604 2564 3604 2559 3605 2567 3605 2560 3605 2560 3606 2567 3606 2568 3606 2560 3607 2568 3607 2562 3607 2562 3608 2568 3608 2569 3608 2562 3609 2569 3609 2561 3609 2561 3610 2569 3610 2570 3610 2561 3611 2570 3611 2563 3611 2571 3612 2572 3612 2570 3612 2570 3613 2572 3613 2573 3613 2570 3614 2573 3614 2563 3614 2574 3615 2575 3615 2576 3615 2576 3616 2575 3616 2577 3616 2576 3617 2577 3617 2578 3617 2578 3618 2577 3618 2579 3618 2578 3619 2579 3619 2580 3619 2580 3620 2579 3620 2581 3620 2567 3621 2581 3621 2568 3621 2568 3622 2581 3622 2579 3622 2568 3623 2579 3623 2569 3623 2569 3624 2579 3624 2577 3624 2569 3625 2577 3625 2570 3625 2570 3626 2577 3626 2575 3626 2570 3627 2575 3627 2571 3627 2571 3628 2575 3628 2574 3628 2571 3629 2574 3629 2582 3629 2556 3630 2557 3630 2583 3630 1701 3631 1700 3631 2556 3631 2584 3632 2585 3632 2586 3632 1693 3633 1695 3633 2585 3633 2585 3634 1695 3634 1696 3634 2585 3635 1696 3635 2587 3635 2587 3636 1696 3636 1691 3636 2587 3637 1691 3637 2588 3637 1691 3638 1690 3638 2588 3638 2588 3639 1690 3639 1702 3639 2588 3640 1702 3640 2589 3640 2589 3641 1702 3641 1701 3641 1701 3642 2556 3642 2589 3642 2589 3643 2556 3643 2583 3643 2589 3644 2583 3644 2588 3644 2588 3645 2583 3645 2590 3645 2588 3646 2590 3646 2587 3646 2587 3647 2590 3647 2586 3647 2587 3648 2586 3648 2585 3648 2584 3649 2586 3649 2591 3649 2591 3650 2586 3650 2590 3650 2591 3651 2590 3651 2592 3651 2592 3652 2590 3652 2583 3652 2592 3653 2583 3653 2593 3653 2593 3654 2583 3654 2557 3654 2593 3655 2557 3655 2555 3655 2594 3656 2595 3656 2596 3656 2597 3657 2598 3657 2599 3657 2598 3658 2600 3658 2599 3658 2599 3659 2600 3659 2601 3659 2599 3660 2601 3660 2602 3660 2564 3661 2603 3661 2604 3661 2604 3662 2603 3662 1693 3662 1693 3663 2605 3663 1694 3663 1694 3664 2605 3664 2596 3664 1694 3665 2596 3665 1707 3665 2606 3666 2607 3666 2608 3666 2608 3667 2607 3667 2609 3667 2608 3668 2609 3668 2610 3668 2610 3669 2609 3669 2611 3669 2610 3670 2611 3670 2612 3670 2595 3671 2606 3671 2596 3671 2596 3672 2606 3672 2608 3672 2596 3673 2608 3673 1707 3673 1707 3674 2608 3674 2610 3674 1707 3675 2610 3675 1706 3675 2603 3676 2597 3676 1693 3676 1693 3677 2597 3677 2599 3677 1693 3678 2599 3678 2605 3678 2605 3679 2599 3679 2613 3679 2605 3680 2613 3680 2596 3680 2596 3681 2613 3681 2614 3681 2596 3682 2614 3682 2594 3682 2615 3683 2616 3683 1914 3683 1706 3684 2610 3684 1712 3684 1712 3685 2610 3685 2612 3685 1712 3686 2612 3686 1914 3686 1914 3687 2612 3687 2617 3687 1914 3688 2617 3688 2615 3688 1757 3689 882 3689 2618 3689 2618 3690 882 3690 880 3690 2618 3691 880 3691 2619 3691 2619 3692 880 3692 878 3692 2619 3693 878 3693 2620 3693 866 3694 2621 3694 868 3694 868 3695 2621 3695 2622 3695 868 3696 2622 3696 870 3696 870 3697 2622 3697 2623 3697 870 3698 2623 3698 872 3698 872 3699 2623 3699 2624 3699 872 3700 2624 3700 874 3700 874 3701 2624 3701 2625 3701 874 3702 2625 3702 876 3702 876 3703 2625 3703 2626 3703 876 3704 2626 3704 878 3704 878 3705 2626 3705 2627 3705 878 3706 2627 3706 2620 3706 855 3707 2628 3707 866 3707 866 3708 2628 3708 2629 3708 866 3709 2629 3709 2621 3709 2630 3710 2631 3710 855 3710 855 3711 2631 3711 2632 3711 855 3712 2632 3712 2628 3712 855 3713 854 3713 2633 3713 2633 3714 2634 3714 855 3714 855 3715 2634 3715 2635 3715 855 3716 2635 3716 2630 3716 2636 3717 1757 3717 2637 3717 1757 3718 2638 3718 2639 3718 2636 3719 2638 3719 1757 3719 634 3720 638 3720 2640 3720 2640 3721 638 3721 1756 3721 2640 3722 1756 3722 2639 3722 2639 3723 1756 3723 1757 3723 2118 3724 2637 3724 2098 3724 2098 3725 2637 3725 2641 3725 2098 3726 2641 3726 2099 3726 2099 3727 2641 3727 2101 3727 1759 3728 1758 3728 2642 3728 2642 3729 1758 3729 2643 3729 2642 3730 2643 3730 2644 3730 2645 3731 2646 3731 2647 3731 2648 3732 2649 3732 2650 3732 2650 3733 2649 3733 2646 3733 2650 3734 2646 3734 2651 3734 2651 3735 2646 3735 2645 3735 364 3736 1759 3736 2647 3736 2647 3737 1759 3737 2642 3737 2647 3738 2642 3738 2645 3738 2645 3739 2642 3739 2644 3739 2645 3740 2644 3740 2651 3740 2651 3741 2644 3741 2652 3741 2651 3742 2652 3742 2650 3742 2650 3743 2652 3743 2648 3743 2653 3744 348 3744 359 3744 2654 3745 2655 3745 2656 3745 2657 3746 2658 3746 2659 3746 2659 3747 2658 3747 2660 3747 2659 3748 2660 3748 2661 3748 2657 3749 2662 3749 2658 3749 2658 3750 2662 3750 2663 3750 2658 3751 2663 3751 2664 3751 2654 3752 2656 3752 2664 3752 2665 3753 2666 3753 2667 3753 2667 3754 2666 3754 2668 3754 2667 3755 2668 3755 2669 3755 2669 3756 2670 3756 2667 3756 2667 3757 2670 3757 2582 3757 2667 3758 2582 3758 2661 3758 2602 3759 2671 3759 2672 3759 2672 3760 2671 3760 2673 3760 2672 3761 2673 3761 2674 3761 2653 3762 359 3762 2655 3762 2655 3763 359 3763 2656 3763 2656 3764 359 3764 360 3764 2656 3765 360 3765 2675 3765 2675 3766 360 3766 363 3766 2675 3767 363 3767 2676 3767 2676 3768 363 3768 364 3768 2676 3769 364 3769 2647 3769 2664 3770 2656 3770 2658 3770 2658 3771 2656 3771 2675 3771 2658 3772 2675 3772 2677 3772 2677 3773 2675 3773 2676 3773 2677 3774 2676 3774 2678 3774 2678 3775 2676 3775 2647 3775 2678 3776 2647 3776 2646 3776 2661 3777 2660 3777 2667 3777 2667 3778 2660 3778 2658 3778 2667 3779 2658 3779 2679 3779 2679 3780 2658 3780 2677 3780 2679 3781 2677 3781 2680 3781 2680 3782 2677 3782 2678 3782 2680 3783 2678 3783 2681 3783 2681 3784 2678 3784 2646 3784 2681 3785 2646 3785 2649 3785 2674 3786 2665 3786 2672 3786 2672 3787 2665 3787 2667 3787 2672 3788 2667 3788 2682 3788 2682 3789 2667 3789 2679 3789 2682 3790 2679 3790 2683 3790 2683 3791 2679 3791 2680 3791 2683 3792 2680 3792 2684 3792 2684 3793 2680 3793 2681 3793 2684 3794 2681 3794 2685 3794 2685 3795 2681 3795 2649 3795 2685 3796 2649 3796 2648 3796 2655 3797 2654 3797 2686 3797 2686 3798 2654 3798 2687 3798 2686 3799 2687 3799 2688 3799 2688 3800 2687 3800 2689 3800 2688 3801 2689 3801 352 3801 352 3802 2689 3802 353 3802 2653 3803 2655 3803 2690 3803 2690 3804 2655 3804 2686 3804 2690 3805 2686 3805 2691 3805 2691 3806 2686 3806 2688 3806 2691 3807 2688 3807 351 3807 351 3808 2688 3808 352 3808 348 3809 2653 3809 347 3809 347 3810 2653 3810 2690 3810 347 3811 2690 3811 349 3811 349 3812 2690 3812 2691 3812 349 3813 2691 3813 350 3813 350 3814 2691 3814 351 3814 2692 3815 2693 3815 2694 3815 2654 3816 2664 3816 2687 3816 2687 3817 2664 3817 2695 3817 2687 3818 2695 3818 2689 3818 2689 3819 2695 3819 2696 3819 2689 3820 2696 3820 353 3820 2697 3821 2698 3821 2696 3821 2696 3822 2698 3822 2699 3822 2696 3823 2699 3823 353 3823 2692 3824 2694 3824 2700 3824 2700 3825 2694 3825 2701 3825 2700 3826 2701 3826 2702 3826 2657 3827 2659 3827 2703 3827 2703 3828 2701 3828 2657 3828 2657 3829 2701 3829 2694 3829 2657 3830 2694 3830 2662 3830 2662 3831 2694 3831 2693 3831 2662 3832 2693 3832 2663 3832 2703 3833 2704 3833 2701 3833 2701 3834 2704 3834 2705 3834 2701 3835 2705 3835 2702 3835 2702 3836 2705 3836 2706 3836 2702 3837 2706 3837 2707 3837 2664 3838 2663 3838 2695 3838 2695 3839 2663 3839 2693 3839 2695 3840 2693 3840 2696 3840 2696 3841 2693 3841 2692 3841 2696 3842 2692 3842 2697 3842 2697 3843 2692 3843 2700 3843 2697 3844 2700 3844 2708 3844 2708 3845 2700 3845 2702 3845 2708 3846 2702 3846 2709 3846 2709 3847 2702 3847 2707 3847 2709 3848 2707 3848 2710 3848 2711 3849 2712 3849 2710 3849 2659 3850 2661 3850 2703 3850 2703 3851 2661 3851 2713 3851 2703 3852 2713 3852 2704 3852 2704 3853 2713 3853 2714 3853 2710 3854 2707 3854 2711 3854 2711 3855 2707 3855 2706 3855 2711 3856 2706 3856 2714 3856 2714 3857 2706 3857 2705 3857 2714 3858 2705 3858 2704 3858 2580 3859 2712 3859 2578 3859 2578 3860 2712 3860 2711 3860 2578 3861 2711 3861 2576 3861 2576 3862 2711 3862 2714 3862 2576 3863 2714 3863 2574 3863 2574 3864 2714 3864 2713 3864 2574 3865 2713 3865 2582 3865 2582 3866 2713 3866 2661 3866 2715 3867 2716 3867 2717 3867 1761 3868 2718 3868 2717 3868 2716 3869 1765 3869 2717 3869 2717 3870 1765 3870 1762 3870 2717 3871 1762 3871 1761 3871 2719 3872 2715 3872 2720 3872 2720 3873 2715 3873 2717 3873 2720 3874 2717 3874 2721 3874 2721 3875 2717 3875 2718 3875 2721 3876 2718 3876 2722 3876 1772 3877 1771 3877 1836 3877 1332 3878 1848 3878 1833 3878 1833 3879 1848 3879 2723 3879 1833 3880 2723 3880 1836 3880 1836 3881 2723 3881 2724 3881 1836 3882 2724 3882 1772 3882 2725 3883 2726 3883 2727 3883 2728 3884 2729 3884 1760 3884 2730 3885 2731 3885 2729 3885 2729 3886 2731 3886 2732 3886 2732 3887 2733 3887 2729 3887 2729 3888 2733 3888 1761 3888 2729 3889 1761 3889 1760 3889 2734 3890 2735 3890 2736 3890 2736 3891 2735 3891 2737 3891 2736 3892 2737 3892 2738 3892 2739 3893 2740 3893 2734 3893 2734 3894 2740 3894 2741 3894 2734 3895 2741 3895 2735 3895 2742 3896 2743 3896 2739 3896 2739 3897 2743 3897 2744 3897 2739 3898 2744 3898 2740 3898 2725 3899 2727 3899 2745 3899 1848 3900 2726 3900 2723 3900 2723 3901 2726 3901 2725 3901 2723 3902 2725 3902 2724 3902 2724 3903 2725 3903 2745 3903 2737 3904 2730 3904 2738 3904 2738 3905 2730 3905 2729 3905 2738 3906 2729 3906 2746 3906 2746 3907 2729 3907 2728 3907 2746 3908 2728 3908 2727 3908 2727 3909 2728 3909 2747 3909 2727 3910 2747 3910 2745 3910 1772 3911 2724 3911 1774 3911 1774 3912 2724 3912 2745 3912 1774 3913 2745 3913 1775 3913 1775 3914 2745 3914 2747 3914 1775 3915 2747 3915 1776 3915 1776 3916 2747 3916 2728 3916 1776 3917 2728 3917 1766 3917 1766 3918 2728 3918 1760 3918 2748 3919 2749 3919 2750 3919 805 3920 822 3920 2751 3920 817 3921 2719 3921 2720 3921 2721 3922 2751 3922 2720 3922 2752 3923 2753 3923 2754 3923 1845 3924 1842 3924 2755 3924 2755 3925 1842 3925 2748 3925 2755 3926 2748 3926 2742 3926 2756 3927 2757 3927 2750 3927 2750 3928 2757 3928 2758 3928 2722 3929 2759 3929 2760 3929 2760 3930 2759 3930 2756 3930 2756 3931 2759 3931 2761 3931 2756 3932 2761 3932 2757 3932 2751 3933 822 3933 2720 3933 2720 3934 822 3934 818 3934 2720 3935 818 3935 817 3935 2722 3936 2760 3936 2762 3936 2722 3937 2762 3937 2721 3937 2721 3938 2762 3938 2763 3938 2721 3939 2763 3939 2751 3939 2751 3940 2763 3940 806 3940 2751 3941 806 3941 805 3941 2758 3942 2754 3942 2750 3942 2750 3943 2754 3943 2753 3943 2750 3944 2753 3944 2748 3944 2748 3945 2753 3945 2752 3945 2748 3946 2752 3946 2742 3946 2764 3947 813 3947 2765 3947 2765 3948 813 3948 812 3948 2765 3949 812 3949 2766 3949 2766 3950 812 3950 807 3950 2766 3951 807 3951 806 3951 814 3952 816 3952 2767 3952 2767 3953 816 3953 2768 3953 2769 3954 2770 3954 2771 3954 2772 3955 836 3955 2773 3955 2773 3956 836 3956 1782 3956 2773 3957 2769 3957 2772 3957 2772 3958 2769 3958 2771 3958 2772 3959 2771 3959 836 3959 836 3960 2771 3960 2774 3960 836 3961 2774 3961 835 3961 835 3962 2774 3962 2775 3962 835 3963 2775 3963 834 3963 2775 3964 2774 3964 2776 3964 843 3965 834 3965 2775 3965 2777 3966 2776 3966 2778 3966 2777 3967 2778 3967 2779 3967 2779 3968 2778 3968 2780 3968 2779 3969 2780 3969 2781 3969 2775 3970 2776 3970 843 3970 843 3971 2776 3971 2777 3971 843 3972 2777 3972 847 3972 847 3973 2777 3973 2779 3973 847 3974 2779 3974 2782 3974 2782 3975 2779 3975 2781 3975 2782 3976 2781 3976 2783 3976 847 3977 2782 3977 1789 3977 1789 3978 2782 3978 2783 3978 1789 3979 2783 3979 1790 3979 2784 3980 1797 3980 1796 3980 2784 3981 1796 3981 2785 3981 2785 3982 1796 3982 1790 3982 2785 3983 1790 3983 2783 3983 2633 3984 854 3984 2786 3984 2786 3985 854 3985 1797 3985 2786 3986 1797 3986 2784 3986 1806 3987 1827 3987 2787 3987 1830 3988 1831 3988 2788 3988 2788 3989 1831 3989 1832 3989 2788 3990 1832 3990 2789 3990 2789 3991 1832 3991 1913 3991 1828 3992 1829 3992 2790 3992 1804 3993 1806 3993 2791 3993 2791 3994 1806 3994 2792 3994 2792 3995 1806 3995 2793 3995 2793 3996 1806 3996 2787 3996 2793 3997 2787 3997 2794 3997 2794 3998 2787 3998 2795 3998 2794 3999 2795 3999 2796 3999 2796 4000 2795 4000 2797 4000 2796 4001 2797 4001 2798 4001 1829 4002 1830 4002 2790 4002 2790 4003 1830 4003 2788 4003 2790 4004 2788 4004 2799 4004 2799 4005 2788 4005 2800 4005 2799 4006 2800 4006 2801 4006 2801 4007 2800 4007 2802 4007 2801 4008 2802 4008 2803 4008 1827 4009 1828 4009 2787 4009 2787 4010 1828 4010 2790 4010 2787 4011 2790 4011 2795 4011 2795 4012 2790 4012 2799 4012 2795 4013 2799 4013 2797 4013 2797 4014 2799 4014 2801 4014 2797 4015 2801 4015 2798 4015 2798 4016 2801 4016 2803 4016 2798 4017 2803 4017 2804 4017 2805 4018 2806 4018 2807 4018 2808 4019 2805 4019 2809 4019 1804 4020 2808 4020 2810 4020 2805 4021 2807 4021 2809 4021 2809 4022 2807 4022 2811 4022 2809 4023 2811 4023 2812 4023 2812 4024 2811 4024 2813 4024 2812 4025 2813 4025 2814 4025 2814 4026 2813 4026 2815 4026 2814 4027 2815 4027 2816 4027 2816 4028 2815 4028 2817 4028 2816 4029 2817 4029 2818 4029 1406 4030 2817 4030 2819 4030 2819 4031 2817 4031 2815 4031 2819 4032 2815 4032 2820 4032 2820 4033 2815 4033 2813 4033 2820 4034 2813 4034 2821 4034 2821 4035 2813 4035 2811 4035 2821 4036 2811 4036 2822 4036 2822 4037 2811 4037 2807 4037 2822 4038 2807 4038 2823 4038 2823 4039 2807 4039 2806 4039 2823 4040 2806 4040 2824 4040 1406 4041 2253 4041 2817 4041 2817 4042 2253 4042 2255 4042 2817 4043 2255 4043 2818 4043 2818 4044 2255 4044 2256 4044 2818 4045 2256 4045 2258 4045 2808 4046 2809 4046 2810 4046 2810 4047 2809 4047 2812 4047 2810 4048 2812 4048 2825 4048 2825 4049 2812 4049 2814 4049 2825 4050 2814 4050 2826 4050 2826 4051 2814 4051 2816 4051 2826 4052 2816 4052 2827 4052 2827 4053 2816 4053 2818 4053 2827 4054 2818 4054 2828 4054 2828 4055 2818 4055 2258 4055 2828 4056 2258 4056 2259 4056 1804 4057 2810 4057 1805 4057 1805 4058 2810 4058 2825 4058 1805 4059 2825 4059 1807 4059 1807 4060 2825 4060 2826 4060 1807 4061 2826 4061 1808 4061 1808 4062 2826 4062 2827 4062 1808 4063 2827 4063 1810 4063 1810 4064 2827 4064 2828 4064 1810 4065 2828 4065 1811 4065 1811 4066 2828 4066 2259 4066 1811 4067 2259 4067 1815 4067 2829 95 2830 95 2831 95 2832 95 2833 95 2834 95 2834 95 2833 95 2835 95 2834 95 2835 95 2836 95 2837 95 2838 95 2839 95 2839 95 2838 95 2840 95 2839 95 2840 95 2841 95 2841 95 2840 95 2836 95 2841 95 2836 95 2830 95 2830 95 2836 95 2835 95 2830 95 2835 95 2831 95 2831 95 2842 95 2829 95 2829 95 2842 95 2843 95 2829 95 2843 95 2844 95 2844 95 2845 95 2829 95 2829 95 2845 95 2846 95 2829 95 2846 95 2847 95 2847 95 2848 95 2829 95 2829 95 2848 95 2849 95 2829 95 2849 95 2850 95 1840 4068 1841 4068 2851 4068 2851 4069 1841 4069 2852 4069 2851 4070 2852 4070 2853 4070 2853 4071 2852 4071 2854 4071 1839 4072 1840 4072 2855 4072 2855 4073 1840 4073 2851 4073 2855 4074 2851 4074 2856 4074 2856 4075 2851 4075 2853 4075 1845 4076 1337 4076 1842 4076 2855 4077 2856 4077 2857 4077 1839 4078 2855 4078 2858 4078 2855 4079 2857 4079 2858 4079 2858 4080 2857 4080 2859 4080 2858 4081 2859 4081 2860 4081 2860 4082 2859 4082 2749 4082 2860 4083 2749 4083 2748 4083 1839 4084 2858 4084 1844 4084 1844 4085 2858 4085 2860 4085 1844 4086 2860 4086 1843 4086 1843 4087 2860 4087 2748 4087 1843 4088 2748 4088 1842 4088 2738 4089 2746 4089 2861 4089 2861 4090 2746 4090 2727 4090 2861 4091 2727 4091 2726 4091 2738 4092 2861 4092 2736 4092 2736 4093 2861 4093 2862 4093 2736 4094 2862 4094 2734 4094 2734 4095 2862 4095 2739 4095 2739 4096 2862 4096 2755 4096 2739 4097 2755 4097 2742 4097 1845 4098 2755 4098 1846 4098 1846 4099 2755 4099 2862 4099 1846 4100 2862 4100 1847 4100 1847 4101 2862 4101 2861 4101 1847 4102 2861 4102 1848 4102 1848 4103 2861 4103 2726 4103 2863 4104 2864 4104 2865 4104 2865 4105 2864 4105 2866 4105 2168 4106 2867 4106 2166 4106 2166 4107 2867 4107 2868 4107 2166 4108 2868 4108 2179 4108 2179 4109 2868 4109 2186 4109 2186 4110 2868 4110 2190 4110 2190 4111 2868 4111 2198 4111 2190 4112 2198 4112 2194 4112 2869 4113 2870 4113 2866 4113 2866 4114 2870 4114 2871 4114 2872 4115 2873 4115 2874 4115 2874 4116 2873 4116 2875 4116 2874 4117 2875 4117 2868 4117 2868 4118 2875 4118 2876 4118 2868 4119 2876 4119 2198 4119 2867 4120 2877 4120 2868 4120 2868 4121 2877 4121 2865 4121 2868 4122 2865 4122 2874 4122 2874 4123 2865 4123 2866 4123 2874 4124 2866 4124 2872 4124 2872 4125 2866 4125 2871 4125 2878 4126 2863 4126 2865 4126 2878 4127 2865 4127 2879 4127 2879 4128 2865 4128 2877 4128 2879 4129 2877 4129 2880 4129 2880 4130 2877 4130 2867 4130 2881 4131 2882 4131 2883 4131 2884 4132 2885 4132 2886 4132 2885 4133 2887 4133 2886 4133 2886 4134 2887 4134 2888 4134 2886 4135 2888 4135 2889 4135 2890 4136 2891 4136 2892 4136 2892 4137 2891 4137 2893 4137 2894 4138 2895 4138 2896 4138 2896 4139 2895 4139 2897 4139 2896 4140 2897 4140 2898 4140 2894 4141 2896 4141 2899 4141 2899 4142 2896 4142 2900 4142 2899 4143 2900 4143 2901 4143 2901 4144 2900 4144 2890 4144 2901 4145 2890 4145 2902 4145 2890 4146 2892 4146 2902 4146 2902 4147 2892 4147 2903 4147 2902 4148 2903 4148 2904 4148 2904 4149 2903 4149 2883 4149 2904 4150 2883 4150 2905 4150 2905 4151 2883 4151 2882 4151 2905 4152 2882 4152 2906 4152 2889 4153 2869 4153 2886 4153 2886 4154 2869 4154 2866 4154 2886 4155 2866 4155 2907 4155 2907 4156 2866 4156 2864 4156 2907 4157 2864 4157 2908 4157 2908 4158 2864 4158 2863 4158 2863 4159 2881 4159 2908 4159 2908 4160 2881 4160 2883 4160 2908 4161 2883 4161 2907 4161 2907 4162 2883 4162 2903 4162 2907 4163 2903 4163 2886 4163 2886 4164 2903 4164 2892 4164 2886 4165 2892 4165 2884 4165 2884 4166 2892 4166 2893 4166 2909 4167 2898 4167 2910 4167 899 4168 2911 4168 1858 4168 1858 4169 2911 4169 2912 4169 1858 4170 2912 4170 1860 4170 1860 4171 2912 4171 2913 4171 1860 4172 2913 4172 1862 4172 1862 4173 2913 4173 2914 4173 1862 4174 2914 4174 1864 4174 899 4175 2915 4175 2911 4175 2911 4176 2915 4176 2916 4176 2911 4177 2916 4177 2912 4177 2912 4178 2916 4178 2909 4178 2912 4179 2909 4179 2913 4179 2913 4180 2909 4180 2910 4180 2913 4181 2910 4181 2914 4181 2917 4182 1856 4182 1854 4182 2918 4183 2917 4183 2919 4183 2901 4184 2918 4184 2920 4184 2917 4185 1854 4185 2919 4185 2919 4186 1854 4186 1852 4186 2919 4187 1852 4187 2921 4187 2921 4188 1852 4188 1850 4188 2921 4189 1850 4189 2922 4189 2922 4190 1850 4190 1865 4190 2922 4191 1865 4191 2923 4191 2923 4192 1865 4192 1864 4192 2923 4193 1864 4193 2914 4193 2918 4194 2919 4194 2920 4194 2920 4195 2919 4195 2921 4195 2920 4196 2921 4196 2924 4196 2924 4197 2921 4197 2922 4197 2924 4198 2922 4198 2925 4198 2925 4199 2922 4199 2923 4199 2925 4200 2923 4200 2926 4200 2926 4201 2923 4201 2914 4201 2926 4202 2914 4202 2910 4202 2901 4203 2920 4203 2899 4203 2899 4204 2920 4204 2924 4204 2899 4205 2924 4205 2894 4205 2894 4206 2924 4206 2925 4206 2894 4207 2925 4207 2895 4207 2895 4208 2925 4208 2926 4208 2895 4209 2926 4209 2897 4209 2897 4210 2926 4210 2910 4210 2897 4211 2910 4211 2898 4211 2288 4212 1857 4212 1856 4212 2301 95 2927 95 2298 95 2298 95 2927 95 2928 95 2298 95 2928 95 2929 95 2930 4213 2301 4213 2931 4213 2931 4214 2301 4214 2288 4214 2931 95 2288 95 2932 95 2932 95 2288 95 1856 95 2933 95 2934 95 2301 95 1875 95 1877 95 2935 95 2935 95 1877 95 2298 95 2935 95 2298 95 2936 95 2936 95 2298 95 2937 95 2930 95 2938 95 2301 95 2301 4215 2938 4215 2939 4215 2301 4216 2939 4216 2940 4216 2934 95 2941 95 2301 95 2301 4217 2941 4217 2942 4217 2301 95 2942 95 2927 95 2940 95 2943 95 2301 95 2301 4218 2943 4218 2944 4218 2301 4219 2944 4219 2933 4219 2937 95 2298 95 2945 95 2945 95 2298 95 2929 95 2945 95 2929 95 2946 95 2946 95 2929 95 2947 95 2946 95 2947 95 2948 95 2948 95 2947 95 2949 95 2948 95 2949 95 2950 95 2950 95 2951 95 2948 95 2948 95 2951 95 2952 95 2948 95 2952 95 2953 95 2954 95 2955 95 2956 95 2953 95 2957 95 2948 95 2948 95 2957 95 2954 95 2948 95 2954 95 2958 95 2958 95 2954 95 2956 95 2959 4220 1879 4220 1869 4220 2960 4221 2959 4221 2961 4221 1885 4222 2960 4222 2962 4222 2959 4223 1869 4223 2961 4223 2961 4224 1869 4224 1871 4224 2961 4225 1871 4225 2963 4225 2963 4226 1871 4226 1873 4226 2963 4227 1873 4227 2964 4227 2964 4228 1873 4228 1875 4228 2964 4229 1875 4229 2965 4229 2960 4230 2961 4230 2962 4230 2962 4231 2961 4231 2963 4231 2962 4232 2963 4232 2966 4232 2966 4233 2963 4233 2964 4233 2966 4234 2964 4234 2967 4234 2967 4235 2964 4235 2965 4235 2967 4236 2965 4236 2968 4236 1885 4237 2962 4237 2969 4237 2969 4238 2962 4238 2966 4238 2969 4239 2966 4239 2970 4239 2970 4240 2966 4240 2967 4240 2970 4241 2967 4241 2971 4241 2971 4242 2967 4242 2968 4242 2971 4243 2968 4243 2972 4243 2973 4244 2959 4244 2960 4244 914 4245 2974 4245 1888 4245 1888 4246 2974 4246 2975 4246 1888 4247 2975 4247 1887 4247 1887 4248 2975 4248 2973 4248 1887 4249 2973 4249 1884 4249 1884 4250 2973 4250 2960 4250 1884 4251 2960 4251 1885 4251 914 4252 1866 4252 2974 4252 2974 4253 1866 4253 1878 4253 2974 4254 1878 4254 2975 4254 2975 4255 1878 4255 1880 4255 2975 4256 1880 4256 2973 4256 2973 4257 1880 4257 1879 4257 2973 4258 1879 4258 2959 4258 2976 4259 2802 4259 2800 4259 2977 4260 2978 4260 2979 4260 2979 4261 2978 4261 2980 4261 2979 4262 2980 4262 2981 4262 2981 4263 2980 4263 2982 4263 2970 4264 1905 4264 2969 4264 2969 4265 1905 4265 1885 4265 2970 4266 2971 4266 1905 4266 1905 4267 2971 4267 2972 4267 1905 4268 2972 4268 1906 4268 1906 4269 2972 4269 2983 4269 1906 4270 2983 4270 2977 4270 2977 4271 2983 4271 2984 4271 2977 4272 2984 4272 2978 4272 1909 4273 1908 4273 2977 4273 2977 4274 1908 4274 1907 4274 2977 4275 1907 4275 1906 4275 1912 4276 1911 4276 2985 4276 2985 4277 1911 4277 1910 4277 2986 4278 2987 4278 2976 4278 2987 4279 2986 4279 2988 4279 2976 4280 2800 4280 2986 4280 2986 4281 2800 4281 2788 4281 2986 4282 2788 4282 2989 4282 2989 4283 2788 4283 2789 4283 2989 4284 2789 4284 2985 4284 2985 4285 2789 4285 1913 4285 2985 4286 1913 4286 1912 4286 1910 4287 1909 4287 2985 4287 2985 4288 1909 4288 2977 4288 2985 4289 2977 4289 2989 4289 2989 4290 2977 4290 2979 4290 2989 4291 2979 4291 2986 4291 2986 4292 2979 4292 2981 4292 2986 4293 2981 4293 2988 4293 2988 4294 2981 4294 2982 4294 2990 4295 2991 4295 2239 4295 2233 4296 2992 4296 2235 4296 2235 4297 2992 4297 2990 4297 2235 4298 2990 4298 2237 4298 2237 4299 2990 4299 2239 4299 2228 4300 2993 4300 2229 4300 2229 4301 2993 4301 2992 4301 2229 4302 2992 4302 2231 4302 2231 4303 2992 4303 2233 4303 2994 4304 1914 4304 2995 4304 2995 4305 1914 4305 2616 4305 2226 4306 1923 4306 1924 4306 2227 4307 2996 4307 2228 4307 2228 4308 2996 4308 2997 4308 2228 4309 2997 4309 2993 4309 2994 4310 2998 4310 1914 4310 1914 4311 2998 4311 2999 4311 1914 4312 2999 4312 1924 4312 1924 4313 2999 4313 2996 4313 1924 4314 2996 4314 2226 4314 2226 4315 2996 4315 2227 4315 3000 4316 3001 4316 3002 4316 3003 4317 3004 4317 3005 4317 3005 4318 3004 4318 3006 4318 3005 4319 3006 4319 3002 4319 3002 4320 3006 4320 3007 4320 3002 4321 3007 4321 3000 4321 3005 4322 3008 4322 3009 4322 3003 4323 3005 4323 1927 4323 1927 4324 3005 4324 3009 4324 1927 4325 3009 4325 1928 4325 3008 4326 3005 4326 3010 4326 3010 4327 3005 4327 3002 4327 3010 4328 3002 4328 3011 4328 3010 4329 3011 4329 3012 4329 3008 4330 3010 4330 3013 4330 3009 4331 3008 4331 3014 4331 1928 4332 3009 4332 3015 4332 1928 4333 3015 4333 1950 4333 1950 4334 3015 4334 3016 4334 1950 4335 3016 4335 1952 4335 1952 4336 3016 4336 3017 4336 1952 4337 3017 4337 1954 4337 1954 4338 3017 4338 1956 4338 1956 4339 3017 4339 3018 4339 1956 4340 3018 4340 1958 4340 1958 4341 3018 4341 3019 4341 1958 4342 3019 4342 1960 4342 3010 4343 3012 4343 3013 4343 3013 4344 3012 4344 3020 4344 3013 4345 3020 4345 3021 4345 3021 4346 3020 4346 3022 4346 3021 4347 3022 4347 3023 4347 3023 4348 3022 4348 3024 4348 3023 4349 3024 4349 3025 4349 3025 4350 3024 4350 3026 4350 3025 4351 3026 4351 3027 4351 3027 4352 3026 4352 3028 4352 3027 4353 3028 4353 3029 4353 3029 4354 3028 4354 3030 4354 3029 4355 3030 4355 3031 4355 3031 4356 3030 4356 3032 4356 3031 4357 3032 4357 3033 4357 3033 4358 3032 4358 3034 4358 3033 4359 3034 4359 3035 4359 3035 4360 3034 4360 2434 4360 3035 4361 2434 4361 2425 4361 3008 4362 3013 4362 3014 4362 3014 4363 3013 4363 3021 4363 3014 4364 3021 4364 3036 4364 3036 4365 3021 4365 3023 4365 3036 4366 3023 4366 3037 4366 3037 4367 3023 4367 3025 4367 3037 4368 3025 4368 3038 4368 3038 4369 3025 4369 3027 4369 3038 4370 3027 4370 3039 4370 3039 4371 3027 4371 3029 4371 3039 4372 3029 4372 3040 4372 3040 4373 3029 4373 3031 4373 3040 4374 3031 4374 3041 4374 3041 4375 3031 4375 3033 4375 3041 4376 3033 4376 3042 4376 3042 4377 3033 4377 3035 4377 3042 4378 3035 4378 3043 4378 3043 4379 3035 4379 2425 4379 3043 4380 2425 4380 2417 4380 3009 4381 3014 4381 3015 4381 3015 4382 3014 4382 3036 4382 3015 4383 3036 4383 3016 4383 3016 4384 3036 4384 3037 4384 3016 4385 3037 4385 3017 4385 3017 4386 3037 4386 3038 4386 3017 4387 3038 4387 3018 4387 3018 4388 3038 4388 3039 4388 3018 4389 3039 4389 3019 4389 3019 4390 3039 4390 3040 4390 3019 4391 3040 4391 3044 4391 3044 4392 3040 4392 3041 4392 3044 4393 3041 4393 3045 4393 3045 4394 3041 4394 3042 4394 3045 4395 3042 4395 3046 4395 3046 4396 3042 4396 3043 4396 3046 4397 3043 4397 3047 4397 3047 4398 3043 4398 2417 4398 3047 4399 2417 4399 2405 4399 1960 4400 3019 4400 1961 4400 1961 4401 3019 4401 3044 4401 1961 4402 3044 4402 1946 4402 1946 4403 3044 4403 3045 4403 1946 4404 3045 4404 1944 4404 1944 4405 3045 4405 3046 4405 1944 4406 3046 4406 1942 4406 1942 4407 3046 4407 3047 4407 1942 4408 3047 4408 1940 4408 1940 4409 3047 4409 2405 4409 1940 4410 2405 4410 1938 4410 2003 4411 2001 4411 3048 4411 3049 4412 3048 4412 3050 4412 3051 4413 3052 4413 3048 4413 3048 4414 3052 4414 3053 4414 3048 4415 3053 4415 3054 4415 3054 4416 3055 4416 3048 4416 3048 4417 3055 4417 3056 4417 3048 4418 3056 4418 3050 4418 3057 4419 3058 4419 3059 4419 3059 4420 3058 4420 3060 4420 3059 4421 3060 4421 3051 4421 3051 4422 3060 4422 3061 4422 3051 4423 3061 4423 3052 4423 3062 4424 3063 4424 3064 4424 3064 4425 3063 4425 3057 4425 1979 4426 3065 4426 3066 4426 3066 4427 3065 4427 3067 4427 3066 4428 3067 4428 3064 4428 3064 4429 3067 4429 3068 4429 3064 4430 3068 4430 3062 4430 1979 4431 1977 4431 3065 4431 3065 4432 1977 4432 1975 4432 3065 4433 1975 4433 3069 4433 1975 4434 1973 4434 3069 4434 3069 4435 1973 4435 1971 4435 3069 4436 1971 4436 3070 4436 3070 4437 1971 4437 1969 4437 3070 4438 1969 4438 1968 4438 1968 4439 2054 4439 3070 4439 3070 4440 2054 4440 2052 4440 3070 4441 2052 4441 2050 4441 2050 4442 2048 4442 3070 4442 3070 4443 2048 4443 2047 4443 3070 4444 2047 4444 2040 4444 1987 4445 1985 4445 3064 4445 3064 4446 1985 4446 1983 4446 3064 4447 1983 4447 3066 4447 3066 4448 1983 4448 1981 4448 3066 4449 1981 4449 1979 4449 3057 4450 3059 4450 3064 4450 3064 4451 3059 4451 1989 4451 3064 4452 1989 4452 1987 4452 1997 4453 1995 4453 3051 4453 3051 4454 1995 4454 1993 4454 3051 4455 1993 4455 3059 4455 3059 4456 1993 4456 1991 4456 3059 4457 1991 4457 1989 4457 3048 4458 2001 4458 3051 4458 3051 4459 2001 4459 1999 4459 3051 4460 1999 4460 1997 4460 2003 4461 3048 4461 2005 4461 2005 4462 3048 4462 3049 4462 2005 4463 3049 4463 2007 4463 3071 4464 2011 4464 3049 4464 3049 4465 2011 4465 2009 4465 3049 4466 2009 4466 2007 4466 2019 4467 2017 4467 3072 4467 3072 4468 2017 4468 2015 4468 3072 4469 2015 4469 3071 4469 3071 4470 2015 4470 2013 4470 3071 4471 2013 4471 2011 4471 3050 4472 3073 4472 3049 4472 3049 4473 3073 4473 3074 4473 3049 4474 3074 4474 3071 4474 3071 4475 3074 4475 3075 4475 3071 4476 3075 4476 3072 4476 2028 4477 2027 4477 2121 4477 2026 4478 2543 4478 2027 4478 2121 4479 2030 4479 2029 4479 2024 4480 2030 4480 2121 4480 2023 4481 2024 4481 2121 4481 1964 4482 2021 4482 2120 4482 2120 4483 2021 4483 2023 4483 2120 4484 2023 4484 2121 4484 2543 4485 2542 4485 2027 4485 2027 4486 2542 4486 2121 4486 2029 4487 2028 4487 2121 4487 2037 4488 2039 4488 3076 4488 2042 4489 2037 4489 3077 4489 3077 4490 2037 4490 3076 4490 3077 4491 3076 4491 3078 4491 3078 4492 3076 4492 3079 4492 3078 4493 3079 4493 3080 4493 3080 4494 3079 4494 3081 4494 3080 4495 3081 4495 3082 4495 3082 4496 3081 4496 3083 4496 2040 4497 2042 4497 3084 4497 3084 4498 2042 4498 3077 4498 3084 4499 3077 4499 3085 4499 3085 4500 3077 4500 3078 4500 3085 4501 3078 4501 3086 4501 3086 4502 3078 4502 3080 4502 3086 4503 3080 4503 3087 4503 3087 4504 3080 4504 3082 4504 2061 4505 2063 4505 3088 4505 3088 4506 2063 4506 3089 4506 3088 4507 3089 4507 3090 4507 3090 4508 3089 4508 3091 4508 3090 4509 3091 4509 3092 4509 3092 4510 3091 4510 3093 4510 3092 4511 3093 4511 3094 4511 3094 4512 3093 4512 3095 4512 2039 4513 2061 4513 3076 4513 3076 4514 2061 4514 3088 4514 3076 4515 3088 4515 3079 4515 3079 4516 3088 4516 3090 4516 3079 4517 3090 4517 3081 4517 3081 4518 3090 4518 3092 4518 3081 4519 3092 4519 3083 4519 3083 4520 3092 4520 3094 4520 3096 4521 2112 4521 2097 4521 2624 4522 2623 4522 3096 4522 3096 4523 2097 4523 2624 4523 2624 4524 2097 4524 2095 4524 2624 4525 2095 4525 2625 4525 2625 4526 2095 4526 2094 4526 2625 4527 2094 4527 2626 4527 2626 4528 2094 4528 2108 4528 2626 4529 2108 4529 2627 4529 2627 4530 2108 4530 2109 4530 2627 4531 2109 4531 2620 4531 2620 4532 2109 4532 2101 4532 2620 4533 2101 4533 2619 4533 3097 4534 3098 4534 3099 4534 3099 4535 3098 4535 3100 4535 3101 4536 3102 4536 2093 4536 2111 4537 2112 4537 3103 4537 3103 4538 2112 4538 3104 4538 3103 4539 3104 4539 3105 4539 3105 4540 3104 4540 3106 4540 3105 4541 3106 4541 3107 4541 3107 4542 3106 4542 3108 4542 3107 4543 3108 4543 3109 4543 3109 4544 3108 4544 3110 4544 3101 4545 2093 4545 3111 4545 3111 4546 2093 4546 2092 4546 3111 4547 2092 4547 3112 4547 3112 4548 2092 4548 3113 4548 3112 4549 3113 4549 3114 4549 3114 4550 3113 4550 3115 4550 3114 4551 3115 4551 3116 4551 3116 4552 3115 4552 3117 4552 3116 4553 3117 4553 3118 4553 3119 4554 3120 4554 3118 4554 3121 4555 3122 4555 3120 4555 3123 4556 2765 4556 3097 4556 3097 4557 3099 4557 3123 4557 3123 4558 3099 4558 2776 4558 3123 4559 2776 4559 2774 4559 3122 4560 3121 4560 3124 4560 3124 4561 3121 4561 3125 4561 3124 4562 3125 4562 3100 4562 3100 4563 3125 4563 2780 4563 3100 4564 2780 4564 3099 4564 3099 4565 2780 4565 2778 4565 3099 4566 2778 4566 2776 4566 3126 4567 3127 4567 3121 4567 3121 4568 3127 4568 3128 4568 3121 4569 3128 4569 3125 4569 3125 4570 3128 4570 3129 4570 3125 4571 3129 4571 2780 4571 3120 4572 3119 4572 3121 4572 3121 4573 3119 4573 3130 4573 3121 4574 3130 4574 3126 4574 3126 4575 3130 4575 3131 4575 3126 4576 3131 4576 3127 4576 3109 4577 3132 4577 3107 4577 3107 4578 3132 4578 3133 4578 3107 4579 3133 4579 3105 4579 3105 4580 3133 4580 3134 4580 3105 4581 3134 4581 3103 4581 3103 4582 3134 4582 3135 4582 3103 4583 3135 4583 2111 4583 2111 4584 3135 4584 2110 4584 2092 4585 2110 4585 3113 4585 3113 4586 2110 4586 3135 4586 3113 4587 3135 4587 3115 4587 3115 4588 3135 4588 3134 4588 3115 4589 3134 4589 3117 4589 3117 4590 3134 4590 3133 4590 3117 4591 3133 4591 3118 4591 3118 4592 3133 4592 3132 4592 3118 4593 3132 4593 3119 4593 3119 4594 3132 4594 3109 4594 3119 4595 3109 4595 3130 4595 3130 4596 3109 4596 3110 4596 3130 4597 3110 4597 3131 4597 3136 4598 3137 4598 3138 4598 3139 4599 3140 4599 3141 4599 3142 4600 3138 4600 3143 4600 2093 4601 3102 4601 2072 4601 2072 4602 3102 4602 3144 4602 2072 4603 3144 4603 3142 4603 3145 4604 3136 4604 3139 4604 3137 4605 3136 4605 3146 4605 3139 4606 3141 4606 3145 4606 3145 4607 3141 4607 3147 4607 3145 4608 3147 4608 3148 4608 3148 4609 3147 4609 3149 4609 3148 4610 3149 4610 3150 4610 3150 4611 3149 4611 3151 4611 3150 4612 3151 4612 3152 4612 3152 4613 3151 4613 3153 4613 3152 4614 3153 4614 3154 4614 3154 4615 3153 4615 3155 4615 3154 4616 3155 4616 3156 4616 3156 4617 3155 4617 3157 4617 3156 4618 3157 4618 3158 4618 3158 4619 3157 4619 3159 4619 3158 4620 3159 4620 3160 4620 3160 4621 3159 4621 3161 4621 3160 4622 3161 4622 3162 4622 3162 4623 3161 4623 3163 4623 3162 4624 3163 4624 3164 4624 3164 4625 3163 4625 3165 4625 3164 4626 3165 4626 3166 4626 3166 4627 3165 4627 3095 4627 3166 4628 3095 4628 3093 4628 3136 4629 3145 4629 3146 4629 3146 4630 3145 4630 3148 4630 3146 4631 3148 4631 3167 4631 3167 4632 3148 4632 3150 4632 3167 4633 3150 4633 3168 4633 3168 4634 3150 4634 3152 4634 3168 4635 3152 4635 3169 4635 3169 4636 3152 4636 3154 4636 3169 4637 3154 4637 3170 4637 3170 4638 3154 4638 3156 4638 3170 4639 3156 4639 3171 4639 3171 4640 3156 4640 3158 4640 3171 4641 3158 4641 3172 4641 3172 4642 3158 4642 3160 4642 3172 4643 3160 4643 3173 4643 3173 4644 3160 4644 3162 4644 3173 4645 3162 4645 3174 4645 3174 4646 3162 4646 3164 4646 3174 4647 3164 4647 3175 4647 3175 4648 3164 4648 3166 4648 3175 4649 3166 4649 3176 4649 3176 4650 3166 4650 3093 4650 3176 4651 3093 4651 3091 4651 3138 4652 3137 4652 3143 4652 3143 4653 3137 4653 3146 4653 3143 4654 3146 4654 3177 4654 3177 4655 3146 4655 3167 4655 3177 4656 3167 4656 3178 4656 3178 4657 3167 4657 3168 4657 3178 4658 3168 4658 3179 4658 3179 4659 3168 4659 3169 4659 3179 4660 3169 4660 3180 4660 3180 4661 3169 4661 3170 4661 3180 4662 3170 4662 3181 4662 3181 4663 3170 4663 3171 4663 3181 4664 3171 4664 3182 4664 3182 4665 3171 4665 3172 4665 3182 4666 3172 4666 3183 4666 3183 4667 3172 4667 3173 4667 3183 4668 3173 4668 3184 4668 3184 4669 3173 4669 3174 4669 3184 4670 3174 4670 3185 4670 3185 4671 3174 4671 3175 4671 3185 4672 3175 4672 3186 4672 3186 4673 3175 4673 3176 4673 3186 4674 3176 4674 3187 4674 3187 4675 3176 4675 3091 4675 3187 4676 3091 4676 3089 4676 3142 4677 3143 4677 2072 4677 2072 4678 3143 4678 3177 4678 2072 4679 3177 4679 2073 4679 2073 4680 3177 4680 3178 4680 2073 4681 3178 4681 2075 4681 2075 4682 3178 4682 3179 4682 2075 4683 3179 4683 2076 4683 2076 4684 3179 4684 3180 4684 2076 4685 3180 4685 2113 4685 2113 4686 3180 4686 3181 4686 2113 4687 3181 4687 2117 4687 2117 4688 3181 4688 3182 4688 2117 4689 3182 4689 2088 4689 2088 4690 3182 4690 3183 4690 2088 4691 3183 4691 2089 4691 2089 4692 3183 4692 3184 4692 2089 4693 3184 4693 2090 4693 2090 4694 3184 4694 3185 4694 2090 4695 3185 4695 2091 4695 2091 4696 3185 4696 3186 4696 2091 4697 3186 4697 2086 4697 2086 4698 3186 4698 3187 4698 2086 4699 3187 4699 2087 4699 2087 4700 3187 4700 3089 4700 2087 4701 3089 4701 2063 4701 2239 95 2991 95 2154 95 2154 4702 2991 4702 3188 4702 2154 4703 3188 4703 2155 4703 2155 95 3188 95 2152 95 3189 95 3190 95 2152 95 2152 4704 3190 4704 3191 4704 2152 4705 3191 4705 2153 4705 3188 4706 3192 4706 2152 4706 2152 4707 3192 4707 3193 4707 2152 4708 3193 4708 3194 4708 3195 95 3196 95 3197 95 3194 4709 3198 4709 2152 4709 2152 4710 3198 4710 3199 4710 2152 95 3199 95 3200 95 3197 95 3201 95 3195 95 3195 95 3201 95 3202 95 3195 95 3202 95 3200 95 3200 95 3202 95 3203 95 3200 95 3203 95 2152 95 2152 95 3203 95 3204 95 2152 4711 3204 4711 3189 4711 1367 4712 3205 4712 2175 4712 2175 4713 3205 4713 3206 4713 2175 4714 3206 4714 2177 4714 2177 4715 3206 4715 3207 4715 1367 4716 2144 4716 3208 4716 3208 4717 2144 4717 2143 4717 3208 4718 2143 4718 3209 4718 3209 4719 2143 4719 2142 4719 3209 4720 2142 4720 3210 4720 3210 4721 2142 4721 2145 4721 3210 4722 2145 4722 3211 4722 3211 4723 2145 4723 2147 4723 3211 4724 2147 4724 3212 4724 3212 4725 2147 4725 2148 4725 3212 4726 2148 4726 3213 4726 3213 4727 2148 4727 2150 4727 3213 4728 2150 4728 3214 4728 3214 4729 2150 4729 2151 4729 3214 4730 2151 4730 3215 4730 1367 4731 3208 4731 3205 4731 3205 4732 3208 4732 3209 4732 3205 4733 3209 4733 3206 4733 3206 4734 3209 4734 3210 4734 3206 4735 3210 4735 3207 4735 3207 4736 3210 4736 3211 4736 3207 4737 3211 4737 3216 4737 3216 4738 3211 4738 3212 4738 3216 4739 3212 4739 3217 4739 3217 4740 3212 4740 3213 4740 3217 4741 3213 4741 3218 4741 3218 4742 3213 4742 3214 4742 3218 4743 3214 4743 3219 4743 3219 4744 3214 4744 3215 4744 3219 4745 3215 4745 3220 4745 2162 4746 2171 4746 3220 4746 3220 4747 2171 4747 2170 4747 3220 4748 2170 4748 3219 4748 3219 4749 2170 4749 2174 4749 3219 4750 2174 4750 3218 4750 3218 4751 2174 4751 2173 4751 3218 4752 2173 4752 3217 4752 3217 4753 2173 4753 2172 4753 3217 4754 2172 4754 3216 4754 3216 4755 2172 4755 2182 4755 3216 4756 2182 4756 3207 4756 3207 4757 2182 4757 2178 4757 3207 4758 2178 4758 2177 4758 2163 4759 2162 4759 3221 4759 3221 4760 2162 4760 3220 4760 3221 4761 3220 4761 3222 4761 3222 4762 3220 4762 3215 4762 3222 4763 3215 4763 2153 4763 2153 4764 3215 4764 2151 4764 3190 4765 3189 4765 3223 4765 3223 4766 3189 4766 3224 4766 3223 4767 3224 4767 3225 4767 3225 4768 3224 4768 3226 4768 3225 4769 3226 4769 2167 4769 2167 4770 3226 4770 2168 4770 3191 4771 3190 4771 3227 4771 3227 4772 3190 4772 3223 4772 3227 4773 3223 4773 3228 4773 3228 4774 3223 4774 3225 4774 3228 4775 3225 4775 2165 4775 2165 4776 3225 4776 2167 4776 2153 4777 3191 4777 3222 4777 3222 4778 3191 4778 3227 4778 3222 4779 3227 4779 3221 4779 3221 4780 3227 4780 3228 4780 3221 4781 3228 4781 2163 4781 2163 4782 3228 4782 2165 4782 2792 4783 2793 4783 3229 4783 3229 4784 2793 4784 3230 4784 3229 4785 3230 4785 3231 4785 3231 4786 3230 4786 3232 4786 3231 4787 3232 4787 3233 4787 3233 4788 3232 4788 3234 4788 3233 4789 3234 4789 3235 4789 3235 4790 3234 4790 2832 4790 2791 4791 2792 4791 3236 4791 3236 4792 2792 4792 3229 4792 3236 4793 3229 4793 3237 4793 3237 4794 3229 4794 3231 4794 3237 4795 3231 4795 3238 4795 3238 4796 3231 4796 3233 4796 3238 4797 3233 4797 3239 4797 3239 4798 3233 4798 3235 4798 1804 4799 2791 4799 2808 4799 2808 4800 2791 4800 3236 4800 2808 4801 3236 4801 2805 4801 2805 4802 3236 4802 3237 4802 2805 4803 3237 4803 2806 4803 2806 4804 3237 4804 3238 4804 2806 4805 3238 4805 2824 4805 2824 4806 3238 4806 3239 4806 2482 4807 2354 4807 2353 4807 2510 4808 2513 4808 3240 4808 2510 4809 3240 4809 2511 4809 2511 4810 3240 4810 3241 4810 2511 4811 3241 4811 2523 4811 2523 4812 3241 4812 3242 4812 2523 4813 3242 4813 2520 4813 2520 4814 3242 4814 3243 4814 2520 4815 3243 4815 2348 4815 2348 4816 3243 4816 3244 4816 3244 4817 3243 4817 3242 4817 3244 4818 3242 4818 3245 4818 3245 4819 3242 4819 3241 4819 3245 4820 3241 4820 3246 4820 3246 4821 3241 4821 3240 4821 3246 4822 3240 4822 3247 4822 2483 4823 3247 4823 2489 4823 2489 4824 3247 4824 3240 4824 2489 4825 3240 4825 2495 4825 2495 4826 3240 4826 2513 4826 2495 4827 2513 4827 2501 4827 2483 4828 2482 4828 3247 4828 3247 4829 2482 4829 2353 4829 3247 4830 2353 4830 3246 4830 3246 4831 2353 4831 2352 4831 3246 4832 2352 4832 3245 4832 3245 4833 2352 4833 2351 4833 3245 4834 2351 4834 3244 4834 3244 4835 2351 4835 2349 4835 3244 4836 2349 4836 2348 4836 2503 4837 2643 4837 1758 4837 2515 4838 3248 4838 3249 4838 2508 4839 2506 4839 3249 4839 3249 4840 2506 4840 2505 4840 3249 4841 2505 4841 2515 4841 2643 4842 2503 4842 2644 4842 2503 4843 2502 4843 2644 4843 2644 4844 2502 4844 2508 4844 2644 4845 2508 4845 2652 4845 2652 4846 2508 4846 3249 4846 2652 4847 3249 4847 2648 4847 2648 4848 3249 4848 3248 4848 2573 4849 2572 4849 3250 4849 2582 4850 2670 4850 2571 4850 2571 4851 2670 4851 2669 4851 2571 4852 2669 4852 2572 4852 2572 4853 2669 4853 2668 4853 2572 4854 2668 4854 3250 4854 3250 4855 2668 4855 2666 4855 3250 4856 2666 4856 3251 4856 3251 4857 2666 4857 2665 4857 3251 4858 2665 4858 3252 4858 3252 4859 2665 4859 2674 4859 3252 4860 2674 4860 3253 4860 3253 4861 2674 4861 2673 4861 3253 4862 2673 4862 3254 4862 3254 4863 2673 4863 2671 4863 3254 4864 2671 4864 3255 4864 3255 4865 2671 4865 2602 4865 2602 4866 2601 4866 3255 4866 3255 4867 2601 4867 2600 4867 3255 4868 2600 4868 3254 4868 3254 4869 2600 4869 2598 4869 3254 4870 2598 4870 3253 4870 3253 4871 2598 4871 2597 4871 3253 4872 2597 4872 3252 4872 3252 4873 2597 4873 2603 4873 3252 4874 2603 4874 3251 4874 3251 4875 2603 4875 2564 4875 3251 4876 2564 4876 3250 4876 3250 4877 2564 4877 2563 4877 3250 4878 2563 4878 2573 4878 2604 4879 2591 4879 2592 4879 2555 4880 2565 4880 2593 4880 2593 4881 2565 4881 2566 4881 2593 4882 2566 4882 2592 4882 2592 4883 2566 4883 2564 4883 2592 4884 2564 4884 2604 4884 1693 4885 2585 4885 2604 4885 2604 4886 2585 4886 2584 4886 2604 4887 2584 4887 2591 4887 3256 4888 3257 4888 3258 4888 2612 4889 2611 4889 3259 4889 3259 4890 2611 4890 3260 4890 3260 4891 2611 4891 2609 4891 3260 4892 2609 4892 3261 4892 3261 4893 2609 4893 3262 4893 3262 4894 2609 4894 2607 4894 3262 4895 2607 4895 3263 4895 3263 4896 2607 4896 2606 4896 3263 4897 2606 4897 3264 4897 3265 4898 3266 4898 3267 4898 3267 4899 3266 4899 3256 4899 3267 4900 3256 4900 3268 4900 3268 4901 3256 4901 3258 4901 3264 4902 2606 4902 3265 4902 3265 4903 2606 4903 2595 4903 3265 4904 2595 4904 3266 4904 3266 4905 2595 4905 2594 4905 3266 4906 2594 4906 3256 4906 3256 4907 2594 4907 2614 4907 3256 4908 2614 4908 3257 4908 3269 4909 2616 4909 2615 4909 3261 4910 3269 4910 3260 4910 3260 4911 3269 4911 2615 4911 3260 4912 2615 4912 3259 4912 3259 4913 2615 4913 2617 4913 3259 4914 2617 4914 2612 4914 2786 4915 2784 4915 3270 4915 2633 4916 2786 4916 3271 4916 2786 4917 3270 4917 3271 4917 3271 4918 3270 4918 3272 4918 3271 4919 3272 4919 3273 4919 3273 4920 3272 4920 3274 4920 3273 4921 3274 4921 3275 4921 3275 4922 3274 4922 3127 4922 3275 4923 3127 4923 3276 4923 2633 4924 3271 4924 2634 4924 2634 4925 3271 4925 3273 4925 2634 4926 3273 4926 2635 4926 2635 4927 3273 4927 3275 4927 2635 4928 3275 4928 2630 4928 2630 4929 3275 4929 3276 4929 2630 4930 3276 4930 2631 4930 3276 4931 3127 4931 3131 4931 2631 4932 3276 4932 3277 4932 3276 4933 3131 4933 3277 4933 3277 4934 3131 4934 3110 4934 3277 4935 3110 4935 3278 4935 3278 4936 3110 4936 3108 4936 3278 4937 3108 4937 3279 4937 3279 4938 3108 4938 3106 4938 3279 4939 3106 4939 3280 4939 3280 4940 3106 4940 3104 4940 3280 4941 3104 4941 3281 4941 3281 4942 3104 4942 2112 4942 3281 4943 2112 4943 3096 4943 2631 4944 3277 4944 2632 4944 2632 4945 3277 4945 3278 4945 2632 4946 3278 4946 2628 4946 2628 4947 3278 4947 3279 4947 2628 4948 3279 4948 2629 4948 2629 4949 3279 4949 3280 4949 2629 4950 3280 4950 2621 4950 2621 4951 3280 4951 3281 4951 2621 4952 3281 4952 2622 4952 2622 4953 3281 4953 3096 4953 2622 4954 3096 4954 2623 4954 2619 4955 2101 4955 2641 4955 2619 4956 2641 4956 2618 4956 2618 4957 2641 4957 2637 4957 2618 4958 2637 4958 1757 4958 2742 4959 3282 4959 2743 4959 2743 4960 3282 4960 2744 4960 2744 4961 3282 4961 3283 4961 2744 4962 3283 4962 2740 4962 3284 4963 2735 4963 3283 4963 3283 4964 2735 4964 2741 4964 3283 4965 2741 4965 2740 4965 2718 4966 1761 4966 2733 4966 2718 4967 2733 4967 3285 4967 3285 4968 2733 4968 2732 4968 3285 4969 2732 4969 3286 4969 3286 4970 2732 4970 2731 4970 3286 4971 2731 4971 3287 4971 3287 4972 2731 4972 2730 4972 3287 4973 2730 4973 3284 4973 3284 4974 2730 4974 2737 4974 3284 4975 2737 4975 2735 4975 2742 4976 2752 4976 3282 4976 3282 4977 2752 4977 2754 4977 3282 4978 2754 4978 3283 4978 3283 4979 2754 4979 2758 4979 3283 4980 2758 4980 3284 4980 3284 4981 2758 4981 2757 4981 3284 4982 2757 4982 3287 4982 3287 4983 2757 4983 2761 4983 3287 4984 2761 4984 3286 4984 3286 4985 2761 4985 2759 4985 3286 4986 2759 4986 3285 4986 3285 4987 2759 4987 2722 4987 3285 4988 2722 4988 2718 4988 3111 4989 3288 4989 3101 4989 2763 4990 3289 4990 806 4990 3290 4991 2750 4991 3291 4991 3291 4992 2750 4992 2749 4992 3291 4993 2749 4993 2859 4993 3289 4994 2763 4994 3292 4994 2763 4995 2762 4995 3292 4995 3292 4996 2762 4996 2760 4996 3292 4997 2760 4997 3290 4997 3290 4998 2760 4998 2756 4998 3290 4999 2756 4999 2750 4999 3097 5000 2765 5000 3289 5000 3289 5001 2765 5001 2766 5001 3289 5002 2766 5002 806 5002 3097 5003 3289 5003 3098 5003 3098 5004 3289 5004 3292 5004 3098 5005 3292 5005 3100 5005 3293 5006 3294 5006 3295 5006 3295 5007 3294 5007 3120 5007 3295 5008 3120 5008 3122 5008 3112 5009 3114 5009 3296 5009 3296 5010 3114 5010 3116 5010 3296 5011 3116 5011 3297 5011 3297 5012 3116 5012 3118 5012 3297 5013 3118 5013 3298 5013 3298 5014 3118 5014 3299 5014 3111 5015 3112 5015 3288 5015 3288 5016 3112 5016 3296 5016 3288 5017 3296 5017 3300 5017 3300 5018 3296 5018 3297 5018 3300 5019 3297 5019 3301 5019 3301 5020 3297 5020 3302 5020 3302 5021 3297 5021 3298 5021 3302 5022 3298 5022 3303 5022 3304 5023 3305 5023 3306 5023 3306 5024 3305 5024 3307 5024 3308 5025 3309 5025 3310 5025 3310 5026 3309 5026 3311 5026 3310 5027 3311 5027 3307 5027 3307 5028 3311 5028 3312 5028 3307 5029 3312 5029 3306 5029 2859 5030 2857 5030 3293 5030 3293 5031 2857 5031 2856 5031 3293 5032 2856 5032 2853 5032 2859 5033 3293 5033 3291 5033 3291 5034 3293 5034 3295 5034 3291 5035 3295 5035 3290 5035 3290 5036 3295 5036 3122 5036 3290 5037 3122 5037 3292 5037 3292 5038 3122 5038 3124 5038 3292 5039 3124 5039 3100 5039 3304 5040 3303 5040 3305 5040 3305 5041 3303 5041 3298 5041 3305 5042 3298 5042 3307 5042 3307 5043 3298 5043 3299 5043 3307 5044 3299 5044 3310 5044 3118 5045 3120 5045 3299 5045 3299 5046 3120 5046 3294 5046 3299 5047 3294 5047 3310 5047 3310 5048 3294 5048 3293 5048 3310 5049 3293 5049 3308 5049 3308 5050 3293 5050 2853 5050 3308 5051 2853 5051 2854 5051 2764 5052 2765 5052 2770 5052 2770 5053 2765 5053 3123 5053 2770 5054 3123 5054 2771 5054 2771 5055 3123 5055 2774 5055 3270 5056 2784 5056 2785 5056 3274 5057 3272 5057 3313 5057 3313 5058 3272 5058 3270 5058 3270 5059 2785 5059 3313 5059 3313 5060 2785 5060 2783 5060 3313 5061 2783 5061 2781 5061 3127 5062 3274 5062 3128 5062 3128 5063 3274 5063 3313 5063 3128 5064 3313 5064 3129 5064 3129 5065 3313 5065 2781 5065 3129 5066 2781 5066 2780 5066 3314 5067 2804 5067 3315 5067 3315 5068 2804 5068 2803 5068 3315 5069 2803 5069 3316 5069 3316 5070 2803 5070 2802 5070 3232 5071 3230 5071 3317 5071 2804 5072 3318 5072 3319 5072 3320 5073 2831 5073 2835 5073 3320 5074 2835 5074 3321 5074 3321 5075 2835 5075 2833 5075 3321 5076 2833 5076 3322 5076 3322 5077 2833 5077 2832 5077 3322 5078 2832 5078 3234 5078 2842 5079 2831 5079 3318 5079 3318 5080 2831 5080 3320 5080 3318 5081 3320 5081 3319 5081 3319 5082 3320 5082 3321 5082 3319 5083 3321 5083 3323 5083 3323 5084 3321 5084 3322 5084 3323 5085 3322 5085 3317 5085 3317 5086 3322 5086 3234 5086 3317 5087 3234 5087 3232 5087 2804 5088 3319 5088 2798 5088 2798 5089 3319 5089 3323 5089 2798 5090 3323 5090 2796 5090 2796 5091 3323 5091 3317 5091 2796 5092 3317 5092 2794 5092 2794 5093 3317 5093 3230 5093 2794 5094 3230 5094 2793 5094 2804 5095 3314 5095 3318 5095 3318 5096 3314 5096 3324 5096 3318 5097 3324 5097 2842 5097 2842 5098 3324 5098 2843 5098 3325 5099 2850 5099 2849 5099 3326 5100 3325 5100 3327 5100 3326 5101 3327 5101 3328 5101 3328 5102 3327 5102 3329 5102 3328 5103 3329 5103 3330 5103 3330 5104 3329 5104 3331 5104 3330 5105 3331 5105 3332 5105 3332 5106 3331 5106 3333 5106 3332 5107 3333 5107 3334 5107 3334 5108 3333 5108 3335 5108 3334 5109 3335 5109 3336 5109 3336 5110 3335 5110 3337 5110 3336 5111 3337 5111 3338 5111 3325 5112 2849 5112 3327 5112 3327 5113 2849 5113 2848 5113 3327 5114 2848 5114 3329 5114 3329 5115 2848 5115 2847 5115 3329 5116 2847 5116 3331 5116 3331 5117 2847 5117 2846 5117 3331 5118 2846 5118 3333 5118 3333 5119 2846 5119 2845 5119 3333 5120 2845 5120 3335 5120 3335 5121 2845 5121 2844 5121 3335 5122 2844 5122 3337 5122 3337 5123 2844 5123 2843 5123 3337 5124 2843 5124 3324 5124 3338 5125 3337 5125 3339 5125 3339 5126 3337 5126 3324 5126 3339 5127 3324 5127 3314 5127 3340 5128 2830 5128 2829 5128 3340 5129 3341 5129 3342 5129 3342 5130 3343 5130 3340 5130 3340 5131 3343 5131 3344 5131 3340 5132 3344 5132 3311 5132 3345 5133 3346 5133 3347 5133 3346 5134 3348 5134 3347 5134 3347 5135 3348 5135 3349 5135 3347 5136 3349 5136 3350 5136 2850 5137 3345 5137 2829 5137 2829 5138 3345 5138 3347 5138 2829 5139 3347 5139 3340 5139 3340 5140 3347 5140 3350 5140 3340 5141 3350 5141 3341 5141 2867 5142 2168 5142 3351 5142 3351 5143 2168 5143 3226 5143 3351 5144 3226 5144 3352 5144 3352 5145 3226 5145 3224 5145 3352 5146 3224 5146 3204 5146 3204 5147 3224 5147 3189 5147 2880 5148 2867 5148 3353 5148 3353 5149 2867 5149 3351 5149 3353 5150 3351 5150 3354 5150 3354 5151 3351 5151 3352 5151 3354 5152 3352 5152 3203 5152 3203 5153 3352 5153 3204 5153 3355 5154 3356 5154 3357 5154 3358 5155 3359 5155 3360 5155 3360 5156 3359 5156 3361 5156 3360 5157 3361 5157 3362 5157 3362 5158 3361 5158 3363 5158 3362 5159 3363 5159 3364 5159 3365 5160 3366 5160 3358 5160 3358 5161 3366 5161 3367 5161 3358 5162 3367 5162 3359 5162 3358 5163 3368 5163 3365 5163 3365 5164 3368 5164 3369 5164 3365 5165 3369 5165 3370 5165 3370 5166 3369 5166 3371 5166 2878 5167 2879 5167 3372 5167 3372 5168 2879 5168 2880 5168 3369 5169 3373 5169 3371 5169 3371 5170 3373 5170 3372 5170 3371 5171 3372 5171 3374 5171 3374 5172 3372 5172 2880 5172 3375 5173 3376 5173 3377 5173 3376 5174 3375 5174 3357 5174 2863 5175 3378 5175 3379 5175 3379 5176 3378 5176 3380 5176 3379 5177 3380 5177 3381 5177 3381 5178 3380 5178 3382 5178 3381 5179 3382 5179 3383 5179 3383 5180 3382 5180 3384 5180 3383 5181 3384 5181 3385 5181 3385 5182 3384 5182 3386 5182 3385 5183 3386 5183 3387 5183 3387 5184 3386 5184 3388 5184 3387 5185 3388 5185 3389 5185 3389 5186 3388 5186 3390 5186 3389 5187 3390 5187 3391 5187 3391 5188 3390 5188 3375 5188 3391 5189 3375 5189 3392 5189 3392 5190 3375 5190 3377 5190 3392 5191 3377 5191 3393 5191 2863 5192 2878 5192 3378 5192 3378 5193 2878 5193 3372 5193 3378 5194 3372 5194 3380 5194 3380 5195 3372 5195 3373 5195 3380 5196 3373 5196 3382 5196 3382 5197 3373 5197 3369 5197 3382 5198 3369 5198 3384 5198 3384 5199 3369 5199 3368 5199 3384 5200 3368 5200 3386 5200 3386 5201 3368 5201 3358 5201 3386 5202 3358 5202 3388 5202 3388 5203 3358 5203 3360 5203 3388 5204 3360 5204 3390 5204 3390 5205 3360 5205 3362 5205 3390 5206 3362 5206 3375 5206 3375 5207 3362 5207 3364 5207 3375 5208 3364 5208 3357 5208 3357 5209 3364 5209 3363 5209 3357 5210 3363 5210 3355 5210 3394 5211 3395 5211 3396 5211 2906 5212 3397 5212 3398 5212 3398 5213 3397 5213 3399 5213 3398 5214 3399 5214 3400 5214 3400 5215 3399 5215 3401 5215 3400 5216 3401 5216 3402 5216 3402 5217 3401 5217 3403 5217 3402 5218 3403 5218 3404 5218 3404 5219 3403 5219 3405 5219 3404 5220 3405 5220 3406 5220 3406 5221 3405 5221 3407 5221 3406 5222 3407 5222 3408 5222 3408 5223 3407 5223 3409 5223 3408 5224 3409 5224 3410 5224 3410 5225 3409 5225 3411 5225 3410 5226 3411 5226 3412 5226 3412 5227 3411 5227 3396 5227 3412 5228 3396 5228 3413 5228 3413 5229 3396 5229 3395 5229 3413 5230 3395 5230 3414 5230 2881 5231 2863 5231 3415 5231 2881 5232 3415 5232 2882 5232 2863 5233 3416 5233 3415 5233 3415 5234 3416 5234 3417 5234 3415 5235 3417 5235 3418 5235 3418 5236 3417 5236 3419 5236 3418 5237 3419 5237 3420 5237 3420 5238 3419 5238 3421 5238 3420 5239 3421 5239 3422 5239 3422 5240 3421 5240 3423 5240 3422 5241 3423 5241 3424 5241 3424 5242 3423 5242 3425 5242 3424 5243 3425 5243 3426 5243 3426 5244 3425 5244 3427 5244 3426 5245 3427 5245 3428 5245 3428 5246 3427 5246 3429 5246 3428 5247 3429 5247 3430 5247 3430 5248 3429 5248 3431 5248 3430 5249 3431 5249 3432 5249 3432 5250 3431 5250 3433 5250 3433 5251 3394 5251 3432 5251 3432 5252 3394 5252 3396 5252 3432 5253 3396 5253 3430 5253 3430 5254 3396 5254 3411 5254 3430 5255 3411 5255 3428 5255 3428 5256 3411 5256 3409 5256 3428 5257 3409 5257 3426 5257 3426 5258 3409 5258 3407 5258 3426 5259 3407 5259 3424 5259 3424 5260 3407 5260 3405 5260 3424 5261 3405 5261 3422 5261 3422 5262 3405 5262 3403 5262 3422 5263 3403 5263 3420 5263 3420 5264 3403 5264 3401 5264 3420 5265 3401 5265 3418 5265 3418 5266 3401 5266 3399 5266 3418 5267 3399 5267 3415 5267 3415 5268 3399 5268 3397 5268 3415 5269 3397 5269 2882 5269 2882 5270 3397 5270 2906 5270 2905 5271 2906 5271 3434 5271 2902 5272 2904 5272 3435 5272 2932 5273 1856 5273 3436 5273 3436 5274 1856 5274 2917 5274 3436 5275 2917 5275 3435 5275 3435 5276 2917 5276 2918 5276 3435 5277 2918 5277 2902 5277 2902 5278 2918 5278 2901 5278 2931 5279 2932 5279 3437 5279 3437 5280 2932 5280 3436 5280 3437 5281 3436 5281 3434 5281 3434 5282 3436 5282 3435 5282 3434 5283 3435 5283 2905 5283 2905 5284 3435 5284 2904 5284 1875 5285 2935 5285 2965 5285 2965 5286 2935 5286 3438 5286 2965 5287 3438 5287 2968 5287 2968 5288 3438 5288 3439 5288 2968 5289 3439 5289 2972 5289 2978 5290 2984 5290 3439 5290 3439 5291 2984 5291 2983 5291 3439 5292 2983 5292 2972 5292 3440 5293 3441 5293 3442 5293 3442 5294 3441 5294 3443 5294 2945 5295 3441 5295 2937 5295 2937 5296 3441 5296 3440 5296 2937 5297 3440 5297 2936 5297 3444 5298 3443 5298 3445 5298 3445 5299 3443 5299 3441 5299 3445 5300 3441 5300 3446 5300 3446 5301 3441 5301 2945 5301 2935 5302 2936 5302 3438 5302 3438 5303 2936 5303 3440 5303 3438 5304 3440 5304 3439 5304 3439 5305 3440 5305 3442 5305 3439 5306 3442 5306 2978 5306 2978 5307 3442 5307 3443 5307 2978 5308 3443 5308 2980 5308 2980 5309 3443 5309 3444 5309 2980 5310 3444 5310 2982 5310 3434 5311 2906 5311 3398 5311 3437 5312 3434 5312 3447 5312 2931 5313 3437 5313 3448 5313 3434 5314 3398 5314 3447 5314 3447 5315 3398 5315 3400 5315 3447 5316 3400 5316 3449 5316 3449 5317 3400 5317 3402 5317 3449 5318 3402 5318 3450 5318 3450 5319 3402 5319 3404 5319 3450 5320 3404 5320 3451 5320 3451 5321 3404 5321 3406 5321 3451 5322 3406 5322 3452 5322 3452 5323 3406 5323 3408 5323 3452 5324 3408 5324 3453 5324 3453 5325 3408 5325 3410 5325 3453 5326 3410 5326 3454 5326 3454 5327 3410 5327 3412 5327 3454 5328 3412 5328 3455 5328 3455 5329 3412 5329 3413 5329 3455 5330 3413 5330 3456 5330 3456 5331 3413 5331 3414 5331 3456 5332 3414 5332 3457 5332 3437 5333 3447 5333 3448 5333 3448 5334 3447 5334 3449 5334 3448 5335 3449 5335 3458 5335 3458 5336 3449 5336 3450 5336 3458 5337 3450 5337 3459 5337 3459 5338 3450 5338 3451 5338 3459 5339 3451 5339 3460 5339 3460 5340 3451 5340 3452 5340 3460 5341 3452 5341 3461 5341 3461 5342 3452 5342 3453 5342 3461 5343 3453 5343 3462 5343 3462 5344 3453 5344 3454 5344 3462 5345 3454 5345 3463 5345 3463 5346 3454 5346 3455 5346 3463 5347 3455 5347 3464 5347 3464 5348 3455 5348 3456 5348 3464 5349 3456 5349 3465 5349 3465 5350 3456 5350 3457 5350 3465 5351 3457 5351 3466 5351 2931 5352 3448 5352 2930 5352 2930 5353 3448 5353 3458 5353 2930 5354 3458 5354 2938 5354 2938 5355 3458 5355 3459 5355 2938 5356 3459 5356 2939 5356 2939 5357 3459 5357 3460 5357 2939 5358 3460 5358 2940 5358 2940 5359 3460 5359 3461 5359 2940 5360 3461 5360 2943 5360 2943 5361 3461 5361 3462 5361 2943 5362 3462 5362 2944 5362 2944 5363 3462 5363 3463 5363 2944 5364 3463 5364 2933 5364 2933 5365 3463 5365 3464 5365 2933 5366 3464 5366 2934 5366 2934 5367 3464 5367 3465 5367 2934 5368 3465 5368 2941 5368 2941 5369 3465 5369 3466 5369 2941 5370 3466 5370 2942 5370 3467 5371 2929 5371 2928 5371 3468 5372 3469 5372 3470 5372 3470 5373 3469 5373 3467 5373 3470 5374 3467 5374 3471 5374 3471 5375 3467 5375 2928 5375 3472 5376 3468 5376 3473 5376 3473 5377 3468 5377 3470 5377 3473 5378 3470 5378 3474 5378 3474 5379 3470 5379 3471 5379 3474 5380 3471 5380 2927 5380 2927 5381 3471 5381 2928 5381 3414 5382 3472 5382 3457 5382 3457 5383 3472 5383 3473 5383 3457 5384 3473 5384 3466 5384 3466 5385 3473 5385 3474 5385 3466 5386 3474 5386 2942 5386 2942 5387 3474 5387 2927 5387 3475 5388 3476 5388 3477 5388 3477 5389 3476 5389 3478 5389 3477 5390 3478 5390 2947 5390 2947 5391 3478 5391 2949 5391 3469 5392 3475 5392 3467 5392 3467 5393 3475 5393 3477 5393 3467 5394 3477 5394 2929 5394 2929 5395 3477 5395 2947 5395 3479 5396 2946 5396 2948 5396 3480 5397 3479 5397 3481 5397 3479 5398 2948 5398 3481 5398 3481 5399 2948 5399 2958 5399 3481 5400 2958 5400 3482 5400 3482 5401 2958 5401 2956 5401 3482 5402 2956 5402 3483 5402 3483 5403 2956 5403 2955 5403 3483 5404 2955 5404 3484 5404 3484 5405 2955 5405 2954 5405 3484 5406 2954 5406 3485 5406 3485 5407 2954 5407 2957 5407 3485 5408 2957 5408 3486 5408 3486 5409 2957 5409 2953 5409 3486 5410 2953 5410 3487 5410 3487 5411 2953 5411 2952 5411 3487 5412 2952 5412 3488 5412 3488 5413 2952 5413 2951 5413 3488 5414 2951 5414 3489 5414 3489 5415 2951 5415 2950 5415 3489 5416 2950 5416 3490 5416 3490 5417 2950 5417 2949 5417 3490 5418 2949 5418 3478 5418 3480 5419 3481 5419 3491 5419 3491 5420 3481 5420 3482 5420 3491 5421 3482 5421 3492 5421 3492 5422 3482 5422 3483 5422 3492 5423 3483 5423 3493 5423 3493 5424 3483 5424 3484 5424 3493 5425 3484 5425 3494 5425 3494 5426 3484 5426 3485 5426 3494 5427 3485 5427 3495 5427 3495 5428 3485 5428 3486 5428 3495 5429 3486 5429 3496 5429 3496 5430 3486 5430 3487 5430 3496 5431 3487 5431 3497 5431 3497 5432 3487 5432 3488 5432 3497 5433 3488 5433 3498 5433 3498 5434 3488 5434 3489 5434 3498 5435 3489 5435 3499 5435 3499 5436 3489 5436 3490 5436 3499 5437 3490 5437 3500 5437 3500 5438 3490 5438 3478 5438 3500 5439 3478 5439 3476 5439 3479 5440 3480 5440 3444 5440 3444 5441 3480 5441 2982 5441 2945 5442 2946 5442 3446 5442 3446 5443 2946 5443 3479 5443 3446 5444 3479 5444 3445 5444 3445 5445 3479 5445 3444 5445 3501 5446 3316 5446 2802 5446 2982 5447 3480 5447 2988 5447 2988 5448 3480 5448 3502 5448 2988 5449 3502 5449 2987 5449 2987 5450 3502 5450 3501 5450 2987 5451 3501 5451 2976 5451 2976 5452 3501 5452 2802 5452 3269 5453 3261 5453 3262 5453 2616 5454 3269 5454 3503 5454 3503 5455 3269 5455 3262 5455 3503 5456 3262 5456 3504 5456 3504 5457 3262 5457 3263 5457 3263 5458 3264 5458 3504 5458 3504 5459 3264 5459 3265 5459 3504 5460 3265 5460 3267 5460 3267 5461 3268 5461 3504 5461 3504 5462 3268 5462 3258 5462 3504 5463 3258 5463 3505 5463 2616 5464 3503 5464 2995 5464 2995 5465 3503 5465 3504 5465 2995 5466 3504 5466 2994 5466 2994 5467 3504 5467 3505 5467 2994 5468 3505 5468 2998 5468 3505 5469 3258 5469 3506 5469 2998 5470 3505 5470 3507 5470 3505 5471 3506 5471 3507 5471 3507 5472 3506 5472 3508 5472 3507 5473 3508 5473 3509 5473 3509 5474 3508 5474 3510 5474 3509 5475 3510 5475 3511 5475 3511 5476 3510 5476 3512 5476 3511 5477 3512 5477 3513 5477 3513 5478 3512 5478 3514 5478 3513 5479 3514 5479 3515 5479 3515 5480 3514 5480 3516 5480 3515 5481 3516 5481 3517 5481 3516 5482 3518 5482 3519 5482 3516 5483 3519 5483 3517 5483 3517 5484 3519 5484 3520 5484 3517 5485 3520 5485 3521 5485 2998 5486 3507 5486 2999 5486 2999 5487 3507 5487 3509 5487 2999 5488 3509 5488 2996 5488 2996 5489 3509 5489 3511 5489 2996 5490 3511 5490 2997 5490 2997 5491 3511 5491 3513 5491 2997 5492 3513 5492 2993 5492 2993 5493 3513 5493 3515 5493 2993 5494 3515 5494 2992 5494 2992 5495 3515 5495 3517 5495 2992 5496 3517 5496 2990 5496 2990 5497 3517 5497 3521 5497 2990 5498 3521 5498 2991 5498 3522 5499 3001 5499 3000 5499 3523 5500 3522 5500 3524 5500 3052 5501 3523 5501 3525 5501 3522 5502 3000 5502 3524 5502 3524 5503 3000 5503 3007 5503 3524 5504 3007 5504 3526 5504 3526 5505 3007 5505 3006 5505 3526 5506 3006 5506 3527 5506 3006 5507 3004 5507 3527 5507 3527 5508 3004 5508 3003 5508 3527 5509 3003 5509 3528 5509 3528 5510 3003 5510 1927 5510 3528 5511 1927 5511 3529 5511 3523 5512 3524 5512 3525 5512 3525 5513 3524 5513 3526 5513 3525 5514 3526 5514 3530 5514 3530 5515 3526 5515 3527 5515 3530 5516 3527 5516 3531 5516 3531 5517 3527 5517 3528 5517 3531 5518 3528 5518 3532 5518 3532 5519 3528 5519 3529 5519 3532 5520 3529 5520 3533 5520 3052 5521 3525 5521 3053 5521 3053 5522 3525 5522 3530 5522 3053 5523 3530 5523 3054 5523 3054 5524 3530 5524 3531 5524 3054 5525 3531 5525 3055 5525 3055 5526 3531 5526 3532 5526 3055 5527 3532 5527 3056 5527 3056 5528 3532 5528 3533 5528 3056 5529 3533 5529 3050 5529 3534 5530 3535 5530 3536 5530 3001 5531 3522 5531 3537 5531 3535 5532 3061 5532 3060 5532 3535 5533 3060 5533 3536 5533 3536 5534 3060 5534 3058 5534 3536 5535 3058 5535 3538 5535 3538 5536 3058 5536 3057 5536 3538 5537 3057 5537 3539 5537 3539 5538 3057 5538 3063 5538 3539 5539 3063 5539 3540 5539 3540 5540 3063 5540 3062 5540 3540 5541 3062 5541 3541 5541 3541 5542 3062 5542 3068 5542 3541 5543 3068 5543 3542 5543 3542 5544 3068 5544 3067 5544 3542 5545 3067 5545 3543 5545 3543 5546 3067 5546 3065 5546 3543 5547 3065 5547 3544 5547 3544 5548 3065 5548 3069 5548 3544 5549 3069 5549 3545 5549 3545 5550 3069 5550 3070 5550 3545 5551 3070 5551 3546 5551 3546 5552 3070 5552 2040 5552 3546 5553 2040 5553 3084 5553 3534 5554 3536 5554 3547 5554 3547 5555 3536 5555 3538 5555 3547 5556 3538 5556 3548 5556 3548 5557 3538 5557 3539 5557 3548 5558 3539 5558 3549 5558 3549 5559 3539 5559 3540 5559 3549 5560 3540 5560 3550 5560 3550 5561 3540 5561 3541 5561 3550 5562 3541 5562 3551 5562 3551 5563 3541 5563 3542 5563 3551 5564 3542 5564 3552 5564 3552 5565 3542 5565 3543 5565 3552 5566 3543 5566 3553 5566 3553 5567 3543 5567 3544 5567 3553 5568 3544 5568 3554 5568 3554 5569 3544 5569 3545 5569 3554 5570 3545 5570 3555 5570 3555 5571 3545 5571 3546 5571 3555 5572 3546 5572 3556 5572 3556 5573 3546 5573 3084 5573 3556 5574 3084 5574 3085 5574 3052 5575 3061 5575 3523 5575 3523 5576 3061 5576 3535 5576 3523 5577 3535 5577 3522 5577 3522 5578 3535 5578 3534 5578 3522 5579 3534 5579 3537 5579 3537 5580 3534 5580 3547 5580 3537 5581 3547 5581 3557 5581 3557 5582 3547 5582 3548 5582 3557 5583 3548 5583 3558 5583 3558 5584 3548 5584 3549 5584 3558 5585 3549 5585 3559 5585 3559 5586 3549 5586 3550 5586 3559 5587 3550 5587 3560 5587 3560 5588 3550 5588 3551 5588 3560 5589 3551 5589 3561 5589 3561 5590 3551 5590 3552 5590 3561 5591 3552 5591 3562 5591 3562 5592 3552 5592 3553 5592 3562 5593 3553 5593 3563 5593 3563 5594 3553 5594 3554 5594 3563 5595 3554 5595 3564 5595 3564 5596 3554 5596 3555 5596 3564 5597 3555 5597 3565 5597 3565 5598 3555 5598 3556 5598 3565 5599 3556 5599 3566 5599 3566 5600 3556 5600 3085 5600 3566 5601 3085 5601 3086 5601 3001 5602 3537 5602 3567 5602 3567 5603 3537 5603 3557 5603 3567 5604 3557 5604 3568 5604 3568 5605 3557 5605 3558 5605 3568 5606 3558 5606 3569 5606 3569 5607 3558 5607 3559 5607 3569 5608 3559 5608 3570 5608 3570 5609 3559 5609 3560 5609 3570 5610 3560 5610 3571 5610 3571 5611 3560 5611 3561 5611 3571 5612 3561 5612 3572 5612 3572 5613 3561 5613 3562 5613 3572 5614 3562 5614 3573 5614 3573 5615 3562 5615 3563 5615 3573 5616 3563 5616 3574 5616 3574 5617 3563 5617 3564 5617 3574 5618 3564 5618 3575 5618 3575 5619 3564 5619 3565 5619 3575 5620 3565 5620 3576 5620 3576 5621 3565 5621 3566 5621 3576 5622 3566 5622 3577 5622 3577 5623 3566 5623 3086 5623 3577 5624 3086 5624 3087 5624 3301 5625 3302 5625 3578 5625 3579 5626 3580 5626 3581 5626 3582 5627 3583 5627 3584 5627 3584 5628 3585 5628 3582 5628 3582 5629 3585 5629 3586 5629 3582 5630 3586 5630 3587 5630 3587 5631 3588 5631 3582 5631 3582 5632 3588 5632 3589 5632 3582 5633 3589 5633 3590 5633 3306 5634 3591 5634 3583 5634 3306 5635 3583 5635 3304 5635 3304 5636 3583 5636 3582 5636 3304 5637 3582 5637 3303 5637 3312 5638 3592 5638 3306 5638 3306 5639 3592 5639 3593 5639 3306 5640 3593 5640 3591 5640 3312 5641 3311 5641 3594 5641 3312 5642 3594 5642 3592 5642 3592 5643 3594 5643 3595 5643 3592 5644 3595 5644 3596 5644 3597 5645 3144 5645 3598 5645 3598 5646 3144 5646 3102 5646 3301 5647 3578 5647 3300 5647 3300 5648 3578 5648 3598 5648 3300 5649 3598 5649 3288 5649 3288 5650 3598 5650 3102 5650 3288 5651 3102 5651 3101 5651 3599 5652 3600 5652 3601 5652 3601 5653 3600 5653 3602 5653 3590 5654 3579 5654 3582 5654 3582 5655 3579 5655 3581 5655 3582 5656 3581 5656 3600 5656 3600 5657 3581 5657 3603 5657 3600 5658 3603 5658 3602 5658 3602 5659 3603 5659 3604 5659 3602 5660 3604 5660 3601 5660 3599 5661 3597 5661 3600 5661 3600 5662 3597 5662 3598 5662 3600 5663 3598 5663 3582 5663 3582 5664 3598 5664 3578 5664 3582 5665 3578 5665 3303 5665 3303 5666 3578 5666 3302 5666 3144 5667 3597 5667 3142 5667 3142 5668 3597 5668 3138 5668 3597 5669 3599 5669 3138 5669 3138 5670 3599 5670 3601 5670 3138 5671 3601 5671 3136 5671 3136 5672 3601 5672 3604 5672 3136 5673 3604 5673 3139 5673 3605 5674 3188 5674 2991 5674 3518 5675 3606 5675 3519 5675 3519 5676 3606 5676 3607 5676 3519 5677 3607 5677 3520 5677 3520 5678 3607 5678 3605 5678 3520 5679 3605 5679 3521 5679 3521 5680 3605 5680 2991 5680 3192 5681 3188 5681 3608 5681 3608 5682 3188 5682 3605 5682 3608 5683 3605 5683 3609 5683 3609 5684 3605 5684 3607 5684 3609 5685 3607 5685 3356 5685 3356 5686 3607 5686 3606 5686 3354 5687 3203 5687 3202 5687 3353 5688 3354 5688 3610 5688 2880 5689 3353 5689 3611 5689 3354 5690 3202 5690 3610 5690 3610 5691 3202 5691 3201 5691 3610 5692 3201 5692 3612 5692 3612 5693 3201 5693 3197 5693 3612 5694 3197 5694 3613 5694 3613 5695 3197 5695 3196 5695 3613 5696 3196 5696 3614 5696 3614 5697 3196 5697 3195 5697 3614 5698 3195 5698 3615 5698 3615 5699 3195 5699 3200 5699 3615 5700 3200 5700 3616 5700 3616 5701 3200 5701 3199 5701 3616 5702 3199 5702 3617 5702 3617 5703 3199 5703 3198 5703 3617 5704 3198 5704 3618 5704 3618 5705 3198 5705 3194 5705 3618 5706 3194 5706 3619 5706 3619 5707 3194 5707 3193 5707 3619 5708 3193 5708 3620 5708 3620 5709 3193 5709 3192 5709 3620 5710 3192 5710 3608 5710 3353 5711 3610 5711 3611 5711 3611 5712 3610 5712 3612 5712 3611 5713 3612 5713 3621 5713 3621 5714 3612 5714 3613 5714 3621 5715 3613 5715 3622 5715 3622 5716 3613 5716 3614 5716 3622 5717 3614 5717 3623 5717 3623 5718 3614 5718 3615 5718 3623 5719 3615 5719 3624 5719 3624 5720 3615 5720 3616 5720 3624 5721 3616 5721 3625 5721 3625 5722 3616 5722 3617 5722 3625 5723 3617 5723 3626 5723 3626 5724 3617 5724 3618 5724 3626 5725 3618 5725 3627 5725 3627 5726 3618 5726 3619 5726 3627 5727 3619 5727 3628 5727 3628 5728 3619 5728 3620 5728 3628 5729 3620 5729 3629 5729 3629 5730 3620 5730 3608 5730 3629 5731 3608 5731 3609 5731 2880 5732 3611 5732 3374 5732 3374 5733 3611 5733 3621 5733 3374 5734 3621 5734 3371 5734 3371 5735 3621 5735 3622 5735 3371 5736 3622 5736 3370 5736 3370 5737 3622 5737 3623 5737 3370 5738 3623 5738 3365 5738 3365 5739 3623 5739 3624 5739 3365 5740 3624 5740 3366 5740 3366 5741 3624 5741 3625 5741 3366 5742 3625 5742 3367 5742 3367 5743 3625 5743 3626 5743 3367 5744 3626 5744 3359 5744 3359 5745 3626 5745 3627 5745 3359 5746 3627 5746 3361 5746 3361 5747 3627 5747 3628 5747 3361 5748 3628 5748 3363 5748 3363 5749 3628 5749 3629 5749 3363 5750 3629 5750 3355 5750 3355 5751 3629 5751 3609 5751 3355 5752 3609 5752 3356 5752 3630 5753 3631 5753 3632 5753 3632 5754 3631 5754 3633 5754 3632 5755 3633 5755 3634 5755 3632 5756 3634 5756 3635 5756 3635 5757 3634 5757 3580 5757 3636 5758 3637 5758 3630 5758 3630 5759 3637 5759 3638 5759 3630 5760 3638 5760 3631 5760 3639 5761 3640 5761 3641 5761 3641 5762 3640 5762 3642 5762 3641 5763 3642 5763 3643 5763 3643 5764 3642 5764 3637 5764 3643 5765 3637 5765 3644 5765 3644 5766 3637 5766 3636 5766 3641 5767 3643 5767 3645 5767 3645 5768 3643 5768 3644 5768 3314 5769 3315 5769 3646 5769 3314 5770 3646 5770 3339 5770 3339 5771 3646 5771 3647 5771 3339 5772 3647 5772 3338 5772 3338 5773 3647 5773 3648 5773 3338 5774 3648 5774 3336 5774 3648 5775 3649 5775 3336 5775 3336 5776 3649 5776 3650 5776 3336 5777 3650 5777 3334 5777 3334 5778 3650 5778 3651 5778 3334 5779 3651 5779 3332 5779 3332 5780 3651 5780 3652 5780 3332 5781 3652 5781 3330 5781 3644 5782 3636 5782 3653 5782 3654 5783 3655 5783 3656 5783 3656 5784 3655 5784 3657 5784 3658 5785 3654 5785 3659 5785 3659 5786 3654 5786 3656 5786 3659 5787 3656 5787 3660 5787 3660 5788 3656 5788 3653 5788 3639 5789 3641 5789 3652 5789 3652 5790 3641 5790 3645 5790 3652 5791 3645 5791 3330 5791 3330 5792 3645 5792 3644 5792 3330 5793 3644 5793 3328 5793 3328 5794 3644 5794 3653 5794 3328 5795 3653 5795 3326 5795 3326 5796 3653 5796 3656 5796 3326 5797 3656 5797 3661 5797 3661 5798 3656 5798 3657 5798 3639 5799 3652 5799 3662 5799 3662 5800 3652 5800 3651 5800 3662 5801 3651 5801 3663 5801 3663 5802 3651 5802 3650 5802 3663 5803 3650 5803 3664 5803 3664 5804 3650 5804 3649 5804 3664 5805 3649 5805 3665 5805 3665 5806 3649 5806 3648 5806 3665 5807 3648 5807 3666 5807 3666 5808 3648 5808 3647 5808 3666 5809 3647 5809 3667 5809 3667 5810 3647 5810 3646 5810 3667 5811 3646 5811 3668 5811 3668 5812 3646 5812 3315 5812 3668 5813 3315 5813 3316 5813 3669 5814 3670 5814 3671 5814 3672 5815 3498 5815 3673 5815 3673 5816 3498 5816 3499 5816 3673 5817 3499 5817 3674 5817 3674 5818 3499 5818 3500 5818 3674 5819 3500 5819 3675 5819 3675 5820 3500 5820 3476 5820 3491 5821 3492 5821 3676 5821 3676 5822 3492 5822 3493 5822 3676 5823 3493 5823 3677 5823 3677 5824 3493 5824 3494 5824 3677 5825 3494 5825 3678 5825 3678 5826 3494 5826 3495 5826 3678 5827 3495 5827 3679 5827 3679 5828 3495 5828 3496 5828 3679 5829 3496 5829 3672 5829 3672 5830 3496 5830 3497 5830 3672 5831 3497 5831 3498 5831 3480 5832 3491 5832 3502 5832 3502 5833 3491 5833 3676 5833 3502 5834 3676 5834 3501 5834 3476 5835 3669 5835 3675 5835 3675 5836 3669 5836 3671 5836 3675 5837 3671 5837 3674 5837 3674 5838 3671 5838 3680 5838 3674 5839 3680 5839 3673 5839 3673 5840 3680 5840 3681 5840 3673 5841 3681 5841 3672 5841 3672 5842 3681 5842 3682 5842 3672 5843 3682 5843 3679 5843 3679 5844 3682 5844 3683 5844 3679 5845 3683 5845 3678 5845 3678 5846 3683 5846 3684 5846 3678 5847 3684 5847 3677 5847 3677 5848 3684 5848 3685 5848 3677 5849 3685 5849 3676 5849 3676 5850 3685 5850 3686 5850 3676 5851 3686 5851 3501 5851 3501 5852 3686 5852 3316 5852 3316 5853 3686 5853 3687 5853 3687 5854 3686 5854 3685 5854 3687 5855 3685 5855 3688 5855 3688 5856 3685 5856 3684 5856 3688 5857 3684 5857 3689 5857 3689 5858 3684 5858 3683 5858 3689 5859 3683 5859 3690 5859 3690 5860 3683 5860 3682 5860 3690 5861 3682 5861 3691 5861 3691 5862 3682 5862 3681 5862 3691 5863 3681 5863 3692 5863 3692 5864 3681 5864 3680 5864 3692 5865 3680 5865 3693 5865 3693 5866 3680 5866 3671 5866 3693 5867 3671 5867 3694 5867 3694 5868 3671 5868 3670 5868 3694 5869 3670 5869 3695 5869 3696 5870 3695 5870 3697 5870 3697 5871 3695 5871 3670 5871 3697 5872 3670 5872 3698 5872 3698 5873 3670 5873 3669 5873 3698 5874 3669 5874 3475 5874 3475 5875 3669 5875 3476 5875 3699 5876 3696 5876 3700 5876 3700 5877 3696 5877 3697 5877 3700 5878 3697 5878 3701 5878 3701 5879 3697 5879 3698 5879 3701 5880 3698 5880 3702 5880 3702 5881 3698 5881 3475 5881 3702 5882 3475 5882 3469 5882 3468 5883 3472 5883 3703 5883 3472 5884 3414 5884 3704 5884 3704 5885 3414 5885 3395 5885 3704 5886 3395 5886 3705 5886 3705 5887 3395 5887 3394 5887 3706 5888 3705 5888 3707 5888 3707 5889 3705 5889 3394 5889 3707 5890 3394 5890 3433 5890 3472 5891 3704 5891 3703 5891 3703 5892 3704 5892 3705 5892 3703 5893 3705 5893 3708 5893 3708 5894 3705 5894 3706 5894 3708 5895 3706 5895 3699 5895 3469 5896 3468 5896 3702 5896 3702 5897 3468 5897 3703 5897 3702 5898 3703 5898 3701 5898 3701 5899 3703 5899 3708 5899 3701 5900 3708 5900 3700 5900 3700 5901 3708 5901 3699 5901 3506 5902 3258 5902 3257 5902 3516 5903 3514 5903 3709 5903 3709 5904 3514 5904 3512 5904 3506 5905 3710 5905 3508 5905 3508 5906 3710 5906 3709 5906 3508 5907 3709 5907 3510 5907 3510 5908 3709 5908 3512 5908 3356 5909 3606 5909 3709 5909 3709 5910 3606 5910 3518 5910 3709 5911 3518 5911 3516 5911 3257 5912 2614 5912 3711 5912 3506 5913 3257 5913 3710 5913 3710 5914 3257 5914 3711 5914 3710 5915 3711 5915 3393 5915 3393 5916 3377 5916 3710 5916 3710 5917 3377 5917 3376 5917 3710 5918 3376 5918 3709 5918 3709 5919 3376 5919 3357 5919 3709 5920 3357 5920 3356 5920 3712 5921 3653 5921 3636 5921 3713 5922 3349 5922 3348 5922 3714 5923 3715 5923 3716 5923 3716 5924 3715 5924 3717 5924 3718 5925 3719 5925 3658 5925 3658 5926 3719 5926 3720 5926 3712 5927 3721 5927 3653 5927 3653 5928 3721 5928 3722 5928 3653 5929 3722 5929 3660 5929 3660 5930 3722 5930 3718 5930 3660 5931 3718 5931 3659 5931 3659 5932 3718 5932 3658 5932 3717 5933 3713 5933 3716 5933 3716 5934 3713 5934 3348 5934 3716 5935 3348 5935 3723 5935 3723 5936 3348 5936 3346 5936 3723 5937 3346 5937 3724 5937 3724 5938 3346 5938 3345 5938 3724 5939 3345 5939 3725 5939 3725 5940 3345 5940 2850 5940 3725 5941 2850 5941 3325 5941 3720 5942 3714 5942 3658 5942 3658 5943 3714 5943 3716 5943 3658 5944 3716 5944 3654 5944 3654 5945 3716 5945 3723 5945 3654 5946 3723 5946 3655 5946 3655 5947 3723 5947 3724 5947 3655 5948 3724 5948 3657 5948 3657 5949 3724 5949 3725 5949 3657 5950 3725 5950 3661 5950 3661 5951 3725 5951 3325 5951 3661 5952 3325 5952 3326 5952 3311 5953 3344 5953 3594 5953 3594 5954 3344 5954 3343 5954 3594 5955 3343 5955 3595 5955 3595 5956 3343 5956 3342 5956 3595 5957 3342 5957 3596 5957 3596 5958 3342 5958 3341 5958 3596 5959 3341 5959 3592 5959 3592 5960 3341 5960 3350 5960 3349 5961 3584 5961 3350 5961 3350 5962 3584 5962 3583 5962 3583 5963 3591 5963 3350 5963 3350 5964 3591 5964 3593 5964 3350 5965 3593 5965 3592 5965 3580 5966 3721 5966 3712 5966 3632 5967 3712 5967 3630 5967 3630 5968 3712 5968 3636 5968 3712 5969 3632 5969 3635 5969 3712 5970 3635 5970 3580 5970 3721 5971 3580 5971 3722 5971 3722 5972 3580 5972 3579 5972 3722 5973 3579 5973 3718 5973 3718 5974 3579 5974 3590 5974 3718 5975 3590 5975 3719 5975 3719 5976 3590 5976 3589 5976 3719 5977 3589 5977 3720 5977 3720 5978 3589 5978 3588 5978 3720 5979 3588 5979 3714 5979 3714 5980 3588 5980 3587 5980 3714 5981 3587 5981 3715 5981 3715 5982 3587 5982 3586 5982 3715 5983 3586 5983 3717 5983 3717 5984 3586 5984 3585 5984 3717 5985 3585 5985 3713 5985 3713 5986 3585 5986 3584 5986 3713 5987 3584 5987 3349 5987 3726 5988 599 5988 598 5988 596 5989 3727 5989 598 5989 598 5990 3727 5990 3728 5990 598 5991 3728 5991 3726 5991 3729 5992 3730 5992 593 5992 593 5993 3730 5993 3731 5993 593 5994 3731 5994 596 5994 596 5995 3731 5995 3732 5995 596 5996 3732 5996 3727 5996 593 5997 591 5997 3729 5997 3729 5998 591 5998 584 5998 3729 5999 584 5999 3733 5999 3733 106 584 106 3734 106 3734 6000 584 6000 582 6000 3734 106 582 106 727 106 2870 6001 2869 6001 3735 6001 3735 6002 2869 6002 3736 6002 3735 6003 3736 6003 3737 6003 3737 6004 3736 6004 3738 6004 3737 6005 3738 6005 3739 6005 3739 6006 3738 6006 3740 6006 3739 6007 3740 6007 903 6007 903 6008 3740 6008 902 6008 2871 6009 2870 6009 3741 6009 3741 6010 2870 6010 3735 6010 3741 6011 3735 6011 3742 6011 3742 6012 3735 6012 3737 6012 3742 6013 3737 6013 3743 6013 3743 6014 3737 6014 3739 6014 3743 6015 3739 6015 904 6015 904 6016 3739 6016 903 6016 3744 6017 2915 6017 899 6017 3745 6018 2916 6018 2915 6018 3746 6019 2909 6019 2916 6019 2896 6020 2898 6020 2909 6020 2909 6021 3746 6021 2896 6021 2896 6022 3746 6022 3747 6022 2896 6023 3747 6023 2900 6023 2900 6024 3747 6024 3748 6024 2900 6025 3748 6025 2890 6025 899 6026 898 6026 3744 6026 3744 6027 898 6027 897 6027 3744 6028 897 6028 3749 6028 3749 6029 897 6029 896 6029 3749 6030 896 6030 3750 6030 3750 6031 896 6031 895 6031 3750 6032 895 6032 3751 6032 3751 6033 895 6033 894 6033 3751 6034 894 6034 3752 6034 3752 6035 894 6035 907 6035 3752 6036 907 6036 3753 6036 3753 6037 907 6037 906 6037 3753 6038 906 6038 3754 6038 3754 6039 906 6039 905 6039 3754 6040 905 6040 3755 6040 3755 6041 905 6041 901 6041 3755 6042 901 6042 3756 6042 3756 6043 901 6043 902 6043 3756 6044 902 6044 3740 6044 2915 6045 3744 6045 3745 6045 3745 6046 3744 6046 3749 6046 3745 6047 3749 6047 3757 6047 3757 6048 3749 6048 3750 6048 3757 6049 3750 6049 3758 6049 3758 6050 3750 6050 3751 6050 3758 6051 3751 6051 3759 6051 3759 6052 3751 6052 3752 6052 3759 6053 3752 6053 3760 6053 3760 6054 3752 6054 3753 6054 3760 6055 3753 6055 3761 6055 3761 6056 3753 6056 3754 6056 3761 6057 3754 6057 3762 6057 3762 6058 3754 6058 3755 6058 3762 6059 3755 6059 3763 6059 3763 6060 3755 6060 3756 6060 3763 6061 3756 6061 3764 6061 3764 6062 3756 6062 3740 6062 3764 6063 3740 6063 3738 6063 2916 6064 3745 6064 3746 6064 3746 6065 3745 6065 3757 6065 3746 6066 3757 6066 3747 6066 3747 6067 3757 6067 3758 6067 3747 6068 3758 6068 3748 6068 3748 6069 3758 6069 3759 6069 3748 6070 3759 6070 3765 6070 3765 6071 3759 6071 3760 6071 3765 6072 3760 6072 3766 6072 3766 6073 3760 6073 3761 6073 3766 6074 3761 6074 3767 6074 3767 6075 3761 6075 3762 6075 3767 6076 3762 6076 3768 6076 3768 6077 3762 6077 3763 6077 3768 6078 3763 6078 3769 6078 3769 6079 3763 6079 3764 6079 3769 6080 3764 6080 3770 6080 3770 6081 3764 6081 3738 6081 3770 6082 3738 6082 3736 6082 2890 6083 3748 6083 2891 6083 2891 6084 3748 6084 3765 6084 2891 6085 3765 6085 2893 6085 2893 6086 3765 6086 3766 6086 2893 6087 3766 6087 2884 6087 2884 6088 3766 6088 3767 6088 2884 6089 3767 6089 2885 6089 2885 6090 3767 6090 3768 6090 2885 6091 3768 6091 2887 6091 2887 6092 3768 6092 3769 6092 2887 6093 3769 6093 2888 6093 2888 6094 3769 6094 3770 6094 2888 6095 3770 6095 2889 6095 2889 6096 3770 6096 3736 6096 2889 6097 3736 6097 2869 6097 3743 6098 904 6098 925 6098 3742 6099 3743 6099 3771 6099 3741 6100 3742 6100 3772 6100 2871 6101 3741 6101 3773 6101 3743 6102 925 6102 3771 6102 3771 6103 925 6103 924 6103 3771 6104 924 6104 3774 6104 3774 6105 924 6105 921 6105 3774 6106 921 6106 3775 6106 3775 6107 921 6107 919 6107 3775 6108 919 6108 3776 6108 3776 6109 919 6109 918 6109 3776 6110 918 6110 2195 6110 3742 6111 3771 6111 3772 6111 3772 6112 3771 6112 3774 6112 3772 6113 3774 6113 3777 6113 3777 6114 3774 6114 3775 6114 3777 6115 3775 6115 3778 6115 3778 6116 3775 6116 3776 6116 3778 6117 3776 6117 3779 6117 3779 6118 3776 6118 2195 6118 3779 6119 2195 6119 2196 6119 3741 6120 3772 6120 3773 6120 3773 6121 3772 6121 3777 6121 3773 6122 3777 6122 3780 6122 3780 6123 3777 6123 3778 6123 3780 6124 3778 6124 3781 6124 3781 6125 3778 6125 3779 6125 3781 6126 3779 6126 3782 6126 3782 6127 3779 6127 2196 6127 3782 6128 2196 6128 2197 6128 2871 6129 3773 6129 2872 6129 2872 6130 3773 6130 3780 6130 2872 6131 3780 6131 2873 6131 2873 6132 3780 6132 3781 6132 2873 6133 3781 6133 2875 6133 2875 6134 3781 6134 3782 6134 2875 6135 3782 6135 2876 6135 2876 6136 3782 6136 2197 6136 2876 6137 2197 6137 2198 6137 3783 6138 2837 6138 2839 6138 3783 6139 2839 6139 3784 6139 3785 6140 3786 6140 3784 6140 3787 6141 3788 6141 3786 6141 3786 6142 3785 6142 3787 6142 3787 6143 3785 6143 3789 6143 3787 6144 3789 6144 3790 6144 3790 6145 3789 6145 3340 6145 3790 6146 3340 6146 3311 6146 3784 6147 2839 6147 3785 6147 3785 6148 2839 6148 2841 6148 3785 6149 2841 6149 3789 6149 3789 6150 2841 6150 2830 6150 3789 6151 2830 6151 3340 6151 2837 6152 3783 6152 3791 6152 3791 6153 3783 6153 3784 6153 3791 6154 3784 6154 3792 6154 3792 6155 3784 6155 3786 6155 3792 6156 3786 6156 3793 6156 3793 6157 3786 6157 3788 6157 3793 6158 3788 6158 3794 6158 2837 6159 3791 6159 3795 6159 3795 6160 3791 6160 3792 6160 3795 6161 3792 6161 3796 6161 3796 6162 3792 6162 3793 6162 3796 6163 3793 6163 3797 6163 3797 6164 3793 6164 3794 6164 3797 6165 3794 6165 3798 6165 3794 6166 3788 6166 3799 6166 3800 6167 3798 6167 3801 6167 3801 6168 3798 6168 3794 6168 3800 6169 3801 6169 3802 6169 3802 6170 3801 6170 3803 6170 3802 6171 3803 6171 3804 6171 3804 6172 3803 6172 3805 6172 3804 6173 3805 6173 3806 6173 3806 6174 3805 6174 3807 6174 3806 6175 3807 6175 3808 6175 3794 6176 3799 6176 3801 6176 3801 6177 3799 6177 3809 6177 3801 6178 3809 6178 3803 6178 3803 6179 3809 6179 3810 6179 3803 6180 3810 6180 3805 6180 3805 6181 3810 6181 3811 6181 3805 6182 3811 6182 3807 6182 3807 6183 3811 6183 3812 6183 3807 6184 3812 6184 3813 6184 3813 6185 3812 6185 3814 6185 3813 6186 3814 6186 3815 6186 3808 6187 3807 6187 3816 6187 3816 6188 3807 6188 3813 6188 3816 6189 3813 6189 3817 6189 3817 6190 3813 6190 3815 6190 3817 6191 3815 6191 3818 6191 3818 6192 3815 6192 3819 6192 1837 6193 3820 6193 3821 6193 3821 6194 3820 6194 3822 6194 3821 6195 3822 6195 3823 6195 3823 6196 3822 6196 3824 6196 3823 6197 3824 6197 3825 6197 3825 6198 3824 6198 3826 6198 3825 6199 3826 6199 3827 6199 3827 6200 3826 6200 3828 6200 3827 6201 3828 6201 3829 6201 3829 6202 3828 6202 3830 6202 3829 6203 3830 6203 3819 6203 3819 6204 3830 6204 3831 6204 3819 6205 3831 6205 3818 6205 1837 6206 3821 6206 3832 6206 3832 6207 3821 6207 3823 6207 3832 6208 3823 6208 3833 6208 3833 6209 3823 6209 3825 6209 3833 6210 3825 6210 3834 6210 3834 6211 3825 6211 3827 6211 3834 6212 3827 6212 3835 6212 3835 6213 3827 6213 3829 6213 3835 6214 3829 6214 3836 6214 3836 6215 3829 6215 3819 6215 3836 6216 3819 6216 3837 6216 3837 6217 3819 6217 3815 6217 3837 6218 3815 6218 3814 6218 1838 6219 1837 6219 3838 6219 3838 6220 1837 6220 3832 6220 3838 6221 3832 6221 3833 6221 3833 6222 3834 6222 3838 6222 3838 6223 3834 6223 3835 6223 3838 6224 3835 6224 3839 6224 3839 6225 3835 6225 3836 6225 3814 6226 3840 6226 3837 6226 3837 6227 3840 6227 3841 6227 3837 6228 3841 6228 3842 6228 3842 6229 3841 6229 3843 6229 3842 6230 3843 6230 3844 6230 3844 6231 3843 6231 2854 6231 3844 6232 2854 6232 2852 6232 1841 6233 1838 6233 2852 6233 2852 6234 1838 6234 3838 6234 2852 6235 3838 6235 3844 6235 3844 6236 3838 6236 3839 6236 3844 6237 3839 6237 3842 6237 3842 6238 3839 6238 3836 6238 3842 6239 3836 6239 3837 6239 3787 6240 3845 6240 3788 6240 3790 6241 3311 6241 3309 6241 3846 6242 3812 6242 3811 6242 3811 6243 3810 6243 3846 6243 3846 6244 3810 6244 3809 6244 3846 6245 3809 6245 3845 6245 3845 6246 3809 6246 3799 6246 3845 6247 3799 6247 3788 6247 3814 6248 3812 6248 3840 6248 3840 6249 3812 6249 3846 6249 3840 6250 3846 6250 3841 6250 3841 6251 3846 6251 3843 6251 3308 6252 2854 6252 3843 6252 3843 6253 3846 6253 3308 6253 3308 6254 3846 6254 3845 6254 3308 6255 3845 6255 3309 6255 3309 6256 3845 6256 3787 6256 3309 6257 3787 6257 3790 6257 3847 6258 3848 6258 3849 6258 3850 6259 3849 6259 3851 6259 3852 6260 3853 6260 3854 6260 936 6261 3853 6261 934 6261 3853 6262 936 6262 3854 6262 3854 6263 936 6263 937 6263 3854 6264 937 6264 932 6264 3852 6265 934 6265 3853 6265 932 6266 3855 6266 3854 6266 3854 6267 3855 6267 3850 6267 3854 6268 3850 6268 3852 6268 3852 6269 3850 6269 3851 6269 3852 6270 3851 6270 934 6270 932 6271 931 6271 3855 6271 3855 6272 931 6272 929 6272 3855 6273 929 6273 928 6273 3856 6274 3857 6274 3847 6274 3849 6275 3850 6275 3847 6275 3847 6276 3850 6276 3855 6276 3847 6277 3855 6277 3856 6277 3856 6278 3855 6278 928 6278 3856 6279 928 6279 739 6279 739 6280 3858 6280 3856 6280 3856 6281 3858 6281 3859 6281 3856 6282 3859 6282 3857 6282 3857 6283 3859 6283 3860 6283 3857 6284 3860 6284 3861 6284 3848 6285 3847 6285 3862 6285 3862 6286 3847 6286 3857 6286 3862 6287 3857 6287 3863 6287 3863 6288 3857 6288 3861 6288 3863 6289 3861 6289 3864 6289 3865 6290 3866 6290 3864 6290 3864 6291 3861 6291 3865 6291 3865 6292 3861 6292 3860 6292 3865 6293 3860 6293 3867 6293 3860 6294 3859 6294 3867 6294 3867 6295 3859 6295 3858 6295 3867 6296 3858 6296 3868 6296 3868 6297 3858 6297 739 6297 3868 6298 739 6298 738 6298 3869 6299 3866 6299 3865 6299 3870 6300 3869 6300 3871 6300 3871 6301 3869 6301 3865 6301 3871 6302 3865 6302 3872 6302 3872 6303 3865 6303 3867 6303 3872 6304 3867 6304 3873 6304 3873 6305 3867 6305 3868 6305 3873 6306 3868 6306 1429 6306 1429 6307 3868 6307 738 6307 3874 6308 3870 6308 3875 6308 3875 6309 3870 6309 3871 6309 3875 6310 3871 6310 3876 6310 3876 6311 3871 6311 3872 6311 3876 6312 3872 6312 3877 6312 3877 6313 3872 6313 3873 6313 3877 6314 3873 6314 1431 6314 1431 6315 3873 6315 1429 6315 3878 6316 3874 6316 3879 6316 3879 6317 3874 6317 3875 6317 3879 6318 3875 6318 3880 6318 3880 6319 3875 6319 3876 6319 3880 6320 3876 6320 3881 6320 3881 6321 3876 6321 3877 6321 3881 6322 3877 6322 1399 6322 1399 6323 3877 6323 1431 6323 3882 6324 3883 6324 3884 6324 3883 6325 3878 6325 3884 6325 3884 6326 3878 6326 3879 6326 3884 6327 3879 6327 3885 6327 3885 6328 3879 6328 3880 6328 3885 6329 3880 6329 3886 6329 3886 6330 3880 6330 3881 6330 3886 6331 3881 6331 1404 6331 1404 6332 3881 6332 1399 6332 3887 6333 3882 6333 3888 6333 3888 6334 3882 6334 3884 6334 3888 6335 3884 6335 3889 6335 3889 6336 3884 6336 3885 6336 3889 6337 3885 6337 3890 6337 3890 6338 3885 6338 3886 6338 3890 6339 3886 6339 1423 6339 1423 6340 3886 6340 1404 6340 3891 6341 3892 6341 3893 6341 3894 6342 3895 6342 3896 6342 3897 6343 3898 6343 2838 6343 3897 6344 2838 6344 3899 6344 3900 6345 3899 6345 2838 6345 3901 6346 3900 6346 2838 6346 3895 6347 3898 6347 3896 6347 3896 6348 3898 6348 3897 6348 3896 6349 3897 6349 3902 6349 3902 6350 3897 6350 3899 6350 3902 6351 3899 6351 3903 6351 3903 6352 3899 6352 3900 6352 3903 6353 3900 6353 3904 6353 3904 6354 3900 6354 3901 6354 3892 6355 3894 6355 3893 6355 3893 6356 3894 6356 3896 6356 3893 6357 3896 6357 3905 6357 3905 6358 3896 6358 3902 6358 3905 6359 3902 6359 3906 6359 3906 6360 3902 6360 3903 6360 3906 6361 3903 6361 3907 6361 3907 6362 3903 6362 3904 6362 3908 6363 3891 6363 3909 6363 3909 6364 3891 6364 3893 6364 3909 6365 3893 6365 3910 6365 3910 6366 3893 6366 3905 6366 3910 6367 3905 6367 3911 6367 3911 6368 3905 6368 3906 6368 3911 6369 3906 6369 3912 6369 3912 6370 3906 6370 3907 6370 3913 6371 3908 6371 3914 6371 3914 6372 3908 6372 3909 6372 3914 6373 3909 6373 3915 6373 3915 6374 3909 6374 3910 6374 3915 6375 3910 6375 3916 6375 3916 6376 3910 6376 3911 6376 3916 6377 3911 6377 3917 6377 3917 6378 3911 6378 3912 6378 1423 6379 3913 6379 3890 6379 3890 6380 3913 6380 3914 6380 3890 6381 3914 6381 3889 6381 3889 6382 3914 6382 3915 6382 3889 6383 3915 6383 3888 6383 3888 6384 3915 6384 3916 6384 3888 6385 3916 6385 3887 6385 3887 6386 3916 6386 3917 6386 1409 6387 1407 6387 3918 6387 1423 6388 1422 6388 3919 6388 3920 6389 2824 6389 3921 6389 3921 6390 2824 6390 3239 6390 3921 6391 3239 6391 2834 6391 2834 6392 3239 6392 3235 6392 2834 6393 3235 6393 2832 6393 2820 6394 2821 6394 3918 6394 3918 6395 2821 6395 2822 6395 3918 6396 2822 6396 3920 6396 3920 6397 2822 6397 2823 6397 3920 6398 2823 6398 2824 6398 2820 6399 3918 6399 2819 6399 2819 6400 3918 6400 1407 6400 2819 6401 1407 6401 1406 6401 3922 6402 3908 6402 3919 6402 3919 6403 3908 6403 3913 6403 3919 6404 3913 6404 1423 6404 3923 6405 3892 6405 3922 6405 3922 6406 3892 6406 3891 6406 3922 6407 3891 6407 3908 6407 2840 6408 2838 6408 3923 6408 3923 6409 2838 6409 3898 6409 3898 6410 3895 6410 3923 6410 3923 6411 3895 6411 3894 6411 3923 6412 3894 6412 3892 6412 1426 6413 1409 6413 3924 6413 3924 6414 1409 6414 3918 6414 3924 6415 3918 6415 3925 6415 3925 6416 3918 6416 3920 6416 3925 6417 3920 6417 3926 6417 3926 6418 3920 6418 3921 6418 3926 6419 3921 6419 2836 6419 2836 6420 3921 6420 2834 6420 2836 6421 2840 6421 3926 6421 3926 6422 2840 6422 3923 6422 3926 6423 3923 6423 3925 6423 3925 6424 3923 6424 3922 6424 3925 6425 3922 6425 3924 6425 3924 6426 3922 6426 3919 6426 3924 6427 3919 6427 1426 6427 1426 6428 3919 6428 1422 6428 3863 6429 3864 6429 3817 6429 3817 6430 3864 6430 3866 6430 3817 6431 3866 6431 3816 6431 3817 6432 3818 6432 3863 6432 3863 6433 3818 6433 3831 6433 3863 6434 3831 6434 3862 6434 3862 6435 3831 6435 3830 6435 3862 6436 3830 6436 3848 6436 3848 6437 3830 6437 3828 6437 3824 6438 934 6438 3826 6438 3826 6439 934 6439 3851 6439 3826 6440 3851 6440 3828 6440 3828 6441 3851 6441 3849 6441 3828 6442 3849 6442 3848 6442 3824 6443 3822 6443 934 6443 934 6444 3822 6444 3820 6444 934 6445 3820 6445 1837 6445 3866 6446 3869 6446 3816 6446 3816 6447 3869 6447 3870 6447 3816 6448 3870 6448 3808 6448 2838 6449 2837 6449 3795 6449 3798 6450 3901 6450 3797 6450 3797 6451 3901 6451 2838 6451 3797 6452 2838 6452 3796 6452 3796 6453 2838 6453 3795 6453 3870 6454 3874 6454 3808 6454 3808 6455 3874 6455 3878 6455 3808 6456 3878 6456 3806 6456 3806 6457 3878 6457 3883 6457 3806 6458 3883 6458 3804 6458 3804 6459 3883 6459 3882 6459 3804 6460 3882 6460 3802 6460 3802 6461 3882 6461 3887 6461 3887 6462 3917 6462 3802 6462 3802 6463 3917 6463 3912 6463 3802 6464 3912 6464 3800 6464 3800 6465 3912 6465 3907 6465 3800 6466 3907 6466 3798 6466 3798 6467 3907 6467 3904 6467 3798 6468 3904 6468 3901 6468 1578 106 1577 106 713 106 713 6469 1577 6469 1595 6469 1595 6470 1593 6470 713 6470 713 6471 1593 6471 1591 6471 713 106 1591 106 716 106 716 106 1591 106 1588 106 716 6472 1588 6472 1525 6472 676 6473 674 6473 3927 6473 709 6474 676 6474 710 6474 710 6475 676 6475 3927 6475 710 6476 3927 6476 714 6476 714 6477 3927 6477 1578 6477 714 6478 1578 6478 713 6478 1578 6479 3927 6479 3928 6479 3927 6480 674 6480 672 6480 3927 6481 672 6481 3928 6481 3928 6482 672 6482 670 6482 3928 6483 670 6483 3929 6483 3929 6484 670 6484 669 6484 3929 6485 669 6485 3930 6485 3930 6486 669 6486 667 6486 3930 6487 667 6487 3931 6487 1578 6488 3928 6488 1579 6488 1579 6489 3928 6489 3929 6489 1579 6490 3929 6490 1581 6490 1581 6491 3929 6491 3930 6491 1581 6492 3930 6492 1583 6492 1583 6493 3930 6493 3931 6493 1583 6494 3931 6494 1585 6494 716 6495 1525 6495 717 6495 717 6496 1525 6496 715 6496 715 6497 1525 6497 711 6497 938 6498 678 6498 1502 6498 1502 6499 678 6499 682 6499 1502 6500 682 6500 1511 6500 1511 6501 682 6501 681 6501 1511 6502 681 6502 1516 6502 1516 6503 681 6503 683 6503 3572 6504 3932 6504 3571 6504 3577 6505 3087 6505 3933 6505 3095 6506 3934 6506 3094 6506 3581 6507 3935 6507 3603 6507 3663 6508 3664 6508 3935 6508 3696 6509 3699 6509 3936 6509 3937 6510 3706 6510 3707 6510 3425 6511 3423 6511 3938 6511 3381 6512 3383 6512 3419 6512 2648 6513 3248 6513 3939 6513 2519 6514 2348 6514 2350 6514 3034 6515 3032 6515 3940 6515 3032 6516 3030 6516 3940 6516 3940 6517 3030 6517 3028 6517 3940 6518 3028 6518 3026 6518 3026 6519 3024 6519 3940 6519 3940 6520 3024 6520 3022 6520 3940 6521 3022 6521 3020 6521 3020 6522 3012 6522 3940 6522 3940 6523 3012 6523 3011 6523 3940 6524 3011 6524 3002 6524 3941 6525 2433 6525 3942 6525 3942 6526 2433 6526 2434 6526 3943 6527 2427 6527 3944 6527 3944 6528 2427 6528 2428 6528 3944 6529 2428 6529 2429 6529 2391 6530 2393 6530 3943 6530 3943 6531 2393 6531 2426 6531 3943 6532 2426 6532 2427 6532 2382 6533 2383 6533 3945 6533 3945 6534 2383 6534 2384 6534 3945 6535 2384 6535 2386 6535 2380 6536 2381 6536 3946 6536 3947 6537 2330 6537 3948 6537 3948 6538 2330 6538 2329 6538 3948 6539 2329 6539 2379 6539 2365 6540 2363 6540 3947 6540 3947 6541 2363 6541 2362 6541 3947 6542 2362 6542 2330 6542 2519 6543 2350 6543 2517 6543 2350 6544 2365 6544 2517 6544 2517 6545 2365 6545 3947 6545 2517 6546 3947 6546 2515 6546 2515 6547 3947 6547 3248 6547 2648 6548 3939 6548 2685 6548 2684 6549 3949 6549 2683 6549 2683 6550 3949 6550 3950 6550 2683 6551 3950 6551 2682 6551 2682 6552 3950 6552 3951 6552 2682 6553 3951 6553 2672 6553 2672 6554 3951 6554 3952 6554 2672 6555 3952 6555 2602 6555 3953 6556 3711 6556 2613 6556 2613 6557 3711 6557 2614 6557 3954 6558 3387 6558 3389 6558 3389 6559 3391 6559 3954 6559 3954 6560 3391 6560 3392 6560 3954 6561 3392 6561 3393 6561 3419 6562 3383 6562 3421 6562 3416 6563 2863 6563 3379 6563 3381 6564 3419 6564 3379 6564 3379 6565 3419 6565 3417 6565 3379 6566 3417 6566 3416 6566 3431 6567 3429 6567 3938 6567 3938 6568 3429 6568 3427 6568 3938 6569 3427 6569 3425 6569 3707 6570 3433 6570 3955 6570 3664 6571 3665 6571 3935 6571 3935 6572 3665 6572 3666 6572 3935 6573 3666 6573 3667 6573 3668 6574 3316 6574 3687 6574 3668 6575 3687 6575 3667 6575 3667 6576 3687 6576 3935 6576 3935 6577 3687 6577 3688 6577 3935 6578 3688 6578 3689 6578 3689 6579 3690 6579 3935 6579 3935 6580 3690 6580 3691 6580 3935 6581 3691 6581 3692 6581 3692 6582 3693 6582 3935 6582 3935 6583 3693 6583 3694 6583 3935 6584 3694 6584 3695 6584 3580 6585 3634 6585 3581 6585 3581 6586 3634 6586 3633 6586 3581 6587 3633 6587 3631 6587 3631 6588 3638 6588 3581 6588 3581 6589 3638 6589 3637 6589 3581 6590 3637 6590 3642 6590 3642 6591 3640 6591 3581 6591 3581 6592 3640 6592 3639 6592 3581 6593 3639 6593 3935 6593 3935 6594 3639 6594 3662 6594 3935 6595 3662 6595 3663 6595 3141 6596 3140 6596 3956 6596 3141 6597 3956 6597 3147 6597 3695 6598 3696 6598 3935 6598 3935 6599 3696 6599 3936 6599 3935 6600 3936 6600 3603 6600 3603 6601 3936 6601 3956 6601 3603 6602 3956 6602 3604 6602 3604 6603 3956 6603 3140 6603 3604 6604 3140 6604 3139 6604 3957 6605 3153 6605 3958 6605 3958 6606 3153 6606 3151 6606 3958 6607 3151 6607 3149 6607 3095 6608 3165 6608 3959 6608 3959 6609 3165 6609 3163 6609 3959 6610 3163 6610 3161 6610 3161 6611 3159 6611 3960 6611 3960 6612 3159 6612 3157 6612 3960 6613 3157 6613 3957 6613 3957 6614 3157 6614 3155 6614 3957 6615 3155 6615 3153 6615 3094 6616 3934 6616 3083 6616 3083 6617 3934 6617 3961 6617 3083 6618 3961 6618 3082 6618 3577 6619 3933 6619 3576 6619 3962 6620 3963 6620 3574 6620 3932 6621 3572 6621 3963 6621 3963 6622 3572 6622 3573 6622 3963 6623 3573 6623 3574 6623 3940 6624 3568 6624 3964 6624 3002 6625 3001 6625 3940 6625 3940 6626 3001 6626 3567 6626 3940 6627 3567 6627 3568 6627 3965 6628 3955 6628 3938 6628 3938 6629 3955 6629 3433 6629 3938 6630 3433 6630 3431 6630 3966 6631 3965 6631 3967 6631 3967 6632 3965 6632 3938 6632 3967 6633 3938 6633 3954 6633 3954 6634 3938 6634 3423 6634 3954 6635 3423 6635 3387 6635 3387 6636 3423 6636 3421 6636 3387 6637 3421 6637 3385 6637 3385 6638 3421 6638 3383 6638 3966 6639 3967 6639 3968 6639 3968 6640 3967 6640 3954 6640 3968 6641 3954 6641 3953 6641 3953 6642 3954 6642 3393 6642 3953 6643 3393 6643 3711 6643 3950 6644 3969 6644 3951 6644 3951 6645 3969 6645 3966 6645 3951 6646 3966 6646 3952 6646 3952 6647 3966 6647 3968 6647 3952 6648 3968 6648 2602 6648 2602 6649 3968 6649 3953 6649 2602 6650 3953 6650 2599 6650 2599 6651 3953 6651 2613 6651 2381 6652 2382 6652 3946 6652 3946 6653 2382 6653 3945 6653 3946 6654 3945 6654 3970 6654 3937 6655 3707 6655 3971 6655 3971 6656 3707 6656 3955 6656 3971 6657 3955 6657 3972 6657 3972 6658 3955 6658 3965 6658 3972 6659 3965 6659 3973 6659 3973 6660 3965 6660 3966 6660 3973 6661 3966 6661 3974 6661 3974 6662 3966 6662 3969 6662 3974 6663 3969 6663 3975 6663 3975 6664 3969 6664 3950 6664 3975 6665 3950 6665 3976 6665 3976 6666 3950 6666 3949 6666 3976 6667 3949 6667 3977 6667 3977 6668 3949 6668 2684 6668 3977 6669 2684 6669 2685 6669 3248 6670 3947 6670 3939 6670 3939 6671 3947 6671 3948 6671 3939 6672 3948 6672 3978 6672 3978 6673 3948 6673 3979 6673 3978 6674 3979 6674 3980 6674 3980 6675 3979 6675 3981 6675 3980 6676 3981 6676 3982 6676 3982 6677 3981 6677 3983 6677 3982 6678 3983 6678 3984 6678 3984 6679 3983 6679 3985 6679 3984 6680 3985 6680 3986 6680 2685 6681 3939 6681 3977 6681 3977 6682 3939 6682 3978 6682 3977 6683 3978 6683 3976 6683 3976 6684 3978 6684 3980 6684 3976 6685 3980 6685 3975 6685 3975 6686 3980 6686 3982 6686 3975 6687 3982 6687 3974 6687 3974 6688 3982 6688 3984 6688 3974 6689 3984 6689 3973 6689 3973 6690 3984 6690 3986 6690 3973 6691 3986 6691 3972 6691 3987 6692 3988 6692 3989 6692 3990 6693 3943 6693 3991 6693 3991 6694 3943 6694 3944 6694 3991 6695 3944 6695 3992 6695 3992 6696 3944 6696 2429 6696 3992 6697 2429 6697 3993 6697 3993 6698 2429 6698 2430 6698 3993 6699 2430 6699 3994 6699 3994 6700 2430 6700 2431 6700 3994 6701 2431 6701 3941 6701 3941 6702 2431 6702 2432 6702 3941 6703 2432 6703 2433 6703 3995 6704 3996 6704 3989 6704 3989 6705 3996 6705 3962 6705 3989 6706 3962 6706 3987 6706 3987 6707 3962 6707 3574 6707 3568 6708 3569 6708 3964 6708 3964 6709 3569 6709 3570 6709 3964 6710 3570 6710 3997 6710 3997 6711 3570 6711 3571 6711 3997 6712 3571 6712 3998 6712 3998 6713 3571 6713 3932 6713 3998 6714 3932 6714 3999 6714 3999 6715 3932 6715 3963 6715 3999 6716 3963 6716 4000 6716 4000 6717 3963 6717 3962 6717 4000 6718 3962 6718 4001 6718 4001 6719 3962 6719 3996 6719 4002 6720 3933 6720 3961 6720 3961 6721 3933 6721 3087 6721 3961 6722 3087 6722 3082 6722 3574 6723 3575 6723 3987 6723 3987 6724 3575 6724 3576 6724 3987 6725 3576 6725 3988 6725 3988 6726 3576 6726 3933 6726 3988 6727 3933 6727 3989 6727 3989 6728 3933 6728 4002 6728 3989 6729 4002 6729 3995 6729 3095 6730 3959 6730 3934 6730 3934 6731 3959 6731 4003 6731 3934 6732 4003 6732 3961 6732 3961 6733 4003 6733 4004 6733 3961 6734 4004 6734 4002 6734 4002 6735 4004 6735 4005 6735 4002 6736 4005 6736 3995 6736 3990 6737 4006 6737 3943 6737 3943 6738 4006 6738 4007 6738 3943 6739 4007 6739 2391 6739 2391 6740 4007 6740 2389 6740 4005 6741 4008 6741 3995 6741 3995 6742 4008 6742 4006 6742 3995 6743 4006 6743 3996 6743 3996 6744 4006 6744 3990 6744 3996 6745 3990 6745 4001 6745 4001 6746 3990 6746 3991 6746 4001 6747 3991 6747 4000 6747 4000 6748 3991 6748 3992 6748 4000 6749 3992 6749 3999 6749 3999 6750 3992 6750 3993 6750 3999 6751 3993 6751 3998 6751 3998 6752 3993 6752 3994 6752 3998 6753 3994 6753 3997 6753 3997 6754 3994 6754 3941 6754 3997 6755 3941 6755 3964 6755 3964 6756 3941 6756 3942 6756 3964 6757 3942 6757 3940 6757 3940 6758 3942 6758 2434 6758 3940 6759 2434 6759 3034 6759 3161 6760 3960 6760 3959 6760 3959 6761 3960 6761 4009 6761 3959 6762 4009 6762 4003 6762 4003 6763 4009 6763 4010 6763 4003 6764 4010 6764 4004 6764 4004 6765 4010 6765 4011 6765 4004 6766 4011 6766 4005 6766 4005 6767 4011 6767 4012 6767 4005 6768 4012 6768 4008 6768 2389 6769 4007 6769 2388 6769 2388 6770 4007 6770 4006 6770 2388 6771 4006 6771 2386 6771 2386 6772 4006 6772 4008 6772 2386 6773 4008 6773 3945 6773 3945 6774 4008 6774 4012 6774 3945 6775 4012 6775 3970 6775 3970 6776 4012 6776 4011 6776 3970 6777 4011 6777 4013 6777 4013 6778 4011 6778 4010 6778 4013 6779 4010 6779 4014 6779 4014 6780 4010 6780 4009 6780 4014 6781 4009 6781 4015 6781 4015 6782 4009 6782 3960 6782 4015 6783 3960 6783 4016 6783 4016 6784 3960 6784 3957 6784 4016 6785 3957 6785 4017 6785 4017 6786 3957 6786 3958 6786 4017 6787 3958 6787 3956 6787 3956 6788 3958 6788 3149 6788 3956 6789 3149 6789 3147 6789 2379 6790 2380 6790 3948 6790 3948 6791 2380 6791 3946 6791 3948 6792 3946 6792 3979 6792 3979 6793 3946 6793 3970 6793 3979 6794 3970 6794 3981 6794 3981 6795 3970 6795 4013 6795 3981 6796 4013 6796 3983 6796 3983 6797 4013 6797 4014 6797 3983 6798 4014 6798 3985 6798 3985 6799 4014 6799 4015 6799 3985 6800 4015 6800 3986 6800 3986 6801 4015 6801 4016 6801 3986 6802 4016 6802 3972 6802 3972 6803 4016 6803 4017 6803 3972 6804 4017 6804 3971 6804 3971 6805 4017 6805 3956 6805 3971 6806 3956 6806 3937 6806 3937 6807 3956 6807 3936 6807 3937 6808 3936 6808 3706 6808 3706 6809 3936 6809 3699 6809 1658 6810 1662 6810 4018 6810 1659 6811 1625 6811 4019 6811 1660 6812 4020 6812 1661 6812 1661 6813 4020 6813 4021 6813 1661 6814 4021 6814 1662 6814 1659 6815 4019 6815 1660 6815 1660 6816 4019 6816 4022 6816 1660 6817 4022 6817 4020 6817 4020 6818 4022 6818 4023 6818 4020 6819 4023 6819 4021 6819 4021 6820 4023 6820 4024 6820 4021 6821 4024 6821 4025 6821 4025 6822 4024 6822 4026 6822 4025 6823 4026 6823 4027 6823 4027 6824 4026 6824 4028 6824 4027 6825 4028 6825 4029 6825 4029 6826 4028 6826 4030 6826 4029 6827 4030 6827 4031 6827 4031 6828 4030 6828 4032 6828 4031 6829 4032 6829 4033 6829 4033 6830 4032 6830 3075 6830 4033 6831 3075 6831 4034 6831 1662 6832 4021 6832 4018 6832 4018 6833 4021 6833 4025 6833 4018 6834 4025 6834 4035 6834 4035 6835 4025 6835 4027 6835 4035 6836 4027 6836 4036 6836 4036 6837 4027 6837 4029 6837 4036 6838 4029 6838 4037 6838 4037 6839 4029 6839 4031 6839 4037 6840 4031 6840 4038 6840 4038 6841 4031 6841 4033 6841 4038 6842 4033 6842 4039 6842 4039 6843 4033 6843 4034 6843 4039 6844 4034 6844 4040 6844 1658 6845 4018 6845 1653 6845 1653 6846 4018 6846 4035 6846 1653 6847 4035 6847 1931 6847 1931 6848 4035 6848 4036 6848 1931 6849 4036 6849 1932 6849 1932 6850 4036 6850 4037 6850 1932 6851 4037 6851 1925 6851 1925 6852 4037 6852 4038 6852 1925 6853 4038 6853 1926 6853 1926 6854 4038 6854 4039 6854 1926 6855 4039 6855 1933 6855 1933 6856 4039 6856 4040 6856 1933 6857 4040 6857 1934 6857 1937 6858 1934 6858 4041 6858 4041 6859 1934 6859 4040 6859 4041 6860 4040 6860 4042 6860 4042 6861 4040 6861 4034 6861 4042 6862 4034 6862 3074 6862 3074 6863 4034 6863 3075 6863 1929 6864 1937 6864 4043 6864 4043 6865 1937 6865 4041 6865 4043 6866 4041 6866 4044 6866 4044 6867 4041 6867 4042 6867 4044 6868 4042 6868 3073 6868 3073 6869 4042 6869 3074 6869 1927 6870 1929 6870 3529 6870 3529 6871 1929 6871 4043 6871 3529 6872 4043 6872 3533 6872 3533 6873 4043 6873 4044 6873 3533 6874 4044 6874 3050 6874 3050 6875 4044 6875 3073 6875 1280 6876 4045 6876 1275 6876 1275 6877 4045 6877 4046 6877 1275 6878 4046 6878 1276 6878 1280 6879 1281 6879 4045 6879 4045 6880 1281 6880 4047 6880 4045 6881 4047 6881 4046 6881 4046 6882 4047 6882 2130 6882 4048 6883 4049 6883 4050 6883 4051 6884 4052 6884 655 6884 655 6885 4052 6885 656 6885 656 6886 4052 6886 658 6886 658 6887 4052 6887 4053 6887 658 6888 4053 6888 659 6888 659 6889 4053 6889 4054 6889 659 6890 4054 6890 660 6890 660 6891 4054 6891 4055 6891 660 6892 4055 6892 662 6892 662 6893 4055 6893 4056 6893 662 6894 4056 6894 663 6894 663 6895 4056 6895 4057 6895 663 6896 4057 6896 661 6896 661 6897 4057 6897 4058 6897 661 6898 4058 6898 657 6898 4049 6899 2118 6899 2102 6899 4048 6900 4050 6900 4051 6900 4049 6901 2102 6901 4050 6901 4050 6902 2102 6902 2080 6902 4050 6903 2080 6903 4059 6903 4059 6904 2080 6904 2079 6904 4059 6905 2079 6905 4060 6905 4060 6906 2079 6906 2084 6906 4060 6907 2084 6907 4061 6907 4061 6908 2084 6908 2083 6908 4061 6909 2083 6909 4062 6909 4062 6910 2083 6910 2082 6910 4062 6911 2082 6911 4063 6911 4063 6912 2082 6912 2068 6912 4063 6913 2068 6913 4064 6913 4051 6914 4050 6914 4052 6914 4052 6915 4050 6915 4059 6915 4052 6916 4059 6916 4053 6916 4053 6917 4059 6917 4060 6917 4053 6918 4060 6918 4054 6918 4054 6919 4060 6919 4061 6919 4054 6920 4061 6920 4055 6920 4055 6921 4061 6921 4062 6921 4055 6922 4062 6922 4056 6922 4056 6923 4062 6923 4063 6923 4056 6924 4063 6924 4057 6924 4057 6925 4063 6925 4064 6925 4057 6926 4064 6926 4058 6926 1282 6927 1271 6927 4065 6927 1282 6928 4065 6928 4066 6928 4066 6929 4065 6929 1939 6929 4066 6930 1939 6930 2128 6930 2128 6931 2130 6931 4047 6931 2128 6932 4047 6932 4066 6932 4066 6933 4047 6933 1281 6933 4066 6934 1281 6934 1282 6934 667 6935 1276 6935 4046 6935 667 6936 4046 6936 3931 6936 3931 6937 4046 6937 2130 6937 3931 6938 2130 6938 1585 6938 4067 6939 1947 6939 1945 6939 1241 6940 4067 6940 4068 6940 4067 6941 1945 6941 4068 6941 4068 6942 1945 6942 1943 6942 4068 6943 1943 6943 4069 6943 4069 6944 1943 6944 1941 6944 4069 6945 1941 6945 4070 6945 4070 6946 1941 6946 1939 6946 4070 6947 1939 6947 4065 6947 1241 6948 4068 6948 1268 6948 1268 6949 4068 6949 4069 6949 1268 6950 4069 6950 1266 6950 1266 6951 4069 6951 4070 6951 1266 6952 4070 6952 1264 6952 1264 6953 4070 6953 4065 6953 1264 6954 4065 6954 1271 6954 2639 6955 2638 6955 4049 6955 4051 6956 655 6956 654 6956 4049 6957 2638 6957 2118 6957 2118 6958 2638 6958 2636 6958 2118 6959 2636 6959 2637 6959 654 6960 653 6960 4051 6960 4051 6961 653 6961 634 6961 4051 6962 634 6962 4048 6962 4048 6963 634 6963 2640 6963 4048 6964 2640 6964 4049 6964 4049 6965 2640 6965 2639 6965 1251 6966 1252 6966 4071 6966 4071 6967 1252 6967 4072 6967 4071 6968 4072 6968 1936 6968 1936 6969 4072 6969 1935 6969 1256 6970 1251 6970 4073 6970 4073 6971 1251 6971 4071 6971 4073 6972 4071 6972 1930 6972 1930 6973 4071 6973 1936 6973 1256 6974 4073 6974 4074 6974 1256 6975 4074 6975 1255 6975 1255 6976 4074 6976 4075 6976 1255 6977 4075 6977 1253 6977 1253 6978 4075 6978 4076 6978 1253 6979 4076 6979 1254 6979 1254 6980 4076 6980 4077 6980 1254 6981 4077 6981 1249 6981 4073 6982 1930 6982 1963 6982 4073 6983 1963 6983 4074 6983 4074 6984 1963 6984 1962 6984 4074 6985 1962 6985 4075 6985 4075 6986 1962 6986 1948 6986 4075 6987 1948 6987 4076 6987 4076 6988 1948 6988 1949 6988 4076 6989 1949 6989 4077 6989 2018 6990 2020 6990 2034 6990 639 6991 4078 6991 4079 6991 639 6992 4079 6992 640 6992 640 6993 4079 6993 4080 6993 640 6994 4080 6994 646 6994 646 6995 4080 6995 4081 6995 646 6996 4081 6996 647 6996 647 6997 4081 6997 4082 6997 647 6998 4082 6998 648 6998 648 6999 4082 6999 4083 6999 648 7000 4083 7000 652 7000 652 7001 4083 7001 4084 7001 652 7002 4084 7002 629 7002 629 7003 4084 7003 4085 7003 629 7004 4085 7004 644 7004 644 7005 4085 7005 4086 7005 644 7006 4086 7006 635 7006 635 7007 4086 7007 4087 7007 635 7008 4087 7008 636 7008 636 7009 4087 7009 4088 7009 636 7010 4088 7010 637 7010 637 7011 4088 7011 2036 7011 637 7012 2036 7012 631 7012 4089 7013 1967 7013 1970 7013 4078 7014 4089 7014 4090 7014 1978 7015 4091 7015 1976 7015 1976 7016 4091 7016 4092 7016 4089 7017 1970 7017 4090 7017 4090 7018 1970 7018 1972 7018 4090 7019 1972 7019 4092 7019 4092 7020 1972 7020 1974 7020 4092 7021 1974 7021 1976 7021 1988 7022 4093 7022 1986 7022 1986 7023 4093 7023 4094 7023 1978 7024 1980 7024 4091 7024 4091 7025 1980 7025 1982 7025 4091 7026 1982 7026 4094 7026 4094 7027 1982 7027 1984 7027 4094 7028 1984 7028 1986 7028 1998 7029 4095 7029 1996 7029 1996 7030 4095 7030 4096 7030 1988 7031 1990 7031 4093 7031 4093 7032 1990 7032 1992 7032 4093 7033 1992 7033 4096 7033 4096 7034 1992 7034 1994 7034 4096 7035 1994 7035 1996 7035 2008 7036 4097 7036 2006 7036 2006 7037 4097 7037 4098 7037 1998 7038 2000 7038 4095 7038 4095 7039 2000 7039 2002 7039 4095 7040 2002 7040 4098 7040 4098 7041 2002 7041 2004 7041 4098 7042 2004 7042 2006 7042 2008 7043 2010 7043 4097 7043 4097 7044 2010 7044 2012 7044 4097 7045 2012 7045 4099 7045 4099 7046 2012 7046 2014 7046 4099 7047 2014 7047 2016 7047 2035 7048 4099 7048 2034 7048 2034 7049 4099 7049 2016 7049 2034 7050 2016 7050 2018 7050 4078 7051 4090 7051 4079 7051 4079 7052 4090 7052 4092 7052 4079 7053 4092 7053 4080 7053 4080 7054 4092 7054 4091 7054 4080 7055 4091 7055 4081 7055 4081 7056 4091 7056 4094 7056 4081 7057 4094 7057 4082 7057 4082 7058 4094 7058 4093 7058 4082 7059 4093 7059 4083 7059 4083 7060 4093 7060 4096 7060 4083 7061 4096 7061 4084 7061 4084 7062 4096 7062 4095 7062 4084 7063 4095 7063 4085 7063 4085 7064 4095 7064 4098 7064 4085 7065 4098 7065 4086 7065 4086 7066 4098 7066 4097 7066 4086 7067 4097 7067 4087 7067 4087 7068 4097 7068 4099 7068 4087 7069 4099 7069 4088 7069 4088 7070 4099 7070 2035 7070 4088 7071 2035 7071 2036 7071 643 7072 642 7072 4100 7072 4100 7073 642 7073 4101 7073 4100 7074 4101 7074 4102 7074 4102 7075 4101 7075 4103 7075 4102 7076 4103 7076 2044 7076 2044 7077 4103 7077 2045 7077 639 7078 643 7078 4078 7078 4078 7079 643 7079 4100 7079 4078 7080 4100 7080 4089 7080 4089 7081 4100 7081 4102 7081 4089 7082 4102 7082 1967 7082 1967 7083 4102 7083 2044 7083 641 7084 645 7084 4104 7084 4104 7085 645 7085 4105 7085 4104 7086 4105 7086 4106 7086 4106 7087 4105 7087 4107 7087 4106 7088 4107 7088 2060 7088 2060 7089 4107 7089 2064 7089 642 7090 641 7090 4101 7090 4101 7091 641 7091 4104 7091 4101 7092 4104 7092 4103 7092 4103 7093 4104 7093 4106 7093 4103 7094 4106 7094 2045 7094 2045 7095 4106 7095 2060 7095 2066 7096 2064 7096 4108 7096 4108 7097 2064 7097 4107 7097 4108 7098 4107 7098 4109 7098 4109 7099 4107 7099 4105 7099 4109 7100 4105 7100 633 7100 633 7101 4105 7101 645 7101 632 7102 657 7102 4110 7102 4110 7103 657 7103 4058 7103 4110 7104 4058 7104 4111 7104 4111 7105 4058 7105 4064 7105 4111 7106 4064 7106 2067 7106 2067 7107 4064 7107 2068 7107 633 7108 632 7108 4109 7108 4109 7109 632 7109 4110 7109 4109 7110 4110 7110 4108 7110 4108 7111 4110 7111 4111 7111 4108 7112 4111 7112 2066 7112 2066 7113 4111 7113 2067 7113 1249 7114 4077 7114 4112 7114 1249 7115 4112 7115 1250 7115 1250 7116 4112 7116 4113 7116 1250 7117 4113 7117 1259 7117 1259 7118 4113 7118 1247 7118 1247 7119 4113 7119 4114 7119 1247 7120 4114 7120 1245 7120 1245 7121 4114 7121 4115 7121 1245 7122 4115 7122 1243 7122 1243 7123 4115 7123 4067 7123 1243 7124 4067 7124 1241 7124 4077 7125 1949 7125 1951 7125 4077 7126 1951 7126 4112 7126 4112 7127 1951 7127 1953 7127 4112 7128 1953 7128 4113 7128 4113 7129 1953 7129 1955 7129 4113 7130 1955 7130 4114 7130 1955 7131 1957 7131 4114 7131 4114 7132 1957 7132 1959 7132 4114 7133 1959 7133 4115 7133 4115 7134 1959 7134 1947 7134 4115 7135 1947 7135 4067 7135 4022 7136 4116 7136 4023 7136 4117 7137 2019 7137 3072 7137 4118 7138 4119 7138 4120 7138 4120 7139 4119 7139 4121 7139 4120 7140 4121 7140 4117 7140 4122 7141 4123 7141 4124 7141 4124 7142 4123 7142 4125 7142 4124 7143 4125 7143 4120 7143 4120 7144 4125 7144 4126 7144 4120 7145 4126 7145 4118 7145 4127 7146 4128 7146 4116 7146 4116 7147 4128 7147 4122 7147 1623 7148 2537 7148 1624 7148 1624 7149 2537 7149 4129 7149 1624 7150 4129 7150 1625 7150 4127 7151 4116 7151 4130 7151 4130 7152 4116 7152 4022 7152 4130 7153 4022 7153 4129 7153 4129 7154 4022 7154 4019 7154 4129 7155 4019 7155 1625 7155 4122 7156 4124 7156 4116 7156 4116 7157 4124 7157 4024 7157 4116 7158 4024 7158 4023 7158 4032 7159 4030 7159 4120 7159 4120 7160 4030 7160 4028 7160 4120 7161 4028 7161 4124 7161 4124 7162 4028 7162 4026 7162 4124 7163 4026 7163 4024 7163 4117 7164 3072 7164 4120 7164 4120 7165 3072 7165 3075 7165 4120 7166 3075 7166 4032 7166 2020 7167 2019 7167 4117 7167 2020 7168 4117 7168 2032 7168 2032 7169 4117 7169 4121 7169 2032 7170 4121 7170 2033 7170 2537 7171 2536 7171 4129 7171 4129 7172 2536 7172 2540 7172 4129 7173 2540 7173 4130 7173 4130 7174 2540 7174 2539 7174 4130 7175 2539 7175 4127 7175 4127 7176 2539 7176 2545 7176 4127 7177 2545 7177 4128 7177 4128 7178 2545 7178 2546 7178 4128 7179 2546 7179 4122 7179 4122 7180 2546 7180 2548 7180 4122 7181 2548 7181 4123 7181 4123 7182 2548 7182 2549 7182 4123 7183 2549 7183 4125 7183 4125 7184 2549 7184 2026 7184 4125 7185 2026 7185 4126 7185 4126 7186 2026 7186 2025 7186 4126 7187 2025 7187 4118 7187 4118 7188 2025 7188 2033 7188 4118 7189 2033 7189 4119 7189 4119 7190 2033 7190 4121 7190 664 7191 4131 7191 665 7191 665 632 4131 632 1273 632 3 7192 1725 7192 1738 7192 1672 7193 1673 7193 1697 7193 4132 7194 4133 7194 4134 7194 4134 7195 4133 7195 4135 7195 4134 7196 4135 7196 4136 7196 4136 7197 4135 7197 3 7197 1 7198 8 7198 1679 7198 1738 7199 1745 7199 3 7199 3 7200 1745 7200 1750 7200 3 7201 1750 7201 1755 7201 1697 7202 1703 7202 1672 7202 1672 7203 1703 7203 1708 7203 1672 7204 1708 7204 1671 7204 1671 7205 1708 7205 1714 7205 1671 7206 1714 7206 1679 7206 1679 7207 1714 7207 1715 7207 1679 7208 1715 7208 1718 7208 1755 7209 4137 7209 3 7209 3 7210 4137 7210 4138 7210 3 7211 4138 7211 4136 7211 3 7212 1 7212 1725 7212 1725 7213 1 7213 1679 7213 1725 7214 1679 7214 1726 7214 1726 7215 1679 7215 1718 7215 9 7216 1689 7216 7 7216 7 7217 1689 7217 1684 7217 7 7218 1684 7218 1683 7218 1682 7219 6 7219 1683 7219 1683 7220 6 7220 5 7220 1683 7221 5 7221 7 7221 1679 7222 8 7222 1680 7222 1680 7223 8 7223 6 7223 1680 7224 6 7224 1681 7224 1681 7225 6 7225 1682 7225 2710 7226 10 7226 2709 7226 2709 7227 10 7227 11 7227 11 7228 13 7228 2709 7228 2709 7229 13 7229 14 7229 2709 7230 14 7230 2708 7230 12 7231 0 7231 353 7231 353 7232 2699 7232 12 7232 12 7233 2699 7233 2698 7233 12 7234 2698 7234 14 7234 14 7235 2698 7235 2697 7235 14 7236 2697 7236 2708 7236 2581 7237 9 7237 2580 7237 2580 7238 9 7238 10 7238 2580 7239 10 7239 2712 7239 2712 7240 10 7240 2710 7240 2581 7241 2567 7241 9 7241 9 7242 2567 7242 2559 7242 9 7243 2559 7243 1689 7243 2209 7244 2210 7244 4139 7244 1378 7245 1380 7245 2242 7245 2242 7246 1380 7246 4140 7246 2242 7247 4140 7247 2215 7247 2215 7248 4140 7248 4141 7248 4142 7249 4143 7249 4144 7249 4145 7250 4142 7250 4146 7250 4146 7251 4142 7251 4147 7251 4145 7252 4148 7252 4142 7252 4142 7253 4148 7253 4149 7253 4142 7254 4149 7254 4143 7254 4150 7255 4147 7255 4151 7255 4151 7256 4147 7256 4142 7256 4151 7257 4142 7257 4152 7257 4152 7258 4142 7258 4144 7258 4141 7259 4150 7259 2215 7259 2215 7260 4150 7260 4151 7260 2215 7261 4151 7261 2216 7261 2216 7262 4151 7262 4153 7262 2216 7263 4153 7263 2218 7263 2218 7264 4153 7264 4154 7264 2218 7265 4154 7265 2220 7265 2220 7266 4154 7266 2222 7266 4154 7267 4155 7267 2222 7267 2222 7268 4155 7268 4156 7268 2222 7269 4156 7269 2224 7269 2224 7270 4156 7270 4157 7270 2224 7271 4157 7271 2213 7271 2213 7272 4157 7272 2211 7272 2211 7273 4157 7273 4158 7273 2211 7274 4158 7274 2210 7274 2210 7275 4158 7275 4159 7275 2210 7276 4159 7276 4160 7276 4160 7277 4161 7277 2210 7277 2210 7278 4161 7278 4162 7278 2210 7279 4162 7279 4139 7279 4139 7280 4162 7280 4163 7280 4139 7281 4163 7281 4164 7281 4165 7282 1917 7282 4166 7282 4166 7283 1917 7283 2207 7283 4166 7284 2207 7284 4167 7284 4167 7285 2207 7285 4139 7285 4139 7286 2207 7286 2208 7286 4139 7287 2208 7287 2209 7287 1917 106 4165 106 4168 106 4169 106 1786 106 4168 106 4168 7288 1786 7288 1785 7288 1785 7289 1784 7289 4168 7289 4168 7290 1784 7290 1783 7290 4168 106 1783 106 1917 106 4170 7291 4171 7291 1935 7291 372 7292 370 7292 4171 7292 4171 7293 370 7293 1663 7293 4171 7294 1663 7294 1935 7294 1935 7295 4072 7295 4170 7295 4170 7296 4072 7296 1252 7296 4170 7297 1252 7297 1263 7297 4172 7298 4173 7298 4174 7298 1269 7299 4175 7299 1270 7299 1270 7300 4175 7300 4176 7300 1270 7301 4176 7301 1242 7301 4177 7302 1248 7302 1246 7302 1260 7303 1258 7303 4177 7303 4177 7304 1258 7304 1257 7304 4177 7305 1257 7305 1248 7305 4171 7306 4170 7306 4178 7306 4178 7307 4170 7307 1263 7307 4178 7308 1263 7308 4179 7308 4179 7309 1263 7309 1262 7309 4179 7310 1262 7310 4180 7310 1262 7311 1261 7311 4180 7311 4180 7312 1261 7312 1260 7312 4180 7313 1260 7313 4174 7313 4174 7314 1260 7314 4177 7314 4174 7315 4177 7315 4172 7315 4172 7316 4177 7316 1246 7316 4172 7317 1246 7317 4176 7317 4176 7318 1246 7318 1244 7318 4176 7319 1244 7319 1242 7319 4181 7320 4182 7320 4183 7320 4184 7321 4185 7321 4186 7321 4187 7322 4188 7322 4189 7322 4176 7323 4175 7323 4190 7323 4172 7324 4176 7324 4191 7324 4173 7325 4172 7325 4192 7325 4193 7326 4194 7326 4192 7326 4192 7327 4194 7327 4195 7327 4192 7328 4195 7328 4173 7328 4176 7329 4190 7329 4191 7329 4191 7330 4190 7330 4196 7330 4191 7331 4196 7331 4197 7331 4197 7332 4196 7332 4198 7332 4197 7333 4198 7333 4199 7333 4198 7334 4200 7334 4199 7334 4199 7335 4200 7335 4201 7335 4199 7336 4201 7336 4202 7336 4202 7337 4201 7337 4203 7337 4202 7338 4203 7338 4204 7338 4203 7339 4205 7339 4204 7339 4204 7340 4205 7340 4206 7340 4204 7341 4206 7341 4207 7341 4207 7342 4206 7342 4208 7342 4207 7343 4208 7343 4209 7343 4192 7344 4210 7344 4193 7344 4193 7345 4210 7345 4211 7345 4193 7346 4211 7346 4212 7346 4212 7347 4211 7347 4213 7347 4212 7348 4213 7348 4214 7348 4214 7349 4213 7349 4215 7349 4214 7350 4215 7350 4216 7350 4216 7351 4215 7351 4217 7351 4216 7352 4217 7352 4218 7352 4218 7353 4217 7353 4219 7353 4218 7354 4219 7354 4220 7354 4220 7355 4219 7355 4221 7355 4220 7356 4221 7356 4222 7356 4222 7357 4221 7357 4223 7357 4222 7358 4223 7358 4224 7358 4224 7359 4223 7359 4181 7359 4224 7360 4181 7360 4225 7360 4225 7361 4181 7361 4183 7361 4208 7362 4226 7362 4209 7362 4209 7363 4226 7363 4227 7363 4209 7364 4227 7364 4228 7364 4228 7365 4227 7365 4229 7365 4228 7366 4229 7366 4230 7366 4230 7367 4229 7367 4187 7367 4230 7368 4187 7368 4184 7368 4184 7369 4187 7369 4189 7369 4184 7370 4189 7370 4185 7370 4172 7371 4191 7371 4192 7371 4192 7372 4191 7372 4197 7372 4192 7373 4197 7373 4210 7373 4210 7374 4197 7374 4199 7374 4210 7375 4199 7375 4211 7375 4211 7376 4199 7376 4202 7376 4211 7377 4202 7377 4213 7377 4213 7378 4202 7378 4204 7378 4213 7379 4204 7379 4215 7379 4215 7380 4204 7380 4207 7380 4215 7381 4207 7381 4217 7381 4217 7382 4207 7382 4209 7382 4217 7383 4209 7383 4219 7383 4219 7384 4209 7384 4228 7384 4219 7385 4228 7385 4221 7385 4221 7386 4228 7386 4230 7386 4221 7387 4230 7387 4223 7387 4223 7388 4230 7388 4184 7388 4223 7389 4184 7389 4181 7389 4181 7390 4184 7390 4186 7390 4181 7391 4186 7391 4182 7391 375 7392 374 7392 4231 7392 4232 7393 4233 7393 4234 7393 4234 7394 4233 7394 4231 7394 375 7395 4231 7395 371 7395 371 7396 4231 7396 4233 7396 371 7397 4233 7397 368 7397 4171 7398 4178 7398 372 7398 372 7399 4178 7399 4179 7399 372 7400 4179 7400 373 7400 374 7401 373 7401 4231 7401 4231 7402 373 7402 4179 7402 4231 7403 4179 7403 4235 7403 4179 7404 4180 7404 4235 7404 4235 7405 4180 7405 4174 7405 4235 7406 4174 7406 4236 7406 4236 7406 4174 7406 4173 7406 4236 7407 4173 7407 4237 7407 4237 7408 4173 7408 4195 7408 4237 7409 4195 7409 4238 7409 4238 7410 4195 7410 4194 7410 4238 7411 4194 7411 4239 7411 4224 7412 4225 7412 4240 7412 4218 7413 4220 7413 4240 7413 4240 7414 4220 7414 4222 7414 4240 7415 4222 7415 4224 7415 4240 7416 4193 7416 4212 7416 4212 7417 4214 7417 4240 7417 4240 7418 4214 7418 4216 7418 4240 7419 4216 7419 4218 7419 4225 7420 4241 7420 4240 7420 4240 7421 4241 7421 4194 7421 4240 7422 4194 7422 4193 7422 4241 7423 4242 7423 4194 7423 4194 7424 4242 7424 4243 7424 4194 7425 4243 7425 4244 7425 4244 7426 4245 7426 4194 7426 4194 7427 4245 7427 4246 7427 4194 7428 4246 7428 4247 7428 4247 7429 4248 7429 4194 7429 4194 7430 4248 7430 4249 7430 4194 7431 4249 7431 4239 7431 1265 95 4250 95 1267 95 1267 95 4250 95 4175 95 1267 95 4175 95 1269 95 4229 7432 4227 7432 4251 7432 4252 7433 4198 7433 4196 7433 4252 7434 4196 7434 4250 7434 4250 7435 4196 7435 4190 7435 4250 7436 4190 7436 4175 7436 4205 7437 4203 7437 4253 7437 4253 7438 4203 7438 4201 7438 4253 7439 4201 7439 4252 7439 4252 7440 4201 7440 4200 7440 4252 7441 4200 7441 4198 7441 4205 7442 4253 7442 4206 7442 4206 7443 4253 7443 4254 7443 4206 7444 4254 7444 4208 7444 4251 7445 4227 7445 4254 7445 4254 7446 4227 7446 4226 7446 4254 7447 4226 7447 4208 7447 4229 7448 4251 7448 4187 7448 4187 7449 4251 7449 4255 7449 4187 7450 4255 7450 4188 7450 4250 106 1265 106 948 106 4250 7451 948 7451 4252 7451 948 7452 947 7452 555 7452 555 106 554 106 4256 106 4256 7453 4257 7453 555 7453 555 106 4257 106 4258 106 555 7454 4258 7454 4259 7454 4259 106 4260 106 555 106 555 7455 4260 7455 4261 7455 555 7456 4261 7456 948 7456 948 7457 4261 7457 4262 7457 948 7458 4262 7458 4255 7458 4253 7459 4252 7459 4254 7459 4254 106 4252 106 948 106 4254 106 948 106 4251 106 4251 106 948 106 4255 106 2525 106 1758 106 969 106 2442 7460 2441 7460 2476 7460 2441 106 2443 106 2476 106 2476 7461 2443 7461 2444 7461 2476 7462 2444 7462 2445 7462 970 7463 1219 7463 2497 7463 1004 7464 963 7464 2440 7464 2525 7465 969 7465 2526 7465 2526 7466 969 7466 970 7466 2526 7467 970 7467 2527 7467 2497 7468 2498 7468 970 7468 970 7469 2498 7469 2499 7469 970 7470 2499 7470 2500 7470 2440 7471 1220 7471 1216 7471 2440 7472 2442 7472 1220 7472 1220 7473 2442 7473 2476 7473 1220 106 2476 106 1219 106 1219 7474 2476 7474 2496 7474 1219 7475 2496 7475 2497 7475 2500 7476 2501 7476 970 7476 970 7477 2501 7477 2512 7477 970 7478 2512 7478 2527 7478 1216 106 1217 106 2440 106 2440 7479 1217 7479 1218 7479 2440 7480 1218 7480 1004 7480 2440 7481 963 7481 2438 7481 2438 7482 963 7482 961 7482 2438 7483 961 7483 2469 7483 2469 7484 961 7484 959 7484 2469 7485 959 7485 2470 7485 2470 7486 959 7486 957 7486 2470 7487 957 7487 2471 7487 2471 7488 957 7488 2472 7488 2472 7489 957 7489 956 7489 2472 7490 956 7490 1462 7490 955 632 991 632 1472 632 1472 632 991 632 1240 632 586 98 926 98 1315 98 1315 98 1317 98 586 98 586 7491 1317 7491 1318 7491 586 7492 1318 7492 1312 7492 1237 98 587 98 1321 98 1321 7493 587 7493 586 7493 1321 98 586 98 1314 98 1314 98 586 98 1312 98 4263 7494 4264 7494 4265 7494 4266 7495 4267 7495 4268 7495 4266 7496 4268 7496 4265 7496 4265 7497 4268 7497 4269 7497 4265 7498 4269 7498 4263 7498 4270 7499 4271 7499 4272 7499 4272 7500 4271 7500 4273 7500 4272 7501 4273 7501 4274 7501 4274 7502 4273 7502 4275 7502 4274 7503 4275 7503 4269 7503 4269 7504 4275 7504 4276 7504 4269 7505 4276 7505 4263 7505 4277 7506 4278 7506 4279 7506 4270 7507 4280 7507 4271 7507 4271 7508 4280 7508 4277 7508 4271 7509 4277 7509 4281 7509 4281 7510 4277 7510 4279 7510 4282 95 811 95 813 95 4282 95 813 95 4283 95 833 7511 829 7511 1782 7511 1782 7512 829 7512 4284 7512 1782 7513 4284 7513 2773 7513 2773 95 4284 95 4285 95 2773 95 4285 95 2769 95 2769 95 4285 95 4286 95 2769 7514 4286 7514 2770 7514 2770 95 4286 95 4283 95 2770 95 4283 95 2764 95 2764 95 4283 95 813 95 857 7515 856 7515 4287 7515 859 7516 4288 7516 860 7516 860 7517 4288 7517 4289 7517 860 7518 4289 7518 567 7518 859 7519 857 7519 4288 7519 4288 7520 857 7520 4287 7520 4288 7521 4287 7521 4290 7521 4290 7522 4287 7522 4291 7522 4290 7523 4291 7523 4292 7523 4292 7524 4291 7524 4293 7524 4294 7525 4295 7525 4291 7525 4291 7526 4295 7526 4296 7526 4291 7527 4296 7527 4293 7527 4297 7528 4298 7528 4299 7528 4299 7529 4298 7529 4300 7529 4299 7530 4300 7530 4301 7530 4297 7531 4302 7531 4298 7531 4298 7532 4302 7532 4303 7532 4298 7533 4303 7533 4304 7533 4303 7534 4305 7534 4304 7534 4304 7535 4305 7535 4295 7535 4304 7536 4295 7536 4294 7536 628 7537 614 7537 4300 7537 4300 7537 614 7537 4301 7537 1641 7538 4306 7538 4307 7538 1636 7539 1638 7539 4307 7539 4307 7540 1638 7540 1639 7540 4307 7541 1639 7541 1641 7541 1636 7542 4307 7542 1634 7542 1634 7543 4307 7543 4308 7543 1634 7544 4308 7544 612 7544 1656 7545 4309 7545 4310 7545 4310 7546 4309 7546 4311 7546 4310 7547 4311 7547 4312 7547 4312 7548 4311 7548 4307 7548 4312 7549 4307 7549 4306 7549 4313 7550 4189 7550 4314 7550 4314 7551 4189 7551 4188 7551 4315 7552 4241 7552 4225 7552 4225 7553 4183 7553 4315 7553 4315 7554 4183 7554 4182 7554 4315 7555 4182 7555 4316 7555 4316 7556 4182 7556 4186 7556 4316 7557 4186 7557 4313 7557 4313 7558 4186 7558 4185 7558 4313 7559 4185 7559 4189 7559 4188 7560 4255 7560 4314 7560 4314 7561 4255 7561 4262 7561 811 7562 4282 7562 816 7562 816 7563 4282 7563 2768 7563 2768 7564 4282 7564 4283 7564 2768 7565 4283 7565 4317 7565 589 7566 3734 7566 583 7566 583 7567 3734 7567 727 7567 583 7568 727 7568 4318 7568 727 7569 726 7569 4318 7569 4318 7570 726 7570 733 7570 4318 7571 733 7571 4319 7571 4319 7572 733 7572 728 7572 4319 7573 728 7573 4320 7573 777 95 666 95 775 95 775 7574 666 7574 668 7574 668 7575 671 7575 775 7575 775 95 671 95 673 95 775 7576 673 7576 774 7576 774 7577 673 7577 675 7577 675 95 677 95 774 95 774 95 677 95 680 95 774 95 680 95 679 95 687 95 686 95 693 95 693 7578 686 7578 680 7578 693 7579 680 7579 702 7579 702 7580 680 7580 677 7580 1288 7581 1287 7581 4279 7581 4278 7582 4131 7582 4279 7582 4279 7582 4131 7582 664 7582 666 7583 777 7583 664 7583 664 7584 777 7584 785 7584 785 7585 945 7585 664 7585 664 7585 945 7585 946 7585 664 7585 946 7585 788 7585 1288 7586 4279 7586 1290 7586 1290 7587 4279 7587 664 7587 1290 7588 664 7588 884 7588 884 7585 664 7585 788 7585 884 7585 788 7585 787 7585 315 632 4321 632 314 632 314 7589 4321 7589 309 7589 309 7590 4321 7590 310 7590 4322 7591 4323 7591 4324 7591 4324 7592 4325 7592 4322 7592 4322 7593 4325 7593 4326 7593 4322 7594 4326 7594 4327 7594 4328 7595 4329 7595 4330 7595 4330 7596 4329 7596 4331 7596 4330 7597 4331 7597 4332 7597 4332 7598 4331 7598 4333 7598 4334 7599 4335 7599 4333 7599 4333 7600 4335 7600 4336 7600 4333 7601 4336 7601 4332 7601 4337 7602 4338 7602 4334 7602 4334 7603 4338 7603 4339 7603 4334 7604 4339 7604 4335 7604 4340 7605 4341 7605 4342 7605 4334 7606 4343 7606 4337 7606 4337 7607 4343 7607 4340 7607 4337 7608 4340 7608 4344 7608 4344 7609 4340 7609 4342 7609 4317 7610 4283 7610 4286 7610 4329 7611 4328 7611 4345 7611 4345 7612 4328 7612 4317 7612 4345 7613 4317 7613 4346 7613 4317 7614 4286 7614 4346 7614 4346 7615 4286 7615 4285 7615 4346 7616 4285 7616 4347 7616 4348 7617 4349 7617 4284 7617 826 7618 842 7618 4348 7618 4348 7619 842 7619 571 7619 4348 7620 571 7620 570 7620 826 7621 4348 7621 827 7621 827 7622 4348 7622 4284 7622 827 7623 4284 7623 829 7623 4284 7624 4349 7624 4285 7624 4285 7625 4349 7625 4350 7625 4285 7626 4350 7626 4347 7626 1161 7627 1159 7627 4351 7627 4351 7628 1159 7628 1158 7628 4352 7629 1153 7629 1152 7629 4353 7630 1156 7630 1155 7630 1040 7631 1041 7631 4354 7631 4354 7632 1041 7632 1042 7632 4354 7633 1042 7633 4353 7633 4353 7634 1042 7634 1045 7634 4353 7635 1045 7635 1156 7635 1040 7636 4354 7636 1039 7636 1039 7637 4354 7637 4355 7637 1039 7638 4355 7638 1033 7638 1033 7639 4355 7639 4356 7639 1033 7640 4356 7640 1034 7640 1034 7641 4356 7641 4357 7641 1034 7642 4357 7642 1035 7642 4358 7643 1037 7643 4357 7643 4357 7644 1037 7644 1036 7644 4357 7645 1036 7645 1035 7645 1038 7646 1037 7646 4359 7646 4359 7647 1037 7647 4358 7647 4359 7648 4358 7648 4360 7648 4361 7649 4362 7649 4363 7649 4363 7650 4362 7650 4360 7650 4364 7651 4365 7651 4361 7651 4365 7652 4364 7652 1022 7652 1022 7653 4364 7653 1023 7653 1023 7654 4364 7654 4366 7654 1023 7655 4366 7655 1024 7655 1024 7656 4366 7656 4367 7656 1024 7657 4367 7657 1025 7657 1025 7658 4367 7658 4368 7658 1025 7659 4368 7659 1026 7659 1026 7660 4368 7660 4369 7660 1026 7661 4369 7661 1000 7661 1000 7662 4369 7662 4351 7662 1000 7663 4351 7663 1017 7663 1017 7664 4351 7664 1158 7664 1017 7665 1158 7665 1018 7665 4361 7666 4363 7666 4364 7666 4364 7667 4363 7667 4370 7667 4364 7668 4370 7668 4366 7668 4366 7669 4370 7669 4371 7669 4366 7670 4371 7670 4367 7670 4367 7671 4371 7671 4372 7671 4367 7672 4372 7672 4368 7672 4368 7673 4372 7673 4373 7673 4368 7674 4373 7674 4369 7674 4369 7675 4373 7675 4352 7675 4369 7676 4352 7676 4351 7676 4351 7677 4352 7677 1152 7677 4351 7678 1152 7678 1161 7678 4360 7679 4358 7679 4363 7679 4363 7680 4358 7680 4357 7680 4363 7681 4357 7681 4370 7681 4370 7682 4357 7682 4356 7682 4370 7683 4356 7683 4371 7683 4371 7684 4356 7684 4355 7684 4371 7685 4355 7685 4372 7685 4372 7686 4355 7686 4354 7686 4372 7687 4354 7687 4373 7687 4373 7688 4354 7688 4353 7688 4373 7689 4353 7689 4352 7689 4352 7690 4353 7690 1155 7690 4352 7691 1155 7691 1153 7691 4374 7692 1038 7692 4375 7692 4375 7693 1038 7693 4359 7693 4375 7694 4359 7694 4376 7694 4376 7695 4359 7695 4360 7695 4376 7696 4360 7696 4377 7696 4377 7697 4360 7697 4362 7697 4377 7698 4362 7698 4378 7698 4378 7699 4362 7699 4361 7699 4378 7700 4361 7700 4379 7700 4379 7701 4361 7701 4365 7701 4379 7702 4365 7702 1003 7702 1003 7703 4365 7703 1022 7703 4380 633 156 633 4381 633 4381 633 156 633 4382 633 4382 633 156 633 4383 633 4382 633 4383 633 4384 633 4384 633 4383 633 4385 633 4384 7704 4385 7704 4386 7704 4386 7705 4385 7705 4387 7705 4386 7706 4387 7706 4388 7706 4389 633 4390 633 4391 633 4392 7707 4393 7707 4394 7707 4394 7708 4393 7708 4395 7708 4396 633 4397 633 4398 633 4398 7709 4397 7709 4399 7709 4398 633 4399 633 4400 633 4400 633 4399 633 4401 633 4402 7710 4403 7710 4404 7710 4404 633 4403 633 4405 633 4404 633 4405 633 4406 633 4406 633 4405 633 4407 633 4406 633 4407 633 4408 633 4408 633 4407 633 4409 633 4408 633 4409 633 4410 633 4410 633 4409 633 4411 633 4410 7585 4411 7585 4412 7585 4413 7711 4412 7711 4414 7711 4413 7712 4414 7712 4415 7712 4415 633 4414 633 4416 633 4415 7713 4416 7713 4417 7713 4418 633 4417 633 4419 633 4418 633 4419 633 4395 633 4388 7714 4387 7714 4420 7714 4420 633 4387 633 4421 633 4420 7715 4421 7715 4422 7715 4389 7716 4391 7716 4423 7716 4423 7717 4391 7717 4424 7717 4423 633 4424 633 4425 633 4425 7718 4424 7718 4426 7718 4425 633 4426 633 4427 633 4427 633 4426 633 4428 633 4427 7719 4428 7719 4429 7719 4429 633 4428 633 4430 633 4429 7720 4430 7720 4431 7720 4431 633 4430 633 4432 633 4431 633 4432 633 4433 633 4433 7721 4432 7721 4434 7721 4433 633 4434 633 4401 633 4401 633 4434 633 4435 633 4401 7722 4435 7722 4400 7722 4421 7723 4436 7723 4422 7723 4422 633 4436 633 4437 633 4422 7724 4437 7724 4438 7724 4438 633 4437 633 4439 633 4438 633 4439 633 4440 633 4440 633 4439 633 4441 633 4440 633 4441 633 4442 633 4442 7725 4441 7725 4443 7725 4442 7726 4443 7726 4396 7726 4396 7727 4443 7727 4444 7727 4396 633 4444 633 4397 633 4390 633 4389 633 4445 633 4445 7728 4389 7728 4446 7728 4445 633 4446 633 4447 633 4447 633 4446 633 4448 633 4447 7729 4448 7729 4449 7729 4449 633 4448 633 4450 633 4449 633 4450 633 4451 633 4451 633 4450 633 4452 633 4451 7730 4452 7730 4453 7730 4453 7731 4452 7731 4454 7731 4453 633 4454 633 4455 633 4454 7732 4456 7732 4455 7732 4455 633 4456 633 4457 633 4455 7733 4457 7733 4458 7733 4458 633 4457 633 4459 633 4458 633 4459 633 4460 633 4460 633 4459 633 4461 633 4460 633 4461 633 4462 633 4462 633 4461 633 4463 633 4462 7734 4463 7734 4402 7734 4402 633 4463 633 4464 633 4402 633 4464 633 4403 633 4465 7735 4466 7735 4467 7735 4467 7736 4466 7736 4468 7736 4467 7737 4468 7737 4469 7737 4465 7738 4470 7738 4466 7738 4466 7739 4470 7739 4471 7739 4466 7740 4471 7740 4472 7740 4472 7741 4471 7741 4473 7741 4472 7742 4473 7742 4474 7742 4475 7743 4476 7743 4477 7743 4477 7744 4478 7744 4475 7744 4475 7745 4478 7745 4479 7745 4475 7746 4479 7746 4468 7746 4468 7747 4479 7747 4480 7747 4468 7748 4480 7748 4469 7748 4481 7749 4482 7749 4483 7749 4483 7750 4482 7750 4484 7750 4483 7751 4484 7751 4476 7751 4476 7752 4484 7752 4485 7752 4476 7753 4485 7753 4477 7753 4481 7754 4483 7754 4486 7754 4486 7755 4483 7755 4487 7755 4486 7756 4487 7756 4488 7756 4489 7757 4490 7757 4491 7757 4491 7758 4490 7758 4492 7758 4491 7759 4492 7759 4493 7759 4493 7760 4492 7760 4494 7760 4493 7761 4494 7761 4495 7761 4495 7762 4494 7762 4496 7762 4495 7763 4496 7763 4497 7763 4497 7764 4496 7764 4498 7764 4497 7765 4498 7765 4499 7765 4499 7766 4498 7766 4472 7766 4499 7767 4472 7767 4500 7767 4500 7768 4472 7768 4474 7768 4500 7769 4474 7769 4501 7769 4502 7770 4488 7770 4503 7770 4503 7771 4488 7771 4487 7771 4503 7772 4487 7772 4504 7772 4504 7773 4487 7773 4490 7773 4504 7774 4490 7774 4505 7774 4505 7775 4490 7775 4489 7775 4506 7776 4507 7776 4508 7776 4508 7777 4507 7777 4509 7777 4508 7778 4509 7778 4510 7778 4509 7779 4511 7779 4512 7779 4509 7780 4512 7780 4510 7780 4510 7781 4512 7781 4513 7781 4510 7782 4513 7782 4514 7782 4515 7783 4516 7783 4517 7783 4517 7784 4516 7784 4518 7784 4517 7785 4518 7785 4519 7785 4520 7786 4521 7786 4522 7786 4522 7787 4521 7787 4523 7787 4522 7788 4523 7788 4519 7788 4519 7789 4523 7789 4524 7789 4519 7790 4524 7790 4517 7790 4525 106 4526 106 4527 106 4528 106 4507 106 4506 106 4506 7791 4529 7791 4528 7791 4528 7792 4529 7792 4530 7792 4528 106 4530 106 4527 106 4527 7793 4530 7793 4531 7793 4532 106 4533 106 4534 106 4534 7794 4533 7794 4535 7794 4531 106 4536 106 4527 106 4527 106 4536 106 4537 106 4527 7795 4537 7795 4525 7795 4525 7796 4537 7796 4538 7796 4525 7797 4538 7797 4534 7797 4534 7798 4538 7798 4532 7798 4535 7799 4539 7799 4534 7799 4534 7800 4539 7800 4540 7800 4534 106 4540 106 4541 106 4527 95 4526 95 4542 95 4543 7801 4544 7801 4545 7801 4545 95 4544 95 4527 95 4545 95 4527 95 4546 95 4546 95 4527 95 4542 95 4543 7802 4547 7802 4544 7802 4544 95 4547 95 4548 95 4544 95 4548 95 4549 95 4544 106 4549 106 4550 106 4550 7803 4549 7803 4551 7803 4550 7804 4551 7804 4552 7804 4516 98 4515 98 4553 98 4554 7805 4555 7805 4556 7805 4555 98 4557 98 4556 98 4556 7806 4557 7806 4558 7806 4556 98 4558 98 4553 98 4553 7807 4558 7807 4559 7807 4553 7808 4559 7808 4516 7808 4556 7809 4560 7809 4561 7809 4561 98 4562 98 4556 98 4556 7810 4562 7810 4563 7810 4556 7811 4563 7811 4554 7811 4554 98 4563 98 4564 98 4554 98 4564 98 4565 98 4564 98 4566 98 4565 98 4565 7812 4566 7812 4567 7812 4565 98 4567 98 4568 98 4568 7813 4567 7813 4569 7813 4568 7814 4569 7814 4570 7814 4571 7815 4572 7815 4573 7815 4573 7816 4572 7816 4574 7816 4573 7817 4574 7817 4575 7817 4575 7818 4574 7818 4576 7818 4575 7819 4576 7819 4577 7819 4577 7819 4576 7819 4578 7819 4579 106 4580 106 4578 106 4578 106 4580 106 4577 106 4581 106 4582 106 4583 106 4583 106 4582 106 1435 106 4584 98 1451 98 4585 98 4584 98 4585 98 4586 98 4587 7820 4585 7820 4588 7820 4588 7821 4585 7821 4589 7821 4588 7822 4589 7822 4590 7822 4590 7823 4589 7823 4591 7823 4592 7824 4593 7824 4594 7824 4594 7825 4593 7825 4595 7825 4594 7826 4595 7826 4596 7826 4597 7827 4598 7827 4599 7827 4592 7828 4594 7828 4600 7828 4600 7829 4594 7829 4601 7829 4600 7830 4601 7830 4599 7830 4599 7831 4601 7831 4602 7831 4599 7832 4602 7832 4597 7832 4603 7833 4604 7833 4605 7833 4605 7834 4604 7834 4599 7834 4605 7835 4599 7835 4606 7835 4606 7836 4599 7836 4598 7836 4607 7837 4608 7837 4609 7837 4609 7838 4608 7838 4610 7838 4609 7839 4610 7839 4611 7839 4612 7840 4613 7840 4611 7840 4611 7841 4613 7841 4614 7841 4611 7842 4614 7842 4609 7842 4615 7843 4616 7843 4617 7843 4617 7844 4616 7844 4618 7844 4617 7845 4618 7845 4619 7845 4596 7846 4613 7846 4594 7846 4594 7847 4613 7847 4612 7847 4594 7848 4612 7848 4620 7848 4620 7849 4612 7849 4621 7849 4620 7850 4621 7850 4622 7850 4622 7851 4621 7851 4623 7851 4622 7852 4623 7852 4619 7852 4619 7853 4623 7853 4624 7853 4619 7854 4624 7854 4617 7854 4625 7855 4615 7855 4626 7855 4626 7856 4615 7856 4617 7856 4626 7857 4617 7857 4627 7857 4627 7858 4617 7858 4628 7858 4627 7859 4628 7859 4629 7859 4630 7860 4631 7860 4632 7860 4632 7861 4631 7861 4627 7861 4632 7862 4627 7862 4633 7862 4633 7863 4627 7863 4629 7863 4634 7864 4635 7864 4636 7864 4636 7865 4635 7865 4637 7865 4636 7866 4637 7866 4638 7866 4634 7867 4639 7867 4635 7867 4635 7868 4639 7868 4640 7868 4635 7869 4640 7869 4604 7869 4604 7870 4640 7870 4641 7870 4604 7871 4641 7871 4599 7871 4642 7872 4643 7872 4644 7872 4642 7873 4644 7873 4645 7873 4645 7874 4644 7874 4646 7874 4645 7875 4646 7875 4647 7875 4647 7876 4646 7876 4648 7876 4647 7877 4648 7877 4649 7877 4649 7878 4648 7878 4650 7878 4649 7879 4650 7879 4651 7879 4651 7880 4652 7880 4649 7880 4649 7881 4652 7881 4586 7881 4649 7882 4586 7882 4585 7882 4581 7883 4653 7883 4654 7883 4582 7884 4581 7884 4655 7884 4655 7885 4581 7885 4654 7885 4655 7886 4654 7886 4656 7886 4656 7887 4654 7887 4657 7887 4656 7888 4657 7888 4658 7888 4658 7889 4657 7889 4659 7889 4658 7890 4659 7890 4660 7890 4660 7891 4659 7891 4661 7891 4660 7892 4661 7892 4662 7892 4663 7893 4664 7893 4665 7893 4665 7894 4664 7894 4662 7894 4665 7895 4662 7895 4666 7895 4666 7896 4662 7896 4661 7896 4582 7897 4667 7897 4668 7897 4668 7898 4667 7898 4669 7898 4670 7899 4671 7899 4672 7899 4672 7900 4671 7900 4673 7900 4672 7901 4673 7901 4674 7901 4674 7902 4673 7902 4675 7902 4674 7903 4675 7903 4667 7903 4667 7904 4675 7904 4676 7904 4667 7905 4676 7905 4669 7905 4670 7906 4672 7906 4677 7906 4677 7907 4672 7907 4678 7907 4677 7908 4678 7908 4679 7908 4679 7909 4678 7909 4680 7909 4679 7910 4680 7910 4681 7910 4681 7911 4680 7911 4682 7911 4681 7912 4682 7912 4683 7912 4615 7913 4625 7913 4684 7913 4684 7914 4625 7914 4683 7914 4684 7915 4683 7915 4685 7915 4685 7916 4683 7916 4682 7916 4664 95 4663 95 4686 95 4687 7917 4688 7917 4689 7917 4642 95 4686 95 4643 95 4643 95 4686 95 4690 95 4689 95 4664 95 4687 95 4687 95 4664 95 4686 95 4687 95 4686 95 4691 95 4691 95 4686 95 4642 95 4691 95 4642 95 4692 95 4692 95 4642 95 4693 95 4692 7918 4693 7918 4694 7918 4695 7919 4696 7919 4697 7919 4695 7920 4698 7920 4699 7920 4700 632 4701 632 4702 632 4702 7921 4701 7921 4695 7921 4702 632 4695 632 4703 632 4703 632 4695 632 4697 632 4704 632 4696 632 4705 632 4705 632 4696 632 4695 632 4705 632 4695 632 4706 632 4706 632 4695 632 4699 632 4707 7922 4708 7922 4709 7922 4709 7923 4708 7923 4710 7923 4709 7924 4710 7924 4711 7924 4709 7925 4712 7925 4707 7925 4707 7926 4712 7926 4713 7926 4707 7927 4713 7927 4714 7927 4714 7928 4713 7928 4715 7928 4714 7929 4715 7929 4716 7929 4716 7930 4715 7930 4717 7930 4716 7931 4717 7931 4718 7931 4718 7932 4717 7932 4719 7932 4718 7933 4719 7933 4720 7933 4721 7934 4722 7934 4723 7934 4720 7935 4719 7935 4723 7935 4723 7936 4719 7936 4724 7936 4723 7937 4724 7937 4721 7937 4725 7938 4726 7938 4724 7938 4724 7939 4726 7939 4727 7939 4724 7940 4727 7940 4721 7940 4728 7941 4729 7941 4725 7941 4725 7942 4729 7942 4730 7942 4725 7943 4730 7943 4726 7943 4731 7944 4732 7944 4728 7944 4728 7945 4732 7945 4733 7945 4728 7946 4733 7946 4729 7946 4734 7947 4735 7947 4731 7947 4731 7948 4735 7948 4736 7948 4731 7949 4736 7949 4732 7949 4737 7950 4738 7950 4734 7950 4734 7951 4738 7951 4739 7951 4734 7952 4739 7952 4735 7952 4711 7953 4740 7953 4709 7953 4709 7954 4740 7954 4741 7954 4709 7955 4741 7955 4737 7955 4737 7956 4741 7956 4742 7956 4737 7957 4742 7957 4738 7957 4739 7958 4738 7958 4743 7958 4744 7959 4745 7959 4746 7959 4747 7960 4748 7960 4749 7960 4750 7961 4751 7961 4752 7961 4751 7962 4753 7962 4752 7962 4752 7963 4753 7963 4754 7963 4752 7964 4754 7964 4755 7964 4747 7965 4749 7965 4756 7965 4757 7966 4758 7966 4759 7966 4759 7967 4758 7967 4760 7967 4761 7968 4762 7968 4760 7968 4760 7969 4762 7969 4763 7969 4760 7970 4763 7970 4759 7970 4764 7971 4765 7971 4766 7971 4766 7972 4765 7972 4767 7972 4766 7973 4767 7973 4768 7973 4764 7974 4766 7974 4769 7974 4769 7975 4766 7975 4770 7975 4769 7976 4770 7976 4771 7976 4772 7977 4773 7977 4770 7977 4770 7978 4773 7978 4774 7978 4770 7979 4774 7979 4771 7979 4775 7980 4776 7980 4777 7980 4777 7981 4776 7981 4778 7981 4777 7982 4778 7982 4772 7982 4772 7983 4778 7983 4779 7983 4772 7984 4779 7984 4773 7984 4780 7985 4781 7985 4775 7985 4775 7986 4781 7986 4782 7986 4775 7987 4782 7987 4776 7987 4783 7988 4780 7988 4784 7988 4784 7989 4780 7989 4785 7989 4783 7990 4786 7990 4780 7990 4780 7991 4786 7991 4787 7991 4780 7992 4787 7992 4781 7992 4788 7993 4789 7993 4790 7993 4790 7994 4789 7994 4791 7994 4790 7995 4791 7995 4792 7995 4792 7996 4793 7996 4790 7996 4790 7997 4793 7997 4794 7997 4790 7998 4794 7998 4795 7998 4796 7999 4744 7999 4797 7999 4797 8000 4744 8000 4746 8000 4797 8001 4746 8001 4710 8001 4710 8002 4746 8002 4711 8002 4743 8003 4738 8003 4798 8003 4738 8004 4742 8004 4798 8004 4798 8005 4742 8005 4741 8005 4798 8006 4741 8006 4746 8006 4746 8007 4741 8007 4740 8007 4746 8008 4740 8008 4711 8008 4739 8009 4743 8009 4735 8009 4735 8010 4743 8010 4799 8010 4735 8011 4799 8011 4736 8011 4736 8012 4799 8012 4800 8012 4736 8013 4800 8013 4732 8013 4732 8014 4800 8014 4733 8014 4733 8015 4800 8015 4801 8015 4733 8016 4801 8016 4729 8016 4729 8017 4801 8017 4730 8017 4730 8018 4801 8018 4802 8018 4730 8019 4802 8019 4726 8019 4726 8020 4802 8020 4727 8020 4727 8021 4802 8021 4752 8021 4727 8022 4752 8022 4721 8022 4721 8023 4752 8023 4755 8023 4721 8024 4755 8024 4722 8024 4745 8025 4803 8025 4746 8025 4746 8026 4803 8026 4804 8026 4746 8027 4804 8027 4798 8027 4798 8028 4804 8028 4805 8028 4798 8029 4805 8029 4743 8029 4743 8030 4805 8030 4806 8030 4743 8031 4806 8031 4799 8031 4799 8032 4806 8032 4807 8032 4799 8033 4807 8033 4800 8033 4800 8034 4807 8034 4808 8034 4800 8035 4808 8035 4801 8035 4801 8036 4808 8036 4809 8036 4801 8037 4809 8037 4802 8037 4802 8038 4809 8038 4810 8038 4802 8039 4810 8039 4752 8039 4752 8040 4810 8040 4749 8040 4752 8041 4749 8041 4750 8041 4750 8042 4749 8042 4748 8042 4803 8043 4788 8043 4804 8043 4804 8044 4788 8044 4790 8044 4804 8045 4790 8045 4805 8045 4805 8046 4790 8046 4811 8046 4805 8047 4811 8047 4806 8047 4806 8048 4811 8048 4812 8048 4806 8049 4812 8049 4807 8049 4807 8050 4812 8050 4813 8050 4807 8051 4813 8051 4808 8051 4808 8052 4813 8052 4814 8052 4808 8053 4814 8053 4809 8053 4809 8054 4814 8054 4815 8054 4809 8055 4815 8055 4810 8055 4810 8056 4815 8056 4761 8056 4810 8057 4761 8057 4749 8057 4749 8058 4761 8058 4760 8058 4749 8059 4760 8059 4756 8059 4756 8060 4760 8060 4758 8060 4756 8061 4758 8061 4816 8061 4795 8062 4817 8062 4790 8062 4790 8063 4817 8063 4785 8063 4790 8064 4785 8064 4811 8064 4811 8065 4785 8065 4780 8065 4811 8066 4780 8066 4812 8066 4812 8067 4780 8067 4775 8067 4812 8068 4775 8068 4813 8068 4813 8069 4775 8069 4777 8069 4813 8070 4777 8070 4814 8070 4814 8071 4777 8071 4772 8071 4814 8072 4772 8072 4815 8072 4815 8073 4772 8073 4770 8073 4815 8074 4770 8074 4761 8074 4761 8075 4770 8075 4766 8075 4761 8076 4766 8076 4762 8076 4762 8077 4766 8077 4768 8077 4818 8078 4819 8078 4820 8078 4821 8079 4822 8079 4774 8079 4822 8080 4823 8080 4774 8080 4774 8081 4823 8081 4824 8081 4774 8082 4824 8082 4771 8082 4771 8083 4824 8083 4825 8083 4771 8084 4825 8084 4769 8084 4769 8085 4825 8085 4826 8085 4769 8086 4826 8086 4764 8086 4764 8087 4826 8087 4827 8087 4764 8088 4827 8088 4765 8088 4828 8089 4829 8089 4830 8089 4830 8090 4829 8090 4831 8090 4830 8091 4831 8091 4832 8091 4832 8092 4831 8092 4833 8092 4832 8093 4833 8093 4834 8093 4835 8094 4776 8094 4836 8094 4836 8095 4776 8095 4782 8095 4836 8096 4782 8096 4837 8096 4837 8097 4782 8097 4781 8097 4837 8098 4781 8098 4838 8098 4835 8099 4839 8099 4776 8099 4776 8100 4839 8100 4828 8100 4776 8101 4828 8101 4778 8101 4778 8102 4828 8102 4830 8102 4778 8103 4830 8103 4820 8103 4820 8104 4830 8104 4832 8104 4820 8105 4832 8105 4818 8105 4787 8106 4786 8106 4840 8106 4787 8107 4840 8107 4781 8107 4781 8108 4840 8108 4841 8108 4781 8109 4841 8109 4838 8109 4821 8110 4774 8110 4819 8110 4819 8111 4774 8111 4773 8111 4819 8112 4773 8112 4820 8112 4820 8113 4773 8113 4779 8113 4820 8114 4779 8114 4778 8114 4842 8115 4843 8115 4844 8115 4839 8116 4845 8116 4828 8116 4835 8117 4846 8117 4847 8117 4831 8118 4848 8118 4833 8118 4833 8119 4848 8119 4849 8119 4833 8120 4849 8120 4834 8120 4850 8121 4851 8121 4852 8121 4852 8122 4851 8122 4853 8122 4852 8123 4853 8123 4854 8123 4854 8124 4853 8124 4855 8124 4854 8125 4855 8125 4856 8125 4857 8126 4858 8126 4850 8126 4850 8127 4858 8127 4859 8127 4850 8128 4859 8128 4851 8128 4860 8129 4861 8129 4862 8129 4862 8130 4861 8130 4863 8130 4862 8131 4863 8131 4864 8131 4864 8132 4863 8132 4857 8132 4864 8133 4857 8133 4865 8133 4865 8134 4857 8134 4850 8134 4860 8135 4862 8135 4866 8135 4866 8136 4862 8136 4867 8136 4866 8137 4867 8137 4868 8137 4868 8138 4867 8138 4869 8138 4868 8139 4869 8139 4870 8139 4828 8140 4845 8140 4829 8140 4845 8141 4871 8141 4829 8141 4829 8142 4871 8142 4872 8142 4829 8143 4872 8143 4831 8143 4831 8144 4872 8144 4873 8144 4831 8145 4873 8145 4848 8145 4874 8146 4844 8146 4838 8146 4838 8147 4844 8147 4843 8147 4838 8148 4843 8148 4837 8148 4837 8149 4843 8149 4842 8149 4837 8150 4842 8150 4836 8150 4835 8151 4836 8151 4846 8151 4846 8152 4836 8152 4842 8152 4846 8153 4842 8153 4875 8153 4875 8154 4842 8154 4844 8154 4875 8155 4844 8155 4876 8155 4876 8156 4844 8156 4874 8156 4876 8157 4874 8157 4877 8157 4878 8158 4849 8158 4879 8158 4879 8159 4849 8159 4848 8159 4879 8160 4848 8160 4880 8160 4880 8161 4848 8161 4873 8161 4880 8162 4873 8162 4881 8162 4881 8163 4873 8163 4872 8163 4881 8164 4872 8164 4882 8164 4882 8165 4872 8165 4871 8165 4882 8166 4871 8166 4883 8166 4883 8167 4871 8167 4845 8167 4883 8168 4845 8168 4847 8168 4847 8169 4845 8169 4839 8169 4847 8170 4839 8170 4835 8170 4856 8171 4884 8171 4854 8171 4854 8172 4884 8172 4885 8172 4854 8173 4885 8173 4852 8173 4852 8174 4885 8174 4886 8174 4852 8175 4886 8175 4850 8175 4850 8176 4886 8176 4887 8176 4850 8177 4887 8177 4865 8177 4865 8178 4887 8178 4888 8178 4865 8179 4888 8179 4864 8179 4864 8180 4888 8180 4889 8180 4864 8181 4889 8181 4862 8181 4862 8182 4889 8182 4890 8182 4862 8183 4890 8183 4867 8183 4867 8184 4890 8184 4891 8184 4867 8185 4891 8185 4869 8185 4869 8186 4891 8186 4892 8186 4869 8187 4892 8187 4870 8187 4877 8188 4868 8188 4876 8188 4876 8189 4868 8189 4870 8189 4876 8190 4870 8190 4875 8190 4875 8191 4870 8191 4892 8191 4875 8192 4892 8192 4846 8192 4846 8193 4892 8193 4891 8193 4846 8194 4891 8194 4847 8194 4847 8195 4891 8195 4890 8195 4847 8196 4890 8196 4883 8196 4883 8197 4890 8197 4889 8197 4883 8198 4889 8198 4882 8198 4882 8199 4889 8199 4888 8199 4882 8200 4888 8200 4881 8200 4881 8201 4888 8201 4887 8201 4881 8202 4887 8202 4880 8202 4880 8203 4887 8203 4886 8203 4880 8204 4886 8204 4879 8204 4879 8205 4886 8205 4885 8205 4879 8206 4885 8206 4878 8206 4878 8207 4885 8207 4884 8207 4893 8208 4894 8208 4895 8208 4895 8209 4894 8209 4896 8209 4895 8210 4896 8210 4897 8210 4893 8211 4895 8211 4898 8211 4898 8212 4895 8212 4899 8212 4898 8213 4899 8213 4900 8213 4900 8214 4899 8214 4901 8214 4900 8215 4901 8215 4902 8215 4902 8216 4901 8216 4903 8216 4902 8217 4903 8217 4904 8217 4904 8218 4903 8218 4905 8218 4904 8219 4905 8219 4906 8219 4906 8220 4905 8220 4907 8220 4907 8221 4905 8221 4908 8221 4907 8222 4908 8222 4909 8222 4909 8223 4908 8223 4910 8223 4909 8224 4910 8224 4911 8224 4911 8225 4910 8225 4912 8225 4911 8226 4912 8226 4913 8226 4913 8227 4912 8227 4914 8227 4913 8228 4914 8228 4915 8228 4915 8229 4914 8229 4916 8229 4915 8230 4916 8230 4917 8230 4917 8231 4916 8231 4918 8231 4917 8232 4918 8232 4919 8232 4919 8233 4918 8233 4920 8233 4919 8234 4920 8234 4921 8234 4922 8235 4923 8235 4924 8235 4923 8236 4922 8236 4834 8236 4834 8237 4922 8237 4925 8237 4834 8238 4925 8238 4832 8238 4832 8239 4925 8239 4926 8239 4832 8240 4926 8240 4818 8240 4822 8241 4821 8241 4927 8241 4927 8242 4821 8242 4819 8242 4927 8243 4819 8243 4928 8243 4928 8244 4819 8244 4818 8244 4928 8245 4818 8245 4929 8245 4929 8246 4818 8246 4926 8246 4924 8247 4930 8247 4922 8247 4922 8248 4930 8248 4931 8248 4922 8249 4931 8249 4925 8249 4925 8250 4931 8250 4932 8250 4925 8251 4932 8251 4926 8251 4926 8252 4932 8252 4933 8252 4926 8253 4933 8253 4929 8253 4929 8254 4933 8254 4934 8254 4929 8255 4934 8255 4928 8255 4928 8256 4934 8256 4935 8256 4928 8257 4935 8257 4927 8257 4927 8258 4935 8258 4936 8258 4927 8259 4936 8259 4822 8259 4822 8260 4936 8260 4937 8260 4822 8261 4937 8261 4823 8261 4823 8262 4937 8262 4938 8262 4823 8263 4938 8263 4824 8263 4824 8264 4938 8264 4939 8264 4824 8265 4939 8265 4825 8265 4825 8266 4939 8266 4940 8266 4825 8267 4940 8267 4826 8267 4826 8268 4940 8268 4941 8268 4924 8269 4920 8269 4930 8269 4930 8270 4920 8270 4918 8270 4930 8271 4918 8271 4931 8271 4931 8272 4918 8272 4916 8272 4931 8273 4916 8273 4932 8273 4932 8274 4916 8274 4914 8274 4932 8275 4914 8275 4933 8275 4933 8276 4914 8276 4912 8276 4933 8277 4912 8277 4934 8277 4934 8278 4912 8278 4910 8278 4934 8279 4910 8279 4935 8279 4935 8280 4910 8280 4908 8280 4935 8281 4908 8281 4936 8281 4936 8282 4908 8282 4905 8282 4936 8283 4905 8283 4937 8283 4937 8284 4905 8284 4903 8284 4937 8285 4903 8285 4938 8285 4938 8286 4903 8286 4901 8286 4938 8287 4901 8287 4939 8287 4939 8288 4901 8288 4899 8288 4939 8289 4899 8289 4940 8289 4940 8290 4899 8290 4895 8290 4940 8291 4895 8291 4941 8291 4941 8292 4895 8292 4897 8292 4855 8293 4942 8293 4943 8293 4944 8294 4834 8294 4849 8294 4944 8295 4849 8295 4945 8295 4945 8296 4849 8296 4878 8296 4945 8297 4878 8297 4946 8297 4946 8298 4878 8298 4884 8298 4946 8299 4884 8299 4943 8299 4943 8300 4884 8300 4856 8300 4943 8301 4856 8301 4855 8301 4947 8302 4948 8302 4921 8302 4921 8303 4920 8303 4947 8303 4947 8304 4920 8304 4924 8304 4947 8305 4924 8305 4949 8305 4949 8306 4924 8306 4923 8306 4949 8307 4923 8307 4950 8307 4950 8308 4923 8308 4834 8308 4950 8309 4834 8309 4944 8309 4951 8310 4488 8310 4502 8310 4951 8311 4502 8311 4942 8311 4942 8312 4502 8312 4952 8312 4942 8313 4952 8313 4943 8313 4474 8314 4953 8314 4501 8314 4501 8315 4953 8315 4948 8315 4501 8316 4948 8316 4954 8316 4954 8317 4948 8317 4947 8317 4954 8318 4947 8318 4955 8318 4955 8319 4947 8319 4956 8319 4956 8320 4947 8320 4949 8320 4956 8321 4949 8321 4957 8321 4952 8322 4958 8322 4943 8322 4943 8323 4958 8323 4959 8323 4943 8324 4959 8324 4946 8324 4946 8325 4959 8325 4960 8325 4946 8326 4960 8326 4945 8326 4945 8327 4960 8327 4961 8327 4945 8328 4961 8328 4944 8328 4944 8329 4961 8329 4957 8329 4944 8330 4957 8330 4950 8330 4950 8331 4957 8331 4949 8331 4500 7585 4501 7585 4954 7585 4960 8332 4959 8332 4505 8332 4505 7585 4959 7585 4504 7585 4505 7585 4489 7585 4960 7585 4960 7585 4489 7585 4491 7585 4960 8333 4491 8333 4961 8333 4961 8334 4491 8334 4493 8334 4961 7585 4493 7585 4957 7585 4957 8335 4493 8335 4495 8335 4957 7585 4495 7585 4956 7585 4956 7585 4495 7585 4497 7585 4956 8336 4497 8336 4955 8336 4955 7585 4497 7585 4954 7585 4954 7585 4497 7585 4499 7585 4954 7585 4499 7585 4500 7585 4502 7585 4503 7585 4952 7585 4952 7585 4503 7585 4504 7585 4952 8337 4504 8337 4958 8337 4958 7585 4504 7585 4959 7585 4962 106 4921 106 4948 106 4963 106 4962 106 4964 106 4964 8338 4962 8338 4948 8338 4964 8339 4948 8339 4965 8339 4965 8340 4948 8340 4953 8340 4966 8341 4967 8341 4968 8341 4969 8342 4970 8342 4971 8342 4972 8343 4969 8343 4973 8343 4974 8344 4975 8344 4973 8344 4973 8345 4975 8345 4976 8345 4973 8346 4976 8346 4972 8346 4969 8347 4971 8347 4973 8347 4973 8348 4971 8348 4977 8348 4973 8349 4977 8349 4974 8349 4974 8350 4977 8350 4978 8350 4974 8351 4978 8351 4979 8351 4980 8352 4981 8352 4979 8352 4979 8353 4981 8353 4982 8353 4979 8354 4982 8354 4974 8354 4974 8355 4982 8355 4983 8355 4974 8356 4983 8356 4975 8356 4984 8357 4980 8357 4985 8357 4985 8358 4980 8358 4979 8358 4985 8359 4979 8359 4986 8359 4986 8360 4979 8360 4978 8360 4967 8361 4984 8361 4968 8361 4968 8362 4984 8362 4985 8362 4968 8363 4985 8363 4987 8363 4987 8364 4985 8364 4986 8364 4987 8365 4986 8365 4988 8365 4988 8366 4986 8366 4978 8366 4988 8367 4978 8367 4989 8367 4989 8368 4978 8368 4977 8368 4989 8369 4977 8369 4990 8369 4990 8370 4977 8370 4971 8370 4990 8371 4971 8371 4991 8371 4991 8372 4971 8372 4970 8372 4991 8373 4970 8373 4992 8373 4992 8374 4970 8374 4969 8374 4992 8375 4969 8375 4993 8375 4993 8376 4969 8376 4972 8376 4993 8377 4972 8377 4994 8377 4995 8378 4966 8378 4996 8378 4996 8379 4966 8379 4968 8379 4996 8380 4968 8380 4997 8380 4997 8381 4968 8381 4987 8381 4997 8382 4987 8382 4998 8382 4998 8383 4987 8383 4988 8383 4965 8384 4995 8384 4964 8384 4964 8385 4995 8385 4996 8385 4964 8386 4996 8386 4963 8386 4963 8387 4996 8387 4997 8387 4963 8388 4997 8388 4962 8388 4962 8389 4997 8389 4998 8389 4999 8390 5000 8390 5001 8390 5002 8391 5003 8391 5004 8391 5005 8392 5006 8392 5003 8392 5004 8393 5007 8393 5008 8393 5008 8394 5007 8394 5009 8394 5008 8395 5009 8395 5010 8395 5010 8396 5009 8396 5011 8396 5010 8397 5011 8397 5012 8397 5011 8398 5013 8398 5012 8398 5012 8399 5013 8399 5014 8399 5012 8400 5014 8400 5001 8400 5001 8401 5014 8401 5015 8401 5001 8402 5015 8402 4999 8402 5004 8403 5008 8403 5002 8403 5002 8404 5008 8404 5010 8404 5002 8405 5010 8405 5016 8405 5016 8406 5010 8406 5012 8406 5016 8407 5012 8407 5017 8407 5017 8408 5012 8408 5001 8408 5017 8409 5001 8409 5018 8409 5018 8410 5001 8410 5000 8410 5018 8411 5000 8411 5019 8411 5003 8412 5002 8412 5005 8412 5005 8413 5002 8413 5016 8413 5005 8414 5016 8414 5020 8414 5020 8415 5016 8415 5017 8415 5020 8416 5017 8416 5021 8416 5021 8417 5017 8417 5018 8417 5021 8418 5018 8418 5022 8418 5022 8419 5018 8419 5019 8419 5022 8420 5019 8420 5023 8420 5024 8421 5025 8421 5026 8421 5026 8422 5025 8422 5027 8422 5026 8423 5027 8423 5028 8423 5028 8424 5027 8424 5029 8424 5030 8425 5029 8425 5031 8425 5031 8426 5029 8426 5027 8426 5031 8427 5027 8427 5032 8427 5032 8428 5027 8428 5025 8428 4999 8429 5024 8429 5000 8429 5000 8430 5024 8430 5026 8430 5000 8431 5026 8431 5019 8431 5019 8432 5026 8432 5028 8432 5019 8433 5028 8433 5023 8433 5023 8434 5028 8434 5029 8434 5023 8435 5029 8435 5033 8435 5033 8436 5029 8436 5030 8436 5033 8437 5030 8437 5034 8437 4855 98 5034 98 4942 98 4942 98 5034 98 5030 98 4942 98 5030 98 4951 98 4951 98 5030 98 5031 98 4951 98 5031 98 5032 98 5035 8438 5036 8438 5037 8438 5038 8439 5032 8439 5025 8439 5039 8440 5040 8440 5041 8440 5041 8441 5040 8441 5042 8441 5041 8442 5042 8442 5043 8442 5036 8443 5044 8443 5045 8443 5044 8444 5036 8444 5046 8444 5046 8445 5036 8445 5035 8445 5046 8446 5035 8446 5047 8446 5048 8447 5049 8447 5047 8447 5047 8448 5049 8448 5050 8448 5047 8449 5050 8449 5046 8449 5015 8450 5014 8450 5037 8450 5051 8451 5052 8451 5053 8451 5054 8452 5055 8452 5056 8452 5056 8453 5055 8453 5057 8453 5056 8454 5057 8454 5058 8454 5058 8455 5057 8455 5059 8455 5058 8456 5059 8456 5060 8456 5060 8457 5059 8457 5040 8457 5060 8458 5040 8458 5061 8458 5061 8459 5040 8459 5039 8459 5061 8460 5039 8460 5062 8460 5062 8461 4688 8461 5061 8461 5061 8462 4688 8462 5063 8462 5061 8463 5063 8463 5060 8463 5060 8464 5063 8464 5064 8464 5060 8465 5064 8465 5058 8465 5058 8466 5064 8466 5051 8466 5058 8467 5051 8467 5056 8467 5056 8468 5051 8468 5053 8468 5056 8469 5053 8469 5054 8469 5004 8470 5048 8470 5007 8470 5007 8471 5048 8471 5047 8471 5007 8472 5047 8472 5009 8472 5009 8473 5047 8473 5035 8473 5009 8474 5035 8474 5011 8474 5011 8475 5035 8475 5037 8475 5011 8476 5037 8476 5013 8476 5013 8477 5037 8477 5014 8477 5055 8478 4999 8478 5057 8478 5057 8479 4999 8479 5015 8479 5057 8480 5015 8480 5059 8480 5059 8481 5015 8481 5037 8481 5059 8482 5037 8482 5040 8482 5040 8483 5037 8483 5036 8483 5040 8484 5036 8484 5042 8484 5042 8485 5036 8485 5045 8485 5042 8486 5045 8486 5043 8486 4688 8487 5065 8487 5063 8487 5063 8488 5065 8488 5066 8488 5063 8489 5066 8489 5064 8489 5064 8490 5066 8490 5067 8490 5064 8491 5067 8491 5051 8491 5051 8492 5067 8492 5068 8492 5051 8493 5068 8493 5052 8493 5052 8494 5068 8494 5069 8494 5052 8495 5069 8495 5053 8495 5053 8496 5069 8496 5038 8496 5053 8497 5038 8497 5054 8497 5054 8498 5038 8498 5025 8498 5054 8499 5025 8499 5055 8499 5055 8500 5025 8500 5024 8500 5055 8501 5024 8501 4999 8501 5070 8502 5071 8502 5072 8502 5073 8503 5074 8503 5075 8503 5076 8504 5077 8504 5078 8504 5078 8505 5077 8505 5079 8505 5078 8506 5079 8506 5080 8506 5080 8507 5079 8507 4994 8507 5070 8508 5081 8508 5082 8508 5082 8509 5081 8509 4995 8509 5082 8510 4995 8510 4965 8510 5083 8511 4984 8511 5084 8511 5084 8512 4984 8512 4967 8512 5084 8513 4967 8513 5081 8513 5081 8514 4967 8514 4966 8514 5081 8515 4966 8515 4995 8515 4994 8516 4972 8516 5080 8516 5080 8517 4972 8517 4976 8517 5080 8518 4976 8518 5078 8518 5078 8519 4976 8519 4975 8519 5078 8520 4975 8520 5085 8520 5085 8521 4975 8521 4983 8521 5085 8522 4983 8522 5086 8522 5086 8523 4983 8523 4982 8523 5086 8524 4982 8524 4981 8524 5076 8525 5078 8525 5087 8525 5087 8526 5078 8526 5085 8526 5087 8527 5085 8527 5088 8527 5088 8528 5085 8528 5086 8528 5088 8529 5086 8529 5089 8529 5089 8530 5086 8530 4981 8530 5089 8531 4981 8531 5083 8531 5083 8532 4981 8532 4980 8532 5083 8533 4980 8533 4984 8533 5070 8534 5090 8534 5081 8534 5081 8535 5090 8535 5091 8535 5081 8536 5091 8536 5084 8536 5084 8537 5091 8537 5092 8537 5084 8538 5092 8538 5083 8538 5083 8539 5092 8539 5075 8539 5083 8540 5075 8540 5089 8540 5089 8541 5075 8541 5074 8541 5089 8542 5074 8542 5088 8542 5088 8543 5074 8543 5093 8543 5088 8544 5093 8544 5087 8544 5087 8545 5093 8545 5076 8545 5070 8546 5072 8546 5090 8546 5090 8547 5072 8547 5094 8547 5090 8548 5094 8548 5091 8548 5091 8549 5094 8549 5095 8549 5091 8550 5095 8550 5092 8550 5092 8551 5095 8551 4694 8551 5092 8552 4694 8552 5075 8552 5075 8553 4694 8553 5096 8553 5075 8554 5096 8554 5073 8554 4953 8555 4474 8555 4473 8555 5038 8556 5069 8556 4486 8556 4488 8557 4951 8557 4486 8557 4486 8558 4951 8558 5032 8558 4486 8559 5032 8559 5038 8559 5097 8560 4477 8560 5098 8560 5098 8561 4477 8561 4485 8561 5098 8562 4485 8562 5099 8562 5099 8563 4485 8563 4484 8563 5099 8564 4484 8564 5068 8564 5068 8565 4484 8565 4482 8565 5068 8566 4482 8566 5069 8566 5069 8567 4482 8567 4481 8567 5069 8568 4481 8568 4486 8568 5100 8569 4465 8569 4467 8569 5100 8570 4467 8570 5101 8570 5101 8571 4467 8571 4469 8571 5101 8572 4469 8572 5102 8572 5102 8573 4469 8573 4480 8573 5102 8574 4480 8574 5103 8574 5103 8575 4480 8575 4479 8575 5103 8576 4479 8576 5097 8576 5097 8577 4479 8577 4478 8577 5097 8578 4478 8578 4477 8578 5100 8579 5071 8579 4465 8579 4465 8580 5071 8580 5070 8580 4465 8581 5070 8581 4470 8581 4470 8582 5070 8582 5082 8582 4470 8583 5082 8583 4471 8583 4471 8584 5082 8584 4473 8584 4473 8585 5082 8585 4965 8585 4473 8586 4965 8586 4953 8586 4767 8587 4765 8587 5104 8587 5104 8588 4765 8588 5105 8588 5104 8589 5105 8589 5106 8589 5107 8590 5108 8590 5105 8590 5105 8591 5108 8591 5109 8591 5105 8592 5109 8592 5106 8592 5110 8593 5111 8593 5105 8593 5105 8594 5111 8594 5107 8594 5112 8595 4827 8595 4826 8595 4765 8596 4827 8596 5105 8596 5105 8597 4827 8597 5112 8597 5105 8598 5112 8598 5110 8598 4894 8599 5111 8599 4896 8599 4896 8600 5111 8600 5110 8600 4896 8601 5110 8601 4897 8601 4897 8602 5110 8602 5112 8602 4897 8603 5112 8603 4941 8603 4941 8604 5112 8604 4826 8604 4921 8605 4962 8605 4919 8605 4919 8606 4962 8606 4998 8606 4919 8607 4998 8607 4917 8607 4917 8608 4998 8608 4915 8608 4915 8609 4998 8609 4988 8609 4915 8610 4988 8610 4913 8610 4913 8611 4988 8611 4911 8611 4911 8612 4988 8612 4989 8612 4911 8613 4989 8613 4909 8613 4990 8614 4906 8614 4989 8614 4989 8615 4906 8615 4907 8615 4989 8616 4907 8616 4909 8616 4898 8617 4900 8617 4991 8617 4991 8618 4900 8618 4902 8618 4991 8619 4902 8619 4990 8619 4990 8620 4902 8620 4904 8620 4990 8621 4904 8621 4906 8621 4898 8622 4991 8622 4893 8622 4893 8623 4991 8623 4992 8623 4893 8624 4992 8624 4894 8624 5113 8625 5114 8625 5115 8625 5115 8626 5114 8626 5116 8626 5115 8627 5116 8627 5117 8627 5116 8628 5076 8628 5117 8628 5117 8629 5076 8629 5093 8629 5117 8630 5093 8630 5118 8630 5118 8631 5093 8631 5074 8631 4694 8632 4693 8632 5096 8632 5096 8633 4693 8633 5118 8633 5096 8634 5118 8634 5073 8634 5073 8635 5118 8635 5074 8635 4993 8636 4994 8636 5114 8636 5114 8637 4994 8637 5079 8637 5114 8638 5079 8638 5116 8638 5116 8639 5079 8639 5077 8639 5116 8640 5077 8640 5076 8640 5113 8641 4587 8641 5114 8641 5114 8642 4587 8642 5119 8642 5114 8643 5119 8643 4993 8643 4993 8644 5119 8644 4992 8644 5120 8645 5121 8645 4744 8645 4710 8646 4708 8646 4797 8646 4797 8647 4708 8647 5120 8647 4797 8648 5120 8648 4796 8648 4796 8649 5120 8649 4744 8649 5122 8650 4723 8650 4722 8650 4753 8651 5123 8651 4754 8651 4754 8652 5123 8652 5122 8652 4754 8653 5122 8653 4755 8653 4755 8654 5122 8654 4722 8654 5124 632 4816 632 4758 632 5125 8655 5126 8655 5127 8655 5128 8656 5125 8656 5129 8656 5129 8657 5125 8657 5127 8657 5129 8658 5127 8658 4874 8658 4874 8659 5127 8659 4877 8659 4786 8660 5128 8660 4840 8660 4840 8661 5128 8661 5129 8661 4840 8662 5129 8662 4841 8662 4841 8663 5129 8663 4874 8663 4841 8664 4874 8664 4838 8664 4786 8665 4783 8665 5128 8665 5128 8666 4783 8666 5130 8666 5128 8667 5130 8667 5125 8667 5130 8668 5131 8668 5125 8668 5125 8669 5131 8669 5132 8669 5125 8670 5132 8670 5126 8670 5004 8671 5003 8671 5133 8671 5004 8672 5133 8672 5048 8672 5043 8673 5045 8673 5134 8673 5134 8674 5045 8674 5044 8674 5134 8675 5044 8675 5046 8675 5046 8676 5050 8676 5134 8676 5134 8677 5050 8677 5049 8677 5134 8678 5049 8678 5135 8678 5136 8679 4689 8679 4688 8679 4688 8680 5062 8680 5136 8680 5136 8681 5062 8681 5039 8681 5136 8682 5039 8682 5041 8682 5137 8683 5138 8683 5139 8683 5139 8684 5138 8684 5133 8684 5139 8685 5133 8685 5006 8685 5006 8686 5133 8686 5003 8686 5138 8687 5140 8687 5133 8687 5133 8688 5140 8688 5135 8688 5133 8689 5135 8689 5048 8689 5048 8690 5135 8690 5049 8690 5140 8691 5141 8691 5135 8691 5135 8692 5141 8692 5136 8692 5135 8693 5136 8693 5134 8693 5134 8694 5136 8694 5041 8694 5134 8695 5041 8695 5043 8695 4868 8696 4877 8696 5006 8696 5006 8697 5005 8697 4868 8697 4868 8698 5005 8698 5020 8698 4868 8699 5020 8699 4866 8699 4866 8700 5020 8700 4860 8700 4863 8701 4861 8701 5022 8701 5022 8702 4861 8702 4860 8702 5022 8703 4860 8703 5021 8703 5021 8704 4860 8704 5020 8704 4853 8705 4851 8705 5023 8705 4851 8706 4859 8706 5023 8706 5023 8707 4859 8707 4858 8707 5023 8708 4858 8708 5022 8708 5022 8709 4858 8709 4857 8709 5022 8710 4857 8710 4863 8710 5023 8711 5033 8711 4853 8711 4853 8712 5033 8712 5034 8712 4853 8713 5034 8713 4855 8713 4792 632 4791 632 5142 632 5142 632 4791 632 5143 632 5144 8714 5145 8714 5130 8714 5145 8715 5146 8715 5130 8715 5130 8716 5146 8716 5147 8716 5130 8717 5147 8717 5131 8717 5131 8718 5147 8718 5132 8718 5148 8719 5149 8719 5150 8719 5150 8720 5149 8720 5151 8720 5150 8721 5151 8721 5152 8721 5152 8722 5151 8722 5144 8722 5152 8723 5144 8723 5153 8723 5144 8724 5130 8724 5153 8724 5153 8725 5130 8725 4783 8725 5153 8726 4783 8726 4784 8726 4793 8727 5148 8727 4794 8727 4794 8728 5148 8728 5150 8728 4794 8729 5150 8729 4795 8729 4795 8730 5150 8730 5152 8730 4795 8731 5152 8731 4817 8731 4817 8732 5152 8732 5153 8732 4817 8733 5153 8733 4785 8733 4785 8734 5153 8734 4784 8734 5099 8735 5068 8735 5067 8735 4694 8736 5095 8736 5154 8736 4694 8737 5154 8737 4692 8737 4692 8738 5154 8738 5155 8738 4692 8739 5155 8739 4691 8739 4691 8740 5155 8740 5156 8740 4691 8741 5156 8741 4687 8741 4687 8742 5156 8742 5065 8742 4687 8743 5065 8743 4688 8743 5099 8744 5067 8744 5098 8744 5098 8745 5067 8745 5157 8745 5098 8746 5157 8746 5097 8746 5097 8747 5157 8747 5158 8747 5097 8748 5158 8748 5103 8748 5103 8749 5158 8749 5102 8749 5102 8750 5158 8750 5159 8750 5102 8751 5159 8751 5101 8751 5101 8752 5159 8752 5100 8752 5100 8753 5159 8753 5072 8753 5100 8754 5072 8754 5071 8754 5095 8755 5094 8755 5154 8755 5154 8756 5094 8756 5160 8756 5154 8757 5160 8757 5155 8757 5155 8758 5160 8758 5161 8758 5155 8759 5161 8759 5156 8759 5156 8760 5161 8760 5162 8760 5156 8761 5162 8761 5065 8761 5065 8762 5162 8762 5066 8762 5094 8763 5072 8763 5160 8763 5160 8764 5072 8764 5159 8764 5160 8765 5159 8765 5161 8765 5161 8766 5159 8766 5158 8766 5161 8767 5158 8767 5162 8767 5162 8768 5158 8768 5157 8768 5162 8769 5157 8769 5066 8769 5066 8770 5157 8770 5067 8770 4762 8771 4768 8771 5163 8771 5164 8772 5165 8772 5166 8772 5166 8773 5165 8773 5167 8773 4590 8774 4757 8774 4759 8774 5168 8775 5169 8775 4588 8775 5169 8776 5168 8776 5167 8776 5167 8777 5168 8777 5163 8777 5167 8778 5163 8778 5166 8778 5108 8779 5164 8779 5109 8779 5109 8780 5164 8780 5166 8780 5109 8781 5166 8781 5106 8781 5106 8782 5166 8782 5163 8782 5106 8783 5163 8783 5104 8783 5104 8784 5163 8784 4768 8784 5104 8785 4768 8785 4767 8785 4588 8786 4590 8786 5168 8786 5168 8787 4590 8787 4759 8787 5168 8788 4759 8788 5163 8788 5163 8789 4759 8789 4763 8789 5163 8790 4763 8790 4762 8790 4894 8791 4992 8791 5111 8791 5111 8792 4992 8792 5119 8792 5111 8793 5119 8793 5107 8793 4588 8794 5169 8794 4587 8794 4587 8795 5169 8795 5167 8795 5167 8796 5165 8796 4587 8796 4587 8797 5165 8797 5164 8797 4587 8798 5164 8798 5119 8798 5119 8799 5164 8799 5108 8799 5119 8800 5108 8800 5107 8800 4587 8801 5113 8801 4585 8801 4585 8802 5113 8802 4649 8802 5113 8803 5115 8803 4649 8803 4649 8804 5115 8804 5117 8804 4649 8805 5117 8805 4647 8805 4647 8806 5117 8806 5118 8806 4647 8807 5118 8807 4645 8807 4645 8808 5118 8808 4693 8808 4645 8809 4693 8809 4642 8809 5121 8810 5170 8810 4744 8810 5143 8811 4791 8811 4789 8811 5171 8812 5172 8812 5173 8812 5173 8813 5172 8813 5170 8813 5173 8814 5170 8814 5174 8814 5174 8815 5170 8815 5121 8815 5143 8816 4789 8816 5171 8816 5171 8817 4789 8817 4788 8817 5171 8818 4788 8818 5172 8818 5172 8819 4788 8819 4803 8819 5172 8820 4803 8820 5170 8820 5170 8821 4803 8821 4745 8821 5170 8822 4745 8822 4744 8822 5175 8823 5121 8823 5176 8823 5176 8824 5121 8824 5120 8824 4720 8825 4723 8825 5122 8825 5177 8826 5178 8826 4716 8826 4716 8827 5178 8827 4714 8827 5177 8828 4716 8828 5179 8828 5179 8829 4716 8829 4718 8829 5179 8830 4718 8830 5180 8830 5178 8831 5175 8831 4714 8831 4714 8832 5175 8832 5176 8832 4714 632 5176 632 4707 632 4707 8833 5176 8833 5120 8833 4707 8834 5120 8834 4708 8834 4720 8835 5122 8835 4718 8835 4718 8836 5122 8836 5181 8836 4718 8837 5181 8837 5180 8837 5180 8838 5181 8838 5182 8838 5182 8839 5181 8839 5122 8839 5182 8840 5122 8840 5123 8840 4748 8841 4747 8841 5183 8841 4816 8842 5124 8842 5184 8842 4748 8843 5183 8843 4750 8843 4750 8844 5183 8844 5185 8844 4750 8845 5185 8845 4751 8845 4753 8846 4751 8846 5123 8846 5123 8847 4751 8847 5185 8847 5123 8848 5185 8848 5186 8848 5186 8849 5185 8849 5183 8849 5186 8850 5183 8850 5187 8850 5187 8851 5183 8851 4747 8851 5187 8852 4747 8852 5184 8852 5184 8853 4747 8853 4756 8853 5184 8854 4756 8854 4816 8854 4758 8855 4757 8855 5124 8855 5124 8856 4757 8856 4590 8856 5124 8857 4590 8857 4591 8857 4664 8858 4689 8858 4662 8858 4662 8859 4689 8859 5136 8859 5137 8860 4582 8860 5138 8860 5138 8861 4582 8861 4655 8861 5138 8862 4655 8862 5140 8862 5140 8863 4655 8863 4656 8863 5140 8864 4656 8864 5141 8864 5141 8865 4656 8865 4658 8865 5141 8866 4658 8866 5136 8866 5136 8867 4658 8867 4660 8867 5136 8868 4660 8868 4662 8868 5126 8869 5132 8869 5139 8869 5139 8870 5132 8870 5137 8870 5137 8871 5132 8871 5147 8871 5137 8872 5147 8872 5146 8872 5146 8873 5145 8873 5137 8873 5137 8874 5145 8874 5144 8874 5144 8875 5151 8875 5137 8875 5137 8876 5151 8876 5149 8876 5137 8877 5149 8877 5148 8877 5006 8878 4877 8878 5139 8878 5139 8879 4877 8879 5127 8879 5139 8880 5127 8880 5126 8880 5148 8881 4793 8881 4792 8881 4792 8882 5142 8882 5148 8882 5148 8883 5142 8883 5143 8883 5148 8884 5143 8884 5188 8884 5188 8885 5143 8885 5171 8885 5189 8886 5190 8886 5191 8886 5173 8887 5174 8887 5189 8887 5189 8888 5174 8888 5121 8888 5189 8889 5121 8889 5175 8889 5189 8890 5191 8890 5173 8890 5173 8891 5191 8891 5192 8891 5173 8892 5192 8892 5171 8892 5171 8893 5192 8893 4667 8893 5171 8894 4667 8894 5188 8894 5193 8895 5189 8895 5175 8895 5175 8896 5178 8896 5193 8896 5193 8897 5178 8897 5177 8897 5193 8898 5177 8898 5194 8898 5194 8899 5177 8899 5179 8899 5194 8900 5179 8900 5195 8900 5195 8901 5179 8901 5180 8901 5195 8902 5180 8902 5196 8902 5182 8903 5196 8903 5180 8903 4591 8904 4589 8904 5197 8904 5124 8905 4591 8905 5184 8905 5184 8906 4591 8906 5197 8906 5184 8907 5197 8907 5187 8907 5187 8908 5197 8908 5198 8908 5187 8909 5198 8909 5186 8909 5182 8910 5123 8910 5196 8910 5196 8911 5123 8911 5186 8911 5196 8912 5186 8912 5199 8912 5199 8913 5186 8913 5198 8913 5188 8914 4667 8914 5148 8914 5148 106 4667 106 4582 106 5148 106 4582 106 5137 106 5200 8915 5201 8915 5202 8915 5202 8916 5201 8916 5203 8916 5202 8917 5203 8917 5204 8917 5204 8918 5203 8918 5205 8918 5204 8919 5205 8919 5206 8919 5206 8920 5205 8920 5207 8920 5206 8921 5207 8921 5208 8921 5208 8922 5207 8922 5209 8922 5208 8923 5209 8923 5210 8923 5210 8924 5209 8924 5211 8924 5210 8925 5211 8925 5212 8925 5212 8926 5211 8926 4603 8926 5212 8927 4603 8927 4605 8927 4589 8928 4585 8928 5213 8928 5213 8929 5214 8929 4589 8929 4589 8930 5214 8930 5215 8930 4589 8931 5215 8931 5216 8931 5200 8932 5202 8932 5216 8932 5216 8933 5202 8933 5217 8933 5216 8934 5217 8934 4589 8934 4605 8935 4606 8935 5218 8935 5208 8936 5210 8936 5218 8936 5218 8937 5210 8937 5212 8937 5218 8938 5212 8938 4605 8938 5219 8939 5204 8939 5206 8939 5219 8940 5206 8940 5220 8940 5204 8941 5219 8941 5202 8941 5202 8942 5219 8942 5221 8942 5202 8943 5221 8943 5217 8943 5217 8944 5221 8944 5197 8944 5217 8945 5197 8945 4589 8945 5222 8946 5199 8946 5198 8946 5223 8947 4597 8947 4602 8947 5198 8948 5224 8948 5222 8948 5222 8949 5224 8949 5225 8949 5222 8950 5225 8950 5226 8950 5226 8951 5225 8951 5223 8951 5226 8952 5223 8952 5227 8952 5227 8953 5223 8953 4602 8953 5227 8954 4602 8954 4601 8954 4606 8955 4598 8955 5218 8955 5218 8956 4598 8956 5220 8956 5218 8957 5220 8957 5208 8957 5208 8958 5220 8958 5206 8958 4598 8959 4597 8959 5220 8959 5220 8960 4597 8960 5223 8960 5220 8961 5223 8961 5219 8961 5219 8962 5223 8962 5225 8962 5219 8963 5225 8963 5221 8963 5221 8964 5225 8964 5224 8964 5221 8965 5224 8965 5197 8965 5197 8966 5224 8966 5198 8966 5227 632 4601 632 4594 632 5195 632 5196 632 5199 632 5190 632 5189 632 5193 632 4622 632 5228 632 4620 632 4620 632 5228 632 5229 632 4620 632 5229 632 4594 632 5193 8967 5194 8967 5190 8967 5190 632 5194 632 4594 632 5190 8968 4594 8968 5230 8968 5230 632 4594 632 5229 632 5195 632 5199 632 5194 632 5194 8969 5199 8969 5222 8969 5194 8970 5222 8970 4594 8970 4594 632 5222 632 5226 632 4594 632 5226 632 5227 632 5228 8971 5231 8971 5232 8971 4685 8972 4682 8972 5233 8972 5192 8973 5234 8973 4667 8973 4667 8974 5234 8974 4674 8974 5233 8975 4682 8975 5235 8975 4682 8976 4680 8976 5235 8976 5235 8977 4680 8977 4678 8977 5235 8978 4678 8978 5234 8978 5234 8979 4678 8979 4672 8979 5234 8980 4672 8980 4674 8980 5236 8981 4684 8981 4685 8981 4615 8982 4684 8982 4616 8982 4616 8983 4684 8983 5236 8983 4616 8984 5236 8984 4618 8984 4685 8985 5233 8985 5236 8985 5236 8986 5233 8986 4619 8986 5236 8987 4619 8987 4618 8987 5228 8988 5232 8988 5229 8988 5229 8989 5232 8989 5237 8989 5229 8990 5237 8990 5230 8990 5230 8991 5237 8991 5191 8991 5230 8992 5191 8992 5190 8992 5192 8993 5191 8993 5234 8993 5234 8994 5191 8994 5237 8994 5234 8995 5237 8995 5235 8995 5235 8996 5237 8996 5232 8996 5235 8997 5232 8997 5233 8997 5233 8998 5232 8998 5231 8998 5233 8999 5231 8999 4619 8999 4619 9000 5231 9000 5228 9000 4619 9001 5228 9001 4622 9001 5238 9002 5239 9002 5240 9002 4612 9003 4611 9003 5241 9003 5241 9004 4611 9004 4610 9004 5241 9005 4610 9005 5242 9005 5241 9006 5243 9006 4612 9006 4612 9007 5243 9007 5244 9007 4612 9008 5244 9008 4621 9008 4621 9009 5244 9009 5245 9009 4621 9010 5245 9010 4623 9010 4623 9011 5245 9011 5246 9011 5247 9012 5248 9012 5249 9012 5250 9013 5251 9013 5252 9013 5248 9014 5247 9014 5252 9014 5252 9015 5247 9015 5253 9015 5252 9016 5253 9016 5250 9016 5254 9017 5255 9017 5256 9017 5256 9018 5255 9018 5257 9018 5257 9019 5258 9019 5256 9019 5256 9020 5258 9020 5259 9020 5256 9021 5259 9021 5250 9021 5250 9022 5259 9022 5260 9022 5250 9023 5260 9023 5251 9023 5239 9024 5261 9024 5240 9024 5240 9025 5261 9025 5262 9025 5240 9026 5262 9026 5263 9026 5263 9027 5262 9027 5264 9027 5261 9028 5265 9028 5262 9028 5262 9029 5265 9029 5266 9029 5262 9030 5266 9030 5264 9030 5264 9031 5266 9031 5267 9031 5268 9032 5254 9032 5269 9032 5269 9033 5254 9033 5256 9033 5269 9034 5256 9034 5270 9034 5270 9035 5256 9035 5250 9035 5270 9036 5250 9036 5267 9036 5267 9037 5250 9037 5253 9037 5267 9038 5253 9038 5264 9038 5264 9039 5253 9039 5247 9039 5264 9040 5247 9040 5263 9040 5263 9041 5247 9041 5249 9041 5263 9042 5249 9042 5240 9042 5240 9043 5249 9043 5271 9043 5240 9044 5271 9044 5238 9044 5265 9045 5246 9045 5266 9045 5266 9046 5246 9046 5245 9046 5266 9047 5245 9047 5267 9047 5267 9048 5245 9048 5244 9048 5267 9049 5244 9049 5270 9049 5270 9050 5244 9050 5243 9050 5270 9051 5243 9051 5269 9051 5269 9052 5243 9052 5241 9052 5269 9053 5241 9053 5268 9053 5268 9054 5241 9054 5242 9054 5257 9055 5255 9055 5272 9055 5272 9056 5255 9056 5273 9056 4610 9057 4608 9057 5242 9057 5242 9058 4608 9058 5274 9058 5242 9059 5274 9059 5268 9059 5268 9060 5274 9060 5273 9060 5268 9061 5273 9061 5254 9061 5254 9062 5273 9062 5255 9062 5275 9063 4607 9063 4609 9063 4609 9064 5276 9064 5275 9064 5275 9065 5276 9065 5277 9065 5275 9066 5277 9066 5278 9066 5278 9067 5277 9067 5279 9067 5278 9068 5279 9068 5280 9068 5280 9069 5279 9069 5281 9069 5280 9070 5281 9070 5282 9070 4613 9071 4596 9071 5283 9071 4595 9072 5284 9072 4596 9072 5284 9073 4595 9073 4593 9073 4600 9074 5285 9074 5286 9074 5276 9075 4609 9075 5283 9075 5283 9076 4609 9076 4614 9076 5283 9077 4614 9077 4613 9077 5282 9078 5281 9078 5287 9078 5287 9079 5281 9079 5288 9079 5289 9080 5290 9080 5291 9080 5291 9081 5290 9081 5292 9081 5291 9082 5292 9082 5293 9082 5293 9083 5292 9083 5294 9083 5293 9084 5294 9084 5288 9084 5288 9085 5294 9085 5295 9085 5288 9086 5295 9086 5287 9086 5296 9087 5297 9087 5298 9087 5298 9088 5297 9088 5299 9088 5298 9089 5299 9089 5300 9089 5301 9090 5300 9090 5302 9090 5302 9091 5300 9091 5299 9091 5302 9092 5299 9092 5303 9092 4592 9093 4600 9093 4593 9093 4593 9094 4600 9094 5286 9094 4593 9095 5286 9095 5284 9095 5284 9096 5286 9096 5304 9096 5284 9097 5304 9097 4596 9097 4596 9098 5304 9098 5305 9098 4596 9099 5305 9099 5283 9099 5283 9100 5305 9100 5306 9100 5283 9101 5306 9101 5276 9101 5276 9102 5306 9102 5277 9102 5285 9103 5301 9103 5286 9103 5286 9104 5301 9104 5302 9104 5286 9105 5302 9105 5304 9105 5304 9106 5302 9106 5303 9106 5304 9107 5303 9107 5305 9107 5305 9108 5303 9108 5307 9108 5305 9109 5307 9109 5306 9109 5306 9110 5307 9110 5308 9110 5306 9111 5308 9111 5277 9111 5277 9112 5308 9112 5279 9112 5297 9113 5290 9113 5299 9113 5299 9114 5290 9114 5289 9114 5299 9115 5289 9115 5303 9115 5303 9116 5289 9116 5291 9116 5303 9117 5291 9117 5307 9117 5307 9118 5291 9118 5293 9118 5307 9119 5293 9119 5308 9119 5308 9120 5293 9120 5288 9120 5308 9121 5288 9121 5279 9121 5279 9122 5288 9122 5281 9122 5309 9123 5310 9123 5301 9123 5311 9124 5312 9124 5313 9124 5311 9125 5313 9125 5314 9125 5301 9126 5310 9126 5300 9126 5310 9127 5315 9127 5300 9127 5300 9128 5315 9128 5314 9128 5300 9129 5314 9129 5298 9129 5298 9130 5314 9130 5313 9130 5298 9131 5313 9131 5296 9131 5285 9132 4600 9132 4599 9132 4599 9133 5316 9133 5285 9133 5285 9134 5316 9134 5317 9134 5285 9135 5317 9135 5301 9135 5301 9136 5317 9136 5318 9136 5301 9137 5318 9137 5309 9137 5319 9138 5320 9138 5321 9138 5322 9139 5323 9139 5324 9139 5325 9140 5326 9140 5327 9140 5328 9141 5329 9141 5330 9141 5331 9142 5332 9142 5333 9142 5333 9143 5332 9143 5334 9143 5335 9144 5336 9144 5337 9144 5337 9145 5336 9145 5338 9145 5337 9146 5338 9146 5339 9146 5339 9147 5338 9147 5340 9147 5339 9148 5340 9148 5341 9148 5341 9149 5340 9149 5334 9149 5341 9150 5334 9150 5342 9150 5342 9151 5334 9151 5332 9151 5343 9152 5336 9152 5344 9152 5344 9153 5336 9153 5335 9153 5344 9154 5335 9154 5345 9154 5346 9155 4630 9155 5347 9155 5347 9156 5348 9156 5346 9156 5346 9157 5348 9157 5349 9157 5346 9158 5349 9158 5350 9158 5350 9159 5349 9159 5351 9159 5351 9160 5349 9160 5352 9160 5351 9161 5352 9161 5353 9161 5353 9162 5352 9162 5354 9162 5354 9163 5352 9163 5355 9163 5354 9164 5355 9164 5356 9164 5328 9165 5330 9165 5357 9165 5357 9166 5330 9166 5358 9166 5357 9167 5358 9167 5326 9167 5326 9168 5358 9168 5359 9168 5326 9169 5359 9169 5327 9169 5360 9170 235 9170 5361 9170 5362 9171 5363 9171 5359 9171 5359 9172 5363 9172 5360 9172 5359 9173 5360 9173 5327 9173 5327 9174 5360 9174 5361 9174 5327 9175 5361 9175 5325 9175 5323 9176 5362 9176 5324 9176 5324 9177 5362 9177 5359 9177 5324 9178 5359 9178 5364 9178 5364 9179 5359 9179 5358 9179 5364 9180 5358 9180 5355 9180 5355 9181 5358 9181 5330 9181 5355 9182 5330 9182 5356 9182 5356 9183 5330 9183 5329 9183 5320 9184 5345 9184 5321 9184 5321 9185 5345 9185 5335 9185 5321 9186 5335 9186 5365 9186 5365 9187 5335 9187 5337 9187 5365 9188 5337 9188 5366 9188 5366 9189 5337 9189 5339 9189 5366 9190 5339 9190 5367 9190 5367 9191 5339 9191 5341 9191 5367 9192 5341 9192 5368 9192 5368 9193 5341 9193 5342 9193 5368 9194 5342 9194 5369 9194 5369 9195 5342 9195 5332 9195 5369 9196 5332 9196 5370 9196 5370 9197 5332 9197 5331 9197 5347 9198 5319 9198 5348 9198 5348 9199 5319 9199 5321 9199 5348 9200 5321 9200 5349 9200 5349 9201 5321 9201 5365 9201 5349 9202 5365 9202 5352 9202 5352 9203 5365 9203 5366 9203 5352 9204 5366 9204 5355 9204 5355 9205 5366 9205 5367 9205 5355 9206 5367 9206 5364 9206 5364 9207 5367 9207 5368 9207 5364 9208 5368 9208 5324 9208 5324 9209 5368 9209 5369 9209 5324 9210 5369 9210 5322 9210 5322 9211 5369 9211 5370 9211 5371 9212 5372 9212 5373 9212 5374 9213 5375 9213 5376 9213 5377 9214 5378 9214 5379 9214 5380 9215 5381 9215 5382 9215 5383 9216 5384 9216 5385 9216 5381 9217 5380 9217 5386 9217 5387 9218 5388 9218 5389 9218 5390 9219 5391 9219 5392 9219 5393 9220 5394 9220 5395 9220 5395 9221 5396 9221 5393 9221 5393 9222 5396 9222 5392 9222 5393 9223 5392 9223 5397 9223 5397 9224 5392 9224 5391 9224 5398 9225 5399 9225 5400 9225 5400 9226 5399 9226 5373 9226 5400 9227 5373 9227 5401 9227 5401 9228 5373 9228 5372 9228 5401 9229 5372 9229 5402 9229 5402 9230 5372 9230 5371 9230 5402 9231 5371 9231 4638 9231 5403 9232 5404 9232 5387 9232 5387 9233 5404 9233 5405 9233 5387 9234 5405 9234 5388 9234 5388 9235 5405 9235 5406 9235 5388 9236 5406 9236 5407 9236 5407 9237 5406 9237 5408 9237 5407 9238 5408 9238 5409 9238 5409 9239 5408 9239 5410 9239 5411 9240 123 9240 5412 9240 5412 9241 123 9241 5413 9241 5412 9242 5413 9242 5414 9242 5414 9243 5383 9243 5412 9243 5412 9244 5383 9244 5385 9244 5412 9245 5385 9245 5415 9245 5415 9246 5385 9246 5416 9246 5384 9247 5386 9247 5385 9247 5385 9248 5386 9248 5380 9248 5385 9249 5380 9249 5416 9249 5416 9250 5380 9250 5382 9250 5416 9251 5382 9251 5417 9251 5417 9252 5418 9252 5419 9252 5411 9253 5412 9253 5420 9253 5420 9254 5412 9254 5415 9254 5420 9255 5415 9255 5394 9255 5394 9256 5415 9256 5416 9256 5394 9257 5416 9257 5395 9257 5395 9258 5416 9258 5417 9258 5395 9259 5417 9259 5396 9259 5396 9260 5417 9260 5419 9260 5396 9261 5419 9261 5392 9261 5421 9262 5422 9262 5423 9262 5398 9263 5410 9263 5423 9263 5423 9264 5410 9264 5408 9264 5423 9265 5408 9265 5421 9265 5421 9266 5408 9266 5406 9266 5421 9267 5406 9267 5418 9267 5418 9268 5406 9268 5405 9268 5418 9269 5405 9269 5419 9269 5419 9270 5405 9270 5404 9270 5419 9271 5404 9271 5392 9271 5392 9272 5404 9272 5403 9272 5392 9273 5403 9273 5390 9273 5378 9274 5374 9274 5379 9274 5379 9275 5374 9275 5376 9275 5379 9276 5376 9276 5424 9276 5424 9277 5376 9277 5425 9277 5424 9278 5425 9278 5426 9278 5426 9279 5425 9279 5427 9279 5426 9280 5427 9280 5428 9280 5428 9281 5427 9281 5429 9281 5428 9282 5429 9282 5430 9282 5430 9283 5429 9283 5431 9283 5430 9284 5431 9284 5432 9284 5432 9285 5431 9285 5433 9285 5398 9286 5423 9286 5399 9286 5399 9287 5423 9287 5422 9287 5399 9288 5422 9288 5373 9288 5373 9289 5422 9289 5434 9289 5373 9290 5434 9290 5371 9290 5381 9291 5377 9291 5382 9291 5382 9292 5377 9292 5379 9292 5382 9293 5379 9293 5417 9293 5417 9294 5379 9294 5424 9294 5417 9295 5424 9295 5418 9295 5418 9296 5424 9296 5426 9296 5418 9297 5426 9297 5421 9297 5421 9298 5426 9298 5428 9298 5421 9299 5428 9299 5422 9299 5422 9300 5428 9300 5430 9300 5422 9301 5430 9301 5434 9301 5434 9302 5430 9302 5432 9302 5434 9303 5432 9303 5371 9303 5371 9304 5432 9304 5435 9304 5433 9305 5436 9305 5432 9305 5432 9306 5436 9306 5437 9306 5432 9307 5437 9307 5435 9307 5438 9308 5439 9308 5440 9308 5441 9309 5442 9309 5443 9309 5443 9310 5442 9310 5444 9310 5443 9311 5444 9311 5445 9311 5443 9312 5446 9312 5441 9312 5441 9313 5446 9313 5447 9313 5441 9314 5447 9314 5333 9314 5333 9315 5447 9315 5331 9315 5448 9316 242 9316 247 9316 5449 9317 5450 9317 5438 9317 5449 9318 5362 9318 5323 9318 5450 9319 5449 9319 5451 9319 5451 9320 5449 9320 5323 9320 5451 9321 5323 9321 5322 9321 237 9322 5452 9322 247 9322 247 9323 5452 9323 5453 9323 247 9324 5453 9324 5448 9324 5448 9325 5453 9325 5454 9325 5448 9326 5454 9326 5455 9326 5455 9327 5454 9327 5456 9327 5455 9328 5456 9328 5457 9328 5445 9329 5458 9329 5443 9329 5443 9330 5458 9330 5459 9330 5443 9331 5459 9331 5446 9331 5446 9332 5459 9332 5460 9332 5446 9333 5460 9333 5447 9333 5447 9334 5460 9334 5370 9334 5447 9335 5370 9335 5331 9335 4521 9336 5440 9336 5445 9336 5445 9337 5440 9337 5439 9337 5445 9338 5439 9338 5458 9338 5458 9339 5439 9339 5438 9339 5458 9340 5438 9340 5459 9340 5459 9341 5438 9341 5450 9341 5459 9342 5450 9342 5460 9342 5460 9343 5450 9343 5451 9343 5460 9344 5451 9344 5370 9344 5370 9345 5451 9345 5322 9345 5362 9346 5449 9346 5363 9346 5363 9347 5449 9347 5461 9347 5363 9348 5461 9348 5360 9348 5360 9349 5461 9349 5462 9349 5360 9350 5462 9350 235 9350 237 9351 235 9351 5452 9351 5452 9352 235 9352 5462 9352 5452 9353 5462 9353 5453 9353 5453 9354 5462 9354 5461 9354 5453 9355 5461 9355 5454 9355 5454 9356 5461 9356 5449 9356 5454 9357 5449 9357 5456 9357 5456 9358 5449 9358 5438 9358 5456 9359 5438 9359 5457 9359 5457 9360 5438 9360 5440 9360 5328 9361 5357 9361 5463 9361 5463 9362 5357 9362 5464 9362 5464 9363 5357 9363 5326 9363 5464 9364 5326 9364 5465 9364 5465 9365 5326 9365 5325 9365 5465 9366 5325 9366 234 9366 234 9367 5325 9367 5361 9367 234 9368 5361 9368 235 9368 5350 9369 5351 9369 5466 9369 5351 9370 5353 9370 5466 9370 5466 9371 5353 9371 5354 9371 5466 9372 5354 9372 5467 9372 5467 9373 5354 9373 5356 9373 5467 9374 5356 9374 5463 9374 5463 9375 5356 9375 5329 9375 5463 9376 5329 9376 5328 9376 5466 9377 5468 9377 5350 9377 5350 9378 5468 9378 5469 9378 5350 9379 5469 9379 5346 9379 4631 9380 4630 9380 5470 9380 5470 9381 4630 9381 5346 9381 5470 9382 5346 9382 5471 9382 5471 9383 5346 9383 5469 9383 5402 9384 4638 9384 4637 9384 5402 9385 4637 9385 5401 9385 5410 9386 5398 9386 5472 9386 4637 9387 5473 9387 5401 9387 5401 9388 5473 9388 5472 9388 5401 9389 5472 9389 5400 9389 5400 9390 5472 9390 5398 9390 5474 9391 5389 9391 5388 9391 5472 9392 5475 9392 5410 9392 5410 9393 5475 9393 5476 9393 5410 9394 5476 9394 5409 9394 5409 9395 5476 9395 5474 9395 5409 9396 5474 9396 5407 9396 5407 9397 5474 9397 5388 9397 5391 9398 5390 9398 5477 9398 5477 9399 5390 9399 5403 9399 5477 9400 5403 9400 5387 9400 5389 9401 5474 9401 5387 9401 5387 9402 5474 9402 5478 9402 5387 9403 5478 9403 5477 9403 5479 9404 5420 9404 5394 9404 5479 9405 5394 9405 5480 9405 5480 9406 5394 9406 5393 9406 5480 9407 5393 9407 5477 9407 5477 9408 5393 9408 5397 9408 5477 9409 5397 9409 5391 9409 5420 9410 5479 9410 5411 9410 5411 9411 5479 9411 122 9411 5411 9412 122 9412 123 9412 5414 9413 5413 9413 5481 9413 5482 9414 5483 9414 5484 9414 5483 9415 5482 9415 5485 9415 114 9416 5486 9416 123 9416 113 9417 5487 9417 5488 9417 5489 9418 5490 9418 5491 9418 113 9419 5488 9419 114 9419 114 9420 5488 9420 5481 9420 114 9421 5481 9421 5486 9421 5486 9422 5481 9422 5413 9422 5486 9423 5413 9423 123 9423 5492 9424 4513 9424 5493 9424 5493 9425 4513 9425 5494 9425 5493 9426 5494 9426 5495 9426 5495 9427 5494 9427 5496 9427 5495 9428 5496 9428 5497 9428 5497 9429 5498 9429 5495 9429 5495 9430 5498 9430 5499 9430 5495 9431 5499 9431 5493 9431 5493 9432 5499 9432 5484 9432 5493 9433 5484 9433 5492 9433 5492 9434 5484 9434 5483 9434 5487 9435 5491 9435 5488 9435 5488 9436 5491 9436 5490 9436 5488 9437 5490 9437 5481 9437 5481 9438 5490 9438 5383 9438 5481 9439 5383 9439 5414 9439 5374 9440 5378 9440 5500 9440 5500 9441 5378 9441 5377 9441 5500 9442 5377 9442 5501 9442 5501 9443 5377 9443 5381 9443 5501 9444 5381 9444 5489 9444 5489 9445 5381 9445 5386 9445 5489 9446 5386 9446 5490 9446 5490 9447 5386 9447 5384 9447 5490 9448 5384 9448 5383 9448 5375 9449 5374 9449 5502 9449 5502 9450 5374 9450 5500 9450 5502 9451 5500 9451 5503 9451 5503 9452 5500 9452 5501 9452 5503 9453 5501 9453 5504 9453 5504 9454 5501 9454 5489 9454 5487 9455 5485 9455 5491 9455 5491 9456 5485 9456 5482 9456 5491 9457 5482 9457 5489 9457 5489 9458 5482 9458 5484 9458 5489 9459 5484 9459 5504 9459 5504 9460 5484 9460 5499 9460 5504 9461 5499 9461 5503 9461 5503 9462 5499 9462 5498 9462 5503 9463 5498 9463 5502 9463 5502 9464 5498 9464 5497 9464 5502 9465 5497 9465 5375 9465 5505 9466 4514 9466 4513 9466 5487 9467 113 9467 119 9467 119 9468 5506 9468 5487 9468 5487 9469 5506 9469 5507 9469 5487 9469 5507 9469 5485 9469 5485 9470 5507 9470 5508 9470 5485 9471 5508 9471 5483 9471 4513 9472 5492 9472 5505 9472 5505 9473 5492 9473 5483 9473 5505 9474 5483 9474 5509 9474 5509 9475 5483 9475 5508 9475 5510 9476 231 9476 242 9476 5440 9477 4521 9477 4520 9477 4520 9478 5511 9478 5440 9478 5440 9479 5511 9479 5512 9479 5440 9480 5512 9480 5457 9480 5512 9481 5513 9481 5457 9481 5457 9482 5513 9482 5514 9482 5457 9483 5514 9483 5455 9483 242 9484 5448 9484 5510 9484 5510 9485 5448 9485 5455 9485 5510 9486 5455 9486 5515 9486 5515 9487 5455 9487 5514 9487 4704 9488 4731 9488 4728 9488 4704 9489 4728 9489 4696 9489 4696 9490 4728 9490 4725 9490 4696 9491 4725 9491 4697 9491 4697 9492 4725 9492 4724 9492 4697 9493 4724 9493 4703 9493 4703 9494 4724 9494 4719 9494 4703 9495 4719 9495 4702 9495 4702 9496 4719 9496 4717 9496 4702 9497 4717 9497 4700 9497 4700 9498 4717 9498 4715 9498 4700 9499 4715 9499 4701 9499 4701 9500 4715 9500 4713 9500 4701 9501 4713 9501 4695 9501 4695 9502 4713 9502 4712 9502 4695 9503 4712 9503 4698 9503 4698 9504 4712 9504 4709 9504 4698 9505 4709 9505 4699 9505 4699 9506 4709 9506 4737 9506 4699 9507 4737 9507 4706 9507 4706 9508 4737 9508 4734 9508 4706 9509 4734 9509 4705 9509 4705 9510 4734 9510 4731 9510 4705 9511 4731 9511 4704 9511 4586 9512 4652 9512 4584 9512 4584 9513 4652 9513 4651 9513 4584 9514 4651 9514 5516 9514 4643 9515 4690 9515 4644 9515 4644 9516 4690 9516 5517 9516 4644 9517 5517 9517 5518 9517 4651 9518 4650 9518 5516 9518 5516 9519 4650 9519 4648 9519 5516 9520 4648 9520 5518 9520 5518 9521 4648 9521 4646 9521 5518 9522 4646 9522 4644 9522 1451 9523 4584 9523 1457 9523 1457 9524 4584 9524 5516 9524 1457 9525 5516 9525 1458 9525 1458 9526 5516 9526 5518 9526 1458 9527 5518 9527 1443 9527 1443 9528 5518 9528 5517 9528 1443 9529 5517 9529 1444 9529 1444 9530 5517 9530 1445 9530 1445 9531 5517 9531 4690 9531 1445 9532 4690 9532 1446 9532 4686 9533 4663 9533 4665 9533 5519 9534 5520 9534 4659 9534 4659 9535 4657 9535 5519 9535 5519 9536 4657 9536 4654 9536 5519 9537 4654 9537 4583 9537 4583 9538 4654 9538 4653 9538 4583 9539 4653 9539 4581 9539 4686 9540 4665 9540 5521 9540 5521 9541 4665 9541 4666 9541 5521 9542 4666 9542 5520 9542 5520 9543 4666 9543 4661 9543 5520 9544 4661 9544 4659 9544 1448 9545 4686 9545 5521 9545 1448 9546 5521 9546 1449 9546 1449 9547 5521 9547 5520 9547 1449 9548 5520 9548 1439 9548 1439 9549 5520 9549 5519 9549 1439 9550 5519 9550 1440 9550 1440 9551 5519 9551 4583 9551 1440 9552 4583 9552 1435 9552 5522 9553 5523 9553 1455 9553 5524 9554 4585 9554 1451 9554 1455 9555 5523 9555 1451 9555 1451 9556 5523 9556 5525 9556 1451 9557 5525 9557 5524 9557 1454 9558 5526 9558 1455 9558 1455 9559 5526 9559 5527 9559 1455 9560 5527 9560 5522 9560 1453 9561 5528 9561 1454 9561 1454 9562 5528 9562 5529 9562 1454 9563 5529 9563 5526 9563 5530 9564 5531 9564 1434 9564 1434 9565 5531 9565 5532 9565 1434 9566 5532 9566 1436 9566 5530 9567 1434 9567 5533 9567 5533 9568 1434 9568 1433 9568 5533 9569 1433 9569 5534 9569 4582 9570 5535 9570 1435 9570 1435 9571 5535 9571 5536 9571 1435 9572 5536 9572 1433 9572 1433 9573 5536 9573 5537 9573 1433 9574 5537 9574 5534 9574 5538 9575 5539 9575 5540 9575 5528 9576 1453 9576 1456 9576 5524 9577 5525 9577 5541 9577 5541 9578 5525 9578 5523 9578 5541 9579 5523 9579 5542 9579 5542 9580 5523 9580 5522 9580 5542 9581 5522 9581 5543 9581 4585 9582 5524 9582 5213 9582 5213 9583 5524 9583 5541 9583 5213 9584 5541 9584 5544 9584 5544 9585 5541 9585 5542 9585 5544 9586 5542 9586 5545 9586 5545 9587 5542 9587 5543 9587 5545 9588 5543 9588 5546 9588 5546 9589 5215 9589 5545 9589 5545 9590 5215 9590 5214 9590 5545 9591 5214 9591 5544 9591 5544 9592 5214 9592 5213 9592 5201 9593 5200 9593 5546 9593 5546 9594 5200 9594 5216 9594 5546 9595 5216 9595 5215 9595 1456 9596 5547 9596 5528 9596 5528 9597 5547 9597 5548 9597 5528 9598 5548 9598 5529 9598 5529 9599 5548 9599 5540 9599 5529 9600 5540 9600 5526 9600 5526 9601 5540 9601 5539 9601 5526 9602 5539 9602 5527 9602 5538 9603 5540 9603 5549 9603 5549 9604 5540 9604 5548 9604 5549 9605 5548 9605 5550 9605 5550 9606 5548 9606 5547 9606 5550 9607 5547 9607 5551 9607 1456 9608 5552 9608 5547 9608 5547 9609 5552 9609 5553 9609 5547 9610 5553 9610 5551 9610 5551 9611 5553 9611 5554 9611 5551 9612 5554 9612 5555 9612 5522 9613 5527 9613 5543 9613 5543 9614 5527 9614 5539 9614 5543 9615 5539 9615 5546 9615 5546 9616 5539 9616 5538 9616 5546 9617 5538 9617 5201 9617 5201 9618 5538 9618 5549 9618 5201 9619 5549 9619 5203 9619 5203 9620 5549 9620 5550 9620 5203 9621 5550 9621 5205 9621 5205 9622 5550 9622 5551 9622 5205 9623 5551 9623 5207 9623 5207 9624 5551 9624 5555 9624 5207 9625 5555 9625 5209 9625 5552 9626 1456 9626 1450 9626 770 9627 768 9627 5556 9627 770 9628 5556 9628 771 9628 5557 9629 1450 9629 1452 9629 5557 9630 5554 9630 1450 9630 1450 9631 5554 9631 5553 9631 1450 9632 5553 9632 5552 9632 5211 9633 5209 9633 5557 9633 5557 9634 5209 9634 5555 9634 5557 9635 5555 9635 5554 9635 1452 9636 771 9636 5557 9636 5557 9637 771 9637 5556 9637 5557 9638 5556 9638 5211 9638 5211 9639 5556 9639 4603 9639 5558 9640 5559 9640 5560 9640 5561 9641 5562 9641 5563 9641 5563 9642 5562 9642 1437 9642 4668 9643 4669 9643 5564 9643 5564 9644 4669 9644 4676 9644 5564 9645 4676 9645 5565 9645 5565 9646 4676 9646 4675 9646 5565 9647 4675 9647 5566 9647 5566 9648 4675 9648 4673 9648 5566 9649 4673 9649 5567 9649 5535 9650 5568 9650 5536 9650 5536 9651 5568 9651 5569 9651 5536 9652 5569 9652 5537 9652 5537 9653 5569 9653 5570 9653 5537 9654 5570 9654 5534 9654 5534 9655 5570 9655 5571 9655 5534 9656 5571 9656 5533 9656 5533 9657 5571 9657 5572 9657 5533 9658 5572 9658 5530 9658 5530 9659 5572 9659 5573 9659 5530 9660 5573 9660 5531 9660 5531 9661 5573 9661 5563 9661 5531 9662 5563 9662 5532 9662 5532 9663 5563 9663 1437 9663 5532 9664 1437 9664 1436 9664 4673 9665 4671 9665 5567 9665 5567 9666 4671 9666 4670 9666 5567 9667 4670 9667 5574 9667 5574 9668 4670 9668 4677 9668 5574 9669 4677 9669 5575 9669 5575 9670 4677 9670 4679 9670 5575 9671 4679 9671 5560 9671 5560 9672 4679 9672 4681 9672 5560 9673 4681 9673 5558 9673 4582 9674 4668 9674 5535 9674 5535 9675 4668 9675 5564 9675 5535 9676 5564 9676 5568 9676 5568 9677 5564 9677 5565 9677 5568 9678 5565 9678 5569 9678 5569 9679 5565 9679 5566 9679 5569 9680 5566 9680 5570 9680 5570 9681 5566 9681 5567 9681 5570 9682 5567 9682 5571 9682 5571 9683 5567 9683 5574 9683 5571 9684 5574 9684 5572 9684 5572 9685 5574 9685 5575 9685 5572 9686 5575 9686 5573 9686 5573 9687 5575 9687 5560 9687 5573 9688 5560 9688 5563 9688 5563 9689 5560 9689 5559 9689 5563 9690 5559 9690 5561 9690 116 9691 118 9691 5576 9691 5576 9692 118 9692 5577 9692 5578 9693 5579 9693 5580 9693 5580 9694 5579 9694 5581 9694 5580 9695 5581 9695 5577 9695 5577 9696 5581 9696 5582 9696 5577 9697 5582 9697 5576 9697 5583 9698 5584 9698 5578 9698 5578 9699 5584 9699 5585 9699 5578 9700 5585 9700 5586 9700 5587 9701 5579 9701 5588 9701 5588 9702 5579 9702 5578 9702 5588 9703 5578 9703 5589 9703 5589 9704 5578 9704 5586 9704 5579 9705 5590 9705 5581 9705 5581 9706 5590 9706 5591 9706 5581 9707 5591 9707 5582 9707 5582 9708 5591 9708 5576 9708 5592 9709 5593 9709 5591 9709 5591 9710 5593 9710 5594 9710 5591 9711 5594 9711 5595 9711 116 9712 5576 9712 131 9712 131 9713 5576 9713 5591 9713 131 9714 5591 9714 5596 9714 5596 9715 5591 9715 5595 9715 5597 9716 5598 9716 5590 9716 5590 9717 5598 9717 5599 9717 5590 9718 5599 9718 5591 9718 5591 9719 5599 9719 5600 9719 5591 9720 5600 9720 5592 9720 5601 9721 130 9721 5602 9721 5602 9722 130 9722 131 9722 5602 9723 5603 9723 5601 9723 5601 9724 5603 9724 5604 9724 5601 9725 5604 9725 5605 9725 5605 9726 5604 9726 5606 9726 5605 9727 5606 9727 5607 9727 131 9728 5608 9728 5602 9728 5602 9729 5608 9729 5609 9729 5602 9730 5609 9730 5603 9730 5603 9731 5609 9731 5610 9731 5603 9732 5610 9732 5604 9732 5604 9733 5610 9733 5611 9733 5604 9734 5611 9734 5606 9734 5612 9735 5613 9735 5614 9735 5615 9736 115 9736 127 9736 5616 9737 5617 9737 5618 9737 5618 9738 5617 9738 5619 9738 5618 9739 5619 9739 5620 9739 5620 9740 5619 9740 5621 9740 5620 9741 5621 9741 5622 9741 5623 9742 5624 9742 5616 9742 5616 9743 5624 9743 5625 9743 5616 9744 5625 9744 5617 9744 5626 9745 5627 9745 5628 9745 5628 9746 5627 9746 5629 9746 5628 9747 5629 9747 5623 9747 5623 9748 5629 9748 5630 9748 5623 9749 5630 9749 5624 9749 5631 9750 126 9750 125 9750 126 9751 5631 9751 127 9751 5632 9752 110 9752 115 9752 5633 9753 5634 9753 5632 9753 5632 9754 5634 9754 5635 9754 5632 9755 5635 9755 110 9755 110 9756 5635 9756 5636 9756 110 9757 5636 9757 111 9757 5614 9758 5613 9758 5632 9758 5632 9759 5613 9759 5637 9759 5632 9760 5637 9760 5633 9760 5638 9761 5639 9761 5640 9761 5640 9762 5639 9762 5641 9762 5640 9763 5641 9763 5614 9763 5614 9764 5641 9764 5642 9764 5614 9765 5642 9765 5612 9765 5640 9766 5643 9766 5638 9766 5638 9767 5643 9767 5644 9767 5638 9768 5644 9768 5645 9768 5645 9769 5644 9769 5646 9769 5645 9770 5646 9770 5647 9770 5622 9771 5648 9771 5620 9771 5620 9772 5648 9772 5649 9772 5620 9773 5649 9773 5650 9773 115 9774 5615 9774 5632 9774 5632 9775 5615 9775 5651 9775 5632 9776 5651 9776 5614 9776 5614 9777 5651 9777 5652 9777 5614 9778 5652 9778 5640 9778 5640 9779 5652 9779 5653 9779 5640 9780 5653 9780 5643 9780 5643 9781 5653 9781 5654 9781 5643 9782 5654 9782 5644 9782 5644 9783 5654 9783 5655 9783 5644 9784 5655 9784 5646 9784 127 9785 5631 9785 5615 9785 5615 9786 5631 9786 5656 9786 5615 9787 5656 9787 5651 9787 5651 9788 5656 9788 5657 9788 5651 9789 5657 9789 5652 9789 5652 9790 5657 9790 5658 9790 5652 9791 5658 9791 5653 9791 5653 9792 5658 9792 5659 9792 5653 9793 5659 9793 5654 9793 5654 9794 5659 9794 5660 9794 5654 9795 5660 9795 5655 9795 124 9796 5626 9796 125 9796 125 9797 5626 9797 5628 9797 125 9798 5628 9798 5631 9798 5631 9799 5628 9799 5623 9799 5631 9800 5623 9800 5656 9800 5656 9801 5623 9801 5616 9801 5656 9802 5616 9802 5657 9802 5657 9803 5616 9803 5618 9803 5657 9804 5618 9804 5658 9804 5658 9805 5618 9805 5620 9805 5658 9806 5620 9806 5659 9806 5659 9807 5620 9807 5650 9807 5659 9808 5650 9808 5660 9808 5661 9809 5505 9809 5509 9809 5662 9810 5663 9810 5664 9810 5663 9811 5665 9811 5666 9811 5663 9812 5662 9812 5665 9812 5665 9813 5662 9813 5667 9813 5665 9814 5667 9814 5668 9814 5669 9815 5670 9815 5664 9815 5664 9816 5670 9816 5671 9816 5664 9817 5671 9817 5662 9817 5672 9818 5673 9818 5674 9818 5674 9819 5673 9819 5675 9819 5674 9820 5675 9820 5669 9820 5669 9821 5675 9821 5676 9821 5669 9822 5676 9822 5670 9822 4514 9823 5505 9823 5677 9823 5677 9824 5505 9824 5661 9824 5677 9825 5661 9825 5666 9825 5678 9826 5508 9826 5679 9826 5679 9827 5508 9827 5507 9827 5679 9828 5507 9828 5680 9828 5680 9829 5507 9829 5506 9829 5680 9830 5506 9830 5681 9830 5681 9831 5506 9831 119 9831 5681 9832 119 9832 112 9832 5680 9833 5682 9833 5679 9833 5679 9834 5682 9834 5683 9834 5679 9835 5683 9835 5678 9835 5678 9836 5683 9836 5684 9836 111 9837 5685 9837 112 9837 112 9838 5685 9838 5686 9838 112 9839 5686 9839 5681 9839 5681 9840 5686 9840 5687 9840 5681 9841 5687 9841 5680 9841 5680 9842 5687 9842 5688 9842 5680 9843 5688 9843 5682 9843 5682 9844 5688 9844 5689 9844 5682 9845 5689 9845 5683 9845 5683 9846 5689 9846 5690 9846 5683 9847 5690 9847 5684 9847 5685 9848 5672 9848 5686 9848 5686 9849 5672 9849 5674 9849 5686 9850 5674 9850 5687 9850 5687 9851 5674 9851 5669 9851 5687 9852 5669 9852 5688 9852 5688 9853 5669 9853 5664 9853 5688 9854 5664 9854 5689 9854 5689 9855 5664 9855 5663 9855 5689 9856 5663 9856 5690 9856 5690 9857 5663 9857 5666 9857 5690 9858 5666 9858 5684 9858 5684 9859 5666 9859 5661 9859 5684 9860 5661 9860 5678 9860 5678 9861 5661 9861 5509 9861 5678 9862 5509 9862 5508 9862 5691 9863 5692 9863 5693 9863 5693 9864 5692 9864 5694 9864 5693 9865 5694 9865 5695 9865 5695 9866 5696 9866 5693 9866 5693 9867 5696 9867 5697 9867 5693 9868 5697 9868 5698 9868 5699 9869 5700 9869 5701 9869 5701 9870 5692 9870 5699 9870 5699 9871 5692 9871 5691 9871 5699 9872 5691 9872 5702 9872 5702 9873 5691 9873 5703 9873 5691 9874 5704 9874 5703 9874 5703 9875 5704 9875 233 9875 5703 9876 233 9876 230 9876 5705 9877 5706 9877 4556 9877 4556 95 5706 95 5707 95 4556 95 5707 95 4560 95 4550 95 4552 95 4556 95 4556 9878 4552 9878 5708 9878 4556 95 5708 95 5705 95 5588 9879 5589 9879 5709 9879 5710 9880 5711 9880 5588 9880 5588 9881 5711 9881 5712 9881 5588 9882 5712 9882 5587 9882 5588 9883 5709 9883 5710 9883 5710 9884 5709 9884 5713 9884 5710 9885 5713 9885 5714 9885 5714 9886 5713 9886 5715 9886 5714 9887 5715 9887 5716 9887 5589 9888 5586 9888 5709 9888 5709 9889 5586 9889 5585 9889 5709 9890 5585 9890 5713 9890 5713 9891 5585 9891 5584 9891 5713 9892 5584 9892 5715 9892 5717 9893 5599 9893 5598 9893 5597 9894 5718 9894 5719 9894 5719 9895 5718 9895 5720 9895 5719 9896 5720 9896 5721 9896 5721 9897 5720 9897 5722 9897 5721 9898 5722 9898 5723 9898 5723 9899 5722 9899 5724 9899 5723 9900 5724 9900 5725 9900 5725 9901 5724 9901 5726 9901 5725 9902 5726 9902 5727 9902 5728 9903 5729 9903 5727 9903 5727 9904 5729 9904 5730 9904 5727 9905 5730 9905 5725 9905 5725 9906 5730 9906 5731 9906 5725 9907 5731 9907 5723 9907 5723 9908 5731 9908 5732 9908 5723 9909 5732 9909 5721 9909 5721 9910 5732 9910 5717 9910 5721 9911 5717 9911 5719 9911 5719 9912 5717 9912 5598 9912 5719 9913 5598 9913 5597 9913 5733 9914 5728 9914 5734 9914 5734 9915 5728 9915 5727 9915 5734 9916 5727 9916 5735 9916 5735 9917 5727 9917 5726 9917 5736 9918 5712 9918 5711 9918 5700 9919 5737 9919 5738 9919 5739 9920 5740 9920 5741 9920 5597 9921 5742 9921 5743 9921 5712 9922 5736 9922 5587 9922 5699 9923 5744 9923 5700 9923 5700 9924 5744 9924 5741 9924 5700 9925 5741 9925 5737 9925 5737 9926 5741 9926 5740 9926 5737 9927 5740 9927 5745 9927 5745 9928 5740 9928 5739 9928 5745 9929 5739 9929 5746 9929 5746 9930 5739 9930 5747 9930 5746 9931 5747 9931 5748 9931 5748 9932 5747 9932 5749 9932 5748 9933 5749 9933 5750 9933 5750 9934 5749 9934 5751 9934 5750 9935 5751 9935 5752 9935 5752 9936 5751 9936 5753 9936 5752 9937 5753 9937 5754 9937 5754 9938 5753 9938 5755 9938 5754 9939 5755 9939 5756 9939 5756 9940 5755 9940 5757 9940 5756 9941 5757 9941 5758 9941 5758 9942 5757 9942 5743 9942 5758 9943 5743 9943 5759 9943 5759 9944 5743 9944 5742 9944 5759 9945 5742 9945 5736 9945 5736 9946 5742 9946 5597 9946 5736 9947 5597 9947 5587 9947 5587 9948 5597 9948 5590 9948 5587 9949 5590 9949 5579 9949 5760 9950 5728 9950 5733 9950 5761 9951 5762 9951 5763 9951 5764 9952 5765 9952 5766 9952 5599 9953 5717 9953 5600 9953 5600 9954 5717 9954 5732 9954 5593 9955 5592 9955 5767 9955 5767 9956 5592 9956 5768 9956 5767 9957 5768 9957 5769 9957 5770 9958 5595 9958 5594 9958 5608 9959 131 9959 5596 9959 5595 9960 5770 9960 5596 9960 5596 9961 5770 9961 5771 9961 5596 9962 5771 9962 5608 9962 5608 9963 5771 9963 5763 9963 5608 9964 5763 9964 5609 9964 5609 9965 5763 9965 5762 9965 5609 9966 5762 9966 5610 9966 5611 9967 5610 9967 5772 9967 5772 9968 5610 9968 5762 9968 5772 9969 5762 9969 5773 9969 5773 9970 5762 9970 5761 9970 5773 9971 5761 9971 5774 9971 5592 9972 5600 9972 5768 9972 5768 9973 5600 9973 5732 9973 5768 9974 5732 9974 5769 9974 5769 9975 5732 9975 5731 9975 5769 9976 5731 9976 5775 9976 5775 9977 5731 9977 5776 9977 5776 9978 5731 9978 5730 9978 5776 9979 5730 9979 5760 9979 5760 9980 5730 9980 5729 9980 5760 9981 5729 9981 5728 9981 5733 9982 5764 9982 5760 9982 5760 9983 5764 9983 5766 9983 5760 9984 5766 9984 5776 9984 5776 9985 5766 9985 5777 9985 5776 9986 5777 9986 5775 9986 5775 9987 5777 9987 5778 9987 5775 9988 5778 9988 5769 9988 5765 9989 5774 9989 5766 9989 5766 9990 5774 9990 5761 9990 5766 9991 5761 9991 5777 9991 5777 9992 5761 9992 5763 9992 5777 9993 5763 9993 5778 9993 5778 9994 5763 9994 5771 9994 5778 9995 5771 9995 5769 9995 5769 9996 5771 9996 5770 9996 5769 9997 5770 9997 5767 9997 5767 9998 5770 9998 5594 9998 5767 9999 5594 9999 5593 9999 5779 10000 5780 10000 5781 10000 5662 10001 5671 10001 5782 10001 5637 10002 5613 10002 5783 10002 5783 10003 5613 10003 5612 10003 5784 10004 5785 10004 5786 10004 5787 10005 5668 10005 5667 10005 5788 10006 5789 10006 5790 10006 5790 10007 5789 10007 5791 10007 5792 10008 5793 10008 5794 10008 5794 10009 5793 10009 5795 10009 5794 10010 5795 10010 5796 10010 5796 10011 5795 10011 5797 10011 5796 10012 5797 10012 5798 10012 5798 10013 5797 10013 5791 10013 5798 10014 5791 10014 5799 10014 5799 10015 5791 10015 5789 10015 5645 10016 5647 10016 5800 10016 5801 10017 5638 10017 5802 10017 5802 10018 5638 10018 5645 10018 5802 10019 5645 10019 5803 10019 5803 10020 5645 10020 5800 10020 5804 10021 5641 10021 5801 10021 5801 10022 5641 10022 5639 10022 5801 10023 5639 10023 5638 10023 5781 10024 5634 10024 5633 10024 111 10025 5636 10025 5685 10025 5685 10026 5636 10026 5635 10026 5685 10027 5635 10027 5672 10027 5672 10028 5635 10028 5634 10028 5672 10029 5634 10029 5673 10029 5673 10030 5634 10030 5781 10030 5673 10031 5781 10031 5675 10031 5675 10032 5781 10032 5676 10032 5676 10033 5781 10033 5780 10033 5676 10034 5780 10034 5670 10034 5662 10035 5782 10035 5667 10035 5633 10036 5637 10036 5781 10036 5781 10037 5637 10037 5783 10037 5781 10038 5783 10038 5779 10038 5779 10039 5783 10039 5612 10039 5779 10040 5612 10040 5804 10040 5804 10041 5612 10041 5642 10041 5804 10042 5642 10042 5641 10042 5785 10043 5792 10043 5786 10043 5786 10044 5792 10044 5794 10044 5786 10045 5794 10045 5805 10045 5805 10046 5794 10046 5796 10046 5805 10047 5796 10047 5806 10047 5806 10048 5796 10048 5798 10048 5806 10049 5798 10049 5807 10049 5807 10050 5798 10050 5799 10050 5807 10051 5799 10051 5808 10051 5808 10052 5799 10052 5789 10052 5808 10053 5789 10053 5782 10053 5782 10054 5789 10054 5788 10054 5782 10055 5788 10055 5667 10055 5667 10056 5788 10056 5790 10056 5667 10057 5790 10057 5787 10057 5671 10058 5670 10058 5782 10058 5782 10059 5670 10059 5780 10059 5782 10060 5780 10060 5808 10060 5808 10061 5780 10061 5779 10061 5808 10062 5779 10062 5807 10062 5807 10063 5779 10063 5804 10063 5807 10064 5804 10064 5806 10064 5806 10065 5804 10065 5801 10065 5806 10066 5801 10066 5805 10066 5805 10067 5801 10067 5802 10067 5805 10068 5802 10068 5786 10068 5786 10069 5802 10069 5803 10069 5786 10070 5803 10070 5784 10070 5784 10071 5803 10071 5800 10071 4529 10072 4506 10072 4508 10072 5809 10073 5797 10073 5793 10073 5793 10074 5797 10074 5795 10074 5809 10075 5810 10075 5668 10075 5791 10076 5797 10076 5790 10076 5790 10077 5797 10077 5809 10077 5790 10078 5809 10078 5787 10078 5787 10079 5809 10079 5668 10079 5811 10080 4510 10080 4514 10080 4514 10081 5677 10081 5811 10081 5811 10082 5677 10082 5666 10082 5811 10083 5666 10083 5810 10083 5810 10084 5666 10084 5665 10084 5810 10085 5665 10085 5668 10085 4529 10086 4508 10086 4530 10086 4530 10087 4508 10087 5812 10087 4530 10088 5812 10088 4531 10088 4531 10089 5812 10089 5813 10089 4531 10090 5813 10090 4536 10090 5814 10091 4538 10091 5815 10091 5815 10092 4538 10092 4537 10092 5815 10093 4537 10093 4536 10093 4536 10094 5813 10094 5815 10094 5815 10095 5813 10095 5816 10095 5815 10096 5816 10096 5814 10096 5809 10097 5816 10097 5810 10097 5810 10098 5816 10098 5813 10098 5810 10099 5813 10099 5811 10099 5811 10100 5813 10100 5812 10100 5811 10101 5812 10101 4510 10101 4510 10102 5812 10102 4508 10102 5817 10103 240 10103 241 10103 5818 10104 5819 10104 5820 10104 5821 10105 5822 10105 5823 10105 5823 10106 5822 10106 5824 10106 5825 10107 5826 10107 5822 10107 5822 10108 5826 10108 5827 10108 5822 10109 5827 10109 5824 10109 5828 10110 5829 10110 5820 10110 5820 10111 5829 10111 5830 10111 5820 10112 5830 10112 5818 10112 5818 10113 5830 10113 5831 10113 5818 10114 5831 10114 5832 10114 5832 10115 5831 10115 5833 10115 5832 10116 5833 10116 5825 10116 5825 10117 5833 10117 5834 10117 5825 10118 5834 10118 5826 10118 5835 10119 5836 10119 5837 10119 5838 10120 5836 10120 5839 10120 5839 10121 5836 10121 5835 10121 5839 10122 5835 10122 5840 10122 5840 10123 5835 10123 5841 10123 5842 10124 5843 10124 5841 10124 5841 10125 5843 10125 5844 10125 5841 10126 5844 10126 5840 10126 5845 10127 5846 10127 5847 10127 5847 10128 5846 10128 5848 10128 5847 10129 5848 10129 5849 10129 5849 10130 5848 10130 5850 10130 5849 10131 5850 10131 5842 10131 5842 10132 5850 10132 5851 10132 5842 10133 5851 10133 5843 10133 5852 10134 243 10134 227 10134 243 10135 5852 10135 241 10135 5823 10136 246 10136 5821 10136 5821 10137 246 10137 239 10137 5821 10138 239 10138 240 10138 240 10139 5817 10139 5821 10139 5821 10140 5817 10140 5853 10140 5821 10141 5853 10141 5822 10141 5822 10142 5853 10142 5854 10142 5822 10143 5854 10143 5825 10143 5825 10144 5854 10144 5855 10144 5825 10145 5855 10145 5832 10145 5832 10146 5855 10146 5856 10146 5832 10147 5856 10147 5818 10147 5818 10148 5856 10148 5857 10148 5818 10149 5857 10149 5819 10149 241 10150 5852 10150 5817 10150 5817 10151 5852 10151 5858 10151 5817 10152 5858 10152 5853 10152 5853 10153 5858 10153 5859 10153 5853 10154 5859 10154 5854 10154 5854 10155 5859 10155 5860 10155 5854 10156 5860 10156 5855 10156 5855 10157 5860 10157 5861 10157 5855 10158 5861 10158 5856 10158 5856 10159 5861 10159 5862 10159 5856 10160 5862 10160 5857 10160 226 10161 5845 10161 227 10161 227 10162 5845 10162 5847 10162 227 10163 5847 10163 5852 10163 5852 10164 5847 10164 5849 10164 5852 10165 5849 10165 5858 10165 5858 10166 5849 10166 5842 10166 5858 10167 5842 10167 5859 10167 5859 10168 5842 10168 5841 10168 5859 10169 5841 10169 5860 10169 5860 10170 5841 10170 5835 10170 5860 10171 5835 10171 5861 10171 5861 10172 5835 10172 5837 10172 5861 10173 5837 10173 5862 10173 5863 10174 5864 10174 5865 10174 5865 10175 5864 10175 5866 10175 228 10176 5867 10176 5868 10176 5868 10177 5867 10177 5869 10177 5869 10178 5870 10178 5868 10178 5868 10179 5870 10179 5871 10179 5868 10180 5871 10180 228 10180 228 10181 5871 10181 229 10181 5872 10182 5873 10182 5870 10182 5870 10183 5873 10183 5874 10183 5870 10184 5874 10184 5871 10184 5869 10185 5866 10185 5870 10185 5870 10186 5866 10186 5864 10186 5870 10187 5864 10187 5872 10187 5872 10188 5864 10188 5863 10188 5872 10189 5863 10189 5875 10189 5876 10190 5877 10190 5878 10190 5879 10191 5741 10191 5744 10191 5878 10192 5703 10192 230 10192 5744 10193 5699 10193 5878 10193 5878 10194 5699 10194 5702 10194 5878 10195 5702 10195 5703 10195 5878 10196 5877 10196 5744 10196 5744 10197 5877 10197 5880 10197 5744 10198 5880 10198 5879 10198 230 10199 229 10199 5878 10199 5878 10200 229 10200 5881 10200 5878 10201 5881 10201 5882 10201 5882 10202 5883 10202 5878 10202 5878 10203 5883 10203 5884 10203 5878 10204 5884 10204 5876 10204 5885 10205 5886 10205 5887 10205 5888 10206 5889 10206 5886 10206 5888 10207 5890 10207 5889 10207 5889 10208 5890 10208 5891 10208 5889 10209 5891 10209 4520 10209 4520 10210 5891 10210 5511 10210 5892 10211 5893 10211 5894 10211 5894 10212 5895 10212 5892 10212 5892 10213 5895 10213 5896 10213 5892 10214 5896 10214 5897 10214 5897 10215 5896 10215 5898 10215 5897 10216 5898 10216 5899 10216 5900 10217 5901 10217 5902 10217 5902 10218 5901 10218 5903 10218 5888 10219 5904 10219 5890 10219 5890 10220 5904 10220 5905 10220 5890 10221 5905 10221 5891 10221 5891 10222 5905 10222 5512 10222 5891 10223 5512 10223 5511 10223 5514 10224 5513 10224 5906 10224 5902 10225 5894 10225 5900 10225 5900 10226 5894 10226 5893 10226 5900 10227 5893 10227 5907 10227 5907 10228 5893 10228 5892 10228 5907 10229 5892 10229 5908 10229 5908 10230 5892 10230 5897 10230 5908 10231 5897 10231 5909 10231 5909 10232 5897 10232 5910 10232 5909 10233 5910 10233 231 10233 5899 10234 226 10234 5897 10234 5897 10235 226 10235 225 10235 5897 10236 225 10236 5910 10236 5910 10237 225 10237 232 10237 5910 10238 232 10238 231 10238 5886 10239 5885 10239 5888 10239 5888 10240 5885 10240 5911 10240 5888 10241 5911 10241 5904 10241 5904 10242 5911 10242 5906 10242 5904 10243 5906 10243 5905 10243 5905 10244 5906 10244 5513 10244 5905 10245 5513 10245 5512 10245 231 10246 5510 10246 5909 10246 5909 10247 5510 10247 5515 10247 5909 10248 5515 10248 5908 10248 5908 10249 5515 10249 5514 10249 5908 10250 5514 10250 5907 10250 5907 10251 5514 10251 5906 10251 5907 10252 5906 10252 5900 10252 5900 10253 5906 10253 5911 10253 5900 10254 5911 10254 5901 10254 5901 10255 5911 10255 5885 10255 5901 10256 5885 10256 5903 10256 5903 10257 5885 10257 5887 10257 5912 10258 5913 10258 5914 10258 5707 10259 5706 10259 5915 10259 5916 10260 5917 10260 5918 10260 5919 10261 5920 10261 5921 10261 5921 10262 5920 10262 5922 10262 5648 10263 5919 10263 5649 10263 5649 10264 5919 10264 5921 10264 5649 10265 5921 10265 5650 10265 5650 10266 5921 10266 5660 10266 5922 10267 5923 10267 5921 10267 5921 10268 5923 10268 5924 10268 5921 10269 5924 10269 5660 10269 5660 10270 5924 10270 5925 10270 5660 10271 5925 10271 5655 10271 5926 10272 5647 10272 5646 10272 5927 10273 5928 10273 5929 10273 5929 10274 5928 10274 5930 10274 5929 10275 5930 10275 5926 10275 4526 10276 4525 10276 5931 10276 5931 10277 4525 10277 4534 10277 5931 10278 4534 10278 5929 10278 5929 10279 4534 10279 5932 10279 5929 10280 5932 10280 5927 10280 5926 10281 5646 10281 5929 10281 5929 10282 5646 10282 5655 10282 5929 10283 5655 10283 5931 10283 5931 10284 5655 10284 5925 10284 5931 10285 5925 10285 4526 10285 4526 10286 5925 10286 5924 10286 4526 10287 5924 10287 4542 10287 4542 10288 5924 10288 5933 10288 4542 10289 5933 10289 4546 10289 5913 10290 5708 10290 5914 10290 5914 10291 5708 10291 4552 10291 5914 10292 4552 10292 4551 10292 4549 10293 4548 10293 4551 10293 4551 10294 4548 10294 4547 10294 4551 10295 4547 10295 5914 10295 5914 10296 4547 10296 4543 10296 5914 10297 4543 10297 5934 10297 5934 10298 4543 10298 4545 10298 5934 10299 4545 10299 5935 10299 5707 10300 5915 10300 4560 10300 4560 10301 5915 10301 5936 10301 4560 10302 5936 10302 4561 10302 5937 10303 4564 10303 5938 10303 5938 10304 4564 10304 4563 10304 5938 10305 4563 10305 5939 10305 5939 10306 4563 10306 4562 10306 5940 10307 5941 10307 5938 10307 5938 10308 5941 10308 5942 10308 5938 10309 5942 10309 5937 10309 5836 10310 5838 10310 5943 10310 4561 10311 5936 10311 4562 10311 4562 10312 5936 10312 5944 10312 4562 10313 5944 10313 5939 10313 5939 10314 5944 10314 5836 10314 5939 10315 5836 10315 5938 10315 5938 10316 5836 10316 5943 10316 5938 10317 5943 10317 5940 10317 5828 10318 5820 10318 5945 10318 5820 10319 5819 10319 5945 10319 5945 10320 5819 10320 5857 10320 5945 10321 5857 10321 5936 10321 5936 10322 5857 10322 5862 10322 5936 10323 5862 10323 5944 10323 5944 10324 5862 10324 5837 10324 5944 10325 5837 10325 5836 10325 5945 10326 5946 10326 5947 10326 5828 10327 5945 10327 5948 10327 5948 10328 5945 10328 5947 10328 5948 10329 5947 10329 5949 10329 5946 10330 5945 10330 5950 10330 5950 10331 5945 10331 5936 10331 5950 10332 5936 10332 5951 10332 5951 10333 5936 10333 5915 10333 5951 10334 5915 10334 5912 10334 5912 10335 5915 10335 5706 10335 5912 10336 5706 10336 5913 10336 5913 10337 5706 10337 5705 10337 5913 10338 5705 10338 5708 10338 5917 10339 5916 10339 5935 10339 5935 10340 5916 10340 5952 10340 5935 10341 5952 10341 5934 10341 5934 10342 5952 10342 5953 10342 5934 10343 5953 10343 5914 10343 5914 10344 5953 10344 5954 10344 5914 10345 5954 10345 5912 10345 4545 10346 4546 10346 5935 10346 5935 10347 4546 10347 5933 10347 5935 10348 5933 10348 5917 10348 5917 10349 5933 10349 5924 10349 5917 10350 5924 10350 5918 10350 5918 10351 5924 10351 5923 10351 5955 10352 5692 10352 5738 10352 5738 10353 5692 10353 5701 10353 5738 10354 5701 10354 5700 10354 5695 10355 5956 10355 5696 10355 5696 10356 5956 10356 5957 10356 5696 10357 5957 10357 5697 10357 5958 10358 5957 10358 5959 10358 5959 10359 5957 10359 5956 10359 5959 10360 5956 10360 5960 10360 5960 10361 5956 10361 5695 10361 5960 10362 5695 10362 5955 10362 5955 10363 5695 10363 5694 10363 5955 10364 5694 10364 5692 10364 5716 10365 5715 10365 5961 10365 5961 10366 5715 10366 5962 10366 5961 10367 5962 10367 5963 10367 5963 10368 5962 10368 5964 10368 5963 10369 5964 10369 5965 10369 5965 10370 5964 10370 5966 10370 5965 10371 5966 10371 5967 10371 5967 10372 5966 10372 5968 10372 5967 10373 5968 10373 5958 10373 5958 10374 5968 10374 5957 10374 5715 10375 5584 10375 5962 10375 5962 10376 5584 10376 5969 10376 5962 10377 5969 10377 5964 10377 5964 10378 5969 10378 5970 10378 5964 10379 5970 10379 5966 10379 5966 10380 5970 10380 5971 10380 5966 10381 5971 10381 5968 10381 5968 10382 5971 10382 5972 10382 5968 10383 5972 10383 5957 10383 5957 10384 5972 10384 5697 10384 5716 10385 5973 10385 5714 10385 5714 10386 5974 10386 5710 10386 5710 10387 5974 10387 5975 10387 5710 10388 5975 10388 5711 10388 5716 10389 5976 10389 5973 10389 5973 10390 5976 10390 5977 10390 5973 10391 5977 10391 5978 10391 5714 10392 5973 10392 5974 10392 5974 10393 5973 10393 5978 10393 5974 10394 5978 10394 5975 10394 5975 10395 5978 10395 5979 10395 5975 10396 5979 10396 5980 10396 5981 10397 5982 10397 5983 10397 5982 10398 5981 10398 5984 10398 5984 10399 5981 10399 5985 10399 5984 10400 5985 10400 5986 10400 5986 10401 5985 10401 5987 10401 5986 10402 5987 10402 5988 10402 5988 10403 5987 10403 5989 10403 5988 10404 5989 10404 5990 10404 5991 10405 5992 10405 5993 10405 5993 10406 5992 10406 5994 10406 5993 10407 5994 10407 5989 10407 5989 10408 5994 10408 5995 10408 5989 10409 5995 10409 5990 10409 5991 10410 5993 10410 5996 10410 5996 10411 5993 10411 5997 10411 5996 10412 5997 10412 5998 10412 5998 10413 5997 10413 5999 10413 5998 10414 5999 10414 6000 10414 6000 10415 5999 10415 6001 10415 6000 10416 6001 10416 6002 10416 5736 10417 5711 10417 5975 10417 5980 10418 6002 10418 5975 10418 5975 10419 6002 10419 6001 10419 5975 10420 6001 10420 5736 10420 5736 10421 6001 10421 5999 10421 5736 10422 5999 10422 5759 10422 5759 10423 5999 10423 5997 10423 5759 10424 5997 10424 5758 10424 5758 10425 5997 10425 5993 10425 5758 10426 5993 10426 5756 10426 5756 10427 5993 10427 5989 10427 5756 10428 5989 10428 5754 10428 5754 10429 5989 10429 5987 10429 5754 10430 5987 10430 5752 10430 5752 10431 5987 10431 5985 10431 5752 10432 5985 10432 5750 10432 5750 10433 5985 10433 5981 10433 5750 10434 5981 10434 5748 10434 5748 10435 5981 10435 6003 10435 5748 10436 6003 10436 5746 10436 5746 10437 6003 10437 6004 10437 5746 10438 6004 10438 5745 10438 5745 10439 6004 10439 6005 10439 5745 10440 6005 10440 5737 10440 6006 10441 6007 10441 6008 10441 5738 10442 5737 10442 6008 10442 6008 10443 5737 10443 6005 10443 6008 10444 6005 10444 6006 10444 6006 10445 6005 10445 6004 10445 6006 10446 6004 10446 6009 10446 6009 10447 6004 10447 6003 10447 6009 10448 6003 10448 6010 10448 6010 10449 6003 10449 5981 10449 6010 10450 5981 10450 6011 10450 6011 10451 5981 10451 5983 10451 6011 10452 5983 10452 6012 10452 6013 10453 6014 10453 5718 10453 5718 10454 6014 10454 5720 10454 5720 10455 6014 10455 5722 10455 5722 10456 6014 10456 6015 10456 5722 10457 6015 10457 5724 10457 5724 10458 6015 10458 6016 10458 5724 10459 6016 10459 5726 10459 6017 10460 6018 10460 6019 10460 6020 10461 6021 10461 6018 10461 6018 10462 6017 10462 6020 10462 6020 10463 6017 10463 6022 10463 6020 10464 6022 10464 6023 10464 6023 10465 6022 10465 6024 10465 6024 10466 6022 10466 6025 10466 6024 10467 6025 10467 6026 10467 6026 10468 6025 10468 6027 10468 6026 10469 6027 10469 6028 10469 5718 10470 5597 10470 6013 10470 6013 10471 5597 10471 5743 10471 6013 10472 5743 10472 5757 10472 5755 10473 6028 10473 5757 10473 5757 10474 6028 10474 6027 10474 5757 10475 6027 10475 6013 10475 6013 10476 6027 10476 6025 10476 6013 10477 6025 10477 6014 10477 6014 10478 6025 10478 6022 10478 6014 10479 6022 10479 6015 10479 6015 10480 6022 10480 6017 10480 6015 10481 6017 10481 6016 10481 6016 10482 6017 10482 6019 10482 6016 10483 6019 10483 5726 10483 5726 10484 6019 10484 5735 10484 6029 10485 5753 10485 5751 10485 6030 10486 6031 10486 6021 10486 6032 10487 6033 10487 6034 10487 5755 10488 5753 10488 6028 10488 6028 10489 5753 10489 6029 10489 6028 10490 6029 10490 6026 10490 6026 10491 6029 10491 6035 10491 6026 10492 6035 10492 6024 10492 6024 10493 6035 10493 6036 10493 6024 10494 6036 10494 6023 10494 6023 10495 6036 10495 6030 10495 6023 10496 6030 10496 6020 10496 6020 10497 6030 10497 6021 10497 5749 10498 6037 10498 5751 10498 5751 10499 6037 10499 6038 10499 5751 10500 6038 10500 6029 10500 6029 10501 6038 10501 6039 10501 6029 10502 6039 10502 6035 10502 6035 10503 6039 10503 6040 10503 6035 10504 6040 10504 6036 10504 6036 10505 6040 10505 6032 10505 6036 10506 6032 10506 6030 10506 6030 10507 6032 10507 6034 10507 6030 10508 6034 10508 6031 10508 6041 10509 6033 10509 6042 10509 6042 10510 6033 10510 6032 10510 6042 10511 6032 10511 6043 10511 6043 10512 6032 10512 6040 10512 6043 10513 6040 10513 6044 10513 6044 10514 6040 10514 6039 10514 6044 10515 6039 10515 6045 10515 6045 10516 6039 10516 6038 10516 6045 10517 6038 10517 6046 10517 6046 10518 6038 10518 6037 10518 6047 10519 5747 10519 5739 10519 5749 10520 5747 10520 6037 10520 6037 10521 5747 10521 6047 10521 6037 10522 6047 10522 6046 10522 6046 10523 6047 10523 6048 10523 6046 10524 6048 10524 6045 10524 6045 10525 6048 10525 6049 10525 6045 10526 6049 10526 6044 10526 6044 10527 6049 10527 6043 10527 6043 10528 6049 10528 6050 10528 6043 10529 6050 10529 6042 10529 6051 10530 6052 10530 6053 10530 6054 10531 6052 10531 6055 10531 6055 10532 6052 10532 6051 10532 6055 10533 6051 10533 6056 10533 5741 10534 6057 10534 6058 10534 6058 10535 6057 10535 6059 10535 6058 10536 6059 10536 6060 10536 6060 10537 6059 10537 6061 10537 6060 10538 6061 10538 6056 10538 6056 10539 6061 10539 6062 10539 6056 10540 6062 10540 6055 10540 6041 10541 6042 10541 6053 10541 6053 10542 6042 10542 6050 10542 6053 10543 6050 10543 6051 10543 6051 10544 6050 10544 6049 10544 6051 10545 6049 10545 6056 10545 6056 10546 6049 10546 6048 10546 6056 10547 6048 10547 6060 10547 6060 10548 6048 10548 6047 10548 6060 10549 6047 10549 6058 10549 6058 10550 6047 10550 5739 10550 6058 10551 5739 10551 5741 10551 5928 10552 6063 10552 5930 10552 4535 10553 6064 10553 6065 10553 5647 10554 6066 10554 5800 10554 5800 10555 6066 10555 6067 10555 5800 10556 6067 10556 5784 10556 5784 10557 6067 10557 5785 10557 5785 10558 6067 10558 6068 10558 5785 10559 6068 10559 5792 10559 4538 10560 5814 10560 4532 10560 4535 10561 6065 10561 4539 10561 4539 10562 6065 10562 6069 10562 4539 10563 6069 10563 4540 10563 6070 10564 6071 10564 4541 10564 4541 10565 6071 10565 5932 10565 4541 10566 5932 10566 4534 10566 5647 10567 5926 10567 6066 10567 6066 10568 5926 10568 6072 10568 6066 10569 6072 10569 6067 10569 6067 10570 6072 10570 6073 10570 6067 10571 6073 10571 6068 10571 5793 10572 5792 10572 5809 10572 5809 10573 5792 10573 6068 10573 5809 10574 6068 10574 5816 10574 5816 10575 6068 10575 6073 10575 5816 10576 6073 10576 5814 10576 5814 10577 6073 10577 6074 10577 5814 10578 6074 10578 4532 10578 4532 10579 6074 10579 4533 10579 5926 10580 5930 10580 6072 10580 6072 10581 5930 10581 6063 10581 6072 10582 6063 10582 6070 10582 6070 10583 6063 10583 5928 10583 6070 10584 5928 10584 6071 10584 6071 10585 5928 10585 5927 10585 6071 10586 5927 10586 5932 10586 4541 10587 4540 10587 6070 10587 6070 10588 4540 10588 6069 10588 6070 10589 6069 10589 6072 10589 6072 10590 6069 10590 6065 10590 6072 10591 6065 10591 6073 10591 6073 10592 6065 10592 6064 10592 6073 10593 6064 10593 6074 10593 6074 10594 6064 10594 4535 10594 6074 10595 4535 10595 4533 10595 6075 10596 6076 10596 6077 10596 6077 10597 6076 10597 6078 10597 6077 10598 6078 10598 6079 10598 6075 10599 6077 10599 6080 10599 6080 10600 6077 10600 6081 10600 6080 10601 6081 10601 6082 10601 4554 10602 6083 10602 4555 10602 4555 10603 6083 10603 6084 10603 4555 10604 6084 10604 4557 10604 4557 10605 6084 10605 4558 10605 4558 10606 6084 10606 6085 10606 4558 10607 6085 10607 4559 10607 4516 10608 4559 10608 4518 10608 4518 10609 4559 10609 6085 10609 4518 10610 6085 10610 4519 10610 4519 10611 6085 10611 4522 10611 5889 10612 6086 10612 5886 10612 5886 10613 6086 10613 6078 10613 5886 10614 6078 10614 5887 10614 5887 10615 6078 10615 6076 10615 4554 10616 6087 10616 6083 10616 6083 10617 6087 10617 6079 10617 6083 10618 6079 10618 6084 10618 6084 10619 6079 10619 6078 10619 6084 10620 6078 10620 6085 10620 6085 10621 6078 10621 6086 10621 6085 10622 6086 10622 4522 10622 4522 10623 6086 10623 5889 10623 4522 10624 5889 10624 4520 10624 5848 10625 6088 10625 5850 10625 5899 10626 5845 10626 226 10626 5903 10627 5887 10627 6076 10627 6089 10628 5894 10628 6090 10628 6090 10629 5894 10629 5902 10629 6090 10630 5902 10630 6091 10630 6091 10631 5902 10631 5903 10631 6091 10632 5903 10632 6092 10632 6092 10633 5903 10633 6076 10633 6092 10634 6076 10634 6075 10634 5898 10635 5896 10635 6089 10635 6089 10636 5896 10636 5895 10636 6089 10637 5895 10637 5894 10637 5899 10638 5898 10638 5845 10638 5845 10639 5898 10639 6089 10639 5845 10640 6089 10640 5846 10640 5846 10641 6089 10641 5848 10641 6088 10642 6093 10642 5850 10642 5850 10643 6093 10643 6094 10643 5850 10644 6094 10644 5851 10644 5851 10645 6094 10645 6095 10645 5840 10646 5844 10646 6095 10646 6095 10647 5844 10647 5843 10647 6095 10648 5843 10648 5851 10648 6095 10649 6096 10649 5840 10649 5840 10650 6096 10650 6097 10650 5840 10651 6097 10651 5839 10651 5838 10652 5839 10652 6098 10652 6098 10653 5839 10653 6097 10653 6098 10654 6097 10654 6099 10654 6099 10655 6097 10655 6100 10655 6082 10656 6081 10656 6101 10656 6101 10657 6081 10657 6102 10657 6103 10658 6104 10658 6105 10658 6105 10659 6104 10659 6106 10659 6105 10660 6106 10660 6107 10660 6107 10661 6106 10661 6108 10661 6107 10662 6108 10662 6109 10662 6109 10663 6108 10663 6110 10663 6109 10664 6110 10664 6111 10664 6112 10665 6100 10665 6111 10665 6111 10666 6100 10666 6097 10666 6111 10667 6097 10667 6109 10667 6109 10668 6097 10668 6096 10668 6109 10669 6096 10669 6107 10669 6107 10670 6096 10670 6095 10670 6107 10671 6095 10671 6105 10671 6105 10672 6095 10672 6094 10672 6105 10673 6094 10673 6103 10673 6103 10674 6094 10674 6093 10674 5848 10675 6089 10675 6088 10675 6088 10676 6089 10676 6090 10676 6088 10677 6090 10677 6093 10677 6093 10678 6090 10678 6091 10678 6093 10679 6091 10679 6103 10679 6103 10680 6091 10680 6092 10680 6103 10681 6092 10681 6104 10681 6104 10682 6092 10682 6075 10682 6104 10683 6075 10683 6106 10683 6106 10684 6075 10684 6080 10684 6106 10685 6080 10685 6108 10685 6108 10686 6080 10686 6082 10686 6108 10687 6082 10687 6110 10687 6110 10688 6082 10688 6101 10688 6110 10689 6101 10689 6111 10689 6111 10690 6101 10690 6102 10690 6111 10691 6102 10691 6112 10691 6113 10692 6114 10692 6115 10692 6113 10693 6116 10693 6117 10693 6118 10694 6119 10694 6120 10694 6121 10695 6122 10695 5876 10695 5881 10696 229 10696 5871 10696 6118 10697 6120 10697 6123 10697 6115 10698 5873 10698 5872 10698 6113 10699 6115 10699 6124 10699 6124 10700 6115 10700 5872 10700 6124 10701 5872 10701 5875 10701 5883 10702 5882 10702 6125 10702 6125 10703 5882 10703 5881 10703 6125 10704 5881 10704 6126 10704 6126 10705 5881 10705 5871 10705 6126 10706 5871 10706 6127 10706 6127 10707 5871 10707 5874 10707 6113 10708 6117 10708 6114 10708 6114 10709 6117 10709 6128 10709 6114 10710 6128 10710 6115 10710 6129 10711 6130 10711 6131 10711 6131 10712 6130 10712 6132 10712 6131 10713 6132 10713 6133 10713 6133 10714 6132 10714 6134 10714 6133 10715 6134 10715 6120 10715 6120 10716 6134 10716 6135 10716 6120 10717 6135 10717 6123 10717 5876 10718 5884 10718 6121 10718 6121 10719 5884 10719 5883 10719 6121 10720 5883 10720 6136 10720 6136 10721 5883 10721 6125 10721 6136 10722 6125 10722 6137 10722 6137 10723 6125 10723 6126 10723 6137 10724 6126 10724 6128 10724 6128 10725 6126 10725 6127 10725 6128 10726 6127 10726 6115 10726 6115 10727 6127 10727 5874 10727 6115 10728 5874 10728 5873 10728 5880 10729 5877 10729 6138 10729 6138 10730 5877 10730 5876 10730 6138 10731 5876 10731 6139 10731 6139 10732 5876 10732 6122 10732 6139 10733 6122 10733 6140 10733 6140 10734 6122 10734 6121 10734 6140 10735 6121 10735 6129 10735 6129 10736 6121 10736 6136 10736 6129 10737 6136 10737 6130 10737 6130 10738 6136 10738 6137 10738 6130 10739 6137 10739 6132 10739 6132 10740 6137 10740 6128 10740 6132 10741 6128 10741 6134 10741 6134 10742 6128 10742 6117 10742 6134 10743 6117 10743 6135 10743 6135 10744 6117 10744 6116 10744 6135 10745 6116 10745 6123 10745 6123 10746 6116 10746 6113 10746 6141 10747 5879 10747 5880 10747 6057 10748 5741 10748 5879 10748 5880 10749 6138 10749 6141 10749 6141 10750 6138 10750 6139 10750 6141 10751 6139 10751 6142 10751 6119 10752 6143 10752 6120 10752 6120 10753 6143 10753 6144 10753 6120 10754 6144 10754 6133 10754 6133 10755 6144 10755 6145 10755 6133 10756 6145 10756 6131 10756 6131 10757 6145 10757 6146 10757 6131 10758 6146 10758 6129 10758 6129 10759 6146 10759 6142 10759 6129 10760 6142 10760 6140 10760 6140 10761 6142 10761 6139 10761 5879 10762 6141 10762 6057 10762 6057 10763 6141 10763 6142 10763 6057 10764 6142 10764 6059 10764 6059 10765 6142 10765 6146 10765 6059 10766 6146 10766 6061 10766 6061 10767 6146 10767 6145 10767 6061 10768 6145 10768 6062 10768 6062 10769 6145 10769 6144 10769 6062 10770 6144 10770 6055 10770 6055 10771 6144 10771 6143 10771 6055 10772 6143 10772 6054 10772 5950 10773 6147 10773 5946 10773 5946 10774 6147 10774 6148 10774 5946 10775 6148 10775 5947 10775 6149 10776 5949 10776 5947 10776 5947 10777 6148 10777 6149 10777 6149 10778 6148 10778 6150 10778 6149 10779 6150 10779 6151 10779 5950 10780 6152 10780 6147 10780 6147 10781 6152 10781 6153 10781 6147 10782 6153 10782 6148 10782 6148 10783 6153 10783 6154 10783 6148 10784 6154 10784 6150 10784 6155 10785 6156 10785 6157 10785 6157 10786 6156 10786 6158 10786 6157 10787 6158 10787 6152 10787 6152 10788 6158 10788 6159 10788 6152 10789 6159 10789 6153 10789 6155 10790 6157 10790 6160 10790 6160 10791 6157 10791 6161 10791 6160 10792 6161 10792 6162 10792 6162 10793 6161 10793 6163 10793 6162 10794 6163 10794 6164 10794 6164 10795 6163 10795 6165 10795 6164 10796 6165 10796 6166 10796 6166 10797 6165 10797 6167 10797 6166 10798 6167 10798 6168 10798 6169 10799 6170 10799 6171 10799 6171 10800 6170 10800 6172 10800 6171 10801 6172 10801 6173 10801 5920 10802 6172 10802 5922 10802 5922 10803 6172 10803 6170 10803 5922 10804 6170 10804 6167 10804 6167 10805 6170 10805 6169 10805 6167 10806 6169 10806 6168 10806 6163 10807 5916 10807 6165 10807 6165 10808 5916 10808 5918 10808 6165 10809 5918 10809 6167 10809 6167 10810 5918 10810 5923 10810 6167 10811 5923 10811 5922 10811 5950 10812 5951 10812 6152 10812 6152 10813 5951 10813 5912 10813 6152 10814 5912 10814 6157 10814 6157 10815 5912 10815 5954 10815 6157 10816 5954 10816 6161 10816 6161 10817 5954 10817 5953 10817 6161 10818 5953 10818 6163 10818 6163 10819 5953 10819 5952 10819 6163 10820 5952 10820 5916 10820 6174 632 6175 632 6012 632 6012 632 6175 632 6176 632 6012 10821 6176 10821 6177 10821 5992 10822 5991 10822 5994 10822 5994 10823 5991 10823 5995 10823 6002 10824 5980 10824 6012 10824 6012 10825 5980 10825 5979 10825 6012 10826 5979 10826 5978 10826 6012 10827 6007 10827 6006 10827 5991 10828 6012 10828 5983 10828 6000 632 6002 632 5998 632 5998 632 6002 632 6012 632 5998 632 6012 632 5996 632 5996 10829 6012 10829 5991 10829 6178 632 6012 632 6179 632 6179 10830 6012 10830 6177 10830 6179 10831 6177 10831 6180 10831 5986 10832 5988 10832 5991 10832 5991 10833 5988 10833 5990 10833 5991 10834 5990 10834 5995 10834 6178 632 6181 632 6012 632 6012 632 6181 632 6182 632 6012 10835 6182 10835 6183 10835 6009 632 6010 632 6006 632 6006 10836 6010 10836 6011 10836 6006 10837 6011 10837 6012 10837 5983 10838 5982 10838 5991 10838 5991 10839 5982 10839 5984 10839 5991 10840 5984 10840 5986 10840 5978 632 5977 632 6012 632 6012 10841 5977 10841 5976 10841 6012 10842 5976 10842 6174 10842 6183 632 6184 632 6012 632 6012 10843 6184 10843 6185 10843 6012 632 6185 632 6007 632 6183 10844 6182 10844 5958 10844 6186 10845 6185 10845 6184 10845 6007 10846 6185 10846 6008 10846 6008 10847 6185 10847 6186 10847 6008 10848 6186 10848 5738 10848 5738 10849 6186 10849 5955 10849 6183 10850 5958 10850 6184 10850 6184 10851 5958 10851 5959 10851 6184 10852 5959 10852 6186 10852 6186 10853 5959 10853 5960 10853 6186 10854 5960 10854 5955 10854 6177 10855 6176 10855 6175 10855 5967 10856 5958 10856 6182 10856 6182 10857 6181 10857 5967 10857 5967 10858 6181 10858 6178 10858 5967 10859 6178 10859 5965 10859 6178 10860 6179 10860 5965 10860 5965 10861 6179 10861 6180 10861 5965 10862 6180 10862 5963 10862 5963 10863 6180 10863 6177 10863 6177 10864 6175 10864 5963 10864 5963 10865 6175 10865 6174 10865 5963 10866 6174 10866 5961 10866 5961 10867 6174 10867 5976 10867 5961 10868 5976 10868 5716 10868 6187 10869 6188 10869 6189 10869 6190 10870 6191 10870 6018 10870 5733 10871 5734 10871 6192 10871 6192 10872 5734 10872 5735 10872 5735 10873 6019 10873 6192 10873 6192 10874 6019 10874 6018 10874 6192 10875 6018 10875 6193 10875 6187 10876 6018 10876 6194 10876 6194 10877 6018 10877 6021 10877 6194 10878 6021 10878 6195 10878 6187 10879 6189 10879 6018 10879 6018 10880 6189 10880 6196 10880 6018 10881 6196 10881 6190 10881 6191 10882 6197 10882 6018 10882 6018 10883 6197 10883 6198 10883 6018 10884 6198 10884 6193 10884 6041 10885 6199 10885 6033 10885 6033 10886 6199 10886 6034 10886 6195 10887 6021 10887 6031 10887 6195 10888 6031 10888 6200 10888 6200 10889 6031 10889 6034 10889 6200 10890 6034 10890 6201 10890 6201 10891 6034 10891 6199 10891 6052 10892 6054 10892 6202 10892 6202 10893 6054 10893 6143 10893 6202 10894 6143 10894 6119 10894 6052 10895 6202 10895 6053 10895 6053 10896 6202 10896 6203 10896 6053 10897 6203 10897 6204 10897 6205 10898 6206 10898 6207 10898 6207 10899 6206 10899 6203 10899 6207 10900 6203 10900 6208 10900 6208 10901 6203 10901 6202 10901 6201 10902 6199 10902 6209 10902 6209 10903 6199 10903 6041 10903 6209 10904 6041 10904 6210 10904 6210 10905 6041 10905 6053 10905 6210 10906 6053 10906 6211 10906 6211 10907 6053 10907 6204 10907 6212 10908 6213 10908 6214 10908 6173 10909 6215 10909 6216 10909 6217 10910 6172 10910 5920 10910 6216 10911 6218 10911 6219 10911 6173 10912 6216 10912 6220 10912 6220 10913 6216 10913 6219 10913 6220 10914 6219 10914 6221 10914 5920 10915 6222 10915 6217 10915 6217 10916 6222 10916 6223 10916 6217 10917 6223 10917 6213 10917 6213 10918 6223 10918 6224 10918 6213 10919 6224 10919 6214 10919 6173 10920 6172 10920 6215 10920 6215 10921 6172 10921 6217 10921 6215 10922 6217 10922 6216 10922 6216 10923 6217 10923 6213 10923 6216 10924 6213 10924 6218 10924 6218 10925 6213 10925 6212 10925 4568 10926 4570 10926 6225 10926 6112 10927 6102 10927 6226 10927 6112 10928 6226 10928 6100 10928 5940 10929 5943 10929 6227 10929 5943 10930 5838 10930 6098 10930 4569 10931 4567 10931 6228 10931 6228 10932 4567 10932 4566 10932 5941 10933 6229 10933 5942 10933 5942 10934 6229 10934 6228 10934 5942 10935 6228 10935 5937 10935 5937 10936 6228 10936 4566 10936 5937 10937 4566 10937 4564 10937 4554 10938 4565 10938 6230 10938 4565 10939 4568 10939 6230 10939 6230 10940 4568 10940 6225 10940 6230 10941 6225 10941 6231 10941 6231 10942 6225 10942 6232 10942 6231 10943 6232 10943 6226 10943 6226 10944 6232 10944 6227 10944 6226 10945 6227 10945 6100 10945 6100 10946 6227 10946 5943 10946 6100 10947 5943 10947 6099 10947 6099 10948 5943 10948 6098 10948 4570 10949 4569 10949 6225 10949 6225 10950 4569 10950 6228 10950 6225 10951 6228 10951 6232 10951 6232 10952 6228 10952 6229 10952 6232 10953 6229 10953 6227 10953 6227 10954 6229 10954 5941 10954 6227 10955 5941 10955 5940 10955 4554 10956 6230 10956 6087 10956 6087 10957 6230 10957 6231 10957 6087 10958 6231 10958 6079 10958 6079 10959 6231 10959 6226 10959 6079 10960 6226 10960 6077 10960 6077 10961 6226 10961 6102 10961 6077 10962 6102 10962 6081 10962 6233 10963 6190 10963 6234 10963 6234 10964 6190 10964 6196 10964 6234 10965 6196 10965 6221 10965 6221 10966 6196 10966 6235 10966 6233 10967 6234 10967 6236 10967 6237 10968 6238 10968 6239 10968 6191 10969 6190 10969 6233 10969 6197 10970 6240 10970 6241 10970 6242 10971 6243 10971 6236 10971 6242 10972 6219 10972 6244 10972 6244 10973 6219 10973 6218 10973 6244 10974 6218 10974 6212 10974 6242 10975 6236 10975 6219 10975 6219 10976 6236 10976 6234 10976 6219 10977 6234 10977 6221 10977 6197 10978 6241 10978 6198 10978 6198 10979 6241 10979 6245 10979 6198 10980 6245 10980 6193 10980 6240 10981 6197 10981 6246 10981 6246 10982 6197 10982 6191 10982 6246 10983 6191 10983 6247 10983 6243 10984 6239 10984 6236 10984 6236 10985 6239 10985 6238 10985 6236 10986 6238 10986 6233 10986 6233 10987 6238 10987 6237 10987 6233 10988 6237 10988 6191 10988 6191 10989 6237 10989 6248 10989 6191 10990 6248 10990 6247 10990 6249 10991 6250 10991 6251 10991 6252 10992 6253 10992 6254 10992 6254 10993 6253 10993 6255 10993 6254 10994 6255 10994 6256 10994 6250 10995 6257 10995 6251 10995 6251 10996 6257 10996 6252 10996 6251 10997 6252 10997 6258 10997 6258 10998 6252 10998 6254 10998 6258 10999 6254 10999 6259 10999 6260 11000 6261 11000 6262 11000 6208 11001 6263 11001 6207 11001 6207 11002 6263 11002 6264 11002 6207 11003 6264 11003 6205 11003 6205 11004 6264 11004 6260 11004 6205 11005 6260 11005 6206 11005 6206 11006 6260 11006 6262 11006 6261 11007 6249 11007 6262 11007 6262 11008 6249 11008 6251 11008 6262 11009 6251 11009 6265 11009 6265 11010 6251 11010 6258 11010 6265 11011 6258 11011 6266 11011 6266 11012 6258 11012 6259 11012 6266 11013 6259 11013 6267 11013 6203 11014 6206 11014 6262 11014 6267 11015 6268 11015 6266 11015 6266 11016 6268 11016 6203 11016 6266 11017 6203 11017 6265 11017 6265 11018 6203 11018 6262 11018 6269 11019 6270 11019 6271 11019 6272 11020 5949 11020 6149 11020 6259 11021 6273 11021 6267 11021 6267 11022 6273 11022 6274 11022 6267 11023 6274 11023 6275 11023 6275 11024 6274 11024 6149 11024 6275 11025 6149 11025 6151 11025 6254 11026 6256 11026 6276 11026 6276 11027 6256 11027 6277 11027 6276 11028 6277 11028 6271 11028 6271 11029 6277 11029 6278 11029 6271 11030 6278 11030 6269 11030 6259 11031 6254 11031 6273 11031 6273 11032 6254 11032 6276 11032 6273 11033 6276 11033 6274 11033 6274 11034 6276 11034 6271 11034 6274 11035 6271 11035 6149 11035 6149 11036 6271 11036 6270 11036 6149 11037 6270 11037 6272 11037 6223 11038 6279 11038 6224 11038 6280 11039 6281 11039 6282 11039 6283 11040 6284 11040 6285 11040 6243 11041 6242 11041 6286 11041 6286 11042 6242 11042 6244 11042 6286 11043 6244 11043 6287 11043 6287 11044 6244 11044 6212 11044 6288 11045 6289 11045 6290 11045 6290 11046 6289 11046 6247 11046 6247 11047 6248 11047 6290 11047 6290 11048 6248 11048 6237 11048 6290 11049 6237 11049 6239 11049 6245 11050 6241 11050 6288 11050 6288 11051 6241 11051 6240 11051 6288 11052 6240 11052 6289 11052 6289 11053 6240 11053 6246 11053 6289 11054 6246 11054 6247 11054 6288 11055 6291 11055 6292 11055 6245 11056 6288 11056 6193 11056 6193 11057 6288 11057 6292 11057 6193 11058 6292 11058 6192 11058 6293 11059 6294 11059 6295 11059 6295 11060 6294 11060 6296 11060 6295 11061 6296 11061 6297 11061 6297 11062 6296 11062 6285 11062 6284 11063 6298 11063 6285 11063 6285 11064 6298 11064 5607 11064 6285 11065 5607 11065 6297 11065 6299 11066 6300 11066 6301 11066 6301 11067 6300 11067 6302 11067 6280 11068 6282 11068 6303 11068 6222 11069 5920 11069 6304 11069 6304 11070 5920 11070 5919 11070 6304 11071 5919 11071 6305 11071 6305 11072 5919 11072 5648 11072 6305 11073 5648 11073 6306 11073 6279 11074 6223 11074 6307 11074 6223 11075 6222 11075 6307 11075 6307 11076 6222 11076 6304 11076 6307 11077 6304 11077 6282 11077 6282 11078 6304 11078 6305 11078 6282 11079 6305 11079 6303 11079 6303 11080 6305 11080 6306 11080 6212 11081 6214 11081 6287 11081 6287 11082 6214 11082 6308 11082 6287 11083 6308 11083 6286 11083 6286 11084 6308 11084 6290 11084 6286 11085 6290 11085 6243 11085 6243 11086 6290 11086 6239 11086 6281 11087 6309 11087 6282 11087 6282 11088 6309 11088 6299 11088 6282 11089 6299 11089 6307 11089 6307 11090 6299 11090 6301 11090 6307 11091 6301 11091 6279 11091 6279 11092 6301 11092 6308 11092 6279 11093 6308 11093 6224 11093 6224 11094 6308 11094 6214 11094 6302 11095 6283 11095 6301 11095 6301 11096 6283 11096 6285 11096 6301 11097 6285 11097 6308 11097 6308 11098 6285 11098 6296 11098 6308 11099 6296 11099 6290 11099 6290 11100 6296 11100 6294 11100 6290 11101 6294 11101 6288 11101 6288 11102 6294 11102 6293 11102 6288 11103 6293 11103 6291 11103 6310 11104 6311 11104 6312 11104 5948 11105 6313 11105 5828 11105 6269 11106 6278 11106 6314 11106 6315 11107 6316 11107 6317 11107 6317 11108 6318 11108 6315 11108 6315 11109 6318 11109 6319 11109 6315 11110 6319 11110 6320 11110 6320 11111 6319 11111 6261 11111 6261 11112 6260 11112 6320 11112 6320 11113 6260 11113 6264 11113 6320 11114 6264 11114 6321 11114 6264 11115 6263 11115 6321 11115 6321 11116 6263 11116 6208 11116 6321 11117 6208 11117 6202 11117 6255 11118 6253 11118 6318 11118 6318 11119 6253 11119 6252 11119 6252 11120 6257 11120 6318 11120 6318 11121 6257 11121 6250 11121 6318 11122 6250 11122 6319 11122 6319 11123 6250 11123 6249 11123 6319 11124 6249 11124 6261 11124 6317 11125 6322 11125 6318 11125 6318 11126 6322 11126 6323 11126 6318 11127 6323 11127 6255 11127 6255 11128 6323 11128 6324 11128 6255 11129 6324 11129 6256 11129 6256 11130 6324 11130 6314 11130 6256 11131 6314 11131 6277 11131 6277 11132 6314 11132 6278 11132 6313 11133 5948 11133 6325 11133 6326 11134 6327 11134 6325 11134 6325 11135 6327 11135 6328 11135 6325 11136 6328 11136 6313 11136 6313 11137 6328 11137 6329 11137 6313 11138 6329 11138 5828 11138 6310 11139 6326 11139 6311 11139 6311 11140 6326 11140 6325 11140 6311 11141 6325 11141 6272 11141 6272 11142 6325 11142 5948 11142 6272 11143 5948 11143 5949 11143 6330 11144 6331 11144 6332 11144 6332 11145 6331 11145 6333 11145 6332 11146 6333 11146 6334 11146 6334 11147 6333 11147 6335 11147 6334 11148 6335 11148 6336 11148 6336 11149 6335 11149 6337 11149 6336 11150 6337 11150 6338 11150 6338 11151 6337 11151 6339 11151 6338 11152 6339 11152 6312 11152 6312 11153 6339 11153 6340 11153 6312 11154 6340 11154 6310 11154 6272 11155 6270 11155 6311 11155 6311 11156 6270 11156 6269 11156 6311 11157 6269 11157 6312 11157 6312 11158 6269 11158 6314 11158 6312 11159 6314 11159 6338 11159 6338 11160 6314 11160 6324 11160 6338 11161 6324 11161 6336 11161 6336 11162 6324 11162 6323 11162 6336 11163 6323 11163 6334 11163 6334 11164 6323 11164 6322 11164 6334 11165 6322 11165 6332 11165 6332 11166 6322 11166 6317 11166 6332 11167 6317 11167 6330 11167 6330 11168 6317 11168 6316 11168 6330 11169 6316 11169 5865 11169 6341 11170 6342 11170 4577 11170 6343 95 4573 95 6342 95 6342 95 4573 95 4575 95 6342 95 4575 95 4577 95 4577 95 4580 95 6341 95 6341 11171 4580 11171 6344 11171 6341 11172 6344 11172 6345 11172 6345 95 6344 95 6346 95 6345 11173 6346 11173 6347 11173 6347 95 6346 95 6348 95 6347 11174 6348 11174 6349 11174 6349 95 6348 95 6350 95 6349 95 6350 95 6351 95 6351 11175 6350 11175 6352 11175 6351 95 6352 95 6353 95 6353 95 6352 95 6354 95 6353 95 6354 95 6355 95 6355 95 6354 95 6356 95 6355 95 6356 95 6357 95 6357 95 6356 95 6358 95 6357 95 6358 95 6359 95 6359 95 6358 95 6360 95 6359 95 6360 95 6361 95 6361 95 6360 95 6362 95 6361 95 6362 95 6343 95 6343 11176 6362 11176 4571 11176 6343 11177 4571 11177 4573 11177 6192 11178 6292 11178 5733 11178 5733 11179 6292 11179 6291 11179 5733 11180 6291 11180 5764 11180 5764 11181 6291 11181 6293 11181 5764 11182 6293 11182 5765 11182 5765 11183 6293 11183 5774 11183 5774 11184 6293 11184 6295 11184 5774 11185 6295 11185 6297 11185 5607 11186 5606 11186 6297 11186 6297 11187 5606 11187 5611 11187 5611 11188 5772 11188 6297 11188 6297 11189 5772 11189 5773 11189 6297 11190 5773 11190 5774 11190 6298 11191 6363 11191 6364 11191 6299 11192 6309 11192 6365 11192 5626 11193 124 11193 128 11193 5626 11194 128 11194 5627 11194 128 11195 6366 11195 5627 11195 5627 11196 6366 11196 6367 11196 5627 11197 6367 11197 5629 11197 5629 11198 6367 11198 6368 11198 5629 11199 6368 11199 5630 11199 5630 11200 6368 11200 5624 11200 5624 11201 6368 11201 5625 11201 5625 11202 6368 11202 6369 11202 5625 11203 6369 11203 5617 11203 5617 11204 6369 11204 6370 11204 5617 11205 6370 11205 5619 11205 6280 11206 6303 11206 6371 11206 6371 11207 6303 11207 6306 11207 5619 11208 6370 11208 5621 11208 5621 11209 6370 11209 6371 11209 5621 11210 6371 11210 5622 11210 5622 11211 6371 11211 6306 11211 5622 11212 6306 11212 5648 11212 6280 11213 6371 11213 6281 11213 6281 11214 6371 11214 6370 11214 6281 11215 6370 11215 6309 11215 6299 11216 6365 11216 6300 11216 6298 11217 6284 11217 6363 11217 6363 11218 6284 11218 6283 11218 6363 11219 6283 11219 6365 11219 6365 11220 6283 11220 6302 11220 6365 11221 6302 11221 6300 11221 6372 11222 5601 11222 6373 11222 6373 11223 5601 11223 5605 11223 6373 11224 5605 11224 6364 11224 6364 11225 5605 11225 5607 11225 6364 11226 5607 11226 6298 11226 6309 11227 6370 11227 6365 11227 6365 11228 6370 11228 6369 11228 6365 11229 6369 11229 6363 11229 6363 11230 6369 11230 6368 11230 6363 11231 6368 11231 6364 11231 6364 11232 6368 11232 6367 11232 6364 11233 6367 11233 6373 11233 6373 11234 6367 11234 6366 11234 6373 11235 6366 11235 6372 11235 6372 11236 6366 11236 128 11236 6372 11237 128 11237 5601 11237 5601 11238 128 11238 129 11238 5601 11239 129 11239 130 11239 6329 11240 6328 11240 6374 11240 6337 11241 6375 11241 6339 11241 6376 11242 244 11242 245 11242 5867 11243 228 11243 244 11243 6330 11244 6377 11244 6331 11244 6331 11245 6377 11245 6378 11245 6331 11246 6378 11246 6333 11246 244 11247 6376 11247 5867 11247 5867 11248 6376 11248 6379 11248 5867 11249 6379 11249 5869 11249 5869 11250 6379 11250 6377 11250 5869 11251 6377 11251 5866 11251 5866 11252 6377 11252 6330 11252 5866 11253 6330 11253 5865 11253 6375 11254 6337 11254 6378 11254 6378 11255 6337 11255 6335 11255 6378 11256 6335 11256 6333 11256 6328 11257 6327 11257 6374 11257 6374 11258 6327 11258 6326 11258 6374 11259 6326 11259 6380 11259 6380 11260 6326 11260 6310 11260 6380 11261 6310 11261 6340 11261 6381 11262 5833 11262 6380 11262 6380 11263 5833 11263 5831 11263 6380 11264 5831 11264 6374 11264 6374 11265 5831 11265 5830 11265 6374 11266 5830 11266 6329 11266 6329 11267 5830 11267 5829 11267 6329 11268 5829 11268 5828 11268 6382 11269 5826 11269 6381 11269 6381 11270 5826 11270 5834 11270 6381 11271 5834 11271 5833 11271 6383 11272 5823 11272 6384 11272 6384 11273 5823 11273 5824 11273 6384 11274 5824 11274 6382 11274 6382 11275 5824 11275 5827 11275 6382 11276 5827 11276 5826 11276 246 11277 5823 11277 245 11277 245 11278 5823 11278 6383 11278 245 11279 6383 11279 6376 11279 6376 11280 6383 11280 6384 11280 6376 11281 6384 11281 6379 11281 6379 11282 6384 11282 6382 11282 6379 11283 6382 11283 6377 11283 6377 11284 6382 11284 6381 11284 6377 11285 6381 11285 6378 11285 6378 11286 6381 11286 6380 11286 6378 11287 6380 11287 6375 11287 6375 11288 6380 11288 6340 11288 6375 11289 6340 11289 6339 11289 6119 11290 6118 11290 6315 11290 6315 11291 6320 11291 6119 11291 6119 11292 6320 11292 6321 11292 6119 11293 6321 11293 6202 11293 5863 11294 5865 11294 6316 11294 5863 11295 6316 11295 5875 11295 6118 11296 6123 11296 6315 11296 6315 11297 6123 11297 6113 11297 6315 11298 6113 11298 6316 11298 6316 11299 6113 11299 6124 11299 6316 11300 6124 11300 5875 11300 6385 11301 6342 11301 6386 11301 6386 11302 6342 11302 6341 11302 6386 11303 6341 11303 6387 11303 6387 11304 6341 11304 6345 11304 6387 11304 6345 11304 6388 11304 6388 11305 6345 11305 6347 11305 6388 11305 6347 11305 6389 11305 6389 11306 6347 11306 6349 11306 6389 11307 6349 11307 6390 11307 6390 11308 6349 11308 6351 11308 6390 11308 6351 11308 6391 11308 6391 11309 6351 11309 6353 11309 6391 11310 6353 11310 6392 11310 6392 11311 6353 11311 6355 11311 6392 11312 6355 11312 6393 11312 6393 11313 6355 11313 6357 11313 6393 11313 6357 11313 6394 11313 6394 11314 6357 11314 6359 11314 6394 11314 6359 11314 6395 11314 6395 11315 6359 11315 6361 11315 6395 11316 6361 11316 6396 11316 6396 11317 6361 11317 6343 11317 6396 11318 6343 11318 6385 11318 6385 11319 6343 11319 6342 11319 6389 95 6390 95 6397 95 6397 95 6390 95 6391 95 6397 95 6391 95 6392 95 6386 95 6387 95 6397 95 6397 95 6387 95 6388 95 6397 95 6388 95 6389 95 6395 95 6396 95 6397 95 6397 11320 6396 11320 6385 11320 6397 11321 6385 11321 6386 11321 6392 11322 6393 11322 6397 11322 6397 95 6393 95 6394 95 6397 95 6394 95 6395 95 6398 95 6399 95 6268 95 6268 11323 6267 11323 6275 11323 6400 95 6401 95 6398 95 4574 95 4572 95 4576 95 4576 95 4572 95 6150 95 4576 11324 6150 11324 4578 11324 4578 95 6150 95 6154 95 4578 95 6154 95 4579 95 6268 95 4572 95 6402 95 6268 11325 6275 11325 4572 11325 4572 11326 6275 11326 6151 11326 4572 11327 6151 11327 6150 11327 6403 95 6404 95 6168 95 6405 95 6164 95 6404 95 6404 95 6164 95 6166 95 6404 11328 6166 11328 6168 11328 6154 11329 6153 11329 4579 11329 4579 11330 6153 11330 6159 11330 4579 11331 6159 11331 6406 11331 6406 11332 6159 11332 6158 11332 6406 95 6158 95 6156 95 6407 95 6235 95 6408 95 6408 11333 6235 11333 6409 11333 6408 95 6409 95 6410 95 6410 11334 6409 11334 6411 11334 6410 11335 6411 11335 6412 11335 6412 95 6411 95 6413 95 6168 95 6169 95 6403 95 6403 11336 6169 11336 6171 11336 6403 95 6171 95 6407 95 6407 95 6171 95 6173 95 6407 95 6173 95 6235 95 6235 95 6173 95 6220 95 6235 95 6220 95 6221 95 6156 95 6155 95 6406 95 6406 95 6155 95 6160 95 6406 11337 6160 11337 6405 11337 6405 95 6160 95 6162 95 6405 95 6162 95 6164 95 6414 95 6415 95 6416 95 6402 11338 6413 11338 6268 11338 6268 11339 6413 11339 6411 11339 6268 11340 6411 11340 6398 11340 6398 11341 6411 11341 6417 11341 6398 95 6417 95 6400 95 6400 11342 6417 11342 6414 11342 6400 95 6414 95 6418 95 6418 95 6414 95 6416 95 4572 11343 4571 11343 6362 11343 4572 11344 6362 11344 6402 11344 6402 11345 6362 11345 6360 11345 6402 11346 6360 11346 6413 11346 6413 11347 6360 11347 6358 11347 6413 11348 6358 11348 6412 11348 6412 11349 6358 11349 6356 11349 6412 11350 6356 11350 6410 11350 6410 11351 6356 11351 6354 11351 6410 11351 6354 11351 6408 11351 6408 11352 6354 11352 6352 11352 6408 11353 6352 11353 6407 11353 6407 11354 6352 11354 6350 11354 6407 11355 6350 11355 6403 11355 6403 11356 6350 11356 6348 11356 6403 11357 6348 11357 6404 11357 6404 11358 6348 11358 6346 11358 6404 11359 6346 11359 6405 11359 6405 11360 6346 11360 6344 11360 6405 11361 6344 11361 6406 11361 6406 11362 6344 11362 4580 11362 6406 11362 4580 11362 4579 11362 6203 11363 6268 11363 6399 11363 6203 11364 6399 11364 6204 11364 6204 11365 6399 11365 6398 11365 6204 11366 6398 11366 6211 11366 6188 11367 6411 11367 6409 11367 6235 11368 6196 11368 6409 11368 6409 11369 6196 11369 6189 11369 6409 11370 6189 11370 6188 11370 6211 11371 6398 11371 6401 11371 6211 11372 6401 11372 6210 11372 6210 11373 6401 11373 6400 11373 6210 11374 6400 11374 6209 11374 6209 11375 6400 11375 6201 11375 6201 11376 6400 11376 6418 11376 6195 11377 6415 11377 6414 11377 6195 11378 6414 11378 6194 11378 6194 11379 6414 11379 6417 11379 6194 11380 6417 11380 6187 11380 6187 11381 6417 11381 6411 11381 6187 11382 6411 11382 6188 11382 6415 11383 6195 11383 6200 11383 6415 11384 6200 11384 6416 11384 6416 11385 6200 11385 6201 11385 6416 11386 6201 11386 6418 11386 4550 633 4556 633 4544 633 4544 633 4556 633 4553 633 4544 633 4553 633 4527 633 4527 11387 4553 11387 4528 11387 4492 11388 4490 11388 6419 11388 6419 633 4490 633 4487 633 6419 633 4487 633 4483 633 4498 633 4496 633 6419 633 6419 11389 4496 11389 4494 11389 6419 11390 4494 11390 4492 11390 4468 11388 4466 11388 6419 11388 6419 633 4466 633 4472 633 6419 633 4472 633 4498 633 4483 11391 4476 11391 6419 11391 6419 11392 4476 11392 4475 11392 6419 11393 4475 11393 4468 11393 1446 11394 4690 11394 1448 11394 1448 11394 4690 11394 4686 11394 6420 11395 6421 11395 6422 11395 6423 11396 6424 11396 6425 11396 6426 11397 6427 11397 6428 11397 6423 633 6425 633 6429 633 6430 633 6431 633 6432 633 6433 633 6434 633 6435 633 6435 633 6434 633 6436 633 6435 633 6436 633 6437 633 6437 11398 6436 11398 6438 11398 6437 633 6438 633 6424 633 6424 633 6438 633 6439 633 6424 633 6439 633 6425 633 6428 11399 6427 11399 6440 11399 6440 11400 6427 11400 6441 11400 6440 633 6441 633 6442 633 6443 633 210 633 6444 633 6443 11401 6444 11401 6445 11401 6445 633 6444 633 6446 633 6445 11402 6446 11402 6447 11402 6447 11403 6446 11403 6448 11403 6428 11404 6449 11404 6426 11404 6426 633 6449 633 6450 633 6426 11405 6450 11405 6451 11405 6451 633 6450 633 6452 633 6451 11406 6452 11406 6453 11406 6453 633 6452 633 6454 633 6453 11407 6454 11407 6455 11407 6455 633 6454 633 6456 633 6456 11408 6457 11408 6458 11408 6458 11409 6457 11409 6459 11409 6458 11410 6459 11410 6460 11410 6460 11411 6459 11411 6461 11411 6460 633 6461 633 6462 633 6462 633 6461 633 6463 633 6462 633 6463 633 6464 633 6441 11412 6465 11412 6442 11412 6442 633 6465 633 6466 633 6442 11413 6466 11413 6467 11413 6467 633 6466 633 6468 633 6467 11414 6468 11414 6469 11414 6470 633 6469 633 6429 633 6470 11415 6429 11415 6471 11415 6471 11416 6429 11416 6425 11416 6463 11417 6472 11417 6464 11417 6464 633 6472 633 6473 633 6464 633 6473 633 6474 633 6474 7585 6473 7585 6475 7585 6432 11418 6431 11418 6476 11418 6476 11419 6431 11419 6477 11419 6476 11420 6477 11420 6478 11420 6478 633 6477 633 6479 633 6478 11421 6479 11421 6480 11421 6480 633 6479 633 6481 633 6480 11422 6481 11422 6482 11422 6482 11423 6481 11423 6483 11423 6482 11424 6483 11424 6484 11424 6483 633 6485 633 6484 633 6484 11425 6485 11425 6486 11425 6484 11426 6486 11426 6487 11426 6487 633 6486 633 6488 633 6487 11427 6488 11427 6448 11427 6448 633 6488 633 6489 633 6448 633 6489 633 6447 633 6420 11428 6422 11428 6490 11428 6490 11429 6422 11429 6491 11429 6490 11430 6491 11430 6492 11430 6492 633 6491 633 6493 633 6430 633 6432 633 6494 633 6494 11431 6432 11431 6495 11431 6494 633 6495 633 6496 633 6496 633 6495 633 6497 633 6496 633 6497 633 6498 633 6498 633 6497 633 6499 633 6498 11432 6499 11432 6433 11432 6433 633 6499 633 6500 633 6433 633 6500 633 6434 633 6501 633 6493 633 6502 633 6501 633 6502 633 6503 633 6503 633 6502 633 6504 633 6503 11433 6504 11433 6505 11433 6505 633 6504 633 6506 633 6505 633 6506 633 6507 633 6507 11434 6506 11434 6508 11434 6507 633 6508 633 6509 633 6509 11435 6508 11435 6510 11435 6509 633 6510 633 6511 633 6511 11436 6510 11436 6512 11436 6512 633 6513 633 6514 633 6513 633 6515 633 6514 633 6514 633 6515 633 6516 633 6514 11437 6516 11437 6517 11437 6517 633 6516 633 6518 633 6517 11438 6518 11438 6519 11438 6519 11439 6518 11439 6520 11439 6519 633 6520 633 6521 633 6521 11440 6520 11440 6522 11440 6521 633 6522 633 6523 633 6523 633 6522 633 6524 633 6523 7585 6524 7585 6475 7585 6525 11441 6526 11441 6527 11441 6526 11442 6528 11442 6527 11442 6527 11443 6528 11443 6529 11443 6527 11444 6529 11444 6530 11444 6530 11445 6531 11445 6527 11445 6527 11446 6531 11446 6532 11446 6527 11447 6532 11447 6533 11447 6534 11448 4234 11448 6535 11448 6535 11449 4234 11449 6533 11449 6536 11450 6537 11450 4234 11450 4234 11451 6537 11451 6538 11451 4234 11452 6538 11452 6539 11452 6534 11453 6540 11453 4234 11453 4234 11454 6540 11454 6541 11454 4234 11455 6541 11455 6542 11455 6542 11456 6543 11456 4234 11456 4234 11457 6543 11457 6544 11457 4234 11458 6544 11458 6536 11458 6539 11459 6545 11459 4234 11459 4234 11460 6545 11460 6546 11460 4234 11461 6546 11461 6547 11461 6547 11462 6548 11462 4234 11462 4234 11463 6548 11463 6549 11463 4234 11464 6549 11464 6550 11464 6550 11465 6551 11465 4234 11465 4234 11466 6551 11466 6552 11466 4234 11467 6552 11467 6553 11467 6553 11468 6554 11468 4234 11468 4234 11469 6554 11469 6555 11469 4234 11470 6555 11470 6556 11470 6556 11471 6557 11471 4234 11471 4234 11472 6557 11472 6558 11472 4234 11473 6558 11473 6559 11473 6559 11474 6560 11474 4234 11474 4234 11475 6560 11475 6561 11475 4234 11476 6561 11476 6562 11476 6562 11477 6563 11477 4234 11477 4234 11478 6563 11478 6564 11478 4234 11479 6564 11479 4232 11479 6565 11480 6566 11480 6527 11480 6565 11481 6527 11481 6567 11481 6568 11482 6569 11482 6570 11482 6570 11483 6569 11483 6571 11483 6570 11484 6571 11484 6572 11484 6572 11485 6573 11485 6570 11485 6570 11486 6573 11486 6574 11486 6570 11487 6574 11487 6567 11487 6575 11488 6576 11488 6527 11488 6527 11489 6576 11489 6577 11489 6527 11490 6577 11490 6578 11490 6566 11491 6579 11491 6527 11491 6527 11492 6579 11492 6580 11492 6527 11493 6580 11493 6581 11493 6581 11494 6582 11494 6527 11494 6527 11495 6582 11495 6583 11495 6527 11496 6583 11496 6575 11496 6584 11497 6585 11497 6586 11497 6578 11498 6587 11498 6527 11498 6527 11499 6587 11499 6588 11499 6527 11500 6588 11500 6589 11500 6589 11501 6590 11501 6527 11501 6527 11502 6590 11502 6591 11502 6527 11503 6591 11503 6592 11503 6592 11504 6586 11504 6527 11504 6527 11505 6586 11505 6593 11505 6527 11506 6593 11506 6525 11506 6594 7585 6584 7585 6595 7585 6595 7585 6584 7585 6586 7585 6595 7585 6586 7585 6596 7585 6596 7585 6586 7585 6592 7585 6596 11507 6592 11507 6597 11507 6598 11508 6599 11508 6570 11508 6570 11509 6599 11509 6600 11509 6570 11510 6600 11510 6568 11510 6601 632 6602 632 6598 632 6533 11511 4234 11511 6527 11511 6527 11512 4234 11512 4231 11512 6527 11513 4231 11513 6603 11513 6603 11514 4231 11514 4235 11514 6603 11515 4235 11515 6604 11515 4235 11516 4236 11516 6604 11516 6604 11517 4236 11517 6605 11517 6604 11518 6605 11518 6606 11518 6567 11519 6527 11519 6570 11519 6570 11520 6527 11520 6603 11520 6570 11521 6603 11521 6607 11521 6607 11522 6603 11522 6604 11522 6607 11523 6604 11523 6608 11523 6608 11524 6604 11524 6606 11524 6608 11525 6606 11525 6609 11525 6598 11526 6570 11526 6601 11526 6601 11527 6570 11527 6607 11527 6601 11528 6607 11528 6610 11528 6610 11529 6607 11529 6608 11529 6610 11530 6608 11530 6611 11530 6611 11531 6608 11531 6609 11531 6611 11532 6609 11532 6612 11532 6613 11533 6614 11533 6615 11533 6616 11534 6617 11534 6618 11534 6618 11535 6617 11535 6619 11535 6620 11536 6621 11536 6622 11536 6622 11537 6621 11537 6619 11537 6622 11538 6619 11538 6623 11538 6623 11539 6619 11539 6617 11539 6624 11540 4327 11540 4326 11540 6625 11541 4326 11541 6618 11541 6618 11542 4326 11542 6626 11542 6618 11543 6626 11543 6616 11543 6614 11544 6624 11544 6615 11544 6615 11545 6624 11545 4326 11545 6615 11546 4326 11546 6627 11546 6627 11547 4326 11547 6625 11547 6628 11548 718 11548 721 11548 721 11549 722 11549 6628 11549 6628 11550 722 11550 724 11550 6628 11551 724 11551 6629 11551 6629 11552 724 11552 723 11552 6629 11553 723 11553 6630 11553 6630 11554 723 11554 6615 11554 6615 11555 723 11555 1781 11555 6615 11556 1781 11556 6613 11556 6631 11557 6632 11557 6633 11557 6633 11558 6634 11558 6635 11558 6636 11559 6637 11559 6638 11559 6638 11560 6637 11560 6639 11560 6634 11561 6640 11561 6635 11561 6635 11562 6640 11562 6641 11562 6635 11563 6641 11563 6637 11563 6637 11564 6641 11564 6642 11564 6637 11565 6642 11565 6639 11565 6643 11566 6631 11566 6644 11566 6644 11567 6631 11567 6633 11567 6644 11568 6633 11568 6645 11568 6645 11569 6633 11569 6635 11569 6645 11570 6635 11570 6646 11570 6646 11571 6635 11571 6637 11571 6646 11572 6637 11572 6647 11572 6647 11573 6637 11573 6648 11573 6648 11574 6637 11574 6636 11574 6648 11575 6636 11575 6649 11575 187 11576 174 11576 185 11576 210 11577 190 11577 6650 11577 6650 11578 190 11578 188 11578 233 11579 6651 11579 222 11579 222 11580 6651 11580 216 11580 6651 11581 6652 11581 216 11581 216 11582 6652 11582 6653 11582 216 11583 6653 11583 217 11583 217 11584 6653 11584 6654 11584 217 11585 6654 11585 182 11585 182 11586 6654 11586 183 11586 183 11587 6654 11587 6655 11587 183 11588 6655 11588 184 11588 6655 11589 6656 11589 184 11589 184 11590 6656 11590 6657 11590 184 11591 6657 11591 185 11591 185 11592 6657 11592 6658 11592 185 11593 6658 11593 187 11593 187 11594 6658 11594 6659 11594 187 11595 6659 11595 188 11595 188 11596 6659 11596 6660 11596 188 11597 6660 11597 6650 11597 6661 632 6662 632 6663 632 6664 632 4266 632 4265 632 4 632 4265 632 6665 632 4135 632 6666 632 3 632 3 632 6666 632 6667 632 6668 11598 6669 11598 6670 11598 4256 11599 6602 11599 6601 11599 6671 632 6672 632 6666 632 6666 11600 6672 11600 6673 11600 6667 11601 6674 11601 3 11601 3 11602 6674 11602 6675 11602 3 11603 6675 11603 6676 11603 6668 11604 6670 11604 6677 11604 6678 632 6679 632 6663 632 6663 11605 6679 11605 6680 11605 6665 632 6681 632 4 632 4 632 6681 632 6682 632 4 632 6682 632 325 632 325 632 6682 632 6683 632 325 11606 6683 11606 323 11606 323 11607 6683 11607 6684 11607 323 11608 6684 11608 6685 11608 984 632 1038 632 983 632 983 632 1038 632 4374 632 983 632 4374 632 6686 632 6686 11609 4374 11609 6687 11609 6686 11610 6687 11610 6685 11610 6685 11611 6687 11611 6688 11611 6685 11612 6688 11612 323 11612 6689 632 6690 632 6691 632 6691 11613 6690 11613 4256 11613 4256 11614 6690 11614 6602 11614 6691 632 6692 632 6689 632 6689 632 6692 632 6693 632 6689 632 6693 632 6694 632 6612 632 4257 632 6611 632 6611 632 4257 632 4256 632 6611 632 4256 632 6610 632 6610 632 4256 632 6601 632 6669 11615 6678 11615 6670 11615 6670 11616 6678 11616 6663 11616 6670 11617 6663 11617 6695 11617 6695 11618 6663 11618 6696 11618 6695 11619 6696 11619 6697 11619 6422 632 6698 632 6666 632 6666 11620 6698 11620 6699 11620 6666 11621 6699 11621 6667 11621 6675 632 6700 632 6676 632 6676 11622 6700 11622 6695 11622 6676 632 6695 632 6701 632 6701 632 6695 632 6697 632 6664 11623 4265 11623 6702 11623 6702 11624 4265 11624 4 11624 6702 632 4 632 6703 632 6703 11625 4 11625 3 11625 6703 632 3 632 6704 632 6704 632 3 632 6676 632 6704 632 6676 632 6694 632 6694 11626 6676 11626 6705 11626 6694 11627 6705 11627 6689 11627 6680 632 6706 632 6663 632 6663 11628 6706 11628 6707 11628 6663 11629 6707 11629 6708 11629 6709 11630 6422 11630 6710 11630 6710 632 6422 632 6666 632 6710 11631 6666 11631 6711 11631 6711 11632 6666 11632 6673 11632 6712 632 6713 632 6708 632 6708 632 6713 632 6714 632 6708 11633 6714 11633 6663 11633 6663 11634 6714 11634 6715 11634 6663 632 6715 632 6661 632 5697 632 5972 632 5698 632 5698 11635 5972 11635 5971 11635 5698 11636 5971 11636 6670 11636 6670 632 5971 632 6677 632 6677 632 5971 632 5970 632 6677 632 5970 632 5583 632 5583 11637 5970 11637 5969 11637 5583 632 5969 632 5584 632 369 11638 368 11638 4233 11638 6716 11639 6717 11639 4232 11639 4309 11640 4233 11640 6718 11640 6718 11641 4233 11641 4232 11641 1656 11642 1655 11642 4309 11642 4309 98 1655 98 1654 98 4309 11643 1654 11643 4233 11643 4233 11644 1654 11644 1664 11644 4233 11645 1664 11645 369 11645 6621 98 6620 98 6719 98 6717 11646 6720 11646 4232 11646 4232 11647 6720 11647 6721 11647 4232 11648 6721 11648 6722 11648 6722 11649 6723 11649 4232 11649 4232 11650 6723 11650 6724 11650 4232 11651 6724 11651 6718 11651 6719 98 6725 98 6621 98 6621 98 6725 98 6726 98 6621 98 6726 98 6727 98 6727 98 6728 98 6621 98 6621 98 6728 98 6729 98 6621 11652 6729 11652 4232 11652 4232 11653 6729 11653 6730 11653 4232 11654 6730 11654 6716 11654 6731 11655 6732 11655 6733 11655 6638 11656 6734 11656 6735 11656 6638 11657 6735 11657 6636 11657 6636 11658 6735 11658 6736 11658 6636 11659 6736 11659 6649 11659 6737 11660 6738 11660 6739 11660 6739 11661 6738 11661 6740 11661 6739 11662 6740 11662 6741 11662 6740 11663 6742 11663 6741 11663 6741 11664 6742 11664 6743 11664 6741 11665 6743 11665 6744 11665 6744 11666 6743 11666 6745 11666 6744 11667 6745 11667 6746 11667 6746 11668 6745 11668 6747 11668 6746 11669 6747 11669 6748 11669 6748 11670 6747 11670 6731 11670 6748 11671 6731 11671 6749 11671 6749 11672 6731 11672 6733 11672 6749 11673 6733 11673 6750 11673 6750 11674 6733 11674 6751 11674 6732 11675 6736 11675 6733 11675 6733 11676 6736 11676 6735 11676 6733 11677 6735 11677 6751 11677 6751 11678 6735 11678 6734 11678 6751 11679 6734 11679 6752 11679 6704 11680 562 11680 6703 11680 6703 11681 562 11681 561 11681 6703 11682 561 11682 6702 11682 6702 11683 561 11683 560 11683 6702 11684 560 11684 6664 11684 6664 11685 560 11685 558 11685 4256 11686 554 11686 6691 11686 6691 11687 554 11687 564 11687 6691 11688 564 11688 6692 11688 6692 11689 564 11689 563 11689 6692 11690 563 11690 6693 11690 6693 11690 563 11690 565 11690 6693 11691 565 11691 6694 11691 6694 11692 565 11692 559 11692 117 11693 104 11693 103 11693 102 11694 89 11694 88 11694 134 11695 140 11695 156 11695 98 11696 97 11696 132 11696 156 11697 6753 11697 134 11697 134 11698 6753 11698 6754 11698 134 11699 6754 11699 132 11699 132 11700 6754 11700 6755 11700 132 11701 6755 11701 98 11701 98 11702 6755 11702 6756 11702 98 11703 6756 11703 99 11703 6756 11704 6757 11704 99 11704 99 11705 6757 11705 6758 11705 99 11706 6758 11706 100 11706 118 11707 117 11707 6759 11707 6759 11708 117 11708 103 11708 6759 11709 103 11709 6760 11709 6760 11710 103 11710 102 11710 6760 11711 102 11711 6761 11711 6761 11694 102 11694 88 11694 6761 11712 88 11712 6762 11712 6762 11713 88 11713 100 11713 6762 11714 100 11714 6763 11714 6763 11715 100 11715 6758 11715 313 11716 312 11716 6764 11716 6765 11717 6766 11717 6767 11717 6768 11718 6769 11718 6770 11718 6771 11719 6772 11719 6773 11719 6773 11720 6772 11720 6774 11720 6773 11721 6774 11721 6775 11721 6776 11722 6777 11722 6778 11722 6778 11723 6777 11723 6779 11723 6770 11724 6780 11724 6781 11724 6781 11725 6780 11725 6782 11725 6781 11726 6782 11726 6783 11726 6783 11727 6782 11727 6784 11727 6783 11728 6784 11728 6785 11728 6769 11729 6786 11729 6770 11729 6770 11730 6786 11730 6787 11730 6770 11731 6787 11731 6780 11731 6766 11732 6765 11732 6788 11732 6788 11733 6765 11733 6789 11733 6788 11734 6789 11734 6790 11734 418 11735 420 11735 6791 11735 6791 11736 420 11736 422 11736 6791 11737 422 11737 445 11737 442 11738 6792 11738 440 11738 440 11739 6792 11739 6791 11739 440 11740 6791 11740 438 11740 438 11741 6791 11741 445 11741 6793 11742 477 11742 479 11742 479 11743 481 11743 6793 11743 6793 11744 481 11744 483 11744 6793 11745 483 11745 6791 11745 6791 11746 483 11746 485 11746 6791 11747 485 11747 487 11747 487 11748 488 11748 6791 11748 6791 11749 488 11749 392 11749 6791 11750 392 11750 418 11750 435 11751 464 11751 6794 11751 442 11752 423 11752 6792 11752 6792 11753 423 11753 425 11753 6792 11754 425 11754 427 11754 427 11755 429 11755 6792 11755 6792 11756 429 11756 431 11756 6792 11757 431 11757 433 11757 464 11758 462 11758 6794 11758 6794 11759 462 11759 460 11759 6794 11760 460 11760 458 11760 458 11761 456 11761 6794 11761 6794 11762 456 11762 454 11762 6794 11763 454 11763 452 11763 6790 11764 6795 11764 6788 11764 6788 11765 6795 11765 6796 11765 6788 11766 6796 11766 6766 11766 6766 11767 6796 11767 6797 11767 6766 11768 6797 11768 6767 11768 6767 11769 6797 11769 4321 11769 6767 11770 4321 11770 316 11770 316 11771 4321 11771 315 11771 398 11772 396 11772 307 11772 307 11773 396 11773 394 11773 307 11774 394 11774 308 11774 398 11775 307 11775 400 11775 400 11776 307 11776 6798 11776 400 11777 6798 11777 402 11777 452 11778 450 11778 6794 11778 6794 11779 450 11779 448 11779 6794 11780 448 11780 447 11780 447 11781 416 11781 6794 11781 6794 11782 416 11782 414 11782 6794 11783 414 11783 6798 11783 414 11784 412 11784 6798 11784 6798 11785 412 11785 410 11785 6798 11786 410 11786 409 11786 409 11787 406 11787 6798 11787 6798 11788 406 11788 404 11788 6798 11789 404 11789 402 11789 6799 11790 386 11790 6800 11790 6800 11791 386 11791 389 11791 6800 11792 389 11792 6801 11792 6801 11793 389 11793 535 11793 6801 11794 535 11794 537 11794 537 11795 539 11795 6801 11795 6801 11796 539 11796 541 11796 6801 11797 541 11797 543 11797 543 11798 545 11798 6801 11798 6801 11799 545 11799 547 11799 6801 11800 547 11800 549 11800 549 11801 551 11801 6801 11801 6801 11802 551 11802 532 11802 6801 11803 532 11803 530 11803 530 11804 528 11804 6801 11804 6801 11805 528 11805 527 11805 6801 11806 527 11806 525 11806 525 11807 523 11807 6801 11807 6801 11808 523 11808 521 11808 6801 11809 521 11809 519 11809 519 11810 517 11810 6801 11810 6801 11811 517 11811 515 11811 6801 11812 515 11812 513 11812 513 11813 512 11813 6801 11813 6801 11814 512 11814 491 11814 6801 11815 491 11815 6802 11815 6802 11816 491 11816 493 11816 6802 11817 493 11817 495 11817 495 11818 497 11818 6802 11818 6802 11819 497 11819 499 11819 6802 11820 499 11820 501 11820 501 11821 503 11821 6802 11821 6802 11822 503 11822 505 11822 6802 11823 505 11823 507 11823 507 11824 509 11824 6802 11824 6802 11825 509 11825 467 11825 6802 11826 467 11826 469 11826 471 11827 473 11827 6793 11827 6793 11828 473 11828 475 11828 6793 11829 475 11829 477 11829 6790 11830 6768 11830 6795 11830 6795 11831 6768 11831 6770 11831 6795 11832 6770 11832 6803 11832 6803 11833 6770 11833 6781 11833 6803 11834 6781 11834 6804 11834 6804 11835 6781 11835 6783 11835 6804 11836 6783 11836 6778 11836 6778 11837 6783 11837 6785 11837 6778 11838 6785 11838 6776 11838 312 11839 310 11839 6764 11839 6764 11840 310 11840 6805 11840 6764 11841 6805 11841 6806 11841 6806 11842 6805 11842 6807 11842 6806 11843 6807 11843 6808 11843 6808 11844 6807 11844 6809 11844 6808 11845 6809 11845 6810 11845 6810 11846 6809 11846 6811 11846 6810 11847 6811 11847 6812 11847 6812 11848 6811 11848 6813 11848 6812 11849 6813 11849 6774 11849 469 11850 471 11850 6802 11850 6802 11851 471 11851 6793 11851 6802 11852 6793 11852 6814 11852 6814 11853 6793 11853 6791 11853 6814 11854 6791 11854 6815 11854 6815 11855 6791 11855 6792 11855 6815 11856 6792 11856 6794 11856 6794 11857 6792 11857 433 11857 6794 11858 433 11858 435 11858 6779 11859 6775 11859 6778 11859 6778 11860 6775 11860 6774 11860 6778 11861 6774 11861 6804 11861 6804 11862 6774 11862 6813 11862 6804 11863 6813 11863 6803 11863 6803 11864 6813 11864 6811 11864 6803 11865 6811 11865 6795 11865 6795 11866 6811 11866 6809 11866 6795 11867 6809 11867 6796 11867 6796 11868 6809 11868 6807 11868 6796 11869 6807 11869 6797 11869 6797 11870 6807 11870 6805 11870 6797 11871 6805 11871 4321 11871 4321 11872 6805 11872 310 11872 6771 11873 6799 11873 6772 11873 6772 11874 6799 11874 6800 11874 6772 11875 6800 11875 6774 11875 6774 11876 6800 11876 6801 11876 6774 11877 6801 11877 6812 11877 6812 11878 6801 11878 6802 11878 6812 11879 6802 11879 6810 11879 6810 11880 6802 11880 6814 11880 6810 11881 6814 11881 6808 11881 6808 11882 6814 11882 6815 11882 6808 11883 6815 11883 6806 11883 6806 11884 6815 11884 6794 11884 6806 11885 6794 11885 6764 11885 6764 11886 6794 11886 6798 11886 6764 11887 6798 11887 313 11887 313 11888 6798 11888 307 11888 6816 11889 6817 11889 6818 11889 6819 11890 6820 11890 6821 11890 1105 11891 1138 11891 6822 11891 1012 11892 1013 11892 1105 11892 1105 11893 6822 11893 1012 11893 1012 11894 6822 11894 6823 11894 1012 11895 6823 11895 1011 11895 6824 11896 6825 11896 6826 11896 6826 11897 6825 11897 6827 11897 6826 11898 6827 11898 6828 11898 6824 11899 6829 11899 6825 11899 6825 11900 6829 11900 6830 11900 6825 11901 6830 11901 6831 11901 6832 11902 6833 11902 6834 11902 6820 11903 6819 11903 6834 11903 6834 11904 6819 11904 6835 11904 6834 11905 6835 11905 6832 11905 6789 11906 6836 11906 6790 11906 6790 11907 6836 11907 6837 11907 6790 11908 6837 11908 6768 11908 6768 11909 6837 11909 6838 11909 6768 11910 6838 11910 6769 11910 6769 11911 6838 11911 6821 11911 6769 11912 6821 11912 6786 11912 6786 11913 6821 11913 6820 11913 316 11914 6839 11914 6767 11914 6767 11915 6839 11915 6840 11915 6767 11916 6840 11916 6765 11916 6765 11917 6840 11917 6841 11917 6765 11918 6841 11918 6789 11918 6789 11919 6841 11919 6842 11919 6789 11920 6842 11920 6836 11920 6817 11921 6785 11921 6784 11921 6816 11922 6777 11922 6817 11922 6817 11923 6777 11923 6776 11923 6817 11924 6776 11924 6785 11924 6771 11925 6773 11925 6843 11925 6843 11926 6773 11926 6775 11926 6843 11927 6775 11927 6816 11927 6816 11928 6775 11928 6779 11928 6816 11929 6779 11929 6777 11929 6771 11930 6843 11930 6799 11930 6799 11931 6843 11931 1121 11931 6799 11932 1121 11932 386 11932 6844 11933 6845 11933 6846 11933 1010 11934 1011 11934 6847 11934 6847 11935 1011 11935 6823 11935 6847 11936 6823 11936 6848 11936 6848 11937 6823 11937 6849 11937 6849 11938 6823 11938 6822 11938 6849 11939 6822 11939 6850 11939 6850 11940 6822 11940 1138 11940 6850 11941 1138 11941 1137 11941 6833 11942 6851 11942 6834 11942 6834 11943 6851 11943 6828 11943 6834 11944 6828 11944 6852 11944 6852 11945 6828 11945 6827 11945 6852 11946 6827 11946 6853 11946 6853 11947 6827 11947 6825 11947 6853 11948 6825 11948 6844 11948 6844 11949 6825 11949 6831 11949 6844 11950 6831 11950 6845 11950 6845 11951 6831 11951 1009 11951 6845 11952 1009 11952 6846 11952 6846 11953 6818 11953 6844 11953 6844 11954 6818 11954 6817 11954 6844 11955 6817 11955 6853 11955 6853 11956 6817 11956 6784 11956 6853 11957 6784 11957 6852 11957 6852 11958 6784 11958 6782 11958 6852 11959 6782 11959 6834 11959 6834 11960 6782 11960 6780 11960 6834 11961 6780 11961 6820 11961 6820 11962 6780 11962 6787 11962 6820 11963 6787 11963 6786 11963 1009 11964 1010 11964 6846 11964 6846 11965 1010 11965 6847 11965 6846 11966 6847 11966 6818 11966 6818 11967 6847 11967 6848 11967 6818 11968 6848 11968 6816 11968 6816 11969 6848 11969 6849 11969 6816 11970 6849 11970 6843 11970 6843 11971 6849 11971 6850 11971 6843 11972 6850 11972 1121 11972 1121 11973 6850 11973 1137 11973 6819 11974 6854 11974 6855 11974 318 11975 6839 11975 316 11975 319 11976 322 11976 6856 11976 6856 11977 322 11977 321 11977 6856 11978 321 11978 327 11978 6839 11979 318 11979 6840 11979 6840 11980 318 11980 319 11980 6840 11981 319 11981 6841 11981 6838 11982 6837 11982 6856 11982 6856 11983 6837 11983 6836 11983 6856 11984 6836 11984 319 11984 319 11985 6836 11985 6842 11985 319 11986 6842 11986 6841 11986 324 11987 6857 11987 326 11987 326 11988 6857 11988 6858 11988 326 11989 6858 11989 327 11989 327 11990 6858 11990 6859 11990 327 11991 6859 11991 6856 11991 6856 11992 6859 11992 6821 11992 6856 11993 6821 11993 6838 11993 6855 11994 6860 11994 6861 11994 6828 11995 6851 11995 6861 11995 6829 11996 6824 11996 6861 11996 6861 11997 6824 11997 6826 11997 6861 11998 6826 11998 6828 11998 6851 11999 6833 11999 6861 11999 6861 12000 6833 12000 6832 12000 6861 12001 6832 12001 6855 12001 6855 12002 6832 12002 6835 12002 6855 12003 6835 12003 6819 12003 6830 12004 6829 12004 6862 12004 6862 12005 6829 12005 6861 12005 6862 12006 6861 12006 6863 12006 6863 12007 6861 12007 6860 12007 6863 12008 6860 12008 6864 12008 6864 12009 6860 12009 6865 12009 6864 12010 6865 12010 6866 12010 6866 12011 6865 12011 323 12011 6819 12012 6821 12012 6854 12012 6854 12013 6821 12013 6859 12013 6854 12014 6859 12014 6855 12014 6855 12015 6859 12015 6858 12015 6855 12016 6858 12016 6860 12016 6860 12017 6858 12017 6857 12017 6860 12018 6857 12018 6865 12018 6865 12019 6857 12019 324 12019 6865 12020 324 12020 323 12020 6684 12021 383 12021 6685 12021 6685 12022 383 12022 384 12022 6685 12023 384 12023 6686 12023 6686 12024 384 12024 385 12024 6686 12025 385 12025 983 12025 983 12026 385 12026 379 12026 6665 12027 378 12027 6681 12027 6681 12028 378 12028 381 12028 6681 12029 381 12029 6682 12029 6682 12030 381 12030 380 12030 6682 12031 380 12031 6683 12031 6683 12032 380 12032 382 12032 4276 12033 4275 12033 6867 12033 6867 12034 4275 12034 4273 12034 4271 12035 4281 12035 6868 12035 6868 12036 4281 12036 4279 12036 6868 12037 4279 12037 6869 12037 6870 12038 4273 12038 4271 12038 4273 12039 6871 12039 6867 12039 6867 12040 6871 12040 6872 12040 6867 12041 6872 12041 4276 12041 4276 12042 6872 12042 4263 12042 6873 12043 6874 12043 6871 12043 6871 12044 6874 12044 6875 12044 6871 12045 6875 12045 6872 12045 6876 12046 6877 12046 6873 12046 6873 12047 6877 12047 6878 12047 6873 12048 6878 12048 6874 12048 6879 12049 6880 12049 6881 12049 6881 12050 6880 12050 6882 12050 6881 12051 6882 12051 6883 12051 6883 12052 6882 12052 6884 12052 6883 12053 6884 12053 6876 12053 6876 12054 6884 12054 6885 12054 6876 12055 6885 12055 6877 12055 6879 12056 6881 12056 6886 12056 6886 12057 6881 12057 6887 12057 6886 12058 6887 12058 6888 12058 6888 12059 6887 12059 6889 12059 6888 12060 6889 12060 6890 12060 6890 12061 6889 12061 6891 12061 6890 12062 6891 12062 6892 12062 6892 12063 6891 12063 6893 12063 6893 12064 6891 12064 6894 12064 6893 12065 6894 12065 6895 12065 6895 12066 6894 12066 6896 12066 6896 12067 6894 12067 6897 12067 6896 12068 6897 12068 6898 12068 6899 12069 1467 12069 1466 12069 6898 12070 6897 12070 6900 12070 6900 12071 6897 12071 6901 12071 6900 12072 6901 12072 6902 12072 6902 12073 6901 12073 6899 12073 6902 12074 6899 12074 6903 12074 6903 12075 6899 12075 1466 12075 6903 12076 1466 12076 1474 12076 6904 12077 1461 12077 1460 12077 6905 12078 6906 12078 6907 12078 6907 12079 6906 12079 6908 12079 6907 12080 6908 12080 6909 12080 6909 12081 6908 12081 6910 12081 6909 12082 6910 12082 6911 12082 6911 12083 6910 12083 6912 12083 6911 12084 6912 12084 6913 12084 6913 12085 6912 12085 6904 12085 6913 12086 6904 12086 6914 12086 6914 12087 6904 12087 1460 12087 6914 12088 1460 12088 1471 12088 6869 12089 6915 12089 6868 12089 6868 12090 6915 12090 6916 12090 6868 12091 6916 12091 6917 12091 6917 12092 6916 12092 6918 12092 6917 12093 6918 12093 6919 12093 6919 12094 6918 12094 6920 12094 6919 12095 6920 12095 6921 12095 6921 12096 6920 12096 6922 12096 6921 12097 6922 12097 6923 12097 6923 12098 6922 12098 6924 12098 6923 12099 6924 12099 6925 12099 6925 12100 6924 12100 6926 12100 6925 12101 6926 12101 6905 12101 6905 12102 6926 12102 6927 12102 6905 12103 6927 12103 6906 12103 4273 12104 6870 12104 6871 12104 6871 12105 6870 12105 6928 12105 6871 12106 6928 12106 6873 12106 6873 12107 6928 12107 6929 12107 6873 12108 6929 12108 6876 12108 6876 12109 6929 12109 6930 12109 6876 12110 6930 12110 6883 12110 6883 12111 6930 12111 6931 12111 6883 12112 6931 12112 6881 12112 6881 12113 6931 12113 6932 12113 6881 12114 6932 12114 6887 12114 6887 12115 6932 12115 6933 12115 6887 12116 6933 12116 6889 12116 6889 12117 6933 12117 6934 12117 6889 12118 6934 12118 6891 12118 6891 12119 6934 12119 6935 12119 6891 12120 6935 12120 6894 12120 6894 12121 6935 12121 6936 12121 6894 12122 6936 12122 6897 12122 6897 12123 6936 12123 6937 12123 6897 12124 6937 12124 6901 12124 6901 12125 6937 12125 6938 12125 6901 12126 6938 12126 6899 12126 4271 12127 6868 12127 6870 12127 6870 12128 6868 12128 6917 12128 6870 12129 6917 12129 6928 12129 6928 12130 6917 12130 6919 12130 6928 12131 6919 12131 6929 12131 6929 12132 6919 12132 6921 12132 6929 12133 6921 12133 6930 12133 6930 12134 6921 12134 6923 12134 6930 12135 6923 12135 6931 12135 6931 12136 6923 12136 6925 12136 6931 12137 6925 12137 6932 12137 6932 12138 6925 12138 6905 12138 6932 12139 6905 12139 6933 12139 6933 12140 6905 12140 6907 12140 6933 12141 6907 12141 6934 12141 6934 12142 6907 12142 6909 12142 6934 12143 6909 12143 6935 12143 6935 12144 6909 12144 6911 12144 6935 12145 6911 12145 6936 12145 6936 12146 6911 12146 6913 12146 6936 12147 6913 12147 6937 12147 6937 12148 6913 12148 6914 12148 6937 12149 6914 12149 6938 12149 6938 12150 6914 12150 1471 12150 6938 12151 1471 12151 6899 12151 6899 12152 1471 12152 1469 12152 6899 12153 1469 12153 1467 12153 562 7585 6704 7585 559 7585 559 7585 6704 7585 6694 7585 4261 12154 6939 12154 6940 12154 4261 12155 6940 12155 4262 12155 4262 12156 6940 12156 6941 12156 4262 12157 6941 12157 4314 12157 4260 12158 6942 12158 6943 12158 4260 12159 6943 12159 4261 12159 4261 12160 6943 12160 6944 12160 4261 12161 6944 12161 6939 12161 4259 12162 6945 12162 6946 12162 4259 12163 6946 12163 4260 12163 4260 12164 6946 12164 6947 12164 4260 12165 6947 12165 6942 12165 6612 12166 6948 12166 4257 12166 4257 12167 6948 12167 6949 12167 4257 12168 6949 12168 4258 12168 4258 12169 6949 12169 6950 12169 4258 12170 6950 12170 4259 12170 4259 12171 6950 12171 6951 12171 4259 12172 6951 12172 6945 12172 6831 12173 6830 12173 6862 12173 6952 12174 1009 12174 6831 12174 6953 12175 6954 12175 6955 12175 6955 12176 6954 12176 6956 12176 6955 12177 6956 12177 6957 12177 6957 12178 6956 12178 6952 12178 6958 12179 6959 12179 6953 12179 6953 12180 6959 12180 6954 12180 6960 12181 6688 12181 6687 12181 6953 12182 6961 12182 6958 12182 6958 12183 6961 12183 6960 12183 6958 12184 6960 12184 6962 12184 6962 12185 6960 12185 6687 12185 6952 12186 6831 12186 6957 12186 6957 12187 6831 12187 6862 12187 6957 12188 6862 12188 6955 12188 6955 12189 6862 12189 6863 12189 6955 12190 6863 12190 6953 12190 6953 12191 6863 12191 6864 12191 6953 12192 6864 12192 6961 12192 6961 12193 6864 12193 6866 12193 6961 12194 6866 12194 6960 12194 6960 12195 6866 12195 323 12195 6960 12196 323 12196 6688 12196 4379 12197 1003 12197 1009 12197 1009 12198 6952 12198 4379 12198 4379 12199 6952 12199 6956 12199 4379 12200 6956 12200 4378 12200 6687 12201 4374 12201 6962 12201 6962 12202 4374 12202 4375 12202 6962 12203 4375 12203 6958 12203 6958 12204 4375 12204 4376 12204 6958 12205 4376 12205 6959 12205 6959 12206 4376 12206 4377 12206 6959 12207 4377 12207 4378 12207 6959 12208 4378 12208 6954 12208 6954 12209 4378 12209 6956 12209 6683 7585 382 7585 6684 7585 6684 7585 382 7585 383 7585 6963 106 1473 106 1472 106 4264 12210 376 12210 4265 12210 4265 106 376 106 378 106 4265 106 378 106 6665 106 6964 12211 6965 12211 376 12211 376 12212 6965 12212 1472 12212 376 106 1472 106 1240 106 4264 12213 6966 12213 376 12213 376 106 6966 106 6967 106 376 12214 6967 12214 6964 12214 6968 106 6963 106 6969 106 6969 12215 6963 12215 1472 12215 6969 106 1472 106 6970 106 6970 12216 1472 12216 6965 12216 1474 12217 1473 12217 6903 12217 6903 12218 1473 12218 6963 12218 6903 12219 6963 12219 6902 12219 6902 12220 6963 12220 6900 12220 6900 12221 6963 12221 6898 12221 6898 12222 6963 12222 6968 12222 6898 12223 6968 12223 6896 12223 6888 12224 6890 12224 6970 12224 6970 12225 6890 12225 6892 12225 6970 12226 6892 12226 6969 12226 6969 12227 6892 12227 6893 12227 6969 12228 6893 12228 6968 12228 6968 12229 6893 12229 6895 12229 6968 12230 6895 12230 6896 12230 6888 12231 6970 12231 6886 12231 6886 12232 6970 12232 6965 12232 6886 12233 6965 12233 6879 12233 6964 12234 6882 12234 6965 12234 6965 12235 6882 12235 6880 12235 6965 12236 6880 12236 6879 12236 6967 12237 6885 12237 6964 12237 6964 12238 6885 12238 6884 12238 6964 12239 6884 12239 6882 12239 6966 12240 6878 12240 6967 12240 6967 12241 6878 12241 6877 12241 6967 12242 6877 12242 6885 12242 4263 12243 6872 12243 4264 12243 4264 12244 6872 12244 6875 12244 4264 12245 6875 12245 6966 12245 6966 12246 6875 12246 6874 12246 6966 12247 6874 12247 6878 12247 6971 12248 6972 12248 6973 12248 6974 12249 6972 12249 6971 12249 6975 12250 6974 12250 6971 12250 6971 12251 6976 12251 6977 12251 6971 12252 6978 12252 6979 12252 6971 12253 6980 12253 6981 12253 6982 12254 6980 12254 6971 12254 6983 12255 6982 12255 6971 12255 6971 12256 6984 12256 6985 12256 6986 12257 6984 12257 6971 12257 6987 12258 6986 12258 6971 12258 6971 12259 6988 12259 6989 12259 6990 12260 6988 12260 6971 12260 6989 12261 6975 12261 6971 12261 6646 12262 6647 12262 6990 12262 6979 12263 6978 12263 6738 12263 6991 12264 6992 12264 6993 12264 6994 12265 6995 12265 6996 12265 6997 12266 6998 12266 6999 12266 6999 12267 6998 12267 6643 12267 7000 12268 7001 12268 7002 12268 7002 12269 7003 12269 7000 12269 7000 12270 7003 12270 7004 12270 7000 12271 7004 12271 6999 12271 6999 12272 7004 12272 7005 12272 6999 12273 7005 12273 6997 12273 7001 12274 7000 12274 7006 12274 7006 12275 7000 12275 7007 12275 7006 12276 7007 12276 7008 12276 7009 12277 7010 12277 7007 12277 7007 12278 7010 12278 7011 12278 7007 12279 7011 12279 7008 12279 7012 12280 7013 12280 7014 12280 7014 12281 7013 12281 7015 12281 7014 12282 7015 12282 7016 12282 7017 12283 7018 12283 7019 12283 7019 12284 7018 12284 7020 12284 6991 12285 7021 12285 6992 12285 6992 12286 7021 12286 7022 12286 6992 12287 7022 12287 7023 12287 7023 12288 7022 12288 6996 12288 7023 12289 6996 12289 7024 12289 7024 12290 6996 12290 6995 12290 7024 12291 6995 12291 7025 12291 6971 12292 7026 12292 7027 12292 7027 12293 7026 12293 7028 12293 7027 12294 7028 12294 7029 12294 6971 12295 6977 12295 6978 12295 6978 12296 6977 12296 6740 12296 6978 12297 6740 12297 6738 12297 6973 12298 6976 12298 6971 12298 6974 12299 6731 12299 6972 12299 6972 12300 6731 12300 6747 12300 6972 12301 6747 12301 6973 12301 6973 12302 6747 12302 6745 12302 6973 12303 6745 12303 6976 12303 6976 12304 6745 12304 6743 12304 6976 12305 6743 12305 6977 12305 6977 12306 6743 12306 6742 12306 6977 12307 6742 12307 6740 12307 6990 12308 6647 12308 6988 12308 6988 12309 6647 12309 6648 12309 6988 12310 6648 12310 6989 12310 6989 12311 6648 12311 6649 12311 6989 12312 6649 12312 6975 12312 6975 12313 6649 12313 6736 12313 6975 12314 6736 12314 6974 12314 6974 12315 6736 12315 6732 12315 6974 12316 6732 12316 6731 12316 6644 12317 6645 12317 7030 12317 7030 12318 6645 12318 6646 12318 7030 12319 6646 12319 7031 12319 7031 12320 6646 12320 6990 12320 7031 12321 6990 12321 6971 12321 7032 12322 7033 12322 7034 12322 7034 12323 7033 12323 7035 12323 7034 12324 7035 12324 7036 12324 7037 12325 6985 12325 7038 12325 7038 12326 6985 12326 6984 12326 7038 12327 6984 12327 7039 12327 7039 12328 6984 12328 6986 12328 7039 12329 6986 12329 7040 12329 7040 12330 6986 12330 6987 12330 7040 12331 6987 12331 6993 12331 6971 12332 7027 12332 6983 12332 6983 12333 7027 12333 7029 12333 6983 12334 7029 12334 6982 12334 6982 12335 7029 12335 7041 12335 6982 12336 7041 12336 6980 12336 6980 12337 7041 12337 7042 12337 6980 12338 7042 12338 6981 12338 6738 12339 7028 12339 6979 12339 6979 12340 7028 12340 7026 12340 6979 12341 7026 12341 6971 12341 6999 12342 7032 12342 7000 12342 7000 12343 7032 12343 7034 12343 7000 12344 7034 12344 7007 12344 7007 12345 7034 12345 7036 12345 7007 12346 7036 12346 7009 12346 6993 12347 6992 12347 7040 12347 7040 12348 6992 12348 7023 12348 7040 12349 7023 12349 7039 12349 7039 12350 7023 12350 7024 12350 7039 12351 7024 12351 7038 12351 7038 12352 7024 12352 7025 12352 7038 12353 7025 12353 7037 12353 7037 12354 7043 12354 6985 12354 6985 12355 7043 12355 6971 12355 7017 12356 7012 12356 7018 12356 7018 12357 7012 12357 7014 12357 7018 12358 7014 12358 7009 12358 7009 12359 7014 12359 7016 12359 7009 12360 7016 12360 7010 12360 7044 12361 7020 12361 7045 12361 7045 12362 7020 12362 7018 12362 7045 12363 7018 12363 7046 12363 7046 12364 7018 12364 7009 12364 7046 12365 7009 12365 7047 12365 7047 12366 7009 12366 7036 12366 7047 12367 7036 12367 7048 12367 7048 12368 7036 12368 7035 12368 7048 12369 7035 12369 6971 12369 7033 12370 6971 12370 7035 12370 6643 12371 6644 12371 6999 12371 6999 12372 6644 12372 7030 12372 6999 12373 7030 12373 7032 12373 7032 12374 7030 12374 7031 12374 7032 12375 7031 12375 7033 12375 7033 12376 7031 12376 6971 12376 6994 12377 7044 12377 6995 12377 6995 12378 7044 12378 7045 12378 6995 12379 7045 12379 7025 12379 7025 12380 7045 12380 7046 12380 7025 12381 7046 12381 7037 12381 7037 12382 7046 12382 7047 12382 7037 12383 7047 12383 7043 12383 7043 12384 7047 12384 7048 12384 7043 12385 7048 12385 6971 12385 7029 12386 7049 12386 7041 12386 7041 12387 7049 12387 6991 12387 7041 12388 6991 12388 7042 12388 7042 12389 6991 12389 6993 12389 7042 12390 6993 12390 6981 12390 6981 12391 6993 12391 6987 12391 6981 12392 6987 12392 6971 12392 7050 12393 7049 12393 7029 12393 7028 12394 7051 12394 7029 12394 7029 12395 7051 12395 7052 12395 7029 12396 7052 12396 7050 12396 6737 12397 7053 12397 6738 12397 6738 12398 7053 12398 7054 12398 6738 12399 7054 12399 7028 12399 7028 12400 7054 12400 7055 12400 7028 12401 7055 12401 7051 12401 6599 12402 6598 12402 7056 12402 7057 12403 7058 12403 7059 12403 6539 12404 7060 12404 7061 12404 7059 12405 7062 12405 6593 12405 6533 12406 6532 12406 7063 12406 7063 7585 6532 7585 6531 7585 7063 7585 6531 7585 7064 7585 6552 12407 7065 12407 6553 12407 6553 633 7065 633 6554 633 6593 7585 7062 7585 6525 7585 6578 12408 7066 12408 6587 12408 6587 12409 7066 12409 6588 12409 6539 12410 7061 12410 6545 12410 6545 12411 7061 12411 7067 12411 6545 7585 7067 7585 6546 7585 6546 633 7067 633 6547 633 6547 12412 7068 12412 6548 12412 6548 12413 7068 12413 6549 12413 6525 12414 7069 12414 6526 12414 6526 7585 7069 7585 6528 7585 6562 12415 6561 12415 7070 12415 7070 12416 6561 12416 6560 12416 6560 12417 6559 12417 7071 12417 7071 12418 6559 12418 6558 12418 7071 7585 6558 7585 7072 7585 7072 7585 6558 7585 6557 7585 6557 12419 6556 12419 7073 12419 7073 12420 6556 12420 6555 12420 7073 633 6555 633 6554 633 6579 12421 7074 12421 6580 12421 6580 7585 7074 7585 7075 7585 6580 12422 7075 12422 6581 12422 6581 12423 7075 12423 6582 12423 6582 12424 7076 12424 6583 12424 6583 7585 7076 7585 6575 7585 6550 633 6549 633 7077 633 6550 12425 7077 12425 6551 12425 6551 633 7077 633 6552 633 6552 7585 7078 7585 7065 7585 6539 12426 6538 12426 7079 12426 7079 12427 6538 12427 6537 12427 7079 12428 6537 12428 6536 12428 6536 12429 6544 12429 7080 12429 7080 7585 6544 7585 6543 7585 6543 12430 6542 12430 7081 12430 7081 12431 6542 12431 6541 12431 7081 7585 6541 7585 7082 7585 7082 12432 6541 12432 6540 12432 6540 12433 6534 12433 7083 12433 7083 12434 6534 12434 6535 12434 7083 12435 6535 12435 6533 12435 6576 7585 6575 7585 7084 7585 6576 12436 7084 12436 6577 12436 6577 7585 7084 7585 6578 7585 6578 12437 7085 12437 7066 12437 7086 7585 7087 7585 7056 7585 7056 7585 7087 7585 7088 7585 7056 12438 7088 12438 6599 12438 6599 7585 7088 7585 7089 7585 6599 7585 7089 7585 6600 7585 6600 7585 7089 7585 7090 7585 6600 12439 7090 12439 6568 12439 6568 12440 7090 12440 6569 12440 6569 7585 7091 7585 6571 7585 6571 7585 7091 7585 7092 7585 6571 7585 7092 7585 6572 7585 6572 7585 7092 7585 6573 7585 6573 12441 7093 12441 6574 12441 6574 7585 7093 7585 6567 7585 4232 633 6564 633 7094 633 7094 7585 6564 7585 6563 7585 7094 12442 6563 12442 6562 12442 6531 12443 6530 12443 7095 12443 7095 12444 6530 12444 6529 12444 7095 12445 6529 12445 6528 12445 7059 7585 6593 7585 7057 7585 7057 12446 6593 12446 6586 12446 6586 12447 6585 12447 7096 12447 7096 7585 6585 7585 6584 7585 7096 12448 6584 12448 6594 12448 6594 7585 6595 7585 7097 7585 7097 7585 6595 7585 6596 7585 6596 12449 6597 12449 7098 12449 7098 7585 6597 7585 6592 7585 7098 7585 6592 7585 7099 7585 7099 7585 6592 7585 6591 7585 6591 12450 6590 12450 7100 12450 7100 7585 6590 7585 6589 7585 7100 7585 6589 7585 6588 7585 6565 7585 6567 7585 7101 7585 6565 7585 7101 7585 6566 7585 6566 7585 7101 7585 6579 7585 6579 12451 7102 12451 7074 12451 6689 12452 7103 12452 6690 12452 6690 12453 7103 12453 7056 12453 6690 12454 7056 12454 6602 12454 6602 12455 7056 12455 6598 12455 7097 12456 6596 12456 7103 12456 7103 12457 6596 12457 7098 12457 7103 12458 7098 12458 7099 12458 7099 12459 6591 12459 7103 12459 7103 12460 6591 12460 7100 12460 7103 12461 7100 12461 6588 12461 6588 12462 7066 12462 7103 12462 7103 12463 7066 12463 7085 12463 7103 12464 7085 12464 6578 12464 6578 12465 7084 12465 7103 12465 7103 12466 7084 12466 6575 12466 7103 12467 6575 12467 7076 12467 7076 12468 6582 12468 7103 12468 7103 12469 6582 12469 7075 12469 7103 12470 7075 12470 7074 12470 7074 12471 7102 12471 7103 12471 7103 12472 7102 12472 6579 12472 7103 12473 6579 12473 7101 12473 7101 12474 6567 12474 7103 12474 7103 12475 6567 12475 7093 12475 7103 12476 7093 12476 6573 12476 6573 12477 7092 12477 7103 12477 7103 12478 7092 12478 7091 12478 7103 12479 7091 12479 6569 12479 6569 12480 7090 12480 7103 12480 7103 12481 7090 12481 7089 12481 7103 12482 7089 12482 7088 12482 7088 12483 7087 12483 7103 12483 7103 12484 7087 12484 7086 12484 7103 12485 7086 12485 7056 12485 7104 12486 7080 12486 6543 12486 6543 12487 7081 12487 7104 12487 7104 12488 7081 12488 7082 12488 7104 12489 7082 12489 6540 12489 6540 12490 7083 12490 7104 12490 7104 12491 7083 12491 6533 12491 7104 12492 6533 12492 7063 12492 7063 12493 7064 12493 7104 12493 7104 12494 7064 12494 6531 12494 7104 12495 6531 12495 7095 12495 7095 12496 6528 12496 7104 12496 7104 12497 6528 12497 7069 12497 7104 12498 7069 12498 6525 12498 6525 12499 7062 12499 7104 12499 7104 12500 7062 12500 7059 12500 7104 12501 7059 12501 7058 12501 7058 12502 7057 12502 7104 12502 7104 12503 7057 12503 6586 12503 7104 12504 6586 12504 7105 12504 7105 12505 6586 12505 7096 12505 7105 12506 7096 12506 7103 12506 7103 12507 7096 12507 6594 12507 7103 12508 6594 12508 7097 12508 7106 12509 6621 12509 4232 12509 4232 12510 7094 12510 7106 12510 7106 12511 7094 12511 6562 12511 7106 12512 6562 12512 7070 12512 7070 12513 6560 12513 7106 12513 7106 12514 6560 12514 7071 12514 7106 12515 7071 12515 7072 12515 7072 12516 6557 12516 7106 12516 7106 12517 6557 12517 7073 12517 7106 12518 7073 12518 6554 12518 6554 12519 7065 12519 7106 12519 7106 12520 7065 12520 7078 12520 7106 12521 7078 12521 6552 12521 6552 12522 7077 12522 7106 12522 7106 12523 7077 12523 6549 12523 7106 12524 6549 12524 7068 12524 7068 12525 6547 12525 7106 12525 7106 12526 6547 12526 7067 12526 7106 12527 7067 12527 7061 12527 7061 12528 7060 12528 7106 12528 7106 12529 7060 12529 6539 12529 7106 12530 6539 12530 7107 12530 7107 12531 6539 12531 7079 12531 7107 12532 7079 12532 7104 12532 7104 12533 7079 12533 6536 12533 7104 12534 6536 12534 7080 12534 7108 12535 7109 12535 7110 12535 7109 12536 6628 12536 6629 12536 7111 12537 7112 12537 7108 12537 7112 12538 7111 12538 6663 12538 7109 12539 6629 12539 7110 12539 7110 12540 6629 12540 6630 12540 7110 12541 6630 12541 7113 12541 7113 12542 6630 12542 6615 12542 7113 12543 6615 12543 7114 12543 7108 12544 7110 12544 7111 12544 7111 12545 7110 12545 7113 12545 7111 12546 7113 12546 7115 12546 7115 12547 7113 12547 7114 12547 7115 12548 7114 12548 7116 12548 7116 12549 7114 12549 7117 12549 7116 12550 7117 12550 7118 12550 7118 12551 7117 12551 7119 12551 7118 12552 7119 12552 7120 12552 6621 12553 7106 12553 6619 12553 6619 12554 7106 12554 7119 12554 6619 12555 7119 12555 6618 12555 6618 12556 7119 12556 7117 12556 6618 12557 7117 12557 6625 12557 6625 12558 7117 12558 7114 12558 6625 12559 7114 12559 6627 12559 6627 12560 7114 12560 6615 12560 7106 12561 7107 12561 7119 12561 7119 12562 7107 12562 7104 12562 7119 12563 7104 12563 7120 12563 7120 12564 7104 12564 7105 12564 7120 12565 7105 12565 7103 12565 6663 12566 7111 12566 6696 12566 6696 12567 7111 12567 7115 12567 6696 12568 7115 12568 6697 12568 6697 12569 7115 12569 7116 12569 6697 12570 7116 12570 6701 12570 6701 12571 7116 12571 7118 12571 6701 12572 7118 12572 6676 12572 6676 12573 7118 12573 7120 12573 6676 12574 7120 12574 6705 12574 6705 12575 7120 12575 7103 12575 6705 12576 7103 12576 6689 12576 81 12577 137 12577 139 12577 81 12578 139 12578 80 12578 80 12579 139 12579 136 12579 80 12580 136 12580 82 12580 82 12581 136 12581 135 12581 82 12582 135 12582 83 12582 83 12583 135 12583 133 12583 83 12583 133 12583 85 12583 85 12584 133 12584 132 12584 85 12584 132 12584 97 12584 89 12585 102 12585 101 12585 89 12585 101 12585 91 12585 91 12586 101 12586 109 12586 91 12586 109 12586 92 12586 92 12587 109 12587 108 12587 92 12588 108 12588 96 12588 96 12589 108 12589 107 12589 96 12590 107 12590 95 12590 95 12591 107 12591 106 12591 95 12591 106 12591 93 12591 176 12592 219 12592 221 12592 176 12592 221 12592 177 12592 177 12593 221 12593 223 12593 177 12594 223 12594 178 12594 178 12595 223 12595 224 12595 178 12596 224 12596 179 12596 179 12597 224 12597 218 12597 179 12597 218 12597 181 12597 181 12598 218 12598 217 12598 181 12598 217 12598 182 12598 174 12599 187 12599 186 12599 174 12599 186 12599 172 12599 172 12600 186 12600 189 12600 172 12600 189 12600 169 12600 169 12601 189 12601 191 12601 169 12602 191 12602 168 12602 168 12603 191 12603 192 12603 168 12604 192 12604 166 12604 166 12605 192 12605 194 12605 166 12606 194 12606 164 12606 6432 12607 6476 12607 7121 12607 6499 12608 6497 12608 7121 12608 7121 12609 6497 12609 6495 12609 7121 12610 6495 12610 6432 12610 6478 12611 6480 12611 6650 12611 6650 12612 6480 12612 6482 12612 6482 12613 6484 12613 6650 12613 6650 12614 6484 12614 6487 12614 6650 12615 6487 12615 6448 12615 6448 12616 6446 12616 6650 12616 6650 12617 6446 12617 6444 12617 6650 12618 6444 12618 210 12618 6467 12619 6469 12619 7122 12619 6467 12620 7122 12620 6442 12620 6449 12621 6428 12621 7122 12621 7122 12622 6428 12622 6440 12622 7122 12623 6440 12623 6442 12623 6469 12624 6470 12624 7122 12624 7122 12625 6470 12625 6471 12625 7122 12626 6471 12626 6425 12626 6425 12627 6439 12627 7121 12627 7121 12628 6439 12628 6438 12628 7121 12629 6438 12629 6436 12629 6436 12630 6434 12630 7121 12630 7121 12631 6434 12631 6500 12631 7121 12632 6500 12632 6499 12632 6454 12633 6452 12633 7122 12633 7122 12634 6452 12634 6450 12634 7122 12635 6450 12635 6449 12635 6459 12636 6457 12636 7122 12636 7122 12637 6457 12637 6456 12637 7122 12638 6456 12638 6454 12638 6472 12639 6463 12639 7123 12639 7123 12640 6463 12640 6461 12640 7123 12641 6461 12641 6459 12641 6523 12642 6475 12642 7123 12642 7123 12643 6475 12643 6473 12643 7123 12644 6473 12644 6472 12644 6505 12645 6507 12645 7123 12645 7123 12646 6507 12646 6509 12646 7123 12647 6509 12647 6511 12647 6511 12648 6512 12648 7123 12648 7123 12649 6512 12649 6514 12649 7123 12650 6514 12650 6517 12650 6517 12651 6519 12651 7123 12651 7123 12652 6519 12652 6521 12652 7123 12653 6521 12653 6523 12653 6422 12654 6421 12654 6698 12654 6698 12655 6421 12655 6420 12655 6420 12656 6490 12656 7123 12656 7123 12657 6490 12657 6492 12657 7123 12658 6492 12658 6493 12658 6493 12659 6501 12659 7123 12659 7123 12660 6501 12660 6503 12660 7123 12661 6503 12661 6505 12661 6420 12662 7123 12662 6698 12662 6698 12663 7123 12663 7124 12663 6698 12664 7124 12664 6699 12664 6699 12665 7124 12665 7125 12665 6699 12666 7125 12666 6667 12666 6667 12667 7125 12667 7126 12667 6667 12668 7126 12668 6674 12668 6459 12669 7122 12669 7123 12669 7123 12670 7122 12670 7127 12670 7123 12671 7127 12671 7124 12671 7124 12672 7127 12672 7128 12672 7124 12673 7128 12673 7125 12673 7125 12674 7128 12674 7129 12674 7125 12675 7129 12675 7126 12675 5698 12676 6670 12676 5693 12676 5693 12677 6670 12677 7130 12677 5693 12678 7130 12678 5691 12678 5691 12679 7130 12679 7131 12679 5691 12680 7131 12680 5704 12680 5704 12681 7131 12681 7132 12681 5704 12682 7132 12682 233 12682 6695 12683 6700 12683 7133 12683 7133 12684 6700 12684 7134 12684 7133 12685 7134 12685 7135 12685 7135 12686 7134 12686 7136 12686 7135 12687 7136 12687 7137 12687 7137 12688 7136 12688 7138 12688 6700 12689 6675 12689 7134 12689 7134 12690 6675 12690 7139 12690 7134 12691 7139 12691 7136 12691 7136 12692 7139 12692 7140 12692 7136 12693 7140 12693 7138 12693 7138 12694 7140 12694 7141 12694 6425 12695 7121 12695 7122 12695 7122 12696 7121 12696 7142 12696 7122 12697 7142 12697 7127 12697 7127 12698 7142 12698 7143 12698 7127 12699 7143 12699 7128 12699 7128 12700 7143 12700 7144 12700 7128 12701 7144 12701 7129 12701 6653 12702 6652 12702 7132 12702 7132 12703 6652 12703 6651 12703 7132 12704 6651 12704 233 12704 7141 12705 6654 12705 7138 12705 7138 12706 6654 12706 6653 12706 7138 12707 6653 12707 7137 12707 7137 12708 6653 12708 7132 12708 7137 12709 7132 12709 7135 12709 7135 12710 7132 12710 7131 12710 7135 12711 7131 12711 7133 12711 7133 12712 7131 12712 7130 12712 7133 12713 7130 12713 6695 12713 6695 12714 7130 12714 6670 12714 6657 12715 6656 12715 7141 12715 7141 12716 6656 12716 6655 12716 7141 12717 6655 12717 6654 12717 6675 12718 6674 12718 7139 12718 7139 12719 6674 12719 7126 12719 7139 12720 7126 12720 7140 12720 7140 12721 7126 12721 7129 12721 7140 12722 7129 12722 7141 12722 7141 12723 7129 12723 7144 12723 7141 12724 7144 12724 6657 12724 6657 12725 7144 12725 7143 12725 6657 12726 7143 12726 6658 12726 6658 12727 7143 12727 7142 12727 6658 12728 7142 12728 6659 12728 6476 12729 6478 12729 7121 12729 7121 12730 6478 12730 6650 12730 7121 12731 6650 12731 7142 12731 7142 12732 6650 12732 6660 12732 7142 12733 6660 12733 6659 12733 7145 12734 7146 12734 7147 12734 7146 12735 7148 12735 7149 12735 7148 12736 6680 12736 6679 12736 4424 12737 4391 12737 7150 12737 4418 12738 4395 12738 7151 12738 6708 12739 6707 12739 4392 12739 4392 12740 6707 12740 7151 12740 4392 12741 7151 12741 4393 12741 4393 12742 7151 12742 4395 12742 4391 12743 4390 12743 7150 12743 7150 12744 4390 12744 4445 12744 7150 12745 4445 12745 4447 12745 4447 12746 4449 12746 7150 12746 7150 12747 4449 12747 4451 12747 7150 12748 4451 12748 7151 12748 4451 12749 4453 12749 7151 12749 7151 12750 4453 12750 4455 12750 7151 12751 4455 12751 4458 12751 4458 12752 4460 12752 7151 12752 7151 12753 4460 12753 4462 12753 7151 12754 4462 12754 4402 12754 4402 12755 4404 12755 7151 12755 7151 12756 4404 12756 4406 12756 7151 12757 4406 12757 4408 12757 4408 12758 4410 12758 7151 12758 7151 12759 4410 12759 4412 12759 7151 12760 4412 12760 4413 12760 4413 12761 4415 12761 7151 12761 7151 12762 4415 12762 4417 12762 7151 12763 4417 12763 4418 12763 4386 12764 4388 12764 7152 12764 7152 12765 4388 12765 4420 12765 7152 12766 4420 12766 4422 12766 4422 12767 4438 12767 7152 12767 7152 12768 4438 12768 4440 12768 7152 12769 4440 12769 7150 12769 7150 12770 4440 12770 4442 12770 7150 12771 4442 12771 4396 12771 4396 12772 4398 12772 7150 12772 7150 12773 4398 12773 4400 12773 7150 12774 4400 12774 4435 12774 4435 12775 4434 12775 7150 12775 7150 12776 4434 12776 4432 12776 7150 12777 4432 12777 4430 12777 4430 12778 4428 12778 7150 12778 7150 12779 4428 12779 4426 12779 7150 12780 4426 12780 4424 12780 6753 12781 156 12781 7152 12781 7152 12782 156 12782 4380 12782 7152 12783 4380 12783 4381 12783 4381 12784 4382 12784 7152 12784 7152 12785 4382 12785 4384 12785 7152 12786 4384 12786 4386 12786 7148 12787 6679 12787 7149 12787 7149 12788 6679 12788 6678 12788 7149 12789 6678 12789 7153 12789 7153 12790 6678 12790 6669 12790 7153 12791 6669 12791 7154 12791 7154 12792 6669 12792 6668 12792 7154 12793 6668 12793 7155 12793 7155 12794 6668 12794 6677 12794 7155 12795 6677 12795 7156 12795 7156 12796 6677 12796 5583 12796 7156 12797 5583 12797 5578 12797 7146 12798 7149 12798 7147 12798 7147 12799 7149 12799 7153 12799 7147 12800 7153 12800 7157 12800 7157 12801 7153 12801 7154 12801 7157 12802 7154 12802 7158 12802 7158 12803 7154 12803 7155 12803 7158 12804 7155 12804 7159 12804 7159 12805 7155 12805 7156 12805 7159 12806 7156 12806 7160 12806 7160 12807 7156 12807 5578 12807 7160 12808 5578 12808 5580 12808 6707 12809 6706 12809 7151 12809 7151 12810 6706 12810 7161 12810 7151 12811 7161 12811 7150 12811 7150 12812 7161 12812 7162 12812 7150 12813 7162 12813 7152 12813 7152 12814 7162 12814 7163 12814 7152 12815 7163 12815 6753 12815 7145 12816 7147 12816 7164 12816 7164 12817 7147 12817 7157 12817 7164 12818 7157 12818 7165 12818 7165 12819 7157 12819 7158 12819 7165 12820 7158 12820 7166 12820 7166 12821 7158 12821 7159 12821 7166 12822 7159 12822 7167 12822 7167 12823 7159 12823 7160 12823 7167 12824 7160 12824 7168 12824 7168 12825 7160 12825 5580 12825 7168 12826 5580 12826 5577 12826 6756 12827 6755 12827 7163 12827 7163 12828 6755 12828 6754 12828 7163 12829 6754 12829 6753 12829 6763 12830 6758 12830 7165 12830 7165 12831 6758 12831 6757 12831 7165 12832 6757 12832 7164 12832 7164 12833 6757 12833 6756 12833 7164 12834 6756 12834 7145 12834 7145 12835 6756 12835 7163 12835 7145 12836 7163 12836 7146 12836 7146 12837 7163 12837 7162 12837 7146 12838 7162 12838 7148 12838 7148 12839 7162 12839 7161 12839 7148 12840 7161 12840 6680 12840 6680 12841 7161 12841 6706 12841 6763 12842 7165 12842 6762 12842 6762 12843 7165 12843 7166 12843 6762 12844 7166 12844 6761 12844 6761 12845 7166 12845 7167 12845 6761 12846 7167 12846 6760 12846 6760 12847 7167 12847 7168 12847 6760 12848 7168 12848 6759 12848 6759 12849 7168 12849 5577 12849 6759 12850 5577 12850 118 12850 7169 12851 7019 12851 7020 12851 7170 12852 7002 12852 7001 12852 7170 12853 7001 12853 7171 12853 7172 12854 7173 12854 7174 12854 7174 12855 7173 12855 7175 12855 7174 12856 7175 12856 7176 12856 7176 12857 7175 12857 7177 12857 7176 12858 7177 12858 7178 12858 7178 12859 7177 12859 7171 12859 7179 12860 7180 12860 7181 12860 7181 12861 7180 12861 7182 12861 7181 12862 7182 12862 7183 12862 7183 12863 7182 12863 7184 12863 7183 12864 7184 12864 7185 12864 7185 12865 7184 12865 7186 12865 7185 12866 7186 12866 7187 12866 7187 12867 7186 12867 7188 12867 7187 12868 7188 12868 7172 12868 7172 12869 7188 12869 7189 12869 7172 12870 7189 12870 7173 12870 7190 12871 7180 12871 7191 12871 7191 12872 7180 12872 7179 12872 7191 12873 7179 12873 7192 12873 7192 12874 7179 12874 7193 12874 7019 12875 7169 12875 7017 12875 7171 12876 7001 12876 7178 12876 7178 12877 7001 12877 7006 12877 7178 12878 7006 12878 7176 12878 7176 12879 7006 12879 7008 12879 7176 12880 7008 12880 7174 12880 7174 12881 7008 12881 7011 12881 7174 12882 7011 12882 7172 12882 7172 12883 7011 12883 7010 12883 7172 12884 7010 12884 7187 12884 7187 12885 7010 12885 7016 12885 7187 12886 7016 12886 7185 12886 7185 12887 7016 12887 7015 12887 7185 12888 7015 12888 7183 12888 7183 12889 7015 12889 7013 12889 7183 12890 7013 12890 7181 12890 7181 12891 7013 12891 7012 12891 7181 12892 7012 12892 7179 12892 7179 12893 7012 12893 7017 12893 7179 12894 7017 12894 7193 12894 7193 12895 7017 12895 7169 12895 7193 12896 7169 12896 7192 12896 7194 12897 6643 12897 6998 12897 7194 12898 6998 12898 7195 12898 7195 12899 6998 12899 7196 12899 7196 12900 6998 12900 6997 12900 7196 12901 6997 12901 7197 12901 7197 12902 6997 12902 7005 12902 7197 12903 7005 12903 7198 12903 7198 12904 7005 12904 7004 12904 7198 12905 7004 12905 7199 12905 7199 12906 7004 12906 7003 12906 7199 12907 7003 12907 7200 12907 7200 12908 7003 12908 7002 12908 7200 12909 7002 12909 7170 12909 7195 12910 6632 12910 7194 12910 7194 12911 6632 12911 6631 12911 7194 12912 6631 12912 6643 12912 6605 12913 4236 12913 4237 12913 6606 12914 6605 12914 7201 12914 6609 12915 6606 12915 7202 12915 6605 12916 4237 12916 7201 12916 7201 12917 4237 12917 4238 12917 7201 12918 4238 12918 7203 12918 4238 12919 4239 12919 7203 12919 7203 12920 4239 12920 4249 12920 7203 12921 4249 12921 7204 12921 7204 12922 4249 12922 4248 12922 7204 12923 4248 12923 7205 12923 6606 12924 7201 12924 7202 12924 7202 12925 7201 12925 7203 12925 7202 12926 7203 12926 7206 12926 7206 12927 7203 12927 7204 12927 7206 12928 7204 12928 7207 12928 7207 12929 7204 12929 7205 12929 7207 12930 7205 12930 7208 12930 6609 12931 7202 12931 7209 12931 7209 12932 7202 12932 7206 12932 7209 12933 7206 12933 7210 12933 7210 12934 7206 12934 7207 12934 7210 12935 7207 12935 7211 12935 7211 12936 7207 12936 7208 12936 7211 12937 7208 12937 7212 12937 6945 12938 6951 12938 7212 12938 7212 12939 6951 12939 6950 12939 7212 12940 6950 12940 7211 12940 7211 12941 6950 12941 6949 12941 7211 12942 6949 12942 7210 12942 7210 12943 6949 12943 6948 12943 7210 12944 6948 12944 7209 12944 7209 12945 6948 12945 6612 12945 7209 12946 6612 12946 6609 12946 6946 12947 6945 12947 7213 12947 7213 12948 6945 12948 7212 12948 7213 12949 7212 12949 7214 12949 7214 12950 7212 12950 7208 12950 7214 12951 7208 12951 7215 12951 7215 12952 7208 12952 7205 12952 7215 12953 7205 12953 4247 12953 4247 12954 7205 12954 4248 12954 4247 12955 4246 12955 7215 12955 7215 12956 4246 12956 7216 12956 7215 12957 7216 12957 7214 12957 7214 12958 7216 12958 7217 12958 7214 12959 7217 12959 7213 12959 7213 12960 7217 12960 7218 12960 7213 12961 7218 12961 6946 12961 6943 12962 6942 12962 7218 12962 7218 12963 6942 12963 6947 12963 7218 12964 6947 12964 6946 12964 4245 12965 4244 12965 7219 12965 7219 12966 4244 12966 7220 12966 7219 12967 7220 12967 7221 12967 7221 12968 7220 12968 7222 12968 7221 12969 7222 12969 7223 12969 7223 12970 7222 12970 7224 12970 4246 12971 4245 12971 7216 12971 7216 12972 4245 12972 7219 12972 7216 12973 7219 12973 7217 12973 7217 12974 7219 12974 7221 12974 7217 12975 7221 12975 7218 12975 7218 12976 7221 12976 7223 12976 7218 12977 7223 12977 6943 12977 6943 12978 7223 12978 7224 12978 6940 12979 6939 12979 7224 12979 7224 12980 6939 12980 6944 12980 7224 12981 6944 12981 6943 12981 4243 12982 4242 12982 7225 12982 7225 12983 4242 12983 7226 12983 7225 12984 7226 12984 7227 12984 7227 12985 7226 12985 7228 12985 7227 12986 7228 12986 7229 12986 7229 12987 7228 12987 7230 12987 4313 12988 7230 12988 4316 12988 4316 12989 7230 12989 7228 12989 4316 12990 7228 12990 4315 12990 4315 12991 7228 12991 7226 12991 4315 12992 7226 12992 4241 12992 4241 12993 7226 12993 4242 12993 4244 12994 4243 12994 7220 12994 7220 12995 4243 12995 7225 12995 7220 12996 7225 12996 7222 12996 7222 12997 7225 12997 7227 12997 7222 12998 7227 12998 7224 12998 7224 12999 7227 12999 7229 12999 7224 13000 7229 13000 6940 13000 6940 13001 7229 13001 7230 13001 6940 13002 7230 13002 6941 13002 6941 13003 7230 13003 4313 13003 6941 13004 4313 13004 4314 13004 7231 13005 7232 13005 7233 13005 6626 13006 4326 13006 4325 13006 6626 13007 4325 13007 6616 13007 6616 13008 4325 13008 4324 13008 6616 13009 4324 13009 6617 13009 6622 13010 7234 13010 6620 13010 6620 13011 7234 13011 7235 13011 4324 13012 7236 13012 6617 13012 6617 13013 7236 13013 7237 13013 6617 13014 7237 13014 6623 13014 6623 13015 7237 13015 7238 13015 6623 13016 7238 13016 6622 13016 6622 13017 7238 13017 4341 13017 6622 13018 4341 13018 7234 13018 7234 13019 4341 13019 4340 13019 7234 13020 4340 13020 7235 13020 7235 13021 4340 13021 4343 13021 7235 13022 4343 13022 7233 13022 4343 13023 4334 13023 7233 13023 7233 13024 4334 13024 4333 13024 7233 13025 4333 13025 7231 13025 7231 13026 4333 13026 4331 13026 7231 13027 4331 13027 7232 13027 7232 13028 4331 13028 7239 13028 7232 13029 7239 13029 7240 13029 6752 13030 6734 13030 7241 13030 7241 13031 6734 13031 7242 13031 7241 13032 7242 13032 7243 13032 7243 13033 7242 13033 7240 13033 7240 13034 7242 13034 7232 13034 7232 13035 7242 13035 7244 13035 7232 13036 7244 13036 7233 13036 7233 13037 7244 13037 7245 13037 7233 13038 7245 13038 7235 13038 6620 13039 7235 13039 6719 13039 6719 13040 7235 13040 7245 13040 6719 13041 7245 13041 6725 13041 6725 13042 7245 13042 7246 13042 7246 13043 7245 13043 7244 13043 7246 13044 7244 13044 7247 13044 7247 13045 7244 13045 7242 13045 7247 13046 7242 13046 7248 13046 7248 13047 7242 13047 6734 13047 7248 13048 6734 13048 6638 13048 7249 13049 6726 13049 6725 13049 6633 13050 6632 13050 7250 13050 6641 13051 6640 13051 7251 13051 6641 13052 7251 13052 6642 13052 6642 13053 7251 13053 7252 13053 6642 13054 7252 13054 6639 13054 7251 13055 7253 13055 7252 13055 7252 13056 7253 13056 7254 13056 7252 13057 7254 13057 7255 13057 7249 13058 7256 13058 7257 13058 7257 13059 7256 13059 7258 13059 7257 13060 7258 13060 7259 13060 7259 13061 7258 13061 7260 13061 7259 13062 7260 13062 7261 13062 7262 13063 7263 13063 7264 13063 7264 13064 7263 13064 7265 13064 7264 13065 7265 13065 7266 13065 7266 13066 7265 13066 7267 13066 7266 13067 7267 13067 7250 13067 7250 13068 7267 13068 7268 13068 7250 13069 7268 13069 6633 13069 6633 13070 7268 13070 6634 13070 7254 13071 7256 13071 7255 13071 7255 13072 7256 13072 7249 13072 7255 13073 7249 13073 7246 13073 7246 13074 7249 13074 6725 13074 7246 13075 7247 13075 7255 13075 7255 13076 7247 13076 7248 13076 7255 13077 7248 13077 7252 13077 7252 13078 7248 13078 6638 13078 7252 13079 6638 13079 6639 13079 7261 13080 6730 13080 7259 13080 7259 13081 6730 13081 6729 13081 7259 13082 6729 13082 7257 13082 7257 13083 6729 13083 6728 13083 7257 13084 6728 13084 7249 13084 7249 13085 6728 13085 6727 13085 7249 13086 6727 13086 6726 13086 6640 13087 6634 13087 7251 13087 7251 13088 6634 13088 7268 13088 7251 13089 7268 13089 7253 13089 7253 13090 7268 13090 7267 13090 7253 13091 7267 13091 7254 13091 7254 13092 7267 13092 7265 13092 7254 13093 7265 13093 7256 13093 7256 13094 7265 13094 7263 13094 7256 13095 7263 13095 7258 13095 7258 13096 7263 13096 7262 13096 7258 13097 7262 13097 7260 13097 7250 13098 6632 13098 7195 13098 7250 13099 7195 13099 7266 13099 7195 13100 7269 13100 7266 13100 7266 13101 7269 13101 7270 13101 7266 13102 7270 13102 7264 13102 7264 13103 7270 13103 7271 13103 7264 13104 7271 13104 7262 13104 7262 13105 7271 13105 7272 13105 7262 13106 7272 13106 7260 13106 7260 13107 7272 13107 7273 13107 7260 13108 7273 13108 7261 13108 7261 13109 7273 13109 6716 13109 7261 13110 6716 13110 6730 13110 6717 13111 6716 13111 7273 13111 7274 13112 7275 13112 7273 13112 7273 13113 7275 13113 7276 13113 7273 13114 7276 13114 6717 13114 7273 13115 7272 13115 7274 13115 7274 13116 7272 13116 7271 13116 7274 13117 7271 13117 7277 13117 7277 13118 7271 13118 7270 13118 7277 13119 7270 13119 7278 13119 7278 13120 7270 13120 7269 13120 7278 13121 7269 13121 7279 13121 7279 13122 7269 13122 7280 13122 7197 13123 7269 13123 7196 13123 7196 13124 7269 13124 7195 13124 7197 13125 7198 13125 7269 13125 7269 13126 7198 13126 7199 13126 7269 13127 7199 13127 7280 13127 7280 13128 7199 13128 7200 13128 7280 13129 7200 13129 7170 13129 7281 13130 7282 13130 7283 13130 7284 13131 4307 13131 7285 13131 7285 13132 4307 13132 4311 13132 7180 13133 7286 13133 7287 13133 7186 13134 7184 13134 7287 13134 7287 13135 7184 13135 7182 13135 7287 13136 7182 13136 7180 13136 7170 13137 7171 13137 7280 13137 7280 13138 7171 13138 7177 13138 7175 13139 7173 13139 7288 13139 7288 13140 7173 13140 7189 13140 7288 13141 7189 13141 7188 13141 7188 13142 7186 13142 7288 13142 7288 13143 7186 13143 7287 13143 7288 13144 7287 13144 7289 13144 7289 13145 7287 13145 7286 13145 7289 13146 7286 13146 7290 13146 7290 13147 7286 13147 7291 13147 7290 13148 7291 13148 7292 13148 7292 13149 7291 13149 7283 13149 7292 13150 7283 13150 7293 13150 7293 13151 7283 13151 7282 13151 4309 13152 6718 13152 4311 13152 4311 13153 6718 13153 7281 13153 4311 13154 7281 13154 7285 13154 7285 13155 7281 13155 7283 13155 7285 13156 7283 13156 7284 13156 7284 13157 7283 13157 7291 13157 7284 13158 7291 13158 7294 13158 7294 13159 7291 13159 7286 13159 7294 13160 7286 13160 7295 13160 7295 13161 7286 13161 7180 13161 7295 13162 7180 13162 7190 13162 6720 13163 6717 13163 7293 13163 7293 13164 6717 13164 7276 13164 7276 13165 7275 13165 7293 13165 7293 13166 7275 13166 7274 13166 7293 13167 7274 13167 7292 13167 7292 13168 7274 13168 7277 13168 7292 13169 7277 13169 7290 13169 7290 13170 7277 13170 7278 13170 7290 13171 7278 13171 7289 13171 7289 13172 7278 13172 7279 13172 7289 13173 7279 13173 7288 13173 7288 13174 7279 13174 7280 13174 7288 13175 7280 13175 7175 13175 7175 13176 7280 13176 7177 13176 6718 13177 6724 13177 7281 13177 7281 13178 6724 13178 6723 13178 7281 13179 6723 13179 7282 13179 7282 13180 6723 13180 6722 13180 7282 13181 6722 13181 7293 13181 7293 13182 6722 13182 6721 13182 7293 13183 6721 13183 6720 13183 7296 13184 604 13184 7297 13184 7297 13185 604 13185 603 13185 7297 13186 603 13186 606 13186 7298 13187 7299 13187 7020 13187 7020 13188 7299 13188 7169 13188 7300 13189 7191 13189 7192 13189 7190 13190 7191 13190 7295 13190 7295 13191 7191 13191 7300 13191 7295 13192 7300 13192 7294 13192 7192 13193 7297 13193 7300 13193 7300 13194 7297 13194 606 13194 7300 13195 606 13195 7294 13195 7294 13196 606 13196 612 13196 7294 13197 612 13197 7284 13197 7284 13198 612 13198 4308 13198 7284 13199 4308 13199 4307 13199 7192 13200 7169 13200 7297 13200 7297 13201 7169 13201 7299 13201 7297 13202 7299 13202 7296 13202 7296 13203 7299 13203 7298 13203 7296 13204 7298 13204 7301 13204 7302 13205 7298 13205 7020 13205 7020 13206 7044 13206 7302 13206 7302 13207 7044 13207 6994 13207 7302 13208 6994 13208 7303 13208 7303 13209 6994 13209 6996 13209 7303 13210 6996 13210 7304 13210 7304 13211 6996 13211 7022 13211 7304 13212 7022 13212 7305 13212 7305 13213 7022 13213 7021 13213 7305 13214 7021 13214 7306 13214 7306 13215 7021 13215 6991 13215 7306 13216 6991 13216 7307 13216 614 13217 616 13217 7307 13217 7307 13218 616 13218 620 13218 7307 13219 620 13219 7306 13219 7306 13220 620 13220 621 13220 7306 13221 621 13221 7305 13221 7305 13222 621 13222 619 13222 7305 13223 619 13223 7304 13223 7304 13224 619 13224 618 13224 7304 13225 618 13225 7303 13225 7303 13226 618 13226 617 13226 7303 13227 617 13227 7302 13227 7302 13228 617 13228 615 13228 7302 13229 615 13229 7298 13229 7298 13230 615 13230 7301 13230 4301 13231 614 13231 7308 13231 7308 13232 614 13232 7307 13232 7308 13233 7307 13233 7049 13233 7049 13234 7307 13234 6991 13234 7243 13235 7309 13235 7241 13235 7243 13236 7240 13236 7309 13236 7309 13237 7240 13237 7239 13237 7309 13238 7239 13238 7310 13238 7310 13239 7239 13239 4331 13239 7310 13240 4331 13240 4329 13240 7311 13241 7312 13241 1377 13241 1377 13242 7312 13242 1379 13242 7313 11388 7314 11388 7315 11388 7315 633 7314 633 7316 633 7315 633 7316 633 7317 633 7318 13243 7319 13243 7315 13243 7315 13244 7319 13244 7320 13244 7315 13245 7320 13245 7313 13245 7321 633 7322 633 7315 633 7315 633 7322 633 7323 633 7315 633 7323 633 7318 633 7317 633 7324 633 7315 633 7315 13246 7324 13246 7325 13246 7315 13247 7325 13247 7321 13247 7326 633 7327 633 7328 633 7328 633 7327 633 7329 633 7328 633 7329 633 7330 633 7330 633 7329 633 7331 633 7332 11383 7333 11383 7334 11383 7332 11384 7334 11384 7335 11384 7335 13248 7334 13248 7336 13248 7335 13249 7336 13249 7337 13249 7333 11377 7332 11377 7338 11377 7333 11378 7338 11378 7339 11378 7339 11379 7338 11379 7340 11379 7339 11380 7340 11380 7341 11380 7341 13250 7340 13250 7342 13250 7341 13251 7342 13251 7343 13251 7344 13252 7345 13252 7346 13252 7344 13253 7346 13253 7347 13253 7347 13254 7346 13254 7348 13254 7347 13255 7348 13255 7349 13255 7349 13256 7348 13256 7336 13256 7336 13257 7348 13257 7337 13257 7343 11367 7342 11367 7350 11367 7351 13258 7352 13258 7350 13258 7350 11369 7352 11369 7353 11369 7350 13259 7353 13259 7343 13259 7354 13260 7355 13260 7356 13260 7354 13261 7356 13261 7357 13261 7357 13262 7356 13262 7345 13262 7357 13263 7345 13263 7344 13263 7358 11343 7359 11343 7360 11343 7358 11344 7360 11344 7361 11344 7361 11345 7360 11345 7362 11345 7361 11346 7362 11346 7363 11346 7363 11347 7362 11347 7364 11347 7363 11347 7364 11347 7365 11347 7365 11350 7364 11350 7366 11350 7365 11350 7366 11350 7367 11350 7367 11351 7366 11351 7368 11351 7367 11351 7368 11351 7369 11351 7369 11352 7368 11352 7370 11352 7369 11353 7370 11353 7371 11353 7371 11354 7370 11354 7372 11354 7371 11355 7372 11355 7373 11355 7373 11356 7372 11356 7374 11356 7373 11357 7374 11357 7375 11357 7375 13264 7374 13264 7376 13264 7375 13265 7376 13265 7377 13265 7377 11361 7376 11361 7378 11361 7377 11361 7378 11361 7379 11361 7379 13266 7378 13266 7380 13266 7379 11362 7380 11362 7381 11362 7382 95 7358 95 7383 95 7345 13267 7356 13267 7355 13267 7355 13268 7384 13268 7385 13268 7348 95 7346 95 7345 95 7381 95 7386 95 7387 95 7387 95 7386 95 7383 95 7383 13269 7386 13269 7388 13269 7383 13270 7388 13270 7382 13270 7355 95 7358 95 7361 95 7355 13271 7385 13271 7358 13271 7358 13272 7385 13272 7389 13272 7358 95 7389 95 7383 95 7373 95 7375 95 7390 95 7377 95 7391 95 7375 95 7375 95 7391 95 7392 95 7375 95 7392 95 7390 95 7387 13273 7393 13273 7381 13273 7381 13274 7393 13274 7394 13274 7381 95 7394 95 7379 95 7379 13275 7394 13275 7395 13275 7379 95 7395 95 7396 95 7371 95 7351 95 7369 95 7369 13276 7351 13276 7350 13276 7369 95 7350 95 7367 95 7367 13277 7350 13277 7342 13277 7367 95 7342 95 7365 95 7365 95 7342 95 7363 95 7390 95 7397 95 7373 95 7373 13278 7397 13278 7398 13278 7373 13279 7398 13279 7371 13279 7371 13280 7398 13280 7399 13280 7371 13281 7399 13281 7351 13281 7351 13282 7399 13282 7400 13282 7351 95 7400 95 7401 95 7396 95 7402 95 7379 95 7379 95 7402 95 7403 95 7379 95 7403 95 7377 95 7377 95 7403 95 7404 95 7377 13283 7404 13283 7391 13283 7338 95 7332 95 7335 95 7361 95 7363 95 7355 95 7355 13284 7363 13284 7342 13284 7355 13285 7342 13285 7345 13285 7345 95 7342 95 7340 95 7345 95 7340 95 7348 95 7348 11342 7340 11342 7338 11342 7348 95 7338 95 7337 95 7337 95 7338 95 7335 95 7405 95 7406 95 7407 95 7407 11321 7406 11321 7408 11321 7407 11320 7408 11320 7409 11320 7410 13286 7411 13286 7407 13286 7407 95 7411 95 7412 95 7407 95 7412 95 7405 95 7413 95 7414 95 7407 95 7407 95 7414 95 7415 95 7407 95 7415 95 7410 95 7409 95 7416 95 7407 95 7407 95 7416 95 7417 95 7407 95 7417 95 7413 95 7415 13287 7418 13287 7410 13287 7410 13288 7418 13288 7419 13288 7410 13289 7419 13289 7411 13289 7411 13290 7419 13290 7420 13290 7411 13291 7420 13291 7412 13291 7412 13292 7420 13292 7421 13292 7412 13293 7421 13293 7405 13293 7405 13294 7421 13294 7422 13294 7405 13295 7422 13295 7406 13295 7406 13296 7422 13296 7423 13296 7406 13297 7423 13297 7408 13297 7408 13298 7423 13298 7424 13298 7408 13299 7424 13299 7409 13299 7409 13300 7424 13300 7425 13300 7409 13301 7425 13301 7416 13301 7416 13302 7425 13302 7426 13302 7416 13303 7426 13303 7417 13303 7417 13304 7426 13304 7427 13304 7417 13305 7427 13305 7413 13305 7413 13306 7427 13306 7428 13306 7413 13307 7428 13307 7414 13307 7414 13308 7428 13308 7429 13308 7414 13308 7429 13308 7415 13308 7415 13309 7429 13309 7418 13309 7430 13310 7431 13310 7432 13310 7432 13311 7433 13311 7430 13311 7430 13312 7433 13312 7434 13312 7430 13313 7434 13313 7435 13313 7436 13314 7437 13314 7438 13314 7439 13315 7440 13315 7438 13315 7438 13316 7440 13316 7441 13316 7438 13317 7441 13317 7436 13317 7431 13318 7442 13318 7432 13318 7432 13319 7442 13319 7439 13319 7432 13320 7439 13320 7443 13320 7443 13321 7439 13321 7438 13321 7444 13322 7445 13322 7446 13322 7447 13323 7448 13323 7449 13323 7450 13324 283 13324 284 13324 7451 13325 256 13325 283 13325 7452 13326 7453 13326 7454 13326 7454 13327 7453 13327 7455 13327 7454 13328 7455 13328 7456 13328 283 13329 7450 13329 7451 13329 7451 13330 7450 13330 7457 13330 7451 13331 7457 13331 7458 13331 7458 13332 7457 13332 7453 13332 7458 13333 7453 13333 7459 13333 7459 13334 7453 13334 7452 13334 7459 13335 7452 13335 7437 13335 7448 13336 7447 13336 7455 13336 7455 13337 7447 13337 7460 13337 7455 13338 7460 13338 7456 13338 7445 13339 7461 13339 7446 13339 7446 13340 7461 13340 7462 13340 7446 13341 7462 13341 7463 13341 7463 13342 7462 13342 7464 13342 7463 13343 7464 13343 7465 13343 7466 13344 7467 13344 7463 13344 7463 13345 7467 13345 7468 13345 7463 13346 7468 13346 7446 13346 7446 13347 7468 13347 7469 13347 7446 13348 7469 13348 7444 13348 7444 13349 7469 13349 7470 13349 7444 13350 7470 13350 7471 13350 7472 13351 7473 13351 7466 13351 7466 13352 7473 13352 7474 13352 7466 13353 7474 13353 7467 13353 7475 13354 7476 13354 7477 13354 7477 13355 7476 13355 7478 13355 7477 13356 7478 13356 7472 13356 7472 13357 7478 13357 7479 13357 7472 13358 7479 13358 7473 13358 285 13359 7476 13359 284 13359 284 13360 7476 13360 7475 13360 284 13361 7475 13361 7450 13361 7450 13362 7475 13362 7477 13362 7450 13363 7477 13363 7457 13363 7457 13364 7477 13364 7472 13364 7457 13365 7472 13365 7453 13365 7453 13366 7472 13366 7466 13366 7453 13367 7466 13367 7455 13367 7455 13368 7466 13368 7463 13368 7455 13369 7463 13369 7448 13369 7448 13370 7463 13370 7465 13370 7448 13371 7465 13371 7449 13371 7480 13372 7481 13372 7482 13372 7483 13373 7484 13373 7485 13373 7486 13374 214 13374 215 13374 7486 13375 215 13375 7487 13375 215 13376 7488 13376 7487 13376 7487 13377 7488 13377 7489 13377 7487 13378 7489 13378 7490 13378 7490 13379 7489 13379 7491 13379 7490 13380 7491 13380 7492 13380 7492 13381 7491 13381 7493 13381 7493 13382 7491 13382 7494 13382 7494 13383 7491 13383 7495 13383 7494 13384 7495 13384 7496 13384 7496 13385 7495 13385 7497 13385 7496 13386 7497 13386 7498 13386 7498 13387 7497 13387 7499 13387 7499 13388 7497 13388 7500 13388 7499 13389 7500 13389 7501 13389 7502 13390 7501 13390 7503 13390 7503 13391 7501 13391 7500 13391 7503 13392 7500 13392 7504 13392 7504 13393 7500 13393 7505 13393 7505 13394 7500 13394 7506 13394 7506 13395 7500 13395 7497 13395 7506 13396 7497 13396 7484 13396 7483 13397 7485 13397 7507 13397 7480 13398 7508 13398 7481 13398 7481 13399 7508 13399 7509 13399 7481 13400 7509 13400 7485 13400 7485 13401 7509 13401 7510 13401 7485 13402 7510 13402 7507 13402 7511 13403 7512 13403 7513 13403 7513 13404 7512 13404 7514 13404 7513 13405 7514 13405 7482 13405 7482 13406 7514 13406 7515 13406 7482 13407 7515 13407 7480 13407 7484 13408 7497 13408 7485 13408 7485 13409 7497 13409 7495 13409 7485 13410 7495 13410 7481 13410 7481 13411 7495 13411 7491 13411 7481 13412 7491 13412 7482 13412 7482 13413 7491 13413 7489 13413 7482 13414 7489 13414 7513 13414 7513 13415 7489 13415 7488 13415 7513 13416 7488 13416 7511 13416 7511 13417 7488 13417 215 13417 7511 13418 215 13418 7512 13418 7512 13419 215 13419 209 13419 7512 13420 209 13420 207 13420 7516 13421 7517 13421 7518 13421 7518 13422 7517 13422 7519 13422 7518 13423 7519 13423 7520 13423 7520 13424 7519 13424 7521 13424 7520 13425 7521 13425 7522 13425 7522 13426 7521 13426 7523 13426 7523 13427 7521 13427 7524 13427 7523 13428 7524 13428 7525 13428 7515 13429 7526 13429 7525 13429 7525 13430 7526 13430 7527 13430 7527 13431 7528 13431 7525 13431 7525 13432 7528 13432 7529 13432 7525 13433 7529 13433 7523 13433 7419 13434 7418 13434 7530 13434 7429 95 7531 95 7418 95 7418 95 7531 95 7532 95 7418 13435 7532 13435 7530 13435 7530 95 7380 95 7419 95 7419 13436 7380 13436 7378 13436 7419 13437 7378 13437 7420 13437 7420 95 7378 95 7376 95 7420 11173 7376 11173 7421 11173 7421 95 7376 95 7374 95 7421 13438 7374 13438 7422 13438 7422 95 7374 95 7372 95 7422 13439 7372 13439 7423 13439 7423 11175 7372 11175 7370 11175 7423 95 7370 95 7424 95 7424 13440 7370 13440 7368 13440 7424 95 7368 95 7425 95 7425 95 7368 95 7366 95 7425 95 7366 95 7426 95 7426 95 7366 95 7364 95 7426 95 7364 95 7427 95 7427 95 7364 95 7362 95 7427 13441 7362 13441 7428 13441 7428 13442 7362 13442 7360 13442 7428 13443 7360 13443 7429 13443 7429 11176 7360 11176 7359 11176 7429 11177 7359 11177 7531 11177 7464 13444 7533 13444 7534 13444 7535 13445 7536 13445 7471 13445 7537 13446 7538 13446 7539 13446 7438 13447 7540 13447 7443 13447 7443 13448 7540 13448 7541 13448 7443 13449 7541 13449 7432 13449 7432 13450 7541 13450 7433 13450 7433 13451 7541 13451 7542 13451 7433 13452 7542 13452 7543 13452 7543 13453 7544 13453 7433 13453 7433 13454 7544 13454 7545 13454 7433 13455 7545 13455 7434 13455 7546 13456 7435 13456 7547 13456 7547 13457 7435 13457 7434 13457 7547 13458 7434 13458 7548 13458 7548 13459 7434 13459 7545 13459 7549 13460 7550 13460 7541 13460 7541 13461 7550 13461 7551 13461 7551 13462 7552 13462 7541 13462 7541 13463 7552 13463 7553 13463 7541 13464 7553 13464 7542 13464 7542 13465 7553 13465 7554 13465 7542 13466 7554 13466 7543 13466 7540 13467 7555 13467 7541 13467 7541 13468 7555 13468 7556 13468 7541 13469 7556 13469 7549 13469 7549 13470 7556 13470 7557 13470 7549 13471 7557 13471 7558 13471 7558 13472 7557 13472 7539 13472 7558 13473 7539 13473 7559 13473 7559 13474 7539 13474 7538 13474 7536 13475 7535 13475 7560 13475 7462 13476 7461 13476 7560 13476 7560 13477 7461 13477 7445 13477 7560 13478 7445 13478 7536 13478 7536 13479 7445 13479 7444 13479 7536 13480 7444 13480 7471 13480 7464 13481 7462 13481 7533 13481 7533 13482 7462 13482 7560 13482 7533 13483 7560 13483 7561 13483 7561 13484 7560 13484 7535 13484 7561 13485 7535 13485 7562 13485 7452 13486 7454 13486 7563 13486 7563 13487 7454 13487 7456 13487 7563 13488 7456 13488 7564 13488 7564 13489 7456 13489 7460 13489 7564 13490 7460 13490 7565 13490 7565 13491 7460 13491 7447 13491 7565 13492 7447 13492 7566 13492 7566 13493 7447 13493 7449 13493 7566 13494 7449 13494 7534 13494 7534 13495 7449 13495 7465 13495 7534 13496 7465 13496 7464 13496 7561 13497 7567 13497 7533 13497 7533 13498 7567 13498 7537 13498 7533 13499 7537 13499 7534 13499 7534 13500 7537 13500 7539 13500 7534 13501 7539 13501 7566 13501 7566 13502 7539 13502 7557 13502 7566 11161 7557 11161 7565 11161 7565 13503 7557 13503 7556 13503 7565 13504 7556 13504 7564 13504 7564 13505 7556 13505 7555 13505 7564 13506 7555 13506 7563 13506 7563 13507 7555 13507 7540 13507 7563 13508 7540 13508 7452 13508 7452 13509 7540 13509 7438 13509 7452 13510 7438 13510 7437 13510 7568 13511 7569 13511 7570 13511 7505 13512 7506 13512 7571 13512 7509 13513 7508 13513 7572 13513 7573 13514 7574 13514 7575 13514 7575 13515 7574 13515 7576 13515 7575 13516 7576 13516 7577 13516 7577 13517 7576 13517 7578 13517 7579 13518 7580 13518 7581 13518 7581 13519 7580 13519 7582 13519 7582 13520 7583 13520 7581 13520 7581 13521 7583 13521 7584 13521 7581 13522 7584 13522 7585 13522 7586 13523 7587 13523 7579 13523 7579 13524 7587 13524 7588 13524 7579 13525 7588 13525 7580 13525 7580 13526 7588 13526 7589 13526 7580 13527 7589 13527 7582 13527 7579 13528 7519 13528 7517 13528 7586 13529 7579 13529 7590 13529 7590 13530 7579 13530 7517 13530 7590 13531 7517 13531 7516 13531 7521 13532 7591 13532 7524 13532 7524 13533 7591 13533 7592 13533 7524 13534 7592 13534 7525 13534 7525 13535 7592 13535 7572 13535 7508 13536 7480 13536 7572 13536 7572 13537 7480 13537 7515 13537 7572 13538 7515 13538 7525 13538 7483 13539 7507 13539 7593 13539 7593 13540 7507 13540 7510 13540 7505 13541 7571 13541 7504 13541 7594 13542 7595 13542 7596 13542 7596 13543 7595 13543 7597 13543 7596 13544 7597 13544 7598 13544 7598 13545 7597 13545 7502 13545 7598 13546 7502 13546 7503 13546 7569 13547 7568 13547 7599 13547 7568 13548 7594 13548 7599 13548 7599 13549 7594 13549 7596 13549 7599 13550 7596 13550 7571 13550 7571 13551 7596 13551 7598 13551 7571 13552 7598 13552 7504 13552 7504 13553 7598 13553 7503 13553 7578 13554 7600 13554 7577 13554 7577 13555 7600 13555 7601 13555 7577 13556 7601 13556 7575 13556 7575 13557 7601 13557 7581 13557 7575 13558 7581 13558 7573 13558 7573 13559 7581 13559 7585 13559 7506 13560 7484 13560 7571 13560 7571 13561 7484 13561 7483 13561 7571 13562 7483 13562 7599 13562 7599 13563 7483 13563 7593 13563 7599 13564 7593 13564 7569 13564 7569 13565 7593 13565 7601 13565 7569 13566 7601 13566 7570 13566 7570 13567 7601 13567 7600 13567 7510 13568 7509 13568 7593 13568 7593 13569 7509 13569 7572 13569 7593 13570 7572 13570 7601 13570 7601 13571 7572 13571 7592 13571 7601 13572 7592 13572 7581 13572 7581 13573 7592 13573 7591 13573 7581 13574 7591 13574 7579 13574 7579 13575 7591 13575 7521 13575 7579 13576 7521 13576 7519 13576 7537 13577 7567 13577 7602 13577 7561 13578 7562 13578 7603 13578 7604 13579 7605 13579 7384 13579 7384 13580 7605 13580 7606 13580 7384 13581 7606 13581 7385 13581 7385 13582 7606 13582 7603 13582 7385 13583 7603 13583 7389 13583 7607 13584 7558 13584 7608 13584 7608 13585 7558 13585 7559 13585 7608 13586 7559 13586 7602 13586 7602 13587 7559 13587 7538 13587 7602 13588 7538 13588 7537 13588 7604 13589 7607 13589 7605 13589 7605 13590 7607 13590 7608 13590 7605 13591 7608 13591 7606 13591 7606 13592 7608 13592 7602 13592 7606 13593 7602 13593 7603 13593 7603 13594 7602 13594 7567 13594 7603 13595 7567 13595 7561 13595 7354 13596 7609 13596 7610 13596 7384 13597 7355 13597 7611 13597 7611 13598 7355 13598 7354 13598 7611 13599 7354 13599 7612 13599 7612 13600 7354 13600 7610 13600 7547 13601 7613 13601 7546 13601 7554 13602 7553 13602 7614 13602 7551 13603 7550 13603 7607 13603 7607 13604 7550 13604 7549 13604 7607 13605 7549 13605 7558 13605 7553 13606 7552 13606 7614 13606 7614 13607 7552 13607 7551 13607 7614 13608 7551 13608 7615 13608 7615 13609 7551 13609 7607 13609 7615 13610 7607 13610 7604 13610 7544 13611 7543 13611 7610 13611 7610 13612 7609 13612 7544 13612 7544 13613 7609 13613 7616 13613 7544 13614 7616 13614 7545 13614 7613 13615 7547 13615 7616 13615 7616 13616 7547 13616 7548 13616 7616 13617 7548 13617 7545 13617 7543 13618 7554 13618 7610 13618 7610 13619 7554 13619 7614 13619 7610 13620 7614 13620 7612 13620 7612 13621 7614 13621 7615 13621 7612 13622 7615 13622 7611 13622 7611 13623 7615 13623 7604 13623 7611 13624 7604 13624 7384 13624 7617 13625 7618 13625 7619 13625 7584 13626 7620 13626 7585 13626 7621 13627 7622 13627 7617 13627 7623 13628 7588 13628 7587 13628 7574 13629 7573 13629 7619 13629 7574 13630 7624 13630 7576 13630 7576 13631 7624 13631 7625 13631 7576 13632 7625 13632 7578 13632 7574 13633 7619 13633 7624 13633 7624 13634 7619 13634 7618 13634 7624 13635 7618 13635 7401 13635 7623 13636 7587 13636 7626 13636 7626 13637 7587 13637 7586 13637 7626 13638 7586 13638 7590 13638 7588 13639 7623 13639 7589 13639 7589 13640 7623 13640 7621 13640 7589 13641 7621 13641 7582 13641 7573 13642 7585 13642 7619 13642 7619 13643 7585 13643 7620 13643 7619 13644 7620 13644 7617 13644 7617 13645 7620 13645 7584 13645 7617 13646 7584 13646 7621 13646 7621 13647 7584 13647 7583 13647 7621 13648 7583 13648 7582 13648 7617 13649 7622 13649 7618 13649 7618 13650 7622 13650 7352 13650 7618 13651 7352 13651 7401 13651 7401 13652 7352 13652 7351 13652 7627 13653 7628 13653 7629 13653 7630 13654 7631 13654 7632 13654 7630 13655 7632 13655 7633 13655 7634 13656 7635 13656 7636 13656 7635 13657 7637 13657 7638 13657 7639 13658 7640 13658 7641 13658 7641 13659 7640 13659 7642 13659 7643 13660 7644 13660 7645 13660 7645 13661 7644 13661 7641 13661 7645 13662 7641 13662 7646 13662 7646 13663 7641 13663 7642 13663 7646 13664 7642 13664 7647 13664 7648 13665 7649 13665 7650 13665 7649 13666 7627 13666 7650 13666 7650 13667 7627 13667 7629 13667 7650 13668 7629 13668 7651 13668 7651 13669 7629 13669 7652 13669 7651 13670 7652 13670 7632 13670 7632 13671 7652 13671 7636 13671 7632 13672 7636 13672 7633 13672 7633 13673 7636 13673 7635 13673 7633 13674 7635 13674 7653 13674 7653 13675 7635 13675 7638 13675 7628 13676 7639 13676 7629 13676 7629 13677 7639 13677 7641 13677 7629 13678 7641 13678 7652 13678 7652 13679 7641 13679 7644 13679 7652 13680 7644 13680 7636 13680 7636 13681 7644 13681 7643 13681 7636 13682 7643 13682 7634 13682 7648 10956 7650 10956 7654 10956 7654 13683 7650 13683 7651 13683 7654 13684 7651 13684 7655 13684 7655 13685 7651 13685 7632 13685 7655 13686 7632 13686 7656 13686 7656 13687 7632 13687 7631 13687 7656 13688 7631 13688 7657 13688 7600 13689 7578 13689 7658 13689 7658 13690 7578 13690 7625 13690 7399 13691 7659 13691 7660 13691 7661 13692 7662 13692 7595 13692 7399 13693 7660 13693 7400 13693 7400 13694 7660 13694 7624 13694 7400 13695 7624 13695 7401 13695 7595 13696 7594 13696 7661 13696 7661 13697 7594 13697 7568 13697 7661 13698 7568 13698 7658 13698 7658 13699 7568 13699 7570 13699 7658 13700 7570 13700 7600 13700 7399 13701 7662 13701 7659 13701 7659 13702 7662 13702 7661 13702 7659 13703 7661 13703 7660 13703 7660 13704 7661 13704 7658 13704 7660 13705 7658 13705 7624 13705 7624 13706 7658 13706 7625 13706 7663 13707 7664 13707 7435 13707 7435 13708 7664 13708 7665 13708 7435 13709 7665 13709 7430 13709 7663 13710 7435 13710 7666 13710 7666 13711 7435 13711 7354 13711 7666 13712 7354 13712 7357 13712 7616 13713 7609 13713 7613 13713 7613 13714 7609 13714 7354 13714 7613 13715 7354 13715 7546 13715 7546 13716 7354 13716 7435 13716 7336 13717 7667 13717 7349 13717 7349 13718 7667 13718 7668 13718 7349 13719 7668 13719 7347 13719 7347 13720 7668 13720 7666 13720 7347 13721 7666 13721 7344 13721 7344 13722 7666 13722 7357 13722 7668 10885 7667 10885 7669 10885 7669 10886 7667 10886 7670 10886 7333 10887 7671 10887 7672 10887 7333 13723 7672 13723 7334 13723 7334 13724 7672 13724 7670 13724 7334 10890 7670 10890 7336 10890 7336 13725 7670 13725 7667 13725 7341 13726 7343 13726 7353 13726 7622 13727 7621 13727 7673 13727 7518 13728 7674 13728 7516 13728 7516 13729 7674 13729 7675 13729 7675 13730 7676 13730 7516 13730 7516 13731 7676 13731 7673 13731 7516 13732 7673 13732 7590 13732 7341 13733 7673 13733 7339 13733 7339 13734 7673 13734 7671 13734 7339 13735 7671 13735 7333 13735 7341 13736 7353 13736 7673 13736 7673 13737 7353 13737 7352 13737 7673 13738 7352 13738 7622 13738 7621 13739 7623 13739 7673 13739 7673 13740 7623 13740 7626 13740 7673 13741 7626 13741 7590 13741 7677 13742 7678 13742 7679 13742 7680 13743 7681 13743 7682 13743 7682 13744 7683 13744 7680 13744 7680 10858 7683 10858 7684 10858 7680 13745 7684 13745 7685 13745 7684 13746 7686 13746 7685 13746 7685 13747 7686 13747 7687 13747 7685 13748 7687 13748 7688 13748 7688 13749 7687 13749 7677 13749 7677 13750 7679 13750 7688 13750 7688 13751 7679 13751 7689 13751 7688 10866 7689 10866 7690 10866 7690 13752 7689 13752 7691 13752 7690 13753 7691 13753 7692 13753 7693 13754 7682 13754 7681 13754 7694 13755 7695 13755 7696 13755 7697 13756 7695 13756 7698 13756 7698 13757 7695 13757 7694 13757 7698 13758 7694 13758 7699 13758 7699 13759 7694 13759 7700 13759 7693 13760 7681 13760 7696 13760 7696 13761 7681 13761 7701 13761 7696 13762 7701 13762 7694 13762 7694 13763 7701 13763 7702 13763 7694 13764 7702 13764 7700 13764 7689 13765 7679 13765 7703 13765 7703 632 7679 632 7678 632 7703 13766 7678 13766 7677 13766 7704 13767 7705 13767 7706 13767 7706 13768 7705 13768 7707 13768 7708 632 7709 632 7703 632 7703 13769 7709 13769 7710 13769 7703 13770 7710 13770 7711 13770 7703 13771 7697 13771 7712 13771 7705 13772 7703 13772 7713 13772 7714 632 7708 632 7715 632 7715 632 7708 632 7703 632 7715 632 7703 632 7716 632 7716 632 7703 632 7705 632 7684 13773 7703 13773 7686 13773 7686 13774 7703 13774 7677 13774 7686 13775 7677 13775 7687 13775 7717 13776 7718 13776 7705 13776 7705 13777 7718 13777 7719 13777 7705 13778 7719 13778 7707 13778 7684 13779 7683 13779 7703 13779 7703 632 7683 632 7682 632 7703 13780 7682 13780 7693 13780 7720 632 7721 632 7712 632 7712 13781 7721 13781 7722 13781 7712 13782 7722 13782 7703 13782 7713 13783 7723 13783 7705 13783 7705 13784 7723 13784 7724 13784 7705 13785 7724 13785 7717 13785 7711 632 7725 632 7703 632 7703 13786 7725 13786 7691 13786 7703 13787 7691 13787 7689 13787 7693 632 7696 632 7703 632 7703 13788 7696 13788 7695 13788 7703 13789 7695 13789 7697 13789 7726 13790 7727 13790 7728 13790 7728 13791 7727 13791 7729 13791 7728 13792 7729 13792 7730 13792 7603 13793 7562 13793 7730 13793 7730 13794 7729 13794 7603 13794 7603 13795 7729 13795 7383 13795 7603 13796 7383 13796 7389 13796 7726 13797 7731 13797 7727 13797 7727 13798 7731 13798 7393 13798 7727 13799 7393 13799 7729 13799 7729 13800 7393 13800 7387 13800 7729 13801 7387 13801 7383 13801 7402 13802 7396 13802 7732 13802 7732 13803 7396 13803 7395 13803 7732 13804 7395 13804 7731 13804 7731 13805 7395 13805 7394 13805 7731 13806 7394 13806 7393 13806 7402 10790 7732 10790 7403 10790 7403 10791 7732 10791 7733 10791 7403 13807 7733 13807 7404 13807 7404 13808 7733 13808 7734 13808 7404 10794 7734 10794 7391 10794 7391 13809 7734 13809 7735 13809 7391 13810 7735 13810 7392 13810 7392 13811 7735 13811 7736 13811 7392 13812 7736 13812 7390 13812 7397 13813 7737 13813 7398 13813 7398 13814 7737 13814 7662 13814 7398 13815 7662 13815 7399 13815 7595 13816 7662 13816 7738 13816 7738 13817 7662 13817 7737 13817 7738 13818 7737 13818 7736 13818 7736 13819 7737 13819 7397 13819 7736 13820 7397 13820 7390 13820 7734 13821 7739 13821 7735 13821 7735 13822 7739 13822 7740 13822 7735 13823 7740 13823 7736 13823 7736 13824 7740 13824 7741 13824 7736 13825 7741 13825 7738 13825 7726 13826 7742 13826 7731 13826 7731 13827 7742 13827 7743 13827 7731 13828 7743 13828 7732 13828 7732 13829 7743 13829 7744 13829 7732 13830 7744 13830 7733 13830 7733 13831 7744 13831 7745 13831 7733 13832 7745 13832 7734 13832 7734 13833 7745 13833 7746 13833 7734 13834 7746 13834 7739 13834 7747 13835 7748 13835 7749 13835 7750 13836 7751 13836 7748 13836 7749 13837 7752 13837 7747 13837 7747 13838 7752 13838 7753 13838 7747 13839 7753 13839 7754 13839 7430 13840 7665 13840 7755 13840 7755 13841 7665 13841 7756 13841 7755 13842 7756 13842 7757 13842 7757 13843 7756 13843 7758 13843 7757 13844 7758 13844 7759 13844 7759 13845 7758 13845 7760 13845 7759 13846 7760 13846 7761 13846 7761 13847 7760 13847 7754 13847 7761 13848 7754 13848 7762 13848 7762 13849 7754 13849 7753 13849 7748 13850 7747 13850 7750 13850 7750 13851 7747 13851 7754 13851 7750 13852 7754 13852 7763 13852 7763 13853 7754 13853 7760 13853 7763 10766 7760 10766 7764 10766 7764 13854 7760 13854 7758 13854 7764 13855 7758 13855 7765 13855 7765 13856 7758 13856 7756 13856 7765 13857 7756 13857 7766 13857 7766 13858 7756 13858 7665 13858 7766 13859 7665 13859 7664 13859 7439 13860 7767 13860 7768 13860 7439 13861 7769 13861 7770 13861 7431 13862 7430 13862 7755 13862 7771 13863 7772 13863 7773 13863 7774 13864 257 13864 7775 13864 7431 13865 7755 13865 7442 13865 7768 13866 7776 13866 7777 13866 7439 13867 7768 13867 7440 13867 7440 13868 7768 13868 7777 13868 7440 13869 7777 13869 7441 13869 7778 13870 7779 13870 7780 13870 7780 13871 7779 13871 7774 13871 7780 13872 7774 13872 7781 13872 7781 13873 7774 13873 7775 13873 7781 13874 7775 13874 7782 13874 7782 13875 7775 13875 7783 13875 7439 13876 7770 13876 7767 13876 7767 13877 7770 13877 7784 13877 7767 13878 7784 13878 7768 13878 7761 13879 7785 13879 7759 13879 7759 13880 7785 13880 7786 13880 7759 13881 7786 13881 7757 13881 7757 13882 7786 13882 7787 13882 7757 13883 7787 13883 7755 13883 7755 13884 7787 13884 7788 13884 7755 13885 7788 13885 7442 13885 7773 13886 7789 13886 7771 13886 7771 13887 7789 13887 7778 13887 7771 13888 7778 13888 7790 13888 7790 13889 7778 13889 7780 13889 7790 13890 7780 13890 7791 13890 7791 13891 7780 13891 7781 13891 7791 13892 7781 13892 7784 13892 7784 13893 7781 13893 7782 13893 7784 13894 7782 13894 7768 13894 7768 13895 7782 13895 7783 13895 7768 13896 7783 13896 7776 13896 7749 13897 7792 13897 7752 13897 7752 13898 7792 13898 7773 13898 7752 13899 7773 13899 7753 13899 7753 13900 7773 13900 7772 13900 7753 13901 7772 13901 7762 13901 7762 13902 7772 13902 7771 13902 7762 13903 7771 13903 7761 13903 7761 13904 7771 13904 7790 13904 7761 13905 7790 13905 7785 13905 7785 13906 7790 13906 7791 13906 7785 13907 7791 13907 7786 13907 7786 13908 7791 13908 7784 13908 7786 13909 7784 13909 7787 13909 7787 13910 7784 13910 7770 13910 7787 13911 7770 13911 7788 13911 7788 13912 7770 13912 7769 13912 7788 13913 7769 13913 7442 13913 7442 13914 7769 13914 7439 13914 7793 13915 7794 13915 7795 13915 7796 13916 7797 13916 288 13916 7798 13917 7799 13917 7800 13917 7801 13918 7802 13918 7803 13918 7803 13919 7802 13919 7804 13919 7803 13920 7804 13920 7805 13920 7805 13921 7804 13921 7798 13921 7805 13922 7798 13922 7806 13922 7806 13923 7798 13923 7800 13923 7806 13924 7800 13924 7807 13924 7808 13925 7809 13925 7801 13925 7801 13926 7809 13926 7810 13926 7801 13927 7810 13927 7802 13927 7796 13928 7808 13928 7797 13928 7797 13929 7808 13929 7801 13929 7797 13930 7801 13930 7811 13930 7811 13931 7801 13931 7793 13931 7794 13932 7812 13932 7795 13932 7795 13933 7812 13933 7813 13933 7795 13934 7813 13934 7814 13934 7814 13935 7813 13935 7815 13935 7816 13936 7817 13936 7815 13936 7815 13937 7817 13937 7818 13937 7815 13938 7818 13938 7814 13938 7815 13939 7819 13939 7816 13939 7816 13940 7819 13940 7820 13940 7816 13941 7820 13941 7821 13941 7637 13942 7821 13942 7638 13942 7638 13943 7821 13943 7820 13943 7638 13944 7820 13944 7653 13944 7653 13945 7820 13945 7633 13945 7822 13946 7657 13946 7823 13946 7823 13947 7657 13947 7631 13947 7824 13948 7825 13948 7826 13948 7826 13949 7825 13949 7827 13949 7826 13950 7827 13950 7828 13950 7828 13951 7827 13951 7829 13951 7828 13952 7829 13952 7830 13952 7830 13953 7829 13953 7831 13953 7830 13954 7831 13954 7832 13954 7630 13955 7633 13955 7832 13955 7832 13956 7633 13956 7820 13956 7832 13957 7820 13957 7830 13957 7830 13958 7820 13958 7819 13958 7830 13959 7819 13959 7828 13959 7828 13960 7819 13960 7815 13960 7828 13961 7815 13961 7826 13961 7826 13962 7815 13962 7813 13962 7826 13963 7813 13963 7824 13963 7824 13964 7813 13964 7812 13964 7793 13965 7801 13965 7794 13965 7794 13966 7801 13966 7803 13966 7794 13967 7803 13967 7812 13967 7812 13968 7803 13968 7805 13968 7812 13969 7805 13969 7824 13969 7824 13970 7805 13970 7806 13970 7824 13971 7806 13971 7825 13971 7825 13972 7806 13972 7807 13972 7825 13973 7807 13973 7827 13973 7827 13974 7807 13974 7833 13974 7827 13975 7833 13975 7829 13975 7829 13976 7833 13976 7822 13976 7829 13977 7822 13977 7831 13977 7831 13978 7822 13978 7823 13978 7831 13979 7823 13979 7832 13979 7832 13980 7823 13980 7631 13980 7832 13981 7631 13981 7630 13981 7807 13982 7800 13982 7656 13982 7656 13983 7800 13983 7834 13983 7656 13984 7834 13984 7655 13984 7807 13985 7656 13985 7833 13985 7833 13986 7656 13986 7657 13986 7833 13987 7657 13987 7822 13987 7648 13988 7835 13988 7836 13988 7836 13989 7835 13989 7837 13989 7836 13990 7837 13990 7838 13990 7838 13991 7837 13991 7839 13991 7839 13992 7837 13992 7840 13992 7839 13993 7840 13993 7841 13993 7841 13994 7840 13994 7842 13994 7841 13995 7842 13995 7843 13995 7844 13996 7845 13996 7846 13996 7846 13997 7845 13997 7847 13997 7846 13998 7847 13998 7848 13998 7848 13999 7847 13999 7834 13999 7848 14000 7834 14000 7799 14000 7799 14001 7834 14001 7800 14001 7845 14002 7842 14002 7847 14002 7847 14003 7842 14003 7840 14003 7847 14004 7840 14004 7834 14004 7834 14005 7840 14005 7837 14005 7834 14006 7837 14006 7655 14006 7655 14007 7837 14007 7835 14007 7655 14008 7835 14008 7654 14008 7654 14009 7835 14009 7648 14009 7849 14010 7850 14010 7851 14010 7852 14011 7853 14011 7854 14011 7855 14012 7856 14012 7857 14012 7857 14013 7856 14013 7858 14013 7857 14014 7858 14014 7859 14014 7859 14015 7858 14015 7860 14015 7860 14016 7858 14016 7861 14016 7860 14017 7861 14017 7862 14017 7863 14018 7864 14018 7865 14018 7852 14019 7854 14019 7866 14019 7866 14020 7854 14020 7867 14020 7866 14021 7867 14021 7868 14021 7869 14022 7870 14022 7871 14022 7871 14023 7870 14023 7872 14023 7871 14024 7872 14024 7873 14024 7855 14025 7874 14025 7856 14025 7856 14026 7874 14026 7875 14026 7856 14027 7875 14027 7858 14027 7858 14028 7875 14028 7876 14028 7858 14029 7876 14029 7861 14029 7877 14030 7862 14030 7878 14030 7878 14031 7862 14031 7861 14031 7878 14032 7861 14032 7879 14032 7879 14033 7861 14033 7876 14033 7879 14034 7876 14034 7864 14034 7864 14035 7876 14035 7880 14035 7864 14036 7880 14036 7865 14036 7865 14037 7880 14037 7881 14037 7874 14038 7851 14038 7875 14038 7875 14039 7851 14039 7850 14039 7875 14040 7850 14040 7869 14040 7869 14041 7850 14041 7849 14041 7869 14042 7849 14042 7870 14042 7870 14043 7849 14043 7882 14043 7870 14044 7882 14044 7872 14044 7871 14045 7868 14045 7869 14045 7869 14046 7868 14046 7867 14046 7869 14047 7867 14047 7875 14047 7875 14048 7867 14048 7854 14048 7875 14049 7854 14049 7876 14049 7876 14050 7854 14050 7853 14050 7876 14051 7853 14051 7880 14051 7880 14052 7853 14052 7852 14052 7880 14053 7852 14053 7881 14053 7883 14054 7884 14054 7885 14054 7886 14055 7884 14055 7887 14055 7887 14056 7884 14056 7883 14056 7887 10522 7883 10522 7888 10522 7888 14057 7883 14057 7889 14057 7888 14058 7889 14058 7890 14058 7890 14059 7889 14059 7891 14059 7890 14060 7891 14060 7892 14060 7892 14061 7891 14061 7893 14061 7893 14062 7891 14062 7894 14062 7893 14063 7894 14063 7895 14063 7896 14064 7663 14064 7666 14064 7664 14065 7663 14065 7766 14065 7766 14066 7663 14066 7896 14066 7766 14067 7896 14067 7897 14067 7751 14068 7750 14068 7898 14068 7898 14069 7750 14069 7763 14069 7898 14070 7763 14070 7899 14070 7899 14071 7763 14071 7764 14071 7899 14072 7764 14072 7897 14072 7897 14073 7764 14073 7765 14073 7897 14074 7765 14074 7766 14074 7668 14075 7895 14075 7666 14075 7666 14076 7895 14076 7894 14076 7666 14077 7894 14077 7896 14077 7896 14078 7894 14078 7891 14078 7896 14079 7891 14079 7897 14079 7897 14080 7891 14080 7889 14080 7897 14081 7889 14081 7899 14081 7899 14082 7889 14082 7883 14082 7899 14083 7883 14083 7898 14083 7898 14084 7883 14084 7885 14084 7898 14085 7885 14085 7751 14085 7900 14086 7901 14086 7902 14086 7903 10486 7672 10486 7671 10486 7904 10487 7669 10487 7670 10487 7905 14087 7901 14087 7906 14087 7906 14088 7901 14088 7900 14088 7906 10490 7900 10490 7907 10490 7907 14089 7900 14089 7908 14089 7907 14090 7908 14090 7909 14090 7909 14091 7908 14091 7910 14091 7909 10494 7910 10494 7911 10494 7911 10495 7910 10495 7903 10495 7911 10496 7903 10496 7912 10496 7912 14092 7903 14092 7671 14092 7886 14093 7887 14093 7902 14093 7902 14094 7887 14094 7913 14094 7902 14095 7913 14095 7900 14095 7900 14096 7913 14096 7914 14096 7900 14097 7914 14097 7908 14097 7908 10503 7914 10503 7915 10503 7908 10504 7915 10504 7910 10504 7910 10505 7915 10505 7904 10505 7910 10506 7904 10506 7903 10506 7903 10507 7904 10507 7670 10507 7903 10508 7670 10508 7672 10508 7668 14098 7669 14098 7895 14098 7895 14099 7669 14099 7904 14099 7895 14100 7904 14100 7893 14100 7893 14101 7904 14101 7915 14101 7893 14102 7915 14102 7892 14102 7892 10514 7915 10514 7914 10514 7892 14103 7914 14103 7890 14103 7890 14104 7914 14104 7913 14104 7890 14105 7913 14105 7888 14105 7888 10518 7913 10518 7887 10518 7916 10453 7917 10453 7918 10453 7918 14106 7917 14106 7919 14106 7919 14107 7917 14107 7920 14107 7920 14108 7917 14108 7921 14108 7920 14109 7921 14109 7922 14109 7922 14110 7921 14110 7923 14110 7922 14111 7923 14111 7924 14111 7925 14112 7673 14112 7676 14112 7912 14113 7671 14113 7673 14113 7673 14114 7925 14114 7912 14114 7912 14115 7925 14115 7926 14115 7912 10464 7926 10464 7911 10464 7911 10465 7926 10465 7909 10465 7909 14116 7926 14116 7927 14116 7909 14117 7927 14117 7907 14117 7907 14118 7927 14118 7928 14118 7907 14119 7928 14119 7906 14119 7918 14120 7929 14120 7916 14120 7916 14121 7929 14121 7930 14121 7916 14122 7930 14122 7931 14122 7905 14123 7906 14123 7931 14123 7931 10474 7906 10474 7928 10474 7931 14124 7928 14124 7916 14124 7916 14125 7928 14125 7927 14125 7916 14126 7927 14126 7917 14126 7917 14127 7927 14127 7926 14127 7917 14128 7926 14128 7921 14128 7921 14129 7926 14129 7925 14129 7921 14130 7925 14130 7923 14130 7923 14131 7925 14131 7676 14131 7923 14132 7676 14132 7924 14132 7924 14133 7676 14133 7675 14133 7932 14134 7723 14134 7713 14134 7723 14135 7932 14135 7724 14135 7724 14136 7932 14136 7933 14136 7724 10400 7933 10400 7717 10400 7717 14137 7933 14137 7934 14137 7717 14138 7934 14138 7718 14138 7718 14139 7934 14139 7935 14139 7718 14140 7935 14140 7719 14140 7705 14141 7704 14141 7936 14141 7936 14142 7704 14142 7706 14142 7936 10407 7706 10407 7935 10407 7935 14143 7706 14143 7707 14143 7935 10409 7707 10409 7719 10409 7705 14144 7936 14144 7716 14144 7716 14145 7936 14145 7937 14145 7716 14146 7937 14146 7715 14146 7715 14147 7937 14147 7938 14147 7715 14148 7938 14148 7714 14148 7714 14149 7938 14149 7939 14149 7714 14150 7939 14150 7708 14150 7940 14151 7941 14151 7942 14151 7709 10418 7708 10418 7942 10418 7942 14152 7708 14152 7939 14152 7942 14153 7939 14153 7940 14153 7940 14154 7939 14154 7938 14154 7940 14155 7938 14155 7943 14155 7943 14156 7938 14156 7937 14156 7943 14157 7937 14157 7944 14157 7944 14158 7937 14158 7936 14158 7944 14159 7936 14159 7945 14159 7945 10427 7936 10427 7935 10427 7945 14160 7935 14160 7946 14160 7946 14161 7935 14161 7934 14161 7946 14162 7934 14162 7947 14162 7947 14163 7934 14163 7933 14163 7947 10432 7933 10432 7948 10432 7948 14164 7933 14164 7932 14164 7948 14165 7932 14165 7949 14165 7949 14166 7932 14166 7950 14166 7949 14167 7950 14167 7951 14167 7951 14168 7950 14168 7952 14168 7951 14169 7952 14169 7953 14169 7953 14170 7952 14170 7954 14170 7953 14171 7954 14171 7955 14171 7712 14172 7697 14172 7698 14172 7699 14173 7955 14173 7698 14173 7698 14174 7955 14174 7954 14174 7698 14175 7954 14175 7712 14175 7712 10445 7954 10445 7952 10445 7712 14176 7952 14176 7720 14176 7720 14177 7952 14177 7950 14177 7720 14178 7950 14178 7721 14178 7721 14179 7950 14179 7932 14179 7721 14180 7932 14180 7722 14180 7722 14181 7932 14181 7713 14181 7722 14182 7713 14182 7703 14182 7692 14183 7956 14183 7957 14183 7957 14184 7958 14184 7959 14184 7959 14185 7958 14185 7942 14185 7959 14186 7942 14186 7941 14186 7692 14187 7691 14187 7956 14187 7956 14188 7691 14188 7725 14188 7956 14189 7725 14189 7711 14189 7957 14190 7956 14190 7958 14190 7958 14191 7956 14191 7711 14191 7958 14192 7711 14192 7942 14192 7942 14193 7711 14193 7710 14193 7942 14194 7710 14194 7709 14194 7692 14195 7960 14195 7690 14195 7690 14196 7960 14196 7961 14196 7690 14197 7961 14197 7688 14197 7688 14198 7961 14198 7962 14198 7688 14199 7962 14199 7685 14199 7685 10370 7962 10370 7963 10370 7685 10371 7963 10371 7680 10371 7680 14200 7963 14200 7964 14200 7680 14201 7964 14201 7681 14201 7681 14202 7964 14202 7965 14202 7960 14203 6709 14203 7961 14203 7961 14204 6709 14204 6710 14204 7961 14205 6710 14205 7962 14205 7962 14206 6710 14206 6711 14206 7962 14207 6711 14207 7963 14207 7963 14208 6711 14208 6673 14208 7963 14209 6673 14209 7964 14209 7964 14210 6673 14210 6672 14210 7964 14211 6672 14211 7965 14211 7965 14212 6672 14212 6671 14212 7700 14213 7966 14213 7699 14213 7699 14214 7966 14214 7967 14214 7699 14215 7967 14215 7968 14215 7969 14216 7970 14216 7971 14216 7971 14217 7970 14217 7965 14217 7971 14218 7965 14218 6671 14218 7681 14219 7965 14219 7701 14219 7701 14220 7965 14220 7970 14220 7701 14221 7970 14221 7702 14221 7702 14222 7970 14222 7969 14222 7702 14223 7969 14223 7700 14223 7700 14224 7969 14224 7972 14224 7700 10364 7972 10364 7966 10364 7743 14225 7973 14225 7974 14225 7975 14226 7976 14226 7977 14226 7739 14227 7978 14227 7740 14227 7979 14228 7595 14228 7738 14228 7980 14229 7981 14229 7979 14229 7979 14230 7981 14230 7982 14230 7982 14231 7502 14231 7979 14231 7979 14232 7502 14232 7597 14232 7979 14233 7597 14233 7595 14233 7738 14234 7741 14234 7979 14234 7979 14235 7741 14235 7983 14235 7979 14236 7983 14236 7980 14236 7980 14237 7983 14237 7984 14237 7980 14238 7984 14238 7985 14238 7874 14239 7855 14239 7986 14239 7882 14240 7849 14240 7987 14240 7987 14241 7849 14241 7851 14241 7987 14242 7851 14242 7874 14242 7988 14243 7989 14243 7990 14243 7990 14244 7989 14244 7873 14244 7990 14245 7873 14245 7987 14245 7987 14246 7873 14246 7872 14246 7987 14247 7872 14247 7882 14247 7874 14248 7986 14248 7987 14248 7987 14249 7986 14249 7985 14249 7987 14250 7985 14250 7990 14250 7990 14251 7985 14251 7984 14251 7990 14252 7984 14252 7988 14252 7988 14253 7984 14253 7983 14253 7988 14254 7983 14254 7991 14254 7991 14255 7983 14255 7992 14255 7991 14256 7992 14256 7993 14256 7973 10290 7994 10290 7974 10290 7974 10291 7994 10291 7995 10291 7974 14257 7995 14257 7996 14257 7997 14258 7998 14258 7996 14258 7996 14259 7998 14259 7999 14259 7996 14260 7999 14260 7974 14260 7974 10296 7999 10296 8000 10296 7974 10297 8000 10297 8001 10297 8001 10298 8000 10298 8002 10298 8001 14261 8002 14261 8003 14261 7975 14262 7977 14262 8004 14262 8004 14263 7977 14263 8005 14263 8004 14264 8005 14264 8006 14264 7646 14265 7647 14265 8007 14265 8007 14266 7647 14266 8008 14266 8007 14267 8008 14267 8009 14267 8009 14268 8008 14268 8010 14268 7634 14269 7643 14269 8007 14269 8007 14270 7643 14270 7645 14270 8007 14271 7645 14271 7646 14271 8011 14272 7637 14272 7635 14272 8006 14273 8005 14273 8010 14273 8010 14274 8005 14274 8012 14274 8010 14275 8012 14275 8009 14275 8009 14276 8012 14276 8011 14276 8009 14277 8011 14277 8007 14277 8007 14278 8011 14278 7635 14278 8007 14279 7635 14279 7634 14279 7471 14280 8013 14280 8014 14280 8013 14281 8015 14281 8014 14281 8014 14282 8015 14282 8016 14282 8014 14283 8016 14283 8005 14283 8005 14284 8016 14284 8017 14284 8005 14285 8017 14285 8012 14285 8012 14286 8017 14286 8018 14286 8012 14287 8018 14287 8011 14287 8014 14288 7728 14288 7730 14288 7471 14289 8014 14289 7535 14289 7535 14290 8014 14290 7730 14290 7535 14291 7730 14291 7562 14291 7728 10330 8014 10330 7726 10330 7726 14292 8014 14292 8005 14292 7726 14293 8005 14293 7742 14293 7742 14294 8005 14294 7977 14294 7742 14295 7977 14295 7743 14295 7743 14296 7977 14296 7976 14296 7743 14297 7976 14297 7973 14297 7973 14298 7976 14298 8019 14298 7973 14299 8019 14299 7994 14299 7978 14300 7739 14300 8003 14300 8003 14301 7739 14301 7746 14301 8003 14302 7746 14302 8001 14302 8001 14303 7746 14303 7745 14303 8001 14304 7745 14304 7974 14304 7974 14305 7745 14305 7744 14305 7974 14306 7744 14306 7743 14306 8002 14307 7993 14307 8003 14307 8003 14308 7993 14308 7992 14308 8003 14309 7992 14309 7978 14309 7978 14310 7992 14310 7983 14310 7978 14311 7983 14311 7740 14311 7740 14312 7983 14312 7741 14312 8020 14313 7848 14313 7799 14313 8021 14314 7846 14314 7848 14314 8021 14315 8022 14315 7846 14315 7846 14316 8022 14316 8023 14316 7846 14317 8023 14317 7844 14317 7844 14318 8023 14318 8024 14318 8025 14319 8026 14319 7802 14319 7802 14320 7810 14320 8025 14320 8025 14321 7810 14321 7809 14321 8025 14322 7809 14322 8027 14322 8027 14323 7809 14323 7808 14323 8027 14324 7808 14324 7796 14324 8028 14325 8029 14325 7804 14325 7804 14326 8029 14326 7798 14326 8021 14327 8030 14327 8022 14327 8022 14328 8030 14328 8031 14328 8022 14329 8031 14329 8023 14329 8023 14330 8031 14330 8032 14330 8023 14331 8032 14331 8024 14331 8033 14332 8034 14332 8035 14332 7804 14333 7802 14333 8028 14333 8028 14334 7802 14334 8026 14334 8028 14335 8026 14335 8036 14335 8036 14336 8026 14336 8025 14336 8036 14337 8025 14337 8037 14337 8037 14338 8025 14338 8027 14338 8037 14339 8027 14339 8038 14339 8038 14340 8027 14340 8039 14340 8038 14341 8039 14341 282 14341 7796 14342 288 14342 8027 14342 8027 14343 288 14343 287 14343 8027 14344 287 14344 8039 14344 8039 14345 287 14345 286 14345 8039 14346 286 14346 282 14346 7848 14347 8020 14347 8021 14347 8021 14348 8020 14348 8040 14348 8021 14349 8040 14349 8030 14349 8030 14350 8040 14350 8035 14350 8030 14351 8035 14351 8031 14351 8031 14352 8035 14352 8034 14352 8031 14353 8034 14353 8032 14353 282 14354 8041 14354 8038 14354 8038 14355 8041 14355 8042 14355 8038 14356 8042 14356 8037 14356 8037 14357 8042 14357 8033 14357 8037 14358 8033 14358 8036 14358 8036 14359 8033 14359 8035 14359 8036 14360 8035 14360 8028 14360 8028 14361 8035 14361 8040 14361 8028 14362 8040 14362 8029 14362 8029 14363 8040 14363 8020 14363 8029 14364 8020 14364 7798 14364 7798 14365 8020 14365 7799 14365 7773 14366 7792 14366 8043 14366 7748 14367 7751 14367 8044 14367 8043 14368 8045 14368 254 14368 8044 14369 8046 14369 8043 14369 8043 14370 8046 14370 8047 14370 8043 14371 8047 14371 8045 14371 8043 14372 7792 14372 8044 14372 8044 14373 7792 14373 7749 14373 8044 14374 7749 14374 7748 14374 254 14375 257 14375 8043 14375 8043 14376 257 14376 7774 14376 8043 14377 7774 14377 7779 14377 7779 14378 7778 14378 8043 14378 8043 14379 7778 14379 7789 14379 8043 14380 7789 14380 7773 14380 7437 14381 7436 14381 7459 14381 7459 14382 7436 14382 8048 14382 7459 14383 8048 14383 7458 14383 257 14384 256 14384 7775 14384 7775 14385 256 14385 8049 14385 7775 14386 8049 14386 8050 14386 7777 14387 7776 14387 8050 14387 8050 14388 7776 14388 7783 14388 8050 14389 7783 14389 7775 14389 256 14390 7451 14390 8049 14390 8049 14391 7451 14391 7458 14391 8049 14392 7458 14392 8050 14392 8050 14393 7458 14393 8048 14393 8050 14394 8048 14394 7777 14394 7777 14395 8048 14395 7436 14395 7777 14396 7436 14396 7441 14396 8051 14397 266 14397 270 14397 8052 14398 8015 14398 8013 14398 8053 14399 8054 14399 7476 14399 7476 14400 8054 14400 7478 14400 8055 14401 7473 14401 8054 14401 8054 14402 7473 14402 7479 14402 8054 14403 7479 14403 7478 14403 7471 14404 7470 14404 8013 14404 8013 14405 7470 14405 7469 14405 8013 14406 7469 14406 8052 14406 8052 14407 7469 14407 7468 14407 8052 14408 7468 14408 8056 14408 8056 14409 7468 14409 7467 14409 8056 14410 7467 14410 8055 14410 8055 14411 7467 14411 7474 14411 8055 14412 7474 14412 7473 14412 8057 14413 8011 14413 8018 14413 7637 14414 8011 14414 7821 14414 7821 14415 8011 14415 8057 14415 7821 14416 8057 14416 7816 14416 7816 14417 8057 14417 8058 14417 8059 14418 7818 14418 8058 14418 8058 14419 7818 14419 7817 14419 8058 14420 7817 14420 7816 14420 7797 14421 7811 14421 8060 14421 8060 14422 7811 14422 7793 14422 8060 14423 7793 14423 8061 14423 8061 14424 7793 14424 7795 14424 8061 14425 7795 14425 8059 14425 8059 14426 7795 14426 7814 14426 8059 14427 7814 14427 7818 14427 8062 14428 277 14428 276 14428 277 14429 8062 14429 270 14429 7476 14430 285 14430 8053 14430 8053 14431 285 14431 267 14431 8053 14432 267 14432 266 14432 266 14433 8051 14433 8053 14433 8053 14434 8051 14434 8063 14434 8053 14435 8063 14435 8054 14435 8054 14436 8063 14436 8064 14436 8054 14437 8064 14437 8055 14437 8055 14438 8064 14438 8065 14438 8055 14439 8065 14439 8056 14439 8056 14440 8065 14440 8066 14440 8056 14441 8066 14441 8052 14441 8052 14442 8066 14442 8016 14442 8052 14443 8016 14443 8015 14443 270 14444 8062 14444 8051 14444 8051 14445 8062 14445 8067 14445 8051 14446 8067 14446 8063 14446 8063 14447 8067 14447 8068 14447 8063 14448 8068 14448 8064 14448 8064 14449 8068 14449 8069 14449 8064 14450 8069 14450 8065 14450 8065 14451 8069 14451 8070 14451 8065 14452 8070 14452 8066 14452 8066 14453 8070 14453 8017 14453 8066 14454 8017 14454 8016 14454 288 14455 7797 14455 276 14455 276 14456 7797 14456 8060 14456 276 14457 8060 14457 8062 14457 8062 14458 8060 14458 8061 14458 8062 14459 8061 14459 8067 14459 8067 14460 8061 14460 8059 14460 8067 14461 8059 14461 8068 14461 8068 14462 8059 14462 8058 14462 8068 14463 8058 14463 8069 14463 8069 14464 8058 14464 8057 14464 8069 14465 8057 14465 8070 14465 8070 14466 8057 14466 8018 14466 8070 14467 8018 14467 8017 14467 8071 14468 8072 14468 8073 14468 7878 14469 8074 14469 7877 14469 7877 14470 8074 14470 8075 14470 7878 14471 8076 14471 8077 14471 8078 14472 8074 14472 8079 14472 8079 14473 8074 14473 7878 14473 8079 14474 7878 14474 8080 14474 8080 14475 7878 14475 8077 14475 8081 14476 8082 14476 8083 14476 8083 14477 8084 14477 8081 14477 8081 14478 8084 14478 8085 14478 8081 14479 8085 14479 8076 14479 8076 14480 8085 14480 8086 14480 8076 14481 8086 14481 8077 14481 8071 14482 8073 14482 8087 14482 8087 14483 8073 14483 8088 14483 8087 14484 8088 14484 8089 14484 8089 14485 8088 14485 8090 14485 8089 14486 8090 14486 8091 14486 7864 14487 7863 14487 8092 14487 8092 14488 7863 14488 8093 14488 8092 14489 8093 14489 8091 14489 8091 14490 8090 14490 8092 14490 8092 14491 8090 14491 7879 14491 8092 14492 7879 14492 7864 14492 7878 14493 7879 14493 8076 14493 8076 14494 7879 14494 8090 14494 8076 14495 8090 14495 8081 14495 8081 14496 8090 14496 8088 14496 8081 14497 8088 14497 8082 14497 8082 14498 8088 14498 8073 14498 8094 14499 8095 14499 8096 14499 8097 14500 8098 14500 8099 14500 8100 14501 8101 14501 8102 14501 8102 14502 8101 14502 8103 14502 7859 14503 7860 14503 8104 14503 8080 14504 8077 14504 8105 14504 8106 14505 8107 14505 8079 14505 8079 14506 8107 14506 8078 14506 7862 14507 7877 14507 8108 14507 8108 14508 7877 14508 8075 14508 8108 14509 8075 14509 8109 14509 8109 14510 8075 14510 8074 14510 8109 14511 8074 14511 8110 14511 8110 14512 8074 14512 8078 14512 8110 14513 8078 14513 8111 14513 8111 14514 8078 14514 8107 14514 8112 14515 7855 14515 7857 14515 8113 14516 8114 14516 8115 14516 8115 14517 8114 14517 8112 14517 8115 14518 8112 14518 8116 14518 8116 14519 8112 14519 7857 14519 8117 14520 8118 14520 8113 14520 8113 14521 8118 14521 8119 14521 8113 14522 8119 14522 8114 14522 8096 14523 8120 14523 8121 14523 196 14524 8122 14524 8123 14524 8123 14525 8122 14525 8124 14525 8123 14526 8124 14526 8125 14526 8125 14527 8124 14527 8120 14527 8125 14528 8120 14528 8126 14528 8126 14529 8120 14529 8096 14529 8126 14530 8096 14530 8127 14530 8127 14531 8096 14531 8128 14531 8128 14532 8096 14532 8095 14532 8128 14533 8095 14533 8129 14533 8097 14534 8099 14534 8105 14534 8121 14535 8100 14535 8096 14535 8096 14536 8100 14536 8102 14536 8096 14537 8102 14537 8094 14537 8094 14538 8102 14538 8103 14538 8094 14539 8103 14539 8117 14539 8117 14540 8103 14540 8130 14540 8117 14541 8130 14541 8118 14541 7860 14542 7862 14542 8104 14542 8104 14543 7862 14543 8108 14543 8104 14544 8108 14544 8131 14544 8131 14545 8108 14545 8109 14545 8131 14546 8109 14546 8132 14546 8132 14547 8109 14547 8110 14547 8132 14548 8110 14548 8133 14548 8133 14549 8110 14549 8111 14549 8133 14550 8111 14550 8134 14550 8134 14551 8111 14551 8107 14551 8134 14552 8107 14552 8099 14552 8099 14553 8107 14553 8106 14553 8099 14554 8106 14554 8105 14554 8105 14555 8106 14555 8079 14555 8105 14556 8079 14556 8080 14556 8098 14557 8129 14557 8099 14557 8099 14558 8129 14558 8095 14558 8099 14559 8095 14559 8134 14559 8134 14560 8095 14560 8094 14560 8134 14561 8094 14561 8133 14561 8133 14562 8094 14562 8117 14562 8133 14563 8117 14563 8132 14563 8132 14564 8117 14564 8113 14564 8132 10066 8113 10066 8131 10066 8131 14565 8113 14565 8115 14565 8131 14566 8115 14566 8104 14566 8104 14567 8115 14567 8116 14567 8104 14568 8116 14568 7859 14568 7859 14569 8116 14569 7857 14569 8135 14570 8136 14570 7518 14570 8137 14571 8138 14571 8139 14571 7520 14572 7522 14572 8140 14572 8141 14573 8142 14573 8143 14573 8143 14574 8142 14574 8144 14574 8145 14575 8146 14575 8147 14575 8147 14576 8146 14576 8148 14576 8147 14577 8148 14577 8149 14577 8150 14578 8151 14578 8152 14578 8153 14579 206 14579 8154 14579 8151 14580 8150 14580 8154 14580 8154 14581 8150 14581 8155 14581 8154 14582 8155 14582 8153 14582 8153 14583 8155 14583 8139 14583 8153 14584 8139 14584 8156 14584 8156 14585 8139 14585 8138 14585 8156 14586 8138 14586 8157 14586 7527 14587 8157 14587 7528 14587 7528 14588 8157 14588 8138 14588 7528 14589 8138 14589 7529 14589 7529 14590 8138 14590 8137 14590 7529 14591 8137 14591 7523 14591 8146 14592 8143 14592 8148 14592 8148 14593 8143 14593 8144 14593 8148 14594 8144 14594 8149 14594 8149 14595 8144 14595 8158 14595 8149 14596 8158 14596 8159 14596 8159 14597 8158 14597 8160 14597 8160 14598 8158 14598 8161 14598 8160 14599 8161 14599 8135 14599 8135 14600 8161 14600 8162 14600 8135 14601 8162 14601 8136 14601 7518 14602 7520 14602 8135 14602 8135 14603 7520 14603 8140 14603 8135 14604 8140 14604 8160 14604 8160 14605 8140 14605 8163 14605 8160 14606 8163 14606 8159 14606 8159 14607 8163 14607 8164 14607 8159 14608 8164 14608 8149 14608 7522 14609 7523 14609 8140 14609 8140 14610 7523 14610 8137 14610 8140 14611 8137 14611 8163 14611 8163 14612 8137 14612 8139 14612 8163 14613 8139 14613 8164 14613 8164 14614 8139 14614 8155 14614 8164 14615 8155 14615 8149 14615 8149 14616 8155 14616 8150 14616 8149 14617 8150 14617 8147 14617 8147 14618 8150 14618 8152 14618 8147 14619 8152 14619 8145 14619 7940 14620 8165 14620 7941 14620 7968 14621 7955 14621 7699 14621 7885 14622 8166 14622 7751 14622 7929 14623 8167 14623 7930 14623 8168 14624 8169 14624 8170 14624 8168 14625 8170 14625 7929 14625 8165 14626 7940 14626 8171 14626 8170 14627 8171 14627 7929 14627 7929 14628 8171 14628 7940 14628 7929 14629 7940 14629 8167 14629 8167 14630 7940 14630 7943 14630 8167 14631 7943 14631 7930 14631 7930 14632 7943 14632 7944 14632 7930 14633 7944 14633 7931 14633 7931 14634 7944 14634 7945 14634 7931 14635 7945 14635 7905 14635 7905 14636 7945 14636 7946 14636 7905 14637 7946 14637 7901 14637 7901 14638 7946 14638 7947 14638 7901 9936 7947 9936 7902 9936 7902 14639 7947 14639 7948 14639 7902 14640 7948 14640 7886 14640 7886 14641 7948 14641 7949 14641 7886 14642 7949 14642 7884 14642 7884 14643 7949 14643 7951 14643 7884 14644 7951 14644 7885 14644 7885 14645 7951 14645 7953 14645 7885 14646 7953 14646 8166 14646 8166 14647 7953 14647 7955 14647 8166 14648 7955 14648 7751 14648 7751 14649 7955 14649 7968 14649 7751 14650 7968 14650 8044 14650 8044 14651 7968 14651 8046 14651 8142 14652 8141 14652 8172 14652 7929 14653 7918 14653 8173 14653 8173 14654 7918 14654 7919 14654 8173 14655 7919 14655 8174 14655 8174 14656 7919 14656 7920 14656 8174 14657 7920 14657 8175 14657 8175 14658 7920 14658 7922 14658 8175 14659 7922 14659 8176 14659 8176 14660 7922 14660 7924 14660 8176 14661 7924 14661 8177 14661 8136 14662 8162 14662 8177 14662 8177 14663 8162 14663 8161 14663 8177 14664 8161 14664 8176 14664 8176 14665 8161 14665 8158 14665 8176 14666 8158 14666 8175 14666 8175 14667 8158 14667 8144 14667 8175 14668 8144 14668 8174 14668 8174 14669 8144 14669 8142 14669 8174 14670 8142 14670 8173 14670 8173 14671 8142 14671 8172 14671 8173 14672 8172 14672 7929 14672 7518 9914 8136 9914 7674 9914 7674 14673 8136 14673 8177 14673 7674 14674 8177 14674 7675 14674 7675 14675 8177 14675 7924 14675 8178 14676 8179 14676 8180 14676 7959 14677 7941 14677 8178 14677 8178 14678 7941 14678 8165 14678 8178 14679 8165 14679 8171 14679 8178 14680 8180 14680 7959 14680 7959 9884 8180 9884 8181 9884 7959 14681 8181 14681 7957 14681 7957 14682 8181 14682 7960 14682 7957 14683 7960 14683 7692 14683 8179 14684 8182 14684 8180 14684 8180 14685 8182 14685 8183 14685 8180 14686 8183 14686 8181 14686 8181 14687 8183 14687 6709 14687 8181 14688 6709 14688 7960 14688 8019 95 7976 95 7327 95 7327 95 7976 95 7975 95 7327 95 7975 95 8004 95 7326 95 7995 95 7327 95 7327 95 7995 95 7994 95 7327 95 7994 95 8019 95 7971 14689 6671 14689 6666 14689 7971 14690 6666 14690 7969 14690 7969 14691 6666 14691 7972 14691 7972 14692 6666 14692 8184 14692 7972 14693 8184 14693 7966 14693 7966 14694 8184 14694 8185 14694 7966 14695 8185 14695 8186 14695 8046 14696 7968 14696 7967 14696 7967 14697 7966 14697 8046 14697 8046 14698 7966 14698 8186 14698 8046 14699 8186 14699 8047 14699 8047 14700 8186 14700 8045 14700 8186 14701 8187 14701 8045 14701 8045 14702 8187 14702 260 14702 8045 14703 260 14703 254 14703 8188 14704 8189 14704 8190 14704 8097 14705 8191 14705 8192 14705 8191 14706 8086 14706 8085 14706 8191 14707 8097 14707 8086 14707 8086 14708 8097 14708 8105 14708 8086 14709 8105 14709 8077 14709 8193 14710 8129 14710 8192 14710 8192 14711 8129 14711 8098 14711 8192 14712 8098 14712 8097 14712 8125 14713 8126 14713 8194 14713 8194 14714 8126 14714 8127 14714 8194 14715 8127 14715 8193 14715 8193 14716 8127 14716 8128 14716 8193 14717 8128 14717 8129 14717 8083 14718 8189 14718 8084 14718 8084 14719 8189 14719 8188 14719 8084 14720 8188 14720 8085 14720 8195 14721 8196 14721 8197 14721 8197 14722 8196 14722 8198 14722 8197 14723 8198 14723 8199 14723 8199 14724 8198 14724 8200 14724 8199 14725 8200 14725 8201 14725 8201 14726 8200 14726 201 14726 8201 14727 201 14727 197 14727 8199 14728 8202 14728 8197 14728 8197 14729 8202 14729 8203 14729 8197 14730 8203 14730 8195 14730 8195 14731 8203 14731 8204 14731 196 14732 8123 14732 197 14732 197 14733 8123 14733 8205 14733 197 14734 8205 14734 8201 14734 8201 14735 8205 14735 8206 14735 8201 14736 8206 14736 8199 14736 8199 14737 8206 14737 8207 14737 8199 14738 8207 14738 8202 14738 8202 14739 8207 14739 8208 14739 8202 14740 8208 14740 8203 14740 8203 14741 8208 14741 8209 14741 8203 14742 8209 14742 8204 14742 8123 14743 8125 14743 8205 14743 8205 14744 8125 14744 8194 14744 8205 14745 8194 14745 8206 14745 8206 14746 8194 14746 8193 14746 8206 14747 8193 14747 8207 14747 8207 14748 8193 14748 8192 14748 8207 14749 8192 14749 8208 14749 8208 14750 8192 14750 8191 14750 8208 14751 8191 14751 8209 14751 8209 14752 8191 14752 8085 14752 8209 14753 8085 14753 8204 14753 8204 14754 8085 14754 8188 14754 8204 14755 8188 14755 8195 14755 8195 14756 8188 14756 8190 14756 8195 14757 8190 14757 8196 14757 8103 14758 8101 14758 8210 14758 8211 14759 198 14759 211 14759 8212 14760 7496 14760 8213 14760 8213 14761 7496 14761 7498 14761 8213 14762 7498 14762 8214 14762 8214 14763 7498 14763 7499 14763 8214 14764 7499 14764 7501 14764 8215 14765 7493 14765 8212 14765 8212 14766 7493 14766 7494 14766 8212 14767 7494 14767 7496 14767 7486 14768 7487 14768 8216 14768 8216 14769 7487 14769 7490 14769 8216 14770 7490 14770 8215 14770 8215 14771 7490 14771 7492 14771 8215 14772 7492 14772 7493 14772 8217 14773 212 14773 213 14773 212 14774 8217 14774 211 14774 8218 14775 195 14775 198 14775 8121 14776 8120 14776 8218 14776 8218 14777 8120 14777 8124 14777 8218 14778 8124 14778 195 14778 195 14779 8124 14779 8122 14779 195 14780 8122 14780 196 14780 8210 14781 8101 14781 8218 14781 8218 14782 8101 14782 8100 14782 8218 14783 8100 14783 8121 14783 8114 14784 8119 14784 8219 14784 8219 14785 8119 14785 8118 14785 8219 14786 8118 14786 8210 14786 8210 14787 8118 14787 8130 14787 8210 14788 8130 14788 8103 14788 8219 14789 8220 14789 8114 14789 8114 14790 8220 14790 8221 14790 8114 14791 8221 14791 8112 14791 8112 14792 8221 14792 7986 14792 8112 14793 7986 14793 7855 14793 7501 14794 7502 14794 8214 14794 8214 14795 7502 14795 7982 14795 8214 14796 7982 14796 7981 14796 198 14797 8211 14797 8218 14797 8218 14798 8211 14798 8222 14798 8218 14799 8222 14799 8210 14799 8210 14800 8222 14800 8223 14800 8210 14801 8223 14801 8219 14801 8219 14802 8223 14802 8224 14802 8219 14803 8224 14803 8220 14803 8220 14804 8224 14804 8225 14804 8220 14805 8225 14805 8221 14805 8221 14806 8225 14806 7985 14806 8221 14807 7985 14807 7986 14807 211 14808 8217 14808 8211 14808 8211 14809 8217 14809 8226 14809 8211 14810 8226 14810 8222 14810 8222 14811 8226 14811 8227 14811 8222 14812 8227 14812 8223 14812 8223 14813 8227 14813 8228 14813 8223 14814 8228 14814 8224 14814 8224 14815 8228 14815 8229 14815 8224 14816 8229 14816 8225 14816 8225 14817 8229 14817 7980 14817 8225 14818 7980 14818 7985 14818 214 14819 7486 14819 213 14819 213 14820 7486 14820 8216 14820 213 14821 8216 14821 8217 14821 8217 14822 8216 14822 8215 14822 8217 14823 8215 14823 8226 14823 8226 14824 8215 14824 8212 14824 8226 14825 8212 14825 8227 14825 8227 14826 8212 14826 8213 14826 8227 14827 8213 14827 8228 14827 8228 14828 8213 14828 8214 14828 8228 14829 8214 14829 8229 14829 8229 14830 8214 14830 7981 14830 8229 14831 7981 14831 7980 14831 7512 14832 207 14832 8230 14832 8230 14833 207 14833 206 14833 8230 14834 8231 14834 7512 14834 7512 14835 8231 14835 8232 14835 7512 14836 8232 14836 7514 14836 7514 14837 8232 14837 7526 14837 7514 14838 7526 14838 7515 14838 206 14839 8153 14839 8230 14839 8230 14840 8153 14840 8156 14840 8230 14841 8156 14841 8231 14841 8231 14842 8156 14842 8157 14842 8231 14843 8157 14843 8232 14843 8232 14844 8157 14844 7527 14844 8232 14845 7527 14845 7526 14845 8169 9705 8168 9705 8233 9705 8233 14846 8168 14846 8234 14846 8233 14847 8234 14847 8235 14847 8235 14848 8234 14848 8236 14848 8146 14849 8145 14849 8234 14849 8234 14850 8145 14850 8152 14850 8234 14851 8152 14851 8151 14851 208 14852 8236 14852 206 14852 206 14853 8236 14853 8234 14853 206 14854 8234 14854 8154 14854 8154 14855 8234 14855 8151 14855 7929 14856 8172 14856 8168 14856 8168 14857 8172 14857 8141 14857 8168 14858 8141 14858 8234 14858 8234 14859 8141 14859 8143 14859 8234 14860 8143 14860 8146 14860 208 14861 210 14861 8236 14861 8236 14862 210 14862 6443 14862 8236 14863 6443 14863 6445 14863 6445 14864 6447 14864 8236 14864 8236 14865 6447 14865 6489 14865 8236 14866 6489 14866 6488 14866 6488 14867 6486 14867 8236 14867 8236 14868 6486 14868 6485 14868 8236 14869 6485 14869 6483 14869 6483 14870 6481 14870 8236 14870 8236 14871 6481 14871 6479 14871 8236 14872 6479 14872 6477 14872 6477 14873 6431 14873 8236 14873 8236 14874 6431 14874 6430 14874 8236 14875 6430 14875 6494 14875 6494 14876 6496 14876 8236 14876 8236 14877 6496 14877 6498 14877 8236 14878 6498 14878 8235 14878 6498 14879 6433 14879 8235 14879 8235 14880 6433 14880 6435 14880 8235 14881 6435 14881 8233 14881 8233 14882 6435 14882 6437 14882 8233 14883 6437 14883 6424 14883 6424 14884 6423 14884 8233 14884 8233 14885 6423 14885 6429 14885 8233 14886 6429 14886 6469 14886 6469 14887 6468 14887 8233 14887 8233 14888 6468 14888 6466 14888 8233 14889 6466 14889 6465 14889 6465 14890 6441 14890 8233 14890 8233 14891 6441 14891 6427 14891 8233 14892 6427 14892 6426 14892 6451 14893 8170 14893 6426 14893 6426 14894 8170 14894 8169 14894 6426 14895 8169 14895 8233 14895 8178 14896 8171 14896 8170 14896 6451 14897 6453 14897 8170 14897 8170 14898 6453 14898 6455 14898 8170 14899 6455 14899 8178 14899 8178 14900 6455 14900 6456 14900 8178 14901 6456 14901 6458 14901 6458 14902 6460 14902 8178 14902 8178 14903 6460 14903 6462 14903 8178 14904 6462 14904 6464 14904 6464 14905 6474 14905 8178 14905 8178 14906 6474 14906 6475 14906 8178 14907 6475 14907 6524 14907 6524 14908 6522 14908 8178 14908 8178 14909 6522 14909 6520 14909 8178 14910 6520 14910 6518 14910 6518 14911 6516 14911 8178 14911 8178 14912 6516 14912 6515 14912 8178 14913 6515 14913 6513 14913 6513 14914 6512 14914 8178 14914 8178 14915 6512 14915 6510 14915 8178 14916 6510 14916 6508 14916 6508 14917 6506 14917 8178 14917 8178 14918 6506 14918 6504 14918 8178 14919 6504 14919 6502 14919 6422 14920 6709 14920 6491 14920 6491 14921 6709 14921 8183 14921 6491 14922 8183 14922 8182 14922 6502 14923 6493 14923 8178 14923 8178 14924 6493 14924 6491 14924 8178 14925 6491 14925 8179 14925 8179 14926 6491 14926 8182 14926 8237 14927 8238 14927 8239 14927 8240 14928 8241 14928 8242 14928 8239 14929 8243 14929 8244 14929 248 14930 8243 14930 249 14930 249 14931 8243 14931 8239 14931 249 14932 8239 14932 8245 14932 8245 14933 8239 14933 8238 14933 8237 14934 8239 14934 8246 14934 8246 14935 8239 14935 8247 14935 8246 14936 8247 14936 8248 14936 8249 14937 8250 14937 8251 14937 8251 14938 8250 14938 8252 14938 8251 14939 8252 14939 8253 14939 8253 14940 8254 14940 8251 14940 8251 14941 8254 14941 8255 14941 8251 14942 8255 14942 8247 14942 8247 14943 8255 14943 8256 14943 8247 14944 8256 14944 8248 14944 8257 14945 8249 14945 8258 14945 8258 14946 8249 14946 8251 14946 8258 14947 8251 14947 8259 14947 8259 14948 8251 14948 8247 14948 8259 14949 8247 14949 8242 14949 8242 14950 8247 14950 8239 14950 8242 14951 8239 14951 8240 14951 8240 14952 8239 14952 8244 14952 8260 14953 8261 14953 8262 14953 8262 14954 8261 14954 8263 14954 8241 14955 8260 14955 8242 14955 8242 14956 8260 14956 8262 14956 8242 14957 8262 14957 8259 14957 8259 14958 8262 14958 8264 14958 8259 14959 8264 14959 8258 14959 8258 14960 8264 14960 8265 14960 8258 14961 8265 14961 8257 14961 8266 14962 8267 14962 8265 14962 8265 14963 8267 14963 8268 14963 8265 14964 8268 14964 8257 14964 8263 14965 8269 14965 8262 14965 8262 14966 8269 14966 8270 14966 8262 14967 8270 14967 8264 14967 8264 14968 8270 14968 8271 14968 8264 14969 8271 14969 8265 14969 8265 14970 8271 14970 8272 14970 8265 14971 8272 14971 8266 14971 8270 14972 8269 14972 8273 14972 8272 14973 8271 14973 8274 14973 8275 9650 8276 9650 8277 9650 8277 14974 8276 14974 8278 14974 8277 14975 8278 14975 8279 14975 8280 14976 8281 14976 8282 14976 8282 9644 8281 9644 8283 9644 8282 14977 8283 14977 8284 14977 8284 14978 8283 14978 8285 14978 8284 14979 8285 14979 8286 14979 8286 9648 8285 9648 8287 9648 8286 14980 8287 14980 8288 14980 8279 14981 8278 14981 8289 14981 8289 14982 8278 14982 8290 14982 8289 14983 8290 14983 8291 14983 8291 14984 8290 14984 8292 14984 8291 14985 8292 14985 8293 14985 8293 14986 8292 14986 8294 14986 8293 14987 8294 14987 8295 14987 8287 14988 8296 14988 8288 14988 8288 14989 8296 14989 8297 14989 8288 14990 8297 14990 8298 14990 8298 14991 8297 14991 8299 14991 8298 14992 8299 14992 8300 14992 8300 14993 8299 14993 8301 14993 8300 14994 8301 14994 8274 14994 8274 14995 8301 14995 8266 14995 8274 14996 8266 14996 8272 14996 8302 9674 8280 9674 8275 9674 8275 14997 8280 14997 8282 14997 8275 9676 8282 9676 8276 9676 8276 14998 8282 14998 8284 14998 8276 14999 8284 14999 8278 14999 8278 15000 8284 15000 8286 15000 8278 15001 8286 15001 8290 15001 8290 15002 8286 15002 8288 15002 8290 15003 8288 15003 8292 15003 8292 15004 8288 15004 8298 15004 8292 15005 8298 15005 8294 15005 8294 15006 8298 15006 8300 15006 8294 15007 8300 15007 8303 15007 8303 15008 8300 15008 8274 15008 8303 15009 8274 15009 8273 15009 8273 15010 8274 15010 8271 15010 8273 15011 8271 15011 8270 15011 8295 15012 8294 15012 8304 15012 8304 15013 8294 15013 8303 15013 8304 15014 8303 15014 8305 15014 8305 15015 8303 15015 8273 15015 8305 15016 8273 15016 8306 15016 8306 15017 8273 15017 8269 15017 8306 15018 8269 15018 8263 15018 8307 15019 8308 15019 8309 15019 8310 15020 8311 15020 8312 15020 8312 15021 8311 15021 8313 15021 8312 15022 8313 15022 8314 15022 8315 15023 8316 15023 8317 15023 8317 15024 8316 15024 8318 15024 8317 15025 8318 15025 8310 15025 8310 15026 8318 15026 8319 15026 8310 15027 8319 15027 8311 15027 8320 15028 8315 15028 204 15028 204 15029 8315 15029 8317 15029 204 15030 8317 15030 203 15030 203 15031 8317 15031 8321 15031 923 15032 8321 15032 922 15032 922 15033 8321 15033 8317 15033 922 15034 8317 15034 920 15034 920 15035 8317 15035 8310 15035 920 15036 8310 15036 1382 15036 1382 15037 8310 15037 8312 15037 1382 15038 8312 15038 1356 15038 1356 15039 8312 15039 8322 15039 1356 15040 8322 15040 1357 15040 8314 15041 8307 15041 8312 15041 8312 15042 8307 15042 8309 15042 8312 15043 8309 15043 8322 15043 8322 15044 8309 15044 8323 15044 8322 15045 8323 15045 8324 15045 1364 15046 1360 15046 8322 15046 8322 15047 1360 15047 1359 15047 8322 15048 1359 15048 1357 15048 1363 15049 8325 15049 8326 15049 8326 15050 8327 15050 1363 15050 1363 15051 8327 15051 8328 15051 1363 15052 8328 15052 1361 15052 8329 15053 8330 15053 8325 15053 8325 15054 8330 15054 8331 15054 8325 15055 8331 15055 8326 15055 1363 15056 1364 15056 8325 15056 8325 15057 1364 15057 8322 15057 8325 15058 8322 15058 8329 15058 8329 15059 8322 15059 8324 15059 8332 15060 8333 15060 8334 15060 8335 15061 1353 15061 1361 15061 8336 9577 8337 9577 8338 9577 8338 15062 8337 15062 8339 15062 8338 15063 8339 15063 8340 15063 8340 15064 8339 15064 8341 15064 8340 15065 8341 15065 8342 15065 8343 9582 8336 9582 8344 9582 8344 15066 8336 15066 8338 15066 8344 15067 8338 15067 8345 15067 8345 9585 8338 9585 8340 9585 8345 15068 8340 15068 8346 15068 8346 15069 8340 15069 8342 15069 8346 15070 8342 15070 8347 15070 8347 15071 8348 15071 8346 15071 8346 15072 8348 15072 8349 15072 8346 9591 8349 9591 8345 9591 8345 15073 8349 15073 8344 15073 8350 15074 8351 15074 8347 15074 8347 9594 8351 9594 8352 9594 8347 15075 8352 15075 8348 15075 1361 15076 8353 15076 8335 15076 8335 15077 8353 15077 8354 15077 8335 15078 8354 15078 8355 15078 8355 15079 8354 15079 8334 15079 8355 15080 8334 15080 8356 15080 8356 15081 8334 15081 8333 15081 8356 15082 8333 15082 8357 15082 8332 15083 8334 15083 8358 15083 8358 15084 8334 15084 8354 15084 8358 9605 8354 9605 8359 9605 8359 15085 8354 15085 8353 15085 8359 15086 8353 15086 8360 15086 1361 15087 8328 15087 8353 15087 8353 15088 8328 15088 8327 15088 8353 15089 8327 15089 8360 15089 8360 15090 8327 15090 8326 15090 8360 15091 8326 15091 8331 15091 8341 15092 8357 15092 8342 15092 8342 15093 8357 15093 8333 15093 8342 15094 8333 15094 8347 15094 8347 15095 8333 15095 8332 15095 8347 15096 8332 15096 8350 15096 8350 15097 8332 15097 8358 15097 8350 9619 8358 9619 8361 9619 8361 15098 8358 15098 8359 15098 8361 15099 8359 15099 8362 15099 8362 15100 8359 15100 8360 15100 8362 15101 8360 15101 8363 15101 8363 15102 8360 15102 8331 15102 8363 15103 8331 15103 8330 15103 8263 15104 8364 15104 8306 15104 8306 15105 8364 15105 8365 15105 8306 15106 8365 15106 8305 15106 8291 15107 8293 15107 8366 15107 8366 15108 8293 15108 8295 15108 8366 15109 8295 15109 8365 15109 8365 15110 8295 15110 8304 15110 8365 15111 8304 15111 8305 15111 8367 15112 8302 15112 8275 15112 8275 15113 8277 15113 8367 15113 8367 15114 8277 15114 8279 15114 8367 15115 8279 15115 8366 15115 8366 15116 8279 15116 8289 15116 8366 15117 8289 15117 8291 15117 8341 15118 8339 15118 1355 15118 8336 15119 8343 15119 1368 15119 1355 15120 8339 15120 1368 15120 1368 15121 8339 15121 8337 15121 1368 15122 8337 15122 8336 15122 1354 15123 8356 15123 1355 15123 1355 15124 8356 15124 8357 15124 1355 15125 8357 15125 8341 15125 1353 15126 8335 15126 1354 15126 1354 15127 8335 15127 8355 15127 1354 15128 8355 15128 8356 15128 1380 15129 1379 15129 7312 15129 8367 15130 4147 15130 4150 15130 1380 15131 7312 15131 4140 15131 7312 15132 8368 15132 4140 15132 4140 15133 8368 15133 8369 15133 4140 15134 8369 15134 4141 15134 4141 15135 8369 15135 8370 15135 4141 15136 8370 15136 4150 15136 4150 15137 8370 15137 8371 15137 4150 15138 8371 15138 8367 15138 7312 9533 8372 9533 8373 9533 8370 15139 8369 15139 8374 15139 8374 15140 8375 15140 8370 15140 8370 15141 8375 15141 8376 15141 8370 9537 8376 9537 8371 9537 8371 15142 8376 15142 8377 15142 8371 9539 8377 9539 8378 9539 7312 15143 8373 15143 8368 15143 8368 15144 8373 15144 8379 15144 8368 15145 8379 15145 8369 15145 8369 15146 8379 15146 8380 15146 8369 15147 8380 15147 8374 15147 8381 15148 1374 15148 1371 15148 8381 15149 1371 15149 8382 15149 8382 15150 1371 15150 1370 15150 8382 15151 1370 15151 8383 15151 8383 15152 1370 15152 1372 15152 8383 15153 1372 15153 8384 15153 8384 15154 1372 15154 1373 15154 8384 15155 1373 15155 1369 15155 1374 15156 8381 15156 1375 15156 1375 15157 8381 15157 7311 15157 1375 15158 7311 15158 1377 15158 8385 9512 8386 9512 8384 9512 8384 15159 8386 15159 8387 15159 8384 15160 8387 15160 8383 15160 8388 15161 7311 15161 8389 15161 8389 15162 7311 15162 8381 15162 8389 15163 8381 15163 8382 15163 8387 15164 8390 15164 8383 15164 8383 15165 8390 15165 8391 15165 8383 15166 8391 15166 8382 15166 8382 15167 8391 15167 8392 15167 8382 15168 8392 15168 8389 15168 8260 15169 4153 15169 8261 15169 8261 15170 4153 15170 4151 15170 4151 95 4152 95 8261 95 8261 95 4152 95 8364 95 8261 95 8364 95 8263 95 8393 15171 8394 15171 8395 15171 8393 9501 8395 9501 8396 9501 8396 9502 8395 9502 8397 9502 8396 15172 8397 15172 8398 15172 8398 9504 8397 9504 8399 9504 8398 9505 8399 9505 8400 9505 8400 15173 8399 15173 8401 15173 8400 9507 8401 9507 8402 9507 8402 9508 8401 9508 8403 9508 8402 9509 8403 9509 8404 9509 8404 9510 8403 9510 8405 9510 8404 9511 8405 9511 8406 9511 8406 9488 8405 9488 8407 9488 8406 9489 8407 9489 8408 9489 8408 9490 8407 9490 8409 9490 8408 9491 8409 9491 8410 9491 8410 15174 8409 15174 8411 15174 8410 9493 8411 9493 8412 9493 8412 15175 8411 15175 8413 15175 8412 15176 8413 15176 8414 15176 8414 9496 8413 9496 8415 9496 8414 9497 8415 9497 8416 9497 8416 15177 8415 15177 8394 15177 8416 15178 8394 15178 8393 15178 8041 15179 282 15179 281 15179 8417 15180 8418 15180 7844 15180 7844 15181 8024 15181 8417 15181 8417 9479 8024 9479 8032 9479 8417 15182 8032 15182 8419 15182 8032 15183 8034 15183 8419 15183 8419 15184 8034 15184 8033 15184 8419 15185 8033 15185 8420 15185 281 15186 8421 15186 8041 15186 8041 15187 8421 15187 8420 15187 8041 15187 8420 15187 8042 15187 8042 15188 8420 15188 8033 15188 8189 15189 8083 15189 8422 15189 8423 15190 199 15190 201 15190 201 15191 8200 15191 8423 15191 8423 15192 8200 15192 8198 15192 8423 15193 8198 15193 8424 15193 8424 15194 8198 15194 8196 15194 8424 15195 8196 15195 8425 15195 8422 15196 8426 15196 8189 15196 8189 15197 8426 15197 8425 15197 8189 15198 8425 15198 8190 15198 8190 15199 8425 15199 8196 15199 8427 15200 8428 15200 8429 15200 8430 15201 8425 15201 8431 15201 8425 15202 8430 15202 8424 15202 200 15203 8432 15203 205 15203 199 15204 8423 15204 8433 15204 8434 15205 8435 15205 8436 15205 199 15206 8433 15206 200 15206 200 15207 8433 15207 8429 15207 200 15208 8429 15208 8432 15208 8432 15209 8429 15209 8428 15209 8432 15210 8428 15210 205 15210 8426 15211 8422 15211 8437 15211 8437 15212 8422 15212 8438 15212 8437 15213 8438 15213 8439 15213 8439 15214 8438 15214 8440 15214 8439 15215 8440 15215 8441 15215 8425 15216 8426 15216 8431 15216 8431 15217 8426 15217 8437 15217 8431 15218 8437 15218 8442 15218 8442 15219 8437 15219 8439 15219 8442 15220 8439 15220 8443 15220 8443 15221 8439 15221 8441 15221 8443 15222 8441 15222 8444 15222 8423 15223 8436 15223 8433 15223 8433 15224 8436 15224 8435 15224 8433 15225 8435 15225 8429 15225 8429 15226 8435 15226 8445 15226 8429 15227 8445 15227 8427 15227 8446 15228 8447 15228 8448 15228 8448 15229 8447 15229 8449 15229 8448 15230 8449 15230 8450 15230 8450 15231 8449 15231 8451 15231 8450 15232 8451 15232 8434 15232 8434 15233 8451 15233 8452 15233 8434 15234 8452 15234 8435 15234 8435 15235 8452 15235 8453 15235 8435 15236 8453 15236 8445 15236 8454 15237 8446 15237 8455 15237 8455 15238 8446 15238 8448 15238 8455 15239 8448 15239 8456 15239 8456 15240 8448 15240 8450 15240 8456 15241 8450 15241 8457 15241 8457 15242 8450 15242 8434 15242 8423 15243 8424 15243 8436 15243 8436 15244 8424 15244 8430 15244 8436 15245 8430 15245 8434 15245 8434 15246 8430 15246 8431 15246 8434 15247 8431 15247 8457 15247 8457 15248 8431 15248 8442 15248 8457 15249 8442 15249 8456 15249 8456 15250 8442 15250 8443 15250 8456 15251 8443 15251 8455 15251 8455 15252 8443 15252 8444 15252 8455 15253 8444 15253 8454 15253 8458 15254 8459 15254 8308 15254 8458 15255 8308 15255 8460 15255 8461 15256 8462 15256 8314 15256 8308 15257 8307 15257 8460 15257 8460 15258 8307 15258 8314 15258 8460 15259 8314 15259 8463 15259 8463 15260 8314 15260 8462 15260 8319 15261 8464 15261 8465 15261 8314 15262 8313 15262 8461 15262 8461 15263 8313 15263 8311 15263 8461 15264 8311 15264 8466 15264 8466 15265 8311 15265 8319 15265 8466 15266 8319 15266 8467 15266 8467 15267 8319 15267 8465 15267 8468 15268 8469 15268 8316 15268 8316 15269 8469 15269 8470 15269 8316 15270 8470 15270 8471 15270 8464 15271 8319 15271 8471 15271 8471 15272 8319 15272 8318 15272 8471 15273 8318 15273 8316 15273 8320 15274 8472 15274 8473 15274 8320 15275 8473 15275 8315 15275 8315 15276 8473 15276 8474 15276 8315 15277 8474 15277 8316 15277 8316 15278 8474 15278 8475 15278 8316 15279 8475 15279 8468 15279 8472 15280 8320 15280 8476 15280 8476 15281 8320 15281 204 15281 8476 15282 204 15282 205 15282 8477 15283 8478 15283 8237 15283 8237 15284 8478 15284 8238 15284 8238 15285 8478 15285 8479 15285 8238 15286 8479 15286 8245 15286 8245 15287 8479 15287 8480 15287 8245 15288 8480 15288 249 15288 249 15289 8480 15289 8481 15289 249 15290 8481 15290 250 15290 8482 15291 8483 15291 8248 15291 8483 15292 8484 15292 8248 15292 8248 15293 8484 15293 8485 15293 8248 15294 8485 15294 8246 15294 8246 15295 8485 15295 8486 15295 8246 15296 8486 15296 8237 15296 8237 15297 8486 15297 8487 15297 8237 15298 8487 15298 8477 15298 8248 15299 8256 15299 8482 15299 8482 15300 8256 15300 8255 15300 8482 15301 8255 15301 8488 15301 8252 15302 8489 15302 8253 15302 8253 15303 8489 15303 8488 15303 8253 15304 8488 15304 8254 15304 8254 15305 8488 15305 8255 15305 8490 15306 8491 15306 8417 15306 8492 15307 8493 15307 8494 15307 8494 15308 8493 15308 8495 15308 8494 15309 8495 15309 8496 15309 8494 15310 8497 15310 8492 15310 8492 15311 8497 15311 8498 15311 8492 15312 8498 15312 8499 15312 8499 15313 8498 15313 8500 15313 8421 15314 281 15314 280 15314 8501 15315 8502 15315 8490 15315 8501 15316 8503 15316 8504 15316 8502 15317 8501 15317 8505 15317 8505 15318 8501 15318 8504 15318 8505 15319 8504 15319 8506 15319 268 15320 8507 15320 280 15320 280 15321 8507 15321 8508 15321 280 15322 8508 15322 8421 15322 8421 15323 8508 15323 8509 15323 8421 15324 8509 15324 8420 15324 8420 15325 8509 15325 8510 15325 8420 15326 8510 15326 8419 15326 8496 15327 8511 15327 8494 15327 8494 15328 8511 15328 8512 15328 8494 15329 8512 15329 8497 15329 8497 15330 8512 15330 8513 15330 8497 15331 8513 15331 8498 15331 8498 15332 8513 15332 8514 15332 8498 15333 8514 15333 8500 15333 8418 15334 8417 15334 8496 15334 8496 15335 8417 15335 8491 15335 8496 15336 8491 15336 8511 15336 8511 15337 8491 15337 8490 15337 8511 15338 8490 15338 8512 15338 8512 15339 8490 15339 8502 15339 8512 15340 8502 15340 8513 15340 8513 15341 8502 15341 8505 15341 8513 15342 8505 15342 8514 15342 8514 15343 8505 15343 8506 15343 8503 15344 8501 15344 8515 15344 8515 15345 8501 15345 8516 15345 8515 15346 8516 15346 8517 15346 8517 15347 8516 15347 8518 15347 8517 15348 8518 15348 250 15348 268 15349 250 15349 8507 15349 8507 15350 250 15350 8518 15350 8507 15351 8518 15351 8508 15351 8508 15352 8518 15352 8516 15352 8508 15353 8516 15353 8509 15353 8509 15354 8516 15354 8501 15354 8509 15355 8501 15355 8510 15355 8510 15356 8501 15356 8490 15356 8510 15357 8490 15357 8419 15357 8419 15358 8490 15358 8417 15358 8519 15359 8520 15359 8521 15359 8446 15360 8454 15360 8522 15360 8449 15361 8447 15361 8523 15361 8524 15362 8451 15362 8525 15362 8445 15363 8453 15363 8526 15363 8451 15364 8524 15364 8452 15364 8471 15365 8465 15365 8464 15365 8469 15366 8468 15366 8527 15366 8474 15367 8473 15367 8528 15367 8528 15368 8529 15368 8474 15368 8474 15369 8529 15369 8527 15369 8474 15370 8527 15370 8475 15370 8475 15371 8527 15371 8468 15371 8462 15372 8530 15372 8463 15372 8463 15373 8530 15373 8521 15373 8463 15374 8521 15374 8460 15374 8460 15375 8521 15375 8520 15375 8460 15376 8520 15376 8458 15376 8458 15377 8520 15377 8519 15377 8458 15378 8519 15378 8459 15378 8470 15379 8531 15379 8471 15379 8471 15380 8531 15380 8532 15380 8471 15381 8532 15381 8465 15381 8465 15382 8532 15382 8533 15382 8465 15383 8533 15383 8467 15383 8467 15384 8533 15384 8534 15384 8467 15385 8534 15385 8466 15385 8466 15386 8534 15386 8461 15386 8476 15387 205 15387 8535 15387 8535 15388 205 15388 8428 15388 8535 15389 8428 15389 8427 15389 8427 15390 8445 15390 8535 15390 8535 15391 8445 15391 8526 15391 8535 15392 8526 15392 8536 15392 8536 15393 8526 15393 8537 15393 8453 15394 8452 15394 8526 15394 8526 15395 8452 15395 8524 15395 8526 15396 8524 15396 8537 15396 8537 15397 8524 15397 8525 15397 8537 15398 8525 15398 8538 15398 8538 15399 8539 15399 8540 15399 8476 15400 8535 15400 8472 15400 8472 15401 8535 15401 8536 15401 8472 15402 8536 15402 8473 15402 8473 15403 8536 15403 8537 15403 8473 15404 8537 15404 8528 15404 8528 15405 8537 15405 8538 15405 8528 15406 8538 15406 8529 15406 8529 15407 8538 15407 8540 15407 8529 15408 8540 15408 8527 15408 8541 15409 8542 15409 8543 15409 8462 15410 8461 15410 8543 15410 8543 15411 8461 15411 8534 15411 8543 15412 8534 15412 8541 15412 8541 15413 8534 15413 8533 15413 8541 15414 8533 15414 8539 15414 8539 15415 8533 15415 8532 15415 8539 15416 8532 15416 8540 15416 8540 15417 8532 15417 8531 15417 8540 15418 8531 15418 8527 15418 8527 15419 8531 15419 8470 15419 8527 15420 8470 15420 8469 15420 8447 15421 8446 15421 8523 15421 8523 15422 8446 15422 8522 15422 8523 15423 8522 15423 8544 15423 8544 15424 8522 15424 8545 15424 8544 15425 8545 15425 8546 15425 8546 15426 8545 15426 8547 15426 8546 15427 8547 15427 8548 15427 8548 15428 8547 15428 8549 15428 8548 15429 8549 15429 8550 15429 8550 15430 8549 15430 8551 15430 8550 15431 8551 15431 8552 15431 8552 15432 8551 15432 8553 15432 8462 15433 8543 15433 8530 15433 8530 15434 8543 15434 8542 15434 8530 15435 8542 15435 8521 15435 8521 15436 8542 15436 8554 15436 8521 15437 8554 15437 8519 15437 8451 15438 8449 15438 8525 15438 8525 15439 8449 15439 8523 15439 8525 15440 8523 15440 8538 15440 8538 15441 8523 15441 8544 15441 8538 15442 8544 15442 8539 15442 8539 15443 8544 15443 8546 15443 8539 15444 8546 15444 8541 15444 8541 15445 8546 15445 8548 15445 8541 15446 8548 15446 8542 15446 8542 15447 8548 15447 8550 15447 8542 15448 8550 15448 8554 15448 8554 15449 8550 15449 8552 15449 8554 15450 8552 15450 8519 15450 8519 15451 8552 15451 8555 15451 8553 15452 8556 15452 8552 15452 8552 15453 8556 15453 8557 15453 8552 15454 8557 15454 8555 15454 8558 15455 8559 15455 8560 15455 8506 15456 8504 15456 8561 15456 8480 15457 8479 15457 8562 15457 8477 15458 8487 15458 8563 15458 8500 15459 8564 15459 8499 15459 8499 15460 8564 15460 8565 15460 8566 15461 8567 15461 8568 15461 8568 15462 8567 15462 8569 15462 8568 15463 8569 15463 8570 15463 8570 15464 8569 15464 8571 15464 8570 15465 8571 15465 8572 15465 8572 15466 8571 15466 8565 15466 8572 15467 8565 15467 8573 15467 8573 15468 8565 15468 8564 15468 8574 15469 8567 15469 8575 15469 8575 15470 8567 15470 8566 15470 8575 15471 8566 15471 8576 15471 8488 15472 8489 15472 8577 15472 8577 15473 8578 15473 8488 15473 8488 15474 8578 15474 8579 15474 8488 15475 8579 15475 8482 15475 8482 15476 8579 15476 8483 15476 8483 15477 8579 15477 8580 15477 8483 15478 8580 15478 8484 15478 8484 15479 8580 15479 8485 15479 8485 15480 8580 15480 8581 15480 8485 15481 8581 15481 8486 15481 8477 15482 8563 15482 8478 15482 8478 15483 8563 15483 8582 15483 8478 15484 8582 15484 8479 15484 8479 15485 8582 15485 8583 15485 8479 15486 8583 15486 8562 15486 8517 15487 250 15487 8481 15487 8503 15488 8515 15488 8583 15488 8583 15489 8515 15489 8517 15489 8583 15490 8517 15490 8562 15490 8562 15491 8517 15491 8481 15491 8562 15492 8481 15492 8480 15492 8504 15493 8503 15493 8561 15493 8561 15494 8503 15494 8583 15494 8561 15495 8583 15495 8584 15495 8584 15496 8583 15496 8582 15496 8584 15497 8582 15497 8581 15497 8581 15498 8582 15498 8563 15498 8581 15499 8563 15499 8486 15499 8486 15500 8563 15500 8487 15500 8559 15501 8576 15501 8560 15501 8560 15502 8576 15502 8566 15502 8560 15503 8566 15503 8585 15503 8585 15504 8566 15504 8568 15504 8585 15505 8568 15505 8586 15505 8586 15506 8568 15506 8570 15506 8586 15507 8570 15507 8587 15507 8587 15508 8570 15508 8572 15508 8587 15509 8572 15509 8588 15509 8588 15510 8572 15510 8573 15510 8588 15511 8573 15511 8589 15511 8589 15512 8573 15512 8564 15512 8589 15513 8564 15513 8514 15513 8514 15514 8564 15514 8500 15514 8577 15515 8558 15515 8578 15515 8578 15516 8558 15516 8560 15516 8578 15517 8560 15517 8579 15517 8579 15518 8560 15518 8585 15518 8579 15519 8585 15519 8580 15519 8580 15520 8585 15520 8586 15520 8580 15521 8586 15521 8581 15521 8581 15522 8586 15522 8587 15522 8581 15523 8587 15523 8584 15523 8584 15524 8587 15524 8588 15524 8584 15525 8588 15525 8561 15525 8561 15526 8588 15526 8589 15526 8561 15527 8589 15527 8506 15527 8506 15528 8589 15528 8514 15528 8590 15529 8591 15529 8592 15529 8559 15530 8558 15530 8593 15530 8575 15531 8576 15531 8594 15531 8595 15532 8596 15532 8597 15532 8596 15533 8595 15533 8598 15533 8599 15534 8600 15534 8601 15534 8600 15535 8599 15535 8602 15535 8603 15536 8604 15536 8605 15536 8603 15537 8606 15537 8489 15537 8489 15538 8606 15538 8593 15538 8489 15539 8593 15539 8577 15539 8577 15540 8593 15540 8558 15540 8607 15541 8608 15541 8609 15541 8609 15542 8608 15542 8610 15542 8609 15543 8610 15543 8611 15543 8611 15544 8610 15544 8612 15544 8611 15545 8612 15545 8613 15545 8613 15546 8612 15546 8614 15546 8613 15547 8614 15547 8615 15547 8615 15548 8614 15548 8616 15548 8615 15549 8616 15549 8617 15549 8617 15550 8616 15550 8597 15550 8617 15551 8597 15551 8601 15551 8601 15552 8597 15552 8596 15552 8601 15553 8596 15553 8599 15553 8599 15554 8596 15554 8598 15554 8576 15555 8559 15555 8594 15555 8594 15556 8559 15556 8593 15556 8594 15557 8593 15557 8618 15557 8618 15558 8593 15558 8606 15558 8619 15559 8590 15559 8618 15559 8618 15560 8590 15560 8592 15560 8618 15561 8592 15561 8594 15561 8594 15562 8592 15562 8620 15562 8594 15563 8620 15563 8575 15563 8575 15564 8620 15564 8574 15564 8603 15565 8605 15565 8606 15565 8606 15566 8605 15566 8621 15566 8606 15567 8621 15567 8618 15567 8618 15568 8621 15568 8622 15568 8618 15569 8622 15569 8619 15569 8608 15570 8591 15570 8610 15570 8610 15571 8591 15571 8590 15571 8610 15572 8590 15572 8612 15572 8612 15573 8590 15573 8619 15573 8612 15574 8619 15574 8614 15574 8614 15575 8619 15575 8622 15575 8614 15576 8622 15576 8616 15576 8616 15577 8622 15577 8621 15577 8616 15578 8621 15578 8597 15578 8597 15579 8621 15579 8605 15579 8597 15580 8605 15580 8595 15580 8595 15581 8605 15581 8604 15581 8623 15582 8624 15582 8625 15582 8626 15583 8627 15583 8628 15583 8459 15584 8519 15584 8629 15584 8629 15585 8519 15585 8630 15585 8629 15586 8630 15586 8631 15586 8632 15587 8633 15587 8634 15587 8635 15588 8636 15588 8637 15588 8637 15589 8636 15589 8638 15589 8637 15590 8638 15590 8639 15590 8627 15591 8626 15591 8640 15591 8640 15592 8626 15592 8633 15592 8640 15593 8633 15593 8641 15593 8641 15594 8633 15594 8632 15594 8641 15595 8632 15595 8642 15595 8638 15596 8623 15596 8639 15596 8639 15597 8623 15597 8625 15597 8639 15598 8625 15598 8643 15598 8643 15599 8625 15599 8642 15599 8643 15600 8642 15600 8644 15600 8644 15601 8642 15601 8632 15601 8557 15602 8645 15602 8555 15602 8555 15603 8645 15603 8646 15603 8555 15604 8646 15604 8519 15604 8519 15605 8646 15605 8647 15605 8519 15606 8647 15606 8630 15606 8557 15607 8556 15607 8645 15607 8645 15608 8556 15608 8648 15608 8645 15609 8648 15609 8649 15609 8634 15610 8631 15610 8632 15610 8632 15611 8631 15611 8630 15611 8632 15612 8630 15612 8644 15612 8644 15613 8630 15613 8647 15613 8644 15614 8647 15614 8643 15614 8643 15615 8647 15615 8646 15615 8643 15616 8646 15616 8639 15616 8639 15617 8646 15617 8645 15617 8639 15618 8645 15618 8637 15618 8637 15619 8645 15619 8649 15619 8637 15620 8649 15620 8635 15620 8635 15621 8649 15621 8648 15621 8650 15622 8651 15622 8628 15622 8652 15623 8653 15623 8654 15623 8628 15624 8627 15624 8650 15624 8650 15625 8627 15625 8640 15625 8650 15626 8640 15626 8655 15626 8655 15627 8640 15627 8641 15627 8655 15628 8641 15628 8654 15628 8654 15629 8641 15629 8642 15629 8654 15630 8642 15630 8652 15630 8652 15631 8642 15631 8625 15631 8652 15632 8625 15632 8624 15632 8656 15633 8657 15633 8658 15633 8659 15634 8660 15634 8661 15634 8661 15635 8660 15635 8651 15635 8661 15636 8651 15636 8650 15636 8661 15637 8662 15637 8659 15637 8659 15638 8662 15638 8663 15638 8659 15639 8663 15639 8664 15639 8664 15640 8663 15640 8665 15640 8664 15641 8665 15641 8666 15641 8666 15642 8665 15642 8667 15642 8666 15643 8667 15643 8668 15643 8658 15644 8657 15644 8669 15644 8669 15645 8657 15645 8670 15645 8669 15646 8670 15646 8671 15646 8672 15647 8673 15647 8674 15647 8674 15648 8673 15648 8654 15648 8674 15649 8654 15649 8653 15649 8675 15650 8676 15650 8677 15650 8677 15651 8676 15651 8678 15651 8677 15652 8678 15652 8679 15652 8679 15653 8678 15653 8680 15653 8679 15654 8680 15654 8681 15654 8650 15655 8655 15655 8661 15655 8661 15656 8655 15656 8675 15656 8661 15657 8675 15657 8662 15657 8662 15658 8675 15658 8677 15658 8662 15659 8677 15659 8663 15659 8663 15660 8677 15660 8679 15660 8663 15661 8679 15661 8665 15661 8665 15662 8679 15662 8681 15662 8665 15663 8681 15663 8667 15663 8655 15664 8654 15664 8675 15664 8675 15665 8654 15665 8673 15665 8675 15666 8673 15666 8676 15666 8676 15667 8673 15667 8672 15667 8676 15668 8672 15668 8678 15668 8678 15669 8672 15669 8656 15669 8678 15670 8656 15670 8680 15670 8680 15671 8656 15671 8658 15671 8680 15672 8658 15672 8681 15672 8681 15673 8658 15673 8669 15673 8681 15674 8669 15674 8667 15674 8682 15675 8683 15675 8668 15675 8669 15676 8671 15676 8684 15676 8684 15677 8685 15677 8669 15677 8669 15678 8685 15678 8682 15678 8669 15678 8682 15678 8667 15678 8667 15679 8682 15679 8668 15679 8686 15680 8607 15680 8609 15680 8686 15681 8609 15681 8687 15681 8609 15682 8611 15682 8687 15682 8687 15683 8611 15683 8613 15683 8687 15684 8613 15684 8688 15684 8613 15685 8615 15685 8688 15685 8688 15686 8615 15686 8617 15686 8688 15687 8617 15687 8689 15687 8689 15688 8617 15688 8690 15688 8602 15689 8691 15689 8600 15689 8600 15690 8691 15690 8690 15690 8600 15691 8690 15691 8601 15691 8601 15692 8690 15692 8617 15692 8692 15693 8693 15693 8694 15693 8695 15694 8696 15694 8697 15694 8698 8973 8699 8973 8700 8973 8700 8974 8699 8974 8701 8974 8697 15695 8696 15695 8702 15695 8696 15696 8703 15696 8702 15696 8702 8977 8703 8977 8704 8977 8702 15697 8704 15697 8699 15697 8699 15698 8704 15698 8705 15698 8699 8980 8705 8980 8701 8980 8706 15699 8707 15699 8695 15699 8708 15700 8707 15700 8709 15700 8709 15701 8707 15701 8706 15701 8709 15702 8706 15702 8710 15702 8695 15703 8697 15703 8706 15703 8706 15704 8697 15704 8711 15704 8706 15705 8711 15705 8710 15705 8692 15706 8694 15706 8712 15706 8712 15707 8694 15707 8713 15707 8712 15708 8713 15708 8714 15708 8714 15709 8713 15709 8715 15709 8714 8992 8715 8992 8716 8992 8698 15710 8715 15710 8699 15710 8699 15711 8715 15711 8713 15711 8699 8995 8713 8995 8702 8995 8702 8996 8713 8996 8694 8996 8702 15712 8694 15712 8697 15712 8697 15713 8694 15713 8693 15713 8697 15714 8693 15714 8711 15714 8711 15715 8693 15715 8692 15715 8711 15716 8692 15716 8717 15716 8718 632 8719 632 8720 632 8721 632 8722 632 8723 632 8716 632 8724 632 8725 632 8717 632 8692 632 8726 632 8726 632 8692 632 8712 632 8726 632 8712 632 8720 632 8725 632 8727 632 8716 632 8716 632 8727 632 8720 632 8716 8968 8720 8968 8714 8968 8714 632 8720 632 8712 632 8721 8967 8723 8967 8727 8967 8727 15717 8723 15717 8728 15717 8727 8970 8728 8970 8720 8970 8720 632 8728 632 8729 632 8720 632 8729 632 8718 632 8730 15718 8731 15718 8732 15718 8733 15719 8734 15719 8732 15719 8732 15720 8734 15720 8735 15720 8732 15721 8735 15721 8730 15721 8736 8939 8737 8939 8738 8939 8736 15722 8738 15722 8739 15722 8737 15723 8736 15723 8740 15723 8740 15724 8736 15724 8741 15724 8740 15725 8741 15725 8742 15725 8742 8944 8741 8944 8743 8944 8742 8945 8743 8945 8744 8945 8728 8946 8723 8946 8745 8946 8746 15726 8747 15726 8748 15726 8745 15727 8749 15727 8728 15727 8728 8949 8749 8949 8750 8949 8728 15728 8750 15728 8729 15728 8729 15729 8750 15729 8746 15729 8729 15730 8746 15730 8718 15730 8718 15731 8746 15731 8748 15731 8718 15732 8748 15732 8719 15732 8731 15733 8751 15733 8732 15733 8732 8956 8751 8956 8739 8956 8732 15734 8739 15734 8733 15734 8733 15735 8739 15735 8738 15735 8751 15736 8747 15736 8739 15736 8739 15737 8747 15737 8746 15737 8739 15738 8746 15738 8736 15738 8736 15739 8746 15739 8750 15739 8736 8963 8750 8963 8741 8963 8741 8964 8750 8964 8749 8964 8741 8965 8749 8965 8743 8965 8743 15740 8749 15740 8745 15740 8351 15741 8350 15741 8740 15741 8740 15742 8350 15742 8361 15742 8740 15743 8361 15743 8737 15743 8737 15744 8361 15744 8362 15744 8737 15745 8362 15745 8738 15745 8738 15746 8362 15746 8363 15746 8738 15747 8363 15747 8733 15747 8733 15748 8363 15748 8330 15748 8733 15749 8330 15749 8734 15749 8734 15750 8330 15750 8329 15750 8734 8925 8329 8925 8735 8925 8735 15751 8329 15751 8324 15751 8735 15752 8324 15752 8730 15752 8744 15753 8343 15753 8344 15753 8344 15754 8349 15754 8744 15754 8744 15755 8349 15755 8348 15755 8744 15756 8348 15756 8352 15756 8351 15757 8740 15757 8352 15757 8352 15758 8740 15758 8742 15758 8352 15759 8742 15759 8744 15759 8752 8914 8700 8914 8753 8914 8753 106 8700 106 8302 106 8753 106 8302 106 8754 106 8755 15760 8722 15760 8756 15760 8757 15761 8744 15761 8743 15761 8758 15762 8759 15762 8757 15762 8757 15763 8743 15763 8758 15763 8758 15764 8743 15764 8745 15764 8758 15765 8745 15765 8760 15765 8755 15766 8761 15766 8722 15766 8722 15767 8761 15767 8760 15767 8722 8912 8760 8912 8723 8912 8723 15768 8760 15768 8745 15768 8725 15769 8724 15769 8762 15769 8762 8896 8763 8896 8725 8896 8725 8897 8763 8897 8764 8897 8725 8898 8764 8898 8727 8898 8727 8899 8764 8899 8765 8899 8727 8900 8765 8900 8721 8900 8721 15770 8765 15770 8756 15770 8721 15771 8756 15771 8722 15771 8752 15772 8766 15772 8767 15772 8724 15773 8716 15773 8715 15773 8768 15774 8769 15774 8724 15774 8724 15775 8769 15775 8770 15775 8724 15776 8770 15776 8762 15776 8724 15777 8715 15777 8768 15777 8768 15778 8715 15778 8698 15778 8768 15779 8698 15779 8767 15779 8767 15780 8698 15780 8700 15780 8767 15781 8700 15781 8752 15781 8753 15782 8771 15782 8772 15782 8772 15783 8773 15783 8753 15783 8753 15784 8773 15784 8766 15784 8753 8884 8766 8884 8752 8884 8774 15785 8775 15785 8776 15785 8776 15786 8775 15786 8754 15786 8754 15787 8775 15787 8777 15787 8754 15788 8777 15788 8778 15788 8778 15789 8779 15789 8754 15789 8754 15790 8779 15790 8780 15790 8780 15791 8781 15791 8754 15791 8754 15792 8781 15792 8782 15792 8754 15793 8782 15793 8753 15793 8783 15794 8784 15794 8776 15794 8776 15795 8784 15795 8785 15795 8776 15796 8785 15796 8774 15796 8786 8858 8787 8858 8788 8858 8788 8859 8787 8859 8789 8859 8754 15797 8302 15797 8790 15797 8790 15798 8302 15798 8791 15798 8790 15799 8791 15799 8792 15799 8792 15800 8791 15800 8793 15800 8792 8864 8793 8864 8794 8864 8794 15801 8793 15801 8795 15801 8794 15802 8795 15802 8789 15802 8789 8867 8795 8867 8796 8867 8789 8868 8796 8868 8788 8868 8797 15803 8798 15803 8759 15803 8759 15804 8798 15804 8799 15804 8759 15805 8799 15805 8757 15805 8800 15806 8801 15806 8759 15806 8761 15807 8802 15807 8760 15807 8760 15808 8802 15808 8803 15808 8760 15809 8803 15809 8758 15809 8800 15810 8759 15810 8804 15810 8804 15811 8759 15811 8758 15811 8804 15812 8758 15812 8805 15812 8805 15813 8758 15813 8803 15813 8805 15814 8803 15814 8806 15814 8806 15815 8803 15815 8802 15815 8806 15816 8802 15816 8807 15816 8807 15817 8802 15817 8761 15817 8807 15818 8761 15818 8808 15818 8756 15819 8809 15819 8755 15819 8755 15820 8809 15820 8810 15820 8755 15821 8810 15821 8761 15821 8763 15822 8811 15822 8812 15822 8809 15823 8813 15823 8810 15823 8810 15824 8813 15824 8814 15824 8810 15825 8814 15825 8815 15825 8763 8831 8762 8831 8811 8831 8811 15826 8762 15826 8816 15826 8811 632 8816 632 8817 632 8817 15827 8816 15827 8818 15827 8817 15828 8818 15828 8819 15828 8809 15829 8756 15829 8813 15829 8813 15830 8756 15830 8765 15830 8813 15831 8765 15831 8812 15831 8812 15832 8765 15832 8764 15832 8812 15833 8764 15833 8763 15833 8762 8823 8770 8823 8816 8823 8816 15834 8770 15834 8818 15834 8770 15835 8820 15835 8821 15835 8766 15836 8822 15836 8823 15836 8767 15837 8824 15837 8768 15837 8768 15838 8824 15838 8820 15838 8768 15839 8820 15839 8769 15839 8769 15840 8820 15840 8770 15840 8766 15841 8823 15841 8767 15841 8767 15842 8823 15842 8825 15842 8767 15843 8825 15843 8824 15843 8824 15844 8825 15844 8826 15844 8824 15845 8826 15845 8820 15845 8820 15846 8826 15846 8827 15846 8820 15847 8827 15847 8821 15847 8828 8801 8829 8801 8343 8801 8343 8802 8829 8802 8830 8802 8829 8803 8831 8803 8830 8803 8830 15848 8831 15848 8832 15848 8830 15849 8832 15849 8833 15849 8833 8806 8832 8806 8834 8806 8833 15850 8834 15850 8835 15850 8835 8808 8834 8808 8836 8808 8835 8809 8836 8809 8837 8809 8838 15851 8839 15851 8840 15851 8840 15852 8839 15852 8841 15852 8840 15853 8841 15853 8842 15853 8843 15854 8844 15854 8828 15854 8828 15855 8844 15855 8845 15855 8845 15856 8846 15856 8828 15856 8828 15857 8846 15857 8847 15857 8828 15858 8847 15858 8841 15858 8841 15859 8847 15859 8848 15859 8841 15860 8848 15860 8842 15860 8849 15861 8850 15861 8851 15861 8847 8772 8846 8772 8852 8772 8852 15862 8846 15862 8845 15862 8799 15863 8798 15863 8853 15863 8854 15864 8844 15864 8843 15864 8844 15865 8854 15865 8845 15865 8845 15866 8854 15866 8851 15866 8845 15867 8851 15867 8852 15867 8848 15868 8847 15868 8855 15868 8855 15869 8847 15869 8852 15869 8855 15870 8852 15870 8856 15870 8856 15871 8852 15871 8851 15871 8856 15872 8851 15872 8857 15872 8857 15873 8851 15873 8850 15873 8857 15874 8850 15874 8858 15874 8843 15875 8799 15875 8854 15875 8854 15876 8799 15876 8853 15876 8854 15877 8853 15877 8851 15877 8851 15878 8853 15878 8859 15878 8851 15879 8859 15879 8849 15879 8860 15880 8861 15880 8862 15880 8863 8736 8864 8736 8865 8736 8863 8737 8865 8737 8866 8737 8866 15881 8865 15881 8867 15881 8866 15882 8867 15882 8868 15882 8868 8740 8867 8740 8869 8740 8868 8741 8869 8741 8870 8741 8870 8742 8869 8742 8871 8742 8870 8743 8871 8743 8872 8743 8860 15883 8862 15883 8873 15883 8873 15884 8862 15884 8874 15884 8873 15885 8874 15885 8875 15885 8875 15886 8874 15886 8876 15886 8875 15887 8876 15887 8877 15887 8877 8749 8876 8749 8878 8749 8878 15888 8876 15888 8879 15888 8878 15889 8879 15889 8880 15889 8880 15890 8879 15890 8881 15890 8881 8753 8879 8753 8882 8753 8881 15891 8882 15891 8883 15891 8864 15892 8884 15892 8865 15892 8865 15893 8884 15893 8885 15893 8865 15894 8885 15894 8867 15894 8867 15895 8885 15895 8886 15895 8867 15896 8886 15896 8869 15896 8869 8760 8886 8760 8887 8760 8869 15897 8887 15897 8871 15897 8871 15898 8887 15898 8888 15898 8884 15899 8882 15899 8885 15899 8885 8764 8882 8764 8879 8764 8885 15900 8879 15900 8886 15900 8886 15901 8879 15901 8876 15901 8886 8767 8876 8767 8887 8767 8887 8768 8876 8768 8874 8768 8887 15902 8874 15902 8888 15902 8888 15903 8874 15903 8862 15903 8780 15904 8779 15904 8889 15904 8779 15905 8778 15905 8889 15905 8889 15906 8778 15906 8777 15906 8889 15907 8777 15907 8890 15907 8890 15908 8777 15908 8775 15908 8753 8719 8782 8719 8891 8719 8891 15909 8782 15909 8781 15909 8891 8721 8781 8721 8892 8721 8892 15910 8781 15910 8780 15910 8892 15911 8780 15911 8893 15911 8780 15912 8889 15912 8893 15912 8893 15913 8889 15913 8894 15913 8893 15914 8894 15914 8895 15914 8771 15915 8753 15915 8896 15915 8896 15916 8753 15916 8891 15916 8896 15917 8891 15917 8897 15917 8897 15918 8891 15918 8892 15918 8897 15919 8892 15919 8898 15919 8898 15920 8892 15920 8893 15920 8898 15921 8893 15921 8899 15921 8899 15922 8893 15922 8895 15922 8772 632 8822 632 8773 632 8773 632 8822 632 8766 632 8900 8696 8784 8696 8783 8696 8783 15923 8901 15923 8900 15923 8900 15924 8901 15924 8902 15924 8900 15925 8902 15925 8903 15925 8903 15926 8902 15926 8904 15926 8905 15927 8906 15927 8907 15927 8907 15928 8906 15928 8904 15928 8907 8703 8904 8703 8908 8703 8908 8704 8904 8704 8902 8704 8909 8705 8910 8705 8911 8705 8910 15929 8912 15929 8911 15929 8911 15930 8912 15930 8913 15930 8911 15931 8913 15931 8907 15931 8907 15932 8913 15932 8914 15932 8907 15933 8914 15933 8905 15933 8911 15934 8915 15934 8909 15934 8909 15935 8915 15935 8916 15935 8909 15936 8916 15936 8917 15936 8918 8671 8919 8671 8920 8671 8918 15937 8920 15937 8921 15937 8922 15938 8923 15938 8924 15938 8924 15939 8923 15939 8925 15939 8924 15940 8925 15940 8926 15940 8926 15941 8927 15941 8924 15941 8924 15942 8927 15942 8928 15942 8924 15943 8928 15943 8929 15943 8789 8679 8787 8679 8872 8679 8872 15944 8930 15944 8789 15944 8789 8681 8930 8681 8931 8681 8789 15945 8931 15945 8932 15945 8754 15946 8790 15946 8776 15946 8776 15947 8790 15947 8920 15947 8776 15948 8920 15948 8783 15948 8783 8686 8920 8686 8919 8686 8790 15949 8792 15949 8920 15949 8920 15950 8792 15950 8929 15950 8920 15951 8929 15951 8921 15951 8921 15952 8929 15952 8928 15952 8792 15953 8794 15953 8929 15953 8929 8692 8794 8692 8789 8692 8929 15954 8789 15954 8924 15954 8924 15955 8789 15955 8932 15955 8924 15956 8932 15956 8922 15956 8933 15957 8894 15957 8934 15957 8934 15958 8894 15958 8889 15958 8934 15959 8889 15959 8935 15959 8889 15960 8890 15960 8935 15960 8935 15961 8890 15961 8775 15961 8935 15962 8775 15962 8774 15962 8935 15963 8774 15963 8785 15963 8934 15964 8935 15964 8936 15964 8936 15965 8935 15965 8785 15965 8936 15966 8785 15966 8937 15966 8937 15967 8785 15967 8784 15967 8933 15968 8934 15968 8938 15968 8938 15969 8934 15969 8936 15969 8938 8662 8936 8662 8939 8662 8939 15970 8936 15970 8937 15970 8939 8664 8937 8664 8940 8664 8759 632 8801 632 8797 632 8810 15971 8815 15971 8941 15971 8808 8651 8761 8651 8942 8651 8942 15972 8761 15972 8810 15972 8942 8653 8810 8653 8943 8653 8943 15973 8810 15973 8941 15973 8818 15974 8770 15974 8821 15974 8944 8646 8819 8646 8945 8646 8945 15975 8819 15975 8818 15975 8945 15976 8818 15976 8946 15976 8946 15977 8818 15977 8821 15977 8829 15978 8947 15978 8831 15978 8831 15979 8947 15979 8948 15979 8831 15980 8948 15980 8832 15980 8948 8628 8949 8628 8832 8628 8832 8629 8949 8629 8950 8629 8832 15981 8950 15981 8834 15981 8834 15982 8950 15982 8951 15982 8863 15983 8836 15983 8952 15983 8952 8633 8836 8633 8834 8633 8952 15984 8834 15984 8953 15984 8953 15985 8834 15985 8951 15985 8954 15986 8955 15986 8947 15986 8947 15987 8955 15987 8956 15987 8947 15988 8956 15988 8948 15988 8948 8639 8956 8639 8957 8639 8948 15989 8957 15989 8949 15989 8829 15990 8828 15990 8947 15990 8947 15991 8828 15991 8841 15991 8947 15992 8841 15992 8954 15992 8954 15993 8841 15993 8839 15993 8958 15994 8959 15994 8960 15994 8960 15995 8959 15995 8961 15995 8960 15996 8961 15996 8962 15996 8962 15997 8961 15997 8963 15997 8963 15998 8961 15998 8964 15998 8963 15999 8964 15999 8965 15999 8965 16000 8964 16000 8966 16000 8966 8612 8964 8612 8967 8612 8966 16001 8967 16001 8968 16001 8969 8614 8970 8614 8967 8614 8967 8615 8970 8615 8971 8615 8967 8616 8971 8616 8968 8616 8972 16002 8973 16002 8974 16002 8974 16003 8973 16003 8975 16003 8974 16004 8975 16004 8969 16004 8969 16005 8975 16005 8976 16005 8969 16006 8976 16006 8970 16006 8972 16007 8974 16007 8977 16007 8977 16008 8974 16008 8839 16008 8977 16009 8839 16009 8838 16009 8978 16010 8840 16010 8979 16010 8979 16011 8840 16011 8842 16011 8980 8595 8981 8595 8982 8595 8983 16012 8981 16012 8979 16012 8979 16013 8981 16013 8980 16013 8979 16014 8980 16014 8978 16014 8838 16015 8840 16015 8984 16015 8984 16016 8840 16016 8978 16016 8984 16017 8978 16017 8985 16017 8985 16018 8978 16018 8980 16018 8985 16019 8980 16019 8986 16019 8986 16020 8980 16020 8982 16020 8858 16021 8983 16021 8857 16021 8857 16022 8983 16022 8979 16022 8857 16023 8979 16023 8856 16023 8842 16024 8848 16024 8979 16024 8979 16025 8848 16025 8855 16025 8979 16026 8855 16026 8856 16026 8987 8555 8988 8555 8989 8555 8990 16027 8991 16027 8992 16027 8993 16028 8994 16028 8992 16028 8992 8558 8994 8558 8995 8558 8992 16029 8995 16029 8990 16029 8875 16030 8996 16030 8873 16030 8873 16031 8996 16031 8997 16031 8873 8562 8997 8562 8860 8562 8860 16032 8997 16032 8998 16032 8860 16033 8998 16033 8861 16033 8861 8565 8998 8565 8999 8565 8861 16034 8999 16034 8991 16034 8991 16035 8999 16035 9000 16035 8991 16036 9000 16036 8992 16036 8881 16037 9001 16037 9002 16037 8881 8570 9002 8570 8880 8570 8880 8571 9002 8571 9003 8571 8880 16038 9003 16038 8878 16038 8878 16039 9003 16039 9004 16039 8878 16040 9004 16040 8877 16040 8877 16041 9004 16041 9005 16041 8877 16042 9005 16042 8875 16042 8875 16043 9005 16043 9006 16043 8875 16044 9006 16044 8996 16044 8881 16045 8883 16045 9001 16045 9001 16046 8883 16046 9007 16046 9001 16047 9007 16047 9008 16047 9008 8582 9007 8582 9009 8582 9008 16048 9009 16048 9010 16048 9010 16049 9009 16049 8989 16049 8989 16050 9009 16050 9011 16050 8989 8586 9011 8586 8987 8586 9007 16051 8883 16051 8882 16051 8953 16052 8951 16052 9012 16052 8949 16053 8957 16053 9013 16053 9013 16054 8957 16054 8956 16054 9013 16055 8956 16055 9014 16055 9014 16056 8956 16056 8955 16056 9007 8508 9015 8508 9009 8508 9009 8509 9015 8509 9016 8509 9009 8510 9016 8510 9011 8510 9017 8511 9018 8511 9019 8511 9019 16057 9018 16057 9020 16057 9019 16058 9020 16058 9015 16058 9015 16059 9020 16059 9021 16059 9015 8515 9021 8515 9016 8515 8955 8516 9022 8516 9014 8516 9014 16060 9022 16060 9023 16060 9014 16061 9023 16061 9013 16061 9013 16062 9023 16062 9024 16062 9013 16063 9024 16063 9025 16063 9025 16064 9024 16064 9026 16064 9025 16065 9026 16065 9027 16065 9027 16066 9026 16066 9028 16066 9027 16067 9028 16067 9029 16067 8949 16068 9013 16068 9030 16068 9030 16069 9013 16069 9025 16069 9030 16070 9025 16070 9031 16070 9031 16071 9025 16071 9027 16071 9031 16072 9027 16072 9032 16072 9032 16073 9027 16073 9029 16073 9032 8531 9029 8531 9017 8531 9017 16074 9029 16074 9033 16074 9017 8533 9033 8533 9018 8533 9007 8534 9034 8534 9015 8534 9015 8535 9034 8535 9035 8535 9015 8536 9035 8536 9019 8536 9019 8537 9035 8537 9036 8537 9019 8538 9036 8538 9017 8538 9017 16075 9036 16075 9012 16075 9017 16076 9012 16076 9032 16076 9032 16077 9012 16077 8951 16077 9032 16078 8951 16078 9031 16078 9031 16079 8951 16079 8950 16079 9031 16080 8950 16080 9030 16080 9030 8545 8950 8545 8949 8545 9007 8546 8882 8546 9034 8546 9034 16081 8882 16081 8884 16081 9034 16082 8884 16082 9035 16082 9035 16083 8884 16083 8864 16083 9035 16084 8864 16084 9036 16084 9036 16085 8864 16085 8863 16085 9036 16086 8863 16086 9012 16086 9012 16087 8863 16087 8952 16087 9012 16088 8952 16088 8953 16088 9037 16089 9038 16089 9039 16089 8990 16090 8995 16090 9040 16090 8931 16091 9041 16091 8932 16091 8932 16092 9041 16092 9042 16092 8932 8442 9042 8442 8922 8442 9038 16093 8925 16093 8923 16093 8925 16094 9038 16094 8926 16094 8926 16095 9038 16095 9037 16095 8926 16096 9037 16096 9043 16096 8921 16097 8928 16097 9043 16097 9043 16098 8928 16098 8927 16098 9043 16099 8927 16099 8926 16099 9044 16100 9045 16100 9039 16100 9046 8451 9047 8451 9048 8451 9049 16101 9050 16101 9051 16101 9051 16102 9050 16102 9052 16102 9051 16103 9052 16103 9053 16103 9053 16104 9052 16104 9054 16104 9053 16105 9054 16105 9055 16105 9055 16106 9054 16106 9041 16106 9055 16107 9041 16107 9056 16107 9056 16108 9041 16108 8931 16108 9056 16109 8931 16109 8930 16109 8930 8461 8872 8461 9056 8461 9056 16110 8872 16110 9057 16110 9056 16111 9057 16111 9055 16111 9055 8464 9057 8464 9058 8464 9055 16112 9058 16112 9053 16112 9053 16113 9058 16113 9046 16113 9053 16114 9046 16114 9051 16114 9051 16115 9046 16115 9048 16115 9051 16116 9048 16116 9049 16116 8918 8470 8921 8470 9059 8470 9059 16117 8921 16117 9043 16117 9059 16118 9043 16118 9060 16118 9060 16119 9043 16119 9037 16119 9060 16120 9037 16120 9061 16120 9061 16121 9037 16121 9039 16121 9061 16122 9039 16122 9062 16122 9062 16123 9039 16123 9045 16123 9050 16124 9063 16124 9052 16124 9052 8479 9063 8479 9044 8479 9052 16125 9044 16125 9054 16125 9054 16126 9044 16126 9039 16126 9054 16127 9039 16127 9041 16127 9041 16128 9039 16128 9038 16128 9041 16129 9038 16129 9042 16129 9042 16130 9038 16130 8923 16130 9042 16131 8923 16131 8922 16131 8872 8487 8871 8487 9057 8487 9057 16132 8871 16132 8888 16132 9057 16133 8888 16133 9058 16133 9058 16134 8888 16134 8862 16134 9058 16135 8862 16135 9046 16135 9046 16136 8862 16136 8861 16136 9046 8493 8861 8493 9047 8493 9047 8494 8861 8494 8991 8494 9047 8495 8991 8495 9048 8495 9048 16137 8991 16137 8990 16137 9048 16138 8990 16138 9049 16138 9049 16139 8990 16139 9040 16139 9049 8499 9040 8499 9050 8499 9050 16140 9040 16140 9064 16140 9050 16141 9064 16141 9063 16141 8917 98 8916 98 9065 98 9065 16142 8916 16142 9066 16142 9065 16143 9066 16143 8994 16143 8994 98 9066 98 9067 98 8994 98 9067 98 8995 98 9063 16144 9068 16144 9069 16144 9070 16145 8919 16145 8918 16145 8901 16146 8783 16146 8919 16146 8918 8393 9059 8393 9071 8393 9071 8394 9059 8394 9060 8394 9071 8395 9060 8395 9072 8395 9072 16147 9060 16147 9061 16147 9072 8397 9061 8397 9073 8397 9061 8398 9062 8398 9073 8398 9073 16148 9062 16148 9045 16148 9073 16149 9045 16149 9069 16149 9069 16150 9045 16150 9044 16150 9069 16151 9044 16151 9063 16151 8918 16152 9071 16152 9070 16152 9070 8404 9071 8404 9072 8404 9070 16153 9072 16153 9074 16153 9074 16154 9072 16154 9073 16154 9074 16155 9073 16155 9075 16155 9075 16156 9073 16156 9069 16156 9075 8409 9069 8409 9076 8409 9076 16157 9069 16157 9068 16157 9076 16158 9068 16158 9077 16158 8919 16159 9070 16159 8901 16159 8901 16160 9070 16160 9074 16160 8901 16161 9074 16161 8902 16161 8902 16162 9074 16162 9075 16162 8902 8416 9075 8416 8908 8416 8908 8417 9075 8417 9076 8417 8908 8418 9076 8418 8907 8418 8907 16163 9076 16163 9077 16163 8907 16164 9077 16164 8911 16164 9064 16165 9040 16165 9078 16165 9078 16166 9040 16166 9079 16166 9078 16167 9079 16167 9080 16167 9080 16168 9079 16168 9081 16168 9066 8425 9081 8425 9067 8425 9067 8426 9081 8426 9079 8426 9067 16169 9079 16169 8995 16169 8995 16170 9079 16170 9040 16170 9063 16171 9064 16171 9068 16171 9068 16172 9064 16172 9078 16172 9068 16173 9078 16173 9077 16173 9077 16174 9078 16174 9080 16174 9077 16175 9080 16175 8911 16175 8911 16176 9080 16176 9081 16176 8911 16177 9081 16177 8915 16177 8915 16178 9081 16178 9066 16178 8915 16179 9066 16179 8916 16179 9021 16180 9020 16180 9082 16180 9083 8342 9084 8342 9085 8342 9022 8343 9083 8343 9086 8343 9087 16181 9024 16181 9086 16181 9086 16182 9024 16182 9023 16182 9086 8346 9023 8346 9022 8346 9083 8347 9085 8347 9086 8347 9086 16183 9085 16183 9088 16183 9086 16184 9088 16184 9087 16184 9087 16185 9088 16185 9089 16185 9087 16186 9089 16186 9090 16186 9033 8352 9029 8352 9090 8352 9090 8353 9029 8353 9028 8353 9090 16187 9028 16187 9087 16187 9087 16188 9028 16188 9026 16188 9087 16189 9026 16189 9024 16189 9018 16190 9033 16190 9091 16190 9091 16191 9033 16191 9090 16191 9091 16192 9090 16192 9092 16192 9092 16193 9090 16193 9089 16193 9020 16194 9018 16194 9082 16194 9082 16195 9018 16195 9091 16195 9082 16196 9091 16196 9093 16196 9093 16197 9091 16197 9092 16197 9093 16198 9092 16198 8964 16198 8964 16199 9092 16199 9089 16199 8964 16200 9089 16200 8967 16200 8967 16201 9089 16201 9088 16201 8967 16202 9088 16202 8969 16202 8969 16203 9088 16203 9085 16203 8969 16204 9085 16204 8974 16204 8974 8372 9085 8372 9084 8372 8974 16205 9084 16205 8839 16205 8839 8374 9084 8374 9083 8374 8839 16206 9083 16206 8954 16206 8954 16207 9083 16207 9022 16207 8954 8377 9022 8377 8955 8377 9016 16208 9021 16208 9094 16208 9094 16209 9021 16209 9082 16209 9094 16210 9082 16210 9095 16210 9095 16211 9082 16211 9093 16211 9095 16212 9093 16212 8961 16212 8961 8383 9093 8383 8964 8383 9011 8384 9016 8384 9096 8384 9096 8385 9016 8385 9094 8385 9096 16213 9094 16213 9097 16213 9097 16214 9094 16214 9095 16214 9097 16215 9095 16215 8959 16215 8959 16216 9095 16216 8961 16216 8959 106 8958 106 9098 106 9097 106 8959 106 9096 106 9096 16217 8959 16217 9098 16217 9096 16218 9098 16218 9011 16218 9011 16219 9098 16219 8987 16219 9099 7585 9100 7585 9101 7585 9102 16220 9103 16220 9104 16220 9104 7585 9103 7585 9105 7585 9104 16221 9106 16221 9102 16221 9102 7585 9106 7585 9107 7585 9102 16222 9107 16222 9108 16222 9108 8334 9107 8334 9109 8334 9108 7585 9109 7585 9110 7585 9110 8335 9109 8335 9111 8335 9110 7585 9111 7585 9112 7585 9112 7585 9111 7585 9113 7585 9112 8336 9113 8336 9114 8336 9114 7585 9113 7585 9101 7585 9101 7585 9113 7585 9115 7585 9101 7585 9115 7585 9099 7585 9116 7585 9117 7585 9118 7585 9118 7585 9117 7585 9105 7585 9118 16223 9105 16223 9119 16223 9119 7585 9105 7585 9103 7585 8994 16224 8993 16224 9116 16224 8994 16225 9116 16225 9065 16225 9065 8312 9116 8312 9118 8312 9065 8313 9118 8313 9120 8313 8988 16226 8987 16226 9100 16226 9100 16227 8987 16227 9098 16227 9100 16228 9098 16228 9101 16228 9101 16229 9098 16229 9121 16229 9101 8318 9121 8318 9114 8318 9114 8319 9121 8319 9112 8319 9112 16230 9121 16230 9122 16230 9112 8321 9122 8321 9110 8321 9118 16231 9119 16231 9120 16231 9120 16232 9119 16232 9103 16232 9120 16233 9103 16233 9123 16233 9123 16234 9103 16234 9102 16234 9123 8326 9102 8326 9124 8326 9124 8327 9102 8327 9108 8327 9124 8328 9108 8328 9125 8328 9125 8329 9108 8329 9110 8329 9125 8330 9110 8330 9126 8330 9126 8331 9110 8331 9122 8331 9121 16235 9098 16235 8958 16235 8958 16236 9127 16236 9121 16236 9121 16237 9127 16237 9128 16237 9121 8305 9128 8305 9122 8305 9122 8306 9128 8306 9129 8306 9122 8307 9129 8307 9126 8307 9126 8308 9129 8308 9130 8308 9126 8309 9130 8309 9125 8309 8917 16238 9065 16238 9120 16238 9125 8294 9130 8294 9131 8294 9125 8295 9131 8295 9124 8295 9124 8296 9131 8296 9132 8296 9124 8297 9132 8297 9123 8297 9123 8298 9132 8298 9133 8298 9123 16239 9133 16239 9120 16239 9120 16240 9133 16240 9134 16240 9120 16241 9134 16241 8917 16241 8977 16242 8838 16242 9135 16242 9135 16243 8838 16243 8984 16243 9135 16244 8984 16244 8985 16244 8977 16245 9135 16245 8972 16245 8972 16246 9135 16246 9136 16246 8972 16247 9136 16247 8973 16247 8973 8214 9136 8214 9137 8214 8973 16248 9137 16248 8975 16248 8975 8216 9137 8216 9138 8216 8975 16249 9138 16249 8976 16249 8976 16250 9138 16250 9139 16250 8976 16251 9139 16251 8970 16251 8970 16252 9139 16252 8971 16252 8971 16253 9139 16253 9140 16253 8971 16254 9140 16254 8968 16254 8968 16255 9140 16255 9141 16255 8968 16256 9141 16256 8966 16256 8966 16257 9141 16257 9142 16257 8966 16258 9142 16258 8965 16258 8965 16259 9142 16259 9143 16259 8965 16260 9143 16260 8963 16260 8963 8229 9143 8229 9144 8229 8963 16261 9144 16261 8962 16261 8962 8231 9144 8231 9145 8231 8962 8232 9145 8232 8960 8232 8960 8233 9145 8233 9127 8233 8960 16262 9127 16262 8958 16262 9146 8235 9129 8235 9128 8235 9129 8236 9146 8236 9130 8236 9130 8237 9146 8237 9147 8237 9130 8238 9147 8238 9148 8238 9148 8239 9147 8239 9149 8239 9148 8240 9149 8240 9150 8240 9151 16263 9152 16263 9153 16263 9153 16264 9152 16264 9154 16264 9153 8243 9154 8243 9155 8243 9155 8244 9154 8244 9150 8244 9155 16265 9150 16265 9156 16265 9156 16266 9150 16266 9149 16266 9128 8247 9157 8247 9146 8247 9146 16267 9157 16267 9158 16267 9146 16268 9158 16268 9147 16268 9147 16269 9158 16269 9159 16269 9147 8251 9159 8251 9149 8251 9149 16270 9159 16270 9160 16270 9149 16271 9160 16271 9156 16271 9156 16272 9160 16272 9161 16272 9156 16273 9161 16273 9155 16273 9155 16274 9161 16274 9162 16274 9155 16275 9162 16275 9153 16275 9153 16276 9162 16276 9163 16276 9153 16277 9163 16277 9151 16277 9151 16278 9163 16278 9164 16278 9151 16279 9164 16279 9165 16279 9165 16280 9164 16280 9166 16280 9165 16281 9166 16281 9167 16281 9167 16282 9166 16282 9168 16282 9167 16283 9168 16283 9169 16283 9169 16284 9168 16284 9170 16284 9169 16285 9170 16285 8982 16285 8982 16286 9170 16286 8986 16286 9128 16287 9127 16287 9157 16287 9157 8270 9127 8270 9145 8270 9157 16288 9145 16288 9158 16288 9158 8272 9145 8272 9144 8272 9158 16289 9144 16289 9159 16289 9159 8274 9144 8274 9143 8274 9159 16290 9143 16290 9160 16290 9160 8276 9143 8276 9142 8276 9160 16291 9142 16291 9161 16291 9161 16292 9142 16292 9141 16292 9161 16293 9141 16293 9162 16293 9162 16294 9141 16294 9140 16294 9162 16295 9140 16295 9163 16295 9163 16296 9140 16296 9139 16296 9163 16297 9139 16297 9164 16297 9164 16298 9139 16298 9138 16298 9164 8285 9138 8285 9166 8285 9166 16299 9138 16299 9137 16299 9166 8287 9137 8287 9168 8287 9168 8288 9137 8288 9136 8288 9168 16300 9136 16300 9170 16300 9170 16301 9136 16301 9135 16301 9170 8291 9135 8291 8986 8291 8986 16302 9135 16302 8985 16302 9171 16303 9172 16303 9173 16303 9174 8116 9175 8116 9176 8116 9177 16304 9178 16304 9179 16304 9180 8118 9181 8118 9182 8118 9182 8119 9181 8119 9131 8119 9182 8120 9131 8120 9130 8120 9183 16305 8910 16305 9184 16305 9184 8122 8910 8122 8909 8122 9184 8123 8909 8123 9185 8123 9185 16306 8909 16306 8917 16306 9185 16307 8917 16307 9134 16307 8914 16308 8913 16308 9183 16308 9183 16309 8913 16309 8912 16309 9183 16310 8912 16310 8910 16310 8904 16311 8906 16311 9186 16311 9186 16312 8906 16312 8905 16312 9186 16313 8905 16313 9187 16313 9187 16314 8905 16314 8914 16314 9187 16315 8914 16315 9188 16315 9188 16316 8914 16316 9183 16316 8904 8135 9186 8135 8903 8135 8903 16317 9186 16317 9189 16317 8903 8137 9189 8137 8900 8137 8900 16318 9189 16318 9190 16318 8900 16319 9190 16319 9191 16319 9176 8140 9175 8140 9192 8140 9175 8141 9193 8141 9192 8141 9192 8142 9193 8142 9194 8142 9192 16320 9194 16320 9180 16320 9180 16321 9194 16321 9195 16321 9180 16322 9195 16322 9181 16322 8937 16323 9173 16323 8940 16323 8940 16324 9173 16324 9172 16324 8940 16325 9172 16325 9196 16325 9196 16326 9172 16326 9171 16326 9196 16327 9171 16327 9197 16327 9177 16328 9197 16328 9178 16328 9178 16329 9197 16329 9171 16329 9178 16330 9171 16330 9198 16330 9198 16331 9171 16331 9173 16331 9198 16332 9173 16332 9199 16332 9199 16333 9173 16333 8937 16333 9199 16334 8937 16334 8784 16334 9132 8158 9131 8158 9200 8158 9200 8159 9131 8159 9181 8159 9200 16335 9181 16335 9201 16335 9201 16336 9181 16336 9195 16336 9201 16337 9195 16337 9202 16337 9202 16338 9195 16338 9194 16338 9202 16339 9194 16339 9203 16339 9203 8165 9194 8165 9193 8165 9203 16340 9193 16340 9204 16340 9204 16341 9193 16341 9175 16341 9204 16342 9175 16342 9179 16342 9179 16343 9175 16343 9174 16343 9179 16344 9174 16344 9177 16344 9134 16345 9133 16345 9185 16345 9185 16346 9133 16346 9205 16346 9185 16347 9205 16347 9184 16347 9184 16348 9205 16348 9206 16348 9184 16349 9206 16349 9183 16349 9183 16350 9206 16350 9207 16350 9183 16351 9207 16351 9188 16351 9188 16352 9207 16352 9208 16352 9188 16353 9208 16353 9187 16353 9187 16354 9208 16354 9209 16354 9187 16355 9209 16355 9186 16355 9186 8182 9209 8182 9210 8182 9186 16356 9210 16356 9189 16356 9189 16357 9210 16357 9211 16357 9189 16358 9211 16358 9190 16358 9190 16359 9211 16359 9212 16359 9190 16360 9212 16360 9191 16360 8784 16361 8900 16361 9199 16361 9199 16362 8900 16362 9191 16362 9199 16363 9191 16363 9198 16363 9198 16364 9191 16364 9212 16364 9198 16365 9212 16365 9178 16365 9178 16366 9212 16366 9211 16366 9178 16367 9211 16367 9179 16367 9179 16368 9211 16368 9210 16368 9179 16369 9210 16369 9204 16369 9204 16370 9210 16370 9209 16370 9204 16371 9209 16371 9203 16371 9203 16372 9209 16372 9208 16372 9203 16373 9208 16373 9202 16373 9202 16374 9208 16374 9207 16374 9202 16375 9207 16375 9201 16375 9201 16376 9207 16376 9206 16376 9201 16377 9206 16377 9200 16377 9200 16378 9206 16378 9205 16378 9200 16379 9205 16379 9132 16379 9132 16380 9205 16380 9133 16380 9150 16381 9154 16381 9213 16381 9152 16382 9151 16382 9214 16382 9151 16383 9165 16383 9214 16383 9214 16384 9165 16384 9167 16384 9214 16385 9167 16385 9215 16385 9215 16386 9167 16386 9169 16386 9215 16387 9169 16387 9216 16387 9216 16388 9169 16388 8982 16388 9216 8086 8982 8086 9217 8086 9217 8087 8982 8087 8981 8087 9217 16389 8981 16389 8983 16389 9176 8089 9192 8089 9218 8089 9218 8090 9192 8090 9180 8090 9218 8091 9180 8091 9148 8091 9148 16390 9180 16390 9182 16390 9148 8093 9182 8093 9130 8093 9177 16391 9219 16391 9197 16391 9197 16392 9219 16392 9220 16392 9197 16393 9220 16393 9196 16393 9196 16394 9220 16394 9221 16394 9196 16395 9221 16395 8940 16395 9177 16396 9174 16396 9219 16396 9219 16397 9174 16397 9176 16397 9219 8101 9176 8101 9222 8101 9222 8102 9176 8102 9218 8102 9222 16398 9218 16398 9213 16398 9213 16399 9218 16399 9148 16399 9213 16400 9148 16400 9150 16400 9223 8106 8933 8106 8938 8106 9223 16401 8938 16401 9221 16401 9221 16402 8938 16402 8939 16402 9221 16403 8939 16403 8940 16403 9152 16404 9214 16404 9154 16404 9154 16405 9214 16405 9224 16405 9154 16406 9224 16406 9213 16406 9213 16407 9224 16407 9225 16407 9213 16408 9225 16408 9222 16408 9226 16409 9227 16409 9228 16409 8821 16410 8827 16410 9229 16410 8805 16411 8806 16411 9230 16411 8807 16412 8808 16412 9231 16412 9231 16413 8808 16413 8942 16413 9231 16414 8942 16414 8943 16414 8805 16415 9230 16415 8804 16415 8853 16416 8798 16416 8797 16416 8801 16417 8800 16417 8797 16417 8797 16418 8800 16418 9232 16418 8797 16419 9232 16419 8853 16419 9233 7968 8849 7968 9232 7968 9232 16420 8849 16420 8859 16420 9232 16421 8859 16421 8853 16421 9217 16422 8983 16422 9234 16422 9234 16423 8983 16423 8858 16423 9234 16424 8858 16424 8850 16424 9217 7974 9234 7974 9216 7974 9216 16425 9234 16425 9235 16425 9216 16426 9235 16426 9215 16426 9236 7977 9224 7977 9235 7977 9235 16427 9224 16427 9214 16427 9235 16428 9214 16428 9215 16428 9237 7980 9219 7980 9238 7980 9238 7981 9219 7981 9222 7981 9238 7982 9222 7982 9236 7982 9236 7983 9222 7983 9225 7983 9236 16429 9225 16429 9224 16429 9239 16430 9221 16430 9237 16430 9237 16431 9221 16431 9220 16431 9237 7987 9220 7987 9219 7987 8894 7988 9239 7988 8895 7988 8895 7989 9239 7989 8899 7989 8894 16432 8933 16432 9239 16432 9239 16433 8933 16433 9223 16433 9239 16434 9223 16434 9221 16434 8825 16435 8823 16435 9240 16435 9240 16436 8823 16436 8822 16436 9240 16437 8822 16437 8772 16437 8772 7996 8771 7996 9240 7996 9240 16438 8771 16438 8896 16438 9240 7998 8896 7998 8897 7998 8946 16439 8821 16439 8945 16439 8945 16440 8821 16440 9229 16440 8945 8001 9229 8001 8944 8001 8944 8002 9229 8002 9241 8002 9228 16441 9227 16441 9242 16441 9227 16442 9243 16442 9242 16442 9242 16443 9243 16443 9244 16443 9242 16444 9244 16444 9229 16444 9229 8007 9244 8007 9245 8007 9229 8008 9245 8008 9241 8008 9226 8009 9228 8009 9246 8009 9246 8010 9228 8010 9247 8010 9246 8011 9247 8011 9248 8011 9248 8012 9247 8012 9249 8012 9248 16445 9249 16445 9250 16445 9250 16446 9249 16446 9251 16446 9251 8015 9249 8015 9252 8015 9251 16447 9252 16447 9253 16447 9253 8017 9252 8017 9254 8017 9254 16448 9252 16448 9255 16448 9254 16449 9255 16449 9256 16449 9256 16450 9255 16450 9257 16450 9257 16451 9255 16451 9231 16451 9257 8022 9231 8022 9258 8022 9258 16452 9231 16452 8943 16452 9258 16453 8943 16453 8941 16453 8827 16454 8826 16454 9229 16454 9229 16455 8826 16455 9259 16455 9229 16456 9259 16456 9242 16456 9242 16457 9259 16457 9260 16457 9242 16458 9260 16458 9228 16458 9228 8030 9260 8030 9261 8030 9228 16459 9261 16459 9247 16459 9247 8032 9261 8032 9262 8032 9247 8033 9262 8033 9249 8033 9249 8034 9262 8034 9263 8034 9249 16460 9263 16460 9252 16460 9252 16461 9263 16461 9264 16461 9252 16462 9264 16462 9255 16462 9255 8038 9264 8038 9265 8038 9255 16463 9265 16463 9231 16463 9231 16464 9265 16464 9230 16464 9231 16465 9230 16465 8807 16465 8807 16466 9230 16466 8806 16466 8826 16467 8825 16467 9259 16467 9259 16468 8825 16468 9240 16468 9259 16469 9240 16469 9260 16469 9260 16470 9240 16470 9266 16470 9260 16471 9266 16471 9261 16471 9261 16472 9266 16472 9267 16472 9261 8049 9267 8049 9262 8049 9262 8050 9267 8050 9268 8050 9262 16473 9268 16473 9263 16473 9263 16474 9268 16474 9269 16474 9263 16475 9269 16475 9264 16475 9264 16476 9269 16476 9270 16476 9264 8055 9270 8055 9265 8055 9265 8056 9270 8056 9233 8056 9265 16477 9233 16477 9230 16477 9230 8058 9233 8058 9232 8058 9230 16478 9232 16478 8804 16478 8804 16479 9232 16479 8800 16479 8897 16480 8898 16480 9240 16480 9240 16481 8898 16481 8899 16481 9240 16482 8899 16482 9266 16482 9266 16483 8899 16483 9239 16483 9266 16484 9239 16484 9267 16484 9267 16485 9239 16485 9237 16485 9267 16486 9237 16486 9268 16486 9268 16487 9237 16487 9238 16487 9268 16488 9238 16488 9269 16488 9269 16489 9238 16489 9236 16489 9269 8072 9236 8072 9270 8072 9270 16490 9236 16490 9235 16490 9270 16491 9235 16491 9233 16491 9233 16492 9235 16492 9234 16492 9233 8076 9234 8076 8849 8076 8849 8077 9234 8077 8850 8077 8817 7922 8819 7922 8399 7922 8399 16493 8819 16493 8944 16493 8399 7924 8944 7924 9241 7924 8399 7925 8397 7925 8817 7925 8817 16494 8397 16494 8395 16494 8817 16495 8395 16495 8811 16495 8811 16496 8395 16496 8394 16496 8811 7929 8394 7929 8812 7929 8812 7930 8394 7930 8415 7930 8812 16497 8415 16497 8813 16497 8813 16498 8415 16498 8413 16498 8813 16499 8413 16499 8814 16499 9258 7934 8941 7934 8815 7934 8814 7935 8413 7935 8815 7935 8815 7936 8413 7936 8411 7936 8815 16500 8411 16500 9258 16500 8409 16501 9256 16501 8411 16501 8411 7939 9256 7939 9257 7939 8411 7940 9257 7940 9258 7940 8407 16502 9253 16502 8409 16502 8409 7942 9253 7942 9254 7942 8409 7943 9254 7943 9256 7943 8405 16503 9250 16503 8407 16503 8407 7945 9250 7945 9251 7945 8407 16504 9251 16504 9253 16504 8403 16505 9246 16505 8405 16505 8405 16506 9246 16506 9248 16506 8405 16507 9248 16507 9250 16507 8401 16508 9227 16508 8403 16508 8403 16509 9227 16509 9226 16509 8403 7952 9226 7952 9246 7952 9241 7953 9245 7953 8399 7953 8399 16510 9245 16510 9244 16510 8399 16511 9244 16511 8401 16511 8401 16512 9244 16512 9243 16512 8401 16513 9243 16513 9227 16513 8396 7919 8408 7919 8410 7919 8396 7920 8398 7920 8400 7920 8416 632 8393 632 8414 632 8414 7921 8393 7921 8396 7921 8414 632 8396 632 8412 632 8412 632 8396 632 8410 632 8406 632 8408 632 8404 632 8404 632 8408 632 8396 632 8404 632 8396 632 8402 632 8402 632 8396 632 8400 632 8786 95 8372 95 7312 95 8870 7917 8872 7917 8787 7917 8837 95 7312 95 8388 95 8388 95 7312 95 7311 95 8787 95 8786 95 8870 95 8870 95 8786 95 7312 95 8870 95 7312 95 8868 95 8868 95 7312 95 8837 95 8868 95 8837 95 8866 95 8866 95 8837 95 8836 95 8866 7918 8836 7918 8863 7918 8283 16514 8700 16514 8285 16514 8285 7903 8700 7903 8701 7903 8285 16515 8701 16515 8287 16515 8287 16516 8701 16516 8705 16516 8287 16517 8705 16517 8296 16517 8283 16518 8281 16518 8700 16518 8700 16519 8281 16519 8280 16519 8700 16520 8280 16520 8302 16520 8708 16521 8257 16521 8707 16521 8707 16522 8257 16522 8268 16522 8707 16523 8268 16523 8695 16523 8695 16524 8268 16524 8267 16524 8695 7916 8267 7916 8696 7916 8696 16525 8267 16525 8266 16525 8696 16526 8266 16526 8703 16526 8703 16527 8266 16527 8301 16527 8703 16528 8301 16528 8704 16528 8704 16529 8301 16529 8299 16529 8704 16530 8299 16530 8705 16530 8705 16531 8299 16531 8297 16531 8705 16532 8297 16532 8296 16532 8378 16533 8377 16533 8376 16533 8302 7884 8378 7884 8791 7884 8791 16534 8378 16534 8376 16534 8791 16535 8376 16535 8793 16535 8793 16536 8376 16536 8375 16536 8793 16537 8375 16537 8795 16537 8795 7889 8375 7889 8374 7889 8795 7890 8374 7890 8796 7890 8796 16538 8374 16538 8380 16538 8796 16539 8380 16539 8788 16539 8372 7893 8786 7893 8373 7893 8373 7894 8786 7894 8788 7894 8373 16540 8788 16540 8379 16540 8379 16541 8788 16541 8380 16541 8837 7872 8388 7872 8389 7872 8837 7873 8389 7873 8835 7873 8835 16542 8389 16542 8392 16542 8835 16543 8392 16543 8833 16543 8833 16544 8392 16544 8391 16544 8833 16545 8391 16545 8830 16545 8830 16546 8391 16546 8390 16546 8830 7879 8390 7879 8387 7879 8387 16547 8386 16547 8830 16547 8830 16548 8386 16548 8385 16548 8830 7882 8385 7882 8343 7882 8660 16549 8659 16549 8720 16549 8747 16550 8751 16550 8628 16550 8660 16551 8720 16551 8651 16551 8651 16552 8720 16552 8719 16552 8651 16553 8719 16553 8628 16553 8628 16554 8719 16554 8748 16554 8628 16555 8748 16555 8747 16555 8324 16556 8323 16556 8730 16556 8730 16557 8323 16557 8628 16557 8730 16558 8628 16558 8731 16558 8731 16559 8628 16559 8751 16559 8683 16560 9271 16560 8668 16560 8668 16561 9271 16561 9272 16561 8668 16562 9272 16562 9273 16562 9274 16563 8664 16563 9273 16563 9273 16564 8664 16564 8666 16564 9273 16565 8666 16565 8668 16565 8708 16566 8709 16566 8599 16566 8599 16567 8709 16567 8710 16567 8599 16568 8710 16568 8711 16568 8659 16569 8664 16569 8720 16569 8720 16570 8664 16570 9274 16570 8720 16571 9274 16571 8726 16571 8726 16572 9274 16572 9275 16572 8726 16573 9275 16573 8717 16573 8717 16574 9275 16574 8691 16574 8717 16575 8691 16575 8711 16575 8711 16576 8691 16576 8602 16576 8711 16577 8602 16577 8599 16577 8257 7855 8708 7855 8249 7855 8249 16578 8708 16578 8599 16578 8249 16579 8599 16579 8250 16579 8250 16580 8599 16580 8598 16580 8250 16581 8598 16581 8595 16581 8489 16582 8252 16582 8603 16582 8603 16583 8252 16583 8250 16583 8603 16584 8250 16584 8604 16584 8604 16585 8250 16585 8595 16585 8631 16586 8309 16586 8629 16586 8629 16587 8309 16587 8308 16587 8629 16588 8308 16588 8459 16588 8631 16589 8634 16589 8309 16589 8309 16590 8634 16590 8633 16590 8309 16591 8633 16591 8323 16591 8323 16592 8633 16592 8626 16592 8323 16593 8626 16593 8628 16593 8828 16594 8343 16594 8843 16594 8843 16595 8343 16595 8744 16595 8843 16596 8744 16596 8799 16596 8799 98 8744 98 8757 98 1369 98 1368 98 8384 98 8384 98 1368 98 8343 98 8384 98 8343 98 8385 98 8378 106 8302 106 8371 106 8371 106 8302 106 8367 106 258 16597 4157 16597 9276 16597 248 95 9277 95 8243 95 8243 95 9277 95 9278 95 8243 16598 9278 16598 8244 16598 9276 95 9279 95 258 95 258 95 9279 95 9280 95 258 95 9280 95 248 95 248 95 9280 95 9281 95 248 95 9281 95 9277 95 7381 106 7380 106 7386 106 7386 106 7380 106 7530 106 7359 7815 7358 7815 7531 7815 7531 7816 7358 7816 7382 7816 7531 7817 7382 7817 7532 7817 7532 7818 7382 7818 7388 7818 7532 7819 7388 7819 7530 7819 7530 7819 7388 7819 7386 7819 7843 98 9282 98 7329 98 7648 16599 7836 16599 7327 16599 7836 98 7838 98 7327 98 7327 16600 7838 16600 7839 16600 7327 98 7839 98 7329 98 7329 16601 7839 16601 7841 16601 7329 16602 7841 16602 7843 16602 7327 16603 8004 16603 8006 16603 8006 98 8010 98 7327 98 7327 16604 8010 16604 8008 16604 7327 16605 8008 16605 7648 16605 7648 16606 8008 16606 7647 16606 7648 98 7647 98 7649 98 7647 98 7642 98 7649 98 7649 16607 7642 16607 7640 16607 7649 98 7640 98 7627 98 7627 16608 7640 16608 7639 16608 7627 16609 7639 16609 7628 16609 7328 106 7997 106 7326 106 7326 16610 7997 16610 7996 16610 7326 16611 7996 16611 7995 16611 7330 95 7988 95 7991 95 8000 7801 7328 7801 8002 7801 8002 16612 7328 16612 7330 16612 8002 16613 7330 16613 7993 16613 7993 16614 7330 16614 7991 16614 8000 7802 7999 7802 7328 7802 7328 95 7999 95 7998 95 7328 95 7998 95 7997 95 7989 16615 7988 16615 7330 16615 7331 106 9283 106 8072 106 8072 106 8071 106 7331 106 7331 16616 8071 16616 8087 16616 7331 106 8087 106 7330 106 7330 16617 8087 16617 8089 16617 7865 106 7881 106 7873 106 7873 16618 7881 16618 7852 16618 8089 106 8091 106 7330 106 7330 16619 8091 16619 8093 16619 7330 16620 8093 16620 7989 16620 7989 16621 8093 16621 7863 16621 7989 16622 7863 16622 7873 16622 7873 16623 7863 16623 7865 16623 7852 16624 7866 16624 7873 16624 7873 16625 7866 16625 7868 16625 7873 16626 7868 16626 7871 16626 9284 16627 9285 16627 9286 16627 8072 16628 9283 16628 8073 16628 8073 16629 9283 16629 9284 16629 8073 16630 9284 16630 8082 16630 9284 16631 9286 16631 8082 16631 8082 16632 9286 16632 8422 16632 8082 16633 8422 16633 8083 16633 8607 16634 8686 16634 9287 16634 9287 16635 8686 16635 9288 16635 9001 16636 7322 16636 9002 16636 9002 16637 7322 16637 7321 16637 9002 7737 7321 7737 9003 7737 9001 16638 9008 16638 7322 16638 7322 16639 9008 16639 9010 16639 7322 16640 9010 16640 7323 16640 7323 16641 9010 16641 8989 16641 7323 16642 8989 16642 8988 16642 7325 16643 7324 16643 8996 16643 8996 16644 9006 16644 7325 16644 7325 16645 9006 16645 9005 16645 7325 16646 9005 16646 7321 16646 7321 16647 9005 16647 9004 16647 7321 16648 9004 16648 9003 16648 9000 16649 8999 16649 7317 16649 7317 16650 8999 16650 8998 16650 7317 16651 8998 16651 7324 16651 7324 7752 8998 7752 8997 7752 7324 7753 8997 7753 8996 7753 9000 7754 7317 7754 8992 7754 8992 7755 7317 7755 7316 7755 8992 16652 7316 16652 8993 16652 9106 16653 7314 16653 9107 16653 9107 16654 7314 16654 7313 16654 9107 16655 7313 16655 9109 16655 9109 16656 7313 16656 7320 16656 9109 16657 7320 16657 9111 16657 9111 16658 7320 16658 7319 16658 9111 16659 7319 16659 9113 16659 9113 16660 7319 16660 7318 16660 9113 16661 7318 16661 9115 16661 9115 16662 7318 16662 7323 16662 9115 7767 7323 7767 9099 7767 9099 7768 7323 7768 8988 7768 9099 16663 8988 16663 9100 16663 9116 16664 8993 16664 9117 16664 9117 7771 8993 7771 7316 7771 9117 7772 7316 7772 9105 7772 9105 16665 7316 16665 7314 16665 9105 16666 7314 16666 9104 16666 9104 16667 7314 16667 9106 16667 9289 16668 9290 16668 1425 16668 1425 16669 9290 16669 1427 16669 9291 16670 9292 16670 9293 16670 9293 633 9292 633 9294 633 9293 633 9294 633 9295 633 9296 13243 9297 13243 9293 13243 9293 16671 9297 16671 9298 16671 9293 16672 9298 16672 9291 16672 9299 633 9300 633 9293 633 9293 633 9300 633 9301 633 9293 633 9301 633 9296 633 9295 633 9302 633 9293 633 9293 16673 9302 16673 9303 16673 9293 16674 9303 16674 9299 16674 9304 633 9305 633 9306 633 9306 633 9305 633 9307 633 9306 633 9307 633 9308 633 9308 633 9307 633 9309 633 9310 16675 9311 16675 9312 16675 9310 11384 9312 11384 9313 11384 9313 16676 9312 16676 9314 16676 9313 16677 9314 16677 9315 16677 9311 16678 9310 16678 9316 16678 9311 16679 9316 16679 9317 16679 9317 16680 9316 16680 9318 16680 9317 16681 9318 16681 9319 16681 9319 16682 9318 16682 9320 16682 9319 16683 9320 16683 9321 16683 9322 16684 9323 16684 9324 16684 9322 16685 9324 16685 9325 16685 9325 16686 9324 16686 9326 16686 9325 16687 9326 16687 9327 16687 9327 16688 9326 16688 9314 16688 9314 16689 9326 16689 9315 16689 9321 16690 9320 16690 9328 16690 9329 11368 9330 11368 9328 11368 9328 16691 9330 16691 9331 16691 9328 13259 9331 13259 9321 13259 9332 13260 9333 13260 9334 13260 9332 16692 9334 16692 9335 16692 9335 16693 9334 16693 9323 16693 9335 16694 9323 16694 9322 16694 9336 11343 9337 11343 9338 11343 9336 11344 9338 11344 9339 11344 9339 11345 9338 11345 9340 11345 9339 11346 9340 11346 9341 11346 9341 11347 9340 11347 9342 11347 9341 16695 9342 16695 9343 16695 9343 11350 9342 11350 9344 11350 9343 16696 9344 16696 9345 16696 9345 16697 9344 16697 9346 16697 9345 11351 9346 11351 9347 11351 9347 11352 9346 11352 9348 11352 9347 11353 9348 11353 9349 11353 9349 11354 9348 11354 9350 11354 9349 11355 9350 11355 9351 11355 9351 16698 9350 16698 9352 16698 9351 11357 9352 11357 9353 11357 9353 11358 9352 11358 9354 11358 9353 11359 9354 11359 9355 11359 9355 11361 9354 11361 9356 11361 9355 11361 9356 11361 9357 11361 9357 16699 9356 16699 9358 16699 9357 11362 9358 11362 9359 11362 9323 16700 9334 16700 9333 16700 9333 16701 9360 16701 9361 16701 9326 95 9324 95 9323 95 9362 95 9336 95 9363 95 9363 95 9336 95 9364 95 9363 95 9364 95 9365 95 9365 16702 9364 16702 9366 16702 9365 95 9366 95 9359 95 9333 95 9336 95 9339 95 9333 16703 9361 16703 9336 16703 9336 16704 9361 16704 9367 16704 9336 95 9367 95 9364 95 9351 95 9353 95 9368 95 9355 95 9369 95 9353 95 9353 95 9369 95 9370 95 9353 95 9370 95 9368 95 9366 95 9371 95 9359 95 9359 16705 9371 16705 9372 16705 9359 16706 9372 16706 9357 16706 9357 16707 9372 16707 9373 16707 9357 95 9373 95 9374 95 9349 95 9329 95 9347 95 9347 95 9329 95 9328 95 9347 95 9328 95 9345 95 9345 95 9328 95 9320 95 9345 95 9320 95 9343 95 9343 95 9320 95 9341 95 9368 95 9375 95 9351 95 9351 16708 9375 16708 9376 16708 9351 95 9376 95 9349 95 9349 95 9376 95 9377 95 9349 95 9377 95 9329 95 9329 95 9377 95 9378 95 9329 95 9378 95 9379 95 9374 95 9380 95 9357 95 9357 95 9380 95 9381 95 9357 95 9381 95 9355 95 9355 95 9381 95 9382 95 9355 95 9382 95 9369 95 9316 95 9310 95 9313 95 9339 16709 9341 16709 9333 16709 9333 16710 9341 16710 9320 16710 9333 16711 9320 16711 9323 16711 9323 16712 9320 16712 9318 16712 9323 95 9318 95 9326 95 9326 95 9318 95 9316 95 9326 95 9316 95 9315 95 9315 95 9316 95 9313 95 9383 95 9384 95 9385 95 9385 95 9384 95 9386 95 9385 95 9386 95 9387 95 9388 95 9389 95 9385 95 9385 95 9389 95 9390 95 9385 95 9390 95 9383 95 9391 95 9392 95 9385 95 9385 95 9392 95 9393 95 9385 95 9393 95 9388 95 9387 95 9394 95 9385 95 9385 95 9394 95 9395 95 9385 95 9395 95 9391 95 9393 16713 9396 16713 9388 16713 9388 16714 9396 16714 9397 16714 9388 16715 9397 16715 9389 16715 9389 16716 9397 16716 9398 16716 9389 16717 9398 16717 9390 16717 9390 16718 9398 16718 9399 16718 9390 16719 9399 16719 9383 16719 9383 16720 9399 16720 9400 16720 9383 11307 9400 11307 9384 11307 9384 16721 9400 16721 9401 16721 9384 11308 9401 11308 9386 11308 9386 16722 9401 16722 9402 16722 9386 16722 9402 16722 9387 16722 9387 11311 9402 11311 9403 11311 9387 16723 9403 16723 9394 16723 9394 16724 9403 16724 9404 16724 9394 16725 9404 16725 9395 16725 9395 16726 9404 16726 9405 16726 9395 16727 9405 16727 9391 16727 9391 16728 9405 16728 9406 16728 9391 16729 9406 16729 9392 16729 9392 16730 9406 16730 9407 16730 9392 16731 9407 16731 9393 16731 9393 16732 9407 16732 9396 16732 9408 16733 9409 16733 9410 16733 9410 16734 9411 16734 9408 16734 9408 13312 9411 13312 9412 13312 9408 13313 9412 13313 9413 13313 9414 13314 9415 13314 9416 13314 9417 16735 9418 16735 9416 16735 9416 16736 9418 16736 9419 16736 9416 16737 9419 16737 9414 16737 9409 16738 9420 16738 9410 16738 9410 13319 9420 13319 9417 13319 9410 16739 9417 16739 9421 16739 9421 16740 9417 16740 9416 16740 9422 16741 9423 16741 9424 16741 9425 13323 9426 13323 9427 13323 9428 13324 158 13324 159 13324 9429 13325 143 13325 158 13325 9430 16742 9431 16742 9432 16742 9432 16743 9431 16743 9433 16743 9432 16744 9433 16744 9434 16744 158 13329 9428 13329 9429 13329 9429 13330 9428 13330 9435 13330 9429 16745 9435 16745 9436 16745 9436 16746 9435 16746 9431 16746 9436 16747 9431 16747 9437 16747 9437 16748 9431 16748 9430 16748 9437 13335 9430 13335 9415 13335 9426 13336 9425 13336 9433 13336 9433 16749 9425 16749 9438 16749 9433 16750 9438 16750 9434 16750 9423 16751 9439 16751 9424 16751 9424 16752 9439 16752 9440 16752 9424 16753 9440 16753 9441 16753 9441 16754 9440 16754 9442 16754 9441 16755 9442 16755 9443 16755 9444 16756 9445 16756 9441 16756 9441 13345 9445 13345 9446 13345 9441 16757 9446 16757 9424 16757 9424 16758 9446 16758 9447 16758 9424 16759 9447 16759 9422 16759 9422 16760 9447 16760 9448 16760 9422 16761 9448 16761 9449 16761 9450 16762 9451 16762 9444 16762 9444 16763 9451 16763 9452 16763 9444 13353 9452 13353 9445 13353 9453 13354 9454 13354 9455 13354 9455 16764 9454 16764 9456 16764 9455 16765 9456 16765 9450 16765 9450 16766 9456 16766 9457 16766 9450 16767 9457 16767 9451 16767 160 13359 9454 13359 159 13359 159 13360 9454 13360 9453 13360 159 13361 9453 13361 9428 13361 9428 13362 9453 13362 9455 13362 9428 13363 9455 13363 9435 13363 9435 13364 9455 13364 9450 13364 9435 16768 9450 16768 9431 16768 9431 16769 9450 16769 9444 16769 9431 16770 9444 16770 9433 16770 9433 16771 9444 16771 9441 16771 9433 16772 9441 16772 9426 16772 9426 16773 9441 16773 9443 16773 9426 16774 9443 16774 9427 16774 9458 16775 9459 16775 9460 16775 9461 16776 9462 16776 9463 16776 9464 16777 9465 16777 9466 16777 9464 16778 9466 16778 9467 16778 9466 16779 9468 16779 9467 16779 9467 16780 9468 16780 9469 16780 9467 16781 9469 16781 9470 16781 9470 16782 9469 16782 9471 16782 9470 16783 9471 16783 9472 16783 9472 16784 9471 16784 9473 16784 9473 16785 9471 16785 9474 16785 9474 16786 9471 16786 9475 16786 9474 16787 9475 16787 9476 16787 9476 16788 9475 16788 9477 16788 9476 16789 9477 16789 9478 16789 9478 16790 9477 16790 9479 16790 9479 16791 9477 16791 9480 16791 9479 16792 9480 16792 9481 16792 9482 16793 9481 16793 9483 16793 9483 16794 9481 16794 9480 16794 9483 16795 9480 16795 9484 16795 9484 16796 9480 16796 9485 16796 9485 16797 9480 16797 9486 16797 9486 16798 9480 16798 9477 16798 9486 16799 9477 16799 9462 16799 9461 16800 9463 16800 9487 16800 9458 16801 9488 16801 9459 16801 9459 16802 9488 16802 9489 16802 9459 16803 9489 16803 9463 16803 9463 16804 9489 16804 9490 16804 9463 16805 9490 16805 9487 16805 9491 16806 9492 16806 9493 16806 9493 16807 9492 16807 9494 16807 9493 16808 9494 16808 9460 16808 9460 16809 9494 16809 9495 16809 9460 16810 9495 16810 9458 16810 9462 16811 9477 16811 9463 16811 9463 16812 9477 16812 9475 16812 9463 16813 9475 16813 9459 16813 9459 16814 9475 16814 9471 16814 9459 16815 9471 16815 9460 16815 9460 16816 9471 16816 9469 16816 9460 16817 9469 16817 9493 16817 9493 16818 9469 16818 9468 16818 9493 16819 9468 16819 9491 16819 9491 16820 9468 16820 9466 16820 9491 16821 9466 16821 9492 16821 9492 16822 9466 16822 9496 16822 9492 16823 9496 16823 9497 16823 9498 16824 9499 16824 9500 16824 9500 16825 9499 16825 9501 16825 9500 16826 9501 16826 9502 16826 9502 16827 9501 16827 9503 16827 9502 16828 9503 16828 9504 16828 9504 16829 9503 16829 9505 16829 9505 16830 9503 16830 9506 16830 9505 16831 9506 16831 9507 16831 9495 16832 9508 16832 9507 16832 9507 16833 9508 16833 9509 16833 9509 16834 9510 16834 9507 16834 9507 16835 9510 16835 9511 16835 9507 16836 9511 16836 9505 16836 9397 16837 9396 16837 9512 16837 9512 95 9358 95 9397 95 9397 95 9358 95 9356 95 9397 95 9356 95 9398 95 9398 95 9356 95 9354 95 9398 16838 9354 16838 9399 16838 9399 16839 9354 16839 9352 16839 9399 16840 9352 16840 9400 16840 9400 95 9352 95 9350 95 9400 95 9350 95 9401 95 9401 16841 9350 16841 9348 16841 9401 95 9348 95 9402 95 9402 95 9348 95 9346 95 9402 16842 9346 16842 9403 16842 9403 95 9346 95 9344 95 9403 95 9344 95 9404 95 9404 95 9344 95 9342 95 9404 95 9342 95 9405 95 9405 16843 9342 16843 9340 16843 9405 95 9340 95 9406 95 9406 95 9340 95 9338 95 9406 95 9338 95 9407 95 9338 95 9337 95 9407 95 9407 95 9337 95 9513 95 9407 95 9513 95 9396 95 9396 16844 9513 16844 9514 16844 9396 16845 9514 16845 9512 16845 9442 13444 9515 13444 9516 13444 9517 16846 9518 16846 9449 16846 9519 16847 9520 16847 9521 16847 9416 13447 9522 13447 9421 13447 9421 13448 9522 13448 9523 13448 9421 16848 9523 16848 9410 16848 9410 16849 9523 16849 9411 16849 9411 13451 9523 13451 9524 13451 9411 13452 9524 13452 9525 13452 9525 16850 9526 16850 9411 16850 9411 16851 9526 16851 9527 16851 9411 13455 9527 13455 9412 13455 9528 13456 9413 13456 9529 13456 9529 13457 9413 13457 9412 13457 9529 13458 9412 13458 9530 13458 9530 13459 9412 13459 9527 13459 9531 16852 9532 16852 9523 16852 9523 16853 9532 16853 9533 16853 9533 16854 9534 16854 9523 16854 9523 16855 9534 16855 9535 16855 9523 13464 9535 13464 9524 13464 9524 13465 9535 13465 9536 13465 9524 13466 9536 13466 9525 13466 9522 16856 9537 16856 9523 16856 9523 16857 9537 16857 9538 16857 9523 16858 9538 16858 9531 16858 9531 16859 9538 16859 9539 16859 9531 16860 9539 16860 9540 16860 9540 16861 9539 16861 9521 16861 9540 16862 9521 16862 9541 16862 9541 16863 9521 16863 9520 16863 9518 13475 9517 13475 9542 13475 9440 13476 9439 13476 9542 13476 9542 13477 9439 13477 9423 13477 9542 16864 9423 16864 9518 16864 9518 16865 9423 16865 9422 16865 9518 16866 9422 16866 9449 16866 9442 13481 9440 13481 9515 13481 9515 13482 9440 13482 9542 13482 9515 13483 9542 13483 9543 13483 9543 13484 9542 13484 9517 13484 9543 16867 9517 16867 9544 16867 9430 16868 9432 16868 9545 16868 9545 16869 9432 16869 9434 16869 9545 13488 9434 13488 9546 13488 9546 16870 9434 16870 9438 16870 9546 16871 9438 16871 9547 16871 9547 16872 9438 16872 9425 16872 9547 16873 9425 16873 9548 16873 9548 16874 9425 16874 9427 16874 9548 16875 9427 16875 9516 16875 9516 16876 9427 16876 9443 16876 9516 16877 9443 16877 9442 16877 9543 13497 9549 13497 9515 13497 9515 13498 9549 13498 9519 13498 9515 13499 9519 13499 9516 13499 9516 13500 9519 13500 9521 13500 9516 16878 9521 16878 9548 16878 9548 13502 9521 13502 9539 13502 9548 16879 9539 16879 9547 16879 9547 16880 9539 16880 9538 16880 9547 13504 9538 13504 9546 13504 9546 13505 9538 13505 9537 13505 9546 13506 9537 13506 9545 13506 9545 16881 9537 16881 9522 16881 9545 13508 9522 13508 9430 13508 9430 13509 9522 13509 9416 13509 9430 13510 9416 13510 9415 13510 9550 16882 9551 16882 9552 16882 9485 16883 9486 16883 9553 16883 9489 16884 9488 16884 9554 16884 9555 16885 9556 16885 9557 16885 9557 16886 9556 16886 9558 16886 9557 16887 9558 16887 9559 16887 9559 16888 9558 16888 9560 16888 9561 16889 9562 16889 9563 16889 9563 16890 9562 16890 9564 16890 9564 16891 9565 16891 9563 16891 9563 16892 9565 16892 9566 16892 9563 16893 9566 16893 9567 16893 9568 16894 9569 16894 9561 16894 9561 16895 9569 16895 9570 16895 9561 16896 9570 16896 9562 16896 9562 16897 9570 16897 9571 16897 9562 16898 9571 16898 9564 16898 9561 16899 9501 16899 9499 16899 9568 11056 9561 11056 9572 11056 9572 16900 9561 16900 9499 16900 9572 11058 9499 11058 9498 11058 9503 11059 9573 11059 9506 11059 9506 16901 9573 16901 9574 16901 9506 16902 9574 16902 9507 16902 9507 16903 9574 16903 9554 16903 9488 16904 9458 16904 9554 16904 9554 16905 9458 16905 9495 16905 9554 16906 9495 16906 9507 16906 9461 16907 9487 16907 9575 16907 9575 16908 9487 16908 9490 16908 9485 16909 9553 16909 9484 16909 9576 16910 9577 16910 9578 16910 9578 16911 9577 16911 9579 16911 9578 16912 9579 16912 9580 16912 9580 16913 9579 16913 9482 16913 9580 16914 9482 16914 9483 16914 9551 16915 9550 16915 9581 16915 9550 16916 9576 16916 9581 16916 9581 16917 9576 16917 9578 16917 9581 16918 9578 16918 9553 16918 9553 16919 9578 16919 9580 16919 9553 16920 9580 16920 9484 16920 9484 16921 9580 16921 9483 16921 9560 16922 9582 16922 9559 16922 9559 16923 9582 16923 9583 16923 9559 16924 9583 16924 9557 16924 9557 16925 9583 16925 9563 16925 9557 16926 9563 16926 9555 16926 9555 16927 9563 16927 9567 16927 9486 16928 9462 16928 9553 16928 9553 16929 9462 16929 9461 16929 9553 16930 9461 16930 9581 16930 9581 16931 9461 16931 9575 16931 9581 16932 9575 16932 9551 16932 9551 16933 9575 16933 9583 16933 9551 16934 9583 16934 9552 16934 9552 16935 9583 16935 9582 16935 9490 16936 9489 16936 9575 16936 9575 16937 9489 16937 9554 16937 9575 16938 9554 16938 9583 16938 9583 16939 9554 16939 9574 16939 9583 16940 9574 16940 9563 16940 9563 16941 9574 16941 9573 16941 9563 16942 9573 16942 9561 16942 9561 16943 9573 16943 9503 16943 9561 16944 9503 16944 9501 16944 9519 13577 9549 13577 9584 13577 9543 16945 9544 16945 9585 16945 9586 16946 9587 16946 9360 16946 9360 16947 9587 16947 9588 16947 9360 16948 9588 16948 9361 16948 9361 16949 9588 16949 9585 16949 9361 16950 9585 16950 9367 16950 9589 16951 9540 16951 9590 16951 9590 16952 9540 16952 9541 16952 9590 13586 9541 13586 9584 13586 9584 13587 9541 13587 9520 13587 9584 16953 9520 16953 9519 16953 9586 16954 9589 16954 9587 16954 9587 16955 9589 16955 9590 16955 9587 16956 9590 16956 9588 16956 9588 13592 9590 13592 9584 13592 9588 16957 9584 16957 9585 16957 9585 13594 9584 13594 9549 13594 9585 16958 9549 16958 9543 16958 9332 16959 9591 16959 9592 16959 9360 16960 9333 16960 9593 16960 9593 16961 9333 16961 9332 16961 9593 16962 9332 16962 9594 16962 9594 16963 9332 16963 9592 16963 9529 16964 9595 16964 9528 16964 9536 16965 9535 16965 9596 16965 9533 16966 9532 16966 9589 16966 9589 16967 9532 16967 9531 16967 9589 16968 9531 16968 9540 16968 9535 16969 9534 16969 9596 16969 9596 13607 9534 13607 9533 13607 9596 16970 9533 16970 9597 16970 9597 16971 9533 16971 9589 16971 9597 16972 9589 16972 9586 16972 9526 13611 9525 13611 9592 13611 9592 16973 9591 16973 9526 16973 9526 16974 9591 16974 9598 16974 9526 16975 9598 16975 9527 16975 9595 16976 9529 16976 9598 16976 9598 13616 9529 13616 9530 13616 9598 13617 9530 13617 9527 13617 9525 13618 9536 13618 9592 13618 9592 16977 9536 16977 9596 16977 9592 16978 9596 16978 9594 16978 9594 16979 9596 16979 9597 16979 9594 16980 9597 16980 9593 16980 9593 16981 9597 16981 9586 16981 9593 13624 9586 13624 9360 13624 9599 16982 9600 16982 9601 16982 9566 16983 9602 16983 9567 16983 9603 16984 9604 16984 9599 16984 9605 16985 9570 16985 9569 16985 9556 16986 9555 16986 9601 16986 9556 16987 9606 16987 9558 16987 9558 10973 9606 10973 9607 10973 9558 16988 9607 16988 9560 16988 9556 16989 9601 16989 9606 16989 9606 16990 9601 16990 9600 16990 9606 16991 9600 16991 9379 16991 9605 16992 9569 16992 9608 16992 9608 16993 9569 16993 9568 16993 9608 16994 9568 16994 9572 16994 9570 16995 9605 16995 9571 16995 9571 16996 9605 16996 9603 16996 9571 16997 9603 16997 9564 16997 9555 16998 9567 16998 9601 16998 9601 16999 9567 16999 9602 16999 9601 17000 9602 17000 9599 17000 9599 17001 9602 17001 9566 17001 9599 17002 9566 17002 9603 17002 9603 17003 9566 17003 9565 17003 9603 17004 9565 17004 9564 17004 9599 17005 9604 17005 9600 17005 9600 17006 9604 17006 9330 17006 9600 17007 9330 17007 9379 17007 9379 17008 9330 17008 9329 17008 9609 17009 9610 17009 9611 17009 9612 13654 9613 13654 9614 13654 9612 17010 9614 17010 9615 17010 9616 17011 9617 17011 9618 17011 9617 17012 9619 17012 9620 17012 9621 17013 9622 17013 9623 17013 9623 17014 9622 17014 9624 17014 9625 13660 9626 13660 9627 13660 9627 13661 9626 13661 9623 13661 9627 13662 9623 13662 9628 13662 9628 17015 9623 17015 9624 17015 9628 17016 9624 17016 9629 17016 9630 17017 9631 17017 9632 17017 9631 17018 9609 17018 9632 17018 9632 17019 9609 17019 9611 17019 9632 17020 9611 17020 9633 17020 9633 17021 9611 17021 9634 17021 9633 17022 9634 17022 9614 17022 9614 17023 9634 17023 9618 17023 9614 13672 9618 13672 9615 13672 9615 13673 9618 13673 9617 13673 9615 13674 9617 13674 9635 13674 9635 13675 9617 13675 9620 13675 9610 17024 9621 17024 9611 17024 9611 17025 9621 17025 9623 17025 9611 17026 9623 17026 9634 17026 9634 17027 9623 17027 9626 17027 9634 17028 9626 17028 9618 17028 9618 13681 9626 13681 9625 13681 9618 17029 9625 17029 9616 17029 9630 17030 9632 17030 9636 17030 9636 13683 9632 13683 9633 13683 9636 13684 9633 13684 9637 13684 9637 13685 9633 13685 9614 13685 9637 13686 9614 13686 9638 13686 9638 13687 9614 13687 9613 13687 9638 17031 9613 17031 9639 17031 9582 17032 9560 17032 9640 17032 9640 17033 9560 17033 9607 17033 9377 17034 9641 17034 9642 17034 9643 17035 9644 17035 9577 17035 9377 10912 9642 10912 9378 10912 9378 17036 9642 17036 9606 17036 9378 17037 9606 17037 9379 17037 9577 17038 9576 17038 9643 17038 9643 17039 9576 17039 9550 17039 9643 17040 9550 17040 9640 17040 9640 17041 9550 17041 9552 17041 9640 17042 9552 17042 9582 17042 9377 10920 9644 10920 9641 10920 9641 17043 9644 17043 9643 17043 9641 17044 9643 17044 9642 17044 9642 17045 9643 17045 9640 17045 9642 17046 9640 17046 9606 17046 9606 17047 9640 17047 9607 17047 9645 17048 9646 17048 9413 17048 9413 17049 9646 17049 9647 17049 9413 17050 9647 17050 9408 17050 9645 17051 9413 17051 9648 17051 9648 17052 9413 17052 9332 17052 9648 17053 9332 17053 9335 17053 9598 17054 9591 17054 9595 17054 9595 17055 9591 17055 9332 17055 9595 17056 9332 17056 9528 17056 9528 17057 9332 17057 9413 17057 9314 17058 9649 17058 9327 17058 9327 17059 9649 17059 9650 17059 9327 13719 9650 13719 9325 13719 9325 17060 9650 17060 9648 17060 9325 17061 9648 17061 9322 17061 9322 17062 9648 17062 9335 17062 9650 17063 9649 17063 9651 17063 9651 17064 9649 17064 9652 17064 9311 17065 9653 17065 9654 17065 9311 17066 9654 17066 9312 17066 9312 17067 9654 17067 9652 17067 9312 17068 9652 17068 9314 17068 9314 17069 9652 17069 9649 17069 9319 17070 9321 17070 9331 17070 9604 17071 9603 17071 9655 17071 9500 17072 9656 17072 9498 17072 9498 17073 9656 17073 9657 17073 9657 17074 9658 17074 9498 17074 9498 17075 9658 17075 9655 17075 9498 17076 9655 17076 9572 17076 9319 17077 9655 17077 9317 17077 9317 10877 9655 10877 9653 10877 9317 17078 9653 17078 9311 17078 9319 17079 9331 17079 9655 17079 9655 17080 9331 17080 9330 17080 9655 17081 9330 17081 9604 17081 9603 17082 9605 17082 9655 17082 9655 17083 9605 17083 9608 17083 9655 17084 9608 17084 9572 17084 9659 17085 9660 17085 9661 17085 9662 17086 9663 17086 9664 17086 9664 17087 9665 17087 9662 17087 9662 17088 9665 17088 9666 17088 9662 17089 9666 17089 9667 17089 9666 17090 9668 17090 9667 17090 9667 17091 9668 17091 9669 17091 9667 17092 9669 17092 9670 17092 9670 17093 9669 17093 9659 17093 9659 17094 9661 17094 9670 17094 9670 17095 9661 17095 9671 17095 9670 17096 9671 17096 9672 17096 9672 17097 9671 17097 9673 17097 9672 17098 9673 17098 9674 17098 9675 13754 9664 13754 9663 13754 9676 17099 9677 17099 9678 17099 9679 10846 9677 10846 9680 10846 9680 17100 9677 17100 9676 17100 9680 13758 9676 13758 9681 13758 9681 17101 9676 17101 9682 17101 9675 17102 9663 17102 9678 17102 9678 17103 9663 17103 9683 17103 9678 17104 9683 17104 9676 17104 9676 17105 9683 17105 9684 17105 9676 13764 9684 13764 9682 13764 9671 17106 9661 17106 9685 17106 9685 632 9661 632 9660 632 9685 17107 9660 17107 9659 17107 9686 17108 9687 17108 9688 17108 9688 17109 9687 17109 9689 17109 9690 632 9691 632 9685 632 9685 17110 9691 17110 9692 17110 9685 17111 9692 17111 9693 17111 9685 17112 9679 17112 9694 17112 9687 17113 9685 17113 9695 17113 9696 632 9690 632 9697 632 9697 17114 9690 17114 9685 17114 9697 632 9685 632 9698 632 9698 632 9685 632 9687 632 9666 632 9685 632 9668 632 9668 17115 9685 17115 9659 17115 9668 17116 9659 17116 9669 17116 9699 17117 9700 17117 9687 17117 9687 13777 9700 13777 9701 13777 9687 17118 9701 17118 9689 17118 9666 17119 9665 17119 9685 17119 9685 632 9665 632 9664 632 9685 632 9664 632 9675 632 9702 632 9703 632 9694 632 9694 17120 9703 17120 9704 17120 9694 17121 9704 17121 9685 17121 9695 17122 9705 17122 9687 17122 9687 17123 9705 17123 9706 17123 9687 17124 9706 17124 9699 17124 9693 17125 9707 17125 9685 17125 9685 17126 9707 17126 9673 17126 9685 17127 9673 17127 9671 17127 9675 632 9678 632 9685 632 9685 17128 9678 17128 9677 17128 9685 17129 9677 17129 9679 17129 9708 13790 9709 13790 9710 13790 9710 17130 9709 17130 9711 17130 9710 17131 9711 17131 9712 17131 9585 17132 9544 17132 9712 17132 9712 17133 9711 17133 9585 17133 9585 17134 9711 17134 9364 17134 9585 17135 9364 17135 9367 17135 9708 13797 9713 13797 9709 13797 9709 13798 9713 13798 9371 13798 9709 13799 9371 13799 9711 13799 9711 17136 9371 17136 9366 17136 9711 17137 9366 17137 9364 17137 9380 13802 9374 13802 9714 13802 9714 17138 9374 17138 9373 17138 9714 17139 9373 17139 9713 17139 9713 17140 9373 17140 9372 17140 9713 17141 9372 17141 9371 17141 9380 17142 9714 17142 9381 17142 9381 17143 9714 17143 9715 17143 9381 17144 9715 17144 9382 17144 9382 17145 9715 17145 9716 17145 9382 17146 9716 17146 9369 17146 9369 17147 9716 17147 9717 17147 9369 17148 9717 17148 9370 17148 9370 17149 9717 17149 9718 17149 9370 17150 9718 17150 9368 17150 9375 17151 9719 17151 9376 17151 9376 17152 9719 17152 9644 17152 9376 17153 9644 17153 9377 17153 9577 17154 9644 17154 9720 17154 9720 17155 9644 17155 9719 17155 9720 17156 9719 17156 9718 17156 9718 17157 9719 17157 9375 17157 9718 10806 9375 10806 9368 10806 9716 17158 9721 17158 9717 17158 9717 17159 9721 17159 9722 17159 9717 17160 9722 17160 9718 17160 9718 13824 9722 13824 9723 13824 9718 17161 9723 17161 9720 17161 9708 17162 9724 17162 9713 17162 9713 17163 9724 17163 9725 17163 9713 10814 9725 10814 9714 10814 9714 17164 9725 17164 9726 17164 9714 17165 9726 17165 9715 17165 9715 17166 9726 17166 9727 17166 9715 17167 9727 17167 9716 17167 9716 17168 9727 17168 9728 17168 9716 17169 9728 17169 9721 17169 9729 17170 9730 17170 9731 17170 9732 13836 9733 13836 9730 13836 9731 17171 9734 17171 9729 17171 9729 17172 9734 17172 9735 17172 9729 17173 9735 17173 9736 17173 9408 13840 9647 13840 9737 13840 9737 13841 9647 13841 9738 13841 9737 13842 9738 13842 9739 13842 9739 13843 9738 13843 9740 13843 9739 17174 9740 17174 9741 17174 9741 17175 9740 17175 9742 17175 9741 17176 9742 17176 9743 17176 9743 13847 9742 13847 9736 13847 9743 13848 9736 13848 9744 13848 9744 17177 9736 17177 9735 17177 9730 17178 9729 17178 9732 17178 9732 17179 9729 17179 9736 17179 9732 17180 9736 17180 9745 17180 9745 17181 9736 17181 9742 17181 9745 17182 9742 17182 9746 17182 9746 13854 9742 13854 9740 13854 9746 17183 9740 17183 9747 17183 9747 17184 9740 17184 9738 17184 9747 13857 9738 13857 9748 13857 9748 13858 9738 13858 9647 13858 9748 13859 9647 13859 9646 13859 9417 17185 9749 17185 9750 17185 9417 17186 9751 17186 9752 17186 9409 17187 9408 17187 9737 17187 9753 13863 9754 13863 9755 13863 9756 13864 144 13864 9757 13864 9409 17188 9737 17188 9420 17188 9750 13866 9758 13866 9759 13866 9417 13867 9750 13867 9418 13867 9418 13868 9750 13868 9759 13868 9418 17189 9759 17189 9419 17189 9760 17190 9761 17190 9762 17190 9762 13871 9761 13871 9756 13871 9762 17191 9756 17191 9763 17191 9763 13873 9756 13873 9757 13873 9763 17192 9757 17192 9764 17192 9764 17193 9757 17193 9765 17193 9417 17194 9752 17194 9749 17194 9749 17195 9752 17195 9766 17195 9749 17196 9766 17196 9750 17196 9743 13879 9767 13879 9741 13879 9741 17197 9767 17197 9768 17197 9741 17198 9768 17198 9739 17198 9739 17199 9768 17199 9769 17199 9739 13883 9769 13883 9737 13883 9737 13884 9769 13884 9770 13884 9737 13885 9770 13885 9420 13885 9755 17200 9771 17200 9753 17200 9753 17201 9771 17201 9760 17201 9753 17202 9760 17202 9772 17202 9772 17203 9760 17203 9762 17203 9772 13890 9762 13890 9773 13890 9773 17204 9762 17204 9763 17204 9773 17205 9763 17205 9766 17205 9766 17206 9763 17206 9764 17206 9766 17207 9764 17207 9750 17207 9750 17208 9764 17208 9765 17208 9750 17209 9765 17209 9758 17209 9731 13897 9774 13897 9734 13897 9734 17210 9774 17210 9755 17210 9734 17211 9755 17211 9735 17211 9735 17212 9755 17212 9754 17212 9735 17213 9754 17213 9744 17213 9744 13902 9754 13902 9753 13902 9744 13903 9753 13903 9743 13903 9743 13904 9753 13904 9772 13904 9743 17214 9772 17214 9767 17214 9767 13906 9772 13906 9773 13906 9767 17215 9773 17215 9768 17215 9768 17216 9773 17216 9766 17216 9768 13909 9766 13909 9769 13909 9769 17217 9766 17217 9752 17217 9769 13911 9752 13911 9770 13911 9770 13912 9752 13912 9751 13912 9770 13913 9751 13913 9420 13913 9420 17218 9751 17218 9417 17218 9775 17219 9776 17219 9777 17219 9778 17220 9779 17220 161 17220 9780 17221 9781 17221 9782 17221 9783 17222 9784 17222 9785 17222 9785 17223 9784 17223 9786 17223 9785 13920 9786 13920 9787 13920 9787 17224 9786 17224 9780 17224 9787 17225 9780 17225 9788 17225 9788 17226 9780 17226 9782 17226 9788 17227 9782 17227 9789 17227 9790 17228 9791 17228 9783 17228 9783 17229 9791 17229 9792 17229 9783 17230 9792 17230 9784 17230 9778 17231 9790 17231 9779 17231 9779 17232 9790 17232 9783 17232 9779 17233 9783 17233 9793 17233 9793 17234 9783 17234 9775 17234 9776 17235 9794 17235 9777 17235 9777 13933 9794 13933 9795 13933 9777 17236 9795 17236 9796 17236 9796 13935 9795 13935 9797 13935 9798 13936 9799 13936 9797 13936 9797 17237 9799 17237 9800 17237 9797 13938 9800 13938 9796 13938 9797 13939 9801 13939 9798 13939 9798 13940 9801 13940 9802 13940 9798 13941 9802 13941 9803 13941 9619 17238 9803 17238 9620 17238 9620 17239 9803 17239 9802 17239 9620 17240 9802 17240 9635 17240 9635 17241 9802 17241 9615 17241 9804 17242 9639 17242 9805 17242 9805 17243 9639 17243 9613 17243 9806 13948 9807 13948 9808 13948 9808 17244 9807 17244 9809 17244 9808 17245 9809 17245 9810 17245 9810 17246 9809 17246 9811 17246 9810 17247 9811 17247 9812 17247 9812 13953 9811 13953 9813 13953 9812 13954 9813 13954 9814 13954 9612 17248 9615 17248 9814 17248 9814 17249 9615 17249 9802 17249 9814 13957 9802 13957 9812 13957 9812 13958 9802 13958 9801 13958 9812 17250 9801 17250 9810 17250 9810 17251 9801 17251 9797 17251 9810 17252 9797 17252 9808 17252 9808 13962 9797 13962 9795 13962 9808 17253 9795 17253 9806 17253 9806 17254 9795 17254 9794 17254 9775 13965 9783 13965 9776 13965 9776 17255 9783 17255 9785 17255 9776 13967 9785 13967 9794 13967 9794 13968 9785 13968 9787 13968 9794 13969 9787 13969 9806 13969 9806 17256 9787 17256 9788 17256 9806 17257 9788 17257 9807 17257 9807 17258 9788 17258 9789 17258 9807 17259 9789 17259 9809 17259 9809 13974 9789 13974 9815 13974 9809 17260 9815 17260 9811 17260 9811 17261 9815 17261 9804 17261 9811 17262 9804 17262 9813 17262 9813 17263 9804 17263 9805 17263 9813 17264 9805 17264 9814 17264 9814 17265 9805 17265 9613 17265 9814 17266 9613 17266 9612 17266 9789 17267 9782 17267 9638 17267 9638 17268 9782 17268 9816 17268 9638 13984 9816 13984 9637 13984 9789 17269 9638 17269 9815 17269 9815 17270 9638 17270 9639 17270 9815 17271 9639 17271 9804 17271 9630 17272 9817 17272 9818 17272 9818 17273 9817 17273 9819 17273 9818 17274 9819 17274 9820 17274 9820 17275 9819 17275 9821 17275 9821 17276 9819 17276 9822 17276 9821 17277 9822 17277 9823 17277 9824 17278 9823 17278 9825 17278 9825 17279 9823 17279 9822 17279 9825 17280 9822 17280 9826 17280 9826 17281 9822 17281 9827 17281 9828 17282 9829 17282 9830 17282 9830 13999 9829 13999 9816 13999 9830 14000 9816 14000 9781 14000 9781 14001 9816 14001 9782 14001 9630 17283 9636 17283 9817 17283 9817 17284 9636 17284 9637 17284 9817 17285 9637 17285 9819 17285 9819 14006 9637 14006 9816 14006 9819 17286 9816 17286 9822 17286 9822 17287 9816 17287 9829 17287 9822 17288 9829 17288 9827 17288 9827 17289 9829 17289 9828 17289 9827 17290 9828 17290 9831 17290 9832 17291 9833 17291 9834 17291 9835 17292 9836 17292 9837 17292 9838 17293 9839 17293 9840 17293 9840 17294 9839 17294 9841 17294 9840 17295 9841 17295 9842 17295 9842 17296 9841 17296 9843 17296 9843 17297 9841 17297 9844 17297 9843 17298 9844 17298 9845 17298 9846 17299 9847 17299 9848 17299 9835 17300 9837 17300 9849 17300 9849 17301 9837 17301 9850 17301 9849 17302 9850 17302 9851 17302 9852 17303 9853 17303 9854 17303 9854 17304 9853 17304 9855 17304 9854 17305 9855 17305 9856 17305 9838 17306 9857 17306 9839 17306 9839 17307 9857 17307 9858 17307 9839 17308 9858 17308 9841 17308 9841 17309 9858 17309 9859 17309 9841 17310 9859 17310 9844 17310 9860 17311 9845 17311 9861 17311 9861 17312 9845 17312 9844 17312 9861 10574 9844 10574 9862 10574 9862 17313 9844 17313 9859 17313 9862 17314 9859 17314 9847 17314 9847 17315 9859 17315 9863 17315 9847 17316 9863 17316 9848 17316 9848 17317 9863 17317 9864 17317 9857 17318 9834 17318 9858 17318 9858 17319 9834 17319 9833 17319 9858 17320 9833 17320 9852 17320 9852 17321 9833 17321 9832 17321 9852 10584 9832 10584 9853 10584 9853 17322 9832 17322 9865 17322 9853 17323 9865 17323 9855 17323 9854 17324 9851 17324 9852 17324 9852 17325 9851 17325 9850 17325 9852 17326 9850 17326 9858 17326 9858 17327 9850 17327 9837 17327 9858 17328 9837 17328 9859 17328 9859 17329 9837 17329 9836 17329 9859 17330 9836 17330 9863 17330 9863 17331 9836 17331 9835 17331 9863 17332 9835 17332 9864 17332 9866 14054 9867 14054 9868 14054 9869 17333 9867 17333 9870 17333 9870 17334 9867 17334 9866 17334 9870 17335 9866 17335 9871 17335 9871 17336 9866 17336 9872 17336 9871 17337 9872 17337 9873 17337 9873 17338 9872 17338 9874 17338 9873 17339 9874 17339 9875 17339 9875 17340 9874 17340 9876 17340 9876 17341 9874 17341 9877 17341 9876 14063 9877 14063 9878 14063 9879 17342 9645 17342 9648 17342 9646 14065 9645 14065 9748 14065 9748 14066 9645 14066 9879 14066 9748 17343 9879 17343 9880 17343 9733 14068 9732 14068 9881 14068 9881 17344 9732 17344 9745 17344 9881 17345 9745 17345 9882 17345 9882 17346 9745 17346 9746 17346 9882 17347 9746 17347 9880 17347 9880 17348 9746 17348 9747 17348 9880 17349 9747 17349 9748 17349 9650 17350 9878 17350 9648 17350 9648 17351 9878 17351 9877 17351 9648 17352 9877 17352 9879 17352 9879 17353 9877 17353 9874 17353 9879 17354 9874 17354 9880 17354 9880 17355 9874 17355 9872 17355 9880 14081 9872 14081 9882 14081 9882 17356 9872 17356 9866 17356 9882 14083 9866 14083 9881 14083 9881 14084 9866 14084 9868 14084 9881 14085 9868 14085 9733 14085 9883 17357 9884 17357 9885 17357 9886 17358 9654 17358 9653 17358 9887 17359 9651 17359 9652 17359 9888 14087 9884 14087 9889 14087 9889 17360 9884 17360 9883 17360 9889 17361 9883 17361 9890 17361 9890 17362 9883 17362 9891 17362 9890 17363 9891 17363 9892 17363 9892 17364 9891 17364 9893 17364 9892 17365 9893 17365 9894 17365 9894 17366 9893 17366 9886 17366 9894 17367 9886 17367 9895 17367 9895 10497 9886 10497 9653 10497 9869 17368 9870 17368 9885 17368 9885 17369 9870 17369 9896 17369 9885 17370 9896 17370 9883 17370 9883 17371 9896 17371 9897 17371 9883 17372 9897 17372 9891 17372 9891 17373 9897 17373 9898 17373 9891 17374 9898 17374 9893 17374 9893 17375 9898 17375 9887 17375 9893 17376 9887 17376 9886 17376 9886 10507 9887 10507 9652 10507 9886 17377 9652 17377 9654 17377 9650 17378 9651 17378 9878 17378 9878 17379 9651 17379 9887 17379 9878 17380 9887 17380 9876 17380 9876 17381 9887 17381 9898 17381 9876 17382 9898 17382 9875 17382 9875 17383 9898 17383 9897 17383 9875 17384 9897 17384 9873 17384 9873 17385 9897 17385 9896 17385 9873 17386 9896 17386 9871 17386 9871 17387 9896 17387 9870 17387 9899 17388 9900 17388 9901 17388 9901 17389 9900 17389 9902 17389 9902 14107 9900 14107 9903 14107 9903 17390 9900 17390 9904 17390 9903 17391 9904 17391 9905 17391 9905 17392 9904 17392 9906 17392 9905 17393 9906 17393 9907 17393 9908 17394 9655 17394 9658 17394 9895 17395 9653 17395 9655 17395 9655 14114 9908 14114 9895 14114 9895 17396 9908 17396 9909 17396 9895 17397 9909 17397 9894 17397 9894 17398 9909 17398 9892 17398 9892 17399 9909 17399 9910 17399 9892 17400 9910 17400 9890 17400 9890 17401 9910 17401 9911 17401 9890 10469 9911 10469 9889 10469 9901 17402 9912 17402 9899 17402 9899 17403 9912 17403 9913 17403 9899 17404 9913 17404 9914 17404 9888 17405 9889 17405 9914 17405 9914 17406 9889 17406 9911 17406 9914 10475 9911 10475 9899 10475 9899 17407 9911 17407 9910 17407 9899 17408 9910 17408 9900 17408 9900 17409 9910 17409 9909 17409 9900 17410 9909 17410 9904 17410 9904 17411 9909 17411 9908 17411 9904 17412 9908 17412 9906 17412 9906 17413 9908 17413 9658 17413 9906 17414 9658 17414 9907 17414 9907 17415 9658 17415 9657 17415 9915 17416 9705 17416 9695 17416 9705 17417 9915 17417 9706 17417 9706 17418 9915 17418 9916 17418 9706 17419 9916 17419 9699 17419 9699 17420 9916 17420 9917 17420 9699 17421 9917 17421 9700 17421 9700 17422 9917 17422 9918 17422 9700 17423 9918 17423 9701 17423 9687 17424 9686 17424 9919 17424 9919 10406 9686 10406 9688 10406 9919 17425 9688 17425 9918 17425 9918 17426 9688 17426 9689 17426 9918 17427 9689 17427 9701 17427 9687 17428 9919 17428 9698 17428 9698 17429 9919 17429 9920 17429 9698 17430 9920 17430 9697 17430 9697 17431 9920 17431 9921 17431 9697 17432 9921 17432 9696 17432 9696 17433 9921 17433 9922 17433 9696 17434 9922 17434 9690 17434 9923 17435 9924 17435 9925 17435 9691 17436 9690 17436 9925 17436 9925 17437 9690 17437 9922 17437 9925 17438 9922 17438 9923 17438 9923 17439 9922 17439 9921 17439 9923 17440 9921 17440 9926 17440 9926 17441 9921 17441 9920 17441 9926 17442 9920 17442 9927 17442 9927 17443 9920 17443 9919 17443 9927 17444 9919 17444 9928 17444 9928 17445 9919 17445 9918 17445 9928 17446 9918 17446 9929 17446 9929 17447 9918 17447 9917 17447 9929 17448 9917 17448 9930 17448 9930 17449 9917 17449 9916 17449 9930 17450 9916 17450 9931 17450 9931 17451 9916 17451 9915 17451 9931 17452 9915 17452 9932 17452 9932 17453 9915 17453 9933 17453 9932 17454 9933 17454 9934 17454 9934 17455 9933 17455 9935 17455 9934 14169 9935 14169 9936 14169 9936 14170 9935 14170 9937 14170 9936 17456 9937 17456 9938 17456 9694 17457 9679 17457 9680 17457 9681 17458 9938 17458 9680 17458 9680 14174 9938 14174 9937 14174 9680 14175 9937 14175 9694 14175 9694 17459 9937 17459 9935 17459 9694 17460 9935 17460 9702 17460 9702 17461 9935 17461 9933 17461 9702 17462 9933 17462 9703 17462 9703 17463 9933 17463 9915 17463 9703 17464 9915 17464 9704 17464 9704 17465 9915 17465 9695 17465 9704 17466 9695 17466 9685 17466 9674 17467 9939 17467 9940 17467 9940 17468 9941 17468 9942 17468 9942 17469 9941 17469 9925 17469 9942 17470 9925 17470 9924 17470 9674 17471 9673 17471 9939 17471 9939 17472 9673 17472 9707 17472 9939 17473 9707 17473 9693 17473 9940 10392 9939 10392 9941 10392 9941 17474 9939 17474 9693 17474 9941 17475 9693 17475 9925 17475 9925 17476 9693 17476 9692 17476 9925 17477 9692 17477 9691 17477 9674 17478 9943 17478 9672 17478 9672 17479 9943 17479 9944 17479 9672 17480 9944 17480 9670 17480 9670 17481 9944 17481 9945 17481 9670 17482 9945 17482 9667 17482 9667 17483 9945 17483 9946 17483 9667 17484 9946 17484 9662 17484 9662 17485 9946 17485 9947 17485 9662 17486 9947 17486 9663 17486 9663 17487 9947 17487 9948 17487 9943 17488 6662 17488 9944 17488 9944 17489 6662 17489 6661 17489 9944 17490 6661 17490 9945 17490 9945 17491 6661 17491 6715 17491 9945 17492 6715 17492 9946 17492 9946 14208 6715 14208 6714 14208 9946 17493 6714 17493 9947 17493 9947 17494 6714 17494 6713 17494 9947 17495 6713 17495 9948 17495 9948 17496 6713 17496 6712 17496 9949 17497 9681 17497 9682 17497 9681 14215 9949 14215 9950 14215 9951 17498 9952 17498 9953 17498 9953 17499 9952 17499 9948 17499 9953 17500 9948 17500 6712 17500 9663 17501 9948 17501 9683 17501 9683 17502 9948 17502 9952 17502 9683 17503 9952 17503 9684 17503 9684 14222 9952 14222 9951 14222 9684 17504 9951 17504 9682 17504 9682 17505 9951 17505 9954 17505 9682 17506 9954 17506 9949 17506 9725 17507 9955 17507 9956 17507 9957 17508 9958 17508 9959 17508 9721 17509 9960 17509 9722 17509 9961 17510 9577 17510 9720 17510 9962 17511 9963 17511 9961 17511 9961 17512 9963 17512 9964 17512 9964 17513 9482 17513 9961 17513 9961 17514 9482 17514 9579 17514 9961 17515 9579 17515 9577 17515 9720 17516 9723 17516 9961 17516 9961 17517 9723 17517 9965 17517 9961 17518 9965 17518 9962 17518 9962 17519 9965 17519 9966 17519 9962 17520 9966 17520 9967 17520 9857 17521 9838 17521 9968 17521 9865 17522 9832 17522 9969 17522 9969 17523 9832 17523 9834 17523 9969 17524 9834 17524 9857 17524 9970 17525 9971 17525 9972 17525 9972 17526 9971 17526 9856 17526 9972 17527 9856 17527 9969 17527 9969 17528 9856 17528 9855 17528 9969 17529 9855 17529 9865 17529 9857 17530 9968 17530 9969 17530 9969 17531 9968 17531 9967 17531 9969 17532 9967 17532 9972 17532 9972 17533 9967 17533 9966 17533 9972 17534 9966 17534 9970 17534 9970 17535 9966 17535 9965 17535 9970 17536 9965 17536 9973 17536 9973 17537 9965 17537 9974 17537 9973 17538 9974 17538 9975 17538 9955 17539 9976 17539 9956 17539 9956 17540 9976 17540 9977 17540 9956 17541 9977 17541 9978 17541 9979 17542 9980 17542 9978 17542 9978 17543 9980 17543 9981 17543 9978 17544 9981 17544 9956 17544 9956 17545 9981 17545 9982 17545 9956 17546 9982 17546 9983 17546 9983 17547 9982 17547 9984 17547 9983 17548 9984 17548 9985 17548 9957 17549 9959 17549 9986 17549 9986 17550 9959 17550 9987 17550 9986 14264 9987 14264 9988 14264 9628 17551 9629 17551 9989 17551 9989 17552 9629 17552 9990 17552 9989 17553 9990 17553 9991 17553 9991 17554 9990 17554 9992 17554 9616 17555 9625 17555 9989 17555 9989 14270 9625 14270 9627 14270 9989 17556 9627 17556 9628 17556 9993 14272 9619 14272 9617 14272 9988 17557 9987 17557 9992 17557 9992 17558 9987 17558 9994 17558 9992 17559 9994 17559 9991 17559 9991 17560 9994 17560 9993 17560 9991 14277 9993 14277 9989 14277 9989 17561 9993 17561 9617 17561 9989 17562 9617 17562 9616 17562 9449 17563 9995 17563 9996 17563 9995 14281 9997 14281 9996 14281 9996 14282 9997 14282 9998 14282 9996 17564 9998 17564 9987 17564 9987 17565 9998 17565 9999 17565 9987 17566 9999 17566 9994 17566 9994 17567 9999 17567 10000 17567 9994 17568 10000 17568 9993 17568 9996 17569 9710 17569 9712 17569 9449 17570 9996 17570 9517 17570 9517 14290 9996 14290 9712 14290 9517 17571 9712 17571 9544 17571 9710 17572 9996 17572 9708 17572 9708 17573 9996 17573 9987 17573 9708 17574 9987 17574 9724 17574 9724 17575 9987 17575 9959 17575 9724 17576 9959 17576 9725 17576 9725 17577 9959 17577 9958 17577 9725 17578 9958 17578 9955 17578 9955 17579 9958 17579 10001 17579 9955 17580 10001 17580 9976 17580 9960 17581 9721 17581 9985 17581 9985 17582 9721 17582 9728 17582 9985 17583 9728 17583 9983 17583 9983 17584 9728 17584 9727 17584 9983 14304 9727 14304 9956 14304 9956 17585 9727 17585 9726 17585 9956 17586 9726 17586 9725 17586 9984 17587 9975 17587 9985 17587 9985 17588 9975 17588 9974 17588 9985 17589 9974 17589 9960 17589 9960 17590 9974 17590 9965 17590 9960 17591 9965 17591 9722 17591 9722 17592 9965 17592 9723 17592 10002 17593 9830 17593 9781 17593 10003 17594 9828 17594 9830 17594 10003 17595 10004 17595 9828 17595 9828 17596 10004 17596 10005 17596 9828 17597 10005 17597 9831 17597 9831 17598 10005 17598 10006 17598 10007 14319 10008 14319 9784 14319 9784 17599 9792 17599 10007 17599 10007 17600 9792 17600 9791 17600 10007 17601 9791 17601 10009 17601 10009 17602 9791 17602 9790 17602 10009 17603 9790 17603 9778 17603 10010 17604 10011 17604 9786 17604 9786 14326 10011 14326 9780 14326 10003 14327 10012 14327 10004 14327 10004 17605 10012 17605 10013 17605 10004 17606 10013 17606 10005 17606 10005 17607 10013 17607 10014 17607 10005 17608 10014 17608 10006 17608 10015 17609 10016 17609 10017 17609 9786 17610 9784 17610 10010 17610 10010 17611 9784 17611 10008 17611 10010 17612 10008 17612 10018 17612 10018 17613 10008 17613 10007 17613 10018 17614 10007 17614 10019 17614 10019 17615 10007 17615 10009 17615 10019 17616 10009 17616 10020 17616 10020 17617 10009 17617 10021 17617 10020 17618 10021 17618 151 17618 9778 17619 161 17619 10009 17619 10009 17620 161 17620 153 17620 10009 17621 153 17621 10021 17621 10021 17622 153 17622 152 17622 10021 14346 152 14346 151 14346 9830 17623 10002 17623 10003 17623 10003 17624 10002 17624 10022 17624 10003 14349 10022 14349 10012 14349 10012 14350 10022 14350 10017 14350 10012 17625 10017 17625 10013 17625 10013 17626 10017 17626 10016 17626 10013 17627 10016 17627 10014 17627 151 17628 10023 17628 10020 17628 10020 17629 10023 17629 10024 17629 10020 17630 10024 17630 10019 17630 10019 17631 10024 17631 10015 17631 10019 17632 10015 17632 10018 17632 10018 17633 10015 17633 10017 17633 10018 17634 10017 17634 10010 17634 10010 17635 10017 17635 10022 17635 10010 17636 10022 17636 10011 17636 10011 17637 10022 17637 10002 17637 10011 17638 10002 17638 9780 17638 9780 17639 10002 17639 9781 17639 9755 14366 9774 14366 10025 14366 9730 14367 9733 14367 10026 14367 10025 17640 10027 17640 145 17640 10026 17641 10028 17641 10025 17641 10025 17642 10028 17642 10029 17642 10025 17643 10029 17643 10027 17643 10025 14372 9774 14372 10026 14372 10026 14373 9774 14373 9731 14373 10026 14374 9731 14374 9730 14374 145 14375 144 14375 10025 14375 10025 14376 144 14376 9756 14376 10025 14377 9756 14377 9761 14377 9761 17644 9760 17644 10025 17644 10025 17645 9760 17645 9771 17645 10025 17646 9771 17646 9755 17646 9415 14381 9414 14381 9437 14381 9437 14382 9414 14382 10030 14382 9437 17647 10030 17647 9436 17647 144 14384 143 14384 9757 14384 9757 14385 143 14385 10031 14385 9757 17648 10031 17648 10032 17648 9759 14387 9758 14387 10032 14387 10032 17649 9758 17649 9765 17649 10032 14389 9765 14389 9757 14389 143 17650 9429 17650 10031 17650 10031 17651 9429 17651 9436 17651 10031 17652 9436 17652 10032 17652 10032 17653 9436 17653 10030 17653 10032 14394 10030 14394 9759 14394 9759 14395 10030 14395 9414 14395 9759 17654 9414 17654 9419 17654 10033 14397 155 14397 157 14397 10034 17655 9997 17655 9995 17655 10035 17656 10036 17656 9454 17656 9454 17657 10036 17657 9456 17657 10037 17658 9451 17658 10036 17658 10036 17659 9451 17659 9457 17659 10036 17660 9457 17660 9456 17660 9449 17661 9448 17661 9995 17661 9995 17662 9448 17662 9447 17662 9995 17663 9447 17663 10034 17663 10034 17664 9447 17664 9446 17664 10034 17665 9446 17665 10038 17665 10038 17666 9446 17666 9445 17666 10038 17667 9445 17667 10037 17667 10037 17668 9445 17668 9452 17668 10037 17669 9452 17669 9451 17669 10039 17670 9993 17670 10000 17670 9619 17671 9993 17671 9803 17671 9803 17672 9993 17672 10039 17672 9803 17673 10039 17673 9798 17673 9798 14417 10039 14417 10040 14417 10041 14418 9800 14418 10040 14418 10040 17674 9800 17674 9799 17674 10040 14420 9799 14420 9798 14420 9779 17675 9793 17675 10042 17675 10042 17676 9793 17676 9775 17676 10042 17677 9775 17677 10043 17677 10043 14424 9775 14424 9777 14424 10043 17678 9777 17678 10041 17678 10041 17679 9777 17679 9796 17679 10041 14427 9796 14427 9800 14427 10044 14428 163 14428 162 14428 163 14429 10044 14429 157 14429 9454 17680 160 17680 10035 17680 10035 17681 160 17681 154 17681 10035 17682 154 17682 155 17682 155 14433 10033 14433 10035 14433 10035 17683 10033 17683 10045 17683 10035 14435 10045 14435 10036 14435 10036 14436 10045 14436 10046 14436 10036 14437 10046 14437 10037 14437 10037 14438 10046 14438 10047 14438 10037 17684 10047 17684 10038 17684 10038 17685 10047 17685 10048 17685 10038 14441 10048 14441 10034 14441 10034 17686 10048 17686 9998 17686 10034 14443 9998 14443 9997 14443 157 14444 10044 14444 10033 14444 10033 14445 10044 14445 10049 14445 10033 14446 10049 14446 10045 14446 10045 14447 10049 14447 10050 14447 10045 14448 10050 14448 10046 14448 10046 14449 10050 14449 10051 14449 10046 14450 10051 14450 10047 14450 10047 14451 10051 14451 10052 14451 10047 14452 10052 14452 10048 14452 10048 17687 10052 17687 9999 17687 10048 17688 9999 17688 9998 17688 161 17689 9779 17689 162 17689 162 17690 9779 17690 10042 17690 162 14457 10042 14457 10044 14457 10044 17691 10042 17691 10043 17691 10044 14459 10043 14459 10049 14459 10049 14460 10043 14460 10041 14460 10049 14461 10041 14461 10050 14461 10050 14462 10041 14462 10040 14462 10050 14463 10040 14463 10051 14463 10051 14464 10040 14464 10039 14464 10051 14465 10039 14465 10052 14465 10052 17692 10039 17692 10000 17692 10052 17693 10000 17693 9999 17693 10053 17694 10054 17694 10055 17694 9861 17695 10056 17695 9860 17695 9860 17696 10056 17696 10057 17696 9861 17697 10058 17697 10059 17697 10060 17698 10056 17698 10061 17698 10061 17699 10056 17699 9861 17699 10061 17700 9861 17700 10062 17700 10062 17701 9861 17701 10059 17701 10063 17702 10064 17702 10065 17702 10065 17703 10066 17703 10063 17703 10063 17704 10066 17704 10067 17704 10063 17705 10067 17705 10058 17705 10058 17706 10067 17706 10068 17706 10058 17707 10068 17707 10059 17707 10053 17708 10055 17708 10069 17708 10069 17709 10055 17709 10070 17709 10069 17710 10070 17710 10071 17710 10071 17711 10070 17711 10072 17711 10071 17712 10072 17712 10073 17712 9847 17713 9846 17713 10074 17713 10074 17714 9846 17714 10075 17714 10074 17715 10075 17715 10073 17715 10073 17716 10072 17716 10074 17716 10074 17717 10072 17717 9862 17717 10074 17718 9862 17718 9847 17718 9861 17719 9862 17719 10058 17719 10058 17720 9862 17720 10072 17720 10058 17721 10072 17721 10063 17721 10063 17722 10072 17722 10070 17722 10063 17723 10070 17723 10064 17723 10064 17724 10070 17724 10055 17724 10076 17725 10077 17725 10078 17725 10079 17726 10080 17726 10081 17726 10082 17727 10083 17727 10084 17727 10084 17728 10083 17728 10085 17728 9842 17729 9843 17729 10086 17729 10062 17730 10059 17730 10087 17730 10088 17731 10089 17731 10061 17731 10061 17732 10089 17732 10060 17732 9845 17733 9860 17733 10090 17733 10090 17734 9860 17734 10057 17734 10090 17735 10057 17735 10091 17735 10091 17736 10057 17736 10056 17736 10091 17737 10056 17737 10092 17737 10092 17738 10056 17738 10060 17738 10092 17739 10060 17739 10093 17739 10093 17740 10060 17740 10089 17740 10094 17741 9838 17741 9840 17741 10095 17742 10096 17742 10097 17742 10097 17743 10096 17743 10094 17743 10097 17744 10094 17744 10098 17744 10098 17745 10094 17745 9840 17745 10099 17746 10100 17746 10095 17746 10095 17747 10100 17747 10101 17747 10095 17748 10101 17748 10096 17748 10078 17749 10102 17749 10103 17749 10104 17750 10105 17750 10106 17750 10106 17751 10105 17751 10107 17751 10106 17752 10107 17752 10108 17752 10108 17753 10107 17753 10102 17753 10108 17754 10102 17754 10109 17754 10109 17755 10102 17755 10078 17755 10109 17756 10078 17756 10110 17756 10110 17757 10078 17757 10111 17757 10111 17758 10078 17758 10077 17758 10111 17759 10077 17759 10112 17759 10079 17760 10081 17760 10087 17760 10103 17761 10082 17761 10078 17761 10078 17762 10082 17762 10084 17762 10078 17763 10084 17763 10076 17763 10076 17764 10084 17764 10085 17764 10076 17765 10085 17765 10099 17765 10099 17766 10085 17766 10113 17766 10099 17767 10113 17767 10100 17767 9843 17768 9845 17768 10086 17768 10086 17769 9845 17769 10090 17769 10086 17770 10090 17770 10114 17770 10114 17771 10090 17771 10091 17771 10114 17772 10091 17772 10115 17772 10115 17773 10091 17773 10092 17773 10115 17774 10092 17774 10116 17774 10116 17775 10092 17775 10093 17775 10116 17776 10093 17776 10117 17776 10117 17777 10093 17777 10089 17777 10117 17778 10089 17778 10081 17778 10081 17779 10089 17779 10088 17779 10081 17780 10088 17780 10087 17780 10087 17781 10088 17781 10061 17781 10087 17782 10061 17782 10062 17782 10080 17783 10112 17783 10081 17783 10081 17784 10112 17784 10077 17784 10081 17785 10077 17785 10117 17785 10117 17786 10077 17786 10076 17786 10117 17787 10076 17787 10116 17787 10116 17788 10076 17788 10099 17788 10116 17789 10099 17789 10115 17789 10115 17790 10099 17790 10095 17790 10115 17791 10095 17791 10114 17791 10114 17792 10095 17792 10097 17792 10114 17793 10097 17793 10086 17793 10086 17794 10097 17794 10098 17794 10086 17795 10098 17795 9842 17795 9842 17796 10098 17796 9840 17796 10118 17797 10119 17797 9500 17797 10120 17798 10121 17798 10122 17798 9502 17799 9504 17799 10123 17799 10124 17800 10125 17800 10126 17800 10126 17801 10125 17801 10127 17801 10128 17802 10129 17802 10130 17802 10130 17803 10129 17803 10131 17803 10130 17804 10131 17804 10132 17804 10133 17805 10134 17805 10135 17805 10136 17806 10137 17806 10138 17806 10134 17807 10133 17807 10138 17807 10138 17808 10133 17808 10139 17808 10138 17809 10139 17809 10136 17809 10136 17810 10139 17810 10122 17810 10136 17811 10122 17811 10140 17811 10140 17812 10122 17812 10121 17812 10140 17813 10121 17813 10141 17813 9509 17814 10141 17814 9510 17814 9510 17815 10141 17815 10121 17815 9510 17816 10121 17816 9511 17816 9511 17817 10121 17817 10120 17817 9511 17818 10120 17818 9505 17818 10129 17819 10126 17819 10131 17819 10131 17820 10126 17820 10127 17820 10131 17821 10127 17821 10132 17821 10132 17822 10127 17822 10142 17822 10132 17823 10142 17823 10143 17823 10143 17824 10142 17824 10144 17824 10144 17825 10142 17825 10145 17825 10144 17826 10145 17826 10118 17826 10118 17827 10145 17827 10146 17827 10118 17828 10146 17828 10119 17828 9500 17829 9502 17829 10118 17829 10118 17830 9502 17830 10123 17830 10118 17831 10123 17831 10144 17831 10144 17832 10123 17832 10147 17832 10144 17833 10147 17833 10143 17833 10143 17834 10147 17834 10148 17834 10143 17835 10148 17835 10132 17835 9504 17836 9505 17836 10123 17836 10123 17837 9505 17837 10120 17837 10123 17838 10120 17838 10147 17838 10147 17839 10120 17839 10122 17839 10147 17840 10122 17840 10148 17840 10148 17841 10122 17841 10139 17841 10148 17842 10139 17842 10132 17842 10132 17843 10139 17843 10133 17843 10132 17844 10133 17844 10130 17844 10130 17845 10133 17845 10135 17845 10130 17846 10135 17846 10128 17846 9923 17847 10149 17847 9924 17847 9950 17848 9938 17848 9681 17848 9868 17849 10150 17849 9733 17849 9912 17850 10151 17850 9913 17850 10152 17851 10153 17851 10154 17851 10149 17852 9923 17852 10154 17852 9733 17853 10155 17853 10026 17853 10026 17854 10155 17854 10028 17854 10152 17855 10154 17855 9912 17855 9912 17856 10154 17856 9923 17856 9912 17857 9923 17857 10151 17857 10151 17858 9923 17858 9926 17858 10151 17859 9926 17859 9913 17859 9913 17860 9926 17860 9927 17860 9913 17861 9927 17861 9914 17861 9914 17862 9927 17862 9928 17862 9914 17863 9928 17863 9888 17863 9888 17864 9928 17864 9929 17864 9888 17865 9929 17865 9884 17865 9884 17866 9929 17866 9930 17866 9884 17867 9930 17867 9885 17867 9885 14639 9930 14639 9931 14639 9885 17868 9931 17868 9869 17868 9869 17869 9931 17869 9932 17869 9869 17870 9932 17870 9867 17870 9867 17871 9932 17871 9934 17871 9867 17872 9934 17872 9868 17872 9868 14645 9934 14645 9936 14645 9868 17873 9936 17873 10150 17873 10150 17874 9936 17874 9938 17874 10150 17875 9938 17875 9733 17875 9733 17876 9938 17876 9950 17876 9733 17877 9950 17877 10155 17877 10125 17878 10124 17878 10156 17878 9912 17879 9901 17879 10157 17879 10157 17880 9901 17880 9902 17880 10157 17881 9902 17881 10158 17881 10158 17882 9902 17882 9903 17882 10158 17883 9903 17883 10159 17883 10159 17884 9903 17884 9905 17884 10159 17885 9905 17885 10160 17885 10160 17886 9905 17886 9907 17886 10160 17887 9907 17887 10161 17887 10119 17888 10146 17888 10161 17888 10161 17889 10146 17889 10145 17889 10161 17890 10145 17890 10160 17890 10160 17891 10145 17891 10142 17891 10160 17892 10142 17892 10159 17892 10159 17893 10142 17893 10127 17893 10159 17894 10127 17894 10158 17894 10158 17895 10127 17895 10125 17895 10158 17896 10125 17896 10157 17896 10157 17897 10125 17897 10156 17897 10157 17898 10156 17898 9912 17898 9500 17899 10119 17899 9656 17899 9656 17900 10119 17900 10161 17900 9656 17901 10161 17901 9657 17901 9657 17902 10161 17902 9907 17902 10162 17903 10163 17903 10164 17903 9942 17904 9924 17904 10162 17904 10162 17905 9924 17905 10149 17905 10162 17906 10149 17906 10154 17906 10162 17907 10164 17907 9942 17907 9942 17908 10164 17908 10165 17908 9942 17909 10165 17909 9940 17909 9940 17910 10165 17910 9943 17910 9940 17911 9943 17911 9674 17911 10163 17912 10166 17912 10164 17912 10164 17913 10166 17913 10167 17913 10164 9890 10167 9890 10165 9890 10165 17914 10167 17914 6662 17914 10165 17915 6662 17915 9943 17915 10001 95 9958 95 9305 95 9305 95 9958 95 9957 95 9305 95 9957 95 9986 95 9304 95 9977 95 9305 95 9305 95 9977 95 9976 95 9305 95 9976 95 10001 95 6708 17916 4392 17916 6712 17916 6712 17917 4392 17917 9953 17917 9950 17918 9949 17918 10155 17918 10155 17919 9949 17919 9954 17919 9953 17920 4392 17920 9951 17920 9951 17921 4392 17921 4394 17921 9951 17922 4394 17922 9954 17922 9954 17923 4394 17923 4395 17923 9954 17924 4395 17924 10155 17924 10155 17925 4395 17925 4419 17925 10155 17926 4419 17926 4417 17926 4417 17927 4416 17927 10155 17927 10155 17928 4416 17928 4414 17928 10155 17929 4414 17929 4412 17929 4412 17930 4411 17930 10155 17930 10155 17931 4411 17931 4409 17931 10155 17932 4409 17932 4407 17932 4407 17933 4405 17933 10155 17933 10155 17934 4405 17934 4403 17934 10155 17935 4403 17935 4464 17935 4464 17936 4463 17936 10155 17936 10155 17937 4463 17937 4461 17937 10155 17938 4461 17938 4459 17938 4459 17939 4457 17939 10155 17939 10155 17940 4457 17940 4456 17940 10155 17941 4456 17941 4454 17941 4454 17942 4452 17942 10155 17942 10155 17943 4452 17943 4450 17943 10155 17944 4450 17944 4448 17944 4448 17945 4446 17945 10155 17945 10155 17946 4446 17946 4389 17946 10155 17947 4389 17947 4423 17947 4427 17948 4429 17948 10027 17948 10027 17949 4429 17949 4431 17949 10027 17950 4431 17950 4433 17950 4433 17951 4401 17951 10027 17951 10027 17952 4401 17952 4399 17952 10027 17953 4399 17953 4397 17953 4397 17954 4444 17954 10027 17954 10027 17955 4444 17955 4443 17955 10027 17956 4443 17956 4441 17956 4441 17957 4439 17957 10027 17957 10027 17958 4439 17958 4437 17958 10027 17959 4437 17959 4436 17959 4436 17960 4421 17960 10027 17960 10027 17961 4421 17961 4387 17961 10027 17962 4387 17962 4385 17962 4427 17963 10027 17963 4425 17963 4425 17964 10027 17964 10029 17964 4425 17965 10029 17965 4423 17965 4423 17966 10029 17966 10028 17966 4423 17967 10028 17967 10155 17967 4385 17968 4383 17968 10027 17968 10027 17969 4383 17969 156 17969 10027 17970 156 17970 145 17970 10168 17971 10169 17971 10170 17971 10079 17972 10171 17972 10172 17972 10171 17973 10068 17973 10067 17973 10171 17974 10079 17974 10068 17974 10068 17975 10079 17975 10087 17975 10068 17976 10087 17976 10059 17976 10173 17977 10112 17977 10172 17977 10172 17978 10112 17978 10080 17978 10172 17979 10080 17979 10079 17979 10108 17980 10109 17980 10174 17980 10174 17981 10109 17981 10110 17981 10174 17982 10110 17982 10173 17982 10173 17983 10110 17983 10111 17983 10173 17984 10111 17984 10112 17984 10065 17985 10169 17985 10066 17985 10066 17986 10169 17986 10168 17986 10066 17987 10168 17987 10067 17987 10175 17988 10176 17988 10177 17988 10177 17989 10176 17989 10178 17989 10177 17990 10178 17990 10179 17990 10179 17991 10178 17991 10180 17991 10179 17992 10180 17992 10181 17992 10181 17993 10180 17993 10182 17993 10181 17994 10182 17994 10183 17994 10179 17995 10184 17995 10177 17995 10177 17996 10184 17996 10185 17996 10177 17997 10185 17997 10175 17997 10175 17998 10185 17998 10186 17998 10104 17999 10106 17999 10183 17999 10183 18000 10106 18000 10187 18000 10183 18001 10187 18001 10181 18001 10181 18002 10187 18002 10188 18002 10181 18003 10188 18003 10179 18003 10179 18004 10188 18004 10189 18004 10179 18005 10189 18005 10184 18005 10184 18006 10189 18006 10190 18006 10184 18007 10190 18007 10185 18007 10185 18008 10190 18008 10191 18008 10185 18009 10191 18009 10186 18009 10106 18010 10108 18010 10187 18010 10187 18011 10108 18011 10174 18011 10187 18012 10174 18012 10188 18012 10188 18013 10174 18013 10173 18013 10188 18014 10173 18014 10189 18014 10189 18015 10173 18015 10172 18015 10189 18016 10172 18016 10190 18016 10190 18017 10172 18017 10171 18017 10190 18018 10171 18018 10191 18018 10191 18019 10171 18019 10067 18019 10191 18020 10067 18020 10186 18020 10186 18021 10067 18021 10168 18021 10186 18022 10168 18022 10175 18022 10175 18023 10168 18023 10170 18023 10175 18024 10170 18024 10176 18024 10085 18025 10083 18025 10192 18025 10193 18026 10194 18026 10195 18026 10196 18027 9476 18027 10197 18027 10197 18028 9476 18028 9478 18028 10197 18029 9478 18029 10198 18029 10198 18030 9478 18030 9479 18030 10198 18031 9479 18031 9481 18031 10199 18032 9473 18032 10196 18032 10196 18033 9473 18033 9474 18033 10196 18034 9474 18034 9476 18034 9464 18035 9467 18035 10200 18035 10200 18036 9467 18036 9470 18036 10200 18037 9470 18037 10199 18037 10199 18038 9470 18038 9472 18038 10199 18039 9472 18039 9473 18039 10201 18040 10202 18040 10203 18040 10202 18041 10201 18041 10195 18041 10204 18042 10205 18042 10194 18042 10103 18043 10102 18043 10204 18043 10204 18044 10102 18044 10107 18044 10204 18045 10107 18045 10205 18045 10205 18046 10107 18046 10105 18046 10205 18047 10105 18047 10104 18047 10192 18048 10083 18048 10204 18048 10204 18049 10083 18049 10082 18049 10204 18050 10082 18050 10103 18050 10096 18051 10101 18051 10206 18051 10206 18052 10101 18052 10100 18052 10206 18053 10100 18053 10192 18053 10192 18054 10100 18054 10113 18054 10192 18055 10113 18055 10085 18055 10206 18056 10207 18056 10096 18056 10096 18057 10207 18057 10208 18057 10096 18058 10208 18058 10094 18058 10094 18059 10208 18059 9968 18059 10094 18060 9968 18060 9838 18060 9481 18061 9482 18061 10198 18061 10198 18062 9482 18062 9964 18062 10198 18063 9964 18063 9963 18063 10194 18064 10193 18064 10204 18064 10204 18065 10193 18065 10209 18065 10204 18066 10209 18066 10192 18066 10192 18067 10209 18067 10210 18067 10192 18068 10210 18068 10206 18068 10206 18069 10210 18069 10211 18069 10206 18070 10211 18070 10207 18070 10207 18071 10211 18071 10212 18071 10207 18072 10212 18072 10208 18072 10208 18073 10212 18073 9967 18073 10208 18074 9967 18074 9968 18074 10195 18075 10201 18075 10193 18075 10193 18076 10201 18076 10213 18076 10193 18077 10213 18077 10209 18077 10209 18078 10213 18078 10214 18078 10209 18079 10214 18079 10210 18079 10210 18080 10214 18080 10215 18080 10210 18081 10215 18081 10211 18081 10211 18082 10215 18082 10216 18082 10211 18083 10216 18083 10212 18083 10212 18084 10216 18084 9962 18084 10212 18085 9962 18085 9967 18085 9465 18086 9464 18086 10203 18086 10203 18087 9464 18087 10200 18087 10203 18088 10200 18088 10201 18088 10201 18089 10200 18089 10199 18089 10201 18090 10199 18090 10213 18090 10213 18091 10199 18091 10196 18091 10213 18092 10196 18092 10214 18092 10214 18093 10196 18093 10197 18093 10214 18094 10197 18094 10215 18094 10215 18095 10197 18095 10198 18095 10215 18096 10198 18096 10216 18096 10216 18097 10198 18097 9963 18097 10216 18098 9963 18098 9962 18098 9492 18099 9497 18099 10217 18099 10217 18100 9497 18100 10137 18100 10217 18101 10218 18101 9492 18101 9492 18102 10218 18102 10219 18102 9492 18103 10219 18103 9494 18103 9494 18104 10219 18104 9508 18104 9494 18105 9508 18105 9495 18105 10137 18106 10136 18106 10217 18106 10217 18107 10136 18107 10140 18107 10217 18108 10140 18108 10218 18108 10218 18109 10140 18109 10141 18109 10218 18110 10141 18110 10219 18110 10219 18111 10141 18111 9509 18111 10219 18112 9509 18112 9508 18112 10153 9705 10152 9705 10220 9705 10220 18113 10152 18113 10221 18113 10220 18114 10221 18114 10222 18114 10222 18115 10221 18115 10223 18115 10129 18116 10128 18116 10221 18116 10221 18117 10128 18117 10135 18117 10221 18118 10135 18118 10134 18118 10224 18119 10223 18119 10137 18119 10137 18120 10223 18120 10221 18120 10137 18121 10221 18121 10138 18121 10138 18122 10221 18122 10134 18122 9912 18123 10156 18123 10152 18123 10152 18124 10156 18124 10124 18124 10152 18125 10124 18125 10221 18125 10221 18126 10124 18126 10126 18126 10221 18127 10126 18127 10129 18127 10224 18128 6628 18128 10223 18128 10223 18129 6628 18129 7109 18129 7112 18130 10153 18130 7108 18130 7108 18131 10153 18131 10220 18131 7108 18132 10220 18132 7109 18132 7109 18133 10220 18133 10222 18133 7109 18134 10222 18134 10223 18134 6663 18135 6662 18135 7112 18135 7112 18136 6662 18136 10167 18136 7112 18137 10167 18137 10166 18137 10154 18138 10153 18138 10162 18138 10162 18139 10153 18139 7112 18139 10162 18140 7112 18140 10163 18140 10163 18141 7112 18141 10166 18141 1383 18142 1420 18142 10225 18142 147 18143 142 18143 10226 18143 10227 18144 10228 18144 147 18144 10227 18145 147 18145 10229 18145 10229 18146 147 18146 10226 18146 10229 18147 10226 18147 891 18147 10230 18148 10231 18148 10229 18148 10229 18149 10231 18149 10232 18149 10229 18150 10232 18150 10227 18150 10233 18151 10234 18151 10235 18151 10235 18152 10234 18152 10236 18152 10235 18153 10236 18153 10237 18153 10237 18154 10238 18154 10235 18154 10235 18155 10238 18155 10239 18155 10235 18156 10239 18156 10229 18156 10229 18157 10239 18157 10240 18157 10229 18158 10240 18158 10230 18158 891 18159 888 18159 10229 18159 10229 18160 888 18160 1386 18160 10229 18161 1386 18161 10235 18161 10235 18162 1386 18162 1384 18162 1384 18163 1383 18163 10235 18163 10235 18164 1383 18164 10225 18164 10235 18165 10225 18165 10233 18165 10233 18166 10225 18166 10241 18166 10233 18167 10241 18167 10242 18167 10243 18168 10244 18168 10245 18168 1419 18169 1418 18169 10246 18169 1417 18170 1416 18170 10247 18170 1420 18171 1419 18171 10225 18171 10225 18172 1419 18172 10246 18172 10225 18173 10246 18173 10241 18173 1417 18174 10247 18174 1418 18174 1418 18175 10247 18175 10248 18175 1418 18176 10248 18176 10246 18176 10246 18177 10248 18177 10249 18177 10246 18178 10249 18178 10243 18178 10243 18179 10245 18179 10246 18179 10246 18180 10245 18180 10242 18180 10246 18181 10242 18181 10241 18181 10243 18182 10249 18182 10250 18182 10248 18183 10247 18183 10251 18183 10251 18184 10247 18184 1416 18184 10252 18185 10253 18185 10254 18185 10254 18186 10253 18186 10255 18186 10254 18187 10255 18187 10256 18187 10256 14978 10255 14978 10257 14978 10256 18188 10257 18188 10258 18188 10258 18189 10257 18189 10259 18189 10258 18190 10259 18190 10260 18190 10261 18191 10262 18191 10263 18191 10263 18192 10262 18192 10264 18192 10263 18193 10264 18193 10265 18193 10265 18194 10264 18194 10266 18194 10265 18195 10266 18195 10267 18195 10267 18196 10266 18196 10268 18196 10267 18197 10268 18197 10269 18197 10269 18198 10268 18198 10270 18198 10269 18199 10270 18199 10271 18199 10271 18200 10270 18200 10272 18200 10271 18201 10272 18201 10273 18201 10273 18202 10272 18202 10251 18202 10273 18203 10251 18203 10274 18203 10274 18204 10251 18204 1416 18204 10274 18205 1416 18205 1415 18205 10259 18206 10275 18206 10260 18206 10260 18207 10275 18207 10276 18207 10260 18208 10276 18208 10277 18208 10277 18209 10276 18209 10278 18209 10277 18210 10278 18210 10279 18210 10279 18211 10278 18211 10280 18211 10279 18212 10280 18212 10250 18212 10250 18213 10280 18213 10244 18213 10250 18214 10244 18214 10243 18214 10281 18215 10252 18215 10261 18215 10261 14997 10252 14997 10254 14997 10261 18216 10254 18216 10262 18216 10262 18217 10254 18217 10256 18217 10262 18218 10256 18218 10264 18218 10264 18219 10256 18219 10258 18219 10264 18220 10258 18220 10266 18220 10266 18221 10258 18221 10260 18221 10266 18222 10260 18222 10268 18222 10268 18223 10260 18223 10277 18223 10268 18224 10277 18224 10270 18224 10270 18225 10277 18225 10279 18225 10270 18226 10279 18226 10272 18226 10272 18227 10279 18227 10250 18227 10272 18228 10250 18228 10251 18228 10251 18229 10250 18229 10249 18229 10251 18230 10249 18230 10248 18230 10282 18231 10283 18231 10284 18231 10285 18232 10286 18232 10287 18232 10287 18233 10288 18233 10285 18233 10285 18234 10288 18234 10289 18234 10285 18235 10289 18235 10290 18235 10290 18236 10289 18236 10291 18236 10290 18237 10291 18237 10292 18237 10293 18238 10294 18238 10285 18238 10285 18239 10294 18239 10295 18239 10295 18240 10296 18240 10285 18240 10285 18241 10296 18241 10297 18241 10285 18242 10297 18242 10286 18242 741 18243 10293 18243 736 18243 736 18244 10293 18244 10285 18244 736 18245 10285 18245 737 18245 737 18246 10285 18246 1430 18246 1430 18247 10285 18247 1432 18247 1432 18248 10285 18248 10290 18248 1432 18249 10290 18249 1400 18249 1400 18250 10290 18250 10298 18250 1400 18251 10298 18251 1401 18251 10292 18252 10282 18252 10290 18252 10290 18253 10282 18253 10284 18253 10290 18254 10284 18254 10298 18254 10298 18255 10284 18255 10299 18255 10298 18256 10299 18256 10300 18256 10300 18257 10299 18257 10301 18257 1393 18258 1391 18258 10302 18258 10302 18259 1391 18259 1390 18259 10302 18260 1390 18260 1401 18260 1398 18261 1394 18261 10303 18261 10303 18262 1394 18262 10304 18262 1393 18263 10302 18263 1394 18263 1394 18264 10302 18264 10305 18264 1394 18265 10305 18265 10304 18265 10306 18266 10307 18266 10302 18266 10302 18267 10307 18267 10308 18267 10302 18268 10308 18268 10305 18268 1401 18269 10298 18269 10302 18269 10302 18270 10298 18270 10300 18270 10302 18271 10300 18271 10306 18271 10306 18272 10300 18272 10301 18272 10309 18273 10310 18273 10311 18273 10312 18274 1395 18274 1398 18274 10313 18275 10314 18275 10315 18275 10315 18276 10314 18276 10316 18276 10315 18277 10316 18277 10317 18277 10317 18278 10316 18278 10318 18278 10317 18279 10318 18279 10319 18279 10320 18280 10313 18280 10321 18280 10321 18281 10313 18281 10315 18281 10321 18282 10315 18282 10322 18282 10322 18283 10315 18283 10317 18283 10322 18284 10317 18284 10323 18284 10323 18285 10317 18285 10319 18285 10323 18286 10319 18286 10324 18286 10324 18287 10325 18287 10323 18287 10323 18288 10325 18288 10326 18288 10323 18289 10326 18289 10322 18289 10322 18290 10326 18290 10321 18290 10327 18291 10328 18291 10324 18291 10324 18292 10328 18292 10329 18292 10324 18293 10329 18293 10325 18293 1398 18294 10330 18294 10312 18294 10312 18295 10330 18295 10331 18295 10312 18296 10331 18296 10332 18296 10332 18297 10331 18297 10311 18297 10332 18298 10311 18298 10333 18298 10333 18299 10311 18299 10310 18299 10333 18300 10310 18300 10334 18300 10309 18301 10311 18301 10335 18301 10335 18302 10311 18302 10331 18302 10335 18303 10331 18303 10336 18303 10336 18304 10331 18304 10330 18304 10336 18305 10330 18305 10337 18305 1398 18306 10303 18306 10330 18306 10330 18307 10303 18307 10304 18307 10330 18308 10304 18308 10337 18308 10337 18309 10304 18309 10305 18309 10337 18310 10305 18310 10308 18310 10318 18311 10334 18311 10319 18311 10319 18312 10334 18312 10310 18312 10319 18313 10310 18313 10324 18313 10324 18314 10310 18314 10309 18314 10324 18315 10309 18315 10327 18315 10327 18316 10309 18316 10335 18316 10327 18317 10335 18317 10338 18317 10338 18318 10335 18318 10336 18318 10338 18319 10336 18319 10339 18319 10339 18320 10336 18320 10337 18320 10339 18321 10337 18321 10340 18321 10340 18322 10337 18322 10308 18322 10340 18323 10308 18323 10307 18323 10271 18324 10273 18324 1414 18324 1414 18325 10273 18325 10274 18325 1414 18326 10274 18326 1415 18326 10271 18327 1414 18327 10269 18327 10269 18328 1414 18328 1413 18328 10269 18329 1413 18329 10267 18329 10281 18330 10261 18330 1412 18330 1412 18331 10261 18331 10263 18331 1412 18332 10263 18332 1413 18332 1413 18333 10263 18333 10265 18333 1413 18334 10265 18334 10267 18334 10318 18335 10316 18335 1397 18335 10313 18336 10320 18336 1392 18336 1397 18337 10316 18337 1392 18337 1392 18338 10316 18338 10314 18338 1392 18339 10314 18339 10313 18339 1396 18340 10333 18340 1397 18340 1397 18341 10333 18341 10334 18341 1397 18342 10334 18342 10318 18342 1395 18343 10312 18343 1396 18343 1396 18344 10312 18344 10332 18344 1396 18345 10332 18345 10333 18345 1427 18346 9290 18346 10341 18346 1427 18347 10341 18347 1428 18347 1428 18348 10341 18348 10342 18348 1428 18349 10342 18349 1410 18349 1410 18350 10342 18350 10343 18350 1410 18351 10343 18351 1411 18351 1411 18352 10343 18352 10344 18352 1411 18353 10344 18353 1412 18353 9290 18354 10345 18354 10346 18354 10343 18355 10342 18355 10347 18355 10347 18356 10348 18356 10343 18356 10343 18357 10348 18357 10349 18357 10343 18358 10349 18358 10344 18358 10344 15142 10349 15142 10350 15142 10344 18359 10350 18359 10351 18359 9290 18360 10346 18360 10341 18360 10341 18361 10346 18361 10352 18361 10341 18362 10352 18362 10342 18362 10342 18363 10352 18363 10353 18363 10342 18364 10353 18364 10347 18364 1392 18365 10354 18365 1402 18365 1402 18366 10354 18366 10355 18366 10356 18367 9289 18367 1425 18367 1425 18368 1424 18368 10356 18368 10356 18369 1424 18369 1421 18369 10356 18370 1421 18370 10357 18370 10357 18371 1421 18371 1405 18371 10357 18372 1405 18372 10355 18372 10355 18373 1405 18373 1403 18373 10355 18374 1403 18374 1402 18374 10358 18375 10359 18375 10354 18375 10354 18376 10359 18376 10360 18376 10354 18377 10360 18377 10355 18377 10361 18378 9289 18378 10362 18378 10362 18379 9289 18379 10356 18379 10362 18380 10356 18380 10357 18380 10360 18381 10363 18381 10355 18381 10355 18382 10363 18382 10364 18382 10355 18383 10364 18383 10357 18383 10357 18384 10364 18384 10365 18384 10357 18385 10365 18385 10362 18385 10366 15171 10367 15171 10368 15171 10366 18386 10368 18386 10369 18386 10369 18387 10368 18387 10370 18387 10369 18388 10370 18388 10371 18388 10371 18389 10370 18389 10372 18389 10371 18390 10372 18390 10373 18390 10373 18391 10372 18391 10374 18391 10373 18392 10374 18392 10375 18392 10375 18393 10374 18393 10376 18393 10375 18394 10376 18394 10377 18394 10377 18395 10376 18395 10378 18395 10377 18396 10378 18396 10379 18396 10379 18397 10378 18397 10380 18397 10379 18398 10380 18398 10381 18398 10381 18399 10380 18399 10382 18399 10381 18400 10382 18400 10383 18400 10383 18401 10382 18401 10384 18401 10383 18402 10384 18402 10385 18402 10385 18403 10384 18403 10386 18403 10385 18404 10386 18404 10387 18404 10387 18405 10386 18405 10388 18405 10387 18406 10388 18406 10389 18406 10389 15177 10388 15177 10367 15177 10389 18407 10367 18407 10366 18407 10023 18408 151 18408 150 18408 10390 15180 10391 15180 9831 15180 9831 15181 10006 15181 10390 15181 10390 9479 10006 9479 10014 9479 10390 18409 10014 18409 10392 18409 10014 15183 10016 15183 10392 15183 10392 18410 10016 18410 10015 18410 10392 18411 10015 18411 10393 18411 150 15186 10394 15186 10023 15186 10023 18412 10394 18412 10393 18412 10023 9486 10393 9486 10024 9486 10024 15188 10393 15188 10015 15188 10169 18413 10065 18413 10395 18413 10396 18414 10397 18414 10182 18414 10182 18415 10180 18415 10396 18415 10396 18416 10180 18416 10178 18416 10396 18417 10178 18417 10398 18417 10398 18418 10178 18418 10176 18418 10398 18419 10176 18419 10399 18419 10395 18420 10400 18420 10169 18420 10169 18421 10400 18421 10399 18421 10169 18422 10399 18422 10170 18422 10170 18423 10399 18423 10176 18423 10401 18424 10402 18424 10403 18424 10404 18425 10399 18425 10405 18425 10399 18426 10404 18426 10398 18426 10406 18427 10407 18427 10408 18427 10397 18428 10396 18428 10409 18428 10410 18429 10411 18429 10412 18429 10397 18430 10409 18430 10406 18430 10406 18431 10409 18431 10403 18431 10406 18432 10403 18432 10407 18432 10407 18433 10403 18433 10402 18433 10407 18434 10402 18434 10408 18434 10400 18435 10395 18435 10413 18435 10413 18436 10395 18436 10414 18436 10413 18437 10414 18437 10415 18437 10415 18438 10414 18438 10416 18438 10415 18439 10416 18439 10417 18439 10417 18440 10418 18440 10415 18440 10415 18441 10418 18441 10419 18441 10415 18442 10419 18442 10413 18442 10413 18443 10419 18443 10405 18443 10413 9433 10405 9433 10400 9433 10400 18444 10405 18444 10399 18444 10396 18445 10412 18445 10409 18445 10409 18446 10412 18446 10411 18446 10409 18447 10411 18447 10403 18447 10403 18448 10411 18448 10420 18448 10403 18449 10420 18449 10401 18449 10421 18450 10422 18450 10423 18450 10423 18451 10422 18451 10424 18451 10423 18452 10424 18452 10425 18452 10425 18453 10424 18453 10426 18453 10425 18454 10426 18454 10410 18454 10410 18455 10426 18455 10427 18455 10410 18456 10427 18456 10411 18456 10411 18457 10427 18457 10428 18457 10411 18458 10428 18458 10420 18458 10429 18459 10421 18459 10430 18459 10430 18460 10421 18460 10423 18460 10430 18461 10423 18461 10431 18461 10431 18462 10423 18462 10425 18462 10431 18463 10425 18463 10432 18463 10432 18464 10425 18464 10410 18464 10396 18465 10398 18465 10412 18465 10412 18466 10398 18466 10404 18466 10412 18467 10404 18467 10410 18467 10410 18468 10404 18468 10405 18468 10410 18469 10405 18469 10432 18469 10432 18470 10405 18470 10419 18470 10432 18471 10419 18471 10431 18471 10431 18472 10419 18472 10418 18472 10431 18473 10418 18473 10430 18473 10430 18474 10418 18474 10417 18474 10430 18475 10417 18475 10429 18475 10433 18476 10434 18476 10283 18476 10433 18477 10283 18477 10435 18477 10436 18478 10437 18478 10292 18478 10283 18479 10282 18479 10435 18479 10435 18480 10282 18480 10292 18480 10435 18481 10292 18481 10438 18481 10438 18482 10292 18482 10437 18482 10288 18483 10439 18483 10440 18483 10292 18484 10291 18484 10436 18484 10436 18485 10291 18485 10289 18485 10436 18486 10289 18486 10441 18486 10441 18487 10289 18487 10288 18487 10441 18488 10288 18488 10442 18488 10442 18489 10288 18489 10440 18489 10443 18490 10444 18490 10286 18490 10286 18491 10444 18491 10445 18491 10286 18492 10445 18492 10446 18492 10439 18493 10288 18493 10446 18493 10446 18494 10288 18494 10287 18494 10446 18495 10287 18495 10286 18495 10296 18496 10447 18496 10448 18496 10296 18497 10448 18497 10297 18497 10297 18498 10448 18498 10449 18498 10297 18499 10449 18499 10286 18499 10286 18500 10449 18500 10450 18500 10286 18501 10450 18501 10443 18501 10447 18502 10296 18502 10451 18502 10451 18503 10296 18503 10295 18503 10451 18504 10295 18504 10408 18504 10452 18505 10453 18505 10232 18505 10232 18506 10453 18506 10227 18506 10227 15285 10453 15285 10454 15285 10227 15286 10454 15286 10228 15286 10228 15287 10454 15287 10455 15287 10228 15288 10455 15288 147 15288 147 18507 10455 18507 10456 18507 147 18508 10456 18508 146 18508 10457 15291 10458 15291 10230 15291 10458 18509 10459 18509 10230 18509 10230 15293 10459 15293 10460 15293 10230 18510 10460 18510 10231 18510 10231 15295 10460 15295 10461 15295 10231 18511 10461 18511 10232 18511 10232 18512 10461 18512 10462 18512 10232 18513 10462 18513 10452 18513 10230 18514 10240 18514 10457 18514 10457 18515 10240 18515 10239 18515 10457 18516 10239 18516 10463 18516 10236 18517 10464 18517 10237 18517 10237 18518 10464 18518 10463 18518 10237 18519 10463 18519 10238 18519 10238 18520 10463 18520 10239 18520 10465 15309 10466 15309 10467 15309 10468 15306 10469 15306 10390 15306 10470 18521 10471 18521 10472 18521 10472 18522 10471 18522 10473 18522 10472 18523 10473 18523 10474 18523 10474 18524 10473 18524 10475 18524 10474 18525 10475 18525 10465 18525 10465 18526 10475 18526 10476 18526 10465 15308 10476 15308 10466 15308 10394 15314 150 15314 149 15314 10477 18527 10478 18527 10468 18527 10477 18528 10479 18528 10480 18528 10478 18529 10477 18529 10481 18529 10481 15318 10477 15318 10480 15318 10481 15319 10480 15319 10482 15319 148 15320 10483 15320 149 15320 149 18530 10483 18530 10484 18530 149 18531 10484 18531 10394 18531 10394 18532 10484 18532 10485 18532 10394 18533 10485 18533 10393 18533 10393 18534 10485 18534 10486 18534 10393 18535 10486 18535 10392 18535 10467 18536 10487 18536 10465 18536 10465 18537 10487 18537 10488 18537 10465 15329 10488 15329 10474 15329 10474 18538 10488 18538 10489 18538 10474 18539 10489 18539 10472 18539 10472 18540 10489 18540 10490 18540 10472 15333 10490 15333 10470 15333 10391 15334 10390 15334 10467 15334 10467 15335 10390 15335 10469 15335 10467 18541 10469 18541 10487 18541 10487 18542 10469 18542 10468 18542 10487 18543 10468 18543 10488 18543 10488 18544 10468 18544 10478 18544 10488 18545 10478 18545 10489 18545 10489 18546 10478 18546 10481 18546 10489 15342 10481 15342 10490 15342 10490 15343 10481 15343 10482 15343 10479 15344 10477 15344 10491 15344 10491 15345 10477 15345 10492 15345 10491 15346 10492 15346 10493 15346 10493 15347 10492 15347 10494 15347 10493 15348 10494 15348 146 15348 148 15349 146 15349 10483 15349 10483 15350 146 15350 10494 15350 10483 18547 10494 18547 10484 18547 10484 18548 10494 18548 10492 18548 10484 18549 10492 18549 10485 18549 10485 18550 10492 18550 10477 18550 10485 18551 10477 18551 10486 18551 10486 15356 10477 15356 10468 15356 10486 18552 10468 18552 10392 18552 10392 18553 10468 18553 10390 18553 10495 18554 10496 18554 10497 18554 10421 18555 10429 18555 10498 18555 10424 18556 10422 18556 10499 18556 10500 18557 10426 18557 10501 18557 10420 18558 10428 18558 10502 18558 10426 18559 10500 18559 10427 18559 10446 18560 10440 18560 10439 18560 10444 18561 10443 18561 10503 18561 10449 18562 10448 18562 10504 18562 10504 18563 10505 18563 10449 18563 10449 18564 10505 18564 10503 18564 10449 18565 10503 18565 10450 18565 10450 18566 10503 18566 10443 18566 10437 18567 10506 18567 10438 18567 10438 18568 10506 18568 10497 18568 10438 18569 10497 18569 10435 18569 10435 18570 10497 18570 10496 18570 10435 18571 10496 18571 10433 18571 10433 18572 10496 18572 10495 18572 10433 18573 10495 18573 10434 18573 10445 18574 10507 18574 10446 18574 10446 18575 10507 18575 10508 18575 10446 18576 10508 18576 10440 18576 10440 18577 10508 18577 10509 18577 10440 18578 10509 18578 10442 18578 10442 18579 10509 18579 10510 18579 10442 18580 10510 18580 10441 18580 10441 18581 10510 18581 10436 18581 10451 18582 10408 18582 10511 18582 10511 18583 10408 18583 10402 18583 10511 18584 10402 18584 10401 18584 10401 18585 10420 18585 10511 18585 10511 18586 10420 18586 10502 18586 10511 18587 10502 18587 10512 18587 10512 18588 10502 18588 10513 18588 10428 18589 10427 18589 10502 18589 10502 18590 10427 18590 10500 18590 10502 18591 10500 18591 10513 18591 10513 18592 10500 18592 10501 18592 10513 18593 10501 18593 10514 18593 10514 18594 10515 18594 10516 18594 10451 18595 10511 18595 10447 18595 10447 18596 10511 18596 10512 18596 10447 18597 10512 18597 10448 18597 10448 18598 10512 18598 10513 18598 10448 18599 10513 18599 10504 18599 10504 18600 10513 18600 10514 18600 10504 18601 10514 18601 10505 18601 10505 18602 10514 18602 10516 18602 10505 18603 10516 18603 10503 18603 10517 18604 10518 18604 10519 18604 10437 18605 10436 18605 10519 18605 10519 18606 10436 18606 10510 18606 10519 18607 10510 18607 10517 18607 10517 18608 10510 18608 10509 18608 10517 18609 10509 18609 10515 18609 10515 18610 10509 18610 10508 18610 10515 18611 10508 18611 10516 18611 10516 18612 10508 18612 10507 18612 10516 18613 10507 18613 10503 18613 10503 18614 10507 18614 10445 18614 10503 18615 10445 18615 10444 18615 10422 18616 10421 18616 10499 18616 10499 18617 10421 18617 10498 18617 10499 18618 10498 18618 10520 18618 10520 18619 10498 18619 10521 18619 10520 18620 10521 18620 10522 18620 10522 18621 10521 18621 10523 18621 10522 18622 10523 18622 10524 18622 10524 18623 10523 18623 10525 18623 10524 18624 10525 18624 10526 18624 10526 18625 10525 18625 10527 18625 10526 18626 10527 18626 10528 18626 10528 18627 10527 18627 10529 18627 10437 18628 10519 18628 10506 18628 10506 18629 10519 18629 10518 18629 10506 18630 10518 18630 10497 18630 10497 18631 10518 18631 10530 18631 10497 18632 10530 18632 10495 18632 10426 18633 10424 18633 10501 18633 10501 18634 10424 18634 10499 18634 10501 18635 10499 18635 10514 18635 10514 18636 10499 18636 10520 18636 10514 18637 10520 18637 10515 18637 10515 18638 10520 18638 10522 18638 10515 18639 10522 18639 10517 18639 10517 18640 10522 18640 10524 18640 10517 18641 10524 18641 10518 18641 10518 18642 10524 18642 10526 18642 10518 18643 10526 18643 10530 18643 10530 18644 10526 18644 10528 18644 10530 9303 10528 9303 10495 9303 10495 18645 10528 18645 10531 18645 10529 18646 10532 18646 10528 18646 10528 18647 10532 18647 10533 18647 10528 18648 10533 18648 10531 18648 10534 18649 10535 18649 10536 18649 10482 15456 10480 15456 10537 15456 10455 15457 10454 15457 10538 15457 10452 15458 10462 15458 10539 15458 10470 15459 10540 15459 10471 15459 10471 18650 10540 18650 10541 18650 10542 15461 10543 15461 10544 15461 10544 15462 10543 15462 10545 15462 10544 15463 10545 15463 10546 15463 10546 18651 10545 18651 10547 18651 10546 18652 10547 18652 10548 18652 10548 18653 10547 18653 10541 18653 10548 18654 10541 18654 10549 18654 10549 18655 10541 18655 10540 18655 10550 15469 10543 15469 10551 15469 10551 15470 10543 15470 10542 15470 10551 15471 10542 15471 10552 15471 10463 18656 10464 18656 10553 18656 10553 18657 10554 18657 10463 18657 10463 15474 10554 15474 10555 15474 10463 18658 10555 18658 10457 18658 10457 18659 10555 18659 10458 18659 10458 15477 10555 15477 10556 15477 10458 15478 10556 15478 10459 15478 10459 15479 10556 15479 10460 15479 10460 15480 10556 15480 10557 15480 10460 15481 10557 15481 10461 15481 10452 15482 10539 15482 10453 15482 10453 15483 10539 15483 10558 15483 10453 15484 10558 15484 10454 15484 10454 18660 10558 18660 10559 18660 10454 18661 10559 18661 10538 18661 10493 18662 146 18662 10456 18662 10479 18663 10491 18663 10559 18663 10559 18664 10491 18664 10493 18664 10559 18665 10493 18665 10538 18665 10538 18666 10493 18666 10456 18666 10538 18667 10456 18667 10455 18667 10480 18668 10479 18668 10537 18668 10537 18669 10479 18669 10559 18669 10537 18670 10559 18670 10560 18670 10560 18671 10559 18671 10558 18671 10560 15497 10558 15497 10557 15497 10557 15498 10558 15498 10539 15498 10557 15499 10539 15499 10461 15499 10461 15500 10539 15500 10462 15500 10535 18672 10552 18672 10536 18672 10536 18673 10552 18673 10542 18673 10536 18674 10542 18674 10561 18674 10561 18675 10542 18675 10544 18675 10561 15505 10544 15505 10562 15505 10562 18676 10544 18676 10546 18676 10562 15507 10546 15507 10563 15507 10563 18677 10546 18677 10548 18677 10563 18678 10548 18678 10564 18678 10564 15510 10548 15510 10549 15510 10564 18679 10549 18679 10565 18679 10565 15512 10549 15512 10540 15512 10565 15513 10540 15513 10490 15513 10490 15514 10540 15514 10470 15514 10553 18680 10534 18680 10554 18680 10554 18681 10534 18681 10536 18681 10554 18682 10536 18682 10555 18682 10555 18683 10536 18683 10561 18683 10555 15519 10561 15519 10556 15519 10556 15520 10561 15520 10562 15520 10556 15521 10562 15521 10557 15521 10557 15522 10562 15522 10563 15522 10557 15523 10563 15523 10560 15523 10560 15524 10563 15524 10564 15524 10560 15525 10564 15525 10537 15525 10537 18684 10564 18684 10565 18684 10537 18685 10565 18685 10482 18685 10482 15528 10565 15528 10490 15528 10566 18686 10567 18686 10568 18686 10434 18687 10495 18687 10569 18687 10569 18688 10495 18688 10570 18688 10569 18689 10570 18689 10571 18689 10572 18690 10573 18690 10574 18690 10575 18691 10576 18691 10577 18691 10567 18692 10566 18692 10578 18692 10578 18693 10566 18693 10573 18693 10578 18694 10573 18694 10579 18694 10579 18695 10573 18695 10572 18695 10579 18696 10572 18696 10580 18696 10572 18697 10581 18697 10580 18697 10580 18698 10581 18698 10582 18698 10580 18699 10582 18699 10583 18699 10583 18700 10582 18700 10584 18700 10583 18701 10584 18701 10585 18701 10585 18702 10584 18702 10575 18702 10585 18703 10575 18703 10586 18703 10586 18704 10575 18704 10577 18704 10533 18705 10587 18705 10531 18705 10531 18706 10587 18706 10588 18706 10531 18707 10588 18707 10495 18707 10495 18708 10588 18708 10589 18708 10495 18709 10589 18709 10570 18709 10533 18710 10532 18710 10587 18710 10587 18711 10532 18711 10590 18711 10587 18712 10590 18712 10591 18712 10574 18713 10571 18713 10572 18713 10572 18714 10571 18714 10570 18714 10572 18715 10570 18715 10581 18715 10581 18716 10570 18716 10589 18716 10581 18717 10589 18717 10582 18717 10582 18718 10589 18718 10588 18718 10582 18719 10588 18719 10584 18719 10584 18720 10588 18720 10587 18720 10584 18721 10587 18721 10575 18721 10575 18722 10587 18722 10591 18722 10575 18723 10591 18723 10576 18723 10576 18724 10591 18724 10590 18724 10592 18725 10568 18725 10593 18725 10593 18726 10568 18726 10567 18726 10567 18727 10578 18727 10593 18727 10593 18728 10578 18728 10579 18728 10593 18729 10579 18729 10594 18729 10594 18730 10579 18730 10580 18730 10594 18731 10580 18731 10595 18731 10596 18732 10597 18732 10598 18732 10598 18733 10597 18733 10595 18733 10595 18734 10580 18734 10598 18734 10598 18735 10580 18735 10583 18735 10598 18736 10583 18736 10585 18736 10599 18737 10600 18737 10601 18737 10602 18738 10603 18738 10600 18738 10603 18739 10602 18739 10604 18739 10592 18740 10593 18740 10605 18740 10606 18741 10607 18741 10601 18741 10601 18742 10607 18742 10608 18742 10601 18743 10608 18743 10599 18743 10609 18744 10610 18744 10611 18744 10611 18745 10610 18745 10612 18745 10613 18746 10614 18746 10615 18746 10615 18747 10614 18747 10616 18747 10615 18748 10616 18748 10617 18748 10617 18749 10616 18749 10618 18749 10617 18750 10618 18750 10612 18750 10612 18751 10618 18751 10619 18751 10612 18752 10619 18752 10611 18752 10596 18753 10620 18753 10597 18753 10597 18754 10620 18754 10621 18754 10597 18755 10621 18755 10595 18755 10594 18756 10595 18756 10622 18756 10622 18757 10595 18757 10621 18757 10622 18758 10621 18758 10623 18758 10624 18759 10592 18759 10604 18759 10604 18760 10592 18760 10605 18760 10604 18761 10605 18761 10603 18761 10603 18762 10605 18762 10625 18762 10603 18763 10625 18763 10600 18763 10600 18764 10625 18764 10626 18764 10600 18765 10626 18765 10601 18765 10601 18766 10626 18766 10627 18766 10601 18767 10627 18767 10606 18767 10606 18768 10627 18768 10628 18768 10593 18769 10594 18769 10605 18769 10605 18770 10594 18770 10622 18770 10605 18771 10622 18771 10625 18771 10625 18772 10622 18772 10623 18772 10625 18773 10623 18773 10626 18773 10626 18774 10623 18774 10629 18774 10626 18775 10629 18775 10627 18775 10627 18776 10629 18776 10630 18776 10627 18777 10630 18777 10628 18777 10628 18778 10630 18778 10631 18778 10620 18779 10614 18779 10621 18779 10621 18780 10614 18780 10613 18780 10621 18781 10613 18781 10623 18781 10623 18782 10613 18782 10615 18782 10623 18783 10615 18783 10629 18783 10629 18784 10615 18784 10617 18784 10629 18785 10617 18785 10630 18785 10630 18786 10617 18786 10612 18786 10630 18787 10612 18787 10631 18787 10631 18788 10612 18788 10610 18788 10632 18789 10633 18789 10607 18789 10607 18790 10606 18790 10632 18790 10632 18791 10606 18791 10628 18791 10632 18792 10628 18792 10634 18792 10634 18793 10628 18793 10631 18793 10634 18794 10631 18794 10635 18794 10635 18795 10631 18795 10610 18795 10635 18796 10610 18796 10609 18796 10636 18797 10637 18797 10638 18797 10639 18798 10640 18798 10641 18798 10641 18799 10640 18799 10642 18799 10641 18800 10642 18800 10643 18800 10643 18801 10642 18801 10636 18801 10643 18802 10636 18802 10644 18802 10644 18803 10636 18803 10638 18803 10645 18804 10646 18804 10647 18804 10648 18805 10649 18805 10650 18805 10651 18806 10652 18806 10653 18806 10654 18807 10655 18807 10656 18807 10656 18808 10655 18808 10639 18808 10656 18809 10639 18809 10641 18809 10657 18810 10658 18810 10659 18810 10659 18811 10658 18811 10660 18811 10659 18812 10660 18812 10661 18812 10661 18813 10660 18813 10654 18813 10661 18814 10654 18814 10662 18814 10662 18815 10654 18815 10656 18815 10648 18816 10650 18816 10663 18816 10663 18817 10650 18817 10664 18817 10663 18818 10664 18818 10665 18818 10665 18819 10664 18819 10644 18819 10665 18820 10644 18820 10638 18820 10645 18821 10647 18821 10666 18821 10666 18822 10647 18822 10667 18822 10666 18823 10667 18823 10668 18823 10643 18824 10644 18824 10669 18824 10669 18825 10644 18825 10664 18825 10669 18826 10664 18826 10670 18826 10670 18827 10664 18827 10650 18827 10670 18828 10650 18828 10668 18828 10668 18829 10650 18829 10649 18829 10668 18830 10649 18830 10666 18830 10666 18831 10649 18831 10648 18831 10666 18832 10648 18832 10645 18832 10645 18833 10648 18833 10651 18833 10645 18834 10651 18834 10646 18834 10646 18835 10651 18835 10653 18835 10646 18836 10653 18836 10647 18836 10647 18837 10653 18837 10671 18837 10647 18838 10671 18838 10667 18838 10671 18839 10657 18839 10667 18839 10667 18840 10657 18840 10659 18840 10667 18841 10659 18841 10668 18841 10668 18842 10659 18842 10661 18842 10668 18843 10661 18843 10670 18843 10670 18844 10661 18844 10662 18844 10670 18845 10662 18845 10669 18845 10669 18846 10662 18846 10656 18846 10669 18847 10656 18847 10643 18847 10643 18848 10656 18848 10641 18848 10672 18849 10673 18849 10658 18849 10653 18850 10652 18850 10674 18850 10658 18851 10657 18851 10672 18851 10672 18852 10657 18852 10671 18852 10672 18853 10671 18853 10675 18853 10675 18854 10671 18854 10653 18854 10675 18855 10653 18855 10676 18855 10676 18856 10653 18856 10674 18856 10676 18857 10674 18857 10677 18857 10677 18858 10674 18858 10678 18858 10679 18859 10680 18859 10681 18859 10682 18860 10683 18860 10684 18860 10685 8973 10686 8973 10687 8973 10687 18861 10686 18861 10688 18861 10684 18862 10683 18862 10689 18862 10683 18863 10690 18863 10689 18863 10689 18864 10690 18864 10691 18864 10689 18865 10691 18865 10686 18865 10686 18866 10691 18866 10692 18866 10686 18867 10692 18867 10688 18867 10693 18868 10694 18868 10682 18868 10695 18869 10694 18869 10696 18869 10696 18870 10694 18870 10693 18870 10696 18871 10693 18871 10697 18871 10682 18872 10684 18872 10693 18872 10693 18873 10684 18873 10698 18873 10693 18874 10698 18874 10697 18874 10679 18875 10681 18875 10699 18875 10699 18876 10681 18876 10700 18876 10699 18877 10700 18877 10701 18877 10701 18878 10700 18878 10702 18878 10701 18879 10702 18879 10703 18879 10685 8993 10702 8993 10686 8993 10686 18880 10702 18880 10700 18880 10686 18881 10700 18881 10689 18881 10689 18882 10700 18882 10681 18882 10689 18883 10681 18883 10684 18883 10684 18884 10681 18884 10680 18884 10684 18885 10680 18885 10698 18885 10698 18886 10680 18886 10679 18886 10698 18887 10679 18887 10704 18887 10705 632 10706 632 10707 632 10708 632 10709 632 10710 632 10703 632 10711 632 10712 632 10704 632 10679 632 10713 632 10713 632 10679 632 10699 632 10713 632 10699 632 10707 632 10712 18888 10714 18888 10703 18888 10703 18889 10714 18889 10707 18889 10703 632 10707 632 10701 632 10701 632 10707 632 10699 632 10708 18888 10710 18888 10714 18888 10714 18890 10710 18890 10715 18890 10714 18891 10715 18891 10707 18891 10707 18892 10715 18892 10716 18892 10707 632 10716 632 10705 632 10717 18893 10718 18893 10719 18893 10720 18894 10721 18894 10719 18894 10719 18895 10721 18895 10722 18895 10719 18896 10722 18896 10717 18896 10723 18897 10724 18897 10725 18897 10725 18898 10724 18898 10726 18898 10725 18899 10726 18899 10727 18899 10727 18900 10726 18900 10728 18900 10727 18901 10728 18901 10729 18901 10729 18902 10728 18902 10730 18902 10729 18903 10730 18903 10731 18903 10715 18904 10710 18904 10732 18904 10733 18905 10734 18905 10735 18905 10732 18906 10736 18906 10715 18906 10715 18907 10736 18907 10737 18907 10715 18908 10737 18908 10716 18908 10716 18909 10737 18909 10733 18909 10716 18910 10733 18910 10705 18910 10705 18911 10733 18911 10735 18911 10705 18912 10735 18912 10706 18912 10718 18913 10738 18913 10719 18913 10719 18914 10738 18914 10724 18914 10719 18915 10724 18915 10720 18915 10720 18916 10724 18916 10723 18916 10738 18917 10734 18917 10724 18917 10724 18918 10734 18918 10733 18918 10724 18919 10733 18919 10726 18919 10726 18920 10733 18920 10737 18920 10726 8963 10737 8963 10728 8963 10728 18921 10737 18921 10736 18921 10728 18922 10736 18922 10730 18922 10730 18923 10736 18923 10732 18923 10328 18924 10327 18924 10727 18924 10727 18925 10327 18925 10338 18925 10727 18926 10338 18926 10725 18926 10725 18927 10338 18927 10339 18927 10725 18928 10339 18928 10723 18928 10723 18929 10339 18929 10340 18929 10723 18930 10340 18930 10720 18930 10720 18931 10340 18931 10307 18931 10720 18932 10307 18932 10721 18932 10721 8924 10307 8924 10306 8924 10721 18933 10306 18933 10722 18933 10722 18934 10306 18934 10301 18934 10722 18935 10301 18935 10717 18935 10731 18936 10320 18936 10321 18936 10321 18937 10326 18937 10731 18937 10731 18938 10326 18938 10325 18938 10731 18939 10325 18939 10329 18939 10328 18940 10727 18940 10329 18940 10329 18941 10727 18941 10729 18941 10329 18942 10729 18942 10731 18942 10739 106 10687 106 10740 106 10740 106 10687 106 10281 106 10740 106 10281 106 10741 106 10742 18943 10709 18943 10743 18943 10744 18944 10731 18944 10730 18944 10745 18945 10746 18945 10744 18945 10744 18946 10730 18946 10745 18946 10745 18947 10730 18947 10732 18947 10745 18948 10732 18948 10747 18948 10742 18949 10748 18949 10709 18949 10709 18950 10748 18950 10747 18950 10709 18951 10747 18951 10710 18951 10710 18952 10747 18952 10732 18952 10712 18953 10711 18953 10749 18953 10749 18954 10750 18954 10712 18954 10712 18955 10750 18955 10751 18955 10712 18956 10751 18956 10714 18956 10714 8899 10751 8899 10752 8899 10714 8900 10752 8900 10708 8900 10708 15770 10752 15770 10743 15770 10708 18957 10743 18957 10709 18957 10739 18958 10753 18958 10754 18958 10711 15773 10703 15773 10702 15773 10755 18959 10756 18959 10711 18959 10711 18960 10756 18960 10757 18960 10711 18961 10757 18961 10749 18961 10711 18962 10702 18962 10755 18962 10755 18963 10702 18963 10685 18963 10755 18964 10685 18964 10754 18964 10754 18965 10685 18965 10687 18965 10754 18966 10687 18966 10739 18966 10740 18967 10758 18967 10759 18967 10759 18968 10760 18968 10740 18968 10740 18969 10760 18969 10753 18969 10740 8884 10753 8884 10739 8884 10761 18970 10762 18970 10763 18970 10763 18971 10762 18971 10741 18971 10741 18972 10762 18972 10764 18972 10741 18973 10764 18973 10765 18973 10765 18974 10766 18974 10741 18974 10741 18975 10766 18975 10767 18975 10767 18976 10768 18976 10741 18976 10741 18977 10768 18977 10769 18977 10741 18978 10769 18978 10740 18978 10770 18979 10771 18979 10763 18979 10763 18980 10771 18980 10772 18980 10763 18981 10772 18981 10761 18981 10773 18982 10774 18982 10775 18982 10775 18983 10774 18983 10776 18983 10741 15797 10281 15797 10777 15797 10777 18984 10281 18984 10778 18984 10777 18985 10778 18985 10779 18985 10779 15800 10778 15800 10780 15800 10779 18986 10780 18986 10781 18986 10781 18987 10780 18987 10782 18987 10781 18988 10782 18988 10776 18988 10776 18989 10782 18989 10783 18989 10776 18990 10783 18990 10775 18990 10784 18991 10785 18991 10746 18991 10746 18992 10785 18992 10786 18992 10746 18993 10786 18993 10744 18993 10787 18994 10788 18994 10746 18994 10748 18995 10789 18995 10747 18995 10747 18996 10789 18996 10790 18996 10747 18997 10790 18997 10745 18997 10787 18998 10746 18998 10791 18998 10791 18999 10746 18999 10745 18999 10791 19000 10745 19000 10792 19000 10792 19001 10745 19001 10790 19001 10792 19002 10790 19002 10793 19002 10793 19003 10790 19003 10789 19003 10793 19004 10789 19004 10794 19004 10794 19005 10789 19005 10748 19005 10794 19006 10748 19006 10795 19006 10743 8838 10796 8838 10742 8838 10742 19007 10796 19007 10797 19007 10742 19008 10797 19008 10748 19008 10750 19009 10798 19009 10799 19009 10796 19010 10800 19010 10797 19010 10797 19011 10800 19011 10801 19011 10797 19012 10801 19012 10802 19012 10750 8831 10749 8831 10798 8831 10798 19013 10749 19013 10803 19013 10798 632 10803 632 10804 632 10804 15827 10803 15827 10805 15827 10804 19014 10805 19014 10806 19014 10796 15829 10743 15829 10800 15829 10800 15830 10743 15830 10752 15830 10800 15831 10752 15831 10799 15831 10799 19015 10752 19015 10751 19015 10799 19016 10751 19016 10750 19016 10749 19017 10757 19017 10803 19017 10803 19018 10757 19018 10805 19018 10757 19019 10807 19019 10808 19019 10753 19020 10809 19020 10810 19020 10754 19021 10811 19021 10755 19021 10755 19022 10811 19022 10807 19022 10755 19023 10807 19023 10756 19023 10756 19024 10807 19024 10757 19024 10753 19025 10810 19025 10754 19025 10754 19026 10810 19026 10812 19026 10754 19027 10812 19027 10811 19027 10811 19028 10812 19028 10813 19028 10811 19029 10813 19029 10807 19029 10807 19030 10813 19030 10814 19030 10807 19031 10814 19031 10808 19031 10815 19032 10816 19032 10320 19032 10320 19033 10816 19033 10817 19033 10816 19034 10818 19034 10817 19034 10817 19035 10818 19035 10819 19035 10817 19036 10819 19036 10820 19036 10820 19037 10819 19037 10821 19037 10820 19038 10821 19038 10822 19038 10822 19039 10821 19039 10823 19039 10822 19040 10823 19040 10824 19040 10825 19041 10826 19041 10827 19041 10827 19042 10826 19042 10828 19042 10827 19043 10828 19043 10829 19043 10830 19044 10831 19044 10815 19044 10815 19045 10831 19045 10832 19045 10832 19046 10833 19046 10815 19046 10815 19047 10833 19047 10834 19047 10815 19048 10834 19048 10828 19048 10828 19049 10834 19049 10835 19049 10828 19050 10835 19050 10829 19050 10836 19051 10837 19051 10838 19051 10834 19052 10833 19052 10839 19052 10839 19053 10833 19053 10832 19053 10786 19054 10785 19054 10840 19054 10841 19055 10831 19055 10830 19055 10831 19056 10841 19056 10832 19056 10832 19057 10841 19057 10838 19057 10832 19058 10838 19058 10839 19058 10835 19059 10834 19059 10842 19059 10842 19060 10834 19060 10839 19060 10842 19061 10839 19061 10843 19061 10843 19062 10839 19062 10838 19062 10843 19063 10838 19063 10844 19063 10844 19064 10838 19064 10837 19064 10844 19065 10837 19065 10845 19065 10830 19066 10786 19066 10841 19066 10841 19067 10786 19067 10840 19067 10841 19068 10840 19068 10838 19068 10838 19069 10840 19069 10846 19069 10838 19070 10846 19070 10836 19070 10847 19071 10848 19071 10849 19071 10850 19072 10851 19072 10852 19072 10850 19073 10852 19073 10853 19073 10853 19074 10852 19074 10854 19074 10853 8739 10854 8739 10855 8739 10855 8740 10854 8740 10856 8740 10855 19075 10856 19075 10857 19075 10857 19076 10856 19076 10858 19076 10857 19077 10858 19077 10859 19077 10847 19078 10849 19078 10860 19078 10860 19079 10849 19079 10861 19079 10860 19080 10861 19080 10862 19080 10862 19081 10861 19081 10863 19081 10862 8748 10863 8748 10864 8748 10864 19082 10863 19082 10865 19082 10865 15888 10863 15888 10866 15888 10865 19083 10866 19083 10867 19083 10867 19084 10866 19084 10868 19084 10868 19085 10866 19085 10869 19085 10868 19086 10869 19086 10870 19086 10851 19087 10871 19087 10852 19087 10852 19088 10871 19088 10872 19088 10852 8757 10872 8757 10854 8757 10854 19089 10872 19089 10873 19089 10854 19090 10873 19090 10856 19090 10856 19091 10873 19091 10874 19091 10856 19092 10874 19092 10858 19092 10858 19093 10874 19093 10875 19093 10871 19094 10869 19094 10872 19094 10872 19095 10869 19095 10866 19095 10872 19096 10866 19096 10873 19096 10873 8766 10866 8766 10863 8766 10873 19097 10863 19097 10874 19097 10874 19098 10863 19098 10861 19098 10874 19099 10861 19099 10875 19099 10875 8770 10861 8770 10849 8770 10767 8714 10766 8714 10876 8714 10766 19100 10765 19100 10876 19100 10876 19101 10765 19101 10764 19101 10876 19102 10764 19102 10877 19102 10877 19103 10764 19103 10762 19103 10740 19104 10769 19104 10878 19104 10878 19105 10769 19105 10768 19105 10878 19106 10768 19106 10879 19106 10879 19107 10768 19107 10767 19107 10879 15911 10767 15911 10880 15911 10767 19108 10876 19108 10880 19108 10880 19109 10876 19109 10881 19109 10880 19110 10881 19110 10882 19110 10758 19111 10740 19111 10883 19111 10883 19112 10740 19112 10878 19112 10883 19113 10878 19113 10884 19113 10884 19114 10878 19114 10879 19114 10884 19115 10879 19115 10885 19115 10885 19116 10879 19116 10880 19116 10885 19117 10880 19117 10886 19117 10886 19118 10880 19118 10882 19118 10759 632 10809 632 10760 632 10760 632 10809 632 10753 632 10887 19119 10771 19119 10770 19119 10770 19120 10888 19120 10887 19120 10887 19121 10888 19121 10889 19121 10887 19122 10889 19122 10890 19122 10890 19123 10889 19123 10891 19123 10892 19124 10893 19124 10894 19124 10894 19125 10893 19125 10891 19125 10894 19126 10891 19126 10895 19126 10895 19127 10891 19127 10889 19127 10896 19128 10897 19128 10898 19128 10897 19129 10899 19129 10898 19129 10898 19130 10899 19130 10900 19130 10898 19131 10900 19131 10894 19131 10894 19132 10900 19132 10901 19132 10894 19133 10901 19133 10892 19133 10898 19134 10902 19134 10896 19134 10896 8712 10902 8712 10903 8712 10896 19135 10903 19135 10904 19135 10905 19136 10906 19136 10907 19136 10905 19137 10907 19137 10908 19137 10909 19138 10910 19138 10911 19138 10911 19139 10910 19139 10912 19139 10911 19140 10912 19140 10913 19140 10913 19141 10914 19141 10911 19141 10911 19142 10914 19142 10915 19142 10911 19143 10915 19143 10916 19143 10776 8679 10774 8679 10859 8679 10859 15944 10917 15944 10776 15944 10776 19144 10917 19144 10918 19144 10776 19145 10918 19145 10919 19145 10741 19146 10777 19146 10763 19146 10763 19147 10777 19147 10907 19147 10763 19148 10907 19148 10770 19148 10770 19149 10907 19149 10906 19149 10777 19150 10779 19150 10907 19150 10907 19151 10779 19151 10916 19151 10907 19152 10916 19152 10908 19152 10908 15952 10916 15952 10915 15952 10779 19153 10781 19153 10916 19153 10916 19154 10781 19154 10776 19154 10916 19155 10776 19155 10911 19155 10911 19156 10776 19156 10919 19156 10911 19157 10919 19157 10909 19157 10920 19158 10881 19158 10921 19158 10921 19159 10881 19159 10876 19159 10921 19160 10876 19160 10922 19160 10876 19161 10877 19161 10922 19161 10922 19162 10877 19162 10762 19162 10922 19163 10762 19163 10761 19163 10922 19164 10761 19164 10772 19164 10921 19165 10922 19165 10923 19165 10923 19166 10922 19166 10772 19166 10923 19167 10772 19167 10924 19167 10924 19168 10772 19168 10771 19168 10920 19169 10921 19169 10925 19169 10925 19170 10921 19170 10923 19170 10925 19171 10923 19171 10926 19171 10926 19172 10923 19172 10924 19172 10926 19173 10924 19173 10927 19173 10746 632 10788 632 10784 632 10797 19174 10802 19174 10928 19174 10795 19175 10748 19175 10929 19175 10929 19176 10748 19176 10797 19176 10929 19177 10797 19177 10930 19177 10930 19178 10797 19178 10928 19178 10805 19179 10757 19179 10808 19179 10931 19180 10806 19180 10932 19180 10932 19181 10806 19181 10805 19181 10932 19182 10805 19182 10933 19182 10933 19183 10805 19183 10808 19183 10816 19184 10934 19184 10818 19184 10818 19185 10934 19185 10935 19185 10818 19186 10935 19186 10819 19186 10935 19187 10936 19187 10819 19187 10819 19188 10936 19188 10937 19188 10819 19189 10937 19189 10821 19189 10821 19190 10937 19190 10938 19190 10850 19191 10823 19191 10939 19191 10939 19192 10823 19192 10821 19192 10939 19193 10821 19193 10940 19193 10940 15985 10821 15985 10938 15985 10941 19194 10942 19194 10934 19194 10934 19195 10942 19195 10943 19195 10934 19196 10943 19196 10935 19196 10935 19197 10943 19197 10944 19197 10935 19198 10944 19198 10936 19198 10816 19199 10815 19199 10934 19199 10934 19200 10815 19200 10828 19200 10934 19201 10828 19201 10941 19201 10941 19202 10828 19202 10826 19202 10945 19203 10946 19203 10947 19203 10947 19204 10946 19204 10948 19204 10947 19205 10948 19205 10949 19205 10949 19206 10948 19206 10950 19206 10950 19207 10948 19207 10951 19207 10950 19208 10951 19208 10952 19208 10952 19209 10951 19209 10953 19209 10953 19210 10951 19210 10954 19210 10953 19211 10954 19211 10955 19211 10956 19212 10957 19212 10954 19212 10954 8615 10957 8615 10958 8615 10954 19213 10958 19213 10955 19213 10959 19214 10960 19214 10961 19214 10961 19215 10960 19215 10962 19215 10961 19216 10962 19216 10956 19216 10956 19217 10962 19217 10963 19217 10956 19218 10963 19218 10957 19218 10959 19219 10961 19219 10964 19219 10964 19220 10961 19220 10826 19220 10964 19221 10826 19221 10825 19221 10965 19222 10827 19222 10966 19222 10966 19223 10827 19223 10829 19223 10967 19224 10968 19224 10969 19224 10970 19225 10968 19225 10966 19225 10966 19226 10968 19226 10967 19226 10966 19227 10967 19227 10965 19227 10825 19228 10827 19228 10971 19228 10971 19229 10827 19229 10965 19229 10971 19230 10965 19230 10972 19230 10972 19231 10965 19231 10967 19231 10972 19232 10967 19232 10973 19232 10973 19233 10967 19233 10969 19233 10845 19234 10970 19234 10844 19234 10844 19235 10970 19235 10966 19235 10844 19236 10966 19236 10843 19236 10829 19237 10835 19237 10966 19237 10966 19238 10835 19238 10842 19238 10966 19239 10842 19239 10843 19239 10974 19240 10975 19240 10976 19240 10977 19241 10978 19241 10979 19241 10980 19242 10981 19242 10979 19242 10979 19243 10981 19243 10982 19243 10979 19244 10982 19244 10977 19244 10862 19245 10983 19245 10860 19245 10860 19246 10983 19246 10984 19246 10860 19247 10984 19247 10847 19247 10847 19248 10984 19248 10985 19248 10847 19249 10985 19249 10848 19249 10848 19250 10985 19250 10986 19250 10848 16034 10986 16034 10978 16034 10978 19251 10986 19251 10987 19251 10978 16036 10987 16036 10979 16036 10868 19252 10988 19252 10989 19252 10868 19253 10989 19253 10867 19253 10867 19254 10989 19254 10990 19254 10867 19255 10990 19255 10865 19255 10865 19256 10990 19256 10991 19256 10865 19257 10991 19257 10864 19257 10864 19258 10991 19258 10992 19258 10864 19259 10992 19259 10862 19259 10862 19260 10992 19260 10993 19260 10862 19261 10993 19261 10983 19261 10868 19262 10870 19262 10988 19262 10988 19263 10870 19263 10994 19263 10988 19264 10994 19264 10995 19264 10995 19265 10994 19265 10996 19265 10995 19266 10996 19266 10997 19266 10997 19267 10996 19267 10976 19267 10976 19268 10996 19268 10998 19268 10976 19269 10998 19269 10974 19269 10994 19270 10870 19270 10869 19270 10940 19271 10938 19271 10999 19271 10936 19272 10944 19272 11000 19272 11000 19273 10944 19273 10943 19273 11000 19274 10943 19274 11001 19274 11001 19275 10943 19275 10942 19275 10994 19276 11002 19276 10996 19276 10996 19277 11002 19277 11003 19277 10996 19278 11003 19278 10998 19278 11004 19279 11005 19279 11006 19279 11006 19280 11005 19280 11007 19280 11006 19281 11007 19281 11002 19281 11002 19282 11007 19282 11008 19282 11002 19283 11008 19283 11003 19283 10942 19284 11009 19284 11001 19284 11001 19285 11009 19285 11010 19285 11001 19286 11010 19286 11000 19286 11000 19287 11010 19287 11011 19287 11000 19288 11011 19288 11012 19288 11012 19289 11011 19289 11013 19289 11012 19290 11013 19290 11014 19290 11014 19291 11013 19291 11015 19291 11014 19292 11015 19292 11016 19292 10936 19293 11000 19293 11017 19293 11017 19294 11000 19294 11012 19294 11017 19295 11012 19295 11018 19295 11018 19296 11012 19296 11014 19296 11018 19297 11014 19297 11019 19297 11019 19298 11014 19298 11016 19298 11019 19299 11016 19299 11004 19299 11004 19300 11016 19300 11020 19300 11004 19301 11020 19301 11005 19301 10994 19302 11021 19302 11002 19302 11002 19303 11021 19303 11022 19303 11002 19304 11022 19304 11006 19304 11006 19305 11022 19305 11023 19305 11006 19306 11023 19306 11004 19306 11004 19307 11023 19307 10999 19307 11004 19308 10999 19308 11019 19308 11019 19309 10999 19309 10938 19309 11019 19310 10938 19310 11018 19310 11018 19311 10938 19311 10937 19311 11018 19312 10937 19312 11017 19312 11017 19313 10937 19313 10936 19313 10994 19314 10869 19314 11021 19314 11021 16081 10869 16081 10871 16081 11021 19315 10871 19315 11022 19315 11022 19316 10871 19316 10851 19316 11022 19317 10851 19317 11023 19317 11023 19318 10851 19318 10850 19318 11023 19319 10850 19319 10999 19319 10999 19320 10850 19320 10939 19320 10999 19321 10939 19321 10940 19321 11024 19322 11025 19322 11026 19322 10977 19323 10982 19323 11027 19323 10918 19324 11028 19324 10919 19324 10919 19325 11028 19325 11029 19325 10919 19326 11029 19326 10909 19326 11025 19327 10912 19327 10910 19327 10912 19328 11025 19328 10913 19328 10913 19329 11025 19329 11024 19329 10913 19330 11024 19330 11030 19330 10908 19331 10915 19331 11030 19331 11030 19332 10915 19332 10914 19332 11030 8449 10914 8449 10913 8449 11031 19333 11032 19333 11026 19333 11033 19334 11034 19334 11035 19334 11036 19335 11037 19335 11038 19335 11038 19336 11037 19336 11039 19336 11038 19337 11039 19337 11040 19337 11040 19338 11039 19338 11041 19338 11040 19339 11041 19339 11042 19339 11042 19340 11041 19340 11028 19340 11042 19341 11028 19341 11043 19341 11043 19342 11028 19342 10918 19342 11043 19343 10918 19343 10917 19343 10917 19344 10859 19344 11043 19344 11043 8462 10859 8462 11044 8462 11043 19345 11044 19345 11042 19345 11042 19346 11044 19346 11045 19346 11042 19347 11045 19347 11040 19347 11040 19348 11045 19348 11033 19348 11040 19349 11033 19349 11038 19349 11038 19350 11033 19350 11035 19350 11038 19351 11035 19351 11036 19351 10905 19352 10908 19352 11046 19352 11046 19353 10908 19353 11030 19353 11046 19354 11030 19354 11047 19354 11047 19355 11030 19355 11024 19355 11047 19356 11024 19356 11048 19356 11048 19357 11024 19357 11026 19357 11048 19358 11026 19358 11049 19358 11049 19359 11026 19359 11032 19359 11037 19360 11050 19360 11039 19360 11039 19361 11050 19361 11031 19361 11039 19362 11031 19362 11041 19362 11041 19363 11031 19363 11026 19363 11041 19364 11026 19364 11028 19364 11028 19365 11026 19365 11025 19365 11028 19366 11025 19366 11029 19366 11029 19367 11025 19367 10910 19367 11029 19368 10910 19368 10909 19368 10859 19369 10858 19369 11044 19369 11044 19370 10858 19370 10875 19370 11044 19371 10875 19371 11045 19371 11045 19372 10875 19372 10849 19372 11045 19373 10849 19373 11033 19373 11033 19374 10849 19374 10848 19374 11033 19375 10848 19375 11034 19375 11034 19376 10848 19376 10978 19376 11034 19377 10978 19377 11035 19377 11035 19378 10978 19378 10977 19378 11035 19379 10977 19379 11036 19379 11036 19380 10977 19380 11027 19380 11036 19381 11027 19381 11037 19381 11037 19382 11027 19382 11051 19382 11037 19383 11051 19383 11050 19383 10904 98 10903 98 11052 98 11052 19384 10903 19384 11053 19384 11052 98 11053 98 10981 98 10981 98 11053 98 11054 98 10981 98 11054 98 10982 98 11050 16144 11055 16144 11056 16144 11057 19385 10906 19385 10905 19385 10888 19386 10770 19386 10906 19386 10905 19387 11046 19387 11058 19387 11058 19388 11046 19388 11047 19388 11058 8395 11047 8395 11059 8395 11059 19389 11047 19389 11048 19389 11059 19390 11048 19390 11060 19390 11048 19391 11049 19391 11060 19391 11060 19392 11049 19392 11032 19392 11060 19393 11032 19393 11056 19393 11056 19394 11032 19394 11031 19394 11056 19395 11031 19395 11050 19395 10905 19396 11058 19396 11057 19396 11057 19397 11058 19397 11059 19397 11057 19398 11059 19398 11061 19398 11061 19399 11059 19399 11060 19399 11061 19400 11060 19400 11062 19400 11062 19401 11060 19401 11056 19401 11062 19402 11056 19402 11063 19402 11063 19403 11056 19403 11055 19403 11063 19404 11055 19404 11064 19404 10906 19405 11057 19405 10888 19405 10888 19406 11057 19406 11061 19406 10888 19407 11061 19407 10889 19407 10889 19408 11061 19408 11062 19408 10889 19409 11062 19409 10895 19409 10895 19410 11062 19410 11063 19410 10895 19411 11063 19411 10894 19411 10894 19412 11063 19412 11064 19412 10894 19413 11064 19413 10898 19413 11051 19414 11027 19414 11065 19414 11065 19415 11027 19415 11066 19415 11065 19416 11066 19416 11067 19416 11067 19417 11066 19417 11068 19417 11053 19418 11068 19418 11054 19418 11054 19419 11068 19419 11066 19419 11054 19420 11066 19420 10982 19420 10982 19421 11066 19421 11027 19421 11050 19422 11051 19422 11055 19422 11055 19423 11051 19423 11065 19423 11055 19424 11065 19424 11064 19424 11064 19425 11065 19425 11067 19425 11064 19426 11067 19426 10898 19426 10898 19427 11067 19427 11068 19427 10898 19428 11068 19428 10902 19428 10902 19429 11068 19429 11053 19429 10902 19430 11053 19430 10903 19430 11008 19431 11007 19431 11069 19431 11070 19432 11071 19432 11072 19432 11009 19433 11070 19433 11073 19433 11074 19434 11011 19434 11073 19434 11073 19435 11011 19435 11010 19435 11073 19436 11010 19436 11009 19436 11070 19437 11072 19437 11073 19437 11073 19438 11072 19438 11075 19438 11073 19439 11075 19439 11074 19439 11074 19440 11075 19440 11076 19440 11074 19441 11076 19441 11077 19441 11020 19442 11016 19442 11077 19442 11077 19443 11016 19443 11015 19443 11077 16187 11015 16187 11074 16187 11074 19444 11015 19444 11013 19444 11074 19445 11013 19445 11011 19445 11005 19446 11020 19446 11078 19446 11078 19447 11020 19447 11077 19447 11078 19448 11077 19448 11079 19448 11079 19449 11077 19449 11076 19449 11007 19450 11005 19450 11069 19450 11069 19451 11005 19451 11078 19451 11069 19452 11078 19452 11080 19452 11080 19453 11078 19453 11079 19453 11080 19454 11079 19454 10951 19454 10951 19455 11079 19455 11076 19455 10951 19456 11076 19456 10954 19456 10954 19457 11076 19457 11075 19457 10954 19458 11075 19458 10956 19458 10956 19459 11075 19459 11072 19459 10956 19460 11072 19460 10961 19460 10961 19461 11072 19461 11071 19461 10961 19462 11071 19462 10826 19462 10826 19463 11071 19463 11070 19463 10826 19464 11070 19464 10941 19464 10941 19465 11070 19465 11009 19465 10941 19466 11009 19466 10942 19466 11003 19467 11008 19467 11081 19467 11081 19468 11008 19468 11069 19468 11081 19469 11069 19469 11082 19469 11082 19470 11069 19470 11080 19470 11082 19471 11080 19471 10948 19471 10948 19472 11080 19472 10951 19472 10998 19473 11003 19473 11083 19473 11083 19474 11003 19474 11081 19474 11083 19475 11081 19475 11084 19475 11084 19476 11081 19476 11082 19476 11084 19477 11082 19477 10946 19477 10946 19478 11082 19478 10948 19478 10946 106 10945 106 11085 106 11084 106 10946 106 11083 106 11083 19479 10946 19479 11085 19479 11083 19480 11085 19480 10998 19480 10998 8340 11085 8340 10974 8340 11086 7585 11087 7585 11088 7585 11089 19481 11090 19481 11091 19481 11091 7585 11090 7585 11092 7585 11091 19482 11093 19482 11089 19482 11089 7585 11093 7585 11094 7585 11089 19483 11094 19483 11095 19483 11095 19484 11094 19484 11096 19484 11095 7585 11096 7585 11097 7585 11097 19485 11096 19485 11098 19485 11097 7585 11098 7585 11099 7585 11099 7585 11098 7585 11100 7585 11099 19486 11100 19486 11101 19486 11101 7585 11100 7585 11088 7585 11088 7585 11100 7585 11102 7585 11088 7585 11102 7585 11086 7585 11103 7585 11104 7585 11105 7585 11105 7585 11104 7585 11092 7585 11105 19487 11092 19487 11106 19487 11106 7585 11092 7585 11090 7585 10981 19488 10980 19488 11103 19488 10981 16225 11103 16225 11052 16225 11052 19489 11103 19489 11105 19489 11052 19490 11105 19490 11107 19490 10975 19491 10974 19491 11087 19491 11087 8315 10974 8315 11085 8315 11087 19492 11085 19492 11088 19492 11088 19493 11085 19493 11108 19493 11088 19494 11108 19494 11101 19494 11101 19495 11108 19495 11099 19495 11099 19496 11108 19496 11109 19496 11099 19497 11109 19497 11097 19497 11105 19498 11106 19498 11107 19498 11107 16232 11106 16232 11090 16232 11107 19499 11090 19499 11110 19499 11110 19500 11090 19500 11089 19500 11110 19501 11089 19501 11111 19501 11111 19502 11089 19502 11095 19502 11111 19503 11095 19503 11112 19503 11112 19504 11095 19504 11097 19504 11112 19505 11097 19505 11113 19505 11113 19506 11097 19506 11109 19506 11108 19507 11085 19507 10945 19507 10945 19508 11114 19508 11108 19508 11108 19509 11114 19509 11115 19509 11108 19510 11115 19510 11109 19510 11109 19511 11115 19511 11116 19511 11109 19512 11116 19512 11113 19512 11113 19513 11116 19513 11117 19513 11113 19514 11117 19514 11112 19514 10904 19515 11052 19515 11107 19515 11112 8294 11117 8294 11118 8294 11112 19516 11118 19516 11111 19516 11111 19517 11118 19517 11119 19517 11111 19518 11119 19518 11110 19518 11110 19519 11119 19519 11120 19519 11110 16239 11120 16239 11107 16239 11107 19520 11120 19520 11121 19520 11107 19521 11121 19521 10904 19521 10964 19522 10825 19522 11122 19522 11122 19523 10825 19523 10971 19523 11122 19524 10971 19524 10972 19524 10964 19525 11122 19525 10959 19525 10959 19526 11122 19526 11123 19526 10959 19527 11123 19527 10960 19527 10960 19528 11123 19528 11124 19528 10960 19529 11124 19529 10962 19529 10962 19530 11124 19530 11125 19530 10962 19531 11125 19531 10963 19531 10963 19532 11125 19532 11126 19532 10963 19533 11126 19533 10957 19533 10957 19534 11126 19534 10958 19534 10958 19535 11126 19535 11127 19535 10958 19536 11127 19536 10955 19536 10955 19537 11127 19537 11128 19537 10955 19538 11128 19538 10953 19538 10953 19539 11128 19539 11129 19539 10953 19540 11129 19540 10952 19540 10952 19541 11129 19541 11130 19541 10952 19542 11130 19542 10950 19542 10950 19543 11130 19543 11131 19543 10950 19544 11131 19544 10949 19544 10949 19545 11131 19545 11132 19545 10949 19546 11132 19546 10947 19546 10947 19547 11132 19547 11114 19547 10947 19548 11114 19548 10945 19548 11133 19549 11116 19549 11115 19549 11116 19550 11133 19550 11117 19550 11117 19551 11133 19551 11134 19551 11117 19552 11134 19552 11135 19552 11135 19553 11134 19553 11136 19553 11135 19554 11136 19554 11137 19554 11138 19555 11139 19555 11140 19555 11140 19556 11139 19556 11141 19556 11140 19557 11141 19557 11142 19557 11142 19558 11141 19558 11137 19558 11142 19559 11137 19559 11143 19559 11143 19560 11137 19560 11136 19560 11115 19561 11144 19561 11133 19561 11133 19562 11144 19562 11145 19562 11133 8249 11145 8249 11134 8249 11134 19563 11145 19563 11146 19563 11134 19564 11146 19564 11136 19564 11136 19565 11146 19565 11147 19565 11136 19566 11147 19566 11143 19566 11143 19567 11147 19567 11148 19567 11143 19568 11148 19568 11142 19568 11142 19569 11148 19569 11149 19569 11142 19570 11149 19570 11140 19570 11140 19571 11149 19571 11150 19571 11140 19572 11150 19572 11138 19572 11138 19573 11150 19573 11151 19573 11138 16279 11151 16279 11152 16279 11152 19574 11151 19574 11153 19574 11152 19575 11153 19575 11154 19575 11154 19576 11153 19576 11155 19576 11154 19577 11155 19577 11156 19577 11156 19578 11155 19578 11157 19578 11156 19579 11157 19579 10969 19579 10969 19580 11157 19580 10973 19580 11115 19581 11114 19581 11144 19581 11144 19582 11114 19582 11132 19582 11144 19583 11132 19583 11145 19583 11145 19584 11132 19584 11131 19584 11145 19585 11131 19585 11146 19585 11146 19586 11131 19586 11130 19586 11146 19587 11130 19587 11147 19587 11147 19588 11130 19588 11129 19588 11147 19589 11129 19589 11148 19589 11148 19590 11129 19590 11128 19590 11148 19591 11128 19591 11149 19591 11149 19592 11128 19592 11127 19592 11149 19593 11127 19593 11150 19593 11150 19594 11127 19594 11126 19594 11150 19595 11126 19595 11151 19595 11151 19596 11126 19596 11125 19596 11151 19597 11125 19597 11153 19597 11153 19598 11125 19598 11124 19598 11153 19599 11124 19599 11155 19599 11155 19600 11124 19600 11123 19600 11155 19601 11123 19601 11157 19601 11157 19602 11123 19602 11122 19602 11157 19603 11122 19603 10973 19603 10973 19604 11122 19604 10972 19604 11158 19605 11159 19605 11160 19605 11161 19606 11162 19606 11163 19606 11164 19607 11165 19607 11166 19607 11167 8118 11168 8118 11169 8118 11169 19608 11168 19608 11118 19608 11169 19609 11118 19609 11117 19609 11170 19610 10897 19610 11171 19610 11171 19611 10897 19611 10896 19611 11171 19612 10896 19612 11172 19612 11172 19613 10896 19613 10904 19613 11172 19614 10904 19614 11121 19614 10901 19615 10900 19615 11170 19615 11170 19616 10900 19616 10899 19616 11170 19617 10899 19617 10897 19617 10891 19618 10893 19618 11173 19618 11173 19619 10893 19619 10892 19619 11173 19620 10892 19620 11174 19620 11174 19621 10892 19621 10901 19621 11174 19622 10901 19622 11175 19622 11175 19623 10901 19623 11170 19623 10891 19624 11173 19624 10890 19624 10890 19625 11173 19625 11176 19625 10890 19626 11176 19626 10887 19626 10887 19627 11176 19627 11177 19627 10887 19628 11177 19628 11178 19628 11163 19629 11162 19629 11179 19629 11162 19630 11180 19630 11179 19630 11179 19631 11180 19631 11181 19631 11179 19632 11181 19632 11167 19632 11167 19633 11181 19633 11182 19633 11167 19634 11182 19634 11168 19634 10924 19635 11160 19635 10927 19635 10927 19636 11160 19636 11159 19636 10927 19637 11159 19637 11183 19637 11183 19638 11159 19638 11158 19638 11183 19639 11158 19639 11184 19639 11164 19640 11184 19640 11165 19640 11165 19641 11184 19641 11158 19641 11165 19642 11158 19642 11185 19642 11185 19643 11158 19643 11160 19643 11185 19644 11160 19644 11186 19644 11186 19645 11160 19645 10924 19645 11186 19646 10924 19646 10771 19646 11119 19647 11118 19647 11187 19647 11187 19648 11118 19648 11168 19648 11187 19649 11168 19649 11188 19649 11188 19650 11168 19650 11182 19650 11188 19651 11182 19651 11189 19651 11189 19652 11182 19652 11181 19652 11189 19653 11181 19653 11190 19653 11190 19654 11181 19654 11180 19654 11190 19655 11180 19655 11191 19655 11191 19656 11180 19656 11162 19656 11191 19657 11162 19657 11166 19657 11166 19658 11162 19658 11161 19658 11166 19659 11161 19659 11164 19659 11121 19660 11120 19660 11172 19660 11172 19661 11120 19661 11192 19661 11172 19662 11192 19662 11171 19662 11171 19663 11192 19663 11193 19663 11171 19664 11193 19664 11170 19664 11170 19665 11193 19665 11194 19665 11170 19666 11194 19666 11175 19666 11175 19667 11194 19667 11195 19667 11175 19668 11195 19668 11174 19668 11174 19669 11195 19669 11196 19669 11174 19670 11196 19670 11173 19670 11173 19671 11196 19671 11197 19671 11173 19672 11197 19672 11176 19672 11176 19673 11197 19673 11198 19673 11176 19674 11198 19674 11177 19674 11177 19675 11198 19675 11199 19675 11177 19676 11199 19676 11178 19676 10771 19677 10887 19677 11186 19677 11186 19678 10887 19678 11178 19678 11186 19679 11178 19679 11185 19679 11185 19680 11178 19680 11199 19680 11185 19681 11199 19681 11165 19681 11165 19682 11199 19682 11198 19682 11165 16367 11198 16367 11166 16367 11166 19683 11198 19683 11197 19683 11166 19684 11197 19684 11191 19684 11191 19685 11197 19685 11196 19685 11191 19686 11196 19686 11190 19686 11190 19687 11196 19687 11195 19687 11190 19688 11195 19688 11189 19688 11189 19689 11195 19689 11194 19689 11189 19690 11194 19690 11188 19690 11188 19691 11194 19691 11193 19691 11188 19692 11193 19692 11187 19692 11187 19693 11193 19693 11192 19693 11187 19694 11192 19694 11119 19694 11119 19695 11192 19695 11120 19695 11137 19696 11141 19696 11200 19696 11139 19697 11138 19697 11201 19697 11138 19698 11152 19698 11201 19698 11201 19699 11152 19699 11154 19699 11201 19700 11154 19700 11202 19700 11202 19701 11154 19701 11156 19701 11202 19702 11156 19702 11203 19702 11203 19703 11156 19703 10969 19703 11203 19704 10969 19704 11204 19704 11204 19705 10969 19705 10968 19705 11204 19706 10968 19706 10970 19706 11163 19707 11179 19707 11205 19707 11205 19708 11179 19708 11167 19708 11205 19709 11167 19709 11135 19709 11135 19710 11167 19710 11169 19710 11135 19711 11169 19711 11117 19711 11164 19712 11206 19712 11184 19712 11184 19713 11206 19713 11207 19713 11184 19714 11207 19714 11183 19714 11183 19715 11207 19715 11208 19715 11183 19716 11208 19716 10927 19716 11164 19717 11161 19717 11206 19717 11206 19718 11161 19718 11163 19718 11206 19719 11163 19719 11209 19719 11209 19720 11163 19720 11205 19720 11209 19721 11205 19721 11200 19721 11200 16399 11205 16399 11135 16399 11200 19722 11135 19722 11137 19722 11210 19723 10920 19723 10925 19723 11210 19724 10925 19724 11208 19724 11208 19725 10925 19725 10926 19725 11208 16403 10926 16403 10927 16403 11139 19726 11201 19726 11141 19726 11141 19727 11201 19727 11211 19727 11141 19728 11211 19728 11200 19728 11200 19729 11211 19729 11212 19729 11200 19730 11212 19730 11209 19730 11213 19731 11214 19731 11215 19731 10808 19732 10814 19732 11216 19732 10792 19733 10793 19733 11217 19733 10794 19734 10795 19734 11218 19734 11218 19735 10795 19735 10929 19735 11218 19736 10929 19736 10930 19736 10792 19737 11217 19737 10791 19737 10840 19738 10785 19738 10784 19738 10788 19739 10787 19739 10784 19739 10784 19740 10787 19740 11219 19740 10784 19741 11219 19741 10840 19741 11220 19742 10836 19742 11219 19742 11219 19743 10836 19743 10846 19743 11219 19744 10846 19744 10840 19744 11204 19745 10970 19745 11221 19745 11221 19746 10970 19746 10845 19746 11221 19747 10845 19747 10837 19747 11204 19748 11221 19748 11203 19748 11203 19749 11221 19749 11222 19749 11203 19750 11222 19750 11202 19750 11223 19751 11211 19751 11222 19751 11222 19752 11211 19752 11201 19752 11222 19753 11201 19753 11202 19753 11224 19754 11206 19754 11225 19754 11225 19755 11206 19755 11209 19755 11225 19756 11209 19756 11223 19756 11223 19757 11209 19757 11212 19757 11223 19758 11212 19758 11211 19758 11226 19759 11208 19759 11224 19759 11224 19760 11208 19760 11207 19760 11224 19761 11207 19761 11206 19761 10881 19762 11226 19762 10882 19762 10882 19763 11226 19763 10886 19763 10881 19764 10920 19764 11226 19764 11226 19765 10920 19765 11210 19765 11226 19766 11210 19766 11208 19766 10812 19767 10810 19767 11227 19767 11227 19768 10810 19768 10809 19768 11227 19769 10809 19769 10759 19769 10759 19770 10758 19770 11227 19770 11227 19771 10758 19771 10883 19771 11227 19772 10883 19772 10884 19772 10933 19773 10808 19773 10932 19773 10932 19774 10808 19774 11216 19774 10932 19775 11216 19775 10931 19775 10931 8002 11216 8002 11228 8002 11215 16441 11214 16441 11229 16441 11214 19776 11230 19776 11229 19776 11229 19777 11230 19777 11231 19777 11229 19778 11231 19778 11216 19778 11216 8007 11231 8007 11232 8007 11216 19779 11232 19779 11228 19779 11213 19780 11215 19780 11233 19780 11233 19781 11215 19781 11234 19781 11233 19782 11234 19782 11235 19782 11235 19783 11234 19783 11236 19783 11235 19784 11236 19784 11237 19784 11237 19785 11236 19785 11238 19785 11238 19786 11236 19786 11239 19786 11238 19787 11239 19787 11240 19787 11240 19788 11239 19788 11241 19788 11241 19789 11239 19789 11242 19789 11241 19790 11242 19790 11243 19790 11243 19791 11242 19791 11244 19791 11244 8021 11242 8021 11218 8021 11244 19792 11218 19792 11245 19792 11245 19793 11218 19793 10930 19793 11245 19794 10930 19794 10928 19794 10814 19795 10813 19795 11216 19795 11216 19796 10813 19796 11246 19796 11216 19797 11246 19797 11229 19797 11229 19798 11246 19798 11247 19798 11229 19799 11247 19799 11215 19799 11215 19800 11247 19800 11248 19800 11215 19801 11248 19801 11234 19801 11234 19802 11248 19802 11249 19802 11234 19803 11249 19803 11236 19803 11236 19804 11249 19804 11250 19804 11236 19805 11250 19805 11239 19805 11239 19806 11250 19806 11251 19806 11239 19807 11251 19807 11242 19807 11242 19808 11251 19808 11252 19808 11242 19809 11252 19809 11218 19809 11218 19810 11252 19810 11217 19810 11218 19811 11217 19811 10794 19811 10794 19812 11217 19812 10793 19812 10813 19813 10812 19813 11246 19813 11246 19814 10812 19814 11227 19814 11246 19815 11227 19815 11247 19815 11247 19816 11227 19816 11253 19816 11247 19817 11253 19817 11248 19817 11248 19818 11253 19818 11254 19818 11248 19819 11254 19819 11249 19819 11249 19820 11254 19820 11255 19820 11249 19821 11255 19821 11250 19821 11250 19822 11255 19822 11256 19822 11250 19823 11256 19823 11251 19823 11251 16476 11256 16476 11257 16476 11251 19824 11257 19824 11252 19824 11252 19825 11257 19825 11220 19825 11252 19826 11220 19826 11217 19826 11217 19827 11220 19827 11219 19827 11217 19828 11219 19828 10791 19828 10791 19829 11219 19829 10787 19829 10884 19830 10885 19830 11227 19830 11227 19831 10885 19831 10886 19831 11227 19832 10886 19832 11253 19832 11253 19833 10886 19833 11226 19833 11253 19834 11226 19834 11254 19834 11254 19835 11226 19835 11224 19835 11254 19836 11224 19836 11255 19836 11255 16487 11224 16487 11225 16487 11255 19837 11225 19837 11256 19837 11256 19838 11225 19838 11223 19838 11256 19839 11223 19839 11257 19839 11257 19840 11223 19840 11222 19840 11257 19841 11222 19841 11220 19841 11220 19842 11222 19842 11221 19842 11220 19843 11221 19843 10836 19843 10836 19844 11221 19844 10837 19844 10804 19845 10806 19845 10372 19845 10372 19846 10806 19846 10931 19846 10372 19847 10931 19847 11228 19847 10372 19848 10370 19848 10804 19848 10804 19849 10370 19849 10368 19849 10804 19850 10368 19850 10798 19850 10798 16496 10368 16496 10367 16496 10798 7929 10367 7929 10799 7929 10799 7930 10367 7930 10388 7930 10799 16497 10388 16497 10800 16497 10800 19851 10388 19851 10386 19851 10800 19852 10386 19852 10801 19852 11245 19853 10928 19853 10802 19853 10801 19854 10386 19854 10802 19854 10802 19855 10386 19855 10384 19855 10802 19856 10384 19856 11245 19856 10382 19857 11243 19857 10384 19857 10384 19858 11243 19858 11244 19858 10384 19859 11244 19859 11245 19859 10380 19860 11240 19860 10382 19860 10382 19861 11240 19861 11241 19861 10382 7943 11241 7943 11243 7943 10378 19862 11237 19862 10380 19862 10380 19863 11237 19863 11238 19863 10380 19864 11238 19864 11240 19864 10376 19865 11233 19865 10378 19865 10378 19866 11233 19866 11235 19866 10378 19867 11235 19867 11237 19867 10374 19868 11214 19868 10376 19868 10376 19869 11214 19869 11213 19869 10376 19870 11213 19870 11233 19870 11228 19871 11232 19871 10372 19871 10372 16510 11232 16510 11231 16510 10372 19872 11231 19872 10374 19872 10374 19873 11231 19873 11230 19873 10374 7957 11230 7957 11214 7957 10371 632 10381 632 10369 632 10369 19874 10381 19874 10383 19874 10377 632 10379 632 10375 632 10375 19875 10379 19875 10381 19875 10375 632 10381 632 10373 632 10373 632 10381 632 10371 632 10389 632 10366 632 10387 632 10387 632 10366 632 10369 632 10387 19876 10369 19876 10385 19876 10385 19877 10369 19877 10383 19877 10773 95 10345 95 9290 95 10857 19878 10859 19878 10774 19878 10824 95 9290 95 10361 95 10361 95 9290 95 9289 95 10774 95 10773 95 10857 95 10857 95 10773 95 9290 95 10857 95 9290 95 10855 95 10855 95 9290 95 10824 95 10855 95 10824 95 10853 95 10853 95 10824 95 10823 95 10853 19879 10823 19879 10850 19879 10281 7897 10687 7897 10252 7897 10252 19880 10687 19880 10253 19880 10276 19881 10275 19881 10692 19881 10692 19882 10275 19882 10259 19882 10692 19883 10259 19883 10688 19883 10688 19884 10259 19884 10257 19884 10688 19885 10257 19885 10687 19885 10687 19886 10257 19886 10255 19886 10687 19887 10255 19887 10253 19887 10276 19888 10692 19888 10278 19888 10278 19889 10692 19889 10691 19889 10278 19890 10691 19890 10280 19890 10280 19891 10691 19891 10690 19891 10280 19892 10690 19892 10244 19892 10244 16526 10690 16526 10683 16526 10244 19893 10683 19893 10245 19893 10695 19894 10242 19894 10694 19894 10694 19895 10242 19895 10245 19895 10694 19896 10245 19896 10682 19896 10682 7916 10245 7916 10683 7916 10351 19897 10350 19897 10349 19897 10281 19898 10351 19898 10778 19898 10778 19899 10351 19899 10349 19899 10778 19900 10349 19900 10780 19900 10780 19901 10349 19901 10348 19901 10780 19902 10348 19902 10782 19902 10782 19903 10348 19903 10347 19903 10782 19904 10347 19904 10783 19904 10783 19905 10347 19905 10353 19905 10783 19906 10353 19906 10775 19906 10345 19907 10773 19907 10346 19907 10346 19908 10773 19908 10775 19908 10346 19909 10775 19909 10352 19909 10352 19910 10775 19910 10353 19910 10824 19911 10361 19911 10362 19911 10824 19912 10362 19912 10822 19912 10822 19913 10362 19913 10365 19913 10822 19914 10365 19914 10820 19914 10820 19915 10365 19915 10364 19915 10820 19916 10364 19916 10817 19916 10817 19917 10364 19917 10363 19917 10817 19918 10363 19918 10360 19918 10360 19919 10359 19919 10817 19919 10817 19920 10359 19920 10358 19920 10817 19921 10358 19921 10320 19921 10624 19922 10604 19922 10707 19922 10707 19923 10604 19923 10602 19923 10707 19924 10602 19924 10600 19924 10734 19925 10738 19925 10568 19925 10624 19926 10707 19926 10592 19926 10592 19927 10707 19927 10706 19927 10592 19928 10706 19928 10568 19928 10568 19929 10706 19929 10735 19929 10568 19930 10735 19930 10734 19930 10301 19931 10299 19931 10717 19931 10717 19932 10299 19932 10568 19932 10717 19933 10568 19933 10718 19933 10718 19934 10568 19934 10738 19934 10633 19935 10640 19935 10607 19935 10607 19936 10640 19936 10639 19936 10607 19937 10639 19937 10655 19937 10654 19938 10599 19938 10655 19938 10655 19939 10599 19939 10608 19939 10655 19940 10608 19940 10607 19940 10695 19941 10696 19941 11258 19941 11258 19942 10696 19942 10697 19942 11258 19943 10697 19943 10698 19943 10600 19944 10599 19944 10707 19944 10707 19945 10599 19945 10654 19945 10707 19946 10654 19946 10713 19946 10713 19947 10654 19947 10660 19947 10713 19948 10660 19948 10704 19948 10704 19949 10660 19949 10658 19949 10704 19950 10658 19950 10698 19950 10698 19951 10658 19951 10673 19951 10698 19952 10673 19952 11258 19952 10242 19953 10695 19953 10233 19953 10233 19954 10695 19954 11258 19954 10233 16579 11258 16579 10234 16579 10234 19955 11258 19955 11259 19955 10234 19956 11259 19956 11260 19956 10464 19957 10236 19957 11261 19957 11261 19958 10236 19958 10234 19958 11261 19959 10234 19959 11262 19959 11262 19960 10234 19960 11260 19960 10571 19961 10284 19961 10569 19961 10569 19962 10284 19962 10283 19962 10569 19963 10283 19963 10434 19963 10571 19964 10574 19964 10284 19964 10284 19965 10574 19965 10573 19965 10284 19966 10573 19966 10299 19966 10299 19967 10573 19967 10566 19967 10299 19968 10566 19968 10568 19968 10815 19969 10320 19969 10830 19969 10830 19970 10320 19970 10731 19970 10830 19971 10731 19971 10786 19971 10786 98 10731 98 10744 98 10354 98 1392 98 10320 98 10354 98 10320 98 10358 98 10351 106 10281 106 10344 106 10344 106 10281 106 1412 106 728 98 719 98 4320 98 4320 98 719 98 9497 98 10183 19972 10182 19972 585 19972 585 19973 10182 19973 10397 19973 585 19974 10397 19974 10406 19974 927 98 585 98 10294 98 10294 19975 585 19975 10406 19975 10294 19976 10406 19976 10295 19976 10295 19977 10406 19977 10408 19977 10202 98 10195 98 4320 98 4320 19978 10195 19978 10194 19978 10137 19979 9497 19979 10224 19979 10224 98 9497 98 719 98 10224 19980 719 19980 6628 19980 6628 19981 719 19981 718 19981 10104 19982 10183 19982 10205 19982 10205 19983 10183 19983 585 19983 10205 98 585 98 10194 98 10194 98 585 98 581 98 10194 98 581 98 4320 98 10202 98 4320 98 10203 98 10203 98 4320 98 9497 98 10203 98 9497 98 9465 98 9465 98 9497 98 9496 98 9465 98 9496 98 9466 98 927 95 10294 95 740 95 740 95 10294 95 10293 95 740 95 10293 95 741 95 142 95 141 95 10226 95 10226 95 141 95 891 95 9359 106 9358 106 9365 106 9365 106 9358 106 9512 106 9337 19984 9336 19984 9513 19984 9513 7816 9336 7816 9362 7816 9513 7817 9362 7817 9514 7817 9514 19985 9362 19985 9363 19985 9514 19986 9363 19986 9512 19986 9512 19987 9363 19987 9365 19987 9824 98 11263 98 9307 98 9630 19988 9818 19988 9305 19988 9818 19989 9820 19989 9305 19989 9305 19990 9820 19990 9821 19990 9305 98 9821 98 9307 98 9307 19991 9821 19991 9823 19991 9307 19992 9823 19992 9824 19992 9305 19993 9986 19993 9988 19993 9988 98 9992 98 9305 98 9305 19994 9992 19994 9990 19994 9305 98 9990 98 9630 98 9630 98 9990 98 9629 98 9630 98 9629 98 9631 98 9629 98 9624 98 9631 98 9631 19995 9624 19995 9622 19995 9631 98 9622 98 9609 98 9609 19996 9622 19996 9621 19996 9609 98 9621 98 9610 98 9306 106 9979 106 9304 106 9304 19997 9979 19997 9978 19997 9304 19998 9978 19998 9977 19998 9308 95 9970 95 9973 95 9982 95 9306 95 9984 95 9984 95 9306 95 9308 95 9984 95 9308 95 9975 95 9975 95 9308 95 9973 95 9982 95 9981 95 9306 95 9306 95 9981 95 9980 95 9306 95 9980 95 9979 95 9971 106 9970 106 9308 106 9309 106 11264 106 10054 106 10054 106 10053 106 9309 106 9309 19999 10053 19999 10069 19999 9309 106 10069 106 9308 106 9308 20000 10069 20000 10071 20000 9848 106 9864 106 9856 106 9856 20001 9864 20001 9835 20001 10071 20002 10073 20002 9308 20002 9308 20003 10073 20003 10075 20003 9308 20004 10075 20004 9971 20004 9971 20005 10075 20005 9846 20005 9971 106 9846 106 9856 106 9856 20006 9846 20006 9848 20006 9835 20007 9849 20007 9856 20007 9856 106 9849 106 9851 106 9856 106 9851 106 9854 106 9826 20008 11265 20008 9825 20008 9825 20009 11265 20009 11263 20009 9825 20010 11263 20010 9824 20010 9831 20011 10391 20011 9827 20011 9827 20012 10391 20012 11266 20012 9827 20013 11266 20013 9826 20013 9826 20014 11266 20014 11267 20014 9826 20015 11267 20015 11265 20015 10054 20016 11264 20016 10055 20016 10055 20017 11264 20017 11268 20017 10055 20018 11268 20018 10064 20018 11268 20019 11269 20019 11270 20019 11268 20020 11270 20020 10064 20020 10064 20021 11270 20021 10395 20021 10064 20022 10395 20022 10065 20022 10988 20023 9300 20023 10989 20023 10989 20024 9300 20024 9299 20024 10989 20025 9299 20025 10990 20025 10988 20026 10995 20026 9300 20026 9300 20027 10995 20027 10997 20027 9300 16640 10997 16640 9301 16640 9301 20028 10997 20028 10976 20028 9301 20029 10976 20029 10975 20029 9303 20030 9302 20030 10983 20030 10983 20031 10993 20031 9303 20031 9303 20032 10993 20032 10992 20032 9303 20033 10992 20033 9299 20033 9299 20034 10992 20034 10991 20034 9299 20035 10991 20035 10990 20035 10987 20036 10986 20036 9295 20036 9295 20037 10986 20037 10985 20037 9295 20038 10985 20038 9302 20038 9302 20039 10985 20039 10984 20039 9302 20040 10984 20040 10983 20040 10987 20041 9295 20041 10979 20041 10979 20042 9295 20042 9294 20042 10979 20043 9294 20043 10980 20043 11093 20044 9292 20044 11094 20044 11094 20045 9292 20045 9291 20045 11094 16655 9291 16655 11096 16655 11096 20046 9291 20046 9298 20046 11096 20047 9298 20047 11098 20047 11098 7762 9298 7762 9297 7762 11098 20048 9297 20048 11100 20048 11100 20048 9297 20048 9296 20048 11100 20049 9296 20049 11102 20049 11102 20050 9296 20050 9301 20050 11102 20051 9301 20051 11086 20051 11086 20052 9301 20052 10975 20052 11086 20053 10975 20053 11087 20053 11103 20054 10980 20054 11104 20054 11104 20055 10980 20055 9294 20055 11104 20056 9294 20056 11092 20056 11092 20057 9294 20057 9292 20057 11092 20058 9292 20058 11091 20058 11091 16667 9292 16667 11093 16667 4345 20059 7310 20059 4329 20059 4348 20060 11271 20060 4349 20060 4349 20061 11271 20061 4350 20061 7310 20062 4345 20062 7309 20062 7309 20063 4345 20063 4346 20063 7309 20064 4346 20064 7241 20064 4347 20065 6751 20065 4346 20065 4346 20066 6751 20066 6752 20066 4346 20067 6752 20067 7241 20067 4347 20068 4350 20068 6751 20068 6751 20069 4350 20069 11271 20069 6751 20070 11271 20070 11272 20070 11272 20071 11271 20071 4348 20071 11272 20072 4348 20072 570 20072 11273 20073 6737 20073 6739 20073 11274 20074 4288 20074 11275 20074 11275 20075 4288 20075 4290 20075 11275 20076 4290 20076 11276 20076 11276 20077 4290 20077 4292 20077 11276 20078 4292 20078 11277 20078 11277 20079 4292 20079 4293 20079 11277 20080 4293 20080 11273 20080 570 20081 575 20081 11272 20081 11272 20082 575 20082 568 20082 11272 20083 568 20083 11278 20083 11278 20084 568 20084 567 20084 11278 20085 567 20085 11274 20085 11274 20086 567 20086 4289 20086 11274 20087 4289 20087 4288 20087 11273 20088 6739 20088 11277 20088 11277 20089 6739 20089 6741 20089 11277 20090 6741 20090 11276 20090 11276 20091 6741 20091 6744 20091 11276 20092 6744 20092 11275 20092 11275 20093 6744 20093 6746 20093 11275 20094 6746 20094 11274 20094 11274 20095 6746 20095 6748 20095 11274 20096 6748 20096 11278 20096 11278 20097 6748 20097 6749 20097 11278 20098 6749 20098 11272 20098 11272 20099 6749 20099 6750 20099 11272 20100 6750 20100 6751 20100 4301 20101 7308 20101 11279 20101 11280 20102 11281 20102 4295 20102 4295 20103 11281 20103 11282 20103 4295 20104 11282 20104 4296 20104 4293 20105 4296 20105 11273 20105 11273 20106 4296 20106 11282 20106 11273 20107 11282 20107 6737 20107 4295 20108 4305 20108 11280 20108 11280 20109 4305 20109 4303 20109 11280 20110 4303 20110 11283 20110 11283 20111 4303 20111 4302 20111 11283 20112 4302 20112 11284 20112 11284 20113 4302 20113 4297 20113 11284 20114 4297 20114 11279 20114 11279 20115 4297 20115 4299 20115 11279 20116 4299 20116 4301 20116 6737 20117 11282 20117 7053 20117 7053 20118 11282 20118 11281 20118 7053 20119 11281 20119 7054 20119 7054 20120 11281 20120 11280 20120 7054 20121 11280 20121 7055 20121 7055 20122 11280 20122 11283 20122 7055 20123 11283 20123 7051 20123 7051 20124 11283 20124 11284 20124 7051 20125 11284 20125 7052 20125 7052 20126 11284 20126 11279 20126 7052 20127 11279 20127 7050 20127 7050 20128 11279 20128 7308 20128 7050 20129 7308 20129 7049 20129 4319 7585 4320 7585 581 7585 581 7585 583 7585 4318 7585 581 7585 4318 7585 4319 7585 557 20130 951 20130 952 20130 952 98 1272 98 11285 98 11286 98 11287 98 557 98 6664 98 558 98 4266 98 4266 98 558 98 557 98 4266 98 557 98 4267 98 4267 20131 557 20131 11287 20131 11285 98 11288 98 952 98 952 20132 11288 20132 11289 20132 952 20133 11289 20133 11290 20133 11286 98 557 98 11291 98 11291 20134 557 20134 952 20134 11291 98 952 98 11292 98 11292 98 952 98 11290 98 11292 20135 11290 20135 11293 20135 4131 106 4278 106 1273 106 1273 106 4278 106 11294 106 1273 106 11294 106 11295 106 11296 20136 11297 20136 11298 20136 11299 20137 11300 20137 11301 20137 11297 20138 11302 20138 11298 20138 11298 20139 11302 20139 11303 20139 11298 20140 11303 20140 11294 20140 11294 20141 11303 20141 11304 20141 11294 20142 11304 20142 11295 20142 11299 106 11301 106 11298 106 11298 20143 11301 20143 11305 20143 11298 20144 11305 20144 11296 20144 6926 98 6924 98 1286 98 6869 20145 4279 20145 1287 20145 1286 98 1461 98 6904 98 6920 20146 6918 20146 1287 20146 6918 20147 6916 20147 1287 20147 1287 20148 6916 20148 6915 20148 1287 20149 6915 20149 6869 20149 1286 20150 6924 20150 1287 20150 1287 20151 6924 20151 6922 20151 1287 20152 6922 20152 6920 20152 6904 98 6912 98 1286 98 1286 20153 6912 20153 6910 20153 1286 98 6910 98 6908 98 6908 98 6906 98 1286 98 1286 20154 6906 20154 6927 20154 1286 20155 6927 20155 6926 20155 625 20156 623 20156 1238 20156 11306 20157 2125 20157 2532 20157 1238 95 1350 95 625 95 625 20158 1350 20158 1351 20158 625 20159 1351 20159 11306 20159 11306 95 1351 95 1608 95 11306 20160 1608 20160 2125 20160 796 95 795 95 11307 95 2532 20161 2529 20161 11306 20161 11306 20162 2529 20162 2531 20162 11306 95 2531 95 11307 95 11307 20163 2531 20163 791 20163 11307 95 791 95 796 95 4298 95 877 95 879 95 4298 95 879 95 4300 95 879 20164 881 20164 4300 20164 4300 20165 881 20165 883 20165 4300 20166 883 20166 628 20166 628 20167 883 20167 1338 20167 628 20168 1338 20168 649 20168 877 20169 4298 20169 875 20169 875 95 4298 95 4304 95 875 20170 4304 20170 873 20170 873 95 4304 95 4294 95 873 95 4294 95 4291 95 856 95 867 95 4287 95 4287 95 867 95 869 95 4287 20171 869 20171 4291 20171 4291 95 869 95 871 95 4291 95 871 95 873 95 1642 95 4306 95 1643 95 1643 20172 4306 20172 1641 20172 1642 20173 1646 20173 4306 20173 4306 95 1646 95 1648 95 4306 95 1648 95 4312 95 1648 20174 1650 20174 4312 20174 4312 20175 1650 20175 1652 20175 4312 95 1652 95 4310 95 4310 95 1652 95 1657 95 4310 95 1657 95 1656 95 279 7585 252 7585 4168 7585 4168 20176 252 20176 4169 20176 4166 95 278 95 4165 95 4165 95 278 95 279 95 4165 95 279 95 4168 95 4169 20177 252 20177 1786 20177 1786 20178 252 20178 251 20178 4155 20179 11308 20179 4156 20179 4156 20180 11308 20180 4157 20180 11309 20181 9276 20181 4157 20181 4157 20182 11308 20182 11309 20182 11309 20183 11308 20183 8244 20183 11309 20184 8244 20184 9278 20184 9279 95 9276 95 9280 95 9280 20185 9276 20185 11309 20185 9280 20186 11309 20186 9281 20186 9281 20187 11309 20187 9278 20187 9281 95 9278 95 9277 95 4155 20188 4154 20188 11308 20188 11308 20189 4154 20189 4153 20189 11308 20190 4153 20190 8260 20190 8260 20191 8241 20191 11308 20191 11308 20192 8241 20192 8240 20192 11308 20193 8240 20193 8244 20193 272 20194 4158 20194 258 20194 258 20195 4158 20195 4157 20195 271 20196 273 20196 4162 20196 4162 20197 4161 20197 271 20197 271 20198 4161 20198 4160 20198 271 20199 4160 20199 272 20199 272 20200 4160 20200 4159 20200 272 20201 4159 20201 4158 20201 4148 20202 4145 20202 8366 20202 8366 20203 4145 20203 4146 20203 8366 20204 4146 20204 8367 20204 8367 20205 4146 20205 4147 20205 4148 20206 8366 20206 4149 20206 4149 20207 8366 20207 8365 20207 4149 20208 8365 20208 4143 20208 4143 20209 8365 20209 4144 20209 4144 20210 8365 20210 8364 20210 4144 20211 8364 20211 4152 20211 11310 20212 9272 20212 9271 20212 11311 20213 11312 20213 11313 20213 11311 20214 11313 20214 11314 20214 9271 20215 11315 20215 11310 20215 11310 20216 11315 20216 11316 20216 11310 20217 11316 20217 11317 20217 11317 20218 11316 20218 11314 20218 11317 20219 11314 20219 11318 20219 11318 20220 11314 20220 11313 20220 11319 20221 8687 20221 8688 20221 9274 20222 9273 20222 11320 20222 11320 20223 9273 20223 9272 20223 11320 20224 9272 20224 11310 20224 11320 20225 11321 20225 9274 20225 9274 20226 11321 20226 11322 20226 9274 20227 11322 20227 9275 20227 9275 20228 11322 20228 11323 20228 9275 20229 11323 20229 8691 20229 8691 20230 11323 20230 8690 20230 11324 20231 11325 20231 11326 20231 11326 20232 11325 20232 11327 20232 11326 20233 11327 20233 11328 20233 11328 20234 11327 20234 11329 20234 11328 20235 11329 20235 11330 20235 11313 20236 11312 20236 11329 20236 11329 20237 11312 20237 11331 20237 11329 20238 11331 20238 11330 20238 11319 20239 8688 20239 11332 20239 11332 20240 8688 20240 8689 20240 11332 20241 8689 20241 11333 20241 8686 20242 8687 20242 11334 20242 11334 20243 8687 20243 11319 20243 11334 20244 11319 20244 11335 20244 11335 20245 11319 20245 11332 20245 11335 20246 11332 20246 11336 20246 11336 20247 11332 20247 11333 20247 11336 20248 11333 20248 11337 20248 11325 20249 11338 20249 11327 20249 11327 20250 11338 20250 11339 20250 11327 20251 11339 20251 11329 20251 11329 20252 11339 20252 11340 20252 11329 20253 11340 20253 11313 20253 11313 20254 11340 20254 11318 20254 11317 20255 11318 20255 11341 20255 11341 20256 11318 20256 11340 20256 11341 20257 11340 20257 11342 20257 11342 20258 11340 20258 11339 20258 11342 20259 11339 20259 11337 20259 11337 20260 11339 20260 11338 20260 11337 20261 11338 20261 11336 20261 11336 20262 11338 20262 11325 20262 11336 20263 11325 20263 11335 20263 11335 20264 11325 20264 11324 20264 11335 20265 11324 20265 11334 20265 8689 20266 8690 20266 11333 20266 11333 20267 8690 20267 11323 20267 11333 20268 11323 20268 11337 20268 11337 20269 11323 20269 11322 20269 11337 20270 11322 20270 11342 20270 11342 20271 11322 20271 11321 20271 11342 20272 11321 20272 11341 20272 11341 20273 11321 20273 11320 20273 11341 20274 11320 20274 11317 20274 11317 20275 11320 20275 11310 20275 4162 7585 273 7585 4163 7585 4163 7585 273 7585 274 7585 4163 20276 274 20276 4164 20276 4164 20277 274 20277 275 20277 4164 20278 275 20278 4139 20278 4139 20279 275 20279 269 20279 4139 20280 269 20280 4167 20280 4167 20281 269 20281 278 20281 4167 20282 278 20282 4166 20282 11343 20283 11344 20283 9282 20283 9282 20284 11344 20284 11345 20284 7844 20285 8418 20285 7845 20285 7845 20286 8418 20286 11346 20286 7845 20287 11346 20287 7842 20287 7842 20288 11346 20288 11343 20288 7842 20289 11343 20289 7843 20289 7843 20290 11343 20290 9282 20290 8607 20291 11347 20291 8608 20291 8608 20292 11347 20292 8591 20292 11347 20293 11348 20293 8591 20293 8591 20294 11348 20294 11349 20294 8591 20295 11349 20295 8592 20295 8592 20296 11349 20296 8620 20296 8571 20297 8569 20297 8565 20297 8565 20298 8569 20298 11350 20298 8565 20299 11350 20299 8499 20299 8418 20300 8496 20300 11351 20300 11351 20301 8496 20301 8495 20301 8495 20302 8493 20302 11351 20302 11351 20303 8493 20303 8492 20303 11351 20304 8492 20304 8499 20304 11352 20305 11353 20305 11354 20305 11354 20306 11353 20306 11355 20306 8418 20307 11351 20307 11346 20307 11346 20308 11351 20308 11354 20308 11346 20309 11354 20309 11343 20309 11343 20310 11354 20310 11355 20310 11343 20311 11355 20311 11344 20311 11348 20312 11356 20312 11352 20312 11356 20313 11348 20313 11357 20313 11357 20314 11348 20314 11347 20314 11357 20315 11347 20315 11358 20315 11358 20316 11347 20316 8607 20316 11358 20317 8607 20317 9287 20317 11352 20318 11354 20318 11348 20318 11348 20319 11354 20319 11351 20319 11348 20320 11351 20320 11349 20320 11349 20321 11351 20321 8499 20321 11349 20322 8499 20322 8620 20322 8620 20323 8499 20323 11350 20323 8620 20324 11350 20324 8574 20324 8574 20325 11350 20325 8569 20325 8574 20326 8569 20326 8567 20326 11326 20327 11328 20327 11359 20327 9288 20328 8686 20328 11334 20328 9288 20329 11334 20329 11359 20329 11359 20330 11334 20330 11324 20330 11359 20331 11324 20331 11326 20331 4272 20332 4274 20332 11360 20332 4269 20333 4268 20333 11361 20333 11294 20334 4278 20334 4277 20334 11362 20335 1274 20335 1273 20335 1284 20336 1283 20336 11363 20336 11363 20337 1283 20337 1274 20337 1277 20338 1285 20338 11364 20338 11364 20339 1285 20339 1284 20339 4274 20340 4269 20340 11360 20340 11360 20341 4269 20341 11361 20341 11360 20342 11361 20342 11365 20342 11365 20343 11361 20343 11366 20343 11366 20344 11367 20344 11365 20344 11365 20345 11367 20345 11368 20345 11365 20346 11368 20346 11369 20346 11368 20347 11370 20347 11369 20347 11369 20348 11370 20348 11371 20348 11369 20349 11371 20349 11372 20349 11372 20350 11371 20350 11373 20350 11372 20351 11373 20351 11374 20351 11373 20352 11375 20352 11374 20352 11374 20353 11375 20353 11376 20353 11374 20354 11376 20354 11377 20354 11376 20355 11378 20355 11377 20355 11377 20356 11378 20356 11379 20356 11377 20357 11379 20357 11380 20357 11380 20358 11379 20358 11381 20358 11380 20359 11381 20359 11382 20359 11382 20360 11381 20360 11383 20360 11382 20361 11383 20361 11384 20361 11384 20362 11383 20362 11385 20362 11385 20363 11386 20363 11384 20363 11384 20364 11386 20364 11387 20364 11384 20365 11387 20365 11388 20365 11388 20366 11387 20366 11389 20366 11388 20367 11389 20367 11390 20367 1278 20368 1277 20368 11391 20368 11391 20369 1277 20369 11364 20369 11391 20370 11364 20370 11392 20370 11392 20371 11364 20371 11390 20371 11392 20372 11390 20372 11393 20372 11393 20373 11390 20373 11389 20373 1284 20374 11363 20374 11364 20374 11364 20375 11363 20375 11394 20375 11364 20376 11394 20376 11390 20376 11390 20377 11394 20377 11395 20377 11390 20378 11395 20378 11388 20378 11388 20379 11395 20379 11396 20379 11388 20380 11396 20380 11384 20380 11384 20381 11396 20381 11397 20381 11384 20382 11397 20382 11382 20382 11382 20383 11397 20383 11398 20383 11382 20384 11398 20384 11380 20384 11380 20385 11398 20385 11399 20385 11380 20386 11399 20386 11377 20386 11377 20387 11399 20387 11400 20387 11377 20388 11400 20388 11374 20388 11374 20389 11400 20389 11401 20389 11374 20390 11401 20390 11372 20390 11372 20391 11401 20391 11402 20391 11372 20392 11402 20392 11369 20392 11369 20393 11402 20393 11403 20393 11369 20394 11403 20394 11365 20394 11365 20395 11403 20395 11404 20395 11365 20396 11404 20396 11360 20396 11360 20397 11404 20397 4270 20397 11360 20398 4270 20398 4272 20398 1274 20399 11362 20399 11363 20399 11363 20400 11362 20400 11405 20400 11363 20401 11405 20401 11394 20401 11394 20402 11405 20402 11406 20402 11394 20403 11406 20403 11395 20403 11395 20404 11406 20404 11407 20404 11395 20405 11407 20405 11396 20405 11396 20406 11407 20406 11408 20406 11396 20407 11408 20407 11397 20407 11397 20408 11408 20408 11409 20408 11397 20409 11409 20409 11398 20409 11398 20410 11409 20410 11410 20410 11398 20411 11410 20411 11399 20411 11399 20412 11410 20412 11411 20412 11399 20413 11411 20413 11400 20413 11400 20414 11411 20414 11412 20414 11400 20415 11412 20415 11401 20415 11401 20416 11412 20416 11413 20416 11401 20417 11413 20417 11402 20417 11402 20418 11413 20418 11414 20418 11402 20419 11414 20419 11403 20419 11403 20420 11414 20420 11415 20420 11403 20421 11415 20421 11404 20421 1273 20422 11295 20422 11362 20422 11362 20423 11295 20423 11304 20423 11362 20424 11304 20424 11405 20424 11405 20425 11304 20425 11303 20425 11405 20426 11303 20426 11406 20426 11406 20427 11303 20427 11302 20427 11406 20428 11302 20428 11407 20428 11407 20429 11302 20429 11297 20429 11407 20430 11297 20430 11408 20430 11408 20431 11297 20431 11296 20431 11408 20432 11296 20432 11409 20432 11409 20433 11296 20433 11305 20433 11409 20434 11305 20434 11410 20434 11410 20435 11305 20435 11301 20435 11410 20436 11301 20436 11411 20436 11411 20437 11301 20437 11300 20437 11411 20438 11300 20438 11412 20438 11412 20439 11300 20439 11299 20439 11412 20440 11299 20440 11413 20440 11413 20441 11299 20441 11298 20441 11413 20442 11298 20442 11414 20442 11414 20443 11298 20443 11294 20443 11414 20444 11294 20444 11415 20444 11415 20445 11294 20445 4277 20445 11415 20446 4277 20446 11404 20446 11404 20447 4277 20447 4280 20447 11404 20448 4280 20448 4270 20448 923 95 202 95 8321 95 8321 95 202 95 203 95 763 20449 121 20449 757 20449 757 20450 121 20450 11416 20450 757 20451 11416 20451 758 20451 763 20452 764 20452 121 20452 121 20453 764 20453 766 20453 121 95 766 95 120 95 238 95 900 95 236 95 236 95 900 95 742 95 236 20454 742 20454 744 20454 744 20455 748 20455 236 20455 236 20456 748 20456 747 20456 236 20457 747 20457 11417 20457 11417 20458 747 20458 753 20458 11417 20459 753 20459 752 20459 3733 20460 3734 20460 589 20460 3733 20461 589 20461 3729 20461 589 20462 590 20462 3729 20462 3729 20463 590 20463 592 20463 3729 20464 592 20464 3730 20464 3730 20465 592 20465 594 20465 3730 20466 594 20466 3731 20466 3731 20467 594 20467 595 20467 3731 20468 595 20468 3732 20468 6613 20469 1773 20469 6614 20469 6614 20470 1773 20470 1764 20470 6614 20471 1764 20471 6624 20471 6624 20472 1764 20472 1763 20472 6624 20473 1763 20473 4327 20473 6613 20474 1781 20474 1780 20474 1779 20475 1778 20475 1780 20475 1780 20476 1778 20476 1767 20476 1780 20477 1767 20477 6613 20477 6613 20478 1767 20478 1770 20478 6613 20479 1770 20479 1773 20479 3728 20480 3727 20480 3732 20480 3732 20481 595 20481 3728 20481 3728 20482 595 20482 597 20482 3728 20483 597 20483 3726 20483 3726 20484 597 20484 599 20484 2715 20485 4322 20485 2716 20485 2716 20486 4322 20486 4327 20486 2716 20487 4327 20487 1765 20487 1765 20488 4327 20488 1763 20488 2715 20489 2719 20489 4322 20489 4322 20490 2719 20490 817 20490 4322 20491 817 20491 4323 20491 4323 20492 817 20492 819 20492 4323 20493 819 20493 11418 20493 11418 20494 819 20494 11419 20494 4344 20495 4342 20495 11420 20495 11420 20496 11421 20496 4344 20496 4344 20497 11421 20497 11422 20497 4344 20498 11422 20498 4337 20498 11422 20499 11423 20499 4337 20499 4337 20500 11423 20500 11424 20500 4337 20501 11424 20501 4338 20501 4338 20502 11424 20502 11425 20502 4338 20503 11425 20503 11419 20503 11419 20504 11425 20504 11426 20504 11419 20505 11426 20505 11418 20505 11427 20506 4336 20506 4335 20506 11427 20507 4335 20507 11419 20507 11419 20508 4335 20508 4339 20508 11419 20509 4339 20509 4338 20509 11427 20510 810 20510 4336 20510 4336 20511 810 20511 815 20511 4336 20512 815 20512 4332 20512 815 20513 814 20513 4332 20513 4332 20514 814 20514 2767 20514 4332 20515 2767 20515 4330 20515 4330 20516 2767 20516 2768 20516 4330 20517 2768 20517 4328 20517 4328 20518 2768 20518 4317 20518 819 20519 820 20519 11419 20519 11419 20520 820 20520 821 20520 11419 20521 821 20521 11427 20521 11427 20522 821 20522 808 20522 11427 20523 808 20523 810 20523 4341 20524 7238 20524 4342 20524 4342 20525 7238 20525 7237 20525 4342 20526 7237 20526 11420 20526 795 20527 801 20527 7296 20527 7296 20528 801 20528 800 20528 7296 20529 800 20529 798 20529 798 20530 797 20530 7296 20530 7296 20531 797 20531 804 20531 7296 20532 804 20532 604 20532 795 20533 7296 20533 11307 20533 11307 20534 7296 20534 7301 20534 11307 20535 7301 20535 11306 20535 4513 20536 4512 20536 5494 20536 5494 20537 4512 20537 11428 20537 5494 20538 11428 20538 5496 20538 5496 20539 11428 20539 5497 20539 11429 20540 5375 20540 11430 20540 5427 20541 5425 20541 11429 20541 11429 20542 5425 20542 5376 20542 11429 20543 5376 20543 5375 20543 5433 20544 11429 20544 5436 20544 5436 20545 11429 20545 11430 20545 5436 20546 11430 20546 11431 20546 5433 20547 5431 20547 11429 20547 11429 20548 5431 20548 5429 20548 11429 20549 5429 20549 5427 20549 11431 20550 11432 20550 11433 20550 11433 20551 11432 20551 11434 20551 11433 20552 11434 20552 11435 20552 11436 20553 11437 20553 11430 20553 11430 20554 11437 20554 11438 20554 11430 20555 11438 20555 11431 20555 11431 20556 11438 20556 11439 20556 11431 20557 11439 20557 11432 20557 5375 20558 5497 20558 11430 20558 11430 20559 5497 20559 11428 20559 11430 20560 11428 20560 11436 20560 11436 20561 11428 20561 4512 20561 11436 20562 4512 20562 4511 20562 11435 20563 5312 20563 5311 20563 5371 20564 11440 20564 11441 20564 4638 20565 5371 20565 4636 20565 4636 20566 5371 20566 11441 20566 4636 20567 11441 20567 4634 20567 11442 20568 4640 20568 4639 20568 4640 20569 5318 20569 5317 20569 4640 20570 5317 20570 4641 20570 4641 20571 5317 20571 5316 20571 4641 20572 5316 20572 4599 20572 11435 20573 5311 20573 11433 20573 5318 20574 4640 20574 5309 20574 5309 20575 4640 20575 11442 20575 5309 20576 11442 20576 5310 20576 5310 20577 11442 20577 11443 20577 5310 20578 11443 20578 5315 20578 5315 20579 11443 20579 11444 20579 5315 20580 11444 20580 5314 20580 5314 20581 11444 20581 11445 20581 5314 20582 11445 20582 5311 20582 5311 20583 11445 20583 11446 20583 5311 20584 11446 20584 11433 20584 11440 20585 5371 20585 11447 20585 11447 20586 5371 20586 5435 20586 11447 20587 5435 20587 11448 20587 11448 20588 5435 20588 5437 20588 11448 20589 5437 20589 11449 20589 11449 20590 5437 20590 5436 20590 11449 20591 5436 20591 11431 20591 4639 20592 4634 20592 11442 20592 11442 20593 4634 20593 11441 20593 11442 20594 11441 20594 11443 20594 11443 20595 11441 20595 11440 20595 11443 20596 11440 20596 11444 20596 11444 20597 11440 20597 11447 20597 11444 20598 11447 20598 11445 20598 11445 20599 11447 20599 11448 20599 11445 20600 11448 20600 11446 20600 11446 20601 11448 20601 11449 20601 11446 20602 11449 20602 11433 20602 11433 20603 11449 20603 11431 20603 4604 20604 4603 20604 5556 20604 4637 18231 4635 18231 5473 18231 5473 20605 4635 20605 11450 20605 5473 20606 11450 20606 5472 20606 11451 20607 5476 20607 11450 20607 11450 20608 5476 20608 5475 20608 11450 20609 5475 20609 5472 20609 5480 20610 5477 20610 11452 20610 11452 20611 5477 20611 5478 20611 11452 20612 5478 20612 11451 20612 11451 20613 5478 20613 5474 20613 11451 20614 5474 20614 5476 20614 5479 20615 5480 20615 122 20615 122 20616 5480 20616 11452 20616 122 20617 11452 20617 121 20617 121 20618 11452 20618 11416 20618 758 20619 11416 20619 760 20619 760 20620 11416 20620 11452 20620 760 20621 11452 20621 767 20621 767 20622 11452 20622 11451 20622 767 20623 11451 20623 768 20623 768 20624 11451 20624 11450 20624 768 20625 11450 20625 5556 20625 5556 20626 11450 20626 4635 20626 5556 20627 4635 20627 4604 20627 5239 20628 5238 20628 11453 20628 11454 20629 11455 20629 11453 20629 11453 20630 11455 20630 11456 20630 11453 20631 11456 20631 5239 20631 5239 20632 11456 20632 11457 20632 5239 20633 11457 20633 5261 20633 5261 20634 11457 20634 11458 20634 5261 20635 11458 20635 5265 20635 11458 20636 11459 20636 5265 20636 5265 20637 11459 20637 11460 20637 5265 20638 11460 20638 5246 20638 4624 20639 4623 20639 11461 20639 11461 20640 4623 20640 5246 20640 11461 20641 5246 20641 11462 20641 11462 20642 5246 20642 11460 20642 756 20643 1441 20643 11463 20643 4681 20644 4683 20644 5558 20644 5558 20645 4683 20645 11463 20645 1437 20646 5562 20646 1441 20646 1441 20647 5562 20647 5561 20647 1441 20648 5561 20648 11463 20648 11463 20649 5561 20649 5559 20649 11463 20650 5559 20650 5558 20650 4683 20651 4625 20651 11463 20651 11463 20652 4625 20652 11464 20652 11463 20653 11464 20653 756 20653 756 20654 11464 20654 754 20654 11465 20655 11466 20655 11467 20655 5338 20656 5336 20656 5343 20656 5340 20657 5338 20657 5334 20657 5334 20658 5338 20658 11468 20658 5334 20659 11468 20659 5333 20659 4521 20660 5445 20660 11469 20660 11469 20661 5445 20661 5444 20661 5444 20662 5442 20662 11469 20662 11469 20663 5442 20663 5441 20663 11469 20664 5441 20664 5333 20664 4521 20665 11469 20665 4523 20665 4523 20666 11469 20666 11470 20666 4523 20667 11470 20667 4524 20667 11467 20668 11471 20668 11472 20668 5338 20669 5343 20669 11468 20669 11468 20670 5343 20670 11465 20670 11468 20671 11465 20671 5333 20671 5333 20672 11465 20672 11467 20672 5333 20673 11467 20673 11469 20673 11469 20674 11467 20674 11472 20674 11469 20675 11472 20675 11470 20675 11471 20676 11467 20676 11473 20676 11473 20677 11467 20677 11466 20677 11473 20678 11466 20678 11474 20678 11474 20679 11466 20679 11475 20679 11474 20680 11475 20680 11476 20680 11476 20681 11475 20681 11477 20681 11478 20682 4629 20682 11479 20682 11479 20683 4629 20683 4628 20683 11479 20684 4628 20684 4617 20684 4632 20685 4633 20685 11480 20685 5320 20686 5319 20686 11481 20686 11481 20687 5319 20687 5347 20687 11481 20688 5347 20688 4630 20688 11454 20689 11476 20689 11455 20689 11455 20690 11476 20690 11477 20690 11455 20691 11477 20691 11456 20691 11456 20692 11477 20692 11482 20692 11456 20693 11482 20693 11457 20693 11457 20694 11482 20694 11483 20694 11457 20695 11483 20695 11458 20695 11458 20696 11483 20696 11484 20696 11458 20697 11484 20697 11459 20697 11459 20698 11484 20698 11478 20698 11459 20699 11478 20699 11460 20699 11460 20700 11478 20700 11479 20700 11460 20701 11479 20701 11462 20701 11462 20702 11479 20702 4617 20702 11462 20703 4617 20703 11461 20703 11461 20704 4617 20704 4624 20704 11465 20705 5343 20705 5344 20705 11465 20706 5344 20706 11485 20706 11485 20707 5344 20707 5345 20707 11485 20708 5345 20708 5320 20708 11486 20709 11481 20709 11487 20709 11487 20710 11481 20710 4630 20710 11487 20711 4630 20711 4632 20711 11486 20712 11488 20712 11489 20712 5320 20713 11481 20713 11485 20713 11485 20714 11481 20714 11486 20714 11485 20715 11486 20715 11465 20715 11465 20716 11486 20716 11489 20716 11465 20717 11489 20717 11466 20717 4632 20718 11480 20718 11487 20718 11487 20719 11480 20719 11490 20719 11487 20720 11490 20720 11486 20720 11486 20721 11490 20721 11491 20721 11486 20722 11491 20722 11488 20722 11475 20723 11466 20723 11477 20723 11477 20724 11466 20724 11489 20724 11477 20725 11489 20725 11482 20725 11482 20726 11489 20726 11488 20726 11482 20727 11488 20727 11483 20727 11483 20728 11488 20728 11491 20728 11483 20729 11491 20729 11484 20729 11484 20730 11491 20730 11490 20730 11484 20731 11490 20731 11478 20731 11478 20732 11490 20732 11480 20732 11478 20733 11480 20733 4629 20733 4629 20734 11480 20734 4633 20734 11492 20735 11417 20735 752 20735 236 20736 11417 20736 234 20736 234 20737 11417 20737 11492 20737 234 20738 11492 20738 5465 20738 5467 20739 5463 20739 11492 20739 11492 20740 5463 20740 5464 20740 11492 20741 5464 20741 5465 20741 4626 20742 4627 20742 11493 20742 11493 20743 4627 20743 4631 20743 11493 20744 4631 20744 5470 20744 5470 20745 5471 20745 11493 20745 11493 20746 5471 20746 5469 20746 11493 20747 5469 20747 11494 20747 11494 20748 5469 20748 5468 20748 11494 20749 5468 20749 5466 20749 752 20750 750 20750 11492 20750 11492 20751 750 20751 11494 20751 11492 20752 11494 20752 5467 20752 5467 20753 11494 20753 5466 20753 4625 20754 4626 20754 11464 20754 11464 20755 4626 20755 11493 20755 11464 20756 11493 20756 754 20756 754 20757 11493 20757 11494 20757 754 20758 11494 20758 749 20758 749 20759 11494 20759 750 20759 10395 20760 11270 20760 10414 20760 10414 20761 11270 20761 11495 20761 10414 20762 11495 20762 10416 20762 10416 20763 11495 20763 10417 20763 10523 20764 10521 20764 10525 20764 10525 20765 10521 20765 10532 20765 10525 20766 10532 20766 10527 20766 10527 20767 10532 20767 10529 20767 11496 20768 10590 20768 10429 20768 10429 20769 10590 20769 10532 20769 10429 20770 10532 20770 10498 20770 10498 20771 10532 20771 10521 20771 10577 20772 10576 20772 11497 20772 11497 20773 10576 20773 10590 20773 11497 20774 10590 20774 11498 20774 11498 20775 10590 20775 11496 20775 11498 20776 11496 20776 11499 20776 11499 20777 11496 20777 11500 20777 10429 20778 10417 20778 11496 20778 11496 20779 10417 20779 11495 20779 11496 20780 11495 20780 11500 20780 11500 20781 11495 20781 11270 20781 11500 20782 11270 20782 11269 20782 11501 20783 11502 20783 11503 20783 10535 20784 10534 20784 11504 20784 10673 20785 10672 20785 11258 20785 10677 20786 10678 20786 11505 20786 10672 20787 10675 20787 11258 20787 11258 20788 10675 20788 11506 20788 11258 20789 11506 20789 11259 20789 11262 20790 11507 20790 11261 20790 11261 15565 11507 15565 11508 15565 11261 15537 11508 15537 10464 15537 10464 15538 11508 15538 11504 15538 10464 20791 11504 20791 10553 20791 10553 20792 11504 20792 10534 20792 10676 20793 10677 20793 11509 20793 11509 20794 10677 20794 11505 20794 11509 20795 11505 20795 11510 20795 11510 20796 11505 20796 11511 20796 11509 20797 11512 20797 10676 20797 10676 20798 11512 20798 11513 20798 10676 20799 11513 20799 10675 20799 10675 20800 11513 20800 11514 20800 10675 20801 11514 20801 11506 20801 11506 20802 11514 20802 11260 20802 11506 20803 11260 20803 11259 20803 11502 20804 10550 20804 10551 20804 11503 20805 11502 20805 11515 20805 11515 20806 11502 20806 10551 20806 11515 20807 10551 20807 10552 20807 11507 20808 11516 20808 11508 20808 11508 20809 11516 20809 11503 20809 11508 20810 11503 20810 11504 20810 11504 15557 11503 15557 11515 15557 11504 20811 11515 20811 10535 20811 10535 15555 11515 15555 10552 15555 11516 20812 11517 20812 11503 20812 11503 20813 11517 20813 11518 20813 11503 20814 11518 20814 11501 20814 11501 20815 11518 20815 11519 20815 11501 20816 11519 20816 11520 20816 11511 20817 11520 20817 11510 20817 11510 20818 11520 20818 11519 20818 11510 15572 11519 15572 11509 15572 11509 20819 11519 20819 11518 20819 11509 20820 11518 20820 11512 20820 11512 20821 11518 20821 11517 20821 11512 20822 11517 20822 11513 20822 11513 20823 11517 20823 11516 20823 11513 20824 11516 20824 11514 20824 11514 20825 11516 20825 11507 20825 11514 20826 11507 20826 11260 20826 11260 20827 11507 20827 11262 20827 10547 20828 10545 20828 10543 20828 11501 20829 11521 20829 11502 20829 11502 20830 11521 20830 10547 20830 11502 20831 10547 20831 10550 20831 10550 20832 10547 20832 10543 20832 10541 20833 10547 20833 10471 20833 10471 20834 10547 20834 11521 20834 10471 20835 11521 20835 10473 20835 10473 20836 11521 20836 11522 20836 11266 20837 10391 20837 10467 20837 10467 20838 10466 20838 11522 20838 10466 20839 10476 20839 11522 20839 11522 20840 10476 20840 10475 20840 11522 20841 10475 20841 10473 20841 10467 20842 11522 20842 11266 20842 11266 20843 11522 20843 11523 20843 11266 20844 11523 20844 11267 20844 11520 20845 11511 20845 11524 20845 11520 20846 11524 20846 11501 20846 11501 20847 11524 20847 11525 20847 11501 20848 11525 20848 11521 20848 11521 20849 11525 20849 11526 20849 11521 20850 11526 20850 11522 20850 11522 20851 11526 20851 11527 20851 11522 20852 11527 20852 11523 20852 8438 20853 8422 20853 9286 20853 8440 20854 11528 20854 8441 20854 8441 20855 11528 20855 8444 20855 8444 20856 11528 20856 8454 20856 8454 20857 11528 20857 11529 20857 8454 20858 11529 20858 8522 20858 8549 20859 8547 20859 8545 20859 8522 20860 11529 20860 8545 20860 8545 20861 11529 20861 11530 20861 8545 20862 11530 20862 8549 20862 8551 20863 8549 20863 8553 20863 8553 20864 8549 20864 11530 20864 8553 20865 11530 20865 8556 20865 8556 20866 11530 20866 11529 20866 8556 20867 11529 20867 8648 20867 8648 20868 11529 20868 11531 20868 8648 20869 11531 20869 8635 20869 8635 20870 11531 20870 11532 20870 8635 20871 11532 20871 8636 20871 9285 20872 11528 20872 9286 20872 9286 20873 11528 20873 8440 20873 9286 20874 8440 20874 8438 20874 9285 20875 11533 20875 11528 20875 11528 20876 11533 20876 11534 20876 11528 20877 11534 20877 11529 20877 11529 20878 11534 20878 11535 20878 11529 20879 11535 20879 11531 20879 1279 95 11285 95 1272 95 11288 20880 11285 20880 11391 20880 11391 20881 11285 20881 1279 20881 11391 20882 1279 20882 1278 20882 11389 20883 11289 20883 11393 20883 11393 20884 11289 20884 11288 20884 11393 20885 11288 20885 11392 20885 11392 20886 11288 20886 11391 20886 11389 20887 11387 20887 11289 20887 11289 20888 11387 20888 11386 20888 11289 20889 11386 20889 11290 20889 11381 20890 11293 20890 11383 20890 11383 20891 11293 20891 11290 20891 11383 20892 11290 20892 11385 20892 11385 20893 11290 20893 11386 20893 11381 20894 11379 20894 11293 20894 11293 20895 11379 20895 11378 20895 11293 20896 11378 20896 11292 20896 11373 20897 11291 20897 11375 20897 11375 20898 11291 20898 11292 20898 11375 20899 11292 20899 11376 20899 11376 20900 11292 20900 11378 20900 11373 20901 11371 20901 11291 20901 11291 20902 11371 20902 11370 20902 11291 20903 11370 20903 11286 20903 11370 20904 11368 20904 11286 20904 11286 20905 11368 20905 11367 20905 11286 20906 11367 20906 11287 20906 4268 20907 4267 20907 11361 20907 11361 20908 4267 20908 11287 20908 11361 20909 11287 20909 11366 20909 11366 20910 11287 20910 11367 20910 11306 20911 7301 20911 625 20911 625 20912 7301 20912 615 20912 9285 20913 9284 20913 11536 20913 11536 20914 8623 20914 8638 20914 8638 20915 8636 20915 11536 20915 11536 20916 8636 20916 11532 20916 11536 20917 11532 20917 11531 20917 11533 20918 9285 20918 11534 20918 11534 20919 9285 20919 11536 20919 11534 20920 11536 20920 11535 20920 11535 20921 11536 20921 11531 20921 8672 20922 8674 20922 11537 20922 8670 20923 8657 20923 11537 20923 11537 20924 8657 20924 8656 20924 11537 20925 8656 20925 8672 20925 8670 20926 11537 20926 8671 20926 8671 20927 11537 20927 11536 20927 8671 20928 11536 20928 8684 20928 8674 20929 8653 20929 11537 20929 11537 20930 8653 20930 8652 20930 11537 20931 8652 20931 11536 20931 11536 20932 8652 20932 8624 20932 11536 20933 8624 20933 8623 20933 11357 20934 11358 20934 9287 20934 11538 20935 11344 20935 11355 20935 11355 20936 11353 20936 11538 20936 11538 20937 11353 20937 11352 20937 11538 20938 11352 20938 11356 20938 11359 20939 11328 20939 9288 20939 9288 20940 11328 20940 11330 20940 9288 20941 11330 20941 9287 20941 9287 20942 11330 20942 11538 20942 9287 20943 11538 20943 11357 20943 11357 20944 11538 20944 11356 20944 11330 20945 11331 20945 11538 20945 11538 20946 11331 20946 11312 20946 11538 20947 11312 20947 11344 20947 11344 20948 11312 20948 11311 20948 11344 20949 11311 20949 11345 20949 9283 20950 7331 20950 7329 20950 7329 20951 9282 20951 11345 20951 11345 20952 11311 20952 7329 20952 7329 20953 11311 20953 8684 20953 7329 20954 8684 20954 9283 20954 9283 20955 8684 20955 11536 20955 9283 20956 11536 20956 9284 20956 11316 20957 11315 20957 11314 20957 11314 20958 11315 20958 9271 20958 8682 20959 8685 20959 8683 20959 8683 20960 8685 20960 8684 20960 8683 20961 8684 20961 9271 20961 9271 20962 8684 20962 11311 20962 9271 20963 11311 20963 11314 20963 11539 20964 11540 20964 11541 20964 11541 20965 11540 20965 11542 20965 11541 20966 11542 20966 11543 20966 11544 20967 11545 20967 11542 20967 11542 20968 11540 20968 11544 20968 11544 20969 11540 20969 11539 20969 11544 20970 11539 20970 11546 20970 11546 20971 11539 20971 11547 20971 11546 20972 11547 20972 11548 20972 11545 20973 11549 20973 11550 20973 11542 20974 11551 20974 11552 20974 11421 20975 11552 20975 11550 20975 11550 20976 11552 20976 11551 20976 11550 20977 11551 20977 11545 20977 11542 20978 11545 20978 11551 20978 11549 20979 11423 20979 11550 20979 11550 20980 11423 20980 11422 20980 11550 20981 11422 20981 11421 20981 11423 20982 11549 20982 11424 20982 11425 20983 11424 20983 11426 20983 11426 20984 11424 20984 11549 20984 11426 20985 11549 20985 11418 20985 11418 20986 11549 20986 11545 20986 11420 20987 7237 20987 11553 20987 11552 20988 11421 20988 11420 20988 11420 20989 11553 20989 11552 20989 11552 20990 11553 20990 11543 20990 11552 20991 11543 20991 11542 20991 11545 20992 11544 20992 11418 20992 11418 20993 11544 20993 11546 20993 11418 20994 11546 20994 4323 20994 4323 20995 11546 20995 11548 20995 4323 20996 11548 20996 4324 20996 7236 632 4324 632 11548 632 7236 632 11541 632 7237 632 7237 632 11541 632 11543 632 7237 632 11543 632 11553 632 11548 632 11547 632 7236 632 7236 632 11547 632 11539 632 7236 632 11539 632 11541 632 5248 20997 5252 20997 11554 20997 11554 20998 11453 20998 5238 20998 5238 20999 5271 20999 11554 20999 11554 21000 5271 21000 5249 21000 11554 21001 5249 21001 5248 21001 5252 21002 5251 21002 11554 21002 11554 21003 5251 21003 5260 21003 11554 21004 5260 21004 5259 21004 5259 21005 5258 21005 11554 21005 11554 21006 5258 21006 5257 21006 11554 21007 5257 21007 5272 21007 11555 21008 11476 21008 11554 21008 11554 21009 11476 21009 11454 21009 11554 21010 11454 21010 11453 21010 11555 21011 4517 21011 4524 21011 4524 21012 11470 21012 11555 21012 11555 21013 11470 21013 11472 21013 11555 21014 11472 21014 11471 21014 11471 21015 11473 21015 11555 21015 11555 21016 11473 21016 11474 21016 11555 21017 11474 21017 11476 21017 4553 21018 4515 21018 5272 21018 11556 21019 4509 21019 4507 21019 4517 21020 11555 21020 4515 21020 4515 21021 11555 21021 11554 21021 4515 21022 11554 21022 5272 21022 4553 21023 5272 21023 4528 21023 4528 21024 5272 21024 5280 21024 4528 21025 5280 21025 4507 21025 4507 21026 5280 21026 11557 21026 4507 21027 11557 21027 11556 21027 5275 21028 5278 21028 4607 21028 4607 21029 5278 21029 5280 21029 4607 21030 5280 21030 4608 21030 4608 21031 5280 21031 5272 21031 4608 21032 5272 21032 5274 21032 5274 21033 5272 21033 5273 21033 4511 21034 4509 21034 11556 21034 11436 21035 4511 21035 11437 21035 11437 21036 4511 21036 11556 21036 11437 21037 11556 21037 11438 21037 11438 21038 11556 21038 11439 21038 11557 21039 5313 21039 5312 21039 5312 21040 11435 21040 11557 21040 11557 21041 11435 21041 11434 21041 11557 21042 11434 21042 11556 21042 11556 21043 11434 21043 11432 21043 11556 21044 11432 21044 11439 21044 5292 21045 5290 21045 11558 21045 11558 21046 5290 21046 5297 21046 11558 21047 5297 21047 5296 21047 11558 21048 5282 21048 5287 21048 5287 21049 5295 21049 11558 21049 11558 21050 5295 21050 5294 21050 11558 21051 5294 21051 5292 21051 5296 21052 5313 21052 11558 21052 11558 21053 5313 21053 11557 21053 11558 21054 11557 21054 5282 21054 5282 21055 11557 21055 5280 21055 11269 21056 11268 21056 11559 21056 10586 21057 10577 21057 11559 21057 11559 21058 10577 21058 11497 21058 11500 21059 11269 21059 11499 21059 11499 21060 11269 21060 11559 21060 11499 21061 11559 21061 11498 21061 11498 21062 11559 21062 11497 21062 10620 21063 11560 21063 10614 21063 10614 21064 11560 21064 10616 21064 10611 21065 10619 21065 11560 21065 11560 21066 10619 21066 10618 21066 11560 21067 10618 21067 10616 21067 10611 21068 11560 21068 10609 21068 10609 21069 11560 21069 11559 21069 10609 21070 11559 21070 10635 21070 10620 21071 10596 21071 11560 21071 11560 21072 10596 21072 10598 21072 11560 21073 10598 21073 11559 21073 11559 21074 10598 21074 10585 21074 11559 21075 10585 21075 10586 21075 11561 21076 11505 21076 10678 21076 11561 21077 10678 21077 10637 21077 10637 21078 11562 21078 10638 21078 10638 21079 11562 21079 10663 21079 10638 21080 10663 21080 10665 21080 10648 21081 10663 21081 10651 21081 10651 21082 10663 21082 11562 21082 10651 21083 11562 21083 10652 21083 10652 21084 11562 21084 10637 21084 10652 21085 10637 21085 10674 21085 10674 21086 10637 21086 10678 21086 11526 21087 11525 21087 11561 21087 11561 21088 11265 21088 11267 21088 11267 21089 11523 21089 11561 21089 11561 21090 11523 21090 11527 21090 11561 21091 11527 21091 11526 21091 11525 21092 11524 21092 11561 21092 11561 21093 11524 21093 11511 21093 11561 21094 11511 21094 11505 21094 11264 21095 9309 21095 9307 21095 11265 21096 11561 21096 11263 21096 11263 21097 11561 21097 10637 21097 11263 21098 10637 21098 9307 21098 9307 21099 10637 21099 10635 21099 9307 21100 10635 21100 11264 21100 11264 21101 10635 21101 11559 21101 11264 21102 11559 21102 11268 21102 10632 21103 10634 21103 10633 21103 10633 21104 10634 21104 10635 21104 10633 21105 10635 21105 10640 21105 10640 21106 10635 21106 10637 21106 10640 21107 10637 21107 10642 21107 10642 21108 10637 21108 10636 21108 362 21109 1213 21109 329 21109 329 21110 1213 21110 1215 21110 329 21111 1215 21111 331 21111 1210 21112 1209 21112 362 21112 362 21113 1209 21113 1211 21113 362 21114 1211 21114 1213 21114 362 21115 356 21115 1210 21115 1210 21116 356 21116 339 21116 1210 21117 339 21117 295 21117 4136 21118 4138 21118 11563 21118 11563 21119 4138 21119 11564 21119 11563 21120 11564 21120 262 21120 262 21121 11564 21121 261 21121 261 21122 11564 21122 11565 21122 261 21123 11565 21123 259 21123 259 21124 11565 21124 263 21124 263 21125 11565 21125 11566 21125 263 21126 11566 21126 264 21126 264 21127 11566 21127 11567 21127 264 21128 11567 21128 265 21128 1751 21129 11568 21129 1752 21129 1752 21130 11568 21130 11569 21130 1752 21131 11569 21131 1753 21131 1753 21132 11569 21132 11570 21132 1753 21133 11570 21133 1754 21133 1754 21134 11570 21134 11571 21134 1754 21135 11571 21135 1755 21135 1755 21136 11571 21136 4137 21136 11568 21137 11567 21137 11569 21137 11569 21138 11567 21138 11566 21138 11569 21139 11566 21139 11570 21139 11570 21140 11566 21140 11565 21140 11570 21141 11565 21141 11571 21141 11571 21142 11565 21142 11564 21142 11571 21143 11564 21143 4137 21143 4137 21144 11564 21144 4138 21144 265 21145 11567 21145 255 21145 255 21146 11567 21146 11568 21146 255 21147 11568 21147 253 21147 253 21148 11568 21148 1751 21148 253 21149 1751 21149 251 21149 220 633 219 633 175 633 175 633 219 633 176 633 165 633 164 633 193 633 193 633 164 633 194 633 138 633 137 633 79 633 79 633 137 633 81 633 94 633 93 633 105 633 105 633 93 633 106 633 76 21150 75 21150 73 21150 73 21151 75 21151 50 21151 73 21152 50 21152 74 21152 74 21153 50 21153 49 21153 357 21154 16 21154 358 21154 4134 21155 260 21155 8187 21155 4134 21156 8187 21156 4132 21156 4132 21157 8187 21157 8186 21157 4132 21158 8186 21158 4133 21158 6666 21159 4135 21159 8184 21159 8184 21160 4135 21160 4133 21160 8184 21161 4133 21161 8185 21161 8185 21162 4133 21162 8186 21162 262 21163 260 21163 11563 21163 11563 21164 260 21164 4134 21164 11563 21165 4134 21165 4136 21165 11572 21166 11573 21166 11574 21166 11574 21167 11573 21167 11575 21167 11573 106 11576 106 11575 106 11575 106 11576 106 11577 106 11578 633 11579 633 11577 633 11577 21168 11579 21168 11580 21168 11577 633 11580 633 11575 633 11575 633 11580 633 11574 633 11581 21169 11580 21169 11582 21169 11582 21169 11580 21169 11579 21169 11582 21170 11579 21170 11583 21170 11583 21171 11579 21171 11578 21171 11583 21172 11578 21172 11576 21172 11576 21173 11578 21173 11577 21173 11573 7585 11572 7585 11576 7585 11576 7585 11572 7585 11581 7585 11576 7585 11581 7585 11583 7585 11583 21174 11581 21174 11582 21174 11580 98 11581 98 11574 98 11574 98 11581 98 11572 98 11584 21175 11585 21175 11586 21175 11586 21176 11585 21176 11587 21176 11586 21177 11587 21177 11588 21177 11588 21178 11589 21178 11590 21178 11588 21178 11590 21178 11586 21178 11586 21179 11590 21179 11591 21179 11586 21180 11591 21180 11584 21180 11585 21181 11592 21181 11587 21181 11587 21181 11592 21181 11593 21181 11587 21182 11593 21182 11588 21182 11588 21183 11593 21183 11589 21183 11592 95 11591 95 11593 95 11593 95 11591 95 11590 95 11593 95 11590 95 11589 95 11591 21184 11592 21184 11584 21184 11584 21184 11592 21184 11585 21184 11594 21185 11595 21185 11596 21185 11596 21186 11595 21186 11597 21186 11596 21187 11597 21187 11598 21187 11595 21188 11599 21188 11600 21188 11595 21189 11600 21189 11597 21189 11597 21190 11600 21190 11601 21190 11597 21190 11601 21190 11598 21190 11598 21191 11601 21191 11596 21191 11596 21192 11601 21192 11602 21192 11596 21193 11602 21193 11594 21193 11594 21193 11602 21193 11603 21193 11599 95 11603 95 11600 95 11600 95 11603 95 11602 95 11600 95 11602 95 11601 95 11603 21194 11599 21194 11594 21194 11594 21194 11599 21194 11595 21194 11604 632 11605 632 11606 632 11607 7585 11608 7585 11606 7585 11606 7585 11608 7585 11604 7585 11605 98 11609 98 11606 98 11606 98 11609 98 11607 98 11609 21195 11605 21195 11608 21195 11608 21196 11605 21196 11604 21196 11607 95 11609 95 11608 95 11610 7585 11611 7585 11612 7585 11612 7585 11611 7585 11613 7585 11613 632 11614 632 11612 632 11615 98 11610 98 11614 98 11614 98 11610 98 11612 98 11615 21197 11614 21197 11611 21197 11611 21198 11614 21198 11613 21198 11611 95 11610 95 11615 95 11616 7585 11617 7585 11618 7585 11618 7585 11617 7585 11619 7585 11619 95 11617 95 11620 95 11621 95 11622 95 11623 95 11623 95 11622 95 11619 95 11623 95 11619 95 11624 95 11624 95 11619 95 11620 95 11617 21199 11616 21199 11620 21199 11620 21200 11616 21200 11625 21200 11620 21201 11625 21201 11624 21201 11624 21202 11625 21202 11626 21202 11624 21203 11626 21203 11623 21203 11623 21204 11626 21204 11627 21204 11623 21205 11627 21205 11621 21205 11621 21206 11627 21206 11628 21206 11621 21207 11628 21207 11622 21207 11622 21208 11628 21208 11629 21208 11622 21209 11629 21209 11619 21209 11619 21210 11629 21210 11618 21210 11616 21211 11618 21211 11629 21211 11626 21212 11625 21212 11627 21212 11627 21213 11625 21213 11616 21213 11627 21214 11616 21214 11628 21214 11628 21215 11616 21215 11629 21215 11630 632 11631 632 11632 632 11632 7585 11631 7585 11633 7585 11633 7585 11631 7585 11634 7585 11635 106 11630 106 11633 106 11633 106 11630 106 11632 106 11634 21216 11631 21216 11635 21216 11635 21217 11631 21217 11630 21217 11634 95 11635 95 11633 95 11636 21218 11637 21218 11638 21218 11636 21219 11638 21219 11639 21219 11639 21220 11638 21220 11640 21220 11639 21221 11640 21221 11641 21221 11641 21222 11640 21222 11642 21222 11641 21223 11642 21223 11643 21223 11643 21224 11642 21224 11644 21224 11643 21225 11644 21225 11645 21225 11645 21226 11644 21226 11646 21226 11645 21227 11646 21227 11647 21227 11647 21228 11646 21228 11648 21228 11647 21229 11648 21229 11649 21229 11649 21230 11648 21230 11650 21230 11649 21231 11650 21231 11651 21231 11651 21232 11650 21232 11652 21232 11651 21233 11652 21233 11653 21233 11653 21234 11652 21234 11654 21234 11653 21235 11654 21235 11655 21235 11655 21236 11654 21236 11656 21236 11655 21237 11656 21237 11657 21237 11657 21238 11656 21238 11658 21238 11657 21239 11658 21239 11659 21239 11659 21240 11658 21240 11637 21240 11659 21241 11637 21241 11636 21241 11648 21242 11660 21242 11650 21242 11650 21243 11660 21243 11661 21243 11650 21244 11661 21244 11652 21244 11652 21245 11661 21245 11662 21245 11652 21246 11662 21246 11654 21246 11654 21247 11662 21247 11663 21247 11654 21248 11663 21248 11656 21248 11656 21249 11663 21249 11664 21249 11656 21250 11664 21250 11658 21250 11658 21251 11664 21251 11665 21251 11658 21251 11665 21251 11637 21251 11637 21252 11665 21252 11666 21252 11637 21252 11666 21252 11638 21252 11638 21253 11666 21253 11667 21253 11638 21254 11667 21254 11640 21254 11640 21255 11667 21255 11668 21255 11640 21256 11668 21256 11642 21256 11642 21257 11668 21257 11669 21257 11642 21258 11669 21258 11644 21258 11644 21259 11669 21259 11670 21259 11644 21260 11670 21260 11646 21260 11646 21261 11670 21261 11671 21261 11646 21261 11671 21261 11648 21261 11648 21242 11671 21242 11660 21242 11666 21262 11672 21262 11667 21262 11667 21263 11672 21263 11673 21263 11667 21264 11673 21264 11668 21264 11668 21265 11673 21265 11674 21265 11668 21266 11674 21266 11669 21266 11669 21267 11674 21267 11675 21267 11669 21268 11675 21268 11670 21268 11670 21269 11675 21269 11676 21269 11670 21270 11676 21270 11671 21270 11671 21271 11676 21271 11677 21271 11671 21272 11677 21272 11660 21272 11660 21273 11677 21273 11678 21273 11660 21274 11678 21274 11661 21274 11661 21265 11678 21265 11679 21265 11661 21275 11679 21275 11662 21275 11662 21276 11679 21276 11680 21276 11662 21277 11680 21277 11663 21277 11663 21265 11680 21265 11681 21265 11663 21278 11681 21278 11664 21278 11664 21279 11681 21279 11682 21279 11664 21280 11682 21280 11665 21280 11665 21267 11682 21267 11683 21267 11665 21272 11683 21272 11666 21272 11666 21281 11683 21281 11672 21281 11659 632 11684 632 11657 632 11657 632 11684 632 11685 632 11657 632 11685 632 11655 632 11655 632 11685 632 11686 632 11655 632 11686 632 11653 632 11653 632 11686 632 11687 632 11653 632 11687 632 11651 632 11651 632 11687 632 11688 632 11651 632 11688 632 11649 632 11649 632 11688 632 11689 632 11649 632 11689 632 11647 632 11647 632 11689 632 11690 632 11647 632 11690 632 11645 632 11645 632 11690 632 11691 632 11645 632 11691 632 11643 632 11643 632 11691 632 11692 632 11643 632 11692 632 11641 632 11641 632 11692 632 11693 632 11641 632 11693 632 11639 632 11639 632 11693 632 11694 632 11639 632 11694 632 11636 632 11636 632 11694 632 11695 632 11636 632 11695 632 11659 632 11659 632 11695 632 11684 632 11695 21282 11696 21282 11684 21282 11684 21283 11696 21283 11697 21283 11684 21284 11697 21284 11685 21284 11685 21284 11697 21284 11698 21284 11685 21285 11698 21285 11686 21285 11686 21286 11698 21286 11699 21286 11686 21287 11699 21287 11687 21287 11687 21288 11699 21288 11700 21288 11687 16714 11700 16714 11688 16714 11688 16714 11700 16714 11701 16714 11688 21289 11701 21289 11689 21289 11689 21290 11701 21290 11702 21290 11689 21291 11702 21291 11690 21291 11690 21292 11702 21292 11703 21292 11690 16728 11703 16728 11691 16728 11691 16728 11703 16728 11704 16728 11691 21293 11704 21293 11692 21293 11692 21294 11704 21294 11705 21294 11692 21295 11705 21295 11693 21295 11693 21296 11705 21296 11706 21296 11693 21297 11706 21297 11694 21297 11694 21297 11706 21297 11707 21297 11694 21298 11707 21298 11695 21298 11695 21299 11707 21299 11696 21299 11697 21300 11682 21300 11698 21300 11698 21301 11682 21301 11681 21301 11698 21302 11681 21302 11699 21302 11699 21303 11681 21303 11680 21303 11699 21304 11680 21304 11700 21304 11700 21305 11680 21305 11679 21305 11700 21306 11679 21306 11701 21306 11701 21307 11679 21307 11678 21307 11701 21308 11678 21308 11702 21308 11702 21309 11678 21309 11677 21309 11702 21310 11677 21310 11703 21310 11703 21311 11677 21311 11676 21311 11703 21312 11676 21312 11704 21312 11704 21313 11676 21313 11675 21313 11704 21314 11675 21314 11705 21314 11705 21315 11675 21315 11674 21315 11705 21316 11674 21316 11706 21316 11706 21317 11674 21317 11673 21317 11706 21318 11673 21318 11707 21318 11707 21319 11673 21319 11672 21319 11707 21320 11672 21320 11696 21320 11696 21321 11672 21321 11683 21321 11696 21322 11683 21322 11697 21322 11697 21323 11683 21323 11682 21323 11708 21324 11709 21324 11710 21324 11711 21325 11712 21325 11710 21325 11710 21326 11712 21326 11713 21326 11710 21327 11713 21327 11708 21327 11709 21328 11714 21328 11710 21328 11710 21329 11714 21329 11715 21329 11710 21330 11715 21330 11711 21330 11711 21331 11715 21331 11712 21331 11712 21332 11715 21332 11714 21332 11712 21333 11714 21333 11713 21333 11713 21334 11714 21334 11709 21334 11713 21335 11709 21335 11708 21335 11716 95 11717 95 11718 95 11718 95 11717 95 11719 95 11720 98 11721 98 11716 98 11716 98 11721 98 11722 98 11716 21336 11722 21336 11717 21336 11716 21337 11718 21337 11720 21337 11720 21338 11718 21338 11721 21338 11722 21339 11719 21339 11717 21339 11719 21340 11722 21340 11718 21340 11718 21341 11722 21341 11721 21341 11723 21342 11724 21342 11725 21342 11725 21343 11726 21343 11723 21343 11723 21344 11726 21344 11727 21344 11723 21345 11727 21345 11728 21345 11728 21346 11729 21346 11723 21346 11723 21347 11729 21347 11730 21347 11723 21348 11730 21348 11731 21348 11731 21349 11732 21349 11723 21349 11723 21350 11732 21350 11733 21350 11723 21351 11733 21351 11734 21351 11734 21352 11733 21352 11735 21352 11736 21353 11737 21353 11738 21353 11739 21354 11740 21354 11738 21354 11738 21355 11740 21355 11741 21355 11738 21356 11741 21356 11736 21356 11739 21357 11742 21357 11743 21357 11743 21358 11742 21358 11744 21358 11736 21359 11741 21359 11743 21359 11743 21360 11741 21360 11740 21360 11743 21361 11740 21361 11739 21361 11745 21362 11746 21362 11742 21362 11742 21363 11746 21363 11747 21363 11742 21364 11747 21364 11744 21364 11748 21365 11749 21365 11750 21365 11745 21366 11742 21366 11750 21366 11750 21367 11742 21367 11751 21367 11750 21368 11751 21368 11748 21368 11752 21369 11729 21369 11728 21369 11739 21370 11738 21370 11742 21370 11742 21371 11738 21371 11737 21371 11742 21372 11737 21372 11753 21372 11748 21373 11751 21373 11754 21373 11754 21374 11751 21374 11742 21374 11754 21375 11742 21375 11755 21375 11755 21376 11742 21376 11753 21376 11755 21377 11753 21377 11756 21377 11757 21378 11748 21378 11727 21378 11727 21379 11748 21379 11754 21379 11727 21380 11754 21380 11728 21380 11728 21381 11754 21381 11755 21381 11728 21382 11755 21382 11752 21382 11752 21383 11755 21383 11756 21383 11749 21384 11723 21384 11734 21384 11749 21385 11734 21385 11750 21385 11734 21386 11758 21386 11750 21386 11750 21387 11758 21387 11759 21387 11750 21388 11759 21388 11745 21388 11745 21389 11759 21389 11746 21389 11736 21390 11743 21390 11760 21390 11760 21391 11743 21391 11744 21391 11760 21392 11744 21392 11761 21392 11753 21393 11737 21393 11736 21393 11732 21394 11731 21394 11762 21394 11762 21395 11731 21395 11730 21395 11744 21396 11747 21396 11761 21396 11761 21397 11747 21397 11746 21397 11761 21398 11746 21398 11763 21398 11763 21399 11746 21399 11759 21399 11763 21400 11759 21400 11733 21400 11733 21401 11759 21401 11758 21401 11733 21402 11758 21402 11735 21402 11735 21403 11758 21403 11734 21403 11733 21404 11732 21404 11763 21404 11763 21405 11732 21405 11762 21405 11763 21406 11762 21406 11761 21406 11761 21407 11762 21407 11764 21407 11761 21408 11764 21408 11760 21408 11736 21409 11760 21409 11753 21409 11753 21410 11760 21410 11764 21410 11753 21411 11764 21411 11756 21411 11756 21412 11764 21412 11762 21412 11756 21413 11762 21413 11752 21413 11752 21414 11762 21414 11730 21414 11752 21415 11730 21415 11729 21415 11724 21416 11765 21416 11725 21416 11725 21417 11765 21417 11757 21417 11725 21418 11757 21418 11726 21418 11726 21419 11757 21419 11727 21419 11765 21420 11724 21420 11723 21420 11749 21421 11748 21421 11723 21421 11723 21422 11748 21422 11757 21422 11723 21423 11757 21423 11765 21423 11766 106 11767 106 11768 106 11768 106 11767 106 11769 106 11770 633 11767 633 11771 633 11771 633 11767 633 11766 633 11770 21424 11771 21424 11772 21424 11773 21425 11769 21425 11774 21425 11774 21426 11769 21426 11775 21426 11774 21427 11775 21427 11776 21427 11776 21428 11775 21428 11777 21428 11776 21429 11777 21429 11778 21429 11778 21430 11777 21430 11779 21430 11778 21431 11779 21431 11780 21431 11780 21432 11779 21432 11781 21432 11780 21433 11781 21433 11782 21433 11781 21434 11770 21434 11782 21434 11782 21435 11770 21435 11772 21435 11782 21436 11772 21436 11783 21436 11783 21436 11772 21436 11784 21436 11783 21437 11784 21437 11785 21437 11785 21437 11784 21437 11786 21437 11785 21438 11786 21438 11787 21438 11787 21438 11786 21438 11788 21438 11787 21439 11788 21439 11789 21439 11789 21439 11788 21439 11790 21439 11789 21440 11790 21440 11791 21440 11791 21440 11790 21440 11792 21440 11791 21441 11792 21441 11793 21441 11793 21441 11792 21441 11794 21441 11793 21442 11794 21442 11773 21442 11773 21442 11794 21442 11795 21442 11773 21443 11795 21443 11769 21443 11769 21444 11795 21444 11768 21444 11778 95 11780 95 11796 95 11796 95 11780 95 11782 95 11796 95 11782 95 11783 95 11773 95 11774 95 11796 95 11796 95 11774 95 11776 95 11796 95 11776 95 11778 95 11789 95 11791 95 11796 95 11796 95 11791 95 11793 95 11796 95 11793 95 11773 95 11783 95 11785 95 11796 95 11796 95 11785 95 11787 95 11796 95 11787 95 11789 95 11775 632 11769 632 11767 632 11777 632 11775 632 11779 632 11779 21445 11775 21445 11767 21445 11779 21446 11767 21446 11781 21446 11781 21447 11767 21447 11770 21447 11795 21448 11794 21448 11792 21448 11772 21449 11771 21449 11766 21449 11790 21450 11788 21450 11786 21450 11768 21451 11795 21451 11766 21451 11766 21452 11795 21452 11792 21452 11766 21453 11792 21453 11772 21453 11772 21454 11792 21454 11790 21454 11772 21455 11790 21455 11784 21455 11784 21456 11790 21456 11786 21456 11797 633 11798 633 11799 633 11799 633 11798 633 11800 633 11799 633 11800 633 11801 633 11801 21457 11800 21457 11802 21457 11803 21166 11798 21166 11804 21166 11804 21458 11798 21458 11797 21458 11800 21459 11805 21459 11802 21459 11802 21459 11805 21459 11806 21459 11802 21460 11806 21460 11801 21460 11801 21461 11806 21461 11807 21461 11801 21462 11807 21462 11799 21462 11799 21463 11807 21463 11808 21463 11808 98 11804 98 11799 98 11799 98 11804 98 11797 98 11807 21464 11806 21464 11808 21464 11808 21465 11806 21465 11805 21465 11808 7585 11805 7585 11804 7585 11804 7585 11805 7585 11803 7585 11805 106 11800 106 11803 106 11803 106 11800 106 11798 106 11809 95 11810 95 11811 95 11812 95 11813 95 11814 95 11815 95 11812 95 11816 95 11816 95 11812 95 11814 95 11816 95 11814 95 11817 95 11817 95 11814 95 11811 95 11818 95 11809 95 11819 95 11819 95 11809 95 11811 95 11819 95 11811 95 11820 95 11820 95 11811 95 11814 95 11818 21466 11821 21466 11809 21466 11809 21467 11821 21467 11822 21467 11809 21468 11822 21468 11810 21468 11810 21469 11822 21469 11823 21469 11810 21470 11823 21470 11811 21470 11811 21471 11823 21471 11824 21471 11811 21472 11824 21472 11817 21472 11817 21473 11824 21473 11825 21473 11817 21474 11825 21474 11816 21474 11816 21475 11825 21475 11826 21475 11816 21476 11826 21476 11815 21476 11815 21477 11826 21477 11827 21477 11815 21478 11827 21478 11812 21478 11812 21479 11827 21479 11828 21479 11812 21480 11828 21480 11813 21480 11813 21481 11828 21481 11829 21481 11813 21482 11829 21482 11814 21482 11814 21483 11829 21483 11830 21483 11814 21484 11830 21484 11820 21484 11820 21485 11830 21485 11831 21485 11820 21486 11831 21486 11819 21486 11819 21487 11831 21487 11832 21487 11819 21488 11832 21488 11818 21488 11818 21489 11832 21489 11821 21489 11829 632 11828 632 11833 632 11833 21490 11828 21490 11827 21490 11833 21491 11827 21491 11826 21491 11832 21492 11831 21492 11833 21492 11833 632 11831 632 11830 632 11833 632 11830 632 11829 632 11823 632 11822 632 11833 632 11833 21491 11822 21491 11821 21491 11833 21490 11821 21490 11832 21490 11826 21493 11825 21493 11833 21493 11833 632 11825 632 11824 632 11833 632 11824 632 11823 632 11834 633 11835 633 11836 633 11836 633 11835 633 11837 633 11838 95 11839 95 11834 95 11834 21494 11839 21494 11835 21494 11834 21495 11836 21495 11838 21495 11838 21496 11836 21496 11840 21496 11838 7585 11840 7585 11839 7585 11839 7585 11840 7585 11841 7585 11839 21497 11841 21497 11835 21497 11835 21498 11841 21498 11837 21498 11840 632 11836 632 11841 632 11841 632 11836 632 11837 632 11842 21499 11843 21499 11844 21499 11845 21500 11846 21500 11847 21500 11848 95 11849 95 11850 95 11850 95 11849 95 11842 95 11850 95 11842 95 11847 95 11847 95 11842 95 11844 95 11847 95 11844 95 11845 95 11845 21501 11844 21501 11851 21501 11845 95 11851 95 11852 95 11852 95 11851 95 11853 95 11850 21502 11854 21502 11848 21502 11848 21503 11854 21503 11855 21503 11848 21504 11855 21504 11849 21504 11849 21505 11855 21505 11856 21505 11849 21470 11856 21470 11842 21470 11842 21471 11856 21471 11857 21471 11842 21472 11857 21472 11843 21472 11843 21473 11857 21473 11858 21473 11843 21506 11858 21506 11844 21506 11844 21507 11858 21507 11859 21507 11844 21508 11859 21508 11851 21508 11851 21509 11859 21509 11860 21509 11851 21510 11860 21510 11853 21510 11853 21510 11860 21510 11861 21510 11853 21511 11861 21511 11852 21511 11852 21512 11861 21512 11862 21512 11852 21482 11862 21482 11845 21482 11845 21483 11862 21483 11863 21483 11845 21484 11863 21484 11846 21484 11846 21485 11863 21485 11864 21485 11846 21513 11864 21513 11847 21513 11847 21514 11864 21514 11865 21514 11847 21515 11865 21515 11850 21515 11850 21515 11865 21515 11854 21515 11862 632 11861 632 11866 632 11866 21516 11861 21516 11860 21516 11866 21517 11860 21517 11859 21517 11865 21518 11864 21518 11866 21518 11866 632 11864 632 11863 632 11866 632 11863 632 11862 632 11856 632 11855 632 11866 632 11866 21517 11855 21517 11854 21517 11866 21516 11854 21516 11865 21516 11859 21493 11858 21493 11866 21493 11866 632 11858 632 11857 632 11866 632 11857 632 11856 632 11867 632 11868 632 11869 632 11870 632 11871 632 11872 632 11873 632 11874 632 11867 632 11875 632 11873 632 11876 632 11876 632 11873 632 11867 632 11876 632 11867 632 11872 632 11872 632 11867 632 11869 632 11872 632 11869 632 11870 632 11870 632 11869 632 11877 632 11878 21519 11879 21519 11880 21519 11881 21520 11882 21520 11880 21520 11883 21521 11884 21521 11880 21521 11880 21522 11885 21522 11886 21522 11887 21523 11880 21523 11886 21523 11888 21524 11885 21524 11880 21524 11889 21525 11880 21525 11890 21525 11880 21526 11891 21526 11892 21526 11893 21527 11880 21527 11892 21527 11889 21528 11891 21528 11880 21528 11884 21529 11888 21529 11880 21529 11882 21530 11883 21530 11880 21530 11893 21531 11881 21531 11880 21531 11880 21532 11894 21532 11895 21532 11896 21533 11880 21533 11895 21533 11897 21534 11894 21534 11880 21534 11898 21535 11890 21535 11896 21535 11896 21536 11890 21536 11880 21536 11879 21537 11897 21537 11880 21537 11887 21538 11878 21538 11880 21538 11892 21539 11869 21539 11893 21539 11893 21540 11869 21540 11868 21540 11893 21541 11868 21541 11881 21541 11881 21542 11868 21542 11882 21542 11882 21543 11868 21543 11867 21543 11882 21544 11867 21544 11883 21544 11883 21545 11867 21545 11884 21545 11884 21546 11867 21546 11874 21546 11884 21547 11874 21547 11888 21547 11888 21548 11874 21548 11873 21548 11888 21549 11873 21549 11885 21549 11885 21550 11873 21550 11875 21550 11885 21551 11875 21551 11886 21551 11886 21552 11875 21552 11876 21552 11886 21553 11876 21553 11887 21553 11887 21554 11876 21554 11872 21554 11887 21555 11872 21555 11878 21555 11878 21556 11872 21556 11879 21556 11879 21557 11872 21557 11871 21557 11879 21558 11871 21558 11897 21558 11897 21559 11871 21559 11894 21559 11894 21560 11871 21560 11870 21560 11894 21561 11870 21561 11895 21561 11895 21562 11870 21562 11896 21562 11896 21563 11870 21563 11877 21563 11896 21564 11877 21564 11898 21564 11892 98 11891 98 11869 98 11869 98 11891 98 11889 98 11869 98 11889 98 11877 98 11877 98 11889 98 11890 98 11877 98 11890 98 11898 98 11899 632 11900 632 11901 632 11901 21565 11900 21565 11902 21565 11901 21566 11902 21566 11903 21566 11904 21567 11905 21567 11901 21567 11901 632 11905 632 11906 632 11901 632 11906 632 11899 632 11907 632 11908 632 11901 632 11901 21568 11908 21568 11909 21568 11901 21569 11909 21569 11904 21569 11903 21570 11910 21570 11901 21570 11901 632 11910 632 11911 632 11901 632 11911 632 11907 632 11912 21571 11909 21571 11913 21571 11913 21572 11909 21572 11908 21572 11913 21573 11908 21573 11914 21573 11914 21574 11908 21574 11907 21574 11914 21575 11907 21575 11915 21575 11915 21576 11907 21576 11911 21576 11915 21577 11911 21577 11916 21577 11916 21578 11911 21578 11910 21578 11916 21579 11910 21579 11917 21579 11917 21580 11910 21580 11903 21580 11917 21581 11903 21581 11918 21581 11918 21582 11903 21582 11902 21582 11918 21583 11902 21583 11919 21583 11919 21584 11902 21584 11900 21584 11919 21585 11900 21585 11920 21585 11920 21586 11900 21586 11899 21586 11920 21587 11899 21587 11921 21587 11921 21588 11899 21588 11906 21588 11921 21589 11906 21589 11922 21589 11922 21590 11906 21590 11905 21590 11922 21591 11905 21591 11923 21591 11923 21592 11905 21592 11904 21592 11923 21593 11904 21593 11912 21593 11912 21594 11904 21594 11909 21594 11924 21595 11913 21595 11914 21595 11912 21596 11913 21596 11924 21596 11924 21597 11916 21597 11917 21597 11915 21598 11916 21598 11924 21598 11914 21599 11915 21599 11924 21599 11924 21600 11919 21600 11920 21600 11918 21601 11919 21601 11924 21601 11917 21602 11918 21602 11924 21602 11924 21603 11922 21603 11923 21603 11921 21604 11922 21604 11924 21604 11920 21605 11921 21605 11924 21605 11923 21606 11912 21606 11924 21606 11925 632 11926 632 11927 632 11927 21607 11926 21607 11928 21607 11927 21608 11928 21608 11929 21608 11930 632 11931 632 11927 632 11927 632 11931 632 11932 632 11927 632 11932 632 11925 632 11933 632 11934 632 11927 632 11927 21609 11934 21609 11935 21609 11927 21610 11935 21610 11930 21610 11929 632 11936 632 11927 632 11927 632 11936 632 11937 632 11927 632 11937 632 11933 632 11938 21611 11939 21611 11940 21611 11941 21612 11939 21612 11938 21612 11938 21613 11942 21613 11943 21613 11944 21614 11942 21614 11938 21614 11940 21615 11944 21615 11938 21615 11938 21616 11945 21616 11946 21616 11947 21617 11945 21617 11938 21617 11943 21618 11947 21618 11938 21618 11938 21619 11948 21619 11949 21619 11950 21620 11948 21620 11938 21620 11946 21621 11950 21621 11938 21621 11949 21622 11941 21622 11938 21622 11941 21623 11935 21623 11939 21623 11939 21624 11935 21624 11934 21624 11939 21625 11934 21625 11940 21625 11940 21626 11934 21626 11933 21626 11940 21627 11933 21627 11944 21627 11944 21628 11933 21628 11937 21628 11944 21629 11937 21629 11942 21629 11942 21630 11937 21630 11936 21630 11942 21631 11936 21631 11943 21631 11943 21632 11936 21632 11929 21632 11943 21581 11929 21581 11947 21581 11947 21582 11929 21582 11928 21582 11947 21583 11928 21583 11945 21583 11945 21584 11928 21584 11926 21584 11945 21633 11926 21633 11946 21633 11946 21634 11926 21634 11925 21634 11946 21635 11925 21635 11950 21635 11950 21636 11925 21636 11932 21636 11950 21637 11932 21637 11948 21637 11948 21638 11932 21638 11931 21638 11948 21639 11931 21639 11949 21639 11949 21640 11931 21640 11930 21640 11949 21641 11930 21641 11941 21641 11941 21642 11930 21642 11935 21642 11951 21643 11952 21643 11953 21643 11954 21644 11952 21644 11951 21644 11951 21645 11955 21645 11956 21645 11957 21646 11955 21646 11951 21646 11953 21647 11957 21647 11951 21647 11951 21648 11958 21648 11959 21648 11960 21649 11958 21649 11951 21649 11956 21650 11960 21650 11951 21650 11951 21651 11961 21651 11962 21651 11963 21652 11961 21652 11951 21652 11959 21653 11963 21653 11951 21653 11962 21654 11954 21654 11951 21654 11954 21655 11964 21655 11952 21655 11952 21656 11964 21656 11965 21656 11952 21657 11965 21657 11953 21657 11953 21658 11965 21658 11966 21658 11953 21659 11966 21659 11957 21659 11957 21660 11966 21660 11967 21660 11957 21661 11967 21661 11955 21661 11955 21662 11967 21662 11968 21662 11955 21663 11968 21663 11956 21663 11956 21664 11968 21664 11969 21664 11956 21665 11969 21665 11960 21665 11960 21666 11969 21666 11970 21666 11960 21667 11970 21667 11958 21667 11958 21668 11970 21668 11971 21668 11958 21669 11971 21669 11959 21669 11959 21670 11971 21670 11972 21670 11959 21671 11972 21671 11963 21671 11963 21671 11972 21671 11973 21671 11963 21672 11973 21672 11961 21672 11961 21672 11973 21672 11974 21672 11961 21673 11974 21673 11962 21673 11962 2566 11974 2566 11975 2566 11962 21674 11975 21674 11954 21674 11954 21675 11975 21675 11964 21675 11965 21676 11976 21676 11966 21676 11966 21677 11976 21677 11977 21677 11966 21678 11977 21678 11967 21678 11967 21679 11977 21679 11978 21679 11967 21680 11978 21680 11968 21680 11968 21681 11978 21681 11979 21681 11968 21682 11979 21682 11969 21682 11969 21683 11979 21683 11980 21683 11969 21684 11980 21684 11970 21684 11970 21685 11980 21685 11981 21685 11970 21686 11981 21686 11971 21686 11971 21687 11981 21687 11982 21687 11971 21688 11982 21688 11972 21688 11972 21689 11982 21689 11983 21689 11972 21690 11983 21690 11973 21690 11973 21691 11983 21691 11984 21691 11973 21692 11984 21692 11974 21692 11974 21693 11984 21693 11985 21693 11974 21694 11985 21694 11975 21694 11975 21695 11985 21695 11986 21695 11975 21696 11986 21696 11964 21696 11964 21697 11986 21697 11987 21697 11964 21698 11987 21698 11965 21698 11965 21699 11987 21699 11976 21699 11983 632 11982 632 11988 632 11988 21700 11982 21700 11981 21700 11988 21701 11981 21701 11980 21701 11986 21702 11985 21702 11988 21702 11988 632 11985 632 11984 632 11988 632 11984 632 11983 632 11977 21703 11976 21703 11988 21703 11988 21704 11976 21704 11987 21704 11988 21705 11987 21705 11986 21705 11980 632 11979 632 11988 632 11988 632 11979 632 11978 632 11988 632 11978 632 11977 632 11989 21706 11990 21706 11991 21706 11992 21707 11990 21707 11989 21707 11989 21708 11993 21708 11994 21708 11995 21709 11993 21709 11989 21709 11991 21710 11995 21710 11989 21710 11989 21711 11996 21711 11997 21711 11998 21712 11996 21712 11989 21712 11994 21713 11998 21713 11989 21713 11989 21714 11999 21714 12000 21714 12001 21715 11999 21715 11989 21715 11997 21716 12001 21716 11989 21716 12000 21717 11992 21717 11989 21717 11992 21718 12002 21718 11990 21718 11990 21718 12002 21718 12003 21718 11990 21719 12003 21719 11991 21719 11991 21720 12003 21720 12004 21720 11991 21721 12004 21721 11995 21721 11995 21722 12004 21722 12005 21722 11995 21723 12005 21723 11993 21723 11993 21724 12005 21724 12006 21724 11993 21725 12006 21725 11994 21725 11994 21726 12006 21726 12007 21726 11994 21727 12007 21727 11998 21727 11998 21728 12007 21728 12008 21728 11998 21729 12008 21729 11996 21729 11996 21730 12008 21730 12009 21730 11996 21731 12009 21731 11997 21731 11997 21732 12009 21732 12010 21732 11997 21733 12010 21733 12001 21733 12001 21734 12010 21734 12011 21734 12001 21735 12011 21735 11999 21735 11999 21736 12011 21736 12012 21736 11999 21737 12012 21737 12000 21737 12000 21738 12012 21738 12013 21738 12000 21739 12013 21739 11992 21739 11992 21739 12013 21739 12002 21739 12003 21740 12014 21740 12004 21740 12004 21741 12014 21741 12015 21741 12004 21742 12015 21742 12005 21742 12005 21743 12015 21743 12016 21743 12005 21744 12016 21744 12006 21744 12006 21681 12016 21681 12017 21681 12006 21745 12017 21745 12007 21745 12007 21746 12017 21746 12018 21746 12007 21747 12018 21747 12008 21747 12008 21748 12018 21748 12019 21748 12008 21749 12019 21749 12009 21749 12009 21750 12019 21750 12020 21750 12009 21751 12020 21751 12010 21751 12010 21752 12020 21752 12021 21752 12010 21753 12021 21753 12011 21753 12011 21754 12021 21754 12022 21754 12011 21755 12022 21755 12012 21755 12012 21756 12022 21756 12023 21756 12012 21757 12023 21757 12013 21757 12013 21758 12023 21758 12024 21758 12013 21759 12024 21759 12002 21759 12002 21760 12024 21760 12025 21760 12002 21761 12025 21761 12003 21761 12003 21762 12025 21762 12014 21762 12021 632 12020 632 12026 632 12026 21763 12020 21763 12019 21763 12026 21764 12019 21764 12018 21764 12024 21765 12023 21765 12026 21765 12026 632 12023 632 12022 632 12026 632 12022 632 12021 632 12015 21766 12014 21766 12026 21766 12026 21767 12014 21767 12025 21767 12026 21768 12025 21768 12024 21768 12018 21769 12017 21769 12026 21769 12026 632 12017 632 12016 632 12026 632 12016 632 12015 632 12027 632 12028 632 12029 632 12030 632 12031 632 12032 632 12033 632 12034 632 12035 632 12035 632 12034 632 12027 632 12035 632 12027 632 12036 632 12036 632 12027 632 12029 632 12027 632 12037 632 12028 632 12028 632 12037 632 12030 632 12028 632 12030 632 12038 632 12038 632 12030 632 12032 632 12039 95 12040 95 12041 95 12042 95 12043 95 12044 95 12045 95 12046 95 12044 95 12044 95 12046 95 12047 95 12047 21770 12039 21770 12044 21770 12044 95 12039 95 12041 95 12044 95 12041 95 12042 95 12042 95 12041 95 12048 95 12042 95 12048 95 12049 95 12049 95 12048 95 12050 95 12032 21771 12050 21771 12038 21771 12038 21772 12050 21772 12048 21772 12038 21773 12048 21773 12028 21773 12028 21774 12048 21774 12041 21774 12028 21775 12041 21775 12029 21775 12029 21776 12041 21776 12040 21776 12029 21777 12040 21777 12036 21777 12036 21778 12040 21778 12039 21778 12036 21779 12039 21779 12035 21779 12035 21780 12039 21780 12047 21780 12035 98 12047 98 12033 98 12033 98 12047 98 12046 98 12033 21781 12046 21781 12034 21781 12034 21782 12046 21782 12045 21782 12034 21783 12045 21783 12027 21783 12027 21784 12045 21784 12044 21784 12027 21785 12044 21785 12037 21785 12037 21786 12044 21786 12043 21786 12037 21787 12043 21787 12030 21787 12030 21788 12043 21788 12042 21788 12030 21789 12042 21789 12031 21789 12031 21790 12042 21790 12049 21790 12050 106 12032 106 12049 106 12049 106 12032 106 12031 106 12051 632 12052 632 12053 632 12053 7585 12052 7585 12054 7585 12054 7585 12052 7585 12055 7585 12054 106 12056 106 12053 106 12053 106 12056 106 12051 106 12055 21791 12052 21791 12056 21791 12056 21792 12052 21792 12051 21792 12055 95 12056 95 12054 95 12057 7585 12058 7585 12059 7585 12059 7585 12058 7585 12060 7585 12061 95 12062 95 12063 95 12060 95 12061 95 12059 95 12059 95 12061 95 12063 95 12059 95 12063 95 12064 95 12064 95 12063 95 12065 95 12060 21793 12058 21793 12061 21793 12061 21794 12058 21794 12066 21794 12061 21795 12066 21795 12062 21795 12062 21796 12066 21796 12067 21796 12062 21797 12067 21797 12063 21797 12063 21798 12067 21798 12068 21798 12063 21799 12068 21799 12065 21799 12065 21800 12068 21800 12069 21800 12065 21801 12069 21801 12064 21801 12064 21802 12069 21802 12070 21802 12064 21803 12070 21803 12059 21803 12059 21804 12070 21804 12057 21804 12058 21805 12057 21805 12070 21805 12068 21806 12067 21806 12066 21806 12058 21807 12070 21807 12066 21807 12066 21808 12070 21808 12069 21808 12066 21809 12069 21809 12068 21809

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/palm/palm_G1M5.dae b/URDFs/sr_description/meshes/components/palm/palm_G1M5.dae new file mode 100644 index 0000000..09dad6d --- /dev/null +++ b/URDFs/sr_description/meshes/components/palm/palm_G1M5.dae @@ -0,0 +1,143 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_decimate-ready.blend + + 2012-07-23T02:03:42.155704 + 2012-07-23T02:03:42.155716 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.78691 9.19201 96.43330 -3.92405 9.96326 98.56781 -2.62062 9.46742 96.43924 -5.43032 9.80370 99.67536 -4.79349 9.69696 99.05482 -4.19838 9.56087 98.36475 -3.70107 9.41038 97.67665 -3.29574 9.25230 97.00842 -2.77315 8.93963 95.81378 -5.28283 10.68463 99.70127 -4.62052 10.57362 99.05590 -4.00144 10.43204 98.33804 -3.48421 10.27552 97.62236 -4.60233 11.04699 97.44498 -3.06268 10.11112 96.92741 -4.25756 11.04698 96.20253 -2.72672 9.94482 96.26660 -2.72672 9.95522 93.81953 -2.72672 10.02494 95.04327 -4.15142 11.04698 95.04391 -4.22323 11.04697 94.01063 -2.86901 5.74386 90.32433 -4.62794 7.94142 90.84270 -4.18119 7.94142 91.62482 -3.86182 7.94142 92.36639 -3.64156 7.94142 93.06497 -2.86899 7.19214 93.23296 -1.99944 7.30184 92.42417 -1.99944 6.94656 91.57980 -1.99944 6.38827 90.62457 -1.99944 8.25571 93.05316 -1.99944 7.51917 93.15262 -2.00608 8.38057 93.92613 -2.01864 8.65396 94.05002 -2.00608 7.87464 93.62244 -4.49718 11.01932 91.70681 -4.65287 11.17864 92.90418 -5.12373 11.27726 91.90456 -2.62016 8.73646 95.12651 -3.42962 8.64119 95.29340 -2.44319 8.56278 94.71519 -3.05339 8.50667 94.93190 -2.66969 8.34255 94.60554 -2.07694 8.79775 92.93053 -2.19144 9.32990 94.73645 -2.05462 8.88449 94.20363 -2.24790 9.44767 94.97076 -2.19861 9.23126 95.04590 -2.19702 7.58718 93.89459 -2.32404 7.07942 93.26062 -2.31886 5.63812 90.39952 -3.27289 7.83903 94.26450 -2.40430 8.83116 95.13353 -2.22730 8.65637 94.63448 -2.25253 9.00930 95.10451 -2.62331 7.53031 93.96103 -2.30936 8.16196 94.33179 -2.00608 8.32860 93.39331 -3.50552 7.94157 93.72603 -6.26160 11.17530 88.88427 -9.96445 8.49697 87.00079 -4.23845 5.63631 88.40635 -1.99944 7.99697 92.17238 -2.07130 8.64962 92.46509 -2.25794 9.21523 92.83736 -2.50042 9.65676 93.29486 -3.31068 10.47650 94.44254 -3.48535 10.58686 93.59962 -3.71003 10.70574 92.56482 -3.96819 10.81415 91.43005 -4.23984 10.89921 90.28439 -13.13533 10.99697 85.43847 -10.99945 10.99697 85.20283 -8.86359 10.99697 85.43846 -6.83064 10.99697 86.13393 -4.99944 10.99697 87.25483 -17.23631 10.98760 88.17897 -4.76363 10.98769 88.17481 -4.50802 10.95645 89.19074 -18.41133 1.43357 87.00079 -19.12988 1.27291 87.70229 -19.12988 -0.00303 87.59161 -18.84514 -0.00303 87.29073 -18.54927 -0.00303 87.00079 -19.12988 2.37195 87.98257 -18.00349 2.81535 87.00079 -17.34730 4.08411 87.00079 -16.49944 5.99697 87.00079 -15.99944 6.96932 88.11702 -12.03442 8.49697 87.00079 -8.57618 7.14735 87.00079 -9.94944 7.94142 87.46532 -9.94944 7.47344 87.00079 -8.39124 7.94142 87.85355 -7.30655 6.58200 87.00080 -6.12860 5.76542 87.00080 -4.06877 2.91600 87.00080 -5.04713 4.64133 87.00080 -3.63364 1.65375 87.00080 -3.44961 -0.00303 87.00080 -3.15375 -0.00303 87.29074 -2.86901 -0.00303 87.59161 -2.86901 1.27350 87.70241 -2.86901 2.37288 87.98289 -2.86901 3.31200 88.37459 -15.99944 8.49697 87.00079 -19.99944 -0.00303 87.25483 -19.99944 1.33074 87.37052 -19.99944 2.47985 87.66354 -1.99944 -8.00303 87.25484 -1.99944 -0.00303 87.25484 -1.99944 4.28706 88.55138 -10.99994 11.39697 88.27529 -19.56388 -0.00303 87.75066 -19.94282 -0.00303 87.48594 -19.78578 -0.00303 87.66471 -19.32740 -0.00303 87.72430 -2.21310 -0.00303 87.66472 -2.05606 -0.00303 87.48595 -2.31886 3.11933 88.42470 -2.67149 -0.00303 87.72430 -2.43500 -0.00303 87.75066 -13.76685 -11.00303 83.83875 -10.99943 -11.00303 83.54883 -8.23170 -11.00303 83.83883 -6.57136 -11.00303 84.38750 -4.99944 -11.00303 85.19009 -19.72185 -9.24094 87.00952 -19.02166 -10.21902 86.44582 -2.27803 -9.24322 87.00867 -2.97677 -10.21861 86.44615 -3.91117 -10.77342 85.81319 -19.12987 -8.00303 87.59161 -18.90861 -9.03460 87.35694 -18.36907 -9.82743 86.83522 -18.54927 -4.00303 87.00080 -17.61403 -10.30840 86.21866 -16.91593 -4.00303 85.72745 -16.73857 -10.50303 85.61664 -15.61810 -10.50303 85.01742 -15.88833 -9.00303 85.14693 -15.52103 -9.48780 84.97308 -15.88833 -6.00303 85.14693 -15.41294 -5.67444 84.92504 -15.07323 -5.46536 84.78296 -15.06578 -4.00303 84.77999 -14.74852 -5.29607 84.65945 -15.04330 -10.02226 84.77108 -14.44095 -10.49866 84.55418 -14.27803 -5.11393 84.50076 -13.56440 -5.00303 84.30403 -13.06992 -4.00303 84.19742 -11.86180 -5.00303 84.03466 -10.99943 -4.00303 84.00080 -10.13707 -5.00303 84.03466 -8.92895 -4.00303 84.19742 -8.43447 -5.00303 84.30403 -7.75159 -5.10488 84.49121 -7.14236 -5.34857 84.69920 -6.93310 -4.00303 84.77999 -6.60089 -5.66467 84.91850 -6.38052 -10.50303 85.01753 -6.11055 -9.00303 85.14693 -5.26031 -10.50303 85.61664 -6.11055 -6.00303 85.14693 -5.08295 -4.00303 85.72745 -4.31402 -10.50130 86.22202 -3.64806 -9.84937 86.81806 -3.44961 -4.00303 87.00080 -3.09106 -9.03650 87.35612 -2.86901 -8.00303 87.59161 -13.03604 -5.00303 84.67027 -8.96283 -5.00303 84.67027 -12.59840 -5.00303 85.13993 -9.40047 -5.00303 85.13993 -12.27033 -5.00303 85.69276 -9.72854 -5.00303 85.69276 -12.06769 -5.00303 86.30224 -9.93118 -5.00303 86.30224 -10.99943 -10.00303 85.00080 -12.66555 -10.00303 85.05358 -10.99943 -10.00303 85.40250 -12.38011 -10.00303 85.47595 -10.99943 -10.00303 85.74326 -12.17045 -10.00303 85.94012 -10.99943 -10.00303 86.01086 -9.95637 -10.00303 86.43204 -12.04251 -10.00303 86.43199 -6.58866 -6.00303 84.98119 -6.58878 -9.00303 84.98116 -7.09450 -6.00303 84.94080 -7.09457 -9.00303 84.94081 -7.59312 -6.00303 85.02869 -7.59319 -9.00303 85.02872 -8.05351 -6.00303 85.23886 -8.05357 -9.00303 85.23889 -8.44640 -6.00303 85.55786 -8.44646 -9.00303 85.55791 -8.74675 -6.00303 85.96545 -8.74683 -9.00303 85.96560 -8.93540 -6.00303 86.43652 -8.93547 -9.00303 86.43675 -15.41021 -9.00303 84.98119 -15.41021 -6.00303 84.98119 -14.90438 -9.00303 84.94080 -14.90438 -6.00303 84.94080 -14.40575 -9.00303 85.02869 -14.40575 -6.00303 85.02869 -13.94536 -9.00303 85.23886 -13.94536 -6.00303 85.23886 -13.55247 -9.00303 85.55786 -13.55247 -6.00303 85.55786 -13.25213 -9.00303 85.96545 -13.25213 -6.00303 85.96545 -13.06347 -9.00303 86.43652 -13.06347 -6.00303 86.43652 -13.71113 -5.29592 85.04181 -12.97319 -5.29592 85.86537 -7.25136 -5.30497 84.66199 -8.28282 -5.29592 85.03847 -9.02428 -5.29592 85.86275 -15.20861 -9.24626 84.91932 -14.45941 -9.51198 84.86862 -13.92234 -9.70494 84.92410 -13.03527 -9.71013 85.75558 -12.97082 -9.98200 85.01439 -13.25342 -9.92569 84.99265 -13.52180 -9.84500 84.97118 -19.32739 -8.00303 87.72430 -19.56388 -8.00303 87.75066 -19.78578 -8.00303 87.66472 -19.94282 -8.00303 87.48595 -2.67151 -8.00302 87.72429 -2.43502 -8.00302 87.75067 -2.21312 -8.00302 87.66473 -2.05606 -8.00302 87.48595 -5.22536 -10.75303 85.55949 -3.52903 -9.98157 86.87932 -2.86596 -9.19326 87.46947 -4.23798 -10.62444 86.18590 -3.30825 -10.17120 86.83067 -2.61141 -9.29184 87.43205 -5.13856 -10.91940 85.41756 -3.15324 -10.23448 86.72431 -4.00331 -10.79866 85.96618 -2.31082 -9.29155 87.14125 -16.86900 -10.93604 85.40337 -14.52264 -10.85658 84.42581 -12.04944 -10.85241 83.89981 -10.99943 -10.66970 84.02230 -13.47455 -10.61703 84.28741 -10.99943 -10.97928 83.70176 -9.94944 -10.85241 83.89981 -7.47623 -10.85658 84.42581 -19.08425 -9.16383 87.46036 -16.78412 -10.77336 85.54215 -17.71125 -10.54603 86.21458 -18.57539 -10.08604 86.87474 -19.28141 -9.25626 87.46587 -17.83893 -10.70810 86.13063 -18.75820 -10.20360 86.79390 -19.46508 -9.30571 87.39326 -16.98495 -10.99559 85.21379 -17.99289 -10.79692 85.97325 -18.92981 -10.24095 86.64246 -19.63477 -9.30826 87.23492 -10.99943 -10.04902 84.66844 -10.99943 -10.18686 84.38903 -10.99943 -10.40319 84.16565 -12.78643 -10.32127 84.33206 -12.73147 -10.17210 84.66017 -9.26630 -10.17210 84.66017 -9.21134 -10.32127 84.33206 -8.52322 -10.61703 84.28741 -8.47597 -9.84500 84.97118 -8.74434 -9.92569 84.99265 -9.02695 -9.98200 85.01439 -8.96250 -9.71013 85.75558 -8.07543 -9.70494 84.92410 -7.53835 -9.51198 84.86862 -6.78915 -9.24626 84.91932 -9.82731 -10.00303 85.94012 -9.61765 -10.00303 85.47595 -9.33221 -10.00303 85.05358 -7.55681 -10.49866 84.55418 -6.95446 -10.02226 84.77108 -6.47673 -9.48780 84.97308 -9.99943 -5.00303 86.93854 -11.99943 -5.00303 93.26875 -9.99943 -5.00303 93.26875 -9.76705 -5.00303 94.09372 -11.22196 -5.00303 94.02587 -10.77691 -5.00303 94.02587 -11.62292 -5.00303 94.21896 -10.37594 -5.00303 94.21896 -12.36546 -5.07242 94.00080 -11.90040 -5.00303 94.56692 -10.09847 -5.00303 94.56692 -12.16913 -5.00303 94.92145 -9.82974 -5.00303 94.92146 -11.99943 -5.00303 95.00080 -9.99943 -5.00303 95.00080 -9.91382 -5.00303 95.44342 -12.07844 -5.00303 95.45930 -10.13171 -5.00303 95.49785 -11.86516 -5.00303 95.50132 -10.49671 -5.00303 95.86525 -10.23375 -5.00303 95.88861 -11.75377 -5.00303 95.89827 -11.49825 -5.00303 95.86751 -10.99721 -5.00303 96.00079 -10.71798 -5.00303 96.13889 -11.26470 -5.00303 96.14278 -8.99906 -6.00303 94.00079 -8.99943 -9.00303 86.93854 -8.99943 -9.00303 94.00080 -11.99943 -10.00303 86.93854 -9.99943 -10.00303 94.00080 -11.99943 -10.00303 94.00080 -12.99944 -9.00303 94.00080 -12.99944 -6.00303 93.96098 -12.99944 -6.00303 86.93854 -12.38214 -5.07915 86.93854 -12.69802 -5.28750 94.00080 -12.70656 -5.29593 86.93854 -12.92101 -5.61481 94.00080 -12.99450 -6.00303 94.14118 -9.56780 -5.11040 94.23586 -9.61675 -5.07915 86.93854 -9.30086 -5.28749 94.00080 -9.29233 -5.29592 86.93854 -9.07786 -5.61481 94.00080 -9.07556 -5.62034 86.93854 -9.13342 -9.50305 94.00080 -9.29233 -9.71013 86.93854 -9.49946 -9.86907 94.00080 -9.61675 -9.92691 86.93854 -12.49944 -9.86905 94.00080 -12.70654 -9.71013 86.93854 -12.86546 -9.50303 94.00080 -12.92332 -9.38571 86.93854 -10.99943 -5.00303 95.00080 -12.73674 -5.33823 94.18478 -12.92749 -5.64578 94.15256 -9.26214 -5.33822 94.18479 -9.07139 -5.64578 94.15256 -9.72595 -5.02203 94.50558 -12.81211 -5.27567 95.41162 -13.10184 -5.94570 95.54117 -12.15939 -5.27567 96.45306 -12.32968 -5.94570 96.71619 -10.99944 -5.94570 97.17154 -10.99944 -5.27567 96.85945 -9.66919 -5.94570 96.71619 -9.83949 -5.27567 96.45306 -8.89703 -5.94570 95.54117 -9.18676 -5.27567 95.41162 -11.99943 -10.00303 95.50080 -9.99943 -10.00303 95.50080 -8.89703 -8.94570 95.54117 -13.10184 -8.94570 95.54117 -12.32968 -8.94570 96.71619 -10.99944 -8.94570 97.17154 -9.66919 -8.94570 96.71619 -17.75948 10.89910 90.28619 -17.49210 10.95624 89.19573 -17.95351 10.83841 91.10439 -18.28336 10.70835 92.54009 -18.50646 10.59098 93.56621 -19.04420 10.19218 94.41814 -18.68239 10.48045 94.41386 -19.27217 9.95521 93.81952 -19.74095 9.21523 92.83735 -19.99944 7.99697 92.17237 -18.66365 4.10292 88.26276 -19.12988 4.09936 88.83099 -17.84210 6.16047 88.98504 -19.12988 5.29650 89.82285 -15.99944 7.74294 89.00079 -15.99944 8.49697 89.00079 -19.99944 4.28585 88.55056 -19.99944 5.53739 89.58749 -19.99944 7.42452 92.80273 -15.73728 11.26217 88.88427 -15.11795 11.39697 89.68382 -19.68002 5.63813 90.39954 -19.68002 3.11935 88.42470 -16.49944 8.49697 92.08532 -16.49944 7.94142 89.74381 -11.99943 -5.00303 86.93854 -8.99943 -6.00303 86.93854 -9.99943 -10.00303 86.93854 -12.99944 -9.00303 86.93854 -12.92332 -5.62036 86.93854 -9.07556 -9.38571 86.93854 -12.38212 -9.92691 86.93854 -18.73264 7.83903 94.26450 -14.28900 9.10507 98.62046 -13.78540 11.49697 99.47164 -18.07484 9.96326 98.56780 -16.28111 10.27446 100.34765 -19.40844 9.57200 96.42619 -19.38140 9.77928 96.36005 -19.77822 8.65637 94.63448 -19.75300 9.00930 95.10450 -19.80692 9.23126 95.04589 -19.80851 7.58718 93.89458 -19.85573 8.20532 94.23191 -19.56388 7.03771 93.27090 -19.82544 9.29202 94.66216 -19.75098 9.44767 94.97076 -19.62539 9.63634 95.45103 -19.45986 9.80788 95.89677 -19.38222 7.53031 93.96102 -19.55777 8.55985 94.71039 -18.56921 8.64121 95.29345 -19.32961 8.34236 94.60520 -19.69616 8.16196 94.33179 -13.54441 9.65113 100.62135 -14.33799 9.49194 99.77038 -16.96824 9.74083 99.29839 -15.84827 9.88731 100.26470 -14.17510 8.69990 97.51351 -17.92096 8.54095 95.21242 -18.21762 9.43370 97.78474 -19.38537 8.73646 95.12650 -19.02626 9.09237 96.37290 -14.73763 11.49697 98.71239 -15.48995 11.49697 97.75495 -16.00270 11.49697 96.64925 -16.24766 11.49697 95.45495 -16.21191 11.49697 94.23913 -16.02825 11.49697 93.17276 -15.79537 11.49697 92.22712 -15.49461 11.49697 91.41562 -15.11051 11.49697 90.76318 -14.86599 9.95133 100.91682 -16.87505 11.27728 91.90439 -17.34590 11.17867 92.90395 -16.34875 11.34554 91.02052 -17.50171 11.01932 91.70683 -19.95091 8.88449 94.20363 -19.99944 7.87464 93.62243 -19.99944 8.32860 93.39330 -17.37778 8.49544 94.56344 -19.12988 6.30681 91.12612 -19.12990 7.19214 93.23295 -17.93302 7.94142 91.86849 -17.58020 7.94142 91.18249 -17.11091 7.94142 90.46915 -17.77565 11.08882 94.01063 -19.27217 10.01127 94.47569 -19.27217 10.00166 95.68507 -19.27217 10.02460 95.09306 -17.84745 11.04698 95.04556 -19.27217 9.94482 96.26659 -17.74075 11.04698 96.20577 -18.64199 10.22999 97.42496 -18.22036 10.36962 98.04487 -17.39480 11.04699 97.44958 -17.71625 10.50161 98.68006 -16.75669 11.04699 98.70905 -16.53280 10.70933 99.86160 -15.96703 10.77157 100.31409 -15.80674 11.04699 99.87800 -14.94548 10.83814 100.99229 -14.60171 11.04698 100.82497 -4.08456 8.54095 95.21242 -5.75123 11.49697 95.45495 -6.88885 11.49697 90.76254 -6.50431 11.49697 91.41553 -6.20346 11.49697 92.22728 -5.97059 11.49697 93.17297 -5.78696 11.49697 94.23913 -7.35129 11.49697 90.29107 -8.26082 11.49697 89.71020 -9.30060 11.49697 89.29076 -10.99943 11.49697 95.12437 -10.99943 11.49528 88.98592 -8.09143 11.39697 88.93648 -5.65019 11.34554 91.02040 -6.88093 11.39697 89.68382 -10.99944 8.49697 95.00079 -9.94944 8.49697 88.86504 -4.41073 8.49697 95.04091 -4.62775 8.49544 94.56345 -4.86253 8.49697 93.95770 -4.97702 8.49697 93.42587 -5.15264 8.49697 92.86423 -5.40616 8.49697 92.26855 -5.75942 8.49697 91.64041 -6.23881 8.49697 90.99002 -6.87369 8.49697 90.33944 -7.69372 8.49697 89.72611 -8.71850 8.49697 89.20879 -10.99944 8.55728 98.13480 -5.23617 7.94142 90.03386 -6.04362 7.94142 89.22797 -5.23870 11.04699 98.70362 -6.18704 11.04698 99.87298 -5.90890 10.75973 100.22089 -7.39114 11.04698 100.82124 -7.00228 10.83605 100.96210 -8.76036 11.04697 101.47259 -8.42268 10.85606 101.66717 -8.95340 10.85606 101.84870 -10.23691 11.04697 101.80639 -10.17666 10.85606 102.10032 -11.75499 11.04697 101.80717 -11.46010 10.85606 102.13297 -8.98314 9.96856 101.74918 -8.45173 9.65113 100.62135 -9.69498 9.65113 101.03237 -10.18862 9.96856 101.99714 -12.05994 9.96856 101.96366 -10.99948 9.65113 101.17181 -6.50894 11.49697 97.75497 -5.99619 11.49697 96.64927 -7.26126 11.49697 98.71239 -8.21348 11.49697 99.47164 -6.03239 9.87593 100.17509 -7.70988 9.10508 98.62046 -7.66148 9.49238 99.77200 -7.55751 9.96396 101.15311 -7.89038 10.38170 101.66822 -9.93147 10.38028 102.29176 -12.06741 10.38028 102.29176 -5.71777 10.27446 100.34765 -10.99944 11.48797 100.50080 -8.72876 11.48797 100.01020 -9.86098 11.48797 100.37675 -7.08771 7.94142 88.47514 -13.90792 11.39697 88.93671 -12.50619 11.39697 88.44625 -9.49355 11.39697 88.44605 -12.69840 11.49697 89.29080 -13.73816 11.49697 89.71024 -12.16097 11.48797 100.37675 -13.27012 11.48797 100.01020 -14.10851 10.38170 101.66822 -14.64758 11.49697 90.29107 -13.59535 9.96856 101.54812 -12.30398 9.65113 101.03236 -13.63363 10.85606 101.64468 -12.65105 10.85606 101.95438 -13.23189 11.04697 101.47488 19.21309 9.19201 100.43330 18.07596 9.96326 102.56781 19.37938 9.46742 100.43924 16.56968 9.80370 103.67536 17.20651 9.69696 103.05482 17.80162 9.56087 102.36475 18.29893 9.41038 101.67665 18.70426 9.25230 101.00842 19.22685 8.93964 99.81378 16.71717 10.68463 103.70127 17.37948 10.57362 103.05590 17.99856 10.43204 102.33804 18.51579 10.27552 101.62236 17.39767 11.04699 101.44498 18.93732 10.11113 100.92741 17.74244 11.04698 100.20253 19.27328 9.94482 100.26660 19.27329 10.02495 99.04327 17.84858 11.04698 99.04391 17.77677 11.04697 98.01063 19.13099 5.74386 94.32433 17.37206 7.94142 94.84270 17.81881 7.94142 95.62482 18.13819 7.94142 96.36639 18.35844 7.94142 97.06497 19.13101 7.19214 97.23296 20.00056 7.42460 96.80299 20.00056 6.94656 95.57980 20.00056 6.38827 94.62457 20.00056 8.25571 97.05316 20.00056 7.58539 97.30751 19.99392 8.38057 97.92613 17.50282 11.01933 95.70681 17.34713 11.17865 96.90418 16.87627 11.27726 95.90456 19.37984 8.73646 99.12651 18.57038 8.64119 99.29340 19.55681 8.56278 98.71519 18.94661 8.50667 98.93190 19.33031 8.34255 98.60554 19.92306 8.79775 96.93053 19.80856 9.32990 98.73645 19.94539 8.88449 98.20363 19.75210 9.44767 98.97076 19.80139 9.23127 99.04590 19.99392 7.87464 97.62244 19.80298 7.58718 97.89459 19.67596 7.07942 97.26062 19.68114 5.63812 94.39952 18.72711 7.83903 98.26450 19.59571 8.83116 99.13353 19.77270 8.65637 98.63448 19.74747 9.00930 99.10451 19.37669 7.53031 97.96103 19.69064 8.16196 98.33179 19.99392 8.32860 97.39331 18.49448 7.94157 97.72603 15.73840 11.17530 92.88427 12.03555 8.49697 91.00079 17.76155 5.63631 92.40635 18.03181 10.81416 95.43005 17.76016 10.89921 94.28439 6.83172 10.99697 90.13396 8.86467 10.99697 89.43847 13.13641 10.99697 89.43846 15.16936 10.99697 90.13393 17.00056 10.99697 91.25483 4.76370 10.98760 92.17897 17.23637 10.98769 92.17481 17.49198 10.95645 93.19074 3.58867 1.43357 91.00079 2.87013 1.27291 91.70229 2.87013 -0.00303 91.59161 3.15487 -0.00303 91.29073 3.45073 -0.00303 91.00079 2.87013 2.37195 91.98257 3.99651 2.81535 91.00079 4.65271 4.08412 91.00079 5.50056 5.99697 91.00079 6.00056 6.96932 92.11702 9.96558 8.49697 91.00079 13.42382 7.14735 91.00079 12.05057 7.94142 91.46532 12.05057 7.47344 91.00079 13.60876 7.94142 91.85355 14.69345 6.58200 91.00080 15.99923 5.63255 91.00080 17.93123 2.91600 91.00080 16.95287 4.64133 91.00080 18.36637 1.65375 91.00080 18.55039 -0.00303 91.00080 18.84625 -0.00303 91.29074 19.13099 -0.00303 91.59161 19.13099 1.27351 91.70241 19.13099 2.37288 91.98289 19.13099 3.31200 92.37459 6.00056 8.49697 91.00079 2.00056 2.47986 91.66354 11.00006 11.39697 92.27529 2.32517 -0.00303 91.70768 2.05718 -0.00303 91.48594 2.21422 -0.00303 91.66471 2.43612 -0.00303 91.75066 2.67261 -0.00303 91.72430 19.78690 -0.00303 91.66472 19.94394 -0.00303 91.48595 19.68114 3.11933 92.42470 19.32852 -0.00303 91.72430 19.56500 -0.00303 91.75066 15.42864 -11.00303 88.38750 17.00056 -11.00303 89.19009 19.72198 -9.24321 91.00867 19.02323 -10.21861 90.44615 18.08883 -10.77341 89.81319 17.73979 -10.91053 89.59454 2.87013 -8.00303 91.59161 3.09140 -9.03460 91.35694 3.63093 -9.82743 90.83522 3.45073 -4.00303 91.00080 4.38597 -10.30840 90.21866 5.08407 -4.00303 89.72745 5.26143 -10.50303 89.61664 6.38190 -10.50303 89.01742 6.11167 -9.00303 89.14693 6.47897 -9.48780 88.97308 6.11167 -6.00303 89.14693 6.58706 -5.67444 88.92504 6.92677 -5.46536 88.78296 6.93422 -4.00303 88.77999 7.25148 -5.29607 88.65945 6.95670 -10.02226 88.77108 7.55905 -10.49866 88.55418 7.72198 -5.11393 88.50076 8.43560 -5.00303 88.30403 8.93008 -4.00303 88.19742 10.13820 -5.00303 88.03466 11.00057 -4.00303 88.00080 11.86293 -5.00303 88.03466 13.07105 -4.00303 88.19742 13.56553 -5.00303 88.30403 14.24841 -5.10488 88.49121 14.85765 -5.34857 88.69920 15.06690 -4.00303 88.77999 15.39911 -5.66467 88.91850 15.61948 -10.50303 89.01753 15.88945 -9.00303 89.14693 16.73969 -10.50303 89.61664 15.88945 -6.00303 89.14693 16.91706 -4.00303 89.72745 17.68598 -10.50130 90.22202 18.35194 -9.84937 90.81806 18.55039 -4.00303 91.00080 18.90894 -9.03650 91.35612 19.13099 -8.00303 91.59161 8.96396 -5.00303 88.67027 13.03717 -5.00303 88.67027 9.40160 -5.00303 89.13993 12.59953 -5.00303 89.13993 9.72967 -5.00303 89.69276 12.27146 -5.00303 89.69276 9.93231 -5.00303 90.30224 12.06882 -5.00303 90.30224 11.00057 -10.00303 89.00080 9.33445 -10.00303 89.05358 11.00057 -10.00303 89.40250 9.61989 -10.00303 89.47595 11.00057 -10.00303 89.74326 9.82955 -10.00303 89.94012 11.00057 -10.00303 90.01086 12.04364 -10.00303 90.43204 9.95749 -10.00303 90.43199 15.41134 -6.00303 88.98119 15.41122 -9.00303 88.98116 14.90550 -6.00303 88.94080 14.90544 -9.00303 88.94081 14.40688 -6.00303 89.02869 14.40681 -9.00303 89.02872 13.94649 -6.00303 89.23886 13.94644 -9.00303 89.23889 13.55360 -6.00303 89.55786 13.55354 -9.00303 89.55791 13.25326 -6.00303 89.96545 13.25317 -9.00303 89.96560 13.06460 -6.00303 90.43652 13.06454 -9.00303 90.43675 6.58979 -9.00303 88.98119 6.58979 -6.00303 88.98119 7.09562 -9.00303 88.94080 7.09562 -6.00303 88.94080 7.59425 -9.00303 89.02869 7.59425 -6.00303 89.02869 8.05464 -9.00303 89.23886 8.05464 -6.00303 89.23886 8.44753 -9.00303 89.55786 8.44753 -6.00303 89.55786 8.74787 -9.00303 89.96545 8.74787 -6.00303 89.96545 8.93653 -9.00303 90.43652 8.93653 -6.00303 90.43652 8.28888 -5.29592 89.04181 9.02681 -5.29592 89.86537 14.74864 -5.30497 88.66199 13.71718 -5.29592 89.03847 12.97572 -5.29592 89.86275 6.79139 -9.24625 88.91932 7.54059 -9.51198 88.86862 8.07767 -9.70493 88.92410 8.96474 -9.71013 89.75558 9.02918 -9.98200 89.01439 8.74658 -9.92569 88.99265 8.47820 -9.84499 88.97118 2.67261 -8.00303 91.72430 2.43612 -8.00303 91.75066 2.21422 -8.00303 91.66472 2.05718 -8.00303 91.48595 19.32849 -8.00302 91.72429 19.56498 -8.00302 91.75067 19.78688 -8.00302 91.66473 19.94394 -8.00302 91.48595 16.77464 -10.75303 89.55949 18.47097 -9.98157 90.87932 19.13404 -9.19326 91.46947 17.76203 -10.62444 90.18590 18.69175 -10.17119 90.83067 19.38859 -9.29184 91.43205 16.86144 -10.91940 89.41756 18.84677 -10.23448 90.72431 17.99669 -10.79865 89.96618 19.68918 -9.29155 91.14125 5.13100 -10.93604 89.40337 7.47736 -10.85658 88.42581 9.95057 -10.85241 87.89981 11.00057 -10.66970 88.02230 8.52545 -10.61703 88.28741 11.00057 -10.97928 87.70176 12.05057 -10.85241 87.89981 14.52377 -10.85658 88.42581 2.91575 -9.16382 91.46036 5.21588 -10.77336 89.54215 4.28875 -10.54603 90.21458 3.42461 -10.08604 90.87474 2.71859 -9.25626 91.46587 4.16107 -10.70809 90.13063 3.24180 -10.20360 90.79390 2.53492 -9.30571 91.39326 4.00711 -10.79692 89.97325 3.07019 -10.24095 90.64246 2.36523 -9.30826 91.23492 11.00057 -10.04902 88.66844 11.00057 -10.18686 88.38903 11.00057 -10.40319 88.16565 9.21358 -10.32127 88.33206 9.26853 -10.17210 88.66017 12.73371 -10.17210 88.66017 12.78866 -10.32127 88.33206 13.47679 -10.61703 88.28741 13.52403 -9.84499 88.97118 13.25566 -9.92569 88.99265 12.97305 -9.98200 89.01439 13.03750 -9.71013 89.75558 13.92457 -9.70493 88.92410 14.46165 -9.51198 88.86862 15.21085 -9.24625 88.91932 12.17269 -10.00303 89.94012 12.38235 -10.00303 89.47595 12.66779 -10.00303 89.05358 14.44319 -10.49865 88.55418 15.04554 -10.02226 88.77108 15.52327 -9.48780 88.97308 12.00057 -5.00303 90.93854 10.00057 -5.00303 97.26875 12.00057 -5.00303 97.26875 12.23295 -5.00303 98.09372 10.77804 -5.00303 98.02587 11.22309 -5.00303 98.02587 10.37708 -5.00303 98.21896 11.62406 -5.00303 98.21896 9.63454 -5.07242 98.00080 10.09960 -5.00303 98.56692 11.90153 -5.00303 98.56692 9.83087 -5.00303 98.92145 12.17026 -5.00303 98.92146 10.00057 -5.00303 99.00080 12.00057 -5.00303 99.00080 12.08618 -5.00303 99.44342 9.92156 -5.00303 99.45930 11.86829 -5.00303 99.49785 10.13484 -5.00303 99.50132 11.50329 -5.00303 99.86525 11.76625 -5.00303 99.88861 10.24623 -5.00303 99.89827 10.50175 -5.00303 99.86751 11.00279 -5.00303 100.00079 11.28202 -5.00303 100.13889 10.73530 -5.00303 100.14278 13.00094 -6.00303 98.00079 13.00057 -9.00303 90.93854 13.00057 -9.00303 98.00080 10.00057 -10.00303 90.93854 12.00057 -10.00303 98.00080 10.00057 -10.00303 98.00080 9.00056 -9.00303 98.00080 9.00056 -6.00303 97.96098 9.00056 -6.00303 90.93854 9.61786 -5.07915 90.93854 9.30198 -5.28750 98.00080 9.29344 -5.29593 90.93854 9.07900 -5.61481 98.00080 9.00550 -6.00303 98.14118 12.43220 -5.11040 98.23586 12.38325 -5.07915 90.93854 12.69915 -5.28749 98.00080 12.70767 -5.29592 90.93854 12.92214 -5.61481 98.00080 12.92444 -5.62034 90.93854 12.86658 -9.50305 98.00080 12.70767 -9.71013 90.93854 12.50054 -9.86907 98.00080 12.38325 -9.92691 90.93854 9.50056 -9.86905 98.00080 9.29346 -9.71013 90.93854 9.13454 -9.50303 98.00080 9.07669 -9.38571 90.93854 11.00057 -5.00303 99.00080 9.26326 -5.33823 98.18478 9.07251 -5.64578 98.15256 12.73786 -5.33822 98.18479 12.92861 -5.64578 98.15256 12.27405 -5.02203 98.50558 9.18789 -5.27567 99.41162 8.89816 -5.94570 99.54117 9.84061 -5.27567 100.45306 9.67032 -5.94570 100.71619 11.00056 -5.94570 101.17154 11.00056 -5.27567 100.85945 12.33081 -5.94570 100.71619 12.16051 -5.27567 100.45306 13.10297 -5.94570 99.54117 12.81324 -5.27567 99.41162 10.00057 -10.00303 99.50080 12.00057 -10.00303 99.50080 13.10297 -8.94570 99.54117 8.89816 -8.94570 99.54117 9.67032 -8.94570 100.71619 11.00056 -8.94570 101.17154 12.33081 -8.94570 100.71619 4.24052 10.89910 94.28619 4.50790 10.95624 93.19573 4.04649 10.83841 95.10439 3.71665 10.70835 96.54009 3.49354 10.59098 97.56621 2.95580 10.19218 98.41814 3.31761 10.48045 98.41386 2.72783 9.95522 97.81952 2.25906 9.21523 96.83735 2.07241 8.64962 96.46508 2.00056 7.99697 96.17237 3.33635 4.10292 92.26276 2.87013 4.09936 92.83099 4.15790 6.16047 92.98504 2.87012 5.29650 93.82285 6.00056 7.74294 93.00079 6.00056 8.49697 93.00079 2.00056 4.28585 92.55056 2.00056 5.53739 93.58749 2.00056 7.42452 96.80273 6.26273 11.26217 92.88427 6.88205 11.39697 93.68382 2.31998 5.63813 94.39954 2.31998 3.11935 92.42470 5.50056 8.49697 96.08532 5.50056 7.94142 93.74381 10.00057 -5.00303 90.93854 13.00057 -6.00303 90.93854 12.00057 -10.00303 90.93854 9.00056 -9.00303 90.93854 9.07668 -5.62035 90.93854 12.92445 -9.38571 90.93854 9.61788 -9.92691 90.93854 3.26737 7.83903 98.26450 8.21460 11.49697 103.47164 3.92516 9.96326 102.56780 5.71889 10.27446 104.34765 2.59157 9.57200 100.42619 2.61861 9.77928 100.36005 2.22178 8.65637 98.63448 2.24701 9.00930 99.10450 2.19308 9.23126 99.04589 2.19150 7.58718 97.89458 2.14427 8.20532 98.23191 2.43612 7.03771 97.27090 2.17456 9.29202 98.66216 2.24902 9.44767 98.97076 2.37461 9.63634 99.45103 2.54015 9.80788 99.89677 2.61779 7.53031 97.96102 2.44224 8.55985 98.71039 3.43079 8.64121 99.29345 2.67040 8.34236 98.60520 2.30384 8.16196 98.33179 8.45559 9.65113 104.62135 7.66201 9.49194 103.77038 5.03176 9.74083 103.29839 6.15173 9.88731 104.26470 7.82490 8.69990 101.51351 4.07904 8.54095 99.21242 3.78238 9.43370 101.78474 2.61464 8.73646 99.12650 2.97374 9.09237 100.37290 7.26237 11.49697 102.71239 6.51005 11.49697 101.75495 5.99730 11.49697 100.64925 5.75235 11.49697 99.45495 5.78809 11.49697 98.23913 5.97176 11.49697 97.17276 6.20463 11.49697 96.22712 6.50539 11.49697 95.41562 6.88949 11.49697 94.76318 7.13401 9.95133 104.91682 5.12495 11.27728 95.90439 4.65410 11.17867 96.90395 5.65125 11.34554 95.02052 4.49829 11.01932 95.70683 2.04909 8.88449 98.20363 2.00056 7.87464 97.62243 2.00056 8.32860 97.39330 4.62223 8.49544 98.56344 2.87012 6.30681 95.12612 2.87011 7.19214 97.23295 4.06698 7.94142 95.86849 4.41981 7.94142 95.18249 4.88910 7.94142 94.46915 4.22435 11.08882 98.01063 2.72783 10.01127 98.47569 2.72783 10.00166 99.68507 2.72783 10.02460 99.09306 4.15255 11.04698 99.04556 2.72783 9.94482 100.26659 4.25925 11.04698 100.20577 3.35801 10.22999 101.42496 3.77964 10.36962 102.04487 4.60520 11.04699 101.44958 4.28376 10.50161 102.68006 5.24331 11.04699 102.70905 5.46721 10.70933 103.86160 6.03297 10.77157 104.31409 6.19326 11.04699 103.87800 7.05452 10.83814 104.99229 7.39829 11.04698 104.82497 17.91544 8.54095 99.21242 16.24877 11.49697 99.45495 15.11115 11.49697 94.76254 15.49569 11.49697 95.41553 15.79654 11.49697 96.22728 16.02941 11.49697 97.17297 16.21304 11.49697 98.23913 14.64871 11.49697 94.29107 13.73918 11.49697 93.71020 12.69940 11.49697 93.29076 11.00057 11.49697 99.12437 11.00057 11.49528 92.98592 13.90857 11.39697 92.93648 16.34981 11.34554 95.02040 15.11907 11.39697 93.68382 11.00057 8.49697 99.00079 12.05057 8.49697 92.86504 17.58927 8.49697 99.04091 17.37226 8.49544 98.56345 17.13748 8.49697 97.95770 17.02299 8.49697 97.42587 16.84736 8.49697 96.86423 16.59384 8.49697 96.26855 16.24058 8.49697 95.64041 15.76119 8.49697 94.99002 15.12631 8.49697 94.33944 14.30628 8.49697 93.72611 13.28150 8.49697 93.20879 11.00056 8.55728 102.13480 16.76383 7.94142 94.03386 15.95638 7.94142 93.22797 16.76130 11.04699 102.70362 15.81296 11.04698 103.87298 16.09110 10.75973 104.22089 14.60886 11.04698 104.82124 14.99772 10.83605 104.96210 13.23964 11.04697 105.47259 13.57732 10.85606 105.66717 13.04660 10.85606 105.84870 11.76309 11.04697 105.80639 11.82334 10.85606 106.10032 10.24501 11.04697 105.80717 10.53990 10.85606 106.13297 13.01686 9.96856 105.74918 13.54827 9.65113 104.62135 12.30502 9.65113 105.03237 11.81138 9.96856 105.99714 9.94006 9.96856 105.96366 11.00053 9.65113 105.17181 16.00381 11.49697 100.64927 13.78652 11.49697 103.47164 15.96762 9.87593 104.17509 14.29012 9.10508 102.62046 14.67593 8.71842 101.57586 14.44250 9.96396 105.15311 14.10963 10.38171 105.66822 12.06853 10.38028 106.29176 9.93260 10.38028 106.29176 16.28223 10.27446 104.34765 11.00056 11.48797 104.50080 13.27124 11.48797 104.01020 12.13903 11.48797 104.37675 14.91229 7.94142 92.47514 8.09208 11.39697 92.93671 9.49381 11.39697 92.44625 12.50645 11.39697 92.44605 9.30160 11.49697 93.29080 8.26184 11.49697 93.71024 9.83903 11.48797 104.37675 8.72988 11.48797 104.01020 7.89150 10.38170 105.66822 7.35242 11.49697 94.29107 8.40465 9.96856 105.54812 9.69602 9.65113 105.03236 8.36637 10.85606 105.64468 9.34895 10.85606 105.95438 8.76811 11.04697 105.47488 24.00056 7.42452 92.80273 24.00056 5.53739 89.58749 24.00056 4.28586 88.55056 24.00056 7.99697 92.17237 24.07241 8.64962 92.46508 24.25905 9.21523 92.83735 24.50154 9.65676 93.29485 24.72783 9.95522 93.81952 25.31761 10.48045 94.41386 24.95580 10.19218 94.41814 25.49354 10.59098 93.56621 25.71664 10.70835 92.54009 26.04649 10.83841 91.10439 26.50790 10.95624 89.19573 26.24052 10.89910 90.28619 24.31694 9.33731 80.00230 24.65771 9.87446 80.00000 27.01505 -10.99559 85.21379 39.73980 -10.91053 85.59454 39.76828 -10.89972 80.00000 40.08883 -10.77342 85.81319 40.50205 -10.59673 80.00000 41.02324 -10.21861 86.44615 41.12120 -10.12139 80.00000 41.59687 -9.50222 80.00000 41.72198 -9.24321 87.00867 26.22410 -10.90081 80.00080 25.90226 -10.76947 85.81947 25.49917 -10.59693 80.00000 24.40259 -9.49962 80.00000 24.97834 -10.21902 86.44582 24.27815 -9.24094 87.00952 39.00056 -11.00303 85.19009 39.00026 -10.99969 80.00000 37.42865 -11.00303 84.38750 28.57306 -11.00303 84.38726 26.99799 -11.00650 79.96545 42.00056 4.28707 88.55138 42.00056 2.48084 87.66388 42.00056 1.33137 87.37064 42.00056 -0.00303 87.25484 42.00056 -8.00303 87.25484 24.00056 2.47986 87.66354 24.00056 1.33074 87.37052 24.00056 -0.00303 87.25483 24.00056 -8.00303 87.25484 39.49199 10.95645 89.19074 39.23637 10.98769 88.17481 26.76369 10.98761 88.17897 27.00056 10.99697 87.25483 39.00056 10.99697 87.25483 37.16936 10.99697 86.13393 35.13641 10.99697 85.43846 33.00055 10.99697 85.20283 30.86467 10.99697 85.43847 28.83172 10.99697 86.13396 41.90019 -8.76805 80.00000 24.10026 -8.76782 80.00000 42.00026 -7.99969 80.00000 24.00026 -3.99969 80.00000 24.00026 -7.99969 80.00000 24.00026 6.00031 80.00000 24.00026 8.00031 80.00000 24.07367 8.65989 80.00000 25.12580 10.34262 80.00000 25.66303 10.68178 80.00157 40.30249 10.70294 80.00000 40.87493 10.34245 80.00000 41.34298 9.87424 80.00000 41.70312 9.30205 80.00000 41.92687 8.65984 80.00000 42.00026 8.00031 80.00000 42.00026 6.00031 80.00000 27.00026 11.00031 80.00000 39.00026 11.00031 68.44582 39.76017 10.89921 90.28439 40.03181 10.81415 91.43005 40.28997 10.70574 92.56482 40.51466 10.58686 93.59962 40.68932 10.47650 94.44254 41.49958 9.65676 93.29486 41.74207 9.21523 92.83736 41.92871 8.64963 92.46509 42.00056 7.99698 92.17238 41.27329 9.95522 93.81953 3.69851 10.70317 84.00000 -4.99944 -11.00303 80.00080 -3.49865 -10.59694 80.00000 -2.87826 -10.12085 80.00000 -2.40227 -9.49953 79.99998 -2.05395 -8.57232 87.20531 -17.77590 -10.90081 80.00080 -18.09775 -10.76947 85.81947 -18.50153 -10.59674 80.00000 -19.12068 -10.12140 80.00000 -19.59635 -9.50222 80.00000 -15.42694 -11.00303 84.38726 -16.99944 -11.00303 83.00080 -1.99945 2.48084 87.66388 -1.99945 1.33136 87.37064 -1.99945 5.53833 89.58846 -19.99944 -8.00303 87.25484 -19.92759 8.64962 92.46508 -19.49847 9.65676 93.29485 -16.99944 10.99697 87.25483 -15.16828 10.99697 86.13396 5.01505 -10.99559 89.21378 17.76828 -10.89972 84.00000 18.50205 -10.59673 84.00000 19.12120 -10.12139 84.00000 19.59687 -9.50222 84.00000 19.94605 -8.57232 91.20531 4.22410 -10.90081 84.00079 3.90226 -10.76947 89.81947 3.49847 -10.59674 84.00000 2.87932 -10.12140 84.00000 2.97833 -10.21902 90.44581 2.40364 -9.50222 84.00000 2.27815 -9.24094 91.00951 17.00026 -10.99969 84.00000 13.76830 -11.00303 87.83882 11.00056 -11.00303 87.54882 8.23315 -11.00303 87.83874 6.57306 -11.00303 88.38725 5.00026 -10.99969 84.00000 20.00056 4.28707 92.55137 20.00056 2.48084 91.66387 20.00056 1.33136 91.37063 20.00056 -0.00303 91.25483 20.00056 -8.00303 91.25484 2.00056 1.33074 91.37052 2.00056 -0.00303 91.25483 2.00056 -8.00303 91.25483 20.00056 7.99697 96.17237 19.92871 8.64962 96.46508 19.74206 9.21523 96.83735 19.49958 9.65676 97.29485 19.27328 9.95522 97.81952 18.68931 10.47650 98.44253 18.51465 10.58686 97.59961 18.28996 10.70574 96.56481 2.50154 9.65676 97.29485 5.00056 10.99697 91.25483 11.00054 10.99697 89.20283 -19.89967 -8.76805 80.00000 -2.09974 -8.76782 80.00000 19.90018 -8.76805 84.00000 2.10032 -8.76805 84.00000 2.00026 -7.99969 84.00000 20.00026 -7.99969 84.00000 -16.99974 -10.99970 80.00000 -10.99974 -11.00136 78.34409 11.00056 -11.00303 82.16397 -1.99974 -7.99969 80.00000 -1.99974 -3.99969 80.00000 -19.99974 -7.99969 80.00000 -19.99974 8.00031 71.65829 -19.92632 8.66000 80.00000 -19.70237 9.30253 80.00000 -19.34188 9.87497 80.00000 -18.87368 10.34303 80.00000 -18.30149 10.70316 80.00000 -4.34009 10.92688 80.00000 -3.62834 10.66877 79.99939 -3.12528 10.34261 80.00000 -2.65719 9.87445 80.00000 -2.34403 9.38150 80.00058 -1.99944 7.99697 80.00080 -1.99974 6.00031 80.00000 2.00026 8.00031 84.00000 2.07369 8.66001 84.00000 2.29763 9.30254 84.00000 2.65812 9.87498 84.00000 3.12632 10.34303 84.00000 18.30201 10.70317 84.00000 18.87420 10.34303 84.00000 19.34240 9.87498 84.00000 19.70288 9.30254 84.00000 19.92683 8.66001 84.00000 20.00026 8.00031 84.00000 20.00026 6.00031 84.00000 17.00026 11.00031 84.00000 5.00026 11.00031 84.00000 -4.99974 11.00031 80.00000 -16.99974 11.00031 80.00000 3.86241 -10.59802 81.40353 2.42948 -9.53943 80.00157 -2.16309 -9.49833 78.95819 -2.83410 -10.59802 77.81886 -1.49683 -9.49833 78.12273 -0.91783 -10.59777 76.62256 -0.53404 -9.49833 77.65906 0.59526 -10.59777 76.55095 0.53456 -9.49833 77.65906 1.99690 -10.59777 77.12538 1.49734 -9.49833 78.12273 3.02454 -10.59777 78.23828 2.16361 -9.49833 78.95819 3.71604 -10.59802 79.60367 2.11456 -8.81990 80.00000 19.58443 -9.49802 79.99977 19.89211 -8.79794 80.00000 18.40394 -10.64841 79.90620 19.92081 -9.49833 78.79944 18.99247 -10.59777 78.21025 20.03621 -10.59777 77.10303 20.79969 -9.49833 77.92055 21.45118 -10.59777 76.54335 22.00026 -9.49833 77.59886 -1.22603 -10.99969 75.15271 36.38472 -10.99969 74.66985 22.28898 -10.99969 75.00835 -0.26943 -10.99969 75.00728 21.31737 -10.99969 75.04686 0.69725 -10.99969 75.04883 20.37126 -10.99969 75.27280 1.63810 -10.99969 75.27588 -2.13715 -10.99969 75.47989 19.48711 -10.99969 75.67751 2.51731 -10.99969 75.67976 18.69775 -10.99969 76.24588 3.30253 -10.99969 76.24567 -4.24974 -10.99969 75.50000 3.96375 -10.99969 76.95193 18.03361 -10.99969 76.95605 4.47660 -10.99969 77.77237 17.51946 -10.99969 77.78136 4.82196 -10.99969 78.67668 17.17464 -10.99969 78.69104 -4.20597 -11.00002 77.51928 -16.99974 -10.99969 71.07354 4.98589 -10.99969 79.62120 5.01205 -10.99969 81.49242 17.00672 -10.99969 81.49741 5.00026 -10.99969 82.40479 3.15365 10.59839 78.48140 2.16361 9.49895 78.95819 2.18247 10.59839 77.26360 1.49734 9.49895 78.12273 0.77908 10.59839 76.58775 0.53456 9.49895 77.65906 -0.77857 10.59839 76.58775 -0.53405 9.49895 77.65906 -2.18196 10.59839 77.26360 -1.49683 9.49895 78.12273 -3.15313 10.59839 78.48140 -2.16309 9.49895 78.95819 4.33270 10.83834 80.00000 3.58877 10.63364 80.00013 3.12979 10.34580 80.00000 2.65477 9.87078 80.00000 2.34381 9.38248 79.99774 2.07547 8.66787 80.00000 22.77908 10.59839 76.58775 22.53456 9.49895 77.65906 21.22144 10.59839 76.58775 21.46596 9.49895 77.65906 19.81805 10.59839 77.26360 20.50317 9.49895 78.12273 17.66800 10.88732 80.00000 18.84687 10.59839 78.48140 19.34576 9.87077 80.00000 18.87074 10.34580 80.00000 18.39397 10.64952 80.00264 19.83691 9.49895 78.95819 19.65764 9.37099 80.00056 2.00026 -7.99969 80.00000 1.93211 -7.99969 79.48236 1.81694 7.99696 79.12401 1.73231 -7.99969 79.00000 1.41447 -7.99969 78.58580 1.35816 7.99634 78.50421 1.00026 -7.99969 78.26796 0.70652 7.99770 78.11432 0.51789 -7.99969 78.06816 0.00026 -7.99969 78.00000 0.00362 7.99684 77.98100 -0.51738 -7.99969 78.06816 -0.73896 7.99722 78.12480 -0.99974 -7.99969 78.26796 -1.34970 7.99713 78.50260 -1.41395 -7.99969 78.58580 -1.73179 -7.99969 79.00000 22.00020 -7.99969 78.00000 22.00362 7.99684 77.98100 21.48263 -7.99969 78.06815 21.26106 7.99722 78.12480 21.00025 -7.99969 78.26796 20.65031 7.99713 78.50260 20.58604 -7.99969 78.58580 20.26821 -7.99969 79.00000 20.18043 7.99652 79.12059 20.00026 -7.99969 80.00000 20.06841 -7.99969 79.48236 -1.81518 7.99650 79.11426 2.00087 7.99860 80.00000 20.02610 8.00223 79.78577 20.00026 6.00031 80.00000 17.00026 11.00031 80.00000 5.00026 11.00031 80.00000 -4.84600 11.00031 78.76964 -4.96166 11.00031 79.38405 17.07212 11.00031 79.15535 4.92874 11.00031 79.15738 17.29248 11.00031 78.31572 4.70803 11.00031 78.31569 4.33671 11.00031 77.51099 17.66463 11.00031 77.50955 -0.93444 11.00031 75.08815 -1.77980 11.00031 75.32759 -2.56862 11.00031 75.71039 -4.38788 10.99998 77.50107 -3.28124 11.00031 76.22751 18.17623 11.00031 76.77870 3.82524 11.00031 76.77983 18.80557 11.00031 76.15372 3.19481 11.00031 76.15361 19.52892 11.00031 75.65346 2.47028 11.00031 75.65271 20.32602 11.00031 75.28865 1.67287 11.00031 75.28807 21.17697 11.00031 75.06825 22.05642 11.00031 75.00032 0.82237 11.00031 75.06805 -0.05691 11.00031 75.00034 35.76831 -11.00303 83.83883 33.00057 -11.00303 83.54883 30.23315 -11.00303 83.83875 22.96992 -10.59777 76.63701 23.20083 -9.49833 77.92055 24.07971 -9.49833 78.79944 24.42620 -10.59802 77.56999 40.44828 -10.60419 74.80899 41.17694 -10.06092 74.96077 41.68639 -9.55202 74.60719 42.00000 -5.53847 70.52470 41.99767 -8.01113 74.09462 23.24969 -10.99969 75.15863 39.02267 -11.00002 75.08292 24.16356 -10.99969 75.49222 25.02965 -10.99969 76.31189 25.97642 -11.00002 77.80835 33.00041 -11.01419 78.34450 25.15365 10.59839 78.48140 24.16361 9.49895 78.95819 24.18247 10.59839 77.26360 23.49735 9.49895 78.12273 23.93211 -7.99969 79.48236 23.94208 7.99737 79.45579 23.73231 -7.99969 79.00000 23.60646 7.99701 78.77991 23.41448 -7.99969 78.58580 23.20683 8.00031 78.40495 23.00026 -7.99969 78.26796 22.70653 7.99771 78.11432 22.51792 -7.99969 78.06816 42.00000 -4.37194 66.47318 26.96239 11.00031 79.38576 26.84682 11.00031 78.77084 24.56712 11.00031 75.70917 23.77808 11.00031 75.32674 22.93337 11.00031 75.08784 25.28084 11.00031 76.22670 26.77643 10.99998 78.09213 25.81986 10.88883 78.11772 32.41966 -10.39946 12.09682 32.07253 -12.24215 12.44395 31.50558 -13.97236 13.01090 30.73585 -15.53810 13.78063 31.63869 -14.49044 14.44561 29.78649 -16.89231 14.73000 28.68600 -17.99429 15.83049 27.46747 -18.81092 17.04902 32.07041 -8.48608 13.14742 28.40349 -8.47888 11.38137 35.00025 -3.93633 11.33591 35.00025 -5.76714 10.52314 35.00025 -7.43725 9.41714 35.00025 -8.90012 8.04874 35.00025 -10.11498 6.45606 35.00025 -11.04798 4.68349 35.00025 -11.67312 2.78041 35.00025 -11.97299 0.79987 35.00025 -11.93923 -1.20297 35.00025 -11.57278 -3.17229 29.56896 -8.93371 8.01144 30.37484 -8.14502 8.83751 28.55564 -9.64302 7.14184 27.30582 -10.22031 6.25847 27.40025 -11.09018 4.58267 27.40025 -11.64889 2.88026 26.69314 -11.32162 2.97825 27.40025 -11.94789 1.11364 26.69314 -11.69481 0.52943 25.93359 -9.85955 5.58084 23.33167 -11.28459 5.48865 25.97391 -12.57047 6.52176 24.85194 -11.60693 5.52240 25.38119 -14.24428 7.11447 22.47212 -13.82473 6.34820 24.59638 -15.75172 7.89929 23.89290 -14.44108 6.48145 23.64218 -17.04913 8.85348 21.12374 -15.89684 7.69659 22.38843 -16.75303 7.98591 22.54626 -18.09895 9.94942 19.40502 -17.31880 9.41531 20.47079 -18.33958 9.90356 21.34031 -18.87077 11.15535 20.05931 -19.34222 12.43637 17.46704 -17.96563 11.35329 18.30849 -19.06128 12.06586 18.74032 -19.49967 13.75536 33.46514 -13.23542 -4.38078 33.17361 -11.74079 -2.47919 31.96513 -11.92772 -1.31220 30.60025 -11.99514 -0.33012 30.05848 -11.99939 -0.08363 29.53337 -11.99967 0.01540 28.99234 -11.99966 -0.01997 28.45432 -11.99809 -0.19527 27.92001 -11.98834 -0.52153 27.40787 -11.94871 -0.93188 27.09578 -11.87235 -1.37937 26.71759 -11.59961 -1.87070 26.45649 -11.05894 -2.46481 26.48153 -14.05493 -5.30130 26.40025 -4.32847 -11.00000 24.01463 -8.49968 5.09244 16.67795 -16.49934 11.57507 17.65359 -16.36674 10.59943 18.59801 -15.99816 9.65502 19.48311 -15.40482 8.76991 22.28349 -8.49967 5.96953 22.19817 -9.88384 6.05485 21.94514 -11.22494 6.30789 21.53238 -12.48305 6.72064 20.97256 -13.62080 7.28047 20.28258 -14.60443 7.97044 22.28349 -7.74968 5.96953 19.83408 -7.73186 8.35989 24.57748 -13.49051 -6.58543 17.34177 -13.08415 -7.20829 20.86789 -13.10861 -7.33405 24.43242 -12.36088 -7.88292 17.48629 -11.32987 -8.83814 24.26431 -11.05180 -8.98052 20.85670 -11.35649 -8.91334 24.07885 -9.60768 -9.85024 17.65667 -9.26180 -10.04916 20.84362 -9.30734 -10.08301 23.88002 -8.05947 -10.48217 16.21432 -4.66904 -11.01525 17.84032 -7.03250 -10.77016 20.82957 -7.10759 -10.77834 23.45517 -4.75135 -11.00000 20.80625 -4.91046 -11.00024 23.67152 -6.43582 -10.86811 18.49701 -4.88507 -10.99056 17.10318 -14.40371 -5.27383 21.01717 -14.45248 -5.46440 19.67205 -14.44833 -5.46252 17.62941 -16.83755 -0.58108 20.16150 -16.82432 -1.00220 23.59675 -18.29618 2.50569 18.73591 -18.84136 3.96948 21.20890 -18.77235 3.32656 16.32313 -18.63193 4.75818 25.02458 -19.76640 6.56033 20.33439 -20.43481 8.38559 22.72505 -20.30991 7.52827 17.99380 -20.21678 9.37159 15.74767 -19.64619 10.48572 26.83457 -20.85997 10.49575 24.62881 -21.45601 11.60829 22.33832 -21.62800 12.67454 20.08241 -21.41371 13.85310 17.90191 -20.78959 15.13326 28.95048 -21.59927 14.31419 26.83901 -22.22966 15.57203 25.69386 -14.36625 -4.94374 26.67791 -14.31856 -4.75937 27.05751 -14.55941 -4.13273 27.51717 -14.71325 -3.63396 28.06561 -14.79880 -3.22257 29.33738 -14.75585 -2.73757 29.99210 -14.63437 -2.69855 28.62729 -14.79947 -2.94484 31.81377 -14.02564 -3.27142 31.22617 -14.24843 -3.01117 30.60025 -14.46437 -2.79936 32.28778 -13.85514 -3.54527 32.72167 -14.68274 -0.78008 25.76056 -17.30739 1.19689 29.24789 -16.00011 0.24117 26.34064 -17.95326 2.99865 33.49831 -15.35544 1.85464 30.21492 -16.97527 3.37435 26.92072 -18.59914 4.80041 27.72791 -19.13109 6.68708 34.47482 -15.90300 4.43259 31.44747 -17.74713 6.43111 28.53512 -19.66305 8.57375 35.62984 -16.33092 6.95041 29.58687 -20.05982 10.55781 32.90879 -18.32579 9.40888 30.63861 -20.45659 12.54188 31.93859 -20.68924 14.62075 34.56216 -18.72138 12.30512 23.40025 -15.35262 -3.49114 17.67848 -2.25269 -10.97999 26.40025 0.00032 -11.00000 26.40025 -5.99968 6.00000 26.40025 -6.18543 -10.84601 26.39507 -7.73162 5.01775 26.40025 -7.98379 -10.39034 26.51307 -10.34244 5.16880 26.40025 -9.67426 -9.64862 26.40025 -10.42215 3.51740 26.40025 -10.62459 -2.84802 26.40025 -11.22704 -8.63210 26.40025 -12.58132 -7.37891 26.40025 -13.70245 -5.92588 26.40025 -10.92695 -1.26284 26.40025 -10.99412 0.34961 26.40025 -10.82463 1.95455 17.80788 0.01881 -10.96892 26.40131 0.00470 11.02763 27.05665 0.00902 11.89370 35.02811 0.00038 11.99570 18.44563 0.00032 14.19054 30.44322 -16.82160 15.96257 41.72396 -14.98816 14.96004 40.58631 -14.56790 15.87016 36.07827 -8.49957 15.91767 41.68601 -7.84641 15.45741 41.99378 -9.96123 14.29536 41.76836 -10.68854 14.90430 41.47512 -13.70568 15.47653 40.74386 -13.57435 15.74585 41.90142 -13.68791 14.88158 42.00025 -13.19034 14.22322 36.80173 -18.68935 15.87161 40.32484 -16.75150 15.04226 41.17762 -15.92868 15.16056 40.12450 -15.27101 15.93373 41.79856 -15.10147 14.19986 41.57338 -15.56666 14.15112 36.39445 -18.92611 15.09956 38.38988 -16.84989 11.79218 40.17875 -16.92108 14.26558 42.00025 2.48337 21.60506 42.00025 -10.67037 4.09572 42.00025 -11.57090 7.14653 42.00025 -4.59768 15.66448 42.01282 -6.84140 14.96247 42.00025 -9.20317 14.24871 42.00025 1.33143 20.13086 42.02021 -13.83867 14.29792 42.00025 -11.52747 14.08447 42.00025 -12.69090 10.55043 42.00025 -2.45947 16.88491 40.37364 0.00032 17.38353 42.00025 0.00032 18.43768 26.40025 11.00032 12.00000 35.70737 -6.77643 9.54630 35.70737 -9.35620 7.03646 35.70737 -11.05159 3.86154 41.54034 -12.20096 3.64140 41.57278 -13.76807 8.91658 38.94659 -14.48250 5.48678 40.27235 -13.74717 5.04461 36.94197 -16.64471 9.40473 40.17191 -14.74203 7.98174 40.18572 -15.74563 10.95821 36.00025 -3.63533 10.38181 36.00025 -5.32250 9.62640 36.00025 -6.85840 8.59988 36.00025 -8.20481 7.32637 36.00025 -9.31814 5.84517 36.00025 -10.16628 4.19999 36.00002 10.99987 11.00575 39.03521 10.99585 49.49404 39.00025 11.00032 0.00000 35.77664 10.99998 11.66449 42.00025 8.00032 0.00000 42.00025 3.41451 23.22381 36.00025 -1.84419 10.84425 36.00155 0.00021 11.04205 39.66782 10.92510 0.00000 35.50025 0.00032 11.86602 35.70735 0.00032 11.70711 35.86629 0.00032 11.50000 35.70737 -3.55614 11.15383 35.01630 10.99907 11.99929 26.46544 8.99548 11.93410 35.02872 -0.00088 13.18406 27.01681 -0.01593 12.24285 35.70737 -11.70236 0.32163 35.70737 -11.24701 -3.24868 41.79050 -5.24932 -8.18536 41.12244 -5.67564 -9.11020 40.10453 -6.72086 -9.32953 41.79050 -7.10811 -7.05963 41.12244 -7.73129 -7.86506 40.10453 -9.11759 -7.54228 41.79050 -8.66228 -5.53637 41.12244 -9.45589 -6.17453 41.79050 -9.81318 -3.68586 40.99850 -10.87407 -3.69895 35.70857 -12.46417 -4.83863 35.39104 -11.27122 -6.77530 39.76682 -10.03020 -6.70477 39.67771 -8.88076 -7.94828 38.50327 -9.60950 -7.80175 39.57241 -7.56018 -9.00135 37.77982 -7.19140 -9.58311 39.45084 -6.08439 -9.85267 39.31380 -4.48102 -10.48151 36.95520 -4.63787 -10.65918 35.95850 -8.66244 -7.28350 35.90602 -9.91289 -8.07626 35.75685 -9.60337 -6.61510 35.60590 -10.89876 -7.17277 35.52370 -10.17083 -6.08433 35.27900 -10.59459 -5.56352 35.08573 -11.80042 -6.21057 35.00025 -10.88384 -5.05321 34.38255 -12.56367 -5.28366 34.20457 -11.39358 -3.76551 41.83179 -10.32557 -1.58042 40.45203 -11.22837 -3.75616 41.39480 -11.07880 -1.49079 35.97550 -13.18312 -2.76720 39.88445 -11.55432 -3.60652 38.22656 -12.18830 -3.49943 39.99825 -12.45262 -0.54365 36.62261 -13.68488 -0.23199 36.00025 -3.91054 -10.86223 36.00025 -5.67979 -10.45229 36.00025 -8.87659 -8.87691 36.00025 -7.36012 -9.77795 36.00025 -7.77785 -7.77817 36.00025 -8.97281 -6.36262 36.00025 -9.91164 -4.77001 36.00025 -10.56956 -3.04591 36.00025 -10.92969 -1.23886 36.00025 -10.72610 2.43797 36.00025 -10.98286 0.60790 36.00025 11.00032 0.00000 42.00025 -9.96424 1.30748 42.00025 -9.39662 -1.40472 42.00025 7.87836 -1.39156 42.00025 -9.03509 -2.69429 42.00025 7.51684 -2.73898 42.00025 -8.43500 -3.93786 42.00025 6.92669 -4.00316 42.00025 -7.60726 -5.08039 42.00025 6.12571 -5.14584 42.00025 -6.58570 -6.06751 42.00025 5.13849 -6.13182 42.00025 -5.36798 -6.89020 42.00025 3.99485 -6.93136 42.00025 -4.01987 -7.49526 42.00025 2.73022 -7.51982 42.00025 -2.56724 -7.87046 42.00025 1.38154 -7.87986 42.00025 -1.03347 -8.00000 42.00025 0.00032 -8.00000 36.00243 -2.08998 -11.00134 36.00025 0.00032 -11.00000 36.00025 10.86488 -1.72086 36.00025 10.46189 -3.39935 36.00025 9.80128 -4.99411 36.00025 8.89931 -6.46590 36.00025 7.77821 -7.77845 36.00025 6.46557 -8.89947 36.00025 4.99391 -9.80123 36.00025 3.39927 -10.46170 36.00025 1.72095 -10.86460 39.00025 1.64007 -10.87710 39.00025 0.00032 -11.00000 39.00025 3.24445 -10.51074 39.00025 4.77550 -9.90947 39.00025 6.19860 -9.08743 39.00025 7.48293 -8.06292 39.00025 8.60061 -6.85820 38.97711 10.48833 -3.49900 39.00025 10.89241 -1.81746 40.87072 10.34581 0.00000 40.39354 10.64984 -0.00285 40.44881 9.92724 -3.46402 41.34576 9.87079 0.00000 41.69691 9.31188 0.00003 41.92503 8.66788 0.00000 40.40950 0.00075 -10.63610 39.66782 0.00032 -10.92478 41.59834 2.45910 -9.17630 41.92503 0.00032 -8.66756 41.64241 0.00280 -9.40395 40.49889 2.87802 -10.20072 41.34576 0.00032 -9.87047 40.87072 0.00032 -10.34549 41.59834 4.75032 -8.22724 40.49889 5.53952 -9.03621 41.59834 6.71784 -6.71751 40.49889 7.78487 -7.19281 41.59834 8.22756 -4.75000 41.59834 9.17661 -2.45878 39.16365 -2.79369 -10.86733 37.00700 -1.75784 -11.00000 38.00713 -1.40528 -11.00000 39.00025 -1.03347 -11.00000 40.10453 -3.96232 -10.42357 41.12244 -3.40579 -9.86750 41.79050 -3.19041 -8.87217 40.21046 -1.03285 -10.73261 39.68842 -1.03347 -10.92000 41.19122 -1.03675 -10.06106 41.74584 -1.03501 -9.19169 41.92567 -1.03347 -8.66481 42.00125 -0.71631 18.43793 42.00047 4.69463 28.63178 42.00025 4.55122 26.76699 42.00025 0.00032 18.84803 37.13560 0.00032 19.33138 42.00025 4.10720 24.95290 12.48855 0.00032 15.79746 33.23856 -20.92189 16.69963 40.06757 -16.00425 15.87180 40.76066 -15.52186 15.75184 40.22589 -16.42364 15.52244 33.35737 -19.37798 18.47001 36.38074 -17.22534 16.86727 34.80528 -18.14896 17.55972 36.71384 -18.03838 16.64430 38.09460 -16.32222 16.33483 33.58095 -19.83546 18.33452 33.70298 -20.36124 17.97835 33.54759 -20.85854 17.23243 30.69171 -22.24771 18.43513 31.62679 -21.89856 18.60092 31.84028 -21.44528 19.19135 31.80485 -20.76753 19.56403 31.41272 -21.95370 17.93778 32.26551 -19.55745 19.09028 41.25215 -11.00445 15.38837 40.64713 -11.32652 15.57718 40.52986 -9.02008 15.79778 41.13953 -8.51999 15.75000 40.40797 -6.80917 16.37211 41.01591 -6.13438 16.52873 41.58786 -5.17697 16.53330 40.38424 -4.48807 17.39216 41.93192 -4.01259 16.46580 40.92645 -3.84365 17.70301 41.23049 -3.30020 17.89991 41.47659 -2.75849 18.06087 41.81115 -1.86582 18.29766 35.71275 -9.70514 15.91655 35.29206 -10.91734 16.03664 39.14009 -13.04748 15.91205 36.25659 -12.37569 16.18197 35.09933 -11.52614 16.16334 34.11800 -13.05610 16.55863 38.58134 -14.43949 16.13064 41.26543 -14.76040 15.59119 29.34525 -16.44808 19.29173 31.47700 -15.17923 17.95151 33.81829 -18.55210 18.04124 35.41711 -17.43465 17.18345 33.03078 -13.91455 16.94667 36.99712 -16.05521 16.52681 29.02715 -17.60599 18.87496 28.50963 -18.42133 17.89616 30.80184 -16.13773 17.10027 33.63822 -12.77722 15.80504 16.99428 -9.81800 31.76485 16.69925 -10.41788 31.94674 16.30979 -10.98208 32.00584 15.84935 -11.48071 31.94181 15.35213 -11.88407 31.76527 14.83885 -12.18266 31.48938 14.32936 -12.36808 31.12731 26.16752 -19.31767 18.34896 24.82522 -19.49928 19.69126 26.32936 -19.14903 20.07642 27.02606 -18.27390 20.87606 23.48092 -19.35032 21.03556 21.39506 -18.03484 23.97550 20.94673 -18.08838 23.56975 22.17502 -18.87526 22.34147 24.09405 -18.94074 22.31174 22.80765 -17.27495 24.78395 22.34495 -17.61963 24.59529 21.90648 -17.85584 24.34606 24.97444 -18.08273 22.92768 17.42155 -19.33856 15.07412 16.14120 -18.86353 16.35448 14.93633 -18.08837 17.55934 15.52851 -17.95703 24.59624 20.26193 -19.88960 26.44862 19.21382 -18.99056 27.48279 16.93622 -16.85897 30.15846 18.19185 -18.06313 28.61580 18.99066 -17.98845 29.04794 19.74082 -17.36263 29.20479 16.33141 -15.51816 32.23310 17.21596 -14.86782 32.39306 30.56804 -19.94081 20.11284 28.39665 -17.08982 20.17259 28.93770 -20.18408 21.22098 27.43289 -17.51014 21.05082 27.35306 -20.11139 22.33945 26.40682 -17.71803 21.98104 25.85386 -19.72125 23.44511 25.32321 -17.67927 22.96891 24.46295 -19.04943 24.50940 24.25482 -17.38544 23.94786 23.00918 -19.02773 26.10271 23.14839 -16.87866 24.86744 23.19882 -18.14021 25.50321 22.34574 -16.22029 25.72816 21.27265 -17.60897 27.67948 22.07966 -17.02658 26.40910 21.59014 -15.58498 26.50463 20.15720 -16.65143 28.87076 17.49983 -14.38133 32.22543 20.96544 -14.97776 27.19388 21.12335 -15.73274 27.21871 20.37682 -14.31138 27.89104 20.01768 -13.85381 28.33471 19.66210 -13.33201 28.79596 16.91113 -19.99842 18.42204 24.66112 -22.43105 16.84361 22.50270 -22.21692 18.20885 18.23429 -20.36765 20.84407 20.40215 -21.55375 19.64542 22.79481 -21.72366 24.32345 19.74209 -20.53287 23.21113 31.13405 -20.31158 19.93935 29.80934 -22.52407 19.04909 29.85641 -20.68763 20.83751 29.93627 -21.36656 20.86927 29.86304 -22.07504 20.56565 29.12959 -22.67236 19.52594 29.57405 -22.54630 20.02339 27.99811 -22.82753 20.33092 28.59649 -20.85482 21.73914 28.03761 -21.54364 22.23439 27.85562 -22.26048 22.00522 27.48744 -22.73599 21.51742 27.17079 -22.85069 20.93241 26.17777 -22.79241 21.67210 27.13896 -20.80618 22.81973 25.20728 -22.62564 22.41556 26.18318 -21.30885 23.64078 25.89422 -22.01130 23.49060 24.43566 -22.42148 23.01668 25.44652 -22.47526 23.06169 25.65500 -20.47569 23.97180 23.60282 -22.11311 23.67620 24.21118 -19.83891 25.12654 24.41178 -20.65827 25.04418 22.83073 -19.52563 26.36698 24.02091 -21.32278 24.97269 22.36362 -20.15979 26.41168 23.50173 -21.75924 24.59905 21.24988 -20.69806 25.57819 21.68996 -20.62116 26.04126 22.01063 -21.25250 24.95750 20.78845 -4.83021 30.14515 20.66220 -5.25023 29.82250 20.44985 -5.82760 29.58581 20.26107 -6.37132 29.46358 20.02914 -7.07309 29.38226 19.77643 -7.90248 29.36014 19.56011 -8.67049 29.39127 19.40948 -9.26246 29.44418 19.25456 -9.92532 29.53010 19.10081 -10.63181 29.65855 18.94978 -11.71702 29.80161 17.11525 -13.81543 32.82055 19.11136 -12.30309 29.54571 19.37698 -12.71614 29.27194 20.37775 -0.00297 29.53154 20.79310 -0.01740 30.14642 19.14005 -0.00313 29.62202 19.71731 -0.01338 29.35699 16.27308 0.00031 32.48605 12.03045 0.00031 32.48605 6.02004 0.00031 26.47563 5.60119 0.00031 25.95040 5.30971 0.00031 25.34515 5.16022 0.00031 24.69020 5.16022 0.00031 24.01842 5.30971 0.00031 23.36347 5.60119 0.00032 22.75821 6.22134 -0.00375 22.03880 2.30026 0.00032 14.50000 2.23344 0.00032 15.05036 2.30026 0.00032 10.00000 2.03685 0.00032 15.56878 1.72190 0.00032 16.02510 1.30688 0.00032 16.39281 0.81590 0.00032 16.65052 0.27751 0.00032 16.78323 -0.27700 0.00032 16.78323 -2.29975 -2.19968 10.00000 -1.37883 -2.19331 8.50335 1.41852 -2.18136 8.50477 2.10002 -2.18630 8.88861 2.29769 -2.19447 9.43569 2.30026 -2.19968 10.00000 3.40761 -10.99969 32.26213 1.31037 -10.99969 28.35047 -0.46236 -10.99969 24.08344 15.58798 -19.62919 16.00001 14.01899 -18.14679 5.70156 15.70020 -16.39166 12.55283 14.74955 -16.04640 13.50348 13.85454 -15.47327 14.39849 7.96479 -5.69968 20.28823 6.74123 -9.81800 21.51180 6.44189 -9.49952 21.81114 6.15404 -8.86181 22.10994 6.02004 -8.07461 22.23299 15.42370 -15.28663 32.26077 12.34679 -14.95873 28.08373 8.56765 -12.45528 30.71023 6.45156 -12.39952 27.24237 9.72782 -15.05955 23.61679 13.13618 -17.59838 20.42720 4.79622 -12.34811 23.80454 7.35380 -14.73762 19.06053 3.31448 -12.27908 19.90973 11.06191 -17.03690 16.10121 13.38918 -18.54927 11.10373 5.79650 -14.29902 15.81470 2.03309 -12.17345 15.57590 2.30026 -12.41869 14.50000 9.32602 -16.29676 11.64081 11.69067 -17.19778 6.20607 4.45563 -13.76030 8.99365 2.30026 -12.71350 9.36676 7.94874 -15.40209 7.06859 2.30026 -12.66151 4.17625 2.30026 -5.99968 14.50000 2.29793 -6.49553 9.45545 1.35699 -6.49441 8.50294 -1.36301 -6.49383 8.50312 1.99340 -6.48360 8.76972 6.02004 -8.07460 26.47563 5.60269 -8.07460 25.95279 5.31731 -8.07460 25.36661 5.16495 -8.07460 24.72981 5.15527 -8.07460 24.06573 5.29752 -8.07460 23.39903 5.59000 -8.07460 22.77616 5.67436 -9.66423 22.90162 6.56361 -10.39752 21.79491 6.50046 -10.93473 22.15886 5.54018 -10.15569 23.95549 6.54932 -11.42115 22.59444 6.71143 -11.83646 23.08673 5.83148 -10.48407 25.04061 6.98741 -12.15973 23.61970 7.36413 -12.36337 24.15833 6.10162 -9.14249 26.39405 6.33935 -10.15108 26.15632 6.71724 -11.05583 25.77843 7.21442 -11.82133 25.28125 7.82302 -12.43309 24.67265 14.49035 -18.02280 17.06124 14.08940 -17.80055 16.48175 13.84051 -17.51784 16.00992 13.66921 -17.10376 15.50943 13.61620 -16.65177 15.09981 13.67642 -16.05519 14.68299 16.09159 -18.85471 14.28276 15.48012 -17.78049 13.34021 13.83343 -12.43310 30.68306 12.03045 -8.07460 32.48605 13.21518 -11.80923 31.30131 12.70999 -11.02191 31.80650 12.33751 -10.11270 32.17899 12.10930 -9.12466 32.40720 0.00017 -11.18913 19.04367 -0.07636 -11.28434 16.80126 0.51040 -11.45072 16.74271 1.36779 -11.78772 16.34721 1.75114 -11.99076 15.99144 2.55636 -11.72720 21.34207 0.96721 -11.61329 16.58686 1.51737 -11.18120 23.97203 4.38211 -11.72720 26.07352 3.53360 -11.18120 28.57726 6.74065 -11.72720 30.53659 6.07224 -11.18120 32.91625 5.79498 -8.75979 -8.48914 4.75562 -5.59203 -10.16755 5.21512 -3.95656 -10.43944 5.21100 -5.29716 -9.87301 5.21083 -6.45814 -9.39645 5.21100 -7.77663 -8.83888 5.21083 -2.71436 -8.73502 5.20335 -6.40573 -7.44081 5.21083 -1.68769 -7.07251 5.21083 -5.34324 -6.28935 5.21083 -0.88467 -5.29113 5.21083 -4.46593 -4.85772 5.21083 -0.31883 -3.42087 5.21083 -3.82337 -3.30645 5.21083 -3.43141 -1.67378 5.21083 -3.29968 0.00000 5.10653 -8.62178 -8.75725 5.56788 -9.22203 -8.36798 7.94215 -9.49526 -8.74051 4.67872 -7.97769 -9.10891 4.65165 -6.42327 -9.95996 4.67074 -4.85293 -10.53828 4.77767 -3.38496 -10.84128 4.68751 -1.54675 -8.49245 4.52895 -2.93278 -10.93212 2.01772 -6.48097 1.21031 1.40157 -6.49028 1.49474 -2.29975 -6.49968 0.00000 0.00025 -6.49968 1.50000 0.00025 -6.49968 0.00000 5.21083 0.00032 0.02374 2.30025 -3.94129 -10.59821 2.30025 -1.96335 -10.94992 2.30025 -5.81076 -9.92661 2.30025 -7.52813 -8.95549 2.30028 -0.53686 -8.14925 2.30025 -9.04393 -7.71366 2.30025 -10.29997 -6.25601 2.30025 -11.27331 -4.62133 2.30026 -11.93863 -2.86299 2.31554 0.01654 -3.92799 2.29917 -6.49742 0.52470 7.08376 -13.40058 -2.55378 4.55497 -12.84383 -1.73479 2.30026 -12.28110 -1.05125 6.95038 -14.37706 2.40711 3.51229 -13.13803 3.88574 17.23772 -3.05346 -10.96484 17.22123 -1.64601 -8.41793 16.19582 -6.67250 -7.99257 16.20164 -3.87406 -8.52431 16.19854 -5.91443 -7.05483 16.20295 -5.21217 -6.09825 16.20301 -3.46626 -7.26002 16.21576 -4.45627 -4.43459 16.20633 -3.06177 -5.94199 16.20823 -2.70407 -4.54707 16.20252 -3.79117 -2.54031 16.20536 -2.43660 -3.05217 16.19454 -3.58016 -1.05027 16.22372 -3.54935 -0.03475 16.19878 -2.29308 -1.47719 16.20554 -2.27144 0.00000 16.18242 -3.40822 -11.02234 16.20020 -2.61073 -9.88014 16.24841 -1.38861 -7.11042 16.20554 -8.50857 -9.78224 13.68469 -14.26965 -4.67986 10.07449 -13.24681 -5.12991 10.33482 -12.33418 -6.62455 13.77124 -13.24650 -6.43772 10.65601 -11.20818 -7.94220 11.03062 -9.83635 -9.10342 14.00948 -11.86053 -8.03451 15.68676 -10.02945 -9.58227 13.70732 -10.13295 -9.30498 16.19149 -7.38475 -10.66328 16.37179 -9.38429 -9.92920 9.88299 -13.91818 -3.49885 15.15664 -16.66497 0.00675 10.51843 -15.63732 1.33570 12.79545 -16.31463 0.77952 0.00025 -2.19968 1.50000 1.40112 -2.19185 1.49555 1.91201 -2.18626 1.29956 2.28986 -2.16860 0.71338 2.28722 -1.81631 -0.79531 0.00025 -2.19968 0.00000 2.27369 -2.19633 -0.16033 2.29455 -1.26716 -0.99756 -2.31627 -2.09971 -0.45267 17.70000 8.17118 -6.31601 17.46791 10.46586 0.40569 17.63077 10.52348 0.25819 18.27831 10.98081 1.47328 17.80645 10.63646 -0.01972 18.09589 10.91687 0.92456 17.94184 10.79483 0.38151 17.64867 10.12079 -0.44574 17.70586 10.24945 -2.09050 17.70026 9.79379 -3.02495 17.70000 9.01431 -5.27042 17.70000 9.62212 -4.30024 17.70026 9.00032 -3.32455 17.69255 9.02092 -0.82216 17.15031 0.00032 0.00000 17.58226 0.00032 -4.95371 17.22123 -0.61647 -5.65773 17.21782 0.00058 -2.76681 16.29574 0.01833 0.00993 16.26741 -0.45891 -4.49720 16.20050 0.00032 -1.73224 16.20426 -0.28531 -3.35202 16.75961 6.80614 0.12598 17.91330 7.12353 -8.09598 17.91993 4.97721 -9.56275 17.91993 2.56215 -10.47151 17.83099 10.86485 1.34915 17.28860 10.70415 0.94975 16.71546 9.70102 0.11945 17.68258 0.41522 -10.32301 17.70026 1.74768 -10.09996 17.70026 2.74612 -9.87538 17.70026 -1.22318 -9.62565 17.70026 3.79540 -9.52155 17.70026 4.86644 -9.02127 17.70026 5.92604 -8.36351 17.70026 -0.55721 -8.19759 17.70071 6.93745 -7.57631 17.70026 0.00032 -6.72384 17.69897 6.92263 -0.90658 17.70000 6.04312 -0.72010 17.70026 5.18110 -0.25902 18.28079 10.77432 -2.24156 18.28946 10.09972 -4.35492 18.28100 9.49011 -5.56272 18.28100 8.71467 -6.71269 18.28100 7.47546 -8.13674 18.45026 5.90116 -9.28333 18.45026 4.61769 -9.98397 18.45026 3.34297 -10.47982 18.45026 2.12328 -10.79319 18.45026 0.99835 -10.95463 3.23595 9.18400 -0.00043 16.70025 9.00032 0.00000 3.21558 7.33902 0.00956 18.33503 10.99501 -0.00135 18.43223 10.99463 1.94478 3.26448 10.99998 1.82654 3.17098 10.89998 1.30252 17.70025 0.00032 0.00000 26.31675 0.00470 11.43305 37.50025 0.00032 21.00000 8.00662 0.00032 20.25200 37.40801 0.00032 20.14593 26.40025 0.00032 6.00000 26.40025 11.00032 0.00000 26.40025 1.72095 -10.86460 26.40025 3.39927 -10.46170 26.40025 4.99391 -9.80123 26.40025 6.46557 -8.89947 26.40025 7.77821 -7.77845 26.40025 8.89931 -6.46590 26.40025 9.80128 -4.99411 26.40025 10.46189 -3.39934 26.40025 10.86488 -1.72086 -0.81539 0.00032 16.65052 -1.30637 0.00032 16.39281 -1.72139 0.00032 16.02510 -2.03634 0.00032 15.56878 -2.29975 0.00032 10.00000 2.61186 10.99627 0.89393 -3.23746 10.99975 1.76076 -0.05217 10.99998 3.21228 -21.20044 10.99998 11.01760 -33.80920 11.00183 14.35474 -2.31910 -1.65903 -0.89958 -2.30683 5.29970 -0.98680 2.30025 0.00032 -1.00000 2.30887 7.50036 -0.98330 -2.32838 9.09664 -0.96652 2.34565 9.21986 -0.94771 3.30625 9.92307 0.20287 16.80244 10.21738 0.39946 3.30676 10.56971 0.72336 -2.48352 10.76608 0.16776 2.30311 9.91917 -0.77643 -2.32170 10.08648 -0.69673 2.54243 10.73518 0.23922 2.55547 7.50180 -0.29983 2.60148 8.99936 -0.25305 2.59315 9.78928 -0.15288 3.40026 0.00032 0.00000 5.15499 0.00226 -2.32482 5.07386 0.00032 -3.17214 4.39345 0.02717 -3.11124 4.96766 -0.61587 -5.85920 17.31603 10.44393 0.51952 17.18981 9.87308 0.04523 17.26482 9.02818 -0.14886 41.70798 3.88144 30.84089 41.23909 3.51172 30.85783 40.68318 3.30035 30.86492 41.67065 2.00021 22.58901 40.82568 1.72519 23.15766 41.67065 3.29589 25.50531 41.61946 3.73011 28.65680 40.82568 2.83887 25.81909 40.92420 3.26715 28.67481 37.50006 3.92558 32.07094 37.50021 3.75936 32.92620 37.50026 3.23185 35.25445 37.50909 3.57046 33.79903 40.09034 3.37438 30.86365 37.50025 2.19422 22.05424 37.40435 0.73243 20.14508 39.83923 2.33243 24.11969 39.83923 2.94015 25.74439 37.50025 3.32473 24.15276 38.71609 3.23855 25.05828 39.83924 3.25593 27.19051 37.49462 3.94249 26.10386 40.01752 3.32974 28.77477 37.50026 4.21362 27.70216 38.53032 3.82532 31.03299 37.50026 4.26847 29.53542 37.50026 4.06082 31.35496 17.34274 6.79722 -0.13387 17.06789 10.45824 0.64087 42.00000 4.60716 30.81112 -15.61547 11.00031 37.17566 41.94769 0.00032 19.36700 38.07147 0.00032 19.68669 41.71842 -0.00575 20.01340 38.97182 0.00032 20.13456 39.72058 0.01237 20.58066 41.14101 -0.02315 20.67498 40.32361 -0.00980 20.87783 37.50026 0.00031 43.27423 40.88453 0.00680 45.22026 33.25978 0.00031 41.06781 39.00605 10.99998 50.90359 42.00026 -3.32900 61.75028 42.00026 -2.68931 58.80986 42.00026 -2.01866 56.14603 42.00026 -1.33825 53.73418 42.00026 -0.66312 51.54675 42.00000 0.01941 49.44596 42.00026 0.90463 46.98812 42.00026 1.27223 45.99088 42.00026 2.64223 42.40155 42.00026 3.26882 40.78413 42.00026 3.80804 39.20901 42.00026 4.26056 37.45741 42.00000 4.41831 35.70791 40.77634 1.29834 41.78915 37.50026 2.06831 38.47019 37.50026 2.36053 37.78061 39.12905 2.10223 39.00675 40.75076 1.88919 40.25132 37.50026 1.77210 39.16007 40.80231 0.65552 43.46875 37.50026 1.47398 39.84914 37.50026 1.17579 40.53640 37.50026 0.87904 41.22108 37.50026 0.58421 41.90436 37.50026 0.29134 42.58809 37.86468 -1.28829 46.67346 40.95145 -1.31296 49.00164 40.88810 -2.05795 51.15122 40.90550 -2.78022 53.51790 40.92114 -3.49185 56.08374 40.93563 -4.22286 59.06838 38.00026 -4.32987 56.00669 40.94827 -4.89696 62.31456 40.99276 -6.27097 69.45977 39.56744 -6.94584 69.68526 34.57989 -2.49604 47.51219 31.27980 -8.57772 66.95869 31.61232 -6.53616 57.16276 40.39569 3.10140 35.40694 39.23923 3.58346 31.84345 40.61332 2.37786 38.01182 37.50026 2.82658 36.56092 40.81791 3.10269 35.64899 41.35299 2.08151 40.32795 41.38855 3.32110 35.68161 41.89888 2.68740 40.56076 41.78449 3.78594 35.75152 41.42602 0.11571 45.58865 41.92104 0.68990 45.90020 34.05500 -10.99969 74.02666 40.05586 -10.39787 74.10013 39.10843 -10.81996 74.49616 36.98519 -10.49187 73.65433 40.50635 -9.57438 73.47955 34.98815 -10.54967 73.19110 40.75598 -9.05269 73.03568 33.17701 -10.60156 72.65685 40.74006 -8.17370 72.10387 33.82185 -9.33063 71.18475 40.78117 -7.47096 71.16954 40.90627 -6.78083 70.13556 33.58817 -8.44890 69.18834 41.62707 -0.92331 48.99154 41.68417 -3.34011 57.58210 41.73455 -5.01147 66.37407 41.13453 -8.96965 73.12192 41.55864 -6.34840 70.15401 41.40157 -8.82005 73.27260 41.60799 -8.70256 73.39328 41.87943 -5.99443 70.34272 41.74710 -8.55435 73.54313 41.88245 -8.39852 73.70244 41.01022 -9.77275 73.81819 35.06305 -10.90893 73.79314 -10.39859 0.00693 33.55040 -9.72471 0.00914 33.46120 -9.21055 0.02211 33.70504 -3.90136 0.00031 41.24135 -19.54399 11.00031 39.92645 -34.39244 11.00066 18.74107 -9.87971 11.00031 45.36718 4.37943 10.99998 41.38831 -16.99974 11.00031 50.35270 -19.99974 0.57544 58.42723 -19.99974 -0.62254 58.42270 -19.99974 -1.83460 58.18477 -19.99974 -3.07323 57.68963 -19.99974 -4.33871 56.89842 -19.99974 -5.60764 55.77402 -19.99974 -6.84118 54.29290 -19.99974 -7.99843 52.44462 -19.99974 1.78033 58.20071 -19.99974 3.01323 57.72005 -19.99974 4.28182 56.94114 -19.99974 5.56375 55.81977 -19.99974 6.81651 54.32781 -19.99974 7.99879 52.44454 -19.94339 8.57903 52.41385 -19.76470 9.16436 52.28873 -19.45675 9.72167 52.07311 -19.01309 10.22437 51.76245 -18.43685 10.63370 51.35896 -17.75019 10.90493 50.87816 -20.97570 6.66662 53.13668 -21.76647 5.15921 53.69040 -22.34637 3.51567 54.09644 -22.70031 1.77899 54.34427 -22.81889 -0.00457 54.42730 -22.69871 -1.79026 54.34315 -22.34294 -3.52745 54.09404 -21.76038 -5.17257 53.68612 -20.96898 -6.67675 53.13198 -34.89827 10.93751 20.04466 -21.02757 10.85019 40.96526 -35.94353 10.52684 22.15638 -22.47069 10.40390 41.97574 -23.83393 9.67363 42.93029 -36.26926 10.29696 23.00828 -36.98425 9.50867 24.39764 -37.54630 8.92159 25.43555 -25.08009 8.67930 43.80286 -37.79276 8.57469 25.87786 -38.32590 7.55097 26.86637 -26.17513 7.44804 44.56963 -38.86015 6.57738 27.71235 -27.08917 6.01347 45.20964 -39.62720 5.08638 28.24946 -27.79724 4.41473 45.70544 -40.18956 3.46510 28.64323 -28.28000 2.69548 46.04348 -28.60279 0.00031 46.16705 -28.44713 -2.03133 46.05942 -27.98740 -3.99307 45.73752 -27.15089 -5.95878 45.22412 -26.18835 -7.46677 44.55591 -25.04080 -8.75295 43.74731 -23.81610 -9.68477 42.91781 -22.44876 -10.41244 41.96039 -21.00856 -10.85341 40.95195 -19.55254 -11.00203 39.92435 -3.97840 -2.99969 41.23504 -6.78160 8.39193 43.19787 -12.98907 0.00031 47.54439 -7.71932 9.42093 43.85447 -5.94083 7.17651 42.53284 -3.97840 -10.99969 41.23504 -16.99974 -10.99969 50.35269 -17.49796 -10.95803 50.70154 -17.99345 -10.83033 51.04849 -18.44906 -10.62637 51.36751 -18.85875 -10.35427 51.65438 -8.75665 10.29449 44.58081 -19.22317 -10.01373 51.90955 -19.54042 -9.59498 52.13169 -19.78990 -9.10196 52.30639 -19.94936 -8.54718 52.41803 -11.19383 6.33192 34.07961 -10.53331 -10.99969 33.61710 -10.50889 4.72718 33.60001 -13.11352 9.07640 35.42378 -14.30466 10.15367 36.25784 -19.54399 0.00031 39.92645 -12.06864 7.79271 34.69215 -5.21253 5.84098 42.12601 -4.69914 4.61927 41.82664 -9.84612 3.17395 33.60001 -4.37969 3.41569 41.53366 -4.11728 2.24397 41.40826 -9.45415 1.59322 33.60001 -4.00320 1.10051 41.28574 -30.48229 -11.00002 24.31037 -0.27107 -10.99969 68.60693 -2.66889 -10.99969 58.10773 14.65039 -10.99969 57.10164 11.95373 -10.99924 54.07259 11.26303 -11.00247 52.76604 10.93462 -11.00078 51.02586 10.92849 -10.99944 48.99999 11.21852 -10.99969 46.78522 11.69197 -10.99969 44.64636 12.28615 -10.99969 42.55486 8.89405 -10.99969 39.42823 -9.14861 -11.00002 33.85215 5.89719 -10.99969 35.93079 -9.23438 -10.99969 31.98065 -10.03276 -11.00002 33.42924 -9.56210 -11.00002 33.51434 9.64666 -11.72720 34.63951 9.14133 -11.18120 36.89913 -9.14059 -2.99969 33.86267 -2.59805 5.30170 -0.25484 -2.55236 8.99997 -0.30389 -2.59264 9.78984 -0.15267 -16.47413 10.36967 0.38117 -15.65766 9.70758 -0.00211 -15.94733 9.65974 -0.31978 -14.94063 8.91659 -0.05852 -15.17003 8.85892 -0.15302 -15.33845 8.81154 -0.32358 -15.48324 8.77052 -0.51663 -15.54072 8.75496 -0.66610 -15.08167 7.93320 -0.17256 -15.41384 7.93282 -0.57848 -15.24522 5.30287 -0.29857 -16.91968 10.57752 -0.00234 -17.79844 10.99998 -0.00251 -15.55918 8.56459 -0.96405 -15.88354 9.44507 -0.80491 -15.90167 8.69561 -3.82647 -16.91649 9.68695 -3.50190 -15.90167 6.98317 -6.44125 -17.00111 7.33618 -7.64990 -15.90167 4.51484 -8.35877 -17.00111 4.69491 -9.50245 -15.90167 1.55781 -9.37146 -17.00111 1.61866 -10.47457 -17.00111 -1.60754 -10.47620 -15.90167 -1.56781 -9.36968 -3.30688 9.55089 0.05247 -15.34548 9.84637 0.19977 -3.30590 10.27285 0.43030 -15.92924 10.33615 0.42252 -17.27900 10.99998 1.29352 -3.30505 10.99998 1.06111 -18.50000 10.34273 -3.49773 -18.49975 8.53493 -6.93976 -18.49975 7.30819 -8.22161 -18.49975 5.89133 -9.28956 -18.49975 4.32120 -10.11582 -18.49975 2.63864 -10.67892 -18.49975 0.88750 -10.96417 -18.49975 -0.88677 -10.96417 -2.29975 -1.19968 -1.00000 -2.29975 4.68862 -0.95294 -14.65761 8.99585 -0.00238 -14.53943 8.47437 0.00048 -14.58253 7.93702 -0.00659 -3.21332 9.00074 0.00555 -14.58696 5.30010 0.00507 -3.19026 5.30140 0.00492 -15.49975 -0.00600 -7.99999 -15.49975 1.43289 -7.87068 -15.49975 2.82533 -7.48459 -15.49975 4.12550 -6.85439 -15.49975 5.29115 -6.00059 -15.49975 6.28421 -4.95102 -15.49975 7.07219 -3.74014 -15.49975 7.62971 -2.40674 -15.49975 7.93757 -0.99999 -15.49562 5.30014 -0.88210 -15.49975 0.08440 -0.89750 -21.19975 -10.99968 0.00000 -21.19975 10.85058 -1.80882 -21.19975 -10.84930 -1.81268 -21.19975 10.40543 -3.56842 -21.19975 -10.40283 -3.57412 -21.19975 9.67698 -5.23089 -21.19975 -9.67123 -5.24035 -21.19975 8.68505 -6.75095 -21.19975 -8.67606 -6.76168 -21.19975 7.45665 -8.08721 -21.19975 -7.44421 -8.09809 -21.19975 6.02522 -9.20329 -21.19975 -6.00708 -9.21472 -21.19975 4.42972 -10.06877 -21.19975 -4.40793 -10.07806 -21.19975 2.71362 -10.66010 -21.19975 0.92363 -10.96118 -21.19975 -2.68749 -10.66656 -21.19975 -10.99968 12.00000 -21.19975 11.00032 0.00001 -18.49975 11.00032 0.00001 -2.69517 11.00598 1.04604 -21.28766 0.02173 11.85503 -21.20026 0.00145 11.01392 -21.19975 -0.89245 -10.96371 -15.53830 -5.19961 -0.89828 -15.49975 -7.63069 -2.40161 -15.54911 -8.07651 -0.98458 -15.49975 -7.07442 -3.73471 -15.49975 -6.28827 -4.94506 -15.49975 -5.29690 -5.99495 -15.49975 -4.13314 -6.84941 -15.49975 -2.83463 -7.48085 -15.49975 -1.44397 -7.86854 -2.25981 -2.41399 0.05523 -2.29975 -1.64968 10.00000 -18.50000 -10.25767 -3.32631 -18.49975 -10.97317 -0.76321 -18.49975 -10.99968 0.00000 -18.49975 -8.53429 -6.93977 -18.49975 -7.30755 -8.22161 -18.49975 -5.89069 -9.28955 -18.49975 -4.32055 -10.11584 -18.49975 -2.63804 -10.67891 -17.27788 -10.65702 0.00003 -17.36909 -10.78195 0.72198 -17.00000 -9.92136 -3.43190 -16.07855 -9.68662 -0.56021 -16.69233 -10.37179 0.09989 -15.90167 -8.69931 -3.81660 -17.00000 -9.28786 -5.08864 -15.90167 -6.98984 -6.43331 -17.00111 -7.32789 -7.65723 -15.90167 -4.52369 -8.35363 -17.00111 -4.68476 -9.50714 -2.28917 -2.16863 9.28612 -1.91132 -2.18628 8.70035 -2.30004 -11.00044 14.49992 -17.60893 -10.97441 1.55585 -2.29975 -10.99968 2.00000 -2.01710 -6.48071 8.78909 -2.29892 -6.49807 9.48267 -14.49975 -6.33126 0.00000 -3.29975 -5.19968 0.00000 -14.66082 -7.92152 0.00184 -14.67584 -8.98036 -0.00246 -2.29975 -8.99968 0.00000 -2.29975 -10.90406 1.38899 -2.29975 -10.61666 0.82298 -2.29975 -10.17759 0.38367 -2.29975 -9.61116 0.09577 -15.35954 -9.81387 0.16855 -16.29393 -10.41649 0.56215 -16.80311 -10.67837 0.91532 -15.30478 -8.81331 -0.28651 -15.68901 -9.70580 -0.04810 -15.13338 -7.93045 -0.23264 -15.10497 -5.20571 -0.14487 -22.15526 0.00736 11.99910 -33.79974 11.00032 0.00001 -30.79975 11.00032 0.00001 -30.79928 10.99949 11.01066 -22.16006 10.99998 11.99840 -29.84198 10.99384 11.99812 -30.59873 10.98676 11.61279 -33.88254 11.00032 15.89547 -34.09110 11.00032 17.35023 -36.79974 -0.00779 -7.99999 -36.79974 -1.39740 -7.87694 -36.79974 1.38282 -7.87963 -36.79974 2.73173 -7.51926 -36.79974 -2.74417 -7.51450 -36.79974 3.99724 -6.92997 -36.79974 -4.00772 -6.92355 -36.79974 5.14114 -6.12959 -36.79974 -5.14931 -6.12219 -36.79974 6.12841 -5.14261 -36.79974 -6.13455 -5.13452 -36.79974 6.92918 -3.99884 -36.79974 -6.93295 -3.99121 -36.79974 7.51870 -2.73384 -36.79974 -7.52079 -2.72634 -36.79974 7.87958 -1.38464 -36.79974 -7.88005 -1.37831 -36.79974 -7.99968 0.00001 -36.79974 8.00032 0.00001 -36.81443 -0.00809 12.38539 -36.80211 -3.57614 12.74254 -36.79083 -7.04813 13.76281 -36.79802 -8.00355 14.36795 -36.79670 3.53228 12.70869 -36.79967 7.13470 13.80729 -36.79974 8.00032 14.35488 -30.79856 -11.00002 11.02333 -30.79975 -10.99968 0.00000 -30.79975 -10.84952 -1.81137 -30.79975 10.85039 -1.80994 -30.79975 10.40469 -3.57057 -30.79975 -10.40324 -3.57295 -30.79975 9.67536 -5.23388 -30.79975 -9.67312 -5.23685 -30.79975 8.68226 -6.75453 -30.79975 -8.67907 -6.75782 -30.79975 7.45247 -8.09107 -30.79975 -7.44809 -8.09452 -30.79975 6.01951 -9.20702 -30.79975 -6.01360 -9.21047 -30.79975 4.42244 -10.07197 -30.79975 -4.41473 -10.07508 -30.79975 2.70481 -10.66234 -30.79975 -2.69563 -10.66450 -30.79975 -0.90320 -10.96282 -30.79975 0.91344 -10.96202 -29.86834 -11.00002 11.99649 -33.79974 -10.99968 0.00000 -33.79974 -10.47466 -3.50000 -33.79974 -8.52034 -6.95690 -33.79974 -7.29403 -8.23361 -33.79974 -5.87881 -9.29708 -33.79974 -4.31131 -10.11978 -33.79974 -2.63219 -10.68035 -33.79974 -0.88477 -10.96432 -33.79974 0.88549 -10.96432 -33.79974 2.63279 -10.68035 -33.79974 4.31196 -10.11976 -33.79974 5.87945 -9.29708 -33.79974 7.29467 -8.23361 -33.79974 8.52097 -6.95689 -33.80000 10.20262 -3.50128 -33.79974 10.97460 -0.75180 -35.39380 10.77261 21.17247 -40.53284 1.75501 28.88359 -40.64822 0.00008 28.96439 -40.53275 -1.75507 28.88353 -40.18940 -3.46507 28.64311 -39.62696 -5.08633 28.24928 -38.85982 -6.57728 27.71213 -37.50930 -8.97024 25.36487 -36.64715 -8.81307 26.97615 -35.21536 -9.88050 25.97359 -35.78766 -10.70378 22.41512 -33.65039 -10.60402 24.87779 -34.58218 -10.99969 19.69899 -39.02973 4.63813 17.88104 -38.32103 7.12673 19.06549 -38.93689 7.18572 20.70181 -38.75257 2.72742 17.02576 -39.97427 3.83272 18.59786 -40.54150 5.53276 21.42246 -38.65963 8.35522 23.49710 -40.50451 5.92099 24.85538 -38.76624 8.03745 24.72670 -40.83186 2.04116 19.19834 -38.70994 -0.01001 16.61257 -41.76626 2.94589 22.28004 -41.63396 3.10566 25.64623 -42.02340 0.00708 25.91892 -42.19225 0.00362 22.57833 -41.12955 -0.00178 19.40678 -41.63728 -3.09212 25.64855 -41.76810 -2.93905 22.28134 -40.83067 -2.04447 19.19751 -38.65361 -2.75281 16.83338 -40.51082 -5.90924 24.85980 -40.34552 -5.52707 21.42490 -39.97205 -3.83528 18.59630 -39.45963 -7.33046 24.22604 -38.28183 -8.52112 24.55591 -38.99642 -6.80644 20.06092 -38.72624 -8.31356 23.17014 -38.64497 -5.09668 17.59837 -38.54078 -6.84553 19.16334 -36.82760 6.86990 14.41475 -37.17046 8.97825 18.08128 -36.94878 0.00125 13.50852 -36.88181 3.44134 13.53779 -36.99055 6.43146 15.16719 -37.03085 3.32365 14.13066 -37.36453 0.00043 14.74739 -37.29959 8.25182 17.84787 -37.22893 3.20819 14.71187 -37.27509 6.01377 15.88422 -37.49868 3.09749 15.26969 -37.46149 8.89192 19.55737 -38.01134 -0.00703 15.81520 -37.57735 5.71607 16.39530 -37.59179 7.81341 18.20928 -37.81487 2.99184 15.80113 -37.87581 8.75508 20.77563 -37.72676 9.17571 21.41618 -37.93076 5.43082 16.88494 -37.93949 7.38716 18.56073 -38.15658 8.82061 23.43724 -38.32058 2.86247 16.45827 -38.29770 8.20162 20.97428 -38.23787 8.66316 24.26986 -38.35055 5.17675 17.32110 -37.87741 8.82850 25.08818 -36.39843 -9.49824 0.00001 -36.69753 -8.77614 0.00001 -35.29974 -10.59776 0.00000 -34.57621 -10.89746 0.00000 -36.39861 -8.92548 -3.24872 -35.92107 -10.12100 0.00000 -36.39861 -7.27606 -6.10560 -35.29974 -7.48949 -7.49813 -36.39861 -4.74900 -8.22605 -35.29974 -4.80793 -9.44456 -36.39861 -1.64910 -9.35433 -35.29974 -1.65636 -10.46778 -35.29974 1.65716 -10.46775 -36.39861 1.64974 -9.35433 -35.29974 4.80872 -9.44449 -36.39861 4.74964 -8.22605 -35.29974 7.49025 -7.49800 -36.39861 7.27670 -6.10560 -35.30000 9.69700 -3.48610 -36.39861 8.92612 -3.24872 -36.72453 8.66788 0.00001 -36.47666 9.34764 -0.00175 -36.14523 9.87079 0.00001 -35.67022 10.34581 0.00001 -35.19560 10.63941 -0.00103 -34.46731 10.92510 0.00001 -34.93652 10.77807 14.35292 -35.58376 10.41524 14.35459 -36.21264 9.77333 14.35911 -36.54551 9.21337 14.35887 -36.74974 8.52429 14.35802 -35.68760 10.64610 18.53470 -36.53004 10.03759 18.28289 -36.51375 10.32512 21.99279 -36.95128 10.04975 21.78611 -37.38790 9.67667 21.55380 -30.54963 -11.00002 11.66703 -34.03627 -10.99969 16.91241 -33.79976 -10.99968 14.35430 -36.85474 -0.00069 12.86618 -36.83413 -6.80393 14.48792 -36.85308 -8.25110 15.52941 -36.85374 -3.46387 13.32596 -36.98067 -3.33462 13.98189 -37.07059 0.00082 13.92410 -36.94965 -8.46890 16.47707 -36.98058 -6.44915 15.09952 -37.21180 -8.51306 17.67779 -37.17058 -6.12276 15.66230 -37.26193 -3.17345 14.80018 -37.16951 -8.87374 17.99792 -37.42837 -9.10094 19.63635 -37.50796 -5.75593 16.29498 -37.60750 -7.75384 18.23819 -37.65326 -3.02726 15.54314 -37.73828 -9.15561 21.34811 -37.91945 -5.42590 16.86414 -38.33669 -8.16650 21.07707 -38.10238 -2.90063 16.18632 -38.15025 -7.16990 18.72191 -38.38188 -5.17725 17.33242 -38.70362 -7.76277 21.09305 -36.79264 -10.16235 21.86770 -35.07729 -10.92664 19.09569 -35.45325 -10.78913 18.51328 -35.89947 -10.55703 18.41645 -37.38953 -9.68077 21.55745 -36.47078 -10.08791 18.29237 -37.06798 -9.19611 18.17721 -34.48074 -10.91786 14.35772 -34.34378 -10.99937 17.05172 -35.15562 -10.66385 14.35444 -35.06882 -10.81567 16.93250 -35.53715 -10.59231 16.85389 -35.98821 -10.04511 14.35748 -36.15683 -10.12153 16.75027 -36.41797 -9.45354 14.35339 -36.76658 -9.26479 16.64902 -36.69753 -8.77615 14.35431 -35.29974 -9.68938 -3.36010 -2.29974 -11.00234 16.69960 -1.44589 -11.04272 16.30637 -2.29974 -10.99968 17.78291 -1.46361 -10.99969 21.00946 -2.29974 -1.03093 14.50000 -21.40210 10.99998 11.61420 -2.29974 0.00032 14.50000 -2.23293 0.00032 15.05036 13.08471 -11.72125 38.31503 14.12754 -11.52959 38.50729 12.68278 -11.15350 40.65638 13.74406 -10.89054 40.62271 15.60446 -9.66423 32.83173 14.55059 -10.15569 32.96590 13.46548 -10.48407 32.67461 12.53120 -10.58549 31.98529 15.75026 -8.07460 32.90340 15.16408 -8.07460 33.18877 14.52727 -8.07460 33.34113 13.86319 -8.07460 33.35080 13.19649 -8.07460 33.20856 12.57363 -8.07460 32.91608 16.27308 -8.07461 32.48605 16.32271 -8.59969 32.43642 16.57858 -9.28281 32.18708 10.92894 -12.52152 33.74552 14.00826 -13.53416 34.81595 13.47464 -12.60679 36.32713 16.81638 -15.27418 32.40680 15.12647 -14.03560 34.29334 14.01890 -12.66681 36.52951 14.52405 -12.49547 36.58097 15.84711 -13.60443 34.37605 15.89327 -12.56954 34.95237 11.36593 -10.94797 48.99925 31.13271 -10.95601 72.55887 27.47768 -10.76175 70.15973 30.11902 -10.68794 71.44340 23.74240 -11.00002 68.45868 27.24411 -11.00002 70.83820 28.51817 -10.99969 71.69499 30.14903 -10.99969 72.51250 31.98543 -10.99969 73.29703 14.98376 -10.93201 56.80616 18.00202 -9.76163 55.00232 17.00939 -11.00269 59.61674 24.42076 -4.89193 45.53317 18.99706 -11.00134 62.17648 20.79791 -11.00002 64.63757 22.00057 -11.00002 66.67688 27.69250 -4.34221 46.92801 22.76087 -10.99969 67.55106 25.00082 -8.35501 56.99504 26.29809 -10.03401 67.49997 31.16720 -3.36012 47.48281 12.53987 -10.94118 54.14969 14.72139 -9.78387 51.55350 20.36497 -6.03566 44.81443 17.58012 -7.99503 48.14509 22.39955 -4.32243 42.36769 25.44507 -0.81405 36.97451 24.71200 -1.22857 36.98088 24.01040 -1.59847 36.81342 11.73357 -10.92608 52.60122 11.55999 -10.87983 50.93764 15.86816 -8.36230 46.51120 23.36963 -1.92981 36.48373 20.13634 -4.13406 40.55922 22.83476 -2.21207 36.02043 22.43384 -2.43179 35.46378 11.70368 -10.78236 49.00004 12.63184 -10.60558 45.06303 12.07336 -10.70185 47.10021 14.39754 -9.20448 44.82515 21.78853 -2.89039 34.14164 13.97252 -10.52930 40.97762 13.67023 -10.47681 41.96799 13.28852 -10.51060 43.04075 18.38548 -6.26749 37.94861 21.33570 -3.40360 32.89510 20.99578 -4.04728 31.53897 14.26397 -10.65805 39.96035 15.06748 -11.44301 37.17268 14.81115 -11.12672 38.02728 14.54371 -10.86076 38.96341 17.21881 -8.33919 35.85537 15.31516 -11.79939 36.40387 16.64741 -13.38308 33.52111 16.77633 -10.93123 34.08897 21.10985 0.00031 32.06593 21.65439 0.00031 33.81062 22.43384 0.00031 35.46378 22.77413 0.00031 35.95178 23.20424 0.00031 36.36321 26.92183 -0.00352 36.82514 15.74787 0.00031 32.90489 12.55568 0.00031 32.90489 15.14261 0.00031 33.19637 14.48767 0.00031 33.34586 13.16094 0.00031 33.19637 13.81588 0.00031 33.34586 23.70720 0.00031 36.68166 25.15811 0.01660 37.00173 24.26314 0.00031 36.89453 41.21310 9.19201 96.43330 40.07596 9.96326 98.56781 41.37939 9.46742 96.43924 38.56969 9.80370 99.67536 39.20652 9.69696 99.05482 39.80162 9.56087 98.36475 40.29893 9.41038 97.67665 40.70426 9.25230 97.00842 41.22685 8.93964 95.81378 38.71717 10.68463 99.70127 39.37949 10.57362 99.05590 39.99857 10.43204 98.33804 40.51579 10.27552 97.62236 39.39767 11.04699 97.44498 40.93732 10.11112 96.92741 39.74244 11.04698 96.20253 41.27328 9.94482 96.26660 41.27329 10.02495 95.04327 39.84858 11.04698 95.04391 39.77678 11.04697 94.01063 41.13099 5.74386 90.32433 39.37206 7.94142 90.84270 39.81881 7.94142 91.62482 40.13819 7.94142 92.36639 40.35844 7.94142 93.06497 41.13102 7.19214 93.23296 42.00056 7.30184 92.42417 42.00056 6.94657 91.57980 42.00056 6.38827 90.62457 42.00056 8.25571 93.05316 42.00056 7.70610 93.46570 41.99392 8.32860 93.39331 41.98137 8.65396 94.05002 39.50283 11.01932 91.70681 39.34713 11.17865 92.90418 38.87627 11.27726 91.90456 41.37984 8.73646 95.12651 40.57038 8.64119 95.29340 41.55681 8.56278 94.71519 40.94661 8.50667 94.93190 41.33031 8.34255 94.60554 41.92306 8.79775 92.93053 41.80856 9.32990 94.73645 41.94539 8.88449 94.20363 41.75210 9.44767 94.97076 41.80140 9.23127 95.04590 41.80298 7.58719 93.89459 41.67596 7.07942 93.26062 41.68114 5.63812 90.39952 40.72712 7.83903 94.26450 41.59571 8.83116 95.13353 41.77270 8.65637 94.63448 41.74747 9.00930 95.10451 41.95660 8.26940 94.08394 41.37669 7.53031 93.96103 41.69064 8.16196 94.33179 40.49448 7.94157 93.72603 37.73840 11.17530 88.88427 34.03556 8.49697 87.00079 39.76155 5.63631 88.40635 25.58867 1.43357 87.00079 24.87012 1.27291 87.70229 24.87012 -0.00303 87.59161 25.15486 -0.00303 87.29073 25.45073 -0.00303 87.00079 24.87012 2.37196 87.98257 25.99651 2.81535 87.00079 26.65270 4.08412 87.00079 27.50056 5.99697 87.00079 28.00056 6.96932 88.11702 31.96557 8.49697 87.00079 35.42382 7.14735 87.00079 34.05057 7.94142 87.46532 34.05057 7.47344 87.00079 35.60876 7.94142 87.85355 36.69345 6.58200 87.00080 37.99923 5.63255 87.00080 39.93123 2.91600 87.00080 38.95287 4.64133 87.00080 40.36637 1.65375 87.00080 40.55040 -0.00303 87.00080 40.84626 -0.00303 87.29074 41.13099 -0.00303 87.59161 41.13099 1.27351 87.70241 41.13099 2.37288 87.98289 41.13099 3.31200 88.37459 28.00056 8.49697 87.00079 33.00006 11.39697 88.27529 24.32517 -0.00303 87.70768 24.05718 -0.00303 87.48594 24.21422 -0.00303 87.66471 24.43612 -0.00303 87.75066 24.67260 -0.00303 87.72430 41.78690 -0.00303 87.66472 41.94394 -0.00303 87.48595 41.68114 3.11934 88.42470 41.32852 -0.00303 87.72430 41.56501 -0.00303 87.75066 24.87013 -8.00303 87.59161 25.09139 -9.03460 87.35694 25.63093 -9.82743 86.83522 25.45073 -4.00303 87.00080 26.38597 -10.30840 86.21866 27.08407 -4.00303 85.72745 27.26143 -10.50303 85.61664 28.38190 -10.50303 85.01742 28.11167 -9.00303 85.14693 28.47897 -9.48780 84.97308 28.11167 -6.00303 85.14693 28.58706 -5.67444 84.92504 28.92677 -5.46536 84.78296 28.93422 -4.00303 84.77999 29.25148 -5.29607 84.65945 28.95670 -10.02226 84.77108 29.55905 -10.49865 84.55418 29.72197 -5.11393 84.50076 30.43560 -5.00303 84.30403 30.93008 -4.00303 84.19742 32.13820 -5.00303 84.03466 33.00057 -4.00303 84.00080 33.86293 -5.00303 84.03466 35.07105 -4.00302 84.19742 35.56553 -5.00302 84.30403 36.24842 -5.10488 84.49121 36.85765 -5.34857 84.69920 37.06691 -4.00302 84.77999 37.39911 -5.66466 84.91850 37.61948 -10.50303 85.01753 37.88945 -9.00303 85.14693 38.73970 -10.50303 85.61664 37.88945 -6.00302 85.14693 38.91706 -4.00302 85.72745 39.68599 -10.50130 86.22202 40.35194 -9.84937 86.81806 40.55040 -4.00302 87.00080 40.90894 -9.03650 87.35612 41.13099 -8.00303 87.59161 30.96395 -5.00303 84.67027 35.03717 -5.00302 84.67027 31.40160 -5.00303 85.13993 34.59953 -5.00303 85.13993 31.72967 -5.00303 85.69276 34.27146 -5.00303 85.69276 31.93231 -5.00303 86.30224 34.06882 -5.00303 86.30224 33.00057 -10.00303 85.00080 31.33445 -10.00303 85.05358 33.00057 -10.00303 85.40250 31.61989 -10.00303 85.47595 33.00057 -10.00303 85.74326 31.82955 -10.00303 85.94012 33.00057 -10.00303 86.01086 34.04364 -10.00303 86.43204 31.95749 -10.00303 86.43199 37.41134 -6.00302 84.98119 37.41122 -9.00303 84.98116 36.90551 -6.00302 84.94080 36.90544 -9.00303 84.94081 36.40688 -6.00302 85.02869 36.40681 -9.00303 85.02872 35.94649 -6.00302 85.23886 35.94644 -9.00303 85.23889 35.55360 -6.00302 85.55786 35.55355 -9.00303 85.55791 35.25326 -6.00302 85.96545 35.25317 -9.00303 85.96560 35.06460 -6.00302 86.43652 35.06454 -9.00303 86.43675 28.58979 -9.00303 84.98119 28.58979 -6.00303 84.98119 29.09562 -9.00303 84.94080 29.09562 -6.00303 84.94080 29.59425 -9.00303 85.02869 29.59425 -6.00303 85.02869 30.05464 -9.00303 85.23886 30.05463 -6.00303 85.23886 30.44753 -9.00303 85.55786 30.44753 -6.00303 85.55786 30.74787 -9.00303 85.96545 30.74787 -6.00303 85.96545 30.93653 -9.00303 86.43652 30.93653 -6.00303 86.43652 30.28887 -5.29592 85.04181 31.02681 -5.29592 85.86537 36.74865 -5.30497 84.66199 35.71718 -5.29592 85.03847 34.97572 -5.29592 85.86275 28.79139 -9.24625 84.91932 29.54059 -9.51198 84.86862 30.07767 -9.70493 84.92410 30.96474 -9.71013 85.75558 31.02918 -9.98200 85.01439 30.74658 -9.92569 84.99265 30.47820 -9.84499 84.97118 24.67261 -8.00303 87.72430 24.43612 -8.00303 87.75066 24.21422 -8.00303 87.66472 24.05718 -8.00303 87.48595 41.32850 -8.00302 87.72429 41.56498 -8.00302 87.75067 41.78688 -8.00302 87.66473 41.94394 -8.00302 87.48595 38.77465 -10.75303 85.55949 40.47097 -9.98157 86.87932 41.13404 -9.19326 87.46947 39.76203 -10.62444 86.18590 40.69175 -10.17119 86.83067 41.38859 -9.29184 87.43205 38.86145 -10.91940 85.41756 40.84677 -10.23448 86.72431 39.99669 -10.79865 85.96618 41.68918 -9.29155 87.14125 27.13100 -10.93604 85.40337 29.47736 -10.85658 84.42581 31.95056 -10.85241 83.89981 33.00057 -10.66970 84.02230 30.52545 -10.61703 84.28741 33.00057 -10.97928 83.70176 34.05057 -10.85241 83.89981 36.52377 -10.85658 84.42581 24.91575 -9.16382 87.46036 27.21588 -10.77336 85.54215 26.28875 -10.54603 86.21458 25.42461 -10.08604 86.87474 24.71859 -9.25626 87.46587 26.16107 -10.70809 86.13063 25.24180 -10.20360 86.79390 24.53492 -9.30571 87.39326 26.00711 -10.79692 85.97325 25.07019 -10.24095 86.64246 24.36523 -9.30825 87.23492 33.00057 -10.04902 84.66844 33.00057 -10.18686 84.38903 33.00057 -10.40319 84.16565 31.21358 -10.32127 84.33206 31.26853 -10.17210 84.66017 34.73371 -10.17210 84.66017 34.78867 -10.32127 84.33206 35.47679 -10.61703 84.28741 35.52404 -9.84499 84.97118 35.25566 -9.92569 84.99265 34.97306 -9.98200 85.01439 35.03751 -9.71013 85.75558 35.92458 -9.70493 84.92410 36.46165 -9.51198 84.86862 37.21085 -9.24625 84.91932 34.17269 -10.00303 85.94012 34.38235 -10.00303 85.47595 34.66779 -10.00303 85.05358 36.44320 -10.49865 84.55418 37.04554 -10.02226 84.77108 37.52327 -9.48780 84.97308 34.00057 -5.00303 86.93854 32.00057 -5.00303 93.26875 34.00057 -5.00303 93.26875 34.23295 -5.00303 94.09372 32.77805 -5.00303 94.02587 33.22309 -5.00303 94.02587 32.37708 -5.00303 94.21896 33.62406 -5.00303 94.21896 31.63453 -5.07242 94.00080 32.09960 -5.00303 94.56692 33.90154 -5.00303 94.56692 31.83087 -5.00303 94.92145 34.17026 -5.00303 94.92146 32.00057 -5.00303 95.00080 34.00057 -5.00303 95.00080 34.08618 -5.00303 95.44342 31.92156 -5.00303 95.45930 33.86829 -5.00303 95.49785 32.13484 -5.00303 95.50132 33.50329 -5.00303 95.86525 33.76625 -5.00303 95.88861 32.24623 -5.00303 95.89827 32.50175 -5.00303 95.86751 33.00279 -5.00303 96.00079 33.28202 -5.00303 96.13889 32.73530 -5.00303 96.14278 35.00094 -6.00302 94.00079 35.00057 -9.00303 86.93854 35.00057 -9.00303 94.00080 32.00057 -10.00303 86.93854 34.00057 -10.00303 94.00080 32.00057 -10.00303 94.00080 31.00056 -9.00303 94.00080 31.00056 -6.00303 93.96098 31.00056 -6.00303 86.93854 31.61786 -5.07915 86.93854 31.30198 -5.28749 94.00080 31.29344 -5.29593 86.93854 31.07899 -5.61481 94.00080 31.00550 -6.00303 94.14118 34.43220 -5.11040 94.23586 34.38325 -5.07915 86.93854 34.69915 -5.28749 94.00080 34.70768 -5.29592 86.93854 34.92214 -5.61481 94.00080 34.92445 -5.62034 86.93854 34.86658 -9.50305 94.00080 34.70768 -9.71013 86.93854 34.50055 -9.86907 94.00080 34.38325 -9.92691 86.93854 31.50056 -9.86905 94.00080 31.29346 -9.71013 86.93854 31.13453 -9.50303 94.00080 31.07668 -9.38571 86.93854 31.26325 -5.33823 94.18478 31.07251 -5.64578 94.15256 34.73787 -5.33821 94.18479 34.92861 -5.64577 94.15256 34.27405 -5.02203 94.50558 31.18788 -5.27567 95.41162 30.89816 -5.94570 95.54117 31.84060 -5.27567 96.45306 31.67032 -5.94570 96.71619 33.00056 -5.94570 97.17154 33.00056 -5.27567 96.85945 34.33081 -5.94570 96.71619 34.16051 -5.27567 96.45306 35.10297 -5.94570 95.54117 34.81324 -5.27567 95.41162 32.00057 -10.00303 95.50080 34.00057 -10.00303 95.50080 35.10297 -8.94570 95.54117 30.89816 -8.94570 95.54117 31.67032 -8.94570 96.71619 33.00056 -8.94570 97.17154 34.33081 -8.94570 96.71619 25.33635 4.10292 88.26276 24.87012 4.09936 88.83099 26.15790 6.16047 88.98504 24.87012 5.29650 89.82285 28.00056 7.74294 89.00079 28.00056 8.49697 89.00079 28.26272 11.26217 88.88427 28.88205 11.39697 89.68382 24.31998 5.63814 90.39954 24.31998 3.11935 88.42470 27.50056 8.49697 92.08532 27.50056 7.94142 89.74381 32.00057 -5.00303 86.93854 35.00057 -6.00302 86.93854 34.00057 -10.00303 86.93854 31.00056 -9.00303 86.93854 31.07668 -5.62035 86.93854 34.92445 -9.38571 86.93854 31.61788 -9.92691 86.93854 25.26737 7.83903 94.26450 30.42106 11.49197 99.79163 25.92516 9.96326 98.56780 27.71889 10.27446 100.34765 24.59157 9.57200 96.42619 24.61860 9.77928 96.36005 24.22178 8.65637 94.63448 24.24700 9.00930 95.10450 24.19308 9.23127 95.04589 24.19150 7.58718 93.89458 24.14427 8.20532 94.23191 24.43612 7.03771 93.27090 24.17456 9.29202 94.66216 24.24902 9.44767 94.97076 24.37461 9.63634 95.45103 24.54014 9.80788 95.89677 24.61778 7.53031 93.96102 24.44224 8.55986 94.71039 25.43079 8.64121 95.29345 24.67039 8.34236 94.60520 24.30384 8.16196 94.33179 30.45559 9.65113 100.62135 29.66201 9.49194 99.77038 29.71100 9.10508 98.62046 27.03176 9.74083 99.29839 28.15173 9.88731 100.26470 29.82490 8.69990 97.51351 26.07904 8.54095 95.21242 25.78238 9.43370 97.78474 24.61463 8.73646 95.12650 24.97374 9.09237 96.37290 30.21460 11.49697 99.47164 29.26237 11.49697 98.71239 28.51005 11.49697 97.75495 27.99730 11.49697 96.64925 27.75234 11.49697 95.45495 27.78809 11.49697 94.23913 27.97175 11.49697 93.17276 28.20463 11.49697 92.22712 28.50539 11.49697 91.41562 28.88949 11.49697 90.76318 29.13401 9.95133 100.91682 27.12495 11.27728 91.90439 26.65410 11.17867 92.90395 27.65125 11.34554 91.02052 26.49829 11.01932 91.70683 24.04909 8.88449 94.20363 24.00056 7.87464 93.62243 24.00056 8.32860 93.39330 26.62222 8.49544 94.56344 24.87012 6.30682 91.12612 24.87010 7.19214 93.23295 26.06698 7.94142 91.86849 26.41980 7.94142 91.18249 26.88909 7.94142 90.46915 26.22435 11.08882 94.01063 24.72783 10.01128 94.47569 24.72783 10.00166 95.68507 24.72783 10.02460 95.09306 26.15255 11.04698 95.04556 24.72783 9.94483 96.26659 26.25925 11.04698 96.20577 25.35801 10.22999 97.42496 25.77964 10.36962 98.04487 26.60520 11.04699 97.44958 26.28375 10.50161 98.68006 27.24331 11.04699 98.70905 27.46720 10.70933 99.86160 28.03297 10.77157 100.31409 28.19325 11.04699 99.87800 29.05452 10.83815 100.99229 29.39829 11.04698 100.82497 39.91544 8.54095 95.21242 38.24878 11.49697 95.45495 37.11116 11.49697 90.76254 37.49569 11.49697 91.41553 37.79654 11.49697 92.22728 38.02941 11.49697 93.17297 38.21304 11.49697 94.23913 36.64871 11.49697 90.29107 35.73919 11.49697 89.71020 34.69940 11.49697 89.29076 33.00057 11.49697 95.12437 33.00057 11.49528 88.98592 35.90857 11.39697 88.93648 38.34981 11.34554 91.02040 37.11908 11.39697 89.68382 33.00056 8.49697 95.00079 34.05057 8.49697 88.86504 39.58928 8.49697 95.04091 39.37226 8.49544 94.56345 39.13748 8.49697 93.95770 39.02299 8.49697 93.42587 38.84736 8.49697 92.86423 38.59385 8.49697 92.26855 38.24058 8.49697 91.64041 37.76120 8.49697 90.99002 37.12631 8.49697 90.33944 36.30628 8.49697 89.72611 35.28151 8.49697 89.20879 33.00056 8.55728 98.13480 38.76384 7.94142 90.03386 37.95638 7.94142 89.22797 38.76131 11.04699 98.70362 37.81296 11.04698 99.87298 38.09110 10.75973 100.22089 36.60886 11.04698 100.82124 36.99772 10.83605 100.96210 35.23964 11.04697 101.47259 35.57732 10.85606 101.66717 35.04660 10.85606 101.84870 33.76310 11.04697 101.80639 33.82334 10.85606 102.10032 32.24501 11.04697 101.80717 32.53990 10.85606 102.13297 35.01686 9.96856 101.74918 35.54827 9.65113 100.62135 34.30502 9.65113 101.03237 33.81138 9.96856 101.99714 31.94006 9.96856 101.96366 33.00053 9.65113 101.17181 37.49107 11.49697 97.75497 38.00381 11.49697 96.64927 36.73875 11.49697 98.71239 35.78653 11.49697 99.47164 37.96762 9.87593 100.17509 36.29012 9.10508 98.62046 36.67593 8.71842 97.57586 36.33852 9.49238 99.77200 36.44250 9.96396 101.15311 36.10963 10.38171 101.66822 34.06853 10.38028 102.29176 31.93259 10.38028 102.29176 38.28223 10.27446 100.34765 33.00056 11.48798 100.50080 35.27124 11.48798 100.01020 35.58015 11.49197 99.79154 34.13903 11.48798 100.37675 36.91229 7.94142 88.47514 30.09208 11.39697 88.93671 31.49381 11.39697 88.44625 34.50645 11.39697 88.44605 31.30160 11.49697 89.29080 30.26184 11.49697 89.71024 31.83903 11.48798 100.37675 30.72988 11.48798 100.01020 29.89149 10.38171 101.66822 29.35241 11.49697 90.29107 30.40465 9.96856 101.54812 31.69602 9.65113 101.03236 30.36637 10.85606 101.64468 31.34895 10.85606 101.95438 30.76811 11.04697 101.47488 9.72146 11.00031 54.88705 30.63460 10.99998 64.29271 -1.22348 10.99998 31.37399 2.19250 11.00015 12.22483 39.01376 10.99859 12.24816 -22.29964 11.00020 21.38510 14.33852 9.49238 103.77200 7.71100 9.10508 102.62046 14.73874 11.49697 102.71239 15.49106 11.49697 101.75497 33.00057 -5.00303 95.00080 + + + + + + + + + + -0.27653 -0.59294 0.75627 -0.22124 -0.61003 0.76087 0.87478 -0.29895 0.38129 0.89685 -0.28227 0.34057 0.11993 0.99253 0.02254 -0.55015 -0.62730 0.55121 0.85361 0.22300 0.47076 0.78945 0.37028 0.48956 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24572 0.96262 0.11395 0.24710 0.96090 0.12493 0.36884 -0.86583 0.33807 0.40262 -0.84456 0.35300 0.30819 -0.87861 0.36477 0.79235 -0.48637 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14655 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23108 0.60973 0.41632 0.67447 0.45012 -0.62955 0.63329 0.52768 -0.56847 0.63119 0.51462 -0.58327 0.62846 0.69906 0.28925 0.65394 0.69603 0.25859 0.66983 0.73326 0.39301 0.55486 0.51544 -0.63934 0.57058 0.71478 -0.44325 0.54095 0.50371 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04158 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14387 -0.94000 0.30935 0.14373 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 0.40524 0.83720 0.36725 0.40441 0.85375 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24716 0.49012 0.83244 0.25851 0.53337 0.82040 0.20604 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09072 0.58199 0.81145 0.05332 0.58209 0.81139 0.05314 0.63891 0.76804 -0.04376 0.58234 0.81175 0.04408 -0.62975 -0.61576 0.47356 -0.62713 -0.61181 0.48208 -0.67408 -0.63036 0.38504 -0.72332 -0.61625 0.31151 -0.77754 -0.57908 0.24515 -0.69443 -0.64412 0.32073 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00001 -0.00001 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.10122 0.99362 0.04977 0.24187 0.96694 -0.08072 0.35177 0.89015 -0.28966 0.31960 0.94341 -0.08850 0.36436 0.93124 0.00607 0.42888 0.90108 -0.06413 0.34159 0.93060 -0.13153 0.35863 0.93029 -0.07715 0.44976 0.89314 0.00495 0.43933 0.89793 0.02653 0.56738 0.81415 -0.12343 0.54248 0.83922 -0.03771 0.19557 -0.87047 0.45170 0.27452 -0.77218 0.57305 0.30521 -0.65708 0.68927 0.99038 0.13278 -0.03900 0.90737 0.41198 0.08332 0.91040 0.37203 0.18104 0.82860 0.54907 -0.10926 0.75315 0.64246 -0.14144 0.78420 0.61951 -0.03530 0.90005 -0.34130 0.27096 0.80594 -0.53026 0.26322 0.80748 -0.45607 0.37412 -0.22704 -0.86992 0.43782 0.85822 -0.44314 0.25900 0.91971 -0.36186 0.15226 0.87148 -0.43736 0.22190 0.81241 -0.55874 0.16670 -0.20344 -0.87645 0.43641 0.22710 0.97309 -0.03911 0.27743 0.96072 0.00660 0.22383 0.97307 -0.05512 0.20009 0.97977 0.00241 0.18875 0.98134 -0.03660 0.26631 0.96371 -0.01852 0.27545 0.96128 -0.00810 -0.26496 -0.92700 0.26547 -0.29922 -0.92728 0.22501 -0.29985 -0.92803 0.22101 -0.32465 -0.92748 0.18544 -0.32484 -0.92795 0.18269 -0.34306 -0.92762 0.14774 -0.34305 -0.92790 0.14600 -0.35599 -0.92772 0.11224 -0.35592 -0.92787 0.11129 0.92069 0.37501 -0.10818 -0.69462 -0.69976 0.16684 -0.19265 -0.86351 0.46608 0.12591 -0.54798 0.82696 0.18329 -0.69229 0.69795 0.23960 -0.72465 0.64612 0.33000 -0.71943 0.61116 0.04364 -0.78466 0.61839 -0.14946 -0.85152 0.50256 -0.39572 -0.90000 0.18275 -0.40310 -0.90211 0.15396 -0.38048 -0.92472 -0.01171 0.24914 -0.62470 0.74005 0.33786 -0.80616 0.48576 0.74850 -0.58760 0.30737 0.49646 -0.68116 0.53810 0.96437 -0.18410 0.18999 0.99852 -0.05405 0.00589 0.94067 -0.09921 0.32450 0.94004 -0.09055 0.32883 0.48679 -0.51345 0.70669 0.82623 -0.38748 0.40890 -0.36662 -0.92729 0.07565 0.87625 -0.16493 0.45275 -0.36475 -0.92779 0.07852 0.20020 -0.56806 0.79827 0.17871 -0.91400 0.36422 -0.18706 -0.74811 0.63666 0.83447 -0.22089 0.50484 0.89415 -0.23045 0.38391 0.94096 0.33621 -0.03941 0.98449 0.17299 -0.02905 0.99690 0.06550 -0.04351 0.99055 0.13647 -0.01331 1.00000 0.00000 -0.00000 0.99993 0.00516 0.01023 -0.70491 -0.69427 0.14522 0.96140 0.25493 0.10352 0.99982 0.00256 0.01897 0.99021 0.13920 -0.01049 0.99228 0.12114 -0.02652 0.70425 -0.06136 0.70730 0.72397 -0.08034 0.68514 0.69834 -0.06705 0.71261 0.70755 -0.17462 0.68475 0.68757 -0.20294 0.69719 0.68968 -0.35670 0.63017 0.66014 -0.28997 0.69291 0.73912 -0.29694 0.60458 0.65962 -0.29237 0.69240 0.71356 -0.46795 0.52140 0.52244 -0.74493 0.41489 0.56236 -0.62219 0.54464 0.53895 -0.63976 0.54794 -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.29656 -0.66599 0.68448 -0.31840 -0.67290 0.66770 -0.43573 -0.62856 0.64424 -0.45505 -0.62819 0.63112 -0.66290 -0.37590 0.64750 -0.53420 -0.51395 0.67118 -0.49917 -0.61019 0.61522 -0.69782 -0.07751 0.71207 -0.90614 -0.31237 -0.28518 -0.71726 -0.15742 0.67879 -0.57400 -0.07080 0.81579 -0.67104 -0.18329 0.71841 -0.68092 -0.28192 0.67592 -0.63745 -0.38469 0.66759 -0.72203 -0.43278 0.53979 0.00000 -1.00000 0.00000 0.11515 0.99316 -0.01950 0.12396 0.99229 -0.00068 -0.07001 0.99177 -0.10718 -0.06792 0.99150 -0.11096 -0.04278 0.99157 -0.12227 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 0.04210 0.99151 -0.12305 0.04277 0.99157 -0.12228 0.06838 0.99149 -0.11075 0.21031 0.97181 -0.10652 0.04527 0.99623 -0.07396 -0.16531 0.98571 -0.03238 -0.17404 0.98465 -0.01341 0.12153 -0.43758 0.89093 -0.78240 -0.27455 0.55900 0.64069 -0.18973 0.74399 0.46658 -0.17002 0.86798 -0.87579 -0.11927 0.46772 -0.94190 -0.02903 0.33465 -0.97122 0.01020 0.23795 -0.74452 -0.13397 0.65402 -0.35313 -0.20995 0.91171 0.11078 -0.00001 0.99385 0.55619 -0.07182 0.82794 0.35731 0.14609 0.92249 0.75105 0.02515 0.65977 0.97107 -0.02064 0.23789 0.84841 -0.13085 0.51291 0.86783 -0.13547 0.47804 -0.40482 -0.22605 0.88602 -0.71334 -0.06060 0.69819 -0.55344 -0.12230 0.82386 -0.10840 -0.20591 0.97255 -0.21381 -0.37604 0.90160 0.78238 -0.27465 0.55896 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.16235 -0.92614 0.34045 -0.99978 -0.01466 0.01477 1.00000 -0.00000 0.00000 0.94706 -0.18941 -0.25923 1.00000 0.00000 -0.00000 0.72758 0.00000 0.68602 0.72632 -0.00007 0.68736 0.69543 0.00038 0.71860 0.71539 0.00227 0.69872 0.69992 0.00000 0.71422 0.63154 -0.00250 0.77534 0.61482 -0.00663 0.78864 0.56683 0.00142 0.82383 0.47157 0.00882 0.88178 0.42644 -0.00127 0.90452 0.48578 -0.00165 0.87408 0.49187 0.00000 0.87067 0.44156 -0.03337 0.89661 0.41672 -0.06071 0.90701 0.45581 -0.00052 0.89008 0.35546 0.00009 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37465 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00250 0.92737 -0.48356 0.00000 0.87531 -0.47159 0.00881 0.88178 -0.42806 -0.01025 0.90369 -0.48965 -0.00150 0.87192 -0.45567 -0.02415 0.88982 -0.53890 0.00034 0.84237 -0.65575 -0.02015 0.75471 -0.61483 -0.00378 0.78865 -0.69506 0.00038 0.71895 -0.72738 -0.00008 0.68623 -0.72632 -0.00000 0.68736 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.32754 0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90968 0.63033 -0.00000 0.77633 0.63035 0.00000 0.77631 0.80505 -0.00000 0.59321 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37168 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07960 0.00000 0.99683 0.07960 0.00000 0.99683 -0.17359 0.00000 0.98482 -0.17359 0.00000 0.98482 -0.41529 0.00000 0.90969 -0.41529 0.00000 0.90969 -0.63033 0.00000 0.77633 -0.63033 0.00000 0.77633 -0.80504 0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32893 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39518 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35199 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39126 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85625 0.38631 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12333 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81900 -0.17246 -0.19506 0.98057 0.02092 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15933 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30813 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26660 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37310 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18796 0.97320 0.19359 0.12413 0.32737 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23702 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86546 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54636 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29877 -0.95399 0.02541 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18797 -0.97320 -0.19359 0.12413 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 -0.36118 0.00000 0.93250 -0.36118 0.00000 0.93250 -0.75130 0.00000 0.65997 -0.75130 0.00000 0.65997 -0.97127 -0.00000 0.23796 -0.97127 0.00000 0.23798 -0.55763 -0.00000 0.83009 -0.55763 -0.00000 0.83009 -0.11087 -0.00000 0.99383 -0.11078 0.00000 0.99385 0.36114 -0.00000 0.93251 0.36118 0.00000 0.93250 0.75128 -0.00000 0.65998 0.75129 0.00000 0.65997 0.97128 0.00000 0.23795 0.97128 0.00000 0.23794 -0.52021 -0.25876 0.81390 -0.55629 -0.06917 0.82810 -0.57632 -0.14637 0.80401 -0.57290 -0.14179 0.80727 -0.50295 -0.10159 0.85832 -0.53494 -0.16968 0.82768 -0.36795 -0.46362 0.80602 -0.42242 -0.48537 0.76549 -0.28739 -0.53790 0.79251 -0.21087 -0.46595 0.85932 -0.10883 -0.19107 0.97553 0.04715 -0.24580 0.96817 -0.07666 -0.52074 0.85027 -0.31183 -0.70556 0.63636 0.03122 -0.83832 0.54428 0.21992 -0.66340 0.71522 0.34776 -0.26959 0.89799 0.50716 -0.68460 0.52355 0.65752 -0.32584 0.67933 0.00853 -0.93684 0.34965 -0.01764 -0.79254 0.60956 -0.19340 -0.85881 0.47439 0.71447 -0.30917 0.62765 0.61605 -0.70539 0.35058 0.40619 -0.89006 0.20691 0.22140 -0.97480 -0.02747 0.44467 -0.88743 0.12141 0.94100 -0.24772 0.23053 0.81543 -0.57879 -0.00930 0.95828 -0.24461 0.14786 0.11803 -0.96573 0.23118 0.47154 -0.01437 0.88173 0.41234 -0.30593 0.85813 0.29316 -0.70443 0.64640 0.14306 -0.95333 0.26588 0.33917 -0.38521 0.85824 0.13045 -0.90945 0.39482 0.07105 -0.94250 0.32658 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03997 -0.73161 0.68055 0.01607 -0.98803 0.15344 -0.03998 -0.73156 0.68061 -0.01608 -0.98803 0.15344 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 -0.13850 -0.95397 0.26603 -0.29317 -0.70441 0.64642 -0.45559 -0.25841 0.85186 0.55630 -0.06906 0.82810 0.54644 -0.07521 0.83412 0.57602 -0.13818 0.80567 0.49186 -0.30734 0.81463 0.53316 -0.23207 0.81356 0.52427 -0.22855 0.82031 0.49192 -0.26575 0.82909 0.48669 -0.26087 0.83372 0.22611 -0.43020 0.87395 0.11924 -0.19633 0.97326 0.10861 -0.19695 0.97438 0.29526 -0.70457 0.64529 0.36092 -0.63712 0.68104 0.26070 -0.59799 0.75792 0.00840 -0.57544 0.81780 0.13169 -0.69253 0.70927 -0.28897 -0.27361 0.91741 -0.13707 -0.62234 0.77065 -0.34751 -0.27251 0.89720 0.00035 -0.95410 0.29950 -0.06955 -0.83809 0.54107 0.11954 -0.91012 0.39673 -0.37961 -0.70148 0.60317 -0.20138 -0.87331 0.44359 -0.64729 -0.30492 0.69859 -0.48193 -0.69947 0.52772 -0.21391 -0.97644 -0.02847 -0.43222 -0.89152 0.13555 -0.71877 -0.29106 0.63139 -0.69107 -0.67926 0.24704 -0.45140 -0.88525 0.11212 -0.93651 -0.26515 0.22946 -0.92389 -0.26238 0.27854 -0.77550 -0.62094 0.11413 0.08395 -0.47203 0.87758 0.07372 -0.31442 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39305 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.42738 -0.87288 0.23542 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18886 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18766 0.98223 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18766 0.98223 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18886 -0.67101 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92408 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19359 0.12407 0.81663 -0.54564 -0.18814 0.90235 -0.34994 0.25159 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02538 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54656 0.32005 -0.92238 0.21629 0.34529 -0.86546 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68808 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 -0.71754 0.00259 0.69651 -0.69992 0.00000 0.71422 0.00000 -1.00000 -0.00000 -0.99976 -0.02028 0.00805 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 -0.00012 -0.00000 -1.00000 -0.00000 -0.00000 -0.54306 0.83970 0.00048 -0.82645 0.56302 0.00033 -0.98019 0.19804 -0.00000 -0.98037 0.19532 0.02685 -0.00000 1.00000 0.00000 0.48299 0.87548 -0.01569 0.55273 0.83336 -0.00014 0.82644 0.56303 0.00033 0.98001 0.19893 0.00016 0.96592 -0.25883 -0.00000 0.70708 -0.70711 0.00482 0.25880 -0.96592 0.00361 -0.25882 -0.96593 0.00000 -0.70710 -0.70710 0.00482 -0.96592 -0.25882 0.00361 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.53936 0.83398 0.11644 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06986 -0.98282 0.18451 -0.00432 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85102 0.52047 0.06989 0.98001 0.19893 -0.00121 -0.38262 0.92383 0.01196 -0.60549 0.79206 -0.07758 -0.98242 0.18315 0.03619 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86396 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92863 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48080 0.35274 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78087 0.11745 0.43570 0.89716 -0.07251 0.98234 0.18357 0.03605 0.84345 0.53137 -0.07891 0.60508 0.79038 0.09581 0.47838 0.87812 -0.00723 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02737 0.99781 -0.00006 -0.06621 -0.83570 0.00000 0.54918 -0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 0.83570 0.00000 0.54918 -0.99746 0.00249 -0.07125 -0.96449 -0.25844 -0.05450 -0.69956 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66578 0.40977 0.96449 -0.25845 -0.05450 0.69954 -0.69957 0.14577 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.18723 0.98232 -0.00049 -0.67986 -0.71506 0.16275 -0.25882 -0.96593 -0.00000 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 0.68062 -0.46742 0.56416 0.68415 -0.46919 0.55840 0.00000 -1.00000 0.00000 -0.06980 0.99114 -0.11304 -0.17002 0.98539 0.00995 0.49377 -0.55480 0.66962 -0.88917 -0.28233 0.36009 -0.06968 0.99117 -0.11285 -0.04752 0.99190 -0.11780 0.82964 0.00000 0.55830 1.00000 0.00000 -0.00005 0.00000 -1.00000 -0.00000 -1.00000 0.00000 -0.00000 -0.55558 0.83146 -0.00032 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 0.19509 0.98078 0.00289 0.55557 0.83147 -0.00032 0.83147 0.55556 -0.00016 0.98078 0.19510 -0.00005 0.98077 -0.19509 0.00479 0.83147 -0.55556 -0.00242 0.55557 -0.83147 -0.00242 0.19509 -0.98079 -0.00000 -0.19508 -0.98078 0.00479 -0.55557 -0.83147 -0.00242 -0.83147 -0.55557 -0.00242 -0.98078 -0.19510 -0.00000 0.00000 1.00000 -0.00000 -0.19510 0.98078 0.00000 -0.43988 0.89769 0.02576 -0.34308 0.92963 -0.13449 -0.12092 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29117 0.13333 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.26953 -0.73824 0.61835 -0.04401 -0.78448 0.61859 0.34486 -0.87107 0.34972 -0.24901 -0.62075 0.74341 -0.53274 -0.67686 0.50798 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71481 -0.55303 -0.49987 0.66655 -0.10705 -0.93718 0.33202 -0.08363 -0.97549 0.20352 -0.95619 0.27850 0.09024 0.81839 -0.55914 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34274 -0.93162 0.12091 0.41584 -0.90391 0.10015 -0.02010 -0.99838 0.05318 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.11792 0.96141 0.24855 -0.28024 0.91713 0.28345 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 -0.21447 0.96105 0.17429 -0.21468 0.96201 0.16869 -0.24705 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05398 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06977 0.99156 -0.10925 -0.34004 -0.62630 0.70151 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50577 -0.84008 0.26126 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08802 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67439 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41724 -0.54080 0.73037 -0.41201 -0.60635 0.68014 -0.70424 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95385 0.19679 0.22679 -0.77616 0.60749 0.16894 -0.89673 0.40568 0.17691 0.33004 -0.80724 0.48932 -0.20020 -0.56807 0.79826 -0.19713 -0.77268 0.60342 -0.56010 -0.42940 0.70845 -0.86716 -0.48961 0.09123 -0.79167 -0.53552 0.29407 -0.86902 -0.31567 0.38100 0.40409 -0.56439 0.71984 0.33802 -0.85130 0.40128 0.52007 -0.78742 0.33089 0.14974 -0.78142 0.60577 -0.67308 -0.65371 0.34586 -0.79487 -0.52330 0.30714 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02856 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01957 -0.79797 0.60051 -0.05130 -0.76800 0.64031 -0.01382 -0.80117 0.58934 -0.10394 -0.76278 0.64443 -0.05371 -0.72711 0.68601 0.02658 -0.71869 0.69533 -0.00068 -0.67621 0.73321 0.07167 -0.19381 -0.87163 0.45023 -0.33486 -0.67114 0.66139 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.10649 -0.94309 0.31503 -0.16500 -0.93292 0.32005 -0.17354 -0.93264 0.31632 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.14310 -0.93869 0.31366 -0.59996 0.78186 -0.16950 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.47585 0.87781 -0.05491 -0.33781 0.94059 0.03414 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.15144 0.98776 0.03735 -0.99876 0.02243 0.04443 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00118 -1.00000 -0.00103 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42687 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.68055 -0.57907 0.44891 -0.55875 0.82932 -0.00524 -0.63044 0.77342 -0.06608 -0.62318 0.78201 -0.01031 -0.62355 0.78160 -0.01687 -0.58167 0.81243 0.04018 -0.58190 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03148 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51069 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40436 0.85353 0.32861 -0.39688 0.83488 0.38139 -0.32068 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 0.00024 -1.00000 -0.00003 -0.00108 -0.99981 0.01924 -0.26638 -0.92815 0.25995 -0.22267 -0.92832 0.29772 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05538 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00095 1.00000 -0.00028 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00745 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 0.32528 0.86091 0.39118 0.33532 0.84040 0.42579 0.23285 0.86496 0.44455 0.25027 0.81275 0.52612 0.17651 0.83818 0.51604 0.10816 0.84369 0.52582 0.11187 0.86176 0.49483 0.00028 0.83866 0.54466 -0.00914 -0.99996 0.00102 -0.00630 -0.99996 0.00607 0.10399 -0.94352 0.31456 0.07081 -0.93620 0.34427 -0.00555 -0.95073 0.30998 0.04525 -0.90484 0.42333 0.14454 -0.93969 0.30998 0.14454 -0.93969 0.30997 0.12737 -0.94154 0.31190 0.18908 -0.91839 0.34758 0.30400 0.34310 0.88875 0.28039 0.27889 0.91848 0.15528 -0.63718 0.75491 0.25235 -0.50582 0.82490 0.18035 0.44574 0.87681 0.02349 0.38357 0.92321 0.00000 -0.58193 0.81324 0.43016 -0.54482 0.71982 0.39039 -0.60766 0.69162 0.53245 0.40400 0.74383 0.44473 0.03813 0.89485 0.46219 0.52024 0.71814 0.29459 -0.64015 0.70952 0.00016 0.94744 0.31993 0.19414 0.95999 0.20179 0.13733 0.94752 0.28870 0.17056 0.96125 0.21658 0.17105 0.96162 0.21453 0.21458 0.96108 0.17403 0.21475 0.96198 0.16875 0.05806 -0.98803 0.14291 0.11694 -0.95226 0.28202 0.03296 0.95258 0.30251 0.07028 0.94785 0.31086 0.09366 0.95264 0.28931 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.04460 0.99084 -0.12748 -0.02095 0.99228 -0.12226 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 0.04752 0.99190 -0.11780 -0.16727 -0.92856 0.33134 -0.21990 -0.92662 0.30498 -0.03234 0.95249 0.30284 -0.07021 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.23218 -0.60875 0.75863 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.01264 0.86767 0.49698 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.04879 -0.99862 0.01922 -0.27653 -0.59294 0.75627 -0.22124 -0.61003 0.76087 0.88921 -0.28229 0.36004 0.11993 0.99253 0.02254 -0.55015 -0.62730 0.55121 0.85361 0.22300 0.47076 0.78945 0.37028 0.48956 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24572 0.96262 0.11395 0.24710 0.96090 0.12493 0.36884 -0.86583 0.33807 0.40262 -0.84456 0.35300 0.30819 -0.87861 0.36477 0.79235 -0.48637 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14655 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23108 0.60973 0.41632 0.67447 0.45012 -0.62955 0.63329 0.52768 -0.56847 0.63119 0.51462 -0.58327 0.62846 0.69906 0.28925 0.65394 0.69603 0.25859 0.66983 0.73326 0.39301 0.55486 0.51544 -0.63934 0.57058 0.71478 -0.44325 0.54095 0.50370 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04158 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14387 -0.94000 0.30935 0.14373 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 0.40524 0.83720 0.36725 0.40441 0.85375 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24716 0.49012 0.83244 0.25851 0.53337 0.82040 0.20604 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09071 0.58199 0.81145 0.05332 0.58209 0.81139 0.05314 0.63891 0.76804 -0.04376 0.58234 0.81175 0.04408 -0.62975 -0.61576 0.47356 -0.62713 -0.61181 0.48208 -0.67408 -0.63036 0.38504 -0.72332 -0.61625 0.31151 -0.77754 -0.57908 0.24515 -0.69443 -0.64412 0.32073 1.00000 0.00000 -0.00000 1.00000 0.00001 -0.00000 1.00000 0.00017 -0.00017 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.10122 0.99362 0.04977 0.24187 0.96694 -0.08072 0.35177 0.89015 -0.28966 0.31960 0.94341 -0.08850 0.36436 0.93124 0.00607 0.42888 0.90108 -0.06413 0.34159 0.93060 -0.13153 0.35863 0.93029 -0.07715 0.44976 0.89314 0.00495 0.43934 0.89793 0.02653 0.56738 0.81415 -0.12343 0.54248 0.83922 -0.03771 0.19557 -0.87047 0.45170 0.27452 -0.77218 0.57305 0.30521 -0.65708 0.68927 0.99038 0.13278 -0.03901 0.90737 0.41199 0.08331 0.91039 0.37203 0.18103 0.82860 0.54908 -0.10926 0.75315 0.64246 -0.14144 0.78419 0.61951 -0.03530 0.90067 -0.31037 0.30406 0.79873 -0.53748 0.27045 0.75401 -0.46134 0.46757 -0.22704 -0.86992 0.43782 0.85822 -0.44314 0.25900 0.92693 -0.34949 0.13658 0.84589 -0.47572 0.24118 0.82161 -0.54314 0.17310 -0.20344 -0.87645 0.43641 0.22710 0.97309 -0.03911 0.27743 0.96072 0.00660 0.22383 0.97307 -0.05511 0.20009 0.97977 0.00241 0.18875 0.98134 -0.03660 0.26631 0.96371 -0.01852 0.27545 0.96128 -0.00810 -0.26496 -0.92700 0.26547 -0.29922 -0.92728 0.22501 -0.29985 -0.92803 0.22101 -0.32465 -0.92748 0.18544 -0.32485 -0.92795 0.18269 -0.34306 -0.92762 0.14775 -0.34305 -0.92790 0.14600 -0.35599 -0.92772 0.11224 -0.35592 -0.92787 0.11129 0.92068 0.37502 -0.10818 -0.69462 -0.69976 0.16684 -0.19265 -0.86351 0.46608 0.12591 -0.54798 0.82696 0.18329 -0.69229 0.69795 0.23961 -0.72465 0.64612 0.33000 -0.71943 0.61116 0.04364 -0.78466 0.61839 -0.14946 -0.85152 0.50256 -0.39572 -0.90000 0.18275 -0.40310 -0.90211 0.15396 -0.38048 -0.92472 -0.01172 0.24914 -0.62470 0.74005 0.33786 -0.80616 0.48576 0.74850 -0.58760 0.30737 0.49646 -0.68116 0.53810 0.96437 -0.18410 0.18999 0.99852 -0.05405 0.00589 0.94067 -0.09921 0.32450 0.94004 -0.09055 0.32883 0.48679 -0.51345 0.70669 0.82623 -0.38748 0.40890 -0.36662 -0.92729 0.07565 -0.36475 -0.92779 0.07852 0.20020 -0.56806 0.79827 0.17871 -0.91400 0.36422 -0.18706 -0.74811 0.63666 0.83447 -0.22089 0.50484 0.89415 -0.23045 0.38391 0.94096 0.33621 -0.03941 0.99369 0.10940 -0.02488 0.99055 0.13648 -0.01331 1.00000 -0.00000 0.00000 0.99987 0.00727 0.01441 -0.70491 -0.69427 0.14522 0.96140 0.25493 0.10352 0.99981 0.00685 0.01805 0.99021 0.13920 -0.01050 0.99228 0.12113 -0.02651 0.70425 -0.06136 0.70730 0.72397 -0.08033 0.68514 0.69834 -0.06705 0.71261 0.70755 -0.17462 0.68475 0.68757 -0.20294 0.69719 0.68968 -0.35670 0.63017 0.66014 -0.28997 0.69291 0.73912 -0.29694 0.60458 0.65962 -0.29237 0.69240 0.71356 -0.46795 0.52140 0.52244 -0.74493 0.41489 0.56236 -0.62219 0.54464 0.53895 -0.63976 0.54794 -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.29656 -0.66599 0.68448 -0.31840 -0.67290 0.66770 -0.45185 -0.62142 0.64005 -0.45819 -0.62148 0.63547 -0.66290 -0.37590 0.64750 -0.53420 -0.51395 0.67118 -0.49409 -0.60833 0.62114 -0.69782 -0.07751 0.71207 -0.90614 -0.31237 -0.28518 -0.71726 -0.15742 0.67879 -0.57400 -0.07080 0.81579 -0.67104 -0.18329 0.71841 -0.68092 -0.28192 0.67592 -0.63745 -0.38469 0.66759 -0.72203 -0.43278 0.53979 -0.00000 -1.00000 -0.00000 0.11515 0.99316 -0.01950 0.12396 0.99229 -0.00068 -0.07001 0.99177 -0.10718 -0.06792 0.99150 -0.11096 -0.04278 0.99157 -0.12227 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 0.04209 0.99151 -0.12305 0.04277 0.99157 -0.12228 0.06837 0.99149 -0.11075 0.21031 0.97181 -0.10652 0.04527 0.99623 -0.07396 -0.16531 0.98571 -0.03238 -0.17404 0.98465 -0.01341 0.12153 -0.43758 0.89093 -0.78240 -0.27455 0.55900 0.50696 -0.21300 0.83524 0.43301 -0.20106 0.87868 -0.87579 -0.11926 0.46772 -0.94189 -0.02903 0.33465 -0.97122 0.01020 0.23796 -0.74452 -0.13397 0.65402 -0.35310 -0.20995 0.91172 -0.35677 0.15627 0.92103 0.11078 -0.00001 0.99385 0.55619 -0.07182 0.82794 0.35730 0.14610 0.92249 0.75105 0.02515 0.65977 0.97108 -0.02064 0.23787 0.84841 -0.13085 0.51291 0.86783 -0.13547 0.47803 -0.40482 -0.22605 0.88602 -0.71334 -0.06060 0.69819 -0.55344 -0.12230 0.82386 -0.10840 -0.20591 0.97255 -0.21381 -0.37604 0.90160 0.78239 -0.27465 0.55896 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.16235 -0.92614 0.34045 -0.99978 -0.01466 0.01477 1.00000 -0.00000 0.00000 0.94706 -0.18941 -0.25923 1.00000 0.00000 -0.00000 0.72758 0.00000 0.68602 0.72631 -0.00007 0.68736 0.69543 0.00038 0.71859 0.71540 0.00227 0.69872 0.69992 0.00000 0.71422 0.63154 -0.00250 0.77534 0.61482 -0.00663 0.78864 0.56683 0.00142 0.82383 0.47157 0.00882 0.88178 0.42644 -0.00127 0.90452 0.48578 -0.00165 0.87408 0.49187 0.00000 0.87067 0.44156 -0.03337 0.89661 0.41672 -0.06071 0.90701 0.45581 -0.00052 0.89008 0.35546 0.00009 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37465 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00250 0.92737 -0.48356 0.00000 0.87531 -0.47159 0.00881 0.88178 -0.42806 -0.01025 0.90369 -0.48965 -0.00150 0.87192 -0.45567 -0.02415 0.88982 -0.53890 0.00034 0.84237 -0.65575 -0.02015 0.75471 -0.61483 -0.00378 0.78865 -0.69506 0.00038 0.71895 -0.72738 -0.00008 0.68623 -0.72632 0.00000 0.68736 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.32754 0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90968 0.63033 -0.00000 0.77633 0.63035 0.00000 0.77631 0.80505 -0.00000 0.59321 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37168 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07960 0.00000 0.99683 0.07960 0.00000 0.99683 -0.17359 0.00000 0.98482 -0.17359 0.00000 0.98482 -0.41529 0.00000 0.90969 -0.41529 0.00000 0.90969 -0.63033 0.00000 0.77633 -0.63033 0.00000 0.77633 -0.80504 0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 -0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32893 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39518 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35199 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39126 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85625 0.38631 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12333 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81900 -0.17246 -0.19506 0.98057 0.02092 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15933 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30813 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26660 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37310 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18796 0.97320 0.19359 0.12413 0.32737 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23702 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86546 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54636 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29876 -0.95399 0.02540 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18796 -0.97320 -0.19359 0.12413 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 -0.36118 0.00000 0.93250 -0.36118 0.00000 0.93250 -0.75130 0.00000 0.65997 -0.75130 0.00000 0.65997 -0.97127 0.00000 0.23797 -0.97127 -0.00000 0.23796 -0.55763 0.00000 0.83009 -0.55763 0.00000 0.83009 -0.11087 -0.00000 0.99383 -0.11078 0.00000 0.99385 0.36114 -0.00000 0.93251 0.36118 0.00000 0.93250 0.75128 -0.00000 0.65998 0.75129 0.00000 0.65997 0.97128 0.00000 0.23793 0.97128 0.00000 0.23792 -0.52021 -0.25876 0.81390 -0.55629 -0.06917 0.82810 -0.57632 -0.14637 0.80401 -0.57290 -0.14179 0.80727 -0.50295 -0.10159 0.85832 -0.53494 -0.16968 0.82768 -0.36795 -0.46362 0.80602 -0.42242 -0.48537 0.76549 -0.28739 -0.53790 0.79251 -0.21087 -0.46595 0.85932 -0.10883 -0.19107 0.97553 0.04715 -0.24580 0.96817 -0.07666 -0.52074 0.85027 -0.31183 -0.70556 0.63636 0.03122 -0.83832 0.54428 0.21992 -0.66340 0.71522 0.34776 -0.26959 0.89799 0.50716 -0.68460 0.52355 0.65752 -0.32584 0.67933 0.00853 -0.93684 0.34965 -0.01764 -0.79254 0.60956 -0.19340 -0.85881 0.47439 -0.06005 -0.94361 0.32556 0.71447 -0.30917 0.62765 0.61605 -0.70539 0.35058 0.40619 -0.89006 0.20691 0.33853 -0.93969 0.04886 0.44467 -0.88743 0.12141 0.94101 -0.24772 0.23052 0.81543 -0.57879 -0.00930 0.95828 -0.24461 0.14786 0.11803 -0.96573 0.23117 0.47154 -0.01437 0.88173 0.41234 -0.30593 0.85813 0.29316 -0.70443 0.64640 0.14305 -0.95333 0.26587 0.33917 -0.38521 0.85824 0.13045 -0.90945 0.39481 0.07104 -0.94250 0.32657 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03996 -0.73162 0.68054 0.01607 -0.98803 0.15343 -0.03998 -0.73156 0.68060 -0.01608 -0.98803 0.15343 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 -0.13850 -0.95397 0.26603 -0.29317 -0.70441 0.64642 -0.45559 -0.25841 0.85186 0.55630 -0.06906 0.82810 0.54643 -0.07521 0.83412 0.57602 -0.13818 0.80567 0.49186 -0.30734 0.81463 0.53316 -0.23207 0.81356 0.52427 -0.22855 0.82031 0.49192 -0.26575 0.82909 0.48669 -0.26087 0.83372 0.22611 -0.43020 0.87395 0.11924 -0.19633 0.97326 0.10861 -0.19695 0.97438 0.29526 -0.70457 0.64529 0.36092 -0.63712 0.68104 0.26070 -0.59799 0.75792 0.00840 -0.57544 0.81780 0.13169 -0.69253 0.70927 -0.28897 -0.27361 0.91741 -0.13707 -0.62234 0.77065 -0.34751 -0.27251 0.89720 0.00034 -0.95410 0.29949 -0.06955 -0.83809 0.54107 0.11955 -0.91012 0.39673 -0.37961 -0.70149 0.60317 -0.20139 -0.87331 0.44359 -0.64730 -0.30492 0.69859 -0.48193 -0.69947 0.52771 -0.21390 -0.97644 -0.02846 -0.43222 -0.89152 0.13554 -0.71877 -0.29107 0.63139 -0.69106 -0.67926 0.24705 -0.45140 -0.88525 0.11213 -0.93651 -0.26515 0.22944 -0.92389 -0.26237 0.27855 -0.77550 -0.62094 0.11414 0.08395 -0.47203 0.87758 0.07372 -0.31442 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39306 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 1.00000 0.00000 -0.42738 -0.87288 0.23542 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18886 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18765 0.98224 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18765 0.98224 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18886 -0.67100 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92408 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19359 0.12406 0.81662 -0.54564 -0.18814 0.90236 -0.34994 0.25159 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02537 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54656 0.32005 -0.92238 0.21629 0.34529 -0.86546 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68808 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 -0.71754 0.00259 0.69651 -0.69992 0.00000 0.71422 0.00000 -1.00000 -0.00000 -0.99976 -0.02028 0.00805 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 -0.00012 0.00000 -1.00000 -0.00000 -0.00000 -0.54306 0.83970 0.00048 -0.82645 0.56302 0.00033 -0.98019 0.19804 -0.00000 -0.98037 0.19532 0.02685 0.00000 1.00000 -0.00000 0.48299 0.87548 -0.01569 0.55272 0.83336 -0.00014 0.82644 0.56303 0.00033 0.98001 0.19893 0.00016 0.96592 -0.25883 0.00000 0.70708 -0.70711 0.00483 0.25880 -0.96592 0.00361 -0.25882 -0.96593 0.00000 -0.70710 -0.70710 0.00482 -0.96592 -0.25882 0.00361 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.53936 0.83398 0.11645 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06987 -0.98282 0.18451 -0.00432 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85102 0.52047 0.06989 0.98001 0.19893 -0.00121 -0.38262 0.92383 0.01196 -0.60549 0.79206 -0.07758 -0.98242 0.18315 0.03619 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86397 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92863 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48080 0.35274 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78087 0.11745 0.43570 0.89716 -0.07251 0.98234 0.18357 0.03605 0.84345 0.53137 -0.07891 0.60508 0.79038 0.09581 0.47838 0.87812 -0.00723 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02737 0.99781 -0.00006 -0.06621 -0.83570 0.00000 0.54918 -0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 0.83570 0.00000 0.54918 -0.99746 0.00249 -0.07125 -0.96449 -0.25844 -0.05450 -0.69956 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66578 0.40977 0.96449 -0.25845 -0.05450 0.69954 -0.69957 0.14577 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.18723 0.98232 -0.00049 -0.67986 -0.71506 0.16275 -0.25882 -0.96593 -0.00000 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 0.68062 -0.46742 0.56416 0.68415 -0.46919 0.55840 0.00000 -1.00000 0.00000 -0.06980 0.99114 -0.11304 -0.17002 0.98539 0.00995 0.49377 -0.55480 0.66962 -0.88917 -0.28233 0.36009 -0.06967 0.99117 -0.11285 -0.04752 0.99190 -0.11780 1.00000 0.00000 -0.00005 0.00000 -1.00000 0.00000 -1.00000 -0.00000 -0.00000 -0.55558 0.83146 -0.00032 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 0.19509 0.98078 0.00289 0.55557 0.83147 -0.00032 0.83147 0.55556 -0.00016 0.98078 0.19510 -0.00005 0.98077 -0.19509 0.00479 0.83147 -0.55556 -0.00242 0.55557 -0.83147 -0.00242 0.19509 -0.98079 0.00000 -0.19508 -0.98078 0.00479 -0.55557 -0.83147 -0.00242 -0.83147 -0.55557 -0.00242 -0.98078 -0.19510 -0.00000 0.00000 1.00000 -0.00000 -0.19510 0.98078 0.00000 -0.43988 0.89769 0.02576 -0.34308 0.92963 -0.13449 -0.12091 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29117 0.13333 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.26954 -0.73824 0.61835 -0.04401 -0.78448 0.61859 0.34486 -0.87107 0.34972 -0.24901 -0.62075 0.74341 -0.53274 -0.67686 0.50798 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71481 -0.55303 -0.49987 0.66655 -0.10705 -0.93718 0.33202 -0.08363 -0.97549 0.20352 -0.95619 0.27850 0.09024 0.81840 -0.55913 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34274 -0.93162 0.12091 0.41584 -0.90391 0.10015 -0.02010 -0.99838 0.05318 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.11791 0.96141 0.24855 -0.28024 0.91713 0.28345 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 -0.21448 0.96105 0.17429 -0.21468 0.96201 0.16869 -0.24706 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05397 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06977 0.99156 -0.10925 -0.34004 -0.62630 0.70151 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50576 -0.84008 0.26126 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08802 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67439 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41725 -0.54080 0.73037 -0.41201 -0.60635 0.68014 -0.70424 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95385 0.19679 0.22679 -0.77616 0.60749 0.16894 -0.89673 0.40568 0.17691 0.33004 -0.80724 0.48932 -0.20020 -0.56807 0.79826 -0.19713 -0.77268 0.60342 -0.56010 -0.42940 0.70845 -0.77051 -0.59690 0.22366 -0.89494 -0.39110 0.21476 -0.86902 -0.31567 0.38100 0.40409 -0.56439 0.71984 0.33802 -0.85130 0.40128 0.52007 -0.78743 0.33090 0.14974 -0.78142 0.60577 -0.67308 -0.65372 0.34586 -0.79487 -0.52330 0.30714 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02855 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01957 -0.79797 0.60051 -0.05130 -0.76800 0.64031 -0.01382 -0.80117 0.58934 -0.10394 -0.76278 0.64443 -0.05371 -0.72711 0.68601 0.02658 -0.71869 0.69533 -0.00068 -0.67621 0.73321 0.07167 -0.19381 -0.87163 0.45023 -0.33486 -0.67114 0.66139 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.10649 -0.94309 0.31503 -0.16500 -0.93292 0.32005 -0.17354 -0.93264 0.31632 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.14311 -0.93869 0.31366 -0.59996 0.78186 -0.16950 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.47585 0.87781 -0.05491 -0.33781 0.94059 0.03414 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.15145 0.98776 0.03735 -0.99876 0.02243 0.04443 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -0.00118 -1.00000 -0.00104 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42687 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.68055 -0.57907 0.44891 -0.55875 0.82932 -0.00524 -0.63044 0.77342 -0.06608 -0.62318 0.78201 -0.01031 -0.62355 0.78160 -0.01687 -0.58167 0.81243 0.04018 -0.58190 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03148 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51068 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40437 0.85353 0.32861 -0.39689 0.83488 0.38139 -0.32068 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 0.00024 -1.00000 -0.00003 -0.00108 -0.99981 0.01924 -0.26638 -0.92815 0.25995 -0.22267 -0.92832 0.29772 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05538 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00095 1.00000 -0.00028 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00746 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 0.32528 0.86091 0.39118 0.33532 0.84040 0.42579 0.23285 0.86496 0.44455 0.25027 0.81275 0.52612 0.17651 0.83818 0.51604 0.10816 0.84369 0.52582 0.11187 0.86176 0.49483 0.00028 0.83866 0.54466 -0.00914 -0.99996 0.00102 -0.00630 -0.99996 0.00607 0.10399 -0.94352 0.31456 0.07081 -0.93620 0.34427 -0.00555 -0.95073 0.30998 0.04525 -0.90484 0.42333 0.25684 -0.87163 0.41749 0.14454 -0.93969 0.30998 0.14440 -0.93971 0.30999 0.14454 -0.93969 0.30997 0.13338 -0.93583 0.32624 0.30399 0.34310 0.88875 0.28039 0.27889 0.91848 0.15528 -0.63718 0.75491 0.25235 -0.50582 0.82490 0.18035 0.44574 0.87681 0.02349 0.38357 0.92321 0.00000 -0.58193 0.81324 0.43016 -0.54482 0.71982 0.39039 -0.60766 0.69162 0.53245 0.40400 0.74383 0.44473 0.03813 0.89485 0.46219 0.52024 0.71814 0.29459 -0.64015 0.70952 0.00016 0.94744 0.31993 0.13733 0.94752 0.28870 0.19414 0.95999 0.20179 0.17056 0.96125 0.21658 0.17105 0.96162 0.21453 0.21458 0.96108 0.17403 0.21475 0.96198 0.16875 0.05806 -0.98803 0.14291 0.06866 -0.98340 0.16795 0.03296 0.95258 0.30251 0.07028 0.94785 0.31086 0.09366 0.95264 0.28931 0.09772 -0.92104 0.37701 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.04460 0.99084 -0.12748 -0.02095 0.99228 -0.12226 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 0.04752 0.99190 -0.11780 -0.16727 -0.92856 0.33134 -0.21990 -0.92662 0.30498 -0.03234 0.95249 0.30284 -0.07021 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.23218 -0.60875 0.75863 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.01264 0.86767 0.49698 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.04880 -0.99862 0.01922 -0.62317 0.78208 -0.00435 -0.79379 0.60818 -0.00359 -0.72015 0.69382 -0.00040 -0.56267 0.82663 -0.00899 0.12908 -0.99163 -0.00064 0.12485 -0.99217 -0.00128 0.36682 -0.93029 -0.00220 0.38166 -0.92430 0.00016 0.51311 -0.85831 -0.00515 0.60885 -0.79305 0.01918 0.81095 -0.58507 0.00715 0.79300 -0.60921 0.00286 0.92422 -0.38184 -0.00239 0.99149 -0.12913 0.01646 0.97569 -0.21914 -0.00014 -0.13521 -0.99081 0.00250 -0.19312 -0.98111 0.01146 -0.38658 -0.92225 -0.00057 -0.50701 -0.86189 0.00957 -0.70726 -0.70678 -0.01571 -0.81114 -0.58481 0.00718 -0.92423 -0.38183 -0.00232 -0.99163 -0.12910 -0.00002 -0.97530 -0.22066 0.00986 0.00033 -1.00000 -0.00064 -0.00366 -0.99999 0.00209 1.00000 0.00000 -0.00002 1.00000 0.00003 -0.00003 1.00000 0.00000 -0.00003 1.00000 0.00006 -0.00012 1.00000 0.00002 -0.00006 1.00000 0.00000 -0.00005 1.00000 0.00000 -0.00004 -1.00000 0.00003 0.00002 -1.00000 -0.00004 0.00002 -1.00000 -0.00002 0.00003 -1.00000 -0.00001 0.00003 -1.00000 -0.00001 0.00003 -1.00000 -0.00000 0.00004 -1.00000 -0.00000 0.00004 -1.00000 0.00000 0.00004 -1.00000 0.00000 0.00004 -1.00000 0.00000 0.00004 0.99387 0.11059 0.00001 0.99399 0.10945 -0.00006 0.94966 0.31330 0.00012 0.94433 0.32901 -0.00064 0.87678 0.48090 0.00059 0.84631 0.53268 -0.00126 0.70722 0.70699 0.00253 0.47877 0.87793 -0.00310 0.53288 0.84619 0.00034 0.38651 0.92228 0.00018 0.30651 0.95187 -0.00200 0.26150 0.96519 -0.00463 0.22112 0.97524 -0.00318 0.12467 0.99220 -0.00086 0.03864 0.99925 0.00018 -0.99400 0.10941 0.00005 -0.99386 0.11061 -0.00001 -0.94966 0.31327 0.00016 -0.94115 0.33798 -0.00103 -0.87679 0.48088 0.00062 -0.84441 0.53570 0.00115 -0.70715 0.70704 0.00622 -0.47694 0.87893 -0.00316 -0.53383 0.84556 0.00651 -0.39699 0.91779 -0.00806 -0.30905 0.95104 -0.00274 -0.23172 0.97278 0.00046 -0.12069 0.99247 -0.02087 -0.17400 0.98465 -0.01340 -0.23705 0.97147 -0.00722 0.00028 1.00000 0.00046 0.00006 1.00000 0.00057 0.00017 1.00000 0.00049 0.53733 0.84337 -0.00092 0.66533 0.74655 -0.00102 0.79725 0.60364 0.00048 -0.23323 0.97240 -0.00623 -0.16937 0.98548 -0.01221 -0.11540 0.99313 -0.01951 -0.22254 0.97492 0.00046 -0.30619 0.95197 -0.00200 -0.53267 0.84630 0.00638 0.21433 -0.97665 -0.01444 0.26119 -0.96529 0.00000 0.51313 -0.85830 -0.00517 0.60868 -0.79319 0.01911 0.81099 -0.58502 0.00702 0.79382 -0.60814 0.00291 0.92413 -0.38208 -0.00241 0.94827 -0.31747 0.00259 0.99163 -0.12910 -0.00280 0.99545 -0.09531 -0.00008 -0.14678 -0.98916 0.00429 -0.12639 -0.99198 -0.00109 -0.19312 -0.98111 0.01146 -0.38648 -0.92230 -0.00056 -0.50699 -0.86190 0.00960 -0.60896 -0.79320 -0.00266 -0.79300 -0.60921 0.00296 -0.81111 -0.58485 0.00728 -0.92422 -0.38184 -0.00231 -0.99163 -0.12915 -0.00002 -0.97530 -0.22066 0.00986 0.00000 -1.00000 0.00000 -0.00025 -1.00000 -0.00009 0.00012 -1.00000 -0.00036 0.00003 -1.00000 -0.00032 -0.00003 -1.00000 -0.00032 -0.00012 -1.00000 -0.00036 -0.00058 -1.00000 -0.00111 0.00015 -1.00000 -0.00017 -0.00298 -0.99999 0.00338 1.00000 -0.00015 -0.00000 1.00000 0.00003 -0.00003 1.00000 0.00000 -0.00003 1.00000 0.00015 -0.00018 1.00000 0.00000 -0.00003 1.00000 0.00005 -0.00011 1.00000 0.00002 -0.00006 1.00000 0.00001 -0.00005 1.00000 0.00000 -0.00004 -1.00000 0.00002 0.00001 -1.00000 -0.00002 0.00001 -1.00000 -0.00002 0.00001 -1.00000 -0.00001 0.00002 -1.00000 -0.00000 0.00002 -1.00000 -0.00000 0.00002 -1.00000 0.00000 0.00002 -1.00000 0.00002 0.00004 0.97040 0.24152 -0.00000 0.99313 0.11603 -0.01492 0.94918 0.31472 -0.00229 0.84408 0.53622 0.00128 0.87546 0.48329 -0.00241 0.70715 0.70705 0.00324 0.79196 0.61055 -0.00573 0.66692 0.74513 0.00165 0.54401 0.83908 -0.00079 0.53605 0.84418 -0.00055 0.46613 0.88471 0.00043 0.34092 0.94009 -0.00055 0.40230 0.91550 -0.00406 0.30021 0.95387 -0.00036 0.11062 0.99386 0.00160 0.24080 0.97054 -0.00825 0.13002 0.99151 -0.00223 0.03755 0.99929 0.00046 -0.99400 0.10941 0.00003 -0.99385 0.11074 -0.00001 -0.94966 0.31327 0.00016 -0.94429 0.32911 -0.00060 -0.87680 0.48086 0.00064 -0.84619 0.53288 0.00117 -0.79340 0.60869 -0.00405 -0.72016 0.69381 -0.00040 -0.70698 0.70721 0.00621 -0.56264 0.82666 -0.00898 -0.62316 0.78208 -0.00434 -0.47691 0.87895 -0.00316 -0.53267 0.84630 0.00638 -0.39694 0.91781 -0.00805 -0.30620 0.95197 -0.00200 -0.22254 0.97492 0.00046 -0.11540 0.99313 -0.01951 -0.16937 0.98548 -0.01221 -0.23323 0.97240 -0.00623 0.00028 1.00000 0.00046 -0.00000 1.00000 0.00054 -0.00028 1.00000 0.00046 -0.00043 1.00000 0.00126 -0.00008 1.00000 0.00073 0.00006 1.00000 0.00057 0.00017 1.00000 0.00049 0.12908 -0.99163 -0.00064 0.12485 -0.99217 -0.00128 0.36682 -0.93029 -0.00220 0.38167 -0.92430 0.00016 0.51311 -0.85831 -0.00515 0.60885 -0.79305 0.01918 0.81095 -0.58507 0.00715 0.79300 -0.60921 0.00286 0.92423 -0.38184 -0.00239 0.94827 -0.31747 0.00259 0.99162 -0.12915 -0.00280 0.99545 -0.09530 -0.00008 -0.12638 -0.99198 0.00114 -0.19312 -0.98111 0.01146 -0.38648 -0.92230 -0.00056 -0.50699 -0.86190 0.00960 -0.60896 -0.79320 -0.00266 -0.79300 -0.60921 0.00296 -0.81111 -0.58485 0.00728 -0.92423 -0.38184 -0.00231 -0.99163 -0.12914 -0.00002 -0.97530 -0.22066 0.00986 0.00033 -1.00000 -0.00064 0.00071 -1.00000 -0.00051 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00071 -1.00000 -0.00051 -0.00435 -0.99999 0.00080 1.00000 0.00000 -0.00002 1.00000 0.00003 -0.00003 1.00000 0.00000 -0.00004 1.00000 0.00006 -0.00012 1.00000 0.00002 -0.00006 1.00000 0.00000 -0.00005 1.00000 -0.00000 -0.00004 -1.00000 0.00003 0.00002 -1.00000 -0.00004 0.00002 -1.00000 -0.00002 0.00003 -1.00000 -0.00001 0.00003 -1.00000 -0.00001 0.00003 -1.00000 -0.00000 0.00004 -1.00000 -0.00000 0.00004 -1.00000 -0.00000 0.00004 0.99386 0.11062 0.00001 0.99399 0.10945 -0.00006 0.94965 0.31330 0.00012 0.94429 0.32911 -0.00064 0.87678 0.48090 0.00059 0.84619 0.53288 -0.00126 0.79725 0.60365 0.00048 0.66534 0.74654 -0.00101 0.70699 0.70722 0.00251 0.53731 0.84339 -0.00092 0.47873 0.87796 -0.00308 0.53268 0.84632 0.00034 0.38651 0.92228 0.00018 0.30648 0.95187 -0.00200 0.22253 0.97490 -0.00686 0.24080 0.97054 -0.00825 0.13002 0.99151 -0.00223 0.03755 0.99929 0.00046 -0.99400 0.10941 0.00005 -0.99386 0.11063 -0.00001 -0.94966 0.31327 0.00016 -0.94429 0.32911 -0.00060 -0.87680 0.48086 0.00064 -0.84619 0.53288 0.00117 -0.79340 0.60869 -0.00405 -0.72016 0.69381 -0.00040 -0.70698 0.70721 0.00621 -0.56264 0.82666 -0.00898 -0.62316 0.78208 -0.00434 -0.47691 0.87895 -0.00316 -0.39694 0.91781 -0.00805 0.00028 1.00000 0.00046 -0.00000 1.00000 0.00054 -0.00028 1.00000 0.00046 -0.00043 1.00000 0.00126 -0.00008 1.00000 0.00073 0.00006 1.00000 0.00057 0.00017 1.00000 0.00049 -0.22254 0.97492 -0.00234 -0.26529 0.96412 -0.00948 -0.53130 0.84719 -0.00015 -0.53268 0.84632 0.00012 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00015 -1.00000 0.00004 0.00000 -0.26530 0.96416 -0.00233 -0.23574 0.97161 0.02001 -0.62513 -0.77886 0.05084 -0.30181 -0.95305 0.02454 -0.33016 -0.94392 0.00462 -0.32954 -0.94413 -0.00426 -0.00008 -1.00000 -0.00111 0.00056 -1.00000 0.00003 -0.12638 -0.99198 -0.00000 -0.12638 -0.99198 0.00000 -0.27370 -0.95899 -0.07368 -0.38588 -0.92099 -0.05363 -0.54347 -0.83600 -0.07576 -0.60829 -0.79233 -0.04689 -0.79300 -0.60922 0.00054 -0.92423 -0.38184 -0.00242 -0.91610 -0.40095 0.00194 -0.99043 -0.13802 0.00000 -0.99162 -0.12914 -0.00186 0.59854 -0.77997 0.18275 0.78515 -0.60149 0.14748 0.26397 -0.96113 0.08090 0.26035 -0.96202 0.08208 0.75170 -0.63672 0.17185 0.90408 -0.37380 0.20713 0.99118 -0.12904 0.03021 0.92888 -0.27427 0.24889 0.51993 -0.74683 0.41463 0.75982 -0.23558 0.60594 0.77282 -0.22598 0.59303 0.58640 -0.26856 0.76420 0.12797 -0.97041 0.20478 0.22703 -0.94630 0.23016 0.39792 -0.65997 0.63726 0.42274 -0.22529 0.87780 0.37068 -0.24842 0.89492 0.30668 -0.70741 0.63681 0.08815 -0.96538 0.24549 0.03413 -0.69185 0.72123 0.01227 -0.96574 0.25923 -0.01021 -0.97131 0.23759 0.03891 -0.96590 0.25596 0.12597 -0.26255 0.95666 0.00000 -0.22183 0.97508 0.00000 -0.70988 0.70432 -0.12597 -0.26255 0.95666 -0.06132 -0.96523 0.25410 -0.09606 -0.96739 0.23438 -0.10206 -0.96965 0.22217 -0.27445 -0.69009 0.66966 -0.30460 -0.71216 0.63249 -0.42087 -0.24324 0.87390 -0.37402 -0.21156 0.90297 -0.58640 -0.26856 0.76420 -0.15351 -0.96492 0.21301 -0.18300 -0.96848 0.16898 -0.18275 -0.96816 0.17110 -0.53285 -0.68846 0.49203 -0.54720 -0.71424 0.43638 -0.76094 -0.22959 0.60684 -0.77050 -0.23824 0.59124 -0.22247 -0.96497 0.13907 -0.24525 -0.96149 0.12403 -0.23841 -0.96689 0.09105 -0.63264 -0.70511 0.32027 -0.89045 -0.26656 0.36884 -0.60736 -0.78471 0.12386 -0.94578 -0.22726 0.23205 -0.30183 -0.95192 0.05238 -0.98211 -0.13686 0.12930 -0.87393 -0.38315 -0.29908 0.12908 -0.99163 0.00033 0.38166 -0.92430 0.00252 0.60810 -0.79208 -0.05302 0.69821 -0.71585 -0.00770 0.79300 -0.60921 -0.00311 0.92423 -0.38184 0.00099 0.91548 -0.40234 -0.00327 0.99095 -0.13426 -0.00100 0.99163 -0.12915 -0.00000 0.67743 -0.71061 0.19003 0.88672 -0.38978 0.24859 0.98583 -0.13356 0.10149 0.97943 -0.15522 0.12895 0.10904 -0.99402 0.00652 0.28762 -0.95764 -0.01413 0.68539 -0.69506 0.21709 0.24734 -0.96725 0.05695 0.20292 -0.97617 0.07692 0.89297 -0.25650 0.36988 0.22286 -0.96491 0.13884 0.49582 -0.71298 0.49581 0.51918 -0.70066 0.48941 0.68460 -0.25032 0.68459 0.78373 -0.15523 0.60139 0.58840 -0.25650 0.76681 0.18134 -0.96845 0.17094 0.18256 -0.96826 0.17072 0.15336 -0.96494 0.21299 0.26708 -0.68755 0.67523 0.09075 -0.96909 0.22942 0.10609 -0.96697 0.23177 0.36989 -0.25651 0.89296 0.17791 -0.72629 0.66397 0.25313 -0.20840 0.94472 0.12617 -0.25650 0.95828 0.06062 -0.96534 0.25385 0.01025 -0.96595 0.25851 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00016 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00018 -1.00000 -0.00016 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00005 -1.00000 -0.00120 -0.00028 -1.00000 -0.00000 -0.00056 -1.00000 0.00001 -0.00056 -1.00000 -0.00001 0.00056 -1.00000 0.00000 -0.00056 -1.00000 0.00000 -0.24527 0.96827 0.04780 -0.22826 0.97176 0.05986 -0.52672 0.83982 0.13141 -0.70313 0.70313 0.10591 -0.84328 0.53711 -0.01968 -0.68443 0.70188 0.19728 -0.91749 0.34514 0.19771 -0.99384 0.11078 0.00430 -0.94986 0.24120 0.19899 -0.23784 0.96508 0.10975 -0.55995 0.69789 0.44655 -0.20444 0.96521 0.16304 -0.16393 0.97257 0.16503 -0.20874 0.96701 0.14602 -0.55995 0.69789 0.44655 -0.75861 0.24188 0.60498 -0.78418 0.21995 0.58024 -0.14822 0.96543 0.21440 -0.10833 0.96833 0.22495 -0.10224 0.96931 0.22358 -0.31075 0.69789 0.64528 -0.31076 0.69788 0.64528 -0.41901 0.25970 0.87005 -0.50302 0.19754 0.84140 -0.06555 0.96514 0.25339 -0.17992 0.26654 0.94688 0.00000 0.96591 0.25888 0.02339 0.97201 0.23378 -0.01965 0.96671 0.25511 -0.00000 0.69788 0.71621 -0.00000 0.20957 0.97779 0.00000 0.69788 0.71621 0.18328 0.26830 0.94574 0.07118 0.96528 0.25131 0.10779 0.96865 0.22382 0.10822 0.96879 0.22301 0.31075 0.69788 0.64528 0.31076 0.69789 0.64528 0.42374 0.21506 0.87988 0.50829 0.25765 0.82174 0.15352 0.96523 0.21155 0.19299 0.96906 0.15390 0.19411 0.96633 0.16891 0.55995 0.69789 0.44655 0.76121 0.22812 0.60705 0.77241 0.23995 0.58806 0.55995 0.69789 0.44655 0.68963 0.70055 0.18341 0.34029 0.93821 0.06303 0.10972 0.98575 -0.12748 0.22349 0.97461 0.01382 0.23798 0.97024 0.04480 0.24426 0.96571 0.08796 0.82646 0.52526 0.20264 0.70487 0.70478 0.08027 0.53585 0.82616 -0.17414 0.95148 0.24029 0.19223 0.95126 0.23679 0.19759 -0.23579 0.97181 0.00000 -0.70710 0.70711 -0.00012 -0.70699 0.70722 -0.00015 -0.84619 0.53288 0.00015 -0.84349 0.53714 0.00100 -0.94429 0.32911 0.00023 -0.93617 0.35152 -0.00378 -0.99384 0.11079 -0.00023 -0.99386 0.11063 -0.00020 0.16683 0.98599 0.00000 0.22253 0.97488 0.00961 0.31131 0.95029 -0.00559 0.53268 0.84632 0.00090 0.53728 0.84340 0.00012 0.70711 0.70710 -0.00015 0.70699 0.70722 -0.00012 0.84619 0.53288 0.00015 0.84836 0.52942 -0.00054 0.94428 0.32911 -0.00505 0.96584 0.25905 0.00604 0.99276 0.11050 -0.04718 0.00000 0.96675 0.25571 0.01835 0.97120 0.23754 -0.00000 0.20957 0.97779 0.00000 0.69788 0.71621 0.18328 0.26830 0.94574 0.06562 0.96514 0.25337 0.31075 0.69788 0.64528 0.10721 0.96899 0.22263 0.10421 0.96814 0.22770 0.31076 0.69789 0.64528 0.42374 0.21507 0.87988 0.50828 0.25766 0.82175 0.14825 0.96544 0.21437 0.19861 0.96720 0.15839 0.19691 0.97068 0.13784 0.18227 0.96597 0.18353 0.55995 0.69788 0.44655 0.55995 0.69789 0.44655 0.76122 0.22813 0.60705 0.77262 0.24018 0.58769 0.23784 0.96508 0.10979 0.69018 0.70040 0.18194 0.31053 0.94863 0.06057 0.16655 0.98433 -0.05799 0.22783 0.97351 0.01938 0.24344 0.96781 0.06389 0.83000 0.51819 0.20635 0.70480 0.70479 0.08073 0.52727 0.82929 -0.18511 0.95178 0.23848 0.19296 0.95034 0.22152 0.21859 -0.99144 0.00004 0.13053 -0.97866 -0.00244 0.20549 -0.92388 0.00192 0.38268 -0.79334 0.00031 0.60877 -0.80376 -0.00036 0.59495 -0.60876 0.00190 0.79335 -0.51344 -0.00119 0.85812 -0.38268 0.00185 0.92388 -0.18634 -0.00064 0.98248 -0.13055 0.00120 0.99144 0.13055 0.00115 0.99144 0.19012 -0.00084 0.98176 0.38268 0.00203 0.92388 0.52607 -0.00097 0.85044 0.60877 0.00168 0.79335 0.79334 -0.00021 0.60878 0.79577 -0.00005 0.60559 0.96593 0.00000 0.25882 0.96593 0.00000 0.25882 0.97732 0.00358 0.21172 0.13054 0.00115 0.99144 0.19012 -0.00084 0.98176 0.38269 0.00203 0.92387 0.52607 -0.00097 0.85044 0.60877 0.00168 0.79335 0.79335 -0.00024 0.60876 0.79603 -0.00005 0.60525 0.92388 0.00218 0.38269 0.97412 -0.00171 0.22602 0.99144 -0.00000 0.13053 0.99246 0.00030 0.12254 0.97908 -0.00023 0.20350 0.99991 -0.01225 0.00613 1.00000 0.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00003 1.00000 -0.00027 0.00000 1.00000 0.00000 0.00239 -1.00000 0.00010 -0.00081 -1.00000 0.00244 -0.00022 -1.00000 0.00214 0.00022 -1.00000 0.00214 0.00081 -1.00000 0.00244 -0.00097 -1.00000 0.00113 1.00000 0.00000 -0.00002 0.12908 -0.99163 0.00065 0.26385 -0.96435 -0.02034 -0.04513 -0.68002 0.73180 -0.01600 -0.96561 0.25949 -0.03666 -0.97146 0.23435 -0.12616 -0.25650 0.95827 -0.17643 -0.73165 0.65845 -0.25313 -0.20840 0.94472 -0.08960 -0.96526 0.24546 -0.36989 -0.25651 0.89296 -0.40714 -0.65620 0.63533 -0.28836 -0.84526 0.44988 -0.17366 -0.97868 0.10966 -0.16250 -0.97165 0.17170 -0.49668 -0.71177 0.49668 -0.68460 -0.25032 0.68459 -0.60138 -0.15522 0.78374 -0.76681 -0.25650 0.58840 -0.89297 -0.25650 0.36988 -0.69498 -0.69451 0.18616 -0.73522 -0.59489 0.32490 -0.94448 -0.20867 0.25378 -0.98329 -0.12801 0.12945 -0.89309 -0.36896 -0.25740 -0.38120 -0.90897 0.16872 -0.26085 -0.96261 0.07303 -0.13240 -0.98940 0.05973 0.38166 -0.92430 -0.00263 0.59840 -0.80118 -0.00505 0.60896 -0.79320 -0.00278 0.70648 -0.70773 -0.00068 0.79286 -0.60911 0.01879 0.92406 -0.38178 0.01887 0.99163 -0.12914 -0.00018 0.97953 -0.20107 -0.00960 1.00000 -0.00157 -0.00043 -0.00002 -1.00000 -0.00068 -0.00002 -1.00000 0.00013 -0.00002 -1.00000 0.00006 -0.00002 -1.00000 0.00002 -0.00210 -1.00000 0.00111 -0.00048 -0.99999 -0.00524 0.00239 -1.00000 0.00008 -0.00185 -1.00000 -0.00213 -0.23168 0.97269 0.01428 -0.52948 0.83808 0.13144 -0.70321 0.70311 0.10552 -0.84427 0.53553 -0.02043 -0.36553 0.92804 0.07157 -0.11223 0.98871 0.09933 -0.23637 0.97137 0.02405 -0.21941 0.97476 0.04124 -0.92473 0.33145 0.18711 -0.99386 0.11061 0.00329 -0.97843 0.17869 0.10364 -0.68003 0.70286 0.20867 -0.86266 0.26917 0.42822 -0.55995 0.69789 0.44655 -0.20169 0.96615 0.16085 -0.32623 0.93363 0.14802 -0.55996 0.69788 0.44655 -0.76421 0.21114 0.60943 -0.65944 0.26063 0.70514 -0.15344 0.96524 0.21161 -0.10763 0.96874 0.22350 -0.10839 0.96863 0.22363 -0.31075 0.69789 0.64528 -0.42056 0.24599 0.87328 -0.49292 0.20030 0.84671 -0.31076 0.69788 0.64528 -0.07108 0.96528 0.25135 -0.17992 0.26654 0.94688 -0.00000 0.69788 0.71621 -0.02558 0.96626 0.25629 -0.99433 0.00000 0.10630 -0.99433 0.00000 0.10630 -0.99433 0.00000 0.10630 -0.99144 0.00083 0.13052 -0.92388 0.00121 0.38268 -0.89566 -0.00093 0.44475 -0.79335 0.00213 0.60876 -0.68423 -0.00064 0.72926 -0.60876 0.00107 0.79336 -0.50231 -0.00092 0.86468 -0.38270 0.00185 0.92387 -0.18634 -0.00064 0.98249 -0.13053 0.00121 0.99144 -0.11256 0.98952 0.09042 -0.37715 -0.49770 0.78106 -0.59381 -0.68830 0.41668 -0.45311 -0.80432 0.38439 0.74346 0.33559 -0.57849 0.75130 0.33239 -0.57015 0.36334 0.45632 -0.81226 0.37411 0.45573 -0.80768 0.37906 0.45604 -0.80519 0.05928 0.37141 -0.92657 0.24949 0.53468 -0.80739 0.13607 0.40198 -0.90548 0.84200 0.53395 -0.07701 0.45374 0.88933 0.05672 -0.67410 0.25741 0.69233 -0.68432 0.22999 0.69196 -0.64363 0.42045 0.63950 -0.63039 0.44778 0.63411 -0.58248 0.57083 0.57868 -0.56772 0.59291 0.57110 -0.50387 0.70406 0.50042 -0.48856 0.72086 0.49159 -0.41016 0.81613 0.40707 -0.39523 0.82794 0.39788 -0.29042 0.91105 0.29267 -0.89026 0.08336 -0.44776 -0.98699 0.09845 0.12712 -0.83906 0.09969 -0.53482 0.00027 0.72315 -0.69069 -0.00075 0.79510 -0.60648 -0.00942 0.78022 -0.62544 0.00268 0.83536 -0.54970 -0.00015 0.88490 -0.46577 0.00118 0.88758 -0.46066 -0.00114 0.95005 -0.31208 -0.00107 0.95014 -0.31182 0.00095 0.98598 -0.16688 -0.00292 0.98873 -0.14970 0.07724 0.99701 -0.00011 0.02792 0.99948 -0.01585 0.01220 0.99952 -0.02851 0.00275 0.99912 -0.04177 0.00147 0.99902 -0.04424 -0.00835 0.99982 0.01685 -0.00300 0.99991 -0.01309 -0.01646 0.99969 -0.01894 0.00126 0.99753 0.07023 -0.05103 0.99303 0.10622 0.42260 0.81392 -0.39867 0.47354 0.81794 -0.32669 0.93251 0.35202 -0.08070 0.36861 0.88323 -0.28987 0.92923 0.35781 -0.09215 0.43148 0.89183 -0.13591 0.39751 0.90473 -0.15313 0.91065 0.40845 -0.06225 0.92550 0.37665 -0.03978 0.33633 0.94174 0.00087 0.55095 0.83364 0.03868 0.27862 0.95992 -0.03051 0.92007 0.39097 0.02488 0.91019 0.41383 0.01724 0.98768 0.15374 0.02932 0.90263 0.43039 -0.00503 0.45179 0.02711 0.89171 0.46010 0.01347 0.88777 -0.18918 0.08439 0.97831 0.00749 0.13905 0.99026 0.50969 0.06569 0.85785 -0.49433 0.27846 0.82347 0.50650 0.11765 0.85418 0.50904 0.11294 0.85330 0.04395 0.30685 0.95074 -0.38456 0.41000 0.82705 -0.40103 0.42869 0.80957 0.04395 0.30685 0.95074 0.53655 0.14504 0.83131 -0.38334 0.57562 0.72229 0.12749 0.48136 0.86720 0.54343 0.17994 0.81995 0.53680 0.19865 0.81999 -0.26208 0.64036 0.72198 -0.28997 0.69621 0.65666 0.12749 0.48136 0.86720 0.57854 0.20950 0.78829 -0.20180 0.80021 0.56474 0.58076 0.23874 0.77828 0.24354 0.61356 0.75116 -0.10716 0.81604 0.56798 0.24354 0.61356 0.75116 0.60567 0.23195 0.76116 -0.11253 0.88419 0.45337 0.63524 0.26748 0.72452 0.63264 0.25378 0.73169 0.38189 0.69184 0.61280 0.38189 0.69183 0.61280 0.04978 0.93137 0.36064 0.06235 0.91482 0.39903 0.10809 0.96864 0.22372 -0.65727 0.54030 -0.52543 -0.62486 0.54410 -0.55992 -0.55243 0.58988 -0.58896 -0.47768 0.62122 -0.62122 -0.43485 0.61798 -0.65499 -0.50265 0.60914 -0.61343 -0.30034 0.67446 -0.67446 -0.31049 0.67352 -0.67080 -0.13273 0.69985 -0.70185 -0.08938 0.70704 -0.70150 0.04633 0.70428 -0.70840 0.15908 0.70319 -0.69298 0.22622 0.68940 -0.68815 0.32898 0.67175 -0.66372 0.40733 0.64372 -0.64784 0.53846 0.59823 -0.59344 0.52581 0.60510 -0.59781 0.70531 0.50957 -0.49282 0.76467 0.45585 -0.45550 0.81939 0.40451 -0.40616 0.84882 0.37910 -0.36848 0.94535 0.23085 -0.23027 0.95095 0.21682 -0.22062 0.99530 0.06846 -0.06846 0.99306 0.08515 -0.08117 0.13061 -0.87210 -0.47158 -0.28867 0.93989 0.18241 0.07548 -0.86680 -0.49291 0.07969 -0.86364 -0.49776 0.12792 -0.78522 -0.60586 0.08530 -0.74672 -0.65965 0.11121 -0.67497 -0.72942 0.07330 -0.63522 -0.76884 0.09116 -0.54544 -0.83318 0.05995 -0.50932 -0.85849 0.06785 -0.40086 -0.91362 0.04496 -0.37257 -0.92692 0.04266 -0.24540 -0.96848 0.02877 -0.22766 -0.97332 0.01187 -0.08264 -0.99651 0.01506 -0.07613 -0.99698 0.00009 -0.00006 -1.00000 0.00000 0.00000 -1.00000 -0.00415 0.00383 -0.99998 0.45196 0.00000 0.89204 0.70676 0.00501 0.70744 0.70604 0.00537 0.70815 0.70521 0.00563 0.70898 0.70422 0.00573 0.70996 0.69843 0.00000 0.71568 0.69859 0.00104 0.71552 0.69945 0.00288 0.71468 0.70060 0.00424 0.71354 0.70187 0.00513 0.71229 0.70310 0.00559 0.71107 0.00232 0.00474 -0.99999 -0.05594 -0.82159 -0.56733 0.18420 -0.79108 -0.58332 0.01476 -0.85919 -0.51144 -0.02640 -0.81272 -0.58206 -0.00329 -0.79008 -0.61299 0.05582 -0.74993 -0.65915 -0.03087 -0.67896 -0.73353 -0.02185 -0.66944 -0.74255 0.02603 -0.66920 -0.74262 0.04197 -0.63876 -0.76826 -0.02325 -0.50375 -0.86353 0.02718 -0.49542 -0.86823 0.01392 -0.51455 -0.85735 -0.01631 -0.49574 -0.86832 0.03194 -0.37419 -0.92680 -0.01449 -0.30661 -0.95172 -0.00148 -0.30141 -0.95349 -0.01018 -0.30144 -0.95343 0.02324 -0.22837 -0.97330 0.00106 -0.10242 -0.99474 -0.00525 -0.10051 -0.99492 -0.00766 -0.10056 -0.99490 -0.00527 -0.10054 -0.99492 0.00474 -0.07745 -0.99698 -0.04890 -0.88888 -0.45552 0.03656 -0.88033 -0.47296 -0.00338 -0.91134 -0.41164 -0.07234 -0.88355 -0.46272 0.06737 -0.89477 -0.44141 0.13924 -0.88713 -0.44001 -0.06006 -0.91885 -0.39001 0.03747 -0.90785 -0.41762 -0.07678 -0.91604 -0.39366 0.18202 -0.90555 -0.38321 0.06209 -0.93108 -0.35948 0.18925 -0.89988 -0.39294 -0.05695 -0.94552 -0.32055 -0.17298 -0.94479 -0.27829 0.06640 -0.92905 -0.36394 -0.06606 -0.94450 -0.32179 -0.19546 -0.94709 -0.25457 0.22966 -0.90665 -0.35389 0.23196 -0.90445 -0.35801 0.09473 -0.94707 -0.30674 -0.04324 -0.96755 -0.24897 -0.04016 -0.96668 -0.25281 -0.16996 -0.96704 -0.18962 0.09834 -0.94518 -0.31139 -0.29756 -0.94782 -0.11447 -0.18253 -0.96779 -0.17341 -0.31953 -0.94384 -0.08410 0.27078 -0.90621 -0.32476 0.12917 -0.95774 -0.25701 0.27121 -0.90576 -0.32565 0.27078 -0.90621 -0.32476 -0.01230 -0.98267 -0.18494 0.12202 -0.90000 -0.41847 0.12154 -0.89963 -0.41940 0.12733 -0.90868 -0.39761 0.13045 -0.92160 -0.36555 0.12863 -0.95634 -0.26244 0.22744 -0.89579 -0.38188 0.10051 -0.98546 -0.13696 0.19128 -0.93592 -0.29575 0.20627 -0.92579 -0.31682 0.13608 -0.91802 -0.37246 0.19814 -0.86524 -0.46054 0.16070 -0.93835 -0.30605 0.20875 -0.92419 -0.31983 0.21013 -0.92360 -0.32064 0.25633 -0.91574 -0.30937 0.24110 -0.90305 -0.35548 0.26061 -0.87912 -0.39904 0.27250 -0.89162 -0.36161 0.26061 -0.87912 -0.39904 0.30326 -0.90227 -0.30651 0.30924 -0.88496 -0.34816 0.29164 -0.89289 -0.34306 0.30035 -0.87672 -0.37570 0.30035 -0.87672 -0.37570 0.33924 -0.87821 -0.33714 0.33340 -0.88131 -0.33488 0.33451 -0.87413 -0.35213 0.33451 -0.87413 -0.35213 0.36553 -0.87122 -0.32767 0.36579 -0.87163 -0.32628 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00301 0.00003 1.00000 0.00008 0.00033 0.99996 -0.00341 -0.00777 0.99898 0.04513 -0.00040 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 0.83796 -0.54485 -0.03095 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 -0.71717 0.05795 0.69448 -0.55497 0.21372 0.80395 -0.80723 0.52726 0.26529 -0.72129 0.59767 0.35003 -0.78294 0.61492 0.09420 0.88315 -0.44351 0.15278 0.86726 -0.46700 0.17254 0.98507 -0.12747 0.11567 0.95233 -0.18593 0.24185 0.81160 -0.07581 0.57928 -0.06885 0.13460 0.98851 0.90736 -0.09318 0.40990 0.99993 -0.00799 0.00884 0.94954 -0.03318 0.31188 0.99791 -0.00455 0.06442 0.94000 -0.00574 0.34113 0.99982 0.00158 0.01894 0.81201 0.03161 0.58278 0.98286 0.04225 0.17947 0.98113 0.05168 0.18633 0.30593 -0.90594 -0.29269 0.47175 -0.88147 0.02145 0.49683 -0.86265 0.09489 0.69753 -0.71612 0.02514 0.69333 -0.72050 0.01343 0.37837 -0.87151 -0.31194 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 0.99978 0.01109 -0.01755 -0.32529 0.15854 -0.93223 -0.92768 0.09334 -0.36152 -0.42575 0.40413 -0.80958 -0.56426 0.33499 -0.75458 -0.89192 0.20196 -0.40458 -0.91677 0.16322 -0.36454 -0.34179 0.51889 -0.78354 -0.93004 0.20418 -0.30550 -0.46187 0.61849 -0.63572 -0.51754 0.58453 -0.62488 -0.89722 0.30792 -0.31650 -0.90712 0.28921 -0.30577 -0.33487 0.74919 -0.57147 -0.93086 0.29206 -0.21953 -0.48856 0.76967 -0.41100 -0.89255 0.40082 -0.20663 -0.01301 0.68308 -0.73023 0.96410 -0.25286 -0.08105 0.64621 -0.73047 -0.22098 0.65241 -0.72431 -0.22303 0.96329 -0.25501 -0.08391 0.65790 -0.71270 -0.24336 0.65631 -0.71352 -0.24524 0.89654 -0.41889 -0.14403 0.98256 -0.16595 -0.08387 0.96316 -0.25567 -0.08343 0.66412 -0.70490 -0.24912 0.33921 -0.88929 -0.30675 0.35368 -0.88176 -0.31211 0.36578 -0.87832 -0.30785 0.35780 -0.88287 -0.30417 0.39110 -0.87570 -0.28317 0.39121 -0.87564 -0.28322 0.36335 -0.87253 -0.32660 0.38429 -0.87037 -0.30786 0.37983 -0.87319 -0.30540 0.39741 -0.86898 -0.29485 0.38260 -0.86873 -0.31451 0.39150 -0.86707 -0.30810 0.39069 -0.86763 -0.30753 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.99995 -0.00744 0.00702 1.00000 0.00000 0.00000 0.99996 0.00838 -0.00276 1.00000 0.00000 -0.00000 0.01280 0.00534 -0.99990 0.04314 0.03423 -0.99848 -0.00008 0.00033 -1.00000 -0.26483 -0.01101 -0.96423 -0.40300 -0.00013 -0.91520 -0.60877 0.00076 -0.79335 -0.79332 0.00264 -0.60880 -0.95903 -0.00358 -0.28327 -0.94703 -0.00119 -0.32113 -0.88914 0.07034 -0.45220 -0.26074 0.17494 -0.94943 -0.60418 0.12249 -0.78737 -0.78350 0.15685 -0.60126 -0.95857 0.03104 -0.28314 0.01280 0.16519 -0.98618 0.00217 -0.99999 -0.00248 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 0.22443 -0.76869 -0.59896 -0.47303 0.77964 -0.41037 -0.90459 0.37603 -0.20080 -0.33698 0.89449 -0.29383 -0.93004 0.35022 -0.11127 -0.50689 0.84780 -0.15586 -0.43248 0.89148 -0.13498 -0.91310 0.40102 -0.07372 -0.87135 0.48590 -0.06817 -0.34806 0.93734 0.01580 -0.92763 0.37333 0.01075 -0.92204 0.38397 0.04897 -0.83964 0.53267 0.10616 -0.51768 0.84870 0.10824 -0.39748 0.90213 0.16787 -0.36773 0.87320 0.31983 -0.92352 0.35834 0.13674 -0.77819 0.56879 0.26627 -0.59766 0.73597 0.31803 -0.34482 0.88488 0.31320 -0.89380 0.40803 0.18608 -0.94013 0.29360 0.17308 -0.99322 0.08881 0.07497 -0.94116 0.30504 0.14549 -0.00285 0.98312 0.18294 0.01444 0.96237 0.27134 -0.04490 0.93805 0.34359 0.97987 -0.00926 -0.19942 0.83517 -0.06883 -0.54566 0.39271 -0.03282 -0.91907 0.52149 -0.10815 -0.84638 0.20219 -0.20117 -0.95846 0.98308 -0.04581 -0.17736 0.98040 -0.06235 -0.18691 0.83464 -0.17429 -0.52249 0.56861 -0.26034 -0.78032 0.83461 -0.17433 -0.52252 0.50097 -0.31907 -0.80450 0.29605 -0.35214 -0.88789 0.39530 -0.30590 -0.86612 0.98329 -0.07454 -0.16608 0.98049 -0.10182 -0.16812 0.83454 -0.28541 -0.47126 0.58231 -0.42119 -0.69535 0.83450 -0.28547 -0.47129 0.22118 -0.47357 -0.85253 0.40922 -0.54545 -0.73145 0.39100 -0.55458 -0.73455 0.48856 -0.52159 -0.69946 0.98275 -0.10354 -0.15325 0.83441 -0.38578 -0.39361 0.98112 -0.13537 -0.13812 0.98154 -0.13290 -0.13754 0.58798 -0.56623 -0.57764 0.83438 -0.38585 -0.39362 0.24479 -0.70319 -0.66753 0.37732 -0.79371 -0.47713 0.66848 -0.62182 -0.40802 0.36523 -0.82975 -0.42204 0.98297 -0.14883 -0.10782 0.83429 -0.46816 -0.29117 0.98016 -0.16832 -0.10468 0.52732 -0.74838 -0.40232 0.76900 -0.57053 -0.28834 0.98325 -0.16413 -0.07920 0.98411 -0.16712 -0.05997 0.97938 -0.19452 -0.05453 0.79208 -0.58936 -0.15897 0.54847 -0.81781 -0.17425 0.83754 -0.50942 -0.19754 0.24116 -0.90679 -0.34580 0.23757 -0.90988 -0.34012 0.28245 -0.89439 -0.34682 0.21185 -0.87484 -0.43563 0.35111 -0.77042 -0.53213 0.23246 -0.82996 -0.50707 0.36607 -0.76433 -0.53084 0.29801 -0.85201 -0.43044 0.15126 -0.85211 -0.50103 0.26637 -0.83419 -0.48288 0.35981 -0.76995 -0.52699 0.33968 -0.67842 -0.65144 0.15536 -0.69272 -0.70427 0.22851 -0.53218 -0.81521 0.12734 -0.61217 -0.78041 0.19141 -0.54438 -0.81671 0.15352 -0.61284 -0.77515 0.14113 -0.50569 -0.85109 0.17977 -0.48039 -0.85844 0.16662 -0.33673 -0.92674 0.13565 -0.36900 -0.91948 0.09008 -0.36191 -0.92785 0.09373 -0.35656 -0.92956 0.03520 -0.22558 -0.97359 0.08755 -0.21464 -0.97276 0.15205 -0.07548 -0.98549 0.01352 -0.12812 -0.99167 0.02579 -0.07399 -0.99693 -0.99738 0.05116 -0.05116 -0.99899 0.04470 -0.00439 -0.98455 0.12134 -0.12622 -0.97560 0.17227 -0.13609 -0.95772 0.20045 -0.20639 -0.92994 0.26932 -0.25035 -0.93731 0.26907 -0.22147 -0.89702 0.31184 -0.31322 -0.86148 0.36518 -0.35284 -0.84974 0.36469 -0.38070 -0.77099 0.45751 -0.44301 -0.74932 0.45996 -0.47640 0.98449 -0.17173 -0.03594 0.86553 -0.50071 0.01216 0.58103 -0.79151 -0.18954 0.45332 -0.87269 -0.18143 0.71134 -0.66686 -0.22201 0.66082 -0.72341 -0.19999 0.95265 -0.29031 -0.09049 0.96087 -0.26854 -0.06801 0.96093 -0.26548 -0.07836 0.23368 -0.92081 -0.31226 0.31773 -0.91141 -0.26148 0.27299 -0.92805 -0.25336 0.27643 -0.90848 -0.31344 0.32752 -0.90330 -0.27710 0.30867 -0.91302 -0.26667 0.39194 -0.87588 -0.28144 0.31510 -0.92106 -0.22882 0.31712 -0.91312 -0.25623 0.35462 -0.87823 -0.32087 -1.00000 0.00003 -0.00010 -1.00000 0.00119 -0.00002 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00072 -0.00011 -1.00000 -0.00104 0.00006 -1.00000 0.00008 -0.00002 -1.00000 0.00004 -0.00002 -1.00000 0.00003 -0.00002 -1.00000 0.00002 -0.00002 -1.00000 0.00001 -0.00001 -1.00000 0.00001 -0.00001 -1.00000 0.00001 -0.00001 -1.00000 0.00000 -0.00001 -1.00000 0.00000 -0.00001 -1.00000 -0.00014 0.00006 -1.00000 0.00027 -0.00002 -0.00214 0.07474 -0.99720 -0.00000 0.07845 -0.99692 0.00194 0.22262 -0.97490 -0.00385 0.23343 -0.97237 0.00365 0.36554 -0.93079 -0.00548 0.38265 -0.92388 0.00517 0.50018 -0.86590 -0.00693 0.52245 -0.85264 0.00652 0.62359 -0.78173 -0.00818 0.64940 -0.76040 0.00767 0.73307 -0.68011 -0.00922 0.76035 -0.64944 -0.02101 0.92367 -0.38262 -0.01645 0.97224 -0.23343 -0.00000 0.99824 -0.05927 0.35722 0.17212 -0.91802 0.11166 0.07428 -0.99097 0.96038 0.02415 -0.27766 0.98787 0.10823 -0.11131 0.93250 0.04989 -0.35771 0.69547 0.07868 -0.71423 0.82909 0.18337 -0.52819 0.70147 0.12593 -0.70149 0.52989 0.11076 -0.84080 0.31479 0.13244 -0.93988 0.24810 0.21566 -0.94442 0.96721 0.06551 -0.24540 0.96565 0.10962 -0.23559 0.96253 0.10377 -0.25053 0.70945 0.26970 -0.65111 0.27135 0.35183 -0.89587 0.31293 0.38072 -0.87013 0.69322 0.28890 -0.66029 0.24214 0.48530 -0.84015 0.96571 0.14876 -0.21279 0.71432 0.42602 -0.55520 0.96251 0.16513 -0.21521 0.68874 0.46005 -0.56036 0.28820 0.59714 -0.74858 0.30555 0.60419 -0.73593 0.96720 0.17949 -0.17972 0.23996 0.71167 -0.66026 0.71854 0.55177 -0.42339 0.96566 0.21274 -0.14912 0.96253 0.21514 -0.16509 0.59454 0.70061 -0.39455 0.34383 0.81964 -0.45823 0.32452 0.82202 -0.46793 0.96570 0.23530 -0.10984 0.68411 0.67386 -0.27912 0.96251 0.25060 -0.10380 0.96720 0.24532 -0.06582 0.35188 0.90903 -0.22328 0.34778 0.91888 -0.18628 0.70146 0.70148 -0.12599 0.84506 0.53093 -0.06309 0.96537 0.25549 -0.05276 0.93369 0.33075 -0.13719 0.99366 0.11196 -0.00981 0.02596 -0.07364 -0.99695 0.02719 -0.07262 -0.99699 0.11416 -0.15023 -0.98204 0.33588 -0.11082 -0.93536 0.56277 -0.08353 -0.82238 0.84148 -0.06213 -0.53671 0.93964 -0.12022 -0.32035 0.99372 -0.00942 -0.11149 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00213 -0.00242 -0.99999 -0.00000 0.00064 -1.00000 0.99377 0.00000 -0.11149 0.99371 0.00031 -0.11197 0.94640 -0.00028 -0.32300 0.93344 0.01977 -0.35818 0.84279 -0.02596 -0.53761 0.84359 -0.02714 -0.53630 0.70688 0.02458 -0.70690 0.56408 -0.05169 -0.82410 0.53293 -0.02365 -0.84583 0.33773 0.02283 -0.94097 0.36271 0.00292 -0.93190 0.11547 -0.00229 -0.99331 0.11197 0.00000 -0.99371 0.53068 0.83134 -0.16509 0.63799 0.75138 -0.16850 0.11178 0.99199 -0.05890 0.40884 0.89732 -0.16631 -0.01167 0.99685 -0.07846 -0.01644 0.97224 -0.23341 0.04465 0.87104 -0.48918 0.01656 0.85251 -0.52245 1.00000 0.00000 0.00000 0.00068 1.00000 0.00005 1.00000 0.00139 -0.00221 1.00000 0.00000 -0.00000 1.00000 -0.00057 -0.00007 0.96108 -0.18408 0.20600 -0.53626 -0.00717 0.84402 -0.55044 -0.01512 0.83474 -0.54727 -0.01162 0.83688 -0.54385 -0.00046 0.83918 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 1.00000 0.00000 -0.00000 0.37766 -0.86405 -0.33286 0.23688 -0.10002 0.96638 0.45395 -0.46288 0.76137 0.52006 -0.48691 0.70175 0.54044 -0.63883 0.54756 0.01391 0.58449 0.81128 0.28188 -0.10246 0.95396 0.17574 0.03601 0.98378 0.34837 -0.11248 0.93058 0.48158 -0.02409 0.87607 0.49105 -0.03750 0.87032 0.45549 -0.46198 0.76099 0.59290 -0.35278 0.72389 0.49711 -0.66547 0.55681 0.48479 -0.64095 0.59512 0.65255 -0.54130 0.53025 0.61616 -0.70852 0.34402 0.54542 -0.83759 -0.03087 0.46533 -0.86933 -0.16653 0.35532 -0.93401 -0.03705 0.61884 -0.71504 0.32518 0.45305 -0.88854 -0.07238 0.40190 -0.90708 -0.12525 0.62780 -0.70164 0.33700 0.64446 -0.34229 0.68374 0.64690 -0.31906 0.69262 0.49574 -0.01488 0.86834 0.31042 -0.90359 -0.29524 0.19712 -0.94212 -0.27119 0.30595 -0.90474 -0.29638 0.25619 0.08329 0.96303 0.35441 0.05971 0.93318 0.65589 0.07864 0.75075 0.33233 -0.07304 0.94033 0.70502 -0.07075 0.70565 0.18563 -0.13329 0.97354 0.59359 -0.13713 0.79300 0.26145 -0.22915 0.93762 0.09384 -0.30455 0.94786 0.64705 -0.20609 0.73407 0.50628 -0.30629 0.80614 0.92086 -0.11615 0.37219 0.20414 -0.39211 0.89698 0.85379 -0.22507 0.46945 0.99414 -0.02716 0.10461 0.03058 -0.45502 0.88996 0.58375 -0.35222 0.73156 0.98612 -0.08230 0.14419 0.38079 -0.49582 0.78049 0.49721 -0.44686 0.74370 0.87158 -0.23252 0.43161 0.98167 -0.08871 0.16868 0.73298 -0.41723 0.53728 -0.49780 0.00049 0.86729 -0.53505 -0.00673 0.84479 0.06065 -0.40107 0.91404 -0.00335 -0.25160 0.96783 0.01577 -0.09440 0.99541 0.06214 -0.01977 0.99787 0.09038 0.06707 0.99365 0.09117 0.07842 0.99274 0.19419 0.29610 0.93521 0.13442 0.18590 0.97333 0.10863 0.16946 0.97953 0.11531 0.17850 0.97716 0.11753 0.10784 0.98720 0.17125 0.08539 0.98152 0.12379 0.06446 0.99021 0.24679 -0.07474 0.96618 0.35050 0.03207 0.93601 0.39220 0.05271 0.91837 0.36788 -0.04795 0.92864 0.78976 -0.09106 0.60662 0.66966 -0.30065 0.67909 0.72318 -0.28607 0.62863 0.37583 0.29608 0.87811 0.46053 0.19281 0.86645 0.39487 0.29723 0.86933 0.32214 0.28835 0.90171 0.38228 0.15263 0.91135 0.34096 0.29127 0.89382 0.31917 0.24590 0.91524 0.24376 0.28028 0.92845 0.28428 0.12676 0.95032 0.21391 0.20920 0.95419 0.20973 0.16969 0.96292 0.16269 0.22790 0.96000 0.15327 0.09099 0.98399 0.17915 0.02928 0.98339 0.16703 0.07723 0.98292 0.13319 0.12558 0.98310 -0.72461 0.66718 -0.17263 -0.64765 0.40925 -0.64270 -0.72537 0.66588 -0.17446 -0.55727 0.82129 0.12221 -0.72461 0.66718 -0.17263 -0.55062 0.79718 0.24764 -0.78114 0.61235 -0.12185 -0.73373 0.59258 0.33241 -0.72407 0.39819 0.56318 -0.09458 0.02775 0.99513 -0.37204 0.21849 0.90214 -0.47570 0.32103 0.81893 -0.40013 0.74685 0.53114 -0.60544 0.53951 0.58512 -0.77736 0.62326 -0.08523 -0.19258 0.74450 0.63924 -0.32484 0.00105 0.94577 -0.56236 0.14376 0.81430 -0.64037 -0.00028 -0.76806 -0.49276 0.00237 -0.87016 -0.41716 0.00532 -0.90882 -0.33998 0.00245 -0.94043 -0.13747 -0.00143 -0.99051 0.08637 0.00025 -0.99626 0.25539 0.00782 -0.96681 0.31937 0.00426 -0.94762 0.54563 -0.00105 -0.83803 0.71226 0.02560 -0.70144 0.93160 -0.00080 -0.36348 -0.30416 0.90367 0.30146 -0.18905 0.96405 0.18675 -0.17716 0.96777 0.17900 -0.06828 0.99545 0.06640 -0.05877 0.99646 0.06018 0.05452 0.99694 -0.05595 0.06133 0.99629 -0.06038 0.17567 0.96847 -0.17664 0.17968 0.96727 -0.17919 0.29178 0.91090 -0.29178 -0.70674 0.00018 -0.70747 -0.70611 0.00492 -0.70809 -0.61196 0.16866 -0.77269 -0.46813 0.38436 -0.79569 -0.44363 0.41038 -0.79673 -0.69206 0.03289 -0.72109 -0.48019 0.38657 -0.78739 -0.40348 0.47314 -0.78316 -0.38153 0.49799 -0.77874 -0.39694 0.47979 -0.78245 -0.44098 0.43297 -0.78618 -0.40228 0.50656 -0.76261 -0.34299 0.53871 -0.76951 -0.24323 0.62462 -0.74208 -0.19831 0.66189 -0.72289 -0.04255 0.76144 -0.64683 0.10821 0.82845 -0.54951 0.27356 0.86693 -0.41665 -0.44726 0.88269 0.14429 -0.75424 0.39578 -0.52391 -0.36634 0.92877 -0.05634 -0.35602 0.93444 0.00824 -0.57417 0.75230 -0.32308 -0.57417 0.75230 -0.32308 -0.69341 0.48731 -0.53076 -0.69411 0.49033 -0.52705 -0.20769 0.97526 -0.07574 -0.64096 0.47871 -0.60001 -0.14771 0.96017 -0.23718 -0.15512 0.95287 -0.26071 -0.41269 0.77129 -0.48456 -0.41269 0.77129 -0.48456 -0.54553 0.58509 -0.60005 -0.55466 0.54384 -0.62975 0.02743 0.94790 -0.31739 -0.50278 0.50624 -0.70066 -0.24694 0.71941 -0.64920 0.01823 0.89022 -0.45516 0.14343 0.94816 -0.28359 0.02092 0.85122 -0.52440 -0.43186 0.52573 -0.73288 -0.27682 0.71995 -0.63643 -0.17014 0.84707 -0.50352 -0.19663 0.73931 -0.64402 -0.45398 -0.84709 0.27630 -0.45336 -0.84836 0.27340 -0.45223 -0.86230 0.22788 -0.30938 -0.84587 0.43451 -0.31640 -0.85101 0.41914 -0.32734 -0.85421 0.40396 -0.19253 -0.84339 0.50162 -0.21017 -0.82126 0.53043 0.09595 -0.70459 0.70310 0.27925 -0.53463 0.79762 0.33612 -0.58740 0.73619 0.50998 -0.31935 0.79870 0.73324 -0.11449 0.67026 0.69769 -0.07380 0.71259 0.71001 0.09334 0.69797 0.71342 0.11150 0.69181 0.44660 0.28490 0.84817 0.42570 0.34563 0.83625 0.49308 0.35893 0.79249 0.47192 0.33974 0.81355 0.48858 0.35542 0.79685 0.50407 0.30407 0.80836 0.54130 0.35319 0.76306 0.51591 0.34372 0.78466 0.54947 0.35729 0.75527 0.55754 0.31099 0.76970 0.59175 0.34319 0.72942 0.56677 0.34312 0.74903 0.61338 0.34863 0.70868 0.61520 0.31115 0.72437 0.62363 0.33026 0.70853 0.64273 0.32843 0.69212 0.66688 0.30032 0.68197 0.66895 0.32925 0.66641 0.67344 0.30988 0.67116 0.68739 0.30795 0.65777 0.71397 0.30241 0.63150 0.70954 0.27941 0.64691 0.71229 0.28197 0.64275 0.68835 0.34821 0.63633 0.74850 0.25388 0.61262 0.75148 0.26301 0.60507 0.80083 0.29475 0.52134 0.75681 0.25970 0.59983 0.78445 0.22816 0.57669 0.78005 0.20708 0.59046 0.79116 0.20451 0.57641 0.79170 0.23137 0.56540 0.80416 0.18675 0.56432 0.81091 0.15960 0.56299 0.82230 0.15237 0.54827 0.83244 0.19121 0.52008 0.82678 0.11503 0.55064 0.83170 0.08125 0.54924 0.84808 -0.01669 0.52960 0.13091 -0.95676 -0.25974 -0.14896 -0.98311 -0.10637 -0.01483 -0.98334 -0.18115 -0.15702 -0.98311 -0.09404 -0.28506 -0.95833 -0.01832 -0.29866 -0.95435 0.00387 -0.43055 -0.89842 0.08642 -0.43412 -0.89521 0.10069 0.16497 -0.96445 -0.20643 0.02009 -0.99224 -0.12274 0.09740 -0.98125 -0.16629 0.15388 -0.96483 -0.21315 -0.03211 -0.99607 -0.08252 0.03310 -0.98901 -0.14411 -0.11736 -0.99264 -0.02984 -0.25592 -0.96410 0.07086 -0.16279 -0.98662 0.00880 -0.10122 -0.99319 -0.05763 -0.39055 -0.90163 0.18584 -0.33754 -0.93102 0.13882 -0.28158 -0.95521 0.09104 -0.23394 -0.97180 0.02977 -0.41348 -0.89274 0.17905 -0.44754 -0.86558 0.22467 -0.40912 -0.89810 0.16137 0.51493 0.13537 0.84647 0.54464 0.11776 0.83036 0.60911 -0.35745 0.70796 0.54714 0.10321 0.83065 0.54651 0.12203 0.82851 0.60694 -0.36523 0.70586 0.51688 -0.75905 0.39583 0.51237 -0.76444 0.39130 0.33939 -0.93857 0.06239 0.33594 -0.93999 0.05969 0.23633 -0.97104 0.03493 0.56947 0.10512 0.81526 0.56418 -0.37381 0.73619 0.57227 0.11905 0.81138 0.56235 -0.37791 0.73549 0.40679 -0.78570 0.46604 0.16299 -0.98123 0.10304 0.26209 -0.94698 0.18586 0.40382 -0.78852 0.46387 0.12047 -0.98446 0.12780 0.59504 0.09132 0.79849 0.52880 -0.37731 0.76026 0.60951 0.12085 0.78351 0.30599 -0.78679 0.53603 0.52745 -0.37947 0.76013 0.30417 -0.78816 0.53506 0.01435 -0.98266 0.18488 0.17156 -0.93705 0.30415 0.00491 -0.97436 0.22496 0.62284 0.08588 0.77762 -0.06248 -0.96671 0.24813 0.64081 0.10404 0.76061 0.48954 -0.37016 0.78951 0.20417 -0.76346 0.61273 0.48799 -0.37199 0.78961 -0.06535 -0.93365 0.35217 -0.06813 -0.93401 0.35068 0.20230 -0.76455 0.61199 0.64413 0.08126 0.76059 -0.17733 -0.92525 0.33536 0.44173 -0.34876 0.82659 0.68964 0.13086 0.71223 0.66294 0.08758 0.74353 0.49288 -0.30563 0.81466 0.10108 -0.71364 0.69318 -0.21116 -0.87870 0.42814 -0.14894 -0.87297 0.46448 0.10565 -0.71178 0.69441 -0.28808 -0.86206 0.41696 0.91485 -0.20150 0.34992 0.90311 -0.15938 0.39873 0.88859 -0.11254 0.44468 0.87019 -0.05658 0.48946 0.85247 0.00678 0.52274 0.80218 0.12953 0.58287 -0.00015 -0.99992 -0.01263 -0.00067 -0.99989 -0.01467 0.00000 -0.99996 -0.00925 -0.41892 -0.90344 0.09113 -0.45134 -0.89229 -0.01032 -0.42374 -0.90574 -0.00948 -0.32299 -0.93012 -0.17480 -0.44401 -0.88822 -0.11794 -0.39608 -0.91111 -0.11406 0.70735 0.00458 0.70685 0.70785 0.00410 0.70635 0.70825 0.00361 0.70595 0.70906 0.00236 0.70515 0.70711 0.00000 0.70711 0.70711 0.00000 0.70711 0.71412 -0.00566 0.70000 0.70900 0.00028 0.70521 0.67873 0.00074 0.73439 -0.20201 -0.84844 0.48923 -0.47056 -0.83934 0.27216 -0.47339 -0.83408 0.28323 -0.41620 -0.87766 0.23769 -0.45618 -0.84470 0.27996 -0.46943 -0.83433 0.28902 -0.45223 -0.86230 0.22788 -0.41518 -0.87772 0.23923 -0.46639 -0.83490 0.29229 -0.41553 -0.87064 0.26328 -0.46430 -0.86460 0.19205 -0.48018 -0.85357 0.20211 -0.48146 -0.86664 0.13091 -0.46477 -0.85994 0.21093 -0.46830 -0.86442 0.18293 -0.47048 -0.86298 0.18417 -0.48609 -0.85727 0.16973 -0.49005 -0.86094 0.13647 -0.48613 -0.86550 0.12076 -0.46105 -0.88093 0.10673 -0.49623 -0.86762 0.03148 -0.46329 -0.88016 0.10334 -0.49635 -0.85895 0.12582 -0.49398 -0.86106 0.12065 -0.49400 -0.86624 0.07478 -0.46250 -0.88601 0.03297 -0.48023 -0.87616 0.04151 -0.49069 -0.86856 -0.06950 -0.48087 -0.87643 0.02531 -0.47163 -0.88150 0.02309 -0.42902 -0.90181 0.05179 -0.44026 -0.89684 -0.04287 -0.44366 -0.89523 -0.04153 -0.43811 -0.89887 -0.00900 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.99999 0.00201 0.00456 -1.00000 -0.00005 0.00040 -1.00000 -0.00037 0.00002 0.00006 -0.00042 1.00000 -0.00051 -0.00006 1.00000 -0.38666 0.00513 0.92221 -0.49078 -0.01193 0.87120 -0.91380 0.01144 0.40601 -0.94048 0.00151 0.33984 0.78154 0.00000 -0.62385 0.78184 -0.00004 -0.62348 0.89911 0.00004 -0.43772 0.90097 -0.00030 -0.43389 0.97255 0.00030 -0.23269 0.97493 -0.00052 -0.22252 0.99989 0.00051 -0.01458 1.00000 -0.00061 -0.00000 0.97799 0.00062 0.20866 0.97493 -0.00049 0.22252 0.90518 0.00051 0.42504 0.90097 -0.00028 0.43388 0.78402 0.00029 0.62073 0.75741 -0.00318 0.65293 0.78350 0.03641 0.62032 0.80946 0.08877 0.58043 0.79493 0.05167 0.60450 0.78860 0.19223 0.58408 0.80773 0.09172 0.58237 0.82851 0.24406 0.50400 0.90218 0.08132 0.42363 0.96470 0.16429 0.20583 0.96508 0.16784 0.20114 0.87739 0.36596 0.31027 0.87067 0.39392 0.29455 0.84607 0.51084 0.15234 0.98309 0.18259 -0.01433 0.94081 0.25339 -0.22510 0.95524 0.22915 -0.18708 0.80063 0.59686 -0.05254 0.80988 0.58521 -0.04031 0.69774 0.67783 -0.23174 0.87204 0.24353 -0.42455 0.67475 0.68234 -0.28128 0.74641 0.29644 -0.59581 0.95409 0.09460 -0.28420 0.82883 0.30580 -0.46855 0.72151 0.50099 -0.47795 0.75783 0.62139 -0.19891 0.48814 0.80969 -0.32576 0.42350 0.86622 -0.26516 0.42596 0.86577 -0.26268 0.56958 0.81799 -0.08037 0.56559 0.82025 -0.08547 0.67156 0.73587 0.08665 0.67569 0.73122 0.09364 0.74476 0.61659 0.25525 0.74888 0.60716 0.26559 0.78264 0.46590 0.41281 0.78408 0.45589 0.42116 0.78258 0.30155 0.54464 0.78148 0.28438 0.55535 0.74144 0.09762 0.66388 0.74133 0.09720 0.66406 0.46094 0.88717 0.02133 0.36986 0.90455 -0.21209 0.65764 0.54677 0.51822 0.65738 0.67553 0.33391 0.59222 0.78959 0.16070 0.45964 0.88808 -0.00723 0.76138 0.26506 0.59165 0.67668 0.14572 0.72172 0.74593 0.32923 0.57896 0.68732 0.65909 0.30528 0.34411 0.93892 -0.00424 0.72858 0.24679 0.63895 0.26118 0.95440 0.14459 0.26610 0.94740 0.17782 0.53039 0.70930 0.46430 0.69505 0.27347 0.66493 0.69345 0.26904 0.66838 0.53039 0.70930 0.46430 0.66675 0.25277 0.70111 0.26551 0.86626 -0.42319 0.09698 0.82390 -0.55838 -0.07392 0.74235 -0.66593 -0.54683 0.29542 -0.78339 0.70711 0.00000 -0.70711 0.70711 0.00000 -0.70711 0.40966 0.81508 -0.40966 0.41055 0.81402 -0.41087 0.52092 0.67646 -0.52061 0.52329 0.67200 -0.52400 0.60918 0.50859 -0.60847 0.61148 0.50131 -0.61219 0.67118 0.31623 -0.67046 0.67200 0.31050 -0.67231 0.70318 0.10741 -0.70286 0.70315 0.10560 -0.70315 0.34651 0.87170 -0.34651 0.34651 0.87170 -0.34651 0.29255 0.91024 -0.29306 -0.26784 -0.96216 0.04999 -0.39825 -0.91268 0.09174 -0.42766 -0.89787 0.10456 -0.25193 -0.96624 0.05399 -0.30961 -0.94743 0.08078 -0.34942 -0.93219 0.09444 -0.43454 -0.89338 0.11423 -0.28015 -0.95593 0.08778 -0.08963 -0.99555 0.02920 -0.40126 -0.90572 0.13660 -0.25567 -0.96172 0.09866 -0.42785 -0.88864 0.16510 -0.08917 -0.99533 0.03705 -0.08509 -0.99568 0.03725 -0.26844 -0.95610 0.11753 -0.39243 -0.90289 0.17546 -0.08595 -0.99523 0.04608 -0.24184 -0.96186 0.12780 -0.41024 -0.88584 0.21679 -0.37911 -0.89958 0.21687 -0.25329 -0.95597 0.14820 0.00000 -0.00160 -1.00000 -0.09886 0.00151 -0.99510 -0.23933 -0.00143 -0.97094 -0.32258 0.00099 -0.94654 -0.46476 -0.00120 -0.88544 -0.51318 0.00067 -0.85828 -0.66316 -0.00053 -0.74848 -0.68014 0.00040 -0.73309 -0.82751 -0.00007 -0.56145 -0.82301 -0.00041 -0.56803 -0.97052 0.00016 -0.24103 -0.93498 0.01068 -0.35455 -0.99271 -0.00000 -0.12052 -0.26904 -0.00000 0.96313 0.70833 -0.00605 0.70585 0.21524 -0.56304 0.79791 -0.11691 -0.00186 -0.99314 -0.14114 -0.12611 -0.98192 -0.10237 0.38309 -0.91802 -0.02680 0.57981 -0.81431 -0.01268 0.77763 -0.62860 -0.00904 0.73493 -0.67808 0.00068 0.80610 -0.59178 -0.00108 0.85264 -0.52250 0.01511 0.91028 -0.41371 0.01390 0.92379 -0.38265 0.02031 0.94338 -0.33109 0.01342 0.97228 -0.23342 0.02136 0.98991 -0.14007 0.01795 0.99676 -0.07845 0.02256 0.99927 -0.03097 -0.00254 0.02715 -0.99963 0.70027 -0.25419 -0.66709 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 0.85182 0.37635 -0.36437 0.49035 -0.14364 -0.85961 0.33670 -0.13168 -0.93236 0.27274 -0.36710 -0.88930 -0.17181 -0.16994 -0.97036 0.88084 -0.21545 -0.42155 0.52655 -0.35895 -0.77065 0.43999 -0.26620 -0.85764 0.83164 -0.16971 -0.52875 0.64705 -0.29844 -0.70161 0.64597 -0.29385 -0.70454 -0.99972 0.00904 0.02167 0.84354 0.44158 -0.30569 0.85233 0.42369 -0.30664 0.84544 0.39219 -0.36251 0.99999 -0.00154 0.00364 1.00000 -0.00004 0.00024 1.00000 0.00004 -0.00021 0.99998 -0.00008 0.00555 1.00000 -0.00167 0.00103 0.99998 -0.00116 -0.00543 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 -0.99998 0.00105 -0.00542 -0.99998 0.00041 -0.00585 -0.95157 -0.21717 0.21763 -0.97135 -0.15403 -0.18098 -0.11021 -0.36691 -0.92371 -0.11021 -0.37742 -0.91946 -0.28870 -0.94076 -0.17783 -0.27373 -0.93935 -0.20663 -0.26439 -0.92372 -0.27720 -0.26412 -0.90207 -0.34133 -0.25030 -0.88459 -0.39350 -0.24398 -0.83325 -0.49615 -0.23022 -0.81220 -0.53603 -0.21648 -0.73959 -0.63729 -0.20440 -0.71901 -0.66426 -0.18613 -0.62266 -0.76003 -0.18487 -0.63448 -0.75051 -0.19445 -0.63456 -0.74801 -0.15710 -0.55161 -0.81917 -0.15864 -0.61231 -0.77454 -0.19033 -0.64605 -0.73919 -0.14755 -0.48683 -0.86094 -0.13671 -0.47755 -0.86790 -0.10090 -0.33636 -0.93631 -0.10809 -0.34240 -0.93331 -0.00869 -0.20153 -0.97944 -0.05392 -0.20445 -0.97739 -0.06813 -0.17466 -0.98227 -0.00375 0.00000 -0.99999 -0.00318 0.00019 -0.99999 -0.92486 0.01457 -0.38002 -0.84035 -0.00942 -0.54197 -0.41922 0.00855 -0.90784 -0.35818 0.00014 -0.93365 -0.00056 -1.00000 0.00086 -0.05784 -0.99833 0.00020 0.01407 -0.99990 -0.00224 0.00670 -0.99998 -0.00141 -0.11453 -0.99285 0.03360 0.01814 -0.99983 -0.00276 -1.00000 0.00000 0.00001 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00001 -1.00000 0.00000 0.00000 -0.99999 0.00019 0.00359 -1.00000 0.00124 0.00107 -1.00000 0.00131 0.00078 -1.00000 0.00132 0.00050 -0.99997 -0.00048 -0.00738 -1.00000 0.00130 0.00025 -1.00000 -0.00018 -0.00001 -1.00000 -0.00052 0.00124 -0.98205 -0.05351 -0.18088 -0.99957 -0.01030 -0.02746 -0.99982 -0.00296 0.01859 -1.00000 -0.00037 -0.00014 -1.00000 -0.00018 -0.00000 -0.26814 -0.91828 -0.29129 -0.37694 -0.90683 -0.18863 -0.27016 -0.94329 -0.19294 -0.26940 -0.95781 -0.10011 -0.38145 -0.91673 -0.11875 -0.37897 -0.92297 -0.06717 -0.37886 -0.90393 -0.19843 -0.44899 -0.88802 -0.09911 -0.38178 -0.91646 -0.11976 -0.43804 -0.89850 -0.02856 -0.37459 -0.92616 -0.04365 -0.02661 -0.00426 -0.99964 0.04036 0.04177 -0.99831 0.01030 -0.00537 -0.99993 -0.84785 0.46175 -0.26065 -0.13187 0.86725 -0.48010 -0.23813 0.79807 -0.55351 -1.00000 0.00228 0.00106 -0.99992 0.00890 0.00936 -1.00000 0.00062 0.00088 -0.99999 0.00317 0.00229 -1.00000 0.00002 0.00108 -0.99997 0.00396 0.00590 -1.00000 0.00227 0.00181 -0.99958 0.02851 0.00482 -0.99999 -0.00304 0.00344 -0.99999 -0.00414 0.00242 -0.99997 -0.00464 -0.00536 -1.00000 0.00129 -0.00214 -0.99999 0.00007 -0.00537 -0.99999 0.00185 -0.00435 -0.99989 -0.01436 0.00479 -0.99952 0.01269 0.02834 -0.99968 -0.02528 0.00298 -0.99941 0.01254 0.03195 -0.20497 -0.89639 -0.39303 -0.17737 -0.84674 -0.50157 -0.12108 -0.85530 -0.50378 -0.18938 -0.82301 -0.53552 -0.08552 -0.81814 -0.56863 -0.16084 -0.73336 -0.66054 -0.15808 -0.73131 -0.66347 -0.10885 -0.74262 -0.66081 -0.06638 -0.67620 -0.73372 -0.14131 -0.61684 -0.77430 -0.09200 -0.60033 -0.79444 -0.12608 -0.60194 -0.78853 -0.03267 -0.50304 -0.86364 0.01233 -0.48371 -0.87514 -0.08330 -0.57927 -0.81087 0.00414 -0.30803 -0.95137 -0.05415 -0.34842 -0.93577 -0.03687 -0.12814 -0.99107 -0.11255 -0.88717 -0.44750 -0.15992 -0.89843 -0.40896 -0.25506 -0.89111 -0.37534 -0.19939 -0.90654 -0.37205 -0.33538 -0.90069 -0.27620 -0.15136 -0.91770 -0.36730 -0.18974 -0.92276 -0.33542 -0.24074 -0.91625 -0.32020 -0.33243 -0.90791 -0.25532 -0.40548 -0.89436 -0.18896 -0.30163 -0.91561 -0.26584 -0.28549 -0.93343 -0.21728 0.00148 -1.00000 -0.00000 0.00561 -0.99997 0.00566 0.01502 -0.99983 0.01061 0.09285 -0.99523 0.02987 -0.01022 -0.98616 -0.16551 -0.00125 0.00438 -0.99999 -1.00000 -0.00030 -0.00026 -1.00000 0.00018 -0.00015 -1.00000 0.00078 0.00014 -0.99999 -0.00294 -0.00306 -0.91934 0.28091 -0.27551 -0.62221 0.59056 -0.51390 -0.75680 0.51962 -0.39653 -0.75665 0.54209 -0.36554 -0.69000 0.56345 -0.45435 -0.69150 0.64682 -0.32163 -0.59269 0.68255 -0.42761 -0.63449 0.76780 -0.08896 -0.66155 0.74966 0.01920 -0.47015 0.86368 -0.18171 -0.46735 0.86435 -0.18568 -0.24237 0.96964 -0.03241 -0.26569 0.96228 0.05851 -0.99895 -0.02723 -0.03686 -0.95393 0.29989 -0.00971 -0.99986 0.01641 -0.00201 -0.68874 0.69793 -0.19631 -0.62449 0.74330 -0.23983 -0.68515 0.72129 -0.10152 -0.55845 0.82676 -0.06792 -0.10616 0.99433 0.00549 -0.32199 0.94674 -0.00327 -0.55271 0.82188 -0.13791 -0.49471 0.86734 -0.05458 -0.99999 0.00117 -0.00309 -0.99994 0.01132 0.00047 -1.00000 -0.00008 0.00021 -1.00000 -0.00021 0.00013 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00148 1.00000 0.00013 0.02107 0.99978 0.00061 -0.90939 0.33804 -0.24235 -0.28227 0.87950 -0.38316 -0.88136 0.42817 -0.19967 -0.21653 0.91472 -0.34118 -0.89159 0.42429 -0.15826 -0.89369 0.41966 -0.15876 -0.83278 0.55081 -0.05551 -0.24266 0.91455 -0.32360 -0.09217 0.97379 -0.20796 -0.78340 0.60764 -0.13062 -0.16852 0.97171 -0.16547 -0.01020 0.99990 -0.00978 -0.99975 0.02213 -0.00431 -0.99963 0.02650 -0.00665 -0.99852 -0.00802 -0.05385 -0.99999 -0.00108 -0.00408 -1.00000 0.00049 -0.00240 -0.99999 0.00126 0.00456 -0.99777 0.03907 0.05414 -0.99965 0.02640 -0.00212 -0.41870 0.89416 -0.15864 0.00633 -0.05715 -0.99835 -0.92670 0.23108 -0.29636 -0.90333 0.24012 -0.35545 -0.92077 0.20575 -0.33145 -0.47893 0.49429 -0.72546 -0.52345 0.46413 -0.71455 -0.34893 0.44904 -0.82256 -0.92567 0.16011 -0.34278 -0.47049 0.31077 -0.82587 -0.44326 0.32496 -0.83542 -0.90046 0.15318 -0.40708 -0.91732 0.12723 -0.37729 -0.35648 0.23249 -0.90491 -0.92659 0.08253 -0.36691 -0.27818 0.19615 -0.94029 -0.43482 0.12792 -0.89139 -0.93974 0.10503 -0.32536 0.00202 0.97664 -0.21485 0.00342 0.92611 -0.37725 0.00232 0.16799 -0.98579 -0.99800 0.05699 -0.02727 -0.98650 -0.07302 -0.14655 -0.99916 0.00647 0.04052 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00001 0.00055 -1.00000 0.00006 -0.00002 -1.00000 0.00003 -0.00026 -1.00000 -0.00019 -0.00000 -0.99992 0.00141 0.01221 -1.00000 0.00003 0.00061 0.00036 1.00000 -0.00085 -0.00074 -0.99999 0.00508 -0.00642 -0.99978 -0.01992 -0.00626 -0.99967 0.02501 -0.00044 -1.00000 0.00076 0.06323 0.95308 -0.29603 0.00013 -1.00000 -0.00013 0.00006 -1.00000 -0.00222 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00071 1.00000 0.00000 -0.00066 1.00000 0.00022 1.00000 0.00000 -0.00000 1.00000 -0.00204 -0.00021 1.00000 0.00000 0.00000 1.00000 0.00001 -0.00005 1.00000 0.00002 -0.00005 1.00000 0.00003 -0.00004 1.00000 0.00004 -0.00004 1.00000 0.00004 -0.00004 0.99997 -0.00678 -0.00351 0.99998 0.00583 -0.00357 0.99996 0.00834 -0.00345 0.99992 0.01266 -0.00304 0.99975 0.02214 -0.00174 0.99947 0.03250 0.00000 -0.00358 0.01694 -0.99985 0.00416 0.07845 -0.99691 -0.00170 0.14206 -0.98986 0.00389 0.24884 -0.96854 0.00056 0.23343 -0.97237 -0.00044 0.36252 -0.93198 0.00313 0.38266 -0.92389 -0.00250 0.47916 -0.87773 0.00408 0.52246 -0.85265 -0.00275 0.58852 -0.80847 0.00934 0.64939 -0.76040 0.00084 0.75437 -0.65645 0.00245 0.76038 -0.64947 -0.00186 0.82911 -0.55908 0.00392 0.85262 -0.52252 -0.00266 0.89274 -0.45057 0.00384 0.92387 -0.38270 -0.00671 0.95261 -0.30411 0.00413 0.97236 -0.23345 -0.00482 0.99518 -0.09792 -0.00064 0.99692 -0.07846 0.79609 0.05508 -0.60266 -0.00361 0.00416 -0.99998 0.82870 0.00504 -0.55967 1.00000 0.00000 -0.00021 0.00000 -1.00000 -0.00000 -0.00028 -1.00000 0.00022 -0.00025 -1.00000 0.00012 -0.00023 -1.00000 0.00005 -0.00022 -1.00000 -0.00000 -0.00020 -1.00000 -0.00005 -0.00018 -1.00000 -0.00009 -0.00202 -0.99999 0.00391 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00043 1.00000 -0.00111 -0.07286 0.98198 -0.17439 0.09330 0.99002 0.10563 -0.00001 1.00000 -0.00002 -0.00505 -0.00190 -0.99999 -0.00030 0.00223 -1.00000 0.00348 0.02062 -0.99978 -0.00004 -0.00542 -0.99999 -0.00160 0.26537 -0.96414 -0.00233 0.62702 -0.77900 -0.00033 0.86865 -0.49543 0.00295 0.98217 -0.18796 0.01463 -0.85812 -0.51324 0.00944 -0.34570 -0.93830 0.00000 -0.00000 1.00000 -0.00815 0.23743 -0.97137 0.01099 0.92840 -0.37141 0.01372 0.77791 -0.62823 0.93698 -0.01282 -0.34914 0.94050 -0.01829 -0.33930 0.36536 0.01785 -0.93069 0.42245 -0.00957 -0.90634 0.33631 0.12197 -0.93382 0.94302 0.13216 -0.30535 0.90984 0.06164 -0.41036 0.40552 0.20639 -0.89048 0.90311 0.20486 -0.37740 0.35689 0.37398 -0.85602 0.53259 0.53044 -0.65953 0.41656 0.82837 -0.37453 0.41649 0.82833 -0.37472 -1.00000 -0.00000 0.00000 -0.99998 0.00449 -0.00520 -0.00001 1.00000 0.00083 -0.00368 0.99999 -0.00194 0.04138 0.99891 0.02183 -0.00501 0.99997 0.00552 0.27965 0.82687 -0.48793 0.04604 0.99044 -0.13001 -0.00756 0.99995 0.00622 0.36433 0.82983 -0.42267 0.70741 -0.00070 0.70680 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 0.85586 0.44005 -0.27175 0.83565 0.48386 -0.25995 0.89149 0.41302 -0.18618 0.86250 0.48437 -0.14654 0.86595 0.47894 -0.14405 0.88942 0.44889 -0.08619 0.96888 0.24646 -0.02283 0.01839 0.97438 -0.22417 -0.00067 0.00719 -0.99997 0.18847 0.96425 -0.18626 0.32297 0.88097 -0.34580 0.70494 -0.00066 0.70927 -0.90892 0.01399 -0.41675 -0.84378 -0.03307 -0.53567 -0.40721 -0.02036 -0.91311 -0.25160 -0.06226 -0.96583 -0.76494 0.59743 -0.24070 -0.72888 0.55463 -0.40139 -0.64509 0.59453 -0.48000 -0.53049 0.60804 -0.59065 -0.30426 0.64766 -0.69854 -0.30627 0.49315 -0.81425 -0.00837 0.71247 -0.70165 0.99290 0.05153 -0.10723 0.99853 0.00494 -0.05394 0.94836 0.00438 -0.31717 0.99991 -0.01321 0.00299 0.99980 0.01913 -0.00603 1.00000 0.00036 -0.00011 1.00000 -0.00048 0.00019 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.00000 0.99996 0.00768 -0.00483 0.99998 -0.00391 0.00413 1.00000 0.00000 0.00000 -0.32558 0.90928 -0.25923 -0.13364 0.91479 -0.38117 0.35963 0.58764 -0.72481 -0.21180 0.16869 -0.96264 -0.25906 0.19434 -0.94611 -0.74889 0.08450 -0.65728 -0.83399 0.14860 -0.53140 0.92740 -0.37379 -0.01480 0.92989 -0.36764 -0.01221 0.61957 -0.78440 0.02924 0.55444 -0.83212 0.01325 0.35548 -0.93316 0.05327 -0.06803 -0.99765 0.00764 -0.12392 -0.99196 0.02552 0.99025 -0.09665 0.10029 0.91955 -0.22227 0.32407 0.95031 -0.23680 0.20206 0.96115 -0.21750 0.16996 0.59344 -0.62964 0.50139 -0.29108 -0.79559 0.53132 0.56090 -0.64167 0.52312 0.13129 -0.80261 0.58188 0.08355 -0.80177 0.59176 0.94016 -0.29536 0.16990 0.94639 -0.29519 0.13115 0.95621 -0.27170 0.10884 0.49565 -0.79371 0.35264 -0.18800 -0.90604 0.37914 -0.12178 -0.92965 0.34774 0.54043 -0.77618 0.32479 0.94133 -0.32780 0.08023 0.92865 -0.36514 0.06539 0.96164 -0.27352 0.02092 0.50768 -0.85233 0.12568 -0.11568 -0.97042 0.21191 0.55307 -0.82651 0.10487 -0.19801 -0.96833 0.15205 -0.06290 -0.99658 0.05351 -0.27455 -0.96110 0.03011 -0.33670 -0.73778 0.58507 -0.30227 -0.73444 0.60765 -0.39705 -0.71898 0.57045 -0.26267 -0.67255 0.69187 -0.40602 -0.75797 0.51051 -0.42005 -0.84998 0.31794 -0.32574 -0.84437 0.42537 -0.38379 -0.81296 0.43795 -0.36326 -0.91024 0.19877 -0.28014 -0.91541 0.28903 -0.35819 -0.91282 0.19611 -0.31385 -0.94615 0.07940 -0.38564 -0.90943 0.15563 -0.32799 -0.94464 -0.00870 -0.42796 -0.90339 0.02703 -0.25399 -0.96097 -0.10967 0.99371 0.11197 -0.00000 0.94261 0.33390 0.00001 0.84675 0.53200 -0.00000 0.70709 0.70712 -0.00001 0.53735 0.84336 0.00001 0.35463 0.93501 -0.00022 -0.92548 -0.17888 -0.33391 -0.89852 -0.09205 -0.42917 -0.97435 0.04967 -0.21949 0.00259 0.78144 -0.62398 0.00149 0.70709 -0.70712 0.00242 0.47639 -0.87923 1.00000 0.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00080 -0.99995 -0.00968 -0.00203 -0.99999 0.00408 -0.03006 -0.99655 0.07738 -0.00350 -0.99956 -0.02935 -0.02316 -0.99935 -0.02755 1.00000 -0.00007 0.00004 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00021 -0.00005 1.00000 -0.00020 0.00003 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00081 -0.00007 1.00000 -0.00005 -0.00000 1.00000 -0.00200 0.00013 1.00000 0.00006 -0.00000 0.14179 0.98990 0.00003 0.10853 0.99409 -0.00003 0.21406 0.97682 0.00101 0.53288 0.84619 0.00004 0.70722 0.70699 -0.00001 0.84631 0.53268 0.00001 0.94433 0.32901 -0.00003 0.99387 0.11059 -0.00001 0.17609 -0.90635 -0.38408 0.09976 -0.93861 -0.33025 0.15264 -0.92168 -0.35666 0.18071 -0.90375 -0.38804 0.20343 -0.89860 -0.38877 0.15178 -0.92233 -0.35534 0.20452 -0.89798 -0.38962 0.16493 -0.92236 -0.34937 0.22733 -0.89351 -0.38726 0.22556 -0.89451 -0.38597 0.22317 -0.89604 -0.38380 0.22072 -0.89791 -0.38085 0.21231 -0.90599 -0.36621 0.22855 -0.92192 -0.31278 0.23696 -0.91595 -0.32387 0.18744 -0.93911 -0.28798 0.27398 -0.93382 -0.23004 0.24137 -0.94997 -0.19821 0.21300 -0.95923 -0.18578 0.38974 -0.89527 -0.21587 0.23721 -0.89968 -0.36649 0.12944 -0.95531 -0.26574 0.27026 -0.91424 -0.30186 0.25989 -0.91700 -0.30261 0.25487 -0.94396 -0.20973 0.26162 -0.91632 -0.30316 -0.28027 -0.95914 -0.03879 -0.10525 -0.98944 -0.09969 -0.03192 -0.97345 -0.22666 -0.02945 -0.96374 -0.26523 0.00041 -0.95510 -0.29628 -0.04268 -0.97666 -0.21049 0.17756 -0.90512 -0.38631 0.11970 -0.92741 -0.35437 -0.16176 -0.97543 -0.14960 -0.28146 -0.95874 -0.03991 -0.30514 -0.93140 -0.19848 -0.27647 -0.94338 -0.18330 -0.27203 -0.94555 -0.17868 0.50172 -0.83822 -0.21369 0.16147 -0.94732 -0.27662 -0.12364 -0.99100 -0.05123 0.02715 -0.99875 -0.04203 0.32277 -0.91635 -0.23690 0.35902 -0.90247 -0.23802 0.35945 -0.93190 -0.04862 0.35445 -0.93385 -0.04788 0.76322 -0.62573 -0.16110 0.61729 -0.78514 -0.05015 0.76316 -0.62581 -0.16110 0.76286 -0.64610 -0.02445 0.94001 -0.32706 -0.09706 0.94589 -0.32382 -0.02104 0.98674 -0.15827 -0.03589 0.92741 -0.37378 -0.01442 1.00000 -0.00086 -0.00022 1.00000 -0.00043 -0.00015 0.33101 -0.87971 -0.34137 0.32896 -0.88025 -0.34197 0.32508 -0.88095 -0.34388 0.39482 -0.85882 -0.32640 0.76532 -0.59938 -0.23460 0.79439 -0.56782 -0.21572 0.98701 -0.14910 -0.05987 0.99002 -0.13138 -0.05090 0.99069 -0.12721 -0.04855 1.00000 -0.00096 -0.00028 0.12946 -0.64097 -0.75657 0.11008 -0.80022 -0.58951 0.15794 -0.68263 -0.71349 0.16731 -0.76142 -0.62630 0.19158 -0.79756 -0.57201 0.17975 -0.71404 -0.67664 0.20875 -0.78596 -0.58196 0.20878 -0.78363 -0.58509 0.21894 -0.82359 -0.52322 0.28291 -0.78273 -0.55434 0.25328 -0.86318 -0.43676 0.25293 -0.87372 -0.41549 0.25472 -0.94413 -0.20916 0.94100 -0.32180 -0.10466 0.93714 -0.33344 -0.10291 0.92195 -0.37275 -0.10516 0.93769 -0.33282 -0.09987 0.58658 -0.77950 -0.21977 0.65529 -0.72112 -0.22489 0.67515 -0.70294 -0.22372 0.48227 -0.84245 -0.24021 0.94690 -0.31180 -0.07850 0.55440 -0.80773 -0.20052 0.94315 -0.32478 -0.07066 0.94453 -0.32071 -0.07077 0.92504 -0.37218 -0.07605 0.65147 -0.74426 -0.14718 0.67907 -0.71821 -0.15179 0.61415 -0.77465 -0.15078 -0.65150 -0.59225 -0.47412 0.29836 -0.75880 -0.57896 0.47432 -0.69238 -0.54372 0.49329 -0.72359 -0.48279 0.61805 -0.63096 -0.46894 0.62730 -0.62540 -0.46407 0.77735 -0.50319 -0.37753 0.77458 -0.60675 -0.17856 0.83112 -0.45052 -0.32599 0.92313 -0.36398 -0.12385 0.85115 -0.42652 -0.30597 0.96943 -0.19914 -0.14337 0.97086 -0.23028 -0.06630 0.97810 -0.17138 -0.11807 0.22139 -0.66125 -0.71675 0.19795 -0.68841 -0.69778 0.30152 -0.65080 -0.69682 0.39222 -0.80198 -0.45054 0.23430 -0.89094 -0.38901 0.62223 -0.56557 -0.54126 0.21208 -0.94252 -0.25824 0.63186 -0.56401 -0.53164 0.69806 -0.56471 -0.44026 0.59018 -0.75119 -0.29564 0.83331 -0.42620 -0.35207 0.85326 -0.40383 -0.32996 0.61214 -0.76132 -0.21373 0.97316 -0.21955 -0.06903 0.04484 -0.95686 -0.28708 0.12421 -0.77762 -0.61635 0.05320 -0.98189 -0.18185 0.14504 -0.84160 -0.52026 0.04815 -0.98350 -0.17440 0.38576 -0.86893 -0.31009 0.47608 -0.83282 -0.28242 0.79467 -0.56588 -0.21974 0.93976 -0.33146 -0.08361 0.99048 -0.12954 -0.04655 0.99073 -0.12746 -0.04698 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 0.25709 -0.91478 -0.31159 0.00001 1.00000 0.00001 -0.00018 1.00000 0.00010 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00003 1.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -0.99532 0.09668 0.00033 -0.99385 0.11073 -0.00001 -0.95644 0.29193 -0.00026 -0.94429 0.32911 0.00048 -0.87534 0.48351 -0.00044 -0.84619 0.53288 0.00056 -0.74993 0.66152 -0.00055 -0.70699 0.70722 0.00052 -0.53268 0.84632 -0.00093 -0.57876 0.81550 0.00076 -0.36769 0.92995 -0.00052 -0.12295 0.99240 0.00455 -0.22254 0.97492 0.00000 -0.61454 0.66814 0.41945 -0.66996 0.56855 0.47739 -0.69560 0.53927 0.47469 -0.72672 0.45227 0.51703 -0.75794 0.39558 0.51870 -0.76924 0.33433 0.54451 -0.79942 0.21822 0.55974 -0.79892 0.24143 0.55085 -0.81442 0.10721 0.57028 -0.82019 0.08090 0.56634 -0.81723 -0.00218 0.57630 -0.82026 -0.08188 0.56611 -0.81371 -0.11197 0.57039 -0.80417 -0.22064 0.55194 -0.79513 -0.24254 0.55583 -0.76778 -0.33966 0.54326 -0.75762 -0.39679 0.51824 -0.72461 -0.45705 0.51580 -0.69536 -0.54039 0.47377 -0.66768 -0.57204 0.47642 -0.61475 -0.66850 0.41856 -0.06688 0.99658 0.04850 -0.20026 0.96938 0.14214 -0.32738 0.91571 0.23300 -0.40102 0.87325 0.27678 -0.44750 0.83706 0.31477 -0.49636 0.79558 0.34738 -0.58417 0.70034 0.41021 -0.55656 0.73554 0.38628 -0.59708 0.68721 0.41381 -0.64563 0.61396 0.45412 -0.69460 0.53185 0.48442 -0.71958 0.47561 0.50596 -0.75525 0.38992 0.52684 -0.57358 -0.00000 -0.81915 -0.59675 0.02602 -0.80201 -0.56986 -0.01409 -0.82162 -0.56984 0.01636 -0.82159 -0.57358 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57357 -0.00000 -0.81916 -0.57358 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57357 0.00000 -0.81915 -0.57357 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 0.00000 -0.81916 -0.57358 -0.00000 -0.81915 -0.57357 -0.00000 -0.81916 -0.57355 -0.00000 -0.81917 -0.46719 -0.00005 -0.88416 -0.47825 -0.00000 -0.87823 -0.57848 -0.00000 -0.81570 -0.57848 -0.00000 -0.81570 -0.57357 -0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57358 0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81915 -0.57357 -0.00000 -0.81916 0.54519 -0.00159 0.83831 0.58146 0.00504 0.81356 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57357 -0.00000 0.81915 0.57358 0.00000 0.81915 0.57308 -0.00060 0.81950 0.57657 -0.00060 0.81705 0.57358 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57357 0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 -0.00000 0.81915 0.57358 0.00000 0.81915 0.56403 0.00624 0.82573 0.57218 -0.00132 0.82013 0.57358 0.00000 0.81915 0.57501 -0.00131 0.81814 0.57453 -0.00126 0.81848 0.56893 -0.00126 0.82238 0.57565 -0.00198 0.81769 0.52026 -0.00165 0.85400 0.58896 -0.01024 0.80810 0.54697 -0.00918 0.83710 0.61850 -0.01922 0.78555 0.44949 -0.01288 0.89319 -0.37378 -0.88909 0.26420 -0.38309 -0.88391 0.26824 -0.46596 -0.82314 0.32453 -0.48598 -0.80351 0.34378 -0.54890 -0.74371 0.38159 -0.57912 -0.70486 0.40963 -0.61570 -0.66079 0.42926 -0.65792 -0.59017 0.46781 -0.69672 -0.52790 0.48570 -0.72500 -0.46209 0.51074 -0.73770 -0.43625 0.51525 -0.77068 -0.33630 0.54126 -0.77314 -0.32991 0.54168 -0.79642 -0.23786 0.55600 -0.81171 -0.14170 0.56661 -0.80133 -0.19870 0.56426 -0.81516 -0.08812 0.57249 -0.81367 -0.09843 0.57293 -0.00000 -1.00000 -0.00000 -0.00001 -1.00000 -0.00014 0.00062 -1.00000 0.00215 -0.00053 -1.00000 -0.00087 0.00000 -1.00000 -0.00000 -0.00042 -1.00000 -0.00066 0.00010 -1.00000 0.00013 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00002 -1.00000 -0.00002 0.00001 -1.00000 0.00004 0.00058 -1.00000 0.00046 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00008 -1.00000 -0.00019 -0.99581 -0.09143 -0.00000 -0.99163 -0.12915 0.00075 -0.96111 -0.27616 -0.00048 -0.92423 -0.38184 0.00094 -0.89231 -0.45143 -0.00029 -0.79300 -0.60922 0.00044 -0.79693 -0.60407 0.00059 -0.68288 -0.73053 -0.00031 -0.60896 -0.79320 0.00089 -0.55333 -0.83296 -0.00015 -0.38648 -0.92230 0.00025 -0.40810 -0.91294 0.00084 -0.24988 -0.96828 -0.00048 -0.08252 -0.99659 0.00116 -0.12638 -0.99198 -0.00000 -0.07921 -0.99578 0.04634 -0.08134 -0.99516 0.05520 -0.22312 -0.96190 0.15803 -0.37853 -0.88591 0.26810 -0.23235 -0.95601 0.17904 -0.07236 -0.99582 0.05576 -0.07481 -0.99514 0.06410 -0.91134 0.00037 0.41165 -0.63266 0.00678 0.77440 -0.42847 -0.00197 0.90356 -0.17791 0.00212 0.98404 0.13124 -0.00655 0.99133 0.35137 0.00137 0.93623 -0.03705 -0.00919 0.99927 -0.02605 -0.01111 0.99960 -0.42970 0.04046 -0.90206 -0.14417 0.19776 -0.96959 -0.63748 -0.06056 -0.76808 -0.40795 0.05693 -0.91123 -0.58871 -0.02189 -0.80804 -0.00094 -1.00000 -0.00075 0.00004 -1.00000 -0.00021 0.00015 -1.00000 -0.00018 0.00005 -1.00000 -0.00018 -0.81912 0.00000 0.57363 -0.81915 0.00007 0.57358 -0.81899 0.01982 0.57346 -0.81744 0.01111 0.57590 0.13080 -0.10869 0.98543 -0.42838 -0.00601 0.90358 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -0.00000 0.99659 -0.08250 0.06911 0.98043 -0.18433 0.02892 0.96905 -0.24515 0.03176 0.91547 -0.40113 0.07993 0.88249 -0.46349 0.00835 0.83743 -0.54647 0.37061 0.89645 -0.24296 -0.00019 0.98278 -0.18477 0.87802 0.37680 -0.29514 -0.99464 0.00002 -0.10336 -0.92874 -0.03124 -0.36941 -0.42401 -0.00249 -0.90566 -0.40166 -0.00719 -0.91576 -0.94765 0.00747 -0.31923 -0.92916 -0.00330 -0.36966 -0.42400 0.00513 -0.90565 -0.32213 0.16214 -0.93271 -0.94783 0.01266 -0.31854 -0.91264 0.11321 -0.39276 -0.45811 0.32302 -0.82813 -0.37910 0.42947 -0.81966 -0.91596 0.21383 -0.33955 -0.01608 0.96354 -0.26707 -0.53564 0.55372 -0.63756 -0.00980 0.99995 0.00128 0.09133 0.85517 -0.51024 0.51178 0.84849 -0.13471 0.10167 0.30712 -0.94622 0.36890 0.39443 -0.84163 0.22113 0.60973 -0.76114 0.09710 0.58560 -0.80476 0.28887 0.32605 -0.90014 0.55510 0.80523 -0.20849 0.47776 0.69293 -0.53999 0.61716 0.46720 -0.63311 0.58369 0.42211 -0.69363 0.65409 0.47219 -0.59093 0.79357 0.49309 -0.35653 0.62114 0.74363 -0.24739 0.89897 0.43191 -0.07292 0.06069 0.00827 -0.99812 0.18985 0.01736 -0.98166 0.31441 0.06473 -0.94708 0.36855 0.05476 -0.92800 0.69775 0.08161 -0.71168 0.76859 0.11653 -0.62904 0.78377 0.11006 -0.61122 0.92466 0.10366 -0.36641 0.97977 0.13552 -0.14728 0.97480 0.10373 -0.19750 0.41884 -0.00472 -0.90805 0.31523 0.02585 -0.94866 0.77380 -0.01778 -0.63318 0.91880 0.01694 -0.39435 0.97981 -0.00740 -0.19978 -0.00305 0.26299 -0.96479 0.01788 0.78766 -0.61585 -0.00583 0.96429 -0.26480 0.42691 0.88796 -0.17110 0.00000 1.00000 -0.00000 0.00048 1.00000 0.00015 0.65592 0.73166 -0.18560 0.42238 0.87851 -0.22318 0.96111 0.26664 -0.07190 0.90640 0.37056 -0.20279 0.99521 0.09554 -0.02091 0.65566 0.73192 -0.18548 0.96723 0.23425 -0.09795 0.54023 0.70398 -0.46104 0.96124 0.23066 -0.15106 0.96158 0.23010 -0.14974 0.64007 0.66276 -0.38866 0.33679 0.81621 -0.46944 0.43846 0.79570 -0.41788 0.96726 0.18434 -0.17441 0.24278 0.70085 -0.67072 0.96254 0.16633 -0.21411 0.95873 0.16800 -0.22936 0.72904 0.41991 -0.54053 0.28875 0.54976 -0.78382 0.34460 0.56504 -0.74965 0.68710 0.41721 -0.59483 0.23894 0.45220 -0.85931 0.96692 0.11126 -0.22954 0.96415 0.08598 -0.25105 0.95498 0.07927 -0.28588 0.71990 0.22488 -0.65664 0.69751 0.21592 -0.68327 0.30055 0.28739 -0.90944 0.32639 0.29998 -0.89637 0.23705 0.15619 -0.95886 0.96618 0.02308 -0.25683 0.95959 -0.00016 -0.28140 0.70828 -0.00040 -0.70594 0.31033 0.00048 -0.95063 0.00065 0.08509 -0.99637 -0.00636 0.22636 -0.97402 0.00054 0.46368 -0.88600 0.00265 0.41660 -0.90908 0.00375 0.65529 -0.75536 -0.01025 0.78758 -0.61613 -0.00000 1.00000 -0.00000 0.00018 1.00000 0.00032 -0.00639 0.73618 -0.67676 0.00531 0.72246 -0.69140 -0.00545 0.61487 -0.78861 0.00433 0.60190 -0.79856 -0.00444 0.47681 -0.87899 0.00330 0.46569 -0.88494 -0.00338 0.32578 -0.94544 0.00221 0.31736 -0.94830 -0.00226 0.16587 -0.98615 0.00106 0.16078 -0.98699 -0.00111 0.00000 -1.00000 -0.00178 0.00533 -0.99998 0.00056 0.00203 -1.00000 -0.98134 -0.00068 -0.19227 -0.95470 0.00541 0.29753 0.00070 -0.00534 -0.99999 -0.00016 0.01317 -0.99991 0.00148 -0.00442 -0.99999 -0.00001 0.00017 -1.00000 -1.00000 -0.00006 -0.00010 -1.00000 -0.00002 -0.00006 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 0.00000 1.00000 0.00003 -0.00003 1.00000 -0.00009 0.00213 0.99994 0.01033 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00079 -0.00054 1.00000 0.00059 -0.00081 1.00000 0.00085 -0.00081 1.00000 0.00114 -0.00074 1.00000 0.00139 -0.00058 1.00000 0.00155 -0.00034 0.99991 0.01261 0.00526 0.99992 0.01037 0.00674 0.99994 0.00785 0.00742 0.99996 0.00548 0.00746 0.99996 -0.00730 0.00517 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 0.99943 -0.00475 0.03332 0.06021 -0.96143 -0.26839 -0.03234 -0.99887 -0.03470 -0.00000 -0.99658 -0.08268 0.07447 -0.96665 -0.24502 0.08582 -0.91225 -0.40055 -0.00609 -0.73527 -0.67775 0.00493 -0.72246 -0.69140 -0.00507 -0.61355 -0.78964 0.00381 -0.60190 -0.79856 -0.00391 -0.47506 -0.87995 0.00269 -0.46570 -0.88494 -0.00276 -0.32365 -0.94617 0.00148 -0.31736 -0.94830 -0.00152 -0.16331 -0.98657 0.00017 -0.16077 -0.98699 -0.00017 0.00139 -1.00000 0.31949 -0.93967 -0.12224 0.20985 -0.97715 -0.03394 0.65933 -0.73646 -0.15136 0.45363 -0.87821 -0.15152 0.38503 -0.88891 -0.24818 0.20208 -0.96084 -0.18960 0.70566 -0.68780 -0.17020 0.95681 -0.28519 -0.05639 0.94522 -0.32310 -0.04662 0.96723 -0.23432 -0.09778 0.67472 -0.68940 -0.26361 0.73440 -0.56821 -0.37121 0.96112 -0.23156 -0.15040 0.96144 -0.23023 -0.15041 0.67704 -0.58493 -0.44663 0.16958 -0.88953 -0.42424 -0.02848 -0.93367 -0.35701 0.32989 -0.75042 -0.57275 0.24307 -0.70080 -0.67067 0.96726 -0.18452 -0.17424 0.96336 -0.15873 -0.21619 0.96043 -0.17111 -0.21975 0.72972 -0.42008 -0.53948 0.28080 -0.57769 -0.76644 0.32399 -0.54248 -0.77508 0.68629 -0.41706 -0.59588 0.23911 -0.45219 -0.85927 0.96692 -0.11155 -0.22939 0.96501 -0.07041 -0.25257 0.95980 -0.09124 -0.26543 0.72077 -0.22533 -0.65552 0.69656 -0.21551 -0.68437 0.29439 -0.30330 -0.90628 0.31813 -0.28476 -0.90427 0.23709 -0.15619 -0.95885 0.96619 -0.02347 -0.25676 0.30961 0.00000 -0.95086 0.70937 0.00035 -0.70484 0.06717 -0.84509 -0.53039 -0.00842 -0.71206 -0.70207 -0.00262 -0.21345 -0.97695 -0.11591 -0.99224 -0.04487 -0.01912 -0.99969 -0.01602 0.00427 -0.99999 -0.00163 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00027 -1.00000 -0.00233 -0.00165 -1.00000 -0.00006 0.00704 -0.99998 -0.00000 0.00000 -0.99987 0.01624 -0.00000 -1.00000 -0.00000 -0.00021 -1.00000 0.00071 -0.01885 -0.99982 0.00276 0.06188 -0.99808 0.00016 -0.00000 0.00000 -1.00000 -0.02573 0.01376 -0.99957 0.00012 -0.00117 -1.00000 -0.00114 0.00408 -0.99999 0.00017 0.00013 -1.00000 0.00020 0.00000 -1.00000 0.99989 -0.00158 0.01474 1.00000 -0.00022 0.00002 1.00000 -0.00015 -0.00002 1.00000 -0.00010 -0.00005 1.00000 -0.00006 -0.00006 1.00000 -0.00004 -0.00008 1.00000 -0.00001 -0.00008 1.00000 0.00000 -0.00009 0.34698 0.00123 0.93787 0.40072 0.00906 0.91615 0.84017 -0.00949 0.54223 0.92621 0.01502 0.37671 -0.00237 -0.19912 -0.97997 -0.00004 -0.15473 -0.98796 0.00207 -0.45310 -0.89146 -0.00138 -0.54534 -0.83821 0.00306 -0.70730 -0.70691 -0.00038 -0.80300 -0.59598 0.00091 -0.89164 -0.45274 -0.00041 -0.90754 -0.41996 0.00285 -0.98797 -0.15461 0.27329 -0.95154 -0.14102 0.44918 -0.88817 -0.09694 0.66329 -0.38694 -0.64056 0.46965 -0.79353 -0.38696 0.70266 -0.44978 -0.55133 0.44405 -0.77056 -0.45722 0.41026 -0.39606 -0.82147 0.19310 -0.72862 -0.65713 0.28278 -0.40988 -0.86720 0.87768 -0.14247 -0.45758 0.44473 -0.03173 -0.89510 0.41113 -0.00213 -0.91158 0.87417 0.01128 -0.48550 0.86685 0.00702 -0.49852 0.44398 0.02422 -0.89571 0.19572 -0.02096 -0.98044 0.10848 -0.89728 -0.42793 0.00784 -0.83683 -0.54740 0.22909 -0.96084 -0.15588 0.27156 -0.91243 -0.30616 0.25632 -0.91571 -0.30946 0.00000 1.00000 0.00008 -0.00411 0.99994 -0.01031 0.01771 0.99973 0.01524 0.00066 1.00000 -0.00010 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -0.99999 0.00483 0.00194 -1.00000 -0.00081 -0.00005 -1.00000 -0.00008 0.00000 1.00000 0.00003 -0.00011 1.00000 0.00000 -0.00004 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 0.00001 -0.00008 -1.00000 0.00041 0.00007 -1.00000 0.00004 -0.00006 -1.00000 -0.00000 -0.98894 -0.14835 -0.07779 -0.99356 -0.08236 0.01710 -0.96923 -0.24555 0.01203 -0.91565 -0.40179 -0.09268 -0.83347 -0.54473 -0.01340 -0.87044 -0.49209 0.00603 -0.73558 -0.67741 -0.00492 -0.72119 -0.69272 0.00506 -0.61401 -0.78928 -0.00391 -0.60074 -0.79944 0.00402 -0.47567 -0.87962 -0.00283 -0.46472 -0.88545 0.00291 -0.32433 -0.94594 -0.00169 -0.31667 -0.94854 0.00174 -0.16417 -0.98643 -0.00049 -0.16041 -0.98705 0.00050 0.00000 -1.00000 0.00076 0.00044 -1.00000 -0.00074 0.16041 -0.98705 0.00196 0.16500 -0.98629 -0.00191 0.31667 -0.94854 0.00309 0.32505 -0.94569 -0.00301 0.46472 -0.88545 0.00416 0.47622 -0.87931 -0.00405 0.60074 -0.79944 0.00517 0.61442 -0.78896 -0.00502 0.72119 -0.69271 0.00611 0.73587 -0.67710 -0.01882 0.89902 -0.43750 -0.16628 0.82561 -0.53918 -0.07078 0.91353 -0.40057 -0.07078 0.96699 -0.24479 -0.05540 0.96129 -0.26990 0.02931 0.99899 -0.03418 -0.00000 0.99659 -0.08255 -0.04440 0.99853 0.03114 -0.12729 0.98791 0.08852 -0.19198 0.97199 0.13553 -0.23751 0.95685 0.16739 -0.40860 0.86799 0.28221 -0.58961 -0.71016 0.38475 -0.42041 -0.85339 0.30819 -0.41594 -0.86902 0.26795 -0.25189 -0.93317 0.25641 -0.05191 -0.99500 0.08536 -0.10673 -0.98976 0.09482 -0.85201 0.40216 -0.33517 -0.69704 0.20628 -0.68672 -0.75212 0.50121 -0.42791 -0.73006 0.51076 -0.45402 -0.74477 0.63870 -0.19335 -0.72456 0.63349 0.27148 -0.73062 0.61775 0.29081 -0.76615 0.63519 0.09773 -0.81076 0.58258 -0.05715 -0.78499 0.52329 0.33159 -0.88295 0.30225 -0.35923 -0.75644 0.08608 -0.64837 -0.72075 0.11594 -0.68343 -0.88461 0.30064 -0.35648 -0.90793 0.41745 -0.03742 -0.92613 0.37675 0.01852 -0.84932 0.38286 0.36341 -0.84329 0.42919 0.32351 -0.88650 0.23406 0.39918 -0.91586 0.14795 0.37324 -0.99040 0.12887 0.04993 -0.98871 0.14639 0.03191 -0.90850 0.07863 0.41042 -0.94294 0.10447 -0.31613 -0.94270 0.10506 -0.31668 -0.75519 0.04331 -0.65407 -0.93327 -0.07756 0.35070 -0.90151 -0.14780 0.40674 -0.99053 -0.12779 0.05020 -0.88637 -0.23413 0.39941 -0.94309 -0.10406 -0.31583 -0.98881 -0.14573 0.03179 -0.75531 -0.04352 -0.65392 -0.94252 -0.10542 -0.31709 -0.74405 -0.06878 -0.66457 -0.92652 -0.37577 0.01892 -0.86892 -0.37882 0.31856 -0.83243 -0.43053 0.34886 -0.78488 -0.52336 0.33174 -0.88522 -0.45571 -0.09330 -0.86172 -0.35309 -0.36437 -0.74899 -0.14182 -0.64723 -0.89337 -0.32373 -0.31158 -0.71593 -0.64677 0.26292 -0.82099 -0.56175 -0.10201 -0.76089 -0.62792 -0.16362 -0.80892 -0.45134 -0.37675 -0.77034 -0.46698 -0.43417 -0.71136 -0.22044 -0.66736 -0.82175 -0.40640 -0.39945 -0.99641 0.01264 -0.08372 -0.99440 0.01900 -0.10391 -0.99909 0.02271 -0.03604 -0.99910 0.01164 -0.04086 -0.98940 0.00979 -0.14488 -0.99479 0.02021 -0.09990 -0.99439 0.04069 -0.09761 -0.95942 0.02107 -0.28120 -0.98285 0.10447 -0.15198 -0.98228 0.06087 -0.17726 -0.97005 0.08808 -0.22637 -0.97071 0.02645 -0.23878 -0.94129 0.03215 -0.33606 -0.92585 0.25437 -0.27947 -0.94810 0.03658 -0.31585 -0.94714 0.11249 -0.30044 -0.94438 0.11344 -0.30867 -0.94449 0.21078 -0.25201 -0.90234 0.03339 -0.42973 -0.90112 0.15446 -0.40512 -0.95800 0.22671 -0.17562 -0.85440 0.05021 -0.51719 -0.88761 0.15914 -0.43224 -0.88753 0.29835 -0.35111 -0.88687 0.39878 -0.23331 -0.88628 0.29947 -0.35330 -0.86074 0.17898 -0.47653 -0.86283 0.05417 -0.50259 -0.87332 0.41807 -0.25005 -0.78554 0.58510 -0.20143 -0.84471 0.34678 -0.40768 -0.84469 0.18333 -0.50288 -0.84246 0.34832 -0.41101 -0.84263 0.46866 -0.26522 -0.87694 0.46920 -0.10406 -0.79621 0.04933 -0.60301 -0.79397 0.21498 -0.56868 -0.80822 0.51113 -0.29244 -0.80824 0.58037 -0.09955 -0.75062 0.06643 -0.65739 -0.76342 0.21694 -0.60839 -0.76389 0.41786 -0.49180 -0.82041 0.38806 -0.41992 -0.77668 0.55286 -0.30184 -0.71552 0.68890 0.11600 -0.67252 0.73641 0.07360 -0.68128 0.71822 -0.14147 -0.80207 0.07691 -0.59226 -0.80199 0.19953 -0.56302 -0.71226 0.19810 -0.67338 -0.75280 0.44516 -0.48489 -0.76563 0.56447 -0.30851 -0.81790 0.55515 -0.15114 -0.69938 0.65228 0.29223 -0.90923 -0.37661 -0.17741 -0.99138 -0.13051 -0.01133 -0.94905 -0.30449 -0.08115 -0.96491 -0.25861 -0.04554 -0.59666 -0.77757 -0.19844 -0.78914 -0.60489 -0.10660 -0.96579 -0.23516 -0.10929 -0.94908 -0.25828 -0.18036 -0.96491 -0.22739 -0.13129 -0.38776 -0.80241 -0.45363 -0.23859 -0.70037 -0.67272 -0.96579 -0.18359 -0.18314 -0.73860 -0.43333 -0.51643 -0.94907 -0.18102 -0.25788 -0.96492 -0.16876 -0.20112 -0.33059 -0.56697 -0.75449 -0.30501 -0.55943 -0.77072 -0.68058 -0.43039 -0.59294 -0.23770 -0.45140 -0.86008 -0.96579 -0.10987 -0.23491 -0.94905 -0.08189 -0.30430 -0.96492 -0.08979 -0.24670 -0.72751 -0.23466 -0.64472 -0.32226 -0.29977 -0.89793 -0.30986 -0.29360 -0.90431 -0.69470 -0.22212 -0.68415 -0.23725 -0.15583 -0.95887 -0.96579 -0.02288 -0.25833 -0.31427 0.00000 -0.94933 -0.31426 0.00001 -0.94934 -0.94902 0.02718 -0.31403 -0.96494 0.00000 -0.26248 -0.71175 0.00001 -0.70244 -0.71176 0.00000 -0.70243 -0.23726 0.15583 -0.95887 -0.96578 0.06695 -0.25059 -0.30662 0.30141 -0.90285 -0.31822 0.29276 -0.90168 -0.69471 0.22213 -0.68414 -0.94895 0.13315 -0.28595 -0.96496 0.08974 -0.24656 -0.72750 0.23466 -0.64473 -0.23770 0.45141 -0.86008 -0.96576 0.14873 -0.21256 -0.68059 0.43040 -0.59292 -0.29934 0.57319 -0.76279 -0.32173 0.55621 -0.76624 -0.73859 0.43333 -0.51643 -0.94887 0.22317 -0.22323 -0.96499 0.16860 -0.20093 -0.23859 0.70038 -0.67272 -0.96575 0.21257 -0.14882 -0.29394 0.85945 -0.41827 -0.39363 0.80545 -0.44306 -0.61553 0.69053 -0.37986 -0.95883 0.24595 -0.14200 -0.58201 0.70424 -0.40659 -0.96576 0.23516 -0.10959 -0.96573 0.25072 -0.06706 -0.94877 0.31477 -0.02745 -0.98964 0.11151 -0.09042 -0.93744 0.34165 -0.06689 -0.58734 0.80068 -0.11806 -0.82265 0.52193 -0.22548 -0.69248 0.69246 -0.20242 -0.51476 0.83137 -0.20939 -0.35241 0.90101 -0.25295 -0.31232 0.91936 -0.23925 -0.35288 0.90052 -0.25404 -0.11191 0.99314 -0.03398 -0.11197 0.99371 -0.00018 -0.19470 0.98086 0.00368 -0.36517 0.93094 -0.00240 -0.52609 0.85043 0.00128 -0.48899 0.87229 -0.00127 -0.71432 0.69982 0.00092 -0.70711 0.70710 0.00148 -0.85959 0.51099 -0.00057 -0.84474 0.53517 0.00095 -0.95877 0.28417 -0.00194 -0.93949 0.34257 0.00178 -0.99548 0.09500 -0.00080 -0.99371 0.11197 -0.00000 -0.71339 0.69851 -0.05630 -0.56259 0.82057 -0.10077 -0.85496 0.50828 -0.10339 -0.84155 0.52929 -0.10786 -0.94907 0.28146 -0.14156 -0.98782 0.09500 -0.12320 -0.40606 0.91384 0.00140 -0.33249 0.94307 -0.00820 -0.25589 0.96528 -0.05253 -0.71102 0.64366 0.28310 -0.54364 0.78034 0.30909 -0.33536 0.94206 0.00732 -0.61036 0.78440 0.11036 -0.69207 0.70324 0.16275 -0.51710 0.85478 -0.04420 -0.57639 0.80331 0.14989 -0.65788 0.74913 0.07743 -0.66787 0.74149 0.06445 -0.61650 0.78145 -0.09628 -0.57265 0.81761 -0.05997 -0.81666 0.57248 -0.07309 -0.80041 0.58146 -0.14577 -0.85598 0.47873 -0.19525 -0.83658 0.53124 -0.13387 0.94876 -0.00015 -0.31601 0.93268 0.00119 -0.36069 0.45376 -0.00118 -0.89112 0.43535 -0.00046 -0.90026 -0.00008 -1.00000 0.00003 -0.00004 -1.00000 0.00008 -0.00000 -1.00000 -0.00000 -0.00014 -1.00000 -0.00003 -0.99645 -0.01178 -0.08335 -0.99838 -0.02493 -0.05121 -0.99840 -0.01889 -0.05325 -0.99831 -0.02479 -0.05261 -0.99608 -0.03423 -0.08157 -0.99623 -0.01169 -0.08592 -0.98927 -0.01950 -0.14477 -0.98227 -0.01710 -0.18671 -0.98195 -0.06726 -0.17676 -0.95916 -0.03073 -0.28118 -0.99051 -0.07150 -0.11737 -0.97885 -0.12529 -0.16172 -0.97854 -0.06962 -0.19394 -0.96279 -0.16218 -0.21617 -0.95926 -0.17227 -0.22393 -0.95864 -0.09615 -0.26787 -0.94131 -0.03120 -0.33609 -0.94724 -0.03592 -0.31851 -0.94603 -0.11758 -0.30201 -0.94252 -0.27674 -0.18729 -0.90548 -0.14467 -0.39897 -0.90630 -0.26320 -0.33068 -0.91788 -0.25225 -0.30637 -0.92164 -0.33165 -0.20146 -0.88554 -0.16664 -0.43364 -0.88712 -0.03633 -0.46011 -0.85388 -0.05461 -0.51760 -0.93377 -0.30990 -0.17895 -0.84346 -0.35236 -0.40548 -0.84410 -0.18374 -0.50372 -0.78477 -0.55201 -0.28182 -0.82329 -0.04665 -0.56570 -0.82116 -0.20268 -0.53349 -0.80804 -0.51687 -0.28269 -0.80829 -0.37583 -0.45323 -0.75065 -0.06076 -0.65790 -0.81602 -0.54582 -0.19022 -0.75011 -0.22158 -0.62309 -0.74505 -0.43762 -0.50338 -0.76738 -0.21066 -0.60560 -0.76702 -0.06712 -0.63810 -0.78483 -0.54598 -0.29316 -0.81263 -0.39394 -0.42947 -0.69897 -0.62124 -0.35427 -0.73121 -0.65735 -0.18227 -0.68418 -0.50855 -0.52276 -0.72607 -0.21577 -0.65289 -0.72268 -0.67883 0.13008 -0.72773 -0.59361 -0.34357 -0.26439 -0.95913 0.10084 -0.43202 -0.89695 -0.09402 -0.60507 -0.78323 0.14299 -0.37513 -0.92668 0.02337 -0.45848 -0.88854 -0.01704 -0.60554 -0.79307 -0.06602 -0.65296 -0.75117 0.09689 -0.65425 -0.75042 0.09391 -0.79256 -0.58910 -0.15750 -0.62249 -0.77873 -0.07806 -0.79490 -0.58781 -0.15038 -0.81050 -0.56211 -0.16469 -0.80987 -0.56342 -0.16328 -0.89865 -0.39226 -0.19637 -0.11935 -0.99279 -0.01103 -0.01440 -0.99946 -0.02951 -0.00113 -1.00000 -0.00022 -0.35219 -0.93587 -0.01041 -0.13165 -0.99122 -0.01197 -0.23745 -0.97008 -0.05070 -0.23772 -0.97009 -0.04912 -0.27333 -0.96060 -0.05035 -0.41704 -0.90479 -0.08624 -0.42482 -0.90444 -0.03896 -0.44559 -0.89136 -0.08320 -0.59525 -0.80066 -0.06794 -0.59636 -0.79987 -0.06757 -0.58807 -0.80012 -0.11830 -0.61667 -0.77970 -0.10854 -0.80649 -0.58640 -0.07556 -0.80826 -0.58407 -0.07472 -0.79714 -0.58499 -0.14953 -0.91898 -0.37912 -0.10838 -0.81507 -0.56331 -0.13544 -0.96749 -0.23987 -0.08019 -0.91153 -0.37765 -0.16281 -0.94301 -0.26140 -0.20591 -0.99276 -0.04471 -0.11144 -0.98909 -0.12734 -0.07404 -0.92994 -0.29900 -0.21403 -0.13052 -0.99145 -0.00000 -0.11930 -0.99286 -0.00062 -0.38269 -0.92388 -0.00041 -0.35226 -0.93590 0.00101 -0.60876 -0.79335 0.00135 -0.59647 -0.80264 0.00229 -0.80905 -0.58775 -0.00068 -0.79366 -0.60836 0.00081 -0.92437 -0.38149 -0.00007 -0.92388 -0.38268 -0.00000 -0.99165 -0.12898 -0.00000 -0.99145 -0.13052 0.00008 -0.12910 -0.98066 -0.14711 -0.37551 -0.90654 -0.19282 -0.46810 -0.85305 -0.23062 -0.45151 -0.78785 -0.41884 -0.54659 -0.72521 -0.41870 -0.60828 -0.70084 -0.37259 -0.57211 -0.79176 -0.21405 -0.47465 0.85109 0.22437 -0.45770 0.85360 0.24877 -0.35988 0.92621 0.11233 -0.54930 0.82112 0.15502 -0.48822 0.87064 -0.06021 -0.19468 0.98086 -0.00401 -0.20492 0.97874 -0.00879 -0.24082 0.96995 -0.03453 -0.25539 0.96524 -0.05557 -0.99997 0.00760 0.00012 -1.00000 -0.00300 0.00085 -0.99999 -0.00336 0.00098 -1.00000 0.00000 -0.00119 -0.88623 -0.43705 -0.15354 -0.85970 -0.49134 -0.13965 -0.72137 -0.64084 0.26257 -0.68728 -0.66793 0.28550 -0.53792 -0.82544 0.17114 -0.08964 -0.99555 0.02920 -0.09554 -0.99512 0.02476 -0.10693 -0.99321 0.04582 -0.12593 -0.99204 0.00244 -0.11738 -0.98105 -0.15415 -0.99917 -0.04075 0.00010 -0.04763 -0.99886 -0.00086 1.00000 -0.00003 0.00020 1.00000 0.00020 -0.00005 1.00000 0.00000 -0.00000 0.23930 0.01659 -0.97080 0.34055 0.00455 -0.94021 0.46476 0.00106 -0.88544 0.66315 -0.00252 -0.74848 0.82299 0.00606 -0.56802 0.93471 0.02630 -0.35445 0.99271 0.00000 -0.12052 0.99272 -0.00003 -0.12047 0.90407 0.01585 -0.42710 0.00004 -1.00000 -0.00060 -0.00002 -1.00000 0.00010 -0.00003 -1.00000 0.00023 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00001 -1.00000 -0.00008 -0.00000 -1.00000 -0.00000 0.00001 -1.00000 0.00001 -0.94721 -0.01690 -0.32017 -0.16339 -0.02334 -0.98629 -0.45212 -0.00025 -0.89196 -0.99462 -0.00929 -0.10313 -0.16357 -0.01428 -0.98643 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -0.38032 0.92486 0.81513 -0.05270 0.57688 0.89867 0.00000 -0.43862 0.90448 -0.00686 -0.42646 0.93932 0.00431 -0.34300 0.95454 -0.00924 -0.29793 0.96947 0.00460 -0.24519 0.98666 -0.00091 -0.16281 0.98983 -0.00941 -0.14195 -0.02276 0.02489 -0.99943 0.11936 -0.02615 -0.99251 0.22525 0.01382 -0.97420 0.35757 -0.00915 -0.93384 0.45244 0.01231 -0.89171 0.53493 -0.00692 -0.84487 0.65212 0.00854 -0.75806 0.69123 -0.00348 -0.72263 0.81067 0.00405 -0.58549 0.82026 0.00000 -0.57198 -0.09964 -0.00182 -0.99502 -0.06235 -0.99576 0.06765 -0.20239 -0.95912 0.19783 -0.06165 -0.99595 0.06545 -0.34540 -0.88056 0.32451 -0.33889 -0.89009 0.30478 -0.19917 -0.96179 0.18786 -0.36683 -0.89147 0.26592 0.63673 -0.60063 0.48355 0.23912 -0.84737 0.47411 -0.27370 -0.82723 0.49069 0.08863 -0.90329 0.41977 0.66470 -0.60402 0.43969 0.68477 -0.59229 0.42460 0.65149 -0.66023 0.37370 0.11709 -0.94461 0.30658 0.23973 -0.93327 0.26746 0.69565 -0.64300 0.32035 0.68751 -0.64940 0.32496 0.66453 -0.69356 0.27817 0.72637 -0.64473 0.23814 0.69088 -0.67950 0.24689 0.24171 -0.95057 0.19490 0.37290 -0.91533 0.15207 0.40213 -0.91136 0.08778 0.34730 -0.93255 0.09866 0.35562 -0.93131 0.07872 0.31504 -0.94817 0.04156 0.11688 -0.99303 0.01542 0.44025 -0.89783 -0.00834 0.32155 -0.94663 0.02245 -0.64977 0.09072 -0.75470 -0.57243 0.08332 -0.81571 -0.51776 0.03186 -0.85493 -0.62121 0.09207 -0.77821 -0.57806 0.10976 -0.80858 -0.43630 0.08042 -0.89620 -0.49554 0.25511 -0.83027 -0.19864 0.16207 -0.96658 -0.22929 0.17023 -0.95836 -0.29247 0.38863 -0.87374 -0.29805 0.38725 -0.87247 -0.01434 0.17727 -0.98406 -0.12744 0.52532 -0.84131 0.03706 0.59182 -0.80522 0.08401 0.59448 -0.79971 0.18424 0.23727 -0.95381 0.20289 0.23340 -0.95098 0.41255 0.24075 -0.87855 0.24404 0.67986 -0.69155 0.48091 0.49382 -0.72447 0.32623 0.64983 -0.68651 0.02677 0.71691 -0.69666 0.43630 0.68206 -0.58689 0.54954 0.28222 -0.78636 0.61730 0.10490 -0.77970 0.33796 0.28522 -0.89690 -0.08532 0.34759 -0.93376 -0.62387 0.00000 -0.78153 -0.62349 -0.00004 -0.78183 -0.43771 0.00004 -0.89911 -0.43389 -0.00030 -0.90097 -0.23269 0.00030 -0.97255 -0.22252 -0.00052 -0.97493 -0.01457 0.00051 -0.99989 0.00000 -0.00061 -1.00000 0.20865 0.00062 -0.97799 0.22252 -0.00049 -0.97493 0.42505 0.00050 -0.90517 0.43389 -0.00028 -0.90097 0.62072 0.00029 -0.78403 0.62348 0.00000 -0.78184 -0.70708 -0.00000 -0.70713 -0.70708 0.00001 -0.70714 -0.71042 -0.00924 -0.70372 -0.70460 0.01247 -0.70949 -0.66158 0.10003 -0.74317 -0.42193 -0.85212 0.30964 -0.40388 -0.83637 0.37064 -0.40135 -0.84376 0.35636 -0.20145 -0.84829 0.48972 0.15380 -0.75746 0.63451 0.48899 -0.45568 0.74381 0.70889 -0.17853 0.68235 -0.16754 -0.86553 0.47200 -0.24997 -0.87603 0.41242 -0.12948 -0.83921 0.52817 -0.20398 -0.85638 0.47435 0.15361 -0.75727 0.63478 0.32932 -0.67672 0.65848 0.49130 -0.45805 0.74082 0.35433 -0.70914 0.60957 0.22033 -0.81194 0.54057 0.59342 -0.51760 0.61640 0.73746 -0.20902 0.64224 0.81603 -0.30858 0.48874 0.72594 -0.35905 0.58659 0.74060 -0.20016 0.64145 0.11686 -0.99315 -0.00101 0.15018 -0.98823 -0.02930 0.13610 -0.98825 -0.06950 0.18337 -0.98195 -0.04643 0.19195 -0.98129 0.01528 0.10686 -0.99213 -0.06532 0.44024 -0.89779 -0.01251 0.11093 -0.98892 -0.09864 0.11212 -0.98865 -0.09996 0.10903 -0.98864 -0.10344 0.24990 -0.92969 -0.27059 0.18287 -0.94559 -0.26912 0.21560 -0.91331 -0.34551 0.16117 -0.94721 -0.27716 0.17857 -0.90744 -0.38036 0.03254 -0.99832 -0.04801 0.04872 -0.99407 -0.09720 0.04951 -0.99203 -0.11590 0.17347 -0.83606 -0.52049 0.17126 -0.85009 -0.49801 0.17572 -0.90893 -0.37812 0.04759 -0.99237 -0.11371 0.05362 -0.98691 -0.15210 0.25357 -0.94470 -0.20794 0.28405 -0.86435 -0.41499 0.26030 -0.89570 -0.36051 0.26668 -0.82308 -0.50141 0.24780 -0.78437 -0.56864 -0.00007 -1.00000 -0.00113 -0.00020 -1.00000 0.00068 -0.00021 -1.00000 0.00069 -0.00002 -1.00000 0.00001 -0.00020 -1.00000 0.00055 0.00022 -1.00000 -0.00060 -0.00003 -1.00000 0.00004 -0.00001 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00005 -1.00000 0.00045 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.35255 -0.85559 -0.37904 0.31161 -0.88044 -0.35737 0.30615 -0.91006 -0.27940 0.34239 -0.91906 -0.19518 0.29292 -0.91642 -0.27273 0.23870 -0.94562 -0.22096 0.23818 -0.94693 -0.21585 0.24692 -0.94779 -0.20179 0.24706 -0.94852 -0.19817 0.26748 -0.91855 -0.29107 0.25699 -0.94569 -0.19906 0.27778 -0.91561 -0.29070 0.31343 -0.86365 -0.39480 0.25646 -0.94826 -0.18715 0.28640 -0.94311 -0.16890 0.22169 -0.95594 -0.19246 0.30773 -0.86553 -0.39518 0.30238 -0.91049 -0.28208 0.25644 -0.94901 -0.18335 0.25605 -0.88811 -0.38170 0.26506 -0.94651 -0.18401 0.25658 -0.94790 -0.18884 0.25937 -0.91405 -0.31183 0.23567 -0.92014 -0.31274 0.29058 -0.93865 -0.18576 0.22897 -0.89099 -0.39205 0.20269 -0.89843 -0.38954 0.30087 -0.93914 -0.16582 0.26048 -0.92746 -0.26829 0.38789 -0.89876 -0.20440 0.32473 -0.88015 -0.34626 0.34608 -0.92538 -0.15461 0.26658 -0.86565 -0.42378 0.27902 -0.85449 -0.43818 0.46876 -0.87558 -0.11673 0.49020 -0.86811 -0.07805 0.48150 -0.87160 -0.09202 0.49020 -0.86788 -0.08050 0.44748 -0.89143 -0.07148 0.50056 -0.86569 -0.00419 0.49951 -0.86628 -0.00653 0.60060 -0.78895 -0.12977 0.50745 -0.85943 -0.06224 0.70137 -0.70492 0.10568 0.69565 -0.70941 0.11318 0.62899 -0.76239 -0.15210 0.66457 -0.74429 -0.06619 0.59521 -0.79938 0.08194 0.62655 -0.76112 0.16771 0.62699 -0.76713 0.13564 0.69117 -0.71644 0.09484 0.71830 -0.69528 0.02532 0.75803 -0.62275 0.19386 0.76046 -0.58037 0.29133 0.75752 -0.59754 0.26289 0.75450 -0.60709 0.24934 0.79914 -0.58591 0.13449 0.79057 -0.60582 0.08939 0.82154 -0.54052 0.18141 0.82078 -0.46928 0.32573 0.83535 -0.39976 0.37735 0.81507 -0.37895 0.43824 0.82467 -0.40327 0.39661 0.82630 -0.43375 0.35929 0.87326 -0.36728 0.32020 0.87431 -0.43232 0.22066 0.87569 -0.41984 0.23853 0.87975 -0.37201 0.29606 0.88118 -0.33041 0.33815 0.88164 -0.27878 0.38078 0.85999 -0.22118 0.45988 0.88171 -0.23170 0.41098 0.87673 -0.10354 0.46971 0.76116 -0.18406 0.62190 0.83000 -0.16690 0.53220 0.84911 0.02206 0.52775 0.00080 1.00000 -0.00292 0.00019 -1.00000 -0.00000 0.04146 -0.99782 -0.05141 -0.00711 -0.99992 0.01040 0.00334 -0.99998 -0.00489 -0.00089 -1.00000 0.00028 -0.00100 -1.00000 0.00047 -0.00108 -1.00000 0.00076 -0.00119 -1.00000 0.00124 -0.00128 -1.00000 0.00203 -0.00211 -0.99999 0.00406 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00135 -0.99999 0.00353 0.00205 -0.99106 0.13340 0.27721 -0.54626 0.79042 -0.11666 0.03639 0.99250 -0.60441 0.20740 0.76921 -0.74548 -0.18726 0.63968 -0.42853 -0.16072 0.88912 0.99622 0.04058 -0.07681 0.99861 0.03368 -0.04044 -0.27653 -0.59294 0.75627 -0.22124 -0.61003 0.76087 0.88920 -0.28229 0.36004 0.11993 0.99253 0.02254 -0.55015 -0.62730 0.55121 0.85361 0.22300 0.47076 0.78945 0.37028 0.48956 0.17108 -0.93225 0.31883 0.17468 -0.93298 0.31470 0.27671 0.96062 0.02535 0.26317 0.96324 0.05398 0.26772 0.96063 0.07428 0.24572 0.96262 0.11395 0.24710 0.96090 0.12493 0.36884 -0.86583 0.33807 0.40262 -0.84456 0.35300 0.30819 -0.87861 0.36477 0.79235 -0.48637 0.36827 0.73055 -0.55835 0.39311 0.93957 -0.14654 0.30941 0.92841 0.29023 0.23200 0.92819 0.29166 0.23107 0.60973 0.41632 0.67447 0.45012 -0.62955 0.63329 0.52768 -0.56847 0.63119 0.51462 -0.58327 0.62846 0.69906 0.28925 0.65394 0.69603 0.25859 0.66983 0.73326 0.39301 0.55486 0.51544 -0.63934 0.57058 0.71478 -0.44325 0.54095 0.50371 -0.69126 0.51811 0.62690 -0.58201 0.51794 0.54684 -0.64325 0.53590 0.85459 0.23614 0.46250 0.87352 0.32514 0.36228 0.77159 0.63476 0.04158 0.14487 -0.93975 0.30966 0.14403 -0.93997 0.30939 0.14387 -0.94000 0.30935 0.14373 -0.94003 0.30933 0.14354 -0.94006 0.30933 0.14339 -0.94007 0.30936 0.10340 -0.93946 0.32668 0.40524 0.83720 0.36725 0.40441 0.85375 0.32798 0.45308 0.83129 0.32198 0.48885 0.83662 0.24716 0.49012 0.83244 0.25851 0.53337 0.82040 0.20604 0.55030 0.82088 0.15270 0.54774 0.82536 0.13699 0.57938 0.81000 0.09072 0.58199 0.81145 0.05332 0.58209 0.81139 0.05314 0.63891 0.76804 -0.04376 0.58234 0.81175 0.04408 -0.62975 -0.61576 0.47356 -0.62713 -0.61181 0.48208 -0.67408 -0.63036 0.38504 -0.72332 -0.61625 0.31151 -0.77754 -0.57908 0.24515 -0.69443 -0.64412 0.32073 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 0.10122 0.99362 0.04977 0.24187 0.96694 -0.08072 0.35177 0.89015 -0.28966 0.31960 0.94341 -0.08850 0.36436 0.93124 0.00607 0.42888 0.90108 -0.06413 0.34159 0.93060 -0.13153 0.35863 0.93029 -0.07715 0.44976 0.89314 0.00495 0.43933 0.89793 0.02653 0.56738 0.81415 -0.12343 0.54248 0.83922 -0.03771 0.19557 -0.87047 0.45170 0.27452 -0.77218 0.57305 0.30521 -0.65708 0.68927 0.99038 0.13277 -0.03900 0.90737 0.41199 0.08332 0.91040 0.37203 0.18104 0.82860 0.54907 -0.10926 0.75316 0.64246 -0.14143 0.78419 0.61951 -0.03530 0.82750 -0.50733 0.24054 0.75402 -0.46134 0.46757 -0.22704 -0.86992 0.43782 0.85822 -0.44314 0.25900 0.91972 -0.36186 0.15225 0.87148 -0.43735 0.22190 0.84363 -0.50055 0.19429 -0.20344 -0.87645 0.43641 0.22710 0.97309 -0.03911 0.27743 0.96072 0.00660 0.22383 0.97307 -0.05512 0.20009 0.97977 0.00241 0.18875 0.98134 -0.03660 0.26631 0.96371 -0.01852 0.27545 0.96128 -0.00810 -0.26496 -0.92700 0.26547 -0.29922 -0.92728 0.22501 -0.29985 -0.92803 0.22101 -0.32465 -0.92748 0.18544 -0.32484 -0.92795 0.18269 -0.34306 -0.92762 0.14774 -0.34305 -0.92790 0.14600 -0.35599 -0.92772 0.11224 -0.35592 -0.92787 0.11129 0.92068 0.37502 -0.10818 -0.69462 -0.69976 0.16684 -0.19265 -0.86351 0.46608 0.12591 -0.54798 0.82696 0.18329 -0.69229 0.69795 0.23960 -0.72465 0.64612 0.33000 -0.71943 0.61116 0.04364 -0.78466 0.61839 -0.14946 -0.85152 0.50256 -0.39572 -0.90000 0.18275 -0.40310 -0.90211 0.15396 -0.38048 -0.92472 -0.01171 0.24914 -0.62470 0.74005 0.33786 -0.80616 0.48576 0.74850 -0.58760 0.30737 0.49646 -0.68116 0.53810 0.96437 -0.18410 0.18999 0.99852 -0.05405 0.00589 0.94067 -0.09921 0.32450 0.93601 -0.05072 0.34831 0.48679 -0.51345 0.70669 0.69862 -0.45435 0.55272 -0.36662 -0.92729 0.07565 0.95921 -0.03705 0.28026 0.99701 -0.05991 0.04874 -0.36474 -0.92779 0.07852 0.20020 -0.56806 0.79827 0.17871 -0.91400 0.36422 -0.18706 -0.74811 0.63666 0.71137 -0.33210 0.61940 0.90024 0.05975 0.43127 0.97304 -0.22827 0.03301 0.94096 0.33621 -0.03941 0.98449 0.17299 -0.02905 0.99287 0.11331 -0.03716 -0.70491 -0.69427 0.14522 0.96140 0.25493 0.10352 0.99978 0.01261 0.01681 0.99021 0.13919 -0.01050 0.99228 0.12113 -0.02651 0.70425 -0.06136 0.70730 0.72397 -0.08034 0.68514 0.69834 -0.06705 0.71261 0.70755 -0.17462 0.68475 0.68757 -0.20294 0.69719 0.68968 -0.35670 0.63017 0.66014 -0.28997 0.69291 0.73912 -0.29694 0.60458 0.65962 -0.29237 0.69240 0.71356 -0.46795 0.52140 0.52244 -0.74493 0.41489 0.56236 -0.62219 0.54464 0.53895 -0.63976 0.54794 -0.16499 -0.69483 0.69999 -0.17217 -0.70201 0.69104 -0.29656 -0.66599 0.68448 -0.31840 -0.67290 0.66770 -0.45185 -0.62142 0.64005 -0.45819 -0.62148 0.63547 -0.66290 -0.37590 0.64750 -0.53420 -0.51395 0.67118 -0.49409 -0.60833 0.62114 -0.69782 -0.07751 0.71207 -0.90614 -0.31237 -0.28518 -0.71726 -0.15742 0.67879 -0.57400 -0.07080 0.81579 -0.67104 -0.18329 0.71841 -0.68092 -0.28192 0.67592 -0.63745 -0.38469 0.66759 -0.72203 -0.43278 0.53979 -0.00000 -1.00000 -0.00000 0.11515 0.99316 -0.01950 0.12396 0.99229 -0.00068 -0.07001 0.99177 -0.10718 -0.06792 0.99150 -0.11096 -0.04278 0.99157 -0.12227 -0.04210 0.99151 -0.12305 -0.01462 0.99156 -0.12881 -0.01424 0.99153 -0.12909 0.01422 0.99156 -0.12889 0.01463 0.99153 -0.12908 0.04210 0.99151 -0.12305 0.04277 0.99157 -0.12228 0.06838 0.99149 -0.11075 0.21031 0.97181 -0.10652 0.04527 0.99623 -0.07396 -0.16531 0.98571 -0.03238 -0.17404 0.98465 -0.01341 0.12153 -0.43758 0.89093 -0.78240 -0.27455 0.55900 0.50696 -0.21300 0.83524 0.43301 -0.20106 0.87868 -0.87579 -0.11927 0.46772 -0.94190 -0.02903 0.33465 -0.97122 0.01020 0.23795 -0.74452 -0.13397 0.65402 -0.35310 -0.20995 0.91172 -0.35677 0.15627 0.92103 0.11078 -0.00001 0.99385 0.55619 -0.07182 0.82794 0.35731 0.14609 0.92249 0.75105 0.02515 0.65977 0.97108 -0.02064 0.23788 0.84841 -0.13085 0.51291 0.86783 -0.13547 0.47804 -0.40482 -0.22605 0.88602 -0.71334 -0.06060 0.69819 -0.55344 -0.12230 0.82386 -0.10840 -0.20591 0.97255 -0.21381 -0.37604 0.90160 0.78239 -0.27465 0.55896 -0.01555 0.99045 -0.13701 0.01553 0.99045 -0.13703 -0.09153 -0.92556 0.36736 -0.09962 -0.92888 0.35672 -0.16235 -0.92614 0.34045 -0.99978 -0.01466 0.01477 1.00000 -0.00000 0.00000 0.94706 -0.18941 -0.25923 1.00000 0.00000 -0.00000 0.72758 0.00000 0.68602 0.72632 -0.00007 0.68736 0.69543 0.00038 0.71860 0.71539 0.00227 0.69872 0.69992 0.00000 0.71422 0.63154 -0.00250 0.77534 0.61482 -0.00663 0.78864 0.56683 0.00142 0.82383 0.47157 0.00882 0.88178 0.42644 -0.00127 0.90452 0.48578 -0.00165 0.87408 0.49187 0.00000 0.87067 0.44156 -0.03338 0.89661 0.41672 -0.06071 0.90701 0.45581 -0.00052 0.89008 0.35546 0.00009 0.93469 0.39201 0.00269 0.91996 0.36579 0.03912 0.92988 0.32273 -0.00904 0.94645 0.27243 -0.04836 0.96096 0.28001 -0.03619 0.95931 0.15621 0.02802 0.98733 0.09443 -0.04776 0.99439 0.00000 0.03384 0.99943 -0.09443 -0.04776 0.99439 -0.15621 0.02802 0.98733 -0.26840 -0.03007 0.96284 -0.37465 -0.15667 0.91383 -0.28017 -0.01406 0.95985 -0.37413 0.00250 0.92737 -0.48356 0.00000 0.87531 -0.47159 0.00881 0.88178 -0.42806 -0.01025 0.90369 -0.48964 -0.00150 0.87192 -0.45567 -0.02415 0.88982 -0.53890 0.00034 0.84237 -0.65575 -0.02015 0.75471 -0.61483 -0.00378 0.78865 -0.69506 0.00038 0.71895 -0.72738 -0.00008 0.68623 -0.72632 0.00000 0.68736 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.32754 0.00000 0.94484 -0.32751 0.00000 0.94485 -0.07959 -0.00001 0.99683 -0.07951 0.00001 0.99683 0.17359 0.00000 0.98482 0.17362 0.00001 0.98481 0.41529 -0.00000 0.90969 0.41530 0.00000 0.90968 0.63033 -0.00000 0.77633 0.63035 0.00000 0.77631 0.80505 -0.00000 0.59321 0.80508 0.00001 0.59317 0.92832 -0.00001 0.37178 0.92836 0.00001 0.37168 0.99196 -0.00001 0.12652 0.99197 0.00000 0.12646 0.32753 0.00000 0.94484 0.32753 0.00000 0.94484 0.07960 0.00000 0.99683 0.07960 0.00000 0.99683 -0.17359 -0.00000 0.98482 -0.17359 -0.00000 0.98482 -0.41529 -0.00000 0.90969 -0.41529 -0.00000 0.90969 -0.63033 -0.00000 0.77633 -0.63033 -0.00000 0.77633 -0.80504 -0.00000 0.59322 -0.80504 0.00000 0.59322 -0.92832 0.00000 0.37178 -0.92832 0.00000 0.37178 -0.99196 0.00000 0.12652 -0.99196 0.00000 0.12652 0.32321 0.16200 0.93236 0.18103 0.32893 0.92684 0.18434 0.32970 0.92591 0.07846 0.16854 0.98257 -0.15946 0.39518 0.90466 -0.04530 0.93154 0.36081 -0.17459 0.86340 0.47335 -0.40055 0.26405 0.87740 -0.32374 0.35198 0.87823 -0.22261 0.92049 0.32116 -0.58008 0.39125 0.71444 -0.78058 0.24464 0.57519 -0.69428 0.36192 0.62209 -0.26047 0.93447 0.24272 -0.27070 0.93161 0.24255 -0.33498 0.92102 0.19879 -0.85626 0.38630 0.34292 -0.32376 0.94000 0.10764 -0.36406 0.92697 0.09047 -0.96697 0.22307 0.12333 -0.97547 0.19402 0.10399 -0.81428 0.54407 0.20232 -0.54726 0.81901 -0.17245 -0.19506 0.98057 0.02093 -0.32326 0.16107 0.93250 -0.07831 0.17886 0.98075 -0.18341 0.32860 0.92649 -0.18489 0.32841 0.92626 0.15933 0.39685 0.90395 0.38658 0.36535 0.84680 0.32857 0.30813 0.89280 0.03931 0.93091 0.36313 0.18145 0.86027 0.47645 0.22260 0.92050 0.32113 0.58023 0.39069 0.71463 0.26659 0.93124 0.24842 0.26641 0.93359 0.23965 0.74691 0.37310 0.55038 0.70825 0.30412 0.63709 0.33504 0.92099 0.19882 0.85639 0.38595 0.34298 0.35675 0.92664 0.11861 0.32228 0.94601 0.03457 0.19430 0.97682 -0.08982 0.55032 0.82362 0.13712 0.92467 0.30317 0.23039 0.81665 0.54566 -0.18796 0.97320 0.19359 0.12413 0.32737 0.03114 0.94438 0.07823 -0.18436 0.97974 0.02499 -0.11891 0.99259 -0.16666 -0.27979 0.94549 -0.19613 -0.27531 0.94114 -0.38267 -0.38845 0.83825 -0.61237 -0.23702 0.75421 -0.64667 -0.32967 0.68785 -0.10740 -0.93639 0.33412 -0.20876 -0.92388 0.32072 -0.29572 -0.89382 0.33709 -0.34529 -0.86546 0.36296 -0.32005 -0.92238 0.21629 -0.74145 -0.38955 0.54636 -0.34663 -0.92484 0.15657 -0.33624 -0.93771 0.08746 -0.29877 -0.95399 0.02541 -0.19458 -0.97825 -0.07183 -0.54907 -0.82173 0.15258 -0.90947 -0.20048 0.36424 -0.90216 -0.35109 0.25069 -0.81665 -0.54566 -0.18796 -0.97320 -0.19359 0.12413 0.55763 0.00000 0.83009 0.55763 0.00000 0.83009 0.11078 0.00000 0.99385 0.11078 0.00000 0.99385 -0.36118 0.00000 0.93250 -0.36118 0.00000 0.93250 -0.75130 0.00000 0.65997 -0.75130 0.00000 0.65997 -0.97127 -0.00000 0.23796 -0.97127 -0.00000 0.23796 -0.55763 0.00000 0.83009 -0.55763 0.00000 0.83009 -0.11087 -0.00000 0.99383 -0.11078 0.00000 0.99385 0.36114 -0.00000 0.93251 0.36118 0.00000 0.93250 0.75128 -0.00000 0.65998 0.75129 0.00000 0.65997 0.97128 0.00000 0.23793 0.97128 0.00000 0.23793 -0.52021 -0.25876 0.81390 -0.55629 -0.06917 0.82810 -0.57632 -0.14637 0.80401 -0.57290 -0.14179 0.80727 -0.50295 -0.10159 0.85832 -0.53494 -0.16968 0.82768 -0.36795 -0.46362 0.80602 -0.42242 -0.48537 0.76549 -0.28739 -0.53790 0.79251 -0.21087 -0.46595 0.85932 -0.10883 -0.19107 0.97553 0.04715 -0.24580 0.96817 -0.07666 -0.52074 0.85027 -0.31183 -0.70556 0.63636 0.03122 -0.83832 0.54428 0.21992 -0.66340 0.71522 0.34776 -0.26959 0.89799 0.50716 -0.68460 0.52355 0.65752 -0.32584 0.67933 0.00853 -0.93684 0.34965 -0.01764 -0.79254 0.60956 -0.19340 -0.85881 0.47439 -0.06005 -0.94361 0.32556 0.71448 -0.30917 0.62765 0.61605 -0.70539 0.35058 0.40619 -0.89006 0.20691 0.33853 -0.93969 0.04886 0.44467 -0.88743 0.12141 0.94101 -0.24772 0.23052 0.81543 -0.57879 -0.00930 0.95828 -0.24461 0.14786 0.11803 -0.96573 0.23118 0.47154 -0.01437 0.88173 0.41234 -0.30593 0.85813 0.29316 -0.70443 0.64640 0.14306 -0.95333 0.26588 0.33917 -0.38521 0.85824 0.13045 -0.90945 0.39482 0.07105 -0.94250 0.32658 0.05431 -0.75231 0.65657 0.20450 -0.37147 0.90564 0.03997 -0.73161 0.68055 0.01607 -0.98803 0.15344 -0.03998 -0.73156 0.68061 -0.01608 -0.98803 0.15344 -0.07105 -0.94249 0.32659 -0.13047 -0.90945 0.39482 -0.44245 -0.11689 0.88914 -0.14198 -0.95001 0.27807 -0.13850 -0.95397 0.26603 -0.29317 -0.70441 0.64642 -0.45559 -0.25841 0.85186 0.55630 -0.06906 0.82810 0.54644 -0.07521 0.83412 0.57602 -0.13818 0.80567 0.49186 -0.30734 0.81463 0.53316 -0.23207 0.81356 0.52427 -0.22855 0.82031 0.49192 -0.26575 0.82909 0.48669 -0.26087 0.83372 0.22611 -0.43020 0.87395 0.11924 -0.19633 0.97326 0.10861 -0.19695 0.97438 0.29526 -0.70457 0.64529 0.36092 -0.63712 0.68104 0.26070 -0.59799 0.75792 0.00840 -0.57544 0.81780 0.13169 -0.69253 0.70927 -0.28897 -0.27361 0.91741 -0.13707 -0.62234 0.77065 -0.34751 -0.27251 0.89720 0.00035 -0.95410 0.29950 -0.06955 -0.83809 0.54107 0.11954 -0.91012 0.39673 -0.37961 -0.70148 0.60317 -0.20138 -0.87331 0.44359 -0.64729 -0.30492 0.69859 -0.48193 -0.69947 0.52772 -0.21391 -0.97644 -0.02847 -0.43222 -0.89152 0.13554 -0.71877 -0.29106 0.63139 -0.69107 -0.67926 0.24704 -0.45140 -0.88525 0.11212 -0.93651 -0.26515 0.22944 -0.92389 -0.26237 0.27854 -0.77550 -0.62094 0.11413 0.08395 -0.47203 0.87758 0.07372 -0.31441 0.94642 0.03184 -0.71799 0.69533 0.05570 -0.91241 0.40547 0.06150 -0.89511 0.44158 0.06957 -0.98816 0.13674 0.01245 -0.91943 0.39305 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00001 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 1.00000 0.00000 -0.42738 -0.87288 0.23542 0.04408 -0.71860 0.69402 -0.04408 -0.71860 0.69402 0.19703 -0.32830 0.92380 -0.11481 -0.90555 0.40841 0.35313 -0.87256 0.33754 0.19738 -0.80199 0.56378 -0.18887 -0.67100 0.71700 -0.25280 -0.65011 0.71656 0.12602 -0.65340 0.74645 -0.21268 -0.29516 0.93147 -0.20427 -0.30071 0.93158 0.10398 -0.30023 0.94818 -0.00009 -0.18766 0.98223 0.26263 -0.12678 0.95653 0.27005 -0.13716 0.95303 -0.27031 -0.13753 0.95290 -0.26263 -0.12678 0.95653 0.00009 -0.18766 0.98223 -0.10398 -0.30023 0.94818 0.20427 -0.30071 0.93158 0.21268 -0.29516 0.93147 -0.12602 -0.65340 0.74645 0.25280 -0.65011 0.71656 0.18886 -0.67101 0.71700 -0.19738 -0.80199 0.56378 -0.35313 -0.87256 0.33754 0.11481 -0.90555 0.40841 -0.19708 -0.32748 0.92408 -0.01244 -0.91943 0.39306 -0.06952 -0.98816 0.13674 -0.06146 -0.89511 0.44158 -0.05567 -0.91241 0.40548 -0.03182 -0.71799 0.69533 -0.07368 -0.31433 0.94645 -0.08391 -0.47203 0.87758 -0.20462 -0.37093 0.90584 -0.05430 -0.75226 0.65663 -0.33959 -0.38433 0.85847 0.97321 -0.19359 0.12407 0.81663 -0.54564 -0.18814 0.90235 -0.34994 0.25159 0.90949 -0.20060 0.36413 0.54902 -0.82167 0.15308 0.19458 -0.97827 -0.07165 0.29844 -0.95409 0.02538 0.33637 -0.93759 0.08825 0.34663 -0.92484 0.15657 0.74181 -0.38858 0.54656 0.32005 -0.92238 0.21629 0.34529 -0.86546 0.36296 0.29572 -0.89382 0.33709 0.20876 -0.92388 0.32072 0.10740 -0.93639 0.33412 0.64689 -0.32874 0.68808 0.61253 -0.23614 0.75435 0.38277 -0.38794 0.83844 0.19602 -0.27496 0.94126 0.16670 -0.27948 0.94557 -0.02495 -0.11903 0.99258 -0.07815 -0.18469 0.97969 -0.32737 0.02958 0.94443 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.36609 0.03957 0.92974 -0.39238 0.00309 0.91980 -0.42782 -0.00097 0.90386 -0.00000 -1.00000 -0.00000 -0.71754 0.00259 0.69651 -0.69992 0.00000 0.71422 0.00000 -1.00000 -0.00000 -0.99976 -0.02028 0.00805 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.10509 0.99359 0.04164 0.00929 0.99894 0.04516 -0.07536 0.99534 -0.06010 0.04501 0.99834 -0.03589 -0.07724 0.99529 -0.05855 0.04527 0.99839 -0.03432 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 1.00000 -0.00012 0.00000 -1.00000 -0.00000 -0.00000 -0.54306 0.83970 0.00048 -0.82645 0.56302 0.00033 -0.98019 0.19804 -0.00000 -0.98037 0.19532 0.02686 -0.00000 1.00000 0.00000 0.48299 0.87548 -0.01569 0.55273 0.83336 -0.00014 0.82644 0.56303 0.00033 0.98001 0.19893 0.00016 0.96592 -0.25883 0.00000 0.70708 -0.70711 0.00483 0.25880 -0.96592 0.00361 -0.25882 -0.96593 0.00000 -0.70710 -0.70710 0.00482 -0.96592 -0.25882 0.00361 -0.53936 0.83398 0.11644 -0.82630 0.56292 -0.01869 -0.85101 0.52047 0.06986 -0.98282 0.18451 -0.00432 0.60483 0.79116 0.09083 0.82630 0.56293 -0.01869 0.85102 0.52047 0.06989 0.98001 0.19893 -0.00121 -0.38262 0.92383 0.01196 -0.60549 0.79206 -0.07758 -0.98242 0.18314 0.03619 -0.84345 0.53137 -0.07891 -0.92041 0.38133 -0.08618 -0.35111 0.93446 0.05920 -0.76713 0.42467 0.48080 -0.30856 0.92342 0.22822 -0.35232 0.90945 0.22082 -0.76827 0.39353 0.50487 -0.16692 0.92772 0.33388 -0.29491 0.41328 0.86153 -0.30269 0.40242 0.86397 -0.13896 0.90740 0.39664 0.00252 0.93496 0.35476 0.29636 0.40326 0.86577 0.30099 0.41388 0.85913 0.13929 0.90693 0.39758 0.17035 0.92863 0.32957 0.76827 0.39353 0.50487 0.34948 0.90266 0.25115 0.33482 0.91862 0.20985 0.76713 0.42468 0.48080 0.35274 0.93400 0.05682 0.92048 0.38348 -0.07524 0.61356 0.78087 0.11745 0.43570 0.89716 -0.07251 0.98234 0.18357 0.03605 0.84345 0.53137 -0.07891 0.60508 0.79038 0.09581 0.47838 0.87812 -0.00723 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.99963 0.00036 0.02738 0.99781 -0.00006 -0.06621 -0.83570 0.00000 0.54918 -0.32386 0.00000 0.94611 0.32386 0.00000 0.94611 0.83570 0.00000 0.54918 -0.99746 0.00249 -0.07125 -0.96449 -0.25844 -0.05450 -0.69956 -0.69956 0.14576 -0.62355 -0.66579 0.40977 -0.20849 -0.76523 0.60906 0.00000 -0.84500 0.53476 0.20849 -0.76523 0.60906 0.62356 -0.66578 0.40977 0.96449 -0.25845 -0.05450 0.69954 -0.69957 0.14577 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.18722 0.98232 -0.00049 -0.67985 -0.71506 0.16276 -0.25882 -0.96593 -0.00000 0.25881 -0.96593 0.00000 0.67986 -0.71506 0.16275 0.68062 -0.46742 0.56416 0.68415 -0.46919 0.55840 0.00000 -1.00000 0.00000 -0.06980 0.99114 -0.11304 -0.17002 0.98539 0.00995 0.49377 -0.55480 0.66962 -0.88917 -0.28233 0.36009 -0.06967 0.99117 -0.11285 -0.04752 0.99190 -0.11780 0.82964 0.00000 0.55830 1.00000 0.00000 -0.00005 0.00000 -1.00000 0.00000 -1.00000 0.00000 -0.00000 -0.55558 0.83146 -0.00032 -0.83148 0.55556 -0.00016 -0.98079 0.19508 0.00017 0.19509 0.98078 0.00289 0.55557 0.83147 -0.00032 0.83147 0.55556 -0.00016 0.98078 0.19510 -0.00005 0.98077 -0.19509 0.00479 0.83147 -0.55556 -0.00242 0.55557 -0.83147 -0.00242 0.19509 -0.98079 0.00000 -0.19508 -0.98078 0.00479 -0.55557 -0.83147 -0.00242 -0.83147 -0.55556 -0.00242 -0.98078 -0.19510 -0.00000 0.00000 1.00000 -0.00000 -0.19510 0.98078 0.00000 -0.43988 0.89769 0.02576 -0.34308 0.92963 -0.13449 -0.12092 0.98996 -0.07325 -0.95319 0.20321 0.22390 -0.94734 0.29117 0.13333 0.19183 -0.86302 0.46733 -0.12591 -0.54799 0.82696 -0.18247 -0.69032 0.70011 -0.26953 -0.73824 0.61835 -0.04401 -0.78448 0.61859 0.34486 -0.87107 0.34972 -0.24901 -0.62075 0.74341 -0.53274 -0.67686 0.50798 -0.48660 -0.68587 0.54112 -0.96437 -0.18410 0.18999 -0.93933 -0.22939 0.25503 -0.97446 0.20974 0.08024 -0.94177 -0.11888 0.31453 -0.47203 -0.51597 0.71482 -0.55303 -0.49987 0.66655 -0.10705 -0.93718 0.33202 -0.08363 -0.97549 0.20352 -0.95619 0.27850 0.09024 0.81839 -0.55913 0.13266 0.26412 -0.93844 0.22266 0.30832 -0.92941 0.20283 0.33334 -0.92709 0.17144 0.34274 -0.93162 0.12091 0.41584 -0.90391 0.10015 -0.02010 -0.99838 0.05318 -0.24651 0.96821 -0.04246 -0.23261 0.97250 -0.01137 -0.22382 0.97307 -0.05512 -0.20008 0.97978 0.00241 -0.17979 0.98145 -0.06663 -0.16469 0.98610 -0.02191 -0.13756 0.98718 -0.08098 -0.13938 0.98610 -0.09040 -0.09303 0.99148 -0.09122 -0.13224 0.95122 0.27873 -0.19139 0.93845 0.28755 -0.24237 0.95494 0.17133 -0.17039 0.96122 0.21683 -0.17097 0.96166 0.21443 -0.21448 0.96105 0.17429 -0.21468 0.96201 0.16868 -0.24705 0.96088 0.12517 -0.24567 0.96264 0.11392 -0.26771 0.96062 0.07445 -0.26316 0.96324 0.05398 -0.27671 0.96062 0.02545 -0.26889 0.96314 -0.00790 -0.25541 0.96660 0.02136 -0.06977 0.99156 -0.10925 -0.34004 -0.62630 0.70151 -0.22351 -0.51770 0.82585 -0.27643 0.32168 0.90560 -0.64544 -0.57069 0.50765 -0.64371 -0.57432 0.50576 -0.84009 0.26126 0.47539 -0.67980 0.64530 0.34853 -0.88395 0.08802 0.45922 -0.81415 0.32643 0.48022 -0.75746 0.39637 0.51879 -0.53143 -0.56199 0.63384 -0.49642 -0.67440 0.54659 -0.69343 0.32814 0.64147 -0.69764 0.31529 0.64334 -0.45269 -0.63929 0.62159 -0.59420 0.42165 0.68494 -0.49637 0.36672 0.78685 -0.55151 0.19113 0.81197 -0.40384 0.44398 0.79987 -0.41725 -0.54080 0.73037 -0.41201 -0.60635 0.68013 -0.70425 -0.60281 0.37504 -0.55089 -0.70644 0.44438 -0.94004 -0.14711 0.30770 -0.95386 0.19678 0.22680 -0.77616 0.60749 0.16894 -0.89673 0.40568 0.17691 0.33004 -0.80724 0.48932 -0.20020 -0.56807 0.79826 -0.19713 -0.77268 0.60342 -0.56010 -0.42940 0.70845 -0.77051 -0.59690 0.22367 -0.89494 -0.39111 0.21477 -0.86902 -0.31567 0.38100 0.40409 -0.56439 0.71984 0.33802 -0.85130 0.40128 0.52007 -0.78742 0.33089 0.14974 -0.78142 0.60577 -0.67308 -0.65371 0.34586 -0.79487 -0.52330 0.30714 -0.99167 0.12432 -0.03377 -0.95469 0.29624 0.02855 -0.93386 0.35289 -0.05809 -0.97012 0.22324 -0.09504 -0.84663 0.52862 -0.06145 -0.77982 0.62569 -0.01958 -0.79797 0.60051 -0.05130 -0.76800 0.64031 -0.01382 -0.80117 0.58934 -0.10394 -0.76278 0.64443 -0.05371 -0.72711 0.68601 0.02658 -0.71869 0.69533 -0.00068 -0.67621 0.73321 0.07167 -0.19381 -0.87163 0.45022 -0.33486 -0.67114 0.66139 -0.14411 -0.93969 0.31018 -0.14454 -0.93969 0.30998 -0.14979 -0.93929 0.30872 -0.14920 -0.93781 0.31344 -0.14857 -0.93762 0.31432 -0.10649 -0.94309 0.31503 -0.16500 -0.93292 0.32005 -0.17354 -0.93264 0.31632 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.14311 -0.93869 0.31366 -0.59996 0.78186 -0.16950 -0.35862 0.93029 -0.07715 -0.34160 0.93060 -0.13153 -0.47585 0.87781 -0.05491 -0.33781 0.94059 0.03414 -0.37058 0.92880 -0.00100 -0.26948 0.95916 -0.08594 -0.15144 0.98776 0.03735 -0.99876 0.02243 0.04443 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -0.00118 -1.00000 -0.00104 0.66897 -0.71791 0.19257 0.71366 -0.64579 0.27138 0.67462 -0.65154 0.34697 0.64887 -0.62988 0.42687 0.64815 -0.62666 0.43267 0.58226 -0.64810 0.49086 0.68055 -0.57907 0.44891 -0.55875 0.82932 -0.00524 -0.63044 0.77342 -0.06608 -0.62318 0.78201 -0.01035 -0.62355 0.78160 -0.01687 -0.58167 0.81243 0.04018 -0.58190 0.81149 0.05352 -0.56600 0.82049 0.08020 -0.58204 0.81255 0.03148 -0.57725 0.80842 0.11502 -0.54375 0.82551 0.15123 -0.54121 0.82067 0.18326 -0.48460 0.83957 0.24552 -0.51069 0.82749 0.23336 -0.47380 0.81601 0.33111 -0.40437 0.85353 0.32861 -0.39689 0.83488 0.38139 -0.32067 0.85478 0.40807 -0.33028 0.84813 0.41424 -0.25945 0.82685 0.49900 -0.21680 0.86266 0.45697 0.00024 -1.00000 -0.00003 -0.00108 -0.99981 0.01924 -0.26638 -0.92815 0.25995 -0.22267 -0.92832 0.29771 0.09301 0.99148 -0.09123 0.13937 0.98611 -0.09039 0.13755 0.98718 -0.08100 0.14941 0.98722 -0.05538 0.06820 0.99154 -0.11046 0.07177 0.99107 -0.11238 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00095 1.00000 -0.00028 -0.00857 -0.99996 0.00185 -0.00805 -0.99996 0.00252 -0.00745 -0.99997 0.00317 -0.00678 -0.99997 0.00381 -0.00601 -0.99997 0.00443 -0.00514 -0.99997 0.00502 -0.00415 -0.99998 0.00554 -0.00302 -0.99998 0.00598 0.32528 0.86091 0.39118 0.33532 0.84040 0.42579 0.23285 0.86496 0.44455 0.25027 0.81275 0.52612 0.17651 0.83818 0.51604 0.10816 0.84369 0.52582 0.11187 0.86176 0.49483 0.00028 0.83866 0.54466 -0.00914 -0.99996 0.00102 -0.00630 -0.99996 0.00607 0.10399 -0.94352 0.31456 0.07081 -0.93620 0.34427 -0.00555 -0.95073 0.30998 0.04525 -0.90484 0.42333 0.25684 -0.87163 0.41749 0.14454 -0.93969 0.30997 0.12737 -0.94154 0.31190 0.18908 -0.91839 0.34758 0.30400 0.34310 0.88875 0.28039 0.27889 0.91848 0.15528 -0.63718 0.75491 0.25235 -0.50582 0.82490 0.18035 0.44574 0.87681 0.02349 0.38357 0.92321 0.00000 -0.58193 0.81324 0.43016 -0.54482 0.71982 0.39039 -0.60766 0.69162 0.53245 0.40400 0.74383 0.44473 0.03813 0.89485 0.46219 0.52024 0.71814 0.29459 -0.64015 0.70952 0.00016 0.94744 0.31993 0.16382 0.95459 0.24886 0.13733 0.94752 0.28870 0.24194 0.95510 0.17103 0.17056 0.96125 0.21658 0.17105 0.96162 0.21453 0.21458 0.96108 0.17403 0.21475 0.96198 0.16875 0.05806 -0.98803 0.14291 0.06866 -0.98340 0.16795 0.03296 0.95258 0.30251 0.07028 0.94785 0.31086 0.09366 0.95264 0.28931 0.09772 -0.92104 0.37701 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.04460 0.99084 -0.12748 -0.02095 0.99228 -0.12226 0.02095 0.99228 -0.12226 0.04459 0.99084 -0.12749 0.04752 0.99190 -0.11780 -0.16727 -0.92856 0.33134 -0.21990 -0.92662 0.30498 -0.03234 0.95249 0.30284 -0.07020 0.94747 0.31203 -0.09560 0.95246 0.28927 -0.23218 -0.60875 0.75863 -0.28734 0.29394 0.91161 -0.13161 0.46089 0.87765 -0.01399 -0.62331 0.78185 0.00000 0.31657 0.94857 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00095 1.00000 -0.00028 -0.10506 -0.94256 0.31707 -0.09281 -0.93476 0.34293 -0.03535 -0.94307 0.33071 -0.16823 0.82874 0.53374 -0.13217 0.79839 0.58746 -0.06546 0.89730 0.43655 0.01264 0.86767 0.49698 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.04880 -0.99862 0.01922 0.52498 -0.65553 0.54284 0.12791 -0.61484 0.77821 -0.80301 -0.20094 0.56106 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 -0.00003 1.00000 -0.00002 0.00016 1.00000 0.00004 0.00048 1.00000 0.00009 0.00007 1.00000 -0.00000 0.00005 1.00000 -0.00001 -0.00125 1.00000 -0.00035 -0.00002 1.00000 0.00015 -0.00005 1.00000 0.00015 -0.00010 1.00000 0.00017 -0.00013 1.00000 0.00018 0.00003 1.00000 -0.00004 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00003 0.00002 1.00000 -0.00001 0.00001 1.00000 -0.00002 0.00001 1.00000 -0.00002 0.00001 1.00000 -0.00002 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00033 -1.00000 0.00019 -0.00003 -1.00000 -0.00020 0.00014 1.00000 -0.00008 0.00022 1.00000 -0.00020 -0.00000 1.00000 -0.00000 0.00006 1.00000 0.00010 0.00014 1.00000 0.00007 -0.00111 1.00000 0.00020 -0.00001 1.00000 -0.00002 -0.00001 1.00000 -0.00002 -0.00001 1.00000 -0.00000 -0.00001 1.00000 0.00001 -0.00001 1.00000 0.00001 0.11197 0.99371 0.00002 0.11183 0.99373 0.00001 0.00036 1.00000 0.00014 0.00000 1.00000 0.00004 0.00039 1.00000 0.00007 -0.00000 1.00000 0.00000 0.00002 1.00000 -0.00001 0.00000 1.00000 0.00000 0.00002 1.00000 -0.00001 0.00001 1.00000 -0.00003 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00045 1.00000 0.00096 0.00002 1.00000 -0.00001 0.00002 1.00000 -0.00001 -0.00080 1.00000 -0.00003 0.00109 1.00000 -0.00155 0.00002 1.00000 -0.00002 0.82964 0.00000 0.55829 -0.89803 -0.26163 0.35369 -0.94949 -0.12100 0.28953 -0.89803 -0.26163 0.35369 -0.94949 -0.12100 0.28953 -0.89803 -0.26163 0.35369 -0.94949 -0.12100 0.28953 -0.06815 -0.99654 0.04757 -0.11101 -0.99121 0.07193 -0.19831 -0.96996 0.14092 -0.29127 -0.93518 0.20149 -0.32658 -0.91668 0.23030 -0.42782 -0.85344 0.29767 -0.43690 -0.84608 0.30539 -0.58019 -0.70719 0.40405 -0.55800 -0.73729 0.38084 -0.68996 -0.53189 0.49096 -0.65099 -0.61356 0.44693 -0.75143 -0.38997 0.53224 -0.73489 -0.44614 0.51078 -0.79398 -0.23807 0.55939 -0.78836 -0.27505 0.55030 -0.81581 -0.08006 0.57275 -0.81562 -0.09275 0.57110 -0.81653 0.08001 0.57174 -0.81080 0.12334 0.57218 -0.79656 0.23801 0.55573 -0.77388 0.32427 0.54402 -0.00001 0.00047 -1.00000 -0.00004 0.00044 -1.00000 0.41887 0.00354 -0.90804 0.21259 -0.01145 -0.97707 0.86681 -0.00625 -0.49861 0.91896 0.00044 -0.39434 0.90148 0.00570 -0.43278 -0.91973 -0.00050 -0.39256 -0.99885 -0.03722 -0.03036 -0.99550 -0.04019 0.08580 0.05326 -0.00009 -0.99858 -0.40106 -0.05433 -0.91444 0.01735 0.01334 -0.99976 0.00924 0.01646 -0.99982 -0.00124 -0.00227 -1.00000 0.01311 0.00163 -0.99991 0.42678 0.01192 -0.90428 0.67196 0.04613 -0.73915 0.94064 -0.00032 -0.33939 -0.32138 0.03814 -0.94618 -0.40721 -0.01937 -0.91313 -0.00770 -0.04993 -0.99872 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.01046 0.99992 0.00670 -0.00053 1.00000 0.00160 -0.00018 1.00000 0.00167 0.00018 1.00000 0.00167 0.00052 1.00000 0.00160 -0.01046 0.99992 0.00670 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.03620 -0.94022 0.33864 0.10266 -0.94500 0.31053 0.11094 -0.94337 0.31263 0.12277 -0.94865 0.29153 -0.03620 -0.94022 0.33864 -0.10286 -0.94501 0.31044 -0.12261 -0.94859 0.29180 -0.11094 -0.94337 0.31265 -0.11094 -0.94337 0.31265 -0.12261 -0.94859 0.29179 -0.10286 -0.94501 0.31044 -0.03620 -0.94022 0.33864 0.12277 -0.94865 0.29153 0.11094 -0.94337 0.31263 0.10266 -0.94500 0.31053 0.03620 -0.94022 0.33864 -0.14454 -0.93969 0.30998 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.01046 0.99992 0.00670 0.00052 1.00000 0.00160 0.00018 1.00000 0.00167 -0.00018 1.00000 0.00167 -0.00053 1.00000 0.00160 0.01046 0.99992 0.00670 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 0.01046 0.99992 0.00670 -0.00053 1.00000 0.00160 -0.00018 1.00000 0.00167 0.00018 1.00000 0.00167 0.00052 1.00000 0.00160 -0.01046 0.99992 0.00670 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.11094 -0.94337 0.31265 -0.12261 -0.94859 0.29179 -0.10286 -0.94501 0.31044 -0.03620 -0.94022 0.33864 0.12277 -0.94865 0.29153 0.11094 -0.94337 0.31263 0.10266 -0.94500 0.31053 0.03620 -0.94022 0.33864 0.14454 -0.93969 0.30998 -0.12148 -0.93608 0.33013 -0.14454 -0.93969 0.30998 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 + + + + + + + + + + + + + + +

119 0 50 0 104 0 50 1 21 1 104 1 50 2 119 2 1172 2 119 3 111 3 1172 3 70 4 78 4 59 4 496 5 497 5 61 5 12 6 1 6 2 6 12 7 11 7 1 7 39 8 8 8 7 8 38 9 8 9 39 9 15 10 19 10 468 10 468 11 517 11 15 11 13 12 15 12 517 12 517 13 516 13 13 13 498 14 13 14 516 14 52 15 8 15 38 15 52 16 0 16 8 16 0 17 7 17 8 17 2 18 0 18 52 18 52 19 54 19 2 19 54 20 47 20 2 20 16 21 2 21 47 21 47 22 46 22 16 22 9 23 500 23 527 23 520 24 3 24 527 24 1 25 527 25 4 25 527 26 3 26 4 26 527 27 1 27 9 27 1 28 10 28 9 28 11 29 10 29 1 29 4 30 5 30 1 30 1 31 0 31 2 31 7 32 0 32 1 32 1 33 6 33 7 33 1 34 5 34 6 34 2 35 14 35 12 35 14 36 2 36 16 36 46 37 18 37 16 37 467 38 520 38 521 38 467 39 3 39 520 39 467 40 4 40 3 40 467 41 5 41 4 41 467 42 6 42 5 42 467 43 7 43 6 43 7 44 467 44 39 44 500 45 9 45 499 45 498 46 499 46 9 46 9 47 10 47 498 47 13 48 498 48 11 48 498 49 10 49 11 49 11 50 12 50 13 50 15 51 13 51 14 51 13 52 12 52 14 52 14 53 16 53 15 53 19 54 15 54 16 54 16 55 18 55 19 55 18 56 17 56 66 56 19 57 18 57 66 57 21 58 22 58 496 58 61 59 21 59 496 59 23 60 22 60 21 60 24 61 23 61 21 61 25 62 24 62 21 62 25 63 21 63 26 63 62 64 27 64 28 64 62 65 28 65 29 65 62 66 29 66 1172 66 62 67 30 67 27 67 31 68 27 68 30 68 69 69 70 69 59 69 69 70 59 70 481 70 69 71 481 71 480 71 35 72 69 72 480 72 68 73 69 73 35 73 35 74 36 74 68 74 35 75 480 75 37 75 36 76 35 76 37 76 67 77 68 77 36 77 66 78 67 78 36 78 36 79 20 79 66 79 66 80 20 80 19 80 40 81 38 81 39 81 39 82 41 82 40 82 41 83 42 83 40 83 30 84 62 84 43 84 43 85 64 85 65 85 43 86 65 86 17 86 44 87 43 87 17 87 18 88 46 88 44 88 17 89 18 89 44 89 48 90 31 90 34 90 49 91 31 91 48 91 1172 92 29 92 50 92 50 93 49 93 21 93 50 94 29 94 28 94 50 95 28 95 27 95 50 96 27 96 49 96 31 97 49 97 27 97 21 98 49 98 26 98 36 99 472 99 473 99 36 100 473 100 20 100 471 101 472 101 36 101 36 102 37 102 471 102 471 103 37 103 480 103 468 104 19 104 20 104 468 105 20 105 473 105 497 106 496 106 492 106 496 107 22 107 491 107 490 108 491 108 22 108 22 109 23 109 490 109 489 110 490 110 23 110 23 111 24 111 489 111 488 112 489 112 24 112 24 113 25 113 488 113 487 114 488 114 25 114 63 115 64 115 43 115 26 116 51 116 58 116 26 117 55 117 51 117 56 118 51 118 55 118 42 119 51 119 56 119 42 120 41 120 51 120 41 121 39 121 51 121 467 122 51 122 39 122 484 123 51 123 467 123 485 124 51 124 484 124 486 125 51 125 485 125 58 126 51 126 486 126 42 127 56 127 40 127 40 128 52 128 38 128 40 129 54 129 52 129 40 130 53 130 54 130 47 131 54 131 53 131 44 132 47 132 53 132 45 133 44 133 53 133 45 134 53 134 32 134 56 135 53 135 40 135 56 136 32 136 53 136 486 137 25 137 58 137 45 138 32 138 33 138 25 139 486 139 487 139 48 140 56 140 55 140 55 141 26 141 48 141 48 142 26 142 49 142 56 143 48 143 32 143 48 144 34 144 32 144 43 145 44 145 45 145 43 146 45 146 33 146 43 147 33 147 32 147 43 148 32 148 57 148 57 149 32 149 34 149 31 150 57 150 34 150 58 151 25 151 26 151 44 152 46 152 47 152 30 153 57 153 31 153 30 154 43 154 57 154 63 155 43 155 62 155 79 156 80 156 81 156 79 157 81 157 82 157 83 158 79 158 82 158 84 159 80 159 79 159 79 160 85 160 84 160 84 161 85 161 86 161 374 162 84 162 86 162 374 163 375 163 84 163 86 164 87 164 374 164 376 165 374 165 87 165 88 166 376 166 87 166 88 167 378 167 388 167 376 168 88 168 388 168 92 169 90 169 91 169 93 170 91 170 90 170 90 171 94 171 93 171 531 172 93 172 94 172 94 173 95 173 531 173 497 174 531 174 95 174 97 175 96 175 61 175 61 176 95 176 97 176 95 177 61 177 497 177 98 178 99 178 100 178 96 179 98 179 100 179 96 180 100 180 101 180 96 181 101 181 102 181 96 182 102 182 103 182 104 183 96 183 103 183 96 184 104 184 61 184 61 185 104 185 21 185 105 186 89 186 379 186 77 187 75 187 59 187 78 188 77 188 59 188 532 189 1176 189 383 189 1177 190 1176 190 532 190 532 191 533 191 1177 191 71 192 1177 192 533 192 533 193 112 193 71 193 72 194 71 194 112 194 534 195 73 195 72 195 112 196 534 196 72 196 74 197 73 197 534 197 534 198 479 198 74 198 74 199 479 199 481 199 74 200 481 200 59 200 75 201 74 201 59 201 1176 202 76 202 383 202 76 203 365 203 383 203 386 204 84 204 375 204 380 205 108 205 386 205 113 206 80 206 84 206 386 207 113 207 84 207 386 208 108 208 107 208 386 209 107 209 106 209 386 210 106 210 114 210 386 211 114 211 115 211 113 212 386 212 115 212 80 213 113 213 116 213 81 214 80 214 116 214 1171 215 121 215 117 215 1171 216 117 216 118 216 110 217 1171 217 118 217 121 218 1171 218 1170 218 119 219 121 219 1170 219 119 220 103 220 102 220 119 221 102 221 101 221 119 222 101 222 120 222 119 223 120 223 121 223 104 224 103 224 119 224 119 225 1170 225 111 225 112 226 533 226 478 226 534 227 112 227 478 227 93 228 483 228 91 228 494 229 483 229 93 229 93 230 531 230 494 230 92 231 91 231 60 231 105 232 378 232 88 232 105 233 88 233 87 233 379 234 378 234 105 234 81 235 132 235 133 235 82 236 81 236 133 236 133 237 134 237 82 237 82 238 134 238 135 238 83 239 82 239 135 239 135 240 134 240 136 240 137 241 135 241 136 241 136 242 138 242 137 242 138 243 139 243 140 243 141 244 140 244 139 244 137 245 138 245 140 245 137 246 140 246 142 246 137 247 142 247 143 247 137 248 143 248 144 248 145 249 137 249 144 249 144 250 146 250 145 250 147 251 141 251 139 251 139 252 148 252 147 252 145 253 146 253 149 253 145 254 149 254 150 254 151 255 145 255 150 255 150 256 152 256 151 256 153 257 151 257 152 257 152 258 154 258 153 258 155 259 153 259 154 259 154 260 156 260 155 260 155 261 156 261 157 261 155 262 157 262 158 262 159 263 155 263 158 263 158 264 160 264 159 264 163 265 164 265 162 265 161 266 163 266 162 266 159 267 160 267 164 267 164 268 163 268 165 268 165 269 159 269 164 269 163 270 166 270 165 270 165 271 166 271 167 271 168 272 165 272 167 272 167 273 169 273 100 273 100 274 169 274 170 274 101 275 100 275 170 275 152 276 150 276 154 276 156 277 154 277 150 277 150 278 171 278 156 278 172 279 156 279 171 279 171 280 173 280 172 280 174 281 172 281 173 281 173 282 175 282 174 282 176 283 174 283 175 283 175 284 177 284 176 284 178 285 176 285 177 285 177 286 389 286 178 286 287 287 178 287 389 287 179 288 181 288 180 288 182 289 180 289 181 289 181 290 183 290 182 290 184 291 182 291 183 291 183 292 185 292 184 292 184 293 185 293 186 293 187 294 184 294 186 294 186 295 391 295 187 295 316 296 187 296 391 296 164 297 188 297 162 297 189 298 162 298 188 298 188 299 190 299 189 299 191 300 189 300 190 300 190 301 192 301 191 301 193 302 191 302 192 302 192 303 194 303 193 303 195 304 193 304 194 304 194 305 196 305 195 305 197 306 195 306 196 306 196 307 198 307 197 307 199 308 197 308 198 308 198 309 200 309 199 309 201 310 199 310 200 310 200 311 390 311 201 311 314 312 201 312 390 312 140 313 202 313 142 313 203 314 142 314 202 314 202 315 204 315 203 315 205 316 203 316 204 316 204 317 206 317 205 317 207 318 205 318 206 318 206 319 208 319 207 319 209 320 207 320 208 320 208 321 210 321 209 321 211 322 209 322 210 322 210 323 212 323 211 323 213 324 211 324 212 324 212 325 214 325 213 325 215 326 213 326 214 326 214 327 392 327 215 327 321 328 215 328 392 328 203 329 143 329 142 329 205 330 146 330 144 330 205 331 144 331 143 331 203 332 205 332 143 332 205 333 207 333 146 333 216 334 150 334 149 334 216 335 149 335 146 335 146 336 207 336 209 336 216 337 146 337 209 337 171 338 150 338 216 338 209 339 211 339 216 339 216 340 211 340 213 340 217 341 216 341 213 341 217 342 173 342 171 342 216 343 217 343 171 343 175 344 173 344 217 344 213 345 215 345 217 345 324 346 177 346 175 346 217 347 324 347 175 347 217 348 215 348 321 348 217 349 321 349 393 349 324 350 217 350 393 350 177 351 324 351 322 351 389 352 177 352 322 352 164 353 160 353 188 353 190 354 188 354 160 354 160 355 158 355 190 355 190 356 158 356 218 356 192 357 190 357 218 357 219 358 194 358 192 358 218 359 219 359 192 359 157 360 156 360 219 360 219 361 218 361 157 361 156 362 172 362 219 362 196 363 194 363 219 363 219 364 172 364 174 364 220 365 219 365 174 365 220 366 198 366 196 366 219 367 220 367 196 367 174 368 176 368 220 368 200 369 198 369 220 369 220 370 176 370 178 370 178 371 287 371 220 371 220 372 287 372 328 372 330 373 220 373 328 373 220 374 330 374 200 374 200 375 330 375 332 375 390 376 200 376 332 376 140 377 221 377 202 377 204 378 202 378 221 378 221 379 222 379 204 379 206 380 204 380 222 380 222 381 223 381 206 381 208 382 206 382 223 382 224 383 210 383 208 383 223 384 224 384 208 384 225 385 180 385 224 385 226 386 225 386 224 386 227 387 226 387 224 387 224 388 223 388 227 388 180 389 182 389 224 389 212 390 210 390 224 390 224 391 182 391 184 391 224 392 184 392 187 392 224 393 187 393 316 393 224 394 316 394 395 394 338 395 224 395 395 395 338 396 214 396 212 396 224 397 338 397 212 397 214 398 338 398 340 398 392 399 214 399 340 399 81 400 116 400 132 400 228 401 132 401 116 401 116 402 113 402 228 402 229 403 228 403 113 403 113 404 115 404 229 404 230 405 229 405 115 405 115 406 114 406 230 406 231 407 230 407 114 407 114 408 106 408 231 408 1173 409 231 409 106 409 170 410 232 410 101 410 120 411 101 411 232 411 232 412 233 412 120 412 121 413 120 413 233 413 233 414 234 414 121 414 117 415 121 415 234 415 234 416 235 416 117 416 118 417 117 417 235 417 235 418 109 418 118 418 110 419 118 419 109 419 163 420 236 420 166 420 232 421 170 421 169 421 237 422 167 422 166 422 167 423 237 423 169 423 169 424 238 424 232 424 238 425 169 425 237 425 166 426 239 426 237 426 239 427 166 427 236 427 240 428 237 428 239 428 237 429 240 429 238 429 233 430 232 430 238 430 238 431 241 431 233 431 241 432 238 432 240 432 236 433 242 433 239 433 243 434 240 434 239 434 240 435 243 435 241 435 234 436 233 436 241 436 245 437 241 437 243 437 241 438 245 438 234 438 242 439 126 439 239 439 239 440 244 440 243 440 244 441 239 441 126 441 235 442 234 442 245 442 243 443 130 443 245 443 130 444 243 444 244 444 131 445 244 445 126 445 244 446 131 446 130 446 109 447 235 447 245 447 130 448 129 448 245 448 245 449 129 449 109 449 262 450 1168 450 246 450 247 451 139 451 138 451 247 452 138 452 255 452 246 453 247 453 255 453 247 454 246 454 1168 454 148 455 139 455 247 455 1168 456 122 456 247 456 248 457 247 457 122 457 248 458 249 458 250 458 250 459 148 459 247 459 251 460 248 460 122 460 122 461 123 461 251 461 124 462 252 462 251 462 123 463 124 463 251 463 253 464 252 464 124 464 124 465 125 465 253 465 253 466 236 466 161 466 253 467 125 467 126 467 253 468 126 468 242 468 236 469 253 469 242 469 163 470 161 470 236 470 132 471 228 471 133 471 254 472 133 472 228 472 133 473 254 473 134 473 255 474 138 474 136 474 136 475 256 475 255 475 256 476 136 476 134 476 134 477 257 477 256 477 257 478 134 478 254 478 254 479 258 479 257 479 258 480 254 480 228 480 228 481 229 481 258 481 246 482 255 482 256 482 256 483 259 483 246 483 259 484 256 484 257 484 260 485 257 485 258 485 257 486 260 486 259 486 261 487 258 487 229 487 258 488 261 488 260 488 229 489 230 489 261 489 262 490 246 490 259 490 263 491 259 491 260 491 259 492 263 492 262 492 264 493 260 493 261 493 260 494 264 494 263 494 265 495 261 495 230 495 261 496 265 496 264 496 1164 497 262 497 263 497 1164 498 263 498 264 498 230 499 231 499 265 499 128 500 264 500 265 500 264 501 128 501 1164 501 231 502 1173 502 265 502 127 503 265 503 1173 503 265 504 127 504 128 504 268 505 250 505 249 505 269 506 250 506 268 506 268 507 267 507 269 507 270 508 269 508 267 508 267 509 266 509 270 509 270 510 266 510 179 510 270 511 179 511 180 511 135 512 137 512 145 512 135 513 145 513 151 513 135 514 151 514 153 514 135 515 153 515 155 515 135 516 155 516 159 516 135 517 159 517 165 517 168 518 135 518 165 518 168 519 98 519 96 519 168 520 96 520 97 520 168 521 97 521 95 521 168 522 95 522 94 522 168 523 94 523 90 523 168 524 90 524 92 524 92 525 60 525 89 525 168 526 92 526 89 526 168 527 89 527 105 527 168 528 105 528 87 528 168 529 87 529 86 529 168 530 86 530 85 530 168 531 85 531 79 531 168 532 79 532 83 532 135 533 168 533 83 533 99 534 98 534 168 534 158 535 157 535 218 535 249 536 248 536 251 536 251 537 252 537 249 537 247 538 248 538 250 538 180 539 225 539 270 539 250 540 269 540 270 540 225 541 250 541 270 541 225 542 226 542 250 542 226 543 227 543 250 543 148 544 250 544 227 544 148 545 227 545 223 545 148 546 223 546 222 546 147 547 148 547 222 547 147 548 222 548 221 548 141 549 147 549 221 549 140 550 141 550 221 550 162 551 280 551 286 551 286 552 280 552 285 552 285 553 280 553 279 553 285 554 279 554 284 554 284 555 279 555 278 555 284 556 278 556 274 556 284 557 274 557 273 557 275 558 273 558 274 558 276 559 273 559 275 559 276 560 271 560 273 560 273 561 271 561 272 561 283 562 271 562 276 562 253 563 273 563 252 563 271 564 283 564 179 564 271 565 179 565 266 565 267 566 271 566 266 566 271 567 267 567 272 567 268 568 272 568 267 568 272 569 268 569 273 569 268 570 249 570 273 570 273 571 253 571 284 571 252 572 273 572 249 572 284 573 253 573 161 573 314 574 394 574 201 574 201 575 394 575 334 575 277 576 199 576 334 576 334 577 199 577 201 577 334 578 336 578 277 578 277 579 336 579 391 579 277 580 391 580 186 580 277 581 186 581 281 581 277 582 281 582 282 582 199 583 277 583 197 583 283 584 277 584 282 584 277 585 274 585 278 585 274 586 277 586 275 586 275 587 277 587 276 587 276 588 277 588 283 588 278 589 195 589 277 589 277 590 195 590 197 590 195 591 278 591 193 591 279 592 193 592 278 592 193 593 279 593 191 593 280 594 191 594 279 594 191 595 280 595 189 595 162 596 189 596 280 596 183 597 281 597 185 597 281 598 183 598 282 598 181 599 282 599 183 599 282 600 181 600 283 600 179 601 283 601 181 601 161 602 285 602 284 602 285 603 161 603 286 603 286 604 161 604 162 604 185 605 281 605 186 605 100 606 168 606 167 606 99 607 168 607 100 607 60 608 483 608 89 608 60 609 91 609 483 609 289 610 287 610 288 610 290 611 289 611 288 611 293 612 291 612 288 612 292 613 294 613 290 613 288 614 295 614 293 614 346 615 290 615 294 615 296 616 293 616 295 616 294 617 297 617 346 617 295 618 298 618 296 618 299 619 346 619 297 619 300 620 296 620 298 620 297 621 301 621 299 621 302 622 299 622 301 622 298 623 303 623 300 623 301 624 304 624 302 624 305 625 300 625 303 625 302 626 304 626 306 626 307 627 302 627 306 627 308 628 309 628 305 628 303 629 308 629 305 629 310 630 309 630 308 630 306 631 310 631 307 631 311 632 307 632 310 632 312 633 311 633 310 633 308 634 312 634 310 634 315 635 314 635 313 635 319 636 320 636 321 636 323 637 295 637 322 637 325 638 323 638 324 638 325 639 321 639 320 639 326 640 325 640 320 640 290 641 287 641 289 641 287 642 290 642 327 642 327 643 329 643 328 643 329 644 331 644 330 644 331 645 313 645 332 645 315 646 333 646 314 646 333 647 335 647 334 647 335 648 317 648 336 648 318 649 337 649 316 649 337 650 339 650 338 650 339 651 319 651 340 651 341 652 304 652 301 652 306 653 304 653 341 653 310 654 306 654 341 654 309 655 310 655 341 655 305 656 309 656 341 656 300 657 305 657 341 657 341 658 296 658 300 658 293 659 296 659 341 659 291 660 293 660 341 660 292 661 291 661 341 661 294 662 292 662 341 662 297 663 294 663 341 663 301 664 297 664 341 664 342 665 295 665 323 665 323 666 325 666 342 666 343 667 342 667 325 667 325 668 326 668 343 668 327 669 344 669 329 669 331 670 329 670 344 670 344 671 345 671 331 671 331 672 345 672 313 672 347 673 298 673 295 673 342 674 347 674 295 674 343 675 326 675 347 675 342 676 343 676 347 676 326 677 348 677 347 677 303 678 298 678 347 678 349 679 347 679 348 679 349 680 308 680 303 680 347 681 349 681 303 681 348 682 350 682 349 682 312 683 308 683 349 683 349 684 350 684 351 684 352 685 349 685 351 685 349 686 352 686 312 686 311 687 312 687 352 687 351 688 353 688 352 688 354 689 352 689 353 689 352 690 354 690 311 690 307 691 311 691 354 691 353 692 355 692 354 692 356 693 302 693 307 693 354 694 356 694 307 694 356 695 354 695 355 695 299 696 302 696 356 696 355 697 313 697 356 697 344 698 346 698 299 698 356 699 344 699 299 699 356 700 313 700 345 700 356 701 345 701 344 701 327 702 346 702 344 702 346 703 327 703 290 703 316 704 317 704 318 704 318 705 358 705 357 705 317 706 358 706 318 706 326 707 320 707 319 707 313 708 355 708 359 708 359 708 315 708 313 708 350 709 348 709 360 709 360 709 361 709 350 709 351 710 350 710 361 710 361 710 362 710 351 710 362 711 363 711 353 711 353 711 351 711 362 711 363 712 359 712 355 712 355 712 353 712 363 712 348 713 326 713 319 713 319 713 360 713 348 713 339 714 360 714 319 714 337 715 360 715 339 715 357 716 361 716 360 716 357 717 362 717 361 717 357 718 358 718 362 718 358 719 363 719 362 719 359 720 363 720 358 720 333 721 315 721 359 721 333 722 359 722 335 722 288 723 292 723 290 723 288 724 291 724 292 724 288 725 322 725 295 725 337 726 357 726 360 726 318 727 357 727 337 727 317 728 335 728 358 728 335 729 359 729 358 729 376 730 377 730 375 730 374 731 376 731 375 731 387 732 379 732 89 732 384 733 532 733 383 733 365 734 364 734 383 734 386 735 375 735 377 735 386 736 385 736 380 736 532 737 384 737 536 737 536 738 535 738 532 738 388 739 378 739 379 739 390 740 313 740 314 740 391 741 317 741 316 741 392 742 319 742 321 742 322 743 324 743 323 743 324 744 393 744 325 744 325 745 393 745 321 745 328 746 287 746 327 746 330 747 328 747 329 747 332 748 330 748 331 748 390 749 332 749 313 749 333 750 394 750 314 750 334 751 394 751 333 751 336 752 334 752 335 752 391 753 336 753 317 753 337 754 395 754 316 754 338 755 395 755 337 755 340 756 338 756 339 756 392 757 340 757 319 757 288 758 287 758 389 758 389 759 322 759 288 759 368 760 370 760 438 760 383 761 440 761 439 761 384 762 383 762 439 762 411 763 405 763 402 763 411 764 410 764 405 764 446 765 396 765 413 765 413 766 396 766 417 766 417 767 396 767 416 767 416 768 396 768 415 768 415 769 396 769 423 769 423 770 396 770 444 770 416 771 414 771 417 771 425 772 404 772 414 772 414 773 404 773 403 773 405 774 403 774 404 774 441 775 403 775 405 775 409 776 441 776 405 776 441 777 407 777 403 777 417 778 414 778 403 778 417 779 403 779 407 779 422 780 495 780 397 780 423 781 495 781 422 781 405 782 410 782 409 782 387 783 388 783 379 783 449 784 388 784 387 784 448 785 449 785 387 785 447 786 448 786 387 786 387 787 444 787 447 787 396 788 447 788 444 788 495 789 423 789 444 789 432 790 450 790 431 790 438 791 450 791 432 791 432 792 433 792 438 792 437 793 438 793 433 793 433 794 434 794 437 794 434 795 439 795 437 795 434 796 435 796 439 796 384 797 439 797 435 797 540 798 384 798 435 798 466 799 545 799 398 799 545 800 538 800 398 800 464 801 466 801 398 801 398 802 427 802 464 802 461 803 464 803 427 803 427 804 428 804 461 804 459 805 461 805 428 805 428 806 429 806 459 806 456 807 459 807 429 807 429 808 430 808 456 808 454 809 456 809 430 809 430 810 431 810 454 810 454 811 431 811 450 811 536 812 384 812 540 812 541 813 539 813 436 813 539 814 541 814 514 814 526 815 543 815 539 815 426 816 424 816 401 816 399 817 401 817 424 817 399 818 402 818 401 818 399 819 455 819 402 819 399 820 457 820 455 820 399 821 458 821 457 821 460 822 458 822 399 822 400 823 399 823 420 823 399 824 424 824 420 824 399 825 400 825 460 825 400 826 462 826 460 826 420 827 421 827 400 827 463 828 462 828 400 828 400 829 539 829 463 829 539 830 465 830 463 830 539 831 543 831 465 831 400 832 436 832 539 832 400 833 421 833 436 833 401 834 425 834 426 834 404 835 425 835 401 835 405 836 404 836 401 836 401 837 402 837 405 837 402 838 455 838 412 838 412 839 411 839 402 839 408 840 446 840 413 840 406 841 413 841 417 841 413 842 406 842 408 842 417 843 407 843 406 843 406 844 442 844 408 844 408 845 442 845 382 845 385 846 381 846 380 846 385 847 386 847 377 847 385 848 446 848 408 848 385 849 445 849 446 849 385 850 377 850 445 850 385 851 408 851 381 851 408 852 382 852 381 852 373 853 443 853 1174 853 372 854 1174 854 443 854 372 855 441 855 409 855 372 856 443 856 441 856 409 857 1175 857 372 857 409 858 371 858 1175 858 409 859 451 859 371 859 453 860 451 860 410 860 451 861 409 861 410 861 410 862 411 862 453 862 452 863 453 863 411 863 411 864 412 864 452 864 455 865 452 865 412 865 425 866 414 866 415 866 416 867 415 867 414 867 419 868 418 868 436 868 436 869 421 869 419 869 421 870 397 870 419 870 421 871 422 871 397 871 423 872 422 872 424 872 422 873 420 873 424 873 422 874 421 874 420 874 423 875 424 875 415 875 424 876 426 876 415 876 425 877 415 877 426 877 477 878 429 878 428 878 477 879 430 879 429 879 431 880 430 880 477 880 477 881 432 881 431 881 477 882 433 882 432 882 477 883 434 883 433 883 477 884 435 884 434 884 477 885 540 885 435 885 541 886 436 886 418 886 438 887 370 887 450 887 440 888 438 888 437 888 437 889 439 889 440 889 438 890 440 890 368 890 440 891 367 891 368 891 366 892 367 892 440 892 366 893 440 893 383 893 364 894 366 894 383 894 443 895 442 895 441 895 382 896 442 896 443 896 443 897 373 897 382 897 444 898 387 898 89 898 446 899 447 899 396 899 447 900 446 900 445 900 447 901 445 901 448 901 445 902 449 902 448 902 376 903 449 903 445 903 449 904 376 904 388 904 445 905 377 905 376 905 450 906 370 906 454 906 371 907 451 907 369 907 370 908 369 908 451 908 451 909 453 909 370 909 453 910 454 910 370 910 456 911 454 911 455 911 454 912 452 912 455 912 454 913 453 913 452 913 455 914 457 914 456 914 459 915 456 915 457 915 457 916 458 916 459 916 461 917 459 917 460 917 459 918 458 918 460 918 460 919 462 919 461 919 464 920 461 920 462 920 462 921 463 921 464 921 466 922 464 922 465 922 464 923 463 923 465 923 465 924 543 924 466 924 545 925 466 925 543 925 482 926 444 926 89 926 444 927 482 927 495 927 491 928 492 928 496 928 492 929 493 929 497 929 469 930 481 930 474 930 480 931 481 931 469 931 469 932 470 932 480 932 470 933 471 933 480 933 479 934 474 934 481 934 479 935 475 935 474 935 468 936 473 936 477 936 477 937 469 937 474 937 477 938 470 938 469 938 477 939 471 939 470 939 477 940 472 940 471 940 477 941 473 941 472 941 474 942 475 942 477 942 475 943 476 943 477 943 478 944 477 944 476 944 495 945 487 945 486 945 495 946 488 946 487 946 495 947 489 947 488 947 495 948 490 948 489 948 495 949 491 949 490 949 495 950 492 950 491 950 495 951 493 951 492 951 495 952 494 952 493 952 501 953 502 953 500 953 499 954 501 954 500 954 503 955 504 955 502 955 501 956 503 956 502 956 505 957 504 957 503 957 506 958 507 958 505 958 503 959 506 959 505 959 506 960 508 960 507 960 495 961 486 961 485 961 495 962 485 962 484 962 512 963 511 963 510 963 510 964 513 964 512 964 512 965 513 965 514 965 515 966 512 966 514 966 522 967 521 967 520 967 520 968 523 968 522 968 523 969 510 969 522 969 511 970 522 970 510 970 524 971 504 971 505 971 525 972 524 972 505 972 525 973 513 973 510 973 525 974 510 974 524 974 505 975 507 975 525 975 525 976 507 976 509 976 525 977 526 977 513 977 524 978 523 978 520 978 527 979 524 979 520 979 527 980 500 980 502 980 527 981 502 981 504 981 527 982 504 982 524 982 523 983 524 983 510 983 508 984 506 984 528 984 501 985 519 985 529 985 503 986 501 986 529 986 501 987 499 987 519 987 518 988 519 988 499 988 499 989 498 989 518 989 516 990 518 990 498 990 484 991 467 991 495 991 495 992 467 992 521 992 506 993 530 993 528 993 503 994 530 994 506 994 503 995 529 995 530 995 477 996 516 996 517 996 477 997 517 997 468 997 533 998 532 998 535 998 535 999 478 999 533 999 478 1000 476 1000 534 1000 479 1001 534 1001 476 1001 476 1002 475 1002 479 1002 493 1003 494 1003 531 1003 531 1004 497 1004 493 1004 528 1005 537 1005 508 1005 545 1006 508 1006 537 1006 538 1007 545 1007 537 1007 526 1008 539 1008 514 1008 526 1009 544 1009 543 1009 526 1010 509 1010 544 1010 526 1011 514 1011 513 1011 526 1012 525 1012 509 1012 536 1013 540 1013 477 1013 535 1014 536 1014 477 1014 477 1015 478 1015 535 1015 418 1016 542 1016 541 1016 514 1017 541 1017 542 1017 542 1018 515 1018 514 1018 544 1019 545 1019 543 1019 508 1020 545 1020 509 1020 545 1021 544 1021 509 1021 508 1022 509 1022 507 1022 482 1023 89 1023 483 1023 482 1024 483 1024 494 1024 482 1025 494 1025 495 1025 652 1026 594 1026 641 1026 594 1027 566 1027 641 1027 594 1028 652 1028 1197 1028 607 1029 615 1029 603 1029 1024 1030 1025 1030 605 1030 558 1031 547 1031 548 1031 558 1032 557 1032 547 1032 582 1033 554 1033 553 1033 581 1034 554 1034 582 1034 561 1035 564 1035 996 1035 996 1036 1044 1036 561 1036 559 1037 561 1037 1044 1037 1044 1038 3475 1038 559 1038 1026 1039 559 1039 3475 1039 596 1040 554 1040 581 1040 596 1041 546 1041 554 1041 546 1042 553 1042 554 1042 548 1043 546 1043 596 1043 596 1044 598 1044 548 1044 598 1045 590 1045 548 1045 562 1046 548 1046 590 1046 590 1047 589 1047 562 1047 555 1048 1028 1048 1053 1048 1046 1049 549 1049 1053 1049 547 1050 1053 1050 550 1050 1053 1051 549 1051 550 1051 1053 1052 547 1052 555 1052 547 1053 556 1053 555 1053 557 1054 556 1054 547 1054 550 1055 551 1055 547 1055 547 1056 546 1056 548 1056 553 1057 546 1057 547 1057 547 1058 552 1058 553 1058 547 1059 551 1059 552 1059 548 1060 560 1060 558 1060 560 1061 548 1061 562 1061 589 1062 563 1062 562 1062 995 1063 1046 1063 1047 1063 995 1064 549 1064 1046 1064 995 1065 550 1065 549 1065 995 1066 551 1066 550 1066 995 1067 552 1067 551 1067 995 1068 553 1068 552 1068 553 1069 995 1069 582 1069 1028 1070 555 1070 1027 1070 1026 1071 1027 1071 555 1071 555 1072 556 1072 1026 1072 559 1073 1026 1073 557 1073 1026 1074 556 1074 557 1074 557 1075 558 1075 559 1075 561 1076 559 1076 560 1076 559 1077 558 1077 560 1077 560 1078 562 1078 561 1078 564 1079 561 1079 562 1079 562 1080 563 1080 564 1080 563 1081 1209 1081 1210 1081 564 1082 563 1082 1210 1082 566 1083 567 1083 1024 1083 605 1084 566 1084 1024 1084 568 1085 567 1085 566 1085 569 1086 568 1086 566 1086 570 1087 569 1087 566 1087 570 1088 566 1088 571 1088 1205 1089 572 1089 573 1089 1205 1090 573 1090 574 1090 1205 1091 574 1091 1197 1091 1205 1092 575 1092 572 1092 576 1093 572 1093 575 1093 606 1094 607 1094 603 1094 606 1095 603 1095 1009 1095 606 1096 1009 1096 1008 1096 578 1097 606 1097 1008 1097 1212 1098 606 1098 578 1098 578 1099 579 1099 1212 1099 578 1100 1008 1100 580 1100 579 1101 578 1101 580 1101 1211 1102 1212 1102 579 1102 1210 1103 1211 1103 579 1103 579 1104 565 1104 1210 1104 1210 1105 565 1105 564 1105 583 1106 581 1106 582 1106 582 1107 584 1107 583 1107 584 1108 585 1108 583 1108 575 1109 1205 1109 586 1109 586 1110 1207 1110 1208 1110 586 1111 1208 1111 1209 1111 587 1112 586 1112 1209 1112 563 1113 589 1113 587 1113 1209 1114 563 1114 587 1114 591 1115 592 1115 576 1115 593 1116 576 1116 592 1116 1197 1117 574 1117 594 1117 594 1118 593 1118 566 1118 594 1119 574 1119 573 1119 594 1120 573 1120 572 1120 594 1121 572 1121 593 1121 576 1122 593 1122 572 1122 566 1123 593 1123 571 1123 579 1124 1000 1124 1001 1124 579 1125 1001 1125 565 1125 999 1126 1000 1126 579 1126 579 1127 580 1127 999 1127 999 1128 580 1128 1008 1128 996 1129 564 1129 565 1129 996 1130 565 1130 1001 1130 1025 1131 1024 1131 1020 1131 1024 1132 567 1132 1019 1132 1018 1133 1019 1133 567 1133 567 1134 568 1134 1018 1134 1017 1135 1018 1135 568 1135 568 1136 569 1136 1017 1136 1016 1137 1017 1137 569 1137 569 1138 570 1138 1016 1138 1015 1139 1016 1139 570 1139 1206 1140 1207 1140 586 1140 571 1141 595 1141 602 1141 571 1142 599 1142 595 1142 600 1143 595 1143 599 1143 585 1144 595 1144 600 1144 585 1145 584 1145 595 1145 584 1146 582 1146 595 1146 995 1147 595 1147 582 1147 1012 1148 595 1148 995 1148 1013 1149 595 1149 1012 1149 1014 1150 595 1150 1013 1150 602 1151 595 1151 1014 1151 585 1152 600 1152 583 1152 583 1153 596 1153 581 1153 583 1154 598 1154 596 1154 583 1155 597 1155 598 1155 590 1156 598 1156 597 1156 587 1157 590 1157 597 1157 588 1158 587 1158 597 1158 588 1159 597 1159 577 1159 600 1160 597 1160 583 1160 600 1161 577 1161 597 1161 1014 1162 570 1162 602 1162 570 1163 1014 1163 1015 1163 592 1164 600 1164 599 1164 599 1165 571 1165 592 1165 592 1166 571 1166 593 1166 600 1167 592 1167 577 1167 592 1168 591 1168 577 1168 586 1169 587 1169 588 1169 586 1170 588 1170 577 1170 586 1171 577 1171 601 1171 601 1172 577 1172 591 1172 601 1173 591 1173 576 1173 602 1174 570 1174 571 1174 587 1175 589 1175 590 1175 575 1176 601 1176 576 1176 575 1177 586 1177 601 1177 1206 1178 586 1178 1205 1178 616 1179 617 1179 618 1179 616 1180 618 1180 619 1180 620 1181 616 1181 619 1181 621 1182 617 1182 616 1182 616 1183 622 1183 621 1183 621 1184 622 1184 623 1184 903 1185 621 1185 623 1185 903 1186 904 1186 621 1186 623 1187 624 1187 903 1187 905 1188 903 1188 624 1188 625 1189 905 1189 624 1189 625 1190 907 1190 917 1190 905 1191 625 1191 917 1191 629 1192 627 1192 628 1192 630 1193 628 1193 627 1193 627 1194 631 1194 630 1194 1057 1195 630 1195 631 1195 631 1196 632 1196 1057 1196 1025 1197 1057 1197 632 1197 634 1198 633 1198 605 1198 605 1199 632 1199 634 1199 632 1200 605 1200 1025 1200 635 1201 636 1201 637 1201 633 1202 635 1202 637 1202 633 1203 637 1203 638 1203 633 1204 638 1204 639 1204 633 1205 639 1205 640 1205 641 1206 633 1206 640 1206 633 1207 641 1207 605 1207 605 1208 641 1208 566 1208 642 1209 626 1209 908 1209 614 1210 612 1210 603 1210 615 1211 614 1211 603 1211 1058 1212 1214 1212 912 1212 608 1213 1214 1213 1058 1213 1058 1214 1059 1214 608 1214 609 1215 608 1215 1059 1215 1059 1216 644 1216 609 1216 1215 1217 609 1217 644 1217 1060 1218 610 1218 1215 1218 644 1219 1060 1219 1215 1219 611 1220 610 1220 1060 1220 1060 1221 1007 1221 611 1221 611 1222 1007 1222 1009 1222 611 1223 1009 1223 603 1223 612 1224 611 1224 603 1224 1214 1225 613 1225 912 1225 613 1226 893 1226 912 1226 915 1227 621 1227 904 1227 909 1228 643 1228 915 1228 645 1229 617 1229 621 1229 915 1230 645 1230 621 1230 915 1231 643 1231 1202 1231 915 1232 1202 1232 1203 1232 915 1233 1203 1233 646 1233 915 1234 646 1234 647 1234 645 1235 915 1235 647 1235 617 1236 645 1236 648 1236 617 1237 648 1237 649 1237 618 1238 617 1238 649 1238 1199 1239 654 1239 650 1239 1199 1240 650 1240 651 1240 1200 1241 1199 1241 651 1241 654 1242 1199 1242 1198 1242 652 1243 654 1243 1198 1243 652 1244 640 1244 639 1244 652 1245 639 1245 638 1245 652 1246 638 1246 653 1246 652 1247 653 1247 654 1247 641 1248 640 1248 652 1248 652 1249 1198 1249 1197 1249 644 1250 1059 1250 1006 1250 1060 1251 644 1251 1006 1251 630 1252 1011 1252 628 1252 1022 1253 1011 1253 630 1253 630 1254 1057 1254 1022 1254 629 1255 628 1255 604 1255 642 1256 907 1256 625 1256 642 1257 625 1257 624 1257 908 1258 907 1258 642 1258 618 1259 661 1259 662 1259 619 1260 618 1260 662 1260 662 1261 663 1261 619 1261 619 1262 663 1262 664 1262 620 1263 619 1263 664 1263 664 1264 663 1264 665 1264 666 1265 664 1265 665 1265 665 1266 667 1266 666 1266 667 1267 668 1267 669 1267 670 1268 669 1268 668 1268 666 1269 667 1269 669 1269 666 1270 669 1270 671 1270 666 1271 671 1271 672 1271 666 1272 672 1272 673 1272 674 1273 666 1273 673 1273 673 1274 675 1274 674 1274 676 1275 670 1275 668 1275 668 1276 677 1276 676 1276 674 1277 675 1277 678 1277 674 1278 678 1278 679 1278 680 1279 674 1279 679 1279 679 1280 681 1280 680 1280 682 1281 680 1281 681 1281 681 1282 683 1282 682 1282 684 1283 682 1283 683 1283 683 1284 685 1284 684 1284 684 1285 685 1285 686 1285 684 1286 686 1286 687 1286 688 1287 684 1287 687 1287 687 1288 689 1288 688 1288 692 1289 693 1289 691 1289 690 1290 692 1290 691 1290 688 1291 689 1291 693 1291 693 1292 692 1292 694 1292 694 1293 688 1293 693 1293 692 1294 695 1294 694 1294 694 1295 695 1295 696 1295 697 1296 694 1296 696 1296 696 1297 698 1297 637 1297 637 1298 698 1298 699 1298 638 1299 637 1299 699 1299 681 1300 679 1300 683 1300 685 1301 683 1301 679 1301 679 1302 700 1302 685 1302 701 1303 685 1303 700 1303 700 1304 702 1304 701 1304 703 1305 701 1305 702 1305 702 1306 704 1306 703 1306 705 1307 703 1307 704 1307 704 1308 706 1308 705 1308 707 1309 705 1309 706 1309 706 1310 918 1310 707 1310 815 1311 707 1311 918 1311 708 1312 710 1312 709 1312 711 1313 709 1313 710 1313 710 1314 712 1314 711 1314 713 1315 711 1315 712 1315 712 1316 714 1316 713 1316 713 1317 714 1317 715 1317 716 1318 713 1318 715 1318 715 1319 920 1319 716 1319 844 1320 716 1320 920 1320 693 1321 717 1321 691 1321 718 1322 691 1322 717 1322 717 1323 719 1323 718 1323 720 1324 718 1324 719 1324 719 1325 721 1325 720 1325 722 1326 720 1326 721 1326 721 1327 723 1327 722 1327 724 1328 722 1328 723 1328 723 1329 725 1329 724 1329 726 1330 724 1330 725 1330 725 1331 727 1331 726 1331 728 1332 726 1332 727 1332 727 1333 729 1333 728 1333 730 1334 728 1334 729 1334 729 1335 919 1335 730 1335 842 1336 730 1336 919 1336 669 1337 731 1337 671 1337 732 1338 671 1338 731 1338 731 1339 733 1339 732 1339 734 1340 732 1340 733 1340 733 1341 735 1341 734 1341 736 1342 734 1342 735 1342 735 1343 737 1343 736 1343 738 1344 736 1344 737 1344 737 1345 739 1345 738 1345 740 1346 738 1346 739 1346 739 1347 741 1347 740 1347 742 1348 740 1348 741 1348 741 1349 743 1349 742 1349 744 1350 742 1350 743 1350 743 1351 921 1351 744 1351 849 1352 744 1352 921 1352 732 1353 672 1353 671 1353 734 1354 675 1354 673 1354 734 1355 673 1355 672 1355 732 1356 734 1356 672 1356 734 1357 736 1357 675 1357 745 1358 679 1358 678 1358 745 1359 678 1359 675 1359 675 1360 736 1360 738 1360 745 1361 675 1361 738 1361 700 1362 679 1362 745 1362 738 1363 740 1363 745 1363 745 1364 740 1364 742 1364 746 1365 745 1365 742 1365 746 1366 702 1366 700 1366 745 1367 746 1367 700 1367 704 1368 702 1368 746 1368 742 1369 744 1369 746 1369 852 1370 706 1370 704 1370 746 1371 852 1371 704 1371 746 1372 744 1372 849 1372 746 1373 849 1373 922 1373 852 1374 746 1374 922 1374 706 1375 852 1375 850 1375 918 1376 706 1376 850 1376 693 1377 689 1377 717 1377 719 1378 717 1378 689 1378 689 1379 687 1379 719 1379 719 1380 687 1380 747 1380 721 1381 719 1381 747 1381 748 1382 723 1382 721 1382 747 1383 748 1383 721 1383 686 1384 685 1384 748 1384 748 1385 747 1385 686 1385 685 1386 701 1386 748 1386 725 1387 723 1387 748 1387 748 1388 701 1388 703 1388 749 1389 748 1389 703 1389 749 1390 727 1390 725 1390 748 1391 749 1391 725 1391 703 1392 705 1392 749 1392 729 1393 727 1393 749 1393 749 1394 705 1394 707 1394 707 1395 815 1395 749 1395 749 1396 815 1396 856 1396 858 1397 749 1397 856 1397 749 1398 858 1398 729 1398 729 1399 858 1399 860 1399 919 1400 729 1400 860 1400 669 1401 750 1401 731 1401 733 1402 731 1402 750 1402 750 1403 751 1403 733 1403 735 1404 733 1404 751 1404 751 1405 752 1405 735 1405 737 1406 735 1406 752 1406 753 1407 739 1407 737 1407 752 1408 753 1408 737 1408 754 1409 709 1409 753 1409 755 1410 754 1410 753 1410 756 1411 755 1411 753 1411 753 1412 752 1412 756 1412 709 1413 711 1413 753 1413 741 1414 739 1414 753 1414 753 1415 711 1415 713 1415 753 1416 713 1416 716 1416 753 1417 716 1417 844 1417 753 1418 844 1418 924 1418 866 1419 753 1419 924 1419 866 1420 743 1420 741 1420 753 1421 866 1421 741 1421 743 1422 866 1422 868 1422 921 1423 743 1423 868 1423 618 1424 649 1424 661 1424 757 1425 661 1425 649 1425 649 1426 648 1426 757 1426 758 1427 757 1427 648 1427 648 1428 647 1428 758 1428 759 1429 758 1429 647 1429 647 1430 646 1430 759 1430 760 1431 759 1431 646 1431 646 1432 1203 1432 760 1432 1204 1433 760 1433 1203 1433 699 1434 761 1434 638 1434 653 1435 638 1435 761 1435 761 1436 762 1436 653 1436 654 1437 653 1437 762 1437 762 1438 763 1438 654 1438 650 1439 654 1439 763 1439 763 1440 764 1440 650 1440 651 1441 650 1441 764 1441 764 1442 1201 1442 651 1442 1200 1443 651 1443 1201 1443 692 1444 765 1444 695 1444 761 1445 699 1445 698 1445 766 1446 696 1446 695 1446 696 1447 766 1447 698 1447 698 1448 767 1448 761 1448 767 1449 698 1449 766 1449 695 1450 768 1450 766 1450 768 1451 695 1451 765 1451 769 1452 766 1452 768 1452 766 1453 769 1453 767 1453 762 1454 761 1454 767 1454 767 1455 770 1455 762 1455 770 1456 767 1456 769 1456 765 1457 771 1457 768 1457 772 1458 769 1458 768 1458 769 1459 772 1459 770 1459 763 1460 762 1460 770 1460 774 1461 770 1461 772 1461 770 1462 774 1462 763 1462 771 1463 656 1463 768 1463 768 1464 773 1464 772 1464 773 1465 768 1465 656 1465 656 1466 660 1466 773 1466 764 1467 763 1467 774 1467 772 1468 658 1468 774 1468 658 1469 772 1469 773 1469 659 1470 773 1470 660 1470 773 1471 659 1471 658 1471 1201 1472 764 1472 774 1472 658 1473 657 1473 774 1473 774 1474 657 1474 1201 1474 1178 1475 1195 1475 775 1475 776 1476 668 1476 667 1476 776 1477 667 1477 784 1477 775 1478 776 1478 784 1478 776 1479 775 1479 1195 1479 677 1480 668 1480 776 1480 1195 1481 1194 1481 776 1481 777 1482 776 1482 1194 1482 777 1483 778 1483 779 1483 779 1484 677 1484 776 1484 780 1485 777 1485 1194 1485 1194 1486 1193 1486 780 1486 1192 1487 781 1487 780 1487 1193 1488 1192 1488 780 1488 782 1489 781 1489 1192 1489 1192 1490 655 1490 782 1490 782 1491 765 1491 690 1491 782 1492 655 1492 656 1492 782 1493 656 1493 771 1493 765 1494 782 1494 771 1494 692 1495 690 1495 765 1495 661 1496 757 1496 662 1496 783 1497 662 1497 757 1497 662 1498 783 1498 663 1498 784 1499 667 1499 665 1499 665 1500 785 1500 784 1500 785 1501 665 1501 663 1501 663 1502 786 1502 785 1502 786 1503 663 1503 783 1503 783 1504 787 1504 786 1504 787 1505 783 1505 757 1505 757 1506 758 1506 787 1506 775 1507 784 1507 785 1507 785 1508 788 1508 775 1508 788 1509 785 1509 786 1509 789 1510 786 1510 787 1510 786 1511 789 1511 788 1511 790 1512 787 1512 758 1512 787 1513 790 1513 789 1513 758 1514 759 1514 790 1514 1178 1515 775 1515 788 1515 791 1516 788 1516 789 1516 788 1517 791 1517 1178 1517 792 1518 789 1518 790 1518 789 1519 792 1519 791 1519 793 1520 790 1520 759 1520 790 1521 793 1521 792 1521 1185 1522 1178 1522 791 1522 1185 1523 791 1523 792 1523 759 1524 760 1524 793 1524 1188 1525 792 1525 793 1525 792 1526 1188 1526 1185 1526 760 1527 1204 1527 793 1527 1190 1528 793 1528 1204 1528 793 1529 1190 1529 1188 1529 796 1530 779 1530 778 1530 797 1531 779 1531 796 1531 796 1532 795 1532 797 1532 798 1533 797 1533 795 1533 795 1534 794 1534 798 1534 798 1535 794 1535 708 1535 798 1536 708 1536 709 1536 664 1537 666 1537 674 1537 664 1538 674 1538 680 1538 664 1539 680 1539 682 1539 664 1540 682 1540 684 1540 664 1541 684 1541 688 1541 664 1542 688 1542 694 1542 697 1543 664 1543 694 1543 697 1544 635 1544 633 1544 697 1545 633 1545 634 1545 697 1546 634 1546 632 1546 697 1547 632 1547 631 1547 697 1548 631 1548 627 1548 697 1549 627 1549 629 1549 629 1550 604 1550 626 1550 697 1551 629 1551 626 1551 697 1552 626 1552 642 1552 697 1553 642 1553 624 1553 697 1554 624 1554 623 1554 697 1555 623 1555 622 1555 697 1556 622 1556 616 1556 697 1557 616 1557 620 1557 664 1558 697 1558 620 1558 636 1559 635 1559 697 1559 645 1560 647 1560 648 1560 687 1561 686 1561 747 1561 778 1562 777 1562 780 1562 780 1563 781 1563 778 1563 776 1564 777 1564 779 1564 709 1565 754 1565 798 1565 779 1566 797 1566 798 1566 754 1567 779 1567 798 1567 754 1568 755 1568 779 1568 755 1569 756 1569 779 1569 677 1570 779 1570 756 1570 677 1571 756 1571 752 1571 677 1572 752 1572 751 1572 676 1573 677 1573 751 1573 676 1574 751 1574 750 1574 670 1575 676 1575 750 1575 669 1576 670 1576 750 1576 691 1577 808 1577 814 1577 814 1578 808 1578 813 1578 813 1579 808 1579 807 1579 813 1580 807 1580 812 1580 812 1581 807 1581 806 1581 812 1582 806 1582 802 1582 812 1583 802 1583 801 1583 803 1584 801 1584 802 1584 804 1585 801 1585 803 1585 804 1586 799 1586 801 1586 801 1587 799 1587 800 1587 811 1588 799 1588 804 1588 782 1589 801 1589 781 1589 799 1590 811 1590 708 1590 799 1591 708 1591 794 1591 795 1592 799 1592 794 1592 799 1593 795 1593 800 1593 796 1594 800 1594 795 1594 800 1595 796 1595 801 1595 796 1596 778 1596 801 1596 801 1597 782 1597 812 1597 781 1598 801 1598 778 1598 812 1599 782 1599 690 1599 842 1600 923 1600 730 1600 730 1601 923 1601 862 1601 805 1602 728 1602 862 1602 862 1603 728 1603 730 1603 862 1604 864 1604 805 1604 805 1605 864 1605 920 1605 805 1606 920 1606 715 1606 805 1607 715 1607 809 1607 805 1608 809 1608 810 1608 728 1609 805 1609 726 1609 811 1610 805 1610 810 1610 805 1611 802 1611 806 1611 802 1612 805 1612 803 1612 803 1613 805 1613 804 1613 804 1614 805 1614 811 1614 806 1615 724 1615 805 1615 805 1616 724 1616 726 1616 724 1617 806 1617 722 1617 807 1618 722 1618 806 1618 722 1619 807 1619 720 1619 808 1620 720 1620 807 1620 720 1621 808 1621 718 1621 691 1622 718 1622 808 1622 712 1623 809 1623 714 1623 809 1624 712 1624 810 1624 710 1625 810 1625 712 1625 810 1626 710 1626 811 1626 708 1627 811 1627 710 1627 690 1628 813 1628 812 1628 813 1629 690 1629 814 1629 814 1630 690 1630 691 1630 714 1631 809 1631 715 1631 637 1632 697 1632 696 1632 636 1633 697 1633 637 1633 604 1634 1011 1634 626 1634 604 1635 628 1635 1011 1635 817 1636 815 1636 816 1636 818 1637 817 1637 816 1637 821 1638 819 1638 816 1638 820 1639 822 1639 818 1639 816 1640 823 1640 821 1640 874 1641 818 1641 822 1641 824 1642 821 1642 823 1642 822 1643 825 1643 874 1643 823 1644 826 1644 824 1644 827 1645 874 1645 825 1645 828 1646 824 1646 826 1646 825 1647 829 1647 827 1647 830 1648 827 1648 829 1648 826 1649 831 1649 828 1649 829 1650 832 1650 830 1650 833 1651 828 1651 831 1651 830 1652 832 1652 834 1652 835 1653 830 1653 834 1653 836 1654 837 1654 833 1654 831 1655 836 1655 833 1655 838 1656 837 1656 836 1656 834 1657 838 1657 835 1657 839 1658 835 1658 838 1658 840 1659 839 1659 838 1659 836 1660 840 1660 838 1660 843 1661 842 1661 841 1661 847 1662 848 1662 849 1662 851 1663 823 1663 850 1663 853 1664 851 1664 852 1664 853 1665 849 1665 848 1665 854 1666 853 1666 848 1666 818 1667 815 1667 817 1667 815 1668 818 1668 855 1668 855 1669 857 1669 856 1669 857 1670 859 1670 858 1670 859 1671 841 1671 860 1671 843 1672 861 1672 842 1672 861 1673 863 1673 862 1673 863 1674 845 1674 864 1674 846 1675 865 1675 844 1675 865 1676 867 1676 866 1676 867 1677 847 1677 868 1677 869 1678 832 1678 829 1678 834 1679 832 1679 869 1679 838 1680 834 1680 869 1680 837 1681 838 1681 869 1681 833 1682 837 1682 869 1682 828 1683 833 1683 869 1683 869 1684 824 1684 828 1684 821 1685 824 1685 869 1685 819 1686 821 1686 869 1686 820 1687 819 1687 869 1687 822 1688 820 1688 869 1688 825 1689 822 1689 869 1689 829 1690 825 1690 869 1690 870 1691 823 1691 851 1691 851 1692 853 1692 870 1692 871 1693 870 1693 853 1693 853 1694 854 1694 871 1694 855 1695 872 1695 857 1695 859 1696 857 1696 872 1696 872 1697 873 1697 859 1697 859 1698 873 1698 841 1698 875 1699 826 1699 823 1699 870 1700 875 1700 823 1700 871 1701 854 1701 875 1701 870 1702 871 1702 875 1702 854 1703 876 1703 875 1703 831 1704 826 1704 875 1704 877 1705 875 1705 876 1705 877 1706 836 1706 831 1706 875 1707 877 1707 831 1707 876 1708 878 1708 877 1708 840 1709 836 1709 877 1709 877 1710 878 1710 879 1710 880 1711 877 1711 879 1711 877 1712 880 1712 840 1712 839 1713 840 1713 880 1713 879 1714 881 1714 880 1714 882 1715 880 1715 881 1715 880 1716 882 1716 839 1716 835 1717 839 1717 882 1717 881 1718 883 1718 882 1718 884 1719 830 1719 835 1719 882 1720 884 1720 835 1720 884 1721 882 1721 883 1721 827 1722 830 1722 884 1722 883 1723 841 1723 884 1723 872 1724 874 1724 827 1724 884 1725 872 1725 827 1725 884 1726 841 1726 873 1726 884 1727 873 1727 872 1727 855 1728 874 1728 872 1728 874 1729 855 1729 818 1729 844 1730 845 1730 846 1730 846 1731 886 1731 885 1731 845 1732 886 1732 846 1732 854 1733 848 1733 847 1733 841 1734 883 1734 887 1734 887 1734 843 1734 841 1734 878 1735 876 1735 888 1735 888 1735 889 1735 878 1735 879 1736 878 1736 889 1736 889 1736 890 1736 879 1736 890 1737 891 1737 881 1737 881 1737 879 1737 890 1737 891 1738 887 1738 883 1738 883 1738 881 1738 891 1738 876 1739 854 1739 847 1739 847 1739 888 1739 876 1739 867 1740 888 1740 847 1740 865 1741 888 1741 867 1741 885 1742 889 1742 888 1742 885 1743 890 1743 889 1743 885 1744 886 1744 890 1744 886 1745 891 1745 890 1745 887 1746 891 1746 886 1746 861 1747 843 1747 887 1747 861 1748 887 1748 863 1748 816 1749 820 1749 818 1749 816 1750 819 1750 820 1750 816 1751 850 1751 823 1751 865 1752 885 1752 888 1752 846 1753 885 1753 865 1753 845 1754 863 1754 886 1754 863 1755 887 1755 886 1755 905 1756 906 1756 904 1756 903 1757 905 1757 904 1757 916 1758 908 1758 626 1758 913 1759 1058 1759 912 1759 893 1760 892 1760 912 1760 915 1761 904 1761 906 1761 915 1762 914 1762 909 1762 1058 1763 913 1763 1062 1763 1062 1764 1061 1764 1058 1764 919 1765 841 1765 842 1765 920 1766 845 1766 844 1766 921 1767 847 1767 849 1767 850 1768 852 1768 851 1768 852 1769 922 1769 853 1769 853 1770 922 1770 849 1770 856 1771 815 1771 855 1771 858 1772 856 1772 857 1772 860 1773 858 1773 859 1773 919 1774 860 1774 841 1774 861 1775 923 1775 842 1775 862 1776 923 1776 861 1776 864 1777 862 1777 863 1777 920 1778 864 1778 845 1778 865 1779 924 1779 844 1779 866 1780 924 1780 865 1780 868 1781 866 1781 867 1781 921 1782 868 1782 847 1782 816 1783 815 1783 918 1783 918 1784 850 1784 816 1784 896 1785 898 1785 966 1785 912 1786 968 1786 967 1786 913 1787 912 1787 967 1787 939 1788 933 1788 930 1788 939 1789 938 1789 933 1789 974 1790 925 1790 941 1790 941 1791 925 1791 945 1791 945 1792 925 1792 944 1792 944 1793 925 1793 943 1793 943 1794 925 1794 951 1794 951 1795 925 1795 972 1795 944 1796 942 1796 945 1796 953 1797 932 1797 942 1797 942 1798 932 1798 931 1798 933 1799 931 1799 932 1799 969 1800 931 1800 933 1800 937 1801 969 1801 933 1801 969 1802 935 1802 931 1802 945 1803 942 1803 931 1803 945 1804 931 1804 935 1804 950 1805 1023 1805 3473 1805 951 1806 1023 1806 950 1806 933 1807 938 1807 937 1807 916 1808 917 1808 908 1808 977 1809 917 1809 916 1809 976 1810 977 1810 916 1810 975 1811 976 1811 916 1811 916 1812 972 1812 975 1812 925 1813 975 1813 972 1813 1023 1814 951 1814 972 1814 960 1815 978 1815 959 1815 966 1816 978 1816 960 1816 960 1817 961 1817 966 1817 965 1818 966 1818 961 1818 961 1819 962 1819 965 1819 962 1820 967 1820 965 1820 962 1821 963 1821 967 1821 913 1822 967 1822 963 1822 1066 1823 913 1823 963 1823 994 1824 1071 1824 926 1824 1071 1825 1064 1825 926 1825 992 1826 994 1826 926 1826 926 1827 955 1827 992 1827 989 1828 992 1828 955 1828 955 1829 956 1829 989 1829 987 1830 989 1830 956 1830 956 1831 957 1831 987 1831 984 1832 987 1832 957 1832 957 1833 958 1833 984 1833 982 1834 984 1834 958 1834 958 1835 959 1835 982 1835 982 1836 959 1836 978 1836 1062 1837 913 1837 1066 1837 1067 1838 1065 1838 964 1838 1065 1839 1067 1839 1042 1839 1052 1840 1069 1840 1065 1840 954 1841 952 1841 929 1841 927 1842 929 1842 952 1842 927 1843 930 1843 929 1843 927 1844 983 1844 930 1844 927 1845 985 1845 983 1845 927 1846 986 1846 985 1846 988 1847 986 1847 927 1847 928 1848 927 1848 948 1848 927 1849 952 1849 948 1849 927 1850 928 1850 988 1850 928 1851 990 1851 988 1851 948 1852 949 1852 928 1852 991 1853 990 1853 928 1853 928 1854 1065 1854 991 1854 1065 1855 993 1855 991 1855 1065 1856 1069 1856 993 1856 928 1857 964 1857 1065 1857 928 1858 949 1858 964 1858 929 1859 953 1859 954 1859 932 1860 953 1860 929 1860 933 1861 932 1861 929 1861 929 1862 930 1862 933 1862 930 1863 983 1863 940 1863 940 1864 939 1864 930 1864 936 1865 974 1865 941 1865 934 1866 941 1866 945 1866 941 1867 934 1867 936 1867 945 1868 935 1868 934 1868 911 1869 936 1869 934 1869 934 1870 970 1870 911 1870 914 1871 910 1871 909 1871 914 1872 915 1872 906 1872 914 1873 974 1873 936 1873 914 1874 973 1874 974 1874 914 1875 906 1875 973 1875 914 1876 936 1876 910 1876 936 1877 911 1877 910 1877 902 1878 971 1878 901 1878 900 1879 901 1879 971 1879 900 1880 969 1880 937 1880 900 1881 971 1881 969 1881 937 1882 1213 1882 900 1882 937 1883 899 1883 1213 1883 937 1884 979 1884 899 1884 981 1885 979 1885 938 1885 979 1886 937 1886 938 1886 938 1887 939 1887 981 1887 980 1888 981 1888 939 1888 939 1889 940 1889 980 1889 983 1890 980 1890 940 1890 953 1891 942 1891 943 1891 944 1892 943 1892 942 1892 947 1893 946 1893 964 1893 964 1894 949 1894 947 1894 949 1895 950 1895 3473 1895 951 1896 950 1896 952 1896 950 1897 948 1897 952 1897 950 1898 949 1898 948 1898 951 1899 952 1899 943 1899 952 1900 954 1900 943 1900 953 1901 943 1901 954 1901 1005 1902 957 1902 956 1902 1005 1903 958 1903 957 1903 959 1904 958 1904 1005 1904 1005 1905 960 1905 959 1905 1005 1906 961 1906 960 1906 1005 1907 962 1907 961 1907 1005 1908 963 1908 962 1908 1005 1909 1066 1909 963 1909 1067 1910 964 1910 946 1910 966 1911 898 1911 978 1911 968 1912 966 1912 965 1912 965 1913 967 1913 968 1913 966 1914 968 1914 896 1914 968 1915 895 1915 896 1915 894 1916 895 1916 968 1916 894 1917 968 1917 912 1917 892 1918 894 1918 912 1918 971 1919 970 1919 969 1919 911 1920 970 1920 971 1920 971 1921 902 1921 911 1921 972 1922 916 1922 626 1922 974 1923 975 1923 925 1923 975 1924 974 1924 973 1924 975 1925 973 1925 976 1925 973 1926 977 1926 976 1926 905 1927 977 1927 973 1927 977 1928 905 1928 917 1928 905 1929 973 1929 906 1929 978 1930 898 1930 982 1930 899 1931 979 1931 897 1931 898 1932 897 1932 979 1932 979 1933 981 1933 898 1933 981 1934 982 1934 898 1934 984 1935 982 1935 983 1935 982 1936 980 1936 983 1936 982 1937 981 1937 980 1937 983 1938 985 1938 984 1938 987 1939 984 1939 985 1939 985 1940 986 1940 987 1940 989 1941 987 1941 988 1941 987 1942 986 1942 988 1942 988 1943 990 1943 989 1943 992 1944 989 1944 990 1944 990 1945 991 1945 992 1945 994 1946 992 1946 993 1946 992 1947 991 1947 993 1947 993 1948 1069 1948 994 1948 1071 1949 994 1949 1069 1949 1010 1950 972 1950 626 1950 972 1951 1010 1951 1023 1951 1019 1952 1020 1952 1024 1952 1020 1953 1021 1953 1025 1953 997 1954 1009 1954 1002 1954 1008 1955 1009 1955 997 1955 997 1956 998 1956 1008 1956 998 1957 999 1957 1008 1957 1007 1958 1002 1958 1009 1958 1007 1959 1003 1959 1002 1959 996 1960 1001 1960 1005 1960 1005 1961 997 1961 1002 1961 1005 1962 998 1962 997 1962 1005 1963 999 1963 998 1963 1005 1964 1000 1964 999 1964 1005 1965 1001 1965 1000 1965 1002 1966 1003 1966 1005 1966 1003 1967 1004 1967 1005 1967 1006 1968 1005 1968 1004 1968 1023 1969 1015 1969 1014 1969 1023 1970 1016 1970 1015 1970 1023 1971 1017 1971 1016 1971 1023 1972 1018 1972 1017 1972 1023 1973 1019 1973 1018 1973 1023 1974 1020 1974 1019 1974 1023 1975 1021 1975 1020 1975 1023 1976 1022 1976 1021 1976 1029 1977 1030 1977 1028 1977 1027 1978 1029 1978 1028 1978 1031 1979 1032 1979 1030 1979 1029 1980 1031 1980 1030 1980 1033 1981 1032 1981 1031 1981 1034 1982 1035 1982 1033 1982 1031 1983 1034 1983 1033 1983 1034 1984 1036 1984 1035 1984 1023 1985 1014 1985 1013 1985 1023 1986 1013 1986 1012 1986 1040 1987 1039 1987 1038 1987 1038 1988 1041 1988 1040 1988 1040 1989 1041 1989 1042 1989 1043 1990 1040 1990 1042 1990 1048 1991 995 1991 1047 1991 3472 1992 1047 1992 1046 1992 1049 1993 1039 1993 3472 1993 1046 1994 1049 1994 3472 1994 1049 1995 1038 1995 1039 1995 1050 1996 1032 1996 1033 1996 1051 1997 1050 1997 1033 1997 1051 1998 1041 1998 1038 1998 1051 1999 1038 1999 1050 1999 1033 2000 1035 2000 1051 2000 1051 2001 1035 2001 1037 2001 1051 2002 1052 2002 1041 2002 1050 2003 1049 2003 1046 2003 1053 2004 1050 2004 1046 2004 1053 2005 1028 2005 1030 2005 1053 2006 1030 2006 1032 2006 1053 2007 1032 2007 1050 2007 1049 2008 1050 2008 1038 2008 1036 2009 1034 2009 1054 2009 1031 2010 1029 2010 1055 2010 1045 2011 1055 2011 1029 2011 1029 2012 1027 2012 1045 2012 3474 2013 1045 2013 1027 2013 1027 2014 1026 2014 3474 2014 3475 2015 3474 2015 1026 2015 1012 2016 995 2016 1023 2016 1023 2017 995 2017 1048 2017 1034 2018 1056 2018 1054 2018 1031 2019 1056 2019 1034 2019 1031 2020 1055 2020 1056 2020 1047 2021 1023 2021 1048 2021 1005 2022 3475 2022 1044 2022 1005 2023 1044 2023 996 2023 1059 2024 1058 2024 1061 2024 1061 2025 1006 2025 1059 2025 1006 2026 1004 2026 1060 2026 1007 2027 1060 2027 1004 2027 1004 2028 1003 2028 1007 2028 1021 2029 1022 2029 1057 2029 1057 2030 1025 2030 1021 2030 1054 2031 1063 2031 1036 2031 1071 2032 1036 2032 1063 2032 1064 2033 1071 2033 1063 2033 1052 2034 1065 2034 1042 2034 1052 2035 1070 2035 1069 2035 1052 2036 1037 2036 1070 2036 1052 2037 1042 2037 1041 2037 1052 2038 1051 2038 1037 2038 1062 2039 1066 2039 1005 2039 1061 2040 1062 2040 1005 2040 1005 2041 1006 2041 1061 2041 946 2042 1068 2042 1067 2042 1042 2043 1067 2043 1068 2043 1068 2044 1043 2044 1042 2044 1070 2045 1071 2045 1069 2045 1036 2046 1071 2046 1037 2046 1071 2047 1070 2047 1037 2047 1036 2048 1037 2048 1035 2048 1010 2049 626 2049 1011 2049 1010 2050 1011 2050 1022 2050 1010 2051 1022 2051 1023 2051 1088 2052 1081 2052 1080 2052 1087 2053 1078 2053 1079 2053 1079 2054 1081 2054 1088 2054 1088 2055 1080 2055 1082 2055 1105 2056 1091 2056 1104 2056 1090 2057 1104 2057 1091 2057 1092 2058 1090 2058 1093 2058 1090 2059 1091 2059 1093 2059 1094 2060 1092 2060 1095 2060 1092 2061 1093 2061 1095 2061 1097 2062 1094 2062 1096 2062 1094 2063 1095 2063 1096 2063 1128 2064 1097 2064 1096 2064 1128 2065 1130 2065 1097 2065 1113 2066 1097 2066 1130 2066 1089 2067 1098 2067 1108 2067 1089 2068 1099 2068 1098 2068 1099 2069 1100 2069 1098 2069 1099 2070 1102 2070 1100 2070 1102 2071 1101 2071 1100 2071 1102 2072 1103 2072 1101 2072 1101 2073 1103 2073 1129 2073 1132 2074 1129 2074 1117 2074 1129 2075 1103 2075 1117 2075 1104 2076 1106 2076 1105 2076 1107 2077 1089 2077 1108 2077 1143 2078 1155 2078 1144 2078 1155 2079 1109 2079 1144 2079 1109 2080 1130 2080 1144 2080 1109 2081 1110 2081 1130 2081 1110 2082 1111 2082 1130 2082 1111 2083 1112 2083 1130 2083 1113 2084 1130 2084 1112 2084 1134 2085 1072 2085 1075 2085 1073 2086 1072 2086 1134 2086 1134 2087 1074 2087 1073 2087 1134 2088 1114 2088 1074 2088 1134 2089 1115 2089 1114 2089 1134 2090 1116 2090 1115 2090 1134 2091 1117 2091 1116 2091 1132 2092 1117 2092 1131 2092 1117 2093 1133 2093 1131 2093 1117 2094 1134 2094 1133 2094 1143 2095 1142 2095 1155 2095 1142 2096 1154 2096 1155 2096 1153 2097 1154 2097 1142 2097 1142 2098 1141 2098 1153 2098 1152 2099 1153 2099 1141 2099 1141 2100 1140 2100 1152 2100 1140 2101 1139 2101 1151 2101 1149 2102 1150 2102 1139 2102 1139 2103 1138 2103 1149 2103 1138 2104 1148 2104 1149 2104 1147 2105 1148 2105 1138 2105 1138 2106 1146 2106 1147 2106 1146 2107 1118 2107 1147 2107 1146 2108 1119 2108 1118 2108 1122 2109 1119 2109 1146 2109 1075 2110 1076 2110 1134 2110 1135 2111 1134 2111 1076 2111 1076 2112 1077 2112 1135 2112 1087 2113 1135 2113 1077 2113 1077 2114 1078 2114 1087 2114 1088 2115 1087 2115 1079 2115 1136 2116 1088 2116 1082 2116 1082 2117 1083 2117 1136 2117 1137 2118 1136 2118 1084 2118 1136 2119 1083 2119 1084 2119 1084 2120 1086 2120 1137 2120 1145 2121 1137 2121 1121 2121 1137 2122 1120 2122 1121 2122 1137 2123 1085 2123 1120 2123 1137 2124 1086 2124 1085 2124 1127 2125 1145 2125 1121 2125 1145 2126 1126 2126 1125 2126 1145 2127 1127 2127 1126 2127 1139 2128 1150 2128 1151 2128 1151 2129 1156 2129 1140 2129 1140 2130 1156 2130 1152 2130 1157 2131 892 2131 893 2131 1157 2132 893 2132 613 2132 1157 2133 613 2133 1214 2133 1254 2134 1157 2134 1214 2134 892 2135 1157 2135 894 2135 1157 2136 1245 2136 894 2136 131 2137 126 2137 1159 2137 126 2138 1158 2138 1159 2138 130 2139 131 2139 1160 2139 131 2140 1159 2140 1160 2140 129 2141 130 2141 1161 2141 130 2142 1160 2142 1161 2142 1217 2143 129 2143 1161 2143 1162 2144 129 2144 1217 2144 1217 2145 1225 2145 1162 2145 109 2146 1162 2146 1225 2146 262 2147 1163 2147 1169 2147 1169 2148 1163 2148 1222 2148 262 2149 1164 2149 1163 2149 1164 2150 1165 2150 1163 2150 1164 2151 128 2151 1165 2151 128 2152 1166 2152 1165 2152 128 2153 1167 2153 1166 2153 128 2154 127 2154 1167 2154 1167 2155 127 2155 1216 2155 1227 2156 1216 2156 1173 2156 1216 2157 127 2157 1173 2157 126 2158 125 2158 1158 2158 1158 2159 125 2159 1223 2159 125 2160 124 2160 1223 2160 124 2161 123 2161 1223 2161 123 2162 122 2162 1223 2162 122 2163 1168 2163 1223 2163 1222 2164 1223 2164 1169 2164 1223 2165 1168 2165 1169 2165 1168 2166 262 2166 1169 2166 1239 2167 62 2167 1240 2167 62 2168 1172 2168 1240 2168 1172 2169 1226 2169 1240 2169 1172 2170 111 2170 1226 2170 111 2171 1225 2171 1226 2171 111 2172 1170 2172 1225 2172 1170 2173 1171 2173 1225 2173 1171 2174 110 2174 1225 2174 109 2175 1225 2175 110 2175 373 2176 1228 2176 382 2176 1228 2177 381 2177 382 2177 1228 2178 380 2178 381 2178 1228 2179 108 2179 380 2179 1228 2180 107 2180 108 2180 1228 2181 106 2181 107 2181 1228 2182 1173 2182 106 2182 1173 2183 1228 2183 1227 2183 1239 2184 1238 2184 62 2184 1238 2185 63 2185 62 2185 64 2186 63 2186 1238 2186 1238 2187 1237 2187 64 2187 65 2188 64 2188 1237 2188 1237 2189 1236 2189 65 2189 1236 2190 17 2190 65 2190 66 2191 17 2191 1236 2191 1236 2192 1235 2192 66 2192 1235 2193 67 2193 66 2193 68 2194 67 2194 1235 2194 1235 2195 1234 2195 68 2195 1234 2196 69 2196 68 2196 70 2197 69 2197 1234 2197 1234 2198 1255 2198 70 2198 1255 2199 78 2199 70 2199 1255 2200 77 2200 78 2200 75 2201 77 2201 1255 2201 373 2202 1174 2202 1228 2202 1229 2203 1228 2203 1174 2203 1174 2204 372 2204 1229 2204 1230 2205 1229 2205 372 2205 372 2206 1175 2206 1230 2206 1231 2207 1230 2207 371 2207 1230 2208 1175 2208 371 2208 371 2209 369 2209 1231 2209 1232 2210 1231 2210 368 2210 1231 2211 370 2211 368 2211 1231 2212 369 2212 370 2212 368 2213 367 2213 1232 2213 1233 2214 1232 2214 366 2214 1232 2215 367 2215 366 2215 366 2216 364 2216 1233 2216 1256 2217 1233 2217 1176 2217 1233 2218 76 2218 1176 2218 1233 2219 365 2219 76 2219 1233 2220 364 2220 365 2220 1177 2221 1256 2221 1176 2221 1255 2222 1256 2222 74 2222 74 2223 75 2223 1255 2223 1256 2224 73 2224 74 2224 1256 2225 72 2225 73 2225 1256 2226 71 2226 72 2226 1256 2227 1177 2227 71 2227 1191 2228 1179 2228 656 2228 660 2229 656 2229 1179 2229 659 2230 660 2230 1180 2230 660 2231 1179 2231 1180 2231 658 2232 659 2232 1181 2232 659 2233 1180 2233 1181 2233 657 2234 658 2234 1182 2234 658 2235 1181 2235 1182 2235 1218 2236 657 2236 1182 2236 1183 2237 657 2237 1218 2237 1218 2238 1221 2238 1183 2238 1201 2239 1183 2239 1221 2239 1178 2240 1184 2240 1196 2240 1178 2241 1185 2241 1184 2241 1185 2242 1186 2242 1184 2242 1185 2243 1188 2243 1186 2243 1188 2244 1187 2244 1186 2244 1188 2245 1189 2245 1187 2245 1188 2246 1190 2246 1189 2246 1189 2247 1190 2247 1219 2247 1220 2248 1219 2248 1204 2248 1219 2249 1190 2249 1204 2249 656 2250 655 2250 1191 2250 1191 2251 655 2251 1224 2251 655 2252 1192 2252 1224 2252 1192 2253 1193 2253 1224 2253 1193 2254 1194 2254 1224 2254 1194 2255 1195 2255 1224 2255 1224 2256 1195 2256 1196 2256 1195 2257 1178 2257 1196 2257 1251 2258 1205 2258 1252 2258 1205 2259 1197 2259 1252 2259 1197 2260 1221 2260 1252 2260 1197 2261 1198 2261 1221 2261 1198 2262 1199 2262 1221 2262 1199 2263 1200 2263 1221 2263 1201 2264 1221 2264 1200 2264 902 2265 1241 2265 911 2265 1241 2266 910 2266 911 2266 1241 2267 909 2267 910 2267 1241 2268 643 2268 909 2268 1241 2269 1202 2269 643 2269 1241 2270 1203 2270 1202 2270 1241 2271 1204 2271 1203 2271 1204 2272 1241 2272 1220 2272 1251 2273 1250 2273 1205 2273 1250 2274 1206 2274 1205 2274 1207 2275 1206 2275 1250 2275 1250 2276 1249 2276 1207 2276 1208 2277 1207 2277 1249 2277 1249 2278 1248 2278 1208 2278 1248 2279 1209 2279 1208 2279 1210 2280 1209 2280 1248 2280 1248 2281 1247 2281 1210 2281 1247 2282 1211 2282 1210 2282 1212 2283 1211 2283 1247 2283 1247 2284 1246 2284 1212 2284 1246 2285 606 2285 1212 2285 607 2286 606 2286 1246 2286 1246 2287 1253 2287 607 2287 1253 2288 615 2288 607 2288 1253 2289 614 2289 615 2289 612 2290 614 2290 1253 2290 902 2291 901 2291 1241 2291 1242 2292 1241 2292 901 2292 901 2293 900 2293 1242 2293 1243 2294 1242 2294 900 2294 900 2295 1213 2295 1243 2295 1244 2296 1243 2296 899 2296 1243 2297 1213 2297 899 2297 899 2298 897 2298 1244 2298 1245 2299 1244 2299 896 2299 1244 2300 898 2300 896 2300 1244 2301 897 2301 898 2301 896 2302 895 2302 1245 2302 1245 2303 895 2303 894 2303 608 2304 1254 2304 1214 2304 1253 2305 1254 2305 611 2305 611 2306 612 2306 1253 2306 1254 2307 610 2307 611 2307 1254 2308 1215 2308 610 2308 1254 2309 609 2309 1215 2309 1254 2310 608 2310 609 2310 1319 2311 1157 2311 1254 2311 1320 2312 1157 2312 1319 2312 1321 2313 1157 2313 1320 2313 1245 2314 1157 2314 1321 2314 1221 2315 1364 2315 1252 2315 1369 2316 1252 2316 1364 2316 1241 2317 1367 2317 1220 2317 1338 2318 1220 2318 1367 2318 1375 2319 1320 2319 1319 2319 1375 2320 1319 2320 1371 2320 1270 2321 1257 2321 1258 2321 1303 2322 1257 2322 1270 2322 1304 2323 1257 2323 1303 2323 1306 2324 1257 2324 1304 2324 1224 2325 1303 2325 1300 2325 1305 2326 1224 2326 1300 2326 1222 2327 1163 2327 1302 2327 1196 2328 1184 2328 1306 2328 1184 2329 1257 2329 1306 2329 1184 2330 1186 2330 1257 2330 1258 2331 1257 2331 1186 2331 1186 2332 1187 2332 1258 2332 1187 2333 1189 2333 1258 2333 1189 2334 1219 2334 1258 2334 1219 2335 1271 2335 1258 2335 1338 2336 1271 2336 1220 2336 1271 2337 1219 2337 1220 2337 1159 2338 1260 2338 1160 2338 1260 2339 1161 2339 1160 2339 1159 2340 1301 2340 1260 2340 1159 2341 1158 2341 1301 2341 1259 2342 1161 2342 1260 2342 1161 2343 1259 2343 1217 2343 1259 2344 1225 2344 1217 2344 1259 2345 1354 2345 1225 2345 1261 2346 1259 2346 1260 2346 1259 2347 1261 2347 1354 2347 1261 2348 1353 2348 1354 2348 1351 2349 1353 2349 1261 2349 1260 2350 1289 2350 1262 2350 1260 2351 1301 2351 1289 2351 1260 2352 1262 2352 1261 2352 1261 2353 1263 2353 1351 2353 1263 2354 1349 2354 1351 2354 1263 2355 1261 2355 1262 2355 1289 2356 1281 2356 1262 2356 1262 2357 1264 2357 1263 2357 1264 2358 1262 2358 1286 2358 1262 2359 1284 2359 1286 2359 1262 2360 1281 2360 1284 2360 1347 2361 1349 2361 1263 2361 1263 2362 1265 2362 1347 2362 1265 2363 1263 2363 1264 2363 1346 2364 1347 2364 1265 2364 1286 2365 1288 2365 1264 2365 1266 2366 1264 2366 1291 2366 1264 2367 1288 2367 1291 2367 1264 2368 1266 2368 1265 2368 1267 2369 1265 2369 1266 2369 1265 2370 1267 2370 1346 2370 1267 2371 1344 2371 1346 2371 1342 2372 1344 2372 1267 2372 1291 2373 1293 2373 1266 2373 1268 2374 1266 2374 1295 2374 1266 2375 1293 2375 1295 2375 1266 2376 1268 2376 1267 2376 1269 2377 1267 2377 1268 2377 1267 2378 1269 2378 1342 2378 1269 2379 1341 2379 1342 2379 1295 2380 1297 2380 1268 2380 1268 2381 1299 2381 1270 2381 1268 2382 1297 2382 1299 2382 1268 2383 1270 2383 1269 2383 1339 2384 1341 2384 1269 2384 1269 2385 1270 2385 1258 2385 1269 2386 1258 2386 1339 2386 1299 2387 1303 2387 1270 2387 1338 2388 1339 2388 1271 2388 1339 2389 1258 2389 1271 2389 1305 2390 1179 2390 1191 2390 1180 2391 1179 2391 1274 2391 1181 2392 1180 2392 1272 2392 1180 2393 1274 2393 1272 2393 1182 2394 1181 2394 1272 2394 1218 2395 1182 2395 1273 2395 1182 2396 1272 2396 1273 2396 1273 2397 1364 2397 1218 2397 1221 2398 1218 2398 1364 2398 1275 2399 1272 2399 1274 2399 1272 2400 1275 2400 1273 2400 1275 2401 1364 2401 1273 2401 1275 2402 1365 2402 1364 2402 1305 2403 1300 2403 1179 2403 1300 2404 1274 2404 1179 2404 1274 2405 1276 2405 1275 2405 1276 2406 1274 2406 1298 2406 1274 2407 1300 2407 1298 2407 1362 2408 1365 2408 1275 2408 1298 2409 1296 2409 1276 2409 1278 2410 1275 2410 1277 2410 1275 2411 1276 2411 1277 2411 1275 2412 1278 2412 1362 2412 1278 2413 1361 2413 1362 2413 1278 2414 1359 2414 1361 2414 1277 2415 1276 2415 1292 2415 1276 2416 1296 2416 1292 2416 1292 2417 1290 2417 1277 2417 1277 2418 1279 2418 1278 2418 1279 2419 1277 2419 1287 2419 1277 2420 1290 2420 1287 2420 1357 2421 1359 2421 1278 2421 1280 2422 1278 2422 1279 2422 1278 2423 1280 2423 1357 2423 1280 2424 1355 2424 1357 2424 1287 2425 1285 2425 1279 2425 1279 2426 1285 2426 1283 2426 1283 2427 1284 2427 1282 2427 1286 2428 1284 2428 1285 2428 1284 2429 1283 2429 1285 2429 1285 2430 1287 2430 1286 2430 1288 2431 1286 2431 1287 2431 1287 2432 1290 2432 1288 2432 1291 2433 1288 2433 1290 2433 1301 2434 1294 2434 1289 2434 1290 2435 1292 2435 1291 2435 1293 2436 1291 2436 1292 2436 1292 2437 1296 2437 1293 2437 1296 2438 1295 2438 1293 2438 1294 2439 1301 2439 1223 2439 1297 2440 1295 2440 1296 2440 1296 2441 1298 2441 1297 2441 1299 2442 1297 2442 1298 2442 1298 2443 1300 2443 1299 2443 1303 2444 1299 2444 1300 2444 1301 2445 1158 2445 1223 2445 1222 2446 1302 2446 1223 2446 1304 2447 1303 2447 1224 2447 1306 2448 1304 2448 1224 2448 1305 2449 1191 2449 1224 2449 1196 2450 1306 2450 1224 2450 1307 2451 1320 2451 1377 2451 1320 2452 1375 2452 1377 2452 1320 2453 1307 2453 1321 2453 1307 2454 1322 2454 1321 2454 1307 2455 1323 2455 1322 2455 1308 2456 1323 2456 1307 2456 1308 2457 1324 2457 1323 2457 1308 2458 1367 2458 1324 2458 1308 2459 1340 2459 1367 2459 1377 2460 1378 2460 1307 2460 1307 2461 1309 2461 1308 2461 1309 2462 1307 2462 1388 2462 1307 2463 1386 2463 1388 2463 1307 2464 1378 2464 1386 2464 1310 2465 1308 2465 1309 2465 1308 2466 1310 2466 1340 2466 1310 2467 1343 2467 1340 2467 1388 2468 1390 2468 1309 2468 1311 2469 1309 2469 1392 2469 1309 2470 1390 2470 1392 2470 1309 2471 1311 2471 1310 2471 1312 2472 1310 2472 1311 2472 1310 2473 1312 2473 1343 2473 1312 2474 1345 2474 1343 2474 1392 2475 1395 2475 1311 2475 1348 2476 1345 2476 1312 2476 1313 2477 1311 2477 1380 2477 1311 2478 1396 2478 1380 2478 1395 2479 1396 2479 1311 2479 1311 2480 1313 2480 1312 2480 1312 2481 1314 2481 1348 2481 1314 2482 1312 2482 1313 2482 1350 2483 1348 2483 1314 2483 1380 2484 1381 2484 1313 2484 1315 2485 1313 2485 1382 2485 1313 2486 1381 2486 1382 2486 1313 2487 1315 2487 1314 2487 1316 2488 1314 2488 1315 2488 1314 2489 1316 2489 1350 2489 1316 2490 1352 2490 1350 2490 1382 2491 1384 2491 1315 2491 1317 2492 1315 2492 1383 2492 1315 2493 1384 2493 1383 2493 1315 2494 1317 2494 1316 2494 1316 2495 1318 2495 1352 2495 1318 2496 1366 2496 1352 2496 1318 2497 1316 2497 1317 2497 1317 2498 1235 2498 1318 2498 1317 2499 1234 2499 1235 2499 1317 2500 1255 2500 1234 2500 1317 2501 1373 2501 1255 2501 1317 2502 1372 2502 1373 2502 1317 2503 1383 2503 1372 2503 1238 2504 1318 2504 1237 2504 1318 2505 1236 2505 1237 2505 1318 2506 1235 2506 1236 2506 1318 2507 1238 2507 1366 2507 1366 2508 1238 2508 1239 2508 1371 2509 1319 2509 1254 2509 1321 2510 1322 2510 1245 2510 1322 2511 1244 2511 1245 2511 1243 2512 1244 2512 1322 2512 1322 2513 1323 2513 1243 2513 1242 2514 1243 2514 1324 2514 1243 2515 1323 2515 1324 2515 1324 2516 1367 2516 1242 2516 1241 2517 1242 2517 1367 2517 1253 2518 1331 2518 1370 2518 1253 2519 1246 2519 1331 2519 1246 2520 1335 2520 1331 2520 1246 2521 1247 2521 1335 2521 1247 2522 1334 2522 1335 2522 1333 2523 1334 2523 1248 2523 1334 2524 1247 2524 1248 2524 1248 2525 1249 2525 1333 2525 1337 2526 1333 2526 1249 2526 1249 2527 1250 2527 1337 2527 1368 2528 1337 2528 1251 2528 1337 2529 1250 2529 1251 2529 1327 2530 1325 2530 1393 2530 1325 2531 1394 2531 1393 2531 1326 2532 1328 2532 1356 2532 1328 2533 1326 2533 1327 2533 1358 2534 1356 2534 1328 2534 1393 2535 1391 2535 1327 2535 1327 2536 1329 2536 1328 2536 1329 2537 1327 2537 1389 2537 1327 2538 1391 2538 1389 2538 1330 2539 1328 2539 1329 2539 1328 2540 1330 2540 1358 2540 1330 2541 1360 2541 1358 2541 1389 2542 1387 2542 1329 2542 1332 2543 1329 2543 1379 2543 1329 2544 1385 2544 1379 2544 1329 2545 1387 2545 1385 2545 1329 2546 1332 2546 1330 2546 1336 2547 1330 2547 1332 2547 1330 2548 1336 2548 1360 2548 1336 2549 1363 2549 1360 2549 1379 2550 1376 2550 1332 2550 1332 2551 1335 2551 1336 2551 1332 2552 1331 2552 1335 2552 1332 2553 1370 2553 1331 2553 1332 2554 1374 2554 1370 2554 1332 2555 1376 2555 1374 2555 1337 2556 1336 2556 1333 2556 1336 2557 1334 2557 1333 2557 1336 2558 1335 2558 1334 2558 1336 2559 1337 2559 1363 2559 1337 2560 1368 2560 1363 2560 1339 2561 1338 2561 1367 2561 1367 2562 1340 2562 1339 2562 1341 2563 1339 2563 1340 2563 1342 2564 1341 2564 1343 2564 1341 2565 1340 2565 1343 2565 1344 2566 1342 2566 1343 2566 1343 2567 1345 2567 1344 2567 1346 2568 1344 2568 1345 2568 1345 2569 1348 2569 1346 2569 1347 2570 1346 2570 1348 2570 1349 2571 1347 2571 1348 2571 1348 2572 1350 2572 1349 2572 1351 2573 1349 2573 1350 2573 1350 2574 1352 2574 1351 2574 1353 2575 1351 2575 1352 2575 1354 2576 1353 2576 1366 2576 1353 2577 1352 2577 1366 2577 1225 2578 1354 2578 1226 2578 1354 2579 1240 2579 1226 2579 1354 2580 1366 2580 1240 2580 1357 2581 1355 2581 1356 2581 1356 2582 1358 2582 1357 2582 1359 2583 1357 2583 1358 2583 1358 2584 1360 2584 1359 2584 1361 2585 1359 2585 1360 2585 1362 2586 1361 2586 1363 2586 1361 2587 1360 2587 1363 2587 1365 2588 1362 2588 1363 2588 1363 2589 1368 2589 1365 2589 1365 2590 1369 2590 1364 2590 1365 2591 1368 2591 1369 2591 1366 2592 1239 2592 1240 2592 1368 2593 1251 2593 1369 2593 1252 2594 1369 2594 1251 2594 1253 2595 1370 2595 1254 2595 1371 2596 1254 2596 1370 2596 1255 2597 1373 2597 1256 2597 1256 2598 1372 2598 1383 2598 1256 2599 1373 2599 1372 2599 1105 2600 1106 2600 1414 2600 1106 2601 1397 2601 1414 2601 1397 2602 1398 2602 1414 2602 1398 2603 1399 2603 1414 2603 1399 2604 1107 2604 1414 2604 1414 2605 1107 2605 1108 2605 1130 2606 1428 2606 1144 2606 1105 2607 1410 2607 1091 2607 1404 2608 1091 2608 1410 2608 1279 2609 1400 2609 1280 2609 1400 2610 1279 2610 1409 2610 1279 2611 1283 2611 1409 2611 1427 2612 1355 2612 1280 2612 1401 2613 1280 2613 1400 2613 1280 2614 1401 2614 1427 2614 1409 2615 1411 2615 1400 2615 1425 2616 1427 2616 1401 2616 1400 2617 1403 2617 1401 2617 1403 2618 1400 2618 1413 2618 1400 2619 1412 2619 1413 2619 1400 2620 1411 2620 1412 2620 1402 2621 1401 2621 1403 2621 1401 2622 1402 2622 1425 2622 1402 2623 1423 2623 1425 2623 1402 2624 1421 2624 1423 2624 1419 2625 1421 2625 1402 2625 1402 2626 1100 2626 1101 2626 1402 2627 1403 2627 1100 2627 1402 2628 1101 2628 1419 2628 1132 2629 1419 2629 1129 2629 1419 2630 1101 2630 1129 2630 1100 2631 1403 2631 1098 2631 1403 2632 1413 2632 1098 2632 1413 2633 1108 2633 1098 2633 1404 2634 1093 2634 1091 2634 1404 2635 1405 2635 1093 2635 1095 2636 1093 2636 1405 2636 1405 2637 1406 2637 1095 2637 1406 2638 1096 2638 1095 2638 1096 2639 1406 2639 1128 2639 1130 2640 1128 2640 1408 2640 1128 2641 1406 2641 1408 2641 1130 2642 1408 2642 1407 2642 1282 2643 1410 2643 1283 2643 1410 2644 1409 2644 1283 2644 1411 2645 1409 2645 1410 2645 1412 2646 1411 2646 1410 2646 1413 2647 1412 2647 1414 2647 1412 2648 1410 2648 1414 2648 1410 2649 1105 2649 1414 2649 1414 2650 1108 2650 1413 2650 1429 2651 1137 2651 1145 2651 1137 2652 1415 2652 1136 2652 1415 2653 1088 2653 1136 2653 1415 2654 1087 2654 1088 2654 1415 2655 1137 2655 1436 2655 1137 2656 1435 2656 1436 2656 1137 2657 1430 2657 1435 2657 1137 2658 1429 2658 1430 2658 1135 2659 1087 2659 1416 2659 1416 2660 1134 2660 1135 2660 1416 2661 1420 2661 1134 2661 1416 2662 1087 2662 1415 2662 1422 2663 1420 2663 1416 2663 1415 2664 1417 2664 1416 2664 1417 2665 1415 2665 1434 2665 1415 2666 1436 2666 1434 2666 1418 2667 1416 2667 1417 2667 1416 2668 1418 2668 1422 2668 1424 2669 1422 2669 1418 2669 1434 2670 1431 2670 1417 2670 1325 2671 1417 2671 1432 2671 1417 2672 1431 2672 1432 2672 1417 2673 1325 2673 1418 2673 1418 2674 1326 2674 1424 2674 1326 2675 1426 2675 1424 2675 1326 2676 1418 2676 1325 2676 1432 2677 1433 2677 1325 2677 1356 2678 1426 2678 1326 2678 1325 2679 1327 2679 1326 2679 1433 2680 1394 2680 1325 2680 1134 2681 1420 2681 1133 2681 1420 2682 1131 2682 1133 2682 1420 2683 1132 2683 1131 2683 1419 2684 1132 2684 1420 2684 1421 2685 1419 2685 1420 2685 1420 2686 1422 2686 1421 2686 1423 2687 1421 2687 1422 2687 1422 2688 1424 2688 1423 2688 1425 2689 1423 2689 1424 2689 1424 2690 1426 2690 1425 2690 1427 2691 1425 2691 1426 2691 1426 2692 1356 2692 1427 2692 1355 2693 1427 2693 1356 2693 1436 2694 1435 2694 1434 2694 1446 2695 1437 2695 1445 2695 1500 2696 1466 2696 1446 2696 1466 2697 1437 2697 1446 2697 1599 2698 1460 2698 1588 2698 1599 2699 1600 2699 1460 2699 1600 2700 1459 2700 1460 2700 1600 2701 1457 2701 1459 2701 1600 2702 1458 2702 1457 2702 1600 2703 1449 2703 1458 2703 1600 2704 1448 2704 1449 2704 1600 2705 1447 2705 1448 2705 1567 2706 1570 2706 1565 2706 1571 2707 1574 2707 1570 2707 1438 2708 1437 2708 1466 2708 1466 2709 1468 2709 1438 2709 1439 2710 1438 2710 1468 2710 1468 2711 1470 2711 1439 2711 1440 2712 1439 2712 1470 2712 1470 2713 1472 2713 1440 2713 1442 2714 1440 2714 1472 2714 1472 2715 1474 2715 1442 2715 1443 2716 1442 2716 1474 2716 1474 2717 1477 2717 1443 2717 1477 2718 1480 2718 1444 2718 1437 2719 1438 2719 1445 2719 1441 2720 1445 2720 1439 2720 1445 2721 1438 2721 1439 2721 1457 2722 1458 2722 1450 2722 1450 2723 1451 2723 1457 2723 1451 2724 1459 2724 1457 2724 1460 2725 1459 2725 1451 2725 1451 2726 1452 2726 1460 2726 1461 2727 1460 2727 1452 2727 1452 2728 1453 2728 1461 2728 1453 2729 1462 2729 1461 2729 1464 2730 1462 2730 1453 2730 1453 2731 1454 2731 1464 2731 1494 2732 1464 2732 1493 2732 1464 2733 1492 2733 1493 2733 1464 2734 1491 2734 1492 2734 1464 2735 1490 2735 1491 2735 1464 2736 1454 2736 1490 2736 1454 2737 1455 2737 1489 2737 1489 2738 1490 2738 1454 2738 1455 2739 1488 2739 1489 2739 1487 2740 1488 2740 1455 2740 1456 2741 1486 2741 1487 2741 1460 2742 1461 2742 1588 2742 1463 2743 1588 2743 1461 2743 1463 2744 1590 2744 1588 2744 1461 2745 1462 2745 1463 2745 1597 2746 1590 2746 1463 2746 1465 2747 1463 2747 1464 2747 1463 2748 1462 2748 1464 2748 1463 2749 1465 2749 1597 2749 1596 2750 1597 2750 1465 2750 1464 2751 1494 2751 1465 2751 1465 2752 1495 2752 1496 2752 1465 2753 1494 2753 1495 2753 1465 2754 1496 2754 1596 2754 1496 2755 1595 2755 1596 2755 1591 2756 1595 2756 1497 2756 1595 2757 1496 2757 1497 2757 1505 2758 1506 2758 1500 2758 1467 2759 1500 2759 1506 2759 1469 2760 1466 2760 1500 2760 1469 2761 1500 2761 1467 2761 1506 2762 1507 2762 1467 2762 1468 2763 1466 2763 1469 2763 1471 2764 1467 2764 1508 2764 1467 2765 1507 2765 1508 2765 1467 2766 1471 2766 1469 2766 1469 2767 1473 2767 1468 2767 1473 2768 1470 2768 1468 2768 1473 2769 1469 2769 1471 2769 1508 2770 1509 2770 1471 2770 1472 2771 1470 2771 1473 2771 1471 2772 1475 2772 1473 2772 1475 2773 1471 2773 1510 2773 1471 2774 1509 2774 1510 2774 1473 2775 1476 2775 1472 2775 1476 2776 1474 2776 1472 2776 1476 2777 1473 2777 1475 2777 1510 2778 1504 2778 1475 2778 1477 2779 1474 2779 1476 2779 1478 2780 1475 2780 1504 2780 1475 2781 1478 2781 1476 2781 1476 2782 1479 2782 1477 2782 1479 2783 1476 2783 1478 2783 1504 2784 1503 2784 1478 2784 1480 2785 1477 2785 1479 2785 1482 2786 1478 2786 1502 2786 1478 2787 1503 2787 1502 2787 1478 2788 1482 2788 1479 2788 1483 2789 1479 2789 1482 2789 1479 2790 1483 2790 1480 2790 1483 2791 1481 2791 1480 2791 1484 2792 1481 2792 1483 2792 1485 2793 1563 2793 1486 2793 1487 2794 1486 2794 1563 2794 1563 2795 1560 2795 1487 2795 1488 2796 1487 2796 1562 2796 1487 2797 1561 2797 1562 2797 1487 2798 1560 2798 1561 2798 1562 2799 1558 2799 1488 2799 1558 2800 1489 2800 1488 2800 1490 2801 1489 2801 1558 2801 1558 2802 1557 2802 1490 2802 1491 2803 1490 2803 1557 2803 1557 2804 1559 2804 1491 2804 1492 2805 1491 2805 1559 2805 1559 2806 1556 2806 1492 2806 1493 2807 1492 2807 1556 2807 1556 2808 1555 2808 1493 2808 1494 2809 1493 2809 1555 2809 1555 2810 1554 2810 1494 2810 1554 2811 1495 2811 1494 2811 1496 2812 1495 2812 1554 2812 1554 2813 1553 2813 1496 2813 1553 2814 1498 2814 1496 2814 1497 2815 1496 2815 1498 2815 1591 2816 1497 2816 1594 2816 1497 2817 1498 2817 1594 2817 1498 2818 1553 2818 1552 2818 1552 2819 1581 2819 1498 2819 1581 2820 1513 2820 1498 2820 1513 2821 1594 2821 1498 2821 1593 2822 1594 2822 1513 2822 1513 2823 1516 2823 1593 2823 1592 2824 1593 2824 1516 2824 1516 2825 1518 2825 1592 2825 1589 2826 1592 2826 1518 2826 1518 2827 1520 2827 1589 2827 1587 2828 1589 2828 1520 2828 1520 2829 1523 2829 1587 2829 1585 2830 1587 2830 1523 2830 1523 2831 1529 2831 1585 2831 1585 2832 1527 2832 1499 2832 1585 2833 1529 2833 1527 2833 1583 2834 1527 2834 1528 2834 1583 2835 1499 2835 1527 2835 1528 2836 1530 2836 1598 2836 1505 2837 1500 2837 1511 2837 1501 2838 1502 2838 1512 2838 1502 2839 1503 2839 1512 2839 1503 2840 1504 2840 1512 2840 1504 2841 1510 2841 1512 2841 1511 2842 1512 2842 1505 2842 1512 2843 1506 2843 1505 2843 1512 2844 1507 2844 1506 2844 1512 2845 1508 2845 1507 2845 1512 2846 1509 2846 1508 2846 1512 2847 1510 2847 1509 2847 1530 2848 1582 2848 1598 2848 1514 2849 1533 2849 1531 2849 1532 2850 1515 2850 1581 2850 1515 2851 1513 2851 1581 2851 1515 2852 1532 2852 1514 2852 1532 2853 1533 2853 1514 2853 1516 2854 1513 2854 1515 2854 1514 2855 1517 2855 1515 2855 1519 2856 1515 2856 1517 2856 1515 2857 1519 2857 1516 2857 1518 2858 1516 2858 1519 2858 1517 2859 1521 2859 1519 2859 1519 2860 1522 2860 1518 2860 1522 2861 1520 2861 1518 2861 1522 2862 1519 2862 1521 2862 1523 2863 1520 2863 1522 2863 1521 2864 1525 2864 1522 2864 1522 2865 1526 2865 1523 2865 1526 2866 1522 2866 1525 2866 1529 2867 1523 2867 1526 2867 1525 2868 1524 2868 1530 2868 1530 2869 1526 2869 1525 2869 1526 2870 1528 2870 1529 2870 1526 2871 1530 2871 1528 2871 1529 2872 1528 2872 1527 2872 1534 2873 1531 2873 1533 2873 1535 2874 1533 2874 1581 2874 1533 2875 1532 2875 1581 2875 1533 2876 1535 2876 1534 2876 1581 2877 1536 2877 1535 2877 1536 2878 1581 2878 1565 2878 1537 2879 1534 2879 1535 2879 1538 2880 1535 2880 1536 2880 1535 2881 1538 2881 1537 2881 1565 2882 1570 2882 1536 2882 1536 2883 1540 2883 1538 2883 1540 2884 1536 2884 1570 2884 1541 2885 1537 2885 1538 2885 1537 2886 1541 2886 1539 2886 1542 2887 1538 2887 1540 2887 1538 2888 1542 2888 1541 2888 1543 2889 1539 2889 1541 2889 1570 2890 1574 2890 1540 2890 1545 2891 1540 2891 1574 2891 1540 2892 1545 2892 1542 2892 1547 2893 1541 2893 1546 2893 1541 2894 1542 2894 1546 2894 1541 2895 1547 2895 1543 2895 1546 2896 1542 2896 1545 2896 1543 2897 1548 2897 1544 2897 1548 2898 1543 2898 1547 2898 1549 2899 1544 2899 1548 2899 1574 2900 1576 2900 1545 2900 1545 2901 1550 2901 1546 2901 1550 2902 1545 2902 1578 2902 1545 2903 1576 2903 1578 2903 1546 2904 1551 2904 1547 2904 1552 2905 1553 2905 1581 2905 1553 2906 1554 2906 1581 2906 1554 2907 1555 2907 1581 2907 1555 2908 1556 2908 1581 2908 1556 2909 1559 2909 1581 2909 1566 2910 1559 2910 1564 2910 1559 2911 1557 2911 1564 2911 1557 2912 1558 2912 1564 2912 1558 2913 1562 2913 1564 2913 1559 2914 1566 2914 1581 2914 1565 2915 1581 2915 1566 2915 1563 2916 1564 2916 1560 2916 1564 2917 1561 2917 1560 2917 1564 2918 1562 2918 1561 2918 1564 2919 1568 2919 1566 2919 1566 2920 1569 2920 1565 2920 1569 2921 1567 2921 1565 2921 1569 2922 1566 2922 1568 2922 1570 2923 1567 2923 1569 2923 1568 2924 1572 2924 1569 2924 1573 2925 1569 2925 1572 2925 1569 2926 1573 2926 1570 2926 1573 2927 1571 2927 1570 2927 1574 2928 1571 2928 1573 2928 1577 2929 1573 2929 1575 2929 1573 2930 1577 2930 1574 2930 1577 2931 1576 2931 1574 2931 1578 2932 1576 2932 1577 2932 1577 2933 1580 2933 1578 2933 1579 2934 1578 2934 1580 2934 1584 2935 1499 2935 1583 2935 1585 2936 1499 2936 1584 2936 1584 2937 1586 2937 1585 2937 1587 2938 1585 2938 1586 2938 1589 2939 1587 2939 1588 2939 1587 2940 1586 2940 1588 2940 1592 2941 1589 2941 1591 2941 1589 2942 1590 2942 1591 2942 1589 2943 1588 2943 1590 2943 1590 2944 1597 2944 1591 2944 1595 2945 1591 2945 1597 2945 1591 2946 1594 2946 1592 2946 1594 2947 1593 2947 1592 2947 1597 2948 1596 2948 1595 2948 1630 2949 1631 2949 1613 2949 1445 2950 1441 2950 1606 2950 1439 2951 1440 2951 1441 2951 1603 2952 1441 2952 1442 2952 1441 2953 1440 2953 1442 2953 1618 2954 1604 2954 1619 2954 1604 2955 1616 2955 1619 2955 1604 2956 1618 2956 1612 2956 1618 2957 1630 2957 1612 2957 1612 2958 1610 2958 1604 2958 1617 2959 1605 2959 1611 2959 1608 2960 1627 2960 1607 2960 1608 2961 1628 2961 1627 2961 1607 2962 1609 2962 1608 2962 1631 2963 1628 2963 1608 2963 1613 2964 1608 2964 1609 2964 1608 2965 1613 2965 1631 2965 1609 2966 1610 2966 1612 2966 1609 2967 1612 2967 1613 2967 1630 2968 1613 2968 1612 2968 1578 2969 1579 2969 1550 2969 1614 2970 1620 2970 1622 2970 1622 2971 1615 2971 1614 2971 1615 2972 1622 2972 1619 2972 1619 2973 1616 2973 1615 2973 1580 2974 1620 2974 1579 2974 1635 2975 1633 2975 1625 2975 1633 2976 1626 2976 1632 2976 1626 2977 1627 2977 1632 2977 1665 2978 1447 2978 1601 2978 1659 2979 1647 2979 1665 2979 1665 2980 1637 2980 1447 2980 1637 2981 1448 2981 1447 2981 1637 2982 1665 2982 1648 2982 1665 2983 1647 2983 1648 2983 1449 2984 1448 2984 1637 2984 1648 2985 1649 2985 1637 2985 1637 2986 1638 2986 1449 2986 1638 2987 1450 2987 1449 2987 1638 2988 1637 2988 1650 2988 1637 2989 1649 2989 1650 2989 1451 2990 1450 2990 1638 2990 1650 2991 1651 2991 1638 2991 1638 2992 1639 2992 1451 2992 1638 2993 1651 2993 1652 2993 1449 2994 1450 2994 1458 2994 1641 2995 1640 2995 1625 2995 1640 2996 1641 2996 1643 2996 1641 2997 1645 2997 1643 2997 1625 2998 1632 2998 1641 2998 1646 2999 1645 2999 1641 2999 1641 3000 1619 3000 1646 3000 1619 3001 1641 3001 1618 3001 1641 3002 1630 3002 1618 3002 1641 3003 1632 3003 1630 3003 1646 3004 1619 3004 1622 3004 1572 3005 1575 3005 1573 3005 1575 3006 1572 3006 1642 3006 1575 3007 1644 3007 1577 3007 1644 3008 1575 3008 1642 3008 1642 3009 1645 3009 1644 3009 1643 3010 1645 3010 1642 3010 1580 3011 1577 3011 1644 3011 1644 3012 1621 3012 1580 3012 1621 3013 1644 3013 1645 3013 1645 3014 1646 3014 1621 3014 1620 3015 1580 3015 1621 3015 1621 3016 1622 3016 1620 3016 1622 3017 1621 3017 1646 3017 1635 3018 1625 3018 1624 3018 1633 3019 1632 3019 1625 3019 1627 3020 1628 3020 1632 3020 1628 3021 1631 3021 1632 3021 1632 3022 1631 3022 1630 3022 1658 3023 1623 3023 1657 3023 1600 3024 1667 3024 1601 3024 1601 3025 1667 3025 1636 3025 1666 3026 1601 3026 1636 3026 1656 3027 1662 3027 1601 3027 1666 3028 1656 3028 1601 3028 1663 3029 1662 3029 1656 3029 1664 3030 1663 3030 1656 3030 1660 3031 1664 3031 1656 3031 1656 3032 1653 3032 1660 3032 1665 3033 1663 3033 1659 3033 1665 3034 1601 3034 1662 3034 1663 3035 1665 3035 1662 3035 1659 3036 1663 3036 1664 3036 1659 3037 1664 3037 1660 3037 1601 3038 1447 3038 1600 3038 1634 3039 1669 3039 1668 3039 1623 3040 1629 3040 1657 3040 1629 3041 1635 3041 1657 3041 1624 3042 1657 3042 1635 3042 1698 3043 1695 3043 1683 3043 1639 3044 1452 3044 1451 3044 1639 3045 1638 3045 1652 3045 1453 3046 1452 3046 1639 3046 1652 3047 1719 3047 1639 3047 1639 3048 1670 3048 1453 3048 1670 3049 1454 3049 1453 3049 1670 3050 1639 3050 1720 3050 1639 3051 1719 3051 1720 3051 1455 3052 1454 3052 1670 3052 1720 3053 1718 3053 1670 3053 1671 3054 1670 3054 1717 3054 1670 3055 1718 3055 1717 3055 1670 3056 1671 3056 1455 3056 1671 3057 1456 3057 1455 3057 1699 3058 1456 3058 1671 3058 1717 3059 1716 3059 1671 3059 1694 3060 1696 3060 1671 3060 1696 3061 1697 3061 1671 3061 1697 3062 1699 3062 1671 3062 1694 3063 1671 3063 1716 3063 1716 3064 1715 3064 1694 3064 1715 3065 1714 3065 1692 3065 1692 3066 1694 3066 1715 3066 1455 3067 1456 3067 1487 3067 1701 3068 1486 3068 1456 3068 1456 3069 1699 3069 1701 3069 1787 3070 1791 3070 1737 3070 1786 3071 1790 3071 1787 3071 1785 3072 1781 3072 1784 3072 1785 3073 1788 3073 1786 3073 1690 3074 1781 3074 1785 3074 1737 3075 1735 3075 1787 3075 1672 3076 1787 3076 1735 3076 1787 3077 1672 3077 1786 3077 1786 3078 1673 3078 1785 3078 1673 3079 1786 3079 1672 3079 1674 3080 1785 3080 1673 3080 1785 3081 1674 3081 1690 3081 1674 3082 1689 3082 1690 3082 1735 3083 1733 3083 1672 3083 1675 3084 1672 3084 1733 3084 1672 3085 1675 3085 1673 3085 1673 3086 1676 3086 1674 3086 1676 3087 1673 3087 1675 3087 1687 3088 1689 3088 1674 3088 1674 3089 1677 3089 1687 3089 1677 3090 1685 3090 1687 3090 1677 3091 1674 3091 1676 3091 1733 3092 1731 3092 1675 3092 1675 3093 1678 3093 1676 3093 1678 3094 1675 3094 1729 3094 1675 3095 1731 3095 1729 3095 1676 3096 1679 3096 1677 3096 1679 3097 1676 3097 1678 3097 1684 3098 1685 3098 1677 3098 1703 3099 1677 3099 1679 3099 1677 3100 1703 3100 1684 3100 1703 3101 1706 3101 1684 3101 1729 3102 1727 3102 1678 3102 1678 3103 1680 3103 1679 3103 1680 3104 1678 3104 1727 3104 1679 3105 1681 3105 1703 3105 1681 3106 1679 3106 1680 3106 1727 3107 1725 3107 1680 3107 1680 3108 1723 3108 1702 3108 1680 3109 1725 3109 1723 3109 1680 3110 1702 3110 1681 3110 1703 3111 1681 3111 1704 3111 1681 3112 1702 3112 1704 3112 1682 3113 1705 3113 1485 3113 1705 3114 1563 3114 1485 3114 1705 3115 1682 3115 1707 3115 1485 3116 1700 3116 1682 3116 1683 3117 1682 3117 1698 3117 1682 3118 1700 3118 1698 3118 1682 3119 1683 3119 1707 3119 1706 3120 1707 3120 1684 3120 1707 3121 1686 3121 1684 3121 1686 3122 1707 3122 1695 3122 1707 3123 1683 3123 1695 3123 1685 3124 1684 3124 1686 3124 1695 3125 1693 3125 1686 3125 1686 3126 1688 3126 1685 3126 1688 3127 1687 3127 1685 3127 1688 3128 1686 3128 1712 3128 1686 3129 1693 3129 1712 3129 1712 3130 1713 3130 1688 3130 1689 3131 1687 3131 1688 3131 1691 3132 1688 3132 1711 3132 1688 3133 1713 3133 1711 3133 1688 3134 1691 3134 1689 3134 1691 3135 1690 3135 1689 3135 1711 3136 1710 3136 1691 3136 1781 3137 1690 3137 1691 3137 1691 3138 1710 3138 1741 3138 1691 3139 1741 3139 1781 3139 1781 3140 1741 3140 1782 3140 1712 3141 1693 3141 1714 3141 1693 3142 1692 3142 1714 3142 1694 3143 1692 3143 1693 3143 1693 3144 1695 3144 1694 3144 1696 3145 1694 3145 1695 3145 1695 3146 1698 3146 1696 3146 1698 3147 1697 3147 1696 3147 1699 3148 1697 3148 1698 3148 1698 3149 1700 3149 1699 3149 1701 3150 1699 3150 1700 3150 1700 3151 1485 3151 1701 3151 1486 3152 1701 3152 1485 3152 1723 3153 1722 3153 1702 3153 1722 3154 1704 3154 1702 3154 1640 3155 1703 3155 1704 3155 1640 3156 1706 3156 1703 3156 1640 3157 1708 3157 1706 3157 1640 3158 1643 3158 1708 3158 1640 3159 1704 3159 1722 3159 1722 3160 1624 3160 1640 3160 1640 3161 1624 3161 1625 3161 1564 3162 1563 3162 1705 3162 1709 3163 1705 3163 1707 3163 1705 3164 1709 3164 1564 3164 1568 3165 1564 3165 1709 3165 1706 3166 1708 3166 1707 3166 1708 3167 1709 3167 1707 3167 1709 3168 1643 3168 1642 3168 1709 3169 1708 3169 1643 3169 1709 3170 1642 3170 1568 3170 1572 3171 1568 3171 1642 3171 1647 3172 1659 3172 1741 3172 1741 3173 1710 3173 1647 3173 1648 3174 1647 3174 1710 3174 1710 3175 1711 3175 1648 3175 1649 3176 1648 3176 1711 3176 1711 3177 1713 3177 1649 3177 1650 3178 1649 3178 1714 3178 1649 3179 1713 3179 1714 3179 1713 3180 1712 3180 1714 3180 1714 3181 1715 3181 1650 3181 1651 3182 1650 3182 1715 3182 1715 3183 1716 3183 1651 3183 1652 3184 1651 3184 1716 3184 1716 3185 1717 3185 1652 3185 1719 3186 1652 3186 1717 3186 1717 3187 1718 3187 1719 3187 1720 3188 1719 3188 1718 3188 1731 3189 1733 3189 1732 3189 1729 3190 1731 3190 1730 3190 1727 3191 1729 3191 1728 3191 1725 3192 1727 3192 1726 3192 1724 3193 1723 3193 1725 3193 1722 3194 1723 3194 1657 3194 1723 3195 1724 3195 1657 3195 1726 3196 1724 3196 1725 3196 1728 3197 1726 3197 1727 3197 1730 3198 1728 3198 1729 3198 1732 3199 1730 3199 1731 3199 1734 3200 1732 3200 1733 3200 1733 3201 1735 3201 1734 3201 1736 3202 1734 3202 1735 3202 1735 3203 1737 3203 1736 3203 1738 3204 1736 3204 1737 3204 1737 3205 1739 3205 1738 3205 1740 3206 1738 3206 1739 3206 1741 3207 1659 3207 1660 3207 1742 3208 1741 3208 1660 3208 1653 3209 1743 3209 1744 3209 1653 3210 1744 3210 1745 3210 1653 3211 1745 3211 1746 3211 1653 3212 1746 3212 1747 3212 1653 3213 1747 3213 1748 3213 1653 3214 1748 3214 1749 3214 1653 3215 1749 3215 1750 3215 1653 3216 1750 3216 1751 3216 1653 3217 1751 3217 1742 3217 1660 3218 1653 3218 1742 3218 1721 3219 1743 3219 1653 3219 1751 3220 1752 3220 1753 3220 1742 3221 1751 3221 1753 3221 1754 3222 1752 3222 1751 3222 1751 3223 1750 3223 1754 3223 1755 3224 1754 3224 1750 3224 1750 3225 1749 3225 1755 3225 1756 3226 1755 3226 1749 3226 1749 3227 1748 3227 1756 3227 1757 3228 1756 3228 1748 3228 1748 3229 1747 3229 1757 3229 1758 3230 1757 3230 1747 3230 1747 3231 1746 3231 1758 3231 1745 3232 1744 3232 1759 3232 1744 3233 1743 3233 1759 3233 1655 3234 1760 3234 1721 3234 1752 3235 1767 3235 1768 3235 1753 3236 1752 3236 1768 3236 1769 3237 1738 3237 1740 3237 1769 3238 1740 3238 1770 3238 1769 3239 1770 3239 1771 3239 1772 3240 1769 3240 1771 3240 1772 3241 1771 3241 1773 3241 1772 3242 1773 3242 1774 3242 1767 3243 1772 3243 1774 3243 1772 3244 1767 3244 1752 3244 1752 3245 1754 3245 1772 3245 1736 3246 1738 3246 1769 3246 1775 3247 1734 3247 1736 3247 1769 3248 1775 3248 1736 3248 1775 3249 1769 3249 1772 3249 1772 3250 1754 3250 1755 3250 1776 3251 1772 3251 1755 3251 1772 3252 1776 3252 1775 3252 1755 3253 1756 3253 1776 3253 1732 3254 1734 3254 1775 3254 1777 3255 1775 3255 1776 3255 1775 3256 1777 3256 1732 3256 1776 3257 1778 3257 1777 3257 1776 3258 1756 3258 1757 3258 1778 3259 1776 3259 1757 3259 1730 3260 1732 3260 1777 3260 1757 3261 1758 3261 1778 3261 1779 3262 1777 3262 1778 3262 1779 3263 1728 3263 1730 3263 1777 3264 1779 3264 1730 3264 1778 3265 1763 3265 1779 3265 1778 3266 1758 3266 1759 3266 1778 3267 1759 3267 1763 3267 1726 3268 1728 3268 1779 3268 1780 3269 1779 3269 1763 3269 1779 3270 1780 3270 1726 3270 1724 3271 1726 3271 1780 3271 1763 3272 1759 3272 1760 3272 1763 3273 1661 3273 1762 3273 1780 3274 1761 3274 1764 3274 1765 3275 1780 3275 1764 3275 1780 3276 1765 3276 1724 3276 1724 3277 1765 3277 1766 3277 1657 3278 1724 3278 1766 3278 1781 3279 1782 3279 1783 3279 1784 3280 1781 3280 1783 3280 1785 3281 1784 3281 1789 3281 1788 3282 1785 3282 1789 3282 1786 3283 1788 3283 1790 3283 1787 3284 1790 3284 1791 3284 1737 3285 1791 3285 1792 3285 1739 3286 1737 3286 1792 3286 1784 3287 1783 3287 1753 3287 1753 3288 1783 3288 1782 3288 1753 3289 1782 3289 1741 3289 1742 3290 1753 3290 1741 3290 1739 3291 1792 3291 1740 3291 1770 3292 1740 3292 1792 3292 1792 3293 1791 3293 1770 3293 1771 3294 1770 3294 1791 3294 1791 3295 1790 3295 1771 3295 1773 3296 1771 3296 1790 3296 1774 3297 1773 3297 1790 3297 1790 3298 1788 3298 1774 3298 1767 3299 1774 3299 1788 3299 1788 3300 1789 3300 1767 3300 1768 3301 1767 3301 1789 3301 1789 3302 1784 3302 1768 3302 1753 3303 1768 3303 1784 3303 1761 3304 1763 3304 1762 3304 1761 3305 1780 3305 1763 3305 1655 3306 1661 3306 1760 3306 1760 3307 1661 3307 1763 3307 1721 3308 1760 3308 1743 3308 1743 3309 1760 3309 1759 3309 1745 3310 1759 3310 1758 3310 1745 3311 1758 3311 1746 3311 1624 3312 1722 3312 1657 3312 1654 3313 1653 3313 1656 3313 1793 3314 1633 3314 1635 3314 1795 3315 1798 3315 1657 3315 1794 3316 1795 3316 1657 3316 1633 3317 1793 3317 1830 3317 1634 3318 1828 3318 1829 3318 1634 3319 1829 3319 1830 3319 1830 3320 1793 3320 1634 3320 1634 3321 1793 3321 1635 3321 1634 3322 1635 3322 1799 3322 1799 3323 1796 3323 1797 3323 1799 3324 1635 3324 1796 3324 1798 3325 1658 3325 1657 3325 1620 3326 1800 3326 1579 3326 1802 3327 1617 3327 1801 3327 1801 3328 1803 3328 1802 3328 1616 3329 1802 3329 1803 3329 1803 3330 1615 3330 1616 3330 1804 3331 1805 3331 1806 3331 1807 3332 1801 3332 1617 3332 1807 3333 1617 3333 1808 3333 1807 3334 1808 3334 1805 3334 1805 3335 1804 3335 1809 3335 1807 3336 1805 3336 1809 3336 1803 3337 1801 3337 1807 3337 1809 3338 1810 3338 1807 3338 1614 3339 1615 3339 1803 3339 1807 3340 1614 3340 1803 3340 1614 3341 1807 3341 1810 3341 1810 3342 1811 3342 1614 3342 1620 3343 1614 3343 1811 3343 1811 3344 1800 3344 1620 3344 1812 3345 1816 3345 1813 3345 1813 3346 1811 3346 1814 3346 1813 3347 1816 3347 1800 3347 1813 3348 1800 3348 1811 3348 1814 3349 1811 3349 1810 3349 1814 3350 1810 3350 1815 3350 1815 3351 1810 3351 1809 3351 1817 3352 1809 3352 1804 3352 1579 3353 1800 3353 1816 3353 1551 3354 1816 3354 1812 3354 1550 3355 1579 3355 1816 3355 1818 3356 1819 3356 1611 3356 1818 3357 1611 3357 1610 3357 1609 3358 1818 3358 1610 3358 1820 3359 1819 3359 1818 3359 1821 3360 1818 3360 1609 3360 1818 3361 1821 3361 1820 3361 1609 3362 1607 3362 1821 3362 1822 3363 1820 3363 1821 3363 1821 3364 1823 3364 1822 3364 1823 3365 1821 3365 1607 3365 1607 3366 1824 3366 1823 3366 1824 3367 1607 3367 1627 3367 1825 3368 1822 3368 1823 3368 1627 3369 1826 3369 1824 3369 1826 3370 1627 3370 1626 3370 1827 3371 1825 3371 1823 3371 1827 3372 1823 3372 1824 3372 1626 3373 1633 3373 1826 3373 1828 3374 1827 3374 1824 3374 1824 3375 1829 3375 1828 3375 1829 3376 1824 3376 1826 3376 1830 3377 1826 3377 1633 3377 1826 3378 1830 3378 1829 3378 1634 3379 1825 3379 1827 3379 1634 3380 1827 3380 1828 3380 1825 3381 1606 3381 1822 3381 1820 3382 1822 3382 1606 3382 1819 3383 1820 3383 1606 3383 1606 3384 1831 3384 1819 3384 1819 3385 1831 3385 1832 3385 1611 3386 1819 3386 1832 3386 1833 3387 1611 3387 1832 3387 1834 3388 1833 3388 1832 3388 1832 3389 1835 3389 1834 3389 1834 3390 1835 3390 1836 3390 1833 3391 1834 3391 1837 3391 1837 3392 1617 3392 1833 3392 1611 3393 1833 3393 1617 3393 1617 3394 1802 3394 1605 3394 1838 3395 1610 3395 1611 3395 1838 3396 1611 3396 1605 3396 1838 3397 1605 3397 1802 3397 1838 3398 1604 3398 1610 3398 1838 3399 1802 3399 1616 3399 1604 3400 1838 3400 1616 3400 1840 3401 1839 3401 1817 3401 1841 3402 1817 3402 1804 3402 1817 3403 1841 3403 1840 3403 1804 3404 1806 3404 1841 3404 1842 3405 1841 3405 1806 3405 1842 3406 1843 3406 1840 3406 1841 3407 1842 3407 1840 3407 1806 3408 1805 3408 1842 3408 1844 3409 1842 3409 1805 3409 1842 3410 1844 3410 1843 3410 1805 3411 1808 3411 1844 3411 1837 3412 1836 3412 1843 3412 1844 3413 1837 3413 1843 3413 1844 3414 1808 3414 1617 3414 1844 3415 1617 3415 1837 3415 1836 3416 1837 3416 1834 3416 1845 3417 1847 3417 1846 3417 1845 3418 1839 3418 1840 3418 1847 3419 1845 3419 1840 3419 1846 3420 1603 3420 1443 3420 1603 3421 1846 3421 1847 3421 1442 3422 1443 3422 1603 3422 1847 3423 1848 3423 1603 3423 1441 3424 1603 3424 1848 3424 1848 3425 1606 3425 1441 3425 1831 3426 1606 3426 1848 3426 1832 3427 1831 3427 1848 3427 1848 3428 1835 3428 1832 3428 1848 3429 1843 3429 1836 3429 1848 3430 1836 3430 1835 3430 1840 3431 1848 3431 1847 3431 1840 3432 1843 3432 1848 3432 1634 3433 1606 3433 1825 3433 1634 3434 1445 3434 1606 3434 1959 3435 1951 3435 1952 3435 1950 3436 1951 3436 1959 3436 1959 3437 1960 3437 1950 3437 1960 3438 1949 3438 1950 3438 1948 3439 1949 3439 1960 3439 1947 3440 1948 3440 1960 3440 1960 3441 1957 3441 1947 3441 1946 3442 1947 3442 1957 3442 1945 3443 1946 3443 1957 3443 1958 3444 1944 3444 1945 3444 1943 3445 1944 3445 1958 3445 1444 3446 1443 3446 1477 3446 1856 3447 1444 3447 1480 3447 1480 3448 1481 3448 1856 3448 1857 3449 1856 3449 1481 3449 1481 3450 1484 3450 1857 3450 1860 3451 1857 3451 1484 3451 1484 3452 1869 3452 1860 3452 1863 3453 1860 3453 1869 3453 1869 3454 1870 3454 1863 3454 1862 3455 1863 3455 1871 3455 1952 3456 1961 3456 1959 3456 1953 3457 1849 3457 1952 3457 1849 3458 1953 3458 1955 3458 1850 3459 1904 3459 1903 3459 1850 3460 1956 3460 1904 3460 1850 3461 1955 3461 1956 3461 1903 3462 1902 3462 1851 3462 1852 3463 1851 3463 1897 3463 1897 3464 1894 3464 1852 3464 1851 3465 1900 3465 1897 3465 1851 3466 1902 3466 1900 3466 1892 3467 1865 3467 1894 3467 1865 3468 1852 3468 1894 3468 1853 3469 1852 3469 1865 3469 1865 3470 1866 3470 1853 3470 1866 3471 1867 3471 1854 3471 1867 3472 1861 3472 1855 3472 1855 3473 1861 3473 1862 3473 1443 3474 1444 3474 1846 3474 1882 3475 1839 3475 1845 3475 1858 3476 1846 3476 1856 3476 1846 3477 1444 3477 1856 3477 1846 3478 1858 3478 1845 3478 1859 3479 1845 3479 1858 3479 1845 3480 1859 3480 1882 3480 1859 3481 1884 3481 1882 3481 1856 3482 1857 3482 1858 3482 1886 3483 1884 3483 1859 3483 1864 3484 1858 3484 1860 3484 1858 3485 1857 3485 1860 3485 1858 3486 1864 3486 1859 3486 1868 3487 1859 3487 1864 3487 1859 3488 1868 3488 1886 3488 1868 3489 1888 3489 1886 3489 1860 3490 1863 3490 1864 3490 1890 3491 1888 3491 1868 3491 1864 3492 1867 3492 1868 3492 1864 3493 1861 3493 1867 3493 1864 3494 1862 3494 1861 3494 1864 3495 1863 3495 1862 3495 1892 3496 1868 3496 1865 3496 1868 3497 1866 3497 1865 3497 1868 3498 1867 3498 1866 3498 1868 3499 1892 3499 1890 3499 1872 3500 1873 3500 1874 3500 1872 3501 1940 3501 1873 3501 1872 3502 1911 3502 1940 3502 1940 3503 1941 3503 1873 3503 1941 3504 1874 3504 1873 3504 1941 3505 1876 3505 1874 3505 1877 3506 1875 3506 1876 3506 1877 3507 1876 3507 1941 3507 1941 3508 1938 3508 1877 3508 1878 3509 1877 3509 1938 3509 1877 3510 1878 3510 1879 3510 1938 3511 1936 3511 1878 3511 1878 3512 1898 3512 1880 3512 1878 3513 1895 3513 1898 3513 1878 3514 1891 3514 1895 3514 1878 3515 1936 3515 1891 3515 1881 3516 1912 3516 1817 3516 1881 3517 1817 3517 1839 3517 1839 3518 1882 3518 1881 3518 1914 3519 1912 3519 1881 3519 1883 3520 1881 3520 1882 3520 1881 3521 1883 3521 1914 3521 1882 3522 1884 3522 1883 3522 1920 3523 1914 3523 1883 3523 1885 3524 1883 3524 1884 3524 1883 3525 1885 3525 1920 3525 1884 3526 1886 3526 1885 3526 1926 3527 1920 3527 1885 3527 1887 3528 1885 3528 1886 3528 1885 3529 1887 3529 1926 3529 1932 3530 1926 3530 1887 3530 1886 3531 1888 3531 1887 3531 1887 3532 1889 3532 1932 3532 1889 3533 1887 3533 1888 3533 1934 3534 1932 3534 1889 3534 1888 3535 1890 3535 1889 3535 1893 3536 1889 3536 1890 3536 1889 3537 1893 3537 1934 3537 1891 3538 1934 3538 1893 3538 1890 3539 1892 3539 1893 3539 1893 3540 1896 3540 1891 3540 1896 3541 1893 3541 1894 3541 1893 3542 1892 3542 1894 3542 1895 3543 1891 3543 1896 3543 1894 3544 1897 3544 1896 3544 1896 3545 1901 3545 1895 3545 1901 3546 1898 3546 1895 3546 1901 3547 1896 3547 1897 3547 1897 3548 1900 3548 1901 3548 1901 3549 1902 3549 1898 3549 1902 3550 1899 3550 1898 3550 1901 3551 1900 3551 1902 3551 1902 3552 1903 3552 1899 3552 1903 3553 1904 3553 1899 3553 1904 3554 1956 3554 1899 3554 1551 3555 1546 3555 1550 3555 1547 3556 1906 3556 1548 3556 1906 3557 1547 3557 1551 3557 1907 3558 1548 3558 1906 3558 1548 3559 1907 3559 1549 3559 1909 3560 1549 3560 1907 3560 1549 3561 1909 3561 1905 3561 1909 3562 1908 3562 1905 3562 1550 3563 1816 3563 1551 3563 1551 3564 1917 3564 1906 3564 1917 3565 1551 3565 1913 3565 1551 3566 1812 3566 1913 3566 1924 3567 1906 3567 1919 3567 1906 3568 1917 3568 1919 3568 1906 3569 1924 3569 1907 3569 1907 3570 1927 3570 1909 3570 1907 3571 1925 3571 1927 3571 1907 3572 1924 3572 1925 3572 1911 3573 1908 3573 1909 3573 1910 3574 1909 3574 1933 3574 1909 3575 1930 3575 1933 3575 1909 3576 1927 3576 1930 3576 1909 3577 1910 3577 1911 3577 1940 3578 1911 3578 1942 3578 1911 3579 1910 3579 1942 3579 1815 3580 1809 3580 1817 3580 1817 3581 1912 3581 1815 3581 1815 3582 1915 3582 1814 3582 1915 3583 1815 3583 1914 3583 1815 3584 1912 3584 1914 3584 1916 3585 1814 3585 1915 3585 1814 3586 1916 3586 1813 3586 1918 3587 1813 3587 1916 3587 1813 3588 1918 3588 1812 3588 1918 3589 1913 3589 1812 3589 1917 3590 1913 3590 1918 3590 1914 3591 1920 3591 1915 3591 1915 3592 1921 3592 1916 3592 1921 3593 1915 3593 1920 3593 1922 3594 1916 3594 1921 3594 1916 3595 1922 3595 1918 3595 1918 3596 1923 3596 1917 3596 1923 3597 1919 3597 1917 3597 1923 3598 1918 3598 1922 3598 1924 3599 1919 3599 1923 3599 1920 3600 1926 3600 1921 3600 1921 3601 1928 3601 1922 3601 1928 3602 1921 3602 1926 3602 1922 3603 1929 3603 1923 3603 1929 3604 1922 3604 1928 3604 1931 3605 1923 3605 1929 3605 1923 3606 1931 3606 1924 3606 1931 3607 1925 3607 1924 3607 1931 3608 1927 3608 1925 3608 1926 3609 1932 3609 1928 3609 1930 3610 1927 3610 1931 3610 1935 3611 1928 3611 1932 3611 1928 3612 1935 3612 1929 3612 1929 3613 1937 3613 1931 3613 1937 3614 1929 3614 1935 3614 1931 3615 1939 3615 1930 3615 1939 3616 1933 3616 1930 3616 1939 3617 1931 3617 1937 3617 1932 3618 1934 3618 1935 3618 1910 3619 1933 3619 1939 3619 1935 3620 1936 3620 1937 3620 1935 3621 1891 3621 1936 3621 1935 3622 1934 3622 1891 3622 1937 3623 1936 3623 1938 3623 1937 3624 1938 3624 1939 3624 1939 3625 1941 3625 1910 3625 1941 3626 1942 3626 1910 3626 1939 3627 1938 3627 1941 3627 1940 3628 1942 3628 1941 3628 1954 3629 1950 3629 1949 3629 1954 3630 1951 3630 1950 3630 1954 3631 1952 3631 1951 3631 1954 3632 1953 3632 1952 3632 1954 3633 1955 3633 1953 3633 1899 3634 1956 3634 1955 3634 1980 3635 1982 3635 1983 3635 1980 3636 1983 3636 1984 3636 1985 3637 1980 3637 1984 3637 1905 3638 1989 3638 1549 3638 1544 3639 1549 3639 1989 3639 1989 3640 2009 3640 1544 3640 1544 3641 1990 3641 1543 3641 1990 3642 1544 3642 2009 3642 2009 3643 2014 3643 1990 3643 1991 3644 1501 3644 1512 3644 1992 3645 1991 3645 1512 3645 1993 3646 1992 3646 1512 3646 1993 3647 1512 3647 1994 3647 1995 3648 1993 3648 1994 3648 1996 3649 1995 3649 1994 3649 1997 3650 1996 3650 1994 3650 1970 3651 1997 3651 1994 3651 1998 3652 1997 3652 1970 3652 1877 3653 1999 3653 1875 3653 2000 3654 1876 3654 1875 3654 2000 3655 1875 3655 1999 3655 2000 3656 1999 3656 2001 3656 1876 3657 1872 3657 1874 3657 1872 3658 1876 3658 2000 3658 1908 3659 1911 3659 1872 3659 2001 3660 2002 3660 2000 3660 2000 3661 2003 3661 1872 3661 2003 3662 2000 3662 2002 3662 2004 3663 1872 3663 2003 3663 1872 3664 2004 3664 1908 3664 1905 3665 1908 3665 2004 3665 2002 3666 2005 3666 2003 3666 2006 3667 2003 3667 2005 3667 2003 3668 2006 3668 2004 3668 2005 3669 2007 3669 2006 3669 2008 3670 1989 3670 1905 3670 2004 3671 2008 3671 1905 3671 2008 3672 2004 3672 2006 3672 2009 3673 1989 3673 2008 3673 2006 3674 2010 3674 2008 3674 2006 3675 2007 3675 2011 3675 2010 3676 2006 3676 2011 3676 2011 3677 2012 3677 2010 3677 2013 3678 2008 3678 2010 3678 2008 3679 2013 3679 2009 3679 2014 3680 2009 3680 2013 3680 2015 3681 2010 3681 2012 3681 2010 3682 2015 3682 2013 3682 2012 3683 2016 3683 2015 3683 2013 3684 2017 3684 2014 3684 2017 3685 2013 3685 2015 3685 2015 3686 2016 3686 2018 3686 1973 3687 2012 3687 2019 3687 2012 3688 1973 3688 1985 3688 2012 3689 1985 3689 1984 3689 2012 3690 1984 3690 2020 3690 2016 3691 2012 3691 2020 3691 2021 3692 1982 3692 2022 3692 1981 3693 2022 3693 1982 3693 2021 3694 2023 3694 1982 3694 1983 3695 1982 3695 2023 3695 2023 3696 2020 3696 1983 3696 1984 3697 1983 3697 2020 3697 2024 3698 2025 3698 1963 3698 1964 3699 1963 3699 2025 3699 2025 3700 2026 3700 1964 3700 1965 3701 1964 3701 2026 3701 2026 3702 2027 3702 1965 3702 1966 3703 1965 3703 2027 3703 2027 3704 2028 3704 1966 3704 1967 3705 1966 3705 2028 3705 2028 3706 2029 3706 1967 3706 1968 3707 1967 3707 2029 3707 2029 3708 2030 3708 1968 3708 1969 3709 1968 3709 2030 3709 2030 3710 1998 3710 1969 3710 1970 3711 1969 3711 1998 3711 1998 3712 2030 3712 1997 3712 2031 3713 1997 3713 2030 3713 2031 3714 2032 3714 1995 3714 2031 3715 1995 3715 1996 3715 1997 3716 2031 3716 1996 3716 2033 3717 2032 3717 2031 3717 2030 3718 2029 3718 2031 3718 2031 3719 2029 3719 2028 3719 2034 3720 2031 3720 2028 3720 2034 3721 2035 3721 2033 3721 2031 3722 2034 3722 2033 3722 2036 3723 2035 3723 2034 3723 2028 3724 2027 3724 2034 3724 2034 3725 2027 3725 2026 3725 2037 3726 2034 3726 2026 3726 2037 3727 2038 3727 2036 3727 2034 3728 2037 3728 2036 3728 2039 3729 2038 3729 2037 3729 2026 3730 2025 3730 2037 3730 2037 3731 2042 3731 2039 3731 2037 3732 2025 3732 2024 3732 2037 3733 2024 3733 2040 3733 2037 3734 2040 3734 2041 3734 2042 3735 2037 3735 2041 3735 2039 3736 2042 3736 2043 3736 2044 3737 2039 3737 2043 3737 1871 3738 2045 3738 2044 3738 2039 3739 2044 3739 2045 3739 2045 3740 2046 3740 2039 3740 2038 3741 2039 3741 2046 3741 2046 3742 2047 3742 2038 3742 2036 3743 2038 3743 2047 3743 2047 3744 2048 3744 2036 3744 2035 3745 2036 3745 2048 3745 2048 3746 2049 3746 2035 3746 2033 3747 2035 3747 2049 3747 2049 3748 2050 3748 2033 3748 2032 3749 2033 3749 2050 3749 2050 3750 1993 3750 2032 3750 1995 3751 2032 3751 1993 3751 1870 3752 2046 3752 2045 3752 1871 3753 1870 3753 2045 3753 2051 3754 2049 3754 2048 3754 2051 3755 2048 3755 2047 3755 2046 3756 2051 3756 2047 3756 2051 3757 2046 3757 1870 3757 2052 3758 1992 3758 1993 3758 2052 3759 1993 3759 2050 3759 2052 3760 2050 3760 2049 3760 2052 3761 2049 3761 2051 3761 1870 3762 1869 3762 2051 3762 1991 3763 1992 3763 2052 3763 2051 3764 1869 3764 1484 3764 1483 3765 2051 3765 1484 3765 2051 3766 1483 3766 2052 3766 1482 3767 1501 3767 1991 3767 2052 3768 1482 3768 1991 3768 1482 3769 2052 3769 1483 3769 1502 3770 1501 3770 1482 3770 2053 3771 1855 3771 1862 3771 1855 3772 1854 3772 1867 3772 1854 3773 1853 3773 1866 3773 1851 3774 1850 3774 1903 3774 2024 3775 1962 3775 2054 3775 1963 3776 1962 3776 2024 3776 2044 3777 2043 3777 2053 3777 2055 3778 2053 3778 2043 3778 2043 3779 2042 3779 2055 3779 2056 3780 2055 3780 2042 3780 2042 3781 2041 3781 2056 3781 2057 3782 2056 3782 2041 3782 2041 3783 2040 3783 2057 3783 2058 3784 2057 3784 2040 3784 2040 3785 2024 3785 2058 3785 2054 3786 2058 3786 2024 3786 2053 3787 1862 3787 2044 3787 1871 3788 2044 3788 1862 3788 1863 3789 1870 3789 1871 3789 2059 3790 2060 3790 2061 3790 2007 3791 2062 3791 2063 3791 2011 3792 2007 3792 2063 3792 2064 3793 2059 3793 2061 3793 2064 3794 2061 3794 2065 3794 2062 3795 2064 3795 2065 3795 2064 3796 2062 3796 2007 3796 2066 3797 2059 3797 2064 3797 2066 3798 1988 3798 2059 3798 2007 3799 2005 3799 2064 3799 2064 3800 2067 3800 2066 3800 2067 3801 2064 3801 2005 3801 1987 3802 1988 3802 2066 3802 2066 3803 2068 3803 1987 3803 2068 3804 2066 3804 2067 3804 2005 3805 2002 3805 2067 3805 1986 3806 1987 3806 2068 3806 2067 3807 2069 3807 2068 3807 2069 3808 2067 3808 2002 3808 2002 3809 2001 3809 2069 3809 2070 3810 2068 3810 2069 3810 1979 3811 1978 3811 2060 3811 2061 3812 2060 3812 1978 3812 1978 3813 1977 3813 2061 3813 2065 3814 2061 3814 1977 3814 1977 3815 1976 3815 2065 3815 2062 3816 2065 3816 1976 3816 1976 3817 1975 3817 2062 3817 2063 3818 2062 3818 1975 3818 1974 3819 2011 3819 2063 3819 1975 3820 1974 3820 2063 3820 2012 3821 2011 3821 1974 3821 1974 3822 1972 3822 2012 3822 1972 3823 1971 3823 2012 3823 2012 3824 1971 3824 2019 3824 1799 3825 1994 3825 1512 3825 1799 3826 1512 3826 1602 3826 2089 3827 2071 3827 2143 3827 2143 3828 2071 3828 2148 3828 2148 3829 2071 3829 2078 3829 2120 3830 2148 3830 2078 3830 2122 3831 2120 3831 2078 3831 2122 3832 2078 3832 2080 3832 2123 3833 2122 3833 2080 3833 2123 3834 2080 3834 2082 3834 2125 3835 2123 3835 2082 3835 2125 3836 2082 3836 2084 3836 2128 3837 2125 3837 2084 3837 2128 3838 2084 3838 2085 3838 2130 3839 2128 3839 2085 3839 2130 3840 2085 3840 2086 3840 2130 3841 2086 3841 2131 3841 2133 3842 2131 3842 2086 3842 2091 3843 2092 3843 2072 3843 2100 3844 2158 3844 2099 3844 2153 3845 2099 3845 2158 3845 2071 3846 2076 3846 2078 3846 2087 3847 2090 3847 2076 3847 2076 3848 2071 3848 2087 3848 2071 3849 2088 3849 2087 3849 2071 3850 2089 3850 2088 3850 2090 3851 2091 3851 2072 3851 2072 3852 2076 3852 2090 3852 2072 3853 2093 3853 2073 3853 2072 3854 2092 3854 2093 3854 2074 3855 2072 3855 2073 3855 2072 3856 2074 3856 2076 3856 2074 3857 2075 3857 2076 3857 2095 3858 2094 3858 2077 3858 2077 3859 2073 3859 2095 3859 2073 3860 2093 3860 2095 3860 2073 3861 2077 3861 2074 3861 2077 3862 2075 3862 2074 3862 2077 3863 2076 3863 2075 3863 2078 3864 2076 3864 2077 3864 2077 3865 2079 3865 2078 3865 2080 3866 2078 3866 2079 3866 2079 3867 2081 3867 2080 3867 2082 3868 2080 3868 2081 3868 2084 3869 2082 3869 2083 3869 2101 3870 2085 3870 2084 3870 2086 3871 2085 3871 2101 3871 2120 3872 2121 3872 1524 3872 1524 3873 2137 3873 2120 3873 2137 3874 2148 3874 2120 3874 2148 3875 2137 3875 2147 3875 2143 3876 2145 3876 2146 3876 2148 3877 2145 3877 2143 3877 2115 3878 2110 3878 2114 3878 2110 3879 2113 3879 2114 3879 2149 3880 2113 3880 2110 3880 2110 3881 2109 3881 2149 3881 2139 3882 2149 3882 2109 3882 2109 3883 2108 3883 2139 3883 2140 3884 2139 3884 2108 3884 2108 3885 2107 3885 2140 3885 2142 3886 2140 3886 2107 3886 2107 3887 2105 3887 2088 3887 2088 3888 2142 3888 2107 3888 2105 3889 2087 3889 2088 3889 2105 3890 2090 3890 2087 3890 2142 3891 2089 3891 2143 3891 2142 3892 2088 3892 2089 3892 2105 3893 2104 3893 2090 3893 2091 3894 2090 3894 2104 3894 2104 3895 2102 3895 2091 3895 2102 3896 2092 3896 2091 3896 2093 3897 2092 3897 2095 3897 2092 3898 2102 3898 2095 3898 2103 3899 2095 3899 2102 3899 2099 3900 2153 3900 2097 3900 2154 3901 2097 3901 2153 3901 2112 3902 2096 3902 2156 3902 2155 3903 2156 3903 2096 3903 2096 3904 2097 3904 2155 3904 2154 3905 2155 3905 2097 3905 2098 3906 2099 3906 2021 3906 2020 3907 2096 3907 2112 3907 2020 3908 2097 3908 2096 3908 2020 3909 2099 3909 2097 3909 2020 3910 2023 3910 2099 3910 2023 3911 2021 3911 2099 3911 2106 3912 2103 3912 2104 3912 2103 3913 2102 3913 2104 3913 2104 3914 2105 3914 2106 3914 2105 3915 2107 3915 2106 3915 2111 3916 2106 3916 2107 3916 2107 3917 2108 3917 2111 3917 2111 3918 2108 3918 2109 3918 2109 3919 2110 3919 2111 3919 2111 3920 2115 3920 2160 3920 2111 3921 2110 3921 2115 3921 2115 3922 2018 3922 2112 3922 2112 3923 2160 3923 2115 3923 2112 3924 2157 3924 2160 3924 2112 3925 2159 3925 2157 3925 2156 3926 2159 3926 2112 3926 2020 3927 2112 3927 2016 3927 2112 3928 2018 3928 2016 3928 2149 3929 2151 3929 2113 3929 2116 3930 2113 3930 2151 3930 2113 3931 2116 3931 2114 3931 2114 3932 2117 3932 2115 3932 2117 3933 2114 3933 2116 3933 2018 3934 2115 3934 2117 3934 2151 3935 2014 3935 2116 3935 2014 3936 2017 3936 2116 3936 2116 3937 2017 3937 2117 3937 2015 3938 2117 3938 2017 3938 2117 3939 2015 3939 2018 3939 1530 3940 2118 3940 1582 3940 1530 3941 2134 3941 2118 3941 1530 3942 1524 3942 2134 3942 2119 3943 1582 3943 2118 3943 2119 3944 2118 3944 2135 3944 2118 3945 2134 3945 2135 3945 2122 3946 2121 3946 2120 3946 2135 3947 2134 3947 2121 3947 2124 3948 2121 3948 2123 3948 2121 3949 2122 3949 2123 3949 2121 3950 2124 3950 2135 3950 2123 3951 2125 3951 2124 3951 2124 3952 2126 3952 2135 3952 2126 3953 2136 3953 2135 3953 2126 3954 2124 3954 2125 3954 2127 3955 2126 3955 2125 3955 2125 3956 2128 3956 2127 3956 2129 3957 2127 3957 2128 3957 2128 3958 2130 3958 2129 3958 2132 3959 2129 3959 2130 3959 2133 3960 2132 3960 2131 3960 2132 3961 2130 3961 2131 3961 2121 3962 2134 3962 1524 3962 1524 3963 2147 3963 2137 3963 2149 3964 2139 3964 2138 3964 2141 3965 2138 3965 2139 3965 2141 3966 1531 3966 2138 3966 2139 3967 2140 3967 2141 3967 1514 3968 1531 3968 2141 3968 2144 3969 2141 3969 2142 3969 2141 3970 2140 3970 2142 3970 2141 3971 2144 3971 1514 3971 1517 3972 1514 3972 2144 3972 2142 3973 2143 3973 2144 3973 2144 3974 2146 3974 1517 3974 2144 3975 2143 3975 2146 3975 1521 3976 1517 3976 2148 3976 1517 3977 2145 3977 2148 3977 1517 3978 2146 3978 2145 3978 1525 3979 1521 3979 2147 3979 1521 3980 2148 3980 2147 3980 1525 3981 2147 3981 1524 3981 1531 3982 1534 3982 2138 3982 2150 3983 2138 3983 1534 3983 2152 3984 2138 3984 2150 3984 2152 3985 2149 3985 2138 3985 2151 3986 2149 3986 2152 3986 1534 3987 1537 3987 2150 3987 1539 3988 2150 3988 1537 3988 2150 3989 1539 3989 2152 3989 2152 3990 1990 3990 2151 3990 1990 3991 2014 3991 2151 3991 1990 3992 2152 3992 1539 3992 1539 3993 1543 3993 1990 3993 2158 3994 2159 3994 2153 3994 2159 3995 2154 3995 2153 3995 2159 3996 2155 3996 2154 3996 2159 3997 2156 3997 2155 3997 2161 3998 2159 3998 2158 3998 2180 3999 2133 3999 2101 3999 2201 4000 2162 4000 2199 4000 2172 4001 2162 4001 2201 4001 2201 4002 2174 4002 2172 4002 2201 4003 2175 4003 2174 4003 2185 4004 2199 4004 2162 4004 2208 4005 2185 4005 2207 4005 2207 4006 2185 4006 2162 4006 2206 4007 2207 4007 2162 4007 2172 4008 2206 4008 2162 4008 2206 4009 2172 4009 2205 4009 2205 4010 2172 4010 2173 4010 2166 4011 2164 4011 2168 4011 2167 4012 2168 4012 2164 4012 2164 4013 2163 4013 2167 4013 2188 4014 2167 4014 2163 4014 2165 4015 2167 4015 2188 4015 2218 4016 2165 4016 2188 4016 2175 4017 2169 4017 2170 4017 2170 4018 2169 4018 2166 4018 2170 4019 2173 4019 2171 4019 2170 4020 2204 4020 2173 4020 2204 4021 2205 4021 2173 4021 2204 4022 2170 4022 2166 4022 2166 4023 2217 4023 2204 4023 2217 4024 2165 4024 2218 4024 2217 4025 2167 4025 2165 4025 2217 4026 2166 4026 2168 4026 2168 4027 2167 4027 2217 4027 2174 4028 2175 4028 2171 4028 2175 4029 2170 4029 2171 4029 2171 4030 2173 4030 2174 4030 2173 4031 2172 4031 2174 4031 2221 4032 2200 4032 2177 4032 2177 4033 2176 4033 2221 4033 2177 4034 2179 4034 2176 4034 2179 4035 2180 4035 2176 4035 2119 4036 2194 4036 1582 4036 2135 4037 2136 4037 2119 4037 2198 4038 2194 4038 2119 4038 2178 4039 2119 4039 2136 4039 2119 4040 2178 4040 2198 4040 2178 4041 2200 4041 2198 4041 2178 4042 2177 4042 2200 4042 2136 4043 2181 4043 2178 4043 2179 4044 2178 4044 2181 4044 2178 4045 2179 4045 2177 4045 2181 4046 2182 4046 2179 4046 2180 4047 2179 4047 2182 4047 2127 4048 2136 4048 2126 4048 2127 4049 2129 4049 2181 4049 2183 4050 2181 4050 2129 4050 2129 4051 2132 4051 2183 4051 2132 4052 2182 4052 2183 4052 2132 4053 2133 4053 2182 4053 2180 4054 2182 4054 2133 4054 2136 4055 2127 4055 2181 4055 2182 4056 2181 4056 2183 4056 2215 4057 2184 4057 2216 4057 2199 4058 2185 4058 2197 4058 2186 4059 2197 4059 2185 4059 2186 4060 2196 4060 2197 4060 2186 4061 2185 4061 2209 4061 2185 4062 2208 4062 2209 4062 2209 4063 2210 4063 2186 4063 2195 4064 2196 4064 2186 4064 2187 4065 2186 4065 2211 4065 2186 4066 2210 4066 2211 4066 2186 4067 2187 4067 2195 4067 2187 4068 2193 4068 2195 4068 2211 4069 2212 4069 2187 4069 2192 4070 2193 4070 2187 4070 2187 4071 2213 4071 1598 4071 2187 4072 2212 4072 2213 4072 2187 4073 1598 4073 2192 4073 2218 4074 2188 4074 2219 4074 2220 4075 2188 4075 2189 4075 2214 4076 2190 4076 2215 4076 1582 4077 2194 4077 1598 4077 2194 4078 2191 4078 1598 4078 2194 4079 2192 4079 2191 4079 2194 4080 2193 4080 2192 4080 2195 4081 2193 4081 2194 4081 2194 4082 2198 4082 2195 4082 2198 4083 2196 4083 2195 4083 2198 4084 2197 4084 2196 4084 2199 4085 2197 4085 2198 4085 2198 4086 2200 4086 2199 4086 2201 4087 2199 4087 2200 4087 2200 4088 2221 4088 2201 4088 2221 4089 2202 4089 2201 4089 2221 4090 2203 4090 2202 4090 1636 4091 2218 4091 2219 4091 1602 4092 1669 4092 1634 4092 1669 4093 1602 4093 2222 4093 1963 4094 1960 4094 1959 4094 1963 4095 1959 4095 1961 4095 1957 4096 1960 4096 1963 4096 1957 4097 1970 4097 2223 4097 1970 4098 2224 4098 2223 4098 2225 4099 2223 4099 2224 4099 1799 4100 1797 4100 2225 4100 2224 4101 1799 4101 2225 4101 1799 4102 1602 4102 1634 4102 2218 4103 1636 4103 2227 4103 2217 4104 2218 4104 2227 4104 2226 4105 1584 4105 1583 4105 2228 4106 1599 4106 2226 4106 1583 4107 2228 4107 2226 4107 1599 4108 2228 4108 2229 4108 1599 4109 2229 4109 2230 4109 1599 4110 2230 4110 2231 4110 1599 4111 2231 4111 2232 4111 1599 4112 2232 4112 2233 4112 1667 4113 1599 4113 2233 4113 2233 4114 2234 4114 1667 4114 1667 4115 2234 4115 2235 4115 1667 4116 2235 4116 2236 4116 1667 4117 2236 4117 2227 4117 1636 4118 1667 4118 2227 4118 2213 4119 1583 4119 1598 4119 2228 4120 1583 4120 2213 4120 2213 4121 2212 4121 2228 4121 2228 4122 2212 4122 2211 4122 2229 4123 2228 4123 2211 4123 2211 4124 2210 4124 2229 4124 2230 4125 2229 4125 2210 4125 2210 4126 2209 4126 2230 4126 2231 4127 2230 4127 2209 4127 2208 4128 2231 4128 2209 4128 2232 4129 2231 4129 2208 4129 2232 4130 2208 4130 2207 4130 2233 4131 2232 4131 2207 4131 2207 4132 2206 4132 2233 4132 2234 4133 2233 4133 2206 4133 2234 4134 2206 4134 2205 4134 2234 4135 2205 4135 2235 4135 2204 4136 2235 4136 2205 4136 2236 4137 2235 4137 2204 4137 2236 4138 2204 4138 2217 4138 2227 4139 2236 4139 2217 4139 1600 4140 1599 4140 1667 4140 1598 4141 1583 4141 1528 4141 1957 4142 1958 4142 1945 4142 1599 4143 1584 4143 2226 4143 1962 4144 1963 4144 1961 4144 1957 4145 1963 4145 1964 4145 1957 4146 1964 4146 1965 4146 1957 4147 1965 4147 1966 4147 1957 4148 1966 4148 1967 4148 1957 4149 1967 4149 1968 4149 1957 4150 1968 4150 1969 4150 1957 4151 1969 4151 1970 4151 1971 4152 1972 4152 1973 4152 1973 4153 1972 4153 1974 4153 1973 4154 1974 4154 1975 4154 1973 4155 1975 4155 1976 4155 1973 4156 1976 4156 1977 4156 1973 4157 1977 4157 1978 4157 1973 4158 1978 4158 1979 4158 1973 4159 1979 4159 2237 4159 1973 4160 2237 4160 2238 4160 1973 4161 2238 4161 2239 4161 1973 4162 2239 4162 2240 4162 2244 4163 2242 4163 2243 4163 2244 4164 2219 4164 2220 4164 2242 4165 2244 4165 2220 4165 2244 4166 1636 4166 2219 4166 2248 4167 2249 4167 2160 4167 2250 4168 2249 4168 2248 4168 2251 4169 2252 4169 2250 4169 2214 4170 2215 4170 2216 4170 2214 4171 2253 4171 2190 4171 2253 4172 2255 4172 2254 4172 2255 4173 2220 4173 2189 4173 2220 4174 2219 4174 2188 4174 2157 4175 2159 4175 2161 4175 2160 4176 2157 4176 2247 4176 1973 4177 2241 4177 1985 4177 2258 4178 2257 4178 2252 4178 2242 4179 2259 4179 2256 4179 2257 4180 2256 4180 2259 4180 2252 4181 2261 4181 2250 4181 2260 4182 2250 4182 2261 4182 2261 4183 2214 4183 2260 4183 2216 4184 2260 4184 2214 4184 2262 4185 2214 4185 2261 4185 2261 4186 2252 4186 2257 4186 2262 4187 2261 4187 2257 4187 2253 4188 2214 4188 2262 4188 2257 4189 2259 4189 2262 4189 2262 4190 2259 4190 2253 4190 2255 4191 2253 4191 2259 4191 2259 4192 2242 4192 2255 4192 2220 4193 2255 4193 2242 4193 1971 4194 1973 4194 2019 4194 2249 4195 2111 4195 2160 4195 2101 4196 2264 4196 2263 4196 2264 4197 2265 4197 2263 4197 2265 4198 2266 4198 2263 4198 2249 4199 2263 4199 2111 4199 2106 4200 2094 4200 2095 4200 2111 4201 2266 4201 2106 4201 2111 4202 2263 4202 2266 4202 2106 4203 2095 4203 2103 4203 2224 4204 1970 4204 1994 4204 2083 4205 2101 4205 2084 4205 2081 4206 2083 4206 2082 4206 2079 4207 2077 4207 2094 4207 2094 4208 2267 4208 2079 4208 2081 4209 2079 4209 2267 4209 2265 4210 2083 4210 2081 4210 2267 4211 2265 4211 2081 4211 2083 4212 2265 4212 2264 4212 2101 4213 2083 4213 2264 4213 2265 4214 2267 4214 2266 4214 2133 4215 2086 4215 2101 4215 2106 4216 2266 4216 2267 4216 2106 4217 2267 4217 2094 4217 2224 4218 1994 4218 1799 4218 2201 4219 2298 4219 2175 4219 2298 4220 2270 4220 2175 4220 2184 4221 2270 4221 2298 4221 2215 4222 2270 4222 2184 4222 2166 4223 2269 4223 2164 4223 2169 4224 2269 4224 2166 4224 2269 4225 2163 4225 2164 4225 2268 4226 2163 4226 2269 4226 2299 4227 2268 4227 2269 4227 2190 4228 2254 4228 2269 4228 2254 4229 2299 4229 2269 4229 2223 4230 2225 4230 2285 4230 2225 4231 2286 4231 2285 4231 2225 4232 1797 4232 2286 4232 2223 4233 2283 4233 2282 4233 2223 4234 2281 4234 2283 4234 2223 4235 2280 4235 2281 4235 2223 4236 2297 4236 2280 4236 2223 4237 2296 4237 2297 4237 2223 4238 2294 4238 2296 4238 2223 4239 2292 4239 2294 4239 2223 4240 2289 4240 2292 4240 2223 4241 2285 4241 2289 4241 2163 4242 2268 4242 2188 4242 2268 4243 2299 4243 2188 4243 2189 4244 2188 4244 2299 4244 2269 4245 2215 4245 2190 4245 2269 4246 2270 4246 2215 4246 2269 4247 2169 4247 2270 4247 2175 4248 2270 4248 2169 4248 2300 4249 2271 4249 1794 4249 2277 4250 1794 4250 2271 4250 2271 4251 2272 4251 2277 4251 2279 4252 2277 4252 2272 4252 2272 4253 2273 4253 2279 4253 2293 4254 2279 4254 2273 4254 2273 4255 2284 4255 2293 4255 1796 4256 1629 4256 2302 4256 1629 4257 2304 4257 2302 4257 2274 4258 2304 4258 1623 4258 2304 4259 1629 4259 1623 4259 2274 4260 2307 4260 2304 4260 2287 4261 2306 4261 2308 4261 2275 4262 2307 4262 2274 4262 2275 4263 2308 4263 2307 4263 2275 4264 2287 4264 2308 4264 1623 4265 1658 4265 2274 4265 2276 4266 2274 4266 1798 4266 2274 4267 1658 4267 1798 4267 2274 4268 2276 4268 2275 4268 2275 4269 2278 4269 2287 4269 2278 4270 2288 4270 2287 4270 2278 4271 2275 4271 2276 4271 1798 4272 1795 4272 2276 4272 2276 4273 1794 4273 2277 4273 2276 4274 1795 4274 1794 4274 2276 4275 2277 4275 2278 4275 2291 4276 2288 4276 2278 4276 2278 4277 2277 4277 2279 4277 2278 4278 2279 4278 2291 4278 2291 4279 2279 4279 2293 4279 2293 4280 2284 4280 2295 4280 2306 4281 2285 4281 2305 4281 2285 4282 2303 4282 2305 4282 2285 4283 2286 4283 2303 4283 2286 4284 1797 4284 2303 4284 2285 4285 2306 4285 2287 4285 2290 4286 2287 4286 2288 4286 2287 4287 2290 4287 2285 4287 2289 4288 2285 4288 2290 4288 2288 4289 2291 4289 2290 4289 2292 4290 2289 4290 2290 4290 2292 4291 2290 4291 2291 4291 2291 4292 2293 4292 2292 4292 2294 4293 2292 4293 2293 4293 2293 4294 2295 4294 2294 4294 2296 4295 2294 4295 2295 4295 2297 4296 2296 4296 2295 4296 1657 4297 1766 4297 1143 4297 1142 4298 1766 4298 1765 4298 1765 4299 1764 4299 1141 4299 1761 4300 1140 4300 1764 4300 1139 4301 1761 4301 1762 4301 1762 4302 1661 4302 1138 4302 2298 4303 2202 4303 2203 4303 2202 4304 2298 4304 2201 4304 1598 4305 2191 4305 2192 4305 2255 4306 2189 4306 2299 4306 2299 4307 2254 4307 2255 4307 2253 4308 2254 4308 2190 4308 1629 4309 1796 4309 1635 4309 1796 4310 2302 4310 1797 4310 2303 4311 1797 4311 2302 4311 2302 4312 2304 4312 2303 4312 2305 4313 2303 4313 2304 4313 2306 4314 2305 4314 2307 4314 2305 4315 2304 4315 2307 4315 2308 4316 2306 4316 2307 4316 1428 4317 2313 4317 1144 4317 1144 4318 2313 4318 2314 4318 1144 4319 2314 4319 2315 4319 1144 4320 2315 4320 2316 4320 1144 4321 2316 4321 2317 4321 1144 4322 2317 4322 2318 4322 1144 4323 2318 4323 2319 4323 1144 4324 2319 4324 2320 4324 1143 4325 1144 4325 2320 4325 1143 4326 2320 4326 2321 4326 1143 4327 2321 4327 2322 4327 1143 4328 2322 4328 2323 4328 1143 4329 2323 4329 2324 4329 1143 4330 2324 4330 2325 4330 1143 4331 2325 4331 2300 4331 1143 4332 2300 4332 1794 4332 1657 4333 1143 4333 1794 4333 2312 4334 1146 4334 1654 4334 1661 4335 1654 4335 1146 4335 1146 4336 1138 4336 1661 4336 1139 4337 1762 4337 1138 4337 1139 4338 1140 4338 1761 4338 1140 4339 1141 4339 1764 4339 1141 4340 1142 4340 1765 4340 1766 4341 1142 4341 1143 4341 2326 4342 2327 4342 2328 4342 2326 4343 2328 4343 2329 4343 2330 4344 2326 4344 2329 4344 2331 4345 2327 4345 2326 4345 2332 4346 2333 4346 2331 4346 2326 4347 2332 4347 2331 4347 2334 4348 2333 4348 2332 4348 2332 4349 2310 4349 2334 4349 2335 4350 2334 4350 2310 4350 2336 4351 2335 4351 2310 4351 2337 4352 2336 4352 2310 4352 2310 4353 2309 4353 2337 4353 2338 4354 2309 4354 2310 4354 2339 4355 2340 4355 2338 4355 2310 4356 2339 4356 2338 4356 2340 4357 2341 4357 2338 4357 2342 4358 2343 4358 2344 4358 2343 4359 2345 4359 2344 4359 2345 4360 2346 4360 2344 4360 2344 4361 2346 4361 2347 4361 2348 4362 2309 4362 2338 4362 2338 4363 2341 4363 2342 4363 2338 4364 2342 4364 2344 4364 2348 4365 2338 4365 2344 4365 2344 4366 2347 4366 2349 4366 2348 4367 2344 4367 2350 4367 2284 4368 2351 4368 2352 4368 2283 4369 2352 4369 2351 4369 2282 4370 2283 4370 2351 4370 2351 4371 2353 4371 2282 4371 2354 4372 2282 4372 2353 4372 2353 4373 2330 4373 2354 4373 2354 4374 2330 4374 2329 4374 2328 4375 2354 4375 2329 4375 2295 4376 2352 4376 2283 4376 2352 4377 2295 4377 2284 4377 2283 4378 2281 4378 2295 4378 2281 4379 2280 4379 2295 4379 2280 4380 2297 4380 2295 4380 2355 4381 2330 4381 2353 4381 2355 4382 2353 4382 2351 4382 2351 4383 2284 4383 2273 4383 2355 4384 2351 4384 2273 4384 2356 4385 2330 4385 2355 4385 2355 4386 2357 4386 2356 4386 2357 4387 2355 4387 2273 4387 2273 4388 2272 4388 2357 4388 2358 4389 2356 4389 2357 4389 2272 4390 2271 4390 2357 4390 2357 4391 2359 4391 2358 4391 2359 4392 2357 4392 2271 4392 2359 4393 2325 4393 2358 4393 2325 4394 2359 4394 2271 4394 2322 4395 2358 4395 2325 4395 2271 4396 2300 4396 2325 4396 2325 4397 2324 4397 2323 4397 2325 4398 2323 4398 2322 4398 2356 4399 2310 4399 2332 4399 2356 4400 2332 4400 2326 4400 2330 4401 2356 4401 2326 4401 2360 4402 2310 4402 2356 4402 2356 4403 2358 4403 2360 4403 2361 4404 2360 4404 2358 4404 2358 4405 2322 4405 2361 4405 2361 4406 2322 4406 2321 4406 2361 4407 2321 4407 2320 4407 1130 4408 1407 4408 1428 4408 2365 4409 2366 4409 2363 4409 2364 4410 2365 4410 2363 4410 2367 4411 2368 4411 2366 4411 2365 4412 2367 4412 2366 4412 2368 4413 2367 4413 2369 4413 2370 4414 2368 4414 2369 4414 2371 4415 2372 4415 2370 4415 2369 4416 2371 4416 2370 4416 2373 4417 2372 4417 2371 4417 2346 4418 2373 4418 2347 4418 2374 4419 2347 4419 2373 4419 2371 4420 2374 4420 2373 4420 2347 4421 2374 4421 2349 4421 2375 4422 2318 4422 2317 4422 2375 4423 2317 4423 2316 4423 2375 4424 2316 4424 2315 4424 2376 4425 2375 4425 2315 4425 2376 4426 2342 4426 2341 4426 2376 4427 2341 4427 2340 4427 2376 4428 2340 4428 2339 4428 2376 4429 2339 4429 2375 4429 2315 4430 2314 4430 2376 4430 2343 4431 2342 4431 2376 4431 2376 4432 2314 4432 2313 4432 2376 4433 2313 4433 1428 4433 2376 4434 1428 4434 2377 4434 2377 4435 2346 4435 2345 4435 2377 4436 2345 4436 2343 4436 2376 4437 2377 4437 2343 4437 2373 4438 2370 4438 2372 4438 2378 4439 2368 4439 2373 4439 2373 4440 2379 4440 2378 4440 2379 4441 2373 4441 2346 4441 2380 4442 2378 4442 2379 4442 2381 4443 2380 4443 2379 4443 2379 4444 2382 4444 2381 4444 2382 4445 2379 4445 2377 4445 2383 4446 2381 4446 2382 4446 2382 4447 2377 4447 1428 4447 2384 4448 2383 4448 2382 4448 2382 4449 1407 4449 2384 4449 1407 4450 2382 4450 1428 4450 1408 4451 2384 4451 1407 4451 2366 4452 2385 4452 2363 4452 2385 4453 2366 4453 2368 4453 2368 4454 2378 4454 2385 4454 1404 4455 2363 4455 2385 4455 2363 4456 1404 4456 2364 4456 2378 4457 2380 4457 2385 4457 1410 4458 2364 4458 1404 4458 2380 4459 2381 4459 2385 4459 1406 4460 2385 4460 2381 4460 2385 4461 1406 4461 1404 4461 2381 4462 2383 4462 1406 4462 2383 4463 2384 4463 1406 4463 1405 4464 1404 4464 1406 4464 2384 4465 1408 4465 1406 4465 1282 4466 2364 4466 1410 4466 2386 4467 2365 4467 2364 4467 2386 4468 2364 4468 1282 4468 2367 4469 2365 4469 2386 4469 1282 4470 2362 4470 2386 4470 2310 4471 2360 4471 2339 4471 2375 4472 2339 4472 2360 4472 2360 4473 2361 4473 2375 4473 2318 4474 2375 4474 2361 4474 2319 4475 2318 4475 2361 4475 2361 4476 2320 4476 2319 4476 2223 4477 2282 4477 2354 4477 2223 4478 2354 4478 2328 4478 2223 4479 2328 4479 2327 4479 2223 4480 2327 4480 2331 4480 2223 4481 2331 4481 2333 4481 2223 4482 2333 4482 2334 4482 2223 4483 2334 4483 2335 4483 2223 4484 2335 4484 2336 4484 2223 4485 2336 4485 2337 4485 2309 4486 2223 4486 2337 4486 2346 4487 2377 4487 2379 4487 2392 4488 2391 4488 2301 4488 2395 4489 1383 4489 1384 4489 2395 4490 1384 4490 1382 4490 2395 4491 1382 4491 1381 4491 2395 4492 1381 4492 1380 4492 2395 4493 1256 4493 1383 4493 1227 4494 2399 4494 2400 4494 1227 4495 2400 4495 2401 4495 1227 4496 2401 4496 2402 4496 2403 4497 1227 4497 2402 4497 1229 4498 2410 4498 2409 4498 1228 4499 1229 4499 2409 4499 2411 4500 2410 4500 1229 4500 1229 4501 1230 4501 2411 4501 2412 4502 2411 4502 1230 4502 1230 4503 1231 4503 2412 4503 2413 4504 2412 4504 1231 4504 1231 4505 1232 4505 2413 4505 2413 4506 1232 4506 1233 4506 2414 4507 2413 4507 1233 4507 2415 4508 2414 4508 1233 4508 2395 4509 2415 4509 1233 4509 1256 4510 2395 4510 1233 4510 2409 4511 2416 4511 2408 4511 2407 4512 2408 4512 2416 4512 2416 4513 2417 4513 2407 4513 2406 4514 2407 4514 2417 4514 2417 4515 2418 4515 2406 4515 2405 4516 2406 4516 2418 4516 2419 4517 2404 4517 2405 4517 2418 4518 2419 4518 2405 4518 2396 4519 2404 4519 2419 4519 2419 4520 2420 4520 2396 4520 2397 4521 2396 4521 2420 4521 2420 4522 2421 4522 2397 4522 2398 4523 2397 4523 2421 4523 2422 4524 2399 4524 2398 4524 2421 4525 2422 4525 2398 4525 2400 4526 2399 4526 2422 4526 2422 4527 2423 4527 2400 4527 2401 4528 2400 4528 2423 4528 2423 4529 2424 4529 2401 4529 2402 4530 2401 4530 2424 4530 2424 4531 2403 4531 2402 4531 2391 4532 2425 4532 2426 4532 2428 4533 2426 4533 2427 4533 2429 4534 2428 4534 2430 4534 2429 4535 2431 4535 2432 4535 2433 4536 2429 4536 2432 4536 2432 4537 2434 4537 2433 4537 2433 4538 2434 4538 2435 4538 2436 4539 2433 4539 2435 4539 2436 4540 2435 4540 2437 4540 2438 4541 2436 4541 2437 4541 2437 4542 2439 4542 2438 4542 2440 4543 2438 4543 2439 4543 2439 4544 2441 4544 2440 4544 2456 4545 2454 4545 2455 4545 2455 4546 2454 4546 2457 4546 2455 4547 2457 4547 2390 4547 2455 4548 2390 4548 2453 4548 2455 4549 2453 4549 2458 4549 2458 4550 2459 4550 2455 4550 2455 4551 2459 4551 2460 4551 2455 4552 2460 4552 2461 4552 2455 4553 2461 4553 2462 4553 2455 4554 2462 4554 2463 4554 2455 4555 2413 4555 2414 4555 2455 4556 2414 4556 2415 4556 2455 4557 2415 4557 2395 4557 2455 4558 2395 4558 2393 4558 2455 4559 2393 4559 2464 4559 2455 4560 2464 4560 2456 4560 2463 4561 2465 4561 2455 4561 2455 4562 2465 4562 2412 4562 2412 4563 2413 4563 2455 4563 2465 4564 2466 4564 2412 4564 2411 4565 2412 4565 2466 4565 2466 4566 2467 4566 2411 4566 2410 4567 2411 4567 2467 4567 2467 4568 2468 4568 2410 4568 2410 4569 2468 4569 2403 4569 2409 4570 2410 4570 2403 4570 2403 4571 2424 4571 2409 4571 2416 4572 2409 4572 2424 4572 2424 4573 2423 4573 2416 4573 2417 4574 2416 4574 2423 4574 2423 4575 2422 4575 2417 4575 2418 4576 2417 4576 2422 4576 2422 4577 2421 4577 2418 4577 2419 4578 2418 4578 2421 4578 2421 4579 2420 4579 2419 4579 2470 4580 2387 4580 2469 4580 2469 4581 2387 4581 2471 4581 2472 4582 2473 4582 2474 4582 2470 4583 2469 4583 2475 4583 2470 4584 2475 4584 2472 4584 2470 4585 2472 4585 2474 4585 2452 4586 2470 4586 2474 4586 2451 4587 2452 4587 2474 4587 2450 4588 2451 4588 2474 4588 2449 4589 2450 4589 2474 4589 2474 4590 2473 4590 2301 4590 2474 4591 2301 4591 2391 4591 2474 4592 2391 4592 2426 4592 2474 4593 2426 4593 2428 4593 2474 4594 2428 4594 2429 4594 2448 4595 2449 4595 2474 4595 2433 4596 2448 4596 2474 4596 2429 4597 2433 4597 2474 4597 2447 4598 2448 4598 2433 4598 2433 4599 2436 4599 2447 4599 2446 4600 2447 4600 2436 4600 2436 4601 2438 4601 2446 4601 2445 4602 2446 4602 2438 4602 2438 4603 2440 4603 2445 4603 2444 4604 2445 4604 2440 4604 2440 4605 2442 4605 2444 4605 2443 4606 2444 4606 2442 4606 2473 4607 2464 4607 2393 4607 2301 4608 2473 4608 2393 4608 2456 4609 2464 4609 2473 4609 2473 4610 2472 4610 2456 4610 2454 4611 2456 4611 2472 4611 2472 4612 2475 4612 2454 4612 2457 4613 2454 4613 2475 4613 2475 4614 2469 4614 2457 4614 2476 4615 2457 4615 2469 4615 2469 4616 2471 4616 2476 4616 2477 4617 2476 4617 2471 4617 2478 4618 2479 4618 2477 4618 2471 4619 2478 4619 2477 4619 2480 4620 2479 4620 2478 4620 2481 4621 2482 4621 2480 4621 2478 4622 2481 4622 2480 4622 2481 4623 2389 4623 2482 4623 2390 4624 2482 4624 2389 4624 1302 4625 2485 4625 2484 4625 2487 4626 2486 4626 2485 4626 2488 4627 2487 4627 2485 4627 2489 4628 2488 4628 2485 4628 1302 4629 2459 4629 2485 4629 2490 4630 2489 4630 2485 4630 2491 4631 2490 4631 2485 4631 2492 4632 2491 4632 2485 4632 2493 4633 2492 4633 2485 4633 2458 4634 2493 4634 2485 4634 2459 4635 2458 4635 2485 4635 2494 4636 2493 4636 2458 4636 2495 4637 2496 4637 2494 4637 2458 4638 2495 4638 2494 4638 2470 4639 2452 4639 2497 4639 1986 4640 2496 4640 2497 4640 1987 4641 1986 4641 2497 4641 2452 4642 2483 4642 2497 4642 2403 4643 2468 4643 1227 4643 1216 4644 1227 4644 2468 4644 2468 4645 2467 4645 1216 4645 1216 4646 2467 4646 1167 4646 2467 4647 2466 4647 1167 4647 1166 4648 1167 4648 2466 4648 2466 4649 2465 4649 1166 4649 2465 4650 2463 4650 1166 4650 1165 4651 1166 4651 2463 4651 2463 4652 2462 4652 1165 4652 1163 4653 1165 4653 2462 4653 2461 4654 1163 4654 2462 4654 2460 4655 1163 4655 2461 4655 2459 4656 1163 4656 2460 4656 1302 4657 1163 4657 2459 4657 2068 4658 2070 4658 1986 4658 2496 4659 1986 4659 2070 4659 2069 4660 2500 4660 2070 4660 2500 4661 2069 4661 2001 4661 2501 4662 2070 4662 2500 4662 2070 4663 2501 4663 2496 4663 2494 4664 2496 4664 2501 4664 2389 4665 2495 4665 2502 4665 2499 4666 2495 4666 2389 4666 2389 4667 2388 4667 2499 4667 2498 4668 2499 4668 2388 4668 2388 4669 2387 4669 2498 4669 2498 4670 2387 4670 2470 4670 2387 4671 2481 4671 2478 4671 2471 4672 2387 4672 2478 4672 2457 4673 2476 4673 2477 4673 2457 4674 2477 4674 2479 4674 2457 4675 2479 4675 2480 4675 2457 4676 2480 4676 2482 4676 2457 4677 2482 4677 2390 4677 2470 4678 2497 4678 2498 4678 2497 4679 2499 4679 2498 4679 2495 4680 2499 4680 2497 4680 2495 4681 2497 4681 2496 4681 2453 4682 2495 4682 2458 4682 2453 4683 2502 4683 2495 4683 2390 4684 2502 4684 2453 4684 2389 4685 2502 4685 2390 4685 2387 4686 2388 4686 2481 4686 2388 4687 2389 4687 2481 4687 1228 4688 2409 4688 2408 4688 1228 4689 2408 4689 2407 4689 1228 4690 2407 4690 2406 4690 1228 4691 2406 4691 2405 4691 1228 4692 2405 4692 2404 4692 1228 4693 2404 4693 1227 4693 2396 4694 1227 4694 2404 4694 2396 4695 2397 4695 1227 4695 2397 4696 2398 4696 1227 4696 2398 4697 2399 4697 1227 4697 2584 4698 2565 4698 2583 4698 2584 4699 2537 4699 2565 4699 2567 4700 2565 4700 2537 4700 2569 4701 2567 4701 2537 4701 2569 4702 2537 4702 2538 4702 2571 4703 2569 4703 2538 4703 2537 4704 2518 4704 2522 4704 2584 4705 2518 4705 2537 4705 2513 4706 2519 4706 2520 4706 2587 4707 2586 4707 2245 4707 2546 4708 2503 4708 2248 4708 2550 4709 2504 4709 2552 4709 2503 4710 2552 4710 2504 4710 2504 4711 2251 4711 2503 4711 2248 4712 2503 4712 2251 4712 2531 4713 2504 4713 2550 4713 2505 4714 2504 4714 2531 4714 2505 4715 2251 4715 2504 4715 2505 4716 2258 4716 2251 4716 2256 4717 2505 4717 2533 4717 2505 4718 2531 4718 2533 4718 2505 4719 2256 4719 2258 4719 2585 4720 2256 4720 2536 4720 2256 4721 2533 4721 2536 4721 2536 4722 2243 4722 2585 4722 2534 4723 2506 4723 2535 4723 2506 4724 2517 4724 2535 4724 2547 4725 2509 4725 2532 4725 2507 4726 2532 4726 2509 4726 2532 4727 2507 4727 2534 4727 2506 4728 2534 4728 2507 4728 2509 4729 2510 4729 2507 4729 2517 4730 2506 4730 2507 4730 2507 4731 2508 4731 2517 4731 2508 4732 2507 4732 2510 4732 2510 4733 2511 4733 2508 4733 2511 4734 2512 4734 2508 4734 2512 4735 2513 4735 2508 4735 2508 4736 2520 4736 2517 4736 2520 4737 2508 4737 2513 4737 2549 4738 2547 4738 2548 4738 2509 4739 2547 4739 2549 4739 2549 4740 2514 4740 2509 4740 2510 4741 2509 4741 2514 4741 2511 4742 2510 4742 2514 4742 2514 4743 2515 4743 2511 4743 2512 4744 2511 4744 2515 4744 2513 4745 2512 4745 2515 4745 2519 4746 2513 4746 2515 4746 2515 4747 2561 4747 2519 4747 2551 4748 2516 4748 2549 4748 2514 4749 2549 4749 2516 4749 2515 4750 2514 4750 2516 4750 2516 4751 2562 4751 2515 4751 2561 4752 2515 4752 2562 4752 2251 4753 2258 4753 2252 4753 2258 4754 2256 4754 2257 4754 2242 4755 2256 4755 2585 4755 2535 4756 2517 4756 2518 4756 2245 4757 2535 4757 2518 4757 2518 4758 2584 4758 2245 4758 2522 4759 2517 4759 2520 4759 2522 4760 2518 4760 2517 4760 2521 4761 2520 4761 2560 4761 2520 4762 2519 4762 2560 4762 2519 4763 2561 4763 2560 4763 2520 4764 2521 4764 2522 4764 2560 4765 2559 4765 2521 4765 2521 4766 2523 4766 2522 4766 2523 4767 2521 4767 2558 4767 2521 4768 2559 4768 2558 4768 2524 4769 2522 4769 2523 4769 2524 4770 2537 4770 2522 4770 2524 4771 2538 4771 2537 4771 2558 4772 2557 4772 2523 4772 2539 4773 2538 4773 2524 4773 2525 4774 2523 4774 2556 4774 2523 4775 2557 4775 2556 4775 2523 4776 2525 4776 2524 4776 2524 4777 2526 4777 2539 4777 2526 4778 2540 4778 2539 4778 2526 4779 2524 4779 2525 4779 2541 4780 2540 4780 2526 4780 2556 4781 2555 4781 2525 4781 2527 4782 2525 4782 2554 4782 2525 4783 2555 4783 2554 4783 2525 4784 2527 4784 2526 4784 2528 4785 2526 4785 2527 4785 2526 4786 2528 4786 2541 4786 2528 4787 2542 4787 2541 4787 2543 4788 2542 4788 2528 4788 2554 4789 2553 4789 2527 4789 2530 4790 2527 4790 2553 4790 2527 4791 2530 4791 2528 4791 2528 4792 2529 4792 2543 4792 2531 4793 2550 4793 2547 4793 2547 4794 2532 4794 2531 4794 2533 4795 2531 4795 2532 4795 2532 4796 2534 4796 2533 4796 2536 4797 2533 4797 2534 4797 2534 4798 2535 4798 2536 4798 2535 4799 2245 4799 2536 4799 2243 4800 2536 4800 2245 4800 2573 4801 2571 4801 2538 4801 2538 4802 2539 4802 2573 4802 2575 4803 2573 4803 2539 4803 2539 4804 2540 4804 2575 4804 2577 4805 2575 4805 2540 4805 2540 4806 2541 4806 2577 4806 2579 4807 2577 4807 2541 4807 2541 4808 2542 4808 2579 4808 2580 4809 2579 4809 2542 4809 2542 4810 2543 4810 2580 4810 2580 4811 2543 4811 2544 4811 2248 4812 2251 4812 2250 4812 2545 4813 2248 4813 2160 4813 2545 4814 2247 4814 2248 4814 2247 4815 2546 4815 2248 4815 2547 4816 2550 4816 2548 4816 2550 4817 2549 4817 2548 4817 2550 4818 2551 4818 2549 4818 2552 4819 2551 4819 2550 4819 2582 4820 2587 4820 2583 4820 2245 4821 2583 4821 2587 4821 2583 4822 2565 4822 2564 4822 2565 4823 2567 4823 2566 4823 2567 4824 2569 4824 2568 4824 2569 4825 2571 4825 2570 4825 2571 4826 2573 4826 2572 4826 2573 4827 2575 4827 2574 4827 2575 4828 2577 4828 2576 4828 2577 4829 2579 4829 2578 4829 2579 4830 2580 4830 2581 4830 2245 4831 2584 4831 2583 4831 2245 4832 2244 4832 2243 4832 2585 4833 2243 4833 2242 4833 2553 4834 2554 4834 2563 4834 2554 4835 2555 4835 2563 4835 2555 4836 2556 4836 2563 4836 2556 4837 2562 4837 2563 4837 2556 4838 2557 4838 2562 4838 2557 4839 2558 4839 2562 4839 2558 4840 2559 4840 2562 4840 2559 4841 2560 4841 2562 4841 2560 4842 2561 4842 2562 4842 2592 4843 2589 4843 2590 4843 2593 4844 2589 4844 2592 4844 2594 4845 2589 4845 2593 4845 2595 4846 2589 4846 2594 4846 2595 4847 2563 4847 2589 4847 2596 4848 2563 4848 2595 4848 2597 4849 2563 4849 2596 4849 2553 4850 2563 4850 2597 4850 2588 4851 2581 4851 2580 4851 2581 4852 2578 4852 2579 4852 2578 4853 2576 4853 2577 4853 2576 4854 2574 4854 2575 4854 2574 4855 2572 4855 2573 4855 2572 4856 2570 4856 2571 4856 2570 4857 2568 4857 2569 4857 2568 4858 2566 4858 2567 4858 2566 4859 2564 4859 2565 4859 2564 4860 2582 4860 2583 4860 2591 4861 2590 4861 2589 4861 2566 4862 2600 4862 2601 4862 2566 4863 2601 4863 2602 4863 2564 4864 2566 4864 2602 4864 2566 4865 2568 4865 2600 4865 2568 4866 2570 4866 2600 4866 2572 4867 2574 4867 2603 4867 2604 4868 2603 4868 2574 4868 2574 4869 2576 4869 2604 4869 2605 4870 2604 4870 2576 4870 2576 4871 2578 4871 2605 4871 2606 4872 2605 4872 2578 4872 2578 4873 2581 4873 2606 4873 2607 4874 2606 4874 2581 4874 2581 4875 2588 4875 2607 4875 2544 4876 2607 4876 2588 4876 2588 4877 2580 4877 2544 4877 2601 4878 2608 4878 2609 4878 2602 4879 2601 4879 2609 4879 2610 4880 2611 4880 2612 4880 2608 4881 2610 4881 2612 4881 2608 4882 2601 4882 2600 4882 2608 4883 2600 4883 2610 4883 2613 4884 2611 4884 2610 4884 2613 4885 2590 4885 2591 4885 2613 4886 2591 4886 2611 4886 2592 4887 2590 4887 2613 4887 2613 4888 2610 4888 2614 4888 2615 4889 2613 4889 2614 4889 2615 4890 2593 4890 2592 4890 2613 4891 2615 4891 2592 4891 2614 4892 2616 4892 2615 4892 2610 4893 2600 4893 2603 4893 2614 4894 2610 4894 2603 4894 2616 4895 2614 4895 2603 4895 2603 4896 2604 4896 2616 4896 2594 4897 2593 4897 2615 4897 2617 4898 2595 4898 2594 4898 2615 4899 2617 4899 2594 4899 2617 4900 2615 4900 2616 4900 2616 4901 2604 4901 2605 4901 2618 4902 2616 4902 2605 4902 2616 4903 2618 4903 2617 4903 2605 4904 2606 4904 2618 4904 2596 4905 2595 4905 2617 4905 2530 4906 2597 4906 2596 4906 2617 4907 2530 4907 2596 4907 2530 4908 2617 4908 2618 4908 2618 4909 2529 4909 2530 4909 2618 4910 2606 4910 2607 4910 2529 4911 2618 4911 2607 4911 2607 4912 2544 4912 2529 4912 2553 4913 2597 4913 2530 4913 2529 4914 2544 4914 2543 4914 2530 4915 2529 4915 2528 4915 2598 4916 2161 4916 2158 4916 2161 4917 2247 4917 2157 4917 2247 4918 2545 4918 2160 4918 1980 4919 2619 4919 2620 4919 1980 4920 2620 4920 1981 4920 1980 4921 1981 4921 1982 4921 1985 4922 2241 4922 2599 4922 1980 4923 1985 4923 2599 4923 2621 4924 2582 4924 2622 4924 2623 4925 2621 4925 2622 4925 2582 4926 2564 4926 2622 4926 2602 4927 2622 4927 2564 4927 2100 4928 2099 4928 2098 4928 2098 4929 2021 4929 2022 4929 2098 4930 2022 4930 2624 4930 2098 4931 2624 4931 2625 4931 2100 4932 2098 4932 2158 4932 2158 4933 2098 4933 2598 4933 2626 4934 2627 4934 2628 4934 2629 4935 2628 4935 2627 4935 2629 4936 2627 4936 2098 4936 2630 4937 2629 4937 2098 4937 2619 4938 1980 4938 2625 4938 2621 4939 2623 4939 2625 4939 2625 4940 2623 4940 2631 4940 2625 4941 2631 4941 2632 4941 2625 4942 2632 4942 2633 4942 2625 4943 2633 4943 2634 4943 2625 4944 2634 4944 2630 4944 2098 4945 2625 4945 2630 4945 1981 4946 2620 4946 2022 4946 2624 4947 2022 4947 2620 4947 2620 4948 2619 4948 2624 4948 2625 4949 2624 4949 2619 4949 2634 4950 2635 4950 2629 4950 2630 4951 2634 4951 2629 4951 2634 4952 2633 4952 2635 4952 2636 4953 2635 4953 2633 4953 2633 4954 2632 4954 2636 4954 2637 4955 2636 4955 2632 4955 2632 4956 2631 4956 2637 4956 2622 4957 2637 4957 2631 4957 2631 4958 2623 4958 2622 4958 2602 4959 2609 4959 2622 4959 2608 4960 2612 4960 2609 4960 2591 4961 2638 4961 2611 4961 2611 4962 2639 4962 2612 4962 2639 4963 2611 4963 2638 4963 2636 4964 2612 4964 2639 4964 2635 4965 2639 4965 2638 4965 2639 4966 2635 4966 2636 4966 2638 4967 2629 4967 2635 4967 2638 4968 2591 4968 2640 4968 2640 4969 2628 4969 2638 4969 2629 4970 2638 4970 2628 4970 2589 4971 2640 4971 2591 4971 2589 4972 2641 4972 2640 4972 2628 4973 2640 4973 2641 4973 2628 4974 2641 4974 2626 4974 2570 4975 2603 4975 2600 4975 2572 4976 2603 4976 2570 4976 2609 4977 2637 4977 2622 4977 2609 4978 2612 4978 2637 4978 2612 4979 2636 4979 2637 4979 2645 4980 2644 4980 2643 4980 2246 4981 2647 4981 2648 4981 2246 4982 2648 4982 2645 4982 2643 4983 2246 4983 2645 4983 2651 4984 2652 4984 2653 4984 2654 4985 2653 4985 2652 4985 2652 4986 2655 4986 2654 4986 2656 4987 2654 4987 2655 4987 2655 4988 2657 4988 2656 4988 2658 4989 2656 4989 2657 4989 2657 4990 2659 4990 2658 4990 2660 4991 2658 4991 2659 4991 2659 4992 2661 4992 2660 4992 2662 4993 2660 4993 2661 4993 2661 4994 2663 4994 2662 4994 2664 4995 2662 4995 2663 4995 2663 4996 2665 4996 2664 4996 2666 4997 2664 4997 2665 4997 2665 4998 2667 4998 2666 4998 2666 4999 2667 4999 2668 4999 2669 5000 2666 5000 2668 5000 2669 5001 2670 5001 2674 5001 2669 5002 2674 5002 2675 5002 2676 5003 2669 5003 2675 5003 2677 5004 2678 5004 2645 5004 2644 5005 2645 5005 2678 5005 2679 5006 2680 5006 2644 5006 2678 5007 2679 5007 2644 5007 2681 5008 2680 5008 2679 5008 2679 5009 2682 5009 2681 5009 2683 5010 2681 5010 2682 5010 2682 5011 2684 5011 2683 5011 2685 5012 2683 5012 2684 5012 2684 5013 2686 5013 2685 5013 2687 5014 2685 5014 2686 5014 2686 5015 2688 5015 2687 5015 2689 5016 2687 5016 2688 5016 2688 5017 2690 5017 2689 5017 2691 5018 2689 5018 2690 5018 2690 5019 2692 5019 2691 5019 2693 5020 2691 5020 2692 5020 2692 5021 2694 5021 2693 5021 2693 5022 2694 5022 2695 5022 2696 5023 2693 5023 2695 5023 2647 5024 2642 5024 2582 5024 2697 5025 2647 5025 2582 5025 2646 5026 2642 5026 2647 5026 2678 5027 2698 5027 2699 5027 2679 5028 2678 5028 2699 5028 2682 5029 2679 5029 2699 5029 2684 5030 2682 5030 2699 5030 2686 5031 2684 5031 2699 5031 2699 5032 2700 5032 2686 5032 2688 5033 2686 5033 2700 5033 2700 5034 2701 5034 2688 5034 2690 5035 2688 5035 2701 5035 2701 5036 2702 5036 2690 5036 2692 5037 2690 5037 2702 5037 2702 5038 2703 5038 2692 5038 2694 5039 2692 5039 2703 5039 2703 5040 2704 5040 2694 5040 2695 5041 2694 5041 2704 5041 2704 5042 2705 5042 2695 5042 2695 5043 2705 5043 2706 5043 2696 5044 2695 5044 2706 5044 2706 5045 2707 5045 2696 5045 2693 5046 2696 5046 2707 5046 2707 5047 2708 5047 2693 5047 2691 5048 2693 5048 2708 5048 2708 5049 2709 5049 2691 5049 2689 5050 2691 5050 2709 5050 2709 5051 2710 5051 2689 5051 2687 5052 2689 5052 2710 5052 2710 5053 2711 5053 2687 5053 2685 5054 2687 5054 2711 5054 2711 5055 2712 5055 2685 5055 2683 5056 2685 5056 2712 5056 2683 5057 2712 5057 2681 5057 2680 5058 2681 5058 2712 5058 2680 5059 2712 5059 2713 5059 2680 5060 2713 5060 2643 5060 2644 5061 2680 5061 2643 5061 2392 5062 2425 5062 2391 5062 2425 5063 2714 5063 2426 5063 2714 5064 2427 5064 2426 5064 2427 5065 2430 5065 2428 5065 2430 5066 2431 5066 2429 5066 2722 5067 2720 5067 2721 5067 2723 5068 2722 5068 2721 5068 2721 5069 2724 5069 2723 5069 2725 5070 2723 5070 2724 5070 2724 5071 2726 5071 2725 5071 2483 5072 2725 5072 2726 5072 2729 5073 2728 5073 2727 5073 2731 5074 2727 5074 2730 5074 2727 5075 2731 5075 2729 5075 2732 5076 2729 5076 2731 5076 2732 5077 2733 5077 2729 5077 2734 5078 2437 5078 2435 5078 2734 5079 2435 5079 2735 5079 2734 5080 2735 5080 2733 5080 2734 5081 2733 5081 2732 5081 2439 5082 2437 5082 2734 5082 2731 5083 2736 5083 2732 5083 2731 5084 2730 5084 2737 5084 2736 5085 2731 5085 2737 5085 2738 5086 2732 5086 2736 5086 2732 5087 2738 5087 2734 5087 2739 5088 2734 5088 2738 5088 2739 5089 2441 5089 2439 5089 2734 5090 2739 5090 2439 5090 2715 5091 2441 5091 2739 5091 2739 5092 2740 5092 2715 5092 2741 5093 2740 5093 2739 5093 2738 5094 2741 5094 2739 5094 2716 5095 2715 5095 2740 5095 2742 5096 2741 5096 2738 5096 2736 5097 2742 5097 2738 5097 2742 5098 2736 5098 2737 5098 2743 5099 2717 5099 2716 5099 2740 5100 2743 5100 2716 5100 2743 5101 2740 5101 2741 5101 2718 5102 2717 5102 2743 5102 2744 5103 2741 5103 2742 5103 2741 5104 2744 5104 2743 5104 2745 5105 2742 5105 2737 5105 2742 5106 2745 5106 2744 5106 2737 5107 2746 5107 2745 5107 2747 5108 2743 5108 2744 5108 2747 5109 2719 5109 2718 5109 2743 5110 2747 5110 2718 5110 2720 5111 2719 5111 2747 5111 2744 5112 2748 5112 2747 5112 2748 5113 2744 5113 2745 5113 2749 5114 2745 5114 2746 5114 2745 5115 2749 5115 2748 5115 2747 5116 2750 5116 2720 5116 2750 5117 2747 5117 2748 5117 2748 5118 2752 5118 2750 5118 2752 5119 2748 5119 2749 5119 2749 5120 2754 5120 2752 5120 2749 5121 2746 5121 2754 5121 2755 5122 2752 5122 2754 5122 2670 5123 2821 5123 2674 5123 2756 5124 2757 5124 2676 5124 2675 5125 2756 5125 2676 5125 2756 5126 2675 5126 2674 5126 2674 5127 2821 5127 2758 5127 2759 5128 2674 5128 2758 5128 2674 5129 2759 5129 2756 5129 2758 5130 2826 5130 2759 5130 2756 5131 2760 5131 2757 5131 2760 5132 2756 5132 2759 5132 2759 5133 2761 5133 2760 5133 2761 5134 2759 5134 2826 5134 2826 5135 2762 5135 2761 5135 2763 5136 2757 5136 2760 5136 2764 5137 2761 5137 2762 5137 2761 5138 2764 5138 2760 5138 2765 5139 2760 5139 2764 5139 2760 5140 2765 5140 2763 5140 2766 5141 2764 5141 2762 5141 2764 5142 2766 5142 2765 5142 2767 5143 2757 5143 2763 5143 2762 5144 2768 5144 2766 5144 2769 5145 2765 5145 2766 5145 2765 5146 2769 5146 2763 5146 2763 5147 2770 5147 2767 5147 2770 5148 2763 5148 2769 5148 2766 5149 2771 5149 2769 5149 2771 5150 2766 5150 2768 5150 2772 5151 2767 5151 2770 5151 2767 5152 2772 5152 2773 5152 2769 5153 2774 5153 2770 5153 2774 5154 2769 5154 2771 5154 2775 5155 2770 5155 2774 5155 2770 5156 2775 5156 2772 5156 2772 5157 2776 5157 2773 5157 2777 5158 2771 5158 2768 5158 2771 5159 2777 5159 2774 5159 2778 5160 2772 5160 2775 5160 2772 5161 2778 5161 2776 5161 2768 5162 2737 5162 2777 5162 2780 5163 2774 5163 2777 5163 2774 5164 2780 5164 2775 5164 2728 5165 2775 5165 2780 5165 2775 5166 2728 5166 2778 5166 2733 5167 2735 5167 2779 5167 2776 5168 2733 5168 2779 5168 2733 5169 2776 5169 2778 5169 2777 5170 2737 5170 2730 5170 2780 5171 2777 5171 2730 5171 2780 5172 2730 5172 2727 5172 2780 5173 2727 5173 2728 5173 2778 5174 2728 5174 2729 5174 2778 5175 2729 5175 2733 5175 2781 5176 2735 5176 2435 5176 2667 5177 2782 5177 2783 5177 2668 5178 2667 5178 2783 5178 2782 5179 2667 5179 2665 5179 2786 5180 2782 5180 2665 5180 2786 5181 2784 5181 2787 5181 2782 5182 2786 5182 2787 5182 2665 5183 2663 5183 2786 5183 2786 5184 2663 5184 2661 5184 2788 5185 2786 5185 2661 5185 2789 5186 2700 5186 2699 5186 2701 5187 2700 5187 2789 5187 2661 5188 2659 5188 2788 5188 2788 5189 2790 5189 2789 5189 2788 5190 2659 5190 2657 5190 2790 5191 2788 5191 2657 5191 2791 5192 2702 5192 2701 5192 2789 5193 2791 5193 2701 5193 2791 5194 2789 5194 2790 5194 2703 5195 2702 5195 2791 5195 2657 5196 2655 5196 2790 5196 2790 5197 2655 5197 2652 5197 2792 5198 2790 5198 2652 5198 2790 5199 2792 5199 2791 5199 2793 5200 2704 5200 2703 5200 2791 5201 2793 5201 2703 5201 2793 5202 2791 5202 2792 5202 2705 5203 2704 5203 2793 5203 2652 5204 2651 5204 2792 5204 2794 5205 2706 5205 2705 5205 2793 5206 2794 5206 2705 5206 2792 5207 2651 5207 2653 5207 2795 5208 2792 5208 2653 5208 2795 5209 2794 5209 2793 5209 2792 5210 2795 5210 2793 5210 2707 5211 2706 5211 2794 5211 2653 5212 2654 5212 2795 5212 2796 5213 2708 5213 2707 5213 2794 5214 2796 5214 2707 5214 2796 5215 2794 5215 2795 5215 2795 5216 2654 5216 2656 5216 2797 5217 2795 5217 2656 5217 2795 5218 2797 5218 2796 5218 2709 5219 2708 5219 2796 5219 2656 5220 2658 5220 2797 5220 2798 5221 2796 5221 2797 5221 2798 5222 2710 5222 2709 5222 2796 5223 2798 5223 2709 5223 2797 5224 2799 5224 2798 5224 2797 5225 2658 5225 2660 5225 2799 5226 2797 5226 2660 5226 2711 5227 2710 5227 2798 5227 2660 5228 2662 5228 2799 5228 2800 5229 2712 5229 2711 5229 2798 5230 2800 5230 2711 5230 2800 5231 2798 5231 2799 5231 2801 5232 2799 5232 2662 5232 2799 5233 2801 5233 2800 5233 2662 5234 2664 5234 2801 5234 2801 5235 2664 5235 2666 5235 2801 5236 2666 5236 2669 5236 2801 5237 2669 5237 2802 5237 2801 5238 2802 5238 2803 5238 2801 5239 2803 5239 2800 5239 2800 5240 2803 5240 2804 5240 2800 5241 2804 5241 2805 5241 2806 5242 2800 5242 2805 5242 2806 5243 2713 5243 2712 5243 2806 5244 2712 5244 2800 5244 2713 5245 2806 5245 2807 5245 2643 5246 2713 5246 2807 5246 2643 5247 2807 5247 2246 5247 2808 5248 2246 5248 2807 5248 2808 5249 2807 5249 2806 5249 2806 5250 2805 5250 2808 5250 2809 5251 2808 5251 2805 5251 2810 5252 2809 5252 2805 5252 2804 5253 2810 5253 2805 5253 2811 5254 2810 5254 2804 5254 2804 5255 2803 5255 2811 5255 2812 5256 2811 5256 2803 5256 2803 5257 2802 5257 2812 5257 2676 5258 2812 5258 2802 5258 2802 5259 2669 5259 2676 5259 2809 5260 2810 5260 2813 5260 2814 5261 2813 5261 2810 5261 2810 5262 2811 5262 2814 5262 2757 5263 2814 5263 2811 5263 2811 5264 2812 5264 2757 5264 2812 5265 2676 5265 2757 5265 2813 5266 2427 5266 2714 5266 2813 5267 2714 5267 2425 5267 2392 5268 2813 5268 2425 5268 2781 5269 2435 5269 2434 5269 2781 5270 2434 5270 2432 5270 2815 5271 2427 5271 2813 5271 2779 5272 2781 5272 2815 5272 2781 5273 2779 5273 2735 5273 2816 5274 2815 5274 2813 5274 2815 5275 2816 5275 2779 5275 2776 5276 2779 5276 2816 5276 2816 5277 2817 5277 2776 5277 2817 5278 2816 5278 2813 5278 2813 5279 2814 5279 2817 5279 2817 5280 2773 5280 2776 5280 2773 5281 2817 5281 2814 5281 2767 5282 2773 5282 2814 5282 2814 5283 2757 5283 2767 5283 2645 5284 2648 5284 2677 5284 2818 5285 2677 5285 2648 5285 2648 5286 2647 5286 2818 5286 2697 5287 2818 5287 2647 5287 2820 5288 2677 5288 2818 5288 2818 5289 2697 5289 2820 5289 2820 5290 2698 5290 2678 5290 2678 5291 2677 5291 2820 5291 2821 5292 2670 5292 2671 5292 2822 5293 2672 5293 2673 5293 2672 5294 2822 5294 2671 5294 2673 5295 2823 5295 2822 5295 2824 5296 2671 5296 2822 5296 2671 5297 2824 5297 2821 5297 2758 5298 2821 5298 2824 5298 2824 5299 2825 5299 2758 5299 2825 5300 2824 5300 2822 5300 2826 5301 2758 5301 2825 5301 2823 5302 2827 5302 2822 5302 2828 5303 2822 5303 2827 5303 2822 5304 2828 5304 2825 5304 2827 5305 2829 5305 2828 5305 2830 5306 2828 5306 2829 5306 2828 5307 2830 5307 2825 5307 2762 5308 2826 5308 2825 5308 2825 5309 2831 5309 2762 5309 2831 5310 2825 5310 2830 5310 2832 5311 2833 5311 2829 5311 2830 5312 2834 5312 2831 5312 2834 5313 2830 5313 2829 5313 2829 5314 2835 5314 2834 5314 2835 5315 2829 5315 2833 5315 2836 5316 2831 5316 2834 5316 2831 5317 2836 5317 2762 5317 2768 5318 2762 5318 2836 5318 2833 5319 2837 5319 2835 5319 2838 5320 2834 5320 2835 5320 2834 5321 2838 5321 2836 5321 2837 5322 2839 5322 2835 5322 2836 5323 2840 5323 2768 5323 2840 5324 2836 5324 2838 5324 2841 5325 2835 5325 2839 5325 2835 5326 2841 5326 2838 5326 2737 5327 2768 5327 2840 5327 2837 5328 2753 5328 2839 5328 2838 5329 2842 5329 2840 5329 2842 5330 2838 5330 2841 5330 2746 5331 2840 5331 2842 5331 2840 5332 2746 5332 2737 5332 2755 5333 2841 5333 2839 5333 2841 5334 2755 5334 2842 5334 2839 5335 2843 5335 2755 5335 2843 5336 2839 5336 2753 5336 2754 5337 2842 5337 2755 5337 2842 5338 2754 5338 2746 5338 2753 5339 2751 5339 2750 5339 2755 5340 2843 5340 2752 5340 2844 5341 2845 5341 2726 5341 2844 5342 2726 5342 2724 5342 2721 5343 2751 5343 2844 5343 2844 5344 2846 5344 2845 5344 2847 5345 2846 5345 2844 5345 2844 5346 2848 5346 2847 5346 2844 5347 2751 5347 2753 5347 2848 5348 2844 5348 2753 5348 2753 5349 2837 5349 2848 5349 2849 5350 2847 5350 2848 5350 2848 5351 2837 5351 2849 5351 2837 5352 2833 5352 2849 5352 2850 5353 2849 5353 2833 5353 2833 5354 2832 5354 2850 5354 2851 5355 2820 5355 2819 5355 2819 5356 2852 5356 2851 5356 2819 5357 2726 5357 2852 5357 2853 5358 2851 5358 2852 5358 2852 5359 2726 5359 2845 5359 2854 5360 2852 5360 2845 5360 2852 5361 2854 5361 2853 5361 2854 5362 2845 5362 2846 5362 2855 5363 2854 5363 2846 5363 2854 5364 2855 5364 2853 5364 2846 5365 2847 5365 2855 5365 2856 5366 2853 5366 2855 5366 2855 5367 2857 5367 2856 5367 2857 5368 2855 5368 2847 5368 2857 5369 2847 5369 2849 5369 2858 5370 2856 5370 2857 5370 2857 5371 2859 5371 2858 5371 2859 5372 2857 5372 2849 5372 2860 5373 2858 5373 2859 5373 2859 5374 2849 5374 2850 5374 2859 5375 2827 5375 2860 5375 2859 5376 2850 5376 2832 5376 2827 5377 2859 5377 2832 5377 2860 5378 2827 5378 2823 5378 2673 5379 2860 5379 2823 5379 2832 5380 2829 5380 2827 5380 2820 5381 2785 5381 2698 5381 2851 5382 2785 5382 2820 5382 2853 5383 2784 5383 2785 5383 2851 5384 2853 5384 2785 5384 2856 5385 2787 5385 2784 5385 2853 5386 2856 5386 2784 5386 2856 5387 2858 5387 2787 5387 2782 5388 2787 5388 2858 5388 2858 5389 2860 5389 2782 5389 2783 5390 2782 5390 2860 5390 2860 5391 2673 5391 2783 5391 2668 5392 2783 5392 2673 5392 2698 5393 2785 5393 2699 5393 2699 5394 2785 5394 2784 5394 2784 5395 2861 5395 2699 5395 2861 5396 2789 5396 2699 5396 2788 5397 2861 5397 2786 5397 2789 5398 2861 5398 2788 5398 2786 5399 2861 5399 2784 5399 2431 5400 2781 5400 2432 5400 2430 5401 2781 5401 2431 5401 2427 5402 2815 5402 2430 5402 2430 5403 2815 5403 2781 5403 2808 5404 2809 5404 2813 5404 2246 5405 2808 5405 2813 5405 2246 5406 2813 5406 2649 5406 2649 5407 2813 5407 2650 5407 2392 5408 2650 5408 2813 5408 2668 5409 2673 5409 2672 5409 2668 5410 2672 5410 2671 5410 2668 5411 2671 5411 2670 5411 2668 5412 2670 5412 2669 5412 2750 5413 2752 5413 2843 5413 2750 5414 2843 5414 2753 5414 2720 5415 2750 5415 2751 5415 2720 5416 2751 5416 2721 5416 2724 5417 2721 5417 2844 5417 2865 5418 2059 5418 1988 5418 2865 5419 2864 5419 2059 5419 2060 5420 2059 5420 2864 5420 2864 5421 2862 5421 2060 5421 2862 5422 2863 5422 2060 5422 2621 5423 2862 5423 2864 5423 2863 5424 2862 5424 2621 5424 2625 5425 2866 5425 2621 5425 2625 5426 1980 5426 2866 5426 2599 5427 2866 5427 1980 5427 2237 5428 1979 5428 2863 5428 1979 5429 2060 5429 2863 5429 2238 5430 2237 5430 2863 5430 2239 5431 2238 5431 2863 5431 2240 5432 2239 5432 2863 5432 2869 5433 2240 5433 2863 5433 2868 5434 2869 5434 2866 5434 2869 5435 2621 5435 2866 5435 2869 5436 2863 5436 2621 5436 2621 5437 2697 5437 2582 5437 2621 5438 2820 5438 2697 5438 2621 5439 2864 5439 2820 5439 2820 5440 2864 5440 2819 5440 2864 5441 2865 5441 2726 5441 2726 5442 2819 5442 2864 5442 2865 5443 1988 5443 2726 5443 1988 5444 2483 5444 2726 5444 1988 5445 1987 5445 2497 5445 2497 5446 2483 5446 1988 5446 2867 5447 2245 5447 2586 5447 2586 5448 2642 5448 2867 5448 2646 5449 2867 5449 2642 5449 2586 5450 2587 5450 2582 5450 2586 5451 2582 5451 2642 5451 2241 5452 1973 5452 2868 5452 1973 5453 2869 5453 2868 5453 1973 5454 2240 5454 2869 5454 2056 5455 2057 5455 2877 5455 1899 5456 1954 5456 2949 5456 2931 5457 2936 5457 2953 5457 2952 5458 2953 5458 2936 5458 2936 5459 2941 5459 2952 5459 2951 5460 2952 5460 2941 5460 2941 5461 2942 5461 2951 5461 1958 5462 2951 5462 1943 5462 2951 5463 2942 5463 1943 5463 2922 5464 2923 5464 2964 5464 2965 5465 2964 5465 2923 5465 2923 5466 2924 5466 2965 5466 2963 5467 2965 5467 2924 5467 2924 5468 2928 5468 2963 5468 2955 5469 2963 5469 2928 5469 2928 5470 2930 5470 2955 5470 2954 5471 2955 5471 2930 5471 2930 5472 2931 5472 2954 5472 2953 5473 2954 5473 2931 5473 2964 5474 2956 5474 2922 5474 2494 5475 2872 5475 2493 5475 2501 5476 2870 5476 2872 5476 2501 5477 2872 5477 2494 5477 2500 5478 2889 5478 2870 5478 2500 5479 2887 5479 2889 5479 2870 5480 2501 5480 2500 5480 2001 5481 2887 5481 2500 5481 2944 5482 2893 5482 2948 5482 2893 5483 2871 5483 2892 5483 2871 5484 2889 5484 2892 5484 2871 5485 2870 5485 2889 5485 2871 5486 2893 5486 2945 5486 2893 5487 2944 5487 2945 5487 2945 5488 2946 5488 2871 5488 2871 5489 2873 5489 2870 5489 2873 5490 2872 5490 2870 5490 2873 5491 2871 5491 2943 5491 2871 5492 2946 5492 2943 5492 2943 5493 2937 5493 2873 5493 2873 5494 2938 5494 2939 5494 2873 5495 2937 5495 2938 5495 2873 5496 2939 5496 2872 5496 2939 5497 2493 5497 2872 5497 2933 5498 2493 5498 2939 5498 2933 5499 2492 5499 2493 5499 2491 5500 2492 5500 2933 5500 2933 5501 2934 5501 2491 5501 2490 5502 2491 5502 2896 5502 2491 5503 2932 5503 2896 5503 2491 5504 2934 5504 2932 5504 1849 5505 1850 5505 2886 5505 2886 5506 2874 5506 2885 5506 2874 5507 2884 5507 2885 5507 2874 5508 2878 5508 2884 5508 2874 5509 2886 5509 1850 5509 2879 5510 2878 5510 2874 5510 1850 5511 1851 5511 2874 5511 2874 5512 2875 5512 2879 5512 2875 5513 2880 5513 2879 5513 2875 5514 2874 5514 1852 5514 2874 5515 1851 5515 1852 5515 2881 5516 2880 5516 2875 5516 1852 5517 1853 5517 2875 5517 2876 5518 2875 5518 1854 5518 2875 5519 1853 5519 1854 5519 2875 5520 2876 5520 2881 5520 2876 5521 2882 5521 2881 5521 2883 5522 2882 5522 2876 5522 1854 5523 1855 5523 2876 5523 2877 5524 2876 5524 2056 5524 2876 5525 2055 5525 2056 5525 2876 5526 2053 5526 2055 5526 2876 5527 1855 5527 2053 5527 2876 5528 2877 5528 2883 5528 2054 5529 2883 5529 2058 5529 2883 5530 2057 5530 2058 5530 2883 5531 2877 5531 2057 5531 2884 5532 2878 5532 1961 5532 2957 5533 1961 5533 2878 5533 2878 5534 2879 5534 2957 5534 2959 5535 2957 5535 2879 5535 2879 5536 2880 5536 2959 5536 2960 5537 2959 5537 2880 5537 2880 5538 2881 5538 2960 5538 2962 5539 2960 5539 2881 5539 2881 5540 2882 5540 2962 5540 2961 5541 2962 5541 2882 5541 2882 5542 2883 5542 2961 5542 2958 5543 2961 5543 2883 5543 2883 5544 2054 5544 2958 5544 1962 5545 2958 5545 2054 5545 1952 5546 2884 5546 1961 5546 1952 5547 2885 5547 2884 5547 1952 5548 2886 5548 2885 5548 1952 5549 1849 5549 2886 5549 1850 5550 1849 5550 1955 5550 1999 5551 2887 5551 2001 5551 2889 5552 2887 5552 2888 5552 2887 5553 1999 5553 2888 5553 1879 5554 1999 5554 1877 5554 1878 5555 2890 5555 1879 5555 1880 5556 2890 5556 1878 5556 1898 5557 1899 5557 1880 5557 2891 5558 2889 5558 2888 5558 2891 5559 2892 5559 2889 5559 2891 5560 2888 5560 1879 5560 2888 5561 1999 5561 1879 5561 1879 5562 2890 5562 2891 5562 2894 5563 2891 5563 1880 5563 2891 5564 2890 5564 1880 5564 2891 5565 2894 5565 2892 5565 2894 5566 2893 5566 2892 5566 2948 5567 2893 5567 2894 5567 1880 5568 1899 5568 2894 5568 2894 5569 2895 5569 2948 5569 2895 5570 2894 5570 2949 5570 2894 5571 1899 5571 2949 5571 2490 5572 2896 5572 2489 5572 2925 5573 2488 5573 2489 5573 2488 5574 2925 5574 2487 5574 2489 5575 2926 5575 2925 5575 2926 5576 2489 5576 2896 5576 2917 5577 2487 5577 2925 5577 2896 5578 2932 5578 2926 5578 2905 5579 2487 5579 2917 5579 2486 5580 2487 5580 2905 5580 2905 5581 2907 5581 2486 5581 2913 5582 2915 5582 2900 5582 2901 5583 2900 5583 2898 5583 2900 5584 2915 5584 2898 5584 2898 5585 2899 5585 2901 5585 2897 5586 2901 5586 2899 5586 2901 5587 2897 5587 2902 5587 2897 5588 2903 5588 2902 5588 2904 5589 2903 5589 2897 5589 2386 5590 2897 5590 2367 5590 2897 5591 2369 5591 2367 5591 2897 5592 2899 5592 2369 5592 2897 5593 2386 5593 2904 5593 2386 5594 2362 5594 2904 5594 2374 5595 2915 5595 2349 5595 2374 5596 2371 5596 2915 5596 2371 5597 2898 5597 2915 5597 2899 5598 2898 5598 2371 5598 2371 5599 2369 5599 2899 5599 2486 5600 2907 5600 2485 5600 2907 5601 2909 5601 2485 5601 2909 5602 2910 5602 2485 5602 2910 5603 2911 5603 2485 5603 2911 5604 2913 5604 2485 5604 2913 5605 2900 5605 2485 5605 2900 5606 2901 5606 2485 5606 2901 5607 2484 5607 2485 5607 2484 5608 1282 5608 1284 5608 2484 5609 2362 5609 1282 5609 2901 5610 2902 5610 2484 5610 2902 5611 2903 5611 2484 5611 2903 5612 2904 5612 2484 5612 2904 5613 2362 5613 2484 5613 2908 5614 2921 5614 2956 5614 2921 5615 2908 5615 2919 5615 2908 5616 2920 5616 2919 5616 2908 5617 2918 5617 2920 5617 2908 5618 2906 5618 2918 5618 2906 5619 2917 5619 2918 5619 2905 5620 2917 5620 2906 5620 2907 5621 2905 5621 2906 5621 2914 5622 2909 5622 2906 5622 2914 5623 2906 5623 2908 5623 2909 5624 2907 5624 2906 5624 2908 5625 2912 5625 2914 5625 2912 5626 2908 5626 2956 5626 2910 5627 2909 5627 2914 5627 2911 5628 2910 5628 2914 5628 2913 5629 2911 5629 2914 5629 2912 5630 2956 5630 2916 5630 2912 5631 2916 5631 2914 5631 2915 5632 2913 5632 2914 5632 2956 5633 2311 5633 2916 5633 2350 5634 2915 5634 2914 5634 2350 5635 2349 5635 2915 5635 2350 5636 2914 5636 2916 5636 2916 5637 2348 5637 2350 5637 2350 5638 2344 5638 2349 5638 2311 5639 2348 5639 2916 5639 2348 5640 2311 5640 2309 5640 2917 5641 2925 5641 2918 5641 2925 5642 2920 5642 2918 5642 2920 5643 2927 5643 2919 5643 2927 5644 2921 5644 2919 5644 2927 5645 2920 5645 2925 5645 2929 5646 2921 5646 2927 5646 2929 5647 2956 5647 2921 5647 2929 5648 2922 5648 2956 5648 2929 5649 2923 5649 2922 5649 2929 5650 2924 5650 2923 5650 2929 5651 2928 5651 2924 5651 2925 5652 2926 5652 2927 5652 2935 5653 2927 5653 2932 5653 2927 5654 2926 5654 2932 5654 2927 5655 2935 5655 2929 5655 2930 5656 2928 5656 2929 5656 2940 5657 2929 5657 2935 5657 2929 5658 2940 5658 2930 5658 2940 5659 2931 5659 2930 5659 2940 5660 2936 5660 2931 5660 2932 5661 2934 5661 2935 5661 2939 5662 2935 5662 2933 5662 2935 5663 2934 5663 2933 5663 2935 5664 2939 5664 2940 5664 2941 5665 2936 5665 2940 5665 2947 5666 2940 5666 2943 5666 2940 5667 2937 5667 2943 5667 2940 5668 2938 5668 2937 5668 2940 5669 2939 5669 2938 5669 2940 5670 2947 5670 2941 5670 2947 5671 2942 5671 2941 5671 2947 5672 1943 5672 2942 5672 2943 5673 2946 5673 2947 5673 2950 5674 2947 5674 2948 5674 2947 5675 2944 5675 2948 5675 2947 5676 2945 5676 2944 5676 2947 5677 2946 5677 2945 5677 2947 5678 2950 5678 1943 5678 2950 5679 1944 5679 1943 5679 2950 5680 1945 5680 1944 5680 2950 5681 1946 5681 1945 5681 2950 5682 1947 5682 1946 5682 2950 5683 1948 5683 1947 5683 2948 5684 2895 5684 2950 5684 1949 5685 1948 5685 2950 5685 2950 5686 1954 5686 1949 5686 1954 5687 2950 5687 2949 5687 2950 5688 2895 5688 2949 5688 1954 5689 1899 5689 1955 5689 2312 5690 1654 5690 2394 5690 2223 5691 2309 5691 1957 5691 2309 5692 1958 5692 1957 5692 2309 5693 2951 5693 1958 5693 2309 5694 2956 5694 2951 5694 2956 5695 2952 5695 2951 5695 2956 5696 2953 5696 2952 5696 2956 5697 2954 5697 2953 5697 2956 5698 2955 5698 2954 5698 2956 5699 2963 5699 2955 5699 2309 5700 2311 5700 2956 5700 2957 5701 1962 5701 1961 5701 2958 5702 1962 5702 2957 5702 2957 5703 2959 5703 2958 5703 2961 5704 2958 5704 2959 5704 2959 5705 2960 5705 2961 5705 2962 5706 2961 5706 2960 5706 2965 5707 2963 5707 2956 5707 2965 5708 2956 5708 2964 5708 1512 5709 2222 5709 1602 5709 1445 5710 1668 5710 1669 5710 1445 5711 1634 5711 1668 5711 1669 5712 2222 5712 1446 5712 1445 5713 1669 5713 1446 5713 1584 5714 1588 5714 1586 5714 1584 5715 1599 5715 1588 5715 3061 5716 3014 5716 3051 5716 3014 5717 2986 5717 3051 5717 3014 5718 3061 5718 1109 5718 1147 5719 1118 5719 3023 5719 3414 5720 3415 5720 3025 5720 2978 5721 2967 5721 2968 5721 2978 5722 2977 5722 2967 5722 3003 5723 2974 5723 2973 5723 3002 5724 2974 5724 3003 5724 2981 5725 2984 5725 3386 5725 3386 5726 3435 5726 2981 5726 2979 5727 2981 5727 3435 5727 3435 5728 3434 5728 2979 5728 3416 5729 2979 5729 3434 5729 3016 5730 2974 5730 3002 5730 3016 5731 2966 5731 2974 5731 2966 5732 2973 5732 2974 5732 2968 5733 2966 5733 3016 5733 3016 5734 3018 5734 2968 5734 3018 5735 3011 5735 2968 5735 2982 5736 2968 5736 3011 5736 3011 5737 3010 5737 2982 5737 2975 5738 3418 5738 3446 5738 3438 5739 2969 5739 3446 5739 2967 5740 3446 5740 2970 5740 3446 5741 2969 5741 2970 5741 3446 5742 2967 5742 2975 5742 2967 5743 2976 5743 2975 5743 2977 5744 2976 5744 2967 5744 2970 5745 2971 5745 2967 5745 2967 5746 2966 5746 2968 5746 2973 5747 2966 5747 2967 5747 2967 5748 2972 5748 2973 5748 2967 5749 2971 5749 2972 5749 2968 5750 2980 5750 2978 5750 2980 5751 2968 5751 2982 5751 3010 5752 2983 5752 2982 5752 3385 5753 3438 5753 3439 5753 3385 5754 2969 5754 3438 5754 3385 5755 2970 5755 2969 5755 3385 5756 2971 5756 2970 5756 3385 5757 2972 5757 2971 5757 3385 5758 2973 5758 2972 5758 2973 5759 3385 5759 3003 5759 3418 5760 2975 5760 3417 5760 3416 5761 3417 5761 2975 5761 2975 5762 2976 5762 3416 5762 2979 5763 3416 5763 2977 5763 3416 5764 2976 5764 2977 5764 2977 5765 2978 5765 2979 5765 2981 5766 2979 5766 2980 5766 2979 5767 2978 5767 2980 5767 2980 5768 2982 5768 2981 5768 2984 5769 2981 5769 2982 5769 2982 5770 2983 5770 2984 5770 2983 5771 1156 5771 1151 5771 2984 5772 2983 5772 1151 5772 2986 5773 2987 5773 3414 5773 3025 5774 2986 5774 3414 5774 2988 5775 2987 5775 2986 5775 2989 5776 2988 5776 2986 5776 2990 5777 2989 5777 2986 5777 2990 5778 2986 5778 2991 5778 1155 5779 2992 5779 2993 5779 1155 5780 2993 5780 2994 5780 1155 5781 2994 5781 1109 5781 1155 5782 2995 5782 2992 5782 2996 5783 2992 5783 2995 5783 1148 5784 1147 5784 3023 5784 1148 5785 3023 5785 3399 5785 1148 5786 3399 5786 3398 5786 2999 5787 1148 5787 3398 5787 1149 5788 1148 5788 2999 5788 2999 5789 3000 5789 1149 5789 2999 5790 3398 5790 3001 5790 3000 5791 2999 5791 3001 5791 1150 5792 1149 5792 3000 5792 1151 5793 1150 5793 3000 5793 3000 5794 2985 5794 1151 5794 1151 5795 2985 5795 2984 5795 3004 5796 3002 5796 3003 5796 3003 5797 3005 5797 3004 5797 3005 5798 3006 5798 3004 5798 2995 5799 1155 5799 3007 5799 3007 5800 1153 5800 1152 5800 3007 5801 1152 5801 1156 5801 3008 5802 3007 5802 1156 5802 2983 5803 3010 5803 3008 5803 1156 5804 2983 5804 3008 5804 3013 5805 2996 5805 3012 5805 1109 5806 2994 5806 3014 5806 3014 5807 3013 5807 2986 5807 3014 5808 2994 5808 2993 5808 3014 5809 2993 5809 2992 5809 3014 5810 2992 5810 3013 5810 2996 5811 3013 5811 2992 5811 2986 5812 3013 5812 2991 5812 3000 5813 3390 5813 3391 5813 3000 5814 3391 5814 2985 5814 3389 5815 3390 5815 3000 5815 3000 5816 3001 5816 3389 5816 3389 5817 3001 5817 3398 5817 3386 5818 2984 5818 2985 5818 3386 5819 2985 5819 3391 5819 3415 5820 3414 5820 3410 5820 3414 5821 2987 5821 3409 5821 3408 5822 3409 5822 2987 5822 2987 5823 2988 5823 3408 5823 3407 5824 3408 5824 2988 5824 2988 5825 2989 5825 3407 5825 3406 5826 3407 5826 2989 5826 2989 5827 2990 5827 3406 5827 3405 5828 3406 5828 2990 5828 1154 5829 1153 5829 3007 5829 2991 5830 3015 5830 3022 5830 2991 5831 3020 5831 3015 5831 3021 5832 3015 5832 3020 5832 3006 5833 3015 5833 3021 5833 3006 5834 3005 5834 3015 5834 3005 5835 3003 5835 3015 5835 3385 5836 3015 5836 3003 5836 3402 5837 3015 5837 3385 5837 3403 5838 3015 5838 3402 5838 3404 5839 3015 5839 3403 5839 3022 5840 3015 5840 3404 5840 3006 5841 3021 5841 3004 5841 3004 5842 3016 5842 3002 5842 3004 5843 3018 5843 3016 5843 3004 5844 3017 5844 3018 5844 3011 5845 3018 5845 3017 5845 3008 5846 3011 5846 3017 5846 3009 5847 3008 5847 3017 5847 3009 5848 3017 5848 3019 5848 3021 5849 3017 5849 3004 5849 3021 5850 3019 5850 3017 5850 3404 5851 2990 5851 3022 5851 3009 5852 3019 5852 2998 5852 2998 5853 3019 5853 2997 5853 2990 5854 3404 5854 3405 5854 3012 5855 3021 5855 3020 5855 3020 5856 2991 5856 3012 5856 3012 5857 2991 5857 3013 5857 3021 5858 3012 5858 3019 5858 3012 5859 2996 5859 2997 5859 3012 5860 2997 5860 3019 5860 3007 5861 3008 5861 3009 5861 3007 5862 3009 5862 2998 5862 3007 5863 2998 5863 2997 5863 3022 5864 2990 5864 2991 5864 3008 5865 3010 5865 3011 5865 2995 5866 2997 5866 2996 5866 2995 5867 3007 5867 2997 5867 1154 5868 3007 5868 1155 5868 3026 5869 3027 5869 3028 5869 3026 5870 3028 5870 3029 5870 3030 5871 3026 5871 3029 5871 3031 5872 3027 5872 3026 5872 3026 5873 3032 5873 3031 5873 3031 5874 3032 5874 3033 5874 3294 5875 3031 5875 3033 5875 3294 5876 3295 5876 3031 5876 3033 5877 3034 5877 3294 5877 3296 5878 3294 5878 3034 5878 3035 5879 3296 5879 3034 5879 3035 5880 3298 5880 3305 5880 3296 5881 3035 5881 3305 5881 3037 5882 3038 5882 3039 5882 3040 5883 3038 5883 3037 5883 3037 5884 3041 5884 3040 5884 3451 5885 3040 5885 3041 5885 3041 5886 3042 5886 3451 5886 3415 5887 3451 5887 3042 5887 3044 5888 3043 5888 3025 5888 3025 5889 3042 5889 3044 5889 3042 5890 3025 5890 3415 5890 3045 5891 3046 5891 3047 5891 3043 5892 3045 5892 3047 5892 3043 5893 3047 5893 3048 5893 3043 5894 3048 5894 3049 5894 3043 5895 3049 5895 3050 5895 3051 5896 3043 5896 3050 5896 3043 5897 3051 5897 3025 5897 3025 5898 3051 5898 2986 5898 3052 5899 3036 5899 3299 5899 1119 5900 1122 5900 3023 5900 1118 5901 1119 5901 3023 5901 3452 5902 1121 5902 3300 5902 1127 5903 1121 5903 3452 5903 3452 5904 3453 5904 1127 5904 1126 5905 1127 5905 3453 5905 3453 5906 3053 5906 1126 5906 1125 5907 1126 5907 3053 5907 3454 5908 1124 5908 1125 5908 3053 5909 3454 5909 1125 5909 1123 5910 1124 5910 3454 5910 3454 5911 3397 5911 1123 5911 1123 5912 3397 5912 3399 5912 1123 5913 3399 5913 3023 5913 1122 5914 1123 5914 3023 5914 1121 5915 1120 5915 3300 5915 1120 5916 1085 5916 3300 5916 3303 5917 3031 5917 3295 5917 1074 5918 1114 5918 3303 5918 3054 5919 3027 5919 3031 5919 3303 5920 3054 5920 3031 5920 3303 5921 1114 5921 1115 5921 3303 5922 1115 5922 1116 5922 3303 5923 1116 5923 3055 5923 3303 5924 3055 5924 3056 5924 3054 5925 3303 5925 3056 5925 3027 5926 3054 5926 3057 5926 3027 5927 3057 5927 3058 5927 3028 5928 3027 5928 3058 5928 1111 5929 3063 5929 3059 5929 1111 5930 3059 5930 3060 5930 1112 5931 1111 5931 3060 5931 3063 5932 1111 5932 1110 5932 3061 5933 3063 5933 1110 5933 3061 5934 3050 5934 3049 5934 3061 5935 3049 5935 3048 5935 3061 5936 3048 5936 3062 5936 3061 5937 3062 5937 3063 5937 3051 5938 3050 5938 3061 5938 3061 5939 1110 5939 1109 5939 3053 5940 3453 5940 3396 5940 3454 5941 3053 5941 3396 5941 3040 5942 3401 5942 3038 5942 3412 5943 3401 5943 3040 5943 3040 5944 3451 5944 3412 5944 3039 5945 3038 5945 3024 5945 3052 5946 3298 5946 3035 5946 3052 5947 3035 5947 3034 5947 3299 5948 3298 5948 3052 5948 3028 5949 3064 5949 3065 5949 3029 5950 3028 5950 3065 5950 3065 5951 3066 5951 3029 5951 3029 5952 3066 5952 3067 5952 3030 5953 3029 5953 3067 5953 3067 5954 3066 5954 3068 5954 3069 5955 3067 5955 3068 5955 3068 5956 3070 5956 3069 5956 3070 5957 3071 5957 3072 5957 3073 5958 3072 5958 3071 5958 3069 5959 3070 5959 3072 5959 3069 5960 3072 5960 3074 5960 3069 5961 3074 5961 3075 5961 3069 5962 3075 5962 3076 5962 3077 5963 3069 5963 3076 5963 3076 5964 3078 5964 3077 5964 3079 5965 3073 5965 3071 5965 3071 5966 3080 5966 3079 5966 3077 5967 3078 5967 3081 5967 3077 5968 3081 5968 3082 5968 3083 5969 3077 5969 3082 5969 3082 5970 3084 5970 3083 5970 3085 5971 3083 5971 3084 5971 3084 5972 3086 5972 3085 5972 3087 5973 3085 5973 3086 5973 3086 5974 3088 5974 3087 5974 3087 5975 3088 5975 3089 5975 3087 5976 3089 5976 3090 5976 3091 5977 3087 5977 3090 5977 3090 5978 3092 5978 3091 5978 3095 5979 3096 5979 3094 5979 3093 5980 3095 5980 3094 5980 3091 5981 3092 5981 3096 5981 3096 5982 3095 5982 3097 5982 3097 5983 3091 5983 3096 5983 3095 5984 3098 5984 3097 5984 3097 5985 3098 5985 3099 5985 3100 5986 3097 5986 3099 5986 3099 5987 3101 5987 3047 5987 3047 5988 3101 5988 3102 5988 3048 5989 3047 5989 3102 5989 3084 5990 3082 5990 3086 5990 3088 5991 3086 5991 3082 5991 3082 5992 3103 5992 3088 5992 3104 5993 3088 5993 3103 5993 3103 5994 3105 5994 3104 5994 3106 5995 3104 5995 3105 5995 3105 5996 3107 5996 3106 5996 3108 5997 3106 5997 3107 5997 3107 5998 3109 5998 3108 5998 3110 5999 3108 5999 3109 5999 3109 6000 3306 6000 3110 6000 3218 6001 3110 6001 3306 6001 3111 6002 3113 6002 3112 6002 3114 6003 3112 6003 3113 6003 3113 6004 3115 6004 3114 6004 3116 6005 3114 6005 3115 6005 3115 6006 3117 6006 3116 6006 3116 6007 3117 6007 3118 6007 3119 6008 3116 6008 3118 6008 3118 6009 3308 6009 3119 6009 3247 6010 3119 6010 3308 6010 3096 6011 3120 6011 3094 6011 3121 6012 3094 6012 3120 6012 3120 6013 3122 6013 3121 6013 3123 6014 3121 6014 3122 6014 3122 6015 3124 6015 3123 6015 3125 6016 3123 6016 3124 6016 3124 6017 3126 6017 3125 6017 3127 6018 3125 6018 3126 6018 3126 6019 3128 6019 3127 6019 3129 6020 3127 6020 3128 6020 3128 6021 3130 6021 3129 6021 3131 6022 3129 6022 3130 6022 3130 6023 3132 6023 3131 6023 3133 6024 3131 6024 3132 6024 3132 6025 3307 6025 3133 6025 3245 6026 3133 6026 3307 6026 3072 6027 3134 6027 3074 6027 3135 6028 3074 6028 3134 6028 3134 6029 3136 6029 3135 6029 3137 6030 3135 6030 3136 6030 3136 6031 3138 6031 3137 6031 3139 6032 3137 6032 3138 6032 3138 6033 3140 6033 3139 6033 3141 6034 3139 6034 3140 6034 3140 6035 3142 6035 3141 6035 3143 6036 3141 6036 3142 6036 3142 6037 3144 6037 3143 6037 3145 6038 3143 6038 3144 6038 3144 6039 3146 6039 3145 6039 3147 6040 3145 6040 3146 6040 3146 6041 3309 6041 3147 6041 3252 6042 3147 6042 3309 6042 3135 6043 3075 6043 3074 6043 3137 6044 3078 6044 3076 6044 3137 6045 3076 6045 3075 6045 3135 6046 3137 6046 3075 6046 3137 6047 3139 6047 3078 6047 3148 6048 3082 6048 3081 6048 3148 6049 3081 6049 3078 6049 3078 6050 3139 6050 3141 6050 3148 6051 3078 6051 3141 6051 3103 6052 3082 6052 3148 6052 3141 6053 3143 6053 3148 6053 3148 6054 3143 6054 3145 6054 3149 6055 3148 6055 3145 6055 3149 6056 3105 6056 3103 6056 3148 6057 3149 6057 3103 6057 3107 6058 3105 6058 3149 6058 3145 6059 3147 6059 3149 6059 3255 6060 3109 6060 3107 6060 3149 6061 3255 6061 3107 6061 3149 6062 3147 6062 3252 6062 3149 6063 3252 6063 3310 6063 3255 6064 3149 6064 3310 6064 3109 6065 3255 6065 3253 6065 3306 6066 3109 6066 3253 6066 3096 6067 3092 6067 3120 6067 3122 6068 3120 6068 3092 6068 3092 6069 3090 6069 3122 6069 3122 6070 3090 6070 3150 6070 3124 6071 3122 6071 3150 6071 3151 6072 3126 6072 3124 6072 3150 6073 3151 6073 3124 6073 3089 6074 3088 6074 3151 6074 3151 6075 3150 6075 3089 6075 3088 6076 3104 6076 3151 6076 3128 6077 3126 6077 3151 6077 3151 6078 3104 6078 3106 6078 3152 6079 3151 6079 3106 6079 3152 6080 3130 6080 3128 6080 3151 6081 3152 6081 3128 6081 3106 6082 3108 6082 3152 6082 3132 6083 3130 6083 3152 6083 3152 6084 3108 6084 3110 6084 3110 6085 3218 6085 3152 6085 3152 6086 3218 6086 3259 6086 3261 6087 3152 6087 3259 6087 3152 6088 3261 6088 3132 6088 3132 6089 3261 6089 3263 6089 3307 6090 3132 6090 3263 6090 3072 6091 3153 6091 3134 6091 3136 6092 3134 6092 3153 6092 3153 6093 3154 6093 3136 6093 3138 6094 3136 6094 3154 6094 3154 6095 3155 6095 3138 6095 3140 6096 3138 6096 3155 6096 3156 6097 3142 6097 3140 6097 3155 6098 3156 6098 3140 6098 3157 6099 3112 6099 3156 6099 3158 6100 3157 6100 3156 6100 3159 6101 3158 6101 3156 6101 3156 6102 3155 6102 3159 6102 3112 6103 3114 6103 3156 6103 3144 6104 3142 6104 3156 6104 3156 6105 3114 6105 3116 6105 3156 6106 3116 6106 3119 6106 3156 6107 3119 6107 3247 6107 3156 6108 3247 6108 3312 6108 3269 6109 3156 6109 3312 6109 3269 6110 3146 6110 3144 6110 3156 6111 3269 6111 3144 6111 3146 6112 3269 6112 3271 6112 3309 6113 3146 6113 3271 6113 3028 6114 3058 6114 3064 6114 3160 6115 3064 6115 3058 6115 3058 6116 3057 6116 3160 6116 3161 6117 3160 6117 3057 6117 3057 6118 3056 6118 3161 6118 3162 6119 3161 6119 3056 6119 3056 6120 3055 6120 3162 6120 3163 6121 3162 6121 3055 6121 3055 6122 1116 6122 3163 6122 1117 6123 3163 6123 1116 6123 3102 6124 3164 6124 3048 6124 3062 6125 3048 6125 3164 6125 3164 6126 3165 6126 3062 6126 3063 6127 3062 6127 3165 6127 3165 6128 3166 6128 3063 6128 3059 6129 3063 6129 3166 6129 3166 6130 3167 6130 3059 6130 3060 6131 3059 6131 3167 6131 3167 6132 1113 6132 3060 6132 1112 6133 3060 6133 1113 6133 3095 6134 3168 6134 3098 6134 3164 6135 3102 6135 3101 6135 3169 6136 3099 6136 3098 6136 3099 6137 3169 6137 3101 6137 3101 6138 3170 6138 3164 6138 3170 6139 3101 6139 3169 6139 3098 6140 3171 6140 3169 6140 3171 6141 3098 6141 3168 6141 3172 6142 3169 6142 3171 6142 3169 6143 3172 6143 3170 6143 3165 6144 3164 6144 3170 6144 3170 6145 3173 6145 3165 6145 3173 6146 3170 6146 3172 6146 3168 6147 3174 6147 3171 6147 3175 6148 3172 6148 3171 6148 3172 6149 3175 6149 3173 6149 3166 6150 3165 6150 3173 6150 3177 6151 3173 6151 3175 6151 3173 6152 3177 6152 3166 6152 3174 6153 1104 6153 3171 6153 3171 6154 3176 6154 3175 6154 3176 6155 3171 6155 1104 6155 1104 6156 1090 6156 3176 6156 3167 6157 3166 6157 3177 6157 3175 6158 1094 6158 3177 6158 1094 6159 3175 6159 3176 6159 1092 6160 3176 6160 1090 6160 3176 6161 1092 6161 1094 6161 1113 6162 3167 6162 3177 6162 1094 6163 1097 6163 3177 6163 3177 6164 1097 6164 1113 6164 1089 6165 1107 6165 3178 6165 3179 6166 3071 6166 3070 6166 3179 6167 3070 6167 3187 6167 3178 6168 3179 6168 3187 6168 3179 6169 3178 6169 1107 6169 3080 6170 3071 6170 3179 6170 1107 6171 1399 6171 3179 6171 3180 6172 3179 6172 1399 6172 3180 6173 3181 6173 3182 6173 3182 6174 3080 6174 3179 6174 3183 6175 3180 6175 1399 6175 1399 6176 1398 6176 3183 6176 1397 6177 3184 6177 3183 6177 1398 6178 1397 6178 3183 6178 3185 6179 3184 6179 1397 6179 1397 6180 1106 6180 3185 6180 3185 6181 3168 6181 3093 6181 3185 6182 1106 6182 1104 6182 3185 6183 1104 6183 3174 6183 3168 6184 3185 6184 3174 6184 3095 6185 3093 6185 3168 6185 3064 6186 3160 6186 3065 6186 3186 6187 3065 6187 3160 6187 3065 6188 3186 6188 3066 6188 3187 6189 3070 6189 3068 6189 3068 6190 3188 6190 3187 6190 3188 6191 3068 6191 3066 6191 3066 6192 3189 6192 3188 6192 3189 6193 3066 6193 3186 6193 3186 6194 3190 6194 3189 6194 3190 6195 3186 6195 3160 6195 3160 6196 3161 6196 3190 6196 3178 6197 3187 6197 3188 6197 3188 6198 3191 6198 3178 6198 3191 6199 3188 6199 3189 6199 3192 6200 3189 6200 3190 6200 3189 6201 3192 6201 3191 6201 3193 6202 3190 6202 3161 6202 3190 6203 3193 6203 3192 6203 3161 6204 3162 6204 3193 6204 1089 6205 3178 6205 3191 6205 3194 6206 3191 6206 3192 6206 3191 6207 3194 6207 1089 6207 3195 6208 3192 6208 3193 6208 3192 6209 3195 6209 3194 6209 3196 6210 3193 6210 3162 6210 3193 6211 3196 6211 3195 6211 1099 6212 1089 6212 3194 6212 1099 6213 3194 6213 3195 6213 3162 6214 3163 6214 3196 6214 1102 6215 3195 6215 3196 6215 3195 6216 1102 6216 1099 6216 3163 6217 1117 6217 3196 6217 1103 6218 3196 6218 1117 6218 3196 6219 1103 6219 1102 6219 3199 6220 3182 6220 3181 6220 3200 6221 3182 6221 3199 6221 3199 6222 3198 6222 3200 6222 3201 6223 3200 6223 3198 6223 3198 6224 3197 6224 3201 6224 3201 6225 3197 6225 3111 6225 3201 6226 3111 6226 3112 6226 3067 6227 3069 6227 3077 6227 3067 6228 3077 6228 3083 6228 3067 6229 3083 6229 3085 6229 3067 6230 3085 6230 3087 6230 3067 6231 3087 6231 3091 6231 3067 6232 3091 6232 3097 6232 3100 6233 3067 6233 3097 6233 3100 6234 3045 6234 3043 6234 3100 6235 3043 6235 3044 6235 3100 6236 3044 6236 3042 6236 3100 6237 3042 6237 3041 6237 3100 6238 3041 6238 3037 6238 3100 6239 3037 6239 3039 6239 3039 6240 3024 6240 3036 6240 3100 6241 3039 6241 3036 6241 3100 6242 3036 6242 3052 6242 3100 6243 3052 6243 3034 6243 3100 6244 3034 6244 3033 6244 3100 6245 3033 6245 3032 6245 3100 6246 3032 6246 3026 6246 3100 6247 3026 6247 3030 6247 3067 6248 3100 6248 3030 6248 3046 6249 3045 6249 3100 6249 3054 6250 3056 6250 3057 6250 3090 6251 3089 6251 3150 6251 3181 6252 3180 6252 3183 6252 3183 6253 3184 6253 3181 6253 3179 6254 3180 6254 3182 6254 3112 6255 3157 6255 3201 6255 3182 6256 3200 6256 3201 6256 3157 6257 3182 6257 3201 6257 3157 6258 3158 6258 3182 6258 3158 6259 3159 6259 3182 6259 3080 6260 3182 6260 3159 6260 3080 6261 3159 6261 3155 6261 3080 6262 3155 6262 3154 6262 3079 6263 3080 6263 3154 6263 3079 6264 3154 6264 3153 6264 3073 6265 3079 6265 3153 6265 3072 6266 3073 6266 3153 6266 3094 6267 3211 6267 3217 6267 3217 6268 3211 6268 3216 6268 3216 6269 3211 6269 3210 6269 3216 6270 3210 6270 3215 6270 3215 6271 3210 6271 3209 6271 3215 6272 3209 6272 3205 6272 3215 6273 3205 6273 3204 6273 3206 6274 3204 6274 3205 6274 3207 6275 3204 6275 3206 6275 3207 6276 3202 6276 3204 6276 3204 6277 3202 6277 3203 6277 3214 6278 3202 6278 3207 6278 3185 6279 3204 6279 3184 6279 3202 6280 3214 6280 3111 6280 3202 6281 3111 6281 3197 6281 3198 6282 3202 6282 3197 6282 3202 6283 3198 6283 3203 6283 3199 6284 3203 6284 3198 6284 3203 6285 3199 6285 3204 6285 3199 6286 3181 6286 3204 6286 3204 6287 3185 6287 3215 6287 3184 6288 3204 6288 3181 6288 3215 6289 3185 6289 3093 6289 3245 6290 3311 6290 3133 6290 3133 6291 3311 6291 3265 6291 3208 6292 3131 6292 3265 6292 3265 6293 3131 6293 3133 6293 3265 6294 3267 6294 3208 6294 3208 6295 3267 6295 3308 6295 3208 6296 3308 6296 3118 6296 3208 6297 3118 6297 3212 6297 3208 6298 3212 6298 3213 6298 3131 6299 3208 6299 3129 6299 3214 6300 3208 6300 3213 6300 3208 6301 3205 6301 3209 6301 3205 6302 3208 6302 3206 6302 3206 6303 3208 6303 3207 6303 3207 6304 3208 6304 3214 6304 3209 6305 3127 6305 3208 6305 3208 6306 3127 6306 3129 6306 3127 6307 3209 6307 3125 6307 3210 6308 3125 6308 3209 6308 3125 6309 3210 6309 3123 6309 3211 6310 3123 6310 3210 6310 3123 6311 3211 6311 3121 6311 3094 6312 3121 6312 3211 6312 3115 6313 3212 6313 3117 6313 3212 6314 3115 6314 3213 6314 3113 6315 3213 6315 3115 6315 3213 6316 3113 6316 3214 6316 3111 6317 3214 6317 3113 6317 3093 6318 3216 6318 3215 6318 3216 6319 3093 6319 3217 6319 3217 6320 3093 6320 3094 6320 3117 6321 3212 6321 3118 6321 3047 6322 3100 6322 3099 6322 3046 6323 3100 6323 3047 6323 3024 6324 3401 6324 3036 6324 3024 6325 3038 6325 3401 6325 3220 6326 3218 6326 3219 6326 3221 6327 3220 6327 3219 6327 3224 6328 3222 6328 3219 6328 3223 6329 3225 6329 3221 6329 3219 6330 3226 6330 3224 6330 3276 6331 3221 6331 3225 6331 3227 6332 3224 6332 3226 6332 3225 6333 3228 6333 3276 6333 3226 6334 3229 6334 3227 6334 3230 6335 3276 6335 3228 6335 3231 6336 3227 6336 3229 6336 3228 6337 3232 6337 3230 6337 3233 6338 3230 6338 3232 6338 3229 6339 3234 6339 3231 6339 3232 6340 3235 6340 3233 6340 3236 6341 3231 6341 3234 6341 3233 6342 3235 6342 3237 6342 3238 6343 3233 6343 3237 6343 3239 6344 3240 6344 3236 6344 3234 6345 3239 6345 3236 6345 3241 6346 3240 6346 3239 6346 3237 6347 3241 6347 3238 6347 3242 6348 3238 6348 3241 6348 3243 6349 3242 6349 3241 6349 3239 6350 3243 6350 3241 6350 3246 6351 3245 6351 3244 6351 3250 6352 3251 6352 3252 6352 3254 6353 3226 6353 3253 6353 3256 6354 3254 6354 3255 6354 3256 6355 3252 6355 3251 6355 3257 6356 3256 6356 3251 6356 3221 6357 3218 6357 3220 6357 3218 6358 3221 6358 3258 6358 3258 6359 3260 6359 3259 6359 3260 6360 3262 6360 3261 6360 3262 6361 3244 6361 3263 6361 3246 6362 3264 6362 3245 6362 3264 6363 3266 6363 3265 6363 3266 6364 3248 6364 3267 6364 3249 6365 3268 6365 3247 6365 3268 6366 3270 6366 3269 6366 3270 6367 3250 6367 3271 6367 3272 6368 3226 6368 3254 6368 3254 6369 3256 6369 3272 6369 3273 6370 3272 6370 3256 6370 3256 6371 3257 6371 3273 6371 3258 6372 3274 6372 3260 6372 3262 6373 3260 6373 3274 6373 3274 6374 3275 6374 3262 6374 3262 6375 3275 6375 3244 6375 3277 6376 3229 6376 3226 6376 3272 6377 3277 6377 3226 6377 3273 6378 3257 6378 3277 6378 3272 6379 3273 6379 3277 6379 3257 6380 3278 6380 3277 6380 3234 6381 3229 6381 3277 6381 3279 6382 3277 6382 3278 6382 3279 6383 3239 6383 3234 6383 3277 6384 3279 6384 3234 6384 3278 6385 3280 6385 3279 6385 3243 6386 3239 6386 3279 6386 3279 6387 3280 6387 3281 6387 3282 6388 3279 6388 3281 6388 3279 6389 3282 6389 3243 6389 3242 6390 3243 6390 3282 6390 3281 6391 3283 6391 3282 6391 3284 6392 3282 6392 3283 6392 3282 6393 3284 6393 3242 6393 3238 6394 3242 6394 3284 6394 3283 6395 3285 6395 3284 6395 3286 6396 3233 6396 3238 6396 3284 6397 3286 6397 3238 6397 3286 6398 3284 6398 3285 6398 3230 6399 3233 6399 3286 6399 3285 6400 3244 6400 3286 6400 3274 6401 3276 6401 3230 6401 3286 6402 3274 6402 3230 6402 3286 6403 3244 6403 3275 6403 3286 6404 3275 6404 3274 6404 3258 6405 3276 6405 3274 6405 3276 6406 3258 6406 3221 6406 3247 6407 3248 6407 3249 6407 3249 6408 3288 6408 3287 6408 3248 6409 3288 6409 3249 6409 3257 6410 3251 6410 3250 6410 3244 6411 3285 6411 3289 6411 3289 6411 3246 6411 3244 6411 3280 6412 3278 6412 3290 6412 3290 6412 3291 6412 3280 6412 3281 6413 3280 6413 3291 6413 3291 6413 3292 6413 3281 6413 3292 6414 3293 6414 3283 6414 3283 6414 3281 6414 3292 6414 3293 6415 3289 6415 3285 6415 3285 6415 3283 6415 3293 6415 3278 6416 3257 6416 3250 6416 3250 6416 3290 6416 3278 6416 3270 6417 3290 6417 3250 6417 3268 6418 3290 6418 3270 6418 3287 6419 3291 6419 3290 6419 3287 6420 3292 6420 3291 6420 3287 6421 3288 6421 3292 6421 3288 6422 3293 6422 3292 6422 3289 6423 3293 6423 3288 6423 3264 6424 3246 6424 3289 6424 3264 6425 3289 6425 3266 6425 3219 6426 3223 6426 3221 6426 3219 6427 3222 6427 3223 6427 3219 6428 3253 6428 3226 6428 3268 6429 3287 6429 3290 6429 3249 6430 3287 6430 3268 6430 3248 6431 3266 6431 3288 6431 3266 6432 3289 6432 3288 6432 3296 6433 3297 6433 3295 6433 3294 6434 3296 6434 3295 6434 3304 6435 3299 6435 3036 6435 3301 6436 3452 6436 3300 6436 1085 6437 1086 6437 3300 6437 3303 6438 3295 6438 3297 6438 3303 6439 3302 6439 1074 6439 3452 6440 3301 6440 3456 6440 3456 6441 3455 6441 3452 6441 3305 6442 3298 6442 3299 6442 3307 6443 3244 6443 3245 6443 3308 6444 3248 6444 3247 6444 3309 6445 3250 6445 3252 6445 3253 6446 3255 6446 3254 6446 3255 6447 3310 6447 3256 6447 3256 6448 3310 6448 3252 6448 3259 6449 3218 6449 3258 6449 3261 6450 3259 6450 3260 6450 3263 6451 3261 6451 3262 6451 3307 6452 3263 6452 3244 6452 3264 6453 3311 6453 3245 6453 3265 6454 3311 6454 3264 6454 3267 6455 3265 6455 3266 6455 3308 6456 3267 6456 3248 6456 3268 6457 3312 6457 3247 6457 3269 6458 3312 6458 3268 6458 3271 6459 3269 6459 3270 6459 3309 6460 3271 6460 3250 6460 3219 6461 3218 6461 3306 6461 3306 6462 3253 6462 3219 6462 1082 6463 1080 6463 3356 6463 3300 6464 3358 6464 3357 6464 3301 6465 3300 6465 3357 6465 3327 6466 3321 6466 3318 6466 3327 6467 3326 6467 3321 6467 3364 6468 3313 6468 3329 6468 3329 6469 3313 6469 3333 6469 3333 6470 3313 6470 3332 6470 3332 6471 3313 6471 3331 6471 3331 6472 3313 6472 3340 6472 3340 6473 3313 6473 3362 6473 3332 6474 3330 6474 3333 6474 3342 6475 3320 6475 3330 6475 3330 6476 3320 6476 3319 6476 3321 6477 3319 6477 3320 6477 3359 6478 3319 6478 3321 6478 3325 6479 3359 6479 3321 6479 3359 6480 3323 6480 3319 6480 3333 6481 3330 6481 3319 6481 3333 6482 3319 6482 3323 6482 3339 6483 3413 6483 3336 6483 3340 6484 3413 6484 3339 6484 3321 6485 3326 6485 3325 6485 3304 6486 3305 6486 3299 6486 3367 6487 3305 6487 3304 6487 3366 6488 3367 6488 3304 6488 3365 6489 3366 6489 3304 6489 3304 6490 3362 6490 3365 6490 3313 6491 3365 6491 3362 6491 3413 6492 3340 6492 3362 6492 3350 6493 3368 6493 3349 6493 3356 6494 3368 6494 3350 6494 3350 6495 3351 6495 3356 6495 3355 6496 3356 6496 3351 6496 3351 6497 3352 6497 3355 6497 3352 6498 3357 6498 3355 6498 3352 6499 3353 6499 3357 6499 3301 6500 3357 6500 3353 6500 3460 6501 3301 6501 3353 6501 3384 6502 3465 6502 3314 6502 3465 6503 3458 6503 3314 6503 3314 6504 3344 6504 3384 6504 3382 6505 3384 6505 3344 6505 3344 6506 3345 6506 3382 6506 3379 6507 3382 6507 3345 6507 3345 6508 3346 6508 3379 6508 3377 6509 3379 6509 3346 6509 3346 6510 3347 6510 3377 6510 3374 6511 3377 6511 3347 6511 3347 6512 3348 6512 3374 6512 3372 6513 3374 6513 3348 6513 3348 6514 3349 6514 3372 6514 3372 6515 3349 6515 3368 6515 3456 6516 3301 6516 3460 6516 3461 6517 3459 6517 3354 6517 3459 6518 3461 6518 3432 6518 3445 6519 3463 6519 3459 6519 3343 6520 3341 6520 3317 6520 3315 6521 3317 6521 3341 6521 3315 6522 3318 6522 3317 6522 3315 6523 3373 6523 3318 6523 3315 6524 3375 6524 3373 6524 3315 6525 3376 6525 3375 6525 3378 6526 3376 6526 3315 6526 3316 6527 3315 6527 3337 6527 3315 6528 3341 6528 3337 6528 3315 6529 3316 6529 3378 6529 3316 6530 3380 6530 3378 6530 3337 6531 3338 6531 3316 6531 3381 6532 3380 6532 3316 6532 3316 6533 3459 6533 3381 6533 3459 6534 3383 6534 3381 6534 3459 6535 3463 6535 3383 6535 3316 6536 3354 6536 3459 6536 3316 6537 3338 6537 3354 6537 3317 6538 3342 6538 3343 6538 3320 6539 3342 6539 3317 6539 3321 6540 3320 6540 3317 6540 3317 6541 3318 6541 3321 6541 3318 6542 3373 6542 3328 6542 3328 6543 3327 6543 3318 6543 3324 6544 3364 6544 3329 6544 3322 6545 3329 6545 3333 6545 3329 6546 3322 6546 3324 6546 3333 6547 3323 6547 3322 6547 1072 6548 3324 6548 3322 6548 3322 6549 3360 6549 1072 6549 3302 6550 1073 6550 1074 6550 3302 6551 3303 6551 3297 6551 3302 6552 3364 6552 3324 6552 3302 6553 3363 6553 3364 6553 3302 6554 3297 6554 3363 6554 3302 6555 3324 6555 1073 6555 3324 6556 1072 6556 1073 6556 1075 6557 3361 6557 1076 6557 1077 6558 1076 6558 3361 6558 1077 6559 3359 6559 3325 6559 1077 6560 3361 6560 3359 6560 3325 6561 1078 6561 1077 6561 3325 6562 1079 6562 1078 6562 3325 6563 3369 6563 1079 6563 3371 6564 3369 6564 3326 6564 3369 6565 3325 6565 3326 6565 3326 6566 3327 6566 3371 6566 3370 6567 3371 6567 3327 6567 3327 6568 3328 6568 3370 6568 3373 6569 3370 6569 3328 6569 3342 6570 3330 6570 3331 6570 3332 6571 3331 6571 3330 6571 3335 6572 3334 6572 3354 6572 3354 6573 3338 6573 3335 6573 3340 6574 3339 6574 3341 6574 3339 6575 3337 6575 3341 6575 3339 6576 3338 6576 3337 6576 3340 6577 3341 6577 3331 6577 3341 6578 3343 6578 3331 6578 3342 6579 3331 6579 3343 6579 3395 6580 3347 6580 3346 6580 3395 6581 3348 6581 3347 6581 3349 6582 3348 6582 3395 6582 3395 6583 3350 6583 3349 6583 3395 6584 3351 6584 3350 6584 3395 6585 3352 6585 3351 6585 3395 6586 3353 6586 3352 6586 3395 6587 3460 6587 3353 6587 3461 6588 3354 6588 3334 6588 3356 6589 1080 6589 3368 6589 3358 6590 3356 6590 3355 6590 3355 6591 3357 6591 3358 6591 3356 6592 3358 6592 1082 6592 3358 6593 1083 6593 1082 6593 1084 6594 1083 6594 3358 6594 1084 6595 3358 6595 3300 6595 1086 6596 1084 6596 3300 6596 3361 6597 3360 6597 3359 6597 1072 6598 3360 6598 3361 6598 3361 6599 1075 6599 1072 6599 3362 6600 3304 6600 3036 6600 3364 6601 3365 6601 3313 6601 3365 6602 3364 6602 3363 6602 3365 6603 3363 6603 3366 6603 3363 6604 3367 6604 3366 6604 3296 6605 3367 6605 3363 6605 3367 6606 3296 6606 3305 6606 3363 6607 3297 6607 3296 6607 3368 6608 1080 6608 3372 6608 1079 6609 3369 6609 1081 6609 1080 6610 1081 6610 3369 6610 3369 6611 3371 6611 1080 6611 3371 6612 3372 6612 1080 6612 3374 6613 3372 6613 3373 6613 3372 6614 3370 6614 3373 6614 3372 6615 3371 6615 3370 6615 3373 6616 3375 6616 3374 6616 3377 6617 3374 6617 3375 6617 3375 6618 3376 6618 3377 6618 3379 6619 3377 6619 3378 6619 3377 6620 3376 6620 3378 6620 3378 6621 3380 6621 3379 6621 3382 6622 3379 6622 3380 6622 3380 6623 3381 6623 3382 6623 3384 6624 3382 6624 3383 6624 3382 6625 3381 6625 3383 6625 3383 6626 3463 6626 3384 6626 3465 6627 3384 6627 3463 6627 3400 6628 3362 6628 3036 6628 3362 6629 3400 6629 3413 6629 3409 6630 3410 6630 3414 6630 3410 6631 3411 6631 3415 6631 3387 6632 3399 6632 3392 6632 3398 6633 3399 6633 3387 6633 3387 6634 3388 6634 3398 6634 3388 6635 3389 6635 3398 6635 3397 6636 3392 6636 3399 6636 3397 6637 3393 6637 3392 6637 3386 6638 3391 6638 3395 6638 3395 6639 3387 6639 3392 6639 3395 6640 3388 6640 3387 6640 3395 6641 3389 6641 3388 6641 3395 6642 3390 6642 3389 6642 3395 6643 3391 6643 3390 6643 3392 6644 3393 6644 3395 6644 3393 6645 3394 6645 3395 6645 3396 6646 3395 6646 3394 6646 3413 6647 3405 6647 3404 6647 3413 6648 3406 6648 3405 6648 3413 6649 3407 6649 3406 6649 3413 6650 3408 6650 3407 6650 3413 6651 3409 6651 3408 6651 3413 6652 3410 6652 3409 6652 3413 6653 3411 6653 3410 6653 3413 6654 3412 6654 3411 6654 3419 6655 3420 6655 3418 6655 3417 6656 3419 6656 3418 6656 3421 6657 3422 6657 3420 6657 3419 6658 3421 6658 3420 6658 3423 6659 3422 6659 3421 6659 3424 6660 3425 6660 3423 6660 3421 6661 3424 6661 3423 6661 3424 6662 3426 6662 3425 6662 3413 6663 3404 6663 3403 6663 3413 6664 3403 6664 3402 6664 3430 6665 3429 6665 3428 6665 3428 6666 3431 6666 3430 6666 3430 6667 3431 6667 3432 6667 3433 6668 3430 6668 3432 6668 3440 6669 3385 6669 3439 6669 3438 6670 3442 6670 3441 6670 3442 6671 3428 6671 3441 6671 3429 6672 3441 6672 3428 6672 3443 6673 3422 6673 3423 6673 3444 6674 3443 6674 3423 6674 3444 6675 3431 6675 3428 6675 3444 6676 3428 6676 3443 6676 3423 6677 3425 6677 3444 6677 3444 6678 3425 6678 3427 6678 3444 6679 3445 6679 3431 6679 3443 6680 3442 6680 3438 6680 3446 6681 3443 6681 3438 6681 3446 6682 3418 6682 3420 6682 3446 6683 3420 6683 3422 6683 3446 6684 3422 6684 3443 6684 3442 6685 3443 6685 3428 6685 3426 6686 3424 6686 3447 6686 3419 6687 3449 6687 3448 6687 3421 6688 3419 6688 3448 6688 3437 6689 3449 6689 3419 6689 3419 6690 3417 6690 3437 6690 3436 6691 3437 6691 3417 6691 3417 6692 3416 6692 3436 6692 3434 6693 3436 6693 3416 6693 3402 6694 3385 6694 3413 6694 3413 6695 3385 6695 3440 6695 3424 6696 3450 6696 3447 6696 3421 6697 3450 6697 3424 6697 3421 6698 3448 6698 3450 6698 3439 6699 3413 6699 3440 6699 3395 6700 3434 6700 3435 6700 3395 6701 3435 6701 3386 6701 3453 6702 3452 6702 3455 6702 3455 6703 3396 6703 3453 6703 3396 6704 3394 6704 3454 6704 3397 6705 3454 6705 3394 6705 3394 6706 3393 6706 3397 6706 3411 6707 3412 6707 3451 6707 3451 6708 3415 6708 3411 6708 3447 6709 3457 6709 3426 6709 3465 6710 3426 6710 3457 6710 3458 6711 3465 6711 3457 6711 3445 6712 3459 6712 3432 6712 3445 6713 3464 6713 3463 6713 3445 6714 3427 6714 3464 6714 3445 6715 3432 6715 3431 6715 3445 6716 3444 6716 3427 6716 3456 6717 3460 6717 3395 6717 3455 6718 3456 6718 3395 6718 3395 6719 3396 6719 3455 6719 3334 6720 3462 6720 3461 6720 3432 6721 3461 6721 3462 6721 3462 6722 3433 6722 3432 6722 3464 6723 3465 6723 3463 6723 3426 6724 3465 6724 3427 6724 3465 6725 3464 6725 3427 6725 3426 6726 3427 6726 3425 6726 3400 6727 3036 6727 3401 6727 3400 6728 3401 6728 3412 6728 3400 6729 3412 6729 3413 6729 1511 6730 2222 6730 1512 6730 1500 6731 2222 6731 1511 6731 1446 6732 2222 6732 1500 6732 1395 6733 3466 6733 1396 6733 1392 6734 3466 6734 1395 6734 1390 6735 3466 6735 1392 6735 1388 6736 3466 6736 1390 6736 1386 6737 3466 6737 1388 6737 1378 6738 3466 6738 1386 6738 1377 6739 3466 6739 1378 6739 1375 6740 3466 6740 1377 6740 1371 6741 3466 6741 1375 6741 1370 6742 3466 6742 1371 6742 1370 6743 1374 6743 3466 6743 1374 6744 1376 6744 3466 6744 1376 6745 1379 6745 3466 6745 1379 6746 1385 6746 3466 6746 1385 6747 1387 6747 3466 6747 1387 6748 1389 6748 3466 6748 1389 6749 1391 6749 3466 6749 1391 6750 1393 6750 3466 6750 1393 6751 1394 6751 3466 6751 2312 6752 3467 6752 1146 6752 1435 6753 3467 6753 1434 6753 1125 6754 3467 6754 1145 6754 1145 6755 3467 6755 1429 6755 1429 6756 3467 6756 1430 6756 1430 6757 3467 6757 1435 6757 1124 6758 3467 6758 1125 6758 1123 6759 3467 6759 1124 6759 1122 6760 3467 6760 1123 6760 1122 6761 1146 6761 3467 6761 2394 6762 3466 6762 3467 6762 2312 6763 2394 6763 3467 6763 1394 6764 1433 6764 3467 6764 1394 6765 3467 6765 3466 6765 1432 6766 3467 6766 1433 6766 1431 6767 3467 6767 1432 6767 1431 6768 1434 6768 3467 6768 1281 6769 2484 6769 1284 6769 1281 6770 1289 6770 2484 6770 1289 6771 1294 6771 2484 6771 1223 6772 2484 6772 1294 6772 1223 6773 1302 6773 2484 6773 3468 6774 2394 6774 1654 6774 2301 6775 2650 6775 2392 6775 2646 6776 3468 6776 2867 6776 1636 6777 3468 6777 1654 6777 1636 6778 1654 6778 1666 6778 1654 6779 1656 6779 1666 6779 2245 6780 3469 6780 2244 6780 3469 6781 1636 6781 2244 6781 2867 6782 3469 6782 2245 6782 1636 6783 3469 6783 3468 6783 3469 6784 2867 6784 3468 6784 1655 6785 3470 6785 1661 6785 3470 6786 1654 6786 1661 6786 1653 6787 3470 6787 1655 6787 1653 6788 1655 6788 1721 6788 1653 6789 1654 6789 3470 6789 1380 6790 2393 6790 2395 6790 2393 6791 2394 6791 3468 6791 2650 6792 2301 6792 2649 6792 2393 6793 3468 6793 2301 6793 2393 6794 3466 6794 2394 6794 1380 6795 3466 6795 2393 6795 1380 6796 1396 6796 3466 6796 2649 6797 3471 6797 2246 6797 3468 6798 3471 6798 2301 6798 3471 6799 2649 6799 2301 6799 2646 6800 2647 6800 3471 6800 2246 6801 3471 6801 2647 6801 2646 6802 3471 6802 3468 6802 907 6803 908 6803 917 6803 3322 6804 3323 6804 3360 6804 3323 6805 3359 6805 3360 6805 934 6806 935 6806 970 6806 935 6807 969 6807 970 6807 406 6808 407 6808 442 6808 407 6809 441 6809 442 6809 2451 6810 2483 6810 2452 6810 2451 6811 2725 6811 2483 6811 2450 6812 2725 6812 2451 6812 2450 6813 2723 6813 2725 6813 2449 6814 2723 6814 2450 6814 2449 6815 2722 6815 2723 6815 2448 6816 2722 6816 2449 6816 2448 6817 2720 6817 2722 6817 2447 6818 2720 6818 2448 6818 2447 6819 2719 6819 2720 6819 2446 6820 2719 6820 2447 6820 2446 6821 2718 6821 2719 6821 2445 6822 2718 6822 2446 6822 2445 6823 2717 6823 2718 6823 2444 6824 2717 6824 2445 6824 2444 6825 2716 6825 2717 6825 2443 6826 2716 6826 2444 6826 2443 6827 2715 6827 2716 6827 2442 6828 2715 6828 2443 6828 2441 6829 2715 6829 2442 6829 2440 6830 2441 6830 2442 6830 2551 6831 2552 6831 2627 6831 2551 6832 2627 6832 2626 6832 2516 6833 2551 6833 2626 6833 2516 6834 2626 6834 2641 6834 2563 6835 2641 6835 2589 6835 2516 6836 2563 6836 2562 6836 2516 6837 2641 6837 2563 6837 2247 6838 2503 6838 2546 6838 2161 6839 2503 6839 2247 6839 2161 6840 2598 6840 2503 6840 2552 6841 2598 6841 2627 6841 2503 6842 2598 6842 2552 6842 2098 6843 2627 6843 2598 6843 2180 6844 2216 6844 2184 6844 2101 6845 2216 6845 2180 6845 2101 6846 2263 6846 2216 6846 2216 6847 2263 6847 2260 6847 2249 6848 2260 6848 2263 6848 2249 6849 2250 6849 2260 6849 2180 6850 2184 6850 2203 6850 2184 6851 2298 6851 2203 6851 2180 6852 2203 6852 2221 6852 427 6853 477 6853 428 6853 398 6854 477 6854 427 6854 398 6855 538 6855 477 6855 477 6856 538 6856 537 6856 477 6857 537 6857 528 6857 477 6858 528 6858 530 6858 477 6859 530 6859 529 6859 477 6860 529 6860 519 6860 477 6861 519 6861 518 6861 477 6862 518 6862 516 6862 512 6863 515 6863 495 6863 511 6864 512 6864 495 6864 521 6865 522 6865 495 6865 511 6866 495 6866 522 6866 515 6867 542 6867 495 6867 495 6868 542 6868 418 6868 419 6869 495 6869 418 6869 397 6870 495 6870 419 6870 3473 6871 1023 6871 947 6871 947 6872 1023 6872 946 6872 1023 6873 1068 6873 946 6873 1043 6874 1068 6874 1023 6874 1039 6875 1023 6875 3472 6875 1047 6876 3472 6876 1023 6876 1039 6877 1040 6877 1023 6877 1040 6878 1043 6878 1023 6878 949 6879 3473 6879 947 6879 1005 6880 3474 6880 3475 6880 1005 6881 1045 6881 3474 6881 1005 6882 1055 6882 1045 6882 1005 6883 1056 6883 1055 6883 1005 6884 1054 6884 1056 6884 1005 6885 1063 6885 1054 6885 1005 6886 1064 6886 1063 6886 926 6887 1064 6887 1005 6887 926 6888 1005 6888 955 6888 955 6889 1005 6889 956 6889 3345 6890 3395 6890 3346 6890 3344 6891 3395 6891 3345 6891 3344 6892 3458 6892 3395 6892 3395 6893 3458 6893 3457 6893 3395 6894 3457 6894 3447 6894 3395 6895 3447 6895 3450 6895 3395 6896 3450 6896 3448 6896 3395 6897 3448 6897 3437 6897 3395 6898 3437 6898 3436 6898 3395 6899 3436 6899 3434 6899 3336 6900 3413 6900 3335 6900 3335 6901 3413 6901 3334 6901 3413 6902 3462 6902 3334 6902 3433 6903 3462 6903 3413 6903 3429 6904 3413 6904 3441 6904 3439 6905 3441 6905 3413 6905 3429 6906 3430 6906 3413 6906 3430 6907 3433 6907 3413 6907 3441 6908 3439 6908 3438 6908 3338 6909 3339 6909 3336 6909 3338 6910 3336 6910 3335 6910 3232 6911 3228 6911 3476 6911 3228 6912 3225 6912 3476 6912 3225 6913 3223 6913 3476 6913 3223 6914 3222 6914 3476 6914 3222 6915 3224 6915 3476 6915 3224 6916 3227 6916 3476 6916 3476 6917 3227 6917 3231 6917 3231 6918 3236 6918 3476 6918 3236 6919 3240 6919 3476 6919 3240 6920 3241 6920 3476 6920 3241 6921 3237 6921 3476 6921 3237 6922 3235 6922 3476 6922 3476 6923 3235 6923 3232 6923

+
+ + +

1601 1634

+
+
+
+
+ + + + 0.00000 0.00002 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/palm/palm_G4.dae b/URDFs/sr_description/meshes/components/palm/palm_G4.dae new file mode 100644 index 0000000..3aaa57f --- /dev/null +++ b/URDFs/sr_description/meshes/components/palm/palm_G4.dae @@ -0,0 +1,122 @@ + + + + + + Blender User + Blender 3.4.1 commit date:2022-12-19, commit time:17:00, hash:55485cb379f7 + + 2023-01-25T12:00:19 + 2023-01-25T12:00:19 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.04392 0.04392 0.04392 1 + + + 0.21961 0.21961 0.21961 1 + + + 0.45000 0.45000 0.45000 1 + + + 32 + + + 1 + + + + + + + + + + + + + + + + + -15.63157 -11.1671 37.04457 -9.852789 -10 45.29752 -15.63157 -8 37.04456 -9.852787 11 45.29753 -15.63157 11 37.04456 -9.996184 -11.77947 45.09273 -9.891212 -11.52065 45.24265 -10.06535 -11.85011 44.99395 -9.852788 -11.1671 45.29752 -10.13958 -11.8742 44.88795 -15.34478 -11.8742 37.45414 -15.40073 -11.86062 37.37424 -15.60974 -11.43769 37.07574 -15.45453 -11.82038 37.2974 -15.54757 -11.6671 37.16453 -31.1548 -10.12936 23.44643 -31.1388 -10.08775 23.46907 -31.16969 -10.12923 23.45685 -31.15277 -10.08763 23.47886 -31.95926 -10.03408 24.04204 -31.92028 -10.03701 24.01628 -32.41716 -9.957194 24.3642 -31.98354 -10.03125 24.05877 -32.47746 -9.947364 24.40462 -32.90916 -9.840753 24.7087 -32.96633 -9.827264 24.74693 -33.39448 -9.688118 25.04852 -33.44838 -9.671392 25.08446 -33.87133 -9.499844 25.38242 -33.92185 -9.480317 25.41599 -34.49449 -9.192632 25.81876 -34.54041 -9.169998 25.84911 -35.09515 -8.824612 26.23935 -35.1364 -8.799649 26.26643 -35.66933 -8.398223 26.64139 -35.70591 -8.371691 26.66521 -36.21322 -7.916285 27.02223 -36.24522 -7.888926 27.04283 -37.19599 -6.798859 27.71037 -37.21931 -6.771961 27.7249 -38.01751 -5.501849 28.28561 -38.03321 -5.477952 28.2948 -39.09484 -2.509955 29.03996 -39.10009 -2.49787 29.04183 -39.3547 0 29.22192 -39.35736 0 29.22198 -30.78843 -10.05235 23.96456 -30.78843 -10.43288 23.96456 -30.79248 -10.03783 23.95903 -30.85965 -10.63651 23.86774 -30.85965 -9.891713 23.86774 -32.96586 -11 21.29985 -32.05224 -8.99898 22.362 -31.15277 -11 23.47886 -34.24037 -9.000475 19.82587 -33.95288 -9.000055 20.16607 -34.5319 -11 19.47051 -33.91099 -9 20.215 -33.86153 -8.999938 20.27262 -34.99076 -9.001958 18.87805 -34.99763 -10.9425 18.86878 -35.32338 -9.002824 18.40917 -35.30551 -10.83623 18.43552 -35.69787 -10.6041 17.81547 -35.88157 -9.004629 17.48455 -35.98874 -10.33803 17.27374 -36.05147 -9.005281 17.1426 -36.42349 -9.006922 16.16142 -36.14739 -10.14442 16.9283 -36.58259 -9.007765 15.47798 -36.5671 -9.299139 15.56322 -36.60354 -9.007891 15.35041 -30.78225 -10.40598 23.9733 -30.78459 -10.40598 23.97494 -30.81714 -10.52709 23.92844 -30.79408 -10.03987 23.96137 -30.76762 -10.22121 23.99917 -30.76519 -10.22008 23.99742 24 0 85.41296 24 0 78.70024 23.95033 0 78.79646 23.975 0 78.70024 23.88242 0 78.86894 23.78801 0 78.89982 22.51415 0 85.41296 23.69038 0 78.88146 21.38016 0 85.63554 20.41444 0 86.27025 20.64093 0 78.53271 20.45454 0 78.73052 20 0 86.77617 20.37647 0 78.78839 20.28034 0 78.80261 20.1 0 78.60358 20 0 78.60358 20.12361 0 78.69785 20.18886 0 78.76985 23.61364 0 78.8184 23.32196 0 78.4992 22.46058 0 78.05376 21.49091 0 78.06588 20.37647 6 78.78839 20.45454 6 78.73052 20.11047 6 79.3445 20 6 80 20 6 78.60358 20.1 6 78.60358 20.12361 6 78.69785 20.18886 6 78.76985 20.28034 6 78.80261 20 2.537532 91.58148 20.00008 0.9425158 91.2116 20.00001 0.5039723 90.86651 19.99998 -0.04999852 90.76329 20.00001 -0.4555604 90.84561 20 4.02107 92.27953 20 8 96.07158 20 6.05 80 20 8 80 19.99998 0.04999887 90.76329 20 -8 86.77617 20 -8 90.96275 20 -7.992074 91.15404 20.00001 -0.8922592 91.15404 20 7.522194 97.05182 20 7.070023 95.73551 20 6.245589 94.3183 20 5.141971 93.10694 20 7.674408 97.32546 20 8.29283 97.78427 20 8.347739 97.80921 19.99999 8.419126 97.84249 23.61364 6 78.8184 23.69038 6 78.88146 23.87255 6 79.29747 23.78801 6 78.89982 23.88242 6 78.86894 23.975 6 78.70024 24 6 78.70024 23.95033 6 78.79646 23.99938 6 79.95001 24 -8 85.41296 24 -8 86.96275 24 8.347738 93.80921 24.00001 8.419132 93.8425 24 8 92.07158 23.99985 -0.89226 87.15404 24 -7.992074 87.15404 24.00001 -0.5667624 86.89865 24.00001 -0.1227943 86.76594 24.00001 -0.04999911 86.76329 24.00004 0.05000001 86.76329 23.99999 0.5197654 86.87382 24.00003 0.8052727 87.06809 24 6.965666 91.51197 24 6.096521 90.12173 23.99938 8 79.95001 24 5.14197 89.10693 24 7.737691 93.39491 24 7.534903 93.09442 24 7.522194 93.05182 23.99992 0.9425114 87.2116 24 2.30319 87.50439 24 3.808211 88.15484 -1.975 0 78.70024 -2 0 78.70024 -1.950333 0 78.79646 -2 0 85.41296 -1.882417 0 78.86894 -1.788005 0 78.89982 0.619842 0 85.63554 1.585566 0 86.27025 -1.690385 0 78.88146 2 0 86.77617 -1.613636 0 78.8184 2 0 78.60358 1.9 0 78.60358 1.876393 0 78.69785 1.811144 0 78.76985 1.719657 0 78.80261 -0.5141522 0 85.41296 1.623529 0 78.78839 1.545454 0 78.73052 1.0144 0 78.27635 0.02500194 0 78.00016 -0.9709919 0 78.25153 -1.690385 6 78.88146 -1.613636 6 78.8184 -1.710841 6 78.96414 -1.788005 6 78.89982 -2 6 79.95001 -1.882417 6 78.86894 -1.950333 6 78.79646 -2 6 78.70024 -1.975 6 78.70024 -2 2.537532 87.58148 -1.99992 0.9425158 87.2116 -1.999988 0.5039723 86.86651 -2 4.02107 88.27953 -2.000019 -0.04999852 86.76329 -1.999992 -0.4555604 86.84561 -2.000022 0.04999887 86.76329 -2 -8 85.41296 -2 -8 86.96275 -2 -7.992074 87.15404 -1.999991 -0.8922592 87.15404 -2.000013 8.419126 93.84249 -2 8.347739 93.80921 -2 8 92.07158 -2 8.29283 93.78427 -2 8 79.95001 -2 5.141971 89.10693 -2 6.245589 90.3183 -2 7.070023 91.73551 -2 7.522194 93.05182 -2 7.674408 93.32546 1.736203 6 79.00723 1.545454 6 78.73052 1.623529 6 78.78839 1.9 6 78.60358 2 6 78.60358 1.876393 6 78.69785 2 6 80 1.811144 6 78.76985 1.719657 6 78.80261 2.000027 0.8052727 91.06809 1.99992 0.9425114 91.2116 2 2.30319 91.50439 2.000001 8.347738 97.80921 2.000011 8.419132 97.8425 2 8 96.07158 2.000036 0.05000001 90.76329 1.999987 0.5197654 90.87382 2 8 80 2 -7.992074 91.15404 1.999853 -0.89226 91.15404 2 -8 90.96275 2.000011 -0.5667624 90.89865 2 -8 86.77617 2 6.965666 95.51197 2 6.096521 94.12173 2 5.14197 93.10694 2.000011 -0.04999911 90.76329 2 3.808211 92.15484 2 7.737691 97.39491 2 7.534903 97.09442 2 7.522194 97.05182 2.000009 -0.1227943 90.76594 -20 -8 86.96275 -20 -7.992074 87.15404 -20.00015 -0.89226 87.15404 -20 0 58.35442 -20 0 67.6 -20 2.783452 57.72694 -20 8 92.07158 -20 5.383815 55.88576 -20 8.347738 93.80921 -19.99999 8.419132 93.8425 -20 -8 81.1 -20 7.627752 52.56674 -20 8 52.48383 -20 7.558959 52.49385 -20 7.545219 52.48383 -20 7.672248 52.67604 -20 7.674957 52.79312 -20 7.593864 53.01306 -20 6.096521 90.12173 -20 6.965666 91.51197 -19.99999 -0.5667624 86.89865 -20 -4.633975 79.45001 -20 5.14197 89.10693 -20 -7.425 80.10408 -20 -7.845929 80.525 -20 -6.85 79.95001 -20 -5.5 79.95001 -20 -5 79.81603 -20 2.30319 87.50439 -20 3.808211 88.15484 -20 -4.5 78.95 -20 -4.5 67.6 -19.99999 -0.1227943 86.76594 -19.99999 -0.04999911 86.76329 -19.99996 0.05000001 86.76329 -20 7.737691 93.39491 -20 7.534903 93.09442 -20 7.522194 93.05182 -20.00001 0.5197654 86.87382 -19.99997 0.8052727 87.06809 -20.00008 0.9425114 87.2116 -21.03607 -10.80751 40.82883 -23.04069 -10.11431 42.23248 -22.19614 -9.342291 39.11337 -23.60113 -7.547463 37.00945 -25.42057 -8.338501 43.89889 -27.0014 -3.675825 33.71841 -26.11347 -4.226118 33.09667 -27.23835 -5.755874 45.17171 -27.89103 -2.607348 34.34133 -27.28798 -3.406847 33.91907 -28.57801 0 46.10976 -28.57801 0 34.82236 -28.31813 -2.616324 45.92778 -28.43525 -1.236314 34.7224 -28.03067 -2.351668 34.43911 -28.62173 0 46.14036 -28.29854 2.9196 45.91407 -40.2508 0 29.53233 -40.54878 1.631817 28.89457 -40.64908 0 28.9648 -39.27928 6.357625 27.39223 -39.36458 5.65907 28.06538 -26.96404 6.358095 44.97964 -40.2399 3.274823 28.67828 -40.3253 2.9196 28.73808 -39.25498 6.5 27.24815 -38.90707 6.5 27.74502 -38.8604 6.577053 27.71235 -24.74977 9.035862 43.42919 -38.49341 7.373648 27.09542 -37.77354 8.604277 25.8405 -21.92066 10.63251 41.44823 -36.96957 9.610816 24.36953 -37.45719 9.039074 25.27304 -34.37295 11 18.74884 -34.38207 10.99998 18.77241 -19.61105 11 39.83102 -35.23461 10.83611 20.81647 -36.06531 10.39656 22.59659 -31.1388 0 23.46907 -26.0733 0 30.63266 -40.02836 0 29.69362 -27.31667 0 31.51188 -28.24811 0 33.04089 -40.21281 0 29.57542 -19.65201 -10.81303 39.85971 -20.79119 -9.407652 38.23279 -21.92945 -8 36.60719 -21.87542 -8 36.56926 -22.24273 -7.548001 36.04982 -24.92514 -4.226118 32.25638 -19.67317 -10.63638 39.5695 -19.57219 -10.69731 39.60398 -19.41918 -10.76541 39.61444 -19.37218 -10.78082 39.60814 -19.17522 -10.81303 39.52585 -19.87025 -10.46113 39.40496 -19.74299 -10.58511 39.52986 -19.67192 -12.7621 39.57008 -19.87025 -12.7621 39.40496 -19.41766 -12.7621 39.61431 -19.17522 -12.7621 39.52585 -19.06016 -13.88552 39.44528 -18.96522 -14.2698 39.37881 -18.72177 -14.93952 39.20834 -23.82293 -8 33.81547 -23.87537 -7.93422 33.74095 -25.06324 -4.03637 32.06108 -31.1388 -10.02759 23.46907 -31.12284 -10.04614 23.49175 -21.79245 -13.15199 36.68659 -27.36366 -14.10366 28.80784 -23.87537 -8 33.74095 -25.79657 -2.358274 31.024 -32.2769 -14.63108 21.85956 -35.85406 -14.7551 16.80078 -31.9534 -9.019498 22.31707 -35.85406 -8 16.80078 -32.48834 -8 21.56055 44.99998 -0.1914873 9.003568 45 -0.186048 9.033534 45.00831 -0.25 9.033459 44.99996 -0.1999999 8.982865 44.99984 -0.2538716 8.946176 44.99984 -0.2483009 8.946512 44.99985 -0.2319718 8.951368 44.99989 -0.2136166 8.964616 -21.175 0 0.1246222 -30.825 0 0.0992316 -21.175 0 11 -30.825 0 11 -21.6875 0 11.88768 -21.31233 0 11.5125 -22.2 0 12.025 -29.8 0 12.025 -30.3125 0 11.88768 -30.68768 0 11.5125 -38.99057 0 16.84909 -39.93136 0 17.74325 -40.04502 0 17.87049 -40.066 0 17.89478 -42.16515 0 22.38991 -42.1957 0 22.59775 -42.19385 0 22.5881 -40.10243 0 29.74549 -40.75143 0 28.81413 -40.76856 0 28.78981 -40.85209 0 28.66065 -40.88351 0 28.61267 -40.95032 0 28.50396 -40.99395 0 28.4334 -41.04599 0 28.34411 -41.09994 0 28.25202 -41.13899 0 28.18113 -41.20148 0 28.06854 -41.22919 0 28.0151 -41.29861 0 27.88296 -41.40068 0 27.67407 -41.39133 0 27.6953 -41.47965 0 27.50556 -41.48172 0 27.49921 -41.52101 0 27.41073 -41.54755 0 27.35132 -41.55947 0 27.32157 -41.61258 0 27.19573 -41.6338 0 27.14121 -41.67476 0 27.03879 -41.7046 0 26.95823 -41.73406 0 26.88048 -42.21768 0 22.77828 -42.22145 0 22.80673 -42.23745 0 22.96887 -42.24235 0 23.01686 -42.25316 0 23.15975 -42.27182 0 24.0804 -42.26582 0 24.24524 -42.26436 0 24.26202 -42.25595 0 24.41359 -42.25326 0 24.44312 -42.24294 0 24.5816 -42.23855 0 24.62358 -42.2224 0 24.78989 -42.22026 0 24.80329 -42.19702 0 24.99766 -42.17309 0 25.16007 -42.16679 0 25.20492 -42.14429 0 25.33693 -42.25836 0 23.22814 -42.26764 0 23.3985 -42.26479 0 23.35079 -42.27367 0 23.56852 -42.2757 0 23.71599 -42.27648 0 23.73821 -42.2756 0 23.89835 -42.27611 0 23.90755 -42.27254 0 24.07656 -42.25948 0 23.25526 -42.25097 0 23.12236 -41.73864 0 26.86579 -41.77175 0 26.77273 -41.79048 0 26.72081 -41.83515 0 26.58481 -41.84399 0 26.55976 -41.8654 0 26.48997 -41.89457 0 26.39733 -41.89468 0 26.39457 -41.94221 0 26.2335 -41.95023 0 26.20213 -41.99703 0 26.02883 -42.03765 0 25.86024 -42.04686 0 25.82363 -42.07651 0 25.68711 -42.09174 0 25.61791 -42.11209 0 25.51264 -42.11234 0 25.51485 -42.12861 0 25.42494 -42.13171 0 25.41167 -42.14986 0 25.30836 -41.80093 0 20.91644 -41.85612 0 21.08345 -41.85998 0 21.09716 -41.90561 0 21.24484 -41.9153 0 21.27941 -41.95202 0 21.40697 -41.96683 0 21.46308 -41.99535 0 21.56982 -42.01452 0 21.64805 -42.02072 0 21.67135 -42.03691 0 21.74098 -42.04492 0 21.77316 -42.05831 0 21.8342 -42.06792 0 21.87525 -42.07874 0 21.92768 -42.08974 0 21.97762 -42.09818 0 22.0214 -42.11037 0 22.08027 -42.11663 0 22.11536 -42.12982 0 22.1832 -42.13407 0 22.20954 -42.16598 0 22.39848 -41.19649 0 19.52743 -41.29412 0 19.71344 -41.28742 0 19.7011 -41.34137 0 19.80744 -41.37102 0 19.86867 -41.38758 0 19.90212 -41.4116 0 19.95331 -41.43275 0 19.99746 -41.45137 0 20.03851 -41.47686 0 20.09348 -41.4903 0 20.12425 -41.51991 0 20.19017 -41.52838 0 20.21052 -41.56191 0 20.28755 -41.56562 0 20.29732 -41.59488 0 20.3663 -41.60199 0 20.38462 -41.62705 0 20.44524 -41.67187 0 20.56007 -41.68902 0 20.60368 -41.7382 0 20.73738 -41.74784 0 20.76286 -41.80353 0 20.92279 -41.20068 0 19.53589 -41.15615 0 19.45419 -41.14612 0 19.43541 -41.11087 0 19.37312 -41.09473 0 19.34406 -41.06484 0 19.29267 -41.04231 0 19.25337 -41.01809 0 19.21287 -40.98886 0 19.16334 -40.97061 0 19.13371 -40.93438 0 19.07396 -40.92243 0 19.05521 -40.87888 0 18.98524 -40.87356 0 18.97738 -40.82236 0 18.89718 -40.82401 0 18.90022 -40.77379 0 18.82374 -40.76481 0 18.80977 -40.72291 0 18.74796 -40.71774 0 18.73989 -40.67139 0 18.67287 -40.10083 0 17.93477 -40.15594 0 17.99949 -40.18094 0 18.02955 -40.21038 0 18.06464 -40.23766 0 18.09807 -40.26414 0 18.13023 -40.29385 0 18.16735 -40.31722 0 18.19625 -40.3495 0 18.23737 -40.36963 0 18.2627 -40.4046 0 18.30813 -40.42137 0 18.32959 -40.45914 0 18.37963 -40.47243 0 18.3969 -40.51311 0 18.45186 -40.52283 0 18.46464 -40.56647 0 18.52481 -40.57256 0 18.53281 -40.61924 0 18.59848 -40.62162 0 18.60141 -40.67001 0 18.67044 36.025 0 11 36.025 0 0.2128129 36.01972 0 0.2127943 26.375 0 0.2127943 26.375 0 11 35 0 12.025 26.51233 0 11.5125 26.8875 0 11.88768 27.4 0 12.025 35.72478 0 11.72478 35.94697 0 11.39225 35.39225 0 11.94698 30.29696 0 41.90764 30.17015 0 41.87215 32.35895 0 43.04232 32.13755 0 42.28835 38.72033 0 46.38016 39.07643 0 46.40801 38.87948 0 46.22781 37.32806 0 45.08153 36.90866 0 44.83335 36.03378 0 44.90519 34.55941 0 43.56946 32.2069 0 42.31118 38.01823 0 45.5457 42.2084 0 70.21218 42.2084 0 67.41297 42 0 67.6 40.4084 0 67.41297 39.25 4.46464e-4 67.6 40.4084 0 64.86296 42 0 85.28413 42.2084 0 85.22474 42.2084 0 81.409 39.2 0 67.59917 39.2 0 64.95001 39.32807 0 62.82043 40.49411 0 63.19118 39.72287 0 60.45989 41.28963 0 58.99728 40.34708 0 57.9257 41.5599 0 53.48676 42.84017 0 53.39157 41.79266 0 52.39184 42.34719 0 52.68526 41.86008 0 51.98737 42.2084 0 78.6098 42.2084 0 75.81059 42.2084 0 73.01139 40.38591 0 16.65846 39.84885 0 16.71328 40.47975 0 17.04018 41.18298 0 16.56071 40.91244 0 17.12517 41.77449 0 16.84374 40.78535 0 17.13699 42.62542 0 16.53031 42.92301 0 16.38492 43.24047 0 16.16123 40.64711 0 17.11091 21.73325 0 27.90483 33.00025 0 16.72511 21.82053 0 27.17433 31.82762 0 16.87757 28.90793 0 17.78647 26.30217 0 19.38668 22.64576 0 24.22991 24.17099 0 21.57956 35.0206 -3.004986 14.7204 35.0206 -0.1999999 14.7204 34.865 -3.09243 14.8748 33.00025 -0.1999999 16.72511 34.75521 -3.270671 14.98374 34.71567 -3.5 15.02297 21.73325 -0.1999999 27.90483 32.68898 -15.62669 17.03397 34.71567 -8 15.02297 34.71568 -8.500018 15.02297 22.88341 -17.09272 26.76358 23.05256 -17.2312 26.59574 20.50851 -6.935604 29.12008 34.04998 -12.79883 15.6835 34.46316 -11.18647 15.27353 34.68121 -9.500018 15.05717 20.51299 -6.856955 29.11564 26.06361 -18.65373 23.60801 27.2232 -18.82072 22.45741 24.16536 -17.96583 25.49156 25.40324 -18.47016 24.26327 25.73501 -18.5647 23.93406 33.4531 -14.29263 16.27577 23.0902 -17.26098 26.55839 28.43778 -18.71653 21.25224 29.62338 -18.33073 20.07582 30.74735 -17.67394 18.96056 20.50064 -0.1999999 29.12789 20.51153 -0.2651532 29.11709 20.51299 -0.3 29.11564 31.77869 -16.76424 17.93721 20.43466 -7.851187 29.19336 20.42846 -8 29.19951 20.42289 -8.809835 29.20504 20.45463 -9.808921 29.17354 22.43283 -16.68443 27.21067 20.59263 -11.75032 29.03661 20.8652 -13.48861 28.76616 20.93198 -13.77596 28.6999 22.23045 -16.47351 27.41148 21.33128 -15.01103 28.30369 21.59716 -15.56776 28.03986 2.873557 -8 0 3.008885 -8 -0.02341377 2.873557 -10 0 3.008885 -13.98923 -0.02341377 2.855663 -10 0.006895124 2.855663 -13.98923 0.006895124 2.725729 -13.98923 0.09357196 2.725729 -10 0.09357196 2.638895 -13.98923 0.2234006 2.638895 -10 0.2234006 2.608401 -13.98923 0.376586 2.608401 -10 0.376586 2.608401 -13.98923 1.889674 2.608401 -10 1.889674 -2.491599 -20.78648 3.585449 -2.491599 -10 3.585449 -2.220439 -10 3.903858 -2.462367 -20.95924 3.627262 -2.485485 -20.87298 3.594389 -2.422348 -21.02638 3.680959 -1.941632 -21.44697 4.12157 -1.889135 -21.48167 4.154058 -1.370787 -10 4.371359 -0.2981954 -10 4.405178 -0.449914 -22.11895 4.427219 -0.5221658 -22.09625 4.434953 -1.239677 -21.82565 4.401827 -1.266123 -21.81391 4.396362 -1.330402 -21.78474 4.38167 1.286473 -10 3.709312 1.286477 -22.40365 3.709309 1.27947 -22.40393 3.714409 1.221374 -22.40559 3.755912 0.9473126 -22.39879 3.933704 0.4733356 -22.34176 4.175066 0.3544617 -22.32056 4.22323 0.2310722 -22.29603 4.268287 -0.299643 -22.16378 4.405387 2.411623 -10 2.479053 2.413721 -21.87829 2.475016 2.122184 -22.17202 2.911698 1.943293 -22.26877 3.121548 1.591412 -22.37195 3.465745 1.382857 -22.3979 3.63701 2.107333 -22.18167 2.930315 2.557765 -14.0726 2.139996 2.524711 -14.16257 2.235364 2.482391 -21.754 2.336817 2.449433 -21.81858 2.406234 2.508401 -14.28923 2.276518 2.512882 -14.22244 2.265506 2.490362 -21.73441 2.318933 2.508401 -21.60413 2.276518 2.504278 -21.67333 2.286472 42.0042 3 64.95001 42 3 67.41297 42.0084 3 67.41297 42.00007 3 64.90646 42.00434 3 64.86294 42.07752 3 63.43943 42.02238 3 64.15135 42.02624 3 64.15138 40.6 0.3751289 67.41297 40.4084 0.2741799 67.41297 42 2.8 67.41297 42.2084 -0.00605905 67.41297 42.44091 -0.02946698 67.41297 42.27122 0.03687548 67.41297 42.0084 0.5014023 67.41297 41.62487 1.4 67.41297 42.04205 0.313437 67.41297 42.13307 0.1556454 67.41297 40.25677 -7.998615 85.409 40.01424 -7.980129 85.409 40.01424 -12.89295 85.409 41.00834 -11.60555 85.409 41.00834 -8 85.409 40.34308 -8 85.409 2.239719 -8 87.22291 2.239719 -14.5 87.22291 2.411329 -8.000001 87.55995 2.920334 -14.5 88.2012 3.928124 -14.5 88.8373 3.49623 -8.000505 88.63247 2.713616 -8.000174 87.98267 5.223824 -7.829246 89.02402 4.92409 -7.9114 89.03207 5.104053 -14.5 89.03084 4.361419 -8.000147 88.9314 3.928124 -8.000659 88.8373 6.015515 -7.619611 88.85345 6.262549 -14.5 88.75128 6.262549 -7.616895 88.75128 18.14124 -8.000664 88.80995 17.64021 -8.000156 88.93104 16.89595 -14.5 89.03084 17.07583 -7.911381 89.03207 18.07188 -14.5 88.8373 19.07967 -14.5 88.2012 19.00399 -8.000318 88.27111 19.58742 -8.000005 87.56206 19.76028 -14.5 87.22291 19.76028 -8 87.22291 16.77618 -7.829246 89.02402 15.98447 -7.619609 88.85345 15.73745 -14.5 88.75128 15.8184 -7.609794 88.78762 15.73745 -7.616895 88.75128 -2.491599 -14.64784 0.369324 -2.529601 -14.64784 0.1781221 -2.491599 -10 0.369324 -2.558485 -10 0.1194986 -2.74125 -14.64784 -0.06348675 -2.654553 -10 0 -2.637832 -14.64784 0.01598435 -2.558485 -14.64784 0.1194986 -2.990994 -14.64784 -0.1306756 -2.990994 -8.5 -0.1306756 -2.799838 -14.64784 -0.09244203 -2.809539 -8.5 -0.09635215 -2.74125 -8.5 -0.06348675 -2.654553 -8.5 0 -15.0916 -8.308312 -0.1071169 -15.0916 -8.147577 0 -2.991152 -8.162956 0 -2.991035 -8.318221 -0.09646111 -15.0916 -8.5 -0.1453216 35.86429 -0.1999999 15.74215 35.86356 -0.25 15.74715 38.17945 -0.25 16.30034 40.35894 -0.25 17.25905 39.34029 -0.1999999 16.74701 38.18106 -0.1999999 16.29555 39.53608 -0.05155014 16.73362 39.43817 -0.09859555 16.74049 40.36814 -0.1543291 17.24239 39.37197 -0.1523826 16.74494 39.35631 -0.1718685 16.74597 40.39433 -0.07322329 17.19494 40.43352 -0.01903009 17.12394 39.65826 -0.01766139 16.72455 43.41786 0.04970836 51.69968 42.44479 -0.6659969 50.95619 42.18235 -0.4169142 50.02568 43.56813 0.4887732 50.97877 43.38594 0.3277283 50.77126 42.86136 0.1001518 49.80036 42.15724 -0.1999999 49.3445 41.94675 -0.2220842 49.08925 41.9178 -0.1999999 48.96374 42.26153 2.80043e-4 48.628 42.57225 0.02982401 49.28041 42.22278 -0.01270037 48.61678 44.34759 2.054254 53.39269 44.07014 0.9883826 52.5395 44.22304 1.39941 52.56538 44.19361 1.322106 52.45764 43.76765 0.6688865 51.3702 43.98228 0.8120055 52.38923 39.48776 -0.3619644 46.40192 39.63323 -0.3871483 46.56661 39.5942 -0.4497938 46.56394 39.3591 -0.06147515 46.43012 39.45329 -0.1254867 46.43749 39.45417 -0.1292854 46.43455 39.51163 -0.1999999 46.44205 39.48817 -0.2407957 46.40152 39.64665 -0.3461493 46.56753 39.64935 -0.2683004 46.56771 39.62717 -0.1999999 46.5662 39.29936 -0.4467367 46.2592 39.45301 -0.4730244 46.43568 39.55305 -0.4908408 46.56114 39.3244 -0.3370082 46.23328 39.32599 -0.2971841 46.23164 39.31879 -0.2217944 46.23909 39.28335 -0.1181721 46.27577 39.22332 -0.04149967 46.33789 39.15 -0.003661394 46.41377 39.06424 -0.4107237 46.019 39.07709 -0.2673093 46.00447 38.97255 -0.03490632 46.12263 39.04396 -0.1315023 46.04192 38.19139 -0.3 45.30072 38.17821 -0.1851949 45.31937 38.16819 -0.15 45.33354 38.08449 -0.02283608 45.45195 38.1048 -0.04019236 45.42321 38.14067 -0.08786791 45.37247 32.17473 -0.1851949 42.01369 32.17779 -0.3 41.99106 30.37795 -0.3 41.61879 28.93964 -0.1999999 41.1434 29.08623 -0.1392406 41.23401 30.3671 -0.15 41.65748 29.40391 -0.06414371 41.42659 29.56533 -0.0395264 41.52258 30.33745 -0.04019236 41.76322 32.15295 -0.02283608 42.17458 32.1724 -0.15 42.03089 32.166 -0.08786791 42.07814 32.15767 -0.04019236 42.1397 28.64693 -0.3 41.00105 28.64006 -0.1999999 41.01677 27.01803 -0.3 40.14974 27.00905 -0.1999999 40.16436 25.52261 -0.3 39.08122 25.51169 -0.1999999 39.09446 24.18941 -0.3 37.81607 24.17677 -0.1999999 37.82767 23.0441 -0.3 36.37861 23.02997 -0.1999999 36.38835 22.10871 -0.3 34.7965 22.09337 -0.1999999 34.80419 21.40122 -0.3 33.10018 21.38497 -0.1999999 33.10567 20.93526 -0.3 31.32229 20.91841 -0.1999999 31.32548 20.71979 -0.3 29.49703 20.70266 -0.1999999 29.49785 -15.0916 -7.5 0 -15.0916 -7.5 -0.1453216 25.82394 -12.32839 85.41296 26.0149 -12.52185 85.41296 26.0149 -7.975761 85.41296 22.51415 -10.81118 85.41296 23.52254 -11.0008 85.41296 25.65181 -8 85.41296 24.29824 -11.28796 85.41296 25.18703 -11.80067 85.41296 1.287322 -11.5916 86.01406 1.588286 -12.24217 86.27292 1.878748 -13.1408 86.60353 2.089341 -14.13635 86.92237 2.119318 -14.32817 86.976 2.143555 -14.5 87.02133 2.143555 -8 87.02133 0.005724668 -10.36776 85.45835 -0.3779382 -10.33141 85.41605 -0.4460897 -10.33883 85.41372 -0.5141522 -10.35042 85.41296 0.3133202 -10.49479 85.52933 0.6909502 -10.78023 85.66564 0.9201455 -11.03263 85.77803 21.48743 -11.06003 85.59412 21.76619 -10.89984 85.50769 22.1599 -10.79342 85.43395 22.43445 -10.79789 85.41401 21.10788 -11.40642 85.76297 21.02392 -11.50591 85.80927 19.89054 -14.5 86.95808 20.043 -13.73087 86.71195 20.33497 -12.76933 86.35112 20.65467 -12.06576 86.05874 -4.064463 -12.11764 85.41296 -3.663353 -11.72122 85.41296 -4.064463 -7.968719 85.41296 -2.837289 -11.11275 85.41296 -3.805429 -7.995624 85.41296 -3.651809 -8 85.41296 -2.09568 -10.73989 85.41296 -1.116672 -10.44032 85.41296 42.2084 -2.99 85.22474 42 -8 85.28413 42.5282 -10.88028 85.109 43.38656 -10.34772 84.62522 43.6509 -2.99 84.41181 43.84131 -9.999867 84.23287 44.55062 -9.260519 83.26702 44.65321 -2.99 83.05669 45.00834 -8 81.409 45.00834 -2.99 81.409 45.00827 -8.015653 81.43267 44.7047 -9.02808 82.93768 -2.491599 -20.90245 3.401225 -2.491599 -20.71905 3.173046 -2.491599 -17.29977 0.8190304 -2.491599 -16.17909 0.5163338 -2.491599 -19.6524 2.125362 -2.491599 -18.68116 1.455931 -2.821997 -8.318221 -0.0644865 -2.699634 -8.331606 0 -2.822818 -8.208259 0 36.025 -8 0.2128129 36.025 -8 0.01654875 36.01972 -8 0.2127943 36.01911 -8 0.01653993 26.375 -8 0.2127943 26.375 -8 0.004867196 -31.7739 -7 -0.2784677 -30.825 -7 -0.2773193 -30.825 -7 -0.1643643 -31.76574 -7 -0.1655029 -33.69125 -7 0.2176032 -33.9705 -7 0.2053292 -35.32083 -7 1.312516 -35.75731 -7 1.571519 -36.40324 -7 2.950429 -36.8 -7 3.564489 -36.78481 -7 4.864673 -36.78311 -8 15.25509 -36.85488 -8 15.36589 -36.8 -8 14.35429 -36.46846 -8 16.4475 -36.5367 -8 15.42854 -36.7716 -8 13.914 -36.7858 -8 8.050001 -35.25089 -8 18.54635 -35.77054 -8 17.80753 -36.18895 -8 17.07934 -33.16252 -8 20.97763 -32.58888 -8 21.6329 -32.22562 -8.712735 22.13568 -39.8159 -2.752025 29.54485 -38.62839 -6.029355 28.71335 -36.64101 -8.666837 27.32177 -34.06467 -10.38458 25.51779 -31.84206 -10.96247 23.9615 -31.67816 -11 23.84674 -30.825 11 11 -30.825 11 0 -30.825 10.33062 -3.778672 -30.825 8.403935 -7.097455 -30.825 -10.9965 -0.2773193 -30.825 -10.38369 -3.630282 -30.825 -8.504755 -6.976329 -30.825 -5.590736 -9.473314 -30.825 -7 0.0992316 -30.825 5.454443 -9.552437 -30.825 1.841113 -10.84483 -30.825 -1.996292 -10.81734 -36.8 -4.059227 12.6019 -36.8 -2.09037 12.29491 -36.8 -7.158224 7.000737 -36.8 -8 3.564489 -36.8 -8 -0.04996067 -36.8 3.226537 -7.320482 -36.8 -5.760751 13.13765 -36.8 -7.369039 13.94107 -36.8 8 11 -36.7858 -7 6.635787 -36.8 -7.040527 6.832978 -36.8 -4.930331 -6.300146 -36.8 -6.324011 -4.899682 -36.8 -7.331962 -3.200365 -36.80003 8 14.35487 -36.8 6.323191 13.38157 -36.8 4.536248 12.72431 -36.8 2.514578 12.33802 -36.8 0 12.21355 -36.8 -7.333333 7.107191 -36.8 -7.683552 7.320099 -36.8 -7.918946 7.655617 -36.8 1.34005 -7.886969 -36.8 0 -8 -36.8 -7.892704 -1.305844 -36.8 -1.344153 -7.88627 -36.8 -3.235929 -7.316336 -36.8 8 0 -36.8 7.886969 -1.34005 -36.8 7.320482 -3.226537 -36.8 6.310221 -4.917428 -36.8 4.917429 -6.310222 -31.7739 -10.99647 -0.2784677 -33.8 -10.38369 -3.630282 -33.03819 -10.9993 -0.1240092 -33.8 -10.85247 -1.795536 -33.30476 -10.99989 -0.04996067 -33.84737 -10.99913 -0.04996067 -33.8 8.403935 -7.097455 -33.8 8.676554 -6.761465 -33.8 10.06566 -4.436489 -33.8 10.33062 -3.778672 -33.8 10.84458 -1.842568 -33.8 11 0 -33.8 6.761465 -8.676554 -33.8 5.454443 -9.552437 -33.8 4.436489 -10.06566 -33.8 1.842568 -10.84458 -33.8 -4.449402 -10.05996 -33.8 -1.84821 -10.84362 -33.8 0 -11 -33.8 -6.779205 -8.662701 -33.8 -5.590736 -9.473314 -33.8 -10.08145 -4.400503 -33.8 -8.695515 -6.737062 -33.8 -8.504755 -6.976329 -36.75905 -8.331245 15.2857 -36.60806 -8.995011 15.34819 -36.7019 -8.667995 15.30545 -31.84264 -11 23.61181 -34.58244 -11 19.69899 -34.61785 -10.9996 19.65036 -34.63477 -10.99927 19.62792 -34.84316 -10.98184 19.35059 -35.25437 -10.87692 18.7975 -35.45339 -10.78916 18.51328 -36.29978 -10.26094 18.32885 -36.6335 -9.630109 17.24514 -36.70282 -9.82072 18.24103 -36.92342 -9.479011 18.19297 -36.83929 -8.218725 15.38347 -36.82837 -8.337017 15.38486 -36.86109 -8.279238 15.65517 -36.77154 -8.676156 15.40277 -36.67847 -9.005521 15.44309 -36.62184 -9.161471 15.48659 -36.89535 -8.360342 16.01038 -37.04026 -8.631823 17.16682 -37.10973 -8.745037 17.64838 -37.18205 -8.857699 18.13663 -34.78084 -10.9624 19.76447 -39.17504 -6.029355 27.93265 -38.86058 -6.577975 27.71248 -39.96082 -4.216639 28.48287 -40.36255 -2.752025 28.76416 -36.56306 -10.00648 23.58888 -35.66645 -10.64152 21.76241 -38.23591 -7.857988 26.65407 -37.72815 -8.669953 25.76202 -37.44307 -9.058033 25.2476 -34.84634 -10.96191 19.64333 -37.27032 -9.411594 19.65095 -37.5504 -9.174956 20.40674 -37.38026 -9.084086 19.39775 -37.77455 -9.165685 21.68707 -37.3122 -9.714802 21.31856 -37.85725 -9.125651 22.15164 -37.91339 -9.104361 22.64842 -37.98789 -9.020464 22.88069 -37.19299 -9.769972 23.14676 -37.87092 -9.000868 24.46589 -38.02116 -8.985171 23.06568 -38.62675 -7.614321 26.42286 -38.48486 -8.078951 25.63742 -38.33836 -8.457077 24.8251 -35.81246 -10.71782 20.17951 -36.50033 -10.34322 21.71396 -37.6955 -9.185369 21.23974 -36.70692 -10.15118 19.88081 -37.19042 -8.585906 17.81177 -36.81494 -1.25354e-7 12.63672 -36.85742 -7.343797 14.90762 -38.80732 -7.567835 26.1159 -38.80179 -7.646891 25.9363 -38.788 -7.823812 25.47622 -38.78639 -7.842635 25.42105 -38.73314 -8.206122 23.45326 -38.72037 -8.206205 22.93115 -37.84289 -9.066388 21.71215 -37.82737 -8.760194 20.58793 -37.81484 -8.283812 19.52601 -37.1884 -7.675853 16.81881 -38.72102 -3.522624 17.0112 -38.77141 -2.843359 16.88723 -37.92713 -2.621569 15.8852 -38.86776 -1.849929 16.82413 -38.07326 1.38296e-7 15.90917 -38.96991 -0.689181 16.8411 -37.86127 -3.809265 16.06044 -37.82483 -4.922519 16.4293 -38.67382 -4.495684 17.3361 -37.80786 -5.946931 16.9814 -38.65175 -5.384617 17.81621 -37.80309 -6.861699 17.69712 -38.64629 -6.48536 18.74323 -38.71925 -8.204245 22.88423 -38.7149 -8.193396 22.70001 -38.69725 -8.090636 21.9201 -38.68671 -7.975021 21.42297 -37.80625 -7.646471 18.55362 -38.66083 -7.409017 20.02025 -38.67649 -7.811461 20.90931 -37.43933 0 14.90854 -36.93684 0 13.48765 -37.26931 -2.809127 14.72579 -36.88996 -3.01532 13.45119 -37.22596 -4.151842 14.92416 -36.8713 -4.526565 13.68125 -37.20235 -5.430839 15.34936 -36.8617 -5.985293 14.17141 -37.19145 -6.615503 15.98884 -34.11541 -10.98318 -0.04996067 -34.83836 -10.81447 -0.04996067 -34.83835 -10.66953 -1.765269 -35.49274 -10.47605 -0.04996067 -35.92133 -10.12118 -0.04996067 -35.92132 -9.985573 -1.652108 -36.29565 0 -9.664842 -35.92208 0 -10.12056 -35.92132 -1.700575 -9.977434 -35.46913 0 -10.49279 -34.83835 0 -10.81457 -34.83835 -1.817055 -10.66083 -36.74252 0 -8.584457 -36.61457 0 -9.038352 -36.61457 -1.518616 -8.90986 -36.57164 0 -9.148036 -36.61457 -3.655933 -8.265952 -36.61457 -5.570258 -7.117866 -36.61457 -7.144829 -5.53563 -36.61457 -8.283606 -3.615754 -36.61457 -8.917129 -1.475335 -36.45386 -9.398735 -0.04996067 -34.83835 -9.911506 -4.326324 -34.83835 -8.548936 -6.623497 -34.83835 -6.664929 -8.516674 -34.83835 -4.374399 -9.890381 -35.92132 -4.093984 -9.256373 -35.92132 -6.237683 -7.970724 -35.92132 -8.000918 -6.198906 -35.92132 -9.276142 -4.04899 -41.98481 -2.078503 22.43569 -39.44185 -3.833254 17.89891 -40.02994 -5.647982 26.93356 -40.58638 -5.49103 25.68693 -39.15869 -7.663368 24.68725 -39.59449 -7.313885 23.48236 -39.04639 -7.674705 21.66119 -39.88644 -6.824322 22.24941 -40.01577 -6.219707 21.05695 -39.78789 -4.697836 18.84578 -39.9837 -5.508764 19.91776 -40.65538 -1.280998 18.74864 -39.84402 -0.9638202 17.68589 -41.72768 -1.84092 21.13891 -41.27513 -1.569924 19.88716 -42.0469 -2.280554 23.76217 -41.58477 -2.560947 26.38602 -41.90993 -2.444156 25.10365 -41.05687 -2.634146 27.65263 -40.63912 -4.179968 27.36011 -41.17863 -4.063812 26.10163 -40.95706 -5.240615 24.43645 -41.5223 -3.878484 24.83224 -41.15782 -4.889829 23.13963 -41.68522 -3.618874 23.50892 -41.1745 -4.456604 21.86831 -41.65518 -3.298252 22.20488 -41.00999 -3.947192 20.63637 -41.43572 -2.921246 20.93448 -39.46828 -2.066566 17.42278 -40.15599 -2.74664 18.39895 -40.6631 -3.366139 19.45861 -27.12697 -2.613918 32.25586 -26.90366 -2.672033 31.99987 -26.47272 -3.67709 32.59236 -26.99839 -2.358243 31.8738 -27.75959 -1.854113 32.69883 -27.19101 -1.481944 31.63452 -28.1466 -0.8791561 32.96981 -27.30254 -0.4847767 31.5226 -36.7716 -7.333333 7.107191 -36.7716 -7.158224 7.000737 -36.7716 -7.040527 6.832978 -36.7716 -7.918946 7.655617 -36.7716 -7.683552 7.320099 -33.48769 -10.99989 0.009863734 -34.43727 -10.93142 0.4516338 -34.55667 -10.90292 0.5248018 -35.36021 -10.56168 1.150119 -35.49441 -10.4749 1.282217 -35.7167 -10.30738 1.523895 -36.78528 -8.296994 3.511177 -36.71945 -8.690351 3.295559 -36.42116 -9.459094 2.576025 -36.32208 -9.624401 2.389479 42.2084 -0.00605905 67.61297 42.2084 -0.006046772 67.69438 42.2084 -0.006046772 70.21218 42.2084 -0.006046772 73.01139 42.2084 -0.006046772 75.81059 42.2084 -0.006046772 78.6098 42.2084 -0.006046772 81.409 35.26108 -0.1999999 14.93363 35.26108 -3.002625 14.93363 -21.175 -7 0.1246222 42.26996 -15.96091 2.591812 42.2418 -10.80809 2.564061 42.94095 -15.90305 3.335416 42.45528 -10.73917 2.780819 43.82124 -15.64559 4.654077 42.8282 -10.59167 3.198189 44.1791 -15.47413 5.388258 43.4322 -10.27125 4.007743 44.85776 -15.01485 7.969048 44.73938 -15.10979 7.190607 44.90643 -13.73623 8.7322 44.9065 -13.53729 8.735527 44.89004 -14.84519 8.346134 44.87709 -14.96024 8.17136 44.89999 -14.61382 8.531104 44.90359 -14.40311 8.625903 44.02095 -9.83583 5.042522 44.17881 -9.690975 5.38759 44.31122 -15.39957 5.711511 44.37328 -9.490029 5.87718 44.55042 -9.279051 6.417969 44.83416 -8.856748 7.769877 44.9065 -8.73472 8.735527 37.75388 -15.96091 0.1893878 36.025 -11 0.01654875 39.42168 -15.96091 0.6971006 39.37984 -11 0.6798507 40.93771 -15.96091 1.506319 40.95137 -11 1.51542 42.00563 -10.87177 2.340635 36.01911 -15.96091 0.01653993 26.375 -11 0.004867196 17.75 -8 -0.005571961 17.91905 -8.992829 -0.005367517 20.11266 -14.02943 -0.002712309 19.96266 -13.98923 -0.002893924 20.09125 -10.92678 -0.002738416 20.75 -11 -0.001941204 22.35372 -11 0 20.22247 -14.13923 -0.002579629 20.26266 -14.28923 -0.002530753 20.26266 -15.96091 -0.002530753 18.40727 -9.873923 -0.004776597 19.15961 -10.54375 -0.003865778 19.60195 -10.77164 -0.003330707 -15.5 -7.008462 -0.1458156 -15.5 -7.008462 0 -15.29043 -7.100879 0 -15.29043 -7.100879 -0.1455623 -15.14406 -7.277048 0 -15.14406 -7.277048 -0.1453849 42.44091 -0.03003782 67.52523 42.44074 -0.03001469 67.6126 42.61596 -0.06369072 66.94857 42.38147 0.02783721 66.94766 42.54245 0.02789902 66.27999 42.25202 0.3160369 66.27259 42.17943 0.2026 66.94609 42.04985 0.4361968 66.94404 42.0084 0.6844804 66.94189 42.20593 0.6245077 64.92555 42.0084 1.488927 64.86296 42.0084 1.484822 65.12069 42.08016 0.8870278 65.58515 42.06774 0.6812511 66.26322 42.0084 1.395701 65.5318 42.0084 1.124832 66.14482 43.13632 -0.3062471 64.99293 42.89285 -0.1485887 66.27673 42.75253 -0.06355708 64.97536 42.68138 -0.003515601 64.97101 42.2084 -0.7428959 84.13938 42.72481 -0.4566686 83.35946 42.2084 -0.3043623 83.39956 42.2084 -2.376936 85.15809 43.40394 -1.542342 84.13118 42.2084 -1.541951 84.83062 42.2084 -1.488909 84.79873 44.31258 -1.542342 82.9027 43.37585 -0.4566686 82.47924 42.2084 -0.05039918 82.4005 44.63452 -1.542342 81.409 43.60652 -0.4566686 81.409 45.00834 -2.99 67.69438 44.83602 -1.989627 67.69438 43.62177 -0.4662894 67.69438 44.18947 -0.9342128 67.69438 44.63887 -1.550235 67.69438 43.17089 -0.2310664 67.69438 44.05178 -0.9342128 65.40015 43.20976 -0.4286482 64.10177 43.28587 -0.6069733 63.2256 43.87161 -1.218743 63.08239 44.69368 -1.989627 65.32282 44.31162 -2.124072 62.97481 44.86476 -2.99 65.30221 44.43609 -2.99 62.94438 20.64352 -0.1999999 29.28851 20.65856 -0.3 29.28025 34.86748 -3.090774 14.87396 34.75691 -3.269396 14.98452 35.15885 -3.083438 15.15014 35.17027 -3.263644 15.39358 35.16619 -0.2506735 15.37931 35.27579 -3.471454 15.58194 35.27579 -0.4857268 15.58194 35.27489 -0.4756341 15.58092 35.26951 -0.4619381 15.57476 35.27445 -0.4736123 15.58043 35.1602 -0.1999999 15.14369 35.15398 -0.1999999 15.31986 35.19823 -3.028241 15.0327 -8.129328 -8.008399 84.11455 -8.568182 -8.177098 84.00794 -8.885489 -8.53534 83.94242 -5.887493 -7.551508 84.97338 -6.037596 -7.55091 84.89793 -5.887493 -12.38038 84.97338 -6.075965 -7.551275 84.87909 -6.202408 -7.559607 84.8183 -7.944966 -7.986277 84.16498 -6.285313 -13.14293 84.7795 -7.110949 -7.802872 84.43647 -7.017931 -7.773761 84.47129 -6.520378 -13.78921 84.67391 -8.261513 -14.5 84.08046 -6.69331 -14.5 84.60031 -9 -9 83.9211 -9 -9.004487 83.9211 -9.143492 -9.506356 83.89613 -9.355443 -9.743202 83.86274 -9.127268 -9.479436 83.89886 -9.023364 -9.214381 83.9169 -9.475065 -9.82379 83.84574 -9.635213 -9.895741 83.82501 -10.22995 -14.5 83.76849 -9.95 -9.946413 83.79111 -12.22251 -14.5 83.81034 -12.05 -9.946559 83.79262 -12.22251 -9.932393 83.81034 -4.82851 -12.22445 85.3393 -4.997925 -7.732981 85.30251 27.85792 -7.584428 84.96306 26.95826 -7.753763 85.30012 27.85792 -13.66095 84.96306 26.60054 -7.853807 85.36985 27.18596 -13.19915 85.23769 26.1646 -12.60126 85.41016 26.02907 -12.52929 85.41293 37.41506 -7.687186 84.60243 37.18038 -7.750659 84.5054 35 -9 83.88007 36.96423 -7.812143 84.42147 36.89205 -7.832218 84.39457 35.90687 -8.004347 84.08225 35.45209 -8.163466 83.97098 35.12025 -8.52456 83.90236 36.03851 -7.993303 84.11825 38.17322 -13.32326 84.96015 38.17322 -7.607247 84.96015 37.98005 -7.606793 84.86236 34.94721 -9.31339 83.87071 34.87273 -9.47564 83.85794 37.49997 -13.94716 84.63909 34.79433 -9.590256 83.84506 28.07238 -14.5 84.85463 30.105 -14.5 84.08892 27.96892 -14.07838 84.90622 31.23619 -14.5 83.84607 31.23619 -9.627076 83.84607 31.06087 -9.336281 83.87576 31 -9 83.88674 30.88113 -8.527134 83.90917 30.5528 -8.166684 83.97812 30.10181 -8.005197 84.08979 29.95742 -7.991806 84.12976 29.61917 -7.946952 84.23166 29.13884 -7.831814 84.39674 28.4777 -7.643493 84.6651 28.0272 -7.584778 84.877 34.52494 -9.819937 83.80516 34.52318 -14.5 83.80492 36.63711 -14.5 84.30409 34.46323 -9.851952 83.79695 34.05 -9.942454 83.75098 32.29991 -14.5 83.72644 31.95 -9.942801 83.75444 31.5585 -9.862354 83.79892 39.63344 -12.98848 85.39083 39.38456 -7.85418 85.35913 39.29956 -13.0693 85.34464 39.07001 -7.769585 85.29595 8.879969 -8.524969 87.90248 8.54869 -8.163974 87.97155 9 -9 87.88002 8.094512 -8.004477 88.08344 7.960781 -7.993054 88.12024 8.545011 -14.5 87.97237 9.375262 -9.754577 87.81848 9.098804 -9.422699 87.86254 7.167241 -7.84624 88.37622 12.62474 -14.5 87.81848 12.62474 -9.754577 87.81848 12.52494 -9.819853 87.8043 12.35303 -9.895667 87.78203 12.05 -9.942288 87.74933 11 -14.5 87.7 9.95 -9.942288 87.74933 9.646702 -9.895579 87.78206 14.8561 -7.839867 88.38475 13 -9 87.88002 15.13143 -7.761275 88.48986 13.90549 -8.004477 88.08344 13.45131 -8.163974 87.97155 13.12003 -8.524969 87.90248 14.03922 -7.993054 88.12024 12.90133 -9.422439 87.86257 12.8727 -9.475665 87.85767 13.45499 -14.5 87.97237 -15.66726 -8.986545 -0.1460182 -15.5 -7.998672 -0.1458156 -31.76574 -11.23341 -0.1655029 -30.14191 -11.24566 -0.1635373 -28.73779 -11.26834 -0.1618381 -22.37895 -11.53332 -0.1541417 -17.83622 -10.92463 -0.1486431 -17.46165 -10.81356 -0.14819 -16.51943 -12.06233 -0.1470496 -16.90525 -10.53998 -0.1475167 -13.22441 -12.50407 -0.1430617 -16.15401 -9.868755 -0.1466073 -21.175 -7 -0.1526846 -21.175 -10.99894 -0.1526846 -18.5 -10.99898 -0.1494469 -3.098868 -14.61885 -0.130806 -8.132303 -13.41876 -0.1368982 -2.678354 -21.01803 2.92307 -2.679745 -21.21174 3.162299 -2.880135 -21.28817 3.103244 -2.540699 -20.88482 3.034448 -2.541084 -21.07409 3.268642 -3.102588 -21.28825 3.103165 -2.87753 -21.09252 2.860787 -3.099109 -21.09367 2.859831 -2.862714 -19.95586 1.749463 -3.086498 -20.38189 2.107574 -2.670482 -19.89314 1.827155 -2.849693 -18.92278 1.041825 -2.663623 -18.87136 1.129959 -2.831888 -17.45613 0.3717673 -2.654328 -17.42158 0.4705909 -2.818018 -16.26831 0.05599772 -2.647152 -16.24805 0.1605238 -3.079135 -19.96162 1.742325 -3.061326 -18.93068 1.028287 -3.036592 -17.4641 0.3489559 -3.017025 -16.2741 0.02610367 -2.538522 -19.78524 1.960817 -2.536633 -18.78567 1.276812 -2.534086 -17.36633 0.6286317 -2.53213 -16.21661 0.322735 -2.484989 -20.94001 3.493706 -2.525234 -21.12104 3.357928 -2.661231 -21.27831 3.259957 -2.864244 -21.37858 3.220498 -3.091374 -21.40068 3.247887 -3.056401 -21.50593 3.379773 -2.830385 -21.46183 3.324698 -2.629295 -21.33847 3.344927 -2.498226 -21.16353 3.435925 -2.46657 -20.97624 3.577283 -2.997817 -21.60845 3.503349 -2.779433 -21.54129 3.419528 -2.585149 -21.39472 3.420245 -2.460991 -21.20348 3.505332 -2.436375 -21.01287 3.65463 -2.970405 -21.6451 3.545924 -2.756715 -21.56925 3.451474 -2.566287 -21.41422 3.44507 -2.44508 -21.21743 3.528258 2.618624 -21.84832 1.95892 2.698559 -21.8984 1.897486 2.558445 -21.78822 2.032658 2.536761 -21.75534 2.072993 2.508401 -21.65046 2.201661 2.843231 -22.21306 2.056718 2.900663 -21.96051 1.824486 2.744704 -21.91886 1.872385 2.900697 -21.95895 1.823202 2.516859 -21.9271 2.185225 2.571104 -22.01296 2.12685 2.646496 -22.09202 2.084596 -1.37538 -21.98071 4.227842 -1.287173 -22.02131 4.248744 -0.5154262 -22.31147 4.288125 1.338355 -22.57678 3.542745 1.926852 -22.43286 3.028637 2.801346 -22.29721 2.146037 2.651383 -22.20634 2.153684 2.534075 -22.0861 2.204535 2.463875 -21.95132 2.292324 2.100603 -22.33864 2.834279 2.148122 -22.50717 2.777271 2.243444 -22.6644 2.767024 2.373641 -22.78899 2.804929 1.96421 -22.6121 2.980578 2.050013 -22.78078 2.984258 2.171963 -22.91474 3.039151 1.343498 -22.78166 3.513355 1.397407 -22.9774 3.553878 1.490837 -23.13045 3.657366 1.170732 -22.58699 3.659164 1.167592 -22.79706 3.63285 1.212517 -22.99813 3.681689 1.297452 -23.15413 3.796921 0.4105648 -23.13488 4.278409 0.2715672 -23.11719 4.332113 0.3702644 -22.97383 4.118236 0.2389746 -22.95641 4.166438 0.368407 -22.75683 4.04002 0.2439736 -22.73803 4.084945 0.4053879 -22.53004 4.06041 0.2854775 -22.50951 4.105355 -0.5832153 -22.54694 4.262548 -0.6368222 -22.76822 4.3567 -0.6632313 -22.92156 4.547721 -1.376478 -22.25484 4.210499 -1.484741 -22.46647 4.296882 -1.584257 -22.60206 4.485785 -1.466985 -22.21326 4.187665 -1.581734 -22.4228 4.271439 -1.690211 -22.55559 4.457687 -1.970938 -21.64347 3.967689 -2.078696 -21.86307 3.910066 -2.237683 -22.05027 3.963257 -2.407738 -22.1578 4.113824 2.508401 -16.46593 0.376586 2.508401 -14.28923 0.376586 2.546519 -14.28923 0.1851046 2.546519 -16.46593 0.1851046 2.655062 -14.28923 0.02281886 2.655062 -16.46593 0.02281886 2.817479 -14.28923 -0.08552742 2.817479 -16.46593 -0.08552742 3.009006 -14.28923 -0.1234136 3.009006 -16.46593 -0.1234136 2.536778 -21.74589 2.065237 2.508401 -21.64117 2.194103 2.618689 -21.83872 1.950999 2.744835 -21.90912 1.864355 2.508401 -20.60731 1.481948 2.538692 -20.69316 1.333613 2.508401 -19.20863 0.8406422 2.541307 -19.26743 0.6722204 2.508401 -18.02553 0.5236023 2.543541 -18.05995 0.3427152 2.625897 -20.76861 1.203251 2.635692 -19.31848 0.5259659 2.64402 -18.08953 0.1872532 2.759447 -20.82452 1.106657 2.779134 -19.35508 0.4211302 2.795716 -18.11011 0.07906752 2.900898 -21.94912 1.81514 2.923162 -20.85411 1.055536 2.952753 -19.3724 0.3715116 2.977307 -18.11881 0.03336519 35.33865 -0.3259933 15.60175 35.4318 -0.1999999 15.59769 40.61427 -0.02794003 17.22096 40.58876 -0.105515 17.30641 40.5763 -0.2153852 17.34816 40.57568 -0.2391419 17.35024 40.57967 -0.3329926 17.33688 40.77825 -0.02347695 17.24252 40.77248 -0.08949851 17.32823 40.76914 -0.1856647 17.37803 40.76883 -0.2939141 17.38255 40.77163 -0.3939158 17.34095 40.94675 -0.02924382 17.23737 40.97304 -0.1101337 17.32332 40.98515 -0.2237454 17.36292 40.98025 -0.3434994 17.34689 40.95948 -0.4413791 17.27899 41.82615 -0.4441947 16.99246 42.68152 -0.4464862 16.67434 41.85012 -0.3467714 17.06149 42.70866 -0.3494732 16.74403 41.85615 -0.2263858 17.07884 42.71582 -0.2285801 16.7624 41.8428 -0.1116035 17.04041 42.70128 -0.1128292 16.72506 41.81324 -0.02966034 16.95531 42.66852 -0.03000825 16.64097 43.44428 -0.01858437 16.10777 42.98229 -0.02889764 16.48542 43.47566 -0.02550166 16.09931 43.02786 -0.1089101 16.56269 43.61559 -0.07773274 16.06072 43.69541 -0.1378139 16.03809 43.0492 -0.2215399 16.59886 43.73492 -0.1989506 16.02672 43.88441 -0.1999999 15.85323 43.75872 -0.1999999 16.00076 43.75694 -0.3105185 15.99917 43.04136 -0.3407492 16.58557 44.18159 -0.1999999 15.43725 44.18389 -0.2840637 15.4387 44.50806 -0.1999999 14.82902 44.69516 -0.2387607 14.37367 44.64751 -0.1999999 14.49135 44.84915 -0.2182716 13.84517 44.84216 -0.1999999 13.86101 45.00834 -0.25 12.55014 45 -0.1859726 12.55014 45 -0.1999999 12.73567 44.99933 -0.1999999 12.7705 44.96152 -0.1999999 13.21555 44.84451 -0.3078771 13.84405 43.00616 -0.4389789 16.52589 43.71891 -0.4107344 15.96506 44.15317 -0.3835474 15.41931 44.68217 -0.3325425 14.36914 45.00834 -0.25 9.037966 45 -0.1859726 9.037966 35.25503 -3.5 15.56233 -13.15986 -15.74962 47.5486 -13.14167 -15.51994 47.56034 -13.11733 -15.75921 47.44137 -13.0773 -15.57538 47.40028 -13.1006 -15.76709 47.32711 -13.16911 -15.24431 47.61963 -13.25912 -15.45611 47.68266 -13.31194 -15.72746 47.71965 -13.0268 -15.49705 47.16542 -13.07448 -15.61516 47.22353 -13.10224 -15.77026 47.26924 -13.01369 -15.43586 47.34332 -13.06349 -15.34742 47.50226 -13.06049 -15.08298 47.54358 -12.97149 -15.21828 47.4348 -12.95411 -15.25976 47.38731 -12.9397 -15.33298 47.28022 -12.95307 -15.38916 47.16317 -12.96996 -15.40962 47.10339 -13.1467 -15.77618 47.10201 -13.13953 -15.6693 47.06794 -13.13357 -15.63405 47.05328 -13.10095 -15.52229 46.99387 -13.05767 -15.43653 46.93122 -12.93749 -16.24127 47.67783 -12.91634 -16.25548 47.67643 -13.5442 -15.95438 48.06979 -12.45331 -16.45223 47.64696 -13.48348 -16.05172 48.23362 -12.45816 -16.45108 47.64728 -12.66025 -16.38753 47.66029 -13.51012 -15.62611 47.85841 -13.55358 -15.80452 47.93767 -13.25525 -15.90117 47.70578 -13.22997 -15.94555 47.70232 -13.20109 -15.98899 47.69898 -13.13033 -16.0758 47.69217 -13.75444 -15.47602 48.02949 -13.8078 -15.63837 48.11052 -13.8125 -15.77748 48.23855 -14.48956 -15.20331 48.80451 -13.76785 -15.87347 48.39528 -14.37461 -14.9137 48.46374 -14.45115 -15.0249 48.54832 -14.47594 -15.07695 48.60366 -14.49081 -15.12482 48.66588 -18.22279 -10.64587 51.41854 -18.20917 -10.51951 51.21769 -18.10785 -10.35626 51.07778 -18.48319 -9.852977 51.34059 -18.59531 -9.997874 51.48582 -18.62022 -10.11109 51.68885 -18.81428 -9.313855 51.57242 -18.93611 -9.439803 51.72283 -18.97078 -9.538883 51.92853 -19.55131 -8.150999 52.23411 -19.51984 -8.090434 52.13013 -19.27073 -8.754106 51.95605 -19.40097 -7.961926 51.98328 -19.39664 -7.958164 51.9802 -19.13904 -8.650714 51.79982 -19.49905 -8.06227 52.09051 -19.31464 -8.83581 52.16542 -19.55724 -8.195265 52.33436 -19.55594 -8.168488 52.27045 -21.1712 -5.768577 53.83314 -21.6794 -4.611959 54.18899 -21.76084 -4.596002 54.01243 -20.78508 -6.559434 53.13117 -19.55854 -8.209064 52.40989 -20.76278 -6.624938 53.31358 -20.74139 -6.4614 52.96826 -20.63834 -6.34576 52.84965 -19.62574 -8.065868 52.751 -20.67787 -6.64794 53.48771 -19.60902 -8.108878 52.68918 -19.57099 -8.193512 52.51308 -21.77328 -4.550559 53.82312 -21.71481 -4.482549 53.64987 -21.59435 -4.402325 53.51905 -22.29962 -2.361005 54.62327 -22.37892 -2.352836 54.44522 -22.38524 -2.329573 54.25162 -22.31763 -2.294756 54.07196 -22.18638 -2.253687 53.93359 -22.50962 0 54.77032 -22.58819 0 54.59175 -22.59245 0 54.39671 -22.52174 0 54.21488 -22.38683 0 54.07395 20.65782 -6.856955 29.27892 20.71979 -6.856955 29.49703 -36.7716 -14.7551 13.914 -36.5367 -14.7551 15.42854 43.28486 -0.5619027 57.7513 43.4029 -1.189164 57.33206 43.82482 0.4184012 55.83083 44.26805 2.535291 54.14696 42.79891 2.526927 59.55366 44.28099 2.536665 54.09416 43.15459 -0.06732791 58.21892 42.11055 2.705733 63.11965 42.11397 1.621373 63.09025 42.16381 1.59356 62.69122 42.3012 2.600369 61.818 42.19924 1.544924 62.44176 42.20822 1.529776 62.3819 42.48917 2.560585 60.86584 42.49144 1.18977 60.85537 42.72605 0.8905816 59.84473 43.06317 0.2049341 58.55205 42.05657 1.584454 63.68113 42.07946 2.775875 63.41903 42.07775 2.791752 63.43705 42.07756 2.797111 63.43914 42.07752 2.8 63.43943 39.8465 -0.200366 46.58117 -19.9916 -6.040742 55.21584 -19.9916 -5.768575 55.51778 -19.9916 -2.997754 57.64052 -19.9916 0 58.36642 37.4078 -0.04019236 44.95449 37.46618 -0.15 44.86148 37.48755 -0.3 44.82744 37.05389 -0.3 44.57085 36.98128 -0.04019236 44.7021 37.03443 -0.15 44.60601 34.62957 -0.04019236 43.43687 32.27903 -0.04019236 42.17967 34.68092 -0.15 43.33982 34.69972 -0.3 43.30429 32.35116 -0.3 42.04815 32.34018 -0.1851949 42.06817 32.33184 -0.15 42.08339 32.30891 -0.08786791 42.12519 25.31009 -13.91546 85.10625 25.07016 -14.11526 84.94741 24.84135 -14.6215 84.62564 23.92757 -15.73171 81.92294 23.94872 -15.70635 82.35065 23.79293 -15.38862 81.92885 23.96575 -15.69384 82.48696 24.12604 -15.58868 83.1659 24.2165 -15.17545 83.67212 24.15361 -15.56961 83.24679 24.29829 -15.44419 83.61587 25.93498 -12.70817 85.40805 26.00748 -12.53956 85.41291 24.61423 -13.583 84.94818 24.31674 -15.41661 83.66334 24.51745 -15.08431 84.12118 24.02587 -14.85573 83.67461 24.17965 -13.22178 84.94868 23.57271 -12.87068 84.94917 23.04271 -12.67398 84.94944 22.35349 -12.54407 84.94961 23.7258 -14.5044 83.67728 23.43953 -14.26587 83.67904 23.03947 -14.03395 83.68073 22.68997 -13.90399 83.68166 22.23537 -13.81814 83.68227 23.63789 -15.13084 81.93317 23.39462 -14.84787 81.93779 23.16302 -14.65595 81.94086 22.83982 -14.46948 81.94379 22.55775 -14.36504 81.94541 22.19106 -14.29608 81.94647 42.81844 -0.1990125 63.03818 42.35768 0.420894 63.89526 42.12657 0.9923382 63.78349 42.46059 0.3263666 62.83307 45.00834 -8 72.62341 45.00834 -7.267217 71.76062 45.00834 -4.643889 67.69438 45.00834 -5.335476 68.86626 45.00834 -6.043648 70.0282 44.43609 -3.010334 62.94438 44.82151 -3.598796 64.96705 44.99671 -4.35573 67.01271 44.4243 -2.99 62.89589 44.28771 -2.08412 62.92892 43.89077 -1.263393 63.02492 43.28354 -0.6149333 63.17178 3.140771 -16.97496 86.72658 3.146765 -17.16127 86.30033 3.921063 -17.62916 86.25558 3.774612 -17.67214 85.8021 4.134766 -17.74303 86.11998 3.994978 -17.79065 85.61312 5.214877 -17.99993 85.39155 4.876981 -18 84.78174 5.233865 -18 85.3781 2.143132 -14.52963 87.02027 2.29367 -15.14924 87.19464 2.305052 -15.69053 86.88069 2.536274 -15.994 87.06523 2.363098 -15.86918 86.84045 3.035754 -16.84809 86.78707 2.613427 -16.42733 86.6741 2.943857 -16.92594 86.44831 19.89096 -14.53065 86.95705 19.36524 -16.21084 87.01165 18.90134 -16.92556 86.75092 19.07884 -16.95024 86.36247 18.75215 -17.09246 86.6642 18.54734 -17.48276 85.95076 17.93604 -17.70787 86.16522 18.16463 -17.73564 85.62638 17.71847 -17.80818 86.02522 17.18677 -18 84.68885 16.78512 -17.99993 85.39155 16.76613 -18 85.3781 19.73511 -15.67555 86.81979 19.38074 -16.50734 86.57467 19.68778 -15.82698 86.78576 19.65287 -15.41239 87.16645 19.68949 -15.24274 87.18579 20.38981 -14.89806 85.4027 20.16724 -15.31966 85.92815 20.10826 -15.73044 85.27861 20.32126 -14.33448 86.10295 20.15942 -15.22742 86.06013 19.9019 -14.51923 86.93732 22.31564 -12.53661 84.95272 22.18456 -12.52705 84.9672 21.97657 -12.56015 85.00273 21.80073 -12.6255 85.04696 21.50852 -12.79378 85.15293 21.43473 -12.84709 85.18642 21.06926 -13.17681 85.39508 20.69971 -13.64212 85.68831 20.74784 -14.41986 84.83571 21.0943 -14.12036 84.4174 21.43224 -13.93038 84.09926 21.49967 -13.90283 84.04507 21.76268 -13.82698 83.86239 21.91679 -13.80629 83.77822 22.09397 -13.80443 83.70862 22.20367 -13.81402 83.68555 20.24408 -15.3842 84.65765 20.47412 -15.01785 83.88618 20.72601 -14.75417 83.2731 21.01693 -14.54749 82.75682 21.08309 -14.51108 82.66162 21.38213 -14.38512 82.31582 21.60176 -14.32738 82.13959 21.91195 -14.28938 81.98943 22.12827 -14.29123 81.9487 -18.22279 -14.63382 68.20404 -19.60862 -14.0946 77.87761 -19.47812 -14.54135 78.03184 -19.9916 -11.1813 76.85272 -19.99159 -11.20033 76.85946 -19.95595 -12.07945 77.17071 -19.09129 -15.48933 78.01091 -19.20011 -15.31759 78.29632 -18.98738 -15.59399 77.55313 -18.92258 -15.58031 76.96311 -18.22616 -14.63817 68.242 45.00834 -3.349422 10.45429 45.00834 -4.98431 9.800368 45.00834 -19.82881 10.18105 45.00834 -19.80031 8.916534 45.00834 -15.23914 9.60569 45.00834 -14.49959 8.916534 45.00834 -1.509681 11.54434 45.00834 -1.793861 11.34865 45.00834 -6.813476 9.375516 45.00834 -8.5 9.250606 45.00834 -13.53729 9.037966 45.00834 -13.73154 9.035059 45.00834 -10.83782 9.295021 36.01923 -20.74515 -0.08346033 36.01923 -16.26091 -0.08346033 38.15645 -20.5235 0.1766473 37.7735 -16.26091 0.09133023 39.30113 -20.40313 0.5405234 39.46004 -16.26091 0.6047474 41.06392 -20.21543 1.470659 40.9931 -16.26091 1.423058 42.21906 -20.09109 2.402939 42.34032 -16.26091 2.520748 44.98661 -15.2332 8.29144 44.96013 -15.31363 7.986285 44.94683 -19.80261 7.866156 44.83015 -15.41907 7.134517 44.72018 -19.82363 6.657365 44.43606 -15.68795 5.758437 44.45148 -19.85111 5.799926 44.32445 -15.75213 5.475271 44.32426 -19.86444 5.474811 43.72294 -16.02319 4.281348 43.8652 -19.91332 4.526814 43.27195 -16.15471 3.602412 43.33364 -19.97059 3.687778 42.37608 -20.07413 2.556353 45.00096 -15.06376 8.552131 45.0071 -14.81001 8.767326 35.25503 -4.583749 15.56233 35.14734 -4.985863 15.45464 34.8232 -6.737305 15.1305 26.36712 -18.87793 23.96982 27.25794 -22.42061 25.78207 28.05429 -22.58152 24.98593 26.85251 -18.98093 23.48444 28.85087 -22.6513 24.18955 28.12403 -19.03614 22.21291 29.64641 -22.63131 23.39421 28.14748 -19.03428 22.18946 30.43966 -22.52178 22.60117 28.73871 -18.95239 21.59823 30.61875 -22.48449 22.42213 28.87219 -18.92454 21.46475 31.40793 -22.26357 21.63314 29.35433 -18.79452 20.98261 32.17601 -21.95652 20.86526 30.5671 -18.2514 19.76984 32.92208 -21.56525 20.11938 30.58877 -18.23867 19.74817 33.64501 -21.09055 19.39662 31.1275 -17.88465 19.20944 33.80529 -20.97152 19.23639 31.24693 -17.79589 19.09 34.49831 -20.39358 18.54354 31.67148 -17.44748 18.66545 35.15124 -19.74426 17.89077 32.68877 -16.36727 17.64817 35.76368 -19.02575 17.27848 32.70621 -16.34516 17.63073 36.33475 -18.23934 16.70755 33.13171 -15.75891 17.20523 36.45812 -18.05198 16.5842 33.22363 -15.61924 17.1133 36.97678 -17.18215 16.06567 33.54273 -15.09169 16.79419 37.44089 -16.26373 15.60167 34.24985 -13.59617 16.08708 37.85058 -15.29898 15.19206 34.2611 -13.56721 16.07583 38.20533 -14.28952 14.83739 34.5254 -12.81484 15.81153 38.27788 -14.05496 14.76486 34.57946 -12.64002 15.75748 38.56365 -12.99133 14.47915 34.75712 -11.99274 15.57981 38.78654 -11.9074 14.2563 35.07433 -10.25052 15.2626 38.94725 -10.80522 14.09562 35.07816 -10.21802 15.25877 39.04563 -9.686591 13.99725 35.15147 -9.384343 15.18546 39.05917 -9.431286 13.98371 35.16156 -9.194072 15.17537 39.08084 -8.5 13.96203 35.17772 -8.500014 15.15921 35.37907 -4.643628 15.64894 35.3553 -5.067792 15.57235 35.42746 -4.662819 15.66806 35.46167 -4.675325 15.67785 35.60041 -5.128809 15.56977 35.70618 -4.7433 15.67248 35.622 -4.723937 15.68853 35.53728 -4.700206 15.68977 35.53425 -4.699279 15.68953 35.47406 -4.679655 15.68069 35.03504 -6.778033 15.25471 35.20218 -7.678764 15.18297 35.282 -6.808668 15.26051 34.99439 -8.500014 15.16497 34.93015 -8.500014 15.15068 34.82132 -8.500015 15.10423 25.77718 -22.81509 27.83946 25.35977 -21.96792 27.79455 25.25861 -22.49146 28.25839 26.34669 -23.18228 27.35809 25.85288 -22.55584 27.5841 25.81615 -22.83979 27.80713 25.96272 -22.05028 27.11644 26.03737 -18.7879 24.29943 25.7061 -18.69254 24.63028 25.69553 -19.27469 25.21681 26.35901 -23.14483 27.32055 26.48135 -22.83465 26.98082 26.07783 -21.53801 26.61509 26.63915 -22.58014 26.62675 26.2071 -20.97981 26.03592 26.67044 -22.54552 26.56629 26.23028 -20.88041 25.92936 27.01824 -22.38858 26.04431 26.44136 -19.95026 24.88933 25.688 -19.43348 25.37547 25.61814 -20.274 26.20421 25.52647 -20.97765 26.88001 25.42197 -21.62291 27.48127 24.45836 -18.19291 25.88882 22.93315 -21.07082 30.32813 22.44664 -17.86128 28.91454 21.63132 -20.22158 31.65688 23.35831 -17.47875 26.99855 24.07106 -19.97682 28.02493 23.32003 -17.44867 27.03718 23.14795 -17.3087 27.21079 22.6893 -16.89546 27.67355 20.39912 -12.59302 33.30105 19.65663 -15.29375 35.90433 19.83859 -16.93935 34.30306 19.82005 -17.14949 47.95089 19.23017 -17.08262 46.47637 20.63511 -14.46988 43.80186 18.79305 -17.07585 44.88592 18.59879 -17.1082 43.84672 19.44741 -15.48261 42.16003 21.28484 -16.1118 30.12786 21.15297 -13.93118 29.18985 20.85601 -12.28536 29.45212 20.59074 -14.32586 31.61488 22.03274 -16.09364 28.33447 21.74965 -15.59919 28.61536 21.29589 -14.4511 29.05566 20.49776 -18.63537 32.89089 20.06759 -19.2182 33.88676 20.89022 -19.77906 32.57682 18.4571 -17.6025 39.45761 18.69453 -17.96638 37.78201 19.10285 -18.4124 36.17472 19.40841 -18.69283 35.30922 22.18832 -13.7776 45.29858 20.30943 -17.22329 48.87704 22.32803 -6.135391 35.2708 23.34745 -5.725086 36.86993 22.80775 -8.542918 38.68467 24.46816 -5.426536 38.18765 20.63183 -8.762168 29.63873 20.9979 -6.942741 31.69564 21.01526 -8.295202 32.79648 21.02988 -6.861322 31.79556 20.66675 -9.917212 29.57964 20.6673 -10.02454 30.84142 21.944 -11.44754 41.01692 20.7364 -12.47723 39.3476 21.53614 -9.627192 36.92685 21.90175 -6.804566 34.77791 22.03101 -6.289783 34.68844 21.3386 -6.718351 32.94001 23.52321 -10.74366 42.53871 24.47069 -7.801724 40.28713 25.00666 -5.323956 38.71146 18.41345 -17.23418 42.07569 18.68477 -16.76499 40.45541 19.96099 -13.78109 37.61443 20.71962 -11.00018 35.1018 18.4017 -17.45935 40.29419 20.63004 -8.813689 29.58482 35.38842 -0.4191205 15.6577 35.38887 -4.583749 15.65792 35.54847 -4.583749 15.70515 35.54847 -0.3457587 15.70515 35.50718 -0.2914057 15.69032 35.48452 -0.260052 15.67218 35.44449 -0.1999999 15.60957 22.87397 -23.38581 -0.09937059 19.75243 -22.56079 -0.1031485 19.96278 -16.26091 -0.1028938 15.51323 -21.12326 -0.1082792 19.96278 -14.28923 -0.1028938 9.788833 -18.93657 -0.1152077 4.335438 -16.9189 -0.121808 28.85976 -23.93467 -0.09212535 26.98562 -23.95988 -0.09439408 24.87412 -23.7548 -0.09694963 34.82164 -21.74061 -0.08490949 33.57513 -22.55003 -0.08641821 32.73496 -22.9758 -0.08743524 31.41181 -23.4718 -0.08903664 30.02107 -23.7947 -0.09071999 -8.196562 -15.83939 83.82208 -6.497401 -15.77304 84.42274 -6.548411 -15.5405 84.48957 -6.691272 -14.52533 84.60107 -6.188889 -16.74026 83.9338 -8.011596 -16.97488 83.08627 -6.11402 -16.9089 83.80287 -5.768739 -17.49299 83.16303 -7.734775 -17.73358 81.98505 -5.38741 -17.86478 82.40133 -5.32133 -17.90477 82.26376 -7.408243 -18 80.68607 -4.981596 -18 81.52742 -12.60706 -18 80.33153 -9.991816 -18 80.2766 -12.4599 -17.73358 81.66281 -10.08294 -17.73358 81.61289 -12.33514 -16.97488 82.79141 -10.1602 -16.97488 82.74574 -12.25179 -15.83939 83.54553 -10.21182 -15.83939 83.50269 -2.390463 -15.52002 82.95135 -2.265957 -15.52339 82.68991 -2.380539 -15.45503 82.96014 -2.002961 -15.50115 81.69477 -1.966059 -15.40087 81.3109 -1.99062 -15.49481 81.56384 -1.980605 -15.47994 81.30221 -3.507437 -15.33127 84.2288 -2.765193 -15.49132 83.52268 -2.669643 -15.50053 83.39808 -4.434458 -15.20997 84.6768 -4.227816 -15.25541 84.60283 -3.42908 -15.40378 84.16036 -6.671529 -14.50908 84.60927 -4.960833 -14.44808 84.89855 -5.734604 -14.85367 84.83073 -5.501206 -14.92715 84.84116 -1.867011 -15.07113 81.39294 -2.319721 -15.17566 83.03637 -3.439901 -14.95007 84.30565 -5.079253 -15.04903 84.818 -4.831083 -14.01701 84.9926 -3.372889 -14.68244 84.39671 -2.258821 -14.98037 83.13404 -1.75482 -14.83968 81.50603 -4.616466 -13.50395 85.15687 -3.268402 -14.36047 84.55631 -2.163709 -14.74636 83.31439 -1.56495 -14.5699 81.72634 -3.675942 -13.21404 85.22586 -2.615065 -14.01617 84.48309 -1.846847 -14.47888 83.2517 -1.516815 -14.51453 81.76496 -3.051062 -13.04304 85.13268 -2.199963 -13.82024 84.33675 -1.647477 -14.32476 83.15263 -1.482085 -14.47579 81.76997 -19.57156 -14.00078 78.91812 -19.42741 -14.39608 79.2649 -19.26918 -13.59358 79.94968 -19.25147 -15.21874 78.41186 -19.42635 -14.49433 79.17178 -19.99159 -11.19712 76.86435 -19.96288 -11.92852 77.40215 -19.67965 -13.62008 78.64114 -19.99158 -11.19391 76.86925 -19.94802 -11.77664 77.63259 -19.52351 -13.11181 79.36949 -19.36401 -13.4076 79.74968 -19.26221 -13.57512 79.96389 -19.14468 -14.80048 79.71609 -19.09453 -13.65617 80.28117 -18.78181 -15.7924 78.99798 -15.1282 -14.48259 83.51867 -15.55338 -14.45739 83.36711 -15.60314 -16.16343 82.86106 -16.26661 -14.38818 83.03934 -16.37894 -16.03002 82.49405 -17.36197 -14.20693 82.3208 -17.51641 -15.69956 81.71941 -17.83918 -14.09401 81.90257 -17.98715 -15.50426 81.28743 -18.77558 -13.79208 80.79551 -18.86209 -15.01139 80.19955 -18.92007 -15.58398 76.96962 -18.64511 -15.93229 77.50559 -18.05423 -16.49986 78.22248 -17.74097 -16.74148 78.50598 -18.49895 -16.04661 79.39593 -16.84735 -17.27824 79.13238 -17.63355 -16.63946 80.29983 -16.40139 -17.47898 79.37701 -17.17171 -16.87375 80.66302 -15.39338 -17.8012 79.81513 -16.06194 -17.26903 81.32359 -14.7461 -17.92425 80.0288 -15.30865 -17.42811 81.64327 -13.67572 -18 80.2852 -14.01779 -17.53109 82.00144 -14.15947 -16.97488 82.71234 -14.35985 -14.5 83.7177 -14.30777 -15.83939 83.45641 -14.26819 -16.25 83.25782 26.01467 -12.53613 85.41294 26.01151 -12.67258 85.41112 25.92664 -13.69834 85.30268 25.80265 -14.38553 85.1328 26.02187 -12.53271 85.41294 26.08806 -12.63693 85.41183 26.56291 -13.45537 85.34725 26.85646 -14.04997 85.25067 27.05648 -14.83279 85.12844 26.76956 -14.52078 85.19166 26.70142 -14.93582 85.13082 25.99879 -15.12055 85.00102 25.54101 -14.87884 84.91223 25.34147 -15.26773 84.69944 25.04241 -15.32435 84.48957 2.980246 -15.31737 88.1197 3.229153 -16.28721 87.79201 3.671821 -17.10902 87.24209 4.340935 -17.73401 86.44921 4.490883 -17.81727 86.27261 5.221189 -17.99995 85.39379 5.227501 -17.99995 85.39604 4.858341 -17.84216 86.41396 4.780504 -17.76925 86.62331 4.412605 -17.19824 87.59278 4.139502 -16.38908 88.29711 3.970693 -15.37638 88.72873 5.233814 -17.99995 85.39827 5.230784 -17.81727 86.5416 5.228793 -17.73401 86.77356 5.202161 -17.10902 87.81266 5.156641 -16.28721 88.51914 5.115854 -15.31737 88.93003 5.240126 -17.99993 85.40052 5.601773 -17.74303 86.65332 5.674604 -17.62916 86.89618 5.980859 -16.84809 87.88511 6.156901 -15.994 88.43109 6.243266 -15.14924 88.69325 11 -15.83939 87.43358 15.878 -16.21084 88.32412 13.51339 -15.83939 87.71244 13.67969 -16.97488 86.97218 7.777826 -18 84.5575 8.071414 -17.73358 85.86431 8.320308 -16.97488 86.97218 8.486612 -15.83939 87.71244 15.76275 -15.24274 88.67512 15.77581 -15.41239 88.63565 13.92859 -17.73358 85.86431 16.09318 -17.09246 87.65068 16.04115 -16.92556 87.81574 16.75988 -17.99993 85.40052 14.22217 -18 84.5575 16.448 -17.80818 86.48559 16.37414 -17.70787 86.73397 11 -18 84.2 11 -17.73358 85.53939 11 -16.97488 86.67488 16.77881 -17.99995 85.39379 17.40769 -17.8642 86.15274 17.55848 -17.79173 86.3308 18.15817 -17.31592 87.0382 18.27689 -17.17586 87.18027 18.67742 -16.51132 87.67294 18.96221 -15.6345 88.04244 19.00144 -15.43136 88.09502 16.7725 -17.99995 85.39604 17.08961 -17.88295 86.27298 17.16716 -17.81987 86.48272 17.48981 -17.39194 87.33842 17.55759 -17.26131 87.51527 17.80021 -16.61533 88.1424 17.98915 -15.71226 88.62625 18.01646 -15.4975 88.69594 16.76619 -17.99995 85.39827 16.76833 -17.8642 86.38442 16.76977 -17.79173 86.618 16.78736 -17.31592 87.54676 16.79434 -17.17586 87.73221 16.83115 -16.51132 88.36782 16.87357 -15.6345 88.83393 16.8807 -15.43136 88.89937 -14.29218 -19.52702 4.174715 -14.42198 -20.3628 6.946236 -17.45128 -19.93299 6.756376 -3.870463 -17.49476 0.4429725 3.337863 -19.78473 0.4747334 -31.77968 -13.25838 0.09501314 -31.77696 -11.94655 -0.1336642 -30.1747 -13.91832 0.2961421 -31.78201 -14.31301 0.4509935 -31.77276 -11.54679 -0.1593701 -31.76973 -11.40466 -0.1636742 -31.76643 -11.26253 -0.1654507 -31.77701 -11.87333 -0.1398789 -31.77554 -11.71011 -0.1512974 -30.20483 -16.28382 1.622427 -31.78756 -16.58338 1.886583 -31.78531 -15.70604 1.201583 -30.22885 -18.07028 3.662889 -31.79248 -18.25059 3.992759 -31.79057 -17.64944 3.055961 -31.78602 -19.05369 6.148299 -31.7866 -19.04683 6.116806 -30.24398 -19.07238 6.183017 -31.79026 -18.99841 5.909777 -31.79325 -18.94449 5.704025 -31.79481 -18.88515 5.499876 -31.79483 -18.86947 5.449086 7.758882 -24.19012 2.199836 8.692049 -21.7771 0.4854921 -2.97349 -22.2485 4.620941 1.912609 -23.86734 4.732393 7.129778 -25.81244 4.769803 -4.990111 -21.65311 4.55574 -4.532588 -19.95745 2.083735 -21.33272 -19.52094 6.535034 -22.8982 -19.39514 6.455852 -22.83337 -18.44684 3.845181 -28.90484 -19.10134 6.219707 -28.88152 -18.10602 3.687466 -17.34456 -19.0514 4.046625 -28.79287 -13.94909 0.3008117 -22.55709 -14.26367 0.328085 -16.84702 -14.84912 0.3607633 -13.65135 -15.32179 0.3812161 -8.72928 -16.27506 0.4134896 -9.245342 -18.73783 1.990266 -14.02355 -17.76984 1.886296 -17.13423 -17.28183 1.820474 -22.71491 -16.6647 1.717033 -28.84271 -16.31972 1.635373 -9.609386 -20.46775 4.376186 -11.73032 -20.83137 7.119089 -9.771255 -21.22648 7.242525 -5.177294 -22.3381 7.503815 -3.169701 -22.90545 7.597918 1.697916 -24.47402 7.757259 6.899423 -26.3999 7.808595 12.9788 -28.01286 4.704373 12.74809 -28.63156 7.710525 17.63742 -29.52532 4.57075 17.42691 -30.20864 7.513058 20.05778 -30.92649 7.367105 21.32032 -30.42564 4.428304 21.15154 -31.17733 7.301626 23.83602 -30.83469 4.322892 23.71579 -31.63546 7.144222 14.47188 -23.95866 0.4825216 18.8899 -25.40636 0.4688339 22.24551 -26.24054 0.4529633 24.45698 -26.61001 0.44102 26.86107 -26.80276 0.4286465 29.07213 -26.74437 0.4207959 30.48559 -26.56534 0.4193691 32.22201 -26.16629 0.4231349 33.90403 -25.55802 0.4330754 34.97349 -25.03902 0.4421418 36.54011 -24.0653 0.4579207 38.00708 -22.89412 0.4739683 13.58322 -26.37438 2.169997 18.14954 -27.84429 2.104927 21.7026 -28.70053 2.035111 24.09469 -29.08084 1.983517 26.75156 -29.2738 1.929654 29.25604 -29.19396 1.893305 30.8897 -28.98305 1.883535 32.92743 -28.51644 1.892232 34.92014 -27.80513 1.924227 36.18638 -27.20018 1.954816 38.02497 -26.07572 2.008867 39.71775 -24.74492 2.064094 26.67138 -31.04979 4.212302 29.38792 -30.9695 4.136676 31.18194 -30.73987 4.115269 33.43792 -30.22189 4.130508 35.65141 -29.42552 4.192506 37.05406 -28.74883 4.252359 39.07546 -27.50008 4.358261 40.91389 -26.04072 4.466278 24.93279 -31.78136 7.07146 26.63105 -31.89844 6.978024 29.45086 -31.8434 6.863386 31.32506 -31.61199 6.83029 33.68824 -31.0647 6.851917 36.00294 -30.20891 6.943552 37.46222 -29.48099 7.032145 39.54958 -28.14584 7.188493 41.42953 -26.60174 7.347203 -36.33746 -11.62373 2.803467 -36.51115 -11.6725 3.254428 -36.56675 -11.6568 3.429729 -36.76844 -11.47416 4.651502 -36.77167 -11.50335 4.862359 -36.7716 -11.47976 4.878816 -36.7716 -11.51152 4.868662 -36.7716 -11.49644 4.876293 -36.7716 -11.52305 4.856094 -36.7716 -11.52832 4.842084 -36.7716 -11.52872 4.839007 -36.76819 -11.54561 4.655234 -35.96903 -11.77127 2.135875 -33.35611 -11.9364 0.1213728 -33.86452 -11.92202 0.3214927 -33.64591 -11.83897 0.219795 -34.48169 -11.89582 0.6586133 -34.83467 -11.87567 0.9071926 -35.24356 -11.75153 1.250926 -35.71849 -11.80165 1.785016 -31.94958 -11.94782 -0.1307133 -33.18074 -11.94001 0.06672281 -31.84521 -11.25799 -0.1649376 -32.23511 -11.37878 -0.1429439 -32.63381 -11.5033 -0.08694905 -33.11545 -11.65729 0.02789741 -34.35726 -11.5865 0.5600579 -33.46914 -11.45525 0.1331894 -32.69647 -11.3522 -0.07878232 -31.92397 -11.25345 -0.1631769 -35.40966 -11.50294 1.406067 -34.25364 -11.40407 0.4944285 -33.14978 -11.32514 0.02824944 -32.00269 -11.24891 -0.1601687 -36.19532 -11.41275 2.503741 -34.96372 -11.3513 0.985908 -33.59107 -11.29784 0.1772164 -32.08136 -11.24436 -0.155914 -36.39157 -12.47877 3.074677 -33.68986 -13.16237 0.4619519 -35.30939 -12.8886 1.508298 -36.7716 -11.99529 4.922507 -33.69147 -14.16674 0.8016714 -33.69376 -15.49308 1.517398 -33.69532 -16.32822 2.170262 -33.6974 -17.34274 3.284382 -33.69873 -17.91468 4.176663 -33.70035 -18.50329 5.563476 -34.28423 -18.22715 5.649739 -35.3102 -13.75033 1.800033 -35.31137 -14.88819 2.414451 -35.31217 -15.60457 2.974785 -35.31323 -16.47474 3.930852 -35.31391 -16.96524 4.696458 -35.31474 -17.46997 5.886273 -36.3918 -13.12716 3.294103 -36.39211 -13.98336 3.756301 -36.39233 -14.52245 4.177855 -36.39261 -15.17728 4.897175 -36.39279 -15.54641 5.473228 -36.10527 -16.48434 6.194171 -36.7716 -12.3921 5.056446 -36.7716 -12.91623 5.338857 -36.7716 -13.24633 5.596589 -36.7716 -13.64744 6.036569 -36.7716 -13.87362 6.38904 -36.7716 -14.10648 6.936984 -36.09458 -17.2441 12.61531 -36.59954 -16.04732 13.2776 -36.39046 -16.51683 10.21775 -33.06447 -19.46428 10.53683 -34.2668 -19.00946 11.24017 -35.30513 -18.13422 10.08521 -35.30302 -18.24844 11.93839 -36.39233 -16.04418 6.850329 -36.39253 -15.98086 6.566195 -35.78059 -17.04277 6.372925 -36.7716 -14.17578 7.247684 -36.72184 -14.79636 6.797105 -33.6811 -19.21409 9.996719 -31.76645 -19.58083 9.834491 -33.68401 -19.11679 8.987488 -31.77014 -19.49473 8.946203 -33.69472 -18.69018 6.287596 -31.78561 -19.06639 6.207589 -32.10155 -19.03972 6.13513 -35.30662 -18.03944 9.105177 -35.31209 -17.62912 6.513254 -34.11052 -18.46092 6.156137 -36.39086 -16.42673 9.281348 -36.7716 -14.75317 13.71336 -36.7716 -14.60851 10.37413 -36.7716 -14.5243 9.489169 35.65713 -0.2854154 15.71877 35.55444 -0.1999999 15.67382 35.6294 -0.2031753 15.69921 35.71082 -0.1999999 15.71659 35.5192 -0.1999999 15.65835 37.18444 -2.981839 16.0085 36.57424 -3.568674 15.87041 38.87057 -1.455837 16.55436 40.37289 -0.854007 16.97776 40.81064 -0.5442534 17.19872 40.68782 -0.4504545 17.29597 39.04278 -1.862702 16.42248 39.16335 -1.767373 16.46611 39.0634 -1.680542 16.53664 35.60128 -4.63862 15.7057 35.65426 -4.692218 15.69473 36.71088 -3.711547 15.85793 38.56918 -2.244141 16.2632 37.87341 -2.823539 16.06272 37.33786 -3.145942 15.99482 37.41413 -3.217413 15.95121 36.77831 -3.775877 15.82297 36.64194 -3.641555 15.87395 37.25996 -3.066051 16.01425 38.96279 -1.573484 16.56697 -13.08702 -15.90705 47.35809 -13.11137 -15.94127 47.16561 -13.09228 -15.98361 47.1887 -13.1231 -15.93387 47.55013 -13.07497 -15.94718 47.37062 -13.1376 -15.89295 47.54797 -13.20025 -15.37608 46.62219 -13.33125 -15.58196 46.64584 -13.28269 -16.04219 46.53722 -13.36113 -15.82334 46.61505 -13.11481 -16.1859 46.43106 -12.83555 -16.31262 47.00545 -13.013 -16.17269 47.11254 -13.0049 -16.18347 47.10667 -13.56289 -15.25698 45.89665 -13.68545 -15.45831 45.93247 -13.7143 -15.69426 45.91405 -13.64288 -15.91117 45.84556 -14.57584 -15.86355 44.03929 -13.86465 -15.96766 45.10991 -13.48742 -16.05972 45.74258 -15.94326 -15.68088 42.45545 -14.69868 -15.70469 44.12563 -15.98288 -15.48765 42.47156 -14.752 -15.49702 44.16819 -15.9613 -15.29368 42.43877 -14.72561 -15.28023 44.15884 -15.88192 -15.12935 42.3622 -14.62455 -15.09576 44.09935 -15.84867 -15.84309 42.39296 -13.0161 -16.07001 47.40975 -12.63118 -16.39426 47.53742 -12.45752 -16.45122 47.64444 -12.63942 -16.38876 47.57849 -12.64913 -16.38651 47.61954 -12.89916 -16.23109 47.58192 -13.05495 -16.05974 47.55862 -12.87402 -16.23731 47.48142 -12.80659 -16.30038 47.42086 -12.86315 -16.25967 47.38066 -13.01747 -16.10562 47.25973 -14.70539 -15.88562 60.3252 -15.11964 -15.80883 60.38386 -14.41465 -16.01734 57.00908 -12.25406 -16.49721 46.13861 -11.74219 -16.61557 45.36865 -11.67181 -16.48061 48.64528 -11.21267 -16.70074 44.56369 -10.66613 -16.75345 43.72284 -10.65812 -16.75398 43.71043 -12.38649 -16.46018 46.33666 -12.65176 -16.39233 47.33134 -12.69 -16.39837 48.43601 -15.75577 -15.57921 60.4788 -16.12104 -15.37518 60.53646 -15.34973 -15.58626 56.78392 -16.64329 -14.95867 60.62431 -16.07707 -14.84978 56.58517 -16.92592 -14.64274 60.67576 -16.97044 -14.58443 60.68423 -13.38725 -16.08981 57.23288 -14.03342 -15.89874 60.23485 -16.96996 -14.60991 60.78873 -16.96818 -14.63382 60.87897 -16.97048 -14.58764 60.698 20.95838 -6.809269 31.44152 21.03322 -6.800097 31.79325 21.34117 -6.625187 32.91804 27.92776 -4.254246 40.66053 26.41745 -4.75973 39.75791 25.02339 -5.091895 38.64799 24.48235 -5.203797 38.12536 23.35642 -5.529885 36.81283 22.33281 -5.97912 35.22408 22.0348 -6.148746 34.64668 29.96795 -3.369038 41.49665 28.29277 -4.112174 40.83997 32.06391 -2.204347 41.97514 31.8506 -2.363739 41.9426 31.8013 -2.392319 41.93457 32.17779 -1.980768 41.99106 32.17076 -2.03404 41.9901 32.13276 -2.119052 41.98488 20.71114 -6.921062 29.45013 20.71635 -6.916133 29.49851 20.69296 -6.927685 29.37391 20.65973 -6.932921 29.2948 20.65436 -6.933445 29.28484 20.95502 -6.870165 31.44371 -36.31805 -16.26247 15.34846 -36.3895 -16.67207 13.89861 -35.3016 -18.29604 13.88557 -35.64537 -17.67539 15.12471 -34.65768 -18.30328 15.93415 -35.54576 -16.67679 16.5716 -31.75598 -19.75492 13.87386 -33.32624 -19.38469 14.98638 -33.24433 -19.51348 14.34863 -34.58548 -18.79641 14.77995 -33.67418 -19.37882 13.87688 -19.73395 -14.0086 39.3274 -19.35012 -15.17808 39.0752 -19.6256 -14.43497 39.25759 -21.37669 -15.00374 36.65049 -18.42761 -16.01981 39.26088 -20.43247 -16.5886 36.20354 -18.18639 -16.04862 39.49536 -17.21911 -15.97168 40.6872 -17.0184 -15.94739 40.94549 -18.70776 -15.89704 39.0965 -18.98405 -15.68868 39.01675 -19.2155 -15.4175 39.02076 -13.09591 -16.72521 43.03446 -13.29911 -16.6969 42.98102 -15.85076 -17.05483 39.87976 -14.0446 -16.55207 42.79089 -14.71696 -16.35776 42.62962 -15.33103 -16.11385 42.49424 -10.67023 -16.75513 43.70697 -14.28876 -17.4646 38.83583 -11.50029 -16.8046 43.47142 -12.31041 -16.7945 43.24622 -26.98675 -15.95027 28.72443 -31.93434 -16.5062 21.71087 -26.08232 -17.534 28.24194 -31.04491 -18.10713 21.16181 -19.09587 -17.67816 35.41014 -24.77912 -18.62939 27.42904 -29.73869 -19.1998 20.29267 -16.03929 -17.81687 36.46591 -17.55953 -18.11539 34.38467 -23.26267 -19.08049 26.40147 -28.20667 -19.62441 19.23053 -19.43037 -14.4105 39.41464 -19.15914 -15.14147 39.23067 -19.18993 -14.35036 39.45878 -18.93081 -15.05479 39.27904 -19.53717 -13.99075 39.48598 -19.29155 -13.94589 39.52895 -18.74545 -15.37635 39.24869 -18.88847 -15.54919 39.17958 -18.67893 -15.71369 39.24511 -19.06198 -15.33252 39.1836 -18.86839 -15.20683 39.24709 -18.58653 -15.20824 39.20885 -18.64176 -15.13709 39.19819 -18.67909 -15.06925 39.19665 -18.59003 -15.50078 39.30261 -18.46742 -15.80762 39.37653 -18.42992 -15.56727 39.40488 -18.26989 -15.88707 39.54927 -18.28659 -15.82634 39.55788 -18.30153 -15.70036 39.56012 -18.29123 -15.57515 39.54238 -18.27675 -15.51537 39.52633 -18.46115 -15.30648 39.25597 -18.32411 -15.35641 39.33913 -18.19913 -15.35871 39.45277 -17.11996 -15.40585 40.98357 -17.04153 -15.24536 40.90838 -17.10745 -15.78537 41.00363 -17.14309 -15.59534 41.01699 44.31935 2.486668 53.90983 44.30227 2.52796 54.00159 43.87546 0.05116349 55.41389 43.41401 -1.825567 56.70668 44.32298 2.467779 53.88446 43.80357 -0.2977847 54.98455 43.44801 -1.476264 55.5573 43.11184 -2.386834 56.0671 42.82004 -0.2072498 62.98239 42.46575 0.3165112 62.77561 42.99997 -0.6060224 61.40828 43.35269 -0.9372917 61.98371 43.50585 -1.549507 60.8917 43.09524 -0.9904503 59.41571 43.25604 -1.805878 58.78031 43.41097 -2.724593 59.25613 43.33953 -2.460127 58.85881 43.29228 -1.995732 58.19379 43.30382 -1.77109 57.91163 43.6569 -3.12922 60.16943 43.57575 -3.258531 59.93744 43.63559 -2.756693 60.12583 43.45958 -2.871706 59.46794 43.59724 -2.241487 60.27931 43.66493 -3.279299 60.2262 43.61101 -3.419019 60.10905 43.59967 -3.363567 60.04986 43.70095 -3.982691 60.84486 43.69963 -3.973021 60.82899 43.63803 -3.565779 60.27191 42.72985 -0.08842933 61.05252 43.54731 -1.803108 60.60868 42.90957 -0.4432439 60.20478 43.86239 -4.952772 62.43458 42.54133 -6.556286 62.22093 42.12691 -5.722215 59.9909 43.72369 -0.1141545 53.57924 43.6948 -3.987039 60.83003 43.50783 -4.129261 60.42148 43.3527 -4.187708 60.0383 44.01157 -3.631162 61.56031 41.91975 -4.737287 57.75704 42.79888 -4.063142 58.29885 42.9384 -4.205479 58.91072 42.79654 -3.297625 56.87025 41.90533 -3.587775 55.52129 42.74125 -3.595089 57.28698 41.95402 -3.054473 54.58579 42.20541 -1.616392 52.30656 41.62821 -0.1999999 48.5434 41.08825 -0.6631572 48.91889 41.7776 -0.6647678 49.93495 42.25553 1.87567e-4 48.61454 42.22737 0 48.56586 40.59171 -0.1999999 47.27003 41.31992 -0.1999999 48.10464 40.43368 -0.3655185 47.39191 40.50765 -0.2170613 47.20848 40.35194 -0.1999999 47.0358 39.24964 -0.6583599 46.43988 39.28921 -0.5163654 46.30966 38.52504 -0.8910132 45.91891 38.59407 -0.571184 45.6879 37.79373 -1.106314 45.3978 37.8538 -0.786851 45.16345 37.09178 -1.331379 44.95614 37.11846 -1.013871 44.7016 37.8186 -0.4062722 45.04301 37.05389 -0.633031 44.57085 32.35116 -1.980768 42.04815 34.28525 -1.515915 43.08502 32.2671 -1.980768 42.01163 23.58901 -15.25737 77.62563 22.21062 -14.57886 76.52814 22.1376 -14.30111 81.32678 22.97161 -14.73012 77.58552 23.93606 -15.76396 81.75148 23.93755 -15.77034 81.68941 23.93846 -15.77542 81.5791 23.88413 -16.02726 75.09446 23.59614 -15.41437 75.92512 23.81241 -16.27636 71.74938 23.61846 -16.16022 70.32091 23.63739 -16.70996 67.17178 22.9882 -14.88804 75.87386 22.29287 -15.25833 70.96628 23.0403 -15.6382 70.24047 22.35642 -16.0627 66.18595 23.0732 -16.33556 66.23564 23.59156 -16.8 66.32023 25.30476 -17.20736 83.09816 26.41852 -17.44618 83.44797 26.55592 -17.14388 83.89667 24.42836 -16.60415 82.5616 25.42775 -16.96488 83.60501 24.51152 -16.4597 83.0617 26.60573 -17.0243 84.03732 25.47678 -16.86738 83.76281 26.88364 -16.18353 84.70402 25.77792 -16.18179 84.50457 26.91798 -16.04184 84.7782 25.81808 -16.06772 84.58713 27.05192 -15.07529 85.0932 25.98805 -15.30686 84.9522 28.07642 -14.77188 84.84086 27.99931 -15.82864 84.5987 27.9757 -15.97876 84.53707 27.76403 -16.8469 83.99991 27.7218 -16.96906 83.89163 27.59391 -17.28292 83.55583 24.54958 -16.4001 83.2183 24.81363 -15.97378 83.96672 24.85201 -15.90269 84.05194 25.02728 -15.43557 84.43675 28.42998 -18 64.82235 31.79198 -18 69.47966 26.08366 -18 66.86878 26.83649 -18 81.56642 26.70059 -18 74.98365 29.19456 -18 80.70941 26.52127 -18 71.5677 32.0754 -18 80.23364 35.00834 -18 72.70595 35.00834 -18 80.33868 34.87493 -18 72.60038 34.99343 -18 80.33665 33.21689 -18 71.11179 25.96907 -18 65.99246 25.95128 -18 65.8636 25.93485 -18 65.17181 25.9794 -18 64.85986 26.18617 -18 64.20893 26.3353 -18 63.92037 26.74116 -18 63.38365 26.9847 -18 63.15646 27.19303 -18 62.99827 44.44211 -7.317793 67.67798 44.43409 -8.021047 68.80238 42.8717 -8.85114 66.75883 42.84324 -9.544236 67.85813 44.4498 -6.629245 66.54035 42.89898 -8.171045 65.64416 42.9017 -7.886852 65.15603 44.42384 -6.333463 65.95233 42.80258 -7.138977 63.68506 44.23017 -5.55655 64.18581 43.74713 -1.598157 61.63265 44.05279 -2.590412 61.54903 -0.1234524 -14.10104 66.25225 -0.1206011 -13.76487 71.8245 -1.00224 -14.0269 71.83485 -0.1062179 -13.67568 77.18727 -1.98842 -15.40226 75.90038 -1.670153 -14.56313 77.17977 -0.08374363 -13.82265 81.7124 -0.1374387 -13.82519 81.70785 -0.1910637 -13.82937 81.70666 -0.410162 -13.86225 81.70981 -0.7661648 -13.97181 81.72038 -0.9935509 -13.93374 77.18509 -1.035841 -14.10819 81.73363 -1.336227 -14.33076 81.75552 -1.673269 -14.65552 71.85964 -0.9505984 -14.33373 66.27056 -1.603413 -14.89101 66.31445 -1.958011 -15.65488 66.3746 0.8521837 -14.29077 66.26726 1.615694 -14.92531 66.31722 1.616232 -14.608 71.46456 1.228285 -14.3368 83.00322 0.9389925 -14.10937 82.48884 0.8750532 -13.9966 81.18402 0.7584132 -14.00705 82.24572 0.4608853 -13.89127 81.95264 0.2185366 -13.83919 81.80117 1.694263 -14.97393 84.31412 1.629619 -14.85325 84.08029 1.623955 -14.63262 81.15046 1.465411 -14.60325 83.57373 1.939143 -15.64416 85.06671 1.929915 -15.62635 85.24208 1.883808 -15.46472 85.17268 1.925767 -15.61619 85.29245 1.916982 -15.59227 85.36331 1.941436 -15.64665 85.00015 1.860188 -15.3857 85.0466 1.94694 -15.6406 84.71475 1.968399 -15.47366 81.10713 1.61897 -14.50429 76.41282 1.975491 -15.40195 76.59456 1.969208 -15.46562 71.50025 1.944917 -15.65487 66.37466 0.861189 -13.86761 76.41338 0.853618 -13.97204 71.43751 1.870133 -15.28288 85.90876 2.051039 -15.91594 85.81893 2.137852 -14.52347 87.01024 2.049061 -15.44856 86.49038 2.06099 -15.59438 86.39249 2.286062 -16.19774 86.26126 2.132621 -14.51731 87.00019 1.877059 -15.18268 86.0707 3.567382 -17.6989 84.7518 2.520664 -16.85604 84.72786 3.058403 -17.33744 85.44593 2.344527 -16.59212 85.23284 2.935673 -17.21173 85.59621 2.588867 -16.75849 85.98177 2.475718 -16.5718 86.09348 2.301338 -16.51087 85.34207 2.174425 -16.23572 85.62135 2.130336 -16.12747 85.70136 11.31194 -18 64.99493 15.46385 -18 64.6163 16.60707 -18 64.45978 4.88003 -18 66.16831 4.872113 -18 66.32307 4.948441 -18 76.59562 5.354199 -18 65.38217 5.645069 -18 65.2328 17.17771 -18 83.65095 17.27644 -18 75.98117 17.53605 -18 70.93581 4.890697 -18 66.09849 4.987464 -18 65.80767 5.018236 -18 65.74981 5.711044 -18 65.21164 6.044265 -18 65.16266 5.208477 -18 65.50332 5.281401 -18 65.43766 18.04404 -18 65.9924 18.06145 -18 65.86597 16.76819 -18 64.443 18.07003 -18 65.78192 16.80577 -18 64.44116 17.11184 -18 64.47174 17.1947 -18 64.49479 17.48966 -18 64.63476 17.54402 -18 64.67211 17.83379 -18 64.9644 17.99599 -18 65.27127 18.02261 -18 65.35233 17.79227 -18 64.9095 18.07265 -18 65.68665 19.71337 -16.29905 86.1672 19.95878 -16.03698 85.73 19.53563 -16.63094 86.00988 19.88145 -16.22558 85.62129 19.23395 -17.06825 85.69755 19.0179 -17.30984 85.44482 18.44787 -17.72202 84.67405 19.76179 -16.48538 85.3992 19.68099 -16.63823 85.21766 19.47526 -16.93961 84.66201 20.0996 -15.75374 85.21545 20.08936 -15.77996 85.07913 20.08447 -15.79114 84.96869 20.07856 -15.79775 84.65493 19.97362 -15.58872 86.37362 19.89645 -14.52494 86.9472 19.98342 -15.46212 86.45388 21.62777 -16.06797 66.18691 20.46724 -15.01962 81.3413 20.11446 -15.96795 76.07434 20.48725 -15.26495 76.58929 20.21833 -16.32922 71.13212 20.51032 -15.90354 71.06159 20.42154 -16.8 66.32021 20.07494 -15.7783 83.63395 20.07487 -15.77784 81.35678 21.21603 -14.45959 81.32998 21.31929 -15.35841 70.98107 21.3625 -16.13717 66.19951 20.9494 -16.3297 66.23457 21.2642 -14.71074 76.53989 -12.34904 -17.88404 64.50019 -11.00375 -18 64.68484 -12.94462 -17.75516 64.38252 -14.05368 -17.37136 64.07833 -16.73995 -15.1175 61.75142 -16.93706 -14.71996 61.06494 -15.48529 -16.51916 63.38376 -14.6922 -17.0506 63.82845 -16.32313 -15.70972 62.54963 -15.90367 -16.15798 63.04289 43.74314 -24.13818 11.17635 42.94431 -25.17204 11.66498 42.95254 -25.18302 10.2095 44.88654 -21.21969 10.36199 44.66697 -22.14042 10.54816 44.47673 -22.69654 10.21598 44.47568 -22.69771 10.68977 44.13015 -23.46879 10.9265 44.47202 -22.6775 8.7933 44.87311 -21.26364 8.853857 43.81861 -23.9941 8.736908 42.93498 -25.16892 8.68659 42.92217 -25.1768 8.5473 43.79551 -24.00227 8.347805 44.43721 -22.68454 8.163722 44.8254 -21.26857 8.001327 44.66343 -21.30165 7.015131 44.47353 -21.34409 6.308771 44.05875 -21.44017 5.242366 43.68004 -21.52935 4.522278 42.88238 -25.21246 8.384694 43.7276 -24.04572 7.894709 42.83675 -25.256 8.267551 43.65016 -24.10011 7.567045 42.73859 -25.35187 8.090203 43.48247 -24.22205 7.065082 42.65016 -25.43889 7.97054 43.32941 -24.33465 6.719378 42.46517 -25.62059 7.781414 43.00175 -24.5752 6.153031 42.27333 -25.80729 7.637544 42.65003 -24.83046 5.694301 41.9797 -26.0887 7.483128 42.08455 -25.23307 5.146211 41.78832 -26.26918 7.415294 41.69565 -25.50476 4.863322 44.32853 -22.7262 7.432614 44.20291 -22.77902 6.905545 43.92923 -22.89829 6.101343 43.6786 -23.00906 5.55019 43.14119 -23.24729 4.653166 42.56387 -23.50229 3.933381 41.63583 -23.90921 3.084576 40.99806 -24.1873 2.653536 42.8747 -21.72052 3.376319 42.0214 -21.9239 2.488843 40.67704 -22.24547 1.49808 39.77299 -22.46307 1.031275 40.79205 -18.03504 14.20721 41.85727 -15.04719 13.14199 43.64122 -19.46543 12.67137 39.353 -20.69114 15.64626 42.41375 -22.71106 14.03961 42.90358 -22.09357 13.58916 43.13878 -21.6898 13.35836 43.45957 -20.88254 13.00823 43.58525 -20.31963 12.83611 37.87976 -25.82486 18.03802 39.30178 -25.19001 16.80312 37.59019 -22.92308 17.40907 40.67808 -24.28474 15.58667 41.48599 -23.6133 14.867 35.35808 -26.27976 20.15354 36.83907 -26.10993 18.92332 35.56494 -24.65322 19.43432 31.82088 -25.76299 22.96668 33.34772 -25.82135 21.65153 33.60019 -26.16735 21.57029 33.81862 -26.19799 21.39656 30.00098 -25.10092 24.37901 28.16521 -24.2234 25.82904 42.5116 -11.83155 12.48766 42.73226 -8.5 12.267 43.52978 -14.97974 12.17822 43.46042 -10.73868 11.91831 43.44998 -8.5 11.88151 25.00221 -23.71715 28.81708 25.56431 -24.06285 28.34633 24.91963 -25.25879 28.41094 24.35755 -24.92551 28.88409 24.01464 -26.18176 27.98768 23.45932 -25.8641 28.44541 23.03536 -26.64204 27.16354 22.49516 -26.33683 27.59269 26.09738 -24.40085 27.87444 25.45615 -25.58372 27.93187 24.55221 -26.49254 27.5188 23.56774 -26.94415 26.71847 22.63171 -22.28871 30.88938 21.30316 -21.43041 32.19366 21.91586 -23.4586 30.97894 20.5592 -22.5691 32.27726 20.93585 -24.33494 30.57801 19.55293 -23.4027 31.89042 19.89741 -24.73378 29.77074 18.49201 -23.75919 31.11296 25.02502 -5.211453 38.66946 39.96835 -1.597521 48.91754 39.78326 -1.750751 48.91732 39.09951 -1.749935 47.98867 37.28578 -3.792854 48.91429 20.321 -17.22361 48.89376 20.31363 -17.229 48.89375 25.21312 -7.550062 40.85112 26.42446 -5.007457 39.84712 26.51995 -6.989776 41.65451 27.96581 -4.522791 40.77809 27.86103 -6.273131 42.25041 28.33931 -4.385945 40.96438 29.20182 -5.41858 42.62348 30.05849 -3.666316 41.65169 21.58794 -16.288 48.8953 22.12876 -15.88372 48.89595 23.52122 -13.32587 46.31114 24.32874 -14.20709 48.89861 25.86739 -12.31998 47.75348 26.12991 -12.7971 48.90079 28.27505 -11.03338 48.82331 29.23429 -10.30741 48.90455 31.80533 -6.143017 45.93681 32.52752 -7.636491 48.90853 33.50309 -4.686956 45.8059 36.12334 -4.732814 48.91289 40.18013 -0.6607427 47.64999 37.13234 -3.917164 48.91411 35.06326 -3.143657 45.35452 31.74537 -3.38675 42.66869 32.00024 -2.684512 42.12862 34.29893 -2.194664 43.41433 36.42025 -1.560854 44.57951 30.50781 -4.448124 42.76412 31.94927 -2.712534 42.11985 30.01369 -7.47435 45.74388 28.1743 -8.646679 45.23208 26.33453 -9.629818 44.41458 24.54173 -10.39845 43.31244 18.05608 -17.99964 48.89117 18.61536 -17.91648 48.65697 19.10745 -17.82328 48.89229 16.93794 -17.87894 48.88968 16.9227 -17.87493 48.88965 16.374 -17.93293 47.75283 20.16501 -17.33171 48.8935 19.26349 -17.62735 48.27955 20.28523 -17.24932 48.89346 17.15228 -18.0704 47.43105 17.92874 -17.96571 47.09296 15.6995 -18.102 45.9451 16.56401 -18.23658 45.70072 15.37486 -18.26217 44.77306 16.29105 -18.39168 44.58154 15.00784 -18.62808 42.78891 16.00427 -18.74177 42.69404 14.86388 -19.12288 40.80371 15.93 -19.20862 40.81766 14.87566 -19.40268 39.87412 15.96982 -19.46994 39.94401 15.0641 -20.06452 38.00352 16.20308 -20.08233 38.19723 15.48122 -20.8306 36.19602 16.64495 -20.78356 36.52388 15.81893 -21.29837 35.21965 16.98627 -21.20824 35.62583 16.58291 -22.15691 33.61438 17.7366 -21.98122 34.15801 17.57527 -23.05634 32.14132 18.68763 -22.78231 32.81995 17.41866 -18.09796 45.42586 17.19159 -18.22704 44.34751 16.97438 -18.52534 42.53029 16.95863 -18.92929 40.72782 17.02132 -19.15677 39.89052 17.29003 -19.69123 38.22321 17.74981 -20.30312 36.63535 18.09235 -20.67299 35.78669 18.82782 -21.34409 34.40433 19.74041 -22.03607 33.14823 18.64057 -17.62733 46.76592 18.1851 -17.69885 45.14569 17.98714 -17.78458 44.0942 17.8088 -18.00318 42.31612 17.81899 -18.3204 40.54561 17.8892 -18.50518 39.7208 18.16372 -18.94922 38.07761 18.61608 -19.46742 36.51229 18.94842 -19.78395 35.67479 19.65563 -20.36285 34.30801 20.52621 -20.96463 33.06149 -8.606752 -18 64.82243 -4.941845 -18 81.32876 -4.94293 -18 81.36627 -4.944545 -18 81.38504 -6.208713 -18 64.94049 -6.202927 -18 64.94076 -5.843776 -18 65.00698 -5.291138 -18 65.34287 -5.065467 -18 65.63421 -5.022187 -18 65.71516 -5.756924 -18 65.03841 -5.431131 -18 65.222 -5.359753 -18 65.27958 -4.908126 -18 66.05574 -4.892989 -18 66.15634 -4.885207 -18 66.32305 -4.961329 -18 75.89874 -6.67812 -14.5145 84.60655 -6.016474 -15.09071 84.76178 -5.846463 -15.22416 84.76947 -6.684701 -14.51991 84.60382 -6.28916 -15.32085 84.64747 -6.181163 -15.50836 84.62888 -5.615604 -16.33426 84.38745 -5.488101 -16.49032 84.30503 -4.915392 -17.07881 83.82039 -4.308651 -17.5104 83.07924 -4.208809 -17.56041 82.92838 -5.015244 -15.81059 84.6417 -4.839695 -15.92191 84.58002 -4.095039 -16.34626 84.17008 -3.374042 -16.66445 83.47891 -3.261853 -16.70182 83.33345 -2.770301 -16.7928 82.47401 -3.744517 -17.68127 82.05698 -3.591662 -17.67692 81.4567 -3.58313 -17.67465 81.31658 -2.531439 -16.77727 81.52765 -2.519122 -16.76916 81.30704 -3.599603 -17.67789 81.52666 -2.543476 -16.78072 81.63786 24.3754 -16.69701 81.87747 24.53792 -16.92782 81.57647 25.10989 -17.41772 82.04151 25.00979 -17.37973 81.57441 26.05241 -17.84552 82.16169 25.56832 -17.71877 81.57196 27.08924 -17.92879 82.22355 24.39229 -16.69523 82.05178 25.1643 -17.40374 82.31183 26.1521 -17.79771 82.49796 27.22776 -17.82613 82.58603 -35.85234 -16.88381 6.151394 -34.68392 -18.07139 6.049215 -33.37187 -18.76158 6.04558 -31.99665 -19.04425 6.12855 -31.89165 -19.04662 6.122441 -32.59168 -18.94231 5.962741 -33.31134 -18.72603 5.818956 -34.07868 -18.35572 5.684412 -31.75999 -19.70707 11.86667 -33.67697 -19.33012 11.88216 -13.38039 -16.2227 44.89272 -12.80784 -16.44921 44.6402 -12.64815 -16.49979 44.57107 -12.01918 -16.65198 44.30106 -11.35602 -16.73851 44.01609 -10.66818 -16.75429 43.7149 -14.71267 -15.94883 60.9162 -14.02965 -15.93895 60.84449 -14.00921 -16.15689 61.40715 -16.94309 -14.62308 60.68973 -16.76916 -14.84493 60.72603 -16.60384 -15.02524 60.76212 -16.27516 -15.31942 60.83494 -16.14708 -15.41584 60.8636 -15.78601 -15.64481 60.94598 -15.5482 -15.7665 61.00179 -15.13848 -15.88442 60.96232 -15.14919 -15.92777 61.09878 -15.13757 -15.93174 61.10168 -16.79534 -14.83763 60.81857 32.35033 -2.084603 42.05371 32.26369 -2.059827 42.01264 32.31565 -2.245983 42.06715 32.22891 -2.184384 42.01266 32.24253 -2.403115 42.08531 32.16038 -2.308162 42.01062 31.93946 -2.538724 41.99914 31.8893 -2.566882 41.99104 30.02621 -3.527543 41.54767 28.32783 -4.255874 40.88277 27.95831 -4.3948 40.70123 26.43149 -4.888127 39.7891 43.69724 -3.979992 60.8295 43.51114 -3.783246 60.03322 43.29826 -3.491966 59.05227 43.23526 -2.579695 57.37812 43.20189 -2.840097 57.71924 43.22627 -3.297238 58.54653 22.73941 -17.35062 52.58916 41.67761 -1.441781 51.16355 37.97235 -5.572081 52.98579 41.75863 -6.905205 61.65071 39.92561 -3.525788 52.23655 38.73382 -9.719602 62.23917 33.59878 -9.412514 53.46741 35.85129 -7.545596 53.39844 24.06598 -15.21301 50.371 26.44583 -14.06616 51.62995 28.85541 -12.70097 52.57553 31.25343 -11.14084 53.19153 25.06268 -17.48251 56.29931 25.70577 -17.50531 57.31375 26.66799 -17.52425 58.80411 27.93067 -17.51783 60.69013 28.80577 -17.4905 61.9394 28.75712 -17.0716 61.06563 29.65212 -17.44513 63.09668 32.17689 -14.84673 61.94411 40.83269 -11.36602 68.17037 36.96556 -14.57117 68.28879 35.52156 -12.38198 62.33753 33.77449 -16.95287 67.96208 31.88959 -17.23312 65.89598 34.32996 -1.882369 43.19229 23.58453 -16.81422 66.19082 23.04367 -16.34114 66.10297 22.3579 -16.08686 66.055 24.52074 -17.05934 75.06942 24.64 -17.68328 66.17568 24.29881 -17.40113 67.08985 25.14306 -17.84635 66.98529 25.41904 -17.7892 71.64163 25.51366 -17.75482 75.03036 24.47171 -17.18641 71.70516 24.63018 -17.68725 66.04625 26.93523 -17.96559 62.62568 26.68335 -17.86314 62.26164 26.63969 -17.95108 62.74164 26.30593 -17.80593 62.34035 26.27063 -17.9285 62.93368 25.82253 -17.71742 62.50516 25.58537 -17.871 63.47881 24.89993 -17.49508 63.07522 25.30355 -17.8397 63.81256 24.51525 -17.37591 63.45855 24.85542 -17.77272 64.63923 23.90175 -17.12534 64.45204 24.72603 -17.74352 65.06276 23.72391 -17.01791 64.97236 23.58281 -16.83742 66.03164 32.86815 -17.72695 68.65587 31.89743 -17.39268 66.32215 32.85891 -17.19164 67.17996 33.47824 -17.03544 67.71172 33.73074 -16.96585 67.92597 27.49728 -17.98008 62.78253 27.75724 -17.92873 62.57786 29.50518 -17.74779 64.08357 27.90397 -17.88369 62.45182 27.93028 -17.87425 62.42826 30.07472 -17.67018 64.59372 -2.508 -16.72661 75.9001 -3.57927 -17.66269 75.89949 -2.534682 -16.86368 66.36444 -3.579855 -17.70102 66.34604 -6.069957 -16.26064 62.22174 -6.087413 -16.2621 62.22159 -6.149001 -15.62129 61.7442 -3.268181 -15.38906 62.90318 -3.732769 -16.02286 62.97047 -3.782584 -15.47901 62.5478 -4.726723 -16.13518 62.45963 -4.58048 -15.60338 62.17646 -4.9888 -16.16178 62.37652 -5.184482 -15.68797 62.01141 -2.575958 -15.85208 64.19327 -3.296923 -15.96586 63.32043 -3.511409 -15.99468 63.13616 -2.636093 -15.26263 63.52154 -2.270518 -15.17614 64.02685 -2.433928 -15.8244 64.44187 -2.047474 -15.72152 65.5116 -1.703188 -14.98434 65.42945 -1.880116 -15.05992 64.8235 -1.992434 -15.69497 65.83417 -5.082021 -15.13895 61.26633 -6.183866 -15.25854 61.16044 -6.18816 -15.21385 61.03846 -1.060977 -14.42806 65.24709 -0.2418137 -14.2053 65.06136 -1.262101 -14.50442 64.54533 -0.4684032 -14.28943 64.24247 -1.709479 -14.62181 63.62121 -0.9794574 -14.41832 63.16051 -2.130254 -14.70915 63.03394 -1.463775 -14.514 62.47031 -2.860008 -14.83683 62.31362 -2.308293 -14.65378 61.61989 -3.455274 -14.92769 61.89832 -3.000156 -14.75344 61.12668 -4.380414 -15.05339 61.46216 -4.07962 -14.89198 60.60414 -4.90136 -14.98693 60.3656 -6.197099 -15.12084 60.22798 6.054425 -14.69024 61.14408 6.036028 -15.25113 61.92988 5.154184 -15.21756 62.01371 1.54536 -14.84044 66.20567 1.982141 -15.69283 65.81871 1.662931 -14.91948 65.34315 2.02453 -15.70934 65.56752 1.845862 -14.97026 64.7593 2.389467 -15.77349 64.52231 2.241317 -15.03453 63.98415 2.503071 -15.78535 64.31552 2.607589 -15.07406 63.49196 3.190502 -15.83318 63.44575 3.239372 -15.12307 62.88763 3.448044 -15.84565 63.21872 3.751062 -15.15343 62.54081 3.702184 -15.85644 63.02901 4.552798 -15.19234 62.17466 4.693521 -15.89071 62.53072 4.914302 -15.89745 62.46213 6.013778 -15.92955 62.31046 0.8001773 -14.27591 66.14403 -0.121674 -14.11223 66.10954 0.02662521 -14.20141 64.92322 0.9332807 -14.3558 65.13827 0.2715115 -14.25788 64.11756 1.1449 -14.40702 64.45677 0.81068 -14.32786 63.0458 1.605584 -14.4717 63.55141 1.314345 -14.36987 62.36469 2.033738 -14.51137 62.97639 2.186598 -14.42085 61.52829 2.773572 -14.56048 62.27029 2.894176 -14.45226 61.04797 3.373294 -14.59091 61.86484 4.003359 -14.49357 60.53895 4.31336 -14.63009 61.43589 4.835855 -14.52187 60.3124 5.018853 -14.65569 61.24611 6.058608 -14.56268 60.18694 2.521587 -16.86368 66.3645 2.494993 -16.72644 76.59474 3.56629 -17.66264 76.59513 3.566759 -17.70102 66.34607 18.44496 -17.71919 83.64351 19.47498 -16.92934 83.63747 18.48286 -17.74645 76.02078 18.61965 -17.79634 71.01512 19.48535 -17.02865 76.05368 19.55612 -17.21302 71.08366 19.76644 -17.44478 66.22988 19.3731 -17.68328 66.17565 18.94808 -17.85783 66.11705 2.562165 -16.88396 65.88869 3.59549 -17.70665 66.01335 2.602089 -16.89276 65.67452 2.926462 -16.9268 64.78799 3.02532 -16.93306 64.61334 3.61712 -16.95827 63.88074 3.837413 -16.96482 63.68998 4.054421 -16.97048 63.53075 4.898915 -16.98843 63.11397 5.08669 -16.99195 63.05704 6.020448 -17.00869 62.93452 3.623512 -17.70908 65.86373 3.850251 -17.71849 65.24503 3.91929 -17.72022 65.12313 4.333195 -17.72716 64.61087 4.487699 -17.72896 64.47703 4.640172 -17.73052 64.36511 5.23591 -17.73544 64.07093 5.368796 -17.73641 64.03057 6.031231 -17.74099 63.94332 16.40398 -17.66121 63.08983 15.14593 -16.58948 62.09192 16.24676 -16.72134 62.02931 15.22962 -17.34225 62.75645 15.33973 -17.83079 63.63079 11.14738 -16.184 62.24337 11.1864 -17.13964 62.89583 11.24412 -17.77659 63.86093 16.62523 -16.78535 62.03632 16.71474 -16.8 62.04289 16.68815 -17.67918 63.09556 16.75489 -17.68328 63.10049 19.38268 -17.68724 66.04785 20.42843 -16.81418 66.19181 19.37878 -17.69806 65.86931 19.36111 -17.70918 65.67164 19.1969 -17.7393 65.00982 19.13345 -17.7446 64.85494 18.79529 -17.75727 64.27664 18.71434 -17.7581 64.17284 18.24332 -17.75396 63.70946 18.14067 -17.75151 63.63208 17.57111 -17.73058 63.31061 17.40479 -17.72243 63.24595 20.4241 -16.85301 65.93911 20.39976 -16.89309 65.65953 20.16709 -17.0025 64.72684 20.07725 -17.0219 64.5095 19.60119 -17.06834 63.70017 19.48771 -17.07142 63.55498 18.82791 -17.05619 62.90471 18.68384 -17.04721 62.7955 17.87991 -16.9707 62.33913 17.64353 -16.94109 62.24699 21.58053 -16.10107 66.05926 20.86751 -16.40584 66.11638 -16.63084 -15.04458 60.94364 -16.01963 -15.65245 61.38731 -15.26808 -16.19693 61.87516 -13.7886 -16.25707 61.59187 -14.93441 -16.4584 62.20584 -13.55635 -16.33463 61.71632 -14.59977 -16.67472 62.43129 -13.09873 -16.4419 61.8725 -13.96099 -17.00156 62.71764 -12.72026 -16.50053 61.95545 -13.44243 -17.20376 62.8722 -12.04945 -16.55756 62.04814 -12.53254 -17.45096 63.05057 -11.68396 -16.56824 62.07984 -12.03925 -17.53539 63.11564 -10.8477 -16.54721 62.11933 -10.88838 -17.32145 62.78811 -10.91412 -17.61167 63.21135 -10.9425 -17.82527 63.67782 43.1619 -24.53051 12.68083 42.97471 -23.66224 13.51863 43.83063 -23.57611 12.17183 43.53645 -22.85969 13.01726 44.15087 -22.96518 11.91285 44.5881 -21.76307 11.52235 44.76122 -20.93496 11.3313 44.84476 -19.68773 11.14791 43.80468 -22.34396 12.76206 44.16858 -21.32601 12.37712 44.31015 -20.62296 12.18892 44.37186 -19.56203 12.00933 42.12487 -25.12884 14.01406 41.90972 -24.3846 14.54268 41.07093 -25.10574 15.29545 42.11043 -25.7733 13.33282 39.63077 -26.09487 16.57902 38.12981 -26.81048 17.89601 37.02583 -27.14748 18.84733 35.45291 -27.37743 20.17551 33.82326 -27.3406 21.51991 33.59287 -27.31504 21.70772 31.72614 -26.94247 23.2147 29.83665 -26.30009 24.73099 27.95022 -25.43456 26.2735 41.24897 -25.89731 14.79057 39.73411 -26.96557 16.12249 38.14257 -27.75675 17.49785 36.96646 -28.14228 18.49519 35.28849 -28.42902 19.89005 33.55391 -28.43636 21.30183 33.30933 -28.41602 21.49891 31.33501 -28.07832 23.07846 29.35025 -27.46107 24.66425 27.38075 -26.61199 26.27261 41.19414 -26.57914 14.12328 39.60058 -27.70758 15.4831 37.91653 -28.55286 16.89018 36.66833 -28.97084 17.91061 34.887 -29.29264 19.33568 33.05011 -29.32447 20.77433 32.79168 -29.30683 20.97486 30.71104 -28.98605 22.58011 28.62766 -28.37889 24.19057 26.56502 -27.53191 25.82652 41.86779 -26.25497 12.56552 40.91199 -27.08204 13.36127 39.24469 -28.24032 14.73028 37.47819 -29.10554 16.14417 36.16845 -29.53034 17.16614 34.30262 -29.85175 18.58719 32.38579 -29.87458 20.01482 32.11675 -29.85522 20.21336 29.95555 -29.51825 21.80056 27.79644 -28.89152 23.39357 25.65808 -28.01946 25.02004 26.38546 -17.77924 59.03084 26.83276 -17.86228 61.39475 26.71791 -17.85316 61.34732 24.57769 -17.94086 58.98142 26.04675 -17.94004 59.2935 29.73302 -17.64197 63.8708 28.12782 -17.81811 62.18907 27.90976 -17.83831 61.98931 27.84463 -17.84402 61.93861 27.46038 -17.86941 61.6919 27.33487 -17.87344 61.62479 27.02443 -17.87205 61.47668 26.871 -17.86481 61.41064 29.74676 -17.64023 63.88518 31.97185 -17.3075 66.18857 30.22471 -17.57741 64.38479 33.73253 -16.96098 67.92032 33.48697 -17.01475 67.68658 32.89035 -17.13776 67.10769 19.78063 -17.66497 49.23799 23.08342 -17.775 54.15614 19.17441 -17.92807 49.65564 22.55963 -18.00682 54.52237 18.5347 -17.99206 50.09975 22.00349 -18.06624 54.9089 22.11491 -17.96288 56.08022 17.9251 -17.86069 50.52602 -8.549957 -17.80619 63.76315 -8.464771 -16.40272 62.17437 -8.5005 -17.2498 62.84074 -6.15926 -17.78726 63.83201 -6.11682 -17.17922 62.88074 -3.607701 -17.70697 66.01358 -2.573504 -16.8851 65.89871 -3.64579 -17.71088 65.81562 -3.898046 -17.72589 65.16213 -3.988751 -17.72989 65.011 -4.443154 -17.74615 64.48288 -4.57711 -17.75023 64.372 -4.71494 -17.7542 64.27254 -5.329425 -17.76986 63.9683 -5.490316 -17.77353 63.91951 -6.148705 -17.78706 63.832 -2.626767 -16.89923 65.62179 -2.979331 -16.95365 64.71018 -3.105923 -16.9682 64.50002 -3.738676 -17.02757 63.76844 -3.924788 -17.04251 63.61554 -4.116109 -17.05707 63.47867 -4.967516 -17.11475 63.06238 -5.190222 -17.12832 62.99622 -6.10218 -17.17848 62.88064 26.46297 -17.76782 61.81138 26.57887 -17.82752 61.34946 26.576 -17.80566 61.60562 26.61361 -17.83404 61.34853 26.6658 -17.84368 61.3477 26.66129 -17.8342 61.45039 26.42253 -17.75428 61.88498 26.16498 -17.74402 61.38344 26.44029 -17.80077 61.3561 25.72829 -17.6442 61.46628 25.74155 -17.64741 61.46303 25.74526 -17.64519 61.47684 25.98279 -17.70384 61.41201 26.02921 -17.67632 61.65166 26.26754 -17.78225 62.28804 26.02656 -17.67078 61.95055 23.23162 -16.49782 65.95251 23.32318 -16.66204 65.05377 23.50843 -16.80507 64.39585 23.88261 -17.0033 63.62482 24.24012 -17.15237 63.13325 24.83612 -17.35774 62.56552 25.28048 -17.48736 62.27148 26.50924 -17.77522 61.93774 26.80736 -17.87041 62.20467 26.80212 -17.87211 62.2159 26.70916 -17.84811 62.17792 26.78848 -17.87303 62.22931 26.80857 -17.86807 62.19316 26.79741 -17.85967 62.16157 26.73529 -17.83693 62.09454 26.74917 -17.87091 62.24731 25.04249 -17.4626 61.70149 24.50105 -17.296 61.99184 23.75486 -17.02536 62.59201 23.29356 -16.82481 63.13547 22.79247 -16.55382 64.01434 22.52765 -16.35579 64.78138 22.3651 -16.12642 65.84643 16.85782 -16.3434 61.54592 16.98496 -16.07236 60.86203 17.93899 -16.2435 61.0667 19.45386 -16.6505 62.69406 19.01016 -16.62809 62.34287 18.22174 -16.56072 61.91462 17.68327 -16.4999 61.73532 20.85163 -16.49486 65.41286 20.7268 -16.56432 64.75707 20.39895 -16.62923 63.91967 20.06893 -16.65237 63.38224 18.54795 -16.32976 61.2838 19.43445 -16.42357 61.78305 19.93253 -16.45407 62.18432 20.62615 -16.45534 62.9622 21.00306 -16.42221 63.56705 21.38733 -16.32985 64.51115 21.54382 -16.23029 65.25492 22.29114 -16.24534 65.13102 22.09366 -16.36676 64.28424 21.64019 -16.4792 63.21641 21.20741 -16.51994 62.5336 20.42166 -16.52018 61.65147 19.86018 -16.48475 61.19121 18.85908 -16.3733 60.60631 18.16718 -16.26933 60.34181 17.066 -16.06991 60.11989 16.7401 -16.00446 60.09713 16.69784 -16.01492 60.83719 16.60525 -16.28931 61.51963 16.41113 -15.93609 60.09185 16.39651 -16.00594 61.02326 16.34909 -16.23247 61.50662 16.29681 -16.4822 61.82067 12.31466 -15.74617 61.83424 8.407433 -15.28921 61.84564 8.446093 -14.79704 61.07712 12.40614 -15.1756 60.13368 8.453962 -14.69687 60.16925 12.39232 -15.26179 61.05247 -10.07696 -16.01572 61.74552 -10.11835 -15.60814 61.04097 -10.1279 -15.51404 60.23148 26.49706 -17.7722 61.93008 27.77071 -17.88846 62.32262 27.28394 -17.90797 62.20622 27.3943 -17.90834 62.21977 27.41021 -17.91761 62.26909 27.71906 -17.89271 62.30023 26.83485 -17.86825 62.17473 26.86936 -17.87467 62.18141 27.00712 -17.89196 62.18798 26.57073 -17.79079 61.97629 26.71286 -17.82999 62.07578 27.35461 -17.93034 62.32399 27.2731 -17.94484 62.39589 27.12191 -17.96103 62.50951 42.04496 0.0090245 52.25225 42.84017 0.282193 53.39157 42.16152 0.02427983 52.41926 40.59029 0.2682285 62.38774 41.14378 0.2642874 59.57926 41.22208 0.2639759 59.26297 42.73371 0.2740778 53.77291 40.4084 0.2740623 64.86296 40.4084 0.2741799 64.95001 -0.1822794 -13.62311 83.11024 -0.1547312 -13.62069 83.11404 -0.2573706 -12.88226 84.3165 -0.23627 -12.8789 84.31967 -0.350394 -11.72417 85.12875 -0.3149782 -11.71902 85.1314 -0.2099534 -13.62597 83.10806 -0.2786484 -12.88628 84.31378 -0.3859013 -11.7314 85.12644 1.940542 -14.63032 86.55998 1.84041 -14.92515 86.11347 1.821345 -15.20555 85.64728 1.782543 -15.10423 85.54321 1.519974 -14.59632 84.94626 1.898693 -14.47098 86.49397 1.614424 -13.65781 86.11835 1.250123 -12.9553 85.7641 0.9088857 -12.47809 85.52033 0.5462636 -12.10208 85.33363 0.3505901 -11.94754 85.26005 0.07667034 -11.7898 85.18637 -0.1095907 -11.72901 85.1539 1.795495 -14.79655 86.03005 1.49294 -14.15067 85.55718 1.112865 -13.61709 85.1122 0.767907 -13.27971 84.80593 0.4198866 -13.04223 84.57131 0.2444434 -12.95829 84.47898 0.02161848 -12.88917 84.38697 -0.1094717 -12.87258 84.3469 1.186392 -14.17991 84.36412 0.8778833 -13.91971 83.93923 0.5562933 -13.73942 83.58323 0.3867462 -13.67692 83.42717 0.1564816 -13.6268 83.2519 0.006062626 -13.61558 83.16639 -0.8363823 -11.79788 85.12675 -0.601933 -12.93342 84.31494 -0.4516677 -13.66122 83.11028 -1.569243 -12.01961 85.12779 -2.125699 -12.29598 85.12911 -2.747746 -12.74795 85.13126 -1.128588 -13.09079 84.31878 -1.52953 -13.28728 84.3236 -1.979521 -13.6094 84.33153 -0.8455203 -13.7789 83.11773 -1.145479 -13.92588 83.12707 -1.482338 -14.16692 83.14248 35.04648 -17.99982 72.69026 35.27907 -17.99065 72.59275 35.85982 -17.62383 71.36682 36.73428 -17.58684 71.93637 36.63299 -16.57619 70.3984 38.15291 -16.39297 71.33394 34.26055 -17.67746 70.08004 35.11186 -16.76929 69.23845 35.04111 -17.99992 72.70236 35.24143 -17.99586 72.67939 36.53332 -17.8168 72.49932 37.96208 -17.26937 72.28353 35.03574 -17.99996 72.71447 35.20368 -17.99809 72.76613 36.30419 -17.91568 73.08914 37.54837 -17.67203 73.45524 38.74948 -16.16127 71.53462 38.46001 -17.38541 73.70526 38.72378 -16.99557 72.51048 38.83288 -17.23975 73.78878 39.80029 -16.47509 72.72875 39.74189 -16.80872 73.94641 40.5515 -16.00482 72.80679 40.63018 -16.27012 74.03368 41.50496 -15.25082 72.80339 41.74699 -15.38854 74.03285 39.59627 -15.73163 71.7272 40.19022 -15.35009 71.79553 40.94871 -14.74604 71.79103 41.43854 -14.26875 71.72009 42.11624 -14.64931 72.72489 42.05567 -13.53388 71.52302 42.87954 -13.71624 72.50513 42.07991 -15.07057 74.00308 42.45399 -14.6755 73.94921 43.3211 -13.55859 73.71208 43.93963 -12.19812 72.52133 45.00828 -8.031661 72.63027 45.00827 -8.0335 72.6243 45.0082 -8.05296 72.63486 45.00816 -8.056031 72.62489 44.99117 -8.585703 72.74562 44.98701 -8.617725 72.63317 44.92024 -9.324405 72.88816 44.89914 -9.390848 72.62766 44.53322 -11.04575 73.19532 44.41971 -11.16861 72.56589 44.24708 -11.82695 73.33678 44.14906 -12.05551 73.38006 45.00825 -8.035341 72.61834 45.00809 -8.059102 72.61491 44.97829 -8.649432 72.5209 44.85418 -9.453543 72.36927 44.17688 -11.24262 71.96612 43.50461 -12.21967 71.73909 44.72028 -8.574408 70.71717 44.68849 -9.944083 72.11431 42.12168 -13.15964 71.27186 42.37005 -11.81234 70.23845 43.7699 -11.02691 71.02709 42.61118 -10.60368 69.09731 43.88932 -9.730982 69.79393 37.53981 -15.58876 70.17387 40.78607 -12.93717 70.13732 44.35823 -11.08358 83.14398 44.42913 -11.35389 82.21305 44.84487 -9.800741 81.87351 44.83164 -9.62968 82.35669 45.00831 -8.022361 81.41491 45.00831 -8.020125 81.42083 45.0083 -8.017889 81.42675 44.73259 -9.447835 82.82575 43.99811 -10.73603 83.97718 43.41993 -11.39961 84.47941 43.9818 -11.83463 83.50149 42.29405 -12.37817 85.00708 42.82661 -12.6982 84.53032 43.23526 -12.94376 83.90901 43.38402 -13.03316 83.55706 44.24743 -11.82611 82.29306 44.12258 -12.11469 82.334 43.57977 -13.15079 82.409 41.99632 -14.8303 83.55706 42.15963 -14.98992 82.409 41.53126 -14.37573 84.53032 40.83525 -13.69542 85.18064 42.07939 -15.07109 82.40742 42.02363 -15.12641 82.40446 41.79183 -15.00668 83.5959 41.25049 -14.55338 84.5904 40.48908 -13.84142 85.2236 41.90438 -15.24186 82.39291 41.60512 -15.16073 83.61547 40.99308 -14.70993 84.62193 40.17644 -13.96914 85.2344 41.50212 -15.60465 82.29679 40.91424 -15.68143 83.55722 40.03312 -15.24985 84.54594 39.04871 -14.40293 85.04978 38.83567 -17.23859 81.49294 40.28271 -16.49594 81.88973 39.74575 -16.48409 83.10267 39.00441 -15.97621 84.07846 38.20363 -15.07161 84.6263 38.71987 -17.28571 81.46499 38.27646 -17.17852 82.63825 37.71507 -16.59972 83.60494 37.13455 -15.65121 84.19484 35.92736 -16.97617 83.02805 35.75028 -17.38291 82.48495 35.95975 -17.61757 82.10992 35.5219 -17.73388 81.77867 35.19186 -17.97052 80.8235 35.23271 -17.98183 80.7279 35.02308 -17.99993 80.36367 35.02055 -17.99988 80.36988 35.02561 -17.99996 80.35746 35.02814 -17.99997 80.35125 35.03067 -17.99998 80.34504 35.27359 -17.98952 80.63194 35.31443 -17.99357 80.53575 35.3552 -17.99398 80.43946 36.17338 -17.78019 81.70064 36.38547 -17.86646 81.26802 36.59038 -17.87406 80.82356 36.08258 -16.51795 83.46643 36.41792 -17.06523 83.02908 36.77331 -17.45989 82.46234 37.12492 -17.67548 81.80419 37.44918 -17.69754 81.09877 36.33447 -15.62308 84.01192 36.75595 -16.46495 83.65571 37.22315 -17.10366 83.03357 37.68347 -17.4673 82.21556 38.08509 -17.51491 81.29376 30.03569 -15.83939 83.83168 34.55898 -15.83939 83.54092 29.83834 -16.97488 83.09909 29.54297 -17.73358 82.00269 34.66091 -16.97488 82.78909 34.81348 -17.73358 81.6639 32.28283 -15.83939 83.46056 32.23416 -16.97488 82.70342 32.16131 -17.73358 81.57028 2.534059 -14.13112 0.376586 2.570221 -14.13112 0.1949306 2.673194 -14.13112 0.0409727 2.827276 -14.13112 -0.06181311 3.008975 -14.13112 -0.09775519 34.3299 -30.00265 17.92329 24.56618 -29.18305 21.47299 19.42585 -24.93422 28.97465 23.57031 -17.72076 59.00402 14.17341 -15.58395 59.47192 9.794281 -14.88432 59.67037 1.786134 -15.32861 52.27017 -20.89557 -19.98082 12.51873 41.2237 -26.92485 10.5714 36.77192 -30.02786 10.41557 39.02755 -28.68 10.49069 24.92302 -31.86158 8.183105 29.75404 -31.95034 8.29618 5.861208 -25.94569 9.636059 -2.860336 -22.99702 9.364696 -21.15818 -19.81008 8.765906 -11.57289 -20.97378 9.071703 -20.18539 -18.88029 28.19099 -10.51933 -18.90727 28.46138 -10.36325 -17.60773 36.43695 -10.35182 -17.06866 40.43827 -10.59791 -16.16302 52.37734 -2.195471 -15.46571 52.32373 5.767182 -15.42995 52.18724 14.21896 -16.7208 51.90044 14.40069 -19.10135 40.4385 14.3228 -18.09668 44.26433 14.72481 -23.47018 28.97491 14.49712 -20.38905 36.61437 19.715 -28.06869 21.4088 29.55693 -30.74043 17.80438 31.9583 -30.52035 17.86069 38.99681 -28.45665 14.31244 1.902045 -16.20676 44.48109 -2.023294 -16.77758 40.5406 -2.04868 -16.19869 44.48416 -10.38735 -16.67228 44.43577 -6.088829 -17.50838 36.52088 -2.669334 -22.72907 13.17107 9.868777 -15.86078 52.06632 5.8652 -16.47343 44.44873 1.929724 -16.8945 40.56511 -2.030217 -17.55411 36.59271 -6.230774 -19.08926 28.59207 -10.83679 -20.15547 20.57957 -20.46909 -19.65554 20.24902 -11.29612 -20.94121 12.85249 -6.919521 -21.72381 13.01463 -6.513784 -20.65048 20.73984 -2.353266 -21.35221 20.89179 -2.135908 -19.44936 28.7122 1.892236 -20.03691 28.81609 1.937164 -17.8082 36.64514 5.937801 -18.33374 36.67086 5.904551 -17.27736 40.56128 29.42971 -29.60733 21.54808 27.00131 -29.50016 21.50834 24.70273 -30.43503 17.70535 24.89711 -31.84925 10.09981 27.32348 -32.02724 10.1573 29.73259 -31.96813 10.21693 32.116 -31.63789 10.27939 34.46525 -31.00248 10.34537 19.94961 -30.37707 13.80949 24.81591 -31.36905 13.91589 36.72949 -29.76373 14.23245 34.41167 -30.69452 14.15935 32.05239 -31.28474 14.09215 29.66065 -31.57009 14.02984 27.24548 -31.58629 13.97142 19.84314 -29.38097 17.61559 14.95476 -26.56361 21.34226 15.054 -27.87281 17.52449 15.13393 -28.87985 13.70263 20.02636 -30.91815 9.988451 20.05108 -30.95929 8.074886 15.18789 -29.44712 9.87731 10.23499 -22.05909 28.95251 5.978571 -23.505 21.15572 5.956581 -24.61431 17.30104 5.918068 -25.46952 13.45933 1.769482 -22.29318 21.03166 5.980283 -20.90071 28.89808 10.09077 -19.18557 36.66254 10.02381 -17.99535 40.52119 9.9649 -17.07866 44.37871 44.75586 -0.843139 13.64019 42.74718 -0.7280515 16.27799 43.93702 -0.4397252 15.66457 44.04092 -1.527383 14.372 42.78541 -0.902197 16.04643 42.98387 -1.957977 14.83253 43.14828 -3.112498 13.80962 44.12552 -2.737332 13.2794 43.17446 -3.332237 13.64508 44.13887 -2.969351 13.10337 43.29308 -4.533118 12.8932 44.19898 -4.244363 12.29824 43.37873 -5.793116 12.34357 44.24198 -5.591269 11.70888 43.43385 -7.201682 11.98649 44.2695 -7.103428 11.32566 44.27753 -8.5 11.21295 44.77886 -2.174349 12.48373 44.78247 -2.429461 12.29745 44.79867 -3.830516 11.44554 44.81021 -5.30925 10.8221 44.81756 -6.968297 10.41681 44.8197 -8.5 10.29761 44.82109 -10.79842 10.33756 44.28271 -10.76394 11.24995 44.83024 -15.13698 10.61883 44.31707 -15.04695 11.51168 20.12081 -14.13842 -0.05244028 19.96275 -14.13112 -0.0772354 20.12081 -14.28923 -0.07706356 20.569 -8.810261 29.3702 20.58905 -8.810724 29.41101 20.63478 -9.910614 29.39923 20.48959 -8.809633 29.26267 20.53996 -9.907855 29.24234 20.76139 -12.24966 29.08592 21.07653 -13.855 28.81253 21.222 -14.35643 28.67844 21.66886 -15.45381 28.24999 21.94077 -15.92429 27.98122 22.56472 -16.69317 27.3511 20.84468 -12.26163 29.2603 21.15292 -13.88204 28.99569 21.29734 -14.39048 28.86286 21.74659 -15.50715 28.43212 22.02261 -15.98662 28.15923 22.65847 -16.76715 27.51721 36.0192 -16.1028 -0.05780196 20.11702 -16.10665 -0.07831341 42.32205 -16.10188 2.539199 40.97888 -16.1028 1.444422 39.45019 -16.1028 0.6284435 37.76846 -16.1028 0.1164899 44.97952 -13.72615 8.867868 44.98188 -13.53729 8.87748 44.96741 -14.43717 8.728493 44.97386 -14.72078 8.619923 44.96217 -14.93175 8.430149 44.94514 -15.065 8.214112 44.92118 -15.12484 7.97272 26.18729 -18.66775 23.73534 26.66427 -18.76922 23.2613 27.91011 -18.82332 22.01546 29.11556 -18.58658 20.81001 30.30383 -18.05443 19.62174 31.38591 -17.26675 18.53965 32.38264 -16.20836 17.54291 33.21936 -14.95855 16.70619 33.91219 -13.49323 16.01336 34.40922 -11.92219 15.51633 34.72002 -10.21516 15.20553 26.2949 -18.7458 23.86325 26.77467 -18.84812 23.38471 29.24479 -18.66407 20.91458 28.03008 -18.90263 22.12929 31.53258 -17.33411 18.62678 30.44219 -18.12784 19.71718 33.38013 -15.00817 16.77924 32.53697 -16.26758 17.62239 34.57912 -11.94848 15.58024 34.07827 -13.53159 16.08109 34.89231 -10.22834 15.26705 25.85975 -18.57846 24.06269 25.51667 -18.47925 24.37932 25.96654 -18.65622 24.19142 25.63092 -18.55579 24.51565 24.29662 -17.97995 25.61324 23.22286 -17.27173 26.69954 24.40128 -18.05756 25.75938 23.31822 -17.34816 26.85528 23.27963 -17.31692 26.89137 23.18238 -17.24082 26.73325 23.01467 -17.10242 26.90305 23.11035 -17.17811 27.06274 44.77167 -15.19906 7.10982 44.37722 -15.48373 5.732123 43.67279 -15.838 4.269625 43.23063 -15.97881 3.601225 42.38498 -2.06537 15.00969 39.09371 -7.744481 13.98615 39.28273 -5.538837 14.33952 39.19499 -6.263092 14.17552 41.36745 -6.197128 13.24727 39.13192 -6.998589 14.0576 39.81265 -3.018727 15.33044 39.63864 -3.669376 15.00498 41.75751 -4.014317 13.92288 39.48649 -4.347151 14.72046 39.35675 -5.05165 14.4779 40.15383 -1.987384 15.96882 40.00817 -2.395873 15.69623 40.63434 -0.879701 16.86847 40.38531 -1.413837 16.40213 17.75 -8 0 -19.75012 9.282606 52.22771 -18.76643 10.45214 51.53892 -20.03813 8 52.42937 -17.03813 11 50.32875 -20.03813 7.187853 52.42937 -22.0915 2.720362 53.86716 -21.22588 5.25289 53.26105 -19.33343 -5 79.81603 -12.53002 -9.820047 83.83748 -12.78049 -9.607796 83.84954 -13.5013 -8.499462 83.83413 -13.50073 -8.133553 83.83418 -13.67147 -8.055504 83.81962 -13.13436 -8.499328 83.85126 -13.02591 -8.773854 83.85263 -13 -8.998924 83.85272 -13.15502 -8.465194 83.85081 -13.37805 -8.216938 83.84204 -12.94338 -9.322487 83.85255 -15.12788 -8 83.51877 -13.99998 -8 83.7797 -15.73451 -7.999833 83.29296 -17.0709 -7.996808 82.54124 -17.66153 -7.996282 82.06729 -18.17384 -7.99605 81.5585 -18.56849 -7.999944 81.09384 -18.95099 -7.845929 80.525 -19.08877 -7.667719 80.2914 -19.19069 -7.425 80.10408 -19.24919 -7.150698 79.99002 -19.26909 -6.85 79.95001 -19.26909 -5.5 79.95001 -19.28614 -5.238478 79.9152 -19.9916 -4.5 76.85272 -19.67003 -4.5 78.95 -19.49192 -4.633975 79.45001 -19.9916 -4.5 67.6 -19.9916 0 67.6 44.9793 -8.346832 8.870056 44.99984 -8 8.946176 43.17281 -9.5 -0.5407877 43.56593 -8 -0.624448 44.40542 -8 3.539999 40.63164 -11 0 42.09878 -10.59808 -0.3122239 44.00985 -9.5 3.611209 44.9972 -8 8.69508 44.79846 -8 6.07959 44.79636 -8 6.062592 41.66331 -0.2351384 -9.683796 41.66273 -0.1999999 -9.687094 41.89669 -0.1999999 -9.277047 40.58488 -0.2623777 -10.64873 40.58559 -0.1999999 -10.65144 41.18207 -0.1999999 -10.23606 39.18235 -0.275 -10.99656 39.18214 -0.1999999 -10.99909 40.14959 -0.1999999 -10.8397 40.55559 -10.98903 -0.4911733 42.0149 -10.57828 -0.783462 43.0877 -9.482539 -0.9628561 43.20824 -7.817915 -2.31229 43.38127 -7.952596 -1.492497 43.48985 -7.992021 -0.9818416 40.27199 -10.74963 -2.333529 41.70443 -10.31564 -2.53943 40.19071 -10.61914 -2.869472 41.42717 -9.7895 -4.160581 40.0151 -10.2274 -4.049726 39.77973 -9.404109 -5.706378 41.17753 -8.983589 -5.714834 39.70476 -9.044546 -6.260687 40.97784 -7.962766 -7.077631 39.58735 -8.345894 -7.165617 39.43231 -7.034022 -8.4571 40.82122 -6.707039 -8.280981 39.37992 -6.424726 -8.928768 40.711 -5.280932 -9.255839 42.77357 -9.248149 -2.531697 42.49438 -8.777339 -3.974628 42.95611 -7.43811 -3.53728 42.2444 -8.055422 -5.352837 42.72776 -6.839351 -4.706092 42.04574 -7.140457 -6.55667 42.5433 -6.069741 -5.723596 41.89114 -6.01457 -7.615592 42.39635 -5.115653 -6.613751 41.78336 -4.735718 -8.47027 42.29058 -4.028229 -7.327242 41.71383 -3.311891 -9.115478 42.21952 -2.816476 -7.861939 41.6759 -1.80761 -9.521874 42.17906 -1.536777 -8.196611 42.16362 -0.1999999 -8.332178 39.31948 -5.538814 -9.503765 39.24294 -3.872655 -10.29575 40.63914 -3.693221 -9.9942 39.19903 -2.113069 -10.79514 40.59952 -2.015765 -10.46045 44.79636 8 6.062592 44.99994 8 9.003568 44.99994 0 9.003568 44.99992 8 8.983509 44.40542 8 3.539999 43.56593 8 -0.624448 43.50486 7.994863 -0.9113237 43.38129 7.952606 -1.492405 43.22221 7.832268 -2.245628 42.67709 -4.076298 -4.977373 42.16349 0 -8.333323 42.16419 0.3307868 -8.327054 42.18186 1.664896 -8.172566 42.2251 2.940395 -7.817756 42.2994 4.141479 -7.264505 42.3972 5.122584 -6.608313 42.54447 6.075864 -5.716789 42.73583 6.866046 -4.663351 42.96564 7.457124 -3.489964 36.025 -11 0 36.025 -3.062392 -10.56512 36.025 -10.61905 -2.869793 36.025 -9.044273 -6.26108 36.025 -6.424487 -8.928941 36.025 -0.1999999 -10.99909 36.025 11 11 36.025 11 0 36.025 10.46162 -3.399187 36.025 8.899188 -6.465638 36.025 6.465638 -8.899188 36.025 3.399187 -10.46162 36.025 0 -11 -18.5 10.82065 1.978268 -21.175 10.82065 1.978268 -21.175 11 3 26.375 11 3 26.375 10.82065 1.978268 20.75 10.82065 1.978268 20.05867 10.76414 1.833999 18.63004 10.08733 0.8452252 -15.90685 9.5 0.401924 18.72146 10.16809 0.9264994 -16.47273 10.16915 0.927616 19.45 10.59808 1.5 -17.2 10.59808 1.5 -17.80663 10.76378 1.83317 17.85858 8.799146 0.1083972 17.75 8 0 -15.5 8 0 18.15685 9.5 0.401924 -15.60911 8.801056 0.1089262 42.21895 -0.1999999 48.65937 42.28141 -0.1999999 47.96597 39.85355 -0.1999999 46.4688 40.38549 -0.1999999 46.64968 41.45685 -0.1999999 47.3726 27.45289 -0.1999999 40.14933 27.83639 0 40.4205 29.96534 0 41.75547 25.95978 0 38.96857 24.96159 -0.1999999 38.03841 24.96588 0 38.0427 24.96159 0 38.03841 24.33072 -0.1999999 37.33955 24.33072 0 37.33955 24.64615 2.40028e-5 37.68898 22.51754 0 33.97518 22.51754 -0.1999999 33.97518 22.04279 0 32.2047 21.74617 -0.1999999 30.23132 21.74617 0 30.23132 22.53558 0 34.02817 22.82957 0 34.80249 23.8754 -0.1999999 36.73232 23.53734 0 36.20714 44.07508 -0.1999999 15.92404 44.07508 -1.2299e-5 15.92404 43.29472 0 16.14709 45 0 12.77053 44.94065 -0.1999999 13.58718 44.76366 0 14.40416 44.76366 -0.1999999 14.40416 40.25254 0 -10.80252 39.18207 0 -11 41.84829 0 -9.375223 41.18207 0 -10.23606 42.28141 0 47.96597 40.6 0.3751289 67.6 41.62487 1.4 67.6 42 2.8 67.6 -39.24811 6.5 27.20958 44.52726 2.8 53.00334 44.69887 2.8 51.89873 44.56245 3 52.80884 44.52726 3 53.00334 44.28023 3 54.14993 44.28023 2.8 54.14993 42.50464 0.01007306 48.13273 42.50464 0.06371182 48.13273 42.52906 0.01240372 48.15113 42.52906 0.06397241 48.15113 43.24439 0.1939953 48.69036 43.38637 0.4592789 48.79738 44.10743 1.155077 49.34093 43.96454 0.6469119 49.23322 43.59406 0.3728185 48.95394 44.79364 1.962608 49.8582 44.56021 1.397777 49.68225 44.47695 1.254793 49.61948 44.71686 2.260506 49.80032 44.91413 3.0052 49.94902 44.91413 2.8 49.94902 44.6288 2.039643 49.73394 44.91386 2.760485 49.94882 42.30847 0.06408381 47.98604 41.19042 0.06652599 47.188 40.38549 0.06859594 46.64968 39.63935 0.02821397 46.45204 39.85355 0.04339271 46.4688 40.21927 0.06573867 46.56009 -36.61457 1.51398 -8.910649 -35.92132 1.695384 -9.978317 -34.83835 1.811508 -10.66177 -34.83835 4.361703 -9.895987 -34.83835 6.647487 -8.530295 -34.83835 8.530295 -6.647487 -34.83835 9.895987 -4.361703 -34.83835 10.66178 -1.811508 -34.83835 10.81457 0 -35.3 10.59808 0 -36.39807 9.5 0 -35.92132 10.12132 0 -35.92132 9.978317 -1.695384 -36.61457 8.910649 -1.51398 -36.61457 9.038352 0 -36.61457 8.270637 -3.645322 -36.61457 7.12925 -5.555681 -36.61457 5.555681 -7.12925 -36.61457 3.645322 -8.270637 -35.92132 9.261619 -4.082102 -35.92132 7.983471 -6.221359 -35.92132 6.221359 -7.983471 -35.92132 4.082102 -9.261619 -33.8 11 11 -34.83835 10.81457 11 -35.3 10.59808 11 -35.92132 10.12132 11 -36.39807 9.5 11 -36.61457 9.038351 11 24.07248 8.658164 79.95001 24.13864 8.90329 79.95001 24.17916 9.022792 79.95001 24.18543 9.038352 79.95001 24.22459 9.140276 79.95001 24.24557 9.188741 79.95001 24.24914 9.198266 79.95001 24.27866 9.262662 79.95001 24.27492 9.255751 79.95001 24.93672 10.17781 79.95001 24.93403 10.17567 79.95001 24.8887 10.13172 79.95001 25.96165 10.81457 79.95001 25.9332 10.80404 79.95001 25.92375 10.8003 79.95001 25.90494 10.79312 79.95001 24.4555 9.590002 79.95001 24.47335 9.617416 79.95001 24.48987 9.643708 79.95001 24.51793 9.685032 79.95001 24.52527 9.696506 79.95001 24.56432 9.75142 79.95001 25.4214 10.55131 79.95001 25.45138 10.56939 79.95001 25.47279 10.58239 79.95001 25.4862 10.59006 79.95001 25.52477 10.61242 79.95001 25.52131 10.61026 79.95001 25.63046 10.66933 79.95001 25.66434 10.68626 79.95001 25.68418 10.6962 79.95001 25.70072 10.70405 79.95001 25.73734 10.72134 79.95001 25.79338 10.74679 79.95001 25.81126 10.75443 79.95001 25.82105 10.75878 79.95001 25.82988 10.76239 79.95001 25.84855 10.77023 79.95001 25.87683 10.78194 79.95001 25.88605 10.78552 79.95001 24.30191 9.312732 79.95001 24.31374 9.335664 79.95001 24.33015 9.369209 79.95001 24.87868 10.12132 79.95001 24.84436 10.08689 79.95001 24.76728 10.00374 79.95001 24.75864 9.99458 79.95001 24.74044 9.973421 79.95001 24.71727 9.947109 79.95001 24.71401 9.94274 79.95001 24.67688 9.898757 79.95001 24.6624 9.880322 79.95001 24.63748 9.849525 79.95001 24.61249 9.816534 79.95001 24.59908 9.799408 79.95001 24.56167 9.748404 79.95001 24.33201 9.371804 79.95001 24.35077 9.407693 79.95001 24.35961 9.425178 79.95001 24.37002 9.443325 79.95001 24.39032 9.480635 79.95001 24.38974 9.478695 79.95001 24.42228 9.535577 79.95001 24.43061 9.54862 79.95001 24.45175 9.583162 79.95001 24.98036 10.21873 79.95001 24.99626 10.23272 79.95001 25.0277 10.26089 79.95001 25.05726 10.28599 79.95001 25.07604 10.30216 79.95001 25.0883 10.31201 79.95001 25.12541 10.34252 79.95001 25.11968 10.3376 79.95001 25.17325 10.38001 79.95001 25.18347 10.38751 79.95001 25.2217 10.41641 79.95001 25.21586 10.41181 79.95001 25.24858 10.43568 79.95001 25.27074 10.45173 79.95001 25.28162 10.4591 79.95001 25.32037 10.48598 79.95001 25.31497 10.48207 79.95001 25.37059 10.51917 79.95001 25.38259 10.52665 79.95001 25.41684 10.54825 79.95001 11.72588 -9.258679 98.14145 11.90933 -9.025 97.4 11.54336 -9.398475 98.0016 11.525 -9.409328 97.4 11.27078 -9.514483 97.88589 11.8872 -9.061576 98.33866 11.91034 -9.023241 98.37699 12.05 -8.5 97.4 11.99853 -8.824703 98.57533 12.0497 -8.525 98.875 11 -9.55 97.4 10.475 -9.409328 97.4 10.7467 -9.51899 97.88156 10.88233 -9.543387 97.85675 11.00042 -9.55 97.84976 11.19421 -9.531883 97.86824 10.08988 -9.023629 98.37659 10.10791 -9.053791 98.34643 10.09067 -9.025 97.4 10.28745 -9.27122 98.12892 10.48033 -9.412385 97.98764 10.00783 -8.843651 98.55625 9.95 -8.5 97.4 9.950299 -8.525 98.875 10.09067 -7.975 98.9 10.09067 -7.975 97.4 10.475 -7.590673 98.9 10.475 -7.590673 97.4 11 -7.45 98.9 11 -7.45 97.4 11.525 -7.590673 98.9 11.525 -7.590673 97.4 11.90933 -7.975 98.9 11.90933 -7.975 97.4 12.01422 -8.22824 98.9 12.05 -8.5 98.9 12.0497 -8.525 98.9 9.950299 -8.525 98.9 9.95 -8.5 98.9 9.958983 -8.362949 98.9 9.985778 -8.22824 98.9 16.525 0.04999995 87.65311 16.525 0 87.65311 17.38448 0.04999995 88.91714 17.45112 0 88.99973 18.63169 0.04999995 90.21912 17.45112 -0.04999995 88.99973 18.26127 -0.04999995 89.87972 19.61024 -0.05000019 90.97061 19.61024 0.04999995 90.97061 5.475 0 87.65311 5.475 0.04999995 87.65311 4.548877 0 88.99973 4.615538 0.04999995 88.91712 4.122714 0.04999995 89.48887 2.389772 0.05000001 90.97063 2.389753 -0.04999995 90.9706 3.368342 0.04999995 90.21909 3.740081 -0.04999995 89.87841 4.548877 -0.04999995 88.99973 16.525 2.920343 89.84761 16.525 4.5 90.52 16.525 4.5 83.95001 16.525 0 83.95001 16.525 0.05588293 87.65315 16.525 0.2271351 87.68482 16.525 0.4156218 87.79087 16.525 1.052269 89.28337 16.525 1.063253 89.31496 16.525 1.253013 89.47109 16.525 1.07093 89.33208 16.525 0.6216115 88.00473 16.525 0.8309162 88.37018 16.525 1.040888 89.22087 16.525 1.113824 89.39595 16.525 1.131512 89.41367 16.525 1.200338 89.45713 16.5 4.5 90.50357 12.1 4.5 88.92303 9.525001 4.5 83.95001 13.41069 4.5 89.15636 14.93606 4.5 89.66651 10.33184 4.5 88.88484 9.9 4.5 88.92303 9.525001 4.5 88.97154 9.525001 6 83.95001 9.525001 5.267948 89.35678 9.525001 6 89.79921 5.475 0 83.95001 5.475 1.040888 89.22087 5.475 0.9268653 88.62847 5.475 6 83.95001 5.475 0.6425546 88.03333 5.475 0.4778812 87.84371 5.475 0.2731142 87.70359 5.475 6 91.51933 5.475 5.763355 91.33309 5.475 4.303596 90.41747 5.475 2.936981 89.85299 5.475 1.253273 89.47113 5.475 1.052361 89.28369 5.475 1.20348 89.45837 5.475 1.170739 89.44255 5.475 1.065431 89.32012 5.475 1.135859 89.41751 5.475 1.097699 89.37628 9.003727 8.4 98.77796 9.003727 8.5 98.77796 9.28049 8.4 98.55516 9.28049 8.5 98.55516 9.461881 8.4 98.24965 9.461881 8.5 98.24965 9.525001 8.4 97.9 9.525001 8.5 97.9 9.525001 8.5 97.54931 9.525001 8.4 97.54931 9 -9.050001 90.767 9 -9 90.83775 9 -9.050001 88.9 13 -9.050001 88.9 13 -9 90.83775 13 -9.050001 90.767 13 -9 97.9 13.00001 -6.301752 97.91022 13 -6 90.83775 13 -6.227205 97.9 13 -6 97.86019 13.83894 -1.284456 88.27266 13.69878 -1.252911 88.23622 13.00169 -5.1 88.08366 13.31073 -1.059956 88.14544 13.1364 -0.9017933 88.10946 14.78053 -5.30759 88.56984 15.25272 -5.568563 88.75517 16.0008 -1.3 89.10246 14.03111 -1.3 88.32587 14.2414 -5.1 88.38842 14.77446 -5.304682 88.56762 15.88888 -7 89.04613 16.73993 -7 89.51634 15.88889 -6 89.04614 15.40564 -5.66539 88.82048 12.80889 0 88.04975 9.191111 0 88.04975 12.80889 -0.04999995 88.04972 9.191105 -0.04999995 88.04972 9.158153 -0.338993 88.05531 8.944957 -0.8026482 88.09368 12.98267 -0.6927235 88.08015 12.92569 -0.58349 88.06987 6.111111 -6 89.04614 6.611826 -5.654841 88.81317 5.405203 -1.264313 89.42909 6.74354 -5.571221 88.7569 7.190725 -5.321292 88.5802 8.998311 -5.1 88.08366 8.533525 -1.158682 88.18012 7.758602 -5.1 88.38842 7.96889 -1.3 88.32587 5.999196 -1.3 89.10246 6.111111 -7 89.04614 5.260067 -7 89.51634 4.176049 -7 90.27251 5.131926 -1.231151 89.59593 4.74322 -1.177315 89.85275 2.869491 -1.175788 91.49076 2.869565 -7 91.49082 3.961088 -1.096133 90.44697 4.3221 -1.124149 90.15897 17.3718 -1.161583 89.93339 17.8132 -7 90.26402 18.50654 -1.099363 90.85938 19.13043 -7 91.49082 19.13043 -1.175788 91.49082 17.13864 -1.193938 89.77218 16.86814 -1.23122 89.59597 16.58267 -1.265658 89.42193 12 -10 90.83775 12.05015 -10 90.29071 12.49713 -9.888198 90.40189 12.34114 -9.940012 90.83775 12.72206 -9.721445 90.46941 12.70705 -9.707159 90.83775 12.85062 -9.561365 90.52208 12.93996 -9.34128 90.83775 12.94223 -9.376236 90.58302 12.98665 -9.208695 90.65068 12.99992 -9.061986 90.75175 9.005198 -9.149256 90.68246 9.057496 -9.375482 90.58329 9.060037 -9.341276 90.83775 9.133975 -9.5 90.83775 9.114307 -9.501788 90.54115 9.292938 -9.707152 90.83775 9.277892 -9.721395 90.46943 9.5 -9.866025 90.83775 9.418658 -9.837512 90.42524 9.658842 -9.940007 90.83775 9.949879 -10 90.29098 10 -10 90.83775 9.8532 -9.99507 90.3143 9.621228 -9.941298 90.3712 9 -6 90.83775 8.999991 -8.994227 90.83115 8.989774 -8.752775 90.63575 8.439874 -7.370632 89.44966 8.493509 -7.431004 89.50754 8.747597 -6 89.86517 8.749513 -7.83306 89.86862 8.880521 -6 90.15683 8.785354 -7.911786 89.93635 8.852055 -8.084345 90.08283 8.086535 -7.10175 89.15863 8.397741 -6 89.40725 8.037576 -7.078943 89.12793 8.054093 -6 89.13807 7.666666 -7 88.95212 7.637173 -6 88.94195 7.094532 -7 88.83998 6.749975 -6 88.85343 7.094532 -6 88.83998 9.95 -10 88.9 10.45618 -10 97.71924 10.01211 -9.999983 98.05502 10 -10 97.9 12.05 -10 88.9 11 -10 97.60003 11.54382 -10 97.71924 12 -10 97.9 11.98791 -9.999927 98.055 10.3875 -3.15 97.83912 11.6125 -3.15 99.96089 12.06088 -3.15 99.5125 9.93912 -3.15 98.2875 9.775 -3.15 98.9 11.6125 -3.15 97.83912 11 -3.15 97.67501 12.06088 -3.15 98.2875 12.225 -3.15 98.9 11 -3.15 100.125 10.3875 -3.15 99.96089 9.93912 -3.15 99.5125 9.809215 -5 98.2125 9.742846 -5 98.34306 9.625 -3.3 98.9 9.723166 -5.020742 98.38979 9.658512 -5.020742 98.59828 9.809215 -3.3 98.2125 10.3125 -3.3 97.70922 10.3125 -5 97.70922 11 -3.3 97.525 11 -5 97.525 11.6875 -3.3 97.70922 11.6875 -5 97.70922 12.19079 -3.3 98.2125 12.19079 -5 98.2125 12.3416 -5.020742 98.59877 12.27684 -5.020742 98.38979 12.25716 -5 98.34306 12.375 -3.3 98.9 12.19079 -3.3 99.5875 12.31716 -5.020742 99.29461 12.375 -5.020742 98.9 11.6875 -3.3 100.0908 11.95497 -5.020742 99.88927 12.19079 -5.020742 99.5875 11 -3.3 100.275 11.3479 -5.020742 100.2303 11.6875 -5.020742 100.0908 10.3125 -3.3 100.0908 10.65162 -5.020742 100.2301 11 -5.020742 100.275 9.809215 -3.3 99.5875 10.04468 -5.020742 99.88893 10.3125 -5.020742 100.0908 9.625 -5.020742 98.9 9.682702 -5.020742 99.29415 9.809215 -5.020742 99.5875 9.818057 -5.151254 100.1235 9.568352 -5.107384 98.13504 9.488845 -5.150352 98.12187 9.34028 -5.151254 98.52671 12.88914 -5.555395 98.05845 12.84106 -5.470862 98.06657 12.97233 -5.471708 98.45714 12.81777 -5.435908 98.07051 12.58789 -5.201189 98.10908 12.65985 -5.151254 98.52731 12.43162 -5.107371 98.13506 12.37584 -5.079031 98.16043 12.32773 -5.051606 98.22497 12.99003 -5.900344 98.04128 13.05841 -6.110832 98.22512 13.05617 -6 98.199 13.064 -6.22993 98.31398 13.11477 -5.9006 98.42516 13.07625 -5.9006 99.52203 13.06439 -6.356179 98.47943 13.06564 -6.323883 98.42983 12.85683 -6.642856 99.45629 12.91865 -6.642857 99.17576 13.02044 -6.349895 99.50531 13.00605 -6.55226 98.9 13.0595 -6.405199 98.56475 12.63535 -6.642854 99.94064 12.46487 -6.349895 100.4175 12.34624 -6.642852 100.2946 11.53366 -6.349895 100.9405 11.49045 -6.642848 100.7753 12.06141 -6.642851 100.5219 9.534594 -6.349895 100.417 9.760156 -6.642842 100.39 10.46561 -6.349895 100.9404 10.48365 -6.642845 100.7683 11.30014 -6.642848 100.815 8.979341 -6.349895 99.5046 9.280398 -6.642839 99.79459 9.653255 -6.642842 100.2941 8.993952 -6.552258 98.9 8.936739 -6.372003 98.50564 8.935355 -6.351727 98.47229 9.081323 -6.642837 99.17571 9.142961 -6.642838 99.45564 9.058588 -5.679071 98.04963 9.012384 -5.878861 98.0417 8.885396 -5.9006 98.4244 9.004933 -6 98.04039 8.94383 -6 98.199 8.941594 -6.110831 98.22512 8.93927 -6.16162 98.25527 8.934825 -6.262164 98.34905 9.607116 -5.088003 98.14871 9.66431 -5.056387 98.2099 9.370209 -5.151254 99.38764 10.56898 -5.151254 100.5457 11.43043 -5.151254 100.5458 12.18151 -5.151254 100.124 12.62962 -5.151254 99.38822 9.181074 -5.437565 98.07031 9.027822 -5.471708 98.45644 9.063385 -5.471708 99.47945 9.595544 -5.471708 100.3539 10.48784 -5.471708 100.8555 11.51146 -5.471708 100.8557 12.40394 -5.471708 100.3544 12.93641 -5.471708 99.48014 8.923527 -5.9006 99.5213 9.494117 -5.9006 100.4589 10.45085 -5.9006 100.9967 11.5484 -5.9006 100.9969 12.50533 -5.9006 100.4594 12.99507 -6 98.04039 8.934401 -6.326043 98.43299 11.32931 -7.363168 99.73629 11.74215 -7.195647 99.93025 11.25592 -7.264546 100.0075 11.78098 -7.179602 99.93679 11.83398 -7.157603 99.94299 11.94381 -7.111667 99.94605 12.10568 -7.043078 99.92648 12.24181 -6.984648 99.88651 12.6038 -6.828299 99.63746 12.7778 -6.741575 99.4146 10.20597 -7.174181 99.93864 10.64782 -7.353991 99.75461 10.74405 -7.264546 100.0075 10.9061 -7.457777 99.4401 11.06838 -7.468299 99.38399 10.99903 -7.498518 99.08433 11 -7.49948 99.04977 9.993097 -7.084999 99.94198 9.775164 -6.992025 99.89264 9.443437 -6.84847 99.68663 9.396225 -6.82827 99.63745 10.17371 -7.160788 99.94232 9.216632 -6.738239 99.40651 9.286767 -6.777135 99.50449 9.679464 -7.01647 99.73749 9.453755 -6.864865 99.66917 9.526664 -7.039707 99.51348 10.33336 -7.269131 99.82433 9.952228 -7.231753 99.69901 10.07134 -7.344212 99.63395 10.61391 -7.551449 99.21464 10.6135 -7.573191 99.0513 9.953261 -8.132639 99.2191 9.910025 -8.455853 99.20715 9.972042 -8.207195 99.16957 9.943185 -8.529528 99.12952 9.981597 -8.258778 99.1205 9.95 -8.549263 99.07154 10.02372 -8.162842 99.06352 9.832092 -8.289469 99.28379 9.874403 -8.379746 99.25066 9.877703 -8.386798 99.24739 9.678812 -7.956234 99.32064 9.776186 -8.169442 99.30965 9.834675 -7.824126 99.34141 9.780548 -8.178977 99.30821 9.882887 -7.932943 99.30914 9.923759 -8.039802 99.26661 9.67754 -7.953423 99.32053 9.777729 -7.710232 99.36357 9.596931 -7.772179 99.2993 9.719212 -7.604649 99.37248 9.65624 -7.501065 99.36799 10.45711 -7.366322 99.68009 10.54193 -7.447352 99.52381 10.59178 -7.509815 99.36597 9.525283 -7.171008 99.38873 9.694419 -7.187157 99.56212 9.561137 -7.361258 99.33145 9.514282 -7.584464 99.2389 10.25754 -7.806956 99.05615 10.30554 -7.742834 99.14823 10.30108 -7.698507 99.23943 10.28078 -7.632773 99.34064 10.23711 -7.548548 99.44659 10.16532 -7.448741 99.54932 10.13928 -7.948007 99.05907 10.14277 -7.924562 99.12395 10.14157 -7.877679 99.1888 10.1293 -7.808838 99.26212 10.0999 -7.72158 99.34007 10.04948 -7.619289 99.41664 9.982005 -7.513249 99.48047 9.895339 -7.400285 99.53027 9.80081 -7.29368 99.55776 12.43127 -7.709235 99.2843 12.48571 -7.58443 99.2389 12.35395 -7.347208 99.41812 12.46259 -7.379713 99.29716 12.46907 -7.213155 99.36735 12.41701 -7.741687 99.29247 12.28274 -7.441043 99.42592 12.39163 -7.798947 99.30414 12.21648 -7.537508 99.41856 12.34955 -7.893075 99.31658 12.15561 -7.636309 99.3983 12.29542 -8.012877 99.3215 12.10323 -7.732593 99.368 12.26054 -8.089064 99.31841 12.21869 -8.180674 99.30795 12.0497 -7.848978 99.31871 12.20527 -8.209673 99.3029 12.01195 -7.953299 99.26273 12.15366 -8.319835 99.27423 11.98871 -8.042631 99.20401 12.10464 -8.42458 99.22753 11.97802 -8.110161 99.14789 12.07418 -8.490302 99.1788 11.97573 -8.141011 99.11294 12.05974 -8.522743 99.14064 11.97578 -8.159037 99.08003 12.05032 -8.547314 99.0841 11.97628 -8.162852 99.06352 12.05 -8.549271 99.07154 11.38548 -7.569951 99.10176 11.3865 -7.573192 99.0513 11.74247 -7.806961 99.05615 11.39995 -7.529678 99.30545 11.44009 -7.472164 99.46768 11.78773 -7.187556 99.91512 11.63117 -7.297863 99.78461 11.51607 -7.393321 99.63217 11.74117 -7.803498 99.08193 11.73904 -7.787477 99.13398 11.73951 -7.759815 99.19061 11.75121 -7.698329 99.28464 11.78419 -7.615329 99.38664 11.84343 -7.516356 99.48685 11.93196 -7.40364 99.57754 12.02115 -7.308665 99.63498 12.12671 -7.209578 99.67518 12.24327 -7.111155 99.69251 12.36992 -7.013665 99.68259 12.47443 -7.172865 99.38775 9.95 -8.550001 99 10.00892 -8.203207 99 11 -7.5 99 10.74344 -7.531826 99 10.2916 -7.774975 99 11.99108 -8.203207 99 12.05 -8.550001 99 11.7084 -7.774975 99 11.25656 -7.531826 99 9.95 -8.550001 98.9 9.955459 -8.443077 98.9 12.05 -8.550001 98.9 11.99108 -8.203207 98.9 11.8763 -7.971558 98.9 11.7084 -7.774975 98.9 11.25656 -7.531826 98.9 9.967003 -8.361807 98.9 10.00892 -8.203207 98.9 10.2916 -7.774975 98.9 10.74344 -7.531826 98.9 12.05 -9 99.07154 12.05 -9.034406 99.07036 12.05 -9.211328 99.02565 12.04996 -9.390825 98.9 12.06506 -9.451295 98.96039 12.08633 -9.482668 98.99172 12.08633 -9.264457 99.14406 12.4404 -9.295998 99.21437 12.4404 -9.048569 99.27672 12.37535 -9.050728 99.30817 12.4404 -9.537191 99.04617 12.37535 -9.308901 99.24314 12.29588 -9.313645 99.2537 12.35185 -9.563876 99.07282 12.37535 -9.559496 99.06844 12.29588 -9.051522 99.31974 12.21229 -9.050436 99.30392 12.21229 -9.307154 99.23924 12.17951 -9.545824 99.05479 12.21229 -9.556478 99.06543 12.26409 -9.56589 99.07482 12.29588 -9.567699 99.07663 12.13876 -9.526015 99.03501 12.13876 -9.289532 99.19996 12.13876 -9.047489 99.26097 12.08633 -9.043293 99.19985 12.11923 -9 99.24423 12.21036 -9 99.30491 12.31867 -9 99.32084 12.4234 -9 99.28896 12.48571 -9 99.2389 12.47843 -9.355033 99.14817 12.46923 -9.521179 99.03018 12.05802 -9.435276 98.94439 12.05802 -9.237042 99.08296 12.05802 -9.038707 99.13303 12.06278 -9 99.15044 9.861239 -9.526015 99.03501 9.861239 -9.471044 99.08547 9.787714 -9.498726 99.11843 9.559598 -9.257676 99.2303 9.515912 -9.174027 99.21783 9.530876 -9.5211 99.0301 9.57388 -9 99.2874 9.514286 -9 99.2389 9.559598 -9.537191 99.04617 9.559598 -9.481201 99.09756 9.62465 -9.559496 99.06844 9.62465 -9.501469 99.12171 9.646118 -9.563566 99.0725 9.704122 -9.508922 99.13058 9.704122 -9.567699 99.07663 9.722538 -9.567003 99.07594 9.787714 -9.556477 99.06543 9.62465 -9.268963 99.25974 9.704122 -9.273114 99.27056 9.787714 -9.267436 99.25575 9.861239 -9.25202 99.21556 9.624649 -9 99.30992 9.678866 -9 99.32064 9.787952 -9 99.30555 9.879972 -9 99.24507 9.913665 -9.482668 98.99172 9.941979 -9.435276 98.94439 9.913665 -9.431657 99.03855 9.941979 -9.388591 98.98725 9.913665 -9.230085 99.15835 9.941979 -9.206103 99.09582 9.95 -9.183609 99.03717 9.95 -9.3482 98.93914 9.95 -9.390825 98.9 9.93707 -9 99.1509 9.95 -9 99.07154 9.638736 -9.699225 98.90526 9.65294 -9.806904 98.72328 9.727143 -9.811209 98.7417 9.953845 -9.4864 98.81024 9.76841 -9.951728 98.33737 9.815502 -9.943811 98.41733 9.740926 -9.937585 98.3808 9.687966 -9.882285 98.55451 9.713086 -9.920287 98.4286 9.595624 -9.787303 98.70063 9.656911 -9.872871 98.5404 9.590881 -9.778019 98.71582 9.575194 -9.67939 98.88465 9.535425 -9.570299 98.98289 9.548441 -9.651947 98.89221 9.551848 -9.6671 98.87353 10.1457 -9.874311 98.23313 10.16789 -9.809807 98.24735 10.03525 -9.76208 98.46656 9.96056 -9.64456 98.70318 9.928578 -9.701764 98.72686 10.00445 -9.82446 98.47052 9.875694 -9.754546 98.74363 9.95436 -9.882019 98.46405 9.80535 -9.793406 98.74916 9.888365 -9.924396 98.44567 9.990514 -9.997722 98.11711 9.966005 -9.998608 98.09786 10.05228 -9.977646 98.16477 10.10643 -9.933827 98.20522 10.07654 -9.985174 98.11013 10.14579 -9.927609 98.16937 10.19019 -9.837027 98.20734 10.20208 -9.75 98.21751 10.03293 -9.689511 98.49103 11.8481 -9.746126 98.28113 11.79789 -9.75 98.21754 11.80981 -9.837027 98.20734 12.22047 -9.956727 98.32082 12.23165 -9.951685 98.3376 12.15276 -9.954818 98.37822 12.37521 -9.834509 98.61721 12.43605 -9.711852 98.81417 12.36767 -9.705039 98.89299 12.4391 -9.702023 98.82761 12.442 -9.677424 98.86558 12.04603 -9.676257 98.69644 12.00361 -9.641942 98.59137 12.17105 -9.79571 98.72914 12.09893 -9.74638 98.72039 12.35929 -9.706657 98.89502 12.27201 -9.709021 98.90605 12.35 -9.816774 98.69847 12.34188 -9.818538 98.70127 12.25649 -9.821117 98.72244 11.95848 -9.796837 98.4354 12.00768 -9.873312 98.43048 12.07426 -9.92711 98.41078 12.2516 -9.941665 98.3689 11.85421 -9.927609 98.16937 11.92346 -9.985174 98.11013 12.08684 -9.993285 98.15214 10.75154 -9.75 97.87982 10.52001 -9.75 97.96614 10.29547 -9.75 98.12145 11.71908 -9.75 98.13488 11.47999 -9.75 97.96614 11.26765 -9.75 97.88468 11 -9.75 97.85 12.93365 -6.690876 98.80213 12.78259 -6.955661 98.97019 12.88625 -6.869753 98.69171 12.78006 -7.317301 98.8118 12.88945 -7.138579 98.55567 12.8775 -6.983185 98.63063 12.62781 -7.257876 99.1011 12.63783 -7.469259 99.04783 12.64622 -7.053874 99.1969 12.93997 -9.34125 97.9 12.81097 -9.34125 98.59562 12.92656 -9.376144 97.9 12.59359 -9.707108 98.51212 12.70711 -9.707108 97.9 12.34125 -9.939973 97.9 12.86701 -9 98.61714 9.767628 -5.000012 97.99293 9.633977 -5.069402 97.9 12.23238 -5.000014 97.99292 12.36602 -5.0694 97.9 13.00038 -6 97.89997 9.228517 -7.018667 98.93914 9.221294 -7.321883 98.81444 9.35187 -7.459646 99.03299 9.208996 -6.917225 98.99238 9.353387 -7.052024 99.19787 9.106183 -6.825238 98.71823 9.121994 -6.964532 98.63985 9.111351 -7.128067 98.55799 9.14119 -9.132231 98.61399 9.633719 -9.886041 98.42481 9.299098 -9.569395 98.55334 9.5 -9.866025 97.9 9 -9 97.9 9.008782 -9.132231 97.9 9.132994 -9 98.61714 9.133975 -9.5 97.9 9.177936 -9.569395 97.9 8.985044 -6 98.03699 8.999618 -6 97.89998 9.019205 -6.76355 98.17649 9.034343 -6.869681 98.26905 9.049763 -6.947753 98.34337 9.054231 -6.962121 98.36258 9 -6.227223 97.90001 9.000246 -6.330717 97.93131 9.000257 -6.319462 97.95272 9.003962 -6.538232 98.02583 9.004267 -6.480894 98.08923 9.020076 -6.627499 98.28667 11.5555 -9.985174 97.81922 11 -9.985174 97.68482 10.4445 -9.985174 97.81922 10.51286 -9.837027 97.95223 11 -9.837027 97.83436 11.48713 -9.837027 97.95223 11.51384 -9.927609 97.90026 11 -9.927609 97.77594 10.48616 -9.927609 97.90026 12.97082 -6.67067 98.3531 12.95847 -6.906963 98.30543 12.97167 -6.831212 98.23543 12.96985 -6.813028 98.2475 12.97975 -6.770859 98.18389 12.99765 -6.434971 98.03704 12.99816 -6.47411 97.98577 9.381387 -5.218513 98.03119 9.098912 -5.566365 97.9 9.179525 -5.436984 98.04756 9.296263 -5.28954 97.9 9.402709 -5.197976 97.9 9.999992 -5 97.16774 9.864711 -5 97.56899 11 -4.999992 96.9 10.21154 -4.999992 97.06198 11.78846 -4.999992 97.06198 11.99984 -5 97.16768 12.13533 -5 97.56896 12.33501 -5.057784 97.79937 12.82048 -5.436984 98.04756 12.96499 -5.737719 97.89999 12.61861 -5.218513 98.0312 12.73336 -5.320165 97.9 12.82645 -5.436984 97.9 9 -6 97.86019 9.56411 -5.1 97.50781 9.56411 -5.1 90.83775 9.27874 -5.307336 90.83775 9.062212 -5.652791 90.83775 10.21154 -5.1 97.06198 11 -5.1 96.9 11.78846 -5.1 97.06198 12.43589 -5.1 97.50781 12.93779 -5.652791 90.83775 12.72126 -5.307336 90.83775 12.43589 -5.1 90.83775 13.25333 -7.827156 89.86351 13.50649 -7.431004 89.50754 13.25538 -6 89.85984 13.56013 -7.370632 89.44966 13.60226 -6 89.40725 13.91347 -7.10175 89.15863 13.95629 -6 89.13169 13.96242 -7.078943 89.12793 14.36283 -6 88.94195 14.33333 -7 88.95212 14.92373 -6 88.83921 14.92373 -7 88.83921 15.25003 -6 88.85343 13.00001 -8.994227 90.83115 13.01023 -8.752775 90.63575 13.14795 -8.084345 90.08283 13.21465 -7.911786 89.93635 13.11948 -6 90.15683 15.2578 -5.652791 88.79171 13.55878 -5.652791 89.36275 14.34301 -5.652791 88.88299 13.06098 -5.652791 90.13565 12.58907 -5.1 89.96478 14.27402 -5.307336 88.67774 12.85739 -5.307336 90.06193 13.40746 -5.307336 89.20788 13.20802 -5.1 89.00377 14.18311 -5.1 88.40724 7.816891 -5.1 88.40724 8.79198 -5.1 89.00377 9.410932 -5.1 89.96478 7.725975 -5.307336 88.67774 8.592543 -5.307336 89.20788 7.656993 -5.652791 88.88299 8.939017 -5.652791 90.13565 8.441219 -5.652791 89.36275 6.742197 -5.652791 88.79171 9.142609 -5.307336 90.06193 7.913778 -1.054999 88.13361 7.926749 -1.069616 88.17886 8.193234 -1.021616 88.0765 9.026883 -0.4741105 88.06306 9.083895 -0.04999995 88.04425 8.804026 -0.8457012 88.10768 8.658584 -0.9857968 88.13969 8.281131 -1.193545 88.23319 7.964939 -1.216566 88.31209 8.522912 -0.85109 87.98071 8.521834 -0.8505192 87.97761 8.461206 -0.8932336 87.99154 8.690512 -0.7554785 88.02449 8.651172 -0.7327879 87.94907 8.630571 -0.7544527 87.95351 8.560203 -0.8789338 88.05693 8.976194 -0.04999995 87.98286 8.95933 -0.04999995 87.96485 8.890306 -0.426408 87.97927 8.917546 -0.04999959 87.8953 8.862497 -0.379056 87.90586 8.849254 -0.4151946 87.90845 8.703981 -0.670724 87.93787 7.950116 -1.12847 88.26038 8.222942 -1.05971 88.15162 8.365487 -0.951784 88.02449 8.399433 -0.9848648 88.10018 7.95914 -1.171793 88.29186 8.25188 -1.116484 88.20301 8.604945 -0.9234341 88.10907 9.021751 -0.04999995 88.01776 8.949712 -0.4460386 88.03206 8.741082 -0.7928433 88.07691 8.158233 -1.025037 88.06652 8.917598 0 87.8953 8.976194 0 87.98286 9.083895 0 88.04425 12.91476 0 88.04462 12.91476 -0.04999995 88.04462 12.9298 -0.04999995 88.04008 13.02334 0 87.9833 13.02334 -0.04999995 87.9833 13.0824 0 87.8953 13.06387 -0.04999995 87.93261 13.08245 -0.04999977 87.8953 12.92496 -0.4932844 88.06729 13.30768 -1.025144 88.14341 14.03506 -1.216566 88.31209 13.72794 -1.161043 88.22412 13.08887 -0.1634691 87.89652 13.13224 -0.4203064 87.94712 13.615 -0.9660341 88.06811 13.61963 -0.940514 88.01067 13.45648 -0.8623629 88.02471 13.34928 -0.7332874 87.94916 13.32988 -0.7433295 87.99264 13.25546 -0.6151112 87.92945 13.15091 -0.4156274 87.90847 14.08622 -1.054972 88.13361 13.81063 -1.016727 88.0584 14.07325 -1.069616 88.17886 13.78887 -1.038839 88.11973 14.06432 -1.086148 88.21002 14.04988 -1.12847 88.26038 13.75989 -1.086825 88.1807 13.41544 -0.8990758 88.08657 13.36107 -0.9583711 88.13063 13.2219 -0.8242291 88.09911 13.00483 -0.4628769 88.05435 13.2846 -0.7740201 88.05483 13.08045 -0.4363043 88.00975 16.01933 -1.163197 89.06616 16.03178 -1.128471 89.04177 16.09378 -1.054174 88.9203 16.10679 -1.050571 88.89481 15.73745 -1.055051 88.75128 16.07033 -1.069616 88.96624 16.05227 -1.090751 89.00163 16.0027 -1.254509 89.09873 16.00732 -1.216566 89.08969 16.00879 -1.207976 89.08683 2.852027 -1.090845 91.4877 2.838203 -1.057169 91.4802 2.717831 -1.040775 91.55757 2.161168 -0.7204724 91.31249 2.10529 -0.7423923 91.29227 2.13662 -0.8135201 91.3868 2.025554 -0.9660782 91.31183 2.075659 -1.017191 91.41849 2.026763 -0.9276655 91.30904 2.224552 -1.093937 91.57132 2.230462 -1.096047 91.57517 2.23721 -1.083187 91.57891 2.271391 -0.7091577 91.32292 2.304567 -0.7694419 91.38236 2.349922 -0.7237922 91.30943 2.36656 -0.8128817 91.40848 2.693729 -0.9787024 91.50414 2.631582 -0.9490539 91.48503 2.59327 -0.9673613 91.54013 2.515808 -0.9229715 91.50121 2.492644 -0.9414625 91.54298 2.426128 -0.8780741 91.47243 2.406373 -0.9008815 91.51531 2.34232 -0.8459314 91.4628 2.745924 -0.9506376 91.41223 2.793693 -0.9902547 91.44977 2.806188 -1.005101 91.4589 2.677625 -1.176285 91.62142 2.860819 -1.120725 91.49118 2.730319 -1.124545 91.59114 2.574748 -1.107466 91.64112 2.539999 -1.163745 91.65243 2.447909 -1.150172 91.65132 2.418756 -1.068112 91.63593 2.38778 -1.138796 91.64128 2.321962 -1.123616 91.62126 2.287435 -1.006661 91.58473 2.31398 -1.121546 91.61814 2.138797 -1.056906 91.49977 2.131491 -0.9911025 91.48374 2.068207 -0.8661974 91.35578 2.028463 -0.8070735 91.23262 2.001072 -0.9075111 91.18676 2.094578 -0.7483041 91.28681 2.059003 -0.7736669 91.26343 2.192434 -0.9248337 91.50144 2.587811 -1.026518 91.60144 2.457706 -0.9937679 91.60063 2.347676 -0.942568 91.56118 2.267574 -0.8739933 91.4931 2.220856 -0.7799501 91.39541 2.216527 -0.7101369 91.32202 19.15294 -1.077446 91.48519 19.1965 -1.144767 91.54843 19.26688 -1.144155 91.59368 19.70623 -0.7113268 91.32093 19.65009 -0.7238042 91.30941 19.62881 -0.8208937 91.41684 19.84102 -0.7210968 91.31191 19.76372 -0.7087639 91.32328 19.75858 -0.7784787 91.39725 19.87901 -0.8272652 91.38572 19.88137 -0.7358992 91.29826 19.82053 -0.7969099 91.39763 19.9561 -0.7882291 91.24999 19.93758 -0.770759 91.2661 19.92753 -0.8669204 91.36216 19.90542 -0.7483089 91.28681 19.68826 -1.115435 91.60134 19.64957 -1.125812 91.61701 19.67507 -1.118973 91.60668 19.79394 -1.087089 91.5585 19.8407 -1.067137 91.52 19.82089 -1.033609 91.53378 19.89082 -1.040176 91.4659 19.89852 -1.035329 91.456 19.8239 -0.9360741 91.49765 19.78082 -0.9809741 91.54408 19.86293 -1.056047 91.49797 19.4348 -1.166705 91.64976 19.3449 -1.1383 91.62658 19.34869 -1.174527 91.63059 19.33987 -1.175127 91.6277 19.14217 -1.176678 91.50325 19.76866 -1.093869 91.56875 19.76171 -1.078126 91.57921 19.6614 -1.05703 91.6178 19.58773 -1.086584 91.64007 19.60663 -1.137332 91.63442 19.50874 -1.109761 91.64963 19.57057 -1.147002 91.64904 19.46495 -1.163131 91.6528 19.98071 -0.9564232 91.29158 19.96166 -0.9113526 91.32994 19.97969 -0.8196772 91.22098 19.96849 -0.8029307 91.23643 19.93701 -0.9747087 91.39406 19.85816 -0.8828273 91.44258 19.77149 -0.8944233 91.49845 19.68342 -0.9710536 91.57553 19.72581 -1.021948 91.5853 19.9491 -0.9957025 91.37384 19.55973 -1.028537 91.62195 19.41542 -1.064446 91.62406 19.42642 -1.126974 91.6453 19.71593 -0.8638052 91.48609 19.6218 -0.8314024 91.42771 19.63922 -0.9303699 91.5517 19.54453 -0.8965955 91.48725 19.53234 -0.9800114 91.58919 19.49174 -0.920289 91.50044 19.40832 -1.011003 91.5884 19.38921 -0.9461196 91.49167 19.28529 -1.024252 91.54575 19.27823 -0.9527381 91.43393 19.27239 -1.079749 91.57626 19.18169 -1.021989 91.46739 19.25408 -0.9506341 91.41223 19.19381 -1.005102 91.45891 2.20232 -0.1053122 91.01065 2.273365 -0.1050692 91.01414 2.305844 -0.04999995 91.00697 2.378635 -0.4205834 91.06372 2.383644 -0.3264159 91.02165 2.333301 -0.2616652 91.02729 2.385962 -0.2684018 91.00227 2.389499 -0.1079662 90.9728 2.325122 -0.4101784 91.08544 2.311123 -0.570613 91.18806 2.016726 -0.04999995 90.8532 2.121132 -0.4206516 91.06359 2.189758 -0.4083731 91.08921 2.175744 -0.572845 91.18511 2.004154 -0.4936304 90.91131 2.030253 -0.1141268 90.88474 2.072717 -0.1101409 90.94167 2.083869 -0.04999995 90.95011 2.132325 -0.1070464 90.98587 2.187958 -0.04999995 91.00547 2.269133 -0.2581462 91.04036 2.26053 -0.4052832 91.09565 2.245981 -0.5660703 91.19409 2.063881 -0.4411011 91.02093 2.024408 -0.466675 90.96756 2.140495 -7.889184 91.50154 2.092683 -7.923341 91.44403 2.024547 -7.969582 91.30877 2.340899 -7.721494 91.62805 2.18981 -7.851704 91.54618 2.545746 -7.503365 91.65194 2.643575 -7.378187 91.63298 2.867133 -7.005202 91.49346 2.754488 -7.213155 91.58443 19.2508 -7.221737 91.58751 19.13287 -7.005202 91.49346 19.6591 -7.721494 91.62805 19.35643 -7.378187 91.63298 19.45425 -7.503365 91.65194 19.86109 -7.890347 91.4999 19.81019 -7.851704 91.54618 19.97546 -7.969582 91.30877 19.90732 -7.923341 91.44403 19.97561 -0.4667882 90.96759 19.86767 -0.1071043 90.98588 19.81327 -0.04999995 91.00515 19.79767 -0.1053687 91.01067 19.91761 -0.04999995 90.94879 19.99586 -0.4937537 90.91133 19.98423 -0.04999995 90.85068 19.96974 -0.1141927 90.88474 19.87888 -0.420747 91.06363 19.93614 -0.4412043 91.02095 19.92728 -0.1102021 90.94168 19.69469 -0.04999995 91.0071 19.72662 -0.1051263 91.01416 19.61049 -0.1080283 90.9728 19.66669 -0.2617524 91.02731 19.61403 -0.2684867 91.00229 19.62041 -0.4048455 91.05573 19.67487 -0.4102752 91.08548 19.73086 -0.2582363 91.04039 19.75401 -0.5660954 91.19412 19.82425 -0.5728724 91.18514 19.68886 -0.5706378 91.18807 19.73947 -0.4053757 91.0957 19.81025 -0.4084649 91.08926 19.69469 0.04999995 91.0071 19.98423 0.04999995 90.85068 19.91761 0.04999995 90.94879 19.86735 0.04999995 90.98404 19.81327 0.04999995 91.00515 2.016726 0.05000001 90.8532 2.305844 0.05000001 91.00697 2.273736 0.05000001 91.01216 2.187958 0.05000001 91.00547 2.132676 0.05000001 90.98406 2.083869 0.05000001 90.95011 12.87272 -9.525001 88.9 12.525 -9.872725 88.9 12.72175 -9.721752 88.9 9.072315 -9.41355 88.9 9.278249 -9.721752 88.9 9.586451 -9.927686 88.9 13.16098 -8.455893 89.48565 13.11096 -8.542173 89.70538 13.00001 -8.996537 90.82926 13.00767 -8.876387 90.53476 13.42009 -8.185317 88.75563 13.37987 -8.215502 88.84244 13.72182 -8.039472 88.27304 13.6851 -8.050876 88.31906 8.579906 -8.185317 88.75563 8.314901 -8.050876 88.31906 8.278182 -8.039472 88.27304 8.620131 -8.215502 88.84244 8.839016 -8.455893 89.48565 8.999995 -8.996537 90.82926 8.992331 -8.876387 90.53476 8.889041 -8.542173 89.70538 13.56773 -7.745383 89.34075 13.52361 -8.018767 89.10897 13.57379 -7.988337 89.03895 13.01135 -8.835378 90.56856 13.16136 -8.400229 89.83827 13.23201 -8.293065 89.64829 13.0122 -8.794136 90.60225 13.17386 -8.245539 89.96581 13.25025 -8.108119 89.80148 13.91234 -7.868884 88.6684 13.87479 -7.875457 88.70216 13.62279 -7.703214 89.28186 13.95675 -7.53484 89.00346 13.99894 -7.523157 88.97611 14.16667 -7.866025 88.48072 14.18722 -7.827358 88.53887 14.28868 -7.5 88.82582 14.29455 -7.468149 88.84243 15.94059 -7.468149 88.9419 14.9193 -7.468149 88.72293 7.70545 -7.468149 88.84243 7.711325 -7.5 88.82582 8.001062 -7.523157 88.97611 7.812776 -7.827358 88.53887 7.833333 -7.866025 88.48072 8.087663 -7.868884 88.6684 8.987799 -8.794136 90.60225 8.826141 -8.245539 89.96581 8.749749 -8.108119 89.80148 8.432268 -7.745383 89.34075 8.988652 -8.835378 90.56856 8.838638 -8.400229 89.83827 8.767989 -8.293065 89.64829 8.476394 -8.018767 89.10897 8.426215 -7.988337 89.03895 8.125206 -7.875457 88.70216 8.377206 -7.703214 89.28186 8.043251 -7.53484 89.00346 19.91963 8.689736 96.38453 19.77164 9.148051 80 18.14805 10.77164 80 19.27273 9.958243 97.71873 19.12132 10.12132 80 19.61923 9.462752 96.96124 19.80458 9.065065 96.61929 17 11 80 17 11 91.15404 17.47922 10.96148 93.04126 17.94216 10.84822 94.94868 18.8 10.4 98.9 18.04157 10.81338 95.37368 17.96154 10.84173 95.03101 19.27273 9.971097 97.83267 19.80907 9.285041 97.90611 19.92409 9.004234 98.20426 19.92475 9.001721 98.20187 19.93818 8.947532 98.15267 19.97141 8.778544 98.02308 19.99896 8.487301 97.86834 19.27273 9.947851 100.1658 19.68796 9.55513 99.13549 19.75155 9.4507 98.86997 19.84479 9.248688 98.48961 19.93563 8.250217 98.03442 19.98016 8.32453 97.95166 19.91739 8.267148 98.07478 19.81724 8.220183 98.17555 19.76805 8.180013 98.19653 19.69466 8.18889 98.2427 19.69671 8.16507 98.23104 19.97949 8.355715 97.96926 19.91607 8.295081 98.09049 19.81539 8.245558 98.18949 19.69246 8.212679 98.25522 19.76884 1.108734 91.66001 19.86481 1.077025 91.57472 19.86395 2.346608 91.87863 19.9762 4.233979 92.59642 19.68056 6.581723 95.78952 19.58541 7.043313 97.16944 19.46189 6.552531 95.80332 19.44746 7.038862 97.17054 19.25067 6.611432 95.77548 19.34266 7.060859 97.16515 19.26789 7.09171 97.15756 19.86395 6.693301 95.7368 19.7881 7.124944 97.14938 19.68075 7.069033 97.16312 19.99958 7.50224 97.05672 19.93998 7.291264 97.10853 19.9762 6.86546 95.65544 19.86415 7.18912 97.13362 19.80574 7.137607 97.14627 19.9762 5.756629 93.94793 19.9762 2.406965 91.69804 19.9516 1.027787 91.4391 19.95608 1.02401 91.42881 19.97641 1.003122 91.37234 19.99854 0.958072 91.25204 19.92539 1.046477 91.49033 19.4622 1.161122 91.74623 19.54686 1.150737 91.74377 19.68056 2.30749 91.99568 19.6815 1.128814 91.70797 19.70871 1.1232 91.69542 19.46189 2.297255 92.0263 19.25067 2.317905 91.96452 19.32057 1.174489 91.71611 19.13042 1.806905 91.71451 19.13044 1.184357 91.58605 19.13035 7.195083 97.13219 19.13045 6.647323 95.62755 19.13044 5.787574 94.274 19.86395 4.127807 92.75448 19.68056 4.058996 92.85693 19.46189 4.040993 92.88374 19.25067 4.077318 92.82965 19.13043 3.309217 92.27088 19.86395 5.612276 94.07211 19.68056 5.518718 94.15259 19.46189 5.494241 94.17365 19.25067 5.543629 94.13117 19.13043 4.657988 93.13813 19.69104 0.1338604 91.01071 19.74144 0.7499325 91.37073 19.72193 0.6062481 91.22402 19.81088 0.6100675 91.21945 19.63798 0.6221893 91.20484 19.6184 0.3685107 91.03882 19.66505 0.7612884 91.36135 19.65578 0.7640079 91.3591 19.8947 0.6347926 91.1898 19.89266 0.7842686 91.34236 19.78199 0.7514027 91.36952 19.98484 0.8763912 91.26624 19.97187 0.8536854 91.28501 19.95729 0.6758547 91.14051 19.94081 0.8179988 91.31449 19.91023 0.7945907 91.33383 19.61083 0.1375815 90.97563 19.78004 0.133305 91.0159 19.86803 0.1362346 90.98825 19.93817 0.1421158 90.93276 19.98516 0.1505244 90.85343 19.87262 0.2965917 91.01881 19.78521 0.2878236 91.04712 19.69611 0.2888016 91.04389 19.9975 0.915212 91.23416 19.98976 0.5176127 90.95185 19.94754 0.4793457 91.02481 19.8808 0.4515573 91.0778 19.79458 0.4362587 91.10697 19.70542 0.4362582 91.10697 2.87868 10.12132 80 3.960494 10.81415 95.36478 3.85195 10.77164 80 4.031146 10.83925 95.06217 4.038734 10.84183 95.02986 4.119446 10.86786 94.68843 5 11 91.15404 5 11 80 2.727273 9.958243 97.71873 3.200001 10.4 98.9 3.597251 10.65185 96.98032 2.466682 9.606954 97.1261 2.133587 8.885254 96.49893 2.228361 9.148051 80 9 6 89.9 7.422643 6 90.4028 6.917739 6 90.63349 9.5 6 89.8033 17.91192 10.85833 94.98857 16.88666 11.27843 95.82453 17.7762 11.05001 97.90985 17.79358 11.04076 97.92588 16.72955 11.14794 94.014 16.03461 11.37363 94.49263 16.05132 11.10042 92.37878 15.11851 11.4 93.58303 19.7883 9.363243 98.90268 19.36837 9.815316 100.2444 19.63781 9.567469 99.59197 19.40996 9.589716 100.3221 19.65697 9.430231 99.6367 19.38941 9.468083 100.344 19.63318 9.28393 99.67203 19.34472 9.358374 100.3516 19.56675 9.148318 99.69239 19.18794 9.175562 100.3261 19.46911 9.04036 99.6961 19.5902 8.825829 99.03335 19.61403 8.843555 99.03191 19.71422 8.948119 99.01672 19.7826 9.081138 98.98759 19.80743 9.226062 98.9476 19.38592 8.739488 99.02572 19.24636 8.929163 99.6658 19.02682 9.095395 100.2721 17.84815 11.05001 98.89146 4.153476 11.05001 98.75046 4.223803 11.05001 97.90984 3.958033 10.42331 102.1811 4.24737 10.97421 100.623 2.727273 9.947851 100.1658 17.75263 10.97421 100.623 18.04197 10.42331 102.1811 2.727273 9.971098 97.83267 4.446931 11.05001 100.8886 5.39123 11.05001 102.8292 5.921521 10.76396 104.1294 6.892584 11.05001 104.3796 7.979533 10.85909 105.3774 8.801883 11.05001 105.3858 9.964168 10.85909 105.9716 10.9295 11.05001 105.7478 12.03583 10.85909 105.9716 13.06411 11.05001 105.4297 14.02047 10.85909 105.3774 14.99372 11.05001 104.463 16.07848 10.76396 104.1294 16.52668 11.05001 102.9439 17.51074 11.05001 101.0231 19.65434 8.780303 98.84611 19.78126 8.61693 98.484 19.83365 8.491841 98.31934 19.90814 8.563808 98.25151 19.45553 8.681855 98.85077 19.52537 8.606416 98.6859 19.71906 8.712232 98.66299 19.9282 8.989221 98.21267 19.88761 9.115652 98.45644 19.88987 9.009678 98.52043 19.97534 8.732233 98.07418 19.95739 8.646467 98.1673 19.64835 8.395926 98.39484 19.61365 8.472312 98.48031 19.59217 8.51077 98.53101 19.80645 8.97072 98.79188 19.74139 8.865866 98.82538 19.80146 8.798075 98.62876 19.86072 8.9003 98.57989 19.7749 0.9937691 91.61257 19.85011 0.8957426 91.49278 19.91596 0.9553516 91.47009 19.76857 0.8555395 91.49336 19.83121 1.065692 91.60491 19.17235 1.066357 91.56508 19.18411 1.048577 91.55713 19.28337 1.05721 91.64077 19.65617 0.7668761 91.36288 19.68712 0.8397367 91.47401 19.6358 0.9069462 91.55621 19.63755 0.8573679 91.47795 19.57653 0.917934 91.54986 19.22597 1.003452 91.52639 19.26355 0.9790189 91.4966 19.31222 1.001041 91.58361 19.37561 0.9783393 91.569 19.39148 0.9948791 91.61524 19.48923 0.9564898 91.58248 19.48648 0.9771258 91.62329 19.56714 0.9492103 91.60295 19.13614 1.155007 91.58499 19.54364 1.100602 91.73067 19.39118 1.127835 91.72637 19.26512 1.137104 91.68011 19.67065 1.057567 91.6899 19.38761 1.04948 91.68048 19.51309 1.026922 91.68707 19.61814 0.9913363 91.65655 19.70527 0.9381936 91.59441 18.59713 0.9190438 90.84957 18.46773 0.7110046 90.40734 18.59731 0.3692809 90.25859 17.34357 0.3692809 88.94979 17.18939 0.7110046 89.07286 17.23204 0.9803331 89.71993 16.94389 0.949814 89.26881 17.94671 0.920407 90.28142 2.023801 5.756629 93.94793 2.749337 6.611435 95.77548 2.869559 6.341961 95.06915 2.869551 7.017164 96.52194 2.023801 6.865461 95.65543 2.136056 6.6933 95.7368 2.064243 7.283825 97.11036 2.13586 7.189112 97.13362 2.31944 6.581721 95.78952 2.319296 7.069025 97.16313 2.23183 7.111984 97.15257 2.869647 7.195086 97.13219 2.855265 7.180184 97.13585 2.732112 7.091717 97.15756 2.665061 7.063425 97.16452 2.538113 6.552531 95.80332 2.460063 7.037733 97.17082 2.377343 7.051028 97.16754 2.749337 2.317903 91.96451 2.869581 2.728104 92.01133 2.869574 4.146322 92.75963 2.869566 1.184357 91.58604 2.839852 1.183693 91.61634 2.653506 1.172383 91.72505 2.538113 2.297252 92.0263 2.31944 2.307486 91.99568 2.430889 1.147643 91.74064 2.537746 1.161122 91.74623 2.044634 1.024869 91.43051 2.070086 1.043685 91.48239 2.023801 2.406962 91.69804 2.13509 1.076982 91.5746 2.136056 2.346604 91.87863 2.236083 1.110035 91.66335 2.320415 1.129189 91.70879 2.023801 4.233977 92.59642 2.136056 5.612274 94.07211 2.31944 5.518716 94.15259 2.538113 5.49424 94.17365 2.749337 5.543631 94.13116 2.86956 6.229709 94.88919 2.136056 4.127804 92.75448 2.31944 4.058992 92.85693 2.538113 4.040991 92.88374 2.749337 4.077318 92.82965 2.869566 5.369221 93.79437 2.305342 8.188876 98.24269 2.182766 8.220167 98.17555 2.303291 8.16504 98.23103 2.211904 8.185323 98.18421 2.012098 8.304291 97.90953 2.019843 8.324509 97.95165 2.113832 8.22151 98.10066 2.082612 8.26713 98.07477 2.020513 8.355715 97.96926 2.184616 8.245559 98.18949 2.126818 8.27026 98.14011 2.083931 8.295081 98.09049 2.307542 8.212679 98.25522 2.171387 9.288738 98.55007 2.243365 9.441286 98.84654 2.190932 9.285041 97.90611 2.624676 9.87877 99.97737 2.248456 9.450699 98.86996 2.001044 8.487422 97.8684 2.017031 8.696295 97.97143 2.061975 8.9482 98.15325 2.074261 8.997894 98.19824 2.303088 0.6415332 91.24919 2.358513 0.6543256 91.23503 2.344217 0.764006 91.3591 2.317197 0.5092888 91.14342 2.379533 0.4059969 91.05633 2.328244 0.3627617 91.06333 2.335212 0.2092344 91.01422 2.049422 0.7053512 91.17869 2.102122 0.6702207 91.21752 2.116595 0.7795366 91.34626 2.059185 0.817999 91.31448 2.040443 0.8374139 91.29844 2.015519 0.7473144 91.1323 2.030372 0.8504354 91.28767 2.015166 0.8763864 91.26623 2.167883 0.6470296 91.24315 2.237722 0.6379178 91.25321 2.153253 0.7648242 91.35842 2.230093 0.7504258 91.37032 2.263781 0.358168 91.0746 2.271138 0.2064711 91.02802 2.192893 0.3605412 91.06883 2.123876 0.3709756 91.04335 2.065999 0.3886229 91.00023 2.02576 0.4108422 90.94593 2.004711 0.4343597 90.88842 2.252254 0.504335 91.15117 8.662785 7.944444 91.65961 9.20522 6.622629 90.30236 10.99993 6.861519 90.30236 6.527851 7.645157 92.37686 15.12326 7.944507 92.50598 15.472 7.645246 92.37686 16.31687 7.944535 93.45801 18.63331 7.794329 97.49246 18.50052 7.944618 97.62526 18.30657 7.183207 94.89805 18.0957 7.944598 96.15512 17.35101 7.944567 94.71091 17.31602 6.209383 92.37686 18.72028 4.341181 92.37686 18.0021 1.106109 90.48887 17.14398 1.192677 89.88995 17.86035 1.120409 90.38994 17.65226 1.681632 90.30236 17.97378 1.108967 90.4691 16.98082 3.363069 90.30236 16.63954 1.243563 89.53789 15.89296 4.810346 90.30236 12.79465 6.622664 90.30236 14.46441 5.922695 90.30236 4.683856 6.209258 92.37686 5.236474 1.231642 89.61212 4.347706 1.681499 90.30236 5.019112 3.362949 90.30236 4.023871 1.107235 90.46747 4.132921 1.113291 90.37921 4.892246 1.192329 89.82952 3.99065 1.105806 90.49487 3.279635 4.341027 92.37686 3.693289 7.183063 94.89805 4.703597 7.944498 94.62914 3.940332 7.944567 96.06365 3.430627 7.86729 97.55454 3.499486 7.944628 97.62528 5.5 7.944444 93.64302 6.551599 7.944444 92.72769 13.67145 7.944476 91.77619 12.1 7.944444 91.37167 10.99999 7.944444 91.29174 5.123087 11.28008 95.80598 5.235127 11.14213 94.04239 5.948684 11.10042 92.37878 6.881489 11.4 93.58303 6.106579 11.38174 94.32252 5.923489 11.37086 94.54552 13.86586 11.4 92.81567 14.1775 11.10042 91.2878 11.98331 11.4 92.24678 12.08414 11.10042 90.72279 10.01668 11.4 92.24678 9.915863 11.10042 90.72279 8.134138 11.4 92.81567 7.822498 11.10042 91.2878 14.77427 11 89.85816 12.28775 11 89.18703 9.712252 11 89.18703 7.225733 11 89.85816 15.96502 11.38531 94.45552 16.67042 11.38531 96.20222 17.02541 11.38531 98.01955 14.64814 11.5 94.19028 15.26159 11.5 94.88072 15.74859 11.5 95.97338 16.17315 11.5 97.87876 16.21247 11.5 98.13834 7.347674 11.38531 103.7725 8.491992 11.49455 103.7371 8.39558 11.49981 103.5177 8.677126 11.4955 103.8854 9.045428 11.38531 104.6672 9.234614 11.491 104.109 10.93731 11.38531 104.9891 10.94338 11.491 104.3997 12.83541 11.38531 104.7062 12.65776 11.491 104.1442 13.60979 11.5 103.4759 13.53346 11.49571 103.7008 14.55123 11.38531 103.8467 13.35956 11.49112 103.8665 13.32287 11.4955 103.8854 14.0721 11.5 103.1793 15.91434 11.38531 102.4958 15.2513 11.5 102.0107 16.78936 11.38531 100.7879 16.00827 11.5 100.5332 17.0894 11.38531 98.89241 16.26782 11.5 98.89344 6.012665 11.38531 102.3939 5.172993 11.38531 100.6683 4.912051 11.38531 98.76702 5.733429 11.5 98.78497 5.787528 11.5 98.13834 4.974578 11.38531 98.01955 5.959164 11.5 100.4297 6.68555 11.5 101.9225 7.840441 11.5 103.1151 8.390213 11.5 103.4759 18.12817 10.29442 102.2752 18.16889 10.06916 102.3542 18.1163 9.832924 102.363 17.98274 9.641145 102.2995 16.06002 9.974726 104.2074 15.95542 9.880118 104.0832 17.84339 9.552564 102.2099 14.05338 10.0871 105.448 13.97657 9.97159 105.2833 16.15656 10.17293 104.3076 14.10349 10.27459 105.5555 14.11439 10.49493 105.5788 16.18895 10.41267 104.3188 14.11369 10.5086 105.5773 16.1496 10.63769 104.2384 14.08393 10.70473 105.5135 12.0576 10.70473 106.1202 12.04712 10.0871 106.0486 12.02078 9.97159 105.8688 9.952879 10.0871 106.0486 9.979223 9.97159 105.8688 11 9.97159 105.9432 12.06804 10.49493 106.1915 12.06431 10.27459 106.166 7.923932 10.73264 105.4967 9.942402 10.70473 106.1202 9.931957 10.49493 106.1915 9.935694 10.27459 106.166 8.023433 9.97159 105.2833 7.956994 10.06424 105.4258 7.946616 10.0871 105.448 7.898133 10.26409 105.552 7.886167 10.50603 105.5776 7.916066 10.70473 105.5135 5.85006 10.63677 104.239 5.811018 10.41011 104.3192 5.844563 10.16917 104.3066 5.942734 9.971138 104.2042 4.020989 9.637723 102.2974 4.156606 9.552564 102.2099 6.044575 9.880118 104.0832 2.973183 9.095395 100.2721 2.816394 9.172376 100.3249 3.885314 9.829247 102.3625 2.631195 9.814373 100.2449 3.871441 10.29349 102.2757 2.590173 9.587201 100.3226 3.831182 10.06661 102.3547 2.610592 9.468082 100.344 2.65721 9.354817 100.3516 17.8673 1.11187 90.3792 17.19015 1.032522 89.79237 17.17616 1.067247 89.81972 18.44385 1.108687 90.87754 18.46362 1.020549 90.86113 18.50327 0.9479164 90.82263 17.16646 1.106962 89.84155 17.1614 1.149847 89.85697 17.16098 1.193899 89.86564 17.88029 1.024054 90.35579 17.91233 0.9520404 90.30979 17.2075 1.004589 89.76123 2.433338 0.9239552 91.55622 2.36405 0.8599888 91.48121 3.42424 0.9180271 90.82995 3.5323 0.7110046 90.40731 4.053294 0.9204065 90.28141 2.523612 0.960171 91.58372 2.736445 0.9790191 91.4966 2.633693 0.97921 91.56549 5.05612 0.9498139 89.26879 4.810628 0.7110046 89.07284 4.656444 0.3692808 88.94977 3.402721 0.3692808 90.25856 4.726714 0.9761614 89.7507 2.178297 1.073574 91.61479 2.084523 0.9564331 91.47136 2.150312 0.896705 91.49392 2.231786 0.8563552 91.49434 2.313174 0.8404068 91.47484 2.233604 1.00075 91.62124 2.353441 1.067753 91.70124 2.489581 1.10832 91.73428 2.644532 1.131597 91.7176 2.786765 1.137413 91.64707 2.864635 1.158462 91.5852 2.862429 1.149476 91.58447 2.8278 1.066654 91.56517 2.721035 1.001254 91.56231 2.77424 1.00364 91.52654 2.301877 0.9440349 91.60152 2.369919 0.9116304 91.56174 2.401854 0.9997708 91.66532 2.448346 0.9558445 91.60913 2.514266 1.033304 91.68929 2.534295 0.982132 91.62424 2.641832 1.05261 91.67269 2.630821 0.9973615 91.6088 2.759877 1.057471 91.61317 2.81746 1.050826 91.5582 2.380538 8.460948 98.46638 2.190313 8.557074 98.39762 2.152578 8.443392 98.26985 2.330484 8.585347 98.5656 2.237175 8.649281 98.53798 2.588712 8.720318 98.9602 2.614076 8.739487 99.02572 2.51192 8.769891 99.03341 2.083847 9.033066 98.28696 2.139222 9.173767 98.61323 2.519594 8.657227 98.79122 2.336782 8.353923 98.35531 2.014853 8.667213 98.00733 2.03126 8.587402 98.10588 2.079153 8.510441 98.19607 2.157782 8.732919 98.49291 2.217401 9.081137 98.98759 2.174332 8.949305 98.71679 2.285778 8.948118 99.01672 2.237283 8.844974 98.75554 2.385967 8.843555 99.03191 2.322651 8.758917 98.78076 2.420113 8.69622 98.79204 2.077358 8.934225 98.36124 2.102304 8.830869 98.43227 2.211698 9.363241 98.90268 2.192804 9.247939 98.9409 2.192575 9.226061 98.9476 2.361044 9.566286 99.58785 2.341878 9.429047 99.63258 2.752593 8.928083 99.66204 2.52979 9.039229 99.69216 2.432128 9.147164 99.68836 2.36568 9.282758 99.66794 5.387992 8.357628 94.77312 4.391601 8.357628 96.69664 4.128383 8.355965 97.73209 4.957223 8.5 97.40512 4.863085 8.5 97.85691 6.927097 8.357628 93.24871 5.985034 8.5 95.21217 5.475 8.5 96.03219 9.9 8.5 92.77301 9.087733 8.5 92.97605 8.860074 8.357628 92.27079 9 8.5 93.00509 7.360399 8.5 93.84992 10.99999 8.5 92.67505 10.99999 8.357628 91.93395 12.1 8.5 92.77301 13.13991 8.357628 92.27079 13.5037 8.5 93.20056 15.07289 8.357628 93.2487 14.68429 8.5 93.88185 16.612 8.357628 94.77311 15.77236 8.5 94.90277 16.5578 8.5 96.0963 17.6084 8.357628 96.69662 17.04366 8.5 97.40804 17.87162 8.355962 97.73207 17.13692 8.5 97.85691 13.53855 11.5 93.51055 11.87101 11.5 93.00663 11.67428 11.5 92.9809 11.33811 11.49627 92.80241 10.12899 11.5 93.00663 10.32572 11.5 92.9809 10.80384 11.49468 92.76713 8.461444 11.5 93.51055 7.351858 11.5 94.19028 7.293538 11.5 94.23704 6.649846 11.5 95.02996 6.183833 11.5 96.19513 5.470488 11.38531 95.71788 13.56567 9.366894 103.6417 13.60979 9.318982 103.4759 15.38263 9.046358 101.8228 17.95937 8.560328 99.14781 17.96491 8.561372 99.14839 18.22884 8.739486 99.56527 18.207 8.675528 99.38146 13.46589 9.398838 103.7851 13.32287 9.409926 103.8854 16.15389 8.56032 99.9897 18.08798 8.592896 99.18658 18.15911 8.6262 99.25432 8.533811 9.532044 104.1888 11 9.409926 104.4 8.675601 9.409925 103.8847 3.771158 8.739486 99.56527 5.84611 8.560318 99.98969 6.617371 9.046358 101.8228 3.91637 8.591715 99.18481 4.040637 8.560323 99.1478 3.831266 8.632414 99.26885 3.792936 8.675964 99.38285 8.534851 9.39897 103.7859 8.435207 9.367385 103.6436 8.390213 9.318982 103.4759 18.41025 8.202855 98.27964 18.35398 8.170079 98.09488 18.40682 8.195223 98.25537 17.81277 8.388828 97.88395 17.76799 8.449958 98.38932 18.4172 8.038136 97.74221 18.22396 8.32901 98.43063 18.01884 8.42428 98.59688 17.44428 8.5 98.7231 17.59535 8.5 98.94012 18.49598 7.951324 97.64017 18.45001 8.026434 97.81234 18.41186 8.112875 98.02538 5.213439 1.090434 89.55004 4.08782 0.952255 90.30997 4.119805 1.024362 90.35592 5.233023 1.167804 89.59544 4.891637 1.153125 89.82086 5.179535 1.036128 89.48497 4.844858 1.009312 89.72321 4.876413 1.071063 89.78258 17.94949 8.554957 99.13571 17.80379 8.516889 99.04485 16.22379 8.5 99.57968 18.31309 8.42724 98.76656 18.35736 8.455332 98.87706 18.33361 8.431356 98.78234 18.40692 8.382739 98.71077 18.30608 8.530426 99.04908 18.25774 8.601222 99.21125 18.41707 8.367884 98.67675 18.41488 8.371092 98.6841 18.42776 8.352224 98.64088 18.22322 8.651783 99.32707 18.3264 8.50067 98.98092 18.33673 8.485536 98.94626 18.3553 8.458345 98.88397 3.613655 8.479188 98.90225 3.599746 8.44904 98.83966 3.640652 8.437804 98.80424 3.579904 8.388618 98.71583 3.568176 8.298502 98.52592 3.772883 8.327207 98.42807 3.56892 8.279341 98.48265 3.58976 8.202863 98.27964 3.589083 8.4202 98.78045 3.681859 8.428194 98.77038 3.981182 8.424287 98.5969 3.624379 8.498843 98.94373 3.61569 8.483117 98.91049 4.052092 8.554214 99.13407 3.739218 8.633299 99.25989 3.67662 8.570812 99.10353 4.091715 8.539834 99.1025 4.220495 8.513184 99.03282 4.404645 8.5 98.94012 5.776205 8.5 99.57968 3.588115 8.112804 98.02519 3.579397 8.088348 97.96298 3.633391 8.131237 97.98484 3.54829 8.023335 97.80503 4.19015 8.470419 98.65641 4.23205 8.433513 98.227 4.542073 8.5 98.74633 3.64585 8.224975 98.26665 3.595494 8.187191 98.23081 3.595619 8.144192 98.10848 18.56559 7.985476 97.94601 19.26996 7.355421 97.63544 19.28886 7.383107 97.67987 19.15888 7.48743 97.70639 19.46835 7.680656 97.99874 19.55637 7.850891 98.10895 19.42906 7.926337 98.17524 18.69913 8.203955 98.46259 18.5499 8.18525 98.36601 18.52102 8.541767 99.02569 18.34914 8.502466 98.94716 18.84835 8.247836 98.54031 18.67897 8.608129 99.08317 18.66307 8.61355 99.09888 18.93284 8.514904 98.84305 19.01321 8.324601 98.60499 19.16146 8.420734 98.64287 19.13696 8.090984 98.34494 19.4404 8.293511 98.41815 19.62367 7.992305 98.17529 19.40077 7.561666 97.89628 19.42113 7.596707 97.92909 19.13805 7.786908 98.03654 19.44848 7.644831 97.97045 19.22829 7.297145 97.52498 18.65063 7.783852 97.5231 18.94524 7.481684 97.42347 19.18464 7.242253 97.3833 18.86067 7.735708 97.80469 18.84181 7.987963 98.18479 19.3976 7.556281 97.89102 2.710845 7.383547 97.68055 3.090778 7.694948 97.78565 2.957907 7.711924 97.9102 3.301596 7.73442 97.5033 3.49982 8.122793 98.18967 3.016183 8.494707 98.79713 2.839626 8.421184 98.64377 2.894487 8.280365 98.53455 3.33545 8.344257 98.67936 3.606244 8.480696 98.90688 3.277916 8.593173 99.041 3.531033 8.675383 99.29757 3.057965 8.197619 98.47387 3.206445 8.147405 98.39861 3.355449 8.121463 98.30335 3.207281 7.703168 97.64695 2.729544 7.356136 97.63664 2.768136 7.301971 97.53526 2.785949 7.278398 97.48236 2.805068 7.254463 97.41997 2.363183 8.020673 98.18609 2.369181 8.00712 98.18095 2.371379 8.008738 98.18246 2.443359 7.850263 98.10852 2.523095 7.898868 98.15016 2.510999 7.719446 98.02717 2.666818 7.817526 98.09578 2.578711 7.596982 97.92934 2.81338 7.75396 98.0156 2.61817 7.529383 97.86386 2.647046 7.482301 97.81196 10.2625 8.4 97.62261 9.722613 8.4 98.1625 9.525001 8.4 98.9 10.37084 8.4 97.00154 11 8.4 97.42501 11.3764 8.4 96.93574 11.7375 8.4 97.62261 12.28641 8.4 97.36861 12.27739 8.4 98.1625 12.86983 8.4 98.19026 12.475 8.4 98.9 12.97855 8.4 99.1921 12.27739 8.4 99.6375 12.58498 8.4 100.1198 11.7375 8.4 100.1774 11.78901 8.4 100.7378 11 8.4 100.375 10.79274 8.4 100.8892 10.2625 8.4 100.1774 9.849091 8.4 100.5357 9.722613 8.4 99.6375 9.197621 8.4 99.76685 19.62266 7.560337 97.8883 19.7881 7.608641 97.82955 19.44746 7.552392 97.89796 19.9663 7.447067 97.32124 19.91238 7.360826 97.37625 19.7881 7.254662 97.44397 19.62266 7.19053 97.4849 19.44746 7.179982 97.49163 19.26789 7.225826 97.46238 19.9663 7.753557 97.65326 19.91238 7.688601 97.73227 2.732112 7.251549 97.50122 2.552537 7.522727 97.87319 2.0337 7.727891 97.63182 2.211904 7.580093 97.8057 2.377343 7.530829 97.86365 2.087621 7.661645 97.70975 2.552537 7.2068 97.53213 2.377343 7.217096 97.52502 2.211904 7.279697 97.48178 2.0337 7.467507 97.35208 2.087621 7.383326 97.41022 9.525001 6.5 98.9 9.722613 6.5 98.1625 10.2625 6.5 97.62261 11 6.5 97.42501 11.7375 6.5 97.62261 12.27739 6.5 98.1625 12.475 6.5 98.9 12.27739 6.5 99.6375 11.7375 6.5 100.1774 11 6.5 100.375 10.2625 6.5 100.1774 9.722613 6.5 99.6375 11 6.5 98.9 8.390213 8.5 103.4759 6.617371 8.5 101.8228 8.534851 8.5 103.7859 8.435207 8.5 103.6436 9.197621 8.5 99.76685 12.86983 8.5 98.19026 12.28641 8.5 97.36861 11.3764 8.5 96.93574 10.37084 8.5 97.00154 12.97855 8.5 99.1921 12.58498 8.5 100.1198 15.38263 8.5 101.8228 11.78901 8.5 100.7378 13.60979 8.5 103.4759 10.79274 8.5 100.8892 9.849091 8.5 100.5357 13.46589 8.5 103.7851 13.32287 8.5 103.8854 11 8.5 104.4 13.56567 8.5 103.6417 8.677126 8.5 103.8854 11 -8.5 97.4 -4.102882 10.86282 79.95001 -4.348168 10.92839 79.95001 -4.999813 11 79.95001 -2.430607 9.54862 79.95001 -2.389739 9.478695 79.95001 -2.442612 9.569198 79.95001 -2.87868 10.12132 79.95001 -2.822188 10.06328 79.95001 -2.828661 10.07056 79.95001 -2.473348 9.617416 79.95001 -2.122844 8.849693 79.95001 -2.104779 8.785937 79.95001 -2.130834 8.878211 79.95001 -2.214482 9.113952 79.95001 -2.240225 9.177592 79.95001 -2.245568 9.188741 79.95001 -2.265659 9.235475 79.95001 -2.313738 9.335664 79.95001 -2.32002 9.349293 79.95001 -2.379008 9.460533 79.95001 -2.785493 10.02434 79.95001 -2.767284 10.00374 79.95001 -2.743216 9.977116 79.95001 -2.000183 8.033134 79.95001 -2.000063 8.064223 79.95001 -2.000732 8.066263 79.95001 -2.002117 8.128211 79.95001 -2.002927 8.132493 79.95001 -2.010277 8.255493 79.95001 -2.872714 10.11577 79.95001 -2.917648 10.16 79.95001 -2.936717 10.17781 79.95001 -2.963461 10.20323 79.95001 -2.996259 10.23272 79.95001 -3.010151 10.24547 79.95001 -3.02658 10.25956 79.95001 -3.057716 10.28673 79.95001 -3.106158 10.32699 79.95001 -3.119678 10.3376 79.95001 -3.155479 10.36626 79.95001 -3.183467 10.38751 79.95001 -3.205681 10.40454 79.95001 -3.248579 10.43568 79.95001 -3.256768 10.44182 79.95001 -3.314968 10.48207 79.95001 -2.740439 9.973421 79.95001 -2.714007 9.94274 79.95001 -2.701837 9.928879 79.95001 -2.687991 9.911705 79.95001 -2.662396 9.880322 79.95001 -2.510843 9.675285 79.95001 -2.476147 9.622565 79.95001 -3.308746 10.47809 79.95001 -3.361621 10.51335 79.95001 -3.382585 10.52665 79.95001 -3.416839 10.54825 79.95001 -2.09609 8.755493 79.95001 -2.072894 8.657304 79.95001 -2.06669 8.631856 79.95001 -2.04672 8.527389 79.95001 -2.042593 8.50731 79.95001 -2.035792 8.46203 79.95001 -2.032527 8.444697 79.95001 -2.03087 8.429265 79.95001 -2.023784 8.381857 79.95001 -2.02631 8.396446 79.95001 -2.018279 8.330667 79.95001 -2.016366 8.318789 79.95001 -2.014809 8.297716 79.95001 -2.011703 8.264727 79.95001 -3.983283 10.82257 79.95001 -3.961649 10.81457 79.95001 -3.953696 10.81175 79.95001 -3.924235 10.80061 79.95001 -2.142314 8.913035 79.95001 -2.150233 8.939223 79.95001 -2.163178 8.975931 79.95001 -2.170997 9 79.95001 -2.185426 9.038352 79.95001 -2.192885 9.059861 79.95001 -2.215964 9.119055 79.95001 -3.894899 10.78917 79.95001 -3.886049 10.78552 79.95001 -3.865688 10.77742 79.95001 -3.848549 10.77023 79.95001 -3.836601 10.76537 79.95001 -3.829878 10.76239 79.95001 -3.807639 10.75301 79.95001 -3.81126 10.75443 79.95001 -3.750091 10.72737 79.95001 -3.737338 10.72134 79.95001 -3.693044 10.70051 79.95001 -3.664708 10.68662 79.95001 -3.646236 10.67719 79.95001 -3.636499 10.67241 79.95001 -3.628197 10.66799 79.95001 -3.592308 10.64923 79.95001 -3.580459 10.64308 79.95001 -3.556675 10.62998 79.95001 -3.552629 10.62795 79.95001 -3.538957 10.62018 79.95001 -3.524927 10.61251 79.95001 -3.521306 10.61026 79.95001 -3.469906 10.58068 79.95001 -3.451381 10.56939 79.95001 44.6102 9.478695 9.003568 44.62221 9.457291 9.003568 44.598 9.5 8.983983 44.62815 9.446552 9.003568 44.63404 9.435789 9.003568 44.63989 9.425002 9.003568 44.6457 9.414191 9.003568 44.69055 9.326867 9.003568 44.69596 9.315849 9.003568 44.70663 9.293748 9.003568 44.70132 9.30481 9.003568 44.75728 9.181977 9.003568 44.76209 9.170687 9.003568 44.76685 9.159379 9.003568 44.77157 9.148051 9.003568 44.71191 9.282666 9.003568 44.73253 9.238121 9.003568 44.73757 9.226934 9.003568 44.74256 9.215724 9.003568 44.75242 9.193245 9.003568 44.89771 8.776457 9.003568 44.90397 8.752724 9.003568 44.91003 8.728941 9.003568 44.92157 8.681229 9.003568 44.92704 8.657304 9.003568 44.93232 8.633336 9.003568 44.9374 8.609323 9.003568 44.94229 8.585272 9.003568 44.97427 8.391579 9.003568 44.97737 8.367233 9.003568 44.98028 8.342862 9.003568 44.98299 8.318468 9.003568 44.98549 8.294052 9.003568 44.99351 8.19621 9.003568 44.99502 8.171712 9.003568 44.99633 8.147204 9.003568 44.99833 8.098157 9.003568 44.99903 8.073624 9.003568 44.99953 8.049085 9.003568 44.99984 8.024544 9.003568 43.64619 10.50796 9.003568 43.65643 10.50121 9.003568 43.63591 10.51467 9.003568 43.5317 10.57947 9.003568 43.54224 10.57319 9.003568 43.49993 10.59808 8.985277 43.58414 10.54761 9.003568 43.59455 10.5411 9.003568 43.60493 10.53456 9.003568 43.62561 10.52134 9.003568 43.87451 10.34221 9.003568 43.88408 10.33452 9.003568 43.89361 10.3268 9.003568 43.90311 10.31903 9.003568 43.66664 10.49441 9.003568 43.82622 10.38006 9.003568 43.83594 10.37257 9.003568 43.84563 10.36504 9.003568 43.86492 10.34986 9.003568 44.10383 10.1386 9.003568 44.11256 10.12998 9.003568 44.12126 10.12132 9.003568 43.97797 10.25552 9.003568 43.98719 10.24741 9.003568 43.99636 10.23926 9.003568 44.0055 10.23108 9.003568 44.01461 10.22285 9.003568 44.05071 10.18959 9.003568 44.59801 9.5 9.003568 44.09506 10.14719 9.003568 44.08626 10.15574 9.003568 44.06856 10.17274 9.003568 44.05965 10.18118 9.003568 41.99997 11 9.003568 43.49993 10.59808 9.003568 43.52114 10.58572 9.003568 41.99993 11 8.987045 41.99997 11 9.221344 44.3975 9.5 6.112143 44.00985 9.5 3.611209 43.17281 9.5 -0.5407877 42.7065 10.12132 -0.4415511 43.3078 10.59808 6.247515 42.92915 10.59808 3.805759 42.09878 10.59808 -0.3122239 41.81924 11 6.432437 41.45288 11 4.07152 40.63164 11 0 42.41564 2.8 61.26302 42.48083 2.8 60.95261 42.48083 8 60.95261 44.58328 3.448722 52.79433 44.77061 3.770995 51.75038 44.54322 8 52.9901 44.82143 8 51.40904 45 3.669722 49 45 8 49 44.99303 3.615221 49.45573 44.86763 3.829289 51.0587 43.04892 2.8 58.66058 44.24975 8 54.27413 44.5432 3.385737 52.99066 43.02904 8 58.73381 42 8 64.95001 42.10369 8 63.19303 42.44761 8 61.10871 40.03318 3.939808 28.17742 40.72212 3.671412 28.97665 41.02895 3.675734 32.35592 41.29512 3.417842 35.74123 40.80213 3.466688 35.91257 37.6314 2.563193 39.08329 39.02676 3.183561 37.68794 42.16956 1.727367 43.13401 41.88554 2.306812 41.27316 41.34966 3.333343 36.39018 41.35535 3.324101 36.45606 41.69674 2.686151 39.81808 40.00536 3.951022 28.14552 38.49895 4.582697 29.65194 36.51378 4.862227 31.6371 36.42191 4.860747 31.72897 34.53137 4.546082 33.61951 33.5997 4.182533 34.55118 32.97329 3.853368 35.17759 -1.884672 8 79.33067 1.878716 8 79.31413 1.736203 8 79.00723 1.529575 8 78.71144 0.994921 8 78.26502 0.3395994 8 78.02904 0.02500194 8 78.00016 -0.3569101 8 78.03211 -1.010132 8 78.27384 -1.540842 8 78.72492 -1.710841 8 78.96414 36.77426 11 85.85816 39 11 87.15404 39 11 64.95001 26.375 11 11 -21.175 11 11 -17 11 50.38321 -2.525331 11 75.6846 18.17606 11 76.77859 19.5127 11 75.66257 4.696791 11 78.28531 -17 11 87.15404 -14.77427 11 85.85816 -12.28775 11 85.18704 -0.8922752 11 75.08026 0.8489986 11 75.07261 41.33725 11 53.55486 17.30321 11 78.28531 21.151 11 75.07261 22.89228 11 75.08026 24.52533 11 75.6846 -21.31233 11 11.5125 -21.6875 11 11.88768 -22.2 11 12.025 -29.8 11 12.025 -30.3125 11 11.88768 -30.68768 11 11.5125 -33.8 10.99997 14.35487 -33.89511 11.00003 16.01221 42 11 49 41.99993 11 9.520451 35.94697 11 11.39225 35.72478 11 11.72478 35.39225 11 11.94698 35 11 12.025 3.823937 11 76.77859 39.12274 11 62.85554 39.51165 11 60.49215 -4.71168 11 78.32666 -3.852104 11 76.81233 2.487303 11 75.66257 40.13344 11 57.94927 26.51233 11 11.5125 26.8875 11 11.88768 27.4 11 12.025 41.85069 11 50.99105 25.8521 11 76.81233 26.71168 11 78.32666 26.99981 11 79.95001 -5 11 87.15404 -7.225733 11 85.85816 -9.712252 11 85.18704 27 11 87.15404 29.22573 11 85.85816 31.71225 11 85.18704 34.28775 11 85.18704 45 6.327876 28.02471 45 5.965644 24.84254 45 0.4124416 13.15892 45 4.289943 46.6902 45 5.175963 21.34926 45 4.671211 19.86154 45 3.923815 18.12157 45 2.849726 16.18872 45 2.185285 15.21321 45 4.943964 44.34032 45 6.009005 40.62665 45 6.211642 39.53195 45 6.53226 36.80147 45 6.627478 34.46321 45 6.376598 28.7553 31.5251 3.190818 36.00158 32.13812 3.435829 35.77436 36.15528 1.052706 41.84077 42.04816 0.8481366 45.42818 37.83142 1.847471 40.7913 32.6872 3.696182 35.43057 26.18765 0.5518227 36.81235 28.01691 2.464837 34.9831 26.19155 0.5518226 36.81626 28.32376 2.473762 35.25934 27.09119 0.5457129 37.66611 28.90155 2.529102 35.64735 29.53433 2.633103 35.92346 28.78878 0.5099603 39.04477 30.19884 2.781943 36.07753 30.75391 0.4525856 40.38113 30.87066 2.970154 36.10389 33.03188 0.3885297 41.72801 34.28483 0.3581465 42.42369 36.6474 0.3113536 43.72424 40.03767 0.2652374 45.73113 41.93184 0.2481039 47.00854 23.88467 8 79.33067 23.54084 8 78.72492 23.32196 8 78.4992 23.01013 8 78.27384 22.35691 8 78.03211 21.6604 8 78.02904 20.12129 8 79.31413 20.47043 8 78.71144 20.64093 8 78.53271 21.00508 8 78.26502 21.49091 8 78.06588 -40.90886 3.246996 27.56734 -38.80218 7.658305 25.90358 -38.88824 7.471623 26.15249 -38.81533 7.46268 26.33189 -38.74573 8.167943 23.95245 -38.73102 8.20798 23.35308 -39.28478 7.513591 22.06581 -38.87295 1.774088 16.82135 -38.93585 1.840618 16.88315 -38.79925 2.540331 16.85589 -40.15491 3.194036 18.56193 -38.74524 3.215174 16.94893 -38.66241 4.86925 17.51456 -38.66948 4.631129 17.39754 -39.21597 4.415881 17.90448 -38.68183 4.302002 17.25725 -38.66739 7.596756 20.39369 -39.48751 6.889032 20.91747 -38.64938 6.881505 19.21051 -39.54253 6.147931 19.81982 -38.64563 6.495517 18.75399 -38.64641 5.823754 18.1336 -38.70479 8.131296 22.17198 -38.69708 8.065855 21.81158 -39.47167 7.268867 24.94336 -38.77191 7.993633 24.9056 -38.75905 8.093419 24.45399 -42.1443 1.301581 22.77778 -42.18244 1.419583 24.09478 -41.91352 1.161561 21.48 -41.7354 1.574044 26.52845 -40.14086 6.55557 22.66524 -40.29387 6.02596 25.51907 -39.73337 6.194047 26.74426 -41.21512 1.617951 27.78178 -38.95581 0.8604274 16.83482 -39.28516 0.9648748 17.12774 -40.76107 1.674353 18.98636 -41.69365 2.331088 21.32605 -40.27242 6.010645 21.46707 -40.24301 5.364038 20.31029 -40.41424 4.76994 27.22101 -41.43746 3.158883 26.31982 -40.95626 4.640499 25.98288 -41.47976 4.185125 23.60275 -40.88237 5.43463 23.18446 -41.50003 3.837241 22.32665 -40.9523 4.982882 21.94313 -41.33855 3.424442 21.0774 -40.84975 4.446839 20.73513 -41.89793 2.612088 22.60527 -41.91374 2.8489 23.90663 -37.85078 4.688513 16.36582 -37.83278 5.553548 16.77719 -37.20718 6.161077 15.7506 -37.82878 9.141086 21.99315 -37.86769 9.085597 22.00605 -38.14189 8.825594 23.73651 -36.89415 3.113212 13.49162 -36.87753 4.414692 13.68929 -37.19652 8.879454 18.23491 -37.20143 8.078536 17.2678 -37.19975 8.884393 18.25674 -37.20494 8.87341 18.26449 -37.20554 8.893167 18.29581 -37.18286 8.858471 18.14266 -37.18197 8.857271 18.13688 -36.91363 8.39924 16.17953 -37.54266 9.172064 20.36231 -37.46833 9.141455 19.92625 -37.83908 8.440616 19.89989 -37.64037 9.188021 20.92631 -38.42844 8.235046 25.32458 -38.18966 8.748974 24.00143 -38.17552 8.772505 23.92301 -38.68129 7.403955 26.72577 -38.54846 7.882889 25.98924 -38.4428 8.196501 25.40416 -38.4383 8.20868 25.37923 -37.94269 2.69964 15.92019 -37.2017 7.177649 16.43598 -36.86119 7.992682 15.41843 -36.86338 6.824615 14.62938 -36.86809 5.679324 14.08086 -37.21883 5.161745 15.27447 -37.24143 4.052178 14.935 -37.27935 2.896445 14.76452 -37.40795 9.104564 19.56612 -37.82931 7.893059 18.94523 -37.82386 7.207656 18.08542 -37.82777 9.203487 22.48488 -37.24059 9.777152 21.17753 -37.83555 9.085 24.21179 -35.87269 10.6924 20.08148 -36.51261 10.3479 21.52291 -37.17995 9.80843 22.92006 -36.12248 10.41074 18.39116 -36.73632 9.840538 18.47013 -36.67641 9.855335 18.24702 -36.44984 10.11703 18.29638 -35.7669 10.63907 18.44516 -35.26352 10.85984 18.57954 -35.25526 10.86087 18.55663 -17.46165 10.75501 1.133513 -15.68543 8.925634 -1.422974 -15.5 7.937254 -1 -16.37868 9.995098 -1.593474 -17.46165 10.6797 -1.702618 -18.5 10.93941 1.152948 -17.46165 9.869385 -4.421567 -18.5 10.80406 -2.066943 -18.5 10.86282 -1.731811 -17.46165 8.379814 -6.836207 -18.5 9.326336 -5.832621 -18.5 10.0386 -4.49738 -18.5 2.957435 -10.59498 -18.5 3.87806 -10.29372 -17.46165 3.812687 -10.1202 -18.5 6.421762 -8.9309 -17.46165 6.313511 -8.780353 -18.5 6.587319 -8.809497 -18.5 8.523493 -6.953421 -18.5 1.067453 -10.94808 -17.46165 1.04946 -10.76353 -18.5 -1.072411 -10.9476 -17.46165 -1.785996 -10.66608 -18.5 -1.816619 -10.84896 -17.46165 -4.498532 -9.834543 -18.5 -4.575664 -10.00316 -18.5 -4.957225 -9.81967 -17.46165 -6.901462 -8.326153 -18.5 -7.019794 -8.468914 -18.5 -8.171626 -7.363731 -17.46165 -8.829406 -6.244726 -18.5 -8.980794 -6.351798 -17.46165 -10.7714 -0.9653428 -18.5 -10.2809 -3.911923 -17.46165 -10.14967 -3.733512 -18.5 -10.3237 -3.797526 -18.5 -10.95609 -0.9818942 -15.5 -7.968064 -0.714105 -15.68543 -1.492658 -8.914246 -15.5 -3.327756 -7.275029 -15.68543 -3.759678 -8.219284 -15.5 -5.105305 -6.15921 -15.68543 -5.767942 -6.958637 -15.5 -6.531487 -4.619489 -15.68543 -7.379234 -5.219071 -15.5 -7.508146 -2.761837 -15.68543 -8.482658 -3.120307 -15.68543 -9.002271 -0.8067916 -15.5 7.900231 -1.259499 -15.5 7.300803 -3.270822 -15.68543 8.248403 -3.695354 -15.5 6.198904 -5.057033 -15.68543 7.003484 -5.713405 -15.5 4.670372 -6.4952 -15.68543 5.276558 -7.338237 -15.5 2.820407 -7.486341 -15.68543 3.186479 -8.458024 -15.5 0.7763298 -7.962243 -15.68543 0.8770927 -8.995694 -15.5 0 -8.000006 -15.5 -1.321177 -7.890151 -16.37868 9.236721 -4.138129 -16.37868 7.842637 -6.397982 -16.37868 5.908792 -8.2175 -16.37868 3.56828 -9.471458 -16.37868 0.9821854 -10.07355 -16.37868 -1.671507 -9.982344 -16.37868 -4.21016 -9.204113 -16.37868 -6.459053 -7.792417 -16.37868 -8.26341 -5.844416 -16.37868 -9.499045 -3.49418 -16.37868 -10.08092 -0.9034606 39.22797 3.399272 -10.46159 39.20208 2.289232 -10.75916 39.18283 0.4548318 -10.99059 39.38315 6.465842 -8.899039 39.32893 5.694534 -9.411285 39.24898 4.043044 -10.23004 39.67766 8.899511 -6.465193 39.58858 8.354314 -7.155798 39.43322 7.043553 -8.449164 40.57062 10.99294 -0.3941347 40.28614 10.76937 -2.240693 40.02487 10.25354 -3.983066 39.7881 9.440814 -5.645444 -36.61457 9.038351 14.35487 -35.77213 10.38481 16.3433 -36.311 9.641609 14.35487 -36.21762 9.961236 16.27939 -36.58938 9.104257 14.35487 -36.56151 9.465703 16.23004 -34.9043 10.78936 14.35487 -35.92133 10.1213 14.35487 -34.68632 10.91156 16.49907 -35.25018 10.70718 16.41818 -34.83835 10.81457 14.35487 -21.175 -10.2809 -3.911923 -21.175 6.587319 -8.809497 -21.175 2.957435 -10.59498 -21.175 10.80406 -2.066943 -21.175 9.326336 -5.832621 -21.175 -8.171626 -7.363731 -21.175 -4.957225 -9.81967 -21.175 -1.072411 -10.9476 30.26643 4.304041 32.73357 31.37604 3.414024 35.55693 30.66456 3.176466 35.66014 32.02869 3.68392 35.28399 32.58458 3.970469 34.85717 29.93559 2.985053 35.58761 29.23151 2.850909 35.34356 28.59321 2.78183 34.94218 28.05782 2.78183 34.40678 27.71601 3.68392 30.97131 28.14283 3.970469 30.41543 27.44307 3.414024 31.62396 27.33986 3.176466 32.33544 30.06285 4.764472 29.61246 30.79181 4.955884 29.68499 29.35136 4.526914 29.71566 28.69871 4.257018 29.98861 33.28433 4.526914 33.64863 33.01139 4.257018 34.30129 33.38754 4.764472 32.93716 23.98898 0.9525223 27.49938 24.90591 1.405268 25.68252 26.3244 2.987132 28.02353 29.81453 0.9525223 19.78294 28.18522 1.252132 21.06863 27.67271 0.9525223 21.09825 39.85216 3.97087 27.56749 39.95882 3.95716 27.93506 38.6766 4.533651 28.7246 37.55501 4.72668 26.94104 38.92924 4.052052 25.8423 39.30685 4.03348 26.43646 39.48266 4.014645 26.73138 39.67013 3.993148 27.1044 39.82302 3.974531 27.48311 38.49735 4.022426 25.15485 36.05896 4.72668 25.44499 38.06952 3.938231 24.46658 34.27539 4.533651 24.3234 37.22683 3.604291 23.0927 37.64593 3.79913 23.77879 35.63146 2.263669 20.43821 36.00261 2.670855 21.06123 35.6806 3.220276 21.81438 36.38637 3.026844 21.70208 36.78241 3.331608 22.35969 35.27339 1.804889 19.83429 33.21974 2.751428 20.9614 35.02758 1.447614 19.41817 34.72433 0.9525223 18.90309 24.66729 0.9525223 25.07918 25.92096 0.9525223 22.9007 26.45922 2.205972 24.48987 28.28292 2.960142 23.72718 30.27101 3.623948 23.43879 27.65644 2.850909 33.7685 27.41239 2.985053 33.06441 26.49057 2.291598 33.35573 25.10808 1.776741 31.67298 36.39928 4.90662 31.51565 33.31501 4.955884 32.20819 35.9239 5.167918 30.14416 33.07096 5.090028 31.5041 35.14205 5.302478 28.90084 32.66958 5.159108 30.86581 34.09916 5.302478 27.85795 31.48435 4.90662 26.60072 30.0644 4.533767 26.45944 28.67851 4.07103 26.66047 27.40721 3.5453 27.19214 24.96134 1.903235 30.37763 25.49301 2.428964 29.10634 31.4959 5.090028 29.92903 32.21439 0.9525223 19.03587 30.67193 2.08242 20.70791 32.30797 4.158812 23.64146 32.85584 5.167918 27.07609 32.13418 5.159108 30.33042 23.92786 0.9525223 30.01209 24.04862 0.8077043 31.79179 24.54876 0.649254 34.08253 24.34794 0.6914616 33.4069 25.87261 0.554039 36.47258 25.75071 0.5562255 36.32625 25.06654 0.587813 35.28903 43.14803 10.77165 9.003568 44.4944 9.666721 9.003568 44.57318 9.542318 9.003568 44.59191 9.510624 9.003568 44.87082 8.870861 9.003568 44.89133 8.800144 9.003568 44.60113 9.494692 9.003568 44.68789 9.332375 9.003568 44.67967 9.348843 9.003568 44.9727 8.403745 9.003568 43.97341 10.25957 9.003568 44.90093 8.764603 9.003568 44.91882 8.69318 9.003568 44.61928 9.462659 9.003568 44.99797 8.110424 9.003568 44.99435 8.183964 9.003568 44.99187 8.220695 9.003568 44.98172 8.33067 9.003568 43.81652 10.38752 9.003568 43.83113 10.37633 9.003568 43.86016 10.35368 9.003568 44.93495 8.621338 9.003568 44.96753 8.440196 9.003568 44.76454 9.165042 9.003568 44.75003 9.198881 9.003568 44.73511 9.232538 9.003568 44.7275 9.249298 9.003568 44.70404 9.29929 9.003568 43.8889 10.33068 9.003568 43.95951 10.27164 9.003568 43.41417 10.64577 9.003568 43.47867 10.61027 9.003568 43.49466 10.60115 9.003568 43.5106 10.59193 9.003568 43.52647 10.58261 9.003568 43.57375 10.55408 9.003568 43.58939 10.54437 9.003568 43.6205 10.52468 9.003568 44.99977 8.036815 9.003568 44.63703 9.430407 9.003568 44.10825 10.13431 9.003568 44.0819 10.16002 9.003568 44.05524 10.1854 9.003568 44.04179 10.19797 9.003568 44.00099 10.23518 9.003568 43.65135 10.5046 9.003568 43.78708 10.40963 9.003568 43.14803 10.77165 49 44.12131 10.12133 49 43.5 10.59808 49 44.77163 9.148058 49 44.59807 9.5 49 41.12132 10.12132 64.95001 41.59808 9.5 64.95001 41.70432 9.5 63.14782 40.61322 10.59808 63.02429 40.5 10.59808 64.95001 42.05426 9.5 61.02611 42.6411 9.5 58.6287 40.97962 10.59808 60.80043 41.58124 10.59808 58.34154 43.85955 9.5 54.17776 42.7935 10.59808 53.9145 44.42343 9.5 51.35304 43.33606 10.59808 51.20004 -2.099865 9.148051 79.25424 -2.712684 10.12132 79.0366 -3.629831 10.77164 78.71088 -2.967622 10.77164 77.54425 -1.945489 10.77164 76.67546 -0.6873998 10.77164 76.20989 -2.217795 10.12132 78.16474 -1.453924 10.12132 77.51547 -0.5137149 10.12132 77.16754 3.61836 10.77164 78.67903 2.704111 10.12132 79.0128 2.09323 9.148051 79.23581 2.945923 10.77164 77.51826 1.916193 10.77164 76.65849 2.201578 10.12132 78.14532 1.432029 10.12132 77.50279 1.704223 9.148051 78.56431 1.108522 9.148051 78.06693 0.65406 10.77164 76.20399 0.4887989 10.12132 77.16312 0.3783751 9.148051 77.804 -1.716776 9.148051 78.57934 -1.12547 9.148051 78.07675 -0.3976623 9.148051 77.80741 23.12547 9.148051 78.07675 23.45392 10.12132 77.51547 22.51372 10.12132 77.16754 23.94549 10.77164 76.67546 22.6874 10.77164 76.20989 24.71268 10.12132 79.0366 25.62983 10.77164 78.71088 24.09987 9.148051 79.25424 21.34594 10.77164 76.20399 20.08381 10.77164 76.65849 19.05408 10.77164 77.51826 18.38164 10.77164 78.67903 21.5112 10.12132 77.16312 20.56797 10.12132 77.50279 19.79842 10.12132 78.14532 19.29589 10.12132 79.0128 24.96762 10.77164 77.54425 24.2178 10.12132 78.16474 23.71678 9.148051 78.57934 22.39766 9.148051 77.80741 21.62162 9.148051 77.804 20.89148 9.148051 78.06693 20.29578 9.148051 78.56431 19.90677 9.148051 79.23581 37.71731 0.7317537 18.76999 41.02202 3.163848 25.28242 41.126 3.016624 24.62024 40.20923 2.667485 22.48151 41.44198 2.497807 22.69905 40.47655 2.835138 23.1564 41.28919 2.762512 23.61274 40.74819 2.955729 23.83684 41.14289 2.991639 24.51423 41.024 3.029275 24.52199 38.96354 1.120571 19.26435 42.17921 0.7733224 18.55228 39.18957 1.511712 19.85759 42.0401 1.166726 19.31187 39.42502 1.860706 20.4708 41.90044 1.525664 20.08248 39.66979 2.167421 21.10343 41.74886 1.87948 20.93079 39.94646 2.452306 21.81294 41.66915 2.052017 21.38282 41.60036 2.193989 21.77675 42.28264 0.4539195 17.99095 41.41347 0.4987869 18.20107 40.56697 0.5467174 18.37561 38.74711 0.6870274 18.69186 40.05915 3.925131 28.14538 40.76704 3.59657 28.16532 40.79413 3.554024 27.69503 40.83346 3.490716 27.1806 40.84406 3.473356 27.05732 40.89852 3.382036 26.47388 40.96309 3.269674 25.83909 43.27526 9.137041 -0.903393 42.63774 10.10696 -0.8024461 42.96448 8.928763 -2.419689 42.68424 8.483449 -3.831885 42.43578 7.798531 -5.164206 42.32016 9.866993 -2.47971 42.03364 9.367293 -4.043988 41.77964 8.605607 -5.522711 41.68848 10.75834 -0.623708 41.38225 10.51154 -2.417029 41.10417 9.985954 -4.096827 40.85566 9.178727 -5.690654 40.64986 8.113412 -7.133489 41.57142 7.604269 -6.857194 42.23195 6.893915 -6.363286 42.07833 5.80947 -7.382411 41.4148 6.406852 -7.995253 40.49306 6.836892 -8.366983 41.97903 4.696478 -8.136455 41.90607 3.335008 -8.775747 41.31387 5.179268 -8.840322 41.24007 3.67809 -9.559316 40.39046 5.527036 -9.28453 40.31406 3.924843 -10.06614 41.86517 1.888785 -9.187864 41.84893 0.3753224 -9.367907 41.19895 2.083289 -10.02426 41.18271 0.4139953 -10.22779 40.27064 2.222878 -10.57199 40.25322 0.4417148 -10.79351 43.34797 0.4571265 48.58606 43.12213 0.4703742 47.87717 44.14027 1.331874 48.17952 44.81589 2.471333 49.39089 44.79135 2.46664 48.57777 44.71432 3 51.76988 44.87656 3 50.32487 44.8991 3 50.11582 42.39552 0.1262366 47.77672 42.38817 0.1299771 47.75775 41.96914 0.2360489 47.06887 43.18946 1.275421 45.58485 42.30941 0.1457901 47.62744 44.17031 2.080491 45.88005 44.79883 3.151922 46.27291 44.80654 3.869524 43.93738 44.20125 2.860094 43.55881 43.25887 2.110705 43.27777 44.76925 4.808746 40.33458 41.35452 3.456619 28.99421 41.98216 3.317029 36.38808 42.92328 2.951826 39.88272 42.64878 3.434509 36.40319 43.30575 3.702116 36.43759 44.03933 3.699087 40.06456 43.90191 4.116617 36.49089 44.73875 5.266026 36.63867 44.31869 4.683385 32.80506 44.71054 5.311452 32.81828 44.23109 4.377727 28.91885 44.67627 5.025543 28.86584 43.60722 3.851888 28.96187 43.76987 4.153203 32.79389 42.86414 3.513317 28.98957 43.10746 3.774306 32.78591 42.08644 3.387831 28.99984 42.39485 3.573421 32.78168 41.69672 3.545118 32.78109 42.1261 3.334491 28.17881 42.89533 3.468379 28.17192 43.62805 3.811397 28.15426 44.24232 4.33752 28.12718 44.68067 4.982821 28.09395 44.30368 4.067163 25.1406 44.70105 4.675948 25.04502 44.70497 4.683977 25.04376 43.74156 3.552465 25.22141 43.06577 3.195273 25.27748 42.34469 3.021574 25.30475 41.61764 3.026117 25.30404 44.82432 1.368585 15.81005 44.78816 2.927204 18.60421 44.11705 2.010768 19.04802 43.45713 0.06779432 16.76012 44.27371 0.6051774 16.36797 43.09731 1.410871 19.33854 42.53834 1.267601 19.40792 42.09225 2.305416 22.21612 42.72595 2.389409 22.19075 43.35681 2.614563 22.12276 43.63581 1.660476 19.21766 43.93348 2.980079 22.01238 44.74668 4.020952 21.69805 43.32263 0.09698009 16.92052 42.35139 0.4235439 17.92772 37.69884 0 16.80665 40.48142 0.1416254 17.56431 34.79521 0.2513826 17.91507 37.70875 0.1911485 17.86033 41.30404 0.1289343 17.42229 34.88123 0 16.71603 32.03846 0.2484156 18.05415 29.40216 0.2484156 18.87483 27.04931 0.2484156 20.31973 25.12497 0.2484156 22.29977 23.74778 0.2484156 24.69288 23.00264 0.2484156 27.35153 22.9355 0.2484156 30.11181 42.26153 0.1259029 47.65146 42.45075 0.07571387 48.02477 -9.95 -10 84.9 -12.05 -10 84.9 -11.525 -7.590673 93.4 -11.90933 -7.975 93.4 -11 -8.5 93.4 -12.05 -8.5 93.4 -11.90933 -9.025 93.4 -10.09067 -7.975 93.4 -10.475 -7.590673 93.4 -11 -7.45 93.4 -10.475 -9.409328 93.4 -10.09067 -9.025 93.4 -9.95 -8.5 93.4 -11.525 -9.409328 93.4 -11 -9.55 93.4 -12.475 6 79.95001 -16.525 6 79.95001 -12.475 4.5 79.95001 -16.525 0 79.95001 -5.475 4.5 79.95001 -5.475 0 79.95001 -8.677126 8.5 99.8854 -8.677126 9.409926 99.8854 -11 9.409926 100.4 -11 8.5 100.4 -13.3244 9.409925 99.8847 -13.32287 8.5 99.8854 -8.534111 8.5 99.78511 -8.534111 9.398838 99.78511 -8.434326 8.5 99.64173 -8.434326 9.366894 99.64173 -8.390213 8.5 99.47592 -8.390213 9.318982 99.47592 -13.60979 9.318982 99.47592 -13.60979 8.5 99.47592 -13.56479 8.5 99.64363 -13.56479 9.367385 99.64363 -13.46515 8.5 99.78585 -13.46515 9.39897 99.78585 -6.617371 8.5 97.82277 -5.776206 8.5 95.57968 -5.846113 8.56032 95.9897 -6.617371 9.046358 97.82277 -16.15389 8.560318 95.98969 -16.22379 8.5 95.57968 -15.38263 8.5 97.82277 -15.38263 9.046358 97.82277 -12.99627 8.5 94.77796 -12.99627 8.4 94.77796 -12.80238 8.4 95.76685 -12.80238 8.5 95.76685 -12.15091 8.4 96.53567 -12.15091 8.5 96.53567 -11.20726 8.4 96.88923 -11.20726 8.5 96.88923 -10.21098 8.4 96.73779 -10.21098 8.5 96.73779 -9.415024 8.4 96.11978 -9.415024 8.5 96.11978 -9.021446 8.4 95.1921 -9.021446 8.5 95.1921 -9.130168 8.4 94.19026 -9.130168 8.5 94.19026 -9.71359 8.4 93.36861 -9.71359 8.5 93.36861 -10.6236 8.4 92.93574 -10.6236 8.5 92.93574 -11.62916 8.4 93.00154 -11.62916 8.5 93.00154 -12.475 8.4 93.54931 -12.475 8.5 93.54931 -12.71951 8.5 94.55516 -17.04278 8.5 93.40512 -17.59535 8.5 94.94012 -17.45793 8.5 94.74633 -12.475 8.5 93.9 -16.525 8.5 92.03219 -12.53812 8.5 94.24965 -17.13692 8.5 93.85691 -6.227636 8.5 90.90277 -8.496297 8.5 89.20056 -7.315706 8.5 89.88185 -16.01497 8.5 91.21217 -14.6396 8.5 89.84992 -13 8.5 89.00509 -12.91227 8.5 88.97605 -5.442203 8.5 92.0963 -4.956336 8.5 93.40804 -4.863084 8.5 93.85691 -4.555724 8.5 94.7231 -4.404645 8.5 94.94012 -12.1 8.5 88.77301 -11.00001 8.5 88.67505 -9.9 8.5 88.77301 -10.2625 6.5 93.62261 -9.722613 6.5 94.1625 -11 6.5 94.9 -9.525001 6.5 94.9 -9.722613 6.5 95.6375 -12.27739 6.5 94.1625 -11.7375 6.5 93.62261 -11 6.5 93.42501 -11.7375 6.5 96.17739 -12.27739 6.5 95.6375 -12.475 6.5 94.9 -10.2625 6.5 96.17739 -11 6.5 96.375 -12.27739 8.4 94.1625 -11.7375 8.4 93.62261 -11 8.4 93.42501 -10.2625 8.4 93.62261 -9.722613 8.4 94.1625 -9.525001 8.4 94.9 -9.722613 8.4 95.6375 -10.2625 8.4 96.17739 -11 8.4 96.375 -11.7375 8.4 96.17739 -12.27739 8.4 95.6375 -12.475 8.4 94.9 -19.38593 8.739487 95.02572 -19.41129 8.720318 94.9602 -18.94026 8.511985 94.83631 -18.72208 8.593173 95.041 -18.46897 8.675383 95.29756 -18.22884 8.739486 95.56527 -19.69466 8.188876 94.24269 -19.69671 8.16504 94.23102 -19.16037 8.421184 94.64377 -19.61946 8.460948 94.46638 -19.66322 8.353923 94.35531 -19.69246 8.212679 94.25522 -19.48041 8.657227 94.79122 -18.98382 8.494707 94.79713 -19.19493 7.254463 93.41997 -19.21405 7.278398 93.48236 -19.26789 7.251549 93.50122 -19.42129 7.596982 93.92934 -19.44746 7.522727 93.87319 -19.38183 7.529383 93.86386 -19.9663 7.727891 93.63182 -19.9879 8.304291 93.90953 -19.63682 8.020673 94.1861 -19.7881 7.580093 93.80569 -19.63082 8.00712 94.18095 -19.62266 7.530829 93.86365 -19.55664 7.850263 94.10852 -19.91238 7.661645 93.70975 -19.88617 8.22151 94.10066 -19.7881 8.185323 94.18421 -19.489 7.719446 94.02717 -19.23186 7.301971 93.53526 -19.27046 7.356136 93.63664 -19.44746 7.2068 93.53214 -19.28915 7.383547 93.68055 -19.35295 7.482301 93.81196 -19.62266 7.217096 93.52502 -19.53994 7.037733 93.17082 -19.33494 7.063425 93.16452 -19.26789 7.091717 93.15756 -19.14473 7.180184 93.13585 -19.13035 7.195086 93.13219 -19.7881 7.279697 93.48178 -19.6807 7.069025 93.16313 -19.62266 7.051028 93.16754 -19.9663 7.467507 93.35207 -19.93576 7.283825 93.11036 -19.91238 7.383326 93.41022 -19.86414 7.189112 93.13362 -19.76817 7.111984 93.15257 -2.37633 7.992305 94.17529 -2.377343 7.560337 93.8883 -2.211904 7.608641 93.82954 -2.599233 7.561666 93.89627 -2.602404 7.556281 93.89102 -2.552537 7.552392 93.89796 -2.000418 7.50224 93.05672 -2.060021 7.291264 93.10853 -2.0337 7.447067 93.32123 -2.087621 7.360826 93.37625 -2.135846 7.18912 93.13362 -2.211904 7.254662 93.44397 -2.194257 7.137607 93.14627 -2.211904 7.124944 93.14938 -2.31925 7.069033 93.16312 -2.377343 7.19053 93.4849 -2.414586 7.043313 93.16944 -2.552537 7.179982 93.49162 -2.552537 7.038862 93.17053 -2.657337 7.060859 93.16514 -2.732112 7.225826 93.46237 -2.732112 7.09171 93.15756 -2.869647 7.195083 93.13219 -2.815358 7.242253 93.3833 -2.771715 7.297145 93.52498 -2.730042 7.355421 93.63544 -2.711146 7.383107 93.67988 -2.578867 7.596707 93.92909 -2.443635 7.850891 94.10895 -2.531651 7.680656 93.99874 -2.551525 7.644831 93.97045 -2.0337 7.753557 93.65326 -2.064372 8.250217 94.03442 -2.087621 7.688601 93.73227 -2.23195 8.180013 94.19653 -2.303287 8.16507 94.23104 -3.771158 8.739486 95.56527 -3.336935 8.61355 95.09887 -2.614079 8.739488 95.02572 -3.32103 8.608129 95.08318 -2.544471 8.681855 94.85077 -3.067156 8.514904 94.84305 -2.474632 8.606416 94.6859 -2.407834 8.51077 94.53102 -2.838542 8.420734 94.64287 -2.559598 8.293511 94.41815 -2.305341 8.18889 94.2427 -2.307541 8.212679 94.25522 -2.351653 8.395926 94.39484 -2.386354 8.472312 94.48032 -12.475 8.4 93.9 -12.71951 8.4 94.55516 -12.53812 8.4 94.24965 -18.90922 7.694948 93.78565 -19.04209 7.711924 93.9102 -18.56937 7.86729 93.55454 -18.69841 7.73442 93.5033 -18.41189 8.112804 94.02519 -18.40438 8.144192 94.10848 -18.50018 8.122793 94.18968 -19.10551 8.280365 94.53455 -18.66455 8.344257 94.67936 -18.39376 8.480696 94.90688 -18.38431 8.483117 94.91049 -18.37562 8.498843 94.94373 -18.32338 8.570812 95.10353 -18.20706 8.675964 95.38285 -18.26078 8.633299 95.25989 -18.27673 8.618904 95.22182 -18.43108 8.279341 94.48265 -18.43182 8.298502 94.52592 -18.4201 8.388618 94.71582 -18.41092 8.4202 94.78045 -18.40025 8.44904 94.83966 -18.38635 8.479188 94.90225 -18.94203 8.197619 94.47387 -18.79356 8.147405 94.39861 -18.64455 8.121463 94.30335 -18.41024 8.202863 94.27964 -18.40451 8.187191 94.23081 -18.79272 7.703168 93.64695 -18.45171 8.023335 93.80503 -18.50052 7.944628 93.62528 -19.62862 8.008738 94.18246 -19.47691 7.898868 94.15016 -19.33318 7.817526 94.09578 -19.18662 7.75396 94.0156 -18.4206 8.088348 93.96298 -3.549992 8.026434 93.81234 -3.434408 7.985476 93.94601 -3.588136 8.112875 94.02538 -2.841115 7.48743 93.70639 -2.57094 7.926337 94.17525 -3.585124 8.371092 94.6841 -3.582933 8.367884 94.67675 -3.300865 8.203955 94.46259 -3.57224 8.352224 94.64088 -3.450104 8.18525 94.36601 -3.589752 8.202855 94.27964 -3.478979 8.541767 95.02569 -3.650857 8.502466 94.94716 -3.15165 8.247836 94.54031 -3.663268 8.485536 94.94626 -3.644701 8.458345 94.88397 -3.642644 8.455332 94.87706 -3.593076 8.382739 94.71077 -3.776783 8.651783 95.32707 -3.742259 8.601222 95.21125 -3.693918 8.530426 95.04908 -3.673601 8.50067 94.98092 -3.792997 8.675528 95.38146 -2.986795 8.324601 94.60499 -2.863037 8.090984 94.34494 -2.861956 7.786908 94.03654 -3.504022 7.951324 93.64017 -3.49948 7.944618 93.62526 -3.349373 7.783852 93.5231 -3.366688 7.794329 93.49247 -3.054758 7.481684 93.42347 -3.139334 7.735708 93.80469 -3.593179 8.195223 94.25537 -3.158187 7.987963 94.18479 -18.36661 8.131237 93.98484 -17.87162 8.355965 93.73209 -18.01882 8.424287 94.5969 -17.80985 8.470419 94.65641 -17.76795 8.433513 94.227 -18.22712 8.327206 94.42807 -18.35415 8.224975 94.26665 -17.95936 8.560323 95.1478 -17.94791 8.554214 95.13407 -17.77951 8.513184 95.03282 -17.90829 8.539834 95.1025 -18.16873 8.632414 95.26885 -18.35935 8.437804 94.80424 -18.31814 8.428194 94.77038 -18.08363 8.591715 95.18481 -4.050513 8.554957 95.13572 -4.196212 8.516889 95.04485 -3.686913 8.42724 94.76657 -3.66639 8.431356 94.78234 -4.035095 8.561372 95.14839 -4.040626 8.560328 95.14781 -3.912016 8.592896 95.18658 -3.981164 8.42428 94.59688 -3.77604 8.32901 94.43063 -3.840896 8.6262 95.25431 -16.525 1.065431 85.32013 -16.525 1.097699 85.37628 -16.78656 1.090434 85.55004 -19.18254 1.050826 87.55821 -19.22576 1.00364 87.52654 -17.91218 0.952255 86.30997 -19.1722 1.066654 87.56517 -17.97613 1.107235 86.46747 -18.00935 1.105806 86.49487 -17.8802 1.024362 86.35592 -19.13043 1.184357 87.58605 -19.13537 1.158462 87.58519 -16.525 1.135859 85.41751 -16.525 1.170739 85.44255 -16.76698 1.167804 85.59545 -16.525 1.20348 85.45837 -17.86708 1.113291 86.37921 -17.10836 1.153125 85.82086 -17.10775 1.192329 85.82952 -16.76353 1.231642 85.61212 -16.525 1.253273 85.47113 -16.525 1.040888 85.22087 -16.525 1.052361 85.28369 -16.82047 1.036128 85.48497 -17.15514 1.009312 85.72321 -17.12359 1.071063 85.78258 -19.13757 1.149476 87.58447 -17.27329 0.9761614 85.7507 -17.94671 0.9204065 86.28141 -18.57576 0.9180271 86.82995 -19.26355 0.9790191 87.4966 -3.646018 8.170079 94.09488 -4.187231 8.388828 93.88395 -4.232015 8.449958 94.38932 -3.582806 8.038136 93.74221 -4.128379 8.355962 93.73207 -17.84339 9.552564 98.20986 -19.02682 9.095395 96.27211 -19.24741 8.928083 95.66204 -15.95542 9.880118 100.0832 -13.46619 9.532044 100.1888 -13.97657 9.97159 101.2833 -12.02078 9.97159 101.8688 -11 9.97159 101.9432 -8.023433 9.97159 101.2833 -9.979223 9.97159 101.8688 -6.044576 9.880118 100.0832 -2.753644 8.929163 95.66581 -2.973183 9.095395 96.27211 -4.156607 9.552564 98.20986 -10.66189 11.49627 88.8024 -10.32572 11.5 88.9809 -10.12899 11.5 89.00663 -13.86586 11.4 88.81567 -15.11851 11.4 89.58303 -14.64814 11.5 90.19028 -13.53856 11.5 89.51055 -11.87101 11.5 89.00663 -11.98332 11.4 88.24678 -11.67428 11.5 88.9809 -11.19616 11.49468 88.76713 -10.01669 11.4 88.24678 -8.461447 11.5 89.51055 -8.134141 11.4 88.81567 -7.351861 11.5 90.19028 -6.881489 11.4 89.58303 -14.70646 11.5 90.23703 -16.52951 11.38531 91.71788 -15.81617 11.5 92.19513 -15.35015 11.5 91.02996 -16.21247 11.5 94.13834 -17.02542 11.38531 94.01955 -17.7762 11.05001 93.90984 -16.87691 11.28008 91.80598 -15.89342 11.38174 90.32252 -16.07651 11.37086 90.54552 -13.60979 11.5 99.47592 -8.466541 11.49571 99.70079 -8.390213 11.5 99.47592 -8.640438 11.49112 99.8665 -8.677126 11.4955 99.8854 -5.732177 11.5 94.89344 -5.787528 11.5 94.13834 -5.826847 11.5 93.87876 -6.251409 11.5 91.97337 -16.26657 11.5 94.78497 -13.60442 11.49981 99.51767 -5.991729 11.5 96.53317 -6.748696 11.5 98.0107 -7.927898 11.5 99.17928 -12.76539 11.491 100.109 -11.05662 11.491 100.3997 -9.342239 11.491 100.1442 -16.04084 11.5 96.4297 -15.31445 11.5 97.9225 -14.15956 11.5 99.11511 -13.50801 11.49455 99.73709 -13.32287 11.4955 99.8854 -6.738407 11.5 90.88072 -16.5 7.944444 89.64302 -16.61201 8.357628 90.77313 -17.2964 7.944498 90.62914 -17.6084 8.357628 92.69664 -18.05967 7.944567 92.06364 -15.0729 8.357628 89.24871 -13.13993 8.357628 88.27079 -11.00001 8.357628 87.93395 -8.860089 8.357628 88.27079 -6.92711 8.357628 89.2487 -5.388002 8.357628 90.77311 -4.391606 8.357628 92.69662 -3.904297 7.944598 92.15512 -6.876737 7.944507 88.50598 -5.683129 7.944535 89.45802 -4.648991 7.944567 90.71091 -15.4484 7.944444 88.72768 -13.33722 7.944444 87.65961 -11.00001 7.944444 87.29174 -9.9 7.944444 87.37167 -8.328549 7.944476 87.77619 -19.63896 9.566286 95.58785 -19.37532 9.87877 95.97737 -19.75154 9.450699 94.86997 -19.36881 9.814373 96.24488 -19.27273 9.947851 96.1658 -19.7883 9.363241 94.90268 -19.8072 9.247939 94.9409 -19.65812 9.429047 95.63258 -19.48808 8.769891 95.03341 -19.47021 9.039229 95.69216 -19.61403 8.843555 95.03191 -19.56787 9.147164 95.68836 -19.71422 8.948118 95.01672 -19.63432 9.282758 95.66794 -19.7826 9.081137 94.98759 -19.80743 9.226061 94.9476 -19.40983 9.587201 96.32264 -19.38941 9.468082 96.34396 -19.34279 9.354817 96.35162 -19.18361 9.172376 96.32495 -19.80969 8.557074 94.39761 -19.84742 8.443392 94.26985 -19.66952 8.585347 94.5656 -19.76283 8.649281 94.53798 -19.91615 9.033066 94.28696 -19.86078 9.173767 94.61323 -19.82861 9.288738 94.55007 -19.99896 8.487422 93.8684 -19.97949 8.355715 93.96926 -19.87318 8.27026 94.14011 -19.81538 8.245559 94.18949 -19.93803 8.9482 94.15325 -19.98297 8.696295 93.97143 -19.98515 8.667213 94.00733 -19.96874 8.587402 94.10588 -19.92085 8.510441 94.19606 -19.91607 8.295081 94.09049 -19.84222 8.732919 94.49291 -19.82567 8.949305 94.71679 -19.76272 8.844974 94.75554 -19.67735 8.758917 94.78076 -19.57989 8.69622 94.79204 -19.92574 8.997894 94.19824 -19.92264 8.934225 94.36124 -19.8977 8.830869 94.43226 -19.75664 9.441286 94.84654 -19.86491 1.076982 87.5746 -19.8217 1.073574 87.61479 -19.76392 1.110035 87.66336 -19.98484 0.8763864 87.26623 -19.95537 1.024869 87.43051 -19.76991 0.7504258 87.37032 -19.65578 0.764006 87.3591 -19.63595 0.8599888 87.48121 -19.91548 0.9564331 87.47136 -19.88341 0.7795366 87.34626 -19.84969 0.896705 87.49392 -19.84675 0.7648242 87.35842 -19.76821 0.8563552 87.49435 -19.68683 0.8404068 87.47484 -19.56666 0.9239552 87.55622 -19.96963 0.8504354 87.28767 -19.95956 0.8374139 87.29844 -19.94081 0.817999 87.31448 -19.92992 1.043685 87.48239 -19.7664 1.00075 87.62124 -19.64656 1.067753 87.70124 -19.67959 1.129189 87.70879 -19.51042 1.10832 87.73427 -19.3465 1.172383 87.72505 -19.46225 1.161122 87.74623 -19.56911 1.147643 87.74063 -19.35547 1.131597 87.7176 -19.21324 1.137413 87.64707 -19.16015 1.183693 87.61634 -19.36631 0.97921 87.56548 -19.27897 1.001254 87.5623 -19.69812 0.9440349 87.60152 -19.63008 0.9116304 87.56174 -19.59815 0.9997708 87.66532 -19.55165 0.9558445 87.60913 -19.48574 1.033304 87.68929 -19.46571 0.982132 87.62424 -19.35817 1.05261 87.67269 -19.36918 0.9973615 87.6088 -19.24012 1.057471 87.61316 -19.47639 0.960171 87.58372 -18.4677 0.7110046 86.40731 -16.94388 0.9498139 85.26879 -16.525 0.9268653 84.62847 -17.18937 0.7110046 85.07284 -16.525 0.6425546 84.03333 -16.525 0.4778812 83.84371 -17.34356 0.3692808 84.94977 -16.525 0.2731142 83.70359 -17.38446 0.04999995 84.91712 -16.525 0.04999995 83.65311 -19.61023 0.05000001 86.97063 -18.63166 0.04999995 86.21909 -19.62047 0.4059969 87.05633 -18.59728 0.3692808 86.25856 -19.64149 0.6543256 87.23503 -4.139648 1.120409 86.38994 -4.132701 1.11187 86.3792 -4.026223 1.108967 86.4691 -5.475 1.07093 85.33209 -4.809847 1.032522 85.79237 -4.82384 1.067247 85.81972 -2.869559 1.184357 87.58605 -3.556156 1.108687 86.87754 -2.863858 1.155007 87.58499 -3.536378 1.020549 86.86113 -2.827651 1.066357 87.56508 -2.815888 1.048577 87.55713 -3.496726 0.9479164 86.82263 -2.774029 1.003452 87.52638 -5.475 1.040888 85.22087 -4.767956 0.9803331 85.71994 -5.475 1.052269 85.28337 -5.475 1.113824 85.39595 -4.833543 1.106962 85.84154 -5.475 1.131512 85.41366 -4.838603 1.149847 85.85697 -4.839016 1.193899 85.86564 -5.475 1.200338 85.45713 -5.360457 1.243563 85.5379 -5.475 1.253013 85.47109 -3.997898 1.106109 86.48887 -4.119711 1.024054 86.35579 -4.087671 0.9520404 86.30979 -2.736445 0.9790189 87.4966 -3.402874 0.9190438 86.84957 -4.053287 0.920407 86.28142 -4.792505 1.004589 85.76123 -5.475 1.063253 85.31497 -4.856027 1.192677 85.88995 -16.14994 10.63677 100.239 -16.07848 10.76396 100.1294 -18.04197 10.42331 98.18107 -14.02047 10.85909 101.3774 -14.07607 10.73264 101.4967 -14.08393 10.70473 101.5135 -16.18898 10.41011 100.3192 -14.11383 10.50603 101.5776 -16.15544 10.16917 100.3066 -14.10187 10.26409 101.552 -14.05338 10.0871 101.448 -16.05727 9.971138 100.2042 -14.04301 10.06424 101.4258 -17.97901 9.637723 98.29736 -18.11469 9.829247 98.36253 -18.12856 10.29349 98.27568 -18.16882 10.06661 98.35469 -9.942402 10.70473 102.1202 -9.964168 10.85909 101.9716 -12.03583 10.85909 101.9716 -9.952879 10.0871 102.0486 -12.04712 10.0871 102.0486 -7.979533 10.85909 101.3774 -7.916066 10.70473 101.5135 -7.88631 10.5086 101.5773 -9.931957 10.49493 102.1915 -7.885608 10.49493 101.5788 -9.935694 10.27459 102.166 -7.896506 10.27459 101.5555 -7.946616 10.0871 101.448 -12.0576 10.70473 102.1202 -12.06804 10.49493 102.1915 -12.06431 10.27459 102.166 -3.871836 10.29442 98.27517 -3.831111 10.06916 98.3542 -2.631627 9.815316 96.24444 -2.590037 9.589716 96.32205 -2.610592 9.468083 96.34396 -3.8837 9.832924 98.36301 -2.655286 9.358375 96.35159 -4.017266 9.641145 98.29953 -2.812066 9.175562 96.32612 -5.939976 9.974726 100.2074 -5.843445 10.17293 100.3076 -5.811052 10.41267 100.3188 -5.850398 10.63769 100.2384 -2.727272 9.947851 96.1658 -3.958033 10.42331 98.18107 -5.921521 10.76396 100.1294 -14.65233 11.38531 99.7725 -12.95457 11.38531 100.6672 -11.06269 11.38531 100.9891 -9.164587 11.38531 100.7062 -7.448771 11.38531 99.84667 -6.08566 11.38531 98.49584 -5.210636 11.38531 96.78787 -4.910604 11.38531 94.89241 -4.151848 11.05001 94.89146 -4.223802 11.05001 93.90985 -4.974587 11.38531 94.01955 -4.489265 11.05001 97.0231 -5.47332 11.05001 98.9439 -7.006278 11.05001 100.463 -8.935889 11.05001 101.4297 -11.0705 11.05001 101.7478 -13.19812 11.05001 101.3858 -15.10741 11.05001 100.3796 -15.98733 11.38531 98.39389 -16.60877 11.05001 98.82925 -16.82701 11.38531 96.66828 -17.55307 11.05001 96.8886 -17.08795 11.38531 94.76702 -17.84653 11.05001 94.75045 -6.034978 11.38531 90.45552 -5.965394 11.37363 90.49263 -5.329577 11.38531 92.20222 -5.113342 11.27843 91.82453 -5.948684 11.10042 88.37878 -7.822498 11.10042 87.28781 -9.915863 11.10042 86.72279 -12.08414 11.10042 86.72279 -14.1775 11.10042 87.28781 -16.05132 11.10042 88.37878 -18.03951 10.81415 91.36478 -18.40275 10.65185 92.98032 -18.8 10.4 94.9 -17.96127 10.84183 91.02986 -16.76487 11.14213 90.04239 -17.88055 10.86786 90.68843 -17.96885 10.83925 91.06217 -12.79478 6.622629 86.30236 -11.00007 6.861519 86.30236 -15.08226 6 86.63349 -14.57736 6 86.4028 -15.47215 7.645157 88.37686 -6.528003 7.645246 88.37686 -3.693432 7.183207 90.89805 -2.869566 4.657988 89.13813 -2.86956 5.787574 90.274 -2.869553 6.647323 91.62755 -4.68398 6.209383 88.37686 -3.279722 4.341181 88.37686 -2.869573 3.309217 88.27088 -2.86958 1.806905 87.71451 -4.34774 1.681632 86.30236 -5.475 4.5 86.52 -5.475 2.920343 85.8476 -5.019179 3.363069 86.30236 -5.5 4.5 86.50357 -6.107044 4.810346 86.30236 -7.063942 4.5 85.66651 -12.5 6 85.8033 -12.475 6 85.79921 -12.475 5.267948 85.35678 -12.475 4.5 84.97154 -12.1 4.5 84.92303 -11.66816 4.5 84.88484 -9.9 4.5 84.92303 -9.205351 6.622664 86.30236 -8.589306 4.5 85.15636 -7.535589 5.922695 86.30236 -16.525 6 87.51933 -17.31614 6.209258 88.37686 -16.525 5.763355 87.33309 -17.65229 1.681499 86.30236 -16.525 2.936981 85.85298 -16.98089 3.362949 86.30236 -16.525 4.303596 86.41747 -19.13042 2.728104 88.01133 -18.72036 4.341027 88.37686 -19.13045 7.017164 92.52194 -18.30671 7.183063 90.89805 -19.13044 6.341961 91.06915 -19.13044 6.229709 90.88919 -19.13043 5.369221 89.79437 -19.13043 4.146322 88.75963 -13 6 85.9 -19.69691 0.6415332 87.24919 -19.6828 0.5092888 87.14342 -19.67176 0.3627617 87.06333 -19.66479 0.2092344 87.01422 -19.69416 0.05000001 87.00698 -19.95058 0.7053512 87.17869 -19.89788 0.6702207 87.21752 -19.98448 0.7473144 87.1323 -19.83212 0.6470296 87.24314 -19.76228 0.6379178 87.25321 -19.73622 0.358168 87.0746 -19.72886 0.2064711 87.02802 -19.72626 0.05000001 87.01216 -19.86733 0.05000001 86.98405 -19.81204 0.05000001 87.00547 -19.80711 0.3605412 87.06884 -19.87612 0.3709756 87.04335 -19.934 0.3886229 87.00023 -19.97424 0.4108422 86.94592 -19.99529 0.4343597 86.88842 -19.74775 0.504335 87.15117 -19.98327 0.05000001 86.8532 -19.91613 0.05000001 86.95011 -19.80907 9.285041 93.90612 -19.27273 9.971098 93.83267 -19.86641 8.885254 92.49893 -19.27273 9.958243 93.71873 -19.53332 9.606954 93.1261 -19.81723 8.220167 94.17555 -19.98016 8.324509 93.95165 -19.91739 8.26713 94.07478 -19.9762 5.756629 89.94793 -19.25066 6.611435 91.77548 -19.9762 6.865461 91.65544 -19.86395 6.6933 91.7368 -19.68056 6.581721 91.78952 -19.46189 6.552531 91.80332 -19.25066 2.317903 87.96451 -19.46189 2.297252 88.0263 -19.68056 2.307486 87.99568 -19.9762 2.406962 87.69803 -19.86395 2.346604 87.87863 -19.9762 4.233977 88.59641 -19.86395 5.612274 90.07211 -19.68056 5.518716 90.15259 -19.46189 5.49424 90.17365 -19.25066 5.543631 90.13116 -19.86395 4.127804 88.75448 -19.68056 4.058992 88.85693 -19.46189 4.040991 88.88374 -19.25066 4.077318 88.82965 -5.475 0.05588293 83.65315 -5.475 0.04999995 83.65311 -4.615526 0.04999995 84.91713 -2.510773 0.9564898 87.58248 -2.624387 0.9783393 87.56899 -3.532267 0.7110046 86.40734 -2.344216 0.7640079 87.3591 -2.423465 0.917934 87.54986 -2.362456 0.8573679 87.47795 -2.343827 0.7668761 87.36288 -3.402688 0.3692809 86.25859 -3.36831 0.04999995 86.21912 -2.389761 0.04999995 86.97061 -2.389174 0.1375815 86.97563 -2.381602 0.3685107 87.03882 -2.362021 0.6221893 87.20484 -5.475 0.2271351 83.68482 -4.656432 0.3692809 84.94979 -5.475 0.4156218 83.79087 -4.810616 0.7110046 85.07286 -5.475 0.6216115 84.00473 -5.056107 0.949814 85.26881 -5.475 0.8309162 84.37019 -2.225106 0.9937691 87.61257 -2.149889 0.8957426 87.49278 -2.084036 0.9553516 87.47009 -2.258557 0.7499325 87.37073 -2.218006 0.7514027 87.36952 -2.231433 0.8555395 87.49336 -2.074609 1.046477 87.49033 -2.135195 1.077025 87.57472 -2.16879 1.065692 87.6049 -2.231163 1.108734 87.66001 -2.716631 1.05721 87.64077 -2.334955 0.7612884 87.36135 -2.312886 0.8397367 87.47401 -2.364198 0.9069462 87.55621 -2.687785 1.001041 87.5836 -2.608525 0.9948791 87.61524 -2.513519 0.9771258 87.62329 -2.432861 0.9492103 87.60295 -2.679429 1.174489 87.71611 -2.456357 1.100602 87.73067 -2.537804 1.161122 87.74623 -2.608822 1.127835 87.72638 -2.734881 1.137104 87.68011 -2.329352 1.057567 87.6899 -2.318498 1.128814 87.70797 -2.453141 1.150737 87.74377 -2.043923 1.02401 87.42881 -2.048399 1.027787 87.4391 -2.001463 0.958072 87.25203 -2.002502 0.915212 87.23416 -2.023588 1.003122 87.37234 -2.015163 0.8763912 87.26624 -2.028132 0.8536854 87.28501 -2.05919 0.8179988 87.31449 -2.089772 0.7945907 87.33383 -2.107336 0.7842686 87.34236 -2.291294 1.1232 87.69542 -2.612392 1.04948 87.68048 -2.486905 1.026922 87.68707 -2.38186 0.9913363 87.65655 -2.294731 0.9381936 87.5944 -2.345664 8.780303 94.84611 -2.409796 8.825829 95.03335 -2.218741 8.61693 94.484 -2.166356 8.491841 94.31935 -2.091864 8.563808 94.25151 -2.28094 8.712232 94.66299 -2.248455 9.4507 94.86997 -2.211697 9.363243 94.90268 -2.155215 9.248688 94.48962 -2.192573 9.226062 94.9476 -2.075256 9.001721 94.20187 -2.075913 9.004234 94.20426 -2.071796 8.989221 94.21267 -2.112394 9.115652 94.45644 -2.11013 9.009678 94.52043 -2.02466 8.732233 94.07418 -2.028589 8.778544 94.02308 -2.061818 8.947532 94.15267 -2.020514 8.355715 93.96927 -2.00104 8.487301 93.86834 -2.042609 8.646467 94.1673 -2.08393 8.295081 94.09049 -2.184613 8.245558 94.18949 -2.217399 9.081138 94.98759 -2.193547 8.97072 94.79188 -2.258606 8.865866 94.82538 -2.285777 8.948119 95.01672 -2.385967 8.843555 95.03191 -2.198536 8.798075 94.62876 -2.139284 8.9003 94.57989 -4.206422 11.04076 93.92588 -17.75263 10.97421 96.62297 -4.24737 10.97421 96.62297 -2.727273 9.971097 93.83267 -2.727273 9.958243 93.71873 -2.879335 10.12188 94.12384 -3.2 10.4 94.9 -2.31204 9.55513 95.13549 -2.362194 9.567469 95.59197 -2.343027 9.430231 95.6367 -2.366819 9.28393 95.67203 -2.433249 9.148318 95.69239 -2.530889 9.04036 95.69611 -3.958427 10.81338 91.37368 -4.038463 10.84173 91.03101 -4.088079 10.85833 90.98857 -5.27045 11.14794 90.014 -4.057839 10.84822 90.94868 -4.520786 10.96148 89.04126 -18.0251 10.81943 51.10099 -18.7283 10.45214 51.59337 -19.10929 10.13329 51.86014 -19.712 9.282606 52.28216 -2.30896 0.1338604 87.01071 -2.305306 0.04999995 87.0071 -2.186732 0.04999995 87.00515 -2.278067 0.6062481 87.22402 -2.18912 0.6100675 87.21945 -2.105304 0.6347926 87.1898 -2.042707 0.6758547 87.14052 -2.219965 0.133305 87.01591 -2.132649 0.04999995 86.98404 -2.131968 0.1362346 86.98825 -2.082394 0.04999995 86.94879 -2.061827 0.1421158 86.93276 -2.015771 0.04999995 86.85068 -2.014843 0.1505244 86.85343 -2.127379 0.2965917 87.01881 -2.214793 0.2878236 87.04712 -2.303895 0.2888016 87.04389 -2.010245 0.5176127 86.95185 -2.052461 0.4793457 87.02481 -2.119206 0.4515573 87.0778 -2.205421 0.4362587 87.10697 -2.294579 0.4362582 87.10697 -2.136055 2.346608 87.87863 -2.023802 4.233979 88.59642 -2.319437 6.581723 91.78952 -2.538107 6.552531 91.80332 -2.74933 6.611432 91.77548 -2.136055 6.693301 91.7368 -2.023802 6.86546 91.65544 -2.023802 5.756629 89.94793 -2.023802 2.406965 87.69803 -2.319437 2.30749 87.99568 -2.538107 2.297255 88.02631 -2.74933 2.317905 87.96452 -2.136055 4.127807 88.75448 -2.319437 4.058996 88.85693 -2.538107 4.040993 88.88374 -2.74933 4.077318 88.82965 -2.136055 5.612276 90.07211 -2.319437 5.518718 90.15259 -2.538107 5.494241 90.17365 -2.74933 5.543629 90.13117 -2.01984 8.32453 93.95166 -2.082609 8.267148 94.07478 -2.182764 8.220183 94.17555 -2.380771 9.462752 92.96124 -2.190932 9.285041 93.90611 -2.191529 9.054746 92.61192 -2.080366 8.689736 92.38454 -19.85951 -7.889184 87.50154 -19.90732 -7.923341 87.44403 -18.22959 -7.938191 85.75965 -16.94695 -7.971325 84.75282 -16.26334 -7.987675 84.29141 -16.17951 -7.938191 84.46038 -18.44431 -8 85.48818 -17.63148 -7.999892 84.89883 -19.97546 -7.969582 87.30877 -19.81019 -7.851704 87.54618 -18.00565 -7.707107 86.04278 -19.6591 -7.721494 87.62805 -16.73993 -7 85.51634 -17.82395 -7 86.27251 -17.86229 -7.346117 86.22402 -19.13043 -7 87.49082 -19.13287 -7.005202 87.49346 -19.24551 -7.213155 87.58443 -19.32978 -7.341098 87.62417 -19.45425 -7.503365 87.65193 -15.88889 -7 85.04614 -15.91636 -7.346117 84.99076 -16.01906 -7.707107 84.78376 -16.04746 -7.999783 84.02655 -15.18097 -8 83.84321 -15.16009 -7.938191 84.18869 -14 -8 84.00932 -15.13831 -7.707107 84.54902 -15.12437 -7.346117 84.77969 -14.33333 -7 84.95212 -14.90547 -7 84.83998 -15.12064 -7 84.84139 -14.16667 -7.866025 84.48072 -14.2357 -7.707107 84.67598 -14.28868 -7.5 84.82582 -14.31273 -7.346117 84.89385 -13.91234 -7.868884 84.6684 -13.99894 -7.523157 84.97611 -13.00001 -8.996537 86.82926 -13.01135 -8.835378 86.56856 -13.00767 -8.876387 86.53476 -13.16136 -8.400229 85.83827 -13.11096 -8.542173 85.70538 -13.00001 -8.994227 86.83114 -13.01023 -8.752775 86.63575 -13.0122 -8.794136 86.60225 -13.14795 -8.084345 86.08283 -13.17386 -8.245539 85.96581 -13.21465 -7.911786 85.93635 -13.25025 -8.108119 85.80148 -13.25049 -7.83306 85.86862 -13.56773 -7.745383 85.34075 -13.13376 -8.50037 85.59937 -13.23201 -8.293065 85.64828 -13.16098 -8.455893 85.48565 -13.52361 -8.018767 85.10897 -13.37987 -8.215502 84.84244 -13.57379 -7.988337 85.03896 -13.42009 -8.185317 84.75563 -13.50649 -7.431004 85.50754 -13.56013 -7.370632 85.44966 -13.62279 -7.703214 85.28186 -13.91347 -7.10175 85.15863 -13.95675 -7.53484 85.00346 -13.96242 -7.078943 85.12794 -13 -9 86.83775 -13.87479 -7.875457 84.70216 -13.49424 -8.137325 84.61203 -13.6851 -8.050876 84.31906 -13.72182 -8.039472 84.27304 -2.867133 -7.005202 87.49346 -2.869565 -7 87.49082 -4.186796 -7 86.26402 -4.005383 -7.707107 86.03407 -2.545746 -7.503365 87.65193 -4.139648 -7.382683 86.20426 -2.643575 -7.378187 87.63298 -2.749197 -7.221737 87.58751 -2.092683 -7.923341 87.44403 -2.138914 -7.890347 87.4999 -3.804441 -7.92388 85.77937 -2.18981 -7.851704 87.54618 -2.340899 -7.721494 87.62805 -2.024547 -7.969582 87.30877 -3.567414 -8 85.47892 -6.062705 -7.453886 84.94854 -5.260067 -7 85.51634 -6.111122 -7 85.04613 -7.080421 -7.453886 84.73034 -7.711325 -7.5 84.82582 -7.804008 -7.808878 84.56366 -7.833333 -7.866025 84.48072 -7.076267 -7 84.83921 -7.666666 -7 84.95212 -7.70298 -7.453886 84.84941 -8.432268 -7.745383 85.34075 -8.476394 -8.018767 85.10897 -8.426215 -7.988337 85.03896 -8.278182 -8.039472 84.27304 -8.999995 -8.996537 86.82926 -8.992331 -8.876387 86.53476 -8.988652 -8.835378 86.56856 -8.889041 -8.542173 85.70538 -8.838638 -8.400229 85.83827 -8.839016 -8.455893 85.48565 -8.767989 -8.293065 85.64828 -9 -9 86.83775 -8.999991 -8.994227 86.83114 -8.987799 -8.794136 86.60225 -8.826141 -8.245539 85.96581 -8.749749 -8.108119 85.80148 -8.852055 -8.084345 86.08283 -8.989774 -8.752775 86.63575 -8.493509 -7.431004 85.50754 -8.746675 -7.827156 85.86351 -8.785354 -7.911786 85.93635 -8.087663 -7.868884 84.6684 -8.125206 -7.875457 84.70216 -8.314901 -8.050876 84.31906 -8.579906 -8.185317 84.75563 -8.620131 -8.215502 84.84244 -8.377206 -7.703214 85.28186 -8.043251 -7.53484 85.00346 -8.001062 -7.523157 84.97611 -8.439874 -7.370632 85.44966 -8.086535 -7.10175 85.15863 -8.037576 -7.078943 85.12794 -14 -8 83.87409 -13.5 -8.133975 83.87409 -13.13397 -8.5 83.87409 -13 -9 83.87409 -12.41355 -9.927686 84.9 -12.72175 -9.721752 84.9 -12.92769 -9.41355 84.9 -13 -9.050001 84.9 -12.05012 -10 86.29098 -12.1468 -9.99507 86.3143 -12.72211 -9.721395 86.46943 -12.88569 -9.501788 86.54115 -12.9425 -9.375482 86.58329 -12.9948 -9.149256 86.68246 -13 -9.050001 86.767 -12.37877 -9.941298 86.3712 -12.58134 -9.837512 86.42524 -9.475001 -9.872725 84.9 -9.278249 -9.721752 84.9 -9.127277 -9.525001 84.9 -9 -9.050001 84.9 -9 -9.050001 86.767 -9.000076 -9.061986 86.75175 -9.013349 -9.208695 86.65068 -9.949854 -10 86.29071 -9.502872 -9.888198 86.40189 -9.057771 -9.376236 86.58302 -9.149375 -9.561365 86.52208 -9.277941 -9.721445 86.46942 -11 -3.15 93.67501 -11 -3.3 93.525 -11.6875 -3.3 93.70922 -11.6125 -3.15 93.83912 -12.19079 -3.3 94.2125 -12.06088 -3.15 94.2875 -12.375 -3.3 94.9 -12.225 -3.15 94.9 -12.19079 -3.3 95.5875 -12.06088 -3.15 95.5125 -11.6875 -3.3 96.09078 -11.6125 -3.15 95.96089 -11 -3.3 96.275 -11 -3.15 96.125 -10.3125 -3.3 96.09078 -10.3875 -3.15 95.96089 -9.809215 -3.3 95.5875 -9.93912 -3.15 95.5125 -9.625 -3.3 94.9 -9.775 -3.15 94.9 -9.809215 -3.3 94.2125 -9.93912 -3.15 94.2875 -10.3125 -3.3 93.70922 -10.3875 -3.15 93.83912 -19.69416 -0.04999995 87.00698 -19.61025 -0.04999995 86.97061 -19.81204 -0.04999995 87.00547 -19.91613 -0.04999995 86.95011 -19.98327 -0.04999995 86.8532 -2.389759 -0.05000019 86.97061 -2.015771 -0.04999995 86.85068 -2.082394 -0.04999995 86.94879 -2.186732 -0.04999995 87.00515 -2.305306 -0.04999995 87.0071 -2.031507 -0.8029307 87.23643 -2.02031 -0.8196772 87.22098 -2.024393 -0.4667882 86.96759 -2.13233 -0.1071043 86.98588 -2.20233 -0.1053687 87.01067 -2.004144 -0.4937537 86.91133 -2.030255 -0.1141927 86.88474 -2.121119 -0.420747 87.06363 -2.063865 -0.4412043 87.02095 -2.072719 -0.1102021 86.94168 -2.273379 -0.1051263 87.01416 -2.389512 -0.1080283 86.9728 -2.33331 -0.2617524 87.0273 -2.385969 -0.2684867 87.00229 -2.379591 -0.4048455 87.05573 -2.269135 -0.2582363 87.04039 -2.325129 -0.4102752 87.08547 -2.374776 -0.4780363 87.09632 -2.043897 -0.7882291 87.24999 -2.293771 -0.7113268 87.32093 -2.236277 -0.7087639 87.32328 -2.245995 -0.5660954 87.19412 -2.158977 -0.7210968 87.31191 -2.175753 -0.5728724 87.18514 -2.118627 -0.7358992 87.29826 -2.094576 -0.7483089 87.28681 -2.06242 -0.770759 87.2661 -2.349915 -0.7238042 87.30941 -2.311139 -0.5706378 87.18807 -2.260531 -0.4053757 87.0957 -2.189751 -0.4084649 87.08926 -2.857835 -1.176678 87.50325 -2.869565 -1.175788 87.49082 -2.660127 -1.175127 87.6277 -2.535047 -1.163131 87.65281 -2.5652 -1.166705 87.64977 -2.65131 -1.174527 87.63059 -2.318542 -1.122748 87.61994 -2.344547 -1.129236 87.62926 -2.429427 -1.147002 87.64904 -2.389869 -1.139326 87.64176 -2.159305 -1.067137 87.52 -2.206061 -1.087089 87.5585 -2.228753 -1.095482 87.57406 -2.305349 -1.119242 87.61459 -2.050904 -0.9957025 87.37384 -2.10148 -1.035329 87.456 -2.109177 -1.040176 87.4659 -2.137076 -1.056047 87.49797 -2.019291 -0.9564232 87.29158 -19.77545 -1.093937 87.57132 -19.8612 -1.056906 87.49977 -19.92434 -1.017191 87.41849 -19.97445 -0.9660782 87.31183 -19.99893 -0.9075111 87.18676 -19.46 -1.163745 87.65243 -19.55209 -1.150172 87.65131 -19.61222 -1.138796 87.64128 -19.67804 -1.123616 87.62126 -19.68602 -1.121546 87.61814 -19.76954 -1.096047 87.57517 -19.32238 -1.176285 87.62142 -19.13051 -1.175788 87.49076 -19.79768 -0.1053122 87.01065 -19.72664 -0.1050692 87.01414 -19.62137 -0.4205834 87.06372 -19.61636 -0.3264159 87.02165 -19.6667 -0.2616652 87.02728 -19.61404 -0.2684018 87.00227 -19.6105 -0.1079662 86.9728 -19.67488 -0.4101784 87.08544 -19.68888 -0.570613 87.18806 -19.65008 -0.7237922 87.30943 -19.72861 -0.7091577 87.32292 -19.87887 -0.4206516 87.06359 -19.81024 -0.4083731 87.08922 -19.90542 -0.7483041 87.28682 -19.89471 -0.7423923 87.29227 -19.82426 -0.572845 87.18511 -19.83883 -0.7204724 87.31249 -19.99585 -0.4936304 86.91131 -19.96975 -0.1141268 86.88474 -19.92728 -0.1101409 86.94167 -19.86768 -0.1070464 86.98587 -19.73087 -0.2581462 87.04036 -19.73947 -0.4052832 87.09565 -19.75402 -0.5660703 87.19409 -19.78347 -0.7101369 87.32202 -19.941 -0.7736669 87.26343 -19.93612 -0.4411011 87.02092 -19.97154 -0.8070735 87.23262 -19.97559 -0.466675 86.96756 -2.847061 -1.077446 87.4852 -2.803505 -1.144767 87.54843 -2.733125 -1.144155 87.59368 -2.371187 -0.8208937 87.41684 -2.241417 -0.7784787 87.39725 -2.120993 -0.8272652 87.38573 -2.179469 -0.7969099 87.39762 -2.072468 -0.8669204 87.36216 -2.17911 -1.033609 87.53378 -2.1761 -0.9360741 87.49765 -2.219182 -0.9809741 87.54408 -2.655102 -1.1383 87.62658 -2.238288 -1.078126 87.57921 -2.338598 -1.05703 87.6178 -2.412266 -1.086584 87.64007 -2.491264 -1.109761 87.64963 -2.038338 -0.9113526 87.32994 -2.06299 -0.9747087 87.39406 -2.141843 -0.8828273 87.44258 -2.22851 -0.8944233 87.49845 -2.316578 -0.9710536 87.57553 -2.274193 -1.021948 87.5853 -2.440276 -1.028537 87.62195 -2.584584 -1.064446 87.62406 -2.573581 -1.126974 87.6453 -2.284071 -0.8638052 87.48609 -2.378203 -0.8314024 87.42771 -2.360783 -0.9303699 87.5517 -2.455474 -0.8965955 87.48725 -2.467657 -0.9800114 87.5892 -2.508262 -0.920289 87.50044 -2.591682 -1.011003 87.5884 -2.610793 -0.9461196 87.49167 -2.714707 -1.024252 87.54575 -2.721774 -0.9527381 87.43393 -2.727608 -1.079749 87.57626 -2.818311 -1.021989 87.46739 -2.745924 -0.9506341 87.41223 -2.80619 -1.005102 87.45891 -19.14797 -1.090845 87.4877 -19.1618 -1.057169 87.4802 -19.28217 -1.040775 87.55757 -19.86338 -0.8135201 87.3868 -19.97324 -0.9276655 87.30904 -19.76279 -1.083187 87.57891 -19.69543 -0.7694419 87.38236 -19.63344 -0.8128817 87.40848 -19.30627 -0.9787024 87.50413 -19.36842 -0.9490539 87.48503 -19.40673 -0.9673613 87.54013 -19.48419 -0.9229715 87.50121 -19.50736 -0.9414625 87.54298 -19.57387 -0.8780741 87.47243 -19.59363 -0.9008815 87.51531 -19.65768 -0.8459314 87.46279 -19.25408 -0.9506376 87.41223 -19.20631 -0.9902547 87.44976 -19.19381 -1.005101 87.4589 -19.13918 -1.120725 87.49118 -19.26968 -1.124545 87.59114 -19.42525 -1.107466 87.64112 -19.58124 -1.068112 87.63593 -19.71257 -1.006661 87.58473 -19.86851 -0.9911025 87.48374 -19.93179 -0.8661974 87.35578 -19.80757 -0.9248337 87.50144 -19.41219 -1.026518 87.60144 -19.54229 -0.9937679 87.60063 -19.65233 -0.942568 87.56118 -19.73243 -0.8739933 87.4931 -19.77915 -0.7799501 87.3954 -17.71803 -0.935837 86.08109 -17.73882 -0.9092849 86.05027 -18.48525 -0.8854146 86.6864 -18.87049 -1.067318 87.20212 -18.90943 -0.9775598 87.17549 -17.25678 -1.177315 85.85275 -16.86684 -1.216041 85.59458 -16.86662 -1.166575 85.58477 -16.86808 -1.231151 85.59593 -16.5948 -1.264313 85.42909 -16.0027 -1.254509 85.09873 -16.00783 -1.213471 85.08869 -16.0008 -1.3 85.10245 -18.03891 -1.096133 86.44697 -17.6779 -1.124149 86.15897 -17.6774 -1.112192 86.15823 -18.40973 -1.043631 86.76305 -16.11446 -1.05 84.87978 -16.93816 -0.9951457 85.43614 -16.09378 -1.054174 84.9203 -16.91744 -1.0131 85.47268 -16.07512 -1.065452 84.95685 -16.89855 -1.040076 85.50817 -16.05227 -1.090751 85.00164 -16.88298 -1.075791 85.54019 -16.03409 -1.123223 85.03723 -16.87206 -1.118793 85.56634 -16.01933 -1.163198 85.06616 -18.43867 -0.9505965 86.73496 -17.70008 -0.9708256 86.10933 -18.96439 -0.9173031 87.1294 -17.67878 -1.061449 86.14953 -17.68657 -1.013366 86.13281 -5.887493 -1.064437 84.97338 -5.92385 -1.064631 84.95484 -5.927376 -1.067553 84.96174 -5.417335 -1.265658 85.42192 -5.997298 -1.254509 85.09873 -5.999196 -1.3 85.10245 -3.493458 -1.099363 86.85938 -4.322661 -1.112204 86.15818 -4.628198 -1.161583 85.93339 -5.133406 -1.166574 85.58475 -5.131862 -1.23122 85.59597 -4.861361 -1.193938 85.77218 -5.061864 -0.9951477 85.43611 -5.446044 -1.031719 85.16678 -5.082584 -1.013101 85.47266 -5.700592 -1.056442 85.06303 -5.101476 -1.040076 85.50815 -5.990623 -1.204749 85.08566 -5.980669 -1.163197 85.06616 -5.961106 -1.11326 85.02783 -5.117045 -1.075791 85.54017 -5.127969 -1.118792 85.56632 -4.299978 -0.9708371 86.10929 -4.313496 -1.013377 86.13275 -4.321282 -1.061461 86.14949 -4.052699 -0.8942893 86.22168 -4.282028 -0.9358491 86.08103 -7.963693 -1.204749 84.30773 -7.96889 -1.3 84.32586 -6.374783 -1.065044 84.73854 -7.924438 -1.066206 84.1708 -7.945802 -1.11326 84.24533 -7.959665 -1.175031 84.29369 -8.757117 -0.6284799 83.96778 -8.866845 -0.4207266 83.94599 -8.890417 -0.4276567 83.97998 -8.689268 -1.059956 84.14544 -8.161063 -1.284456 84.27266 -8.288581 -1.19644 84.23251 -8.667265 -0.9853018 84.13934 -8.80631 -0.8508683 84.1089 -9.01733 -0.6927235 84.08016 -9.031214 -0.4771553 84.06405 -9.074315 -0.58349 84.06987 -9.098063 -0.04999995 84.0477 -9.191105 -0.04999995 84.04972 -8.998476 -0.04999995 84.002 -8.929008 -0.1710672 83.93417 -8.936205 -0.04999983 83.93283 -8.391421 -0.9523758 84.04863 -8.228437 -1.058508 84.15067 -8.205227 -1.026793 84.09477 -8.258656 -1.117648 84.2033 -8.404945 -0.9825189 84.09937 -8.61226 -0.9216458 84.1097 -8.565498 -0.8753709 84.05629 -8.742176 -0.7965068 84.07912 -8.689585 -0.7573415 84.02544 -8.952341 -0.4482534 84.03404 -9.098063 0 84.0477 -9.191111 0 84.04975 -8.93625 0 83.93281 -8.998476 0 84.002 -14.1 -1.049952 84.08554 -14.07616 -1.065452 84.16873 -14.05129 -1.123223 84.25548 -14.04086 -1.171794 84.29186 -14.03537 -1.213471 84.31101 -14.03111 -1.3 84.32586 -14.18311 -5.1 84.40724 -14.27402 -5.307336 84.67774 -13.40746 -5.307336 85.20788 -14.90547 -6 84.83998 -14.36283 -6 84.94196 -14.34301 -5.652791 84.88299 -12.93779 -5.652791 86.83775 -13.06098 -5.652791 86.13565 -13 -6 86.83775 -13.11948 -6 86.15683 -13.55878 -5.652791 85.36275 -13.94591 -6 85.13807 -13.60226 -6 85.40725 -13.2524 -6 85.86517 -15.2578 -5.652791 84.79171 -15.25003 -6 84.85343 -15.88889 -6 85.04614 -15.38817 -5.654841 84.81317 -15.25646 -5.571221 84.7569 -14.80927 -5.321292 84.5802 -13.20802 -5.1 85.00377 -12.85739 -5.307336 86.06193 -12.58907 -5.1 85.96478 -12.72126 -5.307336 86.83775 -12.43589 -5.1 86.83775 -14.2414 -5.1 84.38842 -7.816891 -5.1 84.40724 -7.758602 -5.1 84.38842 -8.998311 -5.1 84.08366 -10.21154 -5.1 93.06198 -9.56411 -5.1 93.50781 -9.56411 -5.1 86.83775 -12.43589 -5.1 93.50781 -11.78846 -5.1 93.06198 -13.00169 -5.1 84.08366 -11 -5.1 92.9 -9.410932 -5.1 85.96478 -8.79198 -5.1 85.00377 -6.111111 -6 85.04614 -6.594362 -5.66539 84.82048 -6.742197 -5.652791 84.79171 -7.637173 -6 84.94196 -7.076267 -6 84.83921 -6.749975 -6 84.85343 -8.441219 -5.652791 85.36275 -8.397741 -6 85.40725 -8.043715 -6 85.13169 -7.656993 -5.652791 84.88299 -8.744625 -6 85.85985 -8.939017 -5.652791 86.13565 -8.880521 -6 86.15683 -9.062212 -5.652791 86.83775 -9 -6 86.83775 -9.27874 -5.307336 86.83775 -7.725975 -5.307336 84.67774 -7.219474 -5.30759 84.56984 -7.225537 -5.304682 84.56762 -9.142609 -5.307336 86.06193 -8.592543 -5.307336 85.20788 -6.747278 -5.568563 84.75517 -13 -6 93.86019 -13 -6.227223 93.90001 -13 -9 93.9 -9.664994 -5.057784 93.79937 -10.00016 -5 93.16767 -9 -6 93.86019 -9.035009 -5.737719 93.9 -8.999623 -6 93.89997 -9.266635 -5.320165 93.9 -9.633976 -5.0694 93.9 -12.00001 -5 93.16774 -11.78846 -4.999992 93.06198 -11 -4.999992 92.9 -10.21154 -4.999992 93.06198 -13.00038 -6 93.89998 -12.90109 -5.566365 93.9 -12.70374 -5.28954 93.9 -12.59729 -5.197976 93.9 -12.36602 -5.069402 93.9 -13.05841 -6.110831 94.22512 -13.05617 -6 94.199 -13.01496 -6 94.03699 -12.77871 -7.321883 94.81444 -12.88865 -7.128067 94.55799 -12.86701 -9 94.61714 -12.94577 -6.962121 94.36259 -12.95024 -6.947753 94.34338 -12.96566 -6.869681 94.26905 -12.9808 -6.76355 94.17649 -12.99604 -6.538232 94.02583 -12.99975 -6.330717 93.93131 -12.48571 -9 95.2389 -12.48572 -7.584464 95.2389 -12.64813 -7.459646 95.03299 -12 -10 86.83775 -12 -10 93.9 -12.34116 -9.940007 86.83775 -12.5 -9.866025 93.9 -12.99122 -9.132231 93.9 -12.93996 -9.341276 86.83775 -12.86603 -9.5 93.9 -12.86603 -9.5 86.83775 -12.82206 -9.569395 93.9 -12.70706 -9.707152 86.83775 -12.5 -9.866025 86.83775 -8.94383 -6 94.199 -8.941594 -6.110832 94.22512 -9 -6.227205 93.9 -9.009968 -5.900344 94.04128 -9.004933 -6 94.04039 -9.381388 -5.218513 94.0312 -9.179525 -5.436984 94.04756 -9.050041 -5.705057 94.04818 -9.110857 -5.555395 94.05845 -9.182226 -5.435908 94.0705 -9.412111 -5.201189 94.10909 -9.568378 -5.107371 94.13506 -9.864669 -5 93.56896 -9.767623 -5.000014 93.99291 -11.6875 -5 93.70922 -11 -5 93.525 -10.3125 -5 93.70922 -9.809215 -5 94.2125 -9.742844 -5 94.34306 -12.13529 -5 93.56899 -12.19079 -5 94.2125 -12.23237 -5.000012 93.99292 -12.25715 -5 94.34306 -12.61861 -5.218513 94.03119 -12.43165 -5.107384 94.13504 -12.99507 -6 94.04039 -12.98762 -5.878861 94.0417 -12.82048 -5.436984 94.04756 -12.94141 -5.679071 94.04963 -12.81893 -5.437565 94.07031 -12.51115 -5.150352 94.12187 -9 -9 93.9 -9.060028 -9.34125 93.9 -9.060039 -9.34128 86.83775 -9.073438 -9.376144 93.9 -9.292894 -9.707108 93.9 -9.292946 -9.707159 86.83775 -9.658753 -9.939973 93.9 -9.658861 -9.940012 86.83775 -10 -10 93.9 -10 -10 86.83775 -9.514289 -7.58443 95.2389 -9.514286 -9 95.2389 -9.362173 -7.469259 95.04784 -9.132994 -9 94.61714 -9.219943 -7.317301 94.8118 -8.999994 -6.301752 93.91022 -9.00184 -6.47411 93.98577 -9.020251 -6.770859 94.18389 -9.028329 -6.831212 94.23543 -9.041526 -6.906963 94.30543 -9.110547 -7.138579 94.55567 -8.935606 -6.356179 94.47943 -8.9405 -6.405199 94.56475 -9.029179 -6.67067 94.35309 -9.030148 -6.813028 94.2475 -8.935996 -6.22993 94.31398 -9.00235 -6.434971 94.03704 -9.122505 -6.983185 94.63064 -9.113749 -6.869753 94.69171 -9.066353 -6.690876 94.80213 -8.993953 -6.55226 94.9 -8.934358 -6.323883 94.42983 -11.70453 -9.75 94.12145 -11.79792 -9.75 94.21751 -11.80981 -9.837027 94.20734 -10.01209 -9.999927 94.055 -10.07654 -9.985174 94.11013 -10.4445 -9.985174 93.81922 -10.45618 -10 93.71924 -11 -9.985174 93.68482 -11 -10 93.60003 -11.5555 -9.985174 93.81922 -11.54382 -10 93.71924 -11.92346 -9.985174 94.11013 -11.98789 -9.999983 94.05502 -11.47999 -9.75 93.96614 -11.48714 -9.837027 93.95223 -11.24846 -9.75 93.87982 -11 -9.837027 93.83436 -11 -9.75 93.85 -10.73235 -9.75 93.88468 -10.51286 -9.837027 93.95223 -10.52001 -9.75 93.96614 -10.28092 -9.75 94.13488 -10.19019 -9.837027 94.20734 -10.20211 -9.75 94.21754 -10.14579 -9.927609 94.16936 -10.48616 -9.927609 93.90026 -11 -9.927609 93.77594 -11.51384 -9.927609 93.90026 -11.85421 -9.927609 94.16936 -12.89382 -6.825238 94.71823 -12.878 -6.964532 94.63985 -12.99974 -6.319462 93.95272 -12.99573 -6.480894 94.08923 -12.97992 -6.627499 94.28666 -13.00605 -6.552258 94.9 -13.06326 -6.372003 94.50564 -13.06073 -6.16162 94.25527 -13.06517 -6.262164 94.34905 -13.0656 -6.326043 94.43299 -13.06464 -6.351727 94.47229 -12.40307 -7.772179 95.2993 -12.42612 -9 95.28739 -12.37535 -9 95.30992 -12.32246 -7.953423 95.32053 -12.32119 -7.956234 95.32064 -12.21945 -8.178977 95.30821 -12.22381 -8.169442 95.30964 -12.21205 -9 95.30555 -12.32113 -9 95.32064 -12.05681 -8.529528 95.12952 -12.08998 -8.455853 95.20715 -12.12003 -9 95.24507 -12.1223 -8.386798 95.24739 -12.1256 -8.379746 95.25066 -12.16791 -8.289469 95.28379 -12.06293 -9 95.1509 -12.05 -9 95.07154 -12.05 -8.549263 95.07154 -12.46912 -9.5211 95.0301 -12.48409 -9.174027 95.21783 -12.85881 -9.132231 94.61399 -12.46458 -9.570299 94.98289 -12.28691 -9.920287 94.42861 -12.34309 -9.872871 94.5404 -12.36628 -9.886041 94.42481 -12.40438 -9.787303 94.70063 -12.40912 -9.778019 94.71581 -12.44815 -9.6671 94.87353 -12.45156 -9.651947 94.89221 -12.7009 -9.569395 94.55334 -12.034 -9.998608 94.09786 -12.23159 -9.951728 94.33737 -12.25907 -9.937585 94.38081 -12.91868 -6.642837 95.17571 -12.791 -6.917225 94.99237 -12.77148 -7.018667 94.93914 -12.64661 -7.052024 95.19787 -12.47472 -7.171008 95.38873 -12.78337 -6.738239 95.40651 -12.71323 -6.777135 95.50449 -12.60377 -6.82827 95.63745 -9.723165 -5.020742 94.38979 -9.624165 -5.079031 94.16043 -9.672272 -5.051606 94.22497 -12.27683 -5.020742 94.38979 -12.33569 -5.056387 94.2099 -12.39288 -5.088003 94.14871 -9.18903 -9.34125 94.59562 -9.406411 -9.707108 94.51212 -9.624793 -9.834509 94.61721 -9.748396 -9.941665 94.3689 -9.768353 -9.951685 94.3376 -9.913163 -9.993285 94.15214 -9.779525 -9.956727 94.32082 -9.521567 -9.355033 95.14816 -9.530773 -9.521179 95.03018 -9.560896 -9.702023 94.82761 -9.563953 -9.711852 94.81417 -9.95 -8.549271 95.07154 -9.95 -9 95.07154 -9.949685 -8.547314 95.0841 -9.937224 -9 95.15044 -9.940261 -8.522743 95.14064 -9.925824 -8.490302 95.1788 -9.880765 -9 95.24423 -9.895365 -8.42458 95.22753 -9.846343 -8.319835 95.27423 -9.789643 -9 95.30491 -9.794734 -8.209673 95.3029 -9.681329 -9 95.32084 -9.739457 -8.089064 95.31841 -9.781311 -8.180674 95.30795 -9.582988 -7.741687 95.29246 -9.608368 -7.798947 95.30414 -9.576596 -9 95.28896 -9.650449 -7.893075 95.31658 -9.704585 -8.012877 95.3215 -9.568734 -7.709235 95.2843 -9.372194 -7.257876 95.1011 -9.217406 -6.955661 94.97019 -9.353775 -7.053874 95.1969 -9.222201 -6.741575 95.4146 -9.396202 -6.828299 95.63746 -9.081349 -6.642857 95.17577 -9.537413 -7.379713 95.29716 -9.530934 -7.213155 95.36735 -9.52557 -7.172865 95.38775 -9.95 -8.550001 94.9 -9.950299 -8.525 94.875 -10.00147 -8.824703 94.57533 -12.04615 -9.4864 94.81023 -11.96707 -9.689511 94.49103 -11.99217 -8.843651 94.55625 -12.0497 -8.525 94.875 -12.05 -8.550001 94.9 -12.05 -9.390825 94.9 -11.2533 -9.51899 93.88156 -11.51967 -9.412385 93.98764 -11.71255 -9.27122 94.12892 -11.89208 -9.053791 94.34642 -11.91012 -9.023629 94.37659 -10.27412 -9.258679 94.14145 -10.45664 -9.398475 94.0016 -10.72922 -9.514483 93.88589 -10.80579 -9.531883 93.86824 -10.99958 -9.55 93.84976 -11.11767 -9.543387 93.85675 -10.1519 -9.746126 94.28113 -10.11279 -9.061576 94.33866 -9.996387 -9.641942 94.59137 -10.08966 -9.023241 94.37699 -9.950036 -9.390825 94.9 -9.847243 -9.954818 94.37821 -9.63233 -9.705039 94.89299 -9.557996 -9.677424 94.86559 -9.95397 -9.676257 94.69644 -9.941979 -9.435276 94.94439 -9.828946 -9.79571 94.72914 -9.861239 -9.526015 95.03501 -9.901073 -9.74638 94.72039 -9.913665 -9.482668 94.99172 -9.934941 -9.451295 94.96039 -9.559597 -9.537191 95.04617 -9.624649 -9.559496 95.06844 -9.648146 -9.563876 95.07281 -9.640706 -9.706657 94.89503 -9.704122 -9.567699 95.07663 -9.727988 -9.709021 94.90605 -9.735906 -9.56589 95.07482 -9.787714 -9.556478 95.06543 -9.649998 -9.816774 94.69847 -9.658119 -9.818538 94.70127 -9.743506 -9.821117 94.72244 -9.820487 -9.545824 95.05479 -10.04152 -9.796837 94.4354 -9.992321 -9.873312 94.43048 -9.925744 -9.92711 94.41078 -12.36126 -9.699225 94.90526 -12.34706 -9.806904 94.72328 -12.27286 -9.811209 94.7417 -12.05802 -9.435276 94.94439 -12.1845 -9.943811 94.41733 -12.31203 -9.882285 94.55451 -12.42481 -9.67939 94.88465 -12.21229 -9.556477 95.06543 -12.27746 -9.567003 95.07595 -11.8543 -9.874311 94.23313 -11.83211 -9.809807 94.24735 -11.96475 -9.76208 94.46656 -12.03944 -9.64456 94.70318 -12.07142 -9.701764 94.72686 -11.99555 -9.82446 94.47052 -12.12431 -9.754546 94.74363 -12.04564 -9.882019 94.46404 -12.19465 -9.793406 94.74916 -12.11163 -9.924396 94.44567 -12.00949 -9.997722 94.11711 -11.94772 -9.977646 94.16477 -11.89357 -9.933827 94.20522 -12.4404 -9.537191 95.04617 -12.37535 -9.559496 95.06844 -12.35388 -9.563566 95.0725 -12.29588 -9.567699 95.07663 -12.13876 -9.526015 95.03501 -12.08633 -9.482668 94.99172 -12.05 -8.550001 95 -12.05 -9.183609 95.03717 -12.05 -9.3482 94.93914 -12.13876 -9.471044 95.08547 -12.21229 -9.498726 95.11843 -12.4404 -9.257676 95.2303 -12.4404 -9.481201 95.09756 -12.37535 -9.501469 95.12171 -12.29588 -9.508922 95.13058 -12.37535 -9.268963 95.25973 -12.29588 -9.273114 95.27056 -12.21229 -9.267436 95.25575 -12.13876 -9.25202 95.21555 -12.08633 -9.431657 95.03855 -12.05802 -9.388591 94.98725 -12.08633 -9.230085 95.15835 -12.05802 -9.206103 95.09582 -9.913665 -9.264457 95.14406 -9.559597 -9.295998 95.21437 -9.559597 -9.048569 95.27672 -9.624649 -9.050728 95.30817 -9.624649 -9.308901 95.24314 -9.704122 -9.313645 95.2537 -9.704122 -9.051522 95.31974 -9.787714 -9.050436 95.30391 -9.787714 -9.307154 95.23924 -9.861239 -9.289532 95.19995 -9.861239 -9.047489 95.26097 -9.913665 -9.043293 95.19985 -9.941979 -9.237042 95.08296 -9.941979 -9.038707 95.13303 -9.95 -9.211328 95.02565 -9.95 -9.034406 95.07036 -9.95 -8.550001 95 -9.95 -8.5 94.9 -9.950299 -8.525 94.9 -10.00892 -8.203207 94.9 -11.7084 -7.774975 94.9 -11.99108 -8.203207 94.9 -12.01422 -8.22824 94.9 -12.04102 -8.362949 94.9 -11.90933 -7.975 94.9 -11.525 -7.590673 94.9 -11.25656 -7.531826 94.9 -11 -7.45 94.9 -10.74344 -7.531826 94.9 -10.475 -7.590673 94.9 -10.2916 -7.774975 94.9 -10.09067 -7.975 94.9 -10.1237 -7.971558 94.9 -9.985778 -8.22824 94.9 -12.0497 -8.525 94.9 -12.05 -8.5 94.9 -12.04454 -8.443077 94.9 -12.033 -8.361807 94.9 -11.99108 -8.203207 95 -10.00892 -8.203207 95 -10.2916 -7.774975 95 -11.7084 -7.774975 95 -11.25656 -7.531826 95 -11 -7.5 95 -10.74344 -7.531826 95 -10.02372 -8.162852 95.06352 -10.25753 -7.806961 95.05615 -10.6135 -7.573192 95.0513 -11 -7.49948 95.04977 -11.3865 -7.573191 95.0513 -11.74246 -7.806956 95.05615 -11.86072 -7.948007 95.05907 -11.97628 -8.162842 95.06352 -9.646055 -7.347208 95.41812 -9.717258 -7.441043 95.42592 -9.783523 -7.537508 95.41856 -9.844386 -7.636309 95.3983 -9.896766 -7.732593 95.368 -9.950303 -7.848978 95.31872 -9.988053 -7.953299 95.26273 -10.01128 -8.042631 95.20401 -10.02198 -8.110161 95.14789 -10.02427 -8.141011 95.11294 -10.02422 -8.159037 95.08003 -10.61452 -7.569951 95.10176 -10.60005 -7.529678 95.30545 -10.93162 -7.468299 95.38399 -10.55991 -7.472164 95.46768 -10.67069 -7.363168 95.73629 -10.16602 -7.157603 95.94299 -10.21902 -7.179602 95.9368 -10.21227 -7.187556 95.91512 -10.25785 -7.195647 95.93025 -10.36883 -7.297863 95.78461 -10.48392 -7.393321 95.63217 -10.25883 -7.803498 95.08193 -10.26096 -7.787477 95.13398 -10.26049 -7.759815 95.19061 -10.24879 -7.698329 95.28464 -10.21581 -7.615329 95.38665 -10.15657 -7.516356 95.48685 -10.06804 -7.40364 95.57754 -9.978854 -7.308665 95.63498 -10.05619 -7.111667 95.94604 -9.873291 -7.209578 95.67518 -9.894316 -7.043078 95.92648 -9.756728 -7.111155 95.69251 -9.758188 -6.984648 95.88652 -9.630077 -7.013665 95.68259 -12.32054 -7.01647 95.73749 -12.54624 -6.864865 95.66916 -12.47334 -7.039707 95.51348 -11.82629 -7.160788 95.94232 -11.66664 -7.269131 95.82433 -11.79403 -7.174181 95.93864 -12.0069 -7.084999 95.94198 -12.04777 -7.231753 95.69901 -11.92866 -7.344212 95.63395 -11.0939 -7.457777 95.4401 -11.38609 -7.551449 95.21464 -11.00096 -7.498518 95.08433 -12.04674 -8.132639 95.2191 -12.02796 -8.207195 95.16957 -12.0184 -8.258778 95.1205 -12.16532 -7.824126 95.34141 -12.11711 -7.932943 95.30914 -12.07624 -8.039802 95.26661 -12.22227 -7.710232 95.36357 -12.28079 -7.604649 95.37248 -12.34376 -7.501065 95.36799 -11.35218 -7.353991 95.75461 -11.54289 -7.366322 95.68009 -11.45807 -7.447352 95.52381 -11.40822 -7.509815 95.36598 -12.55656 -6.84847 95.68663 -12.22484 -6.992025 95.89263 -12.30558 -7.187157 95.56213 -12.43886 -7.361258 95.33145 -11.69446 -7.742834 95.14823 -11.69892 -7.698507 95.23943 -11.71922 -7.632773 95.34064 -11.76289 -7.548548 95.44659 -11.83468 -7.448741 95.54931 -11.85723 -7.924562 95.12395 -11.85843 -7.877679 95.1888 -11.8707 -7.808838 95.26213 -11.9001 -7.72158 95.34008 -11.95052 -7.619289 95.41664 -12.018 -7.513249 95.48047 -12.10466 -7.400285 95.53027 -12.19919 -7.29368 95.55776 -10.74408 -7.264546 96.00752 -9.938589 -6.642851 96.52194 -9.653758 -6.642852 96.2946 -9.364654 -6.642854 95.94064 -9.143174 -6.642856 95.45629 -11.25595 -7.264546 96.0075 -12.23984 -6.642842 96.39 -12.34675 -6.642842 96.29413 -12.7196 -6.642839 95.7946 -11.51635 -6.642845 96.76834 -12.85704 -6.642838 95.45564 -10.50955 -6.642848 96.7753 -10.69986 -6.642848 96.815 -11.6875 -5.020742 96.09078 -11.95532 -5.020742 95.88893 -12.18194 -5.151254 96.12353 -12.65972 -5.151254 94.52671 -9.027665 -5.471708 94.45714 -9.340147 -5.151254 94.5273 -8.885227 -5.9006 94.42516 -8.923748 -5.9006 95.52203 -8.979556 -6.349895 95.50531 -9.535134 -6.349895 96.41748 -10.46634 -6.349895 96.94054 -12.46541 -6.349895 96.41696 -11.53439 -6.349895 96.94036 -13.02066 -6.349895 95.5046 -13.1146 -5.9006 94.4244 -12.34149 -5.020742 94.59828 -12.62979 -5.151254 95.38764 -12.19079 -5.020742 95.5875 -12.3173 -5.020742 95.29415 -12.375 -5.020742 94.9 -11.34838 -5.020742 96.23014 -11.43102 -5.151254 96.54567 -11 -5.020742 96.275 -10.56957 -5.151254 96.54583 -10.6521 -5.020742 96.23026 -10.3125 -5.020742 96.09078 -9.818491 -5.151254 96.12395 -10.04503 -5.020742 95.88928 -9.809215 -5.020742 95.5875 -9.370383 -5.151254 95.38822 -9.682842 -5.020742 95.29462 -9.625 -5.020742 94.9 -9.658404 -5.020742 94.59877 -12.97218 -5.471708 94.45644 -12.93661 -5.471708 95.47945 -12.40446 -5.471708 96.35388 -11.51216 -5.471708 96.85549 -10.48853 -5.471708 96.85567 -9.596061 -5.471708 96.35437 -9.063591 -5.471708 95.48014 -13.07647 -5.9006 95.5213 -12.50588 -5.9006 96.45886 -11.54915 -5.9006 96.99671 -10.4516 -5.9006 96.99691 -9.494672 -5.9006 96.45941 -12.80889 0 84.04975 -12.80889 -0.04999995 84.04972 -12.84185 -0.338993 84.05531 -13.05504 -0.8026482 84.09368 -13.46648 -1.158682 84.18012 -19.22909 -8 81.60631 -18.9101 -8 84.49237 -18.16328 -8 84.849 -19.62458 -8 82.34901 -19.69488 -8 83.0644 -19.45047 -8 83.87406 -16.525 0 83.65311 -5.475 0 83.65311 -4.194513 0 85.41084 -4.194513 -0.04999995 85.41084 -3.594703 -0.04999995 86.01576 -15.29455 -1.05 83.46305 -14.1 -1.05 83.76441 34.05 -10 84.9 31.95 -10 84.9 32.475 -7.590673 93.4 32.09067 -7.975 93.4 33 -8.5 93.4 31.95 -8.5 93.4 32.09067 -9.025 93.4 33.90933 -7.975 93.4 33.525 -7.590673 93.4 33 -7.45 93.4 33.525 -9.409328 93.4 33.90933 -9.025 93.4 34.05 -8.5 93.4 32.475 -9.409328 93.4 33 -9.55 93.4 31.525 6 79.95001 27.475 6 79.95001 31.525 4.5 79.95001 27.475 0 79.95001 38.525 4.5 79.95001 38.525 0 79.95001 35.32287 8.5 99.8854 35.32287 9.409926 99.8854 33 9.409925 100.4 33 8.5 100.4 30.6756 9.409925 99.8847 30.67712 8.5 99.8854 35.46589 8.5 99.78511 35.46589 9.398838 99.78511 35.56567 8.5 99.64173 35.56567 9.366894 99.64173 35.60979 8.5 99.47592 35.60979 9.318982 99.47592 30.39021 9.318982 99.47592 30.39021 8.5 99.47592 30.43521 8.5 99.64363 30.43521 9.367385 99.64363 30.53485 8.5 99.78585 30.53485 9.39897 99.78585 37.38263 8.5 97.82277 38.2238 8.5 95.57968 38.15388 8.56032 95.9897 37.38263 9.046358 97.82277 27.84611 8.560318 95.98969 27.77621 8.5 95.57968 28.61737 8.5 97.82277 28.61737 9.046358 97.82277 31.00373 8.5 94.77796 31.00373 8.4 94.77796 31.19762 8.4 95.76685 31.19762 8.5 95.76685 31.84909 8.4 96.53567 31.84909 8.5 96.53567 32.79274 8.4 96.88923 32.79274 8.5 96.88923 33.78902 8.4 96.73779 33.78902 8.5 96.73779 34.58498 8.4 96.11978 34.58498 8.5 96.11978 34.97855 8.4 95.1921 34.97855 8.5 95.1921 34.86983 8.4 94.19026 34.86983 8.5 94.19026 34.28641 8.4 93.36861 34.28641 8.5 93.36861 33.3764 8.4 92.93574 33.3764 8.5 92.93574 32.37084 8.4 93.00154 32.37084 8.5 93.00154 31.525 8.4 93.54931 31.525 8.5 93.54931 26.40465 8.5 94.94012 26.54207 8.5 94.74633 31.28049 8.5 94.55516 31.46188 8.5 94.24965 26.95722 8.5 93.40512 31.525 8.5 93.9 27.475 8.5 92.03219 26.86309 8.5 93.85691 37.77236 8.5 90.90277 35.5037 8.5 89.20056 36.68429 8.5 89.88185 27.98504 8.5 91.21217 29.3604 8.5 89.84992 31 8.5 89.00509 31.08773 8.5 88.97605 38.5578 8.5 92.0963 39.04366 8.5 93.40804 39.13692 8.5 93.85691 39.44427 8.5 94.7231 39.59535 8.5 94.94012 31.9 8.5 88.77301 32.99999 8.5 88.67505 34.1 8.5 88.77301 33.7375 6.5 93.62261 34.27738 6.5 94.1625 33 6.5 94.9 34.475 6.5 94.9 34.27738 6.5 95.6375 31.72261 6.5 94.1625 32.2625 6.5 93.62261 33 6.5 93.42501 32.2625 6.5 96.17739 31.72261 6.5 95.6375 31.525 6.5 94.9 33.7375 6.5 96.17739 33 6.5 96.375 31.72261 8.4 94.1625 32.2625 8.4 93.62261 33 8.4 93.42501 33.7375 8.4 93.62261 34.27738 8.4 94.1625 34.475 8.4 94.9 34.27738 8.4 95.6375 33.7375 8.4 96.17739 33 8.4 96.375 32.2625 8.4 96.17739 31.72261 8.4 95.6375 31.525 8.4 94.9 24.61408 8.739487 95.02572 24.58871 8.720318 94.9602 25.05974 8.511985 94.83631 25.27792 8.593173 95.041 25.53103 8.675383 95.29756 25.77116 8.739486 95.56527 24.30534 8.188876 94.24269 24.30329 8.16504 94.23102 24.83963 8.421184 94.64377 24.38054 8.460948 94.46638 24.33678 8.353923 94.35531 24.30754 8.212679 94.25522 24.51959 8.657227 94.79122 25.01618 8.494707 94.79713 24.80507 7.254463 93.41997 24.78595 7.278398 93.48236 24.73211 7.251549 93.50122 24.57871 7.596982 93.92934 24.55254 7.522727 93.87319 24.61817 7.529383 93.86386 24.0337 7.727891 93.63182 24.0121 8.304291 93.90953 24.36318 8.020673 94.1861 24.21191 7.580093 93.80569 24.36918 8.00712 94.18095 24.37734 7.530829 93.86365 24.44336 7.850263 94.10852 24.08762 7.661645 93.70975 24.11383 8.221511 94.10066 24.21191 8.185323 94.18421 24.511 7.719446 94.02717 24.76814 7.301971 93.53526 24.72954 7.356136 93.63664 24.55254 7.2068 93.53214 24.71085 7.383547 93.68055 24.64705 7.482301 93.81196 24.37734 7.217096 93.52502 24.46006 7.037733 93.17082 24.66506 7.063425 93.16452 24.73211 7.091717 93.15756 24.85527 7.180184 93.13585 24.86965 7.195086 93.13219 24.21191 7.279697 93.48178 24.31929 7.069025 93.16313 24.37734 7.051028 93.16754 24.0337 7.467507 93.35207 24.06424 7.283825 93.11036 24.08762 7.383326 93.41022 24.13586 7.189112 93.13362 24.23183 7.111984 93.15257 41.62367 7.992305 94.17529 41.62266 7.560337 93.8883 41.7881 7.608641 93.82954 41.40077 7.561666 93.89627 41.39759 7.556281 93.89102 41.44746 7.552392 93.89796 41.99958 7.50224 93.05672 42 7.522194 93.05182 42 7.674408 93.32546 41.93997 7.291264 93.10853 41.9663 7.447067 93.32123 41.91238 7.360826 93.37625 41.86415 7.18912 93.13362 41.7881 7.254662 93.44397 41.80574 7.137607 93.14627 41.7881 7.124944 93.14938 41.68075 7.069033 93.16312 41.62266 7.19053 93.4849 41.58541 7.043313 93.16944 41.44746 7.179982 93.49162 41.44746 7.038862 93.17053 41.34266 7.060859 93.16514 41.26789 7.225826 93.46237 41.26789 7.09171 93.15756 41.13035 7.195083 93.13219 41.18464 7.242253 93.3833 41.22828 7.297145 93.52498 41.26996 7.355421 93.63544 41.28885 7.383107 93.67988 41.42113 7.596707 93.92909 41.55636 7.850891 94.10895 41.46835 7.680656 93.99874 41.44847 7.644831 93.97045 41.9663 7.753557 93.65326 41.93563 8.250217 94.03442 41.91238 7.688601 93.73227 41.76805 8.180013 94.19653 41.69671 8.16507 94.23104 42 8.29283 93.78427 42 8.347739 93.80921 40.22884 8.739486 95.56527 40.66306 8.61355 95.09887 41.38592 8.739488 95.02572 40.67897 8.608129 95.08318 41.45553 8.681855 94.85077 40.93284 8.514904 94.84305 41.52537 8.606416 94.6859 41.59217 8.51077 94.53102 41.16146 8.420734 94.64287 41.4404 8.293511 94.41815 41.69466 8.18889 94.2427 41.69246 8.212679 94.25522 41.64834 8.395926 94.39484 41.61365 8.472312 94.48032 31.525 8.4 93.9 31.28049 8.4 94.55516 31.46188 8.4 94.24965 25.09078 7.694948 93.78565 24.95791 7.711924 93.9102 25.43063 7.86729 93.55454 25.3016 7.73442 93.5033 25.58812 8.112804 94.02519 25.59562 8.144192 94.10848 25.49982 8.122793 94.18968 24.89449 8.280365 94.53455 25.33545 8.344257 94.67936 25.60625 8.480696 94.90688 25.61569 8.483117 94.91049 25.62438 8.498843 94.94373 25.67662 8.570812 95.10353 25.79294 8.675964 95.38285 25.73922 8.633299 95.25989 25.72327 8.618904 95.22182 25.56892 8.279341 94.48265 25.56818 8.298502 94.52592 25.5799 8.388618 94.71582 25.58908 8.4202 94.78045 25.59975 8.44904 94.83966 25.61366 8.479188 94.90225 25.05797 8.197619 94.47387 25.20645 8.147405 94.39861 25.35545 8.121463 94.30335 25.58976 8.202863 94.27964 25.59549 8.187191 94.23081 25.20728 7.703168 93.64695 25.54829 8.023335 93.80503 25.49949 7.944628 93.62528 24.37138 8.008738 94.18246 24.52309 7.898868 94.15016 24.66682 7.817526 94.09578 24.81338 7.75396 94.0156 25.5794 8.088348 93.96298 40.45001 8.026434 93.81234 40.56559 7.985476 93.94601 40.41186 8.112875 94.02538 41.15888 7.48743 93.70639 41.42906 7.926337 94.17525 40.41488 8.371092 94.6841 40.41707 8.367884 94.67675 40.69913 8.203955 94.46259 40.42776 8.352224 94.64088 40.5499 8.18525 94.36601 40.41025 8.202855 94.27964 40.52102 8.541767 95.02569 40.34914 8.502466 94.94716 40.84835 8.247836 94.54031 40.33673 8.485536 94.94626 40.3553 8.458345 94.88397 40.35735 8.455332 94.87706 40.40692 8.382739 94.71077 40.22322 8.651783 95.32707 40.25774 8.601222 95.21125 40.30608 8.530426 95.04908 40.3264 8.50067 94.98092 40.207 8.675528 95.38146 41.0132 8.324601 94.60499 41.13696 8.090984 94.34494 41.13805 7.786908 94.03654 40.49597 7.951324 93.64017 40.50052 7.944618 93.62526 40.65062 7.783852 93.5231 40.63331 7.794329 93.49247 40.94524 7.481684 93.42347 40.86067 7.735708 93.80469 40.40682 8.195223 94.25537 40.84181 7.987963 94.18479 25.63339 8.131237 93.98484 26.12838 8.355965 93.73209 25.98118 8.424287 94.5969 26.19015 8.470419 94.65641 26.23205 8.433513 94.227 25.77288 8.327207 94.42807 25.64585 8.224975 94.26665 26.04064 8.560323 95.1478 26.05209 8.554214 95.13407 26.2205 8.513184 95.03282 26.09172 8.539834 95.1025 25.83127 8.632414 95.26885 25.64065 8.437804 94.80424 25.68186 8.428194 94.77038 25.91637 8.591715 95.18481 39.94949 8.554957 95.13572 39.80379 8.516889 95.04485 40.31309 8.42724 94.76657 40.33361 8.431356 94.78234 39.9649 8.561372 95.14839 39.95937 8.560328 95.14781 40.08798 8.592896 95.18658 40.01884 8.42428 94.59688 40.22396 8.32901 94.43063 40.1591 8.6262 95.25431 27.475 1.065431 85.32013 27.475 1.097699 85.37628 27.21344 1.090434 85.55004 24.81746 1.050826 87.55821 24.77424 1.00364 87.52654 26.08782 0.952255 86.30997 24.8278 1.066654 87.56517 26.02387 1.107235 86.46747 25.99065 1.105806 86.49487 26.11981 1.024362 86.35592 24.86957 1.184357 87.58605 24.86463 1.158462 87.58519 27.475 1.135859 85.41751 27.475 1.170739 85.44255 27.23302 1.167804 85.59545 27.475 1.20348 85.45837 26.13292 1.113291 86.37921 26.89164 1.153125 85.82086 26.89225 1.192329 85.82952 27.23648 1.231642 85.61212 27.475 1.253273 85.47113 27.475 1.040888 85.22087 27.475 1.052361 85.28369 27.17954 1.036128 85.48497 26.84486 1.009312 85.72321 26.87641 1.071063 85.78258 24.86243 1.149476 87.58447 26.72671 0.9761614 85.7507 26.0533 0.9204065 86.28141 25.42424 0.9180271 86.82995 24.73645 0.9790191 87.4966 40.35398 8.170079 94.09488 39.81277 8.388828 93.88395 39.76798 8.449958 94.38932 40.41719 8.038136 93.74221 39.87162 8.355962 93.73207 26.15661 9.552564 98.20986 24.97318 9.095395 96.27211 24.75259 8.928083 95.66204 28.04458 9.880118 100.0832 30.53381 9.532044 100.1888 30.02343 9.97159 101.2833 31.97922 9.97159 101.8688 33 9.97159 101.9432 35.97657 9.97159 101.2833 34.02078 9.97159 101.8688 37.95542 9.880118 100.0832 41.24635 8.929163 95.66581 41.02682 9.095395 96.27211 39.84339 9.552564 98.20986 33.33811 11.49627 88.8024 33.67428 11.5 88.9809 33.87101 11.5 89.00663 30.13414 11.4 88.81567 28.88149 11.4 89.58303 29.35186 11.5 90.19028 30.46144 11.5 89.51055 32.12899 11.5 89.00663 32.01668 11.4 88.24678 32.32571 11.5 88.9809 32.80384 11.49468 88.76713 33.98331 11.4 88.24678 35.53855 11.5 89.51055 35.86586 11.4 88.81567 36.64814 11.5 90.19028 37.11851 11.4 89.58303 29.29354 11.5 90.23703 27.47049 11.38531 91.71788 28.18383 11.5 92.19513 28.64985 11.5 91.02996 27.78753 11.5 94.13834 26.97458 11.38531 94.01955 26.2238 11.05001 93.90984 27.12309 11.28008 91.80598 28.10658 11.38174 90.32252 27.92349 11.37086 90.54552 30.39021 11.5 99.47592 35.53346 11.49571 99.70079 35.60979 11.5 99.47592 35.35956 11.49112 99.8665 35.32287 11.4955 99.8854 38.26782 11.5 94.89344 38.21247 11.5 94.13834 38.17315 11.5 93.87876 37.74859 11.5 91.97337 27.73343 11.5 94.78497 30.39558 11.49981 99.51767 38.00827 11.5 96.53317 37.2513 11.5 98.0107 36.0721 11.5 99.17928 31.23461 11.491 100.109 32.94337 11.491 100.3997 34.65776 11.491 100.1442 27.95916 11.5 96.4297 28.68555 11.5 97.9225 29.84044 11.5 99.11511 30.49199 11.49455 99.73709 30.67712 11.4955 99.8854 37.26159 11.5 90.88072 27.5 7.944444 89.64302 27.38799 8.357628 90.77313 26.7036 7.944498 90.62914 26.3916 8.357628 92.69664 25.94033 7.944567 92.06364 28.9271 8.357628 89.24871 30.86007 8.357628 88.27079 32.99999 8.357628 87.93395 35.13991 8.357628 88.27079 37.07289 8.357628 89.2487 38.61199 8.357628 90.77311 39.60839 8.357628 92.69662 40.0957 7.944598 92.15512 37.12326 7.944507 88.50598 38.31687 7.944535 89.45802 39.35101 7.944567 90.71091 28.5516 7.944444 88.72768 30.66279 7.944444 87.65961 32.99999 7.944444 87.29174 34.1 7.944444 87.37167 35.67145 7.944476 87.77619 24.36104 9.566286 95.58785 24.62468 9.87877 95.97737 24.24846 9.450699 94.86997 24.6312 9.814373 96.24488 24.72727 9.947851 96.1658 24.2117 9.363241 94.90268 24.19281 9.247939 94.9409 24.34188 9.429047 95.63258 24.51192 8.769891 95.03341 24.52979 9.039229 95.69216 24.38597 8.843555 95.03191 24.43213 9.147164 95.68836 24.28578 8.948118 95.01672 24.36568 9.282758 95.66794 24.2174 9.081137 94.98759 24.19258 9.226061 94.9476 24.59017 9.587201 96.32264 24.61059 9.468082 96.34396 24.65721 9.354817 96.35162 24.8164 9.172376 96.32495 24.19031 8.557074 94.39761 24.15258 8.443392 94.26985 24.33049 8.585347 94.5656 24.23718 8.649281 94.53798 24.08385 9.033066 94.28696 24.13922 9.173767 94.61323 24.17139 9.288738 94.55007 24.00104 8.487422 93.8684 24.02051 8.355715 93.96926 24.12682 8.27026 94.14011 24.18462 8.245559 94.18949 24.06198 8.9482 94.15325 24.01703 8.696295 93.97143 24.01485 8.667213 94.00733 24.03126 8.587402 94.10588 24.07915 8.510441 94.19606 24.08393 8.295081 94.09049 24.15778 8.732919 94.49291 24.17433 8.949305 94.71679 24.23728 8.844974 94.75554 24.32265 8.758917 94.78076 24.42011 8.69622 94.79204 24.07426 8.997894 94.19824 24.07736 8.934225 94.36124 24.10231 8.830869 94.43226 24.24337 9.441286 94.84654 24.13509 1.076982 87.5746 24.1783 1.073574 87.61479 24.23608 1.110035 87.66336 24.01517 0.8763864 87.26623 24.04463 1.024869 87.43051 24.23009 0.7504258 87.37032 24.34422 0.764006 87.3591 24.36405 0.8599888 87.48121 24.08452 0.9564331 87.47136 24.1166 0.7795366 87.34626 24.15031 0.896705 87.49392 24.15325 0.7648242 87.35842 24.23179 0.8563552 87.49435 24.31317 0.8404068 87.47484 24.43334 0.9239552 87.55622 24.03037 0.8504354 87.28767 24.04044 0.8374139 87.29844 24.05919 0.817999 87.31448 24.07009 1.043685 87.48239 24.23361 1.00075 87.62124 24.35344 1.067753 87.70124 24.32042 1.129189 87.70879 24.48958 1.10832 87.73427 24.65351 1.172383 87.72505 24.53775 1.161122 87.74623 24.43089 1.147643 87.74063 24.64453 1.131597 87.7176 24.78676 1.137413 87.64707 24.83985 1.183693 87.61634 24.63369 0.97921 87.56548 24.72104 1.001254 87.5623 24.30188 0.9440349 87.60152 24.36992 0.9116304 87.56174 24.40185 0.9997708 87.66532 24.44835 0.9558445 87.60913 24.51427 1.033304 87.68929 24.53429 0.982132 87.62424 24.64183 1.05261 87.67269 24.63082 0.9973615 87.6088 24.75988 1.057471 87.61316 24.52361 0.960171 87.58372 25.5323 0.7110046 86.40731 27.05612 0.9498139 85.26879 27.475 0.9268653 84.62847 26.81063 0.7110046 85.07284 27.475 0.6425546 84.03333 27.475 0.4778812 83.84371 26.65645 0.3692808 84.94977 27.475 0.2731142 83.70359 27.475 0.04999995 83.65311 26.61554 0.04999995 84.91712 26.12271 0.04999995 85.48887 25.36834 0.04999995 86.21909 24.37953 0.4059969 87.05633 25.40272 0.3692808 86.25856 24.35851 0.6543256 87.23503 24.38977 0.05000001 86.97063 39.86035 1.120409 86.38994 39.8673 1.11187 86.3792 39.97378 1.108967 86.4691 38.525 1.07093 85.33209 39.19015 1.032522 85.79237 39.17616 1.067247 85.81972 41.13044 1.184357 87.58605 40.44384 1.108687 86.87754 41.13614 1.155007 87.58499 40.46362 1.020549 86.86113 41.17235 1.066357 87.56508 41.18411 1.048577 87.55713 40.50327 0.9479164 86.82263 41.22597 1.003452 87.52638 38.525 1.040888 85.22087 39.23204 0.9803331 85.71994 38.525 1.052269 85.28337 38.525 1.113824 85.39595 39.16646 1.106962 85.84154 38.525 1.131512 85.41366 39.16139 1.149847 85.85697 39.16098 1.193899 85.86564 38.525 1.200338 85.45713 38.63954 1.243563 85.5379 38.525 1.253013 85.47109 40.0021 1.106109 86.48887 39.88029 1.024054 86.35579 39.91233 0.9520404 86.30979 41.26355 0.9790189 87.4966 40.59712 0.9190438 86.84957 39.94671 0.920407 86.28142 39.2075 1.004589 85.76123 38.525 1.063253 85.31497 39.14397 1.192677 85.88995 27.85006 10.63677 100.239 27.92152 10.76396 100.1294 25.95803 10.42331 98.18107 29.97953 10.85909 101.3774 29.92393 10.73264 101.4967 29.91607 10.70473 101.5135 27.81102 10.41011 100.3192 29.88617 10.50603 101.5776 27.84456 10.16917 100.3066 29.89813 10.26409 101.552 29.94662 10.0871 101.448 27.94273 9.971138 100.2042 29.95699 10.06424 101.4258 26.02099 9.637723 98.29736 25.88531 9.829247 98.36253 25.87144 10.29349 98.27568 25.83118 10.06661 98.35469 34.0576 10.70473 102.1202 34.03583 10.85909 101.9716 31.96417 10.85909 101.9716 34.04712 10.0871 102.0486 31.95288 10.0871 102.0486 36.02046 10.85909 101.3774 36.08393 10.70473 101.5135 36.11369 10.5086 101.5773 34.06804 10.49493 102.1915 36.11439 10.49493 101.5788 34.0643 10.27459 102.166 36.10349 10.27459 101.5555 36.05339 10.0871 101.448 31.9424 10.70473 102.1202 31.93196 10.49493 102.1915 31.9357 10.27459 102.166 40.12816 10.29442 98.27517 40.16889 10.06916 98.3542 41.36837 9.815316 96.24444 41.40996 9.589716 96.32205 41.38941 9.468083 96.34396 40.1163 9.832924 98.36301 41.34471 9.358375 96.35159 39.98273 9.641145 98.29953 41.18793 9.175562 96.32612 38.06002 9.974726 100.2074 38.15655 10.17293 100.3076 38.18895 10.41267 100.3188 38.1496 10.63769 100.2384 41.27272 9.947851 96.1658 40.04197 10.42331 98.18107 38.07848 10.76396 100.1294 29.34768 11.38531 99.7725 31.04543 11.38531 100.6672 32.9373 11.38531 100.9891 34.83541 11.38531 100.7062 36.55123 11.38531 99.84667 37.91434 11.38531 98.49584 38.78936 11.38531 96.78787 39.0894 11.38531 94.89241 39.84815 11.05001 94.89146 39.7762 11.05001 93.90985 39.02541 11.38531 94.01955 39.51073 11.05001 97.0231 38.52668 11.05001 98.9439 36.99372 11.05001 100.463 35.06411 11.05001 101.4297 32.9295 11.05001 101.7478 30.80188 11.05001 101.3858 28.89258 11.05001 100.3796 28.01267 11.38531 98.39389 27.39123 11.05001 98.82925 27.17299 11.38531 96.66828 26.44693 11.05001 96.8886 26.91205 11.38531 94.76702 26.15348 11.05001 94.75045 37.96502 11.38531 90.45552 38.03461 11.37363 90.49263 38.67042 11.38531 92.20222 38.88666 11.27843 91.82453 38.05131 11.10042 88.37878 36.1775 11.10042 87.28781 34.08414 11.10042 86.72279 31.91586 11.10042 86.72279 29.8225 11.10042 87.28781 27.94869 11.10042 88.37878 25.59725 10.65185 92.98032 25.2 10.4 94.9 26.03874 10.84183 91.02986 27.23513 11.14213 90.04239 26.11945 10.86786 90.68843 26.03115 10.83925 91.06217 31.20522 6.622629 86.30236 32.99993 6.861519 86.30236 28.91774 6 86.63349 29.42264 6 86.4028 28.52785 7.645157 88.37686 37.472 7.645246 88.37686 40.30657 7.183207 90.89805 41.13043 4.657988 89.13813 41.13044 5.787574 90.274 41.13045 6.647323 91.62755 39.31602 6.209383 88.37686 40.72027 4.341181 88.37686 41.13043 3.309217 88.27088 41.13042 1.806905 87.71451 39.65226 1.681632 86.30236 38.525 4.5 86.52 38.525 2.920343 85.8476 38.98082 3.363069 86.30236 38.5 4.5 86.50357 37.89295 4.810346 86.30236 36.93605 4.5 85.66651 31.5 6 85.8033 31.525 6 85.79921 31.525 5.267948 85.35678 31.525 4.5 84.97154 31.9 4.5 84.92303 32.33184 4.5 84.88484 34.1 4.5 84.92303 34.79465 6.622664 86.30236 35.41069 4.5 85.15636 36.46441 5.922695 86.30236 27.475 6 87.51933 26.68386 6.209258 88.37686 27.475 5.763355 87.33309 26.34771 1.681499 86.30236 27.475 2.936981 85.85298 27.01911 3.362949 86.30236 27.475 4.303596 86.41747 24.86958 2.728104 88.01133 25.27964 4.341027 88.37686 24.86955 7.017164 92.52194 25.69329 7.183063 90.89805 24.86956 6.341961 91.06915 24.86956 6.229709 90.88919 24.86957 5.369221 89.79437 24.86957 4.146322 88.75963 31 6 85.9 24.30309 0.6415332 87.24919 24.3172 0.5092888 87.14342 24.32824 0.3627617 87.06333 24.33521 0.2092344 87.01422 24.30585 0.05000001 87.00698 24.04942 0.7053512 87.17869 24.10212 0.6702207 87.21752 24.01552 0.7473144 87.1323 24.16789 0.6470296 87.24314 24.23772 0.6379178 87.25321 24.26378 0.358168 87.0746 24.27114 0.2064711 87.02802 24.27374 0.05000001 87.01216 24.13268 0.05000001 86.98405 24.18796 0.05000001 87.00547 24.19289 0.3605412 87.06884 24.12388 0.3709756 87.04335 24.066 0.3886229 87.00023 24.02576 0.4108422 86.94592 24.00471 0.4343597 86.88842 24.25226 0.504335 87.15117 24.01673 0.05000001 86.8532 24.08387 0.05000001 86.95011 24.19093 9.285041 93.90612 24.72727 9.971098 93.83267 24.13359 8.885254 92.49893 24.72727 9.958243 93.71873 24.46668 9.606954 93.1261 24.18277 8.220167 94.17555 24.01984 8.324509 93.95165 24.08261 8.26713 94.07478 24.0238 5.756629 89.94793 24.74934 6.611435 91.77548 24.0238 6.865461 91.65544 24.13606 6.6933 91.7368 24.31944 6.581721 91.78952 24.53811 6.552531 91.80332 24.74934 2.317903 87.96451 24.53811 2.297252 88.0263 24.31944 2.307486 87.99568 24.0238 2.406962 87.69803 24.13606 2.346604 87.87863 24.0238 4.233977 88.59641 24.13606 5.612274 90.07211 24.31944 5.518716 90.15259 24.53811 5.49424 90.17365 24.74934 5.543631 90.13116 24.13606 4.127804 88.75448 24.31944 4.058992 88.85693 24.53811 4.040991 88.88374 24.74934 4.077318 88.82965 38.525 0.05588293 83.65315 38.525 0.04999995 83.65311 39.38447 0.04999995 84.91713 41.48923 0.9564898 87.58248 41.37561 0.9783393 87.56899 40.46773 0.7110046 86.40734 41.65578 0.7640079 87.3591 41.57653 0.917934 87.54986 41.63754 0.8573679 87.47795 41.65617 0.7668761 87.36288 40.59731 0.3692809 86.25859 40.63169 0.04999995 86.21912 41.61024 0.04999995 86.97061 41.61082 0.1375815 86.97563 41.6184 0.3685107 87.03882 41.63798 0.6221893 87.20484 38.525 0.2271351 83.68482 39.34357 0.3692809 84.94979 38.525 0.4156218 83.79087 39.18938 0.7110046 85.07286 38.525 0.6216115 84.00473 38.94389 0.949814 85.26881 38.525 0.8309162 84.37019 41.77489 0.9937691 87.61257 41.85011 0.8957426 87.49278 41.91596 0.9553516 87.47009 41.74144 0.7499325 87.37073 41.78199 0.7514027 87.36952 41.76856 0.8555395 87.49336 41.92539 1.046477 87.49033 41.8648 1.077025 87.57472 41.83121 1.065692 87.6049 41.76884 1.108734 87.66001 41.28337 1.05721 87.64077 41.66504 0.7612884 87.36135 41.68711 0.8397367 87.47401 41.6358 0.9069462 87.55621 41.31221 1.001041 87.5836 41.39147 0.9948791 87.61524 41.48648 0.9771258 87.62329 41.56714 0.9492103 87.60295 41.32057 1.174489 87.71611 41.54364 1.100602 87.73067 41.46219 1.161122 87.74623 41.39118 1.127835 87.72638 41.26512 1.137104 87.68011 41.67065 1.057567 87.6899 41.6815 1.128814 87.70797 41.54686 1.150737 87.74377 41.95608 1.02401 87.42881 41.9516 1.027787 87.4391 42.00008 0.9425158 87.2116 41.99853 0.958072 87.25203 41.9975 0.915212 87.23416 41.97641 1.003122 87.37234 41.98484 0.8763912 87.26624 41.97187 0.8536854 87.28501 41.94081 0.8179988 87.31449 41.91023 0.7945907 87.33383 41.89266 0.7842686 87.34236 41.7087 1.1232 87.69542 41.38761 1.04948 87.68048 41.51309 1.026922 87.68707 41.61814 0.9913363 87.65655 41.70527 0.9381936 87.5944 41.65434 8.780303 94.84611 41.5902 8.825829 95.03335 41.78126 8.61693 94.484 41.83364 8.491841 94.31935 41.90814 8.563808 94.25151 41.71906 8.712232 94.66299 41.75154 9.4507 94.86997 41.7883 9.363243 94.90268 41.84478 9.248688 94.48962 41.80743 9.226062 94.9476 41.92474 9.001721 94.20187 41.92408 9.004234 94.20426 41.9282 8.989221 94.21267 41.88761 9.115652 94.45644 41.88987 9.009678 94.52043 41.97534 8.732233 94.07418 41.97141 8.778544 94.02308 41.93818 8.947532 94.15267 41.97949 8.355715 93.96927 41.99999 8.419126 93.84249 41.99896 8.487301 93.86834 41.95739 8.646467 94.1673 41.91607 8.295081 94.09049 41.81538 8.245558 94.18949 41.7826 9.081138 94.98759 41.80645 8.97072 94.79188 41.74139 8.865866 94.82538 41.71422 8.948119 95.01672 41.61403 8.843555 95.03191 41.80146 8.798075 94.62876 41.86071 8.9003 94.57989 39.79357 11.04076 93.92588 26.24737 10.97421 96.62297 39.75263 10.97421 96.62297 41.27272 9.971097 93.83267 41.27272 9.958243 93.71873 40.8 10.4 94.9 24.87868 10.12132 94.12431 41.68796 9.55513 95.13549 41.63781 9.567469 95.59197 41.65697 9.430231 95.6367 41.63318 9.28393 95.67203 41.56675 9.148318 95.69239 41.46911 9.04036 95.69611 40.04157 10.81338 91.37368 39.96154 10.84173 91.03101 39.91192 10.85833 90.98857 38.72955 11.14794 90.014 39.94216 10.84822 90.94868 39.47921 10.96148 89.04126 41.69104 0.1338604 87.01071 41.69469 0.04999995 87.0071 41.81327 0.04999995 87.00515 41.72193 0.6062481 87.22402 41.81088 0.6100675 87.21945 41.89469 0.6347926 87.1898 41.95729 0.6758547 87.14052 41.78004 0.133305 87.01591 41.86735 0.04999995 86.98404 41.86803 0.1362346 86.98825 41.91761 0.04999995 86.94879 41.93817 0.1421158 86.93276 41.98423 0.04999995 86.85068 41.98516 0.1505244 86.85343 41.99998 0.04999887 86.76329 42.00001 0.5039723 86.86651 41.87262 0.2965917 87.01881 41.7852 0.2878236 87.04712 41.6961 0.2888016 87.04389 41.98975 0.5176127 86.95185 41.94754 0.4793457 87.02481 41.88079 0.4515573 87.0778 41.79458 0.4362587 87.10697 41.70542 0.4362582 87.10697 41.86394 2.346608 87.87863 41.9762 4.233979 88.59642 42 4.02107 88.27953 42 5.141971 89.10693 41.68056 6.581723 91.78952 41.46189 6.552531 91.80332 41.25067 6.611432 91.77548 41.86394 6.693301 91.7368 41.9762 6.86546 91.65544 41.9762 5.756629 89.94793 42 6.245589 90.3183 42 7.070023 91.73551 41.9762 2.406965 87.69803 42 2.537532 87.58148 41.68056 2.30749 87.99568 41.46189 2.297255 88.02631 41.25067 2.317905 87.96452 41.86394 4.127807 88.75448 41.68056 4.058996 88.85693 41.46189 4.040993 88.88374 41.25067 4.077318 88.82965 41.86394 5.612276 90.07211 41.68056 5.518718 90.15259 41.46189 5.494241 90.17365 41.25067 5.543629 90.13117 41.98016 8.32453 93.95166 41.91739 8.267148 94.07478 41.81724 8.220183 94.17555 41.61923 9.462752 92.96124 41.80907 9.285041 93.90611 41.80457 9.065065 92.61929 41.91963 8.689736 92.38454 42 8 92.07158 28.05157 -7.5 84.92611 25.55569 -8 85.48818 24.09268 -7.923341 87.44403 24.02455 -7.969582 87.30877 25.86587 -7.866025 85.88034 24.3409 -7.721494 87.62805 24.18981 -7.851704 87.54618 24.17114 -7.866175 87.53067 27.26007 -7 85.51634 26.17605 -7 86.27251 26.09294 -7.5 86.16742 24.86956 -7 87.49082 24.86713 -7.005202 87.49346 24.75449 -7.213155 87.58443 24.54871 -7.499804 87.65165 24.54575 -7.503365 87.65193 28.06011 -7.465131 84.94333 28.11111 -7 85.04614 29.70492 -7.465131 84.84394 29.66667 -7 84.95212 29.09453 -7 84.83998 29.09996 -7.465131 84.72535 29.83333 -7.866025 84.48072 29.8109 -7.823506 84.54418 29.71133 -7.5 84.82582 30.00106 -7.523157 84.97611 30.08766 -7.868884 84.6684 30.99999 -8.994227 86.83114 30.98977 -8.752775 86.63575 30.9878 -8.794136 86.60225 30.85206 -8.084345 86.08283 30.82614 -8.245539 85.96581 30.78536 -7.911786 85.93635 30.74975 -8.108119 85.80148 30.74951 -7.83306 85.86862 30.43227 -7.745383 85.34075 31 -8.996537 86.82926 30.98865 -8.835378 86.56856 30.99233 -8.876387 86.53476 30.83864 -8.400229 85.83827 30.88904 -8.542173 85.70538 30.76799 -8.293065 85.64828 30.83902 -8.455893 85.48565 30.47639 -8.018767 85.10897 30.62013 -8.215502 84.84244 30.42621 -7.988337 85.03896 30.57991 -8.185317 84.75563 30.12521 -7.875457 84.70216 30.3149 -8.050876 84.31906 30.27818 -8.039472 84.27304 30.49351 -7.431004 85.50754 30.43988 -7.370632 85.44966 30.37721 -7.703214 85.28186 30.08654 -7.10175 85.15863 30.04325 -7.53484 85.00346 30.03758 -7.078943 85.12794 31 -9 86.83775 41.13286 -7.005202 87.49346 41.13043 -7 87.49082 39.8132 -7 86.26402 40.1229 -7.866025 85.87147 41.82886 -7.866175 87.53067 41.81019 -7.851704 87.54618 41.6591 -7.721494 87.62805 41.45425 -7.503365 87.65193 39.89619 -7.5 86.15883 41.45129 -7.499804 87.65165 41.2508 -7.221737 87.58751 40.43259 -8 85.47892 42 -8 86.96275 42 -7.992074 87.15404 41.97545 -7.969582 87.30877 41.90732 -7.923341 87.44403 37.94842 -7.5 84.92611 38.73993 -7 85.51634 37.94074 -7.46878 84.94159 37.88888 -7 85.04613 36.91928 -7.46878 84.7226 36.16667 -7.866025 84.48072 36.18683 -7.828161 84.53775 36.28867 -7.5 84.82582 36.92373 -7 84.83921 36.33333 -7 84.95212 36.29444 -7.46878 84.84211 35.56773 -7.745383 85.34075 35.52361 -8.018767 85.10897 35.57378 -7.988337 85.03896 35.72182 -8.039472 84.27304 35.00001 -8.996537 86.82926 35.00767 -8.876387 86.53476 35.01135 -8.835378 86.56856 35.11096 -8.542173 85.70538 35.16136 -8.400229 85.83827 35.16098 -8.455893 85.48565 35.23201 -8.293065 85.64828 35 -9 86.83775 35.00001 -8.994227 86.83114 35.0122 -8.794136 86.60225 35.17386 -8.245539 85.96581 35.25025 -8.108119 85.80148 35.14794 -8.084345 86.08283 35.01023 -8.752775 86.63575 35.50649 -7.431004 85.50754 35.25333 -7.827156 85.86351 35.21464 -7.911786 85.93635 35.91234 -7.868884 84.6684 35.87479 -7.875457 84.70216 35.6851 -8.050876 84.31906 35.42009 -8.185317 84.75563 35.37987 -8.215502 84.84244 35.62279 -7.703214 85.28186 35.95675 -7.53484 85.00346 35.99894 -7.523157 84.97611 35.56013 -7.370632 85.44966 35.91347 -7.10175 85.15863 35.96242 -7.078943 85.12794 31.58645 -9.927686 84.9 31.27825 -9.721752 84.9 31.07232 -9.41355 84.9 31 -9.050001 84.9 31.94988 -10 86.29098 31.8532 -9.99507 86.3143 31.27789 -9.721395 86.46943 31.11431 -9.501788 86.54115 31.0575 -9.375482 86.58329 31.0052 -9.149256 86.68246 31 -9.050001 86.767 31.62123 -9.941298 86.3712 31.41866 -9.837512 86.42524 35 -9.050001 84.9 34.87273 -9.525001 84.9 34.525 -9.872725 84.9 34.72175 -9.721752 84.9 35 -9.050001 86.767 34.99993 -9.061986 86.75175 34.98665 -9.208695 86.65068 34.05014 -10 86.29071 34.49713 -9.888198 86.40189 34.94223 -9.376236 86.58302 34.85062 -9.561365 86.52208 34.72206 -9.721445 86.46942 33 -3.15 93.67501 33 -3.3 93.525 32.3125 -3.3 93.70922 32.3875 -3.15 93.83912 31.80921 -3.3 94.2125 31.93912 -3.15 94.2875 31.625 -3.3 94.9 31.775 -3.15 94.9 31.80921 -3.3 95.5875 31.93912 -3.15 95.5125 32.3125 -3.3 96.09078 32.3875 -3.15 95.96089 33 -3.3 96.275 33 -3.15 96.125 33.6875 -3.3 96.09078 33.6125 -3.15 95.96089 34.19078 -3.3 95.5875 34.06088 -3.15 95.5125 34.375 -3.3 94.9 34.225 -3.15 94.9 34.19078 -3.3 94.2125 34.06088 -3.15 94.2875 33.6875 -3.3 93.70922 33.6125 -3.15 93.83912 24.30585 -0.04999995 87.00698 24.38975 -0.04999995 86.97061 24.18796 -0.04999995 87.00547 24.08387 -0.04999995 86.95011 24.01673 -0.04999995 86.8532 41.61024 -0.05000019 86.97061 41.98423 -0.04999995 86.85068 41.99998 -0.04999852 86.76329 41.91761 -0.04999995 86.94879 41.81327 -0.04999995 87.00515 41.69469 -0.04999995 87.0071 41.96849 -0.8029307 87.23643 41.97969 -0.8196772 87.22098 41.9756 -0.4667882 86.96759 41.86767 -0.1071043 86.98588 41.79767 -0.1053687 87.01067 42.00001 -0.4555604 86.84561 41.99586 -0.4937537 86.91133 42.00001 -0.8922592 87.15404 41.96974 -0.1141927 86.88474 41.87888 -0.420747 87.06363 41.93614 -0.4412043 87.02095 41.92728 -0.1102021 86.94168 41.72662 -0.1051263 87.01416 41.61048 -0.1080283 86.9728 41.66669 -0.2617524 87.0273 41.61403 -0.2684867 87.00229 41.62041 -0.4048455 87.05573 41.67487 -0.4102752 87.08547 41.73086 -0.2582363 87.04039 41.9561 -0.7882291 87.24999 41.70623 -0.7113268 87.32093 41.76372 -0.7087639 87.32328 41.754 -0.5660954 87.19412 41.84102 -0.7210968 87.31191 41.82425 -0.5728724 87.18514 41.88137 -0.7358992 87.29826 41.90542 -0.7483089 87.28681 41.93758 -0.770759 87.2661 41.65008 -0.7238042 87.30941 41.68886 -0.5706378 87.18807 41.73947 -0.4053757 87.0957 41.81025 -0.4084649 87.08926 41.14216 -1.176678 87.50325 41.13043 -1.175788 87.49082 41.33987 -1.175127 87.6277 41.46495 -1.163131 87.65281 41.4348 -1.166705 87.64977 41.34869 -1.174527 87.63059 41.68146 -1.122748 87.61994 41.65545 -1.129236 87.62926 41.57057 -1.147002 87.64904 41.61013 -1.139326 87.64176 41.84069 -1.067137 87.52 41.79394 -1.087089 87.5585 41.77125 -1.095482 87.57406 41.69465 -1.119242 87.61459 41.9491 -0.9957025 87.37384 41.89852 -1.035329 87.456 41.89082 -1.040176 87.4659 41.86292 -1.056047 87.49797 41.98071 -0.9564232 87.29158 24.22455 -1.093937 87.57132 24.1388 -1.056906 87.49977 24.07566 -1.017191 87.41849 24.02556 -0.9660782 87.31183 24.00107 -0.9075111 87.18676 24.54 -1.163745 87.65243 24.44791 -1.150172 87.65131 24.38778 -1.138796 87.64128 24.32196 -1.123616 87.62126 24.31398 -1.121546 87.61814 24.23046 -1.096047 87.57517 24.67763 -1.176285 87.62142 24.86949 -1.175788 87.49076 24.3333 -0.2616652 87.02728 24.38596 -0.2684018 87.00227 24.3895 -0.1079662 86.9728 24.20232 -0.1053122 87.01065 24.27337 -0.1050692 87.01414 24.27139 -0.7091577 87.32292 24.34992 -0.7237922 87.30943 24.31112 -0.570613 87.18806 24.374 -0.4884308 87.10285 24.32512 -0.4101784 87.08544 24.37864 -0.4205834 87.06372 24.38364 -0.3264159 87.02165 24.12113 -0.4206516 87.06359 24.18976 -0.4083731 87.08922 24.09458 -0.7483041 87.28682 24.10529 -0.7423923 87.29227 24.17575 -0.572845 87.18511 24.16117 -0.7204724 87.31249 24.00415 -0.4936304 86.91131 24.03025 -0.1141268 86.88474 24.07272 -0.1101409 86.94167 24.13232 -0.1070464 86.98587 24.26914 -0.2581462 87.04036 24.26053 -0.4052832 87.09565 24.24598 -0.5660703 87.19409 24.21653 -0.7101369 87.32202 24.059 -0.7736669 87.26343 24.06388 -0.4411011 87.02092 24.02846 -0.8070735 87.23262 24.02441 -0.466675 86.96756 41.15294 -1.077446 87.4852 41.19649 -1.144767 87.54843 41.26687 -1.144155 87.59368 41.62881 -0.8208937 87.41684 41.75858 -0.7784787 87.39725 41.879 -0.8272652 87.38573 41.82053 -0.7969099 87.39762 41.92753 -0.8669204 87.36216 41.82089 -1.033609 87.53378 41.8239 -0.9360741 87.49765 41.78082 -0.9809741 87.54408 41.3449 -1.1383 87.62658 41.76171 -1.078126 87.57921 41.6614 -1.05703 87.6178 41.58773 -1.086584 87.64007 41.50873 -1.109761 87.64963 41.96166 -0.9113526 87.32994 41.93701 -0.9747087 87.39406 41.85815 -0.8828273 87.44258 41.77149 -0.8944233 87.49845 41.68342 -0.9710536 87.57553 41.72581 -1.021948 87.5853 41.55973 -1.028537 87.62195 41.41542 -1.064446 87.62406 41.42642 -1.126974 87.6453 41.71593 -0.8638052 87.48609 41.62179 -0.8314024 87.42771 41.63922 -0.9303699 87.5517 41.54452 -0.8965955 87.48725 41.53234 -0.9800114 87.5892 41.49174 -0.920289 87.50044 41.40832 -1.011003 87.5884 41.38921 -0.9461196 87.49167 41.28529 -1.024252 87.54575 41.27822 -0.9527381 87.43393 41.27239 -1.079749 87.57626 41.18169 -1.021989 87.46739 41.25408 -0.9506341 87.41223 41.19381 -1.005102 87.45891 24.85203 -1.090845 87.4877 24.8382 -1.057169 87.4802 24.71783 -1.040775 87.55757 24.13662 -0.8135201 87.3868 24.02676 -0.9276655 87.30904 24.23721 -1.083187 87.57891 24.30457 -0.7694419 87.38236 24.36656 -0.8128817 87.40848 24.69373 -0.9787024 87.50413 24.63158 -0.9490539 87.48503 24.59327 -0.9673613 87.54013 24.51581 -0.9229715 87.50121 24.49264 -0.9414625 87.54298 24.42613 -0.8780741 87.47243 24.40637 -0.9008815 87.51531 24.34232 -0.8459314 87.46279 24.74592 -0.9506376 87.41223 24.79369 -0.9902547 87.44976 24.80619 -1.005101 87.4589 24.86082 -1.120725 87.49118 24.73032 -1.124545 87.59114 24.57475 -1.107466 87.64112 24.41876 -1.068112 87.63593 24.28743 -1.006661 87.58473 24.13149 -0.9911025 87.48374 24.06821 -0.8661974 87.35578 24.19244 -0.9248337 87.50144 24.58781 -1.026518 87.60144 24.45771 -0.9937679 87.60063 24.34768 -0.942568 87.56118 24.26758 -0.8739933 87.4931 24.22086 -0.7799501 87.3954 38.58266 -1.265658 85.42192 38.0027 -1.254509 85.09873 38.0008 -1.3 85.10245 40.50654 -1.099363 86.85938 39.67734 -1.112204 86.15818 39.3718 -1.161583 85.93339 38.8666 -1.166574 85.58475 38.86814 -1.23122 85.59597 39.13864 -1.193938 85.77218 38.91741 -1.013101 85.47266 38.93813 -0.9951477 85.43611 38.42306 -1.040521 85.0789 38.00878 -1.207976 85.08683 38.01179 -1.192793 85.08094 38.04894 -1.095725 85.00815 38.87203 -1.118792 85.56632 38.88296 -1.075791 85.54017 38.07262 -1.067553 84.96174 38.89852 -1.040076 85.50815 38.09416 -1.054021 84.91956 38.17322 -1.053253 84.96015 39.70002 -0.9708371 86.10929 39.6865 -1.013377 86.13275 39.67872 -1.061461 86.14949 39.88504 -0.8982012 86.16999 39.71797 -0.9358491 86.08103 36.03111 -1.3 84.32586 36.03776 -1.192793 84.30265 36.04703 -1.140165 84.27033 36.06028 -1.095725 84.22409 36.08672 -1.054635 84.13187 36.06475 -1.085199 84.20851 37.64339 -1.054168 84.70291 34.98267 -0.6927235 84.08016 35.13634 -0.9017297 84.10945 34.92484 -0.493286 84.06729 35.31073 -1.059956 84.14544 35.30781 -1.02539 84.14346 35.69898 -1.252971 84.23626 35.72809 -1.161207 84.22421 34.91479 -0.04999995 84.04461 34.80889 -0.04999995 84.04972 34.92568 -0.58349 84.06987 35.08248 -0.04999977 83.89521 35.06483 -0.04999995 83.93102 35.08891 -0.1633976 83.89642 35.13315 -0.420019 83.94552 35.61589 -0.9654099 84.0666 35.61989 -0.940301 84.00969 35.45744 -0.8618904 84.02318 35.34943 -0.7331584 83.94863 35.33069 -0.7427794 83.99105 35.25553 -0.6149687 83.92908 35.15098 -0.4155792 83.90827 35.8112 -1.016515 84.05717 35.78966 -1.038072 84.11824 35.76006 -1.086883 84.18076 35.41561 -0.8992136 84.08662 35.83893 -1.284456 84.27266 35.36118 -0.9586004 84.13071 35.22177 -0.8242394 84.09913 35.00471 -0.462878 84.05438 34.92969 -0.04999995 84.04011 35.28455 -0.7739653 84.05481 35.08044 -0.4362709 84.00975 35.02339 -0.04999995 83.98326 34.91479 0 84.04461 34.80889 0 84.04975 35.02339 0 83.98326 35.08243 0 83.89521 30.97962 0 83.98611 30.92022 0 83.90165 30.92017 -0.04999959 83.90167 31.19111 -0.04999995 84.04972 31.19111 0 84.04975 31.08601 -0.04999995 84.04483 31.08601 0 84.04483 31.02175 -0.04999995 84.01776 30.97962 -0.04999995 83.98611 30.36625 -0.9513881 84.02427 30.19399 -1.021387 84.07627 30.22372 -1.05946 84.15138 30.46288 -0.8951597 83.9988 30.56096 -0.8783322 84.05673 30.6903 -0.7557193 84.02453 30.15953 -1.027014 84.07438 29.91607 -1.056843 84.1416 29.94184 -1.1014 84.23152 30.94496 -0.8026482 84.09368 31.15815 -0.338993 84.05531 31.02682 -0.4742746 84.06307 29.96771 -1.253852 84.32173 29.96889 -1.3 84.32586 30.282 -1.193252 84.23295 30.53352 -1.158682 84.18012 30.65942 -0.9851121 84.1395 30.80379 -0.8459738 84.10773 30.70613 -0.6722382 83.94465 30.89025 -0.4265536 83.97928 30.865 -0.3798661 83.91233 30.40022 -0.9844451 84.09996 30.2527 -1.116214 84.20278 30.60573 -0.9227964 84.10888 30.94965 -0.4461918 84.03208 30.74086 -0.7930976 84.07695 29.96275 -1.196823 84.30445 27.9973 -1.254509 85.09873 27.9992 -1.3 85.10245 29.43873 -1.057074 84.29083 27.98907 -1.196823 85.08261 27.95458 -1.1014 85.01502 27.92738 -1.067553 84.96175 27.91344 -1.057648 84.93444 29.81689 -5.1 84.40724 29.72598 -5.307336 84.67774 30.59254 -5.307336 85.20788 29.09453 -6 84.83998 29.63717 -6 84.94196 29.65699 -5.652791 84.88299 31.06221 -5.652791 86.83775 30.93902 -5.652791 86.13565 31 -6 86.83775 30.88052 -6 86.15683 30.44122 -5.652791 85.36275 30.05409 -6 85.13807 30.39774 -6 85.40725 30.7476 -6 85.86517 28.7422 -5.652791 84.79171 28.74998 -6 84.85343 28.11111 -6 85.04614 28.61183 -5.654841 84.81317 28.74354 -5.571221 84.7569 29.19073 -5.321292 84.5802 30.79198 -5.1 85.00377 31.14261 -5.307336 86.06193 31.41093 -5.1 85.96478 31.27874 -5.307336 86.83775 31.56411 -5.1 86.83775 29.7586 -5.1 84.38842 36.18311 -5.1 84.40724 36.2414 -5.1 84.38842 35.00168 -5.1 84.08366 33.78845 -5.1 93.06198 34.43589 -5.1 93.50781 34.43589 -5.1 86.83775 31.56411 -5.1 93.50781 32.21154 -5.1 93.06198 30.99831 -5.1 84.08366 33 -5.1 92.9 34.58906 -5.1 85.96478 35.20802 -5.1 85.00377 37.88889 -6 85.04614 37.40564 -5.66539 84.82048 37.2578 -5.652791 84.79171 36.36283 -6 84.94196 36.92373 -6 84.83921 37.25003 -6 84.85343 35.95629 -6 85.13169 36.34301 -5.652791 84.88299 35.60226 -6 85.40725 35.55878 -5.652791 85.36275 35.25537 -6 85.85985 35.06098 -5.652791 86.13565 35.11948 -6 86.15683 34.93778 -5.652791 86.83775 35 -6 86.83775 34.72126 -5.307336 86.83775 36.27402 -5.307336 84.67774 36.78052 -5.30759 84.56984 36.77446 -5.304682 84.56762 34.85739 -5.307336 86.06193 35.40746 -5.307336 85.20788 37.25272 -5.568563 84.75517 31 -6 93.86019 31 -6.227223 93.90001 31 -9 93.9 34.33501 -5.057784 93.79937 33.99983 -5 93.16767 35 -6 93.86019 34.96499 -5.737719 93.9 35.00038 -6 93.89997 34.73337 -5.320165 93.9 34.36602 -5.0694 93.9 31.99999 -5 93.16774 32.21154 -4.999992 93.06198 33 -4.999992 92.9 33.78845 -4.999992 93.06198 30.99962 -6 93.89998 31.09891 -5.566365 93.9 31.29627 -5.28954 93.9 31.40271 -5.197976 93.9 31.63398 -5.069402 93.9 30.9416 -6.110831 94.22512 30.94383 -6 94.199 30.98504 -6 94.03699 31.22129 -7.321883 94.81444 31.11135 -7.128067 94.55799 31.13299 -9 94.61714 31.05423 -6.962121 94.36259 31.04977 -6.947753 94.34338 31.03434 -6.869681 94.26905 31.0192 -6.76355 94.17649 31.00396 -6.538232 94.02583 31.00025 -6.330717 93.93131 31.51429 -9 95.2389 31.51428 -7.584464 95.2389 31.35187 -7.459646 95.03299 32 -10 86.83775 32 -10 93.9 31.65884 -9.940007 86.83775 31.5 -9.866025 93.9 31.00878 -9.132231 93.9 31.06004 -9.341276 86.83775 31.13397 -9.5 93.9 31.13397 -9.5 86.83775 31.17794 -9.569395 93.9 31.29294 -9.707152 86.83775 31.5 -9.866025 86.83775 35.05617 -6 94.199 35.05841 -6.110832 94.22512 35 -6.227205 93.9 34.99003 -5.900344 94.04128 34.99507 -6 94.04039 34.61861 -5.218513 94.0312 34.82048 -5.436984 94.04756 34.94996 -5.705057 94.04818 34.88914 -5.555395 94.05845 34.81777 -5.435908 94.0705 34.58789 -5.201189 94.10909 34.43162 -5.107371 94.13506 34.13533 -5 93.56896 34.23237 -5.000014 93.99291 32.3125 -5 93.70922 33 -5 93.525 33.6875 -5 93.70922 34.19078 -5 94.2125 34.25716 -5 94.34306 31.86471 -5 93.56899 31.80921 -5 94.2125 31.76763 -5.000012 93.99292 31.74285 -5 94.34306 31.38139 -5.218513 94.03119 31.56835 -5.107384 94.13504 31.00494 -6 94.04039 31.01239 -5.878861 94.0417 31.17952 -5.436984 94.04756 31.05859 -5.679071 94.04963 31.18107 -5.437565 94.07031 31.48885 -5.150352 94.12187 35 -9 93.9 34.93997 -9.34125 93.9 34.93996 -9.34128 86.83775 34.92656 -9.376144 93.9 34.70711 -9.707108 93.9 34.70705 -9.707159 86.83775 34.34125 -9.939973 93.9 34.34114 -9.940012 86.83775 34 -10 93.9 34 -10 86.83775 34.48571 -7.58443 95.2389 34.48571 -9 95.2389 34.63783 -7.469259 95.04784 34.86701 -9 94.61714 34.78006 -7.317301 94.8118 35.00001 -6.301752 93.91022 34.99816 -6.47411 93.98577 34.97975 -6.770859 94.18389 34.97167 -6.831212 94.23543 34.95847 -6.906963 94.30543 34.88945 -7.138579 94.55567 35.06439 -6.356179 94.47943 35.0595 -6.405199 94.56475 34.97082 -6.67067 94.35309 34.96985 -6.813028 94.2475 35.064 -6.22993 94.31398 34.99765 -6.434971 94.03704 34.8775 -6.983185 94.63064 34.88625 -6.869753 94.69171 34.93365 -6.690876 94.80213 35.00605 -6.55226 94.9 35.06564 -6.323883 94.42983 32.29546 -9.75 94.12145 32.20207 -9.75 94.21751 32.19018 -9.837027 94.20734 33.98791 -9.999927 94.055 33.92346 -9.985174 94.11013 33.5555 -9.985174 93.81922 33.54382 -10 93.71924 33 -9.985174 93.68482 33 -10 93.60003 32.4445 -9.985174 93.81922 32.45618 -10 93.71924 32.07654 -9.985174 94.11013 32.01211 -9.999983 94.05502 32.52001 -9.75 93.96614 32.51287 -9.837027 93.95223 32.75154 -9.75 93.87982 33 -9.837027 93.83436 33 -9.75 93.85 33.26765 -9.75 93.88468 33.48713 -9.837027 93.95223 33.47999 -9.75 93.96614 33.71908 -9.75 94.13488 33.80981 -9.837027 94.20734 33.79789 -9.75 94.21754 33.85421 -9.927609 94.16936 33.51384 -9.927609 93.90026 33 -9.927609 93.77594 32.48616 -9.927609 93.90026 32.14579 -9.927609 94.16936 31.10618 -6.825238 94.71823 31.122 -6.964532 94.63985 31.00026 -6.319462 93.95272 31.00427 -6.480894 94.08923 31.02008 -6.627499 94.28666 30.99395 -6.552258 94.9 30.93674 -6.372003 94.50564 30.93927 -6.16162 94.25527 30.93483 -6.262164 94.34905 30.9344 -6.326043 94.43299 30.93535 -6.351727 94.47229 31.59693 -7.772179 95.2993 31.57388 -9 95.28739 31.62465 -9 95.30992 31.67754 -7.953423 95.32053 31.67881 -7.956234 95.32064 31.78055 -8.178977 95.30821 31.77619 -8.169442 95.30964 31.78795 -9 95.30555 31.67887 -9 95.32064 31.94318 -8.529528 95.12952 31.91003 -8.455853 95.20715 31.87997 -9 95.24507 31.87771 -8.386798 95.24739 31.8744 -8.379746 95.25066 31.83209 -8.289469 95.28379 31.93707 -9 95.1509 31.95 -9 95.07154 31.95 -8.549263 95.07154 31.53088 -9.5211 95.0301 31.51591 -9.174027 95.21783 31.14119 -9.132231 94.61399 31.53543 -9.570299 94.98289 31.71309 -9.920287 94.42861 31.65691 -9.872871 94.5404 31.63372 -9.886041 94.42481 31.59563 -9.787303 94.70063 31.59088 -9.778019 94.71581 31.55185 -9.6671 94.87353 31.54844 -9.651947 94.89221 31.2991 -9.569395 94.55334 31.96601 -9.998608 94.09786 31.76841 -9.951728 94.33737 31.74093 -9.937585 94.38081 31.08132 -6.642837 95.17571 31.209 -6.917225 94.99237 31.22852 -7.018667 94.93914 31.35339 -7.052024 95.19787 31.52528 -7.171008 95.38873 31.21663 -6.738239 95.40651 31.28677 -6.777135 95.50449 31.39623 -6.82827 95.63745 34.27684 -5.020742 94.38979 34.37583 -5.079031 94.16043 34.32773 -5.051606 94.22497 31.72316 -5.020742 94.38979 31.66431 -5.056387 94.2099 31.60711 -5.088003 94.14871 34.81097 -9.34125 94.59562 34.59359 -9.707108 94.51212 34.3752 -9.834509 94.61721 34.2516 -9.941665 94.3689 34.23165 -9.951685 94.3376 34.08684 -9.993285 94.15214 34.22047 -9.956727 94.32082 34.47843 -9.355033 95.14816 34.46923 -9.521179 95.03018 34.4391 -9.702023 94.82761 34.43605 -9.711852 94.81417 34.05 -8.549271 95.07154 34.05 -9 95.07154 34.05031 -8.547314 95.0841 34.06278 -9 95.15044 34.05974 -8.522743 95.14064 34.07418 -8.490302 95.1788 34.11923 -9 95.24423 34.10463 -8.42458 95.22753 34.15366 -8.319835 95.27423 34.21036 -9 95.30491 34.20526 -8.209673 95.3029 34.31867 -9 95.32084 34.26054 -8.089064 95.31841 34.21869 -8.180674 95.30795 34.41701 -7.741687 95.29246 34.39163 -7.798947 95.30414 34.4234 -9 95.28896 34.34955 -7.893075 95.31658 34.29542 -8.012877 95.3215 34.43127 -7.709235 95.2843 34.62781 -7.257876 95.1011 34.7826 -6.955661 94.97019 34.64622 -7.053874 95.1969 34.7778 -6.741575 95.4146 34.6038 -6.828299 95.63746 34.91865 -6.642857 95.17577 34.46258 -7.379713 95.29716 34.46906 -7.213155 95.36735 34.47443 -7.172865 95.38775 34.05 -8.550001 94.9 34.0497 -8.525 94.875 33.99853 -8.824703 94.57533 31.95385 -9.4864 94.81023 32.03292 -9.689511 94.49103 32.00783 -8.843651 94.55625 31.9503 -8.525 94.875 31.95 -8.550001 94.9 31.95 -9.390825 94.9 32.7467 -9.51899 93.88156 32.48033 -9.412385 93.98764 32.28746 -9.27122 94.12892 32.10791 -9.053791 94.34642 32.08988 -9.023629 94.37659 33.72588 -9.258679 94.14145 33.54336 -9.398475 94.0016 33.27078 -9.514483 93.88589 33.19421 -9.531883 93.86824 33.00041 -9.55 93.84976 32.88233 -9.543387 93.85675 33.8481 -9.746126 94.28113 33.8872 -9.061576 94.33866 34.00362 -9.641942 94.59137 33.91034 -9.023241 94.37699 34.04996 -9.390825 94.9 34.15275 -9.954818 94.37821 34.36767 -9.705039 94.89299 34.442 -9.677424 94.86559 34.04603 -9.676257 94.69644 34.05802 -9.435276 94.94439 34.17105 -9.79571 94.72914 34.13876 -9.526015 95.03501 34.09893 -9.74638 94.72039 34.08633 -9.482668 94.99172 34.06506 -9.451295 94.96039 34.4404 -9.537191 95.04617 34.37535 -9.559496 95.06844 34.35186 -9.563876 95.07281 34.35929 -9.706657 94.89503 34.29588 -9.567699 95.07663 34.27201 -9.709021 94.90605 34.26409 -9.56589 95.07482 34.21229 -9.556478 95.06543 34.35 -9.816774 94.69847 34.34188 -9.818538 94.70127 34.2565 -9.821117 94.72244 34.17951 -9.545824 95.05479 33.95848 -9.796837 94.4354 34.00768 -9.873312 94.43048 34.07426 -9.92711 94.41078 31.63874 -9.699225 94.90526 31.65294 -9.806904 94.72328 31.72714 -9.811209 94.7417 31.94198 -9.435276 94.94439 31.8155 -9.943811 94.41733 31.68796 -9.882285 94.55451 31.5752 -9.67939 94.88465 31.78771 -9.556477 95.06543 31.72254 -9.567003 95.07595 32.1457 -9.874311 94.23313 32.16789 -9.809807 94.24735 32.03525 -9.76208 94.46656 31.96056 -9.64456 94.70318 31.92858 -9.701764 94.72686 32.00445 -9.82446 94.47052 31.87569 -9.754546 94.74363 31.95436 -9.882019 94.46404 31.80535 -9.793406 94.74916 31.88837 -9.924396 94.44567 31.99051 -9.997722 94.11711 32.05228 -9.977646 94.16477 32.10643 -9.933827 94.20522 31.5596 -9.537191 95.04617 31.62465 -9.559496 95.06844 31.64612 -9.563566 95.0725 31.70412 -9.567699 95.07663 31.86124 -9.526015 95.03501 31.91366 -9.482668 94.99172 31.95 -8.550001 95 31.95 -9.183609 95.03717 31.95 -9.3482 94.93914 31.86124 -9.471044 95.08547 31.78771 -9.498726 95.11843 31.5596 -9.257676 95.2303 31.5596 -9.481201 95.09756 31.62465 -9.501469 95.12171 31.70412 -9.508922 95.13058 31.62465 -9.268963 95.25973 31.70412 -9.273114 95.27056 31.78771 -9.267436 95.25575 31.86124 -9.25202 95.21555 31.91366 -9.431657 95.03855 31.94198 -9.388591 94.98725 31.91366 -9.230085 95.15835 31.94198 -9.206103 95.09582 34.08633 -9.264457 95.14406 34.4404 -9.295998 95.21437 34.4404 -9.048569 95.27672 34.37535 -9.050728 95.30817 34.37535 -9.308901 95.24314 34.29588 -9.313645 95.2537 34.29588 -9.051522 95.31974 34.21229 -9.050436 95.30391 34.21229 -9.307154 95.23924 34.13876 -9.289532 95.19995 34.13876 -9.047489 95.26097 34.08633 -9.043293 95.19985 34.05802 -9.237042 95.08296 34.05802 -9.038707 95.13303 34.05 -9.211328 95.02565 34.05 -9.034406 95.07036 34.05 -8.550001 95 34.05 -8.5 94.9 34.0497 -8.525 94.9 33.99108 -8.203207 94.9 32.29159 -7.774975 94.9 32.00892 -8.203207 94.9 31.98578 -8.22824 94.9 31.95898 -8.362949 94.9 32.09067 -7.975 94.9 32.475 -7.590673 94.9 32.74344 -7.531826 94.9 33 -7.45 94.9 33.25656 -7.531826 94.9 33.525 -7.590673 94.9 33.7084 -7.774975 94.9 33.90933 -7.975 94.9 33.8763 -7.971558 94.9 34.01422 -8.22824 94.9 31.9503 -8.525 94.9 31.95 -8.5 94.9 31.95546 -8.443077 94.9 31.967 -8.361807 94.9 32.00892 -8.203207 95 33.99108 -8.203207 95 33.7084 -7.774975 95 32.29159 -7.774975 95 32.74344 -7.531826 95 33 -7.5 95 33.25656 -7.531826 95 33.97628 -8.162852 95.06352 33.74246 -7.806961 95.05615 33.3865 -7.573192 95.0513 33 -7.49948 95.04977 32.6135 -7.573191 95.0513 32.25754 -7.806956 95.05615 32.13928 -7.948007 95.05907 32.02372 -8.162842 95.06352 34.35395 -7.347208 95.41812 34.28274 -7.441043 95.42592 34.21648 -7.537508 95.41856 34.15561 -7.636309 95.3983 34.10323 -7.732593 95.368 34.0497 -7.848978 95.31872 34.01195 -7.953299 95.26273 33.98871 -8.042631 95.20401 33.97801 -8.110161 95.14789 33.97573 -8.141011 95.11294 33.97578 -8.159037 95.08003 33.38548 -7.569951 95.10176 33.39995 -7.529678 95.30545 33.06838 -7.468299 95.38399 33.44009 -7.472164 95.46768 33.32931 -7.363168 95.73629 33.83398 -7.157603 95.94299 33.78097 -7.179602 95.9368 33.78773 -7.187556 95.91512 33.74215 -7.195647 95.93025 33.63117 -7.297863 95.78461 33.51607 -7.393321 95.63217 33.74117 -7.803498 95.08193 33.73904 -7.787477 95.13398 33.7395 -7.759815 95.19061 33.75121 -7.698329 95.28464 33.78419 -7.615329 95.38665 33.84343 -7.516356 95.48685 33.93196 -7.40364 95.57754 34.02114 -7.308665 95.63498 33.9438 -7.111667 95.94604 34.12671 -7.209578 95.67518 34.10569 -7.043078 95.92648 34.24327 -7.111155 95.69251 34.24181 -6.984648 95.88652 34.36992 -7.013665 95.68259 31.67946 -7.01647 95.73749 31.45376 -6.864865 95.66916 31.52666 -7.039707 95.51348 32.17371 -7.160788 95.94232 32.33335 -7.269131 95.82433 32.20597 -7.174181 95.93864 31.9931 -7.084999 95.94198 31.95223 -7.231753 95.69901 32.07134 -7.344212 95.63395 32.9061 -7.457777 95.4401 32.61391 -7.551449 95.21464 32.99903 -7.498518 95.08433 31.95326 -8.132639 95.2191 31.97204 -8.207195 95.16957 31.9816 -8.258778 95.1205 31.83468 -7.824126 95.34141 31.88289 -7.932943 95.30914 31.92376 -8.039802 95.26661 31.77773 -7.710232 95.36357 31.71921 -7.604649 95.37248 31.65624 -7.501065 95.36799 32.64782 -7.353991 95.75461 32.45711 -7.366322 95.68009 32.54193 -7.447352 95.52381 32.59178 -7.509815 95.36598 31.44344 -6.84847 95.68663 31.77517 -6.992025 95.89263 31.69442 -7.187157 95.56213 31.56114 -7.361258 95.33145 32.30554 -7.742834 95.14823 32.30108 -7.698507 95.23943 32.28078 -7.632773 95.34064 32.23711 -7.548548 95.44659 32.16532 -7.448741 95.54931 32.14277 -7.924562 95.12395 32.14157 -7.877679 95.1888 32.1293 -7.808838 95.26213 32.0999 -7.72158 95.34008 32.04948 -7.619289 95.41664 31.982 -7.513249 95.48047 31.89534 -7.400285 95.53027 31.80081 -7.29368 95.55776 33.25592 -7.264546 96.00752 34.06141 -6.642851 96.52194 34.34624 -6.642852 96.2946 34.63534 -6.642854 95.94064 34.85683 -6.642856 95.45629 32.74405 -7.264546 96.0075 31.76016 -6.642842 96.39 31.65326 -6.642842 96.29413 31.2804 -6.642839 95.7946 32.48365 -6.642845 96.76834 31.14296 -6.642838 95.45564 33.49044 -6.642848 96.7753 33.30014 -6.642848 96.815 32.3125 -5.020742 96.09078 32.04468 -5.020742 95.88893 31.81805 -5.151254 96.12353 31.34028 -5.151254 94.52671 34.97233 -5.471708 94.45714 34.65985 -5.151254 94.5273 35.11477 -5.9006 94.42516 35.07625 -5.9006 95.52203 35.02044 -6.349895 95.50531 34.46487 -6.349895 96.41748 33.53366 -6.349895 96.94054 31.53459 -6.349895 96.41696 32.46561 -6.349895 96.94036 30.97934 -6.349895 95.5046 30.8854 -5.9006 94.4244 31.65851 -5.020742 94.59828 31.37021 -5.151254 95.38764 31.80921 -5.020742 95.5875 31.6827 -5.020742 95.29415 31.625 -5.020742 94.9 32.65163 -5.020742 96.23014 32.56898 -5.151254 96.54567 33 -5.020742 96.275 33.43043 -5.151254 96.54583 33.3479 -5.020742 96.23026 33.6875 -5.020742 96.09078 34.18151 -5.151254 96.12395 33.95497 -5.020742 95.88928 34.19078 -5.020742 95.5875 34.62961 -5.151254 95.38822 34.31716 -5.020742 95.29462 34.375 -5.020742 94.9 34.34159 -5.020742 94.59877 31.02782 -5.471708 94.45644 31.06339 -5.471708 95.47945 31.59554 -5.471708 96.35388 32.48784 -5.471708 96.85549 33.51146 -5.471708 96.85567 34.40394 -5.471708 96.35437 34.93641 -5.471708 95.48014 30.92353 -5.9006 95.5213 31.49412 -5.9006 96.45886 32.45085 -5.9006 96.99671 33.5484 -5.9006 96.99691 34.50533 -5.9006 96.45941 27.4052 -1.264313 85.42909 27.13193 -1.231151 85.59593 26.74322 -1.177315 85.85275 25.96109 -1.096133 86.44697 26.3221 -1.124149 86.15897 27.475 0 83.65311 38.525 0 83.65311 26.19634 0 85.40884 25.62152 -0.04999995 85.99085 26.19634 -0.04999995 85.40884 39.79852 0 85.40318 39.79852 -0.04999995 85.40318 40.35518 -0.04999995 85.96903 39.72364 0.0670588 46.24539 36.34887 0.07887524 44.29877 25.60491 0.1412824 37.39509 30.37539 0.1153646 41.04082 28.33421 0.1303206 39.7014 26.55311 0.1396799 38.28554 25.609 0.1412824 37.39917 32.70687 0.09875792 42.3628 23.12089 0.2092217 31.98277 24.34239 0.1507403 35.7238 25.11744 0.1424378 36.85766 25.25393 0.141864 37.01896 23.73982 0.1669594 34.4213 23.49897 0.1781553 33.69792 26.375 -11 0 26.375 9.334449 -5.819627 26.375 10.8055 -2.05942 26.375 -10.25895 -3.96913 26.375 -8.135639 -7.403471 26.375 -4.916159 -9.840294 26.375 6.605706 -8.795718 26.375 2.986932 -10.5867 26.375 -1.034292 -10.95127 17.75 7.986611 -0.4626535 17.75 -7.772853 -1.892814 17.75 -0.3104059 -7.993976 17.75 -2.344545 -7.648732 17.75 7.602675 -2.489845 17.75 6.713053 -4.351428 17.75 5.376917 -5.923577 17.75 3.683139 -7.101725 17.75 -4.222738 -6.794739 17.75 -5.820059 -5.488799 17.75 -7.030263 -3.817775 17.75 1.744379 -7.807505 34.88123 -0.1999999 16.71603 37.38357 -0.1999999 16.80893 -17.86531 -7.997167 82.97203 -18.10161 -7.997594 83.07537 -12.89557 -0.04999995 84.04897 -13.09519 0 83.85195 -13.09525 -0.04999947 83.85195 -13.08532 -0.04999995 83.88755 -13.06499 0 83.93075 -12.89557 0 84.04897 -12.99306 0 84.00818 -12.99306 -0.04999995 84.00818 -13.06499 -0.04999995 83.93075 -13.81176 -1.02311 84.07808 -12.97271 -0.4730225 84.06298 -13.19439 -0.8438977 84.10735 -13.34698 -0.9903015 84.14096 -13.72462 -1.195456 84.23472 -13.65556 -0.9457876 83.94152 -13.48198 -0.8548734 83.98201 -13.50221 -0.8516258 83.89875 -13.34787 -0.7310742 83.94752 -13.29359 -0.641323 83.8462 -13.15275 -0.4137671 83.90203 -13.16572 -0.4125506 83.85056 -13.13603 -0.3277608 83.85123 -13.78219 -1.06134 84.15318 -13.7535 -1.118252 84.20455 -13.83503 -1.014258 83.99601 -13.63958 -0.9543805 84.02597 -13.60575 -0.9876182 84.10163 -13.40027 -0.9276301 84.11035 -13.44478 -0.8828918 84.05821 -13.30807 -0.7538858 84.02414 -13.10933 -0.4254429 83.97919 -13.0499 -0.4450228 84.03199 -13.25744 -0.7911612 84.07657 -17.08444 -0.04999995 84.52149 -16.21419 -0.04999995 83.06681 -16.21419 0 83.06681 -18.4464 -0.04999995 86.05361 -16.54821 -0.9906947 84.90755 -16.84403 -0.7604314 84.69458 -18.24633 -0.7604314 86.27209 -19.45924 -0.8517897 87.35362 -18.40416 -0.398106 86.09974 -16.07061 -0.5937921 83.13919 -16.15853 -0.3981055 83.09535 -17.03368 -0.398106 84.55803 -16.18902 -0.2862781 83.0798 -15.94838 -0.7604385 83.1976 -15.86648 -0.8395361 83.23513 -15.59529 -0.9976264 83.35047 -13.64543 -0.9407109 83.82212 19.60195 10.75361 -0.622942 20.75 10.98159 -0.6361486 17.97836 -8.888307 -2.164445 18.62868 -9.833944 -2.394722 19.60195 -10.4658 -2.548589 19.60195 10.23666 -3.352465 20.75 10.8055 -2.05942 20.75 10.45368 -3.423538 20.75 9.334449 -5.819627 19.60195 9.038824 -5.859001 20.75 9.230448 -5.983213 20.75 7.39326 -8.144919 19.60195 7.239776 -7.975829 20.75 6.605706 -8.795718 19.60195 4.95918 -9.562151 20.75 5.064316 -9.764871 20.75 2.986932 -10.5867 19.60195 2.348728 -10.51245 20.75 2.398522 -10.73532 20.75 -0.4268081 -10.99172 19.60195 -0.4179475 -10.76353 20.75 -1.034292 -10.95127 19.60195 -3.156824 -10.29867 20.75 -3.223749 -10.51701 19.60195 -5.685726 -9.14881 20.75 -4.916159 -9.840294 20.75 -5.806265 -9.342766 20.75 -8.002581 -7.547098 19.60195 -7.836447 -7.39042 20.75 -8.135639 -7.403471 19.60195 -9.465931 -5.140461 20.75 -10.68767 -2.602619 20.75 -10.25895 -3.96913 20.75 -9.666612 -5.249441 18.62868 -8.894443 -4.830115 18.62868 -7.363335 -6.944236 18.62868 -5.342461 -8.596467 18.62868 -2.966236 -9.676909 18.62868 -0.3927147 -10.1137 18.62868 2.206928 -9.877783 18.62868 4.659779 -8.984854 18.62868 6.802687 -7.494302 18.62868 8.493121 -5.505274 18.62868 9.618639 -3.150065 18.62868 10.10438 -0.5853329 17.97836 -8.03915 -4.365649 17.97836 -6.655274 -6.276476 17.97836 -4.828728 -7.769827 17.97836 -2.681002 -8.746374 17.97836 -0.3549512 -9.141162 17.97836 1.994709 -8.927932 17.97836 4.211693 -8.120867 17.97836 6.148538 -6.773648 17.97836 7.676418 -4.975885 17.97836 8.693708 -2.847155 17.97836 9.13274 -0.529047 18.43259 -8 89.47892 3.55569 -8 89.48818 44.82174 2.44762 50.58581 44.48014 1.4 50.47461 44.87646 2.8 50.32464 44.87638 2.777199 50.32447 44.87353 2.69804 50.33348 44.87194 2.67663 50.33959 44.84444 2.486835 50.44276 44.83523 2.455887 50.48719 44.8269 2.442913 50.54039 43.46329 0.3751289 50.34667 18.21922 -0.3928334 89.92335 19.45924 -0.851789 91.35362 18.06184 -0.7515894 90.08668 17.76386 -0.9072189 90.0706 16.73537 -0.9560475 89.0206 16.93814 -0.9951477 89.43611 16.24802 -1.046932 88.93543 16.16749 -1.049693 88.91319 17.40098 -0.3412906 89.00681 17.25811 -0.5992912 89.0223 17.10627 -0.7531332 89.03121 17.03578 -0.8059881 89.03273 17.67872 -1.061461 90.14949 17.67734 -1.112204 90.15818 16.8666 -1.166574 89.58475 16.87203 -1.118792 89.56632 16.88296 -1.075791 89.54017 16.89852 -1.040076 89.50814 16.91742 -1.013101 89.47266 17.68651 -1.013377 90.13276 17.70002 -0.9708371 90.10929 17.71797 -0.9358491 90.08103 17.86035 -7.382683 90.20426 17.99462 -7.707107 90.03407 18.19556 -7.92388 89.77937 6.262549 -1.055051 88.75128 5.893211 -1.05057 88.89481 5.906222 -1.054174 88.92031 5.929673 -1.069616 88.96624 5.947734 -1.090751 89.00164 5.968224 -1.12847 89.04177 5.980669 -1.163198 89.06616 5.991216 -1.207976 89.08683 5.997298 -1.254509 89.09873 5.99268 -1.216566 89.08969 7.100031 -7.468149 88.72377 6.0594 -7.468149 88.9419 3.502165 -0.8857862 90.69766 4.236092 -0.9072052 90.07065 3.939553 -0.7515902 90.08535 2.540755 -0.8517897 91.35362 3.782141 -0.3928339 89.92204 4.593685 -0.3257692 89.0061 4.894826 -0.7540283 89.03125 4.761369 -0.6231864 89.02388 5.021308 -0.8428159 89.03275 5.394692 -0.99485 89.00594 5.061837 -0.9951457 89.43614 5.832519 -1.049693 88.91319 5.082557 -1.0131 89.47267 5.133378 -1.166575 89.58477 5.13316 -1.216041 89.59458 4.322598 -1.112192 90.15823 3.129515 -1.067318 91.20213 5.101449 -1.040076 89.50817 5.117017 -1.075791 89.54019 5.127941 -1.118793 89.56634 3.090571 -0.9775598 91.17549 3.561327 -0.9505965 90.73496 3.590271 -1.043631 90.76305 4.299919 -0.9708256 90.10933 4.28197 -0.935837 90.08109 4.32122 -1.061449 90.14953 4.313435 -1.013366 90.1328 3.793091 -7.92388 89.78833 4.128827 -7.382683 90.21281 3.99435 -7.707107 90.04279 40.31949 -0.3686949 86.00705 40.18494 -0.7099729 86.15036 38.92451 -0.9537629 85.2577 39.36495 -0.7585376 85.35595 39.62233 -0.5290173 85.38976 39.7513 -0.3051672 85.40035 26.08406 -0.8962015 86.1956 25.42588 -0.8886124 86.76639 25.56133 -0.9505965 86.73496 25.12952 -1.067318 87.20212 27.85792 -1.057298 84.96306 27.13316 -1.216041 85.59458 26.3226 -1.112192 86.15823 25.59027 -1.043631 86.76305 27.10145 -1.040076 85.50817 27.08256 -1.0131 85.47268 27.51212 -1.036461 85.12217 27.11702 -1.075791 85.54019 27.12794 -1.118793 85.56634 27.13338 -1.166575 85.58477 25.09057 -0.9775598 87.17549 26.32122 -1.061449 86.14953 26.31344 -1.013366 86.13281 26.29992 -0.9708256 86.10933 26.28197 -0.935837 86.08109 27.06184 -0.9951457 85.43614 25.91609 -0.8729123 86.30661 25.68881 -0.4830723 86.06298 26.24008 -0.2966951 85.40661 26.99965 -0.9341793 85.28984 26.84611 -0.8761371 85.32563 26.63069 -0.7612471 85.36528 26.37356 -0.5319862 85.39684 -3.659246 -0.4753884 86.08546 -3.877921 -0.8623436 86.32159 -2.559685 -0.8963338 87.41896 -4.815495 -0.8669411 85.34181 -5.067279 -0.9587647 85.28521 -4.242069 -0.3084982 85.40901 -4.372437 -0.5355522 85.40108 -4.630535 -0.7658675 85.37269 -5.887493 0 84.97338 -8.42756 -0.5581032 84.04006 -15.76146 -0.55 83.28139 44.78398 3 51.63153 44.85869 2.903034 51.1089 44.85831 3 51.11178 44.91973 2.777199 50.58483 44.91973 3 50.58483 44.86734 2.606443 50.70095 44.87224 2.58302 50.63324 44.6864 2.97945 52.16585 44.69511 3 52.13785 44.6642 3 52.29616 44.8951 2.622569 50.48309 44.91164 2.687489 50.48359 44.92023 2.731501 50.53071 44.91541 2.777199 50.45095 44.91541 3 50.45095 6.262549 0 88.75128 5.424028 0 89.00183 16.57597 0 89.00183 15.73745 0 88.75128 13.58708 -0.5524861 88.00289 38.17322 0 84.96015 35.58733 -0.5523176 84.00196 27.85792 0 84.96306 30.41535 -0.5534214 84.01006 -20.03731 7.242537 52.43054 -21.33952 5.349134 53.38708 -21.39219 5.430727 53.55628 -21.37589 5.485245 53.74288 -21.29309 5.504388 53.91849 -22.20014 2.850607 54.55362 -22.27979 2.840694 54.37581 -22.28712 2.81246 54.18291 -22.221 2.770205 54.0043 13.35 0 68.65 14.35 0 68.65 13.35 0 67.6 14.35 0 67.6 14.35 3.5 68.65 14.35 3.5 67.6 14.21603 4 67.6 13.85 4.366025 67.6 13.35 4.5 67.6 13.35 4.5 68.65 13.85 4.366025 68.65 14.21603 4 68.65 16.03841 0 70.90145 15.99715 0 70.92485 16.55073 0 71.41286 16.53841 0 71.42047 17.25 0 71.60001 17.25 4 71.60001 16.55073 4 71.41286 16.03841 4 70.90145 15.99715 4 70.92485 16.53841 4 71.42047 6.002849 0 70.92485 5.961595 0 70.90145 5.461594 0 71.42047 5.449273 0 71.41286 4.75 0 71.60001 5.961595 4 70.90145 5.449273 4 71.41286 4.75 4 71.60001 5.461594 4 71.42047 6.002849 4 70.92485 20.1 4 75.95001 20 4 75.51412 20 4 75.95001 20 6 75.95001 20.1 6 75.95001 20 6 75.51412 -2 4.5 71.95001 -1.975 4.5 71.95001 -2 4 71.95001 -1.975 4 71.95001 -2 4 71.7278 -2 4.5 71.7278 1.9 0 71.60001 1.9 4 71.60001 3.9 0 71.60001 3.9 4 71.60001 2.033974 4 71.1 3.4 4 70.73398 3.766025 4 71.1 2.9 4 70.6 2.4 4 70.73398 2.033974 0 71.1 2.4 0 70.73398 2.9 0 70.6 3.4 0 70.73398 3.766025 0 71.1 2 4 75.51412 1.9 4 75.95001 2 4 75.95001 2 6 75.95001 1.9 6 75.95001 2 6 75.51412 -40.575 -0.5 21.5 -40.675 -0.4 21.5 -40.47739 -0.4 20.7625 -40.39078 -0.5 20.8125 -39.9375 -0.4 20.22261 -39.8875 -0.5 20.30922 -39.2 -0.4 20.025 -39.2 -0.5 20.125 -38.4625 -0.4 20.22261 -38.5125 -0.5 20.30922 -37.92261 -0.4 20.7625 -38.00922 -0.5 20.8125 -37.725 -0.4 21.5 -37.825 -0.5 21.5 -37.92261 -0.4 22.2375 -38.00922 -0.5 22.1875 -38.4625 -0.4 22.77739 -38.5125 -0.5 22.69079 -39.2 -0.4 22.975 -39.2 -0.5 22.875 -39.9375 -0.4 22.77739 -39.8875 -0.5 22.69079 -40.47739 -0.4 22.2375 -40.39078 -0.5 22.1875 -37.92261 0 22.2375 -38.4625 0 22.77739 -39.2 0 22.975 -39.9375 0 22.77739 -40.47739 0 22.2375 -40.675 0 21.5 -40.47739 0 20.7625 -39.9375 0 20.22261 -39.2 0 20.025 -38.4625 0 20.22261 -37.92261 0 20.7625 -37.725 0 21.5 -40.54234 0 20.725 -39.975 0 20.15766 -39.2 0 19.95 -38.425 0 20.15766 -37.85766 0 20.725 -37.65 0 21.5 -37.85766 0 22.275 -38.425 0 22.84234 -39.2 0 23.05 -39.975 0 22.84234 -40.54234 0 22.275 -40.75 0 21.5 -40.49904 -0.5 22.25 -39.95 -0.5 22.79904 -39.2 -0.5 23 -38.45 -0.5 22.79904 -37.90096 -0.5 22.25 -37.7 -0.5 21.5 -37.90096 -0.5 20.75 -38.45 -0.5 20.20096 -39.2 -0.5 20 -39.95 -0.5 20.20096 -40.49904 -0.5 20.75 -40.7 -0.5 21.5 -40.7 -0.0866025 21.5 -40.49904 -0.0866025 22.25 -39.95 -0.0866025 22.79904 -39.2 -0.0866025 23 -38.45 -0.0866025 22.79904 -37.90096 -0.0866025 22.25 -37.7 -0.0866025 21.5 -37.90096 -0.0866025 20.75 -38.45 -0.0866025 20.20096 -39.2 -0.0866025 20 -39.95 -0.0866025 20.20096 -40.49904 -0.0866025 20.75 -33.65704 0 19.90779 -34.27294 0 20.22576 -33.71062 0 19.83202 -33.71062 -0.7611421 19.83202 -33.68999 -0.4497478 19.86119 -33.66559 -0.1482408 19.89569 -34.19855 -0.3615938 20.17367 -33.99301 -0.6373495 20.02975 42.2084 -12.4746 83.02506 42.2084 -12.4746 73.21286 42.23523 -12.4746 82.80922 42.23523 -12.4746 73.42666 42.2084 -12.50446 82.93309 42.2084 -12.51764 82.81538 42.2084 -12.51764 73.43614 35.4535 -28.67636 14.28793 35.4535 -14.35754 14.28793 35.61182 -15.23121 14.44746 35.86505 -16.55913 14.70261 36.12701 -17.90912 14.96657 37.22636 -23.92482 16.07429 37.54417 -25.92879 16.39452 37.56209 -26.47425 16.41257 37.54259 -26.63727 16.39293 37.45666 -26.99173 16.30633 37.33153 -27.28117 16.18026 36.94976 -27.72728 15.79558 37.24696 -27.41979 16.09504 41.82282 -23.35718 12.60193 41.56604 -22.93638 12.8228 41.68348 -22.80633 12.71715 41.79517 -22.67262 12.61532 41.85027 -22.7627 12.5886 41.8832 -22.88918 12.57257 39.16473 -19.74985 13.7489 41.50252 -24.0533 12.75527 40.95181 -24.85381 13.00944 39.16473 -26.5384 13.7489 39.55747 -26.23881 13.59782 40.6356 -25.2282 13.14989 36.64868 -17.49437 14.59033 36.64868 -28.06672 14.59033 37.36546 -27.69854 14.35062 37.99253 -18.50484 14.14092 38.59598 -25.38729 15.47185 40.63083 -23.86056 13.6597 36.95178 -20.78357 15.3491 38.63876 -22.50108 14.72801 40.03899 -24.37203 14.18907 36.53269 -17.17028 14.56098 37.52185 -27.4757 15.32054 38.58637 -26.89769 14.4255 40.89089 -24.37361 13.4197 40.33279 -25.39711 13.56597 38.7966 -25.9825 15.29 38.79318 -26.52002 14.91763 40.28388 -24.90909 13.96405 35.84322 -15.34428 14.38654 -21.175 0 15.48078 -21.175 0.3272668 15.48078 -21.175 0 14.85628 -21.175 0.3272668 14.85628 -19.90023 0.3272668 15.48078 -19.90023 0 15.48078 -19.9 0 15.5 -21.39282 4.5 15.1 -21.1 4.5 14.80718 -21.1 0.3272668 14.80718 -20.7 4.5 14.7 -20.7 0.3272668 14.7 -20.3 4.5 14.80718 -20.3 0.3272668 14.80718 -20.00718 4.5 15.1 -20.00718 0.3272668 15.1 -19.9 4.5 15.5 -20.00718 4.5 15.9 -20.00718 0 15.9 -20.3 4.5 16.19282 -20.3 0 16.19282 -20.7 4.5 16.3 -20.7 0 16.3 -21.1 4.5 16.19282 -21.1 0 16.19282 -21.39282 4.5 15.9 -21.39282 0 15.9 -21.5 4.5 15.5 -21.5 0 15.5 -21.39282 0 15.1 -20.7 4.5 15.5 7.65 0 67.6 8.650001 0 67.6 7.65 3.5 67.6 8.650001 4.5 67.6 7.783975 4 67.6 8.150001 4.366025 67.6 8.650001 0 68.65 7.65 0 68.65 8.650001 4.5 68.65 8.150001 4.366025 68.65 7.783975 4 68.65 7.65 3.5 68.65 -10.13397 9.600001 74 -10.5 9.600001 74.36602 -11 9.600001 74.5 -11.86603 9.600001 73 -11.5 9.600001 72.63397 -11 9.600001 72.5 -12 9.600001 73.5 -11.86603 9.600001 74 -11.5 9.600001 74.36602 -10 9.600001 73.5 -10.13397 9.600001 73 -10.5 9.600001 72.63397 -10 9.050001 73.5 -10.13397 9.050001 74 -10.5 9.050001 74.36602 -11 9.050001 74.5 -11.5 9.050001 74.36602 -11.86603 9.050001 74 -12 9.050001 73.5 -11.86603 9.050001 73 -11.5 9.050001 72.63397 -11 9.050001 72.5 -10.5 9.050001 72.63397 -10.13397 9.050001 73 -11 9.050001 73.5 11.59772 9.600001 72.40171 10.40228 9.600001 72.40171 11.59772 9.050001 72.40171 10.40228 9.050001 72.40171 11.21193 9.600001 72.57729 10.78807 9.600001 72.57729 11.21193 9.050001 72.57729 10.78807 9.050001 72.57729 33 9.600001 74.5 32.5 9.600001 74.36602 32.13397 9.600001 74 33 9.600001 72.5 33.5 9.600001 72.63397 33.86602 9.600001 73 33.86602 9.600001 74 33.5 9.600001 74.36602 34 9.600001 73.5 32 9.600001 73.5 32.5 9.600001 72.63397 32.13397 9.600001 73 34 9.050001 73.5 33.86602 9.050001 74 33.5 9.050001 74.36602 33 9.050001 74.5 32.5 9.050001 74.36602 32.13397 9.050001 74 32 9.050001 73.5 32.13397 9.050001 73 32.5 9.050001 72.63397 33 9.050001 72.5 33.5 9.050001 72.63397 33.86602 9.050001 73 33 9.050001 73.5 39.8567 8 66.46176 39.36585 8 66.50459 38.94858 8 66.7666 39.36585 8 68.49542 39.8567 8 68.53824 40.31304 8 68.35245 40.63439 8 67.02104 40.31304 8 66.64756 40.75 8 67.5 40.63439 8 67.97896 38.94858 8 68.2334 40.31304 8.75 68.35245 40.225 8.75 68.40933 39.7 9.380905 67.5 39.36585 8.75 66.50459 39.7 8.75 66.45001 39.8567 8.75 66.46176 40.225 8.75 66.59067 40.60932 8.75 66.975 40.75 8.75 67.5 40.60932 8.75 68.025 40.31304 8.75 66.64756 38.94858 8.929409 67.5 38.94858 8.843377 67.98548 38.94858 8.843377 67.01454 38.94858 8.75 66.7666 39.175 8.75 66.59067 39.7 8.75 68.55001 39.36585 8.75 68.49542 39.175 8.75 68.40933 39.8567 8.75 68.53824 38.94858 8.75 68.2334 3.9 6.05 73.30718 3.60718 6.05 73.6 4.3 6.05 74 3.5 6.05 74 3.60718 6.05 74.4 4.99282 6.05 73.6 4.7 6.05 73.30718 4.3 6.05 73.2 4.7 6.05 74.69282 4.99282 6.05 74.4 5.1 6.05 74 3.9 6.05 74.69282 4.3 6.05 74.8 5.1 10 74 4.99282 10 74.4 4.7 10 74.69282 4.3 10 74.8 3.9 10 74.69282 3.60718 10 74.4 3.5 10 74 3.60718 10 73.6 3.9 10 73.30718 4.3 10 73.2 4.7 10 73.30718 4.99282 10 73.6 4.3 10.48069 74 17.3 6.05 73.30718 17.00718 6.05 73.6 17.7 6.05 74 16.9 6.05 74 17.00718 6.05 74.4 18.39282 6.05 73.6 18.1 6.05 73.30718 17.7 6.05 73.2 18.1 6.05 74.69282 18.39282 6.05 74.4 18.5 6.05 74 17.3 6.05 74.69282 17.7 6.05 74.8 17.7 10.48069 74 18.39282 10 74.4 18.1 10 74.69282 18.5 10 74 17.3 10 74.69282 17.00718 10 74.4 17.7 10 74.8 17.00718 10 73.6 17.3 10 73.30718 16.9 10 74 18.1 10 73.30718 18.39282 10 73.6 17.7 10 73.2 17.7 10.6309 81.5 18.60933 10 82.025 18.225 10 82.40933 18.75 10 81.5 17.175 10 82.40933 16.79067 10 82.025 17.7 10 82.55001 16.79067 10 80.975 17.175 10 80.59067 16.65 10 81.5 18.225 10 80.59067 18.60933 10 80.975 17.7 10 80.45001 18.75 6.15 81.5 18.60933 6.15 82.025 18.225 6.15 82.40933 17.7 6.15 82.55001 17.175 6.15 82.40933 16.79067 6.15 82.025 16.65 6.15 81.5 16.79067 6.15 80.975 17.175 6.15 80.59067 17.7 6.15 80.45001 18.225 6.15 80.59067 18.60933 6.15 80.975 18.69593 6.05 82.075 18.275 6.05 82.49594 17.7 6.05 82.65 17.125 6.05 82.49594 16.70407 6.05 82.075 16.55 6.05 81.5 16.70407 6.05 80.92501 17.125 6.05 80.50408 17.7 6.05 80.35 18.275 6.05 80.50408 18.69593 6.05 80.92501 18.85 6.05 81.5 17.7 6.05 81.5 4.3 10.6309 81.5 5.209327 10 82.025 4.825 10 82.40933 5.35 10 81.5 3.775 10 82.40933 3.390673 10 82.025 4.3 10 82.55001 3.390673 10 80.975 3.775 10 80.59067 3.25 10 81.5 4.825 10 80.59067 5.209327 10 80.975 4.3 10 80.45001 5.35 6.15 81.5 5.209327 6.15 82.025 4.825 6.15 82.40933 4.3 6.15 82.55001 3.775 6.15 82.40933 3.390673 6.15 82.025 3.25 6.15 81.5 3.390673 6.15 80.975 3.775 6.15 80.59067 4.3 6.15 80.45001 4.825 6.15 80.59067 5.209327 6.15 80.975 5.295929 6.05 82.075 4.875 6.05 82.49594 4.3 6.05 82.65 3.725 6.05 82.49594 3.304071 6.05 82.075 3.15 6.05 81.5 3.304071 6.05 80.92501 3.725 6.05 80.50408 4.3 6.05 80.35 4.875 6.05 80.50408 5.295929 6.05 80.92501 5.45 6.05 81.5 4.3 6.05 81.5 -17.92859 8 68.21432 -17.55488 8 66.76418 -17.92859 8 66.78569 -17.21732 8 68.07404 -17 8 67.76926 -17 8 67.23075 -18.42627 8 67.68717 -18.24535 8 68.01486 -18.42627 8 67.31284 -18.24535 8 66.98513 -17.55488 8 68.23583 -17.21732 8 66.92596 -18.24535 8.800001 66.98513 -17.92859 8.800001 66.78569 -17.55488 8.800001 66.76418 -17.21732 8.800001 68.07404 -17.55488 8.800001 68.23583 -17.92859 8.800001 68.21432 -18.24535 8.800001 68.01486 -18.42627 8.800001 67.68717 -18.42627 8.800001 67.31284 -17.21732 8.800001 66.92596 -17 8.800001 67.76926 -17 8.800001 67.23075 24 4 71.7278 23.975 4 71.95001 24 4 71.95001 24 6 71.95001 23.975 6 71.95001 24 6 71.7278 20.1 0 71.60001 18.1 0 71.60001 20.1 4 71.60001 18.1 4 71.60001 18.23398 4 71.1 18.6 4 70.73398 19.1 4 70.6 19.96603 4 71.1 19.6 4 70.73398 18.23398 0 71.1 18.6 0 70.73398 19.1 0 70.6 19.6 0 70.73398 19.96603 0 71.1 + + + + + + + + + + -0.8191521 4.78204e-7 0.5735765 -0.819152 0 0.5735766 -0.819152 0 0.5735765 -0.8191413 0 0.5735919 -0.8191632 2.79601e-6 0.5735605 -0.8191609 0 0.5735639 -0.8191487 -1.63427e-6 0.5735813 -0.8191517 -8.97132e-7 0.573577 -0.8191523 -1.9797e-6 0.5735761 -0.8191224 1.53382e-5 0.5736188 -0.8191567 -1.01138e-5 0.57357 -0.8191531 -3.81392e-5 0.573575 -0.819176 0 0.5735424 0.4743768 -0.5544894 0.6837456 0.4740293 -0.5546649 0.6838445 0.4947394 -0.3620432 0.7900366 0.5341092 -0.2275975 0.8142033 -0.009038746 -0.9748764 0.2225631 0.4885717 -0.3283032 0.8084025 -0.02839404 -0.9547664 0.2959983 0.4702967 -0.3277554 0.8193885 -0.04645311 -0.93085 0.3624368 0.4518113 -0.3279275 0.8296567 -0.06264501 -0.9000734 0.4312117 0.4523546 -0.2829622 0.8457587 -0.3176444 -0.9252257 0.2075078 0.4291021 -0.2809479 0.8584519 -0.3209813 -0.8880451 0.3291611 0.40501 -0.2763057 0.8715631 -0.3163273 -0.8369595 0.4465826 0.3795838 -0.2699262 0.8849046 -0.3067801 -0.7749835 0.5525275 0.420696 -0.1772359 0.8897204 -0.7687585 -0.6371052 -0.05574452 0.3771175 -0.1650956 0.9113319 -0.7103558 -0.6048686 0.3599007 0.4059546 -0.08285784 0.9101293 -0.7157916 -0.3985863 0.573386 0.2428954 -0.04517483 0.9690001 0.02291369 -0.06937527 0.9973275 -0.4500369 0.5046722 -0.7367312 0.8071457 0 -0.5903522 0.8055949 -3.90241e-5 -0.592467 0.8054358 0 -0.5926831 0.7686483 -0.0114603 -0.6395691 0.7781702 -7.54518e-4 -0.6280531 0.7927852 0 -0.6095013 0.763788 0.003354489 -0.6454585 0.7596757 0.00624305 -0.6502721 0.7596448 0.006239652 -0.6503084 0.7587551 0.005279719 -0.6513547 0.7559565 0.002326369 -0.6546179 0.7840247 -0.003993749 -0.6207169 0.7908104 1.29115e-4 -0.6120615 0.8156208 -1.19684e-4 -0.5785868 0.8151085 -3.7711e-4 -0.5793083 0.8451173 5.58846e-4 -0.5345805 0.8560683 -0.008598327 -0.5167913 0.8817846 0.003694593 -0.4716381 0.8955541 -0.001631915 -0.4449496 0.9350007 0.00911951 -0.3545288 0.8833582 -0.09502893 -0.4589638 0.9705591 0.08317822 -0.2260457 0.9472793 -0.04249429 -0.3175784 0.986768 0.005087316 -0.1620594 0.5327048 -0.3695729 0.7613419 0.01300185 -0.3613435 0.9323421 0.8935862 -0.1050923 -0.4364166 0.3106754 0.6021742 0.7354367 0.5293061 0.4260775 0.7336847 -0.1494902 0.1811901 0.97202 0.4992142 0.2321997 0.8347865 0.627141 -0.157635 0.7627879 0.5665621 -0.15707 0.8089106 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 1 1.27744e-4 -3.6478e-4 1 6.6223e-5 5.62375e-6 1 0 0 1 9.58753e-6 -4.25752e-6 1 -8.507e-5 6.76085e-6 1 3.82713e-5 5.26216e-6 1 -9.95739e-7 -1.99148e-6 1 -6.60341e-7 0 1 -1.3065e-6 -8.08575e-6 1 2.71334e-4 -4.12798e-5 -1 0 0 -1 2.03473e-4 -3.53774e-5 -1 0 -5.00586e-4 -1 -1.04563e-4 0 -1 -3.38194e-4 -2.58322e-4 -1 -1.76354e-5 -9.36503e-5 -1 -2.03645e-5 8.57123e-7 -0.9999955 0.002140283 0.002132952 -1 2.88662e-5 1.22116e-4 -1 6.37115e-5 1.20671e-4 -1 2.68769e-4 3.13703e-4 -1 -1.1135e-4 4.10724e-6 -1 4.92288e-5 1.29646e-4 -1 -5.29058e-5 5.16113e-5 -1 -5.50522e-5 5.1299e-5 -0.9999999 -4.96155e-4 -2.70193e-4 -1 3.70169e-5 1.00989e-4 -1 0 8.28142e-5 -1 -2.63171e-5 6.24584e-5 -1 -4.08694e-5 5.58726e-5 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 1.34804e-4 -3.66059e-4 1 7.01853e-5 1.69104e-5 1 1.02879e-5 -1.20041e-5 1 -8.09461e-5 1.95911e-5 1 3.17819e-5 1.54491e-5 1 -1.15272e-6 -5.85229e-6 1 -9.90596e-7 0 1 -1.25209e-6 -4.441e-6 1 2.07754e-4 -4.05452e-5 -0.9999995 2.7748e-4 -0.001011431 -1 1.65321e-4 -3.27124e-5 -1 -1.0622e-4 1.03015e-5 -1 -2.07163e-5 8.58607e-7 -0.9999999 -3.93617e-6 -6.23853e-4 -1 1.47097e-6 0 -1 2.43974e-4 5.88999e-6 -1 1.55237e-4 -2.27729e-5 -1 -2.07521e-5 1.01194e-5 -1 2.40126e-6 -1.46085e-6 -1 4.09707e-7 2.8583e-7 -1 0 2.66037e-6 -1 -3.90564e-6 2.15842e-6 -1 3.30557e-5 3.18155e-6 -1 -2.03652e-5 8.5715e-7 -1 -2.05057e-5 0 -1 3.43667e-4 -1.84845e-4 -1 -6.54632e-6 -1.57521e-5 -1 -7.23275e-6 -1.74038e-5 -1 -1.45688e-5 -1.28314e-5 -1 -7.93349e-6 3.33753e-6 -1 5.61494e-5 -1.45256e-5 -1 2.50387e-4 -1.53862e-4 -1 -1.35966e-4 8.54423e-5 -1 2.97625e-4 -1.88002e-4 -1 -2.4902e-5 2.04957e-5 -0.9999995 2.76725e-4 -0.001008033 -0.508394 -0.7936705 -0.3341001 -0.5109567 -0.7919142 -0.334358 -0.6768431 -0.7033988 -0.217057 -0.6329014 -0.7300925 -0.2576837 -0.5246126 -0.7849944 -0.3294929 -0.8369395 -0.5369967 -0.1056742 -0.8221686 -0.55623 -0.121025 -0.7378796 -0.6496579 -0.1829707 -0.9951031 -0.09884321 0 -0.9934267 -0.1144111 -0.003706037 -0.9473801 -0.3187623 -0.02935463 -0.9423484 -0.3326959 -0.03595858 -0.8872765 -0.4544817 -0.0786572 -0.8117741 0.1339133 0.5684102 -0.811941 0.077838 0.5785267 -0.8162513 0.07482039 0.5728315 -0.6859498 0.5466052 0.4803079 -0.7439259 0.4089754 0.5285011 -0.7386821 0.4281632 0.5206007 -0.7859969 0.2816237 0.5503607 -0.8013663 0.2072525 0.5611227 -0.6646794 0.5844562 0.4654163 -0.6646787 0.5844606 0.4654119 -0.6586481 0.5944426 0.4613249 -0.5752997 0.71043 0.4053634 -0.6195101 0.6387705 0.4562671 -0.5580661 0.7295754 0.3953253 -0.340315 0.9076793 0.2455685 -0.4331554 0.8487504 0.303314 -0.4888569 0.8024064 0.3422909 -7.07609e-4 0.9999998 4.52182e-4 -0.07140374 0.9961893 0.05008399 -0.1039534 0.9916074 0.07686752 -0.2063638 0.9680107 0.1427214 -0.3303839 0.9137481 0.2364549 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.3334925 -0.8163009 -0.4716308 -0.3335708 -0.8162732 -0.4716237 -0.3340283 -0.8156394 -0.4723955 -0.3344266 -0.8154958 -0.4723616 -0.334752 -0.8127353 -0.4768672 -0.3343952 -0.8151971 -0.4728993 -0.3358014 -0.8134602 -0.4748894 -0.3358028 -0.8134601 -0.4748886 -0.3311876 -0.8165243 -0.4728668 -0.3311117 -0.8165432 -0.4728873 -0.331152 -0.816556 -0.4728367 -0.3310951 -0.8165578 -0.4728735 -0.332485 -0.8156074 -0.4735382 -0.3201451 -0.8158098 -0.4816241 -0.3334663 -0.8162884 -0.471671 -0.3313494 -0.8164834 -0.472824 -0.3311851 -0.8165257 -0.472866 -0.6398228 -1.68627e-4 0.7685225 -0.5047751 -0.02000826 0.8630191 -0.7004513 0 0.7137002 0.3427302 0 0.9394339 0.3846468 -0.005957424 0.9230446 0.1330148 3.44717e-5 0.9911141 -0.1713637 -1.95947e-4 0.9852079 -0.0738632 -0.0128082 0.9971862 -0.3231272 6.78198e-5 0.9463557 0.5736259 9.18017e-6 0.8191174 0.5735775 5.56856e-7 0.8191514 0.5735769 0 0.8191519 0.5735771 4.64052e-6 0.8191516 0.573578 0 0.819151 0.5735737 -4.95813e-7 0.819154 0.573574 -2.22231e-6 0.8191538 0.5735771 0 0.8191516 0.5735753 1.43993e-7 0.8191528 0.5735895 0 0.8191429 0.5735725 2.07005e-7 0.8191548 0.5735754 0 0.8191529 0.5735741 0 0.8191537 0.5735783 -1.13062e-6 0.8191508 0.5735785 -5.04593e-7 0.8191506 0.5735743 0 0.8191536 0.5735769 2.49204e-7 0.8191519 0.5735757 0 0.8191527 0.5735787 0 0.8191505 -0.8164565 8.54753e-5 0.5774069 -0.8164561 8.63264e-5 0.5774074 -0.816708 0.002655684 0.577045 -0.8164935 -1.36385e-6 0.5773546 -0.8164787 8.79866e-6 0.5773756 -0.8164916 0 0.5773574 -0.8163855 0.003710985 0.5774955 -0.8164278 0 0.5774476 -0.8168777 -0.001126289 0.5768101 -0.8164865 -3.42378e-6 0.5773645 -0.8164922 0 0.5773565 -0.816481 -2.52257e-5 0.5773725 -0.8164904 -3.79594e-5 0.5773591 -0.8178237 0.002231776 0.5754644 -0.8164923 0 0.5773565 -0.8164925 1.47495e-6 0.5773561 -0.8164924 1.45786e-7 0.5773561 -0.8164923 -1.25682e-6 0.5773565 -0.8164916 -2.12718e-6 0.5773575 -0.8164923 0 0.5773563 -0.8165027 0 0.5773416 -0.8164932 2.52222e-5 0.5773552 -0.8164783 -1.53422e-4 0.5773764 -0.8164925 -4.44002e-7 0.5773561 -0.816493 2.21361e-6 0.5773554 -0.8164922 0 0.5773566 -0.8164929 -4.94396e-7 0.5773556 -0.8164923 0 0.5773564 -0.8164932 1.28372e-6 0.5773552 0.9913578 0.1289892 -0.02390944 0.9920158 0.1161809 -0.04905778 0.9952743 0.0060938 -0.09691345 0.9949554 0.02757531 -0.09645402 0.9941035 0.06218445 -0.08883327 0.9930655 0.09247875 -0.07258504 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -3.58226e-7 1 -3.20014e-7 -2.94304e-7 1 -2.54043e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.62347e-4 0.9999991 -0.001381516 3.85415e-4 1 0 0 1 0 -0.008929669 0.9999602 0 -1.21194e-5 1 -1.68248e-4 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.7043661 0 0.7098369 0.7043523 1.85352e-6 0.7098506 0.7043557 2.49975e-5 0.7098473 0.7043512 0 0.7098517 0.7043555 0 0.7098475 0.7043521 2.88113e-7 0.7098509 0.7043522 0 0.7098508 0.7043521 -7.01571e-7 0.7098509 0.7043527 1.40589e-7 0.7098501 0.7043439 0 0.7098589 0.7043393 0 0.7098634 0.7043497 -1.96097e-6 0.7098532 0.704351 -1.0617e-6 0.7098519 0.7043526 -9.09485e-7 0.7098504 0.7043496 3.99305e-7 0.7098532 0.7043534 3.20251e-6 0.7098495 0.7043504 0 0.7098526 0.7043575 -1.33802e-6 0.7098454 0.7043519 -2.63902e-6 0.709851 0.7043741 0 0.7098289 0.7043526 -9.94365e-6 0.7098503 0.7043531 0 0.7098498 0.7043527 1.42238e-6 0.7098503 0.7043527 -6.32746e-7 0.7098502 0.7043515 1.43427e-6 0.7098515 0.7043521 -3.37183e-5 0.7098508 0.7043517 8.3667e-5 0.7098513 0.7043517 0 0.7098512 0.7043521 0 0.7098508 0.7043522 1.98435e-6 0.7098508 0.7043518 -2.11694e-6 0.7098511 0.7042526 0 0.7099495 0.704347 1.79616e-7 0.7098559 0.7043582 0 0.7098448 0.7043467 -1.27203e-6 0.7098562 0.7043537 0 0.7098492 0.7043552 2.34109e-7 0.7098476 0.7043504 0 0.7098525 0.7043542 -1.28517e-5 0.7098487 0.7043545 0 0.7098485 0.704349 2.57122e-6 0.709854 0.704354 6.05833e-6 0.7098489 -0.1704822 0 -0.9853608 -0.1704823 0 -0.9853608 -0.3595615 -0.006721019 -0.9330973 -0.1940504 0 -0.9809916 -0.5549405 0 -0.83189 -0.5549407 0 -0.83189 -0.8312177 0 -0.5559473 -0.9807559 0 -0.1952381 -0.9807559 0 -0.1952381 0.7613346 0 -0.6483592 0.7869436 -0.02407449 -0.6165552 0.8040148 -0.004628419 -0.5945914 0.5991793 -0.1408175 -0.7881336 0.7001686 0.003474414 -0.7139692 0.5245871 -0.003414571 -0.85135 0.4820646 -0.005181729 -0.8761204 -0.1065741 -4.7415e-4 -0.9943047 0.04487985 -0.003289997 -0.998987 0.1958413 -0.0153141 -0.980516 0.03151392 -0.001836061 -0.9995017 0.2227866 -8.9507e-5 -0.9748673 0.3774924 4.83445e-4 -0.9260125 -0.5885481 0 -0.8084622 -0.5812842 -6.23414e-6 -0.8137006 -0.5442447 -2.95435e-4 -0.8389264 -0.4541293 -0.003701508 -0.8909282 -0.3770495 -0.01010912 -0.9261379 -0.3452584 -0.01302558 -0.9384174 -0.4020563 -0.00711286 -0.9155874 -0.2501171 1.31023e-5 -0.9682157 -0.1437824 0 -0.9896094 -0.8316982 4.1774e-5 -0.5552279 -0.6987842 -0.003140747 -0.7153257 -0.6346017 -4.26521e-4 -0.7728394 -0.6000705 0 -0.7999471 -0.7379111 -0.006440758 -0.6748673 -0.7785516 -0.01233732 -0.6274594 -0.7568991 -0.009215474 -0.6534668 -0.9485296 0 -0.3166886 -0.9787959 -0.01813668 -0.2040337 -0.9430302 -0.006145954 -0.3326504 -0.9032328 -3.19389e-4 -0.4291509 -0.9284991 -0.003487408 -0.3713183 -0.9210927 -0.00239706 -0.3893361 -0.9023913 -1.29487e-5 -0.4309176 -0.8871519 -0.001002192 -0.4614765 -0.9133461 -1.0687e-4 -0.4071844 -0.9202338 0 -0.3913693 -0.9173031 -0.002625942 -0.398181 0 1 0 0 0 1 0.001453995 0 0.999999 -1.74579e-5 0 1 6.18113e-6 0 1 -2.10671e-6 0 1 0 0 1 -4.69751e-4 0 0.9999999 -5.12259e-5 0 1 3.35178e-5 0 1 -0.8911275 0 0.4537531 -0.8208537 -0.007939815 0.5710833 -0.533728 -0.008818149 0.8456102 -0.6387894 0.005550384 0.7693617 -0.8134076 -0.006313443 0.5816599 0.02661812 5.42806e-4 0.9996456 -0.1753281 -0.004973232 0.9844976 -0.1624084 -0.003459095 0.9867176 -0.2122291 0 0.9772199 -0.4285092 0 0.9035374 0.2113368 -0.002794802 0.9774094 0.2345728 -0.006012916 0.97208 0.3822451 0 0.924061 0.2349253 -0.01197177 0.9719398 0.1754283 -0.00497353 0.9844797 0.1623909 0.0024181 0.9867236 0.5337572 -0.002138376 0.8456351 0.5297414 -0.002954661 0.8481541 0.7721946 0.002156496 0.6353826 0.8208488 -0.007967591 0.5710901 0.8909449 0 0.4541115 -0.02668637 5.42673e-4 0.9996438 -0.211328 -0.002794802 0.9774113 -0.2345724 -0.006013333 0.9720801 -0.3685175 -5.73919e-4 0.9296207 -0.4096652 0 0.912236 0.9808147 0 -0.1949427 0.9659745 0.002740979 -0.2586229 0.6093202 -5.34804e-4 -0.7929242 0.7793741 6.49212e-4 -0.6265587 0.79366 0 -0.6083617 0.8970304 0 -0.4419689 0.1961279 0 -0.9805784 0.1858612 -3.31653e-4 -0.982576 0.4430607 1.28992e-4 -0.8964916 0.4336583 0 -0.9010774 0.5908159 0 -0.8068064 7.04808e-4 0.5545557 -0.8321464 0.001180112 0.5277199 -0.8494177 0.001016855 0.1849704 -0.9827436 0.001186966 0.1954627 -0.9807104 -0.2311634 0.1001073 0.9677511 -0.2615166 0.7603649 0.5945203 -0.3610637 0.1004953 0.9271105 -0.2311624 0.1001327 0.9677487 -0.2987678 0.7142707 0.6328943 -0.3784137 0.528598 0.7598599 -0.4378755 0.1949645 0.8776412 -0.4010428 0.3665739 0.8395167 -0.4214543 0.2722582 0.8650155 -0.3827851 0.555424 0.7382275 -0.2467883 0.8312149 0.4981741 -0.2138441 0.8828632 0.4181187 -0.08803069 0.9807607 0.1742384 -0.08185327 0.9840443 0.1579772 0.7157593 -0.5973399 -0.3617648 0.8047906 -0.5016825 -0.3172174 0.3917844 -0.8864554 -0.2463777 0.347092 -0.9297013 -0.1232182 0.4544062 -0.8717041 -0.1834313 0.4294237 -0.8558273 -0.2883663 0.4378761 -0.8518627 -0.2873926 0.9250982 -0.3529422 0.1400896 0.9373539 -0.3483258 -0.006072998 0.9179199 -0.3728831 -0.1355783 0.9298654 -0.33656 -0.1485853 0.8416377 -0.5301651 -0.102815 0.5517049 -0.8104032 -0.1971508 0.5755457 -0.8087072 -0.1214084 0.6154411 -0.7489899 -0.2454515 0.7697532 -0.6037528 -0.2072747 0.8188496 -0.5499961 -0.1642857 0.6617898 -0.3847962 -0.6434021 0.4624919 0.6067771 -0.6464696 0.7088899 0.5265655 -0.4692591 0.5723664 0.388416 -0.7221702 0.7144137 -0.2191272 -0.6645272 0.7218354 -0.004698514 -0.6920488 0.7156968 -0.02325797 -0.6980239 0.7164719 0.2391846 -0.6553311 0.7145302 0.2172281 -0.6650253 0.6609536 -0.3998869 -0.6350048 0.6514874 -0.3998628 -0.644728 0.6032449 -0.566429 -0.5614748 0.6589137 -0.3120476 -0.6844407 0.7128567 -0.05713009 -0.698979 0.7240837 -0.00472486 -0.689696 0.6936092 0.1361512 -0.7073678 0.6594639 0.3912148 -0.6419178 0.6260747 0.4416607 -0.6426246 0.5160798 0.6904637 -0.5068745 0.4448919 0.7476798 -0.4929972 0.275654 0.9397392 -0.2022502 0.6551342 -0.3120541 -0.6880563 0.07592082 0.9196684 -0.3852872 0.67674 0.1360046 -0.7235509 0.6692946 -0.05703806 -0.7408046 0.1628371 0.9704676 -0.1779803 0.1843135 0.9652704 -0.185153 0.4459341 0.7446194 -0.4966737 0.4423233 0.7476184 -0.4953957 0.6523658 -0.1340322 -0.7459586 0.6195235 -0.1338691 -0.773479 0.6057589 0.1948336 -0.7714247 0.5690934 0.441378 -0.6937711 0.5858249 0.3451432 -0.7332704 0.6193097 0.3455232 -0.7050314 0.6142436 0.4416334 -0.6539608 0.1212989 0.9807292 -0.1531561 0.1537027 0.9704426 -0.1860557 0.2745394 0.8966324 -0.347388 0.4164111 0.7442102 -0.5222576 0.3873543 0.7925403 -0.4709953 0.4913519 0.6082909 -0.6233424 0.1986747 0.1946627 -0.9605388 0.2679764 0.5416133 -0.7967709 0.2202885 0.7292919 -0.6477703 0.2041983 0.8092213 -0.5508757 0.2109842 0.7069536 -0.6750573 0.03960788 0.9806947 -0.1914923 0.04857468 0.9656887 -0.2551196 0.06978076 0.9659247 -0.249239 0.07581639 0.9676593 -0.240598 0.1608349 0.6078367 -0.7776033 0.1380341 0.7060546 -0.6945744 0.1234933 0.79262 -0.5970787 0.08974707 0.8964723 -0.4339158 0.181747 0.4414525 -0.8786853 0.1916204 0.2581377 -0.9469143 0.3193118 0.2583044 -0.9117669 0.3165498 0.3361219 -0.8870278 0.3837319 0.1690657 -0.9078363 0.4565533 0.1686751 -0.8735605 0.4565498 0.1686861 -0.8735601 0.5730313 0.1687149 -0.8019792 0.5730307 0.1687017 -0.8019823 0.6784867 0.1687151 -0.7149763 0.678487 0.1687176 -0.7149754 0.7708877 0.1687352 -0.6142155 0.7708938 0.1687005 -0.6142174 0.8484675 0.1686951 -0.5016423 0.848461 0.1687376 -0.5016388 0.9097112 0.1687347 -0.379413 0.9097181 0.1686948 -0.3794141 0.9534596 0.1687347 -0.2498872 0.9534702 0.168668 -0.2498915 0.9788783 0.1686546 -0.1155542 0.9788667 0.1687226 -0.1155544 1 -2.57125e-6 0 1.89977e-6 0 1 3.6721e-6 0 1 -2.59578e-6 0 1 5.25706e-5 0 1 -1.5961e-5 0 1 5.31111e-6 0 1 -0.652054 2.04996e-5 0.7581726 -0.925985 -0.07753688 0.3695131 -0.9046553 -0.02241456 0.4255541 -0.9024845 -0.01370531 0.4305045 -0.7735829 0 0.633695 -0.773853 -3.37815e-5 0.6333652 -0.862704 0.02380037 0.5051489 -0.7678028 -0.01250922 0.6405642 -0.9025053 0.01149708 0.4305254 -0.8639796 0 0.5035269 -0.1105174 -0.01043659 0.9938195 -0.1925938 -0.002245903 0.981276 -0.034258 -1.50787e-4 0.999413 -0.01126235 0 0.9999366 -0.2261261 -0.003253161 0.9740927 -0.3393002 3.89146e-4 0.9406781 -0.5492308 -0.001289069 0.8356698 -0.4513707 -0.01258283 0.8922478 -0.5455588 -0.004485249 0.8380606 0.2965039 -7.00806e-4 0.9550315 0.1853551 -0.004959702 0.9826592 0.1926174 -0.004413366 0.9812641 0.07239151 -4.37208e-4 0.9973763 0.01314485 0 0.9999136 0.4060974 5.16117e-4 0.9138298 0.5492348 -0.003774344 0.8356596 0.490849 -0.008901059 0.8711993 0.7735829 0 0.6336953 0.8973375 0 0.4413451 0.8555864 -0.003944873 0.5176451 0.8811486 0.001312911 0.4728379 0.778928 -0.001183509 0.6271124 0.7804937 -8.97925e-4 0.6251631 0.6743131 4.80455e-4 0.7384455 0.5632157 -0.003270685 0.8263036 2.2816e-6 0 1 4.3811e-6 0 1 -2.87499e-6 0 1 4.92299e-6 0 1 0.2740325 0 0.9617204 0.2740561 0 0.9617137 0.1249419 0 0.9921641 0.2037542 -0.02214395 0.9787716 0.3073165 -0.001502752 0.9516062 0.4877077 0.006961941 0.8729793 0.4909451 0.007629632 0.8711571 0.6539057 -0.001549899 0.7565745 0.8035554 0.0066334 0.5951929 0.8039601 0.006792128 0.5946445 0.9999954 0 0.00306189 0.9775521 9.79923e-4 0.2106915 0.9796712 0.004399657 0.2005622 0.9059414 -6.2048e-4 0.4234028 1 0 0 1 0 0 1 0 0 1 0 0 0.4262173 0.184455 -0.8856158 0.5835602 0.1562265 -0.7969008 0.4737775 0.205745 -0.8562732 0.45388 0.4532772 -0.7671589 0.1827609 0.1818963 -0.9661844 0.18276 0.1818961 -0.9661846 0.1609404 0.5001708 -0.8508393 0.1406325 0.5225501 -0.8409305 -0.4406116 -0.6565089 -0.6122562 -0.2872462 -0.6634015 -0.6909328 -0.4094734 -0.7054318 -0.5785304 -0.3860481 -0.7795962 -0.4931498 -0.3640155 -0.7788811 -0.510722 0.5736142 0 0.8191257 0.5734857 0 0.8192155 0.5735735 0 0.8191542 0.5750502 2.27163e-4 0.8181182 0.5749215 1.54601e-4 0.8182086 0.5748026 6.54341e-4 0.8182919 0.5748247 6.73327e-4 0.8182764 0.5746293 9.83511e-4 0.8184133 0.5735773 -1.23809e-6 0.8191515 0.573578 0 0.8191511 0.5735746 0 0.8191534 0.5748646 0.001688122 0.8182468 0.5745872 0.001133143 0.8184427 0.5743572 0.00130409 0.8186038 0.5735778 -9.29298e-7 0.8191511 0.5735747 9.25715e-7 0.8191533 0.5735758 -6.94013e-7 0.8191526 0.5735763 0 0.8191521 0.573576 6.93431e-7 0.8191525 0.5735807 3.09729e-7 0.8191491 0.5739876 0.001531183 0.8188626 0.5740821 0.001505672 0.8187964 0.5743104 0.001642465 0.8186361 0.5743452 0.001828908 0.8186113 0.5743241 0.001478195 0.8186267 0.5735769 0 0.8191518 0.5735766 4.71534e-7 0.8191519 0.5735769 4.64946e-7 0.8191517 0.5735644 -2.62595e-6 0.8191605 0.5735756 0 0.8191527 0.5735751 2.14956e-6 0.819153 0.5735771 0 0.8191517 0.557542 -0.002010047 0.8301463 0.5737612 0.001621127 0.8190211 0.5738775 0.001736462 0.8189394 0.5738675 0.001776933 0.8189463 0.5739319 0.001601457 0.8189015 -0.8178063 0 0.5754937 1 -3.66518e-7 0 1 -8.65894e-7 0 1 6.55492e-7 0 1 1.80921e-6 0 1 -1.6439e-7 0 1 9.1906e-7 0 -1 0 6.26968e-7 -1 -1.2756e-6 0 -0.9999968 -0.001143455 -0.002287685 -0.9999965 -0.001473009 -0.002252101 -0.9975094 0.01884192 -0.06797248 -1 -1.08498e-5 -9.09651e-6 -1 0 1.49426e-7 -1 -1.04565e-5 2.33565e-6 -1 0 1.0368e-6 -1 2.07139e-5 3.04745e-7 -1 -1.2909e-6 6.74617e-7 -1 -2.26104e-7 7.58076e-7 -1 -2.32833e-5 9.529e-6 -1 -9.46786e-7 0 -0.9979222 -0.05995339 0.02360403 -1 -1.56777e-6 0 -1 5.06251e-6 0 -1 -3.50114e-6 0 -1 -2.09905e-6 0 -1 2.71339e-6 0 -0.9999996 -7.84572e-4 -5.59998e-4 -0.9999995 -0.001012802 0 -0.9999279 0.002775669 0.01168221 -1 -3.72099e-7 0 -1 2.51364e-7 0 -1 -5.30985e-7 0 1.87876e-4 -0.9837052 -0.179789 0 -0.9836958 -0.1798406 -0.01844549 -0.9854419 -0.1690094 0.3357252 -0.9126423 -0.2331795 -0.01964479 -0.9967125 -0.07860261 -0.001394033 -0.9964849 -0.08376109 0 0.7765353 -0.6300737 0.02073502 0.8582641 -0.5127893 0.03397303 0.8643296 -0.501777 0 0.9275849 -0.3736127 0 0.9846693 -0.1744317 0.107786 0.960893 -0.2550818 0 0.9964615 -0.08405065 0 0.6930632 -0.7208768 0.05468946 0.6387763 -0.7674465 0 0.5566944 -0.8307174 0 0.450192 -0.8929318 0.04714703 0.3364042 -0.9405368 6.24309e-5 0.2875998 -0.9577507 0.05027407 -0.3497911 -0.9354779 -0.005899786 -0.2884575 -0.9574747 0.008476078 -0.007162868 -0.9999384 0.103591 -0.08385717 -0.9910787 -4.23e-5 0.08405089 -0.9964615 0.05295813 -0.6497662 -0.7582871 0 -0.5634757 -0.8261327 0 -0.4571487 -0.8893904 0 -0.9308922 -0.3652944 0.04465436 -0.8592224 -0.5096498 0.01652884 -0.871814 -0.4895581 0 -0.7819098 -0.6233916 0 -0.6989415 -0.7151789 0.965853 0.04658496 -0.2548685 0.9403675 0.302931 -0.1547312 0.9538816 0.252507 -0.1623275 0.9188221 0.1341537 -0.3711724 0.9568747 0.1861923 -0.2229871 0.9544763 0.1201892 -0.2730014 0.9256091 0.1411158 -0.3511899 0.9100116 0.09911936 -0.4025597 0.8915132 0.09403795 -0.4431266 0.8652691 0.0642001 -0.4971799 0.8538465 0.07138746 -0.5156064 0.8177893 0.01956629 -0.5751851 0.7499547 -0.08089983 -0.6565235 0.7577382 -0.07253992 -0.6485144 0.7614147 -0.07966053 -0.6433522 0.7568705 -0.06698328 -0.6501235 0.7840297 -0.001945257 -0.6207203 0.8154376 0.02018904 -0.5784929 0.7568814 -0.07102346 -0.6496816 0.754858 -0.06772661 -0.6523823 0.7546295 -0.05956381 -0.653442 1.90738e-6 -1 0 1.19136e-6 -1 0 1.92412e-6 -1 -1.96699e-6 3.87458e-6 -1 0 -0.008774876 -0.9999597 -0.001943826 -0.01369106 -0.9998972 -0.004267692 -0.04797399 -0.9984916 -0.02670341 -0.03059458 -0.9969649 -0.07158839 -0.2475581 -0.968873 2.7058e-4 -0.2265905 -0.9709317 -0.07712632 -0.3308731 -0.9418221 -0.05911374 -0.3579341 -0.9259815 -0.1201736 -0.5222059 -0.8517382 -0.04293048 -0.6266404 -0.7418061 -0.2388423 -0.7073513 -0.6835429 -0.1800645 -0.8184157 -0.5511813 -0.1624655 -0.7636195 -0.6271404 -0.1535582 -0.7379875 -0.6737067 -0.03865182 -0.7389834 -0.6703284 0.06755256 -0.9906559 -0.09260332 -0.1001281 -0.9821395 -0.1689672 -0.08277738 -0.9620851 -0.2630078 0.07224476 -0.9392929 -0.2898222 0.1836627 -0.9615028 -0.2328659 -0.1458972 -0.9364146 -0.348187 0.04351454 -0.9522452 -0.2483542 -0.1776211 -0.917216 -0.3824762 -0.111476 -0.8973616 -0.3828539 -0.2194654 -0.8975984 -0.3859193 -0.2130343 -0.8927136 -0.3917865 -0.2226337 -0.1510012 -0.9828641 0.1057205 -0.1509894 -0.9828655 0.1057239 -0.1512879 -0.9827991 0.1059142 -0.1523567 -0.9829643 0.102805 -0.6711692 -0.5732981 0.4699589 -0.5470032 -0.6740776 0.496394 -0.7240229 -0.4677323 0.5069687 -0.6550533 -0.3999918 0.6410241 -0.776759 -0.3175238 0.5438972 -0.8126124 -0.1260907 0.5690011 -0.8126142 -0.1260915 0.5689983 -0.2034151 -0.9764362 0.07207363 -0.210476 -0.9508154 0.2272664 -0.1384483 -0.9856154 0.09692472 -0.5487737 -0.675286 0.4927843 -0.5396859 -0.7524033 0.3776621 -0.3924105 -0.8776358 0.2752622 -0.3599296 -0.8297749 0.426526 -0.3690611 -0.8775866 0.3059998 -0.6687332 -0.6993744 0.2523318 -0.1533839 -0.982966 0.1012493 -0.1671205 -0.9821452 0.08638113 -0.1689052 -0.9834793 0.06511175 -0.3227313 -0.9445376 0.06077229 -0.8782021 -0.439917 -0.187708 -0.8620829 -0.4576511 -0.217643 -0.8989268 -0.3919296 -0.1957595 -0.8170709 -0.5512371 -0.1689172 -0.7904144 -0.6061506 -0.08846879 -0.7738566 -0.6304708 -0.06043529 -0.835376 -0.5450683 -0.07104516 -0.6897419 -0.721048 0.0659241 -0.6441038 -0.6490548 0.4047939 -0.6280555 -0.7141799 0.3090201 -0.6165476 -0.7243934 0.3084207 -0.6220064 -0.7467785 0.2354358 -0.6146803 -0.7548552 0.2288271 -0.3397776 -0.9373874 0.07652539 -0.3407285 -0.9272732 0.1551409 -0.4353694 -0.8884962 0.1450107 -0.4793799 -0.8469461 0.2299508 -0.5129929 -0.829695 0.2201015 -0.6237225 -0.7265568 0.2882457 -0.7327508 -0.6767795 0.07103502 -0.2515975 -0.9677476 -0.01278567 -0.1914506 -0.9764394 0.09956347 -0.2049763 -0.9765406 0.06597858 -0.7964686 -0.5937158 -0.114627 -0.791015 -0.5943127 -0.1452171 -0.7865672 -0.5991916 -0.1492695 -0.7777559 -0.6215565 -0.09361267 -0.7619376 -0.6287242 -0.1554255 -0.7249273 -0.6824139 -0.09376394 -0.6885139 -0.7250782 0.01449888 -0.6922745 -0.7206196 0.03825539 -0.668659 -0.7431168 -0.02593404 -0.6314505 -0.7723351 0.06905734 -0.5897811 -0.8047001 -0.06794148 -0.5414048 -0.8403243 0.02713084 -0.5157593 -0.8534792 -0.07460391 -0.5161303 -0.8532149 -0.07505941 -0.9414263 -0.2701827 -0.2017869 -0.9993762 -0.001374781 -0.03528833 -0.9921704 -0.0785306 -0.09711325 -0.9953618 -0.05764424 -0.07702165 -0.9978585 -0.02922874 -0.05851531 -0.9975714 -0.03816562 -0.05826526 -0.9976649 -0.0416575 -0.05412608 -0.731924 -0.5897852 0.3412343 -0.6623663 -0.6929853 0.2846795 -0.6674267 -0.6875101 0.2861319 -0.6965454 -0.676449 0.2392516 -0.690831 -0.6951003 0.1989682 -0.6734962 -0.7053894 0.2209723 -0.7558177 -0.647239 0.09910249 -0.7159336 -0.6936691 0.07913416 -0.7425055 -0.6695968 -0.01805067 -0.7436427 -0.6685486 -0.006193518 -0.8312499 -0.5466707 -0.1008704 -0.8316503 -0.5327625 -0.1565948 -0.8705052 -0.473853 -0.1329823 -0.8514857 -0.501074 -0.1545871 -0.8528795 -0.47254 -0.2220419 -0.8754644 -0.4453289 -0.1877353 -0.9412779 -0.2721823 -0.1997818 -0.9528793 -0.2226701 -0.2060077 -0.9625353 -0.2111128 -0.1701684 -0.7336863 -0.1742813 -0.6567575 -0.7471637 -0.1140516 -0.6547815 -0.7198103 -0.03378009 -0.6933484 -0.7004659 -0.05124074 -0.7118441 -0.7155976 -0.01335358 -0.6983851 -0.7548934 -0.1365138 -0.6414827 -0.7553744 -0.2282494 -0.6142571 -0.7623877 -0.2379258 -0.6017944 -0.7622138 -0.3168461 -0.564481 -0.7654905 -0.3203891 -0.5580099 -0.7653866 -0.3990456 -0.5049219 -0.7769986 -0.4077541 -0.4795932 -0.7440631 -0.666552 -0.04559153 -0.7436851 -0.6661114 -0.05681663 -0.7464238 -0.6643912 -0.03789293 -0.7612016 -0.6405043 -0.1016192 -0.75932 -0.6411342 -0.111267 -0.7592626 -0.6301345 -0.1626374 -0.7538822 -0.6312052 -0.1823229 -0.7599415 -0.4778439 -0.4406294 -0.7866978 -0.5131093 -0.3432573 -0.7625502 -0.5200304 -0.3848187 -0.763943 -0.5853423 -0.2715982 -0.7606029 -0.5863082 -0.2787938 -0.7628042 -0.611607 -0.2099207 -0.9421944 -0.03534877 -0.3331973 -0.9588938 -0.01148098 -0.2835327 -0.9591029 -0.0714271 -0.2738979 -0.9643282 -0.05143576 -0.2596641 -0.9643623 -0.09932786 -0.2452334 -0.9671677 -0.08664643 -0.2389121 -0.9672027 -0.127484 -0.2196972 -0.9601888 -0.2376356 -0.1468567 -0.9691052 -0.1537462 -0.1928659 -0.9685602 -0.1529763 -0.1961872 -0.9684872 -0.1210157 -0.2176873 -0.9968647 -0.04010641 -0.06820785 -0.9974242 -0.02866071 -0.06575542 -0.9968004 -0.02400636 -0.07624113 -0.996806 -0.02391088 -0.07619845 -0.995978 -0.01380467 -0.08852851 -0.9959266 -0.01441037 -0.08900982 -0.9897655 0.0161128 -0.1417906 -0.8721552 -0.4390208 -0.2158846 -0.8927542 -0.3731606 -0.2524704 -0.8892124 -0.3619081 -0.2798641 -0.8886467 -0.3364837 -0.311586 -0.8890847 -0.3365526 -0.3102592 -0.8891276 -0.2848772 -0.3581862 -0.8884649 -0.2844622 -0.3601547 -0.8885416 -0.2289827 -0.3975687 -0.8861922 -0.2263662 -0.4042546 -0.8863167 -0.1715391 -0.4301361 -0.8812643 -0.1636675 -0.4433805 -0.8814396 -0.1164123 -0.4577255 -0.8722748 -0.09891217 -0.4789083 -0.8719564 -0.04414552 -0.4875892 -0.8446319 -0.0163089 -0.5350993 -0.2264988 -0.9705529 -0.08200949 -0.6363977 -0.7686122 -0.06506443 -0.772251 -0.05362707 -0.6330503 -0.4531394 -0.07515764 -0.8882657 -0.1751874 -0.0830059 -0.9810298 -0.9622387 -0.02295041 -0.2712377 -0.93077 -0.03082311 -0.3643038 -0.9951646 -0.008282542 -0.09787195 -0.9842824 -0.04641562 -0.1703931 -0.9841915 -0.05108898 -0.1695796 -0.9841914 -0.05108678 -0.1695801 -0.9841911 -0.09109497 -0.1518873 -0.9841915 -0.09109002 -0.1518872 -0.9841912 -0.1255396 -0.1249303 -0.9841912 -0.125539 -0.1249303 -0.9841908 -0.152332 -0.09035325 -0.9841915 -0.152327 -0.09035331 -0.9841907 -0.16983 -0.05026513 -0.984192 -0.1698222 -0.05026525 -0.9814577 -0.1855837 0.04795414 -0.9705145 -0.2401678 -0.02051877 -0.05915719 -0.9946086 -0.08517146 -0.1755185 -0.9788588 -0.105018 -0.1751639 -0.9538964 -0.24372 -0.2386936 -0.9311642 -0.2756061 -0.1756758 -0.9164153 -0.3596123 -0.1744919 -0.8468853 -0.5023325 -0.2050766 -0.6937566 -0.690395 -0.1757788 -0.7697379 -0.6136819 -0.1744899 -0.846888 -0.5023289 -0.1751894 -0.08300632 -0.9810295 -0.1744912 -0.284038 -0.9428019 -0.1744923 -0.2840369 -0.942802 -0.1755082 -0.4500518 -0.8755857 -0.2498415 -0.4980143 -0.8303982 -0.1754313 -0.5547389 -0.8133196 -0.1747692 -0.6881833 -0.704173 -0.8810432 -0.04887878 -0.4705038 -0.8422138 -0.08760666 -0.5319784 -0.8403283 -0.1563684 -0.5190352 -0.840329 -0.1563691 -0.5190336 -0.8403288 -0.2788056 -0.464882 -0.8403293 -0.2788019 -0.4648832 -0.8403282 -0.3842374 -0.3823746 -0.8403288 -0.3842361 -0.3823745 -0.8403301 -0.4662273 -0.2765457 -0.8403269 -0.4662339 -0.2765442 -0.8403276 -0.519789 -0.1538472 -0.8403296 -0.5197856 -0.1538478 -0.842213 -0.5324133 -0.0849325 -0.8039358 -0.5925967 -0.05016463 -0.6335592 -0.06517022 -0.7709447 -0.5388609 -0.1098221 -0.8352054 -0.5362012 -0.2434876 -0.8082093 -0.5362006 -0.2434887 -0.8082092 -0.536201 -0.4341393 -0.7238865 -0.5362011 -0.4341396 -0.7238863 -0.5362013 -0.598309 -0.5954113 -0.5362007 -0.5983105 -0.5954104 -0.5362039 -0.7259833 -0.4306199 -0.536203 -0.7259845 -0.4306194 -0.5362022 -0.8093809 -0.2395617 -0.5362018 -0.8093813 -0.2395611 -0.5389509 -0.8349342 -0.1114312 -0.4580815 -0.8857535 -0.07484668 -0.9883975 -0.09078943 -0.1217686 -0.7336922 -0.1742904 -0.6567485 -0.7185592 -0.5711248 0.3968493 -0.7148377 -0.6047626 0.3510974 -0.7707062 -0.5915982 0.2366927 -0.7579015 -0.5969443 0.2631404 -0.7648102 -0.6086732 0.2111452 -0.6210235 -0.7735828 0.1260934 -0.8080335 -0.5888082 -0.01966518 -0.6992511 -0.7133954 0.04598873 -0.7276172 -0.6844436 -0.04593652 -0.7282494 -0.6771125 -0.1056952 -0.6970785 -0.6949582 -0.1763936 -0.7309461 -0.6800229 -0.05732947 -0.7423636 -0.6642004 -0.08794379 -0.7404904 -0.6651977 -0.09584385 -0.7661533 -0.6028785 -0.2225905 -0.7228371 -0.6135766 -0.3178527 -0.704985 -0.2551506 -0.6617359 -0.7286491 -0.3393874 -0.5948839 -0.736144 -0.343839 -0.582981 -0.7343941 -0.4393411 -0.517344 -0.7517253 -0.4525724 -0.4796741 -0.742722 -0.538508 -0.3979614 -0.755839 -0.5456972 -0.3618317 -0.7462418 -0.6014019 -0.2853753 -0.7574201 -0.6176418 -0.2117391 -0.8233453 -0.04394382 -0.565837 -0.8180041 -0.04434281 -0.5735006 -0.812551 -0.0453788 -0.5811212 -0.8069753 -0.04700773 -0.5887116 -0.8013648 -0.04924643 -0.5961452 -0.7956297 -0.05209165 -0.6035395 -0.7897295 -0.05559295 -0.6109312 -0.7838364 -0.05956828 -0.6181038 -0.7777232 -0.06435859 -0.6253037 -0.7850922 -0.05792194 -0.6166646 -0.7726085 -0.0447883 -0.633301 -0.7667855 -0.03969359 -0.6406751 -0.7608411 -0.03538525 -0.6479728 -0.7547483 -0.0318796 -0.6552395 -0.7454706 -0.02791422 -0.6659538 -0.9476793 -0.07545715 -0.310178 -0.941544 -0.07729279 -0.3279036 -0.9349384 -0.08081519 -0.3454841 -0.927845 -0.08603435 -0.3629074 -0.9201692 -0.06984668 -0.3852406 -0.9162137 -0.06658363 -0.3951192 -0.9116775 -0.06380987 -0.4059218 -0.9069632 -0.06177628 -0.4166553 -0.9948189 -0.1003184 -0.016483 -0.9941733 -0.1018537 -0.03528791 -0.9930286 -0.1047376 -0.05407816 -0.9917168 -0.1081662 -0.06926882 -0.9923502 -0.1063756 -0.06265437 -0.9916614 -0.1002021 -0.08103841 -0.9905705 -0.09519654 -0.09852862 -0.9536828 -0.1165896 0.2773013 -0.9591283 -0.1185613 0.2569361 -0.9644323 -0.1225878 0.2341849 -0.9645959 -0.1227954 0.2334014 -0.9703434 -0.1167177 0.2116856 -0.9742773 -0.1134477 0.1947138 -0.9766774 -0.111725 0.1833547 -0.8192611 -0.1260789 0.5593883 -0.8319894 -0.1277766 0.5398766 -0.8440394 -0.1311502 0.5199973 -0.846915 -0.1324167 0.5149765 -0.856324 -0.1278473 0.5003644 -0.8682481 -0.1235283 0.4805061 -0.7519593 -0.4671399 0.4651213 -0.7705023 -0.4507058 0.4507665 -0.8389905 -0.4408408 0.3189898 -0.8389931 -0.4408398 0.3189846 -0.8891468 -0.4210531 0.1792548 -0.8891496 -0.4210459 0.1792577 -0.9192485 -0.3920035 0.03627145 -0.9192521 -0.391995 0.03627008 -0.928947 -0.3539773 -0.1084328 -0.9289485 -0.3539729 -0.1084335 -0.917866 -0.3082334 -0.2500284 -0.9178674 -0.3082295 -0.2500281 -0.8692263 -0.2341791 -0.4354375 -0.902071 -0.06054472 -0.42732 -0.8970341 -0.06008219 -0.4378587 -0.8918222 -0.06039553 -0.4483367 -0.883755 -0.06201046 -0.4638233 -0.8752803 -0.06593549 -0.4791 -0.8694361 -0.06930971 -0.4891596 -0.8406363 -0.04701787 -0.5395554 -0.8343526 -0.04505985 -0.5493865 -0.8286069 -0.04414308 -0.558088 -0.8634325 -0.07342749 -0.4990919 -0.8572439 -0.0783264 -0.5089183 -0.8690034 -0.06753808 -0.4901755 -0.8526709 -0.05373579 -0.5196778 -0.8467299 -0.04989206 -0.5296785 -0.7728527 -0.1144201 -0.6241849 -0.7728531 -0.1144102 -0.6241863 -0.8471788 -0.1684358 -0.5039023 -0.8471786 -0.168442 -0.5039004 -0.9017134 -0.2181972 -0.3732331 -0.9761825 -0.09252506 -0.1962318 -0.9854691 -0.0886926 -0.1448602 -0.9818067 -0.08888387 -0.1677956 -0.9785565 -0.09074407 -0.1849129 -0.9736241 -0.09488719 -0.2074909 -0.9708591 -0.09780406 -0.2187854 -0.9729774 -0.09519094 -0.210366 -0.969161 -0.08766436 -0.2303085 -0.966737 -0.08403062 -0.241575 -0.9632732 -0.08005821 -0.2563117 -0.9585429 -0.07685554 -0.2743882 -0.9533437 -0.07532143 -0.2923398 -0.9788773 -0.1104993 0.1720156 -0.9809098 -0.1097373 0.160542 -0.9836015 -0.1093142 0.1434524 -0.9865256 -0.1106436 0.1205213 -0.9886998 -0.1138913 0.0974763 -0.9894152 -0.1162554 0.08684754 -0.990657 -0.112734 0.07674473 -0.9924896 -0.1076071 0.05818122 -0.9938111 -0.1037843 0.03960126 -0.9946351 -0.1012994 0.02096796 -0.9949709 -0.1001408 0.002218902 -0.7215307 -0.6614903 0.2045091 -0.7597585 -0.6068076 0.2335628 -0.8030069 -0.5835184 0.1211869 -0.8030085 -0.5835164 0.1211855 -0.8391581 -0.5436174 -0.01714205 -0.8391571 -0.5436191 -0.01714038 -0.8568808 -0.4912908 -0.1561689 -0.8568833 -0.491286 -0.1561701 -0.8554644 -0.4281696 -0.291293 -0.8554613 -0.4281778 -0.2912899 -0.8347687 -0.3549007 -0.4209596 -0.8347688 -0.3549009 -0.4209591 -0.7953552 -0.2738757 -0.5407423 -0.7953569 -0.2738747 -0.5407403 -0.7313445 -0.1776267 -0.658471 -0.7285796 -0.2024888 -0.6543472 -0.6810047 -0.1120103 -0.7236618 -0.6927299 -0.06466776 -0.718292 -0.685954 -0.04975545 -0.7259418 -0.691599 -0.01968884 -0.7220134 -0.6888651 -0.01224696 -0.7247862 -0.879482 -0.1209644 0.4603032 -0.8900453 -0.1201332 0.4397584 -0.8999183 -0.1210497 0.4189202 -0.9082474 -0.1234573 0.3998063 -0.9152027 -0.126722 0.3825517 -0.9179922 -0.1285884 0.375174 -0.9223403 -0.1255633 0.3654071 -0.9295257 -0.1214033 0.3482002 -0.9362384 -0.1184491 0.3307983 -0.9425152 -0.1166375 0.3131466 -0.9483253 -0.1160273 0.2953246 -0.8164169 -0.3166788 0.4828853 -0.8202314 -0.3123467 0.4792286 -0.8850162 -0.305628 0.351195 -0.8850128 -0.3056342 0.3511981 -0.9331039 -0.2919107 0.2100127 -0.933103 -0.2919133 0.2100129 -0.9601721 -0.2717688 0.06489485 -0.9601739 -0.2717618 0.06489616 -0.9658966 -0.245403 -0.08259129 -0.9658957 -0.2454057 -0.08259308 -0.9500351 -0.2136915 -0.2275289 -0.9500343 -0.2136965 -0.2275272 -0.9127138 -0.1769688 -0.3682875 -0.9313464 -0.08271014 -0.3546166 -0.9235618 -0.07321536 -0.376395 -0.6805678 -0.5660555 -0.4651976 -0.7254752 -0.4337065 -0.5344011 -0.7849678 -0.3593561 -0.5046668 -0.7856981 -0.3176566 -0.5308229 -0.8369577 -0.1895349 -0.513399 -0.8350079 -0.1527239 -0.5286182 -0.8534516 -0.03637641 -0.5199011 -0.8555439 -0.0571835 -0.5145627 -0.9785172 -0.0983355 -0.1812019 -0.978517 -0.09833341 -0.1812048 -0.9347136 -0.285197 -0.2120687 -0.9246787 -0.3029402 -0.2306442 -0.8868511 -0.3889959 -0.2493537 -0.8315712 -0.4766454 -0.2851292 -0.811596 -0.4929344 -0.3135725 -0.759018 -0.5560989 -0.3385938 -0.7447651 -0.5687746 -0.3490278 -0.6461156 -0.700706 -0.3025657 0 -0.5193854 -0.8545401 0 -0.5195749 -0.854425 0 -0.8185949 -0.5743713 0 -0.8186442 -0.5743011 0 -0.97952 -0.2013472 0 -0.9795179 -0.2013577 0 -0.8186839 -0.5742445 0 -0.8185757 -0.5743986 0 -0.5195637 -0.8544318 0 -0.5193843 -0.8545409 -0.4444903 -0.5641082 -0.6958523 -0.712249 -0.4162778 -0.5651676 -0.7308383 -0.3569443 -0.5817785 -0.7542758 -0.2854897 -0.5912392 -0.7653496 -0.2944035 -0.5723344 -0.7956576 -0.1641494 -0.5830814 -0.8029946 -0.1697777 -0.5712926 -0.8145605 -0.08199876 -0.5742539 -0.8270446 -0.1109961 -0.5510691 -0.8348362 -0.1029192 -0.5407923 -0.00139898 -0.9999899 -0.004274487 -0.02041363 -0.993709 0.1101173 -0.05924797 -0.9961391 0.06478291 -0.2270327 -0.9728337 -0.04528748 -0.2480063 -0.9683688 -0.02747303 -0.4575819 -0.8847925 0.08809691 -0.4043307 -0.9143811 -0.0205909 -0.5429617 -0.8397575 3.81229e-5 -0.637745 -0.7702476 -1.3766e-4 -0.6115214 -0.7911025 -0.01408284 -0.8044721 -0.592991 0.03444355 -0.952512 0.007466852 -0.3044097 -0.993262 -0.1158912 0 -0.9446572 -0.3250508 -0.04432904 -0.9706989 -0.2402094 0.006566047 -0.8582572 -0.5132187 -0.001108646 -0.7600582 -0.6495765 -0.01903027 0.1212688 0 0.9926197 0.2149941 -0.03026521 0.9761463 0.2676439 -0.01694077 0.9633691 0.6070005 -0.026147 0.7942712 0.5210215 -0.008387207 0.8535024 0.4222012 0.006664872 0.9064778 0.3108163 -0.008924722 0.9504281 0.8699074 -0.03384351 0.4920527 0.820145 0.001830518 0.5721529 0.607392 -0.003982245 0.7943924 0.7017322 -0.08866941 0.7069015 0.6765936 -0.06952953 0.7330667 0.8860594 0 0.463572 0.8928481 -0.03631818 0.4488912 0.9021241 -0.08130484 0.4237471 0.8964339 -0.0627911 0.4387068 -0.001210093 0 0.9999993 -0.001210153 0 0.9999994 0 0 -1 -0.6634345 0 0.7482345 -0.6634389 0 0.7482306 0.003538727 0 -0.9999938 0.003527462 0 -0.9999939 0.002631127 0 -0.9999966 0.002631127 0 -0.9999966 0.7424067 4.4772e-4 -0.6699493 0.7137507 -0.0080868 -0.7003532 0.8299262 0.01817345 -0.5575772 0.7523065 -0.04158836 -0.6574994 0.8935519 0.04695492 -0.4464979 0.8083538 -0.03980565 -0.5873497 0.9860423 0.05604994 -0.1567769 0.9940372 0.001455903 -0.1090322 0.9947778 0.03407043 -0.09621 0.9931856 0.04567104 -0.1072224 0.9954314 0.02450799 -0.09228134 0.9969945 0.008034348 -0.07705473 0.870197 -0.005803287 -0.4926698 0.9093686 -2.60736e-6 -0.4159916 0.9256649 2.83326e-6 -0.3783448 0.9292797 5.94958e-4 -0.3693763 0.9606812 -0.002306878 -0.2776442 0.9514137 -0.009945034 -0.3077551 0.9922295 0.0158022 -0.1234145 0.9799345 -0.02563631 -0.1976649 0.9972062 0 -0.07469809 0.290551 0.06800454 -0.95444 0.1939595 -0.001775383 -0.9810079 0.4708923 9.03869e-4 -0.8821903 0.4694612 3.2748e-4 -0.8829531 0.631658 -3.16801e-4 -0.7752472 0.6168712 -0.006803989 -0.7870348 0.6872503 -1.56884e-4 -0.7264208 0.09914612 -1.15934e-4 -0.9950729 0.001502513 0 -0.9999989 0.001501917 0 -0.9999989 0.001210331 0 -0.9999993 0.001210331 0 -0.9999994 0.001210331 0 -0.9999993 0.001210272 1.70696e-7 -0.9999993 0.001210689 0 -0.9999994 0.001210153 0 -0.9999994 0.00121051 -1.25752e-7 -0.9999993 0.001209318 7.33812e-7 -0.9999994 0.001210331 0 -0.9999993 0.001211047 -1.44884e-6 -0.9999994 0.001210331 0 -0.9999993 0.001210331 0 -0.9999993 0.001210331 0 -0.9999993 0.001210391 -2.87794e-7 -0.9999993 0.001210331 0 -0.9999993 0.001209437 -1.61114e-7 -0.9999993 0.00121051 0 -0.9999993 0.4034974 0.9149808 0 0.4034904 0.9149839 0 0.769158 0.6390587 0 0.7691407 0.6390796 0 0.973419 0.2290315 0 0.9734159 0.2290446 0 0.1001737 0.9949572 0.005059242 0.1025835 0.9947245 0 0.1025626 0.9947265 -7.10091e-5 0.1891376 0.9819507 9.48346e-5 0.6922595 0.7020648 0.1669785 0.645531 0.750863 0.1396226 0.8660151 0.4816054 0.1344406 0.857231 0.4944739 0.1437034 0.9845148 0.1648787 0.05954456 0.9820518 0.175797 0.06833511 0.9748062 0.2230257 0.003552794 0.8808053 0.4483508 0.1521964 0.9873431 0.1458288 0.0623492 0.9865307 0.1496208 0.06611233 0.4495346 0.8929296 -0.02440345 0.4480125 0.8874678 0.1081011 0.3633157 0.931114 0.03207188 0.5333847 0.8454539 0.02662122 0.6423448 0.7647949 0.04982089 0.7024023 0.7094523 0.05752074 0.7884107 0.6049495 0.1115567 0.9403313 0.3372634 0.04506075 0.9741034 0.1995491 0.1063149 0.9892671 0.1428012 0.03096151 0.9843065 0.1544647 0.08533066 0.9826434 0.1648151 0.08513557 0.8756793 0.4465688 0.1837447 0.8605788 0.4788882 0.1734076 0.6409069 0.742659 0.1941546 0.6472524 0.7495316 0.1388047 0.3625346 0.9294977 0.06784528 0.3632991 0.9291533 0.0684697 0.2045298 0.9788477 0.004977166 0.9999965 0.002683699 4.27895e-5 0.9999943 0.002949655 0.001621186 0.9999958 0.002843499 6.15924e-4 0.9999966 0.002000331 -0.001705229 1 1.85799e-6 0 0.2814489 0.8254566 0.4892932 0.4887744 0.09429204 0.8672997 0.526104 0.2474681 0.8136179 0.4783886 0.320621 0.8175247 0.4634931 0.6873952 0.559162 0.408827 0.6043757 0.683806 0.4483225 0.4606178 0.7660537 0.7795258 0.2447504 0.5765735 0.7795268 0.2447562 0.5765696 0.5900179 0.6792864 0.4364045 0.5900262 0.6792805 0.4364024 0.2915978 0.9319083 0.21568 0.3053368 0.9228934 0.2346006 0.9478215 0.2447497 0.2042839 0.9478209 0.2447521 0.2042838 0.7173973 0.6792884 0.1546234 0.7173997 0.679287 0.1546186 0.3236628 0.9435975 0.06975835 0.3064882 0.9509236 0.04253727 0.9854865 0.1697542 0 0.9682219 0.2500195 0.006071925 0.636025 0.7716686 1.65791e-4 0.7261168 0.6875365 0.006924092 0.8078727 0.5893571 -8.27674e-5 0.9123678 0.4093716 5.39654e-5 0.2276495 0.9737432 0 0.2276477 0.9737436 0 0.4620512 0.8856511 0.04615974 0.3096312 0.9508568 0 0.3079461 0.9514039 -3.25048e-4 0.3067655 0.9517852 0 0.306766 0.951785 0 0.4245184 0.9049017 -0.03061527 0.1025573 0.9947271 -1.50028e-4 0.2140949 0.9157679 0.3399009 0.2632745 0.9645019 0.02055794 0.2903326 0.956925 -0.001269519 0.4623242 0.8861836 -0.03057831 0.5817239 0.8114243 -0.05646288 0.5834842 0.8096672 -0.06312865 0.6243005 0.7743159 -0.1033627 0.6985195 0.7016752 -0.1404362 0.8429315 0.5221717 -0.1296272 0.8785097 0.4470046 -0.1685456 0.9711467 0.1695309 -0.1677309 0.9733106 0.1461282 -0.1769552 0.9837682 0.1694521 -0.05904543 0.9837668 0.1694595 -0.05904608 0.9109976 0.4087712 -0.05467808 0.8493198 0.5222146 -0.07712334 0.8069344 0.5886521 -0.04843181 0.6355658 0.7711039 -0.03814643 0.7273409 0.2288371 -0.6469999 0.7478176 0.05895841 -0.6612812 0.7499612 0.1656901 -0.6403944 0.9491707 0.1648795 -0.2681227 0.9491698 0.1648938 -0.2681168 -0.5823246 0.802215 -0.1317161 -0.09798705 0.5638025 0.8200765 -0.6596614 0.6451437 0.3855339 -0.540937 0.2319918 0.8084349 -0.9989411 -0.001134276 0.04599595 -0.8718926 0.001139938 0.4896959 -0.8795775 0 0.4757558 -0.8956165 -0.03549051 0.4434092 -0.939513 -0.2846065 0.1905638 -0.7621527 -0.01090204 0.6473056 -0.9014474 0 -0.4328889 -0.9815647 -0.01288056 0.190696 -0.9993761 3.86517e-4 -0.03531765 -0.9480871 -2.68632e-4 -0.3180109 -0.8455146 0.009583234 -0.5338665 -0.2528846 0.04724252 0.9663423 -0.4490293 0 0.8935171 -0.4407864 3.26453e-4 0.897612 -0.4333863 6.83192e-4 0.901208 -0.3120391 0.01277887 0.9499834 -0.4260314 -0.007754683 0.9046752 -0.3546727 0.01485431 0.9348726 -0.3923965 0.003953695 0.9197878 -0.2669361 0.02887326 0.9632817 -0.2462545 0.03698831 0.9684991 -0.3483858 -0.02637368 0.9369801 -0.3184295 -0.01137381 0.9478783 -0.3145831 -0.02171844 0.9489815 -0.1869026 0 0.9823785 -0.1637665 0.007490932 0.9864708 -0.1743973 0.005465567 0.9846602 -0.1929649 0.00252068 0.9812024 -0.1956827 0.002160549 0.9806649 -0.1816392 0.004252493 0.9833561 -0.1481457 0.01119643 0.9889022 -0.1348256 0.01474446 0.9907596 -0.1565285 0.008093833 0.9876404 -0.1073458 0.001660823 0.9942204 0.02098953 -0.006257414 0.9997602 7.22854e-4 0.003863275 0.9999923 0.1021556 0 0.9947685 -0.3266125 0 0.9451584 -0.3479629 -0.005444824 0.9374925 -0.09655559 0.004511237 0.9953175 -0.1175197 0 0.9930706 0.3508487 0 0.9364323 0.1981438 -0.0257259 0.9798353 0.3899536 0.01994723 0.9206185 0.1627733 -0.006567895 0.9866417 0.0733906 0 0.9973034 0.006692349 0.008411109 0.9999423 0.02382218 0.006305396 0.9996964 -0.4370433 0.3474102 0.8296381 -0.4183712 0.3013958 0.8568116 -0.4001517 0.2610622 0.878479 -0.2536799 0.04956179 0.9660177 -0.3253182 0.1135043 0.9387678 -0.2672345 0.0479784 0.9624364 -0.2309682 0.01279246 0.9728773 -0.3222193 0 0.9466652 -0.4275667 0.3180049 0.8462032 -0.4327111 0.3355805 0.8367478 -0.295988 0.02132672 0.9549536 -0.2668896 0.04679906 0.9625902 -0.3814233 -0.06298941 0.9222519 -0.2199643 0.04098546 0.9746466 0.3523887 -0.02798956 0.9354351 0.1613744 -0.6395067 0.7516578 0.3025078 -0.0491681 0.9518779 0.3139245 0 0.9494481 0.254063 0.05460542 0.965645 0.3214541 0 0.9469252 0.3360028 0.03008723 0.9413803 0.2129852 0.007194519 0.977029 0.2496134 0.02781367 0.9679461 0.2707427 0.04811698 0.9614485 0.2970216 0.077735 0.9517014 0.355762 0.1651479 0.9198694 0.4335019 0.3235444 0.8410679 0.4366119 0.3319983 0.8361502 0.4309498 0.3129909 0.8463563 -0.1465404 5.05244e-6 0.9892047 -0.2298066 0.004733502 0.9732248 -0.3395297 -0.03956961 0.9397627 -0.1318035 -6.139e-7 0.991276 -0.1106371 2.76055e-4 0.9938609 -0.03527516 0.008164763 0.9993443 0.001643359 -0.006018877 0.9999806 0.1117683 0.002474308 0.9937313 0.1133362 0.002224385 0.9935543 0.1447572 0 0.9894673 -0.04761195 0 0.998866 -0.07850378 0.00235176 0.9969111 -0.1368951 -5.2004e-4 0.9905855 -0.3235986 0.002645194 0.9461908 -0.2036146 -0.02629607 0.978698 -0.3506876 0 0.9364925 0.211588 0.00731194 0.9773316 0.2484192 0.02807974 0.9682456 0.268804 0.04796755 0.9619998 0.3228653 -0.02580577 0.9460932 0.2157024 0.05019855 0.975168 0.2990091 0 0.9542503 0.3193494 0.03548139 0.9469726 0.4310853 0.3223574 0.842764 0.323459 0.1096147 0.9398718 -0.1406384 0 0.9900611 -0.1286351 2.61939e-4 0.991692 -0.1074703 0.001524567 0.9942072 -0.07273358 0.00595963 0.9973337 0 -0.01082313 0.9999415 0.1102579 0.01464414 0.9937952 0.1095573 0.01486814 0.9938694 0.1370598 0.008133947 0.9905294 -0.4111401 0.280471 0.8673523 -0.4401082 0.3502324 0.8268265 -0.2551574 0.04946428 0.9656335 -0.3249841 0.1113521 0.9391412 -0.268804 0.04796892 0.9619997 -0.2325423 0.01278877 0.9725022 -0.3032826 0 0.9529007 -0.2633813 0.02167445 0.9644483 -0.2363345 0.03785282 0.9709342 -0.1561138 0 0.9877391 -0.1822489 0.001324534 0.9832516 -0.3229307 -0.015823 0.9462903 0.001209914 1.6245e-7 -0.9999993 0.001208782 0 -0.9999993 0.001210391 0 -0.9999993 0.001210212 0 -0.9999994 0.001210093 0 -0.9999993 0.001210331 0 -0.9999994 0.001209676 -4.23022e-7 -0.9999993 0.001210212 0 -0.9999994 0.001210272 0 -0.9999993 0.001210391 1.77949e-7 -0.9999994 0.001209795 0 -0.9999994 0.001210153 -3.32168e-7 -0.9999994 0.001214444 1.63235e-6 -0.9999993 0.001210331 0 -0.9999993 0.001210212 0 -0.9999993 0.001210272 -1.93772e-7 -0.9999994 0.001210331 0 -0.9999994 0.001210749 7.09611e-7 -0.9999994 0.001208722 0 -0.9999993 0.001210331 0 -0.9999994 0.001210331 0 -0.9999993 0.001210331 0 -0.9999993 0.001210212 0 -0.9999993 0.001210033 0 -0.9999994 0.4341219 -0.701346 -0.5653778 0.781894 -0.4854884 -0.3910792 0.9749346 -0.1734184 -0.1393864 4.91939e-4 -0.7782333 -0.6279752 0.006720244 -0.7810226 -0.6244667 0.006690025 -0.6991212 -0.7149719 0.2801211 -0.6996404 -0.6572942 0.4381282 -0.7018522 -0.5616468 0.4365849 -0.6318502 -0.6404366 0.4592843 -0.621514 -0.6346483 0.459976 -0.5057227 -0.7298402 0.4798308 -0.4966988 -0.7232239 0.4792124 -0.3695334 -0.7961159 0.5062231 -0.3597232 -0.7837969 0.506969 -0.2269756 -0.8315435 0.5279056 -0.2199703 -0.8203223 0.04232752 -0.6558028 -0.7537447 0.04224383 -0.5693593 -0.8210028 0.07366687 -0.564212 -0.8223369 0.07354331 -0.4201898 -0.9044512 0.1167301 -0.4138786 -0.9028171 0.1169561 -0.2618322 -0.9580007 0.1508891 -0.2556207 -0.9549297 0.1506137 -0.09725362 -0.9837974 0.1953028 -0.09163677 -0.9764525 0.4413903 -0.08676397 -0.8931107 0.5273625 -0.0872994 -0.8451435 0.6076061 -0.0749588 -0.7906934 0.7922553 -0.05946785 -0.6072851 0.78356 -0.4850886 -0.3882303 0.7822345 -0.43753 -0.4434827 0.7916563 -0.4276328 -0.4363605 0.7922315 -0.347557 -0.5015709 0.8004022 -0.339568 -0.494014 0.7999303 -0.2526806 -0.5443016 0.8109917 -0.2442409 -0.531638 0.8115514 -0.1538873 -0.5636516 0.8200428 -0.1484522 -0.5527133 0.8197148 -0.0600236 -0.5696182 0.8962332 -0.0421496 -0.4415764 0.9751293 -0.173164 -0.1383374 0.9749249 -0.1564497 -0.1582555 0.976039 -0.1524772 -0.1552379 0.9761373 -0.1238883 -0.1783469 0.9770984 -0.1207587 -0.1752036 0.9770348 -0.08996444 -0.1931564 0.978334 -0.08668392 -0.1880123 0.9784276 -0.05467092 -0.199225 0.9794206 -0.05262809 -0.1948482 0.9793569 -0.02011966 -0.2011352 0.980643 -0.01871246 -0.1949083 0.9843294 -0.127288 -0.1220392 0.9683924 -0.104115 -0.2266634 0.8033455 -0.4563515 -0.3825958 0.7791124 -0.4393479 -0.4471661 0.4519486 -0.6948958 -0.5593411 0.4337458 -0.6841834 -0.5863086 0.003353416 -0.7917054 -0.6108938 4.91264e-4 -0.7896915 -0.6135041 5.01294e-4 -0.7815417 -0.6238529 7.14684e-4 -0.7811825 -0.6243023 0.4465919 -0.6226544 -0.6425397 0.4403713 -0.6463407 -0.6231508 0.789951 -0.3196756 -0.5232448 0.7887812 -0.3822203 -0.4813853 0.9531285 0.06236314 -0.2960693 0.9717479 -0.04180508 -0.2322899 -0.007087767 -0.7712619 -0.6364786 -0.006133735 -0.7680961 -0.6403053 0.4291542 -0.5654276 -0.7043568 0.4283647 -0.5854389 -0.6883059 0.7600098 -0.2215901 -0.610969 0.7702654 -0.2787305 -0.5735857 0.9062866 0.1818134 -0.3815606 0.9412794 0.08711576 -0.3261962 -0.01514458 -0.7625685 -0.6467301 -0.01692718 -0.7583038 -0.6516817 0.4036352 -0.5267112 -0.7481003 0.4098374 -0.5396794 -0.7353771 0.7216087 -0.1596533 -0.6736407 0.7440319 -0.1993125 -0.6377235 0.8600923 0.2521128 -0.4434868 0.9035801 0.185724 -0.3860697 -4.20539e-5 -0.7751168 0.6318181 -2.24531e-4 -0.7751078 0.6318292 -0.4282232 -0.5569904 -0.7116085 -0.03077328 -0.8017734 0.5968354 -0.3770024 -0.5831134 -0.7196165 -0.9791863 -0.01792776 -0.2021701 -0.9616243 -0.01311784 -0.274056 -0.8605845 -0.2373417 -0.4506254 -0.7717356 -0.2823032 -0.5698501 -0.7194485 -0.372831 -0.5859957 -0.4430047 -0.5585488 -0.7012633 0.5337288 0.4429648 -0.7203582 0.3850649 0.5088913 -0.7699058 0.08905702 0.5632332 -0.8214848 -0.5405279 0.493533 -0.6813625 -0.6973063 0.4047877 -0.5915326 -0.436182 -0.5438547 -0.7169152 -0.3416821 -0.4967681 -0.7977938 -0.722373 -0.3800363 -0.5777109 -0.6590445 -0.3648437 -0.657685 -0.8270334 -0.1551659 -0.5403143 -0.872045 -0.1509624 -0.4655619 -0.8976019 0.1754215 -0.4043989 -0.8731491 0.3200733 -0.367646 -0.9281194 0.1791 -0.3263705 -0.9406476 0.1562073 -0.3012996 -0.8139759 0.3281494 -0.4793343 -0.8778383 0.2906011 -0.3807242 -0.8178847 -0.03637039 -0.5742316 -0.8127889 -0.04502362 -0.5808159 -0.6415635 -0.3442975 -0.68546 -0.6454524 -0.3405928 -0.6836576 -0.3751814 -0.6055813 -0.7017908 -0.3957052 -0.5941279 -0.7003067 -0.7823398 0.364386 -0.5051409 -0.7760435 0.3530086 -0.5226293 -0.7503511 0.02076828 -0.6607131 -0.7454062 0.01525205 -0.666436 -0.6109671 -0.3265075 -0.721188 -0.6132004 -0.3248471 -0.7200415 -0.3838276 -0.6271416 -0.6777682 -0.397474 -0.6209169 -0.6756306 -0.5898482 0.4864226 -0.6445714 -0.6193646 0.557327 -0.5529686 -0.6675807 0.08927869 -0.7391653 -0.6598878 0.06320893 -0.7487007 -0.5675736 -0.3138855 -0.7611413 -0.5715238 -0.3073114 -0.7608681 -0.3677266 -0.6644129 -0.6506403 -0.399428 -0.6346908 -0.6615322 -0.5181767 0.5140852 -0.6835272 -0.5109691 0.5115132 -0.6908436 -0.5714825 0.1104016 -0.8131539 -0.5650936 0.1032385 -0.818542 -0.5156847 -0.3092994 -0.7990013 -0.5174404 -0.3077992 -0.7984455 -0.3676433 -0.6736819 -0.6410859 -0.3810883 -0.6661351 -0.6411207 -0.2658267 0.6804814 -0.6828479 -0.4576551 0.5145112 -0.7251414 -0.5091845 0.5113644 -0.6922699 -0.3317173 -0.7056853 -0.6260766 -0.3237811 -0.7100264 -0.6253226 -0.3636523 -0.3186135 -0.8753527 -0.3640853 -0.3182851 -0.8752923 -0.3181387 0.136231 -0.9382052 -0.3258796 0.1426614 -0.9345856 -0.3639544 -0.6734325 -0.6434485 -0.3426199 -0.7042177 -0.6218433 -0.4452836 -0.3040601 -0.8421817 -0.4442495 -0.3071413 -0.8416097 -0.4460808 0.117802 -0.8872061 -0.4499669 0.1524863 -0.8799306 -0.3455826 0.5758929 -0.7408914 -0.2042877 0.5618667 -0.8016062 -0.05826145 0.5962473 -0.800684 -0.1806765 0.5671964 -0.8035199 -0.2180771 0.5726079 -0.7902928 0.05214476 0.5731409 -0.8177961 -0.01802408 0.6377418 -0.7700394 -0.1824112 0.1579178 -0.9704578 -0.1817821 0.1201854 -0.9759666 -0.2691344 -0.3211452 -0.9079827 -0.2677624 -0.331458 -0.9046761 -0.2913413 -0.7259343 -0.6230086 -0.2957926 -0.713968 -0.6346309 0.2473876 0.5590905 -0.7913389 0.2479122 0.5512644 -0.7966476 0.09720993 0.1245371 -0.9874416 0.09474486 0.08049607 -0.9922418 -0.06664925 -0.3476417 -0.9352558 -0.06878703 -0.376451 -0.9238794 -0.216458 -0.7355273 -0.6419855 -0.2166323 -0.7464674 -0.6291717 0.4037442 0.5057583 -0.7623643 0.4109727 0.5005866 -0.7619151 0.2582454 0.06480312 -0.9639036 0.2679553 0.05504989 -0.9618573 0.05032867 -0.3944042 -0.9175578 0.05830752 -0.4026759 -0.9134836 -0.1717742 -0.7521243 -0.6362411 -0.1651425 -0.7579579 -0.6310529 0.6588238 0.400453 -0.6368584 0.5656151 0.4835259 -0.6680437 0.4162434 0.03416883 -0.908611 0.4111241 -0.004459619 -0.9115686 0.1758309 -0.4043443 -0.8975462 0.163322 -0.4420679 -0.8819875 -0.1129283 -0.7438273 -0.6587627 -0.1281627 -0.7707206 -0.6241507 0.7786548 0.3325915 -0.5320523 0.7808244 0.3088314 -0.5430805 0.641991 -0.0727691 -0.7632511 0.6318408 -0.108671 -0.7674424 0.3498667 -0.463396 -0.8141606 0.3240544 -0.5028778 -0.8013131 -0.03106188 -0.7438415 -0.667634 -0.06881535 -0.7734553 -0.6301043 -0.9807558 0 -0.1952387 -0.9807558 0 -0.1952389 -0.8312178 0 -0.5559471 -0.8312172 0 -0.5559478 -0.5549428 0 -0.8318886 -0.5549423 0 -0.8318889 -0.1940504 0 -0.9809916 -0.1940505 0 -0.9809916 -0.9230448 -0.2429898 -0.2982354 -0.9857201 -0.1063061 -0.130595 -0.7041147 -0.4489697 -0.5501351 -0.8450812 -0.3367608 -0.415247 -0.5744786 -0.516102 -0.6353055 -0.3767789 -0.5862415 -0.717188 -0.9857057 -0.1058103 -0.1311052 -0.9856212 -0.09585082 -0.1391528 -0.9846554 -0.09838259 -0.1441341 -0.9846033 -0.07285529 -0.1588978 -0.9832794 -0.07514649 -0.1658758 -0.9833206 -0.04707801 -0.1756825 -0.9821906 -0.04776984 -0.1817135 -0.9821197 -0.017668 -0.1874272 -0.9806061 -0.01746964 -0.1952087 -0.7767621 0.08290779 -0.6243131 -0.8731984 -0.2770645 -0.4009488 -0.8647944 -0.2836813 -0.4143134 -0.8644723 -0.2102333 -0.4566067 -0.853008 -0.2161107 -0.4750511 -0.8533647 -0.1357716 -0.5033238 -0.843601 -0.1373543 -0.5191062 -0.8431672 -0.05134236 -0.5351945 -0.8301537 -0.05058759 -0.5552349 -0.5916441 -0.07160782 -0.8030129 -0.6616341 -0.4264873 -0.6167244 -0.6401577 -0.434147 -0.6338095 -0.6396192 -0.3217375 -0.6981205 -0.6105363 -0.3281031 -0.7208285 -0.6111416 -0.2064588 -0.764121 -0.5865144 -0.2073106 -0.782958 -0.5858501 -0.0777148 -0.8066847 -0.5533508 -0.0757156 -0.8295 -0.3764929 -0.5827506 -0.720177 -0.3754919 -0.5273772 -0.7621543 -0.3385151 -0.5316736 -0.7763575 -0.3380911 -0.3941593 -0.8545951 -0.2886165 -0.3965446 -0.8714659 -0.2890405 -0.2500491 -0.9240839 -0.2475991 -0.2478001 -0.9366375 -0.2472015 -0.09327816 -0.9644639 -0.1932813 -0.0889737 -0.9771009 -0.7257359 0.2411774 0.6443144 -0.6117031 0.4727227 0.6343128 -0.5903543 0.5504242 0.5903518 -0.0925526 0.9713281 0.2189882 -0.05492132 0.9797995 0.1922933 -0.283393 0.750628 0.5968635 -0.1704278 0.826397 0.5366773 -0.4170377 0.3638474 0.8328834 -0.2459377 0.5473412 0.7999577 -0.4300764 0.09008091 0.8982872 -0.3886923 0.1942317 0.9006621 -0.3774119 -0.146246 0.9144247 -0.04044121 0.9759127 0.2143807 -0.05665481 0.9715959 0.2297646 -0.100791 0.7914767 0.6028315 -0.1419411 0.7536004 0.6418249 -0.1441538 0.4589712 0.8766786 -0.1974108 0.3677085 0.9087462 -0.1591551 0.04165691 0.9863744 -0.1394818 0.09004962 0.9861217 -0.2558842 -0.3773733 0.8900072 -0.06643134 -0.1433804 0.9874356 0.02285212 0.9691018 0.2456007 0.04007112 0.9747777 0.2195512 0.0458374 0.7344291 0.6771358 0.0957967 0.7854481 0.611469 0.05743122 0.334007 0.9408194 0.1412113 0.4513052 0.881126 0.04556214 -0.1343496 0.989886 0.1754456 0.04060226 0.9836516 0.004668593 -0.5706565 0.8211756 0.2050328 -0.3710061 0.9057131 0.2774807 -0.5998979 0.7504179 0.2730031 -0.610463 0.7435081 0.3424317 -0.1508496 0.9273538 0.3405625 -0.1609705 0.92634 0.3263434 0.3340352 0.8842627 0.3262513 0.3270877 0.88689 0.2329649 0.7396885 0.6313385 0.2335278 0.7367267 0.6345854 0.08438289 0.9698746 0.2285232 0.08468842 0.9695176 0.2299212 0.2523857 -0.5871006 0.7691648 0.2473764 -0.5999222 0.7608536 0.3082631 -0.1385948 0.9411512 0.3061097 -0.1508409 0.9399701 0.2922714 0.34236 0.8929542 0.2920677 0.3340387 0.8961666 0.2080789 0.7432415 0.6358422 0.2086195 0.7396946 0.6397889 0.07529371 0.970304 0.2298717 0.07560068 0.9698761 0.2315706 0.1408531 0.9696401 0.1998959 0.1392853 0.9704809 0.1968924 0.2969828 0.8728724 0.3871628 0.4088371 0.7436828 0.52895 0.4209601 0.7301414 0.5382251 0.5545377 0.4808709 0.6791548 0.5889183 0.3461258 0.7303233 0.6139302 0.2580224 0.7459989 0.7610124 -0.02158206 0.6483783 0.7365101 -0.02167814 0.6760792 0.637947 -0.1266633 0.7595921 0.6341357 -0.06513416 0.7704735 0.8020598 -0.1684423 0.5729984 0.7943301 0.03224724 0.6066301 0.8806409 0.03225982 0.472685 0.8158962 -0.4419022 0.372875 0.9240348 -0.02289235 0.3816223 0.9177755 0.2831864 0.2783769 0.9497891 0.1090121 0.2932866 0.9915804 0.1291236 0.009764254 0.9953086 0.09483021 0.01918411 0.9782272 -0.190169 0.08311092 0.9011437 -0.422942 0.09518468 0.3412836 -0.6095215 0.7155482 0.1058313 0.9705001 0.216632 0.1063404 0.9693605 0.2214319 0.294018 0.7452964 0.5984034 0.2944195 0.735741 0.60992 0.4139413 0.3484608 0.8409684 0.4107637 0.3262522 0.8513711 0.438979 -0.1279901 0.8893346 0.4278692 -0.1605407 0.8894688 0.3639566 -0.5753503 0.7324669 0.521229 -0.5717088 0.6336162 0.5771094 -0.4507505 0.6810058 0.7084466 -0.4530434 0.541161 0.7551727 -0.3421851 0.5591276 0.846083 -0.3411049 0.4096231 0.8944331 -0.1444416 0.4232331 0.9471647 -0.1451668 0.2860172 0.9592754 -0.05310887 0.2774352 0.9833211 -0.05310398 0.1739532 0.9606624 0.2134719 0.1776444 0.9916374 0.1290563 0 0.9916201 0.1291886 0 0.9916158 0.129123 -0.005035042 0.9916441 0.1289857 -0.002194166 -0.7811626 0.152197 0.6054926 -0.1493505 0.9761382 0.1576353 -0.287315 0.9291622 0.2326106 -0.3194401 0.8943309 0.3132579 -0.5263002 0.6586498 0.5377627 -0.525806 0.671689 0.5218831 -0.6849684 0.2373617 0.6888235 -0.6857886 0.243711 0.6857835 -0.9227431 0.09220969 -0.3742228 -0.9088788 0.1078421 -0.4028767 -0.9719884 0.1770926 -0.1545214 -0.6965138 0.08395296 -0.7126153 -0.6940274 0.09145092 -0.7141168 -0.7427758 0.05362176 -0.6673896 -0.9381121 0.3343724 -0.09022659 -0.9855688 0.1610929 -0.0519942 -0.9934291 0.1122951 0.02210593 -0.9178763 0.3911837 -0.06692332 -0.8750036 0.2236455 -0.4293618 -0.8728488 0.2556025 -0.415695 -0.7041497 0.08163613 -0.705343 -0.6830776 0.1202939 -0.720371 -0.6906072 0.1192842 -0.7133253 -0.7933703 0.2839018 -0.5384825 -0.7972165 0.385718 -0.4644002 -0.846405 0.3796615 -0.3734381 -0.839495 0.529859 -0.1204065 -0.8149616 0.5532544 -0.172474 -0.8245975 0.5643106 0.03990793 -0.9576602 0.1436869 0.2494817 -0.9208472 0.2524285 0.2971878 -0.9173411 0.2749375 0.2879145 -0.8515759 0.4639258 0.2441138 -0.8560813 0.4142421 0.3090771 -0.7365607 0.6380293 0.224493 -0.7519698 0.5917161 0.2905402 -0.5491279 -0.7905741 -0.2710192 -0.2031994 -0.9378436 0.2813531 -0.2888323 -0.947088 0.1400014 -0.6253093 -0.1845456 -0.7582421 -0.6363282 -0.1471968 -0.7572448 -0.644024 -0.3125429 -0.6982479 -0.6466078 -0.3789515 -0.662038 -0.6481572 -0.5260079 -0.5506433 -0.6606189 -0.4941552 -0.5651491 -0.6016115 -0.6624296 -0.446375 -0.6329017 -0.1690649 -0.7555478 -0.6312072 -0.1812853 -0.7541307 -0.6857319 -0.4802407 -0.5469375 -0.6732021 -0.5122665 -0.5332748 -0.7248705 -0.6599147 -0.1976751 -0.6402328 -0.7227502 -0.2602579 -0.6067621 -0.7616043 -0.2275937 -0.5478607 -0.7925416 -0.2678181 -0.4605796 -0.875059 -0.1487894 -0.6447073 -0.1292442 -0.7534244 -0.6527929 -0.1554834 -0.7414084 -0.7203953 -0.314301 -0.6182602 -0.7424948 -0.439889 -0.5051724 -0.7408969 -0.4349628 -0.5117413 -0.7537445 -0.5747678 -0.3186084 -0.8151125 -0.5072384 -0.2798234 -0.814287 -0.4648408 -0.3476492 -0.7936272 -0.37557 -0.4786473 -0.6947988 -0.1680669 -0.6992911 -0.6602376 -0.1105567 -0.7428752 -0.7538801 -0.2753314 -0.596538 -0.6994017 -0.1575592 -0.6971459 -0.7004539 -0.1611191 -0.6952733 -0.8304021 -0.4370415 -0.3455824 -0.8292356 -0.4460061 -0.3368188 -0.7095566 -0.138679 -0.6908673 -0.7105385 -0.1411405 -0.6893581 -0.8613548 -0.3855055 -0.3308377 -0.861082 -0.3917815 -0.3241066 -0.88721 -0.2278177 -0.4011953 -0.5791981 -0.002739429 -0.8151823 -0.7289295 -0.09580922 -0.6778514 -0.7974471 -0.2080286 -0.5663941 -0.6990303 -0.07647776 -0.7109908 -0.9162949 -0.2686833 -0.2970066 -0.9187602 -0.3571555 -0.168285 -0.915432 -0.3045057 -0.2631741 -0.7195167 -0.1176826 -0.6844316 -0.7203803 -0.1191422 -0.6832697 -0.8908299 -0.3276929 -0.3147056 -0.8911518 -0.3314498 -0.3098218 -0.8197554 -0.4636274 0.3362305 -0.8207156 -0.5593705 -0.1163218 -0.8191923 -0.5642898 -0.1024753 -0.7617578 -0.2676438 -0.5899931 -0.8077583 -0.3692603 -0.459536 -0.8116024 -0.3781949 -0.4452756 -0.8272969 -0.4577181 -0.32569 -0.8288145 -0.5098696 -0.2304333 -0.6794898 -0.1343665 -0.7212761 -0.5852912 0.009710371 -0.8107651 -0.6728304 -0.1220836 -0.7296539 -0.700801 -0.6603445 0.2698576 -0.7071878 -0.6583205 0.2578753 -0.7495458 -0.6451542 0.1481795 -0.797578 -0.6031923 -0.005324363 -0.7746424 -0.5542412 0.3045423 -0.8891062 -0.4548709 0.05082142 -0.9023315 -0.428826 -0.04366141 -0.9023276 -0.4288348 -0.04365366 -0.8677854 -0.2871728 -0.4055616 -0.8677719 -0.2871837 -0.4055828 -0.7002353 -0.1010059 -0.7067308 -0.7001948 -0.1010046 -0.706771 -0.8729296 -0.3127599 0.3743998 -0.8729217 -0.3127603 0.3744179 -0.9640918 -0.2655689 -4.05581e-4 -0.9640966 -0.2655519 -4.15322e-4 -0.909132 -0.1778481 -0.3766286 -0.9091408 -0.1778422 -0.3766104 -0.7147501 -0.06255555 -0.6965768 -0.7147742 -0.06254637 -0.6965529 -0.9101659 -0.1058957 0.4004803 -0.910161 -0.105898 0.4004908 -0.9957121 -0.08991914 0.02172559 -0.9957123 -0.08991807 0.02172309 -0.9303139 -0.06021618 -0.3617876 -0.9303138 -0.06021851 -0.3617872 -0.7222065 -0.02118247 -0.6913531 -0.7222078 -0.0211811 -0.6913518 0.7491195 0 -0.6624349 0.7481163 5.00931e-5 -0.6635676 0.9623417 -5.29469e-5 -0.2718427 0.9619265 0 -0.2733084 -0.9881852 0 0.1532647 -0.9881852 0 0.1532645 -0.8953338 0 0.4453961 -0.8953346 0 0.4453943 0.9626483 1.90929e-4 0.270755 0.964986 0.006535708 0.2622202 0.9712209 -0.01407957 0.2377644 0.9628832 -0.001596271 0.2699136 0.9922881 -2.27884e-4 0.1239534 0.9893051 -0.008712708 0.1456007 0.9896972 -0.01126348 0.1427332 0.9886559 -0.006835103 0.1500427 0.9810622 0.01643806 0.1929943 0.9832299 2.36998e-4 0.1823704 0.9732517 -1.4451e-4 0.2297416 0.9738975 -0.002996265 0.2269688 0.9646255 0.003933489 0.2635948 0.9631645 -0.03019988 0.2672121 0.963094 -0.00589317 0.269101 0.9953119 5.14657e-4 0.096717 0.9947252 0.003454923 0.1025177 0.9991498 -0.01042282 0.0398876 0.9970954 0.02565783 0.07171064 0.9986937 0.00268054 0.05102777 0.9986379 0.01844918 0.04880601 0.9892053 0.1433407 0.03043991 0.9974799 0.00231111 0.07091301 0.9974152 0 0.07185471 0.0680741 -7.94357e-6 -0.9976803 0.06813925 -2.35288e-5 -0.9976758 0.08398091 -0.005248785 -0.9964535 0.06777578 7.34564e-5 -0.9977006 0.06803315 1.07255e-5 -0.9976831 -0.5779739 -0.6705296 0.4651198 -0.8143652 -0.1079487 0.570225 -0.6792909 -0.5650388 0.4682896 -0.6911005 -0.5368459 0.4839178 -0.7218628 -0.4726865 0.5054519 -0.7214043 -0.4211525 0.5497332 -0.7840955 -0.3187874 0.5325119 -0.8004664 -0.1410611 0.5825422 -0.8143237 -0.1081069 0.5702542 0.2469079 0.8967918 -0.3671524 0.4918789 0.258731 -0.8313323 0.1318596 0.9658992 -0.2228273 0.1088997 0.9807763 -0.161922 0.1367607 0.9659254 -0.2197375 0.1318504 0.9659029 -0.2228161 0.3601778 0.7069451 -0.6086877 0.3397594 0.7932842 -0.5052365 0.3844857 0.7070784 -0.5934737 0.3601285 0.7070097 -0.6086419 0.4919093 0.2586986 -0.8313244 0.5472893 0.1950007 -0.8139098 0.5314825 0.2587619 -0.8065785 0.5004931 0.442195 -0.7442919 0.4427466 0.6086596 -0.658414 0.1220666 0.9659267 -0.2282227 0.122076 0.9659219 -0.2282375 0.4555611 0.258837 -0.8517438 0.4659289 0.1951249 -0.8630391 0.4230202 0.4421889 -0.7909001 0.3335065 0.7070888 -0.6235375 0.3808512 0.6087823 -0.6959429 0.2871194 0.7933461 -0.5368095 0.4576527 0.2587512 -0.850648 0.4576408 0.2588419 -0.8506268 0.3350247 0.7070926 -0.6227188 0.33503 0.7070806 -0.6227295 0.1226318 0.9659219 -0.2279395 0.1226266 0.9659246 -0.2279307 0.3069278 0.1919416 -0.932177 0.3069646 0.1919582 -0.9321614 0.2814524 0.4362285 -0.8546867 0.2813924 0.4362872 -0.8546765 0.2496736 0.6023042 -0.7582168 0.2496663 0.6022371 -0.7582725 0.1924378 0.7883201 -0.5843965 0.1924421 0.7883338 -0.5843765 0.1401906 0.8939017 -0.4257774 0.1412115 0.9741321 -0.1764261 0.08224433 0.9648118 -0.2497485 -0.1841147 -0.4666041 0.865091 -0.9283641 -0.3654729 0.06759983 -0.9506037 -0.2749956 0.1439794 -0.9668267 -0.08391106 0.2412574 -0.8968608 -0.2503641 0.3646347 -0.8282982 -0.3445783 0.4418008 -0.2796459 -0.09411805 0.955479 -0.02213287 -0.01937723 0.9995673 -0.001534163 -0.001814603 0.9999972 -0.3437711 -0.2957478 0.8912659 -0.788712 -0.3463937 0.5078827 -0.7507059 -0.332833 0.5706689 -0.7087299 -0.4269411 0.5616256 -0.7106731 -0.2280746 0.6655267 -0.2653302 -0.09942281 0.9590178 -0.1648446 -0.1989429 0.9660477 -0.1643633 -0.1991044 0.9660964 -0.1292201 -0.2239941 0.965986 -0.1288056 -0.2240287 0.9660333 -0.08961266 -0.2420335 0.9661208 -0.08930909 -0.2420335 0.966149 -0.04775464 -0.2539309 0.9660428 -0.04759979 -0.2538975 0.9660593 -0.7464483 -0.08232319 0.6603316 -0.5361236 -0.4602556 0.7076273 -0.5342196 -0.4616572 0.708154 -0.4505476 -0.5430053 0.708627 -0.4488475 -0.543954 0.7089782 -0.3529946 -0.6112015 0.7083979 -0.3515879 -0.6116346 0.7087236 -0.2449624 -0.66105 0.7092294 -0.2440115 -0.6612136 0.7094047 -0.1304784 -0.6931923 0.7088441 -0.1299449 -0.6931695 0.7089644 -0.9644692 -0.09610444 0.246096 -0.8280552 -0.4957588 0.2618167 -0.824879 -0.5004893 0.2628405 -0.7327675 -0.6278363 0.2624375 -0.729349 -0.6313505 0.2635272 -0.6165034 -0.7418248 0.2638553 -0.6132324 -0.7442734 0.2645812 -0.4828873 -0.8348827 0.2641795 -0.4800891 -0.8362759 0.2648721 -0.3354319 -0.903961 0.265217 -0.3333958 -0.9046016 0.2655998 -0.1785691 -0.9475125 0.2652043 -0.1774518 -0.9476517 0.2654567 0.6751796 0.7320997 -0.09034752 0.6371201 0.7629792 0.1092732 0.7973582 0.6035037 -0.001826882 0.9747962 0.2230594 0.004098594 0.9212818 0.3842784 0.05975025 0.9218449 0.3836132 0.05516445 0.757972 0.6521056 0.01539731 0.8284287 0.5599873 -0.01096904 0.5353327 0.8436565 -0.04077529 0.616213 0.7855058 -0.05711621 0.9672853 0.2367322 0.09119719 0.9657217 0.2378178 0.10404 0.9582307 0.2202496 0.1824391 0.9854295 0.134481 0.1041323 0.9907589 0.1258597 0.05055946 1 2.83605e-6 0 0.9823266 0 -0.1871757 0.9834703 0.02856123 -0.1788027 0.9955092 -0.01976948 -0.09257751 0.9979751 0.02140355 -0.05989849 0.9998548 0 -0.01704877 0.9612101 0.1463955 -0.2337599 0.9245796 0.1521521 -0.3492884 0.8935266 0.4416295 -0.08107799 0.8964992 0.440891 -0.04363912 0.6565799 0.6858128 -0.3139486 0.6999142 0.7015312 -0.1340677 -0.4700437 -0.8111642 0.3479537 -0.4921553 -0.8372578 0.2382912 -0.357668 -0.9117571 0.2019222 -0.3410887 -0.9224916 0.1807423 -0.1442795 -0.9807025 0.1319321 -0.1534318 -0.9844851 0.08513486 -0.00275135 -0.9999949 0.001656055 -0.9025515 -0.002635359 0.4305739 -0.8933853 -0.09337735 0.4394809 -0.9554537 -0.1628565 0.2461422 -0.8070461 -0.3088721 0.5032641 -0.8244347 -0.3652207 0.432344 -0.7800645 -0.5520941 0.2944341 -0.631306 -0.4675626 0.6187391 -0.7180066 -0.6750775 0.1695197 -0.685411 -0.6241099 0.3750981 -0.6160271 -0.7249268 0.3082074 0.8973253 -0.002635598 0.441362 0.7147243 -0.596903 0.3645216 0.6141844 -0.7185456 0.3262971 0.576333 -0.7752134 0.2586205 0.427119 -0.8392459 0.3365053 0.4034403 -0.8889096 0.2169692 0.3133538 -0.9322305 0.1809856 0.209474 -0.9761651 0.05676698 0.1458522 -0.9857791 0.08346742 0.002735018 -0.9999948 0.001704156 0.8758329 -0.1732255 0.4504551 0.6182909 -0.6400032 0.4561933 0.8083902 -0.4733818 0.3498784 0.7890868 -0.378102 0.4841292 0.8106453 -0.3575336 0.4637069 0.8896274 -0.2365875 0.3906273 0.9643658 -0.1040599 0.243249 0.9337264 -0.3347362 0.1269131 0.9652349 -0.1838787 0.1857696 0.8710607 -0.01553851 0.4909295 0.06570589 -0.2600741 0.9633506 0.0875777 -0.2578174 0.9622164 0.2428549 -0.2489671 0.9375697 0.2028985 -0.2613075 0.94369 0.4017587 -0.2194827 0.8890541 0.3236424 -0.2538303 0.9114964 0.5335077 -0.1819243 0.8259983 0.4525651 -0.2461663 0.8570805 0.6160263 -0.1611413 0.7710675 0.5297207 -0.2183933 0.8195734 0.6802029 -0.1269242 0.7219517 0.6237495 -0.2159655 0.751196 0.7713503 -0.08861088 0.6302117 0.7411184 -0.1812093 0.6464572 0.8425694 -0.05477941 0.5357949 0.8385629 -0.1436445 0.525527 0.8959609 -0.03376632 0.4428477 0.8941736 -0.1816978 0.4091938 0.9495126 -0.1924113 0.2477979 0.9004729 -0.2915089 0.3227555 0.8984493 -0.2979511 0.3225125 0.8265708 -0.3918046 0.4040668 0.822923 -0.3981385 0.4053193 0.7285872 -0.4834426 0.4852257 0.7216505 -0.4911952 0.4877989 0.6504372 -0.5387945 0.5353803 0.6397633 -0.5457118 0.5412039 0.5701839 -0.5828671 0.5789268 0.5536534 -0.593479 0.5841665 0.4328284 -0.6398163 0.635055 0.4035835 -0.6510547 0.6428438 0.2740076 -0.6807285 0.6793589 0.2272039 -0.691618 0.6855968 0.08716487 -0.7023152 0.7065095 0.02688252 -0.7051852 0.7085134 0.9457588 -0.3238033 0.02630507 0.9128804 -0.3998379 0.08233523 0.8449144 -0.5275056 0.08864229 0.8300845 -0.5475577 0.1055485 0.7347038 -0.6654035 0.1320925 0.7259057 -0.6735153 0.1394211 0.6011815 -0.7802323 0.1726805 0.6351351 -0.7573611 0.1516823 0.5109819 -0.832951 0.2123446 0.5575931 -0.8086317 0.1876291 0.4079973 -0.8862205 0.2194346 0.4087542 -0.8859433 0.2191452 0.2601441 -0.9334869 0.2468345 0.2372533 -0.9380099 0.2526827 0.1117143 -0.9594465 0.2588095 0.04203993 -0.9627451 0.2671226 -0.02833002 -0.9635649 0.2659704 -0.0647459 -0.961517 0.2670076 -0.09694212 -0.9589446 0.26651 -0.01800495 -0.7033192 0.7106462 -0.07945364 -0.6993026 0.7103964 0.02827352 -0.2581619 0.9656879 -0.02985966 -0.2556078 0.9663194 -0.8261799 -0.5481486 -0.1302304 -0.9504446 -0.30246 -0.07192271 -0.9583184 -0.2780625 -0.06562966 -0.955321 -0.2876242 -0.06807392 -0.9999997 -8.09061e-4 -2.07951e-4 -0.9897964 -0.1386061 -0.033041 -0.9986155 -0.04805552 -0.02140283 -0.9818593 -0.184529 -0.04360586 -0.9172458 -0.3793383 -0.121502 -0.9197931 -0.3719851 -0.1249307 -0.9190504 -0.378562 -0.1097142 -0.9524602 -0.2964487 -0.07027071 -0.9511361 -0.3004401 -0.07124674 -0.9149521 -0.392439 -0.09409713 -0.9389501 -0.3354646 -0.07639491 -0.8572139 -0.5001814 -0.1224866 -0.8366586 -0.5308455 -0.1349281 -0.9062021 -0.4136219 -0.08783394 -0.8675351 -0.4846378 -0.1118444 1 6.59145e-7 0 1 3.44892e-6 0 1 -3.97874e-6 0 1 -5.60008e-7 0 1 -1.37304e-6 0 1 -2.35363e-5 0 1 9.68185e-7 0 1 2.64598e-6 0 0.1208126 0 -0.9926754 0.09914058 -0.01100862 -0.9950126 0.3021661 0.008067727 -0.9532213 0.2912232 0.003660798 -0.9566482 0.4670154 -0.00420612 -0.8842393 0.4708908 -0.00218594 -0.8821889 0.6279208 0.001878559 -0.778275 0.6316533 0.003846704 -0.7752415 0.9963883 -0.006838679 -0.08463877 0.9982894 -0.001394033 -0.05845129 0.9885352 0.001114189 -0.1509865 0.9828749 -0.004587411 -0.184217 0.961027 0.00594449 -0.2763907 0.9542393 5.56603e-4 -0.2990437 0.9303611 -2.05759e-4 -0.3666445 0.9312387 -5.31407e-6 -0.3644099 0.8930603 6.93889e-6 -0.4499372 0.8999072 0.005398154 -0.436048 0.8333611 -0.004397332 -0.5527116 0.8446888 0.001682162 -0.5352551 0.7578103 -0.002345263 -0.6524708 0.7632663 0.00112605 -0.646083 0.6988612 -1.25193e-4 -0.7152574 0.9985744 -0.002544343 -0.05331647 0.9996118 -5.84802e-4 -0.0278564 0.9999657 0 -0.008283138 -0.7071043 0 0.7071093 -0.7071108 0 0.7071028 -0.7071088 1.63456e-6 0.7071048 -0.7071048 1.68067e-6 0.7071089 -0.7070128 -1.77076e-5 0.7072009 0.671346 0.4643161 0.5776722 0.6735176 0.4645608 0.5749413 0.6451791 0.4673839 0.6043974 0.6361353 0.4646812 0.6159572 0.6184936 0.4690539 0.6304397 0.6060445 0.4679335 0.6432327 0.5922034 0.4667683 0.6568276 0.5921964 0.4667632 0.6568376 0.576265 0.4637059 0.6729751 0.5762307 0.4637017 0.6730075 0.5600348 0.4600515 0.6889948 0.5620216 0.4614307 0.68645 0.5346412 0.4505678 0.7149459 0.5268146 0.4431955 0.7252891 0.5090544 0.4398021 0.7398904 0.4975091 0.4328836 0.751729 0.4847871 0.4253192 0.7642546 0.4847755 0.4253085 0.7642681 0.4704664 0.4149098 0.7787883 0.4704384 0.4149041 0.7788084 0.4560006 0.4039223 0.7930387 0.4575366 0.4062821 0.7909457 0.4342789 0.3829564 0.8153198 0.4286833 0.3717489 0.8234279 0.4126358 0.3609693 0.8363211 0.4034285 0.3489721 0.8458511 0.393122 0.3359203 0.855928 0.3931208 0.3359108 0.8559324 0.3820454 0.3193501 0.8672122 0.382044 0.3193415 0.8672159 0.3709704 0.3022552 0.878079 0.3718534 0.3053411 0.8766368 0.3553907 0.2721762 0.8942134 0.3528094 0.2583953 0.8993095 0.340095 0.2414478 0.9088665 0.3342293 0.2256854 0.9150722 0.3275509 0.2086589 0.9215053 0.3275522 0.2086519 0.9215064 0.3209874 0.1877885 0.9282794 0.3209734 0.1877581 0.9282904 0.3145267 0.1665232 0.9345283 0.3146194 0.1699755 0.9338753 0.3068813 0.1307147 0.9427289 0.307738 0.1159164 0.9443839 0.2996187 0.09471064 0.9493464 0.2977342 0.07703953 0.9515352 0.2954602 0.0578739 0.9536005 0.2954599 0.05787318 0.9536007 0.2941514 0.03504842 0.955116 0.2941507 0.03506374 0.9551157 0.2932046 0.01542633 0.9559254 0.2932025 0.01542884 0.955926 -0.5900777 -0.05761843 0.8052879 -0.4113714 -0.1395666 0.9007192 -0.3258124 -0.1620935 0.9314355 0.1158561 -0.2852939 0.951412 -0.1460179 -0.234058 0.9611949 -0.2069901 -0.2037671 0.9568877 -0.2787489 -0.1781332 0.9436989 -0.5250245 -0.1226411 0.8422045 -0.5106082 -0.06418484 0.8574146 -0.5137529 -0.06271499 0.8556429 -0.03399133 -0.08561027 0.9957487 -0.04452663 -0.1727142 0.9839651 -0.0335626 -0.176425 0.9837418 -0.05912834 -0.2780752 0.9587378 -0.0631057 -0.2751851 0.9593179 0.03138798 -0.02984392 0.9990617 -0.2170717 0.03353166 0.9755796 0.07760667 -0.06482899 0.9948741 -0.3923327 -0.03164649 0.9192789 -0.5075246 -0.0122953 0.8615496 -0.6096752 -0.01116245 0.7925727 0.7132276 0.3825501 0.5873346 0.727326 0.3632513 0.5822762 0.7317162 0.3703528 0.5722153 0.6745454 0.5178453 0.5261415 0.7093209 0.3688363 0.6006861 0.7142026 0.3694459 0.5944951 0.7311109 0.3861661 0.5624523 0.7061796 0.3870024 0.5929078 0.73277 0.4008404 0.5498865 0.6953144 0.4065265 0.5926838 0.7427853 0.4013324 0.5359126 0.6976939 0.4093276 0.5879406 0.7351053 0.4243591 0.528715 0.6899424 0.4366881 0.5773067 0.8035258 0.4185654 0.4232605 0.6747036 0.5068184 0.5365727 0.6867032 0.5043572 0.5235098 0.677044 0.4749458 0.5621725 0.7303069 0.4652133 0.5002285 0.6614423 0.4712516 0.5834519 0.7085967 0.4646725 0.5310087 0.6898154 0.438205 0.5763083 0.7098875 0.4375715 0.5518976 0.69982 0.4130783 0.5827679 0.7108935 0.4143795 0.5682606 0.7068601 0.3914404 0.5891717 0.7159211 0.3941916 0.5762553 0.7064335 0.3784075 0.5981299 0.7214848 0.3859422 0.5748985 0.7071864 0.4954022 0.5044445 0.7334248 0.3658646 0.5729147 0.7711356 0.350875 0.5312597 0.7651506 0.4191248 0.4887526 0.7869727 0.4129071 0.458456 0.7911772 0.4117246 0.4522405 0.7313135 0.3815193 0.5653527 0.7241944 0.4115915 0.5532947 0.7602148 0.3549051 0.5441654 0.7876418 0.412231 0.4579148 0.8039952 0.3827387 0.4550854 0.7209854 0.4062994 0.5613384 0.7219876 0.4280402 0.5436136 0.7077305 0.4738284 0.5240269 0.6996676 0.4712988 0.5369756 0.7049469 0.4843152 0.5181589 0.9775246 -0.08121627 0.1945499 0.6765339 -0.6720323 -0.3011222 0.8142194 -0.5647336 -0.1346209 0.8517948 0.2442373 0.4634587 0.9603025 0.1343066 0.2445017 0.8398012 0.3364573 0.426064 0.8718311 0.3245289 0.3668676 0.8810942 0.2940422 0.3704218 0.9080615 0.2229012 0.3545975 0.865603 0.1674507 0.4719023 0.9589492 -0.2166795 0.1829383 0.948816 -0.144114 0.281033 0.9544865 -0.1469854 0.2595204 0.938928 -0.03384917 0.3424448 0.5964038 -0.7113671 -0.3718324 0.8105976 -0.4188367 -0.4092767 0.7231433 -0.4665249 -0.5093313 0.9911153 -0.07608175 -0.1090967 0.9705317 -0.1445139 -0.1928322 0.7995162 0.1123276 0.590048 0.85018 0.2450426 0.4659914 0.9367936 0.08059996 0.3404724 0.9538685 0.1583387 0.255076 0.947857 0.1956205 0.2515944 0.9968286 0.07932901 0.006307661 0.9928854 0.009958088 0.1186571 0.9930604 -0.004542648 0.1175181 0.977525 -0.08121591 0.1945481 0.9367938 0.08059912 0.3404719 0.9115906 0.01214581 0.4109199 0.9110867 0.03001976 0.4111203 0.7550188 -0.6211141 -0.2101519 0.7679798 -0.61592 -0.1756406 0.7965089 -0.5584614 -0.2317208 0.7965077 -0.5584629 -0.2317212 0.8232844 -0.4835424 -0.2973042 0.8232851 -0.4835419 -0.2973029 0.845701 -0.3728632 -0.381789 0.8891344 -0.3445138 -0.3012479 0.8820976 -0.2864838 -0.3739397 0.913986 -0.2804626 -0.2932075 0.6308 -0.7024068 -0.3297215 0.6602865 -0.6432002 -0.3877052 0.6602863 -0.6432009 -0.3877044 0.6883367 -0.5674872 -0.4518305 0.6883351 -0.5674886 -0.4518313 0.7131924 -0.4638134 -0.5255796 0.6499972 -0.5029071 -0.5697263 0.8610306 -0.5056633 -0.05413895 0.8612143 -0.5082336 -0.002961218 0.8934403 -0.4443948 -0.06540399 0.8934395 -0.4443966 -0.06540352 0.9193112 -0.3705403 -0.1325395 0.919311 -0.3705406 -0.1325403 0.9370492 -0.2801151 -0.2085053 0.9370507 -0.2801117 -0.2085033 0.9406592 -0.1659462 -0.2960106 0.9559355 -0.174532 -0.2360637 0.921661 -0.385644 0.0426594 0.9075428 -0.3998132 0.128513 0.9391472 -0.3366587 0.06828927 0.9419167 -0.3165061 0.1123241 0.9715978 -0.2341546 0.03419673 0.9715979 -0.2341543 0.0341975 0.9880716 -0.147027 -0.04580175 0.9880715 -0.1470268 -0.04580211 0.9911153 -0.07608288 -0.1090962 0.9995443 0.03011304 0.002120137 0.9973256 0.03346955 -0.06497418 -0.5581162 0 0.8297628 -0.6866167 0 0.7270196 -0.5811945 -0.003500521 0.8137572 -0.5578337 -1.589e-5 0.8299529 -0.2837717 1.99494e-5 0.958892 -0.2842324 0 0.9587555 -0.5860643 0.1397681 0.7981188 -0.2982516 0.03369277 0.9538925 -0.6538357 0.2920917 0.6979838 -0.5419897 0.4241486 0.7254965 -0.4599388 0.07220464 0.8850101 -0.5044283 0.1294383 0.8536967 -0.4907813 0.1028126 0.8651956 -0.6428905 0.4371867 0.6289354 -0.5705819 0.0317682 0.8206261 0.001210272 0 -0.9999994 0.001210272 0 -0.9999994 0.001210272 0 -0.9999994 0.001210331 0 -0.9999993 0.001210331 0 -0.9999994 0.001210212 0 -0.9999993 0.001210451 0 -0.9999994 0.00121051 2.08122e-7 -0.9999994 0.001210272 0 -0.9999994 0.001210391 0 -0.9999993 0.001210272 0 -0.9999993 0.001210212 -2.56796e-7 -0.9999993 0.001210331 0 -0.9999994 0.001210391 1.33818e-7 -0.9999994 0.001210272 0 -0.9999993 0.001210391 0 -0.9999993 0.001210153 -1.90723e-7 -0.9999994 -0.3040112 -0.3241667 0.8958199 -0.3378167 -0.1940509 0.9209908 -0.313411 -0.1471421 0.9381486 -0.3146443 0.003005683 0.9492049 -0.2708289 -0.5016889 0.8215595 -0.291647 -0.5531817 0.7803412 -0.2451788 -0.6601178 0.7100225 -0.1995338 -0.774929 0.599726 -0.2092605 -0.8290308 0.5185731 -0.1196542 -0.9145056 0.3864746 -0.09576302 -0.9672259 0.2351672 -0.09009677 -0.9798396 0.1783168 -0.03838872 -0.9931095 0.1107243 0.004113078 -0.9806365 0.1957933 0.004112601 -0.9806364 0.1957942 0.01169908 -0.8304451 0.5569776 0.01169896 -0.830449 0.556972 0.01747936 -0.5540447 0.8323034 0.01748448 -0.5540462 0.8323023 0.02059853 -0.1943455 0.9807169 0.02058947 -0.194343 0.9807175 -0.03065586 -0.9806361 0.1934244 -0.0306555 -0.9806365 0.1934224 -0.08720672 -0.8304471 0.5502297 -0.08720797 -0.8304479 0.5502283 -0.1303209 -0.5540463 0.8222221 -0.130309 -0.5540423 0.8222268 -0.1535449 -0.1943438 0.9688419 -0.153541 -0.194347 0.9688419 0.8850092 -0.192456 0.4239332 0.8411259 0.487982 0.2331973 0.8067404 0.5481256 0.2207447 0.9955898 -0.008798599 0.09340101 0.9826013 -0.1837285 0.02717691 0.5609876 0.7078301 0.4292663 0.728881 0.4374146 0.5266887 0.8274419 -0.1974435 0.5256958 0.3606185 0.7602662 0.5403236 0.3988003 -0.3637023 0.8418307 0.6959569 0.07829886 0.713802 -0.3814495 -0.002927005 0.9243851 -0.1646209 -0.05386471 0.9848851 -0.1701359 0.1620565 0.9720039 -0.06064063 -0.05105501 0.9968532 0.9178816 -0.3304085 0.2198269 0.9329106 -0.2685592 0.2399038 0.6906479 -0.3264493 0.6453189 0.7011271 -0.2582094 0.6646418 0.3949607 -0.2482939 0.884509 0.3555291 -0.02630537 0.934295 0.171774 -0.1640629 0.971379 0.01514357 -0.135783 0.9906229 -0.1961427 -0.08822011 0.9765989 -0.2027938 -0.1500765 0.9676527 0.2518969 -0.278059 0.9269472 0.231209 -0.3647629 0.9019371 0.6446858 -0.3859356 0.6598743 0.6037598 -0.4991422 0.6215555 0.8861321 -0.3964049 0.240069 0.8400437 -0.50458 0.1993134 -0.2432194 -0.1179018 0.9627791 -0.2563905 -0.1958029 0.9465332 0.1748326 -0.3658065 0.9141222 0.1380874 -0.4754771 0.8688231 0.5599659 -0.5066689 0.6555342 0.4883697 -0.648506 0.5838966 0.8149549 -0.5232431 0.2491291 0.7347325 -0.6565227 0.1707226 -0.248607 -0.3911307 0.8861215 -0.09115481 0.05921578 0.9940746 0.1209785 -0.583566 0.8030037 0.2453001 -0.26731 0.9318655 0.4383865 -0.7164403 0.5427067 0.5588418 -0.5084801 0.6550908 0.6550621 -0.7377611 0.1631016 0.6785369 -0.7130176 0.1766171 -0.04413133 -0.3335602 0.9416954 0.1354615 0.04430514 0.9897916 0.2655198 -0.5323761 0.8037878 0.4237149 -0.2466896 0.8715561 0.5075264 -0.6815388 0.527183 0.6570885 -0.4723781 0.5874468 0.6520699 -0.7413043 0.158974 0.7215152 -0.6696001 0.1762143 -0.9484008 -0.07573616 0.3078963 -0.9256238 -0.3652623 -0.09901666 -0.9558003 -0.2887665 0.05531519 -0.9999997 -7.78614e-4 -2.06059e-4 -0.9992424 -0.03284144 0.02088481 -0.999139 -0.04138469 -0.002930223 -0.9869362 -0.1468691 0.06623119 -0.9871213 -0.1597992 0.007477819 -0.9637814 -0.2572795 0.07023262 -0.969186 -0.2420953 0.04548108 -0.9651477 -0.2559919 0.05438774 -0.9642864 -0.1875938 0.1869767 -0.9999991 2.5974e-4 0.001372218 -0.9995046 -0.02552688 0.01841485 -0.9981297 0.005173683 0.06091368 -0.9899173 -0.08027166 0.1167054 -0.9746454 -0.01995855 0.2228638 -0.9613325 -0.08159494 0.2630252 -0.943876 -0.1075547 0.3122984 -0.9369379 -0.1280603 0.3251891 -0.9011955 0.006352245 0.4333664 -0.906032 -0.2962141 0.3022636 -0.8767499 -0.4324483 0.2104715 -0.886222 -0.0220462 0.462736 -0.822007 -0.558308 0.1122359 -0.7928705 -0.6061802 0.06246685 -0.3379512 -0.2585729 0.904947 -0.4243464 -0.2461047 0.8714142 -0.4489384 -0.2538275 0.8567531 -0.5601819 -0.2263242 0.7968524 -0.5934494 -0.2472079 0.7659675 -0.6719527 -0.2158985 0.7084261 -0.7074729 -0.2188863 0.6719902 -0.7746554 -0.1827844 0.6053916 -0.8062266 -0.2126355 0.5520732 -0.856742 -0.176133 0.4847374 -0.8814014 -0.1775298 0.4377383 -0.8843035 -0.1750019 0.4328761 -0.8966588 -0.171491 0.4081591 -0.7332792 -0.6731026 -0.09609735 -0.7064307 -0.7015756 -0.0935266 -0.7027304 -0.7114493 0.00314325 -0.6988815 -0.7151702 0.009819507 -0.6977634 -0.7163274 -0.001169204 -0.6516733 -0.754584 0.07697433 -0.6724388 -0.7401347 0.005160868 -0.5782797 -0.80449 0.1356041 -0.5931479 -0.8040739 0.04050779 -0.4747325 -0.8664814 0.1543989 -0.5098329 -0.8547984 0.09690314 -0.3762495 -0.904595 0.2003601 -0.4048399 -0.9037016 0.1393852 -0.251984 -0.942223 0.2207262 -0.2799532 -0.9407118 0.1915401 -0.1278855 -0.959673 0.2503462 -0.1417912 -0.9617199 0.2345 -0.8531672 -0.4723513 0.2213369 -0.8251109 -0.4967246 0.2691783 -0.826166 -0.4965242 0.2662959 -0.7542562 -0.5467681 0.3635137 -0.755428 -0.5479121 0.3593341 -0.6600908 -0.5994483 0.4527053 -0.6618527 -0.5993657 0.4502354 -0.5477504 -0.6426988 0.5356377 -0.5496441 -0.6436805 0.5325101 -0.4032714 -0.6808034 0.6114564 -0.4054706 -0.681285 0.6094624 -0.2419249 -0.7016635 0.6701797 -0.3759041 -0.7646928 0.5233939 -0.2500964 -0.1947461 0.9484334 -0.3508692 -0.2535371 0.9014487 -0.2819727 -0.4396168 0.852777 -0.2626326 -0.6050252 0.751644 -0.04249078 -0.1928843 0.9803012 -0.04248827 -0.1928915 0.9802998 -0.03892576 -0.4380994 0.8980834 -0.006299495 -0.5529066 0.8332195 -0.03450059 -0.6042327 0.7960607 -0.0265581 -0.7898609 0.6127108 0.0130949 -0.8305036 0.5568595 -0.07125037 -0.9657116 0.2496486 -0.008547067 -0.9803392 0.1971349 0.01184833 -0.03452676 0.9993336 -0.03423076 -0.01250207 0.9993358 0.09535443 -0.287657 0.9529748 -0.2774993 -0.07827162 0.9575322 -0.08746749 -0.5202286 0.8495362 -0.4345316 -0.1414795 0.8894751 0.001752555 -0.00159794 0.9999972 0.003927886 -0.01344084 0.999902 -0.003089845 -0.01278972 0.9999135 0.04114973 -0.1084259 0.9932525 -0.03250432 -0.09735035 0.9947193 0.02536034 -0.244207 0.9693915 -0.05102115 -0.1846032 0.9814879 0.001168549 -3.48059e-5 0.9999994 0.003905117 -0.007173418 0.9999668 0.02111023 0.001401484 0.9997762 0.04590857 -0.05200874 0.9975909 0.1704443 0.006911158 0.9853432 0.1973491 -0.06149363 0.9784028 0.3124996 -0.1066196 0.9439155 -0.004674077 -0.001561045 0.999988 0.2751442 -0.04996305 0.9601039 0.2273688 0.01180905 0.9737371 0.05102092 -0.1530359 0.9869027 -0.1499831 -0.1192431 0.9814714 -0.2105264 -0.0399183 0.9767729 -0.337336 -0.3127364 0.8879191 -0.544268 -0.1702218 0.8214603 -0.5983645 -0.08605891 0.7965888 -0.6413206 -0.4593867 0.6145502 -0.2304259 -0.6388198 0.734039 -0.6069995 -0.03307729 0.7940136 0.03323411 -0.4226081 0.905703 -0.1970261 -0.08604747 0.9766149 0.3347972 -0.1777884 0.9253661 0.253377 -0.06406426 0.9652439 -0.8173494 -0.09267812 0.5686394 -0.8075394 -0.116835 0.5781261 -0.7898891 -0.3080719 0.5302519 -0.7415108 -0.377677 0.5545465 -0.7021608 -0.5556356 0.4452407 -0.6025663 -0.6418955 0.4742195 -0.5869665 -0.6887502 0.4255511 -0.4706021 -0.8412944 0.266003 -0.4040265 -0.8005391 0.4426056 -0.3363347 -0.9117969 0.2355961 -0.2822618 -0.9377323 0.2024511 -0.2146823 -0.9763381 0.02599358 -0.05898106 -0.9859735 0.1561331 -0.003513574 -0.9999938 4.67505e-4 -0.001879036 -0.9999966 0.001869916 -0.04971092 -0.9895339 0.1354688 -0.1105051 -0.987383 0.1134173 -0.1674232 -0.9487193 0.2681437 -0.1878179 -0.9402953 0.2838469 -0.2380861 -0.8736873 0.4242469 -0.3018721 -0.8558927 0.4199059 -0.3799507 -0.6769491 0.6303789 -0.4229583 -0.6501764 0.6311712 -0.4770813 -0.4106863 0.7770009 -0.4991322 -0.389622 0.7739908 -0.5249601 -0.1297072 0.8411855 -0.5297431 -0.1225084 0.839264 2.70392e-4 -0.9999967 0.002572357 -0.05467736 -0.9860159 0.1574264 0.01204538 -0.9874554 0.1574387 -0.05266338 -0.9400442 0.3369623 -0.03209769 -0.9475338 0.3180403 -0.1040704 -0.853458 0.5106651 -0.04003441 -0.867528 0.4957746 -0.1347374 -0.6502341 0.7476908 -0.09323734 -0.6714147 0.7351933 -0.1587513 -0.3908028 0.9066815 -0.1376671 -0.407679 0.9026881 -0.1656543 -0.123077 0.9784737 -0.1610443 -0.1290367 0.9784755 0.002382218 -0.9999936 0.002689123 -0.07474088 -0.9724158 0.220956 0.1483035 -0.9764934 0.1564182 0.05896985 -0.9105263 0.4092241 0.1270394 -0.9332339 0.3360588 0.01545244 -0.7869783 0.6167871 0.2314074 -0.8310443 0.5057826 0.1077111 -0.5511385 0.8274326 0.2480561 -0.623583 0.7413586 0.1726384 -0.307993 0.9355942 0.2434492 -0.3696599 0.8967074 0.2179578 -0.09330558 0.9714878 0.2329993 -0.1157292 0.9655662 -0.07133233 -0.1945912 0.9782872 -0.2890373 -0.5521643 0.7820308 9.81981e-4 -0.9999949 0.003068327 0.06177192 -0.9805992 0.1860359 0.06228333 -0.9810991 0.1832088 0.1278758 -0.9121789 0.3893296 0.190023 -0.8294162 0.5253191 0.1809148 -0.7982839 0.5744674 0.2767361 -0.5529116 0.7859427 0.2782817 -0.5573986 0.7822188 0.298956 -0.3105757 0.9023126 0.3424862 -0.1933609 0.9194101 0.3215444 -0.09376859 0.9422402 -0.3210991 -0.1074141 0.9409345 -0.3422383 -0.1933683 0.9195007 -0.3281302 -0.2379754 0.9141653 -0.2871389 -0.3798387 0.87936 -0.188231 -0.8295219 0.5257971 -0.2201573 -0.719754 0.6583958 -0.2584123 -0.5984159 0.7583677 -9.81996e-4 -0.9999948 0.003068387 -0.05280244 -0.9858598 0.1590354 -0.07419788 -0.980275 0.1831821 -0.1122539 -0.9325206 0.3432265 -0.1731562 -0.8414633 0.5118169 0.02164095 -0.9805558 0.1950438 0.02164 -0.9805555 0.1950454 0.06152325 -0.8298938 0.5545189 0.06152343 -0.8298956 0.5545164 0.09185957 -0.5532228 0.8279531 0.0918554 -0.5532224 0.827954 0.1081755 -0.193939 0.9750312 0.1081743 -0.1939432 0.9750305 -0.1787494 -0.1949502 0.9643875 -0.1090239 -0.1501286 0.9826369 -0.09185528 -0.5532237 0.827953 -0.09185969 -0.5532218 0.8279538 -0.06152361 -0.8298946 0.5545178 -0.06152307 -0.8298949 0.5545174 -0.02164006 -0.9805554 0.1950458 -0.02164095 -0.9805555 0.195045 0.003515183 -0.9999937 5.84655e-4 0.07110798 -0.9789611 0.191256 0.2694834 -0.9305323 0.2479688 0.2771565 -0.9488136 0.1514502 0.3684681 -0.8292829 0.420144 0.452956 -0.868734 0.2003299 0.5448994 -0.7148064 0.4383336 0.5349147 -0.7808204 0.3227782 0.6048282 -0.5883527 0.5366788 0.6475815 -0.6654815 0.3711773 0.7225326 -0.3731259 0.5819998 0.7539224 -0.447547 0.4809396 0.7913587 -0.235171 0.5643103 0.7908485 -0.2919428 0.5378923 0.80338 -0.1058602 0.5859814 0.8136006 -0.1328614 0.5660405 0.09534043 -0.9906394 0.09769356 0.1537597 -0.9538324 0.2579959 0.1584275 -0.9601556 0.2302219 0.2219355 -0.8857722 0.4076181 0.2602124 -0.8992583 0.3516021 0.3215861 -0.7947382 0.5147561 0.3206471 -0.8164566 0.4801916 0.3722485 -0.6870134 0.6240543 0.3950946 -0.7119696 0.5805168 0.4595746 -0.4674975 0.7551406 0.4768046 -0.490558 0.7293903 0.5076199 -0.3064417 0.8052425 0.5085279 -0.3235806 0.7979318 0.5225088 -0.1397745 0.8410992 0.527893 -0.1478462 0.8363436 -2.70546e-4 -0.9999967 0.002573788 0.04062277 -0.992227 0.1176242 -0.01052081 -0.9906007 0.1363807 0.03912204 -0.9607861 0.2745172 0.03315514 -0.9546235 0.2959641 0.07960021 -0.903239 0.4216908 0.03868681 -0.8896359 0.4550292 0.08126682 -0.816323 0.5718501 0.08099019 -0.7968189 0.5987656 0.1163172 -0.7139748 0.6904422 0.09262597 -0.6909036 0.7169886 0.1470701 -0.4908699 0.85873 0.1297246 -0.4703158 0.8729116 0.1514684 -0.3224594 0.9343861 0.1503449 -0.3079138 0.9394603 0.1660724 -0.1474 0.9750351 0.1607856 -0.1405351 0.9769329 -0.002381622 -0.9999936 0.002688467 0.04512262 -0.9896705 0.1360754 -0.1286213 -0.9822408 0.1366006 -0.07308018 -0.9524053 0.2959451 -0.09561532 -0.9325324 0.348197 -0.05460244 -0.8882578 0.4560887 -0.1951545 -0.8409344 0.5047219 -0.1628829 -0.7843543 0.5985463 -0.1640402 -0.7190292 0.6753428 -0.1460848 -0.679543 0.718944 -0.2238831 -0.5983334 0.7693331 -0.1832351 -0.4545226 0.8716846 -0.2382503 -0.3793209 0.8940651 -0.2268339 -0.2913965 0.9293195 -0.2294018 -0.2373076 0.9439597 -0.2164487 -0.1329852 0.9671944 -0.2332337 -0.1070445 0.966511 0.1859423 -0.9823223 0.02164298 0.0489732 -0.989502 0.1359691 0.001876413 -0.9999965 0.001869142 -0.1164187 -0.9493832 -0.2917506 -0.09880465 -0.2590437 -0.9607987 -0.1974818 -0.4076318 -0.8915365 -0.0308268 -0.09379744 -0.995114 0.05557769 -0.1715762 -0.983602 -0.01275563 -0.3197631 -0.9474118 0.003047108 -0.03033572 -0.9995352 0.001307785 -0.01252746 -0.9999207 0.001196742 -0.00181967 -0.9999977 0.01804101 -0.08454763 -0.9962561 0.01239711 -0.06989175 -0.9974775 0.00658375 -0.04947811 -0.9987536 -0.01507693 -0.6153154 -0.7881368 -0.01688826 -0.8414826 -0.5400202 -0.007058024 -0.9770944 -0.2126893 -0.006361365 -0.9737327 -0.2276056 -0.001480758 -0.9673401 -0.2534781 0.007038235 -0.9602165 -0.2791682 0.0146051 -0.9554085 -0.294926 0.1209197 -0.2607296 -0.9578093 -0.255338 -0.688034 -0.679273 -0.2396075 -0.6480804 -0.722897 -0.1515451 -0.650168 -0.7445238 -0.1572526 -0.6251024 -0.7645382 -0.1812777 -0.4917536 -0.8516553 0.6453829 -0.492188 -0.5841506 0.3179662 -0.5447545 -0.7759768 -0.2615621 -0.8564826 -0.4449977 -0.2706293 -0.8430533 -0.4647807 -0.2615351 -0.8605057 -0.4371838 -0.2602591 -0.8419056 -0.4727157 -0.2458693 -0.7815768 -0.5733115 -0.2805314 -0.8507945 -0.4443545 -0.280228 -0.8505309 -0.4450499 -0.231915 -0.7596564 -0.607567 -0.2989127 -0.8114041 -0.5022694 -0.1898733 -0.8429759 -0.5033286 -0.2442026 -0.8418754 -0.48126 -0.3759429 -0.6699417 -0.6401914 -0.31537 -0.7389446 -0.5954013 -0.2924521 -0.7660275 -0.5724278 -0.2768091 -0.7855095 -0.5534905 -0.2660582 -0.8001092 -0.5376229 -0.2342237 -0.8458157 -0.4793068 -0.3742651 -0.8081897 -0.4547032 -0.2869798 -0.8349927 -0.4694996 -0.3410409 -0.3903677 -0.8551632 -0.1914901 -0.5566018 -0.8084096 -0.1767125 -0.6438789 -0.7444412 -0.05805933 -0.9378644 -0.3421105 -0.03249335 -0.939158 -0.3419451 -0.04285073 -0.929698 -0.3658218 -0.01009905 -0.9306086 -0.3658766 -0.01790738 -0.9290441 -0.3695357 0.05306434 -0.9280301 -0.3687063 0.02362114 -0.9201005 -0.3909695 -0.08099311 -0.9403867 -0.3303225 -0.09274154 -0.9457603 -0.3113464 -0.1335389 -0.9408632 -0.3113579 0.05345189 -0.1698989 -0.9840109 -0.001545429 -0.1694858 -0.9855315 -4.55935e-4 -0.1700596 -0.9854338 -0.005889058 -0.1699481 -0.9854355 -0.004452586 -0.173642 -0.9847988 -0.01442641 -0.1729945 -0.9848172 -0.01260071 -0.1778219 -0.9839821 -0.0224933 -0.1766649 -0.984014 -0.02031666 -0.1799107 -0.9834732 -0.03084081 -0.1783192 -0.9834893 -0.02905201 -0.1832742 -0.9826325 -0.04187023 -0.1806011 -0.9826648 -0.04049116 -0.1850372 -0.981897 -0.04798966 -0.1830352 -0.9819344 -0.3364856 -0.0850259 -0.9378423 -0.0747894 -0.5389003 -0.8390431 -0.1199458 -0.5279188 -0.8407824 -0.1244826 -0.5163745 -0.8472672 -0.08772444 -0.5240192 -0.8471768 -0.09338551 -0.5111111 -0.8544265 -0.06283318 -0.5157571 -0.8544277 -0.06952697 -0.5072242 -0.8590051 -0.04054027 -0.5105705 -0.8588798 -0.04609626 -0.497928 -0.8659924 -0.01660037 -0.4998457 -0.8659554 -0.02091413 -0.4901216 -0.8714031 -0.004646658 -0.4904828 -0.8714386 -0.007938146 -0.4889608 -0.8722697 0.05313575 -0.4888784 -0.8707322 0.03166592 -0.4741642 -0.8798668 -0.2207835 -0.7847495 -0.5791572 -0.1814937 -0.7949544 -0.5788849 -0.190256 -0.7807789 -0.5951362 -0.1336128 -0.7925317 -0.5950137 -0.143993 -0.7766475 -0.6132575 -0.09641957 -0.7839551 -0.6132845 -0.1080835 -0.7732276 -0.6248497 -0.06280583 -0.7783682 -0.6246588 -0.07242596 -0.7626789 -0.6427096 -0.02638936 -0.7656894 -0.642669 -0.03367221 -0.7535223 -0.6565595 -0.008030414 -0.7541672 -0.6566335 -0.01356822 -0.7522351 -0.6587551 0.05295872 -0.7516361 -0.6574487 0.02743542 -0.7387595 -0.6734106 -0.1458114 -0.9452731 -0.2918866 -0.179031 -0.9477405 -0.2640753 -0.1749991 -0.9492989 -0.2611647 -0.230398 -0.9374012 -0.2611435 -0.2160686 -0.9479303 -0.2339714 -0.2683158 -0.9344401 -0.2341551 -0.2552629 -0.9404792 -0.2243656 -0.301868 -0.9265715 -0.224368 -0.2938343 -0.9329565 -0.207975 -0.3403827 -0.916976 -0.208074 -0.3382038 -0.9188575 -0.2032712 -0.3467471 -0.9156612 -0.2033002 -0.3513354 -0.9113398 -0.2145305 -0.3071703 -0.9271883 -0.2144023 -0.3193175 -0.9177923 -0.2359954 -0.2679603 -0.934054 -0.2360945 -0.2387238 -0.9350976 -0.2619228 -0.2306097 -0.9379636 -0.2589278 -0.1655808 -0.9516631 -0.2586897 -0.185436 -0.9432138 -0.2756109 0.03211855 -0.214388 -0.9762204 -0.06589382 -0.1813096 -0.981216 -0.06578111 -0.182074 -0.981082 -0.06803238 -0.181206 -0.9810892 -0.06822979 -0.1794319 -0.9814016 -0.06060665 -0.182228 -0.9813867 -0.06160259 -0.1787117 -0.9819712 -0.04719841 -0.1830762 -0.9819651 -0.04921293 -0.1792729 -0.9825678 -0.03256016 -0.1829426 -0.9825842 -0.03538906 -0.1800482 -0.983021 -0.01656448 -0.1827962 -0.9830113 -0.01950079 -0.1800847 -0.9834578 0.003627181 -0.1810984 -0.9834583 0.001247465 -0.1794936 -0.9837583 0.02263027 -0.1778838 -0.9837913 0.02149331 -0.1775346 -0.9838798 0.0416249 -0.1741508 -0.9838389 0.04219222 -0.1743119 -0.9837862 0.06406557 -0.1677286 -0.9837493 0.0666027 -0.1680979 -0.9835178 0.0826863 -0.1608166 -0.9835146 0.08617353 -0.1603972 -0.9832837 0.1002115 -0.152492 -0.983211 0.104516 -0.1522305 -0.9828034 0.1188869 -0.1415959 -0.9827597 0.1231971 -0.1408511 -0.9823357 -0.1851092 -0.5205817 -0.8335043 -0.1954353 -0.5166519 -0.8335921 -0.1962839 -0.511968 -0.8362784 -0.1731216 -0.5204184 -0.836178 -0.1764765 -0.5109883 -0.841277 -0.134188 -0.5237884 -0.8412131 -0.1403753 -0.5134755 -0.8465445 -0.09214341 -0.5241678 -0.8466154 -0.1004207 -0.5162468 -0.8505321 -0.04639786 -0.5240868 -0.8504002 -0.05484211 -0.5166056 -0.8544655 0.0106858 -0.5194817 -0.8544149 0.003974854 -0.5149797 -0.8571932 0.06381082 -0.5106286 -0.8574302 0.06066089 -0.5096214 -0.8582578 0.1167917 -0.5001128 -0.8580483 0.1182857 -0.5005731 -0.8575751 0.1794379 -0.4821727 -0.8575032 0.1862769 -0.4833768 -0.8553642 0.2318825 -0.4628796 -0.8555543 0.2413082 -0.4619367 -0.8534547 0.2815433 -0.4391494 -0.8531597 0.293273 -0.4386937 -0.8494344 0.3349341 -0.4078834 -0.8493824 0.3467431 -0.4059711 -0.8455511 -0.2669603 -0.7840822 -0.5603103 -0.2932845 -0.7743859 -0.5606341 -0.2954987 -0.7686092 -0.5673804 -0.2596701 -0.7815641 -0.5672116 -0.266533 -0.7697107 -0.5800912 -0.2016074 -0.7893014 -0.5799636 -0.2127082 -0.7762155 -0.5935022 -0.138832 -0.7927041 -0.5935875 -0.1525388 -0.7825784 -0.6035752 -0.06992787 -0.7944252 -0.6033231 -0.08349603 -0.7850728 -0.6137502 0.01625853 -0.789424 -0.613633 0.005889117 -0.7839443 -0.6208034 0.09668558 -0.777677 -0.6211848 0.09195721 -0.7765366 -0.6233258 0.1771296 -0.761923 -0.6229757 0.1792461 -0.7623975 -0.6217885 0.2721521 -0.7344595 -0.6216931 0.2818463 -0.7354139 -0.6162217 0.3514658 -0.7044917 -0.6165738 0.3649124 -0.7023261 -0.6112095 0.4261165 -0.6673743 -0.6107671 0.4425213 -0.6653459 -0.6012402 0.5058984 -0.6185518 -0.6012158 0.5223594 -0.6142665 -0.5914537 -0.1306505 -0.9522799 -0.2758505 -0.08370572 -0.9519847 -0.2944802 -0.08181107 -0.9524661 -0.2934541 0.02009701 -0.9558957 -0.2930181 0.006172776 -0.9522269 -0.3053293 0.1173022 -0.9449215 -0.3055546 0.1111539 -0.9444648 -0.3092426 0.2148122 -0.9265056 -0.308939 0.2173933 -0.9265653 -0.3069478 0.3298044 -0.8927961 -0.3068296 0.3414124 -0.891584 -0.2975161 0.425089 -0.8547853 -0.2977275 0.4413518 -0.8496598 -0.2885946 0.5141389 -0.8078157 -0.2882623 0.532887 -0.8012493 -0.2720865 0.6080409 -0.7458435 -0.2720364 0.6264246 -0.7364105 -0.2555226 -0.8982406 0.3089555 -0.3125866 -0.999826 0.01280641 -0.01356309 -0.99996 -0.002630114 0.00855416 -0.9999993 0.001251518 0 -0.9999719 -0.006362915 0.0039649 -0.9999939 -0.003474414 4.5297e-4 -0.9998546 0.009800076 -0.01395797 -0.9998256 -0.004451453 -0.01813852 -0.9868623 -0.01189595 -0.1611255 -0.8304349 -0.4206063 -0.3653332 -0.3654364 -0.1607699 -0.9168475 -0.4672143 0.1666212 -0.8683019 -0.5071823 0.4173475 -0.7540472 -0.6536684 -0.4314262 -0.6217631 -0.6226043 0.6045095 -0.4969227 -0.01640981 -0.08457082 -0.9962824 -0.1524556 0.2350817 -0.9599447 -0.006608426 -0.001633226 -0.9999769 -0.007223427 -0.01232933 -0.9998979 -0.04627627 -0.03241568 -0.9984026 -0.04610592 -0.02925837 -0.9985081 -0.09048837 -0.1528089 -0.9841044 -0.08610808 -0.0477184 -0.9951425 -0.1380866 -0.2772257 -0.9508302 -0.1348796 -0.06793814 -0.9885302 -0.1790935 -0.4178663 -0.8906815 -0.1466042 0.5602076 -0.815276 -0.294848 0.084472 -0.9518031 -0.3891897 0.6449419 -0.6577091 -0.5085124 -0.4187361 -0.7523797 -0.381945 0.1523636 -0.9115391 -0.3945297 -0.2265598 -0.8905151 -0.2508564 0.06423491 -0.9658908 -0.2573873 -0.05459451 -0.9647648 -0.1379488 -0.003678321 -0.9904326 -0.1271188 0.1574626 -0.9793091 -0.02756857 -0.09223675 -0.9953555 -0.01993805 0.04148852 -0.9989401 -0.5928751 0.6528533 -0.4714676 -0.8092727 -0.1948972 -0.5541596 -0.6214665 0.07162094 -0.7801602 -0.6214021 0.07230323 -0.7801486 -0.421323 -0.0854988 -0.9028716 -0.3919217 0.2472484 -0.8861522 -0.2363256 -0.1887096 -0.9531732 -0.1729742 0.4874673 -0.8558363 -0.05623042 -0.3569619 -0.932425 -0.03059661 0.1264726 -0.9914981 -0.6923375 0.688124 -0.2171503 -0.9281159 0.2850149 -0.2395152 -0.7977787 -0.2451412 -0.5508675 -0.6716544 0.5239582 -0.5237826 -0.5336412 -0.43696 -0.7240808 -0.4194576 0.6107418 -0.6716024 -0.3031296 -0.5110582 -0.8043209 -0.1660289 0.7580047 -0.6307641 -0.07855123 -0.6615151 -0.7458067 -0.03801983 0.2481268 -0.9679812 -0.9524126 -0.07540142 -0.2953386 -0.01557743 -0.1716729 -0.9850309 -0.1566975 -0.1873346 -0.9697173 -0.296033 -0.1800042 -0.9380634 -0.5687736 -0.2331119 -0.7887684 -0.478197 -0.1650189 -0.8626102 -0.3656191 -0.1554046 -0.9176994 -0.870661 -0.2914594 -0.3962334 -0.8097235 -0.1611086 -0.5642623 -0.7056905 -0.08658641 -0.7032096 -0.9998281 -0.003260314 -0.01825398 -0.9844491 -0.08419787 -0.1541774 -0.1947149 -0.2274026 -0.9541353 -0.1943117 -0.3133324 -0.9295514 -0.1947103 -0.3139962 -0.929244 -0.1942477 -0.46495 -0.8637647 -0.194812 -0.4655349 -0.8633224 -0.1952784 -0.6032483 -0.7732775 -0.1956633 -0.6037555 -0.7727842 -0.1951993 -0.7245355 -0.6610186 -0.1957118 -0.7249033 -0.6604636 -0.1961801 -0.8250839 -0.5298586 -0.1965056 -0.8253481 -0.5293262 -0.1960373 -0.9023713 -0.383791 -0.19644 -0.9024973 -0.3832885 -0.4422226 -0.8254299 -0.3508628 -0.5553603 -0.2162502 -0.8030011 -0.5544483 -0.2658532 -0.7886123 -0.5546903 -0.2663437 -0.7882765 -0.5537416 -0.3946982 -0.733201 -0.5540807 -0.3950912 -0.732733 -0.5550345 -0.511665 -0.6558474 -0.5552664 -0.512006 -0.6553847 -0.5543164 -0.6148779 -0.5609444 -0.5546291 -0.6150714 -0.5604229 -0.5555804 -0.69963 -0.4492753 -0.5557783 -0.6997705 -0.4488117 -0.556546 -0.739777 -0.3781358 -0.6081087 -0.7306637 -0.310378 -0.8221179 0.004984021 -0.5692954 -0.8307751 -0.1777774 -0.5274544 -0.8308675 -0.1781193 -0.5271933 -0.8302322 -0.2641866 -0.4908359 -0.8303698 -0.2644522 -0.49046 -0.8310086 -0.3421362 -0.4385975 -0.8311025 -0.342368 -0.4382383 -0.8304656 -0.4115247 -0.3754655 -0.8305886 -0.411641 -0.3750658 -0.8312277 -0.4677695 -0.3004204 -0.8313062 -0.4678542 -0.3000708 -0.8306711 -0.5123434 -0.2179214 -0.7798725 -0.5138348 -0.3574532 -0.976741 -0.1368588 -0.1650663 -0.9806876 -0.06238663 -0.1853637 -0.9806968 -0.06253832 -0.1852644 -0.9806063 -0.09282243 -0.1726133 -0.9806196 -0.09293383 -0.1724779 -0.9807145 -0.1201556 -0.1541488 -0.9807241 -0.1202469 -0.1540159 -0.9806332 -0.1446347 -0.1320585 -0.9806449 -0.1446937 -0.1319074 -0.9807398 -0.1643096 -0.1056017 -0.9807484 -0.1643463 -0.1054657 -0.9661998 -0.2509967 0.05880987 -0.9657216 -0.2389025 -0.1015258 -0.9220495 -0.3870551 -0.003615975 -0.4608733 -0.855971 -0.2343276 -0.612043 -0.7893695 -0.04795151 -0.7966203 -0.6033905 -0.03627872 -0.8697597 -0.4817931 -0.1067404 -0.9975097 -0.06883823 -0.01535236 -0.2011927 -0.9560752 -0.2131709 -0.1949402 -0.9763424 -0.09356302 -0.1948258 -0.9763398 -0.09382653 -0.1946319 -0.9689751 -0.1523344 -0.1972025 -0.968756 -0.1504095 -0.1636829 -0.9110983 0.3782961 -0.03455525 -0.9772914 -0.2090636 -0.5305554 -0.8165574 0.2274757 -0.5549468 -0.8281022 -0.07925176 -0.5553789 -0.827911 -0.07821691 -0.554998 -0.8218008 -0.1289217 -0.5564366 -0.8210454 -0.1275261 -0.5196112 -0.8327182 0.1912714 -0.2249543 -0.7586189 -0.611468 -0.8310747 -0.5523512 -0.06498652 -0.8312107 -0.5534358 -0.05289465 -0.8313817 -0.5532398 -0.05225217 -0.831133 -0.5493912 -0.08594977 -0.831656 -0.54873 -0.08510959 -0.7880124 -0.5806244 0.2047241 -0.5780187 -0.5953812 -0.5580465 -0.9913316 -0.1313781 -0.00126475 -0.9915072 -0.1299299 -0.005628585 -0.980531 -0.1927658 -0.03742229 -0.9807547 -0.1943663 -0.01849579 -0.9807734 -0.1942928 -0.01827478 -0.9807404 -0.192997 -0.03000855 -0.9807932 -0.1927703 -0.02973902 -0.9442066 -0.2396969 0.2258747 -0.964707 -0.2571668 -0.05661952 -0.189677 0.1217514 0.9742686 -0.1473119 0.829582 0.5386028 -0.1524342 0.1005223 0.9831882 -0.1629503 0.1273466 0.9783813 -0.2120034 0.1577849 0.9644473 -0.1901935 0.1659209 0.9676243 -0.2926227 0.3143529 0.9030804 -0.2903259 0.313312 0.9041828 -0.3674096 0.40491 0.8372923 -0.4873403 0.4532485 0.7463681 -0.2064568 -0.01554483 0.9783322 -0.1590553 0 0.9872697 -0.141439 0.03143393 0.9894479 -0.1401178 0.02694082 0.9897683 -0.2322875 -0.01928126 0.9724561 -0.3207586 0.01566088 0.9470315 -0.4023575 -0.03791451 0.9146972 0.08876359 -0.6585299 0.7473015 0.1225368 -0.5369013 0.8346986 0.01824885 -0.1832309 0.9829006 0.153676 -0.53715 0.8293694 0.3093983 -0.6207967 0.7203361 0.2537645 -0.5839158 0.771133 0.1321741 -0.4096601 0.9026122 0.153614 -0.3900107 0.9079067 0.1323376 -0.3625043 0.9225386 0.164676 -0.331994 0.9287959 0.1251704 -0.2864983 0.949869 0.029082 -0.1957484 0.9802228 -0.006093859 -0.2288447 0.9734439 -2.87708e-4 -0.2365672 0.9716151 -0.05621701 -0.287338 0.9561781 -0.03978258 -0.3067799 0.9509488 -0.3204206 -0.1509994 0.935163 -0.2381335 -0.0830174 0.967678 -0.2088708 -0.1210575 0.9704217 -0.1544436 -0.07127112 0.9854277 -0.1439426 -0.08576869 0.9858623 -0.1082177 -0.05226778 0.9927523 -0.0885412 -0.0752002 0.9932299 -0.3641377 -0.1000792 0.9259524 -0.1371257 -0.3871386 0.9117677 -0.1084221 -0.4145731 0.9035341 0.06383746 -0.5838916 0.809318 0.2697505 -0.7171868 0.6425557 -0.1629489 -0.4549989 0.8754563 0.0633018 -0.6771711 0.7330977 0.07131397 -0.6756732 0.7337439 -0.9298208 -0.3236547 0.1751595 -0.742907 -0.3803216 -0.5508581 -0.9156206 -0.3361501 -0.2205494 -0.7574754 -0.2990383 -0.5803509 -0.7791498 -0.2070342 -0.5916608 -0.7497435 -0.1135685 -0.6519103 -0.9244129 -0.1420132 -0.3539678 -0.965839 -0.05537176 -0.2531582 -0.9139157 -0.342383 -0.2180188 -0.9595282 -0.2442328 0.1401997 -0.9600885 -0.1057049 0.2589527 -0.991178 -0.02587634 0.1299871 -0.9954565 -0.08924096 0.03320384 -0.982859 -0.1252819 -0.1352506 -0.6466326 0.6350399 0.4225998 -0.7491677 0.5233409 0.4060322 -0.7755948 0.4576009 0.4348037 -0.8588077 -0.4147251 0.3007532 -0.9131037 -0.03904539 0.4058536 -0.9156239 0.06266373 0.3971226 -0.8762149 0.198661 0.4390688 -0.8333365 0.3264393 0.4460804 -0.6015607 -0.7900388 0.1181678 -0.9173411 -0.3969298 0.03053194 -0.8507677 -0.4307131 0.3011325 -0.7309485 -0.6542435 0.1941128 -0.5745922 -0.814698 0.07817423 -0.7294796 0.5157729 0.4492636 -0.7248597 0.5213763 0.4502724 -0.8907654 0.05266821 0.4514015 -0.885297 0.07238823 0.4593575 -0.8381851 -0.4228677 0.3444254 -0.8439245 -0.3931508 0.3649985 -0.5847201 -0.7965621 0.1535944 -0.424149 -0.8841787 0.1957697 -0.5850983 -0.7758706 0.2359765 -0.6100312 -0.7694772 0.1891216 -0.7854749 -0.2095774 0.5823286 -0.7699002 -0.311775 0.5568215 -0.7948029 0.186042 0.5776478 -0.8064283 0.1231179 0.5783731 -0.6787006 0.553027 0.4832461 -0.6892144 0.5350999 0.48852 -0.7149628 0.5186612 0.4688485 -0.7036802 0.5359258 0.4664952 -0.8579103 0.06510251 0.5096583 -0.8465486 0.1253802 0.5173347 -0.8061922 -0.4024139 0.4337247 -0.8266979 -0.3086604 0.4704249 -0.6566787 -0.6823486 0.3212066 -0.5874518 -0.6868412 0.4279599 -0.6523586 -0.5719855 0.4972533 -0.8587692 -0.4737599 -0.195108 -0.7199178 -0.4371662 -0.5390771 -0.3426156 -0.9377568 0.05680495 -0.2312287 -0.9728932 -0.003465056 -0.3012098 -0.9533292 -0.02088385 -0.3056017 -0.9461271 -0.1070097 -0.4605908 -0.8752747 -0.1474802 -0.4707654 -0.8297765 -0.2997517 -0.5452937 -0.7823225 -0.3010421 -0.6294298 -0.7051782 -0.3264077 -0.6357624 -0.6373214 -0.4354627 -0.704724 -0.5380837 -0.4624177 -0.725104 -0.4289134 -0.5387555 -0.8577594 -0.4772645 -0.1909644 -0.7227098 -0.6764111 -0.1419814 -0.7244976 -0.6750209 -0.1394634 -0.5179767 -0.8519365 -0.07684111 -0.5184238 -0.8517347 -0.07605803 -0.3172101 -0.9480757 -0.02302825 -0.482424 -0.8756977 0.02051013 -0.5840994 -0.7925789 0.1750622 -0.6283876 -0.7710151 0.1032708 -0.7728622 -0.6320233 0.05683863 -0.7567428 -0.634461 0.1574794 -0.909375 -0.4027932 0.1038979 -0.8812373 -0.4402668 0.1720057 -0.1790164 -0.9835685 0.02337229 -0.1616603 -0.9858616 0.04407799 -0.0946123 -0.9945853 0.04299795 -0.0162577 -0.9985136 0.05202311 0.02977544 -0.997678 0.0612545 -0.3522381 -0.9354255 -0.03012508 -0.2768626 -0.9608738 -0.008285343 -0.3882414 -0.9199938 -0.05366623 -0.3919034 -0.9192219 -0.03798472 -0.5527069 -0.8315331 -0.05538904 -0.4933002 -0.8682703 -0.05255299 -0.6300139 -0.7717984 -0.08608031 -0.6908563 -0.7136119 -0.1160846 -0.749516 -0.6505332 -0.1226068 -0.7968621 -0.5887574 -0.1355565 -0.3412353 -0.939885 -0.01321339 -0.4096543 -0.9112136 -0.04328048 -0.409075 -0.9113438 -0.04593861 -0.6929925 -0.71307 -0.1062667 -0.7097954 -0.6952477 -0.113231 -0.2810307 -0.9596612 -0.00850743 -0.06352025 -0.997752 0.02135974 -0.08886384 -0.9951884 0.04127317 -0.08621203 -0.9958806 0.02809906 -0.07659602 -0.9966437 0.02888798 -0.08027869 -0.995706 0.04609704 -0.01433366 -0.9991586 0.03842961 -0.8034641 -0.5792338 -0.1375995 -0.8034659 -0.5792278 -0.1376147 -0.8034648 -0.5792294 -0.137615 -0.803467 -0.5792263 -0.1376149 -0.8028845 -0.5800402 -0.1375861 -0.8034617 -0.5792331 -0.1376172 0.9925565 0 -0.1217851 0.9931034 0.001379966 -0.1172339 0.9781066 -3.38005e-4 -0.2081043 0.9673226 -0.003791391 -0.2535207 0.9645652 -0.001560747 -0.2638402 0.4631775 -0.007921576 -0.8862302 0.5113561 0.006636798 -0.8593434 0.5813516 -0.006806671 -0.813624 0.621989 0.005993187 -0.7830031 0.6883406 -0.006131291 -0.7253618 0.6951601 -0.003811657 -0.7188448 0.7820817 0.007416784 -0.6231319 0.7600227 -0.008566915 -0.6498401 0.860768 0.009150385 -0.5089152 0.8415664 -0.007455468 -0.5401023 0.9229195 0.007439196 -0.3849214 0.8911535 -0.02327138 -0.4531047 0.9278876 0.001926541 -0.3728553 0.3360931 -0.007419586 -0.9417997 0.362783 0.005672693 -0.9318564 0.4421405 -0.003176152 -0.8969402 0.1732514 -0.03083914 -0.9843947 0.1765424 -0.02837324 -0.9838841 0.2281488 0.008265852 -0.9735913 0.2025483 0 -0.9792724 0.1949703 -0.008199036 -0.9807749 0.1829521 -0.02138155 -0.9828893 0.1751785 -0.02904462 -0.9841083 0.993093 -0.06037735 -0.1006032 0.8582342 0.3414979 -0.3831623 0.9710811 0.04098451 -0.2352058 0.7468967 -0.07983922 -0.6601296 0.7454163 -0.08489197 -0.6611717 0.8794741 -0.07614523 -0.4698165 0.9614017 -0.03303629 -0.2731584 0.9989386 -0.04497665 0.009941101 0.991235 -0.05452394 -0.1203345 0.9854853 -0.0065068 -0.1696364 0.9702435 -0.131779 -0.2031301 -0.9770382 -0.1497778 0.1515361 -0.9753106 -0.1952298 0.103221 -0.8141953 -0.5469883 0.1946532 -0.7088481 -0.5567675 0.433064 -0.09970694 -0.9777353 0.1846411 -0.5904157 -0.8024791 0.08623552 -0.3520832 -0.8684573 0.3490263 -0.6605935 -0.7044144 0.2596471 -0.8784907 -0.1930583 0.4370157 -0.8581451 -0.1505572 0.4908357 -0.8170337 -0.4467141 0.3645582 -0.9045731 -0.4245967 -0.03827762 -0.6921144 -0.7037245 0.1604667 -0.5538784 -0.8323028 -0.02215486 -0.4317789 -0.891199 0.1390371 -0.1915154 -0.9759556 -0.1040801 -0.8017122 -0.1240472 0.5846965 -0.7156766 -0.4049686 0.5690408 -0.5561367 -0.6715602 0.489611 -0.5352811 -0.695495 0.4793338 -0.5627118 -0.6588523 0.4992685 -0.5762706 -0.6477008 0.4983933 -0.6072807 -0.6108109 0.5080554 -0.6488512 -0.5613903 0.5136468 -0.6803485 -0.5036422 0.5324195 -0.2034274 -0.939441 0.2758041 -0.2582906 -0.9122954 0.3178101 -0.3376531 -0.8698257 0.3597133 -0.4125998 -0.8278741 0.3799816 -0.4860171 -0.7870652 0.3798893 -0.4160324 -0.8189758 0.3952163 0.06796675 -0.9932607 0.0938822 0.02294999 -0.9915893 0.1273743 -0.06138944 -0.9823323 0.1767896 -0.7982055 -0.2893419 0.528346 -0.7953759 -0.1898043 0.5756314 -0.7908872 -0.1889243 0.5820696 -0.7910028 -0.1877496 0.5822926 -0.7950877 -0.1883232 0.5765156 -0.7949243 -0.1908943 0.5758948 -0.7992134 -0.1911968 0.569826 -0.7992494 -0.195985 0.5681465 -0.6661453 -0.5415046 0.5128579 -0.6555008 -0.5395504 0.5283977 -0.6568369 -0.5365184 0.5298238 -0.6680762 -0.5380952 0.5139337 -0.6653631 -0.544721 0.5104616 -0.6770797 -0.5455506 0.4939005 -0.6728433 -0.5578195 0.4859212 -0.4132987 -0.8189311 0.3981662 -0.4083632 -0.8179509 0.405211 -0.4147117 -0.8102718 0.4140941 -0.4256695 -0.8123871 0.3985382 -0.4291306 -0.8088608 0.401984 -0.4459336 -0.8112244 0.3782305 -0.4386054 -0.8188557 0.3702713 -0.4558995 -0.8200929 0.3458368 -0.4432887 -0.8339139 0.3287593 -0.1421204 -0.9671653 0.210697 -0.1181172 -0.9716776 0.2046732 -0.1057691 -0.9692481 0.2221962 -0.1207938 -0.9673949 0.222612 -0.1226245 -0.9658826 0.22811 -0.1345534 -0.968137 0.2112019 -0.1403108 -0.9660304 0.2170211 -0.1602613 -0.968847 0.1888173 -0.1478816 -0.9732589 0.1757791 -0.1679028 -0.9747092 0.1474813 -0.1460113 -0.9818962 0.1206678 -0.5485747 -0.3854565 0.7419496 -0.5360739 -0.3876685 0.7498919 -0.105337 -0.2793033 0.9544076 -0.09641414 -0.279224 0.9553734 0.3656884 -0.1015546 0.9251804 0.3683868 -0.1013011 0.9241371 -0.5882878 -0.2740429 0.760801 -0.5807423 -0.277804 0.7652212 -0.1335658 -0.1989541 0.9708643 -0.1280524 -0.2006913 0.9712496 0.3557379 -0.07227373 0.9317871 0.3574568 -0.07276052 0.931091 -0.6354235 -0.1169734 0.7632525 -0.616231 -0.120854 0.7782376 -0.1707061 -0.08591341 0.9815693 -0.1561769 -0.08757382 0.9838392 0.3425635 -0.03120642 0.9389764 0.3471817 -0.03166019 0.9372634 -0.3539962 -0.07967442 0.931847 -0.5091106 -0.4527142 0.7320221 -0.5238094 -0.4452666 0.7261966 -0.09465086 -0.2832443 0.9543657 -0.1443929 -0.2599291 0.9547709 0.346756 -0.05444407 0.936374 0.1315205 0.2459421 0.9603202 0.1745285 0.1181433 0.9775388 0.2587172 -0.001878798 0.9659513 -0.3873831 -0.08611041 0.9178887 -0.530162 -0.007580876 0.8478625 -0.5425166 -0.01442205 0.8399214 -0.6271325 -0.5182322 0.5814983 -0.684409 -0.4437411 0.5785139 -0.6069491 -0.465116 0.6444222 -0.5903704 -0.4501869 0.6699213 -0.5731013 -0.4597513 0.6783685 -0.5446169 -0.4517011 0.7066531 -0.6933874 -0.2844264 0.662054 -0.7097916 -0.09657102 0.6977607 -0.752869 0.03996586 0.656956 -0.6907976 0.1568626 0.7058278 -0.652327 0.3398312 0.6774839 -0.5183882 -0.4531694 0.7251974 -0.5460349 -0.4504068 0.706385 -0.2001686 -0.1782279 0.9634144 -0.2510419 -0.1730729 0.952378 0.1341855 0.1066117 0.9852047 -0.08485692 0.3050397 0.9485516 -0.1168211 0.3043904 0.9453568 -0.3510707 0.4322175 0.8306247 -0.346821 0.4333987 0.8317938 -0.6354129 0.5018308 0.5868699 -0.5505402 0.5624359 0.6169048 -0.6705234 0.5571708 0.4898564 -0.6469177 -0.5204138 0.5573751 -0.6357123 -0.545414 0.5462542 -0.7377631 -0.2893048 0.609925 -0.7587981 -0.1861877 0.624147 -0.6685486 0.5606524 0.4885813 -0.7501214 0.3347122 0.5703383 -0.771656 0.2006709 0.6035546 -0.779074 0.1503528 0.6086362 -0.774924 -0.1029818 0.6236085 -0.6719574 0.553732 0.4917866 -0.6700015 0.5572242 0.4905093 -0.7753549 0.1881409 0.6028497 -0.7730752 0.2005376 0.6017802 -0.757327 -0.206902 0.6193928 -0.7599053 -0.1862962 0.6227663 -0.6207588 -0.5695528 0.5387654 -0.632435 -0.5450912 0.550365 0.9773989 -0.05151212 0.2050315 0.9788478 -0.1344439 0.1542135 0.9730833 -0.03811186 0.2272807 0.9819208 -0.06602156 0.1774055 0.978641 -0.0800457 0.1893529 0.9722648 -0.09820526 0.2122662 0.9823127 -0.1868213 -0.01262837 0.9629129 -0.2644178 0.05368536 0.9602068 -0.2738564 -0.05482316 0.9165162 -0.3894515 -0.09124487 0.9681363 0.2352901 0.08573621 0.6818268 0.718791 -0.1358374 0.6780149 0.7297279 -0.08827817 0.8352984 0.5468603 -0.05675059 0.8319151 0.5545278 -0.0204069 0.9736592 0.2226213 0.04926896 0.8184326 0.5425057 -0.1893562 0.9867794 0.08911794 0.1353681 0.9882565 0.1138905 -0.101873 0.9914697 0.128865 0.01953929 0.998276 0.01865768 0.05565196 0.9916149 -0.1192619 0.04976481 0.9859266 0.09239697 0.1393256 0.9412984 0.01439207 -0.3372687 0.9666853 -0.01946109 -0.255227 0.9474348 0.1540661 -0.2804123 0.9376818 -0.07795321 -0.3386389 0.9575048 -0.09493321 -0.272346 0.9545064 -0.08771985 -0.2849963 0.9926661 -0.04751342 -0.1111598 0.9726167 -0.1228238 -0.1973094 0.9511426 -0.1336749 -0.2783144 0.8835822 0.4681642 0.01023679 0.6871523 0.7102791 -0.1527264 0.749275 0.6573024 -0.08087354 0.8353639 0.5479866 -0.04333555 0.8796774 0.4750048 0.02319568 0.9795652 0.0398429 -0.1971414 0.9769346 0.05835622 -0.2054103 0.9621668 0.2250255 -0.1536186 0.9411244 0.3027701 -0.1503832 0.9390236 0.312824 -0.1427437 0.8984933 0.4302843 -0.08697819 0.8826909 0.4698576 -0.009523153 0.9617205 0.2443714 0.1240016 0.9748379 0.197716 0.1029536 0.9650089 0.2051782 0.1632779 0.975952 0.1708315 0.1354048 0.9712436 0.1767039 0.1595669 0.9815089 0.1286969 0.1416953 0.9781245 0.1384175 0.1552839 0.9819805 0.1229364 0.1435306 0.7451981 -0.5672176 -0.3506338 0.8617059 -0.4738283 -0.1815203 0.980525 -0.1233652 0.1528126 0.9389606 -0.3302069 -0.09652245 0.9109793 -0.2456331 -0.3313323 0.9620983 -0.0703144 -0.2634823 0.954199 -0.2323669 -0.1884409 0.9233726 -0.2788162 -0.2639029 0.6955171 -0.6314122 -0.3428916 0.7298741 -0.6100866 -0.3083474 0.7347615 -0.5736265 -0.3620474 0.7029794 -0.6306506 -0.3287855 0.6778836 -0.6379221 -0.3654167 0.6945461 -0.637088 -0.3342523 0.9160184 -0.3877562 -0.1027396 0.9214648 -0.3760662 -0.09735041 0.9711904 -0.2375407 -0.01907044 0.7376101 -0.6024064 -0.3050212 0.7770026 -0.5005635 -0.381711 0.7768579 -0.5676646 -0.2724865 0.7828381 -0.5580649 -0.2751872 0.7806738 -0.5677416 -0.2611857 0.6654362 -0.7264608 -0.1716083 0.7566339 -0.5961142 -0.2686133 0.7658388 -0.6050356 -0.217768 0.7510909 -0.5540915 -0.3589501 0.8958829 -0.3330672 -0.2940411 0.9060337 -0.3141539 -0.2835672 0.47415 -0.8176027 -0.3266614 0.4815565 -0.8374381 -0.2584589 0.4823821 -0.8120063 -0.3285627 0.5461746 -0.7820584 -0.3001301 0.5447092 -0.758948 -0.3567774 0.3530984 -0.9233112 -0.1510569 0.3473664 -0.9167255 -0.1973603 0.4815464 -0.7691419 -0.4201595 0.5567585 -0.6113091 -0.5624245 0.567415 -0.5297649 -0.6303883 0.5291517 -0.6531288 -0.5416837 0.4721086 -0.7685942 -0.4317134 0.499279 -0.7608743 -0.4144766 0.5631412 -0.6598933 -0.4974061 0.5619402 -0.6288248 -0.5374036 0.5691029 -0.6362461 -0.5208771 0.6020873 -0.5241975 -0.6022525 0.5751604 -0.6341504 -0.5167629 0.5607181 -0.5379056 -0.6294863 0.5850943 -0.554023 -0.5922191 0.5838029 -0.5487411 -0.5983791 0.5631603 -0.5550145 -0.6122168 0.5599028 -0.5463777 -0.6228807 0.5767752 -0.5154595 -0.6337444 0.5981427 -0.5500465 -0.5828158 0.6083328 -0.1950811 -0.769334 0.6046826 -0.2020684 -0.7704072 0.5945355 -0.1921036 -0.7807841 0.5647647 -0.2010683 -0.8003827 0.5553401 -0.1842688 -0.8109515 0.5571634 0.0549134 -0.8285853 0.5346595 -0.04607939 -0.8438104 0.5092229 0 -0.8606348 0.4716338 0 -0.8817945 0.4729195 -0.002318024 -0.8811026 0.4737918 -0.002699196 -0.8806328 0.4728742 0 -0.88113 0.2244554 0 -0.9744844 0.3127406 0.00499612 -0.9498255 0.3984925 0 -0.9171717 -0.8565071 -0.515536 0.02486407 -0.3463101 -0.9362538 0.05914551 -0.1844446 -0.9815416 0.05056089 -0.439745 -0.8969833 0.04522591 -0.07644438 -0.9969657 0.014692 -0.6372113 -0.7695921 0.04111051 -0.9305087 -0.3655678 0.02266633 -0.9319208 -0.3623602 0.01479429 -0.9332529 -0.3591108 0.008858025 -0.9254654 -0.3774489 0.03234356 -0.9044054 -0.4259918 0.02412122 -0.8826683 -0.468331 0.03953313 -0.8730678 -0.4845101 0.05479776 -0.8357112 -0.5447947 0.06917929 -0.8719385 -0.4831824 0.07910805 -0.4991551 -0.865736 0.0366804 -0.2607877 -0.9641124 0.04977166 -0.3059339 -0.9482929 0.08452963 -0.2842613 -0.9521687 0.1121183 -0.3545498 -0.9272792 0.1201995 -0.3259322 -0.9329866 0.1526577 -0.3608377 -0.9192998 0.157112 -0.7577718 -0.6519294 0.02775073 -0.6504161 -0.7583773 0.04269772 -0.6504646 -0.7565651 0.06711935 -0.6562662 -0.7518937 0.06301224 -0.6561094 -0.7484071 0.09699076 -0.6743273 -0.7327617 0.09134048 -0.674437 -0.7280097 0.1230317 -0.6798306 -0.723421 0.1203847 -0.6732072 -0.7306932 0.1134891 -0.3427377 -0.7271302 0.5948215 -0.6763883 -0.5869608 0.4449449 -0.9073955 -0.3387618 0.2487449 -0.2550734 -0.8466879 0.466966 -0.2828835 -0.6789819 0.6774663 -0.2466365 -0.788313 0.5636781 -0.2689231 -0.5422992 0.7959851 -0.1274833 -0.702039 0.700635 -0.1611815 -0.4268379 0.8898484 -0.130253 -0.5508186 0.8243986 -0.1574416 -0.2861999 0.9451465 -0.02669882 -0.4275861 0.9035804 0.2514964 -0.04523587 0.9668006 0.3173843 -0.3333083 0.887791 0.2037475 -0.2327783 0.9509475 0.2363842 -0.4950392 0.8360974 0.2112752 -0.399467 0.89207 0.232487 -0.6503229 0.7232081 0.1099442 -0.5422303 0.8330058 0.1389852 -0.7782078 0.6124343 0.1050511 -0.679726 0.7259042 0.1282673 -0.8402514 0.5268066 0.0405972 -0.737635 0.6739781 0.3008889 -0.1427155 0.9429201 0.04858243 -0.1445627 0.9883023 -0.04441094 -0.3627283 0.9308362 -0.1132163 -0.2457387 0.9627017 -0.366792 -0.2159704 0.904887 -0.5941078 -0.7410537 0.3128507 -0.6287522 -0.5588919 0.5406575 -0.5905862 -0.6960099 0.4083849 -0.60944 -0.4434024 0.6572498 -0.4596812 -0.6921409 0.5564479 -0.5118278 -0.3780929 0.7714132 -0.4725761 -0.5603734 0.6801865 -0.5013578 -0.2806974 0.8184434 -0.3513328 -0.5132352 0.7830422 -0.3296853 -0.5657765 0.7557807 -0.5050793 -0.3132812 0.8042076 -0.8310953 -0.5512123 0.07379561 -0.8785376 -0.3346281 0.3408752 -0.8336414 -0.5307376 0.1528393 -0.8598309 -0.2494803 0.4454779 -0.6885691 -0.6742299 0.2669959 -0.7907176 -0.2454766 0.5608092 -0.7178177 -0.5821911 0.3818262 -0.7794964 -0.1972799 0.5945302 -0.4947137 -0.7452003 0.4471409 -0.7299943 -0.2096733 0.6504963 -0.5700727 -0.5945246 0.5670605 0.9712752 -0.2031939 -0.1238421 0.9708508 -0.2062661 -0.1220783 0.7512717 -0.5619577 -0.3461132 0.7478072 -0.570172 -0.34013 0.9716712 -0.2035365 -0.1201168 0.9712647 -0.2064634 -0.1183967 0.754567 -0.5636485 -0.3360493 0.7512476 -0.5714452 -0.3302687 0.971676 0 -0.2363173 0.7545847 -0.5689134 -0.3270164 0.9713923 -0.192153 -0.1395498 0.753467 -0.5734082 -0.3216997 0.7530023 -0.5646744 -0.3378322 0.7500678 -0.5711596 -0.3334292 0.7470135 -0.5610827 -0.3565911 0.744921 -0.5668186 -0.3518657 0.9688955 -0.2215859 -0.110187 0.9659723 -0.1804729 -0.1852755 0.9604436 -0.224173 -0.165211 0.9478489 -0.1818439 -0.2617542 0.9457844 -0.2155773 -0.2429368 0.928547 0.2847208 -0.2381901 0.8680542 0.4261623 -0.2546916 0.7832631 0.5826625 -0.2168028 0.9783974 0.1224493 -0.1665678 0.9040879 0.3038313 -0.3005192 0.9587098 0.02163946 -0.283562 0.9648277 -0.04627752 -0.2587778 0.9643616 -0.0410313 -0.2613871 0.9300179 -0.2147085 -0.2982736 0.9213916 0.1519724 -0.3576899 0.9873636 -0.04076677 -0.153138 0.8425114 0.4432747 -0.3060754 0.9377207 0.3031572 -0.1696342 0.6818463 0.6921204 -0.2367594 0.8298968 0.5487724 -0.1005998 0.2850411 -0.9567845 0.05757766 0.285024 -0.9584004 0.01517349 0.9835689 -0.1804888 -0.004018783 0.9368972 -0.3495846 -0.00378257 0.957008 -0.2898976 0.009761214 0.901717 -0.4322119 -0.009981155 0.8251951 -0.564496 -0.01993477 0.7546408 -0.655879 -0.01843816 0.7415757 -0.6699226 0.03562754 0.04990446 -0.9982196 -0.03266847 0.07841885 -0.9963936 -0.03241121 0.2934508 -0.9557039 -0.02273476 0.4499062 -0.8925701 -0.03004926 0.681033 -0.73193 -0.0217396 0.5952188 -0.8035594 -0.002630949 0.7042288 -0.7098073 -0.01534628 0.9320542 -0.3622734 0.005744934 0.6838577 -0.7295123 0.01226747 0.6810069 -0.7321845 0.01164275 0.2791765 -0.9601021 0.01626449 0.2792382 -0.9599959 -0.0208348 0.1478812 -0.9885242 -0.03084039 0.2715267 -0.9608291 0.05550402 0.6503745 -0.7581058 0.04784095 0.6839118 -0.7284917 0.0395534 0.9075235 -0.4189834 0.029226 0.94262 -0.333657 0.01185768 -0.6402767 -0.766685 0.04732942 -0.5689876 -0.8212164 -0.04309374 -0.4335793 -0.8993437 -0.05648034 -0.323608 -0.9451277 -0.04484927 -0.2193223 -0.975529 0.01551985 -0.8482387 -0.5282393 -0.03813916 -0.79137 -0.6097244 -0.04438483 -0.9589111 -0.282873 -0.02173686 -0.9588929 -0.2829246 -0.02186554 -0.958607 -0.2837964 -0.02307134 -0.9590086 -0.282486 -0.02245593 -0.955103 -0.2961984 -0.006706476 -0.9557377 -0.293186 -0.02464693 -0.9386648 -0.3443024 0.01908534 -0.9303029 -0.366103 -0.02247524 -0.9255744 -0.3780258 -0.02021378 -0.9255263 -0.3785697 -0.009280443 -0.928845 -0.3703958 -0.007345497 -0.9299197 -0.3676707 0.008220255 -0.9248102 -0.3803833 0.005894958 -0.9248284 -0.379658 0.02350091 -0.911893 -0.4099669 0.01945847 -0.09720516 -0.9842534 0.1476365 -0.194874 -0.9803424 -0.03087222 -0.2143332 -0.9764204 -0.0257796 -0.1815909 -0.98323 0.01683831 -0.2000221 -0.9795693 0.02086311 -0.1850537 -0.9809392 0.05927503 -0.1914348 -0.9796424 0.06044578 -0.640723 -0.7663065 0.04741859 -0.6407142 -0.7675895 0.01708465 -0.6431889 -0.765532 0.01639997 -0.6431748 -0.7654879 -0.01882988 -0.6477143 -0.7616223 -0.01994848 -0.6476687 -0.7617393 -0.01669198 -0.7051974 -0.7080157 -0.03755486 -0.9554673 -0.2842739 0.07918745 -0.8856768 -0.004099905 0.4642843 -0.9085502 -0.1350191 0.3953561 -0.8696923 -0.1767209 0.4608743 -0.8708701 -0.3210753 0.3721506 -0.8607345 -0.360595 0.3593153 -0.8559937 -0.3924886 0.336493 -0.7999984 -0.46997 0.3730025 -0.8876321 -0.002140402 0.4605482 -0.9128755 -0.1687796 0.3717148 -0.9406054 -0.09317815 0.326465 -0.9381631 -0.275014 0.2102796 -0.9467916 -0.2291628 0.2259868 -0.9385358 -0.2938916 0.1810477 -0.8941805 -0.3837257 0.2306424 -0.2242323 -0.9745067 0.007513701 -0.6255502 -0.7783563 -0.05337011 -0.9001498 -0.4258851 -0.09139007 -0.4505583 -0.8832918 0.129588 -0.4418244 -0.8958911 0.04659003 -0.5130508 -0.8166957 0.2641726 -0.5096882 -0.8336911 0.2125493 -0.6561163 -0.7128213 0.2477849 -0.6548168 -0.7162731 0.24118 -0.7136666 -0.6235263 0.3192099 -0.7145454 -0.6201549 0.3237791 -0.7799248 -0.5384996 0.3189603 -0.7324565 -0.6739081 0.09672409 -0.7208632 -0.6930189 -0.009007036 -0.7603283 -0.627862 0.1664038 -0.7540981 -0.6509807 0.08694958 -0.8243141 -0.5429566 0.1603257 -0.8162099 -0.5655044 0.1183472 -0.8500881 -0.4896147 0.1939786 -0.8454754 -0.5056629 0.1716871 -0.8798938 -0.4354928 0.1900866 -0.9172403 -0.3974777 -0.02611213 -0.9127575 -0.404015 -0.06038123 -0.9206089 -0.3901113 -0.01709896 -0.9188438 -0.3934875 -0.02989494 -0.9257841 -0.3779114 -0.01033902 -0.9271752 -0.3746053 -0.004117965 -0.9281226 -0.3722725 -0.001286745 -0.9330153 -0.3594169 0.01737928 -0.9287229 -0.370641 0.009947955 0 -1 1.0538e-6 0 -1 -1.40009e-5 0 -1 1.27596e-7 0 -1 -1.08115e-6 0 -1 1.04363e-5 0 -1 -2.8959e-7 0 -1 -4.37545e-6 0 -1 5.66587e-6 0.728592 -0.6278378 0.2738127 0.8378009 -0.5229803 0.1567843 0.9174969 -0.3962213 0.03475916 0.7127193 -0.5732771 0.4042086 0.6406469 -0.7535173 0.147591 0.5775033 -0.6992909 0.4212865 0.5271371 -0.8488465 0.03982675 0.4768007 -0.8022358 0.3592755 0.4096134 -0.8953633 -0.1747609 0.2063519 -0.9181063 0.3383783 0.8404707 -0.484496 0.2426373 0.793935 -0.6030448 0.0774877 0.778021 -0.5749044 0.253315 0.7425832 -0.6697323 0.005377948 0.7303479 -0.6468315 0.2195472 0.6851514 -0.7179822 -0.1227567 0.5949047 -0.7780649 0.2017509 0.9148876 -0.4030413 0.02320104 0.9079821 -0.4190081 9.26781e-4 0.9089657 -0.4167032 0.01183873 0.9002173 -0.4340131 -0.0352351 0.9032216 -0.4291608 0.003477871 0.8894542 -0.4488897 -0.08584553 0.8841373 -0.4671775 -0.006814658 0.8811194 -0.3973393 0.2564178 0.8764813 -0.002368867 0.4814302 0.8989193 -0.1357743 0.4165447 0.9293861 -0.1015824 0.3548557 0.9312216 -0.2438312 0.2708744 0.9321216 -0.268542 0.2429701 0.9232427 -0.3249419 0.2050265 0.9465129 -0.3045321 0.106647 0.8746498 -0.004229426 0.484737 0.8990114 -0.1709503 0.4031807 0.8590091 -0.1737775 0.4815651 0.8569815 -0.3523651 0.3760607 0.8547955 -0.3234695 0.4058232 0.8293395 -0.4686475 0.3042461 0.7965277 -0.4186103 0.4362443 0.007350206 -0.9860944 0.1660244 0.874253 -0.4846215 0.02870124 0.8650313 -0.4987344 0.05463689 0.8279491 -0.5566934 0.06776905 0.8281837 -0.5533276 0.08910965 0.9313621 -0.3640943 4.09955e-5 0.9334964 -0.3585621 0.004225969 0.9299227 -0.3677341 -0.003929018 0.9283824 -0.3715007 -0.009661138 0.923563 -0.3703014 0.09954094 0.8869851 -0.4616439 -0.01193928 0.8857064 -0.4642415 -0.002072334 0.8881254 -0.4596012 -1.21787e-4 0.8880828 -0.4590989 0.02317923 0.5502659 -0.832535 0.06397503 0.6103631 -0.7916609 0.02702236 0.7213692 -0.6925492 -0.001468837 0.1610755 -0.9833734 0.08385443 0.2739943 -0.9613673 0.02645975 0.2562755 -0.9536636 0.1576344 0.4280771 -0.8913674 0.1490442 0.1033568 -0.9829415 0.1521297 0.103331 -0.9871217 0.1221209 0.1384889 -0.9835507 0.1159687 0.1384866 -0.9885858 0.05932754 0.1694188 -0.9841019 0.05329996 0.169511 -0.9853603 0.01820093 0.03254902 -0.9755318 0.2174357 0.3916355 -0.9201138 0.0035187 0.5989611 -0.8002583 0.02884846 0.5987009 -0.7995368 0.0479409 0.5820103 -0.8119702 0.04437011 0.5820125 -0.8070327 0.09979814 0.5628086 -0.8208549 0.09717977 0.5629637 -0.8172239 0.1233573 0.6712443 -0.7305256 0.125553 -0.08390891 -0.9963698 -0.01437175 -0.2851012 -0.9572901 -0.04809355 -0.2046884 -0.978187 -0.03539663 -0.1771414 -0.9837314 -0.02989238 -0.06748825 -0.9976354 -0.01300054 -0.5470114 -0.830698 -0.1035337 -0.3170403 -0.9475827 -0.0396561 -0.4633299 -0.8811753 -0.09410279 -0.3772926 -0.923447 -0.06997084 -0.7776095 -0.6145994 -0.1326317 -0.7996535 -0.5846339 -0.1369583 -0.6935364 -0.7082577 -0.1318271 -0.6188493 -0.7783078 -0.1061253 -0.5196031 -0.8497754 -0.08885008 -0.4274027 -0.9016978 -0.06532949 -0.7306321 -0.6725873 -0.1174867 -0.6769422 -0.7307093 -0.08839225 -0.7431412 -0.6541676 -0.1407335 -0.6273807 -0.7768966 -0.0531519 -0.7087095 -0.6931438 -0.1314632 -0.6792082 -0.723752 -0.1218987 0.793348 -0.6087008 0.009082794 0.959215 -0.2538797 -0.1243053 0.9459307 -0.3243663 0.001295685 0.8525695 -0.5226136 6.01822e-4 0.8421254 -0.4625025 -0.277338 0.8406256 -0.5291455 -0.1155582 0.9620921 -0.2726398 -0.00683093 0.7611028 -0.1487806 -0.6313374 0.9789898 -0.1803224 0.09520012 0.9957636 -0.09192788 -0.002071559 0.8958709 -0.4442251 -0.008906662 0.8498095 -0.5211283 0.07905274 0.7993942 -0.6006253 -0.01477813 0.7993688 -0.5995339 -0.03960615 0.8956403 -0.4426088 -0.04388618 0.9613897 -0.2705864 -0.05012863 0.9944559 -0.08953863 -0.05513983 0.9944525 -0.08772617 -0.05803787 0.9827333 -0.09599345 -0.1581789 0.9798382 -0.08174145 -0.1823062 0.9625089 -0.09816014 -0.2528663 0.9514464 -0.08662247 -0.2953749 0.9272478 -0.1084479 -0.3584001 0.9300096 -0.104739 -0.3522953 0.8983176 -0.08786761 -0.4304707 0.885666 -0.1002079 -0.453381 0.8438296 -0.09520232 -0.5280988 0.7991397 -0.6001341 -0.0348553 0.7957776 -0.6023453 -0.06259781 0.7958437 -0.6023687 -0.0615198 0.7903723 -0.6070798 -0.08225518 0.7895926 -0.6076107 -0.08574861 0.7833482 -0.6131369 -0.1021213 0.780608 -0.6150177 -0.1113759 0.7748395 -0.6203801 -0.1214594 0.7676858 -0.6262432 -0.1359344 0.7635407 -0.6300535 -0.1415568 0.7512859 -0.639532 -0.1629987 0.7487345 -0.6419112 -0.1653682 0.7271482 -0.6595026 -0.1905568 0.7294518 -0.6573892 -0.1890491 0.6976088 -0.6823396 -0.2185286 0.7092977 -0.6716139 -0.214083 0.6660637 -0.7075345 -0.2361233 0.6845524 -0.6911046 -0.2318674 0.631618 -0.7319393 -0.255585 0.8957005 -0.442418 -0.04457587 0.8903178 -0.4462261 -0.09064561 0.8901545 -0.4428953 -0.1070924 0.8832749 -0.4492468 -0.1341741 0.8780148 -0.4495868 -0.1642002 0.8718451 -0.455244 -0.1806631 0.8614121 -0.4550154 -0.2256773 0.8584846 -0.4578818 -0.2309734 0.8347592 -0.4711832 -0.2848924 0.8356502 -0.4703357 -0.2836776 0.8020142 -0.4822668 -0.3524088 0.8045957 -0.479749 -0.3499526 0.7502107 -0.5097181 -0.4211552 0.7592388 -0.5011872 -0.4151721 0.6857286 -0.535416 -0.4930579 0.7096967 -0.5124006 -0.483504 0.6149605 -0.5766128 -0.5379045 0.6458086 -0.5486384 -0.5309681 0.5350447 -0.6030093 -0.5916984 0.9615544 -0.2695972 -0.05225598 0.9529583 -0.2756935 -0.1259506 0.9523244 -0.2670921 -0.1474454 0.940184 -0.2785222 -0.1961618 0.9329066 -0.2734089 -0.234378 0.9193093 -0.2858639 -0.270467 0.9046047 -0.2731347 -0.3272429 0.892886 -0.284786 -0.348786 0.8612499 -0.2904869 -0.4169725 0.8513696 -0.2998358 -0.4304282 0.8047827 -0.2918038 -0.5168901 0.7928722 -0.3035296 -0.5284161 0.7187069 -0.318602 -0.6180236 0.7119038 -0.325056 -0.6225205 0.6096649 -0.3340941 -0.7188114 0.6224665 -0.3216484 -0.7134969 0.4949298 -0.3824471 -0.7802428 0.5155752 -0.3636485 -0.7758492 0.36249 -0.3915724 -0.8457376 0.7600578 -0.1672843 -0.6279555 0.8204402 -0.03571659 -0.5706157 0.6997871 -0.1371761 -0.7010568 0.7289589 -0.1102836 -0.6756156 0.6313934 -0.104111 -0.7684422 0.6079301 -0.1264473 -0.7838572 0.472706 -0.1019124 -0.8753074 0.4753072 -0.09938597 -0.8741885 0.31388 -0.1514055 -0.9373131 0.3285379 -0.137888 -0.9343713 0.1331989 -0.1315941 -0.9823142 0.4562353 0.1765468 0.87217 0.5165075 0.1182135 0.8480835 0.5382586 0.1569958 0.8280278 0.550044 0.1613942 0.8193922 0.5420249 0.1562578 0.8257073 0.5334348 0.149142 0.8325889 0.5257644 0.139193 0.8391647 0.5198798 0.1288108 0.8444719 0.5786079 0.2275038 0.7832337 0.5645806 0.2131317 0.7973856 0.5605019 0.1933217 0.8052729 0.5585951 0.1925944 0.8067708 0.5490121 0.1832798 0.8154718 0.5995063 0.2586687 0.7574185 0.5885662 0.2444759 0.7705981 0.6207256 0.3420826 0.7054638 0.6306943 0.291296 0.7192853 0.6072606 0.2674166 0.7481464 0.6247857 0.2382142 0.7435704 0.6160522 0.2516971 0.7464102 0.6142641 0.3432517 0.7105335 0.6264455 0.3457276 0.6985975 0.6503877 0.3530071 0.6725933 0.6330919 0.3634333 0.6834551 0.6553363 0.3590819 0.6645259 0.6782745 0.3676599 0.6362153 0.6719509 0.3737189 0.6393873 0.6940084 0.3654286 0.6203341 0.7074087 0.3716641 0.6011978 0.7142926 0.3773624 0.5893928 0.7151462 0.3790876 0.5872465 0.7143058 0.377199 0.5894813 0.7129152 0.3707516 0.595227 0.7127017 0.3656739 0.5986142 0.5505117 0.3049018 0.7771562 0.562031 0.3109883 0.7664253 0.5764074 0.3272036 0.7487939 0.5767762 0.327147 0.7485347 0.5981994 0.3299267 0.7302779 0.5847283 0.2271496 0.7787785 0.5347248 0.2991645 0.7902975 0.5379977 0.2994918 0.7879487 0.4862036 0.2340958 0.8419058 0.4937188 0.2468472 0.8338513 0.4972842 0.2607824 0.8274667 0.5078619 0.2654749 0.8195117 0.5245282 0.280638 0.8038113 0.4684973 0.2109759 0.8579041 0.4570977 0.206126 0.8652017 0.4777054 0.2218942 0.8500357 0.4407949 0.1556853 0.8840035 0.4424746 0.1570281 0.8829261 0.4404751 0.1380791 0.8870828 0.4252952 0.09657013 0.8998879 0.4259456 0.09734618 0.8994966 0.4376527 0.1217133 0.8908682 0.4210309 0.01131397 0.9069758 0.4178473 0.02599847 0.9081453 0.4160117 0.03263902 0.9087734 0.42102 0.04264682 0.9060482 0.4267256 0.06923615 0.9017271 0.4931563 0.1071621 0.8633152 0.4964903 0.06118476 0.8658834 0.4290311 0.0954768 0.8982297 0.5003738 0.01656103 0.8656511 0.472997 0.02700191 0.8806502 -0.02165019 -0.1288633 0.9914261 0.1119946 -0.298941 0.9476768 -0.1794227 -0.1100478 0.9775976 -0.2428648 -0.05861461 0.9682878 -0.2815431 -0.01908767 0.9593588 -0.5809792 -0.02695924 0.8134719 -0.3916381 -0.07349413 0.9171796 -0.2837384 -0.01550561 0.9587764 0.004731476 -0.1961864 0.9805552 -0.2726457 -0.2530072 0.9282519 -0.1128339 -0.1196428 0.9863845 0.6835615 0.1794872 0.70748 0.6902474 0.1681519 0.7037639 0.6915019 0.1674803 0.7026917 0.530975 -0.2423626 0.811989 0.5370297 -0.2416861 0.8081998 0.2694218 -0.6070212 0.747621 0.2691035 -0.6070194 0.7477371 -0.0477724 -0.8468245 0.5297226 -0.05547827 -0.8453268 0.5313612 0.6947287 0.1554439 0.7022745 0.7086255 0.1573202 0.6878229 0.5444431 -0.2563644 0.7986609 0.5532811 -0.2554156 0.7928701 0.283336 -0.6159307 0.7350851 0.2846202 -0.6159437 0.7345778 -0.03528624 -0.851167 0.5237076 -0.04286146 -0.8497131 0.5255004 0.7458673 0.117533 0.6556432 0.7297159 0.1021266 0.6760805 0.5689498 -0.2892036 0.7698426 0.5487501 -0.3012737 0.7798125 0.2735354 -0.6360169 0.7215685 0.253756 -0.6420481 0.7234516 -0.07854771 -0.849951 0.5209736 -0.09430134 -0.8499253 0.518396 0.7098118 0.1637907 0.6850839 0.7000916 0.1485781 0.6984242 0.5484164 -0.2483002 0.7984902 0.5318632 -0.2638418 0.8046795 0.2728735 -0.6091649 0.7446195 0.2513522 -0.6208144 0.7425709 -0.05926787 -0.8431327 0.5344293 -0.08267593 -0.8471429 0.5248939 0.6865865 -0.3499585 -0.6372817 0.7023906 -0.1165068 -0.7021921 0.6863577 -0.2360822 -0.6878796 0.7672826 -0.2175636 -0.6032775 0.7671412 -0.2123214 -0.6053216 0.8495709 -0.1836675 -0.4944648 0.8494518 -0.1748106 -0.4978683 0.8962069 -0.1519826 -0.4167907 0.8958814 -0.1481263 -0.4188736 0.9325527 -0.1253034 -0.3385922 0.9325902 -0.1069554 -0.3447265 0.9645941 -0.08538264 -0.2495355 0.9650583 -0.06217128 -0.2545527 0.5773152 -0.6967752 -0.4256895 0.5738446 -0.7011848 -0.423134 0.5438053 -0.7428286 -0.3904889 0.6230139 -0.5112437 -0.5920167 0.6005433 -0.5244427 -0.6035791 0.5976709 -0.5242607 -0.6065809 0.5520704 -0.5470938 -0.6292113 0.566565 -0.5500281 -0.6135743 0.524578 -0.5662056 -0.6357902 0.5346554 -0.5642198 -0.6291262 0.5004497 -0.5939841 -0.6298674 0.5465724 -0.7398203 -0.3923323 0.5399139 -0.7298548 -0.4192913 0.5445113 -0.7277253 -0.4170413 0.5575325 -0.720398 -0.4125342 0.5509865 -0.7223082 -0.4179531 0.5628465 -0.7128272 -0.4184273 0.5585164 -0.7128108 -0.4242174 0.5661192 -0.7071544 -0.4236056 0.5767181 -0.7185105 -0.3887659 0.5538303 -0.6821603 -0.4774196 0.5527728 -0.6838219 -0.4762666 0.5822727 -0.6972804 -0.4180416 0.5744452 -0.7012209 -0.4222583 0.5625894 -0.6966075 -0.4452317 0.5331446 -0.7392569 -0.4114077 0.5530496 -0.6834384 -0.4764956 0.5486646 -0.6919144 -0.4692777 0.5554132 -0.6848728 -0.4716625 0.5377199 -0.7039003 -0.4640923 0.5499988 -0.6968579 -0.4603155 0.5137214 -0.735558 -0.4416389 0.5302523 -0.7208563 -0.4463168 0.5386829 -0.6277058 -0.5619665 0.4608108 -0.6866768 -0.5622529 0.5128675 -0.6739866 -0.531704 0.496863 -0.686146 -0.5313482 0.5185433 -0.6910941 -0.5034897 0.5503547 -0.6846738 -0.4778404 0.5149439 -0.6506096 -0.5581577 0.5149457 -0.6506075 -0.5581586 0.49732 -0.6331897 -0.5930799 0.4581335 -0.6403846 -0.6164587 0.5515417 -0.6234153 -0.5542159 0.5515409 -0.6234151 -0.5542169 0.5704497 -0.6123367 -0.5473856 0.5704489 -0.6123384 -0.5473845 0.5891182 -0.6033346 -0.5375194 0.5891178 -0.6033346 -0.5375199 0.6034178 -0.5980362 -0.5274844 0.6034092 -0.5980398 -0.52749 0.5781762 -0.6734306 -0.4606556 0.5781841 -0.6734272 -0.4606505 0.5742452 -0.6748932 -0.463424 0.5742453 -0.6748936 -0.4634233 0.5691022 -0.6773736 -0.4661412 0.5691034 -0.6773726 -0.4661414 0.5575578 -0.6840834 -0.4702758 0.5636956 -0.6793037 -0.4698872 0.5576002 -0.6817577 -0.4735912 0.5328781 -0.6362833 -0.5578393 0.5328803 -0.6362823 -0.5578382 0.508638 -0.5942136 -0.6230552 0.4690608 -0.6222223 -0.6267547 0.1652175 -0.985242 0.04473751 -0.2513423 -0.9528751 0.1698713 0.4148225 -0.8920064 -0.1795745 0.632645 -0.6701748 -0.3881057 0.5474535 -0.7598394 -0.3506264 0.5306841 -0.7746429 -0.3439517 -0.1067753 -0.9877307 0.1139611 0.135419 -0.9903849 -0.02827799 -0.1284022 -0.9855474 0.1104958 -0.1175844 -0.9837227 0.1358811 -0.1154056 -0.9842708 0.1337635 -0.1064521 -0.9807811 0.1635126 -0.1049313 -0.9812653 0.1615795 -0.09655064 -0.9754848 0.1977559 -0.09281986 -0.9763612 0.1952012 -0.08662617 -0.965175 0.2468465 -0.0809192 -0.9664781 0.2436643 -0.0805332 -0.9547348 0.2863497 -0.07681679 -0.956185 0.282506 -0.07870751 -0.9422757 0.3254561 -0.06949406 -0.9442652 0.321767 -0.07801783 -0.9242519 0.373727 -0.06694692 -0.9264022 0.3705362 -0.07834696 -0.9093614 0.4085628 -0.07033383 -0.9118463 0.404462 -0.08358335 -0.8947166 0.4387435 -0.06928288 -0.8968479 0.4368796 -0.09003305 -0.8758438 0.4741221 -0.07278388 -0.8776652 0.4737155 -0.09496116 -0.8592704 0.50263 -0.07838839 -0.8613528 0.5019229 0.1218637 -0.9921699 -0.02735209 0.1519385 -0.9874465 0.04317706 0.168388 -0.9853606 0.0266456 0.1875332 -0.9781437 0.08981251 0.1982203 -0.9772651 0.07524472 0.2146154 -0.9656488 0.1465019 0.236723 -0.9628728 0.1297627 0.2481511 -0.9423176 0.2246302 0.2732207 -0.9391747 0.20809 0.2743089 -0.9178084 0.2870233 0.2873886 -0.9186457 0.2711049 0.283646 -0.892473 0.3507662 0.3118728 -0.8890177 0.3352359 0.2957092 -0.8507034 0.4345801 0.325761 -0.8467332 0.4206218 0.3027408 -0.8119798 0.4990358 0.3229112 -0.812934 0.4846305 0.2940248 -0.7755055 0.5586957 0.3262452 -0.7704933 0.5476352 0.2796034 -0.7230898 0.6316354 0.3138064 -0.7166889 0.6228022 0.2611058 -0.6728613 0.692157 0.291529 -0.6691328 0.6835731 0.28435 -0.9318171 -0.2255264 0.3443189 -0.930911 -0.1218574 0.3669506 -0.9178973 -0.1510362 0.4088397 -0.9110766 -0.05281764 0.4362066 -0.8960044 -0.08306509 0.4642211 -0.8856809 0.008260488 0.4812902 -0.876352 -0.01915889 0.5040078 -0.8599006 0.08091396 0.5388907 -0.8409298 0.04933583 0.5543693 -0.813147 0.1773886 0.5918831 -0.7927927 0.1454452 0.5940274 -0.7639447 0.252032 0.6128224 -0.7583765 0.222067 0.6072281 -0.7229363 0.3296016 0.6463109 -0.7025542 0.2978252 0.6246351 -0.6507773 0.431648 0.6649392 -0.6302449 0.4008083 0.6338209 -0.5819891 0.5094703 0.6612706 -0.5762986 0.4802097 0.6201473 -0.5236242 0.5841534 0.6615803 -0.5035868 0.5556185 0.5961156 -0.4367716 0.6737039 0.6388471 -0.4161444 0.6470689 0.5640159 -0.3532236 0.7464041 0.6023041 -0.3405097 0.7219992 0.4918743 -0.8035002 -0.3353317 0.5533998 -0.80117 -0.227762 0.5799723 -0.7696649 -0.2669237 0.6323745 -0.7611297 -0.1441668 0.6635186 -0.7248129 -0.1854434 0.6982929 -0.7120381 -0.07340866 0.7161931 -0.688786 -0.1124338 0.7430907 -0.669146 0.007734537 0.7798787 -0.6248261 -0.03717005 0.797798 -0.592662 0.1107707 0.8350195 -0.5465358 0.06357002 0.8380717 -0.512794 0.1862214 0.8559826 -0.4971905 0.141759 0.8490732 -0.4568275 0.2652986 0.884867 -0.4132 0.2151195 0.8603972 -0.3545922 0.3660346 0.8962136 -0.3128755 0.3144999 0.8610865 -0.2568954 0.4387881 0.887378 -0.2427798 0.3919416 0.839554 -0.1824955 0.5117075 0.8759177 -0.1460127 0.4598354 0.8016477 -0.07002836 0.5936809 0.8393079 -0.03593581 0.5424674 0.754184 0.03646546 0.65565 0.7905464 0.05618858 0.6098192 0 -1 2.02234e-7 0 -1 0 0 -1 4.02662e-5 0 -1 -5.06361e-6 0 -1 0 0 -1 -4.17167e-5 0 -1 6.65192e-7 0 -1 -2.70361e-6 0 -1 3.53144e-7 0 -1 1.42551e-7 -0.3802704 -6.39208e-4 0.9248752 -0.3088718 -0.0991646 0.94592 -0.2323421 -0.00662887 0.9726116 -0.1390557 -0.1205555 0.9829191 -0.3846572 -0.003370761 0.9230534 -0.2765434 -0.1437337 0.9501919 -0.4142476 -0.1557036 0.8967471 -0.278969 -0.3212956 0.9049561 -0.3432746 -0.2864432 0.8944903 -0.1554291 -0.4846929 0.8607639 -0.3244793 -0.4632717 0.8246773 -0.1380386 -0.6449188 0.7516816 -0.2247542 -0.5922514 0.7737724 -0.03317916 -0.7469919 0.6640048 -0.169515 -0.7195574 0.6734254 0.06963711 -0.8822953 0.4655169 -0.02154827 -0.8715261 0.4898754 0.1053333 -0.940205 0.3239126 0.07436996 -0.9308457 0.3577645 -0.3816844 -0.002170383 0.9242902 -0.311178 -0.1010873 0.9449602 -0.310321 -0.1017438 0.9451715 -0.2149859 -0.218178 0.9519346 -0.2144992 -0.2183866 0.9519966 -0.1014872 -0.3425207 0.9340128 -0.09754955 -0.3419259 0.9346502 0.01932841 -0.4545378 0.8905178 0.02296519 -0.4565349 0.8894091 0.1325117 -0.5500716 0.8245375 0.139976 -0.5498482 0.8234524 0.3239771 -0.6778568 0.6599614 0.3314805 -0.6767756 0.6573396 0.4339683 -0.7293224 0.5289238 0.4374435 -0.7301232 0.5249413 0.7673197 -0.4050047 0.4971839 0.7183173 -0.3852807 0.5792918 0.6835293 -0.3780832 0.6243724 0.6244562 -0.3501328 0.6981844 0.5476257 -0.3792462 0.7458407 0.4221386 -0.2894216 0.8590891 0.3121721 -0.3172459 0.8954907 0.2688053 -0.2783685 0.9220926 0.1859114 -0.2354669 0.9539352 0.1588327 -0.2099705 0.96472 -0.009939491 -0.2263074 0.9740053 -0.01082909 -0.2227265 0.9748209 -0.08716708 -0.1368497 0.9867492 0.8268952 -0.3963808 0.3989068 0.7714441 -0.4120609 0.4848504 0.5279825 -0.7583625 0.3822575 0.5242571 -0.7597104 0.384701 0.1556034 -0.9637843 0.2165811 0.1753206 -0.9628442 0.2054112 0.2320982 -0.9726693 0.006721079 0.2328599 -0.9725091 -0.001579284 0.645694 -0.7631205 0.02695268 0.6481045 -0.761507 0.008221387 0.9204188 -0.3891702 0.03709042 0.9226685 -0.3853605 0.01342773 0.2309165 -0.972772 0.01981365 0.2316989 -0.9727032 0.01281589 0.6424719 -0.7637658 0.0623846 0.6444508 -0.7632318 0.04648095 0.9162243 -0.3909197 0.08783572 0.918596 -0.3893511 0.06772953 0.2254403 -0.9724888 0.05867207 0.2269877 -0.9722961 0.05582946 0.6248028 -0.7629618 0.1658639 0.6292893 -0.7605829 0.1597148 0.8888135 -0.3931721 0.2354283 0.8933752 -0.3874939 0.2274413 -0.9050142 -0.4252084 0.0121392 -0.8803755 -0.4576746 -0.1243914 -0.7092777 -0.6896741 0.1458591 -0.6887273 -0.7195288 0.08906745 -0.4148278 -0.909778 0.01490437 -0.5036661 -0.8313974 0.2347314 -0.06994622 -0.9855315 -0.1543872 -0.2119688 -0.9595093 0.1855024 -0.9006453 -0.433952 0.02288722 -0.9074018 -0.4100437 0.09212052 -0.687719 -0.7221938 0.07401823 -0.7091651 -0.682191 0.1780461 -0.3878366 -0.9131693 0.1253194 -0.4264482 -0.8692739 0.2500101 -0.0385285 -0.9876579 0.1518135 -0.09429609 -0.9478435 0.3044686 -0.8803001 -0.4722574 0.04522073 -0.9063086 -0.4002624 0.1356275 -0.629986 -0.7555651 0.1795524 -0.6983423 -0.6551137 0.2883471 -0.2844918 -0.916934 0.2798151 -0.4034463 -0.8155237 0.4149125 0.1014502 -0.9419355 0.320102 -0.06416016 -0.8601374 0.5060112 -0.1973617 -0.936751 -0.2890433 -0.6364967 -0.02668988 -0.7708175 -0.8697426 -0.4886672 -0.06893533 -0.7005707 -0.6675701 -0.2520932 -0.5660873 -0.7262627 0.3899843 -0.3797461 -0.7188343 -0.5822973 -0.2076405 -0.7437775 0.6353585 -0.07589745 -0.6024867 -0.7945122 -0.0438289 -0.9989899 -0.009919583 -0.0307452 -0.9890397 -0.144414 -0.0610063 -0.5427203 -0.837695 -0.1955527 -0.9520476 0.2352968 -0.1742422 -0.3263447 -0.9290527 -0.336537 -0.848941 0.4074828 -0.2298322 -0.1432994 -0.9626227 -0.437995 -0.7048275 0.5580132 -0.543699 -0.809349 0.222139 -0.3318116 -0.6242299 0.7072752 -0.7117726 -0.3879535 -0.5855526 -0.6078621 -0.4545869 0.6510412 -0.4612113 0.1442508 -0.8754861 -0.4401575 -0.80885 -0.3899014 -0.1470059 -0.8245765 0.5463177 -0.2168802 -0.697526 -0.6829498 -0.157292 -0.9486287 -0.2745229 -0.1604107 -0.8580781 -0.4878221 -0.08411759 -0.9642037 -0.2514668 -0.0844466 -0.9623377 -0.2584085 -0.01411139 -0.973684 -0.2274653 -0.01331657 -0.9770492 -0.2125974 -0.9718235 -0.1947718 0.1327526 -0.1930578 -0.9793376 -0.06022077 -0.5494628 -0.8306645 0.08992809 -0.3981004 -0.9128952 -0.09021371 -0.04735666 -0.9958482 0.07774186 -0.8016489 -0.5348778 -0.2669546 -0.8728888 -0.4593498 0.1645085 -0.7900128 -0.612921 -0.01441055 -0.5538948 -0.8323479 -0.01994526 -0.5542296 -0.8321344 -0.01954311 -0.1923843 -0.9810339 -0.02368462 -0.1930683 -0.9809158 -0.02299702 -0.4201069 -0.8995583 0.1196035 -0.4865483 -0.7931554 0.3662995 -0.4108388 -0.8467454 0.337985 -0.5891959 -0.742263 0.3192085 -0.3243713 -0.9109825 0.2547432 -0.358972 -0.8980734 0.2541719 -0.2406125 -0.9444125 0.2240332 -0.2731139 -0.9363354 0.2206465 -0.186334 -0.9621621 0.1988059 -0.2148301 -0.9553733 0.2027558 -0.1350432 -0.9739388 0.1822267 -0.1597803 -0.9714511 0.1753656 -0.05350494 -0.987509 0.1482001 -0.06948167 -0.9879521 0.1382865 0.0270214 -0.9931861 0.1133638 0.02125698 -0.9947158 0.1004424 0.06986051 -0.9936832 0.0878247 0.06914424 -0.993783 0.08726137 0.04655253 -0.9945821 0.09294867 0.006498098 -0.9977247 0.06710702 -0.03990721 -0.9960644 0.07913959 -0.1034513 -0.9927808 0.06069839 -0.1280611 -0.9895023 0.06697553 -0.2124552 -0.9756208 0.0550177 -0.1971818 -0.9790301 0.05118113 -0.2766658 -0.9589309 0.0625118 -0.2393656 -0.9694721 0.05317872 -0.3482791 -0.9360579 0.04997336 -0.610255 -0.7824289 0.1240725 -0.4873394 -0.8668923 0.1048722 -0.5433759 -0.83551 -0.08164399 -0.8813672 -0.4394351 0.1734614 -0.686053 -0.6697136 0.2842797 -0.772933 -0.5889205 0.2361088 -0.5771055 -0.8134562 0.07237601 -0.5159052 -0.8526722 0.08241319 -0.1980252 -0.9783122 -0.06075769 -0.3246629 -0.9455364 0.02355933 -0.4925406 -0.8693216 0.04103481 -0.02434349 -0.9325163 -0.3603066 -0.7958595 -0.585406 -0.1546204 -0.7781559 -0.6230111 -0.07956641 -0.7449468 -0.6311907 -0.2159924 -0.7187736 -0.6839755 -0.1246677 -0.6330143 -0.7523767 -0.1822698 -0.6315829 -0.7527951 -0.1854793 -0.5739958 -0.8057637 -0.1458561 -0.4999065 -0.8536992 -0.1459147 -0.5043478 -0.8500171 -0.1520006 -0.2904151 -0.9051816 -0.3103312 -0.1749494 -0.9343329 -0.3105073 -0.2080397 -0.8952586 -0.3939945 -0.1339462 -0.9667615 -0.2177857 -0.4215431 -0.8938442 -0.1527882 -0.3580104 -0.9150829 -0.1856124 -0.28595 -0.9489253 -0.1333165 -0.1988654 -0.9709112 -0.1333572 -0.1600152 -0.9813061 -0.1069277 -0.03374022 -0.9937191 -0.1066971 0.007511317 -0.9977998 -0.06587308 -0.7754607 -0.6139522 -0.1473895 -0.7140328 -0.6842824 -0.1480365 -0.7711497 -0.6136022 -0.1697662 -0.7705816 -0.6247427 -0.1260989 -0.798861 -0.5852226 -0.1390523 -0.7989975 -0.5850678 -0.1389207 0.3980675 -0.05230075 -0.9158641 0.2244136 -0.02215719 -0.9742422 0.4211698 -0.02973401 -0.9064944 0.3856073 -0.1585512 -0.9089381 0.4604077 -0.1287142 -0.8783266 0.36541 -0.272864 -0.8899556 0.4769951 -0.2501471 -0.842557 0.3149408 -0.4033758 -0.8591277 0.5042008 -0.4463599 -0.7392865 0.2320432 -0.01319503 -0.972616 0.2191447 -0.06135362 -0.9737615 0.2454227 -0.05027782 -0.9681116 0.2120012 -0.1013086 -0.9720042 0.2527664 -0.09408557 -0.962942 0.2009334 -0.1443429 -0.9689123 0.2707306 -0.1687875 -0.9477425 0.4083604 -0.5050324 -0.7603843 0.2536989 -0.1783428 -0.9507002 0.4068366 -0.5055003 -0.76089 0.4342552 -0.4897966 -0.7559906 0.4282556 -0.4760968 -0.7680683 0.4872701 -0.4483557 -0.7493632 0.4836936 -0.4341853 -0.7599498 0.5235595 -0.4192143 -0.7417175 0.5221799 -0.4163856 -0.7442791 0.5627016 -0.4011141 -0.722824 0.5618394 -0.388288 -0.7304581 0.6297904 -0.3693638 -0.6833261 0.630347 -0.3597141 -0.6879451 0.2575307 -0.177429 -0.9498405 0.3022862 -0.1519885 -0.9410221 0.3191522 -0.1820634 -0.930051 0.4119585 -0.138477 -0.9006189 0.4218538 -0.1627105 -0.8919444 0.4787771 -0.1412369 -0.8665014 0.4815015 -0.1455746 -0.8642711 0.5381957 -0.1243726 -0.8335928 0.5423461 -0.141808 -0.828101 0.6348116 -0.1160871 -0.7638967 0.6362276 -0.1279469 -0.7608181 0.9765918 -0.06103271 -0.2062609 0.97659 -0.06131142 -0.2061868 0.9909959 -0.05899065 -0.1201975 0.9908995 -0.06079542 -0.1200932 0.9027555 -0.3299362 -0.2759976 0.8828941 -0.3267259 -0.3372659 0.9306742 -0.23938 -0.2766637 0.9278112 -0.1872189 -0.3226695 0.9528118 -0.163981 -0.2554603 0.9150665 -0.1786761 -0.3615636 0.9208353 -0.1805773 -0.3456219 0.99271 -0.07520902 0.09418261 0.9843629 -0.1472544 0.09667545 0.9971743 -0.07308298 -0.01738935 0.9935718 -0.1126489 0.01119244 0.9934219 -0.04787003 -0.1040272 0.9910749 -0.1021509 -0.08565026 0.9760302 -0.05334728 -0.2109957 0.9794747 -0.09690195 -0.1767468 0.9606534 -0.06969422 -0.268864 0.9568706 -0.05808782 -0.2846482 0.901422 -0.3333776 -0.2762209 0.8932113 -0.3331939 -0.3019195 0.8885295 -0.3517692 -0.294574 0.8813098 -0.3492425 -0.3183127 0.8737853 -0.3806564 -0.3026551 0.8765276 -0.3846798 -0.2893456 0.8743078 -0.3980617 -0.2777277 0.8785967 -0.4124119 -0.2407997 0.8836489 -0.3982475 -0.2460966 0.8827104 -0.4298982 -0.1897628 0.8935547 -0.3947193 -0.2139085 0.8870092 -0.4374417 -0.1478498 0.9291362 -0.3430483 -0.1379279 0.5486647 -0.7423371 -0.3845813 0.6026875 -0.6989208 -0.3850684 0.6006104 -0.708055 -0.371383 0.591982 -0.7125889 -0.3765295 0.5955348 -0.7042248 -0.3865304 0.5997136 -0.7019712 -0.3841615 0.6012625 -0.704042 -0.3778997 0.5974229 -0.7096573 -0.3734601 0.5985676 -0.7083408 -0.3741258 0.5973961 -0.7116265 -0.3697372 0.5970338 -0.7121319 -0.3693494 0.5878415 -0.7039915 -0.3985455 0.5858414 -0.7056321 -0.398589 0.5994088 -0.697642 -0.3924346 0.5856766 -0.7068371 -0.3966918 0.5893235 -0.7016428 -0.4004938 0.5794682 -0.7080888 -0.4035183 0.5864874 -0.7212349 -0.3685823 0.5743057 -0.7081019 -0.4108098 0.5733081 -0.7093515 -0.4100468 0.5561451 -0.7291113 -0.3988725 0.5670387 -0.7237485 -0.3932623 0.561192 -0.7237722 -0.4015191 0.5739863 -0.7150986 -0.3989659 0.5660066 -0.7160833 -0.4084866 0.5692864 -0.7143258 -0.4070034 0.5528985 -0.7390012 -0.3849421 0.5499195 -0.741053 -0.3852648 0.5596397 -0.7381823 -0.3766834 0.5563038 -0.7405279 -0.3770207 0.5625113 -0.7377813 -0.3731752 0.5630835 -0.7374771 -0.3729135 0.5638267 -0.7370104 -0.3727132 0.5621513 -0.7377154 -0.3738476 0.5625422 -0.7328781 -0.3826698 0.5707581 -0.7253182 -0.3849009 0.5770871 -0.7111132 -0.4016073 0.5738012 -0.7136835 -0.4017564 0.5733572 -0.7138749 -0.4020498 0.5496963 -0.7321819 -0.4021737 0.5643931 -0.7241747 -0.3962721 0.5880371 -0.7043023 -0.3977069 0.5900233 -0.6991718 -0.4037714 0.5924111 -0.6940981 -0.4089953 0.5879855 -0.7121442 -0.383567 0.5934888 -0.7150868 -0.3693537 0.5934889 -0.7150868 -0.3693534 0.578086 -0.7066232 -0.4080445 0.5807717 -0.7040205 -0.4087291 0.5763008 -0.7123168 -0.4006024 0.5769066 -0.7114854 -0.4012073 0.5673549 -0.7297933 -0.3814581 0.5661884 -0.7355167 -0.3720833 0.5715324 -0.7322553 -0.3703415 0.5715317 -0.7322561 -0.3703413 0.5791269 -0.7269902 -0.368914 0.5751991 -0.7086108 -0.4086768 0.571659 -0.7101398 -0.4109838 0.5791261 -0.7269909 -0.3689136 0.5864863 -0.7212355 -0.3685826 0.5770865 -0.7111135 -0.401608 0.587224 -0.7021382 -0.4027034 0.5695441 -0.7018715 -0.4277802 0.4711142 -0.817605 -0.331019 0.4647511 -0.8199613 -0.3341705 0.4784049 -0.7738037 -0.4151589 0.5032728 -0.7718706 -0.3885 0.481324 -0.05076205 -0.8750718 0.5051303 -0.3273568 -0.7985494 0.5042011 -0.1786947 -0.8448962 0.5040868 -0.1853966 -0.8435193 0.50968 -0.1838349 -0.8404945 0.5137576 -0.1993678 -0.8344494 0.496692 -0.5330817 -0.6849241 0.4960733 -0.5353334 -0.683615 0.5246519 -0.5273191 -0.6683375 0.5260395 -0.5215383 -0.6717741 0.5433207 -0.5524324 -0.6321559 -0.6645199 -0.7380229 0.117199 -0.6725956 -0.7178065 0.1799138 -0.3524381 -0.9284271 0.1175189 -0.3608925 -0.9178454 0.165277 -0.691541 -0.7221506 0.01642209 -0.6446714 -0.7644456 -0.004667818 -0.1594095 -0.9871009 0.0148462 -0.1863017 -0.9822211 0.02309805 -0.1872022 -0.9822723 0.009826719 -0.2016851 -0.9793267 0.0155673 -0.2021384 -0.9793481 0.004172742 -0.2164644 -0.9762641 0.0071882 -0.2278186 -0.9732478 0.02979046 -0.1715167 -0.9809685 -0.09101021 -0.4538626 -0.88501 0.1037597 -0.4624069 -0.8858411 0.03827941 -0.5330648 -0.8439984 0.05923634 -0.5355638 -0.8441672 0.02351826 -0.5722218 -0.8191578 0.03927892 -0.57343 -0.8192017 0.009306073 -0.5189074 -0.854825 -0.003090441 -0.7113254 -0.6939368 0.1116599 -0.717705 -0.6938292 0.05916661 -0.8047934 -0.5872339 0.08639627 -0.8085665 -0.5874233 0.03397148 -0.849092 -0.5251273 0.05730807 -0.8509015 -0.5251681 0.0128616 -0.8868421 -0.461377 0.02534806 -0.6301245 -0.7673903 0.1185552 -0.633425 -0.7704757 0.07169389 -0.2254539 -0.9731204 0.04698288 -0.226144 -0.9735936 0.03121441 -0.04584175 -0.9971232 -0.06036609 -0.1222097 -0.9742281 -0.1895902 -0.1863654 -0.9632531 -0.1934207 -0.1676959 -0.9634283 -0.209007 -0.2449424 -0.946497 -0.2101117 -0.2458214 -0.9464771 -0.2091723 -0.3601655 -0.9040087 -0.2303241 -0.3645264 -0.9040934 -0.2230151 -0.4419972 -0.8808135 -0.1697233 -0.4425132 -0.8807845 -0.1685254 -0.5405564 -0.8321303 -0.1239275 -0.5436218 -0.832264 -0.1086825 -0.5842611 -0.8109243 -0.03226387 -0.07158446 -0.9957531 -0.05789244 -0.06168931 -0.9959022 -0.06613087 -0.09259724 -0.9938274 -0.06109821 -0.08764666 -0.9939447 -0.06627357 -0.1330834 -0.9891042 -0.06294304 -0.1304529 -0.9891592 -0.06742566 -0.1599873 -0.9861993 -0.04260462 -0.1567798 -0.9863771 -0.049802 -0.1933498 -0.9808022 -0.02535605 -0.1929192 -0.9808279 -0.02754873 -0.2078933 -0.9781436 0.003943502 -0.2079839 -0.9781198 0.004940867 -0.225821 -0.9735864 0.03368318 -0.5889259 -0.8060387 0.05888915 -0.6298418 -0.7765383 -0.01696115 -0.6266111 -0.7701926 0.1190053 0.1601983 -0.9802875 -0.1156424 0.4493815 -0.8389021 -0.3070827 0.469745 -0.8289528 -0.3036069 0.4788762 -0.826511 -0.2959009 0.4839058 -0.82586 -0.2894657 0.1506639 -0.9869806 -0.05630135 0.1998302 -0.973052 -0.1150552 0.222698 -0.9650602 -0.1380745 0.3964949 -0.8636482 -0.3112936 0.04414236 -0.9985767 -0.02993345 0.1701831 -0.9815289 -0.08740127 0.1550289 -0.9818172 -0.1095497 0.3495281 -0.9021294 -0.2529679 0.4105453 -0.8630135 -0.2943814 0.9308992 -0.3652167 -0.006599426 0.9227334 -0.3854373 -0.001135408 0.6579889 -0.7530139 -0.004573345 0.6480895 -0.7615632 -0.001219213 0.2371045 -0.9714822 -0.001975476 0.2328649 -0.9725088 -8.36184e-4 0.9024171 -0.430626 0.01430082 0.930916 -0.3652241 0.002645254 0.6251125 -0.7804773 0.009469926 0.6579915 -0.7530196 0.002981305 0.2231905 -0.9747671 0.003897726 0.2371031 -0.9714828 0.001884818 0.05597823 -0.5930368 -0.8032272 0.5541901 -0.4785522 -0.6810735 0.4347489 -0.5274583 -0.7299185 0.4265345 -0.5136904 -0.7444398 0.3064512 -0.5116793 -0.8026655 0.2926031 -0.5049105 -0.8120645 0.7234212 -0.427962 -0.5417661 0.6062472 -0.4857366 -0.6297018 0.563077 -0.4838677 -0.6699376 0.637747 -0.5497404 -0.5395038 0.7559628 -0.4569926 -0.4686984 0.7931143 -0.4574031 -0.4021846 0.874336 -0.3981048 -0.2775772 0.6495112 -0.7603204 0.006950855 0.9038229 -0.4240695 -0.05717742 0.7922277 -0.5246064 -0.3117107 0.8784421 -0.4328206 -0.2024995 0.8947361 -0.4309405 -0.1172078 0.9198226 -0.391219 -0.02956402 0.1339921 -0.9289684 -0.3450564 0.1416432 -0.8369863 -0.5285748 0.2739562 -0.9600625 0.05681788 0.2681924 -0.9629607 0.02792358 0.269966 -0.962566 0.0241881 0.2602607 -0.9655327 -0.003351688 0.2630388 -0.9647404 -0.009316265 0.2483897 -0.9680635 -0.03399413 0.2490075 -0.9676505 -0.04059225 0.2314803 -0.9708352 -0.06241732 0.2322844 -0.9700366 -0.0712248 0.210813 -0.9734481 -0.08920061 0.208965 -0.9731502 -0.09650075 0.185136 -0.976391 -0.1112892 0.1830396 -0.9758265 -0.1194114 0.1556069 -0.9792709 -0.1296726 0.1522434 -0.9791193 -0.1347131 0.09688037 -0.9844238 -0.1467105 0.1141539 -0.9868425 -0.1145021 0.2715433 -0.9606012 0.0592423 0.6545721 -0.755999 -9.21687e-4 0.6353642 -0.7658723 -0.09875279 0.6422345 -0.760893 -0.09261119 0.6055925 -0.7714686 -0.1951768 0.6166765 -0.7637473 -0.1907883 0.5607367 -0.7769546 -0.2862097 0.5716642 -0.7706189 -0.2816854 0.5010578 -0.7828751 -0.3688465 0.5151194 -0.7739515 -0.3683085 0.4284696 -0.7882416 -0.441689 0.4413158 -0.7815158 -0.4409915 0.3440281 -0.7942416 -0.5008244 0.3574422 -0.7857149 -0.5048636 0.2498667 -0.7997792 -0.5458203 0.2612181 -0.793904 -0.5490736 0.1050158 -0.8074403 -0.5805274 0.1875074 -0.5497989 -0.8139793 0.167225 -0.5766338 -0.7997058 -0.08599025 -0.8099537 -0.5801557 -0.8949463 -0.4451958 -0.02952742 -0.9017868 -0.4239242 -0.08407706 -0.8891054 -0.4414117 -0.1210265 -0.8587662 -0.4582411 -0.2292069 -0.8334464 -0.4870202 -0.2611101 -0.8144268 -0.4393367 -0.3790677 -0.7908276 -0.4559156 -0.408329 -0.724355 -0.473629 -0.5009844 -0.6925391 -0.5001436 -0.519852 -0.6353688 -0.4496763 -0.6277722 -0.5962965 -0.470292 -0.6505813 -0.5127093 -0.4755877 -0.7148046 -0.545837 -0.4519936 -0.7055239 -0.3776326 -0.5103014 -0.7726489 -0.4074731 -0.4786402 -0.7777336 -0.2456084 -0.4791347 -0.8426782 -0.2763097 -0.4593188 -0.8442034 -0.1003746 -0.5228831 -0.8464741 -0.1335471 -0.481541 -0.8661891 -0.1901883 -0.9810106 -0.03803449 -0.6358416 -0.7510655 0.1777814 -0.177031 -0.9813659 0.07470631 -0.1764684 -0.9829405 0.05183684 -0.180087 -0.9821577 0.05417567 -0.1717176 -0.9850023 0.01683956 -0.175624 -0.9842654 0.01944059 -0.1618818 -0.9866637 -0.01700508 -0.1685587 -0.9855719 -0.01536262 -0.147911 -0.9878128 -0.04846131 -0.1543258 -0.9869105 -0.04681098 -0.130226 -0.9886022 -0.07554358 -0.1383946 -0.9874312 -0.07633262 -0.1107493 -0.9889563 -0.09848928 -0.1170948 -0.9881696 -0.09904456 -0.08974432 -0.9892719 -0.1152698 -0.09488999 -0.9885098 -0.1176621 -0.0682128 -0.9895493 -0.1270403 -0.07034051 -0.9892764 -0.1280019 -0.04666537 -0.99005 -0.1327533 -0.0460487 -0.990159 -0.1321541 -0.08408451 -0.8110783 -0.5788626 -0.1800216 -0.8086032 -0.5601368 -0.1830677 -0.8099936 -0.5571325 -0.2731431 -0.8060985 -0.5249746 -0.2762326 -0.809002 -0.5188559 -0.3588854 -0.8062115 -0.4703447 -0.3622052 -0.8086231 -0.4636121 -0.4375739 -0.8040353 -0.4025623 -0.4388681 -0.8079153 -0.3932783 -0.5021975 -0.8039757 -0.3184664 -0.5033206 -0.8066701 -0.3097609 -0.5553086 -0.8005235 -0.2253769 -0.5533977 -0.8045246 -0.2156185 -0.5888808 -0.798834 -0.1228152 -0.5870637 -0.80144 -0.1142387 -0.6081926 -0.7935976 -0.01745504 -0.6033456 -0.7974271 -0.009169936 -0.5746459 -0.7841582 -0.2342605 -0.8853074 -0.3782451 0.2704836 -0.9023074 -0.4306209 0.02017581 -0.9309261 -0.3651354 -0.007265031 -0.2371203 -0.9714781 -0.002069652 -0.223977 -0.974585 -0.004301726 -0.6580307 -0.7529841 -0.003259181 -0.6270027 -0.7789472 -0.01043295 -0.9258067 -0.3779847 -0.003100633 -0.9039236 -0.4269546 -0.02513474 -0.2232296 -0.9747646 0.001658856 -0.2371205 -0.9714735 0.003626883 -0.6252088 -0.7804522 0.002894341 -0.6580125 -0.7529602 0.008390486 -0.9266926 -0.3758112 0.002632617 -0.9309358 -0.3651387 0.005711793 0.2152321 -0.9765612 -0.001881062 0.2163203 -0.9763169 -0.003290891 0.6058328 -0.7955827 -0.003892481 0.6084734 -0.7935329 -0.008123517 0.8841528 -0.4671719 -0.004925906 0.9039496 -0.4270653 0.02214503 0.8867707 -0.4622098 -1.22519e-4 0.8866904 -0.4622094 -0.0119493 0.5814775 -0.8132085 0.02399611 0.5262538 -0.8494327 0.03900235 0.1833483 -0.9828675 0.01884061 0.1836447 -0.9828811 0.01481556 0.2053322 -0.9786354 0.01056504 0.5110884 -0.8572107 0.06307619 0.5244403 -0.8492008 0.06181108 0.3752791 -0.9261814 0.03678989 0.1522716 -0.98808 0.02261352 0.2163535 -0.9763112 0.002784729 0.205531 -0.9786402 0.004521131 0.6085258 -0.7935125 0.005862891 0.5818777 -0.8131959 0.01144456 0.8600043 -0.5102264 0.007857799 0.8594132 -0.5103307 0.03116816 0.7972047 -0.6006537 0.06066191 0.797011 -0.6006475 0.06321489 0.6910218 -0.7159902 0.09923255 -0.9022244 -0.4301485 -0.03104048 -0.6253414 -0.7800929 -0.02008163 -0.2233009 -0.9747456 -0.002804815 -0.8962281 -0.4398267 -0.0576871 -0.8896288 -0.4403127 -0.1211838 -0.8837031 -0.4445322 -0.1464931 -0.8550474 -0.4418419 -0.2714217 -0.8403328 -0.4580496 -0.2898818 -0.7886742 -0.4609387 -0.4068518 -0.7779623 -0.4639453 -0.423709 -0.7083604 -0.4610187 -0.5344974 -0.6932243 -0.4730817 -0.5437223 -0.5944215 -0.4759853 -0.6481522 -0.5826917 -0.4791259 -0.6564365 -0.5380082 -0.4791914 -0.6934861 -0.5265063 -0.4819074 -0.7003973 -0.4073869 -0.4789977 -0.7775585 -0.3946813 -0.4876223 -0.7787498 -0.2721425 -0.4907132 -0.8277314 -0.2610371 -0.4924046 -0.8302996 -0.1331794 -0.4894086 -0.8618251 -0.1216244 -0.4974583 -0.8589196 -0.6193684 -0.7840689 -0.04023337 -0.6146484 -0.7844898 -0.08236056 -0.609607 -0.7861944 -0.1013799 -0.5920421 -0.7840263 -0.1865181 -0.5786434 -0.7906691 -0.2000361 -0.5419196 -0.7930096 -0.2783145 -0.5335096 -0.7942097 -0.2908582 -0.4880251 -0.7919296 -0.3669868 -0.4751714 -0.7968566 -0.3731377 -0.4069268 -0.79914 -0.4424771 -0.3978027 -0.8004055 -0.4484463 -0.3679928 -0.8004716 -0.4731034 -0.359131 -0.8015515 -0.4780588 -0.2794939 -0.7993412 -0.531918 -0.2693005 -0.8028515 -0.5318898 -0.1858179 -0.8052138 -0.5631185 -0.1774371 -0.8058879 -0.5648548 -0.09156095 -0.8036473 -0.5880203 -0.08261948 -0.8069121 -0.584865 -0.2213317 -0.9751328 -0.01132601 -0.2196568 -0.9752499 -0.0252695 -0.2177763 -0.9754323 -0.03324919 -0.2122251 -0.9751914 -0.06294602 -0.2074058 -0.9758177 -0.06901282 -0.1941096 -0.9762614 -0.09610021 -0.1907632 -0.9763751 -0.1014947 -0.1752853 -0.976109 -0.1283991 -0.1703466 -0.9765728 -0.1314826 -0.1460407 -0.976989 -0.1554498 -0.1423323 -0.9771125 -0.1580911 -0.1321772 -0.977144 -0.1664901 -0.1285693 -0.9772495 -0.1686816 -0.1009178 -0.9769694 -0.1880071 -0.09678244 -0.9773023 -0.1884502 -0.06748181 -0.977701 -0.1988644 -0.06403207 -0.9777705 -0.1996623 -0.03419798 -0.977479 -0.2082435 -0.03048503 -0.9777874 -0.2073705 -0.03223699 -0.9713535 -0.2354425 -0.1215318 -0.6644566 -0.7373788 -0.01565808 -0.7494575 -0.6618673 -0.102385 -0.8738136 -0.4753603 0.06651848 -0.9819644 -0.1769787 -0.08830094 -0.5641164 -0.8209603 -0.05897468 -0.6643311 -0.7451082 -0.06069749 -0.8347398 -0.5472893 -0.03875011 -0.8743809 -0.4836905 -0.02376532 -0.9811325 -0.1918703 -0.01525992 -0.9857819 -0.1673356 -0.03611022 -0.5004518 -0.865011 -0.02048444 -0.5643129 -0.8253068 -0.02490574 -0.8091353 -0.5870946 -0.01439642 -0.8349218 -0.5501802 -0.009961426 -0.97815 -0.2076617 -0.006143569 -0.9811915 -0.1929395 -0.07806801 -0.7641896 -0.6402497 8.3197e-5 -0.767534 -0.6410083 -0.04284745 -0.9724798 -0.2290137 -0.01117908 -0.973247 -0.2294895 -0.1151285 -0.7518322 -0.6492255 -0.03542029 -0.7648164 -0.6432738 -0.05676025 -0.9711192 -0.2317453 -0.02397203 -0.9728473 -0.2302032 0.2272251 -0.9735663 0.02318418 0.6378442 -0.7694705 0.03271299 0.2210637 -0.9737536 0.05417537 0.2243883 -0.9744803 0.006160259 0.2204469 -0.9747665 0.03511983 0.219693 -0.975015 -0.03287464 0.2142953 -0.9767299 -0.008722364 0.1981447 -0.9780089 -0.06509447 0.2016654 -0.9782236 -0.04909008 0.1840279 -0.978097 -0.09726262 0.185052 -0.9788897 -0.08677995 0.1604646 -0.9795532 -0.1213532 0.1622186 -0.9796023 -0.1185939 0.1399717 -0.9792767 -0.1463736 0.138536 -0.9789963 -0.1495792 0.1147107 -0.9792702 -0.1669472 0.1071469 -0.9790615 -0.1730844 0.08798974 -0.9787116 -0.1854226 0.07594585 -0.9772164 -0.1981934 0.05682688 -0.9772584 -0.2042959 0.03488981 -0.9764801 -0.212766 0.02156949 -0.9761785 -0.215894 -0.007224082 -0.9732481 -0.2296428 0.6205917 -0.7765656 0.1086827 0.6291091 -0.7772158 -0.01255434 0.6171637 -0.7846373 0.05876523 0.6127901 -0.781616 -0.1164685 0.5938749 -0.8027437 -0.05399316 0.5550157 -0.8075184 -0.1996792 0.5625103 -0.811134 -0.1601369 0.5153939 -0.8086417 -0.2836684 0.5155637 -0.8176084 -0.2563413 0.4535486 -0.8208898 -0.3470355 0.4575927 -0.8214901 -0.3402394 0.3982805 -0.8194365 -0.4121853 0.395618 -0.8164729 -0.4205455 0.3331578 -0.8186437 -0.4677909 0.3152755 -0.8168731 -0.483032 0.2615792 -0.8153131 -0.5165665 0.2365306 -0.8003798 -0.5508589 0.1820461 -0.8017474 -0.5692631 0.1307606 -0.7958425 -0.591216 0.08662009 -0.7946544 -0.6008507 0.02446895 -0.7668381 -0.6413741 0.6179802 -0.6732286 -0.4060342 0.6885281 -0.7158729 0.1159967 0.1524856 -0.9880822 0.0210185 0.2638772 -0.8540866 -0.4482244 0.3725982 -0.9262644 0.05661386 0.5108491 -0.8572207 0.06485414 0.018965 -0.9831894 0.1816019 0.6711779 -0.7320278 0.1168576 0.6809783 -0.7323036 -3.6079e-5 0.4258247 -0.8657969 0.2628102 0.3883188 -0.8356205 0.3885191 0.2562685 -0.9544718 0.1526766 0.007330834 -0.968608 0.2484852 -0.6767066 -0.7265428 0.1191805 -0.7684943 -0.638248 -0.04534453 -0.638627 -0.7003537 -0.3188422 -0.6339489 -0.7560902 -0.1625935 -0.5526149 -0.801725 -0.2277145 -0.4726163 -0.8405644 -0.2647363 -0.4007637 -0.8874854 -0.2275044 -0.3410339 -0.929247 -0.142113 -0.3138718 -0.9485526 -0.04162347 -0.2407941 -0.9522781 0.1875755 -0.1920987 -0.7885676 -0.584174 -0.7478212 -0.6412709 -0.1718583 -0.719215 -0.6936061 0.04050165 -0.6525929 -0.7217681 -0.2305936 -0.5920312 -0.8058153 0.01268315 -0.5491085 -0.7824217 -0.2937625 -0.1084786 -0.9223973 -0.3706963 -0.4996778 -0.8498122 -0.1677539 -0.1350413 -0.8389877 -0.5271278 -0.07125514 -0.9007953 -0.428358 -0.1324859 -0.8060815 -0.5767843 -0.04219156 -0.8769524 -0.4787217 -0.1136506 -0.7710523 -0.6265478 -0.00665158 -0.8306055 -0.5568218 -0.0980814 -0.7508072 -0.6531989 0.01511651 -0.7990724 -0.6010448 -0.06461191 -0.7293114 -0.6811242 0.03483253 -0.7543655 -0.65553 -0.03327733 -0.7247868 -0.6881691 0.05207973 -0.6543642 -0.7543841 -0.06356632 -0.7184662 -0.6926513 -0.007766485 -0.8244827 -0.5658339 -0.02606099 -0.9082962 -0.4175151 -0.5091732 -0.8066548 -0.3000848 -0.4381506 -0.8781142 -0.1921972 -0.4701994 -0.8293922 -0.3016971 -0.3738997 -0.905716 -0.1996939 -0.4060103 -0.8613671 -0.3052911 -0.2921403 -0.9274923 -0.233264 -0.3346858 -0.8952884 -0.294014 -0.2107847 -0.9479801 -0.238545 -0.2421607 -0.9269345 -0.2866193 -0.129698 -0.9571997 -0.2587419 -0.1516046 -0.9499541 -0.273136 -0.1160676 -0.9567129 -0.2668874 -0.06080144 -0.982827 -0.174225 0.8172025 -0.5499961 0.1722924 0.8126354 -0.3043508 0.4969851 0.6726409 -0.008575022 0.7399194 0.8493987 -0.4880203 0.2008933 0.8792757 -0.4436902 0.173243 0.9005166 -0.394633 0.1825785 0.9179781 -0.3607295 0.164896 0.9410114 -0.28105 0.1884372 0.9431403 -0.2770389 0.1836732 0.9675221 -0.1992859 0.1555193 0.9712525 -0.163037 0.173458 0.9867988 -0.06724214 0.147332 0.984186 -0.04056847 0.1724299 0.8224926 -0.2595214 0.506117 0.8402294 -0.2328525 0.4896882 0.8483468 -0.1983022 0.4909014 0.8666966 -0.1619744 0.4718067 0.8640791 -0.1244578 0.4877271 0.8793711 -0.07537126 0.4701337 0.8766522 -0.04837781 0.4786862 0.8863174 0.008708536 0.4629966 0.8780322 0.02978605 0.4776738 0.6736263 0.004765868 0.7390568 0.6778556 0.01120328 0.7351098 0.6795354 0.02331173 0.7332723 0.6836732 0.03132104 0.7291159 0.6803465 0.04686278 0.7313908 0.6835004 0.0571739 0.7277076 0.680678 0.07094955 0.729139 0.6828263 0.08314818 0.7258338 0.6753069 0.0967825 0.7311593 0.7506365 -0.2243925 0.6214441 0.7965435 -0.5734424 0.1915265 0.6478819 0.03598308 0.7608904 0.6479755 0.04026418 0.7605963 0.6470218 0.03949987 0.7614477 0.64663 0.04653972 0.7613827 0.6435614 0.04475057 0.7640852 0.6440796 0.05345177 0.7630888 0.6388699 0.05148333 0.7675904 0.6411761 0.05937659 0.7650933 0.633992 0.05763942 0.7711887 0.6375299 0.07043713 0.7671991 0.6289302 0.0698418 0.7743185 0.6351836 0.08544224 0.7676207 0.627516 0.086084 0.7738303 0.6352384 0.08782988 0.7673058 0.6273332 0.08864343 0.7736896 0.6374897 0.1091691 0.7626854 0.6340389 0.1100196 0.7654349 0.6472753 0.1316761 0.750797 0.6520764 0.1298871 0.7469443 0.6661622 0.1498644 0.7305948 0.6833104 0.1415648 0.7162725 0.6941418 0.1557754 0.7027812 0.7500721 -0.2273941 0.6210346 0.7327495 -0.2410702 0.6363673 0.7320752 -0.2461618 0.6351932 0.7040836 -0.2624115 0.6598534 0.7027332 -0.2678524 0.6591064 0.6743359 -0.278647 0.6838326 0.6726052 -0.2822826 0.6840459 0.6418734 -0.289637 0.7100063 0.6403228 -0.2928695 0.7100805 0.6039916 -0.2953748 0.740235 0.6037645 -0.2957416 0.7402738 0.5840713 -0.2941306 0.7565369 0.5847672 -0.2939801 0.7560575 0.5648552 -0.2918558 0.7718543 0.5677316 -0.2879897 0.7711956 0.5406338 -0.2812606 0.7928478 0.5466774 -0.2745096 0.7910678 0.5325796 -0.2692527 0.8024102 0.5402003 -0.2618821 0.7997508 0.5425718 -0.2630254 0.7977679 0.5478975 -0.2583865 0.7956411 0.671085 -0.0102517 0.7413096 0.6712231 0.058021 0.7389812 0.7618578 -0.3571657 0.5403754 0.8128451 -0.1623387 0.5594006 0.7907314 -0.4529884 0.4117588 0.7797834 -0.4629662 0.4214264 0.7760156 -0.471922 0.4184369 0.7436279 -0.4972354 0.4469616 0.7378712 -0.5118681 0.4399287 0.6875103 -0.5410695 0.4843279 0.6789762 -0.5574455 0.4777509 0.6302052 -0.5761788 0.5204416 0.6205855 -0.5887271 0.5179519 0.5692342 -0.6008034 0.5612555 0.5568237 -0.6163247 0.5568584 0.4966161 -0.620481 0.6069399 0.4839791 -0.6332628 0.6039392 0.4541828 -0.6311278 0.6288051 0.4475851 -0.6321755 0.6324728 0.4174561 -0.6286134 0.6561827 0.4061585 -0.6382372 0.6539791 0.3583215 -0.6263791 0.6922824 0.3500149 -0.6322743 0.691172 0.318017 -0.6203781 0.7169353 0.311966 -0.624036 0.7164191 0.2979472 -0.6172914 0.7281338 0.2914422 -0.6207022 0.7278669 0.7618223 -0.6291971 0.1540707 0.7326815 -0.656259 0.1802836 0.7230615 -0.6686282 0.1735473 0.6789389 -0.70279 0.2124341 0.6633798 -0.7218296 0.1972036 0.5961804 -0.7607671 0.2565197 0.5755324 -0.7815168 0.2408193 0.5121846 -0.8061501 0.2962923 0.4912719 -0.8220463 0.2879092 0.4258213 -0.8371765 0.3432375 0.3980427 -0.8563681 0.3289313 0.3220897 -0.8616574 0.3921795 0.2930052 -0.8776246 0.3793719 0.2574998 -0.8755012 0.4088907 0.2434549 -0.8764596 0.4153894 0.2078419 -0.8717908 0.4436016 0.1785236 -0.8845739 0.4308809 0.1174635 -0.8694962 0.4797694 0.09146028 -0.8781998 0.4694682 0.04692816 -0.8616759 0.5052846 0.02430969 -0.8673924 0.4970307 -0.003562927 -0.8539916 0.5202748 -0.02399271 -0.8577412 0.5135216 0.4800447 -0.8166763 -0.3203076 -0.1474119 -0.9744399 0.169519 0.2540941 -0.9566485 -0.1423375 0.1559222 -0.9852454 -0.07056879 0.1250822 -0.9909368 -0.04897832 0.07565528 -0.9970177 -0.01523911 0.02385604 -0.999597 0.0153892 -0.02455151 -0.9988116 0.04210317 -0.07474625 -0.9951167 0.06446516 0.3890703 -0.8822844 -0.2649505 0.4089044 -0.8733134 -0.2648037 0.3902439 -0.8842024 -0.2567021 0.3843732 -0.8887397 -0.2497979 0.5044668 -0.7922894 -0.3432067 0.4171741 -0.8664038 -0.2744274 0.3928 -0.8805996 -0.2650519 0.5006181 -0.792237 -0.3489156 0.493773 -0.7994958 -0.3420449 0.5871016 -0.6630621 -0.4643927 0.5880448 -0.6615694 -0.4653271 0.4582635 -0.8267763 -0.3262444 0.5443659 -0.7553464 -0.3648529 0.4729505 -0.8215934 -0.3182802 0.4626132 -0.8290584 -0.3140878 0.4735018 -0.8184033 -0.3255952 0.4523971 -0.8307587 -0.3243099 0.5455666 -0.7454754 -0.3829147 0.05968272 -0.9965519 -0.05764049 0.06377738 -0.9960757 -0.06136643 -0.09570479 -0.9927628 0.07254588 -0.007928729 -0.9991706 0.03994286 -0.002860069 -0.9998667 0.01608449 -0.01816517 -0.9995703 0.02300834 0.1554163 -0.9852104 0.07215511 -0.1588628 -0.9820414 0.1017714 -0.1481226 -0.9847133 0.09164977 0.2691593 -0.9415749 -0.2024602 0.2731021 -0.9400122 -0.2044323 0.2814388 -0.9400643 -0.1925396 0.2909352 -0.9360534 -0.1978905 0.3235772 -0.9335426 -0.1542597 0.4808895 -0.8166195 -0.3191834 0.557519 -0.8135827 -0.1650929 0.3908523 -0.839944 -0.3764687 0.3011346 -0.9408068 -0.155566 0.004426896 -0.9906461 -0.1363844 0.1652103 -0.9844767 -0.05925691 -0.1627114 -0.9841438 0.07061219 -0.1071172 -0.9913623 0.07567542 0.01029974 -0.9837164 -0.1794326 0.05709183 -0.6543345 -0.754047 0.03585916 -0.6188188 -0.7847149 0.03718113 -0.8252152 -0.5635935 0.04948282 -0.8564075 -0.5139239 0.02206152 -0.9094921 -0.4151354 0.01392692 -0.9853259 -0.1701151 0.009258449 -0.9821116 -0.1880724 0.01295322 -0.9837102 -0.1792945 0.02216154 -0.8428217 -0.5377365 0.03400814 -0.8565964 -0.5148653 0.03090929 -0.5839945 -0.811169 0.05217373 -0.6187987 -0.7838152 0.2234383 -0.9746624 -0.01042205 0.625187 -0.7795285 -0.03842759 0.9013495 -0.4295374 -0.05537861 0.2221631 -0.9750089 -0.001190066 0.2187051 -0.9752359 -0.03290903 0.2190494 -0.9754461 -0.02285444 0.2099766 -0.9751744 -0.07031893 0.2093005 -0.976108 -0.0583676 0.1886049 -0.9768625 -0.1008357 0.193013 -0.9770603 -0.08999562 0.1691926 -0.9768304 -0.1310589 0.172631 -0.9778428 -0.1184144 0.1395507 -0.9785909 -0.1512793 0.1474632 -0.9787915 -0.1422036 0.1281926 -0.9789414 -0.1588725 0.136694 -0.979134 -0.1503708 0.1002193 -0.9789428 -0.1778404 0.1079612 -0.9799229 -0.167617 0.06668978 -0.9806119 -0.1842629 0.07676106 -0.9807937 -0.1793087 0.03552651 -0.9806191 -0.1926761 0.04492872 -0.9814667 -0.1862918 0.00903362 -0.9820832 -0.1882314 0.0184102 -0.9820664 -0.1876344 0.6210052 -0.7836488 -0.01572436 0.6119221 -0.7842821 -0.1022403 0.6120714 -0.7869891 -0.07756859 0.5849343 -0.7840145 -0.2077811 0.580733 -0.7945815 -0.1771708 0.5258896 -0.7979464 -0.2944857 0.5360167 -0.8007177 -0.2674651 0.4689816 -0.7977801 -0.3789502 0.4752264 -0.8092554 -0.3453488 0.3861212 -0.8126008 -0.4365667 0.4051184 -0.8154064 -0.4135114 0.3539057 -0.8155552 -0.4578434 0.3743256 -0.8182985 -0.4361971 0.2733042 -0.8155818 -0.5100308 0.2913795 -0.8266564 -0.481391 0.1792216 -0.8298192 -0.5284695 0.2038227 -0.8323441 -0.5154219 0.0902304 -0.829876 -0.5506039 0.1135305 -0.8394532 -0.5314408 0.01558798 -0.8426544 -0.5382293 0.03833204 -0.8427278 -0.5369735 0.8978212 -0.4396745 -0.02456849 0.8855454 -0.4403946 -0.1478579 0.8871292 -0.4470728 -0.1145773 0.8445314 -0.4434866 -0.3001444 0.8439566 -0.4693253 -0.2597519 0.7686113 -0.4734464 -0.4302155 0.783511 -0.4803676 -0.3941543 0.6837113 -0.4765406 -0.5526735 0.6966668 -0.5049086 -0.5096299 0.570333 -0.5092576 -0.6444976 0.5969029 -0.5164047 -0.6140304 0.5238654 -0.5165394 -0.6773125 0.5522782 -0.5235111 -0.6487873 0.4034548 -0.5196213 -0.7531387 0.4306455 -0.547393 -0.7175692 0.2681982 -0.551819 -0.7896616 0.3017467 -0.5583504 -0.7727832 0.1345722 -0.5545547 -0.8211939 0.1671978 -0.5788317 -0.7981221 0.02379167 -0.5835732 -0.811712 0.05495667 -0.5839151 -0.8099524 -0.1794641 -0.9803661 0.08170133 -0.1816434 -0.9799708 0.0816276 -0.1798061 -0.9802853 0.08191889 -0.1776635 -0.9806084 0.08272176 -0.1776768 -0.9806025 0.08276432 -0.1882648 -0.9791223 0.07665526 -0.1935649 -0.9777861 0.08041822 -0.1852478 -0.9794207 0.08011615 -0.1826309 -0.9618955 0.2034779 -0.1821179 -0.9620468 0.2032217 -0.1983154 -0.968643 0.1496729 -0.190733 -0.9703633 0.1483775 -0.429485 -0.9030126 0.01053804 0.0543363 -0.9973536 -0.04830533 -0.1194864 -0.9926846 0.01732939 -0.434544 -0.9005592 0.01283818 -0.6550714 -0.7548817 -0.03217178 -0.7036252 -0.7020194 0.1099114 -0.700735 -0.7110172 0.05852514 -0.6589068 -0.7511487 0.04021853 -0.6667253 -0.744857 -0.02579426 -0.6259372 -0.7780501 -0.05329871 -0.6195456 -0.7784986 -0.1005152 -0.5115782 -0.8516669 -0.1138047 -0.5363098 -0.835378 -0.1204807 -0.4755139 -0.85931 -0.1883422 -0.449834 -0.8749021 -0.1794315 -0.3906281 -0.8999614 -0.1935957 -0.3251424 -0.9315296 -0.1628963 -0.1581149 -0.9789942 -0.1287251 -0.1587313 -0.9625393 -0.2198244 -0.1563214 -0.9616979 -0.2251684 -0.1331841 -0.9683598 -0.2110483 -0.1640505 -0.9654141 -0.2026403 -0.1605808 -0.970395 -0.1804093 -0.143997 -0.9738617 -0.1756658 -0.1313447 -0.9842182 0.1185879 -0.2090384 -0.9752935 0.07145428 -0.3117098 -0.9303886 -0.1929103 -0.2189584 -0.9622804 -0.1614737 -0.2530596 -0.9375368 -0.2387167 -0.2839727 -0.9344933 -0.214667 -0.1814803 -0.9693548 -0.1655789 -0.1055474 -0.9725727 -0.2072732 -0.161785 -0.9613898 -0.2226104 -0.1555487 -0.9615559 -0.2263071 -0.2372792 -0.9697716 0.05693662 -0.243092 -0.9681808 0.05943477 -0.2676976 -0.9620547 0.05280917 -0.275644 -0.9595247 0.05773091 -0.3047437 -0.95112 0.05002307 -0.3139032 -0.9476166 0.05905604 -0.3359913 -0.9398469 0.06162458 -0.3445704 -0.9358869 0.07339632 -0.3664193 -0.9272592 0.07698917 -0.3743642 -0.9223906 0.09511661 -0.3877686 -0.916027 0.1026176 -0.3937383 -0.910511 0.126254 -0.4041743 -0.904931 0.1332034 -0.4040374 -0.8376278 0.367605 -0.3529986 -0.9213933 0.1625622 -0.08357071 -0.920984 -0.380532 0.34739 -0.7995646 -0.489915 0.2421392 -0.7927119 -0.5594431 0.2406623 -0.7877762 -0.5670014 0.1468238 -0.7679641 -0.6234373 0.1283258 -0.7559916 -0.6418796 0.02801084 -0.7581173 -0.6515164 0.6747094 -0.7365939 0.04686719 0.6380489 -0.7668787 -0.06921595 0.6172223 -0.7860436 -0.0342378 0.6120108 -0.7690598 -0.1843636 0.6113728 -0.7706897 -0.1796131 0.5194563 -0.8143575 -0.2588186 0.5212292 -0.8042641 -0.285446 0.4752708 -0.8053017 -0.3544104 0.4519473 -0.7942504 -0.406091 0.3915789 -0.8204653 -0.4165365 0.3390665 -0.789113 -0.5121862 0.6867473 -0.7201374 0.09889578 0.6930369 -0.7169822 0.0750761 0.3980094 -0.9112002 0.1063138 0.01470154 -0.738402 -0.6742006 -0.08582752 -0.9188404 -0.3851833 0.01220846 -0.9351834 -0.3539535 -0.008806049 -0.9375227 -0.3478127 0.08403199 -0.948963 -0.3039867 0.06669825 -0.9524209 -0.2973984 0.1431481 -0.9596357 -0.2420909 0.1363 -0.9606087 -0.2421848 0.2009482 -0.962507 -0.1822097 0.2027386 -0.9621053 -0.1823472 0.2534838 -0.9605619 -0.1143103 0.2632595 -0.9582522 -0.1115668 0.3008258 -0.9526669 -0.04392659 0.321574 -0.9461086 -0.03832489 0.3454129 -0.9378501 0.03357255 0.3660497 -0.9293882 0.04738372 0.3797147 -0.9159489 0.1298252 0.01891142 -0.9872981 0.15775 0.008083641 -0.9856725 0.1684764 0.001968681 -0.9912127 0.1322638 -0.005707621 -0.9896715 0.1432405 -0.01832044 -0.994331 0.1047403 -0.02534717 -0.9930049 0.1153203 -0.0439617 -0.9956685 0.08192563 -0.045529 -0.9950591 0.08822929 -0.06750637 -0.9959987 0.05856251 -0.06816273 -0.9958087 0.06098455 -0.09219628 -0.9949839 0.03882098 -0.09253793 -0.9950475 0.03629446 -0.1159309 -0.9930705 0.01926225 -0.1165726 -0.9931289 0.01028466 -0.1400266 -0.9901475 -6.80514e-4 -0.1447384 -0.9894164 -0.01030457 -0.1725301 -0.9848169 -0.01921468 -0.1738106 -0.9845283 -0.02222973 -0.1951766 -0.9804493 -0.02500641 -0.1940818 -0.9806813 -0.02442657 -0.1487146 -0.9103485 -0.3861992 -0.1540654 -0.9084115 -0.3886546 -0.08261924 -0.7205025 -0.6885132 -0.06835198 -0.7247868 -0.6855742 -0.2016932 -0.9764649 -0.07639414 -0.03990167 -0.999069 -0.01640218 -0.2905555 -0.8551571 -0.4292832 -0.1808438 -0.9037784 -0.3879179 -0.1375149 -0.7639838 -0.6304114 -0.212894 -0.7089326 -0.672377 -0.09467607 -0.6431463 -0.759868 -0.08696269 -0.5464808 -0.8329443 -0.03591012 -0.4956717 -0.8677673 -0.03881072 -0.4879217 -0.8720242 -0.03268837 -0.8409174 -0.5401756 -0.05253666 -0.8122172 -0.5809847 -0.1204952 -0.986612 -0.1098994 -0.04741501 -0.9928056 -0.1099499 -0.05641639 -0.9896255 -0.1321306 -0.069691 -0.5755622 -0.8147829 -0.09931182 -0.8356769 -0.540168 -0.1023659 -0.8410111 -0.5312454 -0.1170201 -0.9886225 -0.09450948 -0.1866721 -0.977862 -0.09454864 -0.1197105 -0.6383593 -0.7603728 -0.1202399 -0.6364635 -0.7618771 -0.143153 -0.7628924 -0.630478 -0.1437826 -0.8347696 -0.5314944 -0.1678462 -0.8862163 -0.4317967 -0.1827179 -0.9801944 -0.07637476 -0.1240561 -0.9267998 -0.3544749 0.04987913 -0.6192193 -0.7836323 0.05373072 -0.6288086 -0.7757015 0.05211156 -0.8010028 -0.5963882 0.08308649 -0.8604794 -0.5026649 0.07117152 -0.7125701 -0.6979818 0.06169557 -0.6604179 -0.7483595 0.05284404 -0.6344189 -0.7711811 0.05598258 -0.6274243 -0.7766626 0.0525012 -0.6243186 -0.7794036 0.09775292 -0.9930123 -0.06611472 0.09736853 -0.9040432 -0.4162034 0.08949571 -0.9892044 -0.1160402 0.09875971 -0.9883213 -0.11605 0.09909272 -0.9884667 -0.1145172 0.09346318 -0.9337813 -0.3454233 0.09164458 -0.8596101 -0.5026647 0.08457791 -0.8440489 -0.5295547 0.05924546 -0.5927082 -0.8032354 -0.04170966 -0.9488953 -0.3128226 0.1968728 -0.9660453 -0.1673251 0.02018666 -0.981404 -0.1908894 0.09996086 -0.9715383 -0.2147588 -0.1429396 -0.9704924 -0.1941983 -0.1209514 -0.9902681 -0.06884747 -0.5329518 -0.3391511 0.7752026 -0.05702596 -0.9537601 -0.2951096 -0.0913096 -0.9647716 -0.2467352 -0.4037955 -0.9022307 0.1514233 -0.1584253 -0.9703466 -0.1825618 -0.1499335 -0.9673553 -0.2043128 0.07980448 -0.9967952 0.005553126 0.08854359 -0.9945746 -0.05460214 0.1109175 -0.9869675 -0.1165877 0.1285107 -0.9718158 -0.1976342 0.07575839 -0.9906069 -0.1138375 0.08520984 -0.986572 -0.1393385 0.02672082 -0.9939936 -0.1061266 0.00806266 -0.9967104 -0.08064395 -0.02302521 -0.9968315 -0.07613623 -0.08458405 -0.824335 0.5597475 -0.08407878 -0.9963282 0.01615035 -0.05472439 -0.9774358 -0.2040212 -0.04643434 -0.9617152 -0.2700883 -0.06818246 -0.9812203 -0.1804384 -0.05214041 -0.9658377 -0.2538487 -0.0906428 -0.9829616 -0.1599076 -0.06613153 -0.9717658 -0.2264901 -0.1254359 -0.9793882 -0.1583182 -0.09809029 -0.9756979 -0.1959385 -0.1516325 -0.9738568 -0.1691467 0.5641077 -0.7052022 -0.4295026 0.5608991 -0.7068969 -0.4309166 0.5490154 -0.7288441 -0.4091069 0.5405393 -0.732045 -0.4146413 0.5104181 -0.780897 -0.3601016 0.4949522 -0.7859432 -0.3705614 0.4470307 -0.8460283 -0.2905164 0.4222182 -0.8524238 -0.3083921 0.1775825 -0.980561 -0.08345502 0.2817424 -0.944305 -0.1700275 0.3092076 -0.9332963 -0.1826168 0.3164988 -0.9302155 -0.1858157 0.3267489 -0.928277 -0.1775869 -0.264355 -0.9638364 0.03370445 -0.2550344 -0.9662016 0.03757697 -0.2550318 -0.9662026 0.03756767 -0.255013 -0.9662079 0.03755944 -0.2549836 -0.9662132 0.03762269 -0.2842455 -0.9583278 0.02850598 -0.09189188 -0.9952856 0.03102284 -0.294457 -0.9556425 -0.00652486 -0.06280875 -0.9979977 -0.007471919 -0.1805008 -0.9834892 -0.01297867 -0.04163759 -0.9990497 -0.01288634 -0.1229861 -0.991932 -0.03074955 0.008771538 -0.9995762 -0.02775943 -0.05344444 -0.9965266 -0.06386435 0.0607993 -0.9966953 -0.05387133 0.005635738 -0.9973275 -0.07284271 0.1042201 -0.9927331 -0.06016105 0.07437211 -0.9914013 -0.1076682 0.1493276 -0.9854781 -0.08083456 0.1234947 -0.987587 -0.09706294 0.1639434 -0.9832594 -0.07952153 0.155252 -0.9825568 -0.1023665 -0.8200134 4.96672e-4 0.5723441 -0.8200123 0 0.572346 -0.8200126 -6.78453e-5 0.5723454 -0.8200114 -3.85576e-4 0.5723472 -0.9746257 -0.1152074 -0.1919174 -0.9706814 -0.0065701 -0.2402802 -0.9635841 0.02166056 -0.2665266 -0.9641065 -0.005109906 -0.2654668 -0.9631738 0 -0.2688797 -0.9622853 -0.2017166 -0.1825304 -0.978397 0.2005568 -0.05016267 -0.9973111 0 -0.07328432 -1 -2.18244e-5 0 0.03452783 -0.98903 0.1436235 0.0666278 -0.9870961 0.1456091 0.002521395 -0.8520433 0.5234653 0.05668866 -0.8486225 0.5259528 -0.03073191 -0.5756037 0.8171511 0.02171099 -0.5722503 0.8197916 -0.04336184 -0.204186 0.9779714 -0.01163709 -0.2014374 0.9794323 0.07376158 -0.9867925 0.1442213 0.09042179 -0.9853108 0.1448675 0.04683709 -0.850264 0.5242685 0.09254842 -0.8458805 0.5252819 0.00449264 -0.5752125 0.8179917 0.06253051 -0.569715 0.8194601 -0.02181577 -0.2050581 0.9785067 0.02303111 -0.1999039 0.9795449 -0.9205082 0.1324363 0.367594 -0.9022478 -0.1924964 0.3858681 -0.9785346 -0.1538932 0.1370657 -0.978088 -0.2056198 0.03262591 -0.9331281 -0.3527042 0.06979888 -0.9480198 -0.3147083 0.04708808 -0.960929 -0.2767165 0.006588578 -0.9191753 -0.3865672 0.0753836 -0.9175078 -0.3974131 -0.01556742 -0.9128707 -0.0212028 0.407698 -0.9110608 -0.02736812 0.4113629 -0.8962848 -0.05301499 0.440299 -0.8975509 -0.0495451 0.4381184 -0.8505843 -0.05582153 0.5228675 -0.8404155 -0.07413452 0.5368481 -0.7723993 -0.08301597 0.6296886 -0.7610073 -0.09682208 0.6414777 -0.6784982 -0.1144972 0.7256243 -0.6650491 -0.1260493 0.7360851 -0.5645774 -0.1406011 0.8133165 -0.5589493 -0.1439329 0.8166145 -0.4607294 -0.1684489 0.8714088 -0.4480991 -0.1740333 0.8768806 -0.3504985 -0.1793798 0.9192246 -0.2958464 -0.1936589 0.9353989 -0.2295669 -0.193869 0.9537892 -0.1265004 -0.2062854 0.9702804 -0.1163994 -0.2046498 0.9718898 -0.7900032 -0.4150657 0.4512377 -0.9469101 -0.1262064 0.2956914 -0.9436211 -0.1329033 0.3031765 -0.9286555 -0.1731094 0.3280735 -0.9199413 -0.1735353 0.3515588 -0.8779421 -0.2491124 0.4088531 -0.863834 -0.2510696 0.4367553 -0.8057239 -0.3223494 0.4968904 -0.786104 -0.3284109 0.5236285 -0.7098289 -0.3949463 0.5832328 -0.6843382 -0.401533 0.6086482 -0.6036785 -0.4515787 0.657 -0.5759385 -0.4611479 0.6750092 -0.4825874 -0.503259 0.7168263 -0.4586229 -0.5074756 0.729475 -0.3140524 -0.5480182 0.7752723 -0.3070822 -0.5487444 0.7775474 -0.1166941 -0.5726498 0.8114522 -0.1445249 -0.5739219 0.8060561 -0.9772099 -0.1618744 0.1373231 -0.959369 -0.222737 0.173204 -0.9653678 -0.2081779 0.1572482 -0.9354085 -0.2871149 0.2063395 -0.9424086 -0.2886922 0.1688876 -0.8755947 -0.4078769 0.2587864 -0.8874758 -0.4059363 0.21818 -0.7917375 -0.5229868 0.3156529 -0.8127409 -0.5131943 0.2758334 -0.681824 -0.6271391 0.3765803 -0.7147396 -0.6141263 0.3346585 -0.56259 -0.7100961 0.4233865 -0.6115457 -0.6893859 0.3882771 -0.4323534 -0.7706967 0.4680782 -0.4932084 -0.7550286 0.432062 -0.2584814 -0.8237478 0.5046058 -0.3327831 -0.8124281 0.4787653 -0.07079607 -0.84731 0.5263589 -0.1397498 -0.8475335 0.5120128 -0.8957418 -0.4441949 0.01837581 -0.8208537 -0.5674914 0.06444203 -0.8353745 -0.5496811 -4.85296e-4 -0.7242929 -0.680828 0.1089628 -0.7560594 -0.6544467 0.008597195 -0.5922131 -0.7948166 0.1324778 -0.6497285 -0.7595909 0.02956992 -0.4528838 -0.8806179 0.1393145 -0.5512431 -0.832246 0.05914312 -0.3238248 -0.932703 0.1587534 -0.4306077 -0.8988004 0.08206582 -0.1635273 -0.9735026 0.1598482 -0.275948 -0.9544612 0.1133866 -0.02024894 -0.9871451 0.1585386 -0.09426504 -0.9860332 0.1373047 0.02990776 -0.2003977 0.9792581 0.08438909 -0.5681681 0.8185742 0.1247101 -0.8425436 0.5239923 0.1440775 -0.9790275 0.1440375 0.03020828 -0.2002172 0.9792857 0.05940818 -0.1941672 0.9791679 0.05996298 -0.193548 0.9792567 0.09091341 -0.1808227 0.9793048 0.09161794 -0.1798502 0.9794183 0.1199323 -0.1628149 0.9793404 0.1205655 -0.1612485 0.9795218 0.1411855 -0.1428655 0.9796204 0.141956 -0.1412392 0.9797449 0.08573478 -0.5676672 0.8187818 0.1676216 -0.5502118 0.8180282 0.1698734 -0.548469 0.8187336 0.2567332 -0.5130074 0.8190919 0.2598164 -0.5100442 0.8199697 0.3386878 -0.46224 0.8195272 0.3418449 -0.4573126 0.8209795 0.3994186 -0.4065974 0.8216712 0.4030727 -0.4010542 0.8226106 0.1275662 -0.8418049 0.5244917 0.2474577 -0.8153305 0.523451 0.2527682 -0.8126145 0.5251342 0.3794422 -0.761391 0.5256496 0.3869174 -0.7561499 0.5277617 0.5007596 -0.6865543 0.5271462 0.5091538 -0.6776378 0.5306312 0.5919938 -0.6057876 0.5315682 0.6011758 -0.5946401 0.5338454 0.148855 -0.9781959 0.1448279 0.2858101 -0.9473357 0.144457 0.2949291 -0.9441304 0.1470869 0.438906 -0.8863789 0.1472892 0.4520174 -0.8792054 0.1505933 0.579851 -0.8007234 0.1503834 0.5953822 -0.7881861 0.1558299 0.6874579 -0.7092271 0.1562004 0.7039301 -0.6920602 0.1597973 0.003158211 -0.9999871 -0.003972828 0.02234339 -0.9989255 -0.04060488 0.1745483 -0.9629765 -0.2054488 0.4101545 -0.7495477 -0.5195686 0.3750178 -0.7631855 -0.5262221 0.4202133 -0.7634714 -0.4904407 0.4271922 -0.7966719 -0.4275754 0.4459732 -0.7964662 -0.4083499 0.442802 -0.8276168 -0.3449302 0.01693922 -0.9600697 -0.2792477 0.1551111 -0.9726727 -0.1727674 0.1534913 -0.9766889 -0.1500642 0.1619994 -0.9766032 -0.1414302 0.1571707 -0.9803026 -0.1196008 0.001584112 -0.9999673 -0.007935583 0.04399573 -0.9989687 0.01121968 0.01402962 -0.998445 -0.05395358 0.2964988 -0.9523511 0.07152664 0.08014416 -0.9324594 -0.3522734 0.6156021 -0.7817424 -0.09956353 0.1861187 -0.7403743 -0.6459147 0.002171099 -0.9999948 -0.002407968 0.02094274 -0.999765 0.00559163 0.01678401 -0.9996903 -0.01837676 0.1421767 -0.9891697 0.03645831 0.1098736 -0.9863443 -0.1226894 0.3552587 -0.9345811 -0.01869589 0.2525899 -0.9389784 -0.2334909 0.4566611 -0.6976115 -0.552086 0.3471106 -0.9114693 -0.2207668 0.3794094 -0.9079365 -0.1780446 0.3956262 -0.8952908 -0.2047789 0.459366 -0.8644271 -0.2043252 0.4486711 -0.8671807 -0.2160829 0.5347638 -0.8211526 -0.1993395 0.5218186 -0.8262599 -0.2121317 0.6066703 -0.7680695 -0.2049888 0.6062873 -0.7682582 -0.2054147 0.4230517 -0.6941869 -0.5823504 0.4717829 -0.676275 -0.5657501 0.4452041 -0.6732049 -0.5904139 0.4856549 -0.6516538 -0.582655 0.4709944 -0.6541615 -0.5918083 0.5011397 -0.6336885 -0.58932 0.4993097 -0.6340469 -0.5904867 0.5167077 -0.6183084 -0.5922061 0.5276666 -0.6129928 -0.5880543 0.533674 -0.6062853 -0.5895848 0.5588969 -0.5935736 -0.579055 0.6651729 -0.7162059 -0.2111734 0.6708451 -0.7097918 -0.2148549 0.6962043 -0.687423 -0.2067591 0.7303848 -0.6481993 -0.2153502 0.7544762 -0.6269592 -0.1941335 0.8008568 -0.5568808 -0.220255 0.9999971 -0.002075552 -0.001313745 0.9999921 -0.003954231 -6.07558e-4 0.9999858 -0.004997909 -0.001914024 0.9995111 -0.03068673 0.006011903 0.9989355 -0.03800261 -0.02614885 0.995212 -0.09731388 -0.009122133 0.9923153 -0.1124081 -0.05171811 0.9745575 -0.2230499 -0.02205538 0.9592037 -0.2543994 -0.123326 0.9286698 -0.3578295 -0.09762537 0.8983954 -0.4124081 -0.1510139 0.8979745 -0.4135737 -0.1503286 0.8568993 -0.4998527 -0.1259803 0.9999933 -0.001774609 -0.003213286 0.9999856 -0.00484997 -0.002310454 0.9999704 -0.00578624 -0.005079925 0.9992833 -0.03756409 0.004686236 0.9970169 -0.03979414 -0.06613576 0.9926214 -0.112488 -0.04526817 0.9821393 -0.1250858 -0.1405564 0.9610552 -0.2555338 -0.1052411 0.9042202 -0.2672492 -0.3331121 0.8685716 -0.3919085 -0.3033001 0.7884597 -0.4434456 -0.426248 0.7520574 -0.5208477 -0.4038902 0.5870541 -0.5494935 -0.594495 0.9854786 -0.1294218 -0.1099185 0.9876798 0.01975977 -0.1552358 0.9879246 0.01589566 -0.1541187 0.9893977 -0.02722609 -0.1426572 0.9815409 -0.124054 -0.1455616 0.9554803 -0.2212685 -0.1951865 0.917786 -0.3761367 0.127241 0.5702199 -0.5247607 -0.6320408 0.580452 -0.5602553 -0.5909227 0.6206939 -0.4990386 -0.6047309 0.6208692 -0.6000827 -0.5044029 0.6567791 -0.5507068 -0.5151343 0.6563969 -0.629715 -0.4154541 0.7424628 -0.4969987 -0.4491562 0.9707629 -0.1960694 -0.1384792 0.9821216 -0.08064627 -0.1700983 0.8699875 -0.4235525 -0.2524381 0.8713862 -0.3600983 -0.3331897 0.8571135 -0.3943551 -0.3314222 0.8533142 -0.286482 -0.4356408 0.784175 -0.4372534 -0.4403169 0.4749453 -0.5855486 -0.6569322 0.554723 -0.6768599 -0.4838836 0.462708 -0.575135 -0.6746267 0.4561137 -0.5777848 -0.6768493 0.4499655 -0.5786026 -0.6802574 0.4654124 -0.5790196 -0.6694235 0.4545408 -0.6013621 -0.6570817 0.4545803 -0.6013113 -0.6571009 0.432278 -0.5538283 -0.7116249 0.4771063 -0.5656836 -0.6725858 0.4623715 -0.5917379 -0.6603476 0.4960196 -0.6463674 -0.5798049 0.5454212 -0.6847807 -0.4833126 0.5499387 -0.6588824 -0.5132654 0.5374112 -0.6650825 -0.518512 0.5348762 -0.6646229 -0.5217125 0.5679646 -0.6394398 -0.5182016 0.5048657 -0.6640309 -0.5515194 0.963747 -0.227476 0.1394508 0.9955013 -0.07739287 0.05465656 0.9890304 -0.137293 0.05449426 0.9999891 0.001636624 0.004391252 0.9891675 -0.1355381 0.0563656 0.9788104 0.01052439 0.2044981 0.9166669 -0.04498285 0.3971127 0.9999969 0 0.002526342 0.8957126 -0.1308847 0.4249331 0.9193086 -0.2603986 0.2950669 0.9791788 0.01040059 0.2027333 0.9953549 -0.09013056 0.03383976 0.9999996 -8.1833e-4 4.10164e-4 0.815486 -0.02710723 0.5781417 0.6928693 -0.1004276 0.7140354 0.6011278 -0.2936672 0.7432395 0.8252124 -0.1550881 0.5431135 0.9612118 -0.2506656 0.1150599 0.905247 -0.06762307 0.4194701 0.8066685 -0.3336436 0.4878196 0.6037873 0.07458221 0.7936488 0.3588535 -0.4039449 0.8414586 0.3505496 0.09887295 0.9313105 0.5692025 -0.2291142 0.7896299 0.7523539 -0.321196 0.5751496 0.7469065 -0.2813711 0.6024626 0.8113498 -0.384235 0.4405395 0.9294055 -0.3294027 0.1664313 0.9108108 -0.3624279 0.1976609 0.9096116 -0.3655817 0.1973751 0.8789785 -0.4287027 0.2088324 0.8745799 -0.444111 0.1946163 0.7764902 -0.5995807 0.1938195 0.7764881 -0.5995826 0.1938219 0.7108241 -0.5488606 0.4398651 0.6446594 -0.5267282 0.5540502 0.6295077 -0.4860953 0.6061613 0.4838918 -0.3736535 0.7913482 0.4241595 -0.3602673 0.8308407 0.227207 -0.1243564 0.965874 0.1554251 -0.1200124 0.9805305 0.6955668 -0.6914697 0.1950808 0.6841238 -0.7004058 0.2034855 0.6614754 -0.7230218 0.1992236 0.5930964 -0.5602645 0.5782218 0.5267257 -0.6454352 0.5531488 0.3957961 -0.3366212 0.8544189 0.3036646 -0.4774684 0.8245071 0.1435902 -0.04972529 0.9883872 0.01823991 -0.2563621 0.9664087 0.6692829 -0.7123843 0.2111141 0.6360051 -0.7456737 0.1986667 0.5472522 -0.5876257 0.595996 0.4778192 -0.6716277 0.5662201 0.3268439 -0.361603 0.8731646 0.2316733 -0.4963272 0.8366522 0.06028974 -0.06329697 0.9961721 -0.07038313 -0.2595198 0.9631697 0.6172153 -0.7485651 0.2422715 0.5798916 -0.7911473 0.1944522 0.4211203 -0.6315653 0.6509861 0.3726117 -0.7410861 0.5585267 0.1412188 -0.3797567 0.914244 0.08813494 -0.5752189 0.8132377 -0.1473993 -0.03746116 0.9883674 -0.2342913 -0.3398895 0.9108144 0.4069002 -0.8937353 0.1888637 0.5200114 -0.8202666 0.2382249 0.5065351 -0.8421491 0.1849518 0.2797176 -0.7480297 0.6018387 0.2766747 -0.7656124 0.5807657 -0.01402068 -0.5270224 0.8497358 -0.01348912 -0.5227631 0.8523713 -0.3061893 -0.2021864 0.9302521 -0.2974398 -0.1630977 0.9407066 0.3254395 -0.9225662 0.20727 0.3582351 -0.9067398 0.2224648 0.1891891 -0.7901594 0.5829716 0.1845963 -0.8073549 0.5604484 -0.04292535 -0.5464456 0.8363938 -0.04257941 -0.5448608 0.8374449 -0.268501 -0.2053321 0.9411408 -0.2584595 -0.1725589 0.9504853 0.1132106 -0.8126217 0.57169 0.1622315 -0.9694229 0.1841203 -0.004706621 -0.9999734 0.005585312 -0.001950085 -0.9999892 0.004237234 -3.22009e-4 -0.9999963 0.002696394 9.17878e-4 -0.9999994 7.70416e-4 -0.06626236 -0.9937929 0.0893588 0.0428 -0.9987751 0.02483218 -0.03032141 -0.9972922 0.06700056 0.02524262 -0.9995651 0.01524889 -0.003087878 -0.999163 0.04079157 0.01635563 -0.9998272 0.008843302 0.01540464 -0.9998229 0.0108143 0.01647561 -0.9998418 0.006707549 -0.1272248 -0.8712453 0.4740732 0.1071533 -0.9738543 0.2003147 -0.1202911 -0.9425325 0.3117089 0.09027719 -0.9889371 0.1177005 -0.002594113 -0.9809338 0.1943252 0.0693075 -0.9950398 0.07135993 0.08095401 -0.9952346 0.05435746 0.08427733 -0.9956433 0.03989779 -0.1221534 -0.6642135 0.7374952 -0.1487974 -0.8130974 0.5627895 -0.07114869 -0.8389248 0.5395768 0.01639193 -0.9262353 0.3765894 0.06589502 -0.9373015 0.3422334 0.08127057 -0.9690582 0.2330693 0.1729425 -0.9787575 0.1101126 0.1709317 -0.9806355 0.09558492 -0.2050987 -0.466692 0.86031 -0.1509227 -0.6719241 0.7250796 -0.03785425 -0.7113273 0.7018409 -0.04280263 -0.832267 0.5527204 0.1169134 -0.8814319 0.4576125 0.08791083 -0.9317895 0.3521932 0.2426409 -0.9576238 0.155184 0.2341569 -0.9623931 0.1377322 -0.2251774 -0.1880227 0.9560035 -0.212476 -0.4690747 0.8572181 -0.03164225 -0.5417573 0.8399391 -0.06461966 -0.7201462 0.6908066 0.1579566 -0.8040632 0.5731772 0.1074003 -0.88466 0.4536981 0.3088852 -0.9294759 0.2016544 0.2920199 -0.9401167 0.1757981 0.2058796 -0.1948381 0.9589847 -0.2254416 -0.1942014 0.9547052 0.2185387 -0.828997 0.5147864 0.1464585 -0.8856003 0.4407516 0.08433747 -0.9801902 0.1792055 0.1287078 -0.9659631 0.2243874 0.03437632 -0.9949231 0.09458553 0.3208228 -0.4024569 0.8573805 0.3030424 -0.5537656 0.7755702 0.3028582 -0.5532849 0.7759851 0.2524149 -0.6892246 0.6791584 0.2288809 -0.753139 0.616762 0.3416575 -0.2335385 0.9103462 0.3637078 -0.193811 0.9111279 0.3522152 -0.04213106 0.9349703 -0.2068237 -0.5529808 0.807116 -0.170491 -0.4774398 0.8619652 -0.2306628 -0.1862952 0.9550334 -0.1603991 -0.8283321 0.5367851 -0.1177111 -0.7760511 0.6195878 -0.1400477 -0.6592975 0.7387242 -0.02618175 -0.980795 0.1932762 -0.3406526 -0.9301618 0.136949 -0.2506517 -0.9553446 0.1564942 -0.04151695 -0.9663757 0.2537608 -0.07541596 -0.8830453 0.4631883 0.1096268 -0.1948794 0.9746815 0.1609802 -0.1547635 0.9747481 0.1356912 -0.5536676 0.8216083 0.1356858 -0.5536639 0.8216116 0.0908426 -0.8301952 0.5500214 0.09083181 -0.8301965 0.5500212 0.03193974 -0.9805995 0.1934027 0.03194141 -0.9805989 0.1934052 -0.006915152 -0.9805997 0.1958992 -0.006915688 -0.9805992 0.1959018 -0.01966834 -0.8301944 0.5571272 -0.01966679 -0.8301956 0.5571254 -0.02937406 -0.5536659 0.8322207 -0.02938657 -0.5536707 0.8322171 -0.03461724 -0.1941645 0.980358 -0.03460168 -0.1941573 0.98036 0.8842906 -0.4657164 -0.03373986 0.7914871 -0.611167 0.004824459 0.7261039 -0.687585 -2.905e-4 0.7924875 -0.6092286 0.02835905 0.8758484 -0.482586 -5.98786e-4 0.9177835 -0.3970811 9.04433e-5 0.919053 -0.3941341 9.63373e-7 0.9332946 -0.3591119 -2.84102e-6 0.9389379 -0.3440856 -9.19791e-4 0.9954947 -0.0947135 0.00443083 0.9999441 -0.004110813 -0.009750306 0.9762535 -0.2154268 0.02281314 0.9950382 -0.0970754 -0.02180659 0.9661183 -0.258089 0.00233221 0.9994904 -0.03192126 1.76536e-4 0.9999921 -0.003998875 8.76788e-6 0.9999988 -0.001619696 0 0.7111377 -0.7030528 5.55368e-7 0.7042984 -0.7099041 -7.22339e-7 0.6906905 -0.7231505 -1.79862e-4 0.001391649 -0.9999991 0 0.1861137 -0.9822983 0.02125364 0.004201054 -0.9999324 -0.01084446 0.07418781 -0.997243 0.001662373 0.01111894 -0.9999383 3.48734e-5 0.6956012 -0.718428 -4.91251e-4 0.6696765 -0.7426529 4.22049e-4 0.6195932 -0.7849202 -0.002167344 0.5894708 -0.8077847 0.002852499 0.5185847 -0.8550248 -0.001640617 0.4557201 -0.8901142 0.004021406 0.4284531 -0.9035642 -1.90291e-5 0.3769182 -0.9262466 3.21806e-6 0.3397596 -0.9405121 -6.30342e-4 0.2781484 -0.9605089 -0.007502317 0.3618966 -0.9321632 0.0101251 0.2053858 -0.9785917 -0.01323246 0.2968068 -0.9548569 0.01240795 0.1009801 -0.9947879 -0.01414674 0.02917551 -0.9988936 -0.03688299 -1 0 0 -1 1.46339e-7 0 -1 0 0 -1 -1.06912e-5 0 -0.8857803 0.4641051 0 -0.9662051 0.2284883 -0.1193357 -0.8982337 0.4395086 0.002918004 -0.9811962 0.1930064 -0.00166887 -0.9870831 0.160175 -0.003322243 -0.997757 0.0669406 0 -0.9685663 0.1571716 -0.1928124 -0.8723227 0.4570547 -0.1736502 -0.8723226 0.4570541 -0.1736518 -0.7393188 0.4570534 -0.4944795 -0.7393171 0.4570502 -0.4944849 -0.4935849 0.4570525 -0.7399169 -0.493585 0.4570518 -0.7399173 -0.1725975 0.4570571 -0.8725302 -0.1725956 0.4570521 -0.8725333 -0.9685655 0.1571785 -0.1928106 -0.8208833 0.1571751 -0.5490416 -0.8208872 0.157177 -0.5490351 -0.5480372 0.157172 -0.8215548 -0.5480507 0.1571787 -0.8215445 -0.1916376 0.1571755 -0.9687987 -0.1916413 0.1571793 -0.9687973 -0.9979363 0.05460399 -0.03378939 -0.9732009 0.2294944 0.01457542 -0.756264 0.581502 0.299867 0.9966919 0.06877917 -0.04329842 0.9970186 0.06640583 -0.0392971 0.971604 0.199142 -0.1277825 0.9677731 0.202142 -0.1501792 0.9179673 0.3455379 -0.1947814 0.9012185 0.2598212 -0.3468405 0.327431 -0.9183787 0.2221927 -0.1817128 -0.9164278 0.3565678 -0.2574715 -0.8898915 0.3765657 -0.2059847 -0.9614522 0.1821539 -0.1910074 -0.9617744 0.1962301 -0.2027873 -0.961431 0.1858168 -0.1196392 -0.9915013 0.05110484 0.03396975 -0.9947949 0.09606945 0.05777764 -0.9941602 0.09114378 -0.0237559 -0.999435 -0.02377986 -0.007141709 -0.9778109 -0.2093678 0.6908232 -0.7225374 -0.02651536 0.6980021 -0.7157289 -0.02291899 0.7043414 -0.7096252 -0.01831501 0.7082901 -0.7057671 -0.01476705 0.7100737 -0.7040115 -0.01277458 0.7102192 -0.7038679 -0.01260375 0.7090839 -0.7049809 -0.01421296 0.7066997 -0.7072896 -0.01780474 0.7026861 -0.7110811 -0.02441251 0.7081437 -0.7059153 -0.01470077 0.5135148 -0.8561648 -0.05731159 0.6357422 -0.7715191 -0.02429699 -0.01847147 -0.9998197 0.004403114 0.01629179 -0.9968321 -0.07784813 0.1202123 -0.987784 -0.09915614 -0.1764194 -0.9842719 -0.009224951 -0.1229861 -0.9897559 -0.07251 -0.07256418 -0.9947305 -0.07242715 -0.3038392 -0.9500805 -0.07091552 -0.3473067 -0.9370757 0.03559827 -0.3558992 -0.934044 0.02996301 -0.2318629 -0.9711814 -0.05519402 -0.1143904 -0.9818992 -0.1509595 -0.1332748 -0.9855386 -0.1046493 -0.1675797 -0.9841354 -0.05826389 -0.04262977 -0.9884486 -0.1454384 -0.07333421 -0.9897499 -0.1225455 -0.09800732 -0.9878791 -0.1203721 -0.006306767 -0.9879736 -0.1544941 -0.01695156 -0.9869376 -0.1602092 -0.03222543 -0.9838937 -0.175826 -0.03120023 -0.9948628 -0.09630471 -0.02779483 -0.9976961 -0.06188774 -0.01639211 -0.9992457 0.03520661 -0.008900165 -0.9919552 0.1262763 -0.006270468 -0.9921142 0.1251811 0.005029439 -0.9903669 0.1383769 0.03716236 -0.9864173 0.1599997 0.03716677 -0.9920767 0.1200103 0.04533201 -0.990045 0.1332515 0.0587663 -0.9931479 0.101014 0.1055938 -0.9915308 0.07560861 0.09774953 -0.9916464 0.08415824 0.08049917 -0.9928894 0.08769601 0.08475214 -0.9925038 0.08805334 0.08881437 -0.9920687 0.08894765 0.0928896 -0.9915742 0.09028851 0.0562005 -0.9940615 0.09318405 0.08139926 -0.9935551 0.07888197 0.05699974 -0.9946276 0.08641237 0.05956399 -0.9943561 0.08779579 0.05653178 -0.9950385 0.08186942 -0.006036698 -0.9947584 0.1020759 0.008062422 -0.9951211 0.09833216 0.02143698 -0.9950885 0.09664082 -0.05479019 -0.9924654 0.1095922 -0.1873149 -0.9625103 0.1961817 -0.1753398 -0.9645112 0.1974192 -0.1290258 -0.9700296 0.2059003 -0.1648845 -0.9700571 0.1783325 -0.1854275 -0.9660766 0.1797572 -0.1553241 -0.9673023 0.200501 -0.2114363 -0.9593609 0.1868728 -0.2060425 -0.9601958 0.1886014 -0.2066769 -0.9601215 0.1882854 -0.2091522 -0.9599216 0.1865635 -0.2113546 -0.9599444 0.1839455 -0.2128882 -0.9600838 0.1814325 -0.2132673 -0.9601901 0.1804221 -0.2114051 -0.9593449 0.1869899 -0.1741257 -0.9655712 0.1932685 -0.1752233 -0.9651724 0.194266 -0.1757938 -0.9649738 0.1947361 -0.1768394 -0.9646025 0.1956274 -0.1790866 -0.9638423 0.1973223 -0.1812463 -0.963154 0.1987066 -0.1829595 -0.9626371 0.1996389 -0.1837655 -0.9624105 0.199991 -0.2042797 -0.9563916 0.2087698 -0.1881096 -0.9626371 0.1947937 -0.1907591 -0.9618375 0.1961618 -0.2309715 -0.9596408 0.1604431 -0.2141269 -0.9619231 0.1698635 -0.2066009 -0.9557003 0.20965 -0.2071047 -0.9561358 0.2071527 -0.2092558 -0.9604514 0.1836987 -0.2273552 -0.963217 0.1432578 -0.2354999 -0.9586116 0.1600117 -0.2378395 -0.9590126 0.1540367 -0.2515908 -0.954101 0.162461 -0.2348775 -0.9413132 0.2424091 -0.1959087 -0.9480845 0.2505106 -0.2548352 -0.9414482 0.2207584 -0.2746344 -0.8901637 0.363572 -0.2719416 -0.8918848 0.3613713 -0.2578653 -0.8976594 0.3573698 -0.2593505 -0.9028782 0.3428533 -0.2701157 -0.907312 0.3222151 -0.2203428 -0.9260874 0.3062863 -0.2249903 -0.9254688 0.3047739 -0.2600654 -0.925518 0.275286 -0.2432435 -0.8966869 0.3698452 -0.2472439 -0.8984758 0.3627834 -0.2286201 -0.9058974 0.3564866 -0.1195319 -0.9318844 0.3424965 0.08178913 -0.9604879 0.2660332 0.2021334 -0.953172 0.2249564 0.1945578 -0.9495312 0.2460442 0.1245856 -0.9569498 0.2621556 0.5896356 -0.8074122 0.02038693 0.710683 -0.7034505 0.009327292 0.7117181 -0.7024388 0.006086885 0.6695614 -0.7420232 0.03300267 -0.02296531 -0.9934806 0.1116641 -0.02303838 -0.9938205 0.1085826 -0.02208602 -0.9938974 0.1080749 -0.001906156 -0.989397 0.1452244 -0.001940667 -0.9937061 0.1120024 0.03552186 -0.9949674 0.09369242 0.03554636 -0.9947332 0.09613764 0.05992633 -0.9943539 0.08757418 0.05663114 -0.9930564 0.1031119 0.05334395 -0.9924808 0.1101649 0.05648964 -0.9935724 0.09809756 0.05525922 -0.9878341 0.1453629 0.0559076 -0.9940028 0.09398347 0.08294165 -0.9943689 0.06596422 0.08294314 -0.992896 0.08531183 0.09931236 -0.992147 0.07603603 0.01978826 -0.9868521 0.1604102 0.01981174 -0.9870146 0.1594045 0.03298026 -0.99052 0.1333506 0.03354364 -0.9945306 0.09891396 0.0350573 -0.9944775 0.09892225 0.1201747 -0.9905094 0.06670349 0.05998754 -0.9959149 0.06749087 0.08079361 -0.9948372 0.06141191 -0.2718502 -0.962337 -0.00227487 -0.3204687 -0.9472332 0.007022559 -0.3214913 -0.9433085 0.08253759 -0.09126508 -0.9878289 0.1259565 -0.1000269 -0.9871858 0.1243342 -0.09971171 -0.9862586 0.1317253 -0.06546586 -0.9890145 0.1325309 -0.06473332 -0.9829378 0.1721716 -0.03018999 -0.9845131 0.1726923 -0.03020405 -0.9807416 0.1929603 -0.01447135 -0.9810917 0.193002 -0.01451432 -0.9805436 0.1957649 -0.04754078 -0.9794242 0.1961334 -0.04667383 -0.9863229 0.1580789 -0.007139384 -0.9876217 0.1566923 -0.0549634 -0.9935733 0.09895014 0.008427262 -0.9952633 0.09685045 -0.01534599 -0.9961648 0.08614051 -0.02253401 -0.9987835 -0.04386317 -0.1192806 -0.9921787 -0.03679358 -0.1000837 -0.9948521 0.01589578 -0.1767499 -0.9840229 0.02141314 -0.1793602 -0.9730956 0.1446203 -0.1696968 -0.9748661 0.1443584 -0.1699839 -0.9564146 0.2374379 -0.1461967 -0.9602701 0.2377141 -0.1457629 -0.9512954 0.2716438 -0.1270466 -0.9538026 0.2722498 -0.1274416 -0.9574611 0.2588958 -0.009622454 -0.9990472 0.04256939 -0.1010686 -0.9937501 0.04739212 -0.05511689 -0.9930225 0.1042531 -0.1170325 -0.9873089 0.1073535 -0.1187493 -0.9730347 0.1977428 -0.09162229 -0.9760397 0.1973623 -0.09197878 -0.9678745 0.2340061 -0.06521654 -0.9700081 0.2341603 -0.06523227 -0.9718477 0.2263999 -0.09318321 -0.969696 0.2258464 -0.0937336 -0.9751553 0.200714 -0.04683959 -0.9630933 0.2650616 -0.07328528 -0.9972963 0.005423426 -0.0168522 -0.9978562 -0.06323796 0.02474933 -0.9996534 -0.008981406 0.2044826 -0.9788467 -0.006782472 0.1381469 -0.9896392 -0.0391103 0.2257391 -0.9723955 -0.05906754 0.2619462 -0.9642074 -0.04108929 0.3482505 -0.9354279 -0.06079739 0.3899109 -0.9200524 -0.03838056 0.4483107 -0.8923194 -0.05276107 0.5400279 -0.8412517 -0.02579432 -0.1992379 -0.9528415 0.2289047 -0.06581783 -0.9692917 0.2369425 -0.06598079 -0.9556534 0.2870074 0.056432 -0.955061 0.290988 0.6005722 -0.7975628 0.05662786 0.5182161 -0.8452809 0.1302009 0.4939944 -0.8632535 0.1037455 0.4088665 -0.900214 0.1498098 0.3649407 -0.9199863 0.1429806 0.3130627 -0.9328503 0.1782754 0.2338477 -0.9553364 0.1806866 0.203953 -0.9584386 0.1994957 0.1109223 -0.9734518 0.2002193 0.08408272 -0.9727394 0.2161208 0.001357793 -0.9766758 0.214715 -0.09187984 -0.9592784 0.2671011 -0.2165825 -0.9248503 0.3126403 -0.2142074 -0.9124363 0.3486764 -0.2209374 -0.9092102 0.3528789 0.03937143 -0.9652006 0.2585303 -0.0110535 -0.9355307 0.3530725 -0.04700189 -0.9446175 0.3247904 -0.1258742 -0.9273191 0.3524699 -0.1272323 -0.9426365 0.3086236 -0.2074146 -0.9305654 0.3017072 -0.209938 -0.9472814 0.2420412 -0.2765496 -0.8880673 0.3672288 -0.2781183 -0.8931002 0.3535851 -0.2860959 -0.8890546 0.3573951 -0.2910994 -0.9072576 0.3035536 -0.2914149 -0.9070253 0.303945 -0.2958777 -0.9252045 0.2375986 -0.2933571 -0.9268324 0.2343577 -0.1878447 -0.9821915 0.003784179 -0.1824756 -0.9830311 0.01877695 -0.1824529 -0.9830582 0.01753848 -0.2259682 -0.9729887 -0.04723781 -0.2968799 -0.9451842 0.1359753 -0.2911722 -0.9480157 0.128394 -0.2007529 -0.9705171 0.1333978 -0.1890525 -0.9747739 0.1186391 -0.09116631 -0.988282 0.1224235 -0.0753526 -0.9907341 0.1129965 0.003883481 -0.9933668 0.114923 0.02181661 -0.9943161 0.1042101 0.1151026 -0.9877582 0.1052863 0.1342364 -0.9865177 0.09361302 0.2391182 -0.9664776 0.09350776 0.2580956 -0.9626878 0.08135664 0.369291 -0.9258685 0.07994771 0.3865519 -0.9197614 0.06794571 0.4966359 -0.8654906 0.06541335 0.5108643 -0.8579481 0.05424886 0.6223727 -0.7810803 0.05065381 0.6247109 -0.7799174 -0.03828006 0.6824977 -0.7302875 -0.02961575 -0.2442904 -0.9018177 0.3564367 -0.2822806 -0.8925851 0.3515814 -0.2821225 -0.8920585 0.3530418 -0.3101894 -0.8899301 0.3343754 -0.3131965 -0.9008038 0.3007665 -0.3310695 -0.9062992 0.2627066 -0.3329434 -0.9135165 0.2337442 -0.344321 -0.915682 0.2072913 -0.3470588 -0.9283963 0.1327801 -0.2653744 -0.9629919 -0.04715114 -0.2783566 -0.9603266 0.01705098 -0.3165006 -0.9466266 0.06103909 -0.2900155 -0.9564378 -0.03343302 -0.3521303 -0.9348871 0.04461562 -0.3516317 -0.9283059 0.1208446 -0.3054618 -0.9443366 0.1221543 -0.3036331 -0.9293738 0.209932 -0.310177 -0.9233384 0.2263552 -0.2738608 -0.9238411 0.2674287 -0.2716583 -0.9121546 0.306881 -0.2535592 -0.9168249 0.3084478 -0.2515975 -0.9084243 0.3338623 -0.2448849 -0.9099958 0.334573 -0.2499608 -0.9264534 0.2814317 -0.2278426 -0.9245092 0.305566 -0.2349821 -0.9464657 0.2213282 -0.2145284 -0.9457523 0.2439885 -0.2199299 -0.9605736 0.1700866 -0.2325609 -0.9577157 0.1693997 -0.1754193 -0.9677431 0.1808352 -0.1940123 -0.9794117 -0.05578517 -0.2226631 -0.9711701 -0.08514565 -0.228091 -0.9699501 0.08468437 -0.232219 -0.9693769 0.07989287 -0.2326813 -0.9557569 0.1799678 -0.2246833 -0.9576659 0.1799821 -0.2228079 -0.9353802 0.2746281 -0.2040202 -0.9394024 0.275498 -0.2026841 -0.9301784 0.3060839 -0.1906436 -0.9324522 0.3069009 -0.1937679 -0.9471827 0.2555367 -0.1616978 -0.9437856 0.2883104 -0.1664399 -0.9659525 0.1980746 -0.1384385 -0.9640117 0.2269721 -0.1417617 -0.9779804 0.1531598 -0.1861438 -0.9707776 0.1514641 -0.1879367 -0.9744129 0.1232859 -0.1496226 -0.9779146 0.1459324 -0.1449973 -0.9670021 0.2094824 -0.1842961 -0.9766426 0.1104724 0.9264159 -0.2578989 0.2743025 0.2855028 -0.7583326 0.5860205 0.7404583 -0.3535639 0.5715891 0.6960943 -0.5207914 0.4941954 0.812443 -0.4350907 0.3881143 0.4081125 -0.7768496 0.47953 0.4159559 -0.6924896 0.5894394 0.4532457 -0.7937728 0.4055774 0.4604446 -0.631149 0.6242129 0.510949 -0.6370581 0.5771379 0.5107125 -0.5282598 0.6783174 0.5521748 -0.5371705 0.6376134 0.5532858 -0.4560518 0.6970592 0.5599448 -0.4800677 0.6752755 0.5586214 -0.3998098 0.7267009 0.5883183 -0.4117374 0.6959555 0.5882058 -0.2894273 0.7551463 0.6095529 -0.301373 0.7332255 0.6093304 -0.1723532 0.7739579 0.623026 -0.1814834 0.7608565 0.623329 -0.05532866 0.7799999 0.6273326 -0.05906468 0.7765084 0.8128274 -0.4352939 0.3870803 0.812883 -0.3580136 0.459399 0.8298273 -0.3577224 0.4282773 0.8304995 -0.3055364 0.4657446 0.8332152 -0.3183328 0.4521247 0.8323137 -0.2673777 0.4855547 0.8443042 -0.2712399 0.4621465 0.8441731 -0.1920439 0.5004906 0.8527307 -0.1972659 0.4836698 0.8525519 -0.1137632 0.5101112 0.8580145 -0.1182959 0.4998173 0.8581632 -0.03639441 0.5120853 0.8597566 -0.03843408 0.509256 0.9722295 -0.2044102 0.1139567 0.9794588 -0.1223335 0.1602969 0.9806275 -0.1222201 0.1530753 0.9806535 -0.1062184 0.1644275 0.9809927 -0.110059 0.1598135 0.9808338 -0.09282052 0.1713168 0.982288 -0.09339743 0.162442 0.9822311 -0.06635111 0.1755552 0.9832644 -0.06766206 0.1691541 0.9832139 -0.03917354 0.1782023 0.9838712 -0.04047131 0.1742401 0.9838789 -0.01250189 0.1783985 0.9840704 -0.01312536 0.1772944 0.9842666 0.00335592 0.1766585 0.9841486 0.003669261 0.1773085 0.8613601 0.009344935 0.5079089 0.8603462 0.01030385 0.5096061 0.6309294 0.01412564 0.7757117 0.6283501 0.01571398 0.7777721 0.9850335 0.01213568 0.1719353 0.9842488 0.01350575 0.1762722 0.8679752 0.03394967 0.4954457 0.8612512 0.03787666 0.506766 0.6478523 0.05164039 0.7600136 0.6307464 0.05773955 0.7738379 0.9862688 0.02054208 0.1638652 0.9850304 0.02300816 0.1708388 0.8786627 0.05790084 0.4739192 0.8679872 0.06479907 0.4923409 0.6752312 0.08889698 0.7322296 0.6478843 0.09912782 0.7552613 0.4053534 0.4043687 -0.8198626 0.1595563 0.4196118 -0.8935702 0.1244742 0.4605436 -0.8788663 0.4380873 0.1170862 -0.8912746 0.4603384 0.1430426 -0.8761436 0.1601725 0.1590558 -0.97419 0.1592838 0.1581671 -0.9744803 0.8969678 0.0420013 -0.4400962 0.6530184 0.04394203 -0.7560663 0.6579193 0.04461103 -0.751766 0.6920183 0.09961467 -0.7149739 0.5591031 0.1077805 -0.8220627 0.7958446 0.2129669 -0.5668127 0.5960415 0.2471243 -0.7639792 0.6841212 0.3111029 -0.6596917 0.6882531 0.3670092 -0.6257891 0.7763653 0.4057317 -0.4823265 0.5275962 0.4866768 -0.6962672 0.6464859 0.556208 -0.5221959 0.5631493 0.6305699 -0.5340828 0.6531926 0.6831932 -0.326476 0.4004472 0.7529414 -0.5222272 0.4587349 0.8028036 -0.3808791 0.9728779 0.03343439 -0.2288907 0.804078 0.03240346 -0.5936402 0.98403 0.04276752 -0.1727888 0.9814224 0.08762353 -0.1706819 0.9946646 0.09160786 -0.04743933 0.9824894 0.1829187 -0.03543084 0.9827088 0.1795616 0.04517918 0.9663539 0.2494167 0.06286191 0.9640551 0.2513029 0.08628147 0.9380639 0.3284248 0.1103333 0.9360288 0.3204966 0.1453693 0.894617 0.4051023 0.1885544 0.8939031 0.4037098 0.194822 0.8395563 0.4839081 0.2469381 0.8393952 0.4894908 0.2362511 0.8551906 0.04877477 -0.5160136 0.8518035 0.106361 -0.5129504 0.8995441 0.1132329 -0.4218993 0.8833815 0.2343168 -0.4058729 0.9086046 0.2369419 -0.3439421 0.8860877 0.3353016 -0.3200334 0.8911324 0.339132 -0.3014509 0.8541841 0.446456 -0.2665457 0.8634297 0.4446404 -0.2382941 0.8054913 0.5651603 -0.1782633 0.806698 0.5650649 -0.173032 0.7301 0.6761413 -0.09892946 0.7267524 0.6783466 -0.1080602 0.001072049 0.4641032 -0.8857805 0.001033544 0.4605492 -0.8876336 0.001234412 0.1601843 -0.9870864 0.00119543 0.1561854 -0.9877271 0.1613151 0 -0.986903 0.1570395 3.51617e-4 -0.9875923 0.4651267 -3.60216e-4 -0.8852441 0.461583 0 -0.8870971 0.001072049 0.4641079 -0.885778 0.001072049 0.4640994 -0.8857825 0.001194655 0.1601808 -0.987087 0.001194655 0.1601822 -0.9870868 0.6234651 0.1604405 -0.7652126 0.5597181 0.4632542 -0.6871036 0.6236473 0.1594724 -0.7652664 0.464867 0.1594815 -0.8708986 0.4648652 0.1594648 -0.8709026 0.2875002 0.1594077 -0.944422 0.2874964 0.1594561 -0.9444149 0.09787809 0.1594312 -0.9823449 0.09787827 0.1594419 -0.9823433 0.5600855 0.462368 -0.6874011 0.4175308 0.4623746 -0.7822262 0.4175219 0.4624295 -0.7821985 0.2582291 0.4623471 -0.8482647 0.2582302 0.4623494 -0.8482631 0.08791399 0.4623501 -0.8823285 0.0879119 0.462349 -0.8823292 0.9217435 -0.05841922 -0.383375 0.6537067 -0.009672462 -0.7566862 0.9714267 -0.05814445 -0.2301078 0.972207 -0.05780041 -0.2268759 0.9935634 -0.04981631 -0.1017355 0.2985703 -0.05179572 -0.9529811 -0.0557717 -0.07518833 -0.9956085 0.803121 -0.05326175 -0.5934305 0.7476476 -0.06406676 -0.6609981 0.8956125 -0.06077891 -0.4406635 0.8801152 -0.06223577 -0.4706635 0.8801012 0.00762844 -0.4747251 0.8831178 0.0128172 -0.4689762 0.9854437 -0.003654778 -0.169963 0.9866775 0.002444922 -0.1626704 0.8578959 0.07731616 -0.5079734 0.8751754 0.0786553 -0.4773693 0.9784441 0.02354711 -0.2051649 0.985275 0.02608102 -0.1689763 0.8603978 0.1991509 -0.4690997 0.8577467 0.1986584 -0.4741367 0.8782235 0.2920528 -0.3787198 0.8544861 0.3014664 -0.4230506 0.8569962 0.4056596 -0.3178015 0.8467106 0.413437 -0.3348898 0.8569052 0.4740068 -0.2025614 0.8497518 0.4828717 -0.2115581 0.9790749 0.08497679 -0.1849089 0.9818093 0.0869351 -0.1687982 0.9818237 0.1083453 -0.1558319 0.9757521 0.1140189 -0.1868358 0.9774585 0.1483468 -0.1502274 0.971657 0.1591804 -0.1747691 0.974844 0.1796523 -0.1319251 0.9712237 0.1900617 -0.1435316 0.03139543 0.02253103 0.9992531 0.1615592 0.9856737 -0.04843467 0.2495011 0.9618925 0.1118575 -0.06718009 0.9916343 -0.1102201 0.1614933 0.9558807 0.2453814 -0.1800009 0.9835785 0.01316088 0.06030339 0.9288943 0.3654025 -0.3045758 0.94507 0.1186431 -0.03494 0.8761536 0.4807641 -0.4085953 0.8822985 0.2336647 -0.1232893 0.8001353 0.5870122 -0.5182868 0.7919884 0.3226968 -0.2017986 0.7029823 0.6819775 -0.6007484 0.6817287 0.4175494 -0.2685311 0.5876118 0.7632846 -0.683548 0.5500533 0.4797954 -0.3234493 0.4576097 0.8282354 -0.733885 0.4047738 0.5455008 -0.3629977 0.3159145 0.8766019 -0.780816 0.2466751 0.5740016 -0.3904218 0.1666461 0.905428 -0.7920216 0.08250534 0.6048922 -0.6090081 0.04807186 0.791706 0.5867542 0.6779195 0.4428825 0.3989861 0.8928 0.209089 0.4963175 0.6050171 0.622594 0.510812 0.5887655 0.6264393 0.5869851 0.6771868 0.4436966 0.5294663 0.6855401 0.4997002 0.5294786 0.6855406 0.4996865 0.4882335 0.6834362 0.5427184 0.4707689 0.6778935 0.5646567 0.3582358 0.5413948 0.7606305 0.3762654 0.5285115 0.7609863 0.4246398 0.6726268 0.606015 0.3681683 0.6538677 0.6609911 0.368181 0.6538665 0.6609852 0.3297801 0.6321838 0.701134 0.3147479 0.6177212 0.7206624 0.2429012 0.4166663 0.876007 0.2633959 0.408688 0.8738403 0.2723223 0.5922493 0.7583413 0.2233718 0.5484859 0.8057718 0.2233815 0.5484575 0.8057885 0.1923103 0.5096951 0.8385867 0.1815738 0.4878918 0.8538106 0.1632383 0.2450035 0.9556812 0.1849455 0.2427586 0.9522938 0.1473916 0.4451229 0.8832561 0.1113812 0.3812515 0.9177372 0.1114144 0.3812302 0.9177421 0.09120517 0.3296525 0.9396867 0.08631575 0.3030782 0.9490486 0.06395071 0.2477921 0.9667003 0.04490584 0.1710234 0.9842431 0.04490065 0.1710311 0.9842421 0.0379799 0.1124748 0.9929286 0.03966224 0.08406674 0.9956705 -0.2166048 0.07031124 0.9737242 0.1497395 0.04947751 0.9874868 0.1282905 0.04574024 0.9906813 0.4002841 0.8915526 0.2119117 0.3248991 0.9015454 0.2857561 0.3248991 0.9015508 0.2857391 0.2176454 0.8933687 0.3930942 0.2176399 0.8933675 0.3930997 0.1127815 0.8598834 0.4978765 0.1127674 0.859897 0.4978561 0.01348119 0.8019387 0.5972542 0.01346194 0.8019564 0.597231 -0.07763636 0.7212941 0.6882641 -0.07764947 0.7212959 0.6882608 -0.1577822 0.6201133 0.7684819 -0.1577687 0.6201108 0.7684866 -0.2248672 0.5013701 0.8355016 -0.2248718 0.5013758 0.8354969 -0.2768185 0.3683633 0.8875135 -0.2768198 0.3683501 0.8875185 -0.312346 0.2249153 0.9229589 -0.3123475 0.224918 0.9229578 -0.3306343 0.07060128 0.9411144 -0.3913499 0.07727092 0.9169922 0.1947681 0.9772186 -0.08431547 0.1856474 0.9769963 -0.1049442 0.425099 0.8864848 0.1828543 0.4166798 0.8959491 0.1537959 0.6082828 0.6727026 0.4212639 0.6071838 0.6792963 0.4121704 0.1895065 0.9789097 -0.07630938 0.1886696 0.9789186 -0.07824462 0.4249237 0.8864589 0.1833863 0.4248459 0.8865553 0.1831008 0.6065968 0.6729639 0.4232729 0.6065674 0.6731768 0.4229764 0.3370103 0.9053201 -0.2584953 0.3418586 0.9052521 -0.2522925 0.569916 0.8212273 0.0279569 0.5788897 0.814159 0.04507678 0.7239667 0.6112002 0.319854 0.7284251 0.5954438 0.3388858 0.2362062 0.9591379 -0.1557598 0.241476 0.9588623 -0.14924 0.4649543 0.8792111 0.1039489 0.4759611 0.8710111 0.1216588 0.6460593 0.6666963 0.3716499 0.6533737 0.6487113 0.3902262 0.759925 0.5729078 0.3070678 0.7567925 0.5744665 0.3118549 0.6245413 0.7809479 -0.008291006 0.6132602 0.7897886 0.01208633 0.3968757 0.8623687 -0.3143406 0.390337 0.8702311 -0.3005577 0.4234294 0.8396766 -0.3400746 0.4213481 0.8393253 -0.3435096 0.6539587 0.7557832 -0.03361266 0.654226 0.7555903 -0.03273987 0.7857635 0.5490655 0.2847856 0.7858825 0.5449402 0.2922826 0.395828 0.8632352 -0.3132815 0.3959933 0.8633996 -0.3126189 0.6288435 0.7774299 -0.01259475 0.6289544 0.777397 -0.008399009 0.7676809 0.5666409 0.2993063 0.7667093 0.5654319 0.3040454 0.8533068 0.4857028 -0.1896325 0.8563657 0.480601 -0.18884 0.7495167 0.5722245 -0.3328421 0.7803316 0.5312325 -0.3299618 0.7600925 0.4922558 -0.424198 0.8323864 0.2912917 -0.4714677 0.8231782 0.3122728 -0.4741976 0.6148132 0.5842269 -0.5297961 0.6353334 0.5586307 -0.5331824 0.6751394 0.3945291 -0.6233246 0.6390343 0.4648818 -0.612797 0.9673414 0.1872884 -0.1708034 0.9546468 0.2329391 -0.1854423 0.9277194 0.21214 -0.3071375 0.9231766 0.2259 -0.310989 0.8935558 0.2060378 -0.3988815 0.8340293 0.2869325 -0.4712376 0.8555912 0.2015447 -0.4768055 0.8026142 0.1813303 -0.5682692 0.8013998 0.1844068 -0.5689927 0.7385175 0.1690751 -0.6526911 0.7406963 0.1608054 -0.6523118 0.3163672 -0.6895673 0.6514667 0.4207828 -0.03609317 0.9064432 0.3869999 -0.2479829 0.8881078 0.3911938 -0.1782995 0.9028714 0.3726121 -0.1073881 0.9217528 0.3313122 -0.4914761 0.805409 0.3546546 -0.4284803 0.8310384 0.3555259 -0.3337478 0.8730486 0.3285159 -0.3610049 0.8727845 0.3645302 -0.3052539 0.8797374 0.2978003 -0.60109 0.7416238 0.3013705 -0.5514339 0.7778795 0.1996171 -0.7657967 0.6113172 0.2032614 -0.7390865 0.6422119 0.21989 -0.771668 0.5968056 0.281509 -0.6481662 0.7075545 0.2479178 -0.690767 0.6792479 0.2484588 -0.7002062 0.6693127 0.2248156 -0.7605651 0.6090967 0.2203903 -0.7775756 0.5889009 0.2972465 -0.5362321 0.7899999 0.4107683 -0.5413479 0.7336293 0.3239054 -0.6011439 0.7305555 0.4351268 -0.2052091 0.876672 0.4413086 -0.3334223 0.8331124 0.4434387 -0.3363782 0.8307899 0.3800777 -0.4635869 0.8003926 0.3981276 -0.5189843 0.7564058 0.3966336 -0.150414 0.9055702 0.4710687 -0.09415829 0.8770567 0.4969941 -0.06380331 0.8654052 0.2930535 -0.03548419 0.9554374 0.2932034 -0.03637874 0.9553577 0.290668 -0.105987 0.9509358 0.2913643 -0.1113882 0.9501051 0.1970078 -0.7384386 0.6449003 0.2229909 -0.6842483 0.6943194 0.237632 -0.6993525 0.6741195 0.219163 -0.6214172 0.7522022 0.2262901 -0.6436622 0.7310895 0.2391973 -0.6118268 0.753958 0.2389892 -0.5965139 0.7661954 0.2486083 -0.5696173 0.7834094 0.2469217 -0.5471916 0.799757 0.2536956 -0.5256951 0.8119627 0.2564677 -0.4863839 0.8352575 0.2571319 -0.4847165 0.8360223 0.2636613 -0.4230965 0.866875 0.2626743 -0.4258013 0.8658496 0.2631264 -0.357041 0.8962624 0.2707639 -0.3164919 0.9091314 0.2718797 -0.3009238 0.9140713 0.2860086 -0.2256619 0.9312765 0.2906048 -0.2446724 0.9250321 0.2857008 -0.1755425 0.9421041 0 1 4.38073e-5 -0.5735744 -2.40809e-7 -0.8191536 -0.5735715 0 -0.8191556 -0.5735782 3.37868e-6 -0.8191508 -0.5735692 -1.76479e-6 -0.8191571 -0.5735789 0 -0.8191504 -0.5735768 4.56318e-7 -0.8191518 -0.5735753 0 -0.8191528 -0.5735779 6.65852e-7 -0.8191511 -0.5735774 2.72933e-7 -0.8191515 -0.573576 0 -0.8191523 -0.5735812 9.86285e-6 -0.8191487 -0.5735774 0 -0.8191514 -0.5735882 -1.09611e-5 -0.8191439 -0.5735802 -4.40141e-6 -0.8191495 -0.5735647 1.41212e-5 -0.8191603 -0.5736044 -6.11805e-6 -0.8191326 -0.5735522 1.3764e-5 -0.819169 -0.5735754 -1.62073e-6 -0.8191528 -0.5735769 2.49168e-6 -0.8191518 -0.5735744 -2.05846e-6 -0.8191534 -0.5735767 1.87095e-7 -0.8191519 -0.5735766 -1.70256e-7 -0.8191519 -0.5735701 0 -0.8191565 -0.573576 0 -0.8191525 -0.6491074 0.701088 0.295187 -0.6790266 0.6947038 0.2372962 -0.7741497 0.6329991 0.002141892 -0.8123713 0.5564796 -0.1743085 -0.8151639 0.4999916 -0.292432 -0.7546357 0.6532814 0.06122583 -0.6755668 0.1379549 -0.7242775 -0.7062868 0.1829027 -0.68389 -0.7706015 0.3127232 -0.5553175 -0.8076515 0.430477 -0.4029746 -0.4752032 0.6971719 0.5367806 -0.5187528 0.705315 0.4831422 -0.3880198 0.6764412 0.6259937 -0.1616427 0.5885552 0.792133 -0.2313485 0.6173303 0.7519185 0.4495517 0.1379559 0.882537 0.496056 0.08538919 0.8640817 0.3640527 0.2207458 0.9048408 0.1551737 0.3928509 0.9064157 0.2394789 0.3230409 0.9155843 0.04021221 0.4734514 0.8799015 -0.5792264 0.7071071 0.4055816 -0.5792275 0.7071073 0.4055797 -0.5792282 0.7071064 0.4055801 -0.5792275 0.707107 0.4055801 -0.5792263 0.7071084 0.4055794 -0.5792304 0.7071062 0.4055774 -0.5792381 0.7070993 0.4055786 -0.9220577 2.99522e-4 0.3870522 -0.04330438 0 0.999062 0.06881678 -0.05239903 0.9962523 -0.2485617 0.07246321 0.9659018 -0.00666666 -0.06452447 0.9978939 -0.0850194 8.07411e-6 0.9963794 -0.04659324 -0.01342105 0.9988239 -0.0414381 -0.004394829 0.9991315 -0.04660964 -0.01504546 0.9987999 -0.0473811 -0.007272422 0.9988504 -0.06390053 -2.51514e-5 0.9979563 -0.1687545 -0.03003275 0.9852005 -0.2490522 -0.2148349 0.9443617 -0.2238011 -0.1180369 0.9674608 -0.1230516 -0.01473683 0.9922909 -0.05428326 -0.04155284 0.9976607 -0.1510448 -7.72207e-6 0.9885269 -0.3358112 1.95542e-6 0.9419293 -0.3488364 9.75376e-4 0.9371832 -0.4176579 -0.001283168 0.9086036 -0.4902532 0.006231129 0.8715578 -0.54895 -0.003940343 0.835846 -0.6585372 0.004153072 0.7525368 -0.6258645 -0.002835273 0.7799267 -0.7046617 0.001361548 0.7095421 -0.7642343 -0.005554676 0.6449149 -0.7621462 -0.006093621 0.6473763 -0.8494805 0.003196239 0.5276107 -0.8824851 0.01452612 0.4701162 -0.8309702 -0.009337663 0.5562387 -0.9011916 0.00651133 0.4333721 -0.8634097 -0.00620979 0.5044654 -0.8798298 -0.002662599 0.4752816 -0.8908818 -0.001099467 0.4542341 -0.896915 -5.24044e-4 0.4422029 -0.9020988 -1.23969e-4 0.4315295 -0.9014289 0 0.4329272 -0.9048444 -0.002298772 0.4257361 -0.9884486 0 0.1515564 -0.9987927 0.03848975 0.03052431 -0.9451489 -0.05469834 0.3220276 -0.9373722 -0.06335133 0.3425202 -0.9932477 0.05764031 0.100681 -0.9696964 0.009283483 0.2441367 -1 -3.69802e-7 0 -1 9.91318e-7 0 -1 2.29774e-6 0 0.9684383 -0.0026443 -0.2492399 0.9953177 0 -0.09665811 0.9999866 -0.001043021 -0.005076348 0.9957405 0 -0.09220051 0.9866802 2.57346e-4 -0.1626725 0.8831959 -2.32059e-4 -0.4690045 0.8794723 0 -0.4759504 0.9468843 -0.2587972 -0.1908774 0.144102 -0.9890957 -0.03040283 0.2450631 -0.9652292 -0.09097623 0.3336814 -0.9388332 -0.08514124 0.7026935 -0.6612862 -0.2625307 0.8558955 -0.4991965 -0.1350775 0.8162797 -0.5609461 -0.1379394 0.7502211 -0.6423884 -0.1565426 0.9983304 -0.05680501 -0.0104801 0.9791512 -0.1294903 -0.1565092 0.9891451 -0.1262651 -0.07516157 0.9943832 -0.08443993 -0.06381338 0.9728386 -0.1977661 -0.1203066 0.9657565 -0.2226876 -0.1331344 0.9460804 -0.2418034 -0.215553 0.9560467 -0.2530259 -0.1481644 0.953927 -0.2587713 -0.1518578 0.9468882 -0.2587717 -0.1908929 0.697924 -0.7022145 -0.1407021 0.6925836 -0.7070981 -0.1426193 0.4542737 -0.8860183 -0.09277433 0.3843001 -0.9191733 -0.0862208 0.868123 -0.03217738 -0.495305 0.5709574 -0.04211449 -0.8198989 0.1624724 -0.03280586 -0.9861677 0.2517245 -0.9659029 -0.06055033 0.6904557 -0.7070944 -0.1526054 0.9447384 -0.2588171 -0.2012045 0.9345082 -0.2625169 -0.2403733 0.9411261 -0.2567254 -0.2199405 0.943964 -0.2573229 -0.2066812 0.2540035 -0.9634007 -0.08568197 0.2373893 -0.9579762 -0.1610217 0.2600079 -0.9471986 -0.1876454 0.2446647 -0.9329028 -0.2642568 0.2552776 -0.9059795 -0.3376899 0.2543613 -0.905923 -0.3385323 0.2300555 -0.8580742 -0.4591115 0.2505484 -0.8424074 -0.4770485 0.2373464 -0.8000102 -0.5510449 0.2548997 -0.7556325 -0.603362 0.245817 -0.7515673 -0.6121445 0.2290756 -0.6690081 -0.7070733 0.2448207 -0.6547434 -0.7151041 0.2357264 -0.5821292 -0.7781766 0.2584632 -0.5314621 -0.8066876 0.9411401 -0.2513555 -0.2259997 0.9341817 -0.2439674 -0.2603544 0.934883 -0.2356225 -0.2654731 0.9304869 -0.2268742 -0.2876148 0.9318773 -0.2149996 -0.2921985 0.9287546 -0.204844 -0.308956 0.9308885 -0.1896551 -0.3122138 0.9286261 -0.1784318 -0.3252936 0.9317044 -0.1605024 -0.3258315 0.9299264 -0.146933 -0.3371164 0.9335345 -0.1287175 -0.3345823 0.9320384 -0.1108219 -0.3449972 0.935653 -0.09509944 -0.3398669 0.9344454 -0.07072508 -0.3490126 0.9372105 -0.06021803 -0.3435264 0.9364257 -0.02851092 -0.3497056 0.9377421 -0.02430373 -0.3464809 0.2834454 -0.9556395 -0.08007562 0.2420641 -0.5165596 -0.8213228 0.2329678 -0.4087432 -0.8824143 0.2423151 -0.4000722 -0.8838697 0.2356536 -0.2598906 -0.9364424 0.2414693 -0.2545778 -0.9364202 0.2379848 -0.1036689 -0.9657205 0.2403301 -0.1016499 -0.9653543 0.1597132 -0.7713848 -0.6160011 0.3960269 -0.04441481 -0.9171641 0.6904363 -0.7035363 -0.1683279 0.6776657 -0.7002467 -0.2245525 0.6867749 -0.686098 -0.2400206 0.6680264 -0.6666599 -0.3306136 0.6771106 -0.6508567 -0.3433758 0.6604291 -0.6179944 -0.4265166 0.6703236 -0.6004111 -0.436088 0.6561705 -0.5546773 -0.5116381 0.6660235 -0.536822 -0.5179139 0.6543333 -0.4790741 -0.5850949 0.6643461 -0.4616378 -0.5878221 0.6551476 -0.3911901 -0.6463375 0.6643538 -0.3757947 -0.6460747 0.6574947 -0.2930423 -0.6941376 0.6652763 -0.2809669 -0.6917117 0.6607021 -0.186497 -0.7271118 0.6660396 -0.178844 -0.7241589 0.6635283 -0.07439196 -0.7444435 0.6661103 -0.07112389 -0.7424544 0.3284054 -0.8803758 -0.3421819 0.7514475 -0.04933595 -0.6579458 0.9995602 0.01599669 -0.02497136 0.9999997 0 -7.60673e-4 0.9975804 -1.71974e-4 -0.06952309 0.9996763 0.01852369 -0.01743954 0.9985395 0.005659401 -0.05373126 0.9999991 2.40558e-4 -0.001388072 0.9999449 0 -0.01049721 0.9971233 0.002116978 -0.07576787 0.9964854 0.004550158 -0.08364474 0.9991593 0.01084613 -0.03953599 0.9975315 5.62489e-5 -0.07022106 0.9882034 -3.32498e-5 -0.1531478 0.9924285 0.004955708 -0.1227241 0.9882034 0 -0.1531478 0.9802809 0 -0.1976097 0.9780864 0 -0.2081999 0.9780862 0 -0.2082 0.9781268 -8.03571e-7 -0.2080095 0.9781312 4.59398e-7 -0.2079887 0.9784178 6.23091e-7 -0.2066364 0.9876989 -0.004446148 -0.1563047 0.9866503 -0.01065379 -0.1625047 0.9866008 -0.01387119 -0.1625626 0.9868376 -0.01099842 -0.1613406 0.9790933 -0.005839943 -0.2033281 0.9813609 -8.70885e-4 -0.192172 0.9840371 5.74039e-4 -0.1779628 0.9859877 -0.003745436 -0.166776 0.9884496 -1.81031e-4 -0.1515498 0.7517011 -0.3601464 -0.5524853 0.9780917 -0.009285032 -0.2079677 0.9847624 0.001221477 -0.1739015 0.9857972 0.006374537 -0.167819 0.986903 0.01130634 -0.1609189 0.98716 0.01229685 -0.1592608 0.9865986 0.01054626 -0.1628253 0.9853033 0.007386445 -0.1706543 0.9833627 0.003970682 -0.1816094 0.9812159 0.001458525 -0.1929072 0.9793833 2.30266e-4 -0.2020109 0.01185566 -0.2727307 -0.9620175 -2.20491e-6 -0.9716144 -0.2365707 -0.01386249 -0.991209 -0.1315768 -0.01138013 -0.9918215 -0.1271249 0 -0.9997507 -0.02233088 6.39867e-6 -0.7915437 -0.6111127 -4.11872e-6 -0.8389549 -0.544201 -0.02469253 -0.9067063 -0.4210391 -0.04201537 -0.897088 -0.43985 4.28026e-6 -0.949087 -0.315014 -0.04224205 -0.7034521 -0.7094864 -0.03059959 -0.7131727 -0.7003202 -3.399e-6 -0.6121363 -0.7907524 -0.03489357 -0.4373216 -0.8986281 -0.04158681 -0.4304923 -0.9016357 4.30638e-6 -0.544425 -0.8388097 -0.03931766 -0.1092015 -0.9932419 -0.002768933 -0.1498979 -0.9886977 0 -0.03369003 -0.9994324 -1 1.77105e-6 0 -1 0 0 -1 -2.60093e-7 0 -1 -4.0449e-7 0 -1 6.0163e-7 0 -1 -7.09195e-7 0 -1 5.48163e-7 0 -1 -3.36222e-6 0 -1 6.51646e-6 0 -1 5.29437e-5 0 -1 1.71137e-5 0 -1 -8.11238e-5 0 -0.9993438 0.01524436 -0.03285676 -0.9999955 -0.00295031 -5.59994e-4 -1 1.35157e-6 0 -0.9999963 -0.001297771 0.002421855 -0.9999976 -0.002225637 -2.11585e-4 -0.9999963 -0.001693785 -0.002168357 -0.9999968 -0.001896679 -0.001730203 -0.9999971 -0.002047717 -0.001313269 -1 -4.01372e-6 0 -0.9999999 4.90076e-4 0 -1 -3.75918e-6 0 -1 1.1698e-6 0 -1 -3.63225e-6 0 -0.9999973 -0.002158522 -9.17299e-4 -0.9999974 -0.002235352 -4.98501e-4 -0.9999975 -0.002254903 -3.50476e-4 -1 -9.78407e-6 0 -0.9974066 -0.02899307 0.06587523 -0.9998983 -0.002993047 -0.0139507 -0.9806909 0.005727291 -0.1954805 -0.9658728 -0.01936495 -0.2582923 -0.8341711 0.0164985 -0.5512591 -0.776094 -0.01637762 -0.6304045 -0.5576269 0.01652967 -0.8299272 -0.5074927 -0.003732085 -0.861648 -0.2156131 0.004150032 -0.9764701 -0.1951237 0.01229381 -0.9807017 -0.03036743 0 -0.9995388 1 -3.06268e-5 0 1 -2.93544e-6 0 1 1.58688e-4 0 0 0.984941 -0.1728912 0 0.9849407 -0.1728929 0 0.9849405 -0.1728939 -0.004425704 0.9381203 -0.3462811 8.04873e-4 0.9852972 -0.1708477 -0.003067851 0.7110787 -0.7031057 -6.21768e-6 0.6177673 -0.7863611 5.22612e-6 0.8000856 -0.5998861 0 0.8002454 -0.5996727 0 0.8954337 -0.4451948 1.45518e-6 0.8953717 -0.4453195 -6.43852e-7 0.93105 -0.3648918 0 0.1344106 -0.9909257 0 0.6024364 -0.7981669 0 0.3863007 -0.922373 7.4888e-6 0.3866084 -0.922244 -7.97158e-6 0.1347369 -0.9908815 -0.001782 -0.9999971 0.001659154 2.53568e-4 -0.9999948 -0.003241539 0.003458738 -0.9999894 -0.003040373 0 -1 0 0.5529876 -0.1009004 -0.8270574 0.5231806 -0.2017424 -0.8279989 0.4958573 -0.3589028 -0.7907682 0.4919783 0.1097298 -0.8636648 0.5338775 -0.1077288 -0.8386713 0.5497863 0.07391637 -0.8320285 0.6088332 -0.1004948 -0.7869073 0.6153738 0.3063712 -0.7262588 0.6816173 0.001075506 -0.7317081 0.7071068 0 -0.7071068 0.7422906 0 -0.6700782 0.7422953 4.05075e-5 -0.670073 0.7422859 0 -0.6700834 0.9658781 0 -0.2589972 0.8623377 0.4741376 -0.177672 0.9888913 0 -0.1486405 0.9466502 0 -0.3222631 0.9348417 0.009717583 -0.354932 0.8247467 0.3934618 -0.4061782 0.8485876 0.3115507 -0.4275922 0.8129355 -0.121479 -0.5695427 0.800065 0 -0.5999133 0.9999846 0 -0.005552649 0.2889823 0 0.9573345 0.2789303 0.03846681 0.9595406 0.2828444 0.01449978 0.9590563 0.2855991 0.006322801 0.9583283 0.2764705 0.08233767 0.9574888 0.2706092 0.1745886 0.9467257 0.252182 -0.01727348 0.9675257 0.9974231 -0.003307819 0.0716682 0.9503003 0.2793341 0.1374835 0.9773284 0 0.2117291 0.910879 0 0.4126735 0.9108791 0 0.4126736 0.180701 0.08910369 -0.9794936 0.1625591 -0.004435181 -0.9866889 0.9571589 -0.00100249 -0.2895613 0.9576175 0.09889173 -0.2705352 0.8680973 -0.03311127 -0.4952888 0.7722495 0.2154902 -0.5976578 0.7523635 0 -0.6587482 0.5203811 0 -0.8539342 0.542396 0.3148648 -0.7788883 0.3961998 -0.03333652 -0.917559 0 -0.004553735 -0.9999896 0 -0.004553735 -0.9999896 0.9959682 -1.48036e-5 0.08970791 0.9959635 0 0.08976024 0.9959684 0 0.08970546 0.9959684 0 0.0897057 0.2212675 -0.9752049 -0.004010498 0.2299711 -0.9731975 0 0.2596712 -0.9356595 0.2389819 0.4661549 -0.8847032 0 0.7071279 -0.7070857 0 0.7070963 -0.7071174 0 0.9659271 -0.2588144 0 0.9659242 -0.2588252 0 0 -1 1.62024e-4 0 -1 -1.67808e-5 0 -1 5.90744e-6 0 -1 -1.3424e-5 0 -1 1.05683e-6 0 -1 -3.72573e-6 0 -1 3.11446e-6 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.9844379 -0.009575068 -0.1754719 -0.9444922 -0.1608756 -0.2864499 0.9878497 -0.02452844 0.153465 0.9840275 0 0.1780172 0.9775683 0 0.2106189 0.9775682 0 0.2106194 0.6020952 0 -0.7984244 0.6019644 0 -0.798523 0.6019606 0 -0.7985258 0.6019445 1.77822e-5 -0.798538 0.6019561 -1.14089e-5 -0.7985292 0.6019448 3.42423e-5 -0.7985377 0.6019457 2.26066e-5 -0.798537 0.601968 7.64987e-6 -0.7985203 0.601939 -3.42021e-5 -0.7985421 0.6019644 0 -0.7985229 0.6019896 0 -0.7985039 0.6019486 -1.63799e-5 -0.7985349 0.6019501 0 -0.7985338 0.6019357 -7.84506e-6 -0.7985447 0.6019659 9.95314e-5 -0.7985218 0.5841083 0 -0.8116759 0.5988482 0 -0.8008626 0.598511 -0.001796543 -0.8011126 0.5809557 0.009697437 -0.8138775 0.5812119 0.01750928 -0.813564 0.5592753 -0.01499253 -0.8288464 0.5559068 0 -0.8312447 0.07801574 0 -0.9969521 0.07798743 2.71994e-5 -0.9969543 0.07801872 -1.07731e-4 -0.9969519 0.07800084 2.36581e-5 -0.9969533 0.07797181 -1.80157e-5 -0.9969556 0.07799452 -6.30616e-6 -0.9969539 0.07797604 1.8659e-5 -0.9969553 0.3219282 0 -0.9467642 0.2483658 -0.1663513 -0.9542756 0.4744481 0 -0.8802835 -0.9307734 0.03073036 -0.3643028 -0.96224 0.02287793 -0.2712395 -0.7722579 0.05346095 -0.6330557 -0.4531447 0.07492655 -0.8882825 -0.1755667 0.4431994 -0.8790624 -0.1745 0.2831867 -0.9430562 -0.1744997 0.2831868 -0.9430564 -0.1751928 0.08275121 -0.9810504 -0.1751943 0.08275043 -0.9810501 -0.296972 0.5315807 -0.7932401 -0.1744992 0.5050293 -0.8452785 -0.1748799 0.6823832 -0.7097677 -0.2152103 0.6905377 -0.6905377 -0.175763 0.7644465 -0.6202653 -0.1744993 0.8452785 -0.505029 -0.1744996 0.845278 -0.5050297 -0.1744992 0.943056 -0.2831881 -0.2520835 0.9353115 -0.2482868 -0.1757068 0.9131541 -0.3677998 -0.1751942 0.9810501 -0.08275145 -0.1751916 0.9810508 -0.08274924 -0.4233629 0.9027546 -0.07614612 -0.792311 0.6079586 -0.05128031 -0.6074064 0.7915803 -0.06677007 -0.9048033 0.4243231 -0.03579163 -0.9843184 0.1757769 -0.01482647 -0.9843181 0.1757789 -0.01482647 -0.9841929 0.1696178 -0.05093401 -0.984193 0.1696174 -0.05093383 -0.9841925 0.1520336 -0.09083473 -0.9841926 0.1520338 -0.09083479 -0.9841924 0.1252322 -0.1252289 -0.9841933 0.1252255 -0.1252288 -0.9841928 0.09083396 -0.1520318 -0.9841926 0.09083694 -0.1520316 -0.9841929 0.0509327 -0.169618 -0.984193 0.05093073 -0.1696183 -0.9842799 0.04647195 -0.1703921 -0.9951649 0.008254587 -0.09787219 -0.8422125 0.5321278 -0.08670717 -0.840344 0.5191515 -0.1558964 -0.8403371 0.519163 -0.1558952 -0.8403421 0.4653269 -0.2780222 -0.8403405 0.4653296 -0.2780222 -0.8403396 0.3832956 -0.3832935 -0.8403409 0.3832927 -0.3832937 -0.840341 0.2780194 -0.4653303 -0.8403397 0.2780238 -0.4653298 -0.8403409 0.1558945 -0.5191574 -0.8403401 0.1558949 -0.5191582 -0.842215 0.08759725 -0.5319783 -0.8810469 0.04878389 -0.4705069 -0.5388323 0.8354692 -0.1079403 -0.5362183 0.8084179 -0.242756 -0.5362192 0.8084172 -0.2427562 -0.536219 0.7245984 -0.4329277 -0.5362199 0.7245981 -0.4329272 -0.5362185 0.5968554 -0.5968529 -0.5362198 0.5968537 -0.5968534 -0.5362206 0.4329252 -0.7245988 -0.5362187 0.4329285 -0.7245982 -0.5362194 0.2427568 -0.808417 -0.536219 0.2427561 -0.8084175 -0.5388678 0.109725 -0.8352137 -0.6335642 0.06496685 -0.7709578 -0.1757985 0.9844263 -1.64392e-7 -0.1757968 0.9844265 0 -0.4245932 0.9053843 0 -0.4245849 0.9053882 0 -0.6087619 0.7933531 0 -0.6087645 0.793351 0 -0.793356 0.608758 0 -0.7933564 0.6087574 0 -0.9053803 0.4246017 0 -0.9053841 0.4245935 0 -0.9844267 0.1757953 0 -0.9844268 0.1757952 0 0.004493057 0 0.99999 -0.01871013 0 0.999825 0.009603381 0 0.999954 -0.008968234 0 0.9999599 -0.0487225 0 0.9988124 -0.01738864 0 0.9998489 0.0937035 0 0.9956002 0.01769632 0 0.9998434 -0.02082878 0 0.999783 -0.07387167 0 0.9972678 0.03553307 0 0.9993686 0.0233854 0 0.9997266 -0.006349027 0 0.9999799 0.03976947 0 0.9992089 0.07743668 0 0.9969974 0.02713489 0 0.9996319 -0.0100308 0 0.9999497 -0.06490349 0 0.9978916 0.03416806 0 0.9994161 -0.002967894 0 0.9999957 0.01154321 0 0.9999334 -0.01929676 0 0.9998139 0.02383822 0 0.9997159 -0.03191983 0 0.9994905 0.02380275 0 0.9997168 -0.03601264 0 0.9993513 0.0232495 0 0.9997297 -0.01532381 0 0.9998826 -0.008574128 0 0.9999634 -0.05361402 0 0.9985618 -0.0439136 0 0.9990354 -0.6441627 0.7606557 0.08035808 -0.7070807 0.7070778 0.008825361 -0.3898997 0.9208453 -0.004709482 -0.7768785 0.6296198 0.006226241 -0.856146 0.5167341 -4.16307e-5 -0.9659265 0.2588163 5.36095e-4 -0.9324769 0.3565945 0.05768209 -0.986163 0.1657586 0.00260967 0.2581068 0.9632984 0.07373648 0.1827502 0.9826104 0.03285205 0.05591231 0.9984357 -5.37856e-5 -0.2588198 0.9659257 2.4188e-4 -0.1085087 0.9777995 0.17926 -0.2391918 0.9673159 0.08418732 0.8582899 0.5131652 -2.60868e-5 0.773613 0.6336371 0.005182623 0.7063022 0.7062878 0.04790401 0.5900461 0.8073688 -0.001152276 0.3720698 0.9282037 0.001451015 0.909957 0.4147027 1.54507e-4 0.9655303 0.2587146 0.02860242 0.984567 0.1749866 0.002766668 0.707108 -0.7071056 0 0.7071033 -0.7071103 0 0.2588211 -0.9659253 0 0.2588195 -0.9659258 0 -0.2588205 -0.9659255 0 -0.2588195 -0.9659258 0 -0.7071092 -0.7071045 0 -0.7071021 -0.7071115 0 -0.9238814 -0.382679 0 -0.9656511 -0.2587459 0.02384531 -0.9914444 -0.1305305 0 -0.999928 0.01200288 0 -0.9999292 0.01190841 0 0.9999297 0.01186078 0 0.999928 0.01200288 0 0.9978592 -0.0654 0 0.9657717 -0.258778 0.01786082 0.9801633 -0.194963 0.03562742 0.9238781 -0.3826869 0 -0.8269478 0 0.5622788 -0.8133218 -0.1600816 0.5593582 -0.7107014 0.1772042 0.6808099 -0.7357001 0 0.6773074 -0.6843436 0.3325034 0.6489339 -0.60064 -0.2959564 0.7427257 -0.6090814 -1.54589e-5 0.7931078 0.8239477 0 0.566666 0.8147776 -0.1709322 0.5540033 0.7556604 0.06870669 0.6513499 0.6090927 -3.55544e-4 0.7930991 0.6005036 -0.2969818 0.7424266 0.6890073 0.1363855 0.7118062 0.724489 -0.1744111 0.6668557 0.7539632 0 0.6569167 -1 3.50232e-4 0 -1 -7.16309e-6 0 -1 4.12094e-7 0 -1 -2.90613e-5 0 -1 2.60275e-7 0 -1 1.29996e-6 0 -1 -2.82687e-6 0 -1 -2.29048e-5 0 -1 4.20592e-5 0 -1 -5.2367e-5 0 0 -1 6.4467e-7 0 -1 0 -1 3.22614e-7 0 -1 -1.11361e-6 0 1 -1.078e-6 0 1 -9.88467e-7 0 1 2.61155e-6 0 1 1.3749e-6 0 1 -2.12964e-6 0 1 -2.92059e-7 0 1 1.81599e-7 0 1 4.48157e-6 0 1 -3.64751e-5 0 1 3.66784e-5 0 -0.6270752 0 -0.7789589 -0.6271012 0 -0.7789379 -0.859868 0 -0.5105164 -0.8598541 0 -0.51054 -0.9840939 0 -0.1776497 1 -3.20299e-6 0 1 0 -9.43902e-7 1 1.16446e-4 2.89373e-6 1 0 -1.35804e-7 -0.2502828 0.006941139 0.9681479 -0.2266163 0.002441048 0.9739812 -0.2018269 4.53258e-4 0.9794212 -0.3704661 -0.01064956 0.928785 -0.2659224 0.01062595 0.963936 -0.2387338 0.002774357 0.9710811 -0.3667802 -0.004983305 0.9302943 -0.3274753 -0.02586853 0.9445056 -0.3480898 -0.01759034 0.9372963 -0.4836029 -9.80827e-7 0.8752875 -0.4826921 9.98973e-4 0.8757897 -0.4235301 -7.70095e-4 0.9058818 -0.3956167 -0.005375862 0.9184 0 -7.6294e-4 0.9999998 -5.27214e-6 -7.62939e-4 0.9999998 0 0.01934748 0.9998129 0.001108467 0.08196389 0.9966347 0.00230652 0.09486025 0.9954879 -0.001431345 0.03744268 0.9992979 0.4271764 -0.009436666 0.9041191 0.4024119 -0.01783233 0.9152851 0.3799861 -0.0262202 0.9246206 -0.1872017 -2.61769e-5 0.9823215 0.003326833 8.10658e-4 0.9999942 0 -0.002331018 0.9999974 0.2053404 2.68649e-4 0.9786907 0.2387363 0.004386186 0.9710746 0.2494528 0.002137124 0.9683847 0.320683 -0.002155363 0.9471841 0.3667538 -0.01214009 0.9302389 0.4830197 0.02945572 0.8751139 0.4835959 0 0.8752915 0.4825879 0.001111567 0.8758468 0.572119 -0.002000689 0.8201682 0.5222215 0.01347118 0.8527035 0.5518486 0.006364703 0.8339201 0.6911008 1.62624e-5 0.7227584 0.6819874 0.003219842 0.7313569 0.6236087 -3.94756e-4 0.7817366 0.5882098 0.001006722 0.8087078 -0.6321077 -0.00390917 0.7748708 -0.6815338 0.006247639 0.73176 -0.7113431 0 0.702845 -0.5689878 0.003546118 0.8223384 -0.5465726 0.007440149 0.8373787 -0.5716111 0.00137633 0.8205236 -0.5204967 -2.18647e-4 0.8538636 -0.4813439 0.001229822 0.8765311 0.2374853 -0.9711472 0.02176797 0.1729357 -0.9833959 -0.05500817 0.5710471 -0.8138325 0.1076191 0.5360773 -0.8424072 0.05450922 0.7693889 -0.6363195 0.0560196 0.8359234 -0.5321295 0.1344258 0.8844972 -0.4610893 0.0711432 0.9608067 -0.2733651 0.04606705 0.9774698 -0.1723708 0.1218242 0.9769566 -0.1701293 0.1288874 0.9775791 -0.1719575 0.1215314 -0.8560658 -0.3604047 0.3704862 -0.9775795 -0.1719548 0.1215314 -0.9804657 -0.1934065 0.03579217 -0.9045231 -0.4213377 0.06567049 -0.9022591 -0.4266539 0.06240975 -0.7920749 -0.6078324 0.05618989 -0.7918872 -0.6081066 0.05586868 -0.6078049 -0.7921473 0.05546116 -0.6219009 -0.7800757 0.068713 -0.4221128 -0.9063093 0.02059775 -0.04983156 -0.9987473 0.004565775 -0.1730678 -0.9841269 0.03926479 -0.2209836 -0.9750617 0.02051597 -0.4474567 -0.8934746 0.03854429 -0.9999991 0 0.001442253 -0.9986428 -1.1243e-4 0.05208224 -0.7496441 -0.03212738 0.661061 -0.8156411 2.35541e-4 0.5785582 -0.9099553 -1.71243e-4 0.4147065 -0.8880226 -0.008808016 0.4597154 -0.9845359 0.02908402 0.1727518 -0.9337037 -0.0614795 0.3527292 -0.9738503 -0.01302522 0.2268174 -0.6672956 -0.07482248 0.7410252 -0.7916045 0.08711588 0.604792 -0.542695 -0.03602927 0.8391568 -0.616673 0.002039968 0.7872168 -0.4286544 -0.001928687 0.9034666 -0.425632 -0.003351628 0.9048902 -0.1923612 0.004307031 0.9813148 0.2887831 0 0.9573946 0.2048385 0.05742818 0.9771097 0.03902977 0 0.9992381 -0.1846898 0 0.982797 4.2562e-5 -1 1.07512e-4 -1.82108e-4 -1 4.56898e-4 0 1 3.17757e-7 0 1 -5.92945e-7 0 1 -8.68143e-7 -0.8880801 0.08635252 -0.4515053 -0.9287958 0.05565696 -0.3663887 -0.9545998 0.03331524 -0.2960228 -0.9659268 0 -0.258816 -0.7071091 0 -0.7071046 -0.7071092 0 -0.7071045 -0.2587999 0 -0.965931 -0.2588235 0 -0.9659246 0.2588235 0 -0.9659247 0.2588 0 -0.9659309 0.7071091 0 -0.7071046 0.7071092 0 -0.7071045 0.9289531 0.2327237 -0.2878994 0.8914298 0 -0.4531589 0.9657714 0.01783221 -0.2587811 0.9498174 0.03596097 -0.3107311 0.9655774 0.02687466 0.2587243 0.9894273 0 0.1450299 0.9939079 0 -0.110214 0.7068361 0.0270937 0.7068583 0.7879603 0 0.6157262 0.9181727 0 0.3961805 0.2587227 0.0272057 0.9655685 0.3799402 0 0.9250112 0.6017621 0 0.7986754 -0.2587227 0.02720403 0.9655686 -0.1277423 0 0.9918074 0.127565 0 0.9918302 -0.7068484 0.02710062 0.7068458 -0.6018638 0 0.7985989 -0.3801038 0 0.9249439 -0.9938882 0 -0.110392 -0.9894544 0 0.1448451 -0.9655754 0.02688503 0.2587305 -0.9182396 0 0.3960255 -0.7880738 0 0.6155809 -0.225041 0.9274713 0.2985862 -0.4481568 0.8790611 -0.162503 0.8238561 0.4951484 -0.2758428 0.683052 0.7020647 -0.2013583 0.4829881 0.8557978 -0.1852909 0.4006889 0.9066979 -0.1317096 0.3764165 0.9198604 -0.1103067 0.9252329 0.2831768 -0.2524974 0.9985896 0.007774949 -0.05252081 0.9728366 -0.0761674 -0.2186037 0.9937817 -0.1057353 0.0349009 0.9920046 -0.1157149 -0.0503683 0.9873983 -0.1158003 -0.1078662 0.8442556 -0.5026115 0.1860486 0.8817738 -0.453245 0.1305525 0.9716224 -0.2303172 0.05388838 0.7875378 -0.5000951 0.3601238 0.8061819 -0.3300993 0.4910247 0.6702757 -0.5010347 0.5474438 0.4265639 -0.4912589 0.759413 0.3950373 -0.2266228 0.890274 0.5395002 -0.5020102 0.6759626 -0.4456167 -0.416068 0.7926621 -0.4062385 -0.4811434 0.7768342 -1.47189e-4 -0.506345 0.862331 -0.05326902 -0.3571463 0.9325284 0.1763839 -0.5032005 0.8459775 -0.8029111 -0.3414248 0.4886338 -0.694601 -0.4987393 0.5184483 -0.5768668 -0.5034077 0.6432772 -0.9768627 -0.2088 0.04628044 -0.9990921 0.001724839 0.04256802 -0.8817144 -0.453391 0.1304467 -0.8442834 -0.5026218 0.1858954 -0.8014883 -0.501991 0.3249949 -0.9282405 0.2263836 -0.2951614 -0.9483416 0.06171751 -0.31119 -0.901656 0.2576199 -0.3473451 -0.97112 -0.03599721 -0.2358605 -0.9773634 -0.07313799 -0.1985238 -0.982526 -0.1018645 -0.1557762 -0.4272775 0.9016773 -0.06642407 -0.3885307 0.9130584 -0.1239688 -0.3449451 0.9358125 -0.07257986 -0.355799 0.9280277 -0.1103252 -0.3264812 0.9240836 0.198695 -0.3981518 0.862991 0.3110011 -0.3431088 0.9275664 0.1479765 -0.3819683 0.92408 0.01327824 -0.4921315 0.8675346 0.07204514 -0.3711478 0.9276582 -0.04122686 -0.1951056 0.8582162 0.4747619 -0.1872893 0.9240816 0.3331606 -0.04778826 0.9273771 0.3710637 -8.10323e-5 0.9008056 0.4342228 0.04771286 0.9273809 0.3710636 0.1422495 0.9272744 0.3463056 0.212592 0.9008688 0.3784706 0.2249682 0.9274801 0.2986136 0.2951893 0.9271752 0.2306717 0.3704316 0.9010428 0.2256157 0.3430716 0.9275708 0.1480352 0.3709337 0.9270664 0.05437064 0.4328562 0.9013349 0.01520156 0.3711649 0.9276545 -0.04115772 0.3605085 0.9284006 -0.09003299 0.2885563 0.953279 -0.08941256 -0.6420768 0.7300562 -0.2339985 -0.67754 0.7059061 -0.2064857 -0.7184946 0.6950839 0.02497786 -0.71849 0.6950888 0.02497702 -0.6141275 0.695092 0.3737573 -0.6141376 0.6950882 0.373748 -0.3522968 0.695092 0.626685 -0.3522946 0.6950959 0.626682 -1.39082e-4 0.695097 0.718916 -1.17049e-4 0.6950809 0.7189315 0.3520827 0.6950803 0.6268183 0.352064 0.6950922 0.6268156 0.6140111 0.6950815 0.3739683 0.6140074 0.6950839 0.3739696 0.7184781 0.6950918 0.0252335 0.7184875 0.6950821 0.02523195 0.6777729 0.7059452 -0.2055853 0.7887923 0.555114 -0.2639229 -0.8419905 0.4522225 -0.2941883 -0.9174318 0.3221177 -0.2335788 -0.9492586 0.3127606 0.03299957 -0.949257 0.3127654 0.03299915 -0.8113877 0.3127648 0.4937897 -0.8113874 0.3127527 0.4937979 -0.4654587 0.3127515 0.8279703 -0.4654534 0.3127513 0.8279733 -1.65063e-4 0.312747 0.9498366 -1.69339e-4 0.3127674 0.9498298 0.4651607 0.3127674 0.8281317 0.4651474 0.3127698 0.8281383 0.8112089 0.31277 0.4940802 0.8112099 0.312765 0.4940816 0.9492484 0.312756 0.0333352 0.9492457 0.3127641 0.03333741 0.9007849 0.3209773 -0.2925067 0.9416044 0.1408153 -0.3058631 0.9319513 0.05030351 -0.3590771 -0.9889059 -0.1157525 -0.09309369 -0.9920046 -0.1153141 -0.051279 -0.9937255 -0.1063781 0.03454488 -0.9912828 -0.1247225 0.04246044 -0.8475974 -0.1244615 0.5158371 -0.8476003 -0.1244701 0.5158305 -0.4862228 -0.1244686 0.8649249 -0.4862388 -0.1244505 0.8649184 -1.68864e-4 -0.1244511 0.9922258 -1.73528e-4 -0.1244732 0.992223 0.4859272 -0.1244714 0.8650906 0.4859006 -0.1244705 0.8651056 0.8474208 -0.1244696 0.5161253 0.8474114 -0.1244606 0.5161431 0.9912479 -0.1247349 0.04322981 0.9987657 -0.02496302 0.04294097 0.1887304 -0.9054033 0.3802968 0.2512668 -0.7702574 0.5861472 0.305617 -0.7680027 0.5628234 0.3836557 -0.7529866 0.5346211 0.4209162 -0.7380548 0.5273563 0.4613611 -0.7347304 0.4973099 0.5498538 -0.7042411 0.4491163 0.5753772 -0.7230031 0.3823711 0.6982008 -0.6407613 0.3192816 0.6893012 -0.6691061 0.2777785 0.7357788 -0.6575209 0.1621599 -0.2010462 -0.8969665 0.3937405 0.01860862 -0.9448136 0.3270797 0.05525648 -0.9402478 0.3359773 -0.02757698 -0.9939184 0.1066105 0.2709768 -0.9619737 0.03432279 -0.4326673 -0.7439509 0.5092507 -0.4515334 -0.7366066 0.503516 -0.5708852 -0.697426 0.4332289 -0.5811671 -0.6885374 0.4337756 -0.6439082 -0.687301 0.3361539 -0.3167329 -0.7522673 0.577732 -0.2334571 -0.7355923 0.635926 -0.305333 -0.7522163 0.5839028 -0.2065551 -0.7911089 0.5757446 0 -0.7743604 0.6327448 -1.13611e-5 -0.9505358 0.3106151 -0.06082761 -0.9432286 0.3265272 -0.7386433 -0.6541802 0.1626482 -0.6856955 -0.6726919 0.2780418 -0.7299219 -0.6262606 0.2738827 -0.6760965 -0.6741884 0.2972603 0.2165283 -0.7689073 0.6015788 0.2580503 -0.7715 0.5815478 0.2037901 -0.7903742 0.5777354 0.1253697 -0.7894176 0.6009179 -0.03491377 -0.7909529 0.6108802 -0.5859251 -0.6613508 0.4683022 -0.3206573 -0.8728213 0.3679154 -0.4188065 -0.7444111 0.5200513 0.187321 -0.9691945 0.1599155 0.1778501 -0.9755126 0.1294004 0.187375 -0.9817487 0.032561 0.8444258 -0.1321479 0.5191165 0.856533 -0.1384295 0.4971806 0.9417151 -0.1232246 0.3130311 0.9779899 -0.1334344 0.1604091 0.9051372 -0.1644896 0.3920075 0.5307915 -0.06144094 0.8452724 0.599871 -0.08926796 0.7951013 0.6671044 -0.1164494 0.7358065 -0.06437081 -0.08061271 0.9946648 0.09331548 -0.1069106 0.98988 0.3197569 -0.1364797 0.9376188 0.2376896 -0.1025336 0.9659143 0.5238342 -0.1344167 0.841148 0.635801 -0.1818521 0.7501247 -0.1248871 -0.01404976 0.9920716 0.01900464 -0.181833 0.9831458 -0.3245248 -0.03362458 0.9452794 -0.2580136 -0.2223102 0.9402166 -0.3332176 -0.1623933 0.9287596 -0.09261447 -0.8142537 0.5730737 -0.1294357 -0.8702486 0.475304 -0.1029931 -0.9047851 0.4132267 0.05437755 -0.9340835 0.35289 0.06191855 -0.921202 0.3841267 0.09303855 -0.9564305 0.2767394 -0.388678 -0.6325004 0.6699798 -0.6406996 -0.6420444 0.42105 -0.6251411 -0.7183817 0.3051663 -0.5931849 -0.7314195 0.3363884 -0.578151 -0.672181 0.4625087 -0.4321648 -0.7379131 0.5183802 -0.5189245 -0.7353259 0.4359051 -0.4373634 -0.6627928 0.6077985 -0.6485752 -0.5723478 0.5017651 -0.5874319 -0.4454698 0.6756335 -0.9234065 -0.2592294 0.2830559 -0.2594264 -0.3229104 0.9101795 0.5294223 -0.8003593 0.2813134 0.5063555 -0.8549512 0.1125283 0.4139359 -0.8105894 0.4142487 0.4253454 -0.8547849 0.2973618 0.2641275 -0.7838103 0.5620304 0.3010708 -0.8503403 0.4315994 0.08999973 -0.7612098 0.6422303 0.1486552 -0.8426295 0.5175685 -0.08668196 -0.7441254 0.6623924 -0.01173722 -0.8338918 0.5518034 -0.2483705 -0.7345471 0.6314688 -0.1582938 -0.8246383 0.5430606 -0.3212739 -0.7631942 0.5606405 0.8694573 -0.4707338 -0.1498459 0.8950282 -0.4326842 0.1082085 0.7574386 -0.3708173 0.5373837 0.8287654 -0.446086 0.3378688 0.582715 -0.3427608 0.7368571 0.7039527 -0.4552104 0.5451918 0.3811443 -0.3223628 0.8664938 0.5305989 -0.4582577 0.7130671 0.1672115 -0.3086908 0.9363495 0.3276857 -0.4573406 0.8267174 -0.04522293 -0.3023636 0.9521193 0.1229851 -0.4532199 0.882874 -0.239481 -0.2995429 0.9235383 -0.07533383 -0.4500071 0.8898418 -0.4163205 -0.303043 0.8572295 -0.2526103 -0.4454936 0.8589084 -0.5629398 -0.3090263 0.7665519 -0.7444324 -0.1162959 0.657492 -0.494018 -0.110474 0.8624046 -0.7025486 -0.3105404 0.6403048 -0.4107675 -0.4428917 0.7969424 -0.4719341 -0.5009428 0.7254891 -0.429044 -0.5626742 0.7066252 -0.2194967 -0.6522761 0.7255048 -0.2811433 -0.5594143 0.7797526 -0.05177348 -0.6561598 0.7528438 -0.1096124 -0.5629007 0.8192241 0.1322597 -0.6631063 0.7367479 0.08451259 -0.5700835 0.8172286 0.3266225 -0.6696497 0.6669986 0.2841712 -0.5837172 0.7606058 0.5044322 -0.6744248 0.5391656 0.4718049 -0.6020163 0.6441867 0.6441001 -0.6751095 0.3596698 0.6284413 -0.6247964 0.4633477 0.7367997 -0.6709768 0.0831654 0.7547057 -0.6289442 0.1866773 0.745777 -0.08495908 0.6607562 0.7241801 -0.1118508 0.6804798 0.6634073 -0.3123581 0.6799436 0.6841796 -0.119718 0.7194206 0.3906339 -0.2220905 0.8933539 0.5856571 -0.0956428 0.8048965 0.2495796 -0.2430035 0.9373684 0.4527673 -0.08508628 0.8875597 0.07973664 -0.2471387 0.9656939 0.284017 -0.08922111 0.9546591 -0.1165487 -0.2398346 0.9637925 0.1085833 -0.08983349 0.99002 0.02734249 -0.1258102 0.9916775 -0.3652574 -0.2154841 0.9056234 -0.1428938 -0.1050129 0.9841513 -0.5102686 -0.2560132 0.8210257 -0.3212597 -0.09464609 0.9422496 -0.7054197 -0.2519969 0.6624807 -0.5459146 -0.1145544 0.8299727 -0.8633057 -0.2345243 0.4468801 -0.7472312 -0.1361007 0.6504785 -0.9424211 -0.2177658 0.2538121 -0.8716219 -0.1580802 0.4639893 -0.9722083 -0.2059574 0.1113222 -0.9543904 -0.1807277 0.2376481 -0.9820165 -0.1882887 0.01381605 -0.9810115 -0.186358 0.05373322 -0.5487885 -0.8348793 0.04251956 -0.1872169 -0.9805341 0.0591855 -0.2025862 -0.9578297 0.2037674 -0.1524704 -0.9806638 0.1226838 -0.08902597 -0.9316444 0.3522969 -0.08708745 -0.9350955 0.3435292 0.3080463 -0.8580798 0.4108608 0.2890588 -0.86604 0.4079459 0.2860772 -0.8730961 0.3947951 0.100484 -0.8487986 0.5190801 0.1160849 -0.8788775 0.462708 0.0767225 -0.9124598 0.4019092 -0.5437417 -0.8349558 0.08481812 -0.5249461 -0.8192998 0.2306068 -0.5265818 -0.8260873 0.2007274 -0.4166746 -0.8154325 0.4018111 -0.4207316 -0.8172464 0.393819 -0.2535098 -0.7948618 0.5512962 -0.2825545 -0.8076046 0.5176271 -0.04890382 -0.7668982 0.6399028 -0.1200913 -0.798088 0.590452 0.1451565 -0.7454984 0.6505089 0.04603403 -0.7894578 0.6120762 0.3146546 -0.7326965 0.6034471 0.16596 -0.7968248 0.5809713 0.3846755 -0.7146201 0.5842457 0.3056682 -0.7682172 0.5625029 0.4468903 -0.7013829 0.5552937 0.3840821 -0.7545644 0.5320841 0.5123718 -0.6955282 0.5037019 0.4613535 -0.7415741 0.4870533 0.5656653 -0.6887909 0.4534203 0.6021493 -0.64529 0.4701244 0.5854874 -0.6082379 0.5359583 -0.8354607 -0.5486367 0.03167641 -0.8303228 -0.5479486 0.1015694 -0.8267931 -0.5462633 0.1342002 -0.7853526 -0.5434459 0.296459 -0.7917169 -0.5462668 0.2734538 -0.6816238 -0.5259108 0.5087308 -0.7151352 -0.5409132 0.4427127 -0.4959752 -0.5071331 0.704858 -0.5688967 -0.5381515 0.6218919 -0.2604447 -0.4821593 0.8364754 -0.3827614 -0.5341839 0.7537515 -0.02808767 -0.4647664 0.8849878 -0.1765269 -0.5290849 0.8300045 0.1893988 -0.4554897 0.8698605 0.01857626 -0.5302225 0.847655 0.3510502 -0.4493929 0.8214682 0.1782293 -0.5270718 0.8309211 0.4854428 -0.4524856 0.7480656 0.3268236 -0.525341 0.7856228 0.5965439 -0.4600523 0.6576377 0.459754 -0.5242496 0.7167906 0.6841156 -0.4730088 0.5552014 0.7509839 -0.4319698 0.4994249 0.7117861 -0.3904346 0.5838848 0.9858614 -0.1675543 0.001731812 0.1873497 -0.9822396 0.01027572 0.1106334 -0.8916996 -0.4388988 0.4472334 -0.6688227 0.5938507 0.4634221 -0.8610429 -0.2093929 0.7635054 -0.6380582 0.09970647 0.7348729 -0.485069 0.4739935 0.8775467 -0.4701344 0.09426391 0.9761623 -0.1884554 -0.107666 -0.9858665 -0.1675248 0.001710176 -0.9761812 -0.1883895 -0.1076088 -0.8276398 -0.5406536 0.1506851 -0.8195579 -0.5409274 0.1890048 -0.5419332 -0.8281638 -0.1430146 -0.4255144 -0.7906494 0.4402401 -0.1772027 -0.9355463 -0.305536 -0.1231026 -0.9923398 0.01037681 0.9999296 -0.01186984 0 0.9999285 -0.01196748 0 0.9979417 -0.06285053 -0.01273745 0.9782232 -0.166207 -0.1243173 -0.999929 -0.01191753 0 -0.9999278 -0.0120151 0 -0.9829406 -0.1791005 -0.04184329 -0.9858741 -0.1674885 0 -0.8960299 -0.4439938 0 -0.6427934 -0.5491176 -0.5341224 -0.8345786 -0.550889 0 -0.4738169 -0.8806235 0 0.9723103 -0.1380966 -0.1885263 0.9667901 -0.2555717 0 0.8345829 -0.5508825 0 0.8345786 -0.550889 0 0.4739322 -0.8805614 0 0.4738169 -0.8806235 0 0.1231186 -0.992392 0 0 -0.9529009 0.3032819 -0.1231186 -0.992392 0 -0.4739322 -0.8805614 0 -0.00117731 0 -0.9999994 2.46548e-5 0 -1 -2.7772e-4 0 -1 2.7772e-4 0 -1 1.41098e-4 0 -1 -9.10003e-4 0 -0.9999996 -1 -3.33369e-6 0 -1 8.15643e-6 2.66107e-4 -1 4.5372e-5 0 -0.8988547 -0.2508466 0.3593555 0.4302737 -0.2206004 0.8753286 0.4300279 -0.5164245 0.740528 0.1419785 -0.558847 0.8170264 0.2509512 -0.5535905 0.7940788 0.4304875 -0.5161691 0.7404391 0.4309149 -0.2204141 0.87506 0.1421616 -0.2417883 0.9598586 0.1418517 -0.2418081 0.9598995 -0.1833977 -0.2401385 0.953257 -0.1835095 -0.2401732 0.9532268 -0.4118138 -0.5211365 0.7475468 -0.2450833 -0.5544305 0.7953245 -0.1835857 -0.5531412 0.8126076 -0.07907533 -0.569986 0.8178405 0.09458541 -0.569228 0.816721 -0.5603619 -0.4738472 0.679311 -0.4995371 -0.485724 0.7173109 -0.499501 -0.2117201 0.8400438 -0.4992315 -0.2117011 0.8402086 -0.7546704 -0.375575 0.537974 -0.7540341 -0.3757739 0.5387271 -0.7548726 -0.160436 0.6359463 -0.7545136 -0.1603987 0.6363817 -0.7590558 -0.08474344 0.6454866 -0.4991011 0.09817647 0.8609643 -0.5538734 -0.03752768 0.8317547 -0.185982 -0.02643883 0.9821974 -0.1454375 0.04308897 0.9884288 0.1442878 -0.08502018 0.9858766 0.2901554 0.08609706 0.9530988 0.4359429 -0.07338476 0.8969775 0.626075 0.02273482 0.7794315 0.7311252 -0.1667218 0.6615587 0.7817113 -0.1694163 0.600188 0.4749112 -0.5033924 0.7218418 0.6140462 -0.479328 0.6270502 -0.9535128 -0.1726638 0.2469829 -0.9191945 -0.2178665 0.3280483 -0.9189621 -0.09652405 0.3823503 -0.918816 -0.09654295 0.3826967 -0.9205178 -0.06047582 0.3859917 -0.8504739 0.1214606 0.511802 -0.9916219 -0.07394248 0.1059184 -0.9916592 -0.07384222 0.1056384 -0.9916967 -0.03150367 0.1246808 -0.9916768 -0.03152304 0.1248342 -0.9919317 -0.004323661 0.1267006 -0.9859402 0.04932582 0.1596524 0.5048919 -0.583711 0.6358975 -0.7767673 -0.3251937 0.5393345 -0.628006 -0.09932368 0.7718442 -0.6202676 -0.5303974 0.5778813 -0.4356441 -0.6086472 0.6631461 -0.4358606 -0.6086471 0.663004 -0.2590598 -0.6531941 0.7114953 -0.1442372 -0.6447005 0.7507043 -0.100264 -0.6727837 0.7330138 0.05356258 -0.6752101 0.7356782 0.1863875 -0.6412264 0.7443712 0.2221796 -0.6592587 0.7183413 0.5049667 -0.58362 0.6359217 -0.794731 -0.3099234 0.5218717 -0.4315002 -0.460631 0.775646 -0.4310984 -0.4606226 0.7758743 -0.1424311 -0.5052767 0.8511222 -0.1420763 -0.5052698 0.8511855 0.1840068 -0.5017314 0.8452261 0.1836163 -0.501818 0.8452596 0.5002173 -0.4420406 0.7445688 0.4998964 -0.4422821 0.744641 -0.5338261 -0.1546434 0.8313335 -0.4307187 -0.1724272 0.8858613 -0.399534 -0.1681286 0.9011689 -0.1420601 -0.1815373 0.973069 -0.1901593 -0.194103 0.9623739 0.1827251 -0.1609684 0.9698973 0.1347612 -0.1815273 0.9741085 0.4989644 -0.1590903 0.8518948 0.544066 -0.1373695 0.8277209 0.9209579 -0.263493 0.2870678 0.9209228 -0.2635924 0.2870893 0.9192149 -0.2011843 0.3384804 0.9190115 -0.2015653 0.3388057 0.9917077 -0.06576025 0.1104146 0.9917345 -0.06559354 0.1102738 0.9919336 -0.08572286 0.09337782 0.991931 -0.08574753 0.09338366 0.7594329 -0.4399461 0.4792798 0.7594053 -0.4399525 0.4793179 0.7555645 -0.3345122 0.5632264 0.7551257 -0.3349573 0.5635502 0.7554153 -0.1313225 0.6419518 0.9135576 -0.01931846 0.4062504 0.8491898 -0.1173675 0.5148802 0.9912934 -0.01145529 0.1311721 0.9865339 -0.03009051 0.1607654 -0.1715823 -0.8536717 0.491736 0.9914031 -0.06613272 0.1129008 -0.1786319 -0.9632487 0.2006058 -0.1979088 -0.949862 0.2420626 -0.1494839 -0.9544659 0.2581659 -0.4128372 -0.8595994 0.3010885 -0.4278699 -0.824474 0.3703649 -0.4223012 -0.7941735 0.4369785 -0.3939076 -0.8091265 0.4360633 -0.5342438 -0.6649314 0.5219672 -0.5744974 -0.6837207 0.4499764 -0.5655663 -0.7339098 0.3761798 0.2199475 -0.7862195 0.5774791 0.7534673 -0.3777744 0.5381204 0.8593696 -0.3131554 0.4042494 0.6943348 -0.5471975 0.4674122 0.6435728 -0.6117359 0.4599928 0.4543336 -0.7553659 0.4722325 0.3891725 -0.8022513 0.4527006 0.08081227 -0.9068939 0.4135373 0.1528095 -0.9533655 0.260276 -0.06794792 -0.9881216 0.1378366 -0.07052969 -0.9882929 0.1352875 0.005916714 -0.999243 0.03845131 0.2264471 -0.9673313 0.1139822 0.1184481 -0.9606567 0.2512152 0.3889892 -0.8366597 0.3856009 0.411432 -0.8164396 0.4051545 0.6090025 -0.6286503 0.4836475 0.6254919 -0.6003837 0.4982963 0.7719847 -0.3474274 0.5322911 0.8147231 -0.3741674 0.4429731 -0.6205344 -0.5720522 0.5363705 -0.5021916 -0.6725336 0.5436011 -0.434339 -0.6964691 0.5712096 -0.4077845 -0.7106443 0.5733207 -0.2577535 -0.7447819 0.6155186 0.16636 -0.7693924 0.6167332 -0.09900385 -0.8080582 0.580724 0.05346834 -0.8059611 0.589549 0.694945 -0.5486526 0.4647923 0.503499 -0.6675301 0.5485366 0.435156 -0.7087764 0.5552254 0.1230366 -0.7909562 0.599375 0.1648309 -0.8964362 0.4113792 -0.1388243 -0.9293572 0.3420866 -0.002291977 -0.9132373 0.4074218 -0.4001916 -0.8648049 0.3032477 -0.3668223 -0.9083217 0.2009804 0.07977962 -0.9820848 0.1707187 0.4365866 -0.8444787 0.3102387 0.4328246 -0.8390684 0.3295865 0.6111744 -0.5415868 0.5771912 0.7112216 -0.6223847 0.3268046 0.5986287 -0.1731566 0.7820872 0.8868215 -0.3671518 0.2806196 0.8148585 -0.1930299 0.546576 0.8301257 -0.1541111 0.5358556 0.9586722 -0.06288141 0.2774773 0.8896576 -0.2294331 0.3948036 0.9950194 -0.02338099 0.09690058 0.8698852 -0.3374211 0.3597873 0.9210858 -0.2729617 0.2776559 0.7594523 -0.4796432 0.4395166 -0.7671297 -0.1773746 0.6164821 0.1404752 -0.9700855 0.1979925 0.3799684 -0.8332741 0.4015948 0.451115 -0.7662066 0.4576273 0.4532676 -0.7635012 0.4600157 0.9531084 -0.2820176 0.1097742 -0.9032101 0.1329863 0.4080765 -0.923031 -0.2526312 0.2901574 -0.9866417 -0.01702129 0.1620143 -0.5206742 -0.6668968 0.5330545 -0.759311 -0.4839072 0.4350639 -0.7904945 -0.4571403 0.4076043 -0.9014954 -0.2951416 0.3165398 -0.9545513 -0.1893451 0.2301747 0.6148553 -0.6202227 0.4871107 0.4335291 -0.7098894 0.5550762 0.4615958 -0.692593 0.5542961 0.2530807 -0.7500274 0.6110723 0.2911145 -0.7399957 0.6063488 0.09561383 -0.7741683 0.6257168 0.1001332 -0.7730163 0.6264337 -0.08016341 -0.7620686 0.6425149 -0.2475775 -0.7446126 0.6198851 0.6229959 -0.701398 0.3462902 0.2748619 -0.8442429 0.4601138 0.3342768 -0.8288701 0.4485906 0.08571588 -0.8661193 0.492433 0.1510013 -0.849357 0.5057582 -0.5303918 -0.7028914 0.4739498 -0.1888621 -0.7890959 0.5845159 -0.4147979 -0.7166453 0.5606803 -0.5637448 -0.6481196 0.511989 -0.8053627 -0.387111 0.4489279 -0.7264586 -0.497901 0.4736589 -0.7829292 -0.4405055 0.4392914 -0.464366 -0.7482511 0.4737979 -0.5394719 -0.7077593 0.4561217 -0.1449651 -0.8982758 0.4148324 -0.229892 -0.8818022 0.4117944 0.1935342 -0.9328131 0.303981 0.1061549 -0.9436949 0.3133227 -0.12589 -0.9185715 0.374671 0.2901493 -0.9203916 0.2620931 0.2450865 -0.9285802 0.2786962 -0.8247212 -0.1039257 0.5559087 -0.6572772 -0.5417512 0.5239203 -0.7050582 -0.4868478 0.515628 -0.366948 -0.8439907 0.3911892 -0.5016484 -0.7671614 0.3997655 -0.04357528 -0.9766309 0.2104598 -0.2292085 -0.9411856 0.2482605 -0.1357197 -0.9694123 0.2044991 0.09172642 -0.9857513 0.1409992 -0.9927582 0.07879132 0.09068191 0.9721832 0.01080304 0.2339727 0.991923 0.08358001 0.09541088 0.9861428 0 0.165899 0.994597 -0.04694783 0.09258931 0.3493193 2.65231e-4 0.9370037 0.3642654 -0.01649105 0.9311492 0.5688021 0.01448535 0.8223469 0.5896217 -0.002733826 0.807675 0.7169932 0.001122474 0.6970794 0.762937 -0.01648068 0.6462628 0.8522 0.01842045 0.5228919 0.8636752 0.012694 0.503889 0.9075348 -0.005454361 0.4199417 -0.6071209 -0.002233386 0.7946065 -0.576487 0.02153021 0.8168227 -0.3818548 -0.02436137 0.9239013 -0.3581558 -7.58083e-6 0.9336619 -0.2240369 -0.001999855 0.9745786 -0.1285039 0.03147017 0.9912096 -0.0950911 0.001414 0.9954677 0.1192067 9.63458e-4 0.992869 0.06280076 0.07133549 0.9954735 0.1793431 -0.00364989 0.9837799 -0.7237711 7.83955e-4 0.6900398 -0.7841346 -0.0188623 0.6203042 -0.7691721 -0.009759664 0.6389672 -0.8957352 0.01382511 0.444373 -0.8718222 0.03778815 0.4883628 -0.9145521 0.002256929 0.4044619 -0.9885224 -0.003178417 0.1510413 -0.9876734 4.31289e-5 0.1565291 0.8510579 -0.5153847 0.1003949 0.8891392 -0.4480326 0.09326452 0.9008464 -0.3743724 0.2198205 0.9421113 -0.1400329 0.3046593 0.9602491 -0.0578593 0.2730823 0.9341524 -0.2224011 0.2791004 0.7687471 -0.121777 0.6278523 0.8900617 -0.188103 0.41522 0.7428112 -0.5642063 0.3604204 0.8104969 -0.5242357 0.261289 0.8109969 -0.5236115 0.2609887 0.8722562 -0.2701812 0.4076412 0.8023027 -0.07779753 0.591826 0.793321 -0.1131371 0.5981989 0.81158 -0.2534192 0.5264189 0.7900153 -0.3176078 0.5244054 0.7940854 -0.355355 0.4931038 0.7643507 -0.5411122 0.3506649 -0.9996843 0 0.02512538 -0.987132 -0.00374639 0.1598643 -0.9861911 -0.00287652 0.1655867 -0.9356288 0.001294493 0.3529832 -0.8567514 -0.009526848 0.5156416 -0.8444258 -0.005876898 0.5356403 -0.6935148 0.003318428 0.7204348 -0.5541296 -0.008664667 0.8323854 -0.4840453 -8.87062e-4 0.8750424 -0.1455034 -0.006641745 0.9893355 -0.2403635 -0.001156091 0.9706823 -0.3531583 1.14056e-4 0.9355636 0.4186735 -4.07185e-4 0.9081369 0.2924345 -0.004351496 0.9562757 0.2912362 -0.004444301 0.9566409 0.08742821 0.001395106 0.9961699 -0.08234572 -0.002608537 0.9966005 0.4975482 1.02592e-4 0.8674364 0.626251 -0.001002967 0.779621 0.6404486 1.18792e-6 0.7680011 0.9197562 -0.3534911 0.1705661 0.8309875 -0.5313394 0.1647371 0.8236439 -0.5461491 0.1527485 0.5367103 -0.8378756 0.09953296 0.5330396 -0.840469 0.09736961 0.5343004 -0.8394635 0.09911698 0.3630349 -0.9294298 0.06607651 0.06181919 -0.9980733 0.005304753 0.1731458 -0.984329 -0.03342354 0.231169 -0.9725213 0.0276302 0.3357777 -0.9400976 0.05890601 0.7973024 -0.3782165 0.4703842 0.7554492 -0.5405626 0.3702549 0.7552475 -0.5351378 0.3784556 0.6649649 -0.6668404 0.3363715 0.582878 -0.7582288 0.2921342 0.9688523 -0.1704226 0.1796708 0.9688522 -0.170416 0.1796766 0.8460913 -0.1707658 0.5049442 0.842908 -0.1493893 0.5169035 -0.467464 0.8839265 0.01231354 -0.6499335 0.7574136 0.06253886 -0.5392661 0.8412685 -0.03820127 -0.4821683 0.8760765 -0.001968145 -0.4561228 0.889326 0.032422 0.7837365 0.61861 -0.05548751 0.4584663 0.8885751 0.01558685 0.4689375 0.8831043 0.01499104 0.4884344 0.872575 -0.006703019 0.4945794 0.8690748 -0.01001673 -0.8881838 -0.1565015 0.4320149 -0.8580549 -0.3582676 0.3679485 -0.8966054 -0.163181 0.4116681 -0.7898328 -0.2274488 0.5695887 -0.821806 -0.1746634 0.5423355 -0.8042003 -0.5400416 0.2482278 -0.8221076 -0.516933 0.2385784 -0.7658966 -0.5524687 0.3289088 -0.7588739 -0.558157 0.3355162 -0.7329711 -0.5581901 0.3888152 -0.8683315 -0.4820391 0.1167855 -0.8673131 -0.4685252 0.1680837 -0.9208906 -0.3047665 0.2430594 -0.923008 -0.2628774 0.2809836 -0.9430461 -0.09778952 0.3179643 -0.9408584 -0.1094514 0.3206339 -0.8198711 -0.299341 0.4880639 -0.8236673 -0.4304264 0.3691956 -0.3968635 -0.8996233 0.1821466 -0.5721343 -0.7940642 0.2052426 -0.8200107 -0.5654236 0.0887618 -0.9567568 -0.2889429 -0.03359574 -0.9837578 3.24316e-4 -0.1795006 -0.607344 -0.7491517 0.2643959 -0.2587704 -0.9657255 0.02030479 -0.1971915 -0.9634728 -0.1812064 -0.2625812 -0.9645078 -0.02785599 -0.3853706 -0.9210582 0.0560472 -0.9811456 -0.06515508 0.1819567 -0.9811477 -0.06514358 0.1819496 -0.8506611 -0.06512427 0.5216652 -0.8497341 -0.07118272 0.5223839 -0.9323958 -0.3173974 0.1729078 -0.9139617 -0.3569208 0.1930842 -0.8184129 -0.3579794 0.4495009 -0.727057 -0.5588627 0.3988242 -0.8345804 -0.5286964 0.1547765 -0.6721858 -0.7298132 0.1246555 -0.6523376 -0.7452985 0.1377893 -0.4089464 -0.9099085 0.06949353 -0.3981903 -0.9120454 0.09806966 -0.5900889 -2.46792e-6 0.8073383 -0.631157 0.004333496 0.7756431 -0.4054578 -0.001250326 0.914113 -0.2487068 0.002754271 0.968575 -0.1025439 -0.004996955 0.9947159 0.3137125 -2.43879e-4 0.949518 0.1049021 -0.003421127 0.9944767 0.1369976 7.00047e-6 0.9905714 -0.1941474 -9.81565e-6 0.9809724 0.911766 -0.02178215 0.4101321 0.779957 5.20985e-4 0.6258329 0.706114 -7.88449e-5 0.7080982 0.549245 -0.002602279 0.8356574 0.5994222 -0.01273542 0.8003318 0.4296578 9.55815e-4 0.9029914 0.8550262 0.01244467 0.5184356 0.986972 -0.005520701 0.1607978 0.9931574 0 0.1167839 -0.9874023 -0.002909362 0.1582031 -0.9859919 -0.04076641 0.1617348 -0.9821872 -0.07494372 0.1723133 -0.9444567 -0.2359321 0.2287739 -0.9700327 -0.05530983 0.2365955 -0.999997 -0.001902699 0.001534938 -0.9998664 -0.0142498 0.008017539 -0.9998113 -0.01176702 0.01545697 -0.9983526 -0.04008567 0.04105317 -0.9979375 -0.03641927 0.05286169 -0.9831292 -0.1112613 0.1451827 -0.9230029 -0.3847124 0.00788182 -0.9513931 -0.3079669 -0.002742588 -0.9859703 -0.04952394 -0.1594059 -0.9843626 -0.08944481 -0.1517563 -0.9842827 -0.09522134 -0.1487295 -0.9795536 -0.1435346 -0.1409699 -0.978914 -0.1601437 -0.1268121 -0.9687013 -0.2300469 -0.09325432 -0.9687778 -0.2176613 -0.1187149 -0.9680017 -0.2302459 -0.09979754 0.7056635 -0.1766172 0.6861818 -0.1082612 -0.9846463 0.1369351 -0.1203287 -0.9798577 0.1593736 -0.03647768 -0.9878966 0.1507641 -0.03773152 -0.9843496 0.172141 0.04164099 -0.9841983 0.1721041 0.03296458 -0.9880757 0.150399 0.1264752 -0.9789876 0.1599605 0.1061433 -0.9843846 0.14043 0.5645973 0.1225073 0.8162242 0.6107822 -0.173619 0.7725293 0.3439412 -0.1756542 0.9224154 0.2320453 0.1615945 0.9591884 0.1173452 -0.1756622 0.9774318 -0.1265568 -0.1754596 0.9763183 -0.2321789 0.1591643 0.9595623 -0.3525267 -0.1758424 0.9191324 -0.5676748 -0.1751909 0.8043965 -0.6201878 0.006606757 0.7844256 -0.7122787 -0.1772167 0.6791563 -0.3357164 -0.8408206 0.4246354 -0.3357301 -0.8408135 0.4246388 -0.1281572 -0.8384639 0.5296734 -0.128149 -0.838476 0.5296564 0.1281415 -0.8384663 0.5296736 0.1281658 -0.8384742 0.5296552 0.3357076 -0.8408176 0.4246484 0.3357353 -0.840816 0.4246295 -0.5240818 -0.5347439 0.662863 -0.5240713 -0.534766 0.6628534 -0.1992382 -0.5311626 0.8235111 -0.1992753 -0.531116 0.8235323 0.1992772 -0.5311136 0.8235332 0.199234 -0.5311676 0.8235089 0.5240668 -0.5347695 0.6628542 0.5240903 -0.5347313 0.6628665 0.9638867 -0.2510191 -0.08894836 0.9852831 -0.01443248 0.1703206 0.9883383 -0.00226289 0.1522577 0.9859213 -0.0677241 -0.1528813 0.9998964 -0.004749655 0.01359462 0.9986082 -0.03664946 0.03792858 0.9974787 -0.02394253 0.06680631 0.9916177 -0.08125776 0.1004568 0.9717184 -0.03769248 0.2331152 0.9676647 0.03669971 0.249556 0.9732431 -0.1625576 0.1623982 0.9772167 -0.1307039 0.1672241 0.9537566 -0.2932983 0.06576037 0.9311171 -0.3595997 0.06090229 0.8988238 -0.4356943 -0.04781424 0.9997572 0.003063797 0.02182549 0.9819575 -0.111739 -0.1525579 0.9741614 -0.212705 -0.07593584 0.9567372 -0.2192202 -0.1913022 0.9634241 -0.2350186 -0.1287644 0.7823472 1.37924e-6 0.6228426 0.852309 -0.01945567 0.5226766 0.8605117 -0.01444637 0.509226 0.999707 -9.27166e-5 0.02421104 0.9960195 -0.002299308 0.0891059 0.9895161 -0.009368896 0.144119 0.9851674 -0.01358741 0.1710576 0.983112 -0.01581144 0.1823211 0.9646921 -0.002935886 0.2633641 0.9191439 0.001923263 0.3939175 0.9848784 -0.1732474 0 0.9848768 -0.1732565 -8.53576e-7 0.933434 -0.3587493 0 0.8334276 -0.5526277 -0.001146793 0.8435829 -0.5369992 -2.26807e-6 0.5369514 -0.8436132 2.49102e-6 0.536872 -0.8436638 -3.67962e-6 0.1732454 -0.9848787 2.92302e-6 0.1731879 -0.9848888 0 -0.5096243 0.860391 -0.003245115 -0.9974278 0.06092923 0.03775399 -0.8126046 0.5792895 -0.06401294 -0.7265824 0.6791959 0.1037834 -0.6520532 0.758067 0.0126903 -0.4850834 0.872559 0.05774867 -0.9696482 0.2220129 -0.1024347 -0.9695748 0.2277649 -0.08970957 -0.8901556 0.4454995 0.09567284 -0.8919458 0.4463496 0.07214605 -0.7307097 0.6793931 0.06699573 -0.6775141 0.6727328 0.2973303 -0.456092 0.8815288 -0.1220133 -0.4962934 0.8518788 -0.167319 -0.4069664 0.9086785 -0.09317731 9.54913e-5 1 -4.61859e-5 2.66431e-6 1 1.35469e-5 3.22118e-6 1 1.1829e-5 -2.66431e-6 1 1.35469e-5 -3.22118e-6 1 1.23433e-5 3.18575e-5 1 1.61656e-5 -3.18284e-5 1 1.61528e-5 3.36612e-7 1 0 -2.04851e-4 1 -1.83652e-5 -8.09107e-5 1 -4.09733e-5 5.29462e-5 1 -5.0787e-5 9.53169e-6 1 2.87072e-5 -3.36578e-7 1 0 0.4240177 0.8942651 -0.1431747 0.3646751 0.9273887 -0.08344119 0.4423913 0.8962181 -0.03291243 0.8658689 0.4976715 -0.05093342 0.990327 0.1336006 0.03746175 0.8337978 0.5472869 0.07251566 0.7312324 0.6799693 0.05423212 0.7189093 0.6824889 0.1318269 0.5141577 0.8576815 -0.004926621 0.5054539 0.8628212 0.007485449 0.5578226 0.8171564 -0.1452221 0.7260557 0.6789543 0.1089231 0.781696 0.6228573 0.03162455 0.8631601 0.503722 0.03491395 0.9072621 0.417971 -0.04664719 0.9517701 0.2711935 0.1434854 0.9918227 0.05116075 -0.1169213 0.9827657 -0.02338838 -0.1833706 0.9843469 -0.001664638 -0.1762344 0.9999536 -0.001675188 -0.009494423 -0.1731942 -0.9848877 0 -0.2588177 -0.9659167 0.004297554 -0.997802 -0.06626671 0 -0.9848749 -0.1732555 -0.002019405 -0.9466494 -0.3222544 0.002668321 -0.9064746 -0.4222605 0 -0.844763 -0.5351406 0 -0.7933348 -0.6087849 -0.001043736 -0.6774625 -0.7355499 0.003315985 -0.6087352 -0.7933734 0 -0.4222118 -0.9064974 0 -0.9185964 0.001868903 0.3951928 -0.9832199 -0.005605995 0.1823383 -0.9663659 -0.03220063 0.2551474 -0.9772257 -0.02187579 0.2110718 -0.9823263 -0.01646482 0.1864513 -0.9886088 -0.01007771 0.1501705 -0.9953975 -0.003292381 0.09577548 -0.9992586 -3.59918e-4 0.03849756 -0.9999694 0 0.007832467 -0.8524719 -3.69483e-6 0.5227732 -0.7983504 -0.04860526 0.6002284 -0.8622552 -0.01415252 0.5062766 -0.9852728 -0.02014374 -0.1697994 -0.9656559 0.0845474 -0.2456837 -0.9943886 -0.001690566 -0.1057755 -0.9999527 -0.00168693 -0.009582936 -0.9747198 0.2232356 -0.009349465 -0.5877897 0.8090139 0 -0.6501052 0.7557542 -0.07873392 -0.4858274 0.8738617 0.01836919 -0.2468534 0.968538 -0.03158777 -0.5782477 0.8158611 -6.21316e-4 -0.8473158 0.5310888 7.6403e-4 -0.8142575 0.580497 -0.002872407 -0.9843201 0.1763668 0.002956688 -0.9749585 0.2223871 0 -0.5387792 -0.3122748 -0.782433 -0.4472015 0 -0.8944333 -0.20121 0 -0.9795482 -0.2012339 0 -0.9795433 0.2012327 0 -0.9795435 0.2012111 0 -0.9795479 0.4472399 0 -0.8944141 0.538876 -0.311868 -0.7825287 0.2599117 0.9643529 -0.04969465 0.9843248 0.1763661 -1.44374e-7 0.9909757 0.1337115 -0.009409248 0.9911614 0.1326433 -0.002222836 0.9082494 0.4184265 0.001533269 0.8473142 0.5310842 -0.002870142 0.7820893 0.6231665 -2.08287e-4 0.3695631 0.9291819 -0.006664872 0.5634194 0.8253875 0.0359745 0.5949014 0.8037988 0 0.5877897 0.8090137 4.62129e-4 -1 0 -1.35804e-7 0.8148012 2.50243e-4 0.5797405 0.7491602 -0.03140234 0.6616441 0.7936923 -0.005573868 0.608294 0.6337434 0.004452168 0.7735306 0.6142101 -0.0045771 0.7891293 0.5312893 7.34131e-5 0.8471905 0.4229115 -7.45714e-4 0.9061707 0.4289147 -0.003463864 0.9033383 0.1801899 0.004689753 0.9836207 0.1878469 0 0.9821983 -0.04354286 0 0.9990516 -0.209338 0.05440813 0.9763286 -0.2887626 -3.8904e-6 0.9574007 0.999999 0 0.001441121 0.9986428 -1.12024e-4 0.05208224 0.9738503 -0.01302582 0.2268174 0.9337038 -0.06147748 0.3527292 0.8831844 -4.91715e-5 0.469026 0.9093204 -0.002721726 0.4160878 0.9845359 0.02908402 0.1727518 -0.1411429 0.405157 0.9032865 0.1800293 -0.03878456 0.9828963 -0.04285168 0.1757904 0.9834945 -0.2843853 0.173965 0.9427945 0.6047141 0.175301 0.776911 0.5216129 0.02975177 0.8526635 0.7815087 0.1746281 0.5989568 0.8400203 0.04052805 0.5410391 0.8951715 0.1757884 0.4095931 0.9699626 0.1737958 0.1701993 0.9699628 0.1737973 0.1701962 0.584693 0.8047415 0.1025943 0.1349248 0.7636505 0.6313741 0.5846868 0.8047459 0.1025935 0.5023995 0.8018054 0.3235781 0.5024039 0.8018019 0.3235801 0.3118475 0.8018063 0.5097625 0.3118594 0.8018036 0.5097597 0.1227889 0.807162 0.5774189 0.1604558 0.8528584 0.4968768 -0.1443917 0.386523 0.9109067 0.09095913 0.4009924 0.9115544 0.09780603 0.1720353 0.9802234 0.4163783 0.175261 0.8921394 0.04929059 0.6360646 0.7700599 0.1771399 0.5286039 0.8301804 0.4453116 0.5213938 0.7279053 0.4452986 0.5213941 0.727913 0.7174016 0.5213907 0.4620463 0.7173905 0.5214 0.462053 0.8381032 0.5253155 0.1470608 0.8381031 0.525316 0.1470593 0 1 1.90263e-7 0 1 -1.1145e-6 0 1 -3.30245e-6 0 1 7.47317e-6 -0.3118458 0.8018072 0.5097623 -0.1818568 0.1747031 0.9676812 -0.9699642 0.1737906 0.170195 -0.9699612 0.1738014 0.170201 -0.5140638 0.1720408 0.8403217 -0.4230897 -0.1102709 0.8993529 -0.6070675 0.175366 0.7750587 -0.8281824 0.1720671 0.5333918 -0.7941392 -0.03484207 0.6067365 -0.89578 0.175823 0.408246 0.03842377 0.1757262 0.983689 0.2816009 0.2216266 0.9335859 0.1571722 0.1762572 0.9717152 0.1439088 0.3864435 0.911017 -0.09921658 0.0375387 0.9943576 -0.07869535 0.6097207 0.7887001 0.1440406 0.3864361 0.9109992 -0.3118607 0.8018026 0.5097602 -0.5024063 0.8018018 0.3235769 -0.5023977 0.8018051 0.3235816 -0.584688 0.804745 0.1025941 -0.584693 0.8047415 0.1025943 -0.8381032 0.5253155 0.1470603 -0.8381016 0.525318 0.1470606 -0.7173878 0.5214058 0.4620506 -0.717403 0.5213863 0.4620491 -0.4453052 0.5213921 0.7279105 -0.4453037 0.5213962 0.7279085 -0.1655775 0.5279587 0.832973 -0.126115 0.8073481 0.5764408 -0.1619169 0.8499501 0.5013659 -0.04773736 0.9464126 0.3194125 -0.04934555 0.1048492 0.9932632 0.04415589 0.01428079 0.9989227 -0.05073827 0.05105972 0.997406 0.07641905 0.07362949 0.9943535 0.04254132 0.1802751 0.9826958 0.0202353 0.213766 0.9766753 0.1932288 0.08874017 0.9771324 0.1377366 0.3888044 0.9109665 0.2270561 0.1691346 0.9590824 -0.4954147 0.8071845 0.3209637 -0.5761986 0.649576 0.4960304 -0.5778176 0.7424639 0.338931 -0.5036285 0.7024297 0.5029422 -0.5431435 0.6965628 0.4688235 -0.7209529 0.1580094 0.6747296 -0.8440247 0.174232 0.5072136 -0.8836687 0.1619159 0.4392188 -0.7940796 0.3275082 0.5120314 -0.7124923 0.5001423 0.4921509 -0.7932647 0.492268 0.3583345 -0.6113166 0.6110984 0.5028427 0.07158482 0.818331 0.5702719 -0.03810197 0.8850671 0.4639014 -0.1901032 0.84325 0.5027825 -0.2235528 0.8523185 0.4728398 0.1601429 0.6018555 0.7823837 0.08659809 0.6924521 0.7162478 -0.05739456 0.6537643 0.7545185 -0.2519442 0.755223 0.6051137 -0.6021839 0.1379675 0.7863458 -0.6323501 0.1370083 0.762471 -0.5253869 0.4122476 0.7443256 -0.4954329 0.4063776 0.7677263 -0.3604459 0.5594674 0.7463746 -0.3357892 0.5545595 0.7613865 -0.2227155 0.6388605 0.7363798 -0.3899226 0.7869285 0.47823 -0.3612422 0.7840829 0.504696 -0.5713133 0.7559884 -0.3195038 0.210005 0.1964433 0.957762 -0.2290672 0.8224555 0.520668 -0.1097276 0.9929857 0.0440393 0.188434 0.4246133 0.8855485 0.1909182 0.419867 0.8872779 0.03974717 0.37739 0.9252011 -0.0136941 0.4310838 0.9022081 -0.1192607 0.35297 0.9280028 -0.1463798 0.3620167 0.9206067 -0.2363035 0.2631537 0.9353668 -0.2714779 0.2734555 0.9227794 -0.3407384 0.09578305 0.9352663 -0.390524 0.09310525 0.9158725 -0.857235 9.6959e-4 0.5149247 -0.8283933 0.07971477 0.5544458 -0.05099296 -7.55123e-4 0.9986988 -0.05116748 0 0.9986901 -0.3919266 0 0.9199966 -0.4895132 0.1532769 0.858419 -0.6079745 0 0.7939566 -0.7302262 0 0.6832055 0.04840552 -7.54843e-4 0.9988275 0.04822862 0 0.9988364 0.2889459 0 0.9573455 0.4905859 0.0687049 0.8686802 0.5187769 0 0.8549097 0.8303479 0 0.5572454 0.7691616 0.1739512 0.614924 0.8952166 9.437e-4 0.4456303 -0.1674631 0.01508659 0.9857629 -0.1641817 0.04306399 0.9854897 -0.209428 0.03863668 0.9770605 -0.2429564 0.1692465 0.9551585 0.04800117 0.05212622 0.9974862 -0.04355728 0.02819722 0.9986529 -0.1259592 0.0273258 0.9916591 0.8938382 0.05534899 0.4449607 0.9779844 0.1843543 0.09777516 0.4242617 0.8143609 0.3960033 0.3803332 0.6817221 0.6249814 0.5645475 0.7126244 0.4164763 0.6676347 0.602741 0.4369979 0.8458024 0.5281198 0.0755499 0.7794568 0.4540055 0.4316552 0.8638076 0.2339417 0.4462151 0.04424947 0.9466972 0.3190713 0.02906894 0.9370053 0.3481037 -0.001794576 0.8836056 0.4682286 -0.06256675 0.7727768 0.6315866 -0.05951106 0.7979996 0.5997126 0.2095714 0.7175073 0.6642765 -0.2733374 -0.1116225 0.9554199 -0.2290445 0.198142 0.9530364 -0.1323371 0.1705453 0.9764226 -0.09930551 0.2630158 0.9596673 -0.03742629 0.2165919 0.9755446 -0.04661148 0.1824601 0.9821078 0.01853281 0.112158 0.9935176 0.09171545 0.1764073 0.9800352 0.1396053 0.05378913 0.9887452 0.2882564 0.08528316 0.9537479 -0.1473196 0.5190244 0.8419682 -0.1481208 0.5461117 0.8245134 0.0481103 0.488867 0.8710308 0.07299381 0.5508251 0.8314226 0.2260918 0.438888 0.8696321 0.2341354 0.4620651 0.855381 0.3587652 0.3239692 0.8754037 0.3833726 0.3460731 0.8563054 0.473937 0.1163009 0.8728448 0.5142139 0.1340197 0.8471262 0.2494839 0.8793584 0.4055696 0.2460379 0.8782609 0.4100283 0.32816 0.9237712 0.1973776 0.2995041 0.7200039 0.6260126 0.433036 0.6193503 0.6548932 0.4384416 0.6372122 0.6338215 0.6006593 0.4511787 0.660035 0.6188319 0.4676232 0.63117 0.7416455 0.154365 0.652789 0.7702339 0.1662831 0.6157027 -0.2885515 0.6173239 0.7318806 -0.05552619 0.992165 0.1119173 -0.124852 0.9579776 0.2582458 -0.2311594 0.7764087 0.5863062 -0.2365342 0.7654419 0.5984566 -0.1726308 0.8819178 0.4386569 -0.1672373 0.8900048 0.4241735 -0.06742179 0.982961 0.1710029 -0.1043229 0.9546037 0.2790139 -0.3615422 0.1685504 0.916994 -0.368167 0.09109729 0.9252861 -0.354411 0.2575181 0.8989313 -0.3134381 0.5193948 0.7949753 -0.3521414 0.349206 0.8683615 -0.3295828 0.4585346 0.8253008 0.5352163 0.3869875 0.7508558 -0.4705386 0.6230906 0.6247813 -0.891919 0.06066596 0.4481074 -0.535171 0.03604388 0.8439745 0.2453979 0.7457265 0.6194126 0.2561617 0.7396968 0.622278 0.2615734 0.8467619 0.4632211 0.2559004 0.8500708 0.4603203 0.2293752 0.8365682 0.4975348 0.2512798 0.8257666 0.5049437 0.2137491 0.818221 0.5336908 0.2764365 0.7897976 0.5475425 0.2082561 0.791579 0.5744842 0.2834529 0.7578815 0.5875969 0.3122366 0.8241717 0.4724929 0.3038583 0.8769186 0.3724029 0.401836 0.7006754 0.5895607 0.5608724 0.08193385 0.8238381 0.6033881 -0.1568602 0.7818681 0.3200101 0.2143245 0.9228535 0.2244235 0.0570476 0.9728205 0.01565331 0.1876996 0.9821017 0.01510477 0.1894915 0.9817662 -0.1384478 0.1348547 0.9811456 -0.2475721 0.1806048 0.9518876 -0.2656793 0.2150826 0.9397627 -0.3106003 0.1982551 0.9296356 -0.5963774 0.1450167 0.7894961 -0.6012326 0.1254901 0.7891589 -0.7713391 0.06846803 0.6327306 -0.7826552 0.2054259 0.5875808 -0.8387657 0.1730272 0.516269 -0.9699791 0.2045732 0.1314929 -0.6937787 0.4729691 0.5431126 -0.8273097 0.3534492 0.4366148 -0.8693844 0.2731997 0.4117437 -0.9607889 0.1579611 0.227888 -0.9760178 0.04620534 0.2127311 -0.5982831 0.5322616 0.5989616 -0.6435318 0.488572 0.5892064 -0.6141997 0.3954057 0.6829445 -0.619018 0.3866826 0.6835885 -0.5090486 0.2480144 0.8242321 -0.5045205 0.2686823 0.8205296 -0.3762286 0.1775504 0.9093558 -0.4614471 -0.01582032 0.8870267 0.4972154 0.5723351 0.6520808 0.4050472 0.6817529 0.6092206 0.2988866 0.68661 0.662747 0.3165889 0.6683701 0.6730921 0.1721764 0.7011789 0.6918841 0.1918805 0.6661677 0.7206959 0.08202505 0.7128628 0.6964902 0.08619832 0.6798792 0.7282405 0.02891266 0.7210363 0.6922938 0.0229116 0.704537 0.7092974 0.008853077 0.7225189 0.6912946 0.01547145 0.7282178 0.6851711 0.01627933 0.724951 0.6886081 -0.02421069 0.6950451 0.7185585 0.582117 0.2611474 0.7700272 0.5349629 0.381718 0.7537283 0.3200116 0.3930803 0.8620212 0.3331826 0.3710476 0.8667832 0.07815909 0.4285399 0.9001359 0.09173017 0.3874831 0.9173018 -0.1173188 0.475487 0.8718649 -0.1163766 0.4371675 0.8918189 -0.2503706 0.5324859 0.8085627 -0.2563571 0.5134102 0.8189574 -0.3217505 0.5961924 0.7355483 -0.3154665 0.6037467 0.7321004 -0.3263683 0.6409613 0.6947319 -0.246048 0.6950024 0.6755976 -0.498003 0.4003423 0.7692329 -0.2890971 0.7379939 0.6097442 0.211946 0.7037686 0.6780773 0.4500941 0.6113702 0.6508777 0.7859521 0.3939632 0.4765213 0.5736004 0.5587217 0.5990099 0.7043607 0.7043607 0.08804506 0.6232019 0.04708147 0.7806426 0.7017382 0.2479428 0.6678981 0.631469 0.1754428 0.7552927 0.6626682 0.3782182 0.6463915 0.6930049 0.1876888 0.6960728 0.6753716 0.09850674 0.7308691 -0.2237724 0.08415353 0.9710016 -0.3916876 0.06070291 0.9180936 -0.3173574 0.255878 0.9131324 -0.5092344 -0.3255001 0.7966994 -0.5093011 -0.2834862 0.8125564 -0.6935946 0.2011712 0.6917057 -0.7045818 0.2005832 0.6806841 0.4316934 -0.3592336 0.8274009 0.3369847 -0.1087048 0.9352138 0.3922624 -0.07794284 0.9165453 0.31249 -0.06457918 0.9477233 0.367852 0.03352141 0.92928 0.1370943 -0.05901789 0.9887983 0.2495537 0.4006998 0.8815683 0.03033363 0.03448611 0.9989448 0.9511043 0.2064635 0.2297245 0.9730685 0.06976914 0.2197043 0.8935502 0.2596601 0.3662579 0.8458472 0.3168384 0.429134 0.8373637 0.3237948 0.4404307 0.809766 0.2308852 0.5394174 0.7059007 0.2573343 0.6599116 0.6863277 0.476862 0.5491421 0.6690511 0.4833599 0.5645653 0.6478186 0.4123428 0.6405501 0.4342997 0.5594655 0.705962 0.3966677 0.5558474 0.7305399 0.3407135 0.4428476 0.8293373 0.9212345 0.06247442 0.3839585 0.8945791 0.09400385 0.4369115 0.8538058 -0.01006841 0.5204944 0.6983069 0.2441084 0.6728883 0.6996234 0.2442733 0.6714594 0.4169393 0.5099988 0.7523716 0.3801605 0.4630732 0.8006504 0.2764202 0.4712733 0.837552 0.4856005 0.2033982 0.850189 -0.06356453 0.3110594 0.9482625 -0.1103398 0.08775281 0.9900124 -0.07751792 0.1225092 0.9894354 -0.1298042 0.3918614 0.9108213 0.02425217 0.3086528 0.9508656 0.1718988 0.368135 0.9137437 0.1057492 0.416861 0.9027979 0.2457582 0.3762586 0.8933265 0.3816681 0.1450107 0.9128534 0.4854131 0.2185179 0.8465366 0.6786996 -0.1743348 0.7134244 0.2968885 0.2730031 0.9150556 -0.06027251 0.7284832 0.6824071 -0.1232779 0.7015795 0.7018468 -0.1465619 0.7476628 0.6477037 -0.1378539 0.7548979 0.6411907 -0.1266545 0.7665137 0.6296154 -0.1569992 0.7610057 0.6294614 -0.1433894 0.7742639 0.6164049 -0.1940705 0.7704682 0.6072193 -0.1960724 0.7696278 0.6076419 -0.2459861 0.781782 0.5729815 -0.2813762 0.7702889 0.5722609 -0.3200826 0.7888023 0.5247268 -0.2312511 0.06006973 0.9710379 -0.2508088 0.271554 0.9291681 -0.3822128 0.3934116 0.8361464 -0.3310983 0.2727573 0.9033147 -0.5825047 0.2584088 0.7706576 0.4455575 0.6151092 0.6504762 0.206544 0.7078925 0.6754464 0.1907845 0.6574859 0.7289127 0.2002906 0.656849 0.7269341 0.1588145 0.6034576 0.7814198 0.1395171 0.6089136 0.780871 0.05707448 0.5500239 0.8331965 0.02419769 0.5687368 0.8221636 -0.1145836 0.5106143 0.8521406 -0.1394159 0.5366561 0.832204 -0.3225975 0.4952612 0.8066271 -0.3300104 0.5125339 0.7927183 -0.5183865 0.5013715 0.6927497 -0.5180928 0.4928303 0.6990696 -0.3940463 0.7628222 0.5126695 -0.321032 0.7955942 0.5137786 -0.455263 0.6385982 0.6204256 -0.0491451 0.1573755 0.9863153 0.510954 0.3278366 0.7946379 0.4410023 0.2684469 0.856419 0.4398856 0.1528698 0.8849472 0.4088022 0.3131327 0.8572216 0.4092111 0.4660736 0.7844245 0.04040515 0.6267737 0.7781531 0.2445402 0.6394504 0.7289056 -0.9831327 0.006680011 0.1827715 -0.3773545 0.2470242 0.8925148 -0.5950488 0.4848211 0.6409879 -0.3806552 0.4897419 0.7843818 -0.1714526 0.5763478 0.7990165 -0.4698134 0.6028276 0.6448833 -0.9922521 0.03557807 0.1190379 -0.9671506 0.0833314 0.2401573 -0.9645736 -0.07984429 0.2514412 -0.7998254 0.1205341 0.5880057 -0.8198214 0.0723263 0.5680335 -0.5956646 -0.002282261 0.8032302 -0.4640073 0.1527166 0.872568 0.2064599 0.2590042 0.9435524 0.2059924 0.3336492 0.919916 0.1719562 0.3509348 0.9204759 0.1721046 0.5029913 0.8469828 0.1146157 0.5281718 0.8413667 0.1150313 0.6463144 0.7543512 -0.02446073 0.7008858 0.712854 0.3975337 0.03301823 0.9169933 0.3328114 -0.07386827 0.9400959 0.3349983 0.1500824 0.9301889 -0.04926425 0.1699522 0.9842202 0.3260206 0.3157801 0.8910632 -0.09875804 0.2535524 0.9622671 -0.09990984 0.5260989 0.8445343 -0.157131 0.5073988 0.8472641 -0.1574875 0.6734755 0.7222385 -0.2449541 0.6471351 0.7219514 -0.6912303 0.4442979 0.5699125 -0.6298378 0.4636464 0.6231665 -0.8259606 0.3399932 0.4496597 -0.8266561 0.3395479 0.448717 -0.9696986 0.1427972 0.198226 -0.9972101 0.04637914 0.05849117 -0.9503709 0.1692249 0.2610709 -0.9498303 0.08636778 0.3006048 -0.8271216 0.141496 0.5439198 -0.7964991 0.1608509 0.5828518 -0.6300271 0.1967343 0.75124 -0.5889841 0.2141592 0.7792519 -0.3294333 0.2382048 0.9136368 -0.3336334 0.001490712 0.9427018 -0.01267176 0.08985269 0.9958745 -0.6407224 3.97718e-5 0.7677727 -0.7689274 -2.54559e-5 0.6393362 -0.7895663 3.22238e-4 0.6136652 -0.893011 -5.37254e-4 0.4500347 -0.9051274 -5.55959e-5 0.4251407 -0.9876513 7.35574e-5 0.1566684 -0.9814406 -7.37168e-4 0.1917651 -0.9993069 -2.07036e-5 0.03722709 -0.01267659 -0.003335833 0.9999142 -0.1649488 -8.08177e-4 0.9863019 -0.2908704 1.48656e-4 0.9567625 -0.4760025 -4.6246e-4 0.8794438 -0.3663458 -0.003222405 0.9304732 -0.6729536 0.004509449 0.7396711 -0.4584801 -0.003561794 0.8886977 -0.5445442 -0.001854896 0.8387302 -0.1156637 -1.81347e-4 0.9932884 0.1902862 9.67844e-5 0.9817287 0.2197731 6.09979e-4 0.9755508 0.7355049 1.65226e-5 0.6775195 0.5629235 1.56275e-4 0.826509 0.6246643 0.003169059 0.780887 0.4016174 -4.99122e-4 0.9158076 -0.7271932 0 0.6864328 -0.532732 -7.3397e-4 0.8462837 -0.09948748 -0.007202565 0.9950128 -0.7232831 0.01000726 0.6904792 -0.6191701 0.003899276 0.7852473 -0.3114306 -0.001729071 0.9502673 -0.2168049 -0.003443062 0.9762089 0.3747031 0.00209254 0.9271425 -0.3904895 0.00388205 0.9205992 -0.1900851 1.87339e-4 0.9817677 0.03571444 -1.9613e-4 0.9993621 0.1141598 -0.001634538 0.9934611 0.3748905 0.002091944 0.9270668 0.3753179 0.002092182 0.9268938 0.6355397 -3.74e-4 0.7720682 0.3767053 -0.004264175 0.9263234 0.3766794 -0.004263401 0.9263339 0.3757272 0.002092301 0.9267279 0.4772863 0.001446187 0.8787468 0.6753699 0.0061872 0.7374533 0.851951 -0.001664996 0.5236189 0.8931132 3.58415e-4 0.4498319 0.7893294 -5.89762e-5 0.6139701 0.7703468 -1.80416e-4 0.6376252 0.7545229 -1.76462e-5 0.6562739 0.7041072 1.11449e-5 0.7100937 0.9334225 1.80533e-4 0.358779 0.9876406 -3.55766e-4 0.1567352 0.9902962 -1.45081e-6 0.1389735 0.8944904 0.2676082 0.3581517 0.3339679 -1.40353e-4 0.9425845 0.4696124 0.1540502 0.869329 0.9915077 0.0749889 0.1062508 0.9761949 -0.1267958 0.175973 0.6302525 0.196744 0.7510484 0.9617887 0.05451524 0.2683107 0.9774525 0.06357163 0.2013589 0.9410208 0.2632958 0.2124977 0.9492318 0.1906333 0.250236 0.9783113 0.1151028 0.1722158 -0.3941242 -0.1114723 0.9122719 -0.3360288 0.03405612 0.9412358 -0.3328158 0.204672 0.9205124 -0.4396718 0.1529363 0.885042 -0.4401825 0.3096911 0.8428114 -0.4322237 0.3081176 0.8474942 -0.2052156 0.3471115 0.9150957 -0.2054892 0.1597196 0.9655382 0.04884248 0.1699671 0.9842386 0.0488708 0.1546774 0.9867556 0.01633858 0.09456592 0.9953845 0.7991829 0.1309485 0.5866509 0.7965958 0.1608473 0.5827208 0.8270366 0.1416046 0.544021 0.8263493 0.3425775 0.446976 0.8462651 0.3216835 0.4246822 -0.06003206 0.6677067 0.742 0.2114924 0.6638359 0.7173514 0.1576837 0.6520595 0.7415891 0.4452129 0.6106254 0.6549215 0.1176977 0.5936227 0.79609 0.5681801 0.4942771 0.6579222 0.6291205 0.4718404 0.6177169 0.6825312 0.4381364 0.5849682 0.7838955 0.3727399 0.4965612 -0.2881942 0.638372 0.7137404 -0.1146655 0.6745254 0.7292923 -0.1145691 0.5112436 0.8517653 0.1576226 0.5260151 0.8357413 0.1001046 0.5075806 0.8557693 0.3803817 0.4898508 0.7844463 0.8254025 0.06651324 0.5606127 0.5957539 8.60916e-4 0.8031667 0.5888009 0.2142587 0.779363 0.3293921 0.2382606 0.9136371 0.3775562 0.2470602 0.8924196 -0.1302962 0.2437784 0.9610385 0.1000042 0.3552411 0.92941 -0.1721128 0.3378016 0.9253472 -0.1716941 0.5202088 0.8366027 -0.3856248 0.4731133 0.792122 -0.007063329 0.6220632 0.7829353 -0.3964344 0 0.9180631 0.9841347 0 0.1774232 0.9841482 0 0.1773486 0.8273018 0 0.5617579 0.5742212 0 0.8187002 0.4741911 -0.0711497 0.8775423 -0.3966175 0 0.917984 0.01640516 0 0.9998654 0.01640516 0 0.9998655 0.3633784 0 0.9316416 -0.9831969 2.3795e-4 0.1825485 0.3975492 -3.54365e-4 0.9175809 0.3974742 0 0.9176134 0.159509 0 0.9871966 -0.01259922 -0.05593669 0.9983549 -0.07781106 0 0.9969682 -0.3612874 0 0.9324546 -0.4684742 -0.07036489 0.8806707 -0.9831554 0 0.1827722 -0.821944 0 0.5695684 -0.8219964 0 0.5694927 -0.5710438 0 0.8209196 0.1861525 0.6947504 0.694744 0.186163 0.6947326 0.694759 0.5086075 0.6947302 0.5085946 0.5085915 0.6947456 0.5085896 0.6947333 0.694759 0.1861606 0.694761 0.6947322 0.1861568 0.6947529 0.69474 -0.1861582 0.6947401 0.6947536 -0.1861554 0.5086029 0.6947368 -0.5085901 0.508567 0.6947597 -0.5085948 0.1861649 0.6947488 -0.6947423 0.1861445 0.6947519 -0.6947447 -0.1861401 0.694752 -0.6947456 -0.1861723 0.6947494 -0.6947397 -0.5085793 0.6947526 -0.5085921 -0.5085927 0.6947437 -0.5085909 -0.6947466 0.6947466 -0.1861573 -0.6947466 0.6947466 -0.1861568 -0.6947493 0.6947429 0.1861606 -0.694747 0.6947461 0.1861573 -0.5085934 0.6947414 0.5085934 -0.508608 0.6947314 0.5085924 -0.1861687 0.6947338 0.6947563 -0.1861445 0.6947519 0.6947447 0.9999802 -0.006307244 0 0.9959661 -0.08972835 -5.40277e-4 0.9658005 -0.2587864 -0.01609438 0.2426575 -0.9701121 -2.53019e-5 0.2588181 -0.9659124 -0.005148112 0.6087603 -0.7933481 0.003122329 0.9682159 -0.2494722 -0.01793426 0.8959789 -0.4440909 0.002251863 0.793357 -0.6087501 -0.002838313 0.7796767 -0.6261824 -3.03387e-5 0.5955401 -0.8033256 4.01518e-5 0.9738288 -0.2270101 -0.01112824 0.9659257 -0.2588177 0.001043975 0.8813076 -0.4720137 -0.02236443 0.7930238 -0.6085085 -0.02882289 0.7498162 -0.6599584 -0.04722893 0.6084733 -0.7929877 -0.03051251 0.550958 -0.8335617 -0.04025274 0.4078708 -0.9119776 -0.04402714 0.258768 -0.9657327 -0.01998829 0.1570889 -0.9863446 -0.04947096 -0.05093395 -0.9987021 -4.42662e-6 -0.8314648 -0.5555775 -6.42287e-5 -0.8036943 -0.5949329 -0.01142275 -0.9118379 -0.4105485 0.001256942 -0.9807765 -0.1950891 -0.004222452 -0.975166 -0.2212726 -0.009478211 -0.9986314 -0.05230152 0 -0.1950793 -0.9807372 -0.009933829 -0.2266644 -0.9739661 -0.003652989 -0.5555666 -0.8314543 0.005440354 -0.461095 -0.8870021 -0.02487385 -0.636334 -0.7714138 3.0805e-5 -0.1948544 -0.9796007 -0.04913341 -0.155981 -0.9870761 -0.03675317 -0.5547658 -0.8302689 -0.05374634 -0.4624657 -0.8865174 -0.014575 -0.8300827 -0.5546551 -0.05762511 -0.7691857 -0.6388719 -0.01400393 -0.9805186 -0.1950376 -0.02331602 -0.9737941 -0.2271592 -0.01113528 0.8646182 -0.5024295 -4.43711e-4 0.999999 -0.0014894 0 0.9694947 -0.2450994 0.002539753 0.9620472 -0.2727031 0.00991863 0.9979826 -0.06348937 7.26043e-5 0.7356973 -0.6772235 0.01085531 0.6739879 -0.7366024 0.05618989 0.7516807 -0.6594613 0.009329259 0.3028057 -0.9456189 0.1188005 0.3626345 -0.9300754 0.05878841 0.443553 -0.8962229 -0.006733059 -0.443553 -0.8962229 -0.006733059 -0.3626345 -0.9300754 0.05878841 -0.3027967 -0.9456216 0.1188024 -0.6034075 -0.7974296 0.002318084 -0.734701 -0.6780918 0.02014905 -0.75168 -0.6594621 0.009329378 -0.999999 -0.0014894 0 -0.9979833 -0.0634787 7.26043e-5 -0.9693944 -0.2453572 0.008623898 -0.9568275 -0.2906496 0.00204122 -0.86462 -0.5024262 -4.43795e-4 0.8060827 -0.452984 0.380836 0.1065872 -0.9911051 -0.07968658 0.9965255 -0.08291375 -0.007888615 0.9876058 -0.142619 0.06553506 0.943447 -0.3315026 -0.003734946 0.9218212 -0.3830256 0.05947387 0.8861793 -0.4578208 0.0713188 0.9999986 -0.001712322 2.78699e-7 0.9993 -0.02466756 0.02812826 0.9990894 -0.03741538 0.02051091 0.9839252 -0.1247506 0.1277835 0.9803951 -0.166317 0.1056601 0.94511 -0.2499157 0.2104977 0.9395975 -0.2685012 0.212282 0.93204 -0.10249 0.3475589 0.9731744 -0.01040434 0.2298333 0.9811203 -0.09125822 0.1705137 0.9984523 0.002709329 0.0555489 0.8660973 -0.1167867 0.4860417 0.9203654 -0.09389746 0.3796195 0.9357648 -0.06798702 0.3460087 0.2657891 -0.9251315 0.2710865 0.3566487 -0.907994 0.2198833 0.4726932 -0.866109 0.1625313 0.4902194 -0.8585281 0.1503814 0.6485463 -0.7431127 0.1648369 0.6599334 -0.735512 0.1533299 0.7307558 -0.674676 0.1039637 0.786666 -0.4731177 0.3966313 0.7160812 -0.5198947 0.4657654 0.6756331 -0.5729522 0.4639461 0.5856152 -0.6115459 0.5320399 0.5370557 -0.6319041 0.5588098 0.2030692 -0.943796 0.2607915 0.3325066 -0.8352718 0.4379048 0.3986248 -0.6634302 0.6332131 0.3821251 -0.6732808 0.6329877 0.434189 -0.4782944 0.7633574 0.8651404 -0.4889375 0.1116791 0.753699 -0.6528748 0.0754491 0.8884337 -0.3415747 0.3066146 0.8725278 -0.3901527 0.2940682 0.8550977 -0.1030052 0.5081318 0.7775999 -0.1697072 0.6054238 0.796858 -0.1457191 0.5863305 0.6876248 -0.2196155 0.6920558 0.7024356 -0.1768068 0.6894373 0.5730182 -0.2250399 0.7880401 0.5893618 -0.2175112 0.7780371 0.4375279 -0.258401 0.8612772 0.4569545 -0.2386251 0.8568843 0.07864397 -0.9486233 0.3064785 -0.3364399 -0.5457083 0.7674703 -0.2913323 -0.5785174 0.7618682 -0.09549552 -0.6609457 0.7443329 0.1514849 -0.6791502 0.7181974 0.1530157 -0.6777991 0.7191485 0.1050868 -0.844803 0.5246568 0.1824302 -0.2386251 0.9538226 0.1824536 -0.2385957 0.9538254 0.164838 -0.4799412 0.8616756 -0.1483636 -0.6790385 0.7189541 -0.1507158 -0.6950682 0.7029687 -0.2038087 -0.2341635 0.9505943 -0.2038192 -0.2341456 0.9505965 -0.4341774 -0.4783117 0.7633532 -0.332507 -0.8352727 0.4379027 -0.2030781 -0.9437931 0.2607948 -0.9984523 0.002720415 0.05555099 -0.9852914 -0.07666188 0.1527218 -0.9719645 -0.01413428 0.2347024 -0.9410755 -0.08613991 0.3270429 -0.9280781 -0.08133834 0.363394 -0.920766 -0.09326058 0.378804 -0.8595273 -0.121885 0.4963436 -0.9965255 -0.08291375 -0.007888615 -0.9803194 -0.1702746 0.09990257 -0.9459779 -0.3239808 -0.01274269 -0.9037134 -0.4159396 0.1014711 -0.9020931 -0.4299925 0.03653359 -0.8265221 -0.5350942 0.1747437 -0.7837833 -0.6200481 0.03498989 -0.672663 -0.7203953 0.1689828 -0.7167843 -0.6912306 0.09176301 -0.5657122 -0.7884991 0.2413275 -0.5681505 -0.8176442 0.09307473 -0.3658609 -0.901408 0.2315374 -0.4633343 -0.872818 0.1533307 -0.2657905 -0.9251307 0.2710879 -0.1065855 -0.9911054 -0.07968527 -0.8600909 -0.09805166 0.5006293 -0.7992736 -0.1526999 0.5812438 -0.7759415 -0.1614671 0.6097895 -0.7106382 -0.2055852 0.6728507 -0.6826375 -0.1850555 0.7069374 -0.5896372 -0.2195554 0.7772538 -0.5729842 -0.2224925 0.7887878 -0.45784 -0.2535963 0.8520984 -0.43667 -0.2393615 0.8671941 -0.9999986 -0.001712322 2.78699e-7 -0.9991863 -0.02676391 0.03017497 -0.9990959 -0.03730231 0.02039849 -0.9819304 -0.131492 0.1360977 -0.980931 -0.1645352 0.1034541 -0.9404131 -0.258293 0.2211513 -0.9435255 -0.261524 0.2033834 -0.8766762 -0.3552054 0.3244508 -0.8803812 -0.3812566 0.2820857 -0.7875394 -0.4675208 0.4015049 -0.8044139 -0.4592685 0.3768166 -0.6830139 -0.5381366 0.4938634 -0.7025583 -0.5588049 0.4406233 -0.5385406 -0.6272335 0.5626299 -0.5831417 -0.6167439 0.5287464 -0.3849246 -0.6655405 0.6394443 -0.3963895 -0.6715729 0.6259915 0.9932801 0.1157355 0 0.9807798 0.1950884 -0.003401875 0.5555658 0.8314675 0.002905189 0.8182767 0.5748223 -0.001701593 0.8314647 0.5555703 -0.002836704 0.9064982 0.4222097 3.11768e-4 0.9560085 0.2933387 -4.29874e-4 0.1950902 0.9807853 0 0.1138229 0.9934636 -0.008624255 0.2438946 0.9698004 -0.001608908 0.6233442 0.7807899 -0.04253578 0.5682843 0.8228306 0.001701653 0.3348062 0.942287 -2.39748e-4 0.3190804 0.9477276 -4.61376e-4 0.76179 0.6437399 -0.07263064 0.7893264 0.6124377 -0.04340374 0.8730751 0.4800986 -0.08511894 0.9434693 0.3261574 -0.05905127 0.9467697 0.3143174 -0.06951248 0.948807 0.3060899 -0.07793891 0.9532145 0.2781646 -0.1183495 0.991124 0.1293687 -0.03061175 0.9762433 0.2162458 -0.01366651 0.8100049 0.2185168 -0.5441899 0.9319347 0.2349282 -0.2762363 0.6964321 0.7175872 0.007150113 0.7860759 0.6157724 -0.05393528 0.7894991 0.6110148 -0.05789709 0.8882893 0.4585592 -0.02580201 0.9375611 0.3459699 -0.03583461 0.8780599 -0.4764595 0.04469072 0.9899584 -0.05958557 0.1281877 0.9001895 -0.05891364 0.4314952 0.729967 -0.4467352 0.5172774 0.6732063 -0.5957449 0.4380428 0.5077162 -0.1820898 0.8420616 0.4662717 -0.3561208 0.8097956 0.9896408 -0.05380249 0.133104 0.9057501 -0.1933383 0.3771435 0.9077641 -0.1722562 0.3824815 0.7398316 -0.3029208 0.6007398 0.7429888 -0.2798617 0.6079844 0.5129907 -0.3842538 0.7675869 0.5171977 -0.3606883 0.7761511 0.6188355 -0.1824815 0.7640309 0.9832772 -0.1081613 0.1465166 0.1452311 -0.9352389 0.3228562 0.03303223 -0.9415452 0.3352634 -0.293294 -0.9017084 0.3176487 -0.2104911 -0.9259968 0.3134062 -0.3894464 -0.8684987 0.3066622 0.5559783 -0.7861015 0.2700607 0.4708025 -0.8314825 0.2949271 0.2664251 -0.9083971 0.3222303 0.963778 -0.2485018 0.09684532 0.8103581 -0.5565322 0.1832805 0.8603166 -0.4804351 0.1704043 0.670464 -0.6992259 0.2481152 0.5924569 -0.7610044 0.2643244 0.99497 -0.08658933 0.05036979 0.9781616 -0.1536495 0.1399703 0.9892531 -0.06225705 0.1322969 0.9000214 -0.095802 0.4251863 0.9270523 -0.08461385 0.3652597 0.9864209 -0.03696793 0.1600224 0.979751 -0.04174888 0.195819 0.9990786 -0.009654402 0.04181843 0.8605691 -0.1180213 0.4954714 0.7847908 -0.1220686 0.6076207 0.8688725 -0.1062847 0.4834917 0.002251505 -0.2130306 0.977043 0.2146084 -0.2314411 0.9488827 0.5568937 -0.1965372 0.8069961 0.3805895 -0.1839438 0.9062651 0.4642896 -0.1885055 0.8653906 0.1456067 -0.2367658 0.9605939 -0.2938775 -0.2288522 0.9280425 -0.2226901 -0.2199503 0.9497532 -0.6627727 -0.1974406 0.7223224 -0.5625534 -0.1671018 0.8096979 -0.6100137 -0.7460992 0.2668697 -0.5742283 -0.7693148 0.2800302 -0.6737141 -0.6237909 0.3962252 0.9922791 -0.05472409 0.1112998 0.8594238 -0.2256 0.4587979 0.8594261 -0.2255967 0.4587953 0.5548641 -0.367095 0.7465703 0.5547485 -0.3671396 0.7466342 0.1448571 -0.4366032 0.8879156 0.1447597 -0.4366153 0.8879256 -0.292257 -0.4219973 0.8581984 -0.2923235 -0.4219769 0.8581855 -0.8038477 -0.2624806 0.5337913 -0.4281908 -0.3138419 0.8474408 0.9942472 -0.07109951 0.08010989 0.8594331 -0.3393806 0.3823555 0.8594077 -0.3394089 0.3823874 0.5548713 -0.5522606 0.6221947 0.5548443 -0.5522818 0.6221998 0.1447835 -0.6568298 0.7400084 0.1447598 -0.6568378 0.740006 -0.292312 -0.6348378 0.7152166 -0.2922584 -0.6348446 0.7152324 -0.7896866 -0.4072628 0.4588379 -0.413411 -0.4924433 0.7658923 0.9997922 -0.01927822 0.006628572 0.9902551 -0.1322691 0.04358559 0.9831339 -0.1533843 0.09960556 0.8594267 -0.4287837 0.2784429 0.859425 -0.4287847 0.2784467 0.55485 -0.6977351 0.4531085 0.5548211 -0.6977558 0.4531119 0.1447545 -0.8298481 0.5388864 0.1447954 -0.8298377 0.5388911 -0.2922902 -0.8020539 0.5208417 -0.2922919 -0.8020498 0.5208471 -0.7256844 -0.5770313 0.3747227 -0.5151674 -0.6077339 0.6043693 0.01638329 -0.04227268 0.9989718 0.06636744 -0.7172743 0.693623 -0.2824074 -0.50999 0.8125001 -0.2839341 -0.6658894 0.6899078 -0.1888867 -0.7175349 0.670422 -0.3556688 -0.6673069 0.654371 0.4167371 -0.6465191 0.6390175 0.3573113 -0.6446036 0.6758809 0.04680627 -0.7226235 0.6896554 0.9149388 -0.2970649 0.2732028 0.8290422 -0.3919905 0.398789 0.7133454 -0.508059 0.4827158 0.7036933 -0.5122058 0.4924033 0.6045194 -0.5649787 0.5615651 -0.3961303 -0.04982656 0.9168414 -0.4020659 -0.05686098 0.9138434 -0.3990143 -0.2298245 0.8876758 0.3008834 -0.04879772 0.9524117 0.5738688 -0.04438078 0.8177439 0.6206126 -0.002093434 0.7841147 0.8241662 -0.08664786 0.5596806 0.86122 -0.02188253 0.5077611 0.9840412 -0.01397174 0.1773916 0.9754118 -0.04893803 0.2148879 0.6204172 -0.1639366 0.7669469 0.3195753 -0.1862334 0.9290795 0.2999438 -0.1985539 0.9330649 -0.03774189 -0.1966895 0.9797391 0.9972331 -0.04603141 0.05837202 0.9837336 -0.1163535 0.1368576 0.9908828 -0.04632157 0.1265133 0.8861973 -0.1303296 0.4445995 0.8568907 -0.1577428 0.4907704 0.6606473 -0.2146911 0.7193419 0.3245568 -0.3514137 0.8781636 0.3552136 -0.3488945 0.8672347 0.3196523 -0.3715685 0.8716418 -8.01245e-5 -0.3739383 0.9274537 -0.03762233 -0.3909991 0.9196218 0.9686111 -0.1561484 0.1934175 0.7822514 -0.4044709 0.4737996 0.8883313 -0.2649282 0.3750742 0.7132312 -0.3815715 0.5879665 0.6646609 -0.4257459 0.613976 0.4160172 -0.4970102 0.7615185 0.3546494 -0.5312272 0.7694293 0.06635284 -0.5465151 0.8348165 0 -0.5671355 0.8236245 -0.2174538 -0.5390948 0.8136895 -0.4026499 -0.3384094 0.8505012 -0.2606291 -0.1940132 0.9457438 -0.05832171 -0.2072089 0.9765568 -0.05866426 -0.150699 0.9868375 0.3636585 0.02482289 0.9312016 -0.5555694 0.8314688 0.001624464 -0.3356441 0.941989 -2.3475e-4 -0.3233692 0.9462728 -4.01084e-4 -0.3092822 0.9509702 -5.97336e-4 -0.1621681 0.9867569 -0.003510892 -0.1950901 0.9807853 0 -0.639286 0.7683238 -0.03149408 -0.6588422 0.7487394 -0.0729146 -0.5666322 0.8239665 0.002741634 -0.8020478 0.5972585 -0.001356482 -0.9049256 0.4254749 -0.008990705 -0.8314631 0.5555651 0.004072904 -0.9807823 0.1950895 -0.002526462 -0.9888051 0.1492129 0 0 -1 -1.70946e-7 0 -1 2.3433e-5 0.3130586 0.9497181 0.005474984 0.3562808 0.9330523 -0.04977542 0.4910723 0.8706071 -0.02985292 0.5511624 0.8341398 -0.02075761 0.3682873 0.9295831 -0.01548504 0.3100692 0.9459473 -0.09508371 0.2502294 0.9638832 -0.09118396 0.2288923 0.96565 -0.1229984 0.1528137 0.9802553 -0.1254892 0.3172255 0.9483501 0 0.2984285 0.9543018 -0.01576399 0.2392559 0.9709551 -0.001734018 0.2026116 0.9787534 -0.03147017 0.04441118 0.9978873 -0.0474196 0.9122221 0.4054284 0.05898141 0.7820222 0.6169214 0.0885961 0.9224092 0.2662788 0.2797447 0.9324893 0.2228925 0.2842227 0.9296078 -0.09288257 0.356654 0.9321332 -0.06556075 0.3561314 0.8583169 -0.3218716 0.3996133 0.8460469 -0.3547016 0.3979842 0.6588669 -0.6236522 0.420657 0.6768111 -0.5973414 0.4302441 0.5735195 -0.7428901 0.3452389 0.7034811 -0.6248495 0.3386406 0.7035732 -0.6247327 0.3386647 0.8727804 -0.3821154 0.3037143 0.8728469 -0.3819521 0.3037289 0.9656519 -0.09913325 0.2401854 0.9656585 -0.09907555 0.2401828 0.9699106 0.1864798 0.1565204 0.969913 0.1864709 0.1565167 0.9236772 0.3721036 0.09142976 0.7685821 0.6362075 0.06724345 0.3560031 -0.8719849 0.3360121 0.3806757 -0.8571308 0.3470059 0.3744877 -0.8507114 0.3688485 0.3270719 -0.8834162 0.3355588 0.4956075 0.8677864 -0.03633224 -0.5677232 0.8218483 -0.04749643 -0.586165 0.791908 0.1711506 0.5861645 0.7919085 0.1711497 0.5637437 0.8249922 -0.03976428 -0.5441378 0.8337056 -0.09406983 -0.6809116 0.7323293 0.007296621 -0.5512677 0.8294167 0.09039884 -0.5712094 0.8184767 0.06177264 -0.4207293 0.9053466 0.0577442 -0.5537317 0.8120453 0.1842923 -0.4757584 0.8485649 0.2314984 -0.5090479 0.7733958 0.3777952 -0.3444751 0.8775319 0.3335786 -0.3629057 0.7589986 0.5405746 -0.2110885 0.8916242 0.4005597 -0.1842054 0.7664566 0.615315 -0.074907 0.8947486 0.440243 0 0.7607574 0.6490364 0.06556534 0.8956215 0.4399584 0.1859354 0.7613781 0.621073 0.200397 0.8943223 0.400036 0.3667541 0.7522063 0.5474278 0.3360176 0.8787056 0.3390705 0.5101599 0.7719926 0.3791626 0.4723601 0.8475341 0.2419958 0.5567529 0.8102479 0.183097 0.3900029 0.9187419 0.06173413 0.5721491 0.8173803 0.06734341 0.5614163 0.8232193 0.08439117 0.6809081 0.7323326 0.007296562 0.5440168 0.8337855 -0.09406155 0.3563173 -0.8725557 0.3341925 0.7911274 -0.33893 0.5091602 0.4555173 -0.7206311 0.5226804 0.9194969 0.392738 0.01680755 0.982186 0.1658672 0.08831179 0.965429 0.2605447 -0.00795263 0.9615122 0.274163 0.0181424 0.9888699 0.0918343 0.1170594 0.9870908 0.1488935 0.05901134 0.9893003 -0.03844881 0.1407364 0.9958282 0.09105449 0.005941212 0.9869822 -0.03647387 0.1566388 0.9878336 -0.02899938 0.1527878 0.9153164 -0.1768759 0.3618159 0.9057117 -0.1978847 0.3748707 0.7845984 -0.3014549 0.5417844 0.7383413 -0.3565573 0.5724676 0.5121976 -0.4391229 0.7381225 0.5221058 -0.4277146 0.7378793 0.5373715 -0.5085828 0.6727374 0.5056794 -0.6018857 0.6180793 0.4886795 -0.5828993 0.6491692 0.9521094 0.3057462 0.002636551 0.9543431 0.2842275 0.09189212 0.9850354 0.1040275 0.1374181 0.9662978 -0.1000564 0.2371867 0.9360086 -0.2452678 0.2524513 0.8443163 -0.4160732 0.3376584 0.8754501 -0.3863444 0.2903878 0.6953166 -0.61917 0.3649156 0.6988671 -0.61708 0.3616588 0.5680515 -0.7336208 0.3729852 0.4091117 -0.8057672 0.4282135 0.4065176 -0.800101 0.4411144 0.6770601 -0.5788168 0.4544898 0.7340388 -0.5408304 0.4107183 0.8331261 -0.3923677 0.3898059 0.8752183 -0.345316 0.3387474 0.954856 -0.1030247 0.2786321 0.4365731 -0.6690573 0.6014702 0.5107552 -0.6725337 0.5355628 0.7140941 -0.4839187 0.5058581 0.7184698 -0.4813749 0.502075 0.8565247 -0.2935442 0.4244965 0.9187612 -0.2017321 0.3393849 0.9534938 -0.09942543 0.2845423 0.9820549 -7.74376e-4 0.1885939 0.9862254 0.1189551 0.1149319 0.9870871 0.1479752 0.06133919 0.9671106 0.2538761 -0.0156272 0.5975686 -0.3944879 0.6980624 0.04703879 -0.7619851 0.6458841 0.687199 -0.3678839 0.6264337 0.6663387 0.01089918 0.7455697 -0.4826734 -0.6031389 0.6350197 -0.3549019 -0.7264697 0.5884611 -0.2509124 -0.8202127 0.5140956 -0.209213 -0.8281377 0.5200172 -0.2752922 -0.8840258 0.3777732 -0.2391951 -0.9010227 0.3618618 -0.2273891 -0.8896132 0.3960844 -0.2185408 -0.8926777 0.3941656 -0.2008532 -0.8796133 0.4312059 -0.2271419 -0.8751751 0.4271711 -0.1778882 -0.8613323 0.4758809 -0.2093266 -0.8582828 0.4685437 -0.5640488 -0.1389828 0.8139612 -0.09069085 -0.3604741 0.9283499 -0.2170867 -0.1151539 0.9693364 -0.346452 -0.3312592 0.8776323 -0.5833108 0.08767706 0.8075032 0.2100796 -0.2703328 0.9395674 0.208374 -0.259759 0.942924 -0.00256133 -0.2526338 0.9675586 0.8595418 -0.2278299 0.4574731 0.9972602 -0.04784458 0.05641919 0.9682614 -0.1158857 0.2214511 0.9654383 -0.1265577 0.2278425 0.8597707 -0.2930262 0.4182466 0.9065671 -0.2200191 0.3601773 0.8734238 -0.2643072 0.4089901 0.8246903 -0.3521807 0.4425547 0.700601 -0.4757108 0.5318436 0.6514824 -0.5039188 0.5671302 0.6033374 -0.5495337 0.5779247 -0.1889842 -0.7230272 0.6644673 0.8411896 -0.1987258 0.5029 0.735489 -0.2185494 0.6413206 0.5979717 -0.3937762 0.6981191 0.502294 -0.3070938 0.808328 0.4265547 -0.3257094 0.8437799 0.4233521 -0.3170079 0.8486925 0.3534678 -0.2803076 0.8924619 -0.3954633 -0.7387787 0.5457243 -0.3811956 -0.7482877 0.5429139 -0.2827296 -0.7516501 0.5958909 -0.2979888 -0.7406184 0.6022351 -0.1696624 -0.7606317 0.6266212 -0.1922844 -0.7329515 0.6525403 -0.07686918 -0.7700489 0.6333371 -0.08821332 -0.7405902 0.6661416 -0.02277982 -0.7753602 0.6311085 -0.01983332 -0.7559242 0.6543588 -7.8216e-5 -0.7740452 0.6331304 -1.92075e-4 -0.7742047 0.6329354 0.02465969 -0.8226476 0.5680166 -0.2299278 -0.7769396 0.5860871 -0.3831057 -0.7553277 0.5317049 0.3592132 -0.6947371 0.6231423 0.3505876 -0.7022421 0.6196325 0.3149369 -0.6284494 0.7112427 0.3153816 -0.6277414 0.7116708 0.2329574 -0.5532495 0.7997787 0.2289852 -0.5764752 0.7843738 0.08156853 -0.4990621 0.8627188 0.08878892 -0.5342922 0.8406239 -0.1294919 -0.4646681 0.8759655 -0.1131899 -0.4983498 0.8595554 -0.3453122 -0.4625939 0.8165577 -0.3335634 -0.476659 0.813346 -0.5234631 -0.4695898 0.7109655 -0.5799268 -0.396643 0.7115893 -0.8269422 -0.003817856 0.562274 -0.2069434 -0.9313904 0.2994769 -0.2155864 -0.9207544 0.3251677 -0.3491221 -0.8044511 0.4805958 -0.1512781 -0.815705 0.5583371 -0.2948567 -0.8663257 0.4031617 -0.3692063 -0.7586262 0.5368176 -0.3851961 -0.7154667 0.5828649 -0.6010875 -0.1614721 0.7827009 -0.5835123 -0.04250717 0.8109912 -0.5957392 -0.1937634 0.7794554 -0.5263324 -0.4992122 0.6883033 -0.5292336 -0.4356507 0.7280937 -0.4731735 -0.6206576 0.6252127 -0.8227307 -0.10339 0.5589497 -0.8202039 -0.1612146 0.5488857 -0.7836965 -0.304555 0.541356 -0.7171917 -0.4988404 0.4866151 -0.7135202 -0.5046232 0.4860499 -0.2307128 -0.9497313 0.211618 -0.232005 -0.9443725 0.2330973 -0.6340209 -0.6710512 0.3843277 -0.4818813 -0.7959774 0.3663474 -0.4422819 -0.7951288 0.4149182 -0.2581723 -0.938709 0.2284133 -0.4245206 -0.7651029 0.4841488 -0.4235679 -0.8099101 0.4057536 -0.6260307 -0.498446 0.5996977 -0.6260336 -0.4984372 0.5997018 -0.7126947 -0.1611294 0.6827179 -0.712697 -0.1611251 0.6827164 -0.9832734 -0.1326679 0.1247906 0.4054934 -0.8289431 0.3852639 -0.8599429 -0.4836689 0.1629807 -0.8046026 -0.559641 0.1985364 -0.5563679 -0.7831343 0.2777689 -0.4501938 -0.8475326 0.2810947 -0.6356491 -0.7275356 0.2581515 0.7292931 -0.6568849 0.1913999 0.59445 -0.7736591 0.2192735 0.7282071 -0.6445175 0.2330485 0.396831 -0.8654869 0.3057083 0.2931479 -0.9037709 0.3118698 0.1272462 -0.932464 0.3381114 -0.1452351 -0.9350273 0.323467 -0.1625571 -0.9319139 0.3242094 -0.3027662 -0.8982259 0.3186267 0.780259 -0.2918717 0.553179 0.7032014 -0.1888471 0.6854522 0.447007 -0.2297168 0.8645317 0.5016536 -0.217024 0.8374034 0.2936473 -0.2190726 0.9304722 -0.1454186 -0.2257881 0.9632617 -0.02063351 -0.2392928 0.9707282 0.1970025 -0.2347205 0.9518909 -0.8774985 -0.1038557 0.4681991 -0.7900349 -0.1218569 0.6008294 -0.8605391 -0.1180042 0.4955276 -0.6143907 -0.183298 0.7674151 -0.5565719 -0.1859815 0.8097153 -0.4250105 -0.2144683 0.8794143 -0.233925 -0.2301855 0.944613 -0.9949716 -0.03973436 0.09193861 -0.9781628 -0.1207547 0.1691625 -0.9667937 -0.2372113 0.09508329 -0.9864296 -0.1544098 0.0558061 -0.9892502 -0.1239957 0.07751888 -0.9922775 -0.1040282 0.06755554 -0.8594238 -0.4287852 0.2784493 -0.8594318 -0.428775 0.2784405 -0.5548095 -0.6977618 0.453117 -0.554843 -0.6977421 0.4531064 -0.1447818 -0.8298416 0.5388889 -0.144758 -0.8298437 0.5388919 0.2923079 -0.8020479 0.5208409 0.29232 -0.8020433 0.5208414 0.8040061 -0.4986954 0.3238475 0.7702077 -0.5411497 0.337546 -0.9942476 -0.07109999 0.08010298 -0.8594249 -0.3393896 0.3823658 -0.8594227 -0.3393938 0.382367 -0.5548223 -0.5522844 0.6222172 -0.5548427 -0.5522757 0.6222068 -0.1447682 -0.656836 0.7400059 -0.1448277 -0.6568269 0.7400024 0.2923386 -0.6348277 0.7152146 0.2922549 -0.6348447 0.7152338 0.749481 -0.4394708 0.4951199 0.5084182 -0.6770235 0.5321187 -0.9751307 -0.04656893 0.2166829 -0.9885768 -0.0428707 0.1444926 -0.9831421 -0.08068162 0.1640791 -0.8594152 -0.2256054 0.4588114 -0.8594229 -0.2256013 0.4587987 -0.554828 -0.3671138 0.7465879 -0.5548429 -0.3671081 0.7465795 -0.1447791 -0.4366113 0.8879243 -0.1448273 -0.4366092 0.8879175 0.2923338 -0.4219865 0.8581774 0.2923184 -0.4219871 0.8581824 0.6129169 -0.3486607 0.7090618 0.6319571 -0.5005986 0.5916345 -0.51728 -0.339904 0.7854214 -0.4806817 -0.1891648 0.8562487 -0.9865351 0.06839799 0.1485608 -0.8838018 -0.3371587 0.3243741 -0.8586996 -0.4614394 0.2229545 -0.9076892 -0.1913347 0.3734856 -0.9902231 -0.05182516 0.1295082 -0.9896942 -0.0603972 0.1298371 -0.655074 -0.5903372 0.471572 -0.7912012 -0.2709405 0.5482629 -0.9056316 -0.1745745 0.3864651 -0.6517601 -0.01581281 0.7582604 -0.7233822 -0.4820879 0.4942769 -0.7430516 -0.2796779 0.6079924 -0.5170721 -0.3826506 0.7656468 -0.5130922 -0.3621476 0.7781939 -0.8806916 0.4727743 -0.02944487 -0.5688109 0.8224276 0.008194804 -0.9886288 0.1503571 -0.002429246 -0.7894609 0.6099324 -0.06880557 -0.7849075 0.619225 -0.0219205 -0.865624 0.4898005 -0.1038784 -0.7895062 0.6110428 -0.05750364 -0.7976898 0.5992788 -0.06749844 -0.7424784 0.6698368 -0.006682336 -0.9744302 0.2186519 -0.05174279 -0.810336 0.2184065 -0.5437409 -0.9142664 0.2333471 -0.3311588 -0.9543248 0.2670156 -0.1340407 -0.9488653 0.3057615 -0.07851451 -0.9364344 0.3495208 -0.03042912 0.324486 -0.6898039 0.647209 0.1915686 -0.5625564 0.8042586 0.4482256 -0.402504 0.7981756 0.3505535 -0.2708272 0.8965293 0.1022925 -0.2300497 0.9677879 0.3947572 -0.1143372 0.9116435 -0.7043938 -0.5000472 0.5037682 -0.6555705 -0.5573495 0.5094988 -0.8013024 -0.4308597 0.4150596 -0.8783396 -0.3525027 0.3228958 -0.8589066 -0.3850307 0.3376845 -0.910874 -0.2983608 0.2851132 -0.1904978 -0.6985876 0.6897 -0.2356302 -0.7084609 0.6652531 0.1845825 -0.4606428 0.8681806 0.1843932 -0.2802907 0.9420384 0.2134104 -0.2888135 0.9332968 0.2133225 -0.09497636 0.9723544 0.1593846 -0.07423418 0.9844216 -0.3551687 -0.1814416 0.9170246 -0.4611541 -0.6492053 0.6048715 -0.4639774 -0.6488566 0.6030838 -0.4596812 -0.4714422 0.752619 -0.7009702 -0.3961284 0.5930625 -0.6220514 -0.408817 0.667773 -0.8772656 -0.2696573 0.3971021 -0.8214866 -0.2952217 0.4878567 -0.9452083 -0.1797339 0.2725383 -0.9465607 -0.08937299 0.3098956 -0.9845089 -0.1275409 0.1203143 -0.9842414 -0.1281616 0.1218343 -0.9835599 -0.08863562 0.1573337 -0.996918 -0.04403752 0.06492525 -0.9903782 -0.03179186 0.1346864 0.3245403 -0.569456 0.7552441 0.1396147 -0.6093717 0.780496 0.1396355 -0.4508578 0.8816061 -0.08717745 -0.4676887 0.8795838 -0.08735769 -0.2962633 0.9511029 0.1131829 -0.2003352 0.9731678 -0.07737708 -0.1017745 0.9917938 -0.9829553 -0.02228486 0.182489 -0.8155956 -0.124777 0.5650084 -0.8209813 -0.1257702 0.5569304 -0.5644935 -0.1499494 0.8117034 -0.6205978 -0.1588637 0.7678677 -0.3644191 -0.1788193 0.9139051 -0.365021 -0.5069872 0.7808482 0.06134676 -0.5149298 0.8550345 -0.1903671 -0.608904 0.7700626 0.08195608 -0.5993229 0.7963011 0.08203899 -0.7160224 0.69324 0.1516396 -0.6878961 0.7097918 0.09245747 -0.6946071 0.7134231 0.3142454 -0.6543677 0.6877884 -0.427043 -0.7286633 0.535429 -0.6023332 -0.7567192 0.2541079 -0.7878543 -0.576384 0.2169498 -0.6627296 -0.7036935 0.2561348 -0.6732212 -0.6963246 0.2488081 -0.7153704 -0.5898194 0.3746443 -0.5549099 -0.5898767 0.586618 -0.6275752 -0.7081101 0.3236194 -0.601709 -0.6366456 0.4823161 -0.677532 -0.5563347 0.4810843 -0.6607921 -0.4966903 0.5627191 -0.7527361 -0.3560443 0.5537337 -0.6842525 -0.1473936 0.7141945 -0.5760421 -0.08674031 0.8128049 -0.5760139 -0.08673429 0.8128255 -0.5763684 -0.08670639 0.8125772 -0.4735017 -0.3449656 0.810429 -0.6046579 -0.1754415 0.776923 -0.5271046 -0.2104837 0.8233211 -0.501281 -0.2736448 0.8208752 -0.5760324 -0.08675169 0.8128105 -0.672229 -0.1755425 0.7192308 -0.6548298 -0.2624744 0.708735 -0.6553826 -0.2617079 0.7085074 -0.6427616 -0.326622 0.6929471 -0.6135316 -0.3786371 0.692974 -0.5960346 -0.4480196 0.6663492 -0.4595754 -0.5472444 0.6995099 -0.4967926 -0.5223601 0.6930636 -0.4452034 -0.3315163 0.8317998 0.07987952 -0.6001227 0.7959097 0.1228914 -0.6488642 0.7509148 0.01017117 -0.5172151 0.855795 0.1147954 -0.4454321 0.8879259 0.07820844 -0.4610771 0.8839069 0.009172856 -0.5165435 0.8562119 -0.01855754 -0.5107029 0.859557 -0.07017695 -0.5272837 0.8467863 -0.1514574 -0.5032654 0.8507553 -0.2144104 -0.511476 0.8321182 0.4127639 -0.6145677 0.6722593 0.489312 -0.6283643 0.6047579 0.5669142 -0.5094512 0.6473546 0.5090141 -0.2555045 0.8219624 0.5361061 -0.1867123 0.823243 0.5679727 -0.2267872 0.7911856 0.4848347 -0.3338918 0.8083635 0.6279364 -0.1336584 0.7667018 0.5903335 -0.1150836 0.7989131 0.5396466 -0.1917005 0.8197759 0.6769543 -0.1954939 0.7095879 0.6332238 -0.4112607 0.6556618 0.5920705 -0.4450163 0.6718728 0.6119197 -0.3813651 0.6929033 0.6456662 -0.3211513 0.6928038 0.6468014 -0.2582681 0.7175972 0.6831139 -0.1876749 0.7057858 0.6335294 -0.1384862 0.7612241 0.5973942 -0.7699185 0.2243788 0.7118337 -0.6369186 0.2960194 0.6985933 -0.607096 0.3786844 0.6607998 -0.5754369 0.481888 0.6462459 -0.5999876 0.4715732 0.6649971 -0.4998326 0.5549292 0.7138282 -0.4523579 0.534623 0.7232118 -0.3222839 0.6108174 0.6225408 -0.709016 0.3312693 0.6615945 -0.7077646 0.2477136 0.7652606 -0.6010462 0.2304773 0.6456272 -0.7415778 0.1822857 0.6044189 -0.6295709 0.4881786 0.6028794 -0.6355223 0.4823359 0.497974 -0.6516962 0.5721136 0.5194752 -0.6671189 0.5339456 0.3064291 -0.7343235 0.6056982 0.3222856 -0.6502376 0.6879848 0.2631645 -0.6364661 0.725021 0.2469524 -0.5820486 0.7747477 0.1557804 -0.5718325 0.805444 -0.3054257 -0.6543934 0.6917257 -0.3460051 -0.6375174 0.6883692 -0.2656857 -0.6337753 0.7264572 -0.1839613 -0.674839 0.7146681 -0.08701044 -0.6538052 0.7516435 -0.05357122 -0.6735309 0.7372152 0.1154297 -0.6699956 0.7333362 -0.2803626 -0.4676063 0.8382966 -0.3728414 -0.4788281 0.7948037 -0.444628 -0.5710214 0.6901018 -0.4446278 -0.5710219 0.6901016 -0.5036656 -0.6468337 0.5726493 -0.5903108 -0.6435196 0.4872532 -0.3552235 0.9334562 -0.04975825 -0.5068652 0.8615897 -0.02740842 -0.5361371 0.8441309 -2.02277e-4 -0.2274955 0.9735643 0.02045649 -0.322987 0.9324494 -0.161918 -0.1158237 0.9932353 0.008278906 -0.1471333 0.9805416 -0.1299614 -0.2266572 0.9663728 -0.1214505 -0.2220426 0.9656196 -0.1351886 -0.2818056 0.9581663 -0.05003088 -0.2968125 0.9473339 -0.1202538 -0.3671564 0.9300821 -0.011985 -0.3690193 0.9293775 -0.009076416 0.1013866 0.9809843 -0.1655012 0.1000065 0.9800484 -0.1717671 0.05480092 0.9818911 -0.1813476 0.05111473 0.9805732 -0.1893768 0 0.9812214 -0.1928848 0 0.9812212 -0.1928858 -0.05709409 0.9803293 -0.1889306 -0.04925638 0.9819718 -0.182497 -0.1046138 0.9797421 -0.1707671 -0.09791082 0.9808836 -0.1681692 0.03283029 0.9978691 -0.05638754 0.03283041 0.997869 -0.05638915 0.01700294 0.9978691 -0.06299465 0.01700246 0.997869 -0.06299591 0 0.9978691 -0.06524884 0 0.997869 -0.06524974 -0.01700234 0.9978692 -0.06299346 -0.01700294 0.997869 -0.06299597 -0.03283077 0.9978691 -0.05638736 -0.03282999 0.9978691 -0.05638837 0.3005337 0.9128918 -0.2762397 0.2789283 0.9539617 -0.1102545 0.3450113 0.9361761 -0.06739097 0.3982705 0.9146154 -0.06970959 0.1031123 0.9911711 -0.08335328 0.1050237 0.9900821 -0.09331393 0.1271907 0.9902571 -0.05668723 0.2083936 0.9744166 -0.0841701 0.136767 0.9890624 -0.05523198 0.1296096 0.9912418 -0.02532011 0.1383057 0.9899101 -0.03081732 0.1367014 0.990396 -0.02070355 -0.0928446 0.9935805 0.06463426 -0.09118163 0.9900201 0.1074534 -0.09665882 0.9782708 0.1834212 -0.05880844 0.9842969 0.1664367 -0.0299685 0.9839091 0.1761384 -0.02996933 0.9839099 0.1761339 0.02633434 0.9839095 0.1767163 0.02633655 0.9839094 0.1767165 0.1001733 0.9935587 0.05297672 0.08978819 0.9885094 0.1216031 0.08996796 0.9796176 0.1795973 0.2522023 0.9279803 0.2743111 0.05821716 0.9842858 0.1667106 0.0747708 0.9903704 0.1165152 0.09852647 0.9901555 0.09942162 0.09852588 0.9901555 0.09942185 0.1245743 0.9901555 0.06382334 0.1245743 0.9901556 0.06382107 0.1382509 0.9901555 0.02188342 0.1382512 0.9901554 0.02188366 0.4039972 0.914281 -0.02961075 0.1382366 0.9903475 -0.01013237 0.1382371 0.9903473 -0.01013499 0.4039846 0.9142863 -0.02961426 0.4034442 0.9127731 0.06386101 0.4034373 0.9127761 0.06386041 0.3635361 0.912773 0.1862443 0.3635303 0.9127754 0.1862438 0.2875187 0.9127742 0.2901316 0.2875211 0.9127736 0.2901309 0.1829466 0.9127755 0.3652008 0.1829469 0.912775 0.3652018 0.06020885 0.9127762 0.403998 0.06020462 0.9127733 0.4040054 -0.06851506 0.9127749 0.4026756 -0.06851124 0.9127749 0.4026767 -0.1904292 0.9127755 0.3613554 -0.1904229 0.9127757 0.3613581 -0.2934308 0.9127748 0.2841491 -0.2934281 0.9127757 0.2841488 -0.3672884 0.9127751 0.17872 -0.3672903 0.9127745 0.1787196 -0.4046747 0.9127725 0.05553996 -0.4046667 0.9127761 0.05554062 -0.1380274 0.9903611 -0.0115481 -0.4034364 0.9143851 -0.0337516 -0.4034408 0.9143833 -0.03374797 -0.1380355 0.99036 -0.0115472 -0.1386718 0.9901555 0.01903289 -0.1386713 0.9901556 0.01903158 -0.125862 0.9901556 0.06124371 -0.1258639 0.9901553 0.06124371 -0.100553 0.9901556 0.09737133 -0.1005538 0.9901555 0.09737157 -0.08095288 0.9903934 0.1121066 -0.003241896 0.9999826 0.00494343 0.8426406 0.3074295 0.4420905 0.8426398 0.3074344 0.4420886 0.8473785 -0.04796999 0.5288181 0.8211503 -0.1623877 0.5471221 0.7874946 -0.2827405 0.5476406 0.6135079 -0.5979903 0.5157672 0.6134886 -0.5980072 0.5157704 0.2736046 -0.8621273 0.4264707 0.249292 -0.843719 0.4753861 0.234277 -0.8582425 0.4566555 0.4116184 -0.5628844 0.7167506 0.4199833 -0.5331732 0.734398 0.5117318 -0.1156041 0.8513322 0.5128425 -0.1092159 0.8515071 0.5188367 0.1196833 0.846454 0.494556 0.3678273 0.7874754 0.5026886 0.3354775 0.7967177 0.6978393 0.6635677 0.2696264 0.6978396 0.6635674 0.2696262 0.5611668 0.6989676 0.443324 0.3967783 0.6934309 0.6014323 0.3824035 0.7178683 0.5817497 0.5611453 0.6989896 0.4433166 0.6901603 0.347465 0.634781 0.6901558 0.34746 0.6347886 0.6875758 -0.1264121 0.7150242 0.6875733 -0.1263985 0.715029 0.5246657 -0.5735982 0.6290556 0.5246679 -0.5736139 0.6290395 0.273591 -0.8621217 0.4264907 0.3021876 -0.8699179 0.3897763 0.3021817 -0.8699128 0.3897923 0 0.6934962 0.7204604 0.1549944 -0.8414003 0.5177088 -0.03904706 -0.8433449 0.5359522 0.2066321 0.6935032 0.6901859 0.2066245 0.6935021 0.6901892 0.270264 0.3347063 0.9027342 0.2702602 0.3218511 0.9073982 0.2847583 0.1192668 0.951151 0.2849001 -0.1150236 0.9516311 0.2848899 -0.1150245 0.9516339 0.2431272 -0.5304432 0.8121079 0.2431234 -0.5304448 0.812108 0.1549947 -0.8413845 0.5177344 -0.1998418 0.7172831 0.6675091 -0.2038026 0.6937133 0.6908158 0 0.6934987 0.7204579 0 0.3217888 0.9468115 0 0.321786 0.9468125 0 -0.1150241 0.9933628 0 -0.1150234 0.9933628 0 -0.5304423 0.8477211 0 -0.5304434 0.8477204 0 -0.6743113 0.7384472 0.03904706 -0.8433449 0.5359522 -0.1467757 -0.8591303 0.4902571 -0.1521017 -0.8415864 0.5182638 -0.1965326 -0.7282934 0.6564783 -0.2431318 -0.5304468 0.8121042 -0.2403323 -0.5397558 0.8067862 -0.2860613 -0.1150035 0.951285 -0.2860537 -0.1150626 0.9512802 -0.2704947 0.3218375 0.9073331 -0.2705067 0.3322778 0.9035583 -0.239385 0.5507136 0.7996309 -0.5616372 0.6981993 0.4439387 -0.3853499 0.7170798 0.5807772 -0.3853562 0.7170738 0.5807803 -0.4510999 0.5513066 0.7018334 -0.4976042 0.3642929 0.7871982 -0.5001231 0.3331784 0.799293 -0.5111512 -0.115633 0.851677 -0.5111424 -0.1156325 0.8516823 -0.4170951 -0.5425655 0.7291464 -0.4088984 -0.5708321 0.7120062 -0.3287196 -0.731167 0.5977778 -0.2699655 -0.8648412 0.4232828 -0.2977289 -0.8724019 0.3876499 -0.2977012 -0.8724132 0.387646 -0.6077166 -0.6053997 0.5139765 -0.6983867 0.6627723 0.2701647 -0.8432591 0.3040026 0.4432794 -0.843261 0.3040175 0.4432656 -0.8469982 -0.05049234 0.5291925 -0.8194793 -0.1687839 0.5476913 -0.7861067 -0.2864987 0.5476815 -0.6077238 -0.6053926 0.5139763 -0.2337519 -0.8613101 0.4511155 -0.2337615 -0.8613054 0.4511194 -0.2699733 -0.8648393 0.4232819 -0.520056 -0.5813401 0.625768 -0.5200669 -0.5813419 0.6257572 -0.6863861 -0.1328995 0.7149908 -0.6863903 -0.1329056 0.7149857 -0.69076 0.3440462 0.6359897 -0.6907549 0.3440726 0.635981 -0.5616542 0.6981717 0.4439606 -0.6984183 0.6627401 0.2701622 -0.374292 -0.8285082 0.4165091 -0.454289 -0.6569819 0.6016614 -0.7000737 -0.1610943 0.695662 -0.6772086 -0.2787047 0.6809642 -0.6306525 -0.406051 0.6613623 -0.5360055 -0.6138277 0.5795807 -0.5409114 -0.604988 0.5842983 -0.4339995 -0.7463448 0.5045927 -0.2061535 -0.9626936 0.1752766 -0.3889484 -0.7647968 0.5136196 -0.4949978 -0.5082711 0.7047252 -0.4460774 -0.6333581 0.6323548 -0.5339748 -0.1680724 0.8286269 -0.5364817 -0.1349225 0.8330567 -0.5048311 -0.2212994 0.8343694 -0.4422161 -0.739508 0.5075164 -0.6416515 -0.2327274 0.730836 -0.6302115 -0.2764273 0.7255492 -0.5199161 -0.6120347 0.5959033 -0.5246404 -0.6042656 0.5996795 -0.2809652 -0.8849335 0.3714181 -0.3782393 -0.8077703 0.452153 -0.3757091 -0.8219102 0.428143 -0.3857832 -0.8119956 0.4379894 -0.3999716 -0.8134477 0.4222864 -0.3225806 -0.887355 0.3294584 -0.3021415 -0.8894866 0.3428181 -0.283796 -0.9056792 0.3149684 -0.5551415 -0.3776761 0.741066 -0.6227157 -0.2861918 0.7282304 -0.5793747 -0.2888659 0.7621557 -0.3602334 -0.8296 0.4266096 -0.6028299 -0.1594885 0.781767 -0.04400247 -0.9957534 -0.08086508 -0.0439701 -0.9957548 -0.08086341 -0.4975602 -0.4631177 0.7334548 -0.5305523 -0.3416164 0.7757658 -0.5759487 -0.3359936 0.7452459 -0.5430139 -0.5024879 0.6727867 -0.5020391 -0.613053 0.6100187 -0.4878563 -0.6529386 0.5793682 -0.4200142 -0.7793086 0.4650444 -0.3836276 -0.7833954 0.4890006 -0.3269454 -0.862337 0.3866284 0.3121839 -0.8456891 0.4328407 0.3405075 -0.807066 0.482389 0.4245132 -0.7655086 0.4835134 0.2535911 -0.9004664 0.3533439 0.2036001 -0.9334087 0.2954574 0.2126442 -0.9233267 0.319766 0.2288931 -0.9559054 0.1839916 0.4935045 -0.7956134 0.3513583 0.5026768 -0.7800378 0.3726357 0.6880383 -0.5479038 0.4758201 0.7194249 -0.4987056 0.4834465 0.7655987 -0.363291 0.5309221 0.8203321 -0.1262083 0.5577874 0.8191282 -0.1612423 0.5504816 0.7474812 -0.1616649 0.6443107 0.6946269 0.05047911 0.717597 0.5344636 -0.4634086 0.7068248 0.5154523 -0.4987801 0.6967979 0.4649869 -0.6360255 0.61584 0.3901671 -0.7536096 0.5290014 0.2305672 -0.9502228 0.2095599 0.2564015 -0.9396252 0.2266341 0.4422966 -0.7951188 0.4149216 0.4235767 -0.8099049 0.4057548 0.6260345 -0.4984427 0.5996963 0.6260307 -0.4984451 0.5996983 0.7126975 -0.161132 0.6827144 0.6032011 -0.161498 0.7810679 0.6001313 -0.1708598 0.7814406 -0.6741978 0.09289932 0.7326849 -0.9752047 -0.04597765 0.2164765 0.152401 -0.7888833 0.5953462 -0.6550789 -0.5118418 0.5557786 -0.4609603 -0.6409113 0.6137983 -0.3388997 -0.6778689 0.6524116 -0.2361942 -0.7372862 0.6329467 0.006444871 -0.7604249 0.6493939 0.253257 -0.823567 0.5075417 0.2644177 -0.840619 0.4726978 -0.8512687 -0.3050705 0.4269353 -0.7966048 -0.3835824 0.4672103 -0.6526278 -0.5127564 0.5578153 -0.9025048 -0.2262765 0.3664481 -0.8730913 -0.2641968 0.4097703 -0.8481851 -0.2022595 0.4895642 -0.7640333 -0.2037973 0.6121438 -0.4937931 -0.3028663 0.8151322 -0.3942072 -0.3226219 0.8605324 -0.3928872 -0.3173543 0.8630909 -0.1709939 -0.2102539 0.962577 0.2023028 -0.3879587 0.8992005 -0.02624952 -0.1977652 0.9798979 -0.1857069 -0.4208563 0.887915 0.1353459 -0.2066919 0.9689995 0.4380589 -0.2538281 0.8623664 0.5041025 -0.004798769 0.8636305 0.7067162 -0.1569556 0.6898675 0.6427842 -0.2585079 0.7211118 0.6426304 -0.2175613 0.7346382 0.6185354 -0.4141545 0.66775 0.2405201 -0.9009171 0.3612458 0.2861109 -0.8852633 0.3666737 0.01365751 -0.7635943 0.645552 0.04686051 -0.7678048 0.6389678 0.0839582 -0.7501422 0.6559253 0.1210417 -0.7617119 0.6365091 0.1956843 -0.7405755 0.6428497 0.2180025 -0.75652 0.6165651 0.3258538 -0.7422171 0.5856049 0.5128924 -0.6038416 0.6101776 0.5495627 -0.4759718 0.6866089 0.4128687 -0.4697301 0.7803162 0.4091587 -0.4615006 0.7871509 0.1850479 -0.4904727 0.8515831 0.1636716 -0.4672231 0.8688579 -0.02654093 -0.5205975 0.8533896 -0.06081199 -0.4997894 0.8640096 -0.1973074 -0.5640676 0.8018091 -0.2268334 -0.5521094 0.8023228 -0.660814 -0.3087259 0.6841149 -0.5937548 -0.3878422 0.7050061 -0.5933408 -0.388089 0.7052189 -0.3130158 -0.6247348 0.7153514 -0.3124867 -0.6248557 0.7154771 7.31583e-5 -0.7740098 0.6331738 0.001626133 -0.7739381 0.6332592 0.205838 -0.8184525 0.5364386 0.2076814 -0.8627645 0.4609837 0.205526 -0.8628882 0.4617177 0.1950821 -0.8829006 0.4271176 0.2215798 -0.880614 0.4188334 0.2040351 -0.8979847 0.389863 0.2388141 -0.8898527 0.3887547 0.329068 -0.7483562 0.5759143 0.3910812 -0.7512552 0.5316684 0.4192334 -0.7383512 0.5282812 -0.5167684 -0.5581254 0.6491891 -0.5848191 -0.6364719 0.502882 -0.2415552 -0.9021549 0.3574461 -0.9567274 0.2884989 0.03796112 -0.9892909 -0.03843152 0.1408069 -0.1860617 -0.8931024 0.409572 -0.6900577 -0.3654771 0.6246975 -0.5504477 -0.4822314 0.6815133 -0.5367394 -0.3906976 0.7478411 -0.5127164 -0.4232143 0.7470018 -0.9889591 0.1386473 0.05231499 -0.9971192 0.07584482 9.42612e-4 -0.9897559 -0.03157705 0.1392335 -0.9891881 -0.03768366 0.1417281 -0.9223141 -0.1636409 0.3500837 -0.905668 -0.2026728 0.3724101 -0.5244287 -0.6207215 0.5828202 -0.7406741 -0.4208389 0.5237332 -0.6692339 -0.4459079 0.5943839 -0.8689616 -0.3763058 0.3214029 -0.8594217 -0.4005321 0.3177551 -0.6966972 -0.6135708 0.3716773 -0.7101134 -0.593373 0.3790088 -0.4691484 -0.7943102 0.3859679 -0.5240197 -0.7382763 0.4246781 -0.3334442 -0.8588017 0.3889404 -0.9305865 0.3634727 -0.04354739 -0.9738184 0.2268171 0.01522612 -0.9886366 0.1262469 0.08160597 -0.9889885 0.1235651 0.08144593 -0.9703502 -0.07667386 0.2292199 -0.9813423 0.03226721 0.1895424 -0.884243 -0.2610943 0.3872262 -0.9209004 -0.1529056 0.3585562 -0.8037726 -0.3539622 0.4781845 -0.7956335 -0.2808104 0.5367615 -0.7910408 -0.2870887 0.5402172 -0.9160014 0.3993142 0.03859919 -0.920552 0.3899511 0.02284967 -0.9800602 0.1848059 0.07299935 -0.9466038 0.3111672 0.08435755 -0.9872883 0.05588656 0.1487902 -0.9877225 0.03650939 0.1518929 -0.9745013 -0.1135216 0.1935465 -0.9663802 0.1919792 0.1710358 -0.934184 -0.2389905 0.2649221 -0.9629849 -0.05046325 0.2647899 -0.8495892 -0.3748066 0.3711039 -0.8855081 -0.2654788 0.3813089 -0.6965817 -0.5592496 0.4494596 -0.7521926 -0.4594794 0.4723188 -0.5094788 -0.7026663 0.4966805 -0.5801559 -0.6169928 0.5317321 -0.3092927 -0.7999895 0.5141545 -0.4593589 -0.6594516 0.5950739 -0.7765536 0.6297211 0.02039515 -0.7481524 0.6407196 0.1724717 -0.908655 0.4104959 0.07641553 -0.9667319 0.2078324 0.1491149 -0.9691873 0.1874465 0.1598116 -0.2473134 -0.9130046 0.3244358 -0.377246 -0.8536006 0.3592377 -0.4771838 -0.8088304 0.3436408 -0.7036255 -0.6247912 0.3384485 -0.7035096 -0.6249037 0.3384813 -0.8728966 -0.3820697 0.3034375 -0.8728289 -0.3821908 0.3034799 -0.9657287 -0.09915328 0.2398681 -0.9657129 -0.09922647 0.2399017 -0.9787896 0.06926906 0.1928027 -0.8386092 0.5246017 0.1467235 -0.9279774 0.2261378 0.2961752 -0.925884 0.2607702 0.2733821 -0.9338321 -0.06701034 0.3513792 -0.9274712 -0.09422963 0.3618262 -0.8444327 -0.3531591 0.4027555 -0.8590508 -0.3269311 0.3938882 -0.6805494 -0.6010023 0.4191046 -0.6496568 -0.6292221 0.4266446 -0.3793109 -0.8557509 0.3518716 -0.3130022 -0.8809961 0.3547896 0.4299927 -0.8333569 0.3473076 0.4640679 -0.8525575 0.240389 0.4506624 -0.8598753 0.2398291 0.5236458 -0.8390074 0.1478575 0.554777 -0.8201855 0.1397086 0.1887723 -0.9809236 0.04641163 0.1858994 -0.981805 0.03873467 0.3487612 -0.8685478 0.3521229 0.1343366 -0.9816098 0.1356317 0.1695061 -0.98161 0.08780485 0.2061018 -0.9700977 0.1281898 0.1681684 -0.983716 0.0634219 0.04584968 -0.9819628 0.183431 0.05932277 -0.9820395 0.1791068 0.08775687 -0.9809224 0.1734651 0.08734494 -0.9816496 0.169514 0.1343411 -0.981609 0.1356332 0.02072483 -0.972322 0.232724 0.02968221 -0.9816098 0.1885769 -0.01679825 -0.9819039 0.1886336 -0.03289079 -0.9773706 0.2089617 -0.05209714 -0.9838857 0.1710407 -0.09444886 -0.9778677 0.1866929 -0.09411072 -0.9821143 0.1630792 -0.1359058 -0.9811735 0.137216 -0.1424135 -0.9781005 0.1517819 -0.1690802 -0.9836106 0.06262731 -0.1888169 -0.9809145 0.04642051 -0.1859178 -0.9818058 0.03862661 -0.5243551 -0.8391672 0.1443958 -0.5468994 -0.8257958 0.1377036 -0.4600876 -0.8552886 0.2383291 -0.1881214 -0.9772993 0.09744966 -0.1513763 -0.9834439 0.09961599 -0.2330174 -0.8564782 0.4605953 -0.3488374 -0.8288621 0.4373786 -0.3477663 -0.8693526 0.3511193 -0.4326433 -0.8278192 0.3571208 -0.4587963 -0.8564637 0.236592 0.3562893 -0.8399462 0.4093267 0.2463608 -0.8379552 0.4869677 0.246363 -0.8379557 0.4869658 0.08485007 -0.8379558 0.5391017 0.0848639 -0.8379498 0.5391088 -0.03928709 -0.8403333 0.5406445 -0.07687163 -0.8692477 0.4883638 -0.1395484 -0.8285932 0.5421805 -0.2330407 -0.8548324 0.463631 -0.009518444 0.9999503 -0.002977669 -0.01211512 0.9998142 0.01499414 0.190159 0.9711483 0.1439113 0 1 2.4603e-6 0 1 8.51352e-7 0 1 0 0 1 9.67353e-7 0 0.9999898 0.004538655 0 1 -4.92738e-6 0.003809869 0.9999925 7.02848e-4 -0.001161158 0.9996215 -0.02749186 -0.001111388 0.9999781 0.006532788 0.002546846 0.9998508 0.01709097 -0.003419518 0.9999573 0.008588314 0 1 -8.08074e-7 0 1 7.66622e-7 0 1 -1.76564e-6 1.55289e-4 0.999714 0.02391612 -0.001310169 0.9999877 -0.004796624 6.28008e-4 0.9998278 0.01855182 0 1 -3.80822e-7 0 1 1.31027e-7 0 1 -3.19824e-7 -0.08078235 0.991627 -0.1007474 -0.1256682 0.9907984 -0.05026119 -0.1356762 0.9903669 -0.02767026 -0.139093 0.9898258 -0.02996885 -0.395878 0.9143335 -0.0852943 -0.2948275 0.9553076 -0.02154839 -0.1050716 0.9907998 -0.08529925 -0.1046963 0.9908446 -0.08524054 -0.1330411 0.9890947 -0.06318122 -0.1389195 0.9881113 -0.0658605 -0.3183547 0.9383704 -0.1345787 0.0036273 0.9996086 -0.02773952 -0.0678367 0.9915319 -0.1107371 -0.06783658 0.9915322 -0.1107348 -0.03774404 0.9914515 -0.1248982 -0.0377435 0.9914513 -0.1248999 -0.01674467 0.9916298 -0.1280243 -0.04155987 0.9921847 -0.1176535 0 0.9838476 -0.1790089 0.007761299 0.9867676 -0.1619551 0.04074716 0.9913895 -0.1244451 0.03774404 0.9914515 -0.1248982 0.03774356 0.9914513 -0.1249001 0.0678364 0.9915322 -0.1107345 0.06783646 0.9915319 -0.1107384 0.144569 -0.9396826 0.3099946 0.1450121 -0.939558 0.3101649 0.144544 -0.9396932 0.3099738 0.1445362 -0.9396932 0.3099777 0.1445435 -0.9396928 0.3099755 0.1445469 -0.9396919 0.3099765 0.1442479 -0.9397769 0.3098582 0.1445387 -0.9397007 0.3099535 0.1445477 -0.9396919 0.3099761 0.1445098 -0.9396921 0.3099933 0.1445434 -0.9396925 0.3099764 0.1445528 -0.9396912 0.3099759 0.1445436 -0.9396928 0.3099752 0.1444988 -0.9397037 0.3099631 0.144714 -0.9396414 0.3100516 0.1447064 -0.9396495 0.3100306 -0.09901279 -0.938517 0.33073 -0.01958066 -0.9629976 0.2687978 0.09902536 -0.9384986 0.3307785 0.06951904 -0.9469416 0.3137972 0.02490609 -0.939401 0.3419144 -0.07560515 -0.937003 0.3410415 -0.07562136 -0.9369994 0.3410478 -0.1445434 -0.939693 0.3099747 -0.1445311 -0.9396939 0.3099778 -0.1445423 -0.9396942 0.3099716 -0.1445469 -0.9396916 0.3099772 -0.1445426 -0.9396931 0.3099747 -0.1445446 -0.9396923 0.3099762 -0.1459371 -0.940254 0.3076114 -0.1444646 -0.9397603 0.3098072 -0.1446304 -0.9395653 0.3103213 -0.1445445 -0.9396998 0.3099535 -0.144553 -0.9396892 0.309982 -0.1445088 -0.9396929 0.309991 -0.1445216 -0.9396975 0.3099713 -0.1445465 -0.9396924 0.3099753 -0.1445243 -0.9396959 0.309975 -0.1445453 -0.9396923 0.3099763 -0.6101512 -0.7270692 0.3147793 -0.1654821 -0.9807176 0.1039656 -0.4826856 -0.8187959 0.3107862 -0.2683205 -0.9406224 0.2079271 -0.1123726 -0.9928659 0.03987258 -0.124587 -0.9918174 0.02786427 -0.1132085 -0.9904403 0.07881563 -0.6438948 -0.7518834 0.141672 -0.6256712 -0.7623242 0.1655218 -0.632139 -0.7560711 0.1695787 -0.5224551 -0.8186044 0.2385949 -0.4765051 -0.8309799 0.2870808 -0.1662703 -0.9751222 0.1465983 -0.5032947 -0.8640779 -0.00799787 -0.4899879 -0.869539 0.06175583 -0.2903733 -0.9121603 0.289218 -0.2698715 -0.9065296 0.3246126 -0.3784515 -0.8846887 0.2722142 0.3346071 -0.8170604 0.4695216 0.439571 -0.7421405 0.5059692 0.5322433 -0.6074908 0.5896372 0.618824 -0.2744392 0.7360299 0.6837051 -0.1533084 0.7134732 0.4615866 -0.5173231 0.7206349 0.4979144 -0.3773614 0.7808198 0.5889183 -0.1830236 0.7871961 0.5467265 -0.1886698 0.8157781 0.5378074 -0.2402074 0.8081235 0.5049612 -0.2436235 0.828047 0.5114169 -0.2132682 0.8324478 0.1737223 -0.9687741 0.1769107 0.2711881 -0.905984 0.3250385 0.3504066 -0.800813 0.4857097 0.3917338 -0.7964932 0.4605903 0.4149935 -0.7318229 0.5405698 0.4539452 -0.7271274 0.5149949 0.5012572 -0.6121029 0.6116138 0.5306103 -0.6102463 0.588262 0.6705505 -0.1689893 0.7223604 0.623658 -0.4150745 0.6623926 0.6727679 -0.2226452 0.7055582 0.4265293 -0.6637884 0.614376 0.4542039 -0.5335633 0.7134487 0.5024596 -0.5286072 0.6841848 0.5079504 -0.4397306 0.7406911 0.5612118 -0.4331008 0.7053121 0.5777334 -0.2854955 0.7646676 0.612708 -0.2835838 0.7376782 0.3148763 -0.8875681 0.3362678 0.3291942 -0.8711063 0.3644243 0.3239315 -0.8912491 0.3174013 0.3941732 -0.8124734 0.4295519 0.3857187 -0.8115866 0.4388034 0.421021 -0.7652727 0.4869283 0.281832 -0.8845471 0.3716816 -0.02897399 -0.9044389 0.4256183 0.1113358 -0.9646778 0.2387495 0.03068757 -0.994583 0.09931254 0.07339316 -0.9848057 0.1573897 0.02639186 -0.9363872 0.3499752 -0.3020026 -0.9034164 0.3043573 0.1471766 -0.9428503 0.2989525 -0.01267713 -0.9177827 0.3968808 -0.2393391 -0.9140148 0.3275571 -0.1986683 -0.9185082 0.3418681 -0.1964586 -0.9354897 0.2937061 -0.2894615 -0.8795199 0.3776996 -0.2020694 -0.9082916 0.3662983 -0.08403509 -0.9830591 0.1628897 -0.01805877 -0.9808159 0.1940986 -0.02352905 -0.8871907 0.4608026 -0.06633126 -0.9215626 0.3825214 -0.06638216 -0.9215589 0.3825215 -0.01261496 -0.9177751 0.3969002 0.07520973 -0.8744069 0.4793288 0.03647541 -0.9118052 0.4089999 -0.2383922 -0.9140841 0.328054 -0.1593804 -0.8847861 0.4378944 -0.03569561 -0.9547557 0.2952412 -0.06953704 -0.9627938 0.2611375 0.03941828 -0.9100318 0.4126602 0.03675276 -0.9120249 0.4084848 0.03618049 -0.9118841 0.40885 0.1080374 -0.9048395 0.4118174 0.3089201 -0.8665085 0.3920861 0.308054 -0.8679109 0.3896582 0.3038555 -0.8808414 0.3630292 0.1147872 -0.9010578 0.418233 0.1116366 -0.8989861 0.423511 0.1289729 -0.9015803 0.4129397 0.1870162 -0.9276032 0.3233841 0.1738272 -0.9310289 0.3208883 -0.08192199 -0.8924434 0.4436596 -0.04245817 -0.9379944 0.3440407 -0.04660987 -0.9210376 0.3866748 -0.05263197 -0.9186428 0.391568 -0.0664497 -0.9014718 0.4277069 -0.08994752 -0.8879565 0.4510463 -0.0464192 -0.926382 0.3737133 -0.08282101 -0.8914423 0.4455012 -0.04208636 -0.924526 0.3787881 -0.03797698 -0.9265117 0.3743447 0.02039986 -0.9550084 0.2958768 -0.01413619 -0.9423811 0.3342426 0.07852119 -0.984371 0.1576333 0.02388477 -0.9820406 0.1871522 -0.1408696 -0.9428476 0.3019837 -0.0343132 -0.9966986 0.07358443 -0.06311494 -0.9857729 0.1557831 -0.09156024 -0.9747695 0.2035712 -0.1275107 -0.9531888 0.2741755 0.5421171 -0.8051444 0.2405235 0.5057865 -0.8322325 0.2270887 0.2358672 -0.9687029 -0.07733994 0.02136701 -0.9959194 0.08768123 0.09730887 -0.9928585 0.06901448 -0.0727232 -0.9828881 0.1692412 0.1812576 -0.9812574 0.06541937 0.4039006 -0.882443 0.2411611 0.4108821 -0.8529391 0.3219795 0.451959 -0.8522352 0.2634925 0.6073577 -0.7492756 0.2640128 0.5485185 -0.7975385 0.2511175 0.07943117 -0.9033461 0.4214934 -0.005031764 -0.8430128 0.53787 0.3398079 -0.9336339 0.1133951 0.3383864 -0.8972868 0.2834981 0.4339548 -0.8995433 0.0500527 0.5166297 -0.8025228 0.298414 0.5053923 -0.8284208 0.2414491 -0.5487345 -0.8042829 0.2280781 -0.4216858 -0.6782062 0.6018452 0.08565706 -0.5722652 0.815583 -0.2945833 -0.9047146 0.3077535 -0.2920348 -0.9053934 0.3081858 -0.1818369 -0.8741904 0.4502515 -0.3397603 -0.8632126 0.3733993 -0.03175252 -0.8642899 0.5019907 0.4604622 -0.3799759 0.8022424 -0.1428117 -0.9219883 0.3599202 -0.1437142 -0.9218488 0.3599183 -0.142757 -0.9219917 0.3599332 0.09348654 -0.9019417 0.4216179 0.09349799 -0.9019524 0.4215923 0.08246397 -0.9516578 0.295884 0.7091846 -0.5436682 0.4488676 0.7091387 -0.5438008 0.4487795 0.1845619 -0.8564179 0.4821673 0.09339064 -0.9019652 0.4215888 0.1833226 -0.8558664 0.4836173 0.07013195 -0.9446899 0.3203789 0.2858134 -0.6991332 0.6553804 0.2463753 -0.6597366 0.7099626 0.2682735 -0.6567191 0.7048045 0.1676627 -0.54753 0.8198172 0.1629979 -0.4815472 0.8611295 0.118394 -0.3499593 0.9292532 0.3094768 -0.5312906 0.788641 -0.1364769 -0.6335753 0.7615488 -0.1124406 -0.6101989 0.7842286 -0.4746009 -0.6918807 0.5441096 -0.6903086 -0.7149075 0.1112719 -0.678989 -0.7212233 0.1371534 -0.684801 -0.714639 0.142614 -0.6461588 -0.7077063 0.2857109 -0.6567057 -0.7026237 0.2739664 -0.5580753 -0.794596 0.2391004 -0.5637571 -0.8015698 0.1991578 -0.5830468 -0.7525017 0.3062639 -0.5572231 -0.7809752 0.2820999 -0.5655069 -0.6968255 0.4411759 -0.5946341 -0.6577245 0.4623947 -0.5957056 -0.6699539 0.4430538 -0.3134055 -0.8922994 0.3249291 -0.3488937 -0.859438 0.373684 -0.2331134 -0.8220852 0.5194557 -0.07045924 -0.8046876 0.5895029 -0.04896986 -0.8265344 0.5607521 -0.1428008 -0.9219596 0.359998 -0.3581854 -0.6229798 0.6954132 -0.4488485 -0.4753694 0.7566763 -0.3274264 -0.6607363 0.6754403 -0.3380253 -0.7490561 0.5697843 -0.3474417 -0.7378838 0.5786293 -0.3559617 -0.8345561 0.4204847 -0.4033125 -0.7823263 0.4746627 -0.3685219 -0.8777461 0.3061919 -0.09540128 -0.5837539 0.8063064 -0.09848248 -0.5909646 0.8006635 -0.0551694 -0.6439491 0.7630766 -0.07101029 -0.7742229 0.6289169 -0.03876036 -0.8063662 0.5901451 0.06925219 -0.7255161 0.6847121 0.1443331 -0.8003039 0.5819638 0.2435472 -0.7158192 0.654437 0.1701064 -0.8445664 0.5077121 0.4297736 -0.711835 0.5555047 0.6055543 -0.7192023 0.3406642 0.431784 -0.8561819 0.2837519 -0.32097 -0.6553594 0.6837269 -0.1082414 -0.7449652 0.6582635 -0.1340247 -0.7713736 0.6221096 -0.108193 -0.8760892 0.4698534 -0.02616178 -0.7970155 0.603392 -0.1151202 -0.8859482 0.4492697 -0.118891 -0.8901919 0.4397992 -0.1141986 -0.9078097 0.4035349 -0.1097915 -0.9070568 0.4064404 -0.1189024 -0.9208043 0.3714588 -0.1009281 -0.9432429 0.3163961 0.08781093 -0.9102538 0.4046323 0.1006805 -0.9012482 0.4214443 0.09969604 -0.8994907 0.4254143 0.1021859 -0.9014365 0.4206786 0.1064218 -0.9034827 0.4152031 0.0776031 -0.9047912 0.418725 0.07366746 -0.9072711 0.414044 -0.1168885 -0.7270097 0.6766048 0.01145893 -0.8212063 0.5705164 0.189999 -0.8427787 0.5036115 0.1846019 -0.8361677 0.5164743 0.338367 -0.8686187 0.3619522 0.3356908 -0.8449329 0.4164136 0.4297405 -0.8438535 0.3213011 0.4415096 -0.8463402 0.2979561 0.6395534 -0.7224478 0.2627559 0.4836947 -0.6820472 0.548499 0.5180535 -0.7027414 0.4876219 0.6341344 -0.7289816 0.2577976 0.5846973 -0.6812512 0.4404839 0.6394237 -0.7119126 0.2903751 0.4001082 -0.6912051 0.6017882 0.5321421 -0.7446359 0.4029172 0.5243258 -0.7539399 0.3957992 0.6291801 -0.7570545 0.1760709 0.6763669 -0.7243623 0.1335184 -0.262708 -0.442157 0.8576024 -0.2244922 -0.4911847 0.84163 -0.1607868 -0.476389 0.8644079 -0.08962404 -0.55899 0.8243165 -0.007700443 -0.5650171 0.8250434 0.03675401 -0.6112754 0.7905641 0.1426039 -0.6319184 0.7618027 0.1518933 -0.6405365 0.7527559 0.2820236 -0.6932706 0.6632034 0.2479131 -0.6449162 0.7229261 0.2987727 -0.6875901 0.6617816 0.5631192 -0.7973005 0.217276 0.5561991 -0.7970201 0.2353753 0.3893497 -0.760927 0.5190349 0.4713669 -0.8281217 0.3033609 0.2402761 -0.7423316 0.6254687 0.3424184 -0.8378916 0.4250734 0.0904836 -0.693246 0.7149984 0.2001549 -0.8198866 0.5363992 -0.05718445 -0.6227399 0.7803365 0.05480569 -0.7772862 0.6267556 -0.205442 -0.5262724 0.8251248 -0.1005581 -0.7098901 0.697097 -0.3138883 -0.4671089 0.8266096 -0.1730752 -0.6448406 0.7444633 -0.4168576 -0.4233136 0.8043851 0 -1 -9.59792e-7 0 -1 2.04657e-6 0 -1 -2.18414e-6 0 -1 -1.09564e-6 0 -1 -8.93761e-7 0 -1 -1.26089e-6 0 -1 -9.69545e-7 0 -1 3.18068e-6 0.1968975 -0.8848397 0.4222443 0.1975515 -0.8476492 0.4924065 0.1987319 -0.9046088 0.3770789 0.2436839 -0.7890154 0.5639796 0.2585803 -0.8322762 0.4903598 0.273508 -0.7612159 0.5879999 0.3147448 -0.6684227 0.6739042 0.3162429 -0.6018732 0.733307 0.4200503 -0.3695062 0.8288686 0.4053407 -0.3959676 0.8239591 0.3421398 -0.5159772 0.7853077 0.3779761 -0.6087656 0.6975232 0.4162951 -0.6308121 0.6548089 0.4160146 -0.5038949 0.756982 -0.1547771 -0.6425161 0.7504779 0.9997776 -0.0184347 0.01024198 0.9605718 -0.2347822 0.1489271 0.9891152 -0.1463539 -0.01522064 0.8830997 -0.4238703 0.201169 0.808053 -0.5445379 0.2247867 0.7093474 -0.6341233 0.3077565 0.6661095 -0.6798215 0.3068241 0.5883107 -0.7400715 0.3258599 0.4670913 -0.8092346 0.3563219 0.4149059 -0.8239271 0.386002 0.2642472 -0.8855513 0.3820635 0.07052803 -0.9070876 0.4149917 0.03278082 -0.9149882 0.4021468 -0.4350017 -0.7182433 0.5430472 -0.5595869 -0.7000638 0.4435914 -0.208197 -0.8954198 0.3935448 -0.2876402 -0.8662885 0.4084209 -0.3861545 -0.8443112 0.3715148 -0.4906893 -0.797551 0.3509078 -0.609759 -0.7445638 0.2716962 -0.2362675 -0.7763742 0.5843122 -0.2889479 -0.7623108 0.5791299 -0.1390153 -0.7293793 0.6698363 -0.1521102 -0.6270058 0.7640198 0.3246853 -0.5239406 0.7874425 0.1206828 -0.582746 0.8036436 0.07124495 -0.6233685 0.7786759 -0.008336067 -0.6170255 0.786899 -0.1057481 -0.6128719 0.7830744 0.8830726 -0.2501504 0.3969983 0.7229043 -0.3503273 0.5955503 0.7078482 -0.3639814 0.6053664 0.4624699 -0.4675987 0.7533082 0.5017443 -0.4504548 0.7384735 -0.1498517 -0.7288808 0.6680399 0.07021993 -0.7353965 0.6739891 0.07048743 -0.7352959 0.6740708 0.4125603 -0.6714792 0.6155565 0.4143266 -0.6704441 0.6154984 0.706323 -0.5214687 0.4787257 0.7083305 -0.5193051 0.4781111 0.8815945 -0.3472488 0.3197022 0.8827546 -0.3452386 0.3186766 0.9795761 -0.1477514 0.1363826 0.9940142 -0.02091109 0.1072311 0.9618406 -0.1630231 0.2197414 0.9672746 -0.1049122 0.2310266 0.5195525 -0.732364 0.440123 0.171513 -0.6319638 0.7557811 -0.972474 -0.1931433 0.1303458 -0.993719 -0.06286859 0.09257531 -0.4576941 -0.4855622 0.7448124 -0.4156621 -0.509181 0.7536311 -0.3486545 -0.5237654 0.7772452 -0.9854065 -0.1024345 0.1359462 -0.8809698 -0.2317705 0.4125225 -0.8972303 -0.2237772 0.3806595 -0.7085701 -0.3813633 0.5937092 -0.6762763 -0.3906009 0.6245649 -0.5066525 -0.4571495 0.7309703 -0.4849891 -0.4370224 0.7574939 -0.07106143 -0.5855999 0.8074795 -0.04159325 -0.6375213 0.7693092 -0.1597636 -0.5795661 0.7991112 0.5203511 -0.7010018 0.4876794 0.4596753 -0.6986199 0.5482963 0.2894243 -0.7548936 0.5885317 0.2859733 -0.7534235 0.5920915 0.2070414 -0.7312029 0.6499817 -0.07042223 -0.8964558 0.4375016 0.1261944 -0.9105149 0.3937484 0.2869347 -0.8594738 0.4230524 0.3922209 -0.8340744 0.387921 0.4514142 -0.8090903 0.3762952 0.5908726 -0.748847 0.3001631 0.7231062 -0.6262224 0.2914841 -0.4140204 -0.8172794 0.4008012 -0.2988846 -0.865458 0.4020578 -0.1603184 -0.8951832 0.4158667 -0.8826149 -0.4212794 0.2086016 -0.8014588 -0.5461421 0.2437061 -0.7084899 -0.6297159 0.3185907 -0.6308935 -0.7061123 0.3215258 -0.4438744 -0.8090311 0.3852846 -0.9673667 -0.2428035 0.07244461 -0.9678254 -0.2436456 0.06285619 -0.9889569 -0.1084826 0.1009739 -0.8825978 -0.344127 0.3203091 -0.8832786 -0.343464 0.3191419 -0.7080683 -0.5172986 0.4806677 -0.7092646 -0.5168798 0.4793527 -0.4143097 -0.6673328 0.6188817 -0.4152292 -0.6673322 0.6182658 -0.07051724 -0.7317336 0.6779332 -0.0706861 -0.7317818 0.6778635 0.1253306 -0.7278331 0.6742042 0.1703354 -0.6808694 0.7123222 -0.3157839 -0.8707323 0.3769696 -0.1931581 -0.8201913 0.5384946 -0.200075 -0.8583781 0.4723948 -0.1747635 -0.9104873 0.3747943 -0.4550735 -0.3595588 0.8146322 -0.4407087 -0.3858338 0.8104988 -0.2846669 -0.8540748 0.4353402 -0.2599188 -0.7731994 0.5784505 -0.3209477 -0.6553931 0.6837049 -0.3308191 -0.6110641 0.719138 -0.3880465 -0.4780367 0.7879726 -0.9659259 0 -0.2588189 -0.7071071 0 -0.7071065 -0.7071074 0 -0.7071061 -0.2588152 0 -0.9659269 0.2588152 0 -0.9659269 0.7071081 0 -0.7071055 0.7071078 0 -0.7071058 0.9659255 0 -0.2588201 0.965927 0 0.2588149 0.9659242 0 0.2588254 0.7071081 0 0.7071055 0.7071183 0 0.7070953 0.2588152 0 0.9659269 -0.2588152 0 0.9659269 -0.7071177 0 0.707096 -0.7071074 0 0.7071061 -0.9659245 0 0.2588244 -0.9659273 0 0.2588136 -0.9659259 0 -0.2588191 0 -1 8.76695e-7 0 -1 -8.76686e-7 0 -1 8.76685e-7 -1.72454e-6 -1 0 0 -1 -4.68536e-6 2.0782e-7 -1 0 2.20784e-7 -1 7.19126e-7 0 -1 2.4361e-7 0 -1 3.05574e-7 0 -1 9.31578e-7 0 -1 2.37328e-7 0 -1 -8.84095e-7 0 -1 2.47364e-7 0 -1 1.23727e-7 0 -1 2.42533e-7 0 -1 1.27001e-6 0 -1 -3.25763e-7 0 -1 2.21313e-7 0 -1 -3.04138e-6 0 -1 9.10413e-7 0 -1 -3.75154e-7 0 -1 -1.10193e-6 0 -1 1.34903e-6 -0.9813141 0 0.1924133 -0.9813154 0 0.1924062 -0.7629346 0 0.6464758 -0.7629266 0 0.6464852 -0.3508589 0 0.9364283 -0.3508756 0 0.9364221 0.1503033 0 0.98864 0.1502847 0 0.9886428 0.613282 0 0.7898641 0.9205788 0 0.3905571 0.9205741 0 0.3905678 0.9941629 0 -0.1078898 0.9941627 0 -0.107891 0.8153551 0 -0.5789612 0.8153659 0 -0.5789459 0.4295434 0 -0.9030462 0.4295552 0 -0.9030407 -0.06528031 0 -0.9978671 -0.06529915 0 -0.9978658 -0.5435742 0 -0.8393613 -0.5704599 -0.7929767 0.2139239 -0.9217382 0 0.3878129 -0.6819888 0 0.7313626 -0.6819867 0 0.7313646 0.6819908 0 0.7313607 0.5704616 -0.7929752 0.2139251 0.921736 0 0.3878179 0.6819865 0 0.7313648 -0.9658411 0 0.2591356 -0.9658411 0 0.2591351 -0.8189725 0 0.5738329 -0.8190259 0 0.5737565 -0.5746807 0 0.8183778 -0.5732666 -3.22167e-4 0.8193688 0.5741791 0 0.8187299 0.5741061 0 0.8187809 0.8207583 0 0.5712757 0.8207954 0 0.5712225 0.9663913 0 0.2570756 0.9663821 0 0.2571105 0.2162912 0 0.9763289 0.2162916 0 0.9763288 -0.2164373 0 0.9762966 -0.2162986 3.98482e-4 0.9763273 0 0 1 1.38402e-5 0 1 6.92007e-6 0 1 -6.92009e-6 0 1 -2.76803e-5 0 1 1.03801e-5 0 1 -1.03801e-5 0 1 0 -0.9987447 -0.05009299 -3.78917e-5 0 1 0.496139 0 0.8682432 0.01699709 0 0.9998556 0.07353311 0 0.9972928 0.03211194 0 0.9994844 -0.02040386 0 0.9997918 -0.00566262 0 0.999984 -0.001345813 0 0.9999991 0.02794277 0 0.9996096 -0.02100497 0 0.9997794 0.00549817 0 0.9999849 -0.01055347 0 0.9999444 0.01705509 0 0.9998546 0.007866024 0 0.9999691 -0.06237828 0 0.9980526 0.005755245 0 0.9999834 0.09950369 0 0.9950373 -0.003968179 0 0.9999922 -0.01769632 0 0.9998434 -0.09594088 0 0.995387 0.02689391 0 0.9996383 -0.02045607 0 0.9997908 0.003152072 0 0.9999951 -0.1102424 0 0.9939048 0.01298063 0 0.9999158 0.050628 0 0.9987176 -0.03949481 0 0.9992198 0.007961869 0 0.9999683 -0.02200287 0 0.999758 0.01548326 0 0.9998802 -0.01944917 0 0.9998109 0.018314 0 0.9998323 -0.01602995 0 0.9998716 9.68805e-5 0 1 -4.4405e-4 0 1 -0.03612095 0 0.9993475 0.0382952 0 0.9992665 -0.015585 0 0.9998786 -0.02221673 0 0.9997532 -0.05121475 0 0.9986878 -0.01999598 0 0.9998001 0.01895391 0 0.9998204 -0.05349469 0 0.9985682 0.006308972 0 0.9999801 0.03224128 0 0.9994802 -0.03172999 0 0.9994965 0.8720866 0.4892314 -0.01084834 0.87476 0.483857 -0.02602714 0.8763557 0.4801067 -0.03870826 0.8776787 0.4760879 -0.05495941 0.8788225 0.4718045 -0.07121574 0.8777366 0.4507974 -0.162358 0.84761 0.415959 -0.3294472 0.06080937 0.02929073 -0.9977197 0.05971574 0.02902132 -0.9977936 0.07612532 0.03261935 -0.9965646 0.07849496 0.03297907 -0.9963689 0.0800119 0.03330117 -0.9962375 0.06182837 0.02954834 -0.9976494 0.06530559 0.03028738 -0.9974056 0.06892937 0.0310353 -0.9971387 0.0704168 0.03136676 -0.9970244 0.07278323 0.03179168 -0.996841 0.07462632 0.03229004 -0.9966887 0.1232443 0.04184037 -0.991494 0.1917861 0.0505799 -0.9801325 0.20435 0.05206465 -0.9775124 0.2260297 0.05465006 -0.9725862 0.2503479 0.05723655 -0.9664626 0.2679814 0.05911231 -0.9616089 0.2885738 0.06107193 -0.955508 0.3100339 0.06288766 -0.9486433 0.4562592 0.07532936 -0.8866528 0.6346179 0.08072161 -0.7685989 0.6839332 0.0819301 -0.7249296 0.7349629 0.08129942 -0.6732161 0.783878 0.08033412 -0.6156963 0.8983898 0.07371991 -0.432968 0.9607996 0.0589683 -0.2709004 0.9768497 0.05187439 -0.207542 0.9920205 0.04062551 -0.1193525 0.9977157 0.02875816 -0.06112623 0.9993308 0.0203278 -0.0304104 0.999863 0.01234847 -0.01103001 0.9999912 0.004116177 -7.60435e-4 0.0337429 0.05143958 -0.998106 0.0331282 0.05062258 -0.9981684 0.5123922 0.8585888 -0.01672571 0.5205845 0.8526736 -0.04403972 0.5272249 0.8440353 -0.09817588 0.5293577 0.83938 -0.1233762 0.5313928 0.8314148 -0.1623918 0.5314471 0.8210765 -0.2083202 0.06018728 0.07485324 -0.9953765 0.06179571 0.07611984 -0.995182 0.0636686 0.07759279 -0.9949502 0.03429549 0.05215775 -0.9980499 0.04282122 0.05972784 -0.9972959 0.05277878 0.0683946 -0.9962613 0.05386316 0.06960242 -0.9961196 0.05620741 0.07146292 -0.9958584 0.05855703 0.07342034 -0.9955806 0.02380275 0 -0.9997168 0.07193905 0.08481389 -0.9937965 0.08166438 0.092727 -0.992337 0.08399742 0.09476631 -0.9919495 0.08662265 0.09687042 -0.9915205 0.08908635 0.0989151 -0.9911002 0.09648358 0.1045783 -0.9898255 0.1168181 0.1207239 -0.9857887 0.7933792 0.6087278 -4.35205e-4 0.867953 0.4966461 -5.26896e-4 0.02499216 0 -0.9996877 0.2588118 0.9659278 -2.15912e-4 0.5035161 0.863986 -1.99136e-4 0.5088121 0.8608317 -0.008895039 0.3727446 0.1001709 -0.9225115 0.9637399 0.2582524 -0.06716465 0.9636731 0.2584715 -0.06728106 0.9545592 0.2587131 -0.1479339 0.954546 0.2587493 -0.147955 0.9468945 0.2587584 -0.1908795 0.9468777 0.2588117 -0.1908908 0.7777283 0.6087327 -0.1567906 0.3133614 0.314423 -0.8960709 0.706219 0.7062745 -0.04930633 0.7058754 0.7066018 -0.04953634 0.6989262 0.7069414 -0.1083336 0.6988567 0.7070039 -0.1083736 0.697571 0.707074 -0.1159362 0.5967702 0.7933379 -0.1203343 0.258827 0.9659236 -5.94663e-4 0.2587561 0.9657721 -0.01815855 0.2585133 0.9658347 -0.01828408 0.2558712 0.9658963 -0.03967893 0.2558267 0.9659072 -0.03969854 0.2537649 0.9659116 -0.05116993 0.253722 0.9659224 -0.05117642 0.978654 0 0.2055151 0.9842228 0.001052737 0.1769303 0.984866 0.002152562 0.1733042 0.9998832 0 0.01528292 0.9972455 0.006100714 0.07392066 0.9969906 0.004541337 0.07739025 0.9903126 -6.93728e-4 0.1388545 0.9647026 0 0.263342 0.9748639 4.07784e-4 0.2228013 0.9752202 2.5038e-5 0.2212365 0.9797927 2.26928e-5 0.2000158 0.9706301 0 0.2405768 0.9647676 -0.01047861 0.2628949 0.9705496 0.02302706 0.2397987 0.9645196 -6.81017e-4 0.2640107 0.9955312 8.3596e-4 -0.09442967 0.9952149 -8.37488e-4 0.09770691 0.9996788 4.25507e-4 0.02534288 0.9982508 -0.004942476 0.05891633 0.9970125 -0.001411378 0.07722783 0.9866551 0.002860307 0.1627991 0.977798 0.0246399 0.2080965 0.9871031 0 0.1600856 0.9881413 -0.003222763 0.1535135 -0.4002332 -0.9156453 0.03751057 -0.1210476 -0.9904545 -0.06593424 0.1060339 -0.9436477 -0.3135058 0.09805369 -0.9458346 -0.3094873 -0.1379315 -0.9835694 -0.1164748 -0.1288996 -0.9835132 -0.1268329 -0.04982662 -0.9773482 -0.2056885 -0.03732204 -0.9824718 -0.1826367 0.02338796 -0.9666484 -0.2550371 -0.3807327 -0.924659 0.006959795 -0.3634963 -0.9311816 0.0277751 -0.2376668 -0.9660141 -0.1016429 -0.242697 -0.9674015 -0.0723381 -0.1509498 -0.9743941 -0.1666448 -0.08217364 -0.9681344 -0.2365659 -0.07747161 -0.9680249 -0.2385918 0.0246852 -0.9394167 -0.3418877 0.04287588 -0.9281347 -0.3697671 0.0812993 -0.9134666 -0.3987095 0.66152 0 0.7499275 0.983101 0 0.1830644 0.9590913 0.03180646 0.2813047 -0.9847232 0 0.1741273 -0.9660435 0.02944767 0.2566961 -0.9069818 0 0.4211699 -0.8197864 0 0.5726694 -0.8233252 -0.001119911 0.5675688 -0.6409165 0.002237498 0.7676075 -0.6456664 0 0.7636197 -0.6499565 -5.0706e-4 0.7599712 -0.3387975 5.06576e-4 0.9408593 -0.2688718 0.007095396 0.9631499 -0.09143078 0 0.9958115 0.08337169 0 0.9965186 0.2447034 0.00780946 0.9695665 0.3470562 -9.17236e-4 0.9378439 0.6677379 0.001191198 0.7443957 0.6475952 0.01203852 0.7618894 0.8319196 -0.004345953 0.5548794 0.8151279 0 0.5792812 0.9035363 0 0.4285116 0 1 2.34225e-6 0 1 5.44955e-6 0 1 0 0 1 2.82298e-7 0 1 1.46921e-7 0 1 0 0 1 -1.60667e-6 0 1 -7.25844e-7 -1.49023e-7 1 0 0 1 2.98599e-7 0 1 0 -1.45109e-6 1 8.76821e-6 -4.9648e-6 1 6.83009e-6 -3.68398e-5 1 -4.11887e-5 3.02401e-5 1 1.83834e-5 0 1 6.84788e-6 0 1 -4.26915e-6 0 1 -6.86727e-6 0 1 -5.58848e-7 0 1 1.92767e-6 0 1 -5.28181e-7 0 1 5.86803e-7 0 1 6.71158e-7 0 1 -4.96976e-7 0 1 -3.13936e-7 0 1 5.24565e-6 0 1 0 0 1 0 0 1 -2.03067e-7 0 1 3.92094e-7 0 1 6.33525e-7 0 1 -4.80794e-7 0 1 -2.37906e-7 0 1 1.86882e-7 0 1 0 0 1 0 0 1 -1.4638e-7 0 1 1.46684e-7 0 1 -1.44101e-6 0 1 2.93368e-7 0.9999999 2.49294e-4 -5.52581e-4 1 1.99935e-5 -1.81056e-6 1 1.96425e-5 -1.62027e-5 1 0 -1.46883e-5 0.9998087 -0.003353416 0.01927208 1 4.35622e-5 -1.62028e-5 1 3.27056e-4 0 1 2.88309e-4 -5.56835e-6 1 6.22353e-6 -2.4573e-6 1 1.60882e-5 -2.95293e-6 1 7.68031e-6 -3.28014e-6 1 6.90749e-6 -3.70963e-6 1 4.67187e-6 -4.13891e-6 1 5.31808e-6 -4.71406e-6 1 1.77893e-5 -1.52601e-6 1 8.58348e-6 -1.07671e-6 1 5.68195e-5 -1.38421e-6 0.1775355 -0.8702827 -0.4594445 0.1611201 -0.924392 -0.3457453 0.1902422 -0.8973158 -0.398287 0.08063715 -0.9158939 -0.3932381 0.1122118 -0.8959339 -0.4297804 0.4194059 -0.8044343 -0.4206951 0.4106067 -0.803979 -0.4301395 0.4060474 -0.8033498 -0.4356086 0.380558 -0.8069947 -0.451592 0.34327 -0.8053108 -0.4833635 0.3600878 -0.8091335 -0.4643703 0.29694 -0.8210468 -0.487554 0.304814 -0.8205812 -0.4834614 0.2534409 -0.8366708 -0.4855408 0.2627582 -0.8346339 -0.4840915 0.2138363 -0.8540521 -0.4742038 0.2445813 -0.8439809 -0.4773638 0.1793034 -0.8693572 -0.460509 0.2049524 -0.8913289 -0.4043853 0.2293779 -0.8837893 -0.4078019 0.1428288 -0.8853748 -0.442393 0.142826 -0.8853771 -0.4423894 0.1936985 -0.9058731 -0.3766627 0.2042537 -0.9020844 -0.3801636 0.2160239 -0.9179792 -0.3326378 0.2588189 0 -0.9659259 0.2588238 0 -0.9659246 0.7071062 0 -0.7071075 0.7071088 0 -0.7071049 0.9659251 0 -0.2588222 0.9659254 0 -0.2588208 -0.9807861 0 -0.1950867 -0.9807859 0 -0.1950873 -0.8314717 0 -0.5555672 -0.8314706 0 -0.5555688 -0.5555708 0 -0.8314694 -0.1950878 0 -0.9807859 -0.1950945 0 -0.9807845 0.9860947 0 0.1661842 0.7278122 0 0.6857766 -0.9816322 0 0.190783 -0.7382221 0 0.6745578 -0.983275 0.002936899 0.1821035 -0.8696638 -0.00292319 0.4936358 -0.8796943 -0.009799301 0.4754387 -0.7178882 0.00640732 0.696129 -0.7382167 0 0.6745637 -0.5857449 0 0.8104955 -0.4593353 0.007118105 0.8882344 -0.3470552 -0.001959025 0.9378427 -0.004403293 0.002649426 0.9999869 0.01249337 0.004339993 0.9999126 0.9847228 0 0.1741293 0.986055 -0.002801418 0.1663966 0.8652897 0.002932786 0.5012636 0.8723574 -0.002260088 0.4888637 0.7235432 8.41653e-4 0.6902787 0.5922914 0 0.8057239 0.4813827 0.007415592 0.8764792 0.3792738 0 0.9252846 0.2124547 0 0.977171 -0.8252858 0.28087 0.4899138 -0.6501419 0.6984899 0.299044 -0.7998018 0.5999158 0.02044939 -0.6439794 0.09615528 -0.7589762 -0.7537703 0.1220074 -0.6457126 -0.7455074 0.1492241 -0.6495775 -0.7086544 0.328013 -0.6246731 -0.7096156 0.2986268 -0.6381754 -0.7161318 0.6583959 -0.2316681 -0.7306675 0.5792888 -0.3613163 -0.7263449 0.5859875 -0.3592239 -0.7298223 0.5190848 -0.4448713 -0.7504439 0.4488841 -0.4851154 -0.7224286 0.6887705 -0.06076294 -0.7095999 0.6904466 -0.1405404 -0.7175303 0.6566583 -0.2322717 -0.7208771 0.6506478 0.2387333 -0.6980665 0.6848688 0.2089449 -0.7095785 0.6920158 0.1327123 -0.9931041 0.05594789 -0.1030244 -0.9948853 0.05918532 -0.08185607 -0.9957764 0.06392425 -0.06590181 -0.9978574 0.06542444 5.42719e-4 -0.9965518 0.07496064 -0.0355758 -0.9964204 0.07911801 -0.02977782 -0.9961583 0.06784486 -0.05536997 -0.9732495 0.05315595 -0.223517 -0.975389 0.05657553 -0.2131092 -0.9773425 0.06088268 -0.2027193 -0.9807162 0.07104611 -0.1820665 -0.9783561 0.07696235 -0.192084 -0.9807428 0.07161229 -0.1817012 -0.9839705 0.06479972 -0.1661415 -0.9876589 0.05874902 -0.1451843 -0.9906941 0.05580359 -0.1241418 -0.9771354 0.1220074 0.1741284 -0.9978224 0.06260645 0.02076244 -0.997214 0.06236457 0.04092526 -0.9960388 0.06466519 0.06103402 -0.9942854 0.06948477 0.08104693 -0.9919206 0.07681751 0.1009585 -0.9872184 0.0914461 0.1305279 -0.9762018 0.1149044 0.1839212 -0.9744269 0.1049786 0.1986749 -0.9713951 0.09396976 0.2180857 -0.9656807 0.08060455 0.2469086 -0.9581747 0.0734263 0.2766044 -0.9535487 0.07160276 0.2926054 -0.752183 0.6587908 0.01467943 -0.8189852 0.5704602 0.06195515 -0.7467436 0.6132498 0.2574853 -0.7467473 0.6132451 0.2574858 -0.7144706 0.6214978 0.3213602 -0.7098091 0.6214454 0.3316274 -0.6451829 0.6524636 0.3975303 -0.6784454 0.59412 0.4321265 -0.844488 0.08107477 0.5294023 -0.8337651 0.07658445 0.5467821 -0.8248646 0.07481926 0.5603575 -0.8547301 0.0878604 0.511583 -0.8550881 0.08819395 0.5109269 -0.8656684 0.08120411 0.493988 -0.950287 0.07106751 0.303157 -0.9451281 0.07130938 0.3188228 -0.9395755 0.07358783 0.3343391 -0.9357017 0.07577949 0.3445575 -0.9296364 0.08000504 0.3596882 -0.921074 0.0881958 0.3792681 -0.9209651 0.088032 0.3795705 -0.915116 0.08249831 0.3946602 -0.9110496 0.0794692 0.4045657 -0.9046639 0.075841 0.4193226 -0.8910641 0.07236099 0.4480723 -0.8761522 0.07625055 0.4759658 -0.6619746 0.0143128 -0.7493897 -0.6971113 -0.005793154 -0.7169396 -0.759249 0.1036809 -0.6424884 -0.7565347 0.1066121 -0.6452048 -0.7666816 0.09701102 -0.6346561 -0.773432 0.09101295 -0.6273114 -0.7799817 0.08557933 -0.6199232 -0.7864335 0.08065944 -0.6123859 -0.7927783 0.07616549 -0.6047325 -0.7990115 0.07222467 -0.5969627 -0.8051958 0.0688095 -0.5890035 -0.8112149 0.06588059 -0.5810253 -0.8171664 0.06348991 -0.5728946 -0.8229805 0.06164985 -0.5647145 -0.8287573 0.06033498 -0.5563462 -0.834379 0.05956387 -0.5479636 -0.8399354 0.05932879 -0.5394339 -0.8453935 0.05965304 -0.5308026 -0.8507138 0.06051963 -0.5221337 -0.8559384 0.06194174 -0.5133544 -0.8610761 0.06393724 -0.5044402 -0.8660389 0.06649267 -0.4955355 -0.8709497 0.06958407 -0.4864204 -0.8756805 0.07328677 -0.4772974 -0.8825671 0.0796265 -0.4633951 -0.9107529 0.1172905 -0.3959447 -0.8842532 0.1533613 -0.4411087 -0.8923069 0.1440182 -0.4278404 -0.8974786 0.1380816 -0.4188863 -0.9024894 0.1325705 -0.4098027 -0.9073759 0.1273394 -0.400567 -0.9120656 0.1226107 -0.3912838 -0.9166207 0.1181449 -0.381901 -0.9231687 0.1121972 -0.3676567 -0.9313419 0.105785 -0.3484419 -0.9389463 0.101009 -0.328903 -0.9459707 0.09785223 -0.309135 -0.9617131 0.04807209 -0.2698095 -0.9672233 0.04802453 -0.2493451 -0.9709414 0.05060058 -0.2339072 -0.781742 0.619515 0.07127958 -0.7502053 0.6610368 -0.01492023 -0.7870132 0.5895676 -0.1817149 -0.7870156 0.589564 -0.1817166 -0.7970547 0.5182846 -0.3099756 -0.7970568 0.5182827 -0.3099736 -0.7801225 0.3920575 -0.4875448 -0.7779211 0.3943307 -0.4892261 -0.7211496 0.3854326 -0.5756605 -0.7866364 0.4079325 0.4634591 -0.7519052 0.3685203 0.5466548 -0.8679654 0.3597564 0.3423618 -0.8679655 0.3597556 0.3423622 -0.9317463 0.3346556 0.140906 -0.8826957 0.4577005 0.1065772 -0.9101301 0.4031769 -0.09545475 -0.9101287 0.40318 -0.0954566 -0.9052903 0.3544424 -0.2341372 -0.9052935 0.3544365 -0.2341336 -0.86201 0.2681238 -0.4301727 -0.9524368 0.09634846 -0.2891043 -0.8491308 0.09114503 -0.5202592 -0.9692339 0.15729 -0.1893296 -0.9692332 0.157294 -0.1893297 -0.9828581 0.1789146 -0.04449445 -0.9828575 0.1789172 -0.04449373 -0.965253 0.2031111 0.1644163 -0.9774928 0.1224702 0.1717823 -0.9781616 0.1335395 0.159271 -0.7316257 0.2252248 -0.6434265 -0.73579 0.2209752 -0.640143 -0.8006224 0.355871 -0.4820371 -0.8246839 0.3341705 -0.4563187 -0.8559482 0.4417637 -0.268696 -0.8559471 0.441767 -0.268694 -0.854007 0.5025039 -0.1347666 -0.8540018 0.5025129 -0.1347656 -0.8189825 0.5704643 0.06195467 -0.8826974 0.4576973 0.1065775 -0.815238 0.4920225 0.3054519 -0.8152392 0.4920211 0.305451 -0.7420286 0.503086 0.4430553 -0.7581843 0.5137012 0.4015815 -0.6724563 0.05010104 -0.7384392 -0.6547372 0.0505194 -0.7541666 -0.7544363 0.1207297 -0.6451746 -0.7544374 0.1207327 -0.6451727 -0.8728826 0.2276285 -0.43158 -0.8907375 0.196033 -0.4100707 -0.9432716 0.2591484 -0.2075595 -0.9432713 0.25915 -0.2075586 -0.9533334 0.2947911 -0.06522035 -0.9533321 0.2947948 -0.06522172 -0.9317477 0.3346514 0.1409066 -0.9652535 0.2031076 0.1644173 -0.9039853 0.218339 0.3676123 -0.9039853 0.2183354 0.3676143 -0.8461772 0.2228043 0.4840891 -0.8405498 0.2067174 0.5007433 -0.8853127 0.2145953 -0.4125169 -0.8228296 0.5664829 -0.04526203 -0.9898003 0.01375436 -0.1417964 -0.9993757 0.001748323 -0.03528779 -0.9968264 -0.003523945 -0.07952982 -0.9950752 0.02718222 -0.09532284 -0.996825 0.01494514 -0.07820969 -0.95034 0.24247 -0.1950956 -0.9326441 0.2804381 -0.2270013 -0.932909 0.2962042 -0.2048026 -0.9502755 0.2421429 -0.1958147 -0.9499053 0.2423429 -0.1973574 -0.9554383 0.230154 -0.1848431 -0.8666235 0.4652171 -0.1803796 -0.8247256 0.5375111 -0.1758112 -0.8929876 0.4281221 -0.1388699 -0.8736696 0.4579332 -0.1643131 -0.6780628 0.7215224 0.14013 -0.6934801 0.7049691 0.148674 -0.723456 0.685409 0.08261913 -0.7235605 0.6861275 0.07542747 -0.726507 0.6865869 0.02803611 -0.7399462 0.6702153 0.05736875 -0.7028359 0.7086783 -0.06161993 -0.7533764 0.6572662 -0.02062064 -0.7497282 0.567843 0.3397971 -0.6558958 0.6814 0.3247997 -0.6874862 0.6683043 0.284134 -0.6876491 0.6843052 0.2426212 -0.7173536 0.6667067 0.2022526 -0.7144749 0.6708562 0.19869 -0.7127984 0.6733494 0.1962628 -0.7064768 0.480622 -0.5195123 -0.7567113 0.2935332 -0.5841458 -0.7606588 0.3043634 -0.5733771 -0.7676604 0.3577122 -0.5317326 -0.7423462 0.1012594 -0.6623206 -0.7418692 0.1494997 -0.6536666 -0.7291682 0.1815317 -0.6598183 -0.7592139 0.2182427 -0.6131595 -0.7597503 0.2788722 -0.5873754 -0.7225944 0.05537468 -0.6890509 -0.705844 0.03702431 -0.7073991 -0.7155516 0.0173282 -0.6983449 -0.9673689 0.1430681 -0.2091149 -0.9970099 0.02666962 -0.07252573 -0.996612 0.03103315 -0.0761674 -0.9653048 0.08377897 -0.2473211 -0.9625993 0.09700292 -0.2529688 -0.9625712 0.0526759 -0.2658609 -0.957974 0.07237607 -0.2775744 -0.9576817 0.0134989 -0.287513 -0.9421903 0.03547066 -0.3331956 -0.8643918 0.4645015 -0.1925237 -0.8648937 0.4543274 -0.2134145 -0.8859527 0.3983296 -0.2375319 -0.8860177 0.3843241 -0.25936 -0.8855347 0.3605204 -0.2930077 -0.8862911 0.3605527 -0.2906715 -0.8863521 0.3142458 -0.3400434 -0.962195 0.1849228 -0.199961 -0.9665949 0.1923841 -0.1693595 -0.9981219 -0.02100372 -0.05754566 -0.9975499 0.04043531 -0.05709046 -0.966722 0.1465728 -0.2096785 -0.8851646 0.2633722 -0.3835608 -0.8974866 0.2765606 -0.343558 -0.76196 0.4042662 -0.5059505 -0.764324 0.5018572 -0.4049053 -0.7537009 0.4988073 -0.4279325 -0.7752278 0.5444919 -0.3202352 -0.7628549 0.5481171 -0.3429579 -0.7553434 0.6236624 -0.2012501 -0.7338603 0.6401901 -0.2271691 -0.756445 0.6404997 -0.1324809 -0.9970812 0.03830808 -0.06604266 -0.9972816 0.03513032 -0.06477123 -0.9667309 0.1137153 -0.2291296 -0.9653457 0.1213454 -0.2310477 -0.8828164 0.210383 -0.4199692 -0.8825541 0.1539121 -0.4443075 -0.8871474 0.1395601 -0.4398778 -0.8702014 0.09972286 -0.4824987 -0.8696659 0.04407024 -0.4916696 -0.8445733 0.02003955 -0.5350649 -0.7794432 0.6216872 -0.07728779 -0.6785033 0.6189681 0.3956157 -0.6011181 0.7599678 0.2471964 -0.5353293 0.8138265 0.2260728 -0.5298732 0.84182 0.1028276 -0.5936321 0.7193695 0.3607059 -0.597903 0.7164011 0.3595576 -0.6254227 0.7291291 0.2778798 -0.7110387 0.6984298 0.08136212 -0.7226657 0.6782736 0.1330379 -0.6152348 0.7494314 0.2446195 -0.6170228 0.7465633 0.2488496 -0.6180422 0.7445998 0.2521806 -0.2097314 0.9777168 -0.009090125 -0.3131825 0.9457014 0.08698099 -0.3129117 0.9457428 0.08750361 -0.4303225 0.8919313 0.1388565 -0.3754196 0.8767864 0.3005091 -0.6915269 0.7204396 0.0525099 -0.7076284 0.7028567 0.07248806 -0.6840156 0.7210463 -0.1105214 -0.859051 0.4648995 -0.2142423 -0.8538792 0.4657258 -0.2323571 -0.8541837 0.4655398 -0.2316097 -0.8542358 0.4656545 -0.2311864 -0.8505969 0.4892206 -0.1927385 -0.8421958 0.508503 -0.1792513 -0.8012849 0.5827131 -0.1356024 -0.7861452 0.5987701 -0.1531347 -0.7984969 0.5909088 -0.1150203 -0.8581336 0.4599323 -0.2281868 -0.8645441 0.4603401 -0.2016197 -0.7326933 0.663191 -0.152769 -0.6756652 0.7350992 0.05572974 -0.1688356 0.4680939 -0.8673999 -0.409027 0.4491146 0.7943507 -0.3784565 0.9207239 -0.09507024 -0.1534121 0.9881033 -0.01080363 -0.8595789 0.5071548 -0.06259608 -0.6966373 0.7162276 0.04140657 -0.6863456 0.7271949 0.01083028 -0.6191667 0.7852243 0.007450759 -0.5985919 0.7989125 -0.05853801 -0.5645825 0.8236211 -0.05380612 -0.4475414 0.8904736 -0.08224147 -0.1659411 0.985218 0.04253262 -0.1449774 0.9878941 -0.05519795 0.258818 0 -0.9659262 0.2588229 0 -0.9659248 0.7071043 0 -0.7071093 0.707107 0 -0.7071066 0.9659259 0 -0.2588188 0.9659262 0 -0.2588175 -0.9659262 0 -0.2588175 -0.9659259 0 -0.2588188 -0.7071088 0 -0.7071049 -0.7071062 0 -0.7071075 -0.2588238 0 -0.9659246 -0.2588189 0 -0.9659259 0.3388367 0.9279187 0.1554241 0.5102915 0.8599926 0.003934264 0.9178755 0.39664 -0.01346921 0.9894358 0.1399273 -0.03791058 0.9836545 0.1797128 -0.0112769 0.7568873 0.6533278 -0.01687049 0.5060249 0.862215 -0.02289295 0.1743243 0.9843415 -0.02613449 0.1757231 0.9816299 0.0743255 0.1103038 0.983765 0.1415609 0.2101857 0.936937 -0.2792328 0.175776 0.9696412 -0.1699966 0.1743246 0.9843413 -0.02613592 0.2591973 0.8219993 -0.5070837 0.1753916 0.8686378 -0.4633643 0.1746485 0.9391542 -0.2957826 0.1756313 0.3061724 -0.9356347 0.174324 0.4650242 -0.8679654 0.1743233 0.4650227 -0.8679662 0.1757881 0.58214 -0.7938588 0.1971899 0.671795 -0.7140083 0.1745256 0.6813973 -0.7108013 0.1754617 0.8003417 -0.5732944 0.2857618 0.1759934 -0.9420014 0.1743243 0.2232827 -0.9590391 0.1749883 -2.22492e-4 -0.9845705 0.2401203 -0.03334438 -0.9701704 0.175697 -0.1293521 -0.9759091 0.1743243 -0.2886022 -0.9414457 0.1743229 -0.2886039 -0.9414454 0.1757628 -0.4266478 -0.8871749 0.2174037 -0.5189422 -0.8267011 0.1747223 -0.5394352 -0.8237002 0.1753472 -0.6816174 -0.710388 0.2584811 -0.708706 -0.6564476 0.1755 -0.7688893 -0.6148244 0.2840099 -0.9575482 -0.04939681 0.1744447 -0.8689957 -0.4630501 0.1883829 -0.8692772 -0.4570221 0.1757946 -0.9220052 -0.3449677 0.1743249 -0.9607536 -0.2157853 0.174323 -0.9607542 -0.2157844 0.175776 -0.97902 -0.103066 0.1112295 -0.992478 -0.05114281 0.9859274 -0.1669326 -0.008990883 0.9841605 -0.05195999 -0.1694945 0.9841606 -0.09425103 -0.150149 0.9841603 -0.09425395 -0.1501489 0.9841607 -0.1300576 -0.120469 0.9841604 -0.13006 -0.1204692 0.9841608 -0.1569132 -0.08249807 0.9841603 -0.1569163 -0.08249789 0.9841604 -0.1729717 -0.03884917 0.9841605 -0.1729714 -0.03884917 0.9844007 -0.1744445 -0.02290344 0.8755102 -0.4830363 -0.01256728 0.9844225 0.1740575 -0.02482932 0.9841607 0.1698942 -0.05063343 0.9841605 0.1698951 -0.05063354 0.9841606 0.1508796 -0.093077 0.9841603 0.1508823 -0.09307694 0.9841604 0.1214818 -0.1291145 0.9841603 0.1214826 -0.1291146 0.9841604 0.08372199 -0.1562659 0.9841605 0.08372092 -0.156266 0.9841604 0.0401988 -0.1726624 0.9841604 0.04019886 -0.1726624 0.9843907 0.008549869 -0.1757892 0.982034 -0.006481826 -0.1885929 0.9843215 -0.01461511 -0.1757774 0.9841605 -0.05195832 -0.1694952 0.5366995 0.8429096 -0.03817373 0.5358204 0.8091619 -0.2411505 0.5358229 0.8091598 -0.2411524 0.5358213 0.7185989 -0.4432959 0.5358228 0.7185966 -0.4432978 0.5358211 0.5785797 -0.614932 0.5358227 0.5785782 -0.6149321 0.5358218 0.3987393 -0.7442459 0.5358213 0.3987385 -0.7442468 0.5358228 0.1914573 -0.822337 0.5358213 0.1914562 -0.8223383 0.5358204 -0.02900302 -0.8438337 0.5358234 -0.02900224 -0.8438318 0.535822 -0.2474656 -0.8072519 0.5358234 -0.247465 -0.807251 0.5358222 -0.448897 -0.7151128 0.5358217 -0.4488973 -0.7151129 0.5358204 -0.619436 -0.5737558 0.5358227 -0.6194327 -0.5737572 0.5358211 -0.7473392 -0.392912 0.5358223 -0.7473375 -0.3929139 0.5358207 -0.8238094 -0.1850253 0.5358233 -0.8238074 -0.1850272 0.8420677 0.5352814 -0.06630194 0.8400818 0.5198639 -0.1549334 0.8400819 0.5198636 -0.1549336 0.8400821 0.4616795 -0.2848058 0.8400821 0.4616789 -0.2848066 0.840082 0.3717206 -0.3950773 0.8400821 0.3717208 -0.3950771 0.8400815 0.2561794 -0.4781583 0.8400822 0.2561784 -0.4781574 0.8400819 0.1230057 -0.5283294 0.8400819 0.1230064 -0.5283293 0.8400824 -0.01863342 -0.5421389 0.8400819 -0.01863288 -0.5421395 0.8400809 -0.1589905 -0.5186389 0.8400818 -0.1589902 -0.5186374 0.8400817 -0.2884047 -0.4594406 0.8400818 -0.2884035 -0.459441 0.840082 -0.3979689 -0.3686231 0.8400822 -0.3979687 -0.3686231 0.840082 -0.4801442 -0.2524356 0.8400811 -0.4801461 -0.2524352 0.8400816 -0.5292747 -0.1188747 0.8400818 -0.5292746 -0.1188741 0.8410408 -0.5315226 -0.1006686 0.5327955 -0.8426373 0.07804787 0.647681 -0.7245646 -0.2356173 0.4408096 -0.8964087 -0.04624295 1.5545e-6 0.2589223 -0.9658982 -0.037817 0.1563229 -0.9869819 -0.01509428 0.1253144 -0.9920023 0 0.02068012 -0.9997861 3.37384e-6 0.5532345 -0.8330256 -0.03212922 0.4537557 -0.8905467 -0.02456849 0.4449999 -0.8951935 -8.70418e-7 0.3384515 -0.9409838 6.23156e-6 0.7848929 -0.6196315 -0.02881681 0.7068133 -0.706813 -0.02556079 0.7036705 -0.7100666 -2.3271e-6 0.6144028 -0.7889926 0 0.9998396 -0.01791459 -0.008763194 0.9928724 -0.1188604 -0.02878987 0.9872791 -0.1563689 0.008259475 0.9584928 -0.284997 -0.01991617 0.8908298 -0.4539006 -0.03470396 0.8997818 -0.434958 -6.77757e-6 0.8344846 -0.5510313 -0.8588765 0.4599323 -0.225374 -0.9795595 0.1749552 -0.09926694 -0.6797285 0.7281715 -0.08795171 -0.8874378 0.4597237 -0.03329354 -0.8129072 0.5739939 -0.09855473 -0.9327141 0.3564178 -0.05487221 -0.5476932 0.8337961 -0.06939983 -0.7759395 0.6302996 -0.02530664 -0.1151562 0.9933252 -0.006647169 -0.5192062 0.8530003 -0.05306243 -0.3382834 0.9408477 -0.01923435 -0.3570775 0.9339215 -0.01692432 -0.1756796 0.9839256 -0.03205102 -0.9479805 0.3151326 -0.04499393 -0.9416778 0.316346 -0.1147531 -0.8040307 0.5735934 -0.1566055 -0.7361767 0.6629903 -0.1359695 -0.6727324 0.7277126 -0.1336622 -0.5913347 0.8007639 -0.09539693 -0.5121096 0.8528552 -0.1018923 -0.3845078 0.9206811 -0.06708341 -0.3312961 0.9410428 -0.06842225 -0.1519744 0.9882264 -0.01767623 -0.1242642 0.9920122 -0.02168428 -0.984427 0.1757937 -8.96098e-6 -0.9844219 0.1758232 0 -0.9340409 0.3571662 0 -0.9053872 0.4245843 -0.001541435 -0.1757703 0.9844312 8.62417e-6 -0.1757969 0.9844265 0 -0.3571285 0.9340553 0 -0.4245929 0.9053831 -0.001540899 -0.548936 0.8356896 0.01709824 -0.6087664 0.7933496 2.17786e-6 -0.7933498 0.6087662 0 -0.776169 0.6304918 -0.006468117 -0.887915 0.4599932 0.003629386 -1 -1.42295e-6 0 -1 6.90578e-7 0 -1 4.02302e-7 0 -1 1.74422e-7 0 -1 -1.73079e-7 0 -1 -3.87321e-7 0 -1 -6.69362e-7 0 4.59097e-5 -0.998675 -0.051463 -0.0423851 -0.98136 -0.1874465 -0.006240367 -0.9756744 -0.2191358 0 -0.9365872 -0.3504348 0 -0.8825277 -0.4702605 -0.06075543 -0.8517236 -0.5204571 0 -0.7810106 -0.6245177 0 -0.1313953 -0.9913302 -0.04623562 -0.2927779 -0.9550621 -0.02609461 -0.2787334 -0.9600139 0 -0.4333935 -0.9012048 0 -0.6071177 -0.7946119 -0.109071 -0.5445923 -0.8315786 0 -0.692345 -0.7215667 0 -2.25955e-4 -1 -0.06974065 0.08695667 -0.993768 0 0.1836516 -0.9829914 -0.01340603 0.4413375 -0.8972411 -0.06313306 0.4713128 -0.8797037 0 0.3110061 -0.9504081 -0.06271058 0.7344464 -0.6757632 0 0.6920174 -0.7218808 0 0.5913441 -0.8064194 -0.06538498 0.928898 -0.364518 0 0.8823146 -0.47066 0 0.8129536 -0.5823286 0 0.9898051 0.1424291 -0.05249762 0.9982693 -0.02650457 -0.02144628 0.9997616 -0.004098892 0 0.984975 -0.1726971 0 0.9538136 -0.3003994 0.2435727 -0.8934546 -0.3773744 0.2184291 -0.9028088 -0.3704389 0.1961457 -0.9130676 -0.3575392 0.296548 -0.8795456 -0.3721005 0.3429353 -0.8745242 -0.3429328 0.3575379 -0.9130679 -0.1961476 0.3704387 -0.9028099 -0.2184254 0.3773709 -0.8934549 -0.2435769 0.2654375 -0.951155 -0.1576297 0.2919954 -0.9432458 -0.1581969 0.3171411 -0.933892 -0.1651286 0.1651288 -0.9338925 -0.3171393 0.158196 -0.9432458 -0.2919957 0.1780303 -0.9236327 -0.3394231 -0.05592322 -0.9743247 -0.2180917 0.41554 -0.809109 -0.4155347 0.6344791 -0.7618686 0.1303561 0.4064596 -0.629853 0.661873 -0.3711382 -0.9256905 0.07316797 -0.3799323 -0.9232509 0.05709058 -0.3187609 -0.9318283 0.1734574 -0.3300762 -0.9339427 0.1371158 -0.3333547 -0.935932 0.1136045 -0.3331829 -0.9366389 0.1081519 -0.3506443 -0.9315996 0.09576392 -0.3613977 -0.9285745 0.08450466 -0.2836942 -0.9336963 0.2184693 -0.2424601 -0.9393755 0.2424597 -0.2387402 -0.934858 0.2627614 -0.134288 -0.9186125 0.3716421 -0.1603834 -0.9194242 0.3590771 -0.2091498 -0.9254302 0.3159675 -0.06074178 -0.8185768 0.5711765 -0.1402919 -0.8274877 0.5436748 -0.1566282 -0.8567451 0.4913814 0.005921483 -0.7604297 0.6493933 0.04852735 -0.7342323 0.6771618 0.7274867 -0.6551269 0.2038917 0.5768278 -0.7463759 0.3319529 0.6245864 -0.7020117 0.3421571 0.4610017 -0.765993 0.4480315 0.4956483 -0.7419233 0.4515336 0.4664741 -0.7518852 0.4659084 0.3386753 -0.7972223 0.4997358 0.3721026 -0.8795437 -0.296551 0.5002778 -0.8020637 -0.3262147 0.5474545 -0.8122774 -0.2012435 0.3212949 -0.8757981 -0.3602045 0.3766601 -0.8036953 -0.4606531 0.4112453 -0.8032674 -0.4308582 0.2701323 -0.885545 -0.3779401 0.1538286 -0.8614413 -0.4839997 0.2076112 -0.8445696 -0.4935586 0.2109997 -0.8452381 -0.4909701 0.2515648 -0.8276853 -0.5016496 0.2667774 -0.8311257 -0.4879139 0.2978646 -0.8145681 -0.4977505 0.3208189 -0.8192756 -0.4752503 0.3428028 -0.8063924 -0.4818897 0.3781969 -0.8103163 -0.4476099 0.007210791 -0.948814 -0.3157534 0.00598526 -0.9335827 -0.3583123 0.03868865 -0.9290186 -0.368005 0.06153255 -0.9075662 -0.4153763 0.06870603 -0.9072592 -0.4149221 0.09725832 -0.8909364 -0.4435911 0.1156736 -0.8878283 -0.4453995 0.1207844 -0.8746511 -0.4694644 0.1692335 -0.8637007 -0.4747433 -0.2505199 -0.9612361 -0.1151741 -0.173792 -0.9664046 -0.1893637 -0.06132847 -0.9771277 -0.2036185 -0.06770944 -0.9666267 -0.2470797 0.157629 -0.9511554 -0.265437 -0.0185967 -0.9952064 -0.09601324 -0.0185973 -0.9952062 -0.0960142 0.03227543 -0.9989578 -0.03227519 0.2467342 -0.9664906 0.07083904 0.2467333 -0.9664908 0.07083898 0.3249593 -0.9431949 0.06917279 0.3249592 -0.9431949 0.06917423 0.3990367 -0.9156383 0.0487461 0.3990364 -0.9156385 0.04874593 0.4646706 -0.8854184 0.01074475 0.3779382 -0.8855469 -0.2701287 0.5673531 -0.7808562 -0.2614845 0.5612686 -0.8060634 -0.1877215 0.5661641 -0.8117232 -0.143401 0.5560368 -0.8240783 -0.1082498 0.5560365 -0.8240783 -0.1082514 0.518034 -0.8542975 -0.04262119 0.5024305 -0.7721472 -0.3890402 0.5078207 -0.7620126 -0.4018148 0.3602077 -0.8757964 -0.3212959 -0.2111808 -0.9770726 0.02705574 -0.2111814 -0.9770725 0.02705568 -0.1294527 -0.9830992 0.1294524 -0.1294529 -0.9830992 0.1294529 -0.02705574 -0.9770724 0.2111811 0.5652062 -0.8006955 0.1985669 0.565207 -0.8006948 0.1985675 0.4597678 -0.849242 0.2596182 0.4597681 -0.8492421 0.2596176 0.3407574 -0.8935135 0.292435 0.3407555 -0.8935143 0.2924343 0.2150846 -0.9309396 0.2951106 0.1689109 -0.9841703 0.05364704 0.239018 -0.957157 -0.1634657 -0.02616035 -0.7884826 0.6145005 -0.04184466 -0.819688 0.5712798 0.006726741 -0.8843856 0.4667088 -0.1119515 -0.9047746 0.4109134 -0.1155418 -0.9060439 0.4071054 0.03062319 -0.8148344 0.5788845 0.1153598 -0.7046217 0.7001432 0.1722739 -0.8467773 0.5032793 0.006727159 -0.8843856 0.4667088 0.09005928 -0.9593423 0.2674914 -0.02705633 -0.9770725 0.2111808 0.09601229 -0.9952065 0.01859658 0.03227543 -0.9989578 -0.03227502 0.1926346 -0.9621765 -0.1926354 0.1753638 -0.9609032 -0.2142725 -0.4126424 -0.9103689 -0.03090202 -0.1281997 -0.9913567 0.02787125 -0.2674924 -0.9593421 -0.09005904 -0.05364757 -0.9841704 -0.1689106 -0.0536465 -0.9841704 -0.1689104 0.1634675 -0.9571562 -0.2390198 0.1111201 -0.9274881 0.356957 0.3129628 -0.6276289 0.7128368 0.3386757 -0.7972227 0.4997349 0.1722728 -0.8467774 0.5032794 0.2150846 -0.9309394 0.2951112 0.09005939 -0.9593421 0.2674926 0.1689107 -0.9841704 0.05364692 0.09601426 -0.9952062 0.01859718 0.2142761 -0.9609022 -0.1753648 0.6973686 -0.7013733 -0.1474878 0.6737859 -0.7387449 0.01639014 0.7013344 -0.7128309 -0.001478672 0.6408063 -0.7612107 0.09962791 0.5180337 -0.8542978 -0.04262101 0.4646671 -0.8854204 0.01074582 0.339421 -0.9236334 -0.17803 0.6647089 -0.7396463 -0.1052883 0.5756399 -0.7837679 -0.2331237 0.5925508 -0.7736296 -0.2244566 0.6538925 -0.736266 -0.1741755 0.4335308 -0.8038967 -0.4071871 0.4493315 -0.8054761 -0.3864058 0.4701662 -0.8080522 -0.3549585 0.4881647 -0.8010659 -0.346394 0.5571427 -0.7821693 -0.2789324 4.01001e-6 0 -1 -7.16974e-4 0 -0.9999998 8.93975e-5 0 -1 0.01941376 0 -0.9998115 0.01723879 0 -0.9998515 3.462e-4 0 -1 -0.003903985 0 -0.9999924 -0.0499376 0 -0.9987524 -4.36279e-4 0 -1 0.1203314 0 -0.9927338 -0.004496812 0 -0.9999899 0.1366374 0 0.9906212 -0.01231938 0 -0.9999242 -0.1267148 0 0.9919393 0.008781194 0 -0.9999615 0.063115 0 0.9980063 0.01355803 0 -0.9999082 0.04415577 0 0.9990248 -0.01413285 0 -0.9999002 9.20132e-4 0 -0.9999997 -0.0144912 0 -0.9998951 0.07124704 0 -0.9974587 0.00526303 0 -0.9999862 0.006908297 0 -0.9999762 -0.01514977 0 -0.9998853 -0.01886457 0 -0.999822 0.02939903 0 -0.9995678 -0.01418292 0 -0.9998995 0.01709151 0 -0.999854 0.0192272 0 -0.9998152 0.009132027 0 -0.9999583 -0.01550197 0 -0.9998798 -0.01960402 0 -0.9998079 0.0338788 0 -0.999426 -0.01298588 0 -0.9999158 0.001373589 0 -0.9999991 -8.96338e-5 0 -1 0.008196413 0 -0.9999665 -0.09950369 0 -0.9950373 0.002747237 0 -0.9999963 -0.1269641 0 0.9919073 0.01550197 0 -0.9998798 0.01999598 0 -0.9998001 -0.03701162 0 -0.9993149 -6.31273e-5 0 -1 -0.02499216 0 -0.9996877 -0.0475651 0 -0.9988682 0.02563256 0 -0.9996715 -0.02701711 0 -0.999635 -3.55366e-4 0 -1 0.1950864 0.980786 -3.30195e-7 0.1950741 0.9807886 0 0.1950849 0.9807865 2.17913e-5 0.1950807 0.9807872 0 0.6900724 0.7237228 0.005043625 0.6888524 0.7248844 0.005001664 0.6828529 0.7305403 0.004781961 0.6752436 0.7375811 0.004509389 0.6710639 0.7413867 0.004362761 0.6630651 0.7485505 0.004102289 0.6616101 0.7498371 0.004054963 0.6555804 0.7551156 0.003858864 0.6434015 0.7655211 0.003483116 0.633518 0.7737213 0.003210425 0.6256767 0.7800768 0.002987504 0.6241436 0.7813042 0.002944707 0.6159307 0.7877956 0.002737224 0.6143178 0.7890542 0.002695381 0.6081783 0.7937965 0.002536118 0.6006332 0.7995213 0.002359509 0.5755943 0.8177334 0.001795291 0.5545566 0.8321449 0.001424908 0.5463789 0.8375371 0.001284062 0.5442178 0.8389431 0.001249432 0.5362009 0.8440898 0.001118838 0.5339906 0.8454898 0.001087486 0.5272789 0.8496918 9.89166e-4 0.5185651 0.8550378 8.68158e-4 0.5128043 0.8585052 7.96546e-4 0.5062844 0.8623664 7.13281e-4 0.5007523 0.8655905 6.51298e-4 0.4956346 0.868531 5.92654e-4 0.4821956 0.8760635 4.51609e-4 0.4275501 0.9039917 0 0.9140965 0.4054657 0.005020916 0.9143168 0.4049684 0.005028367 0.9104866 0.4135112 0.004781007 0.9059228 0.4234188 0.004498839 0.9037402 0.4280588 0.004378557 0.8989282 0.4380769 0.004083216 0.8985897 0.4387711 0.004074752 0.8945448 0.4469615 0.003859698 0.8873103 0.4611598 0.003479838 0.8819168 0.471394 0.003225088 0.8760312 0.4822454 0.002967953 0.8759813 0.482336 0.002965569 0.8701183 0.4928353 0.002717494 0.8700283 0.4929944 0.002714216 0.8655803 0.5007638 0.002535641 0.8607879 0.5089587 0.002359151 0.8448472 0.5350049 0.001799523 0.7729602 0.6344546 -1.19599e-6 0.6087609 0.7933537 -1.00474e-6 0.7065445 0.7076641 0.002539575 0.4422879 0.8968656 -0.003673315 0.698758 0.7153379 0.005382418 0.6979388 0.7161375 0.005342483 0.980785 0.1950921 -1.49719e-6 0.9999745 0.004476606 0.005579888 0.9997856 0.02006125 0.005144476 0.999567 0.0290153 0.004903495 0.998995 0.04459822 0.004497408 0.9985646 0.05339127 0.004269063 0.9977016 0.06764727 0.003929674 0.9962347 0.08662772 0.003477215 0.9947476 0.1023102 0.003130733 0.9929861 0.1181983 0.00280416 0.9919176 0.126857 0.002626299 0.9900872 0.1404346 0.002360641 0.9851993 0.1714038 0.00179249 0.9799273 0.1993511 0.001373887 0.9766184 0.2149773 0.001158833 0.9747275 0.2233952 0.001046478 0.9711737 0.2383718 8.6056e-4 0.9688637 0.2475934 7.60261e-4 0.9654315 0.2606565 6.20419e-4 0.9604227 0.2785463 4.5142e-4 0.9414799 0.3370692 -1.41726e-6 0.8968685 0.4422973 -1.36716e-6 0.9237655 0.3829582 6.40514e-4 0.7933562 0.6087552 -0.001796305 0.919009 0.3942001 0.005359053 0.9192329 0.3936779 0.005365431 0.7924786 0.6081078 0.04671835 0.9643605 0.2583975 0.05691581 0.6083725 0.7928453 0.03576815 0.2587884 0.9658142 0.01521503 0.964345 0.2584702 0.05685043 0.9531226 0.2585051 0.1572657 0.9531101 0.2585926 0.1571978 0.944763 0.2588286 0.2010738 0.9390121 0.2557805 0.2298537 0.7100333 0.7040475 -0.01303619 0.6981293 0.7066522 0.1151443 0.6980345 0.7067678 0.1150095 0.6870199 0.7069106 0.16817 0.6869513 0.7069998 0.168075 0.682016 0.7071041 0.1867032 0.6821068 0.7069956 0.1867823 0.6937816 0.706744 0.1384923 0.6939597 0.7065269 0.1387073 0.9782034 0.194578 0.07250905 0.960407 0.2586902 0.1034303 0.9513474 0.2586771 0.1674047 0.9413515 0.2802609 0.187913 0.9416557 0.2587819 0.2152128 0.9316678 0.2587407 0.2550458 0.9316538 0.2588226 0.2550142 0.9377429 0.2587599 0.2316927 0.894888 0.4413205 0.06642037 0.7919833 0.6077065 0.05878293 0.7004539 0.7071051 0.09678125 0.6081379 0.792537 0.04531675 0.4420379 0.8963915 0.03293913 0.2587301 0.9658308 0.01516193 0.2556793 0.9658434 0.04212623 0.2556132 0.9658637 0.04206258 0.2515301 0.965891 0.06154125 0.2514843 0.965906 0.06149405 0.2496295 0.9659258 0.06835627 0.2496958 0.9659054 0.06840193 0.2540374 0.9658607 0.05077546 0.2541766 0.9658175 0.05090248 0.253652 0.9657582 0.05451536 0.1950666 0.9806809 0.01462835 0.9686749 0 0.2483324 0.9686686 0 0.248357 0.7297576 0 0.6837061 0.7297097 0 0.6837572 0.310906 0 0.9504407 0.3108135 0 0.950471 -0.1848458 0 0.9827677 -0.6348391 0 0.7726444 0.595421 0 0.803414 0.1463466 0 0.9892334 -0.3370844 0 0.9414745 -0.3369916 0 0.9415076 -0.7410374 0 0.6714637 -0.7409902 0 0.6715158 -0.9700455 0 0.2429235 0.9700452 0 0.2429247 0.7409982 0 0.6715071 0.7410454 0 0.671455 0.3369882 0 0.941509 0.3370809 0 0.9414757 -0.146348 0 0.9892331 -0.5954151 0 0.8034183 0.6348367 0 0.7726464 0.184849 0 0.9827671 -0.3108121 0 0.9504715 -0.3109046 0 0.9504413 -0.7297043 0 0.6837629 -0.7297522 0 0.6837118 -0.9686712 0 0.2483469 -0.9686775 0 0.2483223 0.9517472 0.2694581 0.146866 0.9260407 0.3386032 0.1667226 0.9335886 0.3189656 0.1633201 0.9410372 0.299186 0.1579135 0.9774184 0.1890993 0.09431248 0.9800835 0.1575801 0.1208517 0.9812287 0.1365141 0.1362136 0.9820137 0.1155021 0.1493604 0.9825364 0.09451508 0.1602778 0.9828459 0.06301516 0.1733297 0.9831771 0.03156119 0.1799077 0.9831001 9.60542e-4 0.1830664 0.7703548 0.6257021 0.1226807 0.7528311 0.6458215 0.1271227 0.7103232 0.6920194 0.1286475 0.7246377 0.6768289 0.1296264 0.7388237 0.661413 0.1291216 0.79913 0.5906618 0.1118476 0.832419 0.5478081 0.08357715 0.844537 0.5307584 0.07108414 0.8569609 0.5015665 0.1185287 0.8744446 0.4637042 0.1425662 0.8909095 0.4255043 0.1588284 0.9029188 0.3967502 0.165309 0.9107201 0.3774497 0.1676926 0.9184178 0.3580864 0.1681759 0.6663078 0.7364562 0.1169031 0.6811766 0.7218351 0.122281 0.6958407 0.7070201 0.1262075 0.6202583 0.7790086 0.0917887 0.6359207 0.7650291 0.1016635 0.6512162 0.7508753 0.110018 0.5716578 0.8192047 0.04594802 0.5890284 0.807241 0.03751844 0.6061153 0.7948831 0.02802026 0.5203306 0.8515579 0.06407183 0.5333185 0.843753 0.06043398 0.5540332 0.8307898 0.05325227 0.3915154 0.9175081 0.06996327 0.4058752 0.911093 0.07193744 0.4248865 0.9022607 0.07346546 0.4390246 0.895439 0.07380008 0.4484149 0.8907784 0.07374292 0.4624591 0.8836101 0.07324481 0.4764705 0.8762434 0.07192677 0.4857109 0.8712504 0.07076561 0.4995538 0.8635619 0.06860631 0.1092074 0.99383 0.01938331 0.2582423 0.9659604 -0.01521831 0.3184856 0.9465034 0.05194598 0.3430786 0.9374322 0.05931341 0.3528999 0.9336031 0.06202536 0.3625932 0.9297186 0.06441706 0.3722751 0.9257352 0.06652438 0.3819152 0.9216619 0.06841218 0.2044771 0.9788528 0.006034076 0.1721941 0.9802019 0.09774202 0.1721934 0.9802022 0.09774041 0.1282296 0.9802027 0.1508635 0.1282315 0.9802023 0.1508648 0.06871771 0.9802024 0.1856914 0.06871658 0.9802024 0.1856915 0.5649912 0.8233874 0.05308705 0.4883006 0.8274881 0.2771754 0.4883066 0.8274847 0.277175 0.3636338 0.8274883 0.4278243 0.3636443 0.8274839 0.427824 0.1948738 0.827483 0.5265892 0.1948711 0.8274871 0.5265836 -0.1949734 0.9802024 0.03447794 -0.1949757 0.980202 0.03447741 -0.5529117 0.8274838 0.09777134 -0.5529043 0.8274888 0.09777194 -0.822629 0.549656 0.1454647 -0.8226246 0.5496625 0.1454651 -0.9663599 0.19222 0.1708804 -0.1269007 0.9802022 0.1519864 -0.1269008 0.9802024 0.1519856 -0.3598672 0.8274852 0.4310034 -0.3598676 0.8274853 0.4310031 -0.5354176 0.5496594 0.6412508 -0.5354133 0.5496606 0.6412534 -0.06708317 0.9802023 0.1862884 -0.06708109 0.9802025 0.1862882 -0.190231 0.8274863 0.5282789 -0.1902471 0.8274827 0.5282788 -0.2830342 0.5496608 0.7859801 -0.2830542 0.5496588 0.7859742 0.8350068 0.5440958 0.08199715 0.7265099 0.5496578 0.4123831 0.7265029 0.5496629 0.4123885 0.5410336 0.5496567 0.636522 0.541034 0.5496597 0.636519 0.2899257 0.5496625 0.7834631 0.2899205 0.5496612 0.7834659 -0.8117784 0.1395362 0.5670499 -0.8896617 0.1944301 0.4131577 -0.9663603 0.1922184 0.1708797 -0.3324823 0.1922193 0.9233133 -0.6289735 0.1922174 0.7532894 -0.6289727 0.1922172 0.7532902 -0.8491509 0.1922216 0.4919285 -0.7228597 0.5496559 0.4187508 -0.7228468 0.5496671 0.4187585 -0.4858475 0.8274871 0.2814557 -0.4858498 0.8274862 0.2814548 -0.1713279 0.9802021 0.09925049 -0.1713253 0.9802026 0.09925043 0.08251285 0.1431175 0.9862602 -0.08975589 0.1945018 0.976787 -0.3324699 0.1922215 0.9233172 8.68053e-4 0.9802025 0.1979959 8.72814e-4 0.9802022 0.1979971 0.002474844 0.8274835 0.5614848 0.002463936 0.8274876 0.5614786 0.003697097 0.5496609 0.8353797 0.003679096 0.5496608 0.8353798 0.004319429 0.1922189 0.9813426 0.3406128 0.1922169 0.9203454 0.3405777 0.192218 0.9203582 0.635565 0.1922173 0.7477363 0.6355449 0.1922208 0.7477526 0.9653306 0.2295496 0.1242743 0.977383 0.1894587 0.09395766 0.8534443 0.192224 0.4844408 0.8937663 0.1466897 0.4238679 0.7995479 0.1945821 0.5682086 -0.2899202 0.5496646 0.7834637 -0.1948714 0.8274855 0.5265862 -0.06871652 0.9802026 0.1856905 -0.70512 0.6974492 0.1279472 -0.3688521 0.9271545 0.0658245 -0.1757408 0.9839422 0.03119248 -0.1998363 0.9796339 0.01957046 -0.3466941 0.9360311 0.06040745 -0.359401 0.9310091 0.06366336 -0.6905936 0.7123649 0.1249673 -0.6758385 0.7271303 0.1205151 -0.6607892 0.7417804 0.114541 -0.6454818 0.7562357 0.107055 -0.629935 0.7704358 0.0980339 -0.564333 0.8236781 0.05552232 -0.6166449 0.7869477 0.02150934 -0.6003918 0.7990921 0.03133314 -0.5839771 0.8107791 0.04010087 -0.5673493 0.8220881 0.04781448 -0.5505473 0.8330206 0.05453866 -0.533559 0.8436137 0.06025624 -0.5163994 0.8538799 0.0649687 -0.4991062 0.8638153 0.06867432 -0.4728089 0.8781568 0.07274913 -0.4462168 0.8918713 0.07386684 -0.4263231 0.9015732 0.07358306 -0.4124234 0.9080911 0.07264691 -0.3964219 0.9153445 0.07066959 -0.3835152 0.9209728 0.06874006 -0.3818098 0.9217036 0.06843703 -0.9001207 0.4035927 0.1639997 -0.892204 0.4227088 0.1590268 -0.8840304 0.441983 0.1521234 -0.8757902 0.4609286 0.1433056 -0.8671084 0.4801813 0.1324737 -0.8339961 0.5447468 0.0877583 -0.8634054 0.5022627 0.04757523 -0.8518596 0.5200125 0.06262987 -0.8398352 0.5374684 0.07618761 -0.8273862 0.5546668 0.08818626 -0.8146535 0.5715014 0.09862017 -0.8017066 0.5879707 0.1075038 -0.7884848 0.6042296 0.1148843 -0.7750852 0.6202128 0.1207444 -0.7614219 0.6360638 0.1251391 -0.7476496 0.6516343 0.1280354 -0.7265707 0.6746482 0.1301721 -0.9648408 0.1927487 0.1786903 -0.9931474 0.1103147 0.03858667 -0.9554049 0.2578433 0.143939 -0.9342733 0.316854 0.1635144 -0.9193193 0.3554835 0.1687706 -0.9079572 0.3843264 0.1670543 -0.06871753 0.9802025 0.1856904 -8.69952e-4 0.9802021 0.1979977 -8.70351e-4 0.9802021 0.1979979 0.06708121 0.9802027 0.1862874 0.06708353 0.980202 0.1862901 0.1269007 0.9802025 0.1519849 0.1269009 0.9802021 0.1519869 0.1713255 0.9802025 0.09925049 0.1713276 0.9802021 0.09925031 0.1949734 0.9802024 0.03447794 0.1949757 0.980202 0.03447741 -0.1948725 0.8274856 0.5265855 -0.002465009 0.8274862 0.5614807 -0.002477109 0.8274836 0.5614845 0.190237 0.8274838 0.5282807 0.1902396 0.8274863 0.5282759 0.3598666 0.8274856 0.431003 0.3598684 0.8274857 0.4310015 0.4858493 0.8274863 0.2814551 0.4858468 0.8274877 0.2814553 0.5529046 0.8274885 0.09777152 0.5529127 0.8274832 0.09777104 -0.1721938 0.9802021 0.09774059 -0.1721942 0.980202 0.09774082 -0.4883019 0.8274877 0.2771742 -0.4883073 0.8274847 0.2771738 -0.7265117 0.5496555 0.4123829 -0.7264993 0.5496675 0.4123888 -0.853444 0.1922215 0.4844424 -0.2899265 0.5496584 0.7834655 -0.003697097 0.5496611 0.8353797 -0.003679096 0.5496603 0.8353801 0.283046 0.5496599 0.7859765 0.2830398 0.5496585 0.7859798 0.5354188 0.549657 0.6412518 0.5354128 0.5496631 0.6412518 0.7228519 0.5496639 0.4187539 0.7228539 0.5496591 0.4187567 0.822629 0.5496561 0.1454639 0.8226237 0.5496633 0.145466 -0.5796803 0.1433751 0.8021311 -0.7041894 0.1945068 0.6828502 -0.8534539 0.1922149 0.4844275 0.2082693 0.1949143 0.9584531 -0.004288315 0.1922202 0.9813424 -0.004319429 0.1922184 0.9813427 -0.3405939 0.1922184 0.9203521 -0.3405979 0.1922176 0.9203507 -0.6355647 0.1922156 0.7477371 -0.5410317 0.5496599 0.6365208 -0.5410345 0.5496567 0.6365212 -0.3636465 0.8274824 0.427825 -0.3636352 0.8274871 0.4278255 -0.1282318 0.9802022 0.1508651 -0.12823 0.9802026 0.150864 0.3740343 0.1655731 0.9125152 0.3324825 0.192218 0.9233135 0.5810858 0.1938791 0.7904115 0.6316751 0.1690914 0.7565677 0.7097159 0.1947226 0.6770425 0.8491507 0.1922257 0.4919273 0.8491534 0.1922231 0.4919236 0.96636 0.192219 0.1708805 0.9663601 0.1922187 0.1708806 -0.02159464 -0.714405 0.6993992 -0.3407449 -0.9212164 0.1877589 -0.3519468 -0.9238991 0.1501466 -0.1824133 -0.9348865 0.3044877 -0.2180981 -0.9465247 0.2377483 -0.2285748 -0.9388179 0.2576327 -0.2554657 -0.9461141 0.1990112 -0.2820843 -0.9352306 0.2139447 -0.286573 -0.9417013 0.1762804 0.02943307 -0.8396217 0.5423735 -0.02015888 -0.8892955 0.4568885 -0.009754478 -0.8674491 0.4974305 -0.05826371 -0.9089483 0.4128176 -0.04980683 -0.8910067 0.4512498 -0.09747809 -0.9246137 0.3682222 -0.0927844 -0.9109493 0.4019485 -0.1338339 -0.9334829 0.3327136 -0.1284763 -0.9281849 0.3492375 -0.1622018 -0.9370076 0.3093663 -0.1792137 -0.9431505 0.2799103 0.07738554 -0.8603463 0.5038013 0.03618478 -0.8240964 0.5652927 0.09173876 -0.7529268 0.6516789 0.04111349 -0.8039436 0.5932828 -0.03872734 -0.7467302 0.6639987 -0.3181002 -0.9242206 0.2112548 -0.305113 -0.9237508 0.2314968 -0.3076804 -0.9249538 0.2231445 -0.2714573 -0.9204145 0.2813327 -0.2740958 -0.9221822 0.2728581 -0.2380912 -0.912999 0.3312787 -0.2407669 -0.9153506 0.3227455 -0.2050261 -0.901454 0.3812414 -0.2077013 -0.9044006 0.3727196 -0.1711282 -0.8850085 0.432984 -0.1735983 -0.888629 0.4245023 -0.1380406 -0.8642914 0.4836789 -0.1406228 -0.868434 0.4754446 -0.1073226 -0.8404603 0.5311387 -0.1098067 -0.8451377 0.523149 -0.07754808 -0.8127731 0.5773963 -0.07989019 -0.8179373 0.5697336 -0.04874545 -0.7812095 0.622363 -0.05090838 -0.7868067 0.6150965 0.02692633 -0.6723487 0.7397447 -0.0163989 -0.9455242 0.3251388 -0.4325055 -0.8989545 0.06942665 -0.4216388 -0.904547 0.06336915 -0.4204281 -0.90549 0.05769002 -0.4128825 -0.9067161 0.08598887 -0.4124249 -0.9074593 0.08014708 -0.405065 -0.9087538 0.100444 -0.4072173 -0.9085891 0.09295147 -0.3982397 -0.9099116 0.1160436 -0.3990817 -0.9108474 0.1053132 -0.3826474 -0.9132741 0.1396829 -0.3861923 -0.914242 0.1225439 -0.3654801 -0.9170864 0.1593009 -0.3744688 -0.9173948 0.1347597 -0.421637 -0.9047693 0.06012338 -0.4278689 -0.9014189 0.06612318 -0.432733 -0.8994413 0.06121784 0.9438065 0.2588126 -0.205537 0.7042542 0.5913096 -0.392911 0.5915892 0.7932255 -0.1442767 0.9773495 0.1959188 0.08002364 0.9566164 0.1938192 -0.2175296 0.9549389 0.1962307 -0.2226774 0.9545564 0.1876084 -0.2315713 0.9503623 0.1834955 -0.2512788 0.9526292 0.1793768 -0.2456045 0.9475412 0.1695261 -0.2709733 0.9507876 0.1651107 -0.2621862 0.8138837 0.5533868 -0.177078 0.7996982 0.5505529 -0.2395298 0.808948 0.5407902 -0.2305412 0.7900714 0.5220103 -0.3213912 0.7995631 0.5140007 -0.3106482 0.7828701 0.4818043 -0.3936738 0.7929607 0.4753876 -0.3810773 0.513846 0.8189457 -0.2555197 0.5241914 0.8234716 -0.2170667 0.5450102 0.8129942 -0.2049501 0.5158327 0.7841604 -0.3449771 0.5357264 0.7765324 -0.3316545 0.5095726 0.7261494 -0.4615658 0.528686 0.7211608 -0.447681 0.1753222 0.8105301 -0.5588409 0.1944086 0.8700319 -0.453045 0.1663235 0.8689846 -0.4660496 0.1986826 0.9312385 -0.3054834 0.1679436 0.9325562 -0.3195844 0.2037248 0.9676932 -0.1485465 0.1705034 0.9718058 -0.1628563 0.195733 0.9794893 -0.04784864 0.2850219 0.9516934 0.1142033 0.1855042 0.759493 -0.6235052 0.2115392 0.771611 -0.5998896 0.5237694 0.6478955 -0.5530796 0.5062118 0.6500381 -0.5667452 0.7890622 0.425909 -0.4426991 0.7786559 0.4301016 -0.4568455 0.9506656 0.1475205 -0.2728969 0.946407 0.1512524 -0.2853709 0.9469173 0.1290734 -0.2944278 0.9517964 0.1273896 -0.2790262 0.7774797 0.3686862 -0.5095055 0.7876075 0.3672366 -0.4947845 0.5057331 0.5586423 -0.6573835 0.5209721 0.5591776 -0.6449097 0.1681614 0.6742295 -0.7191219 0.2161737 0.5295573 -0.8202672 0.1768321 0.595137 -0.7839276 0.1873892 0.678586 -0.7102157 0.9509406 0.07896244 -0.2991271 0.9552228 0.08226752 -0.2842208 0.7812181 0.230541 -0.5801286 0.7889602 0.2334317 -0.5683762 0.5099752 0.3510495 -0.785296 0.5198579 0.3543971 -0.7772713 0.9488232 0.10469 -0.2979509 0.953333 0.1063748 -0.2825607 0.7792439 0.3023814 -0.5489486 0.7876876 0.3040845 -0.5357993 0.5081781 0.45962 -0.7283574 0.5197272 0.4624759 -0.7183313 0.1843699 0.5541723 -0.8117271 0.1731671 0.4251439 -0.8884064 0.2234917 0.2475031 -0.9427586 0.1791234 0.3278005 -0.9276108 0.1837257 0.4294618 -0.8841987 0.9557471 0.02131724 -0.2934165 0.9570701 0.02409636 -0.2888531 0.7878104 0.064417 -0.61254 0.7901917 0.06659144 -0.6092313 0.5166491 0.09866672 -0.8504931 0.5194638 0.1004544 -0.8485673 0.5203089 0.01661092 -0.8538166 0.5201949 0.0162689 -0.8538928 0.7907808 0.01100373 -0.6120005 0.7906847 0.0106076 -0.6121318 0.957152 0.004014909 -0.2895585 0.9570977 0.003454148 -0.289745 0.9535952 0.05025982 -0.2968674 0.9565725 0.05454081 -0.2863464 0.7847097 0.1492517 -0.6016266 0.7900159 0.1527352 -0.5937566 0.5135151 0.2279365 -0.8272528 0.5199525 0.231142 -0.8223277 0.182429 0.2758365 -0.9437341 0.1784964 0.1197149 -0.9766308 0.1811819 0.1212297 -0.975949 0.1812808 0.01976919 -0.9832327 0.1813853 0.02003258 -0.9832081 0.6674689 -0.7095439 -0.2259048 0.9770212 -0.03345441 0.2105009 0.9813181 -0.03432089 0.1893063 0.9832448 -0.03990131 0.17787 0.9855698 -0.04045265 0.1643645 0.9882417 -0.152867 -0.003175735 0.9865363 -0.1609776 -0.02884912 0.9871664 -0.06840342 0.1443033 0.9913494 -0.06955862 0.111302 0.9861004 -0.1040281 0.1295536 0.9907364 -0.08383673 0.1068319 0.994517 -0.05980253 0.0857889 0.9944707 -0.05762279 0.08779448 0.9880503 -0.1513547 -0.02912628 0.9579101 -0.2720558 0.09161895 0.886065 -0.4629357 -0.02407342 0.9294509 -0.3689041 -0.005566358 0.8742889 -0.482258 -0.0551936 0.8699822 -0.490534 -0.05007463 0.7239292 -0.684769 -0.08377259 0.7069674 -0.6967546 -0.121368 0.4637644 -0.8827546 -0.07527887 0.5001732 -0.8480172 -0.1751968 0.4419245 -0.8460005 -0.2983053 0.4409899 -0.8327333 -0.3347885 0.2375409 -0.9138057 -0.3294444 0.3703705 -0.8759935 -0.3089678 0.3308191 -0.8789367 -0.3435534 0.3638566 -0.8726181 -0.3258007 0.4410679 -0.8507437 -0.2858223 0.6579024 -0.7163921 -0.2322646 0.6674132 -0.7106294 -0.2226333 0.8755774 -0.4625985 -0.1391655 0.8791005 -0.4576426 -0.1332131 0.9868007 -0.1563994 -0.04199695 0.986418 -0.1582905 -0.04386121 0.9864205 -0.1582262 -0.0440374 0.9859994 -0.1602814 -0.04599201 0.8755788 -0.4625746 -0.1392363 0.8716189 -0.4680665 -0.1455826 0.6579042 -0.7165157 -0.2318779 0.6470978 -0.7228935 -0.2422591 0.3703608 -0.8769171 -0.3063483 0.3517886 -0.880156 -0.3187008 0.9829705 -0.1766427 -0.05066019 -0.3222129 -0.946177 0.03046584 -0.02599287 -0.9902779 -0.1366537 -0.03096652 -0.9825688 -0.183302 0.2170032 -0.9631201 -0.1590896 0.2173819 -0.937263 -0.2725494 0.1748912 -0.9732774 -0.1488094 0.379612 -0.9118236 -0.1564368 0.5655435 -0.8166519 -0.1150668 0.8107071 -0.5801693 -0.07847046 0.8083739 -0.5886688 8.89004e-4 0.8484711 -0.5290929 -0.0125572 0.8479829 -0.5295445 0.02253502 0.8249748 -0.5641667 0.03365731 0.4156778 -0.9079225 0.05374759 0.4960696 -0.8678355 0.02786737 0.1597726 -0.9854773 0.05750846 0.2710992 -0.9622238 0.02511185 -0.0938521 -0.9939855 0.05643272 0.0404824 -0.9989863 0.01968747 -0.2177643 -0.9750772 0.04246628 -0.1527182 -0.9862518 -0.06312453 0.5739808 -0.8105006 -0.1167681 0.8421208 -0.5309592 -0.09441822 0.8424782 -0.5191147 -0.1440501 0.9860564 -0.1582553 -0.05145907 0.8717734 -0.4656659 -0.1522059 0.6459711 -0.7349309 -0.206393 0.5664754 -0.7850839 -0.2504974 0.3508275 -0.9002779 -0.2577204 0.158712 -0.935545 -0.3155411 0.9725931 -0.2323629 0.008375108 0.9739212 -0.2266678 0.009962618 0.9790711 -0.2032894 -0.009647607 0.9795482 -0.2010433 -0.008186757 0.9796739 -0.1979345 -0.03257393 0.9846043 -0.1736052 -0.0203855 0.9829463 -0.1808212 -0.03347212 -0.02599728 -0.9915714 -0.1269267 -0.09365969 -0.994059 -0.05544823 0.1747248 -0.9816873 -0.07590401 0.04050827 -0.9983322 -0.04113417 0.3792924 -0.9231969 -0.06200665 0.2713583 -0.9618865 -0.03375107 0.5730707 -0.8181402 -0.0472927 0.4965759 -0.8675941 -0.02632117 0.6947756 -0.7185178 -0.03192454 0.6942468 -0.7192273 0.02708631 0.645646 -0.762286 0.0454027 -0.3225613 -0.9440137 0.06922757 -0.09230625 -0.990512 -0.1018121 -0.189589 -0.9803481 0.05453258 0.1716581 -0.982513 0.07212394 0.1597802 -0.9853125 0.06024682 0.4243644 -0.9030961 0.06582146 0.4156962 -0.9077636 0.05623149 0.6509303 -0.7571607 0.05474835 0.6456741 -0.7621118 0.04786235 0.8274794 -0.560057 0.04017728 0.8249912 -0.5640026 0.03592467 0.9730076 -0.2300475 0.01828652 0.9726414 -0.2317973 0.01545792 0.9729276 -0.2296272 0.02613967 0.840169 -0.5390104 0.05986499 0.9007225 -0.4315685 0.04947274 0.9750909 -0.2198616 0.02930641 0.8269097 -0.558266 0.06752395 0.6504199 -0.7551656 0.08172494 0.6795887 -0.7279807 0.09057217 0.423919 -0.9006068 0.09591728 0.4715904 -0.8748895 0.1103217 0.1714646 -0.9798385 0.1025498 0.2368032 -0.9637479 0.1229395 -0.006316304 -0.994157 0.1077592 -0.1986517 -0.9744577 0.104737 -0.1895198 -0.9788035 0.07762771 -0.2089976 -0.970683 0.1187206 -0.2192056 -0.966862 0.1308693 -0.2389146 -0.9601161 0.1452479 -0.2381684 -0.9602265 0.145743 -0.2279026 -0.9606956 0.1585065 0.8342537 -0.4768665 0.276802 0.6300378 -0.5830496 0.5129382 0.7804925 -0.5155578 0.3535982 0.2737714 -0.8781271 0.3923546 0.04137295 -0.9195045 0.3908963 0.09746611 -0.8952959 0.4346789 0.08702516 -0.8780092 0.4706662 -0.2278293 -0.9574606 0.1770964 -0.2405751 -0.9526046 0.1861941 -0.08851623 -0.9605929 0.2634885 -0.05583596 -0.9511224 0.3037246 -0.07773995 -0.942178 0.3259712 -0.1060826 -0.9350715 0.3382126 -0.08415484 -0.9389398 0.3336316 0.136705 -0.9219294 0.3624335 0.2729661 -0.8984962 0.3437939 0.3482753 -0.8718141 0.3444483 0.4564928 -0.831385 0.3168808 0.5506967 -0.7759161 0.3077133 0.6273792 -0.727839 0.2768499 0.7993264 -0.5547639 0.230899 0.8338863 -0.5167679 0.1938676 0.9808216 -0.1336181 0.141899 0.9763885 -0.1743278 0.1275748 0.8633135 -0.3797309 0.3324068 0.8637741 -0.4237055 0.272705 0.6295013 -0.6723642 0.3894284 0.6277688 -0.6732554 0.3906834 0.400038 -0.7821194 0.4777646 0.456434 -0.7632646 0.4572693 0.2137966 -0.8498504 0.4817109 0.146883 -0.8452116 0.5138511 0.08429884 -0.8593013 0.5044749 0.9785588 -0.2008984 0.04541516 0.9748939 -0.2157913 0.05492001 0.900361 -0.4245746 0.09532368 0.8399985 -0.5302156 0.1152133 0.7991225 -0.5908756 0.1107678 0.6787339 -0.7148855 0.1681044 0.550898 -0.8152888 0.1783698 0.4707291 -0.8589507 0.2015387 0.3484054 -0.9156095 0.2006812 0.2362942 -0.9462109 0.2210208 0.1367552 -0.9674049 0.2131336 -0.006306707 -0.9740231 0.226361 -0.2135302 -0.9581236 0.1907991 -0.260581 -0.9449546 0.1978849 0.9851568 -0.129954 0.1121524 0.9852355 -0.1415002 0.09637922 0.985935 -0.1402055 0.09096497 0.9821332 -0.1644947 0.09141087 0.9821532 -0.1728034 0.07425713 0.9821401 -0.172878 0.07425802 0.9786407 -0.1946781 0.06605291 0.006910979 -0.9872297 0.1591538 0.01560306 -0.9881273 0.152843 0.01870489 -0.988124 0.1525161 -0.005995512 -0.8157088 0.5784319 -0.04063189 -0.858771 0.510746 0.03631198 -0.9046815 0.4245384 0.07564663 -0.8642017 0.4974263 0.05058121 -0.9048894 0.422631 0.07867199 -0.9235557 0.3753077 0.0622518 -0.8955466 0.4405918 0.01005178 -0.9891432 0.1466113 0.02042466 -0.9891971 0.1451619 0.02409362 -0.9919779 0.1240938 -0.0566852 -0.9895583 0.132519 0.02681106 -0.9943342 0.1028619 0.02920418 -0.9943326 0.1022252 0.003676593 -0.8948228 0.4464063 0.0391283 -0.8591517 0.5102229 0.001480937 -0.9839421 0.1784819 -0.01698219 -0.9837707 0.1786252 -0.006584405 -0.9787952 0.2047352 0.03013068 -0.8141277 0.5799037 0.03062438 -0.8148168 0.578909 0.1723114 -0.8148151 0.5535208 0.1723099 -0.8148154 0.5535208 0.3033722 -0.8148149 0.4940062 0.3033716 -0.8148159 0.4940047 0.4157288 -0.8148167 0.4040338 0.4157308 -0.8148152 0.4040349 0.5024604 -0.8148145 0.2891554 0.5024573 -0.8148167 0.2891546 0.5582123 -0.8148145 0.1564495 0.5582091 -0.814817 0.1564483 0.2021249 -0.979062 0.02415025 0.1973899 -0.9787629 0.05532205 0.1973904 -0.9787628 0.05532228 0.1776761 -0.9787627 0.102249 0.1776757 -0.9787628 0.1022489 0.1470074 -0.9787628 0.1428715 0.1470073 -0.9787628 0.1428717 0.1072757 -0.9787629 0.1746858 0.1072762 -0.9787628 0.1746869 0.0609309 -0.9787628 0.1957317 0.06093138 -0.9787627 0.1957318 0.02626454 -0.9790329 0.2020022 0.01070171 -0.9814929 0.1911994 9.9066e-4 -0.9787073 0.205259 0.2043498 -0.9788973 -0.001134693 0.1940321 -0.9809838 0.004719972 0.5795489 -0.8148157 0.01409804 0.5795493 -0.8148154 0.01409775 0.2370467 -0.9259337 -0.2940335 0.2530236 -0.930225 -0.2658203 0.2693456 -0.9197034 -0.2856546 0.2295839 -0.9424465 -0.2430761 0.2603104 -0.9331274 -0.2480157 0.1473262 -0.9722699 -0.1816216 0 -0.9988343 -0.0482707 3.52273e-5 -0.9988377 -0.04820233 -2.76803e-5 0 1 2.07603e-5 0 1 -2.07602e-5 0 1 -3.46004e-6 0 1 3.46005e-6 0 1 -0.216434 0 0.9762973 -0.2162919 3.90475e-4 0.9763287 0.9663899 0 0.2570808 0.9663879 0 0.2570887 -0.9658425 0 0.2591301 -0.9658493 0 0.2591049 -0.8189703 0 0.573836 -0.818991 0 0.5738065 -0.5746836 0 0.8183758 -0.5733343 -3.30449e-4 0.8193215 0.570447 -0.7929872 0.2139196 0.6819812 0 0.7313698 -0.570449 -0.7929857 0.2139198 -0.9217379 0 0.3878137 -0.6819834 0 0.7313677 -0.6819908 0 0.7313607 0.4295398 0 -0.903048 0.4295589 0 -0.9030389 -0.5435609 0 -0.8393698 0 -1 3.68772e-7 -1.7245e-6 -1 0 0 -1 -3.51402e-6 0 -1 1.24711e-6 2.07814e-7 -1 0 2.2079e-7 -1 9.58843e-7 0 -1 9.31577e-7 0 -1 2.37329e-7 0 -1 -2.47363e-7 0 -1 2.47454e-7 0 -1 2.42534e-7 0 -1 -6.51525e-7 0 -1 1.7882e-6 0 -1 9.57955e-7 0 -1 -4.81269e-7 0 -1 3.61116e-7 0 -1 3.10007e-7 0 -1 9.10417e-7 0 -1 -3.75155e-7 0 -1 -8.7669e-7 -0.965927 0 -0.2588149 -0.7071081 0 -0.7071055 -0.7070972 0 -0.7071163 -0.2588348 0 -0.9659217 -0.2587956 0 -0.9659322 0.2587956 0 -0.9659322 0.2588348 0 -0.9659217 0.7070966 0 -0.707117 0.7071074 0 -0.7071061 0.9659273 0 -0.2588138 0.9659259 0 -0.2588189 0.9659259 0 0.2588191 0.9659259 0 0.2588189 0.7071071 0 0.7071065 0.7071074 0 0.7071061 0.2588348 0 0.9659217 0.2587956 0 0.9659322 -0.2587956 0 0.9659322 -0.2588348 0 0.9659217 -0.7071081 0 0.7071055 -0.7071078 0 0.7071058 -0.9659255 0 0.2588201 -0.9659255 0 -0.2588201 -0.2922909 -0.8814336 0.3709998 -0.1937509 -0.823515 0.5331826 -0.2000657 -0.8583732 0.4724077 -0.1747548 -0.9104965 0.3747758 -0.4549981 -0.3598161 0.8145608 -0.330812 -0.6110565 0.7191478 -0.3880484 -0.478039 0.7879704 -0.4407114 -0.3858223 0.8105027 -0.2676658 -0.8616365 0.431205 -0.2565346 -0.7747216 0.5779244 -0.2962013 -0.7076545 0.6414747 -0.320941 -0.6553946 0.6837068 0.519527 -0.7323863 0.440116 0.171675 -0.6319529 0.7557534 -0.9724721 -0.193152 0.1303467 -0.9937175 -0.06287896 0.09258395 -0.4576518 -0.4856497 0.7447814 -0.4156375 -0.5091823 0.7536438 -0.3486443 -0.5237936 0.7772307 -0.9854092 -0.102414 0.1359414 -0.8809574 -0.2317872 0.4125395 -0.8972389 -0.2237756 0.38064 -0.7085362 -0.3813896 0.5937328 -0.6762683 -0.3906164 0.6245638 -0.5066994 -0.4571425 0.7309423 -0.4850218 -0.4369237 0.75753 -0.0710597 -0.5855873 0.8074888 -0.04159337 -0.6375223 0.7693083 -0.1597655 -0.5795658 0.7991112 0.5203481 -0.701006 0.4876766 0.4596636 -0.6986188 0.5483075 0.2894235 -0.7548951 0.5885301 0.2859718 -0.7534413 0.5920697 0.2070417 -0.7311995 0.6499855 -0.07047498 -0.8964548 0.4374954 0.1261919 -0.9105173 0.3937435 0.2869852 -0.8594613 0.4230437 0.3922264 -0.8340734 0.3879178 0.4514144 -0.8090866 0.376303 0.5908645 -0.7488517 0.3001669 0.7230657 -0.6262812 0.2914583 -0.4140213 -0.817281 0.400797 -0.2989646 -0.8654348 0.4020484 -0.1602656 -0.8951885 0.4158757 -0.8826199 -0.4212602 0.208619 -0.8014558 -0.546147 0.2437052 -0.7084824 -0.629725 0.3185892 -0.630898 -0.7061073 0.3215281 -0.4438697 -0.8090326 0.3852872 -0.9673665 -0.2428041 0.07244455 -0.9678234 -0.2436533 0.06285786 -0.9889576 -0.1084759 0.1009753 -0.8825809 -0.3441585 0.3203215 -0.8833034 -0.3434167 0.3191242 -0.7080646 -0.517306 0.4806653 -0.7092663 -0.5168764 0.4793539 -0.4142001 -0.6673609 0.6189247 -0.4153481 -0.6672901 0.6182313 -0.07051527 -0.7317352 0.6779316 -0.0707792 -0.7317707 0.6778658 0.1255027 -0.7277995 0.6742084 0.170345 -0.680811 0.7123756 0.4159782 -0.5039026 0.7569969 -0.1542763 -0.6420478 0.7509816 0.999777 -0.01845955 0.01026272 0.9605613 -0.2348183 0.1489376 0.9891182 -0.1463349 -0.01520836 0.8831321 -0.4238089 0.2011563 0.8080132 -0.5445891 0.2248051 0.7093583 -0.6341077 0.3077635 0.666069 -0.67987 0.3068043 0.5883526 -0.7400393 0.3258576 0.4670926 -0.8092306 0.3563289 0.4149032 -0.8239296 0.3859995 0.2642524 -0.8855479 0.3820675 0.07049489 -0.907092 0.4149877 0.0327419 -0.9149883 0.4021498 -0.2081968 -0.8954187 0.3935475 -0.287668 -0.8662787 0.4084218 -0.3859598 -0.8443931 0.3715314 -0.6097601 -0.7445651 0.27169 -0.490692 -0.7975432 0.350922 -0.5595236 -0.7001122 0.4435947 -0.4350824 -0.7182146 0.5430203 -0.2362471 -0.7764238 0.5842546 -0.2889669 -0.7623287 0.5790968 -0.1389135 -0.7293897 0.6698461 -0.1520994 -0.6270295 0.7640025 0.3247768 -0.5239045 0.7874289 0.1206855 -0.5827421 0.8036459 0.07124507 -0.6233851 0.7786626 -0.008334636 -0.6169797 0.7869351 -0.1057462 -0.6128896 0.7830609 0.8830584 -0.2501564 0.3970261 0.7229078 -0.3503259 0.595547 0.7078784 -0.3639683 0.6053391 0.4624537 -0.4676212 0.7533041 0.5017502 -0.4504444 0.7384759 -0.1498454 -0.7288925 0.6680285 0.07014328 -0.7354022 0.6739908 0.07040804 -0.7353058 0.6740683 0.4125877 -0.6714709 0.6155472 0.4143959 -0.6704115 0.6154873 0.7062885 -0.521484 0.4787599 0.7083031 -0.5193318 0.4781228 0.8815996 -0.3472443 0.3196932 0.8827634 -0.3452237 0.3186683 0.9795755 -0.1477522 0.1363865 0.9940132 -0.02091407 0.1072407 0.9618358 -0.163036 0.2197526 0.9672733 -0.1049082 0.2310341 0.1968928 -0.8848468 0.4222314 0.1975481 -0.8473759 0.4928781 0.1987263 -0.9046089 0.3770819 0.2436803 -0.7890288 0.5639624 0.2586131 -0.8322702 0.4903526 0.2735021 -0.761198 0.5880258 0.3147417 -0.668436 0.6738925 0.3162406 -0.6018808 0.7333017 0.4197906 -0.3697527 0.8288902 0.4053151 -0.3961024 0.823907 0.3421423 -0.5159732 0.7853091 0.3780843 -0.6087687 0.6974619 0.4160851 -0.6308915 0.6548658 0 -1 -1.91958e-6 0 -1 -2.78319e-6 0 -1 2.04659e-6 0 -1 -2.18417e-6 0 -1 -4.46882e-7 0 -1 1.10522e-6 0 -1 1.00354e-6 0 -1 5.7226e-7 0 -1 -1.95468e-6 0 -1 1.15529e-6 0.4297751 -0.7118306 0.5555094 0.6053906 -0.7193142 0.3407187 0.431776 -0.8561838 0.2837585 -0.3209688 -0.655364 0.683723 -0.1082496 -0.7449588 0.6582694 -0.1776633 -0.8121535 0.555736 -0.1957485 -0.8220571 0.5347006 -0.05430066 -0.8265305 0.5602669 -0.02616149 -0.7970837 0.6033018 -0.1151207 -0.8859473 0.4492715 -0.1188907 -0.8901916 0.4397999 -0.1142029 -0.9078058 0.4035423 -0.002021253 -0.9444554 0.3286337 -0.1274546 -0.9326168 0.3376112 -0.1134143 -0.9126738 0.3926371 -0.104786 -0.9061725 0.4097214 0.08781105 -0.9102439 0.4046546 0.1007203 -0.9012412 0.4214498 0.09979414 -0.8994926 0.4253872 0.102187 -0.9014449 0.4206603 0.1064254 -0.9034696 0.4152308 0.07764065 -0.9047179 0.4188764 0.07365053 -0.9072064 0.4141886 -0.1168605 -0.7270169 0.6766018 0.01145911 -0.821204 0.5705197 0.1899978 -0.8427783 0.5036127 0.184603 -0.8361708 0.516469 0.3384032 -0.8686023 0.3619577 0.3356218 -0.8449431 0.4164484 0.4300041 -0.8437376 0.3212531 0.4415079 -0.8463414 0.2979549 0.6395139 -0.7224826 0.2627565 0.4836935 -0.682049 0.5484977 0.5180516 -0.7027454 0.4876183 0.634181 -0.7289463 0.2577823 0.584591 -0.6813164 0.4405241 0.6394276 -0.7119083 0.2903777 0.4001155 -0.6912066 0.6017815 0.5321415 -0.7446337 0.402922 0.5243598 -0.7539231 0.3957864 0.6291877 -0.7570478 0.1760724 0.676401 -0.7243311 0.1335154 -0.2674756 -0.4418354 0.8562934 -0.2245278 -0.4909389 0.8417637 -0.1607881 -0.4763993 0.8644021 -0.08962529 -0.5589835 0.8243209 -0.007700264 -0.5650143 0.8250453 0.03675377 -0.6112736 0.7905656 0.142603 -0.6319245 0.7617978 0.1518535 -0.640569 0.7527363 0.2820227 -0.6932804 0.6631934 0.2479266 -0.6448581 0.7229734 0.2987739 -0.6875919 0.6617791 0.5631181 -0.7973014 0.2172756 0.5562024 -0.7970175 0.2353767 0.3893479 -0.7609241 0.5190403 0.4713931 -0.8281132 0.3033432 0.2402217 -0.7423474 0.6254709 0.3424292 -0.8378804 0.4250867 0.2001857 -0.8198818 0.536395 -0.05721646 -0.6227469 0.7803286 0.05480641 -0.7772816 0.6267612 -0.2054417 -0.5262745 0.8251236 -0.1005645 -0.7098879 0.6970984 -0.3138337 -0.4673999 0.8264659 -0.1730749 -0.6448459 0.7444589 -0.4168732 -0.4232571 0.8044068 -0.5487444 -0.8042732 0.2280886 -0.4216687 -0.6782383 0.6018208 0.08563017 -0.5722759 0.8155782 -0.2919003 -0.905389 0.3083264 -0.2923892 -0.9053173 0.3080735 -0.1818054 -0.8741928 0.4502596 -0.3397878 -0.8632054 0.3733909 -0.03175222 -0.8642929 0.5019859 0.4604533 -0.3799191 0.8022744 -0.1428045 -0.9219964 0.3599022 -0.1437156 -0.9218581 0.3598939 -0.142758 -0.9219929 0.3599298 0.09348946 -0.9019434 0.4216133 0.09349882 -0.9019446 0.4216089 0.08246487 -0.9516575 0.2958846 0.7090221 -0.5439186 0.448821 0.7091495 -0.5437354 0.4488416 0.1841886 -0.8563478 0.4824346 0.09338742 -0.9019722 0.4215744 0.1833573 -0.8558569 0.4836208 0.07013279 -0.9446885 0.3203827 0.285814 -0.6991317 0.6553817 0.2463721 -0.6597442 0.7099567 0.2682728 -0.6567173 0.7048064 0.1676922 -0.5475148 0.8198212 0.1630319 -0.4815656 0.8611128 0.1183937 -0.3499248 0.9292662 0.3094952 -0.5312758 0.7886436 -0.1366745 -0.6336201 0.7614761 -0.1124427 -0.6102018 0.7842261 -0.4746122 -0.6918755 0.5441063 -0.6907269 -0.7144971 0.1113115 -0.6788527 -0.721335 0.1372402 -0.6848323 -0.7146035 0.1426417 -0.6461197 -0.707735 0.2857285 -0.6567122 -0.7026171 0.2739678 -0.5580711 -0.7945997 0.2390986 -0.5637608 -0.8015668 0.1991591 -0.5830315 -0.752517 0.3062558 -0.5572133 -0.7809827 0.2820985 -0.5655107 -0.6968206 0.4411789 -0.5946365 -0.6577172 0.462402 -0.595705 -0.6699577 0.4430489 -0.3134199 -0.8922889 0.324944 -0.3488928 -0.8594387 0.3736829 -0.2331108 -0.822085 0.5194571 -0.07046025 -0.804688 0.589502 -0.04897081 -0.8265365 0.5607489 -0.1427958 -0.9219487 0.3600277 -0.3581973 -0.6229636 0.6954215 -0.449007 -0.4747644 0.7569621 -0.3274348 -0.6607303 0.675442 -0.3379937 -0.7490714 0.5697829 -0.3474417 -0.7378787 0.5786358 -0.3559654 -0.8345559 0.420482 -0.403309 -0.7823306 0.4746586 -0.3685208 -0.8777468 0.306191 -0.09539633 -0.5837365 0.8063197 -0.09848088 -0.5909853 0.8006485 -0.0551905 -0.6439607 0.7630653 -0.07102668 -0.7742132 0.6289269 -0.0387603 -0.8063672 0.5901438 0.06925177 -0.7255168 0.6847114 0.1443338 -0.8003018 0.5819664 0.2435459 -0.7158247 0.6544315 0.1700699 -0.8445796 0.5077024 0.5421155 -0.8051457 0.2405228 0.5057434 -0.8322607 0.2270811 0.2358661 -0.9687035 -0.07733464 0.02136707 -0.9959195 0.08767974 0.09730923 -0.9928582 0.0690183 -0.07270449 -0.9828898 0.1692391 0.1812557 -0.9812577 0.06541961 0.4037684 -0.8825062 0.2411514 0.4108389 -0.8529638 0.3219694 0.4519131 -0.8522668 0.2634693 0.6074343 -0.7492051 0.2640368 0.5485236 -0.7975342 0.2511197 0.07935464 -0.9033558 0.421487 -0.004989802 -0.8430123 0.5378713 0.3398071 -0.9336337 0.1133984 0.3383877 -0.8972887 0.2834906 0.4339543 -0.8995435 0.05005264 0.5166398 -0.8025273 0.2983846 0.5054159 -0.8284053 0.2414532 -0.1408651 -0.942844 0.3019973 -0.03431296 -0.9966986 0.07358402 -0.06311482 -0.9857727 0.1557846 -0.09156137 -0.9747709 0.2035636 -0.1275065 -0.9531962 0.2741518 -0.04251062 -0.937999 0.3440213 0.1080391 -0.9048362 0.4118239 0.3088956 -0.8665028 0.3921178 0.3080582 -0.8678964 0.3896872 0.3038702 -0.8808419 0.363016 0.1147838 -0.9010642 0.4182204 0.1116283 -0.8990139 0.4234538 0.1289614 -0.9015988 0.4129028 0.1870299 -0.9276055 0.3233695 0.1738263 -0.931028 0.3208917 -0.08192014 -0.8924486 0.4436494 -0.04641705 -0.9263669 0.373751 -0.08995801 -0.8879604 0.4510366 -0.0664491 -0.9014669 0.4277172 -0.04723519 -0.9169709 0.3961483 -0.05865061 -0.9253933 0.3744429 -0.05359846 -0.9174775 0.3941602 -0.08283346 -0.8914076 0.4455685 -0.04208713 -0.9245254 0.3787896 -0.03797465 -0.9265142 0.3743387 0.02040016 -0.9550077 0.2958788 -0.01413607 -0.9423821 0.3342396 0.07852154 -0.9843704 0.1576367 0.02388465 -0.9820424 0.1871425 0.02637052 -0.9363914 0.3499653 -0.3020145 -0.9034084 0.3043693 0.1470289 -0.9428227 0.2991119 -0.01267695 -0.9177851 0.3968752 -0.2382262 -0.9140974 0.3281375 -0.198631 -0.9185401 0.3418039 -0.1964573 -0.9354895 0.2937071 -0.2894595 -0.8795216 0.377697 -0.2020874 -0.9082888 0.3662952 -0.08403414 -0.9830604 0.1628823 -0.01805895 -0.9808153 0.194101 -0.02348834 -0.8871639 0.4608563 -0.06641685 -0.9215563 0.3825216 -0.0663827 -0.9215551 0.3825306 -0.01261538 -0.9177694 0.3969134 0.07520931 -0.874405 0.4793325 0.03647702 -0.9118152 0.4089776 -0.2383461 -0.9141189 0.3279905 -0.1593974 -0.8847599 0.4379411 -0.03556388 -0.9547372 0.2953172 -0.069579 -0.9627901 0.2611398 0.03961765 -0.9099979 0.4127156 0.03675901 -0.911978 0.4085891 0.03617984 -0.911889 0.4088393 -0.02997368 -0.9045197 0.4253771 0.1113318 -0.9646804 0.2387408 0.03068739 -0.9945836 0.099307 0.07339376 -0.9848051 0.1573927 0.3346319 -0.8170282 0.4695597 0.4395611 -0.742166 0.5059405 0.5324391 -0.607102 0.5898608 0.618855 -0.2743315 0.736044 0.6836488 -0.1537115 0.7134404 0.4615938 -0.5173051 0.7206433 0.4979136 -0.3773652 0.7808185 0.5889124 -0.183072 0.7871893 0.5467312 -0.1886423 0.8157814 0.537817 -0.2401406 0.8081371 0.5049747 -0.2435205 0.828069 0.5114006 -0.2134108 0.8324214 0.1737343 -0.9687714 0.1769133 0.2711462 -0.9060146 0.3249883 0.3503934 -0.800818 0.4857108 0.3917304 -0.796499 0.4605831 0.4149928 -0.7318216 0.5405721 0.4539654 -0.727114 0.5149958 0.5012523 -0.6120994 0.6116213 0.530598 -0.6102576 0.5882615 0.6705515 -0.1689913 0.7223591 0.6236382 -0.4151268 0.6623784 0.6729151 -0.2219817 0.7056271 0.4265741 -0.6637815 0.6143523 0.4541739 -0.5336148 0.7134293 0.5024377 -0.5286666 0.6841549 0.5079699 -0.4397255 0.7406809 0.5612059 -0.4331182 0.7053061 0.5777343 -0.2854905 0.7646688 0.612748 -0.2835776 0.7376474 0.3292134 -0.8710913 0.3644428 0.3238895 -0.8912731 0.3173766 0.394185 -0.8124607 0.4295647 0.3857138 -0.811592 0.4387978 0.4210134 -0.7652824 0.4869195 0.2818326 -0.8845421 0.3716931 -0.6103726 -0.7268595 0.3148343 -0.3784338 -0.8846958 0.2722156 -0.1654825 -0.9807173 0.1039674 -0.4826831 -0.8187933 0.3107967 -0.1123719 -0.9928659 0.0398736 -0.1245879 -0.9918174 0.02786129 -0.1132079 -0.9904402 0.0788185 -0.6436085 -0.7521166 0.1417351 -0.6256716 -0.7623248 0.1655169 -0.6321288 -0.7560815 0.1695704 -0.5224582 -0.8185991 0.2386064 -0.4765124 -0.8309773 0.2870761 -0.1662707 -0.9751235 0.1465886 -0.5032948 -0.8640777 -0.008007764 -0.4900076 -0.8695277 0.06175827 -0.2903703 -0.9121626 0.2892138 -0.3075416 -0.9157786 0.2583948 -0.1076254 -0.9140687 0.3910183 -0.1445431 -0.9396932 0.3099744 -0.1445313 -0.9396938 0.3099784 -0.1445428 -0.9396934 0.3099738 -0.144543 -0.9396926 0.3099762 -0.1445452 -0.9396929 0.3099744 -0.144537 -0.9396933 0.3099768 -0.1459332 -0.9402673 0.3075724 -0.1444652 -0.9397583 0.309813 -0.1446235 -0.9395757 0.3102925 -0.14455 -0.9396952 0.3099653 -0.1445529 -0.9396888 0.309983 -0.1445102 -0.9396932 0.3099896 -0.144519 -0.939697 0.3099739 -0.1445466 -0.9396923 0.3099754 -0.1445351 -0.9396958 0.3099702 -0.1445455 -0.939692 0.3099766 0.06951904 -0.9469416 0.3137974 0.02490609 -0.9394012 0.341914 -0.07562261 -0.9369972 0.3410536 0.1445096 -0.9396939 0.3099879 0.1441169 -0.9396578 0.3102798 0.1445426 -0.9396944 0.3099709 0.1445322 -0.9396933 0.3099789 0.1445434 -0.939693 0.3099745 0.1445453 -0.9396921 0.3099767 0.1442748 -0.939771 0.3098632 0.1445386 -0.9397009 0.3099533 0.1445477 -0.9396919 0.309976 0.1445089 -0.9396929 0.3099914 0.1445463 -0.939692 0.3099763 0.14455 -0.9396919 0.3099753 0.1445437 -0.9396924 0.309976 0.1445186 -0.9397014 0.3099606 0.1447159 -0.9396426 0.310047 0.1447018 -0.9396525 0.3100236 0.003624856 0.9996087 -0.02773803 -0.0678386 0.9915318 -0.1107375 -0.06783676 0.991532 -0.110737 -0.03774356 0.9914513 -0.1248999 -0.01674455 0.9916298 -0.1280235 -0.04155987 0.9921844 -0.1176558 0 0.9838476 -0.1790087 0.007755637 0.9867674 -0.1619569 0.04075163 0.9913893 -0.1244454 0.03774398 0.9914515 -0.1248981 0.06783664 0.9915321 -0.1107349 0.06783831 0.9915318 -0.1107379 -0.08075231 0.9916291 -0.1007509 -0.1256681 0.9907984 -0.05026203 -0.1356765 0.9903668 -0.02766919 -0.1390928 0.9898258 -0.02996879 -0.395879 0.9143329 -0.08529549 -0.2948299 0.9553068 -0.02155065 -0.1050751 0.9907994 -0.08529943 -0.1046951 0.9908446 -0.08524125 -0.1330413 0.9890947 -0.06318134 -0.1389177 0.9881114 -0.06586331 -0.3183569 0.9383695 -0.1345796 0 1 -3.97115e-7 -0.009518444 0.9999503 -0.002977609 -0.01211446 0.9998143 0.0149933 0.1901533 0.9711495 0.1439115 0 1 -2.12837e-6 0 1 0 0 1 9.67353e-7 0 0.9999898 0.004533469 0 1 -1.89328e-6 0.003809869 0.9999925 7.02849e-4 -0.001161158 0.9996213 -0.02749264 -0.001111328 0.9999781 0.006529569 0.002546608 0.9998508 0.01709061 -0.003419697 0.9999574 0.008578538 0 1 0 0 1 1.61614e-6 0 1 1.53323e-6 0 1 -1.1771e-6 1.55392e-4 0.999714 0.02391606 -0.001310229 0.9999877 -0.004796624 6.28051e-4 0.9998276 0.01855677 0 1 2.85617e-7 0 1 -1.31027e-7 0 1 -1.59913e-7 0 1 -1.32955e-7 0.4299841 -0.8333615 0.3473072 0.4640656 -0.8525587 0.2403889 0.4506615 -0.859876 0.2398283 0.5236504 -0.8390045 0.1478573 0.5547707 -0.8201895 0.1397101 0.1887726 -0.9809235 0.04641169 0.1858996 -0.9818049 0.0387361 0.3487589 -0.8685496 0.3521206 0.1343371 -0.9816097 0.1356322 0.1695077 -0.9816095 0.08780568 0.2061021 -0.9700976 0.1281901 0.1681683 -0.9837161 0.06342107 0.04584974 -0.9819628 0.1834312 0.05932116 -0.9820405 0.179102 0.08775699 -0.9809224 0.1734654 0.08734524 -0.9816499 0.1695118 0.1343395 -0.9816092 0.1356328 -0.01679825 -0.9819038 0.188634 -0.03289073 -0.9773707 0.2089614 -0.09444892 -0.9778677 0.186693 -0.09411072 -0.9821142 0.1630796 -0.1359056 -0.9811736 0.1372158 -0.1424133 -0.9781005 0.1517827 -0.1690794 -0.9836108 0.06262618 -0.1888176 -0.9809144 0.04642128 -0.1859171 -0.9818059 0.03862643 -0.5243503 -0.8391702 0.1443961 -0.5469057 -0.825792 0.1377028 -0.4600903 -0.8552869 0.2383306 -0.1881208 -0.9772995 0.09744936 -0.1513759 -0.9834441 0.09961491 -0.2330175 -0.8564781 0.4605953 -0.3488439 -0.8288597 0.4373782 -0.3477691 -0.86935 0.3511229 -0.4326369 -0.8278221 0.3571219 -0.4587952 -0.8564645 0.2365922 0.3562927 -0.8399469 0.4093224 0.24636 -0.8379565 0.486966 0.2463623 -0.8379568 0.4869641 0.08484995 -0.837956 0.5391012 0.08486396 -0.8379494 0.5391094 -0.03928703 -0.8403337 0.5406441 -0.0768758 -0.8692474 0.4883637 -0.1395422 -0.8285938 0.5421811 -0.2330433 -0.854832 0.4636304 -0.7765779 0.6296912 0.02039492 -0.7481788 0.6406902 0.1724666 -0.9086311 0.4105502 0.07640701 -0.9667407 0.2077873 0.14912 -0.9691833 0.1874704 0.1598087 -0.2473082 -0.9130085 0.324429 -0.3772496 -0.8535987 0.3592384 -0.4771776 -0.8088361 0.3436363 -0.7036303 -0.6247837 0.338452 -0.703507 -0.6249061 0.3384824 -0.8728992 -0.3820684 0.3034318 -0.8728339 -0.3821779 0.3034816 -0.965727 -0.09916633 0.2398698 -0.9657156 -0.0992096 0.239898 -0.9787985 0.06909835 0.1928187 -0.8386106 0.5245989 0.1467252 -0.9279713 0.2261482 0.2961866 -0.9258829 0.2607836 0.273373 -0.9338315 -0.06701004 0.3513811 -0.8444396 -0.3531607 0.4027395 -0.8590444 -0.326958 0.39388 -0.6805582 -0.6009879 0.4191113 -0.6496556 -0.6292238 0.4266439 -0.3793146 -0.8557502 0.3518697 -0.3130001 -0.8809978 0.3547872 -0.5167817 -0.5580938 0.6492058 -0.5848193 -0.6364659 0.5028893 -0.2415491 -0.9021601 0.3574372 -0.9567236 0.2885125 0.03795486 -0.9892907 -0.03843724 0.1408069 -0.1860704 -0.8930909 0.4095933 -0.6900554 -0.3654732 0.6247023 -0.5504447 -0.4822304 0.6815163 -0.5367425 -0.3906773 0.7478494 -0.5127208 -0.4232143 0.7469987 -0.9889658 0.1386009 0.05231356 -0.9971214 0.07581669 9.45445e-4 -0.9897558 -0.03155654 0.1392397 -0.9891871 -0.03768861 0.1417343 -0.922306 -0.1636313 0.3501092 -0.9056655 -0.2026981 0.3724024 -0.5244188 -0.620743 0.5828062 -0.7407455 -0.4208069 0.523658 -0.6689826 -0.4460433 0.5945652 -0.8689612 -0.3763134 0.321395 -0.8594208 -0.4005321 0.317758 -0.696695 -0.6135774 0.3716704 -0.7101284 -0.5933476 0.3790203 -0.4691395 -0.7943191 0.3859605 -0.5240219 -0.7382715 0.4246838 -0.3334394 -0.8588062 0.3889347 -0.9305653 0.3635243 -0.04356908 -0.9737193 0.227245 0.01517838 -0.9886402 0.126214 0.08161282 -0.9889864 0.1235765 0.08145451 -0.9703436 -0.07670778 0.2292361 -0.9813417 0.03226715 0.1895446 -0.8842697 -0.2610335 0.3872063 -0.9209036 -0.1529074 0.3585472 -0.8037638 -0.3539788 0.4781871 -0.7956781 -0.2807867 0.5367078 -0.7910435 -0.2870706 0.540223 -0.915992 0.3993332 0.03862196 -0.9205572 0.3899394 0.02284288 -0.9800628 0.184793 0.07299685 -0.9465978 0.3111865 0.08435434 -0.9872861 0.05588638 0.1488053 -0.9877209 0.03650546 0.1519045 -0.9744986 -0.1135415 0.1935482 -0.9663833 0.1919605 0.1710399 -0.9341928 -0.2389563 0.264922 -0.9629854 -0.05046105 0.2647885 -0.849577 -0.3748396 0.3710986 -0.8855114 -0.2654587 0.3813152 -0.6965894 -0.5592361 0.4494645 -0.7521837 -0.4594922 0.4723203 -0.5094729 -0.7026693 0.4966822 -0.5801631 -0.6169872 0.5317308 -0.3092896 -0.7999941 0.5141493 -0.4593638 -0.6594436 0.595079 -0.6741978 0.09280073 0.7326973 -0.9752125 -0.04591828 0.2164537 0.1526074 -0.7888615 0.5953223 -0.6550915 -0.5118175 0.555786 -0.4609493 -0.6409178 0.6137998 -0.3389991 -0.6778519 0.6523776 -0.2361196 -0.7373125 0.6329438 0.006587862 -0.7604377 0.6493776 0.2532772 -0.823561 0.5075412 0.2646649 -0.8405606 0.4726631 -0.8513177 -0.3049445 0.4269277 -0.7966789 -0.3835106 0.4671431 -0.6525692 -0.5127948 0.5578486 -0.9024927 -0.2263168 0.3664531 -0.8730513 -0.2642699 0.4098085 -0.8481851 -0.202288 0.4895524 -0.7640318 -0.2037702 0.6121545 -0.4939687 -0.3028774 0.8150216 -0.3940423 -0.3226824 0.8605851 -0.3928976 -0.3173223 0.8630981 -0.1709479 -0.2102319 0.96259 0.2022932 -0.3880847 0.8991484 -0.02638912 -0.1978482 0.9798774 -0.1856755 -0.4207931 0.8879514 0.1353471 -0.2066832 0.9690012 0.4380616 -0.2538207 0.8623673 0.5040267 -0.004760503 0.8636751 0.7066601 -0.1573456 0.6898362 0.6427549 -0.25863 0.7210941 0.6425666 -0.21696 0.7348718 0.6184481 -0.4142405 0.6677775 0.2405057 -0.9009056 0.3612841 0.2862839 -0.8851935 0.3667071 0.01365756 -0.7636001 0.6455451 0.0467503 -0.7677935 0.6389895 0.08386164 -0.7501575 0.65592 0.1211657 -0.7617002 0.6364996 0.1955989 -0.740578 0.6428728 0.217998 -0.7565258 0.6165595 0.3259232 -0.7422064 0.5855798 0.5130072 -0.6034462 0.6104723 0.5496456 -0.4759657 0.6865467 0.4129188 -0.4697712 0.7802649 0.4091577 -0.4615079 0.7871471 0.1850457 -0.4904645 0.8515883 0.1636118 -0.4671829 0.8688909 -0.02671808 -0.5205417 0.8534181 -0.06077647 -0.499763 0.8640273 -0.197157 -0.564068 0.8018457 -0.226894 -0.5521123 0.8023037 -0.6608012 -0.3087578 0.684113 -0.5937272 -0.3878509 0.7050246 -0.5933436 -0.3880802 0.7052214 -0.3131234 -0.6247011 0.7153338 -0.3122485 -0.6248737 0.7155655 -3.65793e-5 -0.7740041 0.6331807 0.001716434 -0.7739468 0.6332485 0.2057078 -0.818476 0.5364527 0.2078028 -0.8627347 0.4609845 0.20552 -0.8629015 0.4616954 0.1949645 -0.882918 0.4271355 0.2216628 -0.8805968 0.4188255 0.2040039 -0.8980161 0.3898069 0.2387287 -0.8898978 0.3887035 0.3290654 -0.7483642 0.5759054 0.3910875 -0.7512536 0.531666 0.4189805 -0.7384363 0.5283629 0.3121779 -0.8456957 0.4328325 0.3405005 -0.8070677 0.4823912 0.4245249 -0.7655032 0.4835116 0.2535901 -0.9004673 0.3533424 0.2036105 -0.9334067 0.2954568 0.2126967 -0.9232848 0.3198522 0.228886 -0.9559077 0.1839885 0.4935133 -0.7956089 0.351356 0.502684 -0.78003 0.3726419 0.6880348 -0.5479093 0.4758189 0.7194221 -0.4987108 0.4834455 0.765595 -0.3632951 0.5309249 0.8191263 -0.1612434 0.550484 0.8203356 -0.1262072 0.5577826 0.6001262 -0.170857 0.7814453 0.6032065 -0.1614968 0.7810639 0.5344678 -0.4633963 0.7068296 0.5154528 -0.4987793 0.6967982 0.4649837 -0.6360325 0.6158351 0.3901768 -0.7535955 0.529014 0.7126991 -0.161131 0.6827129 0.7126939 -0.1611397 0.6827161 0.6260346 -0.498443 0.5996961 0.6260351 -0.4984412 0.5996969 0.4235751 -0.8099065 0.4057531 0.4422991 -0.7951166 0.4149232 0.2564008 -0.9396256 0.2266331 0.2305669 -0.950223 0.2095597 -0.3742768 -0.8285305 0.4164783 -0.4542962 -0.6569669 0.6016723 -0.7000576 -0.1612678 0.695638 -0.6772146 -0.2786986 0.6809608 -0.6306439 -0.4060748 0.6613558 -0.5360246 -0.6137865 0.5796066 -0.5409091 -0.6049907 0.5842977 -0.43393 -0.7464172 0.5045456 -0.2061554 -0.9626923 0.1752809 -0.3889842 -0.7647625 0.5136437 -0.4950132 -0.5081756 0.7047834 -0.4461249 -0.6331821 0.6324976 -0.5339758 -0.1680445 0.8286319 -0.5364716 -0.1350818 0.8330373 -0.5048936 -0.2212659 0.8343403 -0.4422304 -0.7395024 0.5075123 -0.6416545 -0.2327163 0.730837 -0.6302079 -0.2764459 0.7255451 -0.519918 -0.6120191 0.5959178 -0.5246437 -0.604265 0.5996773 -0.2810016 -0.8849113 0.3714433 -0.3782762 -0.8077393 0.4521774 -0.3757096 -0.8219112 0.4281408 -0.385758 -0.8120214 0.4379636 -0.3999912 -0.8134379 0.4222864 -0.3225801 -0.8873488 0.3294757 -0.3021839 -0.889464 0.3428394 -0.2837762 -0.9057086 0.3149019 -0.5551416 -0.3776266 0.7410911 -0.6227191 -0.286198 0.728225 -0.5793744 -0.2888599 0.7621583 -0.3601702 -0.8296663 0.4265342 -0.6028319 -0.1594527 0.7817727 -0.04400324 -0.9957531 -0.08086657 -0.04396897 -0.9957547 -0.08086782 -0.4975461 -0.4631686 0.7334321 -0.5305389 -0.3417794 0.7757033 -0.5759035 -0.3361458 0.7452121 -0.5430597 -0.5023609 0.6728446 -0.5020142 -0.6130749 0.6100171 -0.4878815 -0.6529184 0.5793697 -0.4200276 -0.7792899 0.4650636 -0.3836211 -0.7833831 0.4890254 -0.3269385 -0.8623387 0.3866307 -0.5616309 0.6982027 0.4439413 -0.3853486 0.7170819 0.5807754 -0.3853578 0.7170685 0.5807858 -0.497606 0.3642908 0.7871978 -0.5001224 0.3331816 0.799292 -0.5111516 -0.115633 0.8516767 -0.5111442 -0.1156036 0.8516851 -0.4170919 -0.5425931 0.7291277 -0.4088981 -0.5708335 0.7120053 -0.32871 -0.7311458 0.597809 -0.2699556 -0.8648399 0.4232918 -0.2977242 -0.8724063 0.3876438 -0.297709 -0.8724067 0.3876545 -0.6077287 -0.6053888 0.5139751 -0.6983947 0.6627627 0.2701679 -0.8432629 0.3040153 0.4432634 -0.843263 0.3039904 0.4432802 -0.8469972 -0.05046021 0.5291972 -0.8194714 -0.1687898 0.5477012 -0.7861061 -0.2865178 0.5476723 -0.6077157 -0.605396 0.5139818 -0.2337519 -0.8613148 0.4511065 -0.2337616 -0.86131 0.4511106 -0.2699725 -0.8648364 0.4232882 -0.5200551 -0.5813478 0.6257616 -0.5200685 -0.5813323 0.6257647 -0.6863893 -0.1328916 0.7149893 -0.6863924 -0.132915 0.7149819 -0.6907594 0.3440433 0.6359919 -0.6907555 0.3440617 0.6359862 -0.5616497 0.6981774 0.4439572 -0.6984193 0.6627389 0.2701626 0 0.6934916 0.7204648 0.206628 0.6935038 0.6901865 0.206628 0.6935002 0.6901901 0.2702606 0.3218538 0.9073971 0.2847617 0.1191709 0.951162 0.2849001 -0.1150215 0.9516312 0.1549945 -0.8413851 0.5177335 -0.1998431 0.7172879 0.6675034 -0.2038011 0.6937103 0.6908192 0 0.6935033 0.7204536 0 0.3217898 0.9468111 0 0.3217858 0.9468125 -0.1467748 -0.8591263 0.4902644 -0.1521021 -0.8415855 0.5182653 -0.1965377 -0.7283259 0.6564407 -0.2431321 -0.5304453 0.8121051 -0.2403195 -0.5397827 0.8067721 -0.2860547 -0.1150318 0.9512836 -0.2704943 0.3218348 0.9073342 -0.2705066 0.3322797 0.9035577 0.8426373 0.3074384 0.4420905 0.8473813 -0.04797017 0.5288136 0.8211501 -0.1623942 0.5471203 0.7874969 -0.2827312 0.5476422 0.6135058 -0.5979934 0.515766 0.6134988 -0.597999 0.5157678 0.2736082 -0.8621233 0.4264762 0.2492927 -0.8437179 0.4753877 0.2342787 -0.8582401 0.4566589 0.4116181 -0.5628852 0.7167502 0.5128415 -0.1092124 0.8515082 0.5187831 0.1197279 0.8464806 0.4945592 0.3678228 0.7874755 0.5026873 0.3354842 0.7967157 0.6978302 0.6635786 0.2696229 0.6978418 0.663563 0.2696314 0.5611643 0.6989757 0.4433144 0.3967793 0.6934289 0.6014338 0.5611478 0.6989815 0.4433261 0.6901612 0.3474742 0.6347749 0.6901533 0.3474588 0.634792 0.6875732 -0.1264229 0.7150248 0.6875711 -0.1263888 0.7150328 0.5246656 -0.5735985 0.6290555 0.5246641 -0.5736097 0.6290465 0.2735875 -0.8621293 0.4264777 0.3021894 -0.8699163 0.3897785 0.3021835 -0.8699111 0.3897946 -0.09285205 0.9935795 0.06464171 -0.09118247 0.9900199 0.1074543 -0.09665924 0.9782713 0.1834182 -0.02996855 0.9839091 0.1761387 -0.02996748 0.9839097 0.1761349 0.0263344 0.9839101 0.1767131 0.02633464 0.9839095 0.1767165 0.1001778 0.9935588 0.05296701 0.08978837 0.9885094 0.1216034 0.2522026 0.9279802 0.2743114 0.07476723 0.9903703 0.1165183 0.09852635 0.9901555 0.0994215 0.09852606 0.9901556 0.09942203 0.1245751 0.9901555 0.06382262 0.124574 0.9901556 0.06382095 0.1382516 0.9901554 0.02188348 0.138251 0.9901555 0.0218836 0.4039918 0.9142832 -0.02961307 0.1382369 0.9903475 -0.01013237 0.4039865 0.9142855 -0.02961444 0.4034416 0.9127742 0.06386059 0.4034405 0.9127747 0.06386089 0.3635354 0.9127734 0.1862438 0.3635304 0.912775 0.1862455 0.2875191 0.912774 0.2901319 0.2875207 0.912774 0.2901304 0.1829443 0.9127741 0.3652053 0.06020939 0.9127746 0.4040019 0.06020838 0.9127745 0.4040024 -0.06851452 0.9127764 0.4026726 -0.1904286 0.9127752 0.3613567 -0.1904259 0.9127762 0.3613554 -0.2934252 0.9127773 0.2841472 -0.2934277 0.9127758 0.2841489 -0.3672901 0.9127746 0.1787196 -0.3672931 0.9127733 0.1787199 -0.4046725 0.9127736 0.05553972 -0.4046702 0.9127746 0.05553942 -0.1380276 0.9903611 -0.0115481 -0.4034349 0.9143857 -0.03375196 -0.4034351 0.9143857 -0.03374803 -0.138035 0.9903601 -0.01154714 -0.1386719 0.9901556 0.01903164 -0.1258621 0.9901555 0.06124496 -0.1258636 0.9901555 0.06124216 -0.1005533 0.9901554 0.09737288 -0.1005516 0.9901556 0.09737151 -0.08095544 0.9903932 0.1121056 -0.003241181 0.9999825 0.004942357 0.3004791 0.9129295 -0.276174 0.2789282 0.9539623 -0.1102504 0.3450047 0.9361786 -0.06739139 0.3982734 0.914614 -0.06970971 0.1031114 0.9911711 -0.08335417 0.1050241 0.9900822 -0.09331303 0.1271895 0.9902572 -0.05668854 0.2083975 0.9744155 -0.08417165 0.1367673 0.9890623 -0.05523312 0.1296121 0.9912416 -0.02531796 0.1383045 0.9899102 -0.03081709 0.1367011 0.9903959 -0.0207079 0.1013891 0.9809843 -0.1654999 0.1000058 0.9800484 -0.1717679 0.05480247 0.9818907 -0.1813485 0.05111461 0.980573 -0.1893776 0 0.9812214 -0.1928849 -0.04925769 0.9819719 -0.1824966 -0.104614 0.9797421 -0.1707674 -0.09791195 0.9808834 -0.1681702 0.03283041 0.9978691 -0.05638653 0.03282976 0.997869 -0.05638885 0.01700341 0.9978691 -0.06299316 0.01700252 0.997869 -0.0629962 0 0.997869 -0.06524908 0 0.997869 -0.06525009 -0.01700299 0.9978691 -0.06299489 -0.01700288 0.997869 -0.06299573 -0.03283071 0.9978691 -0.05638724 -0.03282999 0.9978691 -0.05638837 -0.3552221 0.9334568 -0.04975819 -0.5068675 0.8615882 -0.02740913 -0.5361365 0.8441314 -2.01763e-4 -0.2274907 0.9735653 0.02046275 -0.3229876 0.9324497 -0.1619159 -0.1158224 0.9932355 0.008277595 -0.1471285 0.9805424 -0.129961 -0.2266585 0.9663724 -0.121451 -0.2220421 0.9656192 -0.135192 -0.2818089 0.9581651 -0.05003386 -0.2968087 0.9473354 -0.1202518 -0.3672534 0.9300442 -0.01195031 0.09245961 -0.6946079 0.7134222 0.314269 -0.6543627 0.6877824 -0.4270393 -0.7286699 0.5354229 -0.7878589 -0.5763782 0.2169482 -0.5549095 -0.5898781 0.5866169 -0.7153749 -0.5898154 0.3746419 -0.6746781 -0.6935948 0.2524594 -0.6663575 -0.7026725 0.2494376 -0.6023244 -0.7567264 0.2541074 -0.6275749 -0.7081101 0.3236199 -0.6017091 -0.6366457 0.4823158 -0.6775314 -0.556336 0.4810839 -0.6607916 -0.4966902 0.5627197 -0.7527361 -0.3560432 0.5537344 -0.6842566 -0.1473875 0.7141917 -0.5760524 -0.08673739 0.8127977 -0.5760849 -0.08672893 0.8127757 -0.5761505 -0.08671087 0.8127311 -0.4735019 -0.3449689 0.8104274 -0.6046589 -0.1754384 0.7769228 -0.5271067 -0.2104831 0.8233199 -0.5012509 -0.273572 0.8209178 -0.5760293 -0.08676064 0.8128117 -0.6722292 -0.1755425 0.7192307 -0.6548417 -0.262467 0.7087266 -0.6553797 -0.2617094 0.7085095 -0.6427614 -0.3266233 0.6929467 -0.6135341 -0.378637 0.6929719 -0.5960379 -0.4480185 0.666347 -0.4595861 -0.5471947 0.6995418 -0.496792 -0.5223615 0.6930629 -0.4452025 -0.3315173 0.8317999 0.01017713 -0.5172218 0.855791 0.1148422 -0.4454226 0.8879246 0.07816827 -0.4610726 0.8839128 0.009172916 -0.5165426 0.8562125 -0.2144142 -0.5114756 0.8321173 0.4127637 -0.6145676 0.6722595 0.4893034 -0.6283669 0.6047623 0.5669085 -0.5094658 0.647348 0.5090084 -0.255545 0.8219532 0.5361066 -0.1867048 0.8232443 0.5679756 -0.2267889 0.791183 0.4848025 -0.3339043 0.8083777 0.6279317 -0.1336476 0.7667074 0.5903329 -0.1150802 0.7989141 0.5396487 -0.1917008 0.8197746 0.6769582 -0.1954888 0.7095857 0.6332243 -0.4112588 0.6556624 0.5920708 -0.4450157 0.6718729 0.6119225 -0.3813655 0.6929007 0.6456624 -0.3211526 0.6928066 0.6467993 -0.2582701 0.7175983 0.6831235 -0.1876716 0.7057774 0.6335145 -0.1385225 0.7612299 0.5973985 -0.7699145 0.2243814 0.711834 -0.6369185 0.296019 0.6986018 -0.6070898 0.3786788 0.6608024 -0.5754343 0.4818876 0.6462436 -0.5999888 0.4715747 0.6649973 -0.4998323 0.5549291 0.71382 -0.452362 0.5346304 0.7232111 -0.3222826 0.6108189 0.6225335 -0.709021 0.3312723 0.6615957 -0.707764 0.2477122 0.7652665 -0.6010392 0.2304761 0.6456226 -0.7415817 0.1822855 0.6028788 -0.6355233 0.4823353 0.4979805 -0.6516944 0.5721101 0.51947 -0.6671175 0.5339524 0.3064289 -0.734318 0.605705 0.3222807 -0.6502385 0.6879863 0.2631682 -0.6364654 0.7250202 0.2469466 -0.58205 0.7747486 0.1557997 -0.5718308 0.8054416 -0.305403 -0.6544008 0.6917287 -0.3460124 -0.6375151 0.6883677 -0.2656784 -0.6337767 0.7264587 -0.1839641 -0.6748391 0.7146674 -0.08701556 -0.6538049 0.7516433 -0.0535618 -0.6735313 0.7372156 0.1154253 -0.6699949 0.7333375 -0.2803625 -0.4676072 0.8382962 -0.3728435 -0.4788271 0.7948033 -0.444628 -0.5710215 0.6901018 -0.444628 -0.5710214 0.6901019 -0.5036714 -0.6468333 0.5726447 -0.5903065 -0.6435213 0.4872563 0.3243186 -0.6898425 0.6472518 0.1915706 -0.5625513 0.8042616 0.4482519 -0.4025143 0.7981557 0.3505443 -0.27083 0.8965321 0.1021859 -0.2300609 0.9677965 0.3947597 -0.1143013 0.9116469 -0.7044813 -0.4999717 0.5037208 -0.6555824 -0.5573374 0.5094966 -0.8012711 -0.4308697 0.4151095 -0.8783323 -0.352497 0.3229216 -0.8588967 -0.3850886 0.3376438 -0.9108754 -0.2983242 0.2851471 -0.1906466 -0.6985905 0.6896559 -0.235632 -0.7084572 0.6652563 0.1847105 -0.4606183 0.8681665 0.1845702 -0.2802771 0.9420077 0.2132873 -0.2888195 0.9333231 0.2133285 -0.09497761 0.9723529 0.1593857 -0.07414394 0.9844283 -0.3553432 -0.181441 0.9169571 -0.4609077 -0.6493203 0.6049359 -0.4637405 -0.6489385 0.6031779 -0.4596771 -0.4714497 0.7526169 -0.7008982 -0.3961859 0.5931092 -0.622142 -0.4087837 0.667709 -0.8772606 -0.2696515 0.397117 -0.8214285 -0.2952948 0.4879099 -0.9452223 -0.1797077 0.2725068 -0.9465273 -0.0894038 0.3099889 -0.9844992 -0.1275923 0.1203401 -0.9842482 -0.1281276 0.1218152 -0.9835616 -0.08863234 0.1573243 -0.9969172 -0.04403412 0.06494021 -0.9903877 -0.03176099 0.1346237 0.324369 -0.5695161 0.7552723 0.1397873 -0.609313 0.780511 0.1396348 -0.4508417 0.8816144 -0.08733779 -0.4676957 0.879564 -0.08702224 -0.296277 0.9511294 0.1131808 -0.2003534 0.9731643 -0.07751637 -0.1017667 0.9917837 -0.9829538 -0.02229386 0.1824966 -0.8156045 -0.1247637 0.5649985 -0.8210285 -0.1257666 0.5568618 -0.5646201 -0.1499245 0.8116199 -0.6205999 -0.1588866 0.7678613 -0.3644201 -0.1788519 0.9138983 -0.3648993 -0.506985 0.7809064 0.06134843 -0.5148818 0.8550632 -0.1903609 -0.6089314 0.7700424 0.08195501 -0.5993176 0.7963051 0.08221459 -0.7160195 0.6932221 0.1517323 -0.6879156 0.709753 -0.8807005 0.4727574 -0.02944731 -0.5688216 0.8224201 0.008195757 -0.988629 0.1503559 -0.002428531 -0.78952 0.6098557 -0.068807 -0.7849123 0.6192191 -0.02191871 -0.8656273 0.489795 -0.1038762 -0.7894989 0.6110522 -0.05750513 -0.7975094 0.5995233 -0.06745982 -0.7424793 0.6698358 -0.006682336 -0.9744307 0.2186492 -0.05174261 -0.8100966 0.2185236 -0.5440506 -0.9142651 0.2333486 -0.3311613 -0.9543224 0.2670195 -0.1340495 -0.9488825 0.3057212 -0.07846373 -0.9364359 0.3495165 -0.03043097 -0.4874429 -0.3498643 0.7999966 -0.511413 -0.2212901 0.8303537 -0.674172 -0.4114567 0.6133478 -0.9896917 -0.06041884 0.129846 -0.9902207 -0.05185061 0.1295171 -0.9076551 -0.1913247 0.3735737 -0.6551252 -0.590167 0.471714 -0.7912368 -0.2708399 0.5482611 -0.905662 -0.1743876 0.3864781 -0.9865352 0.06836372 0.1485761 -0.8837977 -0.3371571 0.3243868 -0.8588312 -0.4612526 0.2228342 -0.7314141 -0.1197767 0.6713323 -0.7429937 -0.2799179 0.6079527 -0.5171281 -0.3827508 0.7655591 -0.5128936 -0.3622295 0.7782865 -0.9832724 -0.132673 0.1247931 0.4054846 -0.8289476 0.3852639 -0.8599395 -0.4836742 0.1629825 -0.8046325 -0.5596024 0.1985242 -0.556348 -0.7831471 0.277773 -0.4502165 -0.8475255 0.2810793 -0.6356382 -0.7275419 0.2581607 0.729277 -0.656906 0.191389 0.5944358 -0.7736704 0.2192719 0.7281992 -0.644526 0.2330499 0.3968712 -0.8654699 0.3057045 0.2931503 -0.9037697 0.3118705 0.1272326 -0.9324659 0.3381116 -0.1452113 -0.9350315 0.3234654 -0.1626263 -0.9318976 0.3242217 -0.3027625 -0.8982309 0.3186161 0.7802382 -0.2918778 0.5532051 0.7027302 -0.1889585 0.6859045 0.4470949 -0.2297077 0.8644886 0.5016539 -0.2170256 0.8374027 0.2936417 -0.2190693 0.9304748 -0.145476 -0.2257964 0.9632511 -0.02055525 -0.2392898 0.9707306 0.1970118 -0.2347228 0.9518885 -0.877508 -0.1038513 0.4681823 -0.7899617 -0.121871 0.6009227 -0.8605963 -0.1179834 0.4954332 -0.6144186 -0.1832968 0.7673931 -0.5564536 -0.1860032 0.8097915 -0.4251898 -0.2144427 0.8793339 -0.2337927 -0.2301988 0.9446426 -0.9949715 -0.03973555 0.09194046 -0.9781679 -0.1207466 0.1691386 -0.9667955 -0.2372043 0.09508359 -0.986429 -0.1544138 0.05580705 -0.9892488 -0.1240063 0.07752043 -0.9922775 -0.1040278 0.06755417 -0.8594204 -0.4287928 0.2784483 -0.8594341 -0.4287717 0.2784383 -0.5548104 -0.6977629 0.4531143 -0.5548434 -0.6977393 0.45311 -0.1447578 -0.8298415 0.5388954 -0.1447929 -0.8298414 0.5388863 0.2923011 -0.8020495 0.5208424 0.2922869 -0.8020535 0.5208441 0.8040176 -0.4986811 0.3238409 0.7701898 -0.54117 0.3375543 -0.9942479 -0.07109475 0.08010458 -0.8594182 -0.3394017 0.3823701 -0.8594285 -0.3393808 0.3823655 -0.5548469 -0.5522782 0.6222007 -0.5548422 -0.5522709 0.6222114 -0.1446998 -0.6568419 0.740014 -0.1447589 -0.6568338 0.7400096 0.292299 -0.6348353 0.715224 0.2923196 -0.6348333 0.7152175 0.7494537 -0.4394919 0.4951422 0.5084673 -0.6770015 0.5320996 -0.9751307 -0.04657119 0.2166824 -0.988578 -0.04286509 0.1444863 -0.9831382 -0.08068537 0.164101 -0.8594427 -0.2255874 0.4587687 -0.8594442 -0.2255831 0.4587679 -0.5548091 -0.3671197 0.746599 -0.5547932 -0.3671133 0.7466139 -0.144832 -0.4366056 0.8879185 -0.1447585 -0.436612 0.8879274 0.2923055 -0.4219951 0.8581828 0.2923203 -0.421981 0.8581848 0.612976 -0.3486474 0.7090172 0.6319139 -0.5006284 0.5916554 -0.8269433 -0.003605723 0.5622739 -0.2069422 -0.9313893 0.2994813 -0.2156648 -0.9207131 0.3252324 -0.349124 -0.8044502 0.4805961 -0.1516457 -0.8156172 0.5583659 -0.294859 -0.8663245 0.4031626 -0.3692007 -0.7586352 0.5368086 -0.3852702 -0.7153352 0.5829771 -0.6010934 -0.1614711 0.7826966 -0.5835132 -0.04250723 0.8109905 -0.5957382 -0.193764 0.779456 -0.5263327 -0.4992088 0.6883056 -0.5292309 -0.4356593 0.7280905 -0.4731758 -0.6206523 0.6252163 -0.8227313 -0.10339 0.5589489 -0.8202055 -0.1612209 0.5488812 -0.7836945 -0.304561 0.5413553 -0.717191 -0.4988417 0.4866151 -0.7135144 -0.5046244 0.4860571 -0.2307077 -0.9497338 0.211612 -0.231996 -0.9443745 0.2330986 -0.6340036 -0.6710673 0.3843281 -0.4818802 -0.7959761 0.366352 -0.442291 -0.7951227 0.4149202 -0.2581515 -0.9387178 0.2284005 -0.4245193 -0.7651048 0.4841468 -0.4235689 -0.8099091 0.4057546 -0.6260312 -0.4984451 0.599698 -0.6260327 -0.4984406 0.5997 -0.7126917 -0.1611334 0.68272 -0.7126959 -0.1611334 0.6827157 0.5976415 -0.3944809 0.698004 0.04645931 -0.7620154 0.6458902 0.6870589 -0.3680875 0.6264677 0.6662507 0.01072496 0.7456508 -0.4826483 -0.6031989 0.6349817 -0.3549246 -0.7264764 0.5884392 -0.2508977 -0.8202279 0.5140784 -0.2092062 -0.8281452 0.5200082 -0.2753179 -0.8840076 0.3777973 -0.2392445 -0.9010013 0.3618823 -0.2272397 -0.889666 0.3960512 -0.218476 -0.8927161 0.3941144 -0.2008448 -0.8796205 0.4311952 -0.2270347 -0.8751873 0.4272029 -0.1779841 -0.8613169 0.4758728 -0.209331 -0.858273 0.4685596 -0.5639882 -0.1391689 0.8139714 -0.09063112 -0.360403 0.9283834 -0.2169354 -0.1149919 0.9693895 -0.3465251 -0.3312225 0.8776172 -0.5833092 0.08766853 0.8075051 0.2100781 -0.2703464 0.9395638 0.2083407 -0.2597481 0.9429343 -0.00256133 -0.2526235 0.9675614 0.8595165 -0.2277304 0.4575702 0.9972683 -0.04769176 0.05640625 0.9682879 -0.1157712 0.2213951 0.9654327 -0.1265886 0.2278491 0.859821 -0.2929422 0.4182017 0.9065555 -0.2200497 0.3601881 0.8734157 -0.2643278 0.4089936 0.8247574 -0.3520883 0.4425035 0.7006143 -0.4757265 0.5318118 0.6514527 -0.5039347 0.5671503 0.6039391 -0.5491583 0.5776529 -0.1889855 -0.7230182 0.6644768 0.8412932 -0.1986693 0.5027486 0.7354676 -0.2185521 0.6413444 0.5979955 -0.3936952 0.6981443 0.5023005 -0.3070838 0.8083279 0.4266086 -0.3256986 0.8437568 0.4233517 -0.3169963 0.8486971 0.3534982 -0.2803124 0.8924484 -0.3955191 -0.7388032 0.5456506 -0.3811845 -0.7483169 0.5428814 -0.2827076 -0.7516927 0.5958478 -0.2979497 -0.7406162 0.6022571 -0.1697051 -0.7606254 0.6266173 -0.1923364 -0.7329496 0.6525271 -0.07682186 -0.7700458 0.6333466 -0.088279 -0.7405855 0.6661381 -0.02282643 -0.7753702 0.6310945 -0.01983439 -0.7558954 0.6543918 1.56443e-4 -0.774012 0.6331709 -1.92073e-4 -0.7742053 0.6329346 0.02474904 -0.8226429 0.5680196 -0.2299736 -0.7769616 0.5860401 -0.3837854 -0.7550562 0.5316003 0.3593137 -0.6946834 0.6231443 0.3504946 -0.7022646 0.6196597 0.3148554 -0.6284186 0.711306 0.3152662 -0.6277803 0.7116876 0.2329843 -0.5533343 0.7997122 0.2289144 -0.5764945 0.7843802 0.08161598 -0.4990599 0.8627155 0.08878964 -0.5342884 0.8406261 -0.1131518 -0.4984157 0.8595222 -0.3453004 -0.4626494 0.8165313 -0.3336392 -0.4766573 0.8133159 -0.5234569 -0.4696184 0.710951 -0.5798932 -0.3966277 0.7116252 0.3563156 -0.872559 0.3341856 0.7911185 -0.3389235 0.5091784 0.4555168 -0.7206277 0.5226855 0.9194871 0.3927609 0.01680821 0.982191 0.1658355 0.08831405 0.9655065 0.2602499 -0.008205771 0.9615827 0.2739161 0.01813161 0.9888707 0.09181874 0.1170648 0.9870953 0.1488627 0.05901598 0.9893006 -0.03845888 0.1407313 0.9958298 0.09103584 0.005949318 0.9869819 -0.03646808 0.1566423 0.9878337 -0.02899515 0.1527873 0.915318 -0.1768668 0.3618165 0.9057102 -0.1978793 0.3748772 0.784608 -0.3014552 0.5417705 0.7383794 -0.3565401 0.5724291 0.5122076 -0.4391114 0.7381224 0.5220531 -0.4277541 0.7378936 0.5373473 -0.5086607 0.6726978 0.5057291 -0.6018389 0.6180843 0.4885841 -0.5829108 0.6492308 0.9520848 0.305823 0.002625405 0.9543358 0.2842527 0.0918889 0.9850344 0.1040313 0.1374219 0.9662982 -0.1000704 0.2371788 0.9360092 -0.2452596 0.2524575 0.8443111 -0.4160768 0.3376666 0.8754381 -0.3863663 0.290395 0.6953612 -0.6191261 0.3649051 0.6988441 -0.6170957 0.3616766 0.5680599 -0.7336014 0.3730107 0.4090663 -0.8057878 0.4282183 0.4065208 -0.8001033 0.4411073 0.6770628 -0.5788214 0.4544797 0.7340343 -0.540835 0.4107203 0.8331277 -0.3923663 0.3898037 0.8752073 -0.3453444 0.3387473 0.9548566 -0.1030372 0.278626 0.4365819 -0.6690456 0.6014768 0.5107609 -0.6725247 0.5355688 0.714094 -0.483914 0.5058627 0.7184742 -0.4813705 0.5020731 0.8565567 -0.2935186 0.4244496 0.9187526 -0.2017441 0.3394011 0.953474 -0.09945231 0.284599 0.9820581 -7.80678e-4 0.1885771 0.9862246 0.1189565 0.1149372 0.9870841 0.1480053 0.06131464 0.9670711 0.2540218 -0.01569855 0.4955622 0.8678127 -0.03632247 -0.5677222 0.8218489 -0.04749715 -0.5861642 0.7919088 0.1711497 0.586165 0.7919082 0.1711497 0.6104615 0.7870543 -0.08878374 0.7108201 0.7033389 0.007008016 0.5637431 0.8249926 -0.03976422 0.6728433 0.739672 0.01293224 0.5614126 0.8232218 0.08439075 0.5721493 0.8173799 0.06734406 0.3899995 0.9187433 0.06173533 0.5567443 0.8102536 0.1830976 0.4723579 0.8475354 0.2419958 0.5101624 0.7719913 0.3791624 0.3360193 0.8787042 0.3390722 0.3667538 0.7522067 0.5474274 0.2003915 0.8943247 0.4000334 0.1859382 0.7613891 0.6210585 0.06556475 0.8956225 0.4399564 -0.07490694 0.8947489 0.4402426 -0.1842054 0.7664569 0.6153149 -0.2110882 0.8916244 0.4005593 -0.3629043 0.759 0.5405735 -0.344475 0.8775315 0.3335799 -0.50905 0.7733951 0.3777939 -0.4757538 0.848568 0.2314969 -0.5537288 0.812047 0.1842937 -0.4207249 0.9053487 0.05774414 -0.5712071 0.8184782 0.06177294 -0.5512676 0.8294167 0.09039926 -0.6809104 0.7323305 0.007296562 -0.5440387 0.8337715 -0.09405833 0.9122205 0.4054318 0.05898129 0.7820225 0.6169217 0.08859264 0.9224067 0.266288 0.2797439 0.932493 0.2228758 0.2842239 0.9296107 -0.09287029 0.3566499 0.9321293 -0.06557744 0.3561385 0.8583116 -0.3218829 0.3996155 0.846046 -0.3546947 0.3979923 0.658864 -0.6236565 0.4206552 0.676833 -0.5973066 0.430258 0.5734122 -0.7429521 0.3452835 0.7034904 -0.6248434 0.3386327 0.7036127 -0.6246876 0.3386662 0.8727809 -0.3821213 0.3037051 0.872838 -0.3819761 0.3037237 0.9656514 -0.09913939 0.2401853 0.965662 -0.09903967 0.2401836 0.9699144 0.1864603 0.1565204 0.9699129 0.1864731 0.1565145 0.9236745 0.3721103 0.09143084 0.7685797 0.63621 0.06724762 0.3806697 -0.857135 0.3470019 0.3745042 -0.8507069 0.368842 0.3270959 -0.8834066 0.335561 0.313084 0.9497097 0.005475461 0.3562812 0.9330521 -0.04977577 0.4910579 0.8706154 -0.02985203 0.5511617 0.8341404 -0.02075815 0.3682855 0.9295838 -0.01548498 0.2502296 0.9638831 -0.09118473 0.228894 0.9656494 -0.1229993 0.1528105 0.9802558 -0.1254896 0.317236 0.9483467 -1.73258e-5 0.2984352 0.9542995 -0.01577627 0.2392556 0.9709552 -0.001734018 0.2026114 0.9787535 -0.03146964 0.0444113 0.9978873 -0.04741895 -0.1484022 0.9889272 0 -0.3220126 0.9467273 -0.003931283 -0.3382815 0.941035 -0.004340589 -0.1736459 0.9848082 -2.43979e-4 -0.3347383 0.9423112 3.81648e-6 -0.4629926 0.8863623 -4.94222e-5 -0.6401031 0.7682781 0.004092752 -0.63929 0.7683206 -0.0314939 -0.658837 0.7487437 -0.07291513 -0.5685983 0.8226144 0.001219868 -0.8026296 0.5964775 -6.39622e-4 -0.9066476 0.4218705 -0.003935337 -0.8153518 0.5789602 0.002589583 -0.9757561 0.2188553 -0.001584172 -0.9888049 0.1492143 0 0.0162875 -0.04227387 0.9989733 0.06641888 -0.717265 0.6936279 -0.2824155 -0.5099641 0.8125136 -0.2840346 -0.665869 0.6898861 -0.1888867 -0.7175534 0.6704021 -0.3553202 -0.6673414 0.6545251 0.4167389 -0.646537 0.6389982 0.3572885 -0.6446201 0.6758771 0.0466932 -0.7226807 0.689603 0.915029 -0.2968817 0.2730993 0.8290254 -0.39199 0.3988243 0.7132773 -0.5081241 0.4827478 0.7035474 -0.5123106 0.4925028 0.6049884 -0.5647097 0.5613305 -0.3961257 -0.04982042 0.9168437 -0.402056 -0.05685222 0.9138484 -0.3990034 -0.2298339 0.8876783 0.3008753 -0.04880368 0.9524139 0.5738722 -0.04438948 0.817741 0.6206219 -0.002091646 0.7841072 0.8241057 -0.08663535 0.5597716 0.8612717 -0.02185696 0.5076745 0.9840447 -0.01394075 0.1773748 0.9753983 -0.04894667 0.2149474 0.6203459 -0.1639462 0.7670024 0.3196664 -0.1862192 0.9290511 0.2998191 -0.1985222 0.9331117 -0.03774136 -0.1966401 0.9797491 0.9972317 -0.04608058 0.05835777 0.9837446 -0.1163058 0.1368201 0.9908853 -0.04632461 0.126493 0.886211 -0.1303016 0.4445801 0.8568868 -0.1577643 0.4907704 0.6606665 -0.2147001 0.7193217 0.324293 -0.3514503 0.8782464 0.355232 -0.3488718 0.8672363 0.3197697 -0.3715792 0.8715941 -9.68337e-5 -0.3739256 0.9274588 -0.03762114 -0.3910159 0.9196147 0.9686128 -0.1561771 0.1933856 0.7823288 -0.4043963 0.4737357 0.8883716 -0.2648921 0.3750044 0.7131315 -0.3816521 0.588035 0.6647211 -0.4256886 0.6139504 0.4159834 -0.4970337 0.7615218 0.3546524 -0.5312239 0.7694303 0.06630074 -0.5465085 0.834825 1.03653e-4 -0.567129 0.8236292 -0.2174505 -0.5391399 0.8136606 -0.4026048 -0.3384066 0.8505236 -0.2606421 -0.194007 0.9457415 -0.05828154 -0.2072193 0.976557 -0.05866521 -0.1508228 0.9868186 0.3636677 0.02475422 0.9311999 0.6187798 -0.1824874 0.7640746 0.9832783 -0.1081536 0.1465153 0.1452081 -0.9352418 0.3228585 0.03305113 -0.9415447 0.3352632 -0.2932935 -0.9017083 0.3176496 -0.2105364 -0.9259862 0.3134073 -0.3893789 -0.8685271 0.3066676 0.5559634 -0.7861108 0.2700642 0.4708082 -0.8314815 0.2949206 0.266431 -0.9083941 0.3222342 0.9637794 -0.2484978 0.09684073 0.8103616 -0.5565278 0.183279 0.8603208 -0.4804273 0.170405 0.6703919 -0.6992936 0.2481194 0.5926856 -0.7608345 0.2643004 0.9949698 -0.08659029 0.05037122 0.978164 -0.1536359 0.1399692 0.9892538 -0.06224906 0.1322956 0.8995705 -0.09603166 0.4260879 0.9270579 -0.08459675 0.3652495 0.9864212 -0.03697425 0.1600197 0.9797575 -0.04174673 0.1957871 0.9990773 -0.009654581 0.04185146 0.8605816 -0.1180197 0.4954501 0.7847608 -0.1220784 0.6076573 0.8689479 -0.1062452 0.4833648 0.00240159 -0.2130337 0.9770419 0.2145354 -0.2314522 0.9488965 0.5569334 -0.196536 0.8069689 0.3804255 -0.1839683 0.9063289 0.4643738 -0.1884937 0.8653481 0.1455485 -0.2367708 0.9606015 -0.2938482 -0.2288635 0.928049 -0.2226903 -0.219947 0.9497538 -0.6627928 -0.1974352 0.7223054 -0.5625227 -0.1670955 0.8097205 -0.6100229 -0.7460917 0.2668695 -0.5742323 -0.769312 0.2800295 -0.6737149 -0.6237918 0.3962223 0.9922766 -0.05473566 0.111316 0.8594537 -0.2255784 0.4587522 0.8594249 -0.2255986 0.4587966 0.5547912 -0.3671219 0.7466111 0.5548002 -0.3671185 0.7466062 0.1449002 -0.4365996 0.8879104 0.1447596 -0.4366118 0.8879272 -0.2922967 -0.421988 0.8581892 -0.2923855 -0.4219756 0.8581652 -0.8038492 -0.2624756 0.5337913 -0.4280771 -0.3138568 0.8474928 0.9942476 -0.07109999 0.08010369 0.8594161 -0.3394004 0.382376 0.8594245 -0.3393912 0.3823652 0.5548408 -0.5522766 0.6222077 0.5548485 -0.5522738 0.6222032 0.144817 -0.6568313 0.7400005 0.1447599 -0.6568352 0.7400082 -0.2923283 -0.63483 0.7152168 -0.2922561 -0.6348473 0.715231 -0.7896921 -0.4072619 0.4588294 -0.4133532 -0.4924693 0.7659066 0.9997907 -0.01935034 0.006641685 0.9902547 -0.132273 0.04358583 0.9831345 -0.1533808 0.0996046 0.8594279 -0.4287802 0.2784443 0.8594242 -0.4287854 0.2784478 0.55484 -0.6977444 0.4531064 0.5548236 -0.6977535 0.4531123 0.1447902 -0.8298402 0.5388889 0.1447599 -0.8298434 0.5388922 -0.2922891 -0.8020533 0.5208433 -0.2922894 -0.8020519 0.5208454 -0.7256661 -0.5770494 0.3747301 -0.5151255 -0.6077497 0.604389 0.8780498 -0.4764782 0.04469019 0.9899584 -0.05958557 0.1281873 0.9001975 -0.05889588 0.4314808 0.7299729 -0.4467207 0.5172816 0.6732221 -0.5957429 0.4380212 0.5077196 -0.1820539 0.8420673 0.4662405 -0.3563517 0.8097118 0.9896451 -0.05381226 0.133067 0.9057238 -0.1934831 0.3771325 0.9077671 -0.1722038 0.3824983 0.7398357 -0.3029038 0.6007432 0.742994 -0.2798137 0.6080003 0.5129666 -0.384243 0.7676085 0.5172047 -0.3606555 0.7761617 0.7893276 0.6124364 -0.04340261 0.873867 0.4785767 -0.08556276 0.9443583 0.3237564 -0.05804681 0.9468643 0.3140306 -0.0695194 0.9488149 0.3060656 -0.07793861 0.9532099 0.2781808 -0.1183483 0.9911236 0.1293721 -0.03061151 0.9762429 0.2162479 -0.01366627 0.809779 0.2186387 -0.5444771 0.9319413 0.2349149 -0.2762255 0.6964294 0.7175897 0.007149338 0.7860813 0.6157656 -0.05393642 0.7895015 0.6110117 -0.05789774 0.8882848 0.4585677 -0.02580195 0.937561 0.34597 -0.03583443 0.9932803 0.1157337 0 0.9999659 0.00550884 0.006156861 0.9998471 0.01658284 0.00557208 0.99944 0.0331279 0.004739463 0.9977998 0.06622028 0.003246545 0.9955946 0.09373503 0.002293229 0.9944992 0.1047275 0.001941144 0.9926277 0.1211947 0.001456737 0.9904854 0.1376141 0.00105983 0.988904 0.1485536 8.24497e-4 0.9863088 0.1649085 5.15668e-4 0.980303 0.1974998 7.395e-5 0.9706253 0.2405966 -4.42543e-5 0.9621216 0.272621 2.20085e-4 0.9558632 0.2938119 5.14093e-4 0.9491417 0.3148481 9.25626e-4 0.9419557 0.3357341 0.001453816 0.9566351 0.2912889 8.39385e-5 0.9334357 0.358745 -1.46758e-5 0.9234102 0.3838147 1.20719e-4 0.9073573 0.42036 5.76045e-4 0.9071123 0.4208886 5.62332e-4 0.8830749 0.469232 -3.37136e-5 0.8633555 0.5045963 2.31903e-5 0.8494186 0.5277196 2.29356e-4 0.8118921 0.5838063 0.001162946 0.7749444 0.6320197 0.003509402 0.7663504 0.6424099 0.00407195 0.757596 0.652707 0.004674494 0.748717 0.6628684 0.005321145 0.7351398 0.6778858 0.006346583 0.7165645 0.6974763 0.007882356 0.6974936 0.7165911 4.24465e-6 0.7325406 0.6807234 7.15449e-6 0.8179278 0.5753167 -0.002180159 0.6031642 0.7967897 -0.0363211 0.6779009 0.7351533 1.56805e-4 0.6628865 0.7487199 3.86912e-4 0.534741 0.8450119 0.00265336 0.6573341 0.7534056 0.01709067 0.6345157 0.7727759 0.0144025 0.6161556 0.7875263 0.01244008 0.5946815 0.8038945 0.01037418 0.572768 0.8196736 0.008489847 0.5504473 0.8348424 0.006791472 0.5334311 0.8458246 0.005658924 0.5219813 0.8529427 0.004951834 0.5045899 0.8633502 0.003958046 0.489938 0.8717514 0.003240466 0.4841046 0.875005 0.002978622 0.475158 0.8798967 0.002585053 0.4632672 0.8862162 0.002111673 0.4542982 0.8908479 0.001797258 0.4546614 0.8906626 0.001807212 0.4313274 0.9021948 0.001078307 0.4086011 0.9127131 5.54155e-4 0.3931498 0.9194744 3.19537e-4 0.3869148 0.9221155 2.39129e-4 0.3775852 0.9259749 1.33477e-4 0.1758274 0.9844211 4.77005e-6 0.1151642 0.993306 -0.008967936 0.2409917 0.9705268 -8.61128e-4 0.3675292 0.9300121 6.02321e-5 0.3496669 0.9368741 -1.04525e-6 0.3338743 0.9426177 4.06066e-6 0.3177547 0.9481729 -1.21704e-4 0.2911013 -0.9091108 0.2979561 0.1258959 -0.9671635 0.220783 0.1033619 -0.9844012 0.1423754 0.03920972 -0.9983744 0.04136854 0.1271985 -0.9841626 0.1234683 0.1267997 -0.9842783 0.1229556 0.211517 -0.9525031 0.2190856 0.3463289 -0.8709469 0.3485798 0.3850626 -0.8404107 0.3813618 0.4337591 -0.7832958 0.44531 0.5632388 -0.1755021 0.8074412 0.6714442 -0.1752517 0.7200344 0.709887 0.02588891 0.7038397 0.6965611 -0.06472849 0.7145718 0.6724151 -0.2237067 0.7055589 0.5811294 -0.5375509 0.6110056 0.6575081 -0.394563 0.6418748 0.5611877 -0.5905207 0.5799602 0.4760829 -0.1756395 0.8616819 0.5352871 -0.008859574 0.8446238 0.4515659 -0.5370526 0.7125046 0.4515566 -0.5370559 0.712508 0.28972 -0.8408824 0.4571424 0.2897267 -0.8408753 0.4571511 0.1061245 -0.9801528 0.1674463 0.06633239 -0.9909009 0.1171135 0.03653901 -0.9840939 0.1738511 -0.02496695 -0.9838009 0.1775174 0.1817737 -0.9643663 0.1922393 0.04065752 -0.987457 0.1525637 0.1408259 -0.8372286 0.5284094 0.1408352 -0.8372243 0.5284137 0.2181469 -0.5314441 0.8185225 0.2181433 -0.5314445 0.8185233 0.2536765 -0.1724091 0.9518001 -0.1921326 -0.04921495 0.9801342 0.006403803 -0.1755579 0.9844483 0.253678 -0.1724014 0.951801 -0.009510397 -0.9627422 0.270254 -0.1192793 -0.7902777 0.6010273 -0.07617175 -0.8372255 0.5415269 -0.1113391 -0.6010398 0.7914258 -0.1435623 -0.5289261 0.8364372 -0.126564 -0.4176127 0.8997673 -0.1371969 -0.1723724 0.9754306 -0.3779719 -0.7789664 0.5003485 -0.4441993 -0.4194635 0.7916674 -0.9803159 -0.1702949 0.09990221 -0.94598 -0.3239746 -0.01274096 -0.998453 0.002690374 0.05553793 -0.9719628 -0.01412642 0.2347099 -0.9410669 -0.0861364 0.3270684 -0.9280688 -0.08133929 0.3634176 -0.859533 -0.1218827 0.4963343 -0.9252038 -0.3760648 0.05072891 -0.8929084 -0.442638 0.08237922 -0.8986559 -0.4363973 0.04444181 -0.8265225 -0.535092 0.1747488 -0.7837843 -0.6200469 0.03498995 -0.6726166 -0.7204345 0.1690005 -0.7167778 -0.6912376 0.09176218 -0.8600863 -0.09805089 0.5006372 -0.7992349 -0.1527114 0.5812941 -0.7759866 -0.1614465 0.6097376 -0.7106288 -0.205588 0.6728599 -0.6826373 -0.1850576 0.7069371 -0.5895543 -0.2195806 0.7773097 -0.5729716 -0.222517 0.7887901 -0.457854 -0.2536042 0.8520883 -0.3412085 -0.1757588 0.9234099 -0.9991934 -0.02635002 0.03030252 -0.9819276 -0.1315127 0.1360974 -0.9809306 -0.1645393 0.1034507 -0.9404112 -0.2583029 0.2211482 -0.9435328 -0.2615058 0.2033733 -0.876677 -0.355208 0.3244453 -0.8803781 -0.3812622 0.2820879 -0.7875387 -0.4675222 0.4015045 -0.8044242 -0.4592464 0.3768215 -0.6829842 -0.5381509 0.4938889 -0.7025839 -0.5587868 0.4406055 -0.5385304 -0.6272404 0.5626318 -0.5831433 -0.6167455 0.5287428 -0.3849257 -0.6655409 0.6394431 -0.2870574 -0.6086019 0.739731 -0.6921328 -0.7118148 0.1194651 -0.5252064 -0.829149 0.1914954 -0.5455643 -0.8307829 0.11027 -0.3659257 -0.9013845 0.231526 -0.4632999 -0.8728341 0.1533429 -0.225986 -0.9293134 0.2920741 -0.2903583 -0.9425479 0.1652138 -0.680603 0.05360144 0.7306891 -0.5825799 -0.5533838 0.5952873 -0.6339432 -0.3947116 0.6650706 -0.6687228 -0.2477495 0.7010207 -0.2893381 -0.9097153 0.2978281 -0.3436934 -0.8715451 0.3496914 -0.394784 -0.8296853 0.3946745 -0.4335357 -0.7832283 0.4456458 -0.5609238 -0.5903322 0.5804072 -0.4942082 -0.8680304 0.04776465 -0.1702753 -0.9696594 0.1754053 -0.06913399 -0.9967521 0.04130303 -0.1346437 -0.9806337 0.1422277 -0.02845627 -0.9989319 0.03640615 -0.07116943 -0.9788396 0.1918543 -0.1014045 -0.9762548 0.1914253 -0.4031405 -0.8290323 0.3875349 -0.2686088 -0.8783122 0.395496 -0.4840546 -0.5551562 0.6763821 -0.3706606 -0.6905753 0.6210609 -0.4259791 -0.5900788 0.6858199 -0.3896284 -0.5032248 0.7713329 -0.6992373 -0.07192516 0.7112622 -0.6690618 -0.1944463 0.7173194 -0.5312725 -0.1942327 0.8246352 -0.5715407 -0.01565581 0.8204244 -0.4702748 -0.2331684 0.8511605 -0.1083933 -0.7117439 0.6940257 -0.3440243 -0.5136831 0.785988 -0.3767488 -0.503254 0.7776862 0.1602561 -0.6439684 0.7480793 0.1404169 -0.6648294 0.7336791 0.1060658 -0.8359374 0.5384783 0.1020187 -0.9411066 0.3223516 0.1827847 -0.2308862 0.9556576 0.1827617 -0.2308744 0.9556648 0.1655403 -0.4728291 0.8654646 -0.08724486 -0.6371859 0.7657563 -0.1610916 -0.6399427 0.7513474 -0.204185 -0.2265524 0.9523563 -0.2041787 -0.2265431 0.9523599 0.8060854 -0.4529783 0.3808373 0.1365418 -0.9884619 -0.06556934 0.9876116 -0.1425783 0.06553548 0.9434431 -0.3315138 -0.003736674 0.9218249 -0.3830168 0.05947279 0.886183 -0.457814 0.07131689 0.999297 -0.02471941 0.02818739 0.9990902 -0.03739041 0.02051335 0.9803954 -0.1663129 0.1056635 0.9451193 -0.2498914 0.2104853 0.9396022 -0.2684926 0.2122719 0.9320351 -0.1024888 0.3475726 0.9731745 -0.0103988 0.2298334 0.9984531 0.002693951 0.05553585 0.8660969 -0.11679 0.4860415 0.9357606 -0.06798917 0.3460198 0.2404307 -0.9280189 0.2845594 0.3566421 -0.9079976 0.2198792 0.4726858 -0.8661135 0.1625287 0.4902184 -0.8585287 0.1503811 0.6485519 -0.7431087 0.1648333 0.659887 -0.7355504 0.1533452 0.7307489 -0.6746836 0.1039628 0.7866711 -0.4731069 0.3966339 0.7160863 -0.5198845 0.4657687 0.5856301 -0.6115199 0.5320534 0.5370602 -0.6319094 0.5587997 0.2168118 -0.9353263 0.2795663 0.3405491 -0.8261745 0.4488453 0.3781937 -0.6665228 0.6424305 0.3863158 -0.6614827 0.642807 0.4354923 -0.4712753 0.766972 0.8651399 -0.488938 0.1116819 0.7536891 -0.652886 0.07545131 0.8884283 -0.3415905 0.3066127 0.872524 -0.3901581 0.2940723 0.855102 -0.1030039 0.5081248 0.7775987 -0.169716 0.6054229 0.6876252 -0.219613 0.6920562 0.7024356 -0.1768057 0.6894374 0.5731338 -0.2250212 0.7879614 0.589189 -0.2175608 0.778154 0.4282703 -0.2605417 0.8652761 0.4564726 -0.2309517 0.8592404 -0.1404777 -0.9900838 0 -0.25789 -0.9624629 0.08460432 -0.3368297 -0.9408923 0.03560155 -0.7469209 -0.6648887 0.005680143 -0.665782 -0.744493 0.0496447 -0.7069244 -0.7069181 0.02290749 -0.5439335 -0.8391284 4.34345e-4 -0.4114282 -0.9114418 -9.27611e-4 -0.999999 -0.001490771 0 -0.9979828 -0.0634855 7.24593e-5 -0.9620342 -0.2727498 0.009898662 -0.9659071 -0.2588153 0.00617963 -0.8779001 -0.4788438 6.17033e-6 -0.8528986 -0.5220767 -5.63434e-6 0.864885 -0.5019702 -2.03108e-4 0.9999989 -0.001510381 0 0.9709382 -0.2393283 0.001028835 0.9621356 -0.2723857 0.01005905 0.997983 -0.06348198 7.3627e-5 0.748174 -0.6634877 0.00443834 0.6787397 -0.7319247 0.05998933 0.7539802 -0.6568034 0.01110768 0.3291857 -0.9358586 0.1257197 0.3747248 -0.9244961 0.06991684 0.4487716 -0.8936423 -0.002783834 -0.08664906 -0.995081 -0.04802131 -0.9850078 -0.1722895 -0.008721947 -0.3434565 -0.9391606 -0.003893494 -0.1945011 -0.9778169 -0.077739 -0.5554161 -0.8312456 -0.02332425 -0.6471145 -0.7609815 -0.04636949 -0.8313908 -0.5555177 -0.01377242 -0.8681694 -0.4953573 -0.03005409 -0.9807837 -0.1950858 -0.002262473 -0.9849969 -0.1723679 -0.008400559 -0.8314648 -0.5555775 -6.35018e-5 -0.8037003 -0.5949248 -0.01142287 -0.9118381 -0.4105483 0.001256942 -0.9751651 -0.2212769 -0.009478211 -0.1950799 -0.980737 -0.009933888 -0.226662 -0.9739667 -0.003652989 -0.5555682 -0.8314532 0.005439519 -0.4610908 -0.8870043 -0.02487361 -0.6363372 -0.771411 3.08051e-5 0.5620676 -0.8262003 -0.03838396 0.608507 -0.7930226 -0.02888607 0.7474596 -0.6629836 -0.04191672 0.7931229 -0.6085841 -0.02411371 0.8573043 -0.5142782 -0.02340108 0.965859 -0.2588008 -0.01177054 0.9293884 -0.3670074 0.03927928 0.9938601 -0.1105245 -0.005138635 0.4139893 -0.9093017 -0.0422306 0.2587763 -0.9657716 -0.01789158 0.1637409 -0.9853534 -0.04761898 0.9959668 -0.08972185 -5.40277e-4 0.9657995 -0.2587906 -0.01609438 0.2426582 -0.9701119 -2.5302e-5 0.2588174 -0.9659126 -0.005148112 0.6087653 -0.7933444 0.003122389 0.9682176 -0.2494658 -0.01793432 0.8959835 -0.4440818 0.002251505 0.7933501 -0.6087591 -0.00283885 0.779673 -0.6261869 -3.10785e-5 0.5955435 -0.8033231 4.01514e-5 -2.59967e-4 -1 -4.12298e-5 -2.60064e-4 -1 -4.56738e-5 -0.1861479 0.6947687 -0.694727 -0.508594 0.6947419 -0.5085922 -0.6947462 0.6947462 0.1861598 0.6947363 0.6947556 0.1861614 0.6947498 0.6947433 -0.1861574 0.6947435 0.6947498 -0.1861564 0.1861769 0.6947488 -0.6947391 0.1861399 0.6947705 -0.6947273 -0.9831955 2.3469e-4 0.182556 0.3977267 -2.82457e-4 0.9175039 0.3974751 0 0.917613 -0.01276069 -0.05588108 0.998356 -0.07781016 0 0.9969682 -0.3612847 0 0.9324556 -0.4684738 -0.07029926 0.8806761 -0.9831535 0 0.1827823 -0.822004 0 0.5694817 -0.5708256 0 0.8210714 -0.3966044 -8.09846e-6 0.9179896 0.9841371 3.35672e-5 0.1774102 0.9841424 0 0.1773808 0.8272952 0 0.5617675 0.8272445 0 0.5618422 0.5744331 0 0.8185516 0.4740738 -0.07114487 0.8776062 -0.3966128 0 0.917986 0.01656597 0 0.9998628 0.01624441 0 0.9998682 0.3636718 0 0.9315271 0.8944391 0.2676211 0.3582706 0.3337631 -1.24618e-4 0.942657 0.469621 0.1540248 0.8693287 0.9914965 0.07507425 0.1062952 0.9761827 -0.1269109 0.1759575 0.6302463 0.1967385 0.751055 0.9617982 0.05451953 0.2682759 0.977449 0.063564 0.201378 0.9410201 0.2633173 0.2124739 0.9492126 0.1906864 0.2502687 0.9783222 0.1150623 0.1721816 -0.393962 -0.1114763 0.9123416 -0.3360279 0.03408539 0.9412351 -0.3328182 0.2046323 0.9205204 -0.4396815 0.1529304 0.8850381 -0.4401896 0.3097065 0.8428019 0.01633858 0.09456342 0.9953848 0.04887086 0.1546737 0.9867562 0.04867029 0.1699692 0.9842468 -0.2056612 0.1597057 0.9655038 -0.2057332 0.3470692 0.9149956 -0.43206 0.3081662 0.8475598 -0.4012489 0.423959 0.8119472 0.7991897 0.130975 0.5866357 0.7965753 0.1608741 0.5827414 0.8270688 0.1415701 0.5439808 0.8264052 0.3425086 0.4469254 0.8462945 0.3216936 0.4246164 -0.06020611 0.6676808 0.7420092 0.2114862 0.6638506 0.7173395 0.1576805 0.6520846 0.7415677 0.4452818 0.6105634 0.6549324 0.1178681 0.5935981 0.7960832 0.5679715 0.4943847 0.6580215 0.6290287 0.4718969 0.6177671 0.6827329 0.4380164 0.5848227 0.7836854 0.3729537 0.496732 -0.288491 0.638323 0.7136643 -0.1145174 0.6745252 0.7293159 -0.1147215 0.5112163 0.8517612 0.157657 0.5260251 0.8357285 0.09996259 0.5075874 0.8557819 0.3803846 0.4898671 0.7844348 0.8253986 0.06646811 0.560624 0.595621 8.64398e-4 0.8032652 0.5889111 0.2142384 0.7792855 0.3293697 0.2382661 0.9136438 0.3777057 0.247045 0.8923605 -0.1303785 0.2437769 0.9610277 0.1001706 0.3552313 0.9293958 -0.1721132 0.3377979 0.9253484 -0.1718375 0.5202369 0.8365557 -0.4500686 0.4530674 0.7695248 -0.1593253 0.6374797 0.7538139 -0.727235 0 0.6863886 -0.532761 -7.34167e-4 0.8462656 -0.09948122 -0.007203876 0.9950134 -0.7247514 0.01000016 0.688938 -0.6191573 0.003899276 0.7852573 -0.3114612 -0.001727342 0.9502574 -0.2170255 -0.003441452 0.9761599 0.3369908 1.33989e-5 0.941508 -0.390345 0.003881156 0.9206604 -0.1902016 1.84782e-4 0.9817451 0.03589683 -1.9864e-4 0.9993555 0.1141285 -0.001635015 0.9934647 0.1804988 -7.0128e-4 0.9835751 0.2661997 -3.02914e-5 0.9639179 0.6357078 -3.7407e-4 0.7719298 0.5658381 -0.001518607 0.824515 0.4683436 -0.003448665 0.8835398 0.3769759 -1.36863e-4 0.9262232 0.4758318 -7.69554e-4 0.879536 0.6746715 0.00407356 0.7381069 0.8519953 -0.001664757 0.5235468 0.8931177 3.58435e-4 0.449823 0.7889735 -5.94479e-5 0.6144273 0.7703421 -1.80116e-4 0.6376309 0.7546812 -1.75389e-5 0.6560918 0.7038877 1.12183e-5 0.7103114 0.9334026 1.79976e-4 0.358831 0.987642 -3.56e-4 0.1567265 0.9902967 -1.14856e-6 0.1389693 -0.640628 3.98625e-5 0.7678514 -0.7690376 -2.51893e-5 0.6392037 -0.7895787 3.21934e-4 0.6136492 -0.8929829 -5.37279e-4 0.4500905 -0.9051377 -5.60272e-5 0.4251185 -0.9876525 7.4318e-5 0.1566609 -0.981438 -7.36796e-4 0.1917786 -0.999307 -2.10296e-5 0.03722226 -0.01267659 -0.00333321 0.9999142 -0.1646571 -8.09182e-4 0.9863506 -0.2909157 1.48488e-4 0.9567488 -0.4759991 -4.6243e-4 0.8794457 -0.3650591 -0.003223001 0.9309788 -0.6730972 0.004508554 0.7395403 -0.458464 -0.003561794 0.8887059 -0.5459012 -0.001855194 0.8378475 -0.115572 -1.82522e-4 0.9932991 0.2175263 1.20764e-4 0.9760545 0.2199102 1.71817e-4 0.9755201 0.7366752 1.59948e-5 0.6762468 0.5628609 1.56107e-4 0.8265516 0.6247548 0.003169715 0.7808147 0.4264854 -1.08268e-4 0.9044946 -0.04938662 0.1572393 0.9863249 0.5107342 0.3278928 0.794756 0.440998 0.2684921 0.8564069 0.4395675 0.1528697 0.8851053 0.4086633 0.3131894 0.857267 0.4090581 0.466124 0.7844744 0.04040461 0.6267541 0.778169 0.2445383 0.6394569 0.7289005 -0.9831311 0.006652176 0.1827815 -0.3774891 0.2470315 0.8924559 -0.5951007 0.4847159 0.6410192 -0.3806565 0.4897183 0.7843958 -0.1714486 0.5763511 0.7990149 -0.4697663 0.602851 0.6448956 -0.9922471 0.03559172 0.119076 -0.9671486 0.08333188 0.240166 -0.9645718 -0.07983684 0.2514505 -0.7998421 0.120507 0.5879886 -0.8198295 0.07231444 0.5680232 -0.5955762 -0.002265572 0.8032957 -0.4640035 0.152735 0.8725669 0.2066706 0.258921 0.9435292 0.2059904 0.3336462 0.9199175 0.1722671 0.3509473 0.920413 0.1721091 0.5029829 0.8469868 0.1146578 0.5281609 0.8413677 0.1150362 0.6463042 0.7543591 -0.02441596 0.700897 0.7128444 0.397386 0.03288322 0.9170622 0.3329291 -0.0739938 0.9400443 0.3349965 0.1500827 0.9301896 -0.04919975 0.1699589 0.9842223 0.32603 0.3157557 0.8910684 -0.09841769 0.2535886 0.9622925 -0.09962701 0.526133 0.8445465 -0.1574113 0.5073379 0.8472485 -0.1574867 0.6734851 0.7222298 -0.244956 0.6471079 0.721975 -0.6912436 0.4443002 0.5698945 -0.6300477 0.463546 0.6230289 -0.8258333 0.3401197 0.4497978 -0.8266831 0.3395266 0.4486835 -0.9696885 0.1428284 0.1982532 -0.9972122 0.04634797 0.05848032 -0.9503642 0.1692609 0.2610726 -0.9498128 0.08639138 0.3006529 -0.827048 0.1415252 0.5440241 -0.7966356 0.1607958 0.5826804 -0.6300446 0.1967142 0.7512305 -0.5888776 0.214187 0.7793248 -0.3294302 0.2381933 0.9136409 -0.3338344 0.001495957 0.9426306 -0.0126717 0.08983534 0.995876 -0.4981424 0.4002536 0.7691887 -0.2888812 0.7380502 0.6097784 0.2119391 0.7037829 0.6780645 0.4497798 0.6115359 0.6509394 0.7859697 0.3939067 0.4765388 0.573474 0.5587282 0.5991248 -0.1297981 0.9382614 0.3206527 0.6231964 0.04707217 0.7806475 0.7022894 0.2477732 0.6673816 0.6313511 0.1754634 0.7553862 0.6626717 0.378211 0.6463921 0.6930682 0.1877112 0.6960036 0.6751783 0.09852558 0.7310452 -0.2239153 0.08413362 0.9709703 -0.3916807 0.06070661 0.9180964 -0.3173843 0.2560284 0.9130809 -0.5092396 -0.3255248 0.7966861 -0.5093035 -0.2834487 0.8125681 -0.6935294 0.201133 0.6917822 -0.7051906 0.200349 0.6801224 0.4688368 -0.004567861 0.8832731 0.3833914 0.1578532 0.9099964 0.3203794 0.1226806 0.9393117 0.2373801 0.133143 0.9622493 0.2365248 0.1311144 0.9627383 0.09846854 0.07355946 0.9924178 0.1369215 0.2119006 0.9676522 0.03033381 0.03457838 0.9989416 0.9511075 0.2064215 0.2297498 0.973066 0.06977373 0.2197144 0.8935688 0.2595751 0.3662727 0.8460007 0.3166836 0.4289457 0.8373325 0.3238238 0.4404684 0.809888 0.2307879 0.5392757 0.7059311 0.2573462 0.6598744 0.6865047 0.4767262 0.5490386 0.6692393 0.4832602 0.5644276 0.6479503 0.4121916 0.6405143 0.4339416 0.5595473 0.7061173 0.396656 0.5558919 0.7305123 0.3407223 0.4428175 0.8293499 0.9212568 0.06257766 0.383888 0.8945667 0.09411418 0.436913 0.8537966 -0.01009851 0.5205088 0.698302 0.2441055 0.6728945 0.6997129 0.2442683 0.6713679 0.4168834 0.5099707 0.7524216 0.3803209 0.4630128 0.8006093 0.2764164 0.4713054 0.8375353 0.4856034 0.2033464 0.8501996 -0.06346845 0.311051 0.9482717 -0.1099523 0.08793658 0.9900392 -0.07725918 0.1226832 0.9894341 -0.1298046 0.3918743 0.9108158 0.02425223 0.3086503 0.9508664 0.1718965 0.3681549 0.9137361 0.1057484 0.4168401 0.9028077 0.2457603 0.3762786 0.8933175 0.3816699 0.1450141 0.9128522 0.485471 0.218548 0.8464956 0.5725212 0.07225787 0.8166997 0.5298753 0.1205851 0.8394591 -0.06043577 0.7284776 0.6823986 -0.1232811 0.7015687 0.701857 -0.1465602 0.7476726 0.6476928 -0.1378433 0.7549164 0.6411713 -0.1266543 0.7665171 0.6296113 -0.1570649 0.7609924 0.6294611 -0.1433115 0.7742919 0.6163878 -0.1942039 0.7704609 0.6071862 -0.196259 0.7696169 0.6075955 -0.2458788 0.7818094 0.5729904 -0.2814345 0.7702773 0.5722478 -0.3200175 0.7888236 0.5247345 -0.2315093 0.06026643 0.9709642 -0.2509646 0.2715442 0.929129 -0.382205 0.3934153 0.8361481 -0.3311001 0.2727588 0.9033136 -0.582445 0.2584233 0.7706979 0.4455899 0.6150385 0.6505209 0.2065486 0.7078728 0.6754657 0.1911652 0.657462 0.7288346 0.2004068 0.6568074 0.7269396 0.1588117 0.6034805 0.7814028 0.1395236 0.6088922 0.7808864 0.0570749 0.5500186 0.8331999 0.02443808 0.5686802 0.8221957 -0.1145907 0.5105287 0.8521909 -0.1395314 0.5366412 0.8321942 -0.3225977 0.4952654 0.8066245 -0.33001 0.5125299 0.7927211 -0.5183905 0.5013599 0.6927551 -0.51798 0.4929577 0.6990633 -0.3941088 0.7627471 0.5127331 -0.3211742 0.7955582 0.5137456 -0.4552987 0.6385338 0.6204658 0.5352201 0.3869377 0.7508787 -0.470336 0.6231728 0.6248518 -0.8919317 0.06066679 0.4480819 -0.5352185 0.03623872 0.8439361 0.2453993 0.7457221 0.6194173 0.2562123 0.7397087 0.622243 0.261551 0.8467375 0.4632782 0.2558937 0.8500759 0.4603148 0.2293765 0.8365638 0.4975414 0.2514467 0.8257231 0.5049317 0.2136212 0.8182535 0.533692 0.2766237 0.7897685 0.54749 0.2079694 0.7916026 0.5745555 0.2833963 0.7578616 0.5876499 0.3122088 0.8241641 0.4725244 0.3039658 0.8768671 0.3724365 0.4015823 0.7008807 0.5894896 0.5608222 0.08194667 0.8238709 0.6034446 -0.1569786 0.7818008 0.31993 0.2142046 0.9229091 0.2245301 0.05701488 0.9727979 0.01565319 0.1877402 0.9820941 0.01510506 0.1893964 0.9817846 -0.1384524 0.1347992 0.9811525 -0.24757 0.1806047 0.9518882 -0.2656781 0.2150848 0.9397627 -0.3124326 0.1982251 0.9290278 -0.5963977 0.1449709 0.7894892 -0.6012377 0.1254575 0.7891601 -0.7713702 0.06846386 0.6326932 -0.782651 0.205441 0.5875811 -0.8387562 0.1730608 0.5162734 -0.9699688 0.2046209 0.1314952 -0.693961 0.4728381 0.542994 -0.8273169 0.3534634 0.4365897 -0.869385 0.2731974 0.4117439 -0.9607878 0.1579805 0.2278794 -0.9760288 0.04604285 0.2127155 -0.5982411 0.5323562 0.5989195 -0.6434425 0.4886004 0.5892804 -0.6141995 0.3953979 0.6829491 -0.6190168 0.3866785 0.683592 -0.5090737 0.2480227 0.8242141 -0.5046138 0.2686761 0.8204743 -0.3761318 0.1775606 0.9093939 -0.4614382 -0.01585716 0.8870307 0.4972036 0.5723553 0.6520721 0.405067 0.6817736 0.6091845 0.2987974 0.6866697 0.6627254 0.3167119 0.668326 0.673078 0.1721754 0.7011855 0.6918777 0.1918814 0.6661676 0.7206957 0.08202481 0.7128675 0.6964854 0.0861997 0.6798684 0.7282505 0.02891218 0.7210406 0.6922895 0.02302378 0.7046027 0.7092284 0.009010493 0.7225601 0.6912494 0.01537644 0.7281721 0.6852219 0.01628047 0.7249013 0.6886604 -0.02400606 0.6950486 0.7185618 0.5820923 0.2612647 0.7700061 0.5349689 0.3817095 0.7537282 0.3200094 0.3930858 0.8620195 0.3331843 0.371058 0.866778 0.07815909 0.4285441 0.900134 0.09173029 0.3874737 0.9173058 -0.1173182 0.4754798 0.871869 -0.1163757 0.437164 0.8918209 -0.2503719 0.532482 0.8085647 -0.2563548 0.5134294 0.818946 -0.3217509 0.5961911 0.7355491 -0.3154512 0.6037934 0.7320684 -0.3265379 0.6409146 0.6946953 -0.2460447 0.694998 0.6756033 0.3944979 0.8107665 0.4324686 0.6379995 0.4073092 0.6534951 0.4592093 0.7128124 0.5301182 0.5559332 0.1593787 0.8158044 0.5538001 0.02899265 0.8321448 0.4665053 0.2647758 0.8439589 0.4840491 0.09126722 0.8702684 0.6244811 0.02240133 0.7807188 0.6381941 0.3353213 0.6930137 0.649995 0.299896 0.6982614 0.7181671 0.1078067 0.6874691 0.6772059 0.2787685 0.6809408 0.1006033 0.9936188 0.05099838 0.2521477 0.9174438 0.3077634 0.184019 0.961765 0.2028425 0.3294451 0.8278709 0.4539778 0.2715603 0.8906877 0.3645964 0.3959144 0.7026662 0.5911954 0.3543258 0.773828 0.5250176 0.449773 0.5447543 0.7077761 0.4175071 0.6288055 0.6559662 0.4855698 0.3621529 0.7956552 0.4652834 0.4485729 0.7630817 0.5000265 0.1663298 0.8498871 0.5054852 -0.09233856 0.8578801 0.5237504 0.03331536 0.8512201 0.545052 0.5819929 0.603492 0.6220303 0.4582296 0.6349048 0.5945532 0.4546704 0.6631602 0.6222931 0.3972916 0.6744708 0.4806766 0.6867611 0.5452607 0.4596547 0.7179104 0.5228025 0.4534118 0.7177271 0.5284749 0.4130108 0.7602691 0.5014112 0.4220595 0.7614089 0.4920593 0.3385603 0.829322 0.4445247 0.5610176 -0.4003252 0.7245682 0.6380164 0.1469041 0.7558798 0.5958952 0.3963028 0.6984649 0.6036006 0.3472749 0.7176814 0.5565183 0.5299676 0.6398607 0.3074784 0.9114213 0.2734377 0.4023635 0.810019 0.4265828 0.3938947 0.8205813 0.4141175 0.4727901 0.6875157 0.5511732 0.4693934 0.6940371 0.5458777 0.5287547 0.5326333 0.6608482 0.5278881 0.5352033 0.6594632 0.5648069 0.3512294 0.746747 0.5646517 0.3521068 0.7464511 0.5774641 0.1531258 0.8019276 0.5607057 -0.1749175 0.8093287 0.5900417 0.02549958 0.8069701 -0.164451 0.9356788 0.3121876 -0.4834239 0.09128057 0.8706144 -0.685409 0.1968759 0.7010381 -0.1097146 -0.9829221 0.1477394 -0.5651926 0.4958386 0.6593189 -0.553704 0.129584 0.8225691 -0.2875215 0.9140686 0.2860248 -0.1381324 0.9849202 0.1041725 -0.3504469 0.8260906 0.4413177 -0.4627416 0.2828581 0.8401557 -0.5109052 -0.08720552 0.8552024 -0.441416 0.4657119 0.7669841 -0.5169258 0.1344254 0.8454098 -0.3940503 0.6517653 0.6480173 -0.07064324 0.9957867 0.05846673 -0.1119631 0.9864798 0.1196745 -0.4093229 0.7014859 0.5834144 -0.3009858 0.8492735 0.4337538 -0.4527872 0.5443758 0.7061436 -0.5047103 0.3600981 0.7845998 -0.5022925 0.6481133 0.5724084 -0.5633807 0.5290854 0.6345636 -0.5733373 0.5045155 0.6455606 -0.6282944 0.3444681 0.6975585 -0.6635929 0.1438524 0.7341328 -0.3846565 0.808018 0.4462581 -0.4633415 0.7012913 0.5417612 -0.4658765 0.6881545 0.5562396 -0.567901 -0.008349537 0.8230545 -0.5496968 -0.2405819 0.7999711 -0.5558601 0.3534797 0.7523774 -0.5861227 0.152326 0.7957745 -0.5191396 0.5364462 0.6653718 -0.5733366 0.3505412 0.7405444 -0.4607525 0.6953401 0.5515518 -0.537029 0.5318624 0.6547689 -0.3855667 0.8218484 0.4194087 -0.4806275 0.6868242 0.5452244 -0.2996087 0.9125365 0.2784093 -0.3976972 0.8231983 0.4051932 -0.359877 0.193347 0.9127462 -0.1794011 0.8542478 0.4879305 -0.3696495 0.09094744 0.9247097 -0.351929 0.2817827 0.8926056 -0.3294585 0.439568 0.8356059 -0.324425 0.4644557 0.8240324 -0.2857396 0.6296994 0.7223792 -0.2784 0.6510617 0.7061247 -0.1393455 0.9250211 0.3534384 -0.2303434 0.8513774 0.4712734 -0.1532817 0.9356906 0.3177859 0.6989906 0.4290636 0.5721159 -0.1170524 0.267026 0.9565542 -0.2618131 0.06013947 0.9632431 -0.2166 0.1939114 0.9568087 -0.1682351 0.1294801 0.9772062 -0.1074985 0.1124426 0.9878263 -0.009103953 0.1672645 0.98587 -0.08373934 0.06887167 0.9941049 -0.04236578 0.07172667 0.9965242 0.02896136 0.04280525 0.9986636 0.02163487 0.04247409 0.9988633 0.7877752 0.1913244 0.5854959 0.8572521 0.2350967 0.4580923 0.742176 0.05154496 0.6682201 0.1919739 0.817247 0.5433723 0.002809882 0.8692551 0.4943559 -0.02409434 0.84842 0.528775 0.2497484 0.7455368 0.6179002 0.2225318 0.6319178 0.7424012 0.3411048 0.5418295 0.7681591 0.3477311 0.5618329 0.7506178 0.4933226 0.3978334 0.7735383 -0.191797 0.4405051 0.8770229 -0.1926059 0.4046075 0.8939776 -0.03023362 0.3575688 0.9333974 -0.004149019 0.4249771 0.9051946 0.1178822 0.3336508 0.9352973 0.1266736 0.3575564 0.9252606 0.2261896 0.2491325 0.9416853 0.253023 0.2729438 0.92816 0.3265394 0.08707875 0.9411638 -0.1122446 0.62807 0.7700191 -0.105812 0.6906703 0.715387 0.05755734 0.6470896 0.7602384 0.1961023 0.8191847 0.5389626 0.3589345 0.7572814 0.5456107 0.2559121 0.4961277 0.8296784 0.2860354 0.512179 0.8098496 0.8180699 0.5293393 0.2248597 0.5151159 0.4169687 0.748861 0.6260462 0.1342902 0.7681357 0.4138134 0.1205536 0.9023444 0.02192813 -7.60417e-4 0.9997593 0.7432491 8.53642e-4 0.6690143 0.7434878 0 0.6687495 0.4170758 0 0.9088717 0.02172464 0 0.999764 0.03364729 0.9957787 0.08539634 0.06669276 0.9841579 0.1642722 0.09761726 0.9639341 0.2475923 0.1654794 0.8924462 0.41971 0.2009872 0.840954 0.5023949 0.2319278 0.7747098 0.5882468 0.2852278 0.62874 0.7234163 0.2903062 0.6127947 0.7349864 0.3307144 0.429673 0.8402436 0.3652689 0.09091418 0.9264521 0.362826 0.1749819 0.9152806 0.3538081 0.2637346 0.897365 0.3279378 0.4479057 0.8317676 -0.3118519 0.8018113 0.5097519 -0.1818749 0.174725 0.9676738 -0.5140621 0.1720594 0.8403189 -0.4230693 -0.110291 0.89936 -0.8281826 0.1720701 0.5333905 -0.7941365 -0.03485381 0.6067392 0.03842377 0.1757255 0.9836891 0.2816013 0.2216272 0.9335857 0.157173 0.1762568 0.9717152 0.1439102 0.3864471 0.9110152 -0.09921628 0.03753823 0.9943576 -0.07869547 0.6097213 0.7886996 0.1440412 0.3864259 0.9110035 -0.3118596 0.8018027 0.5097607 -0.5024073 0.8018007 0.3235776 -0.5023976 0.8018054 0.3235816 -0.5846864 0.8047463 0.102593 -0.8381061 0.5253108 0.1470609 -0.8381004 0.5253203 0.1470593 -0.4453055 0.5213911 0.7279109 -0.4453039 0.5213987 0.7279065 -0.1655777 0.5279604 0.8329718 -0.1260929 0.8073578 0.5764322 -0.1619399 0.8498995 0.5014442 0 1 -3.30237e-6 -0.1411363 0.4052363 0.903252 0.1800479 -0.03879767 0.9828924 -0.04285168 0.1757916 0.9834944 -0.2843846 0.1739667 0.9427943 0.521613 0.02974879 0.8526635 0.7815093 0.1746283 0.598956 0.8400267 0.0405451 0.5410279 0.895159 0.1757948 0.4096177 0.1349068 0.7635704 0.6314749 0.5846882 0.8047448 0.1025937 0.5024037 0.8018021 0.3235799 0.3118464 0.8018062 0.5097634 0.3118641 0.8018076 0.5097506 0.122766 0.807173 0.5774084 0.1604789 0.8528124 0.4969484 -0.1443915 0.3865226 0.910907 0.09780591 0.1720573 0.9802196 0.4163569 0.1752818 0.8921453 0.04929059 0.6360624 0.7700617 0.1771401 0.5286065 0.8301787 0.4453111 0.5213934 0.7279059 0.4452992 0.5213925 0.7279139 0.8381017 0.5253181 0.1470602 0.8147947 2.47852e-4 0.5797496 0.7492204 -0.03140211 0.661576 0.7936931 -0.005574643 0.6082929 0.6337319 0.004453778 0.77354 0.6142284 -0.00457704 0.7891151 0.5312428 7.91363e-5 0.8472197 0.4229115 -7.39804e-4 0.9061707 0.4289067 -0.003471493 0.9033423 0.18019 0.004681646 0.9836207 0.1878472 0 0.9821982 -0.2093378 0.05440807 0.9763286 -0.288762 -3.89041e-6 0.9574009 0.9999991 0 0.001442253 0.998643 -1.12424e-4 0.05207955 0.9738512 -0.01302498 0.2268134 0.9336904 -0.06148946 0.3527627 0.8832291 -5.07486e-5 0.4689419 0.909312 -0.002722561 0.4161064 0.9845359 0.02908474 0.1727518 0.2599096 0.9643535 -0.04969424 0.9843241 0.176369 0 0.9909707 0.1337484 -0.009409844 0.9911625 0.1326349 -0.002222895 0.8473136 0.5310838 0.003122806 0.874465 0.4850884 -6.17684e-4 0.3696108 0.9291628 -0.006664872 0.5634181 0.8253884 0.03597444 0.5877897 0.8090137 4.62033e-4 -0.5387816 -0.3122762 -0.7824308 0.447236 0 -0.894416 0.538863 -0.3119238 -0.7825155 -0.9747205 0.2232323 -0.00934273 -0.5877882 0.809015 0 -0.6501092 0.7557502 -0.07873868 -0.4858255 0.8738629 0.01836913 -0.2468522 0.9685382 -0.03158766 -0.5782446 0.8158633 -6.21274e-4 -0.8473178 0.5310856 7.64199e-4 -0.8142604 0.5804927 -0.002872347 -0.9843185 0.176376 0.002956867 -0.9749591 0.2223848 -1.52666e-7 -0.9852738 -0.02013021 -0.1697947 -0.9656582 0.08453512 -0.2456788 -0.9943879 -0.001690566 -0.1057821 -0.9185776 0.00187093 0.3952362 -0.9832206 -0.005604505 0.1823343 -0.9663627 -0.0322045 0.2551589 -0.9772443 -0.02186703 0.2109868 -0.9823263 -0.01645982 0.1864513 -0.9886086 -0.01007771 0.1501716 -0.9953981 -0.003292977 0.0957697 -0.9992588 -3.59913e-4 0.03849697 -0.9999694 0 0.007835865 -0.8524719 -2.77112e-6 0.5227732 -0.7983461 -0.0486024 0.6002345 -0.8622728 -0.01414948 0.5062465 -0.9978026 -0.0662586 0 -0.9848744 -0.1732585 -0.002019405 -0.9466494 -0.3222544 0.002668201 -0.9064794 -0.4222503 0 -0.7933307 -0.6087901 -0.001043617 -0.6774622 -0.7355502 0.003315985 0.9827647 -0.02338838 -0.1833757 0.9843463 -0.00165832 -0.1762375 0.9999536 -0.001662015 -0.009494364 0.9980308 0.05009877 0.03774464 0.5578207 0.8171578 -0.1452217 0.7260586 0.6789513 0.1089236 0.8669153 0.4809174 -0.1310594 0.9765766 0.2029054 -0.07160741 0.9885307 0.1333551 0.07087641 0.9266643 0.3757242 0.01117217 0.8614449 0.4861271 -0.146947 0.8591267 0.5058518 0.07755947 0.7310883 0.6801217 0.05426263 0.7189501 0.6824523 0.1317943 0.5054867 0.862802 0.007480561 0.5141264 0.8577002 -0.00492537 0.4240078 0.8942703 -0.1431713 0.3646675 0.9273915 -0.08344268 0.4424386 0.8961947 -0.03291201 3.22118e-6 1 1.23433e-5 9.53185e-6 1 2.81218e-5 5.29467e-5 1 -5.07857e-5 9.54831e-5 1 -4.7673e-5 3.36613e-7 1 0 -2.04841e-4 1 -1.83643e-5 -8.09185e-5 1 -4.09714e-5 -3.36572e-7 1 0 3.18579e-5 1 1.61657e-5 -3.22118e-6 1 1.13147e-5 -2.66458e-6 1 1.35471e-5 2.66458e-6 1 1.35471e-5 -0.4069663 0.9086781 -0.09318035 -0.5096234 0.8603916 -0.003249168 -0.9974276 0.06092911 0.03776055 -0.8126065 0.5792862 -0.06401783 -0.7265807 0.6791986 0.1037773 -0.6520597 0.7580615 0.01269447 -0.4850803 0.8725604 0.05775517 -0.9696426 0.2220329 -0.1024433 -0.9695761 0.2277576 -0.08971536 -0.8901588 0.4454951 0.09566432 -0.8919433 0.4463483 0.0721845 -0.7307019 0.6793946 0.06706517 -0.677515 0.6727284 0.2973379 -0.456094 0.8815327 -0.1219776 0.8334271 -0.5526283 -0.001146972 0.8435832 -0.5369986 -2.26807e-6 0.536872 -0.8436638 -3.56135e-6 0.7823129 2.069e-6 0.6228856 0.852309 -0.0194565 0.5226766 0.8605117 -0.01444256 0.509226 0.9997068 -9.38894e-5 0.02421462 0.9960191 -0.002299785 0.08911103 0.9895183 -0.009361743 0.1441039 0.9851686 -0.0135895 0.1710504 0.9831126 -0.01581019 0.1823175 0.9646887 -0.002934992 0.2633765 0.919145 0.00192517 0.3939147 0.9638851 -0.2510256 -0.08894824 0.9883258 -0.002264201 0.1523386 0.9859211 -0.06772649 -0.1528818 0.9998965 -0.004769861 0.01358056 0.9986082 -0.03665983 0.03791755 0.9974784 -0.02395045 0.06680774 0.9916242 -0.08122658 0.1004187 0.9717199 -0.03769946 0.2331076 0.9676737 0.03669464 0.2495219 0.9732412 -0.162563 0.1624036 0.9772188 -0.130689 0.1672245 0.9537564 -0.2932991 0.06576055 0.9311146 -0.359606 0.06090211 0.8988184 -0.4357058 -0.04781395 0.9997573 0.003093302 0.02181679 0.9819588 -0.1117282 -0.1525574 0.9741591 -0.2127147 -0.07593739 0.9567307 -0.2192363 -0.1913164 0.963449 -0.2349423 -0.1287178 0.7056583 -0.1766083 0.6861894 -0.0364775 -0.9878966 0.1507634 -0.03773152 -0.9843495 0.1721407 0.5646078 0.1224897 0.8162196 0.6107761 -0.1736173 0.7725347 0.3438711 -0.1756631 0.9224398 0.2320896 0.1615036 0.959193 0.1173452 -0.1756635 0.9774316 -0.2321785 0.1591748 0.9595606 -0.3525344 -0.1758462 0.9191287 -0.5676757 -0.175182 0.8043977 -0.7122758 -0.1772057 0.6791623 -0.3357353 -0.840801 0.4246593 -0.3357118 -0.8408194 0.4246417 -0.1281564 -0.8384664 0.52967 -0.1281479 -0.8384685 0.5296687 0.1281419 -0.8384651 0.5296754 0.3357103 -0.8408148 0.4246518 0.3357359 -0.8408073 0.4246461 -0.5240674 -0.5347805 0.6628448 -0.1992405 -0.531173 0.8235037 -0.1992757 -0.5311127 0.8235342 0.5240696 -0.5347622 0.6628578 0.5240683 -0.5347737 0.6628495 -0.987402 -0.002909362 0.1582053 -0.9859924 -0.04075419 0.1617349 -0.9821821 -0.0749036 0.1723601 -0.9444509 -0.2359542 0.2287757 -0.9700325 -0.05530476 0.236598 -0.9998661 -0.01427143 0.008017539 -0.9983527 -0.04008567 0.04105055 -0.997938 -0.03640711 0.05286127 -0.9831285 -0.111267 0.1451826 -0.9230018 -0.3847148 0.00788325 -0.9513907 -0.3079745 -0.002741396 -0.985969 -0.04954731 -0.1594057 -0.9843615 -0.08945763 -0.1517561 -0.9842837 -0.09521108 -0.1487296 -0.9795528 -0.143541 -0.1409698 -0.9789192 -0.1601178 -0.1268061 -0.9686985 -0.230057 -0.0932576 -0.968777 -0.2176611 -0.1187222 -0.9680188 -0.2301822 -0.09977883 -0.631145 0.004325807 0.775653 -0.4054704 -0.001253426 0.9141073 -0.2485592 0.002754509 0.9686128 -0.1126739 -0.005001485 0.9936195 0.3136488 -2.61965e-4 0.949539 0.1049022 -0.00341016 0.9944768 0.7799655 5.20991e-4 0.6258223 0.7061133 -8.1473e-5 0.7080989 0.5492458 -0.002602338 0.8356569 0.5994135 -0.01273804 0.8003383 0.4297991 9.53167e-4 0.902924 0.8550184 0.01244741 0.5184483 0.9869758 -0.005520701 0.1607747 0.9931614 0 0.1167502 -0.8236703 -0.430428 0.3691869 -0.3968152 -0.8996447 0.1821461 -0.5721502 -0.7940512 0.2052483 -0.8206612 -0.5644868 0.08871293 -0.9567564 -0.2889428 -0.03360319 -0.9837689 -2.16213e-5 -0.1794405 -0.6073462 -0.7491495 0.2643969 -0.197193 -0.9634722 -0.1812078 -0.3853741 -0.9210571 0.05604237 -0.9811464 -0.06516242 0.1819496 -0.9811458 -0.06515467 0.1819553 -0.8506556 -0.0651648 0.521669 -0.9323975 -0.3173912 0.1729099 -0.9139615 -0.3569207 0.1930856 -0.8184123 -0.3579791 0.4495026 -0.7270581 -0.5588537 0.3988347 -0.834565 -0.5287216 0.1547737 -0.6523413 -0.7452954 0.1377891 -0.40894 -0.9099113 0.06949478 -0.3983454 -0.9119735 0.0981087 -0.868312 -0.4820727 0.1167925 -0.8673169 -0.4685182 0.1680844 -0.9208982 -0.3047421 0.2430614 -0.9230069 -0.2628867 0.2809785 -0.943048 -0.09777498 0.3179636 -0.9408619 -0.1094521 0.3206231 -0.8881902 -0.1565006 0.432002 -0.8580793 -0.3582242 0.3679339 -0.8966061 -0.1631821 0.4116665 -0.7898437 -0.2274469 0.5695743 -0.8217979 -0.1746681 0.5423463 -0.8041942 -0.5400516 0.248226 -0.822115 -0.5169247 0.2385707 -0.7588869 -0.5581446 0.3355075 0.7837464 0.6185976 -0.05548638 0.468919 0.883114 0.01499116 0.4945909 0.8690683 -0.01001662 -0.4674862 0.8839146 0.01231497 -0.5392602 0.8412724 -0.03820085 -0.4821588 0.8760817 -0.001968085 -0.4561127 0.8893322 0.03239554 0.9197797 -0.3534278 0.1705704 0.8309872 -0.5313392 0.1647387 0.823647 -0.5461448 0.1527462 0.5343005 -0.8394637 0.09911525 0.3630461 -0.929426 0.06606775 0.06182092 -0.9980732 0.005304872 0.2311717 -0.9725206 0.02762752 0.335693 -0.9401268 0.05892443 0.797297 -0.3782131 0.4703961 0.7554512 -0.5405592 0.3702558 0.7552502 -0.5351334 0.3784569 0.5828796 -0.7582272 0.292135 0.9688513 -0.1704263 0.1796725 0.9688524 -0.170422 0.1796701 0.8460801 -0.1707875 0.5049557 0.8429066 -0.1494 0.5169026 -0.9996852 0 0.02509158 -0.987132 -0.003749668 0.1598643 -0.9861835 -0.002877295 0.1656318 -0.9356211 0.001291453 0.3530036 -0.8567515 -0.009524703 0.5156416 -0.8444387 -0.005881309 0.53562 -0.6933149 0.003320634 0.7206272 -0.4842925 -8.86924e-4 0.8749058 0.4183311 -3.99727e-4 0.9082946 0.2923775 -0.004350066 0.9562931 0.2913491 -0.004444658 0.9566066 0.08735799 0.001395165 0.996176 -0.08234769 -0.002608597 0.9966003 0.4964233 1.06582e-4 0.8680806 0.6263465 -0.00100404 0.7795442 0.6404486 1.78187e-6 0.7680011 0.7686923 -0.1217665 0.6279212 0.8900746 -0.1880964 0.4151952 0.8104855 -0.5242494 0.2612964 0.8109982 -0.5236082 0.2609913 0.8722674 -0.2701736 0.4076223 0.8022789 -0.0778017 0.5918577 0.7933228 -0.1131166 0.5982003 0.8115671 -0.2534269 0.5264348 0.790039 -0.3175894 0.5243811 0.7940747 -0.3553877 0.4930972 0.764338 -0.5411248 0.3506731 0.8510684 -0.5153684 0.10039 0.8891385 -0.4480343 0.09326344 0.9008468 -0.3743726 0.2198188 0.9421104 -0.1400439 0.3046571 0.9602478 -0.05785691 0.2730877 0.934152 -0.2223853 0.2791148 0.9721832 0.01080125 0.2339727 0.9919255 0.08355051 0.09541112 0.9945971 -0.0469464 0.09258931 0.3492579 2.94473e-4 0.9370267 0.3642295 -0.01648873 0.9311633 0.5896437 -0.002733767 0.807659 0.7169932 0.001118779 0.6970794 0.8521804 0.01842713 0.5229236 0.8638221 0.01267671 0.5036377 0.9075348 -0.005455911 0.4199417 -0.6071199 -0.002231299 0.7946071 -0.3581572 -9.77166e-6 0.9336614 -0.2240383 -0.002001464 0.9745783 -0.1285034 0.03147053 0.9912096 -0.0950911 0.001414775 0.9954677 0.1192067 9.62267e-4 0.992869 0.0629509 0.07136934 0.9954615 0.1793431 -0.003617942 0.98378 -0.7237668 7.81826e-4 0.6900442 -0.7841405 -0.01885652 0.620297 -0.769213 -0.009760439 0.6389179 -0.8718162 0.0378009 0.4883725 -0.9145676 0.002252817 0.4044268 -0.9885218 -0.003178477 0.1510457 -0.7671359 -0.177374 0.6164746 0.1404441 -0.9700989 0.1979488 0.3799632 -0.833279 0.4015893 0.4511585 -0.7662018 0.4575927 0.4533184 -0.7635167 0.45994 0.9530435 -0.28224 0.1097667 -0.7593201 -0.4838955 0.4350613 -0.7904998 -0.4571285 0.407607 -0.9014766 -0.2951915 0.3165472 0.4335424 -0.7098679 0.5550932 0.4616094 -0.692576 0.5543061 0.2530679 -0.7500533 0.6110456 0.2911012 -0.7399621 0.6063961 0.09561723 -0.7741348 0.6257576 0.1001313 -0.7730254 0.6264228 -0.08017086 -0.7620387 0.6425493 -0.2475738 -0.7446215 0.6198758 0.6230306 -0.7013579 0.3463094 0.275671 -0.8441082 0.4598771 0.3342545 -0.8289365 0.4484845 0.08562314 -0.8661257 0.4924378 0.1510008 -0.8493542 0.5057629 -0.5303779 -0.7029103 0.4739373 -0.4147976 -0.7166457 0.5606799 -0.1449643 -0.8982769 0.4148302 -0.2298892 -0.8818053 0.4117894 0.1935384 -0.9328101 0.3039875 0.1061043 -0.9436973 0.3133325 -0.125409 -0.9186975 0.3745231 0.2902315 -0.9203551 0.2621302 -0.6572633 -0.5417787 0.5239093 -0.705041 -0.4868595 0.5156404 -0.3670055 -0.8439682 0.3911837 -0.5016545 -0.7671548 0.3997703 -0.04357314 -0.9766332 0.2104494 -0.2291777 -0.9411935 0.2482588 -0.1357264 -0.9694094 0.2045091 0.09168094 -0.9857547 0.141005 -0.1715863 -0.8536641 0.4917476 0.9914001 -0.06615459 0.1129136 -0.1786203 -0.9632536 0.2005927 -0.1978618 -0.9498676 0.2420795 -0.412836 -0.8595969 0.3010973 -0.4279985 -0.8243573 0.3704761 -0.4222774 -0.7941951 0.4369622 -0.3940263 -0.8090859 0.4360315 -0.534227 -0.6649445 0.5219678 -0.5744946 -0.6837174 0.449985 -0.565564 -0.7339069 0.3761889 0.2200699 -0.7862154 0.5774381 0.8593717 -0.3131561 0.4042445 0.6943417 -0.5471804 0.4674221 0.6435977 -0.6117433 0.459948 0.4543564 -0.7553523 0.4722322 0.389178 -0.802245 0.452707 0.08087992 -0.9068949 0.4135217 0.1528092 -0.9533634 0.2602838 -0.06794905 -0.9881212 0.1378389 -0.0705263 -0.9882941 0.135281 0.2264367 -0.9673343 0.1139769 0.1184483 -0.9606587 0.2512066 0.4114517 -0.81642 0.405174 0.6090105 -0.6286377 0.4836539 0.6254786 -0.6004157 0.4982746 0.7719781 -0.347449 0.5322867 0.8147106 -0.3741872 0.4429791 -0.5021972 -0.6725246 0.5436072 -0.4343436 -0.6964613 0.5712158 -0.4077869 -0.7106466 0.5733162 -0.2577434 -0.7448027 0.6154977 0.1663533 -0.7693956 0.6167311 -0.09900397 -0.8080588 0.5807232 0.05297261 -0.8059588 0.5895969 0.6949425 -0.5486506 0.4647982 0.4352653 -0.7087251 0.5552053 0.1229206 -0.7909603 0.5993935 0.1648263 -0.8964443 0.4113637 -0.1388242 -0.9293556 0.3420907 -0.002291917 -0.9132416 0.4074121 -0.4001904 -0.8648023 0.3032569 -0.3668392 -0.9083129 0.2009897 0.4367185 -0.8444163 0.3102228 0.4327886 -0.8390976 0.329559 0.6111393 -0.5416394 0.577179 0.7112365 -0.6223813 0.3267785 0.598644 -0.1731678 0.7820731 0.9586899 -0.06284427 0.2774243 0.8896451 -0.229439 0.3948284 0.9950215 -0.02336174 0.09688317 0.9210883 -0.2729649 0.2776446 0.75945 -0.479644 0.4395196 1 2.08445e-6 0 1 3.76279e-6 0 0.5048837 -0.5837295 0.6358871 -0.7767626 -0.3252102 0.5393313 -0.6279931 -0.0993216 0.7718549 -0.2590655 -0.6531746 0.7115111 0.05355447 -0.6751802 0.7357063 0.186397 -0.6411797 0.744409 0.2221804 -0.6592555 0.718344 0.504972 -0.5836083 0.6359283 -0.7947358 -0.3099059 0.5218749 -0.4311032 -0.4606034 0.7758831 -0.1422613 -0.5052648 0.8511576 -0.1422461 -0.5052573 0.8511646 0.1840117 -0.501731 0.8452253 0.500215 -0.442049 0.7445654 0.4999085 -0.4422378 0.7446591 -0.5338238 -0.1546268 0.8313379 -0.4305581 -0.1724148 0.8859418 -0.399755 -0.1681432 0.9010682 -0.1420621 -0.1815609 0.9730643 0.4990965 -0.1590739 0.8518205 0.5440639 -0.1373966 0.8277177 0.9209669 -0.2634719 0.2870587 0.920926 -0.2635804 0.2870903 0.9192234 -0.2011579 0.338473 0.9190152 -0.2015661 0.3387954 0.9919364 -0.08569049 0.09337806 0.9919271 -0.08579182 0.09338331 0.7594227 -0.43996 0.4792832 0.7594123 -0.4399353 0.4793224 0.7554793 -0.3345573 0.563314 0.7551216 -0.3349555 0.5635568 0.755407 -0.131333 0.6419596 0.9135625 -0.01931858 0.4062394 0.8491806 -0.1173819 0.514892 0.9912884 -0.01145005 0.1312115 0.9865449 -0.03007489 0.1607009 -0.898837 -0.250897 0.3593645 0.1419728 -0.5588731 0.8170096 0.2509738 -0.5535663 0.7940886 0.1421601 -0.241785 0.9598597 0.142022 -0.2418318 0.9598683 -0.1835587 -0.2401592 0.9532208 -0.1835128 -0.2401457 0.9532331 -0.1835889 -0.5531327 0.8126127 -0.07907581 -0.5700133 0.8178215 0.09458231 -0.5692272 0.816722 -0.5601907 -0.4738795 0.6794296 -0.4996481 -0.4856945 0.7172536 -0.4996332 -0.2117266 0.8399634 -0.4992344 -0.2116758 0.8402134 -0.7546803 -0.3755575 0.5379726 -0.7540412 -0.3757671 0.5387218 -0.7548794 -0.1604335 0.635939 -0.754434 -0.1604344 0.636467 -0.7590625 -0.08476012 0.6454764 -0.49892 0.09821778 0.8610645 -0.5539904 -0.03765434 0.8316711 -0.1861959 -0.02658349 0.982153 -0.1454389 0.04323393 0.9884222 0.1445149 -0.08491355 0.9858525 0.2901556 0.08608645 0.9530997 0.6260823 0.02275043 0.7794252 0.781708 -0.1694412 0.6001853 0.4751482 -0.5033066 0.7217457 -0.9535741 -0.1725527 0.246824 -0.9191606 -0.2178957 0.3281239 -0.9189185 -0.09653455 0.3824524 -0.9188103 -0.09654968 0.3827089 -0.9205153 -0.06045508 0.3860009 -0.9916964 -0.03151154 0.1246808 -0.9916818 -0.03150904 0.1247971 -0.9919387 -0.004321813 0.1266456 -0.9859384 0.04936426 0.1596521 -1 3.33298e-6 0 -1 9.51583e-6 2.66107e-4 -1 4.25363e-5 0 0.001513719 0 -0.9999989 -1.27582e-4 0 -1 2.46545e-5 0 -1 5.83335e-4 0 -0.9999998 0.999929 -0.01191753 0 0.9999278 -0.0120151 0 -0.9999296 -0.01186984 0 -0.9999285 -0.01196748 0 -0.9829399 -0.179104 -0.04184323 -0.9858747 -0.1674852 0 -0.8346237 -0.5508206 0 0.9722958 -0.1381413 -0.1885677 0.9667919 -0.2555649 0 0.8346279 -0.5508141 0 0.8345335 -0.5509573 0 -0.9858696 -0.1675064 0.001710176 -0.9761671 -0.1884446 -0.1076403 -0.8275529 -0.540777 0.1507195 0.9858645 -0.1675359 0.001731812 0.7348219 -0.4851085 0.4740322 0.8775422 -0.4701396 0.09427857 0.9761645 -0.1884487 -0.1076569 0.7457777 -0.08494842 0.6607568 0.7241795 -0.1118582 0.6804792 0.6634866 -0.3123287 0.6798797 0.6841593 -0.1197592 0.719433 0.3906306 -0.2221137 0.8933495 0.5856754 -0.09558314 0.8048902 0.4527704 -0.08508688 0.8875581 0.284012 -0.08921957 0.9546607 -0.1166579 -0.2398315 0.9637799 0.1085853 -0.08983522 0.9900196 0.02760022 -0.1258093 0.9916705 -0.3651824 -0.2154726 0.9056563 -0.1436799 -0.1050133 0.9840368 -0.5102274 -0.2560582 0.8210374 -0.321073 -0.09465241 0.9423127 -0.7054769 -0.251971 0.6624298 -0.5460544 -0.1145391 0.8298829 -0.8633074 -0.2345247 0.4468765 -0.7472413 -0.1361068 0.6504656 -0.8716138 -0.1580787 0.4640051 -0.9810479 -0.1861899 0.05365103 0.3083781 -0.8580229 0.4107308 0.2891848 -0.866069 0.4077949 0.1160838 -0.8788799 0.4627038 0.07672244 -0.9124587 0.4019115 -0.5249457 -0.8192991 0.2306106 -0.5265806 -0.8260881 0.2007269 -0.4166767 -0.8154314 0.4018111 -0.2535104 -0.7948607 0.5512976 -0.2825536 -0.8076022 0.5176314 -0.04892361 -0.7669106 0.6398866 -0.120137 -0.7980771 0.5904575 0.1451942 -0.7454863 0.6505144 0.04599362 -0.7894594 0.6120774 0.314652 -0.7326967 0.6034483 0.1659604 -0.796827 0.5809681 0.3846784 -0.7146167 0.5842479 0.3056787 -0.7682008 0.5625194 0.4468955 -0.7013726 0.5553025 0.3840456 -0.7545807 0.5320875 0.5124095 -0.6955075 0.5036923 0.4613474 -0.7415843 0.4870435 0.5656548 -0.688805 0.4534119 0.6021772 -0.6452817 0.4701004 0.5855112 -0.608225 0.535947 -0.8356698 -0.548319 0.03165805 -0.8267943 -0.5462588 0.1342111 -0.7917211 -0.5462648 0.2734456 -0.7151331 -0.5409173 0.4427113 -0.5688835 -0.538182 0.6218776 -0.2605466 -0.4821421 0.8364536 -0.3826496 -0.5341994 0.7537974 -0.02823573 -0.4647911 0.8849701 -0.1765255 -0.5290808 0.8300074 0.1894885 -0.4554542 0.8698596 0.01871824 -0.5302188 0.8476543 0.350959 -0.4494093 0.8214982 0.4855184 -0.4524638 0.7480297 0.4596594 -0.5242784 0.7168301 0.6841662 -0.4729781 0.5551652 0.7119262 -0.3903557 0.5837668 -0.5859336 -0.6613369 0.4683111 -0.4188062 -0.7444077 0.5200564 0.8444263 -0.1321446 0.5191168 0.9780074 -0.1333947 0.1603349 0.9050805 -0.1645485 0.3921135 0.5307891 -0.06143498 0.8452743 0.5998713 -0.08926367 0.7951015 0.6671125 -0.1164508 0.7357991 -0.06420671 -0.08063912 0.9946733 0.09324592 -0.1067025 0.989909 0.319482 -0.1364928 0.9377105 0.2376942 -0.102532 0.9659135 0.5238233 -0.1344127 0.8411555 0.6358063 -0.1818537 0.7501196 0.01900476 -0.1818327 0.9831458 -0.2580822 -0.2223592 0.9401862 -0.3332186 -0.1623747 0.9287625 0.05437874 -0.9340834 0.35289 0.06190448 -0.9211966 0.3841416 0.09307157 -0.9564307 0.2767274 -0.3885534 -0.6325364 0.670018 -0.6407239 -0.6420008 0.4210795 -0.624956 -0.7185578 0.3051307 -0.5930621 -0.7315684 0.3362812 -0.5781667 -0.6721589 0.4625212 -0.432167 -0.7379099 0.5183828 -0.5189375 -0.7353101 0.4359161 -0.4373279 -0.6627933 0.6078235 -0.6485819 -0.5723357 0.5017703 -0.5874304 -0.445472 0.6756331 -0.9234088 -0.2592301 0.283048 -0.2598137 -0.3228817 0.9100793 0.4139348 -0.8105905 0.4142476 0.4253708 -0.8547789 0.297343 0.264039 -0.7838324 0.5620411 0.301079 -0.8503313 0.4316112 0.09000009 -0.7612076 0.6422328 -0.08671975 -0.744109 0.6624058 -0.0117917 -0.8338954 0.5517967 -0.2483 -0.7345759 0.6314629 -0.158295 -0.8246352 0.543065 -0.3212713 -0.7632011 0.5606327 0.8694537 -0.4707406 -0.1498453 0.8950267 -0.4326835 0.1082233 0.757444 -0.3708171 0.5373764 0.8287693 -0.4460833 0.3378628 0.5826159 -0.3427926 0.7369206 0.7039849 -0.4552209 0.5451416 0.3811463 -0.322369 0.8664904 0.5305604 -0.4582787 0.7130823 0.1671008 -0.3087041 0.936365 0.3276473 -0.4573241 0.8267418 -0.04511398 -0.3023589 0.952126 -0.2395792 -0.2995315 0.9235165 -0.07533407 -0.4500072 0.8898419 -0.4162253 -0.3030852 0.8572607 -0.2526127 -0.4454764 0.8589166 -0.5628743 -0.3090149 0.7666046 -0.7444348 -0.1162934 0.6574898 -0.4939412 -0.1104784 0.862448 -0.7025429 -0.3105552 0.6403039 -0.4108313 -0.4428932 0.7969086 -0.4718797 -0.50098 0.725499 -0.4290459 -0.5626689 0.7066282 -0.2194947 -0.6522767 0.7255048 -0.2811422 -0.559414 0.7797533 -0.05177277 -0.656172 0.7528333 -0.1096134 -0.5628895 0.8192316 0.1323215 -0.6630764 0.7367638 0.0845831 -0.5700455 0.8172478 0.3265652 -0.6696589 0.6670174 0.2843178 -0.5836845 0.760576 0.5043779 -0.6744468 0.5391888 0.4718955 -0.6020175 0.6441194 0.6441025 -0.6751065 0.3596711 0.6284394 -0.6248016 0.4633433 0.7367968 -0.67098 0.08316504 0.7547044 -0.6289432 0.1866865 0.1887335 -0.9054059 0.3802893 0.2512571 -0.7702778 0.5861245 0.3056126 -0.7680147 0.5628094 0.3836345 -0.752992 0.5346286 0.4209461 -0.7380433 0.5273485 0.4613298 -0.7347406 0.4973239 0.5498821 -0.7042222 0.4491112 0.5753524 -0.7230192 0.3823781 0.735785 -0.6575137 0.1621612 -0.02758598 -0.9939181 0.1066104 -0.4326624 -0.7439554 0.5092481 -0.4514882 -0.7366296 0.5035229 -0.5708802 -0.6974324 0.4332252 -0.5811485 -0.6885517 0.4337778 -0.6440086 -0.6872324 0.336102 -0.3167358 -0.7522653 0.5777329 -0.2332518 -0.7356295 0.6359583 0 -0.7743619 0.632743 -2.27222e-5 -0.9505364 0.3106134 -0.06078892 -0.9432337 0.3265194 -0.6857077 -0.6726843 0.2780303 -0.7298887 -0.6262953 0.2738916 -0.6760898 -0.6741964 0.2972573 0.2162781 -0.7689111 0.6016641 0.2580568 -0.771499 0.5815464 0.2037911 -0.7903723 0.5777378 0.1253503 -0.789418 0.6009215 -0.03491395 -0.7909503 0.6108835 -0.2250411 0.9274718 0.2985844 -0.448152 0.8790638 -0.1625012 0.8123238 0.5131161 -0.2772038 0.4830029 0.8557875 -0.1852996 0.4006736 0.9067038 -0.1317149 0.3763956 0.9198688 -0.1103078 0.886956 0.3785788 -0.2645512 0.9985911 0.007810294 -0.05248832 0.931953 0.05031764 -0.3590707 0.9416013 0.1408184 -0.3058712 0.9728367 -0.07616555 -0.2186037 0.9920018 -0.1157358 -0.05037736 0.9873977 -0.1158051 -0.1078662 0.8442506 -0.5026171 0.1860562 0.8817772 -0.4532389 0.1305508 0.9716231 -0.2303144 0.05388844 0.8061835 -0.3300942 0.4910256 0.6702673 -0.5010315 0.5474571 0.3950405 -0.2265992 0.8902786 0.5395273 -0.5019873 0.6759578 0.1763835 -0.5031977 0.8459794 -0.8029068 -0.3414185 0.4886451 -0.6946026 -0.4987359 0.5184494 -0.8817046 -0.4534092 0.1304497 -0.8442854 -0.5026181 0.1858958 -0.8015056 -0.5019748 0.3249769 -0.9282393 0.2263891 -0.295161 -0.9483422 0.06170779 -0.31119 -0.9016539 0.2576193 -0.3473511 -0.977361 -0.07313781 -0.1985353 -0.4272505 0.9016879 -0.06645363 -0.3885337 0.9130575 -0.1239658 -0.3264811 0.9240833 0.1986966 -0.3981559 0.8629879 0.3110044 -0.3431074 0.927567 0.1479759 -0.3819672 0.9240805 0.01327818 0.04771149 0.9273853 0.3710529 0.1422474 0.9272764 0.3463007 0.224975 0.9274755 0.2986226 0.3704327 0.9010421 0.2256164 0.3430814 0.9275664 0.1480394 0.370929 0.9270683 0.05436998 0.4328533 0.9013362 0.0152015 0.3605214 0.9283957 -0.09003251 0.2885534 0.9532799 -0.08941161 -0.6420764 0.7300558 -0.2340011 -0.6775439 0.7059025 -0.206485 -0.7184971 0.6950814 0.02497732 -0.718492 0.6950866 0.02497762 -0.6141291 0.6950914 0.3737558 -0.3522967 0.6950923 0.6266847 0.352074 0.6950827 0.6268205 0.352079 0.6950891 0.6268106 0.6140027 0.6950882 0.3739693 0.718478 0.695092 0.02523314 0.7184834 0.6950863 0.02523249 0.6789507 0.7060951 -0.2011362 0.6816034 0.7016828 -0.2075045 -0.8420011 0.4522098 -0.2941776 -0.9174339 0.3221163 -0.2335726 -0.9492562 0.3127681 0.03299951 -0.9492556 0.31277 0.03299987 -0.8113867 0.3127685 0.4937891 -0.8113927 0.3127488 0.4937917 -1.48557e-4 0.312747 0.9498366 -1.69339e-4 0.3127679 0.9498296 0.4651473 0.3127674 0.8281393 0.4651592 0.3127694 0.8281318 0.9492468 0.3127608 0.03333652 0.91734 0.3220926 -0.2339738 0.9315093 0.2018446 -0.3025713 -0.9889112 -0.115731 -0.09306561 -0.9920014 -0.1153368 -0.05129069 -0.9937251 -0.1063818 0.03454482 -0.9912826 -0.1247235 0.04245972 -0.8476017 -0.1244599 0.5158304 -0.8475958 -0.1244717 0.5158374 -0.4862345 -0.1244677 0.8649184 -0.4862268 -0.1244515 0.8649252 -1.84216e-4 -0.1244511 0.9922258 -1.73528e-4 -0.124473 0.992223 0.4859117 -0.1244851 0.8650974 0.8474157 -0.1244788 0.5161315 0.8474158 -0.1244589 0.5161361 -0.9288172 0.05564951 -0.3663357 -0.7070965 0 -0.7071171 -0.7071218 0 -0.7070918 -0.2588235 0 -0.9659247 0.2588235 0 -0.9659246 0.7071217 0 -0.7070919 0.7070966 0 -0.7071171 0.9498238 0.03595876 -0.310712 0.9655773 0.02687662 0.2587243 0.7068485 0.02709674 0.7068458 0.2586995 0.02720159 0.9655748 0.6017283 0 0.7987009 -0.2586995 0.02720421 0.9655748 -0.127792 0 0.9918011 0.1276147 0 0.9918238 -0.7068359 0.02710109 0.7068582 -0.6018989 0 0.7985724 -0.9894535 0 0.1448515 -0.9655754 0.02688425 0.2587305 -0.9182483 0 0.3960053 -0.7880725 0 0.6155824 -0.9336899 -0.06148761 0.3527643 -0.888008 -0.008810698 0.4597436 -0.9099643 -1.71235e-4 0.4146869 -0.815638 2.35543e-4 0.5785626 -0.9738512 -0.01302498 0.2268134 -0.9986431 -1.12017e-4 0.0520789 -0.9999991 0 0.001442253 0.2887836 0 0.9573944 0.2574582 0.02167409 0.9660464 0.03902876 -0.00698769 0.9992137 0.006594717 0 0.9999783 -0.1923611 0.004299044 0.9813148 -0.425632 -0.003357291 0.9048902 -0.4286811 -0.001921713 0.9034539 -0.6166539 0.002047061 0.7872318 -0.5427675 -0.03605848 0.8391086 -0.7915952 0.087116 0.604804 -0.6672981 -0.07482159 0.741023 -0.7496201 -0.03212958 0.6610881 -0.8560589 -0.3604239 0.3704833 -0.9804669 -0.1934006 0.03579223 -0.9045272 -0.4213289 0.06567078 -0.9022588 -0.4266552 0.06240683 -0.792072 -0.6078364 0.05618661 -0.6218979 -0.7800781 0.06871265 -0.4221154 -0.9063081 0.02059787 -0.2209836 -0.9750617 0.02051705 -0.4474565 -0.8934745 0.0385487 0.5710233 -0.8138492 0.10762 0.5360841 -0.8424029 0.05450987 0.7693951 -0.636312 0.05602002 0.8359134 -0.5321441 0.1344304 0.8845048 -0.4610745 0.0711438 0.9774708 -0.1723653 0.1218243 0.9769529 -0.1701507 0.1288869 -0.2329915 0.002949476 0.9724743 -0.3704215 -0.01064854 0.9288027 -0.2659964 0.01061773 0.9639156 -0.2387219 0.002776443 0.971084 -0.3667865 -0.004981756 0.9302919 -0.3274768 -0.02586686 0.9445052 -0.3482263 -0.01751053 0.9372469 -0.4836033 -1.47124e-6 0.8752874 -0.4826824 0.001000761 0.875795 -0.4235888 -7.68294e-4 0.9058543 -0.3955515 -0.005382061 0.9184281 0 -7.62939e-4 0.9999998 0 -7.6294e-4 0.9999998 0 0.01934748 0.9998129 0.001106381 0.08196479 0.9966347 0.002311229 0.0949316 0.9954811 -0.001431345 0.03744268 0.9992979 0.4271762 -0.009436488 0.9041191 0.4023627 -0.01783287 0.9153068 0.380001 -0.02621996 0.9246144 -0.1951996 -6.3181e-5 0.9807636 0.003326714 8.08918e-4 0.9999942 0 -0.002331018 0.9999974 0.2053384 2.68714e-4 0.9786911 0.2387363 0.004386126 0.9710746 0.2494046 0.002140223 0.968397 0.3207079 -0.002153396 0.9471758 0.3667666 -0.01213812 0.9302338 0.4829937 0.02946078 0.8751282 0.482605 0.001112282 0.8758374 0.5721187 -0.001999676 0.8201685 0.5222118 0.01347213 0.8527094 0.5518402 0.006364881 0.8339257 0.691101 1.64792e-5 0.7227583 0.6819847 0.003219842 0.7313594 0.6236229 -3.94619e-4 0.7817253 0.5882084 0.001006662 0.8087087 -0.6321122 -0.003908514 0.7748671 -0.6815337 0.006247699 0.7317602 -0.7113313 0 0.702857 -0.56901 0.003546297 0.8223231 -0.5465408 0.007440328 0.8373994 -0.5716109 0.001377284 0.8205237 -0.5204926 -2.17099e-4 0.8538662 -0.4813616 0.001231908 0.8765212 1 -2.80261e-6 0 1 0 -9.43905e-7 1 1.0189e-4 2.89373e-6 3.90484e-5 -1 -5.88254e-5 1.94621e-4 -1 8.6227e-5 1 -4.31183e-6 0 1 5.93082e-6 0 1 -2.61154e-6 0 1 1.44726e-6 0 1 1.86343e-6 0 1 5.84113e-7 0 1 2.9056e-7 0 1 -2.80269e-6 0 1 -1.79263e-5 0 1 1.459e-4 0 1 -1.468e-4 0 -1 -1.29046e-6 0 -1 2.44994e-6 0 0 -1 0 0 -1 0 0 -1 0 -1 -7.35128e-7 0 -1 -1.22526e-6 0 -1 3.09075e-7 0 -1 7.26491e-6 0 -1 -4.20851e-7 0 -1 2.60276e-7 0 -1 6.49989e-7 0 -1 7.06662e-7 0 -1 5.72679e-6 0 -1 -1.05219e-5 0 -1 2.62109e-5 0 -1 -2.24336e-5 0 -0.7101083 0 0.7040925 -0.8269445 0 0.5622838 -0.5738846 -0.704185 0.418067 -0.5777199 0.5999701 0.5534218 -0.6961895 0.1475797 0.7025244 -0.610419 -0.1844869 0.7702942 -0.6090812 -1.15942e-5 0.7931081 -3.1162e-5 1 -1.76426e-5 3.8021e-5 1 -1.51025e-4 -0.6441815 0.7606397 0.0803582 -0.7070807 0.7070778 0.008828282 -0.7768822 0.6296151 0.006226301 -0.856146 0.5167341 -4.09482e-5 -0.9659255 0.2588196 5.36992e-4 -0.9324787 0.3565899 0.05768144 -0.9861636 0.1657546 0.00260967 0.2581059 0.9632987 0.07373625 0.1827531 0.98261 0.03284859 0.0559113 0.9984357 -4.93025e-5 -0.2588207 0.9659254 2.41881e-4 -0.1085086 0.9777986 0.1792647 -0.2391921 0.9673169 0.08417361 0.8583107 0.5131304 -2.60878e-5 0.7736148 0.6336351 0.005182683 0.7063023 0.7062879 0.04790222 0.9845656 0.1749942 0.002766668 0.7071021 -0.7071115 0 0.7071092 -0.7071045 0 0.2588217 -0.9659252 0 0.2588183 -0.9659261 0 -0.2588217 -0.9659252 0 -0.2588189 -0.9659259 0 -0.7071033 -0.7071103 0 -0.707108 -0.7071056 0 -0.9238781 -0.3826869 0 -0.965651 -0.258746 0.02384555 -0.9999297 0.01186078 0 0.9999292 0.01190841 0 0.9657706 -0.2587826 0.017861 0.9801641 -0.1949595 0.03562676 0.9238814 -0.382679 0 0 -0.9987482 -0.0500214 8.27506e-5 -0.9987558 -0.04986888 1.38402e-5 0 1 2.07602e-5 0 1 -2.07602e-5 0 1 -3.46003e-6 0 1 3.46003e-6 0 1 0.2162943 0 0.9763283 -0.2164382 0 0.9762964 -0.2162916 3.91355e-4 0.9763288 0.574184 0 0.8187263 0.5741112 0 0.8187775 0.8207608 0 0.5712721 0.8207983 0 0.5712183 0.9663845 0 0.2571014 0.9663823 0 0.2571097 -0.9658438 0 0.2591251 -0.9658506 0 0.2590998 -0.8189677 0 0.5738398 -0.8189885 0 0.5738101 -0.5746778 0 0.8183798 -0.57334 -3.28944e-4 0.8193175 0.6819913 0 0.7313603 0.9217363 0 0.3878172 -0.9217385 0 0.3878121 -0.6819827 0 0.7313684 -0.6819903 0 0.7313613 -0.3508558 0 0.9364295 0.1502819 0 0.9886432 0.6132866 0 0.7898606 0.8153597 0 -0.5789549 -0.5435652 0 -0.839367 0 -1 7.37546e-7 -1.72451e-6 -1 0 0 -1 2.92203e-7 2.07814e-7 -1 0 2.20789e-7 -1 4.79421e-7 0 -1 -2.37329e-7 0 -1 8.84098e-7 0 -1 -2.47364e-7 0 -1 -6.51525e-7 0 -1 -3.04139e-6 0 -1 4.55209e-7 0 -1 -3.75154e-7 0 -1 4.40753e-6 -0.9659277 0 -0.2588126 -0.7071065 0 -0.7071071 -0.7070963 0 -0.7071173 -0.258835 0 -0.9659216 -0.2587959 0 -0.9659321 0.2587957 0 -0.9659321 0.2588351 0 -0.9659215 0.7070976 0 -0.707116 0.965927 0 -0.2588149 0.9659255 0 0.2588201 0.7071078 0 0.7071058 0.258835 0 0.9659216 0.2587959 0 0.9659321 -0.2587957 0 0.9659321 -0.2588351 0 0.9659215 -0.7071065 0 0.7071071 -0.7071068 0 0.7071068 -0.9659262 0 0.2588177 -0.9659262 0 0.2588179 -0.9659262 0 -0.2588177 -0.2922877 -0.8814364 0.3709958 -0.1937514 -0.8235141 0.5331839 -0.3308092 -0.611065 0.7191418 -0.3880459 -0.4780495 0.7879652 -0.4407333 -0.3857128 0.810543 -0.2676678 -0.8616387 0.4311992 -0.2961609 -0.7077509 0.6413872 -0.3209444 -0.6553854 0.6837139 0.5195691 -0.7323437 0.4401371 -0.4576467 -0.485493 0.7448866 -0.4156329 -0.509195 0.7536378 -0.3486559 -0.5237676 0.777243 -0.8972305 -0.2237796 0.3806578 -0.708533 -0.3813979 0.5937312 -0.6762689 -0.3906167 0.624563 -0.5066975 -0.4571485 0.7309397 -0.04159349 -0.6375239 0.769307 -0.1597617 -0.5795711 0.799108 0.5203682 -0.7009665 0.4877121 0.45967 -0.6986286 0.5482899 0.2894267 -0.7548887 0.5885366 0.2859697 -0.7534452 0.5920656 0.2070425 -0.7311907 0.6499952 -0.07047414 -0.8964574 0.4374901 0.2869781 -0.8594663 0.4230382 0.3922251 -0.8340696 0.3879273 0.4514044 -0.8090997 0.3762871 0.5908856 -0.7488351 0.3001671 0.7231339 -0.6261897 0.2914857 -0.4140209 -0.8172802 0.4007991 -0.2989531 -0.8654401 0.4020454 -0.8014565 -0.5461459 0.2437054 -0.7084895 -0.6297155 0.3185924 -0.6308886 -0.7061178 0.3215233 -0.4438809 -0.8090264 0.3852869 -0.7092708 -0.5168675 0.4793568 -0.4141997 -0.6673616 0.6189242 -0.415345 -0.6672964 0.6182267 -0.07051652 -0.7317243 0.6779432 -0.0707786 -0.7317761 0.67786 0.1255019 -0.7278163 0.6741905 0.1703518 -0.6807864 0.7123975 0.4159756 -0.5039117 0.7569922 -0.1542685 -0.6420947 0.7509432 0.999777 -0.01844036 0.01029187 0.9605577 -0.234834 0.1489362 0.9891217 -0.1463094 -0.0152294 0.883128 -0.4238226 0.2011455 0.8080081 -0.5446055 0.2247838 0.7093616 -0.6341043 0.3077626 0.6660916 -0.6798411 0.3068194 0.5883172 -0.7400797 0.3258295 0.4670893 -0.809231 0.3563325 0.4149104 -0.8239226 0.3860062 0.2642551 -0.88555 0.382061 0.07049679 -0.9070867 0.4149987 0.03274148 -0.9149894 0.4021474 -0.2082057 -0.8954064 0.3935707 -0.2876629 -0.8662821 0.4084182 -0.3859505 -0.8443992 0.3715268 -0.6097689 -0.7445545 0.2716993 -0.4907042 -0.7975369 0.3509195 -0.5595369 -0.7001013 0.4435952 -0.4351313 -0.7181234 0.5431019 -0.2362786 -0.7764106 0.5842595 -0.2889636 -0.7623279 0.5790995 -0.1389094 -0.7294035 0.6698319 -0.152095 -0.6270425 0.7639929 0.3247708 -0.5239109 0.787427 0.1206853 -0.5827371 0.8036496 0.07124578 -0.6233674 0.7786765 -0.008332729 -0.6171438 0.7868063 -0.1057674 -0.6127579 0.7831609 0.8830564 -0.2501624 0.3970268 0.7229121 -0.3503187 0.5955459 0.707882 -0.3639582 0.6053408 0.4624413 -0.4676551 0.7532906 0.501767 -0.4504159 0.7384819 -0.1498391 -0.7288879 0.668035 0.07014375 -0.7353978 0.6739956 0.07040774 -0.7353128 0.6740607 0.412596 -0.6714544 0.6155596 0.4143918 -0.6704198 0.6154811 0.70629 -0.5214822 0.4787596 0.7082917 -0.5193542 0.4781151 0.8816134 -0.3472045 0.3196983 0.8827579 -0.3452399 0.3186662 0.9795771 -0.1477447 0.1363827 0.994014 -0.02089798 0.1072363 0.9618362 -0.1630295 0.2197559 0.9672648 -0.1049735 0.2310399 0.1968929 -0.8848494 0.4222261 0.1975533 -0.8473657 0.4928935 0.198725 -0.9046102 0.3770795 0.2436822 -0.7890273 0.5639637 0.2586135 -0.8322697 0.4903532 0.273497 -0.7612082 0.5880148 0.3147403 -0.6684343 0.6738948 0.3162385 -0.6018824 0.7333014 0.4197958 -0.3697234 0.8289006 0.405321 -0.3960708 0.8239192 0.3421464 -0.5159761 0.7853053 0.3780855 -0.6087727 0.6974576 0.4160929 -0.6308736 0.6548781 0 -1 -9.59789e-7 0 -1 1.09564e-6 0 -1 -2.03451e-6 0 -1 4.12505e-7 0 -1 -1.26087e-6 0 -1 2.23636e-6 0 -1 -1.96936e-6 0 -1 3.73413e-6 0 -1 -1.39161e-6 0.6054105 -0.7193112 0.3406899 0.4317935 -0.8561711 0.2837701 -0.1776665 -0.812146 0.5557458 -0.1957454 -0.8220618 0.5346946 -0.1151224 -0.8859436 0.4492782 -0.1188914 -0.8901901 0.4398027 0.0878188 -0.910237 0.4046685 0.1007194 -0.9012429 0.4214462 0.09979289 -0.8994953 0.4253818 0.1021885 -0.9014419 0.4206661 -0.1168611 -0.7270137 0.6766052 0.01145905 -0.8212065 0.5705161 0.1899964 -0.8427808 0.5036089 0.1846045 -0.8361652 0.5164777 0.3383932 -0.8686107 0.361947 0.3356205 -0.84494 0.4164556 0.4300069 -0.8437431 0.3212347 0.4415208 -0.8463315 0.2979636 0.6341808 -0.7289466 0.2577822 0.584593 -0.6813137 0.4405255 0.6394239 -0.7119134 0.2903731 0.6763992 -0.7243292 0.1335344 -0.2676344 -0.4416937 0.8563169 -0.2246572 -0.4907895 0.8418164 -0.08962458 -0.5589933 0.8243143 -0.007700324 -0.5650078 0.8250498 0.03675407 -0.6112789 0.7905614 0.1426053 -0.6319153 0.761805 0.1518551 -0.6405594 0.7527442 0.2820208 -0.6932855 0.6631889 0.2479313 -0.644858 0.7229718 0.2987688 -0.6875941 0.6617791 0.2402213 -0.7423424 0.625477 0.0904839 -0.6932519 0.7149927 0.2001854 -0.8198825 0.5363941 -0.100565 -0.7098841 0.6971021 -0.5487723 -0.8042544 0.2280873 -0.4216923 -0.6782166 0.6018287 0.08563077 -0.5722729 0.8155803 -0.2920604 -0.9052797 0.3084956 -0.2923654 -0.9053264 0.3080691 -0.1818085 -0.8741902 0.4502635 -0.3397849 -0.8632064 0.3733914 -0.03175228 -0.8642919 0.5019875 0.4603459 -0.380275 0.8021675 -0.1428212 -0.9219775 0.3599442 -0.1437144 -0.9218704 0.3598628 -0.1427595 -0.9219942 0.3599259 0.09348583 -0.9019348 0.4216325 0.0934953 -0.9019517 0.4215944 0.0824638 -0.9516562 0.295889 0.7089752 -0.5439577 0.4488476 0.7091604 -0.54367 0.4489039 0.1841359 -0.8563733 0.4824092 0.1833605 -0.8558545 0.4836238 0.2463687 -0.6597479 0.7099543 0.2682718 -0.6567168 0.7048073 0.1676917 -0.5475132 0.8198224 0.1630306 -0.4815628 0.8611147 0.1183922 -0.3499155 0.9292699 0.3094943 -0.5312856 0.7886374 -0.1366717 -0.6336074 0.7614872 -0.1124455 -0.610206 0.7842223 -0.4745866 -0.6919032 0.5440933 -0.6909076 -0.7143477 0.1111485 -0.6788694 -0.7213392 0.1371355 -0.6848385 -0.71461 0.1425796 -0.6461209 -0.7077319 0.2857334 -0.6566995 -0.7026278 0.2739706 -0.5580733 -0.7945999 0.2390927 -0.563759 -0.801567 0.1991639 -0.5830237 -0.7525193 0.3062649 -0.5572121 -0.7809812 0.282105 -0.5655125 -0.6968181 0.4411803 -0.5946351 -0.657723 0.4623955 -0.595705 -0.6699666 0.4430354 -0.313521 -0.8922153 0.3250488 -0.3488886 -0.8594394 0.3736855 -0.2331066 -0.8220897 0.5194514 -0.07046258 -0.8046814 0.5895107 -0.04897069 -0.8265421 0.5607407 -0.1428118 -0.921947 0.3600261 -0.3581978 -0.6229621 0.6954226 -0.4491061 -0.4746908 0.7569495 -0.3274336 -0.6607254 0.6754474 -0.3379956 -0.749068 0.5697861 -0.347437 -0.7378819 0.5786345 -0.3559633 -0.8345527 0.4204902 -0.4033093 -0.7823264 0.4746653 -0.3685188 -0.8777512 0.306181 -0.09539473 -0.5837552 0.8063062 -0.09848076 -0.590984 0.8006494 -0.05519068 -0.6439664 0.7630606 -0.07102674 -0.7742128 0.6289274 -0.03876072 -0.8063654 0.5901462 0.06925183 -0.7255127 0.6847157 0.1443349 -0.8002984 0.5819708 0.2435477 -0.7158206 0.6544352 0.1700744 -0.8445752 0.5077082 0.505741 -0.8322586 0.2270947 0.2358707 -0.9687023 -0.07733613 0.02136665 -0.9959197 0.08767873 0.09730923 -0.9928584 0.06901472 -0.07270449 -0.98289 0.169238 0.1812562 -0.9812577 0.06541979 0.4038981 -0.8824486 0.2411448 0.4108694 -0.8529508 0.3219647 0.5485031 -0.7975512 0.2511104 0.0794301 -0.9033576 0.421469 -0.005031704 -0.8430025 0.5378861 0.3398081 -0.9336338 0.1133952 0.4339542 -0.8995434 0.0500558 0.5054176 -0.8284039 0.2414541 -0.1408789 -0.9428305 0.3020328 -0.03431326 -0.9966986 0.07358455 -0.06311494 -0.9857727 0.1557846 -0.09156209 -0.9747706 0.2035652 -0.1275016 -0.9531998 0.2741413 -0.04251223 -0.9379941 0.3440347 0.108046 -0.9048234 0.4118503 0.3088976 -0.8665034 0.3921152 0.3080726 -0.8678898 0.3896907 0.3038569 -0.8808428 0.363025 0.1147857 -0.9010605 0.4182276 0.1289668 -0.9015986 0.4129012 0.1870047 -0.9276126 0.3233641 0.1738282 -0.9310281 0.3208903 -0.04641801 -0.926386 0.3737038 -0.08995783 -0.8879584 0.4510408 -0.06644833 -0.9014692 0.4277124 -0.04723566 -0.9169801 0.3961265 -0.04208767 -0.9245235 0.3787943 -0.03797346 -0.9265189 0.374327 0.02040016 -0.95501 0.2958712 -0.01413625 -0.9423807 0.3342436 0.07852071 -0.9843708 0.157635 0.02637076 -0.9363902 0.3499687 -0.3020173 -0.9034107 0.3043597 0.1467946 -0.9431554 0.2981765 -0.01267677 -0.9177882 0.3968681 -0.2381426 -0.9141606 0.3280223 -0.1986326 -0.9185386 0.3418067 -0.2894535 -0.8795257 0.3776921 -0.2020882 -0.908288 0.3662968 -0.08403277 -0.98306 0.1628852 -0.01805931 -0.9808146 0.1941047 -0.02348858 -0.8871617 0.4608608 -0.06641876 -0.9215493 0.382538 -0.06637191 -0.9215817 0.3824684 -0.01261597 -0.917777 0.3968961 0.07521146 -0.874394 0.479352 0.03647601 -0.9118202 0.4089663 -0.2382729 -0.9141553 0.3279426 -0.159403 -0.8847512 0.4379566 -0.03556364 -0.9547483 0.2952812 -0.06958144 -0.9627898 0.2611407 0.03961509 -0.9100102 0.412689 0.03673905 -0.9120627 0.4084016 0.03618127 -0.9118804 0.4088583 -0.02995193 -0.9045485 0.4253175 0.1113302 -0.9646813 0.2387375 0.03068691 -0.9945837 0.09930545 0.0733956 -0.984804 0.1573982 0.3346469 -0.8170119 0.4695776 0.5324412 -0.6071044 0.5898565 0.6188136 -0.2744346 0.7360403 0.6836467 -0.153711 0.7134425 0.4615972 -0.5173088 0.7206384 0.4979169 -0.3773618 0.7808179 0.5049774 -0.2435218 0.828067 0.5114083 -0.2133764 0.8324254 0.1737344 -0.968772 0.1769104 0.271127 -0.9060305 0.3249602 0.3503894 -0.8008243 0.4857034 0.3917264 -0.7965036 0.4605784 0.4149844 -0.7318322 0.5405642 0.4539651 -0.7271135 0.5149968 0.5012527 -0.6120999 0.6116204 0.4265834 -0.6637666 0.614362 0.4541746 -0.5336156 0.7134282 0.5024423 -0.5286461 0.6841675 0.5079677 -0.4397363 0.7406761 0.561207 -0.433119 0.7053046 0.6127569 -0.2835633 0.7376455 0.3148766 -0.8875688 0.3362655 0.281832 -0.8845403 0.371698 -0.611026 -0.7262156 0.3150529 -0.3784258 -0.884704 0.2722 -0.165483 -0.9807173 0.103967 -0.4826831 -0.8187978 0.3107846 -0.1245867 -0.9918174 0.02786415 -0.1132071 -0.9904406 0.07881456 -0.6439293 -0.7519236 0.141301 -0.6257103 -0.76229 0.1655322 -0.6321169 -0.7560896 0.1695784 -0.5223855 -0.8186566 0.2385682 -0.4765579 -0.8309497 0.2870806 -0.5032927 -0.8640791 -0.007987976 -0.4900074 -0.8695285 0.06174993 -0.29037 -0.9121593 0.2892245 -0.3075407 -0.9157778 0.2583985 -0.1076228 -0.9140748 0.3910045 -0.1445427 -0.9396934 0.3099737 -0.144531 -0.9396939 0.3099775 -0.1445424 -0.9396938 0.3099731 -0.1445431 -0.9396928 0.3099755 -0.1445451 -0.9396927 0.3099751 -0.144537 -0.9396937 0.3099757 -0.1459318 -0.9402586 0.3076003 -0.144464 -0.9397595 0.3098104 -0.1446225 -0.9395766 0.3102905 -0.1445506 -0.9396945 0.3099666 -0.1445571 -0.9396843 0.3099948 -0.1445136 -0.9396889 0.3100013 -0.1445462 -0.9396923 0.3099754 -0.1445369 -0.9396943 0.3099738 -0.1445453 -0.9396924 0.3099759 -0.09901291 -0.9385171 0.3307298 -0.01958054 -0.9629988 0.2687939 0.09902578 -0.9384981 0.3307797 0.06952083 -0.9469415 0.3137972 0.02490597 -0.9394009 0.3419148 -0.07560718 -0.9370021 0.3410435 -0.07562232 -0.9369965 0.3410556 0.1445125 -0.9396967 0.309978 0.1438955 -0.9398491 0.309803 0.1445428 -0.9396943 0.3099713 0.1445327 -0.9396932 0.3099792 0.1445431 -0.939693 0.3099747 0.1445451 -0.9396921 0.3099763 0.144282 -0.9397625 0.3098856 0.144537 -0.9396991 0.3099592 0.1445043 -0.9396967 0.3099815 0.144546 -0.9396924 0.3099752 0.1445508 -0.9396916 0.3099759 0.1445441 -0.9396922 0.3099771 0.144522 -0.9396969 0.309973 0.144711 -0.9396474 0.310035 0.1447058 -0.9396501 0.3100293 0.003624558 0.9996088 -0.02773612 -0.06783872 0.9915317 -0.1107385 -0.06783652 0.9915322 -0.1107347 -0.03774404 0.9914518 -0.1248954 -0.03774344 0.9914515 -0.1248981 -0.01674562 0.9916287 -0.1280313 -0.04155951 0.9921848 -0.1176524 0 0.9838478 -0.1790069 0.007755577 0.9867666 -0.1619623 0.04075139 0.9913896 -0.1244429 0.03774416 0.9914514 -0.1248986 0.03774344 0.9914515 -0.1248979 0.06783676 0.9915321 -0.1107351 0.06783825 0.9915316 -0.1107394 -0.1256685 0.9907982 -0.0502631 -0.1390931 0.9898258 -0.02996784 -0.2948299 0.9553067 -0.02155065 -0.1050757 0.9907993 -0.08529925 -0.1046943 0.9908447 -0.08524054 -0.1330405 0.9890947 -0.06318169 -0.1389228 0.9881107 -0.06586158 0 1 3.97114e-7 -0.009518325 0.9999503 -0.002977609 -0.0121147 0.9998142 0.0149936 0.1901711 0.9711439 0.143925 0 1 1.70272e-6 0 1 6.65127e-7 0 1 9.67339e-7 0 0.9999898 0.00453782 0 1 -7.66835e-7 0.003809869 0.9999926 7.02104e-4 -0.001161158 0.9996214 -0.02749246 -0.001111328 0.9999781 0.006531238 -0.003419697 0.9999574 0.008583247 0 1 0 0 1 7.66617e-7 0 1 -1.1771e-6 1.55393e-4 0.999714 0.02391612 -0.001310229 0.9999877 -0.004788398 6.28048e-4 0.9998278 0.01855307 0 1 -1.30486e-6 0 1 -3.80819e-7 0 1 2.62055e-7 0 1 6.39645e-7 0 1 -5.31825e-7 0.4640657 -0.852559 0.2403878 0.4506598 -0.859877 0.2398277 0.5236477 -0.8390065 0.1478558 0.5547729 -0.8201878 0.1397107 0.1887722 -0.9809237 0.04641163 0.1859001 -0.9818048 0.03873622 0.2061035 -0.9700973 0.1281909 0.1681694 -0.9837158 0.06342142 0.05931967 -0.9820414 0.1790974 0.08775693 -0.9809224 0.1734652 0.08734548 -0.9816498 0.1695123 0.1343391 -0.9816094 0.1356325 0.02072483 -0.9723221 0.2327237 0.02968221 -0.9816098 0.1885771 -0.01679831 -0.9819037 0.1886345 -0.03289067 -0.9773708 0.2089608 -0.05209702 -0.9838855 0.1710417 -0.09444928 -0.977868 0.1866911 -0.09411054 -0.9821144 0.1630784 -0.1359048 -0.981174 0.1372138 -0.1424142 -0.9781002 0.1517836 -0.1690788 -0.9836109 0.06262677 -0.1888169 -0.9809145 0.04642111 -0.1859186 -0.9818057 0.03862398 -0.5243517 -0.839169 0.1443975 -0.5469041 -0.8257932 0.1377011 -0.4600875 -0.8552884 0.2383302 -0.1881211 -0.9772993 0.09744954 -0.2330174 -0.8564772 0.4605973 -0.3488405 -0.8288634 0.4373739 -0.347772 -0.8693479 0.3511254 -0.4587917 -0.8564669 0.2365897 0.3562922 -0.8399474 0.4093218 0.2463602 -0.8379561 0.4869664 0.08485001 -0.837956 0.5391015 0.08486396 -0.8379496 0.5391092 -0.03928703 -0.8403351 0.5406419 -0.0768758 -0.869247 0.4883645 -0.1395424 -0.8285934 0.5421817 -0.2330429 -0.8548325 0.4636295 -0.7765697 0.6297011 0.02039474 -0.9086408 0.4105286 0.07640784 -0.9667363 0.2078063 0.1491222 -0.9691901 0.1874358 0.1598076 -0.703499 -0.6249172 0.3384785 -0.8729051 -0.3820534 0.3034338 -0.8728396 -0.3821631 0.3034836 -0.9787935 0.06921219 0.1928035 -0.8386172 0.5245883 0.1467263 -0.9279676 0.2261648 0.2961854 -0.9258874 0.2607639 0.273377 -0.93383 -0.06700992 0.3513848 -0.9274765 -0.09418833 0.361823 -0.8590564 -0.3269199 0.3938854 -0.6805509 -0.6009993 0.4191067 -0.5167746 -0.5581107 0.6491969 -0.5848246 -0.6364575 0.5028939 -0.2415559 -0.9021542 0.3574472 -0.1860713 -0.8930951 0.4095835 -0.512723 -0.4232064 0.7470017 -0.9889611 0.1386331 0.05231738 -0.9897547 -0.03158926 0.1392396 -0.9222984 -0.163658 0.3501168 -0.9056669 -0.2026851 0.3724063 -0.5244155 -0.620739 0.5828135 -0.7407438 -0.4208115 0.5236568 -0.6690112 -0.4460075 0.5945598 -0.8594298 -0.40051 0.3177613 -0.6966935 -0.6135761 0.3716753 -0.7101171 -0.5933648 0.3790143 -0.9305598 0.3635386 -0.04356884 -0.9737372 0.227167 0.01520437 -0.9886471 0.1261666 0.08160281 -0.9889851 0.1235919 0.08144658 -0.9813417 0.03227186 0.1895446 -0.8842739 -0.2610167 0.3872082 -0.9208957 -0.152947 0.3585505 -0.8037733 -0.3539671 0.4781796 -0.7956892 -0.2807576 0.5367065 -0.7910453 -0.2870633 0.5402242 -0.9205473 0.3899629 0.02284264 -0.9800586 0.1848137 0.07299989 -0.9466036 0.3111671 0.08436024 -0.9872951 0.05576407 0.1487913 -0.9341975 -0.2389367 0.2649233 -0.8495883 -0.374821 0.3710917 -0.8855064 -0.2654831 0.3813098 -0.752185 -0.4594895 0.4723211 -0.4593622 -0.6594465 0.595077 -0.6742009 0.09275186 0.7327007 -0.9752116 -0.04596722 0.216447 0.1526108 -0.7888523 0.5953337 -0.6550824 -0.5118376 0.5557783 -0.4609481 -0.6409201 0.6137983 -0.2361192 -0.7373135 0.6329427 0.006587922 -0.7604449 0.6493691 0.2532518 -0.8235605 0.5075544 0.2646417 -0.8405464 0.4727016 -0.8512878 -0.3050486 0.4269127 -0.7967163 -0.3834475 0.467131 -0.6525517 -0.5128107 0.5578545 -0.9024946 -0.2263173 0.3664481 -0.8730589 -0.264223 0.4098225 -0.8481642 -0.202324 0.489574 -0.7640244 -0.2038157 0.6121485 -0.4939711 -0.3028632 0.8150255 -0.3928997 -0.3173063 0.8631029 -0.02638912 -0.1978425 0.9798786 0.7066498 -0.1574506 0.6898227 0.6427717 -0.2586022 0.7210892 0.6425587 -0.2169574 0.7348796 0.6184342 -0.4142856 0.6677625 0.2404976 -0.900913 0.3612711 0.2862736 -0.8851976 0.3667052 0.04674977 -0.7677993 0.6389828 0.08385962 -0.7501636 0.6559132 0.121169 -0.7616901 0.6365111 0.195599 -0.7405896 0.6428593 0.5130273 -0.6033956 0.6105055 0.5496538 -0.4759413 0.6865571 0.1850478 -0.4904698 0.8515849 0.1636119 -0.4671745 0.8688954 -0.02671766 -0.5205338 0.8534229 -0.1971547 -0.5640817 0.8018366 -0.2268962 -0.5521006 0.8023111 -0.593728 -0.3878482 0.7050255 -3.65796e-5 -0.7740108 0.6331725 0.001716494 -0.7739255 0.6332744 0.2057045 -0.8184962 0.5364231 0.2078155 -0.8627276 0.4609921 0.19497 -0.882911 0.4271475 0.2216699 -0.8805913 0.4188333 0.2039998 -0.8980235 0.3897924 0.2387223 -0.8899041 0.3886932 0.3290619 -0.7483704 0.5758994 0.3910896 -0.7512359 0.5316894 0.4189705 -0.7384396 0.5283661 0.3121882 -0.8456845 0.4328466 0.3404983 -0.8070707 0.4823876 0.2535857 -0.9004704 0.3533375 0.2036147 -0.933404 0.2954628 0.2126892 -0.9232912 0.3198387 0.2288893 -0.9559066 0.1839902 0.4935086 -0.7956141 0.3513511 0.5026813 -0.7800334 0.3726388 0.6880414 -0.547898 0.4758222 0.7194252 -0.4987061 0.4834457 0.7655959 -0.3632956 0.530923 0.8203361 -0.1262072 0.5577817 0.819126 -0.1612454 0.5504842 0.7474868 -0.1616685 0.6443033 0.6946267 0.05048477 0.7175967 0.5344619 -0.4634124 0.7068235 0.2305695 -0.9502224 0.2095599 0.2564008 -0.9396255 0.2266334 0.4422973 -0.7951185 0.4149215 0.6260362 -0.4984388 0.599698 0.6260359 -0.4984387 0.5996983 0.7126939 -0.1611358 0.6827172 0.6032067 -0.1615014 0.7810629 0.6001278 -0.1708479 0.7814458 -0.3741881 -0.8286132 0.4163935 -0.454266 -0.6570281 0.6016283 -0.7000538 -0.1612831 0.6956382 -0.677221 -0.2786636 0.6809687 -0.6306325 -0.4061164 0.6613413 -0.5360039 -0.6138258 0.5795841 -0.5409182 -0.6049735 0.584307 -0.4339237 -0.7464269 0.5045365 -0.2061492 -0.9626946 0.1752756 -0.3889798 -0.7647715 0.5136336 -0.4950352 -0.5081068 0.7048175 -0.4460949 -0.6332458 0.632455 -0.5339798 -0.1680176 0.8286348 -0.5364645 -0.1351996 0.8330228 -0.5049034 -0.221229 0.8343443 -0.4422245 -0.7395117 0.5075037 -0.6416547 -0.2327188 0.730836 -0.6302099 -0.2764266 0.7255508 -0.519924 -0.6120041 0.5959279 -0.5246193 -0.6043138 0.5996494 -0.2810211 -0.8848963 0.3714643 -0.3782733 -0.8077415 0.452176 -0.3857827 -0.8119946 0.4379916 -0.4000012 -0.8134288 0.4222945 -0.3225858 -0.8873445 0.3294816 -0.3021725 -0.8894728 0.3428265 -0.2837917 -0.9056977 0.314919 -0.5551952 -0.3774481 0.7411419 -0.6227185 -0.2861745 0.7282348 -0.5793734 -0.2888653 0.762157 -0.3601489 -0.8296836 0.4265186 -0.04399925 -0.9957532 -0.0808683 -0.0439701 -0.9957538 -0.08087635 -0.4975469 -0.4631693 0.7334312 -0.5305584 -0.341684 0.7757318 -0.5758924 -0.3362098 0.7451919 -0.5430841 -0.5022893 0.6728783 -0.502007 -0.6130896 0.6100083 -0.4878929 -0.6529077 0.5793722 -0.4200133 -0.7793068 0.4650481 -0.3836439 -0.7833517 0.4890578 -0.3268992 -0.8623746 0.3865841 -0.385351 0.7170776 0.580779 -0.3853559 0.7170649 0.5807915 -0.4510914 0.5513899 0.7017733 -0.4976035 0.3642958 0.7871972 -0.5001237 0.333175 0.7992939 -0.5111524 -0.1156333 0.8516761 -0.5111438 -0.11561 0.8516845 -0.4170936 -0.5425878 0.7291307 -0.408898 -0.5708338 0.7120051 -0.269962 -0.8648291 0.4233099 -0.6077233 -0.6053967 0.5139722 -0.8432655 0.3040034 0.4432668 -0.8432597 0.3040021 0.4432784 -0.8469998 -0.05046039 0.5291929 -0.8194748 -0.1687775 0.5477002 -0.7861033 -0.2865168 0.5476768 -0.6077167 -0.6053971 0.5139794 -0.2337556 -0.86131 0.4511135 -0.2337579 -0.8613146 0.4511036 -0.2699688 -0.8648403 0.4232825 -0.5200552 -0.5813476 0.6257617 -0.5200651 -0.5813398 0.6257606 -0.6863884 -0.1328914 0.7149901 -0.6907581 0.3440534 0.6359879 0 0.6934965 0.7204601 0.1549938 -0.8414016 0.5177069 -0.03904712 -0.843344 0.5359537 0.2066282 0.6935029 0.6901874 0.2702642 0.3347044 0.9027349 0.2702584 0.321847 0.9074002 0.2847561 0.1193307 0.9511436 0.2848995 -0.1150296 0.9516305 0.2848899 -0.1150225 0.9516342 0.2431281 -0.5304426 0.812108 0.243124 -0.5304418 0.8121098 -0.1998428 0.7172892 0.6675022 -0.2038017 0.6937081 0.6908212 0 0.6935024 0.7204543 0 0.3217881 0.9468118 0 0.3217862 0.9468123 0 -0.1150243 0.9933627 0 -0.1150223 0.993363 0 -0.5304449 0.8477196 0 -0.5304446 0.8477197 0.039047 -0.8433452 0.5359517 -0.1467742 -0.8591277 0.4902622 -0.1521025 -0.8415848 0.5182665 -0.1965416 -0.7283131 0.6564537 -0.2431296 -0.5304465 0.812105 -0.2403212 -0.5397863 0.8067691 -0.2860598 -0.1150113 0.9512846 -0.2860549 -0.1150282 0.9512839 -0.2704953 0.321838 0.9073327 -0.270505 0.3322714 0.9035612 -0.2393814 0.5507324 0.799619 0.8426339 0.307453 0.442087 0.842642 0.3074222 0.442093 0.8211486 -0.1624004 0.5471209 0.7875035 -0.2827169 0.5476401 0.6134954 -0.5980116 0.5157573 0.6135058 -0.597984 0.515777 0.2736118 -0.8621194 0.4264819 0.2492936 -0.8437168 0.4753892 0.4116166 -0.5628895 0.7167477 0.4199882 -0.5331578 0.7344065 0.5117309 -0.1156182 0.8513307 0.5128406 -0.1092155 0.8515085 0.5188438 0.1195708 0.8464656 0.4945561 0.3678399 0.7874693 0.697824 0.6635879 0.2696162 0.6978468 0.6635569 0.2696334 0.5611827 0.698942 0.4433442 0.3967781 0.6934377 0.6014245 0.3824058 0.7178641 0.5817533 0.6901628 0.3474666 0.6347774 0.690156 0.347449 0.6347944 0.687575 -0.126412 0.715025 0.6875702 -0.126366 0.7150377 0.5246591 -0.5736131 0.6290477 0.5246695 -0.5736041 0.6290472 0.2735857 -0.8621349 0.4264674 0.3021882 -0.8699193 0.3897727 0.3021863 -0.8699085 0.3897983 -0.09285211 0.9935798 0.06463521 -0.09118306 0.9900198 0.107455 -0.09665977 0.9782711 0.1834192 -0.05880796 0.9842968 0.1664381 -0.0299685 0.9839097 0.1761351 -0.02996772 0.9839093 0.1761373 0.02633416 0.9839103 0.1767117 0.02633464 0.9839094 0.1767169 0.1001762 0.9935585 0.0529741 0.08996802 0.9796181 0.1795945 0.2522814 0.9279326 0.2743998 0.05821651 0.9842858 0.1667109 0.07476752 0.9903702 0.1165188 0.098526 0.9901555 0.09942239 0.09852617 0.9901556 0.09942144 0.1245748 0.9901556 0.06382125 0.1245754 0.9901553 0.0638231 0.1382513 0.9901554 0.02188372 0.1382504 0.9901556 0.02188354 0.4039936 0.9142824 -0.02961319 0.1382369 0.9903474 -0.01013243 0.1382356 0.9903476 -0.01013487 0.4039846 0.9142863 -0.02961689 0.403446 0.9127722 0.0638622 0.403437 0.9127762 0.06386035 0.3635354 0.9127737 0.1862427 0.3635311 0.9127748 0.1862459 0.2875201 0.9127737 0.2901318 0.2875214 0.9127735 0.2901312 0.1829468 0.9127753 0.3652011 0.1829437 0.9127739 0.3652061 0.06020933 0.9127737 0.4040039 0.06020849 0.9127746 0.4040017 -0.06851434 0.9127758 0.4026738 -0.06851136 0.9127749 0.4026762 -0.1904281 0.9127765 0.3613533 -0.1904256 0.9127761 0.3613556 -0.2934263 0.912776 0.2841495 -0.2934283 0.9127761 0.2841474 -0.367291 0.9127741 0.17872 -0.4046717 0.9127738 0.05554068 -0.1380271 0.9903612 -0.0115481 -0.4034369 0.9143849 -0.03375214 -0.1386721 0.9901555 0.01903295 -0.1386712 0.9901556 0.01903152 -0.1258624 0.9901555 0.06124514 -0.1258637 0.9901554 0.06124293 -0.1005529 0.9901554 0.0973736 -0.1005515 0.9901556 0.09737205 -0.0809555 0.9903932 0.1121057 -0.003241479 0.9999825 0.004942774 0.300432 0.9129581 -0.2761307 0.2789307 0.9539614 -0.1102514 0.3450112 0.9361761 -0.06739264 0.398271 0.9146153 -0.0697093 0.103111 0.9911712 -0.08335387 0.1050238 0.9900824 -0.09331142 0.1271902 0.9902571 -0.0566889 0.1367663 0.9890624 -0.0552327 0.1296138 0.9912412 -0.02531951 0.1383028 0.9899105 -0.03081667 0.1367008 0.990396 -0.02070349 0.101389 0.9809846 -0.165498 0.1000059 0.9800481 -0.1717692 0.05480229 0.9818909 -0.181348 0.05111461 0.9805733 -0.1893763 0 0.9812213 -0.1928857 0 0.9812211 -0.1928863 -0.05709427 0.980329 -0.1889324 -0.04925769 0.9819719 -0.1824966 -0.104614 0.9797422 -0.1707665 -0.09791189 0.9808834 -0.1681702 0.03283035 0.9978691 -0.05638766 0.03282982 0.9978691 -0.05638808 0.01700341 0.9978691 -0.0629943 0.01700258 0.997869 -0.06299638 0 0.997869 -0.06524908 -0.01700299 0.997869 -0.06299495 -0.01700288 0.997869 -0.06299561 -0.03282994 0.9978691 -0.05638623 -0.03283005 0.997869 -0.05638939 -0.4369461 0.8950852 -0.08888679 -0.2274894 0.9735655 0.02046263 -0.3229852 0.9324505 -0.1619158 -0.1158238 0.9932354 0.008278071 -0.1471281 0.9805426 -0.1299606 -0.2266576 0.9663726 -0.1214507 -0.2220422 0.9656198 -0.1351884 -0.2968089 0.9473353 -0.120252 -0.3672524 0.9300444 -0.01196414 -0.3773506 0.9260564 0.005114614 0.09245955 -0.6946076 0.7134225 0.3142693 -0.6543634 0.6877815 -0.4270411 -0.728666 0.5354267 -0.7878512 -0.5763893 0.2169474 -0.5549074 -0.5898788 0.5866183 -0.7153722 -0.5898203 0.3746396 -0.6746764 -0.6935968 0.2524582 -0.6663579 -0.7026722 0.2494373 -0.602333 -0.7567191 0.2541087 -0.6275791 -0.7081058 0.3236215 -0.6017084 -0.6366471 0.482315 -0.6775314 -0.5563362 0.4810836 -0.6607913 -0.496687 0.5627229 -0.752732 -0.3560476 0.5537371 -0.6842554 -0.1473906 0.7141923 -0.5760509 -0.08672767 0.8127999 -0.5760807 -0.0867449 0.8127769 -0.5761656 -0.08666801 0.812725 -0.4735043 -0.3449674 0.8104267 -0.6046612 -0.1754404 0.7769206 -0.5271056 -0.2104837 0.8233204 -0.501255 -0.273575 0.8209143 -0.5760315 -0.08674108 0.8128123 -0.6722308 -0.1755368 0.7192305 -0.6548426 -0.2624669 0.7087259 -0.6553791 -0.2617101 0.7085098 -0.642761 -0.3266237 0.6929469 -0.6135345 -0.3786383 0.6929707 -0.5960381 -0.4480195 0.6663462 -0.4596809 -0.5468704 0.699733 -0.4967901 -0.5223656 0.6930612 -0.4452041 -0.3315038 0.8318044 0.07987946 -0.6001235 0.795909 0.1228801 -0.64887 0.7509116 0.01017719 -0.5172197 0.8557923 0.1148424 -0.4454258 0.887923 0.07816857 -0.4610692 0.8839145 0.009172916 -0.516544 0.8562116 -0.0185576 -0.5107017 0.8595577 -0.07017695 -0.5272845 0.8467859 -0.1514574 -0.503264 0.8507563 -0.2144136 -0.5114771 0.8321166 0.4127634 -0.6145673 0.6722599 0.489302 -0.6283689 0.6047613 0.5090137 -0.2555229 0.8219569 0.5361073 -0.186705 0.8232438 0.5679765 -0.22679 0.7911821 0.4848043 -0.3339031 0.808377 0.6279373 -0.1336608 0.7667005 0.5396488 -0.1916988 0.8197748 0.6332232 -0.4112625 0.6556612 0.5920714 -0.4450148 0.671873 0.6119234 -0.3813636 0.6929008 0.6456627 -0.3211517 0.6928068 0.6831233 -0.1876738 0.7057771 0.6334971 -0.1384748 0.7612531 0.5973955 -0.7699165 0.2243818 0.6608009 -0.5754373 0.481886 0.6462445 -0.5999874 0.4715752 0.6649975 -0.4998315 0.5549297 0.7138199 -0.4523619 0.5346307 0.7232106 -0.3222844 0.6108185 0.6225342 -0.7090197 0.3312738 0.661594 -0.7077655 0.2477124 0.6456326 -0.7415729 0.1822858 0.6044178 -0.6295727 0.4881777 0.6028799 -0.6355217 0.4823361 0.4979798 -0.6516951 0.5721099 0.5194697 -0.667118 0.5339521 0.3064284 -0.7343189 0.6057042 0.3222802 -0.6502397 0.6879854 0.2631686 -0.6364653 0.7250202 0.2469469 -0.582049 0.7747492 0.1557999 -0.5718291 0.8054426 -0.3054012 -0.6544028 0.6917276 -0.3460116 -0.6375164 0.6883667 -0.2656777 -0.633777 0.7264586 -0.183964 -0.674838 0.7146685 -0.05356198 -0.6735311 0.7372157 0.1154254 -0.6699956 0.7333369 -0.2803633 -0.4676052 0.838297 -0.3728429 -0.4788274 0.7948036 -0.4446291 -0.5710192 0.690103 -0.4446281 -0.5710211 0.6901021 -0.5036723 -0.6468331 0.5726441 -0.5903055 -0.6435229 0.4872555 0.324303 -0.6898587 0.6472423 0.1915732 -0.562559 0.8042557 0.4482613 -0.4025257 0.7981447 0.350552 -0.2708621 0.8965195 0.1021884 -0.2300277 0.9678041 0.3947593 -0.1143093 0.911646 -0.6555659 -0.5573589 0.5094944 -0.8013122 -0.4308165 0.4150854 -0.878338 -0.3524993 0.3229037 -0.8588985 -0.3850894 0.3376384 -0.9108772 -0.2983248 0.2851403 -0.1906493 -0.6986006 0.6896449 0.1845697 -0.2802879 0.9420047 0.2132822 -0.2888069 0.9333281 0.2133225 -0.09496921 0.9723551 0.1593858 -0.07413822 0.9844287 -0.3553535 -0.1814463 0.9169521 -0.4609086 -0.6493216 0.6049338 -0.4637358 -0.648932 0.6031885 -0.4596647 -0.4714557 0.7526207 -0.7008972 -0.3961853 0.5931107 -0.6221602 -0.4087604 0.6677062 -0.8772646 -0.2696715 0.3970949 -0.8214364 -0.2952627 0.4879162 -0.9452219 -0.1797076 0.2725084 -0.9465258 -0.08942174 0.3099884 -0.9845019 -0.127578 0.1203327 -0.9842395 -0.1281813 0.1218292 -0.9835585 -0.08863204 0.1573441 -0.9969161 -0.04405701 0.06494015 0.324371 -0.5694716 0.7553051 0.1397872 -0.6093124 0.7805113 -0.08702188 -0.2962864 0.9511265 0.1131834 -0.2003579 0.973163 -0.07751631 -0.1017754 0.9917828 -0.9829541 -0.02227944 0.1824967 -0.8155965 -0.1247681 0.5650091 -0.8210288 -0.1257717 0.5568602 -0.5646206 -0.1499188 0.8116205 -0.6206133 -0.15889 0.7678498 -0.3644122 -0.178848 0.9139022 -0.3648823 -0.5070185 0.7808926 0.06134998 -0.5148649 0.8550733 -0.1903687 -0.6089163 0.7700525 0.0819565 -0.5993288 0.7962966 0.08221572 -0.7160293 0.6932119 0.1517351 -0.6879031 0.7097646 -0.9886295 0.1503525 -0.002428531 -0.7895177 0.6098586 -0.06880676 -0.7849139 0.6192171 -0.02191871 -0.8656246 0.4898 -0.1038759 -0.9543256 0.267013 -0.1340408 -0.948881 0.3057207 -0.0784837 -0.9364343 0.3495207 -0.03043097 -0.67421 -0.4114374 0.613319 -0.9076399 -0.1913214 0.3736121 -0.7912254 -0.2708891 0.5482532 -0.9865359 0.0683943 0.1485571 -0.8837847 -0.3372095 0.3243678 -0.8587839 -0.4613337 0.2228487 -0.731483 -0.1197637 0.6712595 -0.5128922 -0.3622363 0.7782843 0.4054906 -0.828942 0.3852697 -0.8599348 -0.483683 0.1629816 -0.804623 -0.5596171 0.1985218 -0.556348 -0.7831472 0.2777723 -0.4502373 -0.8475122 0.2810866 -0.6356478 -0.7275322 0.2581646 0.7292767 -0.6569057 0.1913912 0.5944542 -0.7736558 0.2192738 0.7281997 -0.6445264 0.2330471 0.3968824 -0.8654589 0.3057209 0.2931472 -0.9037719 0.3118672 0.1272341 -0.9324642 0.3381156 -0.145213 -0.93503 0.323469 -0.1626216 -0.9319017 0.3242123 -0.3027497 -0.8982362 0.3186134 0.7802353 -0.2918891 0.5532032 0.7027321 -0.1889448 0.6859063 0.4470954 -0.2297032 0.8644896 0.501653 -0.2170327 0.8374013 -0.02055525 -0.2392899 0.9707306 -0.877494 -0.1038497 0.4682089 -0.7899619 -0.1218695 0.6009228 -0.860596 -0.1179866 0.4954329 -0.556454 -0.1859998 0.809792 -0.4251897 -0.2144438 0.8793337 -0.9667977 -0.2371948 0.09508383 -0.9864241 -0.1544451 0.05580681 -0.9892505 -0.1239922 0.0775206 -0.8594235 -0.4287858 0.2784493 -0.1447919 -0.8298441 0.5388823 0.2923011 -0.8020493 0.5208425 0.8040137 -0.4986883 0.3238393 0.7494568 -0.4394937 0.4951362 0.5084691 -0.6770039 0.5320949 -0.9751328 -0.04656785 0.2166736 -0.988578 -0.04286903 0.1444854 -0.8594428 -0.2255864 0.4587688 0.6129775 -0.3486418 0.7090188 0.6319185 -0.5006167 0.5916604 -0.8269451 -0.00339365 0.5622726 -0.2069454 -0.9313868 0.2994871 -0.215679 -0.9206994 0.325262 -0.349126 -0.8044479 0.4805982 -0.1516312 -0.8156525 0.5583181 -0.2948565 -0.8663274 0.4031581 -0.3692005 -0.7586365 0.5368071 -0.3852698 -0.7152447 0.5830886 -0.6010938 -0.161476 0.7826952 -0.5835133 -0.04248982 0.8109912 -0.5957378 -0.1937629 0.7794564 -0.5263334 -0.4992057 0.6883072 -0.5292289 -0.4356665 0.7280877 -0.4731709 -0.6206631 0.6252093 -0.8227313 -0.1034045 0.5589463 -0.8202117 -0.1611791 0.5488846 -0.7836894 -0.304579 0.5413525 -0.7171863 -0.4988511 0.4866122 -0.7135173 -0.5046196 0.486058 -0.2307105 -0.9497326 0.2116145 -0.2319988 -0.944373 0.2331012 -0.6340038 -0.6710675 0.3843274 -0.4818815 -0.795975 0.3663523 -0.4422971 -0.7951166 0.4149254 -0.2581455 -0.9387209 0.2283945 -0.4245184 -0.7651057 0.484146 -0.423564 -0.8099143 0.4057494 -0.6260327 -0.4984424 0.5996986 -0.6260295 -0.4984493 0.5996961 -0.712691 -0.161143 0.6827185 -0.7126979 -0.1611092 0.6827192 0.5976392 -0.3944731 0.6980103 0.04646277 -0.7619901 0.6459198 0.6871777 -0.3677042 0.6265624 0.6662622 0.01090061 0.7456379 -0.4826467 -0.6031866 0.6349947 -0.3548113 -0.7264429 0.5885488 -0.2509095 -0.8202034 0.5141118 -0.2092154 -0.8281443 0.5200058 -0.2753159 -0.8840124 0.3777875 -0.2392419 -0.9010002 0.361887 -0.2272294 -0.8896803 0.396025 -0.2184906 -0.8927081 0.3941248 -0.2008393 -0.8796064 0.4312265 -0.2270243 -0.875185 0.4272134 -0.1779875 -0.8613271 0.475853 -0.2093444 -0.8582643 0.4685697 -0.5639991 -0.1391795 0.813962 -0.09063142 -0.3604258 0.9283745 -0.2169374 -0.1149981 0.9693883 -0.3465172 -0.3312649 0.8776044 -0.5833186 0.08767819 0.8074974 0.210079 -0.270332 0.9395678 0.2083393 -0.2597567 0.9429323 -0.002561211 -0.2526074 0.9675655 0.8594089 -0.2279433 0.4576661 0.997264 -0.04772222 0.05645501 0.9683053 -0.1156407 0.2213866 0.9654206 -0.1266678 0.2278561 0.8599361 -0.2926258 0.4181869 0.906543 -0.2200801 0.3602007 0.8734128 -0.2643715 0.4089719 0.824753 -0.3520966 0.4425049 0.7006568 -0.4756957 0.5317836 0.6514574 -0.5039238 0.5671544 0.6038124 -0.549359 0.5775945 -0.1889701 -0.7230491 0.6644474 0.8413162 -0.1986675 0.5027109 0.7354609 -0.2185916 0.6413385 0.5979889 -0.3937013 0.6981467 0.5022983 -0.3070685 0.808335 0.4266036 -0.3257111 0.8437545 0.4233592 -0.3169457 0.8487122 0.3535028 -0.2803542 0.8924334 -0.3955225 -0.7387961 0.5456577 -0.3811802 -0.7483322 0.5428634 -0.2826935 -0.7517305 0.5958068 -0.2979488 -0.7406266 0.6022449 -0.1697037 -0.7606188 0.6266257 -0.1923268 -0.7329528 0.6525263 -0.07682555 -0.7700403 0.6333528 -0.08828145 -0.7405926 0.6661298 -0.02282601 -0.775383 0.6310786 -0.01983493 -0.7558771 0.654413 1.56447e-4 -0.7739843 0.6332049 -1.92067e-4 -0.7742224 0.6329136 0.02475118 -0.8226181 0.5680553 -0.229951 -0.7769953 0.5860042 -0.3839921 -0.7549184 0.5316469 0.3593267 -0.6946653 0.6231569 0.3504843 -0.7022816 0.6196461 0.3148434 -0.6284449 0.711288 0.3152566 -0.6277998 0.7116747 0.2329803 -0.5533317 0.7997151 0.2289142 -0.5764802 0.7843909 0.08161717 -0.4990621 0.8627141 0.08879101 -0.5342862 0.8406275 -0.1294892 -0.4646896 0.8759545 -0.1131526 -0.4984013 0.8595305 -0.3452979 -0.4626934 0.8165073 -0.3336421 -0.476626 0.813333 -0.5234499 -0.4696169 0.7109572 -0.5798963 -0.3966338 0.7116193 0.3563166 -0.8725562 0.3341919 0.791109 -0.3389195 0.5091955 0.455509 -0.7206392 0.5226765 0.9194743 0.3927911 0.01680248 0.9822008 0.1657801 0.08831113 0.9651775 0.2614864 -0.007571995 0.9616166 0.2738044 0.01802301 0.9888777 0.09173774 0.1170691 0.9870867 0.1489056 0.05905169 0.9893007 -0.03839939 0.1407464 0.9958279 0.09105449 0.005984306 0.9869815 -0.03649711 0.1566386 0.9878358 -0.02897393 0.1527776 0.9153318 -0.1768201 0.3618046 0.9056988 -0.1979227 0.374882 0.7845872 -0.3014786 0.5417876 0.7383769 -0.3565303 0.5724385 0.5122125 -0.4391064 0.738122 0.5220584 -0.4277524 0.7378909 0.5373481 -0.5086707 0.6726896 0.5057382 -0.6018342 0.6180813 0.4885803 -0.5829195 0.6492259 0.9520738 0.3058575 0.002598762 0.9543039 0.2843612 0.09188491 0.985037 0.1039959 0.1374302 0.9663004 -0.1000784 0.2371662 0.9360085 -0.2452683 0.2524514 0.8443151 -0.4160726 0.3376621 0.8754131 -0.386418 0.2904017 0.6953951 -0.6190829 0.3649137 0.6988378 -0.6170975 0.3616856 0.5679772 -0.7336855 0.3729714 0.4090679 -0.8057803 0.4282311 0.4065263 -0.8000971 0.4411133 0.6770765 -0.578812 0.4544713 0.7340158 -0.5408681 0.4107099 0.8331252 -0.3923673 0.3898085 0.8752107 -0.3453546 0.3387278 0.9548652 -0.1029841 0.278616 0.4365859 -0.6690432 0.6014766 0.5107638 -0.6725243 0.5355666 0.714111 -0.4838753 0.5058758 0.7184438 -0.4814172 0.5020717 0.8565614 -0.2935121 0.4244448 0.9187672 -0.2016881 0.3393946 0.9534689 -0.09947818 0.2846069 0.9820591 -7.45069e-4 0.1885722 0.9862267 0.1189367 0.114939 0.9870793 0.1480228 0.06135094 0.9671096 0.2538759 -0.01568716 0.4956942 0.8677366 -0.03633862 -0.5677214 0.8218497 -0.04749482 -0.5861628 0.7919098 0.1711493 0.5861658 0.7919078 0.1711484 0.5440655 0.8337535 -0.09406298 0.5637388 0.8249952 -0.03976732 -0.7110699 0.7030866 0.007005333 -0.610006 0.7874022 -0.08882862 0.6809167 0.7323246 0.007296621 0.5614138 0.8232204 0.08439618 0.5721482 0.8173807 0.06734454 0.3900061 0.9187404 0.06173634 0.5567445 0.810254 0.183096 0.4723566 0.8475362 0.2419952 0.5101597 0.7719943 0.3791594 0.336017 0.8787071 0.339067 0.3667545 0.7522026 0.5474326 0.2003923 0.8943238 0.4000349 0.1859384 0.7613863 0.6210619 0.06556469 0.8956227 0.439956 0 0.7607566 0.6490374 -0.1842056 0.7664562 0.6153156 -0.211089 0.8916235 0.4005607 -0.362905 0.7590003 0.5405724 -0.3444741 0.8775322 0.3335791 -0.5090508 0.7733943 0.3777945 -0.5537346 0.8120433 0.1842926 -0.4207249 0.9053488 0.05774289 -0.5712066 0.8184787 0.06177341 -0.5512663 0.8294175 0.09040039 -0.6728094 0.7397025 0.01295399 0.9122346 0.4054013 0.05897402 0.7820298 0.6169133 0.08858644 0.9223972 0.2663176 0.279747 0.9324907 0.2228753 0.284232 0.9296084 -0.09288197 0.3566529 0.9321307 -0.0655775 0.3561347 0.858317 -0.321858 0.3996242 0.8460455 -0.3547011 0.3979878 0.6588619 -0.6236578 0.4206566 0.6768174 -0.5973281 0.4302528 0.5733568 -0.7430051 0.3452615 0.7035003 -0.6248309 0.3386351 0.7035997 -0.6247056 0.33866 0.8727666 -0.3821539 0.3037056 0.8728474 -0.3819523 0.3037269 0.9656506 -0.09915137 0.2401829 0.9656677 -0.09899121 0.2401807 0.9699199 0.1864302 0.1565219 0.9699198 0.1864366 0.1565156 0.9236775 0.3721038 0.0914272 0.7685651 0.6362287 0.06723755 0.3560028 -0.8719841 0.3360149 0.3806677 -0.8571344 0.3470054 0.3745025 -0.8507059 0.3688461 0.3271057 -0.8834006 0.3355674 0.3130363 0.9497255 0.005457997 0.35628 0.9330525 -0.04977607 0.4912497 0.8705072 -0.02984869 0.5511603 0.8341413 -0.02075755 0.3682922 0.9295812 -0.01548171 0.3100684 0.9459475 -0.09508347 0.2502292 0.9638832 -0.09118455 0.2288929 0.9656497 -0.1229993 0.1528117 0.9802554 -0.1254907 0.3171942 0.9483606 0 0.2984557 0.9542933 -0.01576542 0.2026112 0.9787535 -0.03147006 0.04441124 0.9978873 -0.04741966 -0.1758274 0.9844211 4.51899e-6 -0.1584849 0.9873582 -0.002570629 -0.6194975 0.7845921 -0.02526229 -0.6712079 0.7369584 -0.07982683 -0.307758 0.9514647 -1.98979e-4 -0.3524532 0.9358294 1.50257e-4 -0.3227058 0.9464994 -2.00547e-4 -0.3563725 0.9343441 1.7085e-4 -0.5241084 0.8516482 0.002417564 -0.373416 0.9275097 0.01692622 -0.3775246 0.9258517 0.01655095 -0.3868691 0.9220004 0.0157352 -0.3931462 0.9193501 0.0152105 -0.4085646 0.9126239 0.01388263 -0.4269517 0.9041893 0.01240867 -0.4391503 0.8983405 0.01146686 -0.4692106 0.8830385 0.009186744 -0.4987355 0.8667236 0.00728625 -0.510443 0.8598867 0.006560504 -0.5219296 0.8529683 0.005872964 -0.5334665 0.8458051 0.005222141 -0.5504481 0.8348584 0.004304945 -0.5673065 0.8234994 0.003498494 -0.5782271 0.8158704 0.003002583 -0.5892882 0.807919 0.002539932 -0.600105 0.7999185 0.002117097 -0.6162199 0.7875728 0.001541018 -0.6319757 0.7749875 0.001079738 -0.6424755 0.7663058 8.09202e-4 -0.6577769 0.7532127 4.62684e-4 -0.6779088 0.7351461 1.5431e-4 -0.6974985 0.7165863 0 -0.7574924 0.6525387 0.01995837 -0.770523 0.6371566 0.01805114 -0.7875224 0.6160869 0.01566898 -0.8038482 0.5946825 0.01345282 -0.8196485 0.5727534 0.0113998 -0.8348016 0.5504688 0.009512424 -0.8458924 0.5332902 0.00822097 -0.8528889 0.5220401 0.007404506 -0.8633257 0.5046084 0.006240129 -0.8733832 0.487006 0.00520277 -0.8798983 0.4751403 0.004553794 -0.8862266 0.4632351 0.003948748 -0.8924044 0.451224 0.003384888 -0.9013439 0.4330964 0.002604663 -0.9127101 0.4086041 0.001737594 -0.7485705 0.6627143 0.02126514 -0.9053133 0.4246715 -0.007864952 -0.7259296 0.6877566 0.004149556 -0.8017374 0.597674 -0.001737415 -0.7328356 0.6804058 0 -0.9285091 0.3713091 6.94392e-4 -0.9843216 0.176373 -0.001914501 -0.9888087 0.1491892 5.10358e-5 0.01628726 -0.04227209 0.9989734 0.06641721 -0.7172504 0.693643 -0.2824172 -0.5099718 0.812508 -0.2840396 -0.6658606 0.6898922 -0.1888778 -0.7175611 0.6703965 -0.3553217 -0.6672936 0.654573 0.4167618 -0.6465089 0.6390117 0.3573021 -0.6445931 0.6758956 0.04669022 -0.7227416 0.6895395 0.9150456 -0.2967965 0.2731364 0.8289905 -0.3920495 0.3988384 0.7132759 -0.5081021 0.4827731 0.7035593 -0.5123404 0.4924548 0.6049339 -0.564733 0.561366 -0.3961158 -0.04979521 0.9168494 -0.4020495 -0.05687695 0.9138497 -0.3989985 -0.2298211 0.8876838 0.300883 -0.04882758 0.9524103 0.5738682 -0.04440325 0.8177431 0.6206027 -0.002122879 0.7841224 0.8241045 -0.08663797 0.5597729 0.8612822 -0.02182918 0.5076579 0.9840475 -0.01394414 0.1773592 0.9754035 -0.04890412 0.2149336 0.6203284 -0.1639313 0.7670198 0.3196669 -0.1862234 0.92905 0.2998294 -0.198483 0.9331168 -0.03774219 -0.1966497 0.9797471 0.9972356 -0.0459823 0.05836945 0.9837345 -0.1163865 0.136824 0.9908849 -0.04632359 0.1264966 0.8862215 -0.1303014 0.4445594 0.8568971 -0.1577588 0.4907541 0.6606592 -0.2147107 0.7193253 0.324277 -0.35141 0.8782684 0.3552308 -0.3488726 0.8672366 0.3197715 -0.3715732 0.871596 -9.68331e-5 -0.3739383 0.9274537 -0.03762185 -0.3910274 0.9196098 0.9686154 -0.1561629 0.1933842 0.7823464 -0.4043925 0.4737098 0.8883706 -0.2649313 0.374979 0.7131329 -0.3816131 0.5880587 0.6647285 -0.4256517 0.6139681 0.4160008 -0.4970121 0.7615264 0.3546409 -0.5312643 0.7694076 0.06629753 -0.5465104 0.834824 1.03656e-4 -0.5671004 0.8236488 -0.2174527 -0.5391487 0.8136542 -0.402612 -0.3384013 0.8505223 -0.2606443 -0.1939973 0.9457429 -0.05828064 -0.2072309 0.9765545 -0.05866444 -0.1508247 0.9868184 0.3636813 0.0247628 0.9311943 0.6187841 -0.1824886 0.7640709 0.9832767 -0.1081822 0.1465048 0.145206 -0.935242 0.3228588 0.0330519 -0.9415423 0.3352696 -0.2932968 -0.9017051 0.3176555 -0.2105296 -0.9259899 0.3134011 -0.3893743 -0.8685292 0.306667 0.5559625 -0.7861124 0.2700611 0.4708176 -0.8314711 0.2949352 0.2664326 -0.9083964 0.3222262 0.9637739 -0.2485173 0.09684509 0.8103745 -0.5565096 0.1832765 0.8603211 -0.480426 0.170407 0.6703861 -0.6992996 0.2481182 0.5925604 -0.7609534 0.2642391 0.994969 -0.08660244 0.05036777 0.9781602 -0.1536696 0.1399588 0.9892545 -0.06225717 0.1322864 0.899467 -0.09622323 0.4262633 0.9270774 -0.08456707 0.3652067 0.9864234 -0.03697258 0.1600064 0.9797563 -0.04175269 0.1957916 0.9990747 -0.009652018 0.04191267 0.860578 -0.1180285 0.4954541 0.7847486 -0.122087 0.6076714 0.8689704 -0.1062188 0.4833303 0.002401471 -0.2130214 0.9770447 0.2145354 -0.2314587 0.9488949 0.5569366 -0.196534 0.8069673 0.3804383 -0.1839401 0.9063294 0.4643748 -0.1884986 0.8653464 0.1455466 -0.236764 0.9606035 -0.2938467 -0.2288724 0.9280472 -0.2226904 -0.219945 0.9497544 -0.6628008 -0.1974276 0.7223002 -0.5625342 -0.1670953 0.8097126 -0.6100277 -0.7460864 0.2668735 -0.5742584 -0.7692902 0.2800357 -0.6737297 -0.6237761 0.3962217 0.9922782 -0.0547229 0.1113084 0.8594513 -0.225579 0.4587566 0.8594213 -0.2256042 0.4588006 0.554795 -0.3671175 0.7466105 0.5548027 -0.3671196 0.7466038 0.1448984 -0.4365943 0.8879132 0.1447571 -0.4366165 0.8879253 -0.292295 -0.421993 0.8581874 -0.2923861 -0.4219654 0.8581699 -0.8038578 -0.2624694 0.5337813 -0.4280837 -0.3138684 0.8474851 0.9942497 -0.07107806 0.08009821 0.8594147 -0.339399 0.3823805 0.8594213 -0.3393954 0.3823687 0.5548406 -0.5522826 0.6222025 0.5548546 -0.5522655 0.6222051 0.1448151 -0.6568303 0.7400018 0.1447584 -0.6568316 0.7400118 -0.2923252 -0.6348375 0.7152115 -0.2922587 -0.6348363 0.7152397 -0.7897003 -0.40726 0.4588168 -0.413367 -0.4924588 0.765906 0.9997867 -0.01955109 0.00666058 0.9902595 -0.1322376 0.04358392 0.9831389 -0.1533563 0.0995981 0.8594375 -0.4287566 0.2784512 0.8594174 -0.4287984 0.2784488 0.5548313 -0.697758 0.453096 0.5548361 -0.6977393 0.4531192 0.1447883 -0.8298395 0.5388903 0.144761 -0.8298351 0.5389046 -0.2922872 -0.8020551 0.5208415 -0.2922871 -0.8020542 0.5208429 -0.7256838 -0.5770329 0.3747215 -0.5151453 -0.607737 0.6043849 0.8779995 -0.4765717 0.0446816 0.989959 -0.05958563 0.1281822 0.9002078 -0.05906116 0.431437 0.7300168 -0.446669 0.5172644 0.673115 -0.5959268 0.4379356 0.5077053 -0.1822045 0.8420434 0.4662531 -0.3562183 0.8097633 0.989646 -0.05384576 0.1330469 0.9057189 -0.1935098 0.3771304 0.9077955 -0.1719506 0.3825446 0.7397871 -0.3030021 0.6007535 0.743014 -0.2796506 0.6080508 0.5129567 -0.3841708 0.7676512 0.5172165 -0.3606007 0.7761794 0.7893261 0.6124384 -0.04340255 0.8730816 0.4800869 -0.08511865 0.9434705 0.3261546 -0.05904924 0.9467906 0.3143243 -0.06919586 0.9488061 0.3060972 -0.07792091 0.9532158 0.2781605 -0.118349 0.9911231 0.1293746 -0.03061336 0.9762428 0.2162483 -0.01366829 0.8098239 0.2186636 -0.5444002 0.9319364 0.2349127 -0.2762438 0.6964222 0.7175968 0.007149994 0.7860817 0.6157648 -0.05393868 0.7895069 0.6110047 -0.05789953 0.8882658 0.4586046 -0.02580136 0.937562 0.3459674 -0.03583371 0.9932816 0.1157231 0 0.9659207 0.2588124 -0.003677248 0.6087576 0.7933553 0.001293301 0.8187366 0.5741684 -0.001054108 0.7933489 0.6087674 2.10537e-4 0.9063585 0.4225096 -1.22497e-4 0.9556362 0.2945392 -0.002502202 0.2588188 0.965926 0 0.1189432 0.9928514 -0.009936809 0.252723 0.9675309 -0.003886342 0.6233453 0.7807889 -0.04253762 0.5664666 0.8240788 0.003112912 0.3405404 0.9402283 -0.001753449 0.325443 0.9455593 -0.00211507 0.3796462 -0.5430303 0.7489906 0.03921073 -0.9983743 0.04136961 0.4941896 -0.8680409 0.04776644 0.1822902 -0.9682211 0.1712259 0.1885334 -0.9653069 0.1806596 0.1595222 -0.9659225 0.2038294 0.4346434 -0.7835198 0.4440519 0.3587341 -0.8577191 0.3682767 0.3067207 -0.8982014 0.3148914 0.5526867 -0.2583985 0.7923179 0.658902 -0.2580258 0.706591 0.7349124 9.33388e-4 0.6781614 0.7157721 -0.08447784 0.6932055 0.6583541 -0.3119876 0.6850064 0.4910831 -0.7054659 0.5110336 0.6471445 -0.4916148 0.5826826 0.5764265 -0.6018442 0.5527352 0.06452929 -0.966723 0.2475535 0.215503 -0.9331285 0.2878013 0.4116247 -0.7066898 0.5754604 0.3226596 -0.7719102 0.5477643 0.3530673 -0.7423279 0.5694671 0.4062436 -0.6512244 0.6409937 0.5294163 -0.1480362 0.8353465 0.3082343 -0.4808645 0.8208294 0.4695414 -0.2393273 0.8498548 -0.186866 -0.2371049 0.9533427 0.1158259 -0.6560586 0.7457691 -0.02602148 -0.9439371 0.3290985 0.2990828 -0.5412316 0.7858867 0.1496833 -0.7427107 0.6526682 0.1810106 -0.4707638 0.863491 -0.09106904 -0.9214352 0.3777082 -0.1053122 -0.8429704 0.5275513 -0.1514672 -0.6685488 0.7280799 -0.156929 -0.6755093 0.7204585 -0.1688741 -0.4787185 0.8615744 -0.1868833 -0.2371147 0.9533369 0.199569 -0.2322675 0.951958 0.1995658 -0.2322871 0.951954 -0.4344503 -0.4769071 0.7640763 -0.3342218 -0.8333705 0.4402152 -0.2059963 -0.9420463 0.2647914 -0.9984537 0.002649843 0.05552601 -0.9852952 -0.07664144 0.1527068 -0.9719622 -0.0141111 0.2347136 -0.9280681 -0.08135229 0.3634163 -0.9207684 -0.09323328 0.3788051 -0.8595318 -0.1218826 0.4963364 -0.9965257 -0.08291375 -0.007874786 -0.9803069 -0.1703352 0.09992223 -0.9459753 -0.3239883 -0.01274752 -0.9037282 -0.4159116 0.101455 -0.9020797 -0.4300199 0.03653877 -0.8265352 -0.5350704 0.1747545 -0.7837797 -0.620053 0.03498482 -0.6726139 -0.7204389 0.1689925 -0.7167698 -0.6912432 0.09178113 -0.5657185 -0.7884966 0.2413209 -0.5681504 -0.8176442 0.09307581 -0.365955 -0.9013739 0.2315213 -0.4632703 -0.8728499 0.1533421 -0.260036 -0.9258584 0.2741671 -0.1130563 -0.9906399 -0.07649147 -0.860084 -0.09805065 0.5006413 -0.7992345 -0.1527079 0.5812955 -0.7759814 -0.1614732 0.6097371 -0.7106279 -0.2055854 0.6728615 -0.6826338 -0.1850634 0.7069391 -0.5895482 -0.2195658 0.7773184 -0.5729871 -0.222523 0.7887771 -0.4578532 -0.253611 0.8520868 -0.4343566 -0.2377932 0.8687859 -0.9999994 -0.001141548 2.78699e-7 -0.9990953 -0.0373317 0.02037507 -0.9819251 -0.1315541 0.136076 -0.9809321 -0.164527 0.103457 -0.9404188 -0.2582737 0.22115 -0.9435332 -0.2615146 0.2033603 -0.8766779 -0.3552083 0.3244426 -0.8803758 -0.3812651 0.2820911 -0.7875441 -0.4675109 0.4015073 -0.8044165 -0.45927 0.3768091 -0.6829851 -0.5381515 0.4938868 -0.7025861 -0.558784 0.4406057 -0.5385253 -0.6272744 0.5625989 -0.5831318 -0.616774 0.5287222 -0.3849281 -0.6655327 0.6394503 -0.39268 -0.6696463 0.6303779 -0.6805992 0.05370289 0.7306851 -0.3584298 -0.8577662 0.3684633 -0.4344171 -0.783459 0.4443803 -0.5760959 -0.6016188 0.5533249 -0.4912052 -0.7054118 0.510991 -0.614813 -0.4602088 0.6404787 -0.6570413 -0.3158563 0.6844937 -0.1786069 -0.9656625 0.1886677 -0.09495455 -0.994628 0.04121559 -0.1474592 -0.9818437 0.1193274 -0.2197386 -0.9516496 0.2146577 -0.3065286 -0.8981996 0.3150838 -0.0160405 -0.9996613 0.02049553 -0.1053463 -0.9635838 0.2457811 -0.07348126 -0.9641101 0.2551321 -0.2095717 -0.9367398 0.2803542 -0.3141916 -0.8447383 0.4332446 -0.3884919 -0.7057426 0.5924537 -0.3473125 -0.747591 0.5661111 -0.4068951 -0.6489142 0.6429205 -0.3769111 -0.5545213 0.7419193 -0.7143151 -0.0874986 0.6943327 -0.6591205 -0.2579956 0.7063983 -0.5167484 -0.2575299 0.8164861 -0.5704509 -0.06361109 0.8188648 -0.3069214 -0.4824146 0.8204118 -0.4693107 -0.2413315 0.8494155 -0.09922719 -0.6634256 0.7416337 -0.1196775 -0.6731389 0.729768 -0.1812059 -0.7568417 0.627977 0.08042567 -0.9490139 0.3048023 0.1017338 -0.8449684 0.5250511 -0.09241861 -0.6633078 0.742618 0.1522583 -0.6684695 0.7279876 0.1425874 -0.6775842 0.7214906 0.1824063 -0.2389646 0.9537421 0.1824114 -0.2389491 0.953745 0.1647962 -0.4801625 0.8615604 -0.1787406 -0.5428107 0.8206146 -0.1847276 -0.4727283 0.8616285 -0.203787 -0.2345033 0.9505152 -0.2037834 -0.2345116 0.9505139 0.806131 -0.4529085 0.380824 0.1051623 -0.9911926 -0.08048737 0.9965257 -0.08291375 -0.007874786 0.9876167 -0.1425374 0.06554621 0.9434387 -0.3315262 -0.00373733 0.9218394 -0.3829816 0.05947631 0.8861794 -0.4578209 0.07131659 0.9999974 -0.002283096 1.68613e-4 0.9992839 -0.02524507 0.02818703 0.9990926 -0.03731691 0.0205276 0.983938 -0.1246265 0.1278061 0.9803932 -0.1663264 0.1056632 0.9451234 -0.2498767 0.2104836 0.9395937 -0.268525 0.2122689 0.9320359 -0.1024784 0.3475736 0.973175 -0.01040434 0.2298307 0.9811264 -0.09125488 0.1704804 0.9984558 0.002590894 0.0554918 0.8661031 -0.1167759 0.4860338 0.9203598 -0.09389263 0.3796343 0.9357584 -0.06802332 0.346019 0.2670179 -0.9249718 0.2704235 0.3567006 -0.9079635 0.2199255 0.4726035 -0.866162 0.1625095 0.4902173 -0.858529 0.1503831 0.6485576 -0.7431028 0.1648372 0.659906 -0.7355365 0.1533303 0.7307005 -0.674736 0.1039628 0.7866526 -0.4731236 0.3966506 0.7160832 -0.5198906 0.4657667 0.6756372 -0.5729468 0.4639467 0.5856112 -0.6115417 0.5320492 0.537029 -0.6319513 0.5587821 0.2024472 -0.9441614 0.2599509 0.3321846 -0.8356583 0.4374113 0.3995931 -0.6632674 0.6327732 0.3819561 -0.6737906 0.6325472 0.4341539 -0.4786025 0.7631842 0.8651372 -0.4889422 0.111683 0.753692 -0.6528826 0.07544958 0.8884183 -0.3416166 0.3066123 0.8725326 -0.3901342 0.2940789 0.8551025 -0.1030138 0.5081222 0.7775741 -0.1697741 0.6054381 0.7968421 -0.1457032 0.586356 0.6876257 -0.2196104 0.6920566 0.702435 -0.1768146 0.6894358 0.5731257 -0.2250193 0.7879678 0.5891956 -0.2175633 0.7781483 0.4379583 -0.2583193 0.8610829 0.4570129 -0.2389707 0.8567569 -0.4445822 -0.8957182 -0.00596112 -0.3649419 -0.9290349 0.06092274 -0.308187 -0.9437147 0.1200969 -0.6027565 -0.797923 0.001897335 -0.7372906 -0.6753001 0.01929813 -0.7521376 -0.6589351 0.009682893 -0.999999 -0.001492798 0 -0.9979829 -0.06348389 7.27699e-5 -0.9696961 -0.2441634 0.008589267 -0.9566442 -0.2912538 0.001773118 -0.864662 -0.5023542 -3.99604e-4 0.8645987 -0.5024629 -4.52255e-4 0.9999989 -0.0014894 0 0.9694403 -0.2453138 0.002600014 0.9620477 -0.2727011 0.009917914 0.9979812 -0.06351172 7.19776e-5 0.7352163 -0.6777417 0.01110446 0.6739105 -0.7366805 0.05609369 0.7515966 -0.659558 0.009269356 0.3019227 -0.945916 0.1186827 0.3622169 -0.9302583 0.05846726 0.4433562 -0.8963192 -0.006881117 -0.1948563 -0.9796115 -0.04891258 -0.2067431 -0.9769737 -0.05272227 -0.5552247 -0.8309549 -0.03521001 -0.5935285 -0.8033515 -0.04847991 -0.8313418 -0.5555101 -0.01672136 -0.8573514 -0.5139036 -0.02918761 -0.9807789 -0.1950867 -0.003755629 -0.9840229 -0.1778259 -0.008774816 -0.05093395 -0.9987021 -4.42662e-6 -0.8314648 -0.5555775 -6.45456e-5 -0.8036962 -0.5949302 -0.01142412 -0.911832 -0.4105616 0.001255869 -0.9807765 -0.1950891 -0.004223048 -0.9986326 -0.05227977 0 -0.1950772 -0.9807376 -0.009934663 -0.2266619 -0.9739667 -0.003652989 -0.5555714 -0.831451 0.005440413 -0.4611036 -0.8869978 -0.02487295 -0.6363242 -0.7714219 2.91394e-5 0.9861154 -0.1658626 -0.008131206 0.9657961 -0.2587653 0.01668852 0.2585147 -0.964798 -0.04832112 0.2170755 -0.9756774 -0.03052866 0.4645553 -0.8845155 -0.04266983 0.6083254 -0.7927653 -0.03825592 0.65223 -0.7564091 -0.04941248 0.793178 -0.6086174 -0.02129751 0.8264831 -0.5623311 -0.02663826 0.9092144 -0.4158622 -0.01969897 0.9999812 -0.006136775 0 0.9959626 -0.08976805 -5.41961e-4 0.9658016 -0.2587823 -0.01609438 0.2426589 -0.9701118 -2.53021e-5 0.2588194 -0.9659121 -0.005148172 0.6087504 -0.7933557 0.00312227 0.9682224 -0.2494467 -0.01793354 0.8959832 -0.4440824 0.002253651 0.7933341 -0.60878 -0.002837061 0.7796991 -0.6261545 -3.03395e-5 0.5955353 -0.8033292 4.01509e-5 -0.1861719 0.6947482 -0.694741 -0.5085771 0.6947559 -0.5085899 -0.5085921 0.6947456 -0.5085889 -0.6947402 0.6947531 -0.1861564 -0.6947398 0.6947543 -0.1861536 -0.694746 0.694746 0.1861614 -0.6947503 0.694743 0.1861564 -0.5085866 0.6947514 0.5085866 -0.5086131 0.6947257 0.5085951 -0.1861695 0.6947305 0.6947594 -0.1861431 0.6947556 0.6947412 0.1861529 0.6947487 0.6947455 0.1861622 0.694737 0.6947548 0.5086143 0.6947202 0.5086014 0.5085865 0.6947524 0.5085852 0.6947517 0.6947389 0.1861664 0.694733 0.6947619 0.1861501 0.694765 0.6947265 -0.186163 0.6947222 0.6947727 -0.1861507 0.5086056 0.694734 -0.5085911 0.5085648 0.6947621 -0.5085939 0.1861399 0.6947723 -0.6947255 -0.9831954 2.08613e-4 0.182556 -0.01276069 -0.05588358 0.9983558 -0.3612955 0 0.9324515 -0.4684805 -0.07030028 0.8806725 -0.8219965 0 0.5694927 -0.3965941 0 0.9179941 0.9841384 0 0.1774024 0.9841452 0 0.1773652 0.8272943 0 0.5617688 0.8272435 0 0.5618435 0.5744295 0 0.8185541 0.474082 -0.07110226 0.8776052 -0.39661 0 0.9179872 0.01656574 0 0.9998628 0.01624411 0 0.9998682 0.3636857 0 0.9315217 0.8945063 0.2673662 0.3582932 0.333779 -7.91833e-5 0.9426513 0.4696292 0.1540036 0.8693282 0.9915132 0.07491135 0.1062548 0.9761883 -0.1268779 0.1759504 0.630244 0.1967318 0.7510588 0.9617996 0.05450594 0.2682735 0.9774463 0.0635659 0.2013905 0.9409868 0.263426 0.2124869 0.9491832 0.1907865 0.2503032 0.9783179 0.1150782 0.1721947 -0.3939569 -0.1115245 0.9123378 -0.3360143 0.03408998 0.9412398 -0.3328044 0.2046284 0.9205263 -0.4396581 0.152944 0.8850474 -0.4401664 0.3097075 0.8428137 -0.4320849 0.3081368 0.8475579 -0.2057344 0.3470742 0.9149934 -0.2056623 0.1597204 0.9655011 0.04867041 0.1699581 0.9842486 0.01633828 0.09456443 0.9953848 0.799186 0.1309366 0.5866494 0.796568 0.1608713 0.5827519 0.8270999 0.1415554 0.5439373 0.826433 0.3424938 0.4468855 0.8462937 0.3217229 0.4245957 -0.06021088 0.6676528 0.742034 0.2114763 0.6638794 0.7173158 0.1576848 0.6520295 0.7416151 0.4452781 0.6105924 0.654908 0.1178794 0.5935392 0.7961255 0.5678648 0.4944999 0.6580269 0.6290341 0.4718726 0.6177803 0.6827673 0.4379763 0.5848126 0.7836688 0.3729372 0.4967707 -0.2884802 0.6383462 0.7136479 -0.1145076 0.6745564 0.7292886 -0.1147209 0.5111557 0.8517975 0.1576468 0.5260683 0.8357032 0.09996217 0.5075545 0.8558014 0.3803691 0.489902 0.7844204 0.8253986 0.06645041 0.5606261 0.5956143 8.61025e-4 0.8032702 0.5889039 0.2142482 0.7792881 0.3293865 0.2382547 0.9136407 0.3776975 0.2470448 0.892364 -0.1303765 0.2438049 0.9610209 0.1001691 0.3551995 0.9294082 -0.1721118 0.3378226 0.9253396 -0.1718359 0.5202512 0.8365472 -0.3853777 0.4732067 0.7921866 -0.007063925 0.6220702 0.7829297 -0.727249 0 0.6863738 -0.5327605 -7.33948e-4 0.8462659 -0.0994749 -0.007205545 0.9950141 -0.7250955 0.009994149 0.6885758 -0.6191571 0.003899812 0.7852575 -0.3114914 -0.001722991 0.9502475 -0.2170279 -0.003441154 0.9761594 0.3369963 1.30923e-5 0.941506 -0.3040814 4.81504e-4 0.952646 -0.09530752 2.22818e-5 0.9954479 0.03589642 -1.98653e-4 0.9993556 0.1141268 -0.001635015 0.9934648 0.1804967 -7.01918e-4 0.9835754 0.2662139 -2.9973e-5 0.963914 0.6356933 1.04866e-4 0.7719418 0.5656992 -4.72022e-4 0.8246116 0.4679233 -0.001681268 0.8837676 0.3769232 -1.35812e-4 0.9262446 0.4758428 -7.69206e-4 0.8795301 0.6406952 0.003190577 0.7677887 0.8519833 -0.001663982 0.5235664 0.8931234 3.58848e-4 0.4498116 0.7890656 -5.86782e-5 0.6143091 0.7410674 -3.56949e-4 0.6714307 0.7546874 -6.22498e-4 0.6560843 0.7042761 -1.09851e-4 0.7099263 0.9334043 1.79022e-4 0.3588262 0.9876413 -3.56596e-4 0.156731 0.9902943 -9.67205e-7 0.1389868 -0.6406509 4.41856e-4 0.7678322 -0.7410714 -4.73311e-4 0.6714262 -0.9814407 -7.36798e-4 0.1917643 -0.9993049 -2.10296e-5 0.03728044 -0.1646571 -8.08885e-4 0.9863506 -0.4760037 -4.62644e-4 0.8794432 -0.6407809 0.003614187 0.7677153 -0.4579253 -0.001830339 0.8889888 -0.5460294 -7.27004e-4 0.8377658 -0.115572 -1.82613e-4 0.9932991 0.09540528 8.04348e-6 0.9954385 0.2196307 1.82337e-4 0.9755831 0.7369393 1.63561e-5 0.675959 0.5628647 1.5646e-4 0.8265491 0.6247487 0.003169655 0.7808195 0.3128899 -0.001836359 0.9497877 0.244538 0.6394561 0.7289013 0.1797049 0.638487 0.7483586 0.4508994 0.4527155 0.7692453 0.4099462 0.4345024 0.8019676 0.4087278 0.3131739 0.857242 0.5108425 0.3278803 0.7946915 -0.3774988 0.2470275 0.8924528 -0.5951015 0.4847137 0.6410201 -0.3806625 0.4897261 0.784388 -0.9671528 0.08332204 0.240152 -0.9645804 -0.07977926 0.2514358 -0.7998088 0.120603 0.5880144 -0.8198221 0.07231378 0.568034 -0.5955886 -0.002265632 0.8032865 -0.46401 0.1527372 0.8725631 0.2066769 0.2589122 0.9435302 0.2059955 0.3336543 0.9199135 0.1721075 0.5029973 0.8469786 0.1146531 0.5281796 0.8413566 0.1150344 0.6462935 0.7543686 0.3349962 0.1500888 0.9301886 -0.04919975 0.1699588 0.9842223 0.3260186 0.3157258 0.8910831 -0.09841477 0.2536024 0.9622892 -0.09962505 0.5261227 0.8445531 -0.1574127 0.5073243 0.8472563 -0.9498131 0.08638113 0.3006552 -0.8270484 0.1415159 0.5440261 -0.7966088 0.1608102 0.582713 -0.6300454 0.1967144 0.7512299 -0.5888903 0.2141817 0.7793167 -0.3338344 0.001499593 0.9426306 -0.0126717 0.08983308 0.9958763 -0.4981353 0.400325 0.7691562 -0.2889122 0.7379822 0.609846 0.2119307 0.7038069 0.6780422 0.4498077 0.6114771 0.6509754 0.7859535 0.3939058 0.4765661 0.5733982 0.5587747 0.5991539 -0.1292893 0.9390491 0.3185452 0.6232011 0.04698657 0.780649 0.7023618 0.2478342 0.6672827 0.6313456 0.175486 0.7553856 0.6626964 0.3781554 0.6463993 0.6930857 0.1876118 0.6960131 0.6752058 0.09853523 0.7310185 -0.2239187 0.08406138 0.9709759 -0.3916686 0.06077682 0.918097 -0.3174475 0.2556071 0.913177 -0.5092376 -0.3255876 0.7966617 -0.5093075 -0.283412 0.8125783 -0.6935314 0.2011581 0.6917729 -0.7051948 0.2004085 0.6801006 0.4688296 -0.004601657 0.8832767 0.3833967 0.1578946 0.909987 0.3203685 0.1226637 0.9393177 0.2373782 0.1331406 0.9622501 0.2365339 0.1311366 0.962733 0.09846699 0.07355988 0.9924179 0.1369189 0.2119185 0.9676486 0.03033328 0.0345717 0.9989418 0.9511024 0.2064335 0.2297592 0.9730697 0.06967484 0.2197291 0.8935738 0.2595519 0.3662768 0.8459863 0.316749 0.4289256 0.8373284 0.3238222 0.4404775 0.8098843 0.2308091 0.5392723 0.705921 0.2573322 0.6598907 0.6865321 0.4767058 0.5490222 0.6692038 0.4833139 0.5644236 0.6479077 0.4122892 0.6404945 0.433937 0.5595515 0.7061167 0.3967008 0.5558054 0.7305539 0.3407334 0.4428191 0.8293442 0.9212555 0.06263285 0.3838822 0.894585 0.09400445 0.4368991 0.8537928 -0.01014882 0.5205141 0.6982819 0.24409 0.672921 0.6997408 0.2442753 0.6713363 0.4168913 0.5100017 0.7523961 0.3803091 0.463053 0.8005916 0.2764282 0.4712479 0.8375637 0.4855992 0.203353 0.8502006 -0.06346768 0.3110375 0.9482761 -0.1099463 0.08793783 0.9900398 -0.07726186 0.1226986 0.989432 -0.1298078 0.3919285 0.9107919 0.02425271 0.308616 0.9508776 0.1718927 0.3682212 0.9137101 0.1057501 0.4168078 0.9028224 0.2457743 0.3762161 0.8933401 0.3816759 0.1450136 0.9128497 0.4854679 0.2185056 0.8465083 0.5724837 0.07228142 0.8167238 0.5299401 0.1204225 0.8394414 -0.06044024 0.72846 0.6824171 -0.123279 0.70157 0.701856 -0.1465595 0.7476671 0.6476992 -0.1378147 0.75506 0.6410082 -0.1266552 0.7665183 0.6296096 -0.1570641 0.7609888 0.6294656 -0.1433043 0.7743102 0.6163665 -0.1942153 0.7704402 0.6072087 -0.1962592 0.7696238 0.6075866 -0.245889 0.7818045 0.5729926 -0.2814339 0.7702822 0.5722416 -0.3200218 0.7888067 0.5247572 -0.2315048 0.06030648 0.9709627 -0.2509532 0.271569 0.9291248 -0.3822022 0.393382 0.8361651 -0.3311011 0.2727478 0.9033165 -0.5824496 0.2583777 0.7707099 0.4455893 0.6150609 0.6505 0.2065598 0.7078517 0.6754844 0.1911677 0.657477 0.7288203 0.2003902 0.6568284 0.7269252 0.1588035 0.6034965 0.7813921 0.1395279 0.6088381 0.7809278 0.05707335 0.5500134 0.8332035 0.02443659 0.5686904 0.8221886 -0.1145872 0.5105288 0.8521915 -0.1395319 0.5366445 0.832192 -0.322598 0.4952588 0.8066283 -0.3300127 0.5125234 0.792724 -0.517975 0.4929421 0.699078 -0.3940205 0.762915 0.5125512 -0.3211849 0.7955374 0.5137709 -0.4552881 0.6385397 0.6204675 0.5352198 0.3869842 0.7508549 0.2562105 0.7397034 0.6222501 0.2514431 0.8257337 0.5049161 0.2136316 0.8182241 0.5337329 0.2765983 0.7897949 0.5474646 0.2079738 0.7915796 0.5745856 0.2833821 0.7578688 0.5876473 0.5608271 0.08191037 0.8238713 0.6034469 -0.1570077 0.7817931 0.2245301 0.05701136 0.9727981 0.01565313 0.1877502 0.9820922 -0.7826523 0.2054413 0.5875791 -0.838752 0.1730508 0.5162835 -0.9699809 0.2045364 0.1315371 -0.6939462 0.4728647 0.5429897 -0.8273232 0.3534328 0.4366024 -0.8693733 0.2732138 0.4117578 -0.9607942 0.1579642 0.227864 -0.9760277 0.04614311 0.2126988 -0.5982891 0.5322481 0.5989676 -0.6434532 0.4885876 0.5892794 -0.6142056 0.3954018 0.6829414 -0.6190201 0.3866805 0.6835878 0.4972069 0.5723592 0.6520663 0.4050555 0.6817998 0.6091627 0.2987961 0.6866667 0.662729 0.3167062 0.6683408 0.673066 0.1918815 0.6661671 0.7206962 0.08619886 0.6798762 0.7282432 0.0289123 0.7210379 0.6922922 0.009010612 0.7225507 0.6912592 0.5821214 0.2611377 0.7700272 0.5349664 0.3817077 0.753731 0.3200089 0.3930851 0.86202 0.3331826 0.3710368 0.8667879 -0.3154442 0.6038167 0.7320522 -0.3265429 0.6409007 0.6947059 -0.4834205 0.09138911 0.8706048 -0.6854113 0.1968554 0.7010417 -0.1097085 -0.9829245 0.1477276 -0.5651669 0.4959094 0.6592878 -0.5537037 0.129623 0.8225631 -0.2815157 0.9147555 0.2897782 -0.4638164 0.2759752 0.8418504 -0.5091908 -0.09959685 0.8548715 -0.4595268 0.3984393 0.7937766 -0.506139 0.1358082 0.8516922 -0.4035204 0.6427426 0.6511937 -0.5170108 0.3586108 0.7772376 -0.4605564 0.5436826 0.7016388 -0.2722836 0.8778804 0.3939386 -0.409344 0.7014508 0.5834418 -0.1761506 0.9599232 0.2179871 -0.3413122 0.8269429 0.4468462 0.1154045 0.9631293 -0.2430307 -0.04425936 0.998922 -0.01400065 -0.5022425 0.6481977 0.5723568 -0.5633982 0.5290462 0.6345807 -0.5733423 0.5045051 0.6455643 -0.6282787 0.3445259 0.6975441 -0.6635923 0.1438702 0.7341299 -0.3846547 0.8080193 0.4462572 -0.4548965 0.714556 0.5314877 -0.4555084 0.6889572 0.563782 -0.5679019 -0.008168637 0.8230558 -0.5496977 -0.2405823 0.7999705 -0.5558673 0.3534376 0.7523919 -0.5861221 0.1523087 0.7957783 -0.5191404 0.536447 0.6653705 -0.5733402 0.3505234 0.7405501 -0.4607646 0.6953206 0.5515664 -0.5370295 0.5318604 0.6547701 -0.3855698 0.8218453 0.4194121 -0.4806034 0.686865 0.5451943 -0.2996282 0.912523 0.2784326 -0.4040737 0.8158927 0.4135741 -0.357896 0.2188094 0.9077627 -0.371485 0.0909065 0.9239779 -0.3535826 0.2750445 0.8940525 -0.3365886 0.3973318 0.8537187 -0.3095287 0.5365261 0.785068 -0.2776203 0.642108 0.7145798 -0.2495229 0.7329344 0.6328867 -0.1238135 0.9334173 0.3367528 -0.1778385 0.838442 0.5151588 -0.1077539 0.9558725 0.2733074 -0.2252025 0.8796226 0.4189844 -0.1192922 0.9615018 0.2475554 -0.1677504 0.01499217 0.9857155 -0.1644631 0.04267764 0.9854596 -0.2093252 0.03834241 0.9770941 -0.2184902 0.2194673 0.9508397 0.04798543 0.05212694 0.997487 -0.04457837 0.02814483 0.9986094 -0.126643 0.02716451 0.9915764 0.8954578 0.05549269 0.4416742 0.9797635 0.1840047 0.07877796 0.4262991 0.8161419 0.3901047 0.3808859 0.6813988 0.6249973 0.5663837 0.7137331 0.4120615 0.6695744 0.6036165 0.4328017 0.8476622 0.5272233 0.05919945 0.7813435 0.4542727 0.4279472 0.8658307 0.2339652 0.4422643 0.02603894 0.9259557 0.3767334 0.04654961 0.9366884 0.3470565 -0.03827947 0.8331725 0.5516867 -0.07657909 0.729758 0.6794034 -0.06238186 0.8008154 0.5956535 0.2111207 0.7194648 0.6616634 -0.2734549 -0.1109808 0.955461 -0.2291257 0.1978735 0.9530727 -0.1325858 0.1703204 0.9764283 -0.09951382 0.2626881 0.9597354 -0.03762507 0.2162089 0.9756219 -0.04666006 0.1823421 0.9821274 0.01840221 0.1120809 0.9935287 0.09129798 0.1762244 0.980107 0.1392048 0.05375301 0.9888038 0.2896562 0.08527123 0.9533248 -0.1553276 0.5365605 0.8294434 -0.1549971 0.5474612 0.8223516 0.04785561 0.4886927 0.8711426 0.07281029 0.5506536 0.8315524 0.2258183 0.4387564 0.8697695 0.2339218 0.4620295 0.8554585 0.3587108 0.3238322 0.8754767 0.3832575 0.3459011 0.8564265 0.4734417 0.1162826 0.873116 0.5141282 0.1340401 0.847175 0.2517709 0.8812975 0.399908 0.2474053 0.8799034 0.4056609 0.3255106 0.9233313 0.2037209 0.300844 0.7219445 0.6231285 0.4350801 0.6208347 0.652127 0.4403308 0.638763 0.6309444 0.6028731 0.4521477 0.6573482 0.6210286 0.4686672 0.6282313 0.7442402 0.1544703 0.6498042 0.7724782 0.1666451 0.6127862 0.04821127 -7.60241e-4 0.9988369 0.04839247 0 0.9988285 0.2891911 0 0.9572714 0.4907755 0.06800222 0.8686283 0.5186412 0 0.8549921 0.8305861 0 0.5568902 0.7724699 0.166889 0.6127302 0.8969065 9.55534e-4 0.4422194 -0.8179557 0.001025855 0.5752803 -0.04641085 -7.53497e-4 0.9989222 -0.04695105 0 0.9988972 -0.3881574 0 0.9215931 -0.4780117 0.1454379 0.8662291 -0.6008048 0 0.7993958 -0.8176497 0 0.575716 -0.1907948 0.8430332 0.5028842 -0.4661279 0.6495197 0.6007072 0.01188111 0.8973147 0.4412315 -0.04947191 0.1048886 0.9932528 0.04447919 0.01427918 0.9989083 -0.04646134 0.04937207 0.9976993 0.2542189 0.09265512 0.9626983 0.1379572 0.388113 0.9112278 0.1930022 0.0886293 0.9771873 0.01989704 0.2141039 0.9766083 0.04249274 0.1802836 0.9826964 0.07637852 0.07365107 0.994355 -0.4688178 0.6554532 0.5921072 -0.7627668 0.5166909 0.3888666 -0.6945432 0.4403106 0.5689784 -0.8642022 0.1967056 0.4631 -0.8079369 0.1535267 0.5689178 -0.2243881 0.8520939 0.4728488 -0.05802053 0.6537492 0.7544837 -0.2527779 0.7550457 0.6049869 -0.5948699 0.1369165 0.7920757 -0.6325856 0.1362956 0.7624034 -0.5252886 0.4123963 0.7443127 -0.4953457 0.4065138 0.7677104 -0.3603765 0.5593318 0.7465098 -0.3361117 0.554481 0.7613013 -0.2235609 0.638621 0.7363312 -0.4034766 0.7954629 0.4521565 -0.3337455 0.7997211 0.4990593 0.2011877 0.09542417 0.9748937 -0.1637079 0.8152987 0.5554167 -0.1690093 0.9606018 0.2206357 -0.003735542 0.8913276 0.4533448 0.1278765 0.6198025 0.7742689 0.06257683 0.6873723 0.7236046 0.2401371 0.3006912 0.9229947 0.1721816 0.4152945 0.8932436 0.03941327 0.377299 0.9252525 -0.01428496 0.4309801 0.9022484 -0.1196491 0.3529505 0.9279602 -0.1460427 0.3619056 0.920704 -0.2362024 0.2632175 0.9353743 -0.2709997 0.2735497 0.9228921 -0.3406237 0.09581404 0.9353049 -0.3866548 0.09337013 0.9174858 0.3652706 0.09091454 0.9264513 0.127952 0.9027647 0.4106631 0.3652573 0.09217846 0.9263316 0.3499105 0.2995023 0.8876153 0.3500941 0.2982594 0.8879615 0.2876249 0.6205515 0.729512 0.2876121 0.6205897 0.7294846 0.1188954 0.9460042 0.3015624 0.1950885 0.8698746 0.4530548 0.1194961 0.9513392 0.2840327 -0.3118546 0.8018075 0.5097563 -0.1818748 0.1747249 0.9676739 -0.969964 0.1737865 0.1702 -0.5140618 0.1720622 0.8403185 -0.4230697 -0.1102823 0.8993609 -0.6070693 0.1753634 0.7750578 -0.8281818 0.1720758 0.53339 -0.7941367 -0.0348491 0.6067394 -0.8957825 0.1758024 0.4082492 0.03842395 0.1757264 0.983689 0.2816008 0.2216247 0.9335864 0.1571719 0.1762557 0.9717155 0.143908 0.3864414 0.9110179 -0.09921658 0.03753912 0.9943576 -0.07869529 0.6097201 0.7887006 0.1440431 0.3864548 0.9109909 -0.3118585 0.8018049 0.5097579 -0.5024139 0.801795 0.3235818 -0.5023915 0.8018105 0.3235782 -0.5846831 0.8047486 0.1025937 -0.584693 0.8047415 0.1025928 -0.8381056 0.5253116 0.1470613 -0.7173887 0.5214065 0.4620485 -0.7174013 0.5213897 0.462048 -0.4453061 0.5213893 0.727912 -0.4453045 0.5213971 0.7279074 -0.1655768 0.5279608 0.8329716 -0.1260919 0.8073611 0.5764278 -0.1619396 0.8499003 0.5014432 0 1 1.90263e-7 0 1 0 0 1 1.10073e-6 0 1 -7.47518e-6 0 1 6.21044e-7 -0.1411321 0.4052367 0.9032525 0.1800485 -0.038796 0.9828923 -0.04285138 0.1757894 0.9834947 -0.2843854 0.1739631 0.9427947 0.6099265 -0.1180652 0.7836136 0.51406 0.1720675 0.8403185 0.7815057 0.1746417 0.5989568 0.840027 0.04053914 0.541028 0.8951608 0.1757667 0.4096257 0.9699598 0.1738104 0.1701998 0.9699662 0.1737822 0.1701922 0.5846931 0.8047417 0.1025913 0.134957 0.7633937 0.6316777 0.5846806 0.8047505 0.1025933 0.5023968 0.8018067 0.3235791 0.5024057 0.8017999 0.3235824 0.3118439 0.8018133 0.5097538 0.311864 0.8018061 0.5097528 0.1227655 0.8071729 0.5774086 0.1604857 0.8527988 0.4969694 -0.1443903 0.3865019 0.910916 0.09095919 0.4009901 0.9115555 0.09780627 0.1720542 0.98022 0.4163582 0.1752808 0.892145 0.04929083 0.636065 0.7700597 0.1771403 0.5286049 0.8301796 0.4453099 0.5213919 0.7279077 0.4453002 0.5213891 0.7279157 0.7173849 0.5214098 0.4620506 0.838109 0.525306 0.1470612 0.8381003 0.5253202 0.1470596 0.8147984 2.46656e-4 0.5797445 0.7491998 -0.03141796 0.6615986 0.7936916 -0.005574166 0.6082949 0.6337307 0.004451453 0.773541 0.6142274 -0.004575073 0.7891158 0.5312501 8.00908e-5 0.8472151 0.422913 -7.38821e-4 0.9061701 0.428909 -0.003470897 0.9033411 0.1801902 0.004680991 0.9836207 -0.04354262 0 0.9990516 -0.2093375 0.05440855 0.9763286 -0.2887626 -3.17587e-6 0.9574007 0.9999985 0 0.00173068 0.9986432 -1.08771e-4 0.0520755 0.9738514 -0.01302951 0.2268122 0.9336922 -0.06147933 0.3527593 0.8832191 -4.75763e-5 0.4689608 0.9093097 -0.002721786 0.4161112 0.9845365 0.02908694 0.1727477 0.259906 0.9643544 -0.04969358 0.9843258 0.1763601 0 0.9909647 0.1337929 -0.009412586 0.9911561 0.1326829 -0.002222597 0.8473207 0.5310724 0.003122925 0.8744708 0.485078 -6.18073e-4 0.3696029 0.929166 -0.006664752 0.5634092 0.8253946 0.03597247 0.5948925 0.8038053 0 0.5877897 0.8090137 4.61788e-4 -0.5387836 -0.3122658 -0.7824337 -0.4472056 0 -0.8944313 -0.2012088 0 -0.9795485 -0.2012327 0 -0.9795435 0.5388619 -0.311929 -0.782514 -0.9747191 0.2232387 -0.009349465 -0.6501173 0.7557424 -0.07874614 -0.4858294 0.8738607 0.01836699 -0.2468545 0.9685376 -0.03158795 -0.5782477 0.8158611 -6.2113e-4 -0.8473155 0.5310895 7.64197e-4 -0.8142604 0.5804927 -0.002872526 -0.9843195 0.17637 0.002956688 -0.9749602 0.2223801 0 -0.9852741 -0.02014076 -0.1697917 -0.9656592 0.08454144 -0.2456728 -0.9943872 -0.001705825 -0.1057887 -0.9185786 0.001867711 0.3952341 -0.9832211 -0.005607306 0.1823318 -0.9663619 -0.03219962 0.2551622 -0.9772713 -0.02180528 0.2108687 -0.9823241 -0.01647478 0.1864619 -0.9886074 -0.01007568 0.1501802 -0.9953981 -0.003296494 0.0957697 -0.9992591 -3.58993e-4 0.03848791 -0.9999691 0 0.007866382 -0.8524707 -3.69483e-6 0.5227752 -0.798343 -0.04860532 0.6002384 -0.8622758 -0.01414644 0.5062415 -0.1731964 -0.9848874 0 -0.2588177 -0.9659167 0.004297316 -0.9848755 -0.1732525 -0.002019345 -0.9466494 -0.3222544 0.00266838 -0.8447154 -0.5352157 0 -0.7933387 -0.6087797 -0.001043498 -0.6774622 -0.7355502 0.003316104 -0.6087392 -0.7933704 0 -0.4222022 -0.9065017 0 0.9827637 -0.02341663 -0.1833773 0.9843463 -0.001651942 -0.1762375 0.9999536 -0.001688361 -0.009494364 0.9980325 0.05006486 0.03774476 0.5578172 0.8171606 -0.1452187 0.7260495 0.6789593 0.1089336 0.8669264 0.4808967 -0.1310611 0.976573 0.202922 -0.07160931 0.9885326 0.1333493 0.07086217 0.9266679 0.3757155 0.01115453 0.861448 0.4861288 -0.1469228 0.8591402 0.5058315 0.07754188 0.7310711 0.6801403 0.05426132 0.7189521 0.6824494 0.1317983 0.5055094 0.8627888 0.007480919 0.5141265 0.8577004 -0.004921376 0.3646628 0.9273934 -0.08344161 0.4424232 0.8962026 -0.03290432 3.22117e-6 1 1.23433e-5 9.53192e-6 1 2.8122e-5 5.29459e-5 1 -5.0785e-5 9.54796e-5 1 -4.76713e-5 3.36611e-7 1 0 -8.09224e-5 1 -4.09733e-5 -2.6646e-6 1 1.35472e-5 2.66457e-6 1 1.3547e-5 -0.4963005 0.8518741 -0.1673215 -0.4069665 0.9086785 -0.09317708 -0.5096269 0.8603895 -0.003247201 -0.9974327 0.06084531 0.03776073 -0.8126087 0.5792829 -0.06402039 -0.7265772 0.6792026 0.1037768 -0.6520724 0.7580504 0.01270037 -0.4850743 0.8725633 0.05776125 -0.9696391 0.2220509 -0.1024373 -0.9695739 0.2277712 -0.08970385 -0.8901625 0.4454855 0.09567356 -0.8919483 0.4463412 0.0721656 -0.7306906 0.6794104 0.06702905 -0.6775134 0.6727304 0.2973372 -0.4561242 0.8815185 -0.1219675 0.9848794 -0.1732414 0 0.98488 -0.1732383 -8.53579e-7 0.9333372 -0.3590011 0 0.8334347 -0.552617 -0.001146316 0.8435809 -0.5370022 -2.39706e-6 0.5369582 -0.8436089 2.17967e-6 0.5368652 -0.8436681 -3.76053e-6 0.1732434 -0.9848791 2.72812e-6 0.173189 -0.9848886 0 0.7823092 2.75865e-6 0.6228903 0.8523079 -0.01945817 0.5226785 0.8605102 -0.01444542 0.5092285 0.9997068 -9.50485e-5 0.02421385 0.9960179 -0.00229752 0.08912414 0.989525 -0.009361803 0.1440578 0.9851648 -0.0135861 0.1710727 0.9831131 -0.01581054 0.1823151 0.9646895 -0.002933979 0.2633738 0.9191473 0.001927018 0.3939093 0.963871 -0.2510707 -0.08897477 0.9852727 -0.01462048 0.1703642 0.9883248 -0.00212264 0.1523473 0.9859198 -0.06775754 -0.1528767 0.9998963 -0.004769861 0.01359462 0.998606 -0.03670126 0.03793495 0.9974787 -0.02395713 0.06680154 0.9916255 -0.0812354 0.1003986 0.9717235 -0.03769141 0.2330941 0.9676781 0.03666836 0.2495087 0.9732306 -0.1626302 0.1623997 0.9772267 -0.1306312 0.1672225 0.9537626 -0.2932789 0.06576097 0.9311135 -0.3596091 0.06090205 0.8988131 -0.4357173 -0.04780662 0.9997564 0.003181636 0.02184116 0.9819607 -0.1117175 -0.1525536 0.9741597 -0.2127135 -0.07593387 0.9567309 -0.2192171 -0.1913374 0.9634585 -0.23493 -0.1286684 0.7056628 -0.1766522 0.6861736 -0.1082624 -0.9846459 0.1369368 -0.1203267 -0.9798586 0.1593695 -0.03647714 -0.9878944 0.1507791 0.03296399 -0.9880761 0.1503961 0.126477 -0.978987 0.1599627 0.1061417 -0.9843851 0.1404279 0.5645986 0.1224877 0.8162263 0.6107684 -0.1736282 0.7725381 0.343872 -0.1756471 0.9224424 0.2320846 0.1615055 0.9591938 -0.1265566 -0.1754645 0.9763174 -0.3525308 -0.1758355 0.9191321 -0.5676795 -0.1752293 0.8043847 -0.6201748 0.006606638 0.7844359 -0.7122827 -0.1772207 0.6791512 -0.3357273 -0.8408094 0.4246491 -0.3357089 -0.8408223 0.424638 -0.1281481 -0.8384785 0.5296526 0.1281421 -0.8384645 0.5296763 0.1281648 -0.8384768 0.5296515 0.3357023 -0.8408329 0.4246225 0.3357374 -0.8408007 0.4246583 -0.5240668 -0.5347695 0.6628542 -0.5240865 -0.5347274 0.6628725 -0.1992422 -0.531161 0.8235112 0.1992781 -0.5311076 0.8235369 0.1992364 -0.5311785 0.8235012 0.5240574 -0.5347805 0.6628527 -0.9859917 -0.04077869 0.1617332 -0.9821886 -0.07491165 0.1723187 -0.9444544 -0.2359319 0.2287839 -0.9700314 -0.05529451 0.2366041 -0.9999973 -0.001856267 0.00146228 -0.9998679 -0.01418495 0.007944583 -0.9998115 -0.01174724 0.01545989 -0.9983531 -0.0400753 0.04105055 -0.9831299 -0.1112555 0.1451828 -0.9229968 -0.384727 0.007883191 -0.9513926 -0.3079687 -0.002741456 -0.9859713 -0.04950046 -0.1594061 -0.9843612 -0.08946084 -0.1517557 -0.9842864 -0.09519058 -0.1487249 -0.9795542 -0.1435347 -0.1409661 -0.9789179 -0.1601176 -0.1268159 -0.9686996 -0.2300516 -0.09325987 -0.9687833 -0.2176329 -0.118723 -0.9680047 -0.2302501 -0.09975957 -0.5900718 -3.29046e-6 0.8073509 -0.6311447 0.004328012 0.7756531 -0.4054639 -0.001253426 0.9141103 -0.2485669 0.002755522 0.9686108 -0.1128264 -0.00500822 0.9936022 0.3136476 -2.49873e-4 0.9495394 0.1048998 -0.003410458 0.994477 0.1370012 7.77851e-6 0.9905709 -0.1941441 -1.03321e-5 0.980973 0.9117716 -0.02177387 0.4101201 0.7799738 5.21233e-4 0.6258119 0.7059077 -8.40767e-5 0.7083039 0.5492377 -0.002604007 0.8356621 0.5994275 -0.01274394 0.8003277 0.4297906 9.51851e-4 0.9029281 0.8550257 0.01243948 0.5184366 0.9931575 0 0.1167824 -0.8198702 -0.2993443 0.4880635 -0.8236775 -0.4304115 0.3691901 -0.3968228 -0.8996382 0.1821613 -0.5721104 -0.7940836 0.2052341 -0.8206439 -0.5644979 0.08880323 -0.9567896 -0.2888331 -0.03360438 -0.9837949 6.919e-4 -0.1792966 -0.6073392 -0.7491554 0.2643962 -0.2625789 -0.9645085 -0.02785265 -0.3853974 -0.9210479 0.05603182 -0.9811469 -0.06516242 0.1819472 -0.9811476 -0.06513494 0.1819532 -0.8506535 -0.06516462 0.5216726 -0.8497323 -0.07121312 0.5223827 -0.9324018 -0.3173791 0.1729093 -0.9139563 -0.3569367 0.1930808 -0.8184112 -0.3579745 0.4495082 -0.834581 -0.5286967 0.1547722 -0.6721893 -0.7298104 0.1246528 -0.652336 -0.7453004 0.1377871 -0.4089348 -0.9099137 0.06949388 -0.3983364 -0.9119807 0.0980786 -0.8683077 -0.4820815 0.1167874 -0.8673187 -0.4685147 0.1680848 -0.9208936 -0.304754 0.2430635 -0.9230129 -0.2628692 0.2809755 -0.9430491 -0.09778773 0.317956 -0.9408644 -0.1094347 0.3206218 -0.8881927 -0.156501 0.4319969 -0.8580859 -0.3581978 0.3679441 -0.8966034 -0.1631778 0.4116739 -0.7898406 -0.2274538 0.5695759 -0.8217942 -0.1746635 0.5423533 -0.8041944 -0.5400518 0.2482246 -0.8221131 -0.5169278 0.2385702 -0.7658858 -0.5524798 0.3289148 -0.7588921 -0.5581362 0.3355098 -0.7329748 -0.5581869 0.3888127 0.783603 0.6187801 -0.05547624 0.4584897 0.888563 0.01558768 0.4689215 0.8831127 0.01499128 0.4884036 0.8725921 -0.006705582 0.4946167 0.8690535 -0.01001995 -0.4674769 0.8839196 0.01231753 -0.6499344 0.7574146 0.0625174 -0.5392602 0.8412723 -0.03820252 -0.4821541 0.8760843 -0.001973628 -0.4561445 0.8893169 0.03237199 0.9197326 -0.3535543 0.1705617 0.8309817 -0.5313491 0.1647344 0.8236488 -0.5461421 0.1527475 0.5367223 -0.8378679 0.09953188 0.5330435 -0.8404659 0.09737384 0.5343043 -0.8394604 0.0991218 0.3630246 -0.9294348 0.06606155 0.0618245 -0.9980729 0.005305171 0.1731467 -0.9843289 -0.03341829 0.2311636 -0.9725226 0.02762651 0.797298 -0.3782054 0.4704007 0.7554484 -0.5405651 0.3702529 0.7552475 -0.5351347 0.3784603 0.6648733 -0.6669641 0.3363072 0.5828732 -0.7582299 0.292141 0.9688513 -0.1704224 0.1796764 0.9688547 -0.1704111 0.1796686 0.8460776 -0.1707913 0.5049586 0.8429045 -0.1494033 0.516905 -0.9996833 0 0.02516734 -0.9871262 -0.003756284 0.1598992 -0.9861756 -0.002867579 0.1656793 -0.9356445 0.001300573 0.3529418 -0.8567708 -0.009527027 0.5156095 -0.8444539 -0.005864977 0.535596 -0.6932817 0.003321945 0.7206591 -0.5541177 -0.008664488 0.8323934 -0.4843183 -8.84764e-4 0.8748914 -0.1455022 -0.006641685 0.9893357 -0.353136 1.14049e-4 0.935572 0.4183941 -3.95597e-4 0.9082656 0.2923395 -0.00435537 0.9563047 0.2913514 -0.004441678 0.9566059 0.08736544 0.001395165 0.9961754 -0.08234351 -0.002608478 0.9966007 0.4963976 1.05507e-4 0.8680953 0.6263465 -0.001002907 0.7795442 0.6404545 0 0.7679961 0.7686919 -0.1217497 0.627925 0.8900752 -0.1880888 0.4151974 0.7428156 -0.5642017 0.3604186 0.810483 -0.5242559 0.2612916 0.8109936 -0.5236135 0.260995 0.8722633 -0.2701798 0.4076269 0.8022724 -0.07780945 0.5918654 0.7933198 -0.1131093 0.5982058 0.811563 -0.2534162 0.5264463 0.7900297 -0.3175931 0.5243929 0.7940789 -0.355427 0.4930623 0.7643292 -0.5411415 0.3506662 0.8510496 -0.5154001 0.1003856 0.8891456 -0.44802 0.09326416 0.900844 -0.3743786 0.2198199 0.9421103 -0.140055 0.3046524 0.960245 -0.05788379 0.2730914 0.9341536 -0.2223766 0.2791159 -0.9927645 0.07872861 0.09066665 0.9721847 0.01079851 0.2339667 0.9919177 0.08366852 0.09538811 0.9861437 0 0.1658939 0.9945972 -0.04694932 0.09258645 0.3492634 2.84035e-4 0.9370247 0.3642242 -0.01649111 0.9311653 0.5687997 0.01448273 0.8223487 0.5896487 -0.002744376 0.8076553 0.7169969 0.001122534 0.6970756 0.7629304 -0.01648646 0.6462705 0.8638219 0.01269423 0.5036376 -0.6071178 -0.002237677 0.7946088 -0.5764848 0.02153009 0.8168243 -0.381853 -0.02436125 0.923902 -0.358157 -7.51131e-6 0.9336614 -0.2240383 -0.002003073 0.9745783 -0.1285034 0.03147006 0.9912096 -0.0950911 0.001411676 0.9954677 0.1192045 9.67012e-4 0.9928693 0.0629521 0.0713678 0.9954616 0.1793444 -0.003621697 0.9837797 -0.7237753 7.73337e-4 0.6900354 -0.7841463 -0.01885074 0.6202898 -0.769214 -0.009766399 0.6389168 -0.8957307 0.01382499 0.4443821 -0.8717893 0.03777366 0.4884225 -0.9145674 0.002254784 0.4044275 -0.9885229 -0.003178477 0.1510381 -0.9876746 4.14038e-5 0.1565215 -0.7671447 -0.1773406 0.6164734 0.1404511 -0.9700826 0.1980238 0.37999 -0.8332507 0.4016231 0.4510996 -0.7662396 0.4575871 0.4532742 -0.7635676 0.459899 0.9532018 -0.2818036 0.1095131 -0.9031972 0.133114 0.4080632 -0.923036 -0.2526456 0.290129 -0.9866504 -0.01695054 0.1619684 -0.5206639 -0.666912 0.5330457 -0.7593155 -0.4839102 0.4350528 -0.7904974 -0.4571272 0.4076133 -0.9014804 -0.2951893 0.3165381 -0.9545159 -0.1894035 0.2302733 0.6148586 -0.6202261 0.4871022 0.433519 -0.7098945 0.5550777 0.4616085 -0.6925624 0.5543239 0.2531127 -0.7500114 0.6110785 0.2911792 -0.7399209 0.6064089 0.09561324 -0.7741412 0.6257504 0.1001266 -0.7730376 0.6264085 -0.08017295 -0.7620244 0.6425662 -0.2475837 -0.7445935 0.6199057 0.6229548 -0.7014572 0.3462443 0.2758544 -0.843935 0.4600849 0.334311 -0.8289549 0.4484081 0.08561927 -0.866132 0.4924274 0.1509971 -0.8493586 0.5057567 -0.5304136 -0.7028954 0.4739194 -0.1888643 -0.7890794 0.5845375 -0.4147779 -0.7166431 0.5606977 -0.5637071 -0.6481795 0.5119548 -0.8053491 -0.3871407 0.4489264 -0.726475 -0.4978944 0.4736405 -0.7829278 -0.4405047 0.4392946 -0.4643609 -0.7482577 0.4737927 -0.53947 -0.7077568 0.4561277 -0.1449728 -0.8982679 0.4148465 -0.22988 -0.881812 0.4117799 0.1935363 -0.9328069 0.3039983 0.1061016 -0.9437003 0.3133245 -0.1253761 -0.9187157 0.3744896 0.2903195 -0.9203365 0.2620981 0.245076 -0.9285947 0.2786571 -0.8247179 -0.1039032 0.5559176 -0.7050234 -0.4868986 0.5156275 -0.3670285 -0.8439435 0.3912157 -0.5016377 -0.767177 0.3997491 -0.04357302 -0.9766343 0.2104445 -0.2291686 -0.9412002 0.2482417 -0.1357371 -0.969406 0.204518 0.09167772 -0.9857574 0.1409878 -0.171586 -0.8536605 0.491754 0.9914014 -0.06615465 0.1129029 -0.1786282 -0.9632559 0.2005745 -0.1978711 -0.9498666 0.2420757 -0.1494985 -0.9544601 0.2581787 -0.4128522 -0.8595918 0.3010898 -0.4280118 -0.8243452 0.3704876 -0.422279 -0.794198 0.4369555 -0.3940389 -0.8090768 0.4360367 -0.5342237 -0.6649363 0.5219817 -0.5744243 -0.6838057 0.4499406 0.2200781 -0.78621 0.5774422 0.7534826 -0.3777287 0.5381312 0.8593551 -0.3131967 0.4042484 0.6943214 -0.5472268 0.4673979 0.6436199 -0.6117042 0.4599689 0.4543647 -0.7553479 0.4722314 0.3891693 -0.8022623 0.4526835 0.08088237 -0.9068867 0.4135391 0.1528166 -0.9533588 0.2602965 -0.06795036 -0.9881198 0.1378479 -0.07052338 -0.9883018 0.1352267 0.005915641 -0.9992433 0.03844422 0.1184522 -0.9606539 0.251224 0.3889749 -0.8366813 0.3855684 0.4114583 -0.8164135 0.4051804 0.6089993 -0.6286494 0.4836527 0.6254836 -0.6003981 0.4982897 0.7719402 -0.3475546 0.5322728 0.8147216 -0.3741412 0.4429978 -0.6205204 -0.5721347 0.5362988 -0.5021795 -0.6725665 0.5435716 -0.4343334 -0.6964755 0.5712061 -0.4077998 -0.7106373 0.5733184 -0.2577581 -0.7447454 0.6155608 0.1663509 -0.7694076 0.6167166 -0.0990051 -0.808068 0.5807101 0.05296629 -0.8059877 0.5895579 0.694936 -0.5486627 0.4647939 0.5034814 -0.6675466 0.5485326 0.4352634 -0.7087372 0.5551914 0.1229172 -0.7909533 0.5994033 0.1648136 -0.8964574 0.4113402 -0.1388285 -0.929351 0.3421013 -0.002291798 -0.9132443 0.4074063 -0.4001926 -0.8648073 0.3032395 -0.3668241 -0.9083264 0.200956 0.07978332 -0.982082 0.1707327 0.4367114 -0.8444218 0.3102177 0.4327898 -0.8390857 0.3295882 0.6111359 -0.5416467 0.5771757 0.7112668 -0.6223913 0.3266937 0.5986758 -0.1731771 0.7820467 0.8868401 -0.3671023 0.2806255 0.8148719 -0.1929475 0.546585 0.8301257 -0.154138 0.5358478 0.9587029 -0.06279492 0.2773904 0.8896344 -0.229496 0.3948194 0.9950238 -0.02331662 0.09687113 0.8698726 -0.3374384 0.3598014 0.9210701 -0.272993 0.2776775 0.7594725 -0.4796063 0.4395219 1 -8.33778e-6 0 -0.7767741 -0.3251965 0.5393231 -0.6279937 -0.09931284 0.7718556 -0.6202471 -0.5304655 0.5778407 -0.4356378 -0.6086385 0.6631583 -0.259047 -0.6532002 0.7114943 -0.1442409 -0.6446986 0.7507053 -0.1002693 -0.6727683 0.7330273 0.05355083 -0.6752135 0.7356759 0.1863991 -0.6411694 0.7444174 0.2221899 -0.6592438 0.7183519 0.5049583 -0.5836193 0.635929 -0.7947643 -0.3098588 0.5218596 -0.4314959 -0.4606264 0.775651 -0.4311088 -0.4605605 0.7759055 -0.1422619 -0.5052777 0.8511498 -0.142246 -0.5052677 0.8511584 0.1840151 -0.501721 0.8452305 0.183618 -0.5018224 0.8452566 0.5002076 -0.442032 0.7445805 0.4998874 -0.4422963 0.7446386 -0.5338283 -0.154628 0.8313349 -0.4305527 -0.172422 0.8859431 -0.3997499 -0.1681253 0.9010737 -0.1420642 -0.181569 0.9730625 -0.1901561 -0.1940919 0.9623768 0.1827265 -0.1609823 0.9698947 0.1347651 -0.1815205 0.9741092 0.4990835 -0.1590955 0.8518241 0.5440571 -0.1373842 0.8277243 0.9209575 -0.2634692 0.2870914 0.9209066 -0.2636266 0.2871101 0.9192028 -0.2011816 0.3385149 0.9189931 -0.2016081 0.3388302 0.9917066 -0.06580001 0.110402 0.991736 -0.06559365 0.1102605 0.9919264 -0.0858199 0.09336495 0.9919382 -0.08567386 0.09337323 0.7594336 -0.4399663 0.4792603 0.7594233 -0.4399203 0.4793186 0.7554879 -0.3345612 0.5633 0.7551407 -0.3349258 0.5635488 0.7554174 -0.1313468 0.6419445 0.9135442 -0.01931154 0.4062809 0.8491907 -0.1173729 0.5148775 0.9912901 -0.01142346 0.1312006 0.9865412 -0.03007078 0.1607245 -0.8988714 -0.2507774 0.3593621 0.4302673 -0.2206133 0.8753286 0.4300212 -0.5164306 0.7405277 0.1419779 -0.5588642 0.8170148 0.2509883 -0.5536324 0.7940379 0.4304876 -0.516153 0.7404502 0.4309115 -0.2203999 0.8750653 0.1421627 -0.2417764 0.9598614 0.1420241 -0.2418628 0.9598602 -0.1835584 -0.2401653 0.9532193 -0.1835135 -0.2401307 0.9532366 -0.4117749 -0.5211745 0.7475417 -0.2450876 -0.5544089 0.7953383 -0.07907474 -0.5700299 0.81781 0.09458136 -0.5692202 0.8167269 -0.560213 -0.4738144 0.6794567 -0.4996228 -0.485736 0.7172431 -0.4996186 -0.2117246 0.8399726 -0.4992176 -0.2116793 0.8402224 -0.7546701 -0.3756085 0.5379513 -0.7540531 -0.3757418 0.5387226 -0.7548848 -0.1604412 0.6359304 -0.7544426 -0.1604123 0.6364623 -0.7590588 -0.08487957 0.6454652 -0.4989101 0.09815603 0.8610773 -0.5539854 -0.03761053 0.8316764 -0.1861959 -0.02659046 0.9821528 -0.1454359 0.04322773 0.9884229 0.1445192 -0.08490526 0.9858527 0.2901594 0.08605551 0.9531013 0.4359292 -0.07339924 0.8969829 0.6260827 0.02271974 0.7794256 0.731126 -0.1667149 0.6615595 0.7817217 -0.1694134 0.6001754 0.4751475 -0.5033622 0.7217072 0.6140816 -0.4792671 0.6270622 -0.9535077 -0.1727516 0.2469412 -0.9191281 -0.2180079 0.3281406 -0.9189062 -0.09652715 0.3824838 -0.9187961 -0.09654819 0.3827431 -0.9204982 -0.06043338 0.3860452 -0.8504955 0.1214137 0.5117775 -0.9916262 -0.0739603 0.1058655 -0.9916655 -0.07381099 0.1056014 -0.9917022 -0.03149861 0.1246383 -0.991688 -0.03149521 0.1247523 -0.9919436 -0.00437653 0.1266052 -0.9859274 0.04948878 0.1596816 -1 -1.33319e-5 0 -1 1.63129e-5 2.58916e-4 0.001513898 0 -0.9999989 -1.27586e-4 0 -1 2.46542e-5 0 -1 -2.77739e-4 0 -1 2.77739e-4 0 -1 1.41102e-4 0 -1 5.83322e-4 0 -0.9999998 0.9999302 -0.01182216 0 0.9979452 -0.06279271 -0.01274478 0.9782211 -0.1662066 -0.1243339 -0.9999302 -0.01182216 0 -0.9829402 -0.1791005 -0.0418542 -0.9858763 -0.1674754 0 -0.8960372 -0.4439789 0 -0.6427689 -0.5491357 -0.5341332 -0.8346301 -0.5508109 0 -0.4738188 -0.8806223 0 0.9722985 -0.1381417 -0.188554 0.8346216 -0.5508239 0 0.8345398 -0.5509476 0 0.4739342 -0.8805604 0 0.473811 -0.8806266 0 0.123122 -0.9923916 0 0 -0.9529026 0.3032768 -0.123122 -0.9923916 0 -0.4739264 -0.8805645 0 -0.9858711 -0.1674972 0.001710176 -0.9761756 -0.1884228 -0.1076026 -0.827546 -0.5407762 0.1507613 -0.8195586 -0.5409359 0.1889765 -0.5419375 -0.8281608 -0.1430157 -0.4255152 -0.7906551 0.4402288 -0.1772046 -0.935545 -0.3055393 -0.1231003 -0.99234 0.01037663 0.9858661 -0.1675267 0.001731812 0.1106366 -0.8917009 -0.4388953 0.4472362 -0.6688495 0.5938183 0.4634236 -0.8610414 -0.2093955 0.7635121 -0.6380536 0.09968411 0.8775309 -0.4701534 0.09431517 0.9761704 -0.1884312 -0.1076342 0.7457803 -0.08497017 0.6607511 0.7241933 -0.111815 0.6804715 0.663489 -0.312352 0.6798666 0.6841465 -0.1197793 0.7194418 0.3906261 -0.2221119 0.8933519 0.5857122 -0.09556406 0.8048657 0.2495865 -0.2429902 0.9373699 0.4527472 -0.08512103 0.8875666 0.07973372 -0.2471362 0.9656947 0.284021 -0.08919787 0.9546601 -0.1166589 -0.2398404 0.9637777 0.1085812 -0.089827 0.9900208 0.0276001 -0.1258127 0.99167 -0.3651845 -0.2154782 0.9056542 -0.1436762 -0.105023 0.9840363 -0.5102282 -0.256052 0.8210387 -0.3210807 -0.09466195 0.9423091 -0.7054764 -0.2519931 0.6624218 -0.5460396 -0.1145167 0.8298957 -0.8633079 -0.2344981 0.4468896 -0.7472545 -0.1361244 0.6504468 -0.9424155 -0.2177645 0.2538343 -0.8716359 -0.1580995 0.4639565 -0.9722064 -0.2059615 0.1113308 -0.9543761 -0.1807398 0.2376962 -0.9820197 -0.1882894 0.01358479 -0.981048 -0.1861689 0.05372309 -0.5487983 -0.8348717 0.04254245 -0.1872137 -0.9805347 0.05918443 -0.2025838 -0.9578304 0.2037663 -0.1524689 -0.9806642 0.1226826 -0.089024 -0.9316475 0.3522893 -0.08708614 -0.9350972 0.3435248 0.3083614 -0.8580191 0.4107513 0.2892209 -0.8660604 0.4077875 0.286094 -0.8730972 0.3947806 0.100482 -0.8487922 0.5190908 0.116084 -0.8788766 0.46271 0.07672476 -0.912453 0.4019239 -0.5437248 -0.8349625 0.08485901 -0.5249438 -0.8193015 0.2306058 -0.4166862 -0.8154349 0.4017944 -0.4207372 -0.8172442 0.3938177 -0.2534933 -0.7948703 0.5512916 -0.2825572 -0.8076005 0.517632 -0.0489245 -0.7669139 0.6398825 -0.1201379 -0.7980718 0.5904645 0.1451877 -0.7455078 0.6504911 0.04599487 -0.7894509 0.6120881 0.3146468 -0.7326987 0.6034485 0.1659493 -0.7968508 0.5809386 0.3846836 -0.7146219 0.584238 0.4469009 -0.7013622 0.5553114 0.3840342 -0.7545943 0.5320763 0.5123898 -0.695534 0.5036758 0.4613456 -0.7415883 0.4870391 0.5656566 -0.6888071 0.4534066 0.6021797 -0.6452779 0.4701023 0.5855075 -0.6082257 0.5359503 -0.8356713 -0.5483118 0.03174471 -0.830347 -0.5479561 0.101331 -0.8268027 -0.5462483 0.1342018 -0.7853454 -0.5434576 0.2964563 -0.7917358 -0.5462604 0.2734118 -0.6816121 -0.5259056 0.5087518 -0.7151188 -0.5409065 0.4427475 -0.4959746 -0.5071282 0.7048619 -0.5688948 -0.5381782 0.6218706 -0.2605459 -0.4821585 0.8364443 -0.3826493 -0.5341823 0.7538096 -0.02823555 -0.4648033 0.8849637 -0.1765269 -0.52907 0.8300141 0.1894915 -0.4554613 0.8698552 0.01871907 -0.5301979 0.8476673 0.3509551 -0.4494466 0.8214793 0.1782277 -0.5270752 0.8309192 0.4854896 -0.4524865 0.7480347 0.3268149 -0.5253429 0.7856253 0.5965733 -0.4600266 0.657629 0.459662 -0.5242964 0.7168154 0.6841536 -0.4729804 0.5551788 0.7509872 -0.4319653 0.4994239 0.7119754 -0.3903648 0.5837005 -0.5859307 -0.6613414 0.4683087 -0.3205878 -0.872826 0.3679649 -0.4188207 -0.7443829 0.5200801 0.177854 -0.9755113 0.129405 0.1873719 -0.9817504 0.03252542 0.8444026 -0.1321443 0.5191555 0.8565329 -0.1384387 0.4971783 0.9417222 -0.1232367 0.3130049 0.978002 -0.1333939 0.1603689 0.9050921 -0.1645455 0.3920881 0.5307963 -0.06145298 0.8452686 0.5997357 -0.08913987 0.7952177 0.6671216 -0.1164589 0.7357895 -0.06420505 -0.08063703 0.9946736 0.09324532 -0.1067591 0.989903 0.3194925 -0.1364924 0.9377071 0.2376931 -0.1025315 0.9659138 0.5238205 -0.1344195 0.8411561 0.6358076 -0.1818428 0.7501212 -0.1249354 -0.01405519 0.9920654 0.01900434 -0.1818312 0.9831461 -0.3245322 -0.03362536 0.9452769 -0.2580854 -0.2223584 0.9401856 -0.3332194 -0.1623891 0.9287598 -0.09261292 -0.8142507 0.5730783 -0.1294348 -0.8702536 0.4752949 -0.1029922 -0.9047884 0.4132198 0.05437725 -0.9340836 0.3528897 0.06190425 -0.9211968 0.384141 0.09306693 -0.9564339 0.2767182 -0.3885536 -0.6325552 0.6700001 -0.6407387 -0.6419885 0.4210757 -0.6249415 -0.7185734 0.3051236 -0.5930947 -0.7315335 0.3362997 -0.57816 -0.6721612 0.462526 -0.432164 -0.7379118 0.5183827 -0.5189321 -0.73531 0.4359229 -0.4373263 -0.6627976 0.60782 -0.6485785 -0.5723417 0.5017677 -0.5874307 -0.4454657 0.6756372 -0.9234139 -0.2592315 0.28303 -0.2598105 -0.3228648 0.9100863 0.5294196 -0.8003493 0.2813466 0.5063434 -0.854959 0.1125236 0.4139394 -0.8105928 0.4142386 0.4253802 -0.8547673 0.2973626 0.2640418 -0.7838274 0.5620468 0.3010812 -0.8503335 0.4316053 0.09000027 -0.7612066 0.642234 0.1486585 -0.8426255 0.5175741 -0.08671897 -0.7441066 0.6624087 -0.01179134 -0.8338966 0.5517948 -0.2483029 -0.7345759 0.6314617 -0.1582992 -0.8246313 0.5430697 -0.3212654 -0.7632134 0.5606192 0.8694432 -0.4707437 -0.1498961 0.8950316 -0.4326809 0.1081939 0.7574575 -0.3708238 0.5373526 0.8287795 -0.4460743 0.3378496 0.5826008 -0.3427791 0.7369389 0.7039784 -0.455237 0.5451365 0.3811438 -0.3223668 0.8664925 0.5305543 -0.4582597 0.7130991 0.1670983 -0.3087047 0.9363651 0.3276486 -0.4573258 0.8267403 -0.04511481 -0.3023679 0.9521231 0.1229868 -0.4532176 0.8828749 -0.2395731 -0.2995302 0.9235185 -0.07533425 -0.4500134 0.8898386 -0.4162237 -0.3030973 0.8572573 -0.2526075 -0.4454928 0.8589097 -0.5628709 -0.309 0.766613 -0.7444213 -0.1162928 0.6575052 -0.4939536 -0.1104782 0.862441 -0.7025429 -0.3105639 0.6402996 -0.4108347 -0.4428868 0.7969103 -0.471876 -0.5009914 0.7254934 -0.4290431 -0.5626671 0.7066313 -0.281145 -0.5594121 0.7797536 -0.05177348 -0.656177 0.7528289 -0.1096146 -0.562883 0.819236 0.1323195 -0.663081 0.73676 0.08458262 -0.5700426 0.81725 0.3265689 -0.669658 0.6670166 0.2843157 -0.5836753 0.7605839 0.5043683 -0.6744623 0.5391785 0.4719073 -0.6020034 0.6441238 0.6441064 -0.6751133 0.3596515 0.6284416 -0.6248108 0.463328 0.7368018 -0.670973 0.0831772 0.7547118 -0.6289395 0.1866694 0.1887327 -0.9054054 0.3802911 0.251265 -0.7702518 0.5861555 0.3056193 -0.7680084 0.5628145 0.3836281 -0.752995 0.5346291 0.4209508 -0.7380404 0.5273488 0.4613235 -0.7347512 0.4973142 0.5498914 -0.7042102 0.4491187 0.575345 -0.7230246 0.382379 0.698217 -0.640739 0.3192908 0.6893131 -0.669092 0.2777833 0.7357972 -0.6574994 0.162164 -0.2010471 -0.8969674 0.3937382 0.01860922 -0.94481 0.3270899 0.05525803 -0.9402483 0.3359758 -0.02758675 -0.993918 0.1066111 0.2710881 -0.9619419 0.03433686 -0.4326646 -0.7439528 0.5092501 -0.4514936 -0.7366222 0.5035288 -0.5708727 -0.6974401 0.4332227 -0.5811571 -0.6885403 0.4337842 -0.6440321 -0.6872075 0.336108 -0.3167409 -0.7522596 0.5777376 -0.2332024 -0.735691 0.6359052 -0.3053317 -0.752216 0.5839039 -0.2065558 -0.7911091 0.575744 0 -0.7743589 0.6327466 -0.06078946 -0.9432334 0.3265202 -0.7386425 -0.6541795 0.1626546 -0.6857259 -0.6726617 0.2780402 -0.7298964 -0.6262806 0.2739052 0.2162662 -0.769009 0.6015431 0.2580555 -0.7714987 0.5815471 0.203791 -0.79037 0.5777409 0.125353 -0.7894152 0.6009246 -0.03491407 -0.7909505 0.6108833 -0.2250391 0.9274719 0.2985858 -0.4481711 0.8790522 -0.1625112 0.8123278 0.5131103 -0.2772031 0.4830031 0.8557881 -0.1852967 0.4006853 0.9066979 -0.1317207 0.376381 0.9198759 -0.1102974 0.8869644 0.3785536 -0.264559 0.998593 0.007651269 -0.05247378 0.93195 0.05033159 -0.3590766 0.941599 0.1408416 -0.3058675 0.9728397 -0.07616031 -0.2185925 0.9937809 -0.105743 0.03489995 0.9920054 -0.1157305 -0.05031621 0.987397 -0.1157905 -0.1078874 0.844261 -0.5025988 0.1860585 0.8817864 -0.4532209 0.1305512 0.9716289 -0.2302893 0.05389171 0.787537 -0.5000946 0.3601261 0.806187 -0.3300842 0.4910264 0.6702589 -0.5010483 0.5474518 0.4265621 -0.4912649 0.75941 0.3950389 -0.2265958 0.8902801 0.5395295 -0.5019894 0.6759547 -0.4456152 -0.4160695 0.7926622 -0.4062358 -0.4811542 0.776829 -1.47189e-4 -0.5063471 0.8623298 -0.05326938 -0.3571483 0.9325275 0.1763877 -0.5031925 0.8459815 -0.8029066 -0.3414212 0.4886436 -0.6946002 -0.4987433 0.5184454 -0.5768682 -0.5034041 0.6432788 -0.9768627 -0.2088 0.04628163 -0.9990919 0.001815617 0.04256802 -0.8817077 -0.4534032 0.1304501 -0.8442887 -0.5026103 0.1859021 -0.801499 -0.501986 0.3249762 -0.9282357 0.2263998 -0.2951642 -0.9483411 0.06172734 -0.3111897 -0.9016728 0.2575429 -0.3473584 -0.9711191 -0.03599721 -0.2358645 -0.9773598 -0.07314479 -0.1985386 -0.9825256 -0.1018645 -0.155779 -0.4273055 0.9016686 -0.06636077 -0.3885223 0.9130623 -0.1239661 -0.3449441 0.9358129 -0.07257968 -0.3981549 0.8629905 0.3109987 -0.3431086 0.9275658 0.1479807 -0.3819649 0.9240815 0.01327735 -0.3711493 0.9276576 -0.04122817 -0.1951055 0.8582107 0.4747718 -0.1872881 0.9240821 0.3331601 -0.04778784 0.92738 0.3710563 -8.10326e-5 0.900803 0.434228 0.04771208 0.9273855 0.3710523 0.1422445 0.9272795 0.3462936 0.2125968 0.9008633 0.378481 0.2249765 0.9274733 0.2986286 0.2951797 0.9271807 0.2306622 0.370434 0.9010414 0.2256172 0.3430833 0.927566 0.1480381 0.3709195 0.9270721 0.05437028 0.3711706 0.9276521 -0.04115837 0.3605276 0.9283933 -0.09003221 0.2885563 0.9532791 -0.08940988 -0.6420732 0.7300575 -0.2340045 -0.6775439 0.7059026 -0.2064843 -0.7184971 0.6950814 0.02497667 -0.7184942 0.6950845 0.02497678 -0.6141313 0.6950889 0.373757 -0.6141356 0.6950901 0.3737478 -0.3522959 0.6950895 0.6266883 -0.3522936 0.6950981 0.6266801 -1.39082e-4 0.6951014 0.7189117 -1.1705e-4 0.6950787 0.7189337 0.3520699 0.6950893 0.6268156 0.3520792 0.6950871 0.6268128 0.6140077 0.6950839 0.3739692 0.6140054 0.6950858 0.3739694 0.718473 0.6950971 0.02523297 0.7184855 0.6950842 0.02523255 0.6789546 0.7060917 -0.2011349 0.6816005 0.7016867 -0.207501 -0.8420078 0.4521963 -0.2941792 -0.917435 0.3221115 -0.2335749 -0.9492537 0.3127755 0.03299838 -0.9492556 0.31277 0.03299963 -0.8113881 0.312765 0.4937889 -0.8113909 0.312752 0.4937926 -0.4654594 0.3127478 0.8279713 -0.4654555 0.3127488 0.8279731 -1.48557e-4 0.3127457 0.949837 -1.69339e-4 0.3127685 0.9498294 0.465147 0.3127692 0.8281387 0.8112032 0.3127884 0.4940778 0.8112132 0.3127546 0.4940826 0.9492529 0.3127422 0.03333675 0.9492434 0.3127711 0.03333652 0.9173423 0.3220856 -0.233975 0.9315078 0.2018561 -0.3025679 -0.9889097 -0.1157286 -0.09308391 -0.9920006 -0.1153439 -0.05129063 -0.9937242 -0.1063894 0.03454482 -0.9912821 -0.1247275 0.04246163 -0.8476014 -0.1244599 0.5158312 -0.8475967 -0.1244679 0.515837 -0.4862353 -0.1244679 0.8649179 -1.84215e-4 -0.1244515 0.9922258 -1.73528e-4 -0.1244723 0.9922232 0.4859277 -0.1244754 0.8650896 0.485911 -0.1244829 0.8650981 0.8474173 -0.1244676 0.5161315 0.8474142 -0.1244823 0.5161332 0.991251 -0.1247106 0.04322993 0.9987639 -0.02503794 0.04294085 -0.8880836 0.08634144 -0.4515004 -0.9288044 0.05567795 -0.3663638 -0.9546037 0.03330522 -0.296011 -0.9659264 0 -0.2588172 -0.7070956 0 -0.7071179 -0.7071212 0 -0.7070925 0.7071225 0 -0.7070912 0.7070971 0 -0.7071164 0.9289084 0.2329424 -0.2878664 0.8914272 0 -0.4531641 0.965771 0.01783537 -0.2587823 0.9498258 0.03595781 -0.3107058 0.9655769 0.02687776 0.2587255 0.989427 0 0.1450322 0.9939072 0 -0.1102203 0.7068491 0.02709871 0.7068451 0.7879652 0 0.6157199 0.2586995 0.02720081 0.9655748 0.3799384 0 0.9250119 0.6017244 0 0.7987039 -0.2586995 0.02720415 0.9655748 -0.1277926 0 0.991801 0.1276154 0 0.9918238 -0.7068352 0.0270999 0.706859 -0.6018961 0 0.7985745 -0.380102 0 0.9249446 -0.9938871 0 -0.1104013 -0.965575 0.02688622 0.2587317 -0.9182472 0 0.3960077 0 1 -3.17759e-7 0 1 4.34065e-7 0 1 -1.00243e-6 0 1 7.33839e-7 4.25621e-5 -1 1.07512e-4 -1.82109e-4 -1 4.56901e-4 -0.9986427 -1.10395e-4 0.05208444 -0.7496439 -0.03213423 0.6610608 -0.8156383 2.35543e-4 0.5785622 -0.909963 -1.688e-4 0.4146894 -0.8880031 -0.008816659 0.459753 -0.9845362 0.02908694 0.1727504 -0.9336917 -0.06148952 0.3527591 -0.9738515 -0.01302498 0.2268122 -0.6672942 -0.07482731 0.741026 -0.7915948 0.08711898 0.6048043 -0.542688 -0.03608125 0.8391591 -0.6166544 0.002049088 0.7872315 -0.4286825 -0.00192064 0.9034533 -0.1923614 0.004299461 0.9813147 0.2887828 0 0.9573947 0.2048383 0.05742835 0.9771096 0.03902983 0 0.9992381 -0.8560522 -0.360443 0.3704804 -0.9775812 -0.1719454 0.1215316 -0.980467 -0.1934006 0.03578919 -0.9045316 -0.4213203 0.06566578 -0.902262 -0.426648 0.06240993 -0.792066 -0.607844 0.05618929 -0.7918768 -0.6081199 0.05587029 -0.6078145 -0.79214 0.05546206 -0.6218981 -0.7800782 0.06870967 -0.4221053 -0.9063128 0.02059739 -0.04983067 -0.9987473 0.004565715 -0.1730714 -0.9841262 0.03926819 -0.2209799 -0.9750625 0.02051824 -0.4474601 -0.8934727 0.038549 0.2374817 -0.9711481 0.02176767 0.1729335 -0.9833962 -0.05501067 0.5710285 -0.8138468 0.1076102 0.536088 -0.8424002 0.05451422 0.7693921 -0.6363158 0.05601984 0.8359154 -0.5321419 0.1344264 0.8844957 -0.4610932 0.07113605 0.9608101 -0.2733547 0.04605865 0.9774705 -0.1723766 0.12181 0.9769445 -0.1700776 0.1290469 0.9775835 -0.171939 0.1215223 -0.2502403 0.00695163 0.9681588 -0.2266392 0.002441346 0.9739758 -0.2016535 4.50944e-4 0.9794568 -0.3704223 -0.01064854 0.9288025 -0.2659907 0.01061564 0.9639172 -0.2387214 0.002776145 0.9710842 -0.3667868 -0.00498116 0.9302918 -0.3274762 -0.0258668 0.9445054 -0.3482887 -0.01746553 0.9372246 -0.4836033 0 0.8752874 -0.4826825 0.001000583 0.8757949 -0.4235897 -7.6708e-4 0.9058538 -0.3955438 -0.005384385 0.9184314 0 -7.62941e-4 0.9999998 0 -7.62939e-4 0.9999998 0 0.01934748 0.9998129 0.001106381 0.08196479 0.9966346 0.002311229 0.0949316 0.9954811 -0.001431345 0.03744268 0.9992979 0.4271765 -0.009435892 0.904119 0.4023557 -0.01783502 0.9153096 0.3800029 -0.02622008 0.9246137 -0.1872712 -2.7915e-5 0.9823083 0.003326714 8.08914e-4 0.9999942 0 -0.002331018 0.9999974 0.2053382 2.68975e-4 0.9786911 0.2387362 0.004386007 0.9710746 0.2494055 0.002140462 0.9683969 0.3207073 -0.002153158 0.9471759 0.3667665 -0.01213836 0.930234 0.4829936 0.02946114 0.8751282 0.4835963 0 0.8752912 0.4826055 0.001112461 0.8758372 0.5222118 0.01347088 0.8527094 0.5518383 0.006366193 0.8339269 0.6911003 1.60456e-5 0.722759 0.6819842 0.003219842 0.7313599 0.6236229 -3.94444e-4 0.7817253 0.5882103 0.001006066 0.8087075 -0.6321126 -0.003909587 0.7748668 -0.6815338 0.006246924 0.73176 -0.7113303 0 0.7028579 -0.5690062 0.003545999 0.8223257 -0.5465422 0.007439076 0.8373985 -0.5716104 0.001377522 0.820524 -0.5204926 -2.17161e-4 0.8538662 -0.4813626 0.00123161 0.8765208 1 -1.60149e-6 0 1 0 -1.07875e-6 1 5.82229e-5 3.30714e-6 1 -9.15974e-5 1.81697e-5 1 5.15803e-5 1.41842e-5 1 6.64306e-5 1.52249e-5 1 -1.30115e-6 -5.20461e-6 1 -1.32079e-6 0 1 -8.71022e-7 -1.46504e-5 1 1.37656e-6 0 1 2.71352e-4 -3.5385e-5 1 1.12521e-6 0 0.9999982 8.38842e-4 0.001705229 1 1.27742e-4 -3.72609e-4 1 1.60194e-5 -1.01624e-5 -0.6270686 0 -0.7789641 -0.859857 0 -0.510535 -0.9840933 0 -0.1776529 -0.9840927 0 -0.1776561 1 8.62366e-6 0 1 -3.50833e-6 0 1 5.6484e-6 0 1 -1.37106e-5 0 1 1.15781e-6 0 1 1.59723e-6 0 1 1.94704e-7 0 1 1.07558e-4 0 1 7.29501e-5 0 -1 2.15076e-6 0 -1 -1.33633e-6 0 -1 4.52405e-6 0 -1 -1.31872e-5 0 -1 1.74358e-4 0 -1 1.83332e-5 0 -1 -4.20851e-6 0 -1 -1.0411e-6 0 -1 5.19991e-6 0 -1 -4.58143e-5 0 -1 -8.41751e-5 0 0.7555878 0.07007384 0.6512886 0.5751219 -0.7027096 0.4188485 0.8269484 0 0.5622777 0.6090837 -3.09172e-4 0.793106 0.609194 -0.2057343 0.7658695 0.6904781 0.1200274 0.7133256 0.7109593 -0.03851395 0.7021777 0.7358786 0 0.6771135 -0.8269456 0 0.5622821 -0.578656 -0.6984612 0.421081 -0.5792042 0.5972182 0.554845 -0.712886 0 0.7012801 -0.6943722 0.1733343 0.6984286 -0.6078863 -0.2241602 0.761726 -0.6090822 0 0.7931072 -0.6441837 0.7606378 0.08035844 -0.7070792 0.7070792 0.008825361 -0.3899075 0.9208421 -0.004714965 -0.7768747 0.6296245 0.006221771 -0.8561073 0.5167981 -4.16288e-5 -0.9324809 0.356584 0.05768305 -0.9861647 0.1657485 0.002610087 0.2581033 0.9632996 0.07373362 0.182753 0.9826098 0.03285658 0.05591732 0.9984355 -4.93078e-5 -0.2588168 0.9659265 2.37976e-4 -0.1085105 0.977797 0.1792727 -0.2391763 0.9673203 0.0841791 0.8582617 0.5132124 -2.34777e-5 0.7736285 0.6336184 0.005185365 0.7063023 0.7062879 0.04790097 0.5900437 0.8073707 -0.001152276 0.3720673 0.9282046 0.001448154 0.9099496 0.4147191 1.57596e-4 0.9655318 0.2587088 0.02860438 0.9845656 0.1749942 0.002767264 0.7071068 -0.7071068 0 0.7071115 -0.7071021 0 0.2588172 -0.9659264 0 -0.2588194 -0.9659258 0 -0.7071068 -0.7071068 0 -0.9238748 -0.3826949 0 -0.9656516 -0.2587439 0.02384471 -0.9914479 -0.1305032 0 -0.9999304 0.01179945 0 -0.9999303 0.01181316 0 0.9999303 0.01181316 0 0.9999304 0.01179945 0 0.9978616 -0.0653631 0 0.9657682 -0.2587913 0.01786124 0.9801641 -0.1949595 0.03562623 0.1266207 -0.9769566 -0.1718233 0.08168762 -0.9850232 -0.151844 0.1005259 -0.9815852 -0.1624353 0.1333022 -0.9710704 -0.1981239 0.1398097 -0.9700084 -0.198839 0.1665888 -0.9502327 -0.2632604 0.1781539 -0.9462273 -0.2700281 0.1689129 -0.9498375 -0.263206 0.1613384 -0.9438356 -0.2883478 0.1584774 -0.9514921 -0.2637192 0.1656739 -0.9499365 -0.264902 0.1536871 -0.9498863 -0.2722063 0.08366435 -0.9849832 -0.1510249 0.03681576 -0.9961391 -0.07969611 0.3156964 -0.8949599 -0.31525 0.0758925 -0.9890338 -0.1266992 0.09030902 -0.9890502 -0.1167228 0.09195882 -0.9882346 -0.1222131 0.1040614 -0.9882776 -0.111708 0.1042147 -0.9881385 -0.1127908 0.1085363 -0.988154 -0.1084976 0.1084604 -0.9881553 -0.1085613 0.0551933 -0.993402 -0.1005307 0.05184412 -0.9934048 -0.1022711 0.05596959 -0.9917321 -0.1154767 0.06049704 -0.9917334 -0.1131592 0.06218189 -0.9905669 -0.1221098 0.06863749 -0.9903394 -0.1204861 0.07372051 -0.990325 -0.1175658 0.3150008 -0.8951902 -0.315292 0.3031511 -0.8949553 -0.3273447 0.3029253 -0.8961464 -0.3242807 0.2685762 -0.8958761 -0.3539391 0.2646027 -0.9028735 -0.3388289 0.2234329 -0.9028573 -0.3673235 0.2178662 -0.9140134 -0.3422192 0.1870901 -0.9140427 -0.3598934 0.1807202 -0.9263924 -0.3303597 0.1653391 -0.9264194 -0.3382459 0.1656664 -0.9323979 -0.3212304 0.1485127 -0.9411379 -0.3036502 0.1626116 -0.9411412 -0.2963289 0.2004036 -0.9788816 -0.04036426 0.1229859 -0.9881994 -0.09130436 0.1163905 -0.9879519 -0.1020017 0.1155827 -0.9878102 -0.1042681 0.1140146 -0.9881263 -0.1029916 0.1128087 -0.987861 -0.1067937 0.3254507 -0.8949913 -0.3050777 0.1301298 -0.9872966 -0.09116888 0.1419277 -0.9872904 -0.07151484 0.1471691 -0.9858415 -0.08036047 0.1560369 -0.985973 -0.0592432 0.1587944 -0.9849593 -0.06811535 0.1631224 -0.985042 -0.05552697 0.1635857 -0.9850555 -0.05390173 0.1806668 -0.9823505 -0.04844522 0.1849198 -0.9823605 -0.02779531 0.3248378 -0.8945524 -0.3070123 0.3394911 -0.8946377 -0.2904639 0.3372747 -0.8942033 -0.2943576 0.3675532 -0.8935614 -0.2577844 0.3720223 -0.8873499 -0.2724142 0.4140081 -0.8874448 -0.2025812 0.4265547 -0.8753476 -0.2276349 0.4533838 -0.8760014 -0.1645134 0.4592142 -0.8676163 -0.1906946 0.4825523 -0.8673176 -0.1220807 0.5126324 -0.8443588 -0.1557763 0.5305011 -0.8447672 -0.0702641 0.5684306 -0.8160074 -0.1049696 1 -5.73323e-7 0 1 -3.49462e-7 0 1 9.42132e-7 0 1 -1.26202e-6 0 1 1.81797e-7 0 1 -6.48463e-7 0 -1 -1.09554e-6 0 -1 3.50388e-6 0 -1 8.39122e-7 0 -1 -6.8365e-7 0 -1 5.85547e-7 0 -1 -3.9254e-7 0 -1 2.42987e-7 0 -1 2.77995e-6 0 -1 -1.74554e-6 0 1 0 -9.53674e-7 1 -5.70972e-7 0 1 2.61608e-7 0 1 1.24091e-7 0 1 0 3.63129e-6 1 -1.34422e-5 0 1 2.86385e-7 0 1 3.23399e-7 0 1 -4.38068e-6 0 1 -4.75204e-7 0 1 6.45255e-7 0 0 -1 0 0 -1 0 0 -1 1.28773e-7 0 -1 0 0 -1 5.61193e-7 0 -1 -6.32284e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0125879 -0.9985727 0.05190569 0 -1 0 0 -1 -1.37682e-7 0 -1 -1.32469e-7 0 0 -1 0 -1 0 0 -1 0 4.24657e-4 -0.9999996 -8.83573e-4 0.01453012 -0.9998867 -0.003959357 8.49824e-4 -0.9999992 9.84929e-4 0.002107441 -0.9999976 6.88276e-4 0.00112766 -0.9999983 -0.001550912 3.28672e-4 -0.9999991 -0.001345396 0.001506865 -0.9999988 4.81703e-4 0.001513242 -0.9999988 -4.5634e-4 0.001001119 -0.9999987 -0.00132209 -8.90258e-5 -0.9999995 -9.99111e-4 -8.80644e-4 -0.9999966 -0.00245881 -0.001185059 -0.9999992 -4.37696e-4 -0.01896917 -0.9993633 0.0302236 -0.01047354 -0.999747 0.0199092 0.0403518 -0.9991656 -0.006309807 0 -0.965925 -0.2588219 -0.001084566 -0.9654282 -0.260667 0 -0.2588133 -0.9659274 -0.0994178 -0.1376993 -0.985472 0 -0.3839479 -0.9233548 0 -0.7071048 -0.7071088 -0.07537257 -0.6288882 -0.7738338 0 -0.7950621 -0.6065281 -0.8555082 -0.5177888 -8.08227e-4 -0.930044 -0.3674151 0.004935324 -0.5210976 -0.1395797 -0.8420065 -0.9934106 -0.114463 -0.005802273 -0.6983448 -0.6385055 -0.3234586 -0.5361516 -0.5361625 -0.651975 -0.5622324 -0.8269782 0.001436889 -0.4156534 -0.9095206 -0.00210309 -0.2241848 -0.8367378 -0.499611 -0.1666053 -0.9860237 -4.54874e-5 -0.008582234 -7.61927e-4 0.9999629 -0.9632683 0.001096189 0.2685385 -0.931418 0.07040309 0.3570773 -0.009021699 0 0.9999593 -0.3860408 0 0.9224818 -0.3858871 0 0.922546 -0.7326156 0 0.6806427 -0.7326992 0 0.6805527 -0.9047622 0 0.4259172 0.05196559 0.8380253 0.5431512 -0.04922223 0.1047808 0.9932765 0.0440368 0.01433056 0.9989271 -0.00876826 0.03466314 0.9993607 0.07575649 0.07369631 0.9943993 0.04291009 0.1809524 0.9825553 0.02244848 0.2112741 0.977169 0.1938098 0.08958458 0.9769404 0.1362956 0.3929949 0.9093837 0.2251039 0.1756005 0.9583803 -0.4860789 0.8606468 0.1517054 -0.6406016 0.745324 0.1847208 -0.6443601 0.7100998 0.2838279 -0.8512659 0.5246621 0.008735656 -0.852211 0.4719033 0.2259287 -0.9464721 0.185903 0.2638761 -0.9862667 0.1449998 -0.07907634 -0.9171165 0.3192354 0.2387179 -0.02812081 0.8863071 0.4622433 0.1534845 0.6132582 0.774827 0.08889865 0.6917343 0.7166594 -0.06393831 0.9776053 0.2004991 -0.110499 0.984319 0.1375004 -0.3139958 0.9303427 0.1893913 -0.1848996 0.8444443 0.5027186 -0.2185964 0.8536748 0.4727104 -0.05302673 0.65429 0.7543823 -0.2465052 0.7562644 0.6060523 -0.5115123 0.6950021 0.5052993 -0.533782 0.6935623 0.4837853 -0.6972122 0.5021105 0.5116447 -0.7195212 0.5011889 0.4807274 -0.8460207 0.1768738 0.502956 -0.8931928 0.1596965 0.4203615 -0.7249251 0.1449081 0.6734131 -0.6220421 0.1720029 0.7638578 -0.5259694 0.4112378 0.7444728 -0.4964013 0.4054197 0.7676071 -0.3594442 0.5607957 0.7458606 -0.3342812 0.5551691 0.7616058 -0.2182407 0.640705 0.7361169 -0.3846673 0.7895703 0.4781317 -0.356019 0.7865302 0.5045997 -0.4889767 0.8536467 0.1794136 -0.3109406 0.9378232 0.1542844 0.1878756 0.4304398 0.8828502 0.1935563 0.4189966 0.8871178 0.0429567 0.377513 0.9250075 -0.01054149 0.4316546 0.9019775 -0.11785 0.3531407 0.9281181 -0.1456919 0.3630456 0.9203107 -0.2369514 0.2625685 0.9353673 -0.271561 0.2727643 0.9229595 -0.3374392 0.1049388 0.9354799 -0.3839283 0.1004215 0.917886 0 -0.1319245 -0.9912598 0.04768067 -0.2585341 -0.9648247 0 -0.3839856 -0.9233392 0 -0.7071027 -0.707111 0 -0.7070977 -0.7071158 0 -0.9659267 -0.258816 0 -0.9659269 -0.2588152 0.7078261 -0.5653922 0.4234548 0.8835263 0 0.4683819 0.6090829 -3.40088e-4 0.7931065 0.6117396 -0.1514695 0.7764225 0.7090334 0.1896268 0.6792006 0.6972194 -0.3602231 0.6197778 0.8010311 0.248392 0.5446566 0.8406444 0 0.5415875 0.1416911 0.9834622 0.1128084 0.2486662 0.9494814 0.1914427 0.4001767 0.8441253 0.356807 0.4036728 0.8415967 0.3588361 0.4334844 0.7626557 0.4800497 0.3683762 0.8097677 0.4567006 0.1908275 0.7706671 0.6079943 0.3281238 0.827949 0.4547914 0.3488553 0.7251861 0.5936373 0.5904797 0.02791082 0.8065699 0.6017563 0.1314382 0.7877902 0.5974436 0.2324609 0.7674784 0.588074 0.3036416 0.749647 0.5310172 0.5025725 0.6822329 0.7673708 0.4475898 0.4591355 0.8206967 0.2921134 0.4910467 0.6091783 0.1763791 0.7731703 0.7357367 0.1759434 0.6540148 0.7357336 0.1759365 0.6540201 0.848884 0.1761049 0.4983804 0.8520789 0.1187949 0.5097543 0.6670325 0.629123 0.3990889 0.5681111 0.7494771 0.3399028 0.4655058 0.8441111 0.2660465 0.4080153 0.879267 0.2457907 0.140127 0.9867848 0.08136492 0.1412274 0.9865976 0.08173102 0.7290983 0.540066 0.4204101 0.6290574 0.539996 0.559188 0.6290568 0.5399981 0.5591866 0.5091307 0.5404155 0.6698784 0.3493871 0.8252883 0.4436531 0.3585934 0.7338229 0.5769877 0.2990422 0.8626362 0.4079616 0.2776805 0.8460944 0.454992 0.2534312 0.8901382 0.3787172 -0.6219282 0.703048 0.3448609 -0.1335524 0.9910418 -1.50641e-4 -0.2478286 0.959281 0.1355032 -0.3538882 0.9352371 0.009730517 -0.5249781 0.8510747 -0.008363783 -0.5226581 0.8521751 0.0250225 -0.09399551 0.9936917 0.0611698 -0.9908174 0.1351507 -0.003910839 -0.9852004 -0.1677564 -0.03518605 -0.6630911 -0.7448828 -0.07389134 -0.871219 -0.482798 -0.08879005 -0.3001555 -0.9470773 -0.1138033 -0.4552913 -0.8839836 -0.1062204 -0.288048 0.9563385 0.04944765 -0.1943228 0.9804181 0.03192234 -0.1935224 0.9639598 -0.182567 -0.3332388 0.9357081 -0.1157689 -0.1947062 0.949782 -0.2449564 -0.1937301 0.8888647 -0.4151968 -0.2125754 0.881645 -0.4213239 -0.1950837 0.8276793 -0.5262028 -0.1935224 0.7475797 -0.6353533 -0.1935225 0.7475808 -0.6353518 -0.194889 0.624788 -0.7560809 -0.2614769 0.5511556 -0.7923746 -0.1944469 0.5221225 -0.8304087 -0.1941182 0.3608691 -0.9121906 -0.2433875 0.3317894 -0.9114156 -0.1950183 0.2401857 -0.9509357 -0.1935222 0.08866882 -0.9770809 -0.1935237 0.088669 -0.9770807 -0.1950173 -0.06516146 -0.9786329 -0.2435014 -0.1622954 -0.9562256 -0.194121 -0.19085 -0.9622336 -0.1935225 -0.4060869 -0.8931084 -0.2964351 -0.354584 -0.88679 -0.1948882 -0.4785523 -0.8561579 -0.1935223 -0.6209938 -0.7595497 -0.193521 -0.6209957 -0.7595486 -0.1950807 -0.7194849 -0.6665471 -0.2127515 -0.7913652 -0.5731301 -0.1095479 -0.9868903 -0.1185197 -0.1942036 -0.9711319 -0.1385209 -0.1946922 -0.9358849 -0.2936227 -0.267166 -0.8990711 -0.3468335 -0.1947049 -0.8902056 -0.4118544 -0.193732 -0.7996532 -0.5683509 -0.5539289 -0.823648 -0.1215187 -0.5523502 -0.7777476 -0.3000304 -0.5523512 -0.7777464 -0.3000311 -0.5523514 -0.6751475 -0.4889622 -0.5523509 -0.6751486 -0.4889612 -0.5523525 -0.5276411 -0.6453694 -0.5523509 -0.5276421 -0.6453699 -0.552349 -0.3450418 -0.7588524 -0.5523523 -0.345041 -0.7588502 -0.5523499 -0.1394894 -0.8218592 -0.5523506 -0.1394889 -0.8218587 -0.5523508 0.07533931 -0.8302003 -0.5523501 0.07534098 -0.8302007 -0.5523506 0.2851593 -0.7833217 -0.5523512 0.2851582 -0.7833218 -0.552351 0.4760093 -0.6843417 -0.5523499 0.4760109 -0.6843415 -0.5523512 0.6351992 -0.5398427 -0.5523518 0.6351983 -0.5398433 -0.5523506 0.7521402 -0.3594358 -0.5523512 0.7521395 -0.3594362 -0.5523506 0.8190519 -0.1551223 -0.552351 0.8190516 -0.1551223 -0.554618 0.8320396 0.0104441 -0.62816 0.7754543 -0.0639199 -0.8285566 -0.5576899 -0.0497592 -0.8293091 -0.5213425 -0.2011182 -0.8293088 -0.521343 -0.2011185 -0.8293095 -0.4525667 -0.3277639 -0.8293079 -0.4525699 -0.3277636 -0.8293084 -0.3536922 -0.4326078 -0.8293079 -0.3536928 -0.4326081 -0.8293079 -0.2312904 -0.5086779 -0.8293089 -0.231289 -0.508677 -0.8293079 -0.09350383 -0.5509133 -0.8293085 -0.09350258 -0.5509126 -0.829308 0.05050146 -0.5565051 -0.8293085 0.05050331 -0.5565041 -0.829308 0.1911492 -0.5250813 -0.8293084 0.1911479 -0.525081 -0.829308 0.319083 -0.4587312 -0.8293084 0.3190811 -0.4587318 -0.8293089 0.4257891 -0.3618705 -0.8293077 0.4257921 -0.3618702 -0.8293092 0.5041768 -0.2409399 -0.8293086 0.5041779 -0.2409396 -0.8293095 0.5490297 -0.1039824 -0.8293076 0.5490325 -0.1039828 -0.9805186 -0.1950195 -0.02347242 -0.9804697 -0.1834912 -0.07078444 -0.9804698 -0.1834899 -0.07078474 -0.9804697 -0.1592852 -0.1153581 -0.98047 -0.1592836 -0.1153579 -0.9804699 -0.1244835 -0.1522586 -0.9804699 -0.1244834 -0.1522585 -0.98047 -0.08140361 -0.1790316 -0.98047 -0.08140289 -0.1790315 -0.98047 -0.03290855 -0.1938962 -0.98047 -0.03290843 -0.1938964 -0.98047 0.0177741 -0.1958644 -0.9804699 0.01777493 -0.1958643 -0.9804699 0.06727576 -0.1848047 -0.98047 0.06727617 -0.1848047 -0.9804699 0.1123023 -0.1614528 -0.98047 0.1123014 -0.161453 -0.98047 0.1498585 -0.127362 -0.9804699 0.1498593 -0.127362 -0.9804691 0.1774529 -0.08479964 -0.9804702 0.1774469 -0.08479976 -0.980469 0.193239 -0.03659713 -0.9804704 0.1932321 -0.03659713 -0.9781512 0.1900082 -0.08436465 -0.8194897 0.5564258 0.1372118 -0.8845775 0.4405636 -0.1530569 -0.7816936 0.6236091 0.008176147 3.85785e-4 -1 -2.53519e-5 -0.001598238 -0.9999973 0.00168991 -7.00968e-4 -0.999999 0.001297473 4.68742e-4 -0.9999999 -5.55047e-5 2.45034e-5 -1 -9.828e-7 -4.93584e-6 -1 0 -4.88798e-4 -1 -5.86878e-5 -3.93055e-4 -1 -3.51322e-5 5.24281e-4 -0.9999998 5.52064e-4 -6.59006e-4 -0.9999996 6.35074e-4 8.5568e-4 -0.9999985 0.001500844 0.2212619 -0.9752137 0.001318275 0.2224178 -0.9747733 0.01864117 0.212029 -0.9771802 0.01275122 0.2197656 -0.97486 0.03675597 0.2080155 -0.9772076 0.04236686 0.2141064 -0.9753857 0.05273729 0.2124903 -0.9756941 0.05356329 0.2078208 -0.9765175 0.05678164 0.2137943 -0.9752103 0.05707174 0.9778568 -0.04034352 0.2053499 0.9717622 -0.04973834 0.2306611 0.9656359 -0.1013113 0.2393393 0.9646923 -0.02603387 0.2620896 0.9636231 -0.04729741 0.2630467 0.988135 -0.004923462 0.1535089 0.9956016 0 0.09368854 0.9943048 -0.01150149 0.1059516 0.9727023 -0.1763036 0.1508881 0.9790863 -0.1327722 0.1541478 0.9806678 -0.02144116 0.1945017 0.28092 -0.957975 0.05803519 0.2047766 -0.9743571 0.09324628 0.06465905 -0.9978128 0.01374524 0.0620771 -0.996929 0.04774129 0.03937113 -0.9992032 0.006562173 0.9771629 -0.05305862 0.2057605 0.9769475 -0.03562849 0.2104859 0.9726399 -0.04546022 0.227827 0.970417 -0.04730683 0.236755 0.9772728 -0.07730174 0.197389 0.9744599 -0.1454604 0.1710827 0.9760478 -0.1560092 0.1516312 0.9549043 -0.2853396 0.08209294 0.9554821 -0.2500937 0.1565482 0.9406784 -0.319005 0.1155858 0.9949814 -0.00741589 0.09978538 0.9950337 -0.003989934 0.09945935 0.9946579 -0.02431774 0.100321 0.9845122 -0.1571605 0.07769495 0.995719 -0.08491826 -0.03650856 0.9913565 -0.1280271 0.02866077 0.832712 -0.4462349 0.3278189 0.9645579 -0.2633533 0.01652866 0.9430961 -0.318301 0.09619933 0.9452289 -0.3187458 0.07030886 0.936953 -0.3203371 0.1396539 0.5669476 -0.8219425 0.05459892 0.6940728 -0.7061413 0.140098 0.723159 -0.6813746 0.1130034 0.8438513 -0.5295158 0.08676367 0.386616 -0.9214646 0.03783112 0.3060044 -0.9511252 -0.04150146 0.3575686 -0.9216164 0.1508908 0.1961396 -0.9793478 -0.04906356 0.1976494 -0.9768857 -0.08141946 0.1854749 -0.9790806 0.08366781 0.02583974 -0.9996045 -0.01109552 0.07597148 -0.9967852 0.02544939 0.04223966 -0.9991003 0.003804445 0.8705338 -0.480354 0.1069153 0.7637262 -0.6398914 0.08521479 0.7104265 -0.7037102 -0.009286582 0.631537 -0.7745779 0.03449833 0.3245505 -0.9388561 0.1149625 0.9959675 0 0.08971619 0.9941282 -0.01478493 0.107195 0.9950083 -5.97174e-4 0.09979146 0.03815817 0.01531147 0.9991545 0.03880244 0.0216217 0.999013 0.03988802 0.03356099 0.9986405 0.04132175 0.05969649 0.997361 0.04260808 0.1120812 0.9927852 0.04277789 0.1666768 0.9850832 0.0316056 -0.03841763 0.9987619 -0.03208291 0.06196105 0.9975628 -0.03709858 0 0.9993117 -0.6285842 0.02666682 0.7772844 -0.6154483 0.1733538 0.768877 -0.6138935 0.1295474 0.7786863 -0.6045407 0.2659627 0.7508625 -0.3990485 0.7680347 0.5008824 -0.3207008 0.8173056 0.4787092 -0.3394736 0.776139 0.5313813 -0.3519579 0.7280516 0.5882743 -0.2966049 0.8608188 0.4135417 -0.3019128 0.8647144 0.4013949 -0.4231792 0.759132 0.4946088 -0.2801464 0.8528505 0.4406406 -0.2539819 0.853757 0.4545243 -0.2673529 0.8491984 0.4553951 -0.2683435 0.9380487 0.219218 -0.2124882 0.9577502 0.1938131 -0.009214937 0.9958699 -0.09032338 -0.6944714 0.4196663 0.5844568 -0.5875117 0.6106295 0.5310006 -0.4414087 0.8039854 0.3984546 -0.5316076 0.7217036 0.4433254 -0.4257586 0.8217212 0.3788194 -0.5356154 0.4945662 0.6844856 -0.5291439 0.5327931 0.6604077 -0.615604 0.5339363 0.5796067 -0.7297807 0.1736763 0.6612539 -0.7282795 0.1416544 0.6704797 -0.04922735 0.9921289 0.1151397 -0.6635922 0.1438711 0.7341298 -0.6854027 0.1969165 0.7010329 -0.1097208 -0.9829202 0.1477477 -0.5651621 0.4959222 0.6592822 -0.5537047 0.1295562 0.8225731 -0.470462 0.3499713 0.8100529 -0.5041275 -0.1333867 0.8532664 -0.4664364 0.2585793 0.8459161 -0.4834054 0.09138971 0.8706132 -0.06191813 0.9979985 -0.01285547 -0.4434737 0.4595997 0.7694799 -0.5169283 0.1344117 0.8454105 -0.4086343 0.6180166 0.6716201 -0.4968131 0.361007 0.789209 -0.3471313 0.7653677 0.5419522 -0.4635398 0.543364 0.6999189 -0.2683026 0.8811404 0.3893654 -0.4074411 0.7017241 0.5844443 -0.1832216 0.9562922 0.2278929 -0.3410625 0.8269311 0.4470584 -0.2521109 0.9174604 0.3077444 -0.628314 0.3443571 0.6975957 -0.5733512 0.5044708 0.6455832 -0.5633615 0.5291254 0.6345473 -0.5022962 0.6481053 0.5724143 -0.4783874 0.6870489 0.5469089 -0.3817663 0.8075926 0.4494984 -0.3918859 0.7961484 0.4610566 -0.5679009 -0.008375406 0.8230543 -0.5496934 -0.240613 0.7999642 -0.5558546 0.3535042 0.75237 -0.5861111 0.152309 0.7957862 -0.5191301 0.5364735 0.6653572 -0.5733666 0.3504123 0.7405823 -0.4607303 0.6953919 0.5515049 -0.5369899 0.5319576 0.6547236 -0.3856072 0.8218068 0.4194528 -0.48062 0.686827 0.5452278 -0.2996173 0.9125313 0.2784172 -0.409452 0.8095554 0.420677 -0.4693409 -0.2409688 0.8495019 -0.6690621 -0.1944472 0.7173188 -0.6992375 -0.07192099 0.7112625 -0.5825821 -0.5533816 0.5952873 -0.633946 -0.3946889 0.6650814 -0.6687229 -0.2477438 0.7010226 -0.2893421 -0.9097127 0.2978322 -0.3436904 -0.8715475 0.3496884 -0.3947847 -0.8296837 0.3946773 -0.4335363 -0.7832295 0.4456434 -0.5609177 -0.5903484 0.5803965 -0.4941897 -0.8680411 0.04776287 -0.170275 -0.9696595 0.175405 -0.06913352 -0.996752 0.04130274 -0.1346431 -0.9806339 0.142227 -0.1219935 -0.9766733 0.1767116 -0.1158092 -0.9807652 0.1571241 -0.2550358 -0.8945026 0.367181 -0.3038927 -0.8303991 0.4669975 -0.319967 -0.8142101 0.4844409 -0.4396713 -0.5531598 0.707604 -0.4438425 -0.5443258 0.711838 -0.5328996 -0.1942706 0.8235758 -0.5713412 -0.03079366 0.8201348 0.1041645 0.9547564 0.27855 0.05552017 0.992168 0.1118945 0.1248673 0.9579656 0.2582831 0.06742262 0.9829611 0.1710022 0.1728685 0.8819683 0.4384616 0.2121372 0.8201782 0.5313243 0.2360612 0.7653652 0.5987414 0.2930907 0.6012173 0.7433947 0.2890393 0.617334 0.7316797 0.3256345 0.4583753 0.8269549 0.3325442 0.4238073 0.8424974 0.3652682 0.09106069 0.9264379 0.3631115 0.1685331 0.9163769 0.3544135 0.2575075 0.8989333 0.3437287 0.3489307 0.8718361 0.1409105 -0.6562915 0.7412326 -0.186805 -0.2387492 0.9529443 -0.1867726 -0.2387509 0.9529502 -0.07637202 -0.9485578 0.307255 -0.1073065 -0.8449455 0.5239776 -0.1595298 -0.6832932 0.712503 -0.1552707 -0.6779505 0.7185223 -0.1687223 -0.4801681 0.8607971 0.1994822 -0.2338721 0.9515833 0.199468 -0.2339017 0.951579 0.1469645 -0.6977715 0.7010823 0.325447 -0.5453973 0.7724158 0.4274497 0.7697871 0.4740408 0.2533993 0.8901495 0.3787118 0.1908335 0.7706686 0.6079906 0.3281229 0.8279529 0.4547851 0.3489231 0.7251689 0.5936185 0.6056532 0.027493 0.7952536 0.6139699 0.129496 0.7786346 0.6083032 0.2294998 0.7598007 0.5983833 0.3000574 0.7429018 0.5413348 0.4978321 0.6775839 0.6193444 0.1734199 0.7657272 0.7307546 0.1736561 0.6601828 0.7291272 0.1339768 0.6711362 0.5808774 0.6220791 0.5249752 0.277682 0.8460934 0.454993 0.3029145 0.8654145 0.3991249 0.3860762 0.7573929 0.5265941 0.3453732 0.8343784 0.4295699 0.522276 0.5324041 0.6661636 0.6365979 0.5330228 0.5573419 0.6664834 0.4128698 0.6207564 0.5071406 0.7301553 0.4579102 0.4436207 0.8089252 0.385799 0.3756548 0.8630263 0.337741 0.2503517 0.9484459 0.1943568 0.1473471 0.9824134 0.114686 0.2674262 0.9161641 0.2985408 0.5559331 0.1593636 0.8158074 0.5537053 0.02912831 0.832203 0.5237523 0.03331238 0.8512191 0.6244822 0.0223152 0.7807202 0.6379685 0.4074022 0.6534675 0.6772247 0.2787061 0.6809476 0.7181876 0.107768 0.6874538 0.04925167 0.9921291 0.1151274 0.0593121 0.9981381 0.01422762 0.1959435 0.955357 0.2211316 0.3273466 0.8280659 0.4551385 0.2813766 0.8802624 0.3820541 0.3959023 0.7027001 0.5911632 0.3603181 0.7645096 0.5345053 0.4485805 0.5447526 0.7085339 0.4216736 0.6174078 0.6640776 0.4855633 0.3621861 0.7956441 0.4624748 0.4590364 0.758553 0.5010205 0.1662533 0.8493165 0.474643 0.349893 0.8076441 0.5038282 -0.1015422 0.8578149 0.4674135 0.2585107 0.8453976 0.4840324 0.09141325 0.8702622 0.3435897 0.8302111 0.4389712 0.4648715 0.7048317 0.5358234 0.4592941 0.7127116 0.5301803 0.5450658 0.5819633 0.6035082 0.6223049 0.3972648 0.6744756 0.650012 0.2998357 0.6982714 0.6381871 0.3353331 0.6930144 0.4806862 0.6867511 0.5452648 0.6219944 0.4582739 0.6349079 0.5945338 0.4547249 0.6631402 0.4533361 0.7178538 0.5283677 0.4588039 0.7191166 0.5218912 0.4006273 0.8028553 0.4414991 0.5610387 -0.4002342 0.7246021 0.6380304 0.1468735 0.7558741 0.5959103 0.3962898 0.6984594 0.603562 0.3474364 0.7176356 0.5565601 0.529852 0.6399201 0.3072902 0.9114363 0.2735995 0.4052281 0.8063396 0.4308211 0.3938543 0.8206245 0.4140701 0.4728028 0.6874935 0.5511899 0.4693651 0.6940802 0.5458471 0.5287502 0.5325894 0.6608872 0.5278972 0.5351203 0.6595233 0.5647925 0.3512933 0.746728 0.5646118 0.3521981 0.7464383 0.5774624 0.1531348 0.801927 0.5606999 -0.1749607 0.8093234 0.5900434 0.02538585 0.8069725 0.1110156 -0.9807059 0.1609085 0.03920984 -0.9983743 0.04136866 0.141456 -0.9804515 0.1367667 0.1305724 -0.9838665 0.1223021 0.3448004 -0.8708918 0.350229 0.2904031 -0.9091405 0.2985459 0.2125017 -0.9524065 0.2185515 0.5611692 -0.1947467 0.8044643 0.668975 -0.1944668 0.7173947 0.7152495 0.02109885 0.6985507 0.7004837 -0.06870585 0.7103534 0.6698415 -0.2438806 0.7013093 0.5745021 -0.5539312 0.6025842 0.6507015 -0.4118768 0.6379225 0.561177 -0.5905374 0.5799536 0.1239386 -0.9777551 0.1692166 0.3155884 -0.8309103 0.458249 0.3950423 -0.8297047 0.3943754 0.4337648 -0.7832872 0.4453193 0.4693437 -0.2409836 0.849496 0.544603 -0.09289109 0.833534 0.4443247 -0.5442931 0.7115621 0.4401586 -0.5531385 0.7073177 0.3199337 -0.814621 0.4837716 0.2514503 -0.8773717 0.4086464 -0.6235381 0.026847 0.7813319 -0.6118406 0.1609054 0.7744422 -0.610623 0.1300944 0.7811627 -0.6002342 0.2673055 0.7538346 -0.202545 0.7802188 0.5918058 -0.2872712 0.8223017 0.4912181 -0.256232 0.8863865 0.3855701 -0.2367591 0.9058334 0.3512992 -0.4213059 0.7277051 0.5412455 -0.3609084 0.8261888 0.4326168 -0.2641356 0.74101 0.6173627 -0.2747502 0.7737013 0.5708753 -0.2470179 0.9396267 0.2368202 -0.2790681 0.9305247 0.23716 -0.4444129 0.7914138 0.4197158 -0.4603065 0.778011 0.4275708 -0.5869953 0.5741382 0.5707907 -0.7004643 0.3748463 0.607322 -0.5365031 0.4941666 0.6840788 -0.5359261 0.4976582 0.6819967 -0.6058451 0.4990199 0.6196216 -0.7118384 0.1612659 0.6835784 -0.7074482 0.1232254 0.6959401 0.4528411 0.7296133 0.5124445 0.637966 0.4074167 0.6534609 0.4840536 0.0912674 0.8702657 0.1455817 0.9515647 0.2707963 0.4610922 0.2993749 0.8353254 0.5135794 -0.04361432 0.8569329 0.5237488 0.03341257 0.8512173 0.6244813 0.02235198 0.7807199 0.7181677 0.1077638 0.6874751 0.6772413 0.2786303 0.6809621 0.2941604 0.8675686 0.4009919 0.1470625 0.9738238 0.1733199 0.3410131 0.8269251 0.4471073 0.06767344 0.9975718 0.01646161 0.3931712 0.7028487 0.5928071 0.4576216 0.5440005 0.7033107 0.4261097 0.6203562 0.6584746 0.4811856 0.3626554 0.7980862 0.5034736 0.1659502 0.8479239 0.5559287 0.1594127 0.8158008 0.5537962 0.02899247 0.8321473 0.3424466 0.8300003 0.4402612 0.451751 0.719992 0.5268136 0.4618072 0.7092236 0.5326688 0.4592188 0.7127961 0.5301319 0.6380228 0.1469106 0.7558732 0.5958962 0.3963034 0.6984636 0.6222885 0.3972935 0.6744739 0.6220358 0.458227 0.6349013 0.6035964 0.3472857 0.7176796 0.5565078 0.5299956 0.6398468 0.4566919 0.7248796 0.5157346 0.4616914 0.6883616 0.5594635 0.4011403 0.8192776 0.4097203 0.2846198 0.9144017 0.2878565 0.299661 0.912516 0.2784207 0.4728018 0.6874936 0.5511906 0.4693928 0.6940361 0.5458793 0.5287448 0.5326623 0.6608328 0.5278872 0.5352025 0.6594645 0.564828 0.3511322 0.7467768 0.5646315 0.3522058 0.7464197 0.5774642 0.1531264 0.8019274 0.5607051 -0.1749172 0.8093293 0.5900417 0.02519577 0.8069796 0.2562026 0.8296701 0.4959919 0.4214566 0.7720545 0.4757165 0.1366808 0.9743089 0.1789987 0.2713519 0.8881115 0.3709802 0.2747194 0.868496 0.4126064 0.1174373 0.748073 0.6531427 0.4053003 0.7509753 0.5213137 0.4876724 0.5471917 0.6802623 0.4706367 0.6483839 0.5984141 0.6222803 0.02686357 0.7823335 0.5939493 0.1326733 0.7934873 0.5936673 0.2334898 0.7700921 0.5874146 0.303847 0.7500807 0.5729097 0.379765 0.7263285 0.6014334 0.2213001 0.7676615 0.7148227 0.221534 0.6632883 0.7064417 0.1189596 0.6977026 0.2724454 0.9237561 0.2691624 0.2939244 0.9201978 0.2585433 0.4028444 0.8361913 0.3721567 0.326779 0.8938954 0.306866 0.4827685 0.7481315 0.4552295 0.5675203 0.6481877 0.507714 0.5879746 0.5820966 0.561649 0.6658306 0.3503702 0.6587188 -0.6208605 0.02691239 0.7834591 -0.5911369 0.2701682 0.759978 -0.5746412 0.3677324 0.7311365 -0.525082 0.5265719 0.6685888 -0.4583525 0.6371461 0.6196433 -0.4257946 0.7116283 0.5588238 -0.2025229 0.7802652 0.5917522 -0.3853586 0.7750499 0.5007957 -0.3240949 0.8498224 0.4156497 -0.3202709 0.834913 0.4476012 -0.2561378 0.8840311 0.3910021 -0.2631145 0.8679527 0.4212232 -0.2708867 0.881379 0.3870294 -0.2733796 0.89357 0.3560848 -0.4245164 0.7537639 0.5016235 -0.3487894 0.8773137 0.3296465 -0.3378773 0.884966 0.320428 -0.3786292 0.8965784 0.2297548 -0.2542431 0.9380807 0.2352977 -0.6930697 0.2177423 0.6871991 -0.5933808 0.217025 0.7751126 -0.6127879 0.1297265 0.7795269 -0.7349596 0.1305007 0.6654352 -0.6622036 0.3572283 0.6586915 -0.5602048 0.638561 0.5276463 -0.5951648 0.6012427 0.533185 -0.4837585 0.7449169 0.4594309 0.03032284 -0.9825617 -0.1834481 0 -0.9928764 -0.1191495 1.44332e-4 -0.9928658 -0.1192373 0 -0.8150951 -0.5793272 0.03011167 -0.8501799 -0.5256306 0 -0.9075756 -0.4198888 0 -0.9541429 -0.2993515 0 -0.7335783 -0.679605 0.004795253 -0.6329521 -0.7741761 0.02496784 -0.6033272 -0.7971029 0 -0.1945508 -0.9808925 0.03285843 -0.2750002 -0.9608826 0 -0.3712723 -0.9285241 0 -0.4879079 -0.8728952 0 -0.0664376 -0.9977906 0.01691937 0.09036409 -0.9957651 0.0168662 0.09027701 -0.9957739 0 0.5322818 -0.8465673 0.03285169 0.443324 -0.8957593 0 0.3678677 -0.9298782 0 0.2448878 -0.9695515 0 0.637004 -0.7708606 0.03174406 0.7616008 -0.6472686 0.006026148 0.7370597 -0.6758008 0 0.8438897 -0.5365168 0 0.9060302 -0.423213 0.03009241 0.9308492 -0.3641625 0 0.9981107 0.06144243 0.03034144 0.9995326 -0.003750741 0 0.9924332 -0.1227862 0 0.9683139 -0.2497364 0.004826605 0 0.9999884 0.004824101 0 0.9999884 -0.2501845 0 0.9681982 -0.432537 0 0.9016162 -0.3783625 0.0116052 0.9255847 -0.3063241 0.04714357 0.9507592 -0.2520288 0.09754884 0.9627906 -0.07110804 0.006021916 0.9974505 -0.2475762 0.07129961 0.9662414 -0.2252648 0.1334808 0.9651107 -0.2298949 0.1258745 0.965041 -0.2409184 -9.86486e-4 0.9705449 -0.2112538 -0.006311297 0.9774109 -0.2122875 -0.009664297 0.9771595 -0.2145327 0.001555621 0.9767156 -0.2078183 -0.001501739 0.9781664 -0.3188695 -0.1208043 0.9400684 -0.3230099 5.92081e-6 0.9463956 -0.2629232 -0.01213353 0.9647405 -0.3422617 -0.09847712 0.9344298 -0.3337433 -0.0548076 0.9410694 -0.4324799 -9.31411e-4 0.9016432 -0.4542663 0 0.8908661 -0.3302921 0.1168668 0.9366158 -0.4241012 0.004623472 0.905603 -0.4206209 0.01149654 0.9071637 -0.4196304 0.01477634 0.9075748 -0.419126 0.01078069 0.9078641 -0.1476271 0.0943368 0.9845339 -0.1268224 0.05202794 0.9905601 -0.2385194 0.2218103 0.9454674 -0.2192524 0.1457512 0.9647202 -0.3741315 -0.01247131 0.9272919 -0.4131545 0.004339814 0.9106506 -0.2171351 0.06832867 0.9737473 -0.2143521 0.02894973 0.9763273 -0.2395997 0.1915373 0.9517906 -0.2441201 2.96521e-4 0.969745 -0.2441133 0 0.9697467 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.9899262 -3.044e-4 0.141584 0.9932971 4.50611e-4 0.1155882 0.9932766 0 0.1157656 0.9692817 -0.2021602 0.1400874 0.9689925 -0.1896511 0.1583855 0.9601813 -0.2158923 0.1773204 0.9661735 -0.1948508 0.1689432 0.9690264 -0.1790611 0.1700736 0.9698648 -0.1532562 0.1894067 0.965614 -0.2466932 0.0820496 0.9982752 0.04909294 -0.03219747 0.9453012 -0.145923 -0.2917397 0.9911609 -0.0800938 -0.1057599 0.9623425 -0.2626745 0.06999468 0.9659059 -0.193355 0.1721615 0.9408269 -0.2377786 -0.2414669 0.9567801 -0.1434192 -0.2529875 0.9662469 -0.0631535 -0.2497572 0.9287407 -0.2716699 -0.2522624 0.9856497 -0.1106879 0.1274476 0.9358744 -0.3522005 0.009702861 0.9396994 -0.3124181 0.1391411 0.9305842 -0.3631733 0.04602581 0.955657 -1.80708e-4 -0.294482 0.9555371 -0.001102209 -0.2948691 0.9555879 0 -0.2947065 0.9994802 0 -0.03223931 0.9994803 0 -0.03223723 0.891674 -0.4039441 0.20432 0.886856 -0.4095815 0.2138444 0.9857476 -0.1147312 0.1230387 0.952886 -0.2293254 0.1985404 0.958601 -0.2118733 0.1902471 0.29172 -0.09128278 0.9521381 0.3503485 0 0.9366194 0.2768426 -0.1246336 0.9527983 0.2839682 -0.1110341 0.9523831 0.2886991 -0.09924089 0.9522627 0.293847 -0.08431529 0.9521265 0.2953119 -0.0795086 0.9520869 0.300341 -0.06115555 0.9518694 0.3032658 -0.04300785 0.9519351 0.306433 -0.02072447 0.9516666 0.3068467 -1.79951e-4 0.951759 0.2861598 0.0304858 0.9576969 0.2900249 0.02870577 0.9565885 0.3622447 0 0.932083 -0.002397358 0 0.9999972 -0.003695011 0.02249526 0.9997402 -0.01494222 0.05124157 0.9985745 -0.01015013 0.0460447 0.9988879 0.01039129 0.03167933 0.9994441 0.07242524 0.00197947 0.997372 0.2070156 -0.002067446 0.9783356 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.002397358 0 0.9999972 0.09322065 0.008155941 0.9956121 0.004650294 0.03941673 0.9992122 0.01127904 0.04685217 0.9988381 -0.005263686 0.03543472 0.9993581 -0.3622534 0 0.9320797 -0.2901266 0.02871519 0.9565574 -0.2672884 0.0390293 0.9628259 -0.2861779 0.02889859 0.9577407 -0.1704955 -0.00908482 0.9853166 -0.04625606 0.01189351 0.9988589 -0.2211866 0.001011908 0.975231 -0.2427403 -9.10519e-4 0.9700909 -0.2648268 -0.01223468 0.9642185 -0.2099795 -0.001426696 0.9777048 -0.2133578 -0.006184875 0.9769546 -0.2144728 -0.009670615 0.9766821 -0.2148171 -0.007681787 0.9766241 -0.3484722 -0.103805 0.9315534 -0.3286884 0 0.9444385 -0.3035033 -0.1019735 0.947358 -0.3068459 -1.64096e-4 0.9517592 -0.2629942 0 0.9647975 -0.4292989 0 0.9031625 -0.3397096 0.02573996 0.9401781 -0.09215694 0.006020128 0.9957264 -0.2603952 0.06879448 0.9630481 -0.2392281 0.126473 0.9626913 -0.2575164 0.09709924 0.9613829 -0.2411907 -9.1756e-4 0.9704774 -0.2194907 0.00101149 0.9756141 -0.2117677 -0.00618118 0.9773005 -0.2127912 -0.009635746 0.9770502 -0.2131345 -0.007696032 0.9769926 -0.2083014 -0.00138992 0.9780638 -0.3214699 -0.1235843 0.9388206 -0.3257569 -1.40028e-4 0.9454536 -0.2631655 -0.01222407 0.9646732 -0.3426812 -0.09908342 0.9342121 -0.3353583 -0.0608502 0.9401234 -0.4331784 -0.002210795 0.9013054 -0.4566029 0 0.8896707 0.4581966 0 0.8888508 0.3274778 -0.00838387 0.9448217 0.210328 7.3955e-5 0.9776309 0.2166407 -0.007098793 0.9762256 0.2036428 -0.002435445 0.9790422 0.2629907 -0.05303227 0.9633398 0.2239109 0.01142632 0.9745426 0.2676075 -0.01373022 0.9634302 0.5839165 -0.3937096 0.7099538 0.2977431 -0.06669825 0.9523133 0.3808667 -0.2015327 0.9023997 0.2411959 0.1199776 0.9630317 0.2591255 0 0.9658436 0.2579089 0.03701329 0.9654601 0.246059 0.09955137 0.964129 0.2346785 0.1305996 0.9632601 0.2605397 0.09672582 0.9606057 0.3178082 0.03939312 0.9473364 0.4180082 0 0.9084433 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.4950678 -0.1984619 -0.8458846 -0.5391275 -0.1532548 -0.8281635 -0.5770028 -0.03486001 -0.8159979 -0.4344399 -0.5883243 -0.6820092 -0.5159223 -0.4488807 -0.7296097 -0.5449656 -0.3302366 -0.7706857 -0.4113815 -0.6024662 -0.6839589 -0.3840062 -0.7830594 -0.4892416 -0.3830476 -0.7482224 -0.5416991 -0.6014198 0.02605253 -0.7985083 -0.6920153 0.1159595 -0.7125085 -0.753974 0.2029403 -0.6247707 -0.8339251 0.3251975 -0.4458875 -0.8401352 0.3377189 -0.4244043 -0.8531662 0.3793672 -0.3580337 -0.8657251 0.4635787 -0.1887192 -0.8597687 0.5055015 -0.07256823 -0.8490406 0.5281863 -0.01222026 -0.7494202 0.5959815 0.2884017 -0.7865821 0.5793601 0.2136135 -0.9076745 0.1289016 0.3993889 -0.9076749 0.1289032 0.3993873 -0.9937462 0.109537 0.02168118 -0.9937467 0.1095319 0.02168983 -0.929487 0.073435 -0.3614712 -0.9294921 0.07343149 -0.3614586 -0.7221345 0.02584904 -0.6912696 -0.7221425 0.02584981 -0.6912612 -0.852679 0.377788 0.360853 -0.8526468 0.377826 0.3608891 -0.9470034 0.321034 -0.0110408 -0.9470002 0.321043 -0.01105296 -0.8981549 0.2152303 -0.3833977 -0.8981525 0.2152331 -0.3834018 -0.7110921 0.07576555 -0.6990048 -0.7111088 0.07575231 -0.6989892 -0.649312 0.6027793 0.4637359 -0.7601983 0.3850705 0.5232775 -0.7572677 0.3774041 0.5330215 -0.8133727 0.1313856 0.5667123 -0.8123882 0.1282342 0.5688422 -0.8190929 -4.29114e-6 0.5736611 -0.8191524 0 0.5735761 -0.8191411 -5.2938e-6 0.5735923 -0.8191505 0 0.5735786 -0.8178227 0 0.5754704 -0.7900024 0.2643734 0.5531754 -0.7900024 0.2643706 0.5531767 -0.6195289 0.6541994 0.4338284 -0.7968763 0.4075978 -0.4459286 -0.1169844 0.9897491 0.08192306 -0.6064063 0.4157679 -0.6777968 -0.3222106 0.9193881 0.2256239 -0.4632166 0.8247738 0.3243126 -0.8192076 0 0.5734972 -0.8191449 0 0.5735866 -0.8189222 0 0.5739045 0 1 0 0 1 0 -5.21097e-6 0 1 -0.258819 -0.9659259 0 -0.7071033 -0.7071103 0 -0.7071086 -0.7071051 0 -0.9659253 -0.2588207 0 -0.9659272 -0.2588139 0 1.42366e-5 0 -1 0 1 0 0 1 0 0 1 0 -0.258535 0 0.966002 -0.7064781 0 0.707735 -0.7064676 0 0.7077455 0.6753323 0 -0.7375136 0.2446533 0 -0.9696107 0.2446337 0 -0.9696156 0.4932516 0 0.8698868 0 1 0 0 1 0 0 1 0 0.7064685 0 0.7077445 0.7064791 0 0.7077339 0.2585349 0 0.966002 -0.2446337 0 -0.9696156 -0.2446533 0 -0.9696107 -0.6753323 0 -0.7375136 -0.4932429 0 0.8698917 -0.9746794 0 0.2236071 -0.9746811 0 0.2235997 -0.99373 0 0.111807 -0.9937309 0 0.1117994 0.9659259 0 0.2588188 0.965928 0 0.2588114 0.7070941 0 0.7071195 0.7071089 0 0.7071048 0.2588148 0 0.965927 0.2588423 0 0.9659197 -0.2588421 0 0.9659197 -0.2588145 0 0.9659271 -0.7071093 0 0.7071043 -0.7070946 0 0.707119 -0.9659278 0 0.2588116 -0.9659259 0 0.258819 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.9746804 0 0.223603 0.9746787 0 0.2236104 -0.6947141 -0.6947814 -0.1861482 -0.6947744 -0.6947166 -0.186165 -0.5086089 -0.6947239 -0.5086019 -0.50859 -0.6947413 -0.5085968 -0.1861614 -0.6947398 -0.6947522 -0.1861523 -0.6947514 -0.694743 0.1861504 -0.6947503 -0.6947447 0.1861636 -0.6947383 -0.6947531 0.5085895 -0.6947456 -0.5085915 0.508605 -0.6947293 -0.5085984 0.6947488 -0.6947442 -0.1861577 0.6947721 -0.6947191 -0.1861643 0.6947314 -0.6947629 0.1861529 0.6947814 -0.6947091 0.1861669 0.5085929 -0.6947441 0.5085904 0.5085963 -0.6947385 0.5085945 0.1861637 -0.6947302 0.6947611 0.1861506 -0.6947547 0.6947402 -0.1861559 -0.694745 0.6947484 -0.1861582 -0.6947457 0.6947471 -0.5085927 -0.6947439 0.5085905 -0.5086055 -0.6947222 0.5086074 -0.6947141 -0.6947814 0.1861484 -0.6947721 -0.6947191 0.1861643 0.9659259 0 0.2588193 0.7071056 0 0.707108 0.7071087 0 0.7071049 0.2588231 0 0.9659247 0.2588173 0 0.9659263 -0.2588173 0 0.9659263 -0.2588231 0 0.9659247 -0.7071087 0 0.7071049 -0.7071056 0 0.707108 -0.9659259 0 0.2588193 -0.9659259 0 -0.2588193 -0.7071056 0 -0.707108 -0.7071087 0 -0.7071049 -0.2588231 0 -0.9659247 -0.2588173 0 -0.9659263 0.2588173 0 -0.9659263 0.2588231 0 -0.9659247 0.7071087 0 -0.7071049 0.7071056 0 -0.707108 0.9659259 0 -0.2588193 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.965926 0 -0.2588185 0.9659256 0 -0.25882 0.707104 0 -0.7071096 0.2588239 0 -0.9659245 0.2588183 0 -0.9659261 -0.2588171 0 -0.9659264 -0.2588226 0 -0.9659249 -0.9659257 0 -0.25882 -0.965926 0 -0.2588185 -0.9659257 0 0.25882 -0.965926 0 0.2588185 -0.2588171 0 0.9659264 -0.2588226 0 0.9659249 0.2588239 0 0.9659245 0.2588183 0 0.9659261 0.707104 0 0.7071096 0.965926 0 0.2588185 0.9659256 0 0.25882 0.6175526 0.4870809 -0.6175604 0.6175806 0.4870184 -0.6175819 0.2260425 0.4870828 -0.8435965 0.2260478 0.4870383 -0.8436208 -0.2260472 0.4870433 -0.8436182 -0.2260417 0.4870731 -0.8436024 -0.6175413 0.4871191 -0.6175416 -0.6175643 0.4870558 -0.6175686 -0.8435978 0.4870812 -0.2260416 -0.8435936 0.4870913 -0.2260352 -0.8435978 0.4870812 0.2260416 -0.8435927 0.4870925 0.2260358 -0.6175543 0.4870823 0.6175577 -0.6175411 0.4871263 0.6175363 -0.2260372 0.4870722 0.8436041 -0.2260475 0.4870725 0.8436012 0.2260511 0.4870633 0.8436055 0.2260369 0.4870755 0.8436023 0.6175584 0.4870783 0.6175569 0.6175788 0.4870193 0.617583 0.8435978 0.4870812 0.2260416 0.8436117 0.4870555 0.2260451 0.8435987 0.4870799 -0.226041 0.8436117 0.4870555 -0.2260451 0 -1 0 -0.8164608 0 0.5774009 -0.8165107 -1.60132e-5 0.5773302 -0.816501 6.06587e-5 0.5773441 0.5735781 0 0.8191509 0.573574 -7.48029e-6 0.8191538 0.5735805 0 0.8191493 -0.5358682 0.1138807 -0.8365862 -0.5145601 0.06278234 -0.8551529 -0.5009691 0.138289 -0.8543455 -0.4716407 0.02992981 -0.8812828 -0.4565151 0.09847676 -0.884249 1 -3.61245e-5 0 -0.9276526 0.3551953 -0.1153132 -0.8509248 0.5220258 -0.05844837 -0.8333916 0.5426977 0.1045842 -0.8486858 0.5288976 0 -0.8486589 0.5289406 0 0.7097811 0 -0.7044223 0.709782 0 -0.7044215 0.7097831 -7.20453e-7 -0.7044204 0.7097818 3.38249e-7 -0.7044217 0.7097826 0 -0.7044209 0.7097815 2.61182e-6 -0.704422 0.7097885 -5.30413e-5 -0.7044149 0.7097828 0 -0.7044206 0.7097907 1.2744e-5 -0.7044127 0.7097764 8.80523e-6 -0.7044271 0.7097216 1.10535e-4 -0.7044823 -0.6621474 -0.01076871 -0.7492963 -0.5859876 -0.1207928 -0.8012663 -0.6004232 -0.05519014 -0.7977758 -0.5797447 0.02370607 -0.8144533 0.4026916 0.007420301 0.9153057 0.4068731 0.01012301 0.9134286 0.4296792 0.001181542 0.9029809 0.4348537 -8.58889e-4 0.9005008 0.4350938 -9.68221e-4 0.9003847 0.3590301 0 0.933326 0.3823742 0.001630127 0.9240062 0.3990789 0.006889164 0.9168907 0.3171585 0 0.9483726 0.3171595 0 0.9483723 0.3171599 0 0.9483721 0.3171597 -2.78533e-7 0.9483722 -0.5780504 -0.2173585 -0.7865197 -0.5440701 -0.1710748 -0.8214141 -0.5458476 -0.1730892 -0.8198113 -0.5518385 -0.1791408 -0.8144832 -0.4650772 -0.2394614 -0.8522683 -0.5054298 -0.2125548 -0.8362783 -0.5111595 -0.1997753 -0.8359461 -0.5580725 -0.1814674 -0.8097065 -0.5602777 -0.1868641 -0.8069515 -0.4383909 -0.2354498 -0.8673967 -0.4348769 -0.2402722 -0.8678429 -0.4273456 -0.2386661 -0.8720173 -0.5367416 -0.2340591 -0.8106324 -0.5641856 -0.198202 -0.8015053 -0.5702688 -0.1970723 -0.7974686 -0.4195619 0.8956725 -0.1474405 -0.485569 0.8655769 -0.1224716 -0.4823912 0.8674855 -0.121523 -0.5409897 0.8345124 -0.1044952 -0.5473157 0.8365936 -0.02359628 -0.6335997 0.7613782 -0.1373131 -0.7683225 0.2212273 -0.6006155 -0.7665838 0.358124 -0.5330071 -0.7771185 0.3489007 -0.5237895 -0.6613621 -0.009911537 -0.7500014 -0.7145463 0.3246275 -0.6197101 -0.6989455 0.1673485 -0.6953199 -0.7759715 0.5232154 -0.3522979 -0.7156076 0.6494463 -0.2571486 -0.7123382 0.6457481 -0.2749247 -0.678878 0.6919192 -0.2457087 -0.6273556 0.7224154 -0.2907594 -0.6381848 0.7083642 -0.3015634 -0.7206715 0.6245791 -0.300888 -0.558957 0.7889028 -0.255342 -0.6975911 0.5174391 -0.4956042 -0.7252532 0.3951863 -0.5637692 -0.7510636 0.3792074 -0.5404676 -0.7525897 0.3692886 -0.5451925 -0.7773056 0.3490492 -0.5234128 -0.6663093 0.01104229 -0.7455938 -0.6709299 0.00677824 -0.7414898 -0.6695004 0.005927801 -0.742788 -0.6682462 0.006965994 -0.7439077 -0.6657852 0.003547847 -0.7461351 -0.6726242 -6.29958e-4 -0.739984 -0.6451225 -0.04643195 -0.7626671 -0.3511003 -0.2293841 -0.9078059 -0.3467407 -0.2180725 -0.9122583 -0.4122288 -0.2471062 -0.8769299 -0.415684 -0.2515574 -0.8740285 -0.2452833 0 0.9694516 -0.2452844 0 0.9694513 -0.2452564 -2.74439e-7 0.9694584 -0.245288 0 0.9694504 -0.9999279 0 0.01200979 0.7070987 -0.00438857 0.7071013 0.5477378 0 0.83665 0.2588208 0 0.9659253 0.2588167 0 0.9659265 -0.2588167 0 0.9659265 -0.2588208 0 0.9659253 -0.7071032 0 0.7071104 -0.7071055 0 0.7071082 -0.9659258 0 0.2588194 -0.9627473 -0.001192808 0.2704001 -0.9999279 0 0.01201009 -0.9659261 0 -0.2588186 -0.707104 0 -0.7071096 -0.2588226 0 -0.965925 0.2588226 0 -0.965925 0.7071063 0 -0.7071073 0.9659261 0 -0.2588186 0.9659261 0 0.2588186 0.7456129 0 0.6663793 0.7456154 0 0.6663765 0 1 0 0 1 1.31444e-7 0 1 -1.22791e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.42366e-5 0 1 0 1 0 0.258819 -0.9659259 0 0.7071068 -0.7071068 0 0.7071051 -0.7071086 0 0.9659264 -0.2588173 0 0.9659253 -0.2588207 0 -5.69463e-5 0 -1 5.21097e-6 0 -1 -0.9659266 0 -0.2588165 -0.9659246 0 -0.2588239 -0.7071118 0 -0.7071018 -0.7070968 0 -0.7071169 -0.25884 0 -0.9659203 -0.2588142 0 -0.9659272 0.258815 0 -0.965927 0.2588391 0 -0.9659205 0.7070984 0 -0.7071152 0.7071101 0 -0.7071034 0.9659248 0 -0.2588232 0.9659263 0 -0.2588172 0.9659266 0 0.2588165 0.9659263 0 0.2588172 0.7071118 0 0.7071018 0.7070968 0 0.7071169 0.258815 0 0.965927 0.2588142 0 0.9659272 -0.258815 0 0.965927 -0.2588142 0 0.9659272 -0.7070984 0 0.7071152 -0.7071101 0 0.7071034 -0.9659266 0 0.2588165 -0.9659263 0 0.2588172 0 1 4.76837e-7 0 1 -4.76837e-7 0 1 -1.90734e-6 0 1 1.90736e-6 0 -1 2.27174e-6 -0.4142487 0 -0.9101638 -0.4142472 0 -0.9101645 0.4142487 0 -0.9101638 0.414248 0 -0.9101642 0 -1 -7.11855e-6 0 -1 7.11825e-6 0 -1 1.50428e-6 -0.9659255 0 -0.2588204 -0.9659237 0 -0.258827 -0.7071135 0 -0.7071001 -0.7070993 0 -0.7071143 0.7071001 0 -0.7071135 0.7071126 0 -0.7071009 0.9659237 0 -0.258827 0.9659255 0 -0.2588204 0.9659255 0 0.2588204 0.7071135 0 0.7071001 0.7070993 0 0.7071143 -0.7071001 0 0.7071135 -0.7071126 0 0.7071009 -0.9659255 0 0.2588204 0 1 9.53674e-7 0 1 -9.53674e-7 0 1 -1.90733e-6 -0.2797425 -0.8568898 -0.4329943 0.08380484 -0.8541522 0.5132259 -0.1723493 -0.8531295 0.4924083 -0.5101974 -0.8491225 0.1367099 -0.5102051 -0.8491176 -0.136712 -0.388274 -0.85195 0.3513185 0.5092027 -0.8474424 -0.1501798 0.4040381 -0.8560427 0.322404 0.3182097 -0.8550151 0.4095017 0.5092066 -0.84744 0.1501809 -0.2797425 -0.8568898 0.4329943 -0.03856486 -0.8565297 0.5146548 0.2125499 -0.8560219 0.471221 0.08384066 -0.8541537 -0.5132178 0.2125499 -0.8560219 -0.471221 -0.0386455 -0.8565166 -0.5146708 0.2641516 -0.902587 -0.3399422 0.3623611 -0.8506269 -0.3809575 -0.1723494 -0.8531297 -0.4924079 -0.388267 -0.8519564 -0.3513104 0.6135805 0 0.7896323 0.5314066 0.03809463 0.84626 0.4110959 0 0.9115921 0.1612226 0 0.9869182 0.08684998 0.03375715 0.9956493 -0.07476943 0 0.9972009 -0.3303552 0 0.9438568 -0.3769484 0.02597141 0.9258701 -0.5426672 0 0.8399478 -0.7580398 0 0.6522083 -0.7414014 0.01640194 0.6708614 -0.9719278 -0.01809269 0.2345832 -0.9659245 0 0.258824 -0.9720857 0 -0.2346263 -0.9657933 -0.01640516 -0.2587939 -0.7579579 0.01469838 -0.6521378 -0.7415219 0 -0.6709287 -0.5426672 0 -0.8399478 -0.3769484 0.02597141 -0.9258701 -0.3303552 0 -0.9438568 -0.07483381 0 -0.9971961 0.08687049 0.0337674 -0.9956472 0.1612226 0 -0.9869182 0.4110959 0 -0.9115921 0.5314066 0.03809463 -0.84626 0.6135805 0 -0.7896323 0 1 1.86264e-6 0 1 -1.86267e-6 0 1 -1.4901e-6 0 1 -2.2352e-6 0 1 2.23516e-6 0 1 1.49011e-6 -0.9659237 0 -0.2588268 -0.9659263 0 -0.2588173 -0.7070993 0 -0.7071144 -0.707118 0 -0.7070956 -0.2588079 0 -0.9659289 -0.258808 0 -0.9659288 0.2588074 0 -0.965929 0.2588075 0 -0.9659289 0.7071182 0 -0.7070955 0.7070997 0 -0.7071139 0.9659266 0 -0.2588164 0.9659242 0 -0.2588257 0.9659242 0 0.2588257 0.965929 0 0.258807 0.7071182 0 0.7070955 0.7070997 0 0.7071139 0.2588074 0 0.965929 0.2588075 0 0.9659289 -0.2588079 0 0.9659289 -0.258808 0 0.9659288 -0.7070993 0 0.7071144 -0.707118 0 0.7070956 -0.9659288 0 0.2588081 -0.9659239 0 0.2588267 -0.3734924 -0.8491201 -0.373495 -0.5101937 -0.8491244 -0.1367118 0.373492 -0.8491205 -0.3734946 0.136712 -0.8491173 -0.5102055 -0.1367122 -0.8491169 -0.5102061 0.3735076 -0.8491156 0.3734899 0.5102021 -0.8491199 0.1367086 0.5101941 -0.8491238 -0.1367144 -0.373508 -0.8491153 0.3734903 -0.1367112 -0.8491195 0.5102022 0.1367112 -0.8491195 0.5102022 -0.5102017 -0.8491198 0.136711 0 1 1.86265e-6 0 1 -1.86268e-6 0 1 1.1176e-6 0 1 -1.11758e-6 -0.373492 -0.8491205 -0.3734946 -0.5101937 -0.8491249 -0.1367092 0.3734917 -0.8491196 -0.3734967 0.136713 -0.8491166 -0.5102064 -0.1367114 -0.8491172 -0.5102058 0.3735067 -0.8491154 0.3734915 0.5102051 -0.8491179 0.1367094 0.5101955 -0.849123 -0.1367148 -0.3735079 -0.8491155 0.3734901 -0.1367102 -0.8491201 0.5102014 0.1367118 -0.8491194 0.510202 -0.5102009 -0.849121 0.1367058 -0.9659242 0 -0.2588257 -0.9659266 0 -0.2588163 -0.7070998 0 -0.7071138 -0.7071186 0 -0.707095 -0.2588068 0 -0.9659292 -0.2588068 0 -0.9659291 0.258809 0 -0.9659286 0.2588092 0 -0.9659286 0.7071161 0 -0.7070975 0.7070977 0 -0.7071159 0.7071161 0 0.7070975 0.7070977 0 0.7071159 0.258809 0 0.9659286 0.2588092 0 0.9659286 -0.2588068 0 0.9659292 -0.2588068 0 0.9659291 -0.7070998 0 0.7071138 -0.7071186 0 0.707095 -0.965929 0 0.2588071 -0.9659242 0 0.2588257 -0.3735085 -0.8491155 -0.3734894 -0.5101951 -0.8491235 -0.1367124 0.3735089 -0.8491151 -0.3734899 0.1366988 -0.8491203 -0.5102041 -0.1366988 -0.8491203 -0.5102041 0.3735071 -0.8491168 0.373488 0.5102002 -0.8491212 0.1367077 0.5101978 -0.8491222 -0.1367102 -0.3735067 -0.8491172 0.3734875 -0.1366879 -0.8491201 0.5102074 0.1366886 -0.8491184 0.51021 -0.5102 -0.8491209 0.1367106 -0.965925 0 -0.2588224 -0.9659249 0 -0.2588225 -0.7071107 0 -0.7071029 -0.7071108 0 -0.7071028 -0.258807 0 -0.965929 -0.2588342 0 -0.9659218 0.2588342 0 -0.9659218 0.258807 0 -0.965929 0.7071107 0 -0.7071029 0.7071108 0 -0.7071028 0.9659268 0 -0.2588159 0.9659268 0 -0.2588158 0.9659268 0 0.2588159 0.9659268 0 0.2588158 0.7071107 0 0.7071029 0.7071108 0 0.7071028 0.258807 0 0.965929 -0.258807 0 0.965929 -0.7071107 0 0.7071029 -0.965925 0 0.2588224 -0.9659249 0 0.2588225 -0.5085862 -0.6947565 -0.5085799 -0.5085735 -0.6947747 -0.5085678 -0.1861429 -0.69478 -0.6947169 -0.1861865 -0.6947369 -0.6947484 0.1861763 -0.6947408 -0.6947472 0.1861568 -0.6947696 -0.6947236 0.5085675 -0.6947655 -0.5085865 0.5086043 -0.6947507 -0.5085697 0.694734 -0.6947593 -0.1861565 0.6947466 -0.6947466 -0.1861574 0.694759 -0.6947337 0.1861588 0.6947587 -0.6947356 0.186153 0.5085996 -0.6947369 0.5085933 0.5085946 -0.6947312 0.5086061 0.1861584 -0.694718 0.6947748 0.1861575 -0.6947667 0.6947264 -0.1861437 -0.6947767 0.69472 -0.1861687 -0.6947219 0.694768 -0.5085942 -0.6947262 0.5086132 -0.5085858 -0.6947568 0.50858 -0.6947343 -0.6947595 0.1861545 -0.6947585 -0.6947354 0.1861544 -0.6947333 -0.6947585 -0.1861618 -0.6947463 -0.6947463 -0.1861588 0 1 7.21122e-7 0 1 -7.21122e-7 0 1 7.21114e-7 0 1 -1.44221e-6 0 1 7.21118e-7 0 1 -7.21118e-7 -0.3735094 -0.8491147 -0.3734903 -0.5101957 -0.8491231 -0.1367126 0.3735089 -0.8491145 -0.3734912 0.1366987 -0.8491206 -0.5102037 -0.1366986 -0.8491208 -0.5102034 0.3735075 -0.8491158 0.3734899 0.5101993 -0.8491213 0.1367105 0.5101961 -0.8491234 -0.1367098 -0.373508 -0.8491159 0.3734889 -0.1366878 -0.8491205 0.5102068 0.1366879 -0.8491201 0.5102074 -0.510199 -0.8491215 0.1367104 -0.9659255 0 -0.2588208 -0.7071111 0 -0.7071025 -0.7071112 0 -0.7071023 -0.2588068 0 -0.9659292 -0.258834 0 -0.9659219 0.258834 0 -0.9659218 0.2588068 0 -0.9659292 0.7071109 0 -0.7071027 0.707111 0 -0.7071025 0.9659255 0 -0.2588203 0.9659255 0 -0.2588204 0.9659255 0 0.2588203 0.9659255 0 0.2588204 0.7071109 0 0.7071027 0.707111 0 0.7071025 0.2588068 0 0.9659292 0.2588068 0 0.9659292 -0.2588068 0 0.9659292 -0.2588068 0 0.9659292 -0.7071111 0 0.7071025 -0.7071112 0 0.7071023 -0.9659255 0 0.2588208 -0.5085878 -0.6947588 -0.5085752 -0.5085796 -0.6947658 -0.5085739 -0.1861428 -0.6947741 -0.6947228 -0.186187 -0.6947404 -0.6947447 0.1861748 -0.6947402 -0.6947482 0.5085647 -0.6947742 -0.5085773 0.5086028 -0.6947486 -0.508574 0.6947306 -0.6947621 -0.1861587 0.6947448 -0.6947476 -0.1861598 0.6947418 -0.6947513 0.1861573 0.6947597 -0.6947337 0.1861562 0.5086018 -0.6947336 0.5085955 0.5085935 -0.6947327 0.5086051 0.1861568 -0.6947119 0.6947813 0.186158 -0.6947709 0.694722 -0.1861437 -0.6947705 0.6947262 -0.1861709 -0.6947188 0.6947706 -0.5085898 -0.6947328 0.5086087 -0.5086035 -0.694735 0.508592 -0.6947495 -0.6947432 0.1861586 -0.6947527 -0.6947412 0.1861543 -0.6947394 -0.694752 -0.1861634 -0.6947352 -0.6947582 -0.1861558 0 1 -7.21119e-7 0 1 7.21119e-7 0 1 7.21117e-7 0 1 -1.44222e-6 0 1 5.40839e-7 0 1 -5.40839e-7 0 1 -7.21108e-7 0 -1 -1.46185e-6 -0.8142076 0 0.580574 -0.814224 0 0.5805509 -0.4322161 0 0.9017701 -0.432174 0 0.9017903 0.0574761 0 0.9983469 0.05742526 0 0.9983499 0.5328267 0 0.8462244 0.5328077 0 0.8462364 0.8754576 0 0.483295 0.8754394 0 0.483328 0.8754398 0 -0.4833274 0.8754454 0 -0.4833172 0.5328449 0 -0.8462129 0.532826 0 -0.8462249 0.05742532 0 -0.9983498 0.05747604 0 -0.998347 -0.4322161 0 -0.9017701 -0.4322155 0 -0.9017705 -0.8142076 0 -0.580574 -0.8142068 0 -0.5805751 0.9937312 0 0.1117973 0.9937303 0 0.1118049 0.9659262 0 0.2588181 0.9659281 0 0.2588107 0.7070939 0 0.7071197 0.7071086 0 0.7071049 0.2588156 0 0.9659268 0.2588431 0 0.9659194 -0.2588413 0 0.96592 -0.2588137 0 0.9659273 -0.7071105 0 0.7071031 -0.7070958 0 0.7071179 -0.9659281 0 0.2588107 -0.9659262 0 0.2588181 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 2 1 1 1 3 1 2 2 3 2 4 2 5 3 6 3 7 3 7 4 6 4 8 4 7 5 8 5 9 5 9 6 8 6 1 6 9 7 1 7 10 7 10 8 1 8 0 8 10 9 0 9 11 9 11 10 0 10 12 10 11 11 12 11 13 11 13 12 12 12 14 12 15 13 16 13 17 13 17 14 16 14 18 14 19 15 20 15 21 15 19 16 21 16 22 16 22 17 21 17 23 17 23 18 21 18 24 18 23 19 24 19 25 19 25 20 24 20 26 20 25 21 26 21 27 21 27 22 26 22 28 22 27 23 28 23 29 23 29 24 28 24 30 24 29 25 30 25 31 25 31 26 30 26 32 26 31 27 32 27 33 27 33 28 32 28 34 28 33 29 34 29 35 29 35 30 34 30 36 30 35 31 36 31 37 31 37 32 36 32 38 32 37 33 38 33 39 33 39 34 38 34 40 34 39 35 40 35 41 35 41 36 40 36 42 36 41 37 42 37 43 37 43 38 42 38 44 38 43 39 44 39 45 39 19 40 22 40 20 40 46 41 47 41 48 41 48 42 47 42 49 42 48 43 49 43 50 43 51 44 52 44 53 44 53 45 52 45 17 45 53 46 17 46 18 46 54 47 55 47 56 47 56 48 55 48 57 48 56 49 57 49 51 49 51 50 57 50 58 50 51 51 58 51 52 51 54 52 56 52 59 52 59 53 56 53 60 53 59 54 60 54 61 54 60 55 62 55 61 55 61 56 62 56 63 56 61 57 63 57 64 57 64 58 63 58 65 58 64 59 65 59 66 59 66 60 65 60 67 60 67 61 65 61 68 61 67 62 68 62 69 62 69 63 68 63 70 63 69 64 70 64 71 64 72 65 73 65 47 65 47 66 73 66 74 66 47 67 74 67 49 67 50 68 75 68 48 68 48 69 75 69 46 69 46 70 75 70 76 70 46 71 76 71 77 71 77 72 76 72 73 72 77 73 73 73 72 73 78 74 79 74 80 74 80 75 79 75 81 75 80 76 82 76 78 76 78 77 82 77 83 77 78 78 83 78 84 78 84 79 83 79 85 79 84 80 85 80 86 80 86 81 85 81 87 81 88 82 89 82 90 82 90 83 89 83 91 83 90 84 91 84 92 84 93 85 94 85 95 85 95 86 94 86 90 86 95 87 90 87 96 87 96 88 90 88 92 88 87 89 85 89 90 89 90 90 85 90 97 90 90 91 97 91 98 91 98 92 99 92 90 92 90 93 99 93 100 93 90 94 100 94 88 94 101 95 102 95 103 95 104 95 105 95 106 95 106 95 107 95 104 95 104 95 107 95 108 95 104 95 108 95 103 95 103 95 108 95 109 95 103 95 109 95 101 95 110 96 111 96 112 96 113 97 114 97 90 97 115 98 110 98 90 98 94 98 105 98 90 98 90 98 105 98 104 98 90 98 104 98 116 98 116 98 104 98 117 98 116 98 117 98 118 98 110 99 112 99 90 99 90 100 112 100 119 100 90 101 119 101 113 101 120 98 90 98 121 98 121 102 90 102 114 102 121 103 114 103 122 103 122 104 114 104 123 104 124 98 125 98 116 98 116 98 125 98 126 98 116 98 126 98 90 98 90 98 126 98 127 98 90 98 127 98 115 98 128 98 124 98 129 98 129 98 124 98 116 98 129 98 116 98 130 98 130 105 116 105 131 105 132 95 133 95 134 95 134 95 133 95 135 95 134 95 135 95 136 95 137 95 138 95 139 95 139 95 138 95 140 95 140 95 134 95 136 95 140 95 136 95 139 95 78 106 141 106 142 106 143 107 144 107 145 107 138 108 79 108 140 108 140 109 79 109 78 109 140 110 78 110 146 110 146 111 78 111 142 111 146 112 142 112 147 112 146 113 148 113 140 113 140 114 148 114 149 114 140 115 149 115 150 115 150 116 151 116 140 116 140 117 151 117 152 117 140 118 152 118 153 118 154 106 145 106 155 106 155 119 145 119 156 119 155 120 156 120 157 120 158 106 143 106 159 106 159 106 143 106 145 106 159 106 145 106 160 106 160 106 145 106 154 106 153 121 161 121 140 121 140 122 161 122 162 122 140 123 162 123 156 123 156 124 162 124 163 124 156 125 163 125 157 125 164 126 165 126 166 126 166 127 165 127 167 127 166 128 167 128 168 128 168 129 167 129 169 129 170 130 171 130 172 130 172 131 171 131 173 131 172 132 173 132 174 132 175 133 176 133 177 133 175 134 177 134 173 134 173 135 177 135 178 135 173 136 178 136 179 136 169 137 167 137 172 137 172 138 167 138 180 138 172 139 180 139 170 139 179 140 181 140 173 140 173 141 181 141 182 141 173 142 182 142 183 142 183 143 184 143 173 143 173 144 184 144 185 144 173 145 185 145 174 145 186 95 187 95 188 95 186 95 188 95 189 95 189 95 188 95 190 95 189 95 190 95 191 95 191 95 190 95 192 95 192 95 190 95 193 95 192 95 193 95 194 95 195 146 196 146 197 146 167 98 198 98 195 98 199 147 200 147 167 147 195 148 197 148 167 148 167 149 197 149 201 149 167 150 201 150 199 150 202 98 167 98 203 98 203 151 167 151 200 151 203 152 200 152 204 152 204 153 200 153 205 153 206 154 207 154 208 154 208 98 207 98 209 98 165 98 193 98 167 98 167 98 193 98 190 98 167 98 190 98 198 98 198 98 190 98 210 98 198 98 210 98 211 98 211 98 210 98 212 98 212 98 210 98 213 98 213 98 210 98 208 98 213 98 208 98 214 98 214 98 208 98 209 98 214 98 209 98 215 98 216 95 217 95 218 95 219 95 220 95 221 95 221 95 220 95 222 95 221 95 222 95 223 95 223 95 222 95 216 95 223 95 216 95 224 95 224 95 216 95 218 95 225 155 226 155 227 155 228 156 229 156 230 156 231 157 232 157 173 157 220 106 175 106 222 106 222 106 175 106 173 106 222 106 173 106 233 106 234 158 235 158 236 158 236 159 235 159 237 159 236 160 237 160 238 160 239 106 230 106 240 106 240 106 230 106 233 106 240 106 233 106 241 106 231 161 173 161 242 161 232 162 225 162 173 162 173 163 225 163 227 163 173 106 227 106 233 106 233 106 227 106 243 106 233 106 243 106 241 106 244 164 228 164 245 164 245 165 228 165 230 165 245 106 230 106 246 106 246 106 230 106 239 106 238 166 237 166 173 166 173 167 237 167 247 167 173 168 247 168 242 168 248 169 249 169 250 169 251 106 252 106 253 106 253 106 252 106 254 106 253 106 254 106 255 106 256 107 257 107 254 107 248 170 250 170 258 170 259 106 260 106 261 106 261 106 260 106 262 106 259 106 263 106 260 106 260 106 263 106 264 106 260 106 264 106 254 106 254 106 264 106 265 106 254 106 265 106 255 106 266 106 267 106 254 106 250 171 268 171 269 171 266 106 254 106 270 106 271 106 272 106 273 106 273 106 272 106 258 106 273 106 258 106 274 106 274 172 258 172 250 172 274 173 250 173 275 173 275 174 250 174 269 174 276 106 277 106 269 106 269 106 277 106 270 106 269 106 270 106 278 106 278 106 270 106 254 106 278 106 254 106 279 106 279 106 254 106 252 106 268 175 280 175 269 175 269 176 280 176 281 176 269 177 281 177 282 177 283 106 256 106 284 106 284 106 256 106 254 106 284 106 254 106 285 106 285 106 254 106 267 106 282 178 286 178 269 178 269 179 286 179 287 179 269 180 287 180 276 180 276 181 287 181 288 181 289 182 290 182 291 182 291 183 290 183 292 183 293 184 294 184 290 184 290 185 294 185 295 185 290 186 295 186 292 186 296 187 297 187 293 187 293 188 297 188 298 188 293 189 298 189 294 189 299 190 300 190 301 190 301 191 300 191 302 191 301 192 302 192 296 192 296 193 302 193 303 193 296 194 303 194 297 194 304 195 305 195 306 195 306 196 305 196 307 196 306 197 307 197 308 197 309 198 310 198 311 198 311 199 310 199 312 199 311 200 312 200 305 200 305 201 312 201 313 201 305 202 313 202 307 202 314 203 309 203 315 203 315 204 309 204 311 204 315 205 311 205 316 205 316 206 311 206 317 206 316 207 317 207 318 207 318 208 317 208 319 208 320 209 321 209 317 209 317 210 321 210 322 210 317 211 322 211 319 211 323 212 324 212 325 212 325 213 324 213 326 213 325 214 326 214 320 214 320 215 326 215 327 215 320 216 327 216 321 216 44 217 328 217 329 217 45 218 44 218 329 218 45 219 329 219 330 219 330 220 329 220 331 220 330 221 331 221 332 221 332 222 300 222 330 222 330 223 300 223 299 223 330 224 299 224 333 224 333 225 299 225 304 225 333 226 304 226 306 226 334 227 289 227 335 227 335 228 289 228 291 228 335 229 291 229 336 229 336 230 291 230 292 230 336 231 292 231 337 231 337 232 292 232 338 232 338 233 292 233 295 233 338 234 295 234 339 234 340 235 341 235 334 235 341 236 342 236 334 236 334 237 342 237 343 237 334 238 343 238 344 238 336 239 337 239 335 239 335 240 337 240 345 240 335 241 345 241 334 241 334 242 345 242 346 242 334 243 346 243 340 243 347 244 340 244 348 244 348 245 340 245 346 245 348 246 346 246 345 246 349 247 350 247 344 247 344 248 343 248 349 248 349 249 343 249 342 249 349 250 342 250 347 250 347 251 342 251 341 251 347 252 341 252 340 252 305 253 304 253 299 253 2 254 344 254 0 254 0 255 344 255 350 255 320 256 317 256 311 256 350 257 351 257 0 257 0 258 351 258 352 258 0 259 352 259 353 259 2 260 4 260 344 260 344 261 4 261 325 261 344 262 325 262 334 262 334 263 325 263 289 263 311 264 305 264 320 264 320 265 305 265 299 265 320 266 299 266 325 266 325 267 299 267 301 267 325 268 301 268 296 268 296 269 293 269 325 269 325 270 293 270 290 270 325 271 290 271 289 271 345 272 337 272 354 272 354 273 337 273 338 273 354 274 338 274 355 274 355 275 338 275 339 275 355 276 339 276 356 276 328 277 357 277 46 277 46 278 357 278 358 278 46 279 358 279 47 279 47 280 358 280 16 280 47 281 16 281 15 281 348 282 345 282 359 282 359 283 345 283 354 283 359 284 354 284 360 284 360 285 354 285 361 285 360 286 361 286 77 286 329 287 328 287 362 287 362 288 328 288 46 288 362 289 46 289 356 289 356 290 46 290 77 290 356 291 77 291 355 291 355 292 77 292 361 292 77 293 72 293 360 293 360 294 72 294 47 294 360 295 47 295 363 295 363 296 47 296 15 296 363 297 15 297 364 297 364 298 15 298 365 298 364 299 365 299 366 299 366 300 365 300 367 300 368 301 369 301 370 301 368 302 370 302 371 302 370 303 372 303 373 303 373 304 374 304 370 304 370 305 374 305 375 305 370 306 375 306 371 306 376 307 377 307 378 307 378 308 377 308 379 308 380 309 381 309 382 309 382 310 381 310 378 310 382 311 378 311 383 311 383 312 378 312 379 312 383 313 379 313 384 313 384 314 379 314 385 314 386 315 387 315 388 315 386 316 388 316 389 316 390 317 391 317 392 317 330 318 333 318 393 318 393 319 333 319 306 319 393 320 306 320 308 320 308 321 394 321 395 321 395 322 394 322 396 322 395 323 396 323 397 323 397 324 396 324 398 324 397 325 398 325 399 325 399 326 398 326 400 326 399 327 400 327 401 327 401 328 400 328 402 328 401 329 402 329 403 329 403 330 402 330 404 330 403 331 404 331 405 331 405 332 404 332 406 332 405 333 406 333 407 333 407 334 406 334 408 334 406 335 409 335 408 335 408 336 409 336 410 336 408 337 410 337 411 337 411 338 410 338 412 338 411 339 412 339 413 339 413 340 412 340 414 340 413 341 414 341 415 341 415 342 414 342 416 342 415 343 416 343 417 343 392 344 391 344 418 344 418 345 391 345 419 345 418 346 419 346 420 346 420 347 419 347 421 347 420 348 421 348 422 348 423 349 424 349 425 349 425 350 424 350 426 350 425 351 426 351 427 351 427 352 426 352 428 352 427 353 428 353 429 353 429 354 428 354 430 354 429 355 430 355 431 355 431 356 430 356 432 356 431 357 432 357 433 357 433 358 432 358 434 358 433 359 434 359 435 359 436 360 437 360 438 360 438 361 437 361 439 361 438 362 439 362 440 362 440 363 439 363 441 363 440 364 441 364 442 364 442 365 441 365 443 365 442 366 443 366 423 366 423 367 443 367 444 367 423 368 444 368 424 368 438 369 445 369 436 369 436 370 445 370 422 370 436 371 422 371 446 371 446 372 422 372 421 372 416 373 447 373 417 373 417 374 447 374 448 374 417 375 448 375 449 375 449 376 448 376 450 376 449 377 450 377 451 377 451 378 450 378 452 378 451 379 452 379 453 379 453 380 452 380 454 380 453 381 454 381 455 381 455 382 454 382 456 382 455 383 456 383 457 383 457 384 456 384 458 384 457 385 458 385 459 385 459 386 458 386 460 386 459 387 460 387 461 387 461 388 460 388 462 388 461 389 462 389 463 389 463 390 462 390 464 390 463 391 464 391 465 391 465 392 464 392 435 392 465 393 435 393 466 393 466 394 435 394 434 394 467 395 468 395 469 395 469 396 468 396 470 396 469 397 470 397 471 397 471 398 470 398 472 398 471 399 472 399 473 399 473 400 472 400 474 400 473 401 474 401 475 401 475 402 474 402 476 402 475 403 476 403 477 403 477 404 476 404 478 404 477 405 478 405 479 405 479 406 478 406 480 406 479 407 480 407 481 407 481 408 480 408 482 408 481 409 482 409 483 409 483 410 482 410 484 410 483 411 484 411 485 411 485 412 484 412 486 412 485 413 486 413 487 413 487 414 486 414 390 414 487 415 390 415 488 415 488 416 390 416 392 416 489 417 490 417 491 417 491 418 490 418 492 418 491 419 492 419 493 419 493 420 492 420 494 420 493 421 494 421 495 421 495 422 494 422 496 422 495 423 496 423 497 423 497 424 496 424 498 424 497 425 498 425 499 425 499 426 498 426 500 426 499 427 500 427 501 427 501 428 500 428 502 428 501 429 502 429 503 429 503 430 502 430 504 430 503 431 504 431 505 431 505 432 504 432 506 432 505 433 506 433 507 433 507 434 506 434 508 434 507 435 508 435 509 435 509 436 508 436 510 436 509 437 510 437 467 437 467 438 510 438 511 438 467 439 511 439 468 439 491 440 512 440 489 440 489 441 512 441 513 441 489 442 513 442 514 442 514 443 513 443 515 443 514 444 515 444 516 444 516 445 515 445 517 445 516 446 517 446 518 446 518 447 517 447 519 447 518 448 519 448 520 448 520 449 519 449 521 449 520 450 521 450 522 450 522 451 521 451 523 451 522 452 523 452 524 452 524 453 523 453 525 453 524 454 525 454 526 454 525 455 527 455 526 455 526 456 527 456 528 456 526 457 528 457 529 457 529 458 528 458 530 458 529 459 530 459 531 459 531 460 530 460 532 460 388 461 533 461 389 461 389 462 533 462 534 462 389 463 534 463 535 463 535 464 534 464 536 464 535 465 536 465 537 465 537 466 536 466 538 466 537 467 538 467 539 467 539 468 538 468 540 468 539 469 540 469 541 469 541 470 540 470 542 470 541 471 542 471 543 471 543 472 542 472 544 472 543 473 544 473 545 473 545 474 544 474 546 474 545 475 546 475 547 475 547 476 546 476 548 476 547 477 548 477 549 477 549 478 548 478 550 478 549 479 550 479 551 479 551 480 550 480 552 480 551 481 552 481 532 481 532 482 552 482 553 482 532 483 553 483 531 483 554 484 555 484 556 484 557 485 558 485 559 485 560 486 561 486 558 486 558 487 561 487 562 487 558 311 562 311 559 311 563 488 564 488 565 488 565 489 564 489 554 489 565 490 554 490 559 490 559 491 554 491 556 491 559 492 556 492 557 492 566 493 567 493 568 493 566 494 568 494 569 494 570 495 571 495 572 495 573 496 574 496 575 496 575 497 574 497 576 497 575 498 576 498 568 498 568 499 576 499 577 499 568 500 577 500 569 500 570 501 572 501 575 501 575 502 572 502 578 502 575 503 578 503 573 503 579 504 580 504 581 504 581 505 580 505 582 505 581 506 582 506 583 506 583 507 582 507 584 507 585 508 586 508 587 508 588 509 583 509 589 509 589 510 583 510 584 510 589 511 584 511 590 511 590 512 584 512 591 512 590 513 591 513 592 513 592 514 591 514 593 514 592 515 593 515 594 515 594 516 593 516 595 516 595 517 593 517 596 517 595 518 596 518 597 518 597 519 596 519 598 519 597 520 598 520 599 520 587 521 600 521 585 521 585 522 600 522 601 522 585 523 601 523 581 523 581 524 601 524 602 524 581 525 602 525 579 525 603 526 604 526 605 526 606 527 607 527 608 527 607 528 606 528 609 528 608 529 610 529 606 529 606 530 610 530 611 530 606 531 611 531 612 531 603 532 605 532 606 532 606 533 605 533 613 533 606 534 613 534 609 534 614 535 615 535 616 535 616 536 615 536 617 536 617 537 618 537 616 537 616 538 618 538 619 538 616 539 619 539 620 539 620 540 619 540 621 540 622 541 623 541 624 541 624 542 623 542 625 542 624 543 625 543 626 543 626 544 625 544 627 544 628 545 629 545 614 545 614 546 629 546 625 546 614 547 625 547 615 547 627 548 625 548 630 548 630 549 625 549 629 549 630 550 629 550 631 550 632 551 633 551 634 551 635 552 636 552 637 552 638 553 639 553 640 553 641 554 642 554 638 554 638 555 642 555 643 555 638 556 643 556 639 556 631 557 629 557 637 557 637 558 629 558 644 558 637 559 644 559 635 559 634 560 633 560 638 560 638 561 633 561 645 561 638 562 645 562 641 562 640 563 646 563 638 563 638 564 646 564 647 564 638 565 647 565 648 565 649 566 650 566 628 566 628 567 650 567 651 567 628 568 651 568 629 568 629 569 651 569 638 569 629 570 638 570 652 570 652 571 638 571 648 571 653 572 654 572 634 572 634 573 654 573 655 573 634 574 655 574 632 574 632 575 655 575 656 575 632 576 656 576 657 576 657 577 656 577 658 577 658 578 659 578 657 578 657 579 659 579 660 579 657 580 660 580 661 580 661 581 660 581 662 581 661 582 662 582 663 582 664 583 665 583 666 583 666 584 665 584 667 584 666 585 667 585 668 585 667 586 669 586 668 586 668 587 669 587 670 587 668 588 670 588 671 588 671 589 670 589 672 589 671 589 672 589 673 589 673 590 672 590 674 590 673 591 674 591 675 591 674 106 676 106 675 106 675 106 676 106 677 106 678 592 679 592 680 592 681 593 682 593 683 593 683 594 682 594 678 594 683 595 678 595 684 595 684 596 678 596 680 596 684 597 680 597 685 597 685 598 680 598 686 598 687 599 688 599 689 599 689 600 690 600 687 600 687 601 690 601 691 601 687 602 691 602 686 602 686 603 691 603 692 603 686 604 692 604 685 604 693 605 694 605 695 605 695 606 696 606 693 606 693 607 696 607 697 607 693 608 697 608 698 608 698 609 699 609 693 609 693 610 699 610 700 610 693 611 700 611 687 611 687 612 700 612 701 612 687 613 701 613 688 613 702 614 703 614 704 614 705 615 706 615 693 615 693 616 706 616 707 616 693 617 707 617 694 617 702 618 704 618 693 618 693 619 704 619 708 619 693 620 708 620 705 620 677 621 676 621 702 621 702 622 676 622 709 622 702 623 709 623 710 623 711 624 712 624 713 624 710 625 714 625 702 625 702 626 714 626 713 626 702 627 713 627 703 627 703 628 713 628 712 628 711 629 713 629 715 629 715 630 713 630 716 630 715 631 716 631 717 631 718 632 719 632 720 632 721 632 718 632 722 632 723 632 724 632 725 632 725 632 724 632 722 632 726 633 727 633 582 633 720 633 719 633 728 633 729 633 730 633 731 633 720 634 728 634 732 634 732 635 728 635 733 635 732 633 733 633 734 633 734 633 733 633 726 633 734 633 726 633 735 633 735 636 726 636 582 636 735 637 582 637 731 637 731 638 582 638 580 638 731 639 580 639 729 639 736 640 737 640 738 640 739 633 740 633 738 633 738 633 740 633 741 633 738 641 741 641 736 641 742 642 743 642 744 642 744 643 743 643 745 643 746 644 747 644 745 644 745 645 747 645 748 645 745 646 748 646 744 646 749 647 750 647 751 647 751 648 750 648 752 648 751 649 752 649 746 649 746 650 752 650 753 650 746 651 753 651 747 651 749 652 751 652 754 652 754 653 751 653 755 653 754 654 755 654 756 654 757 655 758 655 759 655 759 656 758 656 760 656 759 657 761 657 757 657 757 658 761 658 762 658 757 659 762 659 763 659 763 660 762 660 764 660 764 661 762 661 765 661 764 662 765 662 766 662 760 663 767 663 759 663 759 664 767 664 768 664 759 665 768 665 769 665 769 666 768 666 770 666 769 667 770 667 771 667 772 668 773 668 774 668 774 669 773 669 775 669 776 670 777 670 778 670 778 671 777 671 775 671 778 672 775 672 779 672 779 673 775 673 773 673 780 674 781 674 782 674 782 675 781 675 783 675 782 676 783 676 776 676 776 677 783 677 784 677 776 678 784 678 777 678 777 678 784 678 785 678 786 679 787 679 788 679 788 680 789 680 786 680 786 681 789 681 781 681 786 682 781 682 790 682 791 683 792 683 793 683 794 684 795 684 793 684 793 685 795 685 796 685 793 686 796 686 791 686 797 687 798 687 799 687 799 688 798 688 800 688 799 689 800 689 794 689 794 690 800 690 801 690 794 691 801 691 795 691 799 692 802 692 797 692 797 693 802 693 803 693 797 694 803 694 804 694 804 695 803 695 605 695 804 696 605 696 604 696 805 697 806 697 807 697 808 698 809 698 810 698 811 699 812 699 813 699 814 700 815 700 816 700 816 701 815 701 811 701 811 702 815 702 807 702 811 703 807 703 812 703 817 704 818 704 819 704 819 705 818 705 820 705 820 706 818 706 821 706 821 707 818 707 822 707 821 708 822 708 805 708 815 709 810 709 807 709 807 710 810 710 809 710 807 711 809 711 805 711 805 712 809 712 808 712 805 713 808 713 821 713 823 714 824 714 825 714 826 715 827 715 828 715 828 716 827 716 829 716 828 717 829 717 830 717 824 718 823 718 831 718 831 719 823 719 830 719 831 720 830 720 832 720 832 721 830 721 829 721 832 722 829 722 833 722 834 723 823 723 835 723 835 724 823 724 825 724 835 725 825 725 836 725 834 726 837 726 823 726 823 727 837 727 838 727 823 728 838 728 830 728 830 729 838 729 839 729 830 730 839 730 828 730 828 731 839 731 840 731 828 732 840 732 826 732 826 733 840 733 841 733 826 734 841 734 842 734 837 735 834 735 843 735 571 736 842 736 841 736 839 737 838 737 844 737 844 738 838 738 837 738 572 739 571 739 845 739 845 740 571 740 841 740 845 741 841 741 846 741 846 742 841 742 840 742 837 743 843 743 844 743 844 744 843 744 847 744 844 745 847 745 848 745 848 746 849 746 844 746 844 747 849 747 846 747 844 748 846 748 839 748 839 749 846 749 840 749 578 750 572 750 850 750 850 751 572 751 845 751 850 752 845 752 851 752 851 753 845 753 846 753 851 754 846 754 852 754 852 755 846 755 849 755 853 756 854 756 855 756 856 757 857 757 858 757 857 758 859 758 858 758 858 759 859 759 860 759 858 760 860 760 861 760 569 761 862 761 566 761 566 762 862 762 861 762 566 763 861 763 567 763 567 764 861 764 860 764 863 765 858 765 864 765 864 766 858 766 861 766 864 767 861 767 865 767 865 768 861 768 862 768 863 769 853 769 858 769 858 770 853 770 855 770 858 771 855 771 856 771 856 772 855 772 866 772 856 773 866 773 867 773 867 774 866 774 868 774 867 775 868 775 869 775 869 776 868 776 870 776 869 777 870 777 871 777 871 778 870 778 872 778 871 779 872 779 873 779 873 780 872 780 874 780 873 781 874 781 875 781 875 782 874 782 876 782 875 783 876 783 877 783 877 784 876 784 878 784 877 785 878 785 879 785 879 786 878 786 880 786 879 787 880 787 881 787 881 788 880 788 882 788 881 789 882 789 883 789 884 98 787 98 885 98 885 790 787 790 786 790 885 98 786 98 790 98 141 633 78 633 84 633 886 633 887 633 888 633 84 791 889 791 141 791 141 792 889 792 890 792 141 633 890 633 891 633 891 793 890 793 892 793 891 794 892 794 888 794 888 795 892 795 893 795 888 796 893 796 886 796 894 797 895 797 171 797 896 798 897 798 743 798 743 799 897 799 898 799 743 800 898 800 899 800 173 801 171 801 238 801 238 802 171 802 895 802 238 803 895 803 900 803 900 804 895 804 896 804 900 805 896 805 742 805 742 806 896 806 743 806 901 807 170 807 902 807 902 808 170 808 180 808 902 809 180 809 903 809 903 810 180 810 904 810 901 811 905 811 170 811 170 812 905 812 906 812 170 813 906 813 171 813 171 814 906 814 907 814 171 815 907 815 894 815 908 816 909 816 86 816 86 817 909 817 910 817 86 818 910 818 84 818 84 819 910 819 911 819 84 820 911 820 889 820 908 821 86 821 912 821 912 822 86 822 87 822 912 823 87 823 913 823 87 824 90 824 120 824 765 825 914 825 766 825 766 826 914 826 915 826 766 827 915 827 120 827 120 828 915 828 916 828 120 829 916 829 87 829 87 830 916 830 917 830 87 831 917 831 913 831 180 633 167 633 904 633 904 633 167 633 202 633 918 633 919 633 920 633 920 832 919 832 921 832 920 633 921 633 922 633 922 633 921 633 923 633 923 833 921 833 924 833 923 633 924 633 202 633 202 834 924 834 925 834 202 835 925 835 904 835 586 836 585 836 926 836 926 837 585 837 927 837 740 838 739 838 927 838 927 839 739 839 928 839 927 840 928 840 926 840 926 841 928 841 929 841 926 842 929 842 930 842 929 843 931 843 930 843 930 844 931 844 932 844 930 845 932 845 933 845 934 846 935 846 936 846 936 847 935 847 933 847 936 848 933 848 937 848 937 849 933 849 932 849 678 98 938 98 679 98 679 850 938 850 939 850 940 98 941 98 679 98 679 851 941 851 772 851 679 98 772 98 774 98 939 852 942 852 679 852 679 98 942 98 943 98 679 853 943 853 940 853 784 854 783 854 944 854 785 855 784 855 945 855 945 856 784 856 944 856 945 857 944 857 946 857 783 858 781 858 944 858 944 859 781 859 789 859 944 860 789 860 946 860 946 861 789 861 788 861 947 632 948 632 949 632 949 632 948 632 950 632 949 632 950 632 951 632 951 632 950 632 952 632 953 95 954 95 955 95 955 95 956 95 953 95 953 95 956 95 957 95 953 95 957 95 958 95 958 95 957 95 959 95 958 95 959 95 960 95 960 95 959 95 961 95 960 95 961 95 962 95 962 95 961 95 963 95 964 95 965 95 966 95 366 95 967 95 968 95 968 95 967 95 964 95 968 95 964 95 969 95 969 95 964 95 966 95 969 95 966 95 970 95 971 95 972 95 366 95 366 95 972 95 973 95 366 95 973 95 967 95 971 95 366 95 974 95 974 95 366 95 367 95 974 95 367 95 975 95 975 862 367 862 976 862 976 863 367 863 365 863 976 864 365 864 52 864 52 865 365 865 15 865 52 866 15 866 17 866 330 867 393 867 977 867 18 868 16 868 357 868 26 869 24 869 328 869 45 870 330 870 43 870 43 871 330 871 977 871 43 872 977 872 41 872 41 873 977 873 978 873 41 874 978 874 39 874 24 875 21 875 328 875 328 876 21 876 20 876 328 877 20 877 357 877 39 878 978 878 37 878 37 879 978 879 979 879 37 880 979 880 35 880 38 881 36 881 328 881 328 882 36 882 34 882 328 883 34 883 32 883 32 884 30 884 328 884 328 885 30 885 28 885 328 886 28 886 26 886 27 887 29 887 980 887 980 888 29 888 31 888 980 889 31 889 979 889 979 890 31 890 33 890 979 891 33 891 35 891 44 892 42 892 328 892 328 893 42 893 40 893 328 894 40 894 38 894 20 895 981 895 982 895 357 896 20 896 18 896 18 897 20 897 982 897 18 898 982 898 53 898 20 899 22 899 981 899 981 900 22 900 23 900 981 901 23 901 980 901 980 902 23 902 25 902 980 903 25 903 27 903 355 904 361 904 354 904 983 98 379 98 984 98 984 98 379 98 377 98 984 905 377 905 985 905 985 98 377 98 986 98 987 98 988 98 954 98 954 906 988 906 989 906 954 907 989 907 990 907 991 98 955 98 377 98 377 908 955 908 954 908 986 98 377 98 992 98 992 909 377 909 954 909 992 98 954 98 993 98 993 910 954 910 990 910 993 98 990 98 994 98 995 911 996 911 997 911 998 106 962 106 999 106 999 912 962 912 1000 912 1001 913 970 913 1002 913 1002 914 970 914 966 914 1003 915 1004 915 1005 915 1006 106 1007 106 1008 106 1009 916 1003 916 1010 916 1010 917 1003 917 1005 917 1010 918 1005 918 1011 918 1011 919 1005 919 1012 919 997 920 996 920 1005 920 1005 921 996 921 1013 921 1005 922 1013 922 1012 922 997 923 1014 923 995 923 995 106 1014 106 1015 106 995 106 1015 106 1001 106 1001 924 1015 924 1016 924 1001 925 1016 925 970 925 1000 106 1017 106 999 106 999 926 1017 926 1018 926 999 106 1018 106 1019 106 1019 927 1018 927 1020 927 1019 928 1020 928 1008 928 1008 929 1020 929 1021 929 1008 930 1021 930 1006 930 1004 931 1003 931 963 931 963 932 1003 932 1022 932 963 933 1022 933 962 933 962 934 1022 934 1023 934 962 106 1023 106 1024 106 1024 106 1025 106 962 106 962 935 1025 935 1026 935 962 936 1026 936 1000 936 988 937 987 937 1027 937 988 938 1027 938 1028 938 1028 939 1027 939 1029 939 1028 940 1029 940 1030 940 1030 941 1029 941 1031 941 1030 942 1031 942 1032 942 1033 943 1034 943 986 943 986 944 1034 944 1035 944 986 945 1035 945 985 945 985 946 1035 946 1036 946 985 947 1036 947 984 947 984 948 1036 948 1037 948 984 949 1037 949 1038 949 1033 950 986 950 1039 950 1039 951 986 951 992 951 1039 952 992 952 1040 952 1040 953 992 953 1041 953 1041 954 992 954 993 954 1041 955 993 955 1042 955 990 956 1043 956 994 956 994 957 1043 957 1044 957 994 958 1044 958 993 958 993 959 1044 959 1045 959 993 960 1045 960 1042 960 989 961 1046 961 990 961 990 962 1046 962 1047 962 990 963 1047 963 1043 963 1028 964 1048 964 988 964 988 965 1048 965 1049 965 988 966 1049 966 989 966 989 967 1049 967 1050 967 989 968 1050 968 1046 968 1051 969 964 969 967 969 69 970 71 970 1052 970 1052 971 1053 971 69 971 69 972 1053 972 1051 972 69 973 1051 973 67 973 67 974 1051 974 967 974 67 975 967 975 66 975 66 976 967 976 973 976 66 977 973 977 64 977 64 978 973 978 972 978 64 979 972 979 61 979 61 980 972 980 971 980 974 981 975 981 976 981 57 982 55 982 974 982 974 983 55 983 54 983 974 984 54 984 971 984 971 985 54 985 59 985 971 986 59 986 61 986 57 987 974 987 58 987 58 988 974 988 976 988 58 989 976 989 52 989 53 990 982 990 1054 990 53 991 1054 991 51 991 51 992 1054 992 1055 992 51 993 1055 993 56 993 56 994 1055 994 1056 994 1056 995 1057 995 56 995 56 996 1057 996 1058 996 56 997 1058 997 60 997 60 998 1058 998 1059 998 60 999 1059 999 62 999 62 1000 1059 1000 1060 1000 62 1001 1060 1001 63 1001 63 1002 1060 1002 1061 1002 63 1003 1061 1003 1062 1003 1062 1004 1061 1004 1063 1004 1062 1005 1063 1005 1064 1005 70 1006 68 1006 1062 1006 1062 1007 68 1007 65 1007 1062 1008 65 1008 63 1008 1065 1009 1066 1009 1067 1009 1067 1010 1066 1010 1068 1010 1068 1011 1069 1011 1067 1011 1067 1012 1069 1012 1070 1012 1067 1013 1070 1013 1071 1013 1071 1014 1070 1014 70 1014 1071 1015 70 1015 1072 1015 1072 1016 70 1016 1062 1016 1072 1017 1062 1017 1073 1017 1073 1018 1062 1018 1064 1018 1073 1019 1064 1019 1074 1019 1054 1020 982 1020 981 1020 1054 1021 981 1021 1055 1021 1055 1022 981 1022 1075 1022 1055 1023 1075 1023 1056 1023 978 1024 1076 1024 1077 1024 978 1025 1077 1025 979 1025 1076 1026 978 1026 1078 1026 1078 1027 978 1027 977 1027 1078 1028 977 1028 1079 1028 1079 1029 977 1029 393 1029 1079 1030 393 1030 308 1030 980 1031 1080 1031 981 1031 981 1032 1080 1032 1081 1032 981 1033 1081 1033 1075 1033 1077 1034 1082 1034 979 1034 979 1035 1082 1035 1083 1035 979 1036 1083 1036 980 1036 980 1037 1083 1037 1084 1037 980 1038 1084 1038 1080 1038 1085 1039 1060 1039 1059 1039 1056 1040 1075 1040 1057 1040 1057 1041 1075 1041 1085 1041 1057 1042 1085 1042 1058 1042 1058 1043 1085 1043 1059 1043 1086 1044 1087 1044 1088 1044 1088 1045 1074 1045 1086 1045 1086 1046 1074 1046 1064 1046 1086 1047 1064 1047 1063 1047 1089 1048 1090 1048 1091 1048 1091 1049 1090 1049 1092 1049 1091 1050 1092 1050 1093 1050 1094 1051 1095 1051 1096 1051 1077 1052 1097 1052 1082 1052 1082 1053 1097 1053 1098 1053 1082 1054 1098 1054 1083 1054 1083 1055 1098 1055 1099 1055 1083 1056 1099 1056 1084 1056 1100 1057 1081 1057 1101 1057 1101 1058 1081 1058 1080 1058 1101 1059 1080 1059 1094 1059 1094 1060 1080 1060 1084 1060 1094 1061 1084 1061 1095 1061 1095 1062 1084 1062 1099 1062 1095 1063 1099 1063 1096 1063 1060 1064 1085 1064 1100 1064 1100 1065 1085 1065 1075 1065 1100 1066 1075 1066 1081 1066 1089 1067 1102 1067 1090 1067 1090 1068 1102 1068 1087 1068 1090 1069 1087 1069 1103 1069 1103 1070 1087 1070 1086 1070 1103 1071 1086 1071 1061 1071 1061 1072 1086 1072 1063 1072 1096 1073 1093 1073 1094 1073 1094 1074 1093 1074 1092 1074 1094 1075 1092 1075 1101 1075 1101 1076 1092 1076 1090 1076 1101 1077 1090 1077 1100 1077 1100 1078 1090 1078 1103 1078 1100 1079 1103 1079 1060 1079 1060 1080 1103 1080 1061 1080 1074 1081 1104 1081 1073 1081 1105 1082 1013 1082 996 1082 1065 1083 1067 1083 965 1083 965 1084 1067 1084 1106 1084 1001 1085 1002 1085 1106 1085 1106 1086 1002 1086 966 1086 1106 1087 966 1087 965 1087 1077 1088 1107 1088 1097 1088 1097 1089 1107 1089 1108 1089 1097 1090 1108 1090 1098 1090 1098 1091 1108 1091 1109 1091 1098 1092 1109 1092 1099 1092 1109 1093 1110 1093 1099 1093 1099 1094 1110 1094 1111 1094 1099 1095 1111 1095 1096 1095 1096 1096 1111 1096 1112 1096 1096 1097 1112 1097 1093 1097 1091 1098 1113 1098 1089 1098 1089 1099 1113 1099 1114 1099 1089 1100 1114 1100 1102 1100 1102 1101 1114 1101 1087 1101 1087 1102 1114 1102 1115 1102 1087 1103 1115 1103 1088 1103 1073 1104 1104 1104 1072 1104 1072 1105 1104 1105 1116 1105 1072 1106 1116 1106 1071 1106 1117 1107 1118 1107 1119 1107 1119 1108 1118 1108 1120 1108 1119 1109 1120 1109 1121 1109 1121 1110 1120 1110 1122 1110 1121 1111 1122 1111 386 1111 1119 1112 1123 1112 1117 1112 1117 1113 1123 1113 1124 1113 1117 1114 1124 1114 1125 1114 1125 1115 1124 1115 1126 1115 1125 1116 1126 1116 1127 1116 1127 1117 1126 1117 1128 1117 1127 1118 1128 1118 1129 1118 1112 1119 1130 1119 1093 1119 1093 1120 1130 1120 1131 1120 1093 1121 1131 1121 1091 1121 1091 1122 1131 1122 1132 1122 1091 1123 1132 1123 1113 1123 1113 1124 1132 1124 1133 1124 1113 1125 1133 1125 1114 1125 1128 1126 1134 1126 1129 1126 1129 1127 1134 1127 1115 1127 1129 1128 1115 1128 1135 1128 1135 1129 1115 1129 1114 1129 1135 1130 1114 1130 1136 1130 1136 1131 1114 1131 1133 1131 1137 1132 1138 1132 1139 1132 1139 1133 1138 1133 1140 1133 1139 1134 1140 1134 1141 1134 1141 1135 1140 1135 1142 1135 1141 1136 1142 1136 1143 1136 1143 1137 1142 1137 1144 1137 1143 1138 1144 1138 1145 1138 1071 1139 1116 1139 1067 1139 1067 1140 1116 1140 1145 1140 1067 1141 1145 1141 1106 1141 1106 1142 1145 1142 1144 1142 1106 1143 1144 1143 1001 1143 1001 1144 1144 1144 1142 1144 1001 1145 1142 1145 995 1145 995 1146 1142 1146 1140 1146 995 1147 1140 1147 996 1147 996 1148 1140 1148 1138 1148 996 1149 1138 1149 1105 1149 1088 1150 1115 1150 1074 1150 1074 1151 1115 1151 1134 1151 1074 1152 1134 1152 1104 1152 1104 1153 1134 1153 1128 1153 1104 1154 1128 1154 1116 1154 1116 1155 1128 1155 1126 1155 1116 1156 1126 1156 1145 1156 1145 1157 1126 1157 1124 1157 1145 1158 1124 1158 1143 1158 1143 1159 1124 1159 1123 1159 1143 1160 1123 1160 1141 1160 1141 1161 1123 1161 1119 1161 1141 1162 1119 1162 1139 1162 1139 1163 1119 1163 1121 1163 1139 1164 1121 1164 1137 1164 1146 1165 1147 1165 1148 1165 1149 1166 1150 1166 1151 1166 1152 1167 1153 1167 1154 1167 1155 1168 1156 1168 1157 1168 1157 1169 1156 1169 1045 1169 1158 1170 1159 1170 1160 1170 1160 1171 1159 1171 1161 1171 1020 1172 1018 1172 1158 1172 1158 1173 1160 1173 1020 1173 1020 1174 1160 1174 1162 1174 1020 1175 1162 1175 1021 1175 1021 1176 1162 1176 1163 1176 1021 1177 1163 1177 1006 1177 1006 1178 1163 1178 1164 1178 1006 1179 1164 1179 1007 1179 1007 1180 1164 1180 1165 1180 1007 1181 1165 1181 1008 1181 1008 1182 1165 1182 1166 1182 1008 1183 1166 1183 1019 1183 1019 1184 1166 1184 1167 1184 1019 1185 1167 1185 999 1185 1032 1186 1146 1186 1030 1186 1030 1187 1146 1187 1148 1187 1030 1188 1148 1188 1028 1188 1028 1189 1148 1189 1168 1189 1028 1190 1168 1190 1048 1190 1048 1191 1168 1191 1169 1191 1170 1192 1050 1192 1169 1192 1169 1193 1050 1193 1049 1193 1169 1194 1049 1194 1048 1194 1045 1195 1044 1195 1157 1195 1157 1196 1044 1196 1043 1196 1157 1197 1043 1197 1171 1197 1171 1198 1043 1198 1047 1198 1171 1199 1047 1199 1170 1199 1170 1200 1047 1200 1046 1200 1170 1201 1046 1201 1050 1201 1161 1202 1152 1202 1160 1202 1160 1203 1152 1203 1154 1203 1160 1204 1154 1204 1162 1204 1162 1205 1154 1205 1172 1205 1162 1206 1172 1206 1163 1206 1163 1207 1172 1207 1173 1207 1163 1208 1173 1208 1164 1208 1164 1209 1173 1209 1174 1209 1164 1210 1174 1210 1165 1210 1165 1211 1174 1211 1175 1211 1165 1212 1175 1212 1166 1212 1166 1213 1175 1213 1151 1213 1166 1214 1151 1214 1167 1214 1167 1215 1151 1215 1150 1215 1153 1216 1155 1216 1154 1216 1154 1217 1155 1217 1157 1217 1154 1218 1157 1218 1172 1218 1172 1219 1157 1219 1171 1219 1172 1220 1171 1220 1173 1220 1173 1221 1171 1221 1170 1221 1173 1222 1170 1222 1174 1222 1174 1223 1170 1223 1169 1223 1174 1224 1169 1224 1175 1224 1175 1225 1169 1225 1168 1225 1175 1226 1168 1226 1151 1226 1151 1227 1168 1227 1148 1227 1151 1228 1148 1228 1149 1228 1149 1229 1148 1229 1147 1229 419 1230 391 1230 1176 1230 1118 1231 1117 1231 1177 1231 1076 1232 1178 1232 1077 1232 1077 1233 1178 1233 1107 1233 1107 1234 1178 1234 1108 1234 1108 1235 1178 1235 1179 1235 1108 1236 1179 1236 1109 1236 1180 1237 1111 1237 1110 1237 1111 1238 1180 1238 1112 1238 1112 1239 1180 1239 1181 1239 1112 1240 1181 1240 1130 1240 1131 1241 1182 1241 1132 1241 1132 1242 1182 1242 1133 1242 1130 1243 1181 1243 1131 1243 1131 1244 1181 1244 1183 1244 1131 1245 1183 1245 1182 1245 1182 1246 1183 1246 1184 1246 1182 1247 1184 1247 1133 1247 1117 1248 1125 1248 1177 1248 1177 1249 1125 1249 1127 1249 1177 1250 1127 1250 1185 1250 1185 1251 1127 1251 1129 1251 1185 1252 1129 1252 1186 1252 1186 1253 1129 1253 1135 1253 1186 1254 1135 1254 1184 1254 1184 1255 1135 1255 1136 1255 1184 1256 1136 1256 1133 1256 1187 1257 531 1257 553 1257 553 1258 552 1258 1187 1258 1187 1259 552 1259 550 1259 1187 1260 550 1260 548 1260 548 1261 546 1261 1187 1261 1187 1262 546 1262 544 1262 1187 1263 544 1263 542 1263 542 1264 540 1264 1187 1264 1187 1265 540 1265 538 1265 1187 1266 538 1266 1188 1266 1188 1267 538 1267 536 1267 1188 1268 536 1268 534 1268 534 1269 533 1269 1188 1269 1188 1270 533 1270 388 1270 1188 1271 388 1271 387 1271 1189 1272 468 1272 511 1272 511 1273 510 1273 1189 1273 1189 1274 510 1274 508 1274 1189 1275 508 1275 506 1275 1190 1276 504 1276 502 1276 502 1277 500 1277 1190 1277 1190 1278 500 1278 498 1278 1190 1279 498 1279 496 1279 441 1280 439 1280 1191 1280 1191 1281 439 1281 437 1281 437 1282 436 1282 1191 1282 1191 1283 436 1283 446 1283 1191 1284 446 1284 1176 1284 1176 1285 446 1285 421 1285 1176 1286 421 1286 419 1286 1192 1287 453 1287 455 1287 455 1288 457 1288 1192 1288 1192 1289 457 1289 459 1289 1192 1290 459 1290 1193 1290 459 1291 461 1291 1193 1291 1193 1292 461 1292 463 1292 1193 1293 463 1293 465 1293 1079 1294 308 1294 395 1294 395 1295 397 1295 1079 1295 1079 1296 397 1296 399 1296 1079 1297 399 1297 1194 1297 1194 1298 399 1298 401 1298 1194 1299 401 1299 403 1299 1076 1300 1078 1300 1178 1300 1178 1301 1078 1301 1195 1301 1178 1302 1195 1302 1179 1302 1179 1303 1195 1303 1196 1303 1179 1304 1196 1304 1197 1304 1197 1305 1196 1305 1198 1305 1197 1306 1198 1306 1199 1306 1199 1307 1198 1307 1200 1307 1199 1308 1200 1308 1201 1308 1201 1309 1200 1309 1202 1309 1201 1310 1202 1310 1203 1310 1203 1311 1202 1311 1204 1311 1203 1312 1204 1312 1190 1312 496 1313 494 1313 1190 1313 1190 1314 494 1314 492 1314 1190 1315 492 1315 490 1315 490 1316 489 1316 1190 1316 1190 1317 489 1317 514 1317 1190 1318 514 1318 516 1318 524 1319 526 1319 1187 1319 1187 1320 526 1320 529 1320 1187 1321 529 1321 531 1321 516 1322 518 1322 1190 1322 1190 1323 518 1323 520 1323 1190 1324 520 1324 1187 1324 1187 1325 520 1325 522 1325 1187 1326 522 1326 524 1326 1188 1327 1205 1327 1187 1327 1187 1328 1205 1328 1206 1328 1187 1329 1206 1329 1190 1329 1190 1330 1206 1330 1207 1330 1190 1331 1207 1331 1203 1331 484 1332 482 1332 1176 1332 391 1333 390 1333 1176 1333 1176 1334 390 1334 486 1334 1176 1335 486 1335 484 1335 482 1336 480 1336 1176 1336 1176 1337 480 1337 478 1337 1176 1338 478 1338 1189 1338 1189 1339 478 1339 476 1339 1189 1340 476 1340 474 1340 474 1341 472 1341 1189 1341 1189 1342 472 1342 470 1342 1189 1343 470 1343 468 1343 465 1344 466 1344 1193 1344 1193 1345 466 1345 434 1345 1193 1346 434 1346 432 1346 432 1347 430 1347 1193 1347 1193 1348 430 1348 428 1348 1193 1349 428 1349 1191 1349 1191 1350 428 1350 426 1350 1191 1351 426 1351 424 1351 424 1352 444 1352 1191 1352 1191 1353 444 1353 443 1353 1191 1354 443 1354 441 1354 1110 1355 1109 1355 1180 1355 1180 1356 1109 1356 1179 1356 1180 1357 1179 1357 1181 1357 1181 1358 1179 1358 1197 1358 1181 1359 1197 1359 1183 1359 1183 1360 1197 1360 1199 1360 1183 1361 1199 1361 1184 1361 1184 1362 1199 1362 1201 1362 1184 1363 1201 1363 1186 1363 1186 1364 1201 1364 1203 1364 1186 1365 1203 1365 1185 1365 1185 1366 1203 1366 1207 1366 1185 1367 1207 1367 1177 1367 1177 1368 1207 1368 1206 1368 1177 1369 1206 1369 1118 1369 1118 1370 1206 1370 1205 1370 1118 1371 1205 1371 1120 1371 1120 1372 1205 1372 1188 1372 1120 1373 1188 1373 1122 1373 1122 1374 1188 1374 387 1374 1122 1375 387 1375 386 1375 403 1376 405 1376 1194 1376 1194 1377 405 1377 407 1377 1194 1378 407 1378 408 1378 408 1379 411 1379 1194 1379 1194 1380 411 1380 413 1380 1194 1381 413 1381 1192 1381 1192 1382 413 1382 415 1382 1192 1383 415 1383 417 1383 417 1384 449 1384 1192 1384 1192 1385 449 1385 451 1385 1192 1386 451 1386 453 1386 1078 1387 1079 1387 1195 1387 1195 1388 1079 1388 1194 1388 1195 1389 1194 1389 1196 1389 1196 1390 1194 1390 1192 1390 1196 1391 1192 1391 1198 1391 1198 1392 1192 1392 1193 1392 1198 1393 1193 1393 1200 1393 1200 1394 1193 1394 1191 1394 1200 1395 1191 1395 1202 1395 1202 1396 1191 1396 1176 1396 1202 1397 1176 1397 1204 1397 1204 1398 1176 1398 1189 1398 1204 1399 1189 1399 1190 1399 1190 1400 1189 1400 506 1400 1190 1401 506 1401 504 1401 1208 1402 1209 1402 1210 1402 1209 1403 1208 1403 1211 1403 1211 1404 1208 1404 1212 1404 1211 1405 1212 1405 1213 1405 1213 1406 1212 1406 1214 1406 1213 1407 1214 1407 1215 1407 331 1408 1215 1408 332 1408 332 1409 1215 1409 1214 1409 332 1410 1214 1410 300 1410 300 1411 1214 1411 302 1411 302 1412 1214 1412 303 1412 303 1413 1214 1413 1212 1413 303 1414 1212 1414 297 1414 297 1415 1212 1415 298 1415 298 1416 1212 1416 1208 1416 298 1417 1208 1417 294 1417 294 1418 1208 1418 1210 1418 294 1419 1210 1419 295 1419 1216 1420 1014 1420 1217 1420 1217 1421 1014 1421 997 1421 1217 1422 997 1422 1218 1422 1218 1423 997 1423 1005 1423 1218 1424 1005 1424 1004 1424 970 1425 1016 1425 1219 1425 1219 1426 1016 1426 1015 1426 1219 1427 1015 1427 1220 1427 1220 1428 1015 1428 1014 1428 1220 1429 1014 1429 1216 1429 70 1430 1070 1430 71 1430 71 1431 1070 1431 1069 1431 71 1432 1069 1432 1052 1432 1052 1433 1069 1433 1068 1433 1052 1434 1068 1434 1053 1434 1053 1435 1068 1435 1066 1435 1053 1436 1066 1436 1051 1436 1051 1437 1066 1437 1065 1437 1051 1438 1065 1438 964 1438 964 1439 1065 1439 965 1439 1031 1440 1221 1440 1032 1440 1032 1441 1221 1441 1222 1441 1032 1442 1222 1442 1146 1442 1146 1443 1222 1443 1147 1443 1147 1444 1222 1444 1223 1444 1147 1445 1223 1445 1149 1445 1223 1446 1224 1446 1149 1446 1149 1447 1224 1447 1225 1447 1149 1448 1225 1448 1150 1448 1150 1449 1225 1449 1226 1449 1150 1450 1226 1450 1167 1450 1227 1451 998 1451 1228 1451 1228 1452 998 1452 999 1452 1228 1453 999 1453 1229 1453 1229 1454 999 1454 1167 1454 1229 1455 1167 1455 1230 1455 1230 1456 1167 1456 1226 1456 1027 1457 953 1457 1029 1457 1029 1458 953 1458 958 1458 1029 1459 958 1459 1031 1459 958 1460 1224 1460 1223 1460 1223 1461 1222 1461 958 1461 958 1462 1222 1462 1221 1462 958 1463 1221 1463 1031 1463 1229 1464 1230 1464 960 1464 960 1465 1230 1465 1226 1465 960 1466 1226 1466 958 1466 958 1467 1226 1467 1225 1467 958 1468 1225 1468 1224 1468 960 1469 962 1469 998 1469 998 1470 1227 1470 960 1470 960 1471 1227 1471 1228 1471 960 1472 1228 1472 1229 1472 987 1473 954 1473 1027 1473 1027 1474 954 1474 953 1474 1231 98 729 98 580 98 1231 98 580 98 1232 98 1232 98 580 98 579 98 1232 98 579 98 1233 98 1233 98 579 98 602 98 1233 98 602 98 1234 98 1234 98 602 98 601 98 1234 98 601 98 1235 98 1235 98 601 98 600 98 1235 98 600 98 1236 98 1236 98 600 98 587 98 1236 98 587 98 1237 98 556 1475 949 1475 557 1475 557 1475 949 1475 951 1475 623 1476 622 1476 1238 1476 1238 1477 622 1477 1239 1477 556 1478 555 1478 949 1478 949 1479 555 1479 947 1479 991 1480 377 1480 1240 1480 1240 1481 377 1481 376 1481 1241 1482 1242 1482 1243 1482 1243 1483 1242 1483 1244 1483 1243 1484 1244 1484 1245 1484 1245 1485 1244 1485 1246 1485 1245 1486 1246 1486 1247 1486 1247 1487 1246 1487 1248 1487 1249 1488 1250 1488 1251 1488 1251 1489 1250 1489 1252 1489 1253 1490 1254 1490 1255 1490 1255 1491 1254 1491 1249 1491 1255 1492 1249 1492 1256 1492 1256 1493 1249 1493 1251 1493 1248 1494 1257 1494 1247 1494 1247 1495 1257 1495 1258 1495 1247 1496 1258 1496 1259 1496 1259 1497 1258 1497 1260 1497 1259 1498 1260 1498 1250 1498 1250 1499 1260 1499 1261 1499 1250 1500 1261 1500 1252 1500 1252 1501 1261 1501 1262 1501 1252 1502 1262 1502 1263 1502 1264 1503 1265 1503 1266 1503 1266 1504 1265 1504 1267 1504 1266 1505 1267 1505 1268 1505 1268 1506 1267 1506 1269 1506 1268 1507 1269 1507 1241 1507 1241 1508 1269 1508 1270 1508 1241 1509 1270 1509 1242 1509 1264 1510 1271 1510 1265 1510 1265 1511 1271 1511 950 1511 1265 1512 950 1512 948 1512 952 1513 950 1513 1272 1513 1272 1514 950 1514 1271 1514 665 1515 1273 1515 667 1515 667 1516 1273 1516 1274 1516 1275 1517 1276 1517 1277 1517 1277 1518 1278 1518 1275 1518 1275 1519 1278 1519 1279 1519 1275 1520 1279 1520 1280 1520 1280 1521 1279 1521 1272 1521 1280 1522 1272 1522 1281 1522 1281 1523 1272 1523 1271 1523 1281 1524 1271 1524 1282 1524 1274 1525 1283 1525 667 1525 667 1526 1283 1526 1284 1526 667 1527 1284 1527 1276 1527 1276 1528 1284 1528 1285 1528 1276 1529 1285 1529 1277 1529 1286 1530 1287 1530 1288 1530 1286 1531 1288 1531 1289 1531 1289 1532 1288 1532 1290 1532 1289 1533 1290 1533 1291 1533 1291 1534 1290 1534 884 1534 1291 1535 884 1535 885 1535 730 1536 729 1536 1292 1536 1292 1537 729 1537 1231 1537 1292 1538 1231 1538 1293 1538 1292 1539 1293 1539 1294 1539 1295 1540 1296 1540 1297 1540 731 1541 1298 1541 735 1541 735 1542 1298 1542 1299 1542 735 1543 1299 1543 734 1543 734 1544 1299 1544 1300 1544 734 1545 1300 1545 732 1545 1301 1546 1302 1546 1303 1546 1297 1547 1304 1547 1305 1547 1305 1548 1304 1548 1306 1548 1305 1549 1306 1549 1307 1549 1308 1550 1296 1550 1309 1550 1309 1551 1296 1551 1295 1551 1309 1552 1295 1552 1294 1552 1308 1553 1310 1553 1296 1553 1296 1554 1310 1554 1311 1554 1296 1555 1311 1555 1297 1555 1297 1556 1311 1556 1301 1556 1297 1557 1301 1557 1304 1557 1304 1558 1301 1558 1303 1558 1304 1559 1303 1559 1306 1559 1307 1560 1300 1560 1305 1560 1305 1561 1300 1561 1299 1561 1305 1562 1299 1562 1297 1562 1297 1563 1299 1563 1298 1563 1297 1564 1298 1564 1295 1564 1295 1565 1298 1565 731 1565 1295 1566 731 1566 1294 1566 1294 1567 731 1567 730 1567 1294 1568 730 1568 1292 1568 720 98 732 98 1300 98 1302 1569 722 1569 1303 1569 1303 1570 722 1570 718 1570 1303 1571 718 1571 1306 1571 1306 1572 718 1572 720 1572 1306 98 720 98 1307 98 1307 1573 720 1573 1300 1573 1312 1574 1313 1574 1314 1574 926 1575 930 1575 1315 1575 1315 1576 930 1576 1316 1576 1315 1577 1316 1577 1317 1577 1313 1578 1312 1578 1316 1578 1316 1579 1312 1579 1318 1579 1316 1580 1318 1580 1317 1580 930 1581 933 1581 1316 1581 1316 1582 933 1582 1319 1582 1316 1583 1319 1583 1313 1583 1313 1584 1319 1584 1320 1584 1313 1585 1320 1585 1314 1585 1314 1586 1320 1586 1321 1586 933 1587 935 1587 1319 1587 1319 1588 935 1588 1322 1588 1319 1589 1322 1589 1320 1589 1320 1590 1322 1590 1323 1590 1320 1591 1323 1591 1321 1591 1321 1592 1323 1592 1237 1592 1324 1593 1325 1593 935 1593 935 1594 1325 1594 1322 1594 1326 1595 1323 1595 1327 1595 1327 1596 1323 1596 1322 1596 1327 1597 1322 1597 1328 1597 1328 1598 1322 1598 1325 1598 1232 1599 1233 1599 1329 1599 1329 1600 1233 1600 1234 1600 1329 1601 1234 1601 1326 1601 1326 1602 1234 1602 1235 1602 1326 1603 1235 1603 1323 1603 1323 1604 1235 1604 1236 1604 1323 1605 1236 1605 1237 1605 1329 1606 1308 1606 1309 1606 1231 1607 1232 1607 1293 1607 1293 1608 1232 1608 1329 1608 1293 1609 1329 1609 1294 1609 1294 1610 1329 1610 1309 1610 1329 1611 1326 1611 1308 1611 1308 1612 1326 1612 1330 1612 1308 1613 1330 1613 1331 1613 1331 1614 1330 1614 1332 1614 1332 1615 1330 1615 1333 1615 1333 1616 1330 1616 1334 1616 1333 1617 1334 1617 1335 1617 1335 1618 1334 1618 1336 1618 1335 1619 1336 1619 1337 1619 1324 1620 1336 1620 1325 1620 1325 1621 1336 1621 1334 1621 1325 1622 1334 1622 1328 1622 1328 1623 1334 1623 1330 1623 1328 1624 1330 1624 1327 1624 1327 1625 1330 1625 1326 1625 650 1626 649 1626 1338 1626 1339 1627 651 1627 650 1627 650 1628 1338 1628 1339 1628 1339 1629 1338 1629 883 1629 1339 1630 883 1630 882 1630 622 1631 624 1631 1340 1631 1340 1632 624 1632 626 1632 1340 1633 626 1633 1341 1633 1341 1634 626 1634 627 1634 1342 1635 1343 1635 1344 1635 1344 1636 1343 1636 1345 1636 1345 1637 1346 1637 1344 1637 1344 1638 1346 1638 1347 1638 1344 1639 1347 1639 1348 1639 1348 1640 1347 1640 1349 1640 1350 1641 1238 1641 1239 1641 1344 1642 1351 1642 1342 1642 1342 1643 1351 1643 1350 1643 1342 1644 1350 1644 1352 1644 1352 1645 1350 1645 1239 1645 1353 1646 1354 1646 1355 1646 1356 1647 1357 1647 1358 1647 1358 1648 1357 1648 1359 1648 1358 1649 1359 1649 1360 1649 1361 1650 1362 1650 1363 1650 1363 1651 1362 1651 1358 1651 1363 1652 1358 1652 1364 1652 1364 1653 1358 1653 1360 1653 1361 1654 1353 1654 1362 1654 1362 1655 1353 1655 1355 1655 1362 1656 1355 1656 1365 1656 1365 1657 1355 1657 1366 1657 1365 1658 1366 1658 1367 1658 1355 1659 1368 1659 1369 1659 1370 1660 1371 1660 1366 1660 1370 1661 1366 1661 1372 1661 1355 1662 1369 1662 1366 1662 1366 1663 1369 1663 1373 1663 1366 1664 1373 1664 1372 1664 1371 1665 1374 1665 1366 1665 1366 1666 1374 1666 1375 1666 1366 1667 1375 1667 1376 1667 1376 1668 1375 1668 1377 1668 1376 1669 1377 1669 1378 1669 1378 1670 1377 1670 1379 1670 1378 1671 1379 1671 1380 1671 1356 1672 1358 1672 1381 1672 1356 1673 1381 1673 1382 1673 1382 1674 1381 1674 918 1674 1382 1675 918 1675 920 1675 1383 1676 1384 1676 1385 1676 1385 1677 1384 1677 1386 1677 1385 1678 1386 1678 1387 1678 1387 1679 1386 1679 1388 1679 888 1680 887 1680 1386 1680 1386 1681 887 1681 1389 1681 1386 1682 1389 1682 1388 1682 1390 1683 1391 1683 1392 1683 1392 1684 1391 1684 1393 1684 1392 1685 1393 1685 1394 1685 1395 1686 1396 1686 1397 1686 1394 1687 1398 1687 1392 1687 1392 1688 1398 1688 1395 1688 1392 1689 1395 1689 1397 1689 1399 1690 1400 1690 1392 1690 1392 1691 1400 1691 1401 1691 1392 1692 1401 1692 1390 1692 1392 1693 1402 1693 1399 1693 1399 1694 1402 1694 1403 1694 1399 1695 1403 1695 1404 1695 1404 1696 1403 1696 1405 1696 1406 1697 1407 1697 1408 1697 1408 1698 1407 1698 1409 1698 1408 1699 1409 1699 1385 1699 1409 1700 1410 1700 1385 1700 1385 1701 1410 1701 1411 1701 1385 1702 1411 1702 1383 1702 1383 1703 1411 1703 1412 1703 1413 1704 1414 1704 1412 1704 1412 1705 1414 1705 1415 1705 1415 1706 1416 1706 1412 1706 1412 1707 1416 1707 1417 1707 1412 1708 1417 1708 1418 1708 1418 1709 1419 1709 1412 1709 1412 1710 1419 1710 1420 1710 1412 1711 1420 1711 1383 1711 1421 1712 1422 1712 1405 1712 1405 1713 1422 1713 1423 1713 1405 1714 1423 1714 1404 1714 1421 1715 1424 1715 1422 1715 1422 1716 1424 1716 1425 1716 1422 1717 1425 1717 1426 1717 1426 1718 1425 1718 1427 1718 1426 1719 1427 1719 1409 1719 1409 1720 1427 1720 1428 1720 1409 1721 1428 1721 1410 1721 738 1722 737 1722 1429 1722 1429 1723 737 1723 1430 1723 1429 1724 1430 1724 1431 1724 1431 1725 1430 1725 1399 1725 1399 1726 1430 1726 1432 1726 1399 1727 1432 1727 1400 1727 1433 1728 1434 1728 1435 1728 1435 1729 1434 1729 1436 1729 1435 1730 1436 1730 1437 1730 1438 1731 1439 1731 755 1731 755 1732 1439 1732 1440 1732 755 1733 1440 1733 756 1733 756 1734 1440 1734 1435 1734 756 1735 1435 1735 1441 1735 1441 1736 1435 1736 1437 1736 1442 1737 1443 1737 1444 1737 1444 1738 1445 1738 1442 1738 1442 1739 1445 1739 1446 1739 1442 1740 1446 1740 1447 1740 1447 1741 1446 1741 1448 1741 1447 1742 1448 1742 1438 1742 1438 1743 1448 1743 1449 1743 1438 1744 1449 1744 1439 1744 1450 1745 1451 1745 1452 1745 1452 1746 1451 1746 771 1746 1453 1747 1454 1747 1455 1747 1450 1748 1456 1748 1451 1748 1451 1749 1456 1749 1453 1749 1451 1750 1453 1750 1455 1750 771 1751 1451 1751 769 1751 769 1752 1451 1752 1457 1752 769 1753 1457 1753 1458 1753 1443 1754 1442 1754 1458 1754 1458 1755 1442 1755 1459 1755 1458 1756 1459 1756 769 1756 790 1757 1460 1757 1461 1757 1461 1758 1286 1758 1289 1758 1462 1759 956 1759 1463 1759 1463 1760 956 1760 955 1760 1463 1761 955 1761 1464 1761 1464 1762 955 1762 1465 1762 1466 1763 1467 1763 1468 1763 1468 1764 1467 1764 1469 1764 1468 1765 1469 1765 1470 1765 1470 1766 1469 1766 1471 1766 790 1767 1461 1767 885 1767 885 1768 1461 1768 1289 1768 885 1769 1289 1769 1291 1769 955 1770 1472 1770 1465 1770 1465 1771 1472 1771 1473 1771 1465 1772 1473 1772 1468 1772 1468 1773 1473 1773 1474 1773 1468 1774 1474 1774 1466 1774 781 1775 780 1775 1475 1775 1475 1776 1476 1776 781 1776 781 1777 1476 1777 1470 1777 781 1778 1470 1778 790 1778 790 1779 1470 1779 1471 1779 790 1780 1471 1780 1460 1780 1477 1781 1478 1781 1479 1781 1480 1782 1481 1782 1478 1782 939 1783 938 1783 1481 1783 1479 1784 1482 1784 1483 1784 1483 1785 1482 1785 1484 1785 1483 1786 1484 1786 1485 1786 1485 1787 1484 1787 1486 1787 1479 1788 1483 1788 1477 1788 1477 1789 1483 1789 1485 1789 1477 1790 1485 1790 1487 1790 1487 1791 1485 1791 1488 1791 1487 1792 1488 1792 1489 1792 1489 1793 1488 1793 1490 1793 1489 1794 1490 1794 1491 1794 1491 1795 1490 1795 1492 1795 1491 1796 1492 1796 1493 1796 1486 1797 1494 1797 1485 1797 1485 1798 1494 1798 1495 1798 1485 1799 1495 1799 1488 1799 1488 1800 1495 1800 1496 1800 1488 1801 1496 1801 1490 1801 1490 1802 1496 1802 1497 1802 1490 1803 1497 1803 1492 1803 1492 1804 1497 1804 780 1804 780 1805 782 1805 1492 1805 1492 1806 782 1806 776 1806 1492 1807 776 1807 1493 1807 1493 1808 776 1808 778 1808 1493 1809 778 1809 779 1809 1478 1810 1477 1810 1480 1810 1480 1811 1477 1811 1487 1811 1480 1812 1487 1812 1498 1812 1498 1813 1487 1813 1489 1813 1498 1814 1489 1814 1499 1814 1499 1815 1489 1815 1491 1815 1499 1816 1491 1816 1500 1816 1500 1817 1491 1817 1493 1817 1500 1818 1493 1818 1501 1818 1501 1819 1493 1819 779 1819 1501 1820 779 1820 773 1820 1481 1821 1480 1821 939 1821 939 1822 1480 1822 1498 1822 939 1823 1498 1823 942 1823 942 1824 1498 1824 1499 1824 942 1825 1499 1825 943 1825 943 1826 1499 1826 1500 1826 943 1827 1500 1827 940 1827 940 1828 1500 1828 1501 1828 940 1829 1501 1829 941 1829 941 1830 1501 1830 773 1830 941 1831 773 1831 772 1831 938 1832 1502 1832 1503 1832 938 1833 1503 1833 1481 1833 1481 1834 1503 1834 1504 1834 1481 1835 1504 1835 1478 1835 1478 1836 1504 1836 1505 1836 1478 1837 1505 1837 1479 1837 1479 1838 1505 1838 1506 1838 1479 1839 1506 1839 1482 1839 1507 1840 1506 1840 1508 1840 1508 1841 1506 1841 1505 1841 1508 1842 1505 1842 1509 1842 1509 1843 1505 1843 1504 1843 1509 1844 1504 1844 1510 1844 1510 1845 1504 1845 1503 1845 1510 1846 1503 1846 1511 1846 1511 1847 1503 1847 1502 1847 1512 1848 1507 1848 1513 1848 1513 1849 1507 1849 1508 1849 1513 1850 1508 1850 1514 1850 1514 1851 1508 1851 1509 1851 1514 1852 1509 1852 1515 1852 1515 1853 1509 1853 1510 1853 1515 1854 1510 1854 1516 1854 1516 1855 1510 1855 1511 1855 1517 1856 1512 1856 1518 1856 1518 1857 1512 1857 1513 1857 1518 1858 1513 1858 1519 1858 1519 1859 1513 1859 1514 1859 1519 1860 1514 1860 1520 1860 1520 1861 1514 1861 1515 1861 1520 1862 1515 1862 683 1862 683 1863 1515 1863 1516 1863 1521 1864 1522 1864 1523 1864 1524 1865 1523 1865 1525 1865 1526 1866 1522 1866 1527 1866 1527 1867 1522 1867 1528 1867 1527 1868 1528 1868 1529 1868 711 1869 1525 1869 1530 1869 1530 1870 1525 1870 1523 1870 1530 1871 1523 1871 1531 1871 1531 1872 1523 1872 1522 1872 1531 1873 1522 1873 1532 1873 1532 1874 1522 1874 1526 1874 685 1875 692 1875 1533 1875 691 1876 690 1876 1534 1876 689 1877 688 1877 1535 1877 694 1878 707 1878 1536 1878 706 1879 705 1879 1537 1879 1526 1880 1538 1880 1532 1880 1532 1881 1538 1881 1539 1881 1532 1882 1539 1882 1531 1882 1531 1883 1539 1883 1540 1883 1531 1884 1540 1884 1530 1884 1530 1885 1540 1885 1541 1885 1530 1886 1541 1886 711 1886 704 1887 703 1887 1541 1887 1541 1888 703 1888 712 1888 1541 1889 712 1889 711 1889 708 1890 704 1890 1542 1890 1542 1891 704 1891 1541 1891 1542 1892 1541 1892 1543 1892 1543 1893 1541 1893 1540 1893 1543 1894 1540 1894 1544 1894 1544 1895 1540 1895 1539 1895 1544 1896 1539 1896 1545 1896 1545 1897 1539 1897 1538 1897 705 1898 708 1898 1537 1898 1537 1899 708 1899 1542 1899 1537 1900 1542 1900 1546 1900 1546 1901 1542 1901 1543 1901 1546 1902 1543 1902 1547 1902 1547 1903 1543 1903 1544 1903 1547 1904 1544 1904 1548 1904 1548 1905 1544 1905 1545 1905 707 1906 706 1906 1536 1906 1536 1907 706 1907 1537 1907 1536 1908 1537 1908 1549 1908 1549 1909 1537 1909 1546 1909 1549 1910 1546 1910 1550 1910 1550 1911 1546 1911 1547 1911 1550 1912 1547 1912 1551 1912 1551 1913 1547 1913 1548 1913 695 1914 694 1914 1552 1914 1552 1915 694 1915 1536 1915 1552 1916 1536 1916 1553 1916 1553 1917 1536 1917 1549 1917 1553 1918 1549 1918 1554 1918 1554 1919 1549 1919 1550 1919 1554 1920 1550 1920 1555 1920 1555 1921 1550 1921 1551 1921 698 1922 697 1922 1552 1922 1552 1923 697 1923 696 1923 1552 1924 696 1924 695 1924 1556 1925 1557 1925 1558 1925 1558 1926 1557 1926 1559 1926 1558 1927 1559 1927 1560 1927 1560 1928 1559 1928 1561 1928 1560 1929 1561 1929 1562 1929 1562 1930 1561 1930 1563 1930 1555 1931 1556 1931 1554 1931 1554 1932 1556 1932 1558 1932 1554 1933 1558 1933 1553 1933 1553 1934 1558 1934 1560 1934 1553 1935 1560 1935 1552 1935 1552 1936 1560 1936 1562 1936 1552 1937 1562 1937 698 1937 698 1938 1562 1938 1563 1938 701 1939 700 1939 1563 1939 1563 1940 700 1940 699 1940 1563 1941 699 1941 698 1941 688 1942 701 1942 1535 1942 1535 1943 701 1943 1563 1943 1535 1944 1563 1944 1564 1944 1564 1945 1563 1945 1561 1945 1564 1946 1561 1946 1565 1946 1565 1947 1561 1947 1559 1947 1565 1948 1559 1948 1566 1948 1566 1949 1559 1949 1557 1949 690 1950 689 1950 1534 1950 1534 1951 689 1951 1535 1951 1534 1952 1535 1952 1567 1952 1567 1953 1535 1953 1564 1953 1567 1954 1564 1954 1568 1954 1568 1955 1564 1955 1565 1955 1568 1956 1565 1956 1569 1956 1569 1957 1565 1957 1566 1957 692 1958 691 1958 1533 1958 1533 1959 691 1959 1534 1959 1533 1960 1534 1960 1570 1960 1570 1961 1534 1961 1567 1961 1570 1962 1567 1962 1571 1962 1571 1963 1567 1963 1568 1963 1571 1964 1568 1964 1572 1964 1572 1965 1568 1965 1569 1965 684 1966 685 1966 1573 1966 1573 1967 685 1967 1533 1967 1573 1968 1533 1968 1574 1968 1574 1969 1533 1969 1570 1969 1574 1970 1570 1970 1575 1970 1575 1971 1570 1971 1571 1971 1575 1972 1571 1972 1576 1972 1576 1973 1571 1973 1572 1973 683 1974 684 1974 1520 1974 1520 1975 684 1975 1573 1975 1520 1976 1573 1976 1519 1976 1519 1977 1573 1977 1574 1977 1519 1978 1574 1978 1518 1978 1518 1979 1574 1979 1575 1979 1518 1980 1575 1980 1517 1980 1517 1981 1575 1981 1576 1981 1577 1982 1578 1982 1579 1982 1577 1983 1579 1983 1580 1983 1580 1984 1579 1984 1581 1984 1580 1985 1581 1985 1582 1985 1582 1986 1581 1986 1583 1986 1582 1987 1583 1987 1584 1987 1584 1988 1583 1988 1585 1988 1584 1989 1585 1989 1586 1989 1523 1990 1524 1990 1587 1990 1524 1991 1525 1991 1588 1991 1522 1992 1521 1992 1589 1992 1589 1993 1521 1993 1523 1993 1590 1994 1528 1994 1522 1994 1528 1995 1590 1995 1529 1995 1524 1996 1588 1996 1587 1996 1587 1997 1588 1997 1591 1997 1587 1998 1591 1998 1592 1998 1592 1999 1591 1999 1593 1999 1592 2000 1593 2000 1594 2000 1594 2001 1593 2001 1595 2001 1594 2002 1595 2002 1596 2002 1596 2003 1595 2003 1577 2003 1596 2004 1577 2004 1580 2004 1523 2005 1587 2005 1589 2005 1589 2006 1587 2006 1592 2006 1589 2007 1592 2007 1597 2007 1597 2008 1592 2008 1594 2008 1597 2009 1594 2009 1598 2009 1598 2010 1594 2010 1596 2010 1598 2011 1596 2011 1599 2011 1599 2012 1596 2012 1580 2012 1599 2013 1580 2013 1582 2013 1522 2014 1589 2014 1590 2014 1590 2015 1589 2015 1597 2015 1590 2016 1597 2016 1600 2016 1600 2017 1597 2017 1598 2017 1600 2018 1598 2018 1601 2018 1601 2019 1598 2019 1599 2019 1601 2020 1599 2020 1602 2020 1602 2021 1599 2021 1582 2021 1602 2022 1582 2022 1584 2022 1529 2023 1590 2023 1603 2023 1603 2024 1590 2024 1600 2024 1603 2025 1600 2025 1604 2025 1604 2026 1600 2026 1601 2026 1604 2027 1601 2027 1605 2027 1605 2028 1601 2028 1602 2028 1605 2029 1602 2029 1606 2029 1606 2030 1602 2030 1584 2030 1606 2031 1584 2031 1586 2031 1348 2032 1607 2032 1344 2032 1344 2033 1607 2033 1608 2033 1344 2034 1608 2034 1351 2034 613 2035 605 2035 1609 2035 1609 2036 605 2036 803 2036 1609 2037 803 2037 1610 2037 1610 2038 803 2038 802 2038 1610 2039 802 2039 1611 2039 1611 2040 802 2040 799 2040 1611 2041 799 2041 1612 2041 1612 2042 799 2042 794 2042 1612 2043 794 2043 1613 2043 609 2044 613 2044 1614 2044 1614 2045 613 2045 1609 2045 1614 2046 1609 2046 1615 2046 1615 2047 1609 2047 1610 2047 1615 2048 1610 2048 1616 2048 1616 2049 1610 2049 1611 2049 1616 2050 1611 2050 1617 2050 1617 2051 1611 2051 1612 2051 1617 2052 1612 2052 1618 2052 1618 2053 1612 2053 1613 2053 607 2054 609 2054 1619 2054 1619 2055 609 2055 1614 2055 1619 2056 1614 2056 1620 2056 1620 2057 1614 2057 1615 2057 1620 2058 1615 2058 1621 2058 1621 2059 1615 2059 1616 2059 1621 2060 1616 2060 1622 2060 1622 2061 1616 2061 1617 2061 1622 2062 1617 2062 1623 2062 1623 2063 1617 2063 1618 2063 1624 2064 1625 2064 1626 2064 1626 2065 1625 2065 1627 2065 1626 2066 1627 2066 1628 2066 1628 2067 1627 2067 1629 2067 1628 2068 1629 2068 1630 2068 1630 2069 1629 2069 1631 2069 1630 2070 1631 2070 1632 2070 1632 2071 1631 2071 1633 2071 1632 2072 1633 2072 608 2072 608 2073 1633 2073 610 2073 1623 2074 1624 2074 1622 2074 1622 2075 1624 2075 1626 2075 1622 2076 1626 2076 1621 2076 1621 2077 1626 2077 1628 2077 1621 2078 1628 2078 1620 2078 1620 2079 1628 2079 1630 2079 1620 2080 1630 2080 1619 2080 1619 2081 1630 2081 1632 2081 1619 2082 1632 2082 607 2082 607 2083 1632 2083 608 2083 612 2084 611 2084 1634 2084 1634 2085 611 2085 1635 2085 1634 2086 1635 2086 1636 2086 1636 2087 1635 2087 1637 2087 1636 2088 1637 2088 1638 2088 1638 2089 1637 2089 1639 2089 1639 2090 1637 2090 1640 2090 1639 2091 1640 2091 1641 2091 1642 2092 1643 2092 1644 2092 1644 2093 1643 2093 1641 2093 1641 2094 1640 2094 1645 2094 1641 2095 1645 2095 1644 2095 1642 2096 1644 2096 1646 2096 1646 2097 1644 2097 1647 2097 1646 2098 1647 2098 1648 2098 1648 2099 1647 2099 1649 2099 1648 2100 1649 2100 1650 2100 1650 2101 1649 2101 1651 2101 1650 2102 1651 2102 1652 2102 1653 2103 1654 2103 1655 2103 1655 2104 1656 2104 1653 2104 1653 2105 1656 2105 1657 2105 1653 2106 1657 2106 1658 2106 1627 2107 1625 2107 1659 2107 611 2108 610 2108 1635 2108 1635 2109 610 2109 1633 2109 1635 2110 1633 2110 1637 2110 1637 2111 1633 2111 1631 2111 1637 2112 1631 2112 1640 2112 1640 2113 1631 2113 1629 2113 1640 2114 1629 2114 1645 2114 1645 2115 1629 2115 1627 2115 1627 2116 1659 2116 1645 2116 1645 2117 1659 2117 1660 2117 1645 2118 1660 2118 1644 2118 1644 2119 1660 2119 1661 2119 1644 2120 1661 2120 1647 2120 1647 2121 1661 2121 1662 2121 1647 2122 1662 2122 1649 2122 1649 2123 1662 2123 1658 2123 1649 2124 1658 2124 1651 2124 1651 2125 1658 2125 1657 2125 1651 2126 1657 2126 1652 2126 1663 2127 1664 2127 1653 2127 1653 2128 1664 2128 1654 2128 1663 2129 370 2129 1664 2129 1664 2130 370 2130 369 2130 1665 2131 1345 2131 1343 2131 1239 2132 622 2132 1352 2132 1352 2133 622 2133 1340 2133 1352 2134 1340 2134 1342 2134 1342 2135 1340 2135 1341 2135 1342 2136 1341 2136 1343 2136 1343 2137 1341 2137 627 2137 1343 2138 627 2138 1665 2138 1666 2139 1667 2139 1668 2139 1668 2140 1667 2140 1669 2140 1668 2141 1669 2141 1670 2141 1671 2142 1667 2142 1672 2142 1672 2143 1667 2143 1666 2143 1672 2144 1666 2144 1673 2144 1674 2145 1675 2145 1669 2145 1669 2146 1675 2146 1676 2146 1669 2147 1676 2147 1670 2147 1674 2148 1669 2148 1677 2148 1677 2149 1669 2149 1667 2149 1677 2150 1667 2150 1678 2150 1678 2151 1667 2151 1671 2151 1678 2152 1671 2152 1679 2152 1679 2153 1680 2153 1678 2153 1678 2154 1680 2154 1681 2154 1678 2155 1681 2155 1677 2155 1677 2156 1681 2156 1682 2156 1677 2157 1682 2157 1674 2157 1674 2158 1682 2158 1683 2158 1674 2159 1683 2159 1684 2159 1685 2160 1676 2160 1686 2160 1686 2161 1676 2161 1675 2161 1686 2162 1675 2162 1687 2162 1687 2163 1675 2163 1674 2163 1687 2164 1674 2164 1688 2164 1688 2165 1674 2165 1684 2165 1688 2166 1684 2166 1689 2166 1690 2167 1691 2167 1692 2167 1693 2168 1694 2168 1695 2168 1695 2169 1694 2169 1696 2169 1697 2170 1673 2170 1698 2170 1698 2171 1673 2171 1699 2171 1699 2172 1700 2172 1698 2172 1698 2173 1700 2173 1701 2173 1698 2174 1701 2174 1692 2174 1692 2175 1701 2175 1702 2175 1692 2176 1702 2176 1690 2176 1703 2177 1697 2177 1704 2177 1704 2178 1697 2178 1698 2178 1704 2179 1698 2179 1705 2179 1705 2180 1698 2180 1692 2180 1706 2181 1705 2181 1707 2181 1707 2182 1705 2182 1692 2182 1707 2183 1692 2183 1694 2183 1694 2184 1692 2184 1691 2184 1694 2185 1691 2185 1696 2185 1708 2186 1703 2186 1709 2186 1709 2187 1703 2187 1704 2187 1709 2188 1704 2188 1710 2188 1710 2189 1704 2189 1705 2189 1710 2190 1705 2190 1711 2190 1711 2191 1705 2191 1706 2191 1706 2192 1712 2192 1711 2192 1711 2193 1712 2193 1713 2193 1711 2194 1713 2194 1710 2194 1714 2195 1708 2195 1713 2195 1713 2196 1708 2196 1709 2196 1713 2197 1709 2197 1710 2197 1715 2198 1714 2198 1716 2198 1716 2199 1714 2199 1713 2199 1716 2200 1713 2200 1717 2200 1717 2201 1713 2201 1712 2201 1718 2202 1715 2202 1719 2202 1719 2203 1715 2203 1716 2203 1719 2204 1716 2204 1720 2204 1720 2205 1716 2205 1717 2205 1721 2206 1722 2206 1723 2206 1724 2207 1725 2207 1726 2207 1723 2208 1722 2208 1726 2208 1726 2209 1722 2209 1727 2209 1726 2210 1727 2210 1724 2210 1728 2211 1729 2211 1723 2211 1723 2212 1729 2212 1730 2212 1723 2213 1730 2213 1721 2213 1726 2214 1718 2214 1723 2214 1723 2215 1718 2215 1719 2215 1723 2216 1719 2216 1728 2216 1728 2217 1719 2217 1720 2217 1731 2218 1732 2218 1733 2218 1734 2219 1729 2219 1735 2219 1734 2220 1735 2220 1736 2220 1727 2221 1722 2221 1737 2221 1737 2222 1722 2222 1721 2222 1737 2223 1721 2223 1734 2223 1734 2224 1721 2224 1730 2224 1734 2225 1730 2225 1729 2225 1738 2226 1725 2226 1737 2226 1737 2227 1725 2227 1724 2227 1737 2228 1724 2228 1727 2228 1739 2229 1740 2229 1741 2229 1741 2230 1740 2230 1736 2230 1741 2231 1736 2231 1742 2231 1742 2232 1736 2232 1735 2232 1740 2233 1731 2233 1736 2233 1736 2234 1731 2234 1733 2234 1736 2235 1733 2235 1734 2235 1734 2236 1733 2236 1743 2236 1734 2237 1743 2237 1737 2237 1737 2238 1743 2238 1744 2238 1737 2239 1744 2239 1738 2239 1738 2240 1744 2240 1745 2240 1732 2241 1746 2241 1733 2241 1733 2242 1746 2242 1747 2242 1733 2243 1747 2243 1743 2243 1743 2244 1747 2244 1748 2244 1743 2245 1748 2245 1744 2245 1744 2246 1748 2246 1749 2246 1744 2247 1749 2247 1745 2247 1745 2248 1749 2248 1750 2248 1746 2249 1751 2249 1747 2249 1747 2250 1751 2250 1752 2250 1747 2251 1752 2251 1748 2251 1748 2252 1752 2252 1753 2252 1748 2253 1753 2253 1749 2253 1749 2254 1753 2254 1754 2254 1749 2255 1754 2255 1750 2255 1750 2256 1754 2256 1755 2256 638 2257 651 2257 1339 2257 638 2258 1339 2258 1756 2258 1756 2259 1339 2259 882 2259 1756 2260 882 2260 1757 2260 969 2261 1758 2261 1759 2261 969 2262 1759 2262 968 2262 968 2263 1759 2263 364 2263 968 2264 364 2264 366 2264 1760 2265 1761 2265 1762 2265 1763 2266 1764 2266 1762 2266 1763 2267 1762 2267 1765 2267 1760 2268 1762 2268 1766 2268 1767 2269 1768 2269 1769 2269 1767 2270 1769 2270 1770 2270 1769 2271 1771 2271 1770 2271 1770 2272 1771 2272 1772 2272 1770 2273 1772 2273 1773 2273 1773 2274 1772 2274 1774 2274 1773 2275 1774 2275 1764 2275 1764 2276 1774 2276 1775 2276 1764 2277 1775 2277 1762 2277 1762 2278 1775 2278 1776 2278 1762 2279 1776 2279 1766 2279 1768 2280 1767 2280 1777 2280 1777 2281 1767 2281 1778 2281 1777 2282 1778 2282 1302 2282 1302 2283 1778 2283 1779 2283 1302 2284 1779 2284 722 2284 722 2285 1779 2285 1780 2285 722 2286 1780 2286 725 2286 725 2287 1780 2287 1781 2287 725 2288 1781 2288 723 2288 832 2289 833 2289 1782 2289 832 2290 1782 2290 831 2290 836 2291 825 2291 1782 2291 1782 2292 825 2292 824 2292 1782 2293 824 2293 831 2293 1740 2294 1739 2294 1783 2294 251 2295 1751 2295 1746 2295 1740 2296 1783 2296 1731 2296 1731 2297 1783 2297 1784 2297 1731 2298 1784 2298 1732 2298 1732 2299 1784 2299 1785 2299 1732 2300 1785 2300 1746 2300 1746 2301 1785 2301 1786 2301 1746 2302 1786 2302 251 2302 850 2303 851 2303 1787 2303 1788 2304 1789 2304 1790 2304 1791 2305 574 2305 573 2305 578 2306 850 2306 573 2306 573 2307 850 2307 1787 2307 573 2308 1787 2308 1791 2308 1791 2309 1787 2309 1792 2309 851 2310 852 2310 1787 2310 1787 2311 852 2311 1788 2311 1787 2312 1788 2312 1792 2312 1792 2313 1788 2313 1790 2313 847 2314 1789 2314 848 2314 848 2315 1789 2315 1788 2315 848 2316 1788 2316 849 2316 849 2317 1788 2317 852 2317 1793 2318 1794 2318 576 2318 576 2319 1794 2319 577 2319 1795 2320 1796 2320 1797 2320 1797 2321 1798 2321 1795 2321 1795 2322 1798 2322 1799 2322 1795 2323 1799 2323 1793 2323 1793 2324 1799 2324 1800 2324 1793 2325 1800 2325 1794 2325 1790 2326 1796 2326 1792 2326 1792 2327 1796 2327 1795 2327 1792 2328 1795 2328 1791 2328 1791 2329 1795 2329 1793 2329 1791 2330 1793 2330 574 2330 574 2331 1793 2331 576 2331 1797 2332 854 2332 1798 2332 1798 2333 854 2333 853 2333 1798 2334 853 2334 1799 2334 1799 2335 853 2335 863 2335 1799 2336 863 2336 1800 2336 863 2337 864 2337 1800 2337 1800 2338 864 2338 865 2338 1800 2339 865 2339 1794 2339 865 2340 862 2340 1794 2340 1794 2341 862 2341 569 2341 1794 2342 569 2342 577 2342 1801 2343 1802 2343 1803 2343 1804 2344 1805 2344 1806 2344 1806 2345 1805 2345 1807 2345 1807 2346 1808 2346 1809 2346 1809 2347 1808 2347 1810 2347 1809 2348 1810 2348 1811 2348 1801 2349 1812 2349 886 2349 886 2350 1812 2350 1813 2350 886 2351 1813 2351 887 2351 1802 2352 1801 2352 1814 2352 1811 2353 1815 2353 1809 2353 1809 2354 1815 2354 1816 2354 1809 2355 1816 2355 1817 2355 1817 2356 1816 2356 1803 2356 1801 2357 886 2357 1814 2357 1814 2358 886 2358 893 2358 1814 2359 893 2359 1818 2359 1818 2360 893 2360 892 2360 1818 2361 892 2361 1819 2361 1819 2362 892 2362 890 2362 1819 2363 890 2363 1820 2363 1820 2364 890 2364 889 2364 1820 2365 889 2365 1821 2365 1803 2366 1802 2366 1817 2366 1817 2367 1802 2367 1814 2367 1817 2368 1814 2368 1822 2368 1822 2369 1814 2369 1818 2369 1822 2370 1818 2370 1823 2370 1823 2371 1818 2371 1819 2371 1823 2372 1819 2372 1824 2372 1824 2373 1819 2373 1820 2373 1824 2374 1820 2374 1825 2374 1825 2375 1820 2375 1821 2375 1825 2376 1821 2376 1826 2376 1807 2377 1809 2377 1806 2377 1806 2378 1809 2378 1817 2378 1806 2379 1817 2379 1827 2379 1827 2380 1817 2380 1822 2380 1827 2381 1822 2381 1828 2381 1828 2382 1822 2382 1823 2382 1828 2383 1823 2383 1829 2383 1829 2384 1823 2384 1824 2384 1829 2385 1824 2385 1830 2385 1830 2386 1824 2386 1825 2386 1830 2387 1825 2387 1831 2387 1831 2388 1825 2388 1826 2388 1831 2389 1826 2389 1832 2389 1331 2390 1332 2390 1833 2390 1310 2391 1834 2391 1311 2391 1311 2392 1834 2392 1301 2392 1302 2393 1301 2393 1835 2393 1835 2394 1301 2394 1834 2394 1835 2395 1834 2395 1836 2395 1836 2396 1834 2396 1310 2396 1836 2397 1310 2397 1833 2397 1833 2398 1310 2398 1308 2398 1833 2399 1308 2399 1331 2399 1771 2400 1769 2400 1836 2400 1836 2401 1769 2401 1768 2401 1836 2402 1768 2402 1835 2402 1835 2403 1768 2403 1777 2403 1835 2404 1777 2404 1302 2404 934 98 1837 98 935 98 935 2405 1837 2405 1838 2405 1839 98 1324 98 1840 98 1840 98 1324 98 935 98 1840 98 935 98 1841 98 1841 98 935 98 1838 98 1842 2406 1337 2406 1843 2406 1843 2407 1337 2407 1336 2407 1843 2408 1336 2408 1844 2408 1844 2409 1336 2409 1324 2409 1844 2410 1324 2410 1839 2410 1335 2411 1337 2411 1845 2411 1845 2412 1846 2412 1335 2412 1335 2413 1846 2413 1847 2413 1335 2414 1847 2414 1333 2414 1333 2415 1847 2415 1848 2415 1333 2416 1848 2416 1332 2416 1849 2417 1850 2417 1851 2417 1851 2418 1850 2418 1852 2418 1851 2419 1852 2419 1853 2419 1853 2420 1852 2420 1854 2420 1853 2421 1854 2421 1855 2421 1855 2422 1854 2422 1856 2422 1855 2423 1856 2423 1857 2423 743 2424 899 2424 1858 2424 743 2425 1858 2425 1859 2425 1859 2426 1858 2426 1860 2426 1859 2427 1860 2427 1861 2427 1861 2428 1860 2428 1862 2428 1861 2429 1862 2429 1863 2429 1863 2430 1862 2430 1864 2430 1863 2431 1864 2431 1849 2431 1849 2432 1864 2432 1865 2432 1849 2433 1865 2433 1850 2433 1866 2434 914 2434 765 2434 1867 2435 1868 2435 1869 2435 1869 2436 1868 2436 1870 2436 1869 2437 1870 2437 1871 2437 1871 2438 1870 2438 1872 2438 1871 2439 1872 2439 1873 2439 1873 2440 1872 2440 1874 2440 1873 2441 1874 2441 1875 2441 1875 2442 1874 2442 1876 2442 1875 2443 1876 2443 1877 2443 1866 2444 765 2444 1878 2444 1869 2445 1879 2445 1867 2445 1867 2446 1879 2446 1880 2446 1867 2447 1880 2447 1881 2447 1881 2448 1880 2448 1878 2448 1881 2449 1878 2449 1882 2449 1882 2450 1878 2450 765 2450 1883 2451 1884 2451 1885 2451 1886 2452 1887 2452 1884 2452 915 2453 914 2453 1888 2453 1889 2454 911 2454 910 2454 1889 2455 910 2455 1890 2455 1890 2456 910 2456 909 2456 1890 2457 909 2457 1891 2457 1891 2458 909 2458 908 2458 1891 2459 908 2459 1892 2459 1892 2460 908 2460 912 2460 1892 2461 912 2461 1893 2461 1893 2462 912 2462 913 2462 1893 2463 913 2463 1894 2463 1894 2464 913 2464 917 2464 1894 2465 917 2465 1895 2465 1895 2466 917 2466 916 2466 1895 2467 916 2467 1896 2467 1896 2468 916 2468 915 2468 1896 2469 915 2469 1886 2469 1886 2470 915 2470 1888 2470 1886 2471 1888 2471 1887 2471 1884 2472 1883 2472 1886 2472 1886 2473 1883 2473 1897 2473 1886 2474 1897 2474 1896 2474 1896 2475 1897 2475 1898 2475 1896 2476 1898 2476 1895 2476 1895 2477 1898 2477 1899 2477 1895 2478 1899 2478 1894 2478 1894 2479 1899 2479 1900 2479 1894 2480 1900 2480 1893 2480 1893 2481 1900 2481 1901 2481 1893 2482 1901 2482 1892 2482 1892 2483 1901 2483 1902 2483 1892 2484 1902 2484 1891 2484 1891 2485 1902 2485 1903 2485 1891 2486 1903 2486 1890 2486 1890 2487 1903 2487 1904 2487 1890 2488 1904 2488 1889 2488 1885 2489 1905 2489 1883 2489 1883 2490 1905 2490 1906 2490 1883 2491 1906 2491 1897 2491 1897 2492 1906 2492 1907 2492 1897 2493 1907 2493 1898 2493 1898 2494 1907 2494 1908 2494 1898 2495 1908 2495 1899 2495 1899 2496 1908 2496 1909 2496 1899 2497 1909 2497 1900 2497 1900 2498 1909 2498 1910 2498 1900 2499 1910 2499 1901 2499 1901 2500 1910 2500 1911 2500 1901 2501 1911 2501 1902 2501 1902 2502 1911 2502 1912 2502 1902 2503 1912 2503 1903 2503 1903 2504 1912 2504 1913 2504 1903 2505 1913 2505 1904 2505 1913 2506 1832 2506 1904 2506 1904 2507 1832 2507 1826 2507 1904 2508 1826 2508 1889 2508 1889 2509 1826 2509 1821 2509 1889 2510 1821 2510 911 2510 911 2511 1821 2511 889 2511 1717 2512 1712 2512 1914 2512 1915 2513 1739 2513 1916 2513 1916 2514 1739 2514 1741 2514 1916 2515 1741 2515 1742 2515 1917 2516 1783 2516 1918 2516 1918 2517 1783 2517 1739 2517 1918 2518 1739 2518 1919 2518 1919 2519 1739 2519 1915 2519 1920 2520 1921 2520 1922 2520 1922 2521 1921 2521 1916 2521 1922 2522 1916 2522 1923 2522 1742 2523 1735 2523 1916 2523 1916 2524 1735 2524 1729 2524 1916 2525 1729 2525 1923 2525 1923 2526 1729 2526 1728 2526 1923 2527 1728 2527 1924 2527 1924 2528 1728 2528 1914 2528 1914 2529 1728 2529 1720 2529 1914 2530 1720 2530 1717 2530 1925 98 1926 98 1663 98 1927 2531 1928 2531 1929 2531 1929 98 1928 98 1930 98 1653 2532 1931 2532 1663 2532 1663 2533 1931 2533 1932 2533 1663 98 1932 98 1925 98 1926 2534 1933 2534 1663 2534 1663 2535 1933 2535 1934 2535 1663 98 1934 98 1935 98 1930 98 1936 98 1929 98 1929 2536 1936 2536 1935 2536 1929 2537 1935 2537 1937 2537 1937 2538 1935 2538 1934 2538 1938 2539 1939 2539 1940 2539 1940 2540 1939 2540 1941 2540 1940 2541 1941 2541 1942 2541 1942 2542 1941 2542 1943 2542 1942 2543 1943 2543 1944 2543 1944 2544 1943 2544 1945 2544 1944 2545 1945 2545 1946 2545 1946 2546 1945 2546 1947 2546 1948 2547 1928 2547 1949 2547 1949 2548 1928 2548 1950 2548 1949 2549 1950 2549 1951 2549 1951 2550 1950 2550 1952 2550 1951 2551 1952 2551 1953 2551 1953 2552 1952 2552 1954 2552 1953 2553 1954 2553 1955 2553 1955 2554 1954 2554 1956 2554 1955 2555 1956 2555 1957 2555 1957 2556 1956 2556 1958 2556 1957 2557 1958 2557 1959 2557 1959 2558 1958 2558 1960 2558 1959 2559 1960 2559 1947 2559 1947 2560 1960 2560 1961 2560 1947 2561 1961 2561 1946 2561 1948 2562 1962 2562 1928 2562 1928 2563 1962 2563 1963 2563 1928 2564 1963 2564 1930 2564 1964 2565 1665 2565 1965 2565 1965 2566 1665 2566 627 2566 1965 2567 627 2567 1966 2567 1966 2568 627 2568 630 2568 1966 2569 630 2569 631 2569 1967 2570 1968 2570 1969 2570 1967 2571 1969 2571 1970 2571 1970 2572 1969 2572 1971 2572 1970 2573 1971 2573 1972 2573 1972 2574 1971 2574 1973 2574 1972 2575 1973 2575 1974 2575 1974 2576 1973 2576 1975 2576 1974 2577 1975 2577 1976 2577 1976 2578 1975 2578 1977 2578 1976 2579 1977 2579 1978 2579 1978 2580 1977 2580 1979 2580 1978 2581 1979 2581 1980 2581 1980 2582 1979 2582 1981 2582 1980 2583 1981 2583 1982 2583 1982 2584 1981 2584 1983 2584 1982 2585 1983 2585 1984 2585 1984 2586 1983 2586 1985 2586 1984 2587 1985 2587 1986 2587 1986 2588 1985 2588 1987 2588 1986 2589 1987 2589 1988 2589 1988 2590 1987 2590 1989 2590 1988 2591 1989 2591 1990 2591 1990 2592 1989 2592 1991 2592 1990 2593 1991 2593 1992 2593 1992 2594 1991 2594 1993 2594 1992 2595 1993 2595 1994 2595 1994 2596 1993 2596 1995 2596 1994 2597 1995 2597 1996 2597 1996 2598 1995 2598 1997 2598 1996 2599 1997 2599 1998 2599 1998 2600 1997 2600 1999 2600 1998 2601 1999 2601 2000 2601 2000 2602 1999 2602 2001 2602 2000 2603 2001 2603 2002 2603 2002 2604 2001 2604 2003 2604 2002 2605 2003 2605 2004 2605 2004 2606 2003 2606 2005 2606 2004 2607 2005 2607 2006 2607 2006 2608 2005 2608 2007 2608 2006 2609 2007 2609 2008 2609 2008 2610 2007 2610 2009 2610 2008 2611 2009 2611 2010 2611 2010 2612 2009 2612 2011 2612 2010 2613 2011 2613 2012 2613 2012 2614 2011 2614 2013 2614 2012 2615 2013 2615 2014 2615 2014 2616 2013 2616 2015 2616 2014 2617 2015 2617 2016 2617 2016 2618 2015 2618 2017 2618 2016 2619 2017 2619 2018 2619 2018 2620 2017 2620 2019 2620 2018 2621 2019 2621 2020 2621 2021 2622 1964 2622 1965 2622 2021 2623 2022 2623 2023 2623 2023 2624 2022 2624 2024 2624 2025 2625 2026 2625 2027 2625 2028 2626 2029 2626 2022 2626 2022 2627 2029 2627 2030 2627 2022 2628 2030 2628 2024 2628 2021 2629 1965 2629 2022 2629 2022 2630 1965 2630 1966 2630 2022 2631 1966 2631 2031 2631 2032 2632 2033 2632 2031 2632 2031 2633 2033 2633 2025 2633 2031 2634 2025 2634 2022 2634 2022 2635 2025 2635 2027 2635 2022 2636 2027 2636 2028 2636 2034 2637 2020 2637 2032 2637 2034 2638 2032 2638 2035 2638 2035 2639 2032 2639 2031 2639 2035 2640 2031 2640 2036 2640 2036 2641 2031 2641 1966 2641 2036 2642 1966 2642 631 2642 2037 2643 2038 2643 2039 2643 2040 2644 2041 2644 2042 2644 2041 2645 2040 2645 2043 2645 2044 2646 2045 2646 2046 2646 2040 2647 2047 2647 2043 2647 2043 2648 2047 2648 2048 2648 2043 2649 2048 2649 2049 2649 2049 2650 2048 2650 2050 2650 2049 2651 2050 2651 2051 2651 2051 2652 2050 2652 2052 2652 2051 2653 2052 2653 2053 2653 2053 2654 2052 2654 2054 2654 2053 2655 2054 2655 2055 2655 2055 2656 2054 2656 1968 2656 2055 2657 1968 2657 1967 2657 1967 2658 2044 2658 2055 2658 2055 2659 2044 2659 2046 2659 2055 2660 2046 2660 2053 2660 2053 2661 2046 2661 2056 2661 2053 2662 2056 2662 2051 2662 2051 2663 2056 2663 2057 2663 2051 2664 2057 2664 2049 2664 2049 2665 2057 2665 2058 2665 2049 2666 2058 2666 2043 2666 2043 2667 2058 2667 2059 2667 2043 2668 2059 2668 2041 2668 2041 2669 2059 2669 2038 2669 2041 2670 2038 2670 2042 2670 2042 2671 2038 2671 2037 2671 2046 2672 2045 2672 2060 2672 2061 2673 2039 2673 2038 2673 2062 2674 2063 2674 2061 2674 2060 2675 2064 2675 2065 2675 2065 2676 2064 2676 2066 2676 2065 2677 2066 2677 2067 2677 2038 2678 2059 2678 2061 2678 2061 2679 2059 2679 2065 2679 2061 2680 2065 2680 2062 2680 2062 2681 2065 2681 2067 2681 2062 2682 2067 2682 2068 2682 2059 2683 2058 2683 2065 2683 2065 2684 2058 2684 2057 2684 2065 2685 2057 2685 2060 2685 2060 2686 2057 2686 2056 2686 2060 2687 2056 2687 2046 2687 2069 2688 2070 2688 2071 2688 2072 2689 2073 2689 2074 2689 2075 2690 2076 2690 2077 2690 2063 2691 2062 2691 2078 2691 2079 2692 2080 2692 2081 2692 2062 2693 2068 2693 2082 2693 2062 2694 2082 2694 2078 2694 2078 2695 2082 2695 2083 2695 2078 2696 2083 2696 2084 2696 2085 2697 2086 2697 2087 2697 2088 2698 2089 2698 2070 2698 2070 2699 2089 2699 2090 2699 2070 2700 2090 2700 2071 2700 2071 2701 2090 2701 2091 2701 2092 2702 2093 2702 2072 2702 2094 2703 2095 2703 2096 2703 2096 2704 2095 2704 2097 2704 2098 2705 2099 2705 2100 2705 2100 2706 2099 2706 2101 2706 2087 2707 2063 2707 2085 2707 2085 2708 2063 2708 2078 2708 2085 2709 2078 2709 2081 2709 2081 2710 2078 2710 2084 2710 2081 2711 2084 2711 2079 2711 2102 2712 2103 2712 2080 2712 2080 2713 2103 2713 2069 2713 2080 2714 2069 2714 2081 2714 2081 2715 2069 2715 2071 2715 2081 2716 2071 2716 2085 2716 2085 2717 2071 2717 2091 2717 2085 2718 2091 2718 2086 2718 2073 2719 2075 2719 2074 2719 2074 2720 2075 2720 2077 2720 2074 2721 2077 2721 2104 2721 2104 2722 2077 2722 2105 2722 2104 2723 2105 2723 2096 2723 2096 2724 2105 2724 2106 2724 2096 2725 2106 2725 2094 2725 2094 2726 2106 2726 2107 2726 2094 2727 2107 2727 2108 2727 2108 2728 2107 2728 2109 2728 2072 2729 2074 2729 2092 2729 2092 2730 2074 2730 2104 2730 2092 2731 2104 2731 2110 2731 2110 2732 2104 2732 2096 2732 2110 2733 2096 2733 2111 2733 2111 2734 2096 2734 2097 2734 2111 2735 2097 2735 2112 2735 2076 2736 2113 2736 2077 2736 2077 2737 2113 2737 2114 2737 2077 2738 2114 2738 2105 2738 2105 2739 2114 2739 2115 2739 2105 2740 2115 2740 2106 2740 2106 2741 2115 2741 2116 2741 2106 2742 2116 2742 2107 2742 2107 2743 2116 2743 2100 2743 2107 2744 2100 2744 2109 2744 2109 2745 2100 2745 2101 2745 2113 2746 2117 2746 2114 2746 2114 2747 2117 2747 2088 2747 2114 2748 2088 2748 2115 2748 2115 2749 2088 2749 2070 2749 2115 2750 2070 2750 2116 2750 2116 2751 2070 2751 2069 2751 2116 2752 2069 2752 2100 2752 2100 2753 2069 2753 2103 2753 2100 2754 2103 2754 2098 2754 2098 2755 2103 2755 2102 2755 2098 2756 2102 2756 2118 2756 2119 2757 1346 2757 1345 2757 1665 2758 1964 2758 1345 2758 1345 2759 1964 2759 2120 2759 1345 2760 2120 2760 2119 2760 2119 2761 2120 2761 2121 2761 2119 2762 2121 2762 2122 2762 1607 2763 1348 2763 1349 2763 2119 2764 2122 2764 2123 2764 2124 2765 2125 2765 1608 2765 1608 2766 1607 2766 2124 2766 2124 2767 1607 2767 1349 2767 2124 2768 1349 2768 2123 2768 2123 2769 1349 2769 1347 2769 2123 2770 1347 2770 2119 2770 2119 2771 1347 2771 1346 2771 2126 2772 2127 2772 2128 2772 2128 2773 2127 2773 2129 2773 2128 2774 2129 2774 2130 2774 2130 2775 2129 2775 2131 2775 2130 2776 2131 2776 1585 2776 1585 2777 2131 2777 2132 2777 1585 2778 2132 2778 1586 2778 2133 2779 2134 2779 2128 2779 2128 2780 2134 2780 2135 2780 2128 2781 2135 2781 2126 2781 2128 2782 1939 2782 1938 2782 1938 2783 2136 2783 2128 2783 2128 2784 2136 2784 2137 2784 2128 2785 2137 2785 2138 2785 2138 2786 2139 2786 2128 2786 2128 2787 2139 2787 2140 2787 2128 2788 2140 2788 2133 2788 2141 2789 2142 2789 2143 2789 2141 2790 2143 2790 1366 2790 1366 2791 2143 2791 2144 2791 1366 2792 2144 2792 1367 2792 2142 2793 2141 2793 2145 2793 2145 2794 2141 2794 2146 2794 2145 2795 2146 2795 2147 2795 2147 2796 2146 2796 2148 2796 2148 2797 2146 2797 2149 2797 2148 2798 2149 2798 2150 2798 2150 2799 2149 2799 2151 2799 2151 2800 2149 2800 2152 2800 2151 2801 2152 2801 2153 2801 2154 2802 2155 2802 2156 2802 2156 2803 2155 2803 2157 2803 2156 2804 2157 2804 2158 2804 2158 2805 2157 2805 2159 2805 2158 2806 2159 2806 2160 2806 2160 2807 2159 2807 2161 2807 2160 2808 2161 2808 1378 2808 1378 2809 2161 2809 1376 2809 2155 2810 2152 2810 2157 2810 2157 2811 2152 2811 2149 2811 2157 2812 2149 2812 2159 2812 2159 2813 2149 2813 2146 2813 2159 2814 2146 2814 2161 2814 2161 2815 2146 2815 2141 2815 2161 2816 2141 2816 1376 2816 1376 2817 2141 2817 1366 2817 2162 2818 2163 2818 2164 2818 2164 2819 2163 2819 2165 2819 2164 2820 2165 2820 2166 2820 2166 2821 2165 2821 2167 2821 2166 2822 2167 2822 2168 2822 2169 2823 2170 2823 2164 2823 2164 2824 2170 2824 2171 2824 2164 2825 2171 2825 2162 2825 2172 2826 2173 2826 2169 2826 2169 2827 2173 2827 2174 2827 2169 2828 2174 2828 2170 2828 1365 2829 1367 2829 2175 2829 1365 2830 2175 2830 2176 2830 2176 2831 2175 2831 2177 2831 2176 2832 2177 2832 2178 2832 2166 2833 2179 2833 2164 2833 2164 2834 2179 2834 2180 2834 2164 2835 2180 2835 2169 2835 2169 2836 2180 2836 2181 2836 2169 2837 2181 2837 2172 2837 2172 2838 2181 2838 2176 2838 2172 2839 2176 2839 2182 2839 2182 2840 2176 2840 2178 2840 1362 2841 1365 2841 2183 2841 2183 2842 1365 2842 2176 2842 2183 2843 2176 2843 2184 2843 2184 2844 2176 2844 2181 2844 2184 2845 2181 2845 2185 2845 2185 2846 2181 2846 2180 2846 2185 2847 2180 2847 2186 2847 2186 2848 2180 2848 2179 2848 1358 2849 1362 2849 2187 2849 2187 2850 1362 2850 2183 2850 2187 2851 2183 2851 2188 2851 2188 2852 2183 2852 2184 2852 2188 2853 2184 2853 2189 2853 2189 2854 2184 2854 2185 2854 2189 2855 2185 2855 2190 2855 2190 2856 2185 2856 2186 2856 1381 2857 1358 2857 2191 2857 2191 2858 1358 2858 2187 2858 2191 2859 2187 2859 2192 2859 2192 2860 2187 2860 2188 2860 2192 2861 2188 2861 2193 2861 2193 2862 2188 2862 2189 2862 2193 2863 2189 2863 2194 2863 2194 2864 2189 2864 2190 2864 918 2865 1381 2865 2195 2865 2195 2866 1381 2866 2191 2866 2195 2867 2191 2867 2196 2867 2196 2868 2191 2868 2192 2868 2196 2869 2192 2869 2197 2869 2197 2870 2192 2870 2193 2870 2197 2871 2193 2871 2198 2871 2198 2872 2193 2872 2194 2872 2199 2873 2200 2873 2201 2873 1921 2874 2202 2874 1916 2874 1916 2875 2202 2875 2203 2875 1917 2876 1918 2876 2204 2876 2204 2877 1918 2877 1919 2877 2204 2878 1919 2878 2205 2878 2205 2879 1919 2879 1915 2879 2205 2880 1915 2880 2206 2880 2206 2881 1915 2881 1916 2881 2206 2882 1916 2882 2199 2882 2199 2883 1916 2883 2203 2883 2199 2884 2203 2884 2200 2884 1917 2885 2204 2885 2207 2885 2207 2886 2204 2886 2205 2886 2207 2887 2205 2887 2208 2887 2208 2888 2205 2888 2206 2888 2208 2889 2206 2889 2209 2889 2209 2890 2206 2890 2199 2890 2209 2891 2199 2891 2210 2891 2210 2892 2199 2892 2201 2892 2210 2893 2201 2893 2211 2893 2200 2894 2203 2894 2212 2894 2212 2895 2203 2895 2202 2895 2213 2896 2211 2896 2201 2896 2202 2897 1921 2897 2214 2897 2214 2898 1921 2898 1920 2898 2215 2899 2216 2899 2217 2899 2217 2900 2216 2900 2218 2900 2217 2901 2218 2901 2219 2901 2219 2902 2218 2902 2220 2902 2219 2903 2220 2903 2221 2903 2221 2904 2220 2904 2222 2904 2221 2905 2222 2905 2223 2905 2223 2906 2222 2906 2224 2906 2223 2907 2224 2907 2225 2907 2225 2908 2224 2908 2213 2908 2225 2909 2213 2909 2212 2909 2212 2910 2213 2910 2201 2910 2212 2911 2201 2911 2200 2911 1923 2912 2226 2912 1922 2912 1922 2913 2226 2913 2227 2913 1922 2914 2227 2914 1920 2914 1920 2915 2227 2915 2228 2915 1920 2916 2228 2916 2214 2916 2214 2917 2228 2917 2229 2917 2214 2918 2229 2918 2230 2918 2230 2919 2229 2919 2231 2919 2230 2920 2231 2920 2232 2920 2232 2921 2231 2921 2233 2921 2232 2922 2233 2922 2234 2922 2234 2923 2233 2923 2235 2923 2234 2924 2235 2924 2236 2924 2236 2925 2235 2925 2237 2925 2236 2926 2237 2926 2238 2926 2238 2927 2237 2927 2239 2927 2238 2928 2239 2928 2240 2928 2202 2929 2214 2929 2212 2929 2212 2930 2214 2930 2230 2930 2212 2931 2230 2931 2225 2931 2225 2932 2230 2932 2232 2932 2225 2933 2232 2933 2223 2933 2223 2934 2232 2934 2234 2934 2223 2935 2234 2935 2221 2935 2221 2936 2234 2936 2236 2936 2221 2937 2236 2937 2219 2937 2219 2938 2236 2938 2238 2938 2219 2939 2238 2939 2217 2939 2217 2940 2238 2940 2240 2940 2217 2941 2240 2941 2241 2941 2242 2942 2215 2942 2243 2942 2243 2943 2215 2943 2217 2943 2243 2944 2217 2944 2244 2944 2244 2945 2217 2945 2241 2945 2160 2946 1378 2946 2242 2946 2242 2947 2243 2947 2160 2947 2160 2948 2243 2948 2244 2948 2160 2949 2244 2949 2158 2949 2244 2950 2241 2950 2158 2950 2158 2951 2241 2951 2240 2951 2158 2952 2240 2952 2156 2952 2156 2953 2240 2953 2239 2953 2156 2954 2239 2954 2154 2954 2245 2955 1813 2955 1812 2955 2245 2956 1812 2956 2246 2956 2246 2957 1812 2957 1801 2957 2246 2958 1801 2958 2247 2958 2247 2959 1801 2959 1803 2959 2247 2960 1803 2960 2248 2960 887 2961 2245 2961 2249 2961 2249 2962 2245 2962 2246 2962 2249 2963 2246 2963 2250 2963 2250 2964 2246 2964 2247 2964 2250 2965 2247 2965 2251 2965 2251 2966 2247 2966 2248 2966 2251 2967 2248 2967 2252 2967 887 2968 2249 2968 1389 2968 1389 2969 2249 2969 2250 2969 1389 2970 2250 2970 1388 2970 1388 2971 2250 2971 2251 2971 1388 2972 2251 2972 1387 2972 1387 2973 2251 2973 2252 2973 1387 2974 2252 2974 1385 2974 1813 2975 2245 2975 887 2975 1406 2976 1408 2976 2253 2976 2253 2977 1408 2977 2254 2977 2253 2978 2254 2978 2255 2978 2255 2979 2254 2979 2256 2979 2256 2980 2254 2980 2257 2980 2256 2981 2257 2981 2258 2981 2258 2982 2257 2982 2259 2982 2259 2983 2257 2983 1816 2983 2259 2984 1816 2984 1815 2984 1803 2985 1816 2985 2248 2985 2248 2986 1816 2986 2257 2986 2248 2987 2257 2987 2252 2987 2252 2988 2257 2988 2254 2988 2252 2989 2254 2989 1385 2989 1385 2990 2254 2990 1408 2990 745 2991 743 2991 1859 2991 745 2992 1859 2992 2260 2992 2260 2993 1859 2993 1861 2993 2260 2994 1861 2994 2261 2994 2261 2995 1861 2995 1863 2995 2261 2996 1863 2996 2262 2996 2262 2997 1863 2997 1849 2997 2262 2998 1849 2998 2263 2998 1849 2999 1851 2999 2263 2999 2263 3000 1851 3000 1853 3000 2263 3001 1853 3001 2264 3001 2264 3002 1853 3002 1855 3002 2264 3003 1855 3003 2265 3003 2265 3004 1855 3004 1857 3004 1857 3005 2266 3005 2265 3005 2265 3006 2266 3006 2267 3006 2265 3007 2267 3007 2264 3007 2264 3008 2267 3008 2268 3008 2264 3009 2268 3009 2263 3009 2263 3010 2268 3010 2269 3010 2263 3011 2269 3011 2262 3011 2262 3012 2269 3012 2270 3012 2262 3013 2270 3013 2261 3013 2261 3014 2270 3014 2271 3014 2261 3015 2271 3015 2260 3015 2260 3016 2271 3016 746 3016 2260 3017 746 3017 745 3017 1857 3018 2272 3018 2266 3018 2266 3019 2272 3019 2273 3019 2266 3020 2273 3020 2267 3020 2267 3021 2273 3021 2274 3021 2267 3022 2274 3022 2268 3022 2268 3023 2274 3023 2275 3023 2268 3024 2275 3024 2269 3024 2269 3025 2275 3025 2276 3025 2269 3026 2276 3026 2270 3026 2270 3027 2276 3027 2277 3027 2270 3028 2277 3028 2271 3028 2271 3029 2277 3029 751 3029 2271 3030 751 3030 746 3030 1857 3031 2278 3031 2272 3031 2272 3032 2278 3032 2279 3032 2272 3033 2279 3033 2273 3033 2273 3034 2279 3034 2280 3034 2273 3035 2280 3035 2274 3035 2274 3036 2280 3036 2281 3036 2274 3037 2281 3037 2275 3037 2275 3038 2281 3038 2282 3038 2275 3039 2282 3039 2276 3039 2276 3040 2282 3040 2283 3040 2276 3041 2283 3041 2277 3041 2277 3042 2283 3042 755 3042 2277 3043 755 3043 751 3043 1442 3044 1447 3044 2284 3044 2285 3045 2286 3045 2287 3045 1857 3046 2288 3046 2278 3046 2278 3047 2288 3047 2289 3047 2278 3048 2289 3048 2279 3048 2279 3049 2289 3049 2280 3049 2280 3050 2289 3050 2290 3050 2280 3051 2290 3051 2281 3051 2281 3052 2290 3052 2291 3052 2281 3053 2291 3053 2282 3053 2282 3054 2291 3054 2283 3054 2283 3055 2291 3055 1438 3055 2283 3056 1438 3056 755 3056 769 3057 1459 3057 2292 3057 2292 3058 1459 3058 2286 3058 2292 3059 2286 3059 2293 3059 2293 3060 2286 3060 2285 3060 2294 3061 2295 3061 2287 3061 2287 3062 2295 3062 2296 3062 2287 3063 2296 3063 2285 3063 1877 3064 2297 3064 2298 3064 2298 3065 2297 3065 2299 3065 2298 3066 2299 3066 2294 3066 2294 3067 2299 3067 2300 3067 2294 3068 2300 3068 2295 3068 2288 3069 2301 3069 2289 3069 2289 3070 2301 3070 2302 3070 2289 3071 2302 3071 2290 3071 2290 3072 2302 3072 2303 3072 2290 3073 2303 3073 2291 3073 2291 3074 2303 3074 2284 3074 2291 3075 2284 3075 1438 3075 1438 3076 2284 3076 1447 3076 1459 3077 1442 3077 2286 3077 2286 3078 1442 3078 2284 3078 2286 3079 2284 3079 2287 3079 2287 3080 2284 3080 2303 3080 2287 3081 2303 3081 2294 3081 2294 3082 2303 3082 2302 3082 2294 3083 2302 3083 2298 3083 2298 3084 2302 3084 2301 3084 1877 3085 1876 3085 2304 3085 2304 3086 1876 3086 1874 3086 2305 3087 1874 3087 1872 3087 2305 3088 1872 3088 2306 3088 2306 3089 1872 3089 1870 3089 2306 3090 1870 3090 2307 3090 2307 3091 1870 3091 1868 3091 2307 3092 1868 3092 2308 3092 2308 3093 1868 3093 1867 3093 2308 3094 1867 3094 2309 3094 2309 3095 1867 3095 1881 3095 2309 3096 1881 3096 2310 3096 2310 3097 1881 3097 1882 3097 2310 3098 1882 3098 2311 3098 2311 3099 1882 3099 765 3099 2311 3100 765 3100 762 3100 2312 3101 2305 3101 2313 3101 2313 3102 2305 3102 2306 3102 2313 3103 2306 3103 2314 3103 2314 3104 2306 3104 2307 3104 2314 3105 2307 3105 2315 3105 2315 3106 2307 3106 2308 3106 2315 3107 2308 3107 2316 3107 2316 3108 2308 3108 2309 3108 2316 3109 2309 3109 2317 3109 2317 3110 2309 3110 2310 3110 2317 3111 2310 3111 2318 3111 2318 3112 2310 3112 2311 3112 2318 3113 2311 3113 2319 3113 2319 3114 2311 3114 762 3114 2319 3115 762 3115 761 3115 1877 3116 2312 3116 2320 3116 2320 3117 2312 3117 2313 3117 2320 3118 2313 3118 2321 3118 2321 3119 2313 3119 2314 3119 2321 3120 2314 3120 2322 3120 2322 3121 2314 3121 2315 3121 2322 3122 2315 3122 2323 3122 2323 3123 2315 3123 2316 3123 2323 3124 2316 3124 2324 3124 2324 3125 2316 3125 2317 3125 2324 3126 2317 3126 2325 3126 2325 3127 2317 3127 2318 3127 2325 3128 2318 3128 2326 3128 2326 3129 2318 3129 2319 3129 2326 3130 2319 3130 2327 3130 2327 3131 2319 3131 761 3131 2327 3132 761 3132 759 3132 1877 3133 2320 3133 2297 3133 2297 3134 2320 3134 2321 3134 2297 3135 2321 3135 2299 3135 2299 3136 2321 3136 2322 3136 2299 3137 2322 3137 2300 3137 2300 3138 2322 3138 2323 3138 2300 3139 2323 3139 2295 3139 2295 3140 2323 3140 2324 3140 2295 3141 2324 3141 2296 3141 2296 3142 2324 3142 2325 3142 2296 3143 2325 3143 2285 3143 2285 3144 2325 3144 2326 3144 2285 3145 2326 3145 2293 3145 2293 3146 2326 3146 2327 3146 2293 3147 2327 3147 2292 3147 2292 3148 2327 3148 759 3148 2292 3149 759 3149 769 3149 1874 3150 2305 3150 2304 3150 2304 3151 2305 3151 2312 3151 2304 3152 2312 3152 1877 3152 2328 3153 2329 3153 2330 3153 1497 3154 1496 3154 2331 3154 1605 3155 2332 3155 1604 3155 1606 3156 1586 3156 2132 3156 2333 3157 2334 3157 1463 3157 2335 3158 2336 3158 2333 3158 2337 3159 2338 3159 1463 3159 1463 3160 2338 3160 2339 3160 1463 3161 2339 3161 1462 3161 2334 3162 2340 3162 1463 3162 1463 3163 2340 3163 2341 3163 1463 3164 2341 3164 2337 3164 2342 3165 2343 3165 2344 3165 2345 3166 2346 3166 2347 3166 2348 3167 2349 3167 2350 3167 2350 3168 2349 3168 2351 3168 2351 3169 2352 3169 2350 3169 2350 3170 2352 3170 2353 3170 2350 3171 2353 3171 2354 3171 1606 3172 2132 3172 1605 3172 1545 3173 1538 3173 2355 3173 2355 3174 1538 3174 1526 3174 1526 3175 1527 3175 2356 3175 2356 3176 1527 3176 1529 3176 2356 3177 1529 3177 2332 3177 2332 3178 1529 3178 1603 3178 2332 3179 1603 3179 1604 3179 2357 3180 1576 3180 1572 3180 1556 3181 1555 3181 2358 3181 1572 3182 1569 3182 2357 3182 2357 3183 1569 3183 1566 3183 2357 3184 1566 3184 2358 3184 2358 3185 1566 3185 1557 3185 2358 3186 1557 3186 1556 3186 1545 3187 2359 3187 1548 3187 1548 3188 2359 3188 2358 3188 1548 3189 2358 3189 1551 3189 1551 3190 2358 3190 1555 3190 1486 3191 1484 3191 2360 3191 2360 3192 1484 3192 1482 3192 2360 3193 1482 3193 1506 3193 1506 3194 1507 3194 2360 3194 2360 3195 1507 3195 1512 3195 2360 3196 1512 3196 2357 3196 2357 3197 1512 3197 1517 3197 2357 3198 1517 3198 1576 3198 1496 3199 1495 3199 2361 3199 2361 3200 1495 3200 1494 3200 2361 3201 1494 3201 1486 3201 2362 3202 2363 3202 2364 3202 2364 3203 2363 3203 2365 3203 2364 3204 2365 3204 2366 3204 2366 3205 2365 3205 2350 3205 2366 3206 2350 3206 2345 3206 2345 3207 2350 3207 2354 3207 2345 3208 2354 3208 2346 3208 2362 3209 2364 3209 2330 3209 2330 3210 2364 3210 2367 3210 2330 3211 2367 3211 2328 3211 2333 3212 1463 3212 2335 3212 2335 3213 1463 3213 1464 3213 2335 3214 1464 3214 2368 3214 2368 3215 1464 3215 1465 3215 2368 3216 1465 3216 2369 3216 2369 3217 1465 3217 1468 3217 2369 3218 1468 3218 2370 3218 2370 3219 1468 3219 1470 3219 2370 3220 1470 3220 2371 3220 2371 3221 1470 3221 1476 3221 2371 3222 1476 3222 2372 3222 2372 3223 1476 3223 1475 3223 2372 3224 1475 3224 2331 3224 2331 3225 1475 3225 780 3225 2331 3226 780 3226 1497 3226 1496 3227 2361 3227 2331 3227 2331 3228 2361 3228 2373 3228 2331 3229 2373 3229 2372 3229 2372 3230 2373 3230 2374 3230 2372 3231 2374 3231 2371 3231 2371 3232 2374 3232 2375 3232 2371 3233 2375 3233 2370 3233 2370 3234 2375 3234 2376 3234 2370 3235 2376 3235 2369 3235 2369 3236 2376 3236 2377 3236 2369 3237 2377 3237 2368 3237 2368 3238 2377 3238 2342 3238 2368 3239 2342 3239 2335 3239 2335 3240 2342 3240 2344 3240 2335 3241 2344 3241 2336 3241 1486 3242 2360 3242 2361 3242 2361 3243 2360 3243 2378 3243 2361 3244 2378 3244 2373 3244 2373 3245 2378 3245 2328 3245 2373 3246 2328 3246 2374 3246 2374 3247 2328 3247 2367 3247 2374 3248 2367 3248 2375 3248 2375 3249 2367 3249 2364 3249 2375 3250 2364 3250 2376 3250 2376 3251 2364 3251 2366 3251 2376 3252 2366 3252 2377 3252 2377 3253 2366 3253 2345 3253 2377 3254 2345 3254 2342 3254 2342 3255 2345 3255 2347 3255 2342 3256 2347 3256 2343 3256 2329 3257 2328 3257 2379 3257 2379 3258 2328 3258 2378 3258 2379 3259 2378 3259 2380 3259 2380 3260 2378 3260 2360 3260 2380 3261 2360 3261 2381 3261 2381 3262 2360 3262 2357 3262 2381 3263 2357 3263 2382 3263 2382 3264 2357 3264 2358 3264 2382 3265 2358 3265 2383 3265 2383 3266 2358 3266 2359 3266 2383 3267 2359 3267 2384 3267 2384 3268 2359 3268 2385 3268 2384 3269 2385 3269 2386 3269 2386 3270 2385 3270 2387 3270 2386 3271 2387 3271 2388 3271 2388 3272 2387 3272 2389 3272 2389 3273 2387 3273 2390 3273 2389 3274 2390 3274 2391 3274 2391 3275 2390 3275 2392 3275 2391 3276 2392 3276 2393 3276 1605 3277 2132 3277 2332 3277 2332 3278 2132 3278 2131 3278 2332 3279 2131 3279 2356 3279 2356 3280 2131 3280 2129 3280 2356 3281 2129 3281 2394 3281 2394 3282 2129 3282 2127 3282 2394 3283 2127 3283 2395 3283 2395 3284 2127 3284 2126 3284 2395 3285 2126 3285 2396 3285 2396 3286 2126 3286 2135 3286 2396 3287 2135 3287 2397 3287 2397 3288 2135 3288 2134 3288 2397 3289 2134 3289 2398 3289 2398 3290 2134 3290 2133 3290 2398 3291 2133 3291 2399 3291 2399 3292 2133 3292 2140 3292 2399 3293 2140 3293 2400 3293 2400 3294 2140 3294 2139 3294 2400 3295 2139 3295 2401 3295 2401 3296 2139 3296 2138 3296 2401 3297 2138 3297 2402 3297 2402 3298 2138 3298 2137 3298 2402 3299 2137 3299 2403 3299 2403 3300 2137 3300 2136 3300 2403 3301 2136 3301 2404 3301 2404 3302 2136 3302 1938 3302 2404 3303 1938 3303 2405 3303 1526 3304 2356 3304 2355 3304 2355 3305 2356 3305 2394 3305 2355 3306 2394 3306 2406 3306 2406 3307 2394 3307 2395 3307 2406 3308 2395 3308 2407 3308 2407 3309 2395 3309 2396 3309 2407 3310 2396 3310 2408 3310 2408 3311 2396 3311 2397 3311 2408 3312 2397 3312 2409 3312 2409 3313 2397 3313 2398 3313 2409 3314 2398 3314 2410 3314 2410 3315 2398 3315 2399 3315 2410 3316 2399 3316 2411 3316 2411 3317 2399 3317 2400 3317 2411 3318 2400 3318 2412 3318 2412 3319 2400 3319 2401 3319 2412 3320 2401 3320 2413 3320 2413 3321 2401 3321 2402 3321 2413 3322 2402 3322 2414 3322 2414 3323 2402 3323 2403 3323 2414 3324 2403 3324 2415 3324 2415 3325 2403 3325 2404 3325 2415 3326 2404 3326 2416 3326 2416 3327 2404 3327 2405 3327 2416 3328 2405 3328 2417 3328 1545 3329 2355 3329 2359 3329 2359 3330 2355 3330 2406 3330 2359 3331 2406 3331 2385 3331 2385 3332 2406 3332 2407 3332 2385 3333 2407 3333 2387 3333 2387 3334 2407 3334 2408 3334 2387 3335 2408 3335 2390 3335 2390 3336 2408 3336 2409 3336 2390 3337 2409 3337 2392 3337 2392 3338 2409 3338 2410 3338 2392 3339 2410 3339 2418 3339 2418 3340 2410 3340 2411 3340 2418 3341 2411 3341 2419 3341 2419 3342 2411 3342 2412 3342 2419 3343 2412 3343 2420 3343 2420 3344 2412 3344 2413 3344 2420 3345 2413 3345 2421 3345 2421 3346 2413 3346 2414 3346 2421 3347 2414 3347 2422 3347 2422 3348 2414 3348 2415 3348 2422 3349 2415 3349 2423 3349 2423 3350 2415 3350 2416 3350 2423 3351 2416 3351 2424 3351 2424 3352 2416 3352 2417 3352 2424 3353 2417 3353 2425 3353 2393 3354 2392 3354 2426 3354 2426 3355 2392 3355 2418 3355 2426 3356 2418 3356 2427 3356 2427 3357 2418 3357 2419 3357 2427 3358 2419 3358 2428 3358 2428 3359 2419 3359 2420 3359 2428 3360 2420 3360 2429 3360 2429 3361 2420 3361 2421 3361 2429 3362 2421 3362 2430 3362 2430 3363 2421 3363 2422 3363 2430 3364 2422 3364 2431 3364 2431 3365 2422 3365 2423 3365 2431 3366 2423 3366 2432 3366 2432 3367 2423 3367 2424 3367 2432 3368 2424 3368 2433 3368 2433 3369 2424 3369 2425 3369 2433 3370 2425 3370 2434 3370 2435 3371 2436 3371 2437 3371 2438 3372 2439 3372 2440 3372 2440 3373 2439 3373 2441 3373 2440 106 2441 106 2442 106 2443 3374 2441 3374 2444 3374 2444 3375 2441 3375 2439 3375 2444 3376 2439 3376 2445 3376 2445 3377 2439 3377 2438 3377 2445 3378 2438 3378 2446 3378 2446 3379 2438 3379 2437 3379 2436 3380 2435 3380 2447 3380 2448 3381 2449 3381 2450 3381 2450 3382 2449 3382 2451 3382 2451 3383 2452 3383 2453 3383 2453 3384 2452 3384 2454 3384 2453 3385 2454 3385 2447 3385 2334 3386 2455 3386 2340 3386 2340 3387 2455 3387 2456 3387 1462 3388 2339 3388 2457 3388 2457 3389 2339 3389 2338 3389 2457 3390 2338 3390 2458 3390 2458 3391 2338 3391 2337 3391 2458 3392 2337 3392 2459 3392 2459 3393 2337 3393 2341 3393 2459 3394 2341 3394 2460 3394 2460 3395 2341 3395 2340 3395 2460 3396 2340 3396 2450 3396 2450 3397 2340 3397 2456 3397 2450 3398 2456 3398 2448 3398 2451 3399 2453 3399 2450 3399 2450 3400 2453 3400 2461 3400 2450 3401 2461 3401 2460 3401 2460 3402 2461 3402 2462 3402 2460 3403 2462 3403 2459 3403 2459 3404 2462 3404 2463 3404 2459 3405 2463 3405 2458 3405 2458 3406 2463 3406 2464 3406 2458 3407 2464 3407 2457 3407 2457 3408 2464 3408 1462 3408 2447 3409 2435 3409 2453 3409 2453 3410 2435 3410 2465 3410 2453 3411 2465 3411 2461 3411 2461 3412 2465 3412 2466 3412 2461 3413 2466 3413 2462 3413 2462 3414 2466 3414 2467 3414 2462 3415 2467 3415 2463 3415 2463 3416 2467 3416 2468 3416 2463 3417 2468 3417 2464 3417 2464 3418 2468 3418 1462 3418 2437 3419 2438 3419 2435 3419 2435 3420 2438 3420 2469 3420 2435 3421 2469 3421 2465 3421 2465 3422 2469 3422 2470 3422 2465 3423 2470 3423 2466 3423 2466 3424 2470 3424 2471 3424 2466 3425 2471 3425 2467 3425 2467 3426 2471 3426 2472 3426 2467 3427 2472 3427 2468 3427 2468 3428 2472 3428 1462 3428 2437 3429 2436 3429 2473 3429 2455 3430 2334 3430 2333 3430 2455 3431 2333 3431 2456 3431 2474 3432 2448 3432 2456 3432 2452 3433 2451 3433 2474 3433 2474 3434 2451 3434 2449 3434 2474 3435 2449 3435 2448 3435 2436 3436 2447 3436 2475 3436 2475 3437 2447 3437 2454 3437 2475 3438 2454 3438 2452 3438 2445 3439 2446 3439 2476 3439 2476 3440 2446 3440 2437 3440 2456 3441 2333 3441 2474 3441 2474 3442 2333 3442 2336 3442 2474 3443 2336 3443 2477 3443 2477 3444 2336 3444 2344 3444 2477 3445 2344 3445 2478 3445 2478 3446 2344 3446 2343 3446 2478 3447 2343 3447 2479 3447 2479 3448 2343 3448 2347 3448 2479 3449 2347 3449 2480 3449 2480 3450 2347 3450 2346 3450 2480 3451 2346 3451 2481 3451 2346 3452 2354 3452 2481 3452 2481 3453 2354 3453 2482 3453 2481 3454 2482 3454 2483 3454 2452 3455 2474 3455 2475 3455 2475 3456 2474 3456 2477 3456 2475 3457 2477 3457 2484 3457 2484 3458 2477 3458 2478 3458 2484 3459 2478 3459 2485 3459 2485 3460 2478 3460 2479 3460 2485 3461 2479 3461 2486 3461 2486 3462 2479 3462 2480 3462 2486 3463 2480 3463 2487 3463 2487 3464 2480 3464 2481 3464 2487 3465 2481 3465 2488 3465 2488 3466 2481 3466 2483 3466 2488 3467 2483 3467 2489 3467 2436 3468 2475 3468 2473 3468 2473 3469 2475 3469 2484 3469 2473 3470 2484 3470 2490 3470 2490 3471 2484 3471 2485 3471 2490 3472 2485 3472 2491 3472 2491 3473 2485 3473 2486 3473 2491 3474 2486 3474 2492 3474 2492 3475 2486 3475 2487 3475 2492 3476 2487 3476 2493 3476 2493 3477 2487 3477 2488 3477 2493 3478 2488 3478 2494 3478 2494 3479 2488 3479 2489 3479 2494 3480 2489 3480 2495 3480 2437 3481 2473 3481 2476 3481 2476 3482 2473 3482 2490 3482 2476 3483 2490 3483 2496 3483 2496 3484 2490 3484 2491 3484 2496 3485 2491 3485 2497 3485 2497 3486 2491 3486 2492 3486 2497 3487 2492 3487 2498 3487 2498 3488 2492 3488 2493 3488 2498 3489 2493 3489 2499 3489 2499 3490 2493 3490 2494 3490 2499 3491 2494 3491 2500 3491 2500 3492 2494 3492 2495 3492 2500 3493 2495 3493 2501 3493 2502 3494 2503 3494 2504 3494 2505 3495 2506 3495 2507 3495 2507 3496 2506 3496 2508 3496 2507 3497 2508 3497 2502 3497 2509 3498 2510 3498 2511 3498 2512 3499 2501 3499 2513 3499 2505 3500 2514 3500 2515 3500 2515 3501 2514 3501 2516 3501 2515 3502 2516 3502 2517 3502 2517 3503 2516 3503 2518 3503 2517 3504 2518 3504 2519 3504 2519 3505 2518 3505 2520 3505 2519 3506 2520 3506 2348 3506 2505 3507 2507 3507 2514 3507 2514 3508 2507 3508 2521 3508 2514 3509 2521 3509 2516 3509 2516 3510 2521 3510 2522 3510 2516 3511 2522 3511 2518 3511 2518 3512 2522 3512 2523 3512 2518 3513 2523 3513 2520 3513 2502 3514 2504 3514 2507 3514 2507 3515 2504 3515 2524 3515 2507 3516 2524 3516 2521 3516 2521 3517 2524 3517 2509 3517 2521 3518 2509 3518 2522 3518 2522 3519 2509 3519 2511 3519 2522 3520 2511 3520 2523 3520 1758 3521 2525 3521 2503 3521 2503 3522 2525 3522 2526 3522 2503 3523 2526 3523 2504 3523 2504 3524 2526 3524 2527 3524 2504 3525 2527 3525 2524 3525 2524 3526 2527 3526 2512 3526 2524 3527 2512 3527 2509 3527 2509 3528 2512 3528 2513 3528 2509 3529 2513 3529 2510 3529 2123 3530 2122 3530 2528 3530 2529 3531 2530 3531 2531 3531 2528 3532 792 3532 791 3532 791 3533 2531 3533 2528 3533 2528 3534 2531 3534 2530 3534 2528 3535 2530 3535 2123 3535 2123 3536 2530 3536 2529 3536 2123 3537 2529 3537 2124 3537 2124 3538 2529 3538 2532 3538 2124 3539 2532 3539 2125 3539 2533 3540 2122 3540 2534 3540 2534 3541 2122 3541 2121 3541 2528 3542 2122 3542 792 3542 792 3543 2122 3543 2533 3543 792 3544 2533 3544 793 3544 793 3545 2533 3545 2535 3545 793 3546 2535 3546 794 3546 2536 3547 2537 3547 2538 3547 2539 3548 2540 3548 2541 3548 2542 3549 2543 3549 2544 3549 2539 3550 2541 3550 2545 3550 2545 3551 2541 3551 2546 3551 2546 3552 2541 3552 2547 3552 2546 3553 2547 3553 2548 3553 2548 3554 2547 3554 2544 3554 2548 3555 2544 3555 2549 3555 2549 3556 2544 3556 2543 3556 2549 3557 2543 3557 2026 3557 2542 3558 2544 3558 2550 3558 2550 3559 2544 3559 2547 3559 2550 3560 2547 3560 2551 3560 2551 3561 2547 3561 2541 3561 2551 3562 2541 3562 2552 3562 794 3563 2535 3563 2552 3563 2552 3564 2535 3564 2533 3564 2552 3565 2533 3565 2551 3565 2551 3566 2533 3566 2534 3566 2551 3567 2534 3567 2550 3567 2550 3568 2534 3568 2121 3568 2550 3569 2121 3569 2542 3569 794 3570 2552 3570 1613 3570 1613 3571 2552 3571 2541 3571 1613 3572 2541 3572 2538 3572 2538 3573 2541 3573 2540 3573 2538 3574 2540 3574 2536 3574 1613 3575 2538 3575 1618 3575 1618 3576 2538 3576 2537 3576 1618 3577 2537 3577 1623 3577 2553 3578 2554 3578 2555 3578 2556 3579 1700 3579 1699 3579 2557 3580 2556 3580 2558 3580 2556 3581 1699 3581 2558 3581 2558 3582 1699 3582 1673 3582 2558 3583 1673 3583 1666 3583 1666 3584 1668 3584 2558 3584 2558 3585 1668 3585 2553 3585 2558 3586 2553 3586 2557 3586 2557 3587 2553 3587 2555 3587 1685 3588 2554 3588 1676 3588 1676 3589 2554 3589 2553 3589 1676 3590 2553 3590 1670 3590 1670 3591 2553 3591 1668 3591 1689 3592 2559 3592 1688 3592 1688 3593 2559 3593 2560 3593 1688 3594 2560 3594 1687 3594 2561 3595 2554 3595 2562 3595 2562 3596 2554 3596 1685 3596 2562 3597 1685 3597 2560 3597 2560 3598 1685 3598 1686 3598 2560 3599 1686 3599 1687 3599 2561 3600 2563 3600 2564 3600 2555 3601 2554 3601 2565 3601 2565 3602 2554 3602 2561 3602 2565 3603 2561 3603 2566 3603 2566 3604 2561 3604 2564 3604 2559 3605 2567 3605 2560 3605 2560 3606 2567 3606 2568 3606 2560 3607 2568 3607 2562 3607 2562 3608 2568 3608 2569 3608 2562 3609 2569 3609 2561 3609 2561 3610 2569 3610 2570 3610 2561 3611 2570 3611 2563 3611 2571 3612 2572 3612 2570 3612 2570 3613 2572 3613 2573 3613 2570 3614 2573 3614 2563 3614 2574 3615 2575 3615 2576 3615 2576 3616 2575 3616 2577 3616 2576 3617 2577 3617 2578 3617 2578 3618 2577 3618 2579 3618 2578 3619 2579 3619 2580 3619 2580 3620 2579 3620 2581 3620 2567 3621 2581 3621 2568 3621 2568 3622 2581 3622 2579 3622 2568 3623 2579 3623 2569 3623 2569 3624 2579 3624 2577 3624 2569 3625 2577 3625 2570 3625 2570 3626 2577 3626 2575 3626 2570 3627 2575 3627 2571 3627 2571 3628 2575 3628 2574 3628 2571 3629 2574 3629 2582 3629 2556 3630 2557 3630 2583 3630 1701 3631 1700 3631 2556 3631 2584 3632 2585 3632 2586 3632 1693 3633 1695 3633 2585 3633 2585 3634 1695 3634 1696 3634 2585 3635 1696 3635 2587 3635 2587 3636 1696 3636 1691 3636 2587 3637 1691 3637 2588 3637 1691 3638 1690 3638 2588 3638 2588 3639 1690 3639 1702 3639 2588 3640 1702 3640 2589 3640 2589 3641 1702 3641 1701 3641 1701 3642 2556 3642 2589 3642 2589 3643 2556 3643 2583 3643 2589 3644 2583 3644 2588 3644 2588 3645 2583 3645 2590 3645 2588 3646 2590 3646 2587 3646 2587 3647 2590 3647 2586 3647 2587 3648 2586 3648 2585 3648 2584 3649 2586 3649 2591 3649 2591 3650 2586 3650 2590 3650 2591 3651 2590 3651 2592 3651 2592 3652 2590 3652 2583 3652 2592 3653 2583 3653 2593 3653 2593 3654 2583 3654 2557 3654 2593 3655 2557 3655 2555 3655 2594 3656 2595 3656 2596 3656 2597 3657 2598 3657 2599 3657 2598 3658 2600 3658 2599 3658 2599 3659 2600 3659 2601 3659 2599 3660 2601 3660 2602 3660 2564 3661 2603 3661 2604 3661 2604 3662 2603 3662 1693 3662 1693 3663 2605 3663 1694 3663 1694 3664 2605 3664 2596 3664 1694 3665 2596 3665 1707 3665 2606 3666 2607 3666 2608 3666 2608 3667 2607 3667 2609 3667 2608 3668 2609 3668 2610 3668 2610 3669 2609 3669 2611 3669 2610 3670 2611 3670 2612 3670 2595 3671 2606 3671 2596 3671 2596 3672 2606 3672 2608 3672 2596 3673 2608 3673 1707 3673 1707 3674 2608 3674 2610 3674 1707 3675 2610 3675 1706 3675 2603 3676 2597 3676 1693 3676 1693 3677 2597 3677 2599 3677 1693 3678 2599 3678 2605 3678 2605 3679 2599 3679 2613 3679 2605 3680 2613 3680 2596 3680 2596 3681 2613 3681 2614 3681 2596 3682 2614 3682 2594 3682 2615 3683 2616 3683 1914 3683 1706 3684 2610 3684 1712 3684 1712 3685 2610 3685 2612 3685 1712 3686 2612 3686 1914 3686 1914 3687 2612 3687 2617 3687 1914 3688 2617 3688 2615 3688 1757 3689 882 3689 2618 3689 2618 3690 882 3690 880 3690 2618 3691 880 3691 2619 3691 2619 3692 880 3692 878 3692 2619 3693 878 3693 2620 3693 866 3694 2621 3694 868 3694 868 3695 2621 3695 2622 3695 868 3696 2622 3696 870 3696 870 3697 2622 3697 2623 3697 870 3698 2623 3698 872 3698 872 3699 2623 3699 2624 3699 872 3700 2624 3700 874 3700 874 3701 2624 3701 2625 3701 874 3702 2625 3702 876 3702 876 3703 2625 3703 2626 3703 876 3704 2626 3704 878 3704 878 3705 2626 3705 2627 3705 878 3706 2627 3706 2620 3706 855 3707 2628 3707 866 3707 866 3708 2628 3708 2629 3708 866 3709 2629 3709 2621 3709 2630 3710 2631 3710 855 3710 855 3711 2631 3711 2632 3711 855 3712 2632 3712 2628 3712 855 3713 854 3713 2633 3713 2633 3714 2634 3714 855 3714 855 3715 2634 3715 2635 3715 855 3716 2635 3716 2630 3716 2636 3717 1757 3717 2637 3717 1757 3718 2638 3718 2639 3718 2636 3719 2638 3719 1757 3719 634 3720 638 3720 2640 3720 2640 3721 638 3721 1756 3721 2640 3722 1756 3722 2639 3722 2639 3723 1756 3723 1757 3723 2118 3724 2637 3724 2098 3724 2098 3725 2637 3725 2641 3725 2098 3726 2641 3726 2099 3726 2099 3727 2641 3727 2101 3727 1759 3728 1758 3728 2642 3728 2642 3729 1758 3729 2643 3729 2642 3730 2643 3730 2644 3730 2645 3731 2646 3731 2647 3731 2648 3732 2649 3732 2650 3732 2650 3733 2649 3733 2646 3733 2650 3734 2646 3734 2651 3734 2651 3735 2646 3735 2645 3735 364 3736 1759 3736 2647 3736 2647 3737 1759 3737 2642 3737 2647 3738 2642 3738 2645 3738 2645 3739 2642 3739 2644 3739 2645 3740 2644 3740 2651 3740 2651 3741 2644 3741 2652 3741 2651 3742 2652 3742 2650 3742 2650 3743 2652 3743 2648 3743 2653 3744 348 3744 359 3744 2654 3745 2655 3745 2656 3745 2657 3746 2658 3746 2659 3746 2659 3747 2658 3747 2660 3747 2659 3748 2660 3748 2661 3748 2657 3749 2662 3749 2658 3749 2658 3750 2662 3750 2663 3750 2658 3751 2663 3751 2664 3751 2654 3752 2656 3752 2664 3752 2665 3753 2666 3753 2667 3753 2667 3754 2666 3754 2668 3754 2667 3755 2668 3755 2669 3755 2669 3756 2670 3756 2667 3756 2667 3757 2670 3757 2582 3757 2667 3758 2582 3758 2661 3758 2602 3759 2671 3759 2672 3759 2672 3760 2671 3760 2673 3760 2672 3761 2673 3761 2674 3761 2653 3762 359 3762 2655 3762 2655 3763 359 3763 2656 3763 2656 3764 359 3764 360 3764 2656 3765 360 3765 2675 3765 2675 3766 360 3766 363 3766 2675 3767 363 3767 2676 3767 2676 3768 363 3768 364 3768 2676 3769 364 3769 2647 3769 2664 3770 2656 3770 2658 3770 2658 3771 2656 3771 2675 3771 2658 3772 2675 3772 2677 3772 2677 3773 2675 3773 2676 3773 2677 3774 2676 3774 2678 3774 2678 3775 2676 3775 2647 3775 2678 3776 2647 3776 2646 3776 2661 3777 2660 3777 2667 3777 2667 3778 2660 3778 2658 3778 2667 3779 2658 3779 2679 3779 2679 3780 2658 3780 2677 3780 2679 3781 2677 3781 2680 3781 2680 3782 2677 3782 2678 3782 2680 3783 2678 3783 2681 3783 2681 3784 2678 3784 2646 3784 2681 3785 2646 3785 2649 3785 2674 3786 2665 3786 2672 3786 2672 3787 2665 3787 2667 3787 2672 3788 2667 3788 2682 3788 2682 3789 2667 3789 2679 3789 2682 3790 2679 3790 2683 3790 2683 3791 2679 3791 2680 3791 2683 3792 2680 3792 2684 3792 2684 3793 2680 3793 2681 3793 2684 3794 2681 3794 2685 3794 2685 3795 2681 3795 2649 3795 2685 3796 2649 3796 2648 3796 2655 3797 2654 3797 2686 3797 2686 3798 2654 3798 2687 3798 2686 3799 2687 3799 2688 3799 2688 3800 2687 3800 2689 3800 2688 3801 2689 3801 352 3801 352 3802 2689 3802 353 3802 2653 3803 2655 3803 2690 3803 2690 3804 2655 3804 2686 3804 2690 3805 2686 3805 2691 3805 2691 3806 2686 3806 2688 3806 2691 3807 2688 3807 351 3807 351 3808 2688 3808 352 3808 348 3809 2653 3809 347 3809 347 3810 2653 3810 2690 3810 347 3811 2690 3811 349 3811 349 3812 2690 3812 2691 3812 349 3813 2691 3813 350 3813 350 3814 2691 3814 351 3814 2692 3815 2693 3815 2694 3815 2654 3816 2664 3816 2687 3816 2687 3817 2664 3817 2695 3817 2687 3818 2695 3818 2689 3818 2689 3819 2695 3819 2696 3819 2689 3820 2696 3820 353 3820 2697 3821 2698 3821 2696 3821 2696 3822 2698 3822 2699 3822 2696 3823 2699 3823 353 3823 2692 3824 2694 3824 2700 3824 2700 3825 2694 3825 2701 3825 2700 3826 2701 3826 2702 3826 2657 3827 2659 3827 2703 3827 2703 3828 2701 3828 2657 3828 2657 3829 2701 3829 2694 3829 2657 3830 2694 3830 2662 3830 2662 3831 2694 3831 2693 3831 2662 3832 2693 3832 2663 3832 2703 3833 2704 3833 2701 3833 2701 3834 2704 3834 2705 3834 2701 3835 2705 3835 2702 3835 2702 3836 2705 3836 2706 3836 2702 3837 2706 3837 2707 3837 2664 3838 2663 3838 2695 3838 2695 3839 2663 3839 2693 3839 2695 3840 2693 3840 2696 3840 2696 3841 2693 3841 2692 3841 2696 3842 2692 3842 2697 3842 2697 3843 2692 3843 2700 3843 2697 3844 2700 3844 2708 3844 2708 3845 2700 3845 2702 3845 2708 3846 2702 3846 2709 3846 2709 3847 2702 3847 2707 3847 2709 3848 2707 3848 2710 3848 2711 3849 2712 3849 2710 3849 2659 3850 2661 3850 2703 3850 2703 3851 2661 3851 2713 3851 2703 3852 2713 3852 2704 3852 2704 3853 2713 3853 2714 3853 2710 3854 2707 3854 2711 3854 2711 3855 2707 3855 2706 3855 2711 3856 2706 3856 2714 3856 2714 3857 2706 3857 2705 3857 2714 3858 2705 3858 2704 3858 2580 3859 2712 3859 2578 3859 2578 3860 2712 3860 2711 3860 2578 3861 2711 3861 2576 3861 2576 3862 2711 3862 2714 3862 2576 3863 2714 3863 2574 3863 2574 3864 2714 3864 2713 3864 2574 3865 2713 3865 2582 3865 2582 3866 2713 3866 2661 3866 2715 3867 2716 3867 2717 3867 1761 3868 2718 3868 2717 3868 2716 3869 1765 3869 2717 3869 2717 3870 1765 3870 1762 3870 2717 3871 1762 3871 1761 3871 2719 3872 2715 3872 2720 3872 2720 3873 2715 3873 2717 3873 2720 3874 2717 3874 2721 3874 2721 3875 2717 3875 2718 3875 2721 3876 2718 3876 2722 3876 1772 3877 1771 3877 1836 3877 1332 3878 1848 3878 1833 3878 1833 3879 1848 3879 2723 3879 1833 3880 2723 3880 1836 3880 1836 3881 2723 3881 2724 3881 1836 3882 2724 3882 1772 3882 2725 3883 2726 3883 2727 3883 2728 3884 2729 3884 1760 3884 2730 3885 2731 3885 2729 3885 2729 3886 2731 3886 2732 3886 2732 3887 2733 3887 2729 3887 2729 3888 2733 3888 1761 3888 2729 3889 1761 3889 1760 3889 2734 3890 2735 3890 2736 3890 2736 3891 2735 3891 2737 3891 2736 3892 2737 3892 2738 3892 2739 3893 2740 3893 2734 3893 2734 3894 2740 3894 2741 3894 2734 3895 2741 3895 2735 3895 2742 3896 2743 3896 2739 3896 2739 3897 2743 3897 2744 3897 2739 3898 2744 3898 2740 3898 2725 3899 2727 3899 2745 3899 1848 3900 2726 3900 2723 3900 2723 3901 2726 3901 2725 3901 2723 3902 2725 3902 2724 3902 2724 3903 2725 3903 2745 3903 2737 3904 2730 3904 2738 3904 2738 3905 2730 3905 2729 3905 2738 3906 2729 3906 2746 3906 2746 3907 2729 3907 2728 3907 2746 3908 2728 3908 2727 3908 2727 3909 2728 3909 2747 3909 2727 3910 2747 3910 2745 3910 1772 3911 2724 3911 1774 3911 1774 3912 2724 3912 2745 3912 1774 3913 2745 3913 1775 3913 1775 3914 2745 3914 2747 3914 1775 3915 2747 3915 1776 3915 1776 3916 2747 3916 2728 3916 1776 3917 2728 3917 1766 3917 1766 3918 2728 3918 1760 3918 2748 3919 2749 3919 2750 3919 805 3920 822 3920 2751 3920 817 3921 2719 3921 2720 3921 2721 3922 2751 3922 2720 3922 2752 3923 2753 3923 2754 3923 1845 3924 1842 3924 2755 3924 2755 3925 1842 3925 2748 3925 2755 3926 2748 3926 2742 3926 2756 3927 2757 3927 2750 3927 2750 3928 2757 3928 2758 3928 2722 3929 2759 3929 2760 3929 2760 3930 2759 3930 2756 3930 2756 3931 2759 3931 2761 3931 2756 3932 2761 3932 2757 3932 2751 3933 822 3933 2720 3933 2720 3934 822 3934 818 3934 2720 3935 818 3935 817 3935 2722 3936 2760 3936 2762 3936 2722 3937 2762 3937 2721 3937 2721 3938 2762 3938 2763 3938 2721 3939 2763 3939 2751 3939 2751 3940 2763 3940 806 3940 2751 3941 806 3941 805 3941 2758 3942 2754 3942 2750 3942 2750 3943 2754 3943 2753 3943 2750 3944 2753 3944 2748 3944 2748 3945 2753 3945 2752 3945 2748 3946 2752 3946 2742 3946 2764 3947 813 3947 2765 3947 2765 3948 813 3948 812 3948 2765 3949 812 3949 2766 3949 2766 3950 812 3950 807 3950 2766 3951 807 3951 806 3951 814 3952 816 3952 2767 3952 2767 3953 816 3953 2768 3953 2769 3954 2770 3954 2771 3954 2772 3955 836 3955 2773 3955 2773 3956 836 3956 1782 3956 2773 3957 2769 3957 2772 3957 2772 3958 2769 3958 2771 3958 2772 3959 2771 3959 836 3959 836 3960 2771 3960 2774 3960 836 3961 2774 3961 835 3961 835 3962 2774 3962 2775 3962 835 3963 2775 3963 834 3963 2775 3964 2774 3964 2776 3964 843 3965 834 3965 2775 3965 2777 3966 2776 3966 2778 3966 2777 3967 2778 3967 2779 3967 2779 3968 2778 3968 2780 3968 2779 3969 2780 3969 2781 3969 2775 3970 2776 3970 843 3970 843 3971 2776 3971 2777 3971 843 3972 2777 3972 847 3972 847 3973 2777 3973 2779 3973 847 3974 2779 3974 2782 3974 2782 3975 2779 3975 2781 3975 2782 3976 2781 3976 2783 3976 847 3977 2782 3977 1789 3977 1789 3978 2782 3978 2783 3978 1789 3979 2783 3979 1790 3979 2784 3980 1797 3980 1796 3980 2784 3981 1796 3981 2785 3981 2785 3982 1796 3982 1790 3982 2785 3983 1790 3983 2783 3983 2633 3984 854 3984 2786 3984 2786 3985 854 3985 1797 3985 2786 3986 1797 3986 2784 3986 1806 3987 1827 3987 2787 3987 1830 3988 1831 3988 2788 3988 2788 3989 1831 3989 1832 3989 2788 3990 1832 3990 2789 3990 2789 3991 1832 3991 1913 3991 1828 3992 1829 3992 2790 3992 1804 3993 1806 3993 2791 3993 2791 3994 1806 3994 2792 3994 2792 3995 1806 3995 2793 3995 2793 3996 1806 3996 2787 3996 2793 3997 2787 3997 2794 3997 2794 3998 2787 3998 2795 3998 2794 3999 2795 3999 2796 3999 2796 4000 2795 4000 2797 4000 2796 4001 2797 4001 2798 4001 1829 4002 1830 4002 2790 4002 2790 4003 1830 4003 2788 4003 2790 4004 2788 4004 2799 4004 2799 4005 2788 4005 2800 4005 2799 4006 2800 4006 2801 4006 2801 4007 2800 4007 2802 4007 2801 4008 2802 4008 2803 4008 1827 4009 1828 4009 2787 4009 2787 4010 1828 4010 2790 4010 2787 4011 2790 4011 2795 4011 2795 4012 2790 4012 2799 4012 2795 4013 2799 4013 2797 4013 2797 4014 2799 4014 2801 4014 2797 4015 2801 4015 2798 4015 2798 4016 2801 4016 2803 4016 2798 4017 2803 4017 2804 4017 2805 4018 2806 4018 2807 4018 2808 4019 2805 4019 2809 4019 1804 4020 2808 4020 2810 4020 2805 4021 2807 4021 2809 4021 2809 4022 2807 4022 2811 4022 2809 4023 2811 4023 2812 4023 2812 4024 2811 4024 2813 4024 2812 4025 2813 4025 2814 4025 2814 4026 2813 4026 2815 4026 2814 4027 2815 4027 2816 4027 2816 4028 2815 4028 2817 4028 2816 4029 2817 4029 2818 4029 1406 4030 2817 4030 2819 4030 2819 4031 2817 4031 2815 4031 2819 4032 2815 4032 2820 4032 2820 4033 2815 4033 2813 4033 2820 4034 2813 4034 2821 4034 2821 4035 2813 4035 2811 4035 2821 4036 2811 4036 2822 4036 2822 4037 2811 4037 2807 4037 2822 4038 2807 4038 2823 4038 2823 4039 2807 4039 2806 4039 2823 4040 2806 4040 2824 4040 1406 4041 2253 4041 2817 4041 2817 4042 2253 4042 2255 4042 2817 4043 2255 4043 2818 4043 2818 4044 2255 4044 2256 4044 2818 4045 2256 4045 2258 4045 2808 4046 2809 4046 2810 4046 2810 4047 2809 4047 2812 4047 2810 4048 2812 4048 2825 4048 2825 4049 2812 4049 2814 4049 2825 4050 2814 4050 2826 4050 2826 4051 2814 4051 2816 4051 2826 4052 2816 4052 2827 4052 2827 4053 2816 4053 2818 4053 2827 4054 2818 4054 2828 4054 2828 4055 2818 4055 2258 4055 2828 4056 2258 4056 2259 4056 1804 4057 2810 4057 1805 4057 1805 4058 2810 4058 2825 4058 1805 4059 2825 4059 1807 4059 1807 4060 2825 4060 2826 4060 1807 4061 2826 4061 1808 4061 1808 4062 2826 4062 2827 4062 1808 4063 2827 4063 1810 4063 1810 4064 2827 4064 2828 4064 1810 4065 2828 4065 1811 4065 1811 4066 2828 4066 2259 4066 1811 4067 2259 4067 1815 4067 2829 95 2830 95 2831 95 2832 95 2833 95 2834 95 2834 95 2833 95 2835 95 2834 95 2835 95 2836 95 2837 95 2838 95 2839 95 2839 95 2838 95 2840 95 2839 95 2840 95 2841 95 2841 95 2840 95 2836 95 2841 95 2836 95 2830 95 2830 95 2836 95 2835 95 2830 95 2835 95 2831 95 2831 95 2842 95 2829 95 2829 95 2842 95 2843 95 2829 95 2843 95 2844 95 2844 95 2845 95 2829 95 2829 95 2845 95 2846 95 2829 95 2846 95 2847 95 2847 95 2848 95 2829 95 2829 95 2848 95 2849 95 2829 95 2849 95 2850 95 1840 4068 1841 4068 2851 4068 2851 4069 1841 4069 2852 4069 2851 4070 2852 4070 2853 4070 2853 4071 2852 4071 2854 4071 1839 4072 1840 4072 2855 4072 2855 4073 1840 4073 2851 4073 2855 4074 2851 4074 2856 4074 2856 4075 2851 4075 2853 4075 1845 4076 1337 4076 1842 4076 2855 4077 2856 4077 2857 4077 1839 4078 2855 4078 2858 4078 2855 4079 2857 4079 2858 4079 2858 4080 2857 4080 2859 4080 2858 4081 2859 4081 2860 4081 2860 4082 2859 4082 2749 4082 2860 4083 2749 4083 2748 4083 1839 4084 2858 4084 1844 4084 1844 4085 2858 4085 2860 4085 1844 4086 2860 4086 1843 4086 1843 4087 2860 4087 2748 4087 1843 4088 2748 4088 1842 4088 2738 4089 2746 4089 2861 4089 2861 4090 2746 4090 2727 4090 2861 4091 2727 4091 2726 4091 2738 4092 2861 4092 2736 4092 2736 4093 2861 4093 2862 4093 2736 4094 2862 4094 2734 4094 2734 4095 2862 4095 2739 4095 2739 4096 2862 4096 2755 4096 2739 4097 2755 4097 2742 4097 1845 4098 2755 4098 1846 4098 1846 4099 2755 4099 2862 4099 1846 4100 2862 4100 1847 4100 1847 4101 2862 4101 2861 4101 1847 4102 2861 4102 1848 4102 1848 4103 2861 4103 2726 4103 2863 4104 2864 4104 2865 4104 2865 4105 2864 4105 2866 4105 2168 4106 2867 4106 2166 4106 2166 4107 2867 4107 2868 4107 2166 4108 2868 4108 2179 4108 2179 4109 2868 4109 2186 4109 2186 4110 2868 4110 2190 4110 2190 4111 2868 4111 2198 4111 2190 4112 2198 4112 2194 4112 2869 4113 2870 4113 2866 4113 2866 4114 2870 4114 2871 4114 2872 4115 2873 4115 2874 4115 2874 4116 2873 4116 2875 4116 2874 4117 2875 4117 2868 4117 2868 4118 2875 4118 2876 4118 2868 4119 2876 4119 2198 4119 2867 4120 2877 4120 2868 4120 2868 4121 2877 4121 2865 4121 2868 4122 2865 4122 2874 4122 2874 4123 2865 4123 2866 4123 2874 4124 2866 4124 2872 4124 2872 4125 2866 4125 2871 4125 2878 4126 2863 4126 2865 4126 2878 4127 2865 4127 2879 4127 2879 4128 2865 4128 2877 4128 2879 4129 2877 4129 2880 4129 2880 4130 2877 4130 2867 4130 2881 4131 2882 4131 2883 4131 2884 4132 2885 4132 2886 4132 2885 4133 2887 4133 2886 4133 2886 4134 2887 4134 2888 4134 2886 4135 2888 4135 2889 4135 2890 4136 2891 4136 2892 4136 2892 4137 2891 4137 2893 4137 2894 4138 2895 4138 2896 4138 2896 4139 2895 4139 2897 4139 2896 4140 2897 4140 2898 4140 2894 4141 2896 4141 2899 4141 2899 4142 2896 4142 2900 4142 2899 4143 2900 4143 2901 4143 2901 4144 2900 4144 2890 4144 2901 4145 2890 4145 2902 4145 2890 4146 2892 4146 2902 4146 2902 4147 2892 4147 2903 4147 2902 4148 2903 4148 2904 4148 2904 4149 2903 4149 2883 4149 2904 4150 2883 4150 2905 4150 2905 4151 2883 4151 2882 4151 2905 4152 2882 4152 2906 4152 2889 4153 2869 4153 2886 4153 2886 4154 2869 4154 2866 4154 2886 4155 2866 4155 2907 4155 2907 4156 2866 4156 2864 4156 2907 4157 2864 4157 2908 4157 2908 4158 2864 4158 2863 4158 2863 4159 2881 4159 2908 4159 2908 4160 2881 4160 2883 4160 2908 4161 2883 4161 2907 4161 2907 4162 2883 4162 2903 4162 2907 4163 2903 4163 2886 4163 2886 4164 2903 4164 2892 4164 2886 4165 2892 4165 2884 4165 2884 4166 2892 4166 2893 4166 2909 4167 2898 4167 2910 4167 899 4168 2911 4168 1858 4168 1858 4169 2911 4169 2912 4169 1858 4170 2912 4170 1860 4170 1860 4171 2912 4171 2913 4171 1860 4172 2913 4172 1862 4172 1862 4173 2913 4173 2914 4173 1862 4174 2914 4174 1864 4174 899 4175 2915 4175 2911 4175 2911 4176 2915 4176 2916 4176 2911 4177 2916 4177 2912 4177 2912 4178 2916 4178 2909 4178 2912 4179 2909 4179 2913 4179 2913 4180 2909 4180 2910 4180 2913 4181 2910 4181 2914 4181 2917 4182 1856 4182 1854 4182 2918 4183 2917 4183 2919 4183 2901 4184 2918 4184 2920 4184 2917 4185 1854 4185 2919 4185 2919 4186 1854 4186 1852 4186 2919 4187 1852 4187 2921 4187 2921 4188 1852 4188 1850 4188 2921 4189 1850 4189 2922 4189 2922 4190 1850 4190 1865 4190 2922 4191 1865 4191 2923 4191 2923 4192 1865 4192 1864 4192 2923 4193 1864 4193 2914 4193 2918 4194 2919 4194 2920 4194 2920 4195 2919 4195 2921 4195 2920 4196 2921 4196 2924 4196 2924 4197 2921 4197 2922 4197 2924 4198 2922 4198 2925 4198 2925 4199 2922 4199 2923 4199 2925 4200 2923 4200 2926 4200 2926 4201 2923 4201 2914 4201 2926 4202 2914 4202 2910 4202 2901 4203 2920 4203 2899 4203 2899 4204 2920 4204 2924 4204 2899 4205 2924 4205 2894 4205 2894 4206 2924 4206 2925 4206 2894 4207 2925 4207 2895 4207 2895 4208 2925 4208 2926 4208 2895 4209 2926 4209 2897 4209 2897 4210 2926 4210 2910 4210 2897 4211 2910 4211 2898 4211 2288 4212 1857 4212 1856 4212 2301 95 2927 95 2298 95 2298 95 2927 95 2928 95 2298 95 2928 95 2929 95 2930 4213 2301 4213 2931 4213 2931 4214 2301 4214 2288 4214 2931 95 2288 95 2932 95 2932 95 2288 95 1856 95 2933 95 2934 95 2301 95 1875 95 1877 95 2935 95 2935 95 1877 95 2298 95 2935 95 2298 95 2936 95 2936 95 2298 95 2937 95 2930 95 2938 95 2301 95 2301 4215 2938 4215 2939 4215 2301 4216 2939 4216 2940 4216 2934 95 2941 95 2301 95 2301 4217 2941 4217 2942 4217 2301 95 2942 95 2927 95 2940 95 2943 95 2301 95 2301 4218 2943 4218 2944 4218 2301 4219 2944 4219 2933 4219 2937 95 2298 95 2945 95 2945 95 2298 95 2929 95 2945 95 2929 95 2946 95 2946 95 2929 95 2947 95 2946 95 2947 95 2948 95 2948 95 2947 95 2949 95 2948 95 2949 95 2950 95 2950 95 2951 95 2948 95 2948 95 2951 95 2952 95 2948 95 2952 95 2953 95 2954 95 2955 95 2956 95 2953 95 2957 95 2948 95 2948 95 2957 95 2954 95 2948 95 2954 95 2958 95 2958 95 2954 95 2956 95 2959 4220 1879 4220 1869 4220 2960 4221 2959 4221 2961 4221 1885 4222 2960 4222 2962 4222 2959 4223 1869 4223 2961 4223 2961 4224 1869 4224 1871 4224 2961 4225 1871 4225 2963 4225 2963 4226 1871 4226 1873 4226 2963 4227 1873 4227 2964 4227 2964 4228 1873 4228 1875 4228 2964 4229 1875 4229 2965 4229 2960 4230 2961 4230 2962 4230 2962 4231 2961 4231 2963 4231 2962 4232 2963 4232 2966 4232 2966 4233 2963 4233 2964 4233 2966 4234 2964 4234 2967 4234 2967 4235 2964 4235 2965 4235 2967 4236 2965 4236 2968 4236 1885 4237 2962 4237 2969 4237 2969 4238 2962 4238 2966 4238 2969 4239 2966 4239 2970 4239 2970 4240 2966 4240 2967 4240 2970 4241 2967 4241 2971 4241 2971 4242 2967 4242 2968 4242 2971 4243 2968 4243 2972 4243 2973 4244 2959 4244 2960 4244 914 4245 2974 4245 1888 4245 1888 4246 2974 4246 2975 4246 1888 4247 2975 4247 1887 4247 1887 4248 2975 4248 2973 4248 1887 4249 2973 4249 1884 4249 1884 4250 2973 4250 2960 4250 1884 4251 2960 4251 1885 4251 914 4252 1866 4252 2974 4252 2974 4253 1866 4253 1878 4253 2974 4254 1878 4254 2975 4254 2975 4255 1878 4255 1880 4255 2975 4256 1880 4256 2973 4256 2973 4257 1880 4257 1879 4257 2973 4258 1879 4258 2959 4258 2976 4259 2802 4259 2800 4259 2977 4260 2978 4260 2979 4260 2979 4261 2978 4261 2980 4261 2979 4262 2980 4262 2981 4262 2981 4263 2980 4263 2982 4263 2970 4264 1905 4264 2969 4264 2969 4265 1905 4265 1885 4265 2970 4266 2971 4266 1905 4266 1905 4267 2971 4267 2972 4267 1905 4268 2972 4268 1906 4268 1906 4269 2972 4269 2983 4269 1906 4270 2983 4270 2977 4270 2977 4271 2983 4271 2984 4271 2977 4272 2984 4272 2978 4272 1909 4273 1908 4273 2977 4273 2977 4274 1908 4274 1907 4274 2977 4275 1907 4275 1906 4275 1912 4276 1911 4276 2985 4276 2985 4277 1911 4277 1910 4277 2986 4278 2987 4278 2976 4278 2987 4279 2986 4279 2988 4279 2976 4280 2800 4280 2986 4280 2986 4281 2800 4281 2788 4281 2986 4282 2788 4282 2989 4282 2989 4283 2788 4283 2789 4283 2989 4284 2789 4284 2985 4284 2985 4285 2789 4285 1913 4285 2985 4286 1913 4286 1912 4286 1910 4287 1909 4287 2985 4287 2985 4288 1909 4288 2977 4288 2985 4289 2977 4289 2989 4289 2989 4290 2977 4290 2979 4290 2989 4291 2979 4291 2986 4291 2986 4292 2979 4292 2981 4292 2986 4293 2981 4293 2988 4293 2988 4294 2981 4294 2982 4294 2990 4295 2991 4295 2239 4295 2233 4296 2992 4296 2235 4296 2235 4297 2992 4297 2990 4297 2235 4298 2990 4298 2237 4298 2237 4299 2990 4299 2239 4299 2228 4300 2993 4300 2229 4300 2229 4301 2993 4301 2992 4301 2229 4302 2992 4302 2231 4302 2231 4303 2992 4303 2233 4303 2994 4304 1914 4304 2995 4304 2995 4305 1914 4305 2616 4305 2226 4306 1923 4306 1924 4306 2227 4307 2996 4307 2228 4307 2228 4308 2996 4308 2997 4308 2228 4309 2997 4309 2993 4309 2994 4310 2998 4310 1914 4310 1914 4311 2998 4311 2999 4311 1914 4312 2999 4312 1924 4312 1924 4313 2999 4313 2996 4313 1924 4314 2996 4314 2226 4314 2226 4315 2996 4315 2227 4315 3000 4316 3001 4316 3002 4316 3003 4317 3004 4317 3005 4317 3005 4318 3004 4318 3006 4318 3005 4319 3006 4319 3002 4319 3002 4320 3006 4320 3007 4320 3002 4321 3007 4321 3000 4321 3005 4322 3008 4322 3009 4322 3003 4323 3005 4323 1927 4323 1927 4324 3005 4324 3009 4324 1927 4325 3009 4325 1928 4325 3008 4326 3005 4326 3010 4326 3010 4327 3005 4327 3002 4327 3010 4328 3002 4328 3011 4328 3010 4329 3011 4329 3012 4329 3008 4330 3010 4330 3013 4330 3009 4331 3008 4331 3014 4331 1928 4332 3009 4332 3015 4332 1928 4333 3015 4333 1950 4333 1950 4334 3015 4334 3016 4334 1950 4335 3016 4335 1952 4335 1952 4336 3016 4336 3017 4336 1952 4337 3017 4337 1954 4337 1954 4338 3017 4338 1956 4338 1956 4339 3017 4339 3018 4339 1956 4340 3018 4340 1958 4340 1958 4341 3018 4341 3019 4341 1958 4342 3019 4342 1960 4342 3010 4343 3012 4343 3013 4343 3013 4344 3012 4344 3020 4344 3013 4345 3020 4345 3021 4345 3021 4346 3020 4346 3022 4346 3021 4347 3022 4347 3023 4347 3023 4348 3022 4348 3024 4348 3023 4349 3024 4349 3025 4349 3025 4350 3024 4350 3026 4350 3025 4351 3026 4351 3027 4351 3027 4352 3026 4352 3028 4352 3027 4353 3028 4353 3029 4353 3029 4354 3028 4354 3030 4354 3029 4355 3030 4355 3031 4355 3031 4356 3030 4356 3032 4356 3031 4357 3032 4357 3033 4357 3033 4358 3032 4358 3034 4358 3033 4359 3034 4359 3035 4359 3035 4360 3034 4360 2434 4360 3035 4361 2434 4361 2425 4361 3008 4362 3013 4362 3014 4362 3014 4363 3013 4363 3021 4363 3014 4364 3021 4364 3036 4364 3036 4365 3021 4365 3023 4365 3036 4366 3023 4366 3037 4366 3037 4367 3023 4367 3025 4367 3037 4368 3025 4368 3038 4368 3038 4369 3025 4369 3027 4369 3038 4370 3027 4370 3039 4370 3039 4371 3027 4371 3029 4371 3039 4372 3029 4372 3040 4372 3040 4373 3029 4373 3031 4373 3040 4374 3031 4374 3041 4374 3041 4375 3031 4375 3033 4375 3041 4376 3033 4376 3042 4376 3042 4377 3033 4377 3035 4377 3042 4378 3035 4378 3043 4378 3043 4379 3035 4379 2425 4379 3043 4380 2425 4380 2417 4380 3009 4381 3014 4381 3015 4381 3015 4382 3014 4382 3036 4382 3015 4383 3036 4383 3016 4383 3016 4384 3036 4384 3037 4384 3016 4385 3037 4385 3017 4385 3017 4386 3037 4386 3038 4386 3017 4387 3038 4387 3018 4387 3018 4388 3038 4388 3039 4388 3018 4389 3039 4389 3019 4389 3019 4390 3039 4390 3040 4390 3019 4391 3040 4391 3044 4391 3044 4392 3040 4392 3041 4392 3044 4393 3041 4393 3045 4393 3045 4394 3041 4394 3042 4394 3045 4395 3042 4395 3046 4395 3046 4396 3042 4396 3043 4396 3046 4397 3043 4397 3047 4397 3047 4398 3043 4398 2417 4398 3047 4399 2417 4399 2405 4399 1960 4400 3019 4400 1961 4400 1961 4401 3019 4401 3044 4401 1961 4402 3044 4402 1946 4402 1946 4403 3044 4403 3045 4403 1946 4404 3045 4404 1944 4404 1944 4405 3045 4405 3046 4405 1944 4406 3046 4406 1942 4406 1942 4407 3046 4407 3047 4407 1942 4408 3047 4408 1940 4408 1940 4409 3047 4409 2405 4409 1940 4410 2405 4410 1938 4410 2003 4411 2001 4411 3048 4411 3049 4412 3048 4412 3050 4412 3051 4413 3052 4413 3048 4413 3048 4414 3052 4414 3053 4414 3048 4415 3053 4415 3054 4415 3054 4416 3055 4416 3048 4416 3048 4417 3055 4417 3056 4417 3048 4418 3056 4418 3050 4418 3057 4419 3058 4419 3059 4419 3059 4420 3058 4420 3060 4420 3059 4421 3060 4421 3051 4421 3051 4422 3060 4422 3061 4422 3051 4423 3061 4423 3052 4423 3062 4424 3063 4424 3064 4424 3064 4425 3063 4425 3057 4425 1979 4426 3065 4426 3066 4426 3066 4427 3065 4427 3067 4427 3066 4428 3067 4428 3064 4428 3064 4429 3067 4429 3068 4429 3064 4430 3068 4430 3062 4430 1979 4431 1977 4431 3065 4431 3065 4432 1977 4432 1975 4432 3065 4433 1975 4433 3069 4433 1975 4434 1973 4434 3069 4434 3069 4435 1973 4435 1971 4435 3069 4436 1971 4436 3070 4436 3070 4437 1971 4437 1969 4437 3070 4438 1969 4438 1968 4438 1968 4439 2054 4439 3070 4439 3070 4440 2054 4440 2052 4440 3070 4441 2052 4441 2050 4441 2050 4442 2048 4442 3070 4442 3070 4443 2048 4443 2047 4443 3070 4444 2047 4444 2040 4444 1987 4445 1985 4445 3064 4445 3064 4446 1985 4446 1983 4446 3064 4447 1983 4447 3066 4447 3066 4448 1983 4448 1981 4448 3066 4449 1981 4449 1979 4449 3057 4450 3059 4450 3064 4450 3064 4451 3059 4451 1989 4451 3064 4452 1989 4452 1987 4452 1997 4453 1995 4453 3051 4453 3051 4454 1995 4454 1993 4454 3051 4455 1993 4455 3059 4455 3059 4456 1993 4456 1991 4456 3059 4457 1991 4457 1989 4457 3048 4458 2001 4458 3051 4458 3051 4459 2001 4459 1999 4459 3051 4460 1999 4460 1997 4460 2003 4461 3048 4461 2005 4461 2005 4462 3048 4462 3049 4462 2005 4463 3049 4463 2007 4463 3071 4464 2011 4464 3049 4464 3049 4465 2011 4465 2009 4465 3049 4466 2009 4466 2007 4466 2019 4467 2017 4467 3072 4467 3072 4468 2017 4468 2015 4468 3072 4469 2015 4469 3071 4469 3071 4470 2015 4470 2013 4470 3071 4471 2013 4471 2011 4471 3050 4472 3073 4472 3049 4472 3049 4473 3073 4473 3074 4473 3049 4474 3074 4474 3071 4474 3071 4475 3074 4475 3075 4475 3071 4476 3075 4476 3072 4476 2028 4477 2027 4477 2121 4477 2026 4478 2543 4478 2027 4478 2121 4479 2030 4479 2029 4479 2024 4480 2030 4480 2121 4480 2023 4481 2024 4481 2121 4481 1964 4482 2021 4482 2120 4482 2120 4483 2021 4483 2023 4483 2120 4484 2023 4484 2121 4484 2543 4485 2542 4485 2027 4485 2027 4486 2542 4486 2121 4486 2029 4487 2028 4487 2121 4487 2037 4488 2039 4488 3076 4488 2042 4489 2037 4489 3077 4489 3077 4490 2037 4490 3076 4490 3077 4491 3076 4491 3078 4491 3078 4492 3076 4492 3079 4492 3078 4493 3079 4493 3080 4493 3080 4494 3079 4494 3081 4494 3080 4495 3081 4495 3082 4495 3082 4496 3081 4496 3083 4496 2040 4497 2042 4497 3084 4497 3084 4498 2042 4498 3077 4498 3084 4499 3077 4499 3085 4499 3085 4500 3077 4500 3078 4500 3085 4501 3078 4501 3086 4501 3086 4502 3078 4502 3080 4502 3086 4503 3080 4503 3087 4503 3087 4504 3080 4504 3082 4504 2061 4505 2063 4505 3088 4505 3088 4506 2063 4506 3089 4506 3088 4507 3089 4507 3090 4507 3090 4508 3089 4508 3091 4508 3090 4509 3091 4509 3092 4509 3092 4510 3091 4510 3093 4510 3092 4511 3093 4511 3094 4511 3094 4512 3093 4512 3095 4512 2039 4513 2061 4513 3076 4513 3076 4514 2061 4514 3088 4514 3076 4515 3088 4515 3079 4515 3079 4516 3088 4516 3090 4516 3079 4517 3090 4517 3081 4517 3081 4518 3090 4518 3092 4518 3081 4519 3092 4519 3083 4519 3083 4520 3092 4520 3094 4520 3096 4521 2112 4521 2097 4521 2624 4522 2623 4522 3096 4522 3096 4523 2097 4523 2624 4523 2624 4524 2097 4524 2095 4524 2624 4525 2095 4525 2625 4525 2625 4526 2095 4526 2094 4526 2625 4527 2094 4527 2626 4527 2626 4528 2094 4528 2108 4528 2626 4529 2108 4529 2627 4529 2627 4530 2108 4530 2109 4530 2627 4531 2109 4531 2620 4531 2620 4532 2109 4532 2101 4532 2620 4533 2101 4533 2619 4533 3097 4534 3098 4534 3099 4534 3099 4535 3098 4535 3100 4535 3101 4536 3102 4536 2093 4536 2111 4537 2112 4537 3103 4537 3103 4538 2112 4538 3104 4538 3103 4539 3104 4539 3105 4539 3105 4540 3104 4540 3106 4540 3105 4541 3106 4541 3107 4541 3107 4542 3106 4542 3108 4542 3107 4543 3108 4543 3109 4543 3109 4544 3108 4544 3110 4544 3101 4545 2093 4545 3111 4545 3111 4546 2093 4546 2092 4546 3111 4547 2092 4547 3112 4547 3112 4548 2092 4548 3113 4548 3112 4549 3113 4549 3114 4549 3114 4550 3113 4550 3115 4550 3114 4551 3115 4551 3116 4551 3116 4552 3115 4552 3117 4552 3116 4553 3117 4553 3118 4553 3119 4554 3120 4554 3118 4554 3121 4555 3122 4555 3120 4555 3123 4556 2765 4556 3097 4556 3097 4557 3099 4557 3123 4557 3123 4558 3099 4558 2776 4558 3123 4559 2776 4559 2774 4559 3122 4560 3121 4560 3124 4560 3124 4561 3121 4561 3125 4561 3124 4562 3125 4562 3100 4562 3100 4563 3125 4563 2780 4563 3100 4564 2780 4564 3099 4564 3099 4565 2780 4565 2778 4565 3099 4566 2778 4566 2776 4566 3126 4567 3127 4567 3121 4567 3121 4568 3127 4568 3128 4568 3121 4569 3128 4569 3125 4569 3125 4570 3128 4570 3129 4570 3125 4571 3129 4571 2780 4571 3120 4572 3119 4572 3121 4572 3121 4573 3119 4573 3130 4573 3121 4574 3130 4574 3126 4574 3126 4575 3130 4575 3131 4575 3126 4576 3131 4576 3127 4576 3109 4577 3132 4577 3107 4577 3107 4578 3132 4578 3133 4578 3107 4579 3133 4579 3105 4579 3105 4580 3133 4580 3134 4580 3105 4581 3134 4581 3103 4581 3103 4582 3134 4582 3135 4582 3103 4583 3135 4583 2111 4583 2111 4584 3135 4584 2110 4584 2092 4585 2110 4585 3113 4585 3113 4586 2110 4586 3135 4586 3113 4587 3135 4587 3115 4587 3115 4588 3135 4588 3134 4588 3115 4589 3134 4589 3117 4589 3117 4590 3134 4590 3133 4590 3117 4591 3133 4591 3118 4591 3118 4592 3133 4592 3132 4592 3118 4593 3132 4593 3119 4593 3119 4594 3132 4594 3109 4594 3119 4595 3109 4595 3130 4595 3130 4596 3109 4596 3110 4596 3130 4597 3110 4597 3131 4597 3136 4598 3137 4598 3138 4598 3139 4599 3140 4599 3141 4599 3142 4600 3138 4600 3143 4600 2093 4601 3102 4601 2072 4601 2072 4602 3102 4602 3144 4602 2072 4603 3144 4603 3142 4603 3145 4604 3136 4604 3139 4604 3137 4605 3136 4605 3146 4605 3139 4606 3141 4606 3145 4606 3145 4607 3141 4607 3147 4607 3145 4608 3147 4608 3148 4608 3148 4609 3147 4609 3149 4609 3148 4610 3149 4610 3150 4610 3150 4611 3149 4611 3151 4611 3150 4612 3151 4612 3152 4612 3152 4613 3151 4613 3153 4613 3152 4614 3153 4614 3154 4614 3154 4615 3153 4615 3155 4615 3154 4616 3155 4616 3156 4616 3156 4617 3155 4617 3157 4617 3156 4618 3157 4618 3158 4618 3158 4619 3157 4619 3159 4619 3158 4620 3159 4620 3160 4620 3160 4621 3159 4621 3161 4621 3160 4622 3161 4622 3162 4622 3162 4623 3161 4623 3163 4623 3162 4624 3163 4624 3164 4624 3164 4625 3163 4625 3165 4625 3164 4626 3165 4626 3166 4626 3166 4627 3165 4627 3095 4627 3166 4628 3095 4628 3093 4628 3136 4629 3145 4629 3146 4629 3146 4630 3145 4630 3148 4630 3146 4631 3148 4631 3167 4631 3167 4632 3148 4632 3150 4632 3167 4633 3150 4633 3168 4633 3168 4634 3150 4634 3152 4634 3168 4635 3152 4635 3169 4635 3169 4636 3152 4636 3154 4636 3169 4637 3154 4637 3170 4637 3170 4638 3154 4638 3156 4638 3170 4639 3156 4639 3171 4639 3171 4640 3156 4640 3158 4640 3171 4641 3158 4641 3172 4641 3172 4642 3158 4642 3160 4642 3172 4643 3160 4643 3173 4643 3173 4644 3160 4644 3162 4644 3173 4645 3162 4645 3174 4645 3174 4646 3162 4646 3164 4646 3174 4647 3164 4647 3175 4647 3175 4648 3164 4648 3166 4648 3175 4649 3166 4649 3176 4649 3176 4650 3166 4650 3093 4650 3176 4651 3093 4651 3091 4651 3138 4652 3137 4652 3143 4652 3143 4653 3137 4653 3146 4653 3143 4654 3146 4654 3177 4654 3177 4655 3146 4655 3167 4655 3177 4656 3167 4656 3178 4656 3178 4657 3167 4657 3168 4657 3178 4658 3168 4658 3179 4658 3179 4659 3168 4659 3169 4659 3179 4660 3169 4660 3180 4660 3180 4661 3169 4661 3170 4661 3180 4662 3170 4662 3181 4662 3181 4663 3170 4663 3171 4663 3181 4664 3171 4664 3182 4664 3182 4665 3171 4665 3172 4665 3182 4666 3172 4666 3183 4666 3183 4667 3172 4667 3173 4667 3183 4668 3173 4668 3184 4668 3184 4669 3173 4669 3174 4669 3184 4670 3174 4670 3185 4670 3185 4671 3174 4671 3175 4671 3185 4672 3175 4672 3186 4672 3186 4673 3175 4673 3176 4673 3186 4674 3176 4674 3187 4674 3187 4675 3176 4675 3091 4675 3187 4676 3091 4676 3089 4676 3142 4677 3143 4677 2072 4677 2072 4678 3143 4678 3177 4678 2072 4679 3177 4679 2073 4679 2073 4680 3177 4680 3178 4680 2073 4681 3178 4681 2075 4681 2075 4682 3178 4682 3179 4682 2075 4683 3179 4683 2076 4683 2076 4684 3179 4684 3180 4684 2076 4685 3180 4685 2113 4685 2113 4686 3180 4686 3181 4686 2113 4687 3181 4687 2117 4687 2117 4688 3181 4688 3182 4688 2117 4689 3182 4689 2088 4689 2088 4690 3182 4690 3183 4690 2088 4691 3183 4691 2089 4691 2089 4692 3183 4692 3184 4692 2089 4693 3184 4693 2090 4693 2090 4694 3184 4694 3185 4694 2090 4695 3185 4695 2091 4695 2091 4696 3185 4696 3186 4696 2091 4697 3186 4697 2086 4697 2086 4698 3186 4698 3187 4698 2086 4699 3187 4699 2087 4699 2087 4700 3187 4700 3089 4700 2087 4701 3089 4701 2063 4701 2239 95 2991 95 2154 95 2154 4702 2991 4702 3188 4702 2154 4703 3188 4703 2155 4703 2155 95 3188 95 2152 95 3189 95 3190 95 2152 95 2152 4704 3190 4704 3191 4704 2152 4705 3191 4705 2153 4705 3188 4706 3192 4706 2152 4706 2152 4707 3192 4707 3193 4707 2152 4708 3193 4708 3194 4708 3195 95 3196 95 3197 95 3194 4709 3198 4709 2152 4709 2152 4710 3198 4710 3199 4710 2152 95 3199 95 3200 95 3197 95 3201 95 3195 95 3195 95 3201 95 3202 95 3195 95 3202 95 3200 95 3200 95 3202 95 3203 95 3200 95 3203 95 2152 95 2152 95 3203 95 3204 95 2152 4711 3204 4711 3189 4711 1367 4712 3205 4712 2175 4712 2175 4713 3205 4713 3206 4713 2175 4714 3206 4714 2177 4714 2177 4715 3206 4715 3207 4715 1367 4716 2144 4716 3208 4716 3208 4717 2144 4717 2143 4717 3208 4718 2143 4718 3209 4718 3209 4719 2143 4719 2142 4719 3209 4720 2142 4720 3210 4720 3210 4721 2142 4721 2145 4721 3210 4722 2145 4722 3211 4722 3211 4723 2145 4723 2147 4723 3211 4724 2147 4724 3212 4724 3212 4725 2147 4725 2148 4725 3212 4726 2148 4726 3213 4726 3213 4727 2148 4727 2150 4727 3213 4728 2150 4728 3214 4728 3214 4729 2150 4729 2151 4729 3214 4730 2151 4730 3215 4730 1367 4731 3208 4731 3205 4731 3205 4732 3208 4732 3209 4732 3205 4733 3209 4733 3206 4733 3206 4734 3209 4734 3210 4734 3206 4735 3210 4735 3207 4735 3207 4736 3210 4736 3211 4736 3207 4737 3211 4737 3216 4737 3216 4738 3211 4738 3212 4738 3216 4739 3212 4739 3217 4739 3217 4740 3212 4740 3213 4740 3217 4741 3213 4741 3218 4741 3218 4742 3213 4742 3214 4742 3218 4743 3214 4743 3219 4743 3219 4744 3214 4744 3215 4744 3219 4745 3215 4745 3220 4745 2162 4746 2171 4746 3220 4746 3220 4747 2171 4747 2170 4747 3220 4748 2170 4748 3219 4748 3219 4749 2170 4749 2174 4749 3219 4750 2174 4750 3218 4750 3218 4751 2174 4751 2173 4751 3218 4752 2173 4752 3217 4752 3217 4753 2173 4753 2172 4753 3217 4754 2172 4754 3216 4754 3216 4755 2172 4755 2182 4755 3216 4756 2182 4756 3207 4756 3207 4757 2182 4757 2178 4757 3207 4758 2178 4758 2177 4758 2163 4759 2162 4759 3221 4759 3221 4760 2162 4760 3220 4760 3221 4761 3220 4761 3222 4761 3222 4762 3220 4762 3215 4762 3222 4763 3215 4763 2153 4763 2153 4764 3215 4764 2151 4764 3190 4765 3189 4765 3223 4765 3223 4766 3189 4766 3224 4766 3223 4767 3224 4767 3225 4767 3225 4768 3224 4768 3226 4768 3225 4769 3226 4769 2167 4769 2167 4770 3226 4770 2168 4770 3191 4771 3190 4771 3227 4771 3227 4772 3190 4772 3223 4772 3227 4773 3223 4773 3228 4773 3228 4774 3223 4774 3225 4774 3228 4775 3225 4775 2165 4775 2165 4776 3225 4776 2167 4776 2153 4777 3191 4777 3222 4777 3222 4778 3191 4778 3227 4778 3222 4779 3227 4779 3221 4779 3221 4780 3227 4780 3228 4780 3221 4781 3228 4781 2163 4781 2163 4782 3228 4782 2165 4782 2792 4783 2793 4783 3229 4783 3229 4784 2793 4784 3230 4784 3229 4785 3230 4785 3231 4785 3231 4786 3230 4786 3232 4786 3231 4787 3232 4787 3233 4787 3233 4788 3232 4788 3234 4788 3233 4789 3234 4789 3235 4789 3235 4790 3234 4790 2832 4790 2791 4791 2792 4791 3236 4791 3236 4792 2792 4792 3229 4792 3236 4793 3229 4793 3237 4793 3237 4794 3229 4794 3231 4794 3237 4795 3231 4795 3238 4795 3238 4796 3231 4796 3233 4796 3238 4797 3233 4797 3239 4797 3239 4798 3233 4798 3235 4798 1804 4799 2791 4799 2808 4799 2808 4800 2791 4800 3236 4800 2808 4801 3236 4801 2805 4801 2805 4802 3236 4802 3237 4802 2805 4803 3237 4803 2806 4803 2806 4804 3237 4804 3238 4804 2806 4805 3238 4805 2824 4805 2824 4806 3238 4806 3239 4806 2482 4807 2354 4807 2353 4807 2510 4808 2513 4808 3240 4808 2510 4809 3240 4809 2511 4809 2511 4810 3240 4810 3241 4810 2511 4811 3241 4811 2523 4811 2523 4812 3241 4812 3242 4812 2523 4813 3242 4813 2520 4813 2520 4814 3242 4814 3243 4814 2520 4815 3243 4815 2348 4815 2348 4816 3243 4816 3244 4816 3244 4817 3243 4817 3242 4817 3244 4818 3242 4818 3245 4818 3245 4819 3242 4819 3241 4819 3245 4820 3241 4820 3246 4820 3246 4821 3241 4821 3240 4821 3246 4822 3240 4822 3247 4822 2483 4823 3247 4823 2489 4823 2489 4824 3247 4824 3240 4824 2489 4825 3240 4825 2495 4825 2495 4826 3240 4826 2513 4826 2495 4827 2513 4827 2501 4827 2483 4828 2482 4828 3247 4828 3247 4829 2482 4829 2353 4829 3247 4830 2353 4830 3246 4830 3246 4831 2353 4831 2352 4831 3246 4832 2352 4832 3245 4832 3245 4833 2352 4833 2351 4833 3245 4834 2351 4834 3244 4834 3244 4835 2351 4835 2349 4835 3244 4836 2349 4836 2348 4836 2503 4837 2643 4837 1758 4837 2515 4838 3248 4838 3249 4838 2508 4839 2506 4839 3249 4839 3249 4840 2506 4840 2505 4840 3249 4841 2505 4841 2515 4841 2643 4842 2503 4842 2644 4842 2503 4843 2502 4843 2644 4843 2644 4844 2502 4844 2508 4844 2644 4845 2508 4845 2652 4845 2652 4846 2508 4846 3249 4846 2652 4847 3249 4847 2648 4847 2648 4848 3249 4848 3248 4848 2573 4849 2572 4849 3250 4849 2582 4850 2670 4850 2571 4850 2571 4851 2670 4851 2669 4851 2571 4852 2669 4852 2572 4852 2572 4853 2669 4853 2668 4853 2572 4854 2668 4854 3250 4854 3250 4855 2668 4855 2666 4855 3250 4856 2666 4856 3251 4856 3251 4857 2666 4857 2665 4857 3251 4858 2665 4858 3252 4858 3252 4859 2665 4859 2674 4859 3252 4860 2674 4860 3253 4860 3253 4861 2674 4861 2673 4861 3253 4862 2673 4862 3254 4862 3254 4863 2673 4863 2671 4863 3254 4864 2671 4864 3255 4864 3255 4865 2671 4865 2602 4865 2602 4866 2601 4866 3255 4866 3255 4867 2601 4867 2600 4867 3255 4868 2600 4868 3254 4868 3254 4869 2600 4869 2598 4869 3254 4870 2598 4870 3253 4870 3253 4871 2598 4871 2597 4871 3253 4872 2597 4872 3252 4872 3252 4873 2597 4873 2603 4873 3252 4874 2603 4874 3251 4874 3251 4875 2603 4875 2564 4875 3251 4876 2564 4876 3250 4876 3250 4877 2564 4877 2563 4877 3250 4878 2563 4878 2573 4878 2604 4879 2591 4879 2592 4879 2555 4880 2565 4880 2593 4880 2593 4881 2565 4881 2566 4881 2593 4882 2566 4882 2592 4882 2592 4883 2566 4883 2564 4883 2592 4884 2564 4884 2604 4884 1693 4885 2585 4885 2604 4885 2604 4886 2585 4886 2584 4886 2604 4887 2584 4887 2591 4887 3256 4888 3257 4888 3258 4888 2612 4889 2611 4889 3259 4889 3259 4890 2611 4890 3260 4890 3260 4891 2611 4891 2609 4891 3260 4892 2609 4892 3261 4892 3261 4893 2609 4893 3262 4893 3262 4894 2609 4894 2607 4894 3262 4895 2607 4895 3263 4895 3263 4896 2607 4896 2606 4896 3263 4897 2606 4897 3264 4897 3265 4898 3266 4898 3267 4898 3267 4899 3266 4899 3256 4899 3267 4900 3256 4900 3268 4900 3268 4901 3256 4901 3258 4901 3264 4902 2606 4902 3265 4902 3265 4903 2606 4903 2595 4903 3265 4904 2595 4904 3266 4904 3266 4905 2595 4905 2594 4905 3266 4906 2594 4906 3256 4906 3256 4907 2594 4907 2614 4907 3256 4908 2614 4908 3257 4908 3269 4909 2616 4909 2615 4909 3261 4910 3269 4910 3260 4910 3260 4911 3269 4911 2615 4911 3260 4912 2615 4912 3259 4912 3259 4913 2615 4913 2617 4913 3259 4914 2617 4914 2612 4914 2786 4915 2784 4915 3270 4915 2633 4916 2786 4916 3271 4916 2786 4917 3270 4917 3271 4917 3271 4918 3270 4918 3272 4918 3271 4919 3272 4919 3273 4919 3273 4920 3272 4920 3274 4920 3273 4921 3274 4921 3275 4921 3275 4922 3274 4922 3127 4922 3275 4923 3127 4923 3276 4923 2633 4924 3271 4924 2634 4924 2634 4925 3271 4925 3273 4925 2634 4926 3273 4926 2635 4926 2635 4927 3273 4927 3275 4927 2635 4928 3275 4928 2630 4928 2630 4929 3275 4929 3276 4929 2630 4930 3276 4930 2631 4930 3276 4931 3127 4931 3131 4931 2631 4932 3276 4932 3277 4932 3276 4933 3131 4933 3277 4933 3277 4934 3131 4934 3110 4934 3277 4935 3110 4935 3278 4935 3278 4936 3110 4936 3108 4936 3278 4937 3108 4937 3279 4937 3279 4938 3108 4938 3106 4938 3279 4939 3106 4939 3280 4939 3280 4940 3106 4940 3104 4940 3280 4941 3104 4941 3281 4941 3281 4942 3104 4942 2112 4942 3281 4943 2112 4943 3096 4943 2631 4944 3277 4944 2632 4944 2632 4945 3277 4945 3278 4945 2632 4946 3278 4946 2628 4946 2628 4947 3278 4947 3279 4947 2628 4948 3279 4948 2629 4948 2629 4949 3279 4949 3280 4949 2629 4950 3280 4950 2621 4950 2621 4951 3280 4951 3281 4951 2621 4952 3281 4952 2622 4952 2622 4953 3281 4953 3096 4953 2622 4954 3096 4954 2623 4954 2619 4955 2101 4955 2641 4955 2619 4956 2641 4956 2618 4956 2618 4957 2641 4957 2637 4957 2618 4958 2637 4958 1757 4958 2742 4959 3282 4959 2743 4959 2743 4960 3282 4960 2744 4960 2744 4961 3282 4961 3283 4961 2744 4962 3283 4962 2740 4962 3284 4963 2735 4963 3283 4963 3283 4964 2735 4964 2741 4964 3283 4965 2741 4965 2740 4965 2718 4966 1761 4966 2733 4966 2718 4967 2733 4967 3285 4967 3285 4968 2733 4968 2732 4968 3285 4969 2732 4969 3286 4969 3286 4970 2732 4970 2731 4970 3286 4971 2731 4971 3287 4971 3287 4972 2731 4972 2730 4972 3287 4973 2730 4973 3284 4973 3284 4974 2730 4974 2737 4974 3284 4975 2737 4975 2735 4975 2742 4976 2752 4976 3282 4976 3282 4977 2752 4977 2754 4977 3282 4978 2754 4978 3283 4978 3283 4979 2754 4979 2758 4979 3283 4980 2758 4980 3284 4980 3284 4981 2758 4981 2757 4981 3284 4982 2757 4982 3287 4982 3287 4983 2757 4983 2761 4983 3287 4984 2761 4984 3286 4984 3286 4985 2761 4985 2759 4985 3286 4986 2759 4986 3285 4986 3285 4987 2759 4987 2722 4987 3285 4988 2722 4988 2718 4988 3111 4989 3288 4989 3101 4989 2763 4990 3289 4990 806 4990 3290 4991 2750 4991 3291 4991 3291 4992 2750 4992 2749 4992 3291 4993 2749 4993 2859 4993 3289 4994 2763 4994 3292 4994 2763 4995 2762 4995 3292 4995 3292 4996 2762 4996 2760 4996 3292 4997 2760 4997 3290 4997 3290 4998 2760 4998 2756 4998 3290 4999 2756 4999 2750 4999 3097 5000 2765 5000 3289 5000 3289 5001 2765 5001 2766 5001 3289 5002 2766 5002 806 5002 3097 5003 3289 5003 3098 5003 3098 5004 3289 5004 3292 5004 3098 5005 3292 5005 3100 5005 3293 5006 3294 5006 3295 5006 3295 5007 3294 5007 3120 5007 3295 5008 3120 5008 3122 5008 3112 5009 3114 5009 3296 5009 3296 5010 3114 5010 3116 5010 3296 5011 3116 5011 3297 5011 3297 5012 3116 5012 3118 5012 3297 5013 3118 5013 3298 5013 3298 5014 3118 5014 3299 5014 3111 5015 3112 5015 3288 5015 3288 5016 3112 5016 3296 5016 3288 5017 3296 5017 3300 5017 3300 5018 3296 5018 3297 5018 3300 5019 3297 5019 3301 5019 3301 5020 3297 5020 3302 5020 3302 5021 3297 5021 3298 5021 3302 5022 3298 5022 3303 5022 3304 5023 3305 5023 3306 5023 3306 5024 3305 5024 3307 5024 3308 5025 3309 5025 3310 5025 3310 5026 3309 5026 3311 5026 3310 5027 3311 5027 3307 5027 3307 5028 3311 5028 3312 5028 3307 5029 3312 5029 3306 5029 2859 5030 2857 5030 3293 5030 3293 5031 2857 5031 2856 5031 3293 5032 2856 5032 2853 5032 2859 5033 3293 5033 3291 5033 3291 5034 3293 5034 3295 5034 3291 5035 3295 5035 3290 5035 3290 5036 3295 5036 3122 5036 3290 5037 3122 5037 3292 5037 3292 5038 3122 5038 3124 5038 3292 5039 3124 5039 3100 5039 3304 5040 3303 5040 3305 5040 3305 5041 3303 5041 3298 5041 3305 5042 3298 5042 3307 5042 3307 5043 3298 5043 3299 5043 3307 5044 3299 5044 3310 5044 3118 5045 3120 5045 3299 5045 3299 5046 3120 5046 3294 5046 3299 5047 3294 5047 3310 5047 3310 5048 3294 5048 3293 5048 3310 5049 3293 5049 3308 5049 3308 5050 3293 5050 2853 5050 3308 5051 2853 5051 2854 5051 2764 5052 2765 5052 2770 5052 2770 5053 2765 5053 3123 5053 2770 5054 3123 5054 2771 5054 2771 5055 3123 5055 2774 5055 3270 5056 2784 5056 2785 5056 3274 5057 3272 5057 3313 5057 3313 5058 3272 5058 3270 5058 3270 5059 2785 5059 3313 5059 3313 5060 2785 5060 2783 5060 3313 5061 2783 5061 2781 5061 3127 5062 3274 5062 3128 5062 3128 5063 3274 5063 3313 5063 3128 5064 3313 5064 3129 5064 3129 5065 3313 5065 2781 5065 3129 5066 2781 5066 2780 5066 3314 5067 2804 5067 3315 5067 3315 5068 2804 5068 2803 5068 3315 5069 2803 5069 3316 5069 3316 5070 2803 5070 2802 5070 3232 5071 3230 5071 3317 5071 2804 5072 3318 5072 3319 5072 3320 5073 2831 5073 2835 5073 3320 5074 2835 5074 3321 5074 3321 5075 2835 5075 2833 5075 3321 5076 2833 5076 3322 5076 3322 5077 2833 5077 2832 5077 3322 5078 2832 5078 3234 5078 2842 5079 2831 5079 3318 5079 3318 5080 2831 5080 3320 5080 3318 5081 3320 5081 3319 5081 3319 5082 3320 5082 3321 5082 3319 5083 3321 5083 3323 5083 3323 5084 3321 5084 3322 5084 3323 5085 3322 5085 3317 5085 3317 5086 3322 5086 3234 5086 3317 5087 3234 5087 3232 5087 2804 5088 3319 5088 2798 5088 2798 5089 3319 5089 3323 5089 2798 5090 3323 5090 2796 5090 2796 5091 3323 5091 3317 5091 2796 5092 3317 5092 2794 5092 2794 5093 3317 5093 3230 5093 2794 5094 3230 5094 2793 5094 2804 5095 3314 5095 3318 5095 3318 5096 3314 5096 3324 5096 3318 5097 3324 5097 2842 5097 2842 5098 3324 5098 2843 5098 3325 5099 2850 5099 2849 5099 3326 5100 3325 5100 3327 5100 3326 5101 3327 5101 3328 5101 3328 5102 3327 5102 3329 5102 3328 5103 3329 5103 3330 5103 3330 5104 3329 5104 3331 5104 3330 5105 3331 5105 3332 5105 3332 5106 3331 5106 3333 5106 3332 5107 3333 5107 3334 5107 3334 5108 3333 5108 3335 5108 3334 5109 3335 5109 3336 5109 3336 5110 3335 5110 3337 5110 3336 5111 3337 5111 3338 5111 3325 5112 2849 5112 3327 5112 3327 5113 2849 5113 2848 5113 3327 5114 2848 5114 3329 5114 3329 5115 2848 5115 2847 5115 3329 5116 2847 5116 3331 5116 3331 5117 2847 5117 2846 5117 3331 5118 2846 5118 3333 5118 3333 5119 2846 5119 2845 5119 3333 5120 2845 5120 3335 5120 3335 5121 2845 5121 2844 5121 3335 5122 2844 5122 3337 5122 3337 5123 2844 5123 2843 5123 3337 5124 2843 5124 3324 5124 3338 5125 3337 5125 3339 5125 3339 5126 3337 5126 3324 5126 3339 5127 3324 5127 3314 5127 3340 5128 2830 5128 2829 5128 3340 5129 3341 5129 3342 5129 3342 5130 3343 5130 3340 5130 3340 5131 3343 5131 3344 5131 3340 5132 3344 5132 3311 5132 3345 5133 3346 5133 3347 5133 3346 5134 3348 5134 3347 5134 3347 5135 3348 5135 3349 5135 3347 5136 3349 5136 3350 5136 2850 5137 3345 5137 2829 5137 2829 5138 3345 5138 3347 5138 2829 5139 3347 5139 3340 5139 3340 5140 3347 5140 3350 5140 3340 5141 3350 5141 3341 5141 2867 5142 2168 5142 3351 5142 3351 5143 2168 5143 3226 5143 3351 5144 3226 5144 3352 5144 3352 5145 3226 5145 3224 5145 3352 5146 3224 5146 3204 5146 3204 5147 3224 5147 3189 5147 2880 5148 2867 5148 3353 5148 3353 5149 2867 5149 3351 5149 3353 5150 3351 5150 3354 5150 3354 5151 3351 5151 3352 5151 3354 5152 3352 5152 3203 5152 3203 5153 3352 5153 3204 5153 3355 5154 3356 5154 3357 5154 3358 5155 3359 5155 3360 5155 3360 5156 3359 5156 3361 5156 3360 5157 3361 5157 3362 5157 3362 5158 3361 5158 3363 5158 3362 5159 3363 5159 3364 5159 3365 5160 3366 5160 3358 5160 3358 5161 3366 5161 3367 5161 3358 5162 3367 5162 3359 5162 3358 5163 3368 5163 3365 5163 3365 5164 3368 5164 3369 5164 3365 5165 3369 5165 3370 5165 3370 5166 3369 5166 3371 5166 2878 5167 2879 5167 3372 5167 3372 5168 2879 5168 2880 5168 3369 5169 3373 5169 3371 5169 3371 5170 3373 5170 3372 5170 3371 5171 3372 5171 3374 5171 3374 5172 3372 5172 2880 5172 3375 5173 3376 5173 3377 5173 3376 5174 3375 5174 3357 5174 2863 5175 3378 5175 3379 5175 3379 5176 3378 5176 3380 5176 3379 5177 3380 5177 3381 5177 3381 5178 3380 5178 3382 5178 3381 5179 3382 5179 3383 5179 3383 5180 3382 5180 3384 5180 3383 5181 3384 5181 3385 5181 3385 5182 3384 5182 3386 5182 3385 5183 3386 5183 3387 5183 3387 5184 3386 5184 3388 5184 3387 5185 3388 5185 3389 5185 3389 5186 3388 5186 3390 5186 3389 5187 3390 5187 3391 5187 3391 5188 3390 5188 3375 5188 3391 5189 3375 5189 3392 5189 3392 5190 3375 5190 3377 5190 3392 5191 3377 5191 3393 5191 2863 5192 2878 5192 3378 5192 3378 5193 2878 5193 3372 5193 3378 5194 3372 5194 3380 5194 3380 5195 3372 5195 3373 5195 3380 5196 3373 5196 3382 5196 3382 5197 3373 5197 3369 5197 3382 5198 3369 5198 3384 5198 3384 5199 3369 5199 3368 5199 3384 5200 3368 5200 3386 5200 3386 5201 3368 5201 3358 5201 3386 5202 3358 5202 3388 5202 3388 5203 3358 5203 3360 5203 3388 5204 3360 5204 3390 5204 3390 5205 3360 5205 3362 5205 3390 5206 3362 5206 3375 5206 3375 5207 3362 5207 3364 5207 3375 5208 3364 5208 3357 5208 3357 5209 3364 5209 3363 5209 3357 5210 3363 5210 3355 5210 3394 5211 3395 5211 3396 5211 2906 5212 3397 5212 3398 5212 3398 5213 3397 5213 3399 5213 3398 5214 3399 5214 3400 5214 3400 5215 3399 5215 3401 5215 3400 5216 3401 5216 3402 5216 3402 5217 3401 5217 3403 5217 3402 5218 3403 5218 3404 5218 3404 5219 3403 5219 3405 5219 3404 5220 3405 5220 3406 5220 3406 5221 3405 5221 3407 5221 3406 5222 3407 5222 3408 5222 3408 5223 3407 5223 3409 5223 3408 5224 3409 5224 3410 5224 3410 5225 3409 5225 3411 5225 3410 5226 3411 5226 3412 5226 3412 5227 3411 5227 3396 5227 3412 5228 3396 5228 3413 5228 3413 5229 3396 5229 3395 5229 3413 5230 3395 5230 3414 5230 2881 5231 2863 5231 3415 5231 2881 5232 3415 5232 2882 5232 2863 5233 3416 5233 3415 5233 3415 5234 3416 5234 3417 5234 3415 5235 3417 5235 3418 5235 3418 5236 3417 5236 3419 5236 3418 5237 3419 5237 3420 5237 3420 5238 3419 5238 3421 5238 3420 5239 3421 5239 3422 5239 3422 5240 3421 5240 3423 5240 3422 5241 3423 5241 3424 5241 3424 5242 3423 5242 3425 5242 3424 5243 3425 5243 3426 5243 3426 5244 3425 5244 3427 5244 3426 5245 3427 5245 3428 5245 3428 5246 3427 5246 3429 5246 3428 5247 3429 5247 3430 5247 3430 5248 3429 5248 3431 5248 3430 5249 3431 5249 3432 5249 3432 5250 3431 5250 3433 5250 3433 5251 3394 5251 3432 5251 3432 5252 3394 5252 3396 5252 3432 5253 3396 5253 3430 5253 3430 5254 3396 5254 3411 5254 3430 5255 3411 5255 3428 5255 3428 5256 3411 5256 3409 5256 3428 5257 3409 5257 3426 5257 3426 5258 3409 5258 3407 5258 3426 5259 3407 5259 3424 5259 3424 5260 3407 5260 3405 5260 3424 5261 3405 5261 3422 5261 3422 5262 3405 5262 3403 5262 3422 5263 3403 5263 3420 5263 3420 5264 3403 5264 3401 5264 3420 5265 3401 5265 3418 5265 3418 5266 3401 5266 3399 5266 3418 5267 3399 5267 3415 5267 3415 5268 3399 5268 3397 5268 3415 5269 3397 5269 2882 5269 2882 5270 3397 5270 2906 5270 2905 5271 2906 5271 3434 5271 2902 5272 2904 5272 3435 5272 2932 5273 1856 5273 3436 5273 3436 5274 1856 5274 2917 5274 3436 5275 2917 5275 3435 5275 3435 5276 2917 5276 2918 5276 3435 5277 2918 5277 2902 5277 2902 5278 2918 5278 2901 5278 2931 5279 2932 5279 3437 5279 3437 5280 2932 5280 3436 5280 3437 5281 3436 5281 3434 5281 3434 5282 3436 5282 3435 5282 3434 5283 3435 5283 2905 5283 2905 5284 3435 5284 2904 5284 1875 5285 2935 5285 2965 5285 2965 5286 2935 5286 3438 5286 2965 5287 3438 5287 2968 5287 2968 5288 3438 5288 3439 5288 2968 5289 3439 5289 2972 5289 2978 5290 2984 5290 3439 5290 3439 5291 2984 5291 2983 5291 3439 5292 2983 5292 2972 5292 3440 5293 3441 5293 3442 5293 3442 5294 3441 5294 3443 5294 2945 5295 3441 5295 2937 5295 2937 5296 3441 5296 3440 5296 2937 5297 3440 5297 2936 5297 3444 5298 3443 5298 3445 5298 3445 5299 3443 5299 3441 5299 3445 5300 3441 5300 3446 5300 3446 5301 3441 5301 2945 5301 2935 5302 2936 5302 3438 5302 3438 5303 2936 5303 3440 5303 3438 5304 3440 5304 3439 5304 3439 5305 3440 5305 3442 5305 3439 5306 3442 5306 2978 5306 2978 5307 3442 5307 3443 5307 2978 5308 3443 5308 2980 5308 2980 5309 3443 5309 3444 5309 2980 5310 3444 5310 2982 5310 3434 5311 2906 5311 3398 5311 3437 5312 3434 5312 3447 5312 2931 5313 3437 5313 3448 5313 3434 5314 3398 5314 3447 5314 3447 5315 3398 5315 3400 5315 3447 5316 3400 5316 3449 5316 3449 5317 3400 5317 3402 5317 3449 5318 3402 5318 3450 5318 3450 5319 3402 5319 3404 5319 3450 5320 3404 5320 3451 5320 3451 5321 3404 5321 3406 5321 3451 5322 3406 5322 3452 5322 3452 5323 3406 5323 3408 5323 3452 5324 3408 5324 3453 5324 3453 5325 3408 5325 3410 5325 3453 5326 3410 5326 3454 5326 3454 5327 3410 5327 3412 5327 3454 5328 3412 5328 3455 5328 3455 5329 3412 5329 3413 5329 3455 5330 3413 5330 3456 5330 3456 5331 3413 5331 3414 5331 3456 5332 3414 5332 3457 5332 3437 5333 3447 5333 3448 5333 3448 5334 3447 5334 3449 5334 3448 5335 3449 5335 3458 5335 3458 5336 3449 5336 3450 5336 3458 5337 3450 5337 3459 5337 3459 5338 3450 5338 3451 5338 3459 5339 3451 5339 3460 5339 3460 5340 3451 5340 3452 5340 3460 5341 3452 5341 3461 5341 3461 5342 3452 5342 3453 5342 3461 5343 3453 5343 3462 5343 3462 5344 3453 5344 3454 5344 3462 5345 3454 5345 3463 5345 3463 5346 3454 5346 3455 5346 3463 5347 3455 5347 3464 5347 3464 5348 3455 5348 3456 5348 3464 5349 3456 5349 3465 5349 3465 5350 3456 5350 3457 5350 3465 5351 3457 5351 3466 5351 2931 5352 3448 5352 2930 5352 2930 5353 3448 5353 3458 5353 2930 5354 3458 5354 2938 5354 2938 5355 3458 5355 3459 5355 2938 5356 3459 5356 2939 5356 2939 5357 3459 5357 3460 5357 2939 5358 3460 5358 2940 5358 2940 5359 3460 5359 3461 5359 2940 5360 3461 5360 2943 5360 2943 5361 3461 5361 3462 5361 2943 5362 3462 5362 2944 5362 2944 5363 3462 5363 3463 5363 2944 5364 3463 5364 2933 5364 2933 5365 3463 5365 3464 5365 2933 5366 3464 5366 2934 5366 2934 5367 3464 5367 3465 5367 2934 5368 3465 5368 2941 5368 2941 5369 3465 5369 3466 5369 2941 5370 3466 5370 2942 5370 3467 5371 2929 5371 2928 5371 3468 5372 3469 5372 3470 5372 3470 5373 3469 5373 3467 5373 3470 5374 3467 5374 3471 5374 3471 5375 3467 5375 2928 5375 3472 5376 3468 5376 3473 5376 3473 5377 3468 5377 3470 5377 3473 5378 3470 5378 3474 5378 3474 5379 3470 5379 3471 5379 3474 5380 3471 5380 2927 5380 2927 5381 3471 5381 2928 5381 3414 5382 3472 5382 3457 5382 3457 5383 3472 5383 3473 5383 3457 5384 3473 5384 3466 5384 3466 5385 3473 5385 3474 5385 3466 5386 3474 5386 2942 5386 2942 5387 3474 5387 2927 5387 3475 5388 3476 5388 3477 5388 3477 5389 3476 5389 3478 5389 3477 5390 3478 5390 2947 5390 2947 5391 3478 5391 2949 5391 3469 5392 3475 5392 3467 5392 3467 5393 3475 5393 3477 5393 3467 5394 3477 5394 2929 5394 2929 5395 3477 5395 2947 5395 3479 5396 2946 5396 2948 5396 3480 5397 3479 5397 3481 5397 3479 5398 2948 5398 3481 5398 3481 5399 2948 5399 2958 5399 3481 5400 2958 5400 3482 5400 3482 5401 2958 5401 2956 5401 3482 5402 2956 5402 3483 5402 3483 5403 2956 5403 2955 5403 3483 5404 2955 5404 3484 5404 3484 5405 2955 5405 2954 5405 3484 5406 2954 5406 3485 5406 3485 5407 2954 5407 2957 5407 3485 5408 2957 5408 3486 5408 3486 5409 2957 5409 2953 5409 3486 5410 2953 5410 3487 5410 3487 5411 2953 5411 2952 5411 3487 5412 2952 5412 3488 5412 3488 5413 2952 5413 2951 5413 3488 5414 2951 5414 3489 5414 3489 5415 2951 5415 2950 5415 3489 5416 2950 5416 3490 5416 3490 5417 2950 5417 2949 5417 3490 5418 2949 5418 3478 5418 3480 5419 3481 5419 3491 5419 3491 5420 3481 5420 3482 5420 3491 5421 3482 5421 3492 5421 3492 5422 3482 5422 3483 5422 3492 5423 3483 5423 3493 5423 3493 5424 3483 5424 3484 5424 3493 5425 3484 5425 3494 5425 3494 5426 3484 5426 3485 5426 3494 5427 3485 5427 3495 5427 3495 5428 3485 5428 3486 5428 3495 5429 3486 5429 3496 5429 3496 5430 3486 5430 3487 5430 3496 5431 3487 5431 3497 5431 3497 5432 3487 5432 3488 5432 3497 5433 3488 5433 3498 5433 3498 5434 3488 5434 3489 5434 3498 5435 3489 5435 3499 5435 3499 5436 3489 5436 3490 5436 3499 5437 3490 5437 3500 5437 3500 5438 3490 5438 3478 5438 3500 5439 3478 5439 3476 5439 3479 5440 3480 5440 3444 5440 3444 5441 3480 5441 2982 5441 2945 5442 2946 5442 3446 5442 3446 5443 2946 5443 3479 5443 3446 5444 3479 5444 3445 5444 3445 5445 3479 5445 3444 5445 3501 5446 3316 5446 2802 5446 2982 5447 3480 5447 2988 5447 2988 5448 3480 5448 3502 5448 2988 5449 3502 5449 2987 5449 2987 5450 3502 5450 3501 5450 2987 5451 3501 5451 2976 5451 2976 5452 3501 5452 2802 5452 3269 5453 3261 5453 3262 5453 2616 5454 3269 5454 3503 5454 3503 5455 3269 5455 3262 5455 3503 5456 3262 5456 3504 5456 3504 5457 3262 5457 3263 5457 3263 5458 3264 5458 3504 5458 3504 5459 3264 5459 3265 5459 3504 5460 3265 5460 3267 5460 3267 5461 3268 5461 3504 5461 3504 5462 3268 5462 3258 5462 3504 5463 3258 5463 3505 5463 2616 5464 3503 5464 2995 5464 2995 5465 3503 5465 3504 5465 2995 5466 3504 5466 2994 5466 2994 5467 3504 5467 3505 5467 2994 5468 3505 5468 2998 5468 3505 5469 3258 5469 3506 5469 2998 5470 3505 5470 3507 5470 3505 5471 3506 5471 3507 5471 3507 5472 3506 5472 3508 5472 3507 5473 3508 5473 3509 5473 3509 5474 3508 5474 3510 5474 3509 5475 3510 5475 3511 5475 3511 5476 3510 5476 3512 5476 3511 5477 3512 5477 3513 5477 3513 5478 3512 5478 3514 5478 3513 5479 3514 5479 3515 5479 3515 5480 3514 5480 3516 5480 3515 5481 3516 5481 3517 5481 3516 5482 3518 5482 3519 5482 3516 5483 3519 5483 3517 5483 3517 5484 3519 5484 3520 5484 3517 5485 3520 5485 3521 5485 2998 5486 3507 5486 2999 5486 2999 5487 3507 5487 3509 5487 2999 5488 3509 5488 2996 5488 2996 5489 3509 5489 3511 5489 2996 5490 3511 5490 2997 5490 2997 5491 3511 5491 3513 5491 2997 5492 3513 5492 2993 5492 2993 5493 3513 5493 3515 5493 2993 5494 3515 5494 2992 5494 2992 5495 3515 5495 3517 5495 2992 5496 3517 5496 2990 5496 2990 5497 3517 5497 3521 5497 2990 5498 3521 5498 2991 5498 3522 5499 3001 5499 3000 5499 3523 5500 3522 5500 3524 5500 3052 5501 3523 5501 3525 5501 3522 5502 3000 5502 3524 5502 3524 5503 3000 5503 3007 5503 3524 5504 3007 5504 3526 5504 3526 5505 3007 5505 3006 5505 3526 5506 3006 5506 3527 5506 3006 5507 3004 5507 3527 5507 3527 5508 3004 5508 3003 5508 3527 5509 3003 5509 3528 5509 3528 5510 3003 5510 1927 5510 3528 5511 1927 5511 3529 5511 3523 5512 3524 5512 3525 5512 3525 5513 3524 5513 3526 5513 3525 5514 3526 5514 3530 5514 3530 5515 3526 5515 3527 5515 3530 5516 3527 5516 3531 5516 3531 5517 3527 5517 3528 5517 3531 5518 3528 5518 3532 5518 3532 5519 3528 5519 3529 5519 3532 5520 3529 5520 3533 5520 3052 5521 3525 5521 3053 5521 3053 5522 3525 5522 3530 5522 3053 5523 3530 5523 3054 5523 3054 5524 3530 5524 3531 5524 3054 5525 3531 5525 3055 5525 3055 5526 3531 5526 3532 5526 3055 5527 3532 5527 3056 5527 3056 5528 3532 5528 3533 5528 3056 5529 3533 5529 3050 5529 3534 5530 3535 5530 3536 5530 3001 5531 3522 5531 3537 5531 3535 5532 3061 5532 3060 5532 3535 5533 3060 5533 3536 5533 3536 5534 3060 5534 3058 5534 3536 5535 3058 5535 3538 5535 3538 5536 3058 5536 3057 5536 3538 5537 3057 5537 3539 5537 3539 5538 3057 5538 3063 5538 3539 5539 3063 5539 3540 5539 3540 5540 3063 5540 3062 5540 3540 5541 3062 5541 3541 5541 3541 5542 3062 5542 3068 5542 3541 5543 3068 5543 3542 5543 3542 5544 3068 5544 3067 5544 3542 5545 3067 5545 3543 5545 3543 5546 3067 5546 3065 5546 3543 5547 3065 5547 3544 5547 3544 5548 3065 5548 3069 5548 3544 5549 3069 5549 3545 5549 3545 5550 3069 5550 3070 5550 3545 5551 3070 5551 3546 5551 3546 5552 3070 5552 2040 5552 3546 5553 2040 5553 3084 5553 3534 5554 3536 5554 3547 5554 3547 5555 3536 5555 3538 5555 3547 5556 3538 5556 3548 5556 3548 5557 3538 5557 3539 5557 3548 5558 3539 5558 3549 5558 3549 5559 3539 5559 3540 5559 3549 5560 3540 5560 3550 5560 3550 5561 3540 5561 3541 5561 3550 5562 3541 5562 3551 5562 3551 5563 3541 5563 3542 5563 3551 5564 3542 5564 3552 5564 3552 5565 3542 5565 3543 5565 3552 5566 3543 5566 3553 5566 3553 5567 3543 5567 3544 5567 3553 5568 3544 5568 3554 5568 3554 5569 3544 5569 3545 5569 3554 5570 3545 5570 3555 5570 3555 5571 3545 5571 3546 5571 3555 5572 3546 5572 3556 5572 3556 5573 3546 5573 3084 5573 3556 5574 3084 5574 3085 5574 3052 5575 3061 5575 3523 5575 3523 5576 3061 5576 3535 5576 3523 5577 3535 5577 3522 5577 3522 5578 3535 5578 3534 5578 3522 5579 3534 5579 3537 5579 3537 5580 3534 5580 3547 5580 3537 5581 3547 5581 3557 5581 3557 5582 3547 5582 3548 5582 3557 5583 3548 5583 3558 5583 3558 5584 3548 5584 3549 5584 3558 5585 3549 5585 3559 5585 3559 5586 3549 5586 3550 5586 3559 5587 3550 5587 3560 5587 3560 5588 3550 5588 3551 5588 3560 5589 3551 5589 3561 5589 3561 5590 3551 5590 3552 5590 3561 5591 3552 5591 3562 5591 3562 5592 3552 5592 3553 5592 3562 5593 3553 5593 3563 5593 3563 5594 3553 5594 3554 5594 3563 5595 3554 5595 3564 5595 3564 5596 3554 5596 3555 5596 3564 5597 3555 5597 3565 5597 3565 5598 3555 5598 3556 5598 3565 5599 3556 5599 3566 5599 3566 5600 3556 5600 3085 5600 3566 5601 3085 5601 3086 5601 3001 5602 3537 5602 3567 5602 3567 5603 3537 5603 3557 5603 3567 5604 3557 5604 3568 5604 3568 5605 3557 5605 3558 5605 3568 5606 3558 5606 3569 5606 3569 5607 3558 5607 3559 5607 3569 5608 3559 5608 3570 5608 3570 5609 3559 5609 3560 5609 3570 5610 3560 5610 3571 5610 3571 5611 3560 5611 3561 5611 3571 5612 3561 5612 3572 5612 3572 5613 3561 5613 3562 5613 3572 5614 3562 5614 3573 5614 3573 5615 3562 5615 3563 5615 3573 5616 3563 5616 3574 5616 3574 5617 3563 5617 3564 5617 3574 5618 3564 5618 3575 5618 3575 5619 3564 5619 3565 5619 3575 5620 3565 5620 3576 5620 3576 5621 3565 5621 3566 5621 3576 5622 3566 5622 3577 5622 3577 5623 3566 5623 3086 5623 3577 5624 3086 5624 3087 5624 3301 5625 3302 5625 3578 5625 3579 5626 3580 5626 3581 5626 3582 5627 3583 5627 3584 5627 3584 5628 3585 5628 3582 5628 3582 5629 3585 5629 3586 5629 3582 5630 3586 5630 3587 5630 3587 5631 3588 5631 3582 5631 3582 5632 3588 5632 3589 5632 3582 5633 3589 5633 3590 5633 3306 5634 3591 5634 3583 5634 3306 5635 3583 5635 3304 5635 3304 5636 3583 5636 3582 5636 3304 5637 3582 5637 3303 5637 3312 5638 3592 5638 3306 5638 3306 5639 3592 5639 3593 5639 3306 5640 3593 5640 3591 5640 3312 5641 3311 5641 3594 5641 3312 5642 3594 5642 3592 5642 3592 5643 3594 5643 3595 5643 3592 5644 3595 5644 3596 5644 3597 5645 3144 5645 3598 5645 3598 5646 3144 5646 3102 5646 3301 5647 3578 5647 3300 5647 3300 5648 3578 5648 3598 5648 3300 5649 3598 5649 3288 5649 3288 5650 3598 5650 3102 5650 3288 5651 3102 5651 3101 5651 3599 5652 3600 5652 3601 5652 3601 5653 3600 5653 3602 5653 3590 5654 3579 5654 3582 5654 3582 5655 3579 5655 3581 5655 3582 5656 3581 5656 3600 5656 3600 5657 3581 5657 3603 5657 3600 5658 3603 5658 3602 5658 3602 5659 3603 5659 3604 5659 3602 5660 3604 5660 3601 5660 3599 5661 3597 5661 3600 5661 3600 5662 3597 5662 3598 5662 3600 5663 3598 5663 3582 5663 3582 5664 3598 5664 3578 5664 3582 5665 3578 5665 3303 5665 3303 5666 3578 5666 3302 5666 3144 5667 3597 5667 3142 5667 3142 5668 3597 5668 3138 5668 3597 5669 3599 5669 3138 5669 3138 5670 3599 5670 3601 5670 3138 5671 3601 5671 3136 5671 3136 5672 3601 5672 3604 5672 3136 5673 3604 5673 3139 5673 3605 5674 3188 5674 2991 5674 3518 5675 3606 5675 3519 5675 3519 5676 3606 5676 3607 5676 3519 5677 3607 5677 3520 5677 3520 5678 3607 5678 3605 5678 3520 5679 3605 5679 3521 5679 3521 5680 3605 5680 2991 5680 3192 5681 3188 5681 3608 5681 3608 5682 3188 5682 3605 5682 3608 5683 3605 5683 3609 5683 3609 5684 3605 5684 3607 5684 3609 5685 3607 5685 3356 5685 3356 5686 3607 5686 3606 5686 3354 5687 3203 5687 3202 5687 3353 5688 3354 5688 3610 5688 2880 5689 3353 5689 3611 5689 3354 5690 3202 5690 3610 5690 3610 5691 3202 5691 3201 5691 3610 5692 3201 5692 3612 5692 3612 5693 3201 5693 3197 5693 3612 5694 3197 5694 3613 5694 3613 5695 3197 5695 3196 5695 3613 5696 3196 5696 3614 5696 3614 5697 3196 5697 3195 5697 3614 5698 3195 5698 3615 5698 3615 5699 3195 5699 3200 5699 3615 5700 3200 5700 3616 5700 3616 5701 3200 5701 3199 5701 3616 5702 3199 5702 3617 5702 3617 5703 3199 5703 3198 5703 3617 5704 3198 5704 3618 5704 3618 5705 3198 5705 3194 5705 3618 5706 3194 5706 3619 5706 3619 5707 3194 5707 3193 5707 3619 5708 3193 5708 3620 5708 3620 5709 3193 5709 3192 5709 3620 5710 3192 5710 3608 5710 3353 5711 3610 5711 3611 5711 3611 5712 3610 5712 3612 5712 3611 5713 3612 5713 3621 5713 3621 5714 3612 5714 3613 5714 3621 5715 3613 5715 3622 5715 3622 5716 3613 5716 3614 5716 3622 5717 3614 5717 3623 5717 3623 5718 3614 5718 3615 5718 3623 5719 3615 5719 3624 5719 3624 5720 3615 5720 3616 5720 3624 5721 3616 5721 3625 5721 3625 5722 3616 5722 3617 5722 3625 5723 3617 5723 3626 5723 3626 5724 3617 5724 3618 5724 3626 5725 3618 5725 3627 5725 3627 5726 3618 5726 3619 5726 3627 5727 3619 5727 3628 5727 3628 5728 3619 5728 3620 5728 3628 5729 3620 5729 3629 5729 3629 5730 3620 5730 3608 5730 3629 5731 3608 5731 3609 5731 2880 5732 3611 5732 3374 5732 3374 5733 3611 5733 3621 5733 3374 5734 3621 5734 3371 5734 3371 5735 3621 5735 3622 5735 3371 5736 3622 5736 3370 5736 3370 5737 3622 5737 3623 5737 3370 5738 3623 5738 3365 5738 3365 5739 3623 5739 3624 5739 3365 5740 3624 5740 3366 5740 3366 5741 3624 5741 3625 5741 3366 5742 3625 5742 3367 5742 3367 5743 3625 5743 3626 5743 3367 5744 3626 5744 3359 5744 3359 5745 3626 5745 3627 5745 3359 5746 3627 5746 3361 5746 3361 5747 3627 5747 3628 5747 3361 5748 3628 5748 3363 5748 3363 5749 3628 5749 3629 5749 3363 5750 3629 5750 3355 5750 3355 5751 3629 5751 3609 5751 3355 5752 3609 5752 3356 5752 3630 5753 3631 5753 3632 5753 3632 5754 3631 5754 3633 5754 3632 5755 3633 5755 3634 5755 3632 5756 3634 5756 3635 5756 3635 5757 3634 5757 3580 5757 3636 5758 3637 5758 3630 5758 3630 5759 3637 5759 3638 5759 3630 5760 3638 5760 3631 5760 3639 5761 3640 5761 3641 5761 3641 5762 3640 5762 3642 5762 3641 5763 3642 5763 3643 5763 3643 5764 3642 5764 3637 5764 3643 5765 3637 5765 3644 5765 3644 5766 3637 5766 3636 5766 3641 5767 3643 5767 3645 5767 3645 5768 3643 5768 3644 5768 3314 5769 3315 5769 3646 5769 3314 5770 3646 5770 3339 5770 3339 5771 3646 5771 3647 5771 3339 5772 3647 5772 3338 5772 3338 5773 3647 5773 3648 5773 3338 5774 3648 5774 3336 5774 3648 5775 3649 5775 3336 5775 3336 5776 3649 5776 3650 5776 3336 5777 3650 5777 3334 5777 3334 5778 3650 5778 3651 5778 3334 5779 3651 5779 3332 5779 3332 5780 3651 5780 3652 5780 3332 5781 3652 5781 3330 5781 3644 5782 3636 5782 3653 5782 3654 5783 3655 5783 3656 5783 3656 5784 3655 5784 3657 5784 3658 5785 3654 5785 3659 5785 3659 5786 3654 5786 3656 5786 3659 5787 3656 5787 3660 5787 3660 5788 3656 5788 3653 5788 3639 5789 3641 5789 3652 5789 3652 5790 3641 5790 3645 5790 3652 5791 3645 5791 3330 5791 3330 5792 3645 5792 3644 5792 3330 5793 3644 5793 3328 5793 3328 5794 3644 5794 3653 5794 3328 5795 3653 5795 3326 5795 3326 5796 3653 5796 3656 5796 3326 5797 3656 5797 3661 5797 3661 5798 3656 5798 3657 5798 3639 5799 3652 5799 3662 5799 3662 5800 3652 5800 3651 5800 3662 5801 3651 5801 3663 5801 3663 5802 3651 5802 3650 5802 3663 5803 3650 5803 3664 5803 3664 5804 3650 5804 3649 5804 3664 5805 3649 5805 3665 5805 3665 5806 3649 5806 3648 5806 3665 5807 3648 5807 3666 5807 3666 5808 3648 5808 3647 5808 3666 5809 3647 5809 3667 5809 3667 5810 3647 5810 3646 5810 3667 5811 3646 5811 3668 5811 3668 5812 3646 5812 3315 5812 3668 5813 3315 5813 3316 5813 3669 5814 3670 5814 3671 5814 3672 5815 3498 5815 3673 5815 3673 5816 3498 5816 3499 5816 3673 5817 3499 5817 3674 5817 3674 5818 3499 5818 3500 5818 3674 5819 3500 5819 3675 5819 3675 5820 3500 5820 3476 5820 3491 5821 3492 5821 3676 5821 3676 5822 3492 5822 3493 5822 3676 5823 3493 5823 3677 5823 3677 5824 3493 5824 3494 5824 3677 5825 3494 5825 3678 5825 3678 5826 3494 5826 3495 5826 3678 5827 3495 5827 3679 5827 3679 5828 3495 5828 3496 5828 3679 5829 3496 5829 3672 5829 3672 5830 3496 5830 3497 5830 3672 5831 3497 5831 3498 5831 3480 5832 3491 5832 3502 5832 3502 5833 3491 5833 3676 5833 3502 5834 3676 5834 3501 5834 3476 5835 3669 5835 3675 5835 3675 5836 3669 5836 3671 5836 3675 5837 3671 5837 3674 5837 3674 5838 3671 5838 3680 5838 3674 5839 3680 5839 3673 5839 3673 5840 3680 5840 3681 5840 3673 5841 3681 5841 3672 5841 3672 5842 3681 5842 3682 5842 3672 5843 3682 5843 3679 5843 3679 5844 3682 5844 3683 5844 3679 5845 3683 5845 3678 5845 3678 5846 3683 5846 3684 5846 3678 5847 3684 5847 3677 5847 3677 5848 3684 5848 3685 5848 3677 5849 3685 5849 3676 5849 3676 5850 3685 5850 3686 5850 3676 5851 3686 5851 3501 5851 3501 5852 3686 5852 3316 5852 3316 5853 3686 5853 3687 5853 3687 5854 3686 5854 3685 5854 3687 5855 3685 5855 3688 5855 3688 5856 3685 5856 3684 5856 3688 5857 3684 5857 3689 5857 3689 5858 3684 5858 3683 5858 3689 5859 3683 5859 3690 5859 3690 5860 3683 5860 3682 5860 3690 5861 3682 5861 3691 5861 3691 5862 3682 5862 3681 5862 3691 5863 3681 5863 3692 5863 3692 5864 3681 5864 3680 5864 3692 5865 3680 5865 3693 5865 3693 5866 3680 5866 3671 5866 3693 5867 3671 5867 3694 5867 3694 5868 3671 5868 3670 5868 3694 5869 3670 5869 3695 5869 3696 5870 3695 5870 3697 5870 3697 5871 3695 5871 3670 5871 3697 5872 3670 5872 3698 5872 3698 5873 3670 5873 3669 5873 3698 5874 3669 5874 3475 5874 3475 5875 3669 5875 3476 5875 3699 5876 3696 5876 3700 5876 3700 5877 3696 5877 3697 5877 3700 5878 3697 5878 3701 5878 3701 5879 3697 5879 3698 5879 3701 5880 3698 5880 3702 5880 3702 5881 3698 5881 3475 5881 3702 5882 3475 5882 3469 5882 3468 5883 3472 5883 3703 5883 3472 5884 3414 5884 3704 5884 3704 5885 3414 5885 3395 5885 3704 5886 3395 5886 3705 5886 3705 5887 3395 5887 3394 5887 3706 5888 3705 5888 3707 5888 3707 5889 3705 5889 3394 5889 3707 5890 3394 5890 3433 5890 3472 5891 3704 5891 3703 5891 3703 5892 3704 5892 3705 5892 3703 5893 3705 5893 3708 5893 3708 5894 3705 5894 3706 5894 3708 5895 3706 5895 3699 5895 3469 5896 3468 5896 3702 5896 3702 5897 3468 5897 3703 5897 3702 5898 3703 5898 3701 5898 3701 5899 3703 5899 3708 5899 3701 5900 3708 5900 3700 5900 3700 5901 3708 5901 3699 5901 3506 5902 3258 5902 3257 5902 3516 5903 3514 5903 3709 5903 3709 5904 3514 5904 3512 5904 3506 5905 3710 5905 3508 5905 3508 5906 3710 5906 3709 5906 3508 5907 3709 5907 3510 5907 3510 5908 3709 5908 3512 5908 3356 5909 3606 5909 3709 5909 3709 5910 3606 5910 3518 5910 3709 5911 3518 5911 3516 5911 3257 5912 2614 5912 3711 5912 3506 5913 3257 5913 3710 5913 3710 5914 3257 5914 3711 5914 3710 5915 3711 5915 3393 5915 3393 5916 3377 5916 3710 5916 3710 5917 3377 5917 3376 5917 3710 5918 3376 5918 3709 5918 3709 5919 3376 5919 3357 5919 3709 5920 3357 5920 3356 5920 3712 5921 3653 5921 3636 5921 3713 5922 3349 5922 3348 5922 3714 5923 3715 5923 3716 5923 3716 5924 3715 5924 3717 5924 3718 5925 3719 5925 3658 5925 3658 5926 3719 5926 3720 5926 3712 5927 3721 5927 3653 5927 3653 5928 3721 5928 3722 5928 3653 5929 3722 5929 3660 5929 3660 5930 3722 5930 3718 5930 3660 5931 3718 5931 3659 5931 3659 5932 3718 5932 3658 5932 3717 5933 3713 5933 3716 5933 3716 5934 3713 5934 3348 5934 3716 5935 3348 5935 3723 5935 3723 5936 3348 5936 3346 5936 3723 5937 3346 5937 3724 5937 3724 5938 3346 5938 3345 5938 3724 5939 3345 5939 3725 5939 3725 5940 3345 5940 2850 5940 3725 5941 2850 5941 3325 5941 3720 5942 3714 5942 3658 5942 3658 5943 3714 5943 3716 5943 3658 5944 3716 5944 3654 5944 3654 5945 3716 5945 3723 5945 3654 5946 3723 5946 3655 5946 3655 5947 3723 5947 3724 5947 3655 5948 3724 5948 3657 5948 3657 5949 3724 5949 3725 5949 3657 5950 3725 5950 3661 5950 3661 5951 3725 5951 3325 5951 3661 5952 3325 5952 3326 5952 3311 5953 3344 5953 3594 5953 3594 5954 3344 5954 3343 5954 3594 5955 3343 5955 3595 5955 3595 5956 3343 5956 3342 5956 3595 5957 3342 5957 3596 5957 3596 5958 3342 5958 3341 5958 3596 5959 3341 5959 3592 5959 3592 5960 3341 5960 3350 5960 3349 5961 3584 5961 3350 5961 3350 5962 3584 5962 3583 5962 3583 5963 3591 5963 3350 5963 3350 5964 3591 5964 3593 5964 3350 5965 3593 5965 3592 5965 3580 5966 3721 5966 3712 5966 3632 5967 3712 5967 3630 5967 3630 5968 3712 5968 3636 5968 3712 5969 3632 5969 3635 5969 3712 5970 3635 5970 3580 5970 3721 5971 3580 5971 3722 5971 3722 5972 3580 5972 3579 5972 3722 5973 3579 5973 3718 5973 3718 5974 3579 5974 3590 5974 3718 5975 3590 5975 3719 5975 3719 5976 3590 5976 3589 5976 3719 5977 3589 5977 3720 5977 3720 5978 3589 5978 3588 5978 3720 5979 3588 5979 3714 5979 3714 5980 3588 5980 3587 5980 3714 5981 3587 5981 3715 5981 3715 5982 3587 5982 3586 5982 3715 5983 3586 5983 3717 5983 3717 5984 3586 5984 3585 5984 3717 5985 3585 5985 3713 5985 3713 5986 3585 5986 3584 5986 3713 5987 3584 5987 3349 5987 3726 5988 599 5988 598 5988 596 5989 3727 5989 598 5989 598 5990 3727 5990 3728 5990 598 5991 3728 5991 3726 5991 3729 5992 3730 5992 593 5992 593 5993 3730 5993 3731 5993 593 5994 3731 5994 596 5994 596 5995 3731 5995 3732 5995 596 5996 3732 5996 3727 5996 593 5997 591 5997 3729 5997 3729 5998 591 5998 584 5998 3729 5999 584 5999 3733 5999 3733 106 584 106 3734 106 3734 6000 584 6000 582 6000 3734 106 582 106 727 106 2870 6001 2869 6001 3735 6001 3735 6002 2869 6002 3736 6002 3735 6003 3736 6003 3737 6003 3737 6004 3736 6004 3738 6004 3737 6005 3738 6005 3739 6005 3739 6006 3738 6006 3740 6006 3739 6007 3740 6007 903 6007 903 6008 3740 6008 902 6008 2871 6009 2870 6009 3741 6009 3741 6010 2870 6010 3735 6010 3741 6011 3735 6011 3742 6011 3742 6012 3735 6012 3737 6012 3742 6013 3737 6013 3743 6013 3743 6014 3737 6014 3739 6014 3743 6015 3739 6015 904 6015 904 6016 3739 6016 903 6016 3744 6017 2915 6017 899 6017 3745 6018 2916 6018 2915 6018 3746 6019 2909 6019 2916 6019 2896 6020 2898 6020 2909 6020 2909 6021 3746 6021 2896 6021 2896 6022 3746 6022 3747 6022 2896 6023 3747 6023 2900 6023 2900 6024 3747 6024 3748 6024 2900 6025 3748 6025 2890 6025 899 6026 898 6026 3744 6026 3744 6027 898 6027 897 6027 3744 6028 897 6028 3749 6028 3749 6029 897 6029 896 6029 3749 6030 896 6030 3750 6030 3750 6031 896 6031 895 6031 3750 6032 895 6032 3751 6032 3751 6033 895 6033 894 6033 3751 6034 894 6034 3752 6034 3752 6035 894 6035 907 6035 3752 6036 907 6036 3753 6036 3753 6037 907 6037 906 6037 3753 6038 906 6038 3754 6038 3754 6039 906 6039 905 6039 3754 6040 905 6040 3755 6040 3755 6041 905 6041 901 6041 3755 6042 901 6042 3756 6042 3756 6043 901 6043 902 6043 3756 6044 902 6044 3740 6044 2915 6045 3744 6045 3745 6045 3745 6046 3744 6046 3749 6046 3745 6047 3749 6047 3757 6047 3757 6048 3749 6048 3750 6048 3757 6049 3750 6049 3758 6049 3758 6050 3750 6050 3751 6050 3758 6051 3751 6051 3759 6051 3759 6052 3751 6052 3752 6052 3759 6053 3752 6053 3760 6053 3760 6054 3752 6054 3753 6054 3760 6055 3753 6055 3761 6055 3761 6056 3753 6056 3754 6056 3761 6057 3754 6057 3762 6057 3762 6058 3754 6058 3755 6058 3762 6059 3755 6059 3763 6059 3763 6060 3755 6060 3756 6060 3763 6061 3756 6061 3764 6061 3764 6062 3756 6062 3740 6062 3764 6063 3740 6063 3738 6063 2916 6064 3745 6064 3746 6064 3746 6065 3745 6065 3757 6065 3746 6066 3757 6066 3747 6066 3747 6067 3757 6067 3758 6067 3747 6068 3758 6068 3748 6068 3748 6069 3758 6069 3759 6069 3748 6070 3759 6070 3765 6070 3765 6071 3759 6071 3760 6071 3765 6072 3760 6072 3766 6072 3766 6073 3760 6073 3761 6073 3766 6074 3761 6074 3767 6074 3767 6075 3761 6075 3762 6075 3767 6076 3762 6076 3768 6076 3768 6077 3762 6077 3763 6077 3768 6078 3763 6078 3769 6078 3769 6079 3763 6079 3764 6079 3769 6080 3764 6080 3770 6080 3770 6081 3764 6081 3738 6081 3770 6082 3738 6082 3736 6082 2890 6083 3748 6083 2891 6083 2891 6084 3748 6084 3765 6084 2891 6085 3765 6085 2893 6085 2893 6086 3765 6086 3766 6086 2893 6087 3766 6087 2884 6087 2884 6088 3766 6088 3767 6088 2884 6089 3767 6089 2885 6089 2885 6090 3767 6090 3768 6090 2885 6091 3768 6091 2887 6091 2887 6092 3768 6092 3769 6092 2887 6093 3769 6093 2888 6093 2888 6094 3769 6094 3770 6094 2888 6095 3770 6095 2889 6095 2889 6096 3770 6096 3736 6096 2889 6097 3736 6097 2869 6097 3743 6098 904 6098 925 6098 3742 6099 3743 6099 3771 6099 3741 6100 3742 6100 3772 6100 2871 6101 3741 6101 3773 6101 3743 6102 925 6102 3771 6102 3771 6103 925 6103 924 6103 3771 6104 924 6104 3774 6104 3774 6105 924 6105 921 6105 3774 6106 921 6106 3775 6106 3775 6107 921 6107 919 6107 3775 6108 919 6108 3776 6108 3776 6109 919 6109 918 6109 3776 6110 918 6110 2195 6110 3742 6111 3771 6111 3772 6111 3772 6112 3771 6112 3774 6112 3772 6113 3774 6113 3777 6113 3777 6114 3774 6114 3775 6114 3777 6115 3775 6115 3778 6115 3778 6116 3775 6116 3776 6116 3778 6117 3776 6117 3779 6117 3779 6118 3776 6118 2195 6118 3779 6119 2195 6119 2196 6119 3741 6120 3772 6120 3773 6120 3773 6121 3772 6121 3777 6121 3773 6122 3777 6122 3780 6122 3780 6123 3777 6123 3778 6123 3780 6124 3778 6124 3781 6124 3781 6125 3778 6125 3779 6125 3781 6126 3779 6126 3782 6126 3782 6127 3779 6127 2196 6127 3782 6128 2196 6128 2197 6128 2871 6129 3773 6129 2872 6129 2872 6130 3773 6130 3780 6130 2872 6131 3780 6131 2873 6131 2873 6132 3780 6132 3781 6132 2873 6133 3781 6133 2875 6133 2875 6134 3781 6134 3782 6134 2875 6135 3782 6135 2876 6135 2876 6136 3782 6136 2197 6136 2876 6137 2197 6137 2198 6137 3783 6138 2837 6138 2839 6138 3783 6139 2839 6139 3784 6139 3785 6140 3786 6140 3784 6140 3787 6141 3788 6141 3786 6141 3786 6142 3785 6142 3787 6142 3787 6143 3785 6143 3789 6143 3787 6144 3789 6144 3790 6144 3790 6145 3789 6145 3340 6145 3790 6146 3340 6146 3311 6146 3784 6147 2839 6147 3785 6147 3785 6148 2839 6148 2841 6148 3785 6149 2841 6149 3789 6149 3789 6150 2841 6150 2830 6150 3789 6151 2830 6151 3340 6151 2837 6152 3783 6152 3791 6152 3791 6153 3783 6153 3784 6153 3791 6154 3784 6154 3792 6154 3792 6155 3784 6155 3786 6155 3792 6156 3786 6156 3793 6156 3793 6157 3786 6157 3788 6157 3793 6158 3788 6158 3794 6158 2837 6159 3791 6159 3795 6159 3795 6160 3791 6160 3792 6160 3795 6161 3792 6161 3796 6161 3796 6162 3792 6162 3793 6162 3796 6163 3793 6163 3797 6163 3797 6164 3793 6164 3794 6164 3797 6165 3794 6165 3798 6165 3794 6166 3788 6166 3799 6166 3800 6167 3798 6167 3801 6167 3801 6168 3798 6168 3794 6168 3800 6169 3801 6169 3802 6169 3802 6170 3801 6170 3803 6170 3802 6171 3803 6171 3804 6171 3804 6172 3803 6172 3805 6172 3804 6173 3805 6173 3806 6173 3806 6174 3805 6174 3807 6174 3806 6175 3807 6175 3808 6175 3794 6176 3799 6176 3801 6176 3801 6177 3799 6177 3809 6177 3801 6178 3809 6178 3803 6178 3803 6179 3809 6179 3810 6179 3803 6180 3810 6180 3805 6180 3805 6181 3810 6181 3811 6181 3805 6182 3811 6182 3807 6182 3807 6183 3811 6183 3812 6183 3807 6184 3812 6184 3813 6184 3813 6185 3812 6185 3814 6185 3813 6186 3814 6186 3815 6186 3808 6187 3807 6187 3816 6187 3816 6188 3807 6188 3813 6188 3816 6189 3813 6189 3817 6189 3817 6190 3813 6190 3815 6190 3817 6191 3815 6191 3818 6191 3818 6192 3815 6192 3819 6192 1837 6193 3820 6193 3821 6193 3821 6194 3820 6194 3822 6194 3821 6195 3822 6195 3823 6195 3823 6196 3822 6196 3824 6196 3823 6197 3824 6197 3825 6197 3825 6198 3824 6198 3826 6198 3825 6199 3826 6199 3827 6199 3827 6200 3826 6200 3828 6200 3827 6201 3828 6201 3829 6201 3829 6202 3828 6202 3830 6202 3829 6203 3830 6203 3819 6203 3819 6204 3830 6204 3831 6204 3819 6205 3831 6205 3818 6205 1837 6206 3821 6206 3832 6206 3832 6207 3821 6207 3823 6207 3832 6208 3823 6208 3833 6208 3833 6209 3823 6209 3825 6209 3833 6210 3825 6210 3834 6210 3834 6211 3825 6211 3827 6211 3834 6212 3827 6212 3835 6212 3835 6213 3827 6213 3829 6213 3835 6214 3829 6214 3836 6214 3836 6215 3829 6215 3819 6215 3836 6216 3819 6216 3837 6216 3837 6217 3819 6217 3815 6217 3837 6218 3815 6218 3814 6218 1838 6219 1837 6219 3838 6219 3838 6220 1837 6220 3832 6220 3838 6221 3832 6221 3833 6221 3833 6222 3834 6222 3838 6222 3838 6223 3834 6223 3835 6223 3838 6224 3835 6224 3839 6224 3839 6225 3835 6225 3836 6225 3814 6226 3840 6226 3837 6226 3837 6227 3840 6227 3841 6227 3837 6228 3841 6228 3842 6228 3842 6229 3841 6229 3843 6229 3842 6230 3843 6230 3844 6230 3844 6231 3843 6231 2854 6231 3844 6232 2854 6232 2852 6232 1841 6233 1838 6233 2852 6233 2852 6234 1838 6234 3838 6234 2852 6235 3838 6235 3844 6235 3844 6236 3838 6236 3839 6236 3844 6237 3839 6237 3842 6237 3842 6238 3839 6238 3836 6238 3842 6239 3836 6239 3837 6239 3787 6240 3845 6240 3788 6240 3790 6241 3311 6241 3309 6241 3846 6242 3812 6242 3811 6242 3811 6243 3810 6243 3846 6243 3846 6244 3810 6244 3809 6244 3846 6245 3809 6245 3845 6245 3845 6246 3809 6246 3799 6246 3845 6247 3799 6247 3788 6247 3814 6248 3812 6248 3840 6248 3840 6249 3812 6249 3846 6249 3840 6250 3846 6250 3841 6250 3841 6251 3846 6251 3843 6251 3308 6252 2854 6252 3843 6252 3843 6253 3846 6253 3308 6253 3308 6254 3846 6254 3845 6254 3308 6255 3845 6255 3309 6255 3309 6256 3845 6256 3787 6256 3309 6257 3787 6257 3790 6257 3847 6258 3848 6258 3849 6258 3850 6259 3849 6259 3851 6259 3852 6260 3853 6260 3854 6260 936 6261 3853 6261 934 6261 3853 6262 936 6262 3854 6262 3854 6263 936 6263 937 6263 3854 6264 937 6264 932 6264 3852 6265 934 6265 3853 6265 932 6266 3855 6266 3854 6266 3854 6267 3855 6267 3850 6267 3854 6268 3850 6268 3852 6268 3852 6269 3850 6269 3851 6269 3852 6270 3851 6270 934 6270 932 6271 931 6271 3855 6271 3855 6272 931 6272 929 6272 3855 6273 929 6273 928 6273 3856 6274 3857 6274 3847 6274 3849 6275 3850 6275 3847 6275 3847 6276 3850 6276 3855 6276 3847 6277 3855 6277 3856 6277 3856 6278 3855 6278 928 6278 3856 6279 928 6279 739 6279 739 6280 3858 6280 3856 6280 3856 6281 3858 6281 3859 6281 3856 6282 3859 6282 3857 6282 3857 6283 3859 6283 3860 6283 3857 6284 3860 6284 3861 6284 3848 6285 3847 6285 3862 6285 3862 6286 3847 6286 3857 6286 3862 6287 3857 6287 3863 6287 3863 6288 3857 6288 3861 6288 3863 6289 3861 6289 3864 6289 3865 6290 3866 6290 3864 6290 3864 6291 3861 6291 3865 6291 3865 6292 3861 6292 3860 6292 3865 6293 3860 6293 3867 6293 3860 6294 3859 6294 3867 6294 3867 6295 3859 6295 3858 6295 3867 6296 3858 6296 3868 6296 3868 6297 3858 6297 739 6297 3868 6298 739 6298 738 6298 3869 6299 3866 6299 3865 6299 3870 6300 3869 6300 3871 6300 3871 6301 3869 6301 3865 6301 3871 6302 3865 6302 3872 6302 3872 6303 3865 6303 3867 6303 3872 6304 3867 6304 3873 6304 3873 6305 3867 6305 3868 6305 3873 6306 3868 6306 1429 6306 1429 6307 3868 6307 738 6307 3874 6308 3870 6308 3875 6308 3875 6309 3870 6309 3871 6309 3875 6310 3871 6310 3876 6310 3876 6311 3871 6311 3872 6311 3876 6312 3872 6312 3877 6312 3877 6313 3872 6313 3873 6313 3877 6314 3873 6314 1431 6314 1431 6315 3873 6315 1429 6315 3878 6316 3874 6316 3879 6316 3879 6317 3874 6317 3875 6317 3879 6318 3875 6318 3880 6318 3880 6319 3875 6319 3876 6319 3880 6320 3876 6320 3881 6320 3881 6321 3876 6321 3877 6321 3881 6322 3877 6322 1399 6322 1399 6323 3877 6323 1431 6323 3882 6324 3883 6324 3884 6324 3883 6325 3878 6325 3884 6325 3884 6326 3878 6326 3879 6326 3884 6327 3879 6327 3885 6327 3885 6328 3879 6328 3880 6328 3885 6329 3880 6329 3886 6329 3886 6330 3880 6330 3881 6330 3886 6331 3881 6331 1404 6331 1404 6332 3881 6332 1399 6332 3887 6333 3882 6333 3888 6333 3888 6334 3882 6334 3884 6334 3888 6335 3884 6335 3889 6335 3889 6336 3884 6336 3885 6336 3889 6337 3885 6337 3890 6337 3890 6338 3885 6338 3886 6338 3890 6339 3886 6339 1423 6339 1423 6340 3886 6340 1404 6340 3891 6341 3892 6341 3893 6341 3894 6342 3895 6342 3896 6342 3897 6343 3898 6343 2838 6343 3897 6344 2838 6344 3899 6344 3900 6345 3899 6345 2838 6345 3901 6346 3900 6346 2838 6346 3895 6347 3898 6347 3896 6347 3896 6348 3898 6348 3897 6348 3896 6349 3897 6349 3902 6349 3902 6350 3897 6350 3899 6350 3902 6351 3899 6351 3903 6351 3903 6352 3899 6352 3900 6352 3903 6353 3900 6353 3904 6353 3904 6354 3900 6354 3901 6354 3892 6355 3894 6355 3893 6355 3893 6356 3894 6356 3896 6356 3893 6357 3896 6357 3905 6357 3905 6358 3896 6358 3902 6358 3905 6359 3902 6359 3906 6359 3906 6360 3902 6360 3903 6360 3906 6361 3903 6361 3907 6361 3907 6362 3903 6362 3904 6362 3908 6363 3891 6363 3909 6363 3909 6364 3891 6364 3893 6364 3909 6365 3893 6365 3910 6365 3910 6366 3893 6366 3905 6366 3910 6367 3905 6367 3911 6367 3911 6368 3905 6368 3906 6368 3911 6369 3906 6369 3912 6369 3912 6370 3906 6370 3907 6370 3913 6371 3908 6371 3914 6371 3914 6372 3908 6372 3909 6372 3914 6373 3909 6373 3915 6373 3915 6374 3909 6374 3910 6374 3915 6375 3910 6375 3916 6375 3916 6376 3910 6376 3911 6376 3916 6377 3911 6377 3917 6377 3917 6378 3911 6378 3912 6378 1423 6379 3913 6379 3890 6379 3890 6380 3913 6380 3914 6380 3890 6381 3914 6381 3889 6381 3889 6382 3914 6382 3915 6382 3889 6383 3915 6383 3888 6383 3888 6384 3915 6384 3916 6384 3888 6385 3916 6385 3887 6385 3887 6386 3916 6386 3917 6386 1409 6387 1407 6387 3918 6387 1423 6388 1422 6388 3919 6388 3920 6389 2824 6389 3921 6389 3921 6390 2824 6390 3239 6390 3921 6391 3239 6391 2834 6391 2834 6392 3239 6392 3235 6392 2834 6393 3235 6393 2832 6393 2820 6394 2821 6394 3918 6394 3918 6395 2821 6395 2822 6395 3918 6396 2822 6396 3920 6396 3920 6397 2822 6397 2823 6397 3920 6398 2823 6398 2824 6398 2820 6399 3918 6399 2819 6399 2819 6400 3918 6400 1407 6400 2819 6401 1407 6401 1406 6401 3922 6402 3908 6402 3919 6402 3919 6403 3908 6403 3913 6403 3919 6404 3913 6404 1423 6404 3923 6405 3892 6405 3922 6405 3922 6406 3892 6406 3891 6406 3922 6407 3891 6407 3908 6407 2840 6408 2838 6408 3923 6408 3923 6409 2838 6409 3898 6409 3898 6410 3895 6410 3923 6410 3923 6411 3895 6411 3894 6411 3923 6412 3894 6412 3892 6412 1426 6413 1409 6413 3924 6413 3924 6414 1409 6414 3918 6414 3924 6415 3918 6415 3925 6415 3925 6416 3918 6416 3920 6416 3925 6417 3920 6417 3926 6417 3926 6418 3920 6418 3921 6418 3926 6419 3921 6419 2836 6419 2836 6420 3921 6420 2834 6420 2836 6421 2840 6421 3926 6421 3926 6422 2840 6422 3923 6422 3926 6423 3923 6423 3925 6423 3925 6424 3923 6424 3922 6424 3925 6425 3922 6425 3924 6425 3924 6426 3922 6426 3919 6426 3924 6427 3919 6427 1426 6427 1426 6428 3919 6428 1422 6428 3863 6429 3864 6429 3817 6429 3817 6430 3864 6430 3866 6430 3817 6431 3866 6431 3816 6431 3817 6432 3818 6432 3863 6432 3863 6433 3818 6433 3831 6433 3863 6434 3831 6434 3862 6434 3862 6435 3831 6435 3830 6435 3862 6436 3830 6436 3848 6436 3848 6437 3830 6437 3828 6437 3824 6438 934 6438 3826 6438 3826 6439 934 6439 3851 6439 3826 6440 3851 6440 3828 6440 3828 6441 3851 6441 3849 6441 3828 6442 3849 6442 3848 6442 3824 6443 3822 6443 934 6443 934 6444 3822 6444 3820 6444 934 6445 3820 6445 1837 6445 3866 6446 3869 6446 3816 6446 3816 6447 3869 6447 3870 6447 3816 6448 3870 6448 3808 6448 2838 6449 2837 6449 3795 6449 3798 6450 3901 6450 3797 6450 3797 6451 3901 6451 2838 6451 3797 6452 2838 6452 3796 6452 3796 6453 2838 6453 3795 6453 3870 6454 3874 6454 3808 6454 3808 6455 3874 6455 3878 6455 3808 6456 3878 6456 3806 6456 3806 6457 3878 6457 3883 6457 3806 6458 3883 6458 3804 6458 3804 6459 3883 6459 3882 6459 3804 6460 3882 6460 3802 6460 3802 6461 3882 6461 3887 6461 3887 6462 3917 6462 3802 6462 3802 6463 3917 6463 3912 6463 3802 6464 3912 6464 3800 6464 3800 6465 3912 6465 3907 6465 3800 6466 3907 6466 3798 6466 3798 6467 3907 6467 3904 6467 3798 6468 3904 6468 3901 6468 1578 106 1577 106 713 106 713 6469 1577 6469 1595 6469 1595 6470 1593 6470 713 6470 713 6471 1593 6471 1591 6471 713 106 1591 106 716 106 716 106 1591 106 1588 106 716 6472 1588 6472 1525 6472 676 6473 674 6473 3927 6473 709 6474 676 6474 710 6474 710 6475 676 6475 3927 6475 710 6476 3927 6476 714 6476 714 6477 3927 6477 1578 6477 714 6478 1578 6478 713 6478 1578 6479 3927 6479 3928 6479 3927 6480 674 6480 672 6480 3927 6481 672 6481 3928 6481 3928 6482 672 6482 670 6482 3928 6483 670 6483 3929 6483 3929 6484 670 6484 669 6484 3929 6485 669 6485 3930 6485 3930 6486 669 6486 667 6486 3930 6487 667 6487 3931 6487 1578 6488 3928 6488 1579 6488 1579 6489 3928 6489 3929 6489 1579 6490 3929 6490 1581 6490 1581 6491 3929 6491 3930 6491 1581 6492 3930 6492 1583 6492 1583 6493 3930 6493 3931 6493 1583 6494 3931 6494 1585 6494 716 6495 1525 6495 717 6495 717 6496 1525 6496 715 6496 715 6497 1525 6497 711 6497 938 6498 678 6498 1502 6498 1502 6499 678 6499 682 6499 1502 6500 682 6500 1511 6500 1511 6501 682 6501 681 6501 1511 6502 681 6502 1516 6502 1516 6503 681 6503 683 6503 3572 6504 3932 6504 3571 6504 3577 6505 3087 6505 3933 6505 3095 6506 3934 6506 3094 6506 3581 6507 3935 6507 3603 6507 3663 6508 3664 6508 3935 6508 3696 6509 3699 6509 3936 6509 3937 6510 3706 6510 3707 6510 3425 6511 3423 6511 3938 6511 3381 6512 3383 6512 3419 6512 2648 6513 3248 6513 3939 6513 2519 6514 2348 6514 2350 6514 3034 6515 3032 6515 3940 6515 3032 6516 3030 6516 3940 6516 3940 6517 3030 6517 3028 6517 3940 6518 3028 6518 3026 6518 3026 6519 3024 6519 3940 6519 3940 6520 3024 6520 3022 6520 3940 6521 3022 6521 3020 6521 3020 6522 3012 6522 3940 6522 3940 6523 3012 6523 3011 6523 3940 6524 3011 6524 3002 6524 3941 6525 2433 6525 3942 6525 3942 6526 2433 6526 2434 6526 3943 6527 2427 6527 3944 6527 3944 6528 2427 6528 2428 6528 3944 6529 2428 6529 2429 6529 2391 6530 2393 6530 3943 6530 3943 6531 2393 6531 2426 6531 3943 6532 2426 6532 2427 6532 2382 6533 2383 6533 3945 6533 3945 6534 2383 6534 2384 6534 3945 6535 2384 6535 2386 6535 2380 6536 2381 6536 3946 6536 3947 6537 2330 6537 3948 6537 3948 6538 2330 6538 2329 6538 3948 6539 2329 6539 2379 6539 2365 6540 2363 6540 3947 6540 3947 6541 2363 6541 2362 6541 3947 6542 2362 6542 2330 6542 2519 6543 2350 6543 2517 6543 2350 6544 2365 6544 2517 6544 2517 6545 2365 6545 3947 6545 2517 6546 3947 6546 2515 6546 2515 6547 3947 6547 3248 6547 2648 6548 3939 6548 2685 6548 2684 6549 3949 6549 2683 6549 2683 6550 3949 6550 3950 6550 2683 6551 3950 6551 2682 6551 2682 6552 3950 6552 3951 6552 2682 6553 3951 6553 2672 6553 2672 6554 3951 6554 3952 6554 2672 6555 3952 6555 2602 6555 3953 6556 3711 6556 2613 6556 2613 6557 3711 6557 2614 6557 3954 6558 3387 6558 3389 6558 3389 6559 3391 6559 3954 6559 3954 6560 3391 6560 3392 6560 3954 6561 3392 6561 3393 6561 3419 6562 3383 6562 3421 6562 3416 6563 2863 6563 3379 6563 3381 6564 3419 6564 3379 6564 3379 6565 3419 6565 3417 6565 3379 6566 3417 6566 3416 6566 3431 6567 3429 6567 3938 6567 3938 6568 3429 6568 3427 6568 3938 6569 3427 6569 3425 6569 3707 6570 3433 6570 3955 6570 3664 6571 3665 6571 3935 6571 3935 6572 3665 6572 3666 6572 3935 6573 3666 6573 3667 6573 3668 6574 3316 6574 3687 6574 3668 6575 3687 6575 3667 6575 3667 6576 3687 6576 3935 6576 3935 6577 3687 6577 3688 6577 3935 6578 3688 6578 3689 6578 3689 6579 3690 6579 3935 6579 3935 6580 3690 6580 3691 6580 3935 6581 3691 6581 3692 6581 3692 6582 3693 6582 3935 6582 3935 6583 3693 6583 3694 6583 3935 6584 3694 6584 3695 6584 3580 6585 3634 6585 3581 6585 3581 6586 3634 6586 3633 6586 3581 6587 3633 6587 3631 6587 3631 6588 3638 6588 3581 6588 3581 6589 3638 6589 3637 6589 3581 6590 3637 6590 3642 6590 3642 6591 3640 6591 3581 6591 3581 6592 3640 6592 3639 6592 3581 6593 3639 6593 3935 6593 3935 6594 3639 6594 3662 6594 3935 6595 3662 6595 3663 6595 3141 6596 3140 6596 3956 6596 3141 6597 3956 6597 3147 6597 3695 6598 3696 6598 3935 6598 3935 6599 3696 6599 3936 6599 3935 6600 3936 6600 3603 6600 3603 6601 3936 6601 3956 6601 3603 6602 3956 6602 3604 6602 3604 6603 3956 6603 3140 6603 3604 6604 3140 6604 3139 6604 3957 6605 3153 6605 3958 6605 3958 6606 3153 6606 3151 6606 3958 6607 3151 6607 3149 6607 3095 6608 3165 6608 3959 6608 3959 6609 3165 6609 3163 6609 3959 6610 3163 6610 3161 6610 3161 6611 3159 6611 3960 6611 3960 6612 3159 6612 3157 6612 3960 6613 3157 6613 3957 6613 3957 6614 3157 6614 3155 6614 3957 6615 3155 6615 3153 6615 3094 6616 3934 6616 3083 6616 3083 6617 3934 6617 3961 6617 3083 6618 3961 6618 3082 6618 3577 6619 3933 6619 3576 6619 3962 6620 3963 6620 3574 6620 3932 6621 3572 6621 3963 6621 3963 6622 3572 6622 3573 6622 3963 6623 3573 6623 3574 6623 3940 6624 3568 6624 3964 6624 3002 6625 3001 6625 3940 6625 3940 6626 3001 6626 3567 6626 3940 6627 3567 6627 3568 6627 3965 6628 3955 6628 3938 6628 3938 6629 3955 6629 3433 6629 3938 6630 3433 6630 3431 6630 3966 6631 3965 6631 3967 6631 3967 6632 3965 6632 3938 6632 3967 6633 3938 6633 3954 6633 3954 6634 3938 6634 3423 6634 3954 6635 3423 6635 3387 6635 3387 6636 3423 6636 3421 6636 3387 6637 3421 6637 3385 6637 3385 6638 3421 6638 3383 6638 3966 6639 3967 6639 3968 6639 3968 6640 3967 6640 3954 6640 3968 6641 3954 6641 3953 6641 3953 6642 3954 6642 3393 6642 3953 6643 3393 6643 3711 6643 3950 6644 3969 6644 3951 6644 3951 6645 3969 6645 3966 6645 3951 6646 3966 6646 3952 6646 3952 6647 3966 6647 3968 6647 3952 6648 3968 6648 2602 6648 2602 6649 3968 6649 3953 6649 2602 6650 3953 6650 2599 6650 2599 6651 3953 6651 2613 6651 2381 6652 2382 6652 3946 6652 3946 6653 2382 6653 3945 6653 3946 6654 3945 6654 3970 6654 3937 6655 3707 6655 3971 6655 3971 6656 3707 6656 3955 6656 3971 6657 3955 6657 3972 6657 3972 6658 3955 6658 3965 6658 3972 6659 3965 6659 3973 6659 3973 6660 3965 6660 3966 6660 3973 6661 3966 6661 3974 6661 3974 6662 3966 6662 3969 6662 3974 6663 3969 6663 3975 6663 3975 6664 3969 6664 3950 6664 3975 6665 3950 6665 3976 6665 3976 6666 3950 6666 3949 6666 3976 6667 3949 6667 3977 6667 3977 6668 3949 6668 2684 6668 3977 6669 2684 6669 2685 6669 3248 6670 3947 6670 3939 6670 3939 6671 3947 6671 3948 6671 3939 6672 3948 6672 3978 6672 3978 6673 3948 6673 3979 6673 3978 6674 3979 6674 3980 6674 3980 6675 3979 6675 3981 6675 3980 6676 3981 6676 3982 6676 3982 6677 3981 6677 3983 6677 3982 6678 3983 6678 3984 6678 3984 6679 3983 6679 3985 6679 3984 6680 3985 6680 3986 6680 2685 6681 3939 6681 3977 6681 3977 6682 3939 6682 3978 6682 3977 6683 3978 6683 3976 6683 3976 6684 3978 6684 3980 6684 3976 6685 3980 6685 3975 6685 3975 6686 3980 6686 3982 6686 3975 6687 3982 6687 3974 6687 3974 6688 3982 6688 3984 6688 3974 6689 3984 6689 3973 6689 3973 6690 3984 6690 3986 6690 3973 6691 3986 6691 3972 6691 3987 6692 3988 6692 3989 6692 3990 6693 3943 6693 3991 6693 3991 6694 3943 6694 3944 6694 3991 6695 3944 6695 3992 6695 3992 6696 3944 6696 2429 6696 3992 6697 2429 6697 3993 6697 3993 6698 2429 6698 2430 6698 3993 6699 2430 6699 3994 6699 3994 6700 2430 6700 2431 6700 3994 6701 2431 6701 3941 6701 3941 6702 2431 6702 2432 6702 3941 6703 2432 6703 2433 6703 3995 6704 3996 6704 3989 6704 3989 6705 3996 6705 3962 6705 3989 6706 3962 6706 3987 6706 3987 6707 3962 6707 3574 6707 3568 6708 3569 6708 3964 6708 3964 6709 3569 6709 3570 6709 3964 6710 3570 6710 3997 6710 3997 6711 3570 6711 3571 6711 3997 6712 3571 6712 3998 6712 3998 6713 3571 6713 3932 6713 3998 6714 3932 6714 3999 6714 3999 6715 3932 6715 3963 6715 3999 6716 3963 6716 4000 6716 4000 6717 3963 6717 3962 6717 4000 6718 3962 6718 4001 6718 4001 6719 3962 6719 3996 6719 4002 6720 3933 6720 3961 6720 3961 6721 3933 6721 3087 6721 3961 6722 3087 6722 3082 6722 3574 6723 3575 6723 3987 6723 3987 6724 3575 6724 3576 6724 3987 6725 3576 6725 3988 6725 3988 6726 3576 6726 3933 6726 3988 6727 3933 6727 3989 6727 3989 6728 3933 6728 4002 6728 3989 6729 4002 6729 3995 6729 3095 6730 3959 6730 3934 6730 3934 6731 3959 6731 4003 6731 3934 6732 4003 6732 3961 6732 3961 6733 4003 6733 4004 6733 3961 6734 4004 6734 4002 6734 4002 6735 4004 6735 4005 6735 4002 6736 4005 6736 3995 6736 3990 6737 4006 6737 3943 6737 3943 6738 4006 6738 4007 6738 3943 6739 4007 6739 2391 6739 2391 6740 4007 6740 2389 6740 4005 6741 4008 6741 3995 6741 3995 6742 4008 6742 4006 6742 3995 6743 4006 6743 3996 6743 3996 6744 4006 6744 3990 6744 3996 6745 3990 6745 4001 6745 4001 6746 3990 6746 3991 6746 4001 6747 3991 6747 4000 6747 4000 6748 3991 6748 3992 6748 4000 6749 3992 6749 3999 6749 3999 6750 3992 6750 3993 6750 3999 6751 3993 6751 3998 6751 3998 6752 3993 6752 3994 6752 3998 6753 3994 6753 3997 6753 3997 6754 3994 6754 3941 6754 3997 6755 3941 6755 3964 6755 3964 6756 3941 6756 3942 6756 3964 6757 3942 6757 3940 6757 3940 6758 3942 6758 2434 6758 3940 6759 2434 6759 3034 6759 3161 6760 3960 6760 3959 6760 3959 6761 3960 6761 4009 6761 3959 6762 4009 6762 4003 6762 4003 6763 4009 6763 4010 6763 4003 6764 4010 6764 4004 6764 4004 6765 4010 6765 4011 6765 4004 6766 4011 6766 4005 6766 4005 6767 4011 6767 4012 6767 4005 6768 4012 6768 4008 6768 2389 6769 4007 6769 2388 6769 2388 6770 4007 6770 4006 6770 2388 6771 4006 6771 2386 6771 2386 6772 4006 6772 4008 6772 2386 6773 4008 6773 3945 6773 3945 6774 4008 6774 4012 6774 3945 6775 4012 6775 3970 6775 3970 6776 4012 6776 4011 6776 3970 6777 4011 6777 4013 6777 4013 6778 4011 6778 4010 6778 4013 6779 4010 6779 4014 6779 4014 6780 4010 6780 4009 6780 4014 6781 4009 6781 4015 6781 4015 6782 4009 6782 3960 6782 4015 6783 3960 6783 4016 6783 4016 6784 3960 6784 3957 6784 4016 6785 3957 6785 4017 6785 4017 6786 3957 6786 3958 6786 4017 6787 3958 6787 3956 6787 3956 6788 3958 6788 3149 6788 3956 6789 3149 6789 3147 6789 2379 6790 2380 6790 3948 6790 3948 6791 2380 6791 3946 6791 3948 6792 3946 6792 3979 6792 3979 6793 3946 6793 3970 6793 3979 6794 3970 6794 3981 6794 3981 6795 3970 6795 4013 6795 3981 6796 4013 6796 3983 6796 3983 6797 4013 6797 4014 6797 3983 6798 4014 6798 3985 6798 3985 6799 4014 6799 4015 6799 3985 6800 4015 6800 3986 6800 3986 6801 4015 6801 4016 6801 3986 6802 4016 6802 3972 6802 3972 6803 4016 6803 4017 6803 3972 6804 4017 6804 3971 6804 3971 6805 4017 6805 3956 6805 3971 6806 3956 6806 3937 6806 3937 6807 3956 6807 3936 6807 3937 6808 3936 6808 3706 6808 3706 6809 3936 6809 3699 6809 1658 6810 1662 6810 4018 6810 1659 6811 1625 6811 4019 6811 1660 6812 4020 6812 1661 6812 1661 6813 4020 6813 4021 6813 1661 6814 4021 6814 1662 6814 1659 6815 4019 6815 1660 6815 1660 6816 4019 6816 4022 6816 1660 6817 4022 6817 4020 6817 4020 6818 4022 6818 4023 6818 4020 6819 4023 6819 4021 6819 4021 6820 4023 6820 4024 6820 4021 6821 4024 6821 4025 6821 4025 6822 4024 6822 4026 6822 4025 6823 4026 6823 4027 6823 4027 6824 4026 6824 4028 6824 4027 6825 4028 6825 4029 6825 4029 6826 4028 6826 4030 6826 4029 6827 4030 6827 4031 6827 4031 6828 4030 6828 4032 6828 4031 6829 4032 6829 4033 6829 4033 6830 4032 6830 3075 6830 4033 6831 3075 6831 4034 6831 1662 6832 4021 6832 4018 6832 4018 6833 4021 6833 4025 6833 4018 6834 4025 6834 4035 6834 4035 6835 4025 6835 4027 6835 4035 6836 4027 6836 4036 6836 4036 6837 4027 6837 4029 6837 4036 6838 4029 6838 4037 6838 4037 6839 4029 6839 4031 6839 4037 6840 4031 6840 4038 6840 4038 6841 4031 6841 4033 6841 4038 6842 4033 6842 4039 6842 4039 6843 4033 6843 4034 6843 4039 6844 4034 6844 4040 6844 1658 6845 4018 6845 1653 6845 1653 6846 4018 6846 4035 6846 1653 6847 4035 6847 1931 6847 1931 6848 4035 6848 4036 6848 1931 6849 4036 6849 1932 6849 1932 6850 4036 6850 4037 6850 1932 6851 4037 6851 1925 6851 1925 6852 4037 6852 4038 6852 1925 6853 4038 6853 1926 6853 1926 6854 4038 6854 4039 6854 1926 6855 4039 6855 1933 6855 1933 6856 4039 6856 4040 6856 1933 6857 4040 6857 1934 6857 1937 6858 1934 6858 4041 6858 4041 6859 1934 6859 4040 6859 4041 6860 4040 6860 4042 6860 4042 6861 4040 6861 4034 6861 4042 6862 4034 6862 3074 6862 3074 6863 4034 6863 3075 6863 1929 6864 1937 6864 4043 6864 4043 6865 1937 6865 4041 6865 4043 6866 4041 6866 4044 6866 4044 6867 4041 6867 4042 6867 4044 6868 4042 6868 3073 6868 3073 6869 4042 6869 3074 6869 1927 6870 1929 6870 3529 6870 3529 6871 1929 6871 4043 6871 3529 6872 4043 6872 3533 6872 3533 6873 4043 6873 4044 6873 3533 6874 4044 6874 3050 6874 3050 6875 4044 6875 3073 6875 1280 6876 4045 6876 1275 6876 1275 6877 4045 6877 4046 6877 1275 6878 4046 6878 1276 6878 1280 6879 1281 6879 4045 6879 4045 6880 1281 6880 4047 6880 4045 6881 4047 6881 4046 6881 4046 6882 4047 6882 2130 6882 4048 6883 4049 6883 4050 6883 4051 6884 4052 6884 655 6884 655 6885 4052 6885 656 6885 656 6886 4052 6886 658 6886 658 6887 4052 6887 4053 6887 658 6888 4053 6888 659 6888 659 6889 4053 6889 4054 6889 659 6890 4054 6890 660 6890 660 6891 4054 6891 4055 6891 660 6892 4055 6892 662 6892 662 6893 4055 6893 4056 6893 662 6894 4056 6894 663 6894 663 6895 4056 6895 4057 6895 663 6896 4057 6896 661 6896 661 6897 4057 6897 4058 6897 661 6898 4058 6898 657 6898 4049 6899 2118 6899 2102 6899 4048 6900 4050 6900 4051 6900 4049 6901 2102 6901 4050 6901 4050 6902 2102 6902 2080 6902 4050 6903 2080 6903 4059 6903 4059 6904 2080 6904 2079 6904 4059 6905 2079 6905 4060 6905 4060 6906 2079 6906 2084 6906 4060 6907 2084 6907 4061 6907 4061 6908 2084 6908 2083 6908 4061 6909 2083 6909 4062 6909 4062 6910 2083 6910 2082 6910 4062 6911 2082 6911 4063 6911 4063 6912 2082 6912 2068 6912 4063 6913 2068 6913 4064 6913 4051 6914 4050 6914 4052 6914 4052 6915 4050 6915 4059 6915 4052 6916 4059 6916 4053 6916 4053 6917 4059 6917 4060 6917 4053 6918 4060 6918 4054 6918 4054 6919 4060 6919 4061 6919 4054 6920 4061 6920 4055 6920 4055 6921 4061 6921 4062 6921 4055 6922 4062 6922 4056 6922 4056 6923 4062 6923 4063 6923 4056 6924 4063 6924 4057 6924 4057 6925 4063 6925 4064 6925 4057 6926 4064 6926 4058 6926 1282 6927 1271 6927 4065 6927 1282 6928 4065 6928 4066 6928 4066 6929 4065 6929 1939 6929 4066 6930 1939 6930 2128 6930 2128 6931 2130 6931 4047 6931 2128 6932 4047 6932 4066 6932 4066 6933 4047 6933 1281 6933 4066 6934 1281 6934 1282 6934 667 6935 1276 6935 4046 6935 667 6936 4046 6936 3931 6936 3931 6937 4046 6937 2130 6937 3931 6938 2130 6938 1585 6938 4067 6939 1947 6939 1945 6939 1241 6940 4067 6940 4068 6940 4067 6941 1945 6941 4068 6941 4068 6942 1945 6942 1943 6942 4068 6943 1943 6943 4069 6943 4069 6944 1943 6944 1941 6944 4069 6945 1941 6945 4070 6945 4070 6946 1941 6946 1939 6946 4070 6947 1939 6947 4065 6947 1241 6948 4068 6948 1268 6948 1268 6949 4068 6949 4069 6949 1268 6950 4069 6950 1266 6950 1266 6951 4069 6951 4070 6951 1266 6952 4070 6952 1264 6952 1264 6953 4070 6953 4065 6953 1264 6954 4065 6954 1271 6954 2639 6955 2638 6955 4049 6955 4051 6956 655 6956 654 6956 4049 6957 2638 6957 2118 6957 2118 6958 2638 6958 2636 6958 2118 6959 2636 6959 2637 6959 654 6960 653 6960 4051 6960 4051 6961 653 6961 634 6961 4051 6962 634 6962 4048 6962 4048 6963 634 6963 2640 6963 4048 6964 2640 6964 4049 6964 4049 6965 2640 6965 2639 6965 1251 6966 1252 6966 4071 6966 4071 6967 1252 6967 4072 6967 4071 6968 4072 6968 1936 6968 1936 6969 4072 6969 1935 6969 1256 6970 1251 6970 4073 6970 4073 6971 1251 6971 4071 6971 4073 6972 4071 6972 1930 6972 1930 6973 4071 6973 1936 6973 1256 6974 4073 6974 4074 6974 1256 6975 4074 6975 1255 6975 1255 6976 4074 6976 4075 6976 1255 6977 4075 6977 1253 6977 1253 6978 4075 6978 4076 6978 1253 6979 4076 6979 1254 6979 1254 6980 4076 6980 4077 6980 1254 6981 4077 6981 1249 6981 4073 6982 1930 6982 1963 6982 4073 6983 1963 6983 4074 6983 4074 6984 1963 6984 1962 6984 4074 6985 1962 6985 4075 6985 4075 6986 1962 6986 1948 6986 4075 6987 1948 6987 4076 6987 4076 6988 1948 6988 1949 6988 4076 6989 1949 6989 4077 6989 2018 6990 2020 6990 2034 6990 639 6991 4078 6991 4079 6991 639 6992 4079 6992 640 6992 640 6993 4079 6993 4080 6993 640 6994 4080 6994 646 6994 646 6995 4080 6995 4081 6995 646 6996 4081 6996 647 6996 647 6997 4081 6997 4082 6997 647 6998 4082 6998 648 6998 648 6999 4082 6999 4083 6999 648 7000 4083 7000 652 7000 652 7001 4083 7001 4084 7001 652 7002 4084 7002 629 7002 629 7003 4084 7003 4085 7003 629 7004 4085 7004 644 7004 644 7005 4085 7005 4086 7005 644 7006 4086 7006 635 7006 635 7007 4086 7007 4087 7007 635 7008 4087 7008 636 7008 636 7009 4087 7009 4088 7009 636 7010 4088 7010 637 7010 637 7011 4088 7011 2036 7011 637 7012 2036 7012 631 7012 4089 7013 1967 7013 1970 7013 4078 7014 4089 7014 4090 7014 1978 7015 4091 7015 1976 7015 1976 7016 4091 7016 4092 7016 4089 7017 1970 7017 4090 7017 4090 7018 1970 7018 1972 7018 4090 7019 1972 7019 4092 7019 4092 7020 1972 7020 1974 7020 4092 7021 1974 7021 1976 7021 1988 7022 4093 7022 1986 7022 1986 7023 4093 7023 4094 7023 1978 7024 1980 7024 4091 7024 4091 7025 1980 7025 1982 7025 4091 7026 1982 7026 4094 7026 4094 7027 1982 7027 1984 7027 4094 7028 1984 7028 1986 7028 1998 7029 4095 7029 1996 7029 1996 7030 4095 7030 4096 7030 1988 7031 1990 7031 4093 7031 4093 7032 1990 7032 1992 7032 4093 7033 1992 7033 4096 7033 4096 7034 1992 7034 1994 7034 4096 7035 1994 7035 1996 7035 2008 7036 4097 7036 2006 7036 2006 7037 4097 7037 4098 7037 1998 7038 2000 7038 4095 7038 4095 7039 2000 7039 2002 7039 4095 7040 2002 7040 4098 7040 4098 7041 2002 7041 2004 7041 4098 7042 2004 7042 2006 7042 2008 7043 2010 7043 4097 7043 4097 7044 2010 7044 2012 7044 4097 7045 2012 7045 4099 7045 4099 7046 2012 7046 2014 7046 4099 7047 2014 7047 2016 7047 2035 7048 4099 7048 2034 7048 2034 7049 4099 7049 2016 7049 2034 7050 2016 7050 2018 7050 4078 7051 4090 7051 4079 7051 4079 7052 4090 7052 4092 7052 4079 7053 4092 7053 4080 7053 4080 7054 4092 7054 4091 7054 4080 7055 4091 7055 4081 7055 4081 7056 4091 7056 4094 7056 4081 7057 4094 7057 4082 7057 4082 7058 4094 7058 4093 7058 4082 7059 4093 7059 4083 7059 4083 7060 4093 7060 4096 7060 4083 7061 4096 7061 4084 7061 4084 7062 4096 7062 4095 7062 4084 7063 4095 7063 4085 7063 4085 7064 4095 7064 4098 7064 4085 7065 4098 7065 4086 7065 4086 7066 4098 7066 4097 7066 4086 7067 4097 7067 4087 7067 4087 7068 4097 7068 4099 7068 4087 7069 4099 7069 4088 7069 4088 7070 4099 7070 2035 7070 4088 7071 2035 7071 2036 7071 643 7072 642 7072 4100 7072 4100 7073 642 7073 4101 7073 4100 7074 4101 7074 4102 7074 4102 7075 4101 7075 4103 7075 4102 7076 4103 7076 2044 7076 2044 7077 4103 7077 2045 7077 639 7078 643 7078 4078 7078 4078 7079 643 7079 4100 7079 4078 7080 4100 7080 4089 7080 4089 7081 4100 7081 4102 7081 4089 7082 4102 7082 1967 7082 1967 7083 4102 7083 2044 7083 641 7084 645 7084 4104 7084 4104 7085 645 7085 4105 7085 4104 7086 4105 7086 4106 7086 4106 7087 4105 7087 4107 7087 4106 7088 4107 7088 2060 7088 2060 7089 4107 7089 2064 7089 642 7090 641 7090 4101 7090 4101 7091 641 7091 4104 7091 4101 7092 4104 7092 4103 7092 4103 7093 4104 7093 4106 7093 4103 7094 4106 7094 2045 7094 2045 7095 4106 7095 2060 7095 2066 7096 2064 7096 4108 7096 4108 7097 2064 7097 4107 7097 4108 7098 4107 7098 4109 7098 4109 7099 4107 7099 4105 7099 4109 7100 4105 7100 633 7100 633 7101 4105 7101 645 7101 632 7102 657 7102 4110 7102 4110 7103 657 7103 4058 7103 4110 7104 4058 7104 4111 7104 4111 7105 4058 7105 4064 7105 4111 7106 4064 7106 2067 7106 2067 7107 4064 7107 2068 7107 633 7108 632 7108 4109 7108 4109 7109 632 7109 4110 7109 4109 7110 4110 7110 4108 7110 4108 7111 4110 7111 4111 7111 4108 7112 4111 7112 2066 7112 2066 7113 4111 7113 2067 7113 1249 7114 4077 7114 4112 7114 1249 7115 4112 7115 1250 7115 1250 7116 4112 7116 4113 7116 1250 7117 4113 7117 1259 7117 1259 7118 4113 7118 1247 7118 1247 7119 4113 7119 4114 7119 1247 7120 4114 7120 1245 7120 1245 7121 4114 7121 4115 7121 1245 7122 4115 7122 1243 7122 1243 7123 4115 7123 4067 7123 1243 7124 4067 7124 1241 7124 4077 7125 1949 7125 1951 7125 4077 7126 1951 7126 4112 7126 4112 7127 1951 7127 1953 7127 4112 7128 1953 7128 4113 7128 4113 7129 1953 7129 1955 7129 4113 7130 1955 7130 4114 7130 1955 7131 1957 7131 4114 7131 4114 7132 1957 7132 1959 7132 4114 7133 1959 7133 4115 7133 4115 7134 1959 7134 1947 7134 4115 7135 1947 7135 4067 7135 4022 7136 4116 7136 4023 7136 4117 7137 2019 7137 3072 7137 4118 7138 4119 7138 4120 7138 4120 7139 4119 7139 4121 7139 4120 7140 4121 7140 4117 7140 4122 7141 4123 7141 4124 7141 4124 7142 4123 7142 4125 7142 4124 7143 4125 7143 4120 7143 4120 7144 4125 7144 4126 7144 4120 7145 4126 7145 4118 7145 4127 7146 4128 7146 4116 7146 4116 7147 4128 7147 4122 7147 1623 7148 2537 7148 1624 7148 1624 7149 2537 7149 4129 7149 1624 7150 4129 7150 1625 7150 4127 7151 4116 7151 4130 7151 4130 7152 4116 7152 4022 7152 4130 7153 4022 7153 4129 7153 4129 7154 4022 7154 4019 7154 4129 7155 4019 7155 1625 7155 4122 7156 4124 7156 4116 7156 4116 7157 4124 7157 4024 7157 4116 7158 4024 7158 4023 7158 4032 7159 4030 7159 4120 7159 4120 7160 4030 7160 4028 7160 4120 7161 4028 7161 4124 7161 4124 7162 4028 7162 4026 7162 4124 7163 4026 7163 4024 7163 4117 7164 3072 7164 4120 7164 4120 7165 3072 7165 3075 7165 4120 7166 3075 7166 4032 7166 2020 7167 2019 7167 4117 7167 2020 7168 4117 7168 2032 7168 2032 7169 4117 7169 4121 7169 2032 7170 4121 7170 2033 7170 2537 7171 2536 7171 4129 7171 4129 7172 2536 7172 2540 7172 4129 7173 2540 7173 4130 7173 4130 7174 2540 7174 2539 7174 4130 7175 2539 7175 4127 7175 4127 7176 2539 7176 2545 7176 4127 7177 2545 7177 4128 7177 4128 7178 2545 7178 2546 7178 4128 7179 2546 7179 4122 7179 4122 7180 2546 7180 2548 7180 4122 7181 2548 7181 4123 7181 4123 7182 2548 7182 2549 7182 4123 7183 2549 7183 4125 7183 4125 7184 2549 7184 2026 7184 4125 7185 2026 7185 4126 7185 4126 7186 2026 7186 2025 7186 4126 7187 2025 7187 4118 7187 4118 7188 2025 7188 2033 7188 4118 7189 2033 7189 4119 7189 4119 7190 2033 7190 4121 7190 664 7191 4131 7191 665 7191 665 632 4131 632 1273 632 3 7192 1725 7192 1738 7192 1672 7193 1673 7193 1697 7193 4132 7194 4133 7194 4134 7194 4134 7195 4133 7195 4135 7195 4134 7196 4135 7196 4136 7196 4136 7197 4135 7197 3 7197 1 7198 8 7198 1679 7198 1738 7199 1745 7199 3 7199 3 7200 1745 7200 1750 7200 3 7201 1750 7201 1755 7201 1697 7202 1703 7202 1672 7202 1672 7203 1703 7203 1708 7203 1672 7204 1708 7204 1671 7204 1671 7205 1708 7205 1714 7205 1671 7206 1714 7206 1679 7206 1679 7207 1714 7207 1715 7207 1679 7208 1715 7208 1718 7208 1755 7209 4137 7209 3 7209 3 7210 4137 7210 4138 7210 3 7211 4138 7211 4136 7211 3 7212 1 7212 1725 7212 1725 7213 1 7213 1679 7213 1725 7214 1679 7214 1726 7214 1726 7215 1679 7215 1718 7215 9 7216 1689 7216 7 7216 7 7217 1689 7217 1684 7217 7 7218 1684 7218 1683 7218 1682 7219 6 7219 1683 7219 1683 7220 6 7220 5 7220 1683 7221 5 7221 7 7221 1679 7222 8 7222 1680 7222 1680 7223 8 7223 6 7223 1680 7224 6 7224 1681 7224 1681 7225 6 7225 1682 7225 2710 7226 10 7226 2709 7226 2709 7227 10 7227 11 7227 11 7228 13 7228 2709 7228 2709 7229 13 7229 14 7229 2709 7230 14 7230 2708 7230 12 7231 0 7231 353 7231 353 7232 2699 7232 12 7232 12 7233 2699 7233 2698 7233 12 7234 2698 7234 14 7234 14 7235 2698 7235 2697 7235 14 7236 2697 7236 2708 7236 2581 7237 9 7237 2580 7237 2580 7238 9 7238 10 7238 2580 7239 10 7239 2712 7239 2712 7240 10 7240 2710 7240 2581 7241 2567 7241 9 7241 9 7242 2567 7242 2559 7242 9 7243 2559 7243 1689 7243 2209 7244 2210 7244 4139 7244 1378 7245 1380 7245 2242 7245 2242 7246 1380 7246 4140 7246 2242 7247 4140 7247 2215 7247 2215 7248 4140 7248 4141 7248 4142 7249 4143 7249 4144 7249 4145 7250 4142 7250 4146 7250 4146 7251 4142 7251 4147 7251 4145 7252 4148 7252 4142 7252 4142 7253 4148 7253 4149 7253 4142 7254 4149 7254 4143 7254 4150 7255 4147 7255 4151 7255 4151 7256 4147 7256 4142 7256 4151 7257 4142 7257 4152 7257 4152 7258 4142 7258 4144 7258 4141 7259 4150 7259 2215 7259 2215 7260 4150 7260 4151 7260 2215 7261 4151 7261 2216 7261 2216 7262 4151 7262 4153 7262 2216 7263 4153 7263 2218 7263 2218 7264 4153 7264 4154 7264 2218 7265 4154 7265 2220 7265 2220 7266 4154 7266 2222 7266 4154 7267 4155 7267 2222 7267 2222 7268 4155 7268 4156 7268 2222 7269 4156 7269 2224 7269 2224 7270 4156 7270 4157 7270 2224 7271 4157 7271 2213 7271 2213 7272 4157 7272 2211 7272 2211 7273 4157 7273 4158 7273 2211 7274 4158 7274 2210 7274 2210 7275 4158 7275 4159 7275 2210 7276 4159 7276 4160 7276 4160 7277 4161 7277 2210 7277 2210 7278 4161 7278 4162 7278 2210 7279 4162 7279 4139 7279 4139 7280 4162 7280 4163 7280 4139 7281 4163 7281 4164 7281 4165 7282 1917 7282 4166 7282 4166 7283 1917 7283 2207 7283 4166 7284 2207 7284 4167 7284 4167 7285 2207 7285 4139 7285 4139 7286 2207 7286 2208 7286 4139 7287 2208 7287 2209 7287 1917 106 4165 106 4168 106 4169 106 1786 106 4168 106 4168 7288 1786 7288 1785 7288 1785 7289 1784 7289 4168 7289 4168 7290 1784 7290 1783 7290 4168 106 1783 106 1917 106 4170 7291 4171 7291 1935 7291 372 7292 370 7292 4171 7292 4171 7293 370 7293 1663 7293 4171 7294 1663 7294 1935 7294 1935 7295 4072 7295 4170 7295 4170 7296 4072 7296 1252 7296 4170 7297 1252 7297 1263 7297 4172 7298 4173 7298 4174 7298 1269 7299 4175 7299 1270 7299 1270 7300 4175 7300 4176 7300 1270 7301 4176 7301 1242 7301 4177 7302 1248 7302 1246 7302 1260 7303 1258 7303 4177 7303 4177 7304 1258 7304 1257 7304 4177 7305 1257 7305 1248 7305 4171 7306 4170 7306 4178 7306 4178 7307 4170 7307 1263 7307 4178 7308 1263 7308 4179 7308 4179 7309 1263 7309 1262 7309 4179 7310 1262 7310 4180 7310 1262 7311 1261 7311 4180 7311 4180 7312 1261 7312 1260 7312 4180 7313 1260 7313 4174 7313 4174 7314 1260 7314 4177 7314 4174 7315 4177 7315 4172 7315 4172 7316 4177 7316 1246 7316 4172 7317 1246 7317 4176 7317 4176 7318 1246 7318 1244 7318 4176 7319 1244 7319 1242 7319 4181 7320 4182 7320 4183 7320 4184 7321 4185 7321 4186 7321 4187 7322 4188 7322 4189 7322 4176 7323 4175 7323 4190 7323 4172 7324 4176 7324 4191 7324 4173 7325 4172 7325 4192 7325 4193 7326 4194 7326 4192 7326 4192 7327 4194 7327 4195 7327 4192 7328 4195 7328 4173 7328 4176 7329 4190 7329 4191 7329 4191 7330 4190 7330 4196 7330 4191 7331 4196 7331 4197 7331 4197 7332 4196 7332 4198 7332 4197 7333 4198 7333 4199 7333 4198 7334 4200 7334 4199 7334 4199 7335 4200 7335 4201 7335 4199 7336 4201 7336 4202 7336 4202 7337 4201 7337 4203 7337 4202 7338 4203 7338 4204 7338 4203 7339 4205 7339 4204 7339 4204 7340 4205 7340 4206 7340 4204 7341 4206 7341 4207 7341 4207 7342 4206 7342 4208 7342 4207 7343 4208 7343 4209 7343 4192 7344 4210 7344 4193 7344 4193 7345 4210 7345 4211 7345 4193 7346 4211 7346 4212 7346 4212 7347 4211 7347 4213 7347 4212 7348 4213 7348 4214 7348 4214 7349 4213 7349 4215 7349 4214 7350 4215 7350 4216 7350 4216 7351 4215 7351 4217 7351 4216 7352 4217 7352 4218 7352 4218 7353 4217 7353 4219 7353 4218 7354 4219 7354 4220 7354 4220 7355 4219 7355 4221 7355 4220 7356 4221 7356 4222 7356 4222 7357 4221 7357 4223 7357 4222 7358 4223 7358 4224 7358 4224 7359 4223 7359 4181 7359 4224 7360 4181 7360 4225 7360 4225 7361 4181 7361 4183 7361 4208 7362 4226 7362 4209 7362 4209 7363 4226 7363 4227 7363 4209 7364 4227 7364 4228 7364 4228 7365 4227 7365 4229 7365 4228 7366 4229 7366 4230 7366 4230 7367 4229 7367 4187 7367 4230 7368 4187 7368 4184 7368 4184 7369 4187 7369 4189 7369 4184 7370 4189 7370 4185 7370 4172 7371 4191 7371 4192 7371 4192 7372 4191 7372 4197 7372 4192 7373 4197 7373 4210 7373 4210 7374 4197 7374 4199 7374 4210 7375 4199 7375 4211 7375 4211 7376 4199 7376 4202 7376 4211 7377 4202 7377 4213 7377 4213 7378 4202 7378 4204 7378 4213 7379 4204 7379 4215 7379 4215 7380 4204 7380 4207 7380 4215 7381 4207 7381 4217 7381 4217 7382 4207 7382 4209 7382 4217 7383 4209 7383 4219 7383 4219 7384 4209 7384 4228 7384 4219 7385 4228 7385 4221 7385 4221 7386 4228 7386 4230 7386 4221 7387 4230 7387 4223 7387 4223 7388 4230 7388 4184 7388 4223 7389 4184 7389 4181 7389 4181 7390 4184 7390 4186 7390 4181 7391 4186 7391 4182 7391 375 7392 374 7392 4231 7392 4232 7393 4233 7393 4234 7393 4234 7394 4233 7394 4231 7394 375 7395 4231 7395 371 7395 371 7396 4231 7396 4233 7396 371 7397 4233 7397 368 7397 4171 7398 4178 7398 372 7398 372 7399 4178 7399 4179 7399 372 7400 4179 7400 373 7400 374 7401 373 7401 4231 7401 4231 7402 373 7402 4179 7402 4231 7403 4179 7403 4235 7403 4179 7404 4180 7404 4235 7404 4235 7405 4180 7405 4174 7405 4235 7406 4174 7406 4236 7406 4236 7406 4174 7406 4173 7406 4236 7407 4173 7407 4237 7407 4237 7408 4173 7408 4195 7408 4237 7409 4195 7409 4238 7409 4238 7410 4195 7410 4194 7410 4238 7411 4194 7411 4239 7411 4224 7412 4225 7412 4240 7412 4218 7413 4220 7413 4240 7413 4240 7414 4220 7414 4222 7414 4240 7415 4222 7415 4224 7415 4240 7416 4193 7416 4212 7416 4212 7417 4214 7417 4240 7417 4240 7418 4214 7418 4216 7418 4240 7419 4216 7419 4218 7419 4225 7420 4241 7420 4240 7420 4240 7421 4241 7421 4194 7421 4240 7422 4194 7422 4193 7422 4241 7423 4242 7423 4194 7423 4194 7424 4242 7424 4243 7424 4194 7425 4243 7425 4244 7425 4244 7426 4245 7426 4194 7426 4194 7427 4245 7427 4246 7427 4194 7428 4246 7428 4247 7428 4247 7429 4248 7429 4194 7429 4194 7430 4248 7430 4249 7430 4194 7431 4249 7431 4239 7431 1265 95 4250 95 1267 95 1267 95 4250 95 4175 95 1267 95 4175 95 1269 95 4229 7432 4227 7432 4251 7432 4252 7433 4198 7433 4196 7433 4252 7434 4196 7434 4250 7434 4250 7435 4196 7435 4190 7435 4250 7436 4190 7436 4175 7436 4205 7437 4203 7437 4253 7437 4253 7438 4203 7438 4201 7438 4253 7439 4201 7439 4252 7439 4252 7440 4201 7440 4200 7440 4252 7441 4200 7441 4198 7441 4205 7442 4253 7442 4206 7442 4206 7443 4253 7443 4254 7443 4206 7444 4254 7444 4208 7444 4251 7445 4227 7445 4254 7445 4254 7446 4227 7446 4226 7446 4254 7447 4226 7447 4208 7447 4229 7448 4251 7448 4187 7448 4187 7449 4251 7449 4255 7449 4187 7450 4255 7450 4188 7450 4250 106 1265 106 948 106 4250 7451 948 7451 4252 7451 948 7452 947 7452 555 7452 555 106 554 106 4256 106 4256 7453 4257 7453 555 7453 555 106 4257 106 4258 106 555 7454 4258 7454 4259 7454 4259 106 4260 106 555 106 555 7455 4260 7455 4261 7455 555 7456 4261 7456 948 7456 948 7457 4261 7457 4262 7457 948 7458 4262 7458 4255 7458 4253 7459 4252 7459 4254 7459 4254 106 4252 106 948 106 4254 106 948 106 4251 106 4251 106 948 106 4255 106 2525 106 1758 106 969 106 2442 7460 2441 7460 2476 7460 2441 106 2443 106 2476 106 2476 7461 2443 7461 2444 7461 2476 7462 2444 7462 2445 7462 970 7463 1219 7463 2497 7463 1004 7464 963 7464 2440 7464 2525 7465 969 7465 2526 7465 2526 7466 969 7466 970 7466 2526 7467 970 7467 2527 7467 2497 7468 2498 7468 970 7468 970 7469 2498 7469 2499 7469 970 7470 2499 7470 2500 7470 2440 7471 1220 7471 1216 7471 2440 7472 2442 7472 1220 7472 1220 7473 2442 7473 2476 7473 1220 106 2476 106 1219 106 1219 7474 2476 7474 2496 7474 1219 7475 2496 7475 2497 7475 2500 7476 2501 7476 970 7476 970 7477 2501 7477 2512 7477 970 7478 2512 7478 2527 7478 1216 106 1217 106 2440 106 2440 7479 1217 7479 1218 7479 2440 7480 1218 7480 1004 7480 2440 7481 963 7481 2438 7481 2438 7482 963 7482 961 7482 2438 7483 961 7483 2469 7483 2469 7484 961 7484 959 7484 2469 7485 959 7485 2470 7485 2470 7486 959 7486 957 7486 2470 7487 957 7487 2471 7487 2471 7488 957 7488 2472 7488 2472 7489 957 7489 956 7489 2472 7490 956 7490 1462 7490 955 632 991 632 1472 632 1472 632 991 632 1240 632 586 98 926 98 1315 98 1315 98 1317 98 586 98 586 7491 1317 7491 1318 7491 586 7492 1318 7492 1312 7492 1237 98 587 98 1321 98 1321 7493 587 7493 586 7493 1321 98 586 98 1314 98 1314 98 586 98 1312 98 4263 7494 4264 7494 4265 7494 4266 7495 4267 7495 4268 7495 4266 7496 4268 7496 4265 7496 4265 7497 4268 7497 4269 7497 4265 7498 4269 7498 4263 7498 4270 7499 4271 7499 4272 7499 4272 7500 4271 7500 4273 7500 4272 7501 4273 7501 4274 7501 4274 7502 4273 7502 4275 7502 4274 7503 4275 7503 4269 7503 4269 7504 4275 7504 4276 7504 4269 7505 4276 7505 4263 7505 4277 7506 4278 7506 4279 7506 4270 7507 4280 7507 4271 7507 4271 7508 4280 7508 4277 7508 4271 7509 4277 7509 4281 7509 4281 7510 4277 7510 4279 7510 4282 95 811 95 813 95 4282 95 813 95 4283 95 833 7511 829 7511 1782 7511 1782 7512 829 7512 4284 7512 1782 7513 4284 7513 2773 7513 2773 95 4284 95 4285 95 2773 95 4285 95 2769 95 2769 95 4285 95 4286 95 2769 7514 4286 7514 2770 7514 2770 95 4286 95 4283 95 2770 95 4283 95 2764 95 2764 95 4283 95 813 95 857 7515 856 7515 4287 7515 859 7516 4288 7516 860 7516 860 7517 4288 7517 4289 7517 860 7518 4289 7518 567 7518 859 7519 857 7519 4288 7519 4288 7520 857 7520 4287 7520 4288 7521 4287 7521 4290 7521 4290 7522 4287 7522 4291 7522 4290 7523 4291 7523 4292 7523 4292 7524 4291 7524 4293 7524 4294 7525 4295 7525 4291 7525 4291 7526 4295 7526 4296 7526 4291 7527 4296 7527 4293 7527 4297 7528 4298 7528 4299 7528 4299 7529 4298 7529 4300 7529 4299 7530 4300 7530 4301 7530 4297 7531 4302 7531 4298 7531 4298 7532 4302 7532 4303 7532 4298 7533 4303 7533 4304 7533 4303 7534 4305 7534 4304 7534 4304 7535 4305 7535 4295 7535 4304 7536 4295 7536 4294 7536 628 7537 614 7537 4300 7537 4300 7537 614 7537 4301 7537 1641 7538 4306 7538 4307 7538 1636 7539 1638 7539 4307 7539 4307 7540 1638 7540 1639 7540 4307 7541 1639 7541 1641 7541 1636 7542 4307 7542 1634 7542 1634 7543 4307 7543 4308 7543 1634 7544 4308 7544 612 7544 1656 7545 4309 7545 4310 7545 4310 7546 4309 7546 4311 7546 4310 7547 4311 7547 4312 7547 4312 7548 4311 7548 4307 7548 4312 7549 4307 7549 4306 7549 4313 7550 4189 7550 4314 7550 4314 7551 4189 7551 4188 7551 4315 7552 4241 7552 4225 7552 4225 7553 4183 7553 4315 7553 4315 7554 4183 7554 4182 7554 4315 7555 4182 7555 4316 7555 4316 7556 4182 7556 4186 7556 4316 7557 4186 7557 4313 7557 4313 7558 4186 7558 4185 7558 4313 7559 4185 7559 4189 7559 4188 7560 4255 7560 4314 7560 4314 7561 4255 7561 4262 7561 811 7562 4282 7562 816 7562 816 7563 4282 7563 2768 7563 2768 7564 4282 7564 4283 7564 2768 7565 4283 7565 4317 7565 589 7566 3734 7566 583 7566 583 7567 3734 7567 727 7567 583 7568 727 7568 4318 7568 727 7569 726 7569 4318 7569 4318 7570 726 7570 733 7570 4318 7571 733 7571 4319 7571 4319 7572 733 7572 728 7572 4319 7573 728 7573 4320 7573 777 95 666 95 775 95 775 7574 666 7574 668 7574 668 7575 671 7575 775 7575 775 95 671 95 673 95 775 7576 673 7576 774 7576 774 7577 673 7577 675 7577 675 95 677 95 774 95 774 95 677 95 680 95 774 95 680 95 679 95 687 95 686 95 693 95 693 7578 686 7578 680 7578 693 7579 680 7579 702 7579 702 7580 680 7580 677 7580 1288 7581 1287 7581 4279 7581 4278 7582 4131 7582 4279 7582 4279 7582 4131 7582 664 7582 666 7583 777 7583 664 7583 664 7584 777 7584 785 7584 785 7585 945 7585 664 7585 664 7585 945 7585 946 7585 664 7585 946 7585 788 7585 1288 7586 4279 7586 1290 7586 1290 7587 4279 7587 664 7587 1290 7588 664 7588 884 7588 884 7585 664 7585 788 7585 884 7585 788 7585 787 7585 315 632 4321 632 314 632 314 7589 4321 7589 309 7589 309 7590 4321 7590 310 7590 4322 7591 4323 7591 4324 7591 4324 7592 4325 7592 4322 7592 4322 7593 4325 7593 4326 7593 4322 7594 4326 7594 4327 7594 4328 7595 4329 7595 4330 7595 4330 7596 4329 7596 4331 7596 4330 7597 4331 7597 4332 7597 4332 7598 4331 7598 4333 7598 4334 7599 4335 7599 4333 7599 4333 7600 4335 7600 4336 7600 4333 7601 4336 7601 4332 7601 4337 7602 4338 7602 4334 7602 4334 7603 4338 7603 4339 7603 4334 7604 4339 7604 4335 7604 4340 7605 4341 7605 4342 7605 4334 7606 4343 7606 4337 7606 4337 7607 4343 7607 4340 7607 4337 7608 4340 7608 4344 7608 4344 7609 4340 7609 4342 7609 4317 7610 4283 7610 4286 7610 4329 7611 4328 7611 4345 7611 4345 7612 4328 7612 4317 7612 4345 7613 4317 7613 4346 7613 4317 7614 4286 7614 4346 7614 4346 7615 4286 7615 4285 7615 4346 7616 4285 7616 4347 7616 4348 7617 4349 7617 4284 7617 826 7618 842 7618 4348 7618 4348 7619 842 7619 571 7619 4348 7620 571 7620 570 7620 826 7621 4348 7621 827 7621 827 7622 4348 7622 4284 7622 827 7623 4284 7623 829 7623 4284 7624 4349 7624 4285 7624 4285 7625 4349 7625 4350 7625 4285 7626 4350 7626 4347 7626 1161 7627 1159 7627 4351 7627 4351 7628 1159 7628 1158 7628 4352 7629 1153 7629 1152 7629 4353 7630 1156 7630 1155 7630 1040 7631 1041 7631 4354 7631 4354 7632 1041 7632 1042 7632 4354 7633 1042 7633 4353 7633 4353 7634 1042 7634 1045 7634 4353 7635 1045 7635 1156 7635 1040 7636 4354 7636 1039 7636 1039 7637 4354 7637 4355 7637 1039 7638 4355 7638 1033 7638 1033 7639 4355 7639 4356 7639 1033 7640 4356 7640 1034 7640 1034 7641 4356 7641 4357 7641 1034 7642 4357 7642 1035 7642 4358 7643 1037 7643 4357 7643 4357 7644 1037 7644 1036 7644 4357 7645 1036 7645 1035 7645 1038 7646 1037 7646 4359 7646 4359 7647 1037 7647 4358 7647 4359 7648 4358 7648 4360 7648 4361 7649 4362 7649 4363 7649 4363 7650 4362 7650 4360 7650 4364 7651 4365 7651 4361 7651 4365 7652 4364 7652 1022 7652 1022 7653 4364 7653 1023 7653 1023 7654 4364 7654 4366 7654 1023 7655 4366 7655 1024 7655 1024 7656 4366 7656 4367 7656 1024 7657 4367 7657 1025 7657 1025 7658 4367 7658 4368 7658 1025 7659 4368 7659 1026 7659 1026 7660 4368 7660 4369 7660 1026 7661 4369 7661 1000 7661 1000 7662 4369 7662 4351 7662 1000 7663 4351 7663 1017 7663 1017 7664 4351 7664 1158 7664 1017 7665 1158 7665 1018 7665 4361 7666 4363 7666 4364 7666 4364 7667 4363 7667 4370 7667 4364 7668 4370 7668 4366 7668 4366 7669 4370 7669 4371 7669 4366 7670 4371 7670 4367 7670 4367 7671 4371 7671 4372 7671 4367 7672 4372 7672 4368 7672 4368 7673 4372 7673 4373 7673 4368 7674 4373 7674 4369 7674 4369 7675 4373 7675 4352 7675 4369 7676 4352 7676 4351 7676 4351 7677 4352 7677 1152 7677 4351 7678 1152 7678 1161 7678 4360 7679 4358 7679 4363 7679 4363 7680 4358 7680 4357 7680 4363 7681 4357 7681 4370 7681 4370 7682 4357 7682 4356 7682 4370 7683 4356 7683 4371 7683 4371 7684 4356 7684 4355 7684 4371 7685 4355 7685 4372 7685 4372 7686 4355 7686 4354 7686 4372 7687 4354 7687 4373 7687 4373 7688 4354 7688 4353 7688 4373 7689 4353 7689 4352 7689 4352 7690 4353 7690 1155 7690 4352 7691 1155 7691 1153 7691 4374 7692 1038 7692 4375 7692 4375 7693 1038 7693 4359 7693 4375 7694 4359 7694 4376 7694 4376 7695 4359 7695 4360 7695 4376 7696 4360 7696 4377 7696 4377 7697 4360 7697 4362 7697 4377 7698 4362 7698 4378 7698 4378 7699 4362 7699 4361 7699 4378 7700 4361 7700 4379 7700 4379 7701 4361 7701 4365 7701 4379 7702 4365 7702 1003 7702 1003 7703 4365 7703 1022 7703 4380 633 156 633 4381 633 4381 633 156 633 4382 633 4382 633 156 633 4383 633 4382 633 4383 633 4384 633 4384 633 4383 633 4385 633 4384 7704 4385 7704 4386 7704 4386 7705 4385 7705 4387 7705 4386 7706 4387 7706 4388 7706 4389 633 4390 633 4391 633 4392 7707 4393 7707 4394 7707 4394 7708 4393 7708 4395 7708 4396 633 4397 633 4398 633 4398 7709 4397 7709 4399 7709 4398 633 4399 633 4400 633 4400 633 4399 633 4401 633 4402 7710 4403 7710 4404 7710 4404 633 4403 633 4405 633 4404 633 4405 633 4406 633 4406 633 4405 633 4407 633 4406 633 4407 633 4408 633 4408 633 4407 633 4409 633 4408 633 4409 633 4410 633 4410 633 4409 633 4411 633 4410 7585 4411 7585 4412 7585 4413 7711 4412 7711 4414 7711 4413 7712 4414 7712 4415 7712 4415 633 4414 633 4416 633 4415 7713 4416 7713 4417 7713 4418 633 4417 633 4419 633 4418 633 4419 633 4395 633 4388 7714 4387 7714 4420 7714 4420 633 4387 633 4421 633 4420 7715 4421 7715 4422 7715 4389 7716 4391 7716 4423 7716 4423 7717 4391 7717 4424 7717 4423 633 4424 633 4425 633 4425 7718 4424 7718 4426 7718 4425 633 4426 633 4427 633 4427 633 4426 633 4428 633 4427 7719 4428 7719 4429 7719 4429 633 4428 633 4430 633 4429 7720 4430 7720 4431 7720 4431 633 4430 633 4432 633 4431 633 4432 633 4433 633 4433 7721 4432 7721 4434 7721 4433 633 4434 633 4401 633 4401 633 4434 633 4435 633 4401 7722 4435 7722 4400 7722 4421 7723 4436 7723 4422 7723 4422 633 4436 633 4437 633 4422 7724 4437 7724 4438 7724 4438 633 4437 633 4439 633 4438 633 4439 633 4440 633 4440 633 4439 633 4441 633 4440 633 4441 633 4442 633 4442 7725 4441 7725 4443 7725 4442 7726 4443 7726 4396 7726 4396 7727 4443 7727 4444 7727 4396 633 4444 633 4397 633 4390 633 4389 633 4445 633 4445 7728 4389 7728 4446 7728 4445 633 4446 633 4447 633 4447 633 4446 633 4448 633 4447 7729 4448 7729 4449 7729 4449 633 4448 633 4450 633 4449 633 4450 633 4451 633 4451 633 4450 633 4452 633 4451 7730 4452 7730 4453 7730 4453 7731 4452 7731 4454 7731 4453 633 4454 633 4455 633 4454 7732 4456 7732 4455 7732 4455 633 4456 633 4457 633 4455 7733 4457 7733 4458 7733 4458 633 4457 633 4459 633 4458 633 4459 633 4460 633 4460 633 4459 633 4461 633 4460 633 4461 633 4462 633 4462 633 4461 633 4463 633 4462 7734 4463 7734 4402 7734 4402 633 4463 633 4464 633 4402 633 4464 633 4403 633 4465 7735 4466 7735 4467 7735 4467 7736 4466 7736 4468 7736 4467 7737 4468 7737 4469 7737 4465 7738 4470 7738 4466 7738 4466 7739 4470 7739 4471 7739 4466 7740 4471 7740 4472 7740 4472 7741 4471 7741 4473 7741 4472 7742 4473 7742 4474 7742 4475 7743 4476 7743 4477 7743 4477 7744 4478 7744 4475 7744 4475 7745 4478 7745 4479 7745 4475 7746 4479 7746 4468 7746 4468 7747 4479 7747 4480 7747 4468 7748 4480 7748 4469 7748 4481 7749 4482 7749 4483 7749 4483 7750 4482 7750 4484 7750 4483 7751 4484 7751 4476 7751 4476 7752 4484 7752 4485 7752 4476 7753 4485 7753 4477 7753 4481 7754 4483 7754 4486 7754 4486 7755 4483 7755 4487 7755 4486 7756 4487 7756 4488 7756 4489 7757 4490 7757 4491 7757 4491 7758 4490 7758 4492 7758 4491 7759 4492 7759 4493 7759 4493 7760 4492 7760 4494 7760 4493 7761 4494 7761 4495 7761 4495 7762 4494 7762 4496 7762 4495 7763 4496 7763 4497 7763 4497 7764 4496 7764 4498 7764 4497 7765 4498 7765 4499 7765 4499 7766 4498 7766 4472 7766 4499 7767 4472 7767 4500 7767 4500 7768 4472 7768 4474 7768 4500 7769 4474 7769 4501 7769 4502 7770 4488 7770 4503 7770 4503 7771 4488 7771 4487 7771 4503 7772 4487 7772 4504 7772 4504 7773 4487 7773 4490 7773 4504 7774 4490 7774 4505 7774 4505 7775 4490 7775 4489 7775 4506 7776 4507 7776 4508 7776 4508 7777 4507 7777 4509 7777 4508 7778 4509 7778 4510 7778 4509 7779 4511 7779 4512 7779 4509 7780 4512 7780 4510 7780 4510 7781 4512 7781 4513 7781 4510 7782 4513 7782 4514 7782 4515 7783 4516 7783 4517 7783 4517 7784 4516 7784 4518 7784 4517 7785 4518 7785 4519 7785 4520 7786 4521 7786 4522 7786 4522 7787 4521 7787 4523 7787 4522 7788 4523 7788 4519 7788 4519 7789 4523 7789 4524 7789 4519 7790 4524 7790 4517 7790 4525 106 4526 106 4527 106 4528 106 4507 106 4506 106 4506 7791 4529 7791 4528 7791 4528 7792 4529 7792 4530 7792 4528 106 4530 106 4527 106 4527 7793 4530 7793 4531 7793 4532 106 4533 106 4534 106 4534 7794 4533 7794 4535 7794 4531 106 4536 106 4527 106 4527 106 4536 106 4537 106 4527 7795 4537 7795 4525 7795 4525 7796 4537 7796 4538 7796 4525 7797 4538 7797 4534 7797 4534 7798 4538 7798 4532 7798 4535 7799 4539 7799 4534 7799 4534 7800 4539 7800 4540 7800 4534 106 4540 106 4541 106 4527 95 4526 95 4542 95 4543 7801 4544 7801 4545 7801 4545 95 4544 95 4527 95 4545 95 4527 95 4546 95 4546 95 4527 95 4542 95 4543 7802 4547 7802 4544 7802 4544 95 4547 95 4548 95 4544 95 4548 95 4549 95 4544 106 4549 106 4550 106 4550 7803 4549 7803 4551 7803 4550 7804 4551 7804 4552 7804 4516 98 4515 98 4553 98 4554 7805 4555 7805 4556 7805 4555 98 4557 98 4556 98 4556 7806 4557 7806 4558 7806 4556 98 4558 98 4553 98 4553 7807 4558 7807 4559 7807 4553 7808 4559 7808 4516 7808 4556 7809 4560 7809 4561 7809 4561 98 4562 98 4556 98 4556 7810 4562 7810 4563 7810 4556 7811 4563 7811 4554 7811 4554 98 4563 98 4564 98 4554 98 4564 98 4565 98 4564 98 4566 98 4565 98 4565 7812 4566 7812 4567 7812 4565 98 4567 98 4568 98 4568 7813 4567 7813 4569 7813 4568 7814 4569 7814 4570 7814 4571 7815 4572 7815 4573 7815 4573 7816 4572 7816 4574 7816 4573 7817 4574 7817 4575 7817 4575 7818 4574 7818 4576 7818 4575 7819 4576 7819 4577 7819 4577 7819 4576 7819 4578 7819 4579 106 4580 106 4578 106 4578 106 4580 106 4577 106 4581 106 4582 106 4583 106 4583 106 4582 106 1435 106 4584 98 1451 98 4585 98 4584 98 4585 98 4586 98 4587 7820 4585 7820 4588 7820 4588 7821 4585 7821 4589 7821 4588 7822 4589 7822 4590 7822 4590 7823 4589 7823 4591 7823 4592 7824 4593 7824 4594 7824 4594 7825 4593 7825 4595 7825 4594 7826 4595 7826 4596 7826 4597 7827 4598 7827 4599 7827 4592 7828 4594 7828 4600 7828 4600 7829 4594 7829 4601 7829 4600 7830 4601 7830 4599 7830 4599 7831 4601 7831 4602 7831 4599 7832 4602 7832 4597 7832 4603 7833 4604 7833 4605 7833 4605 7834 4604 7834 4599 7834 4605 7835 4599 7835 4606 7835 4606 7836 4599 7836 4598 7836 4607 7837 4608 7837 4609 7837 4609 7838 4608 7838 4610 7838 4609 7839 4610 7839 4611 7839 4612 7840 4613 7840 4611 7840 4611 7841 4613 7841 4614 7841 4611 7842 4614 7842 4609 7842 4615 7843 4616 7843 4617 7843 4617 7844 4616 7844 4618 7844 4617 7845 4618 7845 4619 7845 4596 7846 4613 7846 4594 7846 4594 7847 4613 7847 4612 7847 4594 7848 4612 7848 4620 7848 4620 7849 4612 7849 4621 7849 4620 7850 4621 7850 4622 7850 4622 7851 4621 7851 4623 7851 4622 7852 4623 7852 4619 7852 4619 7853 4623 7853 4624 7853 4619 7854 4624 7854 4617 7854 4625 7855 4615 7855 4626 7855 4626 7856 4615 7856 4617 7856 4626 7857 4617 7857 4627 7857 4627 7858 4617 7858 4628 7858 4627 7859 4628 7859 4629 7859 4630 7860 4631 7860 4632 7860 4632 7861 4631 7861 4627 7861 4632 7862 4627 7862 4633 7862 4633 7863 4627 7863 4629 7863 4634 7864 4635 7864 4636 7864 4636 7865 4635 7865 4637 7865 4636 7866 4637 7866 4638 7866 4634 7867 4639 7867 4635 7867 4635 7868 4639 7868 4640 7868 4635 7869 4640 7869 4604 7869 4604 7870 4640 7870 4641 7870 4604 7871 4641 7871 4599 7871 4642 7872 4643 7872 4644 7872 4642 7873 4644 7873 4645 7873 4645 7874 4644 7874 4646 7874 4645 7875 4646 7875 4647 7875 4647 7876 4646 7876 4648 7876 4647 7877 4648 7877 4649 7877 4649 7878 4648 7878 4650 7878 4649 7879 4650 7879 4651 7879 4651 7880 4652 7880 4649 7880 4649 7881 4652 7881 4586 7881 4649 7882 4586 7882 4585 7882 4581 7883 4653 7883 4654 7883 4582 7884 4581 7884 4655 7884 4655 7885 4581 7885 4654 7885 4655 7886 4654 7886 4656 7886 4656 7887 4654 7887 4657 7887 4656 7888 4657 7888 4658 7888 4658 7889 4657 7889 4659 7889 4658 7890 4659 7890 4660 7890 4660 7891 4659 7891 4661 7891 4660 7892 4661 7892 4662 7892 4663 7893 4664 7893 4665 7893 4665 7894 4664 7894 4662 7894 4665 7895 4662 7895 4666 7895 4666 7896 4662 7896 4661 7896 4582 7897 4667 7897 4668 7897 4668 7898 4667 7898 4669 7898 4670 7899 4671 7899 4672 7899 4672 7900 4671 7900 4673 7900 4672 7901 4673 7901 4674 7901 4674 7902 4673 7902 4675 7902 4674 7903 4675 7903 4667 7903 4667 7904 4675 7904 4676 7904 4667 7905 4676 7905 4669 7905 4670 7906 4672 7906 4677 7906 4677 7907 4672 7907 4678 7907 4677 7908 4678 7908 4679 7908 4679 7909 4678 7909 4680 7909 4679 7910 4680 7910 4681 7910 4681 7911 4680 7911 4682 7911 4681 7912 4682 7912 4683 7912 4615 7913 4625 7913 4684 7913 4684 7914 4625 7914 4683 7914 4684 7915 4683 7915 4685 7915 4685 7916 4683 7916 4682 7916 4664 95 4663 95 4686 95 4687 7917 4688 7917 4689 7917 4642 95 4686 95 4643 95 4643 95 4686 95 4690 95 4689 95 4664 95 4687 95 4687 95 4664 95 4686 95 4687 95 4686 95 4691 95 4691 95 4686 95 4642 95 4691 95 4642 95 4692 95 4692 95 4642 95 4693 95 4692 7918 4693 7918 4694 7918 4695 7919 4696 7919 4697 7919 4695 7920 4698 7920 4699 7920 4700 632 4701 632 4702 632 4702 7921 4701 7921 4695 7921 4702 632 4695 632 4703 632 4703 632 4695 632 4697 632 4704 632 4696 632 4705 632 4705 632 4696 632 4695 632 4705 632 4695 632 4706 632 4706 632 4695 632 4699 632 4707 7922 4708 7922 4709 7922 4709 7923 4708 7923 4710 7923 4709 7924 4710 7924 4711 7924 4709 7925 4712 7925 4707 7925 4707 7926 4712 7926 4713 7926 4707 7927 4713 7927 4714 7927 4714 7928 4713 7928 4715 7928 4714 7929 4715 7929 4716 7929 4716 7930 4715 7930 4717 7930 4716 7931 4717 7931 4718 7931 4718 7932 4717 7932 4719 7932 4718 7933 4719 7933 4720 7933 4721 7934 4722 7934 4723 7934 4720 7935 4719 7935 4723 7935 4723 7936 4719 7936 4724 7936 4723 7937 4724 7937 4721 7937 4725 7938 4726 7938 4724 7938 4724 7939 4726 7939 4727 7939 4724 7940 4727 7940 4721 7940 4728 7941 4729 7941 4725 7941 4725 7942 4729 7942 4730 7942 4725 7943 4730 7943 4726 7943 4731 7944 4732 7944 4728 7944 4728 7945 4732 7945 4733 7945 4728 7946 4733 7946 4729 7946 4734 7947 4735 7947 4731 7947 4731 7948 4735 7948 4736 7948 4731 7949 4736 7949 4732 7949 4737 7950 4738 7950 4734 7950 4734 7951 4738 7951 4739 7951 4734 7952 4739 7952 4735 7952 4711 7953 4740 7953 4709 7953 4709 7954 4740 7954 4741 7954 4709 7955 4741 7955 4737 7955 4737 7956 4741 7956 4742 7956 4737 7957 4742 7957 4738 7957 4739 7958 4738 7958 4743 7958 4744 7959 4745 7959 4746 7959 4747 7960 4748 7960 4749 7960 4750 7961 4751 7961 4752 7961 4751 7962 4753 7962 4752 7962 4752 7963 4753 7963 4754 7963 4752 7964 4754 7964 4755 7964 4747 7965 4749 7965 4756 7965 4757 7966 4758 7966 4759 7966 4759 7967 4758 7967 4760 7967 4761 7968 4762 7968 4760 7968 4760 7969 4762 7969 4763 7969 4760 7970 4763 7970 4759 7970 4764 7971 4765 7971 4766 7971 4766 7972 4765 7972 4767 7972 4766 7973 4767 7973 4768 7973 4764 7974 4766 7974 4769 7974 4769 7975 4766 7975 4770 7975 4769 7976 4770 7976 4771 7976 4772 7977 4773 7977 4770 7977 4770 7978 4773 7978 4774 7978 4770 7979 4774 7979 4771 7979 4775 7980 4776 7980 4777 7980 4777 7981 4776 7981 4778 7981 4777 7982 4778 7982 4772 7982 4772 7983 4778 7983 4779 7983 4772 7984 4779 7984 4773 7984 4780 7985 4781 7985 4775 7985 4775 7986 4781 7986 4782 7986 4775 7987 4782 7987 4776 7987 4783 7988 4780 7988 4784 7988 4784 7989 4780 7989 4785 7989 4783 7990 4786 7990 4780 7990 4780 7991 4786 7991 4787 7991 4780 7992 4787 7992 4781 7992 4788 7993 4789 7993 4790 7993 4790 7994 4789 7994 4791 7994 4790 7995 4791 7995 4792 7995 4792 7996 4793 7996 4790 7996 4790 7997 4793 7997 4794 7997 4790 7998 4794 7998 4795 7998 4796 7999 4744 7999 4797 7999 4797 8000 4744 8000 4746 8000 4797 8001 4746 8001 4710 8001 4710 8002 4746 8002 4711 8002 4743 8003 4738 8003 4798 8003 4738 8004 4742 8004 4798 8004 4798 8005 4742 8005 4741 8005 4798 8006 4741 8006 4746 8006 4746 8007 4741 8007 4740 8007 4746 8008 4740 8008 4711 8008 4739 8009 4743 8009 4735 8009 4735 8010 4743 8010 4799 8010 4735 8011 4799 8011 4736 8011 4736 8012 4799 8012 4800 8012 4736 8013 4800 8013 4732 8013 4732 8014 4800 8014 4733 8014 4733 8015 4800 8015 4801 8015 4733 8016 4801 8016 4729 8016 4729 8017 4801 8017 4730 8017 4730 8018 4801 8018 4802 8018 4730 8019 4802 8019 4726 8019 4726 8020 4802 8020 4727 8020 4727 8021 4802 8021 4752 8021 4727 8022 4752 8022 4721 8022 4721 8023 4752 8023 4755 8023 4721 8024 4755 8024 4722 8024 4745 8025 4803 8025 4746 8025 4746 8026 4803 8026 4804 8026 4746 8027 4804 8027 4798 8027 4798 8028 4804 8028 4805 8028 4798 8029 4805 8029 4743 8029 4743 8030 4805 8030 4806 8030 4743 8031 4806 8031 4799 8031 4799 8032 4806 8032 4807 8032 4799 8033 4807 8033 4800 8033 4800 8034 4807 8034 4808 8034 4800 8035 4808 8035 4801 8035 4801 8036 4808 8036 4809 8036 4801 8037 4809 8037 4802 8037 4802 8038 4809 8038 4810 8038 4802 8039 4810 8039 4752 8039 4752 8040 4810 8040 4749 8040 4752 8041 4749 8041 4750 8041 4750 8042 4749 8042 4748 8042 4803 8043 4788 8043 4804 8043 4804 8044 4788 8044 4790 8044 4804 8045 4790 8045 4805 8045 4805 8046 4790 8046 4811 8046 4805 8047 4811 8047 4806 8047 4806 8048 4811 8048 4812 8048 4806 8049 4812 8049 4807 8049 4807 8050 4812 8050 4813 8050 4807 8051 4813 8051 4808 8051 4808 8052 4813 8052 4814 8052 4808 8053 4814 8053 4809 8053 4809 8054 4814 8054 4815 8054 4809 8055 4815 8055 4810 8055 4810 8056 4815 8056 4761 8056 4810 8057 4761 8057 4749 8057 4749 8058 4761 8058 4760 8058 4749 8059 4760 8059 4756 8059 4756 8060 4760 8060 4758 8060 4756 8061 4758 8061 4816 8061 4795 8062 4817 8062 4790 8062 4790 8063 4817 8063 4785 8063 4790 8064 4785 8064 4811 8064 4811 8065 4785 8065 4780 8065 4811 8066 4780 8066 4812 8066 4812 8067 4780 8067 4775 8067 4812 8068 4775 8068 4813 8068 4813 8069 4775 8069 4777 8069 4813 8070 4777 8070 4814 8070 4814 8071 4777 8071 4772 8071 4814 8072 4772 8072 4815 8072 4815 8073 4772 8073 4770 8073 4815 8074 4770 8074 4761 8074 4761 8075 4770 8075 4766 8075 4761 8076 4766 8076 4762 8076 4762 8077 4766 8077 4768 8077 4818 8078 4819 8078 4820 8078 4821 8079 4822 8079 4774 8079 4822 8080 4823 8080 4774 8080 4774 8081 4823 8081 4824 8081 4774 8082 4824 8082 4771 8082 4771 8083 4824 8083 4825 8083 4771 8084 4825 8084 4769 8084 4769 8085 4825 8085 4826 8085 4769 8086 4826 8086 4764 8086 4764 8087 4826 8087 4827 8087 4764 8088 4827 8088 4765 8088 4828 8089 4829 8089 4830 8089 4830 8090 4829 8090 4831 8090 4830 8091 4831 8091 4832 8091 4832 8092 4831 8092 4833 8092 4832 8093 4833 8093 4834 8093 4835 8094 4776 8094 4836 8094 4836 8095 4776 8095 4782 8095 4836 8096 4782 8096 4837 8096 4837 8097 4782 8097 4781 8097 4837 8098 4781 8098 4838 8098 4835 8099 4839 8099 4776 8099 4776 8100 4839 8100 4828 8100 4776 8101 4828 8101 4778 8101 4778 8102 4828 8102 4830 8102 4778 8103 4830 8103 4820 8103 4820 8104 4830 8104 4832 8104 4820 8105 4832 8105 4818 8105 4787 8106 4786 8106 4840 8106 4787 8107 4840 8107 4781 8107 4781 8108 4840 8108 4841 8108 4781 8109 4841 8109 4838 8109 4821 8110 4774 8110 4819 8110 4819 8111 4774 8111 4773 8111 4819 8112 4773 8112 4820 8112 4820 8113 4773 8113 4779 8113 4820 8114 4779 8114 4778 8114 4842 8115 4843 8115 4844 8115 4839 8116 4845 8116 4828 8116 4835 8117 4846 8117 4847 8117 4831 8118 4848 8118 4833 8118 4833 8119 4848 8119 4849 8119 4833 8120 4849 8120 4834 8120 4850 8121 4851 8121 4852 8121 4852 8122 4851 8122 4853 8122 4852 8123 4853 8123 4854 8123 4854 8124 4853 8124 4855 8124 4854 8125 4855 8125 4856 8125 4857 8126 4858 8126 4850 8126 4850 8127 4858 8127 4859 8127 4850 8128 4859 8128 4851 8128 4860 8129 4861 8129 4862 8129 4862 8130 4861 8130 4863 8130 4862 8131 4863 8131 4864 8131 4864 8132 4863 8132 4857 8132 4864 8133 4857 8133 4865 8133 4865 8134 4857 8134 4850 8134 4860 8135 4862 8135 4866 8135 4866 8136 4862 8136 4867 8136 4866 8137 4867 8137 4868 8137 4868 8138 4867 8138 4869 8138 4868 8139 4869 8139 4870 8139 4828 8140 4845 8140 4829 8140 4845 8141 4871 8141 4829 8141 4829 8142 4871 8142 4872 8142 4829 8143 4872 8143 4831 8143 4831 8144 4872 8144 4873 8144 4831 8145 4873 8145 4848 8145 4874 8146 4844 8146 4838 8146 4838 8147 4844 8147 4843 8147 4838 8148 4843 8148 4837 8148 4837 8149 4843 8149 4842 8149 4837 8150 4842 8150 4836 8150 4835 8151 4836 8151 4846 8151 4846 8152 4836 8152 4842 8152 4846 8153 4842 8153 4875 8153 4875 8154 4842 8154 4844 8154 4875 8155 4844 8155 4876 8155 4876 8156 4844 8156 4874 8156 4876 8157 4874 8157 4877 8157 4878 8158 4849 8158 4879 8158 4879 8159 4849 8159 4848 8159 4879 8160 4848 8160 4880 8160 4880 8161 4848 8161 4873 8161 4880 8162 4873 8162 4881 8162 4881 8163 4873 8163 4872 8163 4881 8164 4872 8164 4882 8164 4882 8165 4872 8165 4871 8165 4882 8166 4871 8166 4883 8166 4883 8167 4871 8167 4845 8167 4883 8168 4845 8168 4847 8168 4847 8169 4845 8169 4839 8169 4847 8170 4839 8170 4835 8170 4856 8171 4884 8171 4854 8171 4854 8172 4884 8172 4885 8172 4854 8173 4885 8173 4852 8173 4852 8174 4885 8174 4886 8174 4852 8175 4886 8175 4850 8175 4850 8176 4886 8176 4887 8176 4850 8177 4887 8177 4865 8177 4865 8178 4887 8178 4888 8178 4865 8179 4888 8179 4864 8179 4864 8180 4888 8180 4889 8180 4864 8181 4889 8181 4862 8181 4862 8182 4889 8182 4890 8182 4862 8183 4890 8183 4867 8183 4867 8184 4890 8184 4891 8184 4867 8185 4891 8185 4869 8185 4869 8186 4891 8186 4892 8186 4869 8187 4892 8187 4870 8187 4877 8188 4868 8188 4876 8188 4876 8189 4868 8189 4870 8189 4876 8190 4870 8190 4875 8190 4875 8191 4870 8191 4892 8191 4875 8192 4892 8192 4846 8192 4846 8193 4892 8193 4891 8193 4846 8194 4891 8194 4847 8194 4847 8195 4891 8195 4890 8195 4847 8196 4890 8196 4883 8196 4883 8197 4890 8197 4889 8197 4883 8198 4889 8198 4882 8198 4882 8199 4889 8199 4888 8199 4882 8200 4888 8200 4881 8200 4881 8201 4888 8201 4887 8201 4881 8202 4887 8202 4880 8202 4880 8203 4887 8203 4886 8203 4880 8204 4886 8204 4879 8204 4879 8205 4886 8205 4885 8205 4879 8206 4885 8206 4878 8206 4878 8207 4885 8207 4884 8207 4893 8208 4894 8208 4895 8208 4895 8209 4894 8209 4896 8209 4895 8210 4896 8210 4897 8210 4893 8211 4895 8211 4898 8211 4898 8212 4895 8212 4899 8212 4898 8213 4899 8213 4900 8213 4900 8214 4899 8214 4901 8214 4900 8215 4901 8215 4902 8215 4902 8216 4901 8216 4903 8216 4902 8217 4903 8217 4904 8217 4904 8218 4903 8218 4905 8218 4904 8219 4905 8219 4906 8219 4906 8220 4905 8220 4907 8220 4907 8221 4905 8221 4908 8221 4907 8222 4908 8222 4909 8222 4909 8223 4908 8223 4910 8223 4909 8224 4910 8224 4911 8224 4911 8225 4910 8225 4912 8225 4911 8226 4912 8226 4913 8226 4913 8227 4912 8227 4914 8227 4913 8228 4914 8228 4915 8228 4915 8229 4914 8229 4916 8229 4915 8230 4916 8230 4917 8230 4917 8231 4916 8231 4918 8231 4917 8232 4918 8232 4919 8232 4919 8233 4918 8233 4920 8233 4919 8234 4920 8234 4921 8234 4922 8235 4923 8235 4924 8235 4923 8236 4922 8236 4834 8236 4834 8237 4922 8237 4925 8237 4834 8238 4925 8238 4832 8238 4832 8239 4925 8239 4926 8239 4832 8240 4926 8240 4818 8240 4822 8241 4821 8241 4927 8241 4927 8242 4821 8242 4819 8242 4927 8243 4819 8243 4928 8243 4928 8244 4819 8244 4818 8244 4928 8245 4818 8245 4929 8245 4929 8246 4818 8246 4926 8246 4924 8247 4930 8247 4922 8247 4922 8248 4930 8248 4931 8248 4922 8249 4931 8249 4925 8249 4925 8250 4931 8250 4932 8250 4925 8251 4932 8251 4926 8251 4926 8252 4932 8252 4933 8252 4926 8253 4933 8253 4929 8253 4929 8254 4933 8254 4934 8254 4929 8255 4934 8255 4928 8255 4928 8256 4934 8256 4935 8256 4928 8257 4935 8257 4927 8257 4927 8258 4935 8258 4936 8258 4927 8259 4936 8259 4822 8259 4822 8260 4936 8260 4937 8260 4822 8261 4937 8261 4823 8261 4823 8262 4937 8262 4938 8262 4823 8263 4938 8263 4824 8263 4824 8264 4938 8264 4939 8264 4824 8265 4939 8265 4825 8265 4825 8266 4939 8266 4940 8266 4825 8267 4940 8267 4826 8267 4826 8268 4940 8268 4941 8268 4924 8269 4920 8269 4930 8269 4930 8270 4920 8270 4918 8270 4930 8271 4918 8271 4931 8271 4931 8272 4918 8272 4916 8272 4931 8273 4916 8273 4932 8273 4932 8274 4916 8274 4914 8274 4932 8275 4914 8275 4933 8275 4933 8276 4914 8276 4912 8276 4933 8277 4912 8277 4934 8277 4934 8278 4912 8278 4910 8278 4934 8279 4910 8279 4935 8279 4935 8280 4910 8280 4908 8280 4935 8281 4908 8281 4936 8281 4936 8282 4908 8282 4905 8282 4936 8283 4905 8283 4937 8283 4937 8284 4905 8284 4903 8284 4937 8285 4903 8285 4938 8285 4938 8286 4903 8286 4901 8286 4938 8287 4901 8287 4939 8287 4939 8288 4901 8288 4899 8288 4939 8289 4899 8289 4940 8289 4940 8290 4899 8290 4895 8290 4940 8291 4895 8291 4941 8291 4941 8292 4895 8292 4897 8292 4855 8293 4942 8293 4943 8293 4944 8294 4834 8294 4849 8294 4944 8295 4849 8295 4945 8295 4945 8296 4849 8296 4878 8296 4945 8297 4878 8297 4946 8297 4946 8298 4878 8298 4884 8298 4946 8299 4884 8299 4943 8299 4943 8300 4884 8300 4856 8300 4943 8301 4856 8301 4855 8301 4947 8302 4948 8302 4921 8302 4921 8303 4920 8303 4947 8303 4947 8304 4920 8304 4924 8304 4947 8305 4924 8305 4949 8305 4949 8306 4924 8306 4923 8306 4949 8307 4923 8307 4950 8307 4950 8308 4923 8308 4834 8308 4950 8309 4834 8309 4944 8309 4951 8310 4488 8310 4502 8310 4951 8311 4502 8311 4942 8311 4942 8312 4502 8312 4952 8312 4942 8313 4952 8313 4943 8313 4474 8314 4953 8314 4501 8314 4501 8315 4953 8315 4948 8315 4501 8316 4948 8316 4954 8316 4954 8317 4948 8317 4947 8317 4954 8318 4947 8318 4955 8318 4955 8319 4947 8319 4956 8319 4956 8320 4947 8320 4949 8320 4956 8321 4949 8321 4957 8321 4952 8322 4958 8322 4943 8322 4943 8323 4958 8323 4959 8323 4943 8324 4959 8324 4946 8324 4946 8325 4959 8325 4960 8325 4946 8326 4960 8326 4945 8326 4945 8327 4960 8327 4961 8327 4945 8328 4961 8328 4944 8328 4944 8329 4961 8329 4957 8329 4944 8330 4957 8330 4950 8330 4950 8331 4957 8331 4949 8331 4500 7585 4501 7585 4954 7585 4960 8332 4959 8332 4505 8332 4505 7585 4959 7585 4504 7585 4505 7585 4489 7585 4960 7585 4960 7585 4489 7585 4491 7585 4960 8333 4491 8333 4961 8333 4961 8334 4491 8334 4493 8334 4961 7585 4493 7585 4957 7585 4957 8335 4493 8335 4495 8335 4957 7585 4495 7585 4956 7585 4956 7585 4495 7585 4497 7585 4956 8336 4497 8336 4955 8336 4955 7585 4497 7585 4954 7585 4954 7585 4497 7585 4499 7585 4954 7585 4499 7585 4500 7585 4502 7585 4503 7585 4952 7585 4952 7585 4503 7585 4504 7585 4952 8337 4504 8337 4958 8337 4958 7585 4504 7585 4959 7585 4962 106 4921 106 4948 106 4963 106 4962 106 4964 106 4964 8338 4962 8338 4948 8338 4964 8339 4948 8339 4965 8339 4965 8340 4948 8340 4953 8340 4966 8341 4967 8341 4968 8341 4969 8342 4970 8342 4971 8342 4972 8343 4969 8343 4973 8343 4974 8344 4975 8344 4973 8344 4973 8345 4975 8345 4976 8345 4973 8346 4976 8346 4972 8346 4969 8347 4971 8347 4973 8347 4973 8348 4971 8348 4977 8348 4973 8349 4977 8349 4974 8349 4974 8350 4977 8350 4978 8350 4974 8351 4978 8351 4979 8351 4980 8352 4981 8352 4979 8352 4979 8353 4981 8353 4982 8353 4979 8354 4982 8354 4974 8354 4974 8355 4982 8355 4983 8355 4974 8356 4983 8356 4975 8356 4984 8357 4980 8357 4985 8357 4985 8358 4980 8358 4979 8358 4985 8359 4979 8359 4986 8359 4986 8360 4979 8360 4978 8360 4967 8361 4984 8361 4968 8361 4968 8362 4984 8362 4985 8362 4968 8363 4985 8363 4987 8363 4987 8364 4985 8364 4986 8364 4987 8365 4986 8365 4988 8365 4988 8366 4986 8366 4978 8366 4988 8367 4978 8367 4989 8367 4989 8368 4978 8368 4977 8368 4989 8369 4977 8369 4990 8369 4990 8370 4977 8370 4971 8370 4990 8371 4971 8371 4991 8371 4991 8372 4971 8372 4970 8372 4991 8373 4970 8373 4992 8373 4992 8374 4970 8374 4969 8374 4992 8375 4969 8375 4993 8375 4993 8376 4969 8376 4972 8376 4993 8377 4972 8377 4994 8377 4995 8378 4966 8378 4996 8378 4996 8379 4966 8379 4968 8379 4996 8380 4968 8380 4997 8380 4997 8381 4968 8381 4987 8381 4997 8382 4987 8382 4998 8382 4998 8383 4987 8383 4988 8383 4965 8384 4995 8384 4964 8384 4964 8385 4995 8385 4996 8385 4964 8386 4996 8386 4963 8386 4963 8387 4996 8387 4997 8387 4963 8388 4997 8388 4962 8388 4962 8389 4997 8389 4998 8389 4999 8390 5000 8390 5001 8390 5002 8391 5003 8391 5004 8391 5005 8392 5006 8392 5003 8392 5004 8393 5007 8393 5008 8393 5008 8394 5007 8394 5009 8394 5008 8395 5009 8395 5010 8395 5010 8396 5009 8396 5011 8396 5010 8397 5011 8397 5012 8397 5011 8398 5013 8398 5012 8398 5012 8399 5013 8399 5014 8399 5012 8400 5014 8400 5001 8400 5001 8401 5014 8401 5015 8401 5001 8402 5015 8402 4999 8402 5004 8403 5008 8403 5002 8403 5002 8404 5008 8404 5010 8404 5002 8405 5010 8405 5016 8405 5016 8406 5010 8406 5012 8406 5016 8407 5012 8407 5017 8407 5017 8408 5012 8408 5001 8408 5017 8409 5001 8409 5018 8409 5018 8410 5001 8410 5000 8410 5018 8411 5000 8411 5019 8411 5003 8412 5002 8412 5005 8412 5005 8413 5002 8413 5016 8413 5005 8414 5016 8414 5020 8414 5020 8415 5016 8415 5017 8415 5020 8416 5017 8416 5021 8416 5021 8417 5017 8417 5018 8417 5021 8418 5018 8418 5022 8418 5022 8419 5018 8419 5019 8419 5022 8420 5019 8420 5023 8420 5024 8421 5025 8421 5026 8421 5026 8422 5025 8422 5027 8422 5026 8423 5027 8423 5028 8423 5028 8424 5027 8424 5029 8424 5030 8425 5029 8425 5031 8425 5031 8426 5029 8426 5027 8426 5031 8427 5027 8427 5032 8427 5032 8428 5027 8428 5025 8428 4999 8429 5024 8429 5000 8429 5000 8430 5024 8430 5026 8430 5000 8431 5026 8431 5019 8431 5019 8432 5026 8432 5028 8432 5019 8433 5028 8433 5023 8433 5023 8434 5028 8434 5029 8434 5023 8435 5029 8435 5033 8435 5033 8436 5029 8436 5030 8436 5033 8437 5030 8437 5034 8437 4855 98 5034 98 4942 98 4942 98 5034 98 5030 98 4942 98 5030 98 4951 98 4951 98 5030 98 5031 98 4951 98 5031 98 5032 98 5035 8438 5036 8438 5037 8438 5038 8439 5032 8439 5025 8439 5039 8440 5040 8440 5041 8440 5041 8441 5040 8441 5042 8441 5041 8442 5042 8442 5043 8442 5036 8443 5044 8443 5045 8443 5044 8444 5036 8444 5046 8444 5046 8445 5036 8445 5035 8445 5046 8446 5035 8446 5047 8446 5048 8447 5049 8447 5047 8447 5047 8448 5049 8448 5050 8448 5047 8449 5050 8449 5046 8449 5015 8450 5014 8450 5037 8450 5051 8451 5052 8451 5053 8451 5054 8452 5055 8452 5056 8452 5056 8453 5055 8453 5057 8453 5056 8454 5057 8454 5058 8454 5058 8455 5057 8455 5059 8455 5058 8456 5059 8456 5060 8456 5060 8457 5059 8457 5040 8457 5060 8458 5040 8458 5061 8458 5061 8459 5040 8459 5039 8459 5061 8460 5039 8460 5062 8460 5062 8461 4688 8461 5061 8461 5061 8462 4688 8462 5063 8462 5061 8463 5063 8463 5060 8463 5060 8464 5063 8464 5064 8464 5060 8465 5064 8465 5058 8465 5058 8466 5064 8466 5051 8466 5058 8467 5051 8467 5056 8467 5056 8468 5051 8468 5053 8468 5056 8469 5053 8469 5054 8469 5004 8470 5048 8470 5007 8470 5007 8471 5048 8471 5047 8471 5007 8472 5047 8472 5009 8472 5009 8473 5047 8473 5035 8473 5009 8474 5035 8474 5011 8474 5011 8475 5035 8475 5037 8475 5011 8476 5037 8476 5013 8476 5013 8477 5037 8477 5014 8477 5055 8478 4999 8478 5057 8478 5057 8479 4999 8479 5015 8479 5057 8480 5015 8480 5059 8480 5059 8481 5015 8481 5037 8481 5059 8482 5037 8482 5040 8482 5040 8483 5037 8483 5036 8483 5040 8484 5036 8484 5042 8484 5042 8485 5036 8485 5045 8485 5042 8486 5045 8486 5043 8486 4688 8487 5065 8487 5063 8487 5063 8488 5065 8488 5066 8488 5063 8489 5066 8489 5064 8489 5064 8490 5066 8490 5067 8490 5064 8491 5067 8491 5051 8491 5051 8492 5067 8492 5068 8492 5051 8493 5068 8493 5052 8493 5052 8494 5068 8494 5069 8494 5052 8495 5069 8495 5053 8495 5053 8496 5069 8496 5038 8496 5053 8497 5038 8497 5054 8497 5054 8498 5038 8498 5025 8498 5054 8499 5025 8499 5055 8499 5055 8500 5025 8500 5024 8500 5055 8501 5024 8501 4999 8501 5070 8502 5071 8502 5072 8502 5073 8503 5074 8503 5075 8503 5076 8504 5077 8504 5078 8504 5078 8505 5077 8505 5079 8505 5078 8506 5079 8506 5080 8506 5080 8507 5079 8507 4994 8507 5070 8508 5081 8508 5082 8508 5082 8509 5081 8509 4995 8509 5082 8510 4995 8510 4965 8510 5083 8511 4984 8511 5084 8511 5084 8512 4984 8512 4967 8512 5084 8513 4967 8513 5081 8513 5081 8514 4967 8514 4966 8514 5081 8515 4966 8515 4995 8515 4994 8516 4972 8516 5080 8516 5080 8517 4972 8517 4976 8517 5080 8518 4976 8518 5078 8518 5078 8519 4976 8519 4975 8519 5078 8520 4975 8520 5085 8520 5085 8521 4975 8521 4983 8521 5085 8522 4983 8522 5086 8522 5086 8523 4983 8523 4982 8523 5086 8524 4982 8524 4981 8524 5076 8525 5078 8525 5087 8525 5087 8526 5078 8526 5085 8526 5087 8527 5085 8527 5088 8527 5088 8528 5085 8528 5086 8528 5088 8529 5086 8529 5089 8529 5089 8530 5086 8530 4981 8530 5089 8531 4981 8531 5083 8531 5083 8532 4981 8532 4980 8532 5083 8533 4980 8533 4984 8533 5070 8534 5090 8534 5081 8534 5081 8535 5090 8535 5091 8535 5081 8536 5091 8536 5084 8536 5084 8537 5091 8537 5092 8537 5084 8538 5092 8538 5083 8538 5083 8539 5092 8539 5075 8539 5083 8540 5075 8540 5089 8540 5089 8541 5075 8541 5074 8541 5089 8542 5074 8542 5088 8542 5088 8543 5074 8543 5093 8543 5088 8544 5093 8544 5087 8544 5087 8545 5093 8545 5076 8545 5070 8546 5072 8546 5090 8546 5090 8547 5072 8547 5094 8547 5090 8548 5094 8548 5091 8548 5091 8549 5094 8549 5095 8549 5091 8550 5095 8550 5092 8550 5092 8551 5095 8551 4694 8551 5092 8552 4694 8552 5075 8552 5075 8553 4694 8553 5096 8553 5075 8554 5096 8554 5073 8554 4953 8555 4474 8555 4473 8555 5038 8556 5069 8556 4486 8556 4488 8557 4951 8557 4486 8557 4486 8558 4951 8558 5032 8558 4486 8559 5032 8559 5038 8559 5097 8560 4477 8560 5098 8560 5098 8561 4477 8561 4485 8561 5098 8562 4485 8562 5099 8562 5099 8563 4485 8563 4484 8563 5099 8564 4484 8564 5068 8564 5068 8565 4484 8565 4482 8565 5068 8566 4482 8566 5069 8566 5069 8567 4482 8567 4481 8567 5069 8568 4481 8568 4486 8568 5100 8569 4465 8569 4467 8569 5100 8570 4467 8570 5101 8570 5101 8571 4467 8571 4469 8571 5101 8572 4469 8572 5102 8572 5102 8573 4469 8573 4480 8573 5102 8574 4480 8574 5103 8574 5103 8575 4480 8575 4479 8575 5103 8576 4479 8576 5097 8576 5097 8577 4479 8577 4478 8577 5097 8578 4478 8578 4477 8578 5100 8579 5071 8579 4465 8579 4465 8580 5071 8580 5070 8580 4465 8581 5070 8581 4470 8581 4470 8582 5070 8582 5082 8582 4470 8583 5082 8583 4471 8583 4471 8584 5082 8584 4473 8584 4473 8585 5082 8585 4965 8585 4473 8586 4965 8586 4953 8586 4767 8587 4765 8587 5104 8587 5104 8588 4765 8588 5105 8588 5104 8589 5105 8589 5106 8589 5107 8590 5108 8590 5105 8590 5105 8591 5108 8591 5109 8591 5105 8592 5109 8592 5106 8592 5110 8593 5111 8593 5105 8593 5105 8594 5111 8594 5107 8594 5112 8595 4827 8595 4826 8595 4765 8596 4827 8596 5105 8596 5105 8597 4827 8597 5112 8597 5105 8598 5112 8598 5110 8598 4894 8599 5111 8599 4896 8599 4896 8600 5111 8600 5110 8600 4896 8601 5110 8601 4897 8601 4897 8602 5110 8602 5112 8602 4897 8603 5112 8603 4941 8603 4941 8604 5112 8604 4826 8604 4921 8605 4962 8605 4919 8605 4919 8606 4962 8606 4998 8606 4919 8607 4998 8607 4917 8607 4917 8608 4998 8608 4915 8608 4915 8609 4998 8609 4988 8609 4915 8610 4988 8610 4913 8610 4913 8611 4988 8611 4911 8611 4911 8612 4988 8612 4989 8612 4911 8613 4989 8613 4909 8613 4990 8614 4906 8614 4989 8614 4989 8615 4906 8615 4907 8615 4989 8616 4907 8616 4909 8616 4898 8617 4900 8617 4991 8617 4991 8618 4900 8618 4902 8618 4991 8619 4902 8619 4990 8619 4990 8620 4902 8620 4904 8620 4990 8621 4904 8621 4906 8621 4898 8622 4991 8622 4893 8622 4893 8623 4991 8623 4992 8623 4893 8624 4992 8624 4894 8624 5113 8625 5114 8625 5115 8625 5115 8626 5114 8626 5116 8626 5115 8627 5116 8627 5117 8627 5116 8628 5076 8628 5117 8628 5117 8629 5076 8629 5093 8629 5117 8630 5093 8630 5118 8630 5118 8631 5093 8631 5074 8631 4694 8632 4693 8632 5096 8632 5096 8633 4693 8633 5118 8633 5096 8634 5118 8634 5073 8634 5073 8635 5118 8635 5074 8635 4993 8636 4994 8636 5114 8636 5114 8637 4994 8637 5079 8637 5114 8638 5079 8638 5116 8638 5116 8639 5079 8639 5077 8639 5116 8640 5077 8640 5076 8640 5113 8641 4587 8641 5114 8641 5114 8642 4587 8642 5119 8642 5114 8643 5119 8643 4993 8643 4993 8644 5119 8644 4992 8644 5120 8645 5121 8645 4744 8645 4710 8646 4708 8646 4797 8646 4797 8647 4708 8647 5120 8647 4797 8648 5120 8648 4796 8648 4796 8649 5120 8649 4744 8649 5122 8650 4723 8650 4722 8650 4753 8651 5123 8651 4754 8651 4754 8652 5123 8652 5122 8652 4754 8653 5122 8653 4755 8653 4755 8654 5122 8654 4722 8654 5124 632 4816 632 4758 632 5125 8655 5126 8655 5127 8655 5128 8656 5125 8656 5129 8656 5129 8657 5125 8657 5127 8657 5129 8658 5127 8658 4874 8658 4874 8659 5127 8659 4877 8659 4786 8660 5128 8660 4840 8660 4840 8661 5128 8661 5129 8661 4840 8662 5129 8662 4841 8662 4841 8663 5129 8663 4874 8663 4841 8664 4874 8664 4838 8664 4786 8665 4783 8665 5128 8665 5128 8666 4783 8666 5130 8666 5128 8667 5130 8667 5125 8667 5130 8668 5131 8668 5125 8668 5125 8669 5131 8669 5132 8669 5125 8670 5132 8670 5126 8670 5004 8671 5003 8671 5133 8671 5004 8672 5133 8672 5048 8672 5043 8673 5045 8673 5134 8673 5134 8674 5045 8674 5044 8674 5134 8675 5044 8675 5046 8675 5046 8676 5050 8676 5134 8676 5134 8677 5050 8677 5049 8677 5134 8678 5049 8678 5135 8678 5136 8679 4689 8679 4688 8679 4688 8680 5062 8680 5136 8680 5136 8681 5062 8681 5039 8681 5136 8682 5039 8682 5041 8682 5137 8683 5138 8683 5139 8683 5139 8684 5138 8684 5133 8684 5139 8685 5133 8685 5006 8685 5006 8686 5133 8686 5003 8686 5138 8687 5140 8687 5133 8687 5133 8688 5140 8688 5135 8688 5133 8689 5135 8689 5048 8689 5048 8690 5135 8690 5049 8690 5140 8691 5141 8691 5135 8691 5135 8692 5141 8692 5136 8692 5135 8693 5136 8693 5134 8693 5134 8694 5136 8694 5041 8694 5134 8695 5041 8695 5043 8695 4868 8696 4877 8696 5006 8696 5006 8697 5005 8697 4868 8697 4868 8698 5005 8698 5020 8698 4868 8699 5020 8699 4866 8699 4866 8700 5020 8700 4860 8700 4863 8701 4861 8701 5022 8701 5022 8702 4861 8702 4860 8702 5022 8703 4860 8703 5021 8703 5021 8704 4860 8704 5020 8704 4853 8705 4851 8705 5023 8705 4851 8706 4859 8706 5023 8706 5023 8707 4859 8707 4858 8707 5023 8708 4858 8708 5022 8708 5022 8709 4858 8709 4857 8709 5022 8710 4857 8710 4863 8710 5023 8711 5033 8711 4853 8711 4853 8712 5033 8712 5034 8712 4853 8713 5034 8713 4855 8713 4792 632 4791 632 5142 632 5142 632 4791 632 5143 632 5144 8714 5145 8714 5130 8714 5145 8715 5146 8715 5130 8715 5130 8716 5146 8716 5147 8716 5130 8717 5147 8717 5131 8717 5131 8718 5147 8718 5132 8718 5148 8719 5149 8719 5150 8719 5150 8720 5149 8720 5151 8720 5150 8721 5151 8721 5152 8721 5152 8722 5151 8722 5144 8722 5152 8723 5144 8723 5153 8723 5144 8724 5130 8724 5153 8724 5153 8725 5130 8725 4783 8725 5153 8726 4783 8726 4784 8726 4793 8727 5148 8727 4794 8727 4794 8728 5148 8728 5150 8728 4794 8729 5150 8729 4795 8729 4795 8730 5150 8730 5152 8730 4795 8731 5152 8731 4817 8731 4817 8732 5152 8732 5153 8732 4817 8733 5153 8733 4785 8733 4785 8734 5153 8734 4784 8734 5099 8735 5068 8735 5067 8735 4694 8736 5095 8736 5154 8736 4694 8737 5154 8737 4692 8737 4692 8738 5154 8738 5155 8738 4692 8739 5155 8739 4691 8739 4691 8740 5155 8740 5156 8740 4691 8741 5156 8741 4687 8741 4687 8742 5156 8742 5065 8742 4687 8743 5065 8743 4688 8743 5099 8744 5067 8744 5098 8744 5098 8745 5067 8745 5157 8745 5098 8746 5157 8746 5097 8746 5097 8747 5157 8747 5158 8747 5097 8748 5158 8748 5103 8748 5103 8749 5158 8749 5102 8749 5102 8750 5158 8750 5159 8750 5102 8751 5159 8751 5101 8751 5101 8752 5159 8752 5100 8752 5100 8753 5159 8753 5072 8753 5100 8754 5072 8754 5071 8754 5095 8755 5094 8755 5154 8755 5154 8756 5094 8756 5160 8756 5154 8757 5160 8757 5155 8757 5155 8758 5160 8758 5161 8758 5155 8759 5161 8759 5156 8759 5156 8760 5161 8760 5162 8760 5156 8761 5162 8761 5065 8761 5065 8762 5162 8762 5066 8762 5094 8763 5072 8763 5160 8763 5160 8764 5072 8764 5159 8764 5160 8765 5159 8765 5161 8765 5161 8766 5159 8766 5158 8766 5161 8767 5158 8767 5162 8767 5162 8768 5158 8768 5157 8768 5162 8769 5157 8769 5066 8769 5066 8770 5157 8770 5067 8770 4762 8771 4768 8771 5163 8771 5164 8772 5165 8772 5166 8772 5166 8773 5165 8773 5167 8773 4590 8774 4757 8774 4759 8774 5168 8775 5169 8775 4588 8775 5169 8776 5168 8776 5167 8776 5167 8777 5168 8777 5163 8777 5167 8778 5163 8778 5166 8778 5108 8779 5164 8779 5109 8779 5109 8780 5164 8780 5166 8780 5109 8781 5166 8781 5106 8781 5106 8782 5166 8782 5163 8782 5106 8783 5163 8783 5104 8783 5104 8784 5163 8784 4768 8784 5104 8785 4768 8785 4767 8785 4588 8786 4590 8786 5168 8786 5168 8787 4590 8787 4759 8787 5168 8788 4759 8788 5163 8788 5163 8789 4759 8789 4763 8789 5163 8790 4763 8790 4762 8790 4894 8791 4992 8791 5111 8791 5111 8792 4992 8792 5119 8792 5111 8793 5119 8793 5107 8793 4588 8794 5169 8794 4587 8794 4587 8795 5169 8795 5167 8795 5167 8796 5165 8796 4587 8796 4587 8797 5165 8797 5164 8797 4587 8798 5164 8798 5119 8798 5119 8799 5164 8799 5108 8799 5119 8800 5108 8800 5107 8800 4587 8801 5113 8801 4585 8801 4585 8802 5113 8802 4649 8802 5113 8803 5115 8803 4649 8803 4649 8804 5115 8804 5117 8804 4649 8805 5117 8805 4647 8805 4647 8806 5117 8806 5118 8806 4647 8807 5118 8807 4645 8807 4645 8808 5118 8808 4693 8808 4645 8809 4693 8809 4642 8809 5121 8810 5170 8810 4744 8810 5143 8811 4791 8811 4789 8811 5171 8812 5172 8812 5173 8812 5173 8813 5172 8813 5170 8813 5173 8814 5170 8814 5174 8814 5174 8815 5170 8815 5121 8815 5143 8816 4789 8816 5171 8816 5171 8817 4789 8817 4788 8817 5171 8818 4788 8818 5172 8818 5172 8819 4788 8819 4803 8819 5172 8820 4803 8820 5170 8820 5170 8821 4803 8821 4745 8821 5170 8822 4745 8822 4744 8822 5175 8823 5121 8823 5176 8823 5176 8824 5121 8824 5120 8824 4720 8825 4723 8825 5122 8825 5177 8826 5178 8826 4716 8826 4716 8827 5178 8827 4714 8827 5177 8828 4716 8828 5179 8828 5179 8829 4716 8829 4718 8829 5179 8830 4718 8830 5180 8830 5178 8831 5175 8831 4714 8831 4714 8832 5175 8832 5176 8832 4714 632 5176 632 4707 632 4707 8833 5176 8833 5120 8833 4707 8834 5120 8834 4708 8834 4720 8835 5122 8835 4718 8835 4718 8836 5122 8836 5181 8836 4718 8837 5181 8837 5180 8837 5180 8838 5181 8838 5182 8838 5182 8839 5181 8839 5122 8839 5182 8840 5122 8840 5123 8840 4748 8841 4747 8841 5183 8841 4816 8842 5124 8842 5184 8842 4748 8843 5183 8843 4750 8843 4750 8844 5183 8844 5185 8844 4750 8845 5185 8845 4751 8845 4753 8846 4751 8846 5123 8846 5123 8847 4751 8847 5185 8847 5123 8848 5185 8848 5186 8848 5186 8849 5185 8849 5183 8849 5186 8850 5183 8850 5187 8850 5187 8851 5183 8851 4747 8851 5187 8852 4747 8852 5184 8852 5184 8853 4747 8853 4756 8853 5184 8854 4756 8854 4816 8854 4758 8855 4757 8855 5124 8855 5124 8856 4757 8856 4590 8856 5124 8857 4590 8857 4591 8857 4664 8858 4689 8858 4662 8858 4662 8859 4689 8859 5136 8859 5137 8860 4582 8860 5138 8860 5138 8861 4582 8861 4655 8861 5138 8862 4655 8862 5140 8862 5140 8863 4655 8863 4656 8863 5140 8864 4656 8864 5141 8864 5141 8865 4656 8865 4658 8865 5141 8866 4658 8866 5136 8866 5136 8867 4658 8867 4660 8867 5136 8868 4660 8868 4662 8868 5126 8869 5132 8869 5139 8869 5139 8870 5132 8870 5137 8870 5137 8871 5132 8871 5147 8871 5137 8872 5147 8872 5146 8872 5146 8873 5145 8873 5137 8873 5137 8874 5145 8874 5144 8874 5144 8875 5151 8875 5137 8875 5137 8876 5151 8876 5149 8876 5137 8877 5149 8877 5148 8877 5006 8878 4877 8878 5139 8878 5139 8879 4877 8879 5127 8879 5139 8880 5127 8880 5126 8880 5148 8881 4793 8881 4792 8881 4792 8882 5142 8882 5148 8882 5148 8883 5142 8883 5143 8883 5148 8884 5143 8884 5188 8884 5188 8885 5143 8885 5171 8885 5189 8886 5190 8886 5191 8886 5173 8887 5174 8887 5189 8887 5189 8888 5174 8888 5121 8888 5189 8889 5121 8889 5175 8889 5189 8890 5191 8890 5173 8890 5173 8891 5191 8891 5192 8891 5173 8892 5192 8892 5171 8892 5171 8893 5192 8893 4667 8893 5171 8894 4667 8894 5188 8894 5193 8895 5189 8895 5175 8895 5175 8896 5178 8896 5193 8896 5193 8897 5178 8897 5177 8897 5193 8898 5177 8898 5194 8898 5194 8899 5177 8899 5179 8899 5194 8900 5179 8900 5195 8900 5195 8901 5179 8901 5180 8901 5195 8902 5180 8902 5196 8902 5182 8903 5196 8903 5180 8903 4591 8904 4589 8904 5197 8904 5124 8905 4591 8905 5184 8905 5184 8906 4591 8906 5197 8906 5184 8907 5197 8907 5187 8907 5187 8908 5197 8908 5198 8908 5187 8909 5198 8909 5186 8909 5182 8910 5123 8910 5196 8910 5196 8911 5123 8911 5186 8911 5196 8912 5186 8912 5199 8912 5199 8913 5186 8913 5198 8913 5188 8914 4667 8914 5148 8914 5148 106 4667 106 4582 106 5148 106 4582 106 5137 106 5200 8915 5201 8915 5202 8915 5202 8916 5201 8916 5203 8916 5202 8917 5203 8917 5204 8917 5204 8918 5203 8918 5205 8918 5204 8919 5205 8919 5206 8919 5206 8920 5205 8920 5207 8920 5206 8921 5207 8921 5208 8921 5208 8922 5207 8922 5209 8922 5208 8923 5209 8923 5210 8923 5210 8924 5209 8924 5211 8924 5210 8925 5211 8925 5212 8925 5212 8926 5211 8926 4603 8926 5212 8927 4603 8927 4605 8927 4589 8928 4585 8928 5213 8928 5213 8929 5214 8929 4589 8929 4589 8930 5214 8930 5215 8930 4589 8931 5215 8931 5216 8931 5200 8932 5202 8932 5216 8932 5216 8933 5202 8933 5217 8933 5216 8934 5217 8934 4589 8934 4605 8935 4606 8935 5218 8935 5208 8936 5210 8936 5218 8936 5218 8937 5210 8937 5212 8937 5218 8938 5212 8938 4605 8938 5219 8939 5204 8939 5206 8939 5219 8940 5206 8940 5220 8940 5204 8941 5219 8941 5202 8941 5202 8942 5219 8942 5221 8942 5202 8943 5221 8943 5217 8943 5217 8944 5221 8944 5197 8944 5217 8945 5197 8945 4589 8945 5222 8946 5199 8946 5198 8946 5223 8947 4597 8947 4602 8947 5198 8948 5224 8948 5222 8948 5222 8949 5224 8949 5225 8949 5222 8950 5225 8950 5226 8950 5226 8951 5225 8951 5223 8951 5226 8952 5223 8952 5227 8952 5227 8953 5223 8953 4602 8953 5227 8954 4602 8954 4601 8954 4606 8955 4598 8955 5218 8955 5218 8956 4598 8956 5220 8956 5218 8957 5220 8957 5208 8957 5208 8958 5220 8958 5206 8958 4598 8959 4597 8959 5220 8959 5220 8960 4597 8960 5223 8960 5220 8961 5223 8961 5219 8961 5219 8962 5223 8962 5225 8962 5219 8963 5225 8963 5221 8963 5221 8964 5225 8964 5224 8964 5221 8965 5224 8965 5197 8965 5197 8966 5224 8966 5198 8966 5227 632 4601 632 4594 632 5195 632 5196 632 5199 632 5190 632 5189 632 5193 632 4622 632 5228 632 4620 632 4620 632 5228 632 5229 632 4620 632 5229 632 4594 632 5193 8967 5194 8967 5190 8967 5190 632 5194 632 4594 632 5190 8968 4594 8968 5230 8968 5230 632 4594 632 5229 632 5195 632 5199 632 5194 632 5194 8969 5199 8969 5222 8969 5194 8970 5222 8970 4594 8970 4594 632 5222 632 5226 632 4594 632 5226 632 5227 632 5228 8971 5231 8971 5232 8971 4685 8972 4682 8972 5233 8972 5192 8973 5234 8973 4667 8973 4667 8974 5234 8974 4674 8974 5233 8975 4682 8975 5235 8975 4682 8976 4680 8976 5235 8976 5235 8977 4680 8977 4678 8977 5235 8978 4678 8978 5234 8978 5234 8979 4678 8979 4672 8979 5234 8980 4672 8980 4674 8980 5236 8981 4684 8981 4685 8981 4615 8982 4684 8982 4616 8982 4616 8983 4684 8983 5236 8983 4616 8984 5236 8984 4618 8984 4685 8985 5233 8985 5236 8985 5236 8986 5233 8986 4619 8986 5236 8987 4619 8987 4618 8987 5228 8988 5232 8988 5229 8988 5229 8989 5232 8989 5237 8989 5229 8990 5237 8990 5230 8990 5230 8991 5237 8991 5191 8991 5230 8992 5191 8992 5190 8992 5192 8993 5191 8993 5234 8993 5234 8994 5191 8994 5237 8994 5234 8995 5237 8995 5235 8995 5235 8996 5237 8996 5232 8996 5235 8997 5232 8997 5233 8997 5233 8998 5232 8998 5231 8998 5233 8999 5231 8999 4619 8999 4619 9000 5231 9000 5228 9000 4619 9001 5228 9001 4622 9001 5238 9002 5239 9002 5240 9002 4612 9003 4611 9003 5241 9003 5241 9004 4611 9004 4610 9004 5241 9005 4610 9005 5242 9005 5241 9006 5243 9006 4612 9006 4612 9007 5243 9007 5244 9007 4612 9008 5244 9008 4621 9008 4621 9009 5244 9009 5245 9009 4621 9010 5245 9010 4623 9010 4623 9011 5245 9011 5246 9011 5247 9012 5248 9012 5249 9012 5250 9013 5251 9013 5252 9013 5248 9014 5247 9014 5252 9014 5252 9015 5247 9015 5253 9015 5252 9016 5253 9016 5250 9016 5254 9017 5255 9017 5256 9017 5256 9018 5255 9018 5257 9018 5257 9019 5258 9019 5256 9019 5256 9020 5258 9020 5259 9020 5256 9021 5259 9021 5250 9021 5250 9022 5259 9022 5260 9022 5250 9023 5260 9023 5251 9023 5239 9024 5261 9024 5240 9024 5240 9025 5261 9025 5262 9025 5240 9026 5262 9026 5263 9026 5263 9027 5262 9027 5264 9027 5261 9028 5265 9028 5262 9028 5262 9029 5265 9029 5266 9029 5262 9030 5266 9030 5264 9030 5264 9031 5266 9031 5267 9031 5268 9032 5254 9032 5269 9032 5269 9033 5254 9033 5256 9033 5269 9034 5256 9034 5270 9034 5270 9035 5256 9035 5250 9035 5270 9036 5250 9036 5267 9036 5267 9037 5250 9037 5253 9037 5267 9038 5253 9038 5264 9038 5264 9039 5253 9039 5247 9039 5264 9040 5247 9040 5263 9040 5263 9041 5247 9041 5249 9041 5263 9042 5249 9042 5240 9042 5240 9043 5249 9043 5271 9043 5240 9044 5271 9044 5238 9044 5265 9045 5246 9045 5266 9045 5266 9046 5246 9046 5245 9046 5266 9047 5245 9047 5267 9047 5267 9048 5245 9048 5244 9048 5267 9049 5244 9049 5270 9049 5270 9050 5244 9050 5243 9050 5270 9051 5243 9051 5269 9051 5269 9052 5243 9052 5241 9052 5269 9053 5241 9053 5268 9053 5268 9054 5241 9054 5242 9054 5257 9055 5255 9055 5272 9055 5272 9056 5255 9056 5273 9056 4610 9057 4608 9057 5242 9057 5242 9058 4608 9058 5274 9058 5242 9059 5274 9059 5268 9059 5268 9060 5274 9060 5273 9060 5268 9061 5273 9061 5254 9061 5254 9062 5273 9062 5255 9062 5275 9063 4607 9063 4609 9063 4609 9064 5276 9064 5275 9064 5275 9065 5276 9065 5277 9065 5275 9066 5277 9066 5278 9066 5278 9067 5277 9067 5279 9067 5278 9068 5279 9068 5280 9068 5280 9069 5279 9069 5281 9069 5280 9070 5281 9070 5282 9070 4613 9071 4596 9071 5283 9071 4595 9072 5284 9072 4596 9072 5284 9073 4595 9073 4593 9073 4600 9074 5285 9074 5286 9074 5276 9075 4609 9075 5283 9075 5283 9076 4609 9076 4614 9076 5283 9077 4614 9077 4613 9077 5282 9078 5281 9078 5287 9078 5287 9079 5281 9079 5288 9079 5289 9080 5290 9080 5291 9080 5291 9081 5290 9081 5292 9081 5291 9082 5292 9082 5293 9082 5293 9083 5292 9083 5294 9083 5293 9084 5294 9084 5288 9084 5288 9085 5294 9085 5295 9085 5288 9086 5295 9086 5287 9086 5296 9087 5297 9087 5298 9087 5298 9088 5297 9088 5299 9088 5298 9089 5299 9089 5300 9089 5301 9090 5300 9090 5302 9090 5302 9091 5300 9091 5299 9091 5302 9092 5299 9092 5303 9092 4592 9093 4600 9093 4593 9093 4593 9094 4600 9094 5286 9094 4593 9095 5286 9095 5284 9095 5284 9096 5286 9096 5304 9096 5284 9097 5304 9097 4596 9097 4596 9098 5304 9098 5305 9098 4596 9099 5305 9099 5283 9099 5283 9100 5305 9100 5306 9100 5283 9101 5306 9101 5276 9101 5276 9102 5306 9102 5277 9102 5285 9103 5301 9103 5286 9103 5286 9104 5301 9104 5302 9104 5286 9105 5302 9105 5304 9105 5304 9106 5302 9106 5303 9106 5304 9107 5303 9107 5305 9107 5305 9108 5303 9108 5307 9108 5305 9109 5307 9109 5306 9109 5306 9110 5307 9110 5308 9110 5306 9111 5308 9111 5277 9111 5277 9112 5308 9112 5279 9112 5297 9113 5290 9113 5299 9113 5299 9114 5290 9114 5289 9114 5299 9115 5289 9115 5303 9115 5303 9116 5289 9116 5291 9116 5303 9117 5291 9117 5307 9117 5307 9118 5291 9118 5293 9118 5307 9119 5293 9119 5308 9119 5308 9120 5293 9120 5288 9120 5308 9121 5288 9121 5279 9121 5279 9122 5288 9122 5281 9122 5309 9123 5310 9123 5301 9123 5311 9124 5312 9124 5313 9124 5311 9125 5313 9125 5314 9125 5301 9126 5310 9126 5300 9126 5310 9127 5315 9127 5300 9127 5300 9128 5315 9128 5314 9128 5300 9129 5314 9129 5298 9129 5298 9130 5314 9130 5313 9130 5298 9131 5313 9131 5296 9131 5285 9132 4600 9132 4599 9132 4599 9133 5316 9133 5285 9133 5285 9134 5316 9134 5317 9134 5285 9135 5317 9135 5301 9135 5301 9136 5317 9136 5318 9136 5301 9137 5318 9137 5309 9137 5319 9138 5320 9138 5321 9138 5322 9139 5323 9139 5324 9139 5325 9140 5326 9140 5327 9140 5328 9141 5329 9141 5330 9141 5331 9142 5332 9142 5333 9142 5333 9143 5332 9143 5334 9143 5335 9144 5336 9144 5337 9144 5337 9145 5336 9145 5338 9145 5337 9146 5338 9146 5339 9146 5339 9147 5338 9147 5340 9147 5339 9148 5340 9148 5341 9148 5341 9149 5340 9149 5334 9149 5341 9150 5334 9150 5342 9150 5342 9151 5334 9151 5332 9151 5343 9152 5336 9152 5344 9152 5344 9153 5336 9153 5335 9153 5344 9154 5335 9154 5345 9154 5346 9155 4630 9155 5347 9155 5347 9156 5348 9156 5346 9156 5346 9157 5348 9157 5349 9157 5346 9158 5349 9158 5350 9158 5350 9159 5349 9159 5351 9159 5351 9160 5349 9160 5352 9160 5351 9161 5352 9161 5353 9161 5353 9162 5352 9162 5354 9162 5354 9163 5352 9163 5355 9163 5354 9164 5355 9164 5356 9164 5328 9165 5330 9165 5357 9165 5357 9166 5330 9166 5358 9166 5357 9167 5358 9167 5326 9167 5326 9168 5358 9168 5359 9168 5326 9169 5359 9169 5327 9169 5360 9170 235 9170 5361 9170 5362 9171 5363 9171 5359 9171 5359 9172 5363 9172 5360 9172 5359 9173 5360 9173 5327 9173 5327 9174 5360 9174 5361 9174 5327 9175 5361 9175 5325 9175 5323 9176 5362 9176 5324 9176 5324 9177 5362 9177 5359 9177 5324 9178 5359 9178 5364 9178 5364 9179 5359 9179 5358 9179 5364 9180 5358 9180 5355 9180 5355 9181 5358 9181 5330 9181 5355 9182 5330 9182 5356 9182 5356 9183 5330 9183 5329 9183 5320 9184 5345 9184 5321 9184 5321 9185 5345 9185 5335 9185 5321 9186 5335 9186 5365 9186 5365 9187 5335 9187 5337 9187 5365 9188 5337 9188 5366 9188 5366 9189 5337 9189 5339 9189 5366 9190 5339 9190 5367 9190 5367 9191 5339 9191 5341 9191 5367 9192 5341 9192 5368 9192 5368 9193 5341 9193 5342 9193 5368 9194 5342 9194 5369 9194 5369 9195 5342 9195 5332 9195 5369 9196 5332 9196 5370 9196 5370 9197 5332 9197 5331 9197 5347 9198 5319 9198 5348 9198 5348 9199 5319 9199 5321 9199 5348 9200 5321 9200 5349 9200 5349 9201 5321 9201 5365 9201 5349 9202 5365 9202 5352 9202 5352 9203 5365 9203 5366 9203 5352 9204 5366 9204 5355 9204 5355 9205 5366 9205 5367 9205 5355 9206 5367 9206 5364 9206 5364 9207 5367 9207 5368 9207 5364 9208 5368 9208 5324 9208 5324 9209 5368 9209 5369 9209 5324 9210 5369 9210 5322 9210 5322 9211 5369 9211 5370 9211 5371 9212 5372 9212 5373 9212 5374 9213 5375 9213 5376 9213 5377 9214 5378 9214 5379 9214 5380 9215 5381 9215 5382 9215 5383 9216 5384 9216 5385 9216 5381 9217 5380 9217 5386 9217 5387 9218 5388 9218 5389 9218 5390 9219 5391 9219 5392 9219 5393 9220 5394 9220 5395 9220 5395 9221 5396 9221 5393 9221 5393 9222 5396 9222 5392 9222 5393 9223 5392 9223 5397 9223 5397 9224 5392 9224 5391 9224 5398 9225 5399 9225 5400 9225 5400 9226 5399 9226 5373 9226 5400 9227 5373 9227 5401 9227 5401 9228 5373 9228 5372 9228 5401 9229 5372 9229 5402 9229 5402 9230 5372 9230 5371 9230 5402 9231 5371 9231 4638 9231 5403 9232 5404 9232 5387 9232 5387 9233 5404 9233 5405 9233 5387 9234 5405 9234 5388 9234 5388 9235 5405 9235 5406 9235 5388 9236 5406 9236 5407 9236 5407 9237 5406 9237 5408 9237 5407 9238 5408 9238 5409 9238 5409 9239 5408 9239 5410 9239 5411 9240 123 9240 5412 9240 5412 9241 123 9241 5413 9241 5412 9242 5413 9242 5414 9242 5414 9243 5383 9243 5412 9243 5412 9244 5383 9244 5385 9244 5412 9245 5385 9245 5415 9245 5415 9246 5385 9246 5416 9246 5384 9247 5386 9247 5385 9247 5385 9248 5386 9248 5380 9248 5385 9249 5380 9249 5416 9249 5416 9250 5380 9250 5382 9250 5416 9251 5382 9251 5417 9251 5417 9252 5418 9252 5419 9252 5411 9253 5412 9253 5420 9253 5420 9254 5412 9254 5415 9254 5420 9255 5415 9255 5394 9255 5394 9256 5415 9256 5416 9256 5394 9257 5416 9257 5395 9257 5395 9258 5416 9258 5417 9258 5395 9259 5417 9259 5396 9259 5396 9260 5417 9260 5419 9260 5396 9261 5419 9261 5392 9261 5421 9262 5422 9262 5423 9262 5398 9263 5410 9263 5423 9263 5423 9264 5410 9264 5408 9264 5423 9265 5408 9265 5421 9265 5421 9266 5408 9266 5406 9266 5421 9267 5406 9267 5418 9267 5418 9268 5406 9268 5405 9268 5418 9269 5405 9269 5419 9269 5419 9270 5405 9270 5404 9270 5419 9271 5404 9271 5392 9271 5392 9272 5404 9272 5403 9272 5392 9273 5403 9273 5390 9273 5378 9274 5374 9274 5379 9274 5379 9275 5374 9275 5376 9275 5379 9276 5376 9276 5424 9276 5424 9277 5376 9277 5425 9277 5424 9278 5425 9278 5426 9278 5426 9279 5425 9279 5427 9279 5426 9280 5427 9280 5428 9280 5428 9281 5427 9281 5429 9281 5428 9282 5429 9282 5430 9282 5430 9283 5429 9283 5431 9283 5430 9284 5431 9284 5432 9284 5432 9285 5431 9285 5433 9285 5398 9286 5423 9286 5399 9286 5399 9287 5423 9287 5422 9287 5399 9288 5422 9288 5373 9288 5373 9289 5422 9289 5434 9289 5373 9290 5434 9290 5371 9290 5381 9291 5377 9291 5382 9291 5382 9292 5377 9292 5379 9292 5382 9293 5379 9293 5417 9293 5417 9294 5379 9294 5424 9294 5417 9295 5424 9295 5418 9295 5418 9296 5424 9296 5426 9296 5418 9297 5426 9297 5421 9297 5421 9298 5426 9298 5428 9298 5421 9299 5428 9299 5422 9299 5422 9300 5428 9300 5430 9300 5422 9301 5430 9301 5434 9301 5434 9302 5430 9302 5432 9302 5434 9303 5432 9303 5371 9303 5371 9304 5432 9304 5435 9304 5433 9305 5436 9305 5432 9305 5432 9306 5436 9306 5437 9306 5432 9307 5437 9307 5435 9307 5438 9308 5439 9308 5440 9308 5441 9309 5442 9309 5443 9309 5443 9310 5442 9310 5444 9310 5443 9311 5444 9311 5445 9311 5443 9312 5446 9312 5441 9312 5441 9313 5446 9313 5447 9313 5441 9314 5447 9314 5333 9314 5333 9315 5447 9315 5331 9315 5448 9316 242 9316 247 9316 5449 9317 5450 9317 5438 9317 5449 9318 5362 9318 5323 9318 5450 9319 5449 9319 5451 9319 5451 9320 5449 9320 5323 9320 5451 9321 5323 9321 5322 9321 237 9322 5452 9322 247 9322 247 9323 5452 9323 5453 9323 247 9324 5453 9324 5448 9324 5448 9325 5453 9325 5454 9325 5448 9326 5454 9326 5455 9326 5455 9327 5454 9327 5456 9327 5455 9328 5456 9328 5457 9328 5445 9329 5458 9329 5443 9329 5443 9330 5458 9330 5459 9330 5443 9331 5459 9331 5446 9331 5446 9332 5459 9332 5460 9332 5446 9333 5460 9333 5447 9333 5447 9334 5460 9334 5370 9334 5447 9335 5370 9335 5331 9335 4521 9336 5440 9336 5445 9336 5445 9337 5440 9337 5439 9337 5445 9338 5439 9338 5458 9338 5458 9339 5439 9339 5438 9339 5458 9340 5438 9340 5459 9340 5459 9341 5438 9341 5450 9341 5459 9342 5450 9342 5460 9342 5460 9343 5450 9343 5451 9343 5460 9344 5451 9344 5370 9344 5370 9345 5451 9345 5322 9345 5362 9346 5449 9346 5363 9346 5363 9347 5449 9347 5461 9347 5363 9348 5461 9348 5360 9348 5360 9349 5461 9349 5462 9349 5360 9350 5462 9350 235 9350 237 9351 235 9351 5452 9351 5452 9352 235 9352 5462 9352 5452 9353 5462 9353 5453 9353 5453 9354 5462 9354 5461 9354 5453 9355 5461 9355 5454 9355 5454 9356 5461 9356 5449 9356 5454 9357 5449 9357 5456 9357 5456 9358 5449 9358 5438 9358 5456 9359 5438 9359 5457 9359 5457 9360 5438 9360 5440 9360 5328 9361 5357 9361 5463 9361 5463 9362 5357 9362 5464 9362 5464 9363 5357 9363 5326 9363 5464 9364 5326 9364 5465 9364 5465 9365 5326 9365 5325 9365 5465 9366 5325 9366 234 9366 234 9367 5325 9367 5361 9367 234 9368 5361 9368 235 9368 5350 9369 5351 9369 5466 9369 5351 9370 5353 9370 5466 9370 5466 9371 5353 9371 5354 9371 5466 9372 5354 9372 5467 9372 5467 9373 5354 9373 5356 9373 5467 9374 5356 9374 5463 9374 5463 9375 5356 9375 5329 9375 5463 9376 5329 9376 5328 9376 5466 9377 5468 9377 5350 9377 5350 9378 5468 9378 5469 9378 5350 9379 5469 9379 5346 9379 4631 9380 4630 9380 5470 9380 5470 9381 4630 9381 5346 9381 5470 9382 5346 9382 5471 9382 5471 9383 5346 9383 5469 9383 5402 9384 4638 9384 4637 9384 5402 9385 4637 9385 5401 9385 5410 9386 5398 9386 5472 9386 4637 9387 5473 9387 5401 9387 5401 9388 5473 9388 5472 9388 5401 9389 5472 9389 5400 9389 5400 9390 5472 9390 5398 9390 5474 9391 5389 9391 5388 9391 5472 9392 5475 9392 5410 9392 5410 9393 5475 9393 5476 9393 5410 9394 5476 9394 5409 9394 5409 9395 5476 9395 5474 9395 5409 9396 5474 9396 5407 9396 5407 9397 5474 9397 5388 9397 5391 9398 5390 9398 5477 9398 5477 9399 5390 9399 5403 9399 5477 9400 5403 9400 5387 9400 5389 9401 5474 9401 5387 9401 5387 9402 5474 9402 5478 9402 5387 9403 5478 9403 5477 9403 5479 9404 5420 9404 5394 9404 5479 9405 5394 9405 5480 9405 5480 9406 5394 9406 5393 9406 5480 9407 5393 9407 5477 9407 5477 9408 5393 9408 5397 9408 5477 9409 5397 9409 5391 9409 5420 9410 5479 9410 5411 9410 5411 9411 5479 9411 122 9411 5411 9412 122 9412 123 9412 5414 9413 5413 9413 5481 9413 5482 9414 5483 9414 5484 9414 5483 9415 5482 9415 5485 9415 114 9416 5486 9416 123 9416 113 9417 5487 9417 5488 9417 5489 9418 5490 9418 5491 9418 113 9419 5488 9419 114 9419 114 9420 5488 9420 5481 9420 114 9421 5481 9421 5486 9421 5486 9422 5481 9422 5413 9422 5486 9423 5413 9423 123 9423 5492 9424 4513 9424 5493 9424 5493 9425 4513 9425 5494 9425 5493 9426 5494 9426 5495 9426 5495 9427 5494 9427 5496 9427 5495 9428 5496 9428 5497 9428 5497 9429 5498 9429 5495 9429 5495 9430 5498 9430 5499 9430 5495 9431 5499 9431 5493 9431 5493 9432 5499 9432 5484 9432 5493 9433 5484 9433 5492 9433 5492 9434 5484 9434 5483 9434 5487 9435 5491 9435 5488 9435 5488 9436 5491 9436 5490 9436 5488 9437 5490 9437 5481 9437 5481 9438 5490 9438 5383 9438 5481 9439 5383 9439 5414 9439 5374 9440 5378 9440 5500 9440 5500 9441 5378 9441 5377 9441 5500 9442 5377 9442 5501 9442 5501 9443 5377 9443 5381 9443 5501 9444 5381 9444 5489 9444 5489 9445 5381 9445 5386 9445 5489 9446 5386 9446 5490 9446 5490 9447 5386 9447 5384 9447 5490 9448 5384 9448 5383 9448 5375 9449 5374 9449 5502 9449 5502 9450 5374 9450 5500 9450 5502 9451 5500 9451 5503 9451 5503 9452 5500 9452 5501 9452 5503 9453 5501 9453 5504 9453 5504 9454 5501 9454 5489 9454 5487 9455 5485 9455 5491 9455 5491 9456 5485 9456 5482 9456 5491 9457 5482 9457 5489 9457 5489 9458 5482 9458 5484 9458 5489 9459 5484 9459 5504 9459 5504 9460 5484 9460 5499 9460 5504 9461 5499 9461 5503 9461 5503 9462 5499 9462 5498 9462 5503 9463 5498 9463 5502 9463 5502 9464 5498 9464 5497 9464 5502 9465 5497 9465 5375 9465 5505 9466 4514 9466 4513 9466 5487 9467 113 9467 119 9467 119 9468 5506 9468 5487 9468 5487 9469 5506 9469 5507 9469 5487 9469 5507 9469 5485 9469 5485 9470 5507 9470 5508 9470 5485 9471 5508 9471 5483 9471 4513 9472 5492 9472 5505 9472 5505 9473 5492 9473 5483 9473 5505 9474 5483 9474 5509 9474 5509 9475 5483 9475 5508 9475 5510 9476 231 9476 242 9476 5440 9477 4521 9477 4520 9477 4520 9478 5511 9478 5440 9478 5440 9479 5511 9479 5512 9479 5440 9480 5512 9480 5457 9480 5512 9481 5513 9481 5457 9481 5457 9482 5513 9482 5514 9482 5457 9483 5514 9483 5455 9483 242 9484 5448 9484 5510 9484 5510 9485 5448 9485 5455 9485 5510 9486 5455 9486 5515 9486 5515 9487 5455 9487 5514 9487 4704 9488 4731 9488 4728 9488 4704 9489 4728 9489 4696 9489 4696 9490 4728 9490 4725 9490 4696 9491 4725 9491 4697 9491 4697 9492 4725 9492 4724 9492 4697 9493 4724 9493 4703 9493 4703 9494 4724 9494 4719 9494 4703 9495 4719 9495 4702 9495 4702 9496 4719 9496 4717 9496 4702 9497 4717 9497 4700 9497 4700 9498 4717 9498 4715 9498 4700 9499 4715 9499 4701 9499 4701 9500 4715 9500 4713 9500 4701 9501 4713 9501 4695 9501 4695 9502 4713 9502 4712 9502 4695 9503 4712 9503 4698 9503 4698 9504 4712 9504 4709 9504 4698 9505 4709 9505 4699 9505 4699 9506 4709 9506 4737 9506 4699 9507 4737 9507 4706 9507 4706 9508 4737 9508 4734 9508 4706 9509 4734 9509 4705 9509 4705 9510 4734 9510 4731 9510 4705 9511 4731 9511 4704 9511 4586 9512 4652 9512 4584 9512 4584 9513 4652 9513 4651 9513 4584 9514 4651 9514 5516 9514 4643 9515 4690 9515 4644 9515 4644 9516 4690 9516 5517 9516 4644 9517 5517 9517 5518 9517 4651 9518 4650 9518 5516 9518 5516 9519 4650 9519 4648 9519 5516 9520 4648 9520 5518 9520 5518 9521 4648 9521 4646 9521 5518 9522 4646 9522 4644 9522 1451 9523 4584 9523 1457 9523 1457 9524 4584 9524 5516 9524 1457 9525 5516 9525 1458 9525 1458 9526 5516 9526 5518 9526 1458 9527 5518 9527 1443 9527 1443 9528 5518 9528 5517 9528 1443 9529 5517 9529 1444 9529 1444 9530 5517 9530 1445 9530 1445 9531 5517 9531 4690 9531 1445 9532 4690 9532 1446 9532 4686 9533 4663 9533 4665 9533 5519 9534 5520 9534 4659 9534 4659 9535 4657 9535 5519 9535 5519 9536 4657 9536 4654 9536 5519 9537 4654 9537 4583 9537 4583 9538 4654 9538 4653 9538 4583 9539 4653 9539 4581 9539 4686 9540 4665 9540 5521 9540 5521 9541 4665 9541 4666 9541 5521 9542 4666 9542 5520 9542 5520 9543 4666 9543 4661 9543 5520 9544 4661 9544 4659 9544 1448 9545 4686 9545 5521 9545 1448 9546 5521 9546 1449 9546 1449 9547 5521 9547 5520 9547 1449 9548 5520 9548 1439 9548 1439 9549 5520 9549 5519 9549 1439 9550 5519 9550 1440 9550 1440 9551 5519 9551 4583 9551 1440 9552 4583 9552 1435 9552 5522 9553 5523 9553 1455 9553 5524 9554 4585 9554 1451 9554 1455 9555 5523 9555 1451 9555 1451 9556 5523 9556 5525 9556 1451 9557 5525 9557 5524 9557 1454 9558 5526 9558 1455 9558 1455 9559 5526 9559 5527 9559 1455 9560 5527 9560 5522 9560 1453 9561 5528 9561 1454 9561 1454 9562 5528 9562 5529 9562 1454 9563 5529 9563 5526 9563 5530 9564 5531 9564 1434 9564 1434 9565 5531 9565 5532 9565 1434 9566 5532 9566 1436 9566 5530 9567 1434 9567 5533 9567 5533 9568 1434 9568 1433 9568 5533 9569 1433 9569 5534 9569 4582 9570 5535 9570 1435 9570 1435 9571 5535 9571 5536 9571 1435 9572 5536 9572 1433 9572 1433 9573 5536 9573 5537 9573 1433 9574 5537 9574 5534 9574 5538 9575 5539 9575 5540 9575 5528 9576 1453 9576 1456 9576 5524 9577 5525 9577 5541 9577 5541 9578 5525 9578 5523 9578 5541 9579 5523 9579 5542 9579 5542 9580 5523 9580 5522 9580 5542 9581 5522 9581 5543 9581 4585 9582 5524 9582 5213 9582 5213 9583 5524 9583 5541 9583 5213 9584 5541 9584 5544 9584 5544 9585 5541 9585 5542 9585 5544 9586 5542 9586 5545 9586 5545 9587 5542 9587 5543 9587 5545 9588 5543 9588 5546 9588 5546 9589 5215 9589 5545 9589 5545 9590 5215 9590 5214 9590 5545 9591 5214 9591 5544 9591 5544 9592 5214 9592 5213 9592 5201 9593 5200 9593 5546 9593 5546 9594 5200 9594 5216 9594 5546 9595 5216 9595 5215 9595 1456 9596 5547 9596 5528 9596 5528 9597 5547 9597 5548 9597 5528 9598 5548 9598 5529 9598 5529 9599 5548 9599 5540 9599 5529 9600 5540 9600 5526 9600 5526 9601 5540 9601 5539 9601 5526 9602 5539 9602 5527 9602 5538 9603 5540 9603 5549 9603 5549 9604 5540 9604 5548 9604 5549 9605 5548 9605 5550 9605 5550 9606 5548 9606 5547 9606 5550 9607 5547 9607 5551 9607 1456 9608 5552 9608 5547 9608 5547 9609 5552 9609 5553 9609 5547 9610 5553 9610 5551 9610 5551 9611 5553 9611 5554 9611 5551 9612 5554 9612 5555 9612 5522 9613 5527 9613 5543 9613 5543 9614 5527 9614 5539 9614 5543 9615 5539 9615 5546 9615 5546 9616 5539 9616 5538 9616 5546 9617 5538 9617 5201 9617 5201 9618 5538 9618 5549 9618 5201 9619 5549 9619 5203 9619 5203 9620 5549 9620 5550 9620 5203 9621 5550 9621 5205 9621 5205 9622 5550 9622 5551 9622 5205 9623 5551 9623 5207 9623 5207 9624 5551 9624 5555 9624 5207 9625 5555 9625 5209 9625 5552 9626 1456 9626 1450 9626 770 9627 768 9627 5556 9627 770 9628 5556 9628 771 9628 5557 9629 1450 9629 1452 9629 5557 9630 5554 9630 1450 9630 1450 9631 5554 9631 5553 9631 1450 9632 5553 9632 5552 9632 5211 9633 5209 9633 5557 9633 5557 9634 5209 9634 5555 9634 5557 9635 5555 9635 5554 9635 1452 9636 771 9636 5557 9636 5557 9637 771 9637 5556 9637 5557 9638 5556 9638 5211 9638 5211 9639 5556 9639 4603 9639 5558 9640 5559 9640 5560 9640 5561 9641 5562 9641 5563 9641 5563 9642 5562 9642 1437 9642 4668 9643 4669 9643 5564 9643 5564 9644 4669 9644 4676 9644 5564 9645 4676 9645 5565 9645 5565 9646 4676 9646 4675 9646 5565 9647 4675 9647 5566 9647 5566 9648 4675 9648 4673 9648 5566 9649 4673 9649 5567 9649 5535 9650 5568 9650 5536 9650 5536 9651 5568 9651 5569 9651 5536 9652 5569 9652 5537 9652 5537 9653 5569 9653 5570 9653 5537 9654 5570 9654 5534 9654 5534 9655 5570 9655 5571 9655 5534 9656 5571 9656 5533 9656 5533 9657 5571 9657 5572 9657 5533 9658 5572 9658 5530 9658 5530 9659 5572 9659 5573 9659 5530 9660 5573 9660 5531 9660 5531 9661 5573 9661 5563 9661 5531 9662 5563 9662 5532 9662 5532 9663 5563 9663 1437 9663 5532 9664 1437 9664 1436 9664 4673 9665 4671 9665 5567 9665 5567 9666 4671 9666 4670 9666 5567 9667 4670 9667 5574 9667 5574 9668 4670 9668 4677 9668 5574 9669 4677 9669 5575 9669 5575 9670 4677 9670 4679 9670 5575 9671 4679 9671 5560 9671 5560 9672 4679 9672 4681 9672 5560 9673 4681 9673 5558 9673 4582 9674 4668 9674 5535 9674 5535 9675 4668 9675 5564 9675 5535 9676 5564 9676 5568 9676 5568 9677 5564 9677 5565 9677 5568 9678 5565 9678 5569 9678 5569 9679 5565 9679 5566 9679 5569 9680 5566 9680 5570 9680 5570 9681 5566 9681 5567 9681 5570 9682 5567 9682 5571 9682 5571 9683 5567 9683 5574 9683 5571 9684 5574 9684 5572 9684 5572 9685 5574 9685 5575 9685 5572 9686 5575 9686 5573 9686 5573 9687 5575 9687 5560 9687 5573 9688 5560 9688 5563 9688 5563 9689 5560 9689 5559 9689 5563 9690 5559 9690 5561 9690 116 9691 118 9691 5576 9691 5576 9692 118 9692 5577 9692 5578 9693 5579 9693 5580 9693 5580 9694 5579 9694 5581 9694 5580 9695 5581 9695 5577 9695 5577 9696 5581 9696 5582 9696 5577 9697 5582 9697 5576 9697 5583 9698 5584 9698 5578 9698 5578 9699 5584 9699 5585 9699 5578 9700 5585 9700 5586 9700 5587 9701 5579 9701 5588 9701 5588 9702 5579 9702 5578 9702 5588 9703 5578 9703 5589 9703 5589 9704 5578 9704 5586 9704 5579 9705 5590 9705 5581 9705 5581 9706 5590 9706 5591 9706 5581 9707 5591 9707 5582 9707 5582 9708 5591 9708 5576 9708 5592 9709 5593 9709 5591 9709 5591 9710 5593 9710 5594 9710 5591 9711 5594 9711 5595 9711 116 9712 5576 9712 131 9712 131 9713 5576 9713 5591 9713 131 9714 5591 9714 5596 9714 5596 9715 5591 9715 5595 9715 5597 9716 5598 9716 5590 9716 5590 9717 5598 9717 5599 9717 5590 9718 5599 9718 5591 9718 5591 9719 5599 9719 5600 9719 5591 9720 5600 9720 5592 9720 5601 9721 130 9721 5602 9721 5602 9722 130 9722 131 9722 5602 9723 5603 9723 5601 9723 5601 9724 5603 9724 5604 9724 5601 9725 5604 9725 5605 9725 5605 9726 5604 9726 5606 9726 5605 9727 5606 9727 5607 9727 131 9728 5608 9728 5602 9728 5602 9729 5608 9729 5609 9729 5602 9730 5609 9730 5603 9730 5603 9731 5609 9731 5610 9731 5603 9732 5610 9732 5604 9732 5604 9733 5610 9733 5611 9733 5604 9734 5611 9734 5606 9734 5612 9735 5613 9735 5614 9735 5615 9736 115 9736 127 9736 5616 9737 5617 9737 5618 9737 5618 9738 5617 9738 5619 9738 5618 9739 5619 9739 5620 9739 5620 9740 5619 9740 5621 9740 5620 9741 5621 9741 5622 9741 5623 9742 5624 9742 5616 9742 5616 9743 5624 9743 5625 9743 5616 9744 5625 9744 5617 9744 5626 9745 5627 9745 5628 9745 5628 9746 5627 9746 5629 9746 5628 9747 5629 9747 5623 9747 5623 9748 5629 9748 5630 9748 5623 9749 5630 9749 5624 9749 5631 9750 126 9750 125 9750 126 9751 5631 9751 127 9751 5632 9752 110 9752 115 9752 5633 9753 5634 9753 5632 9753 5632 9754 5634 9754 5635 9754 5632 9755 5635 9755 110 9755 110 9756 5635 9756 5636 9756 110 9757 5636 9757 111 9757 5614 9758 5613 9758 5632 9758 5632 9759 5613 9759 5637 9759 5632 9760 5637 9760 5633 9760 5638 9761 5639 9761 5640 9761 5640 9762 5639 9762 5641 9762 5640 9763 5641 9763 5614 9763 5614 9764 5641 9764 5642 9764 5614 9765 5642 9765 5612 9765 5640 9766 5643 9766 5638 9766 5638 9767 5643 9767 5644 9767 5638 9768 5644 9768 5645 9768 5645 9769 5644 9769 5646 9769 5645 9770 5646 9770 5647 9770 5622 9771 5648 9771 5620 9771 5620 9772 5648 9772 5649 9772 5620 9773 5649 9773 5650 9773 115 9774 5615 9774 5632 9774 5632 9775 5615 9775 5651 9775 5632 9776 5651 9776 5614 9776 5614 9777 5651 9777 5652 9777 5614 9778 5652 9778 5640 9778 5640 9779 5652 9779 5653 9779 5640 9780 5653 9780 5643 9780 5643 9781 5653 9781 5654 9781 5643 9782 5654 9782 5644 9782 5644 9783 5654 9783 5655 9783 5644 9784 5655 9784 5646 9784 127 9785 5631 9785 5615 9785 5615 9786 5631 9786 5656 9786 5615 9787 5656 9787 5651 9787 5651 9788 5656 9788 5657 9788 5651 9789 5657 9789 5652 9789 5652 9790 5657 9790 5658 9790 5652 9791 5658 9791 5653 9791 5653 9792 5658 9792 5659 9792 5653 9793 5659 9793 5654 9793 5654 9794 5659 9794 5660 9794 5654 9795 5660 9795 5655 9795 124 9796 5626 9796 125 9796 125 9797 5626 9797 5628 9797 125 9798 5628 9798 5631 9798 5631 9799 5628 9799 5623 9799 5631 9800 5623 9800 5656 9800 5656 9801 5623 9801 5616 9801 5656 9802 5616 9802 5657 9802 5657 9803 5616 9803 5618 9803 5657 9804 5618 9804 5658 9804 5658 9805 5618 9805 5620 9805 5658 9806 5620 9806 5659 9806 5659 9807 5620 9807 5650 9807 5659 9808 5650 9808 5660 9808 5661 9809 5505 9809 5509 9809 5662 9810 5663 9810 5664 9810 5663 9811 5665 9811 5666 9811 5663 9812 5662 9812 5665 9812 5665 9813 5662 9813 5667 9813 5665 9814 5667 9814 5668 9814 5669 9815 5670 9815 5664 9815 5664 9816 5670 9816 5671 9816 5664 9817 5671 9817 5662 9817 5672 9818 5673 9818 5674 9818 5674 9819 5673 9819 5675 9819 5674 9820 5675 9820 5669 9820 5669 9821 5675 9821 5676 9821 5669 9822 5676 9822 5670 9822 4514 9823 5505 9823 5677 9823 5677 9824 5505 9824 5661 9824 5677 9825 5661 9825 5666 9825 5678 9826 5508 9826 5679 9826 5679 9827 5508 9827 5507 9827 5679 9828 5507 9828 5680 9828 5680 9829 5507 9829 5506 9829 5680 9830 5506 9830 5681 9830 5681 9831 5506 9831 119 9831 5681 9832 119 9832 112 9832 5680 9833 5682 9833 5679 9833 5679 9834 5682 9834 5683 9834 5679 9835 5683 9835 5678 9835 5678 9836 5683 9836 5684 9836 111 9837 5685 9837 112 9837 112 9838 5685 9838 5686 9838 112 9839 5686 9839 5681 9839 5681 9840 5686 9840 5687 9840 5681 9841 5687 9841 5680 9841 5680 9842 5687 9842 5688 9842 5680 9843 5688 9843 5682 9843 5682 9844 5688 9844 5689 9844 5682 9845 5689 9845 5683 9845 5683 9846 5689 9846 5690 9846 5683 9847 5690 9847 5684 9847 5685 9848 5672 9848 5686 9848 5686 9849 5672 9849 5674 9849 5686 9850 5674 9850 5687 9850 5687 9851 5674 9851 5669 9851 5687 9852 5669 9852 5688 9852 5688 9853 5669 9853 5664 9853 5688 9854 5664 9854 5689 9854 5689 9855 5664 9855 5663 9855 5689 9856 5663 9856 5690 9856 5690 9857 5663 9857 5666 9857 5690 9858 5666 9858 5684 9858 5684 9859 5666 9859 5661 9859 5684 9860 5661 9860 5678 9860 5678 9861 5661 9861 5509 9861 5678 9862 5509 9862 5508 9862 5691 9863 5692 9863 5693 9863 5693 9864 5692 9864 5694 9864 5693 9865 5694 9865 5695 9865 5695 9866 5696 9866 5693 9866 5693 9867 5696 9867 5697 9867 5693 9868 5697 9868 5698 9868 5699 9869 5700 9869 5701 9869 5701 9870 5692 9870 5699 9870 5699 9871 5692 9871 5691 9871 5699 9872 5691 9872 5702 9872 5702 9873 5691 9873 5703 9873 5691 9874 5704 9874 5703 9874 5703 9875 5704 9875 233 9875 5703 9876 233 9876 230 9876 5705 9877 5706 9877 4556 9877 4556 95 5706 95 5707 95 4556 95 5707 95 4560 95 4550 95 4552 95 4556 95 4556 9878 4552 9878 5708 9878 4556 95 5708 95 5705 95 5588 9879 5589 9879 5709 9879 5710 9880 5711 9880 5588 9880 5588 9881 5711 9881 5712 9881 5588 9882 5712 9882 5587 9882 5588 9883 5709 9883 5710 9883 5710 9884 5709 9884 5713 9884 5710 9885 5713 9885 5714 9885 5714 9886 5713 9886 5715 9886 5714 9887 5715 9887 5716 9887 5589 9888 5586 9888 5709 9888 5709 9889 5586 9889 5585 9889 5709 9890 5585 9890 5713 9890 5713 9891 5585 9891 5584 9891 5713 9892 5584 9892 5715 9892 5717 9893 5599 9893 5598 9893 5597 9894 5718 9894 5719 9894 5719 9895 5718 9895 5720 9895 5719 9896 5720 9896 5721 9896 5721 9897 5720 9897 5722 9897 5721 9898 5722 9898 5723 9898 5723 9899 5722 9899 5724 9899 5723 9900 5724 9900 5725 9900 5725 9901 5724 9901 5726 9901 5725 9902 5726 9902 5727 9902 5728 9903 5729 9903 5727 9903 5727 9904 5729 9904 5730 9904 5727 9905 5730 9905 5725 9905 5725 9906 5730 9906 5731 9906 5725 9907 5731 9907 5723 9907 5723 9908 5731 9908 5732 9908 5723 9909 5732 9909 5721 9909 5721 9910 5732 9910 5717 9910 5721 9911 5717 9911 5719 9911 5719 9912 5717 9912 5598 9912 5719 9913 5598 9913 5597 9913 5733 9914 5728 9914 5734 9914 5734 9915 5728 9915 5727 9915 5734 9916 5727 9916 5735 9916 5735 9917 5727 9917 5726 9917 5736 9918 5712 9918 5711 9918 5700 9919 5737 9919 5738 9919 5739 9920 5740 9920 5741 9920 5597 9921 5742 9921 5743 9921 5712 9922 5736 9922 5587 9922 5699 9923 5744 9923 5700 9923 5700 9924 5744 9924 5741 9924 5700 9925 5741 9925 5737 9925 5737 9926 5741 9926 5740 9926 5737 9927 5740 9927 5745 9927 5745 9928 5740 9928 5739 9928 5745 9929 5739 9929 5746 9929 5746 9930 5739 9930 5747 9930 5746 9931 5747 9931 5748 9931 5748 9932 5747 9932 5749 9932 5748 9933 5749 9933 5750 9933 5750 9934 5749 9934 5751 9934 5750 9935 5751 9935 5752 9935 5752 9936 5751 9936 5753 9936 5752 9937 5753 9937 5754 9937 5754 9938 5753 9938 5755 9938 5754 9939 5755 9939 5756 9939 5756 9940 5755 9940 5757 9940 5756 9941 5757 9941 5758 9941 5758 9942 5757 9942 5743 9942 5758 9943 5743 9943 5759 9943 5759 9944 5743 9944 5742 9944 5759 9945 5742 9945 5736 9945 5736 9946 5742 9946 5597 9946 5736 9947 5597 9947 5587 9947 5587 9948 5597 9948 5590 9948 5587 9949 5590 9949 5579 9949 5760 9950 5728 9950 5733 9950 5761 9951 5762 9951 5763 9951 5764 9952 5765 9952 5766 9952 5599 9953 5717 9953 5600 9953 5600 9954 5717 9954 5732 9954 5593 9955 5592 9955 5767 9955 5767 9956 5592 9956 5768 9956 5767 9957 5768 9957 5769 9957 5770 9958 5595 9958 5594 9958 5608 9959 131 9959 5596 9959 5595 9960 5770 9960 5596 9960 5596 9961 5770 9961 5771 9961 5596 9962 5771 9962 5608 9962 5608 9963 5771 9963 5763 9963 5608 9964 5763 9964 5609 9964 5609 9965 5763 9965 5762 9965 5609 9966 5762 9966 5610 9966 5611 9967 5610 9967 5772 9967 5772 9968 5610 9968 5762 9968 5772 9969 5762 9969 5773 9969 5773 9970 5762 9970 5761 9970 5773 9971 5761 9971 5774 9971 5592 9972 5600 9972 5768 9972 5768 9973 5600 9973 5732 9973 5768 9974 5732 9974 5769 9974 5769 9975 5732 9975 5731 9975 5769 9976 5731 9976 5775 9976 5775 9977 5731 9977 5776 9977 5776 9978 5731 9978 5730 9978 5776 9979 5730 9979 5760 9979 5760 9980 5730 9980 5729 9980 5760 9981 5729 9981 5728 9981 5733 9982 5764 9982 5760 9982 5760 9983 5764 9983 5766 9983 5760 9984 5766 9984 5776 9984 5776 9985 5766 9985 5777 9985 5776 9986 5777 9986 5775 9986 5775 9987 5777 9987 5778 9987 5775 9988 5778 9988 5769 9988 5765 9989 5774 9989 5766 9989 5766 9990 5774 9990 5761 9990 5766 9991 5761 9991 5777 9991 5777 9992 5761 9992 5763 9992 5777 9993 5763 9993 5778 9993 5778 9994 5763 9994 5771 9994 5778 9995 5771 9995 5769 9995 5769 9996 5771 9996 5770 9996 5769 9997 5770 9997 5767 9997 5767 9998 5770 9998 5594 9998 5767 9999 5594 9999 5593 9999 5779 10000 5780 10000 5781 10000 5662 10001 5671 10001 5782 10001 5637 10002 5613 10002 5783 10002 5783 10003 5613 10003 5612 10003 5784 10004 5785 10004 5786 10004 5787 10005 5668 10005 5667 10005 5788 10006 5789 10006 5790 10006 5790 10007 5789 10007 5791 10007 5792 10008 5793 10008 5794 10008 5794 10009 5793 10009 5795 10009 5794 10010 5795 10010 5796 10010 5796 10011 5795 10011 5797 10011 5796 10012 5797 10012 5798 10012 5798 10013 5797 10013 5791 10013 5798 10014 5791 10014 5799 10014 5799 10015 5791 10015 5789 10015 5645 10016 5647 10016 5800 10016 5801 10017 5638 10017 5802 10017 5802 10018 5638 10018 5645 10018 5802 10019 5645 10019 5803 10019 5803 10020 5645 10020 5800 10020 5804 10021 5641 10021 5801 10021 5801 10022 5641 10022 5639 10022 5801 10023 5639 10023 5638 10023 5781 10024 5634 10024 5633 10024 111 10025 5636 10025 5685 10025 5685 10026 5636 10026 5635 10026 5685 10027 5635 10027 5672 10027 5672 10028 5635 10028 5634 10028 5672 10029 5634 10029 5673 10029 5673 10030 5634 10030 5781 10030 5673 10031 5781 10031 5675 10031 5675 10032 5781 10032 5676 10032 5676 10033 5781 10033 5780 10033 5676 10034 5780 10034 5670 10034 5662 10035 5782 10035 5667 10035 5633 10036 5637 10036 5781 10036 5781 10037 5637 10037 5783 10037 5781 10038 5783 10038 5779 10038 5779 10039 5783 10039 5612 10039 5779 10040 5612 10040 5804 10040 5804 10041 5612 10041 5642 10041 5804 10042 5642 10042 5641 10042 5785 10043 5792 10043 5786 10043 5786 10044 5792 10044 5794 10044 5786 10045 5794 10045 5805 10045 5805 10046 5794 10046 5796 10046 5805 10047 5796 10047 5806 10047 5806 10048 5796 10048 5798 10048 5806 10049 5798 10049 5807 10049 5807 10050 5798 10050 5799 10050 5807 10051 5799 10051 5808 10051 5808 10052 5799 10052 5789 10052 5808 10053 5789 10053 5782 10053 5782 10054 5789 10054 5788 10054 5782 10055 5788 10055 5667 10055 5667 10056 5788 10056 5790 10056 5667 10057 5790 10057 5787 10057 5671 10058 5670 10058 5782 10058 5782 10059 5670 10059 5780 10059 5782 10060 5780 10060 5808 10060 5808 10061 5780 10061 5779 10061 5808 10062 5779 10062 5807 10062 5807 10063 5779 10063 5804 10063 5807 10064 5804 10064 5806 10064 5806 10065 5804 10065 5801 10065 5806 10066 5801 10066 5805 10066 5805 10067 5801 10067 5802 10067 5805 10068 5802 10068 5786 10068 5786 10069 5802 10069 5803 10069 5786 10070 5803 10070 5784 10070 5784 10071 5803 10071 5800 10071 4529 10072 4506 10072 4508 10072 5809 10073 5797 10073 5793 10073 5793 10074 5797 10074 5795 10074 5809 10075 5810 10075 5668 10075 5791 10076 5797 10076 5790 10076 5790 10077 5797 10077 5809 10077 5790 10078 5809 10078 5787 10078 5787 10079 5809 10079 5668 10079 5811 10080 4510 10080 4514 10080 4514 10081 5677 10081 5811 10081 5811 10082 5677 10082 5666 10082 5811 10083 5666 10083 5810 10083 5810 10084 5666 10084 5665 10084 5810 10085 5665 10085 5668 10085 4529 10086 4508 10086 4530 10086 4530 10087 4508 10087 5812 10087 4530 10088 5812 10088 4531 10088 4531 10089 5812 10089 5813 10089 4531 10090 5813 10090 4536 10090 5814 10091 4538 10091 5815 10091 5815 10092 4538 10092 4537 10092 5815 10093 4537 10093 4536 10093 4536 10094 5813 10094 5815 10094 5815 10095 5813 10095 5816 10095 5815 10096 5816 10096 5814 10096 5809 10097 5816 10097 5810 10097 5810 10098 5816 10098 5813 10098 5810 10099 5813 10099 5811 10099 5811 10100 5813 10100 5812 10100 5811 10101 5812 10101 4510 10101 4510 10102 5812 10102 4508 10102 5817 10103 240 10103 241 10103 5818 10104 5819 10104 5820 10104 5821 10105 5822 10105 5823 10105 5823 10106 5822 10106 5824 10106 5825 10107 5826 10107 5822 10107 5822 10108 5826 10108 5827 10108 5822 10109 5827 10109 5824 10109 5828 10110 5829 10110 5820 10110 5820 10111 5829 10111 5830 10111 5820 10112 5830 10112 5818 10112 5818 10113 5830 10113 5831 10113 5818 10114 5831 10114 5832 10114 5832 10115 5831 10115 5833 10115 5832 10116 5833 10116 5825 10116 5825 10117 5833 10117 5834 10117 5825 10118 5834 10118 5826 10118 5835 10119 5836 10119 5837 10119 5838 10120 5836 10120 5839 10120 5839 10121 5836 10121 5835 10121 5839 10122 5835 10122 5840 10122 5840 10123 5835 10123 5841 10123 5842 10124 5843 10124 5841 10124 5841 10125 5843 10125 5844 10125 5841 10126 5844 10126 5840 10126 5845 10127 5846 10127 5847 10127 5847 10128 5846 10128 5848 10128 5847 10129 5848 10129 5849 10129 5849 10130 5848 10130 5850 10130 5849 10131 5850 10131 5842 10131 5842 10132 5850 10132 5851 10132 5842 10133 5851 10133 5843 10133 5852 10134 243 10134 227 10134 243 10135 5852 10135 241 10135 5823 10136 246 10136 5821 10136 5821 10137 246 10137 239 10137 5821 10138 239 10138 240 10138 240 10139 5817 10139 5821 10139 5821 10140 5817 10140 5853 10140 5821 10141 5853 10141 5822 10141 5822 10142 5853 10142 5854 10142 5822 10143 5854 10143 5825 10143 5825 10144 5854 10144 5855 10144 5825 10145 5855 10145 5832 10145 5832 10146 5855 10146 5856 10146 5832 10147 5856 10147 5818 10147 5818 10148 5856 10148 5857 10148 5818 10149 5857 10149 5819 10149 241 10150 5852 10150 5817 10150 5817 10151 5852 10151 5858 10151 5817 10152 5858 10152 5853 10152 5853 10153 5858 10153 5859 10153 5853 10154 5859 10154 5854 10154 5854 10155 5859 10155 5860 10155 5854 10156 5860 10156 5855 10156 5855 10157 5860 10157 5861 10157 5855 10158 5861 10158 5856 10158 5856 10159 5861 10159 5862 10159 5856 10160 5862 10160 5857 10160 226 10161 5845 10161 227 10161 227 10162 5845 10162 5847 10162 227 10163 5847 10163 5852 10163 5852 10164 5847 10164 5849 10164 5852 10165 5849 10165 5858 10165 5858 10166 5849 10166 5842 10166 5858 10167 5842 10167 5859 10167 5859 10168 5842 10168 5841 10168 5859 10169 5841 10169 5860 10169 5860 10170 5841 10170 5835 10170 5860 10171 5835 10171 5861 10171 5861 10172 5835 10172 5837 10172 5861 10173 5837 10173 5862 10173 5863 10174 5864 10174 5865 10174 5865 10175 5864 10175 5866 10175 228 10176 5867 10176 5868 10176 5868 10177 5867 10177 5869 10177 5869 10178 5870 10178 5868 10178 5868 10179 5870 10179 5871 10179 5868 10180 5871 10180 228 10180 228 10181 5871 10181 229 10181 5872 10182 5873 10182 5870 10182 5870 10183 5873 10183 5874 10183 5870 10184 5874 10184 5871 10184 5869 10185 5866 10185 5870 10185 5870 10186 5866 10186 5864 10186 5870 10187 5864 10187 5872 10187 5872 10188 5864 10188 5863 10188 5872 10189 5863 10189 5875 10189 5876 10190 5877 10190 5878 10190 5879 10191 5741 10191 5744 10191 5878 10192 5703 10192 230 10192 5744 10193 5699 10193 5878 10193 5878 10194 5699 10194 5702 10194 5878 10195 5702 10195 5703 10195 5878 10196 5877 10196 5744 10196 5744 10197 5877 10197 5880 10197 5744 10198 5880 10198 5879 10198 230 10199 229 10199 5878 10199 5878 10200 229 10200 5881 10200 5878 10201 5881 10201 5882 10201 5882 10202 5883 10202 5878 10202 5878 10203 5883 10203 5884 10203 5878 10204 5884 10204 5876 10204 5885 10205 5886 10205 5887 10205 5888 10206 5889 10206 5886 10206 5888 10207 5890 10207 5889 10207 5889 10208 5890 10208 5891 10208 5889 10209 5891 10209 4520 10209 4520 10210 5891 10210 5511 10210 5892 10211 5893 10211 5894 10211 5894 10212 5895 10212 5892 10212 5892 10213 5895 10213 5896 10213 5892 10214 5896 10214 5897 10214 5897 10215 5896 10215 5898 10215 5897 10216 5898 10216 5899 10216 5900 10217 5901 10217 5902 10217 5902 10218 5901 10218 5903 10218 5888 10219 5904 10219 5890 10219 5890 10220 5904 10220 5905 10220 5890 10221 5905 10221 5891 10221 5891 10222 5905 10222 5512 10222 5891 10223 5512 10223 5511 10223 5514 10224 5513 10224 5906 10224 5902 10225 5894 10225 5900 10225 5900 10226 5894 10226 5893 10226 5900 10227 5893 10227 5907 10227 5907 10228 5893 10228 5892 10228 5907 10229 5892 10229 5908 10229 5908 10230 5892 10230 5897 10230 5908 10231 5897 10231 5909 10231 5909 10232 5897 10232 5910 10232 5909 10233 5910 10233 231 10233 5899 10234 226 10234 5897 10234 5897 10235 226 10235 225 10235 5897 10236 225 10236 5910 10236 5910 10237 225 10237 232 10237 5910 10238 232 10238 231 10238 5886 10239 5885 10239 5888 10239 5888 10240 5885 10240 5911 10240 5888 10241 5911 10241 5904 10241 5904 10242 5911 10242 5906 10242 5904 10243 5906 10243 5905 10243 5905 10244 5906 10244 5513 10244 5905 10245 5513 10245 5512 10245 231 10246 5510 10246 5909 10246 5909 10247 5510 10247 5515 10247 5909 10248 5515 10248 5908 10248 5908 10249 5515 10249 5514 10249 5908 10250 5514 10250 5907 10250 5907 10251 5514 10251 5906 10251 5907 10252 5906 10252 5900 10252 5900 10253 5906 10253 5911 10253 5900 10254 5911 10254 5901 10254 5901 10255 5911 10255 5885 10255 5901 10256 5885 10256 5903 10256 5903 10257 5885 10257 5887 10257 5912 10258 5913 10258 5914 10258 5707 10259 5706 10259 5915 10259 5916 10260 5917 10260 5918 10260 5919 10261 5920 10261 5921 10261 5921 10262 5920 10262 5922 10262 5648 10263 5919 10263 5649 10263 5649 10264 5919 10264 5921 10264 5649 10265 5921 10265 5650 10265 5650 10266 5921 10266 5660 10266 5922 10267 5923 10267 5921 10267 5921 10268 5923 10268 5924 10268 5921 10269 5924 10269 5660 10269 5660 10270 5924 10270 5925 10270 5660 10271 5925 10271 5655 10271 5926 10272 5647 10272 5646 10272 5927 10273 5928 10273 5929 10273 5929 10274 5928 10274 5930 10274 5929 10275 5930 10275 5926 10275 4526 10276 4525 10276 5931 10276 5931 10277 4525 10277 4534 10277 5931 10278 4534 10278 5929 10278 5929 10279 4534 10279 5932 10279 5929 10280 5932 10280 5927 10280 5926 10281 5646 10281 5929 10281 5929 10282 5646 10282 5655 10282 5929 10283 5655 10283 5931 10283 5931 10284 5655 10284 5925 10284 5931 10285 5925 10285 4526 10285 4526 10286 5925 10286 5924 10286 4526 10287 5924 10287 4542 10287 4542 10288 5924 10288 5933 10288 4542 10289 5933 10289 4546 10289 5913 10290 5708 10290 5914 10290 5914 10291 5708 10291 4552 10291 5914 10292 4552 10292 4551 10292 4549 10293 4548 10293 4551 10293 4551 10294 4548 10294 4547 10294 4551 10295 4547 10295 5914 10295 5914 10296 4547 10296 4543 10296 5914 10297 4543 10297 5934 10297 5934 10298 4543 10298 4545 10298 5934 10299 4545 10299 5935 10299 5707 10300 5915 10300 4560 10300 4560 10301 5915 10301 5936 10301 4560 10302 5936 10302 4561 10302 5937 10303 4564 10303 5938 10303 5938 10304 4564 10304 4563 10304 5938 10305 4563 10305 5939 10305 5939 10306 4563 10306 4562 10306 5940 10307 5941 10307 5938 10307 5938 10308 5941 10308 5942 10308 5938 10309 5942 10309 5937 10309 5836 10310 5838 10310 5943 10310 4561 10311 5936 10311 4562 10311 4562 10312 5936 10312 5944 10312 4562 10313 5944 10313 5939 10313 5939 10314 5944 10314 5836 10314 5939 10315 5836 10315 5938 10315 5938 10316 5836 10316 5943 10316 5938 10317 5943 10317 5940 10317 5828 10318 5820 10318 5945 10318 5820 10319 5819 10319 5945 10319 5945 10320 5819 10320 5857 10320 5945 10321 5857 10321 5936 10321 5936 10322 5857 10322 5862 10322 5936 10323 5862 10323 5944 10323 5944 10324 5862 10324 5837 10324 5944 10325 5837 10325 5836 10325 5945 10326 5946 10326 5947 10326 5828 10327 5945 10327 5948 10327 5948 10328 5945 10328 5947 10328 5948 10329 5947 10329 5949 10329 5946 10330 5945 10330 5950 10330 5950 10331 5945 10331 5936 10331 5950 10332 5936 10332 5951 10332 5951 10333 5936 10333 5915 10333 5951 10334 5915 10334 5912 10334 5912 10335 5915 10335 5706 10335 5912 10336 5706 10336 5913 10336 5913 10337 5706 10337 5705 10337 5913 10338 5705 10338 5708 10338 5917 10339 5916 10339 5935 10339 5935 10340 5916 10340 5952 10340 5935 10341 5952 10341 5934 10341 5934 10342 5952 10342 5953 10342 5934 10343 5953 10343 5914 10343 5914 10344 5953 10344 5954 10344 5914 10345 5954 10345 5912 10345 4545 10346 4546 10346 5935 10346 5935 10347 4546 10347 5933 10347 5935 10348 5933 10348 5917 10348 5917 10349 5933 10349 5924 10349 5917 10350 5924 10350 5918 10350 5918 10351 5924 10351 5923 10351 5955 10352 5692 10352 5738 10352 5738 10353 5692 10353 5701 10353 5738 10354 5701 10354 5700 10354 5695 10355 5956 10355 5696 10355 5696 10356 5956 10356 5957 10356 5696 10357 5957 10357 5697 10357 5958 10358 5957 10358 5959 10358 5959 10359 5957 10359 5956 10359 5959 10360 5956 10360 5960 10360 5960 10361 5956 10361 5695 10361 5960 10362 5695 10362 5955 10362 5955 10363 5695 10363 5694 10363 5955 10364 5694 10364 5692 10364 5716 10365 5715 10365 5961 10365 5961 10366 5715 10366 5962 10366 5961 10367 5962 10367 5963 10367 5963 10368 5962 10368 5964 10368 5963 10369 5964 10369 5965 10369 5965 10370 5964 10370 5966 10370 5965 10371 5966 10371 5967 10371 5967 10372 5966 10372 5968 10372 5967 10373 5968 10373 5958 10373 5958 10374 5968 10374 5957 10374 5715 10375 5584 10375 5962 10375 5962 10376 5584 10376 5969 10376 5962 10377 5969 10377 5964 10377 5964 10378 5969 10378 5970 10378 5964 10379 5970 10379 5966 10379 5966 10380 5970 10380 5971 10380 5966 10381 5971 10381 5968 10381 5968 10382 5971 10382 5972 10382 5968 10383 5972 10383 5957 10383 5957 10384 5972 10384 5697 10384 5716 10385 5973 10385 5714 10385 5714 10386 5974 10386 5710 10386 5710 10387 5974 10387 5975 10387 5710 10388 5975 10388 5711 10388 5716 10389 5976 10389 5973 10389 5973 10390 5976 10390 5977 10390 5973 10391 5977 10391 5978 10391 5714 10392 5973 10392 5974 10392 5974 10393 5973 10393 5978 10393 5974 10394 5978 10394 5975 10394 5975 10395 5978 10395 5979 10395 5975 10396 5979 10396 5980 10396 5981 10397 5982 10397 5983 10397 5982 10398 5981 10398 5984 10398 5984 10399 5981 10399 5985 10399 5984 10400 5985 10400 5986 10400 5986 10401 5985 10401 5987 10401 5986 10402 5987 10402 5988 10402 5988 10403 5987 10403 5989 10403 5988 10404 5989 10404 5990 10404 5991 10405 5992 10405 5993 10405 5993 10406 5992 10406 5994 10406 5993 10407 5994 10407 5989 10407 5989 10408 5994 10408 5995 10408 5989 10409 5995 10409 5990 10409 5991 10410 5993 10410 5996 10410 5996 10411 5993 10411 5997 10411 5996 10412 5997 10412 5998 10412 5998 10413 5997 10413 5999 10413 5998 10414 5999 10414 6000 10414 6000 10415 5999 10415 6001 10415 6000 10416 6001 10416 6002 10416 5736 10417 5711 10417 5975 10417 5980 10418 6002 10418 5975 10418 5975 10419 6002 10419 6001 10419 5975 10420 6001 10420 5736 10420 5736 10421 6001 10421 5999 10421 5736 10422 5999 10422 5759 10422 5759 10423 5999 10423 5997 10423 5759 10424 5997 10424 5758 10424 5758 10425 5997 10425 5993 10425 5758 10426 5993 10426 5756 10426 5756 10427 5993 10427 5989 10427 5756 10428 5989 10428 5754 10428 5754 10429 5989 10429 5987 10429 5754 10430 5987 10430 5752 10430 5752 10431 5987 10431 5985 10431 5752 10432 5985 10432 5750 10432 5750 10433 5985 10433 5981 10433 5750 10434 5981 10434 5748 10434 5748 10435 5981 10435 6003 10435 5748 10436 6003 10436 5746 10436 5746 10437 6003 10437 6004 10437 5746 10438 6004 10438 5745 10438 5745 10439 6004 10439 6005 10439 5745 10440 6005 10440 5737 10440 6006 10441 6007 10441 6008 10441 5738 10442 5737 10442 6008 10442 6008 10443 5737 10443 6005 10443 6008 10444 6005 10444 6006 10444 6006 10445 6005 10445 6004 10445 6006 10446 6004 10446 6009 10446 6009 10447 6004 10447 6003 10447 6009 10448 6003 10448 6010 10448 6010 10449 6003 10449 5981 10449 6010 10450 5981 10450 6011 10450 6011 10451 5981 10451 5983 10451 6011 10452 5983 10452 6012 10452 6013 10453 6014 10453 5718 10453 5718 10454 6014 10454 5720 10454 5720 10455 6014 10455 5722 10455 5722 10456 6014 10456 6015 10456 5722 10457 6015 10457 5724 10457 5724 10458 6015 10458 6016 10458 5724 10459 6016 10459 5726 10459 6017 10460 6018 10460 6019 10460 6020 10461 6021 10461 6018 10461 6018 10462 6017 10462 6020 10462 6020 10463 6017 10463 6022 10463 6020 10464 6022 10464 6023 10464 6023 10465 6022 10465 6024 10465 6024 10466 6022 10466 6025 10466 6024 10467 6025 10467 6026 10467 6026 10468 6025 10468 6027 10468 6026 10469 6027 10469 6028 10469 5718 10470 5597 10470 6013 10470 6013 10471 5597 10471 5743 10471 6013 10472 5743 10472 5757 10472 5755 10473 6028 10473 5757 10473 5757 10474 6028 10474 6027 10474 5757 10475 6027 10475 6013 10475 6013 10476 6027 10476 6025 10476 6013 10477 6025 10477 6014 10477 6014 10478 6025 10478 6022 10478 6014 10479 6022 10479 6015 10479 6015 10480 6022 10480 6017 10480 6015 10481 6017 10481 6016 10481 6016 10482 6017 10482 6019 10482 6016 10483 6019 10483 5726 10483 5726 10484 6019 10484 5735 10484 6029 10485 5753 10485 5751 10485 6030 10486 6031 10486 6021 10486 6032 10487 6033 10487 6034 10487 5755 10488 5753 10488 6028 10488 6028 10489 5753 10489 6029 10489 6028 10490 6029 10490 6026 10490 6026 10491 6029 10491 6035 10491 6026 10492 6035 10492 6024 10492 6024 10493 6035 10493 6036 10493 6024 10494 6036 10494 6023 10494 6023 10495 6036 10495 6030 10495 6023 10496 6030 10496 6020 10496 6020 10497 6030 10497 6021 10497 5749 10498 6037 10498 5751 10498 5751 10499 6037 10499 6038 10499 5751 10500 6038 10500 6029 10500 6029 10501 6038 10501 6039 10501 6029 10502 6039 10502 6035 10502 6035 10503 6039 10503 6040 10503 6035 10504 6040 10504 6036 10504 6036 10505 6040 10505 6032 10505 6036 10506 6032 10506 6030 10506 6030 10507 6032 10507 6034 10507 6030 10508 6034 10508 6031 10508 6041 10509 6033 10509 6042 10509 6042 10510 6033 10510 6032 10510 6042 10511 6032 10511 6043 10511 6043 10512 6032 10512 6040 10512 6043 10513 6040 10513 6044 10513 6044 10514 6040 10514 6039 10514 6044 10515 6039 10515 6045 10515 6045 10516 6039 10516 6038 10516 6045 10517 6038 10517 6046 10517 6046 10518 6038 10518 6037 10518 6047 10519 5747 10519 5739 10519 5749 10520 5747 10520 6037 10520 6037 10521 5747 10521 6047 10521 6037 10522 6047 10522 6046 10522 6046 10523 6047 10523 6048 10523 6046 10524 6048 10524 6045 10524 6045 10525 6048 10525 6049 10525 6045 10526 6049 10526 6044 10526 6044 10527 6049 10527 6043 10527 6043 10528 6049 10528 6050 10528 6043 10529 6050 10529 6042 10529 6051 10530 6052 10530 6053 10530 6054 10531 6052 10531 6055 10531 6055 10532 6052 10532 6051 10532 6055 10533 6051 10533 6056 10533 5741 10534 6057 10534 6058 10534 6058 10535 6057 10535 6059 10535 6058 10536 6059 10536 6060 10536 6060 10537 6059 10537 6061 10537 6060 10538 6061 10538 6056 10538 6056 10539 6061 10539 6062 10539 6056 10540 6062 10540 6055 10540 6041 10541 6042 10541 6053 10541 6053 10542 6042 10542 6050 10542 6053 10543 6050 10543 6051 10543 6051 10544 6050 10544 6049 10544 6051 10545 6049 10545 6056 10545 6056 10546 6049 10546 6048 10546 6056 10547 6048 10547 6060 10547 6060 10548 6048 10548 6047 10548 6060 10549 6047 10549 6058 10549 6058 10550 6047 10550 5739 10550 6058 10551 5739 10551 5741 10551 5928 10552 6063 10552 5930 10552 4535 10553 6064 10553 6065 10553 5647 10554 6066 10554 5800 10554 5800 10555 6066 10555 6067 10555 5800 10556 6067 10556 5784 10556 5784 10557 6067 10557 5785 10557 5785 10558 6067 10558 6068 10558 5785 10559 6068 10559 5792 10559 4538 10560 5814 10560 4532 10560 4535 10561 6065 10561 4539 10561 4539 10562 6065 10562 6069 10562 4539 10563 6069 10563 4540 10563 6070 10564 6071 10564 4541 10564 4541 10565 6071 10565 5932 10565 4541 10566 5932 10566 4534 10566 5647 10567 5926 10567 6066 10567 6066 10568 5926 10568 6072 10568 6066 10569 6072 10569 6067 10569 6067 10570 6072 10570 6073 10570 6067 10571 6073 10571 6068 10571 5793 10572 5792 10572 5809 10572 5809 10573 5792 10573 6068 10573 5809 10574 6068 10574 5816 10574 5816 10575 6068 10575 6073 10575 5816 10576 6073 10576 5814 10576 5814 10577 6073 10577 6074 10577 5814 10578 6074 10578 4532 10578 4532 10579 6074 10579 4533 10579 5926 10580 5930 10580 6072 10580 6072 10581 5930 10581 6063 10581 6072 10582 6063 10582 6070 10582 6070 10583 6063 10583 5928 10583 6070 10584 5928 10584 6071 10584 6071 10585 5928 10585 5927 10585 6071 10586 5927 10586 5932 10586 4541 10587 4540 10587 6070 10587 6070 10588 4540 10588 6069 10588 6070 10589 6069 10589 6072 10589 6072 10590 6069 10590 6065 10590 6072 10591 6065 10591 6073 10591 6073 10592 6065 10592 6064 10592 6073 10593 6064 10593 6074 10593 6074 10594 6064 10594 4535 10594 6074 10595 4535 10595 4533 10595 6075 10596 6076 10596 6077 10596 6077 10597 6076 10597 6078 10597 6077 10598 6078 10598 6079 10598 6075 10599 6077 10599 6080 10599 6080 10600 6077 10600 6081 10600 6080 10601 6081 10601 6082 10601 4554 10602 6083 10602 4555 10602 4555 10603 6083 10603 6084 10603 4555 10604 6084 10604 4557 10604 4557 10605 6084 10605 4558 10605 4558 10606 6084 10606 6085 10606 4558 10607 6085 10607 4559 10607 4516 10608 4559 10608 4518 10608 4518 10609 4559 10609 6085 10609 4518 10610 6085 10610 4519 10610 4519 10611 6085 10611 4522 10611 5889 10612 6086 10612 5886 10612 5886 10613 6086 10613 6078 10613 5886 10614 6078 10614 5887 10614 5887 10615 6078 10615 6076 10615 4554 10616 6087 10616 6083 10616 6083 10617 6087 10617 6079 10617 6083 10618 6079 10618 6084 10618 6084 10619 6079 10619 6078 10619 6084 10620 6078 10620 6085 10620 6085 10621 6078 10621 6086 10621 6085 10622 6086 10622 4522 10622 4522 10623 6086 10623 5889 10623 4522 10624 5889 10624 4520 10624 5848 10625 6088 10625 5850 10625 5899 10626 5845 10626 226 10626 5903 10627 5887 10627 6076 10627 6089 10628 5894 10628 6090 10628 6090 10629 5894 10629 5902 10629 6090 10630 5902 10630 6091 10630 6091 10631 5902 10631 5903 10631 6091 10632 5903 10632 6092 10632 6092 10633 5903 10633 6076 10633 6092 10634 6076 10634 6075 10634 5898 10635 5896 10635 6089 10635 6089 10636 5896 10636 5895 10636 6089 10637 5895 10637 5894 10637 5899 10638 5898 10638 5845 10638 5845 10639 5898 10639 6089 10639 5845 10640 6089 10640 5846 10640 5846 10641 6089 10641 5848 10641 6088 10642 6093 10642 5850 10642 5850 10643 6093 10643 6094 10643 5850 10644 6094 10644 5851 10644 5851 10645 6094 10645 6095 10645 5840 10646 5844 10646 6095 10646 6095 10647 5844 10647 5843 10647 6095 10648 5843 10648 5851 10648 6095 10649 6096 10649 5840 10649 5840 10650 6096 10650 6097 10650 5840 10651 6097 10651 5839 10651 5838 10652 5839 10652 6098 10652 6098 10653 5839 10653 6097 10653 6098 10654 6097 10654 6099 10654 6099 10655 6097 10655 6100 10655 6082 10656 6081 10656 6101 10656 6101 10657 6081 10657 6102 10657 6103 10658 6104 10658 6105 10658 6105 10659 6104 10659 6106 10659 6105 10660 6106 10660 6107 10660 6107 10661 6106 10661 6108 10661 6107 10662 6108 10662 6109 10662 6109 10663 6108 10663 6110 10663 6109 10664 6110 10664 6111 10664 6112 10665 6100 10665 6111 10665 6111 10666 6100 10666 6097 10666 6111 10667 6097 10667 6109 10667 6109 10668 6097 10668 6096 10668 6109 10669 6096 10669 6107 10669 6107 10670 6096 10670 6095 10670 6107 10671 6095 10671 6105 10671 6105 10672 6095 10672 6094 10672 6105 10673 6094 10673 6103 10673 6103 10674 6094 10674 6093 10674 5848 10675 6089 10675 6088 10675 6088 10676 6089 10676 6090 10676 6088 10677 6090 10677 6093 10677 6093 10678 6090 10678 6091 10678 6093 10679 6091 10679 6103 10679 6103 10680 6091 10680 6092 10680 6103 10681 6092 10681 6104 10681 6104 10682 6092 10682 6075 10682 6104 10683 6075 10683 6106 10683 6106 10684 6075 10684 6080 10684 6106 10685 6080 10685 6108 10685 6108 10686 6080 10686 6082 10686 6108 10687 6082 10687 6110 10687 6110 10688 6082 10688 6101 10688 6110 10689 6101 10689 6111 10689 6111 10690 6101 10690 6102 10690 6111 10691 6102 10691 6112 10691 6113 10692 6114 10692 6115 10692 6113 10693 6116 10693 6117 10693 6118 10694 6119 10694 6120 10694 6121 10695 6122 10695 5876 10695 5881 10696 229 10696 5871 10696 6118 10697 6120 10697 6123 10697 6115 10698 5873 10698 5872 10698 6113 10699 6115 10699 6124 10699 6124 10700 6115 10700 5872 10700 6124 10701 5872 10701 5875 10701 5883 10702 5882 10702 6125 10702 6125 10703 5882 10703 5881 10703 6125 10704 5881 10704 6126 10704 6126 10705 5881 10705 5871 10705 6126 10706 5871 10706 6127 10706 6127 10707 5871 10707 5874 10707 6113 10708 6117 10708 6114 10708 6114 10709 6117 10709 6128 10709 6114 10710 6128 10710 6115 10710 6129 10711 6130 10711 6131 10711 6131 10712 6130 10712 6132 10712 6131 10713 6132 10713 6133 10713 6133 10714 6132 10714 6134 10714 6133 10715 6134 10715 6120 10715 6120 10716 6134 10716 6135 10716 6120 10717 6135 10717 6123 10717 5876 10718 5884 10718 6121 10718 6121 10719 5884 10719 5883 10719 6121 10720 5883 10720 6136 10720 6136 10721 5883 10721 6125 10721 6136 10722 6125 10722 6137 10722 6137 10723 6125 10723 6126 10723 6137 10724 6126 10724 6128 10724 6128 10725 6126 10725 6127 10725 6128 10726 6127 10726 6115 10726 6115 10727 6127 10727 5874 10727 6115 10728 5874 10728 5873 10728 5880 10729 5877 10729 6138 10729 6138 10730 5877 10730 5876 10730 6138 10731 5876 10731 6139 10731 6139 10732 5876 10732 6122 10732 6139 10733 6122 10733 6140 10733 6140 10734 6122 10734 6121 10734 6140 10735 6121 10735 6129 10735 6129 10736 6121 10736 6136 10736 6129 10737 6136 10737 6130 10737 6130 10738 6136 10738 6137 10738 6130 10739 6137 10739 6132 10739 6132 10740 6137 10740 6128 10740 6132 10741 6128 10741 6134 10741 6134 10742 6128 10742 6117 10742 6134 10743 6117 10743 6135 10743 6135 10744 6117 10744 6116 10744 6135 10745 6116 10745 6123 10745 6123 10746 6116 10746 6113 10746 6141 10747 5879 10747 5880 10747 6057 10748 5741 10748 5879 10748 5880 10749 6138 10749 6141 10749 6141 10750 6138 10750 6139 10750 6141 10751 6139 10751 6142 10751 6119 10752 6143 10752 6120 10752 6120 10753 6143 10753 6144 10753 6120 10754 6144 10754 6133 10754 6133 10755 6144 10755 6145 10755 6133 10756 6145 10756 6131 10756 6131 10757 6145 10757 6146 10757 6131 10758 6146 10758 6129 10758 6129 10759 6146 10759 6142 10759 6129 10760 6142 10760 6140 10760 6140 10761 6142 10761 6139 10761 5879 10762 6141 10762 6057 10762 6057 10763 6141 10763 6142 10763 6057 10764 6142 10764 6059 10764 6059 10765 6142 10765 6146 10765 6059 10766 6146 10766 6061 10766 6061 10767 6146 10767 6145 10767 6061 10768 6145 10768 6062 10768 6062 10769 6145 10769 6144 10769 6062 10770 6144 10770 6055 10770 6055 10771 6144 10771 6143 10771 6055 10772 6143 10772 6054 10772 5950 10773 6147 10773 5946 10773 5946 10774 6147 10774 6148 10774 5946 10775 6148 10775 5947 10775 6149 10776 5949 10776 5947 10776 5947 10777 6148 10777 6149 10777 6149 10778 6148 10778 6150 10778 6149 10779 6150 10779 6151 10779 5950 10780 6152 10780 6147 10780 6147 10781 6152 10781 6153 10781 6147 10782 6153 10782 6148 10782 6148 10783 6153 10783 6154 10783 6148 10784 6154 10784 6150 10784 6155 10785 6156 10785 6157 10785 6157 10786 6156 10786 6158 10786 6157 10787 6158 10787 6152 10787 6152 10788 6158 10788 6159 10788 6152 10789 6159 10789 6153 10789 6155 10790 6157 10790 6160 10790 6160 10791 6157 10791 6161 10791 6160 10792 6161 10792 6162 10792 6162 10793 6161 10793 6163 10793 6162 10794 6163 10794 6164 10794 6164 10795 6163 10795 6165 10795 6164 10796 6165 10796 6166 10796 6166 10797 6165 10797 6167 10797 6166 10798 6167 10798 6168 10798 6169 10799 6170 10799 6171 10799 6171 10800 6170 10800 6172 10800 6171 10801 6172 10801 6173 10801 5920 10802 6172 10802 5922 10802 5922 10803 6172 10803 6170 10803 5922 10804 6170 10804 6167 10804 6167 10805 6170 10805 6169 10805 6167 10806 6169 10806 6168 10806 6163 10807 5916 10807 6165 10807 6165 10808 5916 10808 5918 10808 6165 10809 5918 10809 6167 10809 6167 10810 5918 10810 5923 10810 6167 10811 5923 10811 5922 10811 5950 10812 5951 10812 6152 10812 6152 10813 5951 10813 5912 10813 6152 10814 5912 10814 6157 10814 6157 10815 5912 10815 5954 10815 6157 10816 5954 10816 6161 10816 6161 10817 5954 10817 5953 10817 6161 10818 5953 10818 6163 10818 6163 10819 5953 10819 5952 10819 6163 10820 5952 10820 5916 10820 6174 632 6175 632 6012 632 6012 632 6175 632 6176 632 6012 10821 6176 10821 6177 10821 5992 10822 5991 10822 5994 10822 5994 10823 5991 10823 5995 10823 6002 10824 5980 10824 6012 10824 6012 10825 5980 10825 5979 10825 6012 10826 5979 10826 5978 10826 6012 10827 6007 10827 6006 10827 5991 10828 6012 10828 5983 10828 6000 632 6002 632 5998 632 5998 632 6002 632 6012 632 5998 632 6012 632 5996 632 5996 10829 6012 10829 5991 10829 6178 632 6012 632 6179 632 6179 10830 6012 10830 6177 10830 6179 10831 6177 10831 6180 10831 5986 10832 5988 10832 5991 10832 5991 10833 5988 10833 5990 10833 5991 10834 5990 10834 5995 10834 6178 632 6181 632 6012 632 6012 632 6181 632 6182 632 6012 10835 6182 10835 6183 10835 6009 632 6010 632 6006 632 6006 10836 6010 10836 6011 10836 6006 10837 6011 10837 6012 10837 5983 10838 5982 10838 5991 10838 5991 10839 5982 10839 5984 10839 5991 10840 5984 10840 5986 10840 5978 632 5977 632 6012 632 6012 10841 5977 10841 5976 10841 6012 10842 5976 10842 6174 10842 6183 632 6184 632 6012 632 6012 10843 6184 10843 6185 10843 6012 632 6185 632 6007 632 6183 10844 6182 10844 5958 10844 6186 10845 6185 10845 6184 10845 6007 10846 6185 10846 6008 10846 6008 10847 6185 10847 6186 10847 6008 10848 6186 10848 5738 10848 5738 10849 6186 10849 5955 10849 6183 10850 5958 10850 6184 10850 6184 10851 5958 10851 5959 10851 6184 10852 5959 10852 6186 10852 6186 10853 5959 10853 5960 10853 6186 10854 5960 10854 5955 10854 6177 10855 6176 10855 6175 10855 5967 10856 5958 10856 6182 10856 6182 10857 6181 10857 5967 10857 5967 10858 6181 10858 6178 10858 5967 10859 6178 10859 5965 10859 6178 10860 6179 10860 5965 10860 5965 10861 6179 10861 6180 10861 5965 10862 6180 10862 5963 10862 5963 10863 6180 10863 6177 10863 6177 10864 6175 10864 5963 10864 5963 10865 6175 10865 6174 10865 5963 10866 6174 10866 5961 10866 5961 10867 6174 10867 5976 10867 5961 10868 5976 10868 5716 10868 6187 10869 6188 10869 6189 10869 6190 10870 6191 10870 6018 10870 5733 10871 5734 10871 6192 10871 6192 10872 5734 10872 5735 10872 5735 10873 6019 10873 6192 10873 6192 10874 6019 10874 6018 10874 6192 10875 6018 10875 6193 10875 6187 10876 6018 10876 6194 10876 6194 10877 6018 10877 6021 10877 6194 10878 6021 10878 6195 10878 6187 10879 6189 10879 6018 10879 6018 10880 6189 10880 6196 10880 6018 10881 6196 10881 6190 10881 6191 10882 6197 10882 6018 10882 6018 10883 6197 10883 6198 10883 6018 10884 6198 10884 6193 10884 6041 10885 6199 10885 6033 10885 6033 10886 6199 10886 6034 10886 6195 10887 6021 10887 6031 10887 6195 10888 6031 10888 6200 10888 6200 10889 6031 10889 6034 10889 6200 10890 6034 10890 6201 10890 6201 10891 6034 10891 6199 10891 6052 10892 6054 10892 6202 10892 6202 10893 6054 10893 6143 10893 6202 10894 6143 10894 6119 10894 6052 10895 6202 10895 6053 10895 6053 10896 6202 10896 6203 10896 6053 10897 6203 10897 6204 10897 6205 10898 6206 10898 6207 10898 6207 10899 6206 10899 6203 10899 6207 10900 6203 10900 6208 10900 6208 10901 6203 10901 6202 10901 6201 10902 6199 10902 6209 10902 6209 10903 6199 10903 6041 10903 6209 10904 6041 10904 6210 10904 6210 10905 6041 10905 6053 10905 6210 10906 6053 10906 6211 10906 6211 10907 6053 10907 6204 10907 6212 10908 6213 10908 6214 10908 6173 10909 6215 10909 6216 10909 6217 10910 6172 10910 5920 10910 6216 10911 6218 10911 6219 10911 6173 10912 6216 10912 6220 10912 6220 10913 6216 10913 6219 10913 6220 10914 6219 10914 6221 10914 5920 10915 6222 10915 6217 10915 6217 10916 6222 10916 6223 10916 6217 10917 6223 10917 6213 10917 6213 10918 6223 10918 6224 10918 6213 10919 6224 10919 6214 10919 6173 10920 6172 10920 6215 10920 6215 10921 6172 10921 6217 10921 6215 10922 6217 10922 6216 10922 6216 10923 6217 10923 6213 10923 6216 10924 6213 10924 6218 10924 6218 10925 6213 10925 6212 10925 4568 10926 4570 10926 6225 10926 6112 10927 6102 10927 6226 10927 6112 10928 6226 10928 6100 10928 5940 10929 5943 10929 6227 10929 5943 10930 5838 10930 6098 10930 4569 10931 4567 10931 6228 10931 6228 10932 4567 10932 4566 10932 5941 10933 6229 10933 5942 10933 5942 10934 6229 10934 6228 10934 5942 10935 6228 10935 5937 10935 5937 10936 6228 10936 4566 10936 5937 10937 4566 10937 4564 10937 4554 10938 4565 10938 6230 10938 4565 10939 4568 10939 6230 10939 6230 10940 4568 10940 6225 10940 6230 10941 6225 10941 6231 10941 6231 10942 6225 10942 6232 10942 6231 10943 6232 10943 6226 10943 6226 10944 6232 10944 6227 10944 6226 10945 6227 10945 6100 10945 6100 10946 6227 10946 5943 10946 6100 10947 5943 10947 6099 10947 6099 10948 5943 10948 6098 10948 4570 10949 4569 10949 6225 10949 6225 10950 4569 10950 6228 10950 6225 10951 6228 10951 6232 10951 6232 10952 6228 10952 6229 10952 6232 10953 6229 10953 6227 10953 6227 10954 6229 10954 5941 10954 6227 10955 5941 10955 5940 10955 4554 10956 6230 10956 6087 10956 6087 10957 6230 10957 6231 10957 6087 10958 6231 10958 6079 10958 6079 10959 6231 10959 6226 10959 6079 10960 6226 10960 6077 10960 6077 10961 6226 10961 6102 10961 6077 10962 6102 10962 6081 10962 6233 10963 6190 10963 6234 10963 6234 10964 6190 10964 6196 10964 6234 10965 6196 10965 6221 10965 6221 10966 6196 10966 6235 10966 6233 10967 6234 10967 6236 10967 6237 10968 6238 10968 6239 10968 6191 10969 6190 10969 6233 10969 6197 10970 6240 10970 6241 10970 6242 10971 6243 10971 6236 10971 6242 10972 6219 10972 6244 10972 6244 10973 6219 10973 6218 10973 6244 10974 6218 10974 6212 10974 6242 10975 6236 10975 6219 10975 6219 10976 6236 10976 6234 10976 6219 10977 6234 10977 6221 10977 6197 10978 6241 10978 6198 10978 6198 10979 6241 10979 6245 10979 6198 10980 6245 10980 6193 10980 6240 10981 6197 10981 6246 10981 6246 10982 6197 10982 6191 10982 6246 10983 6191 10983 6247 10983 6243 10984 6239 10984 6236 10984 6236 10985 6239 10985 6238 10985 6236 10986 6238 10986 6233 10986 6233 10987 6238 10987 6237 10987 6233 10988 6237 10988 6191 10988 6191 10989 6237 10989 6248 10989 6191 10990 6248 10990 6247 10990 6249 10991 6250 10991 6251 10991 6252 10992 6253 10992 6254 10992 6254 10993 6253 10993 6255 10993 6254 10994 6255 10994 6256 10994 6250 10995 6257 10995 6251 10995 6251 10996 6257 10996 6252 10996 6251 10997 6252 10997 6258 10997 6258 10998 6252 10998 6254 10998 6258 10999 6254 10999 6259 10999 6260 11000 6261 11000 6262 11000 6208 11001 6263 11001 6207 11001 6207 11002 6263 11002 6264 11002 6207 11003 6264 11003 6205 11003 6205 11004 6264 11004 6260 11004 6205 11005 6260 11005 6206 11005 6206 11006 6260 11006 6262 11006 6261 11007 6249 11007 6262 11007 6262 11008 6249 11008 6251 11008 6262 11009 6251 11009 6265 11009 6265 11010 6251 11010 6258 11010 6265 11011 6258 11011 6266 11011 6266 11012 6258 11012 6259 11012 6266 11013 6259 11013 6267 11013 6203 11014 6206 11014 6262 11014 6267 11015 6268 11015 6266 11015 6266 11016 6268 11016 6203 11016 6266 11017 6203 11017 6265 11017 6265 11018 6203 11018 6262 11018 6269 11019 6270 11019 6271 11019 6272 11020 5949 11020 6149 11020 6259 11021 6273 11021 6267 11021 6267 11022 6273 11022 6274 11022 6267 11023 6274 11023 6275 11023 6275 11024 6274 11024 6149 11024 6275 11025 6149 11025 6151 11025 6254 11026 6256 11026 6276 11026 6276 11027 6256 11027 6277 11027 6276 11028 6277 11028 6271 11028 6271 11029 6277 11029 6278 11029 6271 11030 6278 11030 6269 11030 6259 11031 6254 11031 6273 11031 6273 11032 6254 11032 6276 11032 6273 11033 6276 11033 6274 11033 6274 11034 6276 11034 6271 11034 6274 11035 6271 11035 6149 11035 6149 11036 6271 11036 6270 11036 6149 11037 6270 11037 6272 11037 6223 11038 6279 11038 6224 11038 6280 11039 6281 11039 6282 11039 6283 11040 6284 11040 6285 11040 6243 11041 6242 11041 6286 11041 6286 11042 6242 11042 6244 11042 6286 11043 6244 11043 6287 11043 6287 11044 6244 11044 6212 11044 6288 11045 6289 11045 6290 11045 6290 11046 6289 11046 6247 11046 6247 11047 6248 11047 6290 11047 6290 11048 6248 11048 6237 11048 6290 11049 6237 11049 6239 11049 6245 11050 6241 11050 6288 11050 6288 11051 6241 11051 6240 11051 6288 11052 6240 11052 6289 11052 6289 11053 6240 11053 6246 11053 6289 11054 6246 11054 6247 11054 6288 11055 6291 11055 6292 11055 6245 11056 6288 11056 6193 11056 6193 11057 6288 11057 6292 11057 6193 11058 6292 11058 6192 11058 6293 11059 6294 11059 6295 11059 6295 11060 6294 11060 6296 11060 6295 11061 6296 11061 6297 11061 6297 11062 6296 11062 6285 11062 6284 11063 6298 11063 6285 11063 6285 11064 6298 11064 5607 11064 6285 11065 5607 11065 6297 11065 6299 11066 6300 11066 6301 11066 6301 11067 6300 11067 6302 11067 6280 11068 6282 11068 6303 11068 6222 11069 5920 11069 6304 11069 6304 11070 5920 11070 5919 11070 6304 11071 5919 11071 6305 11071 6305 11072 5919 11072 5648 11072 6305 11073 5648 11073 6306 11073 6279 11074 6223 11074 6307 11074 6223 11075 6222 11075 6307 11075 6307 11076 6222 11076 6304 11076 6307 11077 6304 11077 6282 11077 6282 11078 6304 11078 6305 11078 6282 11079 6305 11079 6303 11079 6303 11080 6305 11080 6306 11080 6212 11081 6214 11081 6287 11081 6287 11082 6214 11082 6308 11082 6287 11083 6308 11083 6286 11083 6286 11084 6308 11084 6290 11084 6286 11085 6290 11085 6243 11085 6243 11086 6290 11086 6239 11086 6281 11087 6309 11087 6282 11087 6282 11088 6309 11088 6299 11088 6282 11089 6299 11089 6307 11089 6307 11090 6299 11090 6301 11090 6307 11091 6301 11091 6279 11091 6279 11092 6301 11092 6308 11092 6279 11093 6308 11093 6224 11093 6224 11094 6308 11094 6214 11094 6302 11095 6283 11095 6301 11095 6301 11096 6283 11096 6285 11096 6301 11097 6285 11097 6308 11097 6308 11098 6285 11098 6296 11098 6308 11099 6296 11099 6290 11099 6290 11100 6296 11100 6294 11100 6290 11101 6294 11101 6288 11101 6288 11102 6294 11102 6293 11102 6288 11103 6293 11103 6291 11103 6310 11104 6311 11104 6312 11104 5948 11105 6313 11105 5828 11105 6269 11106 6278 11106 6314 11106 6315 11107 6316 11107 6317 11107 6317 11108 6318 11108 6315 11108 6315 11109 6318 11109 6319 11109 6315 11110 6319 11110 6320 11110 6320 11111 6319 11111 6261 11111 6261 11112 6260 11112 6320 11112 6320 11113 6260 11113 6264 11113 6320 11114 6264 11114 6321 11114 6264 11115 6263 11115 6321 11115 6321 11116 6263 11116 6208 11116 6321 11117 6208 11117 6202 11117 6255 11118 6253 11118 6318 11118 6318 11119 6253 11119 6252 11119 6252 11120 6257 11120 6318 11120 6318 11121 6257 11121 6250 11121 6318 11122 6250 11122 6319 11122 6319 11123 6250 11123 6249 11123 6319 11124 6249 11124 6261 11124 6317 11125 6322 11125 6318 11125 6318 11126 6322 11126 6323 11126 6318 11127 6323 11127 6255 11127 6255 11128 6323 11128 6324 11128 6255 11129 6324 11129 6256 11129 6256 11130 6324 11130 6314 11130 6256 11131 6314 11131 6277 11131 6277 11132 6314 11132 6278 11132 6313 11133 5948 11133 6325 11133 6326 11134 6327 11134 6325 11134 6325 11135 6327 11135 6328 11135 6325 11136 6328 11136 6313 11136 6313 11137 6328 11137 6329 11137 6313 11138 6329 11138 5828 11138 6310 11139 6326 11139 6311 11139 6311 11140 6326 11140 6325 11140 6311 11141 6325 11141 6272 11141 6272 11142 6325 11142 5948 11142 6272 11143 5948 11143 5949 11143 6330 11144 6331 11144 6332 11144 6332 11145 6331 11145 6333 11145 6332 11146 6333 11146 6334 11146 6334 11147 6333 11147 6335 11147 6334 11148 6335 11148 6336 11148 6336 11149 6335 11149 6337 11149 6336 11150 6337 11150 6338 11150 6338 11151 6337 11151 6339 11151 6338 11152 6339 11152 6312 11152 6312 11153 6339 11153 6340 11153 6312 11154 6340 11154 6310 11154 6272 11155 6270 11155 6311 11155 6311 11156 6270 11156 6269 11156 6311 11157 6269 11157 6312 11157 6312 11158 6269 11158 6314 11158 6312 11159 6314 11159 6338 11159 6338 11160 6314 11160 6324 11160 6338 11161 6324 11161 6336 11161 6336 11162 6324 11162 6323 11162 6336 11163 6323 11163 6334 11163 6334 11164 6323 11164 6322 11164 6334 11165 6322 11165 6332 11165 6332 11166 6322 11166 6317 11166 6332 11167 6317 11167 6330 11167 6330 11168 6317 11168 6316 11168 6330 11169 6316 11169 5865 11169 6341 11170 6342 11170 4577 11170 6343 95 4573 95 6342 95 6342 95 4573 95 4575 95 6342 95 4575 95 4577 95 4577 95 4580 95 6341 95 6341 11171 4580 11171 6344 11171 6341 11172 6344 11172 6345 11172 6345 95 6344 95 6346 95 6345 11173 6346 11173 6347 11173 6347 95 6346 95 6348 95 6347 11174 6348 11174 6349 11174 6349 95 6348 95 6350 95 6349 95 6350 95 6351 95 6351 11175 6350 11175 6352 11175 6351 95 6352 95 6353 95 6353 95 6352 95 6354 95 6353 95 6354 95 6355 95 6355 95 6354 95 6356 95 6355 95 6356 95 6357 95 6357 95 6356 95 6358 95 6357 95 6358 95 6359 95 6359 95 6358 95 6360 95 6359 95 6360 95 6361 95 6361 95 6360 95 6362 95 6361 95 6362 95 6343 95 6343 11176 6362 11176 4571 11176 6343 11177 4571 11177 4573 11177 6192 11178 6292 11178 5733 11178 5733 11179 6292 11179 6291 11179 5733 11180 6291 11180 5764 11180 5764 11181 6291 11181 6293 11181 5764 11182 6293 11182 5765 11182 5765 11183 6293 11183 5774 11183 5774 11184 6293 11184 6295 11184 5774 11185 6295 11185 6297 11185 5607 11186 5606 11186 6297 11186 6297 11187 5606 11187 5611 11187 5611 11188 5772 11188 6297 11188 6297 11189 5772 11189 5773 11189 6297 11190 5773 11190 5774 11190 6298 11191 6363 11191 6364 11191 6299 11192 6309 11192 6365 11192 5626 11193 124 11193 128 11193 5626 11194 128 11194 5627 11194 128 11195 6366 11195 5627 11195 5627 11196 6366 11196 6367 11196 5627 11197 6367 11197 5629 11197 5629 11198 6367 11198 6368 11198 5629 11199 6368 11199 5630 11199 5630 11200 6368 11200 5624 11200 5624 11201 6368 11201 5625 11201 5625 11202 6368 11202 6369 11202 5625 11203 6369 11203 5617 11203 5617 11204 6369 11204 6370 11204 5617 11205 6370 11205 5619 11205 6280 11206 6303 11206 6371 11206 6371 11207 6303 11207 6306 11207 5619 11208 6370 11208 5621 11208 5621 11209 6370 11209 6371 11209 5621 11210 6371 11210 5622 11210 5622 11211 6371 11211 6306 11211 5622 11212 6306 11212 5648 11212 6280 11213 6371 11213 6281 11213 6281 11214 6371 11214 6370 11214 6281 11215 6370 11215 6309 11215 6299 11216 6365 11216 6300 11216 6298 11217 6284 11217 6363 11217 6363 11218 6284 11218 6283 11218 6363 11219 6283 11219 6365 11219 6365 11220 6283 11220 6302 11220 6365 11221 6302 11221 6300 11221 6372 11222 5601 11222 6373 11222 6373 11223 5601 11223 5605 11223 6373 11224 5605 11224 6364 11224 6364 11225 5605 11225 5607 11225 6364 11226 5607 11226 6298 11226 6309 11227 6370 11227 6365 11227 6365 11228 6370 11228 6369 11228 6365 11229 6369 11229 6363 11229 6363 11230 6369 11230 6368 11230 6363 11231 6368 11231 6364 11231 6364 11232 6368 11232 6367 11232 6364 11233 6367 11233 6373 11233 6373 11234 6367 11234 6366 11234 6373 11235 6366 11235 6372 11235 6372 11236 6366 11236 128 11236 6372 11237 128 11237 5601 11237 5601 11238 128 11238 129 11238 5601 11239 129 11239 130 11239 6329 11240 6328 11240 6374 11240 6337 11241 6375 11241 6339 11241 6376 11242 244 11242 245 11242 5867 11243 228 11243 244 11243 6330 11244 6377 11244 6331 11244 6331 11245 6377 11245 6378 11245 6331 11246 6378 11246 6333 11246 244 11247 6376 11247 5867 11247 5867 11248 6376 11248 6379 11248 5867 11249 6379 11249 5869 11249 5869 11250 6379 11250 6377 11250 5869 11251 6377 11251 5866 11251 5866 11252 6377 11252 6330 11252 5866 11253 6330 11253 5865 11253 6375 11254 6337 11254 6378 11254 6378 11255 6337 11255 6335 11255 6378 11256 6335 11256 6333 11256 6328 11257 6327 11257 6374 11257 6374 11258 6327 11258 6326 11258 6374 11259 6326 11259 6380 11259 6380 11260 6326 11260 6310 11260 6380 11261 6310 11261 6340 11261 6381 11262 5833 11262 6380 11262 6380 11263 5833 11263 5831 11263 6380 11264 5831 11264 6374 11264 6374 11265 5831 11265 5830 11265 6374 11266 5830 11266 6329 11266 6329 11267 5830 11267 5829 11267 6329 11268 5829 11268 5828 11268 6382 11269 5826 11269 6381 11269 6381 11270 5826 11270 5834 11270 6381 11271 5834 11271 5833 11271 6383 11272 5823 11272 6384 11272 6384 11273 5823 11273 5824 11273 6384 11274 5824 11274 6382 11274 6382 11275 5824 11275 5827 11275 6382 11276 5827 11276 5826 11276 246 11277 5823 11277 245 11277 245 11278 5823 11278 6383 11278 245 11279 6383 11279 6376 11279 6376 11280 6383 11280 6384 11280 6376 11281 6384 11281 6379 11281 6379 11282 6384 11282 6382 11282 6379 11283 6382 11283 6377 11283 6377 11284 6382 11284 6381 11284 6377 11285 6381 11285 6378 11285 6378 11286 6381 11286 6380 11286 6378 11287 6380 11287 6375 11287 6375 11288 6380 11288 6340 11288 6375 11289 6340 11289 6339 11289 6119 11290 6118 11290 6315 11290 6315 11291 6320 11291 6119 11291 6119 11292 6320 11292 6321 11292 6119 11293 6321 11293 6202 11293 5863 11294 5865 11294 6316 11294 5863 11295 6316 11295 5875 11295 6118 11296 6123 11296 6315 11296 6315 11297 6123 11297 6113 11297 6315 11298 6113 11298 6316 11298 6316 11299 6113 11299 6124 11299 6316 11300 6124 11300 5875 11300 6385 11301 6342 11301 6386 11301 6386 11302 6342 11302 6341 11302 6386 11303 6341 11303 6387 11303 6387 11304 6341 11304 6345 11304 6387 11304 6345 11304 6388 11304 6388 11305 6345 11305 6347 11305 6388 11305 6347 11305 6389 11305 6389 11306 6347 11306 6349 11306 6389 11307 6349 11307 6390 11307 6390 11308 6349 11308 6351 11308 6390 11308 6351 11308 6391 11308 6391 11309 6351 11309 6353 11309 6391 11310 6353 11310 6392 11310 6392 11311 6353 11311 6355 11311 6392 11312 6355 11312 6393 11312 6393 11313 6355 11313 6357 11313 6393 11313 6357 11313 6394 11313 6394 11314 6357 11314 6359 11314 6394 11314 6359 11314 6395 11314 6395 11315 6359 11315 6361 11315 6395 11316 6361 11316 6396 11316 6396 11317 6361 11317 6343 11317 6396 11318 6343 11318 6385 11318 6385 11319 6343 11319 6342 11319 6389 95 6390 95 6397 95 6397 95 6390 95 6391 95 6397 95 6391 95 6392 95 6386 95 6387 95 6397 95 6397 95 6387 95 6388 95 6397 95 6388 95 6389 95 6395 95 6396 95 6397 95 6397 11320 6396 11320 6385 11320 6397 11321 6385 11321 6386 11321 6392 11322 6393 11322 6397 11322 6397 95 6393 95 6394 95 6397 95 6394 95 6395 95 6398 95 6399 95 6268 95 6268 11323 6267 11323 6275 11323 6400 95 6401 95 6398 95 4574 95 4572 95 4576 95 4576 95 4572 95 6150 95 4576 11324 6150 11324 4578 11324 4578 95 6150 95 6154 95 4578 95 6154 95 4579 95 6268 95 4572 95 6402 95 6268 11325 6275 11325 4572 11325 4572 11326 6275 11326 6151 11326 4572 11327 6151 11327 6150 11327 6403 95 6404 95 6168 95 6405 95 6164 95 6404 95 6404 95 6164 95 6166 95 6404 11328 6166 11328 6168 11328 6154 11329 6153 11329 4579 11329 4579 11330 6153 11330 6159 11330 4579 11331 6159 11331 6406 11331 6406 11332 6159 11332 6158 11332 6406 95 6158 95 6156 95 6407 95 6235 95 6408 95 6408 11333 6235 11333 6409 11333 6408 95 6409 95 6410 95 6410 11334 6409 11334 6411 11334 6410 11335 6411 11335 6412 11335 6412 95 6411 95 6413 95 6168 95 6169 95 6403 95 6403 11336 6169 11336 6171 11336 6403 95 6171 95 6407 95 6407 95 6171 95 6173 95 6407 95 6173 95 6235 95 6235 95 6173 95 6220 95 6235 95 6220 95 6221 95 6156 95 6155 95 6406 95 6406 95 6155 95 6160 95 6406 11337 6160 11337 6405 11337 6405 95 6160 95 6162 95 6405 95 6162 95 6164 95 6414 95 6415 95 6416 95 6402 11338 6413 11338 6268 11338 6268 11339 6413 11339 6411 11339 6268 11340 6411 11340 6398 11340 6398 11341 6411 11341 6417 11341 6398 95 6417 95 6400 95 6400 11342 6417 11342 6414 11342 6400 95 6414 95 6418 95 6418 95 6414 95 6416 95 4572 11343 4571 11343 6362 11343 4572 11344 6362 11344 6402 11344 6402 11345 6362 11345 6360 11345 6402 11346 6360 11346 6413 11346 6413 11347 6360 11347 6358 11347 6413 11348 6358 11348 6412 11348 6412 11349 6358 11349 6356 11349 6412 11350 6356 11350 6410 11350 6410 11351 6356 11351 6354 11351 6410 11351 6354 11351 6408 11351 6408 11352 6354 11352 6352 11352 6408 11353 6352 11353 6407 11353 6407 11354 6352 11354 6350 11354 6407 11355 6350 11355 6403 11355 6403 11356 6350 11356 6348 11356 6403 11357 6348 11357 6404 11357 6404 11358 6348 11358 6346 11358 6404 11359 6346 11359 6405 11359 6405 11360 6346 11360 6344 11360 6405 11361 6344 11361 6406 11361 6406 11362 6344 11362 4580 11362 6406 11362 4580 11362 4579 11362 6203 11363 6268 11363 6399 11363 6203 11364 6399 11364 6204 11364 6204 11365 6399 11365 6398 11365 6204 11366 6398 11366 6211 11366 6188 11367 6411 11367 6409 11367 6235 11368 6196 11368 6409 11368 6409 11369 6196 11369 6189 11369 6409 11370 6189 11370 6188 11370 6211 11371 6398 11371 6401 11371 6211 11372 6401 11372 6210 11372 6210 11373 6401 11373 6400 11373 6210 11374 6400 11374 6209 11374 6209 11375 6400 11375 6201 11375 6201 11376 6400 11376 6418 11376 6195 11377 6415 11377 6414 11377 6195 11378 6414 11378 6194 11378 6194 11379 6414 11379 6417 11379 6194 11380 6417 11380 6187 11380 6187 11381 6417 11381 6411 11381 6187 11382 6411 11382 6188 11382 6415 11383 6195 11383 6200 11383 6415 11384 6200 11384 6416 11384 6416 11385 6200 11385 6201 11385 6416 11386 6201 11386 6418 11386 4550 633 4556 633 4544 633 4544 633 4556 633 4553 633 4544 633 4553 633 4527 633 4527 11387 4553 11387 4528 11387 4492 11388 4490 11388 6419 11388 6419 633 4490 633 4487 633 6419 633 4487 633 4483 633 4498 633 4496 633 6419 633 6419 11389 4496 11389 4494 11389 6419 11390 4494 11390 4492 11390 4468 11388 4466 11388 6419 11388 6419 633 4466 633 4472 633 6419 633 4472 633 4498 633 4483 11391 4476 11391 6419 11391 6419 11392 4476 11392 4475 11392 6419 11393 4475 11393 4468 11393 1446 11394 4690 11394 1448 11394 1448 11394 4690 11394 4686 11394 6420 11395 6421 11395 6422 11395 6423 11396 6424 11396 6425 11396 6426 11397 6427 11397 6428 11397 6423 633 6425 633 6429 633 6430 633 6431 633 6432 633 6433 633 6434 633 6435 633 6435 633 6434 633 6436 633 6435 633 6436 633 6437 633 6437 11398 6436 11398 6438 11398 6437 633 6438 633 6424 633 6424 633 6438 633 6439 633 6424 633 6439 633 6425 633 6428 11399 6427 11399 6440 11399 6440 11400 6427 11400 6441 11400 6440 633 6441 633 6442 633 6443 633 210 633 6444 633 6443 11401 6444 11401 6445 11401 6445 633 6444 633 6446 633 6445 11402 6446 11402 6447 11402 6447 11403 6446 11403 6448 11403 6428 11404 6449 11404 6426 11404 6426 633 6449 633 6450 633 6426 11405 6450 11405 6451 11405 6451 633 6450 633 6452 633 6451 11406 6452 11406 6453 11406 6453 633 6452 633 6454 633 6453 11407 6454 11407 6455 11407 6455 633 6454 633 6456 633 6456 11408 6457 11408 6458 11408 6458 11409 6457 11409 6459 11409 6458 11410 6459 11410 6460 11410 6460 11411 6459 11411 6461 11411 6460 633 6461 633 6462 633 6462 633 6461 633 6463 633 6462 633 6463 633 6464 633 6441 11412 6465 11412 6442 11412 6442 633 6465 633 6466 633 6442 11413 6466 11413 6467 11413 6467 633 6466 633 6468 633 6467 11414 6468 11414 6469 11414 6470 633 6469 633 6429 633 6470 11415 6429 11415 6471 11415 6471 11416 6429 11416 6425 11416 6463 11417 6472 11417 6464 11417 6464 633 6472 633 6473 633 6464 633 6473 633 6474 633 6474 7585 6473 7585 6475 7585 6432 11418 6431 11418 6476 11418 6476 11419 6431 11419 6477 11419 6476 11420 6477 11420 6478 11420 6478 633 6477 633 6479 633 6478 11421 6479 11421 6480 11421 6480 633 6479 633 6481 633 6480 11422 6481 11422 6482 11422 6482 11423 6481 11423 6483 11423 6482 11424 6483 11424 6484 11424 6483 633 6485 633 6484 633 6484 11425 6485 11425 6486 11425 6484 11426 6486 11426 6487 11426 6487 633 6486 633 6488 633 6487 11427 6488 11427 6448 11427 6448 633 6488 633 6489 633 6448 633 6489 633 6447 633 6420 11428 6422 11428 6490 11428 6490 11429 6422 11429 6491 11429 6490 11430 6491 11430 6492 11430 6492 633 6491 633 6493 633 6430 633 6432 633 6494 633 6494 11431 6432 11431 6495 11431 6494 633 6495 633 6496 633 6496 633 6495 633 6497 633 6496 633 6497 633 6498 633 6498 633 6497 633 6499 633 6498 11432 6499 11432 6433 11432 6433 633 6499 633 6500 633 6433 633 6500 633 6434 633 6501 633 6493 633 6502 633 6501 633 6502 633 6503 633 6503 633 6502 633 6504 633 6503 11433 6504 11433 6505 11433 6505 633 6504 633 6506 633 6505 633 6506 633 6507 633 6507 11434 6506 11434 6508 11434 6507 633 6508 633 6509 633 6509 11435 6508 11435 6510 11435 6509 633 6510 633 6511 633 6511 11436 6510 11436 6512 11436 6512 633 6513 633 6514 633 6513 633 6515 633 6514 633 6514 633 6515 633 6516 633 6514 11437 6516 11437 6517 11437 6517 633 6516 633 6518 633 6517 11438 6518 11438 6519 11438 6519 11439 6518 11439 6520 11439 6519 633 6520 633 6521 633 6521 11440 6520 11440 6522 11440 6521 633 6522 633 6523 633 6523 633 6522 633 6524 633 6523 7585 6524 7585 6475 7585 6525 11441 6526 11441 6527 11441 6526 11442 6528 11442 6527 11442 6527 11443 6528 11443 6529 11443 6527 11444 6529 11444 6530 11444 6530 11445 6531 11445 6527 11445 6527 11446 6531 11446 6532 11446 6527 11447 6532 11447 6533 11447 6534 11448 4234 11448 6535 11448 6535 11449 4234 11449 6533 11449 6536 11450 6537 11450 4234 11450 4234 11451 6537 11451 6538 11451 4234 11452 6538 11452 6539 11452 6534 11453 6540 11453 4234 11453 4234 11454 6540 11454 6541 11454 4234 11455 6541 11455 6542 11455 6542 11456 6543 11456 4234 11456 4234 11457 6543 11457 6544 11457 4234 11458 6544 11458 6536 11458 6539 11459 6545 11459 4234 11459 4234 11460 6545 11460 6546 11460 4234 11461 6546 11461 6547 11461 6547 11462 6548 11462 4234 11462 4234 11463 6548 11463 6549 11463 4234 11464 6549 11464 6550 11464 6550 11465 6551 11465 4234 11465 4234 11466 6551 11466 6552 11466 4234 11467 6552 11467 6553 11467 6553 11468 6554 11468 4234 11468 4234 11469 6554 11469 6555 11469 4234 11470 6555 11470 6556 11470 6556 11471 6557 11471 4234 11471 4234 11472 6557 11472 6558 11472 4234 11473 6558 11473 6559 11473 6559 11474 6560 11474 4234 11474 4234 11475 6560 11475 6561 11475 4234 11476 6561 11476 6562 11476 6562 11477 6563 11477 4234 11477 4234 11478 6563 11478 6564 11478 4234 11479 6564 11479 4232 11479 6565 11480 6566 11480 6527 11480 6565 11481 6527 11481 6567 11481 6568 11482 6569 11482 6570 11482 6570 11483 6569 11483 6571 11483 6570 11484 6571 11484 6572 11484 6572 11485 6573 11485 6570 11485 6570 11486 6573 11486 6574 11486 6570 11487 6574 11487 6567 11487 6575 11488 6576 11488 6527 11488 6527 11489 6576 11489 6577 11489 6527 11490 6577 11490 6578 11490 6566 11491 6579 11491 6527 11491 6527 11492 6579 11492 6580 11492 6527 11493 6580 11493 6581 11493 6581 11494 6582 11494 6527 11494 6527 11495 6582 11495 6583 11495 6527 11496 6583 11496 6575 11496 6584 11497 6585 11497 6586 11497 6578 11498 6587 11498 6527 11498 6527 11499 6587 11499 6588 11499 6527 11500 6588 11500 6589 11500 6589 11501 6590 11501 6527 11501 6527 11502 6590 11502 6591 11502 6527 11503 6591 11503 6592 11503 6592 11504 6586 11504 6527 11504 6527 11505 6586 11505 6593 11505 6527 11506 6593 11506 6525 11506 6594 7585 6584 7585 6595 7585 6595 7585 6584 7585 6586 7585 6595 7585 6586 7585 6596 7585 6596 7585 6586 7585 6592 7585 6596 11507 6592 11507 6597 11507 6598 11508 6599 11508 6570 11508 6570 11509 6599 11509 6600 11509 6570 11510 6600 11510 6568 11510 6601 632 6602 632 6598 632 6533 11511 4234 11511 6527 11511 6527 11512 4234 11512 4231 11512 6527 11513 4231 11513 6603 11513 6603 11514 4231 11514 4235 11514 6603 11515 4235 11515 6604 11515 4235 11516 4236 11516 6604 11516 6604 11517 4236 11517 6605 11517 6604 11518 6605 11518 6606 11518 6567 11519 6527 11519 6570 11519 6570 11520 6527 11520 6603 11520 6570 11521 6603 11521 6607 11521 6607 11522 6603 11522 6604 11522 6607 11523 6604 11523 6608 11523 6608 11524 6604 11524 6606 11524 6608 11525 6606 11525 6609 11525 6598 11526 6570 11526 6601 11526 6601 11527 6570 11527 6607 11527 6601 11528 6607 11528 6610 11528 6610 11529 6607 11529 6608 11529 6610 11530 6608 11530 6611 11530 6611 11531 6608 11531 6609 11531 6611 11532 6609 11532 6612 11532 6613 11533 6614 11533 6615 11533 6616 11534 6617 11534 6618 11534 6618 11535 6617 11535 6619 11535 6620 11536 6621 11536 6622 11536 6622 11537 6621 11537 6619 11537 6622 11538 6619 11538 6623 11538 6623 11539 6619 11539 6617 11539 6624 11540 4327 11540 4326 11540 6625 11541 4326 11541 6618 11541 6618 11542 4326 11542 6626 11542 6618 11543 6626 11543 6616 11543 6614 11544 6624 11544 6615 11544 6615 11545 6624 11545 4326 11545 6615 11546 4326 11546 6627 11546 6627 11547 4326 11547 6625 11547 6628 11548 718 11548 721 11548 721 11549 722 11549 6628 11549 6628 11550 722 11550 724 11550 6628 11551 724 11551 6629 11551 6629 11552 724 11552 723 11552 6629 11553 723 11553 6630 11553 6630 11554 723 11554 6615 11554 6615 11555 723 11555 1781 11555 6615 11556 1781 11556 6613 11556 6631 11557 6632 11557 6633 11557 6633 11558 6634 11558 6635 11558 6636 11559 6637 11559 6638 11559 6638 11560 6637 11560 6639 11560 6634 11561 6640 11561 6635 11561 6635 11562 6640 11562 6641 11562 6635 11563 6641 11563 6637 11563 6637 11564 6641 11564 6642 11564 6637 11565 6642 11565 6639 11565 6643 11566 6631 11566 6644 11566 6644 11567 6631 11567 6633 11567 6644 11568 6633 11568 6645 11568 6645 11569 6633 11569 6635 11569 6645 11570 6635 11570 6646 11570 6646 11571 6635 11571 6637 11571 6646 11572 6637 11572 6647 11572 6647 11573 6637 11573 6648 11573 6648 11574 6637 11574 6636 11574 6648 11575 6636 11575 6649 11575 187 11576 174 11576 185 11576 210 11577 190 11577 6650 11577 6650 11578 190 11578 188 11578 233 11579 6651 11579 222 11579 222 11580 6651 11580 216 11580 6651 11581 6652 11581 216 11581 216 11582 6652 11582 6653 11582 216 11583 6653 11583 217 11583 217 11584 6653 11584 6654 11584 217 11585 6654 11585 182 11585 182 11586 6654 11586 183 11586 183 11587 6654 11587 6655 11587 183 11588 6655 11588 184 11588 6655 11589 6656 11589 184 11589 184 11590 6656 11590 6657 11590 184 11591 6657 11591 185 11591 185 11592 6657 11592 6658 11592 185 11593 6658 11593 187 11593 187 11594 6658 11594 6659 11594 187 11595 6659 11595 188 11595 188 11596 6659 11596 6660 11596 188 11597 6660 11597 6650 11597 6661 632 6662 632 6663 632 6664 632 4266 632 4265 632 4 632 4265 632 6665 632 4135 632 6666 632 3 632 3 632 6666 632 6667 632 6668 11598 6669 11598 6670 11598 4256 11599 6602 11599 6601 11599 6671 632 6672 632 6666 632 6666 11600 6672 11600 6673 11600 6667 11601 6674 11601 3 11601 3 11602 6674 11602 6675 11602 3 11603 6675 11603 6676 11603 6668 11604 6670 11604 6677 11604 6678 632 6679 632 6663 632 6663 11605 6679 11605 6680 11605 6665 632 6681 632 4 632 4 632 6681 632 6682 632 4 632 6682 632 325 632 325 632 6682 632 6683 632 325 11606 6683 11606 323 11606 323 11607 6683 11607 6684 11607 323 11608 6684 11608 6685 11608 984 632 1038 632 983 632 983 632 1038 632 4374 632 983 632 4374 632 6686 632 6686 11609 4374 11609 6687 11609 6686 11610 6687 11610 6685 11610 6685 11611 6687 11611 6688 11611 6685 11612 6688 11612 323 11612 6689 632 6690 632 6691 632 6691 11613 6690 11613 4256 11613 4256 11614 6690 11614 6602 11614 6691 632 6692 632 6689 632 6689 632 6692 632 6693 632 6689 632 6693 632 6694 632 6612 632 4257 632 6611 632 6611 632 4257 632 4256 632 6611 632 4256 632 6610 632 6610 632 4256 632 6601 632 6669 11615 6678 11615 6670 11615 6670 11616 6678 11616 6663 11616 6670 11617 6663 11617 6695 11617 6695 11618 6663 11618 6696 11618 6695 11619 6696 11619 6697 11619 6422 632 6698 632 6666 632 6666 11620 6698 11620 6699 11620 6666 11621 6699 11621 6667 11621 6675 632 6700 632 6676 632 6676 11622 6700 11622 6695 11622 6676 632 6695 632 6701 632 6701 632 6695 632 6697 632 6664 11623 4265 11623 6702 11623 6702 11624 4265 11624 4 11624 6702 632 4 632 6703 632 6703 11625 4 11625 3 11625 6703 632 3 632 6704 632 6704 632 3 632 6676 632 6704 632 6676 632 6694 632 6694 11626 6676 11626 6705 11626 6694 11627 6705 11627 6689 11627 6680 632 6706 632 6663 632 6663 11628 6706 11628 6707 11628 6663 11629 6707 11629 6708 11629 6709 11630 6422 11630 6710 11630 6710 632 6422 632 6666 632 6710 11631 6666 11631 6711 11631 6711 11632 6666 11632 6673 11632 6712 632 6713 632 6708 632 6708 632 6713 632 6714 632 6708 11633 6714 11633 6663 11633 6663 11634 6714 11634 6715 11634 6663 632 6715 632 6661 632 5697 632 5972 632 5698 632 5698 11635 5972 11635 5971 11635 5698 11636 5971 11636 6670 11636 6670 632 5971 632 6677 632 6677 632 5971 632 5970 632 6677 632 5970 632 5583 632 5583 11637 5970 11637 5969 11637 5583 632 5969 632 5584 632 369 11638 368 11638 4233 11638 6716 11639 6717 11639 4232 11639 4309 11640 4233 11640 6718 11640 6718 11641 4233 11641 4232 11641 1656 11642 1655 11642 4309 11642 4309 98 1655 98 1654 98 4309 11643 1654 11643 4233 11643 4233 11644 1654 11644 1664 11644 4233 11645 1664 11645 369 11645 6621 98 6620 98 6719 98 6717 11646 6720 11646 4232 11646 4232 11647 6720 11647 6721 11647 4232 11648 6721 11648 6722 11648 6722 11649 6723 11649 4232 11649 4232 11650 6723 11650 6724 11650 4232 11651 6724 11651 6718 11651 6719 98 6725 98 6621 98 6621 98 6725 98 6726 98 6621 98 6726 98 6727 98 6727 98 6728 98 6621 98 6621 98 6728 98 6729 98 6621 11652 6729 11652 4232 11652 4232 11653 6729 11653 6730 11653 4232 11654 6730 11654 6716 11654 6731 11655 6732 11655 6733 11655 6638 11656 6734 11656 6735 11656 6638 11657 6735 11657 6636 11657 6636 11658 6735 11658 6736 11658 6636 11659 6736 11659 6649 11659 6737 11660 6738 11660 6739 11660 6739 11661 6738 11661 6740 11661 6739 11662 6740 11662 6741 11662 6740 11663 6742 11663 6741 11663 6741 11664 6742 11664 6743 11664 6741 11665 6743 11665 6744 11665 6744 11666 6743 11666 6745 11666 6744 11667 6745 11667 6746 11667 6746 11668 6745 11668 6747 11668 6746 11669 6747 11669 6748 11669 6748 11670 6747 11670 6731 11670 6748 11671 6731 11671 6749 11671 6749 11672 6731 11672 6733 11672 6749 11673 6733 11673 6750 11673 6750 11674 6733 11674 6751 11674 6732 11675 6736 11675 6733 11675 6733 11676 6736 11676 6735 11676 6733 11677 6735 11677 6751 11677 6751 11678 6735 11678 6734 11678 6751 11679 6734 11679 6752 11679 6704 11680 562 11680 6703 11680 6703 11681 562 11681 561 11681 6703 11682 561 11682 6702 11682 6702 11683 561 11683 560 11683 6702 11684 560 11684 6664 11684 6664 11685 560 11685 558 11685 4256 11686 554 11686 6691 11686 6691 11687 554 11687 564 11687 6691 11688 564 11688 6692 11688 6692 11689 564 11689 563 11689 6692 11690 563 11690 6693 11690 6693 11690 563 11690 565 11690 6693 11691 565 11691 6694 11691 6694 11692 565 11692 559 11692 117 11693 104 11693 103 11693 102 11694 89 11694 88 11694 134 11695 140 11695 156 11695 98 11696 97 11696 132 11696 156 11697 6753 11697 134 11697 134 11698 6753 11698 6754 11698 134 11699 6754 11699 132 11699 132 11700 6754 11700 6755 11700 132 11701 6755 11701 98 11701 98 11702 6755 11702 6756 11702 98 11703 6756 11703 99 11703 6756 11704 6757 11704 99 11704 99 11705 6757 11705 6758 11705 99 11706 6758 11706 100 11706 118 11707 117 11707 6759 11707 6759 11708 117 11708 103 11708 6759 11709 103 11709 6760 11709 6760 11710 103 11710 102 11710 6760 11711 102 11711 6761 11711 6761 11694 102 11694 88 11694 6761 11712 88 11712 6762 11712 6762 11713 88 11713 100 11713 6762 11714 100 11714 6763 11714 6763 11715 100 11715 6758 11715 313 11716 312 11716 6764 11716 6765 11717 6766 11717 6767 11717 6768 11718 6769 11718 6770 11718 6771 11719 6772 11719 6773 11719 6773 11720 6772 11720 6774 11720 6773 11721 6774 11721 6775 11721 6776 11722 6777 11722 6778 11722 6778 11723 6777 11723 6779 11723 6770 11724 6780 11724 6781 11724 6781 11725 6780 11725 6782 11725 6781 11726 6782 11726 6783 11726 6783 11727 6782 11727 6784 11727 6783 11728 6784 11728 6785 11728 6769 11729 6786 11729 6770 11729 6770 11730 6786 11730 6787 11730 6770 11731 6787 11731 6780 11731 6766 11732 6765 11732 6788 11732 6788 11733 6765 11733 6789 11733 6788 11734 6789 11734 6790 11734 418 11735 420 11735 6791 11735 6791 11736 420 11736 422 11736 6791 11737 422 11737 445 11737 442 11738 6792 11738 440 11738 440 11739 6792 11739 6791 11739 440 11740 6791 11740 438 11740 438 11741 6791 11741 445 11741 6793 11742 477 11742 479 11742 479 11743 481 11743 6793 11743 6793 11744 481 11744 483 11744 6793 11745 483 11745 6791 11745 6791 11746 483 11746 485 11746 6791 11747 485 11747 487 11747 487 11748 488 11748 6791 11748 6791 11749 488 11749 392 11749 6791 11750 392 11750 418 11750 435 11751 464 11751 6794 11751 442 11752 423 11752 6792 11752 6792 11753 423 11753 425 11753 6792 11754 425 11754 427 11754 427 11755 429 11755 6792 11755 6792 11756 429 11756 431 11756 6792 11757 431 11757 433 11757 464 11758 462 11758 6794 11758 6794 11759 462 11759 460 11759 6794 11760 460 11760 458 11760 458 11761 456 11761 6794 11761 6794 11762 456 11762 454 11762 6794 11763 454 11763 452 11763 6790 11764 6795 11764 6788 11764 6788 11765 6795 11765 6796 11765 6788 11766 6796 11766 6766 11766 6766 11767 6796 11767 6797 11767 6766 11768 6797 11768 6767 11768 6767 11769 6797 11769 4321 11769 6767 11770 4321 11770 316 11770 316 11771 4321 11771 315 11771 398 11772 396 11772 307 11772 307 11773 396 11773 394 11773 307 11774 394 11774 308 11774 398 11775 307 11775 400 11775 400 11776 307 11776 6798 11776 400 11777 6798 11777 402 11777 452 11778 450 11778 6794 11778 6794 11779 450 11779 448 11779 6794 11780 448 11780 447 11780 447 11781 416 11781 6794 11781 6794 11782 416 11782 414 11782 6794 11783 414 11783 6798 11783 414 11784 412 11784 6798 11784 6798 11785 412 11785 410 11785 6798 11786 410 11786 409 11786 409 11787 406 11787 6798 11787 6798 11788 406 11788 404 11788 6798 11789 404 11789 402 11789 6799 11790 386 11790 6800 11790 6800 11791 386 11791 389 11791 6800 11792 389 11792 6801 11792 6801 11793 389 11793 535 11793 6801 11794 535 11794 537 11794 537 11795 539 11795 6801 11795 6801 11796 539 11796 541 11796 6801 11797 541 11797 543 11797 543 11798 545 11798 6801 11798 6801 11799 545 11799 547 11799 6801 11800 547 11800 549 11800 549 11801 551 11801 6801 11801 6801 11802 551 11802 532 11802 6801 11803 532 11803 530 11803 530 11804 528 11804 6801 11804 6801 11805 528 11805 527 11805 6801 11806 527 11806 525 11806 525 11807 523 11807 6801 11807 6801 11808 523 11808 521 11808 6801 11809 521 11809 519 11809 519 11810 517 11810 6801 11810 6801 11811 517 11811 515 11811 6801 11812 515 11812 513 11812 513 11813 512 11813 6801 11813 6801 11814 512 11814 491 11814 6801 11815 491 11815 6802 11815 6802 11816 491 11816 493 11816 6802 11817 493 11817 495 11817 495 11818 497 11818 6802 11818 6802 11819 497 11819 499 11819 6802 11820 499 11820 501 11820 501 11821 503 11821 6802 11821 6802 11822 503 11822 505 11822 6802 11823 505 11823 507 11823 507 11824 509 11824 6802 11824 6802 11825 509 11825 467 11825 6802 11826 467 11826 469 11826 471 11827 473 11827 6793 11827 6793 11828 473 11828 475 11828 6793 11829 475 11829 477 11829 6790 11830 6768 11830 6795 11830 6795 11831 6768 11831 6770 11831 6795 11832 6770 11832 6803 11832 6803 11833 6770 11833 6781 11833 6803 11834 6781 11834 6804 11834 6804 11835 6781 11835 6783 11835 6804 11836 6783 11836 6778 11836 6778 11837 6783 11837 6785 11837 6778 11838 6785 11838 6776 11838 312 11839 310 11839 6764 11839 6764 11840 310 11840 6805 11840 6764 11841 6805 11841 6806 11841 6806 11842 6805 11842 6807 11842 6806 11843 6807 11843 6808 11843 6808 11844 6807 11844 6809 11844 6808 11845 6809 11845 6810 11845 6810 11846 6809 11846 6811 11846 6810 11847 6811 11847 6812 11847 6812 11848 6811 11848 6813 11848 6812 11849 6813 11849 6774 11849 469 11850 471 11850 6802 11850 6802 11851 471 11851 6793 11851 6802 11852 6793 11852 6814 11852 6814 11853 6793 11853 6791 11853 6814 11854 6791 11854 6815 11854 6815 11855 6791 11855 6792 11855 6815 11856 6792 11856 6794 11856 6794 11857 6792 11857 433 11857 6794 11858 433 11858 435 11858 6779 11859 6775 11859 6778 11859 6778 11860 6775 11860 6774 11860 6778 11861 6774 11861 6804 11861 6804 11862 6774 11862 6813 11862 6804 11863 6813 11863 6803 11863 6803 11864 6813 11864 6811 11864 6803 11865 6811 11865 6795 11865 6795 11866 6811 11866 6809 11866 6795 11867 6809 11867 6796 11867 6796 11868 6809 11868 6807 11868 6796 11869 6807 11869 6797 11869 6797 11870 6807 11870 6805 11870 6797 11871 6805 11871 4321 11871 4321 11872 6805 11872 310 11872 6771 11873 6799 11873 6772 11873 6772 11874 6799 11874 6800 11874 6772 11875 6800 11875 6774 11875 6774 11876 6800 11876 6801 11876 6774 11877 6801 11877 6812 11877 6812 11878 6801 11878 6802 11878 6812 11879 6802 11879 6810 11879 6810 11880 6802 11880 6814 11880 6810 11881 6814 11881 6808 11881 6808 11882 6814 11882 6815 11882 6808 11883 6815 11883 6806 11883 6806 11884 6815 11884 6794 11884 6806 11885 6794 11885 6764 11885 6764 11886 6794 11886 6798 11886 6764 11887 6798 11887 313 11887 313 11888 6798 11888 307 11888 6816 11889 6817 11889 6818 11889 6819 11890 6820 11890 6821 11890 1105 11891 1138 11891 6822 11891 1012 11892 1013 11892 1105 11892 1105 11893 6822 11893 1012 11893 1012 11894 6822 11894 6823 11894 1012 11895 6823 11895 1011 11895 6824 11896 6825 11896 6826 11896 6826 11897 6825 11897 6827 11897 6826 11898 6827 11898 6828 11898 6824 11899 6829 11899 6825 11899 6825 11900 6829 11900 6830 11900 6825 11901 6830 11901 6831 11901 6832 11902 6833 11902 6834 11902 6820 11903 6819 11903 6834 11903 6834 11904 6819 11904 6835 11904 6834 11905 6835 11905 6832 11905 6789 11906 6836 11906 6790 11906 6790 11907 6836 11907 6837 11907 6790 11908 6837 11908 6768 11908 6768 11909 6837 11909 6838 11909 6768 11910 6838 11910 6769 11910 6769 11911 6838 11911 6821 11911 6769 11912 6821 11912 6786 11912 6786 11913 6821 11913 6820 11913 316 11914 6839 11914 6767 11914 6767 11915 6839 11915 6840 11915 6767 11916 6840 11916 6765 11916 6765 11917 6840 11917 6841 11917 6765 11918 6841 11918 6789 11918 6789 11919 6841 11919 6842 11919 6789 11920 6842 11920 6836 11920 6817 11921 6785 11921 6784 11921 6816 11922 6777 11922 6817 11922 6817 11923 6777 11923 6776 11923 6817 11924 6776 11924 6785 11924 6771 11925 6773 11925 6843 11925 6843 11926 6773 11926 6775 11926 6843 11927 6775 11927 6816 11927 6816 11928 6775 11928 6779 11928 6816 11929 6779 11929 6777 11929 6771 11930 6843 11930 6799 11930 6799 11931 6843 11931 1121 11931 6799 11932 1121 11932 386 11932 6844 11933 6845 11933 6846 11933 1010 11934 1011 11934 6847 11934 6847 11935 1011 11935 6823 11935 6847 11936 6823 11936 6848 11936 6848 11937 6823 11937 6849 11937 6849 11938 6823 11938 6822 11938 6849 11939 6822 11939 6850 11939 6850 11940 6822 11940 1138 11940 6850 11941 1138 11941 1137 11941 6833 11942 6851 11942 6834 11942 6834 11943 6851 11943 6828 11943 6834 11944 6828 11944 6852 11944 6852 11945 6828 11945 6827 11945 6852 11946 6827 11946 6853 11946 6853 11947 6827 11947 6825 11947 6853 11948 6825 11948 6844 11948 6844 11949 6825 11949 6831 11949 6844 11950 6831 11950 6845 11950 6845 11951 6831 11951 1009 11951 6845 11952 1009 11952 6846 11952 6846 11953 6818 11953 6844 11953 6844 11954 6818 11954 6817 11954 6844 11955 6817 11955 6853 11955 6853 11956 6817 11956 6784 11956 6853 11957 6784 11957 6852 11957 6852 11958 6784 11958 6782 11958 6852 11959 6782 11959 6834 11959 6834 11960 6782 11960 6780 11960 6834 11961 6780 11961 6820 11961 6820 11962 6780 11962 6787 11962 6820 11963 6787 11963 6786 11963 1009 11964 1010 11964 6846 11964 6846 11965 1010 11965 6847 11965 6846 11966 6847 11966 6818 11966 6818 11967 6847 11967 6848 11967 6818 11968 6848 11968 6816 11968 6816 11969 6848 11969 6849 11969 6816 11970 6849 11970 6843 11970 6843 11971 6849 11971 6850 11971 6843 11972 6850 11972 1121 11972 1121 11973 6850 11973 1137 11973 6819 11974 6854 11974 6855 11974 318 11975 6839 11975 316 11975 319 11976 322 11976 6856 11976 6856 11977 322 11977 321 11977 6856 11978 321 11978 327 11978 6839 11979 318 11979 6840 11979 6840 11980 318 11980 319 11980 6840 11981 319 11981 6841 11981 6838 11982 6837 11982 6856 11982 6856 11983 6837 11983 6836 11983 6856 11984 6836 11984 319 11984 319 11985 6836 11985 6842 11985 319 11986 6842 11986 6841 11986 324 11987 6857 11987 326 11987 326 11988 6857 11988 6858 11988 326 11989 6858 11989 327 11989 327 11990 6858 11990 6859 11990 327 11991 6859 11991 6856 11991 6856 11992 6859 11992 6821 11992 6856 11993 6821 11993 6838 11993 6855 11994 6860 11994 6861 11994 6828 11995 6851 11995 6861 11995 6829 11996 6824 11996 6861 11996 6861 11997 6824 11997 6826 11997 6861 11998 6826 11998 6828 11998 6851 11999 6833 11999 6861 11999 6861 12000 6833 12000 6832 12000 6861 12001 6832 12001 6855 12001 6855 12002 6832 12002 6835 12002 6855 12003 6835 12003 6819 12003 6830 12004 6829 12004 6862 12004 6862 12005 6829 12005 6861 12005 6862 12006 6861 12006 6863 12006 6863 12007 6861 12007 6860 12007 6863 12008 6860 12008 6864 12008 6864 12009 6860 12009 6865 12009 6864 12010 6865 12010 6866 12010 6866 12011 6865 12011 323 12011 6819 12012 6821 12012 6854 12012 6854 12013 6821 12013 6859 12013 6854 12014 6859 12014 6855 12014 6855 12015 6859 12015 6858 12015 6855 12016 6858 12016 6860 12016 6860 12017 6858 12017 6857 12017 6860 12018 6857 12018 6865 12018 6865 12019 6857 12019 324 12019 6865 12020 324 12020 323 12020 6684 12021 383 12021 6685 12021 6685 12022 383 12022 384 12022 6685 12023 384 12023 6686 12023 6686 12024 384 12024 385 12024 6686 12025 385 12025 983 12025 983 12026 385 12026 379 12026 6665 12027 378 12027 6681 12027 6681 12028 378 12028 381 12028 6681 12029 381 12029 6682 12029 6682 12030 381 12030 380 12030 6682 12031 380 12031 6683 12031 6683 12032 380 12032 382 12032 4276 12033 4275 12033 6867 12033 6867 12034 4275 12034 4273 12034 4271 12035 4281 12035 6868 12035 6868 12036 4281 12036 4279 12036 6868 12037 4279 12037 6869 12037 6870 12038 4273 12038 4271 12038 4273 12039 6871 12039 6867 12039 6867 12040 6871 12040 6872 12040 6867 12041 6872 12041 4276 12041 4276 12042 6872 12042 4263 12042 6873 12043 6874 12043 6871 12043 6871 12044 6874 12044 6875 12044 6871 12045 6875 12045 6872 12045 6876 12046 6877 12046 6873 12046 6873 12047 6877 12047 6878 12047 6873 12048 6878 12048 6874 12048 6879 12049 6880 12049 6881 12049 6881 12050 6880 12050 6882 12050 6881 12051 6882 12051 6883 12051 6883 12052 6882 12052 6884 12052 6883 12053 6884 12053 6876 12053 6876 12054 6884 12054 6885 12054 6876 12055 6885 12055 6877 12055 6879 12056 6881 12056 6886 12056 6886 12057 6881 12057 6887 12057 6886 12058 6887 12058 6888 12058 6888 12059 6887 12059 6889 12059 6888 12060 6889 12060 6890 12060 6890 12061 6889 12061 6891 12061 6890 12062 6891 12062 6892 12062 6892 12063 6891 12063 6893 12063 6893 12064 6891 12064 6894 12064 6893 12065 6894 12065 6895 12065 6895 12066 6894 12066 6896 12066 6896 12067 6894 12067 6897 12067 6896 12068 6897 12068 6898 12068 6899 12069 1467 12069 1466 12069 6898 12070 6897 12070 6900 12070 6900 12071 6897 12071 6901 12071 6900 12072 6901 12072 6902 12072 6902 12073 6901 12073 6899 12073 6902 12074 6899 12074 6903 12074 6903 12075 6899 12075 1466 12075 6903 12076 1466 12076 1474 12076 6904 12077 1461 12077 1460 12077 6905 12078 6906 12078 6907 12078 6907 12079 6906 12079 6908 12079 6907 12080 6908 12080 6909 12080 6909 12081 6908 12081 6910 12081 6909 12082 6910 12082 6911 12082 6911 12083 6910 12083 6912 12083 6911 12084 6912 12084 6913 12084 6913 12085 6912 12085 6904 12085 6913 12086 6904 12086 6914 12086 6914 12087 6904 12087 1460 12087 6914 12088 1460 12088 1471 12088 6869 12089 6915 12089 6868 12089 6868 12090 6915 12090 6916 12090 6868 12091 6916 12091 6917 12091 6917 12092 6916 12092 6918 12092 6917 12093 6918 12093 6919 12093 6919 12094 6918 12094 6920 12094 6919 12095 6920 12095 6921 12095 6921 12096 6920 12096 6922 12096 6921 12097 6922 12097 6923 12097 6923 12098 6922 12098 6924 12098 6923 12099 6924 12099 6925 12099 6925 12100 6924 12100 6926 12100 6925 12101 6926 12101 6905 12101 6905 12102 6926 12102 6927 12102 6905 12103 6927 12103 6906 12103 4273 12104 6870 12104 6871 12104 6871 12105 6870 12105 6928 12105 6871 12106 6928 12106 6873 12106 6873 12107 6928 12107 6929 12107 6873 12108 6929 12108 6876 12108 6876 12109 6929 12109 6930 12109 6876 12110 6930 12110 6883 12110 6883 12111 6930 12111 6931 12111 6883 12112 6931 12112 6881 12112 6881 12113 6931 12113 6932 12113 6881 12114 6932 12114 6887 12114 6887 12115 6932 12115 6933 12115 6887 12116 6933 12116 6889 12116 6889 12117 6933 12117 6934 12117 6889 12118 6934 12118 6891 12118 6891 12119 6934 12119 6935 12119 6891 12120 6935 12120 6894 12120 6894 12121 6935 12121 6936 12121 6894 12122 6936 12122 6897 12122 6897 12123 6936 12123 6937 12123 6897 12124 6937 12124 6901 12124 6901 12125 6937 12125 6938 12125 6901 12126 6938 12126 6899 12126 4271 12127 6868 12127 6870 12127 6870 12128 6868 12128 6917 12128 6870 12129 6917 12129 6928 12129 6928 12130 6917 12130 6919 12130 6928 12131 6919 12131 6929 12131 6929 12132 6919 12132 6921 12132 6929 12133 6921 12133 6930 12133 6930 12134 6921 12134 6923 12134 6930 12135 6923 12135 6931 12135 6931 12136 6923 12136 6925 12136 6931 12137 6925 12137 6932 12137 6932 12138 6925 12138 6905 12138 6932 12139 6905 12139 6933 12139 6933 12140 6905 12140 6907 12140 6933 12141 6907 12141 6934 12141 6934 12142 6907 12142 6909 12142 6934 12143 6909 12143 6935 12143 6935 12144 6909 12144 6911 12144 6935 12145 6911 12145 6936 12145 6936 12146 6911 12146 6913 12146 6936 12147 6913 12147 6937 12147 6937 12148 6913 12148 6914 12148 6937 12149 6914 12149 6938 12149 6938 12150 6914 12150 1471 12150 6938 12151 1471 12151 6899 12151 6899 12152 1471 12152 1469 12152 6899 12153 1469 12153 1467 12153 562 7585 6704 7585 559 7585 559 7585 6704 7585 6694 7585 4261 12154 6939 12154 6940 12154 4261 12155 6940 12155 4262 12155 4262 12156 6940 12156 6941 12156 4262 12157 6941 12157 4314 12157 4260 12158 6942 12158 6943 12158 4260 12159 6943 12159 4261 12159 4261 12160 6943 12160 6944 12160 4261 12161 6944 12161 6939 12161 4259 12162 6945 12162 6946 12162 4259 12163 6946 12163 4260 12163 4260 12164 6946 12164 6947 12164 4260 12165 6947 12165 6942 12165 6612 12166 6948 12166 4257 12166 4257 12167 6948 12167 6949 12167 4257 12168 6949 12168 4258 12168 4258 12169 6949 12169 6950 12169 4258 12170 6950 12170 4259 12170 4259 12171 6950 12171 6951 12171 4259 12172 6951 12172 6945 12172 6831 12173 6830 12173 6862 12173 6952 12174 1009 12174 6831 12174 6953 12175 6954 12175 6955 12175 6955 12176 6954 12176 6956 12176 6955 12177 6956 12177 6957 12177 6957 12178 6956 12178 6952 12178 6958 12179 6959 12179 6953 12179 6953 12180 6959 12180 6954 12180 6960 12181 6688 12181 6687 12181 6953 12182 6961 12182 6958 12182 6958 12183 6961 12183 6960 12183 6958 12184 6960 12184 6962 12184 6962 12185 6960 12185 6687 12185 6952 12186 6831 12186 6957 12186 6957 12187 6831 12187 6862 12187 6957 12188 6862 12188 6955 12188 6955 12189 6862 12189 6863 12189 6955 12190 6863 12190 6953 12190 6953 12191 6863 12191 6864 12191 6953 12192 6864 12192 6961 12192 6961 12193 6864 12193 6866 12193 6961 12194 6866 12194 6960 12194 6960 12195 6866 12195 323 12195 6960 12196 323 12196 6688 12196 4379 12197 1003 12197 1009 12197 1009 12198 6952 12198 4379 12198 4379 12199 6952 12199 6956 12199 4379 12200 6956 12200 4378 12200 6687 12201 4374 12201 6962 12201 6962 12202 4374 12202 4375 12202 6962 12203 4375 12203 6958 12203 6958 12204 4375 12204 4376 12204 6958 12205 4376 12205 6959 12205 6959 12206 4376 12206 4377 12206 6959 12207 4377 12207 4378 12207 6959 12208 4378 12208 6954 12208 6954 12209 4378 12209 6956 12209 6683 7585 382 7585 6684 7585 6684 7585 382 7585 383 7585 6963 106 1473 106 1472 106 4264 12210 376 12210 4265 12210 4265 106 376 106 378 106 4265 106 378 106 6665 106 6964 12211 6965 12211 376 12211 376 12212 6965 12212 1472 12212 376 106 1472 106 1240 106 4264 12213 6966 12213 376 12213 376 106 6966 106 6967 106 376 12214 6967 12214 6964 12214 6968 106 6963 106 6969 106 6969 12215 6963 12215 1472 12215 6969 106 1472 106 6970 106 6970 12216 1472 12216 6965 12216 1474 12217 1473 12217 6903 12217 6903 12218 1473 12218 6963 12218 6903 12219 6963 12219 6902 12219 6902 12220 6963 12220 6900 12220 6900 12221 6963 12221 6898 12221 6898 12222 6963 12222 6968 12222 6898 12223 6968 12223 6896 12223 6888 12224 6890 12224 6970 12224 6970 12225 6890 12225 6892 12225 6970 12226 6892 12226 6969 12226 6969 12227 6892 12227 6893 12227 6969 12228 6893 12228 6968 12228 6968 12229 6893 12229 6895 12229 6968 12230 6895 12230 6896 12230 6888 12231 6970 12231 6886 12231 6886 12232 6970 12232 6965 12232 6886 12233 6965 12233 6879 12233 6964 12234 6882 12234 6965 12234 6965 12235 6882 12235 6880 12235 6965 12236 6880 12236 6879 12236 6967 12237 6885 12237 6964 12237 6964 12238 6885 12238 6884 12238 6964 12239 6884 12239 6882 12239 6966 12240 6878 12240 6967 12240 6967 12241 6878 12241 6877 12241 6967 12242 6877 12242 6885 12242 4263 12243 6872 12243 4264 12243 4264 12244 6872 12244 6875 12244 4264 12245 6875 12245 6966 12245 6966 12246 6875 12246 6874 12246 6966 12247 6874 12247 6878 12247 6971 12248 6972 12248 6973 12248 6974 12249 6972 12249 6971 12249 6975 12250 6974 12250 6971 12250 6971 12251 6976 12251 6977 12251 6971 12252 6978 12252 6979 12252 6971 12253 6980 12253 6981 12253 6982 12254 6980 12254 6971 12254 6983 12255 6982 12255 6971 12255 6971 12256 6984 12256 6985 12256 6986 12257 6984 12257 6971 12257 6987 12258 6986 12258 6971 12258 6971 12259 6988 12259 6989 12259 6990 12260 6988 12260 6971 12260 6989 12261 6975 12261 6971 12261 6646 12262 6647 12262 6990 12262 6979 12263 6978 12263 6738 12263 6991 12264 6992 12264 6993 12264 6994 12265 6995 12265 6996 12265 6997 12266 6998 12266 6999 12266 6999 12267 6998 12267 6643 12267 7000 12268 7001 12268 7002 12268 7002 12269 7003 12269 7000 12269 7000 12270 7003 12270 7004 12270 7000 12271 7004 12271 6999 12271 6999 12272 7004 12272 7005 12272 6999 12273 7005 12273 6997 12273 7001 12274 7000 12274 7006 12274 7006 12275 7000 12275 7007 12275 7006 12276 7007 12276 7008 12276 7009 12277 7010 12277 7007 12277 7007 12278 7010 12278 7011 12278 7007 12279 7011 12279 7008 12279 7012 12280 7013 12280 7014 12280 7014 12281 7013 12281 7015 12281 7014 12282 7015 12282 7016 12282 7017 12283 7018 12283 7019 12283 7019 12284 7018 12284 7020 12284 6991 12285 7021 12285 6992 12285 6992 12286 7021 12286 7022 12286 6992 12287 7022 12287 7023 12287 7023 12288 7022 12288 6996 12288 7023 12289 6996 12289 7024 12289 7024 12290 6996 12290 6995 12290 7024 12291 6995 12291 7025 12291 6971 12292 7026 12292 7027 12292 7027 12293 7026 12293 7028 12293 7027 12294 7028 12294 7029 12294 6971 12295 6977 12295 6978 12295 6978 12296 6977 12296 6740 12296 6978 12297 6740 12297 6738 12297 6973 12298 6976 12298 6971 12298 6974 12299 6731 12299 6972 12299 6972 12300 6731 12300 6747 12300 6972 12301 6747 12301 6973 12301 6973 12302 6747 12302 6745 12302 6973 12303 6745 12303 6976 12303 6976 12304 6745 12304 6743 12304 6976 12305 6743 12305 6977 12305 6977 12306 6743 12306 6742 12306 6977 12307 6742 12307 6740 12307 6990 12308 6647 12308 6988 12308 6988 12309 6647 12309 6648 12309 6988 12310 6648 12310 6989 12310 6989 12311 6648 12311 6649 12311 6989 12312 6649 12312 6975 12312 6975 12313 6649 12313 6736 12313 6975 12314 6736 12314 6974 12314 6974 12315 6736 12315 6732 12315 6974 12316 6732 12316 6731 12316 6644 12317 6645 12317 7030 12317 7030 12318 6645 12318 6646 12318 7030 12319 6646 12319 7031 12319 7031 12320 6646 12320 6990 12320 7031 12321 6990 12321 6971 12321 7032 12322 7033 12322 7034 12322 7034 12323 7033 12323 7035 12323 7034 12324 7035 12324 7036 12324 7037 12325 6985 12325 7038 12325 7038 12326 6985 12326 6984 12326 7038 12327 6984 12327 7039 12327 7039 12328 6984 12328 6986 12328 7039 12329 6986 12329 7040 12329 7040 12330 6986 12330 6987 12330 7040 12331 6987 12331 6993 12331 6971 12332 7027 12332 6983 12332 6983 12333 7027 12333 7029 12333 6983 12334 7029 12334 6982 12334 6982 12335 7029 12335 7041 12335 6982 12336 7041 12336 6980 12336 6980 12337 7041 12337 7042 12337 6980 12338 7042 12338 6981 12338 6738 12339 7028 12339 6979 12339 6979 12340 7028 12340 7026 12340 6979 12341 7026 12341 6971 12341 6999 12342 7032 12342 7000 12342 7000 12343 7032 12343 7034 12343 7000 12344 7034 12344 7007 12344 7007 12345 7034 12345 7036 12345 7007 12346 7036 12346 7009 12346 6993 12347 6992 12347 7040 12347 7040 12348 6992 12348 7023 12348 7040 12349 7023 12349 7039 12349 7039 12350 7023 12350 7024 12350 7039 12351 7024 12351 7038 12351 7038 12352 7024 12352 7025 12352 7038 12353 7025 12353 7037 12353 7037 12354 7043 12354 6985 12354 6985 12355 7043 12355 6971 12355 7017 12356 7012 12356 7018 12356 7018 12357 7012 12357 7014 12357 7018 12358 7014 12358 7009 12358 7009 12359 7014 12359 7016 12359 7009 12360 7016 12360 7010 12360 7044 12361 7020 12361 7045 12361 7045 12362 7020 12362 7018 12362 7045 12363 7018 12363 7046 12363 7046 12364 7018 12364 7009 12364 7046 12365 7009 12365 7047 12365 7047 12366 7009 12366 7036 12366 7047 12367 7036 12367 7048 12367 7048 12368 7036 12368 7035 12368 7048 12369 7035 12369 6971 12369 7033 12370 6971 12370 7035 12370 6643 12371 6644 12371 6999 12371 6999 12372 6644 12372 7030 12372 6999 12373 7030 12373 7032 12373 7032 12374 7030 12374 7031 12374 7032 12375 7031 12375 7033 12375 7033 12376 7031 12376 6971 12376 6994 12377 7044 12377 6995 12377 6995 12378 7044 12378 7045 12378 6995 12379 7045 12379 7025 12379 7025 12380 7045 12380 7046 12380 7025 12381 7046 12381 7037 12381 7037 12382 7046 12382 7047 12382 7037 12383 7047 12383 7043 12383 7043 12384 7047 12384 7048 12384 7043 12385 7048 12385 6971 12385 7029 12386 7049 12386 7041 12386 7041 12387 7049 12387 6991 12387 7041 12388 6991 12388 7042 12388 7042 12389 6991 12389 6993 12389 7042 12390 6993 12390 6981 12390 6981 12391 6993 12391 6987 12391 6981 12392 6987 12392 6971 12392 7050 12393 7049 12393 7029 12393 7028 12394 7051 12394 7029 12394 7029 12395 7051 12395 7052 12395 7029 12396 7052 12396 7050 12396 6737 12397 7053 12397 6738 12397 6738 12398 7053 12398 7054 12398 6738 12399 7054 12399 7028 12399 7028 12400 7054 12400 7055 12400 7028 12401 7055 12401 7051 12401 6599 12402 6598 12402 7056 12402 7057 12403 7058 12403 7059 12403 6539 12404 7060 12404 7061 12404 7059 12405 7062 12405 6593 12405 6533 12406 6532 12406 7063 12406 7063 7585 6532 7585 6531 7585 7063 7585 6531 7585 7064 7585 6552 12407 7065 12407 6553 12407 6553 633 7065 633 6554 633 6593 7585 7062 7585 6525 7585 6578 12408 7066 12408 6587 12408 6587 12409 7066 12409 6588 12409 6539 12410 7061 12410 6545 12410 6545 12411 7061 12411 7067 12411 6545 7585 7067 7585 6546 7585 6546 633 7067 633 6547 633 6547 12412 7068 12412 6548 12412 6548 12413 7068 12413 6549 12413 6525 12414 7069 12414 6526 12414 6526 7585 7069 7585 6528 7585 6562 12415 6561 12415 7070 12415 7070 12416 6561 12416 6560 12416 6560 12417 6559 12417 7071 12417 7071 12418 6559 12418 6558 12418 7071 7585 6558 7585 7072 7585 7072 7585 6558 7585 6557 7585 6557 12419 6556 12419 7073 12419 7073 12420 6556 12420 6555 12420 7073 633 6555 633 6554 633 6579 12421 7074 12421 6580 12421 6580 7585 7074 7585 7075 7585 6580 12422 7075 12422 6581 12422 6581 12423 7075 12423 6582 12423 6582 12424 7076 12424 6583 12424 6583 7585 7076 7585 6575 7585 6550 633 6549 633 7077 633 6550 12425 7077 12425 6551 12425 6551 633 7077 633 6552 633 6552 7585 7078 7585 7065 7585 6539 12426 6538 12426 7079 12426 7079 12427 6538 12427 6537 12427 7079 12428 6537 12428 6536 12428 6536 12429 6544 12429 7080 12429 7080 7585 6544 7585 6543 7585 6543 12430 6542 12430 7081 12430 7081 12431 6542 12431 6541 12431 7081 7585 6541 7585 7082 7585 7082 12432 6541 12432 6540 12432 6540 12433 6534 12433 7083 12433 7083 12434 6534 12434 6535 12434 7083 12435 6535 12435 6533 12435 6576 7585 6575 7585 7084 7585 6576 12436 7084 12436 6577 12436 6577 7585 7084 7585 6578 7585 6578 12437 7085 12437 7066 12437 7086 7585 7087 7585 7056 7585 7056 7585 7087 7585 7088 7585 7056 12438 7088 12438 6599 12438 6599 7585 7088 7585 7089 7585 6599 7585 7089 7585 6600 7585 6600 7585 7089 7585 7090 7585 6600 12439 7090 12439 6568 12439 6568 12440 7090 12440 6569 12440 6569 7585 7091 7585 6571 7585 6571 7585 7091 7585 7092 7585 6571 7585 7092 7585 6572 7585 6572 7585 7092 7585 6573 7585 6573 12441 7093 12441 6574 12441 6574 7585 7093 7585 6567 7585 4232 633 6564 633 7094 633 7094 7585 6564 7585 6563 7585 7094 12442 6563 12442 6562 12442 6531 12443 6530 12443 7095 12443 7095 12444 6530 12444 6529 12444 7095 12445 6529 12445 6528 12445 7059 7585 6593 7585 7057 7585 7057 12446 6593 12446 6586 12446 6586 12447 6585 12447 7096 12447 7096 7585 6585 7585 6584 7585 7096 12448 6584 12448 6594 12448 6594 7585 6595 7585 7097 7585 7097 7585 6595 7585 6596 7585 6596 12449 6597 12449 7098 12449 7098 7585 6597 7585 6592 7585 7098 7585 6592 7585 7099 7585 7099 7585 6592 7585 6591 7585 6591 12450 6590 12450 7100 12450 7100 7585 6590 7585 6589 7585 7100 7585 6589 7585 6588 7585 6565 7585 6567 7585 7101 7585 6565 7585 7101 7585 6566 7585 6566 7585 7101 7585 6579 7585 6579 12451 7102 12451 7074 12451 6689 12452 7103 12452 6690 12452 6690 12453 7103 12453 7056 12453 6690 12454 7056 12454 6602 12454 6602 12455 7056 12455 6598 12455 7097 12456 6596 12456 7103 12456 7103 12457 6596 12457 7098 12457 7103 12458 7098 12458 7099 12458 7099 12459 6591 12459 7103 12459 7103 12460 6591 12460 7100 12460 7103 12461 7100 12461 6588 12461 6588 12462 7066 12462 7103 12462 7103 12463 7066 12463 7085 12463 7103 12464 7085 12464 6578 12464 6578 12465 7084 12465 7103 12465 7103 12466 7084 12466 6575 12466 7103 12467 6575 12467 7076 12467 7076 12468 6582 12468 7103 12468 7103 12469 6582 12469 7075 12469 7103 12470 7075 12470 7074 12470 7074 12471 7102 12471 7103 12471 7103 12472 7102 12472 6579 12472 7103 12473 6579 12473 7101 12473 7101 12474 6567 12474 7103 12474 7103 12475 6567 12475 7093 12475 7103 12476 7093 12476 6573 12476 6573 12477 7092 12477 7103 12477 7103 12478 7092 12478 7091 12478 7103 12479 7091 12479 6569 12479 6569 12480 7090 12480 7103 12480 7103 12481 7090 12481 7089 12481 7103 12482 7089 12482 7088 12482 7088 12483 7087 12483 7103 12483 7103 12484 7087 12484 7086 12484 7103 12485 7086 12485 7056 12485 7104 12486 7080 12486 6543 12486 6543 12487 7081 12487 7104 12487 7104 12488 7081 12488 7082 12488 7104 12489 7082 12489 6540 12489 6540 12490 7083 12490 7104 12490 7104 12491 7083 12491 6533 12491 7104 12492 6533 12492 7063 12492 7063 12493 7064 12493 7104 12493 7104 12494 7064 12494 6531 12494 7104 12495 6531 12495 7095 12495 7095 12496 6528 12496 7104 12496 7104 12497 6528 12497 7069 12497 7104 12498 7069 12498 6525 12498 6525 12499 7062 12499 7104 12499 7104 12500 7062 12500 7059 12500 7104 12501 7059 12501 7058 12501 7058 12502 7057 12502 7104 12502 7104 12503 7057 12503 6586 12503 7104 12504 6586 12504 7105 12504 7105 12505 6586 12505 7096 12505 7105 12506 7096 12506 7103 12506 7103 12507 7096 12507 6594 12507 7103 12508 6594 12508 7097 12508 7106 12509 6621 12509 4232 12509 4232 12510 7094 12510 7106 12510 7106 12511 7094 12511 6562 12511 7106 12512 6562 12512 7070 12512 7070 12513 6560 12513 7106 12513 7106 12514 6560 12514 7071 12514 7106 12515 7071 12515 7072 12515 7072 12516 6557 12516 7106 12516 7106 12517 6557 12517 7073 12517 7106 12518 7073 12518 6554 12518 6554 12519 7065 12519 7106 12519 7106 12520 7065 12520 7078 12520 7106 12521 7078 12521 6552 12521 6552 12522 7077 12522 7106 12522 7106 12523 7077 12523 6549 12523 7106 12524 6549 12524 7068 12524 7068 12525 6547 12525 7106 12525 7106 12526 6547 12526 7067 12526 7106 12527 7067 12527 7061 12527 7061 12528 7060 12528 7106 12528 7106 12529 7060 12529 6539 12529 7106 12530 6539 12530 7107 12530 7107 12531 6539 12531 7079 12531 7107 12532 7079 12532 7104 12532 7104 12533 7079 12533 6536 12533 7104 12534 6536 12534 7080 12534 7108 12535 7109 12535 7110 12535 7109 12536 6628 12536 6629 12536 7111 12537 7112 12537 7108 12537 7112 12538 7111 12538 6663 12538 7109 12539 6629 12539 7110 12539 7110 12540 6629 12540 6630 12540 7110 12541 6630 12541 7113 12541 7113 12542 6630 12542 6615 12542 7113 12543 6615 12543 7114 12543 7108 12544 7110 12544 7111 12544 7111 12545 7110 12545 7113 12545 7111 12546 7113 12546 7115 12546 7115 12547 7113 12547 7114 12547 7115 12548 7114 12548 7116 12548 7116 12549 7114 12549 7117 12549 7116 12550 7117 12550 7118 12550 7118 12551 7117 12551 7119 12551 7118 12552 7119 12552 7120 12552 6621 12553 7106 12553 6619 12553 6619 12554 7106 12554 7119 12554 6619 12555 7119 12555 6618 12555 6618 12556 7119 12556 7117 12556 6618 12557 7117 12557 6625 12557 6625 12558 7117 12558 7114 12558 6625 12559 7114 12559 6627 12559 6627 12560 7114 12560 6615 12560 7106 12561 7107 12561 7119 12561 7119 12562 7107 12562 7104 12562 7119 12563 7104 12563 7120 12563 7120 12564 7104 12564 7105 12564 7120 12565 7105 12565 7103 12565 6663 12566 7111 12566 6696 12566 6696 12567 7111 12567 7115 12567 6696 12568 7115 12568 6697 12568 6697 12569 7115 12569 7116 12569 6697 12570 7116 12570 6701 12570 6701 12571 7116 12571 7118 12571 6701 12572 7118 12572 6676 12572 6676 12573 7118 12573 7120 12573 6676 12574 7120 12574 6705 12574 6705 12575 7120 12575 7103 12575 6705 12576 7103 12576 6689 12576 81 12577 137 12577 139 12577 81 12578 139 12578 80 12578 80 12579 139 12579 136 12579 80 12580 136 12580 82 12580 82 12581 136 12581 135 12581 82 12582 135 12582 83 12582 83 12583 135 12583 133 12583 83 12583 133 12583 85 12583 85 12584 133 12584 132 12584 85 12584 132 12584 97 12584 89 12585 102 12585 101 12585 89 12585 101 12585 91 12585 91 12586 101 12586 109 12586 91 12586 109 12586 92 12586 92 12587 109 12587 108 12587 92 12588 108 12588 96 12588 96 12589 108 12589 107 12589 96 12590 107 12590 95 12590 95 12591 107 12591 106 12591 95 12591 106 12591 93 12591 176 12592 219 12592 221 12592 176 12592 221 12592 177 12592 177 12593 221 12593 223 12593 177 12594 223 12594 178 12594 178 12595 223 12595 224 12595 178 12596 224 12596 179 12596 179 12597 224 12597 218 12597 179 12597 218 12597 181 12597 181 12598 218 12598 217 12598 181 12598 217 12598 182 12598 174 12599 187 12599 186 12599 174 12599 186 12599 172 12599 172 12600 186 12600 189 12600 172 12600 189 12600 169 12600 169 12601 189 12601 191 12601 169 12602 191 12602 168 12602 168 12603 191 12603 192 12603 168 12604 192 12604 166 12604 166 12605 192 12605 194 12605 166 12606 194 12606 164 12606 6432 12607 6476 12607 7121 12607 6499 12608 6497 12608 7121 12608 7121 12609 6497 12609 6495 12609 7121 12610 6495 12610 6432 12610 6478 12611 6480 12611 6650 12611 6650 12612 6480 12612 6482 12612 6482 12613 6484 12613 6650 12613 6650 12614 6484 12614 6487 12614 6650 12615 6487 12615 6448 12615 6448 12616 6446 12616 6650 12616 6650 12617 6446 12617 6444 12617 6650 12618 6444 12618 210 12618 6467 12619 6469 12619 7122 12619 6467 12620 7122 12620 6442 12620 6449 12621 6428 12621 7122 12621 7122 12622 6428 12622 6440 12622 7122 12623 6440 12623 6442 12623 6469 12624 6470 12624 7122 12624 7122 12625 6470 12625 6471 12625 7122 12626 6471 12626 6425 12626 6425 12627 6439 12627 7121 12627 7121 12628 6439 12628 6438 12628 7121 12629 6438 12629 6436 12629 6436 12630 6434 12630 7121 12630 7121 12631 6434 12631 6500 12631 7121 12632 6500 12632 6499 12632 6454 12633 6452 12633 7122 12633 7122 12634 6452 12634 6450 12634 7122 12635 6450 12635 6449 12635 6459 12636 6457 12636 7122 12636 7122 12637 6457 12637 6456 12637 7122 12638 6456 12638 6454 12638 6472 12639 6463 12639 7123 12639 7123 12640 6463 12640 6461 12640 7123 12641 6461 12641 6459 12641 6523 12642 6475 12642 7123 12642 7123 12643 6475 12643 6473 12643 7123 12644 6473 12644 6472 12644 6505 12645 6507 12645 7123 12645 7123 12646 6507 12646 6509 12646 7123 12647 6509 12647 6511 12647 6511 12648 6512 12648 7123 12648 7123 12649 6512 12649 6514 12649 7123 12650 6514 12650 6517 12650 6517 12651 6519 12651 7123 12651 7123 12652 6519 12652 6521 12652 7123 12653 6521 12653 6523 12653 6422 12654 6421 12654 6698 12654 6698 12655 6421 12655 6420 12655 6420 12656 6490 12656 7123 12656 7123 12657 6490 12657 6492 12657 7123 12658 6492 12658 6493 12658 6493 12659 6501 12659 7123 12659 7123 12660 6501 12660 6503 12660 7123 12661 6503 12661 6505 12661 6420 12662 7123 12662 6698 12662 6698 12663 7123 12663 7124 12663 6698 12664 7124 12664 6699 12664 6699 12665 7124 12665 7125 12665 6699 12666 7125 12666 6667 12666 6667 12667 7125 12667 7126 12667 6667 12668 7126 12668 6674 12668 6459 12669 7122 12669 7123 12669 7123 12670 7122 12670 7127 12670 7123 12671 7127 12671 7124 12671 7124 12672 7127 12672 7128 12672 7124 12673 7128 12673 7125 12673 7125 12674 7128 12674 7129 12674 7125 12675 7129 12675 7126 12675 5698 12676 6670 12676 5693 12676 5693 12677 6670 12677 7130 12677 5693 12678 7130 12678 5691 12678 5691 12679 7130 12679 7131 12679 5691 12680 7131 12680 5704 12680 5704 12681 7131 12681 7132 12681 5704 12682 7132 12682 233 12682 6695 12683 6700 12683 7133 12683 7133 12684 6700 12684 7134 12684 7133 12685 7134 12685 7135 12685 7135 12686 7134 12686 7136 12686 7135 12687 7136 12687 7137 12687 7137 12688 7136 12688 7138 12688 6700 12689 6675 12689 7134 12689 7134 12690 6675 12690 7139 12690 7134 12691 7139 12691 7136 12691 7136 12692 7139 12692 7140 12692 7136 12693 7140 12693 7138 12693 7138 12694 7140 12694 7141 12694 6425 12695 7121 12695 7122 12695 7122 12696 7121 12696 7142 12696 7122 12697 7142 12697 7127 12697 7127 12698 7142 12698 7143 12698 7127 12699 7143 12699 7128 12699 7128 12700 7143 12700 7144 12700 7128 12701 7144 12701 7129 12701 6653 12702 6652 12702 7132 12702 7132 12703 6652 12703 6651 12703 7132 12704 6651 12704 233 12704 7141 12705 6654 12705 7138 12705 7138 12706 6654 12706 6653 12706 7138 12707 6653 12707 7137 12707 7137 12708 6653 12708 7132 12708 7137 12709 7132 12709 7135 12709 7135 12710 7132 12710 7131 12710 7135 12711 7131 12711 7133 12711 7133 12712 7131 12712 7130 12712 7133 12713 7130 12713 6695 12713 6695 12714 7130 12714 6670 12714 6657 12715 6656 12715 7141 12715 7141 12716 6656 12716 6655 12716 7141 12717 6655 12717 6654 12717 6675 12718 6674 12718 7139 12718 7139 12719 6674 12719 7126 12719 7139 12720 7126 12720 7140 12720 7140 12721 7126 12721 7129 12721 7140 12722 7129 12722 7141 12722 7141 12723 7129 12723 7144 12723 7141 12724 7144 12724 6657 12724 6657 12725 7144 12725 7143 12725 6657 12726 7143 12726 6658 12726 6658 12727 7143 12727 7142 12727 6658 12728 7142 12728 6659 12728 6476 12729 6478 12729 7121 12729 7121 12730 6478 12730 6650 12730 7121 12731 6650 12731 7142 12731 7142 12732 6650 12732 6660 12732 7142 12733 6660 12733 6659 12733 7145 12734 7146 12734 7147 12734 7146 12735 7148 12735 7149 12735 7148 12736 6680 12736 6679 12736 4424 12737 4391 12737 7150 12737 4418 12738 4395 12738 7151 12738 6708 12739 6707 12739 4392 12739 4392 12740 6707 12740 7151 12740 4392 12741 7151 12741 4393 12741 4393 12742 7151 12742 4395 12742 4391 12743 4390 12743 7150 12743 7150 12744 4390 12744 4445 12744 7150 12745 4445 12745 4447 12745 4447 12746 4449 12746 7150 12746 7150 12747 4449 12747 4451 12747 7150 12748 4451 12748 7151 12748 4451 12749 4453 12749 7151 12749 7151 12750 4453 12750 4455 12750 7151 12751 4455 12751 4458 12751 4458 12752 4460 12752 7151 12752 7151 12753 4460 12753 4462 12753 7151 12754 4462 12754 4402 12754 4402 12755 4404 12755 7151 12755 7151 12756 4404 12756 4406 12756 7151 12757 4406 12757 4408 12757 4408 12758 4410 12758 7151 12758 7151 12759 4410 12759 4412 12759 7151 12760 4412 12760 4413 12760 4413 12761 4415 12761 7151 12761 7151 12762 4415 12762 4417 12762 7151 12763 4417 12763 4418 12763 4386 12764 4388 12764 7152 12764 7152 12765 4388 12765 4420 12765 7152 12766 4420 12766 4422 12766 4422 12767 4438 12767 7152 12767 7152 12768 4438 12768 4440 12768 7152 12769 4440 12769 7150 12769 7150 12770 4440 12770 4442 12770 7150 12771 4442 12771 4396 12771 4396 12772 4398 12772 7150 12772 7150 12773 4398 12773 4400 12773 7150 12774 4400 12774 4435 12774 4435 12775 4434 12775 7150 12775 7150 12776 4434 12776 4432 12776 7150 12777 4432 12777 4430 12777 4430 12778 4428 12778 7150 12778 7150 12779 4428 12779 4426 12779 7150 12780 4426 12780 4424 12780 6753 12781 156 12781 7152 12781 7152 12782 156 12782 4380 12782 7152 12783 4380 12783 4381 12783 4381 12784 4382 12784 7152 12784 7152 12785 4382 12785 4384 12785 7152 12786 4384 12786 4386 12786 7148 12787 6679 12787 7149 12787 7149 12788 6679 12788 6678 12788 7149 12789 6678 12789 7153 12789 7153 12790 6678 12790 6669 12790 7153 12791 6669 12791 7154 12791 7154 12792 6669 12792 6668 12792 7154 12793 6668 12793 7155 12793 7155 12794 6668 12794 6677 12794 7155 12795 6677 12795 7156 12795 7156 12796 6677 12796 5583 12796 7156 12797 5583 12797 5578 12797 7146 12798 7149 12798 7147 12798 7147 12799 7149 12799 7153 12799 7147 12800 7153 12800 7157 12800 7157 12801 7153 12801 7154 12801 7157 12802 7154 12802 7158 12802 7158 12803 7154 12803 7155 12803 7158 12804 7155 12804 7159 12804 7159 12805 7155 12805 7156 12805 7159 12806 7156 12806 7160 12806 7160 12807 7156 12807 5578 12807 7160 12808 5578 12808 5580 12808 6707 12809 6706 12809 7151 12809 7151 12810 6706 12810 7161 12810 7151 12811 7161 12811 7150 12811 7150 12812 7161 12812 7162 12812 7150 12813 7162 12813 7152 12813 7152 12814 7162 12814 7163 12814 7152 12815 7163 12815 6753 12815 7145 12816 7147 12816 7164 12816 7164 12817 7147 12817 7157 12817 7164 12818 7157 12818 7165 12818 7165 12819 7157 12819 7158 12819 7165 12820 7158 12820 7166 12820 7166 12821 7158 12821 7159 12821 7166 12822 7159 12822 7167 12822 7167 12823 7159 12823 7160 12823 7167 12824 7160 12824 7168 12824 7168 12825 7160 12825 5580 12825 7168 12826 5580 12826 5577 12826 6756 12827 6755 12827 7163 12827 7163 12828 6755 12828 6754 12828 7163 12829 6754 12829 6753 12829 6763 12830 6758 12830 7165 12830 7165 12831 6758 12831 6757 12831 7165 12832 6757 12832 7164 12832 7164 12833 6757 12833 6756 12833 7164 12834 6756 12834 7145 12834 7145 12835 6756 12835 7163 12835 7145 12836 7163 12836 7146 12836 7146 12837 7163 12837 7162 12837 7146 12838 7162 12838 7148 12838 7148 12839 7162 12839 7161 12839 7148 12840 7161 12840 6680 12840 6680 12841 7161 12841 6706 12841 6763 12842 7165 12842 6762 12842 6762 12843 7165 12843 7166 12843 6762 12844 7166 12844 6761 12844 6761 12845 7166 12845 7167 12845 6761 12846 7167 12846 6760 12846 6760 12847 7167 12847 7168 12847 6760 12848 7168 12848 6759 12848 6759 12849 7168 12849 5577 12849 6759 12850 5577 12850 118 12850 7169 12851 7019 12851 7020 12851 7170 12852 7002 12852 7001 12852 7170 12853 7001 12853 7171 12853 7172 12854 7173 12854 7174 12854 7174 12855 7173 12855 7175 12855 7174 12856 7175 12856 7176 12856 7176 12857 7175 12857 7177 12857 7176 12858 7177 12858 7178 12858 7178 12859 7177 12859 7171 12859 7179 12860 7180 12860 7181 12860 7181 12861 7180 12861 7182 12861 7181 12862 7182 12862 7183 12862 7183 12863 7182 12863 7184 12863 7183 12864 7184 12864 7185 12864 7185 12865 7184 12865 7186 12865 7185 12866 7186 12866 7187 12866 7187 12867 7186 12867 7188 12867 7187 12868 7188 12868 7172 12868 7172 12869 7188 12869 7189 12869 7172 12870 7189 12870 7173 12870 7190 12871 7180 12871 7191 12871 7191 12872 7180 12872 7179 12872 7191 12873 7179 12873 7192 12873 7192 12874 7179 12874 7193 12874 7019 12875 7169 12875 7017 12875 7171 12876 7001 12876 7178 12876 7178 12877 7001 12877 7006 12877 7178 12878 7006 12878 7176 12878 7176 12879 7006 12879 7008 12879 7176 12880 7008 12880 7174 12880 7174 12881 7008 12881 7011 12881 7174 12882 7011 12882 7172 12882 7172 12883 7011 12883 7010 12883 7172 12884 7010 12884 7187 12884 7187 12885 7010 12885 7016 12885 7187 12886 7016 12886 7185 12886 7185 12887 7016 12887 7015 12887 7185 12888 7015 12888 7183 12888 7183 12889 7015 12889 7013 12889 7183 12890 7013 12890 7181 12890 7181 12891 7013 12891 7012 12891 7181 12892 7012 12892 7179 12892 7179 12893 7012 12893 7017 12893 7179 12894 7017 12894 7193 12894 7193 12895 7017 12895 7169 12895 7193 12896 7169 12896 7192 12896 7194 12897 6643 12897 6998 12897 7194 12898 6998 12898 7195 12898 7195 12899 6998 12899 7196 12899 7196 12900 6998 12900 6997 12900 7196 12901 6997 12901 7197 12901 7197 12902 6997 12902 7005 12902 7197 12903 7005 12903 7198 12903 7198 12904 7005 12904 7004 12904 7198 12905 7004 12905 7199 12905 7199 12906 7004 12906 7003 12906 7199 12907 7003 12907 7200 12907 7200 12908 7003 12908 7002 12908 7200 12909 7002 12909 7170 12909 7195 12910 6632 12910 7194 12910 7194 12911 6632 12911 6631 12911 7194 12912 6631 12912 6643 12912 6605 12913 4236 12913 4237 12913 6606 12914 6605 12914 7201 12914 6609 12915 6606 12915 7202 12915 6605 12916 4237 12916 7201 12916 7201 12917 4237 12917 4238 12917 7201 12918 4238 12918 7203 12918 4238 12919 4239 12919 7203 12919 7203 12920 4239 12920 4249 12920 7203 12921 4249 12921 7204 12921 7204 12922 4249 12922 4248 12922 7204 12923 4248 12923 7205 12923 6606 12924 7201 12924 7202 12924 7202 12925 7201 12925 7203 12925 7202 12926 7203 12926 7206 12926 7206 12927 7203 12927 7204 12927 7206 12928 7204 12928 7207 12928 7207 12929 7204 12929 7205 12929 7207 12930 7205 12930 7208 12930 6609 12931 7202 12931 7209 12931 7209 12932 7202 12932 7206 12932 7209 12933 7206 12933 7210 12933 7210 12934 7206 12934 7207 12934 7210 12935 7207 12935 7211 12935 7211 12936 7207 12936 7208 12936 7211 12937 7208 12937 7212 12937 6945 12938 6951 12938 7212 12938 7212 12939 6951 12939 6950 12939 7212 12940 6950 12940 7211 12940 7211 12941 6950 12941 6949 12941 7211 12942 6949 12942 7210 12942 7210 12943 6949 12943 6948 12943 7210 12944 6948 12944 7209 12944 7209 12945 6948 12945 6612 12945 7209 12946 6612 12946 6609 12946 6946 12947 6945 12947 7213 12947 7213 12948 6945 12948 7212 12948 7213 12949 7212 12949 7214 12949 7214 12950 7212 12950 7208 12950 7214 12951 7208 12951 7215 12951 7215 12952 7208 12952 7205 12952 7215 12953 7205 12953 4247 12953 4247 12954 7205 12954 4248 12954 4247 12955 4246 12955 7215 12955 7215 12956 4246 12956 7216 12956 7215 12957 7216 12957 7214 12957 7214 12958 7216 12958 7217 12958 7214 12959 7217 12959 7213 12959 7213 12960 7217 12960 7218 12960 7213 12961 7218 12961 6946 12961 6943 12962 6942 12962 7218 12962 7218 12963 6942 12963 6947 12963 7218 12964 6947 12964 6946 12964 4245 12965 4244 12965 7219 12965 7219 12966 4244 12966 7220 12966 7219 12967 7220 12967 7221 12967 7221 12968 7220 12968 7222 12968 7221 12969 7222 12969 7223 12969 7223 12970 7222 12970 7224 12970 4246 12971 4245 12971 7216 12971 7216 12972 4245 12972 7219 12972 7216 12973 7219 12973 7217 12973 7217 12974 7219 12974 7221 12974 7217 12975 7221 12975 7218 12975 7218 12976 7221 12976 7223 12976 7218 12977 7223 12977 6943 12977 6943 12978 7223 12978 7224 12978 6940 12979 6939 12979 7224 12979 7224 12980 6939 12980 6944 12980 7224 12981 6944 12981 6943 12981 4243 12982 4242 12982 7225 12982 7225 12983 4242 12983 7226 12983 7225 12984 7226 12984 7227 12984 7227 12985 7226 12985 7228 12985 7227 12986 7228 12986 7229 12986 7229 12987 7228 12987 7230 12987 4313 12988 7230 12988 4316 12988 4316 12989 7230 12989 7228 12989 4316 12990 7228 12990 4315 12990 4315 12991 7228 12991 7226 12991 4315 12992 7226 12992 4241 12992 4241 12993 7226 12993 4242 12993 4244 12994 4243 12994 7220 12994 7220 12995 4243 12995 7225 12995 7220 12996 7225 12996 7222 12996 7222 12997 7225 12997 7227 12997 7222 12998 7227 12998 7224 12998 7224 12999 7227 12999 7229 12999 7224 13000 7229 13000 6940 13000 6940 13001 7229 13001 7230 13001 6940 13002 7230 13002 6941 13002 6941 13003 7230 13003 4313 13003 6941 13004 4313 13004 4314 13004 7231 13005 7232 13005 7233 13005 6626 13006 4326 13006 4325 13006 6626 13007 4325 13007 6616 13007 6616 13008 4325 13008 4324 13008 6616 13009 4324 13009 6617 13009 6622 13010 7234 13010 6620 13010 6620 13011 7234 13011 7235 13011 4324 13012 7236 13012 6617 13012 6617 13013 7236 13013 7237 13013 6617 13014 7237 13014 6623 13014 6623 13015 7237 13015 7238 13015 6623 13016 7238 13016 6622 13016 6622 13017 7238 13017 4341 13017 6622 13018 4341 13018 7234 13018 7234 13019 4341 13019 4340 13019 7234 13020 4340 13020 7235 13020 7235 13021 4340 13021 4343 13021 7235 13022 4343 13022 7233 13022 4343 13023 4334 13023 7233 13023 7233 13024 4334 13024 4333 13024 7233 13025 4333 13025 7231 13025 7231 13026 4333 13026 4331 13026 7231 13027 4331 13027 7232 13027 7232 13028 4331 13028 7239 13028 7232 13029 7239 13029 7240 13029 6752 13030 6734 13030 7241 13030 7241 13031 6734 13031 7242 13031 7241 13032 7242 13032 7243 13032 7243 13033 7242 13033 7240 13033 7240 13034 7242 13034 7232 13034 7232 13035 7242 13035 7244 13035 7232 13036 7244 13036 7233 13036 7233 13037 7244 13037 7245 13037 7233 13038 7245 13038 7235 13038 6620 13039 7235 13039 6719 13039 6719 13040 7235 13040 7245 13040 6719 13041 7245 13041 6725 13041 6725 13042 7245 13042 7246 13042 7246 13043 7245 13043 7244 13043 7246 13044 7244 13044 7247 13044 7247 13045 7244 13045 7242 13045 7247 13046 7242 13046 7248 13046 7248 13047 7242 13047 6734 13047 7248 13048 6734 13048 6638 13048 7249 13049 6726 13049 6725 13049 6633 13050 6632 13050 7250 13050 6641 13051 6640 13051 7251 13051 6641 13052 7251 13052 6642 13052 6642 13053 7251 13053 7252 13053 6642 13054 7252 13054 6639 13054 7251 13055 7253 13055 7252 13055 7252 13056 7253 13056 7254 13056 7252 13057 7254 13057 7255 13057 7249 13058 7256 13058 7257 13058 7257 13059 7256 13059 7258 13059 7257 13060 7258 13060 7259 13060 7259 13061 7258 13061 7260 13061 7259 13062 7260 13062 7261 13062 7262 13063 7263 13063 7264 13063 7264 13064 7263 13064 7265 13064 7264 13065 7265 13065 7266 13065 7266 13066 7265 13066 7267 13066 7266 13067 7267 13067 7250 13067 7250 13068 7267 13068 7268 13068 7250 13069 7268 13069 6633 13069 6633 13070 7268 13070 6634 13070 7254 13071 7256 13071 7255 13071 7255 13072 7256 13072 7249 13072 7255 13073 7249 13073 7246 13073 7246 13074 7249 13074 6725 13074 7246 13075 7247 13075 7255 13075 7255 13076 7247 13076 7248 13076 7255 13077 7248 13077 7252 13077 7252 13078 7248 13078 6638 13078 7252 13079 6638 13079 6639 13079 7261 13080 6730 13080 7259 13080 7259 13081 6730 13081 6729 13081 7259 13082 6729 13082 7257 13082 7257 13083 6729 13083 6728 13083 7257 13084 6728 13084 7249 13084 7249 13085 6728 13085 6727 13085 7249 13086 6727 13086 6726 13086 6640 13087 6634 13087 7251 13087 7251 13088 6634 13088 7268 13088 7251 13089 7268 13089 7253 13089 7253 13090 7268 13090 7267 13090 7253 13091 7267 13091 7254 13091 7254 13092 7267 13092 7265 13092 7254 13093 7265 13093 7256 13093 7256 13094 7265 13094 7263 13094 7256 13095 7263 13095 7258 13095 7258 13096 7263 13096 7262 13096 7258 13097 7262 13097 7260 13097 7250 13098 6632 13098 7195 13098 7250 13099 7195 13099 7266 13099 7195 13100 7269 13100 7266 13100 7266 13101 7269 13101 7270 13101 7266 13102 7270 13102 7264 13102 7264 13103 7270 13103 7271 13103 7264 13104 7271 13104 7262 13104 7262 13105 7271 13105 7272 13105 7262 13106 7272 13106 7260 13106 7260 13107 7272 13107 7273 13107 7260 13108 7273 13108 7261 13108 7261 13109 7273 13109 6716 13109 7261 13110 6716 13110 6730 13110 6717 13111 6716 13111 7273 13111 7274 13112 7275 13112 7273 13112 7273 13113 7275 13113 7276 13113 7273 13114 7276 13114 6717 13114 7273 13115 7272 13115 7274 13115 7274 13116 7272 13116 7271 13116 7274 13117 7271 13117 7277 13117 7277 13118 7271 13118 7270 13118 7277 13119 7270 13119 7278 13119 7278 13120 7270 13120 7269 13120 7278 13121 7269 13121 7279 13121 7279 13122 7269 13122 7280 13122 7197 13123 7269 13123 7196 13123 7196 13124 7269 13124 7195 13124 7197 13125 7198 13125 7269 13125 7269 13126 7198 13126 7199 13126 7269 13127 7199 13127 7280 13127 7280 13128 7199 13128 7200 13128 7280 13129 7200 13129 7170 13129 7281 13130 7282 13130 7283 13130 7284 13131 4307 13131 7285 13131 7285 13132 4307 13132 4311 13132 7180 13133 7286 13133 7287 13133 7186 13134 7184 13134 7287 13134 7287 13135 7184 13135 7182 13135 7287 13136 7182 13136 7180 13136 7170 13137 7171 13137 7280 13137 7280 13138 7171 13138 7177 13138 7175 13139 7173 13139 7288 13139 7288 13140 7173 13140 7189 13140 7288 13141 7189 13141 7188 13141 7188 13142 7186 13142 7288 13142 7288 13143 7186 13143 7287 13143 7288 13144 7287 13144 7289 13144 7289 13145 7287 13145 7286 13145 7289 13146 7286 13146 7290 13146 7290 13147 7286 13147 7291 13147 7290 13148 7291 13148 7292 13148 7292 13149 7291 13149 7283 13149 7292 13150 7283 13150 7293 13150 7293 13151 7283 13151 7282 13151 4309 13152 6718 13152 4311 13152 4311 13153 6718 13153 7281 13153 4311 13154 7281 13154 7285 13154 7285 13155 7281 13155 7283 13155 7285 13156 7283 13156 7284 13156 7284 13157 7283 13157 7291 13157 7284 13158 7291 13158 7294 13158 7294 13159 7291 13159 7286 13159 7294 13160 7286 13160 7295 13160 7295 13161 7286 13161 7180 13161 7295 13162 7180 13162 7190 13162 6720 13163 6717 13163 7293 13163 7293 13164 6717 13164 7276 13164 7276 13165 7275 13165 7293 13165 7293 13166 7275 13166 7274 13166 7293 13167 7274 13167 7292 13167 7292 13168 7274 13168 7277 13168 7292 13169 7277 13169 7290 13169 7290 13170 7277 13170 7278 13170 7290 13171 7278 13171 7289 13171 7289 13172 7278 13172 7279 13172 7289 13173 7279 13173 7288 13173 7288 13174 7279 13174 7280 13174 7288 13175 7280 13175 7175 13175 7175 13176 7280 13176 7177 13176 6718 13177 6724 13177 7281 13177 7281 13178 6724 13178 6723 13178 7281 13179 6723 13179 7282 13179 7282 13180 6723 13180 6722 13180 7282 13181 6722 13181 7293 13181 7293 13182 6722 13182 6721 13182 7293 13183 6721 13183 6720 13183 7296 13184 604 13184 7297 13184 7297 13185 604 13185 603 13185 7297 13186 603 13186 606 13186 7298 13187 7299 13187 7020 13187 7020 13188 7299 13188 7169 13188 7300 13189 7191 13189 7192 13189 7190 13190 7191 13190 7295 13190 7295 13191 7191 13191 7300 13191 7295 13192 7300 13192 7294 13192 7192 13193 7297 13193 7300 13193 7300 13194 7297 13194 606 13194 7300 13195 606 13195 7294 13195 7294 13196 606 13196 612 13196 7294 13197 612 13197 7284 13197 7284 13198 612 13198 4308 13198 7284 13199 4308 13199 4307 13199 7192 13200 7169 13200 7297 13200 7297 13201 7169 13201 7299 13201 7297 13202 7299 13202 7296 13202 7296 13203 7299 13203 7298 13203 7296 13204 7298 13204 7301 13204 7302 13205 7298 13205 7020 13205 7020 13206 7044 13206 7302 13206 7302 13207 7044 13207 6994 13207 7302 13208 6994 13208 7303 13208 7303 13209 6994 13209 6996 13209 7303 13210 6996 13210 7304 13210 7304 13211 6996 13211 7022 13211 7304 13212 7022 13212 7305 13212 7305 13213 7022 13213 7021 13213 7305 13214 7021 13214 7306 13214 7306 13215 7021 13215 6991 13215 7306 13216 6991 13216 7307 13216 614 13217 616 13217 7307 13217 7307 13218 616 13218 620 13218 7307 13219 620 13219 7306 13219 7306 13220 620 13220 621 13220 7306 13221 621 13221 7305 13221 7305 13222 621 13222 619 13222 7305 13223 619 13223 7304 13223 7304 13224 619 13224 618 13224 7304 13225 618 13225 7303 13225 7303 13226 618 13226 617 13226 7303 13227 617 13227 7302 13227 7302 13228 617 13228 615 13228 7302 13229 615 13229 7298 13229 7298 13230 615 13230 7301 13230 4301 13231 614 13231 7308 13231 7308 13232 614 13232 7307 13232 7308 13233 7307 13233 7049 13233 7049 13234 7307 13234 6991 13234 7243 13235 7309 13235 7241 13235 7243 13236 7240 13236 7309 13236 7309 13237 7240 13237 7239 13237 7309 13238 7239 13238 7310 13238 7310 13239 7239 13239 4331 13239 7310 13240 4331 13240 4329 13240 7311 13241 7312 13241 1377 13241 1377 13242 7312 13242 1379 13242 7313 11388 7314 11388 7315 11388 7315 633 7314 633 7316 633 7315 633 7316 633 7317 633 7318 13243 7319 13243 7315 13243 7315 13244 7319 13244 7320 13244 7315 13245 7320 13245 7313 13245 7321 633 7322 633 7315 633 7315 633 7322 633 7323 633 7315 633 7323 633 7318 633 7317 633 7324 633 7315 633 7315 13246 7324 13246 7325 13246 7315 13247 7325 13247 7321 13247 7326 633 7327 633 7328 633 7328 633 7327 633 7329 633 7328 633 7329 633 7330 633 7330 633 7329 633 7331 633 7332 11383 7333 11383 7334 11383 7332 11384 7334 11384 7335 11384 7335 13248 7334 13248 7336 13248 7335 13249 7336 13249 7337 13249 7333 11377 7332 11377 7338 11377 7333 11378 7338 11378 7339 11378 7339 11379 7338 11379 7340 11379 7339 11380 7340 11380 7341 11380 7341 13250 7340 13250 7342 13250 7341 13251 7342 13251 7343 13251 7344 13252 7345 13252 7346 13252 7344 13253 7346 13253 7347 13253 7347 13254 7346 13254 7348 13254 7347 13255 7348 13255 7349 13255 7349 13256 7348 13256 7336 13256 7336 13257 7348 13257 7337 13257 7343 11367 7342 11367 7350 11367 7351 13258 7352 13258 7350 13258 7350 11369 7352 11369 7353 11369 7350 13259 7353 13259 7343 13259 7354 13260 7355 13260 7356 13260 7354 13261 7356 13261 7357 13261 7357 13262 7356 13262 7345 13262 7357 13263 7345 13263 7344 13263 7358 11343 7359 11343 7360 11343 7358 11344 7360 11344 7361 11344 7361 11345 7360 11345 7362 11345 7361 11346 7362 11346 7363 11346 7363 11347 7362 11347 7364 11347 7363 11347 7364 11347 7365 11347 7365 11350 7364 11350 7366 11350 7365 11350 7366 11350 7367 11350 7367 11351 7366 11351 7368 11351 7367 11351 7368 11351 7369 11351 7369 11352 7368 11352 7370 11352 7369 11353 7370 11353 7371 11353 7371 11354 7370 11354 7372 11354 7371 11355 7372 11355 7373 11355 7373 11356 7372 11356 7374 11356 7373 11357 7374 11357 7375 11357 7375 13264 7374 13264 7376 13264 7375 13265 7376 13265 7377 13265 7377 11361 7376 11361 7378 11361 7377 11361 7378 11361 7379 11361 7379 13266 7378 13266 7380 13266 7379 11362 7380 11362 7381 11362 7382 95 7358 95 7383 95 7345 13267 7356 13267 7355 13267 7355 13268 7384 13268 7385 13268 7348 95 7346 95 7345 95 7381 95 7386 95 7387 95 7387 95 7386 95 7383 95 7383 13269 7386 13269 7388 13269 7383 13270 7388 13270 7382 13270 7355 95 7358 95 7361 95 7355 13271 7385 13271 7358 13271 7358 13272 7385 13272 7389 13272 7358 95 7389 95 7383 95 7373 95 7375 95 7390 95 7377 95 7391 95 7375 95 7375 95 7391 95 7392 95 7375 95 7392 95 7390 95 7387 13273 7393 13273 7381 13273 7381 13274 7393 13274 7394 13274 7381 95 7394 95 7379 95 7379 13275 7394 13275 7395 13275 7379 95 7395 95 7396 95 7371 95 7351 95 7369 95 7369 13276 7351 13276 7350 13276 7369 95 7350 95 7367 95 7367 13277 7350 13277 7342 13277 7367 95 7342 95 7365 95 7365 95 7342 95 7363 95 7390 95 7397 95 7373 95 7373 13278 7397 13278 7398 13278 7373 13279 7398 13279 7371 13279 7371 13280 7398 13280 7399 13280 7371 13281 7399 13281 7351 13281 7351 13282 7399 13282 7400 13282 7351 95 7400 95 7401 95 7396 95 7402 95 7379 95 7379 95 7402 95 7403 95 7379 95 7403 95 7377 95 7377 95 7403 95 7404 95 7377 13283 7404 13283 7391 13283 7338 95 7332 95 7335 95 7361 95 7363 95 7355 95 7355 13284 7363 13284 7342 13284 7355 13285 7342 13285 7345 13285 7345 95 7342 95 7340 95 7345 95 7340 95 7348 95 7348 11342 7340 11342 7338 11342 7348 95 7338 95 7337 95 7337 95 7338 95 7335 95 7405 95 7406 95 7407 95 7407 11321 7406 11321 7408 11321 7407 11320 7408 11320 7409 11320 7410 13286 7411 13286 7407 13286 7407 95 7411 95 7412 95 7407 95 7412 95 7405 95 7413 95 7414 95 7407 95 7407 95 7414 95 7415 95 7407 95 7415 95 7410 95 7409 95 7416 95 7407 95 7407 95 7416 95 7417 95 7407 95 7417 95 7413 95 7415 13287 7418 13287 7410 13287 7410 13288 7418 13288 7419 13288 7410 13289 7419 13289 7411 13289 7411 13290 7419 13290 7420 13290 7411 13291 7420 13291 7412 13291 7412 13292 7420 13292 7421 13292 7412 13293 7421 13293 7405 13293 7405 13294 7421 13294 7422 13294 7405 13295 7422 13295 7406 13295 7406 13296 7422 13296 7423 13296 7406 13297 7423 13297 7408 13297 7408 13298 7423 13298 7424 13298 7408 13299 7424 13299 7409 13299 7409 13300 7424 13300 7425 13300 7409 13301 7425 13301 7416 13301 7416 13302 7425 13302 7426 13302 7416 13303 7426 13303 7417 13303 7417 13304 7426 13304 7427 13304 7417 13305 7427 13305 7413 13305 7413 13306 7427 13306 7428 13306 7413 13307 7428 13307 7414 13307 7414 13308 7428 13308 7429 13308 7414 13308 7429 13308 7415 13308 7415 13309 7429 13309 7418 13309 7430 13310 7431 13310 7432 13310 7432 13311 7433 13311 7430 13311 7430 13312 7433 13312 7434 13312 7430 13313 7434 13313 7435 13313 7436 13314 7437 13314 7438 13314 7439 13315 7440 13315 7438 13315 7438 13316 7440 13316 7441 13316 7438 13317 7441 13317 7436 13317 7431 13318 7442 13318 7432 13318 7432 13319 7442 13319 7439 13319 7432 13320 7439 13320 7443 13320 7443 13321 7439 13321 7438 13321 7444 13322 7445 13322 7446 13322 7447 13323 7448 13323 7449 13323 7450 13324 283 13324 284 13324 7451 13325 256 13325 283 13325 7452 13326 7453 13326 7454 13326 7454 13327 7453 13327 7455 13327 7454 13328 7455 13328 7456 13328 283 13329 7450 13329 7451 13329 7451 13330 7450 13330 7457 13330 7451 13331 7457 13331 7458 13331 7458 13332 7457 13332 7453 13332 7458 13333 7453 13333 7459 13333 7459 13334 7453 13334 7452 13334 7459 13335 7452 13335 7437 13335 7448 13336 7447 13336 7455 13336 7455 13337 7447 13337 7460 13337 7455 13338 7460 13338 7456 13338 7445 13339 7461 13339 7446 13339 7446 13340 7461 13340 7462 13340 7446 13341 7462 13341 7463 13341 7463 13342 7462 13342 7464 13342 7463 13343 7464 13343 7465 13343 7466 13344 7467 13344 7463 13344 7463 13345 7467 13345 7468 13345 7463 13346 7468 13346 7446 13346 7446 13347 7468 13347 7469 13347 7446 13348 7469 13348 7444 13348 7444 13349 7469 13349 7470 13349 7444 13350 7470 13350 7471 13350 7472 13351 7473 13351 7466 13351 7466 13352 7473 13352 7474 13352 7466 13353 7474 13353 7467 13353 7475 13354 7476 13354 7477 13354 7477 13355 7476 13355 7478 13355 7477 13356 7478 13356 7472 13356 7472 13357 7478 13357 7479 13357 7472 13358 7479 13358 7473 13358 285 13359 7476 13359 284 13359 284 13360 7476 13360 7475 13360 284 13361 7475 13361 7450 13361 7450 13362 7475 13362 7477 13362 7450 13363 7477 13363 7457 13363 7457 13364 7477 13364 7472 13364 7457 13365 7472 13365 7453 13365 7453 13366 7472 13366 7466 13366 7453 13367 7466 13367 7455 13367 7455 13368 7466 13368 7463 13368 7455 13369 7463 13369 7448 13369 7448 13370 7463 13370 7465 13370 7448 13371 7465 13371 7449 13371 7480 13372 7481 13372 7482 13372 7483 13373 7484 13373 7485 13373 7486 13374 214 13374 215 13374 7486 13375 215 13375 7487 13375 215 13376 7488 13376 7487 13376 7487 13377 7488 13377 7489 13377 7487 13378 7489 13378 7490 13378 7490 13379 7489 13379 7491 13379 7490 13380 7491 13380 7492 13380 7492 13381 7491 13381 7493 13381 7493 13382 7491 13382 7494 13382 7494 13383 7491 13383 7495 13383 7494 13384 7495 13384 7496 13384 7496 13385 7495 13385 7497 13385 7496 13386 7497 13386 7498 13386 7498 13387 7497 13387 7499 13387 7499 13388 7497 13388 7500 13388 7499 13389 7500 13389 7501 13389 7502 13390 7501 13390 7503 13390 7503 13391 7501 13391 7500 13391 7503 13392 7500 13392 7504 13392 7504 13393 7500 13393 7505 13393 7505 13394 7500 13394 7506 13394 7506 13395 7500 13395 7497 13395 7506 13396 7497 13396 7484 13396 7483 13397 7485 13397 7507 13397 7480 13398 7508 13398 7481 13398 7481 13399 7508 13399 7509 13399 7481 13400 7509 13400 7485 13400 7485 13401 7509 13401 7510 13401 7485 13402 7510 13402 7507 13402 7511 13403 7512 13403 7513 13403 7513 13404 7512 13404 7514 13404 7513 13405 7514 13405 7482 13405 7482 13406 7514 13406 7515 13406 7482 13407 7515 13407 7480 13407 7484 13408 7497 13408 7485 13408 7485 13409 7497 13409 7495 13409 7485 13410 7495 13410 7481 13410 7481 13411 7495 13411 7491 13411 7481 13412 7491 13412 7482 13412 7482 13413 7491 13413 7489 13413 7482 13414 7489 13414 7513 13414 7513 13415 7489 13415 7488 13415 7513 13416 7488 13416 7511 13416 7511 13417 7488 13417 215 13417 7511 13418 215 13418 7512 13418 7512 13419 215 13419 209 13419 7512 13420 209 13420 207 13420 7516 13421 7517 13421 7518 13421 7518 13422 7517 13422 7519 13422 7518 13423 7519 13423 7520 13423 7520 13424 7519 13424 7521 13424 7520 13425 7521 13425 7522 13425 7522 13426 7521 13426 7523 13426 7523 13427 7521 13427 7524 13427 7523 13428 7524 13428 7525 13428 7515 13429 7526 13429 7525 13429 7525 13430 7526 13430 7527 13430 7527 13431 7528 13431 7525 13431 7525 13432 7528 13432 7529 13432 7525 13433 7529 13433 7523 13433 7419 13434 7418 13434 7530 13434 7429 95 7531 95 7418 95 7418 95 7531 95 7532 95 7418 13435 7532 13435 7530 13435 7530 95 7380 95 7419 95 7419 13436 7380 13436 7378 13436 7419 13437 7378 13437 7420 13437 7420 95 7378 95 7376 95 7420 11173 7376 11173 7421 11173 7421 95 7376 95 7374 95 7421 13438 7374 13438 7422 13438 7422 95 7374 95 7372 95 7422 13439 7372 13439 7423 13439 7423 11175 7372 11175 7370 11175 7423 95 7370 95 7424 95 7424 13440 7370 13440 7368 13440 7424 95 7368 95 7425 95 7425 95 7368 95 7366 95 7425 95 7366 95 7426 95 7426 95 7366 95 7364 95 7426 95 7364 95 7427 95 7427 95 7364 95 7362 95 7427 13441 7362 13441 7428 13441 7428 13442 7362 13442 7360 13442 7428 13443 7360 13443 7429 13443 7429 11176 7360 11176 7359 11176 7429 11177 7359 11177 7531 11177 7464 13444 7533 13444 7534 13444 7535 13445 7536 13445 7471 13445 7537 13446 7538 13446 7539 13446 7438 13447 7540 13447 7443 13447 7443 13448 7540 13448 7541 13448 7443 13449 7541 13449 7432 13449 7432 13450 7541 13450 7433 13450 7433 13451 7541 13451 7542 13451 7433 13452 7542 13452 7543 13452 7543 13453 7544 13453 7433 13453 7433 13454 7544 13454 7545 13454 7433 13455 7545 13455 7434 13455 7546 13456 7435 13456 7547 13456 7547 13457 7435 13457 7434 13457 7547 13458 7434 13458 7548 13458 7548 13459 7434 13459 7545 13459 7549 13460 7550 13460 7541 13460 7541 13461 7550 13461 7551 13461 7551 13462 7552 13462 7541 13462 7541 13463 7552 13463 7553 13463 7541 13464 7553 13464 7542 13464 7542 13465 7553 13465 7554 13465 7542 13466 7554 13466 7543 13466 7540 13467 7555 13467 7541 13467 7541 13468 7555 13468 7556 13468 7541 13469 7556 13469 7549 13469 7549 13470 7556 13470 7557 13470 7549 13471 7557 13471 7558 13471 7558 13472 7557 13472 7539 13472 7558 13473 7539 13473 7559 13473 7559 13474 7539 13474 7538 13474 7536 13475 7535 13475 7560 13475 7462 13476 7461 13476 7560 13476 7560 13477 7461 13477 7445 13477 7560 13478 7445 13478 7536 13478 7536 13479 7445 13479 7444 13479 7536 13480 7444 13480 7471 13480 7464 13481 7462 13481 7533 13481 7533 13482 7462 13482 7560 13482 7533 13483 7560 13483 7561 13483 7561 13484 7560 13484 7535 13484 7561 13485 7535 13485 7562 13485 7452 13486 7454 13486 7563 13486 7563 13487 7454 13487 7456 13487 7563 13488 7456 13488 7564 13488 7564 13489 7456 13489 7460 13489 7564 13490 7460 13490 7565 13490 7565 13491 7460 13491 7447 13491 7565 13492 7447 13492 7566 13492 7566 13493 7447 13493 7449 13493 7566 13494 7449 13494 7534 13494 7534 13495 7449 13495 7465 13495 7534 13496 7465 13496 7464 13496 7561 13497 7567 13497 7533 13497 7533 13498 7567 13498 7537 13498 7533 13499 7537 13499 7534 13499 7534 13500 7537 13500 7539 13500 7534 13501 7539 13501 7566 13501 7566 13502 7539 13502 7557 13502 7566 11161 7557 11161 7565 11161 7565 13503 7557 13503 7556 13503 7565 13504 7556 13504 7564 13504 7564 13505 7556 13505 7555 13505 7564 13506 7555 13506 7563 13506 7563 13507 7555 13507 7540 13507 7563 13508 7540 13508 7452 13508 7452 13509 7540 13509 7438 13509 7452 13510 7438 13510 7437 13510 7568 13511 7569 13511 7570 13511 7505 13512 7506 13512 7571 13512 7509 13513 7508 13513 7572 13513 7573 13514 7574 13514 7575 13514 7575 13515 7574 13515 7576 13515 7575 13516 7576 13516 7577 13516 7577 13517 7576 13517 7578 13517 7579 13518 7580 13518 7581 13518 7581 13519 7580 13519 7582 13519 7582 13520 7583 13520 7581 13520 7581 13521 7583 13521 7584 13521 7581 13522 7584 13522 7585 13522 7586 13523 7587 13523 7579 13523 7579 13524 7587 13524 7588 13524 7579 13525 7588 13525 7580 13525 7580 13526 7588 13526 7589 13526 7580 13527 7589 13527 7582 13527 7579 13528 7519 13528 7517 13528 7586 13529 7579 13529 7590 13529 7590 13530 7579 13530 7517 13530 7590 13531 7517 13531 7516 13531 7521 13532 7591 13532 7524 13532 7524 13533 7591 13533 7592 13533 7524 13534 7592 13534 7525 13534 7525 13535 7592 13535 7572 13535 7508 13536 7480 13536 7572 13536 7572 13537 7480 13537 7515 13537 7572 13538 7515 13538 7525 13538 7483 13539 7507 13539 7593 13539 7593 13540 7507 13540 7510 13540 7505 13541 7571 13541 7504 13541 7594 13542 7595 13542 7596 13542 7596 13543 7595 13543 7597 13543 7596 13544 7597 13544 7598 13544 7598 13545 7597 13545 7502 13545 7598 13546 7502 13546 7503 13546 7569 13547 7568 13547 7599 13547 7568 13548 7594 13548 7599 13548 7599 13549 7594 13549 7596 13549 7599 13550 7596 13550 7571 13550 7571 13551 7596 13551 7598 13551 7571 13552 7598 13552 7504 13552 7504 13553 7598 13553 7503 13553 7578 13554 7600 13554 7577 13554 7577 13555 7600 13555 7601 13555 7577 13556 7601 13556 7575 13556 7575 13557 7601 13557 7581 13557 7575 13558 7581 13558 7573 13558 7573 13559 7581 13559 7585 13559 7506 13560 7484 13560 7571 13560 7571 13561 7484 13561 7483 13561 7571 13562 7483 13562 7599 13562 7599 13563 7483 13563 7593 13563 7599 13564 7593 13564 7569 13564 7569 13565 7593 13565 7601 13565 7569 13566 7601 13566 7570 13566 7570 13567 7601 13567 7600 13567 7510 13568 7509 13568 7593 13568 7593 13569 7509 13569 7572 13569 7593 13570 7572 13570 7601 13570 7601 13571 7572 13571 7592 13571 7601 13572 7592 13572 7581 13572 7581 13573 7592 13573 7591 13573 7581 13574 7591 13574 7579 13574 7579 13575 7591 13575 7521 13575 7579 13576 7521 13576 7519 13576 7537 13577 7567 13577 7602 13577 7561 13578 7562 13578 7603 13578 7604 13579 7605 13579 7384 13579 7384 13580 7605 13580 7606 13580 7384 13581 7606 13581 7385 13581 7385 13582 7606 13582 7603 13582 7385 13583 7603 13583 7389 13583 7607 13584 7558 13584 7608 13584 7608 13585 7558 13585 7559 13585 7608 13586 7559 13586 7602 13586 7602 13587 7559 13587 7538 13587 7602 13588 7538 13588 7537 13588 7604 13589 7607 13589 7605 13589 7605 13590 7607 13590 7608 13590 7605 13591 7608 13591 7606 13591 7606 13592 7608 13592 7602 13592 7606 13593 7602 13593 7603 13593 7603 13594 7602 13594 7567 13594 7603 13595 7567 13595 7561 13595 7354 13596 7609 13596 7610 13596 7384 13597 7355 13597 7611 13597 7611 13598 7355 13598 7354 13598 7611 13599 7354 13599 7612 13599 7612 13600 7354 13600 7610 13600 7547 13601 7613 13601 7546 13601 7554 13602 7553 13602 7614 13602 7551 13603 7550 13603 7607 13603 7607 13604 7550 13604 7549 13604 7607 13605 7549 13605 7558 13605 7553 13606 7552 13606 7614 13606 7614 13607 7552 13607 7551 13607 7614 13608 7551 13608 7615 13608 7615 13609 7551 13609 7607 13609 7615 13610 7607 13610 7604 13610 7544 13611 7543 13611 7610 13611 7610 13612 7609 13612 7544 13612 7544 13613 7609 13613 7616 13613 7544 13614 7616 13614 7545 13614 7613 13615 7547 13615 7616 13615 7616 13616 7547 13616 7548 13616 7616 13617 7548 13617 7545 13617 7543 13618 7554 13618 7610 13618 7610 13619 7554 13619 7614 13619 7610 13620 7614 13620 7612 13620 7612 13621 7614 13621 7615 13621 7612 13622 7615 13622 7611 13622 7611 13623 7615 13623 7604 13623 7611 13624 7604 13624 7384 13624 7617 13625 7618 13625 7619 13625 7584 13626 7620 13626 7585 13626 7621 13627 7622 13627 7617 13627 7623 13628 7588 13628 7587 13628 7574 13629 7573 13629 7619 13629 7574 13630 7624 13630 7576 13630 7576 13631 7624 13631 7625 13631 7576 13632 7625 13632 7578 13632 7574 13633 7619 13633 7624 13633 7624 13634 7619 13634 7618 13634 7624 13635 7618 13635 7401 13635 7623 13636 7587 13636 7626 13636 7626 13637 7587 13637 7586 13637 7626 13638 7586 13638 7590 13638 7588 13639 7623 13639 7589 13639 7589 13640 7623 13640 7621 13640 7589 13641 7621 13641 7582 13641 7573 13642 7585 13642 7619 13642 7619 13643 7585 13643 7620 13643 7619 13644 7620 13644 7617 13644 7617 13645 7620 13645 7584 13645 7617 13646 7584 13646 7621 13646 7621 13647 7584 13647 7583 13647 7621 13648 7583 13648 7582 13648 7617 13649 7622 13649 7618 13649 7618 13650 7622 13650 7352 13650 7618 13651 7352 13651 7401 13651 7401 13652 7352 13652 7351 13652 7627 13653 7628 13653 7629 13653 7630 13654 7631 13654 7632 13654 7630 13655 7632 13655 7633 13655 7634 13656 7635 13656 7636 13656 7635 13657 7637 13657 7638 13657 7639 13658 7640 13658 7641 13658 7641 13659 7640 13659 7642 13659 7643 13660 7644 13660 7645 13660 7645 13661 7644 13661 7641 13661 7645 13662 7641 13662 7646 13662 7646 13663 7641 13663 7642 13663 7646 13664 7642 13664 7647 13664 7648 13665 7649 13665 7650 13665 7649 13666 7627 13666 7650 13666 7650 13667 7627 13667 7629 13667 7650 13668 7629 13668 7651 13668 7651 13669 7629 13669 7652 13669 7651 13670 7652 13670 7632 13670 7632 13671 7652 13671 7636 13671 7632 13672 7636 13672 7633 13672 7633 13673 7636 13673 7635 13673 7633 13674 7635 13674 7653 13674 7653 13675 7635 13675 7638 13675 7628 13676 7639 13676 7629 13676 7629 13677 7639 13677 7641 13677 7629 13678 7641 13678 7652 13678 7652 13679 7641 13679 7644 13679 7652 13680 7644 13680 7636 13680 7636 13681 7644 13681 7643 13681 7636 13682 7643 13682 7634 13682 7648 10956 7650 10956 7654 10956 7654 13683 7650 13683 7651 13683 7654 13684 7651 13684 7655 13684 7655 13685 7651 13685 7632 13685 7655 13686 7632 13686 7656 13686 7656 13687 7632 13687 7631 13687 7656 13688 7631 13688 7657 13688 7600 13689 7578 13689 7658 13689 7658 13690 7578 13690 7625 13690 7399 13691 7659 13691 7660 13691 7661 13692 7662 13692 7595 13692 7399 13693 7660 13693 7400 13693 7400 13694 7660 13694 7624 13694 7400 13695 7624 13695 7401 13695 7595 13696 7594 13696 7661 13696 7661 13697 7594 13697 7568 13697 7661 13698 7568 13698 7658 13698 7658 13699 7568 13699 7570 13699 7658 13700 7570 13700 7600 13700 7399 13701 7662 13701 7659 13701 7659 13702 7662 13702 7661 13702 7659 13703 7661 13703 7660 13703 7660 13704 7661 13704 7658 13704 7660 13705 7658 13705 7624 13705 7624 13706 7658 13706 7625 13706 7663 13707 7664 13707 7435 13707 7435 13708 7664 13708 7665 13708 7435 13709 7665 13709 7430 13709 7663 13710 7435 13710 7666 13710 7666 13711 7435 13711 7354 13711 7666 13712 7354 13712 7357 13712 7616 13713 7609 13713 7613 13713 7613 13714 7609 13714 7354 13714 7613 13715 7354 13715 7546 13715 7546 13716 7354 13716 7435 13716 7336 13717 7667 13717 7349 13717 7349 13718 7667 13718 7668 13718 7349 13719 7668 13719 7347 13719 7347 13720 7668 13720 7666 13720 7347 13721 7666 13721 7344 13721 7344 13722 7666 13722 7357 13722 7668 10885 7667 10885 7669 10885 7669 10886 7667 10886 7670 10886 7333 10887 7671 10887 7672 10887 7333 13723 7672 13723 7334 13723 7334 13724 7672 13724 7670 13724 7334 10890 7670 10890 7336 10890 7336 13725 7670 13725 7667 13725 7341 13726 7343 13726 7353 13726 7622 13727 7621 13727 7673 13727 7518 13728 7674 13728 7516 13728 7516 13729 7674 13729 7675 13729 7675 13730 7676 13730 7516 13730 7516 13731 7676 13731 7673 13731 7516 13732 7673 13732 7590 13732 7341 13733 7673 13733 7339 13733 7339 13734 7673 13734 7671 13734 7339 13735 7671 13735 7333 13735 7341 13736 7353 13736 7673 13736 7673 13737 7353 13737 7352 13737 7673 13738 7352 13738 7622 13738 7621 13739 7623 13739 7673 13739 7673 13740 7623 13740 7626 13740 7673 13741 7626 13741 7590 13741 7677 13742 7678 13742 7679 13742 7680 13743 7681 13743 7682 13743 7682 13744 7683 13744 7680 13744 7680 10858 7683 10858 7684 10858 7680 13745 7684 13745 7685 13745 7684 13746 7686 13746 7685 13746 7685 13747 7686 13747 7687 13747 7685 13748 7687 13748 7688 13748 7688 13749 7687 13749 7677 13749 7677 13750 7679 13750 7688 13750 7688 13751 7679 13751 7689 13751 7688 10866 7689 10866 7690 10866 7690 13752 7689 13752 7691 13752 7690 13753 7691 13753 7692 13753 7693 13754 7682 13754 7681 13754 7694 13755 7695 13755 7696 13755 7697 13756 7695 13756 7698 13756 7698 13757 7695 13757 7694 13757 7698 13758 7694 13758 7699 13758 7699 13759 7694 13759 7700 13759 7693 13760 7681 13760 7696 13760 7696 13761 7681 13761 7701 13761 7696 13762 7701 13762 7694 13762 7694 13763 7701 13763 7702 13763 7694 13764 7702 13764 7700 13764 7689 13765 7679 13765 7703 13765 7703 632 7679 632 7678 632 7703 13766 7678 13766 7677 13766 7704 13767 7705 13767 7706 13767 7706 13768 7705 13768 7707 13768 7708 632 7709 632 7703 632 7703 13769 7709 13769 7710 13769 7703 13770 7710 13770 7711 13770 7703 13771 7697 13771 7712 13771 7705 13772 7703 13772 7713 13772 7714 632 7708 632 7715 632 7715 632 7708 632 7703 632 7715 632 7703 632 7716 632 7716 632 7703 632 7705 632 7684 13773 7703 13773 7686 13773 7686 13774 7703 13774 7677 13774 7686 13775 7677 13775 7687 13775 7717 13776 7718 13776 7705 13776 7705 13777 7718 13777 7719 13777 7705 13778 7719 13778 7707 13778 7684 13779 7683 13779 7703 13779 7703 632 7683 632 7682 632 7703 13780 7682 13780 7693 13780 7720 632 7721 632 7712 632 7712 13781 7721 13781 7722 13781 7712 13782 7722 13782 7703 13782 7713 13783 7723 13783 7705 13783 7705 13784 7723 13784 7724 13784 7705 13785 7724 13785 7717 13785 7711 632 7725 632 7703 632 7703 13786 7725 13786 7691 13786 7703 13787 7691 13787 7689 13787 7693 632 7696 632 7703 632 7703 13788 7696 13788 7695 13788 7703 13789 7695 13789 7697 13789 7726 13790 7727 13790 7728 13790 7728 13791 7727 13791 7729 13791 7728 13792 7729 13792 7730 13792 7603 13793 7562 13793 7730 13793 7730 13794 7729 13794 7603 13794 7603 13795 7729 13795 7383 13795 7603 13796 7383 13796 7389 13796 7726 13797 7731 13797 7727 13797 7727 13798 7731 13798 7393 13798 7727 13799 7393 13799 7729 13799 7729 13800 7393 13800 7387 13800 7729 13801 7387 13801 7383 13801 7402 13802 7396 13802 7732 13802 7732 13803 7396 13803 7395 13803 7732 13804 7395 13804 7731 13804 7731 13805 7395 13805 7394 13805 7731 13806 7394 13806 7393 13806 7402 10790 7732 10790 7403 10790 7403 10791 7732 10791 7733 10791 7403 13807 7733 13807 7404 13807 7404 13808 7733 13808 7734 13808 7404 10794 7734 10794 7391 10794 7391 13809 7734 13809 7735 13809 7391 13810 7735 13810 7392 13810 7392 13811 7735 13811 7736 13811 7392 13812 7736 13812 7390 13812 7397 13813 7737 13813 7398 13813 7398 13814 7737 13814 7662 13814 7398 13815 7662 13815 7399 13815 7595 13816 7662 13816 7738 13816 7738 13817 7662 13817 7737 13817 7738 13818 7737 13818 7736 13818 7736 13819 7737 13819 7397 13819 7736 13820 7397 13820 7390 13820 7734 13821 7739 13821 7735 13821 7735 13822 7739 13822 7740 13822 7735 13823 7740 13823 7736 13823 7736 13824 7740 13824 7741 13824 7736 13825 7741 13825 7738 13825 7726 13826 7742 13826 7731 13826 7731 13827 7742 13827 7743 13827 7731 13828 7743 13828 7732 13828 7732 13829 7743 13829 7744 13829 7732 13830 7744 13830 7733 13830 7733 13831 7744 13831 7745 13831 7733 13832 7745 13832 7734 13832 7734 13833 7745 13833 7746 13833 7734 13834 7746 13834 7739 13834 7747 13835 7748 13835 7749 13835 7750 13836 7751 13836 7748 13836 7749 13837 7752 13837 7747 13837 7747 13838 7752 13838 7753 13838 7747 13839 7753 13839 7754 13839 7430 13840 7665 13840 7755 13840 7755 13841 7665 13841 7756 13841 7755 13842 7756 13842 7757 13842 7757 13843 7756 13843 7758 13843 7757 13844 7758 13844 7759 13844 7759 13845 7758 13845 7760 13845 7759 13846 7760 13846 7761 13846 7761 13847 7760 13847 7754 13847 7761 13848 7754 13848 7762 13848 7762 13849 7754 13849 7753 13849 7748 13850 7747 13850 7750 13850 7750 13851 7747 13851 7754 13851 7750 13852 7754 13852 7763 13852 7763 13853 7754 13853 7760 13853 7763 10766 7760 10766 7764 10766 7764 13854 7760 13854 7758 13854 7764 13855 7758 13855 7765 13855 7765 13856 7758 13856 7756 13856 7765 13857 7756 13857 7766 13857 7766 13858 7756 13858 7665 13858 7766 13859 7665 13859 7664 13859 7439 13860 7767 13860 7768 13860 7439 13861 7769 13861 7770 13861 7431 13862 7430 13862 7755 13862 7771 13863 7772 13863 7773 13863 7774 13864 257 13864 7775 13864 7431 13865 7755 13865 7442 13865 7768 13866 7776 13866 7777 13866 7439 13867 7768 13867 7440 13867 7440 13868 7768 13868 7777 13868 7440 13869 7777 13869 7441 13869 7778 13870 7779 13870 7780 13870 7780 13871 7779 13871 7774 13871 7780 13872 7774 13872 7781 13872 7781 13873 7774 13873 7775 13873 7781 13874 7775 13874 7782 13874 7782 13875 7775 13875 7783 13875 7439 13876 7770 13876 7767 13876 7767 13877 7770 13877 7784 13877 7767 13878 7784 13878 7768 13878 7761 13879 7785 13879 7759 13879 7759 13880 7785 13880 7786 13880 7759 13881 7786 13881 7757 13881 7757 13882 7786 13882 7787 13882 7757 13883 7787 13883 7755 13883 7755 13884 7787 13884 7788 13884 7755 13885 7788 13885 7442 13885 7773 13886 7789 13886 7771 13886 7771 13887 7789 13887 7778 13887 7771 13888 7778 13888 7790 13888 7790 13889 7778 13889 7780 13889 7790 13890 7780 13890 7791 13890 7791 13891 7780 13891 7781 13891 7791 13892 7781 13892 7784 13892 7784 13893 7781 13893 7782 13893 7784 13894 7782 13894 7768 13894 7768 13895 7782 13895 7783 13895 7768 13896 7783 13896 7776 13896 7749 13897 7792 13897 7752 13897 7752 13898 7792 13898 7773 13898 7752 13899 7773 13899 7753 13899 7753 13900 7773 13900 7772 13900 7753 13901 7772 13901 7762 13901 7762 13902 7772 13902 7771 13902 7762 13903 7771 13903 7761 13903 7761 13904 7771 13904 7790 13904 7761 13905 7790 13905 7785 13905 7785 13906 7790 13906 7791 13906 7785 13907 7791 13907 7786 13907 7786 13908 7791 13908 7784 13908 7786 13909 7784 13909 7787 13909 7787 13910 7784 13910 7770 13910 7787 13911 7770 13911 7788 13911 7788 13912 7770 13912 7769 13912 7788 13913 7769 13913 7442 13913 7442 13914 7769 13914 7439 13914 7793 13915 7794 13915 7795 13915 7796 13916 7797 13916 288 13916 7798 13917 7799 13917 7800 13917 7801 13918 7802 13918 7803 13918 7803 13919 7802 13919 7804 13919 7803 13920 7804 13920 7805 13920 7805 13921 7804 13921 7798 13921 7805 13922 7798 13922 7806 13922 7806 13923 7798 13923 7800 13923 7806 13924 7800 13924 7807 13924 7808 13925 7809 13925 7801 13925 7801 13926 7809 13926 7810 13926 7801 13927 7810 13927 7802 13927 7796 13928 7808 13928 7797 13928 7797 13929 7808 13929 7801 13929 7797 13930 7801 13930 7811 13930 7811 13931 7801 13931 7793 13931 7794 13932 7812 13932 7795 13932 7795 13933 7812 13933 7813 13933 7795 13934 7813 13934 7814 13934 7814 13935 7813 13935 7815 13935 7816 13936 7817 13936 7815 13936 7815 13937 7817 13937 7818 13937 7815 13938 7818 13938 7814 13938 7815 13939 7819 13939 7816 13939 7816 13940 7819 13940 7820 13940 7816 13941 7820 13941 7821 13941 7637 13942 7821 13942 7638 13942 7638 13943 7821 13943 7820 13943 7638 13944 7820 13944 7653 13944 7653 13945 7820 13945 7633 13945 7822 13946 7657 13946 7823 13946 7823 13947 7657 13947 7631 13947 7824 13948 7825 13948 7826 13948 7826 13949 7825 13949 7827 13949 7826 13950 7827 13950 7828 13950 7828 13951 7827 13951 7829 13951 7828 13952 7829 13952 7830 13952 7830 13953 7829 13953 7831 13953 7830 13954 7831 13954 7832 13954 7630 13955 7633 13955 7832 13955 7832 13956 7633 13956 7820 13956 7832 13957 7820 13957 7830 13957 7830 13958 7820 13958 7819 13958 7830 13959 7819 13959 7828 13959 7828 13960 7819 13960 7815 13960 7828 13961 7815 13961 7826 13961 7826 13962 7815 13962 7813 13962 7826 13963 7813 13963 7824 13963 7824 13964 7813 13964 7812 13964 7793 13965 7801 13965 7794 13965 7794 13966 7801 13966 7803 13966 7794 13967 7803 13967 7812 13967 7812 13968 7803 13968 7805 13968 7812 13969 7805 13969 7824 13969 7824 13970 7805 13970 7806 13970 7824 13971 7806 13971 7825 13971 7825 13972 7806 13972 7807 13972 7825 13973 7807 13973 7827 13973 7827 13974 7807 13974 7833 13974 7827 13975 7833 13975 7829 13975 7829 13976 7833 13976 7822 13976 7829 13977 7822 13977 7831 13977 7831 13978 7822 13978 7823 13978 7831 13979 7823 13979 7832 13979 7832 13980 7823 13980 7631 13980 7832 13981 7631 13981 7630 13981 7807 13982 7800 13982 7656 13982 7656 13983 7800 13983 7834 13983 7656 13984 7834 13984 7655 13984 7807 13985 7656 13985 7833 13985 7833 13986 7656 13986 7657 13986 7833 13987 7657 13987 7822 13987 7648 13988 7835 13988 7836 13988 7836 13989 7835 13989 7837 13989 7836 13990 7837 13990 7838 13990 7838 13991 7837 13991 7839 13991 7839 13992 7837 13992 7840 13992 7839 13993 7840 13993 7841 13993 7841 13994 7840 13994 7842 13994 7841 13995 7842 13995 7843 13995 7844 13996 7845 13996 7846 13996 7846 13997 7845 13997 7847 13997 7846 13998 7847 13998 7848 13998 7848 13999 7847 13999 7834 13999 7848 14000 7834 14000 7799 14000 7799 14001 7834 14001 7800 14001 7845 14002 7842 14002 7847 14002 7847 14003 7842 14003 7840 14003 7847 14004 7840 14004 7834 14004 7834 14005 7840 14005 7837 14005 7834 14006 7837 14006 7655 14006 7655 14007 7837 14007 7835 14007 7655 14008 7835 14008 7654 14008 7654 14009 7835 14009 7648 14009 7849 14010 7850 14010 7851 14010 7852 14011 7853 14011 7854 14011 7855 14012 7856 14012 7857 14012 7857 14013 7856 14013 7858 14013 7857 14014 7858 14014 7859 14014 7859 14015 7858 14015 7860 14015 7860 14016 7858 14016 7861 14016 7860 14017 7861 14017 7862 14017 7863 14018 7864 14018 7865 14018 7852 14019 7854 14019 7866 14019 7866 14020 7854 14020 7867 14020 7866 14021 7867 14021 7868 14021 7869 14022 7870 14022 7871 14022 7871 14023 7870 14023 7872 14023 7871 14024 7872 14024 7873 14024 7855 14025 7874 14025 7856 14025 7856 14026 7874 14026 7875 14026 7856 14027 7875 14027 7858 14027 7858 14028 7875 14028 7876 14028 7858 14029 7876 14029 7861 14029 7877 14030 7862 14030 7878 14030 7878 14031 7862 14031 7861 14031 7878 14032 7861 14032 7879 14032 7879 14033 7861 14033 7876 14033 7879 14034 7876 14034 7864 14034 7864 14035 7876 14035 7880 14035 7864 14036 7880 14036 7865 14036 7865 14037 7880 14037 7881 14037 7874 14038 7851 14038 7875 14038 7875 14039 7851 14039 7850 14039 7875 14040 7850 14040 7869 14040 7869 14041 7850 14041 7849 14041 7869 14042 7849 14042 7870 14042 7870 14043 7849 14043 7882 14043 7870 14044 7882 14044 7872 14044 7871 14045 7868 14045 7869 14045 7869 14046 7868 14046 7867 14046 7869 14047 7867 14047 7875 14047 7875 14048 7867 14048 7854 14048 7875 14049 7854 14049 7876 14049 7876 14050 7854 14050 7853 14050 7876 14051 7853 14051 7880 14051 7880 14052 7853 14052 7852 14052 7880 14053 7852 14053 7881 14053 7883 14054 7884 14054 7885 14054 7886 14055 7884 14055 7887 14055 7887 14056 7884 14056 7883 14056 7887 10522 7883 10522 7888 10522 7888 14057 7883 14057 7889 14057 7888 14058 7889 14058 7890 14058 7890 14059 7889 14059 7891 14059 7890 14060 7891 14060 7892 14060 7892 14061 7891 14061 7893 14061 7893 14062 7891 14062 7894 14062 7893 14063 7894 14063 7895 14063 7896 14064 7663 14064 7666 14064 7664 14065 7663 14065 7766 14065 7766 14066 7663 14066 7896 14066 7766 14067 7896 14067 7897 14067 7751 14068 7750 14068 7898 14068 7898 14069 7750 14069 7763 14069 7898 14070 7763 14070 7899 14070 7899 14071 7763 14071 7764 14071 7899 14072 7764 14072 7897 14072 7897 14073 7764 14073 7765 14073 7897 14074 7765 14074 7766 14074 7668 14075 7895 14075 7666 14075 7666 14076 7895 14076 7894 14076 7666 14077 7894 14077 7896 14077 7896 14078 7894 14078 7891 14078 7896 14079 7891 14079 7897 14079 7897 14080 7891 14080 7889 14080 7897 14081 7889 14081 7899 14081 7899 14082 7889 14082 7883 14082 7899 14083 7883 14083 7898 14083 7898 14084 7883 14084 7885 14084 7898 14085 7885 14085 7751 14085 7900 14086 7901 14086 7902 14086 7903 10486 7672 10486 7671 10486 7904 10487 7669 10487 7670 10487 7905 14087 7901 14087 7906 14087 7906 14088 7901 14088 7900 14088 7906 10490 7900 10490 7907 10490 7907 14089 7900 14089 7908 14089 7907 14090 7908 14090 7909 14090 7909 14091 7908 14091 7910 14091 7909 10494 7910 10494 7911 10494 7911 10495 7910 10495 7903 10495 7911 10496 7903 10496 7912 10496 7912 14092 7903 14092 7671 14092 7886 14093 7887 14093 7902 14093 7902 14094 7887 14094 7913 14094 7902 14095 7913 14095 7900 14095 7900 14096 7913 14096 7914 14096 7900 14097 7914 14097 7908 14097 7908 10503 7914 10503 7915 10503 7908 10504 7915 10504 7910 10504 7910 10505 7915 10505 7904 10505 7910 10506 7904 10506 7903 10506 7903 10507 7904 10507 7670 10507 7903 10508 7670 10508 7672 10508 7668 14098 7669 14098 7895 14098 7895 14099 7669 14099 7904 14099 7895 14100 7904 14100 7893 14100 7893 14101 7904 14101 7915 14101 7893 14102 7915 14102 7892 14102 7892 10514 7915 10514 7914 10514 7892 14103 7914 14103 7890 14103 7890 14104 7914 14104 7913 14104 7890 14105 7913 14105 7888 14105 7888 10518 7913 10518 7887 10518 7916 10453 7917 10453 7918 10453 7918 14106 7917 14106 7919 14106 7919 14107 7917 14107 7920 14107 7920 14108 7917 14108 7921 14108 7920 14109 7921 14109 7922 14109 7922 14110 7921 14110 7923 14110 7922 14111 7923 14111 7924 14111 7925 14112 7673 14112 7676 14112 7912 14113 7671 14113 7673 14113 7673 14114 7925 14114 7912 14114 7912 14115 7925 14115 7926 14115 7912 10464 7926 10464 7911 10464 7911 10465 7926 10465 7909 10465 7909 14116 7926 14116 7927 14116 7909 14117 7927 14117 7907 14117 7907 14118 7927 14118 7928 14118 7907 14119 7928 14119 7906 14119 7918 14120 7929 14120 7916 14120 7916 14121 7929 14121 7930 14121 7916 14122 7930 14122 7931 14122 7905 14123 7906 14123 7931 14123 7931 10474 7906 10474 7928 10474 7931 14124 7928 14124 7916 14124 7916 14125 7928 14125 7927 14125 7916 14126 7927 14126 7917 14126 7917 14127 7927 14127 7926 14127 7917 14128 7926 14128 7921 14128 7921 14129 7926 14129 7925 14129 7921 14130 7925 14130 7923 14130 7923 14131 7925 14131 7676 14131 7923 14132 7676 14132 7924 14132 7924 14133 7676 14133 7675 14133 7932 14134 7723 14134 7713 14134 7723 14135 7932 14135 7724 14135 7724 14136 7932 14136 7933 14136 7724 10400 7933 10400 7717 10400 7717 14137 7933 14137 7934 14137 7717 14138 7934 14138 7718 14138 7718 14139 7934 14139 7935 14139 7718 14140 7935 14140 7719 14140 7705 14141 7704 14141 7936 14141 7936 14142 7704 14142 7706 14142 7936 10407 7706 10407 7935 10407 7935 14143 7706 14143 7707 14143 7935 10409 7707 10409 7719 10409 7705 14144 7936 14144 7716 14144 7716 14145 7936 14145 7937 14145 7716 14146 7937 14146 7715 14146 7715 14147 7937 14147 7938 14147 7715 14148 7938 14148 7714 14148 7714 14149 7938 14149 7939 14149 7714 14150 7939 14150 7708 14150 7940 14151 7941 14151 7942 14151 7709 10418 7708 10418 7942 10418 7942 14152 7708 14152 7939 14152 7942 14153 7939 14153 7940 14153 7940 14154 7939 14154 7938 14154 7940 14155 7938 14155 7943 14155 7943 14156 7938 14156 7937 14156 7943 14157 7937 14157 7944 14157 7944 14158 7937 14158 7936 14158 7944 14159 7936 14159 7945 14159 7945 10427 7936 10427 7935 10427 7945 14160 7935 14160 7946 14160 7946 14161 7935 14161 7934 14161 7946 14162 7934 14162 7947 14162 7947 14163 7934 14163 7933 14163 7947 10432 7933 10432 7948 10432 7948 14164 7933 14164 7932 14164 7948 14165 7932 14165 7949 14165 7949 14166 7932 14166 7950 14166 7949 14167 7950 14167 7951 14167 7951 14168 7950 14168 7952 14168 7951 14169 7952 14169 7953 14169 7953 14170 7952 14170 7954 14170 7953 14171 7954 14171 7955 14171 7712 14172 7697 14172 7698 14172 7699 14173 7955 14173 7698 14173 7698 14174 7955 14174 7954 14174 7698 14175 7954 14175 7712 14175 7712 10445 7954 10445 7952 10445 7712 14176 7952 14176 7720 14176 7720 14177 7952 14177 7950 14177 7720 14178 7950 14178 7721 14178 7721 14179 7950 14179 7932 14179 7721 14180 7932 14180 7722 14180 7722 14181 7932 14181 7713 14181 7722 14182 7713 14182 7703 14182 7692 14183 7956 14183 7957 14183 7957 14184 7958 14184 7959 14184 7959 14185 7958 14185 7942 14185 7959 14186 7942 14186 7941 14186 7692 14187 7691 14187 7956 14187 7956 14188 7691 14188 7725 14188 7956 14189 7725 14189 7711 14189 7957 14190 7956 14190 7958 14190 7958 14191 7956 14191 7711 14191 7958 14192 7711 14192 7942 14192 7942 14193 7711 14193 7710 14193 7942 14194 7710 14194 7709 14194 7692 14195 7960 14195 7690 14195 7690 14196 7960 14196 7961 14196 7690 14197 7961 14197 7688 14197 7688 14198 7961 14198 7962 14198 7688 14199 7962 14199 7685 14199 7685 10370 7962 10370 7963 10370 7685 10371 7963 10371 7680 10371 7680 14200 7963 14200 7964 14200 7680 14201 7964 14201 7681 14201 7681 14202 7964 14202 7965 14202 7960 14203 6709 14203 7961 14203 7961 14204 6709 14204 6710 14204 7961 14205 6710 14205 7962 14205 7962 14206 6710 14206 6711 14206 7962 14207 6711 14207 7963 14207 7963 14208 6711 14208 6673 14208 7963 14209 6673 14209 7964 14209 7964 14210 6673 14210 6672 14210 7964 14211 6672 14211 7965 14211 7965 14212 6672 14212 6671 14212 7700 14213 7966 14213 7699 14213 7699 14214 7966 14214 7967 14214 7699 14215 7967 14215 7968 14215 7969 14216 7970 14216 7971 14216 7971 14217 7970 14217 7965 14217 7971 14218 7965 14218 6671 14218 7681 14219 7965 14219 7701 14219 7701 14220 7965 14220 7970 14220 7701 14221 7970 14221 7702 14221 7702 14222 7970 14222 7969 14222 7702 14223 7969 14223 7700 14223 7700 14224 7969 14224 7972 14224 7700 10364 7972 10364 7966 10364 7743 14225 7973 14225 7974 14225 7975 14226 7976 14226 7977 14226 7739 14227 7978 14227 7740 14227 7979 14228 7595 14228 7738 14228 7980 14229 7981 14229 7979 14229 7979 14230 7981 14230 7982 14230 7982 14231 7502 14231 7979 14231 7979 14232 7502 14232 7597 14232 7979 14233 7597 14233 7595 14233 7738 14234 7741 14234 7979 14234 7979 14235 7741 14235 7983 14235 7979 14236 7983 14236 7980 14236 7980 14237 7983 14237 7984 14237 7980 14238 7984 14238 7985 14238 7874 14239 7855 14239 7986 14239 7882 14240 7849 14240 7987 14240 7987 14241 7849 14241 7851 14241 7987 14242 7851 14242 7874 14242 7988 14243 7989 14243 7990 14243 7990 14244 7989 14244 7873 14244 7990 14245 7873 14245 7987 14245 7987 14246 7873 14246 7872 14246 7987 14247 7872 14247 7882 14247 7874 14248 7986 14248 7987 14248 7987 14249 7986 14249 7985 14249 7987 14250 7985 14250 7990 14250 7990 14251 7985 14251 7984 14251 7990 14252 7984 14252 7988 14252 7988 14253 7984 14253 7983 14253 7988 14254 7983 14254 7991 14254 7991 14255 7983 14255 7992 14255 7991 14256 7992 14256 7993 14256 7973 10290 7994 10290 7974 10290 7974 10291 7994 10291 7995 10291 7974 14257 7995 14257 7996 14257 7997 14258 7998 14258 7996 14258 7996 14259 7998 14259 7999 14259 7996 14260 7999 14260 7974 14260 7974 10296 7999 10296 8000 10296 7974 10297 8000 10297 8001 10297 8001 10298 8000 10298 8002 10298 8001 14261 8002 14261 8003 14261 7975 14262 7977 14262 8004 14262 8004 14263 7977 14263 8005 14263 8004 14264 8005 14264 8006 14264 7646 14265 7647 14265 8007 14265 8007 14266 7647 14266 8008 14266 8007 14267 8008 14267 8009 14267 8009 14268 8008 14268 8010 14268 7634 14269 7643 14269 8007 14269 8007 14270 7643 14270 7645 14270 8007 14271 7645 14271 7646 14271 8011 14272 7637 14272 7635 14272 8006 14273 8005 14273 8010 14273 8010 14274 8005 14274 8012 14274 8010 14275 8012 14275 8009 14275 8009 14276 8012 14276 8011 14276 8009 14277 8011 14277 8007 14277 8007 14278 8011 14278 7635 14278 8007 14279 7635 14279 7634 14279 7471 14280 8013 14280 8014 14280 8013 14281 8015 14281 8014 14281 8014 14282 8015 14282 8016 14282 8014 14283 8016 14283 8005 14283 8005 14284 8016 14284 8017 14284 8005 14285 8017 14285 8012 14285 8012 14286 8017 14286 8018 14286 8012 14287 8018 14287 8011 14287 8014 14288 7728 14288 7730 14288 7471 14289 8014 14289 7535 14289 7535 14290 8014 14290 7730 14290 7535 14291 7730 14291 7562 14291 7728 10330 8014 10330 7726 10330 7726 14292 8014 14292 8005 14292 7726 14293 8005 14293 7742 14293 7742 14294 8005 14294 7977 14294 7742 14295 7977 14295 7743 14295 7743 14296 7977 14296 7976 14296 7743 14297 7976 14297 7973 14297 7973 14298 7976 14298 8019 14298 7973 14299 8019 14299 7994 14299 7978 14300 7739 14300 8003 14300 8003 14301 7739 14301 7746 14301 8003 14302 7746 14302 8001 14302 8001 14303 7746 14303 7745 14303 8001 14304 7745 14304 7974 14304 7974 14305 7745 14305 7744 14305 7974 14306 7744 14306 7743 14306 8002 14307 7993 14307 8003 14307 8003 14308 7993 14308 7992 14308 8003 14309 7992 14309 7978 14309 7978 14310 7992 14310 7983 14310 7978 14311 7983 14311 7740 14311 7740 14312 7983 14312 7741 14312 8020 14313 7848 14313 7799 14313 8021 14314 7846 14314 7848 14314 8021 14315 8022 14315 7846 14315 7846 14316 8022 14316 8023 14316 7846 14317 8023 14317 7844 14317 7844 14318 8023 14318 8024 14318 8025 14319 8026 14319 7802 14319 7802 14320 7810 14320 8025 14320 8025 14321 7810 14321 7809 14321 8025 14322 7809 14322 8027 14322 8027 14323 7809 14323 7808 14323 8027 14324 7808 14324 7796 14324 8028 14325 8029 14325 7804 14325 7804 14326 8029 14326 7798 14326 8021 14327 8030 14327 8022 14327 8022 14328 8030 14328 8031 14328 8022 14329 8031 14329 8023 14329 8023 14330 8031 14330 8032 14330 8023 14331 8032 14331 8024 14331 8033 14332 8034 14332 8035 14332 7804 14333 7802 14333 8028 14333 8028 14334 7802 14334 8026 14334 8028 14335 8026 14335 8036 14335 8036 14336 8026 14336 8025 14336 8036 14337 8025 14337 8037 14337 8037 14338 8025 14338 8027 14338 8037 14339 8027 14339 8038 14339 8038 14340 8027 14340 8039 14340 8038 14341 8039 14341 282 14341 7796 14342 288 14342 8027 14342 8027 14343 288 14343 287 14343 8027 14344 287 14344 8039 14344 8039 14345 287 14345 286 14345 8039 14346 286 14346 282 14346 7848 14347 8020 14347 8021 14347 8021 14348 8020 14348 8040 14348 8021 14349 8040 14349 8030 14349 8030 14350 8040 14350 8035 14350 8030 14351 8035 14351 8031 14351 8031 14352 8035 14352 8034 14352 8031 14353 8034 14353 8032 14353 282 14354 8041 14354 8038 14354 8038 14355 8041 14355 8042 14355 8038 14356 8042 14356 8037 14356 8037 14357 8042 14357 8033 14357 8037 14358 8033 14358 8036 14358 8036 14359 8033 14359 8035 14359 8036 14360 8035 14360 8028 14360 8028 14361 8035 14361 8040 14361 8028 14362 8040 14362 8029 14362 8029 14363 8040 14363 8020 14363 8029 14364 8020 14364 7798 14364 7798 14365 8020 14365 7799 14365 7773 14366 7792 14366 8043 14366 7748 14367 7751 14367 8044 14367 8043 14368 8045 14368 254 14368 8044 14369 8046 14369 8043 14369 8043 14370 8046 14370 8047 14370 8043 14371 8047 14371 8045 14371 8043 14372 7792 14372 8044 14372 8044 14373 7792 14373 7749 14373 8044 14374 7749 14374 7748 14374 254 14375 257 14375 8043 14375 8043 14376 257 14376 7774 14376 8043 14377 7774 14377 7779 14377 7779 14378 7778 14378 8043 14378 8043 14379 7778 14379 7789 14379 8043 14380 7789 14380 7773 14380 7437 14381 7436 14381 7459 14381 7459 14382 7436 14382 8048 14382 7459 14383 8048 14383 7458 14383 257 14384 256 14384 7775 14384 7775 14385 256 14385 8049 14385 7775 14386 8049 14386 8050 14386 7777 14387 7776 14387 8050 14387 8050 14388 7776 14388 7783 14388 8050 14389 7783 14389 7775 14389 256 14390 7451 14390 8049 14390 8049 14391 7451 14391 7458 14391 8049 14392 7458 14392 8050 14392 8050 14393 7458 14393 8048 14393 8050 14394 8048 14394 7777 14394 7777 14395 8048 14395 7436 14395 7777 14396 7436 14396 7441 14396 8051 14397 266 14397 270 14397 8052 14398 8015 14398 8013 14398 8053 14399 8054 14399 7476 14399 7476 14400 8054 14400 7478 14400 8055 14401 7473 14401 8054 14401 8054 14402 7473 14402 7479 14402 8054 14403 7479 14403 7478 14403 7471 14404 7470 14404 8013 14404 8013 14405 7470 14405 7469 14405 8013 14406 7469 14406 8052 14406 8052 14407 7469 14407 7468 14407 8052 14408 7468 14408 8056 14408 8056 14409 7468 14409 7467 14409 8056 14410 7467 14410 8055 14410 8055 14411 7467 14411 7474 14411 8055 14412 7474 14412 7473 14412 8057 14413 8011 14413 8018 14413 7637 14414 8011 14414 7821 14414 7821 14415 8011 14415 8057 14415 7821 14416 8057 14416 7816 14416 7816 14417 8057 14417 8058 14417 8059 14418 7818 14418 8058 14418 8058 14419 7818 14419 7817 14419 8058 14420 7817 14420 7816 14420 7797 14421 7811 14421 8060 14421 8060 14422 7811 14422 7793 14422 8060 14423 7793 14423 8061 14423 8061 14424 7793 14424 7795 14424 8061 14425 7795 14425 8059 14425 8059 14426 7795 14426 7814 14426 8059 14427 7814 14427 7818 14427 8062 14428 277 14428 276 14428 277 14429 8062 14429 270 14429 7476 14430 285 14430 8053 14430 8053 14431 285 14431 267 14431 8053 14432 267 14432 266 14432 266 14433 8051 14433 8053 14433 8053 14434 8051 14434 8063 14434 8053 14435 8063 14435 8054 14435 8054 14436 8063 14436 8064 14436 8054 14437 8064 14437 8055 14437 8055 14438 8064 14438 8065 14438 8055 14439 8065 14439 8056 14439 8056 14440 8065 14440 8066 14440 8056 14441 8066 14441 8052 14441 8052 14442 8066 14442 8016 14442 8052 14443 8016 14443 8015 14443 270 14444 8062 14444 8051 14444 8051 14445 8062 14445 8067 14445 8051 14446 8067 14446 8063 14446 8063 14447 8067 14447 8068 14447 8063 14448 8068 14448 8064 14448 8064 14449 8068 14449 8069 14449 8064 14450 8069 14450 8065 14450 8065 14451 8069 14451 8070 14451 8065 14452 8070 14452 8066 14452 8066 14453 8070 14453 8017 14453 8066 14454 8017 14454 8016 14454 288 14455 7797 14455 276 14455 276 14456 7797 14456 8060 14456 276 14457 8060 14457 8062 14457 8062 14458 8060 14458 8061 14458 8062 14459 8061 14459 8067 14459 8067 14460 8061 14460 8059 14460 8067 14461 8059 14461 8068 14461 8068 14462 8059 14462 8058 14462 8068 14463 8058 14463 8069 14463 8069 14464 8058 14464 8057 14464 8069 14465 8057 14465 8070 14465 8070 14466 8057 14466 8018 14466 8070 14467 8018 14467 8017 14467 8071 14468 8072 14468 8073 14468 7878 14469 8074 14469 7877 14469 7877 14470 8074 14470 8075 14470 7878 14471 8076 14471 8077 14471 8078 14472 8074 14472 8079 14472 8079 14473 8074 14473 7878 14473 8079 14474 7878 14474 8080 14474 8080 14475 7878 14475 8077 14475 8081 14476 8082 14476 8083 14476 8083 14477 8084 14477 8081 14477 8081 14478 8084 14478 8085 14478 8081 14479 8085 14479 8076 14479 8076 14480 8085 14480 8086 14480 8076 14481 8086 14481 8077 14481 8071 14482 8073 14482 8087 14482 8087 14483 8073 14483 8088 14483 8087 14484 8088 14484 8089 14484 8089 14485 8088 14485 8090 14485 8089 14486 8090 14486 8091 14486 7864 14487 7863 14487 8092 14487 8092 14488 7863 14488 8093 14488 8092 14489 8093 14489 8091 14489 8091 14490 8090 14490 8092 14490 8092 14491 8090 14491 7879 14491 8092 14492 7879 14492 7864 14492 7878 14493 7879 14493 8076 14493 8076 14494 7879 14494 8090 14494 8076 14495 8090 14495 8081 14495 8081 14496 8090 14496 8088 14496 8081 14497 8088 14497 8082 14497 8082 14498 8088 14498 8073 14498 8094 14499 8095 14499 8096 14499 8097 14500 8098 14500 8099 14500 8100 14501 8101 14501 8102 14501 8102 14502 8101 14502 8103 14502 7859 14503 7860 14503 8104 14503 8080 14504 8077 14504 8105 14504 8106 14505 8107 14505 8079 14505 8079 14506 8107 14506 8078 14506 7862 14507 7877 14507 8108 14507 8108 14508 7877 14508 8075 14508 8108 14509 8075 14509 8109 14509 8109 14510 8075 14510 8074 14510 8109 14511 8074 14511 8110 14511 8110 14512 8074 14512 8078 14512 8110 14513 8078 14513 8111 14513 8111 14514 8078 14514 8107 14514 8112 14515 7855 14515 7857 14515 8113 14516 8114 14516 8115 14516 8115 14517 8114 14517 8112 14517 8115 14518 8112 14518 8116 14518 8116 14519 8112 14519 7857 14519 8117 14520 8118 14520 8113 14520 8113 14521 8118 14521 8119 14521 8113 14522 8119 14522 8114 14522 8096 14523 8120 14523 8121 14523 196 14524 8122 14524 8123 14524 8123 14525 8122 14525 8124 14525 8123 14526 8124 14526 8125 14526 8125 14527 8124 14527 8120 14527 8125 14528 8120 14528 8126 14528 8126 14529 8120 14529 8096 14529 8126 14530 8096 14530 8127 14530 8127 14531 8096 14531 8128 14531 8128 14532 8096 14532 8095 14532 8128 14533 8095 14533 8129 14533 8097 14534 8099 14534 8105 14534 8121 14535 8100 14535 8096 14535 8096 14536 8100 14536 8102 14536 8096 14537 8102 14537 8094 14537 8094 14538 8102 14538 8103 14538 8094 14539 8103 14539 8117 14539 8117 14540 8103 14540 8130 14540 8117 14541 8130 14541 8118 14541 7860 14542 7862 14542 8104 14542 8104 14543 7862 14543 8108 14543 8104 14544 8108 14544 8131 14544 8131 14545 8108 14545 8109 14545 8131 14546 8109 14546 8132 14546 8132 14547 8109 14547 8110 14547 8132 14548 8110 14548 8133 14548 8133 14549 8110 14549 8111 14549 8133 14550 8111 14550 8134 14550 8134 14551 8111 14551 8107 14551 8134 14552 8107 14552 8099 14552 8099 14553 8107 14553 8106 14553 8099 14554 8106 14554 8105 14554 8105 14555 8106 14555 8079 14555 8105 14556 8079 14556 8080 14556 8098 14557 8129 14557 8099 14557 8099 14558 8129 14558 8095 14558 8099 14559 8095 14559 8134 14559 8134 14560 8095 14560 8094 14560 8134 14561 8094 14561 8133 14561 8133 14562 8094 14562 8117 14562 8133 14563 8117 14563 8132 14563 8132 14564 8117 14564 8113 14564 8132 10066 8113 10066 8131 10066 8131 14565 8113 14565 8115 14565 8131 14566 8115 14566 8104 14566 8104 14567 8115 14567 8116 14567 8104 14568 8116 14568 7859 14568 7859 14569 8116 14569 7857 14569 8135 14570 8136 14570 7518 14570 8137 14571 8138 14571 8139 14571 7520 14572 7522 14572 8140 14572 8141 14573 8142 14573 8143 14573 8143 14574 8142 14574 8144 14574 8145 14575 8146 14575 8147 14575 8147 14576 8146 14576 8148 14576 8147 14577 8148 14577 8149 14577 8150 14578 8151 14578 8152 14578 8153 14579 206 14579 8154 14579 8151 14580 8150 14580 8154 14580 8154 14581 8150 14581 8155 14581 8154 14582 8155 14582 8153 14582 8153 14583 8155 14583 8139 14583 8153 14584 8139 14584 8156 14584 8156 14585 8139 14585 8138 14585 8156 14586 8138 14586 8157 14586 7527 14587 8157 14587 7528 14587 7528 14588 8157 14588 8138 14588 7528 14589 8138 14589 7529 14589 7529 14590 8138 14590 8137 14590 7529 14591 8137 14591 7523 14591 8146 14592 8143 14592 8148 14592 8148 14593 8143 14593 8144 14593 8148 14594 8144 14594 8149 14594 8149 14595 8144 14595 8158 14595 8149 14596 8158 14596 8159 14596 8159 14597 8158 14597 8160 14597 8160 14598 8158 14598 8161 14598 8160 14599 8161 14599 8135 14599 8135 14600 8161 14600 8162 14600 8135 14601 8162 14601 8136 14601 7518 14602 7520 14602 8135 14602 8135 14603 7520 14603 8140 14603 8135 14604 8140 14604 8160 14604 8160 14605 8140 14605 8163 14605 8160 14606 8163 14606 8159 14606 8159 14607 8163 14607 8164 14607 8159 14608 8164 14608 8149 14608 7522 14609 7523 14609 8140 14609 8140 14610 7523 14610 8137 14610 8140 14611 8137 14611 8163 14611 8163 14612 8137 14612 8139 14612 8163 14613 8139 14613 8164 14613 8164 14614 8139 14614 8155 14614 8164 14615 8155 14615 8149 14615 8149 14616 8155 14616 8150 14616 8149 14617 8150 14617 8147 14617 8147 14618 8150 14618 8152 14618 8147 14619 8152 14619 8145 14619 7940 14620 8165 14620 7941 14620 7968 14621 7955 14621 7699 14621 7885 14622 8166 14622 7751 14622 7929 14623 8167 14623 7930 14623 8168 14624 8169 14624 8170 14624 8168 14625 8170 14625 7929 14625 8165 14626 7940 14626 8171 14626 8170 14627 8171 14627 7929 14627 7929 14628 8171 14628 7940 14628 7929 14629 7940 14629 8167 14629 8167 14630 7940 14630 7943 14630 8167 14631 7943 14631 7930 14631 7930 14632 7943 14632 7944 14632 7930 14633 7944 14633 7931 14633 7931 14634 7944 14634 7945 14634 7931 14635 7945 14635 7905 14635 7905 14636 7945 14636 7946 14636 7905 14637 7946 14637 7901 14637 7901 14638 7946 14638 7947 14638 7901 9936 7947 9936 7902 9936 7902 14639 7947 14639 7948 14639 7902 14640 7948 14640 7886 14640 7886 14641 7948 14641 7949 14641 7886 14642 7949 14642 7884 14642 7884 14643 7949 14643 7951 14643 7884 14644 7951 14644 7885 14644 7885 14645 7951 14645 7953 14645 7885 14646 7953 14646 8166 14646 8166 14647 7953 14647 7955 14647 8166 14648 7955 14648 7751 14648 7751 14649 7955 14649 7968 14649 7751 14650 7968 14650 8044 14650 8044 14651 7968 14651 8046 14651 8142 14652 8141 14652 8172 14652 7929 14653 7918 14653 8173 14653 8173 14654 7918 14654 7919 14654 8173 14655 7919 14655 8174 14655 8174 14656 7919 14656 7920 14656 8174 14657 7920 14657 8175 14657 8175 14658 7920 14658 7922 14658 8175 14659 7922 14659 8176 14659 8176 14660 7922 14660 7924 14660 8176 14661 7924 14661 8177 14661 8136 14662 8162 14662 8177 14662 8177 14663 8162 14663 8161 14663 8177 14664 8161 14664 8176 14664 8176 14665 8161 14665 8158 14665 8176 14666 8158 14666 8175 14666 8175 14667 8158 14667 8144 14667 8175 14668 8144 14668 8174 14668 8174 14669 8144 14669 8142 14669 8174 14670 8142 14670 8173 14670 8173 14671 8142 14671 8172 14671 8173 14672 8172 14672 7929 14672 7518 9914 8136 9914 7674 9914 7674 14673 8136 14673 8177 14673 7674 14674 8177 14674 7675 14674 7675 14675 8177 14675 7924 14675 8178 14676 8179 14676 8180 14676 7959 14677 7941 14677 8178 14677 8178 14678 7941 14678 8165 14678 8178 14679 8165 14679 8171 14679 8178 14680 8180 14680 7959 14680 7959 9884 8180 9884 8181 9884 7959 14681 8181 14681 7957 14681 7957 14682 8181 14682 7960 14682 7957 14683 7960 14683 7692 14683 8179 14684 8182 14684 8180 14684 8180 14685 8182 14685 8183 14685 8180 14686 8183 14686 8181 14686 8181 14687 8183 14687 6709 14687 8181 14688 6709 14688 7960 14688 8019 95 7976 95 7327 95 7327 95 7976 95 7975 95 7327 95 7975 95 8004 95 7326 95 7995 95 7327 95 7327 95 7995 95 7994 95 7327 95 7994 95 8019 95 7971 14689 6671 14689 6666 14689 7971 14690 6666 14690 7969 14690 7969 14691 6666 14691 7972 14691 7972 14692 6666 14692 8184 14692 7972 14693 8184 14693 7966 14693 7966 14694 8184 14694 8185 14694 7966 14695 8185 14695 8186 14695 8046 14696 7968 14696 7967 14696 7967 14697 7966 14697 8046 14697 8046 14698 7966 14698 8186 14698 8046 14699 8186 14699 8047 14699 8047 14700 8186 14700 8045 14700 8186 14701 8187 14701 8045 14701 8045 14702 8187 14702 260 14702 8045 14703 260 14703 254 14703 8188 14704 8189 14704 8190 14704 8097 14705 8191 14705 8192 14705 8191 14706 8086 14706 8085 14706 8191 14707 8097 14707 8086 14707 8086 14708 8097 14708 8105 14708 8086 14709 8105 14709 8077 14709 8193 14710 8129 14710 8192 14710 8192 14711 8129 14711 8098 14711 8192 14712 8098 14712 8097 14712 8125 14713 8126 14713 8194 14713 8194 14714 8126 14714 8127 14714 8194 14715 8127 14715 8193 14715 8193 14716 8127 14716 8128 14716 8193 14717 8128 14717 8129 14717 8083 14718 8189 14718 8084 14718 8084 14719 8189 14719 8188 14719 8084 14720 8188 14720 8085 14720 8195 14721 8196 14721 8197 14721 8197 14722 8196 14722 8198 14722 8197 14723 8198 14723 8199 14723 8199 14724 8198 14724 8200 14724 8199 14725 8200 14725 8201 14725 8201 14726 8200 14726 201 14726 8201 14727 201 14727 197 14727 8199 14728 8202 14728 8197 14728 8197 14729 8202 14729 8203 14729 8197 14730 8203 14730 8195 14730 8195 14731 8203 14731 8204 14731 196 14732 8123 14732 197 14732 197 14733 8123 14733 8205 14733 197 14734 8205 14734 8201 14734 8201 14735 8205 14735 8206 14735 8201 14736 8206 14736 8199 14736 8199 14737 8206 14737 8207 14737 8199 14738 8207 14738 8202 14738 8202 14739 8207 14739 8208 14739 8202 14740 8208 14740 8203 14740 8203 14741 8208 14741 8209 14741 8203 14742 8209 14742 8204 14742 8123 14743 8125 14743 8205 14743 8205 14744 8125 14744 8194 14744 8205 14745 8194 14745 8206 14745 8206 14746 8194 14746 8193 14746 8206 14747 8193 14747 8207 14747 8207 14748 8193 14748 8192 14748 8207 14749 8192 14749 8208 14749 8208 14750 8192 14750 8191 14750 8208 14751 8191 14751 8209 14751 8209 14752 8191 14752 8085 14752 8209 14753 8085 14753 8204 14753 8204 14754 8085 14754 8188 14754 8204 14755 8188 14755 8195 14755 8195 14756 8188 14756 8190 14756 8195 14757 8190 14757 8196 14757 8103 14758 8101 14758 8210 14758 8211 14759 198 14759 211 14759 8212 14760 7496 14760 8213 14760 8213 14761 7496 14761 7498 14761 8213 14762 7498 14762 8214 14762 8214 14763 7498 14763 7499 14763 8214 14764 7499 14764 7501 14764 8215 14765 7493 14765 8212 14765 8212 14766 7493 14766 7494 14766 8212 14767 7494 14767 7496 14767 7486 14768 7487 14768 8216 14768 8216 14769 7487 14769 7490 14769 8216 14770 7490 14770 8215 14770 8215 14771 7490 14771 7492 14771 8215 14772 7492 14772 7493 14772 8217 14773 212 14773 213 14773 212 14774 8217 14774 211 14774 8218 14775 195 14775 198 14775 8121 14776 8120 14776 8218 14776 8218 14777 8120 14777 8124 14777 8218 14778 8124 14778 195 14778 195 14779 8124 14779 8122 14779 195 14780 8122 14780 196 14780 8210 14781 8101 14781 8218 14781 8218 14782 8101 14782 8100 14782 8218 14783 8100 14783 8121 14783 8114 14784 8119 14784 8219 14784 8219 14785 8119 14785 8118 14785 8219 14786 8118 14786 8210 14786 8210 14787 8118 14787 8130 14787 8210 14788 8130 14788 8103 14788 8219 14789 8220 14789 8114 14789 8114 14790 8220 14790 8221 14790 8114 14791 8221 14791 8112 14791 8112 14792 8221 14792 7986 14792 8112 14793 7986 14793 7855 14793 7501 14794 7502 14794 8214 14794 8214 14795 7502 14795 7982 14795 8214 14796 7982 14796 7981 14796 198 14797 8211 14797 8218 14797 8218 14798 8211 14798 8222 14798 8218 14799 8222 14799 8210 14799 8210 14800 8222 14800 8223 14800 8210 14801 8223 14801 8219 14801 8219 14802 8223 14802 8224 14802 8219 14803 8224 14803 8220 14803 8220 14804 8224 14804 8225 14804 8220 14805 8225 14805 8221 14805 8221 14806 8225 14806 7985 14806 8221 14807 7985 14807 7986 14807 211 14808 8217 14808 8211 14808 8211 14809 8217 14809 8226 14809 8211 14810 8226 14810 8222 14810 8222 14811 8226 14811 8227 14811 8222 14812 8227 14812 8223 14812 8223 14813 8227 14813 8228 14813 8223 14814 8228 14814 8224 14814 8224 14815 8228 14815 8229 14815 8224 14816 8229 14816 8225 14816 8225 14817 8229 14817 7980 14817 8225 14818 7980 14818 7985 14818 214 14819 7486 14819 213 14819 213 14820 7486 14820 8216 14820 213 14821 8216 14821 8217 14821 8217 14822 8216 14822 8215 14822 8217 14823 8215 14823 8226 14823 8226 14824 8215 14824 8212 14824 8226 14825 8212 14825 8227 14825 8227 14826 8212 14826 8213 14826 8227 14827 8213 14827 8228 14827 8228 14828 8213 14828 8214 14828 8228 14829 8214 14829 8229 14829 8229 14830 8214 14830 7981 14830 8229 14831 7981 14831 7980 14831 7512 14832 207 14832 8230 14832 8230 14833 207 14833 206 14833 8230 14834 8231 14834 7512 14834 7512 14835 8231 14835 8232 14835 7512 14836 8232 14836 7514 14836 7514 14837 8232 14837 7526 14837 7514 14838 7526 14838 7515 14838 206 14839 8153 14839 8230 14839 8230 14840 8153 14840 8156 14840 8230 14841 8156 14841 8231 14841 8231 14842 8156 14842 8157 14842 8231 14843 8157 14843 8232 14843 8232 14844 8157 14844 7527 14844 8232 14845 7527 14845 7526 14845 8169 9705 8168 9705 8233 9705 8233 14846 8168 14846 8234 14846 8233 14847 8234 14847 8235 14847 8235 14848 8234 14848 8236 14848 8146 14849 8145 14849 8234 14849 8234 14850 8145 14850 8152 14850 8234 14851 8152 14851 8151 14851 208 14852 8236 14852 206 14852 206 14853 8236 14853 8234 14853 206 14854 8234 14854 8154 14854 8154 14855 8234 14855 8151 14855 7929 14856 8172 14856 8168 14856 8168 14857 8172 14857 8141 14857 8168 14858 8141 14858 8234 14858 8234 14859 8141 14859 8143 14859 8234 14860 8143 14860 8146 14860 208 14861 210 14861 8236 14861 8236 14862 210 14862 6443 14862 8236 14863 6443 14863 6445 14863 6445 14864 6447 14864 8236 14864 8236 14865 6447 14865 6489 14865 8236 14866 6489 14866 6488 14866 6488 14867 6486 14867 8236 14867 8236 14868 6486 14868 6485 14868 8236 14869 6485 14869 6483 14869 6483 14870 6481 14870 8236 14870 8236 14871 6481 14871 6479 14871 8236 14872 6479 14872 6477 14872 6477 14873 6431 14873 8236 14873 8236 14874 6431 14874 6430 14874 8236 14875 6430 14875 6494 14875 6494 14876 6496 14876 8236 14876 8236 14877 6496 14877 6498 14877 8236 14878 6498 14878 8235 14878 6498 14879 6433 14879 8235 14879 8235 14880 6433 14880 6435 14880 8235 14881 6435 14881 8233 14881 8233 14882 6435 14882 6437 14882 8233 14883 6437 14883 6424 14883 6424 14884 6423 14884 8233 14884 8233 14885 6423 14885 6429 14885 8233 14886 6429 14886 6469 14886 6469 14887 6468 14887 8233 14887 8233 14888 6468 14888 6466 14888 8233 14889 6466 14889 6465 14889 6465 14890 6441 14890 8233 14890 8233 14891 6441 14891 6427 14891 8233 14892 6427 14892 6426 14892 6451 14893 8170 14893 6426 14893 6426 14894 8170 14894 8169 14894 6426 14895 8169 14895 8233 14895 8178 14896 8171 14896 8170 14896 6451 14897 6453 14897 8170 14897 8170 14898 6453 14898 6455 14898 8170 14899 6455 14899 8178 14899 8178 14900 6455 14900 6456 14900 8178 14901 6456 14901 6458 14901 6458 14902 6460 14902 8178 14902 8178 14903 6460 14903 6462 14903 8178 14904 6462 14904 6464 14904 6464 14905 6474 14905 8178 14905 8178 14906 6474 14906 6475 14906 8178 14907 6475 14907 6524 14907 6524 14908 6522 14908 8178 14908 8178 14909 6522 14909 6520 14909 8178 14910 6520 14910 6518 14910 6518 14911 6516 14911 8178 14911 8178 14912 6516 14912 6515 14912 8178 14913 6515 14913 6513 14913 6513 14914 6512 14914 8178 14914 8178 14915 6512 14915 6510 14915 8178 14916 6510 14916 6508 14916 6508 14917 6506 14917 8178 14917 8178 14918 6506 14918 6504 14918 8178 14919 6504 14919 6502 14919 6422 14920 6709 14920 6491 14920 6491 14921 6709 14921 8183 14921 6491 14922 8183 14922 8182 14922 6502 14923 6493 14923 8178 14923 8178 14924 6493 14924 6491 14924 8178 14925 6491 14925 8179 14925 8179 14926 6491 14926 8182 14926 8237 14927 8238 14927 8239 14927 8240 14928 8241 14928 8242 14928 8239 14929 8243 14929 8244 14929 248 14930 8243 14930 249 14930 249 14931 8243 14931 8239 14931 249 14932 8239 14932 8245 14932 8245 14933 8239 14933 8238 14933 8237 14934 8239 14934 8246 14934 8246 14935 8239 14935 8247 14935 8246 14936 8247 14936 8248 14936 8249 14937 8250 14937 8251 14937 8251 14938 8250 14938 8252 14938 8251 14939 8252 14939 8253 14939 8253 14940 8254 14940 8251 14940 8251 14941 8254 14941 8255 14941 8251 14942 8255 14942 8247 14942 8247 14943 8255 14943 8256 14943 8247 14944 8256 14944 8248 14944 8257 14945 8249 14945 8258 14945 8258 14946 8249 14946 8251 14946 8258 14947 8251 14947 8259 14947 8259 14948 8251 14948 8247 14948 8259 14949 8247 14949 8242 14949 8242 14950 8247 14950 8239 14950 8242 14951 8239 14951 8240 14951 8240 14952 8239 14952 8244 14952 8260 14953 8261 14953 8262 14953 8262 14954 8261 14954 8263 14954 8241 14955 8260 14955 8242 14955 8242 14956 8260 14956 8262 14956 8242 14957 8262 14957 8259 14957 8259 14958 8262 14958 8264 14958 8259 14959 8264 14959 8258 14959 8258 14960 8264 14960 8265 14960 8258 14961 8265 14961 8257 14961 8266 14962 8267 14962 8265 14962 8265 14963 8267 14963 8268 14963 8265 14964 8268 14964 8257 14964 8263 14965 8269 14965 8262 14965 8262 14966 8269 14966 8270 14966 8262 14967 8270 14967 8264 14967 8264 14968 8270 14968 8271 14968 8264 14969 8271 14969 8265 14969 8265 14970 8271 14970 8272 14970 8265 14971 8272 14971 8266 14971 8270 14972 8269 14972 8273 14972 8272 14973 8271 14973 8274 14973 8275 9650 8276 9650 8277 9650 8277 14974 8276 14974 8278 14974 8277 14975 8278 14975 8279 14975 8280 14976 8281 14976 8282 14976 8282 9644 8281 9644 8283 9644 8282 14977 8283 14977 8284 14977 8284 14978 8283 14978 8285 14978 8284 14979 8285 14979 8286 14979 8286 9648 8285 9648 8287 9648 8286 14980 8287 14980 8288 14980 8279 14981 8278 14981 8289 14981 8289 14982 8278 14982 8290 14982 8289 14983 8290 14983 8291 14983 8291 14984 8290 14984 8292 14984 8291 14985 8292 14985 8293 14985 8293 14986 8292 14986 8294 14986 8293 14987 8294 14987 8295 14987 8287 14988 8296 14988 8288 14988 8288 14989 8296 14989 8297 14989 8288 14990 8297 14990 8298 14990 8298 14991 8297 14991 8299 14991 8298 14992 8299 14992 8300 14992 8300 14993 8299 14993 8301 14993 8300 14994 8301 14994 8274 14994 8274 14995 8301 14995 8266 14995 8274 14996 8266 14996 8272 14996 8302 9674 8280 9674 8275 9674 8275 14997 8280 14997 8282 14997 8275 9676 8282 9676 8276 9676 8276 14998 8282 14998 8284 14998 8276 14999 8284 14999 8278 14999 8278 15000 8284 15000 8286 15000 8278 15001 8286 15001 8290 15001 8290 15002 8286 15002 8288 15002 8290 15003 8288 15003 8292 15003 8292 15004 8288 15004 8298 15004 8292 15005 8298 15005 8294 15005 8294 15006 8298 15006 8300 15006 8294 15007 8300 15007 8303 15007 8303 15008 8300 15008 8274 15008 8303 15009 8274 15009 8273 15009 8273 15010 8274 15010 8271 15010 8273 15011 8271 15011 8270 15011 8295 15012 8294 15012 8304 15012 8304 15013 8294 15013 8303 15013 8304 15014 8303 15014 8305 15014 8305 15015 8303 15015 8273 15015 8305 15016 8273 15016 8306 15016 8306 15017 8273 15017 8269 15017 8306 15018 8269 15018 8263 15018 8307 15019 8308 15019 8309 15019 8310 15020 8311 15020 8312 15020 8312 15021 8311 15021 8313 15021 8312 15022 8313 15022 8314 15022 8315 15023 8316 15023 8317 15023 8317 15024 8316 15024 8318 15024 8317 15025 8318 15025 8310 15025 8310 15026 8318 15026 8319 15026 8310 15027 8319 15027 8311 15027 8320 15028 8315 15028 204 15028 204 15029 8315 15029 8317 15029 204 15030 8317 15030 203 15030 203 15031 8317 15031 8321 15031 923 15032 8321 15032 922 15032 922 15033 8321 15033 8317 15033 922 15034 8317 15034 920 15034 920 15035 8317 15035 8310 15035 920 15036 8310 15036 1382 15036 1382 15037 8310 15037 8312 15037 1382 15038 8312 15038 1356 15038 1356 15039 8312 15039 8322 15039 1356 15040 8322 15040 1357 15040 8314 15041 8307 15041 8312 15041 8312 15042 8307 15042 8309 15042 8312 15043 8309 15043 8322 15043 8322 15044 8309 15044 8323 15044 8322 15045 8323 15045 8324 15045 1364 15046 1360 15046 8322 15046 8322 15047 1360 15047 1359 15047 8322 15048 1359 15048 1357 15048 1363 15049 8325 15049 8326 15049 8326 15050 8327 15050 1363 15050 1363 15051 8327 15051 8328 15051 1363 15052 8328 15052 1361 15052 8329 15053 8330 15053 8325 15053 8325 15054 8330 15054 8331 15054 8325 15055 8331 15055 8326 15055 1363 15056 1364 15056 8325 15056 8325 15057 1364 15057 8322 15057 8325 15058 8322 15058 8329 15058 8329 15059 8322 15059 8324 15059 8332 15060 8333 15060 8334 15060 8335 15061 1353 15061 1361 15061 8336 9577 8337 9577 8338 9577 8338 15062 8337 15062 8339 15062 8338 15063 8339 15063 8340 15063 8340 15064 8339 15064 8341 15064 8340 15065 8341 15065 8342 15065 8343 9582 8336 9582 8344 9582 8344 15066 8336 15066 8338 15066 8344 15067 8338 15067 8345 15067 8345 9585 8338 9585 8340 9585 8345 15068 8340 15068 8346 15068 8346 15069 8340 15069 8342 15069 8346 15070 8342 15070 8347 15070 8347 15071 8348 15071 8346 15071 8346 15072 8348 15072 8349 15072 8346 9591 8349 9591 8345 9591 8345 15073 8349 15073 8344 15073 8350 15074 8351 15074 8347 15074 8347 9594 8351 9594 8352 9594 8347 15075 8352 15075 8348 15075 1361 15076 8353 15076 8335 15076 8335 15077 8353 15077 8354 15077 8335 15078 8354 15078 8355 15078 8355 15079 8354 15079 8334 15079 8355 15080 8334 15080 8356 15080 8356 15081 8334 15081 8333 15081 8356 15082 8333 15082 8357 15082 8332 15083 8334 15083 8358 15083 8358 15084 8334 15084 8354 15084 8358 9605 8354 9605 8359 9605 8359 15085 8354 15085 8353 15085 8359 15086 8353 15086 8360 15086 1361 15087 8328 15087 8353 15087 8353 15088 8328 15088 8327 15088 8353 15089 8327 15089 8360 15089 8360 15090 8327 15090 8326 15090 8360 15091 8326 15091 8331 15091 8341 15092 8357 15092 8342 15092 8342 15093 8357 15093 8333 15093 8342 15094 8333 15094 8347 15094 8347 15095 8333 15095 8332 15095 8347 15096 8332 15096 8350 15096 8350 15097 8332 15097 8358 15097 8350 9619 8358 9619 8361 9619 8361 15098 8358 15098 8359 15098 8361 15099 8359 15099 8362 15099 8362 15100 8359 15100 8360 15100 8362 15101 8360 15101 8363 15101 8363 15102 8360 15102 8331 15102 8363 15103 8331 15103 8330 15103 8263 15104 8364 15104 8306 15104 8306 15105 8364 15105 8365 15105 8306 15106 8365 15106 8305 15106 8291 15107 8293 15107 8366 15107 8366 15108 8293 15108 8295 15108 8366 15109 8295 15109 8365 15109 8365 15110 8295 15110 8304 15110 8365 15111 8304 15111 8305 15111 8367 15112 8302 15112 8275 15112 8275 15113 8277 15113 8367 15113 8367 15114 8277 15114 8279 15114 8367 15115 8279 15115 8366 15115 8366 15116 8279 15116 8289 15116 8366 15117 8289 15117 8291 15117 8341 15118 8339 15118 1355 15118 8336 15119 8343 15119 1368 15119 1355 15120 8339 15120 1368 15120 1368 15121 8339 15121 8337 15121 1368 15122 8337 15122 8336 15122 1354 15123 8356 15123 1355 15123 1355 15124 8356 15124 8357 15124 1355 15125 8357 15125 8341 15125 1353 15126 8335 15126 1354 15126 1354 15127 8335 15127 8355 15127 1354 15128 8355 15128 8356 15128 1380 15129 1379 15129 7312 15129 8367 15130 4147 15130 4150 15130 1380 15131 7312 15131 4140 15131 7312 15132 8368 15132 4140 15132 4140 15133 8368 15133 8369 15133 4140 15134 8369 15134 4141 15134 4141 15135 8369 15135 8370 15135 4141 15136 8370 15136 4150 15136 4150 15137 8370 15137 8371 15137 4150 15138 8371 15138 8367 15138 7312 9533 8372 9533 8373 9533 8370 15139 8369 15139 8374 15139 8374 15140 8375 15140 8370 15140 8370 15141 8375 15141 8376 15141 8370 9537 8376 9537 8371 9537 8371 15142 8376 15142 8377 15142 8371 9539 8377 9539 8378 9539 7312 15143 8373 15143 8368 15143 8368 15144 8373 15144 8379 15144 8368 15145 8379 15145 8369 15145 8369 15146 8379 15146 8380 15146 8369 15147 8380 15147 8374 15147 8381 15148 1374 15148 1371 15148 8381 15149 1371 15149 8382 15149 8382 15150 1371 15150 1370 15150 8382 15151 1370 15151 8383 15151 8383 15152 1370 15152 1372 15152 8383 15153 1372 15153 8384 15153 8384 15154 1372 15154 1373 15154 8384 15155 1373 15155 1369 15155 1374 15156 8381 15156 1375 15156 1375 15157 8381 15157 7311 15157 1375 15158 7311 15158 1377 15158 8385 9512 8386 9512 8384 9512 8384 15159 8386 15159 8387 15159 8384 15160 8387 15160 8383 15160 8388 15161 7311 15161 8389 15161 8389 15162 7311 15162 8381 15162 8389 15163 8381 15163 8382 15163 8387 15164 8390 15164 8383 15164 8383 15165 8390 15165 8391 15165 8383 15166 8391 15166 8382 15166 8382 15167 8391 15167 8392 15167 8382 15168 8392 15168 8389 15168 8260 15169 4153 15169 8261 15169 8261 15170 4153 15170 4151 15170 4151 95 4152 95 8261 95 8261 95 4152 95 8364 95 8261 95 8364 95 8263 95 8393 15171 8394 15171 8395 15171 8393 9501 8395 9501 8396 9501 8396 9502 8395 9502 8397 9502 8396 15172 8397 15172 8398 15172 8398 9504 8397 9504 8399 9504 8398 9505 8399 9505 8400 9505 8400 15173 8399 15173 8401 15173 8400 9507 8401 9507 8402 9507 8402 9508 8401 9508 8403 9508 8402 9509 8403 9509 8404 9509 8404 9510 8403 9510 8405 9510 8404 9511 8405 9511 8406 9511 8406 9488 8405 9488 8407 9488 8406 9489 8407 9489 8408 9489 8408 9490 8407 9490 8409 9490 8408 9491 8409 9491 8410 9491 8410 15174 8409 15174 8411 15174 8410 9493 8411 9493 8412 9493 8412 15175 8411 15175 8413 15175 8412 15176 8413 15176 8414 15176 8414 9496 8413 9496 8415 9496 8414 9497 8415 9497 8416 9497 8416 15177 8415 15177 8394 15177 8416 15178 8394 15178 8393 15178 8041 15179 282 15179 281 15179 8417 15180 8418 15180 7844 15180 7844 15181 8024 15181 8417 15181 8417 9479 8024 9479 8032 9479 8417 15182 8032 15182 8419 15182 8032 15183 8034 15183 8419 15183 8419 15184 8034 15184 8033 15184 8419 15185 8033 15185 8420 15185 281 15186 8421 15186 8041 15186 8041 15187 8421 15187 8420 15187 8041 15187 8420 15187 8042 15187 8042 15188 8420 15188 8033 15188 8189 15189 8083 15189 8422 15189 8423 15190 199 15190 201 15190 201 15191 8200 15191 8423 15191 8423 15192 8200 15192 8198 15192 8423 15193 8198 15193 8424 15193 8424 15194 8198 15194 8196 15194 8424 15195 8196 15195 8425 15195 8422 15196 8426 15196 8189 15196 8189 15197 8426 15197 8425 15197 8189 15198 8425 15198 8190 15198 8190 15199 8425 15199 8196 15199 8427 15200 8428 15200 8429 15200 8430 15201 8425 15201 8431 15201 8425 15202 8430 15202 8424 15202 200 15203 8432 15203 205 15203 199 15204 8423 15204 8433 15204 8434 15205 8435 15205 8436 15205 199 15206 8433 15206 200 15206 200 15207 8433 15207 8429 15207 200 15208 8429 15208 8432 15208 8432 15209 8429 15209 8428 15209 8432 15210 8428 15210 205 15210 8426 15211 8422 15211 8437 15211 8437 15212 8422 15212 8438 15212 8437 15213 8438 15213 8439 15213 8439 15214 8438 15214 8440 15214 8439 15215 8440 15215 8441 15215 8425 15216 8426 15216 8431 15216 8431 15217 8426 15217 8437 15217 8431 15218 8437 15218 8442 15218 8442 15219 8437 15219 8439 15219 8442 15220 8439 15220 8443 15220 8443 15221 8439 15221 8441 15221 8443 15222 8441 15222 8444 15222 8423 15223 8436 15223 8433 15223 8433 15224 8436 15224 8435 15224 8433 15225 8435 15225 8429 15225 8429 15226 8435 15226 8445 15226 8429 15227 8445 15227 8427 15227 8446 15228 8447 15228 8448 15228 8448 15229 8447 15229 8449 15229 8448 15230 8449 15230 8450 15230 8450 15231 8449 15231 8451 15231 8450 15232 8451 15232 8434 15232 8434 15233 8451 15233 8452 15233 8434 15234 8452 15234 8435 15234 8435 15235 8452 15235 8453 15235 8435 15236 8453 15236 8445 15236 8454 15237 8446 15237 8455 15237 8455 15238 8446 15238 8448 15238 8455 15239 8448 15239 8456 15239 8456 15240 8448 15240 8450 15240 8456 15241 8450 15241 8457 15241 8457 15242 8450 15242 8434 15242 8423 15243 8424 15243 8436 15243 8436 15244 8424 15244 8430 15244 8436 15245 8430 15245 8434 15245 8434 15246 8430 15246 8431 15246 8434 15247 8431 15247 8457 15247 8457 15248 8431 15248 8442 15248 8457 15249 8442 15249 8456 15249 8456 15250 8442 15250 8443 15250 8456 15251 8443 15251 8455 15251 8455 15252 8443 15252 8444 15252 8455 15253 8444 15253 8454 15253 8458 15254 8459 15254 8308 15254 8458 15255 8308 15255 8460 15255 8461 15256 8462 15256 8314 15256 8308 15257 8307 15257 8460 15257 8460 15258 8307 15258 8314 15258 8460 15259 8314 15259 8463 15259 8463 15260 8314 15260 8462 15260 8319 15261 8464 15261 8465 15261 8314 15262 8313 15262 8461 15262 8461 15263 8313 15263 8311 15263 8461 15264 8311 15264 8466 15264 8466 15265 8311 15265 8319 15265 8466 15266 8319 15266 8467 15266 8467 15267 8319 15267 8465 15267 8468 15268 8469 15268 8316 15268 8316 15269 8469 15269 8470 15269 8316 15270 8470 15270 8471 15270 8464 15271 8319 15271 8471 15271 8471 15272 8319 15272 8318 15272 8471 15273 8318 15273 8316 15273 8320 15274 8472 15274 8473 15274 8320 15275 8473 15275 8315 15275 8315 15276 8473 15276 8474 15276 8315 15277 8474 15277 8316 15277 8316 15278 8474 15278 8475 15278 8316 15279 8475 15279 8468 15279 8472 15280 8320 15280 8476 15280 8476 15281 8320 15281 204 15281 8476 15282 204 15282 205 15282 8477 15283 8478 15283 8237 15283 8237 15284 8478 15284 8238 15284 8238 15285 8478 15285 8479 15285 8238 15286 8479 15286 8245 15286 8245 15287 8479 15287 8480 15287 8245 15288 8480 15288 249 15288 249 15289 8480 15289 8481 15289 249 15290 8481 15290 250 15290 8482 15291 8483 15291 8248 15291 8483 15292 8484 15292 8248 15292 8248 15293 8484 15293 8485 15293 8248 15294 8485 15294 8246 15294 8246 15295 8485 15295 8486 15295 8246 15296 8486 15296 8237 15296 8237 15297 8486 15297 8487 15297 8237 15298 8487 15298 8477 15298 8248 15299 8256 15299 8482 15299 8482 15300 8256 15300 8255 15300 8482 15301 8255 15301 8488 15301 8252 15302 8489 15302 8253 15302 8253 15303 8489 15303 8488 15303 8253 15304 8488 15304 8254 15304 8254 15305 8488 15305 8255 15305 8490 15306 8491 15306 8417 15306 8492 15307 8493 15307 8494 15307 8494 15308 8493 15308 8495 15308 8494 15309 8495 15309 8496 15309 8494 15310 8497 15310 8492 15310 8492 15311 8497 15311 8498 15311 8492 15312 8498 15312 8499 15312 8499 15313 8498 15313 8500 15313 8421 15314 281 15314 280 15314 8501 15315 8502 15315 8490 15315 8501 15316 8503 15316 8504 15316 8502 15317 8501 15317 8505 15317 8505 15318 8501 15318 8504 15318 8505 15319 8504 15319 8506 15319 268 15320 8507 15320 280 15320 280 15321 8507 15321 8508 15321 280 15322 8508 15322 8421 15322 8421 15323 8508 15323 8509 15323 8421 15324 8509 15324 8420 15324 8420 15325 8509 15325 8510 15325 8420 15326 8510 15326 8419 15326 8496 15327 8511 15327 8494 15327 8494 15328 8511 15328 8512 15328 8494 15329 8512 15329 8497 15329 8497 15330 8512 15330 8513 15330 8497 15331 8513 15331 8498 15331 8498 15332 8513 15332 8514 15332 8498 15333 8514 15333 8500 15333 8418 15334 8417 15334 8496 15334 8496 15335 8417 15335 8491 15335 8496 15336 8491 15336 8511 15336 8511 15337 8491 15337 8490 15337 8511 15338 8490 15338 8512 15338 8512 15339 8490 15339 8502 15339 8512 15340 8502 15340 8513 15340 8513 15341 8502 15341 8505 15341 8513 15342 8505 15342 8514 15342 8514 15343 8505 15343 8506 15343 8503 15344 8501 15344 8515 15344 8515 15345 8501 15345 8516 15345 8515 15346 8516 15346 8517 15346 8517 15347 8516 15347 8518 15347 8517 15348 8518 15348 250 15348 268 15349 250 15349 8507 15349 8507 15350 250 15350 8518 15350 8507 15351 8518 15351 8508 15351 8508 15352 8518 15352 8516 15352 8508 15353 8516 15353 8509 15353 8509 15354 8516 15354 8501 15354 8509 15355 8501 15355 8510 15355 8510 15356 8501 15356 8490 15356 8510 15357 8490 15357 8419 15357 8419 15358 8490 15358 8417 15358 8519 15359 8520 15359 8521 15359 8446 15360 8454 15360 8522 15360 8449 15361 8447 15361 8523 15361 8524 15362 8451 15362 8525 15362 8445 15363 8453 15363 8526 15363 8451 15364 8524 15364 8452 15364 8471 15365 8465 15365 8464 15365 8469 15366 8468 15366 8527 15366 8474 15367 8473 15367 8528 15367 8528 15368 8529 15368 8474 15368 8474 15369 8529 15369 8527 15369 8474 15370 8527 15370 8475 15370 8475 15371 8527 15371 8468 15371 8462 15372 8530 15372 8463 15372 8463 15373 8530 15373 8521 15373 8463 15374 8521 15374 8460 15374 8460 15375 8521 15375 8520 15375 8460 15376 8520 15376 8458 15376 8458 15377 8520 15377 8519 15377 8458 15378 8519 15378 8459 15378 8470 15379 8531 15379 8471 15379 8471 15380 8531 15380 8532 15380 8471 15381 8532 15381 8465 15381 8465 15382 8532 15382 8533 15382 8465 15383 8533 15383 8467 15383 8467 15384 8533 15384 8534 15384 8467 15385 8534 15385 8466 15385 8466 15386 8534 15386 8461 15386 8476 15387 205 15387 8535 15387 8535 15388 205 15388 8428 15388 8535 15389 8428 15389 8427 15389 8427 15390 8445 15390 8535 15390 8535 15391 8445 15391 8526 15391 8535 15392 8526 15392 8536 15392 8536 15393 8526 15393 8537 15393 8453 15394 8452 15394 8526 15394 8526 15395 8452 15395 8524 15395 8526 15396 8524 15396 8537 15396 8537 15397 8524 15397 8525 15397 8537 15398 8525 15398 8538 15398 8538 15399 8539 15399 8540 15399 8476 15400 8535 15400 8472 15400 8472 15401 8535 15401 8536 15401 8472 15402 8536 15402 8473 15402 8473 15403 8536 15403 8537 15403 8473 15404 8537 15404 8528 15404 8528 15405 8537 15405 8538 15405 8528 15406 8538 15406 8529 15406 8529 15407 8538 15407 8540 15407 8529 15408 8540 15408 8527 15408 8541 15409 8542 15409 8543 15409 8462 15410 8461 15410 8543 15410 8543 15411 8461 15411 8534 15411 8543 15412 8534 15412 8541 15412 8541 15413 8534 15413 8533 15413 8541 15414 8533 15414 8539 15414 8539 15415 8533 15415 8532 15415 8539 15416 8532 15416 8540 15416 8540 15417 8532 15417 8531 15417 8540 15418 8531 15418 8527 15418 8527 15419 8531 15419 8470 15419 8527 15420 8470 15420 8469 15420 8447 15421 8446 15421 8523 15421 8523 15422 8446 15422 8522 15422 8523 15423 8522 15423 8544 15423 8544 15424 8522 15424 8545 15424 8544 15425 8545 15425 8546 15425 8546 15426 8545 15426 8547 15426 8546 15427 8547 15427 8548 15427 8548 15428 8547 15428 8549 15428 8548 15429 8549 15429 8550 15429 8550 15430 8549 15430 8551 15430 8550 15431 8551 15431 8552 15431 8552 15432 8551 15432 8553 15432 8462 15433 8543 15433 8530 15433 8530 15434 8543 15434 8542 15434 8530 15435 8542 15435 8521 15435 8521 15436 8542 15436 8554 15436 8521 15437 8554 15437 8519 15437 8451 15438 8449 15438 8525 15438 8525 15439 8449 15439 8523 15439 8525 15440 8523 15440 8538 15440 8538 15441 8523 15441 8544 15441 8538 15442 8544 15442 8539 15442 8539 15443 8544 15443 8546 15443 8539 15444 8546 15444 8541 15444 8541 15445 8546 15445 8548 15445 8541 15446 8548 15446 8542 15446 8542 15447 8548 15447 8550 15447 8542 15448 8550 15448 8554 15448 8554 15449 8550 15449 8552 15449 8554 15450 8552 15450 8519 15450 8519 15451 8552 15451 8555 15451 8553 15452 8556 15452 8552 15452 8552 15453 8556 15453 8557 15453 8552 15454 8557 15454 8555 15454 8558 15455 8559 15455 8560 15455 8506 15456 8504 15456 8561 15456 8480 15457 8479 15457 8562 15457 8477 15458 8487 15458 8563 15458 8500 15459 8564 15459 8499 15459 8499 15460 8564 15460 8565 15460 8566 15461 8567 15461 8568 15461 8568 15462 8567 15462 8569 15462 8568 15463 8569 15463 8570 15463 8570 15464 8569 15464 8571 15464 8570 15465 8571 15465 8572 15465 8572 15466 8571 15466 8565 15466 8572 15467 8565 15467 8573 15467 8573 15468 8565 15468 8564 15468 8574 15469 8567 15469 8575 15469 8575 15470 8567 15470 8566 15470 8575 15471 8566 15471 8576 15471 8488 15472 8489 15472 8577 15472 8577 15473 8578 15473 8488 15473 8488 15474 8578 15474 8579 15474 8488 15475 8579 15475 8482 15475 8482 15476 8579 15476 8483 15476 8483 15477 8579 15477 8580 15477 8483 15478 8580 15478 8484 15478 8484 15479 8580 15479 8485 15479 8485 15480 8580 15480 8581 15480 8485 15481 8581 15481 8486 15481 8477 15482 8563 15482 8478 15482 8478 15483 8563 15483 8582 15483 8478 15484 8582 15484 8479 15484 8479 15485 8582 15485 8583 15485 8479 15486 8583 15486 8562 15486 8517 15487 250 15487 8481 15487 8503 15488 8515 15488 8583 15488 8583 15489 8515 15489 8517 15489 8583 15490 8517 15490 8562 15490 8562 15491 8517 15491 8481 15491 8562 15492 8481 15492 8480 15492 8504 15493 8503 15493 8561 15493 8561 15494 8503 15494 8583 15494 8561 15495 8583 15495 8584 15495 8584 15496 8583 15496 8582 15496 8584 15497 8582 15497 8581 15497 8581 15498 8582 15498 8563 15498 8581 15499 8563 15499 8486 15499 8486 15500 8563 15500 8487 15500 8559 15501 8576 15501 8560 15501 8560 15502 8576 15502 8566 15502 8560 15503 8566 15503 8585 15503 8585 15504 8566 15504 8568 15504 8585 15505 8568 15505 8586 15505 8586 15506 8568 15506 8570 15506 8586 15507 8570 15507 8587 15507 8587 15508 8570 15508 8572 15508 8587 15509 8572 15509 8588 15509 8588 15510 8572 15510 8573 15510 8588 15511 8573 15511 8589 15511 8589 15512 8573 15512 8564 15512 8589 15513 8564 15513 8514 15513 8514 15514 8564 15514 8500 15514 8577 15515 8558 15515 8578 15515 8578 15516 8558 15516 8560 15516 8578 15517 8560 15517 8579 15517 8579 15518 8560 15518 8585 15518 8579 15519 8585 15519 8580 15519 8580 15520 8585 15520 8586 15520 8580 15521 8586 15521 8581 15521 8581 15522 8586 15522 8587 15522 8581 15523 8587 15523 8584 15523 8584 15524 8587 15524 8588 15524 8584 15525 8588 15525 8561 15525 8561 15526 8588 15526 8589 15526 8561 15527 8589 15527 8506 15527 8506 15528 8589 15528 8514 15528 8590 15529 8591 15529 8592 15529 8559 15530 8558 15530 8593 15530 8575 15531 8576 15531 8594 15531 8595 15532 8596 15532 8597 15532 8596 15533 8595 15533 8598 15533 8599 15534 8600 15534 8601 15534 8600 15535 8599 15535 8602 15535 8603 15536 8604 15536 8605 15536 8603 15537 8606 15537 8489 15537 8489 15538 8606 15538 8593 15538 8489 15539 8593 15539 8577 15539 8577 15540 8593 15540 8558 15540 8607 15541 8608 15541 8609 15541 8609 15542 8608 15542 8610 15542 8609 15543 8610 15543 8611 15543 8611 15544 8610 15544 8612 15544 8611 15545 8612 15545 8613 15545 8613 15546 8612 15546 8614 15546 8613 15547 8614 15547 8615 15547 8615 15548 8614 15548 8616 15548 8615 15549 8616 15549 8617 15549 8617 15550 8616 15550 8597 15550 8617 15551 8597 15551 8601 15551 8601 15552 8597 15552 8596 15552 8601 15553 8596 15553 8599 15553 8599 15554 8596 15554 8598 15554 8576 15555 8559 15555 8594 15555 8594 15556 8559 15556 8593 15556 8594 15557 8593 15557 8618 15557 8618 15558 8593 15558 8606 15558 8619 15559 8590 15559 8618 15559 8618 15560 8590 15560 8592 15560 8618 15561 8592 15561 8594 15561 8594 15562 8592 15562 8620 15562 8594 15563 8620 15563 8575 15563 8575 15564 8620 15564 8574 15564 8603 15565 8605 15565 8606 15565 8606 15566 8605 15566 8621 15566 8606 15567 8621 15567 8618 15567 8618 15568 8621 15568 8622 15568 8618 15569 8622 15569 8619 15569 8608 15570 8591 15570 8610 15570 8610 15571 8591 15571 8590 15571 8610 15572 8590 15572 8612 15572 8612 15573 8590 15573 8619 15573 8612 15574 8619 15574 8614 15574 8614 15575 8619 15575 8622 15575 8614 15576 8622 15576 8616 15576 8616 15577 8622 15577 8621 15577 8616 15578 8621 15578 8597 15578 8597 15579 8621 15579 8605 15579 8597 15580 8605 15580 8595 15580 8595 15581 8605 15581 8604 15581 8623 15582 8624 15582 8625 15582 8626 15583 8627 15583 8628 15583 8459 15584 8519 15584 8629 15584 8629 15585 8519 15585 8630 15585 8629 15586 8630 15586 8631 15586 8632 15587 8633 15587 8634 15587 8635 15588 8636 15588 8637 15588 8637 15589 8636 15589 8638 15589 8637 15590 8638 15590 8639 15590 8627 15591 8626 15591 8640 15591 8640 15592 8626 15592 8633 15592 8640 15593 8633 15593 8641 15593 8641 15594 8633 15594 8632 15594 8641 15595 8632 15595 8642 15595 8638 15596 8623 15596 8639 15596 8639 15597 8623 15597 8625 15597 8639 15598 8625 15598 8643 15598 8643 15599 8625 15599 8642 15599 8643 15600 8642 15600 8644 15600 8644 15601 8642 15601 8632 15601 8557 15602 8645 15602 8555 15602 8555 15603 8645 15603 8646 15603 8555 15604 8646 15604 8519 15604 8519 15605 8646 15605 8647 15605 8519 15606 8647 15606 8630 15606 8557 15607 8556 15607 8645 15607 8645 15608 8556 15608 8648 15608 8645 15609 8648 15609 8649 15609 8634 15610 8631 15610 8632 15610 8632 15611 8631 15611 8630 15611 8632 15612 8630 15612 8644 15612 8644 15613 8630 15613 8647 15613 8644 15614 8647 15614 8643 15614 8643 15615 8647 15615 8646 15615 8643 15616 8646 15616 8639 15616 8639 15617 8646 15617 8645 15617 8639 15618 8645 15618 8637 15618 8637 15619 8645 15619 8649 15619 8637 15620 8649 15620 8635 15620 8635 15621 8649 15621 8648 15621 8650 15622 8651 15622 8628 15622 8652 15623 8653 15623 8654 15623 8628 15624 8627 15624 8650 15624 8650 15625 8627 15625 8640 15625 8650 15626 8640 15626 8655 15626 8655 15627 8640 15627 8641 15627 8655 15628 8641 15628 8654 15628 8654 15629 8641 15629 8642 15629 8654 15630 8642 15630 8652 15630 8652 15631 8642 15631 8625 15631 8652 15632 8625 15632 8624 15632 8656 15633 8657 15633 8658 15633 8659 15634 8660 15634 8661 15634 8661 15635 8660 15635 8651 15635 8661 15636 8651 15636 8650 15636 8661 15637 8662 15637 8659 15637 8659 15638 8662 15638 8663 15638 8659 15639 8663 15639 8664 15639 8664 15640 8663 15640 8665 15640 8664 15641 8665 15641 8666 15641 8666 15642 8665 15642 8667 15642 8666 15643 8667 15643 8668 15643 8658 15644 8657 15644 8669 15644 8669 15645 8657 15645 8670 15645 8669 15646 8670 15646 8671 15646 8672 15647 8673 15647 8674 15647 8674 15648 8673 15648 8654 15648 8674 15649 8654 15649 8653 15649 8675 15650 8676 15650 8677 15650 8677 15651 8676 15651 8678 15651 8677 15652 8678 15652 8679 15652 8679 15653 8678 15653 8680 15653 8679 15654 8680 15654 8681 15654 8650 15655 8655 15655 8661 15655 8661 15656 8655 15656 8675 15656 8661 15657 8675 15657 8662 15657 8662 15658 8675 15658 8677 15658 8662 15659 8677 15659 8663 15659 8663 15660 8677 15660 8679 15660 8663 15661 8679 15661 8665 15661 8665 15662 8679 15662 8681 15662 8665 15663 8681 15663 8667 15663 8655 15664 8654 15664 8675 15664 8675 15665 8654 15665 8673 15665 8675 15666 8673 15666 8676 15666 8676 15667 8673 15667 8672 15667 8676 15668 8672 15668 8678 15668 8678 15669 8672 15669 8656 15669 8678 15670 8656 15670 8680 15670 8680 15671 8656 15671 8658 15671 8680 15672 8658 15672 8681 15672 8681 15673 8658 15673 8669 15673 8681 15674 8669 15674 8667 15674 8682 15675 8683 15675 8668 15675 8669 15676 8671 15676 8684 15676 8684 15677 8685 15677 8669 15677 8669 15678 8685 15678 8682 15678 8669 15678 8682 15678 8667 15678 8667 15679 8682 15679 8668 15679 8686 15680 8607 15680 8609 15680 8686 15681 8609 15681 8687 15681 8609 15682 8611 15682 8687 15682 8687 15683 8611 15683 8613 15683 8687 15684 8613 15684 8688 15684 8613 15685 8615 15685 8688 15685 8688 15686 8615 15686 8617 15686 8688 15687 8617 15687 8689 15687 8689 15688 8617 15688 8690 15688 8602 15689 8691 15689 8600 15689 8600 15690 8691 15690 8690 15690 8600 15691 8690 15691 8601 15691 8601 15692 8690 15692 8617 15692 8692 15693 8693 15693 8694 15693 8695 15694 8696 15694 8697 15694 8698 8973 8699 8973 8700 8973 8700 8974 8699 8974 8701 8974 8697 15695 8696 15695 8702 15695 8696 15696 8703 15696 8702 15696 8702 8977 8703 8977 8704 8977 8702 15697 8704 15697 8699 15697 8699 15698 8704 15698 8705 15698 8699 8980 8705 8980 8701 8980 8706 15699 8707 15699 8695 15699 8708 15700 8707 15700 8709 15700 8709 15701 8707 15701 8706 15701 8709 15702 8706 15702 8710 15702 8695 15703 8697 15703 8706 15703 8706 15704 8697 15704 8711 15704 8706 15705 8711 15705 8710 15705 8692 15706 8694 15706 8712 15706 8712 15707 8694 15707 8713 15707 8712 15708 8713 15708 8714 15708 8714 15709 8713 15709 8715 15709 8714 8992 8715 8992 8716 8992 8698 15710 8715 15710 8699 15710 8699 15711 8715 15711 8713 15711 8699 8995 8713 8995 8702 8995 8702 8996 8713 8996 8694 8996 8702 15712 8694 15712 8697 15712 8697 15713 8694 15713 8693 15713 8697 15714 8693 15714 8711 15714 8711 15715 8693 15715 8692 15715 8711 15716 8692 15716 8717 15716 8718 632 8719 632 8720 632 8721 632 8722 632 8723 632 8716 632 8724 632 8725 632 8717 632 8692 632 8726 632 8726 632 8692 632 8712 632 8726 632 8712 632 8720 632 8725 632 8727 632 8716 632 8716 632 8727 632 8720 632 8716 8968 8720 8968 8714 8968 8714 632 8720 632 8712 632 8721 8967 8723 8967 8727 8967 8727 15717 8723 15717 8728 15717 8727 8970 8728 8970 8720 8970 8720 632 8728 632 8729 632 8720 632 8729 632 8718 632 8730 15718 8731 15718 8732 15718 8733 15719 8734 15719 8732 15719 8732 15720 8734 15720 8735 15720 8732 15721 8735 15721 8730 15721 8736 8939 8737 8939 8738 8939 8736 15722 8738 15722 8739 15722 8737 15723 8736 15723 8740 15723 8740 15724 8736 15724 8741 15724 8740 15725 8741 15725 8742 15725 8742 8944 8741 8944 8743 8944 8742 8945 8743 8945 8744 8945 8728 8946 8723 8946 8745 8946 8746 15726 8747 15726 8748 15726 8745 15727 8749 15727 8728 15727 8728 8949 8749 8949 8750 8949 8728 15728 8750 15728 8729 15728 8729 15729 8750 15729 8746 15729 8729 15730 8746 15730 8718 15730 8718 15731 8746 15731 8748 15731 8718 15732 8748 15732 8719 15732 8731 15733 8751 15733 8732 15733 8732 8956 8751 8956 8739 8956 8732 15734 8739 15734 8733 15734 8733 15735 8739 15735 8738 15735 8751 15736 8747 15736 8739 15736 8739 15737 8747 15737 8746 15737 8739 15738 8746 15738 8736 15738 8736 15739 8746 15739 8750 15739 8736 8963 8750 8963 8741 8963 8741 8964 8750 8964 8749 8964 8741 8965 8749 8965 8743 8965 8743 15740 8749 15740 8745 15740 8351 15741 8350 15741 8740 15741 8740 15742 8350 15742 8361 15742 8740 15743 8361 15743 8737 15743 8737 15744 8361 15744 8362 15744 8737 15745 8362 15745 8738 15745 8738 15746 8362 15746 8363 15746 8738 15747 8363 15747 8733 15747 8733 15748 8363 15748 8330 15748 8733 15749 8330 15749 8734 15749 8734 15750 8330 15750 8329 15750 8734 8925 8329 8925 8735 8925 8735 15751 8329 15751 8324 15751 8735 15752 8324 15752 8730 15752 8744 15753 8343 15753 8344 15753 8344 15754 8349 15754 8744 15754 8744 15755 8349 15755 8348 15755 8744 15756 8348 15756 8352 15756 8351 15757 8740 15757 8352 15757 8352 15758 8740 15758 8742 15758 8352 15759 8742 15759 8744 15759 8752 8914 8700 8914 8753 8914 8753 106 8700 106 8302 106 8753 106 8302 106 8754 106 8755 15760 8722 15760 8756 15760 8757 15761 8744 15761 8743 15761 8758 15762 8759 15762 8757 15762 8757 15763 8743 15763 8758 15763 8758 15764 8743 15764 8745 15764 8758 15765 8745 15765 8760 15765 8755 15766 8761 15766 8722 15766 8722 15767 8761 15767 8760 15767 8722 8912 8760 8912 8723 8912 8723 15768 8760 15768 8745 15768 8725 15769 8724 15769 8762 15769 8762 8896 8763 8896 8725 8896 8725 8897 8763 8897 8764 8897 8725 8898 8764 8898 8727 8898 8727 8899 8764 8899 8765 8899 8727 8900 8765 8900 8721 8900 8721 15770 8765 15770 8756 15770 8721 15771 8756 15771 8722 15771 8752 15772 8766 15772 8767 15772 8724 15773 8716 15773 8715 15773 8768 15774 8769 15774 8724 15774 8724 15775 8769 15775 8770 15775 8724 15776 8770 15776 8762 15776 8724 15777 8715 15777 8768 15777 8768 15778 8715 15778 8698 15778 8768 15779 8698 15779 8767 15779 8767 15780 8698 15780 8700 15780 8767 15781 8700 15781 8752 15781 8753 15782 8771 15782 8772 15782 8772 15783 8773 15783 8753 15783 8753 15784 8773 15784 8766 15784 8753 8884 8766 8884 8752 8884 8774 15785 8775 15785 8776 15785 8776 15786 8775 15786 8754 15786 8754 15787 8775 15787 8777 15787 8754 15788 8777 15788 8778 15788 8778 15789 8779 15789 8754 15789 8754 15790 8779 15790 8780 15790 8780 15791 8781 15791 8754 15791 8754 15792 8781 15792 8782 15792 8754 15793 8782 15793 8753 15793 8783 15794 8784 15794 8776 15794 8776 15795 8784 15795 8785 15795 8776 15796 8785 15796 8774 15796 8786 8858 8787 8858 8788 8858 8788 8859 8787 8859 8789 8859 8754 15797 8302 15797 8790 15797 8790 15798 8302 15798 8791 15798 8790 15799 8791 15799 8792 15799 8792 15800 8791 15800 8793 15800 8792 8864 8793 8864 8794 8864 8794 15801 8793 15801 8795 15801 8794 15802 8795 15802 8789 15802 8789 8867 8795 8867 8796 8867 8789 8868 8796 8868 8788 8868 8797 15803 8798 15803 8759 15803 8759 15804 8798 15804 8799 15804 8759 15805 8799 15805 8757 15805 8800 15806 8801 15806 8759 15806 8761 15807 8802 15807 8760 15807 8760 15808 8802 15808 8803 15808 8760 15809 8803 15809 8758 15809 8800 15810 8759 15810 8804 15810 8804 15811 8759 15811 8758 15811 8804 15812 8758 15812 8805 15812 8805 15813 8758 15813 8803 15813 8805 15814 8803 15814 8806 15814 8806 15815 8803 15815 8802 15815 8806 15816 8802 15816 8807 15816 8807 15817 8802 15817 8761 15817 8807 15818 8761 15818 8808 15818 8756 15819 8809 15819 8755 15819 8755 15820 8809 15820 8810 15820 8755 15821 8810 15821 8761 15821 8763 15822 8811 15822 8812 15822 8809 15823 8813 15823 8810 15823 8810 15824 8813 15824 8814 15824 8810 15825 8814 15825 8815 15825 8763 8831 8762 8831 8811 8831 8811 15826 8762 15826 8816 15826 8811 632 8816 632 8817 632 8817 15827 8816 15827 8818 15827 8817 15828 8818 15828 8819 15828 8809 15829 8756 15829 8813 15829 8813 15830 8756 15830 8765 15830 8813 15831 8765 15831 8812 15831 8812 15832 8765 15832 8764 15832 8812 15833 8764 15833 8763 15833 8762 8823 8770 8823 8816 8823 8816 15834 8770 15834 8818 15834 8770 15835 8820 15835 8821 15835 8766 15836 8822 15836 8823 15836 8767 15837 8824 15837 8768 15837 8768 15838 8824 15838 8820 15838 8768 15839 8820 15839 8769 15839 8769 15840 8820 15840 8770 15840 8766 15841 8823 15841 8767 15841 8767 15842 8823 15842 8825 15842 8767 15843 8825 15843 8824 15843 8824 15844 8825 15844 8826 15844 8824 15845 8826 15845 8820 15845 8820 15846 8826 15846 8827 15846 8820 15847 8827 15847 8821 15847 8828 8801 8829 8801 8343 8801 8343 8802 8829 8802 8830 8802 8829 8803 8831 8803 8830 8803 8830 15848 8831 15848 8832 15848 8830 15849 8832 15849 8833 15849 8833 8806 8832 8806 8834 8806 8833 15850 8834 15850 8835 15850 8835 8808 8834 8808 8836 8808 8835 8809 8836 8809 8837 8809 8838 15851 8839 15851 8840 15851 8840 15852 8839 15852 8841 15852 8840 15853 8841 15853 8842 15853 8843 15854 8844 15854 8828 15854 8828 15855 8844 15855 8845 15855 8845 15856 8846 15856 8828 15856 8828 15857 8846 15857 8847 15857 8828 15858 8847 15858 8841 15858 8841 15859 8847 15859 8848 15859 8841 15860 8848 15860 8842 15860 8849 15861 8850 15861 8851 15861 8847 8772 8846 8772 8852 8772 8852 15862 8846 15862 8845 15862 8799 15863 8798 15863 8853 15863 8854 15864 8844 15864 8843 15864 8844 15865 8854 15865 8845 15865 8845 15866 8854 15866 8851 15866 8845 15867 8851 15867 8852 15867 8848 15868 8847 15868 8855 15868 8855 15869 8847 15869 8852 15869 8855 15870 8852 15870 8856 15870 8856 15871 8852 15871 8851 15871 8856 15872 8851 15872 8857 15872 8857 15873 8851 15873 8850 15873 8857 15874 8850 15874 8858 15874 8843 15875 8799 15875 8854 15875 8854 15876 8799 15876 8853 15876 8854 15877 8853 15877 8851 15877 8851 15878 8853 15878 8859 15878 8851 15879 8859 15879 8849 15879 8860 15880 8861 15880 8862 15880 8863 8736 8864 8736 8865 8736 8863 8737 8865 8737 8866 8737 8866 15881 8865 15881 8867 15881 8866 15882 8867 15882 8868 15882 8868 8740 8867 8740 8869 8740 8868 8741 8869 8741 8870 8741 8870 8742 8869 8742 8871 8742 8870 8743 8871 8743 8872 8743 8860 15883 8862 15883 8873 15883 8873 15884 8862 15884 8874 15884 8873 15885 8874 15885 8875 15885 8875 15886 8874 15886 8876 15886 8875 15887 8876 15887 8877 15887 8877 8749 8876 8749 8878 8749 8878 15888 8876 15888 8879 15888 8878 15889 8879 15889 8880 15889 8880 15890 8879 15890 8881 15890 8881 8753 8879 8753 8882 8753 8881 15891 8882 15891 8883 15891 8864 15892 8884 15892 8865 15892 8865 15893 8884 15893 8885 15893 8865 15894 8885 15894 8867 15894 8867 15895 8885 15895 8886 15895 8867 15896 8886 15896 8869 15896 8869 8760 8886 8760 8887 8760 8869 15897 8887 15897 8871 15897 8871 15898 8887 15898 8888 15898 8884 15899 8882 15899 8885 15899 8885 8764 8882 8764 8879 8764 8885 15900 8879 15900 8886 15900 8886 15901 8879 15901 8876 15901 8886 8767 8876 8767 8887 8767 8887 8768 8876 8768 8874 8768 8887 15902 8874 15902 8888 15902 8888 15903 8874 15903 8862 15903 8780 15904 8779 15904 8889 15904 8779 15905 8778 15905 8889 15905 8889 15906 8778 15906 8777 15906 8889 15907 8777 15907 8890 15907 8890 15908 8777 15908 8775 15908 8753 8719 8782 8719 8891 8719 8891 15909 8782 15909 8781 15909 8891 8721 8781 8721 8892 8721 8892 15910 8781 15910 8780 15910 8892 15911 8780 15911 8893 15911 8780 15912 8889 15912 8893 15912 8893 15913 8889 15913 8894 15913 8893 15914 8894 15914 8895 15914 8771 15915 8753 15915 8896 15915 8896 15916 8753 15916 8891 15916 8896 15917 8891 15917 8897 15917 8897 15918 8891 15918 8892 15918 8897 15919 8892 15919 8898 15919 8898 15920 8892 15920 8893 15920 8898 15921 8893 15921 8899 15921 8899 15922 8893 15922 8895 15922 8772 632 8822 632 8773 632 8773 632 8822 632 8766 632 8900 8696 8784 8696 8783 8696 8783 15923 8901 15923 8900 15923 8900 15924 8901 15924 8902 15924 8900 15925 8902 15925 8903 15925 8903 15926 8902 15926 8904 15926 8905 15927 8906 15927 8907 15927 8907 15928 8906 15928 8904 15928 8907 8703 8904 8703 8908 8703 8908 8704 8904 8704 8902 8704 8909 8705 8910 8705 8911 8705 8910 15929 8912 15929 8911 15929 8911 15930 8912 15930 8913 15930 8911 15931 8913 15931 8907 15931 8907 15932 8913 15932 8914 15932 8907 15933 8914 15933 8905 15933 8911 15934 8915 15934 8909 15934 8909 15935 8915 15935 8916 15935 8909 15936 8916 15936 8917 15936 8918 8671 8919 8671 8920 8671 8918 15937 8920 15937 8921 15937 8922 15938 8923 15938 8924 15938 8924 15939 8923 15939 8925 15939 8924 15940 8925 15940 8926 15940 8926 15941 8927 15941 8924 15941 8924 15942 8927 15942 8928 15942 8924 15943 8928 15943 8929 15943 8789 8679 8787 8679 8872 8679 8872 15944 8930 15944 8789 15944 8789 8681 8930 8681 8931 8681 8789 15945 8931 15945 8932 15945 8754 15946 8790 15946 8776 15946 8776 15947 8790 15947 8920 15947 8776 15948 8920 15948 8783 15948 8783 8686 8920 8686 8919 8686 8790 15949 8792 15949 8920 15949 8920 15950 8792 15950 8929 15950 8920 15951 8929 15951 8921 15951 8921 15952 8929 15952 8928 15952 8792 15953 8794 15953 8929 15953 8929 8692 8794 8692 8789 8692 8929 15954 8789 15954 8924 15954 8924 15955 8789 15955 8932 15955 8924 15956 8932 15956 8922 15956 8933 15957 8894 15957 8934 15957 8934 15958 8894 15958 8889 15958 8934 15959 8889 15959 8935 15959 8889 15960 8890 15960 8935 15960 8935 15961 8890 15961 8775 15961 8935 15962 8775 15962 8774 15962 8935 15963 8774 15963 8785 15963 8934 15964 8935 15964 8936 15964 8936 15965 8935 15965 8785 15965 8936 15966 8785 15966 8937 15966 8937 15967 8785 15967 8784 15967 8933 15968 8934 15968 8938 15968 8938 15969 8934 15969 8936 15969 8938 8662 8936 8662 8939 8662 8939 15970 8936 15970 8937 15970 8939 8664 8937 8664 8940 8664 8759 632 8801 632 8797 632 8810 15971 8815 15971 8941 15971 8808 8651 8761 8651 8942 8651 8942 15972 8761 15972 8810 15972 8942 8653 8810 8653 8943 8653 8943 15973 8810 15973 8941 15973 8818 15974 8770 15974 8821 15974 8944 8646 8819 8646 8945 8646 8945 15975 8819 15975 8818 15975 8945 15976 8818 15976 8946 15976 8946 15977 8818 15977 8821 15977 8829 15978 8947 15978 8831 15978 8831 15979 8947 15979 8948 15979 8831 15980 8948 15980 8832 15980 8948 8628 8949 8628 8832 8628 8832 8629 8949 8629 8950 8629 8832 15981 8950 15981 8834 15981 8834 15982 8950 15982 8951 15982 8863 15983 8836 15983 8952 15983 8952 8633 8836 8633 8834 8633 8952 15984 8834 15984 8953 15984 8953 15985 8834 15985 8951 15985 8954 15986 8955 15986 8947 15986 8947 15987 8955 15987 8956 15987 8947 15988 8956 15988 8948 15988 8948 8639 8956 8639 8957 8639 8948 15989 8957 15989 8949 15989 8829 15990 8828 15990 8947 15990 8947 15991 8828 15991 8841 15991 8947 15992 8841 15992 8954 15992 8954 15993 8841 15993 8839 15993 8958 15994 8959 15994 8960 15994 8960 15995 8959 15995 8961 15995 8960 15996 8961 15996 8962 15996 8962 15997 8961 15997 8963 15997 8963 15998 8961 15998 8964 15998 8963 15999 8964 15999 8965 15999 8965 16000 8964 16000 8966 16000 8966 8612 8964 8612 8967 8612 8966 16001 8967 16001 8968 16001 8969 8614 8970 8614 8967 8614 8967 8615 8970 8615 8971 8615 8967 8616 8971 8616 8968 8616 8972 16002 8973 16002 8974 16002 8974 16003 8973 16003 8975 16003 8974 16004 8975 16004 8969 16004 8969 16005 8975 16005 8976 16005 8969 16006 8976 16006 8970 16006 8972 16007 8974 16007 8977 16007 8977 16008 8974 16008 8839 16008 8977 16009 8839 16009 8838 16009 8978 16010 8840 16010 8979 16010 8979 16011 8840 16011 8842 16011 8980 8595 8981 8595 8982 8595 8983 16012 8981 16012 8979 16012 8979 16013 8981 16013 8980 16013 8979 16014 8980 16014 8978 16014 8838 16015 8840 16015 8984 16015 8984 16016 8840 16016 8978 16016 8984 16017 8978 16017 8985 16017 8985 16018 8978 16018 8980 16018 8985 16019 8980 16019 8986 16019 8986 16020 8980 16020 8982 16020 8858 16021 8983 16021 8857 16021 8857 16022 8983 16022 8979 16022 8857 16023 8979 16023 8856 16023 8842 16024 8848 16024 8979 16024 8979 16025 8848 16025 8855 16025 8979 16026 8855 16026 8856 16026 8987 8555 8988 8555 8989 8555 8990 16027 8991 16027 8992 16027 8993 16028 8994 16028 8992 16028 8992 8558 8994 8558 8995 8558 8992 16029 8995 16029 8990 16029 8875 16030 8996 16030 8873 16030 8873 16031 8996 16031 8997 16031 8873 8562 8997 8562 8860 8562 8860 16032 8997 16032 8998 16032 8860 16033 8998 16033 8861 16033 8861 8565 8998 8565 8999 8565 8861 16034 8999 16034 8991 16034 8991 16035 8999 16035 9000 16035 8991 16036 9000 16036 8992 16036 8881 16037 9001 16037 9002 16037 8881 8570 9002 8570 8880 8570 8880 8571 9002 8571 9003 8571 8880 16038 9003 16038 8878 16038 8878 16039 9003 16039 9004 16039 8878 16040 9004 16040 8877 16040 8877 16041 9004 16041 9005 16041 8877 16042 9005 16042 8875 16042 8875 16043 9005 16043 9006 16043 8875 16044 9006 16044 8996 16044 8881 16045 8883 16045 9001 16045 9001 16046 8883 16046 9007 16046 9001 16047 9007 16047 9008 16047 9008 8582 9007 8582 9009 8582 9008 16048 9009 16048 9010 16048 9010 16049 9009 16049 8989 16049 8989 16050 9009 16050 9011 16050 8989 8586 9011 8586 8987 8586 9007 16051 8883 16051 8882 16051 8953 16052 8951 16052 9012 16052 8949 16053 8957 16053 9013 16053 9013 16054 8957 16054 8956 16054 9013 16055 8956 16055 9014 16055 9014 16056 8956 16056 8955 16056 9007 8508 9015 8508 9009 8508 9009 8509 9015 8509 9016 8509 9009 8510 9016 8510 9011 8510 9017 8511 9018 8511 9019 8511 9019 16057 9018 16057 9020 16057 9019 16058 9020 16058 9015 16058 9015 16059 9020 16059 9021 16059 9015 8515 9021 8515 9016 8515 8955 8516 9022 8516 9014 8516 9014 16060 9022 16060 9023 16060 9014 16061 9023 16061 9013 16061 9013 16062 9023 16062 9024 16062 9013 16063 9024 16063 9025 16063 9025 16064 9024 16064 9026 16064 9025 16065 9026 16065 9027 16065 9027 16066 9026 16066 9028 16066 9027 16067 9028 16067 9029 16067 8949 16068 9013 16068 9030 16068 9030 16069 9013 16069 9025 16069 9030 16070 9025 16070 9031 16070 9031 16071 9025 16071 9027 16071 9031 16072 9027 16072 9032 16072 9032 16073 9027 16073 9029 16073 9032 8531 9029 8531 9017 8531 9017 16074 9029 16074 9033 16074 9017 8533 9033 8533 9018 8533 9007 8534 9034 8534 9015 8534 9015 8535 9034 8535 9035 8535 9015 8536 9035 8536 9019 8536 9019 8537 9035 8537 9036 8537 9019 8538 9036 8538 9017 8538 9017 16075 9036 16075 9012 16075 9017 16076 9012 16076 9032 16076 9032 16077 9012 16077 8951 16077 9032 16078 8951 16078 9031 16078 9031 16079 8951 16079 8950 16079 9031 16080 8950 16080 9030 16080 9030 8545 8950 8545 8949 8545 9007 8546 8882 8546 9034 8546 9034 16081 8882 16081 8884 16081 9034 16082 8884 16082 9035 16082 9035 16083 8884 16083 8864 16083 9035 16084 8864 16084 9036 16084 9036 16085 8864 16085 8863 16085 9036 16086 8863 16086 9012 16086 9012 16087 8863 16087 8952 16087 9012 16088 8952 16088 8953 16088 9037 16089 9038 16089 9039 16089 8990 16090 8995 16090 9040 16090 8931 16091 9041 16091 8932 16091 8932 16092 9041 16092 9042 16092 8932 8442 9042 8442 8922 8442 9038 16093 8925 16093 8923 16093 8925 16094 9038 16094 8926 16094 8926 16095 9038 16095 9037 16095 8926 16096 9037 16096 9043 16096 8921 16097 8928 16097 9043 16097 9043 16098 8928 16098 8927 16098 9043 16099 8927 16099 8926 16099 9044 16100 9045 16100 9039 16100 9046 8451 9047 8451 9048 8451 9049 16101 9050 16101 9051 16101 9051 16102 9050 16102 9052 16102 9051 16103 9052 16103 9053 16103 9053 16104 9052 16104 9054 16104 9053 16105 9054 16105 9055 16105 9055 16106 9054 16106 9041 16106 9055 16107 9041 16107 9056 16107 9056 16108 9041 16108 8931 16108 9056 16109 8931 16109 8930 16109 8930 8461 8872 8461 9056 8461 9056 16110 8872 16110 9057 16110 9056 16111 9057 16111 9055 16111 9055 8464 9057 8464 9058 8464 9055 16112 9058 16112 9053 16112 9053 16113 9058 16113 9046 16113 9053 16114 9046 16114 9051 16114 9051 16115 9046 16115 9048 16115 9051 16116 9048 16116 9049 16116 8918 8470 8921 8470 9059 8470 9059 16117 8921 16117 9043 16117 9059 16118 9043 16118 9060 16118 9060 16119 9043 16119 9037 16119 9060 16120 9037 16120 9061 16120 9061 16121 9037 16121 9039 16121 9061 16122 9039 16122 9062 16122 9062 16123 9039 16123 9045 16123 9050 16124 9063 16124 9052 16124 9052 8479 9063 8479 9044 8479 9052 16125 9044 16125 9054 16125 9054 16126 9044 16126 9039 16126 9054 16127 9039 16127 9041 16127 9041 16128 9039 16128 9038 16128 9041 16129 9038 16129 9042 16129 9042 16130 9038 16130 8923 16130 9042 16131 8923 16131 8922 16131 8872 8487 8871 8487 9057 8487 9057 16132 8871 16132 8888 16132 9057 16133 8888 16133 9058 16133 9058 16134 8888 16134 8862 16134 9058 16135 8862 16135 9046 16135 9046 16136 8862 16136 8861 16136 9046 8493 8861 8493 9047 8493 9047 8494 8861 8494 8991 8494 9047 8495 8991 8495 9048 8495 9048 16137 8991 16137 8990 16137 9048 16138 8990 16138 9049 16138 9049 16139 8990 16139 9040 16139 9049 8499 9040 8499 9050 8499 9050 16140 9040 16140 9064 16140 9050 16141 9064 16141 9063 16141 8917 98 8916 98 9065 98 9065 16142 8916 16142 9066 16142 9065 16143 9066 16143 8994 16143 8994 98 9066 98 9067 98 8994 98 9067 98 8995 98 9063 16144 9068 16144 9069 16144 9070 16145 8919 16145 8918 16145 8901 16146 8783 16146 8919 16146 8918 8393 9059 8393 9071 8393 9071 8394 9059 8394 9060 8394 9071 8395 9060 8395 9072 8395 9072 16147 9060 16147 9061 16147 9072 8397 9061 8397 9073 8397 9061 8398 9062 8398 9073 8398 9073 16148 9062 16148 9045 16148 9073 16149 9045 16149 9069 16149 9069 16150 9045 16150 9044 16150 9069 16151 9044 16151 9063 16151 8918 16152 9071 16152 9070 16152 9070 8404 9071 8404 9072 8404 9070 16153 9072 16153 9074 16153 9074 16154 9072 16154 9073 16154 9074 16155 9073 16155 9075 16155 9075 16156 9073 16156 9069 16156 9075 8409 9069 8409 9076 8409 9076 16157 9069 16157 9068 16157 9076 16158 9068 16158 9077 16158 8919 16159 9070 16159 8901 16159 8901 16160 9070 16160 9074 16160 8901 16161 9074 16161 8902 16161 8902 16162 9074 16162 9075 16162 8902 8416 9075 8416 8908 8416 8908 8417 9075 8417 9076 8417 8908 8418 9076 8418 8907 8418 8907 16163 9076 16163 9077 16163 8907 16164 9077 16164 8911 16164 9064 16165 9040 16165 9078 16165 9078 16166 9040 16166 9079 16166 9078 16167 9079 16167 9080 16167 9080 16168 9079 16168 9081 16168 9066 8425 9081 8425 9067 8425 9067 8426 9081 8426 9079 8426 9067 16169 9079 16169 8995 16169 8995 16170 9079 16170 9040 16170 9063 16171 9064 16171 9068 16171 9068 16172 9064 16172 9078 16172 9068 16173 9078 16173 9077 16173 9077 16174 9078 16174 9080 16174 9077 16175 9080 16175 8911 16175 8911 16176 9080 16176 9081 16176 8911 16177 9081 16177 8915 16177 8915 16178 9081 16178 9066 16178 8915 16179 9066 16179 8916 16179 9021 16180 9020 16180 9082 16180 9083 8342 9084 8342 9085 8342 9022 8343 9083 8343 9086 8343 9087 16181 9024 16181 9086 16181 9086 16182 9024 16182 9023 16182 9086 8346 9023 8346 9022 8346 9083 8347 9085 8347 9086 8347 9086 16183 9085 16183 9088 16183 9086 16184 9088 16184 9087 16184 9087 16185 9088 16185 9089 16185 9087 16186 9089 16186 9090 16186 9033 8352 9029 8352 9090 8352 9090 8353 9029 8353 9028 8353 9090 16187 9028 16187 9087 16187 9087 16188 9028 16188 9026 16188 9087 16189 9026 16189 9024 16189 9018 16190 9033 16190 9091 16190 9091 16191 9033 16191 9090 16191 9091 16192 9090 16192 9092 16192 9092 16193 9090 16193 9089 16193 9020 16194 9018 16194 9082 16194 9082 16195 9018 16195 9091 16195 9082 16196 9091 16196 9093 16196 9093 16197 9091 16197 9092 16197 9093 16198 9092 16198 8964 16198 8964 16199 9092 16199 9089 16199 8964 16200 9089 16200 8967 16200 8967 16201 9089 16201 9088 16201 8967 16202 9088 16202 8969 16202 8969 16203 9088 16203 9085 16203 8969 16204 9085 16204 8974 16204 8974 8372 9085 8372 9084 8372 8974 16205 9084 16205 8839 16205 8839 8374 9084 8374 9083 8374 8839 16206 9083 16206 8954 16206 8954 16207 9083 16207 9022 16207 8954 8377 9022 8377 8955 8377 9016 16208 9021 16208 9094 16208 9094 16209 9021 16209 9082 16209 9094 16210 9082 16210 9095 16210 9095 16211 9082 16211 9093 16211 9095 16212 9093 16212 8961 16212 8961 8383 9093 8383 8964 8383 9011 8384 9016 8384 9096 8384 9096 8385 9016 8385 9094 8385 9096 16213 9094 16213 9097 16213 9097 16214 9094 16214 9095 16214 9097 16215 9095 16215 8959 16215 8959 16216 9095 16216 8961 16216 8959 106 8958 106 9098 106 9097 106 8959 106 9096 106 9096 16217 8959 16217 9098 16217 9096 16218 9098 16218 9011 16218 9011 16219 9098 16219 8987 16219 9099 7585 9100 7585 9101 7585 9102 16220 9103 16220 9104 16220 9104 7585 9103 7585 9105 7585 9104 16221 9106 16221 9102 16221 9102 7585 9106 7585 9107 7585 9102 16222 9107 16222 9108 16222 9108 8334 9107 8334 9109 8334 9108 7585 9109 7585 9110 7585 9110 8335 9109 8335 9111 8335 9110 7585 9111 7585 9112 7585 9112 7585 9111 7585 9113 7585 9112 8336 9113 8336 9114 8336 9114 7585 9113 7585 9101 7585 9101 7585 9113 7585 9115 7585 9101 7585 9115 7585 9099 7585 9116 7585 9117 7585 9118 7585 9118 7585 9117 7585 9105 7585 9118 16223 9105 16223 9119 16223 9119 7585 9105 7585 9103 7585 8994 16224 8993 16224 9116 16224 8994 16225 9116 16225 9065 16225 9065 8312 9116 8312 9118 8312 9065 8313 9118 8313 9120 8313 8988 16226 8987 16226 9100 16226 9100 16227 8987 16227 9098 16227 9100 16228 9098 16228 9101 16228 9101 16229 9098 16229 9121 16229 9101 8318 9121 8318 9114 8318 9114 8319 9121 8319 9112 8319 9112 16230 9121 16230 9122 16230 9112 8321 9122 8321 9110 8321 9118 16231 9119 16231 9120 16231 9120 16232 9119 16232 9103 16232 9120 16233 9103 16233 9123 16233 9123 16234 9103 16234 9102 16234 9123 8326 9102 8326 9124 8326 9124 8327 9102 8327 9108 8327 9124 8328 9108 8328 9125 8328 9125 8329 9108 8329 9110 8329 9125 8330 9110 8330 9126 8330 9126 8331 9110 8331 9122 8331 9121 16235 9098 16235 8958 16235 8958 16236 9127 16236 9121 16236 9121 16237 9127 16237 9128 16237 9121 8305 9128 8305 9122 8305 9122 8306 9128 8306 9129 8306 9122 8307 9129 8307 9126 8307 9126 8308 9129 8308 9130 8308 9126 8309 9130 8309 9125 8309 8917 16238 9065 16238 9120 16238 9125 8294 9130 8294 9131 8294 9125 8295 9131 8295 9124 8295 9124 8296 9131 8296 9132 8296 9124 8297 9132 8297 9123 8297 9123 8298 9132 8298 9133 8298 9123 16239 9133 16239 9120 16239 9120 16240 9133 16240 9134 16240 9120 16241 9134 16241 8917 16241 8977 16242 8838 16242 9135 16242 9135 16243 8838 16243 8984 16243 9135 16244 8984 16244 8985 16244 8977 16245 9135 16245 8972 16245 8972 16246 9135 16246 9136 16246 8972 16247 9136 16247 8973 16247 8973 8214 9136 8214 9137 8214 8973 16248 9137 16248 8975 16248 8975 8216 9137 8216 9138 8216 8975 16249 9138 16249 8976 16249 8976 16250 9138 16250 9139 16250 8976 16251 9139 16251 8970 16251 8970 16252 9139 16252 8971 16252 8971 16253 9139 16253 9140 16253 8971 16254 9140 16254 8968 16254 8968 16255 9140 16255 9141 16255 8968 16256 9141 16256 8966 16256 8966 16257 9141 16257 9142 16257 8966 16258 9142 16258 8965 16258 8965 16259 9142 16259 9143 16259 8965 16260 9143 16260 8963 16260 8963 8229 9143 8229 9144 8229 8963 16261 9144 16261 8962 16261 8962 8231 9144 8231 9145 8231 8962 8232 9145 8232 8960 8232 8960 8233 9145 8233 9127 8233 8960 16262 9127 16262 8958 16262 9146 8235 9129 8235 9128 8235 9129 8236 9146 8236 9130 8236 9130 8237 9146 8237 9147 8237 9130 8238 9147 8238 9148 8238 9148 8239 9147 8239 9149 8239 9148 8240 9149 8240 9150 8240 9151 16263 9152 16263 9153 16263 9153 16264 9152 16264 9154 16264 9153 8243 9154 8243 9155 8243 9155 8244 9154 8244 9150 8244 9155 16265 9150 16265 9156 16265 9156 16266 9150 16266 9149 16266 9128 8247 9157 8247 9146 8247 9146 16267 9157 16267 9158 16267 9146 16268 9158 16268 9147 16268 9147 16269 9158 16269 9159 16269 9147 8251 9159 8251 9149 8251 9149 16270 9159 16270 9160 16270 9149 16271 9160 16271 9156 16271 9156 16272 9160 16272 9161 16272 9156 16273 9161 16273 9155 16273 9155 16274 9161 16274 9162 16274 9155 16275 9162 16275 9153 16275 9153 16276 9162 16276 9163 16276 9153 16277 9163 16277 9151 16277 9151 16278 9163 16278 9164 16278 9151 16279 9164 16279 9165 16279 9165 16280 9164 16280 9166 16280 9165 16281 9166 16281 9167 16281 9167 16282 9166 16282 9168 16282 9167 16283 9168 16283 9169 16283 9169 16284 9168 16284 9170 16284 9169 16285 9170 16285 8982 16285 8982 16286 9170 16286 8986 16286 9128 16287 9127 16287 9157 16287 9157 8270 9127 8270 9145 8270 9157 16288 9145 16288 9158 16288 9158 8272 9145 8272 9144 8272 9158 16289 9144 16289 9159 16289 9159 8274 9144 8274 9143 8274 9159 16290 9143 16290 9160 16290 9160 8276 9143 8276 9142 8276 9160 16291 9142 16291 9161 16291 9161 16292 9142 16292 9141 16292 9161 16293 9141 16293 9162 16293 9162 16294 9141 16294 9140 16294 9162 16295 9140 16295 9163 16295 9163 16296 9140 16296 9139 16296 9163 16297 9139 16297 9164 16297 9164 16298 9139 16298 9138 16298 9164 8285 9138 8285 9166 8285 9166 16299 9138 16299 9137 16299 9166 8287 9137 8287 9168 8287 9168 8288 9137 8288 9136 8288 9168 16300 9136 16300 9170 16300 9170 16301 9136 16301 9135 16301 9170 8291 9135 8291 8986 8291 8986 16302 9135 16302 8985 16302 9171 16303 9172 16303 9173 16303 9174 8116 9175 8116 9176 8116 9177 16304 9178 16304 9179 16304 9180 8118 9181 8118 9182 8118 9182 8119 9181 8119 9131 8119 9182 8120 9131 8120 9130 8120 9183 16305 8910 16305 9184 16305 9184 8122 8910 8122 8909 8122 9184 8123 8909 8123 9185 8123 9185 16306 8909 16306 8917 16306 9185 16307 8917 16307 9134 16307 8914 16308 8913 16308 9183 16308 9183 16309 8913 16309 8912 16309 9183 16310 8912 16310 8910 16310 8904 16311 8906 16311 9186 16311 9186 16312 8906 16312 8905 16312 9186 16313 8905 16313 9187 16313 9187 16314 8905 16314 8914 16314 9187 16315 8914 16315 9188 16315 9188 16316 8914 16316 9183 16316 8904 8135 9186 8135 8903 8135 8903 16317 9186 16317 9189 16317 8903 8137 9189 8137 8900 8137 8900 16318 9189 16318 9190 16318 8900 16319 9190 16319 9191 16319 9176 8140 9175 8140 9192 8140 9175 8141 9193 8141 9192 8141 9192 8142 9193 8142 9194 8142 9192 16320 9194 16320 9180 16320 9180 16321 9194 16321 9195 16321 9180 16322 9195 16322 9181 16322 8937 16323 9173 16323 8940 16323 8940 16324 9173 16324 9172 16324 8940 16325 9172 16325 9196 16325 9196 16326 9172 16326 9171 16326 9196 16327 9171 16327 9197 16327 9177 16328 9197 16328 9178 16328 9178 16329 9197 16329 9171 16329 9178 16330 9171 16330 9198 16330 9198 16331 9171 16331 9173 16331 9198 16332 9173 16332 9199 16332 9199 16333 9173 16333 8937 16333 9199 16334 8937 16334 8784 16334 9132 8158 9131 8158 9200 8158 9200 8159 9131 8159 9181 8159 9200 16335 9181 16335 9201 16335 9201 16336 9181 16336 9195 16336 9201 16337 9195 16337 9202 16337 9202 16338 9195 16338 9194 16338 9202 16339 9194 16339 9203 16339 9203 8165 9194 8165 9193 8165 9203 16340 9193 16340 9204 16340 9204 16341 9193 16341 9175 16341 9204 16342 9175 16342 9179 16342 9179 16343 9175 16343 9174 16343 9179 16344 9174 16344 9177 16344 9134 16345 9133 16345 9185 16345 9185 16346 9133 16346 9205 16346 9185 16347 9205 16347 9184 16347 9184 16348 9205 16348 9206 16348 9184 16349 9206 16349 9183 16349 9183 16350 9206 16350 9207 16350 9183 16351 9207 16351 9188 16351 9188 16352 9207 16352 9208 16352 9188 16353 9208 16353 9187 16353 9187 16354 9208 16354 9209 16354 9187 16355 9209 16355 9186 16355 9186 8182 9209 8182 9210 8182 9186 16356 9210 16356 9189 16356 9189 16357 9210 16357 9211 16357 9189 16358 9211 16358 9190 16358 9190 16359 9211 16359 9212 16359 9190 16360 9212 16360 9191 16360 8784 16361 8900 16361 9199 16361 9199 16362 8900 16362 9191 16362 9199 16363 9191 16363 9198 16363 9198 16364 9191 16364 9212 16364 9198 16365 9212 16365 9178 16365 9178 16366 9212 16366 9211 16366 9178 16367 9211 16367 9179 16367 9179 16368 9211 16368 9210 16368 9179 16369 9210 16369 9204 16369 9204 16370 9210 16370 9209 16370 9204 16371 9209 16371 9203 16371 9203 16372 9209 16372 9208 16372 9203 16373 9208 16373 9202 16373 9202 16374 9208 16374 9207 16374 9202 16375 9207 16375 9201 16375 9201 16376 9207 16376 9206 16376 9201 16377 9206 16377 9200 16377 9200 16378 9206 16378 9205 16378 9200 16379 9205 16379 9132 16379 9132 16380 9205 16380 9133 16380 9150 16381 9154 16381 9213 16381 9152 16382 9151 16382 9214 16382 9151 16383 9165 16383 9214 16383 9214 16384 9165 16384 9167 16384 9214 16385 9167 16385 9215 16385 9215 16386 9167 16386 9169 16386 9215 16387 9169 16387 9216 16387 9216 16388 9169 16388 8982 16388 9216 8086 8982 8086 9217 8086 9217 8087 8982 8087 8981 8087 9217 16389 8981 16389 8983 16389 9176 8089 9192 8089 9218 8089 9218 8090 9192 8090 9180 8090 9218 8091 9180 8091 9148 8091 9148 16390 9180 16390 9182 16390 9148 8093 9182 8093 9130 8093 9177 16391 9219 16391 9197 16391 9197 16392 9219 16392 9220 16392 9197 16393 9220 16393 9196 16393 9196 16394 9220 16394 9221 16394 9196 16395 9221 16395 8940 16395 9177 16396 9174 16396 9219 16396 9219 16397 9174 16397 9176 16397 9219 8101 9176 8101 9222 8101 9222 8102 9176 8102 9218 8102 9222 16398 9218 16398 9213 16398 9213 16399 9218 16399 9148 16399 9213 16400 9148 16400 9150 16400 9223 8106 8933 8106 8938 8106 9223 16401 8938 16401 9221 16401 9221 16402 8938 16402 8939 16402 9221 16403 8939 16403 8940 16403 9152 16404 9214 16404 9154 16404 9154 16405 9214 16405 9224 16405 9154 16406 9224 16406 9213 16406 9213 16407 9224 16407 9225 16407 9213 16408 9225 16408 9222 16408 9226 16409 9227 16409 9228 16409 8821 16410 8827 16410 9229 16410 8805 16411 8806 16411 9230 16411 8807 16412 8808 16412 9231 16412 9231 16413 8808 16413 8942 16413 9231 16414 8942 16414 8943 16414 8805 16415 9230 16415 8804 16415 8853 16416 8798 16416 8797 16416 8801 16417 8800 16417 8797 16417 8797 16418 8800 16418 9232 16418 8797 16419 9232 16419 8853 16419 9233 7968 8849 7968 9232 7968 9232 16420 8849 16420 8859 16420 9232 16421 8859 16421 8853 16421 9217 16422 8983 16422 9234 16422 9234 16423 8983 16423 8858 16423 9234 16424 8858 16424 8850 16424 9217 7974 9234 7974 9216 7974 9216 16425 9234 16425 9235 16425 9216 16426 9235 16426 9215 16426 9236 7977 9224 7977 9235 7977 9235 16427 9224 16427 9214 16427 9235 16428 9214 16428 9215 16428 9237 7980 9219 7980 9238 7980 9238 7981 9219 7981 9222 7981 9238 7982 9222 7982 9236 7982 9236 7983 9222 7983 9225 7983 9236 16429 9225 16429 9224 16429 9239 16430 9221 16430 9237 16430 9237 16431 9221 16431 9220 16431 9237 7987 9220 7987 9219 7987 8894 7988 9239 7988 8895 7988 8895 7989 9239 7989 8899 7989 8894 16432 8933 16432 9239 16432 9239 16433 8933 16433 9223 16433 9239 16434 9223 16434 9221 16434 8825 16435 8823 16435 9240 16435 9240 16436 8823 16436 8822 16436 9240 16437 8822 16437 8772 16437 8772 7996 8771 7996 9240 7996 9240 16438 8771 16438 8896 16438 9240 7998 8896 7998 8897 7998 8946 16439 8821 16439 8945 16439 8945 16440 8821 16440 9229 16440 8945 8001 9229 8001 8944 8001 8944 8002 9229 8002 9241 8002 9228 16441 9227 16441 9242 16441 9227 16442 9243 16442 9242 16442 9242 16443 9243 16443 9244 16443 9242 16444 9244 16444 9229 16444 9229 8007 9244 8007 9245 8007 9229 8008 9245 8008 9241 8008 9226 8009 9228 8009 9246 8009 9246 8010 9228 8010 9247 8010 9246 8011 9247 8011 9248 8011 9248 8012 9247 8012 9249 8012 9248 16445 9249 16445 9250 16445 9250 16446 9249 16446 9251 16446 9251 8015 9249 8015 9252 8015 9251 16447 9252 16447 9253 16447 9253 8017 9252 8017 9254 8017 9254 16448 9252 16448 9255 16448 9254 16449 9255 16449 9256 16449 9256 16450 9255 16450 9257 16450 9257 16451 9255 16451 9231 16451 9257 8022 9231 8022 9258 8022 9258 16452 9231 16452 8943 16452 9258 16453 8943 16453 8941 16453 8827 16454 8826 16454 9229 16454 9229 16455 8826 16455 9259 16455 9229 16456 9259 16456 9242 16456 9242 16457 9259 16457 9260 16457 9242 16458 9260 16458 9228 16458 9228 8030 9260 8030 9261 8030 9228 16459 9261 16459 9247 16459 9247 8032 9261 8032 9262 8032 9247 8033 9262 8033 9249 8033 9249 8034 9262 8034 9263 8034 9249 16460 9263 16460 9252 16460 9252 16461 9263 16461 9264 16461 9252 16462 9264 16462 9255 16462 9255 8038 9264 8038 9265 8038 9255 16463 9265 16463 9231 16463 9231 16464 9265 16464 9230 16464 9231 16465 9230 16465 8807 16465 8807 16466 9230 16466 8806 16466 8826 16467 8825 16467 9259 16467 9259 16468 8825 16468 9240 16468 9259 16469 9240 16469 9260 16469 9260 16470 9240 16470 9266 16470 9260 16471 9266 16471 9261 16471 9261 16472 9266 16472 9267 16472 9261 8049 9267 8049 9262 8049 9262 8050 9267 8050 9268 8050 9262 16473 9268 16473 9263 16473 9263 16474 9268 16474 9269 16474 9263 16475 9269 16475 9264 16475 9264 16476 9269 16476 9270 16476 9264 8055 9270 8055 9265 8055 9265 8056 9270 8056 9233 8056 9265 16477 9233 16477 9230 16477 9230 8058 9233 8058 9232 8058 9230 16478 9232 16478 8804 16478 8804 16479 9232 16479 8800 16479 8897 16480 8898 16480 9240 16480 9240 16481 8898 16481 8899 16481 9240 16482 8899 16482 9266 16482 9266 16483 8899 16483 9239 16483 9266 16484 9239 16484 9267 16484 9267 16485 9239 16485 9237 16485 9267 16486 9237 16486 9268 16486 9268 16487 9237 16487 9238 16487 9268 16488 9238 16488 9269 16488 9269 16489 9238 16489 9236 16489 9269 8072 9236 8072 9270 8072 9270 16490 9236 16490 9235 16490 9270 16491 9235 16491 9233 16491 9233 16492 9235 16492 9234 16492 9233 8076 9234 8076 8849 8076 8849 8077 9234 8077 8850 8077 8817 7922 8819 7922 8399 7922 8399 16493 8819 16493 8944 16493 8399 7924 8944 7924 9241 7924 8399 7925 8397 7925 8817 7925 8817 16494 8397 16494 8395 16494 8817 16495 8395 16495 8811 16495 8811 16496 8395 16496 8394 16496 8811 7929 8394 7929 8812 7929 8812 7930 8394 7930 8415 7930 8812 16497 8415 16497 8813 16497 8813 16498 8415 16498 8413 16498 8813 16499 8413 16499 8814 16499 9258 7934 8941 7934 8815 7934 8814 7935 8413 7935 8815 7935 8815 7936 8413 7936 8411 7936 8815 16500 8411 16500 9258 16500 8409 16501 9256 16501 8411 16501 8411 7939 9256 7939 9257 7939 8411 7940 9257 7940 9258 7940 8407 16502 9253 16502 8409 16502 8409 7942 9253 7942 9254 7942 8409 7943 9254 7943 9256 7943 8405 16503 9250 16503 8407 16503 8407 7945 9250 7945 9251 7945 8407 16504 9251 16504 9253 16504 8403 16505 9246 16505 8405 16505 8405 16506 9246 16506 9248 16506 8405 16507 9248 16507 9250 16507 8401 16508 9227 16508 8403 16508 8403 16509 9227 16509 9226 16509 8403 7952 9226 7952 9246 7952 9241 7953 9245 7953 8399 7953 8399 16510 9245 16510 9244 16510 8399 16511 9244 16511 8401 16511 8401 16512 9244 16512 9243 16512 8401 16513 9243 16513 9227 16513 8396 7919 8408 7919 8410 7919 8396 7920 8398 7920 8400 7920 8416 632 8393 632 8414 632 8414 7921 8393 7921 8396 7921 8414 632 8396 632 8412 632 8412 632 8396 632 8410 632 8406 632 8408 632 8404 632 8404 632 8408 632 8396 632 8404 632 8396 632 8402 632 8402 632 8396 632 8400 632 8786 95 8372 95 7312 95 8870 7917 8872 7917 8787 7917 8837 95 7312 95 8388 95 8388 95 7312 95 7311 95 8787 95 8786 95 8870 95 8870 95 8786 95 7312 95 8870 95 7312 95 8868 95 8868 95 7312 95 8837 95 8868 95 8837 95 8866 95 8866 95 8837 95 8836 95 8866 7918 8836 7918 8863 7918 8283 16514 8700 16514 8285 16514 8285 7903 8700 7903 8701 7903 8285 16515 8701 16515 8287 16515 8287 16516 8701 16516 8705 16516 8287 16517 8705 16517 8296 16517 8283 16518 8281 16518 8700 16518 8700 16519 8281 16519 8280 16519 8700 16520 8280 16520 8302 16520 8708 16521 8257 16521 8707 16521 8707 16522 8257 16522 8268 16522 8707 16523 8268 16523 8695 16523 8695 16524 8268 16524 8267 16524 8695 7916 8267 7916 8696 7916 8696 16525 8267 16525 8266 16525 8696 16526 8266 16526 8703 16526 8703 16527 8266 16527 8301 16527 8703 16528 8301 16528 8704 16528 8704 16529 8301 16529 8299 16529 8704 16530 8299 16530 8705 16530 8705 16531 8299 16531 8297 16531 8705 16532 8297 16532 8296 16532 8378 16533 8377 16533 8376 16533 8302 7884 8378 7884 8791 7884 8791 16534 8378 16534 8376 16534 8791 16535 8376 16535 8793 16535 8793 16536 8376 16536 8375 16536 8793 16537 8375 16537 8795 16537 8795 7889 8375 7889 8374 7889 8795 7890 8374 7890 8796 7890 8796 16538 8374 16538 8380 16538 8796 16539 8380 16539 8788 16539 8372 7893 8786 7893 8373 7893 8373 7894 8786 7894 8788 7894 8373 16540 8788 16540 8379 16540 8379 16541 8788 16541 8380 16541 8837 7872 8388 7872 8389 7872 8837 7873 8389 7873 8835 7873 8835 16542 8389 16542 8392 16542 8835 16543 8392 16543 8833 16543 8833 16544 8392 16544 8391 16544 8833 16545 8391 16545 8830 16545 8830 16546 8391 16546 8390 16546 8830 7879 8390 7879 8387 7879 8387 16547 8386 16547 8830 16547 8830 16548 8386 16548 8385 16548 8830 7882 8385 7882 8343 7882 8660 16549 8659 16549 8720 16549 8747 16550 8751 16550 8628 16550 8660 16551 8720 16551 8651 16551 8651 16552 8720 16552 8719 16552 8651 16553 8719 16553 8628 16553 8628 16554 8719 16554 8748 16554 8628 16555 8748 16555 8747 16555 8324 16556 8323 16556 8730 16556 8730 16557 8323 16557 8628 16557 8730 16558 8628 16558 8731 16558 8731 16559 8628 16559 8751 16559 8683 16560 9271 16560 8668 16560 8668 16561 9271 16561 9272 16561 8668 16562 9272 16562 9273 16562 9274 16563 8664 16563 9273 16563 9273 16564 8664 16564 8666 16564 9273 16565 8666 16565 8668 16565 8708 16566 8709 16566 8599 16566 8599 16567 8709 16567 8710 16567 8599 16568 8710 16568 8711 16568 8659 16569 8664 16569 8720 16569 8720 16570 8664 16570 9274 16570 8720 16571 9274 16571 8726 16571 8726 16572 9274 16572 9275 16572 8726 16573 9275 16573 8717 16573 8717 16574 9275 16574 8691 16574 8717 16575 8691 16575 8711 16575 8711 16576 8691 16576 8602 16576 8711 16577 8602 16577 8599 16577 8257 7855 8708 7855 8249 7855 8249 16578 8708 16578 8599 16578 8249 16579 8599 16579 8250 16579 8250 16580 8599 16580 8598 16580 8250 16581 8598 16581 8595 16581 8489 16582 8252 16582 8603 16582 8603 16583 8252 16583 8250 16583 8603 16584 8250 16584 8604 16584 8604 16585 8250 16585 8595 16585 8631 16586 8309 16586 8629 16586 8629 16587 8309 16587 8308 16587 8629 16588 8308 16588 8459 16588 8631 16589 8634 16589 8309 16589 8309 16590 8634 16590 8633 16590 8309 16591 8633 16591 8323 16591 8323 16592 8633 16592 8626 16592 8323 16593 8626 16593 8628 16593 8828 16594 8343 16594 8843 16594 8843 16595 8343 16595 8744 16595 8843 16596 8744 16596 8799 16596 8799 98 8744 98 8757 98 1369 98 1368 98 8384 98 8384 98 1368 98 8343 98 8384 98 8343 98 8385 98 8378 106 8302 106 8371 106 8371 106 8302 106 8367 106 258 16597 4157 16597 9276 16597 248 95 9277 95 8243 95 8243 95 9277 95 9278 95 8243 16598 9278 16598 8244 16598 9276 95 9279 95 258 95 258 95 9279 95 9280 95 258 95 9280 95 248 95 248 95 9280 95 9281 95 248 95 9281 95 9277 95 7381 106 7380 106 7386 106 7386 106 7380 106 7530 106 7359 7815 7358 7815 7531 7815 7531 7816 7358 7816 7382 7816 7531 7817 7382 7817 7532 7817 7532 7818 7382 7818 7388 7818 7532 7819 7388 7819 7530 7819 7530 7819 7388 7819 7386 7819 7843 98 9282 98 7329 98 7648 16599 7836 16599 7327 16599 7836 98 7838 98 7327 98 7327 16600 7838 16600 7839 16600 7327 98 7839 98 7329 98 7329 16601 7839 16601 7841 16601 7329 16602 7841 16602 7843 16602 7327 16603 8004 16603 8006 16603 8006 98 8010 98 7327 98 7327 16604 8010 16604 8008 16604 7327 16605 8008 16605 7648 16605 7648 16606 8008 16606 7647 16606 7648 98 7647 98 7649 98 7647 98 7642 98 7649 98 7649 16607 7642 16607 7640 16607 7649 98 7640 98 7627 98 7627 16608 7640 16608 7639 16608 7627 16609 7639 16609 7628 16609 7328 106 7997 106 7326 106 7326 16610 7997 16610 7996 16610 7326 16611 7996 16611 7995 16611 7330 95 7988 95 7991 95 8000 7801 7328 7801 8002 7801 8002 16612 7328 16612 7330 16612 8002 16613 7330 16613 7993 16613 7993 16614 7330 16614 7991 16614 8000 7802 7999 7802 7328 7802 7328 95 7999 95 7998 95 7328 95 7998 95 7997 95 7989 16615 7988 16615 7330 16615 7331 106 9283 106 8072 106 8072 106 8071 106 7331 106 7331 16616 8071 16616 8087 16616 7331 106 8087 106 7330 106 7330 16617 8087 16617 8089 16617 7865 106 7881 106 7873 106 7873 16618 7881 16618 7852 16618 8089 106 8091 106 7330 106 7330 16619 8091 16619 8093 16619 7330 16620 8093 16620 7989 16620 7989 16621 8093 16621 7863 16621 7989 16622 7863 16622 7873 16622 7873 16623 7863 16623 7865 16623 7852 16624 7866 16624 7873 16624 7873 16625 7866 16625 7868 16625 7873 16626 7868 16626 7871 16626 9284 16627 9285 16627 9286 16627 8072 16628 9283 16628 8073 16628 8073 16629 9283 16629 9284 16629 8073 16630 9284 16630 8082 16630 9284 16631 9286 16631 8082 16631 8082 16632 9286 16632 8422 16632 8082 16633 8422 16633 8083 16633 8607 16634 8686 16634 9287 16634 9287 16635 8686 16635 9288 16635 9001 16636 7322 16636 9002 16636 9002 16637 7322 16637 7321 16637 9002 7737 7321 7737 9003 7737 9001 16638 9008 16638 7322 16638 7322 16639 9008 16639 9010 16639 7322 16640 9010 16640 7323 16640 7323 16641 9010 16641 8989 16641 7323 16642 8989 16642 8988 16642 7325 16643 7324 16643 8996 16643 8996 16644 9006 16644 7325 16644 7325 16645 9006 16645 9005 16645 7325 16646 9005 16646 7321 16646 7321 16647 9005 16647 9004 16647 7321 16648 9004 16648 9003 16648 9000 16649 8999 16649 7317 16649 7317 16650 8999 16650 8998 16650 7317 16651 8998 16651 7324 16651 7324 7752 8998 7752 8997 7752 7324 7753 8997 7753 8996 7753 9000 7754 7317 7754 8992 7754 8992 7755 7317 7755 7316 7755 8992 16652 7316 16652 8993 16652 9106 16653 7314 16653 9107 16653 9107 16654 7314 16654 7313 16654 9107 16655 7313 16655 9109 16655 9109 16656 7313 16656 7320 16656 9109 16657 7320 16657 9111 16657 9111 16658 7320 16658 7319 16658 9111 16659 7319 16659 9113 16659 9113 16660 7319 16660 7318 16660 9113 16661 7318 16661 9115 16661 9115 16662 7318 16662 7323 16662 9115 7767 7323 7767 9099 7767 9099 7768 7323 7768 8988 7768 9099 16663 8988 16663 9100 16663 9116 16664 8993 16664 9117 16664 9117 7771 8993 7771 7316 7771 9117 7772 7316 7772 9105 7772 9105 16665 7316 16665 7314 16665 9105 16666 7314 16666 9104 16666 9104 16667 7314 16667 9106 16667 9289 16668 9290 16668 1425 16668 1425 16669 9290 16669 1427 16669 9291 16670 9292 16670 9293 16670 9293 633 9292 633 9294 633 9293 633 9294 633 9295 633 9296 13243 9297 13243 9293 13243 9293 16671 9297 16671 9298 16671 9293 16672 9298 16672 9291 16672 9299 633 9300 633 9293 633 9293 633 9300 633 9301 633 9293 633 9301 633 9296 633 9295 633 9302 633 9293 633 9293 16673 9302 16673 9303 16673 9293 16674 9303 16674 9299 16674 9304 633 9305 633 9306 633 9306 633 9305 633 9307 633 9306 633 9307 633 9308 633 9308 633 9307 633 9309 633 9310 16675 9311 16675 9312 16675 9310 11384 9312 11384 9313 11384 9313 16676 9312 16676 9314 16676 9313 16677 9314 16677 9315 16677 9311 16678 9310 16678 9316 16678 9311 16679 9316 16679 9317 16679 9317 16680 9316 16680 9318 16680 9317 16681 9318 16681 9319 16681 9319 16682 9318 16682 9320 16682 9319 16683 9320 16683 9321 16683 9322 16684 9323 16684 9324 16684 9322 16685 9324 16685 9325 16685 9325 16686 9324 16686 9326 16686 9325 16687 9326 16687 9327 16687 9327 16688 9326 16688 9314 16688 9314 16689 9326 16689 9315 16689 9321 16690 9320 16690 9328 16690 9329 11368 9330 11368 9328 11368 9328 16691 9330 16691 9331 16691 9328 13259 9331 13259 9321 13259 9332 13260 9333 13260 9334 13260 9332 16692 9334 16692 9335 16692 9335 16693 9334 16693 9323 16693 9335 16694 9323 16694 9322 16694 9336 11343 9337 11343 9338 11343 9336 11344 9338 11344 9339 11344 9339 11345 9338 11345 9340 11345 9339 11346 9340 11346 9341 11346 9341 11347 9340 11347 9342 11347 9341 16695 9342 16695 9343 16695 9343 11350 9342 11350 9344 11350 9343 16696 9344 16696 9345 16696 9345 16697 9344 16697 9346 16697 9345 11351 9346 11351 9347 11351 9347 11352 9346 11352 9348 11352 9347 11353 9348 11353 9349 11353 9349 11354 9348 11354 9350 11354 9349 11355 9350 11355 9351 11355 9351 16698 9350 16698 9352 16698 9351 11357 9352 11357 9353 11357 9353 11358 9352 11358 9354 11358 9353 11359 9354 11359 9355 11359 9355 11361 9354 11361 9356 11361 9355 11361 9356 11361 9357 11361 9357 16699 9356 16699 9358 16699 9357 11362 9358 11362 9359 11362 9323 16700 9334 16700 9333 16700 9333 16701 9360 16701 9361 16701 9326 95 9324 95 9323 95 9362 95 9336 95 9363 95 9363 95 9336 95 9364 95 9363 95 9364 95 9365 95 9365 16702 9364 16702 9366 16702 9365 95 9366 95 9359 95 9333 95 9336 95 9339 95 9333 16703 9361 16703 9336 16703 9336 16704 9361 16704 9367 16704 9336 95 9367 95 9364 95 9351 95 9353 95 9368 95 9355 95 9369 95 9353 95 9353 95 9369 95 9370 95 9353 95 9370 95 9368 95 9366 95 9371 95 9359 95 9359 16705 9371 16705 9372 16705 9359 16706 9372 16706 9357 16706 9357 16707 9372 16707 9373 16707 9357 95 9373 95 9374 95 9349 95 9329 95 9347 95 9347 95 9329 95 9328 95 9347 95 9328 95 9345 95 9345 95 9328 95 9320 95 9345 95 9320 95 9343 95 9343 95 9320 95 9341 95 9368 95 9375 95 9351 95 9351 16708 9375 16708 9376 16708 9351 95 9376 95 9349 95 9349 95 9376 95 9377 95 9349 95 9377 95 9329 95 9329 95 9377 95 9378 95 9329 95 9378 95 9379 95 9374 95 9380 95 9357 95 9357 95 9380 95 9381 95 9357 95 9381 95 9355 95 9355 95 9381 95 9382 95 9355 95 9382 95 9369 95 9316 95 9310 95 9313 95 9339 16709 9341 16709 9333 16709 9333 16710 9341 16710 9320 16710 9333 16711 9320 16711 9323 16711 9323 16712 9320 16712 9318 16712 9323 95 9318 95 9326 95 9326 95 9318 95 9316 95 9326 95 9316 95 9315 95 9315 95 9316 95 9313 95 9383 95 9384 95 9385 95 9385 95 9384 95 9386 95 9385 95 9386 95 9387 95 9388 95 9389 95 9385 95 9385 95 9389 95 9390 95 9385 95 9390 95 9383 95 9391 95 9392 95 9385 95 9385 95 9392 95 9393 95 9385 95 9393 95 9388 95 9387 95 9394 95 9385 95 9385 95 9394 95 9395 95 9385 95 9395 95 9391 95 9393 16713 9396 16713 9388 16713 9388 16714 9396 16714 9397 16714 9388 16715 9397 16715 9389 16715 9389 16716 9397 16716 9398 16716 9389 16717 9398 16717 9390 16717 9390 16718 9398 16718 9399 16718 9390 16719 9399 16719 9383 16719 9383 16720 9399 16720 9400 16720 9383 11307 9400 11307 9384 11307 9384 16721 9400 16721 9401 16721 9384 11308 9401 11308 9386 11308 9386 16722 9401 16722 9402 16722 9386 16722 9402 16722 9387 16722 9387 11311 9402 11311 9403 11311 9387 16723 9403 16723 9394 16723 9394 16724 9403 16724 9404 16724 9394 16725 9404 16725 9395 16725 9395 16726 9404 16726 9405 16726 9395 16727 9405 16727 9391 16727 9391 16728 9405 16728 9406 16728 9391 16729 9406 16729 9392 16729 9392 16730 9406 16730 9407 16730 9392 16731 9407 16731 9393 16731 9393 16732 9407 16732 9396 16732 9408 16733 9409 16733 9410 16733 9410 16734 9411 16734 9408 16734 9408 13312 9411 13312 9412 13312 9408 13313 9412 13313 9413 13313 9414 13314 9415 13314 9416 13314 9417 16735 9418 16735 9416 16735 9416 16736 9418 16736 9419 16736 9416 16737 9419 16737 9414 16737 9409 16738 9420 16738 9410 16738 9410 13319 9420 13319 9417 13319 9410 16739 9417 16739 9421 16739 9421 16740 9417 16740 9416 16740 9422 16741 9423 16741 9424 16741 9425 13323 9426 13323 9427 13323 9428 13324 158 13324 159 13324 9429 13325 143 13325 158 13325 9430 16742 9431 16742 9432 16742 9432 16743 9431 16743 9433 16743 9432 16744 9433 16744 9434 16744 158 13329 9428 13329 9429 13329 9429 13330 9428 13330 9435 13330 9429 16745 9435 16745 9436 16745 9436 16746 9435 16746 9431 16746 9436 16747 9431 16747 9437 16747 9437 16748 9431 16748 9430 16748 9437 13335 9430 13335 9415 13335 9426 13336 9425 13336 9433 13336 9433 16749 9425 16749 9438 16749 9433 16750 9438 16750 9434 16750 9423 16751 9439 16751 9424 16751 9424 16752 9439 16752 9440 16752 9424 16753 9440 16753 9441 16753 9441 16754 9440 16754 9442 16754 9441 16755 9442 16755 9443 16755 9444 16756 9445 16756 9441 16756 9441 13345 9445 13345 9446 13345 9441 16757 9446 16757 9424 16757 9424 16758 9446 16758 9447 16758 9424 16759 9447 16759 9422 16759 9422 16760 9447 16760 9448 16760 9422 16761 9448 16761 9449 16761 9450 16762 9451 16762 9444 16762 9444 16763 9451 16763 9452 16763 9444 13353 9452 13353 9445 13353 9453 13354 9454 13354 9455 13354 9455 16764 9454 16764 9456 16764 9455 16765 9456 16765 9450 16765 9450 16766 9456 16766 9457 16766 9450 16767 9457 16767 9451 16767 160 13359 9454 13359 159 13359 159 13360 9454 13360 9453 13360 159 13361 9453 13361 9428 13361 9428 13362 9453 13362 9455 13362 9428 13363 9455 13363 9435 13363 9435 13364 9455 13364 9450 13364 9435 16768 9450 16768 9431 16768 9431 16769 9450 16769 9444 16769 9431 16770 9444 16770 9433 16770 9433 16771 9444 16771 9441 16771 9433 16772 9441 16772 9426 16772 9426 16773 9441 16773 9443 16773 9426 16774 9443 16774 9427 16774 9458 16775 9459 16775 9460 16775 9461 16776 9462 16776 9463 16776 9464 16777 9465 16777 9466 16777 9464 16778 9466 16778 9467 16778 9466 16779 9468 16779 9467 16779 9467 16780 9468 16780 9469 16780 9467 16781 9469 16781 9470 16781 9470 16782 9469 16782 9471 16782 9470 16783 9471 16783 9472 16783 9472 16784 9471 16784 9473 16784 9473 16785 9471 16785 9474 16785 9474 16786 9471 16786 9475 16786 9474 16787 9475 16787 9476 16787 9476 16788 9475 16788 9477 16788 9476 16789 9477 16789 9478 16789 9478 16790 9477 16790 9479 16790 9479 16791 9477 16791 9480 16791 9479 16792 9480 16792 9481 16792 9482 16793 9481 16793 9483 16793 9483 16794 9481 16794 9480 16794 9483 16795 9480 16795 9484 16795 9484 16796 9480 16796 9485 16796 9485 16797 9480 16797 9486 16797 9486 16798 9480 16798 9477 16798 9486 16799 9477 16799 9462 16799 9461 16800 9463 16800 9487 16800 9458 16801 9488 16801 9459 16801 9459 16802 9488 16802 9489 16802 9459 16803 9489 16803 9463 16803 9463 16804 9489 16804 9490 16804 9463 16805 9490 16805 9487 16805 9491 16806 9492 16806 9493 16806 9493 16807 9492 16807 9494 16807 9493 16808 9494 16808 9460 16808 9460 16809 9494 16809 9495 16809 9460 16810 9495 16810 9458 16810 9462 16811 9477 16811 9463 16811 9463 16812 9477 16812 9475 16812 9463 16813 9475 16813 9459 16813 9459 16814 9475 16814 9471 16814 9459 16815 9471 16815 9460 16815 9460 16816 9471 16816 9469 16816 9460 16817 9469 16817 9493 16817 9493 16818 9469 16818 9468 16818 9493 16819 9468 16819 9491 16819 9491 16820 9468 16820 9466 16820 9491 16821 9466 16821 9492 16821 9492 16822 9466 16822 9496 16822 9492 16823 9496 16823 9497 16823 9498 16824 9499 16824 9500 16824 9500 16825 9499 16825 9501 16825 9500 16826 9501 16826 9502 16826 9502 16827 9501 16827 9503 16827 9502 16828 9503 16828 9504 16828 9504 16829 9503 16829 9505 16829 9505 16830 9503 16830 9506 16830 9505 16831 9506 16831 9507 16831 9495 16832 9508 16832 9507 16832 9507 16833 9508 16833 9509 16833 9509 16834 9510 16834 9507 16834 9507 16835 9510 16835 9511 16835 9507 16836 9511 16836 9505 16836 9397 16837 9396 16837 9512 16837 9512 95 9358 95 9397 95 9397 95 9358 95 9356 95 9397 95 9356 95 9398 95 9398 95 9356 95 9354 95 9398 16838 9354 16838 9399 16838 9399 16839 9354 16839 9352 16839 9399 16840 9352 16840 9400 16840 9400 95 9352 95 9350 95 9400 95 9350 95 9401 95 9401 16841 9350 16841 9348 16841 9401 95 9348 95 9402 95 9402 95 9348 95 9346 95 9402 16842 9346 16842 9403 16842 9403 95 9346 95 9344 95 9403 95 9344 95 9404 95 9404 95 9344 95 9342 95 9404 95 9342 95 9405 95 9405 16843 9342 16843 9340 16843 9405 95 9340 95 9406 95 9406 95 9340 95 9338 95 9406 95 9338 95 9407 95 9338 95 9337 95 9407 95 9407 95 9337 95 9513 95 9407 95 9513 95 9396 95 9396 16844 9513 16844 9514 16844 9396 16845 9514 16845 9512 16845 9442 13444 9515 13444 9516 13444 9517 16846 9518 16846 9449 16846 9519 16847 9520 16847 9521 16847 9416 13447 9522 13447 9421 13447 9421 13448 9522 13448 9523 13448 9421 16848 9523 16848 9410 16848 9410 16849 9523 16849 9411 16849 9411 13451 9523 13451 9524 13451 9411 13452 9524 13452 9525 13452 9525 16850 9526 16850 9411 16850 9411 16851 9526 16851 9527 16851 9411 13455 9527 13455 9412 13455 9528 13456 9413 13456 9529 13456 9529 13457 9413 13457 9412 13457 9529 13458 9412 13458 9530 13458 9530 13459 9412 13459 9527 13459 9531 16852 9532 16852 9523 16852 9523 16853 9532 16853 9533 16853 9533 16854 9534 16854 9523 16854 9523 16855 9534 16855 9535 16855 9523 13464 9535 13464 9524 13464 9524 13465 9535 13465 9536 13465 9524 13466 9536 13466 9525 13466 9522 16856 9537 16856 9523 16856 9523 16857 9537 16857 9538 16857 9523 16858 9538 16858 9531 16858 9531 16859 9538 16859 9539 16859 9531 16860 9539 16860 9540 16860 9540 16861 9539 16861 9521 16861 9540 16862 9521 16862 9541 16862 9541 16863 9521 16863 9520 16863 9518 13475 9517 13475 9542 13475 9440 13476 9439 13476 9542 13476 9542 13477 9439 13477 9423 13477 9542 16864 9423 16864 9518 16864 9518 16865 9423 16865 9422 16865 9518 16866 9422 16866 9449 16866 9442 13481 9440 13481 9515 13481 9515 13482 9440 13482 9542 13482 9515 13483 9542 13483 9543 13483 9543 13484 9542 13484 9517 13484 9543 16867 9517 16867 9544 16867 9430 16868 9432 16868 9545 16868 9545 16869 9432 16869 9434 16869 9545 13488 9434 13488 9546 13488 9546 16870 9434 16870 9438 16870 9546 16871 9438 16871 9547 16871 9547 16872 9438 16872 9425 16872 9547 16873 9425 16873 9548 16873 9548 16874 9425 16874 9427 16874 9548 16875 9427 16875 9516 16875 9516 16876 9427 16876 9443 16876 9516 16877 9443 16877 9442 16877 9543 13497 9549 13497 9515 13497 9515 13498 9549 13498 9519 13498 9515 13499 9519 13499 9516 13499 9516 13500 9519 13500 9521 13500 9516 16878 9521 16878 9548 16878 9548 13502 9521 13502 9539 13502 9548 16879 9539 16879 9547 16879 9547 16880 9539 16880 9538 16880 9547 13504 9538 13504 9546 13504 9546 13505 9538 13505 9537 13505 9546 13506 9537 13506 9545 13506 9545 16881 9537 16881 9522 16881 9545 13508 9522 13508 9430 13508 9430 13509 9522 13509 9416 13509 9430 13510 9416 13510 9415 13510 9550 16882 9551 16882 9552 16882 9485 16883 9486 16883 9553 16883 9489 16884 9488 16884 9554 16884 9555 16885 9556 16885 9557 16885 9557 16886 9556 16886 9558 16886 9557 16887 9558 16887 9559 16887 9559 16888 9558 16888 9560 16888 9561 16889 9562 16889 9563 16889 9563 16890 9562 16890 9564 16890 9564 16891 9565 16891 9563 16891 9563 16892 9565 16892 9566 16892 9563 16893 9566 16893 9567 16893 9568 16894 9569 16894 9561 16894 9561 16895 9569 16895 9570 16895 9561 16896 9570 16896 9562 16896 9562 16897 9570 16897 9571 16897 9562 16898 9571 16898 9564 16898 9561 16899 9501 16899 9499 16899 9568 11056 9561 11056 9572 11056 9572 16900 9561 16900 9499 16900 9572 11058 9499 11058 9498 11058 9503 11059 9573 11059 9506 11059 9506 16901 9573 16901 9574 16901 9506 16902 9574 16902 9507 16902 9507 16903 9574 16903 9554 16903 9488 16904 9458 16904 9554 16904 9554 16905 9458 16905 9495 16905 9554 16906 9495 16906 9507 16906 9461 16907 9487 16907 9575 16907 9575 16908 9487 16908 9490 16908 9485 16909 9553 16909 9484 16909 9576 16910 9577 16910 9578 16910 9578 16911 9577 16911 9579 16911 9578 16912 9579 16912 9580 16912 9580 16913 9579 16913 9482 16913 9580 16914 9482 16914 9483 16914 9551 16915 9550 16915 9581 16915 9550 16916 9576 16916 9581 16916 9581 16917 9576 16917 9578 16917 9581 16918 9578 16918 9553 16918 9553 16919 9578 16919 9580 16919 9553 16920 9580 16920 9484 16920 9484 16921 9580 16921 9483 16921 9560 16922 9582 16922 9559 16922 9559 16923 9582 16923 9583 16923 9559 16924 9583 16924 9557 16924 9557 16925 9583 16925 9563 16925 9557 16926 9563 16926 9555 16926 9555 16927 9563 16927 9567 16927 9486 16928 9462 16928 9553 16928 9553 16929 9462 16929 9461 16929 9553 16930 9461 16930 9581 16930 9581 16931 9461 16931 9575 16931 9581 16932 9575 16932 9551 16932 9551 16933 9575 16933 9583 16933 9551 16934 9583 16934 9552 16934 9552 16935 9583 16935 9582 16935 9490 16936 9489 16936 9575 16936 9575 16937 9489 16937 9554 16937 9575 16938 9554 16938 9583 16938 9583 16939 9554 16939 9574 16939 9583 16940 9574 16940 9563 16940 9563 16941 9574 16941 9573 16941 9563 16942 9573 16942 9561 16942 9561 16943 9573 16943 9503 16943 9561 16944 9503 16944 9501 16944 9519 13577 9549 13577 9584 13577 9543 16945 9544 16945 9585 16945 9586 16946 9587 16946 9360 16946 9360 16947 9587 16947 9588 16947 9360 16948 9588 16948 9361 16948 9361 16949 9588 16949 9585 16949 9361 16950 9585 16950 9367 16950 9589 16951 9540 16951 9590 16951 9590 16952 9540 16952 9541 16952 9590 13586 9541 13586 9584 13586 9584 13587 9541 13587 9520 13587 9584 16953 9520 16953 9519 16953 9586 16954 9589 16954 9587 16954 9587 16955 9589 16955 9590 16955 9587 16956 9590 16956 9588 16956 9588 13592 9590 13592 9584 13592 9588 16957 9584 16957 9585 16957 9585 13594 9584 13594 9549 13594 9585 16958 9549 16958 9543 16958 9332 16959 9591 16959 9592 16959 9360 16960 9333 16960 9593 16960 9593 16961 9333 16961 9332 16961 9593 16962 9332 16962 9594 16962 9594 16963 9332 16963 9592 16963 9529 16964 9595 16964 9528 16964 9536 16965 9535 16965 9596 16965 9533 16966 9532 16966 9589 16966 9589 16967 9532 16967 9531 16967 9589 16968 9531 16968 9540 16968 9535 16969 9534 16969 9596 16969 9596 13607 9534 13607 9533 13607 9596 16970 9533 16970 9597 16970 9597 16971 9533 16971 9589 16971 9597 16972 9589 16972 9586 16972 9526 13611 9525 13611 9592 13611 9592 16973 9591 16973 9526 16973 9526 16974 9591 16974 9598 16974 9526 16975 9598 16975 9527 16975 9595 16976 9529 16976 9598 16976 9598 13616 9529 13616 9530 13616 9598 13617 9530 13617 9527 13617 9525 13618 9536 13618 9592 13618 9592 16977 9536 16977 9596 16977 9592 16978 9596 16978 9594 16978 9594 16979 9596 16979 9597 16979 9594 16980 9597 16980 9593 16980 9593 16981 9597 16981 9586 16981 9593 13624 9586 13624 9360 13624 9599 16982 9600 16982 9601 16982 9566 16983 9602 16983 9567 16983 9603 16984 9604 16984 9599 16984 9605 16985 9570 16985 9569 16985 9556 16986 9555 16986 9601 16986 9556 16987 9606 16987 9558 16987 9558 10973 9606 10973 9607 10973 9558 16988 9607 16988 9560 16988 9556 16989 9601 16989 9606 16989 9606 16990 9601 16990 9600 16990 9606 16991 9600 16991 9379 16991 9605 16992 9569 16992 9608 16992 9608 16993 9569 16993 9568 16993 9608 16994 9568 16994 9572 16994 9570 16995 9605 16995 9571 16995 9571 16996 9605 16996 9603 16996 9571 16997 9603 16997 9564 16997 9555 16998 9567 16998 9601 16998 9601 16999 9567 16999 9602 16999 9601 17000 9602 17000 9599 17000 9599 17001 9602 17001 9566 17001 9599 17002 9566 17002 9603 17002 9603 17003 9566 17003 9565 17003 9603 17004 9565 17004 9564 17004 9599 17005 9604 17005 9600 17005 9600 17006 9604 17006 9330 17006 9600 17007 9330 17007 9379 17007 9379 17008 9330 17008 9329 17008 9609 17009 9610 17009 9611 17009 9612 13654 9613 13654 9614 13654 9612 17010 9614 17010 9615 17010 9616 17011 9617 17011 9618 17011 9617 17012 9619 17012 9620 17012 9621 17013 9622 17013 9623 17013 9623 17014 9622 17014 9624 17014 9625 13660 9626 13660 9627 13660 9627 13661 9626 13661 9623 13661 9627 13662 9623 13662 9628 13662 9628 17015 9623 17015 9624 17015 9628 17016 9624 17016 9629 17016 9630 17017 9631 17017 9632 17017 9631 17018 9609 17018 9632 17018 9632 17019 9609 17019 9611 17019 9632 17020 9611 17020 9633 17020 9633 17021 9611 17021 9634 17021 9633 17022 9634 17022 9614 17022 9614 17023 9634 17023 9618 17023 9614 13672 9618 13672 9615 13672 9615 13673 9618 13673 9617 13673 9615 13674 9617 13674 9635 13674 9635 13675 9617 13675 9620 13675 9610 17024 9621 17024 9611 17024 9611 17025 9621 17025 9623 17025 9611 17026 9623 17026 9634 17026 9634 17027 9623 17027 9626 17027 9634 17028 9626 17028 9618 17028 9618 13681 9626 13681 9625 13681 9618 17029 9625 17029 9616 17029 9630 17030 9632 17030 9636 17030 9636 13683 9632 13683 9633 13683 9636 13684 9633 13684 9637 13684 9637 13685 9633 13685 9614 13685 9637 13686 9614 13686 9638 13686 9638 13687 9614 13687 9613 13687 9638 17031 9613 17031 9639 17031 9582 17032 9560 17032 9640 17032 9640 17033 9560 17033 9607 17033 9377 17034 9641 17034 9642 17034 9643 17035 9644 17035 9577 17035 9377 10912 9642 10912 9378 10912 9378 17036 9642 17036 9606 17036 9378 17037 9606 17037 9379 17037 9577 17038 9576 17038 9643 17038 9643 17039 9576 17039 9550 17039 9643 17040 9550 17040 9640 17040 9640 17041 9550 17041 9552 17041 9640 17042 9552 17042 9582 17042 9377 10920 9644 10920 9641 10920 9641 17043 9644 17043 9643 17043 9641 17044 9643 17044 9642 17044 9642 17045 9643 17045 9640 17045 9642 17046 9640 17046 9606 17046 9606 17047 9640 17047 9607 17047 9645 17048 9646 17048 9413 17048 9413 17049 9646 17049 9647 17049 9413 17050 9647 17050 9408 17050 9645 17051 9413 17051 9648 17051 9648 17052 9413 17052 9332 17052 9648 17053 9332 17053 9335 17053 9598 17054 9591 17054 9595 17054 9595 17055 9591 17055 9332 17055 9595 17056 9332 17056 9528 17056 9528 17057 9332 17057 9413 17057 9314 17058 9649 17058 9327 17058 9327 17059 9649 17059 9650 17059 9327 13719 9650 13719 9325 13719 9325 17060 9650 17060 9648 17060 9325 17061 9648 17061 9322 17061 9322 17062 9648 17062 9335 17062 9650 17063 9649 17063 9651 17063 9651 17064 9649 17064 9652 17064 9311 17065 9653 17065 9654 17065 9311 17066 9654 17066 9312 17066 9312 17067 9654 17067 9652 17067 9312 17068 9652 17068 9314 17068 9314 17069 9652 17069 9649 17069 9319 17070 9321 17070 9331 17070 9604 17071 9603 17071 9655 17071 9500 17072 9656 17072 9498 17072 9498 17073 9656 17073 9657 17073 9657 17074 9658 17074 9498 17074 9498 17075 9658 17075 9655 17075 9498 17076 9655 17076 9572 17076 9319 17077 9655 17077 9317 17077 9317 10877 9655 10877 9653 10877 9317 17078 9653 17078 9311 17078 9319 17079 9331 17079 9655 17079 9655 17080 9331 17080 9330 17080 9655 17081 9330 17081 9604 17081 9603 17082 9605 17082 9655 17082 9655 17083 9605 17083 9608 17083 9655 17084 9608 17084 9572 17084 9659 17085 9660 17085 9661 17085 9662 17086 9663 17086 9664 17086 9664 17087 9665 17087 9662 17087 9662 17088 9665 17088 9666 17088 9662 17089 9666 17089 9667 17089 9666 17090 9668 17090 9667 17090 9667 17091 9668 17091 9669 17091 9667 17092 9669 17092 9670 17092 9670 17093 9669 17093 9659 17093 9659 17094 9661 17094 9670 17094 9670 17095 9661 17095 9671 17095 9670 17096 9671 17096 9672 17096 9672 17097 9671 17097 9673 17097 9672 17098 9673 17098 9674 17098 9675 13754 9664 13754 9663 13754 9676 17099 9677 17099 9678 17099 9679 10846 9677 10846 9680 10846 9680 17100 9677 17100 9676 17100 9680 13758 9676 13758 9681 13758 9681 17101 9676 17101 9682 17101 9675 17102 9663 17102 9678 17102 9678 17103 9663 17103 9683 17103 9678 17104 9683 17104 9676 17104 9676 17105 9683 17105 9684 17105 9676 13764 9684 13764 9682 13764 9671 17106 9661 17106 9685 17106 9685 632 9661 632 9660 632 9685 17107 9660 17107 9659 17107 9686 17108 9687 17108 9688 17108 9688 17109 9687 17109 9689 17109 9690 632 9691 632 9685 632 9685 17110 9691 17110 9692 17110 9685 17111 9692 17111 9693 17111 9685 17112 9679 17112 9694 17112 9687 17113 9685 17113 9695 17113 9696 632 9690 632 9697 632 9697 17114 9690 17114 9685 17114 9697 632 9685 632 9698 632 9698 632 9685 632 9687 632 9666 632 9685 632 9668 632 9668 17115 9685 17115 9659 17115 9668 17116 9659 17116 9669 17116 9699 17117 9700 17117 9687 17117 9687 13777 9700 13777 9701 13777 9687 17118 9701 17118 9689 17118 9666 17119 9665 17119 9685 17119 9685 632 9665 632 9664 632 9685 632 9664 632 9675 632 9702 632 9703 632 9694 632 9694 17120 9703 17120 9704 17120 9694 17121 9704 17121 9685 17121 9695 17122 9705 17122 9687 17122 9687 17123 9705 17123 9706 17123 9687 17124 9706 17124 9699 17124 9693 17125 9707 17125 9685 17125 9685 17126 9707 17126 9673 17126 9685 17127 9673 17127 9671 17127 9675 632 9678 632 9685 632 9685 17128 9678 17128 9677 17128 9685 17129 9677 17129 9679 17129 9708 13790 9709 13790 9710 13790 9710 17130 9709 17130 9711 17130 9710 17131 9711 17131 9712 17131 9585 17132 9544 17132 9712 17132 9712 17133 9711 17133 9585 17133 9585 17134 9711 17134 9364 17134 9585 17135 9364 17135 9367 17135 9708 13797 9713 13797 9709 13797 9709 13798 9713 13798 9371 13798 9709 13799 9371 13799 9711 13799 9711 17136 9371 17136 9366 17136 9711 17137 9366 17137 9364 17137 9380 13802 9374 13802 9714 13802 9714 17138 9374 17138 9373 17138 9714 17139 9373 17139 9713 17139 9713 17140 9373 17140 9372 17140 9713 17141 9372 17141 9371 17141 9380 17142 9714 17142 9381 17142 9381 17143 9714 17143 9715 17143 9381 17144 9715 17144 9382 17144 9382 17145 9715 17145 9716 17145 9382 17146 9716 17146 9369 17146 9369 17147 9716 17147 9717 17147 9369 17148 9717 17148 9370 17148 9370 17149 9717 17149 9718 17149 9370 17150 9718 17150 9368 17150 9375 17151 9719 17151 9376 17151 9376 17152 9719 17152 9644 17152 9376 17153 9644 17153 9377 17153 9577 17154 9644 17154 9720 17154 9720 17155 9644 17155 9719 17155 9720 17156 9719 17156 9718 17156 9718 17157 9719 17157 9375 17157 9718 10806 9375 10806 9368 10806 9716 17158 9721 17158 9717 17158 9717 17159 9721 17159 9722 17159 9717 17160 9722 17160 9718 17160 9718 13824 9722 13824 9723 13824 9718 17161 9723 17161 9720 17161 9708 17162 9724 17162 9713 17162 9713 17163 9724 17163 9725 17163 9713 10814 9725 10814 9714 10814 9714 17164 9725 17164 9726 17164 9714 17165 9726 17165 9715 17165 9715 17166 9726 17166 9727 17166 9715 17167 9727 17167 9716 17167 9716 17168 9727 17168 9728 17168 9716 17169 9728 17169 9721 17169 9729 17170 9730 17170 9731 17170 9732 13836 9733 13836 9730 13836 9731 17171 9734 17171 9729 17171 9729 17172 9734 17172 9735 17172 9729 17173 9735 17173 9736 17173 9408 13840 9647 13840 9737 13840 9737 13841 9647 13841 9738 13841 9737 13842 9738 13842 9739 13842 9739 13843 9738 13843 9740 13843 9739 17174 9740 17174 9741 17174 9741 17175 9740 17175 9742 17175 9741 17176 9742 17176 9743 17176 9743 13847 9742 13847 9736 13847 9743 13848 9736 13848 9744 13848 9744 17177 9736 17177 9735 17177 9730 17178 9729 17178 9732 17178 9732 17179 9729 17179 9736 17179 9732 17180 9736 17180 9745 17180 9745 17181 9736 17181 9742 17181 9745 17182 9742 17182 9746 17182 9746 13854 9742 13854 9740 13854 9746 17183 9740 17183 9747 17183 9747 17184 9740 17184 9738 17184 9747 13857 9738 13857 9748 13857 9748 13858 9738 13858 9647 13858 9748 13859 9647 13859 9646 13859 9417 17185 9749 17185 9750 17185 9417 17186 9751 17186 9752 17186 9409 17187 9408 17187 9737 17187 9753 13863 9754 13863 9755 13863 9756 13864 144 13864 9757 13864 9409 17188 9737 17188 9420 17188 9750 13866 9758 13866 9759 13866 9417 13867 9750 13867 9418 13867 9418 13868 9750 13868 9759 13868 9418 17189 9759 17189 9419 17189 9760 17190 9761 17190 9762 17190 9762 13871 9761 13871 9756 13871 9762 17191 9756 17191 9763 17191 9763 13873 9756 13873 9757 13873 9763 17192 9757 17192 9764 17192 9764 17193 9757 17193 9765 17193 9417 17194 9752 17194 9749 17194 9749 17195 9752 17195 9766 17195 9749 17196 9766 17196 9750 17196 9743 13879 9767 13879 9741 13879 9741 17197 9767 17197 9768 17197 9741 17198 9768 17198 9739 17198 9739 17199 9768 17199 9769 17199 9739 13883 9769 13883 9737 13883 9737 13884 9769 13884 9770 13884 9737 13885 9770 13885 9420 13885 9755 17200 9771 17200 9753 17200 9753 17201 9771 17201 9760 17201 9753 17202 9760 17202 9772 17202 9772 17203 9760 17203 9762 17203 9772 13890 9762 13890 9773 13890 9773 17204 9762 17204 9763 17204 9773 17205 9763 17205 9766 17205 9766 17206 9763 17206 9764 17206 9766 17207 9764 17207 9750 17207 9750 17208 9764 17208 9765 17208 9750 17209 9765 17209 9758 17209 9731 13897 9774 13897 9734 13897 9734 17210 9774 17210 9755 17210 9734 17211 9755 17211 9735 17211 9735 17212 9755 17212 9754 17212 9735 17213 9754 17213 9744 17213 9744 13902 9754 13902 9753 13902 9744 13903 9753 13903 9743 13903 9743 13904 9753 13904 9772 13904 9743 17214 9772 17214 9767 17214 9767 13906 9772 13906 9773 13906 9767 17215 9773 17215 9768 17215 9768 17216 9773 17216 9766 17216 9768 13909 9766 13909 9769 13909 9769 17217 9766 17217 9752 17217 9769 13911 9752 13911 9770 13911 9770 13912 9752 13912 9751 13912 9770 13913 9751 13913 9420 13913 9420 17218 9751 17218 9417 17218 9775 17219 9776 17219 9777 17219 9778 17220 9779 17220 161 17220 9780 17221 9781 17221 9782 17221 9783 17222 9784 17222 9785 17222 9785 17223 9784 17223 9786 17223 9785 13920 9786 13920 9787 13920 9787 17224 9786 17224 9780 17224 9787 17225 9780 17225 9788 17225 9788 17226 9780 17226 9782 17226 9788 17227 9782 17227 9789 17227 9790 17228 9791 17228 9783 17228 9783 17229 9791 17229 9792 17229 9783 17230 9792 17230 9784 17230 9778 17231 9790 17231 9779 17231 9779 17232 9790 17232 9783 17232 9779 17233 9783 17233 9793 17233 9793 17234 9783 17234 9775 17234 9776 17235 9794 17235 9777 17235 9777 13933 9794 13933 9795 13933 9777 17236 9795 17236 9796 17236 9796 13935 9795 13935 9797 13935 9798 13936 9799 13936 9797 13936 9797 17237 9799 17237 9800 17237 9797 13938 9800 13938 9796 13938 9797 13939 9801 13939 9798 13939 9798 13940 9801 13940 9802 13940 9798 13941 9802 13941 9803 13941 9619 17238 9803 17238 9620 17238 9620 17239 9803 17239 9802 17239 9620 17240 9802 17240 9635 17240 9635 17241 9802 17241 9615 17241 9804 17242 9639 17242 9805 17242 9805 17243 9639 17243 9613 17243 9806 13948 9807 13948 9808 13948 9808 17244 9807 17244 9809 17244 9808 17245 9809 17245 9810 17245 9810 17246 9809 17246 9811 17246 9810 17247 9811 17247 9812 17247 9812 13953 9811 13953 9813 13953 9812 13954 9813 13954 9814 13954 9612 17248 9615 17248 9814 17248 9814 17249 9615 17249 9802 17249 9814 13957 9802 13957 9812 13957 9812 13958 9802 13958 9801 13958 9812 17250 9801 17250 9810 17250 9810 17251 9801 17251 9797 17251 9810 17252 9797 17252 9808 17252 9808 13962 9797 13962 9795 13962 9808 17253 9795 17253 9806 17253 9806 17254 9795 17254 9794 17254 9775 13965 9783 13965 9776 13965 9776 17255 9783 17255 9785 17255 9776 13967 9785 13967 9794 13967 9794 13968 9785 13968 9787 13968 9794 13969 9787 13969 9806 13969 9806 17256 9787 17256 9788 17256 9806 17257 9788 17257 9807 17257 9807 17258 9788 17258 9789 17258 9807 17259 9789 17259 9809 17259 9809 13974 9789 13974 9815 13974 9809 17260 9815 17260 9811 17260 9811 17261 9815 17261 9804 17261 9811 17262 9804 17262 9813 17262 9813 17263 9804 17263 9805 17263 9813 17264 9805 17264 9814 17264 9814 17265 9805 17265 9613 17265 9814 17266 9613 17266 9612 17266 9789 17267 9782 17267 9638 17267 9638 17268 9782 17268 9816 17268 9638 13984 9816 13984 9637 13984 9789 17269 9638 17269 9815 17269 9815 17270 9638 17270 9639 17270 9815 17271 9639 17271 9804 17271 9630 17272 9817 17272 9818 17272 9818 17273 9817 17273 9819 17273 9818 17274 9819 17274 9820 17274 9820 17275 9819 17275 9821 17275 9821 17276 9819 17276 9822 17276 9821 17277 9822 17277 9823 17277 9824 17278 9823 17278 9825 17278 9825 17279 9823 17279 9822 17279 9825 17280 9822 17280 9826 17280 9826 17281 9822 17281 9827 17281 9828 17282 9829 17282 9830 17282 9830 13999 9829 13999 9816 13999 9830 14000 9816 14000 9781 14000 9781 14001 9816 14001 9782 14001 9630 17283 9636 17283 9817 17283 9817 17284 9636 17284 9637 17284 9817 17285 9637 17285 9819 17285 9819 14006 9637 14006 9816 14006 9819 17286 9816 17286 9822 17286 9822 17287 9816 17287 9829 17287 9822 17288 9829 17288 9827 17288 9827 17289 9829 17289 9828 17289 9827 17290 9828 17290 9831 17290 9832 17291 9833 17291 9834 17291 9835 17292 9836 17292 9837 17292 9838 17293 9839 17293 9840 17293 9840 17294 9839 17294 9841 17294 9840 17295 9841 17295 9842 17295 9842 17296 9841 17296 9843 17296 9843 17297 9841 17297 9844 17297 9843 17298 9844 17298 9845 17298 9846 17299 9847 17299 9848 17299 9835 17300 9837 17300 9849 17300 9849 17301 9837 17301 9850 17301 9849 17302 9850 17302 9851 17302 9852 17303 9853 17303 9854 17303 9854 17304 9853 17304 9855 17304 9854 17305 9855 17305 9856 17305 9838 17306 9857 17306 9839 17306 9839 17307 9857 17307 9858 17307 9839 17308 9858 17308 9841 17308 9841 17309 9858 17309 9859 17309 9841 17310 9859 17310 9844 17310 9860 17311 9845 17311 9861 17311 9861 17312 9845 17312 9844 17312 9861 10574 9844 10574 9862 10574 9862 17313 9844 17313 9859 17313 9862 17314 9859 17314 9847 17314 9847 17315 9859 17315 9863 17315 9847 17316 9863 17316 9848 17316 9848 17317 9863 17317 9864 17317 9857 17318 9834 17318 9858 17318 9858 17319 9834 17319 9833 17319 9858 17320 9833 17320 9852 17320 9852 17321 9833 17321 9832 17321 9852 10584 9832 10584 9853 10584 9853 17322 9832 17322 9865 17322 9853 17323 9865 17323 9855 17323 9854 17324 9851 17324 9852 17324 9852 17325 9851 17325 9850 17325 9852 17326 9850 17326 9858 17326 9858 17327 9850 17327 9837 17327 9858 17328 9837 17328 9859 17328 9859 17329 9837 17329 9836 17329 9859 17330 9836 17330 9863 17330 9863 17331 9836 17331 9835 17331 9863 17332 9835 17332 9864 17332 9866 14054 9867 14054 9868 14054 9869 17333 9867 17333 9870 17333 9870 17334 9867 17334 9866 17334 9870 17335 9866 17335 9871 17335 9871 17336 9866 17336 9872 17336 9871 17337 9872 17337 9873 17337 9873 17338 9872 17338 9874 17338 9873 17339 9874 17339 9875 17339 9875 17340 9874 17340 9876 17340 9876 17341 9874 17341 9877 17341 9876 14063 9877 14063 9878 14063 9879 17342 9645 17342 9648 17342 9646 14065 9645 14065 9748 14065 9748 14066 9645 14066 9879 14066 9748 17343 9879 17343 9880 17343 9733 14068 9732 14068 9881 14068 9881 17344 9732 17344 9745 17344 9881 17345 9745 17345 9882 17345 9882 17346 9745 17346 9746 17346 9882 17347 9746 17347 9880 17347 9880 17348 9746 17348 9747 17348 9880 17349 9747 17349 9748 17349 9650 17350 9878 17350 9648 17350 9648 17351 9878 17351 9877 17351 9648 17352 9877 17352 9879 17352 9879 17353 9877 17353 9874 17353 9879 17354 9874 17354 9880 17354 9880 17355 9874 17355 9872 17355 9880 14081 9872 14081 9882 14081 9882 17356 9872 17356 9866 17356 9882 14083 9866 14083 9881 14083 9881 14084 9866 14084 9868 14084 9881 14085 9868 14085 9733 14085 9883 17357 9884 17357 9885 17357 9886 17358 9654 17358 9653 17358 9887 17359 9651 17359 9652 17359 9888 14087 9884 14087 9889 14087 9889 17360 9884 17360 9883 17360 9889 17361 9883 17361 9890 17361 9890 17362 9883 17362 9891 17362 9890 17363 9891 17363 9892 17363 9892 17364 9891 17364 9893 17364 9892 17365 9893 17365 9894 17365 9894 17366 9893 17366 9886 17366 9894 17367 9886 17367 9895 17367 9895 10497 9886 10497 9653 10497 9869 17368 9870 17368 9885 17368 9885 17369 9870 17369 9896 17369 9885 17370 9896 17370 9883 17370 9883 17371 9896 17371 9897 17371 9883 17372 9897 17372 9891 17372 9891 17373 9897 17373 9898 17373 9891 17374 9898 17374 9893 17374 9893 17375 9898 17375 9887 17375 9893 17376 9887 17376 9886 17376 9886 10507 9887 10507 9652 10507 9886 17377 9652 17377 9654 17377 9650 17378 9651 17378 9878 17378 9878 17379 9651 17379 9887 17379 9878 17380 9887 17380 9876 17380 9876 17381 9887 17381 9898 17381 9876 17382 9898 17382 9875 17382 9875 17383 9898 17383 9897 17383 9875 17384 9897 17384 9873 17384 9873 17385 9897 17385 9896 17385 9873 17386 9896 17386 9871 17386 9871 17387 9896 17387 9870 17387 9899 17388 9900 17388 9901 17388 9901 17389 9900 17389 9902 17389 9902 14107 9900 14107 9903 14107 9903 17390 9900 17390 9904 17390 9903 17391 9904 17391 9905 17391 9905 17392 9904 17392 9906 17392 9905 17393 9906 17393 9907 17393 9908 17394 9655 17394 9658 17394 9895 17395 9653 17395 9655 17395 9655 14114 9908 14114 9895 14114 9895 17396 9908 17396 9909 17396 9895 17397 9909 17397 9894 17397 9894 17398 9909 17398 9892 17398 9892 17399 9909 17399 9910 17399 9892 17400 9910 17400 9890 17400 9890 17401 9910 17401 9911 17401 9890 10469 9911 10469 9889 10469 9901 17402 9912 17402 9899 17402 9899 17403 9912 17403 9913 17403 9899 17404 9913 17404 9914 17404 9888 17405 9889 17405 9914 17405 9914 17406 9889 17406 9911 17406 9914 10475 9911 10475 9899 10475 9899 17407 9911 17407 9910 17407 9899 17408 9910 17408 9900 17408 9900 17409 9910 17409 9909 17409 9900 17410 9909 17410 9904 17410 9904 17411 9909 17411 9908 17411 9904 17412 9908 17412 9906 17412 9906 17413 9908 17413 9658 17413 9906 17414 9658 17414 9907 17414 9907 17415 9658 17415 9657 17415 9915 17416 9705 17416 9695 17416 9705 17417 9915 17417 9706 17417 9706 17418 9915 17418 9916 17418 9706 17419 9916 17419 9699 17419 9699 17420 9916 17420 9917 17420 9699 17421 9917 17421 9700 17421 9700 17422 9917 17422 9918 17422 9700 17423 9918 17423 9701 17423 9687 17424 9686 17424 9919 17424 9919 10406 9686 10406 9688 10406 9919 17425 9688 17425 9918 17425 9918 17426 9688 17426 9689 17426 9918 17427 9689 17427 9701 17427 9687 17428 9919 17428 9698 17428 9698 17429 9919 17429 9920 17429 9698 17430 9920 17430 9697 17430 9697 17431 9920 17431 9921 17431 9697 17432 9921 17432 9696 17432 9696 17433 9921 17433 9922 17433 9696 17434 9922 17434 9690 17434 9923 17435 9924 17435 9925 17435 9691 17436 9690 17436 9925 17436 9925 17437 9690 17437 9922 17437 9925 17438 9922 17438 9923 17438 9923 17439 9922 17439 9921 17439 9923 17440 9921 17440 9926 17440 9926 17441 9921 17441 9920 17441 9926 17442 9920 17442 9927 17442 9927 17443 9920 17443 9919 17443 9927 17444 9919 17444 9928 17444 9928 17445 9919 17445 9918 17445 9928 17446 9918 17446 9929 17446 9929 17447 9918 17447 9917 17447 9929 17448 9917 17448 9930 17448 9930 17449 9917 17449 9916 17449 9930 17450 9916 17450 9931 17450 9931 17451 9916 17451 9915 17451 9931 17452 9915 17452 9932 17452 9932 17453 9915 17453 9933 17453 9932 17454 9933 17454 9934 17454 9934 17455 9933 17455 9935 17455 9934 14169 9935 14169 9936 14169 9936 14170 9935 14170 9937 14170 9936 17456 9937 17456 9938 17456 9694 17457 9679 17457 9680 17457 9681 17458 9938 17458 9680 17458 9680 14174 9938 14174 9937 14174 9680 14175 9937 14175 9694 14175 9694 17459 9937 17459 9935 17459 9694 17460 9935 17460 9702 17460 9702 17461 9935 17461 9933 17461 9702 17462 9933 17462 9703 17462 9703 17463 9933 17463 9915 17463 9703 17464 9915 17464 9704 17464 9704 17465 9915 17465 9695 17465 9704 17466 9695 17466 9685 17466 9674 17467 9939 17467 9940 17467 9940 17468 9941 17468 9942 17468 9942 17469 9941 17469 9925 17469 9942 17470 9925 17470 9924 17470 9674 17471 9673 17471 9939 17471 9939 17472 9673 17472 9707 17472 9939 17473 9707 17473 9693 17473 9940 10392 9939 10392 9941 10392 9941 17474 9939 17474 9693 17474 9941 17475 9693 17475 9925 17475 9925 17476 9693 17476 9692 17476 9925 17477 9692 17477 9691 17477 9674 17478 9943 17478 9672 17478 9672 17479 9943 17479 9944 17479 9672 17480 9944 17480 9670 17480 9670 17481 9944 17481 9945 17481 9670 17482 9945 17482 9667 17482 9667 17483 9945 17483 9946 17483 9667 17484 9946 17484 9662 17484 9662 17485 9946 17485 9947 17485 9662 17486 9947 17486 9663 17486 9663 17487 9947 17487 9948 17487 9943 17488 6662 17488 9944 17488 9944 17489 6662 17489 6661 17489 9944 17490 6661 17490 9945 17490 9945 17491 6661 17491 6715 17491 9945 17492 6715 17492 9946 17492 9946 14208 6715 14208 6714 14208 9946 17493 6714 17493 9947 17493 9947 17494 6714 17494 6713 17494 9947 17495 6713 17495 9948 17495 9948 17496 6713 17496 6712 17496 9949 17497 9681 17497 9682 17497 9681 14215 9949 14215 9950 14215 9951 17498 9952 17498 9953 17498 9953 17499 9952 17499 9948 17499 9953 17500 9948 17500 6712 17500 9663 17501 9948 17501 9683 17501 9683 17502 9948 17502 9952 17502 9683 17503 9952 17503 9684 17503 9684 14222 9952 14222 9951 14222 9684 17504 9951 17504 9682 17504 9682 17505 9951 17505 9954 17505 9682 17506 9954 17506 9949 17506 9725 17507 9955 17507 9956 17507 9957 17508 9958 17508 9959 17508 9721 17509 9960 17509 9722 17509 9961 17510 9577 17510 9720 17510 9962 17511 9963 17511 9961 17511 9961 17512 9963 17512 9964 17512 9964 17513 9482 17513 9961 17513 9961 17514 9482 17514 9579 17514 9961 17515 9579 17515 9577 17515 9720 17516 9723 17516 9961 17516 9961 17517 9723 17517 9965 17517 9961 17518 9965 17518 9962 17518 9962 17519 9965 17519 9966 17519 9962 17520 9966 17520 9967 17520 9857 17521 9838 17521 9968 17521 9865 17522 9832 17522 9969 17522 9969 17523 9832 17523 9834 17523 9969 17524 9834 17524 9857 17524 9970 17525 9971 17525 9972 17525 9972 17526 9971 17526 9856 17526 9972 17527 9856 17527 9969 17527 9969 17528 9856 17528 9855 17528 9969 17529 9855 17529 9865 17529 9857 17530 9968 17530 9969 17530 9969 17531 9968 17531 9967 17531 9969 17532 9967 17532 9972 17532 9972 17533 9967 17533 9966 17533 9972 17534 9966 17534 9970 17534 9970 17535 9966 17535 9965 17535 9970 17536 9965 17536 9973 17536 9973 17537 9965 17537 9974 17537 9973 17538 9974 17538 9975 17538 9955 17539 9976 17539 9956 17539 9956 17540 9976 17540 9977 17540 9956 17541 9977 17541 9978 17541 9979 17542 9980 17542 9978 17542 9978 17543 9980 17543 9981 17543 9978 17544 9981 17544 9956 17544 9956 17545 9981 17545 9982 17545 9956 17546 9982 17546 9983 17546 9983 17547 9982 17547 9984 17547 9983 17548 9984 17548 9985 17548 9957 17549 9959 17549 9986 17549 9986 17550 9959 17550 9987 17550 9986 14264 9987 14264 9988 14264 9628 17551 9629 17551 9989 17551 9989 17552 9629 17552 9990 17552 9989 17553 9990 17553 9991 17553 9991 17554 9990 17554 9992 17554 9616 17555 9625 17555 9989 17555 9989 14270 9625 14270 9627 14270 9989 17556 9627 17556 9628 17556 9993 14272 9619 14272 9617 14272 9988 17557 9987 17557 9992 17557 9992 17558 9987 17558 9994 17558 9992 17559 9994 17559 9991 17559 9991 17560 9994 17560 9993 17560 9991 14277 9993 14277 9989 14277 9989 17561 9993 17561 9617 17561 9989 17562 9617 17562 9616 17562 9449 17563 9995 17563 9996 17563 9995 14281 9997 14281 9996 14281 9996 14282 9997 14282 9998 14282 9996 17564 9998 17564 9987 17564 9987 17565 9998 17565 9999 17565 9987 17566 9999 17566 9994 17566 9994 17567 9999 17567 10000 17567 9994 17568 10000 17568 9993 17568 9996 17569 9710 17569 9712 17569 9449 17570 9996 17570 9517 17570 9517 14290 9996 14290 9712 14290 9517 17571 9712 17571 9544 17571 9710 17572 9996 17572 9708 17572 9708 17573 9996 17573 9987 17573 9708 17574 9987 17574 9724 17574 9724 17575 9987 17575 9959 17575 9724 17576 9959 17576 9725 17576 9725 17577 9959 17577 9958 17577 9725 17578 9958 17578 9955 17578 9955 17579 9958 17579 10001 17579 9955 17580 10001 17580 9976 17580 9960 17581 9721 17581 9985 17581 9985 17582 9721 17582 9728 17582 9985 17583 9728 17583 9983 17583 9983 17584 9728 17584 9727 17584 9983 14304 9727 14304 9956 14304 9956 17585 9727 17585 9726 17585 9956 17586 9726 17586 9725 17586 9984 17587 9975 17587 9985 17587 9985 17588 9975 17588 9974 17588 9985 17589 9974 17589 9960 17589 9960 17590 9974 17590 9965 17590 9960 17591 9965 17591 9722 17591 9722 17592 9965 17592 9723 17592 10002 17593 9830 17593 9781 17593 10003 17594 9828 17594 9830 17594 10003 17595 10004 17595 9828 17595 9828 17596 10004 17596 10005 17596 9828 17597 10005 17597 9831 17597 9831 17598 10005 17598 10006 17598 10007 14319 10008 14319 9784 14319 9784 17599 9792 17599 10007 17599 10007 17600 9792 17600 9791 17600 10007 17601 9791 17601 10009 17601 10009 17602 9791 17602 9790 17602 10009 17603 9790 17603 9778 17603 10010 17604 10011 17604 9786 17604 9786 14326 10011 14326 9780 14326 10003 14327 10012 14327 10004 14327 10004 17605 10012 17605 10013 17605 10004 17606 10013 17606 10005 17606 10005 17607 10013 17607 10014 17607 10005 17608 10014 17608 10006 17608 10015 17609 10016 17609 10017 17609 9786 17610 9784 17610 10010 17610 10010 17611 9784 17611 10008 17611 10010 17612 10008 17612 10018 17612 10018 17613 10008 17613 10007 17613 10018 17614 10007 17614 10019 17614 10019 17615 10007 17615 10009 17615 10019 17616 10009 17616 10020 17616 10020 17617 10009 17617 10021 17617 10020 17618 10021 17618 151 17618 9778 17619 161 17619 10009 17619 10009 17620 161 17620 153 17620 10009 17621 153 17621 10021 17621 10021 17622 153 17622 152 17622 10021 14346 152 14346 151 14346 9830 17623 10002 17623 10003 17623 10003 17624 10002 17624 10022 17624 10003 14349 10022 14349 10012 14349 10012 14350 10022 14350 10017 14350 10012 17625 10017 17625 10013 17625 10013 17626 10017 17626 10016 17626 10013 17627 10016 17627 10014 17627 151 17628 10023 17628 10020 17628 10020 17629 10023 17629 10024 17629 10020 17630 10024 17630 10019 17630 10019 17631 10024 17631 10015 17631 10019 17632 10015 17632 10018 17632 10018 17633 10015 17633 10017 17633 10018 17634 10017 17634 10010 17634 10010 17635 10017 17635 10022 17635 10010 17636 10022 17636 10011 17636 10011 17637 10022 17637 10002 17637 10011 17638 10002 17638 9780 17638 9780 17639 10002 17639 9781 17639 9755 14366 9774 14366 10025 14366 9730 14367 9733 14367 10026 14367 10025 17640 10027 17640 145 17640 10026 17641 10028 17641 10025 17641 10025 17642 10028 17642 10029 17642 10025 17643 10029 17643 10027 17643 10025 14372 9774 14372 10026 14372 10026 14373 9774 14373 9731 14373 10026 14374 9731 14374 9730 14374 145 14375 144 14375 10025 14375 10025 14376 144 14376 9756 14376 10025 14377 9756 14377 9761 14377 9761 17644 9760 17644 10025 17644 10025 17645 9760 17645 9771 17645 10025 17646 9771 17646 9755 17646 9415 14381 9414 14381 9437 14381 9437 14382 9414 14382 10030 14382 9437 17647 10030 17647 9436 17647 144 14384 143 14384 9757 14384 9757 14385 143 14385 10031 14385 9757 17648 10031 17648 10032 17648 9759 14387 9758 14387 10032 14387 10032 17649 9758 17649 9765 17649 10032 14389 9765 14389 9757 14389 143 17650 9429 17650 10031 17650 10031 17651 9429 17651 9436 17651 10031 17652 9436 17652 10032 17652 10032 17653 9436 17653 10030 17653 10032 14394 10030 14394 9759 14394 9759 14395 10030 14395 9414 14395 9759 17654 9414 17654 9419 17654 10033 14397 155 14397 157 14397 10034 17655 9997 17655 9995 17655 10035 17656 10036 17656 9454 17656 9454 17657 10036 17657 9456 17657 10037 17658 9451 17658 10036 17658 10036 17659 9451 17659 9457 17659 10036 17660 9457 17660 9456 17660 9449 17661 9448 17661 9995 17661 9995 17662 9448 17662 9447 17662 9995 17663 9447 17663 10034 17663 10034 17664 9447 17664 9446 17664 10034 17665 9446 17665 10038 17665 10038 17666 9446 17666 9445 17666 10038 17667 9445 17667 10037 17667 10037 17668 9445 17668 9452 17668 10037 17669 9452 17669 9451 17669 10039 17670 9993 17670 10000 17670 9619 17671 9993 17671 9803 17671 9803 17672 9993 17672 10039 17672 9803 17673 10039 17673 9798 17673 9798 14417 10039 14417 10040 14417 10041 14418 9800 14418 10040 14418 10040 17674 9800 17674 9799 17674 10040 14420 9799 14420 9798 14420 9779 17675 9793 17675 10042 17675 10042 17676 9793 17676 9775 17676 10042 17677 9775 17677 10043 17677 10043 14424 9775 14424 9777 14424 10043 17678 9777 17678 10041 17678 10041 17679 9777 17679 9796 17679 10041 14427 9796 14427 9800 14427 10044 14428 163 14428 162 14428 163 14429 10044 14429 157 14429 9454 17680 160 17680 10035 17680 10035 17681 160 17681 154 17681 10035 17682 154 17682 155 17682 155 14433 10033 14433 10035 14433 10035 17683 10033 17683 10045 17683 10035 14435 10045 14435 10036 14435 10036 14436 10045 14436 10046 14436 10036 14437 10046 14437 10037 14437 10037 14438 10046 14438 10047 14438 10037 17684 10047 17684 10038 17684 10038 17685 10047 17685 10048 17685 10038 14441 10048 14441 10034 14441 10034 17686 10048 17686 9998 17686 10034 14443 9998 14443 9997 14443 157 14444 10044 14444 10033 14444 10033 14445 10044 14445 10049 14445 10033 14446 10049 14446 10045 14446 10045 14447 10049 14447 10050 14447 10045 14448 10050 14448 10046 14448 10046 14449 10050 14449 10051 14449 10046 14450 10051 14450 10047 14450 10047 14451 10051 14451 10052 14451 10047 14452 10052 14452 10048 14452 10048 17687 10052 17687 9999 17687 10048 17688 9999 17688 9998 17688 161 17689 9779 17689 162 17689 162 17690 9779 17690 10042 17690 162 14457 10042 14457 10044 14457 10044 17691 10042 17691 10043 17691 10044 14459 10043 14459 10049 14459 10049 14460 10043 14460 10041 14460 10049 14461 10041 14461 10050 14461 10050 14462 10041 14462 10040 14462 10050 14463 10040 14463 10051 14463 10051 14464 10040 14464 10039 14464 10051 14465 10039 14465 10052 14465 10052 17692 10039 17692 10000 17692 10052 17693 10000 17693 9999 17693 10053 17694 10054 17694 10055 17694 9861 17695 10056 17695 9860 17695 9860 17696 10056 17696 10057 17696 9861 17697 10058 17697 10059 17697 10060 17698 10056 17698 10061 17698 10061 17699 10056 17699 9861 17699 10061 17700 9861 17700 10062 17700 10062 17701 9861 17701 10059 17701 10063 17702 10064 17702 10065 17702 10065 17703 10066 17703 10063 17703 10063 17704 10066 17704 10067 17704 10063 17705 10067 17705 10058 17705 10058 17706 10067 17706 10068 17706 10058 17707 10068 17707 10059 17707 10053 17708 10055 17708 10069 17708 10069 17709 10055 17709 10070 17709 10069 17710 10070 17710 10071 17710 10071 17711 10070 17711 10072 17711 10071 17712 10072 17712 10073 17712 9847 17713 9846 17713 10074 17713 10074 17714 9846 17714 10075 17714 10074 17715 10075 17715 10073 17715 10073 17716 10072 17716 10074 17716 10074 17717 10072 17717 9862 17717 10074 17718 9862 17718 9847 17718 9861 17719 9862 17719 10058 17719 10058 17720 9862 17720 10072 17720 10058 17721 10072 17721 10063 17721 10063 17722 10072 17722 10070 17722 10063 17723 10070 17723 10064 17723 10064 17724 10070 17724 10055 17724 10076 17725 10077 17725 10078 17725 10079 17726 10080 17726 10081 17726 10082 17727 10083 17727 10084 17727 10084 17728 10083 17728 10085 17728 9842 17729 9843 17729 10086 17729 10062 17730 10059 17730 10087 17730 10088 17731 10089 17731 10061 17731 10061 17732 10089 17732 10060 17732 9845 17733 9860 17733 10090 17733 10090 17734 9860 17734 10057 17734 10090 17735 10057 17735 10091 17735 10091 17736 10057 17736 10056 17736 10091 17737 10056 17737 10092 17737 10092 17738 10056 17738 10060 17738 10092 17739 10060 17739 10093 17739 10093 17740 10060 17740 10089 17740 10094 17741 9838 17741 9840 17741 10095 17742 10096 17742 10097 17742 10097 17743 10096 17743 10094 17743 10097 17744 10094 17744 10098 17744 10098 17745 10094 17745 9840 17745 10099 17746 10100 17746 10095 17746 10095 17747 10100 17747 10101 17747 10095 17748 10101 17748 10096 17748 10078 17749 10102 17749 10103 17749 10104 17750 10105 17750 10106 17750 10106 17751 10105 17751 10107 17751 10106 17752 10107 17752 10108 17752 10108 17753 10107 17753 10102 17753 10108 17754 10102 17754 10109 17754 10109 17755 10102 17755 10078 17755 10109 17756 10078 17756 10110 17756 10110 17757 10078 17757 10111 17757 10111 17758 10078 17758 10077 17758 10111 17759 10077 17759 10112 17759 10079 17760 10081 17760 10087 17760 10103 17761 10082 17761 10078 17761 10078 17762 10082 17762 10084 17762 10078 17763 10084 17763 10076 17763 10076 17764 10084 17764 10085 17764 10076 17765 10085 17765 10099 17765 10099 17766 10085 17766 10113 17766 10099 17767 10113 17767 10100 17767 9843 17768 9845 17768 10086 17768 10086 17769 9845 17769 10090 17769 10086 17770 10090 17770 10114 17770 10114 17771 10090 17771 10091 17771 10114 17772 10091 17772 10115 17772 10115 17773 10091 17773 10092 17773 10115 17774 10092 17774 10116 17774 10116 17775 10092 17775 10093 17775 10116 17776 10093 17776 10117 17776 10117 17777 10093 17777 10089 17777 10117 17778 10089 17778 10081 17778 10081 17779 10089 17779 10088 17779 10081 17780 10088 17780 10087 17780 10087 17781 10088 17781 10061 17781 10087 17782 10061 17782 10062 17782 10080 17783 10112 17783 10081 17783 10081 17784 10112 17784 10077 17784 10081 17785 10077 17785 10117 17785 10117 17786 10077 17786 10076 17786 10117 17787 10076 17787 10116 17787 10116 17788 10076 17788 10099 17788 10116 17789 10099 17789 10115 17789 10115 17790 10099 17790 10095 17790 10115 17791 10095 17791 10114 17791 10114 17792 10095 17792 10097 17792 10114 17793 10097 17793 10086 17793 10086 17794 10097 17794 10098 17794 10086 17795 10098 17795 9842 17795 9842 17796 10098 17796 9840 17796 10118 17797 10119 17797 9500 17797 10120 17798 10121 17798 10122 17798 9502 17799 9504 17799 10123 17799 10124 17800 10125 17800 10126 17800 10126 17801 10125 17801 10127 17801 10128 17802 10129 17802 10130 17802 10130 17803 10129 17803 10131 17803 10130 17804 10131 17804 10132 17804 10133 17805 10134 17805 10135 17805 10136 17806 10137 17806 10138 17806 10134 17807 10133 17807 10138 17807 10138 17808 10133 17808 10139 17808 10138 17809 10139 17809 10136 17809 10136 17810 10139 17810 10122 17810 10136 17811 10122 17811 10140 17811 10140 17812 10122 17812 10121 17812 10140 17813 10121 17813 10141 17813 9509 17814 10141 17814 9510 17814 9510 17815 10141 17815 10121 17815 9510 17816 10121 17816 9511 17816 9511 17817 10121 17817 10120 17817 9511 17818 10120 17818 9505 17818 10129 17819 10126 17819 10131 17819 10131 17820 10126 17820 10127 17820 10131 17821 10127 17821 10132 17821 10132 17822 10127 17822 10142 17822 10132 17823 10142 17823 10143 17823 10143 17824 10142 17824 10144 17824 10144 17825 10142 17825 10145 17825 10144 17826 10145 17826 10118 17826 10118 17827 10145 17827 10146 17827 10118 17828 10146 17828 10119 17828 9500 17829 9502 17829 10118 17829 10118 17830 9502 17830 10123 17830 10118 17831 10123 17831 10144 17831 10144 17832 10123 17832 10147 17832 10144 17833 10147 17833 10143 17833 10143 17834 10147 17834 10148 17834 10143 17835 10148 17835 10132 17835 9504 17836 9505 17836 10123 17836 10123 17837 9505 17837 10120 17837 10123 17838 10120 17838 10147 17838 10147 17839 10120 17839 10122 17839 10147 17840 10122 17840 10148 17840 10148 17841 10122 17841 10139 17841 10148 17842 10139 17842 10132 17842 10132 17843 10139 17843 10133 17843 10132 17844 10133 17844 10130 17844 10130 17845 10133 17845 10135 17845 10130 17846 10135 17846 10128 17846 9923 17847 10149 17847 9924 17847 9950 17848 9938 17848 9681 17848 9868 17849 10150 17849 9733 17849 9912 17850 10151 17850 9913 17850 10152 17851 10153 17851 10154 17851 10149 17852 9923 17852 10154 17852 9733 17853 10155 17853 10026 17853 10026 17854 10155 17854 10028 17854 10152 17855 10154 17855 9912 17855 9912 17856 10154 17856 9923 17856 9912 17857 9923 17857 10151 17857 10151 17858 9923 17858 9926 17858 10151 17859 9926 17859 9913 17859 9913 17860 9926 17860 9927 17860 9913 17861 9927 17861 9914 17861 9914 17862 9927 17862 9928 17862 9914 17863 9928 17863 9888 17863 9888 17864 9928 17864 9929 17864 9888 17865 9929 17865 9884 17865 9884 17866 9929 17866 9930 17866 9884 17867 9930 17867 9885 17867 9885 14639 9930 14639 9931 14639 9885 17868 9931 17868 9869 17868 9869 17869 9931 17869 9932 17869 9869 17870 9932 17870 9867 17870 9867 17871 9932 17871 9934 17871 9867 17872 9934 17872 9868 17872 9868 14645 9934 14645 9936 14645 9868 17873 9936 17873 10150 17873 10150 17874 9936 17874 9938 17874 10150 17875 9938 17875 9733 17875 9733 17876 9938 17876 9950 17876 9733 17877 9950 17877 10155 17877 10125 17878 10124 17878 10156 17878 9912 17879 9901 17879 10157 17879 10157 17880 9901 17880 9902 17880 10157 17881 9902 17881 10158 17881 10158 17882 9902 17882 9903 17882 10158 17883 9903 17883 10159 17883 10159 17884 9903 17884 9905 17884 10159 17885 9905 17885 10160 17885 10160 17886 9905 17886 9907 17886 10160 17887 9907 17887 10161 17887 10119 17888 10146 17888 10161 17888 10161 17889 10146 17889 10145 17889 10161 17890 10145 17890 10160 17890 10160 17891 10145 17891 10142 17891 10160 17892 10142 17892 10159 17892 10159 17893 10142 17893 10127 17893 10159 17894 10127 17894 10158 17894 10158 17895 10127 17895 10125 17895 10158 17896 10125 17896 10157 17896 10157 17897 10125 17897 10156 17897 10157 17898 10156 17898 9912 17898 9500 17899 10119 17899 9656 17899 9656 17900 10119 17900 10161 17900 9656 17901 10161 17901 9657 17901 9657 17902 10161 17902 9907 17902 10162 17903 10163 17903 10164 17903 9942 17904 9924 17904 10162 17904 10162 17905 9924 17905 10149 17905 10162 17906 10149 17906 10154 17906 10162 17907 10164 17907 9942 17907 9942 17908 10164 17908 10165 17908 9942 17909 10165 17909 9940 17909 9940 17910 10165 17910 9943 17910 9940 17911 9943 17911 9674 17911 10163 17912 10166 17912 10164 17912 10164 17913 10166 17913 10167 17913 10164 9890 10167 9890 10165 9890 10165 17914 10167 17914 6662 17914 10165 17915 6662 17915 9943 17915 10001 95 9958 95 9305 95 9305 95 9958 95 9957 95 9305 95 9957 95 9986 95 9304 95 9977 95 9305 95 9305 95 9977 95 9976 95 9305 95 9976 95 10001 95 6708 17916 4392 17916 6712 17916 6712 17917 4392 17917 9953 17917 9950 17918 9949 17918 10155 17918 10155 17919 9949 17919 9954 17919 9953 17920 4392 17920 9951 17920 9951 17921 4392 17921 4394 17921 9951 17922 4394 17922 9954 17922 9954 17923 4394 17923 4395 17923 9954 17924 4395 17924 10155 17924 10155 17925 4395 17925 4419 17925 10155 17926 4419 17926 4417 17926 4417 17927 4416 17927 10155 17927 10155 17928 4416 17928 4414 17928 10155 17929 4414 17929 4412 17929 4412 17930 4411 17930 10155 17930 10155 17931 4411 17931 4409 17931 10155 17932 4409 17932 4407 17932 4407 17933 4405 17933 10155 17933 10155 17934 4405 17934 4403 17934 10155 17935 4403 17935 4464 17935 4464 17936 4463 17936 10155 17936 10155 17937 4463 17937 4461 17937 10155 17938 4461 17938 4459 17938 4459 17939 4457 17939 10155 17939 10155 17940 4457 17940 4456 17940 10155 17941 4456 17941 4454 17941 4454 17942 4452 17942 10155 17942 10155 17943 4452 17943 4450 17943 10155 17944 4450 17944 4448 17944 4448 17945 4446 17945 10155 17945 10155 17946 4446 17946 4389 17946 10155 17947 4389 17947 4423 17947 4427 17948 4429 17948 10027 17948 10027 17949 4429 17949 4431 17949 10027 17950 4431 17950 4433 17950 4433 17951 4401 17951 10027 17951 10027 17952 4401 17952 4399 17952 10027 17953 4399 17953 4397 17953 4397 17954 4444 17954 10027 17954 10027 17955 4444 17955 4443 17955 10027 17956 4443 17956 4441 17956 4441 17957 4439 17957 10027 17957 10027 17958 4439 17958 4437 17958 10027 17959 4437 17959 4436 17959 4436 17960 4421 17960 10027 17960 10027 17961 4421 17961 4387 17961 10027 17962 4387 17962 4385 17962 4427 17963 10027 17963 4425 17963 4425 17964 10027 17964 10029 17964 4425 17965 10029 17965 4423 17965 4423 17966 10029 17966 10028 17966 4423 17967 10028 17967 10155 17967 4385 17968 4383 17968 10027 17968 10027 17969 4383 17969 156 17969 10027 17970 156 17970 145 17970 10168 17971 10169 17971 10170 17971 10079 17972 10171 17972 10172 17972 10171 17973 10068 17973 10067 17973 10171 17974 10079 17974 10068 17974 10068 17975 10079 17975 10087 17975 10068 17976 10087 17976 10059 17976 10173 17977 10112 17977 10172 17977 10172 17978 10112 17978 10080 17978 10172 17979 10080 17979 10079 17979 10108 17980 10109 17980 10174 17980 10174 17981 10109 17981 10110 17981 10174 17982 10110 17982 10173 17982 10173 17983 10110 17983 10111 17983 10173 17984 10111 17984 10112 17984 10065 17985 10169 17985 10066 17985 10066 17986 10169 17986 10168 17986 10066 17987 10168 17987 10067 17987 10175 17988 10176 17988 10177 17988 10177 17989 10176 17989 10178 17989 10177 17990 10178 17990 10179 17990 10179 17991 10178 17991 10180 17991 10179 17992 10180 17992 10181 17992 10181 17993 10180 17993 10182 17993 10181 17994 10182 17994 10183 17994 10179 17995 10184 17995 10177 17995 10177 17996 10184 17996 10185 17996 10177 17997 10185 17997 10175 17997 10175 17998 10185 17998 10186 17998 10104 17999 10106 17999 10183 17999 10183 18000 10106 18000 10187 18000 10183 18001 10187 18001 10181 18001 10181 18002 10187 18002 10188 18002 10181 18003 10188 18003 10179 18003 10179 18004 10188 18004 10189 18004 10179 18005 10189 18005 10184 18005 10184 18006 10189 18006 10190 18006 10184 18007 10190 18007 10185 18007 10185 18008 10190 18008 10191 18008 10185 18009 10191 18009 10186 18009 10106 18010 10108 18010 10187 18010 10187 18011 10108 18011 10174 18011 10187 18012 10174 18012 10188 18012 10188 18013 10174 18013 10173 18013 10188 18014 10173 18014 10189 18014 10189 18015 10173 18015 10172 18015 10189 18016 10172 18016 10190 18016 10190 18017 10172 18017 10171 18017 10190 18018 10171 18018 10191 18018 10191 18019 10171 18019 10067 18019 10191 18020 10067 18020 10186 18020 10186 18021 10067 18021 10168 18021 10186 18022 10168 18022 10175 18022 10175 18023 10168 18023 10170 18023 10175 18024 10170 18024 10176 18024 10085 18025 10083 18025 10192 18025 10193 18026 10194 18026 10195 18026 10196 18027 9476 18027 10197 18027 10197 18028 9476 18028 9478 18028 10197 18029 9478 18029 10198 18029 10198 18030 9478 18030 9479 18030 10198 18031 9479 18031 9481 18031 10199 18032 9473 18032 10196 18032 10196 18033 9473 18033 9474 18033 10196 18034 9474 18034 9476 18034 9464 18035 9467 18035 10200 18035 10200 18036 9467 18036 9470 18036 10200 18037 9470 18037 10199 18037 10199 18038 9470 18038 9472 18038 10199 18039 9472 18039 9473 18039 10201 18040 10202 18040 10203 18040 10202 18041 10201 18041 10195 18041 10204 18042 10205 18042 10194 18042 10103 18043 10102 18043 10204 18043 10204 18044 10102 18044 10107 18044 10204 18045 10107 18045 10205 18045 10205 18046 10107 18046 10105 18046 10205 18047 10105 18047 10104 18047 10192 18048 10083 18048 10204 18048 10204 18049 10083 18049 10082 18049 10204 18050 10082 18050 10103 18050 10096 18051 10101 18051 10206 18051 10206 18052 10101 18052 10100 18052 10206 18053 10100 18053 10192 18053 10192 18054 10100 18054 10113 18054 10192 18055 10113 18055 10085 18055 10206 18056 10207 18056 10096 18056 10096 18057 10207 18057 10208 18057 10096 18058 10208 18058 10094 18058 10094 18059 10208 18059 9968 18059 10094 18060 9968 18060 9838 18060 9481 18061 9482 18061 10198 18061 10198 18062 9482 18062 9964 18062 10198 18063 9964 18063 9963 18063 10194 18064 10193 18064 10204 18064 10204 18065 10193 18065 10209 18065 10204 18066 10209 18066 10192 18066 10192 18067 10209 18067 10210 18067 10192 18068 10210 18068 10206 18068 10206 18069 10210 18069 10211 18069 10206 18070 10211 18070 10207 18070 10207 18071 10211 18071 10212 18071 10207 18072 10212 18072 10208 18072 10208 18073 10212 18073 9967 18073 10208 18074 9967 18074 9968 18074 10195 18075 10201 18075 10193 18075 10193 18076 10201 18076 10213 18076 10193 18077 10213 18077 10209 18077 10209 18078 10213 18078 10214 18078 10209 18079 10214 18079 10210 18079 10210 18080 10214 18080 10215 18080 10210 18081 10215 18081 10211 18081 10211 18082 10215 18082 10216 18082 10211 18083 10216 18083 10212 18083 10212 18084 10216 18084 9962 18084 10212 18085 9962 18085 9967 18085 9465 18086 9464 18086 10203 18086 10203 18087 9464 18087 10200 18087 10203 18088 10200 18088 10201 18088 10201 18089 10200 18089 10199 18089 10201 18090 10199 18090 10213 18090 10213 18091 10199 18091 10196 18091 10213 18092 10196 18092 10214 18092 10214 18093 10196 18093 10197 18093 10214 18094 10197 18094 10215 18094 10215 18095 10197 18095 10198 18095 10215 18096 10198 18096 10216 18096 10216 18097 10198 18097 9963 18097 10216 18098 9963 18098 9962 18098 9492 18099 9497 18099 10217 18099 10217 18100 9497 18100 10137 18100 10217 18101 10218 18101 9492 18101 9492 18102 10218 18102 10219 18102 9492 18103 10219 18103 9494 18103 9494 18104 10219 18104 9508 18104 9494 18105 9508 18105 9495 18105 10137 18106 10136 18106 10217 18106 10217 18107 10136 18107 10140 18107 10217 18108 10140 18108 10218 18108 10218 18109 10140 18109 10141 18109 10218 18110 10141 18110 10219 18110 10219 18111 10141 18111 9509 18111 10219 18112 9509 18112 9508 18112 10153 9705 10152 9705 10220 9705 10220 18113 10152 18113 10221 18113 10220 18114 10221 18114 10222 18114 10222 18115 10221 18115 10223 18115 10129 18116 10128 18116 10221 18116 10221 18117 10128 18117 10135 18117 10221 18118 10135 18118 10134 18118 10224 18119 10223 18119 10137 18119 10137 18120 10223 18120 10221 18120 10137 18121 10221 18121 10138 18121 10138 18122 10221 18122 10134 18122 9912 18123 10156 18123 10152 18123 10152 18124 10156 18124 10124 18124 10152 18125 10124 18125 10221 18125 10221 18126 10124 18126 10126 18126 10221 18127 10126 18127 10129 18127 10224 18128 6628 18128 10223 18128 10223 18129 6628 18129 7109 18129 7112 18130 10153 18130 7108 18130 7108 18131 10153 18131 10220 18131 7108 18132 10220 18132 7109 18132 7109 18133 10220 18133 10222 18133 7109 18134 10222 18134 10223 18134 6663 18135 6662 18135 7112 18135 7112 18136 6662 18136 10167 18136 7112 18137 10167 18137 10166 18137 10154 18138 10153 18138 10162 18138 10162 18139 10153 18139 7112 18139 10162 18140 7112 18140 10163 18140 10163 18141 7112 18141 10166 18141 1383 18142 1420 18142 10225 18142 147 18143 142 18143 10226 18143 10227 18144 10228 18144 147 18144 10227 18145 147 18145 10229 18145 10229 18146 147 18146 10226 18146 10229 18147 10226 18147 891 18147 10230 18148 10231 18148 10229 18148 10229 18149 10231 18149 10232 18149 10229 18150 10232 18150 10227 18150 10233 18151 10234 18151 10235 18151 10235 18152 10234 18152 10236 18152 10235 18153 10236 18153 10237 18153 10237 18154 10238 18154 10235 18154 10235 18155 10238 18155 10239 18155 10235 18156 10239 18156 10229 18156 10229 18157 10239 18157 10240 18157 10229 18158 10240 18158 10230 18158 891 18159 888 18159 10229 18159 10229 18160 888 18160 1386 18160 10229 18161 1386 18161 10235 18161 10235 18162 1386 18162 1384 18162 1384 18163 1383 18163 10235 18163 10235 18164 1383 18164 10225 18164 10235 18165 10225 18165 10233 18165 10233 18166 10225 18166 10241 18166 10233 18167 10241 18167 10242 18167 10243 18168 10244 18168 10245 18168 1419 18169 1418 18169 10246 18169 1417 18170 1416 18170 10247 18170 1420 18171 1419 18171 10225 18171 10225 18172 1419 18172 10246 18172 10225 18173 10246 18173 10241 18173 1417 18174 10247 18174 1418 18174 1418 18175 10247 18175 10248 18175 1418 18176 10248 18176 10246 18176 10246 18177 10248 18177 10249 18177 10246 18178 10249 18178 10243 18178 10243 18179 10245 18179 10246 18179 10246 18180 10245 18180 10242 18180 10246 18181 10242 18181 10241 18181 10243 18182 10249 18182 10250 18182 10248 18183 10247 18183 10251 18183 10251 18184 10247 18184 1416 18184 10252 18185 10253 18185 10254 18185 10254 18186 10253 18186 10255 18186 10254 18187 10255 18187 10256 18187 10256 14978 10255 14978 10257 14978 10256 18188 10257 18188 10258 18188 10258 18189 10257 18189 10259 18189 10258 18190 10259 18190 10260 18190 10261 18191 10262 18191 10263 18191 10263 18192 10262 18192 10264 18192 10263 18193 10264 18193 10265 18193 10265 18194 10264 18194 10266 18194 10265 18195 10266 18195 10267 18195 10267 18196 10266 18196 10268 18196 10267 18197 10268 18197 10269 18197 10269 18198 10268 18198 10270 18198 10269 18199 10270 18199 10271 18199 10271 18200 10270 18200 10272 18200 10271 18201 10272 18201 10273 18201 10273 18202 10272 18202 10251 18202 10273 18203 10251 18203 10274 18203 10274 18204 10251 18204 1416 18204 10274 18205 1416 18205 1415 18205 10259 18206 10275 18206 10260 18206 10260 18207 10275 18207 10276 18207 10260 18208 10276 18208 10277 18208 10277 18209 10276 18209 10278 18209 10277 18210 10278 18210 10279 18210 10279 18211 10278 18211 10280 18211 10279 18212 10280 18212 10250 18212 10250 18213 10280 18213 10244 18213 10250 18214 10244 18214 10243 18214 10281 18215 10252 18215 10261 18215 10261 14997 10252 14997 10254 14997 10261 18216 10254 18216 10262 18216 10262 18217 10254 18217 10256 18217 10262 18218 10256 18218 10264 18218 10264 18219 10256 18219 10258 18219 10264 18220 10258 18220 10266 18220 10266 18221 10258 18221 10260 18221 10266 18222 10260 18222 10268 18222 10268 18223 10260 18223 10277 18223 10268 18224 10277 18224 10270 18224 10270 18225 10277 18225 10279 18225 10270 18226 10279 18226 10272 18226 10272 18227 10279 18227 10250 18227 10272 18228 10250 18228 10251 18228 10251 18229 10250 18229 10249 18229 10251 18230 10249 18230 10248 18230 10282 18231 10283 18231 10284 18231 10285 18232 10286 18232 10287 18232 10287 18233 10288 18233 10285 18233 10285 18234 10288 18234 10289 18234 10285 18235 10289 18235 10290 18235 10290 18236 10289 18236 10291 18236 10290 18237 10291 18237 10292 18237 10293 18238 10294 18238 10285 18238 10285 18239 10294 18239 10295 18239 10295 18240 10296 18240 10285 18240 10285 18241 10296 18241 10297 18241 10285 18242 10297 18242 10286 18242 741 18243 10293 18243 736 18243 736 18244 10293 18244 10285 18244 736 18245 10285 18245 737 18245 737 18246 10285 18246 1430 18246 1430 18247 10285 18247 1432 18247 1432 18248 10285 18248 10290 18248 1432 18249 10290 18249 1400 18249 1400 18250 10290 18250 10298 18250 1400 18251 10298 18251 1401 18251 10292 18252 10282 18252 10290 18252 10290 18253 10282 18253 10284 18253 10290 18254 10284 18254 10298 18254 10298 18255 10284 18255 10299 18255 10298 18256 10299 18256 10300 18256 10300 18257 10299 18257 10301 18257 1393 18258 1391 18258 10302 18258 10302 18259 1391 18259 1390 18259 10302 18260 1390 18260 1401 18260 1398 18261 1394 18261 10303 18261 10303 18262 1394 18262 10304 18262 1393 18263 10302 18263 1394 18263 1394 18264 10302 18264 10305 18264 1394 18265 10305 18265 10304 18265 10306 18266 10307 18266 10302 18266 10302 18267 10307 18267 10308 18267 10302 18268 10308 18268 10305 18268 1401 18269 10298 18269 10302 18269 10302 18270 10298 18270 10300 18270 10302 18271 10300 18271 10306 18271 10306 18272 10300 18272 10301 18272 10309 18273 10310 18273 10311 18273 10312 18274 1395 18274 1398 18274 10313 18275 10314 18275 10315 18275 10315 18276 10314 18276 10316 18276 10315 18277 10316 18277 10317 18277 10317 18278 10316 18278 10318 18278 10317 18279 10318 18279 10319 18279 10320 18280 10313 18280 10321 18280 10321 18281 10313 18281 10315 18281 10321 18282 10315 18282 10322 18282 10322 18283 10315 18283 10317 18283 10322 18284 10317 18284 10323 18284 10323 18285 10317 18285 10319 18285 10323 18286 10319 18286 10324 18286 10324 18287 10325 18287 10323 18287 10323 18288 10325 18288 10326 18288 10323 18289 10326 18289 10322 18289 10322 18290 10326 18290 10321 18290 10327 18291 10328 18291 10324 18291 10324 18292 10328 18292 10329 18292 10324 18293 10329 18293 10325 18293 1398 18294 10330 18294 10312 18294 10312 18295 10330 18295 10331 18295 10312 18296 10331 18296 10332 18296 10332 18297 10331 18297 10311 18297 10332 18298 10311 18298 10333 18298 10333 18299 10311 18299 10310 18299 10333 18300 10310 18300 10334 18300 10309 18301 10311 18301 10335 18301 10335 18302 10311 18302 10331 18302 10335 18303 10331 18303 10336 18303 10336 18304 10331 18304 10330 18304 10336 18305 10330 18305 10337 18305 1398 18306 10303 18306 10330 18306 10330 18307 10303 18307 10304 18307 10330 18308 10304 18308 10337 18308 10337 18309 10304 18309 10305 18309 10337 18310 10305 18310 10308 18310 10318 18311 10334 18311 10319 18311 10319 18312 10334 18312 10310 18312 10319 18313 10310 18313 10324 18313 10324 18314 10310 18314 10309 18314 10324 18315 10309 18315 10327 18315 10327 18316 10309 18316 10335 18316 10327 18317 10335 18317 10338 18317 10338 18318 10335 18318 10336 18318 10338 18319 10336 18319 10339 18319 10339 18320 10336 18320 10337 18320 10339 18321 10337 18321 10340 18321 10340 18322 10337 18322 10308 18322 10340 18323 10308 18323 10307 18323 10271 18324 10273 18324 1414 18324 1414 18325 10273 18325 10274 18325 1414 18326 10274 18326 1415 18326 10271 18327 1414 18327 10269 18327 10269 18328 1414 18328 1413 18328 10269 18329 1413 18329 10267 18329 10281 18330 10261 18330 1412 18330 1412 18331 10261 18331 10263 18331 1412 18332 10263 18332 1413 18332 1413 18333 10263 18333 10265 18333 1413 18334 10265 18334 10267 18334 10318 18335 10316 18335 1397 18335 10313 18336 10320 18336 1392 18336 1397 18337 10316 18337 1392 18337 1392 18338 10316 18338 10314 18338 1392 18339 10314 18339 10313 18339 1396 18340 10333 18340 1397 18340 1397 18341 10333 18341 10334 18341 1397 18342 10334 18342 10318 18342 1395 18343 10312 18343 1396 18343 1396 18344 10312 18344 10332 18344 1396 18345 10332 18345 10333 18345 1427 18346 9290 18346 10341 18346 1427 18347 10341 18347 1428 18347 1428 18348 10341 18348 10342 18348 1428 18349 10342 18349 1410 18349 1410 18350 10342 18350 10343 18350 1410 18351 10343 18351 1411 18351 1411 18352 10343 18352 10344 18352 1411 18353 10344 18353 1412 18353 9290 18354 10345 18354 10346 18354 10343 18355 10342 18355 10347 18355 10347 18356 10348 18356 10343 18356 10343 18357 10348 18357 10349 18357 10343 18358 10349 18358 10344 18358 10344 15142 10349 15142 10350 15142 10344 18359 10350 18359 10351 18359 9290 18360 10346 18360 10341 18360 10341 18361 10346 18361 10352 18361 10341 18362 10352 18362 10342 18362 10342 18363 10352 18363 10353 18363 10342 18364 10353 18364 10347 18364 1392 18365 10354 18365 1402 18365 1402 18366 10354 18366 10355 18366 10356 18367 9289 18367 1425 18367 1425 18368 1424 18368 10356 18368 10356 18369 1424 18369 1421 18369 10356 18370 1421 18370 10357 18370 10357 18371 1421 18371 1405 18371 10357 18372 1405 18372 10355 18372 10355 18373 1405 18373 1403 18373 10355 18374 1403 18374 1402 18374 10358 18375 10359 18375 10354 18375 10354 18376 10359 18376 10360 18376 10354 18377 10360 18377 10355 18377 10361 18378 9289 18378 10362 18378 10362 18379 9289 18379 10356 18379 10362 18380 10356 18380 10357 18380 10360 18381 10363 18381 10355 18381 10355 18382 10363 18382 10364 18382 10355 18383 10364 18383 10357 18383 10357 18384 10364 18384 10365 18384 10357 18385 10365 18385 10362 18385 10366 15171 10367 15171 10368 15171 10366 18386 10368 18386 10369 18386 10369 18387 10368 18387 10370 18387 10369 18388 10370 18388 10371 18388 10371 18389 10370 18389 10372 18389 10371 18390 10372 18390 10373 18390 10373 18391 10372 18391 10374 18391 10373 18392 10374 18392 10375 18392 10375 18393 10374 18393 10376 18393 10375 18394 10376 18394 10377 18394 10377 18395 10376 18395 10378 18395 10377 18396 10378 18396 10379 18396 10379 18397 10378 18397 10380 18397 10379 18398 10380 18398 10381 18398 10381 18399 10380 18399 10382 18399 10381 18400 10382 18400 10383 18400 10383 18401 10382 18401 10384 18401 10383 18402 10384 18402 10385 18402 10385 18403 10384 18403 10386 18403 10385 18404 10386 18404 10387 18404 10387 18405 10386 18405 10388 18405 10387 18406 10388 18406 10389 18406 10389 15177 10388 15177 10367 15177 10389 18407 10367 18407 10366 18407 10023 18408 151 18408 150 18408 10390 15180 10391 15180 9831 15180 9831 15181 10006 15181 10390 15181 10390 9479 10006 9479 10014 9479 10390 18409 10014 18409 10392 18409 10014 15183 10016 15183 10392 15183 10392 18410 10016 18410 10015 18410 10392 18411 10015 18411 10393 18411 150 15186 10394 15186 10023 15186 10023 18412 10394 18412 10393 18412 10023 9486 10393 9486 10024 9486 10024 15188 10393 15188 10015 15188 10169 18413 10065 18413 10395 18413 10396 18414 10397 18414 10182 18414 10182 18415 10180 18415 10396 18415 10396 18416 10180 18416 10178 18416 10396 18417 10178 18417 10398 18417 10398 18418 10178 18418 10176 18418 10398 18419 10176 18419 10399 18419 10395 18420 10400 18420 10169 18420 10169 18421 10400 18421 10399 18421 10169 18422 10399 18422 10170 18422 10170 18423 10399 18423 10176 18423 10401 18424 10402 18424 10403 18424 10404 18425 10399 18425 10405 18425 10399 18426 10404 18426 10398 18426 10406 18427 10407 18427 10408 18427 10397 18428 10396 18428 10409 18428 10410 18429 10411 18429 10412 18429 10397 18430 10409 18430 10406 18430 10406 18431 10409 18431 10403 18431 10406 18432 10403 18432 10407 18432 10407 18433 10403 18433 10402 18433 10407 18434 10402 18434 10408 18434 10400 18435 10395 18435 10413 18435 10413 18436 10395 18436 10414 18436 10413 18437 10414 18437 10415 18437 10415 18438 10414 18438 10416 18438 10415 18439 10416 18439 10417 18439 10417 18440 10418 18440 10415 18440 10415 18441 10418 18441 10419 18441 10415 18442 10419 18442 10413 18442 10413 18443 10419 18443 10405 18443 10413 9433 10405 9433 10400 9433 10400 18444 10405 18444 10399 18444 10396 18445 10412 18445 10409 18445 10409 18446 10412 18446 10411 18446 10409 18447 10411 18447 10403 18447 10403 18448 10411 18448 10420 18448 10403 18449 10420 18449 10401 18449 10421 18450 10422 18450 10423 18450 10423 18451 10422 18451 10424 18451 10423 18452 10424 18452 10425 18452 10425 18453 10424 18453 10426 18453 10425 18454 10426 18454 10410 18454 10410 18455 10426 18455 10427 18455 10410 18456 10427 18456 10411 18456 10411 18457 10427 18457 10428 18457 10411 18458 10428 18458 10420 18458 10429 18459 10421 18459 10430 18459 10430 18460 10421 18460 10423 18460 10430 18461 10423 18461 10431 18461 10431 18462 10423 18462 10425 18462 10431 18463 10425 18463 10432 18463 10432 18464 10425 18464 10410 18464 10396 18465 10398 18465 10412 18465 10412 18466 10398 18466 10404 18466 10412 18467 10404 18467 10410 18467 10410 18468 10404 18468 10405 18468 10410 18469 10405 18469 10432 18469 10432 18470 10405 18470 10419 18470 10432 18471 10419 18471 10431 18471 10431 18472 10419 18472 10418 18472 10431 18473 10418 18473 10430 18473 10430 18474 10418 18474 10417 18474 10430 18475 10417 18475 10429 18475 10433 18476 10434 18476 10283 18476 10433 18477 10283 18477 10435 18477 10436 18478 10437 18478 10292 18478 10283 18479 10282 18479 10435 18479 10435 18480 10282 18480 10292 18480 10435 18481 10292 18481 10438 18481 10438 18482 10292 18482 10437 18482 10288 18483 10439 18483 10440 18483 10292 18484 10291 18484 10436 18484 10436 18485 10291 18485 10289 18485 10436 18486 10289 18486 10441 18486 10441 18487 10289 18487 10288 18487 10441 18488 10288 18488 10442 18488 10442 18489 10288 18489 10440 18489 10443 18490 10444 18490 10286 18490 10286 18491 10444 18491 10445 18491 10286 18492 10445 18492 10446 18492 10439 18493 10288 18493 10446 18493 10446 18494 10288 18494 10287 18494 10446 18495 10287 18495 10286 18495 10296 18496 10447 18496 10448 18496 10296 18497 10448 18497 10297 18497 10297 18498 10448 18498 10449 18498 10297 18499 10449 18499 10286 18499 10286 18500 10449 18500 10450 18500 10286 18501 10450 18501 10443 18501 10447 18502 10296 18502 10451 18502 10451 18503 10296 18503 10295 18503 10451 18504 10295 18504 10408 18504 10452 18505 10453 18505 10232 18505 10232 18506 10453 18506 10227 18506 10227 15285 10453 15285 10454 15285 10227 15286 10454 15286 10228 15286 10228 15287 10454 15287 10455 15287 10228 15288 10455 15288 147 15288 147 18507 10455 18507 10456 18507 147 18508 10456 18508 146 18508 10457 15291 10458 15291 10230 15291 10458 18509 10459 18509 10230 18509 10230 15293 10459 15293 10460 15293 10230 18510 10460 18510 10231 18510 10231 15295 10460 15295 10461 15295 10231 18511 10461 18511 10232 18511 10232 18512 10461 18512 10462 18512 10232 18513 10462 18513 10452 18513 10230 18514 10240 18514 10457 18514 10457 18515 10240 18515 10239 18515 10457 18516 10239 18516 10463 18516 10236 18517 10464 18517 10237 18517 10237 18518 10464 18518 10463 18518 10237 18519 10463 18519 10238 18519 10238 18520 10463 18520 10239 18520 10465 15309 10466 15309 10467 15309 10468 15306 10469 15306 10390 15306 10470 18521 10471 18521 10472 18521 10472 18522 10471 18522 10473 18522 10472 18523 10473 18523 10474 18523 10474 18524 10473 18524 10475 18524 10474 18525 10475 18525 10465 18525 10465 18526 10475 18526 10476 18526 10465 15308 10476 15308 10466 15308 10394 15314 150 15314 149 15314 10477 18527 10478 18527 10468 18527 10477 18528 10479 18528 10480 18528 10478 18529 10477 18529 10481 18529 10481 15318 10477 15318 10480 15318 10481 15319 10480 15319 10482 15319 148 15320 10483 15320 149 15320 149 18530 10483 18530 10484 18530 149 18531 10484 18531 10394 18531 10394 18532 10484 18532 10485 18532 10394 18533 10485 18533 10393 18533 10393 18534 10485 18534 10486 18534 10393 18535 10486 18535 10392 18535 10467 18536 10487 18536 10465 18536 10465 18537 10487 18537 10488 18537 10465 15329 10488 15329 10474 15329 10474 18538 10488 18538 10489 18538 10474 18539 10489 18539 10472 18539 10472 18540 10489 18540 10490 18540 10472 15333 10490 15333 10470 15333 10391 15334 10390 15334 10467 15334 10467 15335 10390 15335 10469 15335 10467 18541 10469 18541 10487 18541 10487 18542 10469 18542 10468 18542 10487 18543 10468 18543 10488 18543 10488 18544 10468 18544 10478 18544 10488 18545 10478 18545 10489 18545 10489 18546 10478 18546 10481 18546 10489 15342 10481 15342 10490 15342 10490 15343 10481 15343 10482 15343 10479 15344 10477 15344 10491 15344 10491 15345 10477 15345 10492 15345 10491 15346 10492 15346 10493 15346 10493 15347 10492 15347 10494 15347 10493 15348 10494 15348 146 15348 148 15349 146 15349 10483 15349 10483 15350 146 15350 10494 15350 10483 18547 10494 18547 10484 18547 10484 18548 10494 18548 10492 18548 10484 18549 10492 18549 10485 18549 10485 18550 10492 18550 10477 18550 10485 18551 10477 18551 10486 18551 10486 15356 10477 15356 10468 15356 10486 18552 10468 18552 10392 18552 10392 18553 10468 18553 10390 18553 10495 18554 10496 18554 10497 18554 10421 18555 10429 18555 10498 18555 10424 18556 10422 18556 10499 18556 10500 18557 10426 18557 10501 18557 10420 18558 10428 18558 10502 18558 10426 18559 10500 18559 10427 18559 10446 18560 10440 18560 10439 18560 10444 18561 10443 18561 10503 18561 10449 18562 10448 18562 10504 18562 10504 18563 10505 18563 10449 18563 10449 18564 10505 18564 10503 18564 10449 18565 10503 18565 10450 18565 10450 18566 10503 18566 10443 18566 10437 18567 10506 18567 10438 18567 10438 18568 10506 18568 10497 18568 10438 18569 10497 18569 10435 18569 10435 18570 10497 18570 10496 18570 10435 18571 10496 18571 10433 18571 10433 18572 10496 18572 10495 18572 10433 18573 10495 18573 10434 18573 10445 18574 10507 18574 10446 18574 10446 18575 10507 18575 10508 18575 10446 18576 10508 18576 10440 18576 10440 18577 10508 18577 10509 18577 10440 18578 10509 18578 10442 18578 10442 18579 10509 18579 10510 18579 10442 18580 10510 18580 10441 18580 10441 18581 10510 18581 10436 18581 10451 18582 10408 18582 10511 18582 10511 18583 10408 18583 10402 18583 10511 18584 10402 18584 10401 18584 10401 18585 10420 18585 10511 18585 10511 18586 10420 18586 10502 18586 10511 18587 10502 18587 10512 18587 10512 18588 10502 18588 10513 18588 10428 18589 10427 18589 10502 18589 10502 18590 10427 18590 10500 18590 10502 18591 10500 18591 10513 18591 10513 18592 10500 18592 10501 18592 10513 18593 10501 18593 10514 18593 10514 18594 10515 18594 10516 18594 10451 18595 10511 18595 10447 18595 10447 18596 10511 18596 10512 18596 10447 18597 10512 18597 10448 18597 10448 18598 10512 18598 10513 18598 10448 18599 10513 18599 10504 18599 10504 18600 10513 18600 10514 18600 10504 18601 10514 18601 10505 18601 10505 18602 10514 18602 10516 18602 10505 18603 10516 18603 10503 18603 10517 18604 10518 18604 10519 18604 10437 18605 10436 18605 10519 18605 10519 18606 10436 18606 10510 18606 10519 18607 10510 18607 10517 18607 10517 18608 10510 18608 10509 18608 10517 18609 10509 18609 10515 18609 10515 18610 10509 18610 10508 18610 10515 18611 10508 18611 10516 18611 10516 18612 10508 18612 10507 18612 10516 18613 10507 18613 10503 18613 10503 18614 10507 18614 10445 18614 10503 18615 10445 18615 10444 18615 10422 18616 10421 18616 10499 18616 10499 18617 10421 18617 10498 18617 10499 18618 10498 18618 10520 18618 10520 18619 10498 18619 10521 18619 10520 18620 10521 18620 10522 18620 10522 18621 10521 18621 10523 18621 10522 18622 10523 18622 10524 18622 10524 18623 10523 18623 10525 18623 10524 18624 10525 18624 10526 18624 10526 18625 10525 18625 10527 18625 10526 18626 10527 18626 10528 18626 10528 18627 10527 18627 10529 18627 10437 18628 10519 18628 10506 18628 10506 18629 10519 18629 10518 18629 10506 18630 10518 18630 10497 18630 10497 18631 10518 18631 10530 18631 10497 18632 10530 18632 10495 18632 10426 18633 10424 18633 10501 18633 10501 18634 10424 18634 10499 18634 10501 18635 10499 18635 10514 18635 10514 18636 10499 18636 10520 18636 10514 18637 10520 18637 10515 18637 10515 18638 10520 18638 10522 18638 10515 18639 10522 18639 10517 18639 10517 18640 10522 18640 10524 18640 10517 18641 10524 18641 10518 18641 10518 18642 10524 18642 10526 18642 10518 18643 10526 18643 10530 18643 10530 18644 10526 18644 10528 18644 10530 9303 10528 9303 10495 9303 10495 18645 10528 18645 10531 18645 10529 18646 10532 18646 10528 18646 10528 18647 10532 18647 10533 18647 10528 18648 10533 18648 10531 18648 10534 18649 10535 18649 10536 18649 10482 15456 10480 15456 10537 15456 10455 15457 10454 15457 10538 15457 10452 15458 10462 15458 10539 15458 10470 15459 10540 15459 10471 15459 10471 18650 10540 18650 10541 18650 10542 15461 10543 15461 10544 15461 10544 15462 10543 15462 10545 15462 10544 15463 10545 15463 10546 15463 10546 18651 10545 18651 10547 18651 10546 18652 10547 18652 10548 18652 10548 18653 10547 18653 10541 18653 10548 18654 10541 18654 10549 18654 10549 18655 10541 18655 10540 18655 10550 15469 10543 15469 10551 15469 10551 15470 10543 15470 10542 15470 10551 15471 10542 15471 10552 15471 10463 18656 10464 18656 10553 18656 10553 18657 10554 18657 10463 18657 10463 15474 10554 15474 10555 15474 10463 18658 10555 18658 10457 18658 10457 18659 10555 18659 10458 18659 10458 15477 10555 15477 10556 15477 10458 15478 10556 15478 10459 15478 10459 15479 10556 15479 10460 15479 10460 15480 10556 15480 10557 15480 10460 15481 10557 15481 10461 15481 10452 15482 10539 15482 10453 15482 10453 15483 10539 15483 10558 15483 10453 15484 10558 15484 10454 15484 10454 18660 10558 18660 10559 18660 10454 18661 10559 18661 10538 18661 10493 18662 146 18662 10456 18662 10479 18663 10491 18663 10559 18663 10559 18664 10491 18664 10493 18664 10559 18665 10493 18665 10538 18665 10538 18666 10493 18666 10456 18666 10538 18667 10456 18667 10455 18667 10480 18668 10479 18668 10537 18668 10537 18669 10479 18669 10559 18669 10537 18670 10559 18670 10560 18670 10560 18671 10559 18671 10558 18671 10560 15497 10558 15497 10557 15497 10557 15498 10558 15498 10539 15498 10557 15499 10539 15499 10461 15499 10461 15500 10539 15500 10462 15500 10535 18672 10552 18672 10536 18672 10536 18673 10552 18673 10542 18673 10536 18674 10542 18674 10561 18674 10561 18675 10542 18675 10544 18675 10561 15505 10544 15505 10562 15505 10562 18676 10544 18676 10546 18676 10562 15507 10546 15507 10563 15507 10563 18677 10546 18677 10548 18677 10563 18678 10548 18678 10564 18678 10564 15510 10548 15510 10549 15510 10564 18679 10549 18679 10565 18679 10565 15512 10549 15512 10540 15512 10565 15513 10540 15513 10490 15513 10490 15514 10540 15514 10470 15514 10553 18680 10534 18680 10554 18680 10554 18681 10534 18681 10536 18681 10554 18682 10536 18682 10555 18682 10555 18683 10536 18683 10561 18683 10555 15519 10561 15519 10556 15519 10556 15520 10561 15520 10562 15520 10556 15521 10562 15521 10557 15521 10557 15522 10562 15522 10563 15522 10557 15523 10563 15523 10560 15523 10560 15524 10563 15524 10564 15524 10560 15525 10564 15525 10537 15525 10537 18684 10564 18684 10565 18684 10537 18685 10565 18685 10482 18685 10482 15528 10565 15528 10490 15528 10566 18686 10567 18686 10568 18686 10434 18687 10495 18687 10569 18687 10569 18688 10495 18688 10570 18688 10569 18689 10570 18689 10571 18689 10572 18690 10573 18690 10574 18690 10575 18691 10576 18691 10577 18691 10567 18692 10566 18692 10578 18692 10578 18693 10566 18693 10573 18693 10578 18694 10573 18694 10579 18694 10579 18695 10573 18695 10572 18695 10579 18696 10572 18696 10580 18696 10572 18697 10581 18697 10580 18697 10580 18698 10581 18698 10582 18698 10580 18699 10582 18699 10583 18699 10583 18700 10582 18700 10584 18700 10583 18701 10584 18701 10585 18701 10585 18702 10584 18702 10575 18702 10585 18703 10575 18703 10586 18703 10586 18704 10575 18704 10577 18704 10533 18705 10587 18705 10531 18705 10531 18706 10587 18706 10588 18706 10531 18707 10588 18707 10495 18707 10495 18708 10588 18708 10589 18708 10495 18709 10589 18709 10570 18709 10533 18710 10532 18710 10587 18710 10587 18711 10532 18711 10590 18711 10587 18712 10590 18712 10591 18712 10574 18713 10571 18713 10572 18713 10572 18714 10571 18714 10570 18714 10572 18715 10570 18715 10581 18715 10581 18716 10570 18716 10589 18716 10581 18717 10589 18717 10582 18717 10582 18718 10589 18718 10588 18718 10582 18719 10588 18719 10584 18719 10584 18720 10588 18720 10587 18720 10584 18721 10587 18721 10575 18721 10575 18722 10587 18722 10591 18722 10575 18723 10591 18723 10576 18723 10576 18724 10591 18724 10590 18724 10592 18725 10568 18725 10593 18725 10593 18726 10568 18726 10567 18726 10567 18727 10578 18727 10593 18727 10593 18728 10578 18728 10579 18728 10593 18729 10579 18729 10594 18729 10594 18730 10579 18730 10580 18730 10594 18731 10580 18731 10595 18731 10596 18732 10597 18732 10598 18732 10598 18733 10597 18733 10595 18733 10595 18734 10580 18734 10598 18734 10598 18735 10580 18735 10583 18735 10598 18736 10583 18736 10585 18736 10599 18737 10600 18737 10601 18737 10602 18738 10603 18738 10600 18738 10603 18739 10602 18739 10604 18739 10592 18740 10593 18740 10605 18740 10606 18741 10607 18741 10601 18741 10601 18742 10607 18742 10608 18742 10601 18743 10608 18743 10599 18743 10609 18744 10610 18744 10611 18744 10611 18745 10610 18745 10612 18745 10613 18746 10614 18746 10615 18746 10615 18747 10614 18747 10616 18747 10615 18748 10616 18748 10617 18748 10617 18749 10616 18749 10618 18749 10617 18750 10618 18750 10612 18750 10612 18751 10618 18751 10619 18751 10612 18752 10619 18752 10611 18752 10596 18753 10620 18753 10597 18753 10597 18754 10620 18754 10621 18754 10597 18755 10621 18755 10595 18755 10594 18756 10595 18756 10622 18756 10622 18757 10595 18757 10621 18757 10622 18758 10621 18758 10623 18758 10624 18759 10592 18759 10604 18759 10604 18760 10592 18760 10605 18760 10604 18761 10605 18761 10603 18761 10603 18762 10605 18762 10625 18762 10603 18763 10625 18763 10600 18763 10600 18764 10625 18764 10626 18764 10600 18765 10626 18765 10601 18765 10601 18766 10626 18766 10627 18766 10601 18767 10627 18767 10606 18767 10606 18768 10627 18768 10628 18768 10593 18769 10594 18769 10605 18769 10605 18770 10594 18770 10622 18770 10605 18771 10622 18771 10625 18771 10625 18772 10622 18772 10623 18772 10625 18773 10623 18773 10626 18773 10626 18774 10623 18774 10629 18774 10626 18775 10629 18775 10627 18775 10627 18776 10629 18776 10630 18776 10627 18777 10630 18777 10628 18777 10628 18778 10630 18778 10631 18778 10620 18779 10614 18779 10621 18779 10621 18780 10614 18780 10613 18780 10621 18781 10613 18781 10623 18781 10623 18782 10613 18782 10615 18782 10623 18783 10615 18783 10629 18783 10629 18784 10615 18784 10617 18784 10629 18785 10617 18785 10630 18785 10630 18786 10617 18786 10612 18786 10630 18787 10612 18787 10631 18787 10631 18788 10612 18788 10610 18788 10632 18789 10633 18789 10607 18789 10607 18790 10606 18790 10632 18790 10632 18791 10606 18791 10628 18791 10632 18792 10628 18792 10634 18792 10634 18793 10628 18793 10631 18793 10634 18794 10631 18794 10635 18794 10635 18795 10631 18795 10610 18795 10635 18796 10610 18796 10609 18796 10636 18797 10637 18797 10638 18797 10639 18798 10640 18798 10641 18798 10641 18799 10640 18799 10642 18799 10641 18800 10642 18800 10643 18800 10643 18801 10642 18801 10636 18801 10643 18802 10636 18802 10644 18802 10644 18803 10636 18803 10638 18803 10645 18804 10646 18804 10647 18804 10648 18805 10649 18805 10650 18805 10651 18806 10652 18806 10653 18806 10654 18807 10655 18807 10656 18807 10656 18808 10655 18808 10639 18808 10656 18809 10639 18809 10641 18809 10657 18810 10658 18810 10659 18810 10659 18811 10658 18811 10660 18811 10659 18812 10660 18812 10661 18812 10661 18813 10660 18813 10654 18813 10661 18814 10654 18814 10662 18814 10662 18815 10654 18815 10656 18815 10648 18816 10650 18816 10663 18816 10663 18817 10650 18817 10664 18817 10663 18818 10664 18818 10665 18818 10665 18819 10664 18819 10644 18819 10665 18820 10644 18820 10638 18820 10645 18821 10647 18821 10666 18821 10666 18822 10647 18822 10667 18822 10666 18823 10667 18823 10668 18823 10643 18824 10644 18824 10669 18824 10669 18825 10644 18825 10664 18825 10669 18826 10664 18826 10670 18826 10670 18827 10664 18827 10650 18827 10670 18828 10650 18828 10668 18828 10668 18829 10650 18829 10649 18829 10668 18830 10649 18830 10666 18830 10666 18831 10649 18831 10648 18831 10666 18832 10648 18832 10645 18832 10645 18833 10648 18833 10651 18833 10645 18834 10651 18834 10646 18834 10646 18835 10651 18835 10653 18835 10646 18836 10653 18836 10647 18836 10647 18837 10653 18837 10671 18837 10647 18838 10671 18838 10667 18838 10671 18839 10657 18839 10667 18839 10667 18840 10657 18840 10659 18840 10667 18841 10659 18841 10668 18841 10668 18842 10659 18842 10661 18842 10668 18843 10661 18843 10670 18843 10670 18844 10661 18844 10662 18844 10670 18845 10662 18845 10669 18845 10669 18846 10662 18846 10656 18846 10669 18847 10656 18847 10643 18847 10643 18848 10656 18848 10641 18848 10672 18849 10673 18849 10658 18849 10653 18850 10652 18850 10674 18850 10658 18851 10657 18851 10672 18851 10672 18852 10657 18852 10671 18852 10672 18853 10671 18853 10675 18853 10675 18854 10671 18854 10653 18854 10675 18855 10653 18855 10676 18855 10676 18856 10653 18856 10674 18856 10676 18857 10674 18857 10677 18857 10677 18858 10674 18858 10678 18858 10679 18859 10680 18859 10681 18859 10682 18860 10683 18860 10684 18860 10685 8973 10686 8973 10687 8973 10687 18861 10686 18861 10688 18861 10684 18862 10683 18862 10689 18862 10683 18863 10690 18863 10689 18863 10689 18864 10690 18864 10691 18864 10689 18865 10691 18865 10686 18865 10686 18866 10691 18866 10692 18866 10686 18867 10692 18867 10688 18867 10693 18868 10694 18868 10682 18868 10695 18869 10694 18869 10696 18869 10696 18870 10694 18870 10693 18870 10696 18871 10693 18871 10697 18871 10682 18872 10684 18872 10693 18872 10693 18873 10684 18873 10698 18873 10693 18874 10698 18874 10697 18874 10679 18875 10681 18875 10699 18875 10699 18876 10681 18876 10700 18876 10699 18877 10700 18877 10701 18877 10701 18878 10700 18878 10702 18878 10701 18879 10702 18879 10703 18879 10685 8993 10702 8993 10686 8993 10686 18880 10702 18880 10700 18880 10686 18881 10700 18881 10689 18881 10689 18882 10700 18882 10681 18882 10689 18883 10681 18883 10684 18883 10684 18884 10681 18884 10680 18884 10684 18885 10680 18885 10698 18885 10698 18886 10680 18886 10679 18886 10698 18887 10679 18887 10704 18887 10705 632 10706 632 10707 632 10708 632 10709 632 10710 632 10703 632 10711 632 10712 632 10704 632 10679 632 10713 632 10713 632 10679 632 10699 632 10713 632 10699 632 10707 632 10712 18888 10714 18888 10703 18888 10703 18889 10714 18889 10707 18889 10703 632 10707 632 10701 632 10701 632 10707 632 10699 632 10708 18888 10710 18888 10714 18888 10714 18890 10710 18890 10715 18890 10714 18891 10715 18891 10707 18891 10707 18892 10715 18892 10716 18892 10707 632 10716 632 10705 632 10717 18893 10718 18893 10719 18893 10720 18894 10721 18894 10719 18894 10719 18895 10721 18895 10722 18895 10719 18896 10722 18896 10717 18896 10723 18897 10724 18897 10725 18897 10725 18898 10724 18898 10726 18898 10725 18899 10726 18899 10727 18899 10727 18900 10726 18900 10728 18900 10727 18901 10728 18901 10729 18901 10729 18902 10728 18902 10730 18902 10729 18903 10730 18903 10731 18903 10715 18904 10710 18904 10732 18904 10733 18905 10734 18905 10735 18905 10732 18906 10736 18906 10715 18906 10715 18907 10736 18907 10737 18907 10715 18908 10737 18908 10716 18908 10716 18909 10737 18909 10733 18909 10716 18910 10733 18910 10705 18910 10705 18911 10733 18911 10735 18911 10705 18912 10735 18912 10706 18912 10718 18913 10738 18913 10719 18913 10719 18914 10738 18914 10724 18914 10719 18915 10724 18915 10720 18915 10720 18916 10724 18916 10723 18916 10738 18917 10734 18917 10724 18917 10724 18918 10734 18918 10733 18918 10724 18919 10733 18919 10726 18919 10726 18920 10733 18920 10737 18920 10726 8963 10737 8963 10728 8963 10728 18921 10737 18921 10736 18921 10728 18922 10736 18922 10730 18922 10730 18923 10736 18923 10732 18923 10328 18924 10327 18924 10727 18924 10727 18925 10327 18925 10338 18925 10727 18926 10338 18926 10725 18926 10725 18927 10338 18927 10339 18927 10725 18928 10339 18928 10723 18928 10723 18929 10339 18929 10340 18929 10723 18930 10340 18930 10720 18930 10720 18931 10340 18931 10307 18931 10720 18932 10307 18932 10721 18932 10721 8924 10307 8924 10306 8924 10721 18933 10306 18933 10722 18933 10722 18934 10306 18934 10301 18934 10722 18935 10301 18935 10717 18935 10731 18936 10320 18936 10321 18936 10321 18937 10326 18937 10731 18937 10731 18938 10326 18938 10325 18938 10731 18939 10325 18939 10329 18939 10328 18940 10727 18940 10329 18940 10329 18941 10727 18941 10729 18941 10329 18942 10729 18942 10731 18942 10739 106 10687 106 10740 106 10740 106 10687 106 10281 106 10740 106 10281 106 10741 106 10742 18943 10709 18943 10743 18943 10744 18944 10731 18944 10730 18944 10745 18945 10746 18945 10744 18945 10744 18946 10730 18946 10745 18946 10745 18947 10730 18947 10732 18947 10745 18948 10732 18948 10747 18948 10742 18949 10748 18949 10709 18949 10709 18950 10748 18950 10747 18950 10709 18951 10747 18951 10710 18951 10710 18952 10747 18952 10732 18952 10712 18953 10711 18953 10749 18953 10749 18954 10750 18954 10712 18954 10712 18955 10750 18955 10751 18955 10712 18956 10751 18956 10714 18956 10714 8899 10751 8899 10752 8899 10714 8900 10752 8900 10708 8900 10708 15770 10752 15770 10743 15770 10708 18957 10743 18957 10709 18957 10739 18958 10753 18958 10754 18958 10711 15773 10703 15773 10702 15773 10755 18959 10756 18959 10711 18959 10711 18960 10756 18960 10757 18960 10711 18961 10757 18961 10749 18961 10711 18962 10702 18962 10755 18962 10755 18963 10702 18963 10685 18963 10755 18964 10685 18964 10754 18964 10754 18965 10685 18965 10687 18965 10754 18966 10687 18966 10739 18966 10740 18967 10758 18967 10759 18967 10759 18968 10760 18968 10740 18968 10740 18969 10760 18969 10753 18969 10740 8884 10753 8884 10739 8884 10761 18970 10762 18970 10763 18970 10763 18971 10762 18971 10741 18971 10741 18972 10762 18972 10764 18972 10741 18973 10764 18973 10765 18973 10765 18974 10766 18974 10741 18974 10741 18975 10766 18975 10767 18975 10767 18976 10768 18976 10741 18976 10741 18977 10768 18977 10769 18977 10741 18978 10769 18978 10740 18978 10770 18979 10771 18979 10763 18979 10763 18980 10771 18980 10772 18980 10763 18981 10772 18981 10761 18981 10773 18982 10774 18982 10775 18982 10775 18983 10774 18983 10776 18983 10741 15797 10281 15797 10777 15797 10777 18984 10281 18984 10778 18984 10777 18985 10778 18985 10779 18985 10779 15800 10778 15800 10780 15800 10779 18986 10780 18986 10781 18986 10781 18987 10780 18987 10782 18987 10781 18988 10782 18988 10776 18988 10776 18989 10782 18989 10783 18989 10776 18990 10783 18990 10775 18990 10784 18991 10785 18991 10746 18991 10746 18992 10785 18992 10786 18992 10746 18993 10786 18993 10744 18993 10787 18994 10788 18994 10746 18994 10748 18995 10789 18995 10747 18995 10747 18996 10789 18996 10790 18996 10747 18997 10790 18997 10745 18997 10787 18998 10746 18998 10791 18998 10791 18999 10746 18999 10745 18999 10791 19000 10745 19000 10792 19000 10792 19001 10745 19001 10790 19001 10792 19002 10790 19002 10793 19002 10793 19003 10790 19003 10789 19003 10793 19004 10789 19004 10794 19004 10794 19005 10789 19005 10748 19005 10794 19006 10748 19006 10795 19006 10743 8838 10796 8838 10742 8838 10742 19007 10796 19007 10797 19007 10742 19008 10797 19008 10748 19008 10750 19009 10798 19009 10799 19009 10796 19010 10800 19010 10797 19010 10797 19011 10800 19011 10801 19011 10797 19012 10801 19012 10802 19012 10750 8831 10749 8831 10798 8831 10798 19013 10749 19013 10803 19013 10798 632 10803 632 10804 632 10804 15827 10803 15827 10805 15827 10804 19014 10805 19014 10806 19014 10796 15829 10743 15829 10800 15829 10800 15830 10743 15830 10752 15830 10800 15831 10752 15831 10799 15831 10799 19015 10752 19015 10751 19015 10799 19016 10751 19016 10750 19016 10749 19017 10757 19017 10803 19017 10803 19018 10757 19018 10805 19018 10757 19019 10807 19019 10808 19019 10753 19020 10809 19020 10810 19020 10754 19021 10811 19021 10755 19021 10755 19022 10811 19022 10807 19022 10755 19023 10807 19023 10756 19023 10756 19024 10807 19024 10757 19024 10753 19025 10810 19025 10754 19025 10754 19026 10810 19026 10812 19026 10754 19027 10812 19027 10811 19027 10811 19028 10812 19028 10813 19028 10811 19029 10813 19029 10807 19029 10807 19030 10813 19030 10814 19030 10807 19031 10814 19031 10808 19031 10815 19032 10816 19032 10320 19032 10320 19033 10816 19033 10817 19033 10816 19034 10818 19034 10817 19034 10817 19035 10818 19035 10819 19035 10817 19036 10819 19036 10820 19036 10820 19037 10819 19037 10821 19037 10820 19038 10821 19038 10822 19038 10822 19039 10821 19039 10823 19039 10822 19040 10823 19040 10824 19040 10825 19041 10826 19041 10827 19041 10827 19042 10826 19042 10828 19042 10827 19043 10828 19043 10829 19043 10830 19044 10831 19044 10815 19044 10815 19045 10831 19045 10832 19045 10832 19046 10833 19046 10815 19046 10815 19047 10833 19047 10834 19047 10815 19048 10834 19048 10828 19048 10828 19049 10834 19049 10835 19049 10828 19050 10835 19050 10829 19050 10836 19051 10837 19051 10838 19051 10834 19052 10833 19052 10839 19052 10839 19053 10833 19053 10832 19053 10786 19054 10785 19054 10840 19054 10841 19055 10831 19055 10830 19055 10831 19056 10841 19056 10832 19056 10832 19057 10841 19057 10838 19057 10832 19058 10838 19058 10839 19058 10835 19059 10834 19059 10842 19059 10842 19060 10834 19060 10839 19060 10842 19061 10839 19061 10843 19061 10843 19062 10839 19062 10838 19062 10843 19063 10838 19063 10844 19063 10844 19064 10838 19064 10837 19064 10844 19065 10837 19065 10845 19065 10830 19066 10786 19066 10841 19066 10841 19067 10786 19067 10840 19067 10841 19068 10840 19068 10838 19068 10838 19069 10840 19069 10846 19069 10838 19070 10846 19070 10836 19070 10847 19071 10848 19071 10849 19071 10850 19072 10851 19072 10852 19072 10850 19073 10852 19073 10853 19073 10853 19074 10852 19074 10854 19074 10853 8739 10854 8739 10855 8739 10855 8740 10854 8740 10856 8740 10855 19075 10856 19075 10857 19075 10857 19076 10856 19076 10858 19076 10857 19077 10858 19077 10859 19077 10847 19078 10849 19078 10860 19078 10860 19079 10849 19079 10861 19079 10860 19080 10861 19080 10862 19080 10862 19081 10861 19081 10863 19081 10862 8748 10863 8748 10864 8748 10864 19082 10863 19082 10865 19082 10865 15888 10863 15888 10866 15888 10865 19083 10866 19083 10867 19083 10867 19084 10866 19084 10868 19084 10868 19085 10866 19085 10869 19085 10868 19086 10869 19086 10870 19086 10851 19087 10871 19087 10852 19087 10852 19088 10871 19088 10872 19088 10852 8757 10872 8757 10854 8757 10854 19089 10872 19089 10873 19089 10854 19090 10873 19090 10856 19090 10856 19091 10873 19091 10874 19091 10856 19092 10874 19092 10858 19092 10858 19093 10874 19093 10875 19093 10871 19094 10869 19094 10872 19094 10872 19095 10869 19095 10866 19095 10872 19096 10866 19096 10873 19096 10873 8766 10866 8766 10863 8766 10873 19097 10863 19097 10874 19097 10874 19098 10863 19098 10861 19098 10874 19099 10861 19099 10875 19099 10875 8770 10861 8770 10849 8770 10767 8714 10766 8714 10876 8714 10766 19100 10765 19100 10876 19100 10876 19101 10765 19101 10764 19101 10876 19102 10764 19102 10877 19102 10877 19103 10764 19103 10762 19103 10740 19104 10769 19104 10878 19104 10878 19105 10769 19105 10768 19105 10878 19106 10768 19106 10879 19106 10879 19107 10768 19107 10767 19107 10879 15911 10767 15911 10880 15911 10767 19108 10876 19108 10880 19108 10880 19109 10876 19109 10881 19109 10880 19110 10881 19110 10882 19110 10758 19111 10740 19111 10883 19111 10883 19112 10740 19112 10878 19112 10883 19113 10878 19113 10884 19113 10884 19114 10878 19114 10879 19114 10884 19115 10879 19115 10885 19115 10885 19116 10879 19116 10880 19116 10885 19117 10880 19117 10886 19117 10886 19118 10880 19118 10882 19118 10759 632 10809 632 10760 632 10760 632 10809 632 10753 632 10887 19119 10771 19119 10770 19119 10770 19120 10888 19120 10887 19120 10887 19121 10888 19121 10889 19121 10887 19122 10889 19122 10890 19122 10890 19123 10889 19123 10891 19123 10892 19124 10893 19124 10894 19124 10894 19125 10893 19125 10891 19125 10894 19126 10891 19126 10895 19126 10895 19127 10891 19127 10889 19127 10896 19128 10897 19128 10898 19128 10897 19129 10899 19129 10898 19129 10898 19130 10899 19130 10900 19130 10898 19131 10900 19131 10894 19131 10894 19132 10900 19132 10901 19132 10894 19133 10901 19133 10892 19133 10898 19134 10902 19134 10896 19134 10896 8712 10902 8712 10903 8712 10896 19135 10903 19135 10904 19135 10905 19136 10906 19136 10907 19136 10905 19137 10907 19137 10908 19137 10909 19138 10910 19138 10911 19138 10911 19139 10910 19139 10912 19139 10911 19140 10912 19140 10913 19140 10913 19141 10914 19141 10911 19141 10911 19142 10914 19142 10915 19142 10911 19143 10915 19143 10916 19143 10776 8679 10774 8679 10859 8679 10859 15944 10917 15944 10776 15944 10776 19144 10917 19144 10918 19144 10776 19145 10918 19145 10919 19145 10741 19146 10777 19146 10763 19146 10763 19147 10777 19147 10907 19147 10763 19148 10907 19148 10770 19148 10770 19149 10907 19149 10906 19149 10777 19150 10779 19150 10907 19150 10907 19151 10779 19151 10916 19151 10907 19152 10916 19152 10908 19152 10908 15952 10916 15952 10915 15952 10779 19153 10781 19153 10916 19153 10916 19154 10781 19154 10776 19154 10916 19155 10776 19155 10911 19155 10911 19156 10776 19156 10919 19156 10911 19157 10919 19157 10909 19157 10920 19158 10881 19158 10921 19158 10921 19159 10881 19159 10876 19159 10921 19160 10876 19160 10922 19160 10876 19161 10877 19161 10922 19161 10922 19162 10877 19162 10762 19162 10922 19163 10762 19163 10761 19163 10922 19164 10761 19164 10772 19164 10921 19165 10922 19165 10923 19165 10923 19166 10922 19166 10772 19166 10923 19167 10772 19167 10924 19167 10924 19168 10772 19168 10771 19168 10920 19169 10921 19169 10925 19169 10925 19170 10921 19170 10923 19170 10925 19171 10923 19171 10926 19171 10926 19172 10923 19172 10924 19172 10926 19173 10924 19173 10927 19173 10746 632 10788 632 10784 632 10797 19174 10802 19174 10928 19174 10795 19175 10748 19175 10929 19175 10929 19176 10748 19176 10797 19176 10929 19177 10797 19177 10930 19177 10930 19178 10797 19178 10928 19178 10805 19179 10757 19179 10808 19179 10931 19180 10806 19180 10932 19180 10932 19181 10806 19181 10805 19181 10932 19182 10805 19182 10933 19182 10933 19183 10805 19183 10808 19183 10816 19184 10934 19184 10818 19184 10818 19185 10934 19185 10935 19185 10818 19186 10935 19186 10819 19186 10935 19187 10936 19187 10819 19187 10819 19188 10936 19188 10937 19188 10819 19189 10937 19189 10821 19189 10821 19190 10937 19190 10938 19190 10850 19191 10823 19191 10939 19191 10939 19192 10823 19192 10821 19192 10939 19193 10821 19193 10940 19193 10940 15985 10821 15985 10938 15985 10941 19194 10942 19194 10934 19194 10934 19195 10942 19195 10943 19195 10934 19196 10943 19196 10935 19196 10935 19197 10943 19197 10944 19197 10935 19198 10944 19198 10936 19198 10816 19199 10815 19199 10934 19199 10934 19200 10815 19200 10828 19200 10934 19201 10828 19201 10941 19201 10941 19202 10828 19202 10826 19202 10945 19203 10946 19203 10947 19203 10947 19204 10946 19204 10948 19204 10947 19205 10948 19205 10949 19205 10949 19206 10948 19206 10950 19206 10950 19207 10948 19207 10951 19207 10950 19208 10951 19208 10952 19208 10952 19209 10951 19209 10953 19209 10953 19210 10951 19210 10954 19210 10953 19211 10954 19211 10955 19211 10956 19212 10957 19212 10954 19212 10954 8615 10957 8615 10958 8615 10954 19213 10958 19213 10955 19213 10959 19214 10960 19214 10961 19214 10961 19215 10960 19215 10962 19215 10961 19216 10962 19216 10956 19216 10956 19217 10962 19217 10963 19217 10956 19218 10963 19218 10957 19218 10959 19219 10961 19219 10964 19219 10964 19220 10961 19220 10826 19220 10964 19221 10826 19221 10825 19221 10965 19222 10827 19222 10966 19222 10966 19223 10827 19223 10829 19223 10967 19224 10968 19224 10969 19224 10970 19225 10968 19225 10966 19225 10966 19226 10968 19226 10967 19226 10966 19227 10967 19227 10965 19227 10825 19228 10827 19228 10971 19228 10971 19229 10827 19229 10965 19229 10971 19230 10965 19230 10972 19230 10972 19231 10965 19231 10967 19231 10972 19232 10967 19232 10973 19232 10973 19233 10967 19233 10969 19233 10845 19234 10970 19234 10844 19234 10844 19235 10970 19235 10966 19235 10844 19236 10966 19236 10843 19236 10829 19237 10835 19237 10966 19237 10966 19238 10835 19238 10842 19238 10966 19239 10842 19239 10843 19239 10974 19240 10975 19240 10976 19240 10977 19241 10978 19241 10979 19241 10980 19242 10981 19242 10979 19242 10979 19243 10981 19243 10982 19243 10979 19244 10982 19244 10977 19244 10862 19245 10983 19245 10860 19245 10860 19246 10983 19246 10984 19246 10860 19247 10984 19247 10847 19247 10847 19248 10984 19248 10985 19248 10847 19249 10985 19249 10848 19249 10848 19250 10985 19250 10986 19250 10848 16034 10986 16034 10978 16034 10978 19251 10986 19251 10987 19251 10978 16036 10987 16036 10979 16036 10868 19252 10988 19252 10989 19252 10868 19253 10989 19253 10867 19253 10867 19254 10989 19254 10990 19254 10867 19255 10990 19255 10865 19255 10865 19256 10990 19256 10991 19256 10865 19257 10991 19257 10864 19257 10864 19258 10991 19258 10992 19258 10864 19259 10992 19259 10862 19259 10862 19260 10992 19260 10993 19260 10862 19261 10993 19261 10983 19261 10868 19262 10870 19262 10988 19262 10988 19263 10870 19263 10994 19263 10988 19264 10994 19264 10995 19264 10995 19265 10994 19265 10996 19265 10995 19266 10996 19266 10997 19266 10997 19267 10996 19267 10976 19267 10976 19268 10996 19268 10998 19268 10976 19269 10998 19269 10974 19269 10994 19270 10870 19270 10869 19270 10940 19271 10938 19271 10999 19271 10936 19272 10944 19272 11000 19272 11000 19273 10944 19273 10943 19273 11000 19274 10943 19274 11001 19274 11001 19275 10943 19275 10942 19275 10994 19276 11002 19276 10996 19276 10996 19277 11002 19277 11003 19277 10996 19278 11003 19278 10998 19278 11004 19279 11005 19279 11006 19279 11006 19280 11005 19280 11007 19280 11006 19281 11007 19281 11002 19281 11002 19282 11007 19282 11008 19282 11002 19283 11008 19283 11003 19283 10942 19284 11009 19284 11001 19284 11001 19285 11009 19285 11010 19285 11001 19286 11010 19286 11000 19286 11000 19287 11010 19287 11011 19287 11000 19288 11011 19288 11012 19288 11012 19289 11011 19289 11013 19289 11012 19290 11013 19290 11014 19290 11014 19291 11013 19291 11015 19291 11014 19292 11015 19292 11016 19292 10936 19293 11000 19293 11017 19293 11017 19294 11000 19294 11012 19294 11017 19295 11012 19295 11018 19295 11018 19296 11012 19296 11014 19296 11018 19297 11014 19297 11019 19297 11019 19298 11014 19298 11016 19298 11019 19299 11016 19299 11004 19299 11004 19300 11016 19300 11020 19300 11004 19301 11020 19301 11005 19301 10994 19302 11021 19302 11002 19302 11002 19303 11021 19303 11022 19303 11002 19304 11022 19304 11006 19304 11006 19305 11022 19305 11023 19305 11006 19306 11023 19306 11004 19306 11004 19307 11023 19307 10999 19307 11004 19308 10999 19308 11019 19308 11019 19309 10999 19309 10938 19309 11019 19310 10938 19310 11018 19310 11018 19311 10938 19311 10937 19311 11018 19312 10937 19312 11017 19312 11017 19313 10937 19313 10936 19313 10994 19314 10869 19314 11021 19314 11021 16081 10869 16081 10871 16081 11021 19315 10871 19315 11022 19315 11022 19316 10871 19316 10851 19316 11022 19317 10851 19317 11023 19317 11023 19318 10851 19318 10850 19318 11023 19319 10850 19319 10999 19319 10999 19320 10850 19320 10939 19320 10999 19321 10939 19321 10940 19321 11024 19322 11025 19322 11026 19322 10977 19323 10982 19323 11027 19323 10918 19324 11028 19324 10919 19324 10919 19325 11028 19325 11029 19325 10919 19326 11029 19326 10909 19326 11025 19327 10912 19327 10910 19327 10912 19328 11025 19328 10913 19328 10913 19329 11025 19329 11024 19329 10913 19330 11024 19330 11030 19330 10908 19331 10915 19331 11030 19331 11030 19332 10915 19332 10914 19332 11030 8449 10914 8449 10913 8449 11031 19333 11032 19333 11026 19333 11033 19334 11034 19334 11035 19334 11036 19335 11037 19335 11038 19335 11038 19336 11037 19336 11039 19336 11038 19337 11039 19337 11040 19337 11040 19338 11039 19338 11041 19338 11040 19339 11041 19339 11042 19339 11042 19340 11041 19340 11028 19340 11042 19341 11028 19341 11043 19341 11043 19342 11028 19342 10918 19342 11043 19343 10918 19343 10917 19343 10917 19344 10859 19344 11043 19344 11043 8462 10859 8462 11044 8462 11043 19345 11044 19345 11042 19345 11042 19346 11044 19346 11045 19346 11042 19347 11045 19347 11040 19347 11040 19348 11045 19348 11033 19348 11040 19349 11033 19349 11038 19349 11038 19350 11033 19350 11035 19350 11038 19351 11035 19351 11036 19351 10905 19352 10908 19352 11046 19352 11046 19353 10908 19353 11030 19353 11046 19354 11030 19354 11047 19354 11047 19355 11030 19355 11024 19355 11047 19356 11024 19356 11048 19356 11048 19357 11024 19357 11026 19357 11048 19358 11026 19358 11049 19358 11049 19359 11026 19359 11032 19359 11037 19360 11050 19360 11039 19360 11039 19361 11050 19361 11031 19361 11039 19362 11031 19362 11041 19362 11041 19363 11031 19363 11026 19363 11041 19364 11026 19364 11028 19364 11028 19365 11026 19365 11025 19365 11028 19366 11025 19366 11029 19366 11029 19367 11025 19367 10910 19367 11029 19368 10910 19368 10909 19368 10859 19369 10858 19369 11044 19369 11044 19370 10858 19370 10875 19370 11044 19371 10875 19371 11045 19371 11045 19372 10875 19372 10849 19372 11045 19373 10849 19373 11033 19373 11033 19374 10849 19374 10848 19374 11033 19375 10848 19375 11034 19375 11034 19376 10848 19376 10978 19376 11034 19377 10978 19377 11035 19377 11035 19378 10978 19378 10977 19378 11035 19379 10977 19379 11036 19379 11036 19380 10977 19380 11027 19380 11036 19381 11027 19381 11037 19381 11037 19382 11027 19382 11051 19382 11037 19383 11051 19383 11050 19383 10904 98 10903 98 11052 98 11052 19384 10903 19384 11053 19384 11052 98 11053 98 10981 98 10981 98 11053 98 11054 98 10981 98 11054 98 10982 98 11050 16144 11055 16144 11056 16144 11057 19385 10906 19385 10905 19385 10888 19386 10770 19386 10906 19386 10905 19387 11046 19387 11058 19387 11058 19388 11046 19388 11047 19388 11058 8395 11047 8395 11059 8395 11059 19389 11047 19389 11048 19389 11059 19390 11048 19390 11060 19390 11048 19391 11049 19391 11060 19391 11060 19392 11049 19392 11032 19392 11060 19393 11032 19393 11056 19393 11056 19394 11032 19394 11031 19394 11056 19395 11031 19395 11050 19395 10905 19396 11058 19396 11057 19396 11057 19397 11058 19397 11059 19397 11057 19398 11059 19398 11061 19398 11061 19399 11059 19399 11060 19399 11061 19400 11060 19400 11062 19400 11062 19401 11060 19401 11056 19401 11062 19402 11056 19402 11063 19402 11063 19403 11056 19403 11055 19403 11063 19404 11055 19404 11064 19404 10906 19405 11057 19405 10888 19405 10888 19406 11057 19406 11061 19406 10888 19407 11061 19407 10889 19407 10889 19408 11061 19408 11062 19408 10889 19409 11062 19409 10895 19409 10895 19410 11062 19410 11063 19410 10895 19411 11063 19411 10894 19411 10894 19412 11063 19412 11064 19412 10894 19413 11064 19413 10898 19413 11051 19414 11027 19414 11065 19414 11065 19415 11027 19415 11066 19415 11065 19416 11066 19416 11067 19416 11067 19417 11066 19417 11068 19417 11053 19418 11068 19418 11054 19418 11054 19419 11068 19419 11066 19419 11054 19420 11066 19420 10982 19420 10982 19421 11066 19421 11027 19421 11050 19422 11051 19422 11055 19422 11055 19423 11051 19423 11065 19423 11055 19424 11065 19424 11064 19424 11064 19425 11065 19425 11067 19425 11064 19426 11067 19426 10898 19426 10898 19427 11067 19427 11068 19427 10898 19428 11068 19428 10902 19428 10902 19429 11068 19429 11053 19429 10902 19430 11053 19430 10903 19430 11008 19431 11007 19431 11069 19431 11070 19432 11071 19432 11072 19432 11009 19433 11070 19433 11073 19433 11074 19434 11011 19434 11073 19434 11073 19435 11011 19435 11010 19435 11073 19436 11010 19436 11009 19436 11070 19437 11072 19437 11073 19437 11073 19438 11072 19438 11075 19438 11073 19439 11075 19439 11074 19439 11074 19440 11075 19440 11076 19440 11074 19441 11076 19441 11077 19441 11020 19442 11016 19442 11077 19442 11077 19443 11016 19443 11015 19443 11077 16187 11015 16187 11074 16187 11074 19444 11015 19444 11013 19444 11074 19445 11013 19445 11011 19445 11005 19446 11020 19446 11078 19446 11078 19447 11020 19447 11077 19447 11078 19448 11077 19448 11079 19448 11079 19449 11077 19449 11076 19449 11007 19450 11005 19450 11069 19450 11069 19451 11005 19451 11078 19451 11069 19452 11078 19452 11080 19452 11080 19453 11078 19453 11079 19453 11080 19454 11079 19454 10951 19454 10951 19455 11079 19455 11076 19455 10951 19456 11076 19456 10954 19456 10954 19457 11076 19457 11075 19457 10954 19458 11075 19458 10956 19458 10956 19459 11075 19459 11072 19459 10956 19460 11072 19460 10961 19460 10961 19461 11072 19461 11071 19461 10961 19462 11071 19462 10826 19462 10826 19463 11071 19463 11070 19463 10826 19464 11070 19464 10941 19464 10941 19465 11070 19465 11009 19465 10941 19466 11009 19466 10942 19466 11003 19467 11008 19467 11081 19467 11081 19468 11008 19468 11069 19468 11081 19469 11069 19469 11082 19469 11082 19470 11069 19470 11080 19470 11082 19471 11080 19471 10948 19471 10948 19472 11080 19472 10951 19472 10998 19473 11003 19473 11083 19473 11083 19474 11003 19474 11081 19474 11083 19475 11081 19475 11084 19475 11084 19476 11081 19476 11082 19476 11084 19477 11082 19477 10946 19477 10946 19478 11082 19478 10948 19478 10946 106 10945 106 11085 106 11084 106 10946 106 11083 106 11083 19479 10946 19479 11085 19479 11083 19480 11085 19480 10998 19480 10998 8340 11085 8340 10974 8340 11086 7585 11087 7585 11088 7585 11089 19481 11090 19481 11091 19481 11091 7585 11090 7585 11092 7585 11091 19482 11093 19482 11089 19482 11089 7585 11093 7585 11094 7585 11089 19483 11094 19483 11095 19483 11095 19484 11094 19484 11096 19484 11095 7585 11096 7585 11097 7585 11097 19485 11096 19485 11098 19485 11097 7585 11098 7585 11099 7585 11099 7585 11098 7585 11100 7585 11099 19486 11100 19486 11101 19486 11101 7585 11100 7585 11088 7585 11088 7585 11100 7585 11102 7585 11088 7585 11102 7585 11086 7585 11103 7585 11104 7585 11105 7585 11105 7585 11104 7585 11092 7585 11105 19487 11092 19487 11106 19487 11106 7585 11092 7585 11090 7585 10981 19488 10980 19488 11103 19488 10981 16225 11103 16225 11052 16225 11052 19489 11103 19489 11105 19489 11052 19490 11105 19490 11107 19490 10975 19491 10974 19491 11087 19491 11087 8315 10974 8315 11085 8315 11087 19492 11085 19492 11088 19492 11088 19493 11085 19493 11108 19493 11088 19494 11108 19494 11101 19494 11101 19495 11108 19495 11099 19495 11099 19496 11108 19496 11109 19496 11099 19497 11109 19497 11097 19497 11105 19498 11106 19498 11107 19498 11107 16232 11106 16232 11090 16232 11107 19499 11090 19499 11110 19499 11110 19500 11090 19500 11089 19500 11110 19501 11089 19501 11111 19501 11111 19502 11089 19502 11095 19502 11111 19503 11095 19503 11112 19503 11112 19504 11095 19504 11097 19504 11112 19505 11097 19505 11113 19505 11113 19506 11097 19506 11109 19506 11108 19507 11085 19507 10945 19507 10945 19508 11114 19508 11108 19508 11108 19509 11114 19509 11115 19509 11108 19510 11115 19510 11109 19510 11109 19511 11115 19511 11116 19511 11109 19512 11116 19512 11113 19512 11113 19513 11116 19513 11117 19513 11113 19514 11117 19514 11112 19514 10904 19515 11052 19515 11107 19515 11112 8294 11117 8294 11118 8294 11112 19516 11118 19516 11111 19516 11111 19517 11118 19517 11119 19517 11111 19518 11119 19518 11110 19518 11110 19519 11119 19519 11120 19519 11110 16239 11120 16239 11107 16239 11107 19520 11120 19520 11121 19520 11107 19521 11121 19521 10904 19521 10964 19522 10825 19522 11122 19522 11122 19523 10825 19523 10971 19523 11122 19524 10971 19524 10972 19524 10964 19525 11122 19525 10959 19525 10959 19526 11122 19526 11123 19526 10959 19527 11123 19527 10960 19527 10960 19528 11123 19528 11124 19528 10960 19529 11124 19529 10962 19529 10962 19530 11124 19530 11125 19530 10962 19531 11125 19531 10963 19531 10963 19532 11125 19532 11126 19532 10963 19533 11126 19533 10957 19533 10957 19534 11126 19534 10958 19534 10958 19535 11126 19535 11127 19535 10958 19536 11127 19536 10955 19536 10955 19537 11127 19537 11128 19537 10955 19538 11128 19538 10953 19538 10953 19539 11128 19539 11129 19539 10953 19540 11129 19540 10952 19540 10952 19541 11129 19541 11130 19541 10952 19542 11130 19542 10950 19542 10950 19543 11130 19543 11131 19543 10950 19544 11131 19544 10949 19544 10949 19545 11131 19545 11132 19545 10949 19546 11132 19546 10947 19546 10947 19547 11132 19547 11114 19547 10947 19548 11114 19548 10945 19548 11133 19549 11116 19549 11115 19549 11116 19550 11133 19550 11117 19550 11117 19551 11133 19551 11134 19551 11117 19552 11134 19552 11135 19552 11135 19553 11134 19553 11136 19553 11135 19554 11136 19554 11137 19554 11138 19555 11139 19555 11140 19555 11140 19556 11139 19556 11141 19556 11140 19557 11141 19557 11142 19557 11142 19558 11141 19558 11137 19558 11142 19559 11137 19559 11143 19559 11143 19560 11137 19560 11136 19560 11115 19561 11144 19561 11133 19561 11133 19562 11144 19562 11145 19562 11133 8249 11145 8249 11134 8249 11134 19563 11145 19563 11146 19563 11134 19564 11146 19564 11136 19564 11136 19565 11146 19565 11147 19565 11136 19566 11147 19566 11143 19566 11143 19567 11147 19567 11148 19567 11143 19568 11148 19568 11142 19568 11142 19569 11148 19569 11149 19569 11142 19570 11149 19570 11140 19570 11140 19571 11149 19571 11150 19571 11140 19572 11150 19572 11138 19572 11138 19573 11150 19573 11151 19573 11138 16279 11151 16279 11152 16279 11152 19574 11151 19574 11153 19574 11152 19575 11153 19575 11154 19575 11154 19576 11153 19576 11155 19576 11154 19577 11155 19577 11156 19577 11156 19578 11155 19578 11157 19578 11156 19579 11157 19579 10969 19579 10969 19580 11157 19580 10973 19580 11115 19581 11114 19581 11144 19581 11144 19582 11114 19582 11132 19582 11144 19583 11132 19583 11145 19583 11145 19584 11132 19584 11131 19584 11145 19585 11131 19585 11146 19585 11146 19586 11131 19586 11130 19586 11146 19587 11130 19587 11147 19587 11147 19588 11130 19588 11129 19588 11147 19589 11129 19589 11148 19589 11148 19590 11129 19590 11128 19590 11148 19591 11128 19591 11149 19591 11149 19592 11128 19592 11127 19592 11149 19593 11127 19593 11150 19593 11150 19594 11127 19594 11126 19594 11150 19595 11126 19595 11151 19595 11151 19596 11126 19596 11125 19596 11151 19597 11125 19597 11153 19597 11153 19598 11125 19598 11124 19598 11153 19599 11124 19599 11155 19599 11155 19600 11124 19600 11123 19600 11155 19601 11123 19601 11157 19601 11157 19602 11123 19602 11122 19602 11157 19603 11122 19603 10973 19603 10973 19604 11122 19604 10972 19604 11158 19605 11159 19605 11160 19605 11161 19606 11162 19606 11163 19606 11164 19607 11165 19607 11166 19607 11167 8118 11168 8118 11169 8118 11169 19608 11168 19608 11118 19608 11169 19609 11118 19609 11117 19609 11170 19610 10897 19610 11171 19610 11171 19611 10897 19611 10896 19611 11171 19612 10896 19612 11172 19612 11172 19613 10896 19613 10904 19613 11172 19614 10904 19614 11121 19614 10901 19615 10900 19615 11170 19615 11170 19616 10900 19616 10899 19616 11170 19617 10899 19617 10897 19617 10891 19618 10893 19618 11173 19618 11173 19619 10893 19619 10892 19619 11173 19620 10892 19620 11174 19620 11174 19621 10892 19621 10901 19621 11174 19622 10901 19622 11175 19622 11175 19623 10901 19623 11170 19623 10891 19624 11173 19624 10890 19624 10890 19625 11173 19625 11176 19625 10890 19626 11176 19626 10887 19626 10887 19627 11176 19627 11177 19627 10887 19628 11177 19628 11178 19628 11163 19629 11162 19629 11179 19629 11162 19630 11180 19630 11179 19630 11179 19631 11180 19631 11181 19631 11179 19632 11181 19632 11167 19632 11167 19633 11181 19633 11182 19633 11167 19634 11182 19634 11168 19634 10924 19635 11160 19635 10927 19635 10927 19636 11160 19636 11159 19636 10927 19637 11159 19637 11183 19637 11183 19638 11159 19638 11158 19638 11183 19639 11158 19639 11184 19639 11164 19640 11184 19640 11165 19640 11165 19641 11184 19641 11158 19641 11165 19642 11158 19642 11185 19642 11185 19643 11158 19643 11160 19643 11185 19644 11160 19644 11186 19644 11186 19645 11160 19645 10924 19645 11186 19646 10924 19646 10771 19646 11119 19647 11118 19647 11187 19647 11187 19648 11118 19648 11168 19648 11187 19649 11168 19649 11188 19649 11188 19650 11168 19650 11182 19650 11188 19651 11182 19651 11189 19651 11189 19652 11182 19652 11181 19652 11189 19653 11181 19653 11190 19653 11190 19654 11181 19654 11180 19654 11190 19655 11180 19655 11191 19655 11191 19656 11180 19656 11162 19656 11191 19657 11162 19657 11166 19657 11166 19658 11162 19658 11161 19658 11166 19659 11161 19659 11164 19659 11121 19660 11120 19660 11172 19660 11172 19661 11120 19661 11192 19661 11172 19662 11192 19662 11171 19662 11171 19663 11192 19663 11193 19663 11171 19664 11193 19664 11170 19664 11170 19665 11193 19665 11194 19665 11170 19666 11194 19666 11175 19666 11175 19667 11194 19667 11195 19667 11175 19668 11195 19668 11174 19668 11174 19669 11195 19669 11196 19669 11174 19670 11196 19670 11173 19670 11173 19671 11196 19671 11197 19671 11173 19672 11197 19672 11176 19672 11176 19673 11197 19673 11198 19673 11176 19674 11198 19674 11177 19674 11177 19675 11198 19675 11199 19675 11177 19676 11199 19676 11178 19676 10771 19677 10887 19677 11186 19677 11186 19678 10887 19678 11178 19678 11186 19679 11178 19679 11185 19679 11185 19680 11178 19680 11199 19680 11185 19681 11199 19681 11165 19681 11165 19682 11199 19682 11198 19682 11165 16367 11198 16367 11166 16367 11166 19683 11198 19683 11197 19683 11166 19684 11197 19684 11191 19684 11191 19685 11197 19685 11196 19685 11191 19686 11196 19686 11190 19686 11190 19687 11196 19687 11195 19687 11190 19688 11195 19688 11189 19688 11189 19689 11195 19689 11194 19689 11189 19690 11194 19690 11188 19690 11188 19691 11194 19691 11193 19691 11188 19692 11193 19692 11187 19692 11187 19693 11193 19693 11192 19693 11187 19694 11192 19694 11119 19694 11119 19695 11192 19695 11120 19695 11137 19696 11141 19696 11200 19696 11139 19697 11138 19697 11201 19697 11138 19698 11152 19698 11201 19698 11201 19699 11152 19699 11154 19699 11201 19700 11154 19700 11202 19700 11202 19701 11154 19701 11156 19701 11202 19702 11156 19702 11203 19702 11203 19703 11156 19703 10969 19703 11203 19704 10969 19704 11204 19704 11204 19705 10969 19705 10968 19705 11204 19706 10968 19706 10970 19706 11163 19707 11179 19707 11205 19707 11205 19708 11179 19708 11167 19708 11205 19709 11167 19709 11135 19709 11135 19710 11167 19710 11169 19710 11135 19711 11169 19711 11117 19711 11164 19712 11206 19712 11184 19712 11184 19713 11206 19713 11207 19713 11184 19714 11207 19714 11183 19714 11183 19715 11207 19715 11208 19715 11183 19716 11208 19716 10927 19716 11164 19717 11161 19717 11206 19717 11206 19718 11161 19718 11163 19718 11206 19719 11163 19719 11209 19719 11209 19720 11163 19720 11205 19720 11209 19721 11205 19721 11200 19721 11200 16399 11205 16399 11135 16399 11200 19722 11135 19722 11137 19722 11210 19723 10920 19723 10925 19723 11210 19724 10925 19724 11208 19724 11208 19725 10925 19725 10926 19725 11208 16403 10926 16403 10927 16403 11139 19726 11201 19726 11141 19726 11141 19727 11201 19727 11211 19727 11141 19728 11211 19728 11200 19728 11200 19729 11211 19729 11212 19729 11200 19730 11212 19730 11209 19730 11213 19731 11214 19731 11215 19731 10808 19732 10814 19732 11216 19732 10792 19733 10793 19733 11217 19733 10794 19734 10795 19734 11218 19734 11218 19735 10795 19735 10929 19735 11218 19736 10929 19736 10930 19736 10792 19737 11217 19737 10791 19737 10840 19738 10785 19738 10784 19738 10788 19739 10787 19739 10784 19739 10784 19740 10787 19740 11219 19740 10784 19741 11219 19741 10840 19741 11220 19742 10836 19742 11219 19742 11219 19743 10836 19743 10846 19743 11219 19744 10846 19744 10840 19744 11204 19745 10970 19745 11221 19745 11221 19746 10970 19746 10845 19746 11221 19747 10845 19747 10837 19747 11204 19748 11221 19748 11203 19748 11203 19749 11221 19749 11222 19749 11203 19750 11222 19750 11202 19750 11223 19751 11211 19751 11222 19751 11222 19752 11211 19752 11201 19752 11222 19753 11201 19753 11202 19753 11224 19754 11206 19754 11225 19754 11225 19755 11206 19755 11209 19755 11225 19756 11209 19756 11223 19756 11223 19757 11209 19757 11212 19757 11223 19758 11212 19758 11211 19758 11226 19759 11208 19759 11224 19759 11224 19760 11208 19760 11207 19760 11224 19761 11207 19761 11206 19761 10881 19762 11226 19762 10882 19762 10882 19763 11226 19763 10886 19763 10881 19764 10920 19764 11226 19764 11226 19765 10920 19765 11210 19765 11226 19766 11210 19766 11208 19766 10812 19767 10810 19767 11227 19767 11227 19768 10810 19768 10809 19768 11227 19769 10809 19769 10759 19769 10759 19770 10758 19770 11227 19770 11227 19771 10758 19771 10883 19771 11227 19772 10883 19772 10884 19772 10933 19773 10808 19773 10932 19773 10932 19774 10808 19774 11216 19774 10932 19775 11216 19775 10931 19775 10931 8002 11216 8002 11228 8002 11215 16441 11214 16441 11229 16441 11214 19776 11230 19776 11229 19776 11229 19777 11230 19777 11231 19777 11229 19778 11231 19778 11216 19778 11216 8007 11231 8007 11232 8007 11216 19779 11232 19779 11228 19779 11213 19780 11215 19780 11233 19780 11233 19781 11215 19781 11234 19781 11233 19782 11234 19782 11235 19782 11235 19783 11234 19783 11236 19783 11235 19784 11236 19784 11237 19784 11237 19785 11236 19785 11238 19785 11238 19786 11236 19786 11239 19786 11238 19787 11239 19787 11240 19787 11240 19788 11239 19788 11241 19788 11241 19789 11239 19789 11242 19789 11241 19790 11242 19790 11243 19790 11243 19791 11242 19791 11244 19791 11244 8021 11242 8021 11218 8021 11244 19792 11218 19792 11245 19792 11245 19793 11218 19793 10930 19793 11245 19794 10930 19794 10928 19794 10814 19795 10813 19795 11216 19795 11216 19796 10813 19796 11246 19796 11216 19797 11246 19797 11229 19797 11229 19798 11246 19798 11247 19798 11229 19799 11247 19799 11215 19799 11215 19800 11247 19800 11248 19800 11215 19801 11248 19801 11234 19801 11234 19802 11248 19802 11249 19802 11234 19803 11249 19803 11236 19803 11236 19804 11249 19804 11250 19804 11236 19805 11250 19805 11239 19805 11239 19806 11250 19806 11251 19806 11239 19807 11251 19807 11242 19807 11242 19808 11251 19808 11252 19808 11242 19809 11252 19809 11218 19809 11218 19810 11252 19810 11217 19810 11218 19811 11217 19811 10794 19811 10794 19812 11217 19812 10793 19812 10813 19813 10812 19813 11246 19813 11246 19814 10812 19814 11227 19814 11246 19815 11227 19815 11247 19815 11247 19816 11227 19816 11253 19816 11247 19817 11253 19817 11248 19817 11248 19818 11253 19818 11254 19818 11248 19819 11254 19819 11249 19819 11249 19820 11254 19820 11255 19820 11249 19821 11255 19821 11250 19821 11250 19822 11255 19822 11256 19822 11250 19823 11256 19823 11251 19823 11251 16476 11256 16476 11257 16476 11251 19824 11257 19824 11252 19824 11252 19825 11257 19825 11220 19825 11252 19826 11220 19826 11217 19826 11217 19827 11220 19827 11219 19827 11217 19828 11219 19828 10791 19828 10791 19829 11219 19829 10787 19829 10884 19830 10885 19830 11227 19830 11227 19831 10885 19831 10886 19831 11227 19832 10886 19832 11253 19832 11253 19833 10886 19833 11226 19833 11253 19834 11226 19834 11254 19834 11254 19835 11226 19835 11224 19835 11254 19836 11224 19836 11255 19836 11255 16487 11224 16487 11225 16487 11255 19837 11225 19837 11256 19837 11256 19838 11225 19838 11223 19838 11256 19839 11223 19839 11257 19839 11257 19840 11223 19840 11222 19840 11257 19841 11222 19841 11220 19841 11220 19842 11222 19842 11221 19842 11220 19843 11221 19843 10836 19843 10836 19844 11221 19844 10837 19844 10804 19845 10806 19845 10372 19845 10372 19846 10806 19846 10931 19846 10372 19847 10931 19847 11228 19847 10372 19848 10370 19848 10804 19848 10804 19849 10370 19849 10368 19849 10804 19850 10368 19850 10798 19850 10798 16496 10368 16496 10367 16496 10798 7929 10367 7929 10799 7929 10799 7930 10367 7930 10388 7930 10799 16497 10388 16497 10800 16497 10800 19851 10388 19851 10386 19851 10800 19852 10386 19852 10801 19852 11245 19853 10928 19853 10802 19853 10801 19854 10386 19854 10802 19854 10802 19855 10386 19855 10384 19855 10802 19856 10384 19856 11245 19856 10382 19857 11243 19857 10384 19857 10384 19858 11243 19858 11244 19858 10384 19859 11244 19859 11245 19859 10380 19860 11240 19860 10382 19860 10382 19861 11240 19861 11241 19861 10382 7943 11241 7943 11243 7943 10378 19862 11237 19862 10380 19862 10380 19863 11237 19863 11238 19863 10380 19864 11238 19864 11240 19864 10376 19865 11233 19865 10378 19865 10378 19866 11233 19866 11235 19866 10378 19867 11235 19867 11237 19867 10374 19868 11214 19868 10376 19868 10376 19869 11214 19869 11213 19869 10376 19870 11213 19870 11233 19870 11228 19871 11232 19871 10372 19871 10372 16510 11232 16510 11231 16510 10372 19872 11231 19872 10374 19872 10374 19873 11231 19873 11230 19873 10374 7957 11230 7957 11214 7957 10371 632 10381 632 10369 632 10369 19874 10381 19874 10383 19874 10377 632 10379 632 10375 632 10375 19875 10379 19875 10381 19875 10375 632 10381 632 10373 632 10373 632 10381 632 10371 632 10389 632 10366 632 10387 632 10387 632 10366 632 10369 632 10387 19876 10369 19876 10385 19876 10385 19877 10369 19877 10383 19877 10773 95 10345 95 9290 95 10857 19878 10859 19878 10774 19878 10824 95 9290 95 10361 95 10361 95 9290 95 9289 95 10774 95 10773 95 10857 95 10857 95 10773 95 9290 95 10857 95 9290 95 10855 95 10855 95 9290 95 10824 95 10855 95 10824 95 10853 95 10853 95 10824 95 10823 95 10853 19879 10823 19879 10850 19879 10281 7897 10687 7897 10252 7897 10252 19880 10687 19880 10253 19880 10276 19881 10275 19881 10692 19881 10692 19882 10275 19882 10259 19882 10692 19883 10259 19883 10688 19883 10688 19884 10259 19884 10257 19884 10688 19885 10257 19885 10687 19885 10687 19886 10257 19886 10255 19886 10687 19887 10255 19887 10253 19887 10276 19888 10692 19888 10278 19888 10278 19889 10692 19889 10691 19889 10278 19890 10691 19890 10280 19890 10280 19891 10691 19891 10690 19891 10280 19892 10690 19892 10244 19892 10244 16526 10690 16526 10683 16526 10244 19893 10683 19893 10245 19893 10695 19894 10242 19894 10694 19894 10694 19895 10242 19895 10245 19895 10694 19896 10245 19896 10682 19896 10682 7916 10245 7916 10683 7916 10351 19897 10350 19897 10349 19897 10281 19898 10351 19898 10778 19898 10778 19899 10351 19899 10349 19899 10778 19900 10349 19900 10780 19900 10780 19901 10349 19901 10348 19901 10780 19902 10348 19902 10782 19902 10782 19903 10348 19903 10347 19903 10782 19904 10347 19904 10783 19904 10783 19905 10347 19905 10353 19905 10783 19906 10353 19906 10775 19906 10345 19907 10773 19907 10346 19907 10346 19908 10773 19908 10775 19908 10346 19909 10775 19909 10352 19909 10352 19910 10775 19910 10353 19910 10824 19911 10361 19911 10362 19911 10824 19912 10362 19912 10822 19912 10822 19913 10362 19913 10365 19913 10822 19914 10365 19914 10820 19914 10820 19915 10365 19915 10364 19915 10820 19916 10364 19916 10817 19916 10817 19917 10364 19917 10363 19917 10817 19918 10363 19918 10360 19918 10360 19919 10359 19919 10817 19919 10817 19920 10359 19920 10358 19920 10817 19921 10358 19921 10320 19921 10624 19922 10604 19922 10707 19922 10707 19923 10604 19923 10602 19923 10707 19924 10602 19924 10600 19924 10734 19925 10738 19925 10568 19925 10624 19926 10707 19926 10592 19926 10592 19927 10707 19927 10706 19927 10592 19928 10706 19928 10568 19928 10568 19929 10706 19929 10735 19929 10568 19930 10735 19930 10734 19930 10301 19931 10299 19931 10717 19931 10717 19932 10299 19932 10568 19932 10717 19933 10568 19933 10718 19933 10718 19934 10568 19934 10738 19934 10633 19935 10640 19935 10607 19935 10607 19936 10640 19936 10639 19936 10607 19937 10639 19937 10655 19937 10654 19938 10599 19938 10655 19938 10655 19939 10599 19939 10608 19939 10655 19940 10608 19940 10607 19940 10695 19941 10696 19941 11258 19941 11258 19942 10696 19942 10697 19942 11258 19943 10697 19943 10698 19943 10600 19944 10599 19944 10707 19944 10707 19945 10599 19945 10654 19945 10707 19946 10654 19946 10713 19946 10713 19947 10654 19947 10660 19947 10713 19948 10660 19948 10704 19948 10704 19949 10660 19949 10658 19949 10704 19950 10658 19950 10698 19950 10698 19951 10658 19951 10673 19951 10698 19952 10673 19952 11258 19952 10242 19953 10695 19953 10233 19953 10233 19954 10695 19954 11258 19954 10233 16579 11258 16579 10234 16579 10234 19955 11258 19955 11259 19955 10234 19956 11259 19956 11260 19956 10464 19957 10236 19957 11261 19957 11261 19958 10236 19958 10234 19958 11261 19959 10234 19959 11262 19959 11262 19960 10234 19960 11260 19960 10571 19961 10284 19961 10569 19961 10569 19962 10284 19962 10283 19962 10569 19963 10283 19963 10434 19963 10571 19964 10574 19964 10284 19964 10284 19965 10574 19965 10573 19965 10284 19966 10573 19966 10299 19966 10299 19967 10573 19967 10566 19967 10299 19968 10566 19968 10568 19968 10815 19969 10320 19969 10830 19969 10830 19970 10320 19970 10731 19970 10830 19971 10731 19971 10786 19971 10786 98 10731 98 10744 98 10354 98 1392 98 10320 98 10354 98 10320 98 10358 98 10351 106 10281 106 10344 106 10344 106 10281 106 1412 106 728 98 719 98 4320 98 4320 98 719 98 9497 98 10183 19972 10182 19972 585 19972 585 19973 10182 19973 10397 19973 585 19974 10397 19974 10406 19974 927 98 585 98 10294 98 10294 19975 585 19975 10406 19975 10294 19976 10406 19976 10295 19976 10295 19977 10406 19977 10408 19977 10202 98 10195 98 4320 98 4320 19978 10195 19978 10194 19978 10137 19979 9497 19979 10224 19979 10224 98 9497 98 719 98 10224 19980 719 19980 6628 19980 6628 19981 719 19981 718 19981 10104 19982 10183 19982 10205 19982 10205 19983 10183 19983 585 19983 10205 98 585 98 10194 98 10194 98 585 98 581 98 10194 98 581 98 4320 98 10202 98 4320 98 10203 98 10203 98 4320 98 9497 98 10203 98 9497 98 9465 98 9465 98 9497 98 9496 98 9465 98 9496 98 9466 98 927 95 10294 95 740 95 740 95 10294 95 10293 95 740 95 10293 95 741 95 142 95 141 95 10226 95 10226 95 141 95 891 95 9359 106 9358 106 9365 106 9365 106 9358 106 9512 106 9337 19984 9336 19984 9513 19984 9513 7816 9336 7816 9362 7816 9513 7817 9362 7817 9514 7817 9514 19985 9362 19985 9363 19985 9514 19986 9363 19986 9512 19986 9512 19987 9363 19987 9365 19987 9824 98 11263 98 9307 98 9630 19988 9818 19988 9305 19988 9818 19989 9820 19989 9305 19989 9305 19990 9820 19990 9821 19990 9305 98 9821 98 9307 98 9307 19991 9821 19991 9823 19991 9307 19992 9823 19992 9824 19992 9305 19993 9986 19993 9988 19993 9988 98 9992 98 9305 98 9305 19994 9992 19994 9990 19994 9305 98 9990 98 9630 98 9630 98 9990 98 9629 98 9630 98 9629 98 9631 98 9629 98 9624 98 9631 98 9631 19995 9624 19995 9622 19995 9631 98 9622 98 9609 98 9609 19996 9622 19996 9621 19996 9609 98 9621 98 9610 98 9306 106 9979 106 9304 106 9304 19997 9979 19997 9978 19997 9304 19998 9978 19998 9977 19998 9308 95 9970 95 9973 95 9982 95 9306 95 9984 95 9984 95 9306 95 9308 95 9984 95 9308 95 9975 95 9975 95 9308 95 9973 95 9982 95 9981 95 9306 95 9306 95 9981 95 9980 95 9306 95 9980 95 9979 95 9971 106 9970 106 9308 106 9309 106 11264 106 10054 106 10054 106 10053 106 9309 106 9309 19999 10053 19999 10069 19999 9309 106 10069 106 9308 106 9308 20000 10069 20000 10071 20000 9848 106 9864 106 9856 106 9856 20001 9864 20001 9835 20001 10071 20002 10073 20002 9308 20002 9308 20003 10073 20003 10075 20003 9308 20004 10075 20004 9971 20004 9971 20005 10075 20005 9846 20005 9971 106 9846 106 9856 106 9856 20006 9846 20006 9848 20006 9835 20007 9849 20007 9856 20007 9856 106 9849 106 9851 106 9856 106 9851 106 9854 106 9826 20008 11265 20008 9825 20008 9825 20009 11265 20009 11263 20009 9825 20010 11263 20010 9824 20010 9831 20011 10391 20011 9827 20011 9827 20012 10391 20012 11266 20012 9827 20013 11266 20013 9826 20013 9826 20014 11266 20014 11267 20014 9826 20015 11267 20015 11265 20015 10054 20016 11264 20016 10055 20016 10055 20017 11264 20017 11268 20017 10055 20018 11268 20018 10064 20018 11268 20019 11269 20019 11270 20019 11268 20020 11270 20020 10064 20020 10064 20021 11270 20021 10395 20021 10064 20022 10395 20022 10065 20022 10988 20023 9300 20023 10989 20023 10989 20024 9300 20024 9299 20024 10989 20025 9299 20025 10990 20025 10988 20026 10995 20026 9300 20026 9300 20027 10995 20027 10997 20027 9300 16640 10997 16640 9301 16640 9301 20028 10997 20028 10976 20028 9301 20029 10976 20029 10975 20029 9303 20030 9302 20030 10983 20030 10983 20031 10993 20031 9303 20031 9303 20032 10993 20032 10992 20032 9303 20033 10992 20033 9299 20033 9299 20034 10992 20034 10991 20034 9299 20035 10991 20035 10990 20035 10987 20036 10986 20036 9295 20036 9295 20037 10986 20037 10985 20037 9295 20038 10985 20038 9302 20038 9302 20039 10985 20039 10984 20039 9302 20040 10984 20040 10983 20040 10987 20041 9295 20041 10979 20041 10979 20042 9295 20042 9294 20042 10979 20043 9294 20043 10980 20043 11093 20044 9292 20044 11094 20044 11094 20045 9292 20045 9291 20045 11094 16655 9291 16655 11096 16655 11096 20046 9291 20046 9298 20046 11096 20047 9298 20047 11098 20047 11098 7762 9298 7762 9297 7762 11098 20048 9297 20048 11100 20048 11100 20048 9297 20048 9296 20048 11100 20049 9296 20049 11102 20049 11102 20050 9296 20050 9301 20050 11102 20051 9301 20051 11086 20051 11086 20052 9301 20052 10975 20052 11086 20053 10975 20053 11087 20053 11103 20054 10980 20054 11104 20054 11104 20055 10980 20055 9294 20055 11104 20056 9294 20056 11092 20056 11092 20057 9294 20057 9292 20057 11092 20058 9292 20058 11091 20058 11091 16667 9292 16667 11093 16667 4345 20059 7310 20059 4329 20059 4348 20060 11271 20060 4349 20060 4349 20061 11271 20061 4350 20061 7310 20062 4345 20062 7309 20062 7309 20063 4345 20063 4346 20063 7309 20064 4346 20064 7241 20064 4347 20065 6751 20065 4346 20065 4346 20066 6751 20066 6752 20066 4346 20067 6752 20067 7241 20067 4347 20068 4350 20068 6751 20068 6751 20069 4350 20069 11271 20069 6751 20070 11271 20070 11272 20070 11272 20071 11271 20071 4348 20071 11272 20072 4348 20072 570 20072 11273 20073 6737 20073 6739 20073 11274 20074 4288 20074 11275 20074 11275 20075 4288 20075 4290 20075 11275 20076 4290 20076 11276 20076 11276 20077 4290 20077 4292 20077 11276 20078 4292 20078 11277 20078 11277 20079 4292 20079 4293 20079 11277 20080 4293 20080 11273 20080 570 20081 575 20081 11272 20081 11272 20082 575 20082 568 20082 11272 20083 568 20083 11278 20083 11278 20084 568 20084 567 20084 11278 20085 567 20085 11274 20085 11274 20086 567 20086 4289 20086 11274 20087 4289 20087 4288 20087 11273 20088 6739 20088 11277 20088 11277 20089 6739 20089 6741 20089 11277 20090 6741 20090 11276 20090 11276 20091 6741 20091 6744 20091 11276 20092 6744 20092 11275 20092 11275 20093 6744 20093 6746 20093 11275 20094 6746 20094 11274 20094 11274 20095 6746 20095 6748 20095 11274 20096 6748 20096 11278 20096 11278 20097 6748 20097 6749 20097 11278 20098 6749 20098 11272 20098 11272 20099 6749 20099 6750 20099 11272 20100 6750 20100 6751 20100 4301 20101 7308 20101 11279 20101 11280 20102 11281 20102 4295 20102 4295 20103 11281 20103 11282 20103 4295 20104 11282 20104 4296 20104 4293 20105 4296 20105 11273 20105 11273 20106 4296 20106 11282 20106 11273 20107 11282 20107 6737 20107 4295 20108 4305 20108 11280 20108 11280 20109 4305 20109 4303 20109 11280 20110 4303 20110 11283 20110 11283 20111 4303 20111 4302 20111 11283 20112 4302 20112 11284 20112 11284 20113 4302 20113 4297 20113 11284 20114 4297 20114 11279 20114 11279 20115 4297 20115 4299 20115 11279 20116 4299 20116 4301 20116 6737 20117 11282 20117 7053 20117 7053 20118 11282 20118 11281 20118 7053 20119 11281 20119 7054 20119 7054 20120 11281 20120 11280 20120 7054 20121 11280 20121 7055 20121 7055 20122 11280 20122 11283 20122 7055 20123 11283 20123 7051 20123 7051 20124 11283 20124 11284 20124 7051 20125 11284 20125 7052 20125 7052 20126 11284 20126 11279 20126 7052 20127 11279 20127 7050 20127 7050 20128 11279 20128 7308 20128 7050 20129 7308 20129 7049 20129 4319 7585 4320 7585 581 7585 581 7585 583 7585 4318 7585 581 7585 4318 7585 4319 7585 557 20130 951 20130 952 20130 952 98 1272 98 11285 98 11286 98 11287 98 557 98 6664 98 558 98 4266 98 4266 98 558 98 557 98 4266 98 557 98 4267 98 4267 20131 557 20131 11287 20131 11285 98 11288 98 952 98 952 20132 11288 20132 11289 20132 952 20133 11289 20133 11290 20133 11286 98 557 98 11291 98 11291 20134 557 20134 952 20134 11291 98 952 98 11292 98 11292 98 952 98 11290 98 11292 20135 11290 20135 11293 20135 4131 106 4278 106 1273 106 1273 106 4278 106 11294 106 1273 106 11294 106 11295 106 11296 20136 11297 20136 11298 20136 11299 20137 11300 20137 11301 20137 11297 20138 11302 20138 11298 20138 11298 20139 11302 20139 11303 20139 11298 20140 11303 20140 11294 20140 11294 20141 11303 20141 11304 20141 11294 20142 11304 20142 11295 20142 11299 106 11301 106 11298 106 11298 20143 11301 20143 11305 20143 11298 20144 11305 20144 11296 20144 6926 98 6924 98 1286 98 6869 20145 4279 20145 1287 20145 1286 98 1461 98 6904 98 6920 20146 6918 20146 1287 20146 6918 20147 6916 20147 1287 20147 1287 20148 6916 20148 6915 20148 1287 20149 6915 20149 6869 20149 1286 20150 6924 20150 1287 20150 1287 20151 6924 20151 6922 20151 1287 20152 6922 20152 6920 20152 6904 98 6912 98 1286 98 1286 20153 6912 20153 6910 20153 1286 98 6910 98 6908 98 6908 98 6906 98 1286 98 1286 20154 6906 20154 6927 20154 1286 20155 6927 20155 6926 20155 625 20156 623 20156 1238 20156 11306 20157 2125 20157 2532 20157 1238 95 1350 95 625 95 625 20158 1350 20158 1351 20158 625 20159 1351 20159 11306 20159 11306 95 1351 95 1608 95 11306 20160 1608 20160 2125 20160 796 95 795 95 11307 95 2532 20161 2529 20161 11306 20161 11306 20162 2529 20162 2531 20162 11306 95 2531 95 11307 95 11307 20163 2531 20163 791 20163 11307 95 791 95 796 95 4298 95 877 95 879 95 4298 95 879 95 4300 95 879 20164 881 20164 4300 20164 4300 20165 881 20165 883 20165 4300 20166 883 20166 628 20166 628 20167 883 20167 1338 20167 628 20168 1338 20168 649 20168 877 20169 4298 20169 875 20169 875 95 4298 95 4304 95 875 20170 4304 20170 873 20170 873 95 4304 95 4294 95 873 95 4294 95 4291 95 856 95 867 95 4287 95 4287 95 867 95 869 95 4287 20171 869 20171 4291 20171 4291 95 869 95 871 95 4291 95 871 95 873 95 1642 95 4306 95 1643 95 1643 20172 4306 20172 1641 20172 1642 20173 1646 20173 4306 20173 4306 95 1646 95 1648 95 4306 95 1648 95 4312 95 1648 20174 1650 20174 4312 20174 4312 20175 1650 20175 1652 20175 4312 95 1652 95 4310 95 4310 95 1652 95 1657 95 4310 95 1657 95 1656 95 279 7585 252 7585 4168 7585 4168 20176 252 20176 4169 20176 4166 95 278 95 4165 95 4165 95 278 95 279 95 4165 95 279 95 4168 95 4169 20177 252 20177 1786 20177 1786 20178 252 20178 251 20178 4155 20179 11308 20179 4156 20179 4156 20180 11308 20180 4157 20180 11309 20181 9276 20181 4157 20181 4157 20182 11308 20182 11309 20182 11309 20183 11308 20183 8244 20183 11309 20184 8244 20184 9278 20184 9279 95 9276 95 9280 95 9280 20185 9276 20185 11309 20185 9280 20186 11309 20186 9281 20186 9281 20187 11309 20187 9278 20187 9281 95 9278 95 9277 95 4155 20188 4154 20188 11308 20188 11308 20189 4154 20189 4153 20189 11308 20190 4153 20190 8260 20190 8260 20191 8241 20191 11308 20191 11308 20192 8241 20192 8240 20192 11308 20193 8240 20193 8244 20193 272 20194 4158 20194 258 20194 258 20195 4158 20195 4157 20195 271 20196 273 20196 4162 20196 4162 20197 4161 20197 271 20197 271 20198 4161 20198 4160 20198 271 20199 4160 20199 272 20199 272 20200 4160 20200 4159 20200 272 20201 4159 20201 4158 20201 4148 20202 4145 20202 8366 20202 8366 20203 4145 20203 4146 20203 8366 20204 4146 20204 8367 20204 8367 20205 4146 20205 4147 20205 4148 20206 8366 20206 4149 20206 4149 20207 8366 20207 8365 20207 4149 20208 8365 20208 4143 20208 4143 20209 8365 20209 4144 20209 4144 20210 8365 20210 8364 20210 4144 20211 8364 20211 4152 20211 11310 20212 9272 20212 9271 20212 11311 20213 11312 20213 11313 20213 11311 20214 11313 20214 11314 20214 9271 20215 11315 20215 11310 20215 11310 20216 11315 20216 11316 20216 11310 20217 11316 20217 11317 20217 11317 20218 11316 20218 11314 20218 11317 20219 11314 20219 11318 20219 11318 20220 11314 20220 11313 20220 11319 20221 8687 20221 8688 20221 9274 20222 9273 20222 11320 20222 11320 20223 9273 20223 9272 20223 11320 20224 9272 20224 11310 20224 11320 20225 11321 20225 9274 20225 9274 20226 11321 20226 11322 20226 9274 20227 11322 20227 9275 20227 9275 20228 11322 20228 11323 20228 9275 20229 11323 20229 8691 20229 8691 20230 11323 20230 8690 20230 11324 20231 11325 20231 11326 20231 11326 20232 11325 20232 11327 20232 11326 20233 11327 20233 11328 20233 11328 20234 11327 20234 11329 20234 11328 20235 11329 20235 11330 20235 11313 20236 11312 20236 11329 20236 11329 20237 11312 20237 11331 20237 11329 20238 11331 20238 11330 20238 11319 20239 8688 20239 11332 20239 11332 20240 8688 20240 8689 20240 11332 20241 8689 20241 11333 20241 8686 20242 8687 20242 11334 20242 11334 20243 8687 20243 11319 20243 11334 20244 11319 20244 11335 20244 11335 20245 11319 20245 11332 20245 11335 20246 11332 20246 11336 20246 11336 20247 11332 20247 11333 20247 11336 20248 11333 20248 11337 20248 11325 20249 11338 20249 11327 20249 11327 20250 11338 20250 11339 20250 11327 20251 11339 20251 11329 20251 11329 20252 11339 20252 11340 20252 11329 20253 11340 20253 11313 20253 11313 20254 11340 20254 11318 20254 11317 20255 11318 20255 11341 20255 11341 20256 11318 20256 11340 20256 11341 20257 11340 20257 11342 20257 11342 20258 11340 20258 11339 20258 11342 20259 11339 20259 11337 20259 11337 20260 11339 20260 11338 20260 11337 20261 11338 20261 11336 20261 11336 20262 11338 20262 11325 20262 11336 20263 11325 20263 11335 20263 11335 20264 11325 20264 11324 20264 11335 20265 11324 20265 11334 20265 8689 20266 8690 20266 11333 20266 11333 20267 8690 20267 11323 20267 11333 20268 11323 20268 11337 20268 11337 20269 11323 20269 11322 20269 11337 20270 11322 20270 11342 20270 11342 20271 11322 20271 11321 20271 11342 20272 11321 20272 11341 20272 11341 20273 11321 20273 11320 20273 11341 20274 11320 20274 11317 20274 11317 20275 11320 20275 11310 20275 4162 7585 273 7585 4163 7585 4163 7585 273 7585 274 7585 4163 20276 274 20276 4164 20276 4164 20277 274 20277 275 20277 4164 20278 275 20278 4139 20278 4139 20279 275 20279 269 20279 4139 20280 269 20280 4167 20280 4167 20281 269 20281 278 20281 4167 20282 278 20282 4166 20282 11343 20283 11344 20283 9282 20283 9282 20284 11344 20284 11345 20284 7844 20285 8418 20285 7845 20285 7845 20286 8418 20286 11346 20286 7845 20287 11346 20287 7842 20287 7842 20288 11346 20288 11343 20288 7842 20289 11343 20289 7843 20289 7843 20290 11343 20290 9282 20290 8607 20291 11347 20291 8608 20291 8608 20292 11347 20292 8591 20292 11347 20293 11348 20293 8591 20293 8591 20294 11348 20294 11349 20294 8591 20295 11349 20295 8592 20295 8592 20296 11349 20296 8620 20296 8571 20297 8569 20297 8565 20297 8565 20298 8569 20298 11350 20298 8565 20299 11350 20299 8499 20299 8418 20300 8496 20300 11351 20300 11351 20301 8496 20301 8495 20301 8495 20302 8493 20302 11351 20302 11351 20303 8493 20303 8492 20303 11351 20304 8492 20304 8499 20304 11352 20305 11353 20305 11354 20305 11354 20306 11353 20306 11355 20306 8418 20307 11351 20307 11346 20307 11346 20308 11351 20308 11354 20308 11346 20309 11354 20309 11343 20309 11343 20310 11354 20310 11355 20310 11343 20311 11355 20311 11344 20311 11348 20312 11356 20312 11352 20312 11356 20313 11348 20313 11357 20313 11357 20314 11348 20314 11347 20314 11357 20315 11347 20315 11358 20315 11358 20316 11347 20316 8607 20316 11358 20317 8607 20317 9287 20317 11352 20318 11354 20318 11348 20318 11348 20319 11354 20319 11351 20319 11348 20320 11351 20320 11349 20320 11349 20321 11351 20321 8499 20321 11349 20322 8499 20322 8620 20322 8620 20323 8499 20323 11350 20323 8620 20324 11350 20324 8574 20324 8574 20325 11350 20325 8569 20325 8574 20326 8569 20326 8567 20326 11326 20327 11328 20327 11359 20327 9288 20328 8686 20328 11334 20328 9288 20329 11334 20329 11359 20329 11359 20330 11334 20330 11324 20330 11359 20331 11324 20331 11326 20331 4272 20332 4274 20332 11360 20332 4269 20333 4268 20333 11361 20333 11294 20334 4278 20334 4277 20334 11362 20335 1274 20335 1273 20335 1284 20336 1283 20336 11363 20336 11363 20337 1283 20337 1274 20337 1277 20338 1285 20338 11364 20338 11364 20339 1285 20339 1284 20339 4274 20340 4269 20340 11360 20340 11360 20341 4269 20341 11361 20341 11360 20342 11361 20342 11365 20342 11365 20343 11361 20343 11366 20343 11366 20344 11367 20344 11365 20344 11365 20345 11367 20345 11368 20345 11365 20346 11368 20346 11369 20346 11368 20347 11370 20347 11369 20347 11369 20348 11370 20348 11371 20348 11369 20349 11371 20349 11372 20349 11372 20350 11371 20350 11373 20350 11372 20351 11373 20351 11374 20351 11373 20352 11375 20352 11374 20352 11374 20353 11375 20353 11376 20353 11374 20354 11376 20354 11377 20354 11376 20355 11378 20355 11377 20355 11377 20356 11378 20356 11379 20356 11377 20357 11379 20357 11380 20357 11380 20358 11379 20358 11381 20358 11380 20359 11381 20359 11382 20359 11382 20360 11381 20360 11383 20360 11382 20361 11383 20361 11384 20361 11384 20362 11383 20362 11385 20362 11385 20363 11386 20363 11384 20363 11384 20364 11386 20364 11387 20364 11384 20365 11387 20365 11388 20365 11388 20366 11387 20366 11389 20366 11388 20367 11389 20367 11390 20367 1278 20368 1277 20368 11391 20368 11391 20369 1277 20369 11364 20369 11391 20370 11364 20370 11392 20370 11392 20371 11364 20371 11390 20371 11392 20372 11390 20372 11393 20372 11393 20373 11390 20373 11389 20373 1284 20374 11363 20374 11364 20374 11364 20375 11363 20375 11394 20375 11364 20376 11394 20376 11390 20376 11390 20377 11394 20377 11395 20377 11390 20378 11395 20378 11388 20378 11388 20379 11395 20379 11396 20379 11388 20380 11396 20380 11384 20380 11384 20381 11396 20381 11397 20381 11384 20382 11397 20382 11382 20382 11382 20383 11397 20383 11398 20383 11382 20384 11398 20384 11380 20384 11380 20385 11398 20385 11399 20385 11380 20386 11399 20386 11377 20386 11377 20387 11399 20387 11400 20387 11377 20388 11400 20388 11374 20388 11374 20389 11400 20389 11401 20389 11374 20390 11401 20390 11372 20390 11372 20391 11401 20391 11402 20391 11372 20392 11402 20392 11369 20392 11369 20393 11402 20393 11403 20393 11369 20394 11403 20394 11365 20394 11365 20395 11403 20395 11404 20395 11365 20396 11404 20396 11360 20396 11360 20397 11404 20397 4270 20397 11360 20398 4270 20398 4272 20398 1274 20399 11362 20399 11363 20399 11363 20400 11362 20400 11405 20400 11363 20401 11405 20401 11394 20401 11394 20402 11405 20402 11406 20402 11394 20403 11406 20403 11395 20403 11395 20404 11406 20404 11407 20404 11395 20405 11407 20405 11396 20405 11396 20406 11407 20406 11408 20406 11396 20407 11408 20407 11397 20407 11397 20408 11408 20408 11409 20408 11397 20409 11409 20409 11398 20409 11398 20410 11409 20410 11410 20410 11398 20411 11410 20411 11399 20411 11399 20412 11410 20412 11411 20412 11399 20413 11411 20413 11400 20413 11400 20414 11411 20414 11412 20414 11400 20415 11412 20415 11401 20415 11401 20416 11412 20416 11413 20416 11401 20417 11413 20417 11402 20417 11402 20418 11413 20418 11414 20418 11402 20419 11414 20419 11403 20419 11403 20420 11414 20420 11415 20420 11403 20421 11415 20421 11404 20421 1273 20422 11295 20422 11362 20422 11362 20423 11295 20423 11304 20423 11362 20424 11304 20424 11405 20424 11405 20425 11304 20425 11303 20425 11405 20426 11303 20426 11406 20426 11406 20427 11303 20427 11302 20427 11406 20428 11302 20428 11407 20428 11407 20429 11302 20429 11297 20429 11407 20430 11297 20430 11408 20430 11408 20431 11297 20431 11296 20431 11408 20432 11296 20432 11409 20432 11409 20433 11296 20433 11305 20433 11409 20434 11305 20434 11410 20434 11410 20435 11305 20435 11301 20435 11410 20436 11301 20436 11411 20436 11411 20437 11301 20437 11300 20437 11411 20438 11300 20438 11412 20438 11412 20439 11300 20439 11299 20439 11412 20440 11299 20440 11413 20440 11413 20441 11299 20441 11298 20441 11413 20442 11298 20442 11414 20442 11414 20443 11298 20443 11294 20443 11414 20444 11294 20444 11415 20444 11415 20445 11294 20445 4277 20445 11415 20446 4277 20446 11404 20446 11404 20447 4277 20447 4280 20447 11404 20448 4280 20448 4270 20448 923 95 202 95 8321 95 8321 95 202 95 203 95 763 20449 121 20449 757 20449 757 20450 121 20450 11416 20450 757 20451 11416 20451 758 20451 763 20452 764 20452 121 20452 121 20453 764 20453 766 20453 121 95 766 95 120 95 238 95 900 95 236 95 236 95 900 95 742 95 236 20454 742 20454 744 20454 744 20455 748 20455 236 20455 236 20456 748 20456 747 20456 236 20457 747 20457 11417 20457 11417 20458 747 20458 753 20458 11417 20459 753 20459 752 20459 3733 20460 3734 20460 589 20460 3733 20461 589 20461 3729 20461 589 20462 590 20462 3729 20462 3729 20463 590 20463 592 20463 3729 20464 592 20464 3730 20464 3730 20465 592 20465 594 20465 3730 20466 594 20466 3731 20466 3731 20467 594 20467 595 20467 3731 20468 595 20468 3732 20468 6613 20469 1773 20469 6614 20469 6614 20470 1773 20470 1764 20470 6614 20471 1764 20471 6624 20471 6624 20472 1764 20472 1763 20472 6624 20473 1763 20473 4327 20473 6613 20474 1781 20474 1780 20474 1779 20475 1778 20475 1780 20475 1780 20476 1778 20476 1767 20476 1780 20477 1767 20477 6613 20477 6613 20478 1767 20478 1770 20478 6613 20479 1770 20479 1773 20479 3728 20480 3727 20480 3732 20480 3732 20481 595 20481 3728 20481 3728 20482 595 20482 597 20482 3728 20483 597 20483 3726 20483 3726 20484 597 20484 599 20484 2715 20485 4322 20485 2716 20485 2716 20486 4322 20486 4327 20486 2716 20487 4327 20487 1765 20487 1765 20488 4327 20488 1763 20488 2715 20489 2719 20489 4322 20489 4322 20490 2719 20490 817 20490 4322 20491 817 20491 4323 20491 4323 20492 817 20492 819 20492 4323 20493 819 20493 11418 20493 11418 20494 819 20494 11419 20494 4344 20495 4342 20495 11420 20495 11420 20496 11421 20496 4344 20496 4344 20497 11421 20497 11422 20497 4344 20498 11422 20498 4337 20498 11422 20499 11423 20499 4337 20499 4337 20500 11423 20500 11424 20500 4337 20501 11424 20501 4338 20501 4338 20502 11424 20502 11425 20502 4338 20503 11425 20503 11419 20503 11419 20504 11425 20504 11426 20504 11419 20505 11426 20505 11418 20505 11427 20506 4336 20506 4335 20506 11427 20507 4335 20507 11419 20507 11419 20508 4335 20508 4339 20508 11419 20509 4339 20509 4338 20509 11427 20510 810 20510 4336 20510 4336 20511 810 20511 815 20511 4336 20512 815 20512 4332 20512 815 20513 814 20513 4332 20513 4332 20514 814 20514 2767 20514 4332 20515 2767 20515 4330 20515 4330 20516 2767 20516 2768 20516 4330 20517 2768 20517 4328 20517 4328 20518 2768 20518 4317 20518 819 20519 820 20519 11419 20519 11419 20520 820 20520 821 20520 11419 20521 821 20521 11427 20521 11427 20522 821 20522 808 20522 11427 20523 808 20523 810 20523 4341 20524 7238 20524 4342 20524 4342 20525 7238 20525 7237 20525 4342 20526 7237 20526 11420 20526 795 20527 801 20527 7296 20527 7296 20528 801 20528 800 20528 7296 20529 800 20529 798 20529 798 20530 797 20530 7296 20530 7296 20531 797 20531 804 20531 7296 20532 804 20532 604 20532 795 20533 7296 20533 11307 20533 11307 20534 7296 20534 7301 20534 11307 20535 7301 20535 11306 20535 4513 20536 4512 20536 5494 20536 5494 20537 4512 20537 11428 20537 5494 20538 11428 20538 5496 20538 5496 20539 11428 20539 5497 20539 11429 20540 5375 20540 11430 20540 5427 20541 5425 20541 11429 20541 11429 20542 5425 20542 5376 20542 11429 20543 5376 20543 5375 20543 5433 20544 11429 20544 5436 20544 5436 20545 11429 20545 11430 20545 5436 20546 11430 20546 11431 20546 5433 20547 5431 20547 11429 20547 11429 20548 5431 20548 5429 20548 11429 20549 5429 20549 5427 20549 11431 20550 11432 20550 11433 20550 11433 20551 11432 20551 11434 20551 11433 20552 11434 20552 11435 20552 11436 20553 11437 20553 11430 20553 11430 20554 11437 20554 11438 20554 11430 20555 11438 20555 11431 20555 11431 20556 11438 20556 11439 20556 11431 20557 11439 20557 11432 20557 5375 20558 5497 20558 11430 20558 11430 20559 5497 20559 11428 20559 11430 20560 11428 20560 11436 20560 11436 20561 11428 20561 4512 20561 11436 20562 4512 20562 4511 20562 11435 20563 5312 20563 5311 20563 5371 20564 11440 20564 11441 20564 4638 20565 5371 20565 4636 20565 4636 20566 5371 20566 11441 20566 4636 20567 11441 20567 4634 20567 11442 20568 4640 20568 4639 20568 4640 20569 5318 20569 5317 20569 4640 20570 5317 20570 4641 20570 4641 20571 5317 20571 5316 20571 4641 20572 5316 20572 4599 20572 11435 20573 5311 20573 11433 20573 5318 20574 4640 20574 5309 20574 5309 20575 4640 20575 11442 20575 5309 20576 11442 20576 5310 20576 5310 20577 11442 20577 11443 20577 5310 20578 11443 20578 5315 20578 5315 20579 11443 20579 11444 20579 5315 20580 11444 20580 5314 20580 5314 20581 11444 20581 11445 20581 5314 20582 11445 20582 5311 20582 5311 20583 11445 20583 11446 20583 5311 20584 11446 20584 11433 20584 11440 20585 5371 20585 11447 20585 11447 20586 5371 20586 5435 20586 11447 20587 5435 20587 11448 20587 11448 20588 5435 20588 5437 20588 11448 20589 5437 20589 11449 20589 11449 20590 5437 20590 5436 20590 11449 20591 5436 20591 11431 20591 4639 20592 4634 20592 11442 20592 11442 20593 4634 20593 11441 20593 11442 20594 11441 20594 11443 20594 11443 20595 11441 20595 11440 20595 11443 20596 11440 20596 11444 20596 11444 20597 11440 20597 11447 20597 11444 20598 11447 20598 11445 20598 11445 20599 11447 20599 11448 20599 11445 20600 11448 20600 11446 20600 11446 20601 11448 20601 11449 20601 11446 20602 11449 20602 11433 20602 11433 20603 11449 20603 11431 20603 4604 20604 4603 20604 5556 20604 4637 18231 4635 18231 5473 18231 5473 20605 4635 20605 11450 20605 5473 20606 11450 20606 5472 20606 11451 20607 5476 20607 11450 20607 11450 20608 5476 20608 5475 20608 11450 20609 5475 20609 5472 20609 5480 20610 5477 20610 11452 20610 11452 20611 5477 20611 5478 20611 11452 20612 5478 20612 11451 20612 11451 20613 5478 20613 5474 20613 11451 20614 5474 20614 5476 20614 5479 20615 5480 20615 122 20615 122 20616 5480 20616 11452 20616 122 20617 11452 20617 121 20617 121 20618 11452 20618 11416 20618 758 20619 11416 20619 760 20619 760 20620 11416 20620 11452 20620 760 20621 11452 20621 767 20621 767 20622 11452 20622 11451 20622 767 20623 11451 20623 768 20623 768 20624 11451 20624 11450 20624 768 20625 11450 20625 5556 20625 5556 20626 11450 20626 4635 20626 5556 20627 4635 20627 4604 20627 5239 20628 5238 20628 11453 20628 11454 20629 11455 20629 11453 20629 11453 20630 11455 20630 11456 20630 11453 20631 11456 20631 5239 20631 5239 20632 11456 20632 11457 20632 5239 20633 11457 20633 5261 20633 5261 20634 11457 20634 11458 20634 5261 20635 11458 20635 5265 20635 11458 20636 11459 20636 5265 20636 5265 20637 11459 20637 11460 20637 5265 20638 11460 20638 5246 20638 4624 20639 4623 20639 11461 20639 11461 20640 4623 20640 5246 20640 11461 20641 5246 20641 11462 20641 11462 20642 5246 20642 11460 20642 756 20643 1441 20643 11463 20643 4681 20644 4683 20644 5558 20644 5558 20645 4683 20645 11463 20645 1437 20646 5562 20646 1441 20646 1441 20647 5562 20647 5561 20647 1441 20648 5561 20648 11463 20648 11463 20649 5561 20649 5559 20649 11463 20650 5559 20650 5558 20650 4683 20651 4625 20651 11463 20651 11463 20652 4625 20652 11464 20652 11463 20653 11464 20653 756 20653 756 20654 11464 20654 754 20654 11465 20655 11466 20655 11467 20655 5338 20656 5336 20656 5343 20656 5340 20657 5338 20657 5334 20657 5334 20658 5338 20658 11468 20658 5334 20659 11468 20659 5333 20659 4521 20660 5445 20660 11469 20660 11469 20661 5445 20661 5444 20661 5444 20662 5442 20662 11469 20662 11469 20663 5442 20663 5441 20663 11469 20664 5441 20664 5333 20664 4521 20665 11469 20665 4523 20665 4523 20666 11469 20666 11470 20666 4523 20667 11470 20667 4524 20667 11467 20668 11471 20668 11472 20668 5338 20669 5343 20669 11468 20669 11468 20670 5343 20670 11465 20670 11468 20671 11465 20671 5333 20671 5333 20672 11465 20672 11467 20672 5333 20673 11467 20673 11469 20673 11469 20674 11467 20674 11472 20674 11469 20675 11472 20675 11470 20675 11471 20676 11467 20676 11473 20676 11473 20677 11467 20677 11466 20677 11473 20678 11466 20678 11474 20678 11474 20679 11466 20679 11475 20679 11474 20680 11475 20680 11476 20680 11476 20681 11475 20681 11477 20681 11478 20682 4629 20682 11479 20682 11479 20683 4629 20683 4628 20683 11479 20684 4628 20684 4617 20684 4632 20685 4633 20685 11480 20685 5320 20686 5319 20686 11481 20686 11481 20687 5319 20687 5347 20687 11481 20688 5347 20688 4630 20688 11454 20689 11476 20689 11455 20689 11455 20690 11476 20690 11477 20690 11455 20691 11477 20691 11456 20691 11456 20692 11477 20692 11482 20692 11456 20693 11482 20693 11457 20693 11457 20694 11482 20694 11483 20694 11457 20695 11483 20695 11458 20695 11458 20696 11483 20696 11484 20696 11458 20697 11484 20697 11459 20697 11459 20698 11484 20698 11478 20698 11459 20699 11478 20699 11460 20699 11460 20700 11478 20700 11479 20700 11460 20701 11479 20701 11462 20701 11462 20702 11479 20702 4617 20702 11462 20703 4617 20703 11461 20703 11461 20704 4617 20704 4624 20704 11465 20705 5343 20705 5344 20705 11465 20706 5344 20706 11485 20706 11485 20707 5344 20707 5345 20707 11485 20708 5345 20708 5320 20708 11486 20709 11481 20709 11487 20709 11487 20710 11481 20710 4630 20710 11487 20711 4630 20711 4632 20711 11486 20712 11488 20712 11489 20712 5320 20713 11481 20713 11485 20713 11485 20714 11481 20714 11486 20714 11485 20715 11486 20715 11465 20715 11465 20716 11486 20716 11489 20716 11465 20717 11489 20717 11466 20717 4632 20718 11480 20718 11487 20718 11487 20719 11480 20719 11490 20719 11487 20720 11490 20720 11486 20720 11486 20721 11490 20721 11491 20721 11486 20722 11491 20722 11488 20722 11475 20723 11466 20723 11477 20723 11477 20724 11466 20724 11489 20724 11477 20725 11489 20725 11482 20725 11482 20726 11489 20726 11488 20726 11482 20727 11488 20727 11483 20727 11483 20728 11488 20728 11491 20728 11483 20729 11491 20729 11484 20729 11484 20730 11491 20730 11490 20730 11484 20731 11490 20731 11478 20731 11478 20732 11490 20732 11480 20732 11478 20733 11480 20733 4629 20733 4629 20734 11480 20734 4633 20734 11492 20735 11417 20735 752 20735 236 20736 11417 20736 234 20736 234 20737 11417 20737 11492 20737 234 20738 11492 20738 5465 20738 5467 20739 5463 20739 11492 20739 11492 20740 5463 20740 5464 20740 11492 20741 5464 20741 5465 20741 4626 20742 4627 20742 11493 20742 11493 20743 4627 20743 4631 20743 11493 20744 4631 20744 5470 20744 5470 20745 5471 20745 11493 20745 11493 20746 5471 20746 5469 20746 11493 20747 5469 20747 11494 20747 11494 20748 5469 20748 5468 20748 11494 20749 5468 20749 5466 20749 752 20750 750 20750 11492 20750 11492 20751 750 20751 11494 20751 11492 20752 11494 20752 5467 20752 5467 20753 11494 20753 5466 20753 4625 20754 4626 20754 11464 20754 11464 20755 4626 20755 11493 20755 11464 20756 11493 20756 754 20756 754 20757 11493 20757 11494 20757 754 20758 11494 20758 749 20758 749 20759 11494 20759 750 20759 10395 20760 11270 20760 10414 20760 10414 20761 11270 20761 11495 20761 10414 20762 11495 20762 10416 20762 10416 20763 11495 20763 10417 20763 10523 20764 10521 20764 10525 20764 10525 20765 10521 20765 10532 20765 10525 20766 10532 20766 10527 20766 10527 20767 10532 20767 10529 20767 11496 20768 10590 20768 10429 20768 10429 20769 10590 20769 10532 20769 10429 20770 10532 20770 10498 20770 10498 20771 10532 20771 10521 20771 10577 20772 10576 20772 11497 20772 11497 20773 10576 20773 10590 20773 11497 20774 10590 20774 11498 20774 11498 20775 10590 20775 11496 20775 11498 20776 11496 20776 11499 20776 11499 20777 11496 20777 11500 20777 10429 20778 10417 20778 11496 20778 11496 20779 10417 20779 11495 20779 11496 20780 11495 20780 11500 20780 11500 20781 11495 20781 11270 20781 11500 20782 11270 20782 11269 20782 11501 20783 11502 20783 11503 20783 10535 20784 10534 20784 11504 20784 10673 20785 10672 20785 11258 20785 10677 20786 10678 20786 11505 20786 10672 20787 10675 20787 11258 20787 11258 20788 10675 20788 11506 20788 11258 20789 11506 20789 11259 20789 11262 20790 11507 20790 11261 20790 11261 15565 11507 15565 11508 15565 11261 15537 11508 15537 10464 15537 10464 15538 11508 15538 11504 15538 10464 20791 11504 20791 10553 20791 10553 20792 11504 20792 10534 20792 10676 20793 10677 20793 11509 20793 11509 20794 10677 20794 11505 20794 11509 20795 11505 20795 11510 20795 11510 20796 11505 20796 11511 20796 11509 20797 11512 20797 10676 20797 10676 20798 11512 20798 11513 20798 10676 20799 11513 20799 10675 20799 10675 20800 11513 20800 11514 20800 10675 20801 11514 20801 11506 20801 11506 20802 11514 20802 11260 20802 11506 20803 11260 20803 11259 20803 11502 20804 10550 20804 10551 20804 11503 20805 11502 20805 11515 20805 11515 20806 11502 20806 10551 20806 11515 20807 10551 20807 10552 20807 11507 20808 11516 20808 11508 20808 11508 20809 11516 20809 11503 20809 11508 20810 11503 20810 11504 20810 11504 15557 11503 15557 11515 15557 11504 20811 11515 20811 10535 20811 10535 15555 11515 15555 10552 15555 11516 20812 11517 20812 11503 20812 11503 20813 11517 20813 11518 20813 11503 20814 11518 20814 11501 20814 11501 20815 11518 20815 11519 20815 11501 20816 11519 20816 11520 20816 11511 20817 11520 20817 11510 20817 11510 20818 11520 20818 11519 20818 11510 15572 11519 15572 11509 15572 11509 20819 11519 20819 11518 20819 11509 20820 11518 20820 11512 20820 11512 20821 11518 20821 11517 20821 11512 20822 11517 20822 11513 20822 11513 20823 11517 20823 11516 20823 11513 20824 11516 20824 11514 20824 11514 20825 11516 20825 11507 20825 11514 20826 11507 20826 11260 20826 11260 20827 11507 20827 11262 20827 10547 20828 10545 20828 10543 20828 11501 20829 11521 20829 11502 20829 11502 20830 11521 20830 10547 20830 11502 20831 10547 20831 10550 20831 10550 20832 10547 20832 10543 20832 10541 20833 10547 20833 10471 20833 10471 20834 10547 20834 11521 20834 10471 20835 11521 20835 10473 20835 10473 20836 11521 20836 11522 20836 11266 20837 10391 20837 10467 20837 10467 20838 10466 20838 11522 20838 10466 20839 10476 20839 11522 20839 11522 20840 10476 20840 10475 20840 11522 20841 10475 20841 10473 20841 10467 20842 11522 20842 11266 20842 11266 20843 11522 20843 11523 20843 11266 20844 11523 20844 11267 20844 11520 20845 11511 20845 11524 20845 11520 20846 11524 20846 11501 20846 11501 20847 11524 20847 11525 20847 11501 20848 11525 20848 11521 20848 11521 20849 11525 20849 11526 20849 11521 20850 11526 20850 11522 20850 11522 20851 11526 20851 11527 20851 11522 20852 11527 20852 11523 20852 8438 20853 8422 20853 9286 20853 8440 20854 11528 20854 8441 20854 8441 20855 11528 20855 8444 20855 8444 20856 11528 20856 8454 20856 8454 20857 11528 20857 11529 20857 8454 20858 11529 20858 8522 20858 8549 20859 8547 20859 8545 20859 8522 20860 11529 20860 8545 20860 8545 20861 11529 20861 11530 20861 8545 20862 11530 20862 8549 20862 8551 20863 8549 20863 8553 20863 8553 20864 8549 20864 11530 20864 8553 20865 11530 20865 8556 20865 8556 20866 11530 20866 11529 20866 8556 20867 11529 20867 8648 20867 8648 20868 11529 20868 11531 20868 8648 20869 11531 20869 8635 20869 8635 20870 11531 20870 11532 20870 8635 20871 11532 20871 8636 20871 9285 20872 11528 20872 9286 20872 9286 20873 11528 20873 8440 20873 9286 20874 8440 20874 8438 20874 9285 20875 11533 20875 11528 20875 11528 20876 11533 20876 11534 20876 11528 20877 11534 20877 11529 20877 11529 20878 11534 20878 11535 20878 11529 20879 11535 20879 11531 20879 1279 95 11285 95 1272 95 11288 20880 11285 20880 11391 20880 11391 20881 11285 20881 1279 20881 11391 20882 1279 20882 1278 20882 11389 20883 11289 20883 11393 20883 11393 20884 11289 20884 11288 20884 11393 20885 11288 20885 11392 20885 11392 20886 11288 20886 11391 20886 11389 20887 11387 20887 11289 20887 11289 20888 11387 20888 11386 20888 11289 20889 11386 20889 11290 20889 11381 20890 11293 20890 11383 20890 11383 20891 11293 20891 11290 20891 11383 20892 11290 20892 11385 20892 11385 20893 11290 20893 11386 20893 11381 20894 11379 20894 11293 20894 11293 20895 11379 20895 11378 20895 11293 20896 11378 20896 11292 20896 11373 20897 11291 20897 11375 20897 11375 20898 11291 20898 11292 20898 11375 20899 11292 20899 11376 20899 11376 20900 11292 20900 11378 20900 11373 20901 11371 20901 11291 20901 11291 20902 11371 20902 11370 20902 11291 20903 11370 20903 11286 20903 11370 20904 11368 20904 11286 20904 11286 20905 11368 20905 11367 20905 11286 20906 11367 20906 11287 20906 4268 20907 4267 20907 11361 20907 11361 20908 4267 20908 11287 20908 11361 20909 11287 20909 11366 20909 11366 20910 11287 20910 11367 20910 11306 20911 7301 20911 625 20911 625 20912 7301 20912 615 20912 9285 20913 9284 20913 11536 20913 11536 20914 8623 20914 8638 20914 8638 20915 8636 20915 11536 20915 11536 20916 8636 20916 11532 20916 11536 20917 11532 20917 11531 20917 11533 20918 9285 20918 11534 20918 11534 20919 9285 20919 11536 20919 11534 20920 11536 20920 11535 20920 11535 20921 11536 20921 11531 20921 8672 20922 8674 20922 11537 20922 8670 20923 8657 20923 11537 20923 11537 20924 8657 20924 8656 20924 11537 20925 8656 20925 8672 20925 8670 20926 11537 20926 8671 20926 8671 20927 11537 20927 11536 20927 8671 20928 11536 20928 8684 20928 8674 20929 8653 20929 11537 20929 11537 20930 8653 20930 8652 20930 11537 20931 8652 20931 11536 20931 11536 20932 8652 20932 8624 20932 11536 20933 8624 20933 8623 20933 11357 20934 11358 20934 9287 20934 11538 20935 11344 20935 11355 20935 11355 20936 11353 20936 11538 20936 11538 20937 11353 20937 11352 20937 11538 20938 11352 20938 11356 20938 11359 20939 11328 20939 9288 20939 9288 20940 11328 20940 11330 20940 9288 20941 11330 20941 9287 20941 9287 20942 11330 20942 11538 20942 9287 20943 11538 20943 11357 20943 11357 20944 11538 20944 11356 20944 11330 20945 11331 20945 11538 20945 11538 20946 11331 20946 11312 20946 11538 20947 11312 20947 11344 20947 11344 20948 11312 20948 11311 20948 11344 20949 11311 20949 11345 20949 9283 20950 7331 20950 7329 20950 7329 20951 9282 20951 11345 20951 11345 20952 11311 20952 7329 20952 7329 20953 11311 20953 8684 20953 7329 20954 8684 20954 9283 20954 9283 20955 8684 20955 11536 20955 9283 20956 11536 20956 9284 20956 11316 20957 11315 20957 11314 20957 11314 20958 11315 20958 9271 20958 8682 20959 8685 20959 8683 20959 8683 20960 8685 20960 8684 20960 8683 20961 8684 20961 9271 20961 9271 20962 8684 20962 11311 20962 9271 20963 11311 20963 11314 20963 11539 20964 11540 20964 11541 20964 11541 20965 11540 20965 11542 20965 11541 20966 11542 20966 11543 20966 11544 20967 11545 20967 11542 20967 11542 20968 11540 20968 11544 20968 11544 20969 11540 20969 11539 20969 11544 20970 11539 20970 11546 20970 11546 20971 11539 20971 11547 20971 11546 20972 11547 20972 11548 20972 11545 20973 11549 20973 11550 20973 11542 20974 11551 20974 11552 20974 11421 20975 11552 20975 11550 20975 11550 20976 11552 20976 11551 20976 11550 20977 11551 20977 11545 20977 11542 20978 11545 20978 11551 20978 11549 20979 11423 20979 11550 20979 11550 20980 11423 20980 11422 20980 11550 20981 11422 20981 11421 20981 11423 20982 11549 20982 11424 20982 11425 20983 11424 20983 11426 20983 11426 20984 11424 20984 11549 20984 11426 20985 11549 20985 11418 20985 11418 20986 11549 20986 11545 20986 11420 20987 7237 20987 11553 20987 11552 20988 11421 20988 11420 20988 11420 20989 11553 20989 11552 20989 11552 20990 11553 20990 11543 20990 11552 20991 11543 20991 11542 20991 11545 20992 11544 20992 11418 20992 11418 20993 11544 20993 11546 20993 11418 20994 11546 20994 4323 20994 4323 20995 11546 20995 11548 20995 4323 20996 11548 20996 4324 20996 7236 632 4324 632 11548 632 7236 632 11541 632 7237 632 7237 632 11541 632 11543 632 7237 632 11543 632 11553 632 11548 632 11547 632 7236 632 7236 632 11547 632 11539 632 7236 632 11539 632 11541 632 5248 20997 5252 20997 11554 20997 11554 20998 11453 20998 5238 20998 5238 20999 5271 20999 11554 20999 11554 21000 5271 21000 5249 21000 11554 21001 5249 21001 5248 21001 5252 21002 5251 21002 11554 21002 11554 21003 5251 21003 5260 21003 11554 21004 5260 21004 5259 21004 5259 21005 5258 21005 11554 21005 11554 21006 5258 21006 5257 21006 11554 21007 5257 21007 5272 21007 11555 21008 11476 21008 11554 21008 11554 21009 11476 21009 11454 21009 11554 21010 11454 21010 11453 21010 11555 21011 4517 21011 4524 21011 4524 21012 11470 21012 11555 21012 11555 21013 11470 21013 11472 21013 11555 21014 11472 21014 11471 21014 11471 21015 11473 21015 11555 21015 11555 21016 11473 21016 11474 21016 11555 21017 11474 21017 11476 21017 4553 21018 4515 21018 5272 21018 11556 21019 4509 21019 4507 21019 4517 21020 11555 21020 4515 21020 4515 21021 11555 21021 11554 21021 4515 21022 11554 21022 5272 21022 4553 21023 5272 21023 4528 21023 4528 21024 5272 21024 5280 21024 4528 21025 5280 21025 4507 21025 4507 21026 5280 21026 11557 21026 4507 21027 11557 21027 11556 21027 5275 21028 5278 21028 4607 21028 4607 21029 5278 21029 5280 21029 4607 21030 5280 21030 4608 21030 4608 21031 5280 21031 5272 21031 4608 21032 5272 21032 5274 21032 5274 21033 5272 21033 5273 21033 4511 21034 4509 21034 11556 21034 11436 21035 4511 21035 11437 21035 11437 21036 4511 21036 11556 21036 11437 21037 11556 21037 11438 21037 11438 21038 11556 21038 11439 21038 11557 21039 5313 21039 5312 21039 5312 21040 11435 21040 11557 21040 11557 21041 11435 21041 11434 21041 11557 21042 11434 21042 11556 21042 11556 21043 11434 21043 11432 21043 11556 21044 11432 21044 11439 21044 5292 21045 5290 21045 11558 21045 11558 21046 5290 21046 5297 21046 11558 21047 5297 21047 5296 21047 11558 21048 5282 21048 5287 21048 5287 21049 5295 21049 11558 21049 11558 21050 5295 21050 5294 21050 11558 21051 5294 21051 5292 21051 5296 21052 5313 21052 11558 21052 11558 21053 5313 21053 11557 21053 11558 21054 11557 21054 5282 21054 5282 21055 11557 21055 5280 21055 11269 21056 11268 21056 11559 21056 10586 21057 10577 21057 11559 21057 11559 21058 10577 21058 11497 21058 11500 21059 11269 21059 11499 21059 11499 21060 11269 21060 11559 21060 11499 21061 11559 21061 11498 21061 11498 21062 11559 21062 11497 21062 10620 21063 11560 21063 10614 21063 10614 21064 11560 21064 10616 21064 10611 21065 10619 21065 11560 21065 11560 21066 10619 21066 10618 21066 11560 21067 10618 21067 10616 21067 10611 21068 11560 21068 10609 21068 10609 21069 11560 21069 11559 21069 10609 21070 11559 21070 10635 21070 10620 21071 10596 21071 11560 21071 11560 21072 10596 21072 10598 21072 11560 21073 10598 21073 11559 21073 11559 21074 10598 21074 10585 21074 11559 21075 10585 21075 10586 21075 11561 21076 11505 21076 10678 21076 11561 21077 10678 21077 10637 21077 10637 21078 11562 21078 10638 21078 10638 21079 11562 21079 10663 21079 10638 21080 10663 21080 10665 21080 10648 21081 10663 21081 10651 21081 10651 21082 10663 21082 11562 21082 10651 21083 11562 21083 10652 21083 10652 21084 11562 21084 10637 21084 10652 21085 10637 21085 10674 21085 10674 21086 10637 21086 10678 21086 11526 21087 11525 21087 11561 21087 11561 21088 11265 21088 11267 21088 11267 21089 11523 21089 11561 21089 11561 21090 11523 21090 11527 21090 11561 21091 11527 21091 11526 21091 11525 21092 11524 21092 11561 21092 11561 21093 11524 21093 11511 21093 11561 21094 11511 21094 11505 21094 11264 21095 9309 21095 9307 21095 11265 21096 11561 21096 11263 21096 11263 21097 11561 21097 10637 21097 11263 21098 10637 21098 9307 21098 9307 21099 10637 21099 10635 21099 9307 21100 10635 21100 11264 21100 11264 21101 10635 21101 11559 21101 11264 21102 11559 21102 11268 21102 10632 21103 10634 21103 10633 21103 10633 21104 10634 21104 10635 21104 10633 21105 10635 21105 10640 21105 10640 21106 10635 21106 10637 21106 10640 21107 10637 21107 10642 21107 10642 21108 10637 21108 10636 21108 362 21109 1213 21109 329 21109 329 21110 1213 21110 1215 21110 329 21111 1215 21111 331 21111 1210 21112 1209 21112 362 21112 362 21113 1209 21113 1211 21113 362 21114 1211 21114 1213 21114 362 21115 356 21115 1210 21115 1210 21116 356 21116 339 21116 1210 21117 339 21117 295 21117 4136 21118 4138 21118 11563 21118 11563 21119 4138 21119 11564 21119 11563 21120 11564 21120 262 21120 262 21121 11564 21121 261 21121 261 21122 11564 21122 11565 21122 261 21123 11565 21123 259 21123 259 21124 11565 21124 263 21124 263 21125 11565 21125 11566 21125 263 21126 11566 21126 264 21126 264 21127 11566 21127 11567 21127 264 21128 11567 21128 265 21128 1751 21129 11568 21129 1752 21129 1752 21130 11568 21130 11569 21130 1752 21131 11569 21131 1753 21131 1753 21132 11569 21132 11570 21132 1753 21133 11570 21133 1754 21133 1754 21134 11570 21134 11571 21134 1754 21135 11571 21135 1755 21135 1755 21136 11571 21136 4137 21136 11568 21137 11567 21137 11569 21137 11569 21138 11567 21138 11566 21138 11569 21139 11566 21139 11570 21139 11570 21140 11566 21140 11565 21140 11570 21141 11565 21141 11571 21141 11571 21142 11565 21142 11564 21142 11571 21143 11564 21143 4137 21143 4137 21144 11564 21144 4138 21144 265 21145 11567 21145 255 21145 255 21146 11567 21146 11568 21146 255 21147 11568 21147 253 21147 253 21148 11568 21148 1751 21148 253 21149 1751 21149 251 21149 220 633 219 633 175 633 175 633 219 633 176 633 165 633 164 633 193 633 193 633 164 633 194 633 138 633 137 633 79 633 79 633 137 633 81 633 94 633 93 633 105 633 105 633 93 633 106 633 76 21150 75 21150 73 21150 73 21151 75 21151 50 21151 73 21152 50 21152 74 21152 74 21153 50 21153 49 21153 357 21154 16 21154 358 21154 4134 21155 260 21155 8187 21155 4134 21156 8187 21156 4132 21156 4132 21157 8187 21157 8186 21157 4132 21158 8186 21158 4133 21158 6666 21159 4135 21159 8184 21159 8184 21160 4135 21160 4133 21160 8184 21161 4133 21161 8185 21161 8185 21162 4133 21162 8186 21162 262 21163 260 21163 11563 21163 11563 21164 260 21164 4134 21164 11563 21165 4134 21165 4136 21165 11572 21166 11573 21166 11574 21166 11574 21167 11573 21167 11575 21167 11573 106 11576 106 11575 106 11575 106 11576 106 11577 106 11578 633 11579 633 11577 633 11577 21168 11579 21168 11580 21168 11577 633 11580 633 11575 633 11575 633 11580 633 11574 633 11581 21169 11580 21169 11582 21169 11582 21169 11580 21169 11579 21169 11582 21170 11579 21170 11583 21170 11583 21171 11579 21171 11578 21171 11583 21172 11578 21172 11576 21172 11576 21173 11578 21173 11577 21173 11573 7585 11572 7585 11576 7585 11576 7585 11572 7585 11581 7585 11576 7585 11581 7585 11583 7585 11583 21174 11581 21174 11582 21174 11580 98 11581 98 11574 98 11574 98 11581 98 11572 98 11584 21175 11585 21175 11586 21175 11586 21176 11585 21176 11587 21176 11586 21177 11587 21177 11588 21177 11588 21178 11589 21178 11590 21178 11588 21178 11590 21178 11586 21178 11586 21179 11590 21179 11591 21179 11586 21180 11591 21180 11584 21180 11585 21181 11592 21181 11587 21181 11587 21181 11592 21181 11593 21181 11587 21182 11593 21182 11588 21182 11588 21183 11593 21183 11589 21183 11592 95 11591 95 11593 95 11593 95 11591 95 11590 95 11593 95 11590 95 11589 95 11591 21184 11592 21184 11584 21184 11584 21184 11592 21184 11585 21184 11594 21185 11595 21185 11596 21185 11596 21186 11595 21186 11597 21186 11596 21187 11597 21187 11598 21187 11595 21188 11599 21188 11600 21188 11595 21189 11600 21189 11597 21189 11597 21190 11600 21190 11601 21190 11597 21190 11601 21190 11598 21190 11598 21191 11601 21191 11596 21191 11596 21192 11601 21192 11602 21192 11596 21193 11602 21193 11594 21193 11594 21193 11602 21193 11603 21193 11599 95 11603 95 11600 95 11600 95 11603 95 11602 95 11600 95 11602 95 11601 95 11603 21194 11599 21194 11594 21194 11594 21194 11599 21194 11595 21194 11604 632 11605 632 11606 632 11607 7585 11608 7585 11606 7585 11606 7585 11608 7585 11604 7585 11605 98 11609 98 11606 98 11606 98 11609 98 11607 98 11609 21195 11605 21195 11608 21195 11608 21196 11605 21196 11604 21196 11607 95 11609 95 11608 95 11610 7585 11611 7585 11612 7585 11612 7585 11611 7585 11613 7585 11613 632 11614 632 11612 632 11615 98 11610 98 11614 98 11614 98 11610 98 11612 98 11615 21197 11614 21197 11611 21197 11611 21198 11614 21198 11613 21198 11611 95 11610 95 11615 95 11616 7585 11617 7585 11618 7585 11618 7585 11617 7585 11619 7585 11619 95 11617 95 11620 95 11621 95 11622 95 11623 95 11623 95 11622 95 11619 95 11623 95 11619 95 11624 95 11624 95 11619 95 11620 95 11617 21199 11616 21199 11620 21199 11620 21200 11616 21200 11625 21200 11620 21201 11625 21201 11624 21201 11624 21202 11625 21202 11626 21202 11624 21203 11626 21203 11623 21203 11623 21204 11626 21204 11627 21204 11623 21205 11627 21205 11621 21205 11621 21206 11627 21206 11628 21206 11621 21207 11628 21207 11622 21207 11622 21208 11628 21208 11629 21208 11622 21209 11629 21209 11619 21209 11619 21210 11629 21210 11618 21210 11616 21211 11618 21211 11629 21211 11626 21212 11625 21212 11627 21212 11627 21213 11625 21213 11616 21213 11627 21214 11616 21214 11628 21214 11628 21215 11616 21215 11629 21215 11630 632 11631 632 11632 632 11632 7585 11631 7585 11633 7585 11633 7585 11631 7585 11634 7585 11635 106 11630 106 11633 106 11633 106 11630 106 11632 106 11634 21216 11631 21216 11635 21216 11635 21217 11631 21217 11630 21217 11634 95 11635 95 11633 95 11636 21218 11637 21218 11638 21218 11636 21219 11638 21219 11639 21219 11639 21220 11638 21220 11640 21220 11639 21221 11640 21221 11641 21221 11641 21222 11640 21222 11642 21222 11641 21223 11642 21223 11643 21223 11643 21224 11642 21224 11644 21224 11643 21225 11644 21225 11645 21225 11645 21226 11644 21226 11646 21226 11645 21227 11646 21227 11647 21227 11647 21228 11646 21228 11648 21228 11647 21229 11648 21229 11649 21229 11649 21230 11648 21230 11650 21230 11649 21231 11650 21231 11651 21231 11651 21232 11650 21232 11652 21232 11651 21233 11652 21233 11653 21233 11653 21234 11652 21234 11654 21234 11653 21235 11654 21235 11655 21235 11655 21236 11654 21236 11656 21236 11655 21237 11656 21237 11657 21237 11657 21238 11656 21238 11658 21238 11657 21239 11658 21239 11659 21239 11659 21240 11658 21240 11637 21240 11659 21241 11637 21241 11636 21241 11648 21242 11660 21242 11650 21242 11650 21243 11660 21243 11661 21243 11650 21244 11661 21244 11652 21244 11652 21245 11661 21245 11662 21245 11652 21246 11662 21246 11654 21246 11654 21247 11662 21247 11663 21247 11654 21248 11663 21248 11656 21248 11656 21249 11663 21249 11664 21249 11656 21250 11664 21250 11658 21250 11658 21251 11664 21251 11665 21251 11658 21251 11665 21251 11637 21251 11637 21252 11665 21252 11666 21252 11637 21252 11666 21252 11638 21252 11638 21253 11666 21253 11667 21253 11638 21254 11667 21254 11640 21254 11640 21255 11667 21255 11668 21255 11640 21256 11668 21256 11642 21256 11642 21257 11668 21257 11669 21257 11642 21258 11669 21258 11644 21258 11644 21259 11669 21259 11670 21259 11644 21260 11670 21260 11646 21260 11646 21261 11670 21261 11671 21261 11646 21261 11671 21261 11648 21261 11648 21242 11671 21242 11660 21242 11666 21262 11672 21262 11667 21262 11667 21263 11672 21263 11673 21263 11667 21264 11673 21264 11668 21264 11668 21265 11673 21265 11674 21265 11668 21266 11674 21266 11669 21266 11669 21267 11674 21267 11675 21267 11669 21268 11675 21268 11670 21268 11670 21269 11675 21269 11676 21269 11670 21270 11676 21270 11671 21270 11671 21271 11676 21271 11677 21271 11671 21272 11677 21272 11660 21272 11660 21273 11677 21273 11678 21273 11660 21274 11678 21274 11661 21274 11661 21265 11678 21265 11679 21265 11661 21275 11679 21275 11662 21275 11662 21276 11679 21276 11680 21276 11662 21277 11680 21277 11663 21277 11663 21265 11680 21265 11681 21265 11663 21278 11681 21278 11664 21278 11664 21279 11681 21279 11682 21279 11664 21280 11682 21280 11665 21280 11665 21267 11682 21267 11683 21267 11665 21272 11683 21272 11666 21272 11666 21281 11683 21281 11672 21281 11659 632 11684 632 11657 632 11657 632 11684 632 11685 632 11657 632 11685 632 11655 632 11655 632 11685 632 11686 632 11655 632 11686 632 11653 632 11653 632 11686 632 11687 632 11653 632 11687 632 11651 632 11651 632 11687 632 11688 632 11651 632 11688 632 11649 632 11649 632 11688 632 11689 632 11649 632 11689 632 11647 632 11647 632 11689 632 11690 632 11647 632 11690 632 11645 632 11645 632 11690 632 11691 632 11645 632 11691 632 11643 632 11643 632 11691 632 11692 632 11643 632 11692 632 11641 632 11641 632 11692 632 11693 632 11641 632 11693 632 11639 632 11639 632 11693 632 11694 632 11639 632 11694 632 11636 632 11636 632 11694 632 11695 632 11636 632 11695 632 11659 632 11659 632 11695 632 11684 632 11695 21282 11696 21282 11684 21282 11684 21283 11696 21283 11697 21283 11684 21284 11697 21284 11685 21284 11685 21284 11697 21284 11698 21284 11685 21285 11698 21285 11686 21285 11686 21286 11698 21286 11699 21286 11686 21287 11699 21287 11687 21287 11687 21288 11699 21288 11700 21288 11687 16714 11700 16714 11688 16714 11688 16714 11700 16714 11701 16714 11688 21289 11701 21289 11689 21289 11689 21290 11701 21290 11702 21290 11689 21291 11702 21291 11690 21291 11690 21292 11702 21292 11703 21292 11690 16728 11703 16728 11691 16728 11691 16728 11703 16728 11704 16728 11691 21293 11704 21293 11692 21293 11692 21294 11704 21294 11705 21294 11692 21295 11705 21295 11693 21295 11693 21296 11705 21296 11706 21296 11693 21297 11706 21297 11694 21297 11694 21297 11706 21297 11707 21297 11694 21298 11707 21298 11695 21298 11695 21299 11707 21299 11696 21299 11697 21300 11682 21300 11698 21300 11698 21301 11682 21301 11681 21301 11698 21302 11681 21302 11699 21302 11699 21303 11681 21303 11680 21303 11699 21304 11680 21304 11700 21304 11700 21305 11680 21305 11679 21305 11700 21306 11679 21306 11701 21306 11701 21307 11679 21307 11678 21307 11701 21308 11678 21308 11702 21308 11702 21309 11678 21309 11677 21309 11702 21310 11677 21310 11703 21310 11703 21311 11677 21311 11676 21311 11703 21312 11676 21312 11704 21312 11704 21313 11676 21313 11675 21313 11704 21314 11675 21314 11705 21314 11705 21315 11675 21315 11674 21315 11705 21316 11674 21316 11706 21316 11706 21317 11674 21317 11673 21317 11706 21318 11673 21318 11707 21318 11707 21319 11673 21319 11672 21319 11707 21320 11672 21320 11696 21320 11696 21321 11672 21321 11683 21321 11696 21322 11683 21322 11697 21322 11697 21323 11683 21323 11682 21323 11708 21324 11709 21324 11710 21324 11711 21325 11712 21325 11710 21325 11710 21326 11712 21326 11713 21326 11710 21327 11713 21327 11708 21327 11709 21328 11714 21328 11710 21328 11710 21329 11714 21329 11715 21329 11710 21330 11715 21330 11711 21330 11711 21331 11715 21331 11712 21331 11712 21332 11715 21332 11714 21332 11712 21333 11714 21333 11713 21333 11713 21334 11714 21334 11709 21334 11713 21335 11709 21335 11708 21335 11716 95 11717 95 11718 95 11718 95 11717 95 11719 95 11720 98 11721 98 11716 98 11716 98 11721 98 11722 98 11716 21336 11722 21336 11717 21336 11716 21337 11718 21337 11720 21337 11720 21338 11718 21338 11721 21338 11722 21339 11719 21339 11717 21339 11719 21340 11722 21340 11718 21340 11718 21341 11722 21341 11721 21341 11723 21342 11724 21342 11725 21342 11725 21343 11726 21343 11723 21343 11723 21344 11726 21344 11727 21344 11723 21345 11727 21345 11728 21345 11728 21346 11729 21346 11723 21346 11723 21347 11729 21347 11730 21347 11723 21348 11730 21348 11731 21348 11731 21349 11732 21349 11723 21349 11723 21350 11732 21350 11733 21350 11723 21351 11733 21351 11734 21351 11734 21352 11733 21352 11735 21352 11736 21353 11737 21353 11738 21353 11739 21354 11740 21354 11738 21354 11738 21355 11740 21355 11741 21355 11738 21356 11741 21356 11736 21356 11739 21357 11742 21357 11743 21357 11743 21358 11742 21358 11744 21358 11736 21359 11741 21359 11743 21359 11743 21360 11741 21360 11740 21360 11743 21361 11740 21361 11739 21361 11745 21362 11746 21362 11742 21362 11742 21363 11746 21363 11747 21363 11742 21364 11747 21364 11744 21364 11748 21365 11749 21365 11750 21365 11745 21366 11742 21366 11750 21366 11750 21367 11742 21367 11751 21367 11750 21368 11751 21368 11748 21368 11752 21369 11729 21369 11728 21369 11739 21370 11738 21370 11742 21370 11742 21371 11738 21371 11737 21371 11742 21372 11737 21372 11753 21372 11748 21373 11751 21373 11754 21373 11754 21374 11751 21374 11742 21374 11754 21375 11742 21375 11755 21375 11755 21376 11742 21376 11753 21376 11755 21377 11753 21377 11756 21377 11757 21378 11748 21378 11727 21378 11727 21379 11748 21379 11754 21379 11727 21380 11754 21380 11728 21380 11728 21381 11754 21381 11755 21381 11728 21382 11755 21382 11752 21382 11752 21383 11755 21383 11756 21383 11749 21384 11723 21384 11734 21384 11749 21385 11734 21385 11750 21385 11734 21386 11758 21386 11750 21386 11750 21387 11758 21387 11759 21387 11750 21388 11759 21388 11745 21388 11745 21389 11759 21389 11746 21389 11736 21390 11743 21390 11760 21390 11760 21391 11743 21391 11744 21391 11760 21392 11744 21392 11761 21392 11753 21393 11737 21393 11736 21393 11732 21394 11731 21394 11762 21394 11762 21395 11731 21395 11730 21395 11744 21396 11747 21396 11761 21396 11761 21397 11747 21397 11746 21397 11761 21398 11746 21398 11763 21398 11763 21399 11746 21399 11759 21399 11763 21400 11759 21400 11733 21400 11733 21401 11759 21401 11758 21401 11733 21402 11758 21402 11735 21402 11735 21403 11758 21403 11734 21403 11733 21404 11732 21404 11763 21404 11763 21405 11732 21405 11762 21405 11763 21406 11762 21406 11761 21406 11761 21407 11762 21407 11764 21407 11761 21408 11764 21408 11760 21408 11736 21409 11760 21409 11753 21409 11753 21410 11760 21410 11764 21410 11753 21411 11764 21411 11756 21411 11756 21412 11764 21412 11762 21412 11756 21413 11762 21413 11752 21413 11752 21414 11762 21414 11730 21414 11752 21415 11730 21415 11729 21415 11724 21416 11765 21416 11725 21416 11725 21417 11765 21417 11757 21417 11725 21418 11757 21418 11726 21418 11726 21419 11757 21419 11727 21419 11765 21420 11724 21420 11723 21420 11749 21421 11748 21421 11723 21421 11723 21422 11748 21422 11757 21422 11723 21423 11757 21423 11765 21423 11766 106 11767 106 11768 106 11768 106 11767 106 11769 106 11770 633 11767 633 11771 633 11771 633 11767 633 11766 633 11770 21424 11771 21424 11772 21424 11773 21425 11769 21425 11774 21425 11774 21426 11769 21426 11775 21426 11774 21427 11775 21427 11776 21427 11776 21428 11775 21428 11777 21428 11776 21429 11777 21429 11778 21429 11778 21430 11777 21430 11779 21430 11778 21431 11779 21431 11780 21431 11780 21432 11779 21432 11781 21432 11780 21433 11781 21433 11782 21433 11781 21434 11770 21434 11782 21434 11782 21435 11770 21435 11772 21435 11782 21436 11772 21436 11783 21436 11783 21436 11772 21436 11784 21436 11783 21437 11784 21437 11785 21437 11785 21437 11784 21437 11786 21437 11785 21438 11786 21438 11787 21438 11787 21438 11786 21438 11788 21438 11787 21439 11788 21439 11789 21439 11789 21439 11788 21439 11790 21439 11789 21440 11790 21440 11791 21440 11791 21440 11790 21440 11792 21440 11791 21441 11792 21441 11793 21441 11793 21441 11792 21441 11794 21441 11793 21442 11794 21442 11773 21442 11773 21442 11794 21442 11795 21442 11773 21443 11795 21443 11769 21443 11769 21444 11795 21444 11768 21444 11778 95 11780 95 11796 95 11796 95 11780 95 11782 95 11796 95 11782 95 11783 95 11773 95 11774 95 11796 95 11796 95 11774 95 11776 95 11796 95 11776 95 11778 95 11789 95 11791 95 11796 95 11796 95 11791 95 11793 95 11796 95 11793 95 11773 95 11783 95 11785 95 11796 95 11796 95 11785 95 11787 95 11796 95 11787 95 11789 95 11775 632 11769 632 11767 632 11777 632 11775 632 11779 632 11779 21445 11775 21445 11767 21445 11779 21446 11767 21446 11781 21446 11781 21447 11767 21447 11770 21447 11795 21448 11794 21448 11792 21448 11772 21449 11771 21449 11766 21449 11790 21450 11788 21450 11786 21450 11768 21451 11795 21451 11766 21451 11766 21452 11795 21452 11792 21452 11766 21453 11792 21453 11772 21453 11772 21454 11792 21454 11790 21454 11772 21455 11790 21455 11784 21455 11784 21456 11790 21456 11786 21456 11797 633 11798 633 11799 633 11799 633 11798 633 11800 633 11799 633 11800 633 11801 633 11801 21457 11800 21457 11802 21457 11803 21166 11798 21166 11804 21166 11804 21458 11798 21458 11797 21458 11800 21459 11805 21459 11802 21459 11802 21459 11805 21459 11806 21459 11802 21460 11806 21460 11801 21460 11801 21461 11806 21461 11807 21461 11801 21462 11807 21462 11799 21462 11799 21463 11807 21463 11808 21463 11808 98 11804 98 11799 98 11799 98 11804 98 11797 98 11807 21464 11806 21464 11808 21464 11808 21465 11806 21465 11805 21465 11808 7585 11805 7585 11804 7585 11804 7585 11805 7585 11803 7585 11805 106 11800 106 11803 106 11803 106 11800 106 11798 106 11809 95 11810 95 11811 95 11812 95 11813 95 11814 95 11815 95 11812 95 11816 95 11816 95 11812 95 11814 95 11816 95 11814 95 11817 95 11817 95 11814 95 11811 95 11818 95 11809 95 11819 95 11819 95 11809 95 11811 95 11819 95 11811 95 11820 95 11820 95 11811 95 11814 95 11818 21466 11821 21466 11809 21466 11809 21467 11821 21467 11822 21467 11809 21468 11822 21468 11810 21468 11810 21469 11822 21469 11823 21469 11810 21470 11823 21470 11811 21470 11811 21471 11823 21471 11824 21471 11811 21472 11824 21472 11817 21472 11817 21473 11824 21473 11825 21473 11817 21474 11825 21474 11816 21474 11816 21475 11825 21475 11826 21475 11816 21476 11826 21476 11815 21476 11815 21477 11826 21477 11827 21477 11815 21478 11827 21478 11812 21478 11812 21479 11827 21479 11828 21479 11812 21480 11828 21480 11813 21480 11813 21481 11828 21481 11829 21481 11813 21482 11829 21482 11814 21482 11814 21483 11829 21483 11830 21483 11814 21484 11830 21484 11820 21484 11820 21485 11830 21485 11831 21485 11820 21486 11831 21486 11819 21486 11819 21487 11831 21487 11832 21487 11819 21488 11832 21488 11818 21488 11818 21489 11832 21489 11821 21489 11829 632 11828 632 11833 632 11833 21490 11828 21490 11827 21490 11833 21491 11827 21491 11826 21491 11832 21492 11831 21492 11833 21492 11833 632 11831 632 11830 632 11833 632 11830 632 11829 632 11823 632 11822 632 11833 632 11833 21491 11822 21491 11821 21491 11833 21490 11821 21490 11832 21490 11826 21493 11825 21493 11833 21493 11833 632 11825 632 11824 632 11833 632 11824 632 11823 632 11834 633 11835 633 11836 633 11836 633 11835 633 11837 633 11838 95 11839 95 11834 95 11834 21494 11839 21494 11835 21494 11834 21495 11836 21495 11838 21495 11838 21496 11836 21496 11840 21496 11838 7585 11840 7585 11839 7585 11839 7585 11840 7585 11841 7585 11839 21497 11841 21497 11835 21497 11835 21498 11841 21498 11837 21498 11840 632 11836 632 11841 632 11841 632 11836 632 11837 632 11842 21499 11843 21499 11844 21499 11845 21500 11846 21500 11847 21500 11848 95 11849 95 11850 95 11850 95 11849 95 11842 95 11850 95 11842 95 11847 95 11847 95 11842 95 11844 95 11847 95 11844 95 11845 95 11845 21501 11844 21501 11851 21501 11845 95 11851 95 11852 95 11852 95 11851 95 11853 95 11850 21502 11854 21502 11848 21502 11848 21503 11854 21503 11855 21503 11848 21504 11855 21504 11849 21504 11849 21505 11855 21505 11856 21505 11849 21470 11856 21470 11842 21470 11842 21471 11856 21471 11857 21471 11842 21472 11857 21472 11843 21472 11843 21473 11857 21473 11858 21473 11843 21506 11858 21506 11844 21506 11844 21507 11858 21507 11859 21507 11844 21508 11859 21508 11851 21508 11851 21509 11859 21509 11860 21509 11851 21510 11860 21510 11853 21510 11853 21510 11860 21510 11861 21510 11853 21511 11861 21511 11852 21511 11852 21512 11861 21512 11862 21512 11852 21482 11862 21482 11845 21482 11845 21483 11862 21483 11863 21483 11845 21484 11863 21484 11846 21484 11846 21485 11863 21485 11864 21485 11846 21513 11864 21513 11847 21513 11847 21514 11864 21514 11865 21514 11847 21515 11865 21515 11850 21515 11850 21515 11865 21515 11854 21515 11862 632 11861 632 11866 632 11866 21516 11861 21516 11860 21516 11866 21517 11860 21517 11859 21517 11865 21518 11864 21518 11866 21518 11866 632 11864 632 11863 632 11866 632 11863 632 11862 632 11856 632 11855 632 11866 632 11866 21517 11855 21517 11854 21517 11866 21516 11854 21516 11865 21516 11859 21493 11858 21493 11866 21493 11866 632 11858 632 11857 632 11866 632 11857 632 11856 632 11867 632 11868 632 11869 632 11870 632 11871 632 11872 632 11873 632 11874 632 11867 632 11875 632 11873 632 11876 632 11876 632 11873 632 11867 632 11876 632 11867 632 11872 632 11872 632 11867 632 11869 632 11872 632 11869 632 11870 632 11870 632 11869 632 11877 632 11878 21519 11879 21519 11880 21519 11881 21520 11882 21520 11880 21520 11883 21521 11884 21521 11880 21521 11880 21522 11885 21522 11886 21522 11887 21523 11880 21523 11886 21523 11888 21524 11885 21524 11880 21524 11889 21525 11880 21525 11890 21525 11880 21526 11891 21526 11892 21526 11893 21527 11880 21527 11892 21527 11889 21528 11891 21528 11880 21528 11884 21529 11888 21529 11880 21529 11882 21530 11883 21530 11880 21530 11893 21531 11881 21531 11880 21531 11880 21532 11894 21532 11895 21532 11896 21533 11880 21533 11895 21533 11897 21534 11894 21534 11880 21534 11898 21535 11890 21535 11896 21535 11896 21536 11890 21536 11880 21536 11879 21537 11897 21537 11880 21537 11887 21538 11878 21538 11880 21538 11892 21539 11869 21539 11893 21539 11893 21540 11869 21540 11868 21540 11893 21541 11868 21541 11881 21541 11881 21542 11868 21542 11882 21542 11882 21543 11868 21543 11867 21543 11882 21544 11867 21544 11883 21544 11883 21545 11867 21545 11884 21545 11884 21546 11867 21546 11874 21546 11884 21547 11874 21547 11888 21547 11888 21548 11874 21548 11873 21548 11888 21549 11873 21549 11885 21549 11885 21550 11873 21550 11875 21550 11885 21551 11875 21551 11886 21551 11886 21552 11875 21552 11876 21552 11886 21553 11876 21553 11887 21553 11887 21554 11876 21554 11872 21554 11887 21555 11872 21555 11878 21555 11878 21556 11872 21556 11879 21556 11879 21557 11872 21557 11871 21557 11879 21558 11871 21558 11897 21558 11897 21559 11871 21559 11894 21559 11894 21560 11871 21560 11870 21560 11894 21561 11870 21561 11895 21561 11895 21562 11870 21562 11896 21562 11896 21563 11870 21563 11877 21563 11896 21564 11877 21564 11898 21564 11892 98 11891 98 11869 98 11869 98 11891 98 11889 98 11869 98 11889 98 11877 98 11877 98 11889 98 11890 98 11877 98 11890 98 11898 98 11899 632 11900 632 11901 632 11901 21565 11900 21565 11902 21565 11901 21566 11902 21566 11903 21566 11904 21567 11905 21567 11901 21567 11901 632 11905 632 11906 632 11901 632 11906 632 11899 632 11907 632 11908 632 11901 632 11901 21568 11908 21568 11909 21568 11901 21569 11909 21569 11904 21569 11903 21570 11910 21570 11901 21570 11901 632 11910 632 11911 632 11901 632 11911 632 11907 632 11912 21571 11909 21571 11913 21571 11913 21572 11909 21572 11908 21572 11913 21573 11908 21573 11914 21573 11914 21574 11908 21574 11907 21574 11914 21575 11907 21575 11915 21575 11915 21576 11907 21576 11911 21576 11915 21577 11911 21577 11916 21577 11916 21578 11911 21578 11910 21578 11916 21579 11910 21579 11917 21579 11917 21580 11910 21580 11903 21580 11917 21581 11903 21581 11918 21581 11918 21582 11903 21582 11902 21582 11918 21583 11902 21583 11919 21583 11919 21584 11902 21584 11900 21584 11919 21585 11900 21585 11920 21585 11920 21586 11900 21586 11899 21586 11920 21587 11899 21587 11921 21587 11921 21588 11899 21588 11906 21588 11921 21589 11906 21589 11922 21589 11922 21590 11906 21590 11905 21590 11922 21591 11905 21591 11923 21591 11923 21592 11905 21592 11904 21592 11923 21593 11904 21593 11912 21593 11912 21594 11904 21594 11909 21594 11924 21595 11913 21595 11914 21595 11912 21596 11913 21596 11924 21596 11924 21597 11916 21597 11917 21597 11915 21598 11916 21598 11924 21598 11914 21599 11915 21599 11924 21599 11924 21600 11919 21600 11920 21600 11918 21601 11919 21601 11924 21601 11917 21602 11918 21602 11924 21602 11924 21603 11922 21603 11923 21603 11921 21604 11922 21604 11924 21604 11920 21605 11921 21605 11924 21605 11923 21606 11912 21606 11924 21606 11925 632 11926 632 11927 632 11927 21607 11926 21607 11928 21607 11927 21608 11928 21608 11929 21608 11930 632 11931 632 11927 632 11927 632 11931 632 11932 632 11927 632 11932 632 11925 632 11933 632 11934 632 11927 632 11927 21609 11934 21609 11935 21609 11927 21610 11935 21610 11930 21610 11929 632 11936 632 11927 632 11927 632 11936 632 11937 632 11927 632 11937 632 11933 632 11938 21611 11939 21611 11940 21611 11941 21612 11939 21612 11938 21612 11938 21613 11942 21613 11943 21613 11944 21614 11942 21614 11938 21614 11940 21615 11944 21615 11938 21615 11938 21616 11945 21616 11946 21616 11947 21617 11945 21617 11938 21617 11943 21618 11947 21618 11938 21618 11938 21619 11948 21619 11949 21619 11950 21620 11948 21620 11938 21620 11946 21621 11950 21621 11938 21621 11949 21622 11941 21622 11938 21622 11941 21623 11935 21623 11939 21623 11939 21624 11935 21624 11934 21624 11939 21625 11934 21625 11940 21625 11940 21626 11934 21626 11933 21626 11940 21627 11933 21627 11944 21627 11944 21628 11933 21628 11937 21628 11944 21629 11937 21629 11942 21629 11942 21630 11937 21630 11936 21630 11942 21631 11936 21631 11943 21631 11943 21632 11936 21632 11929 21632 11943 21581 11929 21581 11947 21581 11947 21582 11929 21582 11928 21582 11947 21583 11928 21583 11945 21583 11945 21584 11928 21584 11926 21584 11945 21633 11926 21633 11946 21633 11946 21634 11926 21634 11925 21634 11946 21635 11925 21635 11950 21635 11950 21636 11925 21636 11932 21636 11950 21637 11932 21637 11948 21637 11948 21638 11932 21638 11931 21638 11948 21639 11931 21639 11949 21639 11949 21640 11931 21640 11930 21640 11949 21641 11930 21641 11941 21641 11941 21642 11930 21642 11935 21642 11951 21643 11952 21643 11953 21643 11954 21644 11952 21644 11951 21644 11951 21645 11955 21645 11956 21645 11957 21646 11955 21646 11951 21646 11953 21647 11957 21647 11951 21647 11951 21648 11958 21648 11959 21648 11960 21649 11958 21649 11951 21649 11956 21650 11960 21650 11951 21650 11951 21651 11961 21651 11962 21651 11963 21652 11961 21652 11951 21652 11959 21653 11963 21653 11951 21653 11962 21654 11954 21654 11951 21654 11954 21655 11964 21655 11952 21655 11952 21656 11964 21656 11965 21656 11952 21657 11965 21657 11953 21657 11953 21658 11965 21658 11966 21658 11953 21659 11966 21659 11957 21659 11957 21660 11966 21660 11967 21660 11957 21661 11967 21661 11955 21661 11955 21662 11967 21662 11968 21662 11955 21663 11968 21663 11956 21663 11956 21664 11968 21664 11969 21664 11956 21665 11969 21665 11960 21665 11960 21666 11969 21666 11970 21666 11960 21667 11970 21667 11958 21667 11958 21668 11970 21668 11971 21668 11958 21669 11971 21669 11959 21669 11959 21670 11971 21670 11972 21670 11959 21671 11972 21671 11963 21671 11963 21671 11972 21671 11973 21671 11963 21672 11973 21672 11961 21672 11961 21672 11973 21672 11974 21672 11961 21673 11974 21673 11962 21673 11962 2566 11974 2566 11975 2566 11962 21674 11975 21674 11954 21674 11954 21675 11975 21675 11964 21675 11965 21676 11976 21676 11966 21676 11966 21677 11976 21677 11977 21677 11966 21678 11977 21678 11967 21678 11967 21679 11977 21679 11978 21679 11967 21680 11978 21680 11968 21680 11968 21681 11978 21681 11979 21681 11968 21682 11979 21682 11969 21682 11969 21683 11979 21683 11980 21683 11969 21684 11980 21684 11970 21684 11970 21685 11980 21685 11981 21685 11970 21686 11981 21686 11971 21686 11971 21687 11981 21687 11982 21687 11971 21688 11982 21688 11972 21688 11972 21689 11982 21689 11983 21689 11972 21690 11983 21690 11973 21690 11973 21691 11983 21691 11984 21691 11973 21692 11984 21692 11974 21692 11974 21693 11984 21693 11985 21693 11974 21694 11985 21694 11975 21694 11975 21695 11985 21695 11986 21695 11975 21696 11986 21696 11964 21696 11964 21697 11986 21697 11987 21697 11964 21698 11987 21698 11965 21698 11965 21699 11987 21699 11976 21699 11983 632 11982 632 11988 632 11988 21700 11982 21700 11981 21700 11988 21701 11981 21701 11980 21701 11986 21702 11985 21702 11988 21702 11988 632 11985 632 11984 632 11988 632 11984 632 11983 632 11977 21703 11976 21703 11988 21703 11988 21704 11976 21704 11987 21704 11988 21705 11987 21705 11986 21705 11980 632 11979 632 11988 632 11988 632 11979 632 11978 632 11988 632 11978 632 11977 632 11989 21706 11990 21706 11991 21706 11992 21707 11990 21707 11989 21707 11989 21708 11993 21708 11994 21708 11995 21709 11993 21709 11989 21709 11991 21710 11995 21710 11989 21710 11989 21711 11996 21711 11997 21711 11998 21712 11996 21712 11989 21712 11994 21713 11998 21713 11989 21713 11989 21714 11999 21714 12000 21714 12001 21715 11999 21715 11989 21715 11997 21716 12001 21716 11989 21716 12000 21717 11992 21717 11989 21717 11992 21718 12002 21718 11990 21718 11990 21718 12002 21718 12003 21718 11990 21719 12003 21719 11991 21719 11991 21720 12003 21720 12004 21720 11991 21721 12004 21721 11995 21721 11995 21722 12004 21722 12005 21722 11995 21723 12005 21723 11993 21723 11993 21724 12005 21724 12006 21724 11993 21725 12006 21725 11994 21725 11994 21726 12006 21726 12007 21726 11994 21727 12007 21727 11998 21727 11998 21728 12007 21728 12008 21728 11998 21729 12008 21729 11996 21729 11996 21730 12008 21730 12009 21730 11996 21731 12009 21731 11997 21731 11997 21732 12009 21732 12010 21732 11997 21733 12010 21733 12001 21733 12001 21734 12010 21734 12011 21734 12001 21735 12011 21735 11999 21735 11999 21736 12011 21736 12012 21736 11999 21737 12012 21737 12000 21737 12000 21738 12012 21738 12013 21738 12000 21739 12013 21739 11992 21739 11992 21739 12013 21739 12002 21739 12003 21740 12014 21740 12004 21740 12004 21741 12014 21741 12015 21741 12004 21742 12015 21742 12005 21742 12005 21743 12015 21743 12016 21743 12005 21744 12016 21744 12006 21744 12006 21681 12016 21681 12017 21681 12006 21745 12017 21745 12007 21745 12007 21746 12017 21746 12018 21746 12007 21747 12018 21747 12008 21747 12008 21748 12018 21748 12019 21748 12008 21749 12019 21749 12009 21749 12009 21750 12019 21750 12020 21750 12009 21751 12020 21751 12010 21751 12010 21752 12020 21752 12021 21752 12010 21753 12021 21753 12011 21753 12011 21754 12021 21754 12022 21754 12011 21755 12022 21755 12012 21755 12012 21756 12022 21756 12023 21756 12012 21757 12023 21757 12013 21757 12013 21758 12023 21758 12024 21758 12013 21759 12024 21759 12002 21759 12002 21760 12024 21760 12025 21760 12002 21761 12025 21761 12003 21761 12003 21762 12025 21762 12014 21762 12021 632 12020 632 12026 632 12026 21763 12020 21763 12019 21763 12026 21764 12019 21764 12018 21764 12024 21765 12023 21765 12026 21765 12026 632 12023 632 12022 632 12026 632 12022 632 12021 632 12015 21766 12014 21766 12026 21766 12026 21767 12014 21767 12025 21767 12026 21768 12025 21768 12024 21768 12018 21769 12017 21769 12026 21769 12026 632 12017 632 12016 632 12026 632 12016 632 12015 632 12027 632 12028 632 12029 632 12030 632 12031 632 12032 632 12033 632 12034 632 12035 632 12035 632 12034 632 12027 632 12035 632 12027 632 12036 632 12036 632 12027 632 12029 632 12027 632 12037 632 12028 632 12028 632 12037 632 12030 632 12028 632 12030 632 12038 632 12038 632 12030 632 12032 632 12039 95 12040 95 12041 95 12042 95 12043 95 12044 95 12045 95 12046 95 12044 95 12044 95 12046 95 12047 95 12047 21770 12039 21770 12044 21770 12044 95 12039 95 12041 95 12044 95 12041 95 12042 95 12042 95 12041 95 12048 95 12042 95 12048 95 12049 95 12049 95 12048 95 12050 95 12032 21771 12050 21771 12038 21771 12038 21772 12050 21772 12048 21772 12038 21773 12048 21773 12028 21773 12028 21774 12048 21774 12041 21774 12028 21775 12041 21775 12029 21775 12029 21776 12041 21776 12040 21776 12029 21777 12040 21777 12036 21777 12036 21778 12040 21778 12039 21778 12036 21779 12039 21779 12035 21779 12035 21780 12039 21780 12047 21780 12035 98 12047 98 12033 98 12033 98 12047 98 12046 98 12033 21781 12046 21781 12034 21781 12034 21782 12046 21782 12045 21782 12034 21783 12045 21783 12027 21783 12027 21784 12045 21784 12044 21784 12027 21785 12044 21785 12037 21785 12037 21786 12044 21786 12043 21786 12037 21787 12043 21787 12030 21787 12030 21788 12043 21788 12042 21788 12030 21789 12042 21789 12031 21789 12031 21790 12042 21790 12049 21790 12050 106 12032 106 12049 106 12049 106 12032 106 12031 106 12051 632 12052 632 12053 632 12053 7585 12052 7585 12054 7585 12054 7585 12052 7585 12055 7585 12054 106 12056 106 12053 106 12053 106 12056 106 12051 106 12055 21791 12052 21791 12056 21791 12056 21792 12052 21792 12051 21792 12055 95 12056 95 12054 95 12057 7585 12058 7585 12059 7585 12059 7585 12058 7585 12060 7585 12061 95 12062 95 12063 95 12060 95 12061 95 12059 95 12059 95 12061 95 12063 95 12059 95 12063 95 12064 95 12064 95 12063 95 12065 95 12060 21793 12058 21793 12061 21793 12061 21794 12058 21794 12066 21794 12061 21795 12066 21795 12062 21795 12062 21796 12066 21796 12067 21796 12062 21797 12067 21797 12063 21797 12063 21798 12067 21798 12068 21798 12063 21799 12068 21799 12065 21799 12065 21800 12068 21800 12069 21800 12065 21801 12069 21801 12064 21801 12064 21802 12069 21802 12070 21802 12064 21803 12070 21803 12059 21803 12059 21804 12070 21804 12057 21804 12058 21805 12057 21805 12070 21805 12068 21806 12067 21806 12066 21806 12058 21807 12070 21807 12066 21807 12066 21808 12070 21808 12069 21808 12066 21809 12069 21809 12068 21809

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_distal/bt_2p/th_distal_bt_2p.dae b/URDFs/sr_description/meshes/components/th_distal/bt_2p/th_distal_bt_2p.dae new file mode 100644 index 0000000..f66c8b1 --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_distal/bt_2p/th_distal_bt_2p.dae @@ -0,0 +1,235 @@ + + + + + + Blender User + Blender 2.65.0 r52920 + + 2012-12-14T09:15:39 + 2012-12-14T09:15:39 + + Y_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0.000999987 + 1 + 0.1 + 0.1 + 1 + 1 + 1 + 2 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 2880 + 2 + 30.002 + 1.000799 + 0.04999995 + 29.99998 + 1 + 2 + 0 + 0 + 1 + 1 + 1 + 1 + 8192 + 1 + 1 + 0 + 1 + 1 + 1 + 3 + 0 + 0 + 0 + 0 + 45 + 0 + 1 + 1 + 1 + 3 + 0.15 + 75 + 1 + 1 + 0 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.248 0.68 0.336 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + -0.02630311 -0.145797 1.812762 0.03092855 -0.1589426 1.848879 -0.05050516 -0.1606379 1.853537 -0.03244769 0.1744402 1.011661 -0.03504699 0.1550523 0.9901369 -0.1102896 0.1540641 1.003041 0.1439927 -0.2949027 1.845797 0.1553341 -0.316236 1.832981 0.1172378 -0.3297742 1.870098 0.1665669 -0.4779156 1.658597 0.1954912 -0.4535934 1.68678 0.1449141 -0.5027391 1.708237 0.01737165 0.01660853 1.389251 0.03943461 0.02156704 1.375564 0.03237915 0.03111761 1.346405 0.2914574 -0.03352451 0.04756832 0.2487289 -0.08352851 0.01274698 0.2731174 -0.02436941 0.01741623 -1.95711e-4 0.1415239 1.402911 0.0120902 0.1408236 1.402657 -0.09831357 0.1257223 1.39716 0.0266655 0.08223986 1.391816 0.05361992 0.07285314 1.417605 0.04837381 0.07059931 1.423798 -0.02310633 0.105547 1.462541 -0.04182416 0.0878911 1.464527 -0.03003853 0.09385305 1.465076 -0.1386583 -0.255604 1.843512 -0.1545192 -0.2797141 1.855967 -0.1821019 -0.2452862 1.796298 -0.0111652 0.2705328 0.4896604 0.009399414 0.270702 0.2524672 -0.04291498 0.2700616 0.495241 -0.02292245 -0.2269002 1.784326 0.004561364 -0.07868379 1.83395 -0.01694363 -0.08024412 1.838237 -0.03242844 -0.2870759 0.7746403 0.00184983 -0.280487 0.7528116 0.04429644 -0.2840577 0.7864748 0.0254262 0.2694172 0.5025365 0.2008923 -0.1922207 0.8514864 0.2118269 -0.1972813 0.8333411 0.2609542 -0.129875 0.8596956 -0.1711627 -0.11699 1.921852 -0.1470984 -0.09065634 1.933253 -0.1807508 -0.06888401 1.886231 0.04234278 -0.04339772 1.865057 0.03832364 -0.04737448 1.869551 0.04621917 -0.03954946 1.860115 -0.09875059 -0.2761061 1.883057 -0.225494 -0.1973027 0.8496111 -0.2594479 -0.1813299 0.8332999 -0.1953749 -0.232625 0.8255243 -0.1969338 -0.04529953 1.053185 -0.1907292 -0.02130031 1.070489 -0.1874027 -0.0127905 1.023944 -0.005622506 -0.01219367 1.825848 -0.008421957 -0.0300334 1.864121 0.00266385 -0.0177263 1.837894 -0.05133241 0.2696741 0.6046035 -0.1267825 0.2613348 0.7512629 -0.02822643 0.27068 0.7529202 0.183605 0.1259281 1.302698 0.1745103 0.1443215 1.276648 0.1806342 0.1308308 1.309003 -0.089962 0.01819443 1.157508 -0.05888694 0.08890432 1.093813 -0.09344935 0.07303315 1.095531 0.02497982 -0.1667178 0.9580184 -0.03052014 -0.1251941 0.972746 -0.0462082 -0.1724945 0.9561694 0.0322507 -0.2328251 1.434923 0.02755844 -0.09431064 1.404784 0.0511741 -0.09294974 1.411901 -0.07177525 0.268218 0.579496 -0.01321023 0.2304368 0.6167596 0.03056514 0.2305037 0.5968503 -0.0151031 0.1944255 0.5524389 -0.1718906 0.1554031 1.252542 -0.1852452 0.1527155 1.257302 -0.1829996 0.1635519 1.270121 0.06686615 -0.05592066 1.771409 0.06882601 -0.02182239 1.794676 0.06604051 -0.07283163 1.817871 -0.0403673 0.1205573 1.443794 0.007081806 0.1129678 1.455312 -0.008453726 0.1283624 1.432422 -0.07844161 0.2676398 0.5458982 0.1803687 0.0516597 0.9617278 0.1308607 0.1069294 0.9775844 0.136761 0.1207531 0.9950689 0.03958553 -0.4833888 1.691969 -0.006894111 -0.4873276 1.671205 0.009230673 -0.4906517 1.722068 -0.03691148 -0.003476798 1.727756 -0.02846127 -0.03512382 1.714272 -0.04374051 -0.03645998 1.717941 0.04293459 0.2304477 0.5264178 0.0130521 0.230404 0.4954838 -0.1576937 0.04696714 1.215109 -0.01169759 0.03222167 1.256547 0.1204284 0.04148459 1.230002 -0.1224067 0.2622367 0.2524387 0.04742425 -0.00713706 1.748561 0.054452 -0.04708141 1.747123 0.04784429 -0.04429745 1.739475 0.1050807 -0.002204239 1.018064 0.06055968 -0.06858175 0.9933513 0.08233839 -0.1343714 0.969689 -0.06688684 0.2685987 0.5170424 -0.06330513 -0.06480109 1.795807 -0.09231376 -0.05160295 1.759546 -0.04826843 -0.05206537 1.760816 -0.05816346 -0.2250872 1.931738 -0.04161649 -0.2135827 1.91811 -0.02329021 -0.2261331 1.935355 0.1208586 -0.1114528 1.467167 0.1161074 -0.1187624 1.481307 0.1020332 -0.1129773 1.459724 -0.03521966 -0.0920999 1.87081 -0.04694139 -0.09086674 1.867422 -0.08351707 -0.2632297 0.8958711 -0.06665986 -0.3401129 1.091342 -0.1247431 -0.3116288 1.068408 -0.05470889 -0.07716041 1.868386 -0.06208688 -0.08818501 1.860056 0.1330721 -0.1411746 0.9702992 0.1121389 -0.1732608 0.9632732 0.1169559 -0.1541488 0.9624215 0.02506834 -0.04668813 1.876561 0.02212983 -0.09007847 1.865255 0.02772015 -0.02618992 1.885111 0.06437379 -0.270065 0.8198546 0.1373685 -0.2504904 0.8139687 0.130326 -0.2427765 0.8330833 0.1160516 -0.1517673 1.563144 0.1096081 -0.1577627 1.57672 0.04191964 -0.2662892 1.52691 -0.04908919 0.09815943 1.465029 0.002645075 0.05957537 1.454086 -0.05175095 0.06132292 1.449285 0.03398293 0.2688339 0.5947837 -0.01180529 0.2706436 0.6158927 -0.01371937 -0.04688084 1.746572 0.03557598 -0.03773498 1.721444 -0.03360301 -0.03280007 1.707885 -0.007892727 -0.1086679 1.688679 0.03680336 -0.1165143 1.703422 0.01709276 -0.1240788 1.684972 0.05645811 -0.135219 1.715177 0.03519451 -0.02232927 1.405333 -0.02901434 -0.2848826 1.973121 -0.05381596 -0.2504708 1.954295 -0.1151686 -0.271925 1.950581 -0.2888813 -0.1367592 0.8560286 -0.06274157 0.04506742 1.310975 -0.0844053 0.03449028 1.304093 -0.0905596 0.0293076 1.329957 -0.009831786 -0.2753305 1.551856 0.05040222 -0.1783258 1.642086 0.01098966 -0.1837949 1.653415 0.03185343 -0.00639373 1.800285 0.04433864 -0.00844264 1.799444 0.0369392 -9.60255e-4 1.777189 -0.2194406 -0.1285868 1.152557 -0.1995561 -0.1786636 1.138172 -0.1847423 -0.1286051 1.019858 -0.00560677 0.1605313 1.232066 -0.03846305 0.1617856 1.232066 -0.0819472 0.1705203 1.242125 0.03200346 0.01862233 1.361023 0.04412496 -0.001269161 1.415675 -0.005467653 0.007808983 1.390733 0.04527384 0.03997296 1.319169 0.04601961 0.03459167 1.2889 0.02489089 0.04656416 1.284047 0.03118377 -0.04299646 1.871902 0.283092 0.1398541 0.06142687 0.2956926 0.0793448 0.04678535 0.2704686 0.1418717 0.02835202 0.2538739 -0.1536321 0.8252031 0.2768259 -0.1131846 0.8350475 0.2811299 -0.09065437 0.8673251 0.04401731 -0.531045 1.809513 0.03306019 -0.5037731 1.865726 -0.01927739 -0.5355996 1.815055 -0.0739085 -0.04286062 1.735527 -0.06791228 -0.001980543 1.744838 -0.06281703 -0.03977662 1.727054 -0.02934122 0.05663418 1.256587 0.02307182 0.03188806 1.256049 0.04159325 0.05025482 1.274114 -0.1735662 -0.03330403 1.824608 -0.030761 0.04562693 1.609361 -0.03425925 0.05327129 1.588358 0.256214 -0.0881586 1.159215 0.2569631 -0.2998731 1.744082 0.2457853 -0.3636199 1.712514 -0.04694145 0.06304228 1.44456 -0.05470889 0.0767458 1.445523 -0.06208568 0.06572371 1.437195 0.05062538 0.05283302 1.233425 0.05682224 0.1590604 1.235397 0.07376688 0.04657191 1.235662 -0.05222952 0.01271027 1.377267 -0.07179909 -0.002288997 1.418477 -0.110569 0.019113 1.359675 0.05998313 -0.03852415 1.84501 0.05361998 -0.08105587 1.840467 0.08461487 -0.3065196 1.891564 -0.05526286 0.003225862 1.740322 -0.0422604 0.005658626 1.736139 -0.04888755 0.004284441 1.737893 -0.05340373 -0.2203913 1.766443 -0.04584616 -0.07628762 1.827367 0.04806792 0.267655 0.5450609 0.04853606 -0.01440888 1.013069 -0.2850582 -0.1119282 1.157661 -0.2836633 -0.3340377 1.722264 -0.2862661 -0.06597131 1.177376 0.04329234 -0.1303758 1.792945 0.05630147 -0.1279585 1.775037 0.04633224 -0.1138303 1.740349 -0.07775622 -0.08350002 1.847182 -0.08263444 -0.03711605 1.853349 -0.08976292 -0.07788211 1.831747 -0.01098501 -0.01203888 1.825903 -0.08333426 -0.01988202 1.823044 -0.01451534 -0.0120061 1.825919 -0.08342534 0.01068496 1.380224 -0.1022245 2.33674e-4 1.346019 -0.08538979 -0.001995682 1.386853 -0.02685588 0.06117075 1.449701 -0.0209887 0.1127983 1.468865 -0.02848374 -0.003435969 1.80136 -0.02360743 -0.002861142 1.801476 -0.0365985 0.001278519 1.784471 0.08355146 0.2629684 0.7527164 -0.05624479 -0.1385548 1.792864 -0.04968982 -0.07510668 1.824122 0.04695188 0.2304649 0.5636583 -0.2529471 -0.3084556 1.845014 -0.2413276 -0.2668363 1.853145 -0.27472 -0.2795643 1.798048 0.1157329 0.052863 1.241345 0.1176522 0.05132371 1.242588 0.1195524 0.04856437 1.243364 -0.08598184 -0.04440701 1.739775 -0.06334704 -0.06341701 1.792005 0.129373 -0.171864 1.814124 0.06955444 -0.005118966 1.359185 0.05599182 -0.01467722 1.38608 0.01192319 0.1079389 1.458161 0.02506834 0.1072177 1.4537 0.04219341 0.1123737 1.4417 -0.1735782 -0.1282713 0.8871033 -0.1113049 -0.1933267 0.8658366 -0.1616044 -0.1897262 0.8810364 -0.1498392 -0.07005357 0.9081369 -0.1416282 -0.06190383 0.9202819 -0.1526585 -0.01654738 0.9289627 0.07770383 0.03164392 1.325247 0.08036291 -0.002910971 1.351659 0.07310616 0.01224261 1.378551 0.03055679 0.03896367 1.033103 0.08250725 0.04305309 1.046824 0.01403957 0.05756157 1.047141 0.01553392 -0.1982117 1.705506 -0.004549801 -0.0474022 1.748004 0.02965843 -0.05730217 1.775204 -0.05666136 0.1025621 1.454669 -0.05037641 0.1078547 1.45552 0.1624584 0.2474544 0.752236 0.1984094 0.2349895 0.2524345 -0.1281401 -0.2158167 1.916072 -0.1674637 -0.2036994 1.884229 -0.2000337 -0.1827029 1.816158 0.05531102 0.1333823 1.399949 0.04491931 0.1364424 1.401093 -0.1925506 0.2472994 0.7521265 -0.1928315 0.2475702 0.2524387 -0.01947057 -0.2728541 1.545407 -0.04567807 -0.1753332 1.642641 0.02090173 -0.1754959 1.643058 0.1370425 -0.1271457 1.924961 0.1707794 -0.1812574 1.85559 0.1659528 -0.1043271 1.889304 -0.04410868 0.03105491 1.327383 -0.05322527 0.02520132 1.351497 -0.03438395 0.004936158 1.354915 0.003619432 -0.2054893 1.725501 -0.001472413 -0.1838814 1.665092 0.08589571 -0.1684979 1.619316 -0.02639251 -0.07322388 1.362104 -0.111226 -0.1058182 1.451567 -0.05110466 -0.09200012 1.413603 -0.08806085 -0.02116596 1.822675 -0.08237087 -0.01957118 1.823159 -0.01995015 0.05762869 1.576386 -0.01540344 -0.214038 0.9408974 -0.05613297 -0.2135646 0.9438618 -0.1016736 -0.1926202 0.949199 -0.02080827 0.1589291 1.298066 -0.01710659 0.1211258 1.284978 0.02858477 0.1173055 1.295474 -0.04198557 0.03931516 1.238238 -0.09596288 0.03576016 1.245647 -0.1120867 0.03693306 1.243881 -0.1428174 -0.1654234 0.9611198 -0.128213 -0.1875118 0.96203 -0.1445505 -0.1731925 0.9659653 -0.1603659 -0.138434 0.9684094 -0.1828289 -0.1156295 0.9878912 -0.1844676 -0.09080165 0.9881859 0.03044629 -0.292298 1.904137 0.02441859 -0.330323 1.914194 -0.03649473 -0.3009781 1.911405 -0.1085903 -0.2754123 0.7947295 -0.1046963 -0.2702823 0.8155787 0.02939307 -0.2046771 1.723269 0.08333599 -0.1607442 1.602536 -0.1632128 -0.2173081 0.8536136 -0.1467044 -0.241568 0.8393051 -0.05311912 -0.2679786 0.8296875 0.01547193 -0.09212368 1.414025 0.03194028 -0.05253916 1.305274 -0.05837053 0.03579354 1.331932 -0.1267214 -0.2140343 1.902331 -0.164699 -0.1740368 1.817281 0.009651541 0.1501195 1.378264 0.0299282 0.1486558 1.377008 -0.007767081 0.1580173 1.352868 -0.05673897 -0.03850674 1.723565 0.2691687 -0.09755426 0.04680019 0.2096865 -0.1474986 0.01296728 -0.05396795 -0.2635236 1.881308 0.1060456 -0.241052 1.822265 0.02150404 -0.2337992 1.436714 0.02761906 -0.3813497 1.387466 0.04616552 -0.2457456 1.469688 -0.0867815 -0.009129941 1.764473 -0.08333599 -0.04648447 1.745483 0.119684 0.1561143 1.245633 0.08398473 0.05374157 1.236538 -0.008659243 -0.0461204 1.884165 0.01195865 -0.04898512 1.882447 0.01816493 0.1491595 1.378022 0.02583611 0.1482756 1.3777 -0.02986145 -0.01243567 1.825754 -0.03144472 -0.01835155 1.839442 -0.0256493 -0.01229411 1.825806 0.02617418 -0.2142822 1.917518 -0.006529688 -0.214663 1.919821 -0.02308636 -0.2039579 1.903066 0.06112611 -0.0312007 0.9218226 0.140479 -0.1390021 0.8835672 0.04023551 -0.07619959 0.9054443 -0.01418578 0.1420791 1.403177 -0.01036036 0.1418628 1.403037 -0.1399882 -0.2395274 0.905276 -0.1710689 -0.2930188 1.092758 -0.1871371 -0.2210416 0.9627432 -0.02847516 0.1631419 1.313426 -0.02225965 0.1573652 1.304787 -0.02936536 0.157056 1.305636 0.2478113 0.1324118 0.9273348 0.2067666 0.1629081 0.9343965 0.2168511 0.1385501 0.9534543 0.04621917 0.1143627 1.437252 0.03832364 0.1065348 1.446689 0.1634331 0.01733207 1.275784 0.1715927 -0.1809263 1.811913 0.1534687 -0.1630614 1.778974 0.1004913 -0.2152431 1.903756 0.1681531 -0.1882351 1.845953 -0.09123098 -0.01339989 1.797668 0.06816488 -0.01937335 1.795561 -0.08606719 -0.01181524 1.79831 0.1199383 -0.149593 0.9839819 0.1519588 -0.1332675 1.016159 0.1389946 -0.1162791 0.9952211 -0.03252077 0.141384 1.40286 -0.03774809 0.1411222 1.402768 -0.02941155 0.1418893 1.403666 0.1211656 -0.1062543 1.937616 0.09024709 -0.1326844 1.960376 0.00539875 -0.105381 1.725383 0.009983122 -0.1026945 1.708132 -0.03527796 -0.1018245 1.7131 0.006500899 0.01474601 1.02368 0.1549189 -0.25233 1.802441 0.1111174 -0.2724521 1.861008 0.06139826 0.02673721 1.31048 -0.04476225 -0.2261568 0.9726227 -0.05823105 -0.2387862 0.9970157 -0.03229629 -0.2412784 0.991618 0.1609442 -0.1736025 1.800639 0.1405496 0.0509305 1.199294 -0.07971656 -0.19001 0.9610014 -0.02616012 -0.2001037 0.9560254 0.06747043 -0.1344057 1.752725 0.0716474 -0.1500799 1.756064 0.05870181 -0.1256924 1.728446 -0.06245732 -0.2696839 1.536191 -0.1207497 -0.1663264 1.614877 -0.1322401 -0.1619325 1.594228 0.05647987 0.1057281 1.327282 0.06088668 0.1438288 1.352696 0.06304669 0.1015173 1.338852 -0.1743221 0.00918138 1.069727 -0.1759823 -0.001831471 1.113236 -0.1841903 -0.007989406 1.058222 -0.02297991 0.1506672 1.378567 -0.02018469 0.1514189 1.378517 -0.02848404 0.1505759 1.378525 -0.09399235 0.03197228 1.031245 -0.09595501 0.05159413 1.051376 -0.1509385 0.01860982 1.041233 0.02979457 0.08400088 1.386977 0.07399159 0.08270043 1.39055 0.03144317 0.0938819 1.359829 0.06581401 -0.01528626 1.786885 0.06304675 -0.0523917 1.761713 0.06188744 -0.01114511 1.782324 -0.01324254 -0.04859888 1.294451 -0.02098709 0.01493066 1.318438 -0.03269129 -0.05098497 1.301003 -0.04888755 0.1581942 1.315032 -0.04374057 0.1174489 1.29508 -0.05052524 0.1664752 1.315924 0.182105 0.02927279 1.270527 0.1872256 0.03318834 1.277819 0.1925922 0.02236789 1.290472 -0.1575439 -0.1669485 1.801492 -0.1016187 -0.1501177 1.75611 -0.09205049 -0.1373691 1.723246 0.0668323 0.1704283 1.042002 0.06861281 0.1489188 1.099798 0.1136785 0.1305752 1.086652 0.02668672 0.1395636 1.402234 0.0222615 0.1398549 1.402304 -0.02780139 0.07439279 1.413375 -0.03521972 0.06180906 1.447949 -0.02225959 0.003456175 1.727648 -0.01570081 -0.03476864 1.713294 -0.09957259 -0.06116455 1.785814 -0.2223176 -0.08100283 1.820735 -0.2229777 -0.1584087 1.793158 -0.2005838 -0.1038426 1.882911 0.01926749 -0.01662534 1.208033 -0.142139 -0.13104 1.520879 -0.08579391 -0.04715132 1.849496 0.04992461 -0.0100857 1.798941 0.05355888 -0.005055487 1.772278 -0.1502739 0.03386074 1.252052 -0.1079099 0.009619891 1.317231 -0.1033123 -0.00978136 1.370535 -0.1521241 0.04382324 1.245189 -0.1543819 0.04408365 1.245556 -0.03269177 -0.2048943 1.723866 -0.09693515 -0.1740743 1.634852 -0.01324218 -0.2025082 1.717312 0.03352886 -0.1265127 1.759779 0.07646989 -0.1391624 1.794533 0.01402837 -0.1433587 1.806063 -0.01619851 0.1063343 1.325617 0.01240843 0.1175734 1.294738 0.01099681 0.1036029 1.333121 -0.2662278 0.2083444 0.7529733 -0.2360854 0.163405 0.9345196 -0.2203872 0.2373147 0.7525238 -0.06269264 -0.04966008 1.873916 -0.06736457 -0.04115688 1.8673 -0.057002 -0.203064 1.718837 -0.1114389 -0.162959 1.608449 -0.2336354 0.2315473 0.2524386 -0.2340027 0.2285067 0.0462327 -0.02830457 0.007723689 1.734669 -0.02936536 0.003146946 1.728498 -0.03544014 0.007163286 1.735389 0.03237742 0.1035325 1.450267 0.0315966 0.1068263 1.450579 -0.00242567 -0.1392353 1.805325 0.02189874 -0.1333624 1.796628 0.01688873 -0.1342341 1.781138 -0.08333605 0.1074245 1.322622 -0.0739085 0.1110484 1.312665 -0.04322844 0.1035683 1.333216 0.2048224 -0.3157423 1.87211 0.2330378 -0.2923489 1.826835 0.1934654 -0.2564967 1.871639 -0.2196142 -0.06722158 1.149809 -0.2079181 -0.03831714 1.167684 -0.07363808 0.1171289 1.437174 -0.07173442 0.08611315 1.43638 -0.06726717 0.09932959 1.45041 -0.06352788 0.08905446 1.373093 -0.09568452 0.08066672 1.396137 -0.09957253 0.0927447 1.362952 -0.03709304 -0.4957693 1.882455 -0.07344943 -0.5154424 1.844182 0.04992902 -0.2743471 1.961489 0.03763502 -0.2421705 1.945804 0.01355087 0.1550327 1.307099 0.01919531 0.1166551 1.297261 -0.1934245 0.08277428 0.9750503 -0.1761595 0.0724644 0.960065 -0.2251182 0.009225964 0.946101 0.06882601 0.1320865 1.371815 0.06816482 0.1345357 1.372699 -0.08823037 0.1419562 1.375265 0.06174111 -0.2122246 0.976972 0.02747035 -0.2378034 0.9930908 0.08791977 -0.2118981 0.9988442 -0.1226208 0.02277159 1.136428 -0.1232265 -0.01084333 1.193891 -0.1159783 -0.2527511 1.851096 -0.04563015 -0.1980465 1.705052 0.004561722 0.07522529 1.411088 0.05664199 0.1171538 1.425315 0.05998307 0.1153849 1.422148 0.0649181 0.1211965 1.410602 -0.1582467 -0.226924 1.114589 -0.1717046 -0.1385535 0.9795708 -0.2151107 -0.2083329 0.05810475 -0.2329097 -0.1781684 0.02837324 -0.1818488 -0.2227229 0.0332061 -0.0633471 0.09049201 1.369143 -0.09717565 0.07610189 1.40868 -0.04968976 0.07880222 1.40126 0.1953817 -0.1909027 1.797534 0.1421321 -0.2107783 1.875697 -0.223944 0.09726071 1.319613 -0.2181841 0.1175825 1.311162 -0.09717571 0.1415958 1.345689 -0.1041976 0.09740966 1.350137 -0.06953144 0.1152761 1.301049 -0.05407524 -0.04765486 1.291854 -0.1464844 -0.007267594 1.181215 0.06897419 -0.5319631 1.645353 0.02692157 -0.2654826 0.886187 0.05672103 -0.3183593 1.048308 -0.07239294 0.1536284 1.333171 -0.06791228 0.1519284 1.321977 0.1070029 -0.3178586 1.100067 -0.2805516 0.07581651 0.9491006 -0.3095765 0.01694494 0.9200965 -0.2995335 -0.01916241 0.918906 0.05712676 -0.02050888 1.822969 -0.06009829 -0.01484131 1.82493 -0.06620341 -0.01591408 1.824494 -0.07487255 -0.01719737 1.82436 0.1966561 0.03703916 1.104331 0.2124022 0.01335918 1.077708 0.1999219 0.0585342 1.010669 0.02310049 -0.01375973 1.82564 0.01623511 -0.01345723 1.825383 -0.07763028 -0.0491029 1.863862 0.05090022 -0.1446812 1.976397 0.01320654 -0.2189098 1.958218 0.04939752 -0.2195216 1.947558 -0.09857159 -0.2473363 0.01718932 -0.1804944 -0.1739668 0.003122568 -0.05612635 -0.2310864 0.003203868 -0.04523175 -0.1415596 1.98546 -0.03842258 -0.1040499 1.978789 -0.1002228 -0.1330287 1.971053 0.2492616 -0.05173528 0.9137034 0.1170456 0.01609426 0.939943 0.1252612 -0.0491687 0.9157384 0.181717 -0.1825295 0.8660886 0.0814886 -0.1219409 0.8897739 -0.01848006 -0.01215678 1.825856 -0.1361111 -0.4830334 1.853868 -0.08413779 -0.4583344 1.911028 -0.1334436 -0.4397541 1.90273 -0.01563036 -0.1583181 0.8762947 0.01221895 -0.2591852 0.8381368 -0.0519917 0.07979851 1.398523 0.06188464 0.1315378 0.9800883 -0.1084628 0.1301906 0.9798303 -0.02691197 0.1035643 0.9720657 -0.01545202 -0.4614274 1.920115 0.2949936 -0.002494752 0.8941609 0.2997351 -0.001517236 0.8733031 0.2953623 0.04049682 0.8893678 -0.201187 -0.1846429 0.9131959 -0.2248271 -0.184686 0.9965124 -0.2381126 -0.1346499 0.9468465 -0.1603847 -0.2243701 1.112378 -0.1567756 -0.1743183 1.003472 0.03389447 0.002946853 1.402382 -0.03612214 -0.1514502 0.8874157 -0.0762664 -0.139196 0.8946881 -0.07350647 -0.1460607 0.8812052 0.07803624 -0.1707419 0.9662511 -0.2695917 -0.07980394 0.9039213 -0.2654843 0.05390083 0.9520549 0.02262681 -0.06732392 1.345894 0.05083739 0.1242991 1.421638 -0.04478597 0.149494 1.378143 -0.06229311 0.1543946 1.352928 -0.05360549 0.1486148 1.377823 -0.05443972 0.06264024 1.121688 -0.08336526 0.04852175 1.127325 -0.1078459 0.04792743 1.114678 -0.1416549 0.03454118 0.9461116 -0.1130309 -0.1980435 0.9581496 0.1695026 -0.2703232 1.096965 0.1156224 -0.2313253 0.8969851 0.1596825 -0.2263931 0.9810143 0.006236672 -0.09208011 1.870756 0.01414954 -0.09115004 1.868201 0.04159307 -0.02431309 1.410461 -0.009159803 -0.00860697 1.435836 0.05982488 -0.01321792 1.797801 -0.1305253 0.0491932 1.238794 -0.1407251 0.04009813 1.243975 -0.1440989 0.04592818 1.241956 0.00425738 -0.2279739 0.9719675 -0.2209071 -0.2197489 0.7997519 -0.1795847 -0.2475138 0.7967751 -0.06897491 0.1463445 1.376997 -0.07791751 0.1446858 1.376393 0.2152691 -0.09986484 0.003140449 0.2581328 0.01513016 0.005185604 0.1886072 -0.1613869 0.9215835 0.216084 -0.07927542 0.9386283 0.210985 -0.1248663 0.9461996 -0.04009139 -0.04296219 1.278961 -0.01167851 -0.04051339 1.272233 -0.2280668 -0.3477448 1.873659 -0.2114219 -0.289305 1.896688 -0.2312632 0.09376198 0.9664549 0.006735384 0.1601171 1.311884 0.005549848 0.1182704 1.292823 -0.04423451 -0.1164936 1.732252 -0.1293026 -0.1454415 0.9719947 -0.1575079 -0.1544502 0.9921944 -0.1287547 -0.1811589 0.9799413 0.06957763 -0.05258321 1.762239 -0.1938511 -0.2768626 1.813163 -0.1925671 -0.3278426 1.82009 -0.2155762 -0.2906267 1.77794 0.1513131 -0.3078121 1.924848 0.1498108 -0.2640843 1.91361 -0.005198836 -0.1944801 1.695253 0.1558007 0.02411055 1.264822 -0.2078279 -0.2629645 1.101582 0.02662527 0.1258767 1.430879 -0.07592594 0.1501291 1.357398 -0.08411443 0.1482272 1.345023 -0.02850639 -0.3339878 1.916833 -0.02282315 -0.386906 1.89709 -0.08007824 -0.3424428 1.904983 0.05948835 0.0212695 1.281973 0.1510716 0.1639962 1.274796 0.1411353 -0.04494589 1.855439 0.1669787 -0.04781824 1.83416 -0.08098483 0.08803099 0.9661998 -0.2168433 0.02874201 1.276926 -0.2154147 -0.06004303 1.813668 0.06604045 0.08107739 1.395009 -0.1286211 0.005206167 1.020915 -0.09009355 -0.03313177 1.006254 0.2022629 -0.2356789 1.110658 0.1301856 -0.1312695 1.518437 0.1219673 -0.1393782 1.528246 -0.09570485 -0.5427121 1.711832 -0.1238551 -0.5229044 1.784003 -0.1676057 -0.5079006 1.722417 -0.1183784 -0.1155321 0.8918427 0.04525345 -0.01772797 1.823828 0.05174982 -0.01940262 1.823219 0.1671297 0.04197692 1.258093 0.1483078 0.05092585 1.251355 0.1710619 0.0873714 1.276505 0.1109616 -0.3880362 1.846534 0.1345775 -0.4033233 1.798932 0.08250099 -0.4475098 1.801501 0.1023997 -0.1614469 1.595719 0.2038219 0.03960174 0.9801484 0.1628737 0.1059123 1.003991 0.1964179 -0.2151251 0.801668 0.2237305 -0.1908419 0.8114933 0.06662136 -0.2030412 0.9498164 0.02979129 -0.2100701 0.9430853 0.006400287 -0.05673849 1.890608 0.02776432 -0.08122193 1.955183 0.09618049 -0.06568455 1.913874 0.1502141 0.03970974 1.252117 0.1564055 0.04659849 1.253355 -0.007801651 0.02069658 1.319716 0.186182 -0.06813627 1.828416 -0.011527 0.1507781 1.378607 -0.007423043 0.1506713 1.378569 -0.04570883 -0.1336359 1.769393 -0.05714029 -0.1280592 1.780737 -0.03668785 -0.1373865 1.801211 -0.0325796 -0.003659248 1.80128 -0.04478597 -0.004415035 1.801005 -0.1975272 0.1513218 1.27057 0.02029901 -0.09921437 1.684777 0.04412502 -0.1266981 1.691761 0.07240438 -0.1168696 1.733284 -0.007173359 0.0021981 1.362765 -0.01042836 0.01308757 1.382394 0.002674341 0.004493117 1.35686 0.04128116 0.09304136 0.968149 0.08743691 0.06124216 0.9564419 0.2245867 0.06962275 0.9581241 -0.03027004 -0.04674249 1.883798 -0.02685588 -0.09273821 1.872563 -0.1802964 0.08833551 1.259035 -0.1861313 0.05375695 1.256028 -0.198449 0.08034706 1.272209 0.1736164 0.1329241 1.271385 0.167137 0.1387134 1.26375 0.1093149 0.03571188 1.247627 0.1145384 0.03405034 1.251229 0.05876553 -0.01025456 1.767869 -0.2173429 -0.164055 1.77661 -0.223286 0.0233519 1.291076 -0.2182237 0.01227921 1.294826 -0.1296301 0.07024806 1.054845 -0.1119546 0.08012723 1.067718 -0.09287559 0.09233283 1.060642 0.02623218 0.02869254 1.265895 -0.1697323 -0.1208819 0.9951854 -0.1064078 -0.2623293 1.107411 -0.09348219 -0.2241201 0.9931069 -0.007183909 -0.2428613 0.8627527 -0.05583447 -0.2576594 0.8775576 -0.08661699 -0.2273001 0.8654428 -0.2006763 0.1347481 1.26722 -0.1949085 0.1022251 1.271556 -0.09834921 -0.02180474 1.794627 -0.09631592 -0.01658463 1.796002 0.02764338 0.1709303 1.24091 -0.008158445 0.1751787 1.251616 0.114161 -0.2627628 0.7844254 0.1841555 -0.3311839 1.761829 0.1521409 -0.3521967 1.821199 0.007826924 -0.06032407 1.326662 0.009393215 0.01087784 1.345232 -0.08132749 -0.09286046 1.412041 -0.0585432 -0.09214621 1.404184 -0.07201457 -0.2361975 1.444125 -0.1356329 -0.4488478 1.759034 -0.109019 -0.4699302 1.715107 -0.1458746 -0.4438626 1.682587 -0.05599808 0.04692459 1.038012 -0.1501203 -0.0220589 1.009396 -0.153272 -0.07236921 0.9909031 -0.1853368 -0.03922683 1.004752 -0.1315192 -0.1258193 0.9715831 -0.1002305 -0.156907 0.9601119 -0.009414255 -0.2779946 0.8193202 -0.01202827 -0.286493 0.8008624 -0.1777459 0.01007467 1.02964 -0.02253407 -0.1196842 1.738383 -0.03956675 -0.1242002 1.74824 -0.03384464 -0.1387806 1.749089 0.02212983 0.06383055 1.442393 0.02772015 0.1277191 1.462249 -0.2041492 -0.05532515 1.836302 -0.2147858 0.1245983 1.309896 0.09102803 0.08224916 1.164825 0.05564647 0.0757057 1.18258 0.09777158 0.06227809 1.191017 0.002255022 0.150296 1.378435 0.1101641 -0.1173673 0.9751123 0.07107627 -0.1572093 0.960328 0.02846032 0.1768719 1.057882 0.2568153 0.03499788 0.9400004 0.005281925 -0.5533341 1.703306 -0.04523462 -0.550064 1.754545 -0.03146207 -0.552972 1.68529 -0.007966339 0.158109 1.305309 -0.008552491 0.1190424 1.290702 -0.01431024 -0.2177175 0.7621234 0.1929879 -0.1585211 1.790433 0.1930681 0.1014201 1.318103 0.1942548 -0.08317291 1.80138 0.02712917 -0.1138955 0.9768584 0.1540853 -0.06779128 0.9938072 -0.1041976 -0.03362089 1.827093 -0.09978377 -0.01499557 1.77592 0.203167 -0.01003235 0.9445423 0.2214775 6.48934e-5 0.9814857 -0.02616989 0.001505374 1.361071 -0.04207921 0.01745414 1.370272 -0.01837676 0.004373729 1.365758 -0.06817001 0.1057438 1.446615 -0.1026021 -0.1077821 1.964715 -0.1266921 0.07256424 1.174116 -0.163424 0.08244562 1.138467 -0.1724821 0.05774384 1.179099 -0.01039272 -0.1875743 0.9495581 -0.06188035 0.02644145 1.339541 -0.09191721 0.04337412 1.293018 -0.04709255 0.03634202 1.312339 -0.001730859 0.1094197 1.460935 -0.006160378 0.07295954 1.454086 -8.40658e-4 0.09978759 1.46298 -0.08275181 -0.01693999 1.390217 -0.1467176 0.07133764 1.243139 -0.129082 -0.2017063 0.9981239 -0.09542977 -0.2101687 0.977461 -0.05929309 0.001589477 1.730353 -0.00148046 0.04480308 1.611624 -0.1718379 -0.009184062 1.033069 0.1212568 0.01809799 1.115679 0.1039385 0.01186597 1.14455 0.09890329 0.04368579 1.100689 -0.147579 -0.1246768 1.491433 -0.1508698 -0.1142234 1.475113 -0.1409442 -0.1174862 1.47359 0.2106406 -0.2313468 1.829053 -0.001730799 -0.04453736 1.88381 -0.1026104 -0.1429827 1.80503 -0.06188029 -0.1274675 1.762402 0.02260869 0.04604828 1.310263 0.06575936 0.1376358 1.373754 0.06053936 0.1401391 1.374738 -2.34583e-5 -0.1351388 1.745944 0.007613122 -0.1179028 1.742545 -0.008043348 -0.1331082 1.742594 0.1363864 0.05476069 1.249199 0.1443675 0.06039178 1.253222 -0.01250076 -0.2117302 0.941606 -0.02846133 0.1187852 1.29141 -0.03691148 0.1504365 1.304896 -0.05968087 -0.06401711 1.336809 -0.009202361 -0.008209884 1.709567 -0.01510298 0.004303038 1.727887 -0.02141505 0.01422405 1.742252 -0.04807883 -0.01293379 1.823722 -0.04144477 -0.0224567 1.846975 0.1272057 -0.04482448 1.001274 -0.04182416 -0.06605416 1.8874 -0.03631031 -0.05270546 1.884517 -0.0532782 -0.09999686 1.686927 -0.04942965 -0.1217809 1.678251 -7.26162e-4 -0.1199526 1.673228 0.07037013 0.05002921 1.035757 0.0812062 0.07559937 1.04611 0.1523958 0.1468616 1.255628 0.1425092 0.1534481 1.25247 0.1464834 7.73129e-4 1.019632 0.1177011 0.04071158 1.245692 0.1197569 0.0368058 1.24898 0.1123732 0.03966718 1.24508 -0.01515847 -0.09059995 1.397261 0.00433731 -0.08451175 1.391831 -0.1151206 0.04686617 1.236759 0.01276892 -0.02899795 1.859582 -0.04354518 -0.4833287 1.661057 -0.01318645 -0.2870451 1.114068 0.05090415 -0.1569338 1.81428 0.02692461 -0.1779897 1.833407 0.06268513 -0.1655433 1.798495 0.01843994 0.1025658 1.057305 0.0221827 0.07271003 1.043764 -0.01642584 0.1022143 1.055791 0.06197685 0.1307206 1.398982 -0.1257683 -0.3572449 1.952954 -0.1434571 -0.3098592 1.94831 -0.1890786 -0.3347851 1.917353 -0.07221662 -0.06256586 1.860669 0.06915831 0.0107302 1.315372 -0.1408093 0.1232252 0.9832528 0.01003563 -0.1436322 1.82675 -0.03030335 -0.154594 1.839776 0.004401564 -0.1614702 1.842061 0.05654406 -0.03708523 1.849017 -0.1452315 -0.0196042 0.9382972 -0.1510971 -0.2341649 1.802598 -0.03853082 0.07532018 1.044792 -0.06140947 0.09906834 1.055254 -0.08080792 0.05090475 1.23344 0.001234412 0.05103099 1.231178 -0.1349136 0.05837005 1.040409 -0.08144503 0.06095302 1.039406 -0.1273869 0.02913564 1.028549 -0.163466 0.02116358 1.02652 -0.02650779 0.1837394 1.047106 -0.004222154 0.1665665 1.095795 -0.07433098 -0.02329319 1.407659 -0.02104622 -0.03063106 1.427819 -0.006228744 -0.06796771 1.530401 -0.07866972 0.1355223 1.4008 -0.08646214 0.1329948 1.399807 -0.08815395 0.1223232 1.418926 -0.07062166 0.1585128 0.9790924 -0.1016715 0.05952262 1.081716 -0.1356331 0.03842902 1.100698 -0.1402975 0.03980839 1.071345 -0.2541011 -0.01457703 0.9773293 -0.23693 -0.04846316 0.9325307 0.0649181 -0.03271263 1.833464 0.05974113 -0.3792057 1.886147 -0.09231376 0.1023061 1.336684 -0.0980786 -0.08590686 1.951939 -0.02484351 0.0678119 1.061799 -0.01142358 0.07450956 1.093663 -0.05919927 0.07073014 1.085417 -0.1455242 0.04861569 1.24176 -0.1556316 0.05933147 1.245802 0.03868669 0.02665525 0.9428805 0.1708919 0.02695286 0.944046 0.02586007 -0.4148052 1.478374 0.04585129 -0.4522625 1.601539 -0.002011775 -0.4533203 1.572647 0.1118126 0.05976861 1.046979 0.03932547 0.1528638 1.31473 0.1421661 0.1671192 1.274386 0.1621859 -0.0351212 1.043181 0.1515392 -0.003069162 1.064434 0.140441 0.00285989 1.044601 0.08010071 0.003758013 1.169766 -0.01663696 0.01749581 1.167028 -2.93252e-4 0.06070876 1.1274 -0.05403882 -0.4706134 1.798456 0.006507098 -0.4837641 1.771317 -0.05547797 -0.4843199 1.754586 0.1629788 0.03004479 1.25961 0.1466746 0.03000903 1.257671 0.0497803 -0.3921236 1.434852 0.1802418 -0.3619629 1.719972 0.1593481 -0.3997351 1.702721 0.1608724 -0.3831712 1.772731 0.1921851 -0.1784614 0.9771788 -0.0916056 0.02070814 1.354584 0.1144819 0.04713159 1.241657 0.03706115 0.1486245 1.314969 0.03741335 0.1129168 1.307532 0.03170233 0.1143397 1.303623 -0.05604207 -0.01452589 1.824994 -0.03614431 -0.01274257 1.825643 0.09612512 -0.08139115 1.936859 0.07187741 -0.1008701 1.961784 0.01868152 -0.04720151 1.879372 0.04893589 -0.2163 0.9537235 -0.2840561 0.1863585 0.04577869 -0.2612948 0.210781 0.04750907 -0.2314118 0.2120263 0.02060246 0.06958645 -0.4720472 1.748353 0.01488089 -0.4272278 1.863811 -0.0430597 -0.4492757 1.839016 -0.04902619 -0.4165357 1.872851 -0.1766671 -0.2079986 0.01564967 -0.2361084 -0.1379457 0.007923781 -0.01109117 -0.4232447 1.489981 -0.06281703 0.1141324 1.304192 0.1058904 -0.1970185 0.8718425 0.05839067 -0.2238649 0.8647358 -0.02743941 -0.02791339 1.420368 0.1913387 -0.0696426 0.9156742 0.1913583 -0.1168451 0.9106318 0.129213 0.06165593 1.24731 0.01888281 -0.09333729 1.87421 -0.05175083 -0.0925861 1.872146 0.1709236 0.1320282 1.268394 0.1655998 0.1177179 1.267567 -0.05134874 -0.4547577 1.590099 -0.050206 -0.4171356 1.481845 -0.07639926 -0.009006083 1.799331 0.2500175 -0.1251659 0.8758993 -0.08758544 0.07480114 1.412253 -0.08215981 0.1114346 1.433723 0.1546831 -0.205085 0.9134386 0.191698 -0.4337906 1.809058 0.1974232 -0.3949111 1.843371 0.1439192 -0.4422994 1.867846 -0.2575981 -0.200349 1.128541 -0.2324267 -0.2366933 1.113066 0.27869 0.06250661 0.01729667 0.2352958 0.134597 0.003396272 -0.005762219 0.1417187 1.402985 -0.0623126 0.1390596 1.402189 -0.0540111 0.1397458 1.402283 -0.09745901 0.1268243 1.397561 -0.05938321 -0.3816567 1.389793 -0.07832592 -0.2164678 0.9543203 -0.0508579 -0.2231532 0.95029 -0.1666089 0.1570684 1.250501 0.006934404 0.01275283 1.331775 0.01777255 0.02786809 1.335939 0.006564259 0.03778213 1.31756 -0.01714003 0.03956758 1.311778 -0.07689046 0.2305368 0.5681598 -0.05588543 0.2305184 0.6006577 -0.08209055 -0.005864143 1.76093 -0.07853013 -0.3896091 1.426666 -0.1964805 -0.04429262 1.82637 -0.08557945 -0.4478654 1.594172 -0.07726186 -0.3980154 1.448475 0.00330621 -0.003689348 1.801269 0.009914159 -0.003880321 1.801108 -0.001773893 -0.1528671 1.781881 -0.01631546 -0.1432946 1.798781 0.003424048 -0.1471018 1.780551 -0.008552491 -0.03486663 1.713564 0.1810741 -0.2859686 1.788413 0.1619824 0.05547016 1.162088 -0.1957839 0.142041 1.26273 0.1160542 0.1468197 1.034279 0.07795929 0.1551319 1.003672 0.005549848 -0.03563857 1.715685 -0.06029552 -0.2663366 1.88379 -0.09386831 -0.2075075 0.9529297 -0.117959 -0.2558955 1.109256 0.0270428 -0.2186171 1.761569 0.1568952 -0.01152002 1.025143 0.1624226 -0.04844617 1.008433 0.1266216 -0.4338548 1.745943 -0.0910719 -0.1665178 1.801764 -0.1046312 -0.1981384 1.884573 -0.05475854 -0.1783116 1.833571 -0.01415145 -0.2267047 0.9495826 -0.01948428 -0.3800187 1.370692 -0.2464458 0.00228393 1.060842 -0.2755042 -0.03889846 1.153342 -0.2302353 0.03394061 1.094626 -0.02037447 -0.2270707 1.419292 -0.04603195 -0.1131932 1.740182 0.18565 0.121571 1.306327 0.1803545 0.1156097 1.292977 0.1249728 -0.4370314 1.684045 0.01924431 -0.2231724 0.9499028 -0.1439788 -0.0596764 1.897411 -0.05441915 -0.08400499 1.958609 0.2833844 -0.00615108 0.9105331 0.2752909 0.06469339 0.9291238 0.0145235 0.01826959 1.366735 0.1240984 0.04329615 1.245929 0.13844 0.02975797 1.259309 0.1189652 0.04541105 1.243862 0.1216874 0.04238533 1.245642 0.0902782 -0.4572811 1.667829 0.06117993 -0.4696903 1.65954 0.09291785 -0.4625464 1.713744 0.05503773 -0.2490753 1.479726 -0.2026862 0.1722952 0.9478591 -0.2335258 0.1486045 0.9543794 -0.1375253 0.03362625 1.251552 -0.1438313 0.03486746 1.249998 -0.2574872 -0.06710511 1.028594 -0.2553055 -0.0306527 1.044439 -0.1738042 -0.4158846 1.682711 -0.1530125 -0.4310653 1.666512 -0.05327838 -0.1818794 1.843371 -0.1005954 -0.1664846 1.801074 0.0407902 -0.2253475 1.932617 -0.09773218 -0.1344838 1.7526 -0.1191303 -0.4414997 1.623515 -0.04132485 0.1412352 1.403586 0.15193 0.09177327 1.260086 0.1617575 0.09608823 1.268833 -0.01219373 -0.2252886 0.9470167 -0.07810848 -0.2475845 1.474138 -0.1226128 -0.2366631 0.8851994 0.08435672 -0.4435281 1.62056 0.08098948 -0.4252522 1.927095 0.07184851 -0.3603865 1.961587 0.00932908 -0.3741098 1.970535 0.08063185 -0.2512871 1.086217 0.01017677 -0.2087998 0.8578072 -0.1890314 0.140183 0.9732269 -0.2373914 0.1194984 0.9649832 1.96872e-4 -0.1142713 1.726146 -0.1318058 0.1337575 1.095445 -0.1325925 0.09523814 1.144275 -0.1921682 -0.1874399 1.128782 -0.2106186 -0.1537559 1.14317 0.1220989 -0.2323744 1.114971 -0.04564285 0.01168978 1.022568 0.03314101 -0.064291 1.794406 -0.06594425 -0.1271941 1.694754 -0.03547567 -0.122582 1.681662 0.06779521 -0.02977788 1.819619 0.1186809 -0.4282884 1.645517 0.02419114 0.1407276 1.12711 -0.02818512 0.01531833 1.321664 -0.03428465 0.01516813 1.327127 0.1499806 -0.2041736 1.124119 -0.007677197 0.05166453 1.294166 -0.03911536 -0.1463668 1.767892 -0.2209666 -0.3249648 1.719542 -0.2209661 -0.1178235 1.155019 -0.2050904 -0.3715076 1.699683 -0.04977846 -0.0510891 1.880076 0.2325847 -0.1194545 0.8876929 -0.2115486 0.03447306 1.269489 -0.2140464 0.1170191 1.300706 -0.2084249 0.1063207 1.289623 -0.2405164 0.01119929 1.212647 -0.2685158 -0.01949977 1.199405 -0.258067 -0.2212822 1.788603 -0.01883214 -0.01595824 1.834859 -0.02216851 -0.01713556 1.837496 -0.05437177 0.005353629 1.754436 -0.07829797 -0.00332868 1.756767 -0.08178025 -0.005366325 1.778573 0.1661631 -0.1830716 1.13585 0.1740571 -0.3750463 1.706981 0.1413944 -0.4194791 1.685547 -0.1011722 0.1586169 1.236988 -0.09732913 0.05217546 1.234682 0.06388908 0.1110756 1.429542 0.002886772 0.05474257 1.584316 0.04361093 0.1453588 1.376638 0.05970048 0.1405386 1.374884 0.05710351 0.1415555 1.375254 0.07760846 0.0850085 1.060466 -0.221273 -0.234615 1.857474 -0.184966 -0.1952801 1.846123 -0.2355661 -0.1940733 1.786767 -0.132528 0.1547744 1.038583 -0.1640644 0.1294754 1.00662 -0.1780745 0.1221358 1.036754 -0.01155847 -0.002749443 1.801459 -0.01582056 -0.00309503 1.80148 0.1828114 -0.1475995 1.145413 -0.01734817 -0.01215267 1.825857 0.1904833 -0.3266491 1.717607 -0.1661696 0.03084641 1.257412 -0.176388 0.02957659 1.258082 0.03391683 -0.4295656 1.938584 -0.04004091 -0.4089781 1.954673 0.1930291 -0.09734541 1.154479 -0.09804064 -0.0293312 1.819775 -0.09737652 -0.4676955 1.768288 -0.04873007 -0.3465743 1.976837 0.04383504 -0.02983844 1.849621 0.1866456 0.1817714 0.003107428 -0.2181046 0.1869883 0.003618478 0.1983482 0.2032706 0.01330244 -0.0431441 0.1565783 1.309514 0.1034496 0.1699528 1.252974 -0.04011237 0.161266 1.317453 -0.1952037 0.15547 1.280483 -0.2011976 0.1496723 1.282752 0.01408499 0.0982114 1.464886 -0.0787422 0.0129528 0.9378932 -0.09076595 -0.04122006 0.9181759 0.09051126 -0.1940883 1.872665 0.08559006 -0.2127715 1.93463 0.1538536 -0.4063363 1.724488 0.03805094 -0.1494992 1.822665 0.1864066 -0.09586882 1.844828 -0.201585 0.09489756 1.000604 -0.1799849 0.04977911 1.252099 -0.1730339 0.0682826 1.254718 -0.1774145 0.04439795 1.250861 0.1635217 -0.02445292 1.084612 0.01108574 0.1612798 1.328509 0.02463692 0.1571962 1.317801 -0.008784532 0.1038039 1.463277 0.1543623 -0.358886 1.812663 0.1126697 -0.3892903 1.841585 0.1366896 -0.4053792 1.790588 0.121311 -0.3389589 1.864934 0.05705434 -0.3783603 1.887434 -0.06255966 0.1474137 1.377386 0.07065129 -0.3397145 1.897488 0.225637 -0.03814238 1.020407 0.2258028 -0.0609622 0.9701052 -0.02859532 -0.346333 1.914596 -0.01663607 -0.3801828 1.900145 0.04044938 -0.3440521 1.907268 0.01250982 -0.2240826 1.776585 -0.08716815 -0.4701465 1.655891 -0.1182037 -0.4620088 1.677979 -0.3084549 0.14744 0.04799628 -0.3152599 0.1312726 0.7527212 -0.2903646 0.1816806 0.7519652 -0.1358847 -0.1034603 0.9809677 0.1529475 0.1605377 1.262517 -0.07472908 -0.3291897 1.909392 -0.08804935 -0.3785566 1.886946 -0.2742573 -0.1196773 0.8837212 0.2143062 0.009345889 1.203369 0.1897904 0.02333521 1.22425 0.04222315 -0.4679403 1.90483 0.1767004 0.009779214 1.288648 0.1683331 0.01848572 1.272982 0.06827074 0.1559307 0.9781389 -0.07107114 0.1782953 0.9699205 -0.09420162 0.1262935 1.404394 -0.09788751 0.1245308 1.396939 0.1301358 -0.1919186 0.003507494 -0.07874226 -0.09377962 0.98418 0.1691176 -0.1797974 1.139553 0.1315199 -0.2228423 1.111825 -0.1780475 -0.3606003 1.823138 -0.1643175 -0.4039921 1.79707 -0.1345568 -0.3902181 1.849508 0.2730919 -0.04755258 0.90415 0.08707028 0.0517565 1.071788 0.0318396 0.06696623 1.069319 -0.1950403 -0.3841902 1.750062 -0.1826916 -0.4029502 1.75179 -0.1832852 -0.4079008 1.725682 -0.1988291 -0.4806165 1.750783 -0.2080705 -0.4710338 1.675196 0.01371443 0.1777586 1.018549 -0.07179933 0.02823078 1.266098 -0.03636682 0.03340274 1.251557 0.1757296 0.136605 1.275013 0.1763676 0.1607267 0.957858 0.1623872 0.1796542 0.9400373 0.08248722 0.1907927 0.9515513 -0.2771915 -0.2366726 1.747799 -0.2864269 -0.2804795 1.745447 -0.05052524 0.01251143 1.738766 -0.05135732 -0.2334571 1.436428 -0.1582347 -0.08683013 0.9923043 0.00467199 -0.07792001 1.557745 -0.01819843 -0.08216255 1.569401 -0.0229212 -0.1368793 1.742287 0.04278874 0.01605683 1.75604 -0.2062003 0.03437978 1.264096 -0.2075091 0.03261852 1.21682 -0.1964611 -0.1713099 1.790822 -0.05303835 -0.106433 1.706522 -0.07218152 0.02455556 1.368288 -0.05568236 0.005494534 1.404691 -0.04742479 0.1403475 1.402483 0.1505841 -0.4025343 1.760348 -0.1191549 -0.2282514 1.920328 0.02391487 -0.004113852 1.799241 0.04243081 -0.2190418 1.922317 -0.2102067 -0.3423221 1.765756 -0.06484586 -0.2652574 1.523893 -0.1048982 -0.1178179 1.73589 -0.02310931 -0.2276358 1.950083 0.08831632 -0.1042073 1.439571 0.1800686 -0.3422565 1.765577 0.1313658 0.07932072 1.144941 0.1618695 0.07343316 1.11494 0.2226938 -0.4137527 1.691711 0.230036 -0.193074 1.124136 -0.1000899 0.008482515 1.321719 -0.05527436 0.1567834 1.317521 -0.08162039 0.02191507 1.284464 0.1299849 -0.2061917 1.893067 -0.04232645 0.1248128 1.468699 -0.2234215 0.05068957 0.9742414 -0.05121564 0.1053128 1.07042 -0.01630699 0.108802 1.066136 -9.12538e-4 -0.3242399 1.035539 -0.02027189 -0.2718169 0.8910602 -0.2401771 0.03636473 0.9942528 0.1397169 -0.3959088 1.909151 0.1930692 -0.3437593 1.880236 0.1494405 -0.3462101 1.922455 -0.06137531 0.001369118 1.743492 0.1219022 -0.2290548 0.8478007 0.05534005 0.04940426 1.125418 0.07997053 0.1298478 0.980891 -0.05673903 0.1154022 1.300703 -0.1161134 0.06052196 0.9572876 -0.09465348 0.06687879 0.9695921 -0.08759534 -0.2229566 1.935411 -0.106274 -0.2127486 1.940854 0.1244884 0.05579084 1.245171 -0.100026 -0.3163529 1.966312 0.009304404 -0.4806504 1.650647 0.2274648 -0.03530603 1.05106 0.2506644 -0.04488086 1.17997 -0.07509744 -0.1582657 1.820851 -0.048958 -0.1654927 1.837796 -0.007576465 0.006235063 1.412555 -0.1244992 -0.3357312 1.885472 -0.1689223 -0.3233577 1.851476 0.1610863 -0.07933908 0.997437 0.1183454 0.0328291 1.253755 0.153572 -0.109183 0.9866684 0.1354188 -0.1484161 0.9754756 -0.2066226 -0.2906292 1.800897 0.1753086 0.03773504 1.263693 0.1817929 -0.2860026 1.787119 0.1567028 -0.3157964 1.830701 -0.1837983 -0.4076542 1.697741 -0.1639386 -0.427892 1.746078 0.07646989 -0.142714 1.735765 -0.2774279 0.1329302 0.9276154 0.09329092 -0.3231117 1.889076 0.09972828 0.04677528 1.238797 0.1044255 -0.1846831 0.9865167 0.1323655 -0.1673579 1.006525 0.1733478 0.1129654 0.9722844 0.1820382 0.1328237 0.9697972 0.1713774 0.1154091 1.277213 0.2364016 -0.01603215 1.196115 0.1665711 0.1537122 1.283315 -0.2211003 0.04268372 1.113554 0.2041669 0.22194 0.03313302 0.2515401 0.1902499 0.04734283 0.2309331 0.1837525 0.01687508 -0.06248563 -0.08223623 0.9032472 -0.09518009 -0.1395066 1.782385 0.07179051 -0.2679555 0.7488037 0.05287218 -0.2796249 0.7718002 0.03443443 -0.276317 0.7525365 -0.2059152 -0.04700076 0.916886 -0.2440038 -0.4200614 1.774167 -0.267706 -0.3502035 1.793191 -0.2643783 -0.3870928 1.750707 -0.09570109 -0.3171792 1.901245 -0.1479767 -0.3300415 1.871097 -0.06770032 -0.1122136 1.742967 -0.0390399 -0.1417676 1.824868 -0.2357349 -0.4417421 1.692729 0.2147234 -0.4275464 1.74249 0.1699905 -0.477166 1.766159 -0.1282569 0.03426152 1.249741 0.1759749 0.02124458 1.271935 0.002644658 0.004213213 1.723144 0.0513035 -0.004660964 1.747526 -0.02127945 0.1615008 1.310052 -0.01570087 0.1191404 1.290433 0.03248661 -0.001101374 1.740501 0.03161549 -0.03955078 1.726434 0.02549874 0.01094371 1.740958 0.09499806 -0.5310348 1.700003 0.09411489 -0.5290824 1.754528 0.03345656 -0.5484468 1.748941 0.1159537 -0.5127466 1.651879 -0.154619 -0.365184 1.848314 -0.1465937 -0.4086759 1.819445 -0.06410139 -0.006494641 1.80018 -0.2184565 0.07785642 1.017521 -0.06126308 0.1554831 1.320125 -0.1817892 -0.005758047 1.088323 -0.1686857 0.02819842 1.039558 0.09153282 -0.4792785 1.8694 -0.0565415 -0.03187674 1.860017 0.129033 -0.2457017 0.7518776 0.07399165 0.1349973 1.363818 -0.1819817 -0.3950391 1.775676 0.1427575 -0.289839 1.845569 -0.1636896 0.1689897 1.267225 -0.1734513 0.1661819 1.274776 -0.1965296 -0.0959562 1.038121 -0.1941555 -0.06616795 1.005035 -0.0016523 0.02043426 1.734557 -0.0203371 -0.2778233 0.0454939 0.002750098 -0.260131 0.01852267 0.035838 -0.2745849 0.04630041 0.03508263 0.06462907 1.110853 0.03754138 -0.3052082 1.908492 -0.01556897 -0.3142473 1.915994 -0.08333426 0.134027 1.400182 -0.03642857 0.2304078 0.4918094 -0.1601466 -0.1996825 1.905393 -0.1339216 -0.1347956 1.951778 -0.133221 -0.3079408 1.881777 0.01013058 0.006903171 1.756156 0.02458506 0.003312826 1.740728 -6.85086e-5 0.006913006 1.733441 -0.002599954 -0.01235479 1.825784 -0.1828369 -0.2754814 1.828357 -0.05970013 -0.1758129 0.9522067 -0.02429562 -0.01225554 1.82582 -0.08574074 -0.5397844 1.76847 -0.05426073 -0.4887089 1.70635 0.0524097 0.1077342 1.321771 -0.03373527 -0.07154959 1.540242 0.1218088 0.03047156 1.084322 0.1213772 0.02785629 1.059059 -0.00215131 0.1407533 1.28054 -8.80451e-4 0.1578007 1.306156 0.0733276 0.04957145 1.115473 0.0490626 0.06654697 1.09221 -0.303393 0.07909697 0.9281302 -0.03957223 0.008952319 1.341329 -0.01949495 -0.002467811 1.801422 0.1720516 0.1484811 1.284231 0.01009154 -0.04301518 1.279106 0.01919531 -0.03725397 1.720122 0.01161819 -0.005024075 1.719587 -0.04904901 0.04827779 1.282389 -0.05811536 0.02802735 1.267421 -0.261344 -0.4008644 1.701585 -0.2740953 -0.1613689 1.140506 -0.07199698 0.2304322 0.5240317 -0.03544014 0.1610571 1.312505 -0.298942 0.1258973 0.02036571 -0.2651693 0.1419834 0.004194378 -0.3041772 0.04353153 0.0123015 -0.06242942 0.1474313 1.377393 0.01837062 -0.01164054 1.415092 0.1127279 -0.4960592 1.82563 -0.2744792 -0.02035093 0.002794563 0.07752555 -0.02710533 1.809191 0.1546002 -0.2510602 1.801692 -0.1629499 -0.215753 1.886893 0.1503902 -0.07545143 1.892596 0.1732417 -0.1944566 0.02048879 0.02029919 -0.1826619 1.845521 -0.1086576 -0.1470329 1.747631 0.09870803 -0.2802138 1.873454 0.04482555 0.06669396 1.434528 -0.2125045 -0.1292842 0.9030042 -0.2481207 -0.09572327 0.9458091 -0.2500827 -0.1214807 1.008522 0.01623052 -0.004573225 1.800947 -0.1539324 0.02496206 1.096739 -0.1453581 0.05645245 1.050616 0.005234122 0.1072657 1.460291 0.006236672 0.06182885 1.447895 -0.04058647 -0.0130226 1.825541 -0.0801239 -0.2876495 1.897485 -0.07315325 -0.1180116 1.709933 0.004121661 0.1371201 1.412789 0.1378381 0.02965712 1.040475 0.1469898 0.01230299 1.034787 -0.1446914 -0.2779758 1.861846 0.1872752 0.04145115 1.144337 0.1424305 0.02850162 1.260792 0.003984332 0.0750904 1.411459 -0.08296996 -0.1180165 1.733828 0.126815 -0.05323344 1.001226 0.142351 -0.02896457 1.02023 0.1205801 0.009228885 1.031924 -0.2541196 -0.0597521 0.9591939 0.2169376 -0.12921 1.003195 0.05758124 -0.4231973 1.852544 0.01291394 -0.4625132 1.818264 -0.09125751 -0.01065349 1.778081 -0.1065781 -0.06190246 1.787844 -0.09277504 -0.07998275 1.837519 -0.0431745 -0.2189208 1.958249 0.02597844 -0.121846 1.76267 -0.00887227 -0.2828658 1.902237 0.06672275 0.09816247 1.348069 0.00610429 0.003380179 1.730423 -0.1832025 0.0241056 1.26598 0.2570517 -0.07674008 1.190378 0.2476634 -0.2484056 1.76723 -0.08525663 -0.2532857 1.491306 -0.0725488 -0.00199896 1.751311 0.1605539 0.1089851 1.037531 0.005234122 -0.04662287 1.883146 -0.08856409 0.1440165 1.344489 -0.09469652 0.1402893 1.357885 -0.1765456 -0.04108637 1.017137 -0.1948396 -0.05594921 1.035741 -0.1796675 -0.07823157 1.008167 -0.2110626 -0.04407876 1.160051 -0.1944673 -0.03598535 1.053729 -0.08863389 -0.2953171 1.898826 0.09993916 -0.1864361 0.9634131 0.08601146 -0.1962141 0.9589996 0.01414948 0.06275904 1.445339 0.2342419 -0.3607945 1.796455 0.09337359 -0.2596628 1.856701 -0.2073422 0.01159065 1.284993 0.1038633 -0.255501 0.04655075 0.1008484 -0.2370293 0.01852291 0.1525442 -0.2304853 0.04831731 0.04500305 -0.2647911 1.878609 0.01997542 -0.3211187 1.977882 -0.1665035 0.0493561 1.248992 -0.08427417 -0.5369288 1.645998 -0.1291559 -0.5250135 1.662281 0.0727784 -0.07390105 1.820809 -0.0130589 -0.09926801 0.8970481 0.0452454 -0.2309176 0.004727363 -0.07374686 0.1367453 1.401262 -0.1508354 -0.2422783 1.817868 -0.09188103 0.1232658 1.412903 0.06423974 0.06696563 0.9697248 0.09613627 0.0360319 0.9556031 0.1097239 -0.1228789 1.477473 0.04396778 0.1511014 1.355038 0.05802035 0.1459645 1.354061 0.0431056 0.1524555 1.329477 0.05320006 -0.04676318 1.863201 -0.1049681 -0.01713591 1.209347 0.007517397 -0.01284176 1.825606 -0.1901227 0.02174663 1.267923 0.09741359 0.03652918 1.245 0.1569276 -0.24222 0.7919196 -0.03552889 0.1627327 1.10263 0.05195623 0.1454877 1.331425 0.07727324 -0.2641518 1.113612 -0.07146239 0.1000153 1.067842 0.2057995 0.2295553 0.05263507 -0.038033 -0.06032401 1.326662 -0.1164988 -0.1019723 1.43662 -0.1951486 0.06730663 1.122035 -0.03201413 -0.2185692 1.926041 -0.1719672 -0.2169286 0.9102683 -0.1481565 0.05226576 1.242675 -0.1574943 -0.2937229 1.862168 -0.0860995 0.1714101 1.027185 -0.1722866 -5.11076e-4 1.126282 -0.0930534 -0.3755208 1.886586 -0.1058146 -0.4297626 1.834889 0.2269305 -0.2111408 1.773142 -0.09969568 -0.1950766 1.878317 0.04049867 -0.2625087 1.515718 0.1135092 -0.132632 1.525108 -0.06354182 -0.05328321 1.881114 -0.02135288 -0.181198 1.842903 -0.2689287 -0.1191875 0.02048933 -0.2904202 -0.02525413 0.00851202 -0.08368539 -0.1245762 1.772499 -0.03257966 0.1502498 1.378418 -0.03656393 0.1578341 1.351347 -0.0312851 -0.1500745 1.781214 -0.03803294 -0.2142331 1.749524 0.06197685 -0.02318841 1.821844 0.1693268 0.1460583 1.267359 -0.09564161 0.1376873 1.37382 -0.200347 -0.1820307 1.856458 -0.1379142 0.01283538 0.9473383 -0.05360549 -0.005294203 1.800685 0.1160067 0.03489744 1.250571 0.03199315 -0.2835692 1.121879 -0.1966766 0.04227584 1.257652 -0.2132716 0.01904743 1.279525 -0.01362639 0.001110434 1.182332 -0.02190023 0.08269423 1.108056 0.1813827 -0.1745547 1.798986 0.185625 0.01175737 1.291687 0.003619253 -0.05158019 1.302639 1.30008e-5 -0.003498613 1.801338 -0.007181286 -0.002919673 1.801447 -0.01616907 0.1508092 1.378617 -0.08893519 -0.1316929 1.705485 -0.2804677 -0.1599429 0.8175504 0.06696963 0.1040081 1.332008 0.00676614 0.1050136 1.329245 -0.1945635 -0.09142839 1.029513 -0.2877305 -0.1198141 0.04621487 -0.3027782 -0.04192316 0.0203492 0.1339267 0.01672536 1.091454 0.1454911 -0.003243207 1.125863 0.1583219 -0.01536405 1.074386 0.01701283 0.0918771 1.094098 -0.01573687 0.1073867 1.075339 0.1878784 0.1173091 1.312618 -0.06218105 -0.2123989 1.744485 0.1155304 -0.01867455 0.9358245 0.1115875 -0.0614416 0.9203653 -0.0150001 -0.06507521 1.339718 -0.07773214 -0.2740043 0.7516902 -0.1224554 -0.2689741 0.7739923 -0.1394113 -0.25568 0.7493862 -0.006160378 -0.08091855 1.876959 0.2340289 0.09723329 0.9569082 0.01891779 0.1052083 1.071659 -0.2224274 -0.1454065 0.9184142 0.01868152 0.1067 1.456513 0.01240843 -0.03633558 1.7176 -0.08659625 0.1721704 1.051895 -0.3289195 0.04399639 0.04693323 0.03630089 0.1469065 1.377164 0.007826924 -0.2142331 1.749524 0.00792247 -0.1465318 1.770934 0.008585333 -0.1392309 1.757889 -0.1757514 -0.2620581 1.915294 0.1639791 -0.1843189 1.82063 0.1698463 -0.06742531 1.051183 -0.1623563 8.46501e-4 1.143349 -0.1479915 0.02904164 1.099805 -0.1328052 0.0118348 1.146921 -0.1351295 0.1861152 0.9525323 -0.1919882 0.03067564 1.258795 -0.1804619 0.03970116 1.252202 0.01851558 0.03612762 1.312928 0.03822261 9.59828e-4 1.752005 -0.04232645 -0.02907657 1.891568 -0.01850742 0.05763471 1.207435 0.07082635 0.1755259 0.9688866 -0.06111514 -0.009319901 1.408715 -0.03587853 -0.01313143 1.419188 0.1627871 -0.09820443 1.026613 -0.1247283 -0.4018849 1.934566 -0.1855135 -0.4104024 1.885739 -0.0363003 -0.5399525 1.629436 -0.04137909 0.01360017 1.398405 -0.02315837 0.1419186 1.403092 0.04603248 0.007324159 1.171416 0.08282703 0.02788913 1.13594 0.01779806 -0.07568329 1.825706 0.06162762 0.08709239 1.077835 -0.1739881 0.03176438 1.255919 0.24975 -0.1374559 1.143706 0.2275459 -0.091865 1.028796 0.1036475 -0.2416326 1.925631 0.02966034 -0.1500107 0.8803861 0.01230216 -0.2703569 1.538783 0.03874707 0.1012786 1.068116 0.05188453 -0.04017686 1.855204 0.1147636 0.01890635 1.120909 -0.227046 -0.1717125 0.8692527 0.02843385 -0.01480072 1.824894 -0.2705017 0.177244 0.02045977 -0.08649909 0.06791836 1.191467 -0.03473758 0.1349951 1.136259 0.04787105 0.1096021 1.316639 0.009877741 -0.2237694 1.930794 -0.02201402 -0.1521758 1.786086 -0.198839 0.01171743 1.285823 -0.1460599 0.01282477 1.133535 0.09844291 0.07045704 1.058568 -0.1560352 0.0486955 1.245378 0.04837381 -0.08330971 1.84666 0.07466822 -0.2528158 0.8909834 -0.008231937 0.04952239 1.273519 -0.03547447 0.04244095 1.266503 -0.2051443 0.1279087 1.277815 -0.2060483 0.1387744 1.276987 -0.09408253 -0.02420467 1.821479 -0.09186112 -0.0336945 1.839841 -0.2174276 -0.06403392 1.140124 0.007680475 -0.5385743 1.625554 -0.02239096 -0.01221507 1.825835 0.07240438 -0.1650068 1.797013 -0.2029073 -0.1154935 0.8984674 0.2783639 0.09121602 0.9095413 0.2575386 0.1035357 0.9379853 0.03741335 -0.04099231 1.730394 -0.01879179 0.141885 1.403045 0.04022872 -0.1100692 1.976401 0.02769923 -0.07111972 1.813168 -0.3082273 0.09195554 0.9097166 -0.3274001 0.03143984 0.886001 -0.02247887 0.007580757 1.757559 0.2498247 -0.2845448 1.779319 -0.008390188 -0.01393431 1.421393 0.08045321 -0.3151539 1.962725 0.01548165 -0.2600175 1.874691 0.07261961 -0.1022218 1.441665 -0.1468622 -0.1521943 1.57449 0.06779521 0.1241312 1.396757 -0.3219391 0.0251199 0.9040815 -0.3289796 -0.02767151 0.8707455 -0.3183735 -0.03949356 0.890641 -0.2054457 -0.3652503 1.750498 0.05064791 0.009487807 1.384359 0.05647575 0.0263018 1.352091 -0.2014269 0.01741927 1.274685 -0.07788085 0.07045507 1.424194 -0.3220136 -0.03225076 0.04765403 -0.306611 -0.0793417 0.04663234 -0.1589113 -0.4967001 1.800643 0.1148029 0.05194938 1.241745 0.1694932 0.1524074 1.276857 -0.03052031 0.04436713 0.9493271 -0.2768496 0.1135933 0.9446175 -0.1527293 -0.02600592 1.010871 -0.09834927 0.1321042 1.371766 0.2349438 -0.1546264 0.04809391 -0.2120184 -0.3545063 1.702273 0.03691619 -0.01609569 1.824423 -0.1399348 -0.1581224 1.574193 -0.007966279 0.004199981 1.72817 -0.2012289 -0.1857608 1.834788 0.05245465 0.1453565 1.36814 -0.2253876 -0.4058119 1.837385 -0.03334146 -0.07809627 1.558229 -0.1959692 0.01911485 1.272217 0.2986242 0.02435588 0.04806941 0.1111525 -0.2438251 1.826317 0.1264826 -3.22906e-4 1.15509 0.09991204 -0.0896486 0.905624 0.01293814 0.002669215 1.732376 -0.2032681 0.1399806 1.26898 0.002227485 -0.2032169 1.900724 -0.1989408 -0.4589357 1.812185 -0.01614648 0.04016554 1.301834 0.03177893 -0.1933194 0.9584115 -0.1029844 0.1175956 1.411629 0.1923354 -0.3158159 1.719312 0.1840618 -0.1442322 1.146972 0.1488397 -0.07743537 1.007501 0.1647977 -0.06638079 1.031539 -0.1120831 0.1725019 1.259566 -0.06574535 0.1532167 1.313761 0.1418697 0.00881946 1.086827 -0.05540591 -0.04520654 1.875884 -0.1506779 -0.2477329 0.04801529 0.1436592 0.08233517 1.254815 -0.2009637 0.1265043 1.270326 -0.1327092 -0.1156479 1.462281 -0.2023646 0.05093759 1.157989 0.1061819 -0.2838446 1.94552 0.1017133 5.39214e-4 1.167508 -0.03631031 0.1012036 1.461655 0.1516059 -0.007126748 1.110146 -0.01510298 0.09897303 1.464006 -0.1511624 -0.1401383 1.52755 0.1072768 0.01091915 0.9496211 0.1700159 0.01072233 1.28746 0.003510415 -0.1360113 1.987591 -0.01499998 -0.2189844 1.762579 0.1926322 -0.07785433 1.160563 0.1915978 -0.1107257 1.154611 -0.1339502 -0.4189094 1.79412 -0.1361916 -0.4371916 1.688989 -0.02100366 -0.07582819 1.893272 0.0261957 -0.2725545 1.890818 -0.3197773 -0.08017307 0.8435632 -0.01410549 -0.4556039 1.586472 -0.3083057 -0.08998876 0.8738612 -0.09863185 2.71266e-4 1.178108 0.1140164 -0.4327998 1.714257 -0.04965603 -0.4042109 1.872085 0.1367977 -4.48998e-4 1.139405 0.04615259 -0.4080746 1.855907 0.1070203 -0.4193243 1.790307 0.1459304 0.0396378 1.251856 0.05188453 0.1137325 1.432343 0.133534 -0.5045073 1.766845 -0.09602618 -0.07285201 1.817926 0.06565469 -0.147129 1.787568 0.01568949 -0.3983612 1.881299 -0.1615706 -0.4216858 1.748521 -0.0764079 0.1527713 1.10659 0.1109825 -0.1194213 0.9789684 8.77586e-4 0.01936089 1.324386 -0.1133069 -0.4043908 1.846606 -0.02148044 -0.04656833 1.889698 -0.01510298 -0.05362832 1.887052 0.1430852 0.03661632 1.252488 0.1002908 -0.4032607 1.837144 -0.04038631 -0.1851057 1.653012 -0.01366722 -0.2297501 1.426329 -0.1531968 0.03673732 1.24989 0.06554943 0.01683306 1.35112 0.03513681 -0.547146 1.672917 0.09093123 -0.1931186 1.871133 -0.0016523 0.1743756 1.311707 0.0264607 0.08630138 0.9757229 -0.3229373 0.09624582 0.0476951 -0.06834769 -0.1427534 1.815138 0.1355915 -0.4250605 1.709975 -0.1273744 0.0335977 0.956539 -0.2144727 -0.3306324 1.761951 -0.01510298 -0.05493599 1.886868 -0.2044621 0.1460822 1.282906 -8.4064e-4 -0.05412143 1.885842 0.1301144 -0.1996256 1.905237 -0.2018213 -0.03196752 1.179504 0.1718303 -0.05073779 0.915166 -0.00914061 -0.1539928 1.784992 -0.03395837 0.1985313 0.9503048 0.1587853 -0.1787574 0.8956898 0.04688304 -0.1384829 0.8926661 0.1115875 -0.01938515 1.001708 0.1154153 -0.06187701 0.9857373 0.1075976 -0.09321475 0.9748169 0.09613621 -0.116859 0.96647 0.08043861 -0.11447 0.9035865 0.07772773 -0.1381864 0.958878 0.04605996 -0.1587333 0.9483662 0.006574988 -0.1517254 0.8904042 0.005237638 -0.1715137 0.9437147 -0.02065169 -0.1743987 0.9458173 -0.05665624 -0.1666957 0.9455693 -0.05665636 0.08586865 0.9765038 -0.01529294 0.09196048 0.9790989 -0.09465342 -0.1477057 0.9524809 -0.1111345 -0.1137801 0.9017229 -0.1273744 -0.1144247 0.9655342 -0.1281365 -0.09143626 0.9094911 -0.141091 -0.08466523 0.9770326 -0.1451814 -0.03878688 0.9918407 -0.137483 -0.008427977 1.002777 -0.1281364 0.01060938 1.012582 -0.1147635 0.02876019 1.020334 -0.09444582 0.04742848 1.023403 0.2948142 -0.05813097 0.8582118 -0.06776708 0.06178468 1.028833 0.03621929 0.1379404 1.401607 -0.03544378 0.07114946 1.032037 -0.009554386 0.07200789 1.035502 0.02645027 0.06626635 1.03036 0.05738461 0.05122905 1.027672 0.08043849 0.03364306 1.018487 0.09949558 0.00804454 1.009179 0.1896449 0.2375989 0.7522765 0.2365301 0.2079619 0.7533686 0.2605591 0.1811105 0.7518485 0.2847431 0.1321034 0.7527775 0.2964735 0.08444231 0.7593392 0.2941082 -0.02741289 0.7535164 -0.1677685 -0.500797 1.658317 0.279885 -0.07556754 0.7521492 0.2544851 -0.1292648 0.7534772 0.2161487 -0.1794754 0.7515695 0.1746468 -0.2166406 0.7523409 -0.2089111 -0.2137047 0.7515174 -0.07828748 0.1485973 1.331135 -0.3136448 -0.06676673 0.7526202 -0.2944915 -0.1109437 0.7537131 -0.2586421 -0.1665557 0.7546198 -0.3262022 -0.01400935 0.7496936 -0.0850777 -0.2713248 0.0485987 -0.3304759 0.03598445 0.7586652 -0.08041268 -0.179114 1.639989 -0.3258982 0.08838558 0.7531009 0.09282577 0.01051443 1.022952 0.205065 -0.1877794 0.04591977 0.02549874 0.1648629 1.318101 -0.2639224 -0.1573753 0.0560317 -0.1990573 0.150029 1.2882 0.1242979 0.03151977 1.257217 0.1004204 0.01747566 1.022867 0.03000676 -0.175668 0.9522945 + + + + + + + + + + -4.28424e-7 -0.9396926 -0.3420205 -0.1222932 0.7447382 -0.6560558 -0.7059069 0.04919797 -0.706594 0.680213 -0.7298294 -0.06826013 -0.01779186 0.9488933 0.315095 0.7809725 -0.2778069 -0.5593793 4.76587e-5 0.3417558 -0.9397887 -3.19992e-5 -0.9397019 -0.3419948 -0.2062281 0.3225364 0.9238183 0.4956749 -0.6331814 -0.5944644 -0.01494187 0.9998881 -5.82249e-4 0.2075113 -0.3449585 0.9153922 0.06773531 -0.9795774 -0.1893145 0.02932953 0.9995644 0.003255844 0.5783271 -0.6260199 0.5231029 -0.6815118 0.3428913 0.6465038 0.6946672 -0.7191721 -0.0151326 0.3781085 -0.608956 -0.697285 -0.541141 -0.7372586 0.404495 -0.964258 0.2641617 -0.02061772 -0.008103609 0.9065701 0.4219774 -0.09452736 0.9954903 0.007974922 0.8745753 0.483545 0.0360859 -0.2930653 0.7077878 0.642767 0.002389848 -0.3314365 0.9434745 0.2932836 -0.1937639 -0.9361839 -0.08611714 0.9962086 0.01234251 -0.2160345 0.8546456 -0.4721335 -0.3520805 0.7442994 -0.5675013 0.9984461 -0.0556696 -0.002519428 -0.003272771 0.8287488 0.5596112 -0.1097773 0.9939453 0.004674792 0.4726081 0.6067153 -0.6391699 -0.1308435 0.9857306 0.1059016 -0.2476383 0.3230714 -0.9134003 -0.3714594 0.8568114 0.35762 7.64091e-4 0.9429764 0.3328587 -0.1264737 0.9919698 6.83983e-4 0.7749566 0.1583607 -0.611853 -0.01185554 -0.3418896 0.9396654 -0.09344643 0.9956149 -0.004331171 -1.65748e-6 -0.9396924 -0.3420206 0.04024106 -0.7870765 -0.6155414 0.2252624 -0.8943088 -0.3866115 1.69947e-5 -0.9396959 -0.3420113 -0.06943637 0.9975419 -0.009415328 -0.309989 -0.8935657 -0.3247265 -0.06408703 0.9978817 -0.01117765 -0.4595944 -0.3187879 0.8289434 0.5415104 -0.1731427 -0.8226714 -0.9299498 -0.03245586 0.3662515 0.2653481 -0.8562029 0.4432911 0.8118997 -0.5681006 0.1344648 0.09340876 0.3855898 -0.9179299 0.04166722 0.9991204 0.004728198 -2.38634e-7 0.9396929 0.3420194 0.3326238 0.6930907 -0.6395207 0.00341165 0.9396497 0.3421211 -0.1834586 0.3667348 0.9120574 -0.5560021 -0.6385226 0.532119 -0.4554169 0.8875624 0.06948763 0.2784382 -0.7411298 0.6108999 0.1734239 0.9494796 0.2615582 0.9237033 0.2974137 0.24149 0.03122502 0.8175867 -0.5749581 0 -0.9396926 -0.3420203 0.5120921 0.8477563 -0.1380986 0.4926928 0.3843271 0.7807345 -0.02363574 0.9997159 -0.003097712 0.9053776 0.2681925 -0.329187 0.8122979 -0.5235155 0.2571061 0.10325 -0.8868451 0.4503833 -0.6307802 0.2591224 -0.7314178 -0.2472649 -0.5411704 0.8037379 -0.003087937 0.9395223 0.3424737 0.9877465 -0.1463388 -0.05423772 -0.4595863 -0.3187776 0.8289519 0.09960734 0.01266354 -0.9949463 0 -0.9396926 -0.3420201 0.8882482 -0.1781181 0.4234254 -0.5952628 -0.09898102 -0.7974114 -0.2731378 0.9065724 -0.3217487 -0.8871031 -0.1394907 0.439989 0.0772745 0.9970098 1.69955e-4 -0.008767247 -0.3437244 0.9390297 -0.9997038 -0.0233879 -0.006730794 0.247137 0.9201439 0.3037412 -0.806541 -0.1604709 0.5689823 -0.001099586 0.3513529 -0.9362425 -0.866141 0.3302834 0.3751168 -0.9419037 -0.01746803 0.3354285 -0.1183744 0.940222 0.3193276 0.1013777 0.9948348 0.005129814 0.5770475 0.3121854 -0.7546898 -0.9574136 -0.1056362 -0.2687013 -0.8606554 0.1449097 0.4881327 0.6628978 0.2589921 -0.7024881 1.41002e-6 0.9396927 0.3420199 0.01645725 0.9394904 0.3421794 0.2671654 0.6865203 0.6762489 -0.2865126 0.0386815 -0.9572953 -0.6884248 -0.2942965 0.6629185 -0.9693472 -0.1918833 -0.1534494 -0.1391013 -0.6723539 0.7270428 0.6457249 0.2855561 -0.7081645 0.1433335 -0.3208155 0.9362334 0.0688467 0.9975078 0.01543921 0.1928443 0.9811721 -0.01059877 0.1856437 0.9825397 -0.01232838 -0.09177833 -0.9630655 -0.2531433 0.2994059 0.9536654 -0.02963775 -3.98473e-4 0.3491617 -0.9370623 -0.2087078 0.9779781 -6.26811e-5 -0.2038829 0.9789951 6.45007e-4 0.006150186 0.7068794 -0.7073075 0.8181724 -0.1869553 0.5437294 0.6363532 0.659214 0.400614 -0.01022553 -0.9418003 -0.3360176 5.17818e-4 0.9394243 0.342756 -0.1105549 0.6283215 -0.7700582 4.50583e-7 0.9396927 0.3420199 -0.07110261 0.09833991 -0.9926095 -0.2374601 -0.3384895 0.9105149 -0.009790301 -0.8718692 -0.4896408 -0.5110831 -0.3698885 -0.7758714 -0.6752857 -0.03582495 -0.7366858 -0.07332676 -0.2441287 -0.9669666 -0.3409661 -0.8960964 0.2841712 -1.3771e-4 0.9397383 0.3418947 -0.06613409 -0.5399157 0.839117 2.02691e-5 0.939685 0.3420411 -4.23741e-4 0.9395698 0.3423571 0.3947907 0.8474272 0.3549752 0.2218407 -0.8404929 -0.4943264 0.08478552 0.9664639 0.2424026 -1.07344e-5 -0.9396913 -0.3420239 0.6895102 -0.4228489 -0.5880261 -0.001160264 0.93564 0.3529542 -0.8178763 -0.2123841 0.5347628 -0.857499 0.1680994 -0.4862492 0.03092342 0.07774192 -0.9964939 0.1558753 0.7095726 0.6871751 0.09543079 0.5188743 0.8495073 -0.03568553 0.9188411 0.393011 -0.02663153 -0.8541164 -0.5193997 0.007132649 0.3390864 -0.9407283 -0.0112521 0.3956937 -0.9183136 -0.6471881 -0.698024 -0.3064474 -0.1066213 0.789417 -0.6045267 0.5653675 0.6406061 0.5195993 0.8121032 -0.1345592 0.5677871 -0.2899968 -0.8990465 -0.3280507 0.2259359 -0.9568713 -0.1826205 -0.00162518 -0.3710314 0.9286189 -0.7444043 0.2122209 0.6331071 -0.03797715 0.9059726 -0.4216293 0.6049965 -0.02234029 0.7959147 0.0368784 0.9858825 0.1633269 -0.009641289 -0.3542496 0.9351012 -0.6162512 -0.4787092 -0.6253574 0.5872957 0.7992473 -0.1276217 0.1900284 0.825076 0.5321081 0.1947877 0.9210278 0.3372915 0.1653843 0.4431856 0.8810417 0.9429013 0.1935298 -0.2710781 -0.7325544 -0.6226218 0.2751471 0.8820146 0.1866002 -0.4327016 0.8867185 -0.4550951 -0.08135545 -0.009303033 0.1010197 0.9948409 0.2781981 -0.6741421 0.6842063 -2.21149e-7 0.9396927 0.34202 0.8363454 0.2636741 -0.4806269 0.3373903 -0.2962439 0.8935365 0.9611554 0.2094424 -0.1797618 0.8470102 -0.1691974 -0.5039306 0.01685994 0.9305117 0.3658739 0.4337224 0.8487476 0.3025103 0.004954636 0.304465 -0.9525106 -6.53359e-5 -0.9396883 -0.3420317 -0.08120119 0.3381389 -0.9375865 2.56889e-5 -0.9396854 -0.34204 5.57693e-6 -0.9396896 -0.3420283 -0.9501059 -0.09746438 0.2963097 0.02476286 -0.9429286 -0.332073 0.6471915 -0.4422167 0.6209569 0.2933817 0.9313441 0.2156971 -0.01324212 -0.9399768 -0.3409811 -0.1954067 -0.5807055 -0.7903147 0.00434345 0.9382418 0.3459529 0.004567742 -0.9439278 -0.3301202 0 -0.9396926 -0.3420205 1.0634e-6 -0.9396912 -0.3420241 -0.5099925 0.811407 0.2855282 -0.8929886 -0.1647312 0.4188497 -9.26411e-4 0.9397449 0.3418751 -0.00796616 0.9998599 -0.01472914 -0.1217181 0.8071201 -0.5777038 0.5014176 0.03683978 0.8644207 -0.2282209 0.9734233 0.01903349 -4.60171e-6 -0.939694 -0.3420165 0.7993751 0.1578496 0.5797266 -0.9037814 0.4191735 -0.08644479 0.010782 -0.2835658 0.9588922 -0.93101 -0.0663219 0.3589173 1.78036e-5 -0.9396947 -0.3420146 -0.05485928 -0.8658974 0.4972044 0.06937628 0.4584033 0.8860324 1.58648e-4 0.9396935 0.3420177 0.3675422 0.2813017 -0.8864435 -0.394745 0.4787701 -0.784191 -6.84541e-4 -0.3396393 0.9405555 -0.3874043 0.8036805 0.4516808 -0.1996721 0.846691 0.4931992 -0.008314311 0.9363623 0.3509368 3.22201e-7 -0.9396902 -0.3420268 0.07499009 -0.3265364 0.9422051 0.7303248 0.4316599 0.5294294 -0.8066502 -0.5281518 -0.2652758 -0.5895195 -0.7161387 -0.373647 0 0.9396929 0.3420194 0.4270973 0.7631168 0.4850163 -0.9421298 0.3148814 0.1150698 0.8272434 -0.07541328 0.5567596 0.003307282 0.9368539 0.3497054 -0.0758931 0.9145716 0.3972392 0.002827525 -0.9386039 -0.3449853 0.1791148 -0.925157 -0.3346678 -0.8936198 0.2201629 -0.3911164 0.3411269 -0.8828359 -0.3228516 -0.01733613 0.9392977 0.3426649 1.29791e-7 0.9396926 0.3420202 -0.5047315 -0.1683037 0.8467112 7.08722e-4 0.2738469 -0.9617731 -0.1249637 0.8896953 -0.43912 -0.002355515 0.9395518 0.3423988 0.8874874 0.441446 0.1322556 0.03144669 -0.1263543 -0.9914866 -0.9461724 -0.1384074 0.2925767 0.2590116 -0.3518188 0.8995202 -0.164744 -0.360008 -0.9182885 -0.2173618 0.2090458 0.9534431 0.008213877 -0.3468121 0.9378987 0.01420623 -0.3435791 0.9390163 -0.6923952 0.3522203 -0.6297063 -0.005725502 0.404362 -0.9145811 -0.3646728 -0.6870555 0.6284652 0.002464473 -0.3532304 0.9355332 7.89935e-7 -0.9396916 -0.3420233 7.42736e-4 -0.2778577 0.960622 0.0687744 -0.7565183 0.6503462 0.9748231 0.01643174 0.2223733 -0.8511459 -0.4659511 -0.2417437 0.006355643 -0.3549435 0.9348662 1.60643e-6 -0.9396929 -0.3420194 0.8011347 0.5332859 0.2716421 0.649985 0.1210063 0.7502512 -0.1967608 -0.8894239 0.4125657 -0.31001 0.38624 -0.8687419 -0.1584115 -0.07432901 0.9845715 -0.00555706 -0.3385623 0.9409275 0.9774655 -0.08563536 0.1929454 0.5357217 0.6874951 0.4902579 -0.1051241 0.9599868 0.2595655 0.2895103 -0.8018426 -0.5227161 -0.008141815 -0.3406944 0.9401389 -0.5941445 -0.7427057 -0.3088373 0.6702319 -0.6734278 -0.3119041 0.2030405 0.7433561 0.6373354 0.3248107 -0.2875391 0.9010102 -0.3723782 0.2435446 -0.895556 0.3170977 0.9231435 0.2173826 -0.1201226 -0.3862209 -0.9145513 0.03753548 0.7936733 0.6071851 -0.5467231 -0.8274355 0.1282355 -1.19451e-5 -0.3421199 0.9396563 -1.68756e-6 -0.9396927 -0.34202 0.3205084 -0.10272 -0.9416596 0.8451652 -0.1782112 -0.5039211 -0.2443504 0.3246468 -0.9137272 -0.7739245 -0.0288549 0.63262 -0.004569888 -0.3310559 0.9436002 0.2841535 0.3907557 -0.8755379 0.9101852 -0.1189211 0.3967626 0.5301861 0.1918796 0.8258844 0 0.9396927 0.3420201 0.8583912 -0.04777818 -0.5107659 0.6587904 0.2084097 0.7228836 0.008240342 -0.3458243 0.9382632 0.01775538 0.9417985 0.3357086 0.4656972 0.2969402 -0.8336382 -0.1548442 -0.9281121 -0.3385724 -0.7851055 -0.5507678 -0.2833094 0.004697442 -0.3526881 0.9357292 -0.003031492 -0.357807 0.9337906 0.2450482 0.7624515 0.5988482 -0.4087231 0.9031137 0.1316474 0.1525141 0.3598043 -0.9204783 -0.8141445 -0.3847058 0.434937 0.3617043 0.8752366 0.3211402 0.06792473 0.5405815 0.8385452 -0.01247429 -0.3149567 0.9490241 1.21366e-5 -0.9396938 -0.3420171 0.9998853 0.0151503 -1.55167e-4 0.6892178 0.2420876 -0.6829146 -1.09687e-6 -0.9396926 -0.3420201 -0.02766466 -0.3237904 0.9457244 -0.001428365 -0.3584378 0.9335525 0.749989 -0.5950016 -0.2889456 0.3399773 -0.8446834 -0.4134313 -0.424515 -0.9017095 0.08189606 -0.005367875 -0.3405723 0.9402031 0.1037873 0.6702029 -0.7348852 0.4456494 0.3030634 -0.8423474 8.92187e-7 0.3420577 -0.9396789 -0.576297 0.6504328 -0.4947919 0.7922823 -0.5804557 0.1880425 0.7787038 0.5728564 -0.2558438 0.6348963 -0.7630613 0.1210125 0.163367 0.08521497 -0.9828782 -0.007048249 -0.3343958 0.9424064 0.001419425 0.9352028 0.3541096 0.3468212 -0.1451528 -0.9266313 -0.01334303 -0.3464446 0.9379756 0.06061059 -0.3461065 0.9362354 0.7387326 0.631999 0.234204 -0.007531285 -0.3487132 0.9371992 0.02758044 0.961227 0.2743755 0.08051568 0.9366538 0.3408766 0.4268072 0.9042276 -0.01442193 -8.21752e-6 -0.3420706 0.9396743 -0.5784807 0.6700947 -0.4651164 -0.6856432 -0.4487373 0.5731738 -0.4645311 0.7394483 -0.4872647 0.008437573 -0.3003269 0.953799 0.008856832 -0.3341286 0.9424859 0.01343953 -0.3027486 0.9529757 -0.2166913 -0.2468107 0.9445259 -0.6270397 0.1718668 -0.7597915 0.8147842 0.1891583 -0.5480383 -0.01288908 -0.914923 -0.4034228 0.8748512 0.1558801 -0.4586248 -0.8745973 -0.4558257 -0.1652344 0.4166657 0.2769865 -0.8658338 -0.5212693 0.851095 0.06257617 0.4963161 0.6366961 -0.5901597 0.86046 0.2751404 0.4288432 0.01120442 -0.3416965 0.9397436 0.5647399 0.7613841 0.3183755 -0.1220601 -0.4721425 -0.8730309 -0.7456625 -0.2162679 -0.6302505 0.1069008 0.2140818 -0.9709486 -0.007779121 0.920279 -0.3911853 0.009107112 -0.3379502 0.9411199 0.2920522 -0.942561 0.1621239 -0.8895813 0.2116201 -0.4047988 -0.8881492 0.1341729 -0.4395323 -0.3111454 -0.2267929 -0.922905 0.5929888 0.804759 -0.02696502 -0.01098048 -0.6086368 0.7933731 0.2932237 0.9314047 0.215651 -0.0457136 0.3471723 -0.9366865 -0.05779927 0.2938805 -0.954093 0.09478092 -0.9092864 0.4052342 -0.6239066 0.4266111 -0.6547851 0.4428511 0.224367 0.8680682 -0.929894 -0.03250467 0.3663885 -0.7345129 0.6374429 0.2327172 0.1408342 0.8044387 0.5770998 0.01532429 -0.2847525 0.9584786 0.02108651 0.3295683 -0.9438963 0.2863517 0.9008051 0.3264241 0.2017166 -0.3002339 0.9322929 -0.02770876 -0.9989519 0.0364353 -0.02245825 0.5069129 -0.8617048 0.9998955 -0.01434922 -0.001749694 0.9998431 -0.01558834 -0.008409202 -0.003787994 -0.3395483 0.940581 0.02825093 0.330691 -0.9433161 0.1231923 -0.6579038 0.7429577 -0.06782728 0.3280856 -0.9422098 -0.007936298 0.9398829 0.3414047 0.8549294 0.2003505 -0.4784928 0.2108613 0.6377307 -0.7408354 -0.6271123 -0.2675372 0.7315422 -0.2211145 0.2178036 0.9506155 -0.2253736 0.853994 0.4689361 0.02574211 0.2721081 -0.9619222 0.01652967 0.3036364 -0.9526447 -4.54292e-7 -0.9396928 -0.3420196 -0.03853183 0.3257748 -0.944662 0.004431307 -0.7097792 0.7044103 -0.8817286 0.01857024 0.4713914 0.03585183 0.9367398 0.3481859 -0.2316837 0.02140402 -0.9725556 0.5318809 0.5564185 0.6383582 6.06519e-7 0.9396926 0.3420203 -0.01241594 0.29267 -0.9561329 -0.01358401 0.3133317 -0.9495466 -0.06568032 0.9530329 0.2956593 0.680726 -0.6354281 0.3644766 -0.514269 -0.7211694 -0.4641573 -0.02906984 0.3058888 -0.9516234 -0.3402274 -0.8214958 -0.4575915 0.8198772 0.2829226 0.497751 -0.07077288 0.08683127 -0.993706 -1.58817e-6 -0.9396925 -0.3420205 0.2438943 0.9689642 0.04029858 -0.01240706 -0.3882907 0.9214534 -0.2984373 0.3102431 0.9025986 0.2598344 0.2898399 -0.9211291 -0.01794731 0.3140558 -0.9492349 -0.2052513 0.3367508 -0.918951 -1.8029e-6 -0.9396929 -0.3420195 0.02102977 0.310968 -0.9501878 -0.0544455 -0.8326299 0.5511472 -0.1039531 0.909641 0.4021777 0.02381122 0.3342036 -0.9422001 0.9601192 -0.02936714 -0.2780445 0.1513302 -0.267974 -0.9514669 0.1090927 -0.3510897 0.9299649 0.03766924 0.3612722 -0.9316992 0.2830501 -0.03471636 -0.9584766 0.03507548 0.3604393 -0.932123 0.2027164 -0.5660653 -0.799047 0.05085885 -0.7504964 -0.6589148 -0.1728535 -0.3339512 -0.9266058 0.7802725 0.2762139 0.5611423 0.1396225 0.7513153 0.6450044 0.04537659 0.3565129 -0.9331878 0.1132555 0.9331628 0.3411456 0.7196027 -0.2218 0.6580097 0.03527444 0.4164619 -0.9084686 0.3882895 0.8187354 0.4229699 -0.5164366 -0.1095601 0.8492879 -0.4103935 -0.1836403 0.8932264 -0.6840147 -0.2700469 -0.6776419 0.001789808 0.9404677 0.3398784 -0.139444 0.6288279 -0.7649384 0.01585644 0.4146508 -0.9098425 0.07534492 0.6356753 0.7682709 0.01890498 0.3683342 -0.9295012 -0.6991019 -0.1833437 -0.6911163 -0.7924345 -0.2949034 0.5339284 5.4213e-7 0.9396927 0.3420196 0.3801444 -0.7667129 -0.5173408 5.87292e-4 0.3781182 -0.9257572 -0.01628726 0.3899214 -0.9207041 -0.02289819 -0.5114443 -0.8590112 -0.2891654 -0.8246865 0.4860818 -0.03518849 0.3678846 -0.9292054 -0.02731645 0.3608909 -0.9322078 0.05819708 0.9495187 0.3082651 -3.17558e-7 -0.9396924 -0.3420205 -0.3273931 0.837099 0.4382683 0.4310616 0.6925512 -0.5784106 -0.001738071 0.02836781 0.999596 0.4761618 -0.8715899 -0.1166228 -0.03648656 0.3999535 -0.9158088 -0.01530843 0.3907222 -0.9203814 -0.8013432 0.2874764 -0.5246013 0.7646671 0.3819036 0.5190702 -0.20973 0.3260224 0.9218041 -0.157099 0.4036287 -0.9013344 -0.02935141 0.36925 -0.9288665 -1.63892e-6 -0.9396903 -0.3420264 -0.3470391 0.5254613 0.7768232 0.04532015 -0.9812808 0.1871743 -0.04971277 0.3545697 -0.9337071 -0.3345627 0.03956717 -0.9415425 0.007500469 0.3445777 -0.9387279 0.2109534 -0.9251471 -0.315597 0.302276 0.5413354 -0.7845925 6.2825e-5 0.9428204 0.3333013 0.4015089 0.480724 0.7795479 -0.8186842 -0.4804713 0.3144893 -0.07241034 -0.6590873 -0.7485724 0.07233673 0.9513185 -0.2996007 0.08432358 -0.7132058 -0.6958642 0.2762286 -0.9061123 -0.320403 -0.8494554 0.5173294 -0.1039025 0.8886543 -0.4191923 -0.1859334 -0.9003205 0.4213826 0.1089023 0.1888417 -0.4529598 -0.8713014 0.5851575 0.1708672 -0.7927139 -2.88152e-6 0.342059 -0.9396786 0.4312173 0.4579576 0.7773844 0.3158407 0.4969252 0.8082759 1.44221e-6 -0.939692 -0.3420218 0.2680994 -0.9047116 -0.3310886 -0.5637159 0.5678676 -0.5997923 -0.2322126 0.9614467 -0.1473011 0.02247911 0.7204381 -0.6931549 -0.3085399 -0.3589522 -0.8808838 0.1027057 -0.9310915 -0.3500288 -0.6307749 0.2591233 -0.731422 0.3853387 -0.4718632 -0.7930065 -3.69547e-4 0.9394817 0.342599 0.434614 0.09584224 -0.8955026 0.3427801 0.01790416 -0.9392451 0.03097748 0.41746 -0.9081672 0.6148662 -0.1844042 -0.766769 -0.08855324 -0.9405809 -0.3278201 -0.07741558 -0.9396198 -0.3333486 2.14119e-5 -0.3415244 0.9398729 0.560512 -0.6132602 0.5565413 -0.9395181 -0.0586223 0.3374451 0.795659 -0.5583358 -0.2349213 -0.2905032 0.8936685 -0.342001 0.6933481 -0.5315248 0.4865694 -0.841847 -0.4703192 -0.2647515 0.3965305 0.06208097 -0.9159201 -0.2155452 0.5886998 -0.7790846 -0.3762406 0.3976369 -0.836856 1.10567e-4 0.3416143 -0.9398403 -0.02377158 0.4127076 -0.9105533 -0.2687467 -0.9044119 -0.3313825 -0.4413339 0.6746814 -0.5916329 -0.8202461 0.5266481 0.2232449 -0.2059731 0.291038 0.9342762 0.8388361 0.04923206 -0.5421533 -0.6938683 0.2744457 -0.6657523 -0.2634026 -0.9057164 -0.3321099 -1.65717e-5 -0.9396855 -0.3420396 0.6219093 0.513373 0.5913348 0.9380457 0.250756 -0.2391479 -0.5036254 0.744538 0.4382061 -0.3330815 -0.8861385 -0.3222038 0.01507341 -0.2863559 0.9580047 -0.5916037 0.3678783 -0.7174054 1.12874e-5 -0.9396895 -0.3420284 -0.8271563 -0.1084916 -0.5514002 0.3615771 0.8773943 0.3153429 -0.6981139 0.3809425 -0.6062341 0.3884679 0.8891047 -0.2420445 -1.08181e-6 -0.9396906 -0.3420258 -0.2429535 -0.9134714 -0.3264104 3.06967e-6 -0.9396899 -0.3420276 0.1349675 -0.8601927 -0.4917848 -0.4499583 -0.8311793 -0.3266167 -0.2235575 -0.919941 -0.3220722 0.998341 -0.0207284 0.05371826 0.7353938 0.3676611 -0.5692287 -0.7344666 0.6298645 -0.2526449 -0.007918298 0.9346117 0.3555818 -0.09703266 -0.9348324 -0.3415744 0.2802737 0.6631278 0.6940519 -0.1895495 0.1392676 -0.9719442 -0.8660181 0.4974476 -0.0505833 -0.1313899 -0.391491 -0.9107533 -0.3929952 -0.2113779 -0.8949156 -1.22409e-5 -0.3420898 0.9396672 0.1874867 0.434547 0.8809186 -0.1238858 -0.9326786 -0.3387668 0.8935472 0.1521729 -0.4223939 -0.731344 0.6818324 -0.01551163 0.1021447 -0.9348928 -0.3399146 -0.0150178 0.9214189 0.3882805 0.6442432 -0.1244259 0.7546316 -0.4818273 0.8673143 0.1249334 0.01671999 -0.560577 -0.8279334 0.2530967 -0.9082598 -0.333176 0.2416005 -0.5405374 -0.8058837 0.3686372 -0.2021265 -0.9073321 -0.4195248 0.8987893 0.1271871 2.81334e-4 -0.001014769 -0.9999994 0.7575434 0.1786236 -0.6278708 0.859939 -0.5091955 -0.0349968 0.09446173 -0.9358443 -0.3395178 -0.4173306 0.7020694 0.577004 0.9067017 0.4004129 -0.13252 -0.03633898 -0.8475781 -0.5294249 -0.9718835 0.1403516 -0.1890606 -1.51879e-6 -0.9396909 -0.3420249 0.4487419 0.2207716 0.8659623 -0.689123 -0.6817465 -0.2456241 0.6891916 0.2376259 -0.6845062 -0.01610487 -0.7959782 -0.6051113 -0.9596878 0.1926171 -0.2046902 -0.5849289 -0.762506 -0.2764829 -0.5854634 -0.7621268 -0.2763974 -0.3356646 -0.3127049 -0.8885634 -0.1239233 0.7529301 -0.6463276 -0.429895 -0.8489459 -0.3073775 0.6804181 -0.07119089 -0.7293578 -0.3896554 -0.8646446 -0.3171093 0.4776849 0.3658862 0.7987143 0.1128209 -0.5285934 -0.8413443 -0.3806009 -0.8682314 -0.3183038 0.8904719 -0.1466292 0.4307663 -0.4073747 -0.7861774 -0.4647266 0.1700529 0.9256641 0.3379765 0.3564769 -0.8784263 -0.3182633 0.2202445 -0.4335885 0.8737812 0.3612219 -0.8766179 -0.3178992 0.1293154 0.1217828 -0.9840968 -0.3048229 0.361496 0.8811377 -0.7309381 -0.1871472 0.6562815 -0.4050583 0.7209936 0.5622242 -0.8900075 -0.3796465 -0.2524977 0.5543594 -0.7818982 -0.2851682 0.0176618 -0.3573858 0.9337899 3.20099e-7 0.9396924 0.3420208 0.004102349 0.9401457 0.3407477 1.09801e-5 0.9527128 0.303872 0.5544493 -0.781845 -0.2851392 0.2640197 0.7174828 0.6446022 0.6672069 -2.51028e-4 0.7448725 0.7282729 -0.6443689 -0.2332537 0.1648577 0.9857398 0.03374826 -1.5451e-6 -0.9396919 -0.3420224 0.3921428 0.3788008 0.8382923 0.8355576 0.3867117 0.3902533 -0.964541 -0.247779 -0.09091883 -0.9539884 -0.2823243 -0.1009909 -0.180122 0.2980583 -0.9373992 -0.4264612 -0.3016837 0.852712 0.06868827 -0.3724036 0.9255255 -0.892876 -0.4222838 -0.1563611 -0.7828995 0.1992019 -0.5893955 -0.8351334 -0.5177091 -0.1858208 -0.7661414 0.603719 0.2203422 -0.9783651 -0.1800752 -0.1018557 -0.7776331 -0.5898992 -0.2174988 -0.05600643 0.9361321 0.34716 -0.3379977 0.9405358 0.03391188 0.8271744 -0.5291075 -0.1892824 0.8324063 -0.5215591 -0.1872856 -0.120977 0.01712864 -0.9925075 0.02343761 0.9364302 0.3500702 1.07726e-4 -0.3417035 0.9398078 0.426585 0.801761 -0.4185742 0.6970615 -0.6729697 -0.2474209 -0.5633554 0.6624704 0.4937244 -0.4860696 0.7118974 -0.5068908 -0.5790971 0.812123 -0.0714339 0.02371025 -0.2313545 0.9725805 0.9102141 -0.3885926 -0.1431987 0.001455962 -0.3638541 0.9314549 -0.05603772 0.9229026 0.380934 0.9484559 -0.2986012 -0.1061542 0.09372115 -0.9348812 -0.3423649 0.05710911 -0.4792869 0.8757984 0.9798839 -0.1863408 -0.07144725 -0.9994434 0.0265398 0.02020651 0.4644328 0.8747225 -0.1384302 -0.06016373 -0.3415142 0.9379491 0.4088855 0.6650559 0.6249106 0.004355609 0.4265304 -0.9044628 -0.3289247 0.3312471 -0.884355 0.1267619 0.6568204 -0.7433159 -0.03252124 0.9261124 0.3758435 -0.1831628 0.8755525 -0.4470561 -0.6147539 0.741146 0.2697781 4.47331e-6 -0.9396908 -0.3420251 -0.002400696 0.2698785 -0.9628914 0.9751619 -0.2211196 0.01286095 -0.0994299 0.7599772 0.6422994 -0.04817068 -0.8831071 -0.4666919 0.2565119 -0.9457256 0.1995111 0.81962 -0.5685731 -0.07034033 0.2360183 0.5889401 0.7729456 0.9511299 -0.1393373 0.2755666 0.949099 0.1763731 -0.2609668 -0.5445371 0.6770232 -0.495095 -0.1015099 0.1766806 -0.9790198 3.94592e-5 -0.3419626 0.9397135 -0.9121357 -0.3888795 0.1295427 0.1983593 0.9727624 -0.1199455 -0.2115239 -0.1378586 -0.9676014 0.7093526 -0.5037279 0.4930285 0.5220361 -0.4310497 0.7359853 0.9280776 0.09504848 -0.3600524 -1.60937e-5 -0.3421625 0.9396408 -0.5290234 0.3660126 -0.7656168 -0.2156798 0.03375864 -0.9758805 0.3094331 0.692369 -0.6518255 0.04217594 0.8766177 -0.4793357 0.9965751 0.07649236 -0.03141534 0.1102461 -0.3570463 0.927558 -0.1923731 -0.9212954 -0.337946 4.85258e-6 -0.9396932 -0.3420185 0.4386589 0.8453449 0.3049104 -0.896603 0.4428328 0.001501262 0.01295411 -0.3457726 0.938229 0.4988023 0.3737595 -0.7819848 -0.232395 -0.3499193 0.907496 -0.3604796 -0.3876308 0.8484085 -0.173034 -0.4377946 0.882267 0.637814 0.7234781 0.2641453 0.2400634 -0.6113219 0.7540922 -0.05585116 -0.8850781 -0.4620793 0.01405 0.4208474 0.9070227 -0.8999726 0.05074399 0.4329832 0.2368844 -0.2228466 -0.9456349 0.0131402 0.9154006 0.4023297 0.004961073 -0.3411973 0.9399786 -0.7985203 0.5667102 0.2029901 -0.6732621 -0.5255205 0.5201408 5.13618e-7 -0.9396937 -0.3420171 0.4004181 -0.4128246 0.8180717 -0.2626216 -0.8951889 0.3600928 -0.01261389 0.9590647 -0.2829059 -0.805729 -0.5013073 0.3154233 -0.003839015 0.9212899 0.3888574 -0.03674554 -0.4047359 0.913695 -0.8342301 -0.5379812 0.120981 0.4014706 -0.3500888 0.846321 -0.6648257 -0.7468783 -0.01340359 0.1515811 0.9878405 -0.03455877 -0.828835 -0.5537459 -0.07998692 -0.00324136 -0.9396498 -0.3421224 0.5338761 -0.820897 0.2027422 -0.001253485 -0.9397888 -0.3417537 0.9607303 0.1938735 -0.1985203 0.1957527 0.7449971 0.6376991 -0.1929083 0.9484189 0.2515711 0.1289465 0.9913108 -0.02599489 -0.9764826 0.2017869 0.07591986 0.3305794 0.8832206 0.3326239 -0.4182119 0.3057859 -0.8553325 0.4226248 -0.2927901 0.8577076 0.3631092 -0.1399586 0.921175 -0.4764772 0.3332944 -0.8135627 0.496906 0.1814495 0.8486228 -0.8791306 -0.1109446 0.4634875 0.2517911 -0.3969138 0.8826441 -0.8725337 -0.4858037 0.05176508 -0.3729885 0.2163884 -0.9022504 0.05800223 -0.003865003 -0.998309 -0.6902532 0.2229109 -0.6883759 -0.2946831 0.898652 0.3249405 -0.3861745 0.6247461 -0.6786468 -0.3465489 0.7572667 0.5535801 0.2250844 -0.5368195 -0.8131185 0.864566 -0.4853358 0.1302867 -0.1183531 0.8470333 0.5181961 -0.2372389 0.5384461 0.808575 0.2326166 0.9340597 0.2709649 4.81227e-4 0.7124863 0.7016857 -0.4593991 0.743483 -0.4859893 -0.8185212 -0.4631689 0.3398495 -0.8393365 -0.4291345 0.3337031 -5.79452e-7 -0.9396926 -0.3420204 0.2922319 0.3943076 -0.8712761 -0.9247908 -0.3693053 0.09151792 -0.9315925 -0.3536478 0.08407509 0.8159715 0.2259685 -0.5320985 -1.16393e-6 -0.9396927 -0.3420202 -0.01932811 -0.9946727 -0.101256 0.5720686 0.646379 -0.5049076 0.5770444 0.08105212 0.812681 0.9364097 -0.3382948 0.09323847 0.8814364 -0.4449008 0.158534 -0.1131168 0.8028061 -0.5854118 0.8323175 -0.4367323 0.3413393 0.8379785 -0.4588073 0.2954455 0.4679635 0.826213 0.3136594 0.8490857 -0.4959669 -0.1818529 -0.8839777 0.4519245 -0.1197817 0.368184 -0.02728438 0.9293526 -0.8906628 0.3148147 -0.3280419 0.2672375 -0.9324771 -0.2430441 0.3652683 -0.8972269 0.2481189 0.8032412 0.07767015 -0.5905683 -0.8045518 0.3556915 -0.4755838 -0.1313176 0.9446408 -0.3006815 -0.2609471 -0.6324786 -0.7292994 -0.9155753 0.3593419 0.180542 -0.0562129 -0.9409383 -0.3338791 0.2079629 0.7859742 0.5822339 -0.8255677 0.3678239 -0.4279528 0.6697807 -0.3114861 0.67407 0.4755231 -0.7316315 0.4884597 -0.1521324 -0.9241706 -0.3503775 0.1262118 -0.6885054 0.7141644 -0.08952915 -0.8777828 0.4706187 -0.7580028 -0.5758246 -0.306362 -0.3499482 -0.7434955 -0.5698691 0.09426075 0.6925145 -0.7152193 -0.7532929 0.2703321 -0.5995585 -0.5401715 0.4618818 0.7034771 -0.3434982 -0.845991 0.407809 0.2066132 -0.7677389 -0.6065377 0.7005346 -0.3957499 0.5938294 0.4803716 -0.0680437 -0.8744217 -0.3484326 0.2050898 0.9146217 0.01491057 0.9474714 0.3194926 0.9667348 0.2002725 -0.1591054 -0.3723178 0.4946527 0.7853013 0.2059629 0.7833632 0.5864481 -0.3821023 -0.2950863 0.8757408 -0.5087283 -0.4068874 0.7587082 0.2751876 -0.03033387 -0.9609119 -0.6446586 -0.3346754 0.6873192 -0.6275506 -0.3682126 0.6860027 0.7018586 0.2117342 -0.6801199 -0.01872581 -0.9109002 -0.4122014 0.7725238 -0.1840704 -0.6077213 -0.8411191 -0.181558 0.5094658 -0.878779 -0.2251239 0.4207929 -0.007507503 0.9345923 0.3556417 -0.8993417 0.1744419 -0.4009419 -0.94469 0.309767 0.1077275 0.8109358 0.2103247 -0.5460281 0.0587694 -0.9219697 -0.3827767 0.8884873 -0.1876124 0.4187981 0.9023819 -0.2071891 0.3778617 1.53064e-7 0.9396927 0.3420201 -0.7413206 0.6711475 -0.002176702 0.7563948 -0.2871139 0.5877351 0.6938744 0.7199109 0.01632899 -0.8161287 -0.07337403 0.573193 -0.7252939 0.6477415 0.2331944 0.4921144 -0.3464947 0.7986018 -0.2759542 -0.1370577 0.9513488 0.2804433 0.2190702 -0.9345372 0.4139559 -0.2970697 0.8604593 0.1201292 -0.04999989 -0.9914983 -0.6767141 0.6022534 0.423496 0.1635896 -0.4331993 0.8863278 0.09000253 0.08489727 0.9923166 0.8248549 -0.1779494 -0.5366084 -0.1904675 0.9724254 -0.1345766 -0.104572 0.8073082 -0.5807909 4.91945e-6 -0.9396922 -0.3420212 0.7598667 0.6484562 0.04590278 0.3985144 0.8614221 0.3148623 -0.750589 0.6578589 0.06195002 -0.5882343 0.07681131 0.8050344 -0.5033718 0.8122426 0.2947519 0.5765914 0.627109 -0.5237144 0.8379253 0.4909937 0.238341 -0.9556014 0.2660135 0.1267394 0.1751656 -0.9286074 -0.3271167 -0.2390388 0.3821706 -0.8926399 -0.8931232 -0.3719245 0.2529886 -0.5940217 0.5139797 0.61884 0.2811025 -0.4525457 -0.8462764 0.4638819 0.1578726 -0.8717166 0.5726104 -0.6865234 -0.4481102 -0.7265017 -0.6871626 0.001707553 0.7529515 -0.6563982 0.04696285 -0.04180139 -0.8565261 -0.5144082 0.9200055 -0.3691409 -0.1316244 0.2127392 -0.801391 -0.5590301 -1.23242e-6 0.9396925 0.3420205 0.8689324 0.297597 -0.3954649 0.4562769 0.2965956 -0.8389532 0.2320585 -0.9188239 -0.3192358 -0.7827036 -0.6166067 0.0846827 2.58098e-5 -0.9396855 -0.3420397 -0.107181 -0.9845075 -0.1387709 0.3006237 -0.9529455 0.03899198 0.1930098 0.6731786 0.7138472 0.2256928 -0.02780783 -0.9738016 0.3933188 -0.9031786 -0.1719557 0.7733458 0.4434517 -0.453086 -0.2093648 0.9564891 0.2032117 -0.8006342 0.5445259 -0.2499532 -0.4166712 0.3404415 -0.8429024 -0.9043378 0.4236393 0.05199021 0.449625 -0.6095234 0.6529307 -0.07040756 0.3420433 -0.9370428 -0.2900096 0.8232461 0.4880167 0.002851068 0.9580208 0.2866845 0.3650675 -0.9163058 -0.1646494 -0.9782409 -0.0944311 -0.1847364 0.826954 -0.5618067 -0.02280986 0.7240226 -0.6601766 0.1998954 0.5062983 0.1364876 0.8514888 0.8267889 0.5519273 -0.1086114 -1.85192e-6 -0.9396916 -0.342023 -0.2958374 -0.7491266 0.5926968 0.8216074 0.1224898 0.5567385 -0.5295062 -0.3066228 0.7909524 -0.2697516 0.9628849 0.009318053 0.7043451 -0.02790188 0.7093092 -0.9671552 -0.1504653 -0.204868 0.656234 0.01091104 0.7544787 -0.7749466 -0.5614489 -0.290229 0.1580361 0.3331444 -0.9295372 0.05673718 -0.8563917 -0.5131997 -0.06493932 -0.9309272 -0.359385 0.3273859 -0.005280256 0.944876 -0.1248611 -0.6963537 0.706754 0.01483869 0.8433367 -0.5371806 0.1062819 -0.02338337 0.9940611 0.1567946 -0.1064257 0.9818804 -1.1763e-6 -0.9396929 -0.3420192 0.04082387 0.2700691 -0.9619752 -0.03854686 0.8533085 0.5199794 -0.1113794 0.001931011 0.9937761 0.3517231 -0.2374814 -0.9054797 -0.02729821 -0.4401242 -0.8975219 -0.6739958 -0.2295513 0.7021651 -0.4314705 -0.01547342 0.9019944 0.405991 0.6688963 0.6226951 0.1654427 0.9834497 -0.07386016 -0.621133 -0.09143882 0.7783527 1.55448e-6 -0.9396924 -0.3420205 0.05730533 0.9216013 0.3838843 -0.6767936 0.1512095 0.7204762 -0.7744694 0.07805782 0.6277773 0.1164004 -0.9462118 0.3018845 0.7156205 -0.6351739 0.2905879 -0.0797919 -0.52529 0.847174 -0.0384292 0.9194572 0.3913075 0.8690452 -0.4038005 -0.285842 -0.3639473 -0.9246824 0.1118251 0.0156176 0.9980596 0.06027561 0.008611857 0.1850673 -0.9826881 0.9650872 0.2389668 -0.107245 -0.1069542 -0.8484833 -0.518302 -2.29546e-5 -0.9396873 -0.3420349 -0.03005242 0.8916995 0.4516291 0.6649293 -0.2662173 0.697852 -0.7702093 -0.6329195 0.07867926 -0.1022515 -0.8257863 0.5546365 -0.362509 -0.8913187 -0.2722831 0.2370333 0.6606443 0.7122951 0.5678458 0.7973307 -0.2044867 -0.6781736 -0.02745532 0.7343887 0.929335 -0.04080873 -0.3669757 0.07070279 0.9884372 0.1341384 0.03027296 -0.1836999 0.9825161 0.6844009 0.6846488 0.2507018 -0.8770919 0.3171792 -0.3607035 -0.9884653 0.06779772 -0.1354249 9.57384e-6 -0.939692 -0.3420217 0.8052957 0.1799438 -0.5649063 0.9809216 0.1927646 -0.02519005 -0.9790223 0.005183696 -0.2036872 -0.1667001 -0.8170138 0.5519959 -0.552764 0.6410511 -0.5324525 -0.9268114 -0.3525241 -0.1294112 0.1416403 0.4422838 -0.8856201 0.9882382 0.1069156 0.1093358 -0.315145 0.8915445 0.3253184 -0.3547926 0.8580964 -0.3712046 -0.4732266 0.1155833 -0.8733254 1.75405e-5 -0.3418623 0.93975 0.9926542 0.1126317 0.04417949 -0.2433275 0.9318735 -0.269079 0.5558745 0.1245276 0.8218858 0.6171929 -0.675247 0.4038744 -0.143197 -0.089715 -0.9856196 -0.9191364 -0.2594918 0.2963989 -0.2646304 -0.9047237 0.3338351 0.9693474 0.245626 0.005790829 -0.5635973 0.6569257 -0.500806 0.7611196 0.370182 0.5325997 -0.5019409 0.6332955 0.5890604 0.7075324 0.5397835 0.4561049 0.3183975 -0.3858081 -0.8658956 -0.008993804 -0.9355763 -0.3530103 0.00513488 -0.9394311 -0.3426992 0.5556851 0.2216299 0.8013079 -0.8402735 0.311044 -0.4440632 -0.7679712 0.001894831 -0.6404814 -0.9153845 -0.3077441 -0.2595474 0.3929492 0.2704341 0.8788951 -0.02141749 -0.4074344 0.9129834 -0.7926768 0.5619734 0.2363246 0.316377 -0.2431756 0.9169358 -0.06680101 0.9142091 0.3996993 -0.3376514 0.9412693 -0.001910507 0.9852722 -0.04069381 0.16608 -0.1697608 0.251109 0.9529561 -0.7502554 0.3441456 -0.5645179 0.1034817 0.8973588 0.4289972 -0.3518157 0.2154232 0.9109438 0.7977834 -0.2654899 -0.541347 0.7353195 0.527309 -0.4257352 -0.3968335 0.3981873 0.8270248 -0.938215 -0.3395097 -0.06697541 0.5644371 0.8087024 0.1655635 -0.6298479 0.2483983 0.735928 -0.2497352 0.3278841 -0.9111115 0.4283376 -0.7700109 0.4728742 -0.1406039 0.1042456 0.9845625 0.07670044 0.8529556 0.5163176 0.2817543 0.3354621 -0.8989326 0.505685 -0.6948931 0.5112791 -0.4120435 0.9061344 -0.0956059 -0.6441201 0.3063934 -0.7008797 -0.6353963 0.7718528 -0.02268713 -0.5142729 0.8312397 -0.2111017 -0.328711 -0.4427927 0.8341965 -0.8494579 0.05365842 -0.524921 0.5267302 0.5613607 0.6383021 -0.4188206 -0.00494343 -0.9080555 0.9103561 -0.3170132 -0.2659969 -0.5119671 0.3356143 -0.7907292 -0.2983511 0.7969318 -0.525249 -0.488376 0.8640886 0.1218185 -0.00726366 -0.4544519 0.8907417 0.4379534 -0.1101259 -0.892227 -0.02377974 0.8948411 0.445751 2.02819e-7 0.9396922 0.3420211 5.25817e-4 -0.6831071 0.730318 -0.6323848 0.4098361 0.6573613 0.06354141 0.3892614 0.9189331 -3.56246e-7 -0.9396904 -0.3420264 2.02763e-7 -0.9396927 -0.3420201 -0.08828204 0.4156526 0.9052288 0.9983294 -0.05742305 -0.006389439 0.002305269 0.9403677 0.3401519 -0.4137508 -0.6615018 -0.6254803 -0.1847683 0.9587509 0.2160032 -0.2110859 -0.8214734 0.5297397 0.2020024 -0.9194869 -0.3372518 0.9717255 0.221515 0.08173537 0.002794086 -0.9404797 -0.3398385 -0.8710011 -0.2209846 -0.4387742 -0.6941999 0.2793442 -0.6633651 0.3430802 -0.5399435 0.7686071 0.6485986 0.7607254 -0.02483576 -0.04438698 0.1654414 -0.9852202 -0.9139962 0.1525157 -0.3759652 -0.9416716 -0.3122219 0.1255869 0.7755632 -0.2090309 0.5956574 -3.0204e-5 -0.9396939 -0.3420166 0.9260417 -0.3587528 0.1172322 0.1367889 -0.5583047 -0.8182815 0.1699355 -0.05364573 0.983994 0.5732802 -0.537401 -0.6185064 0.832884 -0.2066661 0.5134136 0.3239023 -0.2434987 0.9142186 0.8740615 -0.1841588 0.4495576 0.4694914 0.6278913 0.6207498 0.4789412 0.7332295 0.4826903 -0.3465865 -0.8810762 -0.3218425 0.4017717 -0.7441678 -0.5336607 0.002315044 0.9394876 0.3425753 -0.1537706 -0.8563792 -0.4929189 0.2553365 0.6498552 0.7158851 0.2347674 0.5495043 0.8018287 -0.3716638 0.8967337 0.2402808 -0.5827198 0.59451 -0.5540718 0.1639888 0.566713 0.8074306 0.03862762 -0.1448265 0.9887027 -0.3940464 0.1388652 -0.9085394 -0.2997086 -0.9444302 -0.1350038 0.1935535 0.8916686 0.4092237 -0.6765809 0.7285505 -0.1070164 -0.09361666 0.6224907 0.7770078 -7.82417e-7 0.9396927 0.3420196 0.003768682 0.3343178 -0.9424529 0.01420539 -0.4437869 -0.8960196 0.01013487 0.3281739 -0.9445629 -0.2959498 0.6393213 0.7097057 0.1514245 -0.7004319 0.697471 -0.003573715 0.8409518 -0.5410982 -0.3780155 0.6922585 0.6147215 -0.4780834 0.6480655 0.59283 0.7406805 -0.5432581 -0.3953011 0.5190185 0.1511064 0.8413006 0.5720217 -0.7704617 -0.2813893 -0.5364613 0.7374179 -0.4103949 0.6211035 -0.2822028 -0.731158 -0.7155441 0.1020239 0.6910773 0.3454156 0.9376793 0.03801989 0.08869737 0.9271077 0.3641484 0.3843393 0.7456079 0.5443824 -0.7152588 0.3899301 -0.5799649 5.07858e-6 -0.939692 -0.3420218 0.6547336 0.6787645 -0.33257 -0.5647573 0.7717146 0.2924134 -0.001288592 -0.9384033 -0.3455395 1.84932e-4 -0.9378883 -0.3469373 0.07460969 0.905001 0.4188158 0.5062854 -0.8109654 -0.2932749 0.01701861 -0.9302675 -0.366487 -0.9926355 0.1180302 0.02727115 0.5314649 -0.8319488 0.1593928 -0.03869831 0.936665 0.3480821 0.0273872 0.762848 0.6459976 0.2234428 -0.5562846 -0.8003879 -0.07367968 0.09953647 0.9923023 -0.5669828 0.1691015 0.8061856 0.9219409 0.3615036 -0.1390685 -0.06398159 0.3019911 -0.9511612 0.751698 -0.1708325 -0.6369979 -0.2145213 0.6936423 0.6876344 0.8206382 0.1507994 -0.5511919 0.8671736 -0.4751189 0.1492384 -0.5282596 0.1595711 0.8339537 -0.5755784 0.7679933 0.2808837 0.6032648 0.7970192 -0.02884644 -0.4296784 0.7931208 0.4316664 -0.9988788 -0.04419463 -0.01697093 0.003077626 0.9314092 -0.3639609 -0.01046609 -0.9326186 -0.3607119 0.02214425 0.5390047 -0.8420116 0.2378244 0.9280396 -0.2866742 -0.6096474 0.7166662 0.3387027 0.5379377 0.7864954 0.3033941 -0.9924867 0.004042923 -0.1222862 -0.1423222 0.9522172 0.2702343 -0.1240663 0.7040644 0.6992145 -0.7275337 -0.6348635 -0.2600832 -0.40028 -0.01801925 -0.9162157 0.7910737 -0.06275224 -0.6084936 -0.1793826 0.875285 -0.449108 -0.7504034 0.6537516 0.09748679 0.339849 0.6057283 -0.7194413 0.4650505 -0.04019343 -0.8843712 -0.3496257 -0.8808714 -0.3191043 0.6556558 0.7089502 0.2598173 0.141235 0.8482591 0.5104011 0.005239486 -0.9377816 -0.347186 -0.8563634 0.4926032 -0.154867 -0.002288162 0.9347131 0.3553959 4.49399e-7 -0.9396926 -0.3420199 0.2023902 -0.2235557 0.9534469 0.4489204 0.8728702 0.1912279 0.0049901 0.3041203 -0.9526206 -8.76826e-4 -0.9394223 -0.3427609 0.1573579 -0.1632443 -0.9739557 0.4269518 -0.9033944 0.03988438 -0.470599 0.6380211 -0.6094799 -0.8402797 -0.5390221 0.05818176 -0.4535802 -0.2140872 -0.8651195 0.449356 0.6694507 0.5915359 -0.6454664 -0.6992301 -0.3073279 0.6145867 0.7451215 0.2589926 -0.1204856 -0.9859551 0.1156532 -0.7208 0.6707217 0.1748704 0.2670174 0.2768148 -0.9230793 -0.06560736 0.9582999 0.2781311 0.8701359 0.1416305 -0.4720216 0.7644413 0.5798574 0.2817713 0.5622517 0.2235763 -0.7961699 5.91995e-4 -0.3215416 0.9468953 0.9101195 0.09306591 -0.4037588 -0.06689274 0.9201143 0.385895 -0.7059213 -0.6100627 0.3598593 -0.3881359 -0.01481473 0.921483 -0.003009438 -0.3648839 0.9310482 -9.50461e-6 -0.3420715 0.9396739 0.004993677 0.9393768 0.3428501 0.07965528 -0.7258081 -0.6832699 -0.1306274 0.9308228 0.3413289 -0.6715658 0.2371315 -0.7019742 -0.003596484 0.9380539 0.3464706 -0.1589609 -0.662914 -0.7316259 -0.09207046 0.6652311 0.740939 0.3089536 -0.8936049 -0.3256041 -0.9359955 -0.05337429 0.3479421 0.02283877 0.9122136 0.4090781 1.59003e-6 -0.9396907 -0.3420252 -0.452549 0.8400961 -0.299062 -0.9840086 -0.02889448 0.1757618 0.8882471 -0.1781188 0.4234274 -0.2151569 0.7882688 0.5764893 0.9374471 0.1448389 -0.316567 -0.4462705 -0.1888962 0.8747347 -0.03539764 -0.9506677 -0.3081847 -0.2973984 0.7794939 0.5513107 0.03012865 0.1896922 0.9813812 -0.03026145 0.918174 0.3950199 -0.1475981 -0.9077232 0.392751 -0.8205242 0.5537655 0.1417177 -0.01666295 -0.9310458 -0.3645217 -6.77247e-4 -0.9393768 -0.3428857 0.9613041 0.1925355 -0.1970391 -0.7681666 -0.6086242 0.1987381 0.54277 0.3602546 -0.7586945 1.95695e-7 0.9396927 0.34202 -4.71764e-5 -0.9396933 -0.3420186 0.7396675 -0.2116078 0.6388381 -0.02580314 0.8070352 0.5899393 0.8397473 0.08246856 0.5366782 0.1593531 -0.6299615 -0.760102 -1.19392e-6 -0.9396923 -0.3420209 -0.7574394 -0.3328529 -0.5616891 -0.6778084 0.2144662 -0.7032639 -0.9647057 0.1288358 -0.2296611 0.8107684 0.5817346 0.06511104 -0.8507573 -0.4943082 -0.1785261 -0.1218326 0.9648806 -0.2327279 0.002325952 -0.9392436 -0.3432434 -0.01074987 0.6675253 -0.7445095 -0.001998603 0.3368926 -0.941541 0.2955194 0.01285237 -0.9552503 0.02962225 0.79514 0.6057021 0.6414407 0.721257 0.2614235 -0.005770266 -0.6977128 -0.7163543 -0.73684 0.6737595 -0.05581146 0.8356333 -0.4274774 0.344935 0.4995881 0.7257233 0.4730089 -0.1103451 -0.2711441 0.9561929 -0.9824223 0.05458998 -0.1785112 0.5268626 0.5353983 -0.6601247 0.7469813 -0.624706 -0.2275111 0.5533379 -0.3278099 0.7657401 0.6987432 -0.3781682 0.6072451 0.2663135 0.7880331 0.5550506 0.04565972 -0.1034563 0.9935854 0.3897079 0.3398874 -0.8559232 -0.2595247 -0.9130954 -0.3144897 0.4580616 -0.263077 0.8490996 0.9660558 -0.1436974 -0.2146794 -0.293742 -0.695628 -0.6556047 0.05769258 -0.43522 0.8984737 -4.11997e-6 -0.9396927 -0.3420196 0.219685 -0.03219038 0.9750397 -0.2757396 0.9601114 -0.04640918 0.1081057 0.8506178 0.5145508 -0.7967518 -0.08189791 -0.5987313 0.8530165 0.2976 0.4287157 0.4069586 -0.2560699 0.8768197 0.284799 0.3351694 -0.8980818 -0.1269314 0.7834901 0.6083022 0.9819472 0.1764172 0.06823849 -0.1262193 0.343025 -0.9308074 -0.0275591 -0.001866579 -0.9996185 -0.3448673 0.9379689 -0.03578972 -0.8314137 0.5209959 0.1931695 -0.8082237 0.1080475 -0.5788785 0.2839422 0.9192515 0.2726783 -0.9989879 0.01483762 -0.0424602 -0.3463581 -0.3556696 0.8680641 -5.68633e-5 0.3424451 -0.9395378 -0.570474 -0.4021704 -0.7161135 0.1616767 0.02203297 -0.9865978 0.09466761 -0.1953494 0.976154 -0.3116739 0.9211127 0.2332612 0.02816689 0.9995286 -0.01221591 0.06647741 0.908307 0.4129883 -0.6473929 0.2370076 -0.7243687 -0.5597299 0.1804788 0.8087829 0.9238071 0.3828455 0.003121674 -1.61229e-6 -0.9396914 -0.3420233 0.1500258 -0.9585991 -0.242033 0.04730641 0.9712706 0.2332286 0.9786538 0.1860237 -0.0873605 0.3604413 -0.8327261 -0.4202966 -0.6070274 0.07464897 -0.791167 0.2559033 0.001428484 -0.9667013 0.6454429 0.3949077 0.6537978 0.9862911 0.01580631 -0.1642562 -0.6945989 0.3335432 0.637402 -0.155182 0.551409 0.8196748 -0.3677372 -0.8339665 0.4114232 0.07757973 0.986113 0.1468418 -0.9730948 -0.04943972 -0.2250385 0.03318029 0.8807889 -0.4723452 -0.3426021 -0.2282713 -0.9113265 -0.8432059 0.2711226 -0.4642157 0.9724022 -0.2039668 -0.1132764 -4.1321e-7 -0.9396927 -0.3420199 -0.6030459 -0.1604301 0.7814076 -0.1838663 0.8152973 -0.5490751 0.01855665 -0.2906094 0.9566618 0.262416 0.9610566 0.08664858 0.7554597 0.08352178 -0.6498499 -0.02076935 0.7481135 0.6632457 -0.1930431 -0.9661925 -0.1708989 0.6633194 -0.2808682 -0.6936284 0.1698864 0.6800665 0.7131958 -0.3985614 -0.1553984 0.9038807 -0.8163722 0.08164888 0.5717254 -0.5639426 -0.3257182 0.7588652 -0.3438615 -0.02287101 -0.9387418 -0.5499894 -0.3440923 0.7609941 0.4574176 -0.3206385 -0.8294336 0.007428348 -0.3782993 0.9256535 -0.5734366 -0.3438076 0.7436173 -0.1348071 -0.9675199 -0.2138508 -0.1207695 0.7326087 0.6698502 0.05769073 -0.435453 0.898361 -0.3993691 -0.4361764 0.8063836 -0.01651924 0.9914354 -0.1295491 0.4700385 0.1443499 -0.8707623 0.5102114 -0.7417309 -0.4353386 0.6646779 0.3500232 -0.660066 -0.5194712 0.330411 -0.7880219 -0.5119919 0.8520762 0.1087676 -0.7953032 -0.2648197 0.5453104 0.8354008 0.003227651 -0.5496318 -0.5095023 0.8537045 0.1076852 0.9883684 0.1034933 -0.1114319 0.2541995 0.6987279 0.6687018 0.9992852 -0.03511774 -0.01399189 0.1047211 -0.8345093 -0.5409508 -3.88929e-7 0.9396926 0.3420201 0.3043891 0.7205093 0.623068 0.0151031 -0.06408691 -0.99783 9.77089e-4 0.9408643 0.3387821 -0.2184662 -0.5543671 -0.8030876 0.9752266 -0.06097835 -0.2126377 0.4250461 0.248811 0.870304 0.05110001 0.9209581 0.3862964 0.2012814 0.9787491 -0.0391907 0.4527992 0.5591689 0.6944804 0.01980781 0.9419564 0.3351507 0.695885 -0.1710034 -0.6974968 0.7500811 0.4561136 0.4788932 -0.9661151 -0.1386889 -0.2176852 0.04245471 0.2455087 -0.9684643 0.139406 0.2454165 0.9593418 -0.5931726 0.6192698 -0.5144426 0.277209 0.8057112 0.5234355 0.6253791 0.3992231 0.6704639 0.7768601 -0.3430657 -0.5280098 -0.4667869 -0.6049291 -0.6451131 -0.09242266 -0.7944541 -0.6002507 0.4553869 0.7013209 0.5484265 -0.6223706 0.7149826 -0.3185198 -0.6846445 -0.7084562 0.1713236 -0.660985 -0.2644212 -0.702268 -0.2940461 -0.3287538 0.897473 -0.5907058 -0.4755008 -0.651894 -0.5428463 -0.5101268 -0.6671496 0.7258239 -0.2939137 -0.621928 -0.03394752 -0.3664495 0.9298185 -0.2767735 -0.5969545 -0.7530218 -0.8987186 0.1839925 -0.3980597 -0.01857095 -0.9405713 -0.3390882 -0.5782626 0.7661021 0.2805349 0.8016858 0.3414041 -0.4906558 -0.01089006 0.5448026 -0.8384936 0.03178989 0.9058539 0.4223957 0.0919401 -0.9611917 0.2601107 3.76699e-6 -0.9396941 -0.3420163 -0.4458304 0.5570803 -0.7006404 -0.05183833 0.9188647 0.3911527 -0.09946835 0.9929884 0.06387561 3.04588e-4 0.3141269 -0.9493809 -0.3449937 0.3496367 -0.871053 0.5739361 -0.8046622 -0.1520403 -0.02618318 0.7859823 0.6176943 0.09569531 0.7757543 0.6237369 0.9676272 -0.07506 0.2409639 0.04705023 0.6816561 0.7301585 0.09332251 0.6335299 0.7680696 -0.001068353 -0.9394493 -0.3426867 0.9985171 0.01456838 -0.05245351 0.007852554 -0.9947941 -0.1016022 6.75394e-6 -0.9396933 -0.3420183 -0.03358423 -0.7931869 -0.6080517 0.4014728 0.8185344 -0.4108782 0.1486299 0.4063107 0.9015657 0.6133747 0.1268392 -0.7795405 0.823547 0.5478447 0.1470943 -0.9047906 -0.3521519 -0.2394639 0.96111 -0.2379446 0.1401781 0.02934044 0.9600102 0.2784239 0.3513693 -0.8792854 -0.3215536 -0.3942831 0.7950369 0.4609308 -0.7711182 -0.5988477 -0.2162359 0.8934457 0.4142538 0.1736334 0.1201051 0.97036 0.2097046 -0.2733432 0.5941389 -0.7564936 0.7614606 0.6119846 0.213665 0.04076939 -0.9991233 -0.009506464 0.7285401 0.6363317 0.2535971 -0.7104021 0.2388141 -0.6620397 0.5374953 -0.1415772 0.8312969 0.1442033 -0.2596461 0.9548766 0.8724042 0.4585088 0.1693537 -0.2212136 0.1220908 -0.9675528 0.3257208 0.427112 0.8434936 0.2516251 -0.7190033 0.6478573 -0.3311862 -0.1546952 -0.9307981 -0.6772067 -0.2233734 0.7010673 3.86428e-7 0.3420268 -0.9396903 0.009755194 -0.3153237 0.948934 1.05274e-5 -0.9396846 -0.3420424 0 0.9396925 0.3420205 -0.451191 0.4229186 0.7858541 -0.5202902 -0.2185881 -0.8255407 0.9443999 0.103407 -0.3121151 0.1961508 -0.5958024 -0.7788095 -0.8646713 0.4183948 0.2780094 -0.07097303 -0.04002368 -0.996675 -0.05618476 -0.115357 -0.9917339 0.1655983 0.9068869 0.3874705 0.7867389 0.2091072 -0.5807892 0.3730902 -0.8749348 0.3086953 -0.08298957 -0.7308285 -0.6774972 0.06045466 0.9212283 0.3842964 -0.3123543 0.354005 0.8815413 -0.003094315 0.634809 -0.7726628 -0.5820676 -0.7528687 -0.3072229 -0.1211068 0.8937683 -0.4318695 -0.8893607 -0.1078548 -0.4443027 -0.571754 -0.5201697 0.6344453 -0.7937861 0.4957886 0.3522746 -4.80602e-5 -0.342449 0.9395364 -0.129871 0.932846 0.3360534 -0.101491 0.9225326 -0.3723346 0.717181 -0.6211192 0.3160102 0.546414 0.1708143 -0.8199111 -0.03306573 0.7796514 0.6253402 0.9796596 0.008069157 0.2005044 -0.9701263 0.1430046 -0.1959707 0.01972842 0.9053819 0.4241394 0.005718171 0.9400657 0.3409455 0.6513791 0.6596412 0.3749383 0.5510094 0.7082164 0.4413822 0.5460502 0.7276829 0.4150986 0.5189285 0.7208424 0.4594557 -0.01281082 0.9923254 0.1229889 0.1395294 -0.9300559 -0.3398935 -0.1052628 0.9551485 0.2767871 3.58846e-5 0.3415852 -0.9398508 -0.007826447 -0.936933 -0.3494215 0.6707041 0.04564595 0.7403193 -0.5122148 0.4965533 -0.7007645 -0.9191104 0.3859177 0.0793963 0.6785214 -0.5064452 -0.532092 -0.2578923 0.240326 -0.9358071 0.5177493 -0.7884595 -0.3320651 0.8290452 0.2667859 0.4914358 0.4510579 -0.8258378 -0.3384358 0.563299 -0.7666704 -0.3080757 0 0.9396925 0.3420206 0.6985591 -0.6500135 -0.2991619 0.7258882 -0.6234129 -0.2905905 0.7652875 -0.5744351 -0.2904468 6.01671e-6 -0.939695 -0.3420135 -0.0332477 -0.1934793 0.9805408 0.8306545 -0.4896553 -0.2650488 0.3708378 0.173738 0.9123017 0.9007615 -0.3554987 -0.2494984 0.9038959 -0.3467923 -0.2504144 -0.6675947 -0.3521867 -0.6559587 0.7976956 0.5656762 0.2090264 0.9637808 -0.157074 -0.2155326 0.9734986 -0.02891188 -0.2268582 -0.12634 -0.9575247 0.2591997 0.6101311 -0.7290555 -0.3101907 0.1611598 -0.5740904 -0.802775 0.8117535 0.2063188 -0.5463412 0.7138602 0.1624307 -0.68119 -0.05975681 0.1661423 -0.9842895 -0.8133897 0.5668398 0.1307277 0.6909508 -0.2414444 0.6813894 0.1807868 -0.7676802 -0.6148033 -0.9235182 0.1551216 0.350787 -1.26255e-5 -0.3421 0.9396635 -0.736717 -0.05571943 0.6739017 0.6963497 0.5858324 0.4146053 0.2365794 0.7344204 0.6361265 0.8292552 0.2491469 -0.5002614 0.756948 0.009125947 -0.6534115 0.9715281 0.117368 -0.2058103 -0.7859958 0.2406561 -0.5694693 -0.8427627 0.3119016 0.4387122 0.01412308 0.8222765 -0.5689129 0.02081423 0.9997829 9.45458e-4 0.02454435 0.9091947 0.4156472 -0.4666437 0.7630664 0.4471837 0.9752576 0.2207967 -0.01101851 0.3847013 0.2060799 0.8997423 -0.4893872 0.276107 0.8272032 -0.2069572 0.263112 0.9423061 0.7525698 -0.2925274 -0.5899715 0.9823958 0.1094021 0.1514259 0.2425024 -0.3954364 0.8859021 0.1835163 -0.2600061 0.9480077 0.007509171 0.3429867 -0.9393103 0.7927726 -0.3619076 0.4904431 0.3650422 -0.2646351 0.8925875 -0.5002301 0.7847869 0.3658951 -4.55609e-7 -0.9396926 -0.3420203 0.5020324 0.5264996 0.6861207 0.9562146 0.125461 -0.2644112 0.0727871 -0.9183904 -0.3889231 0.4774654 -0.1127518 0.8713862 0.003580927 -0.9386427 -0.3448727 -1.33459e-5 -0.3420604 0.939678 -0.6347352 0.4653819 0.6168718 0.1442799 0.00666356 -0.9895144 -0.7264286 0.2582423 0.6368771 0.5815302 0.7853114 0.212388 -0.2493443 0.8948601 0.3702065 0.3948212 -0.135637 -0.9086907 -4.63216e-7 0.9396929 0.3420192 1.52234e-5 -0.9397001 -0.3419995 0.3556706 0.7638552 0.5385385 -0.2193053 -0.8549115 -0.4701399 -0.256003 -0.6143853 0.7463197 0.903856 -0.4270544 0.02586519 0.2269692 -0.8017871 -0.5528311 -0.7892776 -0.5185505 0.3288561 -0.373282 0.7337117 -0.5677391 -0.993879 -0.05170178 0.09762924 -0.9890168 -0.1471866 -0.0134868 -2.69937e-4 0.3196626 -0.9475314 -0.6597204 0.7024983 -0.2669554 -7.50092e-6 -0.9396915 -0.3420233 -0.905317 -0.1338106 0.4031077 0.6290187 -0.2000093 0.7512202 0.1389875 -0.780717 -0.6092319 0.2264268 -0.3467352 0.9102228 -0.2174625 0.3591488 -0.9075915 -0.8925933 0.4250037 0.1504952 0.8564064 0.3717345 -0.3583037 0.4444459 0.7590188 0.4757713 0.8543417 0.2697893 0.4442005 0 0.9396925 0.3420204 0.03304159 -0.5390431 0.8416299 0.05860579 -0.8830201 -0.4656618 -0.9676695 -0.1424357 -0.2081531 -0.7947259 -0.2149709 0.5676251 -0.7344915 -0.4398341 0.5167863 0.6017516 -0.3025574 0.7391576 0.4491386 0.2783449 -0.8489987 0.1281682 0.9031837 0.4096733 -0.8272433 -0.3001093 0.4749768 0.5107133 0.5271541 -0.6791763 0.03094589 0.4282073 -0.9031504 -0.5938715 0.8045587 -0.001373827 0.279994 0.1912924 -0.9407501 -0.4177138 0.832917 0.3629938 3.23563e-7 0.9396927 0.3420197 -0.8302921 -0.2608887 -0.492496 -0.37156 -0.3069444 0.8762011 4.56848e-6 -0.9396896 -0.3420286 0.2565128 0.9210315 -0.2930911 0.4592019 -0.2175787 0.8612741 0.06873106 0.3372479 -0.9389036 0.2749425 0.2696694 -0.9228678 0.2062892 0.9099964 0.3596543 -0.4244706 -0.8164414 0.3914695 -0.03180402 -0.8427947 0.5372948 0.4635858 -0.3007655 -0.8334437 0.1901613 0.005402266 -0.981738 -0.6959148 -0.4945837 -0.5206626 -0.2940389 -0.3287543 0.8974753 0.855601 0.2239158 -0.4666995 -0.6361156 0.3706491 0.6767394 0.4171232 0.8646284 0.2800462 -0.5523533 -0.2758684 -0.78664 -0.7697558 0.5990147 0.2205839 -0.5102072 0.7694115 0.3843106 -0.1326028 -0.9709219 -0.1993168 -0.2098813 -0.411918 -0.8867207 0.532787 0.3871464 -0.7524996 0.7508009 -0.620827 -0.2255474 0.5384233 0.8289942 -0.151225 3.20717e-5 -0.9243771 -0.3814799 -9.42815e-4 -0.9390972 -0.3436504 0.4256393 -0.4615492 -0.7783339 -0.26166 -0.934343 -0.2419447 -0.9481979 -0.1043849 0.300041 -0.4710592 0.1493321 0.8693695 0.5121237 -0.07613068 -0.8555311 -0.8726436 -0.4815752 0.08110743 1.56632e-6 0.9396928 0.3420197 -0.2027848 0.02731174 -0.9788424 0.9675118 0.134518 0.2140699 -0.2704447 -0.5806523 -0.767921 -0.8204604 0.03928947 0.5703518 0.2418835 -0.3032397 0.9217039 0.9866732 0.150866 0.06095421 -0.9993448 0.02525353 0.02592879 -0.3450934 0.9347401 0.08468365 0.6906745 -0.4274055 -0.5833466 -0.6595363 0.05237406 0.7498459 -0.9981227 0.06115889 -0.003261923 -0.5917608 -0.6723278 0.4447411 -0.8887749 -0.431147 -0.1555353 -0.8191959 -0.1597815 0.5508065 0.9339134 0.334921 0.1250346 -0.5664659 0.126312 -0.8143474 0.2385174 -0.6494277 -0.7220478 0.008284449 0.07750338 0.9969577 -0.599103 0.1694302 -0.7825402 0.0422272 0.6460998 0.762084 -0.6564967 0.1520151 0.7388529 0.2461909 0.2851838 -0.9263154 -7.67652e-5 -0.9397005 -0.3419986 1.46661e-6 0.3420497 -0.9396819 -0.03156518 -0.8238182 -0.5659747 -0.08959859 -0.8998097 0.4269831 -0.3095046 0.01892954 -0.9507095 -0.7793673 -0.6012794 0.1762093 -0.1020362 0.7914852 -0.6026108 -0.07852303 0.9469274 0.3117094 0.2360857 -0.5912848 -0.7711328 0.3970482 0.3350179 -0.8544681 0.1859019 0.9282385 0.3222017 0.7299843 -0.6167356 -0.2945505 0.9987339 -0.04183912 0.02793145 -0.6082888 0.08075177 -0.7895973 0.5448033 0.6175804 -0.56726 0.06362181 0.9888322 -0.1347706 -0.4967359 -0.4256663 0.7563475 0.5584143 0.7793307 0.2842835 -0.007808566 -0.9352168 -0.3539897 -5.40094e-7 -0.9396926 -0.3420201 0.2687506 0.003027617 0.963205 -0.08788657 -0.8259739 0.5568151 -0.5146394 -0.840196 -0.1709298 0.2871882 0.910135 0.2986257 -0.06946247 -0.9196037 -0.3866577 -0.9448714 -0.3257778 0.03296816 -2.33059e-7 -0.9396924 -0.3420208 0.2762894 -0.7981415 -0.5353823 -0.5517947 0.3197993 -0.7702279 0.8658316 0.4974001 -0.05411905 0.6739948 0.4830963 -0.5588819 -2.92996e-5 -0.9396908 -0.3420252 -0.03947889 0.7907367 -0.6108819 -0.03725671 -0.1709296 -0.9845786 0.3489095 0.8546501 0.3844938 -0.729258 -0.3864073 0.5646877 -0.01017576 -0.9394266 -0.342599 -0.5335256 -0.6898985 0.4892755 -0.4478568 -0.7309377 0.5149316 -0.3447122 -0.8973952 0.2754188 -0.9654222 -0.1439089 0.2173711 -7.47233e-7 -0.9396928 -0.3420197 -0.3604729 0.7209845 0.5918114 -0.3999273 0.6899673 0.6033268 -0.5726912 0.7648169 0.2950932 -7.39833e-7 -0.939693 -0.342019 0.06201201 -0.9372341 -0.3431426 -0.2451628 0.3456097 -0.9057865 0.4063071 -0.5251708 0.7477368 0 -0.9396926 -0.34202 0.9288672 0.3475862 0.1280227 0.6017497 -0.3025547 0.7391602 0.9996191 -0.01025974 -0.02562135 -0.2571371 0.5945557 -0.7618294 -0.5545275 0.8187029 -0.1490798 -0.9871902 0.1248183 0.09937793 0.06322091 -0.8823237 -0.4663776 -0.08116674 0.8023963 0.5912464 -0.8524236 -0.4200475 -0.3113425 -0.6287341 -0.2780206 0.7262218 -0.1439309 0.1513986 0.9779377 0.8365588 -0.09891796 -0.5388735 -0.7470352 0.2559628 0.6135321 -0.4452204 -0.6904138 -0.570182 0.5346558 0.801571 0.2676325 -0.5112235 0.5476078 0.6624019 0.1287901 -0.6390866 0.7582753 -0.4364634 0.3519685 -0.8280204 0.8107787 -0.5545459 0.1873943 -0.1971723 -0.4245944 0.883653 -0.2338392 -0.8222944 0.5187979 -0.5018692 -0.5922605 0.6303609 -0.4139525 -0.01216399 -0.9102172 -0.893207 0.4491353 0.02141624 -0.7181735 0.6152932 -0.3250247 0.03282797 0.8343074 0.5503214 0.2755906 -0.6350486 0.7216392 -0.9196602 -0.1123129 0.3763121 -0.6626978 -0.5637542 0.4929633 -1.36387e-7 0.9396927 0.34202 0.3396378 -0.2967042 0.8925316 0.06518387 0.6708078 -0.7387611 -0.3261685 0.4501525 -0.8312501 0.01542168 0.9958027 -0.09021663 0.3531684 -0.7642396 -0.5396386 -0.5772796 -0.1108061 -0.8089933 0.1083855 -0.8206118 -0.5611137 0.6527385 0.4068596 -0.6390599 -0.1551406 -0.02506107 0.9875745 0.7660964 0.6049416 0.2171218 -4.12387e-6 1.98018e-5 -1 0.8101053 0.03592914 0.5851825 0.08170992 -0.9662916 -0.2441393 0.009026467 -0.9424782 -0.3341457 -0.2262035 0.8837631 0.4096276 -0.2434448 0.3242033 -0.9141263 0.005088508 -0.9377829 -0.3471847 0.2782034 -0.9349645 0.2201008 0.8062498 0.1911564 -0.5598397 0.8773874 0.4521963 0.1603432 -0.9630939 0.2536825 0.08997452 -0.004342913 0.3428673 -0.9393738 -0.9009848 0.3071033 0.3064537 0.7225871 0.1491286 -0.6750027 -0.8250858 -0.0351597 0.5639126 0.3185004 0.3259564 -0.890118 -1.14967e-6 -0.9396915 -0.3420233 -0.8587788 -0.383804 0.3394015 -0.002055525 0.9415689 0.3368142 -0.6887731 -0.6701489 -0.276572 -0.6321405 -0.7589144 0.156356 0 0.9396929 0.3420193 -0.3105446 -0.2318801 -0.9218425 -0.4507252 0.38063 0.8074451 -0.9324279 0.3611989 -0.01065081 0.4152978 0.8868661 0.2024753 -0.9879463 -0.154515 0.009337902 -0.2739389 0.9567727 -0.09769028 1.72813e-6 0.9396926 0.3420203 0.3910613 -0.06789147 -0.9178572 0.5367526 0.5934543 -0.5997572 0.4292203 -0.7715733 0.4695151 0.9275014 -0.05651408 0.3695231 0.8120521 -0.1346145 0.567847 -0.2370494 -0.602522 0.7620857 0.8542475 -0.4542199 0.2528742 -0.3317797 -0.7513101 -0.5704869 -0.0441488 -0.9737555 0.2232739 0.1353207 0.94178 0.3077962 -0.0338779 0.7647002 0.643495 0.9999836 -0.005098462 -0.002636253 -2.00657e-7 0.9396928 0.3420197 0.5828576 -0.115243 -0.8043607 -0.787366 -0.1930918 -0.585466 0.3205298 -0.7446556 -0.5854473 0.8846482 -0.1839087 0.4284569 -0.2727826 0.9320439 0.2385034 0.197821 -0.112266 -0.9737881 0.6308711 0.2440838 -0.736495 -0.9103175 -0.01038491 -0.4137805 0.2539944 0.8218981 0.5098732 -0.4417603 0.3604556 -0.8215349 0.01226967 0.9103135 -0.4137376 0.4505237 0.8467034 0.2830579 -0.9058293 0.4056012 0.1223152 -0.7757884 -0.2020761 -0.5977604 -0.5509275 0.8092806 0.2038228 0.09494364 0.6893306 0.7181984 0.06408166 0.6753743 0.7346858 -7.52995e-7 -0.9396925 -0.3420205 0.4148254 -0.4367681 -0.7982189 -0.6381651 0.7519929 -0.1650825 0.002689421 0.7762736 0.6303905 0.006081104 -0.9361956 -0.3514268 0.5039601 0.2311871 0.8322121 0.2544077 -0.9416041 0.2205865 0.1381256 0.787957 0.6000375 0.08280533 0.8893216 0.4497227 -0.6534518 0.6762125 0.3402022 0.3468372 0.1068235 0.9318222 -0.6939602 0.3961161 -0.6012581 0.2895824 0.8023512 0.5218952 0.3999302 0.8505893 0.3413996 0 0.9396927 0.3420197 0.5297048 0.7986946 0.2854817 -0.458052 0.8594154 -0.227142 -0.006735265 -0.8096573 -0.5868643 0.9016076 0.04028308 0.4306749 -0.3089973 -0.8931718 -0.326749 0.003584325 -0.3339369 0.9425886 -0.6072918 0.08105719 -0.790333 -0.01031428 0.941009 0.3382245 0.6593757 -0.4977821 -0.5634151 -0.1220488 0.9577956 0.260253 1.51846e-5 -0.9396966 -0.342009 0.1406426 0.9700869 0.1978662 -0.8528128 -0.5202798 -0.04493761 -0.6593138 -0.316268 0.6821144 -0.05948418 -0.5573608 -0.8281369 0.0546292 0.9949766 -0.08388715 0.8289566 -0.5520386 0.08991432 0.671801 -0.4577009 0.5824032 0.9474902 0.2978354 -0.1164326 -0.6220098 -0.7386901 0.2596934 -0.2448331 0.9662109 -0.08058071 0.6683313 0.7274426 0.155437 0.002703607 0.3438654 -0.9390151 -0.09663254 0.9540835 0.2835259 -0.1737662 -0.926337 -0.3342229 0.2494328 0.4996582 0.8295329 -0.9323974 0.1229337 -0.3398859 -0.00801301 0.9391363 0.3434514 0.1515709 0.815928 0.5579319 -0.4588428 -0.2723313 0.8457535 -0.51598 0.06462538 -0.8541594 0.1896548 -0.9622349 0.1952821 0.6705843 0.04580539 0.7404178 0.7819659 -0.1817562 0.5962331 -0.6271871 0.7693265 0.1215449 -0.150478 -0.1519484 -0.9768665 0.007396459 0.9393011 0.3430144 0.2433207 0.9363771 0.2529682 0.09937644 -0.901315 -0.4216107 0.7644389 0.5798625 0.2817671 0.004160702 -0.3550487 0.9348385 -0.2638749 0.7133817 -0.6491968 -0.2686007 -0.9453622 0.1847807 0.0911048 -0.7447469 0.661099 -0.7977101 -0.4119635 -0.4403916 0.6385528 0.2778907 -0.7176539 -0.9522638 -0.2634761 0.1541889 -0.8675999 -0.4201673 -0.2659511 0.2642651 0.9635296 0.04212647 0.9736333 -0.1886546 -0.1282483 -0.5101503 -0.795358 0.3273415 -0.04474818 -0.591091 -0.8053627 0.8081372 -0.5536527 -0.200955 0.04542857 -0.7271086 -0.6850178 0.6821085 -0.2558438 0.6850342 0.2506707 0.6589325 -0.7092052 0.9726691 0.1428511 -0.1830535 -0.5562038 0.4044835 0.7259685 -0.181776 0.8769021 0.4449722 0.9874977 0.1429606 -0.06641376 -0.9517815 -0.1963656 -0.2356954 0.6659045 0.1200131 0.7363207 0.01038706 0.9049532 0.4253845 -0.1738962 0.3781789 -0.909253 -0.03953504 -0.8789348 -0.4753005 4.90037e-7 0.9396926 0.3420202 -0.06403458 0.186017 0.9804577 0.2913346 0.8330815 -0.4702119 0.3121754 0.9467948 -0.07826888 -0.8717405 0.4850399 0.06931734 -0.5193982 0.3335728 -0.7867369 -0.9776198 -0.007310211 0.2102529 0.09443986 0.9039988 0.4169739 -0.06595057 -0.9366067 -0.3441199 -0.5434442 0.8298731 0.1264083 -0.9301756 -0.3516457 -0.1054459 0.006991922 0.9728131 0.231486 -0.9672011 0.1216197 -0.2230035 -0.252706 0.1992111 -0.9468128 0.9571949 -0.1384969 0.2541583 -0.07913398 0.01786571 -0.9967039 0.2664129 0.9633843 -0.03024375 0.05301374 -0.8819602 -0.4683328 -0.9159375 0.3976014 0.05451232 -1.45063e-7 -0.939693 -0.3420188 -0.07877957 -0.188118 0.9789819 -0.02099555 0.9314472 0.3632702 0.008066117 -0.2627921 0.9648187 0.3454201 -0.8796141 -0.3270534 -0.9979351 -0.008439481 -0.06367254 -0.3188104 0.568472 -0.7584191 -0.9106782 0.3688406 -0.1860694 0.01030778 0.9393077 0.342921 0.001281499 -0.3259575 0.9453836 -7.09517e-7 -0.9396923 -0.342021 -0.9264947 -0.1165935 0.3577898 -0.0683853 -0.5950307 -0.8007883 -0.3881252 0.7763136 -0.4966849 0.3650293 -0.264546 0.8926192 1.55289e-7 0.9396926 0.34202 -0.379088 0.8785229 0.2906711 0.8825315 0.4693782 0.02867317 -0.2543542 0.8484157 0.4642142 1.25162e-5 -0.9396843 -0.3420429 -0.6987674 -0.08112543 -0.7107341 2.60584e-6 -0.9396919 -0.3420225 7.10986e-7 0.9396926 0.3420201 -0.4650681 -0.2825185 0.8389844 7.31031e-4 -0.9852166 0.1713122 -0.02489012 0.3024389 0.9528437 -0.01697438 -0.5616788 -0.8271813 -0.977015 -0.1808983 0.1127718 -0.8822885 -0.4628003 0.08592349 -7.9358e-4 -0.9756072 0.2195219 -0.9526203 -0.2869602 -0.1008388 -0.1467493 0.5056583 0.8501614 -0.556562 -0.3956773 0.730533 0.9459471 -0.09915733 0.308791 0.004256725 -0.9839431 0.1784321 -0.7566404 -0.360989 -0.5451442 0.06239199 -0.7328392 -0.6775352 -0.6441435 -0.7579033 0.1032557 -3.34549e-4 -0.9853842 0.1703463 0.003429591 -0.9833518 0.1816803 0.713906 -0.1791142 0.6769463 -0.1616129 -0.3568542 -0.9200741 0.7739809 -0.5967577 0.2117399 0.4168064 -0.8791084 -0.2311726 -0.6154537 -0.7639157 -0.194035 -0.01164245 -0.9859686 0.166524 -0.7839972 0.1086531 -0.6111814 0.006718695 -0.984533 0.1750702 0.8414137 -0.08706593 0.5333315 -0.3621872 0.824879 0.4340451 0.2992824 -0.4705905 -0.830045 0.06155145 -0.05724537 -0.9964609 -0.1237676 0.8310178 0.5423015 -0.1248353 0.9857354 0.1128799 0.8507598 -0.1459043 0.5048959 -0.8354015 0.3508234 -0.423116 0.3127631 0.4201383 0.8518586 2.25871e-5 -0.9396944 -0.3420153 0.4435932 -0.8515682 0.2793864 0.2917898 0.5707672 0.7675177 -0.6285865 -0.08311456 -0.7732858 -0.002482831 -0.939584 -0.3423094 0.8825591 0.4699431 -0.01558834 -0.2031132 0.7457507 0.6345084 0.005211293 0.9394115 0.3427519 0.5420898 -0.02967578 0.8397964 -0.9945376 -0.04992884 0.09166252 -0.7788161 0.4554067 -0.4313353 0.6473002 0.2720595 -0.7120296 -0.2386122 -0.5149053 0.8233692 -0.3213735 0.8886716 0.3270809 -0.1290311 0.793073 0.5953035 -7.74297e-7 -0.9396913 -0.3420236 0.979934 -0.04779428 0.1935071 0 0.9396927 0.3420198 -0.9023927 -0.0856477 0.4223173 0.1056123 0.971576 0.2118633 0.8002425 0.5486542 0.2420545 0.4336546 0.8836939 0.1761503 0.3291113 -0.8850691 -0.3291479 -0.68449 0.3393422 0.6452288 0.03792381 0.7873948 0.6152815 -0.4480295 -0.3284396 0.8315028 0.789417 -0.5707087 -0.2260807 0.003172636 0.7276344 -0.685958 -0.1217385 0.8814995 0.4562219 0.04273945 -0.1869759 -0.9814344 -0.7510294 -0.2886922 -0.5938111 0.3386931 0.933788 0.1154434 -0.2015027 0.8373257 -0.5082148 -0.9747596 -0.1101381 0.1941987 -0.02780562 -0.7428686 0.6688596 0.2661384 0.8298147 -0.4904874 -4.76705e-7 -0.939693 -0.3420194 0.8436586 0.3545808 0.4031285 -0.4911847 -0.8127536 -0.3133193 0.1217291 0.9869233 -0.105662 0.02805763 -0.9219294 0.3863404 -0.6581515 0.6189136 0.4286987 -0.4285835 0.3801806 0.8196212 -0.07138007 -0.9369257 -0.3421622 1.98369e-5 -0.9396825 -0.342048 -0.5770635 -0.8163362 0.02434891 -0.6416709 -0.75075 0.1569496 -0.327055 0.720174 0.6118696 -0.5621945 -0.8262286 0.03582894 -0.4124431 -0.9089444 0.06091666 -0.4032597 0.0322625 0.9145167 -0.5606631 0.7069566 0.4311256 0.2181391 -0.916369 -0.3356832 0.9107679 0.09227257 -0.4024768 -0.8357913 -0.1901947 0.5150523 -5.8886e-7 -0.9396924 -0.342021 -0.8047046 0.5278649 0.2716787 -0.505823 -0.4839301 0.7141112 -0.9672488 0.2502326 0.0425834 0.3373487 -0.2909411 0.8952928 -0.001727402 0.9397607 0.3418288 5.87254e-6 -0.939693 -0.3420192 0.8172781 0.5547772 0.1558167 -0.08655768 0.4217992 0.9025482 -0.6478419 -0.7160305 -0.2600024 -0.07226049 -0.9973856 -4.84795e-4 -0.249362 -0.7370514 0.6281509 -0.4855234 -0.1138011 -0.8667851 -0.4016019 0.8406991 0.3632366 -0.1516604 -0.6555092 0.7398018 0.3539953 -0.2814458 0.8918944 -0.7680435 0.412186 0.4901141 0.2668634 -0.1724618 -0.9481776 0.396036 -0.8496174 0.3482897 2.91807e-6 0.9396924 0.3420208 -0.9605687 -0.04513871 0.2743542 -0.590238 -0.1965866 0.7829259 -0.1910627 -0.3833809 -0.9036117 0.007009983 0.9623595 0.2716891 -0.7446109 -0.2610108 0.6143517 0.627016 0.4466278 0.6382591 0.4286953 0.6601008 0.6168364 -0.3365659 0.004540741 -0.941649 -0.9917908 -0.1128752 -0.06008678 -0.317234 0.8919821 0.3220719 0.4477511 -0.2643659 -0.8541836 -0.5203128 0.5936407 0.6138936 0.2776569 0.486391 -0.8284507 -0.8380403 0.5430147 -0.0531367 -0.5473951 0.8024739 -0.2374751 0 -0.9396927 -0.3420199 -0.04533505 0.1015697 0.9937949 -0.7074706 0.6504032 0.2765159 0.3347274 -0.6565359 0.6759572 0.6288307 -0.200019 0.751375 0.1056329 0.07153099 0.9918292 -0.4664875 0.6848052 0.5598492 0.02534699 -0.9994856 0.01965111 -0.2695477 0.9118914 0.3095129 0.3678122 0.3250588 -0.8712353 -2.48813e-7 -0.9396926 -0.3420204 0.01101255 -0.4353814 0.9001787 0.3046285 -0.5644943 -0.7671685 0.6593518 0.746921 0.08581608 -0.1381075 -0.8242947 -0.5490578 -0.07715904 0.8484895 0.5235571 -0.08120179 0.3381416 -0.9375855 0.06214427 -0.9161744 -0.3959326 -0.6241283 -0.7447867 0.2361284 0.04104894 0.9608299 0.2740817 -0.9999676 0.007359564 0.003278315 -0.8695015 -0.2331389 0.4354463 0.8559195 -0.2238577 0.4661433 0.02474498 -0.9421324 -0.3343264 1.63497e-4 -0.9378803 -0.346959 -0.5435928 0.7655237 0.3442098 0.9710068 0.128135 -0.2018101 -0.1562173 0.7507377 0.6418636 0.04935985 -0.9442372 -0.3255452 0.2128797 -0.1751599 -0.9612498 0.2515446 -0.5667241 -0.7845695 -3.69136e-7 -0.939693 -0.342019 -0.4147692 0.8667914 -0.2768378 0.002333581 0.9055369 0.4242612 -0.1870251 -0.9671494 0.1721733 0.2415542 0.1541569 0.9580643 -0.3757924 -0.8333686 -0.4053109 0.9462398 0.2848219 0.1533192 0.2491255 -0.07168984 0.9658142 0.568812 0.7905195 0.2270064 -0.1282633 -0.9886366 0.07839816 0.01119357 0.9380033 0.346446 -0.1837308 0.8585348 0.4787079 -0.3982359 -0.868849 0.2941252 -0.1091265 0.4160723 0.9027597 -0.00262928 0.3365712 -0.9416544 -0.3416804 0.8305943 0.4397359 0.1626703 -0.4817718 -0.8610658 -0.1320649 -0.587801 0.7981534 -0.3571017 -0.6688972 0.6519624 -0.2804992 0.9428897 -0.179664 -0.4495865 -0.7676061 0.4567853 -0.3773639 -0.8436967 0.3818014 0.03354269 0.9741005 0.2236138 0.8903572 -0.1740399 0.4206829 0.8978573 0.4400131 0.01552236 -0.5438457 0.3998527 0.7378005 -0.5080499 0.672736 -0.5378769 0.1743708 -0.858793 -0.4817358 -0.9801952 0.05575287 -0.1900236 0.8805338 0.4699345 -0.06182247 -0.9436843 0.2169593 0.2497771 0.9326232 -0.1077591 0.3443865 -0.5020485 -0.2214639 -0.836003 0.003459155 0.9377744 0.3472276 -0.3028752 0.7339031 0.6079908 0.6800377 -0.2319154 0.6955314 -0.7193427 0.2731389 -0.6387028 -0.2163845 -0.9723046 0.08832687 0.3047604 -0.7345343 -0.6062842 -0.378385 0.4220734 0.8238197 0.9725019 0.08651256 -0.2162303 0.3483781 -0.3288478 0.8777766 0.2537226 -0.6185172 0.743681 -0.6580581 -0.2769476 0.7001855 0.9987339 -0.04183959 0.02792984 0.8595445 0.4231095 0.2866387 0.7020518 0.1763196 -0.6899527 0.4726488 -0.3129964 0.823794 -0.1577515 0.8819376 0.4441851 -0.7378081 -0.2788888 -0.6147034 -0.02502495 0.5844899 -0.811015 -0.1656062 0.8804574 0.4442626 0.2643719 -0.9643619 -0.01065772 -0.6269808 -0.7208233 -0.2954807 -0.678011 -0.258214 0.6882053 -0.4110401 -0.570614 0.7109471 0.3421722 0.100055 -0.934295 0.001848459 -0.3315313 0.9434424 -0.4612013 -0.3672452 -0.8077279 -0.7089442 -0.1580777 0.6873205 0.247727 0.8420471 0.4791536 -0.004674375 0.9385464 0.3451216 0.3036596 0.254943 0.9180386 0.1166958 -0.9069653 -0.4047173 -0.1208308 -0.9435133 0.3085166 0.02365928 0.7714984 0.6357914 0.05086296 0.8956758 0.4417892 -0.3655095 0.9308074 7.0975e-4 -0.9017674 0.1730169 -0.3960815 0.04217892 0.3493418 -0.9360456 0.03555965 -0.975326 0.2178869 0.535794 0.7446732 -0.3979781 0.4844022 -0.556873 0.6747199 0.1165761 -0.3417238 -0.9325422 -0.2785614 0.8268396 0.4886102 0.9276247 0.08351904 -0.3640564 -0.6959891 0.6375502 0.3303469 0.5879044 0.266152 -0.7638924 -2.4425e-5 -0.9396857 -0.3420391 -0.007304608 -0.7918192 -0.6107119 0.9692105 0.04670047 -0.2417643 -0.3935973 -0.1092601 0.9127669 -0.2092288 0.4958575 0.8428218 -0.4131724 -0.4386017 -0.7980709 0.7819706 -0.1817511 0.5962287 0.7028732 0.2520252 -0.6651712 -1.31767e-6 -0.9396887 -0.342031 0.1536772 -0.5662469 0.8097826 -0.909997 0.3300173 0.2509864 -0.5537595 -0.5475186 -0.6273547 0.8375438 0.3164445 0.4454025 -0.3329954 -0.06444287 0.9407238 0.004891037 0.3381844 -0.9410672 0.6940053 0.5934516 0.4076418 -0.2014671 -0.3268366 0.9233574 0.1657953 -0.4333378 -0.8858501 0.02818459 -0.3968589 0.9174468 -0.2050736 -0.9712472 -0.1209282 -0.9997937 0.01943892 0.005876481 0.6938683 -0.07844924 0.7158159 4.26054e-5 0.3419428 -0.9397208 -0.05253595 0.8426153 -0.5359475 0.2243989 0.4702159 0.8535468 0.08898288 -0.9324221 -0.3502445 0.8433279 -0.1768612 -0.5074625 0.2791287 -0.7362061 0.6165127 0.3134213 -0.8289487 0.4632616 0.2722322 -0.7485123 0.6046643 0.08398491 0.6699284 0.7376601 0.8499291 -0.2144264 -0.4812918 -0.6338919 0.7635762 -0.1230136 -0.9879463 0.1545148 -0.00933808 -0.9058172 -0.2848247 0.3136402 -0.07567572 -0.5234123 -0.8487124 -0.004026949 0.3395652 -0.9405739 0.695352 -0.08470875 0.7136598 0.08192574 0.3047733 -0.9488948 -0.4026163 -0.9109782 -0.08954834 0.2614096 0.6734675 -0.6914524 0.4357019 -0.5994741 0.6714124 0.001902282 0.7001035 -0.7140388 0.3820071 0.9013516 0.2040486 -3.27191e-5 0.3198479 -0.9474689 0.2173303 0.692225 0.6881803 0.01932793 -0.3167038 0.9483276 0.2006239 -0.9174784 0.3434873 0.1369315 0.5916686 0.7944672 -0.2163652 -0.432778 0.8751509 2.05202e-5 -0.9396892 -0.3420297 -0.4418694 0.2901507 -0.8488605 -0.02660989 0.007967829 0.9996142 0.3085919 0.3257085 0.8936919 0.06323361 -0.9208456 -0.3847659 0.1424811 0.2606317 -0.9548666 0.2365954 0.4971714 0.8347714 -0.4136509 0.1267746 0.9015659 -0.7990205 0.1001278 -0.5929085 0.03488349 -0.7731757 0.6332318 -0.7515032 0.6187416 0.2289143 0.575318 -0.6623245 0.4799327 -0.04240787 0.07357597 0.9963876 -0.9284371 0.1762127 -0.3270376 -0.2585266 0.6521748 0.7126234 0.2986108 0.8567891 0.4204093 -0.4720001 0.7585922 0.4491703 0.8202948 -0.05565983 0.5692261 0.5158722 0.3388805 -0.7867882 0.9225739 0.1329324 -0.3621969 0.3098592 -0.2838284 0.9074298 -0.9482758 -0.2191239 0.2296904 -0.6786612 0.3467949 0.6474198 0.6578121 0.744479 0.1141677 -0.3892737 0.658586 -0.6439957 0.5117291 -0.6168138 -0.5980586 0.5592399 -0.1194164 0.82036 -0.7820861 0.002735018 0.6231644 -0.9432564 0.1568176 -0.2927038 -0.8579888 0.1587787 -0.4885126 0.5562 -0.09183919 -0.8259584 0.935859 0.151818 -0.3179925 0.5199772 0.4996832 0.6927774 0.3854725 -0.9093844 -0.1563042 0.05214393 -0.6855974 -0.7261111 0.3652144 -0.9102937 0.1948948 0.4142044 -0.8854966 0.2105481 -0.05670607 -0.334541 0.9406735 0.5712875 -0.7990899 0.1873127 -0.2792726 0.8885109 -0.3640815 -0.4881253 -0.2729953 0.8289796 -0.5694659 0.526469 0.6312995 0.008379876 0.9389469 0.3439602 -6.87276e-4 -0.939907 -0.3414299 0.005237817 -0.9155342 -0.4022061 -0.4615853 -0.3389707 -0.8197792 0.3133481 -0.940244 -0.1332445 0.234205 0.951497 0.1995036 0.6531966 -0.7444168 0.1384845 0.04830312 0.9732391 -0.2246609 -0.3468235 0.3932685 -0.8515006 0.7124013 -0.7017158 0.008898973 -0.05238473 0.993439 -0.1016598 -0.003696143 0.6197336 -0.7848036 0.1748851 -0.5171771 -0.8378204 -0.9999601 -0.008927702 6.93557e-5 -0.1533578 0.9322261 0.327774 0.057594 0.5334815 -0.8438486 -0.4938995 0.2070075 0.8445183 -0.4835189 -0.1500815 0.8623718 -0.1794587 -0.9498878 0.2559448 -0.5311906 0.1992723 0.8234847 0.9658107 -0.1151061 -0.2322937 0.9091889 -0.4012135 0.1113696 -0.3944373 -0.2466471 -0.885203 -0.5284296 0.3666292 -0.7657318 0.01270979 0.9101376 0.4141111 -0.4551411 0.2994307 -0.838563 -2.5206e-5 -0.9396909 -0.342025 5.72669e-7 -0.9396904 -0.3420262 0.05080509 -0.1642006 -0.9851177 0.5840263 0.6318705 0.5095616 0.4347137 -0.8992474 -0.04876554 -0.1812269 0.3375419 -0.9237003 0.0565645 -0.8711696 -0.4877129 0.4710332 -0.8776512 -0.08863461 1.09729e-5 -0.9396882 -0.3420327 0.3377932 -0.9412199 8.41596e-4 0.1976034 -0.979029 0.04954773 0.6327216 0.7518736 -0.1853357 -0.6652562 0.5817143 0.4680199 0.3570706 0.76644 0.5339197 0.895089 0.06225883 0.4415195 -0.9008514 0.1320564 -0.4135552 0.7117986 0.2234659 0.6658872 -0.9787364 -0.1916952 -0.07299321 -0.7916407 -2.15645e-4 0.6109869 0.634328 -0.7196182 0.2824495 -0.06040447 0.9319799 0.3574422 0.3814969 0.2333808 0.8944236 0.7807956 0.4843981 -0.3946097 -0.3582892 0.8194309 0.4473945 -0.07547104 0.9382069 -0.3377452 -0.5542938 0.8241546 0.1163083 0.402543 0.6851335 -0.6070844 2.74627e-7 -0.9396939 -0.3420169 0.1599336 -0.9241864 0.346844 -0.2807404 -0.3251097 0.9030441 0.9199491 0.1671081 -0.3546386 0.1559283 0.5994074 -0.7851096 0.04509603 0.6798159 0.7319949 -0.08977824 0.9694654 0.2282031 0.8727062 -0.4763607 0.1070711 -0.3580105 0.2786158 -0.8911799 -0.08224385 -0.7207524 -0.6882964 0.9902867 -0.1341387 0.03659379 0.1855654 -0.280025 -0.9418871 0.5899311 -0.2066417 0.7805641 -0.9577969 0.239105 -0.159543 -0.01491171 0.9400096 0.3408221 -0.8695816 -0.4915861 -0.04659497 -0.70697 0.6863603 0.1705954 0.4517062 -0.2410495 -0.8589858 0.3993251 -0.3077303 0.8636212 0.3925282 -0.2925204 0.8719825 0.5340456 -0.1345019 0.8346883 -0.1742023 0.9473943 0.2685102 -0.1118559 0.9580524 0.2638635 0.0683515 -0.3460047 0.9357397 -0.07082784 -0.5688375 -0.8193944 -0.7003138 0.2346308 -0.6741728 0.07910484 -0.9923568 -0.09471255 -0.7042989 0.6260578 -0.3346858 -0.8373512 0.2024656 -0.5077898 -0.3766915 0.8932924 0.2452191 0.2796961 0.2828291 -0.9174846 -0.2331885 0.1232131 -0.9645941 0.6309511 0.1903501 -0.7521088 3.02571e-4 0.33995 -0.9404435 -0.8811448 0.01830595 0.4724922 0.8086174 0.4231526 0.4087539 0.2426565 0.3473519 -0.9057949 0.002626419 0.9576123 0.2880481 -0.3764568 -0.03944706 -0.925594 0.6801602 0.2006263 0.7050753 -0.1931099 -0.9664661 -0.1692681 -0.4265019 -0.3990928 -0.8116778 -0.07922303 0.9845254 0.1563118 0.6954746 0.7185195 0.006688058 -0.09188872 0.8030516 0.5887823 -0.9852705 -0.08780419 0.1467405 -0.19542 0.9213116 0.3361489 -0.8326588 -0.4031235 -0.3796981 0.01985698 -0.6148311 -0.7884088 -0.9361406 -0.1218248 0.3298478 -0.6586232 -0.2838332 0.6968889 0.8305453 0.4007199 0.3868048 -0.4115455 -0.8471977 -0.3359855 0.3343024 0.9340598 0.1255952 0.3133431 0.8671691 0.3870838 0.596005 0.7717148 -0.221888 -0.001986443 0.9996263 -0.02726155 0.2029849 0.8819973 0.4252973 -0.08095407 0.4602378 -0.8840971 0.2121891 -0.265132 -0.9405747 0.1568124 0.2189158 0.9630606 -0.3670521 -0.3802154 -0.8489459 0.7928716 -0.2294242 0.5645522 2.12277e-6 -0.9396938 -0.3420168 -0.007114708 0.3747702 -0.9270904 -0.4762324 -0.05152779 -0.8778085 -0.8952446 0.05599379 -0.4420428 0.724171 -0.6889266 -0.03092998 0.9762542 -0.1830114 -0.1159071 0.693764 0.2992419 0.6550922 0.0051409 0.3484857 -0.9373 -0.04153734 -0.9793034 -0.1980895 0.2684946 0.07239294 -0.9605571 -0.3574886 0.9339076 0.004308164 0.1807835 -0.4568109 -0.871 -0.002016425 0.934825 0.3551031 -0.9727539 0.01788848 0.231149 0.7330937 -0.2807071 0.6194974 -0.9633293 0.2511036 -0.09457093 -0.3120206 -0.8924722 -0.3257862 -0.9744643 0.07748049 -0.2107511 -0.8853372 0.3931772 -0.2481728 0.2524136 0.8385432 0.4828381 0.7214722 0.3249174 -0.6114792 0.03737902 0.9186741 0.3932439 -0.6473838 0.4951136 0.5794453 -0.09783482 -0.8054308 -0.5845593 0.9393666 -0.2506022 -0.23407 0.06328123 0.8041802 -0.5910074 -0.5223443 0.290789 -0.8016223 0.550428 0.1269223 0.8251787 0.4266095 0.8874249 -0.174589 0.1872174 0.8830946 0.4302251 0.003436386 0.9436097 0.3310422 0.825951 -0.1016757 0.5544971 0.6152503 0.7664035 0.1846422 0.003981053 -0.9372431 -0.3486541 0.5259453 0.8479014 0.06666928 0.2650731 0.7158729 -0.6459584 -0.4521471 -0.1852474 0.8724943 -0.9260358 0.1674783 0.3382435 -0.526083 0.1917841 -0.8285261 0.9783753 -0.07479977 -0.1928389 -0.07987993 0.765449 0.6385195 -0.4885197 -0.8094345 -0.3258285 0.7078124 -0.2095844 -0.6745932 -0.199088 -0.9798659 -0.01506501 0.173652 -0.0566765 0.9831748 -0.2289836 0.8158618 0.5309765 0.3321903 0.9199155 -0.2083387 0.9876111 -0.1538265 0.03101086 -0.2104151 0.8800401 -0.4257405 0.8760147 -0.1856613 0.4451158 -0.3231806 0.04996252 -0.9450175 -0.599146 0.7483072 0.284711 0.456889 0.7944465 -0.4001341 0.4358861 -0.8751158 0.2101802 0.0396353 -0.8237909 -0.5655065 -0.2152192 0.8789007 0.4256926 -0.1839883 -0.9827862 0.0167219 0.04696136 -0.3693146 -0.928117 0.01605618 0.2714298 -0.9623243 0.0902819 0.9103853 0.403792 0.6079103 0.09807789 0.787925 -0.2862738 -0.3203437 0.9030101 0.1755898 -0.9253905 -0.3358878 -0.8266061 -0.06616467 -0.5588779 -0.3140276 0.7021913 0.6389946 0.2071359 -0.9194527 -0.3342176 -0.3226016 -0.8889605 -0.3250805 -0.3178889 -0.9479071 -0.02046495 -0.06150114 0.402693 0.9132667 -0.2822442 -0.3895272 0.8767023 -0.004154086 0.940992 0.3384033 -0.5359156 -0.6172675 0.5759993 0.806446 0.1952409 -0.5581449 0.002537369 -0.9396585 -0.3421047 0.9959246 0.06704419 0.06032741 0.9957743 -0.07056009 -0.05877757 0.9562749 0.1357901 -0.2590357 -0.9764096 0.2025432 0.07483577 -0.144142 -0.7470755 0.6489232 0.973199 -0.2224081 -0.05846714 0.2493892 0.9319735 0.2631171 -5.02387e-7 -0.9396929 -0.3420194 0.9379394 -0.3250308 -0.1209324 0.909345 -0.3979027 -0.1215121 -0.4678957 -0.399271 0.7884518 0.7766766 -0.5915771 -0.2163563 -0.4248324 0.674926 -0.6033178 1.63726e-5 -0.9396963 -0.3420102 0.3185139 0.7686059 -0.5547917 0.602413 -0.7955941 0.06425428 0.7758573 -0.5927101 -0.2161949 -0.002764403 0.3830187 -0.9237365 -0.5793938 0.3403375 -0.7405899 0.6174098 -0.7334569 -0.2843346 0.585507 -0.7646183 -0.2693333 0.4756616 0.2958984 -0.828366 -0.9095444 -0.1173452 0.3986967 0.4716482 -0.09161472 -0.8770146 -1.03121e-5 0.3421411 -0.9396486 0.8212484 -0.5367982 -0.1933876 0.06073206 -0.3479757 0.9355344 0.3118345 -0.894424 -0.3205696 0.3160845 -0.8919929 -0.3231709 0.001673579 0.3142322 -0.9493446 -0.5156702 -0.6671521 0.53758 -0.8734718 0.2891477 0.3917149 0.02043628 0.9237874 0.3823601 0.01828241 -0.9374907 -0.34753 -5.45401e-7 0.3421061 -0.9396614 0.8385131 0.2711337 0.4726335 0.07175183 -0.9217094 -0.381187 -0.3885008 0.2994112 -0.8714472 -0.1966357 -0.9291671 -0.3130221 -0.4385914 -0.8983448 -0.02478516 -0.4427459 -0.8910748 0.09980875 -0.3307463 -0.8776592 -0.3468735 -0.3245251 -0.248113 0.9127559 -0.1188796 0.4248927 0.8974039 0.5752432 -0.5415017 -0.6130834 -0.4693441 -0.8397625 -0.2729745 -0.9590356 0.1628503 0.2317981 -1.41699e-5 -0.9396796 -0.3420559 -0.6006822 -0.7409803 -0.3002151 0.4602076 -0.07756137 0.8844169 0.5986906 -0.30168 0.7419964 -0.2287642 0.7743233 -0.5899918 0.9774276 -0.02912241 0.209254 -0.7365018 -0.6480241 -0.1939846 0.5675047 -0.7658848 -0.3022564 0.2045507 0.9416998 0.267134 -0.8118335 -0.5440015 -0.2121056 0.259304 -0.1969426 -0.9455025 0.6623557 -0.5435947 0.5155481 -0.5922544 -0.7289308 -0.3433579 -0.9189632 -0.3690728 -0.1388946 -0.918685 -0.3695315 -0.1395147 0.2656839 0.947959 0.1754591 -0.06582248 -0.5803675 -0.8116902 0.1571058 0.9328691 0.3241499 -0.5813933 0.6640279 -0.4701585 5.42811e-5 0.3413825 -0.9399245 -0.02827394 0.8930388 0.4490905 -0.9968888 -0.07596379 -0.02103126 -0.9964182 -0.07989925 -0.0276916 0.5067601 0.7613518 -0.4043979 -0.2379264 -0.836842 -0.4930381 -0.9346417 -0.1036831 -0.3401393 -0.977069 0.2001551 0.07262361 -0.9726338 0.2143045 0.08976113 -0.001360177 -0.3358903 0.9419001 0.04485839 0.01593017 -0.9988663 -0.9069696 0.3908553 0.1569659 -0.9155266 0.3763825 0.1419408 -3.14337e-4 -0.3431642 0.9392753 0.3435315 0.3308733 -0.8789249 -0.8784487 0.4772101 0.02446699 -0.8277244 0.5230183 0.2032837 -0.001155316 0.3529365 -0.9356465 3.47279e-5 0.3415994 -0.9398456 -0.7365338 0.6477679 0.1947169 -0.6750099 0.6930359 0.2531068 0.6663004 0.5799754 -0.4686922 -0.9270151 0.1492649 -0.3440392 -0.8481591 -0.2206562 -0.4815984 0.9265586 -0.3550313 0.1242654 0.9806098 -0.04494804 0.1907462 -0.002368271 0.3457134 -0.9383372 -0.4695647 0.8297409 0.3017266 -0.4983588 0.822895 0.2729145 1.74282e-4 -0.3410372 0.9400498 0.5627732 0.8196901 -0.106745 0.1788095 0.947063 0.2666438 -0.2925422 0.8907445 0.347841 -0.2977088 0.3359692 -0.893585 -0.1575183 0.9379966 0.3087887 -0.02942091 -0.8218346 0.5689661 -2.11597e-7 0.3421381 -0.9396497 -0.1665934 -0.9523811 0.2553757 -0.07651847 0.9375134 0.3394315 0.1524626 0.936504 0.3157774 0.1950618 0.9208227 0.3376929 3.32266e-4 0.008133172 -0.9999669 -0.06272566 0.8767145 0.4769037 0.6899576 -0.05925327 0.7214205 0.2862388 -0.9506291 -0.1198823 0.2916641 0.6121438 -0.7349912 -6.3518e-5 -0.9396814 -0.3420512 0.4718564 0.827749 0.3036167 0.4390718 0.8525609 0.2834707 -0.02258843 0.9209429 0.3890426 0.9467727 0.2597048 -0.1901967 0.6496638 0.710712 0.2698621 0.6070864 0.4707813 0.6401649 2.85714e-4 0.3455424 -0.938403 0.7267503 0.6551872 0.2063096 -0.06298667 0.9315873 0.358019 0.6609706 0.7441285 -0.09690523 0.6920863 -0.4465316 0.5671208 0.8189865 0.5280702 0.2245057 -2.91149e-4 -0.3396441 0.9405539 -3.18165e-4 -0.3432188 0.9392555 0.9171191 0.37401 0.1378734 0.9196102 0.367832 0.1379007 -0.9292561 0.3416295 -0.1406148 0.7480775 -0.03658628 -0.6626021 0.9684202 0.2418553 0.0605669 0.7186698 0.6548697 0.233793 0.4236478 -0.6934887 -0.5827487 0.002703249 0.3362014 -0.9417864 -0.4825999 -0.5226559 -0.7028003 -0.02513718 0.9418765 0.3350177 0.02160835 0.9423912 0.3338142 -0.9187878 -0.08297395 -0.385933 0.177212 0.9256727 0.3342543 0.8392983 -0.265219 -0.4745916 0.1836536 0.9236837 0.3362735 -0.3668468 0.733251 0.5725088 -0.3595316 -0.003289401 -0.9331271 0.2472441 0.7944247 0.554761 -0.2109953 0.9163672 0.3402236 -0.6315064 -0.0526275 -0.7735826 -0.4152611 0.851553 0.3200246 0.1215034 -0.47768 0.8700913 0.06532526 0.9378675 0.3407887 0.05858886 0.9370597 0.3442186 0.351534 0.7115603 0.6083632 0.6086157 0.7419576 0.2812222 -0.3976193 0.5570924 0.7290727 0.02385312 -0.6500688 -0.7595009 0.01189821 0.9348959 0.3547226 0.9802365 -0.01989167 0.196827 -0.5548696 -0.7170724 0.4218139 0.4109567 0.4086397 0.8149406 -0.3213402 0.3532941 0.878592 -0.0487889 -0.9383542 -0.342215 -0.1072677 0.9348042 0.3385778 -0.0943486 0.9338194 0.3450796 -0.21085 0.943152 0.2569175 0.5432389 -0.2073969 -0.8135589 -2.26557e-6 -0.9396931 -0.3420188 -0.1923047 0.9218261 0.3365349 -0.8842356 0.4642049 0.05139279 1.81714e-6 -0.9396916 -0.3420226 0.3222867 0.8903546 0.3215588 0.08397382 -0.4129976 0.9068524 0.159459 -0.9280246 -0.3366649 0.3697847 0.8713215 0.3225804 -0.5469553 -0.2793255 0.7891876 0.5072754 0.8130311 0.2857485 0.7878798 0.615826 -0.001927852 -0.03513002 -0.3441325 0.9382637 -2.93748e-5 -0.9397001 -0.3419996 -0.03383678 0.3285583 -0.9438774 0.6028015 0.7453995 0.2846223 0.2568617 -0.8578667 0.4450696 -0.8754072 0.3277081 0.3553444 0.2910038 0.3354746 -0.8959763 -0.4097611 0.7776331 0.4768466 0.7314705 0.6414967 0.2311554 -0.1429268 0.6432249 0.7522193 -4.11447e-7 0.9396926 0.34202 -0.4247337 -0.3018194 0.8535258 -8.116e-4 0.3452098 -0.9385252 -0.9201079 0.1286716 -0.3699257 0.005307495 0.9401286 0.3407785 0.5926444 -0.199617 0.7803369 -0.2137231 0.7433385 -0.6338536 0.5844975 -0.2646099 0.767036 -0.7903409 0.2061137 -0.5769563 0.8264489 0.5241696 0.2054958 0.4453471 0.8161195 -0.3682594 0.1563137 0.03318589 -0.9871498 -0.5409956 0.3194553 -0.7779923 0.8853708 0.4397712 0.1507308 0.954773 0.2759131 0.1108173 0.9638028 0.2499748 0.09271931 -7.04086e-4 -0.9396871 -0.3420346 0.04753798 -0.9777117 -0.2044993 0.03042113 0.9050997 0.4241099 -0.8116328 -0.07898426 -0.5788038 0.7759445 -0.02671796 -0.6302348 0.1982365 0.06643128 -0.9779004 -0.2072805 0.7120722 0.6708114 -0.8648682 0.4555045 0.2109943 0.9952988 0.08885616 0.03853553 -0.5207901 0.3323848 -0.7863194 0.004254877 -0.9133238 -0.407212 -0.4676321 0.05162757 -0.8824143 -0.533685 -0.8268032 0.1776982 0.9922647 -0.1175769 -0.03983342 0.9964551 -0.07866996 -0.02980142 -0.2531539 -0.9519239 -0.1724933 -0.4867735 -0.82086 -0.2987313 0.2376447 0.6555624 -0.7167726 0.4617338 0.392256 -0.7955734 -0.006608188 0.3413627 -0.9399085 0.9572377 -0.2751069 -0.08951163 -0.08638972 0.9791281 0.1839703 -1.0181e-6 -0.9396927 -0.3420197 -2.07642e-7 0.9396927 0.3420202 -0.5898702 -0.6012016 0.5390825 -0.08488386 -0.9589013 -0.2707453 0.8088888 0.0679593 -0.584021 0.9559538 -0.2798407 -0.08855265 -0.1261947 -0.3203131 0.9388686 0.451375 0.1550436 0.8787617 0.8907694 -0.4253119 -0.1601236 0.7832587 -0.5906562 -0.1939877 0.4811424 0.7865772 -0.3870379 0.8751515 -0.4603557 -0.1489378 -0.5967468 -0.7762291 0.2033762 -0.4478442 0.2832069 0.8480738 0.1124217 -0.7290305 -0.6751857 0.7395008 0.4813167 -0.4706091 0.7961084 -0.5681068 -0.2084852 0.001182734 0.330508 -0.9438025 -0.8062502 0.2134213 -0.5517354 -0.1736623 0.6130796 -0.7706975 -0.5221924 -0.8477827 -0.09262621 -0.4538835 -0.7452052 -0.4885272 0.6911016 -0.6890524 -0.2181407 -0.2585213 0.6202765 0.7405564 0.6413151 -0.7215641 -0.2608836 0.5198554 0.2685104 -0.8109579 -0.4264048 0.5650789 -0.7063037 -0.2410706 0.5364152 0.8087915 0.010396 -0.9736396 -0.2278553 -3.23897e-6 -0.9396938 -0.3420168 0.5163806 -0.8058851 -0.2896555 -0.1148614 0.7211502 0.6831906 0.5887125 -0.7730991 -0.2360835 -0.07140791 -0.8964062 0.4374434 -0.2014642 -0.3268393 0.9233571 -0.5355269 -0.2808424 0.7964538 -0.1647076 0.9688557 0.1849051 0.6005696 -0.2761493 0.7503718 -0.3244985 -0.02319586 0.9456017 0.426025 0.302769 -0.8525454 0.8612703 0.4932455 -0.122157 0.4151551 -0.4405173 -0.7959841 0.129481 0.9670192 0.2193366 0 -0.9396926 -0.3420204 -0.7918102 0.3897716 0.4702285 0.3125281 -0.8925584 -0.3250628 -0.2288572 0.9614917 -0.1521785 -0.7621317 -0.2809054 0.5833072 4.08978e-6 -0.9396913 -0.342024 -0.3107816 -0.9172842 -0.2490067 0.4542408 -0.8574125 -0.2418867 -8.72964e-6 0.3421006 -0.9396634 0.1361091 -0.57796 -0.8046345 0.3965007 -0.8635946 -0.3114348 0.02897369 -0.9177674 -0.3960598 0.59854 -0.7957683 0.09221088 -0.3483268 0.3070074 -0.885672 -0.4436706 0.3976625 0.8031319 -0.5189853 -0.130474 0.8447667 0.04165881 0.7357447 0.6759765 -0.5837196 -0.624653 0.5187292 -0.01356941 0.9403933 0.3398182 -0.480313 -0.7340171 -0.4801232 -0.007480502 0.9405409 0.3395981 0.9902908 -0.04557019 0.13133 -0.2404864 -0.7612003 0.6022794 0.1047061 -0.2861889 0.9524351 -0.4255304 0.8934641 0.143686 0.736006 0.6562722 -0.1661384 0.07669603 0.8383736 -0.5396735 -0.2052658 0.3367494 -0.9189483 0.7286492 -0.1117929 0.6757015 -0.5534665 -0.7982397 -0.2376725 0.723633 0.6839229 0.09276133 -0.5863406 0.7781113 -0.2252721 -0.5019605 -0.8166534 -0.2848035 -0.3266875 -0.6744729 -0.6620889 0.01784348 0.2585157 -0.9658422 -0.4124698 -0.8895533 -0.1963764 -1.60727e-5 8.31223e-4 -0.9999997 -0.3165425 -0.4849647 -0.8152363 -0.001561582 -0.8733987 -0.4870033 0.6990174 -0.699134 -0.1502879 -0.9097715 -0.3974072 -0.1199309 -0.9054043 -0.4087277 -0.114825 -0.8500905 -0.3066757 0.4281311 2.78068e-7 0.9396926 0.3420203 -0.9590746 -0.2501155 -0.1327338 -0.8167553 -0.5302181 -0.227551 0.8253028 -0.1601824 0.541495 -0.480725 -0.8172896 0.3177124 -0.6537872 0.2388972 -0.7179765 0.7921124 0.3717339 0.4841197 -0.006629288 0.3417527 -0.9397665 -0.8131354 -0.1887539 0.5506204 -0.7232614 -0.6664847 -0.1808065 -0.6736795 -0.693825 -0.2544854 -0.3833308 0.6224265 -0.6823802 0.005193948 0.7115221 0.7026445 -0.01887995 0.9704604 0.2405204 -0.968631 -0.1536625 0.1952992 0.7064246 0.1900124 -0.6818061 9.82591e-4 0.8446139 -0.5353751 0.1053067 0.2681837 0.9575949 0.04752266 -0.9378707 -0.3437154 -0.5627418 0.6346066 -0.5297132 -0.2203674 -0.2426889 0.9447435 0.03079617 0.9822603 0.1849768 -0.966691 -0.2356355 -0.09992158 -0.4479784 0.2137741 -0.8681106 0.4601594 0.1062358 0.8814575 0.6466837 -0.2666333 0.7146377 0.6939677 0.07676434 -0.7159022 -0.2458288 -0.8870984 -0.3906719 -0.9875071 -0.1524487 -0.03986281 -0.1090055 -0.8120297 -0.573346 -0.9963299 -0.07946002 -0.03182762 -0.3044384 -0.02750879 0.9521348 -0.1753199 0.8813252 0.4387812 0.5690441 0.772166 0.2827517 -0.9994849 0.0202887 0.0248667 -0.9591262 0.2613834 0.1084235 -0.9662663 0.2405017 0.09213173 -0.5465139 0.785754 0.2896777 -9.04968e-7 -0.9396929 -0.3420193 -0.002651035 0.5603969 -0.82822 0.1671252 0.6300257 0.7583778 0.8143912 0.4630362 -0.3498061 -0.9955808 0.08986681 0.02725565 -0.06693524 0.1152554 0.9910781 -0.1524468 0.6976094 0.7000722 -0.07203406 0.9970997 0.0245586 0.003064692 -0.006821811 -0.9999721 0.3132412 0.8916531 0.3268558 0.6723157 0.5997446 0.433933 -0.2067615 0.7417897 0.6379638 0.4065163 -0.8084989 0.4255281 0.3723769 0.3890838 -0.8425849 0.3131229 0.7882221 -0.5297736 0.4420348 0.836862 -0.3229044 -0.1409166 0.9524086 0.2702965 0.03844451 0.9734117 0.2258137 -0.9865799 0.07431679 0.1453862 0.003636896 -0.002372145 -0.9999905 0.9170772 0.1625484 0.3640708 -0.002517461 -0.3737642 0.9275204 0.8110305 -0.2833359 0.5118109 -0.001256108 5.05025e-4 -0.9999991 0.001348972 0.001514315 -0.9999979 -0.4104741 -0.0142917 -0.9117603 0.9977502 0.0257892 -0.06188154 0.006912887 0.00209403 -0.999974 0.3463392 0.8862307 0.3076431 -0.3218957 -0.2698662 0.9074996 -0.3718897 -0.6228743 0.6882774 5.04941e-7 -0.9396924 -0.3420205 0.7755445 -0.2630828 -0.5738625 0.121819 0.7067121 -0.6969348 -7.94063e-4 0.001158893 -0.999999 0.9621394 -0.1921328 0.1933203 0.7194392 -0.4618283 -0.5187697 0.5035793 -0.857356 -0.1065297 0.3437213 0.8612673 0.3742651 -0.902072 0.4312539 0.01691663 -1.21328e-4 -0.3423662 0.9395666 0.158833 -0.338911 0.9273141 0.6013424 -0.5089315 -0.6159352 0.9668053 -0.140863 0.2131788 -0.02166444 0.009863078 -0.9997166 0.8441019 -0.4667854 -0.2638246 -0.9453855 0.3028435 -0.1205488 0.06945264 0.8618783 0.5023366 0.5007476 0.04400891 -0.8644739 -0.6287565 0.2477993 0.7370622 0.9105645 -0.1166634 0.3965627 0.9789955 0.2038816 -5.24519e-5 0.9711076 0.2386261 -0.002771198 -0.7098643 -0.7042814 -0.008970379 -0.4873395 0.8732045 0.003770232 0.8977711 -0.345098 0.2737051 0.9992889 0.03770136 -1.63185e-4 0.9985826 0.05320298 -0.001474857 -3.07346e-7 0.9396926 0.3420202 0.008981645 -0.9372351 -0.3485825 -0.84397 0.2415704 -0.4789139 -7.05312e-5 -0.9396991 -0.3420022 0.1580373 0.3331475 -0.9295359 -0.9705873 0.2407454 -0.001391351 -0.9622288 0.2722253 -0.003046333 -0.1203603 0.9376285 -0.3261384 0.2267601 0.8656531 0.4463458 -0.9962162 0.08690071 -0.001200199 -0.9935004 0.1137915 -0.00290215 -0.6083957 -0.4905462 0.6238742 0.4313765 -0.07549816 -0.8990074 0.02977305 0.9747552 0.2212821 -0.6474547 0.4171313 -0.6378118 0.6049396 -0.5610438 -0.5650467 -0.9964087 -0.08461636 -0.003131389 -0.9959138 -0.09023779 -0.003597259 0.01489448 0.4253339 0.904914 0.8370757 0.220762 0.5005682 -1.54744e-6 -0.9396924 -0.3420208 -0.9062486 -0.4227319 -0.003360152 -0.9174594 -0.3978244 -0.00205481 -0.9504684 -0.310796 -0.003933787 0.5883521 -0.5513674 -0.5914692 0.678073 0.08079618 -0.7305402 0.5260818 -0.2940418 0.7979832 -0.1713825 0.5648122 0.8072269 1.84645e-5 -0.9396987 -0.3420035 9.74858e-6 -0.9396929 -0.3420192 -0.9728251 -0.231541 2.11986e-4 -0.8404887 -0.5418276 -0.001238524 -0.7560619 -0.6535935 -0.03443902 0.5799503 0.602507 0.5483093 0.4760534 0.2957726 -0.8281858 -6.26251e-6 -0.939689 -0.3420302 -0.7220698 -0.6918107 -0.003633439 -0.2380905 -0.5217338 -0.8192111 -0.8445454 -0.5354835 -6.53419e-4 -0.8531719 -0.08252924 0.5150598 -0.02252018 0.9944214 0.1030476 0.9879488 0.05926531 -0.1429846 -0.6880004 -0.72571 5.29121e-4 0.3719556 -0.3402602 0.8636389 0.2000343 0.41514 -0.8874937 -0.5218315 -0.8530477 -0.001283049 0.004185855 -0.3550584 0.9348347 0.8071244 -0.0525819 -0.5880352 -0.517031 -0.8559643 -0.002008497 -0.2322865 -0.7575477 0.6100527 0.2733364 0.6954886 -0.6645171 -0.8598467 0.190508 -0.4736776 0.7335127 0.6725991 0.09782433 -0.3383663 -0.9409999 -0.005226731 -0.3219071 0.8891439 0.3252677 0.6330962 0.7617651 0.1374886 -0.7828806 -0.1105532 0.6122711 0.2698717 0.7721684 0.5752609 -0.4022058 0.9081957 0.1158064 0.002265036 -0.9381402 -0.346248 0.7975601 -0.6032303 -0.003318786 0.4507286 0.8792283 0.154277 -0.2847648 -0.9585972 -6.78054e-4 0.02905839 0.8888793 0.457219 0.1224026 -0.9394162 0.3201793 -0.7288493 -0.2240548 0.6469761 0.05763167 -0.9983224 -0.005567371 -0.2163027 0.9453803 -0.2438629 3.46191e-7 -0.9396924 -0.3420205 0.5325886 0.5401607 0.6515949 -0.09990447 -0.9949969 -6.13301e-4 0.5126796 -0.7001383 0.4969567 -0.08114939 -0.9966976 -0.002950489 0.3300771 -0.5269533 0.7831789 0.2182744 0.9721572 0.08524537 0.2701263 -0.9628133 -0.00473845 0.2182404 -0.9758931 -0.001959621 0.003884553 0.759162 0.6508901 0.9293998 -0.3434796 0.135047 -0.03432452 -0.3443593 0.9382102 0.1269225 -0.9919103 -0.002180397 -0.4700829 0.3565766 0.8073879 0.4571659 -0.8893726 -0.003957688 0.03510314 0.499002 0.8658896 0.3623436 -0.9320446 1.88656e-5 4.48132e-7 0.9396928 0.3420198 -0.1478831 0.9645919 0.2183873 0.09943306 -0.8086442 0.5798342 0.5187377 -0.1196876 0.8465141 -0.336114 -0.7683522 -0.5446672 0 -0.9396926 -0.3420201 0.5373266 -0.8433742 -2.84161e-4 0.7206187 -0.1077792 0.6849032 -0.2721413 -0.2054962 -0.9400587 -0.5088163 0.8591486 0.05449283 -0.7379173 -0.6368061 0.2235082 0.630753 -0.7759703 -0.004542768 0.6670939 -0.7449716 -0.001711428 0.1649275 -0.7673783 -0.6196204 9.66559e-4 0.9438247 0.3304449 -0.3029788 0.8002241 -0.5175377 0.645829 0.6979103 0.309558 0.7429538 -0.6693319 -0.00379312 -0.752179 0.6562314 0.05989295 -0.6545183 -0.6386941 0.4045686 0.0190218 0.9407274 0.33863 -0.1771417 -0.8469313 0.5013266 0.8575504 -0.5143731 -0.005262851 -0.1836413 0.3481291 -0.9192835 -0.9080781 0.162607 -0.3859444 8.19103e-6 -0.939691 -0.3420247 0.7948195 -0.6068458 -2.0021e-4 0.9444239 -0.3287046 -0.004102349 0.9039659 -0.4276043 -4.0487e-4 0.3724251 -0.5323107 0.7602269 -0.9119737 -0.3143127 -0.2636502 0.3636245 -0.8679072 -0.3383994 0.1295824 0.8469049 0.5157136 0.9590494 -0.2832365 -0.001148998 0.507418 0.2767566 -0.816047 0.2477641 -0.1356314 0.9592795 0.08307236 -0.1845309 -0.9793097 0.9193713 0.1731405 0.3532403 -0.04915678 0.9374327 -0.3446792 0.9834075 -0.1812747 -0.007007241 0 0.9396923 0.3420211 0.9924205 -0.1228592 -0.002662718 0.5126024 -0.2420277 0.8238091 0.880501 -0.2592694 0.3968595 -0.5209888 0.3238743 -0.7897316 0.5703305 -0.03771299 -0.8205491 0.4589151 -0.08008384 0.8848635 0.7144742 -0.5912461 0.3741051 -0.7314491 0.6818904 -0.002759516 0.8967285 0.442572 0.002819955 -1.97913e-6 -0.9396932 -0.3420185 -0.03032255 -0.9431257 -0.3310507 -0.9073066 0.1889242 -0.3756359 0.8480799 0.5298534 -0.003983259 0.001795768 0.770834 0.6370337 0.5375787 0.3487581 -0.7677088 0.4895838 -0.4208087 -0.7636935 -0.1147118 0.8540449 0.5073938 0.6513841 0.7587305 -0.005185842 0.1591098 -0.9665384 0.2012152 0.01238507 -0.941469 -0.3368722 -0.2654289 0.3278841 0.906664 0.7181573 -0.6534148 -0.2393726 0.2322686 -0.8989245 -0.3714647 0.7451606 0.6668846 -8.88047e-4 -0.2592048 0.02319121 -0.9655439 0.5830265 0.8124529 -5.32579e-4 -0.7878525 0.5582692 -0.2600461 0.5342295 0.8453249 0.004954397 0.6693462 -0.4581032 0.5849077 -0.03879302 0.9961671 0.07839792 -0.7272912 -0.5634222 -0.3919221 0.3258146 0.5212089 -0.7887878 -0.3084174 0.8205453 0.4812321 0.09923946 0.7535929 0.6498072 0.8427488 -0.2656819 0.4681749 0.3408094 0.9401318 0.001067936 -0.1084145 0.94927 -0.2951825 -0.1565594 0.7869173 -0.5968673 0.7054682 0.1407628 0.6946225 -0.02666765 0.2874554 -0.9574227 -1.53568e-6 -0.9396924 -0.3420205 -0.2965397 -0.2046794 -0.9328292 -0.381186 0.8882741 -0.2562547 0.447733 0.7344805 0.509974 -0.9747605 0.05645453 -0.2159972 -0.1017509 0.8765658 0.4704033 0.813683 0.5466241 0.1977931 -0.9282565 0.3490401 0.1284943 0.05580049 -0.6932597 -0.7185245 2.94726e-6 -0.939693 -0.342019 -0.8583284 -0.4986857 0.1207677 0.2729045 -0.8987107 -0.3432816 0.5145729 -0.2541794 0.8189064 0.2587028 -0.6282061 0.7337779 -0.09291487 0.5172306 -0.8507875 0.5369333 -0.751932 0.3824932 -0.4356937 -0.02737146 -0.8996787 -0.2564277 0.7373689 0.6249256 0.2472628 -0.4116771 0.8771449 -0.202095 -0.1975263 0.9592398 -0.5296723 -0.4939305 0.6895505 -0.7926059 0.2712352 0.5460836 0.9036591 0.1576967 -0.3981606 -0.5710303 0.5323732 0.6249027 0.0110954 -0.03155559 0.9994405 0.9147551 -0.3795022 0.1385682 -4.61579e-5 -0.9396904 -0.3420264 0.5502122 0.2940877 0.7815234 -0.2672775 0.9584731 0.09945899 -0.9987391 0.01905345 -0.04644596 -0.2254325 0.8163886 0.5316859 0.795476 0.5854209 -0.1565257 -0.2965045 -0.1379674 -0.9450132 0.228603 -0.9568321 -0.1794802 0.5671761 0.6961794 0.4400519 -0.03902089 0.9830538 -0.1791164 -0.7087135 -0.08254253 0.7006511 0.8152118 -0.2807623 0.5065594 0.6842233 0.4191087 -0.5968135 0.9097193 -0.1354521 -0.3925092 0.9419217 0.1762915 -0.2858406 -0.5147068 0.7927991 -0.3264147 0.4097949 0.5025465 0.7612589 4.71132e-4 0.2221923 -0.9750027 0.4052282 -0.0985555 0.9088878 -9.63505e-4 -0.9391621 -0.343473 0.1942211 0.0317378 -0.9804443 3.89852e-4 0.9406594 0.3393521 -0.5400141 0.4541171 0.7086343 -0.1989028 -0.3265358 0.9240195 0.101859 -0.5220137 -0.8468332 0.4878746 -0.8720364 0.0391277 -0.001104056 0.338983 -0.9407919 0.3593226 -0.1317339 -0.9238687 -0.8786345 -0.437686 0.1908724 0.6744976 -0.6730214 0.3034716 0.3159742 -0.8246504 0.469161 -0.7902462 0.5999588 -0.1247413 -5.05934e-6 -0.9396894 -0.3420291 0.5142163 0.8558955 0.05499601 -0.5554836 0.6308455 0.5417305 -0.6418363 -0.7210071 -0.2611419 -0.7468962 0.248461 -0.6167764 -4.33301e-4 0.3443917 -0.9388261 -0.687658 0.3346682 -0.6443009 0.1519077 0.4147533 0.8971642 -0.1098713 -0.8378055 -0.5347995 0.259384 0.2425364 -0.9348241 -0.4365648 -0.8217368 0.3662785 -0.1555026 -0.6159094 0.7723176 -0.06624299 -0.9374513 -0.3417558 0.941953 -0.1222236 0.3127076 -0.9926827 0.004205584 -0.1206783 0.3997913 -0.2976657 0.8669269 -0.002300381 -0.939308 -0.3430673 -0.09086394 -0.983291 -0.1577422 -0.9198092 -0.1125251 0.3758847 0.1735817 -0.7740353 -0.6088832 0.07067745 0.6106722 0.7887231 0.1785176 0.8876466 0.4245174 0.6677218 0.666113 -0.3323269 -0.1723757 -0.7329146 -0.6581207 -0.7419974 0.6292126 0.2313683 -0.2488495 0.9109995 0.3288676 -0.1442075 0.06753516 0.9872402 0.4143851 -0.7869567 0.4571477 0.1760589 -0.1697929 0.9696255 -0.2725647 -0.3658959 -0.8898476 -0.4287518 -0.2725031 0.8613442 0.3703166 -0.2291128 -0.9002071 -0.3604121 0.3569226 -0.8618059 0.05354529 0.01144587 -0.9984999 -0.2799936 0.4581645 -0.8436165 0.02753943 0.1155675 0.9929178 0.8197519 0.5722109 -0.02411556 -0.002816796 0.3458345 -0.9382913 0.1149588 -0.8899376 0.4413564 -0.03250777 0.9680771 -0.2485356 0.2355188 0.8746735 0.4236476 -0.08290684 -0.1096619 -0.9905053 1.7479e-5 -0.9396945 -0.342015 0.2070579 0.5032172 -0.8389872 0.8236744 0.5564357 -0.1092686 -0.1741818 0.01482731 0.9846019 0.3526096 0.05314463 -0.9342601 -0.4136001 -0.5630767 -0.7154575 0.7791252 -0.3469479 -0.5221027 -8.6145e-7 -0.939693 -0.3420191 -0.03734612 -0.03232795 0.9987794 0.1573024 0.218734 0.963022 -0.3712779 0.5055882 0.7788025 -0.07328206 0.6668877 0.7415461 0.1638818 -0.3123756 0.9357159 0.7622857 -0.3279997 0.5579755 0.1066976 -0.800722 0.5894573 0.006828725 -0.3327402 0.9429937 0.3317244 -0.3572699 0.8731078 0.5074833 -0.5314922 0.6782159 -0.001621186 0.08255916 0.9965848 5.71526e-4 -0.333917 0.9426023 -0.4588729 -0.2735759 0.8453354 -0.7937878 0.1045525 0.5991407 0.5890105 0.7919278 0.1609874 -0.8429763 -0.5056247 -0.1836695 -0.03405493 -0.83037 0.5561709 -0.7385451 0.2735545 -0.6162136 -0.9980117 0.01051694 -0.06214493 0.1105552 0.8872233 -0.4478976 0.1282318 0.9745856 -0.1836833 -0.1879609 0.9141226 0.3592361 0.6321201 -0.5327964 -0.5626298 -0.3772603 0.4601701 0.8036903 0.03072327 0.5213404 0.8527955 0.2252066 -0.8943138 -0.3866328 -0.452414 0.1466279 0.8796715 -0.8574973 0.1680744 -0.4862607 0.9233096 -0.03655683 0.3823125 1.75969e-6 -0.9396932 -0.3420186 -0.2804396 -0.0573976 0.958154 0 0.9396927 0.34202 0.6672939 0.6137329 -0.4219607 -0.8163786 -0.3624225 -0.4496399 0.7795215 -0.5522472 -0.2955831 -0.4565719 -0.7561373 0.4688266 -0.0125941 0.3823763 0.9239209 -0.2622056 -0.6797738 -0.6849496 -0.07351201 0.01894211 -0.9971145 0.1079337 -0.8775796 -0.4671235 0.3768407 -0.2988108 0.8767572 -0.9067396 0.3738161 0.1951532 0.12067 -0.9596609 -0.2539482 -0.5740557 -0.3098159 0.7579408 -0.3969612 0.84866 0.3495684 0.4066103 -0.2560546 0.8769859 -0.2172245 -0.7527711 -0.621409 -0.923958 0.3805005 0.03899931 0.354264 0.8311849 -0.4285192 0.9773025 0.2018883 0.06419479 -0.7353064 -0.6764553 0.04162532 0.684509 0.7245345 0.08060586 -0.5091385 0.4490571 -0.7342518 -0.9855142 -0.008924841 0.1693583 -0.8413181 0.3410495 0.4193674 0.1639562 -0.7128754 -0.6818556 0.3385787 0.7386963 0.5828312 -0.1915668 0.9808894 -0.03402853 0.4691593 0.2815139 -0.8370422 -0.1627445 -0.582794 -0.7961567 0.4367182 -0.373607 0.8183489 0.1033406 -0.5642426 -0.8191161 -0.5014199 -0.005070328 0.8651892 0.9483704 -0.2969368 -0.1114547 0.2210177 -0.5209115 -0.8245013 -0.348877 0.9296932 -0.1181329 -0.5177133 -0.5180379 -0.6808889 -0.009145975 0.9349992 0.354532 0.03054392 -0.5097599 0.8597744 -0.1934844 0.7336209 -0.6514323 -0.6826425 -0.2590245 0.6833049 -0.0226466 0.9372048 0.3480438 0.9575651 0.1037974 -0.2688776 -0.1703519 -0.9296985 0.3265592 0.0268712 -0.9955764 0.09003037 -0.9692019 0.2439618 0.03362083 -0.6898735 -0.6986317 -0.1897056 -0.7836719 0.3994281 0.4757264 0.2673513 0.9172211 -0.2953449 -0.3187195 -0.8905781 -0.3244819 -0.7295964 0.6827124 -0.03991025 -0.5341987 0.8453475 0.004402518 0.957892 -0.03304022 -0.2852216 -0.7231042 0.4015488 -0.562031 -0.6734183 0.7308034 0.1115081 0.2368041 0.9133873 0.3311306 2.89794e-7 0.9396926 0.3420201 -0.9746567 0.02720749 0.222045 0.2212108 -0.9325381 0.2853741 -0.1027632 0.911935 0.3972584 0.1906476 -0.9815779 -0.01258176 -0.2115625 0.8574686 0.4690297 0.1125812 0.2591654 -0.9592491 0.1764808 -0.412111 -0.8938787 0.08311617 0.8521239 0.5166979 1.95816e-5 -0.9396978 -0.342006 -0.8523375 0.3959279 0.3417043 0.9442885 0.3261647 0.04399716 -0.005789399 0.9400222 0.341064 -0.2601246 0.3322175 -0.9066238 -0.005110621 -0.9399043 -0.3413995 0.1923722 -0.9400382 -0.2816402 -0.6680758 -0.6779609 -0.3066656 -0.2978106 0.07837903 0.951402 -0.5853311 -0.7774437 -0.2301497 -0.8856066 0.4396255 0.1497682 -0.09643661 -0.8962123 -0.4330165 0.2715358 -0.7404201 0.6148548 -0.4269747 -0.4240086 -0.7986922 -0.1194526 -0.6711592 -0.7316257 -0.2113021 0.5251548 0.8243567 0.5110027 -0.856441 0.07338333 0.269329 -0.9351735 0.2300269 -0.7613897 0.1134288 -0.6382943 -0.4964579 0.7027602 0.5095662 -0.001244246 0.3541027 -0.9352058 -0.6115591 0.3716256 -0.6984912 -0.06790977 -0.7458751 -0.662615 0.1825693 0.02812135 -0.9827908 0.0538786 0.3302267 0.9423627 0.1666868 0.8795704 0.4456137 0.9161865 0.3771854 0.1354017 -0.1690833 -0.223975 -0.9598156 -0.9882604 0.01710909 -0.1518183 -0.05775773 0.9540399 0.2940609 -0.778508 0.5401009 -0.3197128 -0.3371006 0.357514 0.870946 -0.4869819 0.7598909 0.4305978 -0.8233436 0.5283387 0.2072764 -0.294105 0.9255322 0.238521 2.05297e-5 -0.939685 -0.342041 -0.2139291 0.4983426 -0.8401719 -0.07589089 0.9144388 0.3975453 -0.001399219 -0.3488278 0.9371858 0.01858812 0.6781128 0.7347227 -0.7205308 0.3894033 -0.57376 -2.13674e-7 0.9396927 0.3420199 -0.7665436 0.5484231 -0.3341301 0.3175672 0.7874474 0.528278 0.5083307 0.7246524 0.465273 0.1794722 0.3887724 0.9036846 0.8119247 0.1622207 -0.5607697 0.5413529 0.8033369 -0.2481671 0.9846219 0.0913667 -0.1489023 -0.6673899 0.7400419 -0.08323925 -0.3666356 0.8358643 -0.4085453 -0.2037653 0.939655 0.2748238 -0.2471541 0.9372277 -0.2460067 -0.2562214 0.8987219 -0.3558785 -0.6771898 -0.2537683 -0.6906631 0.009771227 0.9511291 -0.3086391 0.6995676 -0.7144559 0.01257222 0.4902445 0.137795 0.8606235 0.296958 -0.2494016 0.9217454 0.08642554 0.9083596 -0.4091619 -0.3020066 -0.3206971 0.8977446 -0.2530375 0.8681065 0.4270401 0.3975577 0.8699912 -0.2916561 -0.006553351 0.9400221 0.3410504 0.3864184 0.7709759 -0.5062382 -0.6315625 0.6027618 -0.4876549 0.6389321 0.7084734 -0.2997186 0.6139759 0.6299906 -0.4755477 0.8088456 0.4572623 -0.3697026 0.2141054 0.7745476 0.5951763 0.7197284 -0.40307 -0.5652661 0.1162436 -0.9660518 -0.230719 -0.8544908 -0.06562423 0.5153046 -0.8720133 0.4842138 -0.07162249 0.5647564 0.7552536 -0.3326292 -0.5234701 -0.4188572 -0.7419823 0.786273 0.01906263 -0.6175852 -0.713674 0.6590802 0.2372402 0.06000518 -0.9880116 -0.1422407 0.02113407 -0.7037712 -0.7101123 0.915017 0.3798901 0.1357479 0.2884728 -0.9188667 -0.2691977 -0.7912082 -0.2190521 0.5709691 -0.007092058 -0.9393173 -0.3429763 -0.2395331 -0.3870732 0.8903921 0.4317972 -0.2176997 -0.8753045 0.3892223 -0.5417698 -0.7449777 0.2323185 -0.4233499 -0.8756729 0.4490413 0.838404 0.3089346 0.01074576 0.9397208 0.3417741 0.04885542 -0.8363569 -0.5460039 -0.04392468 -0.503014 0.8631613 6.35263e-7 0.9396928 0.3420199 -0.0518158 0.8875989 0.4576933 -0.1140595 -0.5595479 -0.820912 0.5361636 -0.6869277 -0.49057 0.4309682 0.8584545 -0.2780691 -0.3761773 -0.4599565 -0.80432 -0.3687857 -0.4506805 -0.8129479 -0.1207013 0.067106 -0.9904181 0.2744498 -0.3432064 0.8982687 -0.5855746 -0.2769097 -0.7618553 -0.5332779 -0.2370901 -0.8120363 -0.4848109 -0.8219462 -0.2989364 -0.7409964 -0.08412516 -0.6662186 0.09956145 0.8034578 0.5869779 0.01334935 -0.3088068 0.951031 -0.01965492 -0.4153775 0.9094368 -0.6554992 0.1784123 -0.7338187 -0.536178 -0.6361693 -0.554799 -0.3664812 -0.9294072 -0.04351681 -0.8636099 0.2207176 -0.4532787 0.04879945 0.3491463 -0.9357967 -0.935661 -0.08136916 0.3433912 -0.286651 0.3272544 -0.9004086 -0.8185368 -0.5723084 -0.04960572 -0.004153788 -0.3622506 0.9320714 -0.1549201 0.9271739 0.3410988 -0.57055 -0.8212517 0.004265427 -0.009381949 -0.354174 0.9351325 0.3487409 0.9202372 0.177604 -0.5381076 -0.2374957 0.808725 0.8227813 -0.3805704 0.4221341 0.6969535 0.6425516 0.3184072 -0.6284751 -0.2632363 -0.7319329 0.007315814 0.9354944 0.3532657 0.07265168 -0.8185498 -0.5698229 -0.5334285 -0.8096925 -0.2446469 -0.3265897 -0.3113918 0.8923981 -0.7216163 0.4694855 -0.5087764 0.1261669 0.9391256 0.3195699 -0.771994 -0.5965816 -0.2193529 0.5160478 0.332005 -0.7895994 -0.3668379 0.9302499 0.008069276 -0.1532579 -0.9881249 0.01101297 -0.6147768 -0.7840716 -0.08533048 1.91947e-6 -0.9396926 -0.3420205 -0.06088262 0.4348452 -0.8984448 0.4365447 -0.2982557 0.8488064 -0.3963211 -0.7246521 0.5637456 -0.545696 0.6265051 -0.5565134 0.9114264 -0.3919962 -0.1250636 0.5417242 -0.2913616 0.7884436 0.6654039 0.2004679 -0.7190621 -0.1730757 -0.8556011 0.4878438 0.7233197 0.1401323 0.6761447 -0.200001 0.9776821 0.06432235 -0.005649268 0.922557 0.3858193 -0.07190257 -0.9497137 -0.3047522 -1.2447e-5 -0.9396939 -0.3420166 -0.07891601 0.03446453 0.9962854 -0.640343 -0.3541583 0.6815664 0.5918225 -0.1999765 0.7808685 -0.04184573 -0.8604851 -0.5077543 0.13262 0.9734002 0.1868261 -0.9203032 0.1903976 0.3417465 -0.8352289 0.5075778 -0.2115596 0.9809141 -0.0360673 0.1910665 -0.9063313 -0.1173893 0.4059354 1.52769e-5 -0.9396958 -0.3420116 0.7249262 -0.6485381 -0.2321217 -0.412568 0.8574323 0.3075672 0.9822722 -0.1633541 -0.09196025 2.29626e-4 0.3657933 -0.9306961 -0.338027 -0.5588264 0.7572653 0.3332366 0.7780723 0.5325006 0.1913886 -0.5393443 -0.8200476 0.7531554 0.03587698 -0.6568636 -0.1262038 0.343026 -0.9308091 0.5689857 -0.7723056 -0.2824878 0.007167994 -0.9247009 -0.380627 0.6915925 -0.6259202 0.3604496 0.4815793 -0.4474028 0.7535995 -0.4181905 0.3057914 -0.855341 0.5232183 0.1727912 0.8344973 0.3756859 -0.4975973 -0.7818292 -0.3104817 -0.7018903 0.6410548 0.9389875 0.09108418 -0.3316715 -0.2440014 -0.3545683 0.902632 -0.1684076 -0.7216002 -0.6715148 -0.07311993 0.6401798 -0.7647373 0.6486839 -0.1519466 -0.7457356 -1.2762e-6 -0.9396923 -0.3420208 -0.7886556 0.244204 -0.5642577 -0.2697201 -0.5777571 -0.7703556 0.1240724 -0.1887599 0.9741539 0.8158727 0.01411205 0.5780592 -0.3335379 -0.01477658 -0.9426208 0.2204602 0.193856 0.9559378 -0.6662721 0.502125 -0.5513185 -0.4232156 0.6012716 -0.6777618 0.9504936 0.18656 0.2485104 0.005979418 0.9356532 0.3528704 -0.3050268 -0.7430921 0.595628 -0.3616037 0.7229982 -0.5886564 -0.2791715 -0.1842716 0.9423944 0.6136357 -0.7388859 -0.2783861 0.04824596 -0.4382192 -0.8975725 0.1722072 0.8308014 0.5292577 0.2106801 0.6746945 0.7073904 0.7339262 0.6218875 0.2731453 7.64831e-7 0.9396924 0.3420204 0.8345101 -0.5501018 0.03131955 0.03795588 0.9728133 -0.2284594 0.2786585 0.8633677 -0.4206494 0.2991839 0.8961919 0.327611 -0.002246677 -0.3358578 0.9419101 0.04880928 0.3491488 -0.9357954 0.2863107 0.8138465 -0.5056481 0.3324815 0.8503741 -0.4078236 -0.7359086 -0.2160622 -0.641682 -1.04388e-4 -0.3424056 0.9395523 -0.2476531 0.3230646 -0.9133987 -0.003038406 -0.9416534 -0.3365708 0.4114717 -0.4172716 0.8102934 -0.8006321 0.01355332 0.599003 0.7668699 0.4781054 -0.4281657 0.2247456 -0.005202591 -0.9744036 0.001026272 -0.9396426 -0.3421561 0.5315256 0.3395432 -0.7760096 -0.08740043 -0.8203716 -0.565112 -0.7044516 -0.4945145 -0.5091202 9.58936e-6 -0.9396958 -0.3420113 0.7359616 0.0699653 -0.6733984 0.5251829 0.04541039 -0.8497771 -0.8473629 0.5309988 -0.00405234 0.5152751 -0.1440138 -0.8448382 0.002972066 0.9394677 0.3426246 0.6796182 0.2465498 -0.6908924 0.5588645 -0.2555437 -0.7889029 0.07945549 0.05872285 0.9951073 0.001305699 -0.9389625 -0.3440169 -0.003456413 -0.3318989 0.9433086 0.8737517 0.342192 -0.3456336 -0.8065645 -0.1845861 -0.5615886 0.2898529 0.731967 0.6166115 0.9326224 -0.1077611 0.3443877 0.1201504 -0.1834577 -0.9756573 2.33842e-7 -0.9396924 -0.3420205 -8.76367e-7 -0.9396925 -0.3420205 -0.137162 -0.3679176 -0.9196864 1.12626e-5 0.9527133 0.303871 -0.1916284 0.6996364 0.6883222 -0.07355231 -0.8703222 -0.4869593 0.946009 0.3035711 0.1136295 -0.9928739 0.1098001 0.04631918 -0.2374797 -0.600475 0.7635661 -0.01430672 -0.9393293 -0.3427181 0.8326091 0.177132 0.5247726 -0.3260362 -0.728909 -0.6019902 -0.265916 -0.8272629 -0.4948987 -0.7631703 -0.5447863 0.3475328 -0.7923609 0.3825734 0.4751862 -0.791292 -0.1042628 -0.6024834 0.1593627 0.9699469 -0.1838658 -0.3881617 0.2704921 -0.881002 -0.03199005 0.87323 0.4862571 0.4157258 -0.2997367 0.8586793 -0.990792 0.08316123 0.1068427 -0.4990759 0.6621217 -0.5590331 0.04612654 0.9977509 0.04863619 -3.11646e-4 -0.254574 0.9670532 0.5007891 0.6416671 0.5809249 0.2449555 0.4754849 0.8449324 -0.5590841 0.6771329 0.4784517 0.9993624 0.0336405 -0.01196616 0.176411 -0.7813252 -0.5986738 0.168555 -0.8723635 -0.4588803 -0.9338957 0.3252074 -0.1485906 -0.2593836 -0.7583332 0.5980392 0.457008 -0.1830563 -0.8704218 -0.5765887 -0.08860868 -0.8122155 0.04706805 0.7393597 -0.6716635 -0.02179306 0.7910211 0.6114006 -0.02272129 -0.9394433 -0.3419505 -0.2451008 0.9323268 -0.2658801 0.6656568 -0.7071821 -0.2383158 0.01532465 0.9367535 0.3496541 -0.6556671 0.7355085 0.1706694 -0.4268776 0.565351 -0.7058001 0 -0.9396926 -0.34202 -0.3286646 0.905093 0.2697892 -0.4096383 0.3301991 -0.8503911 0.9988197 -0.0199393 0.04429095 0.4958333 -0.7664552 0.4082838 0.6683648 -0.7373172 -0.09824359 0.501586 0.6757659 0.5401408 0.8447519 0.4463902 -0.2951784 0.01295465 -0.92284 -0.3849657 -0.6345821 0.6807091 -0.3659791 0.5912375 0.7332546 -0.3358211 -0.4405471 0.6527745 -0.616282 -0.826152 -0.1962608 0.5281615 -0.6901229 -0.6719896 -0.2686274 -0.3395758 0.7940649 0.504132 -7.96983e-4 -0.9396386 -0.3421679 -0.002566814 -0.7043145 -0.7098835 -0.07302194 0.9321391 -0.3546611 -0.9234433 0.3607149 0.1309094 0.1104487 -0.8863462 -0.4496571 0.9604651 0.2105309 -0.1821635 0.4500635 0.7487882 0.486579 0.3147811 0.8932526 0.3209557 -0.9575666 -0.05633211 0.2826532 0.2421462 0.07454121 0.9673721 -0.07646161 0.2223553 0.9719628 0.8399888 -0.3717767 0.3952227 -0.7259204 0.4242483 -0.5413436 -0.1392174 0.9902456 -0.005683422 -0.8977645 -0.05406379 -0.4371453 0.1522283 0.7764406 -0.6115282 0.1588369 -0.3389046 0.9273157 0.00802797 -0.935765 -0.3525328 0.01374667 -0.7441412 0.667881 0.3687336 -0.879985 0.2994359 0.01502174 -0.9115306 -0.4109578 0 -0.9396929 -0.3420194 0.1872469 0.3189142 0.929103 0.5690414 -0.7882539 -0.2341962 -0.01270246 -0.3878973 0.921615 0.5526766 0.8323929 0.040874 0.6269499 -0.1748894 0.7591756 -0.9588697 0.1908718 0.2100877 0.6261888 0.7511393 -0.2089909 0.7679466 0.1673197 -0.6182736 -0.297387 -0.9220891 0.247614 0.08495008 0.9490497 0.3034604 0.7309176 0.2685889 -0.627391 0.6570505 0.5139741 0.5514665 0.5940461 0.6227087 0.5092575 -1.29092e-6 -0.9396927 -0.34202 -0.004595041 0.9997888 0.02002823 0.9799336 -0.04779583 0.1935088 -0.8302435 0.250273 0.4980554 0.146052 0.6156143 0.7743952 -0.7583013 -0.6127299 -0.2225785 0.605574 -0.7845796 -0.1330979 0.8573698 0.03371572 -0.5135955 0.03239321 0.9455608 0.3238294 0.3344528 0.9356693 -0.112536 0.04007017 0.3490613 -0.9362428 -0.5450216 0.8383446 -0.0113908 -0.3904649 0.8648431 0.3155686 -0.7769049 -0.6021751 0.1838591 0.001148223 0.3459784 -0.9382418 -0.1822221 -0.795419 -0.578017 0.003069579 0.9403827 0.3401045 -6.73256e-7 -0.939688 -0.342033 -0.2354442 -0.9604156 -0.1488892 -0.4149451 0.1131548 0.9027826 -0.04673647 -0.3388086 0.9396939 0.6449376 -0.4233379 0.6362707 -0.2653563 -0.9634619 0.03643065 2.95739e-5 -0.3419336 0.939724 -0.08936613 -0.06369918 0.9939597 0.06295591 -0.2605476 -0.9634063 -0.1605435 -0.2798913 0.9465129 0.3906786 -0.7452267 0.5403771 -0.9631242 -0.002901792 0.2690419 -0.2194952 0.002872765 -0.9756093 -0.2892475 -0.8166407 -0.4994335 0.9818355 0.1681 -0.08798474 0.5060818 -0.4376994 -0.7431692 -0.02739387 -0.8480807 -0.5291586 0.3599108 -0.02735292 0.9325857 -0.8499377 0.1063249 0.5160436 -0.9874413 -0.1328722 -0.08546692 0.02456486 -0.8577926 0.5134087 -0.5069305 0.7119985 0.4858803 -0.05422663 0.8877521 0.4571167 -0.923177 -0.07824599 0.3763268 2.15067e-6 -0.9396924 -0.3420205 -0.6715558 0.6958816 0.2544833 -0.7146129 0.6572087 0.2395939 0.4839384 -0.04367285 -0.8740116 -0.6610639 0.7394621 -0.1272411 -0.700453 -0.1774855 0.6912775 0.02509617 -0.9311857 -0.3636803 -0.976918 0.169599 -0.1298747 -0.9217214 -0.2930811 0.2540339 -0.3673628 0.8529049 0.3709418 0.4932161 0.3489843 -0.7968361 0.3556061 -0.2868404 0.8895319 -6.28705e-6 -0.9396896 -0.3420286 0.03356462 -0.7161304 -0.697159 0.07451671 0.6875975 0.7222582 1.07911e-4 0.9397102 0.3419716 0.5694866 0.6764072 0.4670744 0.5738047 -0.7572669 0.3119213 -0.3521804 0.02374809 -0.9356308 -0.7666176 0.6012634 0.2253436 -0.3912577 0.8651291 0.3137978 -0.579761 -0.698496 0.4195002 -0.001225352 0.3510915 -0.9363404 0.01567167 0.5535741 -0.8326525 -0.9678159 0.07361233 -0.2406526 0.6428269 0.7195315 0.2627698 -0.01872807 -0.3978852 0.9172441 -0.3045058 -0.08141678 0.9490245 -0.2396601 0.9412326 0.2380008 0.1843553 0.8552756 -0.4842692 -0.2666401 0.9627251 0.04542803 -0.168798 -0.5802166 -0.7967785 -0.006137728 0.09033423 0.9958925 -0.7357705 -0.3371798 -0.5873257 -0.5508475 -0.8154093 0.1779743 -0.6233301 0.2789784 -0.7305004 -0.8856881 -0.2383287 -0.3984419 -0.1248475 0.7639612 0.633069 -0.7470772 0.221221 -0.6268468 0.7043104 -0.6278544 0.3312788 0.7067652 0.126357 0.6960725 0.09448915 0.7961853 0.5976293 0.4291105 0.5914244 -0.6827016 -0.1598445 0.5351445 -0.8295 -0.2958332 0.1380215 -0.9452157 1.95319e-5 -0.9396877 -0.3420338 0.008442759 0.9397326 0.341806 0.8715495 -0.01910048 -0.4899355 -0.2653326 0.1414429 0.9537257 0.7344228 0.2706611 0.6223871 0.6794283 0.2788653 -0.6786835 0.004342794 0.9382419 0.3459526 -0.7272728 0.644829 0.2350955 0.273187 0.8345178 -0.4784861 1.68198e-7 0.9396925 0.3420206 0.4762179 -0.8160597 -0.3275104 0.6173804 0.2894287 -0.7314865 -0.2283221 -0.9153454 -0.3316804 -0.03874021 -0.8805314 0.472402 0.09534001 -0.2891452 0.9525257 0.06447511 -0.738592 -0.6710626 0.233803 0.9247229 -0.3003728 -0.986072 -0.02132809 0.1649463 0.05916917 0.9706426 0.233135 -0.08343791 0.9563092 0.2801976 -0.4456583 0.8420457 0.3038876 -0.5489923 -0.02691239 0.835394 0.9371808 0.3377856 -0.08713883 -0.00410062 0.3553926 -0.934708 -0.2824465 0.8397544 0.4637203 -0.141669 -0.9473301 0.2872207 -0.389351 -0.05524593 0.9194312 -0.6470917 0.4324319 0.6279132 -0.3619944 0.874146 0.3237726 -0.4818152 -0.3809028 0.789156 0.07552683 -0.7473008 0.6601797 0.7612116 0.4367603 -0.4793719 0.03318333 0.9090023 0.415468 -0.7759597 0.06182247 -0.6277456 -0.2266131 -0.3754611 0.8987078 0.1343024 -0.6312566 0.7638573 -3.13653e-4 -0.3451479 0.9385483 -0.3175328 0.7518257 0.5778677 -0.7175233 0.6880499 0.1083867 0.6206373 -0.6860663 0.3796343 0.4967518 0.341792 -0.7977567 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 11 3 12 4 13 4 14 4 15 5 16 5 17 5 18 6 19 6 20 6 21 7 22 7 23 7 24 8 25 8 26 8 27 9 28 9 29 9 30 10 31 10 32 10 33 11 34 11 35 11 36 12 37 12 38 12 31 13 30 13 39 13 40 14 41 14 42 14 43 15 44 15 45 15 46 16 47 16 48 16 27 17 49 17 28 17 50 18 51 18 52 18 53 19 54 19 55 19 56 20 57 20 58 20 59 21 60 21 61 21 62 22 63 22 64 22 65 23 66 23 67 23 68 24 69 24 70 24 71 25 72 25 73 25 60 26 59 26 74 26 75 27 76 27 77 27 78 28 79 28 80 28 81 29 82 29 83 29 84 30 85 30 86 30 87 31 60 31 74 31 88 32 89 32 90 32 91 33 92 33 93 33 94 34 95 34 96 34 77 35 97 35 98 35 99 36 100 36 101 36 60 37 87 37 102 37 103 38 104 38 105 38 106 39 107 39 108 39 102 40 87 40 109 40 110 41 111 41 112 41 113 42 114 42 115 42 116 43 117 43 118 43 35 44 119 44 120 44 109 45 32 45 102 45 121 46 122 46 123 46 102 47 32 47 31 47 120 48 124 48 125 48 126 49 127 49 128 49 129 50 130 50 131 50 132 51 133 51 134 51 135 52 136 52 137 52 138 53 139 53 140 53 61 54 141 54 142 54 143 55 144 55 145 55 146 56 147 56 148 56 148 57 149 57 150 57 151 58 152 58 153 58 154 59 51 59 50 59 155 60 156 60 157 60 158 61 159 61 160 61 161 62 162 62 163 62 164 63 165 63 166 63 167 64 168 64 169 64 170 65 171 65 172 65 173 66 174 66 175 66 176 67 47 67 46 67 61 68 142 68 59 68 177 69 178 69 179 69 180 70 181 70 182 70 183 71 184 71 185 71 186 72 187 72 188 72 189 73 190 73 191 73 192 74 193 74 194 74 195 75 196 75 197 75 198 76 199 76 200 76 201 77 202 77 203 77 204 78 205 78 206 78 83 79 207 79 208 79 6 80 8 80 209 80 210 81 211 81 212 81 213 82 214 82 110 82 31 83 39 83 215 83 107 84 106 84 216 84 217 85 218 85 219 85 220 86 221 86 222 86 223 87 224 87 225 87 226 88 227 88 228 88 229 89 230 89 231 89 24 90 232 90 233 90 234 91 235 91 236 91 215 92 141 92 237 92 0 93 238 93 239 93 215 94 240 94 141 94 241 95 242 95 243 95 244 96 245 96 246 96 112 97 247 97 248 97 249 98 250 98 251 98 252 99 253 99 254 99 255 100 256 100 257 100 258 101 259 101 260 101 261 102 262 102 263 102 264 103 265 103 266 103 267 104 268 104 269 104 270 105 199 105 271 105 141 106 61 106 237 106 272 107 273 107 237 107 237 108 273 108 31 108 274 109 275 109 276 109 237 110 31 110 215 110 277 111 20 111 278 111 60 112 102 112 279 112 279 113 102 113 280 113 281 114 282 114 283 114 284 115 285 115 286 115 287 116 288 116 289 116 290 117 291 117 292 117 293 118 294 118 295 118 227 119 296 119 297 119 298 120 138 120 194 120 299 121 300 121 301 121 302 122 303 122 304 122 305 123 306 123 307 123 308 124 309 124 310 124 311 125 312 125 313 125 314 126 315 126 316 126 52 127 317 127 318 127 319 128 320 128 283 128 321 129 322 129 323 129 324 130 325 130 293 130 324 131 293 131 295 131 287 132 326 132 288 132 327 133 276 133 328 133 329 134 330 134 331 134 112 135 332 135 96 135 333 136 334 136 16 136 33 137 335 137 336 137 337 138 338 138 339 138 111 139 340 139 341 139 203 140 342 140 343 140 344 141 345 141 176 141 346 142 347 142 330 142 348 143 349 143 350 143 351 144 352 144 353 144 354 145 355 145 356 145 20 146 357 146 358 146 359 147 360 147 361 147 362 148 363 148 364 148 365 149 366 149 367 149 23 150 368 150 369 150 370 151 371 151 372 151 373 152 371 152 374 152 375 153 376 153 377 153 378 154 379 154 380 154 381 155 382 155 383 155 284 156 384 156 385 156 386 157 387 157 388 157 216 158 264 158 389 158 390 159 6 159 391 159 173 160 392 160 174 160 393 161 394 161 395 161 396 162 397 162 249 162 398 163 393 163 399 163 400 164 401 164 402 164 403 165 404 165 405 165 406 166 407 166 408 166 409 167 410 167 411 167 412 168 413 168 414 168 415 169 416 169 417 169 418 170 419 170 420 170 421 171 422 171 423 171 424 172 425 172 426 172 427 173 428 173 429 173 430 174 431 174 432 174 433 175 434 175 435 175 436 176 437 176 438 176 439 177 20 177 440 177 441 178 232 178 442 178 443 179 444 179 95 179 445 180 111 180 110 180 112 181 186 181 188 181 446 182 447 182 448 182 294 183 449 183 450 183 451 184 225 184 224 184 162 185 452 185 453 185 454 186 455 186 456 186 457 187 454 187 458 187 294 188 293 188 449 188 459 189 460 189 461 189 462 190 463 190 464 190 465 191 466 191 467 191 468 192 469 192 470 192 471 193 472 193 125 193 473 194 282 194 474 194 475 195 273 195 476 195 477 196 478 196 479 196 480 197 369 197 481 197 482 198 483 198 484 198 485 199 486 199 487 199 488 200 489 200 490 200 54 201 491 201 492 201 234 202 376 202 235 202 493 203 494 203 495 203 496 204 497 204 498 204 185 205 499 205 500 205 501 206 502 206 151 206 282 207 473 207 283 207 503 208 504 208 466 208 505 209 506 209 507 209 508 210 509 210 510 210 511 211 512 211 513 211 514 212 515 212 65 212 33 213 516 213 335 213 319 214 473 214 517 214 293 215 518 215 441 215 519 216 520 216 521 216 310 217 522 217 523 217 524 218 525 218 526 218 527 219 528 219 529 219 530 220 396 220 531 220 532 221 446 221 533 221 534 222 535 222 536 222 449 223 515 223 537 223 537 224 515 224 538 224 537 225 538 225 449 225 539 226 540 226 541 226 542 227 543 227 486 227 539 228 541 228 544 228 433 229 230 229 99 229 529 230 528 230 140 230 545 231 546 231 547 231 227 232 548 232 296 232 549 233 550 233 551 233 450 234 449 234 538 234 552 235 553 235 554 235 555 236 227 236 556 236 557 237 224 237 223 237 558 238 559 238 560 238 561 239 562 239 563 239 564 240 565 240 566 240 567 241 568 241 569 241 570 242 569 242 571 242 129 243 131 243 176 243 550 244 549 244 572 244 573 245 574 245 575 245 576 246 577 246 571 246 441 247 198 247 578 247 579 248 580 248 581 248 184 249 582 249 499 249 583 250 584 250 585 250 586 251 587 251 588 251 577 252 570 252 571 252 0 253 2 253 238 253 589 254 590 254 165 254 591 255 150 255 251 255 592 256 593 256 594 256 211 257 96 257 212 257 68 258 595 258 108 258 596 259 258 259 597 259 325 260 21 260 598 260 599 261 519 261 521 261 600 262 601 262 602 262 603 263 604 263 605 263 606 264 597 264 258 264 309 265 607 265 522 265 608 266 609 266 610 266 159 267 292 267 291 267 345 268 611 268 612 268 171 269 613 269 614 269 452 270 615 270 453 270 616 271 617 271 618 271 393 272 395 272 619 272 52 273 620 273 621 273 622 274 623 274 509 274 170 275 263 275 171 275 16 276 624 276 625 276 626 277 627 277 628 277 629 278 465 278 630 278 631 279 632 279 241 279 580 280 633 280 606 280 634 281 466 281 635 281 636 282 112 282 248 282 637 283 638 283 639 283 269 284 640 284 144 284 641 285 642 285 643 285 644 286 490 286 645 286 567 287 569 287 570 287 249 288 149 288 401 288 646 289 268 289 267 289 249 290 647 290 372 290 648 291 587 291 361 291 577 292 576 292 594 292 577 293 594 293 321 293 649 294 85 294 254 294 650 295 651 295 510 295 652 296 653 296 654 296 191 297 655 297 261 297 656 298 657 298 658 298 85 299 24 299 252 299 581 300 580 300 659 300 441 301 442 301 198 301 660 302 533 302 661 302 138 303 140 303 528 303 420 304 662 304 21 304 659 305 580 305 606 305 663 306 664 306 415 306 608 307 610 307 665 307 117 308 666 308 667 308 668 309 669 309 670 309 258 310 596 310 671 310 672 311 548 311 673 311 674 312 675 312 676 312 20 313 19 313 440 313 677 314 678 314 679 314 680 315 137 315 136 315 681 316 682 316 554 316 41 317 683 317 684 317 685 318 686 318 128 318 633 319 597 319 606 319 687 320 688 320 689 320 674 321 690 321 691 321 671 322 321 322 594 322 424 323 692 323 425 323 64 324 658 324 693 324 596 325 321 325 671 325 331 326 694 326 695 326 101 327 249 327 397 327 696 328 697 328 698 328 376 329 699 329 700 329 79 330 701 330 80 330 702 331 703 331 704 331 705 332 706 332 707 332 579 333 581 333 708 333 709 334 710 334 708 334 708 335 710 335 579 335 711 336 119 336 712 336 713 337 714 337 715 337 716 338 717 338 63 338 718 339 719 339 655 339 104 340 720 340 422 340 721 341 722 341 723 341 0 342 239 342 35 342 724 343 725 343 726 343 175 344 174 344 727 344 728 345 590 345 638 345 568 346 567 346 710 346 729 347 730 347 589 347 731 348 732 348 733 348 734 349 713 349 735 349 736 350 737 350 445 350 738 351 169 351 739 351 568 352 710 352 709 352 38 353 740 353 133 353 7 354 741 354 742 354 743 355 707 355 744 355 745 356 746 356 747 356 748 357 749 357 750 357 264 358 266 358 751 358 162 359 453 359 163 359 752 360 753 360 754 360 755 361 756 361 301 361 757 362 758 362 132 362 754 363 55 363 759 363 760 364 761 364 762 364 253 365 763 365 764 365 765 366 766 366 661 366 767 367 768 367 769 367 509 368 329 368 770 368 771 369 128 369 772 369 773 370 437 370 436 370 567 371 774 371 710 371 775 372 776 372 777 372 297 373 551 373 572 373 778 374 779 374 780 374 781 375 782 375 783 375 784 376 108 376 107 376 771 377 785 377 128 377 577 378 132 378 134 378 753 379 311 379 754 379 192 380 786 380 787 380 627 381 788 381 789 381 790 382 791 382 792 382 200 383 793 383 494 383 565 384 794 384 566 384 795 385 796 385 797 385 772 386 128 386 798 386 798 387 128 387 686 387 799 388 800 388 801 388 755 389 311 389 753 389 323 390 757 390 577 390 802 391 803 391 804 391 433 392 805 392 230 392 806 393 616 393 618 393 639 394 807 394 808 394 193 395 809 395 810 395 301 396 756 396 798 396 301 397 798 397 299 397 700 398 699 398 236 398 811 399 409 399 411 399 812 400 813 400 814 400 301 401 311 401 755 401 815 402 816 402 817 402 489 403 818 403 490 403 345 404 344 404 819 404 238 405 820 405 821 405 173 406 175 406 822 406 347 407 823 407 824 407 825 408 826 408 827 408 675 409 828 409 829 409 299 410 798 410 830 410 364 411 831 411 832 411 833 412 537 412 293 412 830 413 798 413 686 413 834 414 835 414 836 414 837 415 549 415 838 415 839 416 785 416 771 416 495 417 494 417 793 417 840 418 841 418 711 418 842 419 843 419 844 419 845 420 846 420 839 420 847 421 342 421 848 421 839 422 846 422 849 422 850 423 851 423 852 423 853 424 854 424 72 424 616 425 855 425 617 425 728 426 166 426 590 426 856 427 344 427 176 427 839 428 849 428 785 428 857 429 858 429 394 429 859 430 860 430 861 430 862 431 863 431 864 431 277 432 599 432 865 432 866 433 867 433 868 433 125 434 472 434 869 434 308 435 310 435 523 435 101 436 727 436 870 436 4 437 871 437 5 437 862 438 846 438 863 438 872 439 873 439 874 439 863 440 846 440 845 440 875 441 46 441 48 441 259 442 876 442 260 442 441 443 140 443 139 443 877 444 27 444 29 444 864 445 863 445 878 445 864 446 878 446 879 446 855 447 880 447 881 447 322 448 52 448 318 448 882 449 883 449 884 449 885 450 884 450 752 450 886 451 887 451 773 451 888 452 889 452 890 452 891 453 892 453 893 453 281 454 474 454 282 454 579 455 894 455 580 455 895 456 896 456 897 456 883 457 882 457 879 457 883 458 879 458 878 458 898 459 507 459 899 459 875 460 207 460 900 460 271 461 25 461 24 461 315 462 901 462 653 462 884 463 885 463 882 463 487 464 902 464 485 464 794 465 903 465 44 465 904 466 905 466 906 466 752 467 754 467 885 467 907 468 908 468 806 468 909 469 910 469 354 469 911 470 912 470 913 470 914 471 849 471 846 471 915 472 916 472 739 472 254 473 253 473 481 473 917 474 918 474 919 474 920 475 921 475 922 475 923 476 924 476 925 476 926 477 647 477 927 477 912 478 911 478 928 478 929 479 930 479 931 479 628 480 932 480 626 480 157 481 230 481 933 481 934 482 850 482 852 482 935 483 936 483 937 483 938 484 939 484 348 484 384 485 940 485 941 485 176 486 942 486 129 486 629 487 598 487 537 487 943 488 928 488 338 488 944 489 945 489 946 489 924 490 947 490 93 490 948 491 949 491 950 491 951 492 952 492 562 492 911 493 913 493 953 493 486 494 543 494 954 494 955 495 609 495 956 495 957 496 805 496 433 496 355 497 958 497 959 497 934 498 342 498 960 498 687 499 961 499 962 499 963 500 964 500 717 500 965 501 966 501 913 501 966 502 953 502 913 502 376 503 967 503 377 503 40 504 42 504 968 504 893 505 969 505 970 505 610 506 971 506 932 506 679 507 947 507 924 507 972 508 973 508 974 508 975 509 587 509 976 509 977 510 625 510 978 510 479 511 94 511 211 511 253 512 764 512 481 512 979 513 20 513 358 513 980 514 981 514 982 514 983 515 984 515 985 515 986 516 78 516 80 516 987 517 744 517 988 517 692 518 989 518 990 518 991 519 74 519 992 519 993 520 341 520 340 520 984 521 983 521 994 521 467 522 937 522 936 522 590 523 807 523 639 523 836 524 444 524 443 524 45 525 995 525 765 525 996 526 994 526 997 526 998 527 376 527 999 527 1000 528 1001 528 1002 528 268 529 444 529 1003 529 6 530 1004 530 7 530 396 531 1005 531 397 531 79 532 1006 532 701 532 436 533 1007 533 1008 533 112 534 188 534 332 534 996 535 997 535 966 535 268 536 1003 536 1009 536 877 537 1010 537 27 537 1011 538 984 538 1012 538 996 539 966 539 965 539 269 540 1013 540 319 540 1014 541 1015 541 849 541 931 542 1016 542 678 542 1017 543 1018 543 1019 543 1020 544 1021 544 985 544 85 545 252 545 254 545 301 546 308 546 311 546 1022 547 1023 547 1024 547 746 548 854 548 853 548 747 549 746 549 1025 549 602 550 509 550 600 550 760 551 386 551 1026 551 1021 552 983 552 985 552 1027 553 431 553 1028 553 930 554 1029 554 1016 554 1020 555 1030 555 338 555 1031 556 1032 556 688 556 774 557 1033 557 1034 557 1035 558 12 558 14 558 881 559 203 559 305 559 338 560 1030 560 943 560 851 561 1036 561 1037 561 934 562 1038 562 1039 562 1040 563 1041 563 1042 563 31 564 475 564 102 564 1028 565 431 565 430 565 1043 566 667 566 135 566 1020 567 338 567 1021 567 1044 568 469 568 1045 568 789 569 681 569 554 569 1046 570 454 570 1047 570 1048 571 219 571 1049 571 112 572 111 572 341 572 384 573 941 573 385 573 1050 574 522 574 1051 574 2 575 1052 575 1053 575 1054 576 115 576 352 576 1055 577 435 577 434 577 1051 578 522 578 1012 578 1051 579 1012 579 1056 579 934 580 852 580 718 580 982 581 1057 581 382 581 1056 582 1012 582 996 582 828 583 1058 583 1059 583 984 584 994 584 996 584 254 585 481 585 369 585 1030 586 1060 586 686 586 984 587 996 587 1012 587 1061 588 994 588 983 588 359 589 1062 589 121 589 912 590 928 590 943 590 912 591 943 591 1063 591 1064 592 1065 592 1066 592 943 593 1067 593 1063 593 1068 594 355 594 955 594 1069 595 1045 595 1070 595 462 596 269 596 1071 596 1072 597 796 597 1073 597 312 598 1074 598 1075 598 1067 599 1076 599 1063 599 415 600 664 600 1077 600 1078 601 640 601 269 601 957 602 1079 602 1080 602 82 603 736 603 1081 603 1076 604 1082 604 1063 604 1083 605 767 605 437 605 1084 606 990 606 1085 606 1082 607 1076 607 1086 607 822 608 175 608 1087 608 319 609 33 609 213 609 639 610 808 610 398 610 1088 611 762 611 696 611 1089 612 1090 612 1075 612 1089 613 1075 613 1091 613 311 614 313 614 754 614 1092 615 124 615 120 615 570 616 1093 616 567 616 1091 617 1075 617 1074 617 1094 618 1095 618 1096 618 1091 619 1074 619 1050 619 1097 620 1098 620 1099 620 354 621 107 621 216 621 1050 622 1074 622 522 622 1100 623 938 623 1101 623 1102 624 1103 624 1104 624 1105 625 1106 625 1086 625 1086 626 1106 626 1107 626 1108 627 1109 627 855 627 916 628 1110 628 1111 628 1112 629 1113 629 1114 629 1115 630 914 630 846 630 1086 631 1107 631 1082 631 1116 632 1117 632 1118 632 476 633 946 633 945 633 1119 634 1120 634 1121 634 376 635 1122 635 1123 635 1106 636 1105 636 1124 636 389 637 264 637 1077 637 228 638 1125 638 1100 638 1106 639 1124 639 1126 639 1127 640 328 640 1128 640 1129 641 1066 641 1130 641 1124 642 1131 642 1126 642 736 643 445 643 1132 643 748 644 1133 644 749 644 1130 645 1066 645 1134 645 1135 646 176 646 875 646 1136 647 1137 647 1138 647 1139 648 832 648 428 648 1140 649 202 649 738 649 386 650 388 650 1026 650 1141 651 1139 651 427 651 1142 652 1143 652 995 652 269 653 81 653 83 653 1144 654 139 654 138 654 1145 655 664 655 1146 655 989 656 822 656 990 656 1147 657 351 657 353 657 373 658 1148 658 1054 658 1106 659 1149 659 1107 659 872 660 874 660 1150 660 1151 661 285 661 781 661 453 662 104 662 103 662 1120 663 505 663 1152 663 1153 664 1154 664 1155 664 376 665 615 665 452 665 917 666 1156 666 918 666 1157 667 1158 667 634 667 1159 668 802 668 252 668 1160 669 1161 669 1162 669 1161 670 1163 670 1164 670 204 671 527 671 529 671 622 672 509 672 1165 672 1166 673 677 673 901 673 986 674 616 674 806 674 89 675 1008 675 90 675 705 676 792 676 706 676 789 677 1167 677 1168 677 1169 678 1170 678 1171 678 249 679 1037 679 647 679 319 680 1013 680 1172 680 1173 681 729 681 1174 681 1175 682 1176 682 1177 682 1178 683 664 683 663 683 847 684 848 684 1179 684 1180 685 1181 685 1169 685 596 686 547 686 1182 686 1169 687 1181 687 1170 687 530 688 1183 688 1184 688 1185 689 1064 689 1129 689 1186 690 370 690 1187 690 1188 691 1189 691 894 691 1190 692 982 692 1191 692 334 693 1192 693 624 693 1087 694 155 694 326 694 664 695 1178 695 1193 695 1029 696 1194 696 1195 696 1196 697 1197 697 1198 697 34 698 611 698 35 698 1093 699 1199 699 567 699 265 700 1200 700 1201 700 387 701 146 701 388 701 1202 702 1203 702 1197 702 1100 703 1125 703 572 703 162 704 376 704 452 704 1202 705 1204 705 1203 705 636 706 143 706 112 706 670 707 1205 707 1206 707 436 708 1207 708 773 708 1050 709 1204 709 1091 709 1208 710 306 710 1209 710 133 711 683 711 41 711 137 712 1025 712 71 712 62 713 1210 713 63 713 1211 714 1212 714 1213 714 650 715 623 715 622 715 773 716 1207 716 886 716 1214 717 219 717 1215 717 729 718 394 718 730 718 332 719 1216 719 96 719 1217 720 983 720 1021 720 1178 721 1218 721 637 721 810 722 1219 722 1220 722 1221 723 760 723 762 723 39 724 97 724 215 724 1129 725 1064 725 1066 725 1204 726 1202 726 1091 726 103 727 105 727 1222 727 625 728 624 728 978 728 1094 729 1096 729 1223 729 797 730 1224 730 1225 730 1226 731 1080 731 1079 731 1227 732 229 732 1228 732 982 733 1229 733 1057 733 1149 734 1106 734 1230 734 990 735 822 735 1087 735 153 736 152 736 1231 736 161 737 163 737 1232 737 502 738 1233 738 152 738 707 739 706 739 1035 739 1197 740 1196 740 1202 740 1202 741 1196 741 1234 741 1220 742 844 742 843 742 204 743 441 743 172 743 1202 744 1234 744 1091 744 1091 745 1234 745 1089 745 1235 746 966 746 997 746 821 747 820 747 1236 747 113 748 115 748 1237 748 1238 749 73 749 116 749 1150 750 860 750 859 750 1106 751 1126 751 1239 751 1106 752 1239 752 1230 752 836 753 443 753 477 753 1230 754 1239 754 1162 754 1162 755 1239 755 1160 755 1240 756 1005 756 1241 756 1242 757 665 757 1243 757 157 758 156 758 1244 758 427 759 429 759 1245 759 156 760 1246 760 1244 760 906 761 603 761 895 761 1247 762 1148 762 373 762 25 763 271 763 1248 763 1249 764 507 764 898 764 879 765 1250 765 1251 765 300 766 985 766 984 766 356 767 107 767 354 767 1252 768 122 768 1253 768 856 769 176 769 1135 769 898 770 1254 770 1249 770 1255 771 1256 771 1257 771 210 772 1258 772 187 772 1253 773 122 773 121 773 577 774 134 774 1259 774 323 775 318 775 757 775 976 776 587 776 648 776 813 777 920 777 1260 777 1261 778 4 778 1207 778 1245 779 429 779 1262 779 659 780 1263 780 1264 780 274 781 1265 781 1266 781 1010 782 49 782 27 782 1161 783 1160 783 1163 783 1267 784 960 784 1036 784 1268 785 153 785 867 785 857 786 92 786 1269 786 1270 787 1271 787 195 787 873 788 1272 788 1273 788 1274 789 591 789 13 789 1181 790 1180 790 1275 790 1181 791 1275 791 1198 791 75 792 59 792 142 792 1198 793 1275 793 1196 793 1196 794 1275 794 1276 794 1015 795 1277 795 785 795 1278 796 655 796 719 796 1279 797 1280 797 126 797 1196 798 1276 798 1281 798 1196 799 1281 799 1234 799 1017 800 433 800 1018 800 1004 801 741 801 7 801 1214 802 1098 802 219 802 1282 803 676 803 430 803 73 804 743 804 116 804 1239 805 1283 805 1160 805 1160 806 1283 806 1284 806 269 807 144 807 143 807 944 808 1177 808 468 808 1160 809 1284 809 1163 809 1285 810 1286 810 750 810 704 811 703 811 1287 811 1177 812 1288 812 468 812 1163 813 1289 813 1164 813 866 814 1134 814 1268 814 785 815 126 815 128 815 1164 816 1289 816 1171 816 343 817 1290 817 203 817 1291 818 513 818 1292 818 1164 819 1171 819 1170 819 1293 820 1294 820 1188 820 964 821 1295 821 1059 821 1102 822 477 822 210 822 477 823 443 823 478 823 269 824 422 824 81 824 552 825 1183 825 1296 825 656 826 658 826 1297 826 1298 827 1098 827 1097 827 868 828 867 828 632 828 1225 829 1097 829 1118 829 1299 830 1300 830 1301 830 1146 831 1193 831 1302 831 1055 832 434 832 1303 832 1304 833 1305 833 1306 833 506 834 1307 834 507 834 1308 835 1309 835 1310 835 493 836 893 836 970 836 73 837 72 837 854 837 1311 838 654 838 1312 838 697 839 1313 839 1314 839 1206 840 1205 840 1315 840 10 841 1316 841 1317 841 1318 842 1046 842 1047 842 1242 843 1243 843 197 843 1187 844 1319 844 1186 844 810 845 1320 845 1321 845 1322 846 1323 846 363 846 1324 847 1325 847 1326 847 982 848 381 848 383 848 1205 849 1308 849 1315 849 498 850 902 850 496 850 327 851 1265 851 274 851 1327 852 1328 852 1329 852 940 853 688 853 941 853 690 854 675 854 691 854 539 855 1330 855 1327 855 1331 856 1332 856 642 856 1333 857 1102 857 967 857 1152 858 1249 858 1334 858 1335 859 954 859 543 859 1336 860 1337 860 759 860 1338 861 974 861 1064 861 315 862 653 862 652 862 551 863 224 863 1339 863 1132 864 1081 864 736 864 1340 865 1305 865 1304 865 1341 866 419 866 1110 866 10 867 1242 867 1316 867 41 868 684 868 180 868 1217 869 295 869 294 869 1342 870 1286 870 1285 870 112 871 96 871 268 871 500 872 574 872 573 872 1284 873 1283 873 1343 873 33 874 214 874 213 874 1344 875 80 875 1345 875 1284 876 1343 876 1163 876 312 877 1346 877 1347 877 1163 878 1343 878 1289 878 523 879 522 879 1074 879 1003 880 1348 880 1009 880 1349 881 1350 881 1351 881 1352 882 922 882 905 882 1171 883 1289 883 1353 883 499 884 582 884 574 884 1251 885 862 885 864 885 1171 886 1353 886 1169 886 1169 887 1353 887 1354 887 238 888 2 888 820 888 891 889 982 889 1355 889 98 890 1356 890 77 890 1169 891 1354 891 1180 891 690 892 674 892 926 892 881 893 305 893 855 893 43 894 1357 894 1358 894 1275 895 1180 895 1359 895 176 896 46 896 875 896 1360 897 1361 897 1362 897 1275 898 1359 898 1276 898 214 899 225 899 110 899 1363 900 56 900 58 900 1276 901 1359 901 1364 901 1276 902 1364 902 1281 902 1237 903 1054 903 560 903 41 904 180 904 42 904 1365 905 798 905 756 905 1101 906 1366 906 349 906 1043 907 117 907 667 907 668 908 1367 908 669 908 93 909 92 909 1368 909 1191 910 20 910 277 910 480 911 481 911 764 911 373 912 1054 912 351 912 420 913 1369 913 406 913 345 914 942 914 176 914 194 915 1370 915 298 915 919 916 1371 916 1372 916 1373 917 1374 917 778 917 814 918 1375 918 1376 918 760 919 1026 919 761 919 222 920 402 920 147 920 545 921 1377 921 546 921 1378 922 287 922 289 922 1368 923 92 923 857 923 235 924 376 924 1379 924 64 925 1380 925 658 925 741 926 931 926 742 926 766 927 1095 927 660 927 1381 928 325 928 598 928 1361 929 1382 929 1383 929 1146 930 664 930 1193 930 491 931 1346 931 1090 931 1373 932 634 932 1374 932 1384 933 1385 933 1246 933 1386 934 1387 934 975 934 910 935 1261 935 89 935 1388 936 87 936 991 936 470 937 1044 937 279 937 1141 938 1389 938 1139 938 1390 939 1391 939 1392 939 509 940 602 940 1393 940 1362 941 1009 941 1348 941 1141 942 362 942 1389 942 591 943 1394 943 150 943 1395 944 972 944 974 944 952 945 1396 945 562 945 1321 946 640 946 1397 946 1367 947 500 947 669 947 206 948 456 948 455 948 1384 949 1246 949 156 949 1283 950 1398 950 1343 950 1116 951 1399 951 1117 951 1400 952 693 952 658 952 1401 953 1192 953 334 953 1402 954 249 954 353 954 433 955 1403 955 1053 955 1343 956 1404 956 1289 956 1110 957 419 957 1405 957 899 958 1406 958 1407 958 1387 959 1408 959 975 959 1289 960 1404 960 1353 960 1409 961 999 961 376 961 1337 962 1410 962 1411 962 1412 963 1413 963 252 963 1414 964 838 964 939 964 475 965 470 965 279 965 1151 966 781 966 783 966 1180 967 1354 967 1415 967 1416 968 1079 968 435 968 1417 969 649 969 439 969 1180 970 1415 970 1359 970 964 971 963 971 1295 971 1418 972 1419 972 849 972 1359 973 1415 973 1420 973 354 974 216 974 909 974 1421 975 1005 975 1184 975 1359 976 1420 976 1364 976 517 977 268 977 646 977 134 978 41 978 40 978 1134 979 151 979 1268 979 927 980 1037 980 1422 980 630 981 465 981 467 981 1395 982 974 982 1338 982 155 983 1384 983 156 983 172 984 1423 984 170 984 1016 985 1029 985 1042 985 1226 986 1416 986 1424 986 1425 987 1426 987 1427 987 1428 988 899 988 1407 988 1343 989 1398 989 1404 989 142 990 141 990 75 990 1243 991 932 991 1429 991 210 992 332 992 1258 992 1430 993 679 993 1431 993 1104 994 1432 994 375 994 82 995 375 995 737 995 17 996 16 996 625 996 1101 997 349 997 57 997 248 998 1433 998 1434 998 1435 999 1237 999 559 999 825 1000 1436 1000 826 1000 1354 1001 1353 1001 1437 1001 465 1002 779 1002 635 1002 890 1003 262 1003 1219 1003 1354 1004 1437 1004 1415 1004 1438 1005 508 1005 662 1005 101 1006 870 1006 250 1006 246 1007 1036 1007 244 1007 967 1008 1102 1008 1104 1008 1383 1009 1439 1009 1362 1009 1225 1010 1440 1010 328 1010 1441 1011 1271 1011 1442 1011 747 1012 1025 1012 1443 1012 1006 1013 1154 1013 713 1013 1444 1014 186 1014 1103 1014 570 1015 968 1015 1093 1015 1445 1016 682 1016 1007 1016 345 1017 819 1017 1446 1017 1447 1018 902 1018 1448 1018 14 1019 13 1019 822 1019 1449 1020 1450 1020 1451 1020 268 1021 95 1021 444 1021 1452 1022 1453 1022 411 1022 1010 1023 316 1023 1454 1023 637 1024 398 1024 70 1024 1455 1025 1456 1025 127 1025 1061 1026 983 1026 1217 1026 252 1027 1413 1027 1457 1027 1458 1028 489 1028 488 1028 1404 1029 1398 1029 1459 1029 658 1030 657 1030 1400 1030 721 1031 723 1031 1460 1031 1461 1032 1462 1032 1463 1032 283 1033 33 1033 336 1033 121 1034 732 1034 1253 1034 1404 1035 1459 1035 1464 1035 1404 1036 1464 1036 1353 1036 1035 1037 14 1037 988 1037 759 1038 1337 1038 885 1038 1353 1039 1464 1039 1437 1039 1066 1040 1465 1040 1134 1040 1466 1041 1154 1041 908 1041 1467 1042 668 1042 1468 1042 437 1043 773 1043 887 1043 1448 1044 651 1044 1447 1044 1415 1045 1437 1045 335 1045 1078 1046 1469 1046 640 1046 356 1047 355 1047 1470 1047 1350 1048 563 1048 1471 1048 982 1049 1472 1049 980 1049 1420 1050 1415 1050 516 1050 751 1051 416 1051 415 1051 476 1052 1299 1052 946 1052 1420 1053 516 1053 1473 1053 1420 1054 1473 1054 1364 1054 1474 1055 982 1055 1190 1055 1475 1056 1476 1056 709 1056 1330 1057 544 1057 608 1057 882 1058 1411 1058 724 1058 1477 1059 117 1059 1043 1059 97 1060 39 1060 98 1060 1478 1061 1479 1061 1480 1061 1026 1062 1313 1062 697 1062 1398 1063 336 1063 1459 1063 1481 1064 1469 1064 961 1064 578 1065 969 1065 496 1065 1332 1066 748 1066 1286 1066 1072 1067 1119 1067 1121 1067 426 1068 1482 1068 424 1068 424 1069 1482 1069 449 1069 556 1070 1483 1070 856 1070 276 1071 1484 1071 1225 1071 718 1072 655 1072 1485 1072 1361 1073 1326 1073 1382 1073 133 1074 1486 1074 683 1074 886 1075 1487 1075 887 1075 1437 1076 1464 1076 335 1076 850 1077 1039 1077 851 1077 98 1078 30 1078 1356 1078 1358 1079 44 1079 43 1079 553 1080 1271 1080 1270 1080 172 1081 441 1081 1423 1081 717 1082 964 1082 1059 1082 1415 1083 335 1083 516 1083 1488 1084 406 1084 1369 1084 42 1085 180 1085 182 1085 566 1086 794 1086 44 1086 1029 1087 1195 1087 1489 1087 1286 1088 748 1088 750 1088 67 1089 1490 1089 726 1089 219 1090 218 1090 1215 1090 476 1091 1491 1091 1299 1091 1492 1092 745 1092 1493 1092 19 1093 439 1093 440 1093 791 1094 1227 1094 706 1094 1072 1095 1121 1095 1494 1095 589 1096 730 1096 807 1096 496 1097 537 1097 833 1097 1393 1098 601 1098 1165 1098 152 1099 1495 1099 1231 1099 1496 1100 361 1100 586 1100 1497 1101 458 1101 908 1101 1498 1102 642 1102 641 1102 3 1103 5 1103 1499 1103 1500 1104 1410 1104 1336 1104 1501 1105 950 1105 1502 1105 960 1106 847 1106 717 1106 1468 1107 123 1107 1467 1107 1503 1108 1183 1108 530 1108 1459 1109 336 1109 1464 1109 1052 1110 1504 1110 1053 1110 1505 1111 320 1111 1506 1111 1031 1112 688 1112 1507 1112 204 1113 614 1113 205 1113 874 1114 1508 1114 860 1114 1113 1115 824 1115 1479 1115 227 1116 1125 1116 228 1116 1025 1117 403 1117 1443 1117 72 1118 1025 1118 853 1118 133 1119 740 1119 1486 1119 1226 1120 1079 1120 1416 1120 1315 1121 1308 1121 1386 1121 1509 1122 1510 1122 952 1122 599 1123 254 1123 519 1123 648 1124 361 1124 360 1124 1007 1125 438 1125 1445 1125 317 1126 36 1126 758 1126 1511 1127 1055 1127 1303 1127 1138 1128 1301 1128 978 1128 600 1129 1512 1129 1513 1129 1088 1130 1514 1130 1515 1130 900 1131 1081 1131 1516 1131 717 1132 847 1132 1517 1132 1518 1133 508 1133 510 1133 935 1134 1480 1134 936 1134 1100 1135 572 1135 938 1135 1357 1136 1519 1136 275 1136 1263 1137 606 1137 1520 1137 1333 1138 376 1138 1521 1138 509 1139 1512 1139 600 1139 916 1140 1111 1140 657 1140 852 1141 851 1141 1522 1141 1269 1142 1523 1142 858 1142 1223 1143 715 1143 1524 1143 99 1144 1385 1144 100 1144 1223 1145 1460 1145 1525 1145 65 1146 1526 1146 1527 1146 1528 1147 1186 1147 1529 1147 1191 1148 497 1148 1474 1148 1464 1149 336 1149 335 1149 35 1150 120 1150 214 1150 210 1151 187 1151 1103 1151 744 1152 987 1152 1530 1152 662 1153 520 1153 22 1153 1231 1154 1018 1154 1399 1154 421 1155 81 1155 422 1155 597 1156 545 1156 547 1156 306 1157 1208 1157 307 1157 1339 1158 224 1158 472 1158 1531 1159 999 1159 1532 1159 349 1160 1366 1160 350 1160 413 1161 509 1161 1533 1161 356 1162 784 1162 107 1162 249 1163 1147 1163 353 1163 1534 1164 454 1164 843 1164 786 1165 1434 1165 1433 1165 154 1166 1535 1166 51 1166 1517 1167 847 1167 1179 1167 420 1168 1536 1168 1537 1168 198 1169 200 1169 578 1169 1013 1170 34 1170 1172 1170 515 1171 449 1171 1526 1171 1538 1172 166 1172 728 1172 603 1173 921 1173 604 1173 496 1174 902 1174 487 1174 1539 1175 1540 1175 1509 1175 313 1176 1347 1176 754 1176 1432 1177 111 1177 737 1177 1541 1178 1542 1178 1543 1178 1386 1179 975 1179 1315 1179 1499 1180 886 1180 3 1180 454 1181 1534 1181 433 1181 738 1182 167 1182 169 1182 1470 1183 1068 1183 1302 1183 847 1184 960 1184 342 1184 1527 1185 1544 1185 1545 1185 1546 1186 1027 1186 693 1186 732 1187 731 1187 1253 1187 707 1188 1035 1188 744 1188 972 1189 1458 1189 973 1189 548 1190 875 1190 900 1190 557 1191 869 1191 472 1191 1547 1192 110 1192 473 1192 1331 1193 1502 1193 1332 1193 9 1194 665 1194 10 1194 1548 1195 1549 1195 569 1195 973 1196 1256 1196 1255 1196 730 1197 394 1197 393 1197 412 1198 509 1198 413 1198 1550 1199 790 1199 792 1199 1551 1200 1552 1200 1553 1200 345 1201 612 1201 942 1201 628 1202 627 1202 1168 1202 1062 1203 732 1203 121 1203 611 1204 1554 1204 712 1204 112 1205 341 1205 186 1205 710 1206 1555 1206 1294 1206 947 1207 91 1207 93 1207 1545 1208 1544 1208 1556 1208 1407 1209 1406 1209 1557 1209 489 1210 1442 1210 818 1210 1558 1211 763 1211 253 1211 1439 1212 1559 1212 1009 1212 1231 1213 1495 1213 1018 1213 553 1214 1167 1214 789 1214 443 1215 95 1215 478 1215 880 1216 168 1216 881 1216 1560 1217 1499 1217 1119 1217 1099 1218 1098 1218 1214 1218 1561 1219 1390 1219 1392 1219 1562 1220 824 1220 1478 1220 1563 1221 1564 1221 1565 1221 298 1222 890 1222 1111 1222 227 1223 572 1223 1125 1223 1525 1224 660 1224 1094 1224 203 1225 202 1225 342 1225 344 1226 1554 1226 819 1226 1104 1227 375 1227 377 1227 1360 1228 1362 1228 477 1228 358 1229 357 1229 86 1229 1096 1230 715 1230 1223 1230 867 1231 1566 1231 632 1231 1419 1232 1543 1232 1014 1232 487 1233 428 1233 465 1233 373 1234 1567 1234 371 1234 999 1235 1232 1235 1360 1235 1014 1236 1568 1236 1015 1236 1569 1237 1570 1237 1571 1237 713 1238 715 1238 735 1238 828 1239 1036 1239 960 1239 638 1240 590 1240 639 1240 1015 1241 1568 1241 1277 1241 448 1242 43 1242 45 1242 1189 1243 1572 1243 1069 1243 669 1244 500 1244 573 1244 1545 1245 1556 1245 1251 1245 217 1246 1048 1246 1408 1246 949 1247 1431 1247 923 1247 1573 1248 1524 1248 1574 1248 754 1249 1347 1249 55 1249 1568 1250 1279 1250 1277 1250 1575 1251 261 1251 170 1251 191 1252 190 1252 655 1252 169 1253 986 1253 1344 1253 710 1254 1293 1254 579 1254 163 1255 453 1255 1576 1255 840 1256 1092 1256 1577 1256 1578 1257 99 1257 101 1257 317 1258 1552 1258 36 1258 1280 1259 127 1259 126 1259 1211 1260 1213 1260 1579 1260 1580 1261 957 1261 1581 1261 380 1262 379 1262 1582 1262 1583 1263 866 1263 1584 1263 209 1264 1166 1264 315 1264 1584 1265 866 1265 868 1265 830 1266 1060 1266 299 1266 1077 1267 264 1267 415 1267 1071 1268 269 1268 143 1268 1585 1269 777 1269 1467 1269 1586 1270 1228 1270 1274 1270 1413 1271 803 1271 232 1271 1425 1272 1427 1272 106 1272 1587 1273 383 1273 357 1273 1279 1274 126 1274 785 1274 605 1275 1571 1275 1570 1275 1507 1276 962 1276 1434 1276 1550 1277 705 1277 743 1277 510 1278 1448 1278 1518 1278 1575 1279 420 1279 1537 1279 205 1280 456 1280 206 1280 651 1281 1448 1281 510 1281 820 1282 1053 1282 1403 1282 1544 1283 1588 1283 1589 1283 1441 1284 196 1284 195 1284 114 1285 327 1285 1504 1285 1590 1286 961 1286 1469 1286 1591 1287 1544 1287 1589 1287 1471 1288 563 1288 1192 1288 1385 1289 99 1289 1246 1289 1592 1290 1128 1290 1574 1290 1593 1291 1594 1291 195 1291 1085 1292 990 1292 287 1292 58 1293 1483 1293 1363 1293 1360 1294 1576 1294 1361 1294 645 1295 531 1295 1595 1295 810 1296 1321 1296 657 1296 717 1297 1059 1297 1058 1297 1085 1298 287 1298 1378 1298 217 1299 1408 1299 1387 1299 576 1300 571 1300 1596 1300 347 1301 824 1301 330 1301 1597 1302 283 1302 1505 1302 1544 1303 1591 1303 1598 1303 875 1304 48 1304 1599 1304 71 1305 118 1305 1477 1305 526 1306 525 1306 951 1306 1349 1307 561 1307 1350 1307 1589 1308 1600 1308 1591 1308 678 1309 1016 1309 679 1309 919 1310 918 1310 1371 1310 1557 1311 1406 1311 586 1311 119 1312 1577 1312 120 1312 586 1313 257 1313 1496 1313 1496 1314 257 1314 1062 1314 71 1315 1238 1315 118 1315 596 1316 1601 1316 321 1316 300 1317 984 1317 1011 1317 1505 1318 928 1318 911 1318 843 1319 454 1319 456 1319 1029 1320 1489 1320 1040 1320 789 1321 788 1321 681 1321 1602 1322 227 1322 555 1322 228 1323 1101 1323 57 1323 1329 1324 183 1324 185 1324 21 1325 23 1325 518 1325 901 1326 677 1326 1430 1326 348 1327 939 1327 349 1327 155 1328 1087 1328 1384 1328 935 1329 937 1329 1158 1329 1603 1330 1137 1330 1391 1330 1330 1331 9 1331 11 1331 1604 1332 99 1332 1578 1332 57 1333 344 1333 856 1333 459 1334 762 1334 1088 1334 1578 1335 1083 1335 1605 1335 346 1336 330 1336 329 1336 1318 1337 1208 1337 455 1337 1061 1338 997 1338 994 1338 115 1339 1054 1339 1237 1339 467 1340 936 1340 1606 1340 351 1341 1607 1341 352 1341 1514 1342 698 1342 1608 1342 1294 1343 1579 1343 1188 1343 1277 1344 1279 1344 785 1344 1543 1345 1419 1345 1541 1345 523 1346 1074 1346 312 1346 197 1347 196 1347 1458 1347 770 1348 329 1348 331 1348 1609 1349 1484 1349 276 1349 515 1350 514 1350 1610 1350 1315 1351 976 1351 1206 1351 1419 1352 1418 1352 1541 1352 1232 1353 163 1353 1360 1353 659 1354 606 1354 1263 1354 1541 1355 1418 1355 914 1355 758 1356 36 1356 38 1356 1541 1357 914 1357 1611 1357 170 1358 1423 1358 418 1358 809 1359 247 1359 145 1359 1071 1360 143 1360 636 1360 1442 1361 1296 1361 1503 1361 1155 1362 1466 1362 458 1362 1294 1363 367 1363 1211 1363 425 1364 692 1364 1084 1364 1612 1365 458 1365 1466 1365 271 1366 198 1366 1248 1366 938 1367 1414 1367 939 1367 347 1368 509 1368 823 1368 34 1369 1613 1369 130 1369 1537 1370 304 1370 303 1370 493 1371 495 1371 271 1371 747 1372 1493 1372 745 1372 782 1373 432 1373 431 1373 731 1374 956 1374 1614 1374 1194 1375 379 1375 1292 1375 256 1376 1068 1376 733 1376 733 1377 1068 1377 731 1377 101 1378 397 1378 769 1378 1381 1379 467 1379 325 1379 1328 1380 1395 1380 183 1380 307 1381 1047 1381 617 1381 1417 1382 19 1382 18 1382 1228 1383 1580 1383 1581 1383 653 1384 948 1384 950 1384 607 1385 1012 1385 522 1385 1384 1386 1615 1386 1616 1386 1617 1387 1096 1387 1618 1387 1426 1388 919 1388 1427 1388 1619 1389 1132 1389 1620 1389 509 1390 1393 1390 1165 1390 512 1391 858 1391 1523 1391 388 1392 146 1392 1226 1392 137 1393 680 1393 292 1393 179 1394 977 1394 978 1394 57 1395 711 1395 344 1395 1538 1396 1621 1396 164 1396 1618 1397 1095 1397 766 1397 12 1398 1586 1398 1274 1398 957 1399 435 1399 1079 1399 1600 1400 1541 1400 1611 1400 1600 1401 1611 1401 1591 1401 1591 1402 1611 1402 1115 1402 599 1403 521 1403 865 1403 331 1404 1157 1404 1513 1404 1622 1405 1252 1405 540 1405 700 1406 236 1406 1521 1406 938 1407 1366 1407 1623 1407 1624 1408 249 1408 1402 1408 1356 1409 32 1409 1388 1409 505 1410 507 1410 1249 1410 1022 1411 1024 1411 1334 1411 430 1412 432 1412 1529 1412 255 1413 1625 1413 1307 1413 1067 1414 943 1414 685 1414 1034 1415 1626 1415 1627 1415 1067 1416 685 1416 1456 1416 1067 1417 1456 1417 1076 1417 487 1418 535 1418 527 1418 1076 1419 1455 1419 127 1419 1076 1420 127 1420 1086 1420 1086 1421 127 1421 1280 1421 268 1422 1628 1422 105 1422 1191 1423 1629 1423 20 1423 1086 1424 1280 1424 1105 1424 385 1425 941 1425 1630 1425 1105 1426 1280 1426 1124 1426 1124 1427 1280 1427 1279 1427 1525 1428 1094 1428 1223 1428 1285 1429 589 1429 165 1429 1124 1430 1279 1430 1131 1430 1131 1431 1279 1431 1568 1431 318 1432 317 1432 758 1432 1076 1433 1456 1433 1455 1433 1010 1434 1454 1434 49 1434 325 1435 467 1435 420 1435 676 1436 1059 1436 1028 1436 1 1437 1402 1437 2 1437 1298 1438 1121 1438 1024 1438 1013 1439 1631 1439 34 1439 1351 1440 1350 1440 1462 1440 1377 1441 1632 1441 1633 1441 1521 1442 376 1442 700 1442 631 1443 868 1443 632 1443 1503 1444 530 1444 818 1444 1595 1445 531 1445 1233 1445 392 1446 870 1446 174 1446 174 1447 870 1447 727 1447 799 1448 527 1448 204 1448 993 1449 1103 1449 341 1449 243 1450 242 1450 1099 1450 1322 1451 1373 1451 780 1451 1634 1452 1360 1452 477 1452 556 1453 856 1453 555 1453 1227 1454 933 1454 229 1454 1543 1455 1568 1455 1014 1455 637 1456 639 1456 398 1456 595 1457 1291 1457 378 1457 1268 1458 151 1458 153 1458 716 1459 1295 1459 963 1459 196 1460 1442 1460 1635 1460 1636 1461 957 1461 1394 1461 252 1462 1457 1462 1558 1462 909 1463 1261 1463 910 1463 811 1464 1450 1464 1449 1464 1558 1465 1457 1465 763 1465 1410 1466 1500 1466 1610 1466 843 1467 888 1467 1370 1467 1400 1468 940 1468 384 1468 421 1469 82 1469 81 1469 1101 1470 938 1470 1623 1470 1065 1471 644 1471 1637 1471 1515 1472 1638 1472 877 1472 824 1473 1113 1473 1112 1473 1565 1474 1436 1474 825 1474 956 1475 1068 1475 955 1475 339 1476 1639 1476 337 1476 423 1477 376 1477 421 1477 795 1478 797 1478 99 1478 934 1479 244 1479 1038 1479 1590 1480 1469 1480 1078 1480 214 1481 125 1481 223 1481 657 1482 940 1482 1400 1482 249 1483 1567 1483 1147 1483 321 1484 1601 1484 322 1484 1242 1485 197 1485 1316 1485 1351 1486 1462 1486 1461 1486 404 1487 1640 1487 405 1487 871 1488 1120 1488 5 1488 497 1489 1191 1489 498 1489 495 1490 793 1490 200 1490 865 1491 1641 1491 1191 1491 1564 1492 1002 1492 484 1492 487 1493 1262 1493 428 1493 1642 1494 1643 1494 1644 1494 48 1495 1613 1495 1599 1495 1278 1496 1522 1496 851 1496 1172 1497 34 1497 33 1497 1597 1498 911 1498 281 1498 929 1499 1194 1499 930 1499 642 1500 1342 1500 1645 1500 13 1501 1646 1501 1647 1501 286 1502 1151 1502 693 1502 35 1503 962 1503 961 1503 582 1504 1129 1504 1130 1504 1609 1505 1460 1505 1648 1505 312 1506 1075 1506 1346 1506 1649 1507 970 1507 969 1507 1426 1508 917 1508 919 1508 1613 1509 47 1509 130 1509 966 1510 1235 1510 281 1510 856 1511 1483 1511 58 1511 915 1512 1536 1512 1341 1512 1501 1513 1502 1513 1331 1513 2 1514 1402 1514 1052 1514 945 1515 468 1515 475 1515 614 1516 889 1516 205 1516 1470 1517 784 1517 356 1517 441 1518 139 1518 1423 1518 1650 1519 1540 1519 1651 1519 33 1520 35 1520 214 1520 487 1521 486 1521 954 1521 1008 1522 1207 1522 436 1522 1159 1523 803 1523 802 1523 146 1524 148 1524 1080 1524 828 1525 1059 1525 829 1525 326 1526 155 1526 1227 1526 669 1527 573 1527 1652 1527 780 1528 779 1528 1323 1528 926 1529 1282 1529 430 1529 1653 1530 934 1530 1290 1530 1539 1531 1509 1531 525 1531 442 1532 1248 1532 198 1532 1576 1533 1628 1533 1324 1533 632 1534 1566 1534 1116 1534 1598 1535 1591 1535 1115 1535 391 1536 6 1536 209 1536 930 1537 1194 1537 1029 1537 982 1538 893 1538 892 1538 1376 1539 1352 1539 905 1539 458 1540 1592 1540 1155 1540 1312 1541 1501 1541 1331 1541 9 1542 608 1542 665 1542 1654 1543 1179 1543 656 1543 1485 1544 655 1544 305 1544 249 1545 1220 1545 1219 1545 926 1546 430 1546 1319 1546 909 1547 389 1547 1655 1547 448 1548 447 1548 1519 1548 1070 1549 1656 1549 545 1549 1311 1550 1312 1550 1498 1550 1308 1551 1310 1551 1386 1551 112 1552 145 1552 247 1552 1108 1553 855 1553 986 1553 693 1554 1151 1554 783 1554 1062 1555 733 1555 732 1555 1620 1556 451 1556 224 1556 1657 1557 1218 1557 1178 1557 1442 1558 196 1558 1441 1558 1658 1559 498 1559 1191 1559 650 1560 542 1560 651 1560 1659 1561 334 1561 333 1561 231 1562 805 1562 1580 1562 898 1563 1048 1563 1049 1563 404 1564 403 1564 460 1564 447 1565 722 1565 721 1565 546 1566 1642 1566 1644 1566 1660 1567 165 1567 164 1567 899 1568 1625 1568 1406 1568 852 1569 1522 1569 718 1569 579 1570 1188 1570 894 1570 1110 1571 1405 1571 1144 1571 152 1572 1233 1572 1495 1572 1656 1573 1377 1573 545 1573 675 1574 829 1574 1059 1574 763 1575 1457 1575 518 1575 672 1576 227 1576 1661 1576 353 1577 115 1577 114 1577 318 1578 758 1578 757 1578 908 1579 79 1579 806 1579 1662 1580 1443 1580 403 1580 1322 1581 363 1581 362 1581 483 1582 220 1582 1436 1582 943 1583 1030 1583 686 1583 910 1584 788 1584 958 1584 13 1585 1647 1585 173 1585 1145 1586 1077 1586 664 1586 662 1587 508 1587 1641 1587 840 1588 1577 1588 841 1588 88 1589 90 1589 682 1589 924 1590 93 1590 1368 1590 1580 1591 805 1591 957 1591 1174 1592 729 1592 750 1592 73 1593 1550 1593 743 1593 1220 1594 1287 1594 703 1594 710 1595 1294 1595 1293 1595 834 1596 1362 1596 1663 1596 1664 1597 721 1597 276 1597 1665 1598 1112 1598 1114 1598 37 1599 36 1599 1551 1599 1386 1600 1310 1600 218 1600 1575 1601 191 1601 261 1601 116 1602 118 1602 1238 1602 1563 1603 1000 1603 1002 1603 1061 1604 450 1604 1235 1604 1300 1605 179 1605 1301 1605 465 1606 831 1606 1323 1606 948 1607 1431 1607 949 1607 316 1608 315 1608 652 1608 77 1609 1356 1609 1388 1609 1666 1610 1584 1610 631 1610 249 1611 1624 1611 1287 1611 1427 1612 919 1612 1372 1612 1427 1613 1372 1613 265 1613 52 1614 621 1614 317 1614 218 1615 243 1615 1215 1615 462 1616 704 1616 463 1616 45 1617 44 1617 1031 1617 795 1618 1073 1618 796 1618 513 1619 1489 1619 1195 1619 172 1620 171 1620 614 1620 454 1621 328 1621 1127 1621 1439 1622 1009 1622 1362 1622 417 1623 811 1623 1657 1623 464 1624 463 1624 1 1624 693 1625 782 1625 1546 1625 23 1626 369 1626 763 1626 193 1627 1667 1627 1370 1627 901 1628 1430 1628 948 1628 1016 1629 1042 1629 947 1629 1397 1630 640 1630 1469 1630 1609 1631 1648 1631 1668 1631 1339 1632 711 1632 57 1632 588 1633 1557 1633 586 1633 293 1634 578 1634 833 1634 827 1635 826 1635 760 1635 15 1636 17 1636 1669 1636 378 1637 1292 1637 379 1637 1670 1638 390 1638 391 1638 1542 1639 1600 1639 1671 1639 1566 1640 1399 1640 1116 1640 1185 1641 1129 1641 582 1641 1245 1642 1262 1642 1335 1642 1672 1643 571 1643 569 1643 596 1644 1182 1644 1601 1644 1383 1645 1673 1645 1439 1645 1182 1646 154 1646 50 1646 75 1647 141 1647 76 1647 701 1648 1674 1648 1142 1648 1142 1649 1674 1649 1143 1649 1233 1650 1675 1650 1495 1650 415 1651 417 1651 663 1651 578 1652 496 1652 833 1652 1676 1653 1584 1653 1666 1653 487 1654 536 1654 535 1654 1677 1655 487 1655 801 1655 1008 1656 1261 1656 1207 1656 651 1657 485 1657 1447 1657 924 1658 1368 1658 925 1658 1529 1659 1186 1659 1319 1659 713 1660 734 1660 1006 1660 113 1661 327 1661 114 1661 509 1662 508 1662 1438 1662 68 1663 1678 1663 595 1663 1296 1664 1183 1664 1503 1664 475 1665 280 1665 102 1665 800 1666 455 1666 1208 1666 38 1667 1306 1667 1305 1667 461 1668 460 1668 291 1668 194 1669 1679 1669 1344 1669 1616 1670 100 1670 1385 1670 1053 1671 1504 1671 433 1671 1329 1672 1328 1672 183 1672 205 1673 888 1673 456 1673 1285 1674 165 1674 1660 1674 1680 1675 1681 1675 929 1675 1146 1676 506 1676 1145 1676 243 1677 1099 1677 1214 1677 138 1678 528 1678 1679 1678 1682 1679 1582 1679 1683 1679 630 1680 467 1680 1381 1680 1631 1681 83 1681 208 1681 1308 1682 1666 1682 1309 1682 1684 1683 1685 1683 302 1683 1371 1684 1686 1684 812 1684 1519 1685 1664 1685 275 1685 143 1686 145 1686 112 1686 907 1687 618 1687 457 1687 472 1688 471 1688 1687 1688 1098 1689 1023 1689 219 1689 1665 1690 1114 1690 1479 1690 704 1691 1287 1691 463 1691 1141 1692 1335 1692 542 1692 529 1693 140 1693 441 1693 1267 1694 1036 1694 245 1694 914 1695 1418 1695 849 1695 134 1696 133 1696 41 1696 87 1697 1388 1697 109 1697 1613 1698 48 1698 47 1698 106 1699 1427 1699 265 1699 1316 1700 1458 1700 972 1700 1688 1701 526 1701 561 1701 1201 1702 905 1702 904 1702 1533 1703 331 1703 413 1703 84 1704 24 1704 85 1704 432 1705 782 1705 781 1705 1423 1706 139 1706 1405 1706 717 1707 1689 1707 960 1707 734 1708 1690 1708 1674 1708 604 1709 1571 1709 605 1709 801 1710 487 1710 527 1710 650 1711 510 1711 623 1711 316 1712 652 1712 1311 1712 674 1713 676 1713 1282 1713 1397 1714 1469 1714 1481 1714 1598 1715 1556 1715 1544 1715 1144 1716 1405 1716 139 1716 1431 1717 924 1717 923 1717 436 1718 438 1718 1007 1718 1254 1719 1022 1719 1334 1719 1493 1720 1691 1720 817 1720 1224 1721 1692 1721 1097 1721 1544 1722 1527 1722 1588 1722 1588 1723 1527 1723 1526 1723 890 1724 889 1724 613 1724 49 1725 1454 1725 1498 1725 80 1726 701 1726 1142 1726 477 1727 479 1727 210 1727 854 1728 1492 1728 1550 1728 644 1729 645 1729 1693 1729 560 1730 1054 1730 1148 1730 1588 1731 1694 1731 1589 1731 86 1732 649 1732 1417 1732 1411 1733 1410 1733 725 1733 385 1734 1630 1734 558 1734 1 1735 1624 1735 1402 1735 1589 1736 1694 1736 1671 1736 1589 1737 1671 1737 1600 1737 420 1738 419 1738 1536 1738 1541 1739 1600 1739 1542 1739 76 1740 240 1740 77 1740 351 1741 1054 1741 1607 1741 583 1742 585 1742 1034 1742 1467 1743 123 1743 122 1743 70 1744 1193 1744 1178 1744 25 1745 1248 1745 1695 1745 192 1746 787 1746 193 1746 118 1747 117 1747 1477 1747 236 1748 1333 1748 1521 1748 420 1749 406 1749 408 1749 330 1750 1478 1750 1157 1750 1696 1751 918 1751 1156 1751 1584 1752 868 1752 631 1752 561 1753 563 1753 1350 1753 1157 1754 634 1754 1322 1754 285 1755 1528 1755 781 1755 974 1756 973 1756 1255 1756 376 1757 82 1757 421 1757 1652 1758 1676 1758 1205 1758 1335 1759 427 1759 1245 1759 1380 1760 1654 1760 1297 1760 1472 1761 982 1761 891 1761 414 1762 413 1762 1513 1762 1467 1763 122 1763 1585 1763 501 1764 1595 1764 502 1764 533 1765 722 1765 532 1765 1031 1766 786 1766 192 1766 689 1767 688 1767 940 1767 1530 1768 692 1768 424 1768 209 1769 8 1769 1166 1769 159 1770 291 1770 160 1770 1388 1771 32 1771 109 1771 1599 1772 1613 1772 208 1772 1298 1773 1097 1773 1692 1773 746 1774 853 1774 1025 1774 916 1775 1341 1775 1110 1775 1665 1776 1478 1776 1112 1776 1020 1777 1060 1777 1030 1777 521 1778 1641 1778 865 1778 232 1779 803 1779 1697 1779 882 1780 726 1780 879 1780 1200 1781 1376 1781 1201 1781 184 1782 1185 1782 582 1782 723 1783 660 1783 1525 1783 1158 1784 504 1784 503 1784 1310 1785 1309 1785 218 1785 1443 1786 1698 1786 815 1786 1478 1787 1480 1787 1157 1787 1429 1788 1168 1788 1594 1788 275 1789 274 1789 1357 1789 305 1790 307 1790 855 1790 781 1791 1529 1791 432 1791 1128 1792 1592 1792 1127 1792 26 1793 232 1793 24 1793 89 1794 1261 1794 1008 1794 823 1795 1438 1795 407 1795 224 1796 557 1796 472 1796 1117 1797 1018 1797 433 1797 1679 1798 528 1798 535 1798 1346 1799 1075 1799 1090 1799 1476 1800 1699 1800 568 1800 228 1801 57 1801 226 1801 0 1802 35 1802 464 1802 370 1803 1186 1803 1700 1803 1110 1804 298 1804 1111 1804 1701 1805 565 1805 564 1805 634 1806 1158 1806 503 1806 925 1807 1368 1807 749 1807 1505 1808 1506 1808 339 1808 1702 1809 1000 1809 1563 1809 1703 1810 1683 1810 1704 1810 1026 1811 388 1811 1313 1811 1585 1812 122 1812 1252 1812 1029 1813 1040 1813 1042 1813 1408 1814 588 1814 587 1814 235 1815 1634 1815 236 1815 445 1816 737 1816 111 1816 1155 1817 1154 1817 1466 1817 196 1818 1635 1818 1458 1818 1108 1819 168 1819 880 1819 1157 1820 1480 1820 1158 1820 1609 1821 1668 1821 1484 1821 157 1822 1244 1822 230 1822 473 1823 319 1823 1547 1823 189 1824 1209 1824 190 1824 1019 1825 1675 1825 1508 1825 1446 1826 611 1826 345 1826 1614 1827 544 1827 541 1827 170 1828 418 1828 420 1828 871 1829 506 1829 505 1829 741 1830 929 1830 931 1830 101 1831 250 1831 249 1831 967 1832 376 1832 1333 1832 319 1833 213 1833 1547 1833 1309 1834 241 1834 243 1834 617 1835 855 1835 307 1835 882 1836 724 1836 726 1836 942 1837 612 1837 130 1837 298 1838 1144 1838 138 1838 1227 1839 157 1839 933 1839 64 1840 63 1840 1380 1840 1472 1841 891 1841 493 1841 518 1842 23 1842 763 1842 311 1843 523 1843 312 1843 467 1844 1369 1844 420 1844 1537 1845 303 1845 487 1845 1358 1846 1266 1846 566 1846 912 1847 1705 1847 1706 1847 711 1848 1707 1848 344 1848 1708 1849 314 1849 316 1849 780 1850 1323 1850 1322 1850 154 1851 1709 1851 1535 1851 1710 1852 912 1852 965 1852 218 1853 1387 1853 1386 1853 1228 1854 1581 1854 1274 1854 547 1855 1711 1855 1182 1855 426 1856 1085 1856 1378 1856 965 1857 912 1857 1706 1857 390 1858 1004 1858 6 1858 1712 1859 604 1859 921 1859 405 1860 1640 1860 1662 1860 1705 1861 912 1861 1713 1861 1705 1862 1713 1862 1714 1862 207 1863 875 1863 208 1863 951 1864 562 1864 561 1864 1316 1865 972 1865 1317 1865 895 1866 605 1866 896 1866 1715 1867 812 1867 1686 1867 1714 1868 1713 1868 1716 1868 735 1869 715 1869 1096 1869 1713 1870 1717 1870 1716 1870 1451 1871 1450 1871 1538 1871 192 1872 995 1872 45 1872 1462 1873 1192 1873 1401 1873 690 1874 1718 1874 675 1874 1250 1875 66 1875 1545 1875 1513 1876 1141 1876 601 1876 1719 1877 22 1877 519 1877 263 1878 262 1878 613 1878 1693 1879 1595 1879 501 1879 467 1880 504 1880 937 1880 1328 1881 1720 1881 1395 1881 252 1882 1558 1882 253 1882 1392 1883 1510 1883 1540 1883 1318 1884 455 1884 1046 1884 1660 1885 1645 1885 1285 1885 493 1886 271 1886 84 1886 657 1887 1111 1887 810 1887 774 1888 1034 1888 1555 1888 1721 1889 1132 1889 445 1889 742 1890 931 1890 678 1890 289 1891 790 1891 1492 1891 574 1892 1130 1892 1583 1892 512 1893 1523 1893 1489 1893 826 1894 386 1894 760 1894 21 1895 662 1895 22 1895 1641 1896 521 1896 662 1896 487 1897 303 1897 536 1897 1474 1898 497 1898 969 1898 330 1899 1157 1899 331 1899 221 1900 1722 1900 400 1900 615 1901 423 1901 453 1901 328 1902 1440 1902 1128 1902 632 1903 1116 1903 242 1903 1083 1904 887 1904 1487 1904 270 1905 200 1905 199 1905 626 1906 932 1906 971 1906 1138 1907 946 1907 1299 1907 1057 1908 980 1908 84 1908 550 1909 572 1909 551 1909 1691 1910 747 1910 817 1910 749 1911 1368 1911 1174 1911 745 1912 854 1912 746 1912 1309 1913 243 1913 218 1913 1170 1914 1714 1914 1723 1914 1362 1915 1361 1915 1383 1915 636 1916 1236 1916 842 1916 762 1917 761 1917 696 1917 359 1918 123 1918 360 1918 1087 1919 175 1919 1615 1919 1723 1920 1714 1920 1716 1920 725 1921 724 1921 1411 1921 595 1922 511 1922 1291 1922 1700 1923 1186 1923 371 1923 268 1924 96 1924 95 1924 1050 1925 1051 1925 1204 1925 1724 1926 1203 1926 1204 1926 795 1927 1725 1927 1073 1927 1724 1928 1204 1928 1051 1928 1724 1929 1051 1929 1706 1929 595 1930 378 1930 1726 1930 1072 1931 1494 1931 796 1931 1225 1932 1484 1932 1440 1932 62 1933 1027 1933 1028 1933 987 1934 1727 1934 1530 1934 821 1935 1236 1935 636 1935 1194 1936 1292 1936 1195 1936 575 1937 1583 1937 1584 1937 898 1938 1049 1938 1254 1938 461 1939 1221 1939 459 1939 148 1940 150 1940 957 1940 269 1941 104 1941 422 1941 552 1942 554 1942 1445 1942 399 1943 619 1943 1678 1943 1206 1944 648 1944 360 1944 1265 1945 113 1945 1237 1945 1728 1946 1714 1946 1181 1946 1707 1947 1729 1947 1730 1947 514 1948 1410 1948 1610 1948 1181 1949 1714 1949 1170 1949 1322 1950 362 1950 1141 1950 242 1951 1116 1951 1099 1951 1731 1952 1036 1952 675 1952 1717 1953 1162 1953 1732 1953 787 1954 809 1954 193 1954 1642 1955 1633 1955 1643 1955 1687 1956 125 1956 124 1956 458 1957 907 1957 457 1957 694 1958 331 1958 1533 1958 1682 1959 1683 1959 1426 1959 1627 1960 365 1960 367 1960 367 1961 366 1961 1211 1961 78 1962 806 1962 79 1962 1428 1963 1408 1963 1048 1963 192 1964 80 1964 1142 1964 1282 1965 926 1965 674 1965 511 1966 513 1966 1291 1966 88 1967 910 1967 89 1967 492 1968 1336 1968 54 1968 679 1969 1016 1969 947 1969 799 1970 206 1970 800 1970 873 1971 1508 1971 874 1971 1298 1972 1494 1972 1121 1972 1338 1973 1064 1973 1185 1973 368 1974 23 1974 1719 1974 70 1975 398 1975 399 1975 826 1976 1436 1976 386 1976 160 1977 291 1977 1733 1977 893 1978 982 1978 1474 1978 1673 1979 1382 1979 1559 1979 801 1980 189 1980 1677 1980 264 1981 751 1981 415 1981 1039 1982 1036 1982 851 1982 1647 1983 392 1983 173 1983 1638 1984 1670 1984 1708 1984 838 1985 1339 1985 57 1985 363 1986 1323 1986 831 1986 1655 1987 389 1987 1077 1987 1203 1988 1724 1988 1197 1988 331 1989 695 1989 770 1989 447 1990 446 1990 722 1990 631 1991 241 1991 1309 1991 1458 1992 488 1992 1256 1992 262 1993 655 1993 1278 1993 1402 1994 353 1994 1052 1994 797 1995 796 1995 1494 1995 423 1996 422 1996 720 1996 1339 1997 1687 1997 711 1997 1219 1998 262 1998 1278 1998 1454 1999 316 1999 1311 1999 685 2000 943 2000 686 2000 1071 2001 842 2001 702 2001 1119 2002 5 2002 1120 2002 357 2003 383 2003 86 2003 1705 2004 1724 2004 1706 2004 1734 2005 295 2005 1217 2005 812 2006 1715 2006 813 2006 1722 2007 401 2007 400 2007 1065 2008 1637 2008 1465 2008 1302 2009 1193 2009 69 2009 1201 2010 1376 2010 905 2010 1481 2011 657 2011 1397 2011 980 2012 493 2012 84 2012 1705 2013 1197 2013 1724 2013 894 2014 1189 2014 1069 2014 1302 2015 1068 2015 255 2015 1031 2016 192 2016 45 2016 454 2017 1735 2017 458 2017 582 2018 1130 2018 574 2018 1181 2019 1198 2019 1728 2019 1335 2020 1141 2020 427 2020 1728 2021 1198 2021 1197 2021 1728 2022 1197 2022 1705 2022 1122 2023 1360 2023 1379 2023 801 2024 527 2024 799 2024 1736 2025 870 2025 392 2025 1228 2026 231 2026 1580 2026 1505 2027 283 2027 320 2027 1504 2028 327 2028 328 2028 219 2029 1048 2029 217 2029 553 2030 1296 2030 1271 2030 1681 2031 1582 2031 379 2031 521 2032 520 2032 662 2032 1540 2033 1510 2033 1509 2033 687 2034 689 2034 1481 2034 44 2035 903 2035 1031 2035 598 2036 21 2036 518 2036 7 2037 742 2037 8 2037 668 2038 776 2038 1367 2038 1712 2039 1571 2039 604 2039 1727 2040 989 2040 692 2040 195 2041 1594 2041 1270 2041 1685 2042 536 2042 302 2042 1259 2043 40 2043 570 2043 869 2044 223 2044 125 2044 83 2045 82 2045 1081 2045 166 2046 165 2046 590 2046 2 2047 1053 2047 820 2047 1255 2048 1257 2048 1065 2048 549 2049 551 2049 1339 2049 747 2050 1691 2050 1493 2050 1389 2051 832 2051 1139 2051 549 2052 1339 2052 838 2052 1737 2053 1327 2053 1329 2053 812 2054 814 2054 1371 2054 1695 2055 442 2055 26 2055 1182 2056 50 2056 1601 2056 960 2057 1689 2057 828 2057 509 2058 414 2058 1512 2058 301 2059 607 2059 309 2059 915 2060 304 2060 1536 2060 531 2061 396 2061 1738 2061 1031 2062 1507 2062 786 2062 1637 2063 1693 2063 501 2063 837 2064 838 2064 938 2064 1714 2065 1728 2065 1705 2065 1083 2066 1487 2066 1605 2066 58 2067 57 2067 856 2067 475 2068 279 2068 280 2068 537 2069 496 2069 487 2069 1663 2070 1003 2070 835 2070 1329 2071 185 2071 776 2071 1332 2072 1502 2072 748 2072 974 2073 1255 2073 1064 2073 1155 2074 1592 2074 1574 2074 66 2075 1250 2075 1490 2075 238 2076 248 2076 239 2076 1195 2077 1292 2077 513 2077 1324 2078 1628 2078 1325 2078 268 2079 1559 2079 1382 2079 1638 2080 1708 2080 1010 2080 1235 2081 997 2081 1061 2081 702 2082 844 2082 703 2082 1678 2083 619 2083 511 2083 525 2084 952 2084 951 2084 1719 2085 23 2085 22 2085 1210 2086 716 2086 63 2086 420 2087 408 2087 1438 2087 1723 2088 1164 2088 1170 2088 379 2089 1194 2089 1681 2089 1223 2090 1648 2090 1460 2090 1646 2091 250 2091 1736 2091 30 2092 98 2092 39 2092 1470 2093 355 2093 1068 2093 696 2094 1026 2094 697 2094 1695 2095 1248 2095 442 2095 203 2096 718 2096 1485 2096 577 2097 1259 2097 570 2097 777 2098 668 2098 1467 2098 766 2099 660 2099 661 2099 1257 2100 488 2100 644 2100 982 2101 892 2101 1355 2101 879 2102 1251 2102 864 2102 252 2103 802 2103 1412 2103 540 2104 1252 2104 1253 2104 626 2105 959 2105 627 2105 1723 2106 1716 2106 1732 2106 183 2107 1395 2107 184 2107 1723 2108 1732 2108 1164 2108 768 2109 1083 2109 1578 2109 1295 2110 1028 2110 1059 2110 1103 2111 340 2111 1432 2111 463 2112 1287 2112 1624 2112 1644 2113 1643 2113 1711 2113 1574 2114 1128 2114 1573 2114 1302 2115 255 2115 1146 2115 1256 2116 488 2116 1257 2116 810 2117 1220 2117 193 2117 1200 2118 814 2118 1376 2118 1179 2119 342 2119 1140 2119 1732 2120 1161 2120 1164 2120 1615 2121 100 2121 1616 2121 1114 2122 1113 2122 1479 2122 1516 2123 1081 2123 1132 2123 768 2124 767 2124 1083 2124 1374 2125 635 2125 1739 2125 1716 2126 1717 2126 1732 2126 581 2127 1740 2127 708 2127 26 2128 442 2128 232 2128 35 2129 611 2129 712 2129 507 2130 1307 2130 899 2130 70 2131 1678 2131 68 2131 1740 2132 1475 2132 708 2132 1504 2133 328 2133 433 2133 687 2134 962 2134 1507 2134 398 2135 808 2135 393 2135 337 2136 1639 2136 324 2136 1741 2137 1390 2137 1561 2137 266 2138 904 2138 751 2138 1410 2139 1337 2139 1336 2139 1732 2140 1162 2140 1161 2140 1134 2141 1465 2141 151 2141 464 2142 1078 2142 462 2142 1314 2143 1742 2143 873 2143 277 2144 278 2144 599 2144 296 2145 1619 2145 1620 2145 1033 2146 583 2146 1034 2146 1492 2147 790 2147 1550 2147 627 2148 789 2148 1168 2148 302 2149 536 2149 303 2149 1383 2150 1382 2150 1673 2150 378 2151 1291 2151 1292 2151 221 2152 400 2152 222 2152 482 2153 1314 2153 483 2153 1570 2154 896 2154 605 2154 1218 2155 1451 2155 728 2155 1520 2156 260 2156 876 2156 1432 2157 340 2157 111 2157 660 2158 1095 2158 1094 2158 1707 2159 711 2159 1729 2159 407 2160 1438 2160 408 2160 708 2161 1475 2161 709 2161 371 2162 1528 2162 374 2162 921 2163 603 2163 922 2163 1717 2164 1713 2164 1743 2164 1717 2165 1743 2165 1162 2165 108 2166 1425 2166 106 2166 1162 2167 1743 2167 1230 2167 679 2168 924 2168 1431 2168 1727 2169 692 2169 1530 2169 988 2170 14 2170 989 2170 861 2171 249 2171 401 2171 1585 2172 1252 2172 1622 2172 1100 2173 1101 2173 228 2173 301 2174 309 2174 308 2174 539 2175 1327 2175 1737 2175 697 2176 1314 2176 698 2176 1743 2177 1149 2177 1230 2177 1140 2178 738 2178 739 2178 1603 2179 946 2179 1137 2179 1743 2180 1107 2180 1149 2180 1087 2181 1615 2181 1384 2181 1629 2182 1587 2182 357 2182 934 2183 718 2183 1290 2183 722 2184 446 2184 532 2184 1487 2185 886 2185 1560 2185 202 2186 167 2186 738 2186 566 2187 44 2187 1358 2187 1726 2188 380 2188 1682 2188 576 2189 592 2189 594 2189 1263 2190 1744 2190 1264 2190 1593 2191 1429 2191 1594 2191 1452 2192 1621 2192 1453 2192 1223 2193 1524 2193 1573 2193 8 2194 677 2194 1166 2194 86 2195 1417 2195 979 2195 715 2196 714 2196 1524 2196 467 2197 466 2197 504 2197 487 2198 954 2198 1262 2198 201 2199 203 2199 881 2199 220 2200 1150 2200 221 2200 1082 2201 1107 2201 1063 2201 1550 2202 792 2202 705 2202 114 2203 1504 2203 353 2203 1063 2204 1107 2204 1743 2204 319 2205 646 2205 267 2205 1063 2206 1743 2206 1713 2206 1063 2207 1713 2207 912 2207 1480 2208 1479 2208 1488 2208 1099 2209 1116 2209 1118 2209 1211 2210 366 2210 1212 2210 1236 2211 1403 2211 1534 2211 1563 2212 1002 2212 1564 2212 709 2213 1476 2213 568 2213 218 2214 217 2214 1387 2214 1377 2215 1642 2215 546 2215 897 2216 409 2216 417 2216 1313 2217 1511 2217 1314 2217 1555 2218 367 2218 1294 2218 1419 2219 1014 2219 849 2219 67 2220 726 2220 725 2220 1229 2221 981 2221 1057 2221 375 2222 1432 2222 737 2222 1235 2223 474 2223 281 2223 518 2224 1413 2224 441 2224 904 2225 906 2225 416 2225 564 2226 1266 2226 1435 2226 643 2227 642 2227 1745 2227 342 2228 202 2228 1140 2228 24 2229 1159 2229 252 2229 1379 2230 1634 2230 235 2230 285 2231 374 2231 1528 2231 464 2232 35 2232 1590 2232 1484 2233 1573 2233 1128 2233 786 2234 1433 2234 787 2234 25 2235 1695 2235 26 2235 842 2236 1534 2236 843 2236 219 2237 1023 2237 1049 2237 1344 2238 1679 2238 534 2238 1443 2239 1640 2239 1698 2239 1692 2240 1494 2240 1298 2240 1454 2241 1311 2241 1498 2241 189 2242 1208 2242 1209 2242 841 2243 119 2243 711 2243 344 2244 1746 2244 1554 2244 1165 2245 601 2245 622 2245 1513 2246 601 2246 600 2246 461 2247 827 2247 1221 2247 299 2248 1020 2248 985 2248 537 2249 487 2249 629 2249 913 2250 912 2250 1710 2250 1674 2251 1747 2251 1143 2251 835 2252 444 2252 836 2252 1224 2253 797 2253 1692 2253 1138 2254 978 2254 1136 2254 1154 2255 714 2255 713 2255 147 2256 149 2256 148 2256 226 2257 56 2257 227 2257 819 2258 1554 2258 1748 2258 1627 2259 1626 2259 365 2259 966 2260 281 2260 953 2260 1191 2261 1641 2261 1658 2261 1497 2262 907 2262 458 2262 591 2263 251 2263 1646 2263 1552 2264 1551 2264 36 2264 706 2265 1586 2265 1035 2265 1251 2266 1250 2266 1545 2266 222 2267 400 2267 402 2267 1527 2268 1545 2268 66 2268 462 2269 1078 2269 269 2269 433 2270 99 2270 1225 2270 1443 2271 815 2271 747 2271 1708 2272 316 2272 1010 2272 213 2273 110 2273 1547 2273 494 2274 1649 2274 200 2274 1442 2275 1503 2275 818 2275 121 2276 123 2276 359 2276 1174 2277 1368 2277 1173 2277 288 2278 326 2278 1227 2278 1576 2279 453 2279 103 2279 476 2280 273 2280 1491 2280 1661 2281 1135 2281 672 2281 4 2282 506 2282 871 2282 244 2283 1036 2283 1039 2283 802 2284 804 2284 1412 2284 257 2285 733 2285 1062 2285 284 2286 1749 2286 285 2286 1631 2287 1613 2287 34 2287 1629 2288 982 2288 1587 2288 1006 2289 908 2289 1154 2289 141 2290 240 2290 76 2290 410 2291 1750 2291 411 2291 628 2292 1168 2292 1429 2292 286 2293 1400 2293 384 2293 354 2294 910 2294 1751 2294 965 2295 913 2295 1710 2295 907 2296 806 2296 618 2296 1313 2297 1226 2297 1424 2297 934 2298 1039 2298 850 2298 1507 2299 688 2299 687 2299 1303 2300 434 2300 1017 2300 534 2301 536 2301 1685 2301 1680 2302 929 2302 741 2302 1376 2303 1375 2303 1352 2303 1658 2304 1448 2304 498 2304 1674 2305 1618 2305 1747 2305 396 2306 249 2306 1738 2306 1036 2307 246 2307 245 2307 979 2308 1417 2308 18 2308 1742 2309 1303 2309 1272 2309 920 2310 449 2310 921 2310 1243 2311 1429 2311 1593 2311 1752 2312 1608 2312 1001 2312 1390 2313 1603 2313 1391 2313 728 2314 638 2314 637 2314 222 2315 147 2315 387 2315 555 2316 1135 2316 1661 2316 915 2317 739 2317 302 2317 568 2318 1548 2318 569 2318 423 2319 615 2319 376 2319 1052 2320 353 2320 1504 2320 1297 2321 1654 2321 656 2321 950 2322 949 2322 1502 2322 1726 2323 1682 2323 1425 2323 1377 2324 1633 2324 1642 2324 1481 2325 961 2325 687 2325 991 2326 87 2326 74 2326 1189 2327 1753 2327 1572 2327 1011 2328 1012 2328 607 2328 1754 2329 959 2329 626 2329 1056 2330 996 2330 965 2330 1356 2331 30 2331 32 2331 1227 2332 1228 2332 1586 2332 656 2333 1179 2333 916 2333 1679 2334 535 2334 534 2334 297 2335 296 2335 551 2335 636 2336 248 2336 821 2336 1466 2337 908 2337 1612 2337 468 2338 1288 2338 469 2338 1480 2339 935 2339 1158 2339 1596 2340 571 2340 1755 2340 352 2341 115 2341 353 2341 1117 2342 433 2342 1225 2342 1706 2343 1056 2343 965 2343 686 2344 1060 2344 830 2344 20 2345 1629 2345 357 2345 1417 2346 439 2346 19 2346 1034 2347 1627 2347 1555 2347 566 2348 1266 2348 564 2348 454 2349 433 2349 328 2349 1650 2350 1392 2350 1540 2350 514 2351 65 2351 67 2351 1622 2352 540 2352 539 2352 372 2353 647 2353 370 2353 1051 2354 1056 2354 1706 2354 1274 2355 1581 2355 1636 2355 302 2356 304 2356 915 2356 1684 2357 534 2357 1685 2357 573 2358 575 2358 1584 2358 267 2359 269 2359 319 2359 137 2360 71 2360 1043 2360 1548 2361 1756 2361 1757 2361 1548 2362 1757 2362 1549 2362 1479 2363 406 2363 1488 2363 1680 2364 1704 2364 1681 2364 322 2365 318 2365 323 2365 1549 2366 1757 2366 1758 2366 1562 2367 1478 2367 330 2367 462 2368 702 2368 704 2368 1549 2369 1758 2369 1672 2369 1672 2370 1758 2370 1759 2370 1320 2371 144 2371 1321 2371 1672 2372 1759 2372 1760 2372 1120 2373 871 2373 505 2373 110 2374 1721 2374 445 2374 792 2375 791 2375 706 2375 1103 2376 993 2376 340 2376 1760 2377 1759 2377 1761 2377 1516 2378 1132 2378 548 2378 211 2379 94 2379 96 2379 1760 2380 1761 2380 1755 2380 1755 2381 1761 2381 1762 2381 1382 2382 1326 2382 1325 2382 339 2383 338 2383 928 2383 244 2384 1039 2384 1038 2384 348 2385 350 2385 938 2385 10 2386 665 2386 1242 2386 663 2387 1657 2387 1178 2387 1755 2388 1762 2388 1763 2388 1763 2389 1762 2389 1764 2389 548 2390 1132 2390 1619 2390 274 2391 1266 2391 1357 2391 933 2392 230 2392 229 2392 1314 2393 872 2393 220 2393 1763 2394 1764 2394 592 2394 1602 2395 1661 2395 227 2395 1061 2396 294 2396 450 2396 592 2397 1764 2397 1765 2397 503 2398 466 2398 634 2398 592 2399 1765 2399 1766 2399 668 2400 670 2400 1468 2400 1372 2401 1371 2401 814 2401 592 2402 1766 2402 593 2402 271 2403 199 2403 198 2403 581 2404 1767 2404 1768 2404 29 2405 1498 2405 641 2405 593 2406 1766 2406 1769 2406 1704 2407 1582 2407 1681 2407 268 2408 1325 2408 1628 2408 593 2409 1769 2409 1770 2409 1257 2410 644 2410 1065 2410 763 2411 369 2411 480 2411 1430 2412 1431 2412 948 2412 1621 2413 1538 2413 1450 2413 1770 2414 1769 2414 1771 2414 609 2415 608 2415 544 2415 288 2416 1227 2416 791 2416 1770 2417 1771 2417 1772 2417 72 2418 71 2418 1025 2418 569 2419 1549 2419 1672 2419 909 2420 216 2420 389 2420 1772 2421 1771 2421 259 2421 259 2422 1771 2422 1773 2422 1368 2423 857 2423 1173 2423 299 2424 985 2424 300 2424 395 2425 394 2425 858 2425 1337 2426 1411 2426 882 2426 1483 2427 556 2427 227 2427 349 2428 838 2428 57 2428 259 2429 1773 2429 876 2429 876 2430 1773 2430 1774 2430 691 2431 675 2431 674 2431 1567 2432 373 2432 1147 2432 1617 2433 1618 2433 1674 2433 876 2434 1774 2434 1520 2434 1520 2435 1774 2435 1775 2435 68 2436 784 2436 69 2436 202 2437 201 2437 881 2437 1520 2438 1775 2438 1744 2438 1744 2439 1775 2439 1776 2439 695 2440 509 2440 770 2440 910 2441 958 2441 1751 2441 1336 2442 55 2442 54 2442 1744 2443 1776 2443 1777 2443 1363 2444 227 2444 56 2444 938 2445 350 2445 1366 2445 1744 2446 1777 2446 1264 2446 1264 2447 1777 2447 1778 2447 681 2448 88 2448 682 2448 473 2449 110 2449 112 2449 735 2450 1617 2450 1674 2450 182 2451 181 2451 1779 2451 1722 2452 861 2452 401 2452 1145 2453 506 2453 4 2453 1264 2454 1778 2454 1767 2454 1767 2455 1778 2455 1780 2455 376 2456 234 2456 699 2456 1115 2457 1611 2457 914 2457 439 2458 278 2458 1781 2458 1767 2459 1780 2459 1782 2459 517 2460 112 2460 268 2460 1767 2461 1782 2461 1768 2461 1373 2462 778 2462 780 2462 673 2463 227 2463 672 2463 1379 2464 376 2464 1123 2464 1768 2465 1782 2465 1783 2465 1768 2466 1783 2466 1740 2466 1740 2467 1783 2467 1784 2467 168 2468 167 2468 881 2468 619 2469 395 2469 512 2469 934 2470 1653 2470 342 2470 38 2471 1305 2471 740 2471 848 2472 342 2472 1179 2472 35 2473 712 2473 119 2473 1740 2474 1784 2474 1475 2474 1475 2475 1784 2475 1785 2475 1623 2476 1366 2476 1101 2476 1380 2477 1517 2477 1654 2477 1475 2478 1785 2478 1786 2478 519 2479 368 2479 1719 2479 909 2480 4 2480 1261 2480 1475 2481 1786 2481 1476 2481 395 2482 858 2482 512 2482 453 2483 423 2483 720 2483 1236 2484 1534 2484 842 2484 1476 2485 1786 2485 1787 2485 82 2486 376 2486 375 2486 509 2487 694 2487 1533 2487 1476 2488 1787 2488 1699 2488 1699 2489 1787 2489 1756 2489 491 2490 54 2490 53 2490 963 2491 717 2491 716 2491 1699 2492 1756 2492 1548 2492 750 2493 589 2493 1285 2493 1463 2494 1462 2494 1401 2494 354 2495 1751 2495 355 2495 617 2496 1047 2496 618 2496 433 2497 435 2497 957 2497 1321 2498 1397 2498 657 2498 1618 2499 1096 2499 1095 2499 1212 2500 272 2500 1213 2500 1028 2501 1295 2501 716 2501 1213 2502 272 2502 237 2502 1073 2503 1725 2503 1072 2503 986 2504 806 2504 78 2504 872 2505 1150 2505 220 2505 279 2506 1044 2506 1572 2506 1006 2507 734 2507 1674 2507 1072 2508 1560 2508 1119 2508 809 2509 145 2509 1320 2509 1213 2510 237 2510 61 2510 1213 2511 61 2511 1753 2511 767 2512 1240 2512 437 2512 1421 2513 1241 2513 1005 2513 1566 2514 1231 2514 1399 2514 203 2515 1485 2515 305 2515 860 2516 1675 2516 1738 2516 426 2517 1378 2517 1492 2517 1652 2518 573 2518 1676 2518 1693 2519 645 2519 1595 2519 1678 2520 511 2520 595 2520 816 2521 538 2521 1493 2521 1753 2522 61 2522 1572 2522 61 2523 60 2523 1572 2523 601 2524 650 2524 622 2524 71 2525 73 2525 1238 2525 629 2526 630 2526 598 2526 1572 2527 60 2527 279 2527 744 2528 1035 2528 988 2528 420 2529 1438 2529 662 2529 272 2530 1212 2530 1788 2530 1677 2531 1537 2531 487 2531 1528 2532 371 2532 1186 2532 1788 2533 1212 2533 366 2533 293 2534 441 2534 578 2534 1788 2535 366 2535 1789 2535 554 2536 682 2536 1445 2536 712 2537 1746 2537 1729 2537 1631 2538 208 2538 1613 2538 1702 2539 1608 2539 1752 2539 1789 2540 366 2540 365 2540 1755 2541 1763 2541 1596 2541 1190 2542 1191 2542 1474 2542 1673 2543 1559 2543 1439 2543 296 2544 1620 2544 224 2544 1789 2545 365 2545 1790 2545 565 2546 1032 2546 903 2546 1423 2547 1405 2547 418 2547 1092 2548 120 2548 1577 2548 382 2549 381 2549 982 2549 533 2550 660 2550 722 2550 148 2551 957 2551 1080 2551 1446 2552 1748 2552 611 2552 146 2553 1080 2553 1226 2553 284 2554 1148 2554 1749 2554 473 2555 112 2555 517 2555 1790 2556 365 2556 1626 2556 1576 2557 1324 2557 1361 2557 343 2558 342 2558 1290 2558 743 2559 705 2559 707 2559 1790 2560 1626 2560 1791 2560 1626 2561 585 2561 1791 2561 1791 2562 585 2562 1792 2562 158 2563 1025 2563 137 2563 1622 2564 1737 2564 777 2564 56 2565 226 2565 57 2565 1561 2566 1392 2566 1650 2566 992 2567 74 2567 59 2567 675 2568 1036 2568 828 2568 1604 2569 1605 2569 795 2569 1564 2570 484 2570 1565 2570 1792 2571 585 2571 584 2571 1258 2572 332 2572 188 2572 305 2573 1209 2573 306 2573 1574 2574 714 2574 1155 2574 669 2575 1652 2575 670 2575 197 2576 1593 2576 195 2576 584 2577 1779 2577 1793 2577 275 2578 1664 2578 276 2578 1794 2579 360 2579 123 2579 1615 2580 727 2580 100 2580 788 2581 910 2581 88 2581 1307 2582 506 2582 1146 2582 1795 2583 1779 2583 181 2583 1634 2584 1102 2584 236 2584 0 2585 464 2585 1 2585 239 2586 1434 2586 962 2586 671 2587 1770 2587 258 2587 459 2588 404 2588 460 2588 1507 2589 1434 2589 786 2589 1793 2590 1779 2590 1795 2590 1374 2591 1739 2591 778 2591 1150 2592 874 2592 860 2592 181 2593 1796 2593 1795 2593 1797 2594 1796 2594 180 2594 1502 2595 1133 2595 748 2595 1796 2596 181 2596 180 2596 51 2597 620 2597 52 2597 867 2598 153 2598 1566 2598 647 2599 926 2599 1187 2599 402 2600 149 2600 147 2600 180 2601 684 2601 1797 2601 1781 2602 278 2602 20 2602 263 2603 613 2603 171 2603 1108 2604 986 2604 169 2604 1468 2605 670 2605 1794 2605 813 2606 1375 2606 814 2606 1797 2607 684 2607 683 2607 581 2608 659 2608 1767 2608 1797 2609 683 2609 1798 2609 1301 2610 179 2610 978 2610 1389 2611 364 2611 832 2611 1044 2612 1045 2612 1069 2612 1622 2613 777 2613 1585 2613 518 2614 1457 2614 1413 2614 1486 2615 1340 2615 1798 2615 84 2616 271 2616 24 2616 1486 2617 1798 2617 683 2617 266 2618 1201 2618 904 2618 841 2619 1577 2619 119 2619 1425 2620 1682 2620 1426 2620 91 2621 1269 2621 92 2621 385 2622 1148 2622 284 2622 1070 2623 545 2623 633 2623 1488 2624 1606 2624 1480 2624 1235 2625 450 2625 474 2625 49 2626 1498 2626 28 2626 706 2627 1227 2627 1586 2627 801 2628 800 2628 189 2628 1288 2629 1632 2629 1656 2629 740 2630 1305 2630 1340 2630 210 2631 479 2631 211 2631 1683 2632 917 2632 1426 2632 268 2633 105 2633 269 2633 1478 2634 824 2634 1112 2634 740 2635 1340 2635 1486 2635 1363 2636 1483 2636 227 2636 1350 2637 1471 2637 1462 2637 539 2638 544 2638 1330 2638 1638 2639 1010 2639 877 2639 11 2640 1317 2640 1720 2640 281 2641 911 2641 953 2641 271 2642 495 2642 270 2642 1362 2643 1348 2643 1663 2643 1579 2644 1213 2644 1753 2644 573 2645 1584 2645 1676 2645 1344 2646 534 2646 1684 2646 1460 2647 723 2647 1525 2647 434 2648 433 2648 1017 2648 325 2649 420 2649 21 2649 1265 2650 1435 2650 1266 2650 103 2651 1222 2651 1576 2651 1313 2652 1424 2652 1511 2652 289 2653 288 2653 791 2653 634 2654 1373 2654 1322 2654 478 2655 95 2655 94 2655 568 2656 1699 2656 1548 2656 620 2657 1799 2657 621 2657 1647 2658 1736 2658 392 2658 542 2659 1800 2659 651 2659 621 2660 1799 2660 1553 2660 526 2661 951 2661 561 2661 982 2662 1629 2662 1191 2662 621 2663 1553 2663 1552 2663 31 2664 273 2664 475 2664 391 2665 209 2665 314 2665 1482 2666 1712 2666 449 2666 409 2667 1570 2667 410 2667 1709 2668 1801 2668 1802 2668 1709 2669 1802 2669 1535 2669 1666 2670 631 2670 1309 2670 248 2671 247 2671 1433 2671 1407 2672 588 2672 1408 2672 1535 2673 1802 2673 1803 2673 1599 2674 208 2674 875 2674 594 2675 593 2675 671 2675 911 2676 1597 2676 1505 2676 1400 2677 286 2677 693 2677 1146 2678 255 2678 1307 2678 448 2679 1519 2679 43 2679 1535 2680 1803 2680 620 2680 620 2681 1803 2681 1799 2681 1752 2682 1001 2682 1000 2682 688 2683 1032 2683 565 2683 413 2684 331 2684 1513 2684 1703 2685 917 2685 1683 2685 627 2686 958 2686 788 2686 1362 2687 834 2687 477 2687 1465 2688 501 2688 151 2688 276 2689 1460 2689 1609 2689 944 2690 946 2690 1603 2690 970 2691 1649 2691 493 2691 698 2692 1314 2692 482 2692 1804 2693 1801 2693 1709 2693 899 2694 1307 2694 1625 2694 644 2695 1693 2695 1637 2695 426 2696 1084 2696 1085 2696 959 2697 958 2697 627 2697 372 2698 1567 2698 249 2698 1804 2699 1709 2699 1643 2699 1805 2700 561 2700 1349 2700 1643 2701 1806 2701 1804 2701 291 2702 460 2702 1807 2702 1511 2703 1742 2703 1314 2703 750 2704 729 2704 589 2704 1806 2705 1643 2705 1633 2705 1632 2706 1176 2706 1633 2706 1633 2707 1176 2707 1808 2707 1225 2708 1224 2708 1097 2708 1071 2709 702 2709 462 2709 1137 2710 946 2710 1138 2710 941 2711 688 2711 1630 2711 1088 2712 696 2712 1514 2712 1633 2713 1808 2713 1806 2713 580 2714 894 2714 1069 2714 65 2715 1527 2715 66 2715 1634 2716 477 2716 1102 2716 624 2717 1192 2717 563 2717 1173 2718 394 2718 729 2718 1647 2719 1646 2719 1736 2719 1339 2720 472 2720 1687 2720 416 2721 897 2721 417 2721 205 2722 889 2722 888 2722 387 2723 147 2723 146 2723 1008 2724 1007 2724 90 2724 602 2725 601 2725 1393 2725 1532 2726 1360 2726 1122 2726 1341 2727 1536 2727 419 2727 1136 2728 978 2728 563 2728 1034 2729 585 2729 1626 2729 509 2730 623 2730 510 2730 182 2731 583 2731 1033 2731 1137 2732 1136 2732 563 2732 1137 2733 563 2733 562 2733 1625 2734 257 2734 1406 2734 1270 2735 1594 2735 1167 2735 562 2736 1396 2736 1137 2736 767 2737 397 2737 1005 2737 1575 2738 1537 2738 1677 2738 106 2739 265 2739 1809 2739 1220 2740 703 2740 844 2740 333 2741 16 2741 15 2741 1001 2742 698 2742 482 2742 624 2743 563 2743 978 2743 1621 2744 1450 2744 1453 2744 971 2745 1754 2745 626 2745 1330 2746 11 2746 1327 2746 1302 2747 69 2747 1470 2747 1518 2748 1448 2748 1658 2748 695 2749 694 2749 509 2749 611 2750 1748 2750 1554 2750 609 2751 1754 2751 971 2751 583 2752 1779 2752 584 2752 1137 2753 1396 2753 1391 2753 665 2754 932 2754 1243 2754 1618 2755 766 2755 1747 2755 1233 2756 1738 2756 1675 2756 1689 2757 1058 2757 828 2757 987 2758 988 2758 1727 2758 286 2759 285 2759 1151 2759 177 2760 1791 2760 178 2760 178 2761 1791 2761 1792 2761 51 2762 1535 2762 620 2762 1104 2763 1103 2763 1432 2763 680 2764 136 2764 135 2764 584 2765 1669 2765 1792 2765 1792 2766 1669 2766 178 2766 239 2767 962 2767 35 2767 538 2768 1492 2768 1493 2768 1175 2769 1390 2769 1741 2769 34 2770 130 2770 612 2770 779 2771 1739 2771 635 2771 1741 2772 1808 2772 1176 2772 1741 2773 1176 2773 1175 2773 1001 2774 482 2774 1002 2774 649 2775 599 2775 278 2775 1561 2776 1806 2776 1808 2776 1561 2777 1808 2777 1741 2777 1182 2778 1711 2778 154 2778 955 2779 355 2779 1754 2779 1379 2780 1360 2780 1634 2780 1006 2781 1674 2781 701 2781 1529 2782 1319 2782 430 2782 1806 2783 1561 2783 1804 2783 1804 2784 1561 2784 1650 2784 1188 2785 1579 2785 1189 2785 1646 2786 251 2786 250 2786 890 2787 613 2787 262 2787 1539 2788 1802 2788 1651 2788 1651 2789 1802 2789 1801 2789 1651 2790 1801 2790 1650 2790 1810 2791 1401 2791 334 2791 675 2792 1059 2792 676 2792 763 2793 480 2793 764 2793 1069 2794 1572 2794 1044 2794 578 2795 200 2795 1649 2795 843 2796 1370 2796 1667 2796 1650 2797 1801 2797 1804 2797 1803 2798 1802 2798 1539 2798 447 2799 721 2799 1664 2799 490 2800 530 2800 531 2800 504 2801 1811 2801 937 2801 268 2802 1009 2802 1559 2802 1803 2803 1812 2803 524 2803 1127 2804 458 2804 1735 2804 1803 2805 1539 2805 1812 2805 1474 2806 969 2806 893 2806 1157 2807 1141 2807 1513 2807 193 2808 1370 2808 194 2808 524 2809 1799 2809 1803 2809 558 2810 560 2810 1148 2810 654 2811 653 2811 1501 2811 1553 2812 524 2812 1688 2812 712 2813 1554 2813 1746 2813 1669 2814 17 2814 977 2814 1553 2815 1799 2815 524 2815 500 2816 499 2816 574 2816 175 2817 727 2817 1615 2817 898 2818 899 2818 1428 2818 1241 2819 1421 2819 552 2819 1805 2820 1553 2820 1688 2820 1041 2821 1489 2821 1523 2821 824 2822 407 2822 1479 2822 1321 2823 144 2823 640 2823 649 2824 254 2824 599 2824 1042 2825 1041 2825 91 2825 449 2826 1530 2826 424 2826 411 2827 1750 2827 1452 2827 823 2828 407 2828 824 2828 1805 2829 1551 2829 1553 2829 101 2830 769 2830 1578 2830 758 2831 38 2831 132 2831 546 2832 1644 2832 547 2832 1351 2833 37 2833 1349 2833 879 2834 1490 2834 1250 2834 1677 2835 189 2835 1575 2835 490 2836 531 2836 645 2836 1349 2837 37 2837 1805 2837 137 2838 292 2838 159 2838 1805 2839 37 2839 1551 2839 570 2840 40 2840 968 2840 163 2841 1576 2841 1360 2841 1461 2842 1304 2842 1351 2842 1351 2843 1304 2843 1306 2843 1314 2844 873 2844 872 2844 206 2845 455 2845 800 2845 232 2846 1697 2846 233 2846 1351 2847 1306 2847 37 2847 1045 2848 1656 2848 1070 2848 1461 2849 1463 2849 1340 2849 151 2850 502 2850 152 2850 1461 2851 1340 2851 1304 2851 527 2852 535 2852 528 2852 236 2853 1102 2853 1333 2853 751 2854 904 2854 416 2854 1730 2855 1746 2855 344 2855 1493 2856 817 2856 816 2856 537 2857 598 2857 293 2857 1340 2858 1463 2858 1798 2858 1158 2859 937 2859 1811 2859 314 2860 209 2860 315 2860 240 2861 97 2861 77 2861 1205 2862 1676 2862 1308 2862 1798 2863 1463 2863 1810 2863 1798 2864 1810 2864 1797 2864 1278 2865 719 2865 1522 2865 1684 2866 302 2866 739 2866 986 2867 80 2867 1344 2867 438 2868 1241 2868 1445 2868 1659 2869 1797 2869 1810 2869 1024 2870 1098 2870 1298 2870 1770 2871 1772 2871 258 2871 1269 2872 858 2872 857 2872 265 2873 1201 2873 266 2873 333 2874 1796 2874 1659 2874 606 2875 258 2875 260 2875 464 2876 1590 2876 1078 2876 465 2877 1323 2877 779 2877 1659 2878 1796 2878 1797 2878 15 2879 1795 2879 333 2879 333 2880 1795 2880 1796 2880 663 2881 417 2881 1657 2881 975 2882 1408 2882 587 2882 1571 2883 538 2883 1569 2883 12 2884 1274 2884 13 2884 15 2885 1793 2885 1795 2885 204 2886 529 2886 441 2886 1730 2887 1729 2887 1746 2887 731 2888 1068 2888 956 2888 1635 2889 1442 2889 489 2889 382 2890 1057 2890 383 2890 584 2891 1793 2891 1669 2891 248 2892 1434 2892 239 2892 1669 2893 1793 2893 15 2893 1449 2894 1451 2894 1218 2894 182 2895 1779 2895 583 2895 1335 2896 1262 2896 954 2896 17 2897 625 2897 977 2897 1218 2898 728 2898 637 2898 1760 2899 571 2899 1672 2899 944 2900 468 2900 945 2900 177 2901 1790 2901 1791 2901 319 2902 517 2902 646 2902 455 2903 454 2903 1046 2903 651 2904 1800 2904 485 2904 1300 2905 1790 2905 177 2905 1607 2906 1054 2906 352 2906 849 2907 1015 2907 785 2907 609 2908 955 2908 1754 2908 1032 2909 1031 2909 903 2909 1491 2910 1789 2910 1300 2910 1596 2911 1763 2911 576 2911 433 2912 1534 2912 1403 2912 711 2913 1687 2913 840 2913 995 2914 1143 2914 1813 2914 276 2915 1225 2915 328 2915 1300 2916 1789 2916 1790 2916 1392 2917 1391 2917 1396 2917 1789 2918 1491 2918 273 2918 1334 2919 1249 2919 1254 2919 1789 2920 273 2920 1788 2920 968 2921 42 2921 182 2921 1586 2922 12 2922 1035 2922 1812 2923 1539 2923 525 2923 823 2924 509 2924 1438 2924 551 2925 296 2925 224 2925 1409 2926 1232 2926 999 2926 973 2927 1458 2927 1256 2927 273 2928 272 2928 1788 2928 169 2929 1344 2929 1684 2929 362 2930 364 2930 1389 2930 488 2931 490 2931 644 2931 255 2932 1068 2932 256 2932 269 2933 83 2933 1631 2933 257 2934 256 2934 733 2934 1499 2935 5 2935 1119 2935 437 2936 1240 2936 438 2936 53 2937 1346 2937 491 2937 795 2938 99 2938 1604 2938 1027 2939 62 2939 693 2939 661 2940 533 2940 446 2940 1592 2941 458 2941 1127 2941 319 2942 1172 2942 33 2942 1519 2943 447 2943 1664 2943 540 2944 1614 2944 541 2944 1199 2945 1033 2945 774 2945 1259 2946 134 2946 40 2946 168 2947 1108 2947 169 2947 1103 2948 187 2948 1444 2948 908 2949 1006 2949 79 2949 619 2950 512 2950 511 2950 1394 2951 957 2951 150 2951 1320 2952 145 2952 144 2952 1772 2953 259 2953 258 2953 1303 2954 1017 2954 1272 2954 431 2955 1546 2955 782 2955 1045 2956 1288 2956 1656 2956 1361 2957 1324 2957 1326 2957 1316 2958 197 2958 1458 2958 214 2959 120 2959 125 2959 1555 2960 1627 2960 367 2960 601 2961 542 2961 650 2961 1428 2962 1048 2962 898 2962 1399 2963 1018 2963 1117 2963 1514 2964 696 2964 698 2964 1510 2965 1396 2965 952 2965 1247 2966 373 2966 374 2966 1240 2967 1241 2967 438 2967 739 2968 169 2968 1684 2968 606 2969 260 2969 1520 2969 1199 2970 182 2970 1033 2970 88 2971 681 2971 788 2971 716 2972 1210 2972 1028 2972 402 2973 401 2973 149 2973 1335 2974 543 2974 542 2974 287 2975 1087 2975 326 2975 673 2976 548 2976 227 2976 774 2977 1555 2977 710 2977 1563 2978 1638 2978 1702 2978 458 2979 1612 2979 908 2979 99 2980 1244 2980 1246 2980 1228 2981 229 2981 231 2981 597 2982 547 2982 596 2982 926 2983 927 2983 690 2983 1327 2984 11 2984 1328 2984 1191 2985 277 2985 865 2985 127 2986 685 2986 128 2986 1711 2987 1709 2987 154 2987 374 2988 285 2988 1749 2988 1395 2989 1338 2989 184 2989 931 2990 930 2990 1016 2990 465 2991 635 2991 466 2991 1388 2992 991 2992 77 2992 469 2993 1288 2993 1045 2993 1206 2994 360 2994 1794 2994 1103 2995 186 2995 341 2995 18 2996 20 2996 979 2996 8 2997 742 2997 677 2997 1294 2998 1211 2998 1579 2998 1147 2999 373 2999 351 2999 355 3000 1751 3000 958 3000 1372 3001 1200 3001 265 3001 1809 3002 265 3002 264 3002 249 3003 1814 3003 1037 3003 1458 3004 1635 3004 489 3004 339 3005 928 3005 1505 3005 567 3006 1199 3006 774 3006 1219 3007 1278 3007 249 3007 327 3008 113 3008 1265 3008 225 3009 1620 3009 1721 3009 719 3010 718 3010 1522 3010 1630 3011 688 3011 565 3011 439 3012 649 3012 278 3012 1342 3013 1332 3013 1286 3013 920 3014 922 3014 1260 3014 1118 3015 1097 3015 1099 3015 1041 3016 1523 3016 1269 3016 873 3017 1273 3017 1508 3017 1755 3018 571 3018 1760 3018 1065 3019 1465 3019 1066 3019 301 3020 300 3020 1011 3020 825 3021 827 3021 290 3021 334 3022 624 3022 16 3022 1258 3023 188 3023 187 3023 202 3024 881 3024 167 3024 614 3025 613 3025 889 3025 998 3026 999 3026 1531 3026 553 3027 552 3027 1296 3027 1145 3028 4 3028 1655 3028 1237 3029 560 3029 559 3029 1207 3030 3 3030 886 3030 1135 3031 548 3031 672 3031 880 3032 855 3032 1109 3032 496 3033 969 3033 497 3033 653 3034 950 3034 1501 3034 1645 3035 1342 3035 1285 3035 1069 3036 1070 3036 633 3036 992 3037 59 3037 75 3037 1573 3038 1648 3038 1223 3038 1477 3039 1043 3039 71 3039 172 3040 614 3040 204 3040 70 3041 399 3041 1678 3041 819 3042 1748 3042 1446 3042 153 3043 1231 3043 1566 3043 1605 3044 1604 3044 1578 3044 1701 3045 559 3045 558 3045 787 3046 247 3046 809 3046 477 3047 834 3047 836 3047 70 3048 69 3048 1193 3048 598 3049 518 3049 293 3049 800 3050 1208 3050 189 3050 1123 3051 1122 3051 1379 3051 1701 3052 1435 3052 559 3052 290 3053 827 3053 461 3053 241 3054 632 3054 242 3054 1183 3055 1421 3055 1184 3055 1315 3056 975 3056 976 3056 834 3057 1663 3057 835 3057 210 3058 1216 3058 332 3058 53 3059 1347 3059 1346 3059 1602 3060 555 3060 1661 3060 1251 3061 1556 3061 862 3061 1487 3062 1560 3062 1725 3062 1810 3063 334 3063 1659 3063 1742 3064 1272 3064 873 3064 399 3065 393 3065 619 3065 666 3066 117 3066 116 3066 934 3067 245 3067 244 3067 902 3068 1447 3068 485 3068 787 3069 1433 3069 247 3069 214 3070 223 3070 225 3070 108 3071 595 3071 1726 3071 1144 3072 298 3072 1110 3072 1517 3073 1179 3073 1654 3073 815 3074 817 3074 747 3074 665 3075 610 3075 932 3075 593 3076 1770 3076 671 3076 1084 3077 692 3077 990 3077 927 3078 1422 3078 1731 3078 1108 3079 880 3079 1109 3079 1482 3080 538 3080 1712 3080 426 3081 425 3081 1084 3081 1263 3082 1520 3082 1744 3082 38 3083 37 3083 1306 3083 1358 3084 1357 3084 1266 3084 512 3085 1489 3085 513 3085 942 3086 130 3086 129 3086 1670 3087 391 3087 1708 3087 1336 3088 759 3088 55 3088 1502 3089 923 3089 1133 3089 1736 3090 250 3090 870 3090 918 3091 1686 3091 1371 3091 552 3092 1421 3092 1183 3092 754 3093 759 3093 885 3093 1563 3094 1565 3094 290 3094 765 3095 446 3095 448 3095 1187 3096 926 3096 1319 3096 13 3097 591 3097 1646 3097 886 3098 1499 3098 1560 3098 654 3099 1501 3099 1312 3099 1047 3100 454 3100 618 3100 1255 3101 1065 3101 1064 3101 203 3102 1290 3102 718 3102 1726 3103 378 3103 380 3103 197 3104 1243 3104 1593 3104 540 3105 731 3105 1614 3105 1102 3106 210 3106 1103 3106 1060 3107 1020 3107 299 3107 1019 3108 1018 3108 1675 3108 842 3109 844 3109 702 3109 281 3110 283 3110 1597 3110 1272 3111 1017 3111 1019 3111 249 3112 251 3112 150 3112 431 3113 1027 3113 1546 3113 1367 3114 185 3114 500 3114 775 3115 1329 3115 776 3115 1254 3116 1049 3116 1022 3116 1715 3117 1686 3117 1696 3117 45 3118 765 3118 448 3118 923 3119 925 3119 1133 3119 1700 3120 371 3120 370 3120 1121 3121 1152 3121 1334 3121 468 3122 470 3122 475 3122 62 3123 1028 3123 1210 3123 1175 3124 1603 3124 1390 3124 1511 3125 1424 3125 1055 3125 857 3126 394 3126 1173 3126 35 3127 961 3127 1590 3127 1704 3128 1683 3128 1582 3128 416 3129 906 3129 895 3129 838 3130 1414 3130 938 3130 1737 3131 1329 3131 775 3131 980 3132 1472 3132 493 3132 960 3133 1267 3133 934 3133 1462 3134 1471 3134 1192 3134 86 3135 85 3135 649 3135 268 3136 1382 3136 1325 3136 765 3137 661 3137 446 3137 553 3138 789 3138 554 3138 192 3139 194 3139 1344 3139 1166 3140 901 3140 315 3140 283 3141 336 3141 319 3141 1622 3142 539 3142 1737 3142 309 3143 522 3143 310 3143 1807 3144 1733 3144 291 3144 361 3145 1496 3145 359 3145 1177 3146 1176 3146 1632 3146 371 3147 1567 3147 372 3147 184 3148 1338 3148 1185 3148 1011 3149 607 3149 301 3149 1127 3150 1735 3150 454 3150 565 3151 903 3151 794 3151 1328 3152 11 3152 1720 3152 132 3153 38 3153 133 3153 254 3154 368 3154 519 3154 514 3155 67 3155 725 3155 1781 3156 20 3156 439 3156 1576 3157 1222 3157 1628 3157 1573 3158 1668 3158 1648 3158 342 3159 1653 3159 1290 3159 1630 3160 565 3160 1701 3160 555 3161 856 3161 1135 3161 1271 3162 1296 3162 1442 3162 1707 3163 1730 3163 344 3163 1111 3164 1219 3164 810 3164 236 3165 699 3165 234 3165 1424 3166 1416 3166 435 3166 659 3167 1264 3167 1767 3167 1118 3168 1117 3168 1225 3168 1177 3169 1632 3169 1288 3169 967 3170 1104 3170 377 3170 465 3171 428 3171 831 3171 720 3172 104 3172 453 3172 349 3173 939 3173 838 3173 509 3174 412 3174 414 3174 1579 3175 1753 3175 1189 3175 1774 3176 752 3176 1775 3176 418 3177 1405 3177 419 3177 1775 3178 752 3178 1776 3178 767 3179 1005 3179 1240 3179 548 3180 900 3180 1516 3180 1274 3181 1636 3181 1394 3181 178 3182 977 3182 179 3182 682 3183 90 3183 1007 3183 821 3184 248 3184 238 3184 1778 3185 1777 3185 883 3185 1778 3186 883 3186 1780 3186 1470 3187 69 3187 784 3187 1780 3188 883 3188 1782 3188 1782 3189 883 3189 878 3189 308 3190 523 3190 311 3190 1782 3191 878 3191 1783 3191 11 3192 10 3192 1317 3192 907 3193 1497 3193 908 3193 1159 3194 1697 3194 803 3194 1784 3195 1783 3195 863 3195 1021 3196 337 3196 1734 3196 14 3197 822 3197 989 3197 1784 3198 863 3198 1785 3198 192 3199 1344 3199 1345 3199 1786 3200 1785 3200 845 3200 1152 3201 505 3201 1249 3201 1786 3202 845 3202 1815 3202 1786 3203 1815 3203 1787 3203 1787 3204 1815 3204 1756 3204 531 3205 1738 3205 1233 3205 28 3206 1498 3206 29 3206 905 3207 603 3207 906 3207 493 3208 1649 3208 494 3208 1098 3209 1024 3209 1023 3209 289 3210 791 3210 790 3210 1509 3211 952 3211 525 3211 1757 3212 839 3212 1758 3212 1813 3213 1143 3213 1747 3213 1737 3214 775 3214 777 3214 1253 3215 731 3215 540 3215 693 3216 62 3216 64 3216 603 3217 605 3217 895 3217 43 3218 1519 3218 1357 3218 249 3219 1278 3219 1814 3219 495 3220 200 3220 270 3220 1762 3221 1761 3221 772 3221 1762 3222 772 3222 1816 3222 1762 3223 1816 3223 1764 3223 530 3224 1184 3224 396 3224 1481 3225 689 3225 657 3225 1764 3226 1816 3226 1765 3226 321 3227 323 3227 577 3227 194 3228 138 3228 1679 3228 383 3229 1057 3229 84 3229 1766 3230 1765 3230 1365 3230 1463 3231 1401 3231 1810 3231 991 3232 992 3232 77 3232 1766 3233 1365 3233 1769 3233 1769 3234 1365 3234 756 3234 855 3235 616 3235 986 3235 1217 3236 1021 3236 1734 3236 1769 3237 756 3237 1771 3237 1771 3238 756 3238 755 3238 1794 3239 123 3239 1468 3239 1771 3240 755 3240 1773 3240 769 3241 397 3241 767 3241 376 3242 162 3242 161 3242 1532 3243 376 3243 1531 3243 1773 3244 753 3244 1774 3244 1496 3245 1062 3245 359 3245 621 3246 1552 3246 317 3246 1774 3247 753 3247 752 3247 778 3248 1739 3248 779 3248 1111 3249 890 3249 1219 3249 629 3250 487 3250 465 3250 1696 3251 1686 3251 918 3251 216 3252 106 3252 1809 3252 797 3253 1225 3253 99 3253 1372 3254 814 3254 1200 3254 216 3255 1809 3255 264 3255 1665 3256 1479 3256 1478 3256 711 3257 712 3257 1729 3257 811 3258 411 3258 1450 3258 589 3259 807 3259 590 3259 257 3260 586 3260 1406 3260 1508 3261 1675 3261 860 3261 837 3262 938 3262 549 3262 524 3263 526 3263 1688 3263 338 3264 337 3264 1021 3264 742 3265 678 3265 677 3265 822 3266 13 3266 173 3266 586 3267 361 3267 587 3267 1515 3268 1608 3268 1702 3268 1042 3269 91 3269 947 3269 777 3270 776 3270 668 3270 1794 3271 670 3271 1206 3271 1381 3272 598 3272 630 3272 542 3273 486 3273 1800 3273 558 3274 1148 3274 385 3274 403 3275 1807 3275 460 3275 885 3276 1337 3276 882 3276 932 3277 628 3277 1429 3277 459 3278 1221 3278 762 3278 430 3279 676 3279 1028 3279 1265 3280 1237 3280 1435 3280 286 3281 384 3281 284 3281 601 3282 1141 3282 542 3282 655 3283 190 3283 1209 3283 1287 3284 1220 3284 249 3284 34 3285 612 3285 611 3285 1581 3286 957 3286 1636 3286 547 3287 1644 3287 1711 3287 1412 3288 804 3288 1413 3288 1318 3289 1047 3289 307 3289 222 3290 387 3290 386 3290 261 3291 655 3291 262 3291 1424 3292 435 3292 1055 3292 459 3293 1088 3293 1515 3293 1620 3294 225 3294 451 3294 110 3295 225 3295 1721 3295 1528 3296 1529 3296 781 3296 1494 3297 1692 3297 797 3297 820 3298 1403 3298 1236 3298 1619 3299 296 3299 548 3299 574 3300 1583 3300 575 3300 657 3301 689 3301 940 3301 690 3302 927 3302 1731 3302 1498 3303 1312 3303 642 3303 363 3304 831 3304 364 3304 1330 3305 608 3305 9 3305 905 3306 922 3306 603 3306 417 3307 409 3307 811 3307 1657 3308 811 3308 1449 3308 1262 3309 429 3309 428 3309 1690 3310 735 3310 1674 3310 1614 3311 956 3311 609 3311 50 3312 52 3312 322 3312 1378 3313 289 3313 1492 3313 1130 3314 1134 3314 1583 3314 1573 3315 1484 3315 1668 3315 982 3316 383 3316 1587 3316 717 3317 1058 3317 1689 3317 170 3318 261 3318 263 3318 1444 3319 187 3319 186 3319 1708 3320 391 3320 314 3320 1178 3321 637 3321 70 3321 1451 3322 1538 3322 728 3322 1392 3323 1396 3323 1510 3323 1637 3324 501 3324 1465 3324 1776 3325 752 3325 884 3325 1776 3326 884 3326 1777 3326 1538 3327 164 3327 166 3327 1738 3328 249 3328 861 3328 403 3329 1733 3329 1807 3329 1777 3330 884 3330 883 3330 1273 3331 1019 3331 1508 3331 610 3332 609 3332 971 3332 938 3333 572 3333 549 3333 437 3334 887 3334 1083 3334 1595 3335 1233 3335 502 3335 1241 3336 552 3336 1445 3336 810 3337 809 3337 1320 3337 1043 3338 135 3338 137 3338 1783 3339 878 3339 863 3339 1598 3340 1115 3340 862 3340 916 3341 657 3341 656 3341 784 3342 68 3342 108 3342 1663 3343 1348 3343 1003 3343 949 3344 923 3344 1502 3344 1785 3345 863 3345 845 3345 735 3346 1690 3346 734 3346 998 3347 1531 3347 376 3347 832 3348 831 3348 428 3348 461 3349 291 3349 290 3349 1093 3350 968 3350 1199 3350 380 3351 1582 3351 1682 3351 1756 3352 1815 3352 839 3352 652 3353 654 3353 1311 3353 1025 3354 158 3354 403 3354 1756 3355 839 3355 1757 3355 647 3356 1037 3356 927 3356 722 3357 660 3357 723 3357 578 3358 1649 3358 969 3358 1758 3359 839 3359 771 3359 1758 3360 771 3360 1759 3360 1175 3361 1177 3361 944 3361 1759 3362 771 3362 1761 3362 101 3363 100 3363 727 3363 1628 3364 1222 3364 105 3364 1761 3365 771 3365 772 3365 1293 3366 1188 3366 579 3366 1702 3367 1638 3367 1515 3367 564 3368 1435 3368 1701 3368 1745 3369 642 3369 1645 3369 735 3370 1096 3370 1617 3370 808 3371 730 3371 393 3371 900 3372 207 3372 83 3372 1765 3373 1816 3373 798 3373 1575 3374 189 3374 191 3374 1220 3375 843 3375 1667 3375 1765 3376 798 3376 1365 3376 508 3377 1658 3377 1641 3377 1605 3378 1725 3378 795 3378 647 3379 1187 3379 370 3379 783 3380 782 3380 693 3380 1158 3381 1811 3381 504 3381 1601 3382 50 3382 322 3382 1563 3383 1670 3383 1638 3383 859 3384 861 3384 1722 3384 813 3385 1260 3385 1375 3385 1375 3386 1260 3386 1352 3386 1676 3387 1666 3387 1308 3387 1656 3388 1632 3388 1377 3388 1773 3389 755 3389 753 3389 1556 3390 1598 3390 862 3390 1154 3391 1153 3391 714 3391 1495 3392 1675 3392 1018 3392 1657 3393 1449 3393 1218 3393 240 3394 215 3394 97 3394 677 3395 679 3395 1430 3395 1140 3396 739 3396 916 3396 736 3397 82 3397 737 3397 818 3398 530 3398 490 3398 1274 3399 1394 3399 591 3399 725 3400 1410 3400 514 3400 1594 3401 1168 3401 1167 3401 1814 3402 1278 3402 851 3402 1440 3403 1484 3403 1128 3403 1049 3404 1023 3404 1022 3404 1733 3405 403 3405 158 3405 1687 3406 1092 3406 840 3406 1155 3407 714 3407 1153 3407 3 3408 1207 3408 4 3408 1526 3409 65 3409 515 3409 854 3410 1550 3410 73 3410 726 3411 1490 3411 879 3411 1570 3412 1569 3412 410 3412 860 3413 1738 3413 861 3413 484 3414 483 3414 1436 3414 479 3415 478 3415 94 3415 204 3416 206 3416 799 3416 155 3417 157 3417 1227 3417 1702 3418 1752 3418 1000 3418 269 3419 1631 3419 1013 3419 1247 3420 1749 3420 1148 3420 897 3421 1570 3421 409 3421 807 3422 730 3422 808 3422 1300 3423 177 3423 179 3423 307 3424 1208 3424 1318 3424 1002 3425 482 3425 484 3425 1491 3426 1300 3426 1299 3426 1384 3427 1616 3427 1385 3427 1565 3428 825 3428 290 3428 1812 3429 525 3429 524 3429 67 3430 66 3430 1490 3430 426 3431 1492 3431 538 3431 1037 3432 1036 3432 1731 3432 981 3433 980 3433 1057 3433 929 3434 1681 3434 1194 3434 1712 3435 538 3435 1571 3435 212 3436 96 3436 1216 3436 1135 3437 875 3437 548 3437 396 3438 1184 3438 1005 3438 1132 3439 1721 3439 1620 3439 558 3440 1630 3440 1701 3440 1221 3441 827 3441 760 3441 411 3442 1453 3442 1450 3442 1175 3443 944 3443 1603 3443 483 3444 1314 3444 220 3444 313 3445 312 3445 1347 3445 1608 3446 698 3446 1001 3446 1413 3447 804 3447 803 3447 745 3448 1492 3448 854 3448 160 3449 1733 3449 158 3449 416 3450 895 3450 897 3450 1209 3451 305 3451 655 3451 636 3452 842 3452 1071 3452 1409 3453 376 3453 1232 3453 1655 3454 1077 3454 1145 3454 1532 3455 1122 3455 376 3455 749 3456 1174 3456 750 3456 520 3457 519 3457 22 3457 1215 3458 243 3458 1214 3458 63 3459 1517 3459 1380 3459 1488 3460 1369 3460 1606 3460 161 3461 1232 3461 376 3461 220 3462 222 3462 386 3462 1312 3463 1331 3463 642 3463 1150 3464 859 3464 1722 3464 1150 3465 1722 3465 221 3465 888 3466 890 3466 1370 3466 1157 3467 1322 3467 1141 3467 1081 3468 900 3468 83 3468 339 3469 1506 3469 1639 3469 1768 3470 1740 3470 581 3470 1206 3471 976 3471 648 3471 896 3472 1570 3472 897 3472 1669 3473 977 3473 178 3473 230 3474 1244 3474 99 3474 1133 3475 925 3475 749 3475 835 3476 1003 3476 444 3476 945 3477 475 3477 476 3477 192 3478 1142 3478 995 3478 403 3479 405 3479 1662 3479 1655 3480 4 3480 909 3480 1352 3481 1260 3481 922 3481 915 3482 1341 3482 916 3482 467 3483 1606 3483 1369 3483 274 3484 276 3484 327 3484 934 3485 1267 3485 245 3485 471 3486 125 3486 1687 3486 968 3487 182 3487 1199 3487 1562 3488 330 3488 824 3488 347 3489 346 3489 509 3489 1069 3490 633 3490 580 3490 1731 3491 1718 3491 690 3491 108 3492 1726 3492 1425 3492 137 3493 159 3493 158 3493 170 3494 420 3494 1575 3494 1731 3495 675 3495 1718 3495 1688 3496 561 3496 1805 3496 1441 3497 195 3497 1271 3497 127 3498 1456 3498 685 3498 1037 3499 1814 3499 851 3499 212 3500 1216 3500 210 3500 1436 3501 220 3501 386 3501 1407 3502 1408 3502 1428 3502 185 3503 184 3503 499 3503 1511 3504 1303 3504 1742 3504 383 3505 84 3505 86 3505 231 3506 230 3506 805 3506 456 3507 888 3507 843 3507 995 3508 1813 3508 765 3508 765 3509 1813 3509 1747 3509 1754 3510 355 3510 959 3510 1121 3511 1120 3511 1152 3511 1687 3512 124 3512 1092 3512 1482 3513 426 3513 538 3513 55 3514 1347 3514 53 3514 1643 3515 1709 3515 1711 3515 1072 3516 1725 3516 1560 3516 634 3517 635 3517 1374 3517 298 3518 1370 3518 890 3518 269 3519 105 3519 104 3519 1037 3520 1731 3520 1422 3520 769 3521 768 3521 1578 3521 473 3522 33 3522 283 3522 761 3523 1026 3523 696 3523 1720 3524 1317 3524 1395 3524 1625 3525 255 3525 257 3525 1334 3526 1024 3526 1121 3526 192 3527 1345 3527 80 3527 1662 3528 1640 3528 1443 3528 297 3529 572 3529 227 3529 1479 3530 407 3530 406 3530 498 3531 1448 3531 902 3531 658 3532 1380 3532 1297 3532 346 3533 329 3533 509 3533 633 3534 545 3534 597 3534 1041 3535 1269 3535 91 3535 992 3536 75 3536 77 3536 388 3537 1226 3537 1313 3537 457 3538 618 3538 454 3538 1734 3539 324 3539 295 3539 1651 3540 1540 3540 1539 3540 670 3541 1652 3541 1205 3541 1139 3542 428 3542 427 3542 1407 3543 1557 3543 588 3543 1605 3544 1487 3544 1725 3544 1800 3545 486 3545 485 3545 374 3546 1749 3546 1247 3546 254 3547 369 3547 368 3547 990 3548 1087 3548 287 3548 1299 3549 1301 3549 1138 3549 901 3550 948 3550 653 3550 714 3551 1574 3551 1524 3551 441 3552 1413 3552 232 3552 150 3553 149 3553 249 3553 63 3554 717 3554 1517 3554 337 3555 324 3555 1734 3555 1217 3556 294 3556 1061 3556 936 3557 1480 3557 1606 3557 449 3558 293 3558 325 3558 1747 3559 766 3559 765 3559 862 3560 1115 3560 846 3560 1537 3561 1536 3561 304 3561 609 3562 544 3562 1614 3562 193 3563 1220 3563 1667 3563 721 3564 1460 3564 276 3564 576 3565 1763 3565 592 3565 1815 3566 845 3566 839 3566 921 3567 449 3567 1712 3567 1179 3568 1140 3568 916 3568 743 3569 744 3569 1530 3569 999 3570 1360 3570 1532 3570 1513 3571 1512 3571 414 3571 1040 3572 1489 3572 1041 3572 1272 3573 1019 3573 1273 3573 1270 3574 1167 3574 553 3574 981 3575 1229 3575 982 3575 891 3576 893 3576 493 3576 776 3577 185 3577 1367 3577 866 3578 1268 3578 867 3578 1727 3579 988 3579 989 3579 470 3580 469 3580 1044 3580 557 3581 223 3581 869 3581 577 3582 757 3582 132 3582 642 3583 1332 3583 1342 3583 979 3584 358 3584 86 3584 463 3585 1624 3585 1 3585 1583 3586 1134 3586 866 3586 1816 3587 772 3587 798 3587 1658 3588 508 3588 1518 3588 1355 3589 892 3589 891 3589 1565 3590 484 3590 1436 3590 1317 3591 972 3591 1395 3591 1514 3592 1608 3592 1515 3592

+
+
+ 1 +
+
+ + + + 7.481132 -6.50764 5.343665 + 0 0 1 46.69194 + 0 1 0 0.619768 + 1 0 0 63.5593 + 1 1 1 + + + + 4.076245 1.005454 5.903862 + 0 0 1 106.9363 + 0 1 0 3.163707 + 1 0 0 37.26105 + 1 1 1 + + + + 0 0 0 + 0 0 1 0 + 0 1 0 0 + 1 0 0 0 + 1 1 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_distal/bt_2p/th_distal_bt_2p_adapter.dae b/URDFs/sr_description/meshes/components/th_distal/bt_2p/th_distal_bt_2p_adapter.dae new file mode 100644 index 0000000..eaf49f4 --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_distal/bt_2p/th_distal_bt_2p_adapter.dae @@ -0,0 +1,235 @@ + + + + + + Blender User + Blender 2.65.0 r52920 + + 2012-12-14T09:32:52 + 2012-12-14T09:32:52 + + Y_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0.000999987 + 1 + 0.1 + 0.1 + 1 + 1 + 1 + 2 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 2880 + 2 + 30.002 + 1.000799 + 0.04999995 + 29.99998 + 1 + 2 + 0 + 0 + 1 + 1 + 1 + 1 + 8192 + 1 + 1 + 0 + 1 + 1 + 1 + 3 + 0 + 0 + 0 + 0 + 45 + 0 + 1 + 1 + 1 + 3 + 0.15 + 75 + 1 + 1 + 0 + 1 + 1 + 0 + + + + + + + + + + + + 0.0 0.0 0.0 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + 8.027336 -0.03454494 14.40869 8.026293 -4.06507e-6 14.40812 7.41194 -4.06507e-6 14.25034 8.291929 -0.5260002 14.60398 8.281468 -0.5201291 14.59285 8.049442 -3.999997 14.42116 8.516124 -3.999997 14.88784 8.516124 -0.5983304 14.88784 8.471599 -0.5983304 14.8163 8.39643 -0.5846511 14.71516 8.167757 -0.4046153 14.49852 8.139974 -0.3555756 14.47994 8.072218 -0.2359788 14.43463 8.686944 -4.06507e-6 15.52535 8.682376 -4.06507e-6 15.41757 8.682376 -0.5983304 15.41757 8.056617 -0.1659433 14.42561 8.049308 -0.1331459 14.42139 7.41194 -3.999997 14.25034 8.686944 -3.999997 15.52535 8.516124 -3.999997 16.16285 8.516124 -4.06507e-6 16.16285 8.049442 -3.999997 16.62953 8.049442 -4.06507e-6 16.62953 7.41194 -3.999997 16.80035 7.41194 -4.06507e-6 16.80035 6.774438 -3.999997 16.62953 6.774438 -4.06507e-6 16.62953 6.307756 -3.999997 16.16285 6.307756 -4.06507e-6 16.16285 6.136937 -3.999997 15.52535 6.136937 -4.06507e-6 15.52535 6.307756 -3.999997 14.88784 6.307756 -4.06507e-6 14.88784 6.774438 -3.999997 14.42116 6.774438 -4.06507e-6 14.42116 9.645691 -0.5983304 14.53598 9.513183 -0.5983304 14.89215 9.502134 -6.298337 14.98523 9.645691 -6.298337 14.53598 9.97918 -6.298337 14.20249 9.97918 -0.5983304 14.20249 10.42843 -6.298337 14.05894 10.42843 -0.5983304 14.05894 10.8935 -6.298337 14.13725 10.8935 -0.5983304 14.13725 11.27096 -6.298337 14.42001 11.27096 -0.5983304 14.42001 9.863204 -4.06507e-6 15.82776 9.863204 -6.298337 15.82776 9.580447 -6.298337 15.4503 9.580447 -4.06507e-6 15.4503 9.502134 -4.06507e-6 14.98523 9.513183 -4.06507e-6 14.89215 9.863204 -6.298337 23.61225 9.863204 -4.06507e-6 23.61225 10.26925 -0.5983304 11.8465 10.36772 -0.5983304 10.93136 10.10163 -0.5281161 10.95806 8.619411 -0.3594052 14.07296 8.775657 -0.5281161 14.19388 8.973321 -0.5983304 14.33983 9.807243 -4.06507e-6 7.688572 9.808062 -4.06507e-6 8.666391 9.829289 -0.1678656 8.662921 9.813673 -4.06507e-6 7.232932 9.822136 -0.09677219 7.211144 9.829937 -0.1343082 7.191004 9.836359 -0.1532475 7.174326 9.965791 -0.3884624 6.83177 9.932785 -0.3491383 6.920594 9.934729 -0.3594052 7.162122 9.87207 -0.2510737 7.081357 9.862615 -0.2307038 7.106106 10.06908 -0.4779141 6.546998 10.13092 -0.5281161 7.138862 10.15499 -0.5273115 6.301743 10.15685 -0.5279373 6.296195 10.41535 -0.5983304 6.90968 10.36353 -0.5928915 6.754949 10.31181 -0.5874525 6.600516 10.3086 -0.5844872 6.30274 10.41789 -0.59538 5.49709 10.34356 -0.5861114 5.733593 10.30676 -0.5789291 5.847939 8.543199 -0.1678656 14.01399 8.516117 -4.06507e-6 14.00628 9.777924 -4.06507e-6 11.09323 9.758553 -4.06507e-6 11.33155 9.808918 -0.1678656 10.9843 8.961617 -0.1678656 13.55804 8.848591 -4.06507e-6 13.65862 8.523441 -4.06507e-6 13.99862 9.45965 -4.06507e-6 12.63271 9.23474 -4.06507e-6 13.09075 9.264557 -0.1678656 13.10247 9.186743 -4.06507e-6 13.18848 8.933066 -4.06507e-6 13.54117 9.713805 -0.1678656 11.82998 9.68018 -4.06507e-6 11.82774 9.652345 -4.06507e-6 12.00396 9.810081 -0.3594052 11.8331 9.046084 -0.3594052 13.60438 9.355104 -0.3594052 13.13539 9.764365 -0.5281161 12.71686 9.571492 -0.3594052 12.67424 9.477413 -0.1678656 12.65345 10.24469 -0.5983304 12.07477 10.00748 -0.5281161 11.8395 9.904882 -0.3594052 10.9757 9.924656 -0.3594052 8.649238 9.219272 -0.5281161 13.69939 9.540742 -0.5281161 13.2029 9.894571 -0.5983304 13.1213 10.01255 -0.5983304 12.76865 9.355156 -0.5983304 13.97721 9.450933 -0.5983304 13.82524 9.789004 -0.5983304 13.28881 10.12019 -0.5281161 8.621184 9.808666 -4.06507e-6 9.390007 9.809768 -4.06507e-6 9.833575 9.780622 -4.06507e-6 10.98639 10.39149 -0.5983304 10.71041 10.40092 -0.5983304 9.017369 10.40391 -0.5983304 8.581215 10.41401 -0.5983304 7.10572 9.839041 -0.1678656 7.173466 9.841247 -0.1676719 7.161623 10.3632 -2.088953 25.37427 10.3632 -2.139006 25.44435 10.3632 -6.298337 25.37427 10.3632 -2.545897 26.40046 10.3632 -6.298337 30.5858 10.3632 -2.545897 27.43955 10.3632 -0.4190843 29.48574 10.3632 -0.2046416 29.57571 10.3632 -0.05408036 29.75296 10.3632 -2.139006 28.39566 10.3632 -1.390193 29.11607 10.3632 -4.06507e-6 30.5858 10.3632 -4.06507e-6 29.97915 -5.866098 -3.999997 12.75001 -5.781444 -4.121353 12.75001 -5.220781 -3.999997 12.75001 -5.062478 -4.977856 12.75001 -4.21797 -5.710874 12.75001 -0.03865581 -7.09923 12.75001 1.076599 -7.017244 12.75001 -5.220781 -4.06507e-6 12.75001 2.165159 -6.761198 12.75001 2.780398 -6.497998 12.75001 -3.268848 -6.302227 12.75001 -2.238663 -6.737236 12.75001 -1.152957 -7.005115 12.75001 4.052987 -5.324576 12.75001 4.052987 -4.06507e-6 12.75001 3.810217 -5.652581 12.75001 3.335325 -6.124039 12.75001 13.27742 -6.498341 28.08579 13.27742 -6.298337 28.08579 10.07031 -6.298337 31.2929 10.07031 -4.06507e-6 31.2929 9.363203 -4.06507e-6 32.00001 9.363203 -6.498341 32.00001 -7.101016 -4.06507e-6 12.75001 -7.024879 -1.035381 12.75001 -6.515491 -4.06507e-6 12.75001 -6.774964 -2.125357 12.75001 -6.515491 -2.821956 12.75001 -7.853734 -1.881112 13.75001 -7.729048 -2.4249 13.75001 -7.656427 -2.402101 13.36732 -6.474006 -3.406141 12.77342 -6.48656 -3.229354 12.76633 -6.699624 -3.333126 12.82613 -7.14008 -2.239991 12.82613 -6.323876 -3.999997 12.82631 -6.325336 -3.999997 12.82661 -6.357151 -4.531909 13.0429 -6.345438 -3.999997 12.83386 -6.990055 -3.477682 13.0429 -6.362627 -3.936846 12.82647 -6.397182 -3.809933 12.81163 -5.926835 -3.999997 12.75127 -6.09302 -4.343544 12.82613 -5.980174 -3.999997 12.75448 -8.101018 -4.06507e-6 13.75001 -8.01416 -1.181428 13.75001 -8.049512 -4.06507e-6 13.43323 -7.938856 -1.170297 13.36732 -7.724407 -1.138646 13.0429 -7.891188 -4.06507e-6 13.13712 -8.016641 -4.06507e-6 13.37174 -7.403465 -1.091261 12.82613 -7.745656 -4.06507e-6 12.98552 -7.804277 -4.06507e-6 13.04659 -7.126825 -4.06507e-6 12.75034 -7.456268 -4.06507e-6 12.81523 -7.481406 -4.06507e-6 12.83003 -7.18412 -3.574286 13.36732 -7.252264 -3.608201 13.75001 -7.217074 -3.666807 13.75001 -6.533648 -4.657779 13.36732 -6.595622 -4.701976 13.75001 -5.721139 -5.625729 13.36732 -6.148787 -5.234291 13.75001 -5.775402 -5.679105 13.75001 -4.766742 -6.454114 13.36732 -4.81196 -6.515343 13.75001 -4.773284 -6.539438 13.75001 -3.694142 -7.122387 13.36732 -3.729182 -7.189963 13.75001 -2.529922 -7.613991 13.36732 -3.109972 -7.451434 13.75001 -2.55392 -7.686232 13.75001 -1.30296 -7.916738 13.36732 -1.31532 -7.991839 13.75001 -1.292618 -7.993762 13.75001 -0.04368495 -8.023102 13.36732 -0.04410219 -8.099218 13.75001 1.21667 -7.930447 13.36732 2.470066 -7.713575 13.75001 2.446858 -7.641081 13.36732 1.228211 -8.005682 13.75001 0.6034501 -8.051609 13.75001 2.380756 -7.434626 13.0429 1.183806 -7.716183 13.0429 -0.04250776 -7.806335 13.0429 -1.267763 -7.702832 13.0429 -2.461585 -7.40828 13.0429 -3.594349 -6.929953 13.0429 -4.637981 -6.279726 13.0429 -5.566592 -5.473707 13.0429 -7.449607 -2.337162 13.0429 2.281842 -7.12565 12.82613 1.134617 -7.39551 12.82613 -0.04074198 -7.481907 12.82613 -1.215088 -7.382725 12.82613 -2.359303 -7.100393 12.82613 -3.445009 -6.641943 12.82613 -4.44528 -6.018732 12.82613 -5.335303 -5.246212 12.82613 9.345217 -4.06507e-6 32.00001 9.345217 -3.325049 32.00001 9.336038 -6.71481 32.00001 9.334592 -6.725003 32.00001 9.35091 -6.68462 32.00001 9.325712 -6.787617 32.00001 9.314126 -6.86929 32.00001 9.345217 -6.650109 32.00001 9.34518 -6.650362 32.00001 -10.19715 -4.06507e-6 21.4168 -10.51365 -4.06507e-6 16.61225 -10.45368 -0.9958636 16.61002 3.623558 -9.886523 16.62046 2.959502 -9.092275 31.06765 2.711539 -10.19787 16.61977 2.345925 -9.259928 31.06861 2.469701 -10.26088 16.61938 4.16853 -9.095956 24.27388 3.761714 -9.824101 16.61872 4.379747 -9.152044 22.07816 4.495306 -9.492595 16.6095 4.873825 -9.28906 16.60322 3.740331 -8.987595 28.44233 3.539158 -8.939896 30.24336 3.447188 -8.918081 31.06673 2.201704 -10.33071 16.61895 2.058302 -9.338518 31.06905 1.278771 -10.50061 16.62248 1.132896 -9.496306 31.07015 1.129148 -10.51391 16.62373 1.132702 -9.49632 31.07015 0.7337608 -9.535898 31.07051 0.3404595 -10.58397 16.63036 -0.2332277 -10.58013 16.63084 -0.1022465 -9.559904 31.07106 -0.1988433 -9.562675 31.07112 -0.6346948 -10.57744 16.63117 -1.195761 -10.5307 16.62809 -1.131924 -9.497453 31.07137 -1.591804 -10.46771 16.6271 -1.334073 -9.463166 31.07134 -2.122151 -10.38337 16.62576 -2.061287 -9.339829 31.07126 -2.924519 -10.17753 16.62903 -2.47364 -9.239186 31.0711 -2.545501 -9.216119 31.07106 -3.034028 -10.14944 16.62947 -3.362338 -8.953918 31.07051 -3.943058 -9.821792 16.63142 -7.505881 -7.335816 16.61063 -7.43434 -7.411067 16.61215 -6.773519 -6.740887 31.06467 -7.241617 -7.604454 16.63227 -7.095049 -7.744749 16.66622 -4.204477 -9.707381 16.62938 -3.710593 -8.80285 31.07012 -4.286142 -9.671632 16.62874 -4.220071 -8.581851 31.06956 -5.102644 -9.249811 16.62092 -4.816661 -8.249913 31.06864 -5.403335 -9.058644 16.62185 -5.044172 -8.123328 31.06828 -5.845646 -8.777429 16.62322 -5.393187 -7.895324 31.06764 -6.512108 -8.266319 16.64071 -5.840326 -7.555832 31.06665 -6.549793 -8.237411 16.6417 -6.138968 -7.329081 31.066 -6.724866 -8.086983 16.64895 -7.087978 -7.751424 16.66766 -7.066461 -7.772331 16.66546 -7.04586 -7.792149 16.6644 -7.579933 -7.257913 16.60905 -6.826671 -6.691624 31.06456 -8.133488 -6.615643 16.60694 -7.454368 -5.983551 31.06377 -8.37298 -6.297309 16.60626 -8.2654 -6.446872 16.60655 -9.109559 -5.164702 16.57739 -9.038115 -5.298216 16.57095 -8.281494 -4.762117 31.0632 -9.036364 -5.301286 16.5707 -9.022707 -5.324383 16.57501 -9.015965 -5.335827 16.5764 -8.81655 -5.660374 16.60119 -8.221487 -4.875649 31.06321 -8.663761 -5.893056 16.60547 -7.704961 -5.656977 31.06355 -7.593336 -5.802457 31.06365 -9.561556 -4.06507e-6 31.06574 -9.509081 -0.9914975 31.06488 -9.470994 -1.237769 31.06478 -10.40149 -1.34619 16.60949 -9.365926 -1.917187 31.06449 -10.30897 -1.967136 16.60856 -9.226399 -2.460186 31.0642 -10.1411 -2.67208 16.6078 -9.133006 -2.82367 31.064 -10.12041 -2.758984 16.60771 -9.018461 -3.1696 31.06372 -9.806903 -3.693629 16.60548 -8.825856 -3.640566 31.06341 -9.696516 -3.947262 16.60473 -8.66008 -4.045908 31.06314 -9.447525 -4.519362 16.60305 -9.365315 -4.686747 16.60043 -10.46617 -0.9980987 16.22056 -10.52663 -4.06507e-6 16.2179 -10.52663 -4.06507e-6 13.5323 -10.51455 -0.3610145 13.403 -10.3358 -1.871724 16.22133 -10.52009 -0.2272169 13.47811 -10.52157 -0.1915584 13.49812 -10.51142 -0.4186671 13.33927 -10.50728 -0.4950951 13.25479 -10.50399 -0.5469661 13.13643 -10.50192 -0.5794655 13.06227 -10.50052 -0.5999993 12.89981 -10.33329 -1.870904 7.659739 -10.50052 -0.5999993 10.04798 -10.35236 -1.783017 7.64959 -10.50064 -0.5982857 10.04745 -10.50069 -0.5975257 9.948451 -10.39438 -1.553152 7.625777 -10.50078 -0.5962591 9.783378 -10.50159 -0.5843978 8.902726 -10.50188 -0.5801212 8.585659 -10.50197 -0.578646 8.252725 -10.50219 -0.5754124 7.525321 -10.37108 -1.696755 7.639628 -9.886811 -3.516782 7.892441 -10.32104 -1.970608 16.22141 -10.02607 -3.078793 7.820753 -10.16805 -2.63222 7.747659 -9.475435 -4.488845 9.552103 -9.485583 -4.467551 9.622488 -9.833159 -3.647808 7.911812 -9.432244 -4.578311 9.397751 -9.090508 -5.230178 8.000006 -9.033876 -5.330179 7.982885 -9.033876 -5.330179 8.93354 -9.222965 -4.988093 8.000006 -9.109484 -5.196218 8.981579 -9.287322 -4.865934 8.000006 -9.350377 -4.743029 8.000006 -9.147482 -5.127523 9.009956 -9.588907 -4.244332 8.000006 -9.303222 -4.835237 9.16723 -9.411359 -4.620914 9.347376 -9.489464 -4.459371 9.754478 -9.834702 -3.648613 16.22436 -10.13182 -2.76411 16.22263 -9.474518 -4.490752 9.88205 -9.427483 -4.588057 10.04383 -9.32845 -4.786153 10.22776 -9.307014 -4.827906 10.25713 -9.121912 -5.173866 10.43877 -9.81761 -3.6995 16.22446 -9.461286 -4.518349 16.22443 -9.033876 -5.330179 10.49575 -9.033876 -5.330179 16.17882 -9.033921 -5.330105 16.18274 -9.075822 -5.256299 16.19136 -9.382295 -4.679535 16.22192 2.470066 -7.713575 31.49876 1.601247 -7.939507 31.49884 0.7892155 -8.060802 31.49892 0.6049551 -8.069519 31.49893 -0.02427619 -8.099307 31.49898 -0.837142 -8.055974 31.49898 -1.117589 -8.021881 31.49897 -3.115865 -7.465158 31.49892 -2.704377 -7.634614 31.49895 -1.923995 -7.867548 31.49897 -1.291441 -7.988605 31.49897 -4.42029 -6.787111 31.49874 -3.457072 -7.324655 31.49888 -3.710429 -7.199664 31.49885 -5.687247 -5.76735 31.49855 -5.079577 -6.308977 31.49865 -4.769126 -6.534119 31.49869 -6.418238 -4.941274 31.49847 -6.159986 -5.243574 31.49849 -5.884948 -5.565543 31.49852 -7.276232 -3.559638 31.49842 -7.216873 -3.666897 31.49843 -6.882096 -4.271884 31.49844 -8.101018 -4.06507e-6 31.49862 -8.073176 -0.6693344 31.49856 -8.044871 -0.950415 31.49855 -7.908711 -1.752977 31.49852 -7.872337 -1.88512 31.49851 -7.69257 -2.538163 31.49848 -7.395985 -3.30377 31.49843 5.052981 -5.602886 13.75001 5.052981 -5.602886 19.20001 5.052981 -4.06507e-6 13.75001 5.052981 -4.06507e-6 19.20001 6.168982 -5.602886 19.20001 6.168982 -4.06507e-6 19.20001 6.068987 -4.06507e-6 23.86087 6.068987 -4.06507e-6 20.20001 5.922039 -2.285961 20.20001 5.933379 -2.196286 25.5311 5.940629 -2.134506 25.44768 5.960156 -1.968075 25.22292 5.995822 -1.614143 24.88305 6.014419 -1.387094 24.72851 6.064033 -0.4190843 24.35428 6.067065 -0.2603721 24.29971 6.067631 -0.2088289 24.259 6.02149 -1.300682 24.6697 6.048431 -0.8554201 24.46534 6.068511 -0.1286457 24.19568 6.068846 -0.05814838 24.08448 6.068935 -0.03877687 24.05392 6.068987 -8.68332e-4 23.89038 5.887275 -2.540875 26.40112 5.484035 -4.534368 20.20001 5.879199 -2.596576 26.82422 5.484035 -4.534368 31.50001 5.881307 -2.582152 27.20967 5.88811 -2.534647 27.43721 5.888437 -2.532829 26.34004 5.904568 -2.417509 25.96731 5.921704 -2.285917 25.70784 6.005136 -1.508002 31.50001 6.068987 -4.06507e-6 31.50001 6.068987 -4.06507e-6 29.97915 6.068637 -0.1095574 29.6668 6.068831 -0.05999612 29.75624 6.068957 -0.02818214 29.81364 6.067683 -0.2078454 29.57931 6.067415 -0.2349506 29.55518 6.064688 -0.3901761 29.49136 6.064033 -0.4190843 29.48574 6.056008 -0.6793182 29.42924 5.905656 -2.28386 31.50001 6.032703 -1.136858 29.25748 6.014352 -1.387481 29.11142 6.00825 -1.470853 29.06284 5.973165 -1.846914 28.74833 5.945911 -2.092634 28.46077 5.940785 -2.133582 28.39241 5.921719 -2.285917 28.13819 5.809677 -3.03239 31.50001 5.914365 -2.344687 28.04011 5.895612 -2.482254 27.68823 8.560298 -4.06507e-6 32.43992 8.560283 -6.997604 32.43986 8.56085 -6.997381 32.43976 8.900194 -6.841574 32.30596 9.120046 -6.73591 32.17696 9.303277 -6.660943 32.03706 9.345061 -6.650139 32.00015 8.123381 -7.172112 32.5162 7.661973 -4.06507e-6 32.49124 7.867893 -7.259626 32.51564 6.874619 -3.061582 32.17334 6.845323 -0.06157565 32.15301 6.845285 -4.06507e-6 32.15299 6.874619 -7.482697 32.17334 6.91699 -7.477899 32.2014 7.024733 -7.463385 32.2661 7.341569 -7.403795 32.40851 7.4857 -7.369478 32.45275 7.663494 -7.318367 32.482 -9.036856 -5.30446 16.53762 -2.05041 -8.384574 31.99792 -2.230259 -8.33093 31.99792 -2.346019 -8.762498 31.86372 -5.416224 -6.727133 31.99729 -5.540403 -6.61682 31.99725 -5.822326 -6.952141 31.86281 -7.340501 -4.556511 31.99687 -7.42499 -4.403908 31.99686 -7.798547 -4.625027 31.86231 -8.204447 -2.707202 31.99695 -8.247788 -2.549369 31.99697 -8.663277 -2.677996 31.86246 2.872085 -8.137901 31.99782 2.671113 -8.209814 31.99757 2.806468 -8.623962 31.8631 2.633316 -8.223344 31.99752 1.9517 -8.857165 31.86336 3.104423 -8.035858 31.99869 3.259895 -8.436014 31.87694 3.267196 -8.454819 31.85808 3.391107 -8.773734 31.53805 -9.363124 -0.9761791 31.52496 -9.413714 -4.06507e-6 31.52511 -9.539323 -4.06507e-6 31.21952 -9.062598 -4.06507e-6 31.8506 -9.188408 -4.06507e-6 31.78088 -9.019757 -0.9401481 31.86261 -9.411665 -4.06507e-6 31.53008 -8.59117 -0.8951764 31.9971 -8.609319 -0.7139187 31.99711 -8.894721 -4.06507e-6 31.94364 -8.638318 -4.06507e-6 31.99722 -8.884045 -1.818288 31.86254 -8.434447 -1.869623 31.99704 -8.457901 -1.731027 31.99704 -8.579301 -1.013685 31.99709 -8.144813 -2.861459 31.99693 -8.554692 -3.006134 31.8624 -7.888684 -3.523994 31.99685 -8.214797 -3.837604 31.8623 -7.826896 -3.656138 31.99685 -7.761056 -3.796954 31.99684 -6.957519 -5.108748 31.99691 -7.308545 -5.366091 31.86238 -6.845484 -5.270292 31.99692 -7.070737 -5.675901 31.86242 -6.731468 -5.403553 31.99694 -6.276207 -5.935628 31.99703 -6.475086 -6.347541 31.86255 -6.167429 -6.046448 31.99706 -6.065155 -6.150637 31.99708 -4.865544 -7.125263 31.99744 -5.114796 -7.488851 31.8631 -4.712554 -7.235859 31.99748 -4.783625 -7.705007 31.86322 -4.550236 -7.329841 31.99752 -3.955091 -7.674386 31.99769 -4.001799 -8.139659 31.86345 -3.807838 -7.746716 31.99772 -3.188568 -8.492176 31.86362 -2.88214 -8.1365 31.9979 -3.031442 -8.075226 31.99788 -3.684814 -7.80714 31.99776 -1.85878 -8.421232 31.99793 -1.95493 -8.857895 31.86375 -1.191015 -8.548964 31.99794 -1.07343 -9.007384 31.86377 -1.021171 -8.569573 31.99794 -0.1886956 -9.069298 31.86372 0.695353 -9.04404 31.86362 0.6608792 -8.599614 31.99785 -0.02585572 -8.631412 31.99794 -0.1793079 -8.623231 31.99794 -0.8921347 -8.585219 31.99795 1.855639 -8.424599 31.99765 1.706866 -8.463104 31.99767 1.07388 -9.006579 31.86355 1.020429 -8.56473 31.9978 0.8411833 -8.591269 31.99783 2.913666 -8.952011 31.52655 3.392664 -8.777757 31.52495 1.115156 -9.349082 31.52799 2.02631 -9.19405 31.52737 0.7222124 -9.387959 31.5282 -0.1957886 -9.41414 31.52855 -1.114311 -9.349872 31.5287 -2.029265 -9.194721 31.52863 -2.435225 -9.095688 31.52854 -3.310072 -8.815039 31.5282 -5.309808 -7.773582 31.52655 -4.96606 -7.997919 31.52692 -4.154513 -8.449037 31.52765 -6.04436 -7.216458 31.5256 -7.340128 -5.891938 31.52432 -6.721849 -6.589029 31.52478 -8.095646 -4.801069 31.524 -7.586951 -5.570386 31.52419 -8.527609 -3.983934 31.52396 -8.880364 -3.120918 31.52429 -8.993077 -2.780277 31.52445 -9.222271 -1.887698 31.52474 -1.053648 -5.103578 10.02528 0.3533117 -5.103578 10.0743 0.3413312 -5.749423 9.72789 -9.172397 -0.1672546 6.574673 -9.158867 -4.06507e-6 6.595795 -9.136814 -4.06507e-6 6.626309 9.01953 -5.05795 4.551388 8.995621 -5.10328 4.547796 8.554919 -5.103578 5.331955 -10.36513 -1.031746 4.340297 -10.09689 -1.046498 4.929001 -9.902941 -1.288314 5.252763 -10.51184 -0.9966533 3.981092 -10.51258 -0.9891729 3.981075 -10.50149 -1.096119 3.981329 -10.26133 -2.474416 3.980954 -10.28417 -2.377067 3.981409 -9.702841 -2.575506 5.146624 -10.32729 -2.181772 3.982052 -10.34757 -2.083842 3.982251 -10.36698 -1.985748 3.982377 -10.38551 -1.887475 3.982437 -10.38958 -1.864795 3.982436 -10.40317 -1.789052 3.982436 -10.41993 -1.690466 3.982383 -10.43581 -1.591731 3.982284 -10.45077 -1.492862 3.982144 -10.46484 -1.393859 3.981972 -10.47798 -1.294721 3.981774 -10.47877 -1.288314 3.98176 -10.4902 -1.195479 3.981558 -9.843173 -3.844816 3.962503 -10.08718 -3.091503 3.974476 -10.16157 -2.861832 3.978127 -10.23538 -2.575208 3.980219 -9.4758 -4.859571 3.929725 -9.630399 -4.374821 3.948561 -9.368682 -3.861074 4.969378 -9.667041 -4.283552 3.950962 -8.868317 -5.77331 4.056803 -8.973511 -5.776872 3.870365 -9.054738 -5.528857 3.902702 -9.279834 -5.474005 3.905851 -9.38871 -5.132635 3.919115 -8.905286 -5.103578 4.723583 -9.152035 -5.505149 3.904063 8.849799 -5.379666 4.525887 8.54828 -5.749423 4.660869 8.813037 -5.446841 4.51948 8.639856 -5.749423 4.488833 9.641638 -3.582213 4.641168 9.538731 -3.859896 4.62687 9.000083 -3.861074 5.609408 9.439064 -4.128833 4.613022 9.368895 -4.284222 4.602714 9.875267 -2.817158 4.670579 9.784324 -3.114973 4.659131 9.321092 -2.575506 5.809482 9.513318 -1.288314 5.929291 10.17716 -1.288299 4.699224 10.16962 -1.34762 4.698707 10.1561 -1.446698 4.697741 10.14168 -1.545642 4.696667 10.11015 -1.743142 4.694173 10.01607 -2.234105 4.685687 9.994691 -2.331768 4.683563 10.09307 -1.841653 4.692743 10.08075 -1.909141 4.691675 10.07511 -1.940016 4.691185 10.05628 -2.038215 4.689493 9.972467 -2.429236 4.681286 9.935907 -2.575148 4.677259 9.542091 -0.9410571 5.947283 9.747846 -1.015816 5.593514 9.807928 -1.028527 5.485028 10.11469 -1.048599 4.891925 10.20553 -1.041595 4.701066 10.2047 -1.049701 4.701014 10.19393 -1.149107 4.700339 10.18224 -1.248423 4.699572 8.93314 -0.1700114 6.896176 8.946484 -0.235502 6.876801 8.594504 -1.288314 7.196823 9.002305 -0.4038851 6.795173 9.018449 -0.4394989 6.771388 9.121901 -0.6112199 6.617035 9.177989 -0.6802421 6.531859 9.352675 -0.8375238 6.259299 9.496769 -0.9245913 6.025197 -9.503322 -0.7818829 6.035908 -9.355987 -0.6150197 6.281304 -9.074579 -1.288314 6.581172 -9.926224 -1.007963 5.265179 -9.840192 -0.9885322 5.434642 -9.614052 -0.870366 5.84491 -9.311649 -0.5473833 6.353351 -9.229029 -0.3779422 6.485544 -9.177978 -0.1988153 6.565945 -8.160377 -5.103578 5.918164 -8.163208 -5.749423 5.306486 -8.587363 -5.763788 4.554751 -7.256301 -5.103578 6.997318 -7.29424 -5.749423 6.449099 -7.862711 -5.749423 5.701614 -6.210702 -5.103578 7.939996 -6.266701 -5.749423 7.451524 -6.993251 -5.749423 6.742727 -5.043971 -5.103578 8.727814 -5.102942 -5.749423 8.291967 -5.987356 -5.749423 7.653261 -3.778862 -5.103578 9.345405 -3.82826 -5.749423 8.952161 -4.86436 -5.749423 8.415537 -2.440045 -5.103578 9.780722 -2.470354 -5.749423 9.417754 -3.645854 -5.749423 9.014704 -1.017573 -5.749423 9.680076 -1.058752 -5.749423 9.678627 -2.355302 -5.749423 9.439016 1.753373 -5.103578 9.926836 3.119235 -5.103578 9.585758 3.009675 -5.749423 9.246948 1.802316 -5.749423 9.568094 1.692665 -5.749423 9.580471 0.3758646 -5.749423 9.729106 4.424264 -5.103578 9.05772 5.643 -5.103578 8.353019 5.4403 -5.749423 8.051647 4.507517 -5.749423 8.630125 4.266952 -5.749423 8.733979 3.189584 -5.749423 9.199094 6.751677 -5.103578 7.485403 7.728664 -5.103578 6.471792 7.44692 -5.749423 6.235138 6.822919 -5.749423 6.94583 6.507126 -5.749423 7.213269 5.727468 -5.749423 7.873554 8.241607 -5.749423 5.136213 7.770051 -5.749423 5.867119 8.130832 -3.861074 6.808557 7.103001 -3.861074 7.874913 5.936635 -3.861074 8.787676 4.654479 -3.861074 9.529046 3.281546 -3.861074 10.08456 1.844605 -3.861074 10.44339 0.3716923 -3.861074 10.59852 -1.10847 -3.861074 10.54695 -2.567018 -3.861074 10.28967 -3.975498 -3.861074 9.831701 -5.30644 -3.861074 9.181973 -6.533878 -3.861074 8.353161 -7.63389 -3.861074 7.36143 -8.585008 -3.861074 6.226121 8.420839 -2.575506 7.051401 7.356351 -2.575506 8.155791 6.148381 -2.575506 9.10111 4.820494 -2.575506 9.868922 3.398595 -2.575506 10.44425 1.910401 -2.575506 10.81588 0.3849469 -2.575506 10.97655 -1.14801 -2.575506 10.92313 -2.658578 -2.575506 10.65668 -4.11729 -2.575506 10.18237 -5.495707 -2.575506 9.50947 -6.766925 -2.575506 8.651098 -7.90617 -2.575506 7.623993 -8.891212 -2.575506 6.448191 7.508059 -1.288314 8.323988 6.275182 -1.288314 9.288804 4.919907 -1.288314 10.07245 3.468683 -1.288314 10.65964 1.9498 -1.288314 11.03893 0.3928892 -1.288314 11.20292 -1.171681 -1.288314 11.1484 -2.713407 -1.288314 10.87645 -4.202204 -1.288314 10.39236 -5.609045 -1.288314 9.705585 -6.906482 -1.288314 8.829509 -8.069219 -1.288314 7.781223 8.918663 -4.06507e-6 6.917142 8.653453 -4.06507e-6 7.246183 7.559558 -4.06507e-6 8.381078 6.318217 -4.06507e-6 9.352511 4.95365 -4.06507e-6 10.14153 3.492472 -4.06507e-6 10.73275 1.963173 -4.06507e-6 11.11464 0.3955863 -4.06507e-6 11.27975 -1.17972 -4.06507e-6 11.22487 -2.732018 -4.06507e-6 10.95105 -4.231023 -4.06507e-6 10.46364 -5.647512 -4.06507e-6 9.772152 -6.953853 -4.06507e-6 8.890067 -8.124563 -4.06507e-6 7.834591 4.999471 -5.588879 13.42725 4.952212 -4.06507e-6 13.37393 4.969483 -5.580936 13.37127 4.969475 -5.580936 13.37126 4.919013 -4.06507e-6 13.25001 4.846116 -5.548243 13.14096 4.735996 -4.06507e-6 13.06699 4.751352 -5.522523 13.05222 4.429062 -4.06507e-6 12.85078 4.430195 -5.433564 12.8383 4.552988 -4.06507e-6 12.88398 4.608688 -5.48378 12.91862 4.7513 -5.522509 13.05217 4.061175 -5.32702 12.75004 4.306709 -5.398829 12.78273 4.430024 -5.433519 12.83822 2.571759 -8.03106 31.97018 1.66702 -8.265515 31.96998 0.8215733 -8.390982 31.96977 -8.129204 -4.06507e-6 31.66412 -8.146974 -4.06507e-6 31.69619 -8.114817 -0.6728064 31.69865 -8.210579 -4.06507e-6 31.81096 -8.26555 -4.06507e-6 31.8599 -8.232774 -0.6826114 31.8653 -8.491258 -4.06507e-6 31.98642 -8.33598 -4.06507e-6 31.92259 -8.407335 -0.6971251 31.97066 -8.438254 -4.06507e-6 31.96463 -8.377971 -0.9898584 31.97069 -8.236418 -1.825694 31.97075 -7.949548 -1.762037 31.69874 -8.086379 -0.9553473 31.69868 -8.011686 -2.643559 31.97084 -7.703187 -3.441084 31.97094 -7.732349 -2.551321 31.69882 -7.434281 -3.320892 31.69891 -7.313917 -3.578101 31.69892 -7.578539 -3.707622 31.97096 -7.167915 -4.449357 31.97093 -6.684611 -5.146403 31.97087 -6.917732 -4.293997 31.6989 -6.451445 -4.966845 31.69885 -6.128842 -5.796228 31.97076 -5.922804 -6.006245 31.9707 -5.289348 -6.569509 31.97046 -5.915354 -5.594287 31.69874 -5.716609 -5.797122 31.69869 -5.105721 -6.341432 31.69847 -4.602345 -7.066612 31.97023 -3.862778 -7.495229 31.96996 -3.598864 -7.625018 31.96986 -4.442977 -6.821905 31.69827 -3.729405 -7.23644 31.69803 -3.474737 -7.362027 31.69795 -2.815011 -7.946957 31.96966 -2.002666 -8.18931 31.96963 -2.718146 -7.673461 31.69777 -1.933786 -7.907573 31.69774 -1.163284 -8.349884 31.96961 -0.87137 -8.385334 31.9696 -0.02525967 -8.43044 31.9696 -8.20397 -0.969265 31.86535 -8.065241 -1.787711 31.86544 -7.845009 -2.588529 31.86558 -7.542747 -3.36938 31.86575 -7.420661 -3.630344 31.86577 -7.018651 -4.356657 31.86572 -6.545494 -5.039264 31.86564 -6.001452 -5.675723 31.86545 -5.799765 -5.881448 31.86537 -5.179758 -6.433372 31.86499 -4.507216 -6.920536 31.86465 -3.783154 -7.340719 31.86425 -3.524753 -7.467989 31.8641 -2.757172 -7.783641 31.8638 -1.961532 -8.021076 31.86375 -1.13939 -8.178373 31.86372 -0.8534737 -8.213107 31.86371 -0.02474558 -8.257289 31.86371 -1.123274 -8.06268 31.69772 -0.8414037 -8.096938 31.69771 -0.0243954 -8.140494 31.69771 0.7932537 -8.101884 31.69786 0.804668 -8.218352 31.86396 1.609442 -7.980082 31.69804 1.632651 -8.095105 31.86427 2.48274 -7.753108 31.69823 2.518622 -7.865135 31.86457 5.520848 -4.544024 31.69135 6.311921 -3.061582 32.00001 6.391255 -1.542721 31.99486 6.312696 -1.534064 31.96195 6.468577 -0.062276 31.98984 6.468636 -4.06507e-6 31.98984 6.378089 -4.06507e-6 31.96057 6.123838 -4.06507e-6 31.72771 6.109481 -4.06507e-6 31.69041 6.043059 -1.51122 31.69135 6.086086 -4.06507e-6 31.62965 6.224302 -4.06507e-6 31.86222 6.151063 -1.52037 31.85356 6.363628 -4.06507e-6 31.95589 6.113862 -3.084768 31.96195 6.302429 -3.117238 32.00001 5.954002 -3.057245 31.85356 5.847191 -3.038857 31.69135 5.625693 -4.571516 31.85356 5.782594 -4.612674 31.96195 5.967682 -4.661207 32.00001 6.606316 -3.061582 32.04432 6.78159 -4.06507e-6 32.11149 6.660541 -4.06507e-6 32.06443 6.665414 -0.06193327 32.05189 10.23016 -0.9435456 4.693601 10.30151 -0.8246343 4.679443 10.24919 -0.9118359 4.689825 10.14364 -0.9107779 4.909115 10.32457 -0.7862042 4.674869 10.32066 -0.7927309 4.675644 10.20632 -0.7879328 4.942368 10.47776 -0.6489645 4.706816 10.41262 -0.698347 4.689014 10.2977 -0.6899427 4.989004 10.38994 -0.7155429 4.682814 10.51774 -0.6275665 4.717934 10.51744 -0.6274771 4.720278 10.41042 -0.6246905 5.04527 9.773759 -4.06507e-6 7.027607 9.757838 -0.05050408 6.978687 9.752667 -4.06507e-6 6.994793 9.359276 -0.05403566 6.718255 9.358323 -4.06507e-6 6.730059 9.391441 -4.06507e-6 6.729638 9.590058 -0.03502178 6.800024 9.550562 -4.06507e-6 6.783195 9.588084 -4.06507e-6 6.812435 9.682982 -4.06507e-6 6.8864 9.223564 -4.06507e-6 6.73177 9.121149 -0.1029562 6.753109 9.116112 -4.06507e-6 6.771002 9.065865 -4.06507e-6 6.78935 10.15933 -0.5688559 5.764121 10.19884 -0.5831759 5.653958 10.47212 -0.612859 5.07386 9.852125 -0.8695464 5.493063 9.795903 -0.8529316 5.598681 9.565434 -0.7477592 6.012876 9.437888 -0.6560724 6.231166 9.291327 -0.5023371 6.474574 9.247242 -0.4392009 6.546648 9.172364 -0.2941679 6.668647 9.161731 -0.2663623 6.686027 9.938932 -0.7330667 5.526748 9.888253 -0.7142614 5.631857 9.684971 -0.6026517 6.040912 9.577034 -0.5107116 6.253086 9.460708 -0.3644567 6.483531 9.428627 -0.3074746 6.549339 9.380675 -0.1855682 6.655097 9.375012 -0.1640211 6.669157 10.05887 -0.6340038 5.582406 10.01425 -0.6157647 5.689211 9.83811 -0.5102198 6.105251 9.747303 -0.4252385 6.321465 9.653746 -0.2929609 6.557022 9.629576 -0.2425204 6.624566 9.597241 -0.1377652 6.733736 9.594156 -0.1199137 6.748362 10.00271 -0.4838299 6.196596 9.920797 -0.4136752 6.425097 9.833565 -0.3015142 6.680999 9.809701 -0.2574067 6.757207 9.774095 -0.1613389 6.887148 9.76987 -0.1439492 6.90582 9.759246 -0.07331776 6.965696 9.589477 -0.05354392 6.79172 9.361012 -0.07972526 6.710466 9.128219 -0.1456032 6.74127 -7.131922 -0.426967 11.48284 -7.14312 -0.5356412 11.64499 -7.102484 -3.999997 11.33218 -7.106761 -0.2582412 11.34919 -7.131042 -0.5632829 11.76385 -7.115746 -0.5982857 11.91443 -7.115746 -0.5999993 11.91443 -7.107305 -3.999997 11.95171 -7.088261 -4.06507e-6 11.28155 -7.090526 -0.0866394 11.2891 -6.806212 -4.06507e-6 10.78807 -7.100875 -0.1960437 11.32742 -7.102186 -0.2098869 11.33226 -6.819534 -3.999997 12.50037 -6.819534 -4.06507e-6 12.50037 -7.115679 -0.5999993 11.91475 -7.105204 -0.594024 11.95111 -7.064486 -0.570793 12.09244 -7.047164 -0.5494248 12.13136 -6.99656 -0.4869889 12.24511 -6.960275 -0.418831 12.30575 -6.924676 -0.3519546 12.36525 -6.851743 -4.06507e-6 12.46283 -6.868074 -0.1679252 12.44261 -6.886015 -0.2262483 12.41809 -6.806212 -3.999997 10.78807 -6.288441 -3.999997 10.44784 -6.288441 -4.06507e-6 10.44784 -5.671436 -3.999997 10.39183 -5.671436 -4.06507e-6 10.39183 -5.100871 -3.999997 10.63327 -5.100871 -4.06507e-6 10.63327 -4.711466 -3.999997 11.11515 -4.711466 -4.06507e-6 11.11515 -4.595178 -3.999997 11.72368 -4.595178 -4.06507e-6 11.72368 -4.779453 -3.999997 12.31519 -4.779453 -4.06507e-6 12.31519 -9.364377 -4.06507e-6 11.05095 -9.386333 -4.06507e-6 11.02309 -9.412865 -0.1976977 11.05037 -7.758493 -0.4193525 11.6134 -10.62254 -0.5972724 6.279709 -10.54518 -0.5832206 7.080403 -10.51296 -0.5785267 7.079951 -10.51188 -0.5771707 7.425001 -10.23831 -0.4193525 7.072251 -10.20809 -0.4193525 8.876547 -10.49053 -0.5739819 5.500532 -10.58552 -0.5962144 5.146361 -10.6593 -0.5915206 5.839399 -10.64535 -0.5927723 4.895463 -10.7313 -0.5878251 4.535025 -10.79155 -0.5708228 4.255065 -10.44455 -0.5632084 5.671995 -10.31934 -0.4958849 6.099174 -10.0992 -0.197653 6.782775 -10.10409 -0.2150725 6.768415 -10.1505 -0.3117513 6.630019 -10.17536 -0.3503453 6.554667 -10.23375 -0.4178028 6.37292 -10.2577 -0.4454743 6.298359 -10.06489 -4.06507e-6 7.067416 -10.06459 -4.06507e-6 6.883991 -10.09991 -0.1976977 7.06837 -10.07222 -0.09479033 6.861842 -10.07535 -0.1128059 6.852688 -7.783035 -0.1976977 11.47714 -7.267455 -4.06507e-6 11.33402 -7.688011 -0.5982857 11.99797 -7.709804 -0.5785267 11.88382 -8.208359 -0.5982857 12.07392 -8.405367 -0.5785267 11.91379 -8.407357 -0.5982857 12.04282 -8.954736 -0.5785267 11.80839 -8.99669 -0.5982857 11.95072 -9.02495 -0.5982857 11.9463 -9.37848 -0.5785267 11.60866 -9.440499 -0.5982857 11.71284 -9.670737 -0.5982857 11.58349 -9.696449 -0.5785267 11.35106 -9.783017 -0.5982857 11.44721 -9.924012 -0.5785267 11.07176 -10.03052 -0.5982708 11.1468 -10.37201 -0.5785267 9.918625 -10.47866 -0.5982857 10.14109 -10.19435 -0.5785267 10.52727 -10.30791 -0.5982857 10.57618 -10.13258 -0.5982708 11.02292 -10.4818 -0.5785267 8.900417 -9.588892 -0.1976977 10.83021 -9.556802 -4.06507e-6 10.80678 -9.590435 -4.06507e-6 10.7641 -9.813803 -0.1976977 10.36611 -9.696568 -4.06507e-6 10.56036 -7.741349 -4.06507e-6 11.43654 -7.789331 -4.06507e-6 11.43982 -8.389923 -0.1976977 11.50086 -8.273418 -4.06507e-6 11.47297 -8.829209 -4.06507e-6 11.37521 -8.83955 -0.1976977 11.41154 -8.470993 -4.06507e-6 11.45862 -8.388492 -4.06507e-6 11.46461 -8.861403 -4.06507e-6 11.36772 -8.978973 -4.06507e-6 11.31912 -9.169037 -0.1976977 11.25259 -9.145523 -4.06507e-6 11.2134 -9.278843 -4.06507e-6 11.12877 -9.969289 -0.1976977 9.826037 -9.974519 -4.06507e-6 9.576118 -10.07015 -0.1976977 8.864521 -10.0359 -4.06507e-6 8.866921 -10.0659 -4.06507e-6 7.669259 -8.3951 -0.4193525 11.63922 -8.878144 -0.4193525 11.54451 -9.239214 -0.4193525 11.3719 -9.507882 -0.4193525 11.15112 -9.70118 -0.4193525 10.91114 -9.941312 -0.4193525 10.42011 -10.10423 -0.4193525 9.857059 -9.776073 -4.06507e-6 10.35041 -9.863819 -4.06507e-6 10.11872 -9.925532 -4.06507e-6 9.816248 -10.00118 -0.04804539 6.630601 -10.00144 -0.05853581 6.624856 -9.670461 -4.06507e-6 6.399315 -9.592833 -4.06507e-6 6.395848 -9.593548 -0.05102562 6.381812 -9.20635 -4.06507e-6 6.539197 -10.69557 -0.6487261 3.950028 -10.72729 -0.6204735 3.956495 -10.61813 -0.6262254 4.483331 -10.75477 -0.6021451 3.9622 -10.81179 -0.5640726 3.974039 -10.51894 -0.6953518 4.434974 -10.67314 -0.6753247 3.949832 -10.60702 -0.7544201 3.949512 -10.60777 -0.7528107 3.94926 -10.44046 -0.7905107 4.393236 -10.52182 -0.9359013 3.978172 -10.388 -0.9052347 4.360947 -10.55043 -0.8749555 3.968548 -9.502756 -4.06507e-6 6.391825 -9.349863 -4.06507e-6 6.437904 -9.355927 -0.1000058 6.424673 -9.342002 -4.06507e-6 6.440272 -9.99483 -4.06507e-6 6.647424 -9.952532 -4.06507e-6 6.572516 -10.03508 -4.06507e-6 6.718712 -10.44694 -0.6087016 5.079865 -10.13385 -0.8972328 4.940587 -10.29132 -0.5421828 5.586368 -10.16515 -0.4402142 5.989151 -10.04572 -0.2592396 6.396856 -10.10943 -0.3726076 6.171709 -10.0301 -0.2183954 6.45951 -10.00809 -0.1299719 6.567078 -10.31761 -0.6673973 5.019786 -10.13618 -0.5826246 5.511867 -9.991439 -0.4578571 5.897005 -9.929063 -0.3769438 6.067864 -9.861024 -0.2450239 6.271588 -9.845714 -0.1991729 6.325659 -9.827683 -0.1054447 6.412653 -9.82696 -0.04037129 6.452988 -9.827579 -0.03217566 6.4565 -9.826238 -4.06507e-6 6.46189 -10.20983 -0.7667284 4.97184 -9.998533 -0.679497 5.457806 -9.825284 -0.5460869 5.837104 -9.747865 -0.4577528 6.004826 -9.658205 -0.3105443 6.203922 -9.635898 -0.2581071 6.256458 -9.604001 -0.1470636 6.340345 -9.593988 -0.06270813 6.378545 -9.895573 -0.8206855 5.430946 -9.692589 -0.6911199 5.818787 -9.597251 -0.6010126 5.99352 -9.477827 -0.4426878 6.207391 -9.444537 -0.3828745 6.26638 -9.388039 -0.2453815 6.366641 -9.358744 -0.1201372 6.41949 10.28708 -4.06507e-6 30.96847 10.28708 -6.298337 30.96847 10.20045 -2.061505 25.33782 9.93511 -6.298337 25.20905 10.14429 -2.04644 25.31836 9.625881 -6.298337 24.87003 9.677356 -1.698304 24.95275 9.712196 -1.751546 25.00005 9.88873 -1.926069 25.17534 9.914121 -1.943056 25.19429 9.936562 -1.953129 25.20639 9.502044 -0.7097166 24.42855 9.503087 -0.8601736 24.467 9.500614 -6.298337 24.4286 9.533017 -1.247902 24.63996 9.561164 -1.389344 24.72535 9.570023 -1.433883 24.75224 9.631468 -1.585249 24.86702 9.548573 -0.06004083 24.08405 9.525983 -0.09598243 24.15543 9.506887 -0.2049397 24.264 9.571998 -0.02277302 24.01004 9.524508 -0.2185295 24.16181 9.506545 -0.2068917 24.26595 9.500658 -0.3492128 24.33759 9.585692 -6.298337 23.97769 9.500033 -0.4190843 24.35428 9.587763 -0.01798975 23.97873 9.647108 -4.06507e-6 23.86087 -9.192819 -0.1983385 10.11465 -9.364585 -4.06507e-6 10.21381 -8.899996 -0.1983385 10.40747 -8.999171 -4.06507e-6 10.57923 -8.499998 -0.1983385 10.51465 -8.499998 -4.06507e-6 10.71298 -8.099998 -0.1983385 10.40747 -8.000831 -4.06507e-6 10.57923 -7.807183 -0.1983385 10.11465 -7.635417 -4.06507e-6 10.21381 -7.699998 -0.1983385 9.714647 -7.501664 -4.06507e-6 9.714647 -7.807183 -0.1983385 9.314647 -7.635417 -4.06507e-6 9.215478 -8.099998 -0.1983385 9.021826 -8.000831 -4.06507e-6 8.850062 -8.499998 -0.1983385 8.914648 -8.499998 -4.06507e-6 8.71631 -8.899996 -0.1983385 9.021826 -8.999171 -4.06507e-6 8.850062 -9.192819 -0.1983385 9.314647 -9.364585 -4.06507e-6 9.215478 -9.300004 -0.1983385 9.714647 -9.498338 -4.06507e-6 9.714647 8.077344 -0.1242201 29.64932 8.000656 -0.1205545 29.65371 8 -0.1983385 29.72001 7.661407 -0.09638476 29.68402 7.54114 -0.07139551 29.72986 7.599999 -0.1983385 29.82719 7.475396 -0.05774605 29.75492 7.307177 -0.1983385 30.12001 7.357603 -0.03326344 29.79981 7.215833 -0.004817128 29.90995 7.73978 -0.1080971 29.66864 8.53633 -0.05704569 29.75427 8.399999 -0.1983385 29.82719 8.716686 -0.01705098 29.84971 8.692822 -0.1983385 30.12001 8.839137 -4.06507e-6 29.97915 8.48215 -0.06905603 29.72559 8.46239 -0.07209587 29.72131 8.155837 -0.1193475 29.65494 7.160862 -4.06507e-6 29.97915 7.135411 -4.06507e-6 30.02084 7.2 -0.1983385 30.52 7.001666 -4.06507e-6 30.52 7.307177 -0.1983385 30.92 7.135411 -4.06507e-6 31.01918 7.599999 -0.1983385 31.21283 7.500833 -4.06507e-6 31.38459 8 -0.1983385 31.32001 8 -4.06507e-6 31.51834 8.399999 -0.1983385 31.21283 8.499166 -4.06507e-6 31.38459 8.692822 -0.1983385 30.92 8.864587 -4.06507e-6 31.01918 8.799999 -0.1983385 30.52 8.99834 -4.06507e-6 30.52 8.864587 -4.06507e-6 30.02084 7.50718 -0.1983385 10.4 7.335414 -4.06507e-6 10.49917 7.800003 -0.1983385 10.69282 7.700829 -4.06507e-6 10.86459 8.200003 -0.1983385 10.8 8.200003 -4.06507e-6 10.99834 8.600003 -0.1983385 10.69282 8.69917 -4.06507e-6 10.86459 8.892818 -0.1983385 10.4 9.064583 -4.06507e-6 10.49917 9.000002 -0.1983385 10 9.198336 -4.06507e-6 10 8.892818 -0.1983385 9.600001 9.064583 -4.06507e-6 9.500832 8.600003 -0.1983385 9.30718 8.69917 -4.06507e-6 9.135415 8.200003 -0.1983385 9.199999 8.200003 -4.06507e-6 9.001664 7.800003 -0.1983385 9.30718 7.700829 -4.06507e-6 9.135415 7.50718 -0.1983385 9.600001 7.335414 -4.06507e-6 9.500832 7.399996 -0.1983385 10 7.201662 -4.06507e-6 10 6.168982 -5.602886 20.20001 5.052981 -5.602886 20.20001 5.142202 -5.435441 20.20001 6.168982 -4.06507e-6 20.20001 6.418986 -4.06507e-6 20.13302 6.418986 -5.602886 20.13302 6.601994 -4.06507e-6 19.95001 6.601994 -5.602886 19.95001 6.668982 -4.06507e-6 19.70001 6.668982 -5.602886 19.70001 6.630925 -4.06507e-6 19.50866 6.630925 -5.602886 19.50866 6.522541 -4.06507e-6 19.34645 6.522541 -5.602886 19.34645 6.360327 -4.06507e-6 19.23807 6.360327 -5.602886 19.23807 6.9226 -8.490983 1.560785 6.771838 -8.460854 3.121592 5.57704 -9.316017 3.121592 2.771614 -10.50277 3.294684 2.781352 -10.51762 3.121045 4.248051 -10.00741 3.121592 4.041059 -10.22943 4.11478e-6 4.524609 -10.01193 3.18346e-6 4.377497 -10.06005 1.560785 7.442576 -8.098339 -3.3358e-6 7.37646 -8.098339 1.446598 7.017148 -8.456651 -1.93881e-6 5.718162 -9.357859 1.560785 6.287706 -9.009157 -5.41829e-7 6.718462 -8.708228 -1.47315e-6 4.969364 -9.811882 2.25214e-6 4.993645 -9.798129 2.25214e-6 5.863113 -9.305765 3.89494e-7 2.907244 -10.55563 1.561679 3.043314 -10.56896 5.97743e-6 3.594888 -10.38125 5.04611e-6 3.208098 -10.044 6.186949 2.616157 -10.23947 6.183416 2.629091 -10.2731 5.891711 2.642391 -10.30577 5.600006 3.524711 -9.939452 6.188838 4.032445 -9.716783 6.190772 5.15834 -9.149064 6.137465 5.111148 -9.173308 6.161499 4.945239 -9.262775 6.204921 4.903776 -9.286199 6.20543 4.386937 -9.56132 6.192122 6.631983 -8.406614 4.300266 6.56638 -8.462687 4.300301 6.558878 -8.468275 4.303366 6.517572 -8.498151 4.32291 6.466826 -8.534852 4.346921 6.455233 -8.543242 4.352406 6.349584 -8.611922 4.433088 6.289309 -8.651126 4.479126 6.246721 -8.678813 4.51165 6.245395 -8.679573 4.513125 6.23407 -8.68607 4.525722 6.194418 -8.708809 4.569832 6.100675 -8.754109 4.717305 6.031436 -8.787576 4.826231 5.994921 -8.800808 4.907545 5.944034 -8.817871 5.026883 5.795707 -8.871917 5.323533 5.700243 -8.906697 5.514464 5.565775 -8.960906 5.727469 5.362948 -9.049956 5.97614 5.29324 -9.083723 6.0311 7.363734 -8.098339 1.560576 7.202161 -8.098339 3.007569 7.183974 -8.098339 3.121444 7.01419 -8.098339 4.184684 7.01156 -8.082066 4.300068 7.118632 -7.998336 4.211582 7.656341 -7.44601 4.301252 2.899667 -10.55488 1.648604 2.799345 -10.54505 2.800006 5.286319 -6.907274 7.267107 4.160335 -6.907274 7.965404 2.943908 -6.907274 8.49055 1.663496 -6.907274 8.831129 0.3469117 -6.907274 8.979739 6.297392 -6.907274 6.41084 7.171576 -6.907274 5.415215 6.55478 -7.855524 4.949477 -2.280081 -6.907274 8.692368 -0.9772055 -6.907274 8.933147 -0.8931629 -7.855524 8.164849 -5.784022 -6.907274 6.877583 -4.709902 -6.907274 7.653293 -4.304821 -7.855524 6.995069 7.947503 -6.737997 4.357899 7.829806 -6.882806 4.336165 -8.139433 -6.901566 3.787827 -8.350255 -6.620397 3.815628 -8.488001 -6.43668 3.833793 -7.534454 -6.907274 4.897763 -7.882537 -7.244174 3.753951 -6.886447 -7.855524 4.476529 -7.36099 -7.873718 3.692832 7.42956 -7.375259 4.26225 7.218508 -7.634927 4.223275 7.046906 -7.846061 4.191585 6.922935 -7.998589 4.168691 8.433139 -6.0816 4.449017 8.614769 -5.791966 4.48417 -7.20946 -8.056615 3.675075 -6.695273 -8.098339 4.352253 -5.982558 -8.098339 5.289399 -4.185314 -8.098339 6.800876 -5.1398 -8.098339 6.111563 -5.286562 -7.855524 6.286074 -0.8683674 -8.098339 7.93818 -2.026128 -8.098339 7.724219 -2.083982 -7.855524 7.944777 2.616023 -8.098339 7.544879 1.478215 -8.098339 7.847524 1.520423 -7.855524 8.071604 -6.732414 -6.907274 5.952368 -6.153385 -7.855524 5.440433 -3.533396 -6.907274 8.262637 -3.229501 -7.855524 7.552006 -3.139848 -8.098339 7.342351 0.3170796 -7.855524 8.207432 0.308273 -8.098339 7.979582 2.690715 -7.855524 7.760316 3.696961 -8.098339 7.078224 3.802521 -7.855524 7.280337 4.697536 -8.098339 6.457704 4.831669 -7.855524 6.642098 5.595994 -8.098339 5.696805 5.755787 -7.855524 5.859473 6.372815 -8.098339 4.812072 6.81707 -8.098339 4.158881 8.271507 -6.339345 4.417735 8.045061 -6.617968 4.375916 11.36321 -0.5983304 14.42001 11.36321 -6.298337 14.42001 13.8632 -6.298337 15.42393 12.3632 -6.298337 15.42393 13.8632 -6.298337 26.67158 13.71097 -6.298337 27.43694 11.86321 -6.298337 15.28995 11.49717 -6.298337 14.92393 11.36321 -6.298337 14.42393 13.8632 -6.498341 15.42393 13.8632 -6.498341 26.67158 10.5621 -1.079519 7.118909 10.59238 -0.5983304 7.149189 11.36321 -0.5983304 7.920005 9.557261 -5.172957 6.114062 9.858466 -4.400868 6.41527 11.36321 -6.498341 7.920005 10.12348 -3.561054 6.680287 10.30132 -2.842266 6.858121 10.4609 -1.965855 7.017702 9.161508 -6.012518 5.718311 9.290143 -6.498341 5.846945 9.222596 -6.498624 5.779396 9.156099 -6.022979 5.712899 9.156099 -6.298621 5.712899 9.156099 -6.498341 5.712899 9.156099 -6.499459 5.712899 13.70846 -7.262592 15.16252 13.73322 -7.207592 15.22028 13.69468 -7.25535 26.67158 13.76666 -7.097651 15.28068 13.8114 -6.950576 15.36149 13.82436 -6.890629 15.3816 13.86048 -6.602754 15.42393 13.76415 -7.119958 26.67158 13.53062 -7.602756 14.42393 13.56026 -7.556651 14.72408 13.25989 -7.894863 26.67158 13.61495 -7.461224 14.92024 13.63416 -7.427711 14.98913 13.47679 -7.680003 26.67158 13.53062 -7.602756 12.07686 13.25865 -7.895086 12.07686 13.08499 -8.081768 12.07686 13.0296 -8.123 26.67158 12.62057 -8.331199 12.07686 12.61972 -8.328442 26.67158 12.50863 -8.391324 12.07686 12.46688 -8.405049 26.67158 11.86321 -8.498331 12.07686 11.86321 -8.498331 26.67158 12.4578 -8.391324 11.56076 11.81296 -8.331199 10.1271 12.14135 -8.081768 9.798711 12.54202 -8.081768 10.28693 13.02308 -8.081768 11.44832 12.26415 -7.895086 9.675917 12.45645 -7.602756 9.48361 12.91255 -7.602756 10.03936 13.46015 -7.602756 11.36138 13.25145 -7.602756 10.6734 12.83975 -8.081768 10.84393 12.30726 -8.391324 11.0645 12.06279 -8.391324 10.60714 11.73381 -8.391324 10.20626 11.82478 -8.498331 11.68668 11.71096 -8.498331 11.31149 11.52614 -8.498331 10.96572 11.27742 -8.498331 10.66265 11.99532 -7.53263 8.959704 8.875927 -7.91255 6.261158 11.98112 -7.525403 8.939673 11.82791 -7.447426 8.723465 12.3632 -7.602756 9.390358 12.26231 -7.597659 9.2847 9.182497 -7.26371 5.954596 11.36321 -6.602754 7.923863 11.38062 -6.788556 7.967353 11.44048 -6.985087 8.083151 11.44388 -6.996248 8.089734 11.57207 -7.214401 8.31637 11.60545 -7.25529 8.37265 11.61496 -7.263515 8.387662 11.66154 -7.303734 8.461112 7.875932 -8.498331 7.261158 8.417128 -8.3461 6.719962 4.204152 -7.350047 32.00001 3.358496 -7.888395 32.00001 3.441883 -7.860366 32.00001 6.311921 -7.482697 32.00001 5.588283 -5.661298 32.00001 5.489258 -5.847146 32.00001 4.926813 -6.65528 32.00001 6.312033 -7.498343 32.00001 5.700795 -7.498343 32.00001 4.930829 -7.539441 32.00001 4.177203 -7.660676 32.00001 7.440922 -8.398344 31.09222 7.479815 -8.397703 31.12779 7.705694 -8.363505 31.26391 7.702519 -8.363982 31.26199 7.605573 -8.378659 31.20357 8.262998 -8.225326 31.27554 8.302121 -8.217965 31.25427 8.395059 -8.20047 31.20374 8.49112 -8.182395 31.15151 8.002757 -8.291517 31.31479 7.999307 -8.292396 31.31531 7.971523 -8.299459 31.3195 8.557564 -8.184973 31.08015 8.664957 -8.189161 30.96479 8.789917 -8.291294 30.52427 8.774205 -8.240004 30.72153 8.728719 -8.218829 30.82281 8.686377 -8.19913 30.9171 8.716403 -8.375753 30.16395 8.73383 -8.36191 30.22493 8.796348 -8.312274 30.4436 8.79032 -8.292605 30.51925 8.572212 -8.398344 29.96092 8.687748 -8.380238 30.12361 8.353672 -8.398344 29.80243 8.395797 -8.398344 29.83298 7.968483 -8.398344 29.72063 7.998517 -8.398344 29.727 7.309598 -8.398344 30.12072 7.312497 -8.398344 30.11094 7.590932 -8.398344 29.8325 7.600715 -8.398344 29.8296 7.312973 -8.398344 30.9158 7.282419 -8.398344 30.87367 7.206996 -8.398344 30.51852 7.200619 -8.398344 30.48849 -7.701884 -7.143487 9.659807 -7.704633 -7.140447 9.714414 -8.352975 -6.35143 8.928275 -8.500131 -6.061961 8.916979 -8.525292 -6.012474 8.915047 -8.997629 -5.079378 9.088256 -8.964109 -5.147566 9.063032 -8.896412 -5.281289 9.02866 -8.752184 -5.566169 8.955436 -9.286846 -4.445736 9.570163 -9.248765 -4.534472 9.432961 -9.230356 -4.576732 9.388183 -9.188199 -4.670729 9.317385 -9.135003 -4.789357 9.228055 -9.244571 -4.544143 10.00725 -9.286041 -4.447628 9.86345 -9.299214 -4.4165 9.750052 -9.298186 -4.418943 9.714701 -9.295794 -4.424606 9.632729 -8.89879 -5.277042 10.40548 -8.975069 -5.125378 10.35831 -9.13834 -4.78207 10.19685 -9.157242 -4.740645 10.17075 -9.188468 -4.670386 10.11229 -8.863511 -5.347182 10.42729 -8.626829 -5.812754 10.50453 -8.306908 -6.412585 10.49099 -8.352975 -6.35143 10.50102 -8.371207 -6.315563 10.50421 -8.500012 -6.062199 10.50437 -7.870318 -6.952528 10.2081 -7.947708 -6.860454 10.2811 -8.044126 -6.745745 10.37205 -8.074464 -6.708596 10.39208 -8.101719 -6.673892 10.40368 -7.711435 -7.132892 9.849418 -7.759134 -7.079591 10.0165 -7.813843 -7.017066 10.11078 -8.214632 -6.532554 8.967276 -8.105824 -6.667395 9.031706 -7.981861 -6.821011 9.105114 -7.947976 -6.860678 9.144486 -7.820042 -7.010464 9.293152 -7.809701 -7.022161 9.315815 -7.736067 -7.105444 9.477137 7.411001 -8.423929 10.13223 7.413944 -8.424286 10.00031 7.911941 -8.398344 9.253663 8.129491 -8.398344 9.203114 7.526328 -8.419473 9.568533 7.544344 -8.418535 9.549149 7.720624 -8.40934 9.359534 7.803572 -8.404572 9.313632 7.413951 -8.424286 10.00004 7.417684 -8.424748 9.83272 7.512485 -8.420144 9.602184 7.805427 -8.400921 10.6836 7.686941 -8.403782 10.61382 7.548397 -8.412246 10.44666 7.508693 -8.414675 10.39875 7.50163 -8.415107 10.39023 8.129491 -8.398344 10.79689 7.911941 -8.398344 10.74634 8.501014 -8.398344 10.74121 8.197999 -8.398344 10.78662 8.80616 -8.398344 10.52209 8.589251 -8.398344 10.67785 8.977635 -8.398344 10.18783 8.873797 -8.398344 10.39024 8.977635 -8.398344 9.812164 8.977635 -8.398344 10 8.80616 -8.398344 9.477913 8.873797 -8.398344 9.609759 8.197999 -8.398344 9.213379 8.501014 -8.398344 9.25879 8.589251 -8.398344 9.322152 0.3700308 -10.99816 0.3362693 0.5508639 -9.994615 0.137282 0.5955749 -10.05355 0.08807694 0.3700234 -9.445568 0.3362753 0.4451401 -9.740625 0.2536158 0.4458256 -9.743292 0.2528679 4.756493 -8.098339 -4.490593 5.364043 -8.098339 -5.159139 5.110909 -8.427892 -4.880667 4.68651 -8.181039 -4.413583 0.7088907 -10.20286 -0.03660804 0.8271985 -10.27653 -0.1667976 0.6755941 -10.97714 3.81081e-5 0.8996554 -10.32165 -0.2465286 1.352591 -10.88938 -0.7453785 1.103205 -10.34056 -0.4705135 1.602923 -10.82099 -1.020686 1.791214 -10.18097 -1.227601 4.993824 -8.559171 -4.751812 4.769159 -8.811076 -4.504571 4.150045 -8.748372 -3.823256 4.516592 -9.094272 -4.226618 3.945959 -8.923624 -3.598683 3.936266 -9.622832 -3.588125 3.580069 -9.23783 -3.196058 3.326309 -10.06946 -2.916828 2.787968 -10.37729 -2.324586 2.360781 -9.967689 -1.854348 2.714214 -10.41946 -2.243448 2.092776 -10.06805 -1.559441 2.134835 -10.66393 -1.605751 2.055963 -10.6972 -1.518941 3.854116 -9.682988 -3.49772 3.598226 -9.870354 -3.216089 3.049036 -9.602402 -2.611705 3.017021 -9.624382 -2.57648 -1.343625 -9.79421 -1.495175 -0.7370509 -9.942774 -0.7515481 -0.8536525 -9.970788 -0.6602533 -3.864745 -8.098339 -4.4371 -3.780516 -8.098339 -4.483051 -3.636191 -8.258839 -4.306065 -4.320795 -8.098339 -4.559317 -4.106434 -8.098339 -4.447764 -3.567638 -8.688544 -3.770616 -3.958935 -8.098339 -4.423061 -3.432716 -8.61225 -3.822008 -3.926108 -8.098339 -4.427954 -1.956115 -9.542499 -2.246149 -1.933279 -9.555657 -2.218144 -1.751745 -9.715382 -1.761013 -1.810992 -9.605129 -2.068217 -1.630845 -9.67801 -1.847333 -2.617376 -9.259779 -2.822342 -1.871774 -9.801451 -1.691365 -2.745079 -9.341825 -2.762095 -1.962835 -9.933431 -1.660418 -2.005378 -10.05623 -1.667654 -2.186249 -10.00086 -1.88941 -2.847897 -9.467606 -2.745563 -4.335063 -8.098339 -4.572825 -3.681535 -8.805533 -3.767662 -2.911495 -8.920614 -3.417564 -2.534034 -9.209637 -2.954756 -2.495276 -9.231959 -2.907231 -3.139297 -8.741055 -3.696865 -3.114151 -8.765448 -3.666035 -3.305482 -8.57978 -3.900611 -0.966797 -10.05955 -0.5800492 -1.042428 -10.18745 -0.535762 -1.043791 -10.19359 -0.5354821 -1.04441 -10.19636 -0.535355 -1.076507 -10.34056 -0.5287915 -0.8585326 -9.971951 -0.6564368 -0.9658359 -10.05793 -0.580614 -0.8543901 -9.970952 -0.6596786 -2.89991 -9.579603 -2.764413 -3.169152 -9.420682 -3.094517 -3.73959 -8.900244 -3.793919 -4.148292 -8.527387 -4.295012 -4.509846 -8.098339 -4.738306 1.534102 -9.758417 -1.545123 1.727162 -9.678845 -1.757564 0.8146592 -9.945635 -0.6764816 3.763957 -8.688544 -3.574632 2.888692 -9.341825 -2.611493 2.764394 -9.259779 -2.678475 3.877526 -8.805533 -3.565598 4.570184 -8.098339 -4.337837 4.528423 -8.098339 -4.303602 4.48781 -8.098339 -4.281003 4.357566 -8.098339 -4.232555 4.313117 -8.098339 -4.216022 4.177367 -8.098339 -4.206154 3.510689 -8.583892 -3.720184 4.014594 -8.098339 -4.274678 3.631969 -8.61225 -3.633159 4.084778 -8.098339 -4.228932 4.156677 -8.098339 -4.211244 2.196228 -9.485532 -2.273704 2.645073 -9.224806 -2.767627 2.833997 -9.115059 -2.975527 3.235964 -8.808885 -3.41787 3.361633 -8.713175 -3.556164 3.432681 -8.659054 -3.634341 2.990482 -9.467606 -2.589492 1.065602 -10.1955 -0.4840233 2.048714 -9.933431 -1.553177 1.054151 -10.15133 -0.4881365 1.959441 -9.801451 -1.588944 0.8298807 -9.952981 -0.6636931 0.7761322 -9.942774 -0.7110849 0.8269601 -9.934057 -0.7670075 0.9085663 -9.92005 -0.8567968 1.843294 -9.715382 -1.664904 2.009412 -9.562512 -2.068142 2.179434 -9.492446 -2.255226 0.9899341 -10.06529 -0.534243 0.9490453 -10.01053 -0.5635964 0.8856483 -9.979907 -0.6168472 -0.3874622 -10.9973 0.3160223 -0.7563405 -10.24783 -0.1362456 -0.5952142 -10.06125 0.0613107 -0.8148052 -10.27617 -0.2079253 -0.6451927 -10.97866 4.55586e-5 -0.9422995 -10.338 -0.3642427 -0.9358696 -10.95265 -0.3565588 -0.4751257 -9.795864 0.2085421 -0.4593827 -9.732966 0.2278484 -0.3874548 -9.445537 0.3160521 -4.556919 -8.786503 -4.796101 -4.983152 -8.226608 -5.318633 -5.080799 -8.098339 -5.438344 -2.626727 -10.38957 -2.42957 -2.790498 -10.30825 -2.630372 -1.515696 -10.83948 -1.067638 -1.537668 -10.83519 -1.094592 -2.111027 -10.64125 -1.797274 -2.138915 -10.63182 -1.831454 -3.989513 -9.393592 -4.10038 -4.515553 -8.830775 -4.74538 -3.405134 -9.895523 -3.38393 -3.581079 -9.744395 -3.599639 -3.633934 -9.699007 -3.664439 4.994263 -8.723278 -4.46458 6.164884 -8.098339 -4.148696 6.294733 -8.97925 -0.8481811 2.135073 -10.74133 -1.014599 2.009121 -10.8133 2.22756e-5 1.654697 -10.86156 2.78635e-5 0.9558775 -10.95672 3.90394e-5 3.598866 -10.34691 -0.9773477 2.133821 -10.78384 2.04129e-5 4.994263 -9.755794 -0.9215214 7.368749 -8.098339 -0.7679077 7.306402 -8.098339 -1.416404 6.294733 -8.800928 -1.972414 7.186969 -8.098339 -1.820736 6.247868 -8.098339 -4.044001 6.29427 -8.098339 -3.954582 6.294733 -8.48246 -3.065242 6.825623 -8.098339 -2.930708 6.903303 -8.098339 -2.781031 4.994263 -9.216059 -3.330285 4.994263 -9.562065 -2.142963 3.598866 -10.14144 -2.272785 -0.617022 -9.942729 -0.8534114 0.8115299 -9.748314 -2.068663 0.6320231 -9.942745 -0.8262662 0.5198397 -9.942729 -0.9159358 -0.001626431 -9.9427 -1.053343 -0.5825482 -9.764676 -2.068663 0.03619265 -9.942714 -1.047347 0.3228761 -9.942774 -1.001894 -0.3278501 -9.942759 -1.000499 -0.3781564 -9.942759 -0.9749109 -0.5931951 -9.942729 -0.8655317 2.102708 -9.157543 -3.4187 3.436109 -8.098339 -4.698957 3.177477 -8.232479 -4.701327 1.974834 -8.600507 -4.701327 2.870975 -8.098339 -5.11345 3.13249 -8.098339 -4.921642 0.7320844 -8.79388 -4.701327 1.559434 -8.098339 -5.653145 1.864461 -8.098339 -5.527628 -0.5255215 -8.808632 -4.701327 0.1566835 -8.098339 -5.862199 0.6765999 -8.098339 -5.784715 -2.593728 -8.098339 -5.259525 -1.66581 -8.098339 -5.584561 -1.772466 -8.644481 -4.701327 -1.255224 -8.098339 -5.728384 -0.4849903 -8.098339 -5.801383 -2.983416 -8.304764 -4.701327 -2.91677 -8.098339 -5.048166 -3.449413 -8.098339 -4.699679 -1.887242 -9.204362 -3.4187 -0.5595557 -9.379137 -3.4187 0.7794924 -9.363417 -3.4187 -7.387447 -8.144398 -0.00802803 -7.442469 -8.098339 -0.008463442 -7.360185 -8.098339 -0.8012369 -2.111065 -10.74189 -1.058103 -2.10839 -10.78105 2.18099e-5 -2.786967 -10.63943 5.97743e-6 -3.581541 -10.34886 -1.019395 -1.701819 -10.8659 3.15888e-5 -1.3918 -10.89898 3.53141e-5 -3.581541 -10.12551 -2.369208 -4.983405 -9.171103 -3.467895 -4.983405 -8.636524 -4.641926 -6.025115 -8.098339 -4.355341 -6.079594 -8.098339 -4.292863 -6.287987 -8.098339 -3.922519 -6.770204 -8.098339 -3.065533 -6.28979 -8.43956 -3.191326 -6.824876 -8.098339 -2.968373 -6.28979 -8.785416 -2.0557 -7.164309 -8.098339 -1.901309 -6.28979 -8.979235 -0.8845022 -6.601716 -8.792658 -0.002387464 -6.665053 -8.749102 -0.002307415 -7.285567 -8.098339 -1.520104 -4.982191 -9.802584 -0.003593087 -5.758161 -9.369407 -0.003426849 -5.784745 -9.354566 -0.003421247 -6.282563 -9.012166 -0.002791225 -2.992424 -10.58351 -6.01711e-4 -3.577212 -10.3861 -0.004629671 -3.857518 -10.29148 -0.006560742 -4.034976 -10.23157 -0.007782638 -4.845756 -9.869132 -0.004006624 -4.983405 -9.757538 -0.9611561 -4.932257 -9.83045 -0.003603816 -4.983405 -9.546939 -2.233854 -6.50202 -8.29478 7.085311 -6.538617 -8.262027 7.099615 -6.646337 -8.603845 3.995196 -7.076258 -7.780943 7.309752 -7.221217 -7.641573 7.354838 -7.416303 -7.941518 3.995196 -9.19343 -5.444769 5.948965 -9.276184 -5.472769 3.992226 -8.775527 -6.374527 3.995196 -8.65859 -5.922322 7.914834 -9.003149 -5.381827 7.981029 -7.947492 -6.86029 7.629182 -8.123572 -6.64774 7.706028 -8.457999 -6.198351 7.839565 -8.603769 -6.00246 7.897773 -8.125859 -7.199679 3.995196 -7.275695 -7.589195 7.371783 -7.859127 -6.962616 7.592509 -7.891709 -6.927628 7.604834 -4.91638 -9.696861 3.995196 -4.972035 -9.328176 6.798085 -5.814137 -9.188999 3.995196 -5.505311 -9.022002 6.870353 -5.690271 -8.898173 6.902618 -5.795422 -8.82778 6.92096 -5.855503 -8.787562 6.931441 -3.804991 -9.894122 6.65558 -4.055614 -9.780366 6.685014 -3.948899 -10.12546 3.995196 -4.062893 -9.777058 6.685869 -4.670943 -9.501044 6.757281 -2.821343 -10.60318 1.646837 -2.828548 -10.59558 1.992103 -3.880354 -10.2806 1.992791 -4.872123 -9.854291 1.992791 -5.797135 -9.34336 1.992791 -6.656142 -8.749444 1.992791 -7.421004 -8.098339 2.026933 -7.421816 -8.098339 1.992777 -7.435987 -8.098339 1.396932 -7.455068 -8.098339 0.5947192 -7.372344 -7.905353 3.695238 -8.127632 -7.203926 3.788729 -8.801865 -6.35301 3.86592 -8.781271 -6.379787 3.863583 -8.196773 -7.139717 3.797287 -2.841907 -10.5815 2.632315 -2.876381 -10.51377 3.293313 -2.912829 -10.44217 3.992196 -3.012742 -10.24586 5.908112 -3.049197 -10.16066 6.551599 -9.73397 -4.503731 3.921411 -9.798768 -4.340489 3.924157 -9.730476 -4.310538 3.924389 -10.16961 -3.116373 3.941435 -10.46691 -1.878534 3.947979 -10.42375 -2.487201 3.946469 -10.53465 -1.890544 3.948129 -10.54985 -1.808737 3.948357 -10.61773 -1.443539 3.949374 -10.2528 -3.079105 3.941638 -9.810256 -4.311551 3.924643 -10.12816 -3.510688 3.938116 -10.23616 -3.136713 3.941168 -8.993524 -5.757083 3.872683 6.959838 -7.998366 4.172792 7.080389 -7.920612 4.193348 7.516844 -7.450972 4.266689 6.961753 -7.998366 4.173185 7.000012 -7.998381 4.181034 7.476551 -7.413838 4.260607 7.741777 -7.208918 4.304487 8.0038 -6.782208 4.354269 8.019006 -6.846477 4.354183 8.48206 -6.112729 4.439571 8.394351 -6.355752 4.421468 8.043944 -6.813873 4.358654 8.909932 -5.412523 4.515604 8.964522 -5.442951 4.516665 8.527091 -6.143246 4.443631 8.879332 -5.395476 4.515008 8.893563 -5.403404 4.515285 9.437448 -4.312818 4.581318 9.314327 -4.777078 4.562018 9.500234 -4.340146 4.584711 9.517683 -4.299138 4.586841 9.729399 -3.801543 4.612684 9.866743 -3.139008 4.631646 9.932927 -3.159005 4.635634 10.15992 -1.922954 4.662655 10.04877 -2.793256 4.648698 9.952886 -3.095973 4.637886 10.26954 -1.762349 4.67142 10.25047 -1.851369 4.669458 10.23236 -1.935933 4.667593 2.726262 -10.20815 16.21041 2.212448 -10.34286 16.20535 1.859193 -10.41891 6.165352 1.405676 -10.49203 16.20294 1.405103 -10.48701 6.16757 1.271164 -10.50711 6.168224 1.279285 -10.51539 16.20256 0.959491 -10.55386 6.169746 0.3378443 -10.59914 16.20574 0.02968829 -10.60728 6.221813 -2.127285 -10.39794 16.19729 -1.695769 -10.4737 6.350323 -1.190963 -10.54664 16.19961 -1.533592 -10.5027 6.329647 -0.6282203 -10.59308 16.20353 -0.6135948 -10.59387 6.260502 -0.4487879 -10.59421 16.20394 -0.4487507 -10.59731 6.250588 -0.2106972 -10.60227 6.23627 -2.290162 -10.35604 16.19825 -2.290609 -10.3578 6.430004 -2.173396 -10.38827 6.411217 -3.046731 -10.16142 16.20272 -3.948773 -9.835605 16.20821 -4.058833 -9.787415 16.20796 -4.288944 -9.686653 16.20742 -5.111704 -9.261225 16.20537 -5.687545 -8.893822 16.21232 -5.869704 -8.777593 16.21452 -6.587642 -8.223061 16.24103 -6.765003 -8.069252 16.25053 -7.076258 -7.780943 16.25878 -7.076675 -7.780526 16.26966 3.207644 -10.04303 16.21561 3.633899 -9.896804 16.22021 4.498524 -9.505157 16.21996 4.903776 -9.286199 16.21893 8.558279 -6.292884 4.527015 8.349558 -6.598298 4.426163 8.917926 -5.750243 4.524756 8.872768 -5.771746 4.752909 8.94194 -5.644877 4.817799 9.038842 -5.505417 4.719939 9.00822 -5.518217 4.886564 9.013145 -5.508591 4.891937 9.064196 -5.502347 4.547876 9.524285 -4.610111 4.607285 9.49297 -4.425247 5.41596 9.371979 -4.738752 5.284064 9.607865 -4.402746 4.617381 9.629547 -4.348938 4.62 9.645185 -4.030828 5.5819 9.923971 -3.618408 4.655564 9.88528 -3.261838 5.843345 9.896783 -3.21487 5.855856 10.05534 -3.173549 4.670186 10.06778 -3.131423 4.671571 10.04619 -2.604533 6.018415 10.22106 -2.612312 4.688633 10.17099 -1.912061 6.153769 10.36499 -1.871769 4.703274 10.3666 -1.863439 4.703439 10.41917 -1.592923 4.708787 10.28281 -0.9886514 6.274853 10.19092 -1.801465 6.175388 -8.992383 -5.399649 10.50001 -9.033854 -5.330224 16.17883 -9.019824 -5.353872 10.49377 -9.02685 -5.342041 10.49465 -9.030225 -5.336349 10.49298 -9.033452 -5.33091 10.49437 -9.032818 -5.331967 10.49378 -9.03334 -5.331089 10.49465 -9.033854 -5.330224 10.49552 -9.033831 -5.330254 10.49528 -9.03372 -5.330448 10.49485 -8.978354 -5.423058 10.5032 -8.924121 -5.509977 10.51223 -8.968482 -5.439345 16.19666 -8.807021 -5.697672 10.53172 -8.811365 -5.690907 16.22065 -8.785444 -5.729218 10.53086 -8.67297 -5.901058 16.22448 -8.70123 -5.852406 10.52748 -8.668865 -5.899732 10.52619 -8.5528 -6.0695 10.52154 -8.276092 -6.453027 16.22366 -8.451911 -6.217082 10.51749 -8.14418 -6.621946 16.22321 -7.942596 -6.856043 16.22245 -8.376914 -6.318916 10.50501 -8.440534 -6.232534 10.5156 -7.589931 -7.265587 16.22113 -7.430228 -7.433464 16.22295 -7.190714 -7.67215 16.24101 -8.700201 -5.836804 8.925864 -8.816461 -5.664487 8.925057 -8.850868 -5.613495 8.924818 -8.933174 -5.491514 8.924247 -8.969503 -5.437676 8.923995 -8.467781 -6.181274 8.927477 -8.566151 -6.035481 8.926795 -8.583868 -6.009211 8.926671 -9.03372 -5.330448 8.934433 -9.033839 -5.330239 8.933991 -9.033854 -5.330224 8.933785 -9.001832 -5.384017 8.92889 -9.032199 -5.333025 8.935842 -9.033473 -5.330865 8.934896 -9.033854 -5.330224 7.982884 -0.9999968 -8.748342 0 -0.5000032 -8.748342 0 -0.8660279 -8.748342 -0.5000001 -0.474485 -8.748342 -0.1576888 -0.5000032 -8.748342 -0.8660253 -0.3438465 -8.748342 -0.3629989 -0.1317657 -8.748342 -0.4823255 -2.23027e-6 -8.748342 -0.9999998 -2.4582e-5 -8.748342 -0.4999969 0.4999988 -8.748342 -0.8660253 0.1869701 -8.748342 -0.463714 0.8660235 -8.748342 -0.5000001 0.3907881 -8.748342 -0.3118762 0.9999998 -8.748342 0 0.4936286 -8.748342 -0.07945072 0.8660235 -8.748342 0.5 0.4689149 -8.748342 0.1735057 0.3700085 -8.748342 0.3362912 0.4999988 -8.748342 0.8660256 0.2683453 -8.748342 0.4218918 -2.23027e-6 -8.748342 1 0.03739964 -8.748342 0.4985993 -0.5000032 -8.748342 0.8660256 -0.2023972 -8.748342 0.4572029 -0.8660279 -8.748342 0.5 -0.3942571 -8.748342 0.3075082 -0.492724 -8.748342 0.08497375 -0.9999968 -4.998331 0 -0.8660279 -4.998331 0.5 -0.5000032 -4.998331 0.8660256 -2.23027e-6 -4.998331 1 0.4999988 -4.998331 0.8660256 0.8660235 -4.998331 0.5 0.9999998 -4.998331 0 0.8660235 -4.998331 -0.5000001 0.4999988 -4.998331 -0.8660253 -2.23027e-6 -4.998331 -0.9999998 -0.5000032 -4.998331 -0.8660253 -0.8660279 -4.998331 -0.5000001 1.065602 -10.1955 -0.4840238 0.8378379 -10.14899 -0.2207174 0.4935764 -9.533067 0.1189745 0.5117335 -9.593833 -0.009796619 0.5305238 -9.620596 -0.01655429 0.5576067 -9.814863 -0.361737 0.6719731 -9.918575 -0.4875884 0.7226073 -9.938184 -0.431689 0.653302 -9.922866 -0.5454687 0.6647386 -9.924714 -0.5608839 0.559447 -9.816934 -0.3652606 0.6409265 -9.908904 -0.5217023 0.5470939 -9.763931 -0.2890006 0.5507671 -9.786356 -0.3206381 0.5810611 -9.800081 -0.2759295 0.5549543 -9.811867 -0.3566408 0.6398239 -9.862248 -0.1368211 0.5282738 -9.649177 -0.1270474 0.5409025 -9.726171 -0.2357015 0.5131938 -9.598721 -0.02014082 0.5169712 -9.611357 -0.04689586 0.5224623 -9.629731 -0.08584421 0.4593484 -9.508823 0.1791673 0.5142145 -9.678159 0.1354021 0.4511751 -9.503041 0.1935455 0.6411054 -9.957571 -0.004232466 0.767497 -9.972725 -0.3734865 0.8031555 -10.02139 -0.316551 0.9899341 -10.06529 -0.534244 0.8856483 -9.979907 -0.6168476 0.4498787 -9.445568 0.1934053 0.4628874 -9.445568 0.1701357 0.4802845 -9.445568 0.1390143 0.4887484 -9.445568 -0.01746422 0.4921012 -9.445568 -0.07953315 0.3859229 -9.445568 -0.306611 0.4134156 -9.445568 -0.2812129 0.4360132 -9.445568 -0.2255221 0.4924737 -9.445568 -0.08639091 0.2965756 -9.445568 -0.3891626 0.2476625 -9.445552 -0.4343512 -9.68085e-6 -9.445552 -0.4999992 0.0175364 -9.445552 -0.4996965 0.1533605 -9.445568 -0.4758948 0.1860015 -9.445568 -0.4615147 -0.5071707 -9.571154 0.006498634 -0.4699103 -9.508659 0.1607611 -0.5184956 -9.674061 0.1121255 -0.4572741 -9.49042 0.2057505 -0.6377645 -9.956483 -0.03411394 -0.4601352 -9.492267 0.2012289 -0.5164392 -9.586696 -0.03187036 -0.5278311 -9.616514 -0.04133355 -0.5200825 -9.592805 -0.04695081 -0.5204774 -9.607036 -0.06960195 -0.5209096 -9.622832 -0.09474581 -0.6305449 -9.860758 -0.1672716 -0.5231298 -9.70364 -0.2233521 -0.544066 -9.808693 -0.3886568 -0.529962 -9.783794 -0.350447 -0.5647041 -9.798144 -0.3041975 -0.5250968 -9.775225 -0.337286 -0.5238004 -9.72793 -0.2620128 -0.568027 -9.850968 -0.4535542 -0.6270431 -9.880293 -0.380633 -0.7753543 -9.968449 -0.5624672 -0.6731249 -9.927619 -0.6531715 -0.635127 -9.916607 -0.5940539 -0.7339962 -9.943266 -0.7472393 -0.7295482 -9.943966 -0.7409566 -0.8238874 -10.15079 -0.262309 -0.784906 -10.02214 -0.3565248 -1.042428 -10.18745 -0.5357606 -0.8746631 -10.05759 -0.4665801 -0.9658359 -10.05791 -0.5806126 -0.8585326 -9.971951 -0.6564358 -0.698293 -9.938006 -0.467985 -0.5993493 -9.906236 -0.5383809 -0.2195634 -11.00387 0.448557 0.1070179 -11.0053 0.4768809 0.03584992 -11.00608 0.4904614 -0.01321953 -11.00661 0.499825 -0.2013765 -11.00411 0.4530758 0.1963429 -11.00433 0.4598367 0.2620719 -11.00199 0.4130741 -0.1289643 -9.445552 -0.4702002 -0.1794047 -9.445552 -0.4585437 -0.3946446 -9.445552 -0.3070423 -0.4515521 -9.445552 -0.184238 -0.4657306 -9.445552 -0.1536329 -0.3436751 -9.445552 -0.3484209 -0.3366492 -9.445552 -0.3541271 -0.2194144 -9.445552 -0.4492985 -0.4999511 -9.445552 0.008611381 -0.5000107 -9.445552 0 -0.4893936 -9.445552 -0.1025703 -0.3931619 -9.445537 0.3068297 -0.4559554 -9.445552 0.2052546 -0.4833363 -9.445552 0.08287316 -0.7424973 -4.998331 1.286048 -2.23027e-6 -4.998331 1.485 0.7425003 -4.998331 1.286048 1.28605 -4.998331 0.7425001 1.485003 -4.998331 0 1.28605 -4.998331 -0.7424998 0.7425003 -4.998331 -1.286048 -2.23027e-6 -4.998331 -1.485 -0.7424973 -4.998331 -1.286048 -1.286047 -4.998331 -0.7424998 -1.485 -4.998331 0 -1.286047 -4.998331 0.7425001 0.4761047 -9.630743 -0.2452448 0.5284898 -9.928246 -0.6905506 0.2667285 -9.928246 -0.8276604 0.2664305 -9.927724 -0.8267351 0.4056372 -9.818931 -0.5300348 0.3254838 -9.630743 -0.4253011 0.1642681 -9.630743 -0.509746 0.2047248 -9.818931 -0.6352743 0.1640446 -9.626974 -0.5090559 -0.4943333 -9.627108 -0.2023583 -0.3743119 -9.627108 -0.3810498 -0.1935012 -9.627108 -0.4978539 0.01872849 -9.627108 -0.5338011 0.0304706 -9.927947 -0.8679513 -0.3146179 -9.927947 -0.8095015 -0.6086103 -9.927947 -0.6195806 -0.4664235 -9.817247 -0.47482 0.02334785 -9.817247 -0.6651609 -0.2411179 -9.817247 -0.6203675 -10.65294 -1.875911 3.972074 -10.71373 -1.559247 3.972961 -10.66214 -1.827974 3.972208 -10.34159 -3.172595 3.964951 -10.35964 -3.111068 3.965472 -10.52213 -2.557296 3.970166 -9.912352 -4.356091 3.948162 -10.2202 -3.586281 3.961444 -9.567994 -4.289005 8.000006 -9.897338 -4.393641 3.947514 -9.842019 -4.531969 3.945127 -9.137037 -5.148892 8.000006 -9.257721 -4.92898 8.000006 -9.373257 -4.704912 8.000006 -1.443783 -10.89809 1.647732 1.526085 -10.87506 1.647732 1.418991 -10.79461 3.295457 -0.05104613 -10.90427 3.295457 -1.521701 -10.8034 3.295457 0.04196685 -10.99241 1.647732 -1.286047 -8.098339 0.7425001 -1.485 -8.098339 0 -1.286047 -8.098339 -0.7424998 -0.7424973 -8.098339 -1.286048 -2.23027e-6 -8.098339 -1.485 0.7425003 -8.098339 -1.286048 1.28605 -8.098339 -0.7424998 1.485003 -8.098339 0 1.28605 -8.098339 0.7425001 0.7425003 -8.098339 1.286048 -2.23027e-6 -8.098339 1.485 -0.7424973 -8.098339 1.286048 8.096254 -6.910596 4.380428 7.883808 -7.172529 4.342069 7.715029 -7.380624 4.311594 8.21448 -6.764833 4.401774 2.895882 -7.553358 31.49935 3.258606 -7.376258 13.75001 2.684978 -7.638802 31.49892 4.366567 -6.50372 31.50001 4.366053 -6.503616 13.75001 3.895109 -6.956984 31.50001 3.969831 -6.896947 13.75001 3.487793 -7.216294 31.50001 3.489865 -7.220407 13.75001 3.133175 -7.442031 31.50001 3.01521 -7.499461 31.49974 4.546223 -6.331001 31.50001 5.052981 -5.602886 31.50001 4.578491 -6.292705 13.75001 5.142202 -5.435441 31.50001 8.120676 -8.498331 9.103504 7.875932 -8.498331 9.16037 7.371036 -8.498331 31.16375 7.299339 -8.498331 31.23544 7.192721 -8.498331 30.91788 6.997889 -8.498331 31.06071 7.100699 -8.498331 30.48455 6.654789 -8.498331 31.00001 5.700795 -8.498331 31.00001 7.226554 -8.498331 30.05981 6.079999 -8.498331 28.83943 7.539799 -8.498331 29.74656 6.7493 -8.498331 24.66617 7.964542 -8.498331 29.62071 8.643745 -8.498331 29.89104 8.397876 -8.498331 29.71273 8.53864 -8.498331 10.83386 7.875932 -8.498331 10.83963 8.120676 -8.498331 10.8965 7.875932 -8.498331 16.21893 7.870784 -8.498331 16.46615 8.881925 -8.498331 10.58735 9.074843 -8.498331 10.21131 9.074843 -8.498331 9.788685 8.881925 -8.498331 9.412652 8.53864 -8.498331 9.166139 7.82608 -8.498331 16.98748 7.075136 -8.498331 22.46805 9.081712 -6.298621 5.645625 9.02403 -6.498341 5.601882 9.119688 -6.160681 5.678272 6.514532 -8.496586 4.467994 6.507462 -8.501192 4.446375 6.589291 -8.436266 4.466532 6.504451 -8.503158 4.416374 6.521632 -8.491952 4.357357 6.542069 -8.478601 4.327068 7.022192 -8.159194 4.791675 6.905703 -8.237605 4.741616 7.036766 -8.109931 4.715917 6.853995 -8.272086 4.715597 6.708202 -8.369286 4.642229 6.648598 -8.40867 4.605115 6.561203 -8.466084 4.534496 7.686099 -7.473711 4.716461 7.687015 -7.474561 4.729304 7.831154 -7.608731 5.076825 7.711617 -7.689748 5.038951 7.354622 -7.933292 4.91827 7.058924 -8.134235 4.805665 7.907657 -7.556577 5.100061 7.869517 -7.58255 5.088522 7.888263 -7.538859 5.070596 7.751857 -7.414271 4.734252 7.742783 -7.405986 4.711881 8.20577 -6.833185 4.74324 8.253663 -7.243414 5.18905 8.076965 -7.403333 5.143605 8.028811 -7.356469 5.059714 7.905012 -7.222075 4.719515 8.407845 -7.097472 5.254369 8.289269 -6.965761 5.059431 8.339605 -6.677811 4.75315 8.33582 -6.708 4.877306 8.40926 -6.806914 5.051357 8.495791 -6.923471 5.256451 8.541604 -6.970872 5.311033 8.527725 -6.412823 4.938187 8.797033 -6.72244 5.452626 8.65238 -6.616239 5.295201 8.773921 -6.744925 5.439814 8.824362 -5.901594 5.095188 8.897325 -6.085594 5.406929 8.890747 -5.775992 5.143116 9.006 -5.825196 5.481268 8.952587 -5.955432 5.442478 8.980362 -5.737696 5.338041 8.954732 -5.650212 5.194813 8.972584 -5.723555 5.348291 10.43928 -0.5983304 6.952262 10.32271 -1.028735 6.730466 10.22513 -1.873825 6.630768 10.07131 -2.708811 6.473523 9.900039 -3.392551 6.298268 9.644641 -4.191477 6.03684 9.354187 -4.925881 5.739399 -7.079015 -7.775281 16.34115 -7.088612 -7.75366 16.63514 -7.088105 -7.754807 16.61967 4.900647 -9.286527 16.34254 3.754062 -8.808647 31.05752 4.387808 -8.637492 31.03863 4.5467 -8.612071 31.03394 4.88556 -8.62192 28.6367 5.037283 -8.533572 31.01944 5.425533 -8.649651 24.46495 5.689164 -8.664046 22.26757 6.298778 -8.699392 16.78869 6.901709 -8.625273 16.21893 6.334399 -8.698736 16.40221 6.338527 -8.698646 16.21893 5.812948 -8.913879 16.21893 6.900763 -8.578111 6.27684 7.014436 -8.560513 6.39048 7.050974 -8.555327 6.425556 7.087728 -8.550335 6.460171 7.283007 -8.5277 6.65082 7.476141 -8.511667 6.846048 7.675251 -8.501698 7.045991 7.820202 -8.498599 7.186858 7.825268 -8.498554 7.19361 6.895696 -8.579094 6.271114 7.627082 -8.5035 9.308216 7.473399 -8.512382 9.496298 7.432205 -8.514766 9.54672 7.325088 -8.523677 9.831222 7.321899 -8.523975 9.999935 7.319344 -8.524213 10.13489 7.397828 -8.517418 10.38832 7.474733 -8.512263 10.50297 7.756283 -8.499537 10.78333 7.551675 -8.507107 10.61768 6.305677 -8.707453 5.535012 6.580723 -8.639801 5.914798 6.018487 -8.79309 4.975332 6.062937 -8.7788 5.086675 6.213849 -8.733142 5.384837 8.974707 -7.515792 5.924072 9.053088 -7.255141 5.835306 9.118973 -7.261221 5.88946 9.092255 -7.124905 5.790949 9.132808 -6.88823 5.743571 8.882551 -7.719551 6.026904 8.817314 -7.908586 6.196581 8.767588 -7.898126 6.153974 8.363208 -8.342896 6.654354 8.336453 -8.335505 6.626669 8.54963 -8.176108 6.393897 8.682786 -8.029838 6.247712 7.841265 -8.498167 7.164097 8.131361 -8.442406 6.849859 8.289902 -8.370314 6.677505 8.475437 -8.176763 6.331349 8.594973 -8.030612 6.17374 8.774584 -7.720489 5.936058 8.857704 -7.516791 5.825669 9.024038 -6.500576 5.601885 9.001596 -6.889333 5.633281 8.964336 -7.125993 5.683424 8.927344 -7.261564 5.732769 8.665113 -7.90951 6.08093 8.27623 -8.342538 6.59288 8.242352 -8.370746 6.637359 8.100002 -8.442689 6.823355 7.839164 -8.498181 7.162319 8.68976 -7.408757 5.628299 7.847911 -8.347471 6.343205 8.090405 -8.359376 6.479613 8.44369 -7.978786 5.985928 7.97086 -8.293171 6.176909 8.160105 -8.019481 5.904253 8.349358 -7.745792 5.631599 8.397138 -7.553209 5.551931 7.714187 -8.339141 6.051962 8.054173 -7.889304 5.539953 7.717927 -8.055542 5.465734 7.434738 -8.39876 5.935493 7.678544 -8.069564 5.45108 7.396167 -8.405153 5.912329 7.615214 -8.049537 5.461921 7.50791 -8.268584 5.653283 7.344102 -8.365487 5.897994 6.274102 -8.67017 4.646996 6.354106 -8.638505 4.786148 6.59359 -8.548279 5.051141 6.409077 -8.617197 4.858817 7.027065 -8.40259 5.38039 6.704179 -8.508925 5.146376 7.385453 -8.299861 5.590735 7.353698 -8.496959 31.28631 7.6007 -8.457471 31.50292 7.589442 -8.479853 31.32905 7.679766 -8.462329 31.36212 7.697684 -8.428429 31.57837 7.841317 -8.430992 31.4213 7.836928 -8.367691 31.67317 8.027314 -8.385126 31.43014 8.079893 -8.372162 31.43264 7.970912 -8.309234 31.76439 8.153914 -8.353923 31.43616 8.434652 -8.289699 31.35791 8.514067 -7.909913 32.0171 8.370697 -8.304332 31.37574 8.392436 -8.020927 31.97632 8.09007 -8.2406 31.8336 8.663616 -8.265619 31.19535 8.667609 -8.26614 31.18992 12.8632 -7.91255 27.67158 8.830762 -8.287524 30.96799 8.855386 -8.304049 30.8928 8.906512 -8.338352 30.73673 12.46417 -8.273784 27.27255 12.43757 -8.29788 27.24595 13.02839 -7.547636 27.83676 9.110308 -7.190351 32.07741 12.87232 -7.892419 27.68069 8.893191 -7.496421 32.09265 8.584193 -7.845897 32.04061 13.09325 -7.404317 27.90163 13.19001 -7.190575 27.99838 9.114249 -7.184808 32.07714 9.246885 -6.973495 32.03535 13.22074 -6.947194 28.02911 8.909619 -8.385424 30.54857 8.911645 -8.416061 30.42607 12.35269 -8.374725 27.16106 8.908718 -8.371685 30.60349 8.823497 -8.475457 30.13785 8.84266 -8.462553 30.2005 13.76415 -7.089529 26.86367 12.46695 -8.283172 27.23869 13.0296 -8.043472 27.17363 13.47679 -7.192899 27.62756 13.47679 -6.863494 27.79541 13.0296 -7.812712 27.62653 13.47679 -7.454325 27.36614 13.76415 -7.00124 27.03696 13.76415 -6.863718 27.17448 13.76415 -6.690432 27.26277 13.47679 -6.498341 27.85324 13.69468 -6.498341 27.42859 13.76415 -6.498341 27.2932 13.47679 -7.622172 27.03673 6.32528 -7.669036 31.98533 5.700795 -7.874418 31.89924 5.700795 -8.181353 31.68302 6.396977 -7.977042 31.87798 5.700795 -7.998336 31.86603 6.369022 -7.879619 31.92069 6.351804 -7.819612 31.947 5.700795 -8.397568 31.37609 6.654789 -8.415375 31.37978 6.654789 -8.363609 31.5013 6.609691 -8.325163 31.56246 6.527637 -8.231763 31.67978 5.700795 -8.364369 31.50001 6.510703 -8.20372 31.70523 6.450539 -8.104135 31.79563 6.654789 -8.459334 31.27655 3.233192 -7.967521 31.99947 3.593003 -8.319427 31.87547 3.70649 -8.664151 31.53285 4.356956 -8.494381 31.52215 4.280222 -8.138512 31.8724 5.022337 -8.394037 31.51119 4.983468 -8.031015 31.86926 6.922935 -8.098339 4.168691 6.961485 -8.098339 4.174863 7.000012 -8.098339 4.181034 4.104225 -5.897556 12.82613 4.353469 -6.105218 13.0429 4.520011 -6.243978 13.36732 3.222202 -7.309396 13.36732 3.921536 -6.838117 13.36732 3.783991 -6.670568 13.0429 3.118542 -7.119019 13.0429 3.578139 -6.419827 12.82613 2.963399 -6.834094 12.82613 2.801259 -7.949535 31.96977 2.699283 -7.677529 31.69786 2.740299 -7.787142 31.86396 2.911677 -7.590715 31.6966 2.95723 -7.696394 31.86185 3.025149 -7.853259 31.9683 3.031535 -7.535596 31.69485 3.078943 -7.637758 31.85902 3.149909 -7.789765 31.96623 3.150327 -7.476006 31.69135 3.199173 -7.572774 31.85356 3.27227 -7.717584 31.96195 3.918631 -6.986906 31.69135 5.096947 -5.627502 31.68805 4.575191 -6.355692 31.69135 5.111431 -5.635609 31.75001 4.657698 -6.425981 31.85356 5.191279 -5.680312 31.84151 5.27112 -5.725016 31.93302 4.781169 -6.531183 31.96195 5.325188 -5.75528 31.94962 3.985626 -7.07211 31.85356 4.085888 -7.199635 31.96195 5.417575 -5.574872 31.96195 5.272855 -5.501587 31.85356 5.176155 -5.452622 31.69135 9.321055 -6.715406 32.01942 7.31538 -8.312751 31.89226 6.909085 -8.102093 31.94296 6.936645 -8.23081 31.81787 6.87292 -7.662911 32.15283 6.878232 -7.814918 32.10873 7.066404 -7.956032 32.14661 6.891308 -7.973839 32.0325 6.892813 -7.984702 32.02492 6.874306 -7.490594 32.17309 9.211203 -6.89568 32.0904 9.057118 -7.07515 32.17257 9.168772 -6.816213 32.13777 8.985182 -6.9598 32.24947 8.309013 -7.432778 32.45132 8.696756 -7.176791 32.37122 8.809617 -7.346262 32.25334 8.468276 -7.665638 32.28694 8.070415 -7.569183 32.45886 7.690941 -7.75284 32.40851 8.253827 -7.835377 32.27029 7.9061 -8.062978 32.18809 7.765149 -8.138676 32.13586 7.539628 -7.814202 32.36668 7.190143 -7.927034 32.2184 7.434373 -8.277286 31.96881 7.154433 -8.418027 31.50119 7.014198 -8.362476 31.6524 6.964011 -8.316119 31.70505 6.9622 -8.323927 31.68893 6.961783 -8.32573 31.68521 6.958587 -8.347158 31.63965 7.121464 -8.455668 31.44644 7.104663 -8.45163 31.46637 6.82172 -8.35884 31.55965 6.816422 -8.358975 31.55774 6.903005 -8.459334 31.32046 6.663484 -8.362938 31.50255 6.956135 -8.351703 31.62808 6.927607 -8.356099 31.59786 6.949728 -8.354355 31.61746 6.606316 -7.482697 32.04432 6.606189 -7.49429 32.04426 6.79191 -8.309652 31.61772 6.737081 -8.213569 31.73408 6.686759 -8.084718 31.8474 6.652874 -7.958476 31.92696 6.625605 -7.804249 31.99303 6.611069 -7.658381 32.02968 11.36321 -6.602754 14.42393 12.3632 -6.602754 15.42393 12.3632 -7.602756 14.42393 12.3632 -7.09327 15.27576 12.3632 -7.309858 15.13103 12.3632 -7.454593 14.91444 12.3632 -7.52664 14.80661 12.3632 -6.985445 15.34781 11.43932 -6.985445 14.42393 11.6561 -7.309858 14.42393 11.98052 -7.52664 14.42393 11.43932 -6.749202 14.77748 11.43932 -6.873359 14.69452 11.6561 -6.873359 15.07721 11.6561 -7.102762 14.92393 11.98052 -6.956313 15.27748 11.98052 -7.256035 15.07721 11.51138 -6.602754 14.91444 11.6561 -6.602754 15.13103 11.87269 -6.602754 15.27576 11.98052 -6.602754 15.34781 11.43932 -6.956313 14.57037 11.6561 -7.256035 14.69452 11.98052 -7.456307 14.77748 11.43932 -6.602754 14.80661 -8.54824 -6.025542 8.912244 -8.804942 -5.595986 8.953593 -9.098711 -5.203087 9.014013 -9.110877 -5.181048 10.40624 -8.987146 -5.401049 10.48501 -8.970136 -5.399485 10.45703 -8.696707 -5.850558 10.52808 -8.94654 -5.392302 10.43542 -8.651475 -5.826835 10.50465 -8.890199 -5.364661 10.41971 -9.001623 -5.144973 10.34637 -9.161981 -4.806985 10.17822 -9.180161 -4.766543 10.15148 -9.26199 -4.577283 9.98745 -9.298439 -4.487623 9.849961 -9.309316 -4.459758 9.74646 -9.306537 -4.46694 9.640789 -9.299117 -4.485895 9.583347 -9.26579 -4.568149 9.452537 -9.249011 -4.608248 9.408451 -9.291122 -4.842077 10.22437 -9.311782 -4.801531 10.19531 -9.405869 -4.611839 10.01622 -9.448851 -4.52203 9.864806 -9.461972 -4.494164 9.750011 -9.458603 -4.501332 9.632584 -9.449663 -4.520316 9.568928 -9.410302 -4.602675 9.424802 -9.390781 -4.642848 9.376487 -9.287464 -4.8492 9.200026 -9.135904 -5.135436 9.042677 -9.090434 -5.181391 10.37771 -9.264092 -4.847084 10.19661 -9.283776 -4.807372 10.16794 -9.372014 -4.623462 9.993569 -9.410696 -4.538913 9.850895 -9.421992 -4.513521 9.746433 -9.419131 -4.520003 9.64069 -9.411404 -4.537333 9.582496 -9.376081 -4.61473 9.446966 -9.358096 -4.653205 9.400499 -9.260597 -4.854073 9.227841 -9.114685 -5.136256 9.07125 -9.078624 -5.203192 9.042506 -9.158755 -4.814093 9.246564 -9.024026 -5.099494 9.101134 -8.990715 -5.166937 9.074521 -9.06309 -5.17482 10.35671 -9.23005 -4.842166 10.17809 -9.248803 -4.802753 10.14995 -9.331996 -4.620869 9.979934 -9.367439 -4.538138 9.843012 -9.377467 -4.513626 9.744451 -9.374949 -4.519854 9.645205 -9.368072 -4.536603 9.590173 -9.335766 -4.612271 9.460233 -9.319017 -4.650165 9.415201 -9.226712 -4.849125 9.246449 -9.086514 -5.129863 9.092056 -9.051675 -5.196561 9.063594 -8.829574 -5.607356 8.939272 -8.675406 -5.839784 10.51272 -8.918906 -5.380262 10.42252 -9.032215 -5.162169 10.34582 -9.194183 -4.828085 10.17163 -9.212362 -4.788388 10.14416 -9.292984 -4.604493 9.977764 -9.327436 -4.519869 9.842679 -9.337248 -4.494433 9.744461 -9.334775 -4.500915 9.645241 -9.328063 -4.518275 9.590477 -9.296643 -4.595746 9.46221 -9.280401 -4.634251 9.418015 -9.190957 -4.835088 9.253022 -9.054961 -5.117063 9.102457 -9.021136 -5.183954 9.074716 -8.778314 -5.581815 8.959155 -8.208359 -0.5999993 12.07392 -9.02495 -0.5999993 11.9463 -9.670737 -0.5999993 11.58349 -10.13258 -0.5999993 11.02292 -10.13258 -0.5982857 11.02292 -10.47866 -0.5999993 10.14109 7.23326 -0.4166643 29.38504 6.068987 -0.4166643 29.38504 6.068987 -1.198334 29.11409 10.3632 -1.198334 29.11409 10.3632 -0.4166643 29.38504 8.766739 -0.4166643 29.38504 8.158221 -0.289155 29.40323 8.101886 -0.2773384 29.40458 8.075124 -0.3736446 29.39193 7.921291 -0.2737174 29.40497 8.534289 -0.3923009 29.38903 8.489533 -0.38263 29.39055 7.730601 -0.3204028 29.39939 7.615959 -0.3549734 29.39468 7.327971 -0.4124174 29.38576 9.626909 -1.428423 24.86934 9.75146 -1.656023 25.04714 6.068987 -2.093075 25.55288 9.784906 -1.69575 25.08305 9.939572 -1.814363 25.20325 9.998246 -1.859365 25.24885 10.24005 -1.944987 25.34934 10.3632 -2.093075 25.55288 10.28074 -1.953048 25.35936 10.3632 -1.964865 25.37427 9.524203 -0.941513 24.60408 9.581855 -1.293732 24.78079 6.068987 -1.369683 24.82861 9.605518 -1.369146 24.82946 9.620368 -1.416458 24.86 6.068987 -0.4166643 24.45497 9.502149 -0.4166643 24.45497 9.517869 -0.8635948 24.5739 10.3632 -2.465544 26.50636 6.068987 -2.465544 26.50636 10.3632 -2.42464 27.52919 6.068987 -2.42464 27.52919 10.3632 -1.977233 28.44989 6.068987 -1.977233 28.44989 6.043566 0.9529909 26.25864 6.041703 0.9873232 26.31107 5.922144 2.286794 20.20001 6.054064 0.7302185 26.01868 6.065895 0.3321787 25.80858 6.064696 0.3914704 25.82806 6.068987 2.04768e-6 20.20001 6.068987 2.04768e-6 23.96197 6.06898 0.0086447 25.76004 6.068987 2.04768e-6 25.76 6.05919 0.5749633 25.92495 6.056016 0.6809255 25.98089 6.040914 1.000675 26.34171 6.033992 1.118096 26.61103 6.033031 1.13328 26.67247 6.031317 1.159998 26.92 6.034253 1.113864 27.24389 5.905946 2.284708 31.50001 6.035437 1.094776 27.30352 6.041115 0.9953401 27.49521 6.044043 0.9440502 27.59407 6.045987 0.9064993 27.64378 6.0565 0.6681403 27.86827 6.05837 0.6159713 27.90295 6.059361 0.5778989 27.91987 6.003675 1.52685 31.50001 6.066178 0.3169348 28.03587 6.067154 0.2556166 28.0515 6.068987 2.04768e-6 28.08001 6.068987 2.04768e-6 29.87804 6.068987 2.04768e-6 31.50001 5.484035 4.536035 31.50001 5.484035 4.536035 20.20001 5.808217 3.042551 31.50001 10.3632 1.159998 26.92 10.3632 0.5799999 25.91542 10.3632 2.04768e-6 25.76 10.3632 1.004594 26.34001 10.3632 0.5799999 27.9246 10.3632 1.004594 27.50001 6.068987 -0.5799959 25.91542 10.3632 -0.5799959 25.91542 6.068987 -1.004589 26.34001 10.3632 -1.004589 26.34001 6.068987 -1.159994 26.92 10.3632 -1.159994 26.92 6.068987 -1.004589 27.50001 10.3632 -1.004589 27.50001 6.068987 -0.5799959 27.9246 10.3632 -0.5799959 27.9246 10.3632 2.04768e-6 28.08001 9.500994 -0.3409962 24.42858 6.068987 -0.2033243 24.36443 9.499734 -0.2586672 24.39986 6.068987 -0.05371659 24.18742 9.503475 -0.1276562 24.29567 9.501195 -0.2074966 24.35918 9.592837 2.04768e-6 23.96197 9.585997 -8.17516e-4 23.97782 9.570679 -0.00265032 24.01333 9.525313 -0.04015654 24.1583 9.521043 -0.05726307 24.18516 7.23326 -0.2033243 29.47558 6.068987 -0.2033243 29.47558 7.23326 -0.05371659 29.65259 6.068987 -0.05371659 29.65259 7.23326 2.04768e-6 29.87804 10.3632 6.300004 25.37427 10.3632 6.300004 30.5858 10.3632 2.04768e-6 30.5858 10.3632 2.04768e-6 29.87804 10.3632 -0.05371659 29.65259 10.3632 -0.2033243 29.47558 -10.52666 2.04768e-6 16.2179 -10.52666 4.67512e-5 16.2179 -10.52666 6.16523e-5 14.87507 -10.52666 9.14547e-5 16.2179 -10.52666 1.21257e-4 13.53224 -8.861403 2.04768e-6 11.36772 -8.829216 2.04768e-6 11.37521 -8.839393 0.1978 11.41097 -10.07224 0.09671056 6.861727 -10.06459 2.04768e-6 6.883998 -10.06489 2.04768e-6 7.06724 -7.118026 0.338318 11.39978 -7.129336 0.4150441 11.47898 -7.758687 0.4200509 11.61236 -7.154512 0.599595 11.94893 -7.199349 0.5997589 11.95433 -7.110777 0.5972555 11.93166 -7.13704 0.5771836 11.76129 -7.266695 0.5999824 11.96246 -7.320503 0.5999973 11.97435 -7.107484 0.5988201 11.95084 -7.102976 0.5974045 11.96906 -7.127101 0.5989691 11.95476 -7.10837 0.5991032 11.94728 -7.397192 0.5999973 11.99131 -7.70996 0.5800893 11.88299 -7.139849 0.5750378 11.74307 -7.138545 0.4775246 11.54347 -7.78314 0.1978 11.47656 -7.099638 0.1968464 11.32254 -7.101784 0.213342 11.33154 -7.088261 2.04768e-6 11.28155 -7.097411 0.1797249 11.31319 -7.267455 2.04768e-6 11.33402 -7.74082 2.04768e-6 11.43645 -7.789346 2.04768e-6 11.43978 -10.10412 0.2169331 6.768232 -10.09873 0.1977553 6.784049 -10.09932 0.1978 7.068178 -10.07537 0.1146665 6.852596 -10.17543 0.3522357 6.554271 -10.1506 0.3137162 6.629566 -10.23726 0.4200509 7.072045 -10.51213 0.5800893 7.079751 -10.48976 0.5755892 5.503167 -10.4449 0.5651286 5.670483 -10.31952 0.4978051 6.098349 -10.2579 0.4474392 6.297508 -10.2328 0.4184564 6.375666 -10.79153 0.572609 4.254752 -10.73177 0.5895069 4.532596 -10.71923 0.5942305 5.176217 -10.64495 0.5945733 4.896781 -10.65337 0.589179 5.890829 -10.20704 0.4200509 8.876371 -10.50394 0.5802235 8.062717 -10.5041 0.5777201 7.510326 -10.51049 0.5782118 7.440969 -10.54378 0.5807599 7.079792 -10.58585 0.5980303 5.144711 -10.48097 0.5800893 8.900257 -10.50356 0.5863627 8.902589 -10.50379 0.5828312 8.635834 -10.50301 0.5953779 9.582477 -10.3712 0.5800893 9.918397 -10.50279 0.5987903 9.949308 -10.19359 0.5800893 10.52692 -10.38439 0.5999973 10.48001 -10.50272 0.5999973 10.0791 -9.923349 0.5800893 11.07126 -10.19744 0.5999973 10.92231 -10.33861 0.5999973 10.58834 -9.693252 0.5999973 11.57462 -9.799423 0.5999973 11.46117 -9.69589 0.5800893 11.35044 -9.986768 0.5999973 11.26099 -10.04835 0.5999973 11.16199 -9.49655 0.5999973 11.72396 -9.37807 0.5800893 11.60793 -9.458253 0.5999973 11.74379 -9.112003 0.5999973 11.92306 -8.95452 0.5800893 11.80758 -8.998635 0.5999973 11.95995 -7.682788 0.5999973 12.03151 -7.995682 0.5999973 12.07555 -8.405352 0.5800893 11.91296 -8.396591 0.5999973 12.07588 -8.880424 0.5999973 11.99843 -9.386303 2.04768e-6 11.02305 -9.412469 0.1978 11.04993 -9.55681 2.04768e-6 10.80676 -9.58843 0.1978 10.82985 -9.590435 2.04768e-6 10.7641 -9.696367 2.04768e-6 10.5608 -9.813266 0.1978 10.36586 -9.776065 2.04768e-6 10.35038 -8.273418 2.04768e-6 11.47297 -8.389915 0.1978 11.50028 -8.388506 2.04768e-6 11.46462 -8.47059 2.04768e-6 11.45866 -9.364109 2.04768e-6 11.0512 -9.278843 2.04768e-6 11.12877 -9.168746 0.1978 11.25207 -9.145523 2.04768e-6 11.21337 -8.978645 2.04768e-6 11.31927 -8.395071 0.4200509 11.63816 -8.877861 0.4200509 11.54349 -9.238693 0.4200509 11.37098 -9.507166 0.4200509 11.15034 -9.700338 0.4200509 10.91051 -9.940343 0.4200509 10.41967 -10.10321 0.4200509 9.856785 -10.0659 2.04768e-6 7.669259 -10.06958 0.1978 8.864384 -10.0359 2.04768e-6 8.866921 -9.968723 0.1978 9.825869 -9.974519 2.04768e-6 9.576118 -9.925532 2.04768e-6 9.816213 -9.863819 2.04768e-6 10.11872 8.654384 0.3599992 14.0384 9.07222 0.3599992 13.56894 9.246608 0.5294105 13.66195 9.355856 0.5999973 13.97635 9.012832 0.5999973 14.30219 8.812061 0.5294105 14.15763 9.444087 0.1886507 12.75001 9.536802 0.3559014 12.75001 9.373865 0.3599992 13.09944 9.895376 0.5999973 13.1196 9.813248 0.5999973 13.25002 9.560338 0.5294105 13.16494 9.682185 0.4896095 12.75001 9.754283 0.5223026 12.75001 9.873687 0.5764386 12.75001 10.04959 0.5999973 12.75001 9.283295 0.1679977 13.06762 9.254395 2.04768e-6 13.05647 9.440428 0.167506 12.75001 9.411408 2.04768e-6 12.75001 8.050559 0.1671931 14.42201 8.049367 0.1642128 14.42128 8.516586 2.04768e-6 14.00584 8.045463 0.1544377 14.41888 8.026293 2.04768e-6 14.40812 8.222944 0.4697611 14.54153 8.137731 0.3561696 14.47864 8.112936 0.3231188 14.46035 8.471599 0.5999973 14.8163 8.356212 0.569286 14.66862 8.292033 0.5213639 14.60742 9.477428 0.5999973 13.78329 8.5778 0.1679977 13.98049 8.556573 2.04768e-6 13.96402 8.987523 0.1679977 13.52376 8.848584 2.04768e-6 13.65862 8.958018 2.04768e-6 13.50647 9.186818 2.04768e-6 13.18836 -3.720152 3.185e-5 10.65598 -2.393963 3.185e-5 11.02988 -2.393963 2.04768e-6 11.02988 -6.187263 3.185e-5 9.439655 -4.9909 3.185e-5 10.12325 -4.9909 2.04768e-6 10.12325 -8.286895 3.185e-5 7.662686 -7.291416 3.185e-5 8.615372 -7.291416 2.04768e-6 8.615372 -8.286895 2.04768e-6 7.662686 -9.158867 2.04768e-6 6.595797 -9.158867 3.185e-5 6.595797 -6.187263 2.04768e-6 9.439655 -3.720152 2.04768e-6 10.65598 -9.158867 6.16523e-5 6.595797 -9.134631 6.16523e-5 6.625449 -7.291416 6.16523e-5 8.615372 -8.115793 6.16523e-5 7.826428 -8.286895 6.16523e-5 7.662686 -6.942439 6.16523e-5 8.875894 -4.9909 6.16523e-5 10.12325 -5.636583 6.16523e-5 9.754316 -6.187263 6.16523e-5 9.439655 -4.222671 6.16523e-5 10.44531 -2.393963 6.16523e-5 11.02988 -2.727138 6.16523e-5 10.93595 -3.720152 6.16523e-5 10.65598 8.984996 2.04768e-6 6.846856 8.918657 2.04768e-6 6.917143 8.918657 3.185e-5 6.917143 8.918657 6.16523e-5 6.917143 9.010478 3.185e-5 6.826052 9.063615 2.04768e-6 6.790643 9.114555 2.04768e-6 6.766182 9.122587 2.04768e-6 6.76156 -7.197822 8.000003 3.675876 -7.091495 8.100006 3.673357 -6.689327 8.100006 4.36299 7.608068 7.244022 4.288289 7.691753 7.13134 4.304732 7.050869 7.134171 5.296816 8.589341 5.746858 4.657304 8.275023 5.726623 5.157128 8.391349 6.076367 4.547712 7.631053 6.076367 5.732666 8.091917 6.592544 4.383351 8.703484 5.754204 4.475786 8.462569 6.085815 4.441915 8.207357 6.43711 4.406032 6.965277 8.066537 4.217775 6.413673 8.080157 4.814645 6.194962 7.134171 6.276426 -8.235181 6.738903 3.799844 -7.931987 7.107483 3.763611 -7.386516 7.134171 4.817718 -7.710906 7.376255 3.737191 -7.505076 7.626476 3.712594 -8.903111 5.791189 3.884389 -8.724059 6.073909 3.860727 -8.674386 6.076367 3.981392 -8.721213 6.078409 3.86035 -8.529561 6.381022 3.835024 -8.321139 6.634401 3.810116 -7.994318 6.076367 5.214144 -8.148412 5.726623 5.315175 -8.941317 5.726623 3.889066 -8.85659 5.726623 4.064907 -8.613454 5.726623 4.569512 -7.140304 6.076367 6.333441 -6.130921 6.076367 7.314929 -6.251584 5.726623 7.459871 -7.018338 5.726623 6.768677 -7.279175 5.726623 6.457367 -7.892864 5.726623 5.724921 -3.736826 6.076367 8.782516 -4.878367 5.726623 8.442369 -4.988144 6.076367 8.137251 -5.087773 5.726623 8.300988 -6.006928 5.726623 7.680419 -2.404193 6.076367 9.23668 -3.654654 5.726623 9.039663 -3.812792 5.726623 8.962478 -1.019249 6.076367 9.489865 -2.359668 5.726623 9.460655 -2.454104 5.726623 9.429954 0.3878675 6.076367 9.53656 0.3422104 5.726623 9.744481 -1.018661 5.726623 9.697131 1.78655 6.076367 9.37575 1.696413 5.726623 9.601781 0.395862 5.726623 9.738827 3.146355 6.076367 9.010931 3.017528 5.726623 9.271814 1.82311 5.726623 9.570137 4.437697 6.076367 8.450044 4.27979 5.726623 8.761017 3.209663 5.726623 9.194062 5.632488 6.076367 7.705293 5.458583 5.726623 8.07935 4.525629 5.726623 8.618853 6.704716 6.076367 6.792882 6.530916 5.726623 7.240108 5.742652 5.726623 7.85703 7.777674 5.726623 5.843289 7.475873 5.726623 6.259661 6.834505 5.726623 6.925117 5.20425 7.134171 7.119467 4.100306 7.134171 7.807596 2.90714 7.134171 8.325839 1.650719 7.134171 8.662919 0.3583781 7.134171 8.811505 -0.9417556 7.134171 8.768361 -2.221408 7.134171 8.534425 -3.452713 7.134171 8.11479 -4.608901 7.134171 7.518584 -5.664798 7.134171 6.758782 -6.597432 7.134171 5.851916 -5.974727 8.100006 5.299572 -5.130115 8.100006 6.120843 -4.173877 8.100006 6.808929 -3.126825 8.100006 7.348861 -2.011734 8.100006 7.728889 -0.8528702 8.100006 7.940743 0.3245525 8.100006 7.979816 1.494912 8.100006 7.845254 2.632742 8.100006 7.53999 3.713293 8.100006 7.070662 4.713041 8.100006 6.447484 5.61024 8.100006 5.684015 7.241522 8.100006 2.713255 7.350748 8.100006 1.644432 6.426131 8.876758 1.644885 2.74167 10.60511 1.596323 2.740299 10.60403 1.644569 4.072522 10.18804 1.644885 3.7856 9.800824 6.448566 3.994209 9.698751 6.466246 4.033452 10.08518 3.290483 6.349248 8.774924 3.290483 6.301684 8.631589 4.555403 6.3453 8.60578 4.507956 6.405374 8.570226 4.442612 6.413122 8.565071 4.436736 6.462646 8.532109 4.399168 6.47307 8.524614 4.393431 6.579084 8.448349 4.335079 6.606845 8.428367 4.319795 7.136209 8.087235 3.286828 6.644425 8.401068 4.300009 6.636982 8.406701 4.303208 5.156165 9.105163 6.423602 5.385396 8.999485 6.203907 5.245363 9.496125 3.290483 5.42551 8.982169 6.154356 5.687004 8.877682 5.751892 5.975937 8.778321 5.141899 6.040198 8.758428 4.980489 6.056299 8.751708 4.948738 6.187839 8.696871 4.689327 6.205273 8.687915 4.663804 6.214653 8.683103 4.650073 6.26455 8.653569 4.59579 4.648311 9.378733 6.521681 4.799796 9.293693 6.536787 5.118345 9.124416 6.442798 4.964565 9.202706 6.520846 3.104863 10.05677 6.385398 2.722954 10.18961 6.348466 2.893445 10.13626 6.365781 2.719236 10.23895 5.974236 2.715697 10.28688 5.600006 2.71449 10.30384 5.464343 2.786939 10.6411 5.51177e-6 3.598881 10.3946 5.51177e-6 4.129929 10.16864 5.51177e-6 5.303411 9.599986 1.644885 5.346877 9.589391 5.51177e-6 4.994271 9.800868 5.51177e-6 6.29474 9.020867 5.51177e-6 6.456432 8.897561 5.51177e-6 7.386213 8.100006 1.297398 7.442584 8.100006 -1.10904e-4 7.035678 8.455801 5.04611e-6 2.711383 10.58103 2.664342 2.711972 10.5288 3.191972 2.712076 10.51919 3.289012 13.8632 6.300004 14.42001 11.27096 6.300004 14.42001 13.8632 0.5999973 14.42001 11.27096 0.5999973 14.42001 10.1741 3.373878 6.730904 9.912452 4.245596 6.469254 12.69163 6.499993 9.248435 9.156099 6.499993 5.712899 9.156099 6.500097 5.712899 9.19634 6.499993 5.753139 9.178809 5.980717 5.735606 9.156099 6.02478 5.712899 9.156099 6.300287 5.712899 9.59134 5.09377 6.148142 10.59223 0.5999973 7.149026 10.52611 1.457678 7.082911 12.69163 0.5999973 9.248435 10.48475 1.796993 7.041544 10.33547 2.680304 6.892277 13.8632 6.499993 12.07686 13.8632 6.499993 26.67158 13.8632 6.300004 26.67158 13.8632 3.940897 13.17209 13.8632 3.955321 13.13398 13.8632 3.503161 13.74684 13.8632 3.500002 13.75001 13.8632 0.5999973 13.75001 13.8632 3.694551 13.53724 13.8632 3.74444 13.48259 13.8632 3.785791 13.4373 13.8632 3.999995 12.88398 13.8632 3.999995 12.07686 13.8632 3.899502 13.24288 13.8632 3.929766 13.19114 13.27509 0.5999973 9.989027 13.27509 3.500002 9.989027 13.27691 3.503265 9.992006 13.18908 6.499993 9.854579 13.32464 3.586861 10.07834 13.31221 6.499993 10.08493 13.72691 3.999995 11.04158 13.66369 3.999995 10.82934 13.55872 6.499993 10.54613 13.57911 3.961535 10.59649 13.57829 3.961178 10.59425 13.52025 3.892677 10.4626 13.48124 3.846647 10.37412 13.46369 3.825935 10.3343 13.44441 3.796654 10.29503 13.38538 3.693255 10.18824 13.37787 3.680082 10.17463 13.78634 6.499993 11.2965 13.71053 6.499993 11.04655 10.28795 1.389357 6.694879 10.36357 0.5945137 6.754648 10.31124 0.5889853 6.59784 10.41534 0.5999973 6.909821 10.43898 0.5999973 6.951877 8.989176 5.693393 5.365125 9.515239 4.366489 5.43946 9.402967 4.666285 5.317101 9.386933 4.850628 5.772729 9.028903 5.479561 4.908548 9.694202 3.888639 5.634487 9.696557 4.043775 6.089769 9.910478 3.160315 5.870048 9.948714 3.214451 6.347881 9.931198 3.090548 5.892611 10.10416 2.554568 6.506974 10.07721 2.456205 6.051591 10.24806 1.712876 6.654108 10.17471 1.873242 6.157401 10.2126 1.6467 6.198517 10.25015 1.335504 6.239217 10.30845 0.5861094 6.302415 8.682376 0.5999973 15.41757 8.682376 2.04768e-6 15.41757 8.686944 2.04768e-6 15.52535 8.049442 3.998341 14.42116 8.686944 3.998341 15.52535 8.516124 0.5999973 14.88784 8.516124 3.998341 14.88784 7.41194 2.04768e-6 14.25034 8.516124 2.04768e-6 16.16285 8.516124 3.998341 16.16285 8.049442 2.04768e-6 16.62953 8.049442 3.998341 16.62953 7.41194 2.04768e-6 16.80035 7.41194 3.998341 16.80035 6.774438 2.04768e-6 16.62953 6.774438 3.998341 16.62953 6.307756 2.04768e-6 16.16285 6.307756 3.998341 16.16285 6.136937 2.04768e-6 15.52535 6.136937 3.998341 15.52535 6.307756 2.04768e-6 14.88784 6.307756 3.998341 14.88784 6.774438 2.04768e-6 14.42116 6.774438 3.998341 14.42116 7.41194 3.998341 14.25034 9.938037 0.4218688 11.25001 10.08308 0.5269518 11.25001 3.499982 3.500002 11.25001 10.09921 0.5386343 11.25001 11.13846 3.500002 11.25001 10.36176 0.5999973 11.25001 11.13846 0.5999973 11.25001 9.891695 0.35535 11.25001 3.499982 3.319459 11.25001 9.823716 0.2577772 11.25001 3.912126 2.81726 11.25001 4.253325 2.269672 11.25001 4.833569 2.04768e-6 11.25001 9.765952 2.04768e-6 11.25001 4.823585 0.3009161 11.25001 9.769334 0.0638684 11.25001 4.777459 0.7157644 11.25001 9.7979 0.1657029 11.25001 4.640033 1.32783 11.25001 4.421612 1.92474 11.25001 5.467196 3.500002 12.75001 5.467196 2.04768e-6 12.75001 11.13846 0.5999973 12.75001 11.13846 3.500002 12.75001 12.3632 3.500002 13.25001 12.3632 0.5999973 13.25001 11.89075 0.5999973 13.15728 11.89075 3.500002 13.15728 11.48838 0.5999973 12.89286 11.48838 3.500002 12.89286 13.3632 3.500002 13.25001 13.3632 0.5999973 13.25001 12.84861 3.500002 10.75 12.3632 3.500002 10.75 12.84861 0.5999973 10.75 12.3632 0.5999973 10.75 11.48838 3.500002 11.10715 11.48838 0.5999973 11.10715 11.89075 0.5999973 10.84273 11.89075 3.500002 10.84273 13.55564 3.500002 13.28852 13.61321 0.5999973 13.31699 13.60844 3.500002 13.32407 13.71842 3.500002 13.39812 13.79622 0.5999973 13.5 13.82649 3.500002 13.56193 13.78884 3.500002 13.50487 13.0543 0.5999973 10.70573 13.34403 3.500002 10.18255 13.34469 0.5999973 10.18759 13.34364 3.500002 10.18751 13.32755 3.500002 10.39356 13.32644 0.5999973 10.39721 13.32575 3.500002 10.39682 13.22526 3.500002 10.57884 13.22357 0.5999973 10.58076 13.22326 3.500002 10.58033 13.05546 3.500002 10.70521 13.05424 3.500002 10.70547 11.32744 0.5999973 11.21292 11.32744 3.500002 11.21292 11.32744 0.5999973 12.7871 11.32744 3.500002 12.7871 9.645691 6.300004 14.53598 9.97918 0.5999973 14.20249 9.97918 6.300004 14.20249 10.42843 0.5999973 14.05894 10.42843 6.300004 14.05894 10.8935 0.5999973 14.13725 10.8935 6.300004 14.13725 9.502134 2.04768e-6 14.98523 9.513183 2.04768e-6 14.89215 9.513183 0.5999973 14.89215 9.863204 6.300004 15.82776 9.863204 2.04768e-6 15.82776 9.580447 2.04768e-6 15.4503 9.580447 6.300004 15.4503 9.502134 6.300004 14.98523 9.645691 0.5999973 14.53598 9.863204 2.04768e-6 23.61225 9.863204 6.300004 23.61225 9.926548 0.3599992 10.22401 9.924969 0.3599992 8.903759 10.12056 0.5294105 8.875343 10.40282 0.5999973 9.370024 10.38553 0.5999973 10.16133 10.12257 0.5294105 10.19835 10.15598 0.5293509 6.298606 10.30739 0.5807301 5.845764 10.39032 0.5952736 5.702256 10.34417 0.5878826 5.731481 10.4178 0.597032 5.497137 10.41351 0.5999973 7.27049 10.12706 0.5294105 7.304712 10.15537 0.5291423 6.300435 10.06944 0.4798194 6.545807 9.840733 0.1678189 7.162899 9.862712 0.2325943 7.105758 9.930855 0.3599992 7.32869 9.872144 0.2528896 7.081062 9.932978 0.3510436 6.919949 9.96597 0.3903231 6.83115 9.835555 0.1679977 7.340336 9.812115 2.04768e-6 7.343253 9.813665 2.04768e-6 7.232937 9.813665 4.67512e-5 7.232937 9.82189 0.09700858 7.211739 9.829975 0.1361241 7.190854 9.831337 0.1679977 10.23647 9.777917 2.04768e-6 11.09323 10.40555 0.5999973 8.834777 9.799487 2.04768e-6 10.23938 9.809768 2.04768e-6 9.832301 9.829967 0.1679977 8.91756 9.808666 2.04768e-6 9.390003 9.808271 2.04768e-6 8.921009 9.807235 2.04768e-6 7.68857 -5.750845 4.165592 12.75001 -5.868363 3.998341 12.75001 -5.220781 3.998341 12.75001 -1.933026 3.749999 12.75001 -2.213763 6.747114 12.75001 -3.239716 6.318899 12.75001 -5.220781 2.04768e-6 12.75001 -2.000014 2.04768e-6 12.75001 -2.000014 3.500002 12.75001 -4.18626 5.735816 12.75001 -5.030202 5.012126 12.75001 4.052987 3.999995 12.75001 4.052987 5.326243 12.75001 -1.500013 3.999995 12.75001 3.810217 5.654247 12.75001 2.165159 6.762864 12.75001 1.083081 7.017912 12.75001 -0.02555024 7.100956 12.75001 -1.750017 3.933014 12.75001 -1.133548 7.00994 12.75001 3.335325 6.125705 12.75001 2.780398 6.499665 12.75001 10.07031 4.598336 31.2929 9.363203 4.598336 32.00001 10.07031 2.04768e-6 31.2929 9.363203 2.04768e-6 32.00001 3.812884 7.749247 32.00001 3.369865 7.884295 32.00001 4.206126 7.350149 32.00001 4.921799 6.662817 32.00001 5.489258 5.848812 32.00001 5.900001 7.499995 32.00001 5.588283 5.662965 32.00001 5.900001 4.897626 32.00001 5.692994 7.499995 32.00001 5.318878 7.509696 32.00001 4.559843 7.589506 32.00001 -6.515491 2.823623 12.75001 -6.755042 2.189474 12.75001 -6.515491 2.04768e-6 12.75001 -7.013987 1.108321 12.75001 -7.101016 2.04768e-6 12.75001 -8.001732 1.264395 13.75001 -8.101018 2.04768e-6 13.75001 -8.024896 2.04768e-6 13.36732 -7.854032 1.881095 13.75001 -7.926548 1.252519 13.36732 -6.481121 3.295454 12.76936 -6.671684 3.390329 12.82613 -5.927341 3.998341 12.7512 -6.346436 3.998341 12.83346 -6.326059 3.998341 12.82613 -6.060767 4.390092 12.82613 -6.326 3.998341 12.8261 -5.980412 3.998341 12.75433 -7.119084 2.307462 12.82613 1.223994 7.930981 13.36732 2.446858 7.642748 13.36732 2.470066 7.715242 13.75001 1.235602 8.006217 13.75001 0.6032341 8.053573 13.75001 -0.02886575 8.024829 13.36732 -0.02914142 8.100944 13.75001 -1.281025 7.921981 13.36732 -1.293177 7.997127 13.75001 -2.501781 7.624956 13.36732 -2.525511 7.697271 13.75001 -3.110732 7.453026 13.75001 -3.661218 7.141026 13.36732 -3.695945 7.208766 13.75001 -4.73092 6.482067 13.36732 -4.775794 6.543564 13.75001 -5.684654 5.664231 13.36732 -7.222022 3.669994 13.75001 -7.154161 3.635498 13.36732 -6.5607 4.752221 13.75001 -6.499054 4.707562 13.36732 -6.149637 5.235093 13.75001 -5.738574 5.717965 13.75001 -7.633912 2.47434 13.36732 -7.706324 2.497809 13.75001 -6.960908 3.537299 13.0429 -6.323504 4.580395 13.0429 -5.531097 5.511226 13.0429 -4.60312 6.306978 13.0429 -3.562319 6.94813 13.0429 -2.434204 7.418977 13.0429 -1.246425 7.707985 13.0429 -0.02809089 7.808061 13.0429 1.190928 7.716747 13.0429 2.380756 7.436292 13.0429 -6.471793 3.423439 12.77461 -6.358961 3.940897 12.82758 -5.301284 5.28224 12.82613 -4.411864 6.044926 12.82613 -3.414305 6.659435 12.82613 -2.333062 7.110732 12.82613 -1.194636 7.387714 12.82613 -0.02692115 7.483633 12.82613 1.141449 7.396119 12.82613 2.281842 7.127316 12.82613 -7.427702 2.407493 13.0429 -7.712434 1.218679 13.0429 -7.391984 1.168045 12.82613 -7.808121 2.04768e-6 13.0429 -7.483701 2.04768e-6 12.82613 8.99799 8.499998 28.6723 9.492292 8.499998 29.04249 11.86321 8.499998 26.67158 11.82478 8.499998 11.68668 11.71096 8.499998 11.31149 10.00194 8.499998 10.86777 11.52614 8.499998 10.96572 10.2 8.499998 10 11.27742 8.499998 10.66265 10.14374 8.499998 9.528971 5.900001 8.499998 31.00001 5.900001 8.499998 30.52 5.692994 8.499998 31.00001 5.990808 8.499998 29.90916 6.07456 8.499998 28.74883 8.417374 8.499998 28.4619 6.255363 8.499998 29.35114 6.670808 8.499998 28.8942 6.714088 8.499998 24.59789 7.201192 8.499998 28.57787 7.800666 8.499998 28.42949 7.736792 8.499998 16.96156 7.021656 8.499998 22.43125 7.782122 8.499998 11.95586 7.782122 8.499998 16.22733 8.645041 8.499998 11.94986 7.759084 8.499998 16.75118 11.86321 8.499998 12.07686 9.446977 8.499998 11.56366 6.311921 3.063249 32.00001 6.311921 4.598336 32.00001 6.300924 3.127637 32.00001 5.984483 4.598336 32.00001 9.345217 4.598336 32.00001 9.345217 2.04768e-6 32.00001 10.17071 6.499993 31.1925 13.27742 6.499993 28.08579 10.16547 7.255928 30.98793 13.21435 6.948413 28.02272 10.16529 7.264631 30.98082 13.16976 7.265361 27.97814 13.10237 7.40801 27.91075 10.15487 7.761361 30.57488 12.8632 7.914217 27.67158 10.13884 7.910969 30.3911 12.87273 7.894041 27.68111 13.02858 7.564174 27.83696 9.995809 8.287223 29.80849 10.04235 8.220034 29.9357 10.13169 7.977607 30.30923 12.4044 8.347752 27.21277 9.730435 8.465888 29.32452 12.46528 8.290233 27.27366 12.44559 8.30883 27.25397 9.932092 8.33981 29.6807 9.829222 8.424701 29.47438 5.692994 7.882686 31.92389 5.900001 7.882686 31.92389 5.692994 7.990511 31.85184 5.900001 7.990511 31.85184 5.692994 8.2071 31.70712 5.900001 8.2071 31.70712 5.692994 8.351835 31.49053 5.900001 8.351835 31.49053 5.692994 8.423882 31.38269 5.900001 8.423882 31.38269 13.27742 6.300004 28.08579 10.17071 6.300004 31.1925 9.635648 8.367586 29.36907 9.421236 8.399995 29.11285 9.246981 4.598336 28.95635 10 4.598336 30.52 10 7.698299 30.52 9.801938 4.598336 29.65224 9.984797 7.903727 30.27389 9.910731 8.134025 29.92916 9.870543 8.197861 29.81215 9.795433 8.264722 29.65536 9.723811 8.328455 29.50587 6.000002 8.399995 30.52 6.000002 4.598336 30.52 6.086481 8.399995 29.93825 6.198061 4.598336 29.65224 6.754776 8.399995 28.95929 6.734101 8.399995 28.97162 6.753017 4.598336 28.95635 6.338445 8.399995 29.4068 6.217671 8.399995 29.66154 7.239235 8.399995 28.67035 7.554961 4.598336 28.57015 7.560102 8.399995 28.59093 7.810158 8.399995 28.52904 8.445045 4.598336 28.57015 8.397496 8.399995 28.55991 9.234501 8.399995 28.973 8.950463 8.399995 28.76029 8.442803 8.399995 28.57633 -6.838413 8.101376 8.601487 -6.661387 8.254382 8.927567 -5.792821 8.901241 6.388648 -6.926554 8.022445 8.480031 -6.219866 8.606287 6.453685 -6.441931 8.425477 6.511721 -7.140676 7.82104 6.731647 -7.180432 7.784264 6.746663 -7.180432 7.784264 8.211739 -6.8201 8.117544 6.610556 -7.005098 7.948758 8.39703 -6.59688 8.308368 9.09972 -6.570304 8.330183 9.219524 -6.515378 8.375274 9.467098 -6.500298 8.387508 9.680026 -6.529825 8.363533 10.05874 -5.795116 8.904549 16.19449 -6.549778 8.347186 10.15178 -6.562005 8.337172 10.20878 -6.690124 8.230018 10.56574 -6.747196 8.181113 10.67781 -6.960178 7.991822 10.99076 -6.960901 7.991182 10.99182 -7.045346 7.91307 11.08723 -6.095918 8.698019 16.19707 -7.180432 7.784264 11.21755 -7.180432 7.784264 16.21937 -6.813014 8.123773 16.21131 -7.180447 7.784249 16.2206 -5.683655 8.97664 6.372022 -5.637067 9.013074 16.19314 -5.553695 9.066405 6.35223 -2.395751 10.36744 16.19207 -2.396206 10.36893 6.147125 -2.923305 10.24127 6.182245 -3.119121 10.18365 16.19481 -3.833647 9.935649 6.229536 -3.934959 9.890529 6.234787 -3.956693 9.886744 16.19893 -4.161353 9.789692 6.246519 -4.162232 9.791928 16.19795 -4.699709 9.549918 6.274416 -4.817026 9.489912 16.19482 -4.827755 9.484323 6.282939 -4.853325 9.469601 6.285379 -2.17441 10.42266 6.132346 -2.194258 10.41863 16.1913 -1.577499 10.51569 6.11379 -1.256759 10.56412 16.19558 -1.289765 10.56053 6.104845 -0.7291458 10.60657 16.20025 -0.5533941 10.60769 6.123373 -0.553789 10.60759 16.201 -0.3683217 10.61955 6.128029 1.301599 10.50469 16.20371 1.302061 10.507 6.196127 1.177026 10.52785 16.20308 1.198111 10.52493 6.1868 0.2363004 10.61218 16.20437 0.2709232 10.61064 6.147548 -0.09933334 10.6158 6.136243 3.104044 10.05368 16.2204 2.615606 10.2215 16.21391 2.109175 10.35464 16.20778 1.834882 10.41511 6.243934 1.379249 10.49368 6.203053 4.799796 9.293693 16.22733 4.38453 9.518745 16.22762 3.522021 9.910064 16.22597 -7.268662 7.698389 8.138637 -9.242209 5.085277 7.44372 -9.295965 4.994424 7.401843 -9.530316 4.598336 7.710251 -8.481683 6.274628 7.361601 -8.358205 6.436975 7.727606 -8.382926 6.404938 7.312522 -8.358503 6.437154 7.300385 -9.08942 5.343499 7.803474 -8.696537 5.965801 7.724328 -8.80337 5.804377 7.472607 -8.689346 5.976232 7.723888 -8.547122 6.182702 7.715202 -8.95972 5.557926 7.496926 -9.08942 5.343499 7.498843 -9.159716 5.224692 7.826585 -9.530316 4.598336 8.000454 -8.122491 6.748574 7.183094 -8.191856 6.660881 7.738527 -7.788527 7.147344 7.00897 -7.833341 7.095994 7.829024 -7.783967 7.152127 7.007005 -7.76572 7.17129 7.858263 -7.582838 7.374944 7.937342 -7.500129 7.462846 11.44677 -7.710988 7.23082 11.54416 -7.829646 7.100256 11.59896 -7.519091 7.442863 16.20812 -8.710596 5.944865 11.70353 -9.08942 5.343499 11.62582 -9.08942 5.343499 16.21459 -8.216831 6.628724 16.21164 -8.216555 6.6285 11.69336 -8.218105 6.627249 16.21165 -8.227194 6.615536 11.69595 -8.745374 5.892681 16.21413 -8.628468 6.065833 11.7105 -8.627745 6.066905 11.71056 -10.50272 0.5999973 12.90038 -10.47131 0.9993336 10.15953 -10.49058 0.7743707 9.986403 -10.49501 0.7146617 9.927426 -10.49955 0.649037 9.840927 -10.50028 0.6379804 9.820577 -10.50194 0.6123206 9.692599 -10.50184 0.6138405 9.747986 -10.50166 0.6166717 9.762411 -10.50145 0.6198754 9.654546 -10.49906 0.6563088 9.576495 -10.46823 1.031252 9.248128 -10.43148 1.360508 9.04216 -10.47927 0.9121766 7.526335 -10.35178 1.891705 8.738698 -10.37517 1.752707 7.523388 -10.34072 1.924427 7.520973 -10.32823 2.000245 8.679645 -10.32561 1.999783 7.519913 -10.49704 0.6858429 9.535413 -10.48608 0.8314123 9.393942 -10.50496 0.5633851 13.11597 -10.30992 1.995521 16.41529 -10.50785 0.5115738 13.20944 -10.51087 0.4573783 13.30721 -10.51806 0.2993217 13.44516 -10.51828 0.294598 13.44929 -10.38271 1.705425 16.41529 -10.41008 1.393276 16.41529 -10.21772 2.537521 7.512352 -10.17375 2.71252 8.292147 -10.01051 3.247934 7.537317 -9.990188 3.331261 7.968142 -9.960706 3.418701 7.543317 -9.88477 3.610822 7.832625 -9.886789 3.611537 7.552422 -9.693893 4.117043 7.587237 -9.684684 4.138799 7.577313 -9.883197 3.609585 16.41529 -9.89187 3.613489 11.60259 -9.932245 3.500747 16.41529 -10.14356 2.825307 11.19734 -10.11882 2.757164 16.41529 -10.27758 2.274262 10.90077 -10.32495 1.999827 10.74731 -10.41987 1.44996 10.43983 -9.673375 4.075127 16.41529 -9.15354 5.228536 16.41529 -9.142692 5.248012 16.38763 -9.666236 4.181998 11.87159 -9.891714 3.613966 11.60283 -9.094307 5.334841 16.26428 -9.477483 4.598336 12.05257 -9.477483 4.598336 11.4595 -10.51339 0.2150705 16.41529 -10.52081 0.2157559 13.47921 -10.5245 0.1012852 13.52264 -10.52638 0.01572275 16.30072 -10.52493 0.08343362 16.41529 7.782122 8.499998 7.172841 7.782122 8.499998 8.044143 7.801538 8.499998 7.186767 8.645041 8.499998 8.050145 8.671029 8.499998 8.056259 6.248941 8.699196 5.430189 6.239091 8.701938 5.410524 7.408281 8.511665 8.163377 6.096979 8.7415 5.126964 6.239069 8.701863 9.618736 6.22682 8.705081 10.32643 6.201786 8.711862 10.08448 6.207151 8.710416 10.00046 6.22878 8.704561 9.661943 6.239054 8.701819 16.22733 6.239084 8.701923 10.37066 6.287997 8.689019 9.413282 6.406648 8.660304 9.135906 6.455166 8.648576 9.022475 6.580708 8.621516 8.826165 6.869143 8.569869 8.507079 6.954832 8.557918 8.4386 7.037294 8.546414 8.372697 6.970128 8.555206 6.35912 6.82128 8.577439 6.203071 6.519703 8.634316 5.839417 7.755732 8.500817 8.052561 7.621599 8.502143 7.015488 7.462984 8.508491 6.854776 7.259642 8.522796 6.646629 7.054647 8.544268 6.442063 7.012238 8.549603 6.400919 7.400413 8.512157 11.83321 7.174489 8.530842 11.71707 7.755754 8.500846 11.94738 6.675829 8.602875 11.29495 6.434237 8.65336 10.93919 6.959369 8.558976 11.55523 6.834378 8.575323 11.46119 6.400665 8.661376 10.86656 6.340531 8.675756 10.73646 7.822676 8.499759 7.163816 9.074396 8.491638 8.201271 8.112646 8.446621 6.848802 8.250086 8.38733 6.69939 8.316285 8.331167 6.633194 9.286506 8.484544 8.320863 9.439772 8.481759 8.445223 9.619338 8.478495 8.59093 9.780159 8.48076 8.773986 11.81268 8.331316 10.12737 10.00114 8.491891 9.132728 10.09501 8.498209 9.36053 10.00581 8.49213 9.140336 11.71443 8.402112 10.22563 8.739366 7.972212 6.210114 12.10867 8.118036 9.831394 8.773214 7.905217 6.176261 12.62241 7.118033 9.31765 9.083031 7.263692 5.866446 12.57235 7.256987 9.367712 9.077063 7.30391 5.872412 12.42154 7.675575 9.518524 12.26511 7.896798 9.67496 6.985573 8.050727 4.222313 7.454579 7.665264 4.263849 7.334997 7.778691 4.300434 7.64708 7.457914 4.301224 0.448329 9.740429 0.2501112 0.3700234 9.447235 0.3362707 0.3700308 10.99932 0.3362707 0.5910524 10.06287 0.09305393 0.5910524 10.06286 0.09305858 0.4644669 9.800853 0.2323551 4.200881 9.397017 -3.879241 4.775909 8.819135 -4.512039 4.756493 8.100006 -4.490594 4.805488 8.789407 -4.544588 4.9936 8.557232 -4.751556 5.364043 8.100006 -5.159138 3.048231 9.601461 -2.610822 2.976154 9.650665 -2.531505 2.924559 10.31126 -2.474842 4.193095 8.708658 -3.870626 3.945318 8.923742 -3.597973 3.850465 9.679574 -3.493659 3.592884 9.229692 -3.210156 3.59877 9.882527 -3.216711 2.787007 10.37529 -2.323473 2.377806 9.961801 -1.873086 2.226216 10.63636 -1.706339 2.134939 10.66528 -1.605948 2.092285 10.06654 -1.558896 1.604905 10.83318 -1.022969 1.708245 10.20739 -1.136302 1.590898 10.83762 -1.007562 1.103205 10.34223 -0.4705173 0.9454318 10.95526 -0.2970519 0.9608247 10.33975 -0.3138414 0.6755941 10.97845 4.2299e-5 0.8263044 10.27854 -0.1658132 0.7626318 10.24957 -0.09574842 3.577282 9.899857 -3.193063 0.8264013 9.932863 -0.7663961 0.7761322 9.944441 -0.7110886 0.8868479 9.979757 -0.6155098 4.096245 8.100006 -4.224296 4.014594 8.100006 -4.274678 3.863548 8.257927 -4.10845 4.558166 8.100006 -4.321975 4.338158 8.100006 -4.222033 3.763957 8.690211 -3.57463 4.189548 8.100006 -4.205245 3.631969 8.613917 -3.633157 4.157027 8.100006 -4.211886 4.573134 8.100006 -4.334702 3.877526 8.8072 -3.565596 2.176521 9.488331 -2.252032 2.050226 9.556757 -2.113044 1.843301 9.717035 -1.664906 2.009792 9.572135 -2.068547 1.727176 9.679648 -1.757558 2.764394 9.261446 -2.678475 1.959441 9.803118 -1.588946 2.888692 9.343478 -2.611492 1.422217 9.795668 -1.42197 2.990482 9.469273 -2.589492 3.236373 8.816692 -3.418331 2.690276 9.210022 -2.817394 2.646965 9.233492 -2.769728 3.361923 8.715855 -3.556488 3.307921 8.765163 -3.49706 3.509124 8.581477 -3.71846 2.048721 9.935083 -1.553179 1.097073 10.29074 -0.4687631 1.064395 10.19895 -0.4853845 1.035211 10.11697 -0.5002274 0.9205468 9.990501 -0.5864124 0.9906121 10.06778 -0.5337513 -1.007008 10.11695 -0.554808 -0.9606875 10.06776 -0.5858975 -1.871767 9.803118 -1.691354 -3.567638 8.690211 -3.770612 -2.745072 9.343492 -2.762088 -2.617369 9.261446 -2.822335 -4.252727 8.100006 -4.514644 -4.291827 8.100006 -4.539214 -3.681528 8.8072 -3.767657 -4.331919 8.100006 -4.575825 -4.509846 8.100006 -4.738305 -4.125255 8.100006 -4.459307 -4.081751 8.100006 -4.440422 -3.946724 8.100006 -4.423318 -3.306928 8.585485 -3.90239 -3.780516 8.100006 -4.483051 -3.432716 8.613917 -3.822004 -3.853055 8.100006 -4.441117 -3.925795 8.100006 -4.427295 -2.069297 9.488421 -2.384916 -2.493473 9.226489 -2.904996 -2.669553 9.117754 -3.120894 -2.911414 8.921849 -3.417442 -3.136861 8.739235 -3.69387 -3.232578 8.661705 -3.811227 -3.743248 8.915159 -3.798407 -3.57082 9.098503 -3.586994 -2.84789 9.469273 -2.745556 -1.076499 10.34223 -0.5287771 -1.070464 10.29073 -0.5266956 -1.523787 10.24294 -1.077188 -1.036952 10.19895 -0.5415437 -1.962828 9.935098 -1.660408 -0.8575938 9.922492 -0.8993206 -1.446428 9.761113 -1.621258 -1.751731 9.717049 -1.761003 -1.6308 9.680393 -1.847305 -1.810665 9.601655 -2.067826 -1.95429 9.538772 -2.243913 -0.9090848 10.01297 -0.6205324 -0.8879103 9.990486 -0.6347444 -0.8526988 9.979743 -0.6620004 -0.7928334 9.961459 -0.7083449 -0.7370434 9.944441 -0.7515327 -2.898554 9.580957 -2.762752 -2.617168 9.782883 -2.417754 -2.001728 10.04183 -1.663176 -0.3874622 10.99949 0.3160223 -0.5571492 9.995448 0.1079779 -0.5995579 10.05504 0.055978 -0.38779 9.447577 0.3156219 -0.4581757 9.742202 0.2293311 -0.4585482 9.743797 0.2288673 -5.080799 8.100006 -5.438344 -4.983278 8.234503 -5.318806 -2.56111 10.43657 -2.349202 -0.7056244 10.20406 -0.07406347 -0.8171446 10.27811 -0.21079 -0.6451927 10.98067 4.04364e-5 -0.8850045 10.32317 -0.2939912 -1.28212 10.89706 -0.7813434 -1.513416 10.83146 -1.064772 -1.940983 10.71021 -1.588703 -2.110722 10.63532 -1.796867 -3.581243 9.748684 -3.599866 -3.135885 10.09163 -3.053737 -2.627696 10.39662 -2.430817 -3.71098 9.648787 -3.758955 -3.636854 9.705859 -3.668063 -4.819858 8.459913 -5.118479 -4.509913 8.826213 -4.738426 -4.256728 9.125429 -4.427978 4.994271 9.757461 -0.9215139 7.368756 8.100006 -0.7679011 6.29474 8.980902 -0.8481746 3.598881 10.34856 -0.9773398 2.135096 10.74299 -1.014591 2.13254 10.77864 2.04129e-5 1.391669 10.90002 3.34514e-5 1.732966 10.86264 2.92605e-5 3.598881 10.1431 -2.272779 4.994271 9.563732 -2.142957 4.994271 9.217712 -3.33028 4.994271 8.724946 -4.464577 6.164884 8.100006 -4.148695 6.247868 8.100006 -4.043999 6.294278 8.100006 -3.954572 6.825631 8.100006 -2.930705 6.29474 8.484127 -3.065238 6.903303 8.100006 -2.781026 6.29474 8.802595 -1.972409 7.186969 8.100006 -1.820731 7.306409 8.100006 -1.416397 0.6955915 9.944441 -0.7844675 -0.4698656 9.944441 -0.9419611 -0.5825482 9.766327 -2.068666 -0.5265496 9.944441 -0.9015632 -0.5932472 9.944441 -0.8540242 0.1624055 9.944396 -1.040488 0.8115299 9.749981 -2.068666 -0.1001678 9.944426 -1.039778 -0.1653157 9.944441 -1.039602 0.338351 9.944441 -0.996837 0.6354876 9.944441 -0.8392265 -1.887242 9.206014 -3.418702 -3.449413 8.100006 -4.69968 -2.983416 8.306431 -4.701328 -1.772466 8.646148 -4.701328 -2.593728 8.100006 -5.259525 -2.916778 8.100006 -5.048167 -0.5255289 8.810299 -4.701328 -1.255224 8.100006 -5.728384 -1.66581 8.100006 -5.584561 0.7320844 8.795532 -4.701328 0.1566835 8.100006 -5.862199 -0.4849903 8.100006 -5.801383 2.870975 8.100006 -5.11345 1.864461 8.100006 -5.527628 1.974834 8.602174 -4.701328 1.559434 8.100006 -5.653145 0.6765999 8.100006 -5.784715 3.177477 8.23413 -4.701328 3.13249 8.100006 -4.921643 3.436109 8.100006 -4.698957 2.102708 9.15921 -3.418702 0.7794924 9.365084 -3.418702 -0.5595557 9.38079 -3.418702 -6.289783 8.441316 -3.191078 -6.289783 8.787187 -2.05529 -4.98339 9.548711 -2.233408 -3.581526 10.12728 -2.368735 -4.98339 9.172859 -3.467626 -6.770323 8.100006 -3.06526 -6.28798 8.100006 -3.922538 -2.111042 10.74362 -1.057415 -2.008098 10.81516 2.32069e-5 -1.654731 10.86323 2.92605e-5 -0.9537734 10.95857 4.0902e-5 -4.011983 10.24227 -0.009520053 -3.577749 10.38946 -0.00524944 -3.581526 10.3506 -1.018732 -3.043349 10.57063 5.97743e-6 -2.109992 10.79109 2.18099e-5 -4.98339 9.759264 -0.9605317 -4.829894 9.882929 -0.001794695 -4.100131 10.20354 -0.008687436 -5.633535 9.447935 -0.004783332 -5.960847 9.232821 -0.004041969 -6.289783 8.980947 -0.8839277 -5.068416 9.753826 -0.002681791 -4.980641 9.80133 -0.002355337 -6.791691 8.650082 -8.26625e-4 -6.43752 8.919554 -0.002963066 -6.286251 9.018975 -0.003305315 -7.442462 8.100006 -0.007792413 -7.272298 8.253115 -0.005524158 -7.360222 8.100006 -0.8007121 -6.943333 8.531737 -7.65158e-4 -6.942483 8.532423 -7.56776e-4 -6.935688 8.53795 -6.91583e-4 -6.879481 8.583294 -2.97168e-4 -7.164406 8.100006 -1.90091 -7.285672 8.100006 -1.519621 -6.82501 8.100006 -2.968071 -4.98339 8.63825 -4.641822 -6.025205 8.100006 -4.355213 -6.079691 8.100006 -4.292728 -7.3889 8.000003 3.703947 -7.425907 7.961141 3.707756 -7.425065 7.961722 3.743522 -7.772142 7.597568 3.743398 -6.753067 8.681747 1.8443 -7.430094 8.100006 1.844269 -7.448519 8.100006 1.384641 -5.90575 9.281116 1.8443 -4.992286 9.799647 1.8443 -2.9334 10.52989 3.091126 -2.972955 10.55691 1.844085 -4.011708 10.23579 1.8443 -2.980808 10.56227 1.596432 -3.016467 10.58662 0.4722452 -4.928539 9.714502 3.743522 -3.96395 10.14221 3.743522 -5.824903 9.207549 3.743522 -6.656261 8.6232 3.743522 -8.120524 7.231744 3.779261 -8.76947 6.400021 3.857076 -8.370327 6.911578 3.809215 -8.129137 7.220702 3.780294 -8.77777 6.389396 3.85807 -9.349163 5.493643 3.917146 -9.171481 5.526008 5.707064 -7.283176 8.100006 3.684335 -7.424305 8.100006 1.988535 -2.933065 10.52039 3.192997 -2.931277 10.46911 3.742111 8.962063 5.44201 4.518885 8.871867 5.476313 4.515594 8.719927 5.734341 4.478527 8.778436 5.511852 4.512186 -8.680473 6.355481 3.834828 -8.328835 6.812306 3.793464 -8.288147 6.780522 3.79167 -7.236491 8.000003 3.679361 -8.29787 6.852539 3.789822 -8.020835 7.212462 3.757233 -7.756571 7.413732 3.730618 -7.797527 7.451134 3.734464 -7.36178 7.916855 3.690036 -7.275136 8.000003 3.682844 -8.769843 6.109672 3.847977 -9.201037 5.408318 3.896706 -8.815604 6.140413 3.848794 -9.256097 5.439373 3.89432 -9.116824 5.420329 3.908605 -9.141686 5.375089 3.911245 -9.171228 5.39151 3.897999 -9.18478 5.399155 3.897411 -9.82103 4.276054 3.925448 -9.801449 4.322501 3.924537 -9.737531 4.294725 3.925392 -9.533445 4.532235 3.940682 -9.635234 4.716741 3.9168 -10.04817 3.737303 3.936021 -10.17264 3.10597 3.942483 -10.23942 3.125998 3.942068 -10.46744 1.874136 3.948822 -10.3639 2.728092 3.946004 -10.26116 3.056483 3.942755 -10.67225 0.676321 3.948972 -10.69544 0.6504973 3.950368 -10.58026 1.69711 3.949747 -10.5588 1.799362 3.949376 -10.54043 1.886906 3.949058 -10.38372 1.859339 3.982996 -10.47091 1.347082 3.982708 -10.54492 0.8755645 3.970148 -10.51218 0.9910485 3.981736 -10.53514 0.8928647 3.97278 -10.60467 0.7698109 3.954057 -10.60613 0.767233 3.953664 -10.63245 0.720652 3.946576 -10.09131 3.081503 3.975817 -10.14694 2.913865 3.978699 -10.33659 2.136218 3.983153 -10.36587 1.964243 3.983056 -9.659546 4.260929 3.950158 -9.80063 3.957407 3.960758 -10.02517 3.280806 3.97239 9.508415 4.33545 4.584077 9.441255 4.306065 4.580122 9.428671 4.536392 4.574483 9.143857 4.913466 4.558113 9.371644 4.277544 4.601275 9.29053 4.487025 4.589762 9.271091 4.543545 4.585568 9.655779 3.543811 4.641598 9.868568 3.134774 4.630507 9.736984 3.283235 4.652055 10.1603 1.921552 4.661856 10.07814 1.907366 4.69053 10.06967 1.96481 4.689854 10.0654 1.993822 4.689512 9.826793 2.995061 4.663621 9.790315 3.11211 4.658924 10.20557 1.043218 4.700696 10.25267 0.9142032 4.688658 10.21673 0.985103 4.697999 10.11746 2.523782 4.654742 10.22783 1.933756 4.666115 10.24243 1.855659 4.667621 10.31272 1.479881 4.674863 10.39012 0.7170757 4.682472 10.32107 0.7956942 4.677444 10.3016 0.8178672 4.676026 10.30134 0.8181652 4.676007 9.949333 3.105017 4.636 9.517087 4.313605 4.585121 9.821846 3.545733 4.621788 9.934856 3.155055 4.634386 -9.07741 5.337464 16.61554 -8.210349 4.902201 31.06681 -8.733342 5.886452 16.61599 -7.917436 5.362542 31.0669 -8.525835 6.175207 16.61694 -7.703493 5.665543 31.06715 -8.205327 6.621184 16.61842 -7.696296 5.675735 31.06716 -7.911684 6.963463 16.62067 -7.12383 6.378489 31.06825 -7.511573 7.42984 16.62373 -7.102231 6.405013 31.0683 -7.238018 7.705571 16.63797 -6.480562 7.031383 31.0697 -7.177176 7.76689 16.64114 -6.788174 8.125516 16.63605 -6.439949 7.072317 31.06979 -6.482134 8.369552 16.63288 -5.780163 7.617147 31.07113 -5.710068 7.675024 31.07128 -6.077478 8.692207 16.62868 -5.388173 7.90477 31.0718 -5.673321 8.968997 16.62817 -5.024435 8.127901 31.07224 -5.625429 9.001809 16.62811 -4.588376 8.395406 31.07278 -4.81488 9.472865 16.63411 -4.804018 9.477886 16.63419 -4.227484 8.570703 31.07304 -3.950412 9.871724 16.64061 -3.745096 8.805009 31.07339 -3.886866 9.894225 16.64032 -3.392058 8.935051 31.07347 -3.107774 10.17006 16.63682 -2.859111 9.131344 31.07359 -2.932171 10.21463 16.63585 -2.528171 9.227397 31.07356 -2.191196 10.40273 16.63175 -2.482864 9.240555 31.07355 -1.950609 10.44025 16.63196 -1.637141 9.423467 31.07323 -1.263837 10.54733 16.63257 -1.566785 9.438681 31.0732 -0.9517021 10.57285 16.63368 -0.7319696 9.535166 31.07255 -0.7377811 10.59035 16.63444 -0.6348215 9.546386 31.07247 0.05565357 10.59568 16.63223 0.1795269 9.55947 31.07149 0.2367846 10.5969 16.63172 0.3095768 9.561556 31.07133 1.060349 10.52359 16.62312 0.7024907 9.540099 31.07074 1.088244 9.491938 31.07005 1.174477 10.51343 16.62192 1.631667 9.424077 31.06908 2.053124 10.3513 16.6167 1.987447 9.34373 31.06831 2.096464 10.3433 16.61644 2.546092 9.217577 31.06709 3.442248 8.919777 31.06473 3.509899 9.901288 16.61515 2.868449 9.110453 31.06624 3.019807 10.0686 16.61572 2.598999 10.21224 16.61622 3.956189 9.699511 16.60845 4.316909 9.157332 22.05691 4.380283 9.507778 16.6021 4.772907 9.296092 16.59444 3.725899 8.992153 28.36503 3.780974 9.007263 27.79088 4.123462 9.101274 24.22046 -9.561556 2.04768e-6 31.06574 -9.561563 0.002997159 31.06574 -10.19717 2.04768e-6 21.41681 -10.51368 1.36158e-4 16.61226 -10.51368 2.04768e-6 16.61226 10.36659 1.877787 4.702492 10.36005 1.910271 4.701807 10.4725 0.61466 5.070474 10.40672 1.678543 4.706692 10.51744 0.6291291 4.720024 10.51775 0.6292334 4.717589 10.205 2.680095 4.685581 10.06517 3.140422 4.669723 10.05091 3.18739 4.668104 9.481116 4.705446 4.599948 9.612477 4.387917 4.615981 9.623653 4.360901 4.617345 9.890078 3.716903 4.649862 8.872947 5.773472 4.752628 8.57733 6.265672 4.537775 8.668116 6.14536 4.484326 8.367835 6.574767 4.433563 8.942044 5.646677 4.817398 9.008242 5.520092 4.886032 -9.141336 5.247252 16.43889 -10.51998 0.0240674 16.50984 -9.105141 5.302744 16.50887 -9.084309 5.331444 16.57003 -8.964295 3.327089 31.06603 -8.786263 3.75125 31.06609 -8.652473 4.069986 31.06614 -9.529124 0.781717 31.06525 -9.462672 1.286181 31.06538 -9.405928 1.716944 31.0655 -9.21225 2.542468 31.06589 -9.247403 2.431246 31.06587 0.4689149 8.749994 0.1735057 0.4936286 8.749994 -0.07945072 0.8660235 8.749994 0.5 -0.1317657 8.749994 -0.482326 -0.3438465 8.749994 -0.3630008 -0.5000032 8.749994 -0.8660253 -0.8660279 8.749994 -0.5000001 -0.474485 8.749994 -0.1576907 -0.9999968 8.749994 0 -2.4582e-5 8.749994 -0.4999969 -2.23027e-6 8.749994 -0.9999998 0.1869701 8.749994 -0.463714 0.4999988 8.749994 -0.8660253 0.3907881 8.749994 -0.3118762 0.8660235 8.749994 -0.5000001 0.9999998 8.749994 0 -0.5000032 8.749994 0 -0.492724 8.749994 0.08497142 -0.8660279 8.749994 0.5 -0.3942571 8.749994 0.3075068 -0.5000032 8.749994 0.8660256 -0.2024047 8.749994 0.457202 -2.23027e-6 8.749994 1 0.03739964 8.749994 0.4985993 0.4999988 8.749994 0.8660256 0.2683379 8.749994 0.4218928 0.3700085 8.749994 0.3362912 -0.8660279 4.999997 -0.5000001 -0.9999968 4.999997 0 -0.8660279 4.999997 0.5 -0.5000032 4.999997 0.8660256 -2.23027e-6 4.999997 1 0.4999988 4.999997 0.8660256 0.8660235 4.999997 0.5 0.9999998 4.999997 0 0.8660235 4.999997 -0.5000001 0.4999988 4.999997 -0.8660253 -2.23027e-6 4.999997 -0.9999998 -0.5000032 4.999997 -0.8660253 -9.68085e-6 9.447219 -0.4999969 0.1607068 9.447219 -0.4734644 0.3826968 9.447235 -0.3069039 0.3548242 9.447219 -0.3522812 0.3284193 9.447219 -0.3687638 0.1839824 9.447219 -0.4589316 0.441847 9.447235 -0.2106242 0.4746221 9.447235 -0.1572613 0.4984863 9.447235 0.03886771 0.4909166 9.447235 -0.02336645 0.4842333 9.447235 -0.07830703 0.431595 9.447235 0.2524349 0.457441 9.447235 0.1699122 0.4581861 9.447235 0.16755 0.5140134 9.604158 -0.02815067 0.5111747 9.595903 -0.01023203 0.5305387 9.622278 -0.01656782 0.6411277 9.959253 -0.004256188 0.514222 9.679826 0.1353867 0.4617475 9.510296 0.1807324 0.4685424 9.51496 0.1692115 0.4879214 9.528297 0.1363502 0.550551 9.756538 -0.2746578 0.5459838 9.733902 -0.2425947 0.581076 9.801748 -0.2759467 0.6398388 9.86393 -0.1368411 0.6471925 9.882884 -0.3487017 0.5341225 9.675103 -0.1592869 0.5280428 9.644958 -0.1165891 0.5170532 9.612995 -0.04728746 0.5873718 9.855675 -0.4251558 0.5846747 9.853381 -0.4205681 0.5670689 9.838419 -0.3906531 0.5564817 9.785938 -0.3163182 0.8041166 9.969848 -0.5213852 0.7046737 9.939167 -0.6166245 0.6837748 9.937617 -0.5890057 0.7067599 9.939315 -0.6193822 0.8868479 9.979757 -0.6155088 0.8979492 10.05794 -0.4208676 1.064388 10.19895 -0.4853845 0.8378603 10.15066 -0.2207379 0.8031629 10.02306 -0.3165687 0.7226222 9.939851 -0.4317044 0.6443091 9.904074 -0.521924 -0.6760455 9.932446 -0.6587464 -0.6174169 9.920928 -0.5695718 -0.5318545 9.788412 -0.3499869 -0.5328975 9.803313 -0.3715769 -0.6985239 9.939851 -0.469681 -0.5332254 9.808006 -0.3783811 -0.5403034 9.817513 -0.3944608 -0.6449692 9.920242 -0.5227957 -0.5661271 9.852144 -0.4531034 -0.611002 9.912314 -0.5549905 -0.487002 9.5211 0.129912 -0.5090631 9.595829 -0.03788065 -0.5288891 9.622263 -0.04487627 -0.5140699 9.612786 -0.07597595 -0.6316103 9.863915 -0.1708121 -0.5163349 9.62046 -0.09320265 -0.5278013 9.730267 -0.2657525 -0.5654938 9.801748 -0.3065835 -0.5242102 9.678724 -0.1910595 -0.5213193 9.637343 -0.1311116 -0.5207158 9.679826 0.1077353 -0.4743583 9.509521 0.1583438 -0.4860557 9.517895 0.1370864 -0.6399773 9.959239 -0.03848183 -0.8248634 10.15066 -0.2651667 -0.746461 9.974392 -0.4139595 -0.8527063 9.979743 -0.6619995 -0.9606875 10.06776 -0.5858979 -0.7851071 10.02306 -0.3590101 0.261826 11.00326 0.4126638 0.1952775 11.00569 0.4596486 -0.2014659 11.00606 0.453419 -0.1297541 11.00691 0.471122 -0.01350265 11.00828 0.4998175 0.03580522 11.00767 0.4903296 -0.2206288 11.00584 0.4486888 -0.3925361 9.447562 0.3066002 -0.4798792 9.447503 0.1404131 -0.4815705 9.447503 0.1286156 -0.4633315 9.447413 -0.1550527 -0.4802815 9.447443 -0.08337998 -0.5000032 9.447473 0 -0.4879258 9.447487 0.08428323 -0.3037996 9.447323 -0.3971226 -0.3368281 9.447339 -0.3571949 -0.4020504 9.447368 -0.2783454 -0.4470296 9.447398 -0.2239794 -0.04731339 9.447235 -0.4950748 -0.1029618 9.447264 -0.4892839 -0.129389 9.447264 -0.4771562 -0.2483524 9.447309 -0.4225667 0.7425003 4.999997 1.286048 -2.23027e-6 4.999997 1.485 -0.7424973 4.999997 1.286048 -1.286047 4.999997 0.7425001 -1.485 4.999997 0 -1.286047 4.999997 -0.7424998 -0.7424973 4.999997 -1.286048 -2.23027e-6 4.999997 -1.485 0.7425003 4.999997 -1.286048 1.28605 4.999997 -0.7424998 1.485003 4.999997 0 1.28605 4.999997 0.7425001 -0.4763774 9.944009 -0.814274 -0.4597626 9.68458 -0.3195848 -0.3644027 9.86256 -0.6228705 -0.2827443 9.68458 -0.483296 -0.08978915 9.944009 -0.9391039 0.3032215 9.943607 -0.8933317 0.3020592 9.943577 -0.8899174 0.2308465 9.860264 -0.6801175 0.1793034 9.680706 -0.5282658 0.1802198 9.683879 -0.5309485 -0.05328875 9.68458 -0.5573864 -0.06868165 9.86256 -0.7183576 0.3701426 9.680706 -0.4173877 0.5030387 9.680706 -0.24118 0.6235369 9.943577 -0.7031319 0.4765369 9.860264 -0.5373671 1.363961 10.90142 1.596644 -1.607517 10.87797 1.596644 -1.583876 10.80333 3.193281 -0.1135267 10.9134 3.193281 1.357501 10.81301 3.193281 -0.122609 10.9956 1.596644 -10.18642 3.682943 3.961045 -9.924854 4.321055 3.94919 -10.66642 1.810687 3.972995 -10.66506 1.817392 3.972975 -10.48492 2.708229 3.970361 -10.36848 3.088447 3.966727 -10.35439 3.134476 3.966287 -10.70462 1.62177 3.97355 -10.81175 0.5658587 3.974317 -9.631077 4.263999 7.56102 -9.543369 4.468875 7.534363 -9.90128 4.378574 3.948121 -9.538891 4.478382 7.531963 -9.803692 4.616665 3.943698 8.240997 6.731631 4.410376 7.909467 7.141607 4.349771 7.714545 7.382663 4.314138 7.680816 7.420289 4.307681 -1.485 8.100006 0 -1.286047 8.100006 -0.7424998 -0.7424973 8.100006 -1.286048 -2.23027e-6 8.100006 -1.485 0.7425003 8.100006 -1.286048 1.28605 8.100006 -0.7424998 1.485003 8.100006 0 1.28605 8.100006 0.7425001 0.7425003 8.100006 1.286048 -2.23027e-6 8.100006 1.485 -0.7424973 8.100006 1.286048 -1.286047 8.100006 0.7425001 -10.75457 0.6036183 3.962476 -10.77506 0.587376 3.966672 10.41326 0.7011464 4.68884 3.488039 7.218392 31.50001 3.14342 7.438512 31.50001 3.489865 7.222073 13.75001 3.258599 7.37791 13.75001 3.018369 7.499637 31.49969 2.891777 7.556813 31.49924 2.682624 7.641347 31.4988 2.470066 7.715242 31.49866 5.052981 5.604552 13.75001 5.052981 5.604552 19.20001 4.578491 6.294372 13.75001 5.052981 5.604552 20.20001 4.366053 6.505268 13.75001 3.896882 6.95725 31.50001 3.969831 6.898613 13.75001 4.366962 6.505789 31.50001 4.5417 6.337972 31.50001 5.052981 5.604552 31.50001 -8.04566 0.9453764 31.49858 -7.908473 1.755717 31.49861 -8.101018 2.04768e-6 31.49862 -8.101011 0.003623008 31.49862 -8.059549 0.8186122 31.49858 -7.218177 3.667908 31.49866 -7.279197 3.55524 31.49865 -7.397728 3.301533 31.49864 -7.691967 2.541663 31.49863 -7.872747 1.885386 31.49862 -6.955 4.153835 31.49869 -6.501796 4.832508 31.49872 -5.303281 6.123857 31.49891 -5.891899 5.559849 31.49881 -6.160634 5.244436 31.49877 -6.424914 4.934253 31.49872 -4.42947 6.782787 31.499 -4.661257 6.625639 31.49898 -4.772181 6.538944 31.49897 -3.719429 7.196681 31.49907 -3.117698 7.470222 31.49911 -2.977299 7.534059 31.49912 -2.205374 7.795038 31.49911 -1.127625 8.022131 31.49907 -1.291896 7.990481 31.49908 -1.934635 7.866608 31.4991 0.4991495 8.085611 31.49896 -0.3156461 8.094849 31.49904 2.378037 7.744105 31.49868 1.586986 7.944035 31.4988 0.7783078 8.063528 31.49892 0.6049998 8.077237 31.49894 5.052981 2.04768e-6 19.20001 5.052981 2.04768e-6 13.75001 6.168982 2.04768e-6 19.20001 6.168982 5.604552 19.20001 5.142202 5.437093 20.20001 5.142202 5.437093 31.50001 10.14268 6.300004 31.21222 10.28708 6.300004 30.96847 9.625881 6.300004 24.87003 9.500614 6.300004 24.4286 9.585692 6.300004 23.97769 9.93511 6.300004 25.20905 13.71097 6.300004 27.43694 10.14268 4.598336 31.21222 10.1309 4.598336 31.2169 10.08436 4.598336 31.22056 10.04122 4.598336 31.20269 10.0109 4.598336 31.16719 8.866025 4.598336 31.02001 10 4.598336 31.12179 9.000002 4.598336 30.52 8.866025 4.598336 30.02 8.5 4.598336 29.65398 8 4.598336 29.52001 8.5 4.598336 31.38603 7.499998 4.598336 31.38603 6.874619 4.598336 32.17334 8 4.598336 31.52001 7.661973 4.598336 32.49124 8.560298 4.598336 32.43992 6.606316 4.598336 32.04432 7.499998 4.598336 29.65398 7.133973 4.598336 30.02 6.999997 4.598336 30.52 7.133973 4.598336 31.02001 6.000002 4.598336 31.90001 5.986599 4.598336 31.95001 5.950002 4.598336 31.98661 5.925407 4.598336 31.99673 6.859613 1.531633 32.16303 6.845285 2.04768e-6 32.15299 7.661973 2.04768e-6 32.49124 6.874619 3.063249 32.17334 8.560298 2.04768e-6 32.43992 -9.533304 4.598336 7.716565 -9.67821 4.598336 8.022172 -9.678366 4.598336 8.02238 -9.777318 4.598336 8.156617 -9.661684 4.598336 11.4333 -9.587335 4.598336 11.57187 -9.543324 4.598336 11.71443 -9.491252 4.598336 11.88311 -9.483213 4.598336 11.94363 -9.806524 4.598336 8.187896 -9.883823 4.598336 8.270682 -10.33569 4.598336 8.920783 -10.33569 4.598336 10.50851 -9.883823 4.598336 11.15861 -9.681145 4.598336 11.40924 -6.960082 4.598336 10.99083 -6.548422 4.598336 10.15207 -7.500003 4.598336 9.714647 -6.56269 4.598336 9.217833 -7.633972 4.598336 9.214648 -6.999778 4.598336 8.392028 -8.000003 4.598336 8.848622 -7.764282 4.598336 7.854884 -8.499998 4.598336 8.714648 -8.689361 4.598336 7.723632 -8.999999 4.598336 8.848622 -9.366023 4.598336 9.214648 -9.5 4.598336 9.714647 -10.5 4.598336 9.714647 -9.366023 4.598336 10.21465 -8.999999 4.598336 10.58067 -8.499998 4.598336 10.71465 -8.628468 4.598336 11.71052 -8.000003 4.598336 10.58067 -7.707829 4.598336 11.55107 -7.633972 4.598336 10.21465 -10.26087 2.965184 8.766314 -10.32965 2.489629 8.923418 -10.23866 3.089653 10.70311 -10.05417 3.956409 10.97344 -9.89006 4.576595 11.15261 -10.49178 0.8506944 9.895817 -10.47789 1.093852 10.01124 -10.49875 0.7035455 9.785267 -10.49823 0.7154664 9.798832 -10.49496 0.7862469 9.856498 -10.49992 0.6765297 9.714647 -10.49987 0.6775131 9.736874 -10.49975 0.6805679 9.746491 -10.44069 1.58261 10.1981 -10.33704 2.482968 10.5054 -10.33553 2.492281 10.50843 -10.39121 2.064066 9.064014 -10.44911 1.485395 9.266323 -10.47567 1.128393 9.403635 -10.48854 0.9122958 9.500843 -10.49642 0.7551482 9.595158 -10.49995 0.675874 9.699949 -10.4996 0.6840249 9.674579 -10.49788 0.7233044 9.622547 -9.910139 4.505845 8.296374 -10.12614 3.64648 8.55031 9.024142 6.499993 5.601956 9.081794 6.300287 5.645691 9.119726 6.162407 5.678308 9.029893 5.831318 5.465479 8.967257 5.73531 5.342674 8.980854 5.663918 5.191205 8.890739 5.777748 5.142852 8.824437 5.903275 5.095008 8.89737 6.08726 5.406878 8.952557 5.957173 5.442375 8.986911 6.536784 5.57605 8.948809 6.57423 5.550087 8.794939 6.724464 5.452095 8.509269 6.899925 5.258872 8.559486 6.952064 5.318933 8.666864 6.588669 5.299944 8.762373 6.756263 5.431358 8.54539 6.386356 4.945161 8.356429 6.656693 4.765015 8.352419 6.685467 4.881417 8.427179 6.787674 5.061318 8.260405 7.23386 5.188999 8.433378 7.070886 5.264147 8.314272 6.937789 5.069227 8.100344 7.37785 5.146421 7.893426 7.545935 5.078948 8.055388 7.333787 5.067511 7.749347 7.414432 4.732695 7.931827 7.19701 4.731843 7.744854 7.410335 4.721894 8.231281 6.803678 4.75607 7.90338 7.555025 5.094025 7.712295 7.449346 4.729342 7.859191 7.584917 5.08024 7.859415 7.584767 5.08031 7.815165 7.614763 5.066378 7.676673 7.485526 4.724705 7.675631 7.484557 4.70982 7.02515 8.119675 4.709209 7.658099 7.720427 5.014361 6.899079 8.232492 4.708737 6.991555 8.170861 4.756733 7.041288 8.137318 4.777406 7.319754 7.949548 4.893143 6.796805 8.300649 4.655659 6.703106 8.346038 4.48883 6.712218 8.356529 4.599584 6.631134 8.409786 4.524817 6.627222 8.412348 4.320077 6.616322 8.419471 4.335073 6.595073 8.43336 4.463167 6.588025 8.437964 4.430262 6.589478 8.43701 4.398401 4.786161 9.294899 16.48925 -7.179613 7.77054 16.57423 -7.182586 7.777722 16.41638 5.370711 8.508312 31.00915 4.07326 8.713635 31.04638 4.54094 8.61414 31.0329 4.875382 8.624318 28.55287 4.716804 8.576724 31.02783 5.385054 8.652257 24.40426 5.630647 8.666652 22.23873 6.203105 8.702445 16.77159 6.2208 8.702132 16.61565 13.76415 7.121624 26.67158 13.76532 7.118033 12.07686 13.69468 7.257016 26.67158 13.69451 7.256987 12.07686 13.47679 7.681655 26.67158 13.48124 7.675575 12.07686 13.25989 7.89653 26.67158 13.26 7.896798 12.07686 13.0296 8.124651 26.67158 13.03877 8.118036 12.07686 12.61972 8.330109 26.67158 12.62019 8.331316 12.07686 12.46688 8.406716 26.67158 12.48124 8.402112 12.07686 12.04002 8.402112 10.62236 12.97775 8.118036 11.45734 12.50359 8.118036 10.31261 13.41172 7.675575 11.37102 12.87149 7.675575 10.06679 13.69034 7.118033 11.3156 13.46829 7.118033 10.58358 13.10769 7.118033 9.908962 13.20583 7.675575 10.6923 12.79705 8.118036 10.86162 12.28195 8.402112 11.07498 12.43093 8.402112 11.56611 8.524416 8.192422 6.402513 8.657499 8.05174 6.258255 8.716217 7.96421 6.194444 8.86265 7.745953 6.035323 8.956565 7.548244 5.932931 9.03695 7.297905 5.844896 9.081161 7.160233 5.796482 9.125514 6.92706 5.747521 9.024142 6.500201 5.601956 8.844017 7.548304 5.838066 8.759542 7.745998 5.948344 8.574991 8.051755 6.188549 8.455193 8.192438 6.343992 8.263735 8.343371 6.591637 8.207968 8.38733 6.663774 8.275172 8.334356 6.576851 8.659011 7.912563 6.079191 8.925966 7.264854 5.730819 8.956177 7.160323 5.691274 8.996217 6.927164 5.638739 7.820724 8.499759 7.162162 8.083588 8.446621 6.82421 8.892669 7.290782 5.708602 8.633024 7.91751 6.071369 8.218875 8.354785 6.565362 8.592202 7.94022 6.046099 8.847891 7.316502 5.690459 8.037111 8.364933 6.456292 8.393509 7.993014 5.96758 8.645869 7.433282 5.610952 8.429265 7.558139 5.530552 8.347666 7.722409 5.648205 8.183977 8.051934 5.88422 7.849937 8.38046 6.341995 7.961063 8.271175 6.18971 7.703719 8.05344 5.456263 8.051707 7.884817 5.536705 7.700925 8.336606 6.047626 7.410561 8.395137 5.921886 7.658286 8.06925 5.438738 7.321557 8.409309 5.865977 7.366066 8.402067 5.894264 7.467103 8.247333 5.643321 7.612651 8.085357 5.420664 6.473859 8.571344 4.884339 6.39504 8.600401 4.774774 6.320109 8.628713 4.627554 6.657941 8.506345 5.079076 6.976542 8.403557 5.333533 7.315745 8.308071 5.54752 13.47679 7.623823 27.03673 13.76415 7.002907 27.03696 13.76415 6.865384 27.17448 13.76415 7.091196 26.86367 13.47679 6.86516 27.79541 13.47679 7.455992 27.36614 13.47679 7.194566 27.62756 13.0296 7.814379 27.62653 13.0296 8.045139 27.17363 12.46688 8.313405 27.26079 13.47679 6.499993 27.85324 13.76415 6.692083 27.26277 13.69468 6.499993 27.42859 13.76415 6.499993 27.2932 -8.63831 2.04768e-6 31.99722 -8.63831 0.003816723 31.99722 -8.894721 2.04768e-6 31.94364 -9.08153 0.003429293 31.85515 -9.076255 2.04768e-6 31.84303 -9.082759 0.003429293 31.85476 -9.188416 2.04768e-6 31.78088 -9.411673 2.04768e-6 31.53008 -9.418177 0.00313127 31.51925 -9.416649 2.04768e-6 31.51798 -9.418631 0.00313127 31.51879 -9.539331 2.04768e-6 31.21952 -8.083569 4.826696 31.52395 -8.086981 4.828723 31.51999 -8.522706 4.008996 31.51959 -9.082752 0.003429293 31.85476 -9.050915 0.7424375 31.85536 -8.201907 2.710151 31.99726 -8.088837 3.002064 31.99726 -8.514272 3.160091 31.8555 -8.218037 3.865795 31.85552 -7.81511 3.676417 31.99728 -7.761608 3.790843 31.99729 -7.415439 4.428791 31.99737 -7.788571 4.650997 31.85906 -7.797772 4.656481 31.85565 -7.888073 3.520357 31.99727 -8.344265 2.194019 31.99723 -8.783164 2.309384 31.85547 -8.433046 1.872154 31.99722 -8.933807 1.630994 31.8554 -8.487756 1.549917 31.99719 -8.579733 1.008125 31.99716 -8.594552 0.8729419 31.99715 -8.602964 0.7058551 31.99717 -9.418624 0.00313127 31.51879 -9.386467 0.7700046 31.51907 -9.265038 1.691284 31.51922 -9.108784 2.394857 31.51944 -8.829894 3.277215 31.51953 -3.686877 8.66841 31.5287 2.414746 8.74533 31.86162 2.535594 8.25693 31.99734 2.633785 8.226352 31.99731 3.264768 8.463475 31.86119 2.870058 8.142146 31.99759 3.211168 8.325654 31.90602 3.100624 8.041429 31.99847 1.547074 8.940773 31.86198 1.691816 8.468437 31.99759 2.295857 8.317011 31.99741 0.532014 8.616956 31.99791 0.6322168 8.609237 31.99789 0.6655284 9.050446 31.86227 0.8295902 8.594023 31.99783 1.470288 8.500698 31.99765 0.2777852 8.61946 31.99796 0.292895 9.070667 31.86238 -0.336314 8.625525 31.99808 -0.6024934 9.056004 31.86259 -0.5724974 8.60423 31.99809 -1.20146 8.547562 31.99814 -1.486497 8.953663 31.86272 -1.412304 8.506807 31.99815 -2.061213 8.381369 31.9982 -2.355526 8.765625 31.86278 -2.239811 8.334058 31.99821 -3.55232 8.352714 31.86275 -3.172013 8.026751 31.99823 -2.712364 8.662033 31.86279 -2.576495 8.2282 31.99822 -2.349617 8.304956 31.99821 -4.352147 7.964375 31.86264 -3.9631 7.668065 31.99813 -3.374125 7.935123 31.99821 -4.967439 7.060798 31.99795 -4.86088 7.13286 31.99796 -5.111056 7.499086 31.86246 -4.720243 7.227974 31.99799 -4.134829 7.568257 31.9981 -5.14734 6.920533 31.99791 -5.416492 7.281246 31.86237 -5.652333 6.526844 31.99781 -6.108897 6.70995 31.86211 -5.806702 6.379427 31.99776 -6.280752 5.9267 31.99761 -6.737547 6.077038 31.86183 -6.406481 5.779551 31.99757 -6.84988 5.260574 31.99744 -7.301549 5.385118 31.86163 -6.931948 5.152183 31.99742 -6.949464 5.125987 31.99742 -7.511499 5.087869 31.86158 -7.141995 4.837917 31.9974 -7.796 5.280377 31.52496 -7.578159 5.588757 31.52511 -6.992908 6.306695 31.52577 -6.340484 6.963449 31.52663 -5.621674 7.55647 31.52748 -5.304674 7.782521 31.52779 -4.517096 8.265349 31.52835 -2.814779 8.98956 31.52882 -2.444396 9.097086 31.5288 -1.542541 9.292247 31.5286 -0.6250761 9.398478 31.52817 0.3045477 9.413751 31.52752 0.6913744 9.392786 31.52717 1.606276 9.279015 31.52622 3.320997 8.608045 31.70884 2.50679 9.07627 31.52507 3.389326 8.783716 31.5237 3.40118 8.814203 31.42087 3.909839 8.108335 31.92826 5.366636 8.429694 31.38902 3.237193 7.968934 31.99937 5.355363 8.212628 31.71034 5.338607 7.889764 31.92476 4.050088 8.627804 31.4146 4.703631 8.493843 31.40189 4.618926 7.961096 31.92653 4.669321 8.278059 31.71688 3.992876 8.415895 31.72332 5.827015 6.16523e-5 9.666192 4.946729 6.16523e-5 10.1273 4.945902 0.6304106 10.1246 -4.223476 0.6304106 10.44661 4.538124 4.542129 9.289842 4.738053 3.284203 9.699116 3.351083 4.10706 9.96653 3.351291 3.282966 10.25714 3.746053 2.69823 10.29366 3.351314 3.180223 10.29338 4.443218 1.269968 10.29403 4.876268 1.964974 9.982041 4.57481 0.6840547 10.29401 4.580786 0.6303808 10.29401 4.234036 1.842039 10.29396 4.174208 1.96481 10.29393 4.07285 2.17283 10.29388 4.628529 6.16523e-5 10.29398 4.61897 0.2874156 10.29399 9.002468 0.405865 6.794837 8.639431 0.6304106 7.233926 9.018568 0.4413595 6.771104 9.122221 0.6132593 6.616415 8.640161 6.16523e-5 7.233968 8.932723 0.1691004 6.896747 8.946544 0.2373626 6.876657 9.428321 1.964974 5.875878 9.542196 0.9427538 5.946909 9.497403 0.9265264 6.023948 9.353279 0.8395633 6.25816 8.517786 1.964974 7.132071 9.178287 0.6821772 6.531263 9.136177 0.6304106 6.595219 10.11601 1.050161 4.888928 9.808897 1.030328 5.48302 9.748875 1.017677 5.591447 9.161084 3.284203 5.709336 8.774518 4.542129 5.468419 -9.535755 3.284203 5.058798 -9.133371 4.542129 4.845334 -9.840819 0.9904972 5.433189 -9.925785 1.00963 5.265782 -9.813915 1.964974 5.206366 -10.09752 1.048284 4.927413 -10.36599 1.033308 4.337958 -9.172442 0.1692047 6.574564 -9.121323 0.6304106 6.615959 -9.178 0.2006313 6.565856 -9.229074 0.3797879 6.48537 -9.311827 0.5494078 6.352919 -9.356122 0.6169399 6.280926 -9.368027 0.6304106 6.261089 -8.992891 1.964974 6.522805 -9.503687 0.7839521 6.035093 -9.614373 0.872316 5.844119 -2.726937 0.6304106 10.93313 -2.393971 0.6300082 11.00142 -2.688537 1.964974 10.77919 -2.393941 1.963141 10.83838 -2.393971 1.576813 10.91254 -2.393971 0.9482374 10.98705 -2.612332 3.284203 10.47367 -2.393829 3.12482 10.57352 -2.393904 2.545508 10.72659 -1.08015 4.542129 10.28246 -1.436176 4.313218 10.33472 -2.502101 4.542129 10.03171 -1.664522 4.285531 10.31166 -1.737545 4.264461 10.30813 -1.944961 4.166545 10.31011 -2.009297 4.122348 10.31511 -2.175624 3.963279 10.3422 -2.219635 3.905328 10.35439 -2.329404 3.699394 10.40418 -2.352739 3.6314 10.4224 -2.392786 3.397392 10.49057 -2.393792 3.353508 10.50422 -2.393807 3.284069 10.52527 0.3628708 4.542129 10.33267 -0.219541 4.313218 10.40722 -1.090074 4.313218 10.37693 1.815339 4.313218 10.2749 0.9957754 4.313218 10.36126 0.3662012 4.313218 10.4276 2.198664 4.313218 10.17916 1.798814 4.542129 10.18136 3.229064 4.313218 9.921801 3.199672 4.542129 9.831474 3.35103 4.313218 9.881276 -8.110682 0.6304106 7.822165 -6.941857 0.6304106 8.875814 -5.63764 0.6304106 9.756353 6.308166 0.6304106 9.336835 6.306802 6.16523e-5 9.335174 8.003599 6.16523e-5 7.958128 7.547399 0.6304106 8.366971 7.545908 6.16523e-5 8.365097 6.96784 6.16523e-5 8.879107 -7.996479 1.964974 7.712028 -8.738006 3.284203 6.337925 -7.769833 3.284203 7.493443 -8.369284 4.542129 6.070485 -7.44197 4.542129 7.177243 -6.844113 1.964974 8.750841 -5.558262 1.964974 9.618983 -6.65013 3.284203 8.502811 -5.40072 3.284203 9.346347 -6.369511 4.542129 8.14402 -5.172829 4.542129 8.951961 -4.164005 1.964974 10.29952 -4.04598 3.284203 10.0076 -3.875258 4.542129 9.585309 6.219347 1.964974 9.205369 6.043066 3.284203 8.944458 5.788071 4.542129 8.56703 7.441131 1.964974 8.249163 7.23022 3.284203 8.015353 8.276364 3.284203 6.929923 6.925126 4.542129 7.677131 7.927125 4.542129 6.637502 -7.197822 8.100006 3.675876 -7.236491 8.100006 3.679361 -7.275136 8.100006 3.682844 8.003599 3.185e-5 7.958128 4.628522 3.185e-5 10.29399 5.827015 3.185e-5 9.666192 4.628514 2.04768e-6 10.29399 5.827015 2.04768e-6 9.666192 6.96784 2.04768e-6 8.879107 6.96784 3.185e-5 8.879107 8.003599 2.04768e-6 7.958128 8.645041 4.598336 8.050145 7.754957 4.598336 8.050145 9.446977 4.598336 8.436337 10.00194 4.598336 9.132233 10.2 4.598336 10 10.00194 4.598336 10.86777 9.446977 4.598336 11.56366 8.645041 4.598336 11.94986 7.754957 4.598336 11.94986 6.953021 4.598336 11.56366 6.398065 4.598336 10.86777 6.199998 4.598336 10 6.398065 4.598336 9.132233 6.953021 4.598336 8.436337 8.200003 4.598336 9 7.700001 4.598336 9.133975 7.333977 4.598336 9.5 7.2 4.598336 10 7.333977 4.598336 10.5 7.700001 4.598336 10.86603 8.200003 4.598336 11 8.700004 4.598336 10.86603 9.066029 4.598336 10.5 9.199997 4.598336 10 9.066029 4.598336 9.5 8.700004 4.598336 9.133975 10 7.218139 30.92247 10 6.499993 31.12179 6.000002 7.499995 31.90001 6.000002 8.136394 31.6364 6.000002 7.84442 31.8315 6.000002 8.331495 31.34442 6.000002 8.399995 31.00001 4.747321 3.927739 13.03416 4.75849 3.920438 13.0446 4.751352 5.524175 13.05222 4.846116 5.54991 13.14096 4.789566 3.900157 13.07366 4.969475 5.582588 13.37126 4.995791 2.04768e-6 13.41667 4.995791 3.500002 13.41667 4.994844 3.503459 13.41401 4.999471 5.590545 13.42725 4.973946 3.561797 13.36864 4.969483 5.582602 13.37127 4.920398 3.711226 13.25242 4.90213 3.737601 13.22746 4.897935 3.743665 13.22172 4.061175 5.328687 12.75004 4.306709 5.400496 12.78273 4.678441 3.972711 12.96975 4.7513 5.52416 13.05217 4.539614 3.999995 12.8764 4.608688 5.485447 12.91862 4.430008 3.999995 12.84793 4.430195 5.43523 12.8383 4.430024 5.435185 12.83822 4.520011 6.245645 13.36732 4.353469 6.106885 13.0429 3.921536 6.839784 13.36732 3.222202 7.311063 13.36732 3.118542 7.120686 13.0429 3.783991 6.672235 13.0429 2.963399 6.835761 12.82613 3.578139 6.421478 12.82613 4.104225 5.899208 12.82613 -6.551305 5.03129 31.86472 -6.45789 4.959555 31.69831 -5.922059 5.588265 31.69812 2.572094 8.03368 31.97043 2.47622 8.063587 31.9704 1.652283 8.270594 31.97009 0.8102484 8.393722 31.96976 0.7823013 8.10461 31.69786 1.59513 7.984685 31.69815 2.390285 7.783892 31.69842 2.482799 7.754894 31.69845 0.5196236 8.416282 31.96965 -0.3284983 8.425 31.9694 -1.173551 8.348989 31.96931 -1.133332 8.062782 31.69746 -0.3172405 8.135902 31.69754 0.5017125 8.126753 31.69775 -2.013358 8.18679 31.96921 -2.295087 8.112195 31.96918 -3.098401 7.840486 31.96915 -1.944417 7.906409 31.69738 -2.21652 7.834466 31.69735 -2.992357 7.572146 31.69732 -3.871026 7.489907 31.96932 -4.610414 7.0598 31.96953 -4.851806 6.896423 31.96959 -3.738294 7.23313 31.69747 -4.451985 6.817238 31.69765 -4.684965 6.659316 31.69771 -5.52057 6.374689 31.96979 -6.134058 5.788283 31.97006 -6.007495 5.668866 31.86439 -5.330327 6.155061 31.69788 -5.406978 6.243544 31.86399 -4.752176 6.754832 31.8637 -4.515799 6.91493 31.8636 -3.791744 7.336544 31.8633 -3.035056 7.680194 31.86305 -2.248155 7.9463 31.8631 -1.972178 8.019315 31.86314 -1.149523 8.178043 31.86328 -0.3217704 8.25234 31.86341 0.5089321 8.243384 31.86378 0.793574 8.221092 31.86394 1.618174 8.099901 31.86444 2.424938 7.896634 31.8649 2.518808 7.867293 31.86496 -6.689633 5.137505 31.97028 -6.535167 4.857289 31.69833 -6.62973 4.927563 31.86475 -6.769756 5.031632 31.9703 -6.990733 4.175158 31.69839 -7.091964 4.235612 31.86485 -7.241855 4.325109 31.97036 -8.204619 0.9640476 31.86524 -8.087139 0.9502491 31.69861 -7.949198 1.764747 31.69855 -7.579776 3.702032 31.97046 -7.703255 3.437879 31.97048 -8.009712 2.646642 31.9705 -7.316637 3.573524 31.69848 -7.435786 3.318506 31.69849 -7.731552 2.554732 31.69851 -8.23536 1.82827 31.97055 -8.064578 1.790362 31.86513 -7.843705 2.591791 31.86505 -7.543626 3.366636 31.86503 -7.422725 3.625335 31.865 -8.3785 0.9844771 31.97062 -8.101093 0.8228293 31.69861 -8.21879 0.83478 31.86524 -8.392977 0.8524677 31.97062 -8.142727 0.003623008 31.69854 -8.260901 0.003667712 31.86512 -8.435826 0.003727316 31.97054 2.799158 7.953273 31.97008 2.738086 7.790299 31.86442 2.696966 7.680239 31.69814 3.02129 7.858189 31.96873 2.953251 7.700609 31.86246 2.907602 7.594378 31.69696 -8.129204 2.04768e-6 31.66412 -8.146974 2.04768e-6 31.69619 -8.210579 2.04768e-6 31.81096 -8.26555 2.04768e-6 31.8599 -8.33598 2.04768e-6 31.92259 -8.438254 2.04768e-6 31.96463 -8.491258 2.04768e-6 31.98642 3.034723 7.535922 31.69514 3.153597 7.790851 31.96657 3.082325 7.638411 31.85948 3.16066 7.472443 31.69135 3.176977 7.504554 31.74527 3.283215 7.713692 31.96195 3.258792 7.665636 31.92592 3.209745 7.569077 31.85356 5.325188 5.756946 31.94962 3.938315 7.009895 31.75001 4.592625 6.381484 31.75001 4.73175 6.500395 31.93302 4.051504 7.153707 31.93302 5.096947 5.629154 31.68805 5.111431 5.637275 31.75001 5.191279 5.681979 31.84151 5.27112 5.726682 31.93302 5.176155 5.454289 31.69135 5.272855 5.503254 31.85356 5.417575 5.576523 31.96195 5.921332 4.650714 31.99771 5.90126 4.884185 32 5.782594 4.61434 31.96195 5.625693 4.573183 31.85356 5.520848 4.545691 31.69135 6.112372 3.095077 31.96195 6.432158 1.543703 31.99485 6.430601 1.563447 31.99492 6.311206 1.55321 31.96195 6.377643 2.04768e-6 31.96195 6.468636 2.04768e-6 31.98984 5.845715 3.049033 31.69135 5.952527 3.067481 31.85356 6.149588 1.539367 31.85356 6.041592 1.530113 31.69135 6.215428 2.04768e-6 31.85356 6.107045 2.04768e-6 31.69135 6.606316 3.063249 32.04432 6.655683 1.537832 32.05405 6.665421 2.04768e-6 32.05188 9.760662 2.04768e-6 6.999347 9.81251 2.04768e-6 7.188345 9.755618 2.04768e-6 6.993125 9.757801 0.05129182 6.979061 9.625873 2.04768e-6 6.832952 9.589045 2.04768e-6 6.812572 9.590088 0.03594362 6.800252 9.120932 0.1029393 6.753448 10.19949 0.5850365 5.651917 10.41137 0.626432 5.042177 10.29878 0.691699 4.985977 10.20751 0.7896742 4.939383 10.14491 0.9124448 4.906143 9.478978 2.04768e-6 6.75166 9.357339 2.04768e-6 6.731019 9.359224 0.05467438 6.718469 9.313455 2.04768e-6 6.723573 9.853041 0.871407 5.491103 9.796864 0.8548817 5.596672 10.16001 0.5707761 5.762026 10.0031 0.4857501 6.195362 9.566008 0.7497391 6.011693 9.438416 0.6581416 6.230115 9.291573 0.5042573 6.474056 9.921133 0.415655 6.423998 9.8337 0.3033748 6.680456 9.809828 0.2593269 6.756658 9.774125 0.1631101 6.886919 9.7699 0.1457652 6.905557 9.759253 0.07502937 6.965597 10.05961 0.635924 5.580422 10.01501 0.6177595 5.68718 9.838535 0.5121996 6.104072 9.747668 0.4272779 6.320432 9.653887 0.2948513 6.55653 9.62971 0.2444556 6.624084 9.597255 0.1395216 6.733552 9.594179 0.1217147 6.748157 9.589469 0.05521082 6.791653 9.939766 0.7349869 5.524795 9.889124 0.7162413 5.629858 9.68547 0.6046316 6.039752 9.577474 0.5127808 6.252072 9.460887 0.366362 6.483051 9.428805 0.3094246 6.54887 9.380719 0.1873245 6.654919 9.375064 0.165852 6.66896 9.36102 0.08139216 6.710403 9.247495 0.4411956 6.54613 9.172446 0.2959689 6.668434 9.161836 0.2682378 6.685782 9.128256 0.1473298 6.741178 -6.820189 2.04768e-6 12.49963 -6.820189 3.998341 12.49963 -6.805743 2.04768e-6 10.78756 -6.805743 3.998341 10.78756 -7.102283 3.998341 11.33142 -6.851743 2.04768e-6 12.46283 -6.872694 0.1900961 12.43673 -6.907398 0.2967438 12.38881 -6.927507 0.3585389 12.36104 -7.002848 0.4963597 12.23299 -7.018322 0.5141964 12.19632 -7.076407 0.5811771 12.05863 -7.107513 3.998341 11.95085 -6.287883 2.04768e-6 10.44765 -6.287883 3.998341 10.44765 -5.670945 2.04768e-6 10.39191 -5.670945 3.998341 10.39191 -5.100551 2.04768e-6 10.63351 -5.100551 3.998341 10.63351 -4.711347 2.04768e-6 11.11542 -4.711347 3.998341 11.11542 -4.595185 2.04768e-6 11.72388 -4.595185 3.998341 11.72388 -4.779498 2.04768e-6 12.31527 -4.779498 3.998341 12.31527 -9.507882 2.04768e-6 6.391218 -9.351629 1.69488e-5 6.443117 -9.342002 2.04768e-6 6.440275 -9.312833 1.69488e-5 6.456002 -9.315478 2.04768e-6 6.459619 -9.206357 2.04768e-6 6.539196 -10.03274 4.67512e-5 6.712342 -9.943808 1.69488e-5 6.562102 -9.994524 3.185e-5 6.647789 -10.00118 0.04986131 6.630529 -9.811382 2.04768e-6 6.453135 -9.827735 2.04768e-6 6.466588 -9.827564 0.03391706 6.456456 -10.61869 0.6279817 4.480949 -10.38882 0.9068867 4.358631 -10.44121 0.7922223 4.390918 -10.5196 0.6971082 4.432633 -10.44733 0.610592 5.078261 -9.896162 0.82271 5.429549 -10.13444 0.8990785 4.939032 -10.29169 0.5441775 5.584921 -10.16533 0.4421791 5.988381 -10.1096 0.3746321 6.170937 -9.69288 0.6930997 5.818049 -9.597564 0.6030818 5.992783 -9.477938 0.4445931 6.207072 -10.04577 0.26113 6.396518 -10.03016 0.2203455 6.459138 -10.00809 0.1317879 6.566942 -10.21037 0.7686188 4.970291 -9.999047 0.6815513 5.456429 -9.82553 0.5480667 5.836388 -9.748119 0.4598221 6.004123 -9.658279 0.3124496 6.20363 -9.444671 0.3848543 6.266031 -9.635987 0.260072 6.256149 -9.388062 0.2471676 6.366514 -9.604009 0.1488497 6.340244 -9.358751 0.1218935 6.419436 -9.593981 0.06441974 6.378509 -9.355942 0.1018515 6.424607 -9.593542 0.05278193 6.381771 -9.592819 2.04768e-6 6.395453 -9.670461 2.04768e-6 6.399324 -10.31808 0.6693175 5.018219 -10.13661 0.5846789 5.510469 -9.991641 0.4598519 5.896276 -9.929257 0.3790131 6.067147 -9.861077 0.2469143 6.271289 -9.845766 0.201123 6.32534 -9.827683 0.1072159 6.412548 -9.826946 0.0420978 6.452949 -10.00144 0.06030702 6.624797 10.1309 6.499993 31.2169 10.08436 6.499993 31.22056 10.04122 6.499993 31.20269 10.0109 6.499993 31.16719 10.115 7.772894 30.5849 10.1254 7.266493 31.00623 10.08013 7.267134 31.00734 10.07239 7.770808 30.58309 10.03892 7.257717 30.99104 10.03481 7.755505 30.56978 10.01026 7.240193 30.96068 10.00911 7.729771 30.54739 9.773372 8.408758 29.50219 9.749835 8.387269 29.50922 9.902215 8.256616 29.82893 10.09395 7.984864 30.31918 10.05466 7.979335 30.32005 10.01999 7.961901 30.31171 9.995414 7.935302 30.29546 9.973957 8.212405 29.95265 9.943826 8.192706 29.95116 9.930654 8.276897 29.8281 9.921795 8.165407 29.94297 9.881323 8.229139 29.82339 9.800806 8.421691 29.49015 9.963175 8.287536 29.821 10.00829 8.221912 29.94727 9.658112 8.426401 29.36651 9.679175 8.44823 29.35661 9.704127 8.461865 29.34213 9.470335 8.49511 29.06423 9.457118 8.485632 29.07732 9.450524 8.480909 29.08384 9.434803 8.458781 29.09941 9.43145 8.449497 29.10273 9.732707 8.359524 29.51049 9.643098 8.398565 29.37081 9.424715 8.4309 29.1094 6.073659 8.450004 29.93435 5.986599 8.450004 30.52 7.805412 8.486601 28.47926 7.220214 8.486601 28.62411 7.234139 8.450004 28.65796 5.950002 8.486601 30.52 6.038641 8.486601 29.9237 6.296908 8.486601 29.37897 6.702451 8.486601 28.93291 8.974223 8.486601 28.71629 8.400163 8.450004 28.54677 8.956833 8.450004 28.7485 7.808884 8.450004 28.5157 8.407435 8.486601 28.51091 6.327314 8.450004 29.39934 6.725622 8.450004 28.96125 5.986599 8.450004 31.00001 5.950002 8.486601 31.00001 5.950002 8.411499 31.37757 5.986599 8.377689 31.36356 5.986599 8.171754 31.67176 5.986599 7.863553 31.87769 5.950002 8.197638 31.69764 5.950002 7.87756 31.91151 5.986599 7.499995 31.95001 5.950002 7.499995 31.98661 10.28708 2.04768e-6 30.96847 2.999981 3.500002 10.75 2.999981 3.500002 10.69338 2.999981 3.319459 10.75 -2.000014 2.04768e-6 11.5185 -2.000014 9.14547e-5 11.5185 -2.000014 0.9918383 11.47372 -2.000014 1.648071 11.39594 -2.000014 2.658116 11.20204 -2.000014 3.261747 11.04254 -2.000014 3.500002 10.97033 13.26232 3.999995 11.16041 13.6019 3.999995 10.90768 2.301497 3.999995 10.65204 2.503415 3.999995 10.6064 2.500845 3.999995 10.64985 -1.500013 3.999995 10.7941 -0.2301954 3.999995 10.8954 1.042774 3.999995 10.84783 2.499988 3.999995 10.69338 2.499988 3.999995 10.75 2.576103 3.999995 11.13269 13.74806 3.999995 12.82703 12.84861 3.999995 11.25001 12.3632 3.999995 11.25001 11.83831 3.999995 12.53572 12.07973 3.999995 12.69437 12.3632 3.999995 12.75001 13.3632 3.999995 12.75001 4.771893 3.999995 12.53129 4.553107 3.999995 12.84449 3.499982 3.999995 11.75 11.13846 3.999995 11.75 11.51642 3.999995 11.67582 11.51642 3.999995 12.32419 11.83831 3.999995 11.46429 12.07973 3.999995 11.30564 11.13846 3.999995 12.25001 5.467196 3.999995 12.25001 5.092179 3.999995 12.32299 2.792878 3.999995 11.45711 3.117298 3.999995 11.67388 3.038046 3.500002 10.94135 3.038493 3.319459 10.94244 3.07407 3.500002 10.99526 3.074048 3.319459 10.99524 3.14643 3.500002 11.10356 3.148099 3.319459 11.10522 3.254724 3.500002 11.17592 3.254851 3.319459 11.17564 3.308644 3.500002 11.21194 3.311915 3.319459 11.21329 3.349108 4.30906 9.883697 3.263494 4.12141 10.00252 3.171099 3.915461 10.15433 3.242297 4.074948 10.03193 3.315379 3.186124 10.31276 3.168469 3.210293 10.39199 3.041176 3.263505 10.56649 3.020731 3.566312 10.52163 3.044044 3.259601 10.5537 3.001703 3.512787 10.64575 3.000413 3.506379 10.66956 3.038344 3.609928 10.45471 3.045348 3.626393 10.43576 3.152204 3.216731 10.41312 3.095453 3.744172 10.30024 3.135843 3.836485 10.21494 3.038493 3.163101 10.86217 3.038493 3.231587 10.9212 3.038493 3.185468 10.61189 3.038493 3.137188 10.68833 3.038493 3.129142 10.77838 3.182424 3.022032 10.96973 3.148099 3.030824 10.95705 3.148024 2.989816 10.86873 3.340048 3.169658 11.19943 3.148099 3.157245 11.06602 3.289846 3.122645 11.14375 3.312749 3.144088 11.16915 3.212472 3.050165 11.05793 3.143055 2.985152 10.85414 3.143703 2.985763 10.80189 3.220295 3.057497 10.42884 3.207935 3.045919 10.46211 3.148099 3.072115 10.49505 3.148069 2.989845 10.62331 3.145849 2.987774 10.62928 3.145759 2.987685 10.63693 3.312876 3.144222 10.33312 4.409594 2.04768e-6 11.01504 4.4445 2.04768e-6 11.05426 4.43082 0.2749881 11.05832 4.481924 2.04768e-6 10.39455 4.44041 0.2756139 10.4298 4.668069 2.04768e-6 11.22182 4.605157 0.2864918 11.19954 4.617763 2.04768e-6 11.19394 4.521226 2.04768e-6 11.14044 4.345765 2.04768e-6 10.85976 4.335773 0.2687147 10.85487 4.336936 2.04768e-6 10.69211 4.339201 0.2689382 10.63025 4.354497 2.04768e-6 10.6321 4.454253 2.04768e-6 10.43314 4.38409 2.04768e-6 10.53099 4.398031 0.6563833 10.42984 4.297835 0.6407073 10.63028 4.29446 0.6401857 10.8549 4.388576 0.6549081 11.05834 4.561191 0.6819239 11.19954 4.271557 1.219513 10.42985 4.174275 1.190918 10.6303 4.171004 1.189949 10.85491 4.2624 1.216816 11.05835 4.430024 1.266094 11.19954 4.221303 1.836421 11.19953 4.061429 1.765924 11.05831 3.974279 1.727509 10.85483 3.977438 1.728894 10.6302 4.070272 1.769828 10.42975 4.060393 2.166139 11.19952 3.734109 2.689662 11.19948 3.906426 2.083527 11.05825 3.600364 2.593788 10.42928 3.915076 2.088161 10.42962 3.517678 2.534526 10.62973 3.82561 2.04015 10.63007 3.514712 2.532395 10.85448 3.822518 2.038496 10.85473 3.592072 2.587842 11.05811 2.565844 4.01062 10.48597 2.75827 4.072757 10.27429 2.66592 4.041614 10.36861 2.260765 4.038693 10.46353 2.614019 4.024105 10.42161 2.226336 4.148783 10.30419 2.963474 4.152076 10.11925 2.85582 4.109116 10.19357 3.104826 4.208492 10.02167 3.346754 4.311355 9.883523 -1.451033 4.148783 10.44162 -0.2226777 4.148783 10.53961 1.008724 4.148783 10.49359 1.024318 4.038693 10.65586 -0.2261199 4.038693 10.70259 -1.473466 4.038693 10.60308 5.279688 3.500002 12.7865 5.237346 2.04768e-6 12.80597 5.241034 3.500002 12.81164 5.119545 3.500002 12.89065 5.058949 2.04768e-6 12.96133 5.066489 3.500002 12.9666 5.010156 3.500002 13.04725 4.971941 2.04768e-6 13.18131 4.979049 3.500002 13.18294 4.967471 3.500002 13.23345 3.199784 4.123123 10.03514 3.348326 4.30982 9.883641 3.347536 4.310595 9.883584 3.153702 4.167886 10.0317 3.06089 3.945844 10.23182 2.965269 4.038932 10.22453 2.896634 3.996478 10.31413 3.013154 3.882932 10.32309 2.955002 3.801482 10.47959 2.94095 3.779145 10.54104 2.930773 3.757345 10.64015 2.804694 3.948199 10.46786 2.778014 3.938289 10.52827 2.748949 3.93513 10.62579 2.748807 3.934072 10.65963 2.931376 3.753679 10.66683 2.749984 3.933014 10.69338 2.933001 3.749999 10.69338 2.933001 3.749999 10.75 2.749984 3.933014 10.75 2.976154 3.749999 10.96698 3.099067 3.749999 11.15093 3.499982 3.749999 11.31699 3.283007 3.749999 11.27383 3.499982 3.933014 11.50001 3.212971 3.933014 11.44291 2.969657 3.933014 11.28034 2.807078 3.933014 11.03702 11.13846 3.749999 11.31699 11.13846 3.933014 11.50001 11.70672 3.949614 11.32998 11.59931 3.841506 11.22036 11.66335 3.933014 11.28572 11.42193 3.933014 11.44437 11.52365 3.68804 11.14314 11.53527 3.749999 11.155 11.35276 3.749999 11.27493 11.90513 3.691348 10.87797 12.00741 3.961937 11.12849 12.3632 3.74526 10.82409 12.3632 3.853547 10.89645 11.9461 3.853547 10.97831 12.3632 3.925921 11.00475 12.3632 3.961937 11.05866 12.3632 3.691348 10.78807 12.84861 3.691348 10.78807 12.84861 3.74526 10.82409 12.84861 3.853547 10.89645 12.84861 3.925921 11.00475 12.84861 3.961937 11.05866 13.45777 3.961937 10.78184 13.33557 3.853547 10.67516 13.36401 3.691348 10.40448 13.46783 3.853547 10.4356 13.07121 3.691348 10.73986 13.25393 3.691348 10.60388 13.11604 3.853547 10.83853 13.18316 3.961937 10.98621 4.781631 3.933014 12.94587 5.254564 3.749999 12.7244 5.467196 3.749999 12.68302 5.072971 3.749999 12.8425 4.948919 3.749999 13.02009 4.945723 3.933014 12.71097 5.18593 3.933014 12.55474 5.467196 3.933014 12.5 11.13846 3.749999 12.68302 11.13846 3.933014 12.5 11.52365 3.68804 12.85687 11.35276 3.749999 12.72508 11.53527 3.749999 12.84502 11.59931 3.841506 12.77965 11.42193 3.933014 12.55564 11.66335 3.933014 12.71429 11.70672 3.949614 12.67003 12.3632 3.74526 13.17592 12.3632 3.691348 13.21195 11.90513 3.691348 13.12204 12.00741 3.961937 12.87152 11.9461 3.853547 13.0217 12.3632 3.853547 13.10356 12.3632 3.925921 12.99526 12.3632 3.961937 12.94135 13.3632 3.749999 13.18302 13.3632 3.933014 13.00001 13.58141 3.749999 13.22669 13.76601 3.749999 13.35098 13.65185 3.933014 13.05777 -2.191062 6.16523e-5 11.12538 -2.195152 2.04768e-6 11.12998 -2.234975 2.04768e-6 11.09453 -2.109582 2.04768e-6 11.20616 -2.050305 7.65535e-5 11.29996 -2.055886 2.04768e-6 11.30305 -2.028199 2.04768e-6 11.353 -2.050283 3.434496 10.76189 -2.190972 3.382148 10.59536 -2.050283 3.200518 10.83279 -2.190987 3.151598 10.66522 -2.191032 2.567517 10.81953 -2.191062 1.590731 11.00702 -2.191062 0.9567609 11.08216 -2.050298 2.60775 10.9894 -2.050305 1.616197 11.17973 -2.050305 0.9723326 11.25605 -1.619259 3.985571 10.77 -1.657391 3.974589 10.76629 -1.886139 3.817665 10.80162 -1.799295 3.90053 10.77346 -1.765708 3.923567 10.76828 -1.74922 3.93133 10.76798 -1.999492 3.52286 10.9561 -1.978601 3.644752 10.8851 -1.966427 3.680172 10.86613 -1.930001 3.748374 10.83318 -1.909117 3.78746 10.8143 -2.191948 3.416719 10.58314 -2.051631 3.461482 10.74923 -2.036291 3.607663 10.68565 -2.024146 3.650727 10.66856 -1.961524 3.782259 10.62165 -1.935246 3.819498 10.61012 -1.833359 3.921689 10.58444 -1.793305 3.949957 10.57971 -2.168866 3.602939 10.5217 -2.152542 3.657522 10.50516 -2.070847 3.823759 10.45973 -2.037051 3.870698 10.44856 -1.907023 3.999503 10.42365 -1.856158 4.035147 10.41905 -1.691195 4.113214 10.4172 -1.632961 4.12956 10.42045 -1.663091 4.011588 10.57783 -1.617091 4.024374 10.58119 7.333977 2.04768e-6 9.5 7.2 2.04768e-6 10 7.333977 2.04768e-6 10.5 7.700001 2.04768e-6 10.86603 8.200003 2.04768e-6 11 8.700004 2.04768e-6 10.86603 9.066029 2.04768e-6 10.5 9.199997 2.04768e-6 10 9.066029 2.04768e-6 9.5 8.700004 2.04768e-6 9.133975 8.200003 2.04768e-6 9 7.700001 2.04768e-6 9.133975 8.601083 2.04768e-6 29.73889 8.632703 2.04768e-6 29.76545 8.766739 2.04768e-6 29.87804 8 2.04768e-6 29.52001 8.154965 2.04768e-6 29.56153 8.238418 2.04768e-6 29.58389 8.5 2.04768e-6 29.65398 7.880127 2.04768e-6 29.55213 7.610117 2.04768e-6 29.62448 7.282366 2.04768e-6 29.83679 7.499998 2.04768e-6 29.65398 8.866025 2.04768e-6 30.02 9.000002 2.04768e-6 30.52 8.866025 2.04768e-6 31.02001 8.5 2.04768e-6 31.38603 8 2.04768e-6 31.52001 7.499998 2.04768e-6 31.38603 7.133973 2.04768e-6 31.02001 6.999997 2.04768e-6 30.52 7.133973 2.04768e-6 30.02 -9.366023 2.04768e-6 9.214648 -9.5 2.04768e-6 9.714647 -9.366023 2.04768e-6 10.21465 -8.999999 2.04768e-6 10.58067 -8.499998 2.04768e-6 10.71465 -8.000003 2.04768e-6 10.58067 -7.633972 2.04768e-6 10.21465 -7.500003 2.04768e-6 9.714647 -7.633972 2.04768e-6 9.214648 -8.000003 2.04768e-6 8.848622 -8.499998 2.04768e-6 8.714648 -8.999999 2.04768e-6 8.848622 -9.986202 3.426658 8.176622 -9.714412 4.502298 8.05133 -9.741525 4.428642 11.35535 -9.664739 4.293265 11.602 -9.88801 3.715472 11.37427 -9.943316 3.832044 11.16 -10.17212 2.997043 10.85738 -10.29502 2.411219 10.63204 -10.27505 2.341109 10.76485 -10.14003 2.907829 11.02417 -10.42531 1.537891 10.27752 -10.47226 1.062202 10.06038 -10.48982 0.8251985 9.925934 -10.49385 0.7623603 9.880096 -10.49798 0.6933084 9.812848 -10.49864 0.6816706 9.797024 -10.4999 0.6592592 9.751793 -10.50016 0.6546846 9.697501 -10.50007 0.656279 9.740574 -10.49972 0.6626269 9.667907 -10.49754 0.7009378 9.607213 -10.4957 0.7320216 9.575274 -10.48573 0.8852651 9.465328 -10.46946 1.095848 9.352124 -10.43592 1.443358 9.192528 -10.41835 1.493546 10.35833 -10.47006 1.030671 10.10987 -10.48942 0.7997474 9.956144 -10.49387 0.7384887 9.903748 -10.49842 0.6711503 9.826882 -10.49915 0.6598106 9.808798 -10.50054 0.6379505 9.757101 -10.50072 0.6350448 9.744279 -10.50082 0.6334951 9.69505 -10.50034 0.6412437 9.661228 -10.49794 0.6786009 9.591859 -10.49591 0.7089099 9.555354 -10.48491 0.858294 9.429672 -10.46698 1.063423 9.300225 -10.43003 1.40162 9.117623 -10.3498 1.947658 8.8494 -10.1998 2.877029 8.617416 -10.36301 2.0054 8.958397 -10.17043 2.791854 8.457566 -10.03233 3.533604 8.374139 -9.766126 4.360633 8.095137 -9.634675 4.364641 7.800799 -9.692008 4.227387 7.852088 6.168982 5.604552 20.20001 6.168982 2.04768e-6 20.20001 6.360327 5.604552 19.23807 6.522541 5.604552 19.34645 6.601994 5.604552 19.95001 6.418986 5.604552 20.13302 6.668982 5.604552 19.70001 6.630925 5.604552 19.50866 6.418986 2.04768e-6 20.13302 6.601994 2.04768e-6 19.95001 6.668982 2.04768e-6 19.70001 6.630925 2.04768e-6 19.50866 6.522541 2.04768e-6 19.34645 6.360327 2.04768e-6 19.23807 -10.001 3.185e-5 6.643953 -9.829777 1.69488e-5 6.464102 -6.851854 2.04768e-6 12.46286 8.766739 -0.2033243 29.47558 8.766739 -0.05371659 29.65259 8.220269 -0.08438318 29.47893 7.305441 -0.2131292 29.46648 7.888375 -0.08214801 29.4681 7.640575 -0.08734852 29.50333 7.516412 -0.08733361 29.53546 7.28712 -0.06651669 29.62431 8.143878 -0.08271425 29.47057 7.563455 -0.2099106 29.44177 7.683841 -0.1968721 29.43416 7.904476 -0.1746842 29.4265 8.123359 -0.1765469 29.42702 8.190072 -0.1824775 29.42879 8.538192 -0.2166906 29.4501 8.578746 -0.2176741 29.45392 8.580341 -0.08319109 29.56778 8.616684 -0.08018106 29.58175 + + + + + + + + + + -0.2487352 0.008565187 0.9685337 -0.7246762 0.01432818 0.6889406 -0.8490146 0 0.5283693 -0.7070949 0.005616664 0.7070963 -0.8003147 0.02976042 0.598841 -0.7247998 0.01434367 0.6888102 -0.6358687 0.004319429 0.7717851 -0.5554332 3.86374e-4 0.831561 -0.5553988 3.85149e-4 0.831584 -0.9991033 0 0.0423395 -0.5007086 -6.75654e-5 0.8656159 -0.5003312 -6.85248e-5 0.8658341 -0.2588194 -6.61104e-5 0.9659257 -0.9541143 0 0.2994428 -0.9659024 0.006902992 0.2588146 -0.9991033 0 0.0423395 -0.965925 0 -0.2588219 -0.965925 0 -0.2588219 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.2588194 0 -0.9659257 -0.2588194 0 -0.9659257 0.2588194 0 -0.9659257 0.2588194 0 -0.9659257 0.7071071 0 -0.7071064 0.7071071 0 -0.7071064 0.965925 0 -0.2588219 0.965925 0 -0.2588219 0.9659254 0 0.2588208 0.9659254 0 0.2588208 0.7071064 0 0.7071071 0.7071064 0 0.7071071 0.2588194 0 0.9659257 0.2588194 0 0.9659257 -0.2591935 0 0.9658254 -0.2448998 0.06996172 0.9670209 0.9372315 0.003877043 0.3486865 0.9525478 0 0.3043891 0.7071058 0 0.7071078 0.7071058 0 0.7071078 0.3043825 0 0.9525499 0.3043825 0 0.9525499 -0.1660468 0 0.9861179 -0.1660468 0 0.9861179 -0.5995408 0 0.8003442 -0.5995408 0 0.8003442 0.8003452 0 -0.5995395 0.8003452 0 -0.5995395 0.9861175 0 -0.1660494 0.9861175 0 -0.1660494 0.9930276 0 0.1178825 0.9930276 0 0.1178825 1 0 0 1 0 0 0.2576425 0.9658426 0.02772182 0.543603 0.5486195 0.6352264 0.234607 0.933286 0.2719131 0.07485252 0.9940748 0.07881945 0.9920967 0.1254724 -8.31168e-4 0.9963681 0.08398199 0.01406002 0.9898528 0.142081 0.002080917 0.979599 0.2008995 0.005011737 0.9490262 0.3151056 0.007602035 0.7874258 0.6160897 0.01984924 0.8607484 0.5088184 0.01469904 0.8805961 0.4710809 -0.05131697 0.5325939 0.8462173 0.01612895 0.3487116 0.9371663 0.01092857 0.2116463 0.9766626 -0.03654909 0.2117103 0.9766504 -0.0365082 0.3401814 0.9402994 0.01066672 0.3489704 0.9371173 0.005568981 0.1422489 0.9898133 0.00591433 0.2243314 0.9744508 0.01100087 0.3487887 0.9371475 0.01004129 0.2123072 0.9324516 0.2923349 0.39857 0.7827123 0.4780204 0.6282406 0.2354394 0.7415403 0.6360232 0.137493 0.7593221 0.6081978 0.2332469 0.7587432 0.6339349 0.03195273 0.7727261 0.9882102 0.1303397 0.08032542 0.7337476 0.09059065 0.6733557 0.7148897 0.1467315 0.6836684 0.7147741 0.146729 0.6837899 0.8818153 0.1868643 0.4329936 0.8817958 0.1868636 0.4330336 0.8283843 0.1017333 0.5508446 0.7965362 0.1930748 0.572933 0.7965602 0.1930755 0.5728994 0.9685831 0.1960646 0.1529887 0.8883553 0.448154 0.09991365 0.9915144 0.06680899 0.1115159 0.9685832 0.1960647 0.1529877 0.6282405 0.2354401 0.7415402 0.5621881 0.4394161 0.7006127 0.6586383 0.4481766 0.6044283 0.6642456 0.4392595 0.6048378 0.7444419 0.4480573 0.495026 0.7500461 0.4395295 0.4942111 0.6254435 0.7598335 0.1774072 0.8645868 0.4385737 0.2452403 0.8589994 0.448679 0.246591 0.9590967 0.06579548 0.2753258 0.9472079 0.1361081 0.290296 0.2582783 0.9656707 0.02779346 0.2582849 0.9656748 0.02758735 0.6529574 0.7541768 0.06974226 0.6512229 0.7588663 0.005535244 0.5435923 0.5486447 0.6352136 0.4113712 0.7510759 0.51639 0.4810426 0.7594318 0.4380198 0.4908158 0.751809 0.4403216 0.5433296 0.7593591 0.358004 0.5532313 0.7520773 0.3582105 0.8938005 0.1469459 0.4237069 0.8079535 0.4477877 0.3830111 0.8127002 0.4405624 0.3813441 0.5893199 0.7591013 0.2765272 0.5978411 0.7529467 0.2750587 0.2156524 0.9714163 0.09921878 0.2547294 0.9632499 0.08522045 0.1841645 0.9596986 0.2122777 0.1919233 0.9603763 0.2020956 0.177082 0.9712898 0.1588642 0.2181562 0.9661812 0.1374834 0.2166285 0.9661253 0.1402643 0.2239093 0.9643399 0.1411136 0.22391 0.9643402 0.1411117 0.6493735 0.7604623 -0.003346323 0.6516327 0.7585152 -0.005446553 0.6523281 0.757922 0.004721462 0.9920969 0.1254724 -8.27656e-4 0.9911872 0.1324462 -0.002463459 0.9984474 0.05500805 0.008761525 0.9858322 0.1658726 0.02492445 0.9858328 0.1658731 0.02489262 0.2408572 0.9705597 0.001340806 0.24045 0.9706602 0.001647174 0.2404623 0.9706569 0.001740396 0.2409135 0.9705452 0.001649618 0.2409132 0.9705453 0.00164777 0.2576425 0.9658426 0.02772194 0.2369408 0.9715222 0.001881778 0.6536868 0.7567475 0.005191564 0.6536263 0.7568045 0.004427194 0.8947072 0.446612 0.006060123 0.8866623 0.4494038 -0.108932 0.9687777 0.1670939 0.1831648 0.9688018 0.1669515 0.1831669 0.9836324 0.1800719 0.006440341 0.8953298 0.4453654 0.005862176 0.8953742 0.445245 0.007857024 0.8941761 0.447651 0.007600247 0.8914772 0.4422134 0.09856879 0.6466965 0.7593886 0.07150387 0.6362156 0.7510985 0.1762969 0.2257307 0.9721795 0.06255048 0.2547295 0.9632499 0.08521997 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.7071074 0 0.7071063 0.7071044 0 0.7071092 0.7071045 0 0.7071092 0.7071067 -1.67972e-5 0.7071067 0 0 1 0 0 1 0 0 1 0.9560926 0.2192227 0.194495 0.2443244 0.0561459 0.9680668 0.183058 0.06818658 0.9807347 0.16785 0.05137568 0.9844729 0.1903032 0.3600027 0.913336 0.3189436 0.3405709 0.8844697 0.5084367 0.3052394 0.8051838 0.4612776 0.2258927 0.8580184 0.4852998 0.2713737 0.8311682 0.3689094 0.2064478 0.9062479 0.2683198 0.1412242 0.9529219 0.02038061 0.2034302 0.9788773 0.05908787 0.1851539 0.9809315 0.9844496 0.07237714 0.1600641 0.9774721 0.08145868 0.1947122 0.8284415 0.07541948 0.5549743 0.8804232 0.05674141 0.4707818 0.8804696 0.05674487 0.4706944 0.5536478 0.05221492 0.8311124 0.720582 0.0483039 0.6916853 0.7205574 0.04830205 0.691711 0.01289498 9.48247e-4 0.9999164 0.193241 0.01871174 0.9809729 0.19436 0.01919245 0.9807426 0.5068491 0.03312176 0.8613983 0.5068656 0.03312301 0.8613885 0.9560923 0.2192158 0.1945043 0.8409563 0.5049391 0.1944959 0.8409903 0.5048866 0.1944862 0.8409903 0.5048796 0.1945042 0.7512989 0.6306488 0.1945044 0.7512983 0.6306532 0.1944926 0.7512981 0.6306538 0.1944917 0.6429739 0.7407815 0.1944922 0.6429744 0.7407801 0.1944962 0.5186808 0.8325518 0.1944931 0.5187041 0.832538 0.1944904 0.518707 0.8325322 0.1945073 0.3815721 0.9036423 0.1945077 0.3815748 0.9036384 0.1945205 0.3815703 0.903642 0.1945123 0.2349846 0.9523378 0.1945123 0.2349781 0.9523444 0.1944872 0.0827555 0.9774075 0.1944891 0.08255767 0.9774225 0.1944975 0.08255791 0.9774224 0.1944983 -0.07191711 0.9782631 0.1944971 -0.2245962 0.9548431 0.1945021 -0.2245988 0.9548441 0.1944946 -0.07191205 0.9782641 0.1944943 -0.07192409 0.9782669 0.1944758 -0.1905632 0.810147 0.5543892 -0.1905725 0.8101572 0.5543712 -0.06101965 0.8300293 0.5543717 -0.06101906 0.8300284 0.5543732 0.07004785 0.8293157 0.5543726 0.07005494 0.8293001 0.5543949 0.199375 0.8080204 0.5543941 0.1993685 0.8080438 0.5543621 0.3237565 0.7667229 0.5543625 0.3237574 0.766715 0.5543728 0.4401044 0.7063827 0.5543749 0.4401043 0.7063798 0.5543788 0.5455421 0.6285286 0.5543786 0.5455389 0.6285127 0.5543999 0.6374437 0.5350775 0.5543983 0.6374449 0.5350806 0.554394 0.7135429 0.4283738 0.5543938 0.7135436 0.4283751 0.5543917 0.2274321 0.0916391 0.9694725 0.5164232 0.208082 0.8306677 0.5164257 0.2080844 0.8306656 0.7719519 0.311044 0.5543844 0.7719491 0.3110406 0.5543901 0.9098244 0.3665945 0.1944947 0.909824 0.3665932 0.1944983 -0.1274878 0.541973 0.8306697 -0.1274874 0.5419725 0.8306701 -0.04082012 0.5552666 0.83067 -0.04081499 0.5552557 0.8306776 0.04686474 0.5547783 0.8306772 0.04685723 0.5548039 0.8306606 0.133374 0.5405674 0.8306612 0.1333773 0.5405426 0.830677 0.2165809 0.512902 0.830677 0.2165811 0.5129104 0.8306717 0.2944183 0.4725497 0.8306712 0.2944181 0.4725487 0.8306719 0.3649576 0.4204659 0.830671 0.3649595 0.4204712 0.8306674 0.4264432 0.3579627 0.8306677 0.4264451 0.3579661 0.8306653 0.4614656 0.3096598 0.8313605 0.2026588 0.1356741 0.9698051 0.9560915 0.2192131 0.1945118 0.8112127 0.1859952 0.5543825 0.8112162 0.1859985 0.554376 0.5426853 0.1244288 0.8306685 0.5426856 0.124429 0.8306682 0.1907231 0.04372972 0.9806694 0.1907235 0.04372996 0.9806693 -0.04480618 0.1904794 0.9806681 -0.04480242 0.1904734 0.9806694 -0.01434445 0.195145 0.9806695 -0.01434594 0.1951485 0.9806687 0.01646751 0.1949806 0.9806689 0.01646816 0.1949781 0.9806693 0.04687577 0.189975 0.9806693 0.04687494 0.1899837 0.9806676 0.07612007 0.1802685 0.9806676 0.07611989 0.1802663 0.980668 0.1034755 0.1660809 0.9806681 0.1034746 0.1660768 0.9806689 0.128264 0.1477734 0.9806688 0.1282634 0.147772 0.9806691 0.1498709 0.1258045 0.9806692 0.1498711 0.1258047 0.980669 0.1600139 0.1116209 0.9807835 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.9960319 -0.0601266 0.0656138 0.3223072 -0.9442805 0.06672728 0.2630461 -0.9623038 0.06912356 0.2514492 -0.9654057 0.06903147 0.4214485 -0.9046159 0.0636484 0.411602 -0.909021 0.06530535 0.4734299 -0.8784515 0.06470817 0.4045312 -0.9121922 0.06526803 0.3728151 -0.9255443 0.06615537 0.4115406 -0.9090191 0.06571549 0.3765294 -0.9240119 0.06654036 0.3357275 -0.9395672 0.06708502 0.2514274 -0.9654113 0.06903165 0.2630534 -0.9623331 0.06868755 0.18087 -0.9810724 0.06915867 0.1677485 -0.983338 0.07004892 0.08885699 -0.993584 0.06996464 0.07346463 -0.9948342 0.07005667 0.0985437 -0.9926748 0.06989842 0.08885508 -0.9936031 0.06969606 -0.006624281 -0.9973414 0.07256793 0.02867788 -0.9971215 0.07018792 0.02865332 -0.9971222 0.07018822 -0.006604671 -0.9975041 0.07029908 -0.08320409 -0.9939021 0.07235801 -0.06953179 -0.9950149 0.07148885 -0.1568435 -0.9850564 0.07116234 -0.1668089 -0.9834029 0.07136857 -0.1568295 -0.9850483 0.07130491 -0.1667909 -0.9833788 0.07174205 -0.2476046 -0.9662675 0.07084637 -0.2365483 -0.9690697 0.07034808 -0.3048955 -0.9497188 0.07122457 -0.2475591 -0.9662808 0.07082235 -0.3048929 -0.9496847 0.0716893 -0.3381173 -0.9384965 0.07000774 -0.7238742 -0.6868681 0.06494897 -0.7101954 -0.7009996 0.06497883 -0.6978563 -0.7132539 0.06531184 -0.4003917 -0.9135882 0.07101523 -0.3970206 -0.9150674 0.07089579 -0.400461 -0.9135652 0.07091933 -0.3970138 -0.9150722 0.0708726 -0.4584157 -0.8860582 0.068964 -0.4850943 -0.8716614 0.0699281 -0.5350875 -0.8419853 0.06886386 -0.4851396 -0.8717494 0.06850171 -0.5351432 -0.8420345 0.06782096 -0.5457341 -0.8351868 0.06809854 -0.6060511 -0.7925664 0.06738513 -0.6034318 -0.7945751 0.06723368 -0.6061525 -0.7924995 0.06725823 -0.6034427 -0.7945678 0.06722259 -0.6486933 -0.7581636 0.06621891 -0.6920313 -0.7188829 0.06557422 -0.6918944 -0.7190142 0.06558048 -0.6783929 -0.7317094 0.06621515 -0.6899577 -0.7207772 0.0666235 -0.6732545 -0.7364526 0.06607574 -0.7239235 -0.6868162 0.06494933 -0.6784411 -0.7318596 0.06402313 -0.7559912 -0.6513555 0.06491047 -0.7469044 -0.6620509 0.06182521 -0.8098394 -0.5823724 0.07072907 -0.7861507 -0.6143012 0.06783127 -0.8786587 -0.4732251 0.06337922 -0.8646312 -0.4983682 0.06357693 -0.8641998 -0.4991152 0.0635823 -0.8631812 -0.5008727 0.06359839 -0.8524482 -0.5189081 0.06376844 -0.8824287 -0.4663938 0.06161594 -0.8347218 -0.5469375 0.06402331 -0.8324844 -0.5503174 0.06419271 -0.8102353 -0.5826824 0.06324571 -0.79179 -0.6074845 0.06349194 -0.7917513 -0.607535 0.06349158 -0.996446 -0.05279386 0.0656377 -0.9962087 -0.0576874 0.06511789 -0.9861902 -0.1525443 0.06449186 -0.9870012 -0.1471412 0.06463742 -0.9861829 -0.1525346 0.0646252 -0.9869835 -0.1471469 0.06489539 -0.9665478 -0.248396 0.06391209 -0.9707353 -0.2312412 0.06481075 -0.9664965 -0.248367 0.06479358 -0.9707196 -0.2311787 0.06526833 -0.9473921 -0.3137524 0.06330555 -0.9461508 -0.3175162 0.06310397 -0.9236741 -0.3777858 0.06406271 -0.9149994 -0.3984188 0.06354981 -0.9236931 -0.3778113 0.06363618 -0.9150406 -0.3984312 0.06287527 -0.8823136 -0.4663835 0.06331795 -0.8952972 -0.4407317 0.06479561 -0.8786565 -0.4732294 0.06337922 -0.9981702 -0.06046652 0 -0.9977526 -0.05907917 0.03161507 -0.9888049 -0.1475775 -0.02203899 -0.9989529 -0.0452215 0.0069319 -0.9995225 -0.02852058 0.01189124 -0.9967328 -0.07786041 0.02148306 -0.996737 -0.07779872 0.02151441 -0.9954338 -0.09446537 0.01370489 -0.9954316 -0.09448981 0.01369428 -0.9935141 -0.1135619 0.005791723 -0.991614 -0.1292347 -3.03201e-4 -0.9914531 -0.1304637 0 -0.9773854 -0.2072807 0.04186326 -0.9939554 -0.1097842 -3.25707e-4 -0.9939495 -0.1098387 -3.03008e-4 -0.9940132 -0.1092594 -5.63081e-4 -0.994013 -0.109261 -5.61838e-4 -0.993974 -0.1096155 -1.98134e-4 -0.9939736 -0.1096197 -1.91478e-4 -0.9971572 -0.07391947 -0.01460719 -0.987203 -0.1583282 0.01904386 -0.9773796 -0.207306 0.04187607 -0.9532707 -0.3020503 0.006373584 -0.988927 -0.1476169 -0.01525062 -0.9533506 -0.3017536 0.008208751 -0.9772395 -0.2121388 -3.06921e-4 -0.9138069 -0.406051 -0.008908748 -0.9098415 -0.4147123 -0.01421445 -0.8701542 -0.4927795 0 -0.8772678 -0.4799979 0.001800715 -0.8713656 -0.4906231 -0.003288269 -0.884724 -0.4661026 0.003455221 -0.8897153 -0.4564525 0.007606625 -0.8763079 -0.4816956 -0.007338345 -0.9019885 -0.431427 0.01695829 -0.8862593 -0.4628625 -0.0174067 -0.9267089 -0.373901 0.03753018 -0.901618 -0.4316466 -0.02767944 -0.9066039 -0.4215382 -0.01936239 -0.9187377 -0.3948603 -0.002544403 -0.9206579 -0.3903703 -2.08688e-4 -0.9254117 -0.3789632 -2.08467e-4 -0.9479479 -0.3184244 8.90345e-4 -0.972694 -0.2319651 -0.007649481 -0.9087456 -0.4173332 0.003805756 -0.9038547 -0.4278046 0.005473911 -0.8973559 -0.4412361 0.007943689 -0.8924643 -0.4510025 0.01020932 -0.8846551 -0.4660398 0.01387166 -0.9474281 -0.3182812 -0.03281587 -0.9169123 -0.3989966 -0.008577525 -0.871976 -0.4895297 0.004315733 -0.8848593 -0.4658583 0 -0.8696537 -0.4936621 -5.76485e-4 -0.8567686 -0.4411007 -0.2671661 -0.7017266 -0.3340901 -0.6292564 -0.2516736 0.9678121 0 -0.2289689 0.973433 0.001182913 -0.1477333 0.989027 -5.82547e-4 -0.07331198 0.9973083 0.001283824 -0.04725795 0.9988822 0.001011967 -0.04728573 0.9988809 0.001011967 -0.07332402 0.9973081 8.68881e-5 0.05323219 0.9985822 -5.44717e-5 0.08416515 0.9964509 0.001332819 0.120681 0.9926912 3.82581e-4 0.380763 0.9246049 0.01118987 0.286017 0.9582195 0.003098368 0.0843656 0.9964265 -0.004084467 0.1879668 0.9821754 -2.97787e-4 0.1879844 0.982172 -2.97787e-4 0.5288062 0.8487415 0.00132656 0.2395499 0.9708735 -0.004508435 0.3890001 0.9212373 8.41487e-4 0.3807635 0.9246721 8.41408e-4 0.3890053 0.921235 0.001027107 0.4424286 0.8968038 2.26948e-5 0.5024775 0.8645902 -5.83583e-5 0.6554921 0.7552019 4.99063e-4 0.665376 0.7465071 0.001352906 0.5287775 0.8487584 -0.001895606 0.5870779 0.8095304 -3.8015e-4 0.5870985 0.8095154 -3.80151e-4 0.7659241 0.6429303 0.001013576 0.7603262 0.6495409 8.19465e-4 0.7659239 0.6429309 8.19539e-4 0.7603471 0.6495167 5.37093e-4 0.7143357 0.6998032 -6.86472e-5 0.8573285 0.5147696 -2.50733e-4 0.8749508 0.4842118 -7.48078e-6 0.8573645 0.5147097 -7.12766e-6 0.8749685 0.4841741 0.002389848 0.8219425 0.5695702 -5.35373e-4 0.9973083 0.07332247 0 0.9991337 0.04156136 0.002123057 0.9949678 0.100194 4.17529e-4 0.9859118 0.1672653 -4.71132e-4 0.9747067 0.2234836 0.001405775 0.9641402 0.2653911 0.001070499 0.9747055 0.2234904 0.001072108 0.9641373 0.2654038 -2.8787e-4 0.9275373 0.3737304 4.7865e-4 0.9324766 0.3612279 0.001354932 0.90571 0.423898 6.32443e-5 -1 0 0 -1 0 0 0 0 1 0 0 1 -0.9979403 0.06415045 0 -0.9931625 0.1167397 1.48839e-4 -0.9931634 0.1167324 1.49054e-4 -0.994851 0.1013424 0.001135826 -0.9964515 0.08409017 0.003636002 -0.9995124 0.02536064 0.01821243 -0.9964576 0.08401834 0.003650367 -0.9979116 0.06408709 0.00807631 -0.9990735 0.03985583 0.01623761 -0.9993914 0.02707195 0.02199339 -0.9993769 0.02796524 0.02153569 -0.9992603 0.03377079 0.01839697 -0.9992621 0.03369265 0.01844185 -0.9988333 0.04711276 0.01060038 -0.9981185 0.06128722 0.001794993 -0.9831888 0.1825165 0.005259752 -0.9798342 0.1998125 0 -0.9807403 0.1953071 -0.001943647 -0.9833614 0.1814619 -0.00848639 -0.9832199 0.1823472 0.005316138 -0.9855192 0.1692849 0.009725689 -0.9815477 0.1912122 0.001387834 -0.9916427 0.1290153 -6.1403e-5 -0.9916387 0.1290457 -6.1403e-5 -0.9991048 0.04230386 0 -0.9995211 0.02793616 -0.01331174 -0.999392 0.03383845 -0.008405923 -0.9999859 0.005260288 -7.14103e-4 -0.9995772 0.02413278 -0.01621508 -0.9995757 0.02424883 -0.01613646 -0.9995762 0.02420669 -0.01616406 -0.9995529 0.02565622 -0.01535671 -0.9993837 0.03325641 -0.0112431 -0.9915311 0.1271335 0.02651762 -0.9978429 0.06044274 -0.02561616 -0.9965594 0.08155995 -0.01474249 -0.9965613 0.08153545 -0.01475179 -0.9949544 0.09996402 -0.008536577 -0.9931223 0.1169376 -0.005796372 -0.9912218 0.1321222 -0.004815816 -0.9912249 0.1320984 -0.004817008 -0.9918679 0.1271802 -0.004817068 -0.9914079 0.1307453 -0.004010081 -0.9772174 0.2118697 0.01254385 -0.9851732 0.1709632 -0.01433432 -0.9833606 0.1814662 -0.008484184 0.4889081 0 0.8723353 0.1660177 -9.50085e-6 0.9861229 0.3667961 7.59375e-6 0.9303014 0.50317 0.008077979 0.8641496 0.601863 0.01884692 0.7983769 0.657787 0.02784812 0.752689 0.4889532 1.4029e-5 0.8723099 0.6699646 0 0.7423931 0.1721339 -9.50446e-6 0.9850735 0.05702888 0.007143735 0.998347 -0.003314018 0.003267347 0.9999892 -0.3828008 0.00252068 0.9238275 -0.3826469 1.08965e-4 0.9238947 -0.5521556 0 0.8337411 -0.5148684 5.07238e-4 0.8572691 -0.4107853 0.0052042 0.9117173 -0.2976267 0.01968896 0.9544793 -0.3893949 0.004503905 0.9210599 -0.1620031 -0.0012784 0.9867895 -0.1620097 -0.0012784 0.9867882 -0.8648924 -0.4982782 0.06066393 -0.8678257 -0.4960411 0.02866744 -0.9976536 -0.06034904 0.03233271 -0.9976492 -0.06015038 0.03283643 -0.9074396 -0.4178726 0.04399788 -0.8804497 -0.4728276 0.03524833 -0.8817864 -0.4703816 0.03455114 -0.8806806 -0.4727275 0.03050076 -0.8969328 -0.4410193 0.031834 -0.8973311 -0.440237 0.03143709 -0.9164689 -0.3988046 0.0322436 -0.9164214 -0.3989411 0.03190153 -0.9164202 -0.3989441 0.03189921 -0.9475055 -0.3181813 0.03152829 -0.9474951 -0.3182127 0.03152382 -0.9475679 -0.3179178 0.03230142 -0.9723072 -0.2315207 0.03188413 -0.9722396 -0.2317959 0.03195148 -0.9722785 -0.2315741 0.03237211 -0.9885376 -0.1475176 0.03212493 -0.9885413 -0.1474909 0.03213179 -0.988552 -0.147332 0.03253275 -0.9885529 -0.147324 0.03254008 -0.08226352 -0.275732 0.957708 -0.1950888 -0.2192463 0.9559663 -0.2591243 -0.1434178 0.9551365 -0.2850121 -0.07837921 0.955314 0.09828698 -0.2781002 0.9555103 0.09834396 -0.2780814 0.95551 0.07843995 -0.2864704 0.9548727 0.1067426 -0.2512207 0.9620261 0.08553051 -0.2768208 0.9571075 0.2423606 -0.6384871 0.7304762 0.2424252 -0.6386685 0.7302963 -0.9238491 -0.04793715 0.3797431 -0.4847221 -0.0109148 0.8746001 -0.7447637 -0.07596105 0.6629908 -0.2964171 -0.02976065 0.9545948 -0.4846987 -0.01091355 0.8746131 -0.2891418 -0.04395979 0.9562764 -0.20456 -0.008458018 0.9788176 -0.2864569 -0.07365375 0.9552578 -0.2941201 -0.08085912 0.952342 -0.2914159 -0.04936909 0.9553216 -0.2922452 -0.04524368 0.9552726 -0.2993696 -0.05072736 0.9527878 -0.2964186 -0.02974724 0.9545947 -0.2860399 -0.1106979 0.951802 -0.2806931 -0.09304046 0.9552774 -0.2758462 -0.1067516 0.9552555 -0.2820042 -0.1154002 0.9524475 -0.2714968 -0.1270024 0.954023 -0.2620186 -0.1384903 0.9550742 -0.2688302 -0.1488102 0.9516227 -0.2714954 -0.1270056 0.954023 -0.2532095 -0.1755311 0.9513536 -0.2466334 -0.1629987 0.9553028 -0.2427729 -0.1683008 0.9553722 -0.2391064 -0.1834129 0.9535135 -0.2246397 -0.192049 0.9553294 -0.2246372 -0.1920523 0.9553294 -0.227244 -0.2013391 0.9527974 -0.2129479 -0.2087953 0.9544935 -0.1997773 -0.2152778 0.9558998 -0.2029415 -0.2280836 0.9522566 -0.2129334 -0.20881 0.9544934 -0.1786695 -0.2467833 0.9524575 -0.1766157 -0.2323107 0.9564719 -0.1710005 -0.2361863 0.9565431 -0.1626129 -0.2486241 0.9548524 -0.1459617 -0.2516865 0.9567388 -0.145969 -0.251682 0.9567389 -0.1452547 -0.2607773 0.9544088 -0.1293544 -0.2628676 0.9561213 -0.08808213 -0.2741515 0.9576443 -0.08550888 -0.2865984 0.9542272 -0.1097176 -0.2669558 0.9574428 -0.1150386 -0.2649306 0.9573808 -0.1137937 -0.2769072 0.9541349 -0.1293722 -0.2628588 0.9561214 -0.05638152 -0.2946399 0.9539436 -0.06818783 -0.2792931 0.9577817 -0.05403065 -0.2824074 0.9577718 -0.04957932 -0.2922366 0.9550601 -0.03511053 -0.2890009 0.9566848 0.008361577 -0.2885398 0.9574314 0.01391166 -0.2977536 0.9545414 -0.01534283 -0.2878019 0.957567 -0.02008503 -0.2876862 0.9575141 -0.01581621 -0.296689 0.9548431 -0.03507083 -0.2890056 0.9566847 0.07285571 -0.280908 0.9569653 0.07287365 -0.2809039 0.9569652 0.05026906 -0.2940924 0.9544541 0.04247558 -0.2857343 0.9573671 0.02860355 -0.2874159 0.9573787 0.04411911 -0.2969568 0.9538711 0.0134781 -0.2881599 0.9574875 0.3256363 -0.8922515 0.312807 0.3257179 -0.8924824 0.3120627 0.07006955 -0.948859 0.3078259 0.1602745 -0.9378598 0.3077841 0.1598485 -0.938222 0.3069004 0.2513017 -0.9179654 0.3068991 0.2507429 -0.9182353 0.3065485 0.2513937 -0.9183096 0.3057917 0.3207505 -0.8963679 0.3060126 0.09420067 -0.9466936 0.3080543 0.09382015 -0.9466359 0.308348 0.02750718 -0.9509647 0.308074 0.02723544 -0.95083 0.3085134 0.02747982 -0.950809 0.3085567 -0.06634408 -0.9488885 0.3085597 -0.06624037 -0.9488362 0.3087428 -0.1590963 -0.9377462 0.3087402 -0.1590404 -0.937763 0.3087176 -0.1590831 -0.9377749 0.3086596 -0.2254682 -0.9239735 0.3089289 -0.225633 -0.9239776 0.3087963 -0.2909045 -0.9056414 0.3085257 -0.2906761 -0.905726 0.3084929 -0.2909581 -0.9057799 0.3080685 -0.5204492 -0.7969656 0.306559 -0.4631955 -0.8316464 0.3062909 -0.4626725 -0.8318362 0.3065658 -0.4630384 -0.8313619 0.3072993 -0.3786029 -0.8730546 0.3073037 -0.3788827 -0.872668 0.3080556 -0.3788889 -0.8726636 0.3080611 -0.5757586 -0.7586048 0.304993 -0.5761709 -0.7579813 0.3057639 -0.5210719 -0.7967582 0.3060399 -0.7129833 -0.6321777 0.3033251 -0.6480703 -0.698563 0.3033391 -0.6476497 -0.698922 0.3034104 -0.6478788 -0.6982504 0.3044659 -0.5764277 -0.7583052 0.3044741 -0.7950925 -0.5256605 0.3025045 -0.756233 -0.5800358 0.3027707 -0.7560531 -0.5802226 0.3028623 -0.7561491 -0.5800527 0.302948 -0.7133675 -0.6320535 0.30268 -0.8427344 -0.4454809 0.3022341 -0.8427639 -0.4454134 0.3022516 -0.795237 -0.525589 0.3022489 -0.8822481 -0.3610025 0.3021848 -0.882246 -0.3610186 0.3021715 -0.8427665 -0.445458 0.3021783 -0.8822066 -0.3607165 0.3026467 -0.9047275 -0.2995032 0.3029291 -0.9045691 -0.2997658 0.3031423 -0.9230116 -0.2373265 0.3028627 0.2290526 -0.6595829 0.7158808 0.1840721 -0.6739085 0.7155172 0.1843094 -0.6733044 0.7160246 0.1172888 -0.6881493 0.7160265 0.1175068 -0.6877191 0.7164041 0.06879448 -0.6939284 0.71675 0.06901836 -0.6937678 0.716884 0.02000939 -0.6972594 0.7165396 0.02015382 -0.6970534 0.716736 -0.04864603 -0.6956419 0.7167398 -0.04855257 -0.6955328 0.7168521 -0.1165893 -0.68741 0.7168505 -0.1166205 -0.6874402 0.7168163 -0.1651972 -0.6770541 0.7171524 -0.1653339 -0.6770979 0.7170796 -0.2131198 -0.6639688 0.7167463 -0.213329 -0.6641185 0.7165454 -0.2775497 -0.6399473 0.7165428 -0.2779279 -0.6401652 0.7162015 -0.3392686 -0.6098827 0.7161982 -0.339798 -0.6101242 0.7157415 -0.3816991 -0.584413 0.7160778 -0.3821663 -0.5843947 0.7158433 -0.4223954 -0.5564451 0.7155076 -0.4231131 -0.556653 0.7149217 -0.4752804 -0.5128309 0.7149218 -0.4759228 -0.5129503 0.7144085 -0.5235962 -0.4642112 0.7143912 -0.5239412 -0.4642421 0.7141182 -0.5550635 -0.4259698 0.7144608 -0.5552278 -0.4259034 0.7143728 -0.5840206 -0.3861038 0.7140334 -0.5841823 -0.3860945 0.7139063 -0.6190657 -0.3272379 0.7139139 -0.6190882 -0.3272344 0.7138959 -0.6481639 -0.265052 0.7138845 -0.6479219 -0.2651134 0.7140814 -0.6642301 -0.2199187 0.7144467 -0.6640756 -0.2200688 0.7145441 -0.6779442 -0.1741619 0.7141844 -0.6777225 -0.1742531 0.7143724 -0.6915424 -0.1069329 0.7143771 -0.6913965 -0.1070103 0.7145066 -0.6985781 -0.03848993 0.7144979 -0.923601 -0.04792439 0.3803479 -0.9230113 -0.2373382 0.3028543 -0.9229403 -0.2370878 0.3032666 -0.9416924 -0.1457542 0.3032676 -0.9416483 -0.1455817 0.3034875 -0.9415972 -0.1457441 0.3035679 -0.9496659 -0.07635337 0.3038172 -0.9883495 -0.05243223 0.1428852 0.03069877 0.4720036 -0.881062 0.8104575 0.008408546 -0.5857371 -0.780217 0.4462506 -0.4383171 0.8970963 0.1782455 -0.4042852 0.9249893 0.09123086 -0.3688791 0.9247701 0.09534555 -0.3683877 0.888638 0.2103676 -0.4075145 0.8901702 0.1979103 -0.4104005 0.8893626 0.1765037 -0.421759 0.89244 0.1685321 -0.4185066 0.8951759 0.1605637 -0.4157875 0.8951603 0.160611 -0.415803 0.8976359 0.1524119 -0.413546 0.899766 0.1442682 -0.4118348 0.9016185 0.1359254 -0.4106194 0.9031429 0.1276085 -0.4099377 0.9043806 0.1190761 -0.4097763 0.9052811 0.1106792 -0.4101415 0.897511 0.1706848 -0.4066212 0.9211582 0.1125925 -0.3725458 0.9234135 0.1040505 -0.3694334 0.8656991 0.2869294 -0.4101669 0.8656973 0.2869331 -0.410168 0.885122 0.230865 -0.4040549 0.8851281 0.2308366 -0.4040578 0.8793198 0.2949659 -0.3738875 0.8491134 0.3512715 -0.3944802 0.8195772 0.329531 -0.4687244 0.818236 0.2804631 -0.501827 0.8368988 0.4086933 -0.364102 0.2014476 0.8542509 -0.4792434 0.2014675 0.8542445 -0.4792463 -0.7548792 0.4370422 -0.4890313 -0.7663622 0.4619682 -0.4464017 -0.7725408 0.4838102 -0.411228 -0.8278723 0.3301526 -0.4534608 -0.8278717 0.3301546 -0.4534605 -0.7988612 0.3910616 -0.4570467 -0.8404262 0.2745981 -0.4672042 -0.874162 0.1152164 -0.4717689 -0.8730812 0.1237673 -0.4716045 -0.8716598 0.1321953 -0.4719465 -0.8689972 0.1446747 -0.4731945 -0.8594213 0.1983497 -0.4712243 -0.8653442 0.156977 -0.4759596 -0.8625547 0.1650779 -0.4782768 -0.8625948 0.1649706 -0.4782413 -0.8599475 0.1857922 -0.4753647 -0.8586788 0.2067506 -0.4689615 -0.8558302 0.2272622 -0.4646575 -0.8558287 0.2272693 -0.4646567 -0.8512603 0.09725141 -0.515653 -0.86018 0.1339783 -0.4920775 -0.8652149 0.1826769 -0.4669395 -0.8775407 0.1399783 -0.4586158 -0.9001727 0.09536457 -0.4249643 -0.8997201 0.1003285 -0.4247796 -0.8970828 0.1089605 -0.4282172 -0.8925623 0.1173816 -0.4353779 -0.7435972 0.04583835 -0.6670548 -0.7627885 0.05928534 -0.6439246 -0.7732475 0.07034516 -0.6301903 -0.7831547 0.08222168 -0.6163671 -0.7916079 0.1005024 -0.6027074 -0.8002268 0.1269201 -0.5861129 -0.8017106 0.1397427 -0.5811473 -0.8283862 0.10728 -0.5497885 -0.8512331 0.09725153 -0.5156979 0.8235657 0.09517085 -0.55918 0.8833722 0.09369999 -0.45921 0.8833735 0.09369999 -0.4592077 0.8399476 0.1419602 -0.5237703 0.8392075 0.1780235 -0.5138467 0.8325953 0.1235436 -0.5399279 0.8123596 0.08241534 -0.5773038 0.8007218 0.07339704 -0.5945231 0.7713475 0.06435579 -0.633152 0.7597427 0.4453614 -0.4737554 0.7608152 0.4784843 -0.438421 0.7608154 0.4784844 -0.4384205 0.6855992 0.4472734 -0.5743694 0.6915695 0.4950873 -0.5259469 0.6915722 0.4950874 -0.5259434 0.5980327 0.4498398 -0.6633257 0.6075643 0.4929577 -0.6227828 0.6075586 0.4929576 -0.6227884 0.4988827 0.4530438 -0.7388283 0.5103035 0.4901877 -0.7066161 0.5103045 0.4901877 -0.7066155 0.3902288 0.4568735 -0.7993673 0.4017387 0.4867718 -0.775667 0.4017441 0.486772 -0.7756642 0.2743467 0.4613184 -0.8437531 0.2840522 0.4826971 -0.828443 0.2840553 0.4826973 -0.8284419 0.03099113 0.4725062 -0.8807823 0.03100508 0.4725067 -0.8807815 0.1536672 0.4663642 -0.8711434 0.1596286 0.4779473 -0.8637621 0.1596278 0.4779473 -0.8637623 -0.2122802 0.4819652 -0.8500862 -0.2283116 0.459475 -0.8583452 -0.09855753 0.4774971 -0.8730882 -0.09204578 0.4773184 -0.8738963 -0.0992195 0.4663556 -0.8790153 0.03102225 0.4719942 -0.8810557 -0.4365483 0.4893113 -0.7549835 -0.4723931 0.4434205 -0.7617238 -0.3462984 0.4864425 -0.8021541 -0.3278112 0.4859598 -0.8101747 -0.3535892 0.4518361 -0.8190353 -0.2251756 0.4823067 -0.8465672 -0.6259502 0.4941409 -0.6033334 -0.6805185 0.4241216 -0.5975078 -0.5623643 0.4927414 -0.6640424 -0.5365248 0.4920384 -0.6855943 -0.5821726 0.4341922 -0.6874243 -0.4594612 0.489914 -0.7408642 -0.7741826 0.4598757 -0.4349204 -0.7294182 0.4964806 -0.4705914 -0.7032095 0.4956339 -0.5097485 -0.7652146 0.4131793 -0.4936896 -0.6529591 0.4949249 -0.573318 -0.798875 0.3910385 -0.4570422 -0.8015541 0.3886458 -0.4543846 -0.7461811 0.3881257 -0.5408995 -0.7461821 0.3881247 -0.5408989 -0.6635506 0.3881246 -0.6395779 -0.6635527 0.3881226 -0.6395771 -0.5679769 0.3881229 -0.7257843 -0.5679763 0.3881235 -0.7257844 -0.4613245 0.3881238 -0.7978343 -0.4613255 0.3881229 -0.7978342 -0.3456758 0.3881233 -0.8543234 -0.3456746 0.3881244 -0.8543235 -0.2232837 0.3881244 -0.8941498 -0.2232835 0.3881247 -0.8941497 -0.0965358 0.3881251 -0.9165368 -0.09653705 0.3881239 -0.9165373 0.03209173 0.3881243 -0.9210482 0.03209203 0.3881246 -0.9210481 0.1600956 0.3881241 -0.9075952 0.160097 0.3881255 -0.9075943 0.2849765 0.3881257 -0.8764399 0.2849752 0.3881241 -0.876441 0.4042996 0.3881242 -0.8281918 0.4042999 0.3881247 -0.8281913 0.5157383 0.3881248 -0.7637888 0.5157376 0.3881236 -0.7637898 0.6171141 0.3881235 -0.6844928 0.6171148 0.3881249 -0.6844913 0.7064571 0.388125 -0.5918423 0.7064569 0.3881241 -0.5918433 0.7820214 0.3881241 -0.4876496 0.7820218 0.3881256 -0.487648 0.8006349 0.3887839 -0.4558846 0.8182351 0.2804664 -0.5018265 -0.840421 0.2746087 -0.4672071 -0.8351784 0.2820283 -0.472162 -0.7768806 0.281632 -0.5631518 -0.7768796 0.2816331 -0.5631525 -0.6908501 0.2816331 -0.6658896 -0.690849 0.2816343 -0.6658902 -0.5913424 0.281634 -0.7556431 -0.5913434 0.281633 -0.7556428 -0.4803033 0.2816328 -0.8306574 -0.4803035 0.2816326 -0.8306574 -0.3598974 0.2816325 -0.88947 -0.3598968 0.2816331 -0.8894701 -0.2324695 0.2816328 -0.9309355 -0.2324697 0.2816326 -0.9309355 -0.1005074 0.2816323 -0.9542439 -0.1005073 0.2816324 -0.9542439 0.03341269 0.2816326 -0.9589405 0.03341203 0.2816319 -0.9589406 0.1666816 0.2816323 -0.9449341 0.166682 0.2816328 -0.9449339 0.2967022 0.2816329 -0.9124971 0.2967009 0.2816313 -0.9124979 0.4209315 0.2816311 -0.8622649 0.4209325 0.2816327 -0.8622637 0.5369557 0.2816326 -0.7952116 0.536956 0.281633 -0.7952114 0.6425026 0.281633 -0.7126522 0.6425022 0.2816322 -0.7126529 0.7355215 0.2816323 -0.6161912 0.7355214 0.2816321 -0.6161912 0.8141933 0.281632 -0.5077134 0.8141937 0.281634 -0.5077115 0.8696426 0.2819225 -0.4052672 0.8491206 0.351258 -0.3944767 -0.8594309 0.1730674 -0.4810676 -0.859408 0.1731202 -0.4810895 -0.7974617 0.1728959 -0.5780673 -0.7974596 0.1728993 -0.5780694 -0.7091494 0.1728991 -0.6835299 -0.7091506 0.1728975 -0.6835289 -0.6070088 0.1728976 -0.7756588 -0.6070069 0.1729001 -0.7756599 -0.4930254 0.1728999 -0.8526616 -0.4930263 0.1728988 -0.8526611 -0.3694299 0.1728989 -0.9130321 -0.369431 0.1728976 -0.9130319 -0.2386271 0.1728978 -0.9555959 -0.2386276 0.1728972 -0.9555959 -0.1031715 0.1728972 -0.9795214 -0.1031698 0.1728991 -0.9795213 0.03429836 0.1728988 -0.9843423 0.03429776 0.1728981 -0.9843424 0.1710963 0.1728976 -0.9699652 0.1710969 0.1728984 -0.9699649 0.3045603 0.1728985 -0.9366692 0.3045616 0.1729001 -0.9366685 0.4320828 0.1729004 -0.8851044 0.4320815 0.1728984 -0.8851055 0.5511794 0.1728985 -0.8162766 0.5511795 0.1728986 -0.8162764 0.6595231 0.1728987 -0.7315293 0.6595224 0.1728973 -0.7315303 0.7550039 0.1728973 -0.6325153 0.7550049 0.1728996 -0.6325136 0.8357617 0.1728998 -0.5211601 0.835761 0.1728969 -0.5211626 0.8907918 0.1731217 -0.4201414 0.8907604 0.1853148 -0.4149752 -0.7785333 0.01109158 -0.6275053 -0.7655164 0.05957382 -0.6406525 -0.7187201 0.05942881 -0.6927552 -0.7187203 0.05942833 -0.6927549 -0.6151987 0.05942803 -0.7861291 -0.6152012 0.05942434 -0.7861274 -0.4996805 0.05942469 -0.864169 -0.4996796 0.05942595 -0.8641695 -0.3744168 0.05942589 -0.9253543 -0.3744159 0.05942702 -0.9253547 -0.2418486 0.05942708 -0.9684925 -0.2418476 0.05942827 -0.9684927 -0.1045632 0.05942821 -0.9927411 -0.104564 0.05942732 -0.9927411 0.03476053 0.05942708 -0.9976272 0.03476125 0.05942803 -0.9976272 0.1734063 0.05942833 -0.9830557 0.1734054 0.0594272 -0.983056 0.3086722 0.05942738 -0.9493103 0.3086707 0.05942547 -0.9493107 0.4379137 0.05942529 -0.8970507 0.4379146 0.0594263 -0.8970504 0.5586173 0.059426 -0.827294 0.5586182 0.05942744 -0.8272932 0.6684248 0.05942761 -0.7414019 0.6684243 0.0594269 -0.7414023 0.7651948 0.0594269 -0.6410502 0.7651937 0.05942451 -0.6410519 0.7223518 0.05903488 -0.6890013 0.7290436 0.05966013 -0.6818622 -0.9865333 0 0.1635608 -0.9659109 -0.005698084 0.258812 -0.8816627 -0.002952754 0.4718708 -0.8320432 -0.002838551 0.5547035 -0.9659296 -0.003111362 0.2587862 -0.8813679 0.002294778 0.4724249 -0.7070965 -0.00460726 0.7071021 -0.6840724 -0.003852963 0.729404 -0.258799 -0.002271413 0.9659285 -0.409991 0.001597881 0.9120881 -0.7071115 -0.002715051 0.7070968 -0.6840652 -0.003853797 0.7294107 -0.7261331 -0.00385797 0.6875435 -0.2588233 0 0.9659247 -0.009521961 -0.01824909 0.9997881 -0.1346831 -0.00943619 0.9908438 -0.4108778 -0.002179145 0.9116878 -0.4243165 -0.002167224 0.9055113 -0.03351515 0.1301459 0.9909282 -0.01978898 0.1348737 0.9906651 -0.006246387 0.1381367 0.9903935 0.873883 0.04353976 0.4841827 0.6644495 0.03781437 0.7463759 0.07326388 0.002824008 0.9973087 0.6647962 -0.01654672 0.7468415 0.3800979 0.02485233 0.9246124 0.3800423 0.02485007 0.9246353 0.8746175 0.01014941 0.4847075 0.1304025 -0.006712973 0.9914383 0.1287986 0.01281315 0.9915881 0.12861 0.01299113 0.9916101 0.1285304 0.01280826 0.9916228 0.12748 0.02166402 0.9916046 0.9651392 0.163721 0.2042099 0.9739583 0.09806865 0.204421 0.9739654 0.09805035 0.2043953 0.9780727 0.04066914 0.2042544 0.9853718 0.02968478 0.1678133 0.1268749 0.02140581 0.9916878 0.1268798 0.02141737 0.9916869 0.1240456 0.03419381 0.9916872 0.1232202 0.03373891 0.9918057 0.9438145 0.2597987 0.204252 0.9438163 0.259785 0.2042611 0.9651265 0.1637321 0.2042611 0.1232102 0.0337134 0.9918078 0.1191712 0.04594779 0.99181 0.1188956 0.04611915 0.9918351 0.9437871 0.2597367 0.2044571 0.9127905 0.353564 0.2044649 0.9127641 0.3535789 0.2045571 0.8865343 0.4148753 0.2047814 0.8865103 0.4149029 0.204829 0.8564359 0.4739726 0.2046156 0.1181824 0.04557079 0.9919458 0.1146237 0.05353885 0.9919653 0.1144939 0.05361485 0.9919761 0.1144611 0.05345046 0.9919887 0.1106575 0.06121653 0.9919715 0.1109176 0.06145471 0.9919277 0.1109185 0.06146025 0.9919273 0.1042497 0.07220119 0.9919269 0.1046541 0.07265406 0.9918513 0.8564519 0.4739329 0.2046409 0.8564575 0.4739647 0.2045431 0.8045544 0.5575459 0.2045361 0.7442644 0.6357951 0.2045364 0.7442536 0.6358269 0.2044767 0.8045713 0.557541 0.2044826 0.1046535 0.07264983 0.9918516 0.0967397 0.08292567 0.9918492 0.0970866 0.08285957 0.9918208 0.09762042 0.08368694 0.991699 0.09182584 0.08981585 0.9917163 0.0919575 0.09050256 0.9916417 0.09196007 0.09048771 0.9916427 0.08603459 0.09632617 0.9916247 0.744263 0.6358697 0.2043094 0.6991981 0.6850482 0.204526 0.6992287 0.6850307 0.2044798 0.6512651 0.7308437 0.204258 0.08722651 0.09855425 0.9913015 0.08722436 0.09856486 0.9913006 0.07738214 0.1064868 0.9912984 0.07825255 0.1085973 0.9910011 0.5747387 0.7925117 0.2039622 0.5747231 0.7925358 0.2039127 0.6513762 0.7308388 0.2039211 0.07824778 0.108618 0.9909992 0.06691652 0.1159956 0.990993 0.06766504 0.1161368 0.9909256 0.06814634 0.1181833 0.9906508 0.06043994 0.1221569 0.9906688 0.5747055 0.792637 0.2035687 0.4918536 0.8465504 0.2035496 0.4919747 0.8465701 0.2031744 0.433094 0.8781022 0.2033866 0.4331667 0.8780888 0.2032896 0.3728133 0.9054145 0.2030639 0.06028264 0.123223 0.9905464 0.06026238 0.1232571 0.9905433 0.05240327 0.1269628 0.9905223 0.05270546 0.1288961 0.9902566 0.05272275 0.1288676 0.9902593 0.03984802 0.1334271 0.9902572 0.03986656 0.1337608 0.9902114 0.372835 0.9053944 0.2031134 0.3727775 0.9055007 0.2027451 0.2800745 0.9383258 0.202739 0.03987306 0.1337506 0.9902126 0.02620512 0.1370924 0.9902116 0.02624899 0.137119 0.9902067 0.02623754 0.1372252 0.9901923 0.01687508 0.1385325 0.9902141 0.0167858 0.1387031 0.9901918 0.01678848 0.1387009 0.990192 0.007441222 0.1396688 0.9901703 0.00745058 0.1396177 0.9901775 0.5145596 0.03149235 0.8568761 0.5129062 0.05152696 0.8568968 0.5127199 0.05165076 0.8570009 0.5084813 0.0861783 0.8567497 0.508092 0.08622097 0.8569764 0.4969077 0.1366338 0.8569796 0.496304 0.1366391 0.8573285 0.4800683 0.1858103 0.8573266 0.4793802 0.1857452 0.8577257 0.4652868 0.2176562 0.8579824 0.4651435 0.2176927 0.8580509 0.4496938 0.2489125 0.8577983 0.449918 0.2489647 0.8576657 0.4226033 0.2929458 0.8576651 0.4229432 0.293062 0.8574577 0.3911279 0.334365 0.8574491 0.3918337 0.3346911 0.8569995 0.3676647 0.3604649 0.8572559 0.3680668 0.3605009 0.8570683 0.3428207 0.3851706 0.8568066 0.3441554 0.3860206 0.8558885 0.3033607 0.4188548 0.8558813 0.304476 0.4197343 0.8550541 0.2602518 0.4485247 0.8550406 0.2614166 0.4496567 0.8540903 0.2295996 0.4662305 0.8543495 0.2302609 0.4665319 0.854007 0.1980116 0.4815745 0.8537431 0.1987766 0.4825477 0.8530157 0.1492323 0.5000939 0.8530157 0.1493427 0.5002676 0.8528946 0.09811294 0.5127904 0.8528891 0.09814363 0.512852 0.8528486 0.06294053 0.5179184 0.8531114 0.0629794 0.5179557 0.8530859 0.02779465 0.5214528 0.8528274 0.02780181 0.5214737 0.8528143 0.8143978 0.0410431 0.5788539 0.8112333 0.08160376 0.5790004 0.8111431 0.08169472 0.5791139 0.8040692 0.1363582 0.5786876 0.8039019 0.1363986 0.5789104 0.7861741 0.2163068 0.5789142 0.7859407 0.2163388 0.579219 0.7601644 0.2943765 0.579217 0.7598847 0.2943856 0.5795794 0.7378295 0.3452332 0.5800186 0.7377495 0.3452721 0.5800974 0.7129498 0.3945722 0.5796682 0.713041 0.3945814 0.57955 0.6698029 0.4642094 0.5795461 0.6699559 0.4642407 0.5793442 0.619665 0.5295201 0.5793303 0.619979 0.5296191 0.5789039 0.5821537 0.5704964 0.5793367 0.5823583 0.570473 0.5791541 0.542448 0.6089643 0.5787165 0.5430582 0.6092507 0.5778421 0.4789752 0.6608303 0.5778288 0.4794871 0.6611367 0.5770532 0.4101688 0.7062526 0.5770346 0.4107077 0.7066568 0.5761557 0.3612644 0.7328277 0.5765862 0.3616155 0.7329074 0.5762647 0.3111388 0.7560509 0.5758296 0.3114899 0.7563956 0.5751866 0.2339534 0.7838553 0.5751839 0.2340003 0.7839116 0.5750882 0.1537488 0.8035191 0.5750812 0.1537907 0.8035818 0.5749825 0.09866815 0.8118857 0.5754184 0.09870058 0.811906 0.5753842 0.04355877 0.8170238 0.5749563 0.0435568 0.8170199 0.5749621 -0.04629021 0.9781484 0.2026895 0.0521273 0.977855 0.2026878 0.05213135 0.977858 0.2026723 0.1181683 0.9720451 0.2028903 0.118148 0.972042 0.2029173 0.1840777 0.9617844 0.2026974 0.1840587 0.9617845 0.2027136 0.1840626 0.9617809 0.2027275 0.2800761 0.9383263 0.2027336 -0.006267666 0.1381527 0.9903911 -0.04625815 0.9781026 0.2029173 -0.04622387 0.9781107 0.2028861 -0.03868001 0.816897 0.5754851 -0.03854066 0.8172699 0.5749648 -0.02470022 0.5206663 0.853403 -0.0244745 0.521632 0.8528195 -0.006703972 0.1396653 0.9901761 0.007443368 0.1396234 0.9901767 -0.1446328 0.9683953 0.2032036 -0.1445712 0.9684635 0.2029224 -0.1207576 0.8083342 0.576206 -0.1206192 0.8088677 0.5754859 -0.07688236 0.5143334 0.8541371 -0.07672446 0.5155723 0.8534042 -0.02048015 0.1363473 0.9904494 -0.0200935 0.1367815 0.9903975 -0.2463922 0.9475731 0.2034599 -0.2463412 0.9476502 0.2031626 -0.2056013 0.7905994 0.5767849 -0.2055426 0.7911003 0.5761185 -0.1306564 0.5022271 0.8548081 -0.1306586 0.5034552 0.854085 -0.03432971 0.1316127 0.9907066 -0.03398829 0.1320104 0.9906654 -0.9585511 0.2078227 0.1949092 -0.3841202 0.02319186 0.9229917 -0.3075875 4.1099e-4 0.9515197 -0.9324554 0.04120719 0.3589274 -0.9324249 0.04120594 0.3590071 -0.8008718 0.028418 0.5981612 -0.8308448 0.03686094 0.555282 -0.5578087 0.02214539 0.829674 -0.55555 0.0217269 0.8311991 -0.3075631 0.01396828 0.9514252 -0.3847261 0.01723188 0.9228699 -0.2961161 0.01870161 0.9549688 -0.1923086 0.03279912 0.9807863 -0.9728561 0.1247391 0.1949137 -0.9801734 0.03586369 0.1948689 -0.9905414 0.04194128 0.1306471 -0.1914219 0.02454441 0.9812009 -0.5514191 0.07070386 0.8312268 -0.5514197 0.07070386 0.8312264 -0.8249387 0.1057749 0.5552366 -0.8249568 0.1057732 0.5552102 -0.9728543 0.1247361 0.1949244 -0.9728489 0.1247415 0.1949476 -0.9585419 0.2078262 0.1949508 -0.8128094 0.1762292 0.5552335 -0.812826 0.176229 0.5552092 -0.5433166 0.1177966 0.8312225 -0.5433117 0.1177963 0.8312259 -0.1908218 0.04137235 0.9807525 -0.1908253 0.04137265 0.9807517 -0.4333621 0.001873791 0.9012179 -0.3540689 -0.2123796 0.9107853 -0.3540491 -0.2123797 0.9107932 -0.3006258 4.04599e-4 0.9537421 -0.3006012 0.01893109 0.953562 -0.5458977 -2.25331e-5 0.8378519 -0.4885396 0.08024901 0.8688436 -0.4899964 0.007455527 0.8716926 -0.2125663 0.001723706 0.9771451 -0.1488442 0.01112586 0.9887981 -0.8889203 0.1915716 -0.416078 -0.8088639 0.4387519 -0.3914535 -0.8088533 0.4387761 -0.3914485 -0.8190727 0.447335 -0.3591814 -0.8185204 0.4485175 -0.3589658 -0.5466345 0.8046041 -0.2319551 -0.5465397 0.8046782 -0.2319209 -0.6928246 0.6707314 -0.2647895 -0.4501407 0.8883069 -0.09101837 -0.4310916 0.8898221 -0.1495885 0.9735804 0.1277657 -0.1892544 0.9611316 -0.03813767 -0.2734439 0.8144184 0.2503459 -0.5234973 -0.01242011 0.2131987 -0.9769299 0.3339866 -2.51166e-4 -0.9425778 0.3175441 -0.09525811 -0.9434467 0.5864223 0.2997711 -0.7524933 0.7135426 0.2694494 -0.6467257 0.5431352 -0.4683991 -0.6968546 0.8143768 0.2503601 -0.5235553 -0.01240992 0.2131989 -0.97693 -0.1289686 -0.07662451 -0.9886838 -0.3393453 0.1449363 -0.929429 -0.6150131 0.04471611 -0.787248 -0.6531453 -0.0858919 -0.7523455 -0.3393688 0.1449337 -0.9294208 0.0760585 0.991907 -0.1016643 0.03564071 0.9989737 -0.02794867 0.009128272 0.997851 -0.06488382 -0.1605106 0.9851317 -0.06125289 -0.1604906 0.9851323 -0.0612964 -0.8889433 0.2356856 -0.3927241 -0.8596246 0.2370004 -0.4526327 -0.8563179 0.2605948 -0.4458812 -0.8325506 0.2562731 -0.4911045 -0.83433 0.2615499 -0.485268 -0.8111336 0.2559938 -0.5258607 -0.809113 0.274102 -0.5198118 -0.8044348 0.2757008 -0.526188 -0.7756695 0.2611598 -0.5745715 -0.7749755 0.2757749 -0.5686485 -0.7420474 0.252178 -0.6211056 -0.738735 0.2720676 -0.6166439 -0.7103851 0.239458 -0.6618254 -0.7123544 0.2508561 -0.655456 -0.684697 0.2138013 -0.6967633 -0.6818566 0.2316168 -0.6938481 -0.6609145 0.1859619 -0.7270559 -0.6638735 0.1970496 -0.7214177 -0.7899819 0.4993821 -0.3557332 -0.7601416 0.5001399 -0.414783 -0.7316027 0.560952 -0.3874151 -0.6949919 0.5549005 -0.4572435 -0.6965788 0.5685886 -0.4375899 -0.656462 0.5584986 -0.5070868 -0.629531 0.6112655 -0.4796304 -0.5712633 0.5823459 -0.5783869 -0.5590085 0.6184028 -0.5523472 -0.4926227 0.5706411 -0.6570325 -0.4700856 0.6183961 -0.6297665 -0.4078758 0.5484811 -0.7299355 -0.4110761 0.580402 -0.7029581 -0.3460825 0.4928553 -0.7983235 -0.3319534 0.5402529 -0.7732618 -0.2798262 0.4296216 -0.8585584 -0.290647 0.4681654 -0.8344732 -0.634072 0.7224848 -0.2756236 -0.600245 0.7227701 -0.3425044 -0.5270817 0.7996972 -0.2875228 -0.4813028 0.7928056 -0.3739076 -0.4790691 0.8099026 -0.3384531 -0.4268184 0.7959535 -0.4292833 -0.3611581 0.8559387 -0.3700457 -0.2842574 0.8184863 -0.4992772 -0.253097 0.8594806 -0.4441115 -0.1630733 0.7936975 -0.5860471 -0.1150619 0.8459296 -0.5207339 -0.02574574 0.749488 -0.6615172 -0.03064298 0.7955749 -0.60508 0.0618205 0.6678127 -0.7417578 0.08432471 0.7313344 -0.6767861 0.1667097 0.5692078 -0.8051151 0.1430601 0.6419309 -0.7532984 -0.4378659 0.8863224 -0.1506853 -0.3929167 0.8872209 -0.2417756 -0.2651748 0.9513227 -0.1570587 -0.214558 0.9439523 -0.2508363 -0.2070813 0.957917 -0.1987771 -0.1486334 0.9417051 -0.3018272 -0.04168593 0.9773983 -0.2072558 0.04386413 0.9359319 -0.3494389 0.09237068 0.9606822 -0.2618347 0.1925368 0.8862836 -0.4212254 0.2588448 0.9140141 -0.3123743 0.3628109 0.8042196 -0.4707431 0.3529082 0.8534711 -0.3834615 0.4571159 0.7055033 -0.5415812 0.4780269 0.7638008 -0.4337036 0.5787511 0.5743597 -0.5789285 0.542931 0.6722756 -0.5032607 0.8623738 0.466205 -0.1973938 0.8214306 0.5526003 -0.1410123 0.8626564 0.452413 -0.2261556 0.768652 0.6324943 -0.09552472 0.7625315 0.60225 -0.2363061 0.6636573 0.7434694 -0.08253639 0.6834261 0.7039321 -0.1934124 0.5829888 0.8113203 -0.04339933 0.5173024 0.8345695 -0.1894514 0.4213248 0.9062365 -0.03493702 0.3662174 0.9182562 -0.1506335 0.2831348 0.9589856 -0.01346868 0.3167158 0.9458401 -0.07125777 0.1107443 0.9909625 -0.07569104 0.08755528 0.9955672 -0.0343514 0.8842108 0.4393788 -0.1584854 0.8842577 0.4392617 -0.1585475 0.9170447 0.328992 -0.2253736 0.6250166 0.5573428 -0.5465558 0.6276391 0.4563048 -0.6307576 0.2251541 0.5439475 -0.8083482 0.2190251 0.4584554 -0.8613052 -0.2299639 0.3971922 -0.8884564 -0.2388545 0.348371 -0.9064139 -0.6408082 0.165145 -0.7497279 -0.643563 0.1504549 -0.7504599 0.9330024 0.300306 -0.1982997 0.9493179 0.1977405 -0.244324 0.6876287 0.3908762 -0.611868 0.7039889 0.2720364 -0.6560457 0.2797906 0.385424 -0.8792983 0.2898707 0.2955673 -0.9102829 -0.1939367 0.2726095 -0.942376 -0.1920377 0.2328192 -0.9533713 -0.6264912 0.1103251 -0.771581 -0.6263983 0.10104 -0.772927 0.9973666 0.005166888 0.07233977 0.9826716 2.80565e-4 0.185355 0.9948804 0 -0.1010588 0.995136 0.02037513 -0.09638077 0.9951611 0.02034342 -0.09612697 0.9999665 0.002568006 0.007781147 0.8680166 0.02052623 0.4961106 0.8586252 0.09517955 0.50369 0.8586714 0.09499138 0.5036468 0.6345632 0 -0.7728709 0.6345632 0 -0.7728709 0.6078909 0.01134848 -0.7939395 0.6078883 0.01135021 -0.7939414 0.5829322 0.03408426 -0.8118055 0.5742676 0.0608657 -0.816402 0.574272 0.06083136 -0.8164014 0.9784409 1.64737e-4 -0.2065272 0.9609393 -6.41857e-4 -0.2767584 0.885581 -6.28582e-4 -0.4644847 0.9587866 0.03494447 -0.2819705 0.9102582 0.01580297 -0.4137394 0.9102876 0.01581186 -0.4136746 0.8553962 0.005469143 -0.5179452 0.8554158 0.005471706 -0.5179131 0.758943 0.004599571 -0.6511409 0.765577 0 -0.6433443 0.8055686 0.001272916 -0.5925011 0.8055866 0.00127381 -0.5924766 0.9654334 -8.14229e-5 0.2606498 0.8782464 -7.91656e-5 0.4782086 0.8784778 0 0.4777831 0.5491549 0 0.8357205 0.5491549 0 0.8357205 0.09039825 0 0.9959057 0.09039825 0 0.9959057 -0.3897015 0 0.9209412 -0.3897015 0 0.9209412 -0.7777852 0 0.6285302 -0.7777852 0 0.6285302 -0.9822265 0 0.1876994 -0.9822265 0 0.1876994 -0.9547417 0 -0.2974364 -0.9547417 0 -0.2974364 -0.7018321 0 -0.7123425 -0.7018321 0 -0.7123425 -0.7714626 0.1874461 0.6080375 0.126294 0.8199869 0.5582753 -0.1442235 0.9895392 -0.003431737 -0.1442236 0.9895392 -0.003437101 -0.501464 0.8651766 -0.001829683 -0.4701947 0.8820537 0.02997142 -0.4983715 0.8669233 0.008349001 -0.1477906 0.9887644 -0.02243101 0.05930227 0.99824 -4.47463e-4 0.05933213 0.9982382 -4.47019e-4 0.3402377 0.9402014 -0.01611763 -0.06637889 0.9976216 0.01857399 -0.1714597 0.9851911 3.99502e-4 -0.2266337 0.97398 -4.16456e-4 -0.4422028 0.8968384 -0.01173126 -0.913336 0.3791376 -0.1485658 -0.8687452 0.4924492 -0.05268371 -0.8192253 0.5730004 -0.02325153 -0.7514799 0.6597468 -0.003445684 -0.5014545 0.8651829 -0.001357614 -0.6392294 0.7649947 -0.07854229 -0.5536277 0.8318408 -0.03920578 -0.9846727 0.1744048 -0.001643359 -0.9915487 0.09931594 -0.08347213 -0.9811505 0.1896577 -0.03706294 0.2033601 0.3063486 0.9299436 0.2033616 0.3063182 0.9299533 0.2116956 0.147321 0.9661685 0.3618305 0.277462 0.8899963 0.2801949 0.07603883 0.9569269 0.1714282 0.9632889 0.2066081 0.02423399 0.9858252 0.1660159 0.005015552 0.9931919 0.1163813 -0.02359533 0.9882564 0.150972 -0.02894699 0.9881296 0.1508701 -0.02055585 0.9910992 0.1315281 -0.02055925 0.9910994 0.1315271 -0.05402076 0.9919404 0.1146119 -0.07880538 0.9869719 0.1402721 -0.07880765 0.986972 0.1402708 -0.07510972 0.9928559 0.09271234 -0.1177888 0.9882855 0.09704512 -0.1184138 0.9882662 0.09647846 -0.1159358 0.9886484 0.09556794 -0.1443105 0.9895027 0.007670938 -0.1233674 0.9919385 0.02895689 -0.1143319 0.9928819 0.03337252 -0.1469682 0.9874582 0.05767738 -0.1415387 0.9874353 0.07027369 -0.1035879 0.9937905 0.04062157 -0.1159602 0.9886489 0.09553325 -0.1478945 0.9889932 0.004424929 -0.2829923 0.9590314 0.01319515 -0.2810503 0.9592145 0.03030514 -0.1502521 0.9885562 0.01345193 -0.1443106 0.9895027 0.00767076 -0.7671806 0.1876088 0.6133816 -0.7700405 0.196916 0.6068456 -0.7700284 0.1969159 0.6068611 -0.8913505 0.1374869 0.4319627 -0.8845927 0.07178246 0.460807 0.2088977 0.154273 0.9656923 0.06710553 0.1871187 0.9800426 0.03837996 0.1865171 0.9817018 0.06798052 0.099976 0.9926648 -0.2227466 0.1874209 0.9566909 -0.1932423 0.1286074 0.9726858 -0.07128369 0.1803982 0.9810072 -0.07127636 0.1803982 0.9810077 -0.2227228 0.1874207 0.9566964 -0.3770552 0.1604937 0.9121792 -0.4316703 0.11386 0.8948166 -0.5221697 0.2251792 0.8225771 -0.6223254 0.222781 0.7503864 -0.5356917 0.02848386 0.8439331 -0.6642256 0.1607884 0.7300352 -0.9890454 0.1049969 0.1037532 -0.9819244 0.1691236 0.08498072 -0.9852176 0.1705279 0.01632243 -0.9951238 0.09543079 0.02492958 -0.9846726 0.1744047 -0.001644551 0.1707332 0.5960228 0.7846062 0.2032353 0.5290124 0.8239183 0.03446185 0.526165 0.849684 0.03316003 0.5286628 0.8481839 -0.1637488 0.5251138 0.8351298 -0.1654396 0.5283678 0.8327409 -0.3671678 0.5246825 0.768047 -0.3688884 0.5283879 0.7646749 -0.5403427 0.5250163 0.6575619 -0.541695 0.5290967 0.653164 -0.6621956 0.5263067 0.5333838 -0.6627182 0.5291991 0.5298611 -0.7650353 0.5241665 0.3741264 -0.7634813 0.529339 0.3699953 -0.8163025 0.5271276 0.236192 -0.8153632 0.5292243 0.2347432 -0.845126 0.5270182 0.08952009 -0.8435406 0.5297253 0.08848941 -0.8486002 0.5288438 0.01421624 -0.8480315 0.5297596 0.01404964 -0.84824 0.5296081 -0.002041459 -0.9622019 0.2723269 -0.002367138 -0.9158502 0.2023251 0.3468183 -0.9158405 0.2023253 0.3468437 -0.9559015 0.1025428 0.2752041 -0.9555525 0.2211548 0.1949614 -0.9555576 0.2211547 0.1949368 -0.4831277 0.8755406 0.00403583 -0.5016446 0.8649355 0.01546728 -0.4985659 0.8652416 0.05281066 -0.5010105 0.8637534 0.05402314 -0.4820757 0.8649548 0.1394856 -0.4836099 0.8638257 0.1411616 -0.4507685 0.8649935 0.22044 -0.453608 0.8622748 0.2252154 -0.3908855 0.8649152 0.3148496 -0.3910474 0.8634643 0.3186085 -0.3187445 0.8648365 0.3878914 -0.3182544 0.8627808 0.3928402 -0.2168433 0.8644245 0.4535959 -0.2157225 0.8625487 0.4576827 -0.09673506 0.864432 0.4933555 -0.09527832 0.8627427 0.4965853 0.02036041 0.8646269 0.5020017 0.02173078 0.8632881 0.5042433 0.0798037 0.8652528 0.4949435 0.00904566 0.9855958 0.1688759 0.03257429 0.9742391 0.2231528 -0.9516407 0.1653871 -0.2588961 -0.04302209 0.2655553 -0.9631352 0.7659609 0.01918923 -0.6426008 0.6454923 0.7533823 -0.1255186 0.5372439 0.8372153 -0.1021746 0.5375669 0.8369963 -0.1022694 0.7464123 0.6310852 -0.2111878 0.882357 0.3610098 -0.3018578 0.7435832 0.6290021 -0.226805 0.9306346 0.1430497 -0.3368323 0.872523 0.356907 -0.3336486 0.8725167 0.356926 -0.3336445 0.2868565 0.1085379 -0.9518051 0.2867517 0.1085483 -0.9518355 -0.8369008 0.2761948 -0.4725607 -0.8368877 0.2762 -0.4725805 -0.9455618 -0.09812498 -0.3102973 -0.9773908 0.1194414 -0.1744733 0.30305 0.9529741 0.00106126 0.3169435 0.9483851 -0.01060783 0.2752654 0.9553888 -0.107057 0.9110699 0.2214311 -0.3477351 0.8911297 0.2253515 -0.3938332 0.8835533 0.2495142 -0.3963286 0.08642941 0.9962338 -0.006936073 0.08643919 0.9962329 -0.006946742 0.02338081 0.9902626 -0.1372347 -0.1482051 0.9887049 -0.02231609 -0.1481764 0.9887076 -0.02238351 -0.1891279 0.9769956 -0.09854072 -0.4026373 0.9094201 -0.1041064 -0.4033005 0.9089944 -0.1052511 -0.6366259 0.7669993 -0.08012264 -0.580068 0.7815901 -0.2294299 -0.5337284 0.8330305 -0.1455826 -0.636622 0.7669994 -0.08015364 -0.6801989 0.7187882 -0.143782 -0.7652749 0.6096506 -0.2065925 -0.7537096 0.6299493 -0.1873119 -0.8575124 0.4694505 -0.2104492 -0.8702557 0.4350432 -0.2310684 -0.9059041 0.3140561 -0.2840887 -0.8921465 0.4089072 -0.1920145 -0.9304389 0.2813155 -0.2348294 0.5306327 0.8401029 -0.1124986 0.5062604 0.8454357 -0.1701145 0.3441078 0.9247322 -0.1626666 0.3172207 0.9227995 -0.2186596 0.1458265 0.9645537 -0.2199336 0.1153287 0.9537554 -0.2775787 -0.05600768 0.9558128 -0.2885914 -0.07695341 0.942402 -0.32551 -0.1874525 0.912468 -0.3636808 -0.2049087 0.896275 -0.3933236 -0.3514016 0.8350347 -0.4233601 -0.36374 0.8192298 -0.443346 -0.4429072 0.7417698 -0.5035978 -0.4476954 0.733527 -0.5113774 -0.5571766 0.6199542 -0.5524592 -0.5881513 0.5409693 -0.6011908 -0.6641697 0.3991708 -0.6320928 -0.6715175 0.3686456 -0.6427788 -0.6987134 0.2365461 -0.6751633 -0.6931897 -0.1502758 -0.7049152 -0.651278 0.1517165 -0.7435181 0.7116445 0.6739529 -0.1983676 0.6824803 0.6802072 -0.2674673 0.5869085 0.7649274 -0.265376 0.5534248 0.762389 -0.3353865 0.4469575 0.8263239 -0.3426629 0.4081144 0.8123617 -0.4165466 0.2953488 0.8510082 -0.4342282 0.2644705 0.8306759 -0.4899314 0.1880293 0.8305618 -0.5242253 0.1589002 0.8036648 -0.5734751 0.05255013 0.7915088 -0.6088944 0.02781528 0.7585036 -0.6510749 -0.03025096 0.7138411 -0.6996539 -0.04770374 0.6844265 -0.7275196 -0.1338658 0.6215456 -0.7718555 -0.1735184 0.5202379 -0.8362081 -0.2385299 0.4239665 -0.8737025 -0.2514157 0.3651161 -0.8963707 -0.2731519 0.2686151 -0.9237067 -0.2871609 0.1699111 -0.9426923 -0.3621566 -0.2366442 -0.9015775 0.8415088 0.4630938 -0.278221 0.8137316 0.4687971 -0.3436135 0.7724187 0.532575 -0.3460248 0.7388399 0.5298683 -0.4163593 0.6901991 0.5844802 -0.4266239 0.6524197 0.5706443 -0.4987119 0.5978027 0.6122969 -0.5174209 0.5671885 0.5913382 -0.5732508 0.5279831 0.6023321 -0.5986902 0.4980129 0.5748159 -0.6492841 0.4418101 0.5852258 -0.6799373 0.416196 0.5490852 -0.7247664 0.3850389 0.5304923 -0.7551974 0.3625772 0.4932148 -0.7907445 0.314889 0.4713411 -0.8238219 0.2760877 0.369097 -0.8874362 0.2393887 0.3294098 -0.9133358 0.2258004 0.2544919 -0.9403446 0.2160948 0.2149336 -0.9524215 0.2224059 0.2556974 -0.9408265 -0.0415169 -0.366297 -0.9295714 0.8523727 0.2468165 -0.4610233 0.8509684 0.2630873 -0.4545744 0.8460068 0.2690011 -0.4603381 0.8177193 0.2584789 -0.5143188 0.8056744 0.276672 -0.5237761 0.7841607 0.2615673 -0.5627384 0.7744652 0.2678871 -0.573097 0.7548274 0.2498686 -0.6064662 0.7408975 0.2578359 -0.6201545 0.7250403 0.2349418 -0.6473941 0.7166942 0.231077 -0.6579915 0.7025451 0.2076597 -0.6806672 0.69002 0.2050839 -0.6941276 0.6694063 0.1504141 -0.72751 0.6598751 0.1430236 -0.7376375 0.6526399 0.1019375 -0.7507796 0.6503733 0.0934782 -0.7538411 0.6392823 0.03083932 -0.7683535 0.5884301 -0.05169922 -0.8068936 0.9807839 0 0.195097 0.9807839 0 0.195097 0.8314787 0 0.5555567 0.8314787 0 0.5555567 0.2185466 0 -0.9758266 0.3600446 0.005804777 -0.9329171 0.329344 0.008069634 -0.9441756 0.806056 0.001621663 -0.5918371 0.70794 0.006755709 -0.7062402 0.6062274 0.01907265 -0.7950626 0.7388184 0.001276969 -0.6739034 0.4743636 -6.96851e-4 -0.8803288 0.4742135 -6.96851e-4 -0.8804096 0.9996044 -2.56098e-4 -0.02812427 0.9856352 7.44372e-4 -0.1688863 0.9528988 0.006576299 -0.3032172 0.9529356 0.006568849 -0.3031014 0.9620066 0.004436016 -0.2729898 0.880877 -0.001347124 -0.4733431 0.8808999 -0.001347124 -0.4733009 0.8808709 0.2475973 0.4034378 0.952747 0.004347085 0.3037341 0.9821478 -0.06199848 0.1776006 0.9853909 -0.002781331 0.1702848 0.9853432 0.04242199 0.165225 0.9826614 -2.50011e-4 0.1854094 0.9952729 0.007082581 0.09685856 0.982268 0.05277436 0.1799008 0.9875271 0.02815127 0.154912 0.874339 0.1465759 0.4626521 0.945297 -3.65969e-4 0.3262109 0.8931945 -3.69294e-4 0.4496703 0.7963901 0.003451406 0.6047735 0.7547476 0 0.6560152 -0.5345062 0 -0.8451645 -0.5345062 0 -0.8451645 0.508584 0.6947503 -0.5085906 0.508583 0.6947594 -0.508579 0.1861552 0.6947551 -0.6947386 0.1861546 0.694754 -0.6947397 -0.186155 0.694754 -0.6947398 -0.1861575 0.6947516 -0.6947414 -0.5085919 0.694749 -0.5085845 -0.5085896 0.6947508 -0.5085843 -0.6947387 0.6947531 -0.1861622 -0.6947468 0.694746 -0.1861583 -0.6947458 0.6947451 0.1861649 -0.6947401 0.6947533 0.1861565 -0.5085902 0.6947538 0.5085794 -0.5085908 0.6947481 0.5085868 -0.1861547 0.6947493 0.6947444 -0.1861562 0.6947522 0.6947412 0.1861543 0.6947523 0.6947414 0.1861536 0.6947531 0.694741 0.5085799 0.6947589 0.5085832 0.5085863 0.6947537 0.5085836 0.6947367 0.694755 0.1861625 0.694746 0.6947469 0.1861581 0.6947452 0.694746 -0.1861639 0.6947401 0.6947532 -0.1861565 0.07439267 0.6465265 0.7592557 0.3822774 0.6673104 0.6391878 0.3821789 0.6673101 0.639247 0.5024625 0.7036042 0.5024665 0.3482922 0.8097117 0.4722918 0.5025369 0.7336641 0.4573769 0.2000256 0.6346006 0.7465063 0.07096058 0.8387056 0.5399422 0.2341821 0.7416372 0.6285961 -0.4456196 0.7108291 0.5441922 -0.4645916 0.7538602 0.4645961 -0.5534896 0.713472 0.4296591 -0.4455758 0.710815 0.5442465 -0.2529197 0.6920227 0.6761186 -0.1887727 0.6841292 0.7045084 -0.2333318 0.8497346 0.4727658 -0.09375685 0.7366358 0.6697592 0.5734834 0.7114826 0.4060903 0.6036248 0.7070072 0.3684806 0.6947421 0.6947526 0.1861516 0.6947481 0.6947473 0.1861487 0.6947476 0.6947469 -0.1861522 0.6947433 0.6947527 -0.186146 0.5085849 0.6947556 -0.5085824 0.5085858 0.6947467 -0.5085937 0.1861538 0.6947457 -0.6947484 0.1861573 0.6947519 -0.694741 -0.1861525 0.6947526 -0.6947417 -0.186159 0.6947464 -0.6947463 -0.5085912 0.6947457 -0.5085896 -0.5085808 0.694754 -0.5085887 -0.6947423 0.6947525 -0.1861507 -0.6947348 0.6947591 -0.1861544 -0.6947354 0.6947597 0.1861498 -0.6947406 0.6947525 0.1861574 -0.6036284 0.7070065 0.3684759 0.5085833 0.6947538 -0.5085865 0.5085826 0.6947606 -0.508578 0.1861558 0.6947569 -0.6947365 0.1861525 0.6947509 -0.6947433 -0.1861575 0.6947503 -0.6947427 -0.1861547 0.6947529 -0.6947408 -0.5085924 0.69475 -0.5085825 -0.5085874 0.694754 -0.5085821 -0.6947377 0.6947538 -0.1861632 -0.6947476 0.6947451 -0.1861585 -0.6947467 0.6947442 0.1861652 -0.6947408 0.6947524 0.1861567 -0.5085903 0.6947531 0.5085803 -0.5085908 0.6947492 0.5085854 -0.1861572 0.6947515 0.6947416 -0.1861557 0.6947489 0.6947447 0.186158 0.6947485 0.6947443 0.1861517 0.6947545 0.69474 0.508579 0.6947602 0.5085823 0.5085876 0.6947534 0.508583 0.6947378 0.694754 0.186162 0.694746 0.6947469 0.1861581 0.6947451 0.694746 -0.1861644 0.6947396 0.6947537 -0.1861563 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.2588105 0 -0.9659281 -0.2588105 0 -0.9659281 -0.7071133 0 -0.7071003 -0.7071133 0 -0.7071003 -0.9659252 0 -0.2588216 -0.9659252 0 -0.2588216 -0.9807884 0 0.1950744 -0.9807884 0 0.1950744 -0.8314771 0 0.5555589 -0.8314771 0 0.5555589 -0.5555595 0 0.8314768 -0.5555595 0 0.8314768 -0.1950815 0 0.980787 -0.1950815 0 0.980787 0.5805209 -0.8110796 0.07173091 0.3269104 -0.93989 0.09867173 0.4101839 -0.9119417 0.01054865 0.6439169 -0.7645293 0.02942997 0.6574273 -0.7531591 0.02325785 0.572505 -0.8194945 0.02582514 0.4101861 -0.9119409 0.01054888 0.4922801 -0.869085 0.04849392 0.463697 -0.8853224 0.03448539 0.4926903 -0.8700441 0.01671695 0.5724841 -0.8195093 0.02581417 0.3219611 -0.9460631 0.03613179 0.3105498 -0.9426369 0.1224515 0.311885 -0.942542 0.1197593 0.3316608 -0.9382142 0.09876888 0.3113347 -0.9447163 0.1028677 0.3268543 -0.9399893 0.09790927 0.3986374 -0.9099741 0.1141726 0.5003015 -0.8579167 0.1169506 0.4948235 -0.8611809 0.1162643 0.4896745 -0.8642532 0.1152622 0.4587888 -0.8818727 0.1086896 0.4650666 -0.878829 0.1066429 0.3986371 -0.9099743 0.1141725 0.6457306 -0.7553982 0.1113807 0.621654 -0.7759284 0.1071521 0.5791445 -0.8091566 0.09928309 0.6051803 -0.7933234 0.06629425 0.6051541 -0.7933406 0.06632643 0.6053125 -0.7932349 0.06614404 0.5880648 -0.8042934 0.08539348 0.5882033 -0.8042057 0.08526486 0.5880774 -0.8042865 0.08537048 0.5733509 -0.8135803 0.09672552 0.5738114 -0.8132972 0.09637486 0.5737217 -0.8133526 0.09644162 0.5614911 -0.8208212 0.1047869 0.5615457 -0.8207877 0.1047571 0.5477709 -0.8292262 0.111045 0.5434502 -0.8318272 0.1128063 0.5357593 -0.8364349 0.1154924 0.5357348 -0.8364499 0.1154978 0.5253049 -0.8428149 0.1171236 0.5167283 -0.8480073 0.1177941 0.5064931 -0.8541864 0.1176024 0.5064707 -0.8541998 0.1176013 0.6630563 -0.7448999 0.07403117 0.6630559 -0.7448995 0.07403779 0.6542958 -0.7522343 0.07772111 0.656836 -0.7467008 0.1049003 0.6563105 -0.7461005 0.1122082 0.643118 -0.7588496 0.1026967 0.645116 -0.7544271 0.1210994 0.6706101 -0.7322748 0.1185563 0.6915065 -0.7013147 0.1731373 0.3219395 -0.9460709 0.03612142 0.3192496 -0.9470618 0.03396159 0.3192287 -0.946996 0.03594136 0.3192271 -0.9469979 0.03590357 0.3269116 -0.9398935 0.09863525 0.335666 -0.9400976 0.05953919 0.4604537 -0.8850728 0.06803303 0.462975 -0.8839437 0.06555712 0.582545 -0.8093891 0.07436943 0.5837724 -0.8110945 0.03654259 0.644054 -0.764658 0.0221948 -0.4427186 0.5425805 -0.7138674 -0.3329379 0.5425803 -0.7712062 -0.2159221 0.5425812 -0.8117778 -0.09422439 0.5425804 -0.8347026 0.02955847 0.54258 -0.8394839 -0.5831117 0.6307541 -0.5119864 0.1410183 0.6307528 -0.7630627 0.4543135 0.6307544 -0.6290852 -0.6804354 0.6132486 -0.4011656 0.6999533 0.5676768 -0.4333687 0.7182918 0.557717 -0.4159429 0.6695324 0.5512235 -0.4978746 0.7207821 0.5535047 -0.4172598 0.7183455 0.577054 -0.3885723 0.6703501 0.6313231 -0.389951 0.6768456 0.601881 -0.423815 -0.680438 0.6132445 -0.4011673 -0.6804295 0.6132531 -0.4011688 -0.6588443 0.6302719 -0.4107086 -0.6692827 0.6080579 -0.4269968 -0.6692803 0.6080617 -0.4269952 -0.7505255 0.5201331 -0.4076433 -0.7662289 0.4965248 -0.4078682 0.6593759 0.5913636 -0.4642332 0.6164391 0.6845145 -0.3891562 0.580973 0.6835554 -0.44184 0.427331 0.6835594 -0.591722 0.1326428 0.6835582 -0.7177424 -0.1876208 0.6835585 -0.7053695 0.5418736 0.6307553 -0.5554465 0.509691 0.683559 -0.5224577 0.5096911 0.6835589 -0.5224579 0.251683 0.6307535 -0.7340338 0.2367351 0.683558 -0.6904382 0.236735 0.6835575 -0.6904386 -0.08703678 0.6307533 -0.7710867 -0.08186745 0.6835589 -0.7252897 -0.08186727 0.6835592 -0.7252894 0.7316426 0.5549194 -0.3959338 0.7268045 0.5431057 -0.4204658 0.6686176 0.5425794 -0.5084863 0.5809711 0.683559 -0.4418368 0.6176548 0.6307546 -0.4697353 0.6176549 0.6307555 -0.469734 0.6686144 0.5425806 -0.5084892 0.6686143 0.5425805 -0.5084892 0.5865751 0.5425803 -0.6012789 0.5865807 0.5425788 -0.6012749 0.5418734 0.6307544 -0.5554476 0.4543134 0.6307542 -0.6290855 0.4273313 0.6835576 -0.5917236 0.335682 0.6835578 -0.6481253 0.5865811 0.5425794 -0.601274 0.4917963 0.5425795 -0.6809874 0.4917962 0.5425795 -0.6809874 0.4917957 0.5425789 -0.6809884 0.3863258 0.5425794 -0.7458955 0.335682 0.683557 -0.6481261 0.356877 0.6307541 -0.6890487 0.3568767 0.6307537 -0.6890493 0.3863201 0.5425801 -0.7458978 0.3863203 0.5425804 -0.7458976 0.2724492 0.5425805 -0.7945929 0.2724471 0.5425807 -0.7945935 0.2516827 0.6307532 -0.7340342 0.1410187 0.6307532 -0.7630624 0.1326431 0.6835594 -0.7177412 0.02566653 0.6835594 -0.7294434 0.2724463 0.54258 -0.7945942 0.1526523 0.5425801 -0.826017 0.1526526 0.54258 -0.826017 0.152653 0.5425804 -0.8260166 0.02955126 0.5425811 -0.8394835 0.02566611 0.6835583 -0.7294446 0.02728676 0.630753 -0.7755038 0.02728766 0.6307536 -0.7755032 0.02953892 0.5425809 -0.839484 0.02953803 0.5425802 -0.8394845 -0.09421771 0.5425808 -0.834703 -0.09421753 0.5425806 -0.8347032 -0.08703672 0.6307534 -0.7710867 -0.1994689 0.6307537 -0.749908 -0.1876227 0.6835554 -0.7053722 -0.2892994 0.6835541 -0.6701192 -0.2159252 0.5425801 -0.8117778 -0.215926 0.5425809 -0.8117771 -0.1994693 0.6307533 -0.7499081 -0.3075637 0.6307533 -0.7124288 -0.2892972 0.6835572 -0.670117 -0.3846854 0.6835563 -0.6202966 -0.3329401 0.5425815 -0.7712045 -0.3329386 0.5425802 -0.771206 -0.3075639 0.6307531 -0.7124289 -0.4089738 0.6307535 -0.6594623 -0.3846841 0.6835579 -0.6202957 -0.471711 0.6835576 -0.5569899 -0.4427157 0.5425803 -0.7138695 -0.4427163 0.5425809 -0.7138685 -0.4089755 0.6307522 -0.6594623 -0.5014945 0.6307522 -0.5921613 -0.4717059 0.6835634 -0.5569872 -0.5484749 0.6835641 -0.4815761 -0.5428688 0.5425804 -0.6410148 -0.5428686 0.5425802 -0.6410151 -0.5014948 0.630752 -0.5921613 -0.5831152 0.6307517 -0.5119855 -0.5484851 0.6835533 -0.4815796 -0.6033657 0.6840878 -0.4098458 -0.6046274 0.6821428 -0.4112262 -0.7505273 0.5201323 -0.4076411 -0.5172275 0.5221488 -0.6781125 -0.6997991 0.5535746 -0.4514824 -0.6291211 0.5877007 -0.5087383 -0.6958915 0.5605049 -0.4489648 -0.7166333 0.5418214 -0.4391655 -0.6312183 0.5425806 -0.554229 -0.6312205 0.5425799 -0.5542272 -0.6312217 0.5425814 -0.5542243 -0.5428649 0.5425812 -0.6410176 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 0.7071038 1.78969e-6 -0.7071098 0.707107 2.43214e-6 -0.7071065 0.707106 9.26525e-7 -0.7071077 0.7071024 -2.06492e-6 -0.7071111 0.707106 0 -0.7071076 0.7070996 6.09128e-6 -0.7071141 0.7071043 -1.91188e-7 -0.7071092 0.7071059 -4.13058e-7 -0.7071076 0.7071059 -3.34784e-7 -0.7071076 0.7071193 6.59491e-6 -0.7070944 0.7072937 0 -0.7069198 0.7071192 6.59949e-6 -0.7070944 0.7071093 0 -0.7071042 0.7071093 0 -0.7071042 0.9113382 -0.4116563 0.001350462 0.9564174 -0.2919962 0.002001225 0.9564037 -0.2920408 0.00200051 0.9771192 -0.2126479 0.004353702 0.9920595 -0.1255552 0.007338821 0.889637 -0.4564725 -0.01337093 0.9996322 -0.02610367 0.007360816 0.9875404 -0.1573656 0 0.8265269 -0.5628766 0.004845023 0.8610659 -0.5084417 0.007254302 0.8610768 -0.5084231 0.007255315 0.9113878 -0.4115466 0.001350462 0.8897185 -0.4565047 0.002125978 0.7037437 -0.7104298 -0.005862772 0.7321446 -0.6811492 0 0.732353 -0.6809252 -5.20377e-5 0.7321859 -0.681105 -5.20218e-5 0.7037765 -0.710421 6.63867e-4 0.4731586 -0.880977 -6.93171e-4 0.4480912 -0.8939878 1.94971e-4 0.4731673 -0.8809726 1.93972e-4 0.4480679 -0.8939995 4.41157e-4 0.16356 -0.9865332 -4.59784e-4 0.1527124 -0.9882706 0 0.4726544 -0.8800176 -0.04654937 0.367128 -0.8800225 -0.3012927 0.7302892 -0.6793407 -0.07192838 0.5672236 -0.6793776 -0.4655142 0.7302485 -0.6793851 -0.07192265 0.7302653 -0.6793684 -0.07191115 0.7021993 -0.679369 -0.2130115 0.7022033 -0.6793659 -0.2130083 0.6471538 -0.6793658 -0.3459103 0.6471528 -0.6793665 -0.3459109 0.5672261 -0.6793658 -0.4655283 0.5672569 -0.6793366 -0.4655334 0.4726458 -0.8800221 -0.0465523 0.4726508 -0.8800196 -0.04654806 0.4544868 -0.8800199 -0.1378653 0.4544861 -0.8800201 -0.1378658 0.418856 -0.8800203 -0.2238835 0.4188516 -0.880022 -0.2238855 0.3671282 -0.8800217 -0.3012951 0.3671417 -0.880014 -0.3013011 0.1635388 -0.9864054 -0.01610612 0.1635378 -0.9864056 -0.01610732 0.1572532 -0.9864056 -0.04770183 0.1572512 -0.9864059 -0.04770338 0.1449236 -0.9864057 -0.07746493 0.1449255 -0.9864056 -0.07746398 0.1270287 -0.9864056 -0.1042483 0.1270284 -0.9864057 -0.1042484 0.5917149 -0.5273287 -0.6097524 0.5915835 -0.5277141 -0.6095464 0.5177094 -0.6811415 -0.5177094 0.5116724 -0.6828049 -0.5215064 0.6935198 -0.1950855 -0.6935214 0.674499 -0.02725762 -0.7377724 0.6838399 -0.104925 -0.7220483 0.6847527 -0.2037243 -0.6997215 0.6847482 -0.2037805 -0.6997095 0.6726089 -0.3051432 -0.674155 0.6573872 -0.3682658 -0.6574363 0.6394728 -0.4270769 -0.6392809 0.588029 -0.5555777 -0.5878394 0.6087083 -0.4667224 -0.6415951 0.6087139 -0.4666948 -0.6416099 0.1156534 -0.9865337 -0.1156533 0.1348585 -0.9807786 -0.1410197 0.3370676 -0.8809641 -0.3320959 0.3370569 -0.8809722 -0.3320851 0.3878746 -0.8314452 -0.3978093 0.521497 -0.6810913 -0.5139607 0.5400585 -0.651729 -0.5325281 0.4785967 -0.6978889 -0.5328192 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.6749608 -0.004487216 -0.7378399 0.7071053 -0.003031432 -0.7071018 0.5164094 0.001327633 -0.8563409 0.5159734 0.0013206 -0.8566036 0.5159705 0.0013206 -0.8566053 -0.4760411 -0.01072603 -0.8793577 -0.2588148 -0.001833021 -0.9659253 -0.4778566 0.001292467 -0.8784368 -0.4778559 0.001292467 -0.8784373 -0.1492784 5.86267e-4 -0.9887951 -0.1494088 5.8621e-4 -0.9887753 0.2588146 5.38015e-4 -0.965927 -0.1441603 -0.01963877 -0.9893595 0.2055013 -0.003462016 -0.9786508 -0.7319426 -0.003120839 -0.6813592 -0.7071062 -0.002203166 -0.707104 -0.7319433 -0.001266419 -0.6813644 -0.9968173 0.001199722 -0.07971107 -0.9127637 -0.007307529 -0.4084224 -0.9659268 -0.001186728 -0.2588126 -0.9121806 8.83384e-4 -0.4097875 -0.9121305 8.83384e-4 -0.4098991 -0.9614233 -0.001294195 0.27507 -0.9613997 -0.001293003 0.2751522 -0.9659253 -0.002002358 0.2588133 -0.9968143 0.001199364 -0.07974785 -0.9967738 0.001199364 -0.08025228 -0.7070994 -0.003317594 0.7071063 -0.8153485 7.60413e-4 0.5789702 -0.815334 7.60413e-4 0.5789903 -0.2588192 -0.001454055 0.9659247 -0.5870791 8.72699e-4 0.8095291 -0.5871011 8.72699e-4 0.8095133 0.2588188 -9.21954e-4 0.9659255 -0.2077383 8.72145e-4 0.9781841 -0.2077421 8.72145e-4 0.9781832 0.7071039 2.70479e-4 0.7071096 0.9585373 -0.02378094 0.283973 0.7071128 -3.23822e-4 0.7071007 0.2839801 3.07123e-4 0.9588301 0.2841071 3.07123e-4 0.9587925 0.809511 8.73075e-4 -0.5871042 0.8095108 8.73075e-4 -0.5871042 0.9659265 -0.001454055 -0.2588124 0.9781854 8.72218e-4 -0.2077323 0.965927 7.77222e-4 0.2588139 0.9779446 -0.02204161 -0.2076983 0.9587898 3.07903e-4 0.2841161 -0.9987333 6.68416e-4 -0.05031394 -0.09820115 -0.01109212 0.9951047 -0.258817 3.90004e-4 0.9659263 -0.07578772 3.98243e-4 0.9971239 0.5998523 -0.001109063 0.8001101 0.4550989 0.00151807 0.8904396 0.2588173 0.001481175 0.9659251 0.4314593 -0.01341611 0.9020327 0.1739407 -6.89047e-4 0.9847559 0.9627177 -0.005041599 0.2704611 0.9243775 -0.001517832 0.381476 0.8599143 0.001200675 0.510437 0.707104 0.001163244 0.7071086 0.8474051 -0.01954323 0.5305871 0.7085034 -0.004567384 0.7056927 0.9600226 -0.004515528 -0.279886 0.9927412 -0.01472252 -0.1193656 0.9659212 -0.001991629 -0.2588282 0.9995782 4.30866e-4 0.02903962 0.9659228 4.19331e-4 0.2588299 0.9992862 -0.02203893 0.03067994 0.9892107 -0.01312083 0.1459107 0.5265527 4.58085e-4 -0.8501424 0.6993936 -0.003526329 -0.7147279 0.7992229 -0.01394867 -0.600873 0.7070986 -0.003195047 -0.7071079 0.8826044 0.00110656 -0.4701152 0.8826214 0.00110656 -0.4700831 0.526524 4.58085e-4 -0.8501601 0.2588193 -0.001884579 -0.9659239 0.3011837 -0.005085408 -0.9535526 -0.2199668 -0.005787789 -0.9754902 -0.1863711 -0.007274925 -0.9824525 -0.2588173 -0.003801465 -0.9659188 0.002202451 0.001752018 -0.999996 0.002212941 0.001752018 -0.999996 -0.6884496 -0.003599882 -0.7252752 -0.6884272 -0.003600895 -0.7252965 -0.5612912 -0.01222091 -0.8275281 -0.7071115 -0.001102209 -0.7071012 -0.3908824 6.422e-4 -0.9204404 -0.3908635 6.422e-4 -0.9204484 -0.9987308 6.68416e-4 -0.05036121 -0.9618892 -0.003727316 -0.273414 -0.9659187 -0.00305283 -0.2588276 -0.8646112 0.001129269 -0.5024403 -0.8645887 0.001129269 -0.5024792 -0.275336 -0.003296077 0.9613424 -0.5078877 0.001772999 0.8614215 -0.7071132 0.001716732 0.7070983 -0.5215861 -0.01323354 0.853096 -0.7582503 -6.27812e-4 0.6519633 -0.7582927 -6.25651e-4 0.651914 -0.9096923 4.06798e-4 0.4152829 -0.9659228 4.00764e-4 0.2588298 -0.9114955 -0.009379982 0.4112034 -0.9829818 -0.001183629 0.1836991 0.9997499 0.00169593 0.02229875 0.2263236 -0.003267526 0.9740467 0.2588209 -0.001858651 0.9659236 0.7325119 -8.99575e-4 0.6807535 0.732412 -9.00693e-4 0.6808612 0.7071026 -0.002327203 0.7071073 0.4841475 8.98543e-4 0.874986 0.4841508 8.98543e-4 0.8749841 0.9996048 0.00169593 0.02805906 0.9997499 0.001696109 0.02229845 0.9659183 -0.003186285 0.2588275 0.9248506 6.97707e-4 0.38033 0.9247986 6.97706e-4 0.3804564 0.7071039 0.001262068 -0.7071085 0.5076721 -0.01132649 -0.8614759 0.7699189 2.38262e-4 -0.6381416 0.7699612 2.38764e-4 -0.6380907 0.965923 2.1717e-4 -0.2588294 0.7700824 -0.02075618 -0.6376066 0.9435183 -0.004063546 -0.3312955 0.2588209 -0.001858651 -0.9659236 0.2263195 -0.003267705 -0.9740477 0.5074729 0.001303672 -0.8616667 -0.2588205 -0.002575695 -0.965922 -0.1482029 0.001649975 -0.9889556 -0.1482002 0.001649975 -0.988956 -0.7071104 -0.003054976 -0.7070966 -0.5832841 0.00224781 -0.812265 -0.5832819 0.00224781 -0.8122666 -0.9659175 -0.00329411 -0.2588291 -0.8897429 0.002607047 -0.4564545 -0.8897502 0.002607047 -0.4564403 -0.9659177 -0.003294169 0.2588285 -0.9999963 0.002727687 0 -0.9999963 0.002727687 0 -0.7071104 -0.003054976 0.7070966 -0.8897502 0.002607047 0.4564403 -0.8897421 0.002607047 0.4564562 -0.1481868 0.001649856 0.9889581 -0.148209 0.001649856 0.9889547 -0.2588205 -0.002575576 0.965922 -0.5832762 0.00224781 0.8122708 -0.5832841 0.00224781 0.812265 -0.7400895 1.19902e-5 -0.6725084 -0.7400677 -9.29121e-7 -0.6725324 -0.7377416 -3.07502e-4 -0.6750831 -0.7400647 2.12161e-6 -0.6725357 -0.7400605 1.53963e-4 -0.6725403 -0.7400971 6.71592e-5 -0.6725001 -0.7400471 -1.0416e-5 -0.672555 -0.7400686 9.84852e-6 -0.6725314 -0.7400507 -1.51116e-5 -0.672551 -0.7400621 -9.64465e-6 -0.6725385 -0.7402723 1.49162e-4 -0.6723073 -0.740036 5.6593e-4 -0.6725671 -0.7399505 6.51719e-4 -0.6726609 -0.7400959 3.17809e-4 -0.6725013 -0.7401086 2.33889e-5 -0.6724873 -0.7401041 3.14452e-5 -0.6724923 -0.7400811 3.81187e-5 -0.6725177 -0.7400839 -2.4271e-5 -0.6725144 -0.740065 2.02168e-5 -0.6725355 -0.7400535 1.04309e-4 -0.6725479 -0.7401022 1.05795e-4 -0.6724944 -0.7400519 2.88918e-4 -0.6725498 -0.7400518 2.89072e-4 -0.6725498 -0.7400929 2.18028e-4 -0.6725046 -0.7401434 2.0462e-5 -0.6724491 -0.7400684 3.21585e-5 -0.6725316 -0.740126 -5.84734e-5 -0.6724683 -0.7399041 1.93118e-4 -0.6727124 -0.7401149 8.00352e-5 -0.6724807 -0.7401369 4.99325e-5 -0.6724563 -0.740081 5.34952e-5 -0.6725178 -0.7401006 -3.5088e-5 -0.6724963 -0.7400382 4.66642e-5 -0.6725648 -0.7400655 4.88166e-6 -0.6725349 0.04966801 -0.9708527 -0.2344743 -0.2785401 -0.8134742 -0.5105634 0.3964856 -0.5121743 -0.7618903 0.1179305 -0.7002037 -0.7041357 0.1253668 -0.6971742 -0.705855 -0.08955556 -0.7943704 -0.6007958 -0.08954536 -0.7943673 -0.6008014 -0.2698705 -0.937346 -0.2203462 0.04354262 -0.937627 -0.3449052 0.04357075 -0.9376241 -0.3449096 -0.1753643 -0.948418 -0.2641037 0.2531301 -0.7968873 -0.5485399 0.2531692 -0.7968646 -0.5485547 0.7299298 -0.2146391 -0.6489474 0.7297209 -0.1613485 -0.6644352 0.6752353 -0.1880416 -0.7132304 0.4481818 -0.4557563 -0.7690379 0.488923 -0.4941536 -0.7188647 -0.1512624 -0.8891453 -0.4319034 -0.058007 -0.9209815 -0.3852638 -0.05802994 -0.9209681 -0.3852924 -0.1286063 -0.8260672 -0.5487017 -0.3084553 -0.8253462 -0.4729261 -0.128405 -0.8258934 -0.5490104 -0.1284016 -0.8258967 -0.5490061 0.5805495 -0.5509129 -0.5995475 0.7374444 -0.1932607 -0.6471678 0.7312933 -0.2152144 -0.6472194 0.7359766 -0.1939812 -0.6486212 0.7361059 -0.1933748 -0.6486558 0.3329009 -0.8223636 -0.4614057 0.04356676 -0.9376225 -0.3449144 -0.08820825 -0.9837642 -0.1562924 0.3267254 -0.8265385 -0.4583499 0.0520935 -0.9759423 -0.2117141 0.06178277 -0.9733505 -0.2208432 0.7043521 -0.2131489 -0.6770936 0.7043477 -0.2131459 -0.6770992 0.7178094 -0.1468474 -0.6805772 0.6720217 -0.2155162 -0.708477 0.6628394 -0.2067934 -0.7196391 0.7193597 -0.1288325 -0.6825861 0.6776934 -0.168468 -0.7157863 -0.2624348 -0.9000144 -0.3479973 -0.215852 -0.8904148 -0.4007109 0.1825329 -0.7505838 -0.6350635 0.1825847 -0.7505465 -0.6350928 0.4889276 -0.4941493 -0.7188646 0.5353959 -0.5246459 -0.6618898 0.5354138 -0.5246177 -0.6618974 0.5841684 -0.5442401 -0.6021212 0.5801084 -0.5517174 -0.5992347 0.7508986 -0.3802421 0.5399698 -0.1484007 -0.7505438 -0.6439421 -0.6658067 -0.134136 -0.733968 -0.6236168 -0.1805364 -0.7605976 -0.6307699 -0.2007024 -0.7495652 -0.6187176 -0.2181375 -0.7547215 -0.4410113 -0.4211675 -0.7925446 -0.2863838 -0.5702432 -0.7699396 -0.05084556 -0.7128362 -0.6994851 0.1955782 -0.8189976 -0.5394369 0.3096694 -0.8236377 -0.4751061 0.1431383 -0.8006215 -0.5818219 0.05445981 -0.9026219 -0.4269752 0.05446672 -0.9026179 -0.4269828 0.2098923 -0.8828064 -0.4202358 0.2098124 -0.8827359 -0.4204237 0.1955543 -0.8190202 -0.539411 0.270188 -0.8889644 -0.3697845 0.2245789 -0.8890558 -0.3989288 -0.1483445 -0.7505857 -0.6439061 -0.09192955 -0.7013133 -0.7069008 0.1524631 -0.7698818 -0.6197072 -0.6567623 -0.1750943 -0.7334885 -0.6567643 -0.1750962 -0.7334861 -0.6817804 -0.1439991 -0.7172446 -0.6919294 -0.2426862 -0.6799538 -0.7028787 -0.1754764 -0.6893253 -0.6921734 -0.1942185 -0.6951082 -0.684113 -0.2414689 -0.6882457 -0.5541109 -0.545269 -0.6290016 -0.4992995 -0.5246049 -0.6895575 -0.1487492 -0.923545 -0.3534663 0.03590512 -0.9918822 -0.121986 0.03604608 -0.9918794 -0.1219666 0.2328985 -0.972358 -0.01667696 -0.06609666 -0.9537516 -0.2932388 -0.008528888 -0.933857 -0.357545 -0.008631765 -0.933842 -0.3575817 -0.4623406 -0.6615 -0.5904734 -0.462246 -0.6616174 -0.5904158 -0.3059046 -0.8278234 -0.4702455 -0.141305 -0.9215223 -0.3617036 -0.1411947 -0.9215736 -0.3616158 -0.6725143 -0.1735749 -0.7194415 -0.6724779 -0.1735525 -0.7194811 -0.688234 -0.1749415 -0.7040807 -0.6950364 -0.1503265 -0.7030835 -0.6921657 -0.1942155 -0.6951165 -0.009551167 -0.9336588 -0.3580361 0.2074977 -0.9488555 -0.2379456 -0.2234532 -0.7968946 -0.5612732 -0.2235093 -0.7968614 -0.561298 -0.4992699 -0.5246526 -0.6895428 -0.4498217 -0.494154 -0.7439571 -0.4498378 -0.4941386 -0.7439575 -0.4124293 -0.4610478 -0.785708 -0.2926797 -0.5433781 -0.7868156 0.7749351 6.63202e-6 -0.6320407 0.7749237 -7.28863e-6 -0.6320548 0.7749124 -2.42492e-5 -0.6320686 0.7749345 -1.08962e-5 -0.6320416 0.7751249 2.10209e-4 -0.631808 0.7749322 2.05238e-4 -0.6320443 0.7749211 -1.14889e-6 -0.6320579 0.7749828 1.01136e-5 -0.6319823 0.7749709 8.41918e-6 -0.6319969 0.7749657 6.71077e-5 -0.6320033 0.7749348 7.24169e-5 -0.6320413 0.7749355 6.57791e-5 -0.6320404 0.7749562 9.7623e-5 -0.6320149 0.7749624 1.02759e-4 -0.6320075 0.7749497 9.80131e-5 -0.632023 0.7750264 2.59334e-4 -0.6319289 0.7751092 7.67205e-5 -0.6318273 0.7749785 3.8188e-4 -0.6319876 0.7748205 1.4446e-4 -0.6321813 0.7749375 9.15292e-5 -0.6320379 0.7748257 5.86973e-5 -0.6321749 0.7749611 8.40746e-5 -0.6320091 0.7749428 3.58824e-5 -0.6320314 0.7749704 4.85278e-5 -0.6319976 0.7749707 4.76448e-5 -0.6319973 0.774945 9.31026e-5 -0.6320286 0.7749451 9.30068e-5 -0.6320285 0.7749553 6.04776e-5 -0.6320161 0.7749358 5.12779e-5 -0.6320401 0.7749317 4.99521e-5 -0.6320449 0.3925132 -0.7983322 -0.4567266 0.3925134 -0.7983353 -0.4567209 0.5201916 -0.7479449 -0.4122852 0.5725288 -0.8195288 -0.02415329 0.1484277 -0.9875747 -0.05162793 0.1347898 -0.9897973 -0.04618394 0.2121565 -0.9759782 -0.04955887 0.1349038 -0.9907006 -0.01769959 0.07254648 -0.9960412 -0.05136877 0.2611943 -0.9627256 -0.07026344 0.2297395 -0.9724107 -0.04046088 0.2297211 -0.9724151 -0.04046106 0.4923723 -0.8694827 -0.0396136 0.4924731 -0.8694257 -0.03961092 0.4090281 -0.9093723 -0.07575041 0.3219852 -0.9462057 -0.03194129 0.322007 -0.9461984 -0.03194093 0.6422897 -0.7625635 -0.07720643 0.6429638 -0.7633981 -0.06181573 0.6357389 -0.7689293 -0.06770473 0.635715 -0.7695005 -0.06111764 0.6110913 -0.7817865 -0.1240048 0.6272005 -0.7565028 -0.1852648 0.607465 -0.7291182 -0.3152348 0.6074441 -0.7291328 -0.3152411 0.6078711 -0.7623256 -0.2221536 0.5414415 -0.7923898 -0.2809973 0.6272004 -0.7565011 -0.1852717 0.4079865 -0.8501199 -0.3329312 0.4570415 -0.8157866 -0.3544085 0.5127046 -0.7874636 -0.3421039 0.5128359 -0.7450657 -0.4264698 0.49541 -0.7920175 -0.3567591 0.3927581 -0.8829154 -0.2572964 0.3975511 -0.888341 -0.22979 0.3975529 -0.8883262 -0.2298442 0.1483835 -0.9828754 -0.1092627 0.2654277 -0.9559584 -0.1252672 0.2610907 -0.9571321 -0.125419 0.2622227 -0.9564253 -0.128413 0.2919099 -0.9446371 -0.1498315 0.2853485 -0.9316752 -0.2248502 0.2853484 -0.9316698 -0.2248728 0.3709609 -0.8924584 -0.2567219 0.390938 -0.8845434 -0.2544609 0.3908678 -0.9090825 -0.1441921 0.3908718 -0.9090816 -0.1441868 0.3913474 -0.9185461 -0.05585902 0.4098047 -0.9110931 -0.04438066 0.4834997 -0.7869935 -0.3832354 0.5138122 -0.7899513 -0.334625 0.5136095 -0.8237584 -0.2400571 0.5136101 -0.8237583 -0.240056 0.5136101 -0.8474308 -0.1344085 0.5136044 -0.8474329 -0.1344174 0.5143135 -0.8549499 -0.06739777 0.5725079 -0.8195434 -0.02415394 -0.09879291 -0.9882242 -0.1168456 0.2595773 -0.8339956 -0.4868993 0.2595288 -0.8340337 -0.4868599 0.01417821 -0.9898487 -0.1414165 0.1101875 -0.9842679 -0.1381137 0.1102538 -0.9842619 -0.1381033 0.02959817 -0.9815245 -0.1890335 0.0115469 -0.983871 -0.1785064 0.02636158 -0.9855075 -0.1675713 0.06559431 -0.9865399 -0.1497882 -0.02549225 -0.9870333 -0.1584789 -0.07459908 -0.9863702 -0.1466591 -0.07472145 -0.9863644 -0.1466353 0.1494488 -0.9628778 -0.2247917 0.149447 -0.962866 -0.2248439 0.1494457 -0.9628672 -0.2248396 0.09272623 -0.9847835 -0.1469802 0.01429563 -0.9898468 -0.1414176 0.2269839 -0.9311765 -0.285287 0.2738288 -0.8891637 -0.3666141 0.3927113 -0.7477149 -0.535444 0.3477758 -0.8389465 -0.4185938 0.3477336 -0.8389675 -0.4185869 0.2254454 -0.8848552 -0.4076834 0.2670031 -0.8725119 -0.4091851 0.2586739 -0.8452938 -0.4675108 0.3927171 -0.7477146 -0.5354402 0.3927122 -0.7477168 -0.5354406 0.1325124 -0.851618 -0.5071363 0.2172575 -0.8210037 -0.5279697 0.2172582 -0.8210036 -0.5279697 0.01003628 -0.8555685 -0.5175923 0.08068716 -0.8368767 -0.5414121 0.08068728 -0.8368767 -0.5414121 -0.1866621 -0.8253422 -0.532886 -0.1866618 -0.8253424 -0.532886 -0.1122655 -0.8528038 -0.5100217 -0.05146908 -0.8381161 -0.5430583 -0.0514689 -0.8381161 -0.5430583 -0.313552 -0.8522166 -0.4188221 -0.3135585 -0.8522135 -0.4188237 -0.2802129 -0.859103 -0.4282788 -0.2290585 -0.816499 -0.5299639 -0.3455001 -0.7757349 -0.5280769 -0.3540053 -0.7952212 -0.4922434 -0.3159658 -0.816663 -0.4829359 -0.3132995 -0.852309 -0.4188231 -0.2451543 -0.873874 -0.4198138 -0.2157784 -0.8975475 -0.3845102 -0.1948539 -0.9393216 -0.282324 -0.1948319 -0.9393338 -0.2822986 -0.1949878 -0.9392938 -0.2823239 -0.1251758 -0.9509032 -0.2830439 -0.09010535 -0.9653182 -0.2450343 0.2485391 -0.8873894 -0.3882889 0.2689898 -0.8733412 -0.406103 0.1404984 -0.9029418 -0.4061481 0.1404865 -0.9029485 -0.4061373 0.01071876 -0.9137494 -0.4061369 0.01072728 -0.9137461 -0.4061442 -0.1192673 -0.9059922 -0.4061447 -0.1192637 -0.9059913 -0.4061476 -0.2443738 -0.8804952 -0.4062138 -0.2496247 -0.8996417 -0.3582351 0.2269749 -0.9311809 -0.2852799 0.08467084 -0.9560313 -0.2807755 0.147472 -0.9478456 -0.2825608 0.1404905 -0.9512575 -0.2745388 0.01128852 -0.9615476 -0.2744063 0.01128494 -0.9615486 -0.274403 -0.1239486 -0.9535848 -0.2744319 -0.1274617 -0.9809932 -0.1463071 -0.09227323 -0.9790711 -0.1813982 -0.6401638 -0.7653598 -0.06644421 -0.1620928 -0.9864605 -0.0249297 -0.2041696 -0.9782847 -0.03568977 -0.259319 -0.9630749 -0.07239103 -0.2041583 -0.9782871 -0.03568989 -0.1623513 -0.9853255 -0.05268412 -0.1060023 -0.993433 -0.04306161 -0.1461901 -0.9885216 -0.03812444 -0.1061054 -0.9942564 0.01398992 -0.4160426 -0.8685877 -0.2691915 -0.2980198 -0.918474 -0.25998 -0.2725312 -0.9484438 -0.1618059 -0.2724577 -0.94926 -0.1570739 -0.2755657 -0.9480054 -0.1592144 -0.2592468 -0.9574328 -0.1269389 -0.1673631 -0.9768809 -0.133016 -0.167411 -0.9768729 -0.1330149 -0.4231384 -0.8249414 -0.3747338 -0.4249934 -0.8238148 -0.375113 -0.4249436 -0.8246818 -0.3732597 -0.4386369 -0.7685685 -0.4657254 -0.4855853 -0.7648118 -0.4234029 -0.5045691 -0.7383708 -0.4474578 -0.504756 -0.7426371 -0.4401267 -0.5009272 -0.7876776 -0.3586584 -0.5397627 -0.7851163 -0.3037244 -0.6021712 -0.7228937 -0.3388432 -0.5903611 -0.7721255 -0.2351515 -0.626915 -0.7531324 -0.1994221 -0.5664626 -0.8236744 -0.02609157 -0.6269152 -0.7531339 -0.1994159 -0.6093711 -0.7822461 -0.1294522 -0.6371181 -0.7679238 -0.06613236 -0.6371303 -0.7674968 -0.0708065 -0.6401522 -0.7653695 -0.06644433 -0.4853735 -0.8694372 -0.09215027 -0.4854 -0.8694245 -0.09212875 -0.5665262 -0.8236297 -0.02611815 -0.5665162 -0.8236366 -0.02611851 -0.2617956 -0.9625586 -0.07031339 -0.3194585 -0.9470118 -0.03338909 -0.3194497 -0.9470149 -0.03338921 -0.4078283 -0.911814 -0.04765796 -0.4079562 -0.9117582 -0.04763299 -0.6021714 -0.7228969 -0.3388355 -0.5125414 -0.7776211 -0.3641522 -0.5128291 -0.8212492 -0.2501122 -0.5128326 -0.8212458 -0.2501164 -0.5128329 -0.8469691 -0.1401631 -0.5128251 -0.8469756 -0.1401528 -0.5131347 -0.8573903 -0.03968268 -0.4869119 -0.872515 -0.04042744 -0.3850856 -0.8734927 -0.2978584 -0.3850845 -0.8735287 -0.2977541 -0.3860172 -0.8824722 -0.2687633 -0.3894218 -0.8797804 -0.2726482 -0.3895321 -0.9086567 -0.1503595 -0.3895287 -0.9086587 -0.1503556 -0.3901516 -0.918205 -0.06842064 -0.3194473 -0.9470156 -0.03338849 -0.6398008 -0.7611939 0.1060131 -0.6722071 -0.7329555 0.1044707 -0.8735085 -0.4848271 0.04387933 -0.8735093 -0.4848276 0.04385906 -0.8341118 -0.5433644 0.09493607 -0.752218 -0.6535329 0.08404028 -0.7853434 -0.6120477 0.09291446 -0.8196844 -0.5651165 0.09360015 -0.7911389 -0.6081354 0.0653491 -0.8143585 -0.5745417 0.08198827 -0.7188037 -0.6875228 0.1031203 -0.6764842 -0.7314244 0.08595073 -0.7107291 -0.6965216 0.09859925 -0.7818762 -0.6155967 0.09854167 -0.7177148 -0.6928533 0.0695669 -0.7522241 -0.6535257 0.08404266 -0.4896988 -0.8656499 0.1041417 -0.4848005 -0.8685951 0.1025238 -0.5402613 -0.834729 0.1065139 -0.5402376 -0.8347444 0.1065144 -0.5720599 -0.8135783 0.1041048 -0.5424542 -0.8348247 0.09386819 -0.5863342 -0.8028799 0.1076854 -0.4013533 -0.9103518 0.1008723 -0.4018011 -0.9101589 0.1008298 -0.4029818 -0.9096496 0.1007139 -0.4014779 -0.9103693 0.1002153 -0.4844732 -0.8685272 0.1046239 -0.2626501 -0.9647625 0.01575648 -0.2626196 -0.9647709 0.0157532 -0.3199028 -0.9472271 0.02057033 -0.2868683 -0.957944 0.007059872 -0.3198435 -0.9474692 0.001502037 -0.3198409 -0.9474701 0.001502096 -0.3948947 -0.9186915 0.008008122 -0.4081012 -0.9129356 0.001396358 -0.4874572 -0.8731449 0.001875638 -0.4874312 -0.8731594 0.001876354 -0.4834939 -0.8753387 0.003984928 -0.4872987 -0.873225 0.004249453 -0.4082289 -0.9128785 0.001394212 -0.5666958 -0.8239263 0.001107513 -0.5687033 -0.8225407 0.001825809 -0.5666834 -0.8239322 0.002387166 -0.6477351 -0.7617099 0.01540011 -0.6477351 -0.7617098 0.01540517 -0.5666294 -0.8239693 0.00238943 -0.6421303 -0.7665907 0.002736508 -0.6418911 -0.7667901 0.002961099 -0.4898924 -0.8717051 0.01165205 -0.6417714 -0.7667788 -0.01340496 -0.6827909 -0.7291997 -0.04543602 -0.6397331 -0.7612502 0.106017 -0.6486544 -0.7540708 0.1030774 -0.6410199 -0.7451956 -0.183785 -0.7100539 -0.6791538 -0.1859394 -0.6789566 -0.7338801 0.02092641 -0.8724121 -0.4788378 0.09803754 -0.7888203 -0.6117975 0.05887705 -0.7843356 -0.6175331 0.05891054 -0.7849525 -0.6121033 0.09580755 -0.6789485 -0.7338876 0.02092653 -0.2911097 -0.953128 0.0824753 -0.2911162 -0.9531269 0.08246469 -0.2906484 -0.9517481 0.09848368 -0.3420583 -0.9364268 0.07811003 -0.3175868 -0.9421996 0.1067641 -0.7241783 -0.6807535 0.1101841 -0.6455835 -0.7614437 0.05852735 -0.5740724 -0.8164405 0.0621761 -0.567731 -0.8211344 0.05847918 -0.4914045 -0.868665 0.06279134 -0.4826828 -0.8738702 0.0580362 -0.4042416 -0.9124934 0.06280648 -0.3942525 -0.9171975 0.0575639 -0.3131918 -0.9476181 0.06269556 -0.2868379 -0.9578603 0.01508361 -0.003390729 0.01547563 -0.9998745 0.324898 0.1549791 -0.9329645 0.3147949 0.1368923 -0.9392362 0.0520789 0.0144518 -0.9985384 0.1507152 0.08633577 -0.9848001 0.1507027 0.08632892 -0.9848026 0.3249004 0.1549735 -0.9329646 0.4652794 0.1834579 -0.8659436 0.3367729 0.1239201 -0.9333959 0.3956936 0.07517409 -0.9153008 0.4004346 0.08039832 -0.9127915 0.4099728 0.08674877 -0.9079632 0.4325417 0.09845978 -0.8962218 0.4251461 0.1160051 -0.8976601 0.4250298 0.1159951 -0.8977164 0.3367719 0.1239232 -0.9333958 0.329834 0.005761384 -0.9440214 0.4197943 0.03966015 -0.9067524 0.3387063 0.01043128 -0.9408344 0.4047588 0.0399425 -0.9135507 0.421284 0.0457704 -0.9057731 0.4445924 0.0527864 -0.8941763 0.4654427 0.0599429 -0.8830457 0.4399794 0.06095582 -0.8959366 0.4213547 0.0625149 -0.9047387 0.40796 0.06468141 -0.9107058 0.3995096 0.06743997 -0.9142451 0.3954092 0.07094496 -0.9157611 0.3954183 0.07089358 -0.9157612 -0.002621173 0.002295911 -0.9999939 -0.002622127 0.002301633 -0.9999939 -0.002626121 0.002296924 -0.9999939 0.4450972 0.05292332 -0.8939171 0.4707985 0.05988007 -0.8802062 0.4232289 0.0539841 -0.9044131 -0.00934118 -3.13083e-5 -0.9999564 -0.008795559 -3.91776e-5 -0.9999613 -0.008804202 -3.98029e-5 -0.9999613 0.4743401 0.1153557 -0.8727511 0.4967831 0.1238602 -0.8589909 -0.01656907 0.001306533 -0.9998618 0.001394569 0.008563578 -0.9999624 -0.00338155 0.01545464 -0.9998748 -0.003381848 0.01547795 -0.9998745 -0.02229493 0.006072044 -0.999733 0.001398146 0.008564412 -0.9999624 0.001396834 0.008568644 -0.9999624 0.01914292 0.1354299 -0.990602 0.0191468 0.1354323 -0.9906015 0.01918035 0.1354411 -0.9905998 0.1099038 0.05959182 -0.9921543 0.1363093 0.03779846 -0.989945 0.1144101 0.04862672 -0.9922429 0.2012707 0.005801081 -0.9795185 0.1417231 0.04025018 -0.9890877 0.2006541 -0.05247449 -0.9782558 0.1568658 0.008443593 -0.9875838 0.1417763 0.02838242 -0.9894918 0.1342675 0.03309822 -0.9903922 0.1480457 0.02022445 -0.9887737 0.1342667 0.03309851 -0.9903924 0.1342662 0.03309792 -0.9903925 0.05731868 0.06807357 -0.9960324 -0.1495511 0.196606 -0.9690101 0.1149415 0.03755187 -0.9926622 0.1122214 0.03347736 -0.9931191 -0.2326009 0.2176969 -0.947895 -0.1382306 0.188079 -0.9723778 -0.09362155 0.1532216 -0.983747 -0.01685577 -0.06510394 -0.9977362 -0.01686602 -0.06508499 -0.9977371 0.03233367 0.122608 -0.9919283 0.03232336 0.1226106 -0.9919283 -0.1395384 0.2226217 -0.9648671 -0.08132356 0.1701891 -0.98205 -0.08132249 0.1701908 -0.9820498 0.1461154 -0.00349611 -0.9892614 0.05255734 0.1063214 -0.9929418 0.05113226 0.1045965 -0.9931994 0.03232192 0.1226129 -0.9919281 0.0323286 0.1226016 -0.9919294 0.04155766 0.03972268 -0.9983462 -0.2411917 0.2024903 -0.9491177 0.04432362 0.04469001 -0.998017 0.09956753 0.009311676 -0.9949873 0.06604897 0.02791947 -0.9974257 0.0645132 0.02436703 -0.9976193 0.06451386 0.02436321 -0.9976193 0.08961367 0.009926736 -0.995927 0.06470948 0.01514267 -0.9977893 0.08317124 0.005359232 -0.9965209 0.06471234 0.01514011 -0.9977891 0.06471008 0.01514458 -0.9977892 0.1243818 -0.003505706 -0.9922282 0.06930655 0.007138669 -0.9975699 0.06929022 0.007159471 -0.9975709 0.06928837 0.00714904 -0.9975711 -0.3354361 0.07180315 -0.9393225 -0.3420618 0.05170947 -0.9382537 -0.3484601 0.06742233 -0.9348956 -0.3772909 0.06502872 -0.9238089 -0.4036452 0.06399697 -0.9126746 -0.220071 0.01585304 -0.9753551 0.07948505 1.51833e-4 -0.9968361 -0.2738399 0.04998338 -0.9604756 -0.3886295 0.06415003 -0.9191582 -0.3416995 0.05160647 -0.9383913 -0.3193563 0.04492402 -0.9465692 -0.3035846 0.03934568 -0.9519917 -0.1352998 -0.03669714 -0.9901248 -0.3696177 0.04394531 -0.9281441 -0.1219959 -0.04484903 -0.9915168 -0.340374 0.08807158 -0.9361565 -0.3817895 0.1209549 -0.9163005 -0.3818221 0.1209579 -0.9162865 -0.4309222 0.1266747 -0.8934538 -0.3872067 0.1096792 -0.9154459 -0.3642112 0.09984791 -0.9259485 -0.3322243 0.07989281 -0.9398106 -0.3315288 0.07540535 -0.9404269 -0.3315247 0.075428 -0.9404265 0.06667959 0.08501553 -0.9941459 -0.1514562 0.157215 -0.9758813 -0.3047442 0.2082513 -0.9293882 -0.2295042 0.1672347 -0.9588329 -0.2295014 0.1672407 -0.9588324 -0.3124688 0.163978 -0.9356679 -0.3124699 0.1639782 -0.9356675 -0.405165 0.186554 -0.8950077 -0.2816125 0.1225842 -0.9516657 -0.2816137 0.1225799 -0.9516658 0.253597 -0.96731 2.36904e-4 0.2306773 -0.97303 -7.45366e-4 0.1818181 -0.9833316 0.001051723 0.1483049 -0.9889416 -5.03286e-4 0.1484152 -0.988925 -5.03284e-4 0.1817847 -0.9833379 -9.5899e-4 0.1483185 -0.9889391 -9.36529e-4 0.08860749 -0.9960661 9.94067e-4 0.05730515 -0.9983563 -9.55187e-4 -0.1568477 -0.9876225 7.24901e-4 -0.1757971 -0.984425 0.001719772 -0.08222055 -0.9966129 -0.00158286 -0.09861516 -0.9951257 -6.60264e-5 -0.006308853 -0.9999802 7.01352e-5 -0.0208559 -0.9997825 3.11251e-4 -0.006270825 -0.9999802 3.11367e-4 -0.02075183 -0.9997835 0.001455545 -0.02073615 -0.9997839 0.00145471 -0.3317194 -0.9433522 0.006994187 -0.2514968 -0.9678581 1.85658e-4 -0.2491455 -0.9684661 1.8566e-4 -0.2515875 -0.9678345 2.2909e-4 -0.1760833 -0.9843752 -1.43028e-4 -0.249168 -0.9684326 -0.007324218 -0.3397118 -0.9405293 6.48224e-4 -0.4133713 -0.9105623 -6.44033e-4 -0.4010894 -0.9160386 -8.13589e-4 -0.413828 -0.9103547 -8.13688e-4 -0.4011136 -0.916028 -8.25281e-4 -0.4134552 -0.9105238 -0.001170516 -0.4593069 -0.8882769 0.001119792 -0.537865 -0.8430303 0.00107491 -0.4980341 -0.8671566 -0.001222729 -0.4980314 -0.8671581 -0.001222729 -0.5378932 -0.843013 2.53134e-4 -0.5562328 -0.8310264 5.51265e-4 -0.5562561 -0.8310106 5.51264e-4 -0.665373 -0.7464819 0.00660634 -0.665435 -0.7464266 0.006614029 -0.6062079 -0.7953063 -7.32889e-5 -0.5562648 -0.831005 4.14457e-5 -0.6114054 -0.7912968 -0.005721807 -0.6552122 -0.7554432 -0.001550376 -0.6795453 -0.7336335 0 -0.6795142 -0.7336595 0.00207597 0.3244617 -0.9458986 -6.08131e-4 0.313568 -0.9495657 1.05952e-4 0.3244828 -0.9458916 1.06092e-4 0.3135483 -0.949572 6.24135e-4 0.4016298 -0.915802 -4.78174e-4 0.4126117 -0.910907 4.60798e-5 0.4016259 -0.9158036 6.59932e-4 0.475353 -0.8797951 -3.62159e-4 0.4698873 -0.8827264 0 0.8323473 -0.55187 -0.05135822 0.8284904 -0.5486324 0.1122768 0.852262 -0.5097566 0.1174644 0.8555939 -0.5038953 0.118527 0.8451836 -0.521251 0.1181615 0.8508583 -0.5127367 0.1146351 0.8520597 -0.5103265 0.1164519 0.8789174 -0.4612962 0.1212842 0.9061858 -0.4032709 0.127279 0.8784693 -0.4651332 0.1092828 0.8788322 -0.4610606 0.1227893 0.9185513 -0.3761479 0.1215575 0.9185866 -0.3760591 0.1215651 0.9088482 -0.4002126 0.1175785 0.9200758 -0.376144 0.1094362 0.9327418 -0.3358273 0.1311977 0.9581468 -0.2640955 0.1104915 0.9513822 -0.2848025 0.1173 0.9513655 -0.2848603 0.1172957 0.9565646 -0.2659565 0.1193784 0.9502068 -0.2847349 0.1266226 0.9712333 -0.2002306 0.1288934 0.9734842 -0.1916633 0.1248757 0.9735344 -0.1913985 0.1248898 0.9861811 -0.1019305 0.1306023 0.9863795 -0.1019327 0.1290938 0.9881948 -0.07236576 0.1350339 0.9862703 -0.1247403 0.1082168 0.9837322 -0.1793476 0.01026999 0.9841852 -0.1192018 0.1310361 0.9842545 -0.1211678 0.1286902 0.9132077 -0.1846514 0.3632568 -0.8576992 -0.5141519 2.21118e-5 -0.8598353 -0.5105717 1.94763e-6 -0.8598989 -0.5104603 -0.002005815 -0.8554316 -0.5178171 0.01011747 -0.8680971 -0.4959928 -0.0199638 -0.8594036 -0.5112464 0.007248401 -0.8583545 -0.5128544 0.01441645 -0.8577592 -0.5140517 2.04487e-5 -0.8484158 -0.5293304 3.61723e-4 -0.8578218 -0.5139473 -3.08397e-4 -0.8484199 -0.5293238 -4.39662e-5 -0.848161 -0.5297386 -1.76702e-5 -0.8253918 -0.5645603 4.11266e-5 -0.8351661 -0.5499977 -1.01456e-4 -0.8255421 -0.5643401 -7.24442e-4 -0.8254476 -0.5644782 -7.26091e-4 -0.825526 -0.5643635 -7.26121e-4 -0.8119104 -0.5837822 1.34334e-4 -0.8255088 -0.5643854 0.002098798 -0.7881525 -0.6154788 -0.001164793 -0.8049589 -0.5933058 0.005409002 -0.7577705 -0.6525105 -0.003737449 -0.8051087 -0.5931258 0.001336216 -0.8051913 -0.5930137 0.001348137 -0.7984002 -0.6021127 0.004161953 -0.7861481 -0.6180344 0.00215125 -0.7861097 -0.6180834 0.002148628 -0.8607141 -0.5090852 -0.001847624 -0.8603017 -0.5097839 0.001124501 -0.8603015 -0.5097826 -0.001729905 -0.8602464 -0.5098785 0 -0.8982168 -0.4395529 0 -0.8982167 -0.4395529 0 -0.7741351 -0.6330186 0.001500129 -0.7650552 -0.6439636 0.001136183 -0.7577638 -0.652528 0.001136302 -0.7646879 -0.6443974 0.002107858 -0.7245113 -0.6892597 -0.002101182 -0.7472131 -0.6645468 0.007075369 -0.688185 -0.7254792 -0.009013414 -0.7056844 -0.7085086 -0.005017817 -0.7472439 -0.6645122 0.007083475 -0.7376106 -0.6752091 0.004827797 -0.714165 -0.6999774 0 -0.7062066 -0.7079944 0.004036068 -0.7066225 -0.7075805 0.0038172 -0.7266359 -0.686986 -0.007097005 -0.736227 -0.6766049 -0.01325225 -0.7362517 -0.6765776 -0.01327157 -0.7322353 -0.6810479 -0.002332329 -0.7322632 -0.681018 -0.002330899 -0.6891797 -0.7242289 0.02289056 -0.6891861 -0.7242228 0.02288663 -0.7698454 -0.638229 0.001364946 -0.7601947 -0.6496952 -4.09027e-4 -0.7601434 -0.6497553 -4.09021e-4 -0.8289266 -0.559202 0.01318329 -0.8289002 -0.5592407 0.01319736 -0.8430034 -0.5378936 0.003985047 -0.8289346 -0.5593343 -0.003547906 -0.8289158 -0.559362 -0.003552496 -0.82891 -0.5592267 0.01318401 -0.8290266 -0.559053 0.01321411 -0.8288978 -0.5592447 0.01318812 -0.7778929 -0.6283954 -0.001390755 -0.7779002 -0.6283863 -0.001392841 -0.7695888 -0.6385338 0.002751827 -0.7945047 -0.607255 -0.001903653 -0.8031147 -0.5957912 -0.00629884 -0.8289646 -0.5592994 0.001325786 -0.8019409 -0.5973994 0.002166807 -0.8242632 -0.5661085 0.01054865 -0.8981345 -0.4383198 0.03507494 -0.8596681 -0.5107787 -0.008722305 -0.8593767 -0.5113431 1.3184e-5 -0.8565533 -0.5160585 -1.63978e-6 -0.8440174 -0.5203538 0.1298711 -0.8594564 -0.5111939 -0.003933072 -0.8592047 -0.5116292 0.001721739 -0.8592748 -0.5115143 0 -0.8982167 -0.4395529 0 -0.8982167 -0.4395529 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.9659287 0 0.2588087 0.9659287 0 -0.2588087 0.9659287 0 -0.2588087 0.7071077 0 -0.7071059 0.7071077 0 -0.7071059 0.2588181 0 -0.9659261 0.2588181 0 -0.9659261 -0.2588181 0 -0.9659261 -0.2588181 0 -0.9659261 -0.7071077 0 -0.7071059 -0.7071077 0 -0.7071059 -0.965925 0 -0.2588222 -0.965925 0 -0.2588222 -0.965925 0 0.2588222 -0.965925 0 0.2588222 -0.7071072 0 0.7071063 -0.7071072 0 0.7071063 -0.2588185 0 0.9659261 -0.2588185 0 0.9659261 0.2588185 0 0.9659261 0.2588185 0 0.9659261 0.7071072 0 0.7071063 0.7071072 0 0.7071063 0.9659287 0 0.2588087 -0.7534887 -0.2519102 -0.6072859 -0.785865 -0.5946314 0.1697934 -0.5331652 -0.8234485 0.1940808 -0.04271662 -0.9952419 0.08757185 -0.5083577 -0.8316651 0.2233956 -0.506747 -0.8321415 0.2252732 -0.5066312 -0.8322488 0.2251374 -0.7449198 -0.5820364 0.32608 -0.7448149 -0.5822463 0.3259446 -0.8713346 -0.4635554 0.160911 -0.744901 -0.5821414 0.3259351 -0.7449381 -0.5821282 0.3258739 -0.7858009 -0.5946473 0.1700345 -0.7858078 -0.5946726 0.1699137 -0.8406139 -0.4924519 0.2255206 -0.8800962 -0.4651247 0.0953387 -0.8800864 -0.4651321 0.09539449 -0.8845221 -0.1748091 -0.4325071 -0.8292755 -0.1170947 -0.5464348 -0.8813073 -0.09466838 -0.4629636 -0.8149724 -0.1513857 -0.5593768 -0.8150146 -0.1513229 -0.5593323 -0.8270502 -0.09906935 -0.5533292 -0.8348004 -0.09989613 -0.5414139 -0.8451706 -0.06856775 -0.5300803 -0.4466548 -0.8532844 0.2690821 -0.4969121 -0.8222454 0.2774723 -0.7076363 -0.7063782 -0.01675593 -0.6287364 -0.7772589 0.02364867 -0.7775678 -0.188717 -0.5998119 -0.7912756 -0.1401099 -0.5951908 -0.8191695 -0.4697825 -0.3290378 -0.746518 -0.6585009 -0.09532785 -0.8194518 -0.4690872 -0.3293263 -0.9255556 -0.3115941 -0.2150723 -0.9250642 -0.3115139 -0.2172911 -0.9738654 -0.1570963 -0.1640337 -0.8844999 -0.174788 -0.4325609 -0.7775593 -0.1887217 -0.5998214 -0.7595448 -0.1784328 -0.6255027 -0.7272518 -0.2481194 -0.6399544 -0.5757341 -0.6761083 -0.4597911 -0.6868545 -0.5465258 -0.4791038 -0.6209885 -0.6761673 -0.396448 -0.521049 -0.7819768 -0.3420822 -0.3361768 -0.9319702 -0.1357086 -0.4363871 -0.8803485 -0.185884 -0.358333 -0.927496 -0.1065294 -0.2892222 -0.9544858 -0.07285273 -0.3433212 -0.9307276 -0.1260034 -0.06921935 -0.9935294 0.09004437 -0.108661 -0.9933193 0.03885382 -0.8729013 -7.56099e-6 -0.4878969 -0.8545877 0.008513033 -0.5192372 -0.8728187 0.009903907 -0.4879442 -0.8728331 0.009903907 -0.4879184 -0.9984478 -0.01360988 -0.0540058 -0.99526 -0.001678526 -0.09723591 -0.9985419 0.002193808 -0.05393797 -0.6785368 0.01028144 0.7344945 -0.9265369 -0.01353496 0.3759604 -0.914443 -0.009202122 0.4046099 -0.9266073 -0.002208173 0.3760244 -0.9985253 0.002193808 -0.05424189 -0.6785861 0.0102815 0.734449 -0.5973938 -0.008167147 0.8019065 -0.6783258 -0.02812701 0.7342227 -0.01724749 -3.70223e-6 0.9998513 -0.1726085 -0.003923237 0.9849827 -0.1904731 -0.007968187 0.9816601 -0.4031604 0.003446698 0.9151229 -0.403142 0.003446698 0.9151309 0.9607939 -0.2429226 -0.1336553 0.8535854 -0.05462187 -0.5180815 0.7611672 -0.1975459 -0.6177379 0.8309333 -0.1504093 -0.5356555 0.8537111 -0.05460429 -0.5178762 0.8576548 -0.1093305 -0.5024691 0.8554548 -0.09794485 -0.508531 0.8732979 -0.07062208 -0.4820406 0.8621064 -0.1076349 -0.4951639 0.9738047 -0.02198499 -0.2263211 0.9395863 -0.3292643 -0.09360951 0.9492694 -0.2734645 0.155257 0.9493179 -0.2732475 0.1553424 0.8750926 -0.4541824 0.1671263 0.8359798 -0.4710349 0.2815381 0.6313981 -0.7353591 0.2461371 0.6310631 -0.7357738 0.2457567 0.6805876 -0.6255964 0.3813524 0.6481339 -0.7250133 0.2329767 0.6465111 -0.7214388 0.2480913 0.761413 -0.6443134 0.07148903 0.8176823 -0.5589924 0.1375622 0.8359878 -0.4710693 0.2814568 0.33808 -0.940172 -0.04217195 0.09497892 -0.9792224 -0.1791715 0.09635603 -0.9794213 -0.1773401 0.3380535 -0.9401801 -0.04220551 0.149869 -0.9839845 -0.09650826 0.1812535 -0.9822772 -0.04773521 0.7782153 -0.2009457 -0.5949804 0.7781589 -0.2016377 -0.5948201 0.7938485 -0.1420387 -0.5912949 0.8375775 -0.4644427 -0.2876751 0.822856 -0.1420172 -0.5502174 0.7962999 -0.1912391 -0.5738763 0.6472048 -0.5613303 -0.5157852 0.6488443 -0.5581529 -0.5171715 0.4262626 -0.8389176 -0.3384046 0.4256979 -0.8362454 -0.3456515 0.1567903 -0.9823322 -0.102178 0.7783102 -0.1998291 -0.5952324 0.6559013 -0.6117745 -0.4421826 0.7316505 -0.5329422 -0.4250413 0.5502882 -0.8138465 -0.1866465 0.5503305 -0.8138199 -0.1866376 0.3499534 -0.9366242 0.01636224 0.2972024 -0.9547241 -0.01314049 0.496832 -0.7995404 0.3374804 0.5443035 -0.832184 0.1058464 0.6635316 -0.7466107 -0.04794108 0.6729014 -0.7355667 0.07839137 0.8378697 -0.4637442 -0.2879506 0.9366571 -0.3064798 -0.1695395 0.9362604 -0.3064008 -0.1718577 0.937263 -0.3038298 -0.1709547 0.9607844 -0.2429465 -0.1336797 0.6151401 -0.003659904 -0.7884094 0.6102856 -0.001608073 -0.7921798 0.6195954 1.21041e-5 -0.7849214 -0.1874791 0.003669202 -0.9822617 -0.1874771 0.003669202 -0.982262 0.1701131 -0.00434786 -0.9854149 0.2411504 0.001884698 -0.9704859 0.241155 0.001884698 -0.9704849 -0.6440897 3.62934e-6 -0.7649499 -0.1874659 0.003669619 -0.9822643 -0.3152073 -0.005901694 -0.9490046 -0.5798118 0.00480175 -0.8147363 -0.6246574 0.00479412 -0.7808842 -0.5796943 3.93266e-7 -0.8148341 0.2251483 1.56348e-6 0.9743245 0.1329252 0.0177682 0.9909669 0.2251232 0.01784646 0.9741669 0.9068408 -0.03234469 0.4202305 0.8436638 0.007308304 0.536822 0.9072736 0.01383715 0.4203132 0.630196 0.01638579 0.7762632 0.6303535 0.01638317 0.7761353 0.4902945 0.01614964 0.8714072 0.6296983 -0.04241722 0.7756808 0.225107 0.01784771 0.9741706 0.9963504 -9.79674e-4 -0.08535152 0.999976 -1.0686e-5 -0.00692135 0.9871577 -1.0549e-5 0.1597482 0.9945997 -0.01312881 0.1029512 0.9072246 0.01383715 0.420419 0.850345 0.001847863 -0.5262224 0.8505871 0.001847863 -0.5258309 0.9142644 -0.02157527 -0.4045429 0.9757807 0.01379626 -0.2183154 0.9757812 0.01379626 -0.2183138 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.900887 -0.2339846 0.3655869 -0.05293971 -0.9964101 0.06606197 -0.05298048 -0.9964101 0.06603085 -0.05164504 -0.995344 0.08138203 -0.03160339 -0.9968358 0.07293581 -0.03425639 -0.997271 0.06540024 -0.2219055 -0.8782256 0.4236481 -0.2232202 -0.8766642 0.426184 -0.3817961 -0.5682802 0.728896 -0.4587526 -0.1499774 0.8758155 -0.3959427 -0.1876581 0.8988959 -0.3941757 -0.1880471 0.8995909 -0.3960019 -0.1876376 0.8988741 -0.9008992 -0.2339841 0.3655574 -0.6760163 -0.08672106 0.7317661 -0.7572761 -0.1588674 0.6334777 -0.6584709 -0.2418803 0.712678 -0.6584804 -0.2418801 0.7126693 -0.9850491 -0.1602262 -0.06329059 -0.9859401 -0.1583847 -0.05325722 -0.9855638 -0.1561664 -0.06539195 -0.9855666 -0.1561677 -0.06534618 -0.986367 -0.1556715 -0.05335235 -0.9881997 -0.1325257 -0.0768007 -0.8726863 -0.02084028 -0.4878363 -0.8726789 -0.02082967 -0.4878501 -0.872672 -0.02083176 -0.4878622 -0.8727508 -0.02087569 -0.4877194 -0.872711 -0.02087497 -0.4877905 -0.9855593 -0.1606445 -0.05353754 -0.9485545 -0.1536381 0.2768388 -0.7164165 -0.6644997 0.2125734 -0.8079002 -0.5210511 0.2753233 -0.603825 -0.5682762 0.5589789 -0.3818014 -0.5682768 0.7288959 -0.2232421 -0.8766552 0.426191 -0.6366159 -0.7622953 0.116731 -0.639218 -0.6605852 0.3937353 -0.6345989 -0.561673 0.5308555 -0.8077884 -0.521089 0.2755795 -0.8079059 -0.5210579 0.275294 -0.05141133 -0.9953761 0.08113729 -0.3491328 -0.8759717 0.3328357 -0.3471754 -0.8771904 0.3316719 -0.3469107 -0.8762412 0.3344462 -0.3466311 -0.8764505 0.3341877 0.9069422 -0.0303598 0.4201596 0.9068958 -0.03026521 0.4202666 0.9595334 -0.2493776 -0.1307915 0.98521 -0.1377012 0.1019793 0.9757028 -0.06642341 -0.208787 0.943934 -0.2867068 0.1636696 0.9436732 -0.244603 0.2228229 0.879021 -0.2477843 0.4073388 0.8227409 -0.1331201 0.5526089 0.61205 -0.2387726 0.7539114 0.6122026 -0.2387759 0.7537865 0.5279849 -0.2307254 0.8173113 0.6259464 -0.1168724 0.771059 -0.01695078 -0.1846982 0.9826491 0.2223839 -0.1562196 0.9623621 0.1634502 -0.2050852 0.9649995 0.2195044 -0.2227036 0.9498531 0.2194887 -0.2227032 0.9498568 -0.1695891 -0.1868723 0.9676354 -0.1648652 -0.1831364 0.9691648 -0.164738 -0.1870468 0.9684394 -0.1477708 -0.5706117 0.8078156 -0.01314836 -0.9965775 0.08161246 -0.01463019 -0.9968144 0.07840371 -0.01331496 -0.9965757 0.08160698 0.01305395 -0.9969401 0.07707071 0.01256352 -0.9969947 0.0764445 -0.06001943 -0.9956575 -0.07116091 0.04035204 -0.9972312 0.06246387 0.03785365 -0.9964882 0.07468938 0.03796869 -0.9964871 0.0746451 -0.1459668 -0.951435 0.2710447 -0.1459646 -0.9514347 0.2710469 -0.005851626 -0.9999167 -0.01150357 0.05711585 -0.9963486 0.06346148 0.5670657 -0.6719691 -0.4763338 -0.145924 -0.9514631 0.2709687 0.3636131 -0.836148 0.4106606 0.3634741 -0.8362643 0.4105468 0.8867973 -0.398056 0.2348233 0.8867862 -0.3980818 0.2348216 0.7526431 -0.4218665 0.5055264 0.7035493 -0.6071753 0.3692647 0.703566 -0.6071097 0.3693411 0.998335 -0.0572682 -0.006909966 0.9745359 -0.05234897 -0.2180351 0.975448 -0.05551111 -0.2131195 0.9740118 -0.06174117 -0.2179196 0.9757521 -0.0694167 -0.207579 0.8502792 -0.03079932 -0.5254301 0.8501873 -0.03079825 -0.5255789 0.8499748 -0.02956181 -0.5259932 0.08125948 -0.8736302 0.4797574 0.08125829 -0.8736292 0.4797594 0.2640401 -0.8736276 0.408727 0.2640398 -0.8736263 0.4087299 0.4896034 -0.8546746 0.172684 0.3634772 -0.8362253 0.4106234 -0.08118057 -0.8791853 0.4695134 -0.08167916 -0.8776133 0.4723595 -0.08640241 -0.8757267 0.475013 -0.1392354 -0.5651569 0.8131489 0.1382782 -0.5606694 0.8164123 0.1382821 -0.5606732 0.8164089 0.4493119 -0.5606771 0.6955286 0.4493124 -0.5606778 0.6955276 0.6641218 -0.5638447 0.4909394 0.7153507 -0.6762741 0.1758598 -0.9902885 -0.09918415 0.09742289 -0.9181011 -0.1828721 -0.3516365 -0.9891467 -0.1226114 0.0809645 -0.9891424 -0.1226354 0.08098101 -0.9927898 -0.09790432 0.06916016 -0.9136939 -0.1764287 0.3661098 -0.9137451 -0.1764075 0.3659921 -0.955961 -0.2812082 0.08402806 -0.9762457 -0.2032054 0.07517999 -0.9896017 -0.105768 0.09747648 -0.9896021 -0.1057729 0.09746688 -0.9774373 -0.2109814 0.01015728 -0.988195 -0.1281165 0.08400559 -0.9757126 -0.2019537 0.08485049 -0.9784627 -0.1880798 0.08507001 -0.9543967 -0.2808998 0.1011061 -0.9264482 -0.3669128 0.08407557 -0.9246565 -0.3712373 0.08481252 -0.9264159 -0.3667687 0.08505451 -0.955791 -0.2811794 0.08603262 -0.9534716 -0.2892355 0.08505803 -0.9534776 -0.2892156 0.08505809 -0.8539069 -0.5115317 0.09580367 -0.7576415 0.6522759 0.02270811 -0.9024958 -0.4224882 0.08369636 -0.9246893 -0.3711741 0.08473294 -0.9246587 -0.3712503 0.08473247 -0.7570982 0.6529082 0.02265298 -0.8954579 -0.4396823 0.06953167 -0.8628724 -0.5005909 0.06971454 -0.8657747 -0.4955773 0.06955015 -0.8745982 -0.4799681 0.06861841 -0.8550823 -0.513334 0.07295477 -0.885742 -0.4567121 0.08291655 -0.9022648 -0.4224601 0.08628755 -0.2093175 -0.9776973 0.01714998 0.07428187 -0.9958039 0.05344855 0.210004 -0.9730788 0.09495234 -0.16323 -0.9818409 0.09666615 0.2298005 -0.9727469 0.03090322 0.1349342 -0.9908517 0.002413928 0.2298365 -0.9728168 0.02833336 0.06267291 -0.9972965 0.03836345 0.06273961 -0.9972949 0.03829509 0.08701467 -0.9960655 0.01679068 0.07262074 -0.997064 0.02428221 0.1349248 -0.9908529 0.002413153 -0.1061008 -0.9943515 -0.002808034 -0.1061152 -0.9943498 -0.002808511 -0.08268767 -0.996538 0.008653163 -0.06010389 -0.997836 0.02666342 -0.06334102 -0.9977189 0.02334839 -0.01636719 -0.9997799 0.01312345 -0.01657283 -0.999776 0.01316529 0.01317971 -0.9998443 0.01173579 0.01311892 -0.999845 0.01173609 -0.2042726 -0.9788295 0.01286917 -0.2093235 -0.9777317 0.01498442 -0.2042705 -0.9787619 0.01728332 -0.232602 -0.9657846 0.1147017 -0.2326796 -0.9657524 0.1148159 -0.2178056 -0.9719957 0.08823412 -0.2177711 -0.9720042 0.08822375 -0.09085071 -0.9910445 0.09786194 -0.01627951 -0.997017 0.07544505 -0.0681222 -0.9932384 0.09400457 -0.01463812 -0.9947422 0.1013587 0.1479934 -0.983289 0.1060219 0.07405185 -0.99272 0.09499114 0.06260448 -0.9931098 0.09906327 -0.0146225 -0.9947424 0.1013596 0.2091047 -0.9732779 0.09489554 0.2252843 -0.967053 0.1185556 0.2262077 -0.9664769 0.1214604 0.2099997 -0.9730582 0.09517359 0.1479777 -0.9832909 0.1060265 0.1480879 -0.9832744 0.1060253 0.2269966 -0.9734386 0.02983075 0.2269067 -0.9735105 0.02812081 0.2265366 -0.9720157 0.06218296 0.186414 -0.9821625 0.02463191 0.2100005 -0.9730828 0.09491872 -0.2083835 -0.973996 0.08892798 -0.2083081 -0.9736117 0.09320944 -0.1660217 -0.9831111 0.077003 -0.1745261 -0.9844877 0.01801282 -0.2021011 -0.9782527 0.04665595 -0.06832534 -0.9961999 0.05401325 -0.0632798 -0.9967552 0.04974651 0.07869106 -0.995229 0.05767905 0.07881301 -0.9967712 0.01535212 0.02595669 -0.996506 0.07938432 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.2172215 -0.02047187 -0.9759077 -0.2161659 -0.02024412 -0.9761468 -0.2161563 -0.02024376 -0.976149 -0.2154795 -0.02023661 -0.9762987 -0.1981303 -0.03529173 -0.9795402 -0.2019407 -0.03480631 -0.9787791 -0.2017385 -0.03598582 -0.9787781 -0.2024245 -0.03489702 -0.978676 -0.202564 -0.03614675 -0.9786016 -0.2095608 -0.03622931 -0.9771241 -0.1998432 -0.05034428 -0.9785336 -0.2029922 -0.05064767 -0.9778696 -0.202821 -0.05122405 -0.9778751 -0.2033179 -0.05073285 -0.9777976 -0.2031228 -0.05131274 -0.9778078 -0.2055081 -0.05137479 -0.9773061 -0.1971111 -0.06194353 -0.9784222 -0.1981932 -0.06221693 -0.9781863 -0.1981424 -0.06233477 -0.9781891 -0.19821 -0.06226068 -0.9781802 -0.1981537 -0.06236702 -0.9781847 -0.1984145 -0.06230276 -0.978136 -0.1949045 -0.07554274 -0.9779087 -0.1515258 -0.03752297 -0.9877409 -0.1515111 -0.0375182 -0.9877433 -0.1663414 -0.0419563 -0.9851753 -0.1053345 -0.02240294 -0.9941844 -0.0959447 0.02644538 -0.9950354 -0.1089782 0.002899408 -0.9940399 -0.1385627 -0.005974888 -0.9903357 -0.1301824 -0.008037209 -0.9914575 -0.1418481 -0.008487761 -0.989852 -0.1442203 -0.02343821 -0.989268 -0.1442407 -0.02345407 -0.9892647 -0.1442393 -0.02345454 -0.9892648 -0.9659257 0 0.2588196 -0.9659256 0 -0.2588198 -0.9659256 0 -0.2588198 -0.7071056 0 -0.707108 -0.7071056 0 -0.707108 -0.2588208 0 -0.9659254 -0.2588208 0 -0.9659254 0.2588184 0 -0.9659259 0.2588184 0 -0.9659259 0.7071056 0 -0.707108 0.7071056 0 -0.707108 0.9659256 0 -0.2588198 0.9659256 0 -0.2588198 0.9659257 0 0.2588196 0.9659257 0 0.2588196 0.7071055 0 0.707108 0.7071055 0 0.707108 0.2588178 0 0.9659261 0.2588178 0 0.9659261 -0.2588202 0 0.9659255 -0.2588202 0 0.9659255 -0.7071055 0 0.7071081 -0.7071055 0 0.7071081 -0.9659257 0 0.2588196 0.2746141 -0.08243316 -0.9580146 0.2746146 -0.08243513 -0.9580143 0.2466924 -0.07841259 -0.9659164 0.2421518 -0.0642203 -0.9681106 0.2423185 -0.07412934 -0.9673607 0.2601819 -0.09733515 -0.9606411 0.2480782 -0.1038802 -0.9631543 0.2666301 -0.0721625 -0.9610936 0.2666312 -0.07216125 -0.9610935 0.2643014 -0.07354247 -0.9616321 0.2643032 -0.0735498 -0.9616311 0.2598025 -0.06662768 -0.9633604 0.2699297 -0.06844151 -0.9604446 0.2672756 -0.0673747 -0.9612618 0.2656116 -0.06559926 -0.9618458 0.2626112 -0.06516677 -0.9626987 0.2774034 -0.01922166 -0.9605612 0.2599157 -0.06990009 -0.963098 0.2664482 -0.07452291 -0.9609639 0.2515572 -0.05434685 -0.9663153 0.2579874 -0.05968695 -0.9643028 0.2591989 -0.0575037 -0.9641106 0.2589917 -0.06013172 -0.964006 0.25997 -0.05785173 -0.9638822 0.2744073 -0.06693291 -0.9592813 0.2535428 -0.04310739 -0.9663632 0.2658224 -0.04981303 -0.9627342 0.266173 -0.04697126 -0.9627802 0.2667275 -0.05008685 -0.9624696 0.2675406 -0.04736757 -0.9623816 0.2791189 -0.05417078 -0.9587274 0.2561719 -0.03068476 -0.9661442 0.2787594 -0.02161139 -0.9601178 0.2767665 -0.03810501 -0.9601814 0.2767562 -0.0380817 -0.9601852 0.2773286 -0.03480118 -0.9601446 0.2769717 -0.03816568 -0.9601198 0.2796519 -0.03537976 -0.9594493 0.2628524 -0.01939737 -0.9646411 0.2771241 -0.01920449 -0.9606422 -0.3754885 0.9268258 0.001574218 -0.3933004 0.9194096 8.8891e-4 -0.3286061 0.944467 0 -0.6930603 0.7208797 2.43118e-5 -0.7045133 0.7096907 -5.65345e-4 -0.5370359 0.8435593 5.92477e-4 -0.5588582 0.8292632 -2.57359e-4 -0.5369968 0.8435842 -2.58127e-4 -0.558861 0.8292609 -8.76331e-4 -0.4377183 0.8991121 2.38561e-4 -0.4116336 0.9113492 6.81194e-4 -0.8207764 0.5712497 0 -0.6930531 0.7208866 2.43119e-5 -0.8032275 0.5956676 0.002360343 -0.7043463 0.7094487 -0.02405983 -0.8239085 0.5667229 0 -0.8239085 0.5667229 0 -0.9349816 0.3546963 0 -0.9349816 0.3546963 0 -0.8825353 0.4702463 0 -0.8825353 0.4702463 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.6707594 0 -0.741675 0.6433528 -0.0181837 -0.7653538 0.6891329 0 -0.724635 0.6707315 -0.009126901 -0.7416441 0.6269926 -0.7780323 -0.03932178 0.6232106 -0.7819727 -0.01127648 0.609099 -0.7926407 0.0268194 0.5914281 -0.8051482 0.04415011 0.5837765 -0.810473 0.04835724 0.6494317 -0.7597775 0.03125095 0.6212769 -0.706144 -0.33967 0.6308019 -0.7103842 -0.3121591 0.6610547 -0.7449225 -0.08998352 0.5960111 -0.7913928 -0.1358983 0.6486033 -0.7586171 -0.0617575 0.5666059 -0.8231831 -0.03643339 0.4825349 -0.8752846 -0.03220272 0.6012021 -0.7928915 -0.09939372 0.6248326 -0.7763992 -0.08239191 0.6995134 -0.7089417 -0.08990353 0.696575 -0.7108493 -0.09734821 0.6966175 -0.7108932 -0.09672147 0.5898753 -0.64038 -0.4918951 0.5983521 -0.634895 -0.4887568 0.6332013 -0.6388227 -0.4369918 0.6138421 -0.7105516 -0.3439685 0.6138393 -0.710554 -0.3439684 0.5471166 -0.5077885 -0.665443 0.5490257 -0.5079203 -0.6637679 0.6571507 -0.5800335 -0.4813669 0.6124176 -0.6182236 -0.4926908 0.6164111 -0.6234828 -0.4809432 0.7600237 -0.6426557 -0.09673392 0.760375 -0.6427273 -0.09344267 0.7482667 -0.6562079 -0.0974074 0.7798404 -0.6173326 -0.1036807 0.7798309 -0.617344 -0.1036832 0.6066201 -0.493045 -0.6236336 0.6066378 -0.4930246 -0.6236323 0.7799118 -0.6188983 -0.0932874 0.746414 -0.6531214 -0.1276659 0.6672036 -0.568573 -0.4812111 0.6721752 -0.5717101 -0.4704554 0.6804369 -0.5530211 -0.4808048 0.5717733 -0.4802839 -0.6651336 0.6464383 -0.3892413 -0.6562078 0.5997946 -0.4003424 -0.6928005 0.7579699 -0.5055837 -0.412149 0.7133238 -0.5232192 -0.4662733 0.7895048 -0.603904 -0.1094632 0.7794595 -0.6139801 -0.1243844 0.7551119 -0.64194 -0.1331132 0.7551147 -0.6419448 -0.1330733 0.8150377 -0.4252544 -0.3935382 0.6443877 -0.5154752 -0.5648449 0.5768656 -0.4697263 -0.6682689 0.7574162 -0.3764385 -0.5334931 0.5932906 -0.2908859 -0.7505943 0.8368746 -0.5371996 -0.1051548 0.8413395 -0.5324802 -0.09280407 0.659575 -0.1824666 -0.7291549 0.6338574 -0.2308823 -0.7381858 0.6338161 -0.2309405 -0.7382029 0.8682159 -0.4899533 -0.07840168 0.8713796 -0.4867492 -0.06142342 0.8173778 -0.3290536 -0.4728819 0.8646879 -0.3171171 -0.389553 0.6569312 -0.1475632 -0.739369 0.7553496 -0.07558673 -0.6509483 0.6366132 -0.2316961 -0.7355546 0.7851226 -0.3344113 -0.5212982 0.7864239 -0.3769265 -0.4893504 0.7546661 -0.3803737 -0.5345978 0.8435044 -0.5272533 -0.1024903 0.8939362 -0.4464706 -0.03927147 0.8099308 -0.06765425 -0.5826105 0.7578447 -0.1197941 -0.6413429 0.904168 -0.2729539 -0.3285976 0.8912248 -0.2835054 -0.3540382 0.8858958 -0.3081485 -0.3467466 0.8963335 -0.4420921 -0.03377443 0.8871819 -0.4588526 -0.04860568 0.8899696 -0.4539947 -0.04292821 0.8680569 -0.3111809 -0.3868378 0.8919153 -0.2821593 -0.353374 0.7280723 -0.1250284 -0.674002 0.7841597 -0.06994938 -0.616604 0.7938039 -0.1001144 -0.599877 -0.05116796 -0.7996164 -0.5983272 0.9002693 0.4241641 0.0979802 0.9002696 0.4241629 0.09798192 -0.03005999 -0.9032174 -0.4281294 0.8971139 -0.4405664 -0.03298556 0.7894283 -0.01105386 -0.6137434 0.9451154 -0.0706008 -0.3190181 0.9451214 -0.07060235 -0.3189998 0.8705439 0.05276459 -0.4892538 0.9979558 -0.06288564 -0.01138752 0.9961787 -0.001111984 -0.08733093 0.9900587 -0.1030219 -0.09576088 0.9907718 -0.1009368 -0.09045988 0.9825099 -0.1577923 -0.09887367 0.981815 -0.1623287 -0.09843116 0.9830277 -0.1594151 -0.09079331 0.9721902 -0.2108255 -0.1019746 0.9711074 -0.2188933 -0.09505856 0.9725299 -0.2134447 -0.09288078 0.9566361 -0.2702491 -0.1086867 0.9589762 -0.2676675 -0.09337341 0.8527841 0.03346145 -0.5211907 0.8485951 -0.0366345 -0.527773 0.8495783 -0.03601694 -0.5262313 0.8463815 -0.05770552 -0.5294418 0.8480031 -0.05698561 -0.5269188 0.8436276 -0.07726764 -0.5313399 0.8456118 -0.07640898 -0.5283013 0.8400003 -0.09658813 -0.5339198 0.842861 -0.09618914 -0.5294648 0.8356683 -0.1166269 -0.5367092 0.8389628 -0.1165158 -0.5315691 0.8303307 -0.1367476 -0.5402324 0.8344995 -0.1376166 -0.5335469 0.9419617 -0.3169149 -0.1107841 0.9386023 -0.3284339 -0.1056264 0.9415246 -0.3229932 -0.09595102 0.9172085 -0.3798245 -0.120257 0.9201037 -0.3794803 -0.09697407 -0.4591007 -0.8877183 0.03439378 -0.339314 -0.940012 0.035263 -0.6753333 -0.7368685 0.03081709 -0.6920067 -0.7211203 0.03334909 -0.6921549 -0.7190015 0.06291502 -0.6701756 -0.7414677 0.03302025 -0.6697629 -0.7418558 0.03267663 0.4753504 -0.879743 0.009699344 0.3239668 -0.9455035 0.03269153 0.3239952 -0.9454948 0.03265893 0.4118614 -0.9106107 0.03403306 0.4123837 -0.9103822 0.03382384 0.4119204 -0.9106305 0.03276908 0.4697821 -0.8821902 0.03233003 0.4737242 -0.8797555 0.0401948 0.3228465 -0.9457904 0.03536802 0.251964 -0.9671615 0.03335559 0.2531365 -0.9668282 0.03413408 0.2519266 -0.9671154 0.03494262 0.1816218 -0.982795 0.03357678 0.1810672 -0.9828596 0.03466308 0.1815717 -0.9827612 0.03481775 0.08872872 -0.9954354 0.03515022 0.08866715 -0.9954416 0.03512835 0.08872699 -0.9954404 0.03501486 -0.006347894 -0.999341 0.03573977 -0.006667733 -0.9993175 0.03633105 -0.006387293 -0.9993245 0.03618967 -0.006644904 -0.9993141 0.03642755 -0.08316767 -0.9959156 0.0351448 -0.08242779 -0.9959416 0.03613764 -0.1570571 -0.9869702 0.03496807 -0.156834 -0.9869982 0.03518241 -0.1570427 -0.9869554 0.03544944 -0.2487872 -0.9678927 0.03590029 -0.2482052 -0.9680508 0.03566151 -0.2487913 -0.9679335 0.03474974 -0.2481727 -0.9680988 0.03456616 -0.3387869 -0.9401557 0.03647893 -0.4009106 -0.9154372 0.03529262 -0.40092 -0.9154329 0.0352956 -0.4009347 -0.9154267 0.03528934 -0.4009872 -0.9154032 0.03530102 -0.4589732 -0.8877721 0.03470146 -0.5372486 -0.8427032 0.03486108 -0.5361558 -0.8434888 0.03261232 -0.5373004 -0.8427166 0.03371745 -0.5361844 -0.8434978 0.03190076 -0.6075558 -0.793457 0.03608191 -0.6103277 -0.7915933 0.02966809 -0.6079078 -0.7934775 0.02900683 -0.6505023 -0.7587304 0.03427487 -0.6538397 -0.7559466 0.03222358 -0.6775056 -0.7346578 0.03555512 -0.6781963 -0.734198 0.03167027 -0.6918663 -0.7192781 0.06292837 -0.6890597 -0.7247034 0.001366674 -0.6925444 -0.7207422 0.03021347 -0.6926169 -0.7206658 0.03037309 -0.8641248 -0.4995943 0.06077879 -0.8631848 -0.501373 0.05947554 -0.8579168 -0.5137877 0.001016855 -0.898118 -0.4397505 -0.00192666 -0.7729924 -0.6340445 0.02168798 -0.696692 -0.7155776 0.05068486 -0.6979547 -0.7153825 0.03297275 -0.7095451 -0.7040422 0.02950274 -0.7067486 -0.7066854 0.03319782 -0.7247009 -0.6883224 0.03195142 -0.7243243 -0.6887107 0.03212273 -0.7247464 -0.6882585 0.03229534 -0.7573158 -0.6522434 0.0324223 -0.7571464 -0.652459 0.03203916 -0.7573354 -0.6522508 0.03181517 -0.7875199 -0.6154552 0.03205174 -0.78771 -0.6152207 0.03188455 -0.81142 -0.5835847 0.03203809 -0.8114721 -0.5835146 0.03199636 -0.8114193 -0.5835949 0.03187143 -0.8357439 -0.5482029 0.0317161 -0.834994 -0.5492869 0.03269451 -0.852656 -0.5215975 0.03023219 -0.8491674 -0.5267959 0.03742718 -0.8517223 -0.522755 0.03600615 -0.8591489 -0.5108568 0.02980983 0.3368963 -0.9394636 0.06252276 0.2621487 -0.9612094 0.08575862 0.1605592 -0.967274 0.1964734 0.2782495 -0.9595335 0.04327428 0.1587089 -0.98697 0.02648943 0.0533092 -0.9985343 0.009356319 0.2946841 -0.9538221 0.05817711 0.295209 -0.9538413 0.0551207 0.3276155 -0.9435564 0.0486772 0.3265706 -0.943541 0.05551594 0.3428174 -0.9382117 0.04727554 0.3417947 -0.9382032 0.05432426 0.3766051 -0.9251362 0.04787176 0.0977227 -0.9947413 0.03066092 0.09962517 -0.9948338 0.019508 0.1108842 -0.9936742 0.0177834 0.1105808 -0.9936704 0.01977628 0.116245 -0.9930711 0.0172314 0.1159444 -0.993068 0.01930725 0.1282498 -0.9915863 0.0175727 0.1292086 -0.9916138 0.002690672 0.1292379 -0.9916103 0.002574086 0.1291904 -0.9916169 0.002424299 0.3790631 -0.9253433 0.007140696 0.3789572 -0.9253789 0.008082628 0.3789575 -0.9253788 0.008081376 0.3788619 -0.924967 0.02999478 0.3779319 -0.9252357 0.03326284 0.1292034 -0.9915654 0.01022511 0.1288835 -0.9915982 0.01105165 0.188524 -0.9813862 -0.03660351 0.1690808 -0.9851309 -0.03047215 0.1601299 -0.9867061 -0.02773928 0.1345524 -0.9907007 -0.02019613 0.09311038 -0.995602 -0.01034736 0.05349642 -0.998562 -0.00348711 0.0218451 -0.9997614 -4.8113e-4 0.009004592 -0.9999594 -1.18499e-4 0.004404604 -0.9999904 0 0.2543753 -0.9652846 -0.05931901 0.03109169 -0.9993653 0.01738691 0.06800335 -0.9976493 0.008455216 0.06807434 -0.9976446 0.008442401 0.09390169 -0.9955727 0.00417149 0.1232697 -0.9923731 5.79579e-4 0.1140207 -0.9934406 -0.0086748 0.08366477 -0.9964298 -0.01131308 0.01008224 -0.9999492 0 0.1292087 -0.9916141 -0.002624034 0.0493679 -0.9986629 -0.01533949 0.08363664 -0.9964321 -0.01131594 0.2482883 -0.9686589 -0.007264852 0.314913 -0.9491194 -0.001415193 0.313697 -0.9495172 -0.003362596 0.3182883 -0.9478971 -0.01355159 0.2780889 -0.9605382 -0.005733549 0.1232565 -0.9923746 5.81123e-4 0.1703074 -0.9853799 -0.004677176 0.1943444 -0.9809223 -0.004670977 0.1291903 -0.9916163 -0.002626299 0.3789674 -0.925403 0.00362277 0.3789695 -0.9254092 0 0.4917287 -0.870662 -0.01227349 0.4725368 -0.8812515 -0.01024156 0.4534548 -0.8912373 -0.008652508 0.4314543 -0.9021079 -0.006970345 0.4314811 -0.902095 -0.006971955 0.3966152 -0.91797 -0.005229234 0.316962 -0.9483162 -0.01521277 0.3155359 -0.9489046 -0.004153788 0.3349539 -0.9422253 -0.004158794 0.3677631 -0.9299086 -0.004495978 0.5552983 -0.4128446 -0.7219439 0.5552864 -0.4128792 -0.7219333 0.7926238 -0.2473685 -0.557276 0.9137395 -0.1769472 -0.3657456 0.7043411 -0.09766864 -0.7031105 0.8256156 -0.5027115 -0.2562032 0.8323562 -0.500656 -0.2377533 0.3843594 -0.6865881 -0.6171424 0.1961176 -0.8835026 -0.4253953 0.7407123 -0.6635245 0.1052635 0.6093195 -0.7646027 -0.2100297 0.3843241 -0.6866345 -0.6171126 0.01528608 -0.9998715 -0.004832386 0.3880209 -0.9000195 0.1985058 0.6601976 -0.564284 0.4957041 0.3211635 -0.9418826 -0.09854561 0.1961092 -0.8835077 -0.4253885 0.6940426 -0.1943559 -0.6932032 0.6984205 -0.1950808 -0.6885871 0.5854631 -0.55373 -0.5921283 0.5984526 -0.5555156 -0.5772842 0.3874199 -0.8293741 -0.4025474 0.4088708 -0.8312496 -0.3766282 0.1291195 -0.9796041 -0.1539612 0.1594204 -0.9803325 -0.1163323 0.3876075 -0.803766 -0.4513542 0.5359396 -0.5607284 -0.6311515 0.6408327 -0.09845805 -0.7613406 0.6407948 -0.09847933 -0.7613697 0.623455 -0.2547956 -0.7391774 0.6234823 -0.2547745 -0.7391615 0.5879248 -0.4134801 -0.6952545 0.5879759 -0.4135872 -0.6951473 0.5880037 -0.4134795 -0.6951881 0.588097 -0.4135537 -0.6950648 0.5356855 -0.5608589 -0.6312515 0.4682008 -0.6921496 -0.5492877 0.4683068 -0.69222 -0.5491086 0.4683472 -0.6921374 -0.5491781 0.4684813 -0.6922701 -0.5488966 0.3873732 -0.8038286 -0.4514437 0.2952466 -0.8925463 -0.3408672 0.2953912 -0.8925676 -0.3406863 0.2954991 -0.8924491 -0.3409031 0.2955912 -0.8925727 -0.3404996 0.1948614 -0.955721 -0.2205135 0.1949597 -0.9557135 -0.2204596 0.08856707 -0.9916064 -0.09419417 0.08728069 -0.9916269 -0.09517431 0.01282459 -0.9998925 -0.007110655 0.6434648 0.00121665 -0.7654748 0.6434592 0 -0.7654803 0.568914 -0.413897 -0.7106519 0.5488474 8.03505e-4 -0.8359222 0.4328568 -0.2515626 -0.8656508 0.2092494 -0.9646369 -0.1602823 0.2908715 -0.8925831 -0.3445128 0.1740427 -0.9559063 -0.2365428 0.01138192 -0.9717262 -0.2358358 0.08827632 -0.9916122 -0.09440577 0.02165466 -0.9997655 -2.85132e-4 0.2907809 -0.8926753 -0.3443505 0.2059053 -0.8407258 -0.5007824 0.3348174 -0.8039215 -0.491536 0.5689144 -0.413899 -0.7106503 0.4536202 -0.5605588 -0.692822 0.3633168 -0.6026153 -0.710532 0.4563749 -0.6925144 -0.5586999 0.4563761 -0.6925073 -0.5587078 0.06388014 -0.9779327 -0.1989143 0.09168601 -0.9646212 -0.2471832 0.4173446 -0.8393152 -0.3483871 0.2766923 -0.7674551 -0.57832 0.2766916 -0.7674586 -0.5783157 0.5856568 -0.5968766 -0.5484018 0.4219707 -0.4339793 -0.7959915 0.4219667 -0.4339662 -0.7960009 0.6122639 -0.09869784 -0.784469 0.491624 -0.2872616 -0.8220624 0.6599866 -0.2814538 -0.6965641 0.6599099 -0.2814635 -0.6966327 0.2276 -0.962733 -0.1460933 0.2337629 -0.9628941 -0.1348701 0.238959 -0.9612867 -0.1372098 0.3849257 -0.7712303 -0.5069871 0.43647 -0.7995262 -0.4126157 0.4988384 -0.75999 -0.4166238 0.692392 -0.4976723 -0.5224132 0.4529258 -0.434439 -0.7785376 0.4978281 -0.4823171 -0.7207893 0.6613715 -0.4208958 -0.6208336 0.4755622 -0.8218251 -0.313758 0.3658624 -0.8060446 -0.4652277 0.2515361 -0.9614171 -0.111385 0.2391656 -0.9621363 -0.1307415 0.4516596 -0.6327248 -0.6290175 0.6181825 -0.5140052 -0.5946839 0.6181586 -0.5140165 -0.5946992 0.5815693 -0.6200682 -0.5265858 0.4576926 -0.6322005 -0.6251718 0.4264464 -0.835411 -0.346745 0.3735873 -0.8417292 -0.3897749 0.2471972 -0.9620867 -0.1152507 0.2344923 -0.9641265 -0.1243928 0.2420477 -0.9630462 -0.1181312 0.5939686 -0.6742959 -0.4387782 -0.2959631 -0.4930062 -0.8181387 -0.3046148 -0.5376384 -0.7862282 0.7419558 -0.6696371 -0.03297853 -0.4010709 -0.7275694 -0.5565834 -0.4010668 -0.7275664 -0.5565901 0.6151245 -0.7854194 0.06883537 0.6116377 -0.7858436 0.09137541 0.6205111 -0.7776346 0.1012445 0.5744327 -0.8185421 -0.003985226 0.5781906 -0.8133264 0.06477463 0.6098113 -0.7920821 0.0271328 0.6064802 -0.7919617 0.07055968 0.6064013 -0.7919787 0.0710439 0.4358494 -0.9000195 5.93395e-4 0.4652845 -0.8843604 -0.03764361 0.4654118 -0.8842912 -0.03769475 0.4358151 -0.9000361 4.89084e-4 0.4158708 -0.9088504 -0.03228712 0.4233962 -0.9049296 0.04287314 0.5280669 -0.822328 -0.2119484 0.5494192 -0.8167775 -0.1761057 0.5830382 -0.8086702 -0.078224 0.5572451 -0.8194798 -0.1339061 0.5693447 -0.8212705 -0.03689557 0.5618514 -0.8248702 -0.06254839 0.5606295 -0.8279536 -0.01368856 0.5704221 -0.8160924 0.09280043 0.561705 -0.8273038 -0.007474184 0.5707663 -0.8196097 0.04965806 0.5707353 -0.8196565 0.04923766 0.6046828 -0.7778884 -0.1710215 0.6047406 -0.7778587 -0.1709522 0.6007511 -0.7796476 -0.1767706 0.6120845 -0.7289962 -0.3064593 0.5040892 -0.7966483 -0.3335351 0.5368884 -0.7895849 -0.2971642 0.4015576 -0.9151492 -0.03540492 0.4015563 -0.9151496 -0.0354076 0.3997876 -0.9156414 -0.04207932 0.3950935 -0.9172596 -0.05035787 0.3944014 -0.9170294 -0.05919891 0.3868319 -0.9195494 -0.06920903 0.3834106 -0.9203619 -0.07700794 0.370871 -0.9241366 -0.09179419 0.3685424 -0.9239632 -0.1023159 0.6120893 -0.7289928 -0.3064574 0.6051993 -0.7315554 -0.3139434 0.4954391 -0.7132533 -0.495792 0.597187 -0.6896587 -0.4095592 0.458073 -0.7014319 -0.5460426 0.4580643 -0.7014294 -0.5460531 0.3188148 -0.9347665 -0.1567438 0.3333486 -0.9329846 -0.1357144 0.344601 -0.9292352 -0.1333118 0.3377169 -0.9309333 -0.1389625 0.3142588 -0.9361553 -0.1576536 0.3090625 -0.9367799 -0.1640851 0.01302999 -0.9998303 0.01302999 0.1322649 -0.9907666 0.02979487 -0.0133745 -0.9916173 0.1285153 0.1477437 -0.9820978 0.1168578 0.1846244 -0.9731768 0.1372615 0.1380403 -0.9801629 0.1422167 0.246009 -0.9390144 0.2402738 0.221524 -0.9448267 0.2413079 0.2214769 -0.9448468 0.2412725 0.2354081 -0.9377896 0.255213 0.2202987 -0.9425451 0.2511517 0.3157485 -0.8381098 0.4448312 0.5723565 -0.7493872 0.3329069 0.3083715 -0.8645524 0.3968075 0.4581556 -0.8326827 0.3110192 0.3343697 -0.8907946 0.3077042 0.3875768 -0.8181799 0.4246953 0.4713594 -0.7748655 0.4211934 0.4226759 -0.8012372 0.4235139 0.3696732 -0.8588712 0.3545164 0.3323276 -0.8924842 0.3050087 0.3323359 -0.8924774 0.3050198 0.3838905 -0.8422152 0.378552 0.3840333 -0.8420831 0.3787011 0.5954711 -0.5391429 0.5955998 0.6507165 -0.4304622 0.6255159 0.6006894 -0.5393276 0.5901677 0.5720283 -0.5905394 0.5692512 0.4911888 -0.7187742 0.4920338 0.5954994 -0.539088 0.5956214 0.5954633 -0.5391615 0.5955907 0.6404768 -0.4235733 0.6406053 0.6765733 -0.2908828 0.6764877 0.6960944 -0.1757982 0.6960944 0.7138081 -0.04710531 0.6987555 0.6991745 -0.1757875 0.6930034 0.7055118 -0.1405299 0.6946254 0.6930701 -0.2137442 0.6884529 0.2383946 -0.9412163 0.239332 0.3838972 -0.8422077 0.378562 0.238463 -0.9411814 0.2394013 0.2384442 -0.9411909 0.2393825 0.05347007 -0.9971369 0.05347007 0.1289812 -0.9844077 0.1196047 0.1568914 -0.9756944 0.1529891 0.1569744 -0.9756658 0.1530858 0.8873993 -0.4553244 0.0721262 0.9872337 -0.1573167 0.02491992 0.4835765 -0.8324654 0.2704723 0.1520012 -0.9836682 0.09639823 0.4832736 -0.832634 0.2704942 0.4008035 -0.844212 0.355897 0.7591316 -0.5207293 0.3905897 0.6660714 -0.5361467 0.5185516 0.6943721 -0.1757884 0.6978151 0.504522 -0.5350902 0.6775957 0.6900001 -0.4478273 0.5686392 0.6645293 -0.5283913 0.528397 0.8874023 -0.3259714 0.325975 0.8874015 -0.3259755 0.3259733 0.9872338 -0.1126268 0.112626 0.9872339 -0.07231038 0.1419175 0.8874027 -0.2092868 0.4107497 0.8874021 -0.2092903 0.4107494 0.7541526 -0.2981387 0.5851215 0.6660645 -0.536217 0.5184877 0.747425 -0.1752976 0.6408015 0.6897454 -0.1132668 0.7151377 0.8874024 -0.07211571 0.4553199 0.887403 -0.0721175 0.4553185 0.8874046 -0.07211464 0.4553158 0.9872338 -0.02491641 0.1573168 0.8874037 -0.455317 0.07211828 0.8874052 -0.4553153 0.07211095 0.6993429 -0.7059872 0.1118112 0.6993411 -0.7059885 0.1118133 0.6993622 -0.705965 0.11183 0.5194417 -0.7613743 0.3879297 0.6993434 -0.6368822 0.3244994 0.699351 -0.6368686 0.3245096 0.8874047 -0.410744 0.2092902 0.887402 -0.4107543 0.2092812 0.9872338 -0.1419191 0.07230842 0.4436645 -0.8851562 0.1402152 0.4030814 -0.8972456 0.18021 0.440025 -0.8779519 0.1886221 0.4760703 -0.8597894 0.1847141 0.5552639 -0.8119979 0.1798372 0.9875404 0 0.1573657 0.9737321 0.1197178 0.1936842 0.8860186 -0.0911355 0.4546047 0.8860165 -0.0911355 0.4546088 0.8179036 0.1798967 0.5465077 0.7591806 0 0.6508801 0 -0.08566898 0.9963237 -0.04798811 -0.2585254 0.9648118 0.009490549 -0.7070703 0.7070795 -0.00340867 -0.4023045 0.9154996 -0.03300786 -0.2586736 0.9654006 -0.03246146 -0.409061 0.9119295 -0.04941695 -0.2545891 0.9657859 -0.01868623 -0.9198452 0.3918362 -0.03669703 -0.8580272 0.5122916 -0.05852472 -0.8005457 0.5964072 0.0981729 -0.9612706 0.2575284 -0.04751718 -0.6868792 0.7252167 -0.03888994 -0.7065645 0.7065792 -0.03886717 -0.684389 0.7280804 -0.06594496 -0.5620476 0.8244718 -0.01868671 -0.9198964 0.3917161 -0.0355131 -0.9653216 0.258637 0 -0.9902031 0.1396346 0.1285209 -0.2101155 0.9691923 0.2349339 -0.6415243 0.7302415 0.3163419 -0.8956142 0.312735 0.2285398 -0.6437172 0.730341 0.09077638 -0.247132 0.9647205 0.1239052 -0.2444567 0.9617112 0.2300303 -0.6468837 0.7270678 0.1846329 -0.6615654 0.7268025 0.1796242 -0.6701073 0.7202023 0.1150265 -0.6840968 0.7202641 0.1089841 -0.6921091 0.7135178 0.05878186 -0.9642606 0.2583528 0.04956996 -0.9604415 0.2740343 0.159844 -0.9483651 0.2739592 0.1475067 -0.9469293 0.2855988 0.1595494 -0.9437808 0.2895202 0.2461835 -0.9249824 0.2894843 0.2567936 -0.9172345 0.3045287 0.3174031 -0.89799 0.3047445 0.3274061 -0.8918607 0.3120732 0.04645323 -0.9648939 0.2584991 0.04253488 -0.7064595 0.7064743 0.03861242 -0.6996087 0.7134822 0.03536581 -0.7066599 0.706669 0.01612627 -0.2587808 0.9658014 0.07950896 -0.2365412 0.9683629 0.06761884 -0.24044 0.9683059 0.06628531 -0.2440831 0.9674863 0.04242223 -0.2492352 0.9675135 0.04066282 -0.2527685 0.966672 0.01536893 -0.2554823 0.9666916 0.01381361 -0.2587988 0.9658325 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.005159735 0.999683 -0.02464503 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.02725607 0.9987937 0.04084324 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.3621945 0.2307543 0.9030878 -0.003338813 0.002471148 0.9999914 -0.1076651 0.08289188 0.9907256 -0.6074866 0.4038691 0.6839954 -0.5747673 0.3808903 0.7242687 -0.7257413 0.4890916 0.4838275 -0.7346106 0.4952231 0.46379 -0.7346141 0.495226 0.4637814 -0.7999427 0.5676726 0.1945243 -0.8134086 0.5595006 0.1591396 -0.3858209 0.9018921 0.1942491 -0.3858069 0.9018923 0.1942768 -0.5482133 0.8134613 0.1942756 -0.5481982 0.8134745 0.194262 -0.5482144 0.8134694 0.1942386 -0.6911131 0.6961569 0.194238 -0.6910881 0.6961668 0.1942909 -0.6911297 0.6961361 0.1942533 -0.5286253 0.4763678 0.7025875 -0.6919059 0.4636015 0.5534797 -0.5865998 0.5908809 0.5538597 -0.5865979 0.5908808 0.553862 -0.4652985 0.6904592 0.5538623 -0.4653068 0.6904615 0.5538523 -0.3274778 0.7655099 0.5538527 -0.3274629 0.7655025 0.5538719 -0.3165118 0.3093176 0.8967402 -0.4666682 0.3060743 0.8297827 -0.3926291 0.3954958 0.8303164 -0.3926278 0.3954954 0.8303171 -0.311443 0.4621453 0.8303163 -0.3114314 0.4621399 0.8303235 -0.2191796 0.5123711 0.8303229 -0.2191827 0.5123734 0.8303207 -0.3479886 0.2205693 0.9111822 -0.1365795 0.1407749 0.9805756 -0.1380344 0.1390425 0.980619 -0.1380379 0.1390435 0.9806184 -0.1094917 0.1624772 0.9806186 -0.1094918 0.1624773 0.9806186 -0.07705879 0.1801367 0.9806185 -0.07706433 0.180141 0.9806173 -0.047643 0.1295998 0.9904212 -0.3218821 0.9247266 0.2031564 -0.3223136 0.9244562 0.2037021 -0.2685341 0.7721643 0.5758922 -0.269586 0.7707871 0.5772441 -0.1707657 0.4920876 0.8536328 -0.1721949 0.4890894 0.8550674 -0.04353803 0.1275952 0.9908702 -0.04636836 0.1260331 0.9909418 -0.3681467 0.9076952 0.2013888 -0.3694342 0.9067938 0.2030847 -0.3075956 0.7608677 0.5713715 -0.3107514 0.756231 0.5758023 -0.1970189 0.4907007 0.8487616 -0.2011063 0.4806412 0.8535457 -0.05416607 0.1409838 0.988529 -0.05877697 0.1254048 0.990363 -0.40393 0.892847 0.1991602 -0.4068245 0.8910438 0.2013325 -0.3376955 0.7523092 0.5656789 -0.3453724 0.7445151 0.5713275 -0.2177055 0.4926247 0.8425706 -0.2285987 0.4769669 0.8486726 -0.06250834 0.1551064 0.9859182 -0.07580941 0.1315667 0.9884043 -0.4296668 0.8816674 0.1950615 -0.4347244 0.8782922 0.199041 -0.3597099 0.7496559 0.5555402 -0.372156 0.7360161 0.565491 -0.2345982 0.503829 0.8313363 -0.2517006 0.4765822 0.8423277 -0.07291173 0.1816962 0.9806479 -0.09309589 0.1407276 0.9856617 -0.5267783 0.8275317 0.194154 -0.6798714 0.7071614 0.1941592 -0.7849715 0.563609 0.257225 -0.6890441 0.4680547 0.553302 -0.5717992 0.4205445 0.7044062 -0.5718296 0.4205656 0.7043688 -0.4631999 0.3112851 0.8297876 -0.2066471 0.1602237 0.9652074 -0.1521307 0.1222473 0.980771 -0.2133878 0.1485134 0.9656134 -0.7849519 0.5635953 0.2573148 -0.8051494 0.5603736 0.1942058 -0.6798613 0.7071651 0.1941805 -0.526827 0.8275235 0.1940569 -0.6798626 0.7071629 0.1941837 -0.5771236 0.6002984 0.553688 -0.5771281 0.6003004 0.5536809 -0.3863544 0.4018669 0.8302009 -0.3863675 0.4018752 0.8301905 -0.1358543 0.1413071 0.9805998 -0.1358492 0.1413035 0.980601 -0.5267962 0.8275182 0.1941627 -0.4471763 0.7024472 0.5537159 -0.4471929 0.7024596 0.553687 -0.2993794 0.4702711 0.8301909 -0.2993669 0.4702593 0.8302022 -0.1052643 0.1653541 0.9806005 -0.1052669 0.1653568 0.9805998 -0.5712254 0.4215023 0.7042993 -0.5274505 0.1848534 0.8292317 -0.6632577 0.255316 0.7034934 -0.7125705 0.4298003 0.5545404 -0.8819571 0.3945874 0.2577837 -0.8948418 0.4016128 0.1948465 -0.8524719 0.4542275 0.2587841 -0.2585965 0.06657928 0.9636883 -0.2586516 0.06660866 0.9636714 -0.1722084 0.09175801 0.9807776 -0.9172186 0.3479576 0.1939992 -0.9172112 0.3479611 0.1940276 -0.7787421 0.2954303 0.5534272 -0.778747 0.2954304 0.5534204 -0.5214704 0.1978283 0.8300197 -0.521485 0.1978303 0.8300099 -0.1833952 0.06957268 0.9805743 -0.1833909 0.06957191 0.9805751 0.788385 -0.1118308 0.6049323 0.7883848 -0.1118322 0.6049321 0.5569659 -0.07901144 0.8267685 -0.2804326 -0.6991676 0.6576642 -0.3804797 -0.269923 0.8845206 -0.4673052 -0.4133527 0.7815148 -0.4120401 -0.5591046 0.7194616 -0.5518097 -0.004327416 0.8339588 0.7030752 -0.1667302 0.6912934 0.6463418 -0.2204853 0.7304989 0.655277 -0.2719281 0.7047461 0.6771038 -0.09946155 0.729135 0.6734186 -0.1032519 0.7320154 0.6656928 -0.02426421 0.7458313 0.6192955 -0.05159568 0.7834609 0.6174204 -0.009256005 0.7865789 0.5346054 -0.08593159 0.8407216 0.5321108 -0.02191436 0.8463911 0.4153028 -0.1315569 0.9001201 0.1996346 -0.08957308 0.9757677 0.289492 -0.1423245 0.9465401 0.4115775 -0.03613412 0.9106581 0.5582324 -0.3597937 0.7476129 0.5979664 -0.3280019 0.7313351 0.6081007 -0.3971526 0.6873742 0.5153926 -0.4758503 0.712697 0.518477 -0.5552574 0.6502853 0.2078135 -0.09435421 0.9736072 0.0653252 -0.196977 0.9782294 0.09816521 -0.1170415 0.9882636 -0.09105658 -0.2369796 0.967238 -0.0485357 -0.1695708 0.9843221 0.3770372 -0.6539164 0.6559239 0.4449326 -0.6250762 0.6413381 0.4075284 -0.6731768 0.6170523 0.3279817 -0.7213689 0.6099632 0.3061943 -0.7779305 0.5486977 0.239464 -0.812559 0.5314177 0.1976826 -0.8447269 0.4973511 -0.1114206 -0.1725877 0.978672 -0.2338776 -0.2341074 0.9436604 -0.1894574 -0.1896457 0.9634004 -0.3541218 -0.2624062 0.8976306 -0.3235093 -0.2103316 0.9225521 -0.4722551 -0.2552835 0.8436855 -0.4450526 -0.2379973 0.8632991 -0.4833903 -0.2472797 0.8397539 -0.1417592 -0.1144436 0.9832634 0.7883895 -0.1118174 0.6049288 0.6675338 -0.1528955 0.7287123 0.6660622 -0.08599388 0.7409226 0.5971984 -0.150709 0.7878077 0.5973621 -0.1524022 0.7873576 0.5184289 -0.2264513 0.8245915 0.5185666 -0.227876 0.8241125 0.3959578 -0.3318529 0.8562074 0.3959794 -0.3331804 0.8556817 0.2702739 -0.4249692 0.8639174 0.2699397 -0.4258028 0.8636114 0.1339455 -0.509745 0.8498344 0.1336328 -0.5108492 0.8492205 0.00748676 -0.5758392 0.8175286 0.006826877 -0.5764876 0.8170775 -0.1218819 -0.6301904 0.7668147 -0.1223577 -0.6311469 0.7659518 -0.2481289 -0.6709568 0.6987482 -0.2489126 -0.6714421 0.6980029 -0.3351051 -0.690768 0.6407374 -0.2018129 -0.5793199 0.7897215 -0.07006591 -0.9556368 0.2860927 -0.2767078 -0.8109376 0.5155704 -0.1409509 -0.8058277 0.5751302 0.07980871 -0.8883871 0.4521049 0.1378122 -0.8790062 0.4564601 0.1065919 -0.9009371 0.4206548 0.03160661 -0.9247351 0.3792966 0.006108283 -0.9358531 0.3523374 -0.08533859 -0.9527275 0.2915951 -0.08575928 -0.9583245 0.2725057 -0.3124361 -0.8406634 0.4423447 -0.312525 -0.8406849 0.4422409 -0.3292626 -0.8453337 0.4207102 -0.28325 -0.9549866 0.08814895 -0.0905891 -0.9882083 0.1234416 0.1795833 -0.8577719 0.4816403 0.2889407 -0.8612042 0.4181395 0.1272619 -0.7983497 0.5885934 -0.07777684 -0.9879001 0.1341802 -0.1044335 -0.9290705 0.354854 0.01654398 -0.9199312 0.3917309 0.01454025 -0.9199086 0.3918632 -0.179746 -0.9020887 0.3923361 -0.1040409 -0.9290646 0.3549849 -0.02469789 -0.9899011 0.1395919 -0.06518965 -0.9273589 0.3684504 -0.1183352 -0.9117134 0.3934151 -0.02469736 -0.9899011 0.1395916 -0.05708271 -0.9901559 0.1278001 -0.19064 -0.9143674 0.3571956 -0.6532086 -0.627614 -0.4235789 -0.234139 -0.9089058 0.3450644 -0.2194492 -0.9071683 0.3590092 -0.1488534 0 0.9888593 -0.1488534 0 0.9888593 -0.4333629 0 0.9012195 -0.4333629 0 0.9012195 -0.1488533 -0.001061499 0.9888586 -0.1487041 -0.003910601 0.988874 -0.4333629 -3.17732e-4 0.9012194 -0.4329559 -0.01115101 0.9013462 -0.1879339 -0.7949191 0.5768747 -0.2577804 -0.8579134 0.4444478 -0.2516194 -0.8688665 0.4263316 -0.3136627 -0.8593425 0.4039137 -0.2506304 -0.8870429 0.3877361 -0.2531446 -0.8957902 0.365346 -0.1876329 -0.7948937 0.5770077 -0.1876077 -0.7949068 0.5769979 -0.07269042 -0.8718044 0.484431 -0.01025849 -0.8499743 0.5267243 -0.08164435 -0.8067724 0.5851944 -0.114508 -0.7918497 0.5998849 -0.2949228 -0.8003848 0.5219239 -0.2578135 -0.8578566 0.4445384 -0.1196919 -0.7058877 0.6981379 -0.1215996 -0.681854 0.7213103 -0.09736478 -0.7005399 0.7069399 -0.3637774 -0.5665999 0.7393447 -0.1136484 -0.5735728 0.8112326 -0.1345562 -0.5539073 0.8216332 -0.3627752 -0.5645858 0.741375 -0.3297842 -0.692798 0.641306 -0.3290487 -0.6934071 0.6410254 -0.2916444 -0.7956705 0.5308974 -0.3638121 -0.5663948 0.7394847 -0.3892387 -0.4242504 0.8176215 -0.392508 -0.4199501 0.8182783 -0.4105641 -0.2672778 0.8717796 -0.4146125 -0.2603858 0.8719494 -0.4248243 -0.1023179 0.899475 -0.4302107 -0.0925799 0.8979687 -0.1393854 -0.4308435 0.8915973 -0.1338683 -0.410146 0.9021416 -0.1263878 -0.4284517 0.8946816 -0.1464207 -0.2547418 0.9558597 -0.1380365 -0.2671285 0.9537235 -0.1493449 -0.09191596 0.9845037 -0.1467761 -0.09604287 0.9844961 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.004576027 0.480444 -0.8770134 0.03163337 0.7170166 -0.6963379 0.03162765 0.7169897 -0.6963659 -0.04127901 0.5551026 -0.830757 0.03335112 0.8950719 -0.4446731 0.006977021 0.8314289 -0.5555874 0.006792247 0.8984679 -0.4389865 -0.01745301 0.8313542 -0.555469 0.01421153 0.9880965 -0.1531776 0 0.9807878 -0.195078 0.004576086 0.4804712 -0.8769986 -0.005522251 0.5555874 -0.8314397 0.001306653 0.3177626 -0.9481695 0.01002138 0.1950716 -0.9807378 0 0.1454746 -0.989362 0.9956381 0.0932995 0 0.9807847 0.1950712 -0.002968728 0.8314583 0.5555856 0.001330077 0.6668203 0.7450692 -0.01491999 0.667258 0.7446778 -0.01488924 0.7790548 0.6269214 -0.006568968 0.8622828 0.5064268 -2.43038e-4 0.9564552 0.2918791 1.9067e-4 0.9565822 0.2914624 1.90669e-4 0.1950802 0.9807873 0 0.06133967 0.9980624 -0.01042884 0.2371286 0.9714782 -4.22812e-4 0.453266 0.8913753 2.50303e-4 0.5555818 0.8314619 2.4791e-4 0.4619331 0.8868832 -0.007480323 0.6524143 0.7578613 0.001374304 0.9800508 0.1104149 -0.1652542 0.8264387 0.3127922 -0.4681454 0.826436 0.3128017 -0.4681439 0.5481209 0.4646764 -0.6954419 0.5481118 0.4646906 -0.6954395 0.8264445 0.1098387 -0.5522002 0.5481173 0.1631727 -0.8203303 0.5481212 0.1631684 -0.8203287 0.5481247 0.1631695 -0.8203262 0.1914788 0.1914765 -0.9626383 0.9800513 0.1949254 -0.03877586 0.826432 0.5522165 -0.1098507 0.8264282 0.5522243 -0.1098397 0.5481181 0.8203311 -0.1631674 0.5481341 0.8203161 -0.1631883 0.1915015 0.9626293 -0.1914991 0.191471 0.9626414 -0.1914686 0.9800511 0.1652519 -0.1104158 0.826436 0.4681453 -0.3127993 0.8264333 0.4681533 -0.3127944 0.5481053 0.6954597 -0.464668 0.5481188 0.6954416 -0.4646795 0.1915037 0.8160806 -0.545288 0.1914979 0.8160926 -0.5452719 0.8264256 0.109808 -0.5522345 0.8264356 0.1098368 -0.5522137 0.9800505 0.0387721 -0.1949301 0.1914833 0.1914716 -0.9626384 0.1914843 0.545315 -0.816067 0.1914792 0.5453008 -0.8160777 0.1914827 0.5452957 -0.8160803 0.1914815 0.8160641 -0.5453202 0.1950885 0 -0.9807856 0.2579166 -0.08354032 -0.9625487 0.5546988 0.05599397 -0.830165 0.5546917 0.05599397 -0.8301697 0.7027106 -0.1112426 -0.7027252 0.980788 0 -0.1950768 0.9625524 -0.08353918 -0.2579036 0.8301482 0.05601298 -0.5547218 0.83017 0.05601298 -0.5546894 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.1608095 -0.7036648 0.6920954 0.1608105 -0.7036666 0.6920933 0.1608091 -0.7036665 -0.6920937 0.1608073 -0.7036682 -0.6920924 -0.1062614 -0.6970612 -0.7090939 -0.106264 -0.6970601 -0.7090947 -0.1062636 -0.6970592 -0.7090956 -0.4182229 -0.6970579 -0.5824087 -0.4182308 -0.6970533 -0.5824084 -0.4182309 -0.6970464 -0.5824167 -0.6379817 -0.69704 -0.3272835 -0.6379548 -0.6970595 -0.3272945 -0.6379478 -0.6970733 -0.327279 -0.7170007 -0.6970725 0 -0.7170006 -0.6970725 0 -0.7170006 -0.6970725 0 -0.6379473 -0.697069 0.327289 -0.6379647 -0.697053 0.3272892 -0.6379803 -0.6970416 0.3272827 -0.4182308 -0.6970496 0.5824131 -0.4182268 -0.6970537 0.5824109 -0.4182184 -0.6970584 0.5824112 -0.1062641 -0.6970592 0.7090954 -0.1062692 -0.6970512 0.7091026 -0.1062521 -0.6970589 0.7090975 0.7197418 -0.6632512 -0.2051091 0.3757531 -0.7009419 0.6062097 0.374673 -0.7016081 0.6061074 0.3751364 -0.7023707 0.6049364 0.5321499 -0.7464293 0.3995743 0.3744072 -0.7010823 -0.6068797 0.2887123 -0.7480883 -0.5975025 0.3509643 -0.7465192 -0.5652725 0.4875126 -0.6596202 -0.5720424 0.5448594 -0.7288067 -0.4146915 0.6240651 -0.6781638 -0.3881196 0.5812124 -0.6798618 -0.4471915 0.6425319 -0.6525585 -0.4016467 0.6194258 -0.6194412 -0.4822908 0.6871705 -0.6931156 -0.217687 0.5499054 -0.684908 0.4780222 0.5499501 -0.6849105 0.4779669 0.5840759 -0.6787879 0.4450868 0.6576787 -0.7083047 0.2564432 0.6711196 -0.7045679 0.2306132 0.6999337 -0.6592842 0.2746585 0.7299372 -0.6833982 0.01259022 0.7345546 -0.678304 0.01825815 0.7346206 -0.678359 0.01271438 0.7398543 -0.6724464 0.0207678 0.7382621 -0.6742657 0.01829773 -0.4181012 -0.7020325 0.5764909 -0.4181002 -0.7020224 0.5765039 0.5764909 -0.7020304 -0.4181046 0.5764917 -0.7020298 -0.4181045 -0.4180892 -0.7020262 0.5765073 -0.1491621 -0.6960273 0.7023509 -0.1491587 -0.6960154 0.7023633 -0.1491619 -0.6960146 0.7023636 0.2039958 -0.6960182 0.6884362 0.2039898 -0.6960263 0.6884298 0.2039068 -0.6960099 0.6884709 0.5077161 -0.6960231 0.5077168 0.5077108 -0.6960375 0.5077021 0.6884327 -0.6960343 0.2039527 0.688417 -0.6960406 0.2039843 0.6884377 -0.6960147 0.2040032 0.7023638 -0.6960126 -0.1491698 0.7023628 -0.6960172 -0.1491528 0.7023537 -0.6960258 -0.1491553 0.5764915 -0.7020296 -0.4181051 0.4484272 -0.6865106 -0.5723778 0.3607764 -0.7033621 -0.6124722 0.3035274 -0.7526561 -0.5842773 0.2088882 -0.7194355 -0.6624034 0.09742707 -0.7625346 -0.6395693 0.09780627 -0.7624594 -0.6396012 0.2120793 -0.736229 -0.6426425 -0.5376003 -0.7064006 0.4604173 -0.5417846 -0.7036066 0.4597903 0.4487361 -0.6864317 -0.5722301 0.350736 -0.7504668 -0.5601642 0.4310534 -0.728641 -0.5322363 0.4681513 -0.6991416 -0.540403 0.4835749 -0.7070761 -0.5159444 0.2119877 -0.7362781 -0.6426163 0.1210584 -0.813372 -0.5690087 0.005408763 -0.7823985 -0.6227545 -0.1276582 -0.8409278 -0.5258741 0.02139931 -0.8090444 -0.5873579 -0.09675347 -0.8720033 -0.4798427 -0.2242848 -0.8673104 -0.4443748 -0.2015818 -0.749781 -0.6302328 -0.3850757 -0.9016998 -0.1966065 -0.3552646 -0.8857321 -0.298774 -0.4222503 -0.8778982 -0.2258305 -0.4616525 -0.7912203 -0.401058 -0.5089062 -0.85943 -0.04893445 -0.5258409 -0.8504558 0.0147075 -0.5329007 -0.8438286 -0.06300956 -0.5580516 -0.8298062 -4.23351e-4 -0.5867652 -0.8041175 -0.09540218 -0.5998769 -0.7784546 0.1848137 -0.6209459 -0.76926 0.1505495 -0.6303569 -0.7554675 0.1786596 -0.6297514 -0.7624268 0.1487232 -0.6311559 -0.7548744 0.178345 -0.6501895 -0.7463366 0.1422509 -0.6021573 -0.7253167 0.3336498 -0.5976796 -0.7278881 0.3360922 -0.5987513 -0.7283419 0.3331888 -0.5966306 -0.7288029 0.3359735 -0.5411747 -0.7023414 0.4624353 -0.1459999 0.01384544 -0.9891877 -0.10683 -0.05368232 -0.9928271 -0.1112434 -0.0177648 0.9936343 -0.03988236 0.0768432 0.9962452 0.2001739 0.1396019 0.9697638 0.438001 0.1769062 0.8813962 0.4797002 0.3273333 0.8140888 0.4796379 0.3274378 0.8140836 -0.8725306 -0.48843 -0.01123738 -0.8795866 -0.4740285 0.04030495 -0.8855682 -0.4640986 0.0195288 -0.8717858 -0.4855172 0.06528913 -0.8405258 -0.5205554 0.1501284 -0.8018619 -0.5398878 0.2560051 -0.8795781 -0.4745263 -0.03416514 -0.8712491 -0.486853 -0.06244307 -0.8226568 -0.5332644 -0.1971417 -0.8509963 -0.5105907 -0.122892 -0.8641556 -0.4960565 -0.08463549 -0.8706061 -0.4919606 -0.004468381 -0.8680343 -0.4961035 -0.01994466 -0.8730757 -0.4874432 0.01173895 -0.8091961 -0.5310152 -0.2514449 -0.8186983 -0.5229773 -0.2371238 -0.8186453 -0.5230728 -0.2370964 -0.7686631 -0.5153803 -0.378867 -0.7592075 -0.5149945 -0.3979757 0.09410876 0.09150648 -0.9913476 0.09411227 0.09149789 -0.9913481 -0.6755323 -0.4812425 -0.5586248 -0.5420727 -0.303 -0.7838036 -0.3240045 -0.1961477 -0.9254983 -0.4281538 -0.20748 -0.879566 -0.220063 -0.1404709 -0.9653187 -0.004145503 -0.001480519 -0.9999903 0.07621431 -0.1420201 -0.9869253 0.3420162 -0.1178925 -0.9322693 0.341989 -0.1178967 -0.9322789 0.282544 -0.01548641 -0.9591293 0.4507599 -0.06848138 -0.8900145 0.5094408 -0.1772264 -0.8420575 0.6491441 -0.04830724 -0.75913 0.7022716 -0.1452203 -0.6969403 0.7500861 -0.1929801 -0.6325578 0.7500496 -0.1929986 -0.6325955 0.7110911 -0.1128354 -0.6939869 0.8315279 -0.1120104 -0.5440727 0.8904505 -0.235319 -0.3895161 0.9151788 -0.1587459 -0.3704692 0.956412 -0.2407156 -0.1653242 0.9720366 -0.2306143 0.04429274 0.9720265 -0.2306724 0.04421448 0.9627033 -0.2107361 -0.1696841 0.9702983 -0.2382879 0.04171431 0.9593119 -0.2068514 0.19218 0.9520266 -0.2216294 0.2110113 0.924081 -0.1699852 0.3423146 0.8924313 -0.2232483 0.39208 0.8648987 -0.1608519 0.4754756 0.7986534 -0.08993506 0.5950331 0.7986068 -0.09004682 0.5950787 0.8434162 -0.1719216 0.5090109 -0.8326743 -0.5283659 -0.16578 -0.8311353 -0.5311363 -0.1646465 -0.8287108 -0.5327231 -0.1715937 -0.8247807 -0.5404289 -0.1663535 -0.8246498 -0.5402715 -0.1675099 -0.8172984 -0.5544027 -0.1570385 -0.8158293 -0.5557151 -0.1600099 -0.800298 -0.5873497 -0.120597 -0.7992165 -0.5884932 -0.1221824 -0.7873327 -0.6137247 -0.05872917 -0.7869291 -0.6142019 -0.05914872 -0.7835631 -0.62112 0.01545411 -0.7835326 -0.6211587 0.01544034 -0.7896093 -0.6095397 0.07055848 -0.7899415 -0.609093 0.0706973 -0.7983885 -0.5903156 0.1187574 -0.7995346 -0.5888835 0.1181555 -0.8098655 -0.5684219 0.1449642 -0.8102446 -0.5679106 0.1448489 -0.8185384 -0.5506221 0.1637384 -0.8206042 -0.5483998 0.1608309 -0.8284066 -0.5333975 0.170967 -0.8309927 -0.5310535 0.16563 -0.8320947 -0.5290507 0.1665042 -0.8331254 -0.5279195 0.1649332 -0.8327038 -0.5286781 0.1646325 -0.8821249 -0.4699531 0.03161907 -0.7124171 -0.527758 -0.4625293 -0.6968801 -0.5547108 -0.4545923 -0.6813851 -0.5510389 -0.481737 -0.6555495 -0.5968177 -0.4626699 -0.6259104 -0.5969884 -0.5018377 -0.602663 -0.6444333 -0.470641 -0.6001579 -0.6419965 -0.4771277 -0.5712963 -0.6952115 -0.4362356 -0.5476937 -0.6988946 -0.459976 -0.4979451 -0.80053 -0.3334706 -0.4822772 -0.8047361 -0.3461335 -0.4481322 -0.8791329 -0.1621817 -0.4417219 -0.8815632 -0.1665179 -0.4322874 -0.90073 0.04258102 -0.4344562 -0.899647 0.04339438 -0.451905 -0.8702539 0.1960607 -0.4560946 -0.8676637 0.197832 -0.479299 -0.8119833 0.3330997 -0.4962808 -0.8032582 0.3293657 -0.5267114 -0.746007 0.4074906 -0.5338634 -0.7411507 0.4070448 -0.5608502 -0.6820914 0.4692528 -0.5878633 -0.6722025 0.4500674 -0.6237769 -0.6033905 0.4968121 -0.6523608 -0.5966674 0.4673472 -0.6673892 -0.5699903 0.4792732 -0.6744349 -0.5666195 0.4733709 -0.6866705 -0.5441358 0.4820789 -0.7853946 -0.5284298 0.3223621 0.7239535 -0.2014505 0.6597796 0.6581969 -0.07119202 0.7494723 0.5256662 -0.154266 0.8365866 0.494783 -0.09641385 0.8636516 0.4563797 -0.1026147 0.8838484 -0.5224587 -0.4542176 -0.7216116 -0.4839294 -0.5222872 -0.7021597 -0.4455983 -0.5060707 -0.7384677 -0.3989198 -0.5882757 -0.7034165 -0.3278933 -0.5693597 -0.753867 -0.2883814 -0.6503698 -0.7027482 -0.2815883 -0.642719 -0.7124749 -0.2363877 -0.7258596 -0.6459478 -0.1836099 -0.7147746 -0.6748219 -0.1089316 -0.8678404 -0.4847545 -0.07589447 -0.8620002 -0.5011944 -0.02514916 -0.97202 -0.2335481 -0.01296234 -0.970665 -0.2400865 3.82788e-4 -0.9981257 0.0611965 -0.003020942 -0.9980368 0.06255775 -0.02559632 -0.9590154 0.2821954 -0.03471142 -0.9572969 0.2870153 -0.07044082 -0.8740182 0.4807602 -0.1051388 -0.8705109 0.4807873 -0.1480534 -0.789136 0.5961079 -0.1642283 -0.7840039 0.5986376 -0.205832 -0.6934321 0.6904963 -0.2670058 -0.6923965 0.6702947 -0.3246278 -0.5817221 0.7457991 -0.3912881 -0.5857526 0.70978 -0.4177732 -0.5391177 0.7313123 -0.4345858 -0.5358855 0.723852 -0.4675421 -0.473615 0.7463867 -0.4048963 -0.4583535 0.7911833 -0.4698953 -0.3132042 0.8252887 -0.469958 -0.3132093 0.8252512 -0.4842022 -0.2417372 -0.8408992 -0.4024643 -0.3871495 -0.8295407 -0.2798314 -0.3255621 -0.9031631 -0.2190854 -0.433735 -0.8739998 -0.1555553 -0.3986929 -0.9037957 -0.09438711 -0.5073127 -0.8565774 0.01838141 -0.4552144 -0.8901922 0.0698589 -0.5574602 -0.8272593 0.08071428 -0.5419731 -0.8365109 0.1338328 -0.6433698 -0.7537666 0.210565 -0.6035348 -0.7690305 0.2973713 -0.7811565 -0.548967 0.3403081 -0.7553771 -0.5599964 0.3994156 -0.8793273 -0.2593272 0.415134 -0.8697821 -0.2667263 0.4296925 -0.9004555 0.067411 0.4253365 -0.9023588 0.06955301 0.4048812 -0.8594331 0.3121634 0.3923731 -0.8618635 0.3213015 0.3485294 -0.7697 0.534873 0.3024261 -0.7813102 0.5459789 0.2573131 -0.6901098 0.6764159 0.2338898 -0.6888635 0.6861215 0.1834936 -0.5849543 0.790037 0.09317964 -0.6069183 0.789283 0.02362853 -0.4726684 0.8809236 -0.08150529 -0.4997602 0.8623204 -0.1150152 -0.4400973 0.8905537 -0.1416199 -0.4394707 0.8870227 -0.1781789 -0.3720251 0.9109607 -0.3075106 -0.4133083 0.857096 -0.3876965 -0.2701037 0.881326 -0.4284254 -0.2850668 0.8574314 0.411946 -0.02557384 0.9108493 0.3650428 -0.07123672 0.9282615 0.2195572 -0.137117 0.9659159 -0.05429071 -0.1173375 0.991607 0.1549544 -0.02406644 0.9876285 -0.1171466 -0.1642853 0.979432 -0.0457502 -0.2892994 0.9561448 0.1278239 -0.2173947 0.967678 0.167749 -0.2890584 0.9424996 0.2024877 -0.2860195 0.936585 0.2373825 -0.3497436 0.906272 0.3682432 -0.2934625 0.8821999 0.4381543 -0.4290816 0.7898796 0.5411321 -0.3766753 0.7518589 0.5906049 -0.4722692 0.65433 0.6165903 -0.4672173 0.6336595 0.6556376 -0.5526265 0.5145322 0.7019405 -0.5204108 0.4862633 0.7438313 -0.6001703 0.2941268 0.7559651 -0.591611 0.2802022 0.7715629 -0.6329942 0.06331652 0.7756354 -0.6282868 0.06037819 0.7624289 -0.6002249 -0.2417278 0.7485098 -0.6199606 -0.2353336 0.6923401 -0.5065538 -0.5138759 0.65067 -0.5577279 -0.5153331 0.56646 -0.386073 -0.7280595 0.4824583 -0.4618965 -0.7442349 0.4298366 -0.3556322 -0.8299195 0.4177812 -0.3798711 -0.8253222 0.3610058 -0.2724391 -0.891881 0.2212774 -0.3643544 -0.9045896 0.1534646 -0.2419837 -0.9580671 0.0691356 -0.2988386 -0.951796 0.001446843 -0.1800388 -0.9836584 -0.1698319 -0.2757055 -0.9461203 -0.2352701 -0.162346 -0.9582754 -0.3897685 -0.242129 -0.8885124 0.1581392 0 -0.9874169 0.2009152 -0.01697838 -0.9794614 0.2012453 -0.01697814 -0.9793937 0.1580839 -0.01785206 -0.9872643 0.1104569 0 -0.993881 0.249391 0 -0.9684029 0.2493498 5.18426e-5 -0.9684135 0.09226512 0 -0.9957345 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.001458466 0.5627255 0.8266425 0.001427233 0.4170598 0.9088779 0 0.2476086 0.9688602 -8.45835e-5 0.2466692 0.9690997 -1.26816e-4 0.2476096 0.9688599 1.1988e-4 0.407398 0.9132508 0.007080376 0.8137643 0.5811519 0.002090573 0.7936314 0.6083952 0.003421843 0.7713015 0.6364609 0.003383994 0.7716202 0.6360744 0.006189763 0.7487661 0.6628054 0.01060354 0.7139344 0.7001325 0.01978111 0.6712646 0.7409539 0.001885294 0.5625807 0.8267403 0.001089334 0.5169454 0.8560177 0.001089334 0.5169889 0.8559914 0.03313213 0.6123874 0.7898634 0.03313159 0.6123894 0.7898616 -0.04186153 0.8046899 0.5922178 -0.00857073 0.6930508 0.7208378 0.001238942 0.503404 -0.8640503 0.001238942 0.5034542 -0.8640211 -0.009704828 0.3557392 -0.9345349 -0.008980154 0.3518384 -0.9360177 0 0.2121538 -0.9772363 -0.00250864 0.6416729 -0.7669743 -0.0117613 0.693262 -0.7205896 -0.001592576 0.7603193 -0.6495476 0.002568125 0.9788871 -0.204385 -0.006979763 0.9314585 -0.3637807 -0.03030198 0.8584072 -0.512073 -0.00773561 0.9201142 -0.3915739 0.00142914 0.8577396 -0.5140824 0.00142914 0.8578042 -0.5139747 -0.01130133 0.9999362 0 -0.006166934 0.9992828 -0.0373612 0.002568125 0.9788741 -0.2044482 0.001265287 0.8095879 0.5869974 0.001265347 0.8035733 0.5952044 -0.004229366 0.9201334 0.3915821 -0.01814723 0.8922036 0.4512687 -0.01815074 0.8921939 0.4512878 -0.001200139 0.9553353 0.2955217 0.001131713 0.9914311 0.1306257 0.001131713 0.9914417 0.1305449 -0.001121699 0.6649582 -0.7468798 0 0.9914384 -0.1305754 0.008209347 0.9725572 -0.2325192 -0.001854658 0.874681 -0.4846954 -0.01142811 0.7665779 -0.6420497 0.002576589 0.6648774 -0.746948 -0.002023935 0.8757653 -0.4827326 -0.002038002 0.8759013 -0.482486 -0.005601584 0.7176062 -0.6964266 -0.005596101 0.7175412 -0.6964936 -0.00112164 0.6576135 -0.7533546 0.003681302 0.7300716 -0.6833608 0.008919954 0.7946784 -0.6069651 0.009003818 0.7951708 -0.6063186 0.003350913 0.7621495 -0.6473924 -0.00177288 0.9235326 -0.3835158 -0.00177288 0.9234891 -0.3836207 0 0.9858138 -0.1678425 -0.01357811 0.9966933 -0.08011293 0.02288395 0.8744038 -0.484659 -0.01110255 0.9646144 -0.2634308 -0.001854538 0.8758786 -0.4825279 0.001737833 0.3802413 -0.9248856 0.001396119 0.3869011 -0.9221202 0 0.1908666 -0.981616 -0.009686231 0.894348 0.4472673 0.005250275 0.9995576 0.02927565 -5.75976e-6 0.9885307 0.1510205 0 0.9885562 0.1508525 -0.001841962 0.6197507 0.7847965 0.001580417 0.7056885 0.7085205 -0.001746535 0.8445823 0.5354232 5.40452e-4 0.8930971 0.4498637 5.24487e-4 0.8446041 0.535391 0.003997325 0.9741626 0.2258121 0 0.3251432 0.9456649 -0.004720509 0.2323087 0.9726306 0.007376909 0.619751 0.7847638 -0.002058506 0.4497056 0.8931745 -0.001827895 0.706769 0.7074421 0.1444423 0 0.9895132 0.1444427 1.39784e-4 0.9895132 -0.1544106 -4.44404e-4 0.9880067 -0.1544125 2.89328e-4 0.9880064 -0.154415 0 0.9880061 0.1444432 0 0.989513 -0.1544369 0 0.9880027 -0.4898 0 0.8718348 -0.4898045 -0.001625895 0.8718308 -0.7717887 -0.002775132 0.635873 -0.7717961 -4.66915e-4 0.6358699 -0.7717933 0 0.6358734 -0.4898144 0 0.8718268 -0.7718107 0 0.6358524 -0.9308753 0 0.3653368 -0.930876 -0.002134144 0.365329 -0.930881 0 0.3653225 -0.9735272 0 0.2285713 -0.9735355 0.003490447 0.228509 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.04358738 0.9877591 -0.1497742 -0.03684484 0.991394 -0.1256203 -0.04466938 0.9877535 -0.1494916 -0.1155385 0.908593 -0.4013848 -0.1255183 0.8921801 -0.4338892 -0.1160635 0.9085147 -0.4014104 -0.1267077 0.8922462 -0.4334075 -0.1924846 0.7230135 -0.6634765 -0.1972646 0.7081881 -0.6779057 -0.1930534 0.7228965 -0.6634387 -0.197701 0.7082428 -0.6777215 -0.2467163 0.4665498 -0.8493894 -0.2515963 0.4397621 -0.8621534 -0.247815 0.4663753 -0.8491654 -0.2518863 0.4398615 -0.8620181 -0.2748605 0.1618438 -0.9477648 -0.2766219 0.1413694 -0.9505236 0 -0.3275144 0.9448463 0 -0.3275144 0.9448462 -0.003382205 -0.1292845 0.9916018 -4.19846e-4 -0.1300945 0.9915016 -0.006397962 -0.3052513 0.9522503 -9.85939e-5 -0.1557281 0.9878 4.06392e-4 -0.1329466 0.9911231 0.001928329 -0.1265394 0.9919598 3.85996e-4 -0.136338 0.9906622 -0.006685554 -0.3046193 0.9524508 0.05110526 -0.3984232 0.9157767 0.008057892 -0.3381973 0.9410408 -0.03263205 -0.6263279 -0.7788766 -0.02004784 -0.6796147 -0.7332952 -0.01103025 -0.7188088 -0.6951203 -0.01102948 -0.7188134 -0.6951155 -0.05692195 -0.8233839 -0.5646228 -0.01803731 -0.8136529 -0.5810712 -0.01103013 -0.8123271 -0.5830978 -0.002462804 -0.4487575 -0.8936502 2.83905e-4 -0.5421829 -0.8402605 2.76926e-4 -0.7075356 -0.7066778 -0.05652165 -0.5539366 -0.8306379 -0.03270334 -0.6261173 -0.7790428 0 -0.3650058 -0.9310052 -0.03343242 -0.258107 -0.9655377 -0.01568102 -0.3621867 -0.9319736 0 -0.7928189 -0.6094575 0 -0.9314522 -0.3638638 0 -0.9314522 -0.3638638 0 -0.9992013 0.03995859 0 -0.9992013 0.03995859 0 -0.8994271 0.4370709 0 -0.8994271 0.4370709 0 -0.6488591 0.7609087 0 -0.6488591 0.7609087 0 -0.3275144 0.9448462 -0.01348072 -0.285633 0.9582443 -0.9979714 -0.06337565 0.006048321 -0.9984307 -0.05545419 0.007801473 -0.9995311 -0.02569079 0.01666516 -0.9979446 -0.06408172 0 -0.9996946 -0.01271116 0.02119278 -0.9979763 -0.0635879 3.01408e-4 -0.9999997 -8.82758e-4 0 -0.9992391 -0.03680354 0.01291543 -0.9992405 -0.03675633 0.01292955 -0.9988339 -0.04723054 0.01001054 -0.9975535 -0.06975042 0.004684627 -0.9975629 -0.06961476 0.004713177 -0.9970396 -0.07681483 0.003391563 -0.9956106 -0.09349441 -0.004293978 -0.9964644 -0.0837233 -0.007007718 -0.9971265 -0.07516336 -0.009455323 -0.9971272 -0.07515209 -0.009459018 -0.9976378 -0.06762629 -0.01206016 -0.9981706 -0.05847954 -0.01534855 -0.9986122 -0.04886209 -0.01964783 -0.9989945 -0.03715282 -0.02509611 -0.9916185 -0.1278736 0.01847052 -0.9995338 -0.02954131 -0.007716536 -0.9997569 -0.01883536 -0.01145982 -0.9998461 -0.008858382 -0.01513928 -0.9990864 -0.04273653 0 -0.9990864 -0.04273653 0 -0.9772425 -0.2121248 0 -0.9815494 -0.1911872 0.002890765 -0.9917864 -0.1278978 -0.001445233 -0.9946057 -0.1037184 -0.001444816 -0.9891005 -0.146966 0.009015202 0 -0.9900071 -0.1410177 0.002504229 -0.4668647 0.8843253 -0.005615472 -0.3121695 0.9500098 -0.009087145 -0.2588126 0.9658849 -2.90737e-4 -0.1483845 0.9889298 -3.25262e-4 -0.8365786 0.547847 -0.004057288 -0.7329562 0.6802638 -0.007705152 -0.707082 0.7070897 -0.002192199 -0.6084162 0.793615 0.002504229 -0.4668413 0.8843377 0 -0.9942251 0.1073142 -0.007716894 -0.9707963 0.2397815 -0.009121716 -0.965888 0.2587993 9.8898e-4 -0.9166524 0.3996841 9.8898e-4 -0.91676 0.3994372 0.001200973 -0.4060919 -0.9138314 -4.40134e-4 -0.5536911 -0.832722 -0.005222678 -0.7070933 -0.7071011 -0.008653998 -0.6857802 -0.7277573 -0.001941502 -0.7979471 -0.6027246 0.002411782 -0.8876264 -0.4605579 0.002355396 -0.965926 -0.2588077 -0.02735453 -0.8876785 -0.4596503 -0.01264154 -0.9523887 -0.3046246 -0.02096962 -0.1109833 -0.993601 -0.009961605 -0.2471206 -0.9689336 0.001200973 -0.4061397 -0.9138103 0 -0.003972351 0.9999921 0 0.2588232 0.9659247 0 0.2588232 0.9659247 0 0.7071031 0.7071104 0 0.7071031 0.7071104 0 0.9659283 0.2588101 0 0.9659283 0.2588101 0 0.9659287 -0.2588084 0 0.9659287 -0.2588084 0 0.7071031 -0.7071104 0 0.7071031 -0.7071104 0 0.2588232 -0.9659247 0 0.2588232 -0.9659247 0 -0.2588232 -0.9659247 0 -0.3293291 -0.9442151 0.001534461 -0.3906667 -0.920531 0.004440426 -0.3292648 -0.9442272 0.003902256 -0.7637448 -0.6455065 -0.00195533 -0.6224856 -0.7826288 -0.00195533 -0.622353 -0.7827343 0 -0.9986662 -0.05163204 -4.0645e-7 -0.9986709 -0.05154216 0.002927958 -0.9683411 -0.2496135 0.001863539 -0.9727665 -0.2317796 -0.001218199 -0.8433875 -0.5373045 -0.001218199 -0.8433275 -0.5373988 0 -0.3906602 0.920535 0 -0.3906602 0.920535 0 -0.7637506 0.6455115 0 -0.7637506 0.6455115 0 -0.9727682 0.2317801 0 -0.9727682 0.2317801 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.2227622 -0.1845358 0.9572479 -0.9968525 -0.07926172 -0.001665353 0.1426028 -0.7006309 0.6991286 0.01796317 -0.9837269 0.1787699 0.001813113 -0.9931623 0.1167282 0.01114249 -0.9927486 0.1196911 0.02863883 -0.9909991 0.1307693 -0.02197581 -0.9971594 -0.07204192 -0.03351211 -0.998169 0.05035525 0.05084884 -0.9926797 0.1095514 -0.02232444 -0.9970238 -0.07379108 0.02897506 -0.9909518 0.1310538 0.02089434 -0.9923041 0.1220487 0.01919043 -0.9932895 0.1140511 0.09940946 -0.8937994 0.4373106 0.1957063 -0.4500993 0.871269 0.2777074 -0.1528276 0.9484315 0.4868718 -0.3688868 0.7917565 0.2099071 -0.1223648 0.970034 0.2171741 -0.1491382 0.9646726 0.06723552 -0.1844357 0.9805421 -0.9622202 -0.2722653 -0.001975655 -0.9622575 -0.2721334 -0.001975774 -0.9812556 -0.189314 -0.03602373 -0.8193649 -0.5728183 -0.02281165 -0.2256028 -0.9742193 -4.20871e-4 -0.442107 -0.8968877 -0.01157087 -0.5538664 -0.8316931 -0.03897124 -0.5034399 -0.8638604 -0.01712775 -0.7514952 -0.6597303 -0.003297686 -0.7513922 -0.6598476 -0.003296732 0.2636712 -0.9646106 0.001945793 0.03000915 -0.9995269 0.006751418 -0.01631706 -0.9998514 -0.005563855 -0.4921773 -0.8704559 0.008243024 -0.5037515 -0.8638391 0.004057466 -0.4633425 -0.8854302 0.03642731 -0.5032002 -0.864167 -0.002207994 -0.02118843 -0.9997625 -0.005100369 -0.02117854 -0.9997726 0.002553105 -0.08166873 -0.9966593 4.70232e-4 -0.1400712 -0.9898403 -0.02441781 0.0782327 -0.9969239 -0.004747211 -0.2663161 -0.9637984 0.01298344 -0.2663148 -0.9637985 0.01299571 -0.1579068 -0.9873072 0.01702457 -0.1385524 -0.9903115 0.009293556 -0.1116412 -0.9932142 0.0325855 -0.1105073 -0.99334 0.03261655 -0.1385535 -0.9903115 0.009289383 -0.09885907 -0.9938904 0.04907947 -0.1155158 -0.9921049 0.04882729 -0.1155174 -0.9921049 0.04882347 -0.09527534 -0.9914495 0.08916509 -0.09527534 -0.9914495 0.08916509 -0.09069335 -0.9931339 0.07389032 -0.1088111 -0.9917551 0.06768971 -0.1088145 -0.9917551 0.06768506 -0.06760406 -0.9937309 0.08904206 -0.07552325 -0.9927773 0.09321749 -0.0576514 -0.9921074 0.1113515 -0.05765074 -0.9921074 0.1113519 -0.0491352 -0.9933377 0.1042398 -0.03855669 -0.9922085 0.1184716 0.01823616 -0.991404 0.129559 0.01823735 -0.9914041 0.1295588 0.004729747 -0.9939448 0.1097787 9.75185e-5 -0.9926174 0.1212872 -0.02350634 -0.9921896 0.1225044 -0.0176925 -0.9937156 0.1105275 -0.03855788 -0.9922086 0.1184712 -0.7717969 -0.1847961 0.6084242 -0.7662143 -0.1940032 0.6125996 -0.7704244 -0.1940551 0.6072798 -0.8777043 -0.1431238 0.4573301 -0.8952597 -0.1015582 0.4338154 -0.9163653 -0.1994982 0.3470951 0.0672335 -0.1844357 0.9805423 0.03880155 -0.1141826 0.9927018 -0.07121753 -0.1774412 0.9815512 -0.1915454 -0.1841599 0.9640517 -0.2252317 -0.111761 0.9678741 -0.0712518 -0.1774411 0.9815487 -0.7718048 -0.1847958 0.6084142 -0.6644845 -0.1577726 0.7304575 -0.6335013 -0.1235466 0.7638144 -0.5223667 -0.2224269 0.8232005 -0.4237162 -0.2216199 0.8782649 -0.5357685 -0.01421189 0.8442454 -0.3771327 -0.1576061 0.9126507 0.142597 -0.7006584 0.6991023 0.1340518 -0.8633782 0.4864239 0.02052199 -0.8621931 0.506164 0.02170413 -0.8635723 0.5037577 -0.09768253 -0.8615818 0.4981313 -0.09509307 -0.8633403 0.4955815 -0.2191386 -0.8613296 0.4583554 -0.2151815 -0.8633078 0.4565049 -0.3223618 -0.8615214 0.3922546 -0.3172536 -0.8637206 0.3915826 -0.3944013 -0.8622833 0.3176712 -0.3905575 -0.8638374 0.3181977 -0.4568706 -0.8610244 0.2233968 -0.4511067 -0.8639134 0.2239561 -0.4857037 -0.8627533 0.1405304 -0.4834606 -0.8639176 0.141111 -0.502923 -0.8626886 0.05326229 -0.5001982 -0.8642301 0.05392831 -0.503506 -0.8638836 0.01367068 -0.1709137 -0.9852756 0.004529654 -0.9842109 -0.1710961 -0.04533189 -0.9851874 -0.1714733 -0.001644909 -0.9928993 -0.1178164 0.01644074 -0.9855591 -0.1675227 0.02468997 -0.9807934 -0.1657083 0.1028841 -0.9931287 -0.07942247 0.08595037 -0.9561789 -0.218314 0.1950923 -0.9378637 -0.2179715 0.2700002 -0.9798184 6.67065e-4 0.1998891 -0.916359 -0.1994984 0.3471117 0.1956948 -0.4502384 0.8711997 0.2064566 -0.5266096 0.8246563 0.03327089 -0.5237776 0.8512051 0.03444623 -0.526305 0.8495978 -0.1661434 -0.5226479 0.8362031 -0.1636645 -0.5259715 0.8346065 -0.3705833 -0.5221495 0.7681328 -0.3668537 -0.5259647 0.7673197 -0.5443428 -0.5224375 0.6563156 -0.5397257 -0.5266695 0.6567462 -0.6653317 -0.5238045 0.5319424 -0.6619583 -0.526816 0.5331755 -0.7677843 -0.5216224 0.3720448 -0.7635067 -0.5269534 0.3733332 -0.81803 -0.5247532 0.2355015 -0.8164464 -0.5268896 0.2362254 -0.8466619 -0.5246672 0.08881384 -0.8449063 -0.527377 0.08948022 -0.8500601 -0.5264977 0.01407557 -0.8494706 -0.5274441 0.01422703 -0.8496533 -0.5269615 -0.02002298 -0.8691103 -0.4918768 -0.05200558 0.4940724 -0.7500141 0.4397399 0.1920564 -0.9603307 0.2021863 0.8082326 -0.4480432 0.382122 0.2222251 -0.9649004 0.13994 0.5884753 -0.7572649 0.2832785 0.6536341 -0.7107063 0.2601136 0.4042711 -0.8915457 0.2042336 0.2201355 -0.9681246 0.1194781 0.4126909 -0.9102436 0.03380322 0.1325381 -0.9896339 0.05530345 0.8814594 -0.1806162 0.4363565 0.8795961 -0.1523913 0.4506524 0.5286291 -0.3957642 0.7509474 0.5286286 -0.3957651 0.7509472 0.6288043 -0.1314306 0.7663753 0.4828119 -0.6726367 0.5607607 0.4828149 -0.6726316 0.5607643 0.1920554 -0.9603306 0.2021875 0.07658523 -0.9864194 0.1452974 0.3193748 -0.8792165 0.3535224 0.2217218 -0.9650621 0.1396229 0.1781796 -0.9715208 0.1562029 0.4900533 -0.7584743 0.4296098 0.4370878 -0.7530018 0.4918766 0.2588874 -0.8733794 0.4125357 0.6376913 -0.1174854 0.7612798 0.7138081 -0.15711 0.6824913 0.7350792 -0.1575361 0.6594247 0.885633 -0.1532251 0.4383789 0.8101712 -0.4453337 0.381183 0.7546584 -0.4370712 0.4893459 0.7221035 -0.04294174 0.690451 0.7956398 -0.1986198 0.5722826 0.8222177 -0.1992616 0.5331537 0.8109487 -0.04654306 0.5832632 0.8753802 -0.1803784 0.4485234 0.2222244 -0.9649002 0.1399421 0.2215878 -0.9650565 0.1398746 0.5584191 -0.7509428 0.3524953 0.5485705 -0.7581885 0.3524494 0.7530052 -0.4460096 0.483796 0.6718564 -0.4370781 0.5979731 0.6662359 -0.4460089 0.5976669 0.5711312 -0.4373292 0.6946599 0.5868523 -0.4068704 0.7000434 0.2713607 0 -0.9624777 0.4961187 0 -0.8682547 0.6914079 0 -0.7224646 0.7742906 0 -0.6328303 0.5982183 0 -0.8013331 0.3866204 0 -0.922239 0.7742662 0 -0.6328601 0.7733425 -0.04947149 -0.6320554 0.7742906 0 -0.6328303 0.6914079 0 -0.7224646 0.6914104 0 -0.7224624 0.6858357 -0.1267018 -0.7166422 0.6913964 0 -0.7224757 0.7742913 0 -0.6328294 0.5982184 0 -0.8013331 0.598218 0.001088559 -0.8013327 0.5982183 0 -0.8013331 0.4961187 0 -0.8682547 0.4961148 0 -0.868257 0.4929292 0.1132095 -0.8626728 0.4961234 0 -0.868252 0.5982184 0 -0.8013331 0.3866205 0 -0.922239 0.3866173 0.003991544 -0.9222316 0.3866204 0 -0.922239 0.2713607 0 -0.9624777 0.27136 0 -0.9624779 0.2713525 0.007801532 -0.9624484 0.2713609 0 -0.9624776 0.3866202 0 -0.922239 -0.7272346 0 -0.6863889 -0.7272347 0 -0.686389 -0.008114755 0.9999309 -0.008506894 -0.008244156 -0.9998995 -0.01153033 -0.001446664 0.9999945 -0.003012716 0 1 0 0.6321984 -0.6814727 -0.3686735 -0.6877609 -0.5753661 -0.4426498 -0.6880142 -0.5649123 -0.455533 -0.7021152 -0.5514426 -0.4504943 -0.7023871 -0.5509537 -0.4506688 -0.6954982 -0.5522338 -0.4596958 -0.6617415 -0.5624828 -0.4956929 -0.6743683 -0.5412277 -0.5022947 -0.6127661 -0.5393743 -0.5775753 -0.6254665 -0.5373028 -0.5657714 -0.6373322 -0.6445538 -0.4223247 -0.5758769 -0.6443593 -0.503157 0.7062952 -0.6153955 -0.3499078 0.7063084 -0.6153761 -0.3499152 0.7062954 -0.6153914 -0.3499146 0.7898612 -0.5265516 -0.3144245 0.7901856 -0.525978 -0.3145697 0.789853 -0.5265483 -0.3144506 0.6134793 -0.5594249 -0.5573933 0.7164663 -0.5748511 -0.3952497 0.7751541 -0.4650511 -0.4276257 0.7845031 -0.4915969 -0.3780045 0.7805457 -0.4971274 -0.3789628 0.7816597 -0.4971505 -0.3766294 0.6814028 -0.595898 -0.4249659 0.6140178 -0.4735296 -0.6314679 0.5508914 -0.5683824 -0.6111139 0.6767276 -0.4696158 -0.5670105 0.7022767 -0.4687128 -0.5358318 0.623354 -0.5819352 -0.5222847 0.7507357 -0.4660172 -0.4682137 0.3875138 -0.5339591 -0.7514791 0.4908332 -0.4801688 -0.7269942 0.5125614 -0.4794815 -0.712305 0.465353 -0.5553098 -0.6892588 0.5894478 -0.4743393 -0.6538759 0.2741467 -0.5270289 -0.8044155 0.3830808 -0.4870631 -0.7848685 0.3830931 -0.4870629 -0.7848628 0.1537235 -0.5189262 -0.8408834 0.2686369 -0.4949801 -0.8263347 0.2686364 -0.49498 -0.8263348 0.02845883 -0.5135466 -0.8575896 0.0299198 -0.5095545 -0.859918 0.1500066 -0.5038645 -0.8506577 -0.09739661 -0.5223793 -0.8471327 -0.09074765 -0.5001234 -0.861186 -0.09074491 -0.5001235 -0.8611863 -0.2197371 -0.5299983 -0.8190344 -0.2110147 -0.4916257 -0.8448532 -0.2110108 -0.4916258 -0.8448541 -0.3362101 -0.5364575 -0.7740647 -0.3282278 -0.4841198 -0.811107 -0.3282325 -0.4841197 -0.8111051 -0.4446144 -0.5417928 -0.7132872 -0.4397999 -0.4776576 -0.7605388 -0.4398035 -0.4776576 -0.7605367 -0.5429199 -0.5460515 -0.6380171 -0.5432577 -0.4722714 -0.6941403 -0.5432538 -0.4722715 -0.6941434 -0.7168679 -0.464876 -0.5196064 -0.7168658 -0.464876 -0.5196092 -0.629288 -0.5492627 -0.5498247 -0.6363008 -0.468 -0.6132677 -0.6363008 -0.4679999 -0.6132678 -0.6877516 -0.5753818 -0.4426438 -0.6904217 -0.5648844 -0.4519112 -0.621522 -0.5646415 -0.5430381 -0.6215217 -0.5646407 -0.5430392 -0.5348728 -0.5646405 -0.6285635 -0.5348736 -0.5646423 -0.6285613 -0.4365891 -0.5646421 -0.7004064 -0.4365875 -0.5646394 -0.7004098 -0.3288031 -0.5646394 -0.7570145 -0.328804 -0.5646405 -0.7570132 -0.2138639 -0.5646404 -0.7971471 -0.2138648 -0.5646414 -0.7971462 -0.09427106 -0.5646413 -0.8199349 -0.09426975 -0.5646401 -0.8199358 0.02737331 -0.56464 -0.8248832 0.02737349 -0.5646398 -0.8248834 0.1484215 -0.56464 -0.8118823 0.1484218 -0.5646397 -0.8118823 0.266242 -0.5646395 -0.7812154 0.2662398 -0.5646411 -0.781215 0.3782657 -0.5646416 -0.7335495 0.3782681 -0.5646398 -0.7335497 0.4820632 -0.5646398 -0.6699231 0.4820641 -0.5646391 -0.6699231 0.5753706 -0.5646387 -0.5917193 0.5753682 -0.5646406 -0.5917199 0.6561554 -0.5646408 -0.5006407 0.6561545 -0.5646415 -0.5006409 0.728592 -0.5641926 -0.3883816 0.6878926 -0.6052051 -0.4006627 0.7063027 -0.6153844 -0.3499124 0.651437 -0.652505 -0.3871268 0.6029257 -0.6518096 -0.4600269 0.602928 -0.6518082 -0.4600261 0.5286943 -0.6518086 -0.5437167 0.5286912 -0.6518105 -0.5437174 0.4429559 -0.6518104 -0.6155756 0.4429539 -0.6518117 -0.6155757 0.3475791 -0.6518113 -0.6740407 0.3475816 -0.6518097 -0.6740409 0.2446431 -0.6518099 -0.7178394 0.2446426 -0.6518103 -0.7178394 0.1363809 -0.6518101 -0.7460188 0.1363811 -0.6518099 -0.7460188 0.02515262 -0.6518101 -0.7579649 0.02515321 -0.6518098 -0.7579653 -0.08662348 -0.6518096 -0.7534192 -0.08662396 -0.6518101 -0.7534188 -0.1965143 -0.6518101 -0.7324792 -0.1965143 -0.6518101 -0.7324792 -0.3021289 -0.6518103 -0.6956016 -0.3021287 -0.6518101 -0.6956018 -0.4011718 -0.6518099 -0.6435876 -0.4011712 -0.6518091 -0.6435889 -0.4914823 -0.651809 -0.5775727 -0.4914828 -0.65181 -0.577571 -0.5641118 -0.6521492 -0.5064379 0.6418616 0.7640099 0.06559342 0.2979136 0.9541219 0.02998429 0.4287918 0.8961381 0.1143419 0.5938905 0.7966272 0.1126018 0.5939307 0.7965978 0.1125978 0.6071618 0.7868952 0.1102294 0.6072798 0.7868072 0.1102067 0.6186395 0.7783289 0.107188 0.6187993 0.7782081 0.1071426 0.6189913 0.7780672 0.1070563 0.7316957 0.6651167 0.1491342 0.6558046 0.7500161 0.08600008 0.6278309 0.771614 0.1021775 0.6186014 0.7783508 0.1072494 0.5087744 0.8523759 0.120847 0.5146706 0.8489517 0.1199799 0.5208371 0.8453293 0.1189419 0.5319584 0.8388803 0.1153261 0.5383882 0.8353011 0.1114013 0.549719 0.8289386 0.1032949 0.5495548 0.8290323 0.1034172 0.5596954 0.8234207 0.09337866 0.5594893 0.8235367 0.09359103 0.5436264 0.8320862 0.1100127 0.5939849 0.7965574 0.1125985 0.5939576 0.7965776 0.1125987 0.4768871 0.8707686 0.1197535 0.4985277 0.8583452 0.1213001 0.4934894 0.8612324 0.1214376 0.4881312 0.8680048 0.09108072 0.3407339 0.9336072 0.1108048 0.2850145 0.950663 0.1225011 0.3429153 0.9347932 0.09257763 0.3190606 0.9404287 0.1174479 0.3340203 0.9362637 0.1088149 0.3418257 0.9328764 0.1135642 0.2903664 0.9564515 0.02979582 0.2977384 0.9540392 0.03407263 0.3915287 0.9201616 0.00281161 0.5143243 0.8575578 0.008067846 0.5143505 0.8575421 0.008068621 0.5412909 0.8402864 0.03038024 0.6062548 0.7949873 0.02122229 0.6579808 0.7524919 0.0285862 0.6062802 0.7949679 0.02122253 0.6426622 0.7649766 0.04238015 0.5919094 0.8037315 0.06048947 0.3106025 0.9459508 0.0932911 0.3105962 0.9459465 0.09335589 0.3105978 0.9459512 0.09330195 0.2979137 0.9541226 0.02995926 0.3225504 0.9442008 0.0666778 0.4361871 0.8973991 0.06645035 0.4342989 0.8935143 0.1140908 0.4290491 0.8963303 0.1118428 0.652229 0.7456567 0.136358 0.6327642 0.7704824 0.07724231 0.5453169 0.8346739 0.07712918 0.5401363 0.8384941 0.07197403 0.429964 0.8999731 0.07196795 0.4308984 0.901929 0.0291658 0.3915274 0.9201622 0.002811551 0 0 1 0 0 1 0.707107 -2.23849e-7 -0.7071065 0.7070942 0 -0.7071193 0.7070697 0 -0.7071439 0.7071067 7.11306e-7 -0.707107 0.7071076 -3.39209e-6 -0.7071059 0.7071073 1.26555e-6 -0.7071063 0.7070878 2.57914e-6 -0.7071258 0.7070942 0 -0.7071194 0.7071077 5.32506e-7 -0.7071059 0.7071073 -1.8834e-6 -0.7071064 0.7071077 0 -0.7071059 0.7071036 3.87867e-6 -0.7071101 0.7071077 -1.08618e-6 -0.707106 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.7855135 0 -0.6188445 0.7855135 0 -0.6188445 0.8380546 0.02849 -0.544842 0.7729929 -0.006437182 -0.634382 0.8738161 0.003311038 -0.4862452 0.881907 0.004827916 -0.4713988 0.9583587 0.007901251 -0.2854579 0.939864 7.70445e-4 -0.3415478 0.8819217 -0.002271175 -0.4713906 0.9383108 0.02921777 -0.3445567 0.9123268 0.01351827 -0.4092395 0.9123143 0.0135132 -0.4092677 0.9123191 0.01351463 -0.4092571 0.8949776 0.009104132 -0.4460182 0.8731873 0.004825413 -0.4873608 0.8732932 0.004835188 -0.4871711 0.8731888 0.004826784 -0.4873583 0.9951846 0 -0.09801906 0.9913931 -0.01026028 -0.1305161 0.9569215 0.006848335 -0.2902661 0.9569168 0.006848335 -0.2902813 0.9458076 0.06607007 -0.3179351 0.871635 -0.01368981 -0.4899646 0.7894635 0.01355344 -0.6136479 0.8336085 0.1390898 -0.5345567 0.9443403 0.3151702 -0.09428209 0.9232013 0.3664627 -0.1157784 0.917625 0.3845896 -0.1002756 0.9443347 0.3151816 -0.09430062 0.9416815 0.3170052 -0.1128886 0.9622882 0.2559363 -0.09218609 0.9600614 0.2588704 -0.1061515 0.9620658 0.2515984 -0.1054881 0.973878 0.2068134 -0.09375417 0.9747825 0.1991444 -0.1006993 0.8320829 0.1321873 -0.5386692 0.8387769 0.1161674 -0.5319385 0.8373042 0.1109472 -0.5353618 0.8430018 0.09406143 -0.529623 0.8415117 0.09007674 -0.5326765 0.8457664 0.07383513 -0.5284199 0.8447795 0.07113796 -0.5303651 0.8481835 0.05429601 -0.5269126 0.8470935 0.05237668 -0.5288566 0.8488956 0.03922808 -0.5271028 0.8486466 0.03815048 -0.5275827 0.8526329 -0.004671931 -0.5224894 0.9458156 0.06607264 -0.317911 0.984808 0.1483126 -0.09031289 0.9837688 0.1513368 -0.096417 0.9842995 0.1468355 -0.09794867 0.989535 0.1102846 -0.09304708 0.9897292 0.1070336 -0.09476202 0.9954007 0.03954511 -0.08725637 0.997002 0.07670468 -0.01017677 -0.9991032 0 0.0423395 -0.5923029 -0.001642942 0.8057138 -0.5923762 -0.001645565 0.8056598 -0.6866198 -0.008964061 0.7269614 -0.9540821 -0.008213758 0.2994327 -0.9659254 0 0.2588207 -0.8490146 0 0.5283693 -0.7070949 -0.005622148 0.7070963 -0.7851438 -0.025586 0.6187848 -0.6865869 -0.008960068 0.7269925 -0.2485752 -0.03656089 0.9679224 -0.2201032 -0.1490942 0.9640153 -0.9991033 0 0.0423395 -0.9659251 0 -0.2588219 -0.9659251 0 -0.2588219 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.2588194 0 -0.9659258 -0.2588194 0 -0.9659258 0.2588194 0 -0.9659258 0.2588194 0 -0.9659258 0.7071071 0 -0.7071064 0.7071071 0 -0.7071064 0.9659251 0 -0.2588219 0.9659251 0 -0.2588219 0.9659254 0 0.2588208 0.9659254 0 0.2588208 0.7071065 0 0.7071072 0.7071065 0 0.7071072 0.2588194 0 0.9659258 0.2588194 0 0.9659258 -0.2590107 0 0.9658744 -0.2588194 3.40926e-5 0.9659258 -0.5230587 3.57993e-5 0.8522966 -0.5236626 3.55411e-5 0.8519258 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.1925936 0 -0.9812786 0.1925936 0 -0.9812786 0.5491837 0 -0.8357017 0.5491837 0 -0.8357017 0 0 -1 0 0 -1 0 0 1 0 0 1 0.5491824 0 0.8357025 0.5491824 0 0.8357025 0.1925936 0 0.9812786 0.1925936 0 0.9812786 0.1962366 0 -0.9805566 0.2588086 -0.00434637 -0.9659189 0.5585157 0.00294286 -0.8294887 0.558513 0.00294286 -0.8294905 0.7071002 -0.005871951 -0.7070891 0.9814714 0 -0.191609 0.9659153 -0.004555583 -0.2588179 0.8346917 0.003047525 -0.550709 0.8347247 0.003047525 -0.5506591 0.2104093 0 0.9776135 0.9419995 0 -0.335614 0.9437015 -3.61844e-4 -0.330798 0.9969692 3.60875e-4 0.07779538 0.9969637 3.60875e-4 0.0778672 0.9962327 -2.72175e-4 0.08671975 0.8755403 2.73063e-4 0.4831449 0.8754404 2.73063e-4 0.483326 0.8723387 -1.84417e-4 0.4889022 0.5964369 1.82587e-4 0.80266 0.5970385 1.82586e-4 0.8022125 0.5939755 -9.24064e-5 0.8044831 0.209894 9.27685e-5 0.9777242 0.2116591 9.27707e-5 0.9773436 0.1925867 0 0.98128 0.1925867 0 0.98128 0.549204 0 0.8356884 0.549204 0 0.8356884 0.5492005 0 -0.8356906 0.5492005 0 -0.8356906 0.1925867 0 -0.98128 0.1925867 0 -0.98128 0.7071058 0 0.7071078 0.3043825 0 0.9525499 0.3043825 0 0.9525499 -0.1660468 0 0.9861178 -0.1660468 0 0.9861178 -0.5995408 0 0.8003442 -0.5995408 0 0.8003442 0.9930276 0 0.1178825 0.8003452 0 -0.5995395 0.8003452 0 -0.5995395 0.9861174 0 -0.1660494 0.9861174 0 -0.1660494 0.9930275 0 0.1178825 0.9525431 -0.003123939 0.3043876 0.9372385 0 0.3486891 0.7071058 0 0.7071078 1 0 0 1 0 0 0.654639 -0.7559412 -7.83081e-4 0.259988 -0.9655951 0.00567919 0.3486312 -0.9372041 0.01023274 0.1913707 -0.981455 0.01111823 0.1496465 -0.9886443 -0.01372021 0.1666898 -0.9859116 0.013884 0.1037625 -0.994602 5.27332e-4 0.2378104 -0.9712286 -0.01269894 0.197105 -0.9798851 -0.03122562 0.3487403 -0.9372013 0.005824983 0.3418751 -0.9396934 0.009883701 0.3504598 -0.936523 0.01013028 0.529991 -0.8478676 0.01516801 0.9247272 -0.3743794 -0.06870174 0.896548 -0.4424393 -0.02119231 0.861151 -0.5081098 0.01560533 0.6548041 -0.7555353 0.0199548 0.7183138 -0.694548 -0.0403527 0.6538614 -0.7566143 -1.99093e-4 0.9903436 -0.137935 0.01391243 0.9798548 0 -0.1997115 0.9939996 -0.09584635 -0.05270868 0.9799087 -0.1993586 0.005930006 0.9882057 -0.1496951 0.03226304 0.9503346 -0.2665764 0.1606279 0.9957123 -0.05273789 0.07599824 0.8202403 -0.5714605 0.02527463 0.5865874 -0.8096357 0.02013248 0.5864516 -0.8097341 0.02012717 0.2610929 -0.9652083 0.01426452 0.227582 -0.9737462 0.004969835 0.2405856 -0.9706271 0.001225948 0.243216 -0.9699721 -3.68345e-4 0.6538187 -0.7566506 -9.90194e-4 0.6562678 -0.753566 0.03809261 0.8202444 -0.5714545 0.02527481 0.9822739 -0.1858019 0.02481335 0.982274 -0.185802 0.02480906 0.992168 -0.1249059 -0.001030921 0.9538524 -0.2989545 0.02813911 0.8960544 -0.4431469 0.02659761 0.8958019 -0.4444423 0.00317347 0.9911634 -0.1326237 -0.002470493 0.9917609 -0.1280997 -8.34911e-4 0.9917665 -0.1280112 0.003513455 0.9858043 -0.1678961 -8.28429e-4 0.9903426 -0.1379334 0.01399528 0.2393973 -0.9709209 0.001218795 0.2405546 -0.9706351 9.94982e-4 0.6537252 -0.7567273 0.002703905 0.6549054 -0.7557069 0.002447366 0.8963747 -0.4432848 0.003349721 0.8962528 -0.4435423 -0.001072049 0.8958718 -0.4443116 -9.30868e-4 0.8961355 -0.4414069 0.04583883 0.9624015 -0.2698401 0.03113973 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.7071044 0 0.7071092 0.7071044 0 0.7071092 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.9778887 -0.07678836 0.1945181 0.9539245 -0.2284661 0.1945022 0.2581933 -0.05836689 0.9643285 0.02020615 -0.01419776 0.9996951 0.3299245 -0.2234237 0.9171867 0.3239427 -0.2193728 0.9202916 0.2014521 -0.136444 0.9699485 0.1827024 -0.06901615 0.9807429 -0.2250352 -0.9547384 0.1945089 -0.2250398 -0.9547336 0.1945268 -0.07325053 -0.9781581 0.1945278 -0.07327103 -0.978163 0.1944961 -0.07327353 -0.9781619 0.1945002 0.08029747 -0.9776101 0.1945011 0.0802918 -0.9776072 0.1945182 0.2318994 -0.9530925 0.1945185 0.2319107 -0.9530962 0.1944866 0.3778023 -0.9052292 0.1944879 0.3778213 -0.9052133 0.1945253 0.3778233 -0.905213 0.1945222 0.5144717 -0.835153 0.1945208 0.5144659 -0.8351529 0.1945363 0.6385157 -0.7446169 0.1945336 0.8369955 -0.5114668 0.1945262 0.8369983 -0.5114653 0.1945177 0.7469102 -0.6358358 0.1945194 0.7469106 -0.6358357 0.1945189 0.7469102 -0.6358366 0.1945174 0.6385208 -0.7446162 0.1945195 0.9539211 -0.2284709 0.1945136 0.7101637 -0.4339603 0.554388 0.7101649 -0.4339604 0.5543864 0.6337276 -0.5394843 0.5543881 0.6337257 -0.539484 0.5543905 0.5417588 -0.6317821 0.5543904 0.5417613 -0.631783 0.554387 0.4365128 -0.7086005 0.5543843 0.4365097 -0.7085989 0.5543889 0.3205684 -0.7680423 0.5543886 0.3205588 -0.768035 0.5544046 0.1967557 -0.808654 0.5544059 0.1967612 -0.8086599 0.5543954 0.06812894 -0.8294597 0.5543963 0.06813395 -0.8294669 0.5543846 -0.06216776 -0.8299347 0.5543859 -0.06216859 -0.8299329 0.5543886 -0.1909339 -0.8100598 0.5543892 -0.1909369 -0.8100494 0.5544033 0.2581927 -0.05836808 0.9643286 0.2706882 -0.1562522 0.9499017 0.4825537 -0.2762794 0.8311507 0.4389739 -0.1857005 0.8791002 0.5065393 -0.3095309 0.8047413 0.4562516 -0.3171479 0.8314155 0.4239476 -0.3609021 0.8306733 0.4239414 -0.3609001 0.8306774 0.3624208 -0.4226425 0.830677 0.362419 -0.4226415 0.8306785 0.2920103 -0.4740287 0.8306785 0.292006 -0.4740255 0.8306819 0.2144438 -0.5137914 0.8306818 0.2144539 -0.5138019 0.8306728 0.1316295 -0.540978 0.8306723 0.1316175 -0.5409609 0.8306853 0.04557836 -0.5548737 0.8306851 0.04557853 -0.5548742 0.8306849 -0.041588 -0.5551881 0.8306844 -0.04158574 -0.5551955 0.8306796 -0.1277316 -0.5419011 0.8306791 -0.1277316 -0.5419014 0.8306789 0.1908113 -0.07883608 0.9784559 0.5145612 -0.2125973 0.8306799 0.5145605 -0.2125973 0.8306804 0.7691909 -0.3178012 0.5543896 0.7691871 -0.3178017 0.5543947 0.9065672 -0.3745624 0.1945222 0.9065699 -0.3745604 0.1945132 0.05805146 -0.1684335 0.9840022 0.1393276 -0.1400427 0.9802938 0.1489886 -0.1268336 0.980671 0.1489924 -0.126835 0.9806703 0.12737 -0.1485348 0.9806703 0.1273707 -0.1485353 0.9806702 0.1026252 -0.1665957 0.9806702 0.1026246 -0.1665953 0.9806702 0.07536739 -0.1805698 0.9806704 0.07536613 -0.1805684 0.9806706 0.04625654 -0.190119 0.9806708 0.04625844 -0.1901219 0.98067 0.01601868 -0.1950118 0.9806702 0.01601928 -0.1950132 0.9806698 -0.01461523 -0.195123 0.9806699 -0.01461583 -0.1951208 0.9806703 -0.04489058 -0.1904485 0.9806703 -0.04489016 -0.1904528 0.9806695 0.9539211 -0.2284718 0.1945122 0.8093656 -0.1938496 0.5543912 0.8093648 -0.1938499 0.5543925 0.5414359 -0.1296786 0.8306809 0.5414367 -0.1296784 0.8306803 0.1902846 -0.04557466 0.9806705 0.1902847 -0.04557466 0.9806705 0.9778919 -0.07678407 0.1945037 0.8297 -0.06514805 0.5543947 0.829704 -0.0651462 0.5543891 0.5550463 -0.04358083 0.830677 0.5550401 -0.04358267 0.8306812 0.1950668 -0.01531696 0.9806703 0.1950653 -0.01531732 0.9806706 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0.69387 0.1925854 0.6938698 0.693847 0.1950885 0.6931933 0.6294254 0.4993198 0.5954018 0.6932877 0.1950988 0.6937496 0.5876969 0.5555653 0.5881833 0.6099391 0.5090889 0.6072913 0.587149 0.5554306 0.5888573 0.5139221 0.6866721 0.5141649 0.5932162 0.5555543 0.5826269 0.5932163 0.5555542 0.5826268 0.3592716 0.8730573 0.3296891 0.4238057 0.8027009 0.4195948 0.5128404 0.6871743 0.5145738 0.1379537 0.980784 0.1379542 0.08340919 0.9952634 0.04993808 0.3974712 0.8314507 0.3882093 0.3973042 0.8316063 0.3880468 0.2577041 0.9319621 0.2550198 0.3911692 0.8314598 0.3945394 0.2537141 0.9324672 0.2571653 0.1672078 0.9732964 0.1572758 0 0.1950862 0.9807862 0 0.1950862 0.9807862 0 0.5556011 0.8314491 0 0.5556011 0.8314491 0 0.5555701 0.8314697 0 0.5555701 0.8314697 0 0.8314465 0.5556046 0 0.8314465 0.5556046 0 0.8314876 0.5555434 0 0.8314876 0.5555434 0 0.9807879 0.1950777 0 0.9807879 0.1950777 0.7071068 0 0.7071067 0.7071068 0 0.7071067 -0.7663286 0.008680343 0.6423902 -0.9749267 0 0.2225261 -0.9949709 0.03758174 0.09284597 -0.9757984 0.01292878 0.2182897 -0.9451751 0.003507912 0.3265452 -0.9021835 -0.00196731 0.4313482 -0.7818304 -0.001917243 0.6234882 -0.8926472 0.04808217 0.4481843 -0.8368191 0.02641117 0.5468422 0.9891313 0 0.1470348 0.97486 0.01187312 0.2225018 0.5123474 -9.01822e-4 0.8587779 0.7399055 9.78239e-4 0.67271 0.7817813 0.01138168 0.6234489 0.9035723 -0.005708396 0.4283976 0.903576 -0.005708396 0.4283898 0.5122323 -9.01822e-4 0.8588466 0.4338498 0.01228672 0.9009015 0.2402628 -0.005629897 0.9706916 0.2402567 -0.005629897 0.9706931 0 0.0108143 0.9999415 -0.05248743 0.002034485 0.9986196 -0.5994265 -0.005475103 0.8004112 -0.5994285 -0.005475103 0.8004096 -0.4338511 0.01262164 0.9008962 -0.3406926 -0.001727759 0.9401731 -0.3407 -0.001727759 0.9401705 -0.6330769 0.7738454 -0.0194177 -0.644738 0.763871 -0.02853304 -0.5635725 0.8250401 0.0411694 -0.6308361 0.7759079 0.003555059 -0.6790568 0.7340857 0 -0.630859 0.7758893 0.003545641 -0.679279 0.733879 -0.001348555 -0.6840541 0.7294312 -2.51396e-4 -0.6840617 0.7294242 -2.50258e-4 -0.6212561 0.7835012 -0.01291376 -0.6116033 0.7911201 -0.008384764 -0.6116207 0.7911066 -0.008392214 -0.6081903 0.7937863 0.002834439 -0.6196856 0.7848343 0.005000233 -0.6195998 0.784902 0.004983246 -0.6298597 0.7766767 0.007077455 -0.6397055 0.76856 0.009615659 -0.6531471 0.757112 0.01343673 -0.652468 0.7577017 0.0131812 -0.6673699 0.7444881 0.01884007 -0.5660192 0.8241136 -0.02142769 -0.6900815 0.7237316 0 -0.6251133 0.780525 -0.003751993 -0.6786549 0.7344571 5.69954e-4 -0.6786536 0.7344582 6.67414e-4 -0.5985803 0.8010547 -0.00363177 -0.5888258 0.8082599 -4.10474e-4 -0.5683492 0.8227873 -4.10584e-4 -0.566058 0.8243653 -3.73004e-4 -0.5683558 0.8227828 -3.56234e-4 -0.2353749 0.9719046 1.54779e-4 -0.2462496 0.9692062 7.61928e-4 -0.318302 0.9479891 -7.6931e-4 -0.4065475 0.9136071 0.006413638 -0.3341141 0.9425325 -3.70708e-4 -0.4068946 0.9134749 -5.40491e-4 -0.4188823 0.9080406 -2.40987e-4 -0.4068644 0.9134886 -2.41149e-4 -0.4188356 0.9080619 5.39582e-4 -0.4559333 0.8900139 -8.29697e-6 -0.5026751 0.8644754 5.66967e-5 -0.4989188 0.8666486 4.66796e-4 -0.4988874 0.8666667 4.7012e-4 -0.2354456 0.9718875 1.5478e-4 -0.2462113 0.9692161 -9.67627e-5 -0.1539874 0.9880728 9.2783e-5 -0.1533589 0.9881706 1.3219e-4 -0.1539683 0.9880757 1.52033e-4 -0.08020383 0.9967786 -9.23425e-5 -0.06389045 0.9979564 -0.001003623 -0.00577557 0.9999833 1.01831e-5 -0.06395655 0.9979527 7.88223e-6 0.1827516 0.9831591 2.35354e-4 0.1699262 0.9854568 7.03152e-5 0.08928102 0.9960066 -1.02527e-4 0.09204304 0.995755 1.64853e-4 -0.005808651 0.9999832 -1.72669e-4 0.01388144 0.9999026 0.001442492 0.01391279 0.9999022 0.001443922 0.3249314 0.9457375 3.23649e-4 0.3518154 0.9360676 0.001823961 0.2542749 0.9671313 -0.001196682 0.2983753 0.9544451 0.002598941 0.2462088 0.9692164 -8.95851e-4 0.1826776 0.9831724 9.37784e-4 0.1699218 0.9854575 2.34233e-4 0.1700549 0.9854345 2.35293e-4 0.4764736 0.8791888 0 0.4894619 0.8720244 7.22944e-4 0.4131662 0.9106537 -0.001907765 0.4393463 0.898316 0.001806139 0.3250069 0.9456997 -0.004751622 0.4389935 0.8984599 0.007369756 0.3518998 0.9360377 3.22854e-4 -0.697482 0.7166024 0 -0.8606379 0.5092175 1.05657e-5 -0.7968345 0.6041971 8.23555e-4 -0.7967371 0.6043255 8.07845e-4 -0.8446047 0.5351729 0.01526373 -0.8235182 0.5671128 -0.01416808 -0.8264186 0.5629673 -0.01001679 -0.8236175 0.5671238 -0.004987716 -0.8028342 0.5961679 0.006409049 -0.8434239 0.5369224 0.01872164 -0.8556509 0.5175535 0 -0.8606337 0.5092245 0 -0.8606299 0.509231 3.18221e-6 -0.8606363 0.5092204 8.43876e-6 -0.8606404 0.5092132 0 -0.7968374 0.6041933 8.07859e-4 -0.8025539 0.596549 -0.006041228 -0.7653406 0.6435972 0.006034195 -0.7715294 0.6361895 -0.002326607 -0.7230506 0.6907849 0.003741204 -0.744183 0.6679751 9.14313e-4 -0.7232893 0.6905452 -4.16039e-5 -0.7401973 0.6721184 -0.01910525 -0.7165644 0.6975168 -0.002386987 -0.7090023 0.7052062 0 -0.7391821 0.6734929 0.004157364 -0.73917 0.6735062 0.004154443 -0.7098702 0.7043181 -0.004523873 -0.8461146 0.5330011 0 -0.7592915 0.6507447 0.002788186 -0.7732197 0.6341382 -7.84864e-5 -0.7567297 0.6537279 -7.84478e-5 -0.7730278 0.6343722 -8.94e-5 -0.8123825 0.5831249 1.22738e-4 -0.8274732 0.5614795 0.005361855 -0.8473795 0.5308464 -0.01225489 -0.807442 0.5898256 0.01196891 -0.8294331 0.5585864 0.004697322 -0.9969207 0.07841622 0 -0.9970359 0.07594388 0.01232022 -0.9974721 0.07099848 0.002960741 -0.9977502 0.06704205 -4.42914e-5 -0.9977325 0.06729215 0.001286268 -0.9978423 0.0656532 5.23154e-4 -0.9980017 0.06318759 1.60102e-6 -0.9979999 0.06321698 -1.69053e-6 -0.9980002 0.06321066 -2.16345e-6 -0.9979327 0.06426662 9.9275e-5 -0.9979726 0.06364691 -6.9351e-5 -0.9979086 0.06463831 -4.07724e-4 -0.9979066 0.06467342 -4.84997e-5 -0.9939149 0.1101438 -0.001247286 -0.9897645 0.1422947 -0.01088726 -0.992404 0.1229186 0.005045115 -0.9804661 0.1966549 -0.003618001 -0.9776293 0.2103108 -0.003225326 -0.9804699 0.1966556 -0.002301156 -0.9977059 0.06769657 -3.63622e-4 -0.9972726 0.07379341 -0.001326501 -0.9974505 0.07136034 -1.06737e-4 -0.9963251 0.08551818 -0.004775285 -0.9968619 0.07916063 -8.81431e-5 -0.9971103 0.07595956 0.001137256 -0.9972548 0.07404667 -5.32137e-5 -0.9933979 0.1143593 0.009085476 -0.995687 0.09070718 0.01948744 -0.9956921 0.09064406 0.01951694 -0.997047 0.0709657 0.02934312 -0.9970353 0.07118308 0.02921813 -0.9674658 0.2427605 -0.07125395 -0.9961709 0.08733588 0.003988146 -0.980466 0.1966748 -0.002301156 -0.9764953 0.2154346 0.006709396 -0.9598783 0.2802796 -0.008779764 -0.959921 0.2801297 -0.008895337 -0.9598783 0.2802751 -0.008925437 -0.9342806 0.3564367 0.00852698 -0.9338444 0.3575979 0.007641375 -0.9344375 0.3560451 0.007641673 -0.9300339 0.3599771 -0.07384854 -0.9116991 0.4108537 0.001976191 -0.9524796 0.3046015 -8.54964e-4 -0.9699034 0.2433655 0.007777333 -0.9699066 0.2433533 0.007777214 -0.9724066 0.2332128 0.006084918 -0.9856793 0.1686077 0.002741515 -0.9914958 0.1301099 0.002727687 -0.9871423 0.1583946 0.02147656 -0.9938629 0.1105189 0.004712343 -0.9095696 0.4099374 -0.06807601 -0.9116495 0.4108862 0.008232057 -0.9297719 0.3681309 0.001980423 -0.9504906 0.310747 0.001964867 -0.8744238 0.4851605 -0.00148046 -0.9109768 0.4123747 0.008268177 -0.8806376 0.4736907 -0.009722709 -0.9126487 0.4085704 0.01194471 -0.8869345 0.4618951 0 -0.8869346 0.4618951 0 -0.9961699 0.08734804 0.003983616 -0.9994497 0.03307086 0.002533674 -0.9994469 0.03316015 0.002533674 -0.9997383 0.02286243 -8.95929e-4 -0.9957847 0.08729898 -0.02813678 -0.9981005 0.06160634 6.83842e-7 -0.9997615 0.02163994 0.00298804 0 1 0 0 1 0 0 1 0 0.6599816 0.7149216 -0.2308927 0.2940864 0.9556388 -0.01636457 0.2896909 0.9570493 -0.01165759 0.2907841 0.9567862 -0.002148807 0.3809555 0.9244771 -0.01466161 0.3592499 0.9331994 -0.008858621 0.410435 0.911733 -0.01691544 0.3527317 0.9357025 0.00641942 0.3528728 0.9356496 0.006361544 0.439453 0.8976022 -0.03451877 0.3139989 0.9492968 0.01549845 0.4390248 0.8977743 -0.03547561 0.4021087 0.9153569 -0.0207445 0.3803312 0.9248504 1.83661e-5 0.7283775 0.6675765 -0.1542975 0.4795941 0.8763471 -0.04477936 0.3802673 0.9248766 0 0.3033391 0.9528827 1.86751e-5 0.2539792 0.9672097 1.86687e-5 0.2357887 0.9718043 2.55751e-4 0.2355358 0.9718656 2.6781e-4 0.2132174 0.9770033 0.001678824 0.1816016 0.9833595 0.004990518 0.1476284 0.9889684 0.01214224 0.1476646 0.988963 0.01213347 0.106382 0.9940471 0.02352458 0.1641632 0.9863023 -0.01606434 0.2257301 0.9735636 -0.03492754 0.3528549 0.9317414 -0.08574163 0.03102725 0.9995186 0 0.01387089 0.9999037 -5.15019e-4 0.0303626 0.9995355 -0.002648472 0.04071682 0.9991705 -7.21297e-4 0.06967449 0.9975696 4.93076e-4 0.1073554 0.9942154 -0.003224194 0.1329636 0.991084 -0.008544564 0.1422764 0.9897695 -0.01066553 0.0919407 0.9955894 -0.01867252 0.04206281 0.9986029 -0.03198522 0.1296877 0.9915548 -6.02334e-4 0.03217309 0.9994823 0 0.2064471 0.9784568 -0.001346409 0.1365021 0.9905967 -0.009241104 0.1365067 0.9905961 -0.009240388 0.1754941 0.9844715 -0.004208028 0.2329022 0.9725002 -3.1541e-4 0.2331958 0.9724298 -3.06028e-4 0.2496994 0.9683234 1.84674e-5 0.005407571 0.9999707 -0.005407571 0.03160071 0.999041 -0.03030639 0.08235335 0.9923853 -0.09159314 0.2138487 0.9593811 -0.1840019 0.4293216 0.853642 -0.2949209 0.1227306 0.9795266 -0.1595771 0.1668797 0.968662 -0.1839705 0.1901785 0.9652892 -0.1790221 0.1564124 0.9795264 -0.1267399 0.01493322 0.999777 -0.01493328 0.1565332 0.9794777 -0.1269677 0.1320506 0.9879468 -0.08077025 0.2569909 0.8875019 -0.3824868 0.1152313 0.9876675 -0.1059938 0.1668907 0.9686588 -0.1839771 0.213952 0.9530862 -0.2141289 0.3636381 0.8575196 -0.3639059 0.3139894 0.8909624 -0.3280194 0.5838924 0.5813348 -0.5666741 0.698402 0.1564312 -0.698401 0.6875729 0.2053477 -0.696474 0.6315515 0.4539775 -0.6285277 0.6934148 0.2053527 -0.6906562 0.6330793 0.4539856 -0.626983 0.5691952 0.5813983 -0.5813716 0.5013266 0.7071209 -0.4986499 0.5013462 0.7070931 -0.4986695 0.629484 0.740576 -0.2351536 0.6292341 0.7400089 -0.2375951 0.705275 0.6865938 0.1765675 -0.7400365 3.55244e-6 -0.6725667 -0.9206237 -0.1208578 -0.3712754 -0.7400649 -1.65415e-6 -0.6725354 -0.74003 4.45772e-6 -0.6725739 -0.7401136 -7.12897e-5 -0.6724819 -0.7400999 -7.21109e-5 -0.672497 -0.7400566 -7.89093e-5 -0.6725445 -0.7400596 -7.55263e-5 -0.6725413 -0.7401148 -1.23508e-4 -0.6724805 -0.740087 -4.60355e-5 -0.6725112 -0.7400788 -4.62393e-5 -0.6725201 -0.7400695 -5.74052e-5 -0.6725304 -0.7400841 -6.14398e-5 -0.6725144 -0.7400696 -7.97483e-5 -0.6725304 -0.7401013 -1.2118e-4 -0.6724954 -0.7400862 -1.12466e-4 -0.6725121 -0.7401005 -8.11532e-5 -0.6724963 -0.7398921 2.23933e-5 -0.6727256 -0.7400855 -1.25193e-4 -0.672513 -0.7399282 -1.49964e-4 -0.6726858 -0.740131 -4.35042e-4 -0.6724625 -0.7399734 -3.77601e-4 -0.672636 -0.740105 -4.31637e-4 -0.6724912 -0.7401939 -2.38125e-4 -0.6723935 -0.7400613 -1.62685e-4 -0.6725395 -0.7402542 -1.733e-4 -0.672327 -0.7400686 1.00576e-5 -0.6725314 -0.7400479 1.99515e-5 -0.6725543 -0.7400596 3.47553e-6 -0.6725413 -0.740058 5.35973e-6 -0.6725431 -0.7400971 -1.16695e-4 -0.6725001 -0.7400671 -7.56124e-5 -0.6725332 -0.7401257 -7.86221e-5 -0.6724685 -0.0743944 0.9603561 -0.2686666 0.3055012 0.8133489 -0.4951087 -0.3552255 0.5121715 -0.7819815 -0.08014202 0.7002086 -0.7094259 -0.08748084 0.697177 -0.7115414 0.1215208 0.7943723 -0.5951516 0.1215158 0.7943706 -0.5951548 -0.6378837 0.1737658 -0.7502732 -0.6639167 0.1448341 -0.7336468 -0.6549318 0.176865 -0.7346994 0.2823841 0.9371858 -0.2047975 -0.0252766 0.9375313 -0.3469815 -0.02506929 0.9375641 -0.3469079 0.1664203 0.9470857 -0.2744684 -0.2235177 0.7968559 -0.5613025 -0.2234512 0.7968954 -0.561273 -0.07445251 0.9603579 -0.2686439 -0.6362077 0.1879871 -0.748265 -0.4064746 0.4557437 -0.7918815 -0.4498373 0.4941382 -0.7439582 0.1753036 0.8891641 -0.422677 0.07802087 0.9206805 -0.3824394 0.07796466 0.9207115 -0.3823766 0.1579266 0.8256871 -0.5415718 0.3331979 0.8253468 -0.4558309 0.1579598 0.8257286 -0.5414988 0.1579617 0.8257269 -0.5415009 -0.691368 0.1989015 -0.694585 -0.691366 0.1989008 -0.6945874 -0.6949619 0.1563657 -0.7018389 -0.732047 0.06407982 -0.6782338 -0.7223364 0.1351169 -0.6782136 -0.6432025 0.3521057 -0.6799353 -0.6432218 0.3520587 -0.6799415 -0.02506434 0.9375622 -0.3469133 0.08762776 0.9822185 -0.1660369 -0.298664 0.8255124 -0.4788832 -0.07990169 0.9616091 -0.2625332 -0.3976138 0.7348949 -0.5493932 -0.687484 0.1712955 -0.7057079 -0.6712145 0.1770854 -0.7197999 -0.6669248 0.1744672 -0.7244118 -0.691725 0.1313806 -0.7101096 -0.6549283 0.1768619 -0.7347033 0.2791976 0.899823 -0.3352122 0.2540173 0.8919149 -0.3741164 -0.1483442 0.7505853 -0.6439066 -0.1483518 0.7505795 -0.6439116 -0.4498544 0.4941218 -0.7439587 -0.4992942 0.5246123 -0.6895558 -0.4992622 0.5246636 -0.68954 -0.5465083 0.5426253 -0.6378767 -0.4171622 0.7388879 -0.5291695 0.4264276 0.7348716 -0.5273739 0.1825849 0.7505466 -0.6350925 0.4825174 0.421356 -0.7678775 0.6580629 0.218306 -0.7206218 0.6580606 0.2183095 -0.7206228 0.327116 0.5702354 -0.7535428 0.08813422 0.7128391 -0.6957678 -0.1659591 0.8189468 -0.5493486 -0.2838304 0.823638 -0.4909793 -0.1118528 0.8006223 -0.5886366 -0.03149151 0.9027639 -0.4289824 -0.0314911 0.9027641 -0.4289818 -0.1876725 0.8829836 -0.4302543 -0.1876637 0.8829783 -0.4302694 -0.1659617 0.8189439 -0.5493518 -0.2488029 0.8890151 -0.3843817 -0.2134519 0.8901802 -0.4025137 0.182533 0.7505842 -0.6350631 0.1295635 0.7013125 -0.7009809 -0.1191486 0.7698841 -0.6269624 0.6772745 0.1843325 -0.7122645 0.6772808 0.1843382 -0.7122572 0.7160885 0.1505624 -0.6815777 0.7676137 0.06417989 -0.6376912 0.7057243 0.3567342 -0.6121224 0.7344626 0.187955 -0.6521025 0.6786241 0.3520798 -0.6446 0.5875369 0.5455185 -0.5976704 0.5354158 0.5246166 -0.6618968 -0.0659573 0.9838941 -0.1661387 0.02849513 0.9337875 -0.3566915 0.02851152 0.9337947 -0.3566716 0.02843099 0.933802 -0.3566589 0.4263825 0.7349167 -0.5273475 0.4264196 0.7348769 -0.5273731 0.3299893 0.8276256 -0.4540297 0.0702638 0.955676 -0.2859132 0.002694606 0.972097 -0.2345637 0.1127531 0.9653814 -0.2352137 0.1124671 0.9654357 -0.2351278 0.6943513 0.208955 -0.6886321 0.6943535 0.2089564 -0.6886295 0.7319006 0.155094 -0.6635264 0.7097533 0.2415064 -0.6617589 0.7097492 0.2415047 -0.661764 0.02847135 0.9337952 -0.3566733 -0.1944362 0.9488551 -0.248734 0.2531198 0.796894 -0.5485347 0.2531699 0.796865 -0.5485537 0.5353963 0.5246472 -0.6618884 0.4889263 0.4941497 -0.7188652 0.4889384 0.4941382 -0.718865 0.453814 0.4610478 -0.7625534 0.3342871 0.5433829 -0.7700566 0.7749493 -9.79693e-6 -0.6320235 0.7749057 -5.89589e-7 -0.632077 0.7787352 -5.41728e-4 -0.6273526 0.7749258 0 -0.6320522 0.7749361 -1.49259e-4 -0.6320396 0.7749644 -1.80083e-4 -0.6320049 0.7749254 3.59131e-6 -0.6320526 0.7749218 7.23594e-6 -0.6320571 0.7749178 1.32669e-5 -0.6320621 0.7749332 3.87652e-6 -0.6320433 0.7751252 -1.71457e-4 -0.6318078 0.7749096 -5.44848e-4 -0.6320719 0.7748311 -6.17639e-4 -0.6321679 0.7749626 -3.23967e-4 -0.632007 0.7747928 -3.16602e-4 -0.6322152 0.7749323 -4.90486e-6 -0.6320443 0.7750122 -2.3077e-5 -0.6319465 0.7750081 -2.49303e-5 -0.6319513 0.7749561 -8.83999e-5 -0.6320151 0.7749688 4.17774e-5 -0.6319995 0.7749306 -2.70326e-6 -0.6320464 0.7748929 -1.61115e-4 -0.6320925 0.7748787 -1.61739e-4 -0.6321099 0.7749784 -1.0107e-4 -0.6319878 0.7749891 -9.41917e-5 -0.6319745 0.77502 -8.58276e-5 -0.6319369 0.7749393 -1.21279e-4 -0.6320357 0.77498 -3.32376e-5 -0.6319856 0.7749444 -3.32484e-5 -0.6320295 0.7749415 3.03193e-5 -0.6320331 0.7749209 -9.47518e-5 -0.6320582 0.3911617 0.9193026 -0.04330301 0.6569205 0.7513092 -0.06316691 0.5139479 0.8568708 -0.04037415 0.6059662 0.7946089 -0.03744047 0.2902007 0.9559056 -0.04503428 0.2612094 0.9626571 -0.07113999 0.2055621 0.9780588 -0.03384166 0.1088444 0.9938306 0.0212984 0.205603 0.9780502 -0.03384131 0.1682379 0.9845072 -0.04941177 0.1087948 0.9931672 -0.04221999 0.3030896 0.9529616 9.06179e-4 0.1442223 0.9890037 -0.03273844 0.4360387 0.8674679 -0.2395196 0.3041706 0.9192013 -0.2500987 0.2804458 0.9486353 -0.1464289 0.2805098 0.9480021 -0.1503539 0.2780071 0.94898 -0.1488251 0.2611926 0.9586068 -0.1133638 0.1683804 0.977314 -0.1284732 0.1682669 0.9773332 -0.1284757 0.3931888 0.8827359 -0.2572544 0.4535155 0.7690195 -0.4504805 0.4343811 0.8258591 -0.3595409 0.4343656 0.8261467 -0.3588984 0.4349673 0.8258284 -0.3589023 0.3935987 0.8745756 -0.2831919 0.5045267 0.765217 -0.3998696 0.5126178 0.7407861 -0.4341188 0.5132207 0.7557294 -0.4067893 0.5087323 0.7896316 -0.3430354 0.543891 0.7902591 -0.2822641 0.6074441 0.7291432 -0.3152174 0.5930986 0.7729769 -0.2252573 0.6272033 0.7564986 -0.1852726 0.6272033 0.7564979 -0.1852756 0.6110886 0.7817903 -0.1239947 0.6357086 0.769506 -0.06111705 0.63554 0.7707305 -0.04542458 0.6030771 0.7907681 -0.104804 0.3911629 0.9193018 -0.0433098 0.3911582 0.919304 -0.04330682 0.3908652 0.9090853 -0.1441817 0.3908694 0.9090827 -0.1441868 0.3911328 0.8871399 -0.2449448 0.406919 0.8727299 -0.2697396 0.5139219 0.8568869 -0.04036295 0.513947 0.8568713 -0.04037541 0.5136121 0.8474298 -0.1344082 0.5136101 0.8474314 -0.1344056 0.5136099 0.8237556 -0.2400659 0.5136029 0.8237625 -0.240057 0.5136462 0.7875729 -0.3404358 0.6074432 0.7291328 -0.315243 0.1031052 0.9882116 -0.1131684 -0.103483 0.9839755 -0.1452013 -0.1034924 0.9839746 -0.1452007 -3.92168e-4 0.9825432 -0.1860338 0.01154184 0.9843579 -0.1758019 -2.29934e-4 0.985365 -0.1704573 -0.04848515 0.9873089 -0.1512286 0.03977757 0.9860961 -0.161345 0.076918 0.9864358 -0.1450103 0.1252503 0.9825541 -0.1374757 -0.1292269 0.9625479 -0.2383313 -0.1292284 0.9625595 -0.2382841 -0.06650006 0.9934147 -0.09329998 -0.05711048 0.9877316 -0.1453431 -0.08433806 0.9848733 -0.1513656 -0.1292339 0.9625515 -0.2383133 -0.2471122 0.888917 -0.3856967 -0.2471123 0.8889173 -0.385696 -0.2164554 0.931425 -0.2925655 -0.3455004 0.7757356 -0.5280756 -0.3347045 0.8391888 -0.4286433 -0.2372102 0.8455565 -0.4782944 -0.3454965 0.7757397 -0.5280722 -0.3455013 0.7757376 -0.5280719 -0.1122661 0.8528034 -0.5100222 -0.1866619 0.8253421 -0.5328865 -0.1866623 0.8253419 -0.5328864 0.0100466 0.855571 -0.5175881 -0.05146896 0.8381157 -0.543059 -0.05146914 0.8381156 -0.5430589 0.2172583 0.8210033 -0.5279701 0.2172577 0.8210034 -0.5279701 0.1325024 0.851621 -0.507134 0.08068609 0.8368819 -0.541404 0.08068597 0.8368819 -0.5414041 0.3254566 0.8516601 -0.4107955 0.3254535 0.8516616 -0.4107949 0.2976249 0.8641493 -0.40579 0.2462645 0.804709 -0.5401825 0.3926878 0.7477536 -0.5354073 0.4030184 0.7683491 -0.4972081 0.3414168 0.8165408 -0.4655058 0.3255319 0.8516314 -0.4107956 0.2665226 0.8709058 -0.412903 0.2310014 0.8969022 -0.3771005 0.2030105 0.9389639 -0.277729 0.2030857 0.9389301 -0.2777882 0.2030781 0.9389493 -0.2777291 0.1474673 0.9478156 -0.2826641 0.1019558 0.9651753 -0.2409182 0.1064096 0.9844923 -0.1394701 0.07386791 0.987461 -0.1395154 0.1437435 0.9683291 -0.2041487 -0.3347138 0.8391841 -0.4286454 -0.2114688 0.8859309 -0.4128044 -0.2458778 0.8764531 -0.4139735 -0.2398693 0.8816843 -0.4063196 -0.1192684 0.9059947 -0.406139 -0.119265 0.9059963 -0.4061359 0.01072973 0.9137497 -0.4061359 0.01071757 0.9137452 -0.4061462 0.1404877 0.9029442 -0.4061465 0.1404858 0.9029437 -0.406148 0.2644032 0.8746824 -0.4062285 0.2719124 0.8996064 -0.3417192 -0.2164534 0.9314262 -0.2925631 -0.08103978 0.9577611 -0.2759102 -0.1254068 0.9526525 -0.2769954 -0.1231427 0.9536851 -0.2744463 0.01127827 0.9615488 -0.2744026 0.01127439 0.9615477 -0.2744062 0.1411976 0.9511563 -0.2745268 0.1437399 0.9683321 -0.2041373 -0.5128268 0.8212574 -0.25009 -0.2783016 0.9326776 -0.2294791 -0.3880376 0.8892969 -0.2420283 -0.6021678 0.7229136 -0.3388067 -0.145855 0.9879047 -0.0526371 -0.1346432 0.9897598 -0.04739993 -0.2075091 0.9765898 -0.0566774 -0.1347388 0.9906508 -0.02136695 -0.07134366 0.9962744 -0.04844903 -0.3205235 0.94659 -0.03510248 -0.3205556 0.9465791 -0.03510195 -0.2592992 0.9631803 -0.07104796 -0.2296609 0.9723015 -0.04342436 -0.2296443 0.9723054 -0.0434246 -0.390024 0.9190937 -0.05610728 -0.4017284 0.9128156 -0.07336246 -0.4017439 0.912808 -0.07337152 -0.5465699 0.8312991 -0.1010115 -0.5134016 0.8564948 -0.05324858 -0.4755872 0.8788806 -0.0372262 -0.4755326 0.8789104 -0.03722119 -0.4755957 0.8788763 -0.03721946 -0.6050468 0.7948557 -0.04607409 -0.5489752 0.8351524 -0.0338627 -0.5489329 0.8351802 -0.03386408 -0.6667618 0.7420554 -0.06915485 -0.6438258 0.7614457 -0.07542437 -0.6247231 0.7753052 -0.09285974 -0.6279712 0.7730231 -0.08992999 -0.6371064 0.7664563 -0.08148753 -0.6261294 0.7767211 -0.06831169 -0.6050039 0.7948905 -0.04603672 -0.6269231 0.7531348 -0.1993873 -0.6029225 0.7631974 -0.2324094 -0.5236983 0.7993152 -0.2946785 -0.6269232 0.7531356 -0.1993845 -0.5044258 0.7858376 -0.3577901 -0.4649989 0.7869995 -0.4054723 -0.4993582 0.7490438 -0.4354018 -0.504707 0.7414072 -0.4422513 -0.4863473 0.750405 -0.4476145 -0.3880349 0.8893191 -0.2419513 -0.396923 0.8515969 -0.3423956 -0.4387286 0.8178412 -0.3723613 -0.407464 0.8006022 -0.439328 -0.4074639 0.8006005 -0.4393312 -0.256703 0.9570088 -0.1350467 -0.2590995 0.9556389 -0.1400777 -0.2504623 0.9578912 -0.1404038 -0.1458711 0.9833331 -0.1085251 -0.2783012 0.9326519 -0.2295841 -0.3515198 0.8948029 -0.2752485 -0.3894655 0.8803298 -0.2708065 -0.3874963 0.8818862 -0.2685581 -0.5128234 0.821258 -0.2500951 -0.5132044 0.7872772 -0.3417834 -0.6021622 0.7229174 -0.3388085 -0.2837492 0.9460415 -0.1564986 -0.3895285 0.9086654 -0.1503157 -0.3895353 0.9086638 -0.1503068 -0.5128267 0.8469827 -0.1401038 -0.5128273 0.8469824 -0.1401028 -0.6093704 0.782256 -0.1293962 -0.6371193 0.7679283 -0.06606906 -0.7238801 0.6899011 0.005840301 -0.7238643 0.6899177 0.005839645 -0.6054734 0.7958649 -9.83808e-4 -0.6278921 0.7782989 0.001490116 -0.6310577 0.7757332 0.002003431 -0.6279996 0.7782122 0.001488864 -0.6517063 0.7584512 0.005540132 -0.6463491 0.7629996 0.008017778 -0.5507643 0.8343687 0.02207887 -0.6688484 0.7433932 -0.002909541 -0.6055173 0.7958316 -9.82319e-4 -0.5774829 0.8163772 0.006451368 -0.5492371 0.8356488 -0.005451679 -0.4759619 0.8794631 -0.002199828 -0.4760167 0.8794336 -0.002196848 -0.4936538 0.8696393 0.005782485 -0.5492197 0.8356602 -0.005463123 -0.5491948 0.8356765 -0.005464315 -0.2952103 0.9549595 0.03005194 -0.2952103 0.9549598 0.0300461 -0.2999671 0.9539082 0.008877456 -0.3549923 0.9343385 0.03149658 -0.3209108 0.9470089 -0.01379674 -0.3210588 0.9470533 0.003359198 -0.4022193 0.9155375 0.003261089 -0.4063922 0.9136921 0.003492295 -0.4021775 0.9155426 0.00592488 -0.4760251 0.8794289 -0.002200245 -0.4895135 0.8664751 0.09796714 -0.4485321 0.888342 0.09832274 -0.4008609 0.9111483 0.0954957 -0.4034628 0.9099112 0.09633034 -0.4007786 0.9110571 0.09670346 -0.4007397 0.9110741 0.09670472 -0.4894813 0.8664931 0.09796798 -0.4899272 0.8662598 0.09780311 -0.5547351 0.8257082 0.1023467 -0.5547226 0.8257166 0.1023467 -0.5720934 0.8139222 0.1011916 -0.5559525 0.825805 0.09467381 -0.7014121 0.7069777 0.09057474 -0.7158514 0.6913325 0.09806233 -0.6595074 0.7470462 0.08349788 -0.7202014 0.6863943 0.1008593 -0.6556307 0.7487409 0.09764921 -0.6492022 0.7545361 0.09597778 -0.6116513 0.7843438 0.1033808 -0.6116295 0.7843608 0.1033803 -0.7780291 0.6222934 0.08614856 -0.7781312 0.6221639 0.08616214 -0.7477581 0.6595687 0.07633405 -0.7803456 0.6178798 0.09636062 -0.7058339 0.7042401 0.07644915 -0.7803211 0.6178727 0.09660434 -0.780373 0.6178064 0.09660845 -0.838594 0.5397779 0.07348543 -0.7781316 0.6221637 0.08616018 -0.7811694 0.6183295 0.08627247 -0.8124404 0.5764347 0.08754283 -0.8260095 0.557309 0.08435118 -0.837013 0.53983 0.0894013 -0.6754113 0.7318422 0.0907008 -0.6386088 0.7422237 0.2031818 -0.6427924 0.7641704 0.05349487 -0.3004715 0.9495685 0.08964735 -0.300327 0.9491332 0.09460389 -0.3128215 0.9456034 0.08931422 -0.3004916 0.9495658 0.08960783 -0.3210768 0.9454746 0.05465966 -0.4047309 0.9127711 0.05515182 -0.4057902 0.9123386 0.05452173 -0.4915296 0.8690931 0.05546081 -0.4929251 0.8683556 0.05461907 -0.5741401 0.8168342 0.05608052 -0.576636 0.81518 0.0545212 -0.646938 0.7604527 0.05641752 -0.6514941 0.7582032 0.0261417 -0.02310442 -0.1554773 -0.9875693 -0.02310907 -0.15548 -0.9875688 -0.02324652 -0.1555148 -0.98756 -0.07148778 -0.03523135 -0.9968191 -0.08973401 -0.02406352 -0.995675 -0.07148367 -0.03522604 -0.9968196 -0.07149267 -0.03522723 -0.9968188 -0.07539665 -0.03279489 -0.9966142 -0.09716033 -0.004040539 -0.9952605 -0.08208143 0.01260346 -0.9965459 -0.03995841 -0.05777549 -0.9975296 -0.0498991 -0.05285638 -0.9973546 -0.08976763 0.007400393 -0.9959353 0.13911 -0.1697528 -0.975619 0.1391922 -0.1696289 -0.9756289 0.1390975 -0.1697476 -0.9756217 0.2181574 -0.2004837 -0.9550988 -0.04559266 -0.04131734 -0.9981054 0.004942476 -0.06789523 -0.9976803 0.2963338 -0.2171348 -0.9300745 0.2072096 -0.1920984 -0.959251 0.1596984 -0.1537127 -0.9751251 0.1195027 0.1363475 -0.9834269 0.1195251 0.1362789 -0.9834337 -0.0431711 -0.03770595 -0.9983559 -0.08555066 -0.02217656 -0.9960869 0.2057336 -0.2276098 -0.9517707 0.04632204 -0.1353958 -0.9897081 0.03743219 -0.1282127 -0.99104 0.03743457 -0.1282098 -0.9910404 0.04202878 -0.1307852 -0.9905195 0.04633903 -0.1354105 -0.9897054 0.0463466 -0.1354011 -0.9897063 0.004102289 -0.02133345 -0.999764 0.3173893 -0.1800401 -0.9310475 0.2491804 -0.1525452 -0.9563676 0.02265304 -0.0366488 -0.9990714 0.01988101 -0.04150539 -0.9989405 0.02266389 -0.03665423 -0.999071 0.001803755 -0.02661925 -0.9996441 -0.04566895 -3.512e-4 -0.9989566 0.004106581 -0.02135241 -0.9997637 -0.02452236 -0.005396664 -0.9996848 0.002964019 -0.01081866 -0.9999372 -0.01563394 -0.001404345 -0.9998769 0.002967715 -0.01081979 -0.9999371 0.002965092 -0.01081508 -0.9999371 -0.06769335 0.006857752 -0.9976826 -0.003741919 -0.002838134 -0.999989 -0.00372684 -0.002856552 -0.999989 -0.003725409 -0.002848565 -0.999989 0.3677587 -0.06207174 -0.9278474 0.516518 -0.05832028 -0.854288 0.5026122 -0.05591332 -0.862702 0.1808797 0.0473001 -0.9823672 0.3350267 -0.04609203 -0.9410806 0.3347503 -0.04605817 -0.9411806 -0.001657605 -0.004166424 -0.99999 0.2794407 -0.01181828 -0.9600903 -0.06770241 0.006858527 -0.997682 0.3423854 -0.1296221 -0.9305753 0.4329681 -0.1107166 -0.894584 0.4608739 -0.1148231 -0.8800062 0.3677791 -0.06207895 -0.9278387 0.3677615 -0.06205576 -0.9278473 0.2415081 -0.145758 -0.9593896 0.2415058 -0.1457635 -0.9593894 0.4441639 -0.1752074 -0.8786472 0.3423832 -0.1296222 -0.9305761 0.3423849 -0.1296238 -0.9305753 0.06781101 -0.02071642 -0.9974831 0.02699893 -0.02299243 -0.9993711 -0.07431042 -0.09920662 -0.9922883 -0.2335394 -0.1432861 -0.961732 -0.2491405 -0.1566007 -0.9557223 -0.2491983 -0.1566427 -0.9557003 -0.2335381 -0.1432892 -0.9617318 -0.4041725 -0.1859761 -0.8955766 -0.3041262 -0.1326348 -0.9433531 -0.3199719 -0.05831819 -0.9456304 -0.3635122 -0.1105479 -0.9250071 -0.3041471 -0.1326446 -0.9433451 -0.3041447 -0.1326524 -0.9433447 -0.3199737 -0.058308 -0.9456304 -0.4009857 -0.06108659 -0.9140453 -0.261584 -0.005429565 -0.9651654 0.0642479 -0.007216691 -0.9979078 0.06424975 -0.007227182 -0.9979077 0.0642606 -0.007213652 -0.9979071 0.06931471 -0.00291723 -0.9975906 0.06936901 -0.002916574 -0.9975869 0.07630693 -0.003032207 -0.9970798 0.06604439 -0.00435537 -0.9978073 -0.355778 -0.05744057 -0.9328036 -0.3199663 -0.05830466 -0.9456332 -0.3537636 -0.1090703 -0.9289537 0.08255559 -0.005898535 -0.996569 0.06268668 -0.01404654 -0.9979345 0.06781953 -0.02073615 -0.9974821 0.06781756 -0.02071577 -0.9974827 0.08648008 -0.01130324 -0.9961895 0.0626806 -0.01404607 -0.9979348 0.0626834 -0.01405537 -0.9979345 -0.8454762 0.529833 0.06668591 -0.8418009 0.5356204 0.0669471 -0.8103518 0.5821169 0.06685715 -0.8150998 0.5754699 0.06668329 -0.8103466 0.5821483 0.0666483 -0.8150861 0.5755251 0.06637483 -0.7573784 0.6493023 0.0691694 -0.7735883 0.6300622 0.06769609 -0.7574507 0.6493836 0.06759834 -0.7737509 0.6299768 0.06662338 -0.7099708 0.7007596 0.06983792 -0.7081034 0.7026315 0.06998902 -0.7099273 0.7007876 0.06999862 -0.6756579 0.7338814 0.0700311 -0.7082943 0.7026 0.06835538 -0.6213834 0.7801987 0.07192075 -0.6352165 0.7690674 0.07096099 -0.6351773 0.7690997 0.07096076 -0.6214222 0.7802737 0.07076275 -0.5795112 0.8117851 0.07191586 -0.5635288 0.8229736 0.07176309 -0.5215663 0.850088 0.07293248 -0.5636172 0.8227835 0.07323163 -0.5215725 0.8500669 0.07313293 -0.5015541 0.8621082 0.07220125 -0.4188796 0.9050129 0.07410597 -0.4357705 0.8970304 0.07375979 -0.4182614 0.9053414 0.07358282 -0.4358015 0.8971177 0.07250475 -0.3325645 0.9401557 0.07421702 -0.3447149 0.9357855 0.07400661 -0.332539 0.9401911 0.07388192 -0.3447039 0.9358475 0.07327079 -0.2449523 0.9667242 0.07377421 -0.2779845 0.957787 0.07327079 -0.2450129 0.9667705 0.07296246 -0.2781741 0.9578684 0.07146424 -0.1537131 0.985175 0.07617527 -0.210797 0.9747846 0.07320827 -0.1537103 0.9854366 0.07271909 -0.2108095 0.9749867 0.0704298 -0.08154064 0.9938749 0.07459175 -0.1144499 0.9907475 0.07294428 -0.08154773 0.994016 0.0726785 -0.1143717 0.9907922 0.07245612 -0.006504595 0.9973716 0.07216262 -0.01593607 0.9972985 0.07170635 -0.006528139 0.9974097 0.07163357 -0.01591557 0.9973073 0.07158899 0.08918076 0.993497 0.07078599 0.0545029 0.9961158 0.06915843 0.1237025 0.9898158 0.07044357 0.08920347 0.9934958 0.070773 0.1237277 0.9897931 0.07071727 0.1814225 0.9810354 0.0682311 0.2199059 0.9730889 0.06884354 0.1815336 0.9809458 0.0692169 0.2198922 0.9730835 0.06896251 0.314821 0.9468681 0.06579142 0.3224425 0.9442862 0.06598842 0.3148267 0.9468463 0.06607836 0.322418 0.9442814 0.06617617 0.2518044 0.9654302 0.06737339 0.4119189 0.9090271 0.06318634 0.4745999 0.8780208 0.06192255 0.378247 0.9234551 0.064498 0.4070113 0.9112462 0.06302458 0.41194 0.9090492 0.06272929 0.4044408 0.9124041 0.06281942 0.4267383 0.9022793 0.06153374 -0.9978346 -0.002307713 0.06573164 -0.9977948 -0.009221851 0.06573116 -0.9978371 0 0.0657342 0.900426 0.1895675 0.391532 0.9862191 0.1654234 0.002697229 0.9883859 0.1296359 0.07929599 0.9867784 0.08823269 0.1359529 0.9837316 0.1227195 0.1311952 0.9003715 0.1895954 0.3916437 0.9857671 0.1056692 0.1307567 0.9857159 0.1056687 0.1311424 0.9840015 0.1186891 0.1328685 0.9843055 0.1210557 0.1284062 0.9740251 0.186271 0.1287562 0.9723059 0.1984301 0.1234781 0.9583985 0.2534923 0.1312019 0.9492645 0.292334 0.1159217 0.9412732 0.3170743 0.1160553 0.9491056 0.2922291 0.1174765 0.94106 0.3173221 0.1171017 0.8120004 0.5510385 -0.192385 0.8773728 0.4643114 0.1209619 0.9151211 0.3846796 0.1207271 0.91317 0.3901298 0.1179801 0.9154621 0.3846812 0.118109 0.9132164 0.3900831 0.1177761 0.9158388 0.3846982 0.115094 0.9464461 0.2922061 0.1373151 0.8740764 0.414107 -0.2539805 0.7739582 0.349405 0.5281144 0.8124274 0.5775659 0.07987189 0.899637 0.3859163 -0.2042593 0.9085627 0.3704596 -0.1930633 0.9133964 0.3593196 -0.1913021 -0.9021747 0.4066045 0.1440612 -0.9940161 0.08715921 0.06584203 -0.9905301 0.0868383 0.1063438 -0.9942516 0.07306581 0.07826298 -0.9959517 0.06145989 0.06559574 -0.87392 0.4809061 0.07066375 -0.8701758 0.4881177 0.06734299 -0.9201702 0.3862098 0.06425434 -0.9201616 0.3862304 0.06425428 -0.9092274 0.4114281 0.06350117 -0.8811421 0.4680635 0.06712085 -0.8712142 0.4863203 0.06691962 -0.9972282 0.04158061 0.06170278 -0.9893451 0.1303067 0.06493264 -0.9940772 0.08715224 0.06492316 -0.9892851 0.1302984 0.06585693 -0.9679212 0.2428749 0.06434404 -0.967926 0.2428563 0.06434398 -0.9097544 0.4100321 0.06496655 -0.9097749 0.4099866 0.06496697 -0.9514172 0.300655 0.06642228 -0.9679779 0.2428824 0.06345731 -0.9516012 0.3007482 0.0632919 -0.9743294 0.2162011 0.06276291 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.9659287 0 0.2588087 0.9659287 0 -0.2588087 0.9659287 0 -0.2588087 0.7071077 0 -0.7071059 0.7071077 0 -0.7071059 0.2588182 0 -0.9659261 0.2588182 0 -0.9659261 -0.2588182 0 -0.9659261 -0.2588182 0 -0.9659261 -0.7071077 0 -0.7071059 -0.7071077 0 -0.7071059 -0.965925 0 -0.2588222 -0.965925 0 -0.2588222 -0.965925 0 0.2588222 -0.965925 0 0.2588222 -0.7071072 0 0.7071063 -0.7071072 0 0.7071063 -0.2588185 0 0.9659259 -0.2588185 0 0.9659259 0.2588185 0 0.9659259 0.2588185 0 0.9659259 0.7071072 0 0.7071063 0.7071072 0 0.7071063 0.9659287 0 0.2588087 -0.1628836 3.48116e-6 0.9866454 -0.1904751 0.006553471 0.9816701 -0.8520117 -0.0136196 0.5233454 -0.5293989 0.02184063 0.8480919 -0.5973708 0.01198947 0.8018756 -0.529537 -0.008087337 0.8482482 -0.5296036 -0.008087337 0.8482067 -0.8519695 -0.0136196 0.5234141 -0.914451 0.008207857 0.4046134 -0.8515846 0.03515601 0.523037 -0.9925923 -0.01357221 0.1207328 -0.992591 -0.01357305 0.1207429 -0.9925805 -0.01357305 0.1208286 -0.8546187 2.99464e-6 -0.5192561 -0.8057534 0.02386152 -0.5917703 -0.9541478 -0.01724177 -0.2988388 -0.9951196 -0.01687687 -0.0972222 -0.952086 0.05798006 -0.3002839 -0.9527299 0.05727016 -0.2983723 -0.777653 0.6087142 0.1572349 -0.927877 -0.1154209 -0.3545731 -0.8022431 0.1539795 -0.5767983 -0.8305655 0.1111452 -0.5457176 -0.8284032 0.1008841 -0.5509725 -0.8479506 0.07215213 -0.5251418 -0.873685 0.09301602 -0.4775172 -0.8343062 0.113966 -0.5393931 -0.8769565 0.1492585 -0.4568032 -0.8770471 0.1493237 -0.4566079 -0.7941925 0.5439497 0.2708817 -0.8519438 0.5063142 0.1335582 -0.7607654 0.6482576 0.03159052 -0.864658 0.4601148 0.2016456 -0.8646488 0.4601013 0.2017157 -0.8787252 0.4603136 0.1263061 -0.7776283 0.6086955 0.1574296 -0.7776976 0.6085908 0.1574916 -0.5264782 0.8427792 0.1120002 -0.5263166 0.8429057 0.1118078 -0.5805528 0.7523183 0.3114091 -0.7942462 0.5438793 0.2708657 -0.7942097 0.5439593 0.2708122 -0.2045311 0.9737254 -0.1001298 -0.2034067 0.9738357 -0.1013392 -0.2164601 0.9723262 -0.08790087 -0.2155779 0.9704025 -0.1088349 -0.5418633 0.749926 -0.3794668 -0.739001 0.06516999 -0.6705448 -0.739014 0.3656164 -0.5658471 -0.7329531 0.2114694 -0.646576 -0.7458624 0.02992016 -0.6654278 -0.8191496 0.4698405 -0.3290044 -0.7927275 0.1451965 -0.5920312 -0.7646244 0.1947634 -0.6143426 -0.4586525 0.835092 -0.303742 -0.423235 0.7399857 -0.5227747 -0.2258085 0.9693877 -0.09642708 -0.7390482 0.365457 -0.5659055 -0.565871 0.6701161 -0.4803484 -0.705489 0.5381743 -0.4611439 -0.5364637 0.8161966 -0.2145453 -0.5365087 0.8161689 -0.2145384 -0.288377 0.9557805 0.05764108 -0.5206785 0.8457568 0.1165735 -0.5207127 0.8457302 0.1166136 -0.5216298 0.8464483 0.1069009 -0.6567347 0.7496133 -0.08233731 -0.6726872 0.7386916 0.04273855 -0.8194445 0.4691144 -0.3293057 -0.9255597 0.3116079 -0.215034 -0.925055 0.3115256 -0.2173132 -0.8041459 0.5221476 -0.2840973 -0.9823941 0.1700195 -0.07742792 0.2590232 0.9647962 -0.04555451 0.2590882 0.9647708 -0.04572254 0.3349511 0.7829541 0.5242047 0.335183 0.7830384 0.5239304 0.5102028 0.8197776 0.2601116 0.5256937 0.8197112 0.2274195 0.4676445 0.8358044 0.2876447 0.4676747 0.8358006 0.2876068 0.7647101 0.6199921 0.1755797 0.7647419 0.6199855 0.1754645 0.8370195 0.4864063 0.2506135 0.8903042 0.4478401 0.08244794 0.7156615 0.5904718 0.3730571 0.8569401 0.4751366 0.1997469 0.8441653 0.4593502 0.2763734 0.8903186 0.4478244 0.08237719 0.8884282 0.1093571 -0.4457985 0.8860353 0.0778132 -0.457041 0.8662189 0.08971774 -0.491544 0.8737473 0.06388658 -0.482166 0.8627806 0.09997487 -0.4955953 0.8554549 0.09913903 -0.5082995 0.843894 0.1514421 -0.5146924 0.8085806 0.1887915 -0.5572746 0.8085949 0.1887831 -0.5572568 0.7155835 0.5904952 0.37317 0.5750992 0.7927133 0.202155 0.7074968 0.7064021 0.02108073 0.6265609 0.7772701 0.05720746 0.2342028 0.9689385 -0.07941865 0.4392063 0.8823286 -0.1690978 0.2762519 0.9608294 -0.022174 0.3110818 0.9496647 -0.03694802 0.1472921 0.9839041 0.1011816 0.4678348 0.8356392 0.2878155 0.5879386 0.748147 -0.3075781 0.7108487 0.5468186 -0.4423613 0.8355749 0.4697951 -0.2847929 0.8219568 0.1401686 -0.5520325 0.8438764 0.1514699 -0.514713 0.5181522 0.7489636 -0.4130035 0.7681838 0.3655378 -0.5256195 0.7952774 0.1805514 -0.5787358 0.7056984 0.3567299 -0.6121548 0.7758642 0.06555926 -0.6274845 0.5816125 0.7487154 -0.3180444 0.5581257 0.7757321 -0.2945089 0.7505554 0.6584869 -0.05533206 0.8358715 0.469102 -0.2850652 0.9357214 0.3116093 -0.1653026 0.9353406 0.3115273 -0.1675966 0.9740389 0.1896072 -0.1236827 0.9785314 0.2024434 -0.03863853 -0.6440663 -8.73099e-6 -0.7649698 -0.57675 2.7686e-6 -0.8169206 -0.6237949 -0.005003869 -0.7815722 -0.5768743 -0.005012631 -0.8168177 -0.3152135 0.005674839 -0.9490039 0.2396874 -0.00172764 -0.9708486 0.2396659 -0.001726925 -0.9708538 0.1701118 0.004365861 -0.9854151 -0.1889976 -0.003730356 -0.9819705 -0.1889697 -0.003730356 -0.9819758 0.6071316 7.67878e-5 -0.7946013 0.6223533 0.002073824 -0.7827337 0.2396669 -0.00172764 -0.9708537 0.8762869 0.1392685 -0.4612221 0.6151582 -0.002542436 -0.7883996 0.8851867 -0.002788603 -0.4652278 0.9143706 0.01532042 -0.4045883 0.989856 -0.006949067 -0.1419047 0.9730237 -0.01643151 0.2301197 0.9871197 -0.008815705 0.1597402 0.9731489 0 0.2301766 0.9963508 0 -0.08535391 0.989865 -0.006949305 -0.1418414 0.9898567 -0.006949365 -0.1419003 0.7704699 -0.01306068 0.6373427 0.7704816 -0.01306068 0.6373285 0.8436748 0.00524789 0.536829 0.7701432 0.03024291 0.6371539 0.9730204 -0.01643151 0.2301328 0.1034929 -2.21223e-6 0.9946302 0.1035043 -1.43473e-6 0.994629 0.1329413 0.004398286 0.9911141 0.4170728 -0.008159995 0.9088364 0.4903381 -0.008132874 0.8714944 0.4169809 0.02051782 0.9086836 0.4169893 0.02051633 0.9086797 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.002502202 0.9999908 0.003510951 0.0623809 0.9942075 0.08752077 0.7037923 0.6000709 0.3802517 0.7038044 0.6000192 0.3803109 0.2843478 0.8751124 0.3915667 0.2843513 0.8751096 0.3915706 0.5258113 0.6610396 0.5353028 0.5120155 0.819038 0.2588765 0.542173 0.6019696 0.5862432 0.7040168 0.6000148 0.3799245 0.7038959 0.6000287 0.3801263 0.002502381 0.9999907 0.003510832 -0.01500439 0.9983756 0.05496519 0.1763961 0.9386804 0.2962492 0.2208876 0.9751088 -0.01927191 0.2843846 0.8750057 0.3917784 1.23746e-4 0.9999915 0.004126787 2.45335e-4 0.9999915 0.00411427 0.001110553 0.9999935 0.003464043 -0.002079665 0.9999707 0.007355928 4.49112e-4 0.9999877 0.004936158 1.49436e-5 0.9999624 0.008663773 -0.04364335 0.9335086 0.3558887 -0.0828495 0.6571668 0.7491781 -0.08283835 0.6572771 0.7490826 -0.08970773 0.6637974 0.742513 -0.03738826 0.9363526 0.3490642 -0.1582211 0.2375479 0.9584034 -0.1180905 0.2082439 0.9709218 0.1001526 0.2550112 0.9617373 0.1002162 0.255011 0.9617307 0.4003149 0.2812502 0.8721504 0.8836612 0.05439978 -0.4649555 0.8838109 0.05562657 -0.4645255 0.8838495 0.05560278 -0.464455 0.9867156 0.07989341 -0.1414545 0.9924177 0.07495653 -0.0974099 0.9870633 0.07533848 -0.1415282 0.9928487 0.05364459 -0.1066468 0.9895976 0.02422469 -0.1418083 0.9926831 0.03081107 -0.1167516 0.9563112 0.1852989 0.2261262 0.9786716 0.201732 -0.03880798 0.9512681 0.210992 0.2248808 0.9565519 0.2915341 0.004064083 0.9399675 0.2589674 0.2222545 0.9433879 0.2924966 0.1564127 0.7600839 0.1641189 0.6287587 0.8519193 0.2837807 0.4401158 0.7384539 0.2858356 0.6107239 0.6609019 0.2291783 0.7146229 0.7605184 0.1609812 0.6290443 0.4002974 0.2812498 0.8721585 0.001110732 0.9999935 0.003439962 0.1081757 0.9359835 0.3350117 0.1081733 0.9359844 0.3350099 0.229846 0.6636817 0.7118269 0.2298465 0.6636813 0.7118271 0.2998968 0.2178242 0.9287704 0.4109463 0.1709614 0.8954861 -0.5110816 0.2618212 0.818685 -0.7332544 0.6002749 0.3193871 -0.9432823 0.1514908 -0.2954136 -0.94269 0.151447 -0.2973204 -0.8765815 0.1389193 -0.4607672 -0.9478843 0.1156683 -0.2968771 -0.7745699 -0.2764604 -0.5688682 -0.8645777 0.3363112 -0.3733634 -0.9895126 0.03846877 -0.1392303 -0.9850665 0.1236435 0.1198174 -0.9856677 0.142314 -0.09058624 -0.98173 0.148137 0.1194217 -0.9769301 0.2047734 -0.06062537 -0.977989 0.1713591 0.1190524 -0.9633894 0.266435 -0.02988553 -0.8457822 0.1216555 0.5194731 -0.9237356 0.2767619 0.2647927 -0.8179315 0.2801416 0.5025025 -0.7759848 0.2352266 0.5852488 -0.8352792 0.1978468 0.5129965 -0.5110536 0.2618199 0.8187029 -0.004072844 0.9999671 0.007014513 -0.003057956 0.9999898 0.003356397 -0.003623783 0.99997 0.006831824 -0.3616561 0.90143 0.2379679 -0.2657566 0.9351294 0.2343212 -0.2667806 0.9155632 0.3009517 -0.03011757 0.9989995 0.03305703 0.02140849 0.9993331 0.02958154 -0.001745581 0.9986166 0.05255365 -0.003019332 0.9985502 0.05374491 -0.5914596 0.6599897 0.4632376 -0.2667419 0.9155842 0.3009223 -0.2668499 0.9155211 0.3010185 -0.7331789 0.6003785 0.3193656 -0.7331678 0.6003707 0.3194056 -0.6337924 0.6081255 0.478007 -0.6054419 0.6883237 0.3995631 -0.6054583 0.688243 0.3996772 -0.5148476 0.2345414 0.8245739 -0.4877445 0.239513 0.8394873 -0.3779 0.6588904 0.6504269 -0.3779947 0.6586851 0.6505798 -0.3779963 0.6586875 0.6505764 -0.1799345 0.9336577 0.3096886 -0.1799347 0.9336582 0.3096866 -0.00420016 0.9999651 0.00722891 0.2101896 0.9772593 0.02801346 -0.07456934 0.9960758 0.04766905 0.1601891 0.9816977 0.1029991 -0.2298328 0.9730274 -0.01986223 -0.01429724 0.9998465 0.01013755 -0.01434993 0.9998457 0.01013785 -0.06440997 0.9973686 0.03327727 -0.08700585 0.9961398 0.01163339 -0.07141155 0.9972237 0.02110236 -0.134768 0.9908637 -0.00516057 -0.2001053 0.9797694 -0.003126025 -0.1323881 0.9731525 0.1882752 -0.2298163 0.973032 -0.01982849 0.1088924 0.9940531 0.00101751 0.1088688 0.9940556 0.001017153 0.08205771 0.9965467 0.0126968 0.05845141 0.997796 0.03140974 0.05853807 0.9977934 0.03132879 0.06320178 0.9976482 0.02652186 0.0149343 0.9998033 0.01304614 0.01490479 0.9998038 0.01304191 0.2056639 0.9783341 0.02376496 0.2102004 0.9773118 0.02602738 0.2056012 0.9782386 0.02788311 0.2303404 0.9650559 0.1249418 0.2294309 0.9657076 0.1215336 0.2275356 0.9664978 0.1187838 0.2083175 0.9733261 0.09612554 0.2084833 0.9732859 0.09617334 0.01078516 0.9948731 0.100554 0.0677905 0.9933575 0.09298038 0.08738827 0.9911387 0.1000364 0.1600472 0.9817211 0.1029989 -0.1502918 0.9838492 0.09722608 -0.06590229 0.9938013 0.08953142 -0.07433456 0.9929397 0.09243941 -0.06602329 0.9934056 0.09373569 0.01081627 0.9948728 0.1005538 -0.1503093 0.9838467 0.09722584 -0.2045192 0.975147 0.08520692 -0.228725 0.9692043 0.09125691 -0.2286736 0.9692173 0.09124827 -0.2286559 0.9692218 0.09124451 -0.223954 0.9741915 0.02820324 -0.223954 0.9741915 0.02820324 -0.220229 0.9742266 0.04880434 -0.2005103 0.9793034 0.02757549 -0.2044035 0.9745889 0.09162694 0.2044956 0.9741291 0.09619879 0.204386 0.9735807 0.1018185 0.1620976 0.9832598 0.08321428 0.1791556 0.9834432 0.02725297 0.2090589 0.9763603 0.05490845 0.0679807 0.9961456 0.05543321 0.06314188 0.9967032 0.0509513 -0.07886403 0.995544 0.05169945 -0.07896125 0.9967712 0.01456648 -0.03005123 0.9967518 0.07471865 -0.9576262 0.2764678 0.08073222 -0.9317221 0.3531435 0.08475589 -0.9317244 0.3531375 0.08475595 -0.9217876 0.3793355 0.08007484 -0.9767011 0.1977698 0.08331841 -0.9768279 0.1971299 0.08334934 -0.9767064 0.1977492 0.08330589 -0.9768375 0.197149 0.08319199 -0.9524011 0.2924822 0.08594322 -0.9574204 0.2763149 0.0836445 -0.9526862 0.2925614 0.08244419 -0.9526908 0.2925458 0.08244514 -0.9925085 0.1007485 0.06911265 -0.9886018 0.1192061 0.09195852 -0.8965269 0.1824657 0.4036652 -0.9902839 0.1171329 0.07495123 -0.9879212 0.1285212 0.08656841 -0.988601 0.1192126 0.09195894 -0.9886013 0.1192034 0.09196662 -0.9933372 0.06934762 0.09204477 -0.9858329 0.1216824 -0.1154422 -0.696254 0.1297586 -0.7059695 -0.9124547 0.4011704 0.08055388 -0.9124776 0.4011177 0.08055496 -0.9216136 0.3792545 0.08242851 -0.8941752 0.4408457 0.0781393 -0.921589 0.3792713 0.0826261 -0.8516938 0.5159785 0.09156352 -0.8837476 0.4605504 0.08296585 -0.8944965 0.4404373 0.07675266 -0.884179 0.4603431 0.07944691 -0.8742765 0.4778117 0.08565348 -0.8654368 0.4928971 0.0898419 0.2115985 0.0404514 -0.9765192 0.2116414 0.04045665 -0.9765097 0.1911606 0.03869837 -0.9807956 0.1961219 0.0212537 -0.9803492 0.1576615 0.0136817 -0.9873984 0.1734938 -0.005290806 -0.9848209 0.1842786 -0.006551682 -0.9828523 0.178993 -6.92579e-4 -0.9838501 0.2022497 0.007313251 -0.9793067 0.2017214 0.01835721 -0.9792708 0.214843 0.01706355 -0.9764994 0.2102642 0.0207526 -0.9774244 0.06625109 -0.03371787 -0.9972331 0.2117579 0.02046853 -0.9771078 0.2102328 0.02076625 -0.9774308 -0.9659257 0 0.2588196 -0.9659257 0 -0.2588198 -0.9659257 0 -0.2588198 -0.7071055 0 -0.707108 -0.7071055 0 -0.707108 -0.2588208 0 -0.9659254 -0.2588208 0 -0.9659254 0.2588185 0 -0.965926 0.2588185 0 -0.965926 0.7071055 0 -0.707108 0.7071055 0 -0.707108 0.9659257 0 -0.2588198 0.9659257 0 -0.2588198 0.9659257 0 0.2588196 0.9659257 0 0.2588196 0.7071055 0 0.7071081 0.7071055 0 0.7071081 0.2588178 0 0.9659261 0.2588178 0 0.9659261 -0.2588202 0 0.9659255 -0.2588202 0 0.9659255 -0.7071055 0 0.7071081 -0.7071055 0 0.7071081 -0.9659257 0 0.2588196 -0.1818442 0.07708191 -0.9803015 -0.1905431 0.1142219 -0.9750111 -0.2022501 0.09707003 -0.9745113 -0.2001019 0.09418767 -0.9752374 -0.1991574 0.09403663 -0.9754453 -0.1978431 0.09200745 -0.9759061 -0.2029173 0.0669164 -0.9769068 -0.2029166 0.06692445 -0.9769063 -0.2024874 0.06377136 -0.9772063 -0.2072728 0.06785434 -0.9759272 -0.2092684 0.06814098 -0.9754812 -0.2081708 0.07129609 -0.9754906 -0.2079517 0.0717408 -0.9755046 -0.2054915 0.06900042 -0.9762234 -0.2048623 0.06928128 -0.9763358 -0.2048616 0.06928217 -0.9763358 -0.1973825 0.07270228 -0.977627 -0.2003841 0.07474613 -0.9768619 -0.192439 0.06068152 -0.9794309 -0.1956474 0.06327986 -0.9786306 -0.1962255 0.06223028 -0.9785822 -0.1962241 0.06353628 -0.9784985 -0.1966907 0.06244724 -0.9784749 -0.2029271 0.06638127 -0.9769412 -0.1972779 0.05105793 -0.9790171 -0.2020547 0.05354005 -0.9779097 -0.2021343 0.05256581 -0.9779461 -0.20243 0.05366176 -0.9778254 -0.2027059 0.0527305 -0.9778189 -0.2056277 0.05466455 -0.9771024 -0.203188 0.03821641 -0.9783937 -0.2100808 0.04054176 -0.9768431 -0.210067 0.04051554 -0.9768472 -0.2102121 0.0396654 -0.9768508 -0.2102153 0.03963601 -0.9768514 -0.2116712 0.04088121 -0.9764855 -0.2004889 0.02148348 -0.9794604 -0.2167106 0.0212478 -0.9760046 -0.2167005 0.02124732 -0.9760069 -0.2158623 0.02119147 -0.9761939 0.2770933 0.01853489 -0.9606643 0.27763 0.01940399 -0.9604922 0.28362 0.01941215 -0.9587402 0.2594221 0.03190213 -0.965237 0.2651472 0.03102099 -0.9637089 0.2648013 0.03300714 -0.963738 0.2656412 0.03109371 -0.9635704 0.2659816 0.03326344 -0.963404 0.2782692 0.03354835 -0.959917 0.2588613 0.04538965 -0.9648474 0.2662366 0.04596555 -0.9628111 0.265776 0.04752159 -0.9628628 0.266823 0.04614371 -0.9626403 0.2663881 0.04774856 -0.9626824 0.2740326 0.04829788 -0.9605069 0.2548989 0.05671173 -0.9653033 0.2647965 0.05913347 -0.9624895 0.2641423 0.06066507 -0.9625739 0.2651556 0.05928438 -0.9623814 0.2644267 0.06079471 -0.9624876 0.26963 0.0611158 -0.9610226 0.2481959 0.06855726 -0.9662808 -0.5382966 -0.8427554 -2.3012e-4 -0.5588123 -0.8292938 -7.94693e-4 -0.4391466 -0.8984153 2.17807e-4 -0.4116165 -0.9113569 6.79161e-4 -0.3933179 -0.9194018 0.001138389 -0.3747258 -0.9271355 6.27656e-4 -0.3283696 -0.9445493 0 -0.8239085 -0.5667229 0 -0.8239085 -0.5667229 0 -0.7043213 -0.7094733 -0.0240643 -0.5382975 -0.8427549 -2.3012e-4 -0.5588582 -0.8292632 4.4264e-4 -0.6926786 -0.7212463 -4.64161e-4 -0.7045267 -0.7096775 5.69505e-5 -0.6926785 -0.7212466 5.66827e-5 -0.8031266 -0.5958039 0.002331912 -0.8203407 -0.5718751 0 0.9859702 -0.1669203 -5.59985e-4 0.9724963 -0.2329141 0.001337647 0.9999978 -0.002106964 0 0.9969311 -0.07828366 1.55425e-5 0.9987064 -0.05080831 0.001977145 0.9940516 -0.1089088 5.02735e-4 0.8793177 -0.4762355 -2.46455e-4 0.9059989 -0.42328 1.81879e-4 0.924222 -0.3818536 0.001222252 0.9325287 -0.361096 1.3788e-4 0.9724959 -0.2329197 -2.11154e-4 0.9640905 -0.2655718 0.001080811 0.9640785 -0.2656151 0.001080811 0.8793174 -0.4762364 -2.46455e-4 0.8532949 -0.5214269 0.001376926 0.8316232 -0.5553404 -2.47861e-4 0.6509544 -0.7591156 0.001395225 0.6918517 -0.7220394 -4.55656e-4 0.7614544 -0.6482179 8.0326e-4 0.7611836 -0.6485359 8.13013e-4 0.7614548 -0.6482174 8.13013e-4 0.7611821 -0.6485378 8.28046e-4 0.7978362 -0.6028744 7.92944e-5 0.5611669 -0.8277027 2.06176e-4 0.6158012 -0.7879015 -3.3044e-4 0.615796 -0.7879055 -3.3044e-4 0.5036016 -0.8639341 0.001817703 0.5244861 -0.851419 1.14247e-4 0.4138358 -0.9103515 -7.22824e-5 0.3851808 -0.9228405 0.001045227 0.4139046 -0.9103197 0.001044332 0.3851565 -0.9228504 0.001317679 0.3202794 -0.947323 -5.5872e-4 0.08185535 -0.996644 6.40523e-4 0.1891882 -0.9819408 -3.81322e-4 0.2364251 -0.9716496 -3.80879e-4 0.1892436 -0.9819253 0.003068089 0.2555725 -0.9667897 7.1561e-4 -0.07470005 -0.9972051 0.001361906 -0.01133739 -0.9999355 -5.26382e-4 0.08919906 -0.9960132 0.001097798 -0.299259 -0.9541719 0 -0.2294225 -0.9733269 3.93263e-4 -0.2450336 -0.9695135 0.001454412 -0.1461756 -0.9892585 -5.71909e-4 -0.07467705 -0.9972069 0.001295864 -0.07885575 -0.9968851 0.001336872 -0.07886695 -0.9968843 0.001336872 -1 0 0 -1 0 0 0 0 1 0 0 1 -0.9349797 -0.3547013 0 -0.9349797 -0.3547013 0 -0.8825525 -0.470214 0 -0.8825525 -0.470214 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.3826457 -0.002474606 0.9238919 -0.3743897 0 0.9272714 -0.3826397 -0.00247097 0.9238944 -0.3743897 0 0.9272715 0.05703037 0 0.9983725 0.05703037 0 0.9983725 0.4889081 0 0.8723354 0.4889081 0 0.8723354 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.9125335 -0.003126084 -0.4089898 -0.846509 0.0142011 0.5321851 -0.8203891 0.05259639 0.5693817 -0.8186454 0.0776773 0.5690219 -0.9936262 0.003266274 0.1126785 -0.9992737 3.69626e-4 0.03810334 -0.9984545 7.48697e-4 0.05556988 -0.9969329 0.001594483 0.07824563 -0.999998 -2.09128e-5 0.002017438 -0.9999132 4.23402e-5 0.01317459 -0.9996709 1.4381e-4 0.0256564 -0.9847418 0.008496463 0.1738144 -0.9654979 0.02259987 0.2594286 -0.9792458 3.26004e-4 0.2026761 -0.8947706 -8.66746e-5 0.446526 -0.8951897 -8.66753e-5 0.4456856 -0.9792412 -0.003059327 -0.2026754 -0.9519045 0.03721529 -0.3041262 -0.9731616 0.01713943 -0.2294834 -0.9855502 0.008252322 -0.1691821 -0.9924593 0.004020512 -0.1225085 -0.9967391 0.001580715 -0.08067548 -0.999068 0.04316163 8.41848e-5 -0.9999679 -2.09121e-5 -0.008000969 -0.999459 2.33892e-4 -0.03288835 -0.9986388 6.92241e-4 -0.05215406 -0.818821 0.07487571 -0.5691448 -0.8229705 0.03939145 -0.5667167 -0.8605874 0.008734703 -0.5092279 0.6435284 0 -0.7654222 0.6704758 0.03122067 -0.7412742 0.6707751 0.009100735 -0.7416051 0.6891338 0 -0.7246341 0.8287482 0.1491726 -0.5393737 0.829605 0.1470102 -0.53865 0.8303261 0.1461569 -0.5377699 0.9040594 0.4121678 -0.1131123 0.9056989 0.4086934 -0.1126019 0.9087519 0.4030179 -0.1083813 0.8867504 0.4600067 -0.04547113 0.8872624 0.2754486 -0.3699913 0.7910589 0.05595684 -0.6091753 0.7467617 0.1393487 -0.6503298 0.7642758 0.05832725 -0.6422464 0.7146883 0.3255165 -0.6190797 0.8064175 0.4189104 -0.4173789 0.8720138 0.3191295 -0.3711447 0.890383 0.4529267 -0.04555916 0.9042987 0.4117071 -0.1128761 0.8015351 0.5876821 -0.1103233 0.807466 0.5582607 -0.19064 0.9188166 -0.1174793 -0.3767949 0.5569271 -0.02105462 -0.8302944 0.7412418 0.1020265 -0.6634389 0.6528618 0.1494198 -0.7425934 0.6342805 0.1556965 -0.7572627 0.6406863 0.2276322 -0.7332835 0.6292234 0.2248052 -0.7440031 0.8385008 0.5368539 -0.09329682 0.8456701 0.5241662 -0.1004576 0.8456675 0.5241731 -0.1004444 0.77583 0.3958113 -0.4913464 0.7894982 0.3315913 -0.5164684 0.789498 0.3315877 -0.5164712 0.8675956 0.493131 -0.06403011 0.8733232 0.4814637 -0.07415783 0.8396996 0.3585245 -0.4078782 0.8423382 0.2904101 -0.4540136 0.6801306 0.160096 -0.7153961 0.6562513 0.1971197 -0.7283391 0.6477116 0.3840374 -0.658016 0.5967486 0.2880088 -0.7489606 0.5521885 0.3970362 -0.7331099 0.6799029 0.5454823 -0.4900827 0.6719223 0.5658086 -0.4778922 0.6666459 0.5614287 -0.4902868 0.7505606 0.6531734 -0.1001171 0.7335333 0.5324404 -0.4224171 0.7402384 0.4819003 -0.4688488 0.6605729 0.4291812 -0.6159927 0.6057806 0.496012 -0.6220948 0.5892642 0.4583067 -0.6653741 0.6908037 0.3265566 -0.6450977 0.6466205 0.5159476 -0.5618542 0.711546 0.557697 -0.4274064 0.8109532 0.2956125 -0.5049436 0.7587195 0.6379915 -0.1315743 0.7801589 0.6110054 -0.1342556 0.7925398 0.5952094 -0.1326896 0.7807928 0.6156689 -0.1063686 0.7599601 0.6402344 -0.1120738 0.7804667 0.6126604 -0.1245751 0.6446732 0.5825866 -0.4949639 0.545047 0.5009656 -0.6722777 0.5490466 0.5042672 -0.6665303 0.7493543 0.6545564 -0.1001213 0.7542363 0.6487864 -0.1010147 0.6207962 0.6117341 -0.4902994 0.6207057 0.6116125 -0.4905656 0.5903587 0.6461507 -0.4837002 0.6500709 0.5766025 -0.4949116 0.7154251 0.6921795 -0.09515482 0.7165965 0.6901287 -0.1010537 0.74922 0.6554593 -0.09509223 0.6954891 0.7122207 -0.09506213 0.5931394 0.6435043 -0.4838263 0.6338976 0.7070616 -0.3134288 0.6183277 0.7129311 -0.3307569 0.6622811 0.6723459 -0.330658 0.6201855 0.6411234 -0.4520297 0.6034036 0.6378549 -0.4785867 0.6285964 0.7613251 -0.1589046 0.6029602 0.7880362 -0.1242482 0.6223042 0.7728275 -0.1243991 0.5929288 0.8037505 0.04919981 0.5473325 0.8369152 -1.28513e-4 0.6429782 0.7630575 -0.06574499 0.6225641 0.782553 0.004966437 0.6064089 0.7942883 0.03707224 0.5915539 0.7980031 -0.1151302 0.6530286 0.7288914 -0.205599 0.5288305 0.8435437 0.09365975 0.6817266 0.7138423 -0.1602434 0.7273295 0.6315886 0.2684919 0.6954905 0.7122222 -0.09503924 0.7162755 0.6967666 -0.03828537 0.6283777 0.7615041 -0.1589121 0.4763825 0.8789932 0.02074897 -0.6759416 0.734113 0.06466102 -0.6783307 0.7345582 0.01707971 0.4747381 0.8787135 0.04986357 0.4710336 0.8815647 0.03116041 0.4121435 0.9105798 0.03134232 0.4128959 0.9102029 0.0323674 0.4121564 0.9105017 0.03337121 0.3229509 0.9458949 0.03139084 0.324374 0.9453372 0.03345125 0.3229138 0.9458487 0.03312087 0.3243166 0.945296 0.03513216 0.253755 0.9667153 0.03271216 0.08927434 0.9953954 0.03489804 0.08899962 0.9954227 0.03482204 0.1824709 0.9825899 0.0349487 0.1815434 0.9827718 0.03466296 0.1824218 0.9826655 0.03302508 0.1816613 0.9828099 0.03292208 0.2522124 0.9670504 0.03467905 -0.0804705 0.9961001 0.0361793 -0.08158081 0.9960306 0.03560376 -0.005930244 0.999289 0.03723007 -0.006615877 0.9992957 0.03693932 -0.005959391 0.9993336 0.03601258 -0.006640791 0.9993396 0.03572511 0.08898127 0.9954013 0.03547596 -0.2456584 0.9686844 0.03608936 -0.2459617 0.9686024 0.0362237 -0.2456933 0.9686577 0.03656709 -0.2459146 0.9685974 0.03667491 -0.1540229 0.9873849 0.03671419 -0.1534188 0.9874916 0.03637498 -0.1539893 0.9874362 0.03545224 -0.08157891 0.9959815 0.0369535 -0.3333615 0.9420521 0.03752207 -0.333725 0.9419508 0.03683 -0.333409 0.9420647 0.03677809 -0.418744 0.9073579 0.03681123 -0.4188844 0.9072899 0.03689068 -0.4186899 0.9073657 0.03723138 -0.4195141 0.9069843 0.03724533 -0.5024046 0.8638839 0.03597766 -0.5023421 0.863927 0.03581607 -0.5647907 0.8244283 0.03646385 -0.5654705 0.8239667 0.03636044 -0.5646489 0.8245438 0.03604394 -0.5654675 0.8240169 0.03525388 -0.6227684 0.7815248 0.03712981 -0.6242666 0.7804281 0.0349754 -0.6228993 0.7815963 0.03322112 -0.6722462 0.7394382 0.03628009 -0.6750407 0.7363317 0.04621589 -0.8543133 0.518875 0.03029197 -0.7100564 0.7012205 0.06410849 -0.7185412 0.6940199 0.0451101 -0.7101514 0.7038737 0.0157091 -0.7099508 0.7042514 -6.81644e-5 -0.8542156 0.5190356 0.03029179 -0.8542353 0.5190045 0.03027087 -0.8456765 0.5327086 0.03244829 -0.846 0.5317826 0.03861773 -0.8459274 0.5301227 0.05811059 -0.7100977 0.7011854 0.06403493 -0.7132642 0.700029 0.03483849 -0.7586365 0.6506206 0.0341109 -0.7587952 0.6504533 0.03376555 -0.7586542 0.6506309 0.03351509 -0.756219 0.6534605 0.03349864 -0.8116262 0.5831757 0.03419131 -0.8118685 0.582869 0.03366523 -0.8116647 0.5831713 0.03334224 -0.8469477 0.5306146 0.03358405 -0.8401454 0.5422321 0.01183515 -0.9994589 0 0.03289276 -0.9989634 -0.03253537 0.03183478 -0.9999941 0 0.003419816 -0.9875706 -0.1537829 0.03248411 -0.9931085 -0.1119062 0.03482294 -0.9981116 0 0.06142693 0.02591335 0.9996546 0.004392206 0.2088638 0.9774152 0.0321772 0.2088806 0.9774116 0.03217947 0.1047471 0.9941634 0.02582943 0.09870201 0.9947487 0.02707612 0.1005998 0.9948062 0.01549923 0.1108745 0.9936268 0.02031314 0.1115283 0.9936351 0.01583206 0.1162347 0.9930248 0.01978307 0.1168588 0.993031 0.01527869 0.1284113 0.9915205 0.01993703 0.311537 0.9484525 0.05815911 0.2951854 0.9535034 0.06080204 0.2963938 0.9535647 0.05352723 0.3027745 0.952064 0.04360884 0.3274938 0.9431775 0.05624872 0.3293424 0.9432023 0.04362052 0.34268 0.9378444 0.05493938 0.3444468 0.9378566 0.04220652 0.376973 0.9245924 0.05495589 0.3787995 0.9247287 0.03725278 0.3786935 0.9246084 0.0411185 0.1291745 0.9915409 0.01266944 0.129186 0.9915259 0.01368898 0.3802853 0.9247387 0.01553606 0.3805233 0.9246125 0.01714229 0.1296859 0.991541 0.005297362 0.1297859 0.9915257 0.005707502 0.987541 0.1573619 0 0.9876888 0.1564314 4.06351e-5 0.8897165 0.4565134 -4.10495e-5 0.8910002 0.4540032 -1.09337e-5 0.8897141 0.4565183 -1.09244e-5 0.891008 0.4539874 8.20234e-5 0.703781 0.710417 -8.17712e-5 0.7070938 0.7071197 1.83893e-5 0.7037529 0.7104448 1.84253e-5 0.7071182 0.7070954 1.23842e-4 0.4481177 0.8939745 -1.23627e-4 0.4539955 0.8910039 8.83043e-5 0.4480679 0.8939995 8.83613e-5 0.4539643 0.8910198 1.65697e-4 0.1527124 0.9882706 -1.61479e-4 0.1564334 0.9876885 0 0.3522735 0.8901262 -0.2890996 0.4535424 0.8901145 -0.04467159 0.5479308 0.7053853 -0.4496706 0.7053856 0.7054114 -0.06946909 0.689442 0.4522522 -0.5658073 0.8875885 0.4522649 -0.08742517 0.9830479 0.1556964 -0.09682768 0.9830474 0.1557012 -0.09682363 0.9452732 0.1557011 -0.2867328 0.9452705 0.1557043 -0.2867403 0.7635821 0.1556962 -0.6266587 0.7635825 0.1556975 -0.6266577 0.871162 0.1556979 -0.4656553 0.8711659 0.1557016 -0.4656467 0.8711686 0.155698 -0.465643 0.9452692 0.1556981 -0.286748 0.6894441 0.4522407 -0.5658137 0.689441 0.4522532 -0.5658075 0.7865768 0.4522531 -0.420433 0.7865769 0.452249 -0.4204375 0.8534885 0.4522485 -0.258899 0.8534901 0.4522409 -0.2589071 0.8876012 0.4522407 -0.08742082 0.8875974 0.4522495 -0.08741402 0.5479084 0.7054128 -0.4496544 0.5479131 0.7053999 -0.449669 0.6251127 0.7054002 -0.3341323 0.6251127 0.7054007 -0.3341319 0.6782867 0.705401 -0.2057589 0.6782844 0.705405 -0.2057527 0.7053928 0.7054045 -0.06946533 0.7054094 0.7053865 -0.06947922 0.3522871 0.8901171 -0.2891116 0.3522861 0.8901197 -0.2891045 0.4019148 0.8901195 -0.2148293 0.4019151 0.890119 -0.2148308 0.436105 0.890119 -0.1322893 0.4361061 0.8901181 -0.1322917 0.4535335 0.8901186 -0.04467809 0.4535112 0.8901306 -0.04466819 0.1214958 0.9875714 -0.09970778 0.1214958 0.9875713 -0.09970802 0.1386127 0.9875713 -0.07409095 0.1386125 0.9875714 -0.07408964 0.1504032 0.9875714 -0.04562443 0.1504037 0.9875713 -0.04562616 0.1564149 0.9875712 -0.01540595 0.1564149 0.9875712 -0.01540577 0.7911111 0.313227 0.5253877 0.7539526 0.04089874 0.6556544 0.7396489 0.644867 0.1925255 0.2414143 0.6721977 -0.6999067 0.3276312 0.5527172 -0.7662646 0.5882163 0.6954965 -0.4126576 0.9101312 0.3917605 0.1348518 0.8893144 0.4533777 -0.05973869 0.468585 0.4231678 -0.7754722 0.5334677 0.2010398 -0.821581 0.6242219 0.4298709 -0.6523482 0.8838089 0.2510153 -0.3948078 0.981177 0.1613239 -0.1061431 0.7031456 0.107365 -0.7028933 0.6435285 0 -0.7654223 0.6435284 0 -0.7654223 0.527688 0.5745046 -0.6256915 0.3763344 0.8124644 -0.4452798 0.2806322 0.900617 -0.3318653 0.2809068 0.9005538 -0.3318047 0.2807067 0.9005945 -0.3318633 0.2807397 0.9005917 -0.3318427 0.3764542 0.8125166 -0.4450831 0.4587615 0.703441 -0.5428706 0.4586684 0.7034786 -0.5429006 0.4587814 0.7033917 -0.5429178 0.4584274 0.7035002 -0.5430763 0.5278453 0.5746411 -0.6254335 0.5821382 0.4295195 -0.6903826 0.5818374 0.4296673 -0.6905443 0.5819467 0.4294495 -0.6905876 0.581686 0.4296845 -0.6906611 0.6197425 0.2724282 -0.7360042 0.6195955 0.2722784 -0.7361832 0.640108 0.1075388 -0.7607216 0.6398556 0.1074042 -0.7609527 0.004944682 0.9999707 -0.005833864 0.07970064 0.9923737 -0.09403294 0.07963418 0.9923733 -0.09409475 0.1812527 0.9598335 -0.2141659 0.1811811 0.9598265 -0.2142581 0.5711557 0 -0.8208418 0.6368108 0.1074244 -0.7634999 -0.1003939 0.160083 -0.981985 0.2723093 0.2557679 -0.9275939 0.3249841 0.6976857 -0.6384512 -0.4376492 0.288109 -0.8517373 -0.295389 0.383989 -0.874813 0.7068104 0.4197835 -0.5693864 0.7067986 0.4197085 -0.5694564 0.324978 0.6977376 -0.6383976 -0.5761339 0.3817874 -0.7227088 -0.7892366 0.006407797 -0.6140558 0.004456996 0.9999707 -0.006214141 -0.04663282 0.9805878 -0.1904541 -0.4410524 0.7480291 -0.4959084 0.05557417 0.9497857 -0.3079262 0.375229 0.8916583 -0.2532763 0.3752708 0.8916152 -0.2533662 0.3834657 0.8362585 -0.3919513 0.5792112 0.7808955 -0.2339156 0.6383002 0.5617626 -0.5263037 0.5687026 0.5756759 -0.5875157 0.4742926 0.2254209 -0.8510182 0.6823346 0.2084643 -0.7006869 0.6700788 0.2248809 -0.7074058 0.1440343 0.9805176 -0.1335646 0.1365942 0.9811999 -0.1363408 0.3036698 0.8518337 -0.4268069 0.3786867 0.836665 -0.3957118 0.425715 0.6148924 -0.663833 0.5646399 0.5711749 -0.5957693 0.4900507 0.287491 -0.8229211 0.7005324 0.2931444 -0.6506311 0.6655192 0.2962541 -0.6850677 0.5061174 0.3792137 -0.7746239 0.563614 0.647408 -0.5130324 0.5203394 0.6132445 -0.5942881 0.4308544 0.6570643 -0.6185718 0.3838392 0.8480125 -0.3654344 0.1625814 0.9791503 -0.1217867 0.1568991 0.9798203 -0.1238343 0.3118429 0.8649672 -0.3931741 0.3118752 0.8649535 -0.3931785 0.6587333 0.5968294 -0.4581103 0.5368744 0.5249147 -0.6604775 0.2412535 0.6414294 -0.7282618 0.6418447 0.3720353 -0.6705408 0.6418488 0.3720338 -0.6705379 0.2140433 0.9663465 -0.1426885 0.07823336 0.9795194 -0.1855295 0.3948959 0.8582707 -0.327763 0.428628 0.8023995 -0.4152506 0.1827718 0.8570556 -0.4817158 0.5529828 0.6489596 -0.522553 0.2245016 0.9666145 -0.1235132 0.2452408 0.9622029 -0.1184174 0.3456513 0.8469748 -0.4039291 0.4730191 0.7955178 -0.3786879 0.4381578 0.5743584 -0.6914697 0.6205239 0.5148787 -0.591481 0.5808693 0.626038 -0.5202569 0.2409008 0.963891 -0.1134946 0.2325152 0.9653199 -0.1187183 0.3748772 0.848936 -0.3725245 0.4022535 0.8427613 -0.3576947 0.4280993 0.8406549 -0.3317081 0.467284 0.6429856 -0.6068074 0.5876998 0.6326271 -0.5043728 0.5825812 0.6174827 -0.5285019 0.4599303 0.6435564 -0.6118002 0.4246901 0.8364351 -0.3464316 0.3691646 0.8471646 -0.3821381 0.2263438 0.9663545 -0.1221781 0.2348692 0.9649633 -0.1169704 0.3433755 0.9388759 -0.02460569 0.39135 0.9194701 -0.03768169 0.4437406 0.8927782 -0.07772558 0.4438375 0.8927277 -0.07775235 0.443835 0.8927295 -0.07774674 0.4587144 0.8885816 0.00195378 0.4440385 0.8943787 -0.05400568 0.4297975 0.9026286 -0.02314639 0.4157032 0.9093106 0.01857483 0.5660849 0.8241924 -0.01596224 0.5950511 0.803049 0.03203898 0.5881642 0.8058526 0.06829702 0.587531 0.8091031 -0.01263058 0.5805343 0.8125332 0.0526269 0.5765364 0.8123128 0.08805555 0.6113256 0.7882845 0.0699172 0.6108456 0.7876637 0.080334 0.6000788 0.7992595 0.03301209 0.6012079 0.7990851 0.003497838 0.6285442 0.7705587 0.1056951 0.6145248 0.7833613 0.09329718 0.6146064 0.7834433 0.09206247 0.5666407 0.8230664 -0.03847223 0.5452432 0.8299445 -0.1179073 0.5868642 0.8073563 -0.061369 0.5400068 0.8243442 -0.1698514 0.595 0.7970673 -0.103241 0.3914923 0.9194492 -0.03670102 0.3780723 0.9237911 -0.06059187 0.3852339 0.921074 -0.05672222 0.5906299 0.7991494 -0.1118776 0.541215 0.8050383 -0.2428985 0.6077337 0.7742123 -0.1767915 0.3813282 0.9223313 -0.06239986 0.359839 0.9285795 -0.09086388 0.3692072 0.9251163 -0.08857774 0.3306301 0.9350475 -0.127945 0.3413081 0.9315571 -0.1253404 0.3044016 0.9396023 -0.1564838 -0.02874648 0.9527601 -0.3023605 0.5010706 0.8220527 -0.2704771 0.50107 0.8220531 -0.2704762 0.601408 0.7769455 -0.1861833 0.5133047 0.7958203 -0.3212295 0.6141442 0.7372932 -0.2814704 0.481087 0.7700794 -0.4189667 0.6081327 0.6977565 -0.3785638 0.2806605 0.7294635 -0.623789 0.5911028 0.6318368 -0.5013779 0.8873975 0.4553297 0.07211375 0.9872342 0.1126249 0.1126241 0.9872343 0.1419161 0.07230687 0.9872344 0.1573131 0.02491933 0.676748 0.1950449 0.7099081 0.6744331 0.5220796 0.5220853 0.6800839 0.5502304 0.484492 0.6800843 0.5502273 0.4844949 0.5099232 0.5523149 0.6594896 0.5493853 0.7445016 0.3793329 0.4246088 0.8306078 0.3602752 0.3382357 0.4390648 0.8323573 -0.3593775 0.4719162 0.8050732 0.1515275 0.9806026 0.1243294 0.6767477 0.195035 0.7099112 0.7551788 0.1025419 0.6474491 0.8874036 0.0721125 0.4553183 0.8874023 0.07211905 0.4553198 0.8873993 0.4553244 0.0721262 0.8874008 0.4553219 0.07212352 0.8874008 0.4107563 0.2092822 0.8874017 0.4107567 0.2092776 0.8874026 0.3259741 0.3259718 0.8874017 0.3259723 0.3259758 0.7465457 0.3020589 0.5928152 0.8874049 0.2092879 0.4107446 0.8874008 0.2092738 0.4107606 0.987234 0.0723049 0.1419194 0.6993681 0.7059625 0.1118083 0.6993548 0.7059733 0.1118242 0.6993557 0.6368764 0.3244841 0.6993502 0.6368764 0.3244965 0.6928104 0.4624999 0.55327 0.5099482 0.5524617 0.6593473 0.8874046 0.07211482 0.4553158 0.9872338 0.02491647 0.1573168 0.5925561 0.790567 0.1545353 -0.2537925 0.9553526 0.151297 0.4436436 0.8851719 0.1401826 0.4436864 0.8851487 0.1401931 0.4436926 0.8851466 0.1401868 0.69934 0.7059898 0.1118125 0.9807859 0 0.1950873 0.9766855 -0.1478604 0.155636 0.8860181 0.09114223 0.4546044 0.8280534 0.09054309 0.5532896 0.8381466 -0.3355141 0.4300471 0.7591806 0 0.65088 -0.2045614 0 0.9788537 -0.04075533 0.9913894 0.1244432 -0.1221747 -0.9677155 0.2204546 -0.07644701 -0.9676733 0.240342 -0.120002 -0.96887 0.2165417 -0.08537131 0.9934466 0.07599776 -0.5063596 0.6985563 0.505588 -0.7910558 -0.5181964 0.3251205 -0.5976632 -0.5344133 0.5976632 -0.7630797 -0.565084 0.3136709 -0.1148412 0.9927337 0.03593695 -0.989715 -0.00238806 0.1430335 -0.6241673 0.3314347 0.707507 -0.3074997 0.01247847 0.9514664 -0.2780607 0.1076787 0.9545091 -0.2748561 0.1284508 0.9528664 -0.2712792 0.1470758 0.9511973 -0.268315 0.1424617 0.9527392 -0.2683794 0.142497 0.9527157 -0.2751456 0.1154676 0.9544433 -0.2904455 0.1124919 0.9502563 -0.2748534 0.1284565 0.9528664 -0.3078215 0.08485746 0.9476525 -0.2846271 0.08993059 0.9544107 -0.2874664 0.07924687 0.9545067 -0.3015474 0.066868 0.9511035 -0.2943117 0.04990118 0.9544059 -0.2943119 0.04989993 0.9544059 -0.3088935 0.04065996 0.9502271 -0.3052582 0.03343617 0.9516824 -0.3006467 0.01521122 0.9536144 -0.3008824 0.01220375 0.9535831 -0.3052162 0.01544451 0.9521579 -0.7120128 0.02960175 0.7015421 -0.7069078 0.02939182 0.7066948 -0.9529061 0.03988528 0.3006312 -0.9529256 0.0398494 0.3005744 -0.9456338 0.1244846 0.3004665 -0.945587 0.1245847 0.3005726 -0.9455723 0.1244747 0.3006644 -0.931025 0.2066746 0.300796 -0.9309781 0.2064573 0.3010899 -0.909317 0.2873433 0.3009592 -0.9093037 0.2873771 0.3009672 -0.9092908 0.2873023 0.3010774 -0.7063388 0.02985775 0.707244 -0.7010579 0.09235876 0.7070981 -0.7009737 0.09227782 0.7071922 -0.6900605 0.1531652 0.7073592 -0.6899567 0.1530111 0.7074937 -0.674029 0.2130215 0.7073236 -0.6739819 0.2129565 0.7073882 -0.6516336 0.2735149 0.7075049 -0.6516106 0.2734686 0.707544 -0.6241475 0.3316336 0.7074313 -0.6240116 0.3313501 0.707684 -0.8792781 0.369009 0.3011685 -0.8792378 0.369059 0.3012246 -0.8792452 0.3690201 0.301251 -0.8420709 0.4474568 0.3011626 -0.8420547 0.4471085 0.3017247 -0.3287166 0.8922049 0.3097028 0.08971917 0.2872141 0.9536553 0.1131202 0.2672597 0.956962 0.1131153 0.267268 0.9569601 0.06665635 0.2941538 0.953431 0.07132291 0.2834013 0.9563455 0.07130682 0.2834057 0.9563454 0.02276033 0.2921503 0.9561015 0.02278733 0.2921483 0.9561015 0.03724068 0.2967842 0.9542182 0.0421673 0.2876092 0.9568192 0.04214024 0.2876139 0.956819 0.003110945 0.2977451 0.9546404 0.01586169 0.287245 0.9577258 0.00302273 0.2876744 0.9577236 -0.004653751 0.2975974 0.9546802 -0.02569109 0.2856326 0.9579948 -0.0256682 0.2856341 0.9579949 -0.03396737 0.2946156 0.955012 -0.05431491 0.2813525 0.9580661 -0.05431926 0.2813517 0.9580661 -0.06243181 0.2888522 0.9553359 -0.07422882 0.2804056 0.9570072 -0.1022945 0.2776695 0.955215 -0.09149342 0.2705242 0.9583557 -0.07959663 0.2742509 0.9583584 -0.09458506 0.2796741 0.9554244 -0.07424855 0.2804003 0.9570072 -0.1295627 0.2665814 0.9550643 -0.1181951 0.2603893 0.9582417 -0.1181771 0.260397 0.9582419 -0.1637609 0.2419765 0.9563629 -0.1638097 0.2419431 0.9563629 -0.1554673 0.2532069 0.9548383 -0.1444838 0.2482711 0.9578549 -0.1444776 0.2482746 0.9578548 -0.1834068 0.2349758 0.9545409 -0.1676644 0.2346821 0.9575035 -0.1774579 0.2273739 0.9575018 -0.1909325 0.2309655 0.9540438 -0.2004108 0.2095515 0.9570389 -0.200419 0.2095441 0.957039 -0.2137258 0.2118758 0.9536404 -0.2219653 0.1894065 0.9564814 -0.2219678 0.1894036 0.9564813 -0.2341197 0.1905555 0.9533502 -0.237516 0.1796336 0.9546298 -0.2468172 0.1650361 0.9549054 -0.2424052 0.1710666 0.9549742 -0.2421807 0.161804 0.9566441 -0.2486586 0.1521826 0.9565612 -0.2526367 0.1687812 0.9527264 -0.5973769 0.3770776 0.7077805 -0.5971996 0.3769648 0.7079903 -0.8043371 0.5117385 0.301936 -0.8021743 0.5134533 0.3047656 -0.7781409 0.5491745 0.3048016 -0.7779158 0.5493746 0.3050155 -0.7780449 0.5491895 0.3050197 -0.738668 0.6012467 0.304749 -0.73815 0.6014464 0.3056094 -0.73856 0.6009247 0.3056448 -0.6761398 0.6703804 0.3056553 -0.675436 0.6705823 0.3067666 -0.6759708 0.6700072 0.3068451 -0.6063908 0.7335776 0.3068451 -0.605685 0.7337146 0.30791 -0.60612 0.7333142 0.3080078 -0.5525107 0.7743937 0.3082959 -0.5528873 0.7739499 0.3087348 -0.4153703 0.8553045 0.3097123 -0.4156745 0.8553317 0.3092284 -0.4156855 0.8553295 0.3092198 -0.4972013 0.8106618 0.3092222 -0.4976855 0.8106573 0.3084539 -0.4976709 0.8106617 0.3084661 -0.3286843 0.8922087 0.309726 -0.3285902 0.8921903 0.3098786 -0.2649667 0.9130108 0.3101675 -0.2650408 0.913006 0.3101183 -0.2651179 0.9129813 0.3101255 -0.2008742 0.9293245 0.3098475 -0.201047 0.9293767 0.3095788 -0.2008722 0.9294223 0.3095557 -0.108933 0.9446232 0.309549 -0.1092472 0.9447479 0.3090571 -0.1088711 0.9448139 0.3089887 -0.01490473 0.9509544 0.3089722 -0.01541012 0.9512063 0.3081706 -0.01489228 0.9512555 0.3080444 0.05175554 0.9498704 0.3083304 0.05234044 0.9499837 0.3078824 0.1177854 0.9446208 0.3062977 0.1184452 0.9441093 0.3076171 0.1184217 0.9441183 0.3075987 0.2210055 0.665434 0.7129895 0.0965442 0.2897218 0.9522292 0.09960234 0.2826265 0.9540449 0.2210105 0.6644995 0.713859 0.1546814 0.6829699 0.7138808 0.1540064 0.6823884 0.7145825 0.08705925 0.6941094 0.7145858 0.08652192 0.6935458 0.715198 0.03843939 0.697512 0.7155414 0.03804463 0.6973155 0.7157539 -0.01097309 0.698632 0.715397 -0.01126915 0.6982141 0.7158003 -0.07999068 0.6936953 0.7158132 -0.08016782 0.6933859 0.716093 -0.147477 0.682246 0.7160943 -0.1475401 0.6821055 0.7162151 -0.1944369 0.6698784 0.7165593 -0.1944512 0.6698638 0.7165692 -0.2412484 0.6548625 0.7162082 -0.2412219 0.6549553 0.7161324 -0.3050677 0.6277531 0.7161422 -0.3050183 0.6280185 0.7159305 -0.3652774 0.594993 0.7159301 -0.3652384 0.5954461 0.7155731 -0.4058172 0.5681327 0.7159174 -0.405658 0.5684776 0.7157339 -0.445178 0.5385735 0.7153707 -0.4452177 0.5392676 0.7148228 -0.496575 0.4923658 0.7148351 -0.4966759 0.4930239 0.7143112 -0.5427548 0.4417878 0.7143114 -0.5428882 0.4423109 0.7138862 -0.5718209 0.4035912 0.7142373 -0.571802 0.4037603 0.714157 -0.5877353 0.3802036 0.7141516 -0.2587989 0.1586354 0.9528158 0.2216157 0.6652162 0.7130034 0.3003063 0.9045112 0.3027799 0.3003061 0.9045162 0.3027651 0.3010804 0.9036287 0.3046404 0.301092 0.9036219 0.304649 0.2095756 0.9291174 0.304662 0.2103235 0.9284138 0.3062869 0.2103326 0.9284095 0.3062939 0.05911773 0.2878953 0.9558355 0.02557462 0.8312156 0.5553616 0.07771015 0.129275 0.9885591 0.04895561 0.2562017 0.9653829 0.1316633 0.2599391 0.9566067 0.01704055 0.5554894 0.831349 0.01891928 0.8312978 0.5555053 0.01314091 0.555553 0.8313773 0.2087438 0.9494518 0.2344511 0.1999074 0.9541192 0.2229205 0.2090935 0.9531593 0.2185573 0.09817808 0.9708687 0.2185753 0.107617 0.9733311 0.2025958 0.0213679 0.9789789 0.2028394 0.03082329 0.9803218 0.194985 0.05525451 0.1812588 0.981882 0.039662 0.1854625 0.9818506 0.04133462 0.1874951 0.9813955 0.02007037 0.1908788 0.9814084 0.0215488 0.1930955 0.9809433 0.005029439 0.1939634 0.9809958 0.006308674 0.1950823 0.9807666 0.30804 0.9220669 0.2343163 0.2658866 0.9154645 0.3020416 0.2658854 0.9154595 0.3020579 0.02331429 0.828036 0.56019 0.09056395 0.8237589 0.55966 0.08343088 0.8178529 0.569347 0.1756927 0.8031299 0.5693105 0.1681004 0.7979252 0.5788416 0.2765904 0.7676223 0.5781469 0.1790876 0.6798264 0.7111706 0.01435959 0.5526503 0.8332895 0.0604009 0.5500373 0.832953 0.05603301 0.5445851 0.8368317 0.1169566 0.5348757 0.836797 0.1120852 0.5298832 0.8406312 0.1319381 0.5247491 0.8409702 0.2797256 0.6427738 0.7131589 -0.4640079 -0.00440669 -0.8858202 0.3866191 0.002398192 -0.9222364 -0.3685615 -0.3400657 -0.8651692 -0.3545497 -0.3110483 -0.8817842 -0.3563588 -0.2959309 -0.8862467 -0.3757943 -0.3082823 -0.8739226 -0.4654391 -0.1045187 -0.8788869 -0.4264717 -0.1180438 -0.8967651 -0.4204342 -0.04674017 -0.9061183 -0.4086641 -0.1495304 -0.9003524 -0.398216 -0.1942874 -0.89648 -0.3948661 -0.2320181 -0.8889592 -0.4320048 -0.2107146 -0.87691 -0.3893199 -0.2425206 -0.8886021 -0.4640161 -0.00440669 -0.8858158 -0.4476528 -0.01486718 -0.8940839 -0.420434 -0.0467543 -0.9061177 -0.7837499 -0.05794537 -0.6183677 -0.7864915 -0.07716792 -0.6127613 -0.750968 -0.01715719 -0.6601157 -0.7551242 -9.18112e-4 -0.6555812 -0.7738323 -0.02953577 -0.6327015 -0.7807799 -0.04352027 -0.6232886 -0.8449747 -0.1301739 -0.5187218 -0.8109795 -0.1665289 -0.5608746 -0.7971777 -0.1348339 -0.5884958 -0.7837679 -0.1179771 -0.6097452 -0.7840788 -0.1155711 -0.6098062 -0.7840721 -0.1156451 -0.609801 -0.8741026 -0.1636949 -0.4573277 -0.8587658 -0.1428548 -0.4920506 -0.8449676 -0.130174 -0.5187337 -0.8428739 -0.2810947 -0.4588565 -0.849689 -0.2149395 -0.481487 -0.8546571 -0.231779 -0.4645854 -0.8716965 -0.1340374 -0.4713588 -0.8701456 -0.1464894 -0.4705184 -0.8963849 -0.137155 -0.4215241 -0.8964133 -0.1371432 -0.4214677 -0.8259503 -0.3186015 -0.4650798 -0.8259571 -0.3185781 -0.4650836 -0.8193551 -0.3425339 -0.4597041 -0.8193516 -0.3425533 -0.4596958 -0.8189619 -0.3401803 -0.4621456 -0.8428772 -0.2810839 -0.4588572 -0.8428727 -0.2811008 -0.4588548 -0.7952177 -0.3230044 -0.5131248 0.009469211 -0.0707733 -0.9974474 -0.7742729 -0.4105432 -0.481618 -0.2341948 -0.6821304 -0.6927127 -0.7718185 -0.4448649 -0.4543034 -0.7952104 -0.3229833 -0.5131494 0.7498662 -0.3677459 -0.5499669 0.786832 -0.4566456 -0.415175 0.7913933 -0.477795 -0.3813245 0.8450201 -0.3402996 -0.4124768 0.8387579 -0.4026742 -0.3665223 0.8387634 -0.4026541 -0.3665319 0.8712785 -0.2958793 -0.391573 0.8712803 -0.2958704 -0.3915756 0.8712788 -0.2958755 -0.3915749 0.8778421 -0.1314387 -0.4605619 0.8778442 -0.1314387 -0.4605578 0.8796074 -0.2169452 -0.4233505 0.8823612 -0.2318514 -0.409492 0.9008007 -0.1531029 -0.4063468 0.9005326 -0.1549919 -0.4062248 0.9005408 -0.1549766 -0.4062122 0.9242536 -0.1061499 -0.3667253 0.9026581 -0.1534076 -0.4020876 0.9026859 -0.153384 -0.4020342 0.7741504 -0.01730173 -0.6327653 0.7593965 -0.02581954 -0.6501156 0.7740322 -0.02586507 -0.6326177 0.7864699 -0.03180962 -0.616809 0.8044868 -0.03698241 -0.5928182 0.816255 -0.05110377 -0.5754269 0.8181661 -0.07156044 -0.5705116 0.8157163 -0.1141192 -0.5670835 0.8153411 -0.1180295 -0.5668227 0.8142472 -0.117388 -0.5685259 0.8290756 -0.1344541 -0.5427299 0.2713574 -0.004389405 -0.9624686 0.2006813 -0.04420822 -0.9786586 0.1924776 -0.185017 -0.9637018 0.2763413 -0.1179701 -0.9537917 0.2635121 -0.1135469 -0.9579502 0.2006813 -0.04420989 -0.9786585 0.2591587 -0.2320933 -0.9375338 0.3140835 -0.2425653 -0.9178854 0.1924783 -0.1849994 -0.9637049 0.155645 -0.4435563 -0.8826281 0.1451595 -0.4737972 -0.8685879 0.1662112 -0.4271185 -0.8887877 0.1799468 -0.3994052 -0.8989409 0.1930908 -0.3831291 -0.9032874 0.2060351 -0.369761 -0.9059947 0.2231504 -0.3600345 -0.9058582 0.2453407 -0.3493944 -0.9042851 0.2783076 -0.3399948 -0.8983031 0.2686401 -0.3342575 -0.9033851 0.229979 -0.3082603 -0.9230847 0.2232517 -0.2942873 -0.9292759 0.220247 -0.2829485 -0.9335049 0.2202492 -0.2829172 -0.9335138 0.03212875 -0.3824746 -0.9234073 0.03212833 -0.382476 -0.9234067 0.1118326 -0.383229 -0.9168583 -0.09682631 -0.3824707 -0.9188802 -0.09682816 -0.3824757 -0.918878 0.03213 -0.3824773 -0.9234061 -0.2238948 -0.3824716 -0.8964299 -0.223895 -0.3824747 -0.8964285 -0.2912399 -0.3832659 -0.8765195 0.6913583 -0.01049053 -0.7224359 0.5982182 -6.53474e-4 -0.801333 0.5982183 -6.53474e-4 -0.801333 0.4961115 0.003638207 -0.8682512 0.4961201 0.003638207 -0.8682463 0.2699329 -0.1024574 -0.9574126 -0.5678804 0.003397881 -0.823104 -0.7461249 -0.1145933 -0.6558705 -0.6644802 0.003793537 -0.7472963 -0.6644832 0.003793537 -0.7472935 0.7654835 -0.05172109 -0.6413735 0.7611753 -0.1177687 -0.6377638 0.7611751 -0.117769 -0.637764 0.7456644 -0.2316239 -0.624768 0.7456634 -0.231625 -0.6247687 0.7209175 -0.3397352 -0.6040349 0.7209199 -0.3397325 -0.6040334 0.5581322 -0.07131487 -0.8266817 0.555663 -0.1177679 -0.8230245 0.5556644 -0.1177662 -0.8230238 0.544341 -0.2316259 -0.8062521 0.5443395 -0.2316274 -0.8062525 0.5262755 -0.3397334 -0.7794969 0.5262777 -0.3397311 -0.7794963 0.3091642 -0.004350125 -0.9509988 0.3070157 -0.1177672 -0.9443899 0.3070148 -0.1177682 -0.9443901 0.3007584 -0.2316272 -0.925145 0.3007583 -0.2316272 -0.925145 0.2907778 -0.3397315 -0.8944444 0.2907775 -0.3397318 -0.8944444 -0.4993709 -0.07003074 -0.8635534 -0.4971165 -0.1177658 -0.8596549 -0.4971178 -0.1177677 -0.8596538 -0.4869872 -0.2316277 -0.8421353 -0.4869872 -0.2316275 -0.8421356 -0.4708265 -0.3397325 -0.8141893 -0.4708254 -0.3397308 -0.8141908 -0.7200176 -8.80064e-4 -0.6939552 -0.7150076 -0.1177665 -0.6891264 -0.7150083 -0.117768 -0.6891254 -0.7004374 -0.2316286 -0.675082 -0.700436 -0.2316257 -0.6750844 -0.6771919 -0.3397322 -0.6526815 -0.677192 -0.3397326 -0.6526812 0.826951 -0.4310837 -0.3609969 0.8068943 -0.4447079 -0.3887882 0.7602418 -0.4441043 -0.4741349 0.760241 -0.4441027 -0.4741375 0.7980379 -0.3397355 -0.4977102 0.7980384 -0.3397347 -0.4977097 0.8254317 -0.2316236 -0.5147941 0.8254298 -0.2316266 -0.514796 0.8386295 -0.1521254 -0.5230283 0.8491564 -0.1418593 -0.5087332 0.7602385 -0.444104 -0.4741404 0.6867752 -0.4441041 -0.5754229 0.6867746 -0.4441031 -0.5754243 0.6867721 -0.4441041 -0.5754265 0.5999104 -0.4441042 -0.6654915 0.5999113 -0.4441053 -0.66549 0.6297383 -0.3397337 -0.6985777 0.6297395 -0.3397325 -0.6985771 0.651355 -0.2316256 -0.7225554 0.6513553 -0.2316251 -0.7225553 0.6649046 -0.1177681 -0.7375856 0.6649041 -0.1177688 -0.737586 0.6681785 -0.06428736 -0.7412183 0.6913723 -0.01049053 -0.7224226 0.5999151 -0.4441041 -0.6654873 0.5013502 -0.4441045 -0.7425761 0.5013507 -0.4441051 -0.7425755 0.5013523 -0.4441047 -0.7425745 0.3930098 -0.444105 -0.8051795 0.39301 -0.4441052 -0.8051793 0.4125506 -0.339731 -0.8452129 0.4125502 -0.3397313 -0.8452129 0.4267104 -0.2316274 -0.8742237 0.4267106 -0.2316272 -0.8742237 0.4355871 -0.1177676 -0.8924095 0.4355883 -0.1177663 -0.8924092 0.4386392 0.002415955 -0.8986599 0.3828799 -0.1387681 -0.9133161 0.03115546 -0.4441061 -0.8954324 0.0311554 -0.4441061 -0.8954323 0.155597 -0.4441063 -0.88236 0.1555977 -0.4441058 -0.8823602 0.2770059 -0.4441057 -0.8520785 0.2770047 -0.4441059 -0.8520789 0.2770054 -0.4441066 -0.8520781 0.3929966 -0.4441074 -0.8051847 -0.09389078 -0.4441065 -0.8910409 -0.09389418 -0.4441062 -0.8910407 -0.09682744 -0.3824788 -0.9188767 -0.2238985 -0.3824781 -0.8964263 -0.2171133 -0.4441069 -0.8692703 -0.2171121 -0.4441058 -0.8692712 -0.2171094 -0.4441061 -0.8692717 -0.09389364 -0.4441057 -0.8910411 -0.3360996 -0.4441069 -0.8305457 -0.3360973 -0.4441072 -0.8305464 -0.3421174 -0.4101413 -0.8454228 -0.3606553 -0.3565117 -0.8618742 -0.3360951 -0.444105 -0.8305485 -0.4485284 -0.444105 -0.7756243 -0.4485244 -0.444106 -0.775626 -0.4485244 -0.4441061 -0.775626 -0.5522034 -0.4441062 -0.7055786 -0.5522083 -0.4441046 -0.7055758 -0.5796636 -0.339732 -0.7406565 -0.5796629 -0.3397307 -0.7406579 -0.5995587 -0.2316284 -0.7660794 -0.5995583 -0.2316277 -0.76608 -0.6120306 -0.1177666 -0.7820164 -0.6120312 -0.1177675 -0.7820158 -0.6146776 -0.07295691 -0.7853972 -0.5678806 0.003397941 -0.8231039 -0.5522079 -0.4441043 -0.7055763 -0.6451187 -0.4441039 -0.6217665 -0.6451174 -0.4441044 -0.6217675 -0.6451181 -0.4441055 -0.621766 -0.7254473 -0.4441055 -0.5258294 -0.8021209 -0.1362614 -0.5814077 -0.7876538 -0.2316256 -0.5709214 -0.7876552 -0.23163 -0.5709174 -0.7615174 -0.3397327 -0.5519719 -0.7615169 -0.3397309 -0.5519736 -0.7254474 -0.4441053 -0.5258293 -0.7254487 -0.4441074 -0.5258259 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.006944119 -0.9997557 -0.02098464 0.006931126 -0.9997564 -0.02095478 -0.01268154 -0.9998581 0.01109498 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.01268762 -0.9998579 0.01110261 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.7510743 0 -0.6602177 -0.4640197 -0.002020537 -0.8858226 -0.4624047 -0.08323049 -0.882754 -0.4640077 0.00540167 -0.8858147 -0.4640147 0 -0.8858276 -0.5678838 0 -0.8231087 -0.5678838 0 -0.8231087 -0.6644867 0 -0.7473001 -0.5678839 0 -0.8231087 -0.5678815 0.002885997 -0.8231053 -0.5678837 0 -0.8231088 -0.4640125 0 -0.8858287 -0.664488 0 -0.7472989 -0.6637346 -0.0475651 -0.7464543 -0.6644867 0 -0.7473001 -0.7510743 0 -0.6602177 -0.7510786 0 -0.6602129 -0.7480865 0.08911049 -0.6575911 -0.7510725 0 -0.6602197 -0.6644849 0 -0.7473016 -0.2290135 0 0.9734233 0 0 1 -0.6301257 -0.002945899 0.7764875 -0.6301078 -0.002945899 0.776502 -0.4338669 0.008854627 0.9009334 -0.4905204 0.02027767 0.8711937 -0.3382915 7.78608e-4 0.941041 -0.7512838 0.007079482 0.6599413 -0.7817638 0.01286953 0.6234419 -0.8514296 -2.42685e-4 0.524469 -0.9926559 0.02402025 0.1185636 -0.9606122 0.006662547 0.2778124 -0.9268419 1.40828e-4 0.3754519 -0.8517942 -2.42685e-4 0.5238766 -0.9749287 0 0.2225176 -0.9749287 0 -0.2225176 -0.9749287 0 -0.2225176 -0.7818282 0 -0.6234941 -0.7818282 0 -0.6234941 -0.4338848 0 -0.9009684 -0.4338848 0 -0.9009684 -0.006954669 0 -0.9999759 0 0.001538157 -0.9999988 0.3059267 -6.65549e-4 -0.9520549 0.305884 -6.6555e-4 -0.9520687 0.4338514 0.0124517 -0.9008985 0.457768 0.008900225 -0.8890271 0.8274425 0.002509534 -0.5615448 0.7253639 0.02307736 -0.6879788 0.7818117 0.00725919 -0.6234723 0.6009613 -0.002665579 -0.7992737 0.6009652 -0.002665579 -0.7992708 0.9946933 0.001680254 -0.1028712 0.9638045 0.01486408 -0.2661954 0.9637959 0.01486694 -0.2662262 0.9749057 0.006589949 -0.2225203 0.9077072 -7.05192e-4 -0.4196034 0.9076799 -7.05192e-4 -0.4196626 0.972894 0.01219284 0.2309297 0.9748685 0.01094299 0.2225118 0.9728962 0.01219195 0.2309205 0.9979616 -0.001742899 0.06379354 0.9979649 -0.001742899 0.06374359 0.8426255 0.002713203 0.5384932 0.9193356 -0.002298295 0.3934679 0.9193264 -0.002298295 0.393489 -0.006954669 0.001586556 0.9999746 0.3038815 -6.50303e-4 0.9527097 0.433884 -6.44075e-4 0.9009684 0.3045917 0.03096681 0.9519795 0.4916505 0.003541827 0.8707854 0.6242425 -7.31947e-4 0.7812303 0.7818325 -7.13849e-4 0.6234881 0.6276407 0.04786473 0.7770304 0.7431098 0.01715558 0.6689496 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.2828963 0.06623989 -0.9568604 0.1966711 5.33169e-4 0.9804695 0.2580841 0.03510975 0.9654842 0.3117084 0.07842725 0.9469356 -0.2483506 0.003162205 0.968665 -0.1099656 0.03324419 0.9933793 -0.1099659 0.03324407 0.9933792 -0.1404525 0.01787614 0.989926 0.06122571 -1.86165e-4 0.998124 0.06129562 -1.86165e-4 0.9981197 -0.642009 0.006980657 0.7666653 -0.5538804 0.01999396 0.832356 -0.5748413 0.01326721 0.8181574 -0.3955456 -0.001427531 0.9184454 -0.3955457 -0.001427531 0.9184452 -0.9366757 0.002516448 0.3501892 -0.8814378 0.01368671 0.4721018 -0.8197993 0.03602987 0.5715165 -0.8838123 0.006877601 0.4677911 -0.725371 -0.002179324 0.6883548 -0.7253848 -0.002179324 0.6883401 -0.9975025 0.007862508 0.07019335 -0.9761799 -0.002090096 0.2169527 -0.9761853 -0.002090096 0.2169281 -0.8938278 0.01616811 -0.4481188 -0.8976107 0.01484596 -0.4405392 -0.9413706 0.001697957 -0.3373699 -0.9777524 -3.69972e-4 -0.2097621 -0.9998833 -3.60517e-4 0.01527053 -0.9782543 0.05330502 -0.2004421 -0.9967701 0.02569329 -0.0760864 -0.6957921 0.002988398 -0.7182371 -0.748825 1.12639e-5 -0.6627678 -0.8245546 -3.51273e-5 -0.5657823 -0.8267018 -3.51241e-5 -0.5626403 -0.2446054 0.006659984 -0.9695999 0.1909479 0.006551861 -0.9815783 0.08462899 -9.71268e-6 -0.9964125 -0.170646 -9.60499e-6 -0.9853323 -0.03960365 0.08333033 -0.9957347 -0.09909594 0.04587793 -0.9940198 -0.2446659 0.006643772 -0.9695847 -0.4166614 -0.002888917 -0.9090571 -0.5996072 -0.002822637 -0.8002894 -0.4659489 0.05273795 -0.8832386 -0.5933422 0.01623338 -0.8047866 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.685328 -0.0065099 0.7282054 -0.6825635 -0.0065099 0.7307973 -0.6851114 -0.006231844 0.7284116 -0.8821026 0.01102477 0.4709283 -0.9855989 0 0.1691001 -0.9855988 0 0.1691001 -0.9511128 -0.02293598 0.307991 -0.9865407 0.001149117 0.1635122 -0.9085708 -6.37323e-4 0.4177303 -0.8813381 -0.002561748 0.4724794 -0.9094782 -0.002549946 0.4157438 -0.8145472 -0.01546531 0.5798912 -0.8250466 -0.0118041 0.5649415 -0.8145776 -0.01546281 0.5798485 -0.8148515 -0.01542097 0.5794646 -0.004076361 0 0.9999917 -0.1322047 7.89829e-4 0.9912221 -0.6852577 -0.006510853 0.7282717 -0.7252863 -0.002512395 0.6884428 -0.5602998 -0.01767981 0.8281012 -0.6850814 0.01115047 0.7283811 -0.2513673 -0.01582241 0.9677624 -0.4117995 0.006164789 0.9112537 -0.25138 0.006523668 0.9678665 -0.435799 0.05928534 0.8980894 -0.4226649 0.05543541 0.9045891 -0.8134086 -0.5595006 0.1591396 -0.7346142 -0.495226 0.4637814 -0.5714414 -0.4753859 0.6689268 -0.5285854 -0.4763604 0.7026222 -0.734626 -0.4952226 0.4637664 -0.5136871 -0.3435398 0.7861971 -0.3354047 -0.3093702 0.8898279 -0.3165118 -0.3093176 0.8967402 -0.003338813 -0.002471148 0.9999914 -0.7999427 -0.5676726 0.1945243 -0.6911054 -0.6961604 0.1942527 -0.6911119 -0.6961557 0.1942468 -0.6911086 -0.6961613 0.1942381 -0.5482009 -0.8134786 0.1942382 -0.3858264 -0.9018899 0.194249 -0.3858219 -0.9018946 0.1942363 -0.5481698 -0.8134999 0.1942362 -0.5482105 -0.8134637 0.1942731 -0.327473 -0.7654985 0.5538713 -0.327468 -0.7655144 0.5538523 -0.4653021 -0.6904645 0.5538526 -0.4653031 -0.6904559 0.5538625 -0.5865988 -0.5908798 0.5538619 -0.5865989 -0.5908818 0.5538597 -0.691922 -0.4635791 0.5534784 -0.5747879 -0.3808951 0.7242498 -0.2191808 -0.5123741 0.8303208 -0.2191814 -0.5123702 0.8303231 -0.3114371 -0.4621366 0.8303233 -0.3114368 -0.4621311 0.8303265 -0.3926193 -0.3954859 0.8303258 -0.3926198 -0.3954877 0.8303248 -0.4666848 -0.3060371 0.8297871 -0.3479867 -0.220575 0.9111816 -0.07706105 -0.1801421 0.9806174 -0.07706183 -0.1801351 0.9806186 -0.1094947 -0.1624757 0.9806185 -0.1094952 -0.1624824 0.9806173 -0.1380401 -0.1390485 0.9806174 -0.1380391 -0.1390448 0.980618 -0.1365821 -0.14078 0.9805746 -0.1076651 -0.08289188 0.9907256 0.6215777 -0.5295739 0.5772284 -0.03889703 -0.1258338 0.9912885 -0.03968447 -0.1259568 0.9912417 -0.03187483 -0.1283516 0.9912164 -0.03277176 -0.1289781 0.9911057 -0.03260004 -0.131191 0.990821 -0.01922965 -0.1338616 0.9908134 -0.02005869 -0.1345049 0.9907099 -0.1429819 -0.9686094 0.2033521 -0.239884 -0.9492619 0.2033653 -0.2397629 -0.9492052 0.2037725 -0.2929334 -0.934111 0.2040265 -0.2928673 -0.9341249 0.2040576 -0.01965761 -0.1368963 0.9903904 -0.0103442 -0.1377978 0.9904063 -0.01113647 -0.1384395 0.9903083 -0.01043176 -0.1388436 0.9902594 -0.001187026 -0.1394108 0.9902339 -0.001726627 -0.1400406 0.9901442 -0.001211106 -0.1416152 0.9899211 0.01278293 -0.1410691 0.9899172 0.01260113 -0.1413114 0.9898849 0.08737272 -0.9753924 0.2024242 -0.01108324 -0.9792344 0.2024279 -0.01099067 -0.9791607 0.2027897 -0.07719212 -0.9761281 0.2030156 -0.07710653 -0.9761258 0.2030594 -0.07718539 -0.9761055 0.203127 -0.143104 -0.9686825 0.2029173 0.01285356 -0.1418959 0.9897981 0.02711206 -0.1398915 0.9897956 0.02695351 -0.140126 0.9897667 0.1853376 -0.9616213 0.2023226 0.1852782 -0.9616227 0.2023706 0.08736181 -0.9754032 0.2023774 0.02727037 -0.1407128 0.9896749 0.03671354 -0.1383935 0.9896966 0.03658193 -0.1385914 0.9896737 0.03681468 -0.1386471 0.9896572 0.04605388 -0.13603 0.9896337 0.04600846 -0.1361369 0.9896212 0.1853789 -0.9616438 0.2021779 0.2503008 -0.9467762 0.2023966 0.2502906 -0.9467821 0.2023811 0.3136798 -0.9277585 0.2021615 0.04612183 -0.1362875 0.9895952 0.05929493 -0.1310818 0.9895967 0.05946981 -0.130589 0.9896513 0.4052778 -0.891558 0.2021738 0.4053486 -0.8915383 0.2021188 0.313672 -0.9277709 0.2021166 0.05869281 -0.1297321 0.9898104 0.07139742 -0.1231668 0.9898143 0.07158195 -0.1225678 0.9898753 0.07046902 -0.1215384 0.990082 0.07882571 -0.1160851 0.9901065 0.07814294 -0.1158214 0.9901915 0.4052338 -0.8915464 0.2023131 0.4931101 -0.8461136 0.2023223 0.493143 -0.8460246 0.2026137 0.5494552 -0.8105275 0.20284 0.5494815 -0.8104965 0.2028931 0.6030073 -0.7715588 0.2026802 0.07820045 -0.1158187 0.9901872 0.08587753 -0.1104148 0.9901686 0.08593589 -0.1097769 0.9902343 0.08475214 -0.1089773 0.9904247 0.09515881 -0.09996628 0.99043 0.09518086 -0.09912252 0.9905127 0.5655748 -0.590605 0.575596 0.5035753 -0.6442935 0.5755848 0.5036952 -0.6447466 0.5749722 0.4589942 -0.6769372 0.5753957 0.4589076 -0.6772195 0.5751328 0.412146 -0.7070128 0.57469 0.4122045 -0.7074751 0.5740787 0.3388786 -0.7453798 0.5740821 0.3388878 -0.7457912 0.5735422 0.2623647 -0.776027 0.5735389 0.2623704 -0.7759549 0.5736339 0.2092376 -0.7916243 0.5740652 0.2093135 -0.7915211 0.5741795 0.154994 -0.8042361 0.573743 0.1550394 -0.8040236 0.5740285 0.07301515 -0.8155642 0.5740418 0.07308769 -0.8153411 0.5743493 -0.009292602 -0.8185538 0.5743548 -0.009070396 -0.8180493 0.5750768 -0.06454396 -0.8152399 0.5755155 -0.06416606 -0.8149821 0.5759226 -0.1195698 -0.8090149 0.575498 -0.1191451 -0.8083203 0.5765612 -0.2002239 -0.7921285 0.5765785 -0.1997542 -0.7915114 0.5775882 -0.24424 -0.7785677 0.5780823 -0.2437218 -0.7785853 0.5782773 0.3952696 -0.337157 0.8544514 0.3594974 -0.3750686 0.8544502 0.3602577 -0.3765047 0.8534979 0.3209488 -0.4105454 0.8534895 0.3213961 -0.411644 0.8527918 0.2928674 -0.4319069 0.8530446 0.2928275 -0.4323297 0.8528441 0.2632446 -0.451456 0.8525783 0.2635537 -0.4526503 0.8518492 0.2168195 -0.4768082 0.8518469 0.2169612 -0.477743 0.851287 0.1680443 -0.497071 0.8512823 0.1680357 -0.4968991 0.8513844 0.1339156 -0.5067194 0.8516467 0.1340134 -0.5065063 0.8517581 0.09920859 -0.5148961 0.8514925 0.09925156 -0.5143792 0.8518 0.04669153 -0.5217711 0.8518068 0.04679059 -0.5212447 0.8521235 -0.006013572 -0.5233035 0.8521253 -0.005612254 -0.5219406 0.8529634 -0.04122 -0.5199024 0.8532307 -0.04064822 -0.5193099 0.8536187 -0.07630634 -0.5157072 0.8533601 -0.07547539 -0.51385 0.8545536 -0.1273452 -0.5034915 0.854564 -0.1264044 -0.5018573 0.8556641 -0.1547398 -0.4933414 0.8559614 -0.1542149 -0.4932934 0.8560838 0.09344822 -0.09817516 0.990772 0.1028902 -0.08816963 0.9907773 0.1028747 -0.08749103 0.9908391 0.1013254 -0.08681708 0.991058 0.1061305 -0.08056592 0.991083 0.6512292 -0.4919914 0.5777932 0.6511813 -0.4921483 0.5777135 0.4130433 -0.3120071 0.8555974 0.8141989 -0.5437123 0.2036105 0.7810764 -0.5902253 0.2038475 0.7810946 -0.5901934 0.2038698 0.745221 -0.6349686 0.203619 0.7451956 -0.6350455 0.2034715 0.7452734 -0.635006 0.2033103 0.6773855 -0.7069785 0.2032986 0.1106876 -0.07403695 0.9910938 0.6030015 -0.7715621 0.2026847 0.6029153 -0.7715602 0.2029477 0.6773719 -0.7070894 0.2029581 0.5653365 -0.5899704 0.5764803 0.6218338 -0.5300866 0.5764815 0.3945538 -0.3360884 0.8552028 0.4129919 -0.3123635 0.8554921 0.1061607 -0.08012712 0.9911153 0.1106973 -0.07401853 0.991094 0.814158 -0.5437247 0.2037403 0.6790337 -0.4534507 0.5773177 0.6788772 -0.4534214 0.5775247 0.4308811 -0.2877177 0.8553128 0.4305311 -0.2876044 0.8555272 0.1105605 -0.07378822 0.9911265 0.1101858 -0.07371771 0.9911735 0.8043219 -0.1361724 0.5783801 0.1164094 -0.06330037 0.9911821 0.115671 -0.06257545 0.9913146 0.1190226 -0.0557174 0.9913271 0.1190065 -0.05555826 0.9913378 0.1188696 -0.05562388 0.9913506 0.1225212 -0.04743498 0.9913317 0.8608524 -0.4662502 0.2038232 0.860818 -0.4662722 0.2039183 0.8608313 -0.4662371 0.2039415 0.8869273 -0.4143778 0.2040858 0.8869276 -0.414376 0.2040882 0.9129381 -0.3535245 0.2038736 0.9129335 -0.3535103 0.2039189 0.943831 -0.2599964 0.203924 0.1223667 -0.04741406 0.9913519 0.1223518 -0.04741752 0.9913535 0.1265127 -0.03482532 0.9913535 0.1260293 -0.03480887 0.9914157 0.7867166 -0.2167612 0.5780065 0.760972 -0.2946703 0.578006 0.7609989 -0.2946966 0.5779573 0.7390865 -0.3452813 0.5783874 0.7391054 -0.3453585 0.5783172 0.7175405 -0.3886035 0.5780338 0.7177001 -0.3888365 0.5776788 0.5093346 -0.08632981 0.8562275 0.4980493 -0.1371779 0.8562296 0.4983462 -0.1373581 0.856028 0.4820554 -0.1866589 0.8560264 0.4821401 -0.1867228 0.8559646 0.4680554 -0.2186592 0.8562198 0.4680997 -0.2187526 0.8561717 0.454598 -0.2461686 0.8560034 0.4550485 -0.2466556 0.8556237 0.1260277 -0.03480935 0.9914158 0.1288819 -0.02195233 0.9914169 0.1286504 -0.021739 0.9914517 0.128196 -0.02182948 0.9915085 0.1290979 -0.01418 0.9915305 0.8105481 -0.08876574 0.5789062 0.8105684 -0.08884805 0.5788652 0.5126286 -0.05618304 0.8567703 0.9438071 -0.2600361 0.2039838 0.9652321 -0.1634525 0.2039856 0.9652097 -0.1634134 0.204123 0.9730761 -0.1065647 0.2043693 0.9730769 -0.1066108 0.2043413 0.9776862 -0.04973042 0.2040994 0.9438101 -0.2600141 0.203998 0.7866226 -0.2166863 0.5781625 0.8044672 -0.1362653 0.5781559 0.5089468 -0.08614605 0.8564766 0.5126381 -0.05620586 0.8567631 0.1290781 -0.01414096 0.9915336 0.1298556 -0.006457865 0.9915118 0.9777069 -0.04970759 0.204006 0.8146779 -0.04145419 0.57843 0.8148941 -0.0413745 0.5781313 0.5154982 -0.02624541 0.8564887 0.5159971 -0.02613085 0.8561917 0.1299917 -0.006656169 0.9914928 0.130647 -0.006496965 0.9914077 -0.04639786 -0.1269097 0.9908286 -0.04259175 -0.1246504 0.9912861 -0.1720616 -0.4896637 0.8547656 -0.1693958 -0.4883936 0.8560239 -0.2693387 -0.7710859 0.5769602 -0.267811 -0.7707109 0.5781712 -0.3219997 -0.9245961 0.2035641 -0.3215848 -0.924643 0.204006 -0.06211984 -0.1336106 0.9890851 -0.04804474 -0.1262916 0.990829 -0.2027988 -0.4858254 0.8502037 -0.193023 -0.4818026 0.8547563 -0.3109495 -0.758523 0.5726721 -0.3055617 -0.7574924 0.5769205 -0.3687338 -0.9073442 0.2018955 -0.3672487 -0.9075878 0.2035013 0.9858041 -0.002077043 0.1678869 0.4933164 0.8637381 0.1029343 0.5229288 -0.8016234 0.2897333 0.5228989 -0.8016234 0.2897872 0.2871547 0.936025 0.2034685 0.3088425 -0.8855852 0.3469227 0.308825 -0.8855851 0.3469383 0.1719228 0.9430641 0.2847326 0.19161 -0.863732 0.4661036 0.191582 -0.863732 0.4661151 0.05312591 0.9149439 0.4000688 0.07326793 0 0.9973123 -0.4037386 -0.8923305 0.2018448 -0.3356822 -0.7479028 0.5726772 -0.08240681 -0.1429682 0.9862906 -0.05370092 -0.1372546 0.9890791 -0.2325265 -0.4839479 0.8436385 -0.4070194 -0.8913589 0.199536 -0.430736 -0.8801643 0.1994422 -0.4367789 -0.8781625 0.1950767 -0.360925 -0.7491562 0.5554261 -0.3627888 -0.7399035 0.5665043 -0.347059 -0.7473461 0.5665897 -0.212484 -0.4816504 0.8502137 -0.1089627 -0.1633988 0.9805243 -0.05703026 -0.1548796 0.9862859 -0.2620852 -0.4900699 0.83135 -0.2437483 -0.4786136 0.8435139 -0.2353329 -0.5034684 0.8313471 -0.3773378 -0.7408912 0.5556048 -0.2132888 -0.1486877 0.9656085 -0.4909852 -0.5112199 0.705399 -0.4562544 -0.6969248 0.5532879 -0.4562842 -0.6969715 0.5532047 -0.5122374 -0.8365316 0.1944934 -0.5201194 -0.814297 0.2576747 -0.5201199 -0.8142961 0.2576764 -0.6692981 -0.6968816 0.2576743 -0.6692968 -0.6969001 0.2576278 -0.6692966 -0.6969004 0.2576276 -0.7926481 -0.5525701 0.2576341 -0.3080429 -0.4654887 0.8297167 -0.3079847 -0.4653977 0.8297894 -0.7926509 -0.5525695 0.2576267 -0.7926303 -0.5525621 0.2577062 -0.5814664 -0.4053546 0.7053966 -0.5814539 -0.4053516 0.7054086 -0.5814885 -0.4053668 0.7053714 -0.1055023 -0.1651744 0.9806053 -0.1293455 -0.2273178 0.9651924 -0.1800915 -0.1875175 0.9656108 -0.3664752 -0.6079257 0.7043595 -0.4909901 -0.5112318 0.7053871 -0.1800897 -0.1875142 0.9656118 -0.2132784 -0.1486805 0.9656119 -0.2132426 -0.1486678 0.9656219 -0.8819227 -0.3946046 0.257875 -0.8819321 -0.3946095 0.2578355 -0.8656029 -0.4611834 0.1950429 -0.5679208 -0.4265289 0.7039454 -0.7706428 -0.3143852 0.5543206 -0.6632936 -0.255335 0.7034527 -0.4704711 -0.2989289 0.83024 -0.2585989 -0.06657487 0.963688 -0.2002424 -0.03564006 0.9790979 -0.2284716 -0.1217368 0.9659094 -0.1051158 -0.01879245 0.9942824 -0.09163254 -0.009292066 0.9957495 -0.1812555 -0.07382416 0.9806612 -0.2273902 -0.08626395 0.9699754 -0.5214827 -0.1978325 0.830011 -0.5214841 -0.1978335 0.8300098 -0.7787427 -0.2954288 0.5534271 -0.7787464 -0.2954319 0.5534203 -0.9172116 -0.3479612 0.1940252 -0.9172115 -0.3479607 0.1940274 -0.240347 -0.03685498 0.9699871 -0.1923003 -0.0328443 0.9807863 -0.1908738 -0.04106909 0.980755 -0.0554223 -0.0299825 0.9980127 -0.2641707 -0.02409696 0.9641748 -0.2641639 -0.02417606 0.9641748 -0.2930077 -0.01002937 0.9560576 -0.9727704 -0.1254456 0.1948881 -0.241834 -0.05249351 0.9688967 -0.5432841 -0.1179276 0.8312253 -0.5432839 -0.1179275 0.8312254 -0.8127648 -0.1764221 0.5552375 -0.812757 -0.1764185 0.5552501 -0.9585005 -0.2080538 0.1949111 -0.958504 -0.2080573 0.1948907 -0.1910831 -0.02464139 0.9812645 -0.5513688 -0.07110261 0.8312261 -0.5513695 -0.07110279 0.8312257 -0.8248537 -0.1063704 0.5552492 -0.8248564 -0.1063714 0.5552451 -0.9727699 -0.1254459 0.1948898 -0.9727681 -0.1254428 0.1949011 -0.2632914 -0.01126199 0.9646506 -0.5554255 -0.02375769 0.8312269 -0.5554162 -0.0237559 0.8312331 -0.8309266 -0.03553986 0.5552458 -0.8309457 -0.03554505 0.5552169 -0.9799279 -0.04191803 0.1948953 -0.9799264 -0.04191696 0.194903 -0.1488534 0 0.9888592 -0.1488534 0 0.9888592 -0.4333629 0 0.9012195 -0.4333629 0 0.9012195 -0.2565126 -0.02349996 0.9662551 -0.4713578 -0.001319348 0.8819411 -0.433348 -0.008279979 0.9011886 -0.2543011 -0.002065122 0.9671229 -0.1488364 -0.0151335 0.9887461 -0.490035 -0.001128077 0.8717021 -0.4714228 -0.004227697 0.8818972 -0.3006964 -0.003247797 0.9537144 -0.2562214 -0.009194254 0.9665744 0.004035174 0.9999912 -0.001106977 0.9996648 0 -0.02589035 -0.7040259 -0.02704143 -0.7096593 0.7608609 -0.2015256 -0.6168291 0.4619567 -0.2995463 -0.8347862 -0.4973226 -0.07609885 -0.8642218 0.02818787 -0.9988932 -0.03765642 -0.1365935 -0.9840145 -0.1142702 -0.16128 -0.9850001 -0.06134688 -0.5439187 -0.8324764 -0.1055247 -0.508506 -0.8318483 -0.2223738 -0.5103289 -0.8305538 -0.223035 -0.7026312 -0.6359803 -0.3191215 -0.7019857 -0.6367661 -0.318975 -0.7018967 -0.6368823 -0.3189391 -0.9149847 -0.1584958 -0.3710556 -0.8322933 -0.3671174 -0.4153465 -0.832294 -0.3671154 -0.4153468 0.1629676 -0.2260701 -0.9603822 0.162958 -0.2260701 -0.9603838 -0.8808048 -0.2361441 -0.4103887 -0.8625881 -0.2368992 -0.447013 -0.854164 -0.260167 -0.4502411 -0.8359194 -0.2568686 -0.4850332 -0.8313955 -0.2608264 -0.4906641 0.03504616 -0.9989936 -0.02799093 0.04585754 -0.9978089 -0.04769229 0.1160059 -0.9894702 -0.08655315 0.1099381 -0.9910526 -0.07568567 0.3173822 -0.9456642 -0.07062309 -0.8112586 -0.2560136 -0.5256581 -0.8092077 -0.274231 -0.5195962 -0.8045889 -0.2757806 -0.5259105 -0.7806639 -0.2636755 -0.5666031 -0.7708676 -0.2727695 -0.5756387 -0.7480665 -0.2564371 -0.6120756 -0.7342621 -0.2668083 -0.6242376 0.2834405 -0.9588758 -0.01478213 0.3219732 -0.9436184 -0.07692587 0.4649496 -0.8793361 -0.1029067 0.4669118 -0.877923 -0.1060402 0.6354739 -0.7631355 -0.117461 0.6285519 -0.7703406 -0.1072281 0.7199598 -0.6743031 -0.1642353 0.7108669 -0.6871041 -0.1501876 0.8268581 -0.5362683 -0.1694757 0.8134511 -0.5617059 -0.1509433 0.8718454 -0.4411002 -0.2128759 0.8621683 -0.4666146 -0.1973237 0.9174532 -0.328536 -0.2243739 -0.4379745 -0.8861095 -0.1516187 -0.4128825 -0.8877038 -0.2037398 -0.2488297 -0.9498801 -0.1892394 -0.2385507 -0.9485109 -0.2083764 -0.185177 -0.9530685 -0.2395201 -0.1785228 -0.9513024 -0.2513031 -0.01587796 -0.9676645 -0.2517406 0.007459044 -0.9567974 -0.2906599 0.1258023 -0.9403024 -0.3162358 0.1491547 -0.9234815 -0.3534612 0.2991383 -0.8780093 -0.3736522 0.3156645 -0.8609955 -0.3988015 0.3988096 -0.7977013 -0.4523533 0.4085935 -0.7840926 -0.4671726 0.5265884 -0.6862732 -0.5017307 0.5317922 -0.6766876 -0.5092061 0.5899001 -0.5705612 -0.5713824 0.5890896 -0.5726137 -0.570164 0.6670803 -0.4402844 -0.6009606 0.6800794 -0.3927472 -0.6190651 0.7143957 -0.2659397 -0.6472364 0.7218787 -0.2114125 -0.6589354 0.7618162 0.1970618 -0.6170923 -0.6443918 -0.7211946 -0.2542393 -0.6149676 -0.7227966 -0.3152459 -0.5158515 -0.7984217 -0.310516 -0.4984124 -0.7959249 -0.3436403 -0.4635602 -0.8063459 -0.3673124 -0.4487792 -0.802504 -0.3931725 -0.3436758 -0.8487598 -0.4018626 -0.3108246 -0.8330978 -0.4575327 -0.2305436 -0.844864 -0.4827573 -0.1959558 -0.8200014 -0.5377722 -0.08889317 -0.8203583 -0.5648984 -0.06011766 -0.7896547 -0.6105992 3.05844e-4 -0.7563632 -0.654152 0.02316451 -0.7251255 -0.688227 0.1146745 -0.67677 -0.7272084 0.1324238 -0.6421604 -0.7550457 0.1750148 -0.570716 -0.8022799 0.1848916 -0.5470578 -0.8164209 0.2503513 -0.4597152 -0.8520482 0.2697234 -0.3852404 -0.8825186 0.2978423 -0.2941927 -0.9081523 0.2936335 -0.3175703 -0.9016255 0.4279324 0.4679005 -0.7732678 -0.7981305 -0.4985533 -0.3382784 -0.7689694 -0.4999627 -0.398401 -0.7250069 -0.5599468 -0.4010294 -0.705101 -0.5567193 -0.4391995 -0.6875293 -0.5663248 -0.4545105 -0.6696254 -0.5618749 -0.4856938 -0.6196075 -0.6064541 -0.4982971 -0.587 -0.5903754 -0.5539746 -0.5462712 -0.6093884 -0.5746597 -0.5119942 -0.5848293 -0.6291556 -0.4560887 -0.6027201 -0.6547607 -0.427208 -0.5703143 -0.7015945 -0.3946769 -0.5582314 -0.7297999 -0.3682851 -0.5227296 -0.7688433 -0.317623 -0.5093961 -0.7997694 -0.2973804 -0.4664494 -0.8330606 -0.2751895 -0.431998 -0.8588647 -0.257387 -0.3908352 -0.8837419 -0.2206668 -0.3549488 -0.9084699 -0.2011553 -0.2706956 -0.9414141 -0.1872507 -0.2328744 -0.9543095 -0.1402304 0.02499651 -0.9898033 -0.1945666 -0.08016771 -0.9776077 0.8840765 -0.4397144 -0.158304 0.9294165 -0.3038833 -0.2093794 0.9558815 -0.1869889 -0.2265522 0.9618474 -0.1337715 -0.2386516 0.9746768 -0.03310173 -0.2211545 -0.7104459 -0.239595 -0.6617106 -0.7133318 -0.2497861 -0.6548011 -0.7074285 -0.2441104 -0.663291 -0.6910396 -0.222154 -0.6878313 -0.6776621 -0.2221957 -0.7010014 -0.6655784 -0.1958731 -0.7201662 -0.6597648 -0.1873244 -0.72775 -0.6482528 -0.1609415 -0.7442219 -0.6385398 -0.1541896 -0.7539845 -0.6283588 -0.1092116 -0.7702195 -0.6249586 -0.1012803 -0.7740601 -0.6177236 -0.05874037 -0.7841984 -0.4942418 0.1319859 -0.8592466 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.6348658 0 -0.7726224 0.5754966 -0.04187011 -0.8167317 0.5754945 -0.04188865 -0.8167321 0.6075253 -0.01170724 -0.7942141 0.6075645 -0.01167708 -0.7941846 0.8336455 -0.1770972 0.5231364 0.8336367 -0.1771243 0.5231415 0.8672536 -0.04316508 0.495992 0.8779698 1.31134e-4 0.4787161 0.9884217 -0.02876126 -0.1489807 0.9884128 -0.02876847 -0.1490387 0.9998906 -0.00962156 0.01123368 0.989743 -0.001589953 0.1428505 0.9897385 -0.001588642 0.1428817 0.9728772 1.35662e-4 0.2313216 0.7591499 -0.005693614 -0.650891 0.6348658 0 -0.7726224 0.7676944 0 -0.6408162 0.8084032 -0.00142318 -0.5886275 0.8084523 -0.001426398 -0.5885599 0.8591194 -0.005845248 -0.5117419 0.9180585 -0.01772856 -0.3960483 0.9181032 -0.01774019 -0.3959441 0.9564357 -0.03429722 -0.2899213 0.8859204 -0.001301825 -0.4638356 0.9707316 8.9809e-6 -0.2401669 0.9999644 8.67723e-6 0.008443593 0.9684258 -0.04612237 -0.2449985 0.9884444 -0.02873563 -0.1488351 0.8783531 0 0.4780123 0.548734 0 0.835997 0.548734 0 0.835997 0.08997583 0 0.9959439 0.08997583 0 0.9959439 -0.3900226 0 0.9208053 -0.3900226 0 0.9208053 -0.777964 0 0.6283088 -0.777964 0 0.6283088 -0.98226 0 0.187524 -0.98226 0 0.187524 -0.9547089 0 -0.2975414 -0.9547089 0 -0.2975414 -0.7017979 0 -0.7123761 -0.7017979 0 -0.7123761 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 7.74577e-4 0.9999964 -0.002619087 8.19436e-4 0.9999966 -0.002467215 0.001959502 -0.9999945 -0.002686798 0.7660735 0 -0.6427531 0.001959383 -0.9999945 -0.002686858 0.00279504 0.9999904 -0.00339812 0.7660735 0 -0.6427531 -0.9762294 -0.1189676 -0.1811709 -0.8262374 -0.2796806 -0.4889891 -0.619491 -0.2218399 -0.7530059 0.601405 -0.7898041 -0.1205051 0.6014689 -0.7897526 -0.1205242 0.5034595 -0.8638799 -0.0154941 0.8480877 -0.4326434 -0.3058872 0.8498723 -0.4362684 -0.2956129 0.850269 -0.4353626 -0.2958078 0.7235558 -0.6606671 -0.199965 0.7236713 -0.6605277 -0.2000074 0.8629181 -0.4538114 -0.222323 0.8887075 -0.2257848 -0.3990238 0.9146181 -0.2206208 -0.3388216 0.9170504 -0.1821157 -0.354757 0.3804962 -0.9244273 -0.02562904 0.3136771 -0.9493101 -0.02042335 0.297842 -0.9528672 -0.05774319 0.1444505 -0.9870206 -0.07017505 0.08704757 -0.9961806 -0.006858766 0.8460811 -0.2690727 -0.4601593 0.85589 -0.2471846 -0.45426 0.8856512 -0.249664 -0.3915223 0.05350542 -0.9956195 -0.07667481 -0.1182923 -0.9885907 -0.09324872 -0.1476355 -0.9887918 -0.02223616 -0.2268014 -0.9587498 -0.1713477 -0.3640441 -0.9305335 -0.03973984 -0.4484139 -0.8741388 -0.1865647 -0.4868569 -0.8707069 -0.06956934 0.8460726 -0.2690826 -0.4601691 0.8132899 -0.2569267 -0.5220614 0.8093188 -0.2793717 -0.5166765 0.7791941 -0.2582581 -0.5711035 0.7788969 -0.2720887 -0.5650552 0.7489466 -0.2446721 -0.615804 0.7461007 -0.26357 -0.6114446 -0.5300328 -0.8363544 -0.1399166 -0.6159558 -0.7598245 -0.2080026 -0.6364148 -0.7671845 -0.08002543 -0.7329705 -0.6389499 -0.2334461 -0.7095451 -0.6941738 -0.1211134 -0.8006442 -0.5328927 -0.2738508 -0.8021478 -0.5812392 -0.1368212 0.8339174 -0.4647734 -0.2976028 0.8062716 -0.4696261 -0.3596909 0.7785626 -0.5326168 -0.3319029 0.7284158 -0.5284043 -0.4361184 0.6986782 -0.5870964 -0.4088603 0.6385538 -0.564931 -0.5225917 0.6087744 -0.6194653 -0.4956374 0.5513456 -0.5800854 -0.599599 0.5416957 -0.6146659 -0.5733687 0.4786185 -0.5567343 -0.6789487 0.4559792 -0.6052991 -0.6524538 0.3975086 -0.5228561 -0.7540612 0.4012971 -0.5577271 -0.726568 0.3414011 -0.4584538 -0.8205276 0.3281251 -0.5078845 -0.7964842 0.258251 -0.3240521 -0.9101081 0.2471588 -0.3754883 -0.8932642 0.2181599 -0.2150249 -0.9519299 0.2223662 -0.2553048 -0.9409425 0.7409735 -0.2580587 -0.6199708 0.7195831 -0.2274592 -0.6560963 0.7215095 -0.2394222 -0.6496931 0.6966879 -0.1984248 -0.6893863 0.6938139 -0.2160906 -0.6869694 0.6650958 -0.1399351 -0.7335296 0.6617427 -0.1550462 -0.7335239 0.6509879 -0.09358799 -0.7532967 0.651745 -0.1025476 -0.7514736 0.6419129 -0.04457432 -0.7654808 0.6711406 0.05622017 -0.7391952 0.3112814 -0.1571698 -0.9372308 0.3113105 -0.1571668 -0.9372217 0.160039 0.08369052 -0.9835565 -0.04819864 -0.2512583 -0.9667193 -0.04820293 -0.2512582 -0.9667192 0.7008672 -0.6766507 -0.2256748 0.6699395 -0.6814258 -0.2946863 0.5973302 -0.7646589 -0.2418545 0.5359103 -0.7593854 -0.3689633 0.4616059 -0.830071 -0.3128933 0.3848485 -0.8016771 -0.4573898 0.3146443 -0.862122 -0.3971708 0.2371792 -0.810358 -0.5357852 0.212565 -0.8510043 -0.4802165 0.1258903 -0.7700139 -0.6254838 0.07958215 -0.8245625 -0.5601459 -0.00595045 -0.7093044 -0.7048772 0.001100242 -0.7628431 -0.6465827 -0.08500951 -0.6163638 -0.7828596 -0.1043448 -0.6874836 -0.7186644 -0.2061063 -0.4241412 -0.8818302 -0.2153016 -0.5166005 -0.8287153 -0.2696187 -0.2692953 -0.9245463 -0.2563378 -0.3643922 -0.8952705 -0.3112918 0.1411177 -0.9397783 -0.3556249 -0.07847851 -0.9313282 0.531068 -0.8398324 -0.112465 0.489156 -0.8469012 -0.2085304 0.3594466 -0.9240633 -0.13002 0.2935563 -0.9181619 -0.2660891 0.1675017 -0.9695686 -0.1785493 0.08413511 -0.9383742 -0.3352242 -0.02690947 -0.9711174 -0.2370796 -0.1141331 -0.9134977 -0.3905068 -0.1510276 -0.9412177 -0.3021588 -0.2479009 -0.8490183 -0.4665973 -0.3093324 -0.8817543 -0.3561221 -0.4098032 -0.7499518 -0.5192628 -0.3963384 -0.8113669 -0.4296506 -0.4934239 -0.6409947 -0.5879274 -0.5093053 -0.7132034 -0.481611 -0.6229876 -0.4174776 -0.6615125 -0.6240617 -0.5258564 -0.5779466 -0.6939262 -0.2387641 -0.6793071 -0.6750242 -0.3678642 -0.6395453 -0.7027976 -0.2003788 -0.6825861 -0.6035971 0.3123308 -0.7335667 -0.870158 -0.4352679 -0.231013 -0.9063898 -0.3135184 -0.2831321 -0.8920848 -0.409094 -0.1919026 -0.9484719 -0.17035 -0.2671742 -0.932242 -0.2793847 -0.2299325 -0.9453791 -0.2119885 -0.2476273 -0.7888576 0.3994358 -0.4670704 0.3687423 0 0.9295317 0.5754831 0 0.8178137 0.5224954 0.0108546 0.852573 0.3687423 0 0.9295316 0.078399 0 0.9969221 0.078399 0 0.9969221 -0.382632 0 0.9239009 -0.382632 0 0.9239009 -0.7603859 0 0.6494716 -0.7603859 0 0.6494716 -0.9724032 0 0.2333065 -0.9724032 0 0.2333065 0.3536564 0.5963388 0.7206296 0.4612283 0.5670028 0.6824779 0.4589096 0.5738102 0.678339 0.02788656 0.6396692 0.7681443 -0.06389248 0.642333 0.7637578 -0.4105302 0.5837346 0.7005134 -0.4705219 0.5677446 0.6754815 -0.7695332 0.4088128 0.4906027 -0.7952361 0.3900145 0.464207 -0.9733098 0.1467092 0.1764783 -0.9764131 0.1386957 0.1654719 0.5087422 0.2281752 0.8301309 0.4548541 0.2390453 0.8578842 0.07560127 0.2647607 0.961346 0.02740275 0.2678259 0.9630776 -0.3707961 0.2467972 0.895322 -0.4045271 0.2448932 0.8811272 -0.748475 0.1763035 0.6392983 -0.7640289 0.172769 0.6216194 -0.9704024 0.0641179 0.2328264 -0.9723844 0.06241655 0.2248839 -0.4865562 0.7027252 0.5190765 0.3571738 0.7437628 0.5650166 0.2991057 0.7526234 0.5865951 -0.4749404 0.6737548 0.566115 -0.798743 0.4466906 0.4030846 -0.9763928 0.1382931 0.1659278 -0.4750491 0.6737151 0.5660708 -0.4779207 0.690463 0.5430034 -0.4782802 0.6902788 0.542921 -0.4825944 0.6979238 0.5291551 -0.4824171 0.6980139 0.5291978 -0.9610913 0.1799452 0.2095788 -0.9510228 0.1272706 0.2817054 -0.9281314 0.1850218 0.3230156 -0.9094945 0.1499595 0.3877268 -0.9010522 0.1666705 0.4004072 -0.1884513 0.8744303 0.4470545 -0.1691317 0.8499883 0.4989131 -0.157637 0.8520554 0.4991515 -0.1409043 0.8217004 0.5522267 -0.1042339 0.8276239 0.5515196 -0.0955314 0.7769088 0.6223234 -0.06463873 0.7776094 0.6254163 0.299287 0.7526323 0.5864912 0.2849615 0.833738 0.4729461 0.212965 0.8454238 0.4898004 0.1867517 0.8952508 0.4045364 0.1648994 0.8980491 0.4078186 0.1317586 0.9380945 0.320341 0.1147018 0.9389292 0.324431 0.08971536 0.9359962 0.3403855 0.0330435 0.9690721 0.2445554 -0.4919372 0.7058097 0.5097357 -0.4920638 0.7057083 0.5097539 -0.2493441 0.8817499 0.4004305 -0.4862376 0.7029582 0.5190595 -0.2102591 0.8667982 0.4521635 -0.2422931 0.8846559 0.3983442 0.01930344 0.9680241 0.2501136 -0.04539525 0.986454 0.1576322 -0.05595141 0.9847261 0.1648752 -0.2906264 0.8901364 0.3509895 -0.2863518 0.8929809 0.3472575 -0.2909406 0.8902127 0.3505352 -0.4975033 0.7075858 0.5018095 -0.4980072 0.7070429 0.5020748 -0.6562054 0.452929 0.6035312 -0.7797438 0.4636894 0.4207039 -0.7761562 0.4437041 0.4480047 -0.7524698 0.4684597 0.4629629 -0.7441617 0.4535109 0.4904602 -0.7369037 0.4605479 0.4948419 -0.724377 0.4445564 0.5269227 -0.7103248 0.4628803 0.5302645 -0.689158 0.4514887 0.566762 -0.6850925 0.4570456 0.5672369 -0.6581752 0.4483269 0.6048209 -0.6554152 0.4538572 0.6036925 -0.8713628 0.1303477 0.4730079 -0.8664262 0.153008 0.4752833 -0.8573237 0.1734075 0.4846914 -0.8128442 0.1490136 0.5630979 -0.8076128 0.1623882 0.5669143 -0.7505459 0.1442868 0.6448737 -0.7476808 0.1561487 0.6454387 0.9561027 0.2562559 0.1421284 0.1708132 0.7032576 0.6901099 -0.09465843 0.9874534 0.1263942 0.06281548 0.9652188 0.2537853 0.06281703 0.9652174 0.2537899 -0.01372247 0.9652175 0.261088 0.2586006 0.965219 0.03844338 0.2586333 0.9652101 0.03844535 0.2362655 0.9652109 0.1120118 0.2362149 0.9652254 0.111993 0.1934264 0.9652248 0.1758626 0.1934504 0.9652165 0.1758808 0.1339204 0.9652188 0.2245392 -0.2730952 0.8889561 0.367663 -0.4289273 0.7034493 0.5667279 -0.2422059 0.7032698 0.668392 0.2322428 0.2561797 0.938315 -0.05073422 0.2561674 0.9653 -0.03731393 0.7032555 0.7099573 -0.2422106 0.703249 0.6684123 -0.0890721 0.9652178 0.2458064 -0.1551582 0.9652848 0.2101218 -0.2858538 0.8898513 0.3556013 0.7032327 0.7032327 0.1045343 0.7032001 0.7032656 0.1045334 0.6423841 0.7032665 0.3045638 0.6423842 0.7032662 0.3045639 0.5260154 0.7032729 0.4782415 0.5260068 0.7032835 0.4782354 -0.5546507 0.4506095 0.6995097 -0.4246765 0.7033854 0.5699989 -0.533829 0.4500454 0.7158811 -0.5920922 0.2078851 0.7785953 -0.5922046 0.1548539 0.790768 -0.05073583 0.2561885 0.9652944 -0.3293282 0.2562105 0.9087899 -0.3293195 0.2562185 0.9087909 -0.3293195 0.2562284 0.908788 -0.5794246 0.2562372 0.7736987 -0.08907026 0.9652197 0.2457993 -0.01372271 0.9652191 0.2610815 -0.03731513 0.7032732 0.7099397 0.17081 0.7032666 0.6901015 0.2322473 0.2561626 0.9383187 0.2322487 0.2561782 0.938314 0.133919 0.9652196 0.2245371 0.3641598 0.7032691 0.6105737 0.3641614 0.7032665 0.6105757 0.4951462 0.2561435 0.8301932 0.4951396 0.2561739 0.8301877 0.9561126 0.25622 0.1421266 0.8734294 0.2562122 0.4140972 0.8734367 0.2561675 0.4141092 0.8734357 0.2561706 0.4141095 0.7152173 0.2561705 0.6502621 0.7152137 0.2561845 0.6502606 0.4952466 0.2562051 0.8301143 0.9659084 0.258884 0 0.9659084 0.258884 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.2587919 0.965933 0 0.2587919 0.965933 0 0.2541434 0.9485824 0.1886861 0.9646306 0.2585415 0.05142104 0.9646193 0.258581 0.05143505 0.9646202 0.2192097 0.1464753 0.9646251 0.2191961 0.146463 0.9646239 0.1464684 0.2191981 0.9646178 0.146478 0.2192184 0.9646183 0.05143398 0.2585848 0.7002145 0.7002145 0.1392817 0.7002112 0.7002176 0.139283 0.7002207 0.593607 0.396638 0.7002843 0.5935619 0.3965934 0.7002828 0.3966041 0.5935563 0.7002735 0.3966078 0.593565 0.9646201 0.05143362 0.2585781 0.700275 0.1392678 0.7001567 0.7002432 0.139268 0.7001885 0.2541455 0.1886741 0.9485843 0.2541944 0.1886782 0.9485704 0.2542436 0.9485593 0.1886675 0.25422 0.8041703 0.5372917 0.2542622 0.8041511 0.5373004 0.2540037 0.8041779 0.5373827 0.2540588 0.5373417 0.8041878 0.2540547 0.5373418 0.8041891 0.2541401 0.5373592 0.8041504 0.3804388 0.01229012 0.9247245 0.05181509 0.004146277 0.9986481 0.2588435 0 0.9659193 0.9658985 0 0.2589209 0.9658985 0 0.2589209 0.7071344 0 0.7070791 0.7071344 0 0.7070791 0.2648914 0 0.9642782 0.4010692 0.02549624 0.9156929 0.8603605 0 0.5096859 0.7444018 0 0.6677319 0.831474 -0.003338456 0.5555536 0.8603606 0 0.5096859 0.9807839 0 0.1950969 0.9807839 0 0.1950969 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.9807807 0 0.195113 -0.9805545 -0.001245141 0.1962428 -0.8314823 0.001289486 0.5555496 -0.8294929 2.92127e-5 0.5585171 -0.8314742 2.98478e-5 0.5555633 -0.8294966 -0.002528607 0.5585061 -0.5555692 0.002515196 0.8314666 -0.5506505 -0.001669168 0.8347342 -0.5555374 -0.001667618 0.8314899 -0.5506463 -0.00377655 0.8347302 -0.1950968 0.003749549 0.9807769 -0.191632 0 0.9814669 -0.3196358 -0.3621745 -0.8755928 -0.4044919 -0.3503634 -0.8447673 -0.5329051 -0.2815353 -0.7979662 -0.3504389 -0.466712 -0.8120175 -0.4044921 -0.3503291 -0.8447814 -0.4907205 -0.2898839 -0.8216816 -0.49081 -0.2898308 -0.8216468 -0.4973131 -0.2754152 -0.8226944 -0.9777144 -0.06283062 -0.2003172 -0.9771739 -0.09418553 -0.1904212 -0.9771912 -0.09422862 -0.1903107 -0.987803 -0.1284204 -0.08805382 -0.9882668 -0.1421121 -0.05597162 -0.9428116 -0.1047507 -0.3164392 -0.8824151 -0.1411656 -0.4487937 -0.8053787 -0.1788475 -0.5651362 -0.8523511 -0.1955254 -0.4850436 -0.8048619 -0.2057433 -0.5566571 -0.7773736 -0.2083228 -0.5935418 -0.6779922 -0.2324914 -0.6973339 -0.9794536 -0.1316644 0.1527587 -0.9794535 -0.1705065 -0.1076967 -0.822037 -0.133778 0.5534968 -0.9794541 -0.04737788 0.1960226 -0.979453 -0.186904 0.07575356 -0.3616384 -0.8454957 0.39288 -0.1901105 -0.1257641 0.9736742 -0.5397764 -0.1977582 0.8182501 -0.5101584 -0.2252343 0.8300651 -0.5362627 -0.2270983 0.812926 -0.6442766 -0.1895489 0.7409312 -0.644334 -0.1895374 0.7408841 -0.4080358 -0.5960518 0.6915411 -0.7646589 -0.4911918 0.4171659 -0.5145338 -0.3678144 0.7745758 -0.8623853 -0.5059798 -0.01661169 -0.8029086 -0.5524501 0.2239121 -0.800897 -0.5964258 -0.053294 -0.9794525 -0.2008746 -0.01794928 -0.5542366 -0.7004441 -0.4496665 -0.5542036 -0.7005759 -0.4495016 -0.822502 -0.4786534 -0.3072154 -0.7697636 -0.4571852 -0.4454725 -0.8269013 -0.4754477 -0.3003062 -0.8150386 -0.5791779 -0.01628351 -0.8151313 -0.5790293 -0.01690918 -0.9775295 -0.07988739 -0.1950749 -0.9775921 -0.07973802 -0.1948218 -0.8247184 -0.3097098 -0.473201 -0.8004059 -0.2781278 -0.5310323 -0.6704913 -0.3512113 -0.6535229 -0.7846783 -0.3836004 -0.4869605 -0.4881691 -0.3575962 -0.7961255 -0.4881843 -0.3576655 -0.796085 -0.4880796 -0.3576963 -0.7961354 -0.8220441 -0.1337695 0.5534884 -0.8220436 -0.1337689 0.5534892 -0.822045 -0.3717612 0.4313185 -0.8220442 -0.3717603 0.4313209 -0.8249373 -0.5123915 0.2386069 -0.7757871 -0.474613 0.4158086 -0.7461314 -0.04693615 0.6641423 -0.5652612 0.03923761 -0.8239783 -0.5654372 0.03022205 -0.8242375 -0.6012107 -0.06688815 -0.7962862 -0.6044076 -0.02008414 -0.7964221 -0.167882 -0.005569875 0.9857914 -0.2266722 0.02595317 0.9736252 -0.4843914 -0.03838962 0.8740087 -0.6271501 -0.04269653 0.7777274 -0.7444257 0.08138608 0.6627268 -0.4843613 -0.0383886 0.8740254 -0.9248433 0.01155322 0.3801729 -0.9053982 -0.02594119 0.42377 -0.9979636 -0.03614813 0.05255287 -0.9998716 0.004912257 -0.01525211 -0.9582267 -0.05642986 -0.2803875 -0.565577 0.02023857 -0.8244471 -0.8117452 -0.04783838 -0.582049 -0.8908656 -0.05022698 -0.4514818 -0.8100968 0.07919281 -0.5809231 -0.9582085 -0.05642926 -0.2804502 -0.6012802 -0.06688082 -0.7962343 -0.6012783 -0.06684333 -0.796239 -0.887005 -0.09867787 -0.451093 -0.8869866 -0.09864717 -0.4511358 -0.9937522 -0.1105703 -0.01518887 -0.9937567 -0.1105195 -0.01527369 -0.9002414 -0.100153 0.4237155 -0.9002703 -0.1001207 0.4236617 -0.6250936 -0.06953722 0.7774462 -0.6251304 -0.06951588 0.7774187 -0.2234693 -0.02486032 0.9743939 -0.2234937 -0.02484989 0.9743885 -0.5907478 -0.1326637 -0.7958754 -0.5907252 -0.1326459 -0.7958949 -0.871018 -0.1956083 -0.4506274 -0.8710005 -0.1955844 -0.4506716 -0.9755878 -0.2190865 -0.01515275 -0.9755889 -0.2190806 -0.01516795 -0.8839531 -0.1985141 0.4233427 -0.883973 -0.1985024 0.4233067 -0.6140623 -0.1379002 0.777117 -0.6141021 -0.1378906 0.7770874 -0.2196164 -0.04931503 0.9743391 -0.2196296 -0.04931318 0.9743363 -0.2113762 -0.07734656 0.9743396 -0.2114019 -0.0773465 0.9743341 -0.5910229 -0.216279 0.7771199 -0.5910759 -0.2162737 0.7770811 -0.850787 -0.3113535 0.4233446 -0.8508642 -0.3113216 0.4232126 -0.9389823 -0.3436315 -0.01515674 -0.9390025 -0.3435687 -0.01532483 -0.8383306 -0.3068163 -0.4506281 -0.8382564 -0.3066838 -0.4508559 -0.5685733 -0.2081052 -0.7958747 -0.5435554 -0.2650472 -0.7964279 -0.5435242 -0.2650729 -0.7964408 -0.5683966 -0.2079265 -0.7960476 -0.1910797 -0.1190609 0.974327 -0.1911776 -0.1190814 0.9743053 -0.5342648 -0.3329232 0.7769963 -0.7572474 -0.4716286 -0.4518216 -0.7573894 -0.4720676 -0.4511245 -0.8486929 -0.5286376 -0.01620978 -0.8485714 -0.5288518 -0.01557159 -0.7692307 -0.4791768 0.4226981 -0.1741119 -0.1428898 0.9743036 -0.1742236 -0.1429293 0.9742779 -0.4870097 -0.3997371 0.7765511 -0.4870051 -0.3997325 0.7765564 -0.486791 -0.3994788 0.7768211 -0.5344913 -0.3329488 0.7768296 -0.768993 -0.4792193 0.4230821 -0.7008531 -0.5749882 0.4221296 -0.7005691 -0.5749262 0.4226853 -0.7006986 -0.5751558 0.422158 -0.4870352 -0.3995836 0.7766143 -0.7007783 -0.5749344 0.4223273 -0.7728178 -0.6344001 -0.0170021 -0.772873 -0.6343536 -0.01621156 -0.7730144 -0.6341599 -0.01702666 -0.7730175 -0.6341717 -0.01643502 -0.6889998 -0.5656804 -0.4530838 -0.689142 -0.5657908 -0.4527294 -0.6897085 -0.5658335 -0.4518128 -0.6893383 -0.5654351 -0.4528752 -0.4661093 -0.3828007 -0.797625 -0.2020564 -0.09857982 0.9743999 -0.2020896 -0.0985766 0.9743934 -0.565195 -0.2757903 0.7774924 -0.5653173 -0.2757627 0.7774131 -0.8140724 -0.3972249 0.4236725 -0.8141617 -0.3971722 0.4235505 -0.8985927 -0.4385156 -0.01534229 -0.898661 -0.4383667 -0.01559472 -0.8019475 -0.3913775 -0.4513354 -0.8019091 -0.3911386 -0.4516109 -0.5431537 -0.2651326 -0.7966736 -0.5133408 -0.3200459 -0.7962738 -0.5128741 -0.3193333 -0.7968605 -0.4671002 -0.3831847 -0.7968608 -0.4664168 -0.3824545 -0.7976114 -0.02247083 -0.9947925 -0.09941238 -0.08365607 -0.9189746 -0.3853404 -0.08368897 -0.9189135 -0.3854792 -0.162125 -0.7342253 -0.6592637 -0.1621369 -0.7341806 -0.6593106 -0.2035005 -0.6140924 -0.762547 -0.2043107 -0.5376822 -0.818019 -0.2801269 -0.4673092 -0.838541 -0.2905942 -0.3881648 -0.874576 0.1012231 -0.5486887 -0.8298763 0.06918162 -0.4930539 -0.8672438 0.02708226 -0.6272115 -0.778378 0.02708375 -0.6272115 -0.778378 -0.03276395 -0.4798748 -0.876725 -0.08148908 -0.6287654 -0.7733134 -0.1195927 -0.6281628 -0.7688362 -0.09595125 -0.4020503 -0.9105761 -0.1912097 -0.614307 -0.7655494 -0.1484022 -0.8220954 -0.549669 -0.1487558 -0.8283093 -0.5401625 -0.0861234 -0.828271 -0.5536696 -0.08612328 -0.8282678 -0.5536743 -0.02092546 -0.8282685 -0.5599405 -0.02092546 -0.8282686 -0.5599404 0.04455709 -0.8282683 -0.5585572 0.04455673 -0.8282692 -0.558556 -0.07003515 -0.9645236 -0.2545376 -0.07658755 -0.9798257 -0.1845966 -0.03028798 -0.9803918 -0.1947171 -0.03028792 -0.9803915 -0.1947185 -0.007359147 -0.9803915 -0.1969227 -0.007359147 -0.9803914 -0.1969226 0.01566994 -0.9803915 -0.1964359 0.01567023 -0.9803913 -0.1964371 -0.1910328 0 -0.9815837 -0.2365624 -0.002543151 -0.9716129 -0.5451985 0.001932144 -0.8383048 -0.5451871 0.001932144 -0.8383122 -0.656736 -0.0038594 -0.7541107 -0.819795 0.002628207 -0.5726512 -0.8198097 0.002628207 -0.5726299 -0.9298982 -0.00393486 -0.3677961 -0.9747138 0.00208348 -0.2234471 -0.9747158 0.00208348 -0.2234387 -0.9949013 -0.00277251 0.1008152 -0.9882647 0 0.1527512 -0.4372236 -0.3302174 -0.8365358 -0.3410789 -0.4136269 -0.8441433 -0.2992715 -0.3731065 -0.878196 -0.2975564 -0.3758445 -0.8776111 -0.3388611 -0.4157229 -0.8440068 -0.2536205 -0.5085526 -0.822831 -0.4372286 -0.3301809 -0.8365475 -0.4913509 -0.3815074 -0.7829601 -0.6020799 -0.3332661 -0.7255574 -0.3074795 -0.5601366 -0.7692226 -0.2688403 -0.6584036 -0.7030146 -0.2255499 -0.6655616 -0.7114456 -0.3104797 -0.7447511 -0.5907183 -0.2341458 -0.7486674 -0.62022 -0.6026826 -0.2987988 -0.7399277 -0.6510374 -0.3415235 -0.6778733 -0.7240339 -0.3296219 -0.6059079 -0.7420052 -0.3454479 -0.5745381 -0.8273723 -0.3096325 -0.4685966 -0.7974899 -0.2773969 -0.5357807 -0.8479557 -0.3134177 -0.4274817 -0.8972542 -0.3074277 -0.3168959 -0.9081982 -0.3153327 -0.2752115 -0.9473007 -0.2783776 -0.1585155 -0.3010734 -0.3716679 -0.87819 -0.3431107 -0.4119912 -0.8441198 -0.3397554 -0.4146717 -0.8441645 -0.4288023 -0.499322 -0.7528654 -0.4287009 -0.499381 -0.7528838 -0.5019577 -0.5668225 -0.6532617 -0.5020822 -0.5668082 -0.6531785 -0.5676164 -0.6248141 -0.5361148 -0.567982 -0.6247039 -0.5358559 -0.6278898 -0.6743158 -0.3886547 -0.6282176 -0.6743358 -0.38809 -0.6718789 -0.7058899 -0.2242726 -0.6724036 -0.7057097 -0.2232648 -0.2824829 -0.7937517 -0.5386666 -0.2703195 -0.8604676 -0.4318828 -0.216798 -0.8437593 -0.4909876 -0.2955586 -0.9132614 -0.2803546 -0.2345661 -0.9012031 -0.3644333 -0.298878 -0.9467484 -0.1197471 -0.2347588 -0.95008 -0.2055144 -0.2563444 -0.9664666 -0.01516187 -0.2529797 -0.9669655 -0.0312888 -0.7021298 -0.7116035 -0.02518498 -0.6933852 -0.715811 -0.08265376 -0.9630188 -0.2690066 -0.01517665 -0.9519095 -0.2789841 -0.1266341 -0.2587947 -0.9659189 -0.005095243 -0.2560868 -0.9664177 -0.02136462 -0.7071042 -0.7071051 0.00249803 -0.7006487 -0.7113245 -0.05575782 -0.965671 -0.258729 0.02321034 -0.9590662 -0.2687199 -0.08933967 -0.9659312 -0.2587987 0 -0.9659312 -0.2587987 0 -0.7071064 -0.7071073 0 -0.7071064 -0.7071073 0 -0.2587981 -0.9659315 0 -0.2587981 -0.9659315 0 -0.9485856 -0.2541514 0.1886597 -0.9485668 -0.2541884 0.1887044 -0.8041731 -0.2541874 0.5373031 -0.8041523 -0.2541751 0.5373398 -0.1886909 -0.2541718 0.948574 -0.1886845 -0.2541767 0.9485739 -0.5372924 -0.2541813 0.804182 -0.5373312 -0.2541684 0.8041602 -0.5373265 -0.2541651 0.8041644 -0.8041703 -0.2541608 0.5373198 -0.1392831 -0.7002107 0.700218 -0.1392863 -0.7002086 0.7002194 -0.3966479 -0.7002074 0.5936161 -0.3966476 -0.7002076 0.5936161 -0.5936103 -0.7002087 0.3966543 -0.5936273 -0.700198 0.3966477 -0.7002369 -0.7001951 0.1392668 -0.7002133 -0.7002142 0.1392894 -0.05141127 -0.9646544 0.2584545 -0.05140924 -0.964655 0.2584527 -0.1464029 -0.9646552 0.2191041 -0.146402 -0.9646553 0.2191038 -0.2191041 -0.9646555 0.1464002 -0.2191007 -0.9646563 0.1464004 -0.2584462 -0.9646568 0.05141115 -0.2584559 -0.9646543 0.05140626 0 -0.2588211 0.9659253 0 -0.2588211 0.9659253 0 -0.7071031 0.7071105 0 -0.7071031 0.7071105 0 -0.9659318 0.2587967 0 -0.9659318 0.2587967 0.1446517 -0.964688 0.2201203 0.3919801 -0.7004004 0.5964822 0.5311335 -0.2543006 0.8082255 0.5311486 -0.2543033 0.8082147 0.5311384 -0.2542884 0.8082261 0.1862559 -0.2542918 0.9490228 0.1862561 -0.2542921 0.9490228 0.3919923 -0.7003829 0.5964946 0.3919929 -0.7003886 0.5964876 0.1374611 -0.7003893 0.7003995 0.1374626 -0.7003905 0.7003978 0.1446486 -0.96469 0.2201139 0.1446508 -0.9646883 0.2201198 0.05072689 -0.9646883 0.2584632 0.05072671 -0.9646882 0.2584636 0.5533085 -0.2555121 0.7928199 0.03825861 -0.9800699 0.1949343 0.1610535 -0.5483451 0.820597 0.1084104 -0.8265193 0.5523703 0.1084222 -0.8265628 0.552303 0.1083748 -0.8266443 0.5521904 0.03825855 -0.9800698 0.1949346 0.4228826 -0.7037461 0.5708869 0.288944 -0.8283713 0.4799088 0.1704295 -0.965826 0.1952795 0.1420323 -0.9780991 0.1521487 0.1446554 -0.9646882 0.2201169 0.4228927 -0.7037274 0.5709023 0.4430856 -0.5499282 0.707993 0.1610508 -0.5483509 0.8205936 0.1610507 -0.5483483 0.8205955 0.5533084 -0.2555125 0.7928197 0.5390131 -0.1915499 0.8202278 0.1890203 -0.1915572 0.9631081 0.1890264 -0.1915735 0.9631035 0 -0.1950907 0.9807853 0 -0.1950907 0.9807853 0 -0.555601 0.831449 0 -0.555601 0.831449 0 -0.555598 0.8314511 0 -0.555598 0.8314511 0 -0.8314195 0.5556452 0 -0.8314195 0.5556452 0 -0.8315419 0.555462 0 -0.8315419 0.555462 0 -0.9807878 0.1950774 0 -0.9807878 0.1950774 0.1533522 -0.9807416 0.1209497 0.1572394 -0.9819552 0.1050702 0.1520447 -0.9831303 0.1016719 0.4691347 -0.8288679 0.3047795 0.4595879 -0.8545235 0.2420093 0.8294782 -0.5531902 0.0771144 0.8119411 -0.5826341 0.03590446 0.8262083 -0.551197 0.1164541 0.5151676 -0.8320338 0.2057238 0.5151362 -0.8320543 0.2057192 0.9253014 -0.1883047 -0.3291788 0.9198844 -0.2154123 -0.3277349 0.2060397 -0.1907569 0.9597705 0.5860676 -0.1908226 0.7874715 0.5854799 -0.1907981 0.7879145 0.8593536 -0.1908242 0.4744445 0.9252994 -0.188309 -0.329182 0.925376 -0.1883139 -0.3289637 0.9745721 -0.2107746 0.07604777 0.9730301 -0.2105109 0.09432703 0.9786443 -0.1908212 0.0764364 0.2077694 -0.1908333 0.9593824 0.2077633 -0.1908399 0.9593824 0.1772084 -0.5468077 0.8182899 0.1772111 -0.5468017 0.8182935 0.1772123 -0.5468043 0.8182913 0.4841986 -0.8331174 0.2673333 0.7329735 -0.54679 0.4046857 0.7329714 -0.5468071 0.4046666 0.8593556 -0.1908208 0.4744421 0.8594502 -0.1908327 0.4742659 0.1194708 -0.8254646 0.5516655 0.1194288 -0.8255043 0.5516152 0.1194309 -0.8255902 0.5514863 0.04220861 -0.9799138 0.1949033 0.04220849 -0.9799138 0.1949036 0.5860558 -0.1908366 0.787477 0.4998729 -0.5467916 0.671674 0.499875 -0.5467975 0.6716676 0.3369596 -0.8255084 0.4527629 0.3369597 -0.8255103 0.4527592 0.1190606 -0.9799143 0.159977 0.1190609 -0.979914 0.1599786 -0.3929508 -0.8961291 -0.2062578 -0.1509475 -0.9864781 -0.06384122 -0.3922821 -0.8964487 -0.2061418 -0.9620452 -0.2278271 0.1502126 -0.9769254 -0.1510506 0.1509985 -0.1847453 -0.2543659 -0.9492983 -0.1847492 -0.254369 -0.9492967 -0.5272661 -0.2543713 -0.8107316 -0.5272682 -0.2543708 -0.8107304 -0.9620271 -0.2278862 0.1502388 -0.8855876 -0.2334194 0.4015595 -0.9401431 -0.2639793 -0.2155133 -0.8932588 -0.3435124 0.2899796 -0.936417 -0.2775625 -0.2146677 -0.9353256 -0.2556772 -0.2445305 -0.7928442 -0.254381 -0.5537946 -0.7928252 -0.2543646 -0.5538294 -0.7928346 -0.254359 -0.5538185 -0.5272564 -0.2543616 -0.810741 -0.7067185 -0.6786344 -0.200011 -0.7032432 -0.6978645 -0.1357723 -0.5850484 -0.7004954 -0.4086866 -0.5850484 -0.7004979 -0.4086819 -0.3890853 -0.7004984 -0.5982598 -0.3890854 -0.7004985 -0.5982595 -0.1363285 -0.7004977 -0.7005124 -0.1363325 -0.700501 -0.7005083 -0.3925057 -0.8963608 -0.2060986 -0.3304253 -0.935261 0.1269101 -0.2158638 -0.9647099 -0.1507903 -0.2158634 -0.9647102 -0.1507888 -0.14356 -0.9647098 -0.2207385 -0.1435597 -0.9647091 -0.2207421 -0.05030274 -0.9647095 -0.2584672 -0.0503022 -0.9647093 -0.2584682 0 -0.2588211 -0.9659252 0 -0.2588211 -0.9659252 0 -0.7071031 -0.7071105 0 -0.7071031 -0.7071105 0 -0.965932 -0.2587958 0 -0.965932 -0.2587958 0.1862559 -0.2542921 -0.9490228 0.5311459 -0.2542993 -0.8082178 0.5311384 -0.2542884 -0.8082261 0.5311335 -0.2543005 -0.8082255 0.3919924 -0.700383 -0.5964946 0.3919929 -0.7003886 -0.5964876 0.3919801 -0.7004004 -0.5964822 0.1446486 -0.96469 -0.2201139 0.1446508 -0.9646883 -0.2201199 0.1446517 -0.964688 -0.2201203 0.1862561 -0.2542918 -0.9490228 0.1374608 -0.7003908 -0.7003981 0.1374629 -0.7003895 -0.7003989 0.05072677 -0.9646884 -0.2584626 0.05072724 -0.9646883 -0.258463 0.1610507 -0.5483482 -0.8205955 0.109101 -0.9800694 -0.1660152 0.4228927 -0.7037274 -0.5709024 0.4228826 -0.7037461 -0.5708869 0.288944 -0.8283712 -0.4799088 0.1704295 -0.965826 -0.1952796 0.1704336 -0.965824 -0.1952859 0.1084097 -0.8265217 -0.552367 0.1084209 -0.8265627 -0.5523034 0.108376 -0.8266397 -0.552197 0.03825849 -0.9800698 -0.1949344 0.03825867 -0.9800697 -0.1949346 0.1610535 -0.5483451 -0.820597 0.1610508 -0.5483509 -0.8205936 0.4430856 -0.5499282 -0.707993 0.5533085 -0.2555121 -0.7928198 0.1890197 -0.1915738 -0.9631049 0.189027 -0.1915575 -0.9631067 0.561424 -0.1904865 -0.8053062 0.5311297 -0.2542984 -0.8082286 0 -0.1950907 -0.9807852 -0.01276046 -0.2588069 -0.9658448 0.008534193 -0.5555807 -0.8314188 0.008534193 -0.5555778 -0.8314208 -0.01703017 -0.7069969 -0.7070116 0 -0.9807878 -0.1950774 -0.01275604 -0.9658538 -0.2587739 0.008532106 -0.8315071 -0.5554485 0.008532106 -0.8313915 -0.5556215 0.1897946 -0.2541235 -0.9483667 0.5401841 -0.2541156 -0.8022633 0.8073247 -0.2541289 -0.5325836 0.9606755 -0.2050684 -0.1872156 0.9606674 -0.2050716 -0.1872525 0.9638894 -0.1884322 -0.1881766 0.7985795 -0.2909724 -0.5268831 0.7651764 -0.2853886 -0.5771121 0.6567171 -0.5569248 -0.5084855 0.6082419 -0.6851677 -0.4007331 0.2207541 -0.9121803 -0.3452461 0.1758963 -0.9625969 -0.2060768 0.08667927 -0.9807016 -0.1752455 0.5401802 -0.2541249 -0.802263 0.5401726 -0.2541194 -0.8022699 0.4023262 -0.6935998 -0.597539 0.4049149 -0.6994084 -0.5889583 0.2919907 -0.8255813 -0.4828634 0.2918316 -0.8257822 -0.482616 0.1898002 -0.2541192 -0.9483667 0.1401212 -0.7001234 -0.700138 0.140123 -0.7001222 -0.7001388 0.05172485 -0.9646394 -0.2584485 0.05172413 -0.9646396 -0.2584478 0.4258587 0 -0.9047898 0.006437778 -0.9999532 -0.007231593 0.001865029 0.9999877 -0.004586637 0.4258586 0 -0.9047896 0.006437778 -0.9999532 -0.007231593 0.004066407 0.9999862 -0.003363907 0.01021564 -0.9999318 -0.005661249 0.01021516 -0.9999318 -0.005662202 0.007890403 0.9999671 -0.001883924 0.9858067 0 -0.167885 0.9745368 -0.06503599 -0.2145889 0.7785876 -0.1819887 -0.6005676 0.426102 -0.2624644 -0.8657652 0.4260745 -0.2623795 -0.8658046 0.4260435 -0.2624278 -0.8658052 0.4259455 -0.2311286 -0.8747285 0.4258325 -0.2311871 -0.8747681 0.4256289 -0.1706108 -0.8886686 0.4255727 -0.1705929 -0.888699 0.4255037 -0.1706413 -0.8887228 0.4256932 -0.1065087 -0.8985773 0.4256917 -0.1065095 -0.898578 0.974539 -0.06502437 -0.2145822 0.9745254 -0.05729722 -0.2168347 0.9745162 -0.05732208 -0.21687 0.9744873 -0.04231357 -0.220418 0.9744837 -0.04231995 -0.2204326 0.97451 -0.02640551 -0.2227848 0.97451 -0.02640551 -0.2227849 0.9744819 -0.01012527 -0.2242373 0.9744793 -0.01012861 -0.2242493 0.77856 -0.1820375 -0.6005886 0.7784747 -0.1603508 -0.6068482 0.7784202 -0.160399 -0.6069054 0.77824 -0.1183841 -0.616707 0.7782056 -0.1184042 -0.6167467 0.7783693 -0.07389348 -0.6234429 0.778363 -0.07389783 -0.6234501 0.7781896 -0.02833724 -0.6273898 0.7781782 -0.02834212 -0.6274037 0.4255034 -0.04083859 -0.9040349 0.4254876 -0.04083484 -0.9040425 0.4254933 -0.04083907 -0.9040396 0.1200869 -0.9927634 0 0.2587814 -0.965898 -0.008548617 0.2773884 -0.9607311 -0.007182657 0.6894334 -0.7243299 -0.005284249 0.5655665 -0.8247025 -5.46504e-4 0.4260038 -0.904721 9.39994e-4 0.4261721 -0.9046415 9.39995e-4 0.9659241 -0.2588254 0 0.9985973 -0.04246824 -0.03162223 0.9841337 -0.1768698 -0.01406884 0.9449245 -0.3272556 -0.004623532 0.8824353 -0.4704305 0.001791179 0.7071196 -0.7070919 0.001715064 0.8742229 -0.4842295 -0.03544282 0.791837 -0.6104311 -0.01918172 0.42611 -0.2776907 -0.8609983 0.7786033 -0.1894877 -0.5982236 0.9744405 -0.05363249 -0.2181495 0.9686064 -0.1469275 -0.2005338 0.9647569 -0.1833421 -0.1887593 0.9333256 -0.2862263 -0.2167435 0.9185539 -0.3394443 -0.202574 0.8893405 -0.4119454 -0.1984301 0.8344822 -0.5256057 -0.1654633 0.8536821 -0.4791871 -0.2039771 0.8174463 -0.5371893 -0.2078683 0.7723014 -0.6049864 -0.1937574 0.7391523 -0.6444772 -0.1957116 0.6737118 -0.7168319 -0.1796231 0.6421124 -0.7404366 -0.1986089 0.5509478 -0.8125638 -0.1902537 0.5345085 -0.8227471 -0.1933597 0.4234347 -0.2912788 -0.8578227 0.4218622 -0.3193836 -0.8485438 0.4081353 -0.3312755 -0.8506951 0.3987772 -0.3625612 -0.8423338 0.3922037 -0.3721606 -0.8412328 0.3797098 -0.4036395 -0.8324036 0.3673399 -0.4088232 -0.835419 0.347014 -0.4379976 -0.8293005 0.3407595 -0.4427525 -0.8293692 0.316766 -0.4714164 -0.8230589 0.309369 -0.4719334 -0.8255723 0.2770909 -0.4963046 -0.8227409 0.2739969 -0.4973021 -0.8231745 0.2375347 -0.5198069 -0.8205962 0.2366781 -0.5195593 -0.8210003 0.1938824 -0.5340568 -0.8229175 0.1957249 -0.5340697 -0.8224727 0.1494011 -0.5451496 -0.824919 0.1536208 -0.5483245 -0.8220346 0.7726454 -0.2375376 -0.5887231 0.7687752 -0.2843014 -0.5728502 0.7379392 -0.332791 -0.5871079 0.7217197 -0.3892527 -0.5723662 0.7032158 -0.4246515 -0.5702269 0.6780312 -0.484309 -0.5529182 0.6465155 -0.5101276 -0.5672633 0.6065642 -0.5689114 -0.5553554 0.5878576 -0.5871345 -0.5565039 0.5363059 -0.646345 -0.5427837 0.516417 -0.6538254 -0.5530153 0.4465621 -0.707927 -0.5471944 0.4376798 -0.712161 -0.5488745 0.3543627 -0.7616441 -0.5425175 0.3526846 -0.7616599 -0.5435877 0.2541601 -0.796612 -0.5484632 0.2610743 -0.7957364 -0.5464831 0.1508881 -0.8202964 -0.5516763 0.1646001 -0.825445 -0.5399512 0.4158066 -0.8903448 -0.1854483 0.4181681 -0.8891474 -0.1858828 0.4158 -0.8899604 -0.1872987 0.2758182 -0.9415929 -0.1932018 0.2886967 -0.938468 -0.1895575 0.1271203 -0.9718676 -0.1982771 0.1531557 -0.972453 -0.1757224 0.9993689 -2.89587e-4 0.03551995 0.9993695 -2.89402e-4 0.03550267 0.9878654 -0.002771794 0.1552882 0.9878701 -0.002770602 0.1552579 0.954978 -0.0089221 0.2965424 0.9826605 -0.001292049 0.1854093 0.9182232 5.27462e-5 0.3960632 0.7963949 5.1205e-5 0.6047771 0.9183647 -0.01746571 0.3953497 0.7911428 0 0.6116316 0.8192577 1.60493e-4 -0.5734254 0.8992813 -7.36416e-5 -0.4373708 0.8992965 -7.38473e-5 -0.4373395 0.949606 -0.001821637 -0.3134407 0.9756302 -0.005642771 -0.2193487 0.9868702 -0.008211612 -0.1613064 0.9620159 -8.52064e-4 -0.2729923 0.9990511 5.73562e-5 -0.04355347 0.9990462 5.73562e-5 -0.04366612 0.8191394 1.60493e-4 -0.5735945 0.7388149 -0.003340244 -0.6739002 0.7300749 -0.002945959 -0.6833608 0.1778337 0 -0.9840606 0.2390745 -6.35483e-4 -0.971001 0.3828654 -0.002925992 -0.9237996 0.3600501 -0.001765131 -0.9329313 0.6141155 9.01855e-4 -0.7892156 0.6140704 9.01855e-4 -0.7892507 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.5345062 0 -0.8451645 -0.5345062 0 -0.8451645 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.9659251 0 0.258822 0.9659248 0 -0.2588229 0.9659248 0 -0.2588229 0.7071091 0 -0.7071045 0.7071091 0 -0.7071045 0.2588174 0 -0.9659262 0.2588174 0 -0.9659262 -0.2588176 0 -0.9659261 -0.2588176 0 -0.9659261 -0.7071086 0 -0.7071049 -0.7071086 0 -0.7071049 -0.9659287 0 -0.2588083 -0.9659287 0 -0.2588083 -0.9659289 0 0.2588073 -0.9659289 0 0.2588073 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.2588176 0 0.9659261 -0.2588176 0 0.9659261 0.2588174 0 0.9659262 0.2588174 0 0.9659262 0.7071073 0 0.7071064 0.7071073 0 0.7071064 0.9659251 0 0.258822 -0.6432051 -5.06387e-7 0.765694 -0.6432002 -2.6264e-7 0.7656981 -0.7070906 -0.006562054 0.7070925 -0.2588205 0 0.9659255 -0.2588043 5.84888e-7 0.9659298 -0.2588179 -1.68245e-7 0.9659261 -0.2588206 0 0.9659253 -0.6431916 0 0.7657054 0.258819 0 0.9659258 0.2588174 0 0.9659262 0.2588214 3.99948e-7 0.9659252 0.7070958 -0.005353987 0.7070976 0.6431981 0 0.7656998 0.2588059 0 0.9659294 -0.8194651 0 0.5731291 -0.9659247 0 0.2588233 -0.9659247 0 0.2588233 -0.965925 0 -0.2588223 -0.965925 0 -0.2588223 -0.7071077 0 -0.7071059 -0.7071077 0 -0.7071059 -0.2588213 0 -0.9659252 -0.2588213 0 -0.9659252 0.2588208 0 -0.9659253 0.2588208 0 -0.9659253 0.7071077 0 -0.7071059 0.7071077 0 -0.7071059 0.9659255 0 -0.2588206 0.9659255 0 -0.2588206 0.9659252 0 0.2588216 0.9659252 0 0.2588216 0.8194639 0 0.5731309 0.6431678 -0.009750425 0.7656632 0.9659246 0 0.2588237 0.9659247 0 -0.2588228 0.9659247 0 -0.2588228 0.7071077 0 -0.7071059 0.7071077 0 -0.7071059 0.2588176 0 -0.9659261 0.2588176 0 -0.9659261 -0.2588208 0 -0.9659253 -0.2588208 0 -0.9659253 -0.7071008 0 -0.7071127 -0.7071008 0 -0.7071127 -0.9659287 0 -0.2588082 -0.9659287 0 -0.2588082 -0.9659286 0 0.2588091 -0.9659286 0 0.2588091 -0.7071017 0 0.7071119 -0.7071017 0 0.7071119 -0.2588208 0 0.9659253 -0.2588208 0 0.9659253 0.2588176 0 0.9659261 0.2588176 0 0.9659261 0.7071087 0 0.7071051 0.7071087 0 0.7071051 0.9659246 0 0.2588237 -0.9667078 0.2391716 -0.0909568 -0.8201395 0.4204047 -0.3881122 -0.9041789 0.3732814 -0.2076573 -0.9041268 0.373372 -0.2077208 -0.9098695 0.3634941 -0.2000241 -0.7935469 0.1178888 -0.5969803 -0.7307884 0.01838117 -0.6823565 -0.7752981 0.07678085 0.6269112 -0.7752677 0.07675731 0.6269515 -0.8506536 0.2609066 0.4564167 -0.9221034 0.2620746 0.2846793 -0.9174319 0.3949562 0.04825288 -0.9162305 0.3817177 0.1217097 -0.941036 0.3145291 0.1245907 -0.9127307 0.3794217 0.1515314 -0.9221065 0.2620821 0.2846623 -0.7857863 0.05526781 0.6160238 -0.793938 0.03472721 0.6070062 -0.8257449 0.09738063 0.5555739 -0.8537715 0.01945865 0.5202842 -0.8948556 0.08651059 0.4378918 -0.9144634 0.01651525 0.4043317 -0.9355475 0.0625481 0.3476182 -0.977225 0.198615 0.07472211 -0.9616348 0.2547491 0.1017911 -0.9613065 0.2572158 0.09864085 -0.959598 0.2625948 0.1010723 -0.9410152 0.3146331 0.1244839 -0.9885448 0.1419093 0.05139064 -0.9885458 0.1419106 0.05136752 -0.9775462 0.1957362 0.0780428 -0.9406634 0.04316651 0.3365844 -0.9488617 0.001482963 0.3156888 -0.9738769 0.05595278 0.2200753 -0.9815865 0.001681923 0.1910102 -0.9900426 0.03554904 0.1362051 -0.9933567 0.002121806 0.1150571 -0.995994 0.02511364 0.08582007 -0.9975122 0.006536662 0.07019191 -0.9977854 0.01712518 0.06427234 -0.9986751 0.00425148 0.05128294 -0.998888 0.01681113 0.0440467 -0.9994847 0.008520007 0.03094887 -0.9993906 0.01272135 0.03250575 -0.9997416 0.006890714 0.0216602 -0.9996875 0.01269567 0.02153241 -0.9999009 0.009842753 0.01006138 -0.999952 0.009666502 0.001588702 -0.9999542 0.009418666 0.001732468 -0.9998698 0.01114743 0.01165771 -0.999952 0.009673535 0.001579761 -0.9998865 0.01103931 -0.01024758 -0.9998797 0.009414136 -0.01232773 -0.9996443 0.01285481 -0.02336692 -0.9994783 0.006700098 -0.03159314 -0.9991623 0.01189213 -0.03916001 -0.9988037 0.009945809 -0.04787909 -0.9983099 0.01666408 -0.05567497 -0.9965314 0.005291402 -0.08304876 -0.9955604 0.01773113 -0.09243977 -0.9920678 0.009232223 -0.1253643 -0.9907954 0.02236402 -0.1335074 -0.9832119 0.01126056 -0.1821192 -0.9807618 0.03073382 -0.192774 -0.9885321 0.1400543 0.05647104 -0.9950543 0.09411203 0.03178089 -0.9951267 0.09271484 0.0335673 -0.9973142 0.07058477 0.01954758 -0.9973513 0.06985545 0.02026659 -0.9980343 0.06129491 0.0130611 -0.9980566 0.06089127 0.01323717 -0.9983347 0.05694127 0.009248912 -0.9983473 0.05670243 0.009352684 -0.9984896 0.05460613 0.006040632 -0.9984568 0.05518275 0.006234407 -0.9985316 0.05401885 0.004070162 -0.9985614 0.05346679 0.00407052 -0.9985956 0.05294328 0.001965463 -0.9985932 0.05298864 0.002011537 -0.9986109 0.05268955 2.95213e-4 -0.9986115 0.05267834 2.91051e-4 -0.9985942 0.0529623 -0.002170205 -0.9985961 0.05292326 -0.002206325 -0.998529 0.05394202 -0.00547564 -0.9985232 0.05406099 -0.005363881 -0.998375 0.05632489 -0.008659303 -0.9983732 0.05637425 -0.008536219 -0.9980086 0.0614143 -0.01438719 -0.9979915 0.06185495 -0.01366651 -0.9970754 0.07313519 -0.02218353 -0.9970692 0.07344728 -0.02140963 -0.9953022 0.09122455 -0.03243023 -0.9953012 0.09178256 -0.03084635 -0.9913535 0.1223002 -0.04754835 -0.9913702 0.1232627 -0.04462367 -0.9821035 0.1745614 -0.07071751 -0.9237179 0.007077455 -0.3830083 -0.9545515 0.0649451 -0.290884 -0.9640319 0.01449376 -0.2653911 -0.9821095 0.174523 -0.0707302 -0.9818133 0.1781172 -0.06570321 -0.9664967 0.2384693 -0.09495538 -0.9237158 0.007072865 -0.3830133 -0.9127665 0.05205059 -0.4051519 -0.8708883 0.04065924 -0.4897962 -0.8618466 0.06811654 -0.502574 -0.7942193 0.05138832 -0.6054544 -0.7659528 0.1165476 -0.6322445 -0.7901897 0.1015585 -0.604389 -0.7057464 0.2601607 -0.6589677 -0.7988945 0.1223319 -0.5888993 -0.9253931 0.3443182 -0.1584068 -0.9138531 0.3693272 -0.1687306 -0.9312255 0.3388834 -0.1340785 -0.9330398 0.3344121 -0.1326853 -0.946623 0.2998877 -0.118205 -0.9467114 0.299334 -0.1188972 -0.9467049 0.2993609 -0.1188809 -0.8855106 0.2315971 0.4027826 -0.9062598 0.1815268 0.3817607 -0.911475 0.2136654 0.3515117 -0.937237 0.1412899 0.3187852 -0.9451105 0.1754256 0.2756667 -0.9638129 0.1085338 0.2434853 -0.9675978 0.1320266 0.2152291 -0.9801648 0.07113897 0.184976 -0.9851905 0.09964996 0.1395333 -0.9926608 0.04714715 0.111363 -0.9941965 0.06510585 0.08564132 -0.9971029 0.03581196 0.06710648 -0.997411 0.04789686 0.05364 -0.9985643 0.03366577 0.04166585 -0.9984726 0.03918647 0.03894639 -0.9990845 0.0304135 0.03009158 -0.9989591 0.03684997 0.02688676 -0.9993269 0.03161376 0.01860803 -0.9992514 0.03353518 0.01928448 -0.9994636 0.03010207 0.01290148 -0.9993638 0.03326171 0.01286959 -0.999481 0.03160828 0.006216824 -0.9994636 0.03205418 0.00671184 -0.9995175 0.03104716 9.30958e-4 -0.9995142 0.03115189 9.74972e-4 -0.9994686 0.03198772 -0.006263315 -0.9994896 0.03112989 -0.007184803 -0.9993318 0.03346991 -0.01469033 -0.9993759 0.03022754 -0.01827597 -0.9991187 0.0342952 -0.0242002 -0.99906 0.03312599 -0.02795833 -0.9985876 0.03957706 -0.03544783 -0.9982967 0.03314763 -0.04800987 -0.9972729 0.0460031 -0.05771052 -0.9964796 0.04090142 -0.07318067 -0.9948338 0.05764478 -0.08356279 -0.9930086 0.05100721 -0.1064526 -0.9895722 0.07788872 -0.1211612 -0.9854485 0.06834107 -0.1556302 -0.977417 0.1132184 -0.1784309 -0.9680592 0.09871846 -0.2304693 -0.9553545 0.1491911 -0.255029 -0.9440508 0.1423077 -0.2975173 -0.9280149 0.1907525 -0.3200029 -0.9085462 0.1812426 -0.3764239 -0.8979911 0.207883 -0.3878102 -0.8880576 0.2201366 -0.4036006 -0.8907031 0.2139931 -0.4010671 -0.8791139 0.2310926 -0.4168393 -0.02368551 0 -0.9997195 -0.1823869 0 -0.9832269 -0.1823587 -3.33154e-5 -0.983232 -0.08977007 0 -0.9959625 -0.08977007 0 -0.9959625 -0.08976 0 -0.9959635 -0.08976 0 -0.9959635 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2588105 0 -0.9659281 -0.2588105 0 -0.9659281 -0.7071132 0 -0.7071003 -0.7071132 0 -0.7071003 -0.9659252 0 -0.2588216 -0.9659252 0 -0.2588216 -0.9807885 0 0.1950744 -0.9807885 0 0.1950744 -0.8314772 0 0.5555589 -0.8314772 0 0.5555589 -0.5555595 0 0.8314769 -0.5555595 0 0.8314769 -0.1950815 0 0.980787 -0.1950815 0 0.980787 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.001717746 -0.9999983 -5.79157e-4 -0.001074492 -0.9999992 -4.43573e-4 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 4.71687e-4 -1 7.88013e-7 -4.60806e-4 -0.9999999 -1.39959e-4 -3.19303e-5 -1 -3.71532e-5 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -4.98457e-5 -1 -3.33062e-5 -4.82832e-5 -1 -9.60433e-6 -6.00188e-5 -1 -8.98236e-5 -6.56884e-5 -1 -1.14256e-4 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -4.51605e-5 -1 -4.43873e-5 -4.51605e-5 -1 -4.43873e-5 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.3906602 0.920535 0 -0.3906602 0.920535 0 -0.7637506 0.6455115 0 -0.7637506 0.6455115 0 -0.9727682 0.2317801 0 -0.9727682 0.2317801 -0.1701796 -0.7534013 0.6351579 0.01056456 -0.3906383 0.9204835 -0.02236056 -0.7635596 0.64535 0.1865242 -0.6932735 0.6961181 0.1865261 -0.6932733 0.6961179 0.1017618 -0.7946149 0.5985246 0.1617211 -0.7807254 0.6035844 0.1551195 -0.7849248 0.5998592 0.4737598 -0.6763625 0.5639907 0.02937018 -0.9537297 0.2992273 0.2473904 -0.9230728 0.2945075 -0.10884 -0.9669893 0.2304031 -0.2505766 -0.250378 0.9351589 -0.008147537 -0.7393094 0.6733167 -0.08996248 -0.731346 0.676047 0.06691735 -0.3680769 0.9273841 0.04519683 -0.3706493 0.9276725 0.09505403 -0.2760608 0.9564284 0.04888862 -0.2923282 0.9550676 0.08701419 -0.23925 0.9670512 0.03500562 -0.2584677 0.9653854 0.05436652 -0.2032854 0.977609 -0.002109169 -0.2127645 0.9771012 -0.004147887 -0.2165079 0.9762721 -0.02129143 -0.2129787 0.9768249 -0.04535007 -0.2199275 0.9744614 -0.0263549 -0.2254632 0.9738951 -0.08867549 -0.3132833 0.9455106 -0.03868478 -0.3274301 0.9440831 -0.09663963 -0.3249889 0.9407673 -0.01991099 -0.3438032 0.9388307 -0.07599246 -0.3895305 0.9178731 0.1886596 -0.7084975 0.6800286 0.07451146 -0.7263061 0.683321 0.2677497 -0.5181287 0.8123133 0.1135005 -0.5754822 0.8099 0.222878 -0.4560859 0.8615748 0.08093738 -0.5091735 0.8568498 0.1377686 -0.3860704 0.9121236 -0.00564903 -0.4108312 0.9116939 -0.009705245 -0.4192433 0.9078221 -0.06049084 -0.4093253 0.9103811 -0.107612 -0.4260698 0.8982673 -0.0971536 -0.4291492 0.8979935 -0.1868433 -0.6157801 0.7654439 -0.08737385 -0.6430854 0.7607937 -0.2336978 -0.6266521 0.7434329 -0.03327399 -0.6755596 0.7365542 -0.1676557 -0.7529402 0.6363746 -0.1701911 -0.7533987 0.6351578 -0.1483693 -0.7770586 0.6116917 -0.3712989 -0.8165491 0.4420232 -0.09708839 -0.8904061 0.4446917 -0.3369864 -0.8517691 0.4011604 -0.02835434 -0.9152247 0.4019449 -0.1911108 -0.9548386 0.227508 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2679644 -0.1599673 -0.9500555 -0.2784075 -0.08480131 -0.9567121 -0.2698184 -0.333994 -0.9031313 -0.2722492 -0.1602625 -0.9487868 -0.2610443 -0.3351747 -0.90527 -0.2494692 -0.4632814 -0.8503737 -0.2170949 -0.6360381 -0.7404899 -0.2491458 -0.4632918 -0.8504629 -0.189088 -0.7218837 -0.6656799 -0.2195164 -0.6358525 -0.7399352 -0.111241 -0.9113382 -0.3963435 -0.1396902 -0.8641966 -0.4833745 -0.1140756 -0.9114532 -0.3952718 -0.1445114 -0.8635423 -0.4831262 -0.04661279 -0.9847325 -0.1677178 -0.03498601 -0.9921299 -0.1202263 -0.02998054 -0.9904795 -0.1343557 -0.02146768 -0.9883342 -0.1507799 -0.02175688 -0.9883787 -0.1504468 0.01498413 -0.9842906 -0.1759188 0.05055165 -0.9799861 -0.1925407 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 6 3 8 3 5 3 5 4 8 4 9 4 5 5 9 5 3 5 4 6 10 6 5 6 5 7 10 7 11 7 5 8 11 8 12 8 13 9 14 9 15 9 12 10 16 10 5 10 5 11 16 11 17 11 5 12 17 12 18 12 7 13 6 13 15 13 15 14 6 14 19 14 15 15 19 15 13 15 13 16 19 16 20 16 13 17 20 17 21 17 21 18 20 18 22 18 21 19 22 19 23 19 23 20 22 20 24 20 23 21 24 21 25 21 25 22 24 22 26 22 25 23 26 23 27 23 27 24 26 24 28 24 27 25 28 25 29 25 29 26 28 26 30 26 29 27 30 27 31 27 31 28 30 28 32 28 31 29 32 29 33 29 33 30 32 30 34 30 33 31 34 31 35 31 35 32 34 32 18 32 35 33 18 33 2 33 2 34 18 34 17 34 17 35 0 35 2 35 36 36 37 36 38 36 38 37 39 37 36 37 36 38 39 38 40 38 36 39 40 39 41 39 41 40 40 40 42 40 41 41 42 41 43 41 43 42 42 42 44 42 43 43 44 43 45 43 45 44 44 44 46 44 45 45 46 45 47 45 48 46 49 46 50 46 48 47 50 47 51 47 51 48 50 48 38 48 51 49 38 49 52 49 52 50 38 50 37 50 52 51 37 51 53 51 54 52 49 52 55 52 55 53 49 53 48 53 56 54 57 54 58 54 12 55 11 55 59 55 4 56 3 56 60 56 9 57 8 57 61 57 62 58 63 58 64 58 65 59 62 59 66 59 66 60 62 60 64 60 66 61 64 61 67 61 67 62 64 62 68 62 69 63 70 63 71 63 71 64 70 64 72 64 71 65 72 65 73 65 74 66 75 66 76 66 76 67 75 67 77 67 78 68 79 68 75 68 75 69 79 69 80 69 75 70 80 70 77 70 77 71 80 71 81 71 82 72 83 72 81 72 81 73 83 73 84 73 81 74 84 74 77 74 9 75 61 75 3 75 4 76 60 76 10 76 16 77 85 77 17 77 17 78 85 78 86 78 86 79 0 79 17 79 0 80 86 80 1 80 87 81 88 81 89 81 90 82 91 82 85 82 85 83 91 83 92 83 85 84 92 84 86 84 93 85 94 85 95 85 95 86 94 86 96 86 95 87 96 87 90 87 90 88 96 88 97 88 90 89 97 89 91 89 98 90 99 90 100 90 101 91 89 91 98 91 98 92 89 92 88 92 98 93 88 93 99 93 16 94 12 94 85 94 85 95 12 95 59 95 85 96 59 96 90 96 90 97 59 97 102 97 90 98 102 98 95 98 95 99 102 99 103 99 104 100 101 100 105 100 105 101 101 101 98 101 105 102 98 102 106 102 106 103 98 103 100 103 106 104 100 104 93 104 107 105 56 105 108 105 108 106 56 106 58 106 108 107 58 107 109 107 109 108 58 108 110 108 11 109 10 109 59 109 59 110 10 110 60 110 59 111 60 111 102 111 102 112 60 112 111 112 102 113 111 113 103 113 103 114 111 114 112 114 93 115 95 115 106 115 106 116 95 116 103 116 106 117 103 117 105 117 105 118 103 118 112 118 105 119 112 119 104 119 104 120 112 120 113 120 104 121 113 121 114 121 3 122 61 122 60 122 60 123 61 123 115 123 60 124 115 124 111 124 111 125 115 125 116 125 111 126 116 126 112 126 112 127 116 127 117 127 112 128 117 128 113 128 74 129 69 129 75 129 75 130 69 130 71 130 75 131 71 131 118 131 63 132 119 132 64 132 64 133 119 133 120 133 64 134 120 134 89 134 89 135 120 135 121 135 89 136 121 136 87 136 122 137 123 137 118 137 118 138 123 138 124 138 118 139 124 139 75 139 75 140 124 140 125 140 75 141 125 141 78 141 57 142 122 142 58 142 58 143 122 143 118 143 58 144 118 144 110 144 110 145 118 145 71 145 110 146 71 146 126 146 126 147 71 147 73 147 126 148 73 148 127 148 127 149 68 149 126 149 126 150 68 150 64 150 126 151 64 151 110 151 110 152 64 152 89 152 110 153 89 153 109 153 109 154 89 154 101 154 109 155 101 155 108 155 108 156 101 156 104 156 108 157 104 157 107 157 107 158 104 158 114 158 128 159 129 159 130 159 130 160 129 160 131 160 130 161 131 161 132 161 132 162 131 162 133 162 134 163 135 163 136 163 133 164 137 164 132 164 132 165 137 165 138 165 132 166 138 166 139 166 139 167 138 167 134 167 139 168 134 168 140 168 140 169 134 169 136 169 141 170 142 170 143 170 143 171 142 171 144 171 143 172 144 172 145 172 146 173 147 173 148 173 148 174 147 174 149 174 148 175 149 175 150 175 145 176 151 176 143 176 143 177 151 177 152 177 143 178 152 178 148 178 148 179 152 179 153 179 148 180 153 180 146 180 154 181 155 181 156 181 156 182 155 182 148 182 156 183 148 183 157 183 157 184 148 184 150 184 158 185 159 185 160 185 161 186 162 186 160 186 160 187 162 187 163 187 160 188 163 188 158 188 164 189 165 189 166 189 166 190 165 190 167 190 166 191 167 191 168 191 169 192 170 192 171 192 172 193 173 193 174 193 168 194 167 194 175 194 168 195 175 195 173 195 176 196 177 196 178 196 178 197 177 197 179 197 178 198 179 198 180 198 180 199 179 199 181 199 180 200 181 200 174 200 174 201 181 201 182 201 174 202 182 202 172 202 141 203 183 203 184 203 184 204 183 204 185 204 186 205 187 205 188 205 188 206 187 206 189 206 190 207 191 207 189 207 189 208 191 208 192 208 189 209 192 209 188 209 193 210 194 210 190 210 190 211 194 211 195 211 190 212 195 212 191 212 164 213 196 213 165 213 165 214 196 214 197 214 165 215 197 215 193 215 193 216 197 216 198 216 193 217 198 217 194 217 169 218 171 218 187 218 199 219 200 219 201 219 199 220 201 220 202 220 202 221 201 221 203 221 202 222 203 222 204 222 203 223 205 223 204 223 204 224 205 224 206 224 204 225 206 225 207 225 206 226 208 226 207 226 207 227 208 227 209 227 207 228 209 228 210 228 210 229 209 229 211 229 210 230 211 230 212 230 211 231 213 231 212 231 212 232 213 232 214 232 212 233 214 233 215 233 214 234 216 234 215 234 215 235 216 235 217 235 215 236 217 236 218 236 218 237 217 237 219 237 218 238 219 238 220 238 221 239 222 239 223 239 223 240 222 240 220 240 223 241 220 241 224 241 224 242 220 242 219 242 222 243 225 243 220 243 220 244 225 244 226 244 220 245 226 245 218 245 218 246 226 246 227 246 218 247 227 247 215 247 215 248 227 248 228 248 215 249 228 249 212 249 212 250 228 250 229 250 212 251 229 251 210 251 210 252 229 252 230 252 210 253 230 253 207 253 207 254 230 254 231 254 207 255 231 255 204 255 204 256 231 256 232 256 204 257 232 257 202 257 202 258 232 258 178 258 202 259 178 259 199 259 199 260 178 260 180 260 173 261 175 261 174 261 174 262 175 262 233 262 174 263 233 263 180 263 180 264 233 264 171 264 180 265 171 265 199 265 199 266 171 266 170 266 199 267 170 267 200 267 225 268 234 268 226 268 226 269 234 269 235 269 226 270 235 270 227 270 227 271 235 271 236 271 227 272 236 272 228 272 228 273 236 273 237 273 228 274 237 274 229 274 229 275 237 275 238 275 229 276 238 276 230 276 230 277 238 277 239 277 230 278 239 278 231 278 231 279 239 279 240 279 231 280 240 280 232 280 232 281 240 281 241 281 232 282 241 282 178 282 178 283 241 283 184 283 178 284 184 284 176 284 176 285 184 285 185 285 187 286 171 286 189 286 189 287 171 287 233 287 189 288 233 288 190 288 190 289 233 289 175 289 190 290 175 290 193 290 193 291 175 291 167 291 193 292 167 292 165 292 234 293 149 293 235 293 235 294 149 294 147 294 235 295 147 295 236 295 236 296 147 296 146 296 236 297 146 297 237 297 237 298 146 298 153 298 237 299 153 299 238 299 238 300 153 300 152 300 238 301 152 301 239 301 239 302 152 302 151 302 239 303 151 303 240 303 240 304 151 304 145 304 240 305 145 305 241 305 241 306 145 306 144 306 241 307 144 307 184 307 184 308 144 308 142 308 184 309 142 309 141 309 162 310 242 310 243 310 244 311 245 311 246 311 246 312 245 312 247 312 246 313 247 313 248 313 162 314 243 314 163 314 163 315 243 315 249 315 163 316 249 316 246 316 246 317 249 317 250 317 246 318 250 318 244 318 251 319 252 319 253 319 254 320 255 320 256 320 256 321 255 321 257 321 256 322 257 322 258 322 259 323 260 323 261 323 261 324 260 324 262 324 261 325 262 325 263 325 259 326 264 326 260 326 260 327 264 327 265 327 260 328 265 328 254 328 254 329 265 329 266 329 254 330 266 330 255 330 258 331 257 331 267 331 267 332 257 332 268 332 267 333 268 333 269 333 269 334 268 334 270 334 269 335 270 335 271 335 270 336 272 336 271 336 271 337 272 337 273 337 271 338 273 338 274 338 274 339 273 339 275 339 273 340 276 340 275 340 275 341 276 341 277 341 275 342 277 342 278 342 278 343 277 343 279 343 279 344 277 344 280 344 279 345 280 345 281 345 281 346 280 346 282 346 281 347 282 347 283 347 283 348 282 348 284 348 283 349 284 349 285 349 284 350 286 350 285 350 285 351 286 351 287 351 285 352 287 352 288 352 288 353 287 353 289 353 288 354 289 354 290 354 291 355 292 355 293 355 293 356 292 356 294 356 293 357 294 357 295 357 290 358 289 358 296 358 296 359 289 359 297 359 296 360 297 360 298 360 298 361 297 361 299 361 298 362 299 362 300 362 300 363 299 363 301 363 300 364 301 364 302 364 302 365 301 365 303 365 302 366 303 366 304 366 304 367 303 367 305 367 304 368 305 368 306 368 306 369 305 369 307 369 306 370 307 370 308 370 308 371 307 371 309 371 308 372 309 372 310 372 295 373 311 373 293 373 293 374 311 374 312 374 293 375 312 375 309 375 309 376 312 376 313 376 309 377 313 377 310 377 291 378 293 378 314 378 314 379 293 379 315 379 314 380 315 380 316 380 317 381 318 381 315 381 315 382 318 382 319 382 315 383 319 383 316 383 320 384 321 384 322 384 322 385 321 385 323 385 322 386 323 386 324 386 324 387 325 387 322 387 322 388 325 388 326 388 322 389 326 389 327 389 327 390 326 390 328 390 327 391 328 391 329 391 329 392 328 392 318 392 329 393 318 393 330 393 330 394 318 394 317 394 331 395 251 395 332 395 332 396 251 396 253 396 332 397 253 397 333 397 333 398 253 398 334 398 333 399 334 399 335 399 335 400 334 400 336 400 335 401 336 401 337 401 337 402 336 402 338 402 337 403 338 403 339 403 339 404 338 404 340 404 339 405 340 405 341 405 341 406 340 406 342 406 341 407 342 407 343 407 343 408 342 408 344 408 343 409 344 409 345 409 345 410 344 410 346 410 345 411 346 411 322 411 322 412 346 412 347 412 322 413 347 413 320 413 348 414 349 414 350 414 351 415 352 415 353 415 353 416 352 416 348 416 353 417 348 417 354 417 354 418 348 418 350 418 351 419 355 419 352 419 352 420 355 420 356 420 352 421 356 421 357 421 357 422 358 422 352 422 352 423 358 423 359 423 352 424 359 424 360 424 360 425 359 425 361 425 360 426 361 426 362 426 363 427 364 427 365 427 365 428 364 428 366 428 365 429 366 429 367 429 367 430 368 430 365 430 365 431 368 431 369 431 365 432 369 432 370 432 363 433 365 433 361 433 361 434 365 434 371 434 361 435 371 435 362 435 372 436 373 436 374 436 374 437 373 437 352 437 374 438 352 438 375 438 375 439 352 439 360 439 376 440 377 440 378 440 376 441 378 441 379 441 380 442 381 442 382 442 380 443 382 443 383 443 383 444 382 444 384 444 383 445 384 445 385 445 385 446 384 446 386 446 386 447 384 447 387 447 386 448 387 448 388 448 388 449 387 449 389 449 388 450 389 450 378 450 378 451 389 451 390 451 378 452 390 452 379 452 377 453 391 453 378 453 378 454 391 454 392 454 378 455 392 455 372 455 372 456 392 456 393 456 372 457 393 457 373 457 391 458 394 458 392 458 392 459 394 459 395 459 392 460 395 460 396 460 396 461 397 461 392 461 392 462 397 462 398 462 392 463 398 463 399 463 399 464 398 464 400 464 400 465 398 465 401 465 400 466 401 466 402 466 403 467 404 467 402 467 402 468 404 468 405 468 402 469 405 469 400 469 406 470 221 470 407 470 407 471 221 471 223 471 407 472 223 472 408 472 408 473 223 473 224 473 408 474 224 474 409 474 409 475 224 475 410 475 410 476 224 476 219 476 410 477 219 477 411 477 411 478 219 478 217 478 411 479 217 479 412 479 413 480 414 480 216 480 216 481 414 481 415 481 216 482 415 482 217 482 217 483 415 483 416 483 217 484 416 484 412 484 211 485 209 485 417 485 216 486 214 486 413 486 413 487 214 487 213 487 413 488 213 488 418 488 418 489 213 489 211 489 418 490 211 490 419 490 419 491 211 491 417 491 206 492 420 492 208 492 208 493 420 493 421 493 208 494 421 494 209 494 209 495 421 495 422 495 209 496 422 496 417 496 203 497 423 497 205 497 205 498 423 498 424 498 205 499 424 499 206 499 206 500 424 500 425 500 206 501 425 501 420 501 200 502 426 502 201 502 201 503 426 503 427 503 201 504 427 504 203 504 203 505 427 505 428 505 203 506 428 506 423 506 186 507 429 507 187 507 187 508 429 508 430 508 430 509 431 509 187 509 187 510 431 510 432 510 187 511 432 511 169 511 169 512 432 512 433 512 169 513 433 513 170 513 170 514 433 514 434 514 170 515 434 515 200 515 200 516 434 516 435 516 200 517 435 517 426 517 436 518 437 518 438 518 438 519 437 519 439 519 437 520 440 520 439 520 439 521 440 521 441 521 442 522 443 522 444 522 444 523 445 523 446 523 446 524 447 524 444 524 444 525 447 525 448 525 444 526 448 526 449 526 450 527 451 527 452 527 449 528 453 528 444 528 444 529 453 529 454 529 444 530 454 530 450 530 450 531 452 531 444 531 444 532 452 532 455 532 444 533 455 533 456 533 456 534 457 534 444 534 444 535 457 535 458 535 444 536 458 536 442 536 459 537 460 537 461 537 461 538 460 538 462 538 461 539 462 539 463 539 463 540 462 540 464 540 459 541 465 541 460 541 460 542 465 542 466 542 460 543 466 543 444 543 444 544 466 544 467 544 444 545 467 545 445 545 468 546 469 546 470 546 471 547 468 547 472 547 472 548 468 548 470 548 472 549 470 549 473 549 471 550 474 550 468 550 468 551 474 551 475 551 468 552 475 552 476 552 476 553 477 553 468 553 468 554 477 554 478 554 468 555 478 555 479 555 479 556 478 556 480 556 479 557 480 557 481 557 481 558 482 558 479 558 479 559 482 559 483 559 479 560 483 560 484 560 484 561 485 561 479 561 479 562 485 562 486 562 479 563 486 563 487 563 487 564 486 564 488 564 487 565 488 565 462 565 462 566 488 566 489 566 462 567 489 567 464 567 243 568 242 568 490 568 491 569 492 569 490 569 490 570 492 570 493 570 490 571 493 571 494 571 494 572 495 572 490 572 490 573 495 573 496 573 490 574 496 574 243 574 243 575 496 575 249 575 491 576 490 576 497 576 497 577 490 577 498 577 497 578 498 578 499 578 500 579 498 579 501 579 501 580 498 580 502 580 503 581 504 581 500 581 500 582 504 582 505 582 505 583 506 583 500 583 500 584 506 584 507 584 500 585 507 585 498 585 498 586 507 586 508 586 498 587 508 587 499 587 509 588 323 588 321 588 404 589 403 589 509 589 348 590 253 590 349 590 349 591 253 591 252 591 509 592 321 592 404 592 404 593 321 593 320 593 404 594 320 594 405 594 320 595 347 595 405 595 405 596 347 596 346 596 405 597 346 597 400 597 400 598 346 598 399 598 346 599 344 599 399 599 399 600 344 600 342 600 399 601 342 601 392 601 392 602 342 602 393 602 342 603 340 603 393 603 393 604 340 604 338 604 393 605 338 605 373 605 373 606 338 606 336 606 373 607 336 607 352 607 352 608 336 608 348 608 348 609 336 609 334 609 348 610 334 610 253 610 510 611 511 611 512 611 513 612 514 612 515 612 516 613 517 613 518 613 519 614 520 614 521 614 522 615 523 615 524 615 524 616 523 616 525 616 524 617 525 617 526 617 527 618 522 618 528 618 528 619 522 619 524 619 528 620 524 620 529 620 529 621 524 621 530 621 531 622 532 622 533 622 534 623 535 623 536 623 536 624 535 624 537 624 536 625 538 625 539 625 534 626 536 626 540 626 540 627 536 627 539 627 540 628 539 628 541 628 521 629 520 629 542 629 520 630 543 630 542 630 542 631 543 631 544 631 542 632 544 632 536 632 536 633 544 633 545 633 536 634 545 634 538 634 519 635 521 635 546 635 546 636 521 636 547 636 546 637 547 637 548 637 548 638 547 638 549 638 548 639 549 639 550 639 518 640 517 640 549 640 549 641 517 641 551 641 549 642 551 642 550 642 516 643 518 643 552 643 552 644 518 644 553 644 552 645 553 645 554 645 554 646 553 646 555 646 554 647 555 647 556 647 556 648 555 648 557 648 557 649 555 649 558 649 557 650 558 650 559 650 515 651 514 651 558 651 558 652 514 652 560 652 558 653 560 653 559 653 513 654 515 654 561 654 561 655 515 655 562 655 561 656 562 656 563 656 563 657 562 657 564 657 563 658 564 658 565 658 565 659 564 659 566 659 566 660 564 660 567 660 566 661 567 661 568 661 512 662 511 662 569 662 511 663 570 663 569 663 569 664 570 664 571 664 569 665 571 665 567 665 567 666 571 666 572 666 567 667 572 667 568 667 510 668 512 668 573 668 573 669 512 669 574 669 573 670 574 670 575 670 575 671 574 671 576 671 575 672 576 672 577 672 578 673 579 673 580 673 580 674 581 674 578 674 578 675 581 675 582 675 578 676 582 676 576 676 576 677 582 677 583 677 576 678 583 678 577 678 525 679 584 679 526 679 526 680 584 680 585 680 526 681 585 681 586 681 586 682 585 682 587 682 586 683 587 683 579 683 579 684 587 684 588 684 579 685 588 685 580 685 589 686 590 686 530 686 590 687 589 687 266 687 272 688 270 688 591 688 591 689 270 689 268 689 591 690 268 690 592 690 592 691 268 691 257 691 592 692 257 692 589 692 589 693 257 693 255 693 589 694 255 694 266 694 272 695 591 695 273 695 273 696 591 696 593 696 273 697 593 697 276 697 276 698 593 698 594 698 276 699 594 699 277 699 277 700 594 700 595 700 277 701 595 701 280 701 280 702 595 702 282 702 282 703 595 703 596 703 282 704 596 704 284 704 284 705 596 705 597 705 284 706 597 706 286 706 286 707 597 707 287 707 287 708 597 708 598 708 287 709 598 709 289 709 599 710 303 710 600 710 600 711 303 711 301 711 600 712 301 712 601 712 601 713 301 713 299 713 601 714 299 714 598 714 598 715 299 715 297 715 598 716 297 716 289 716 602 717 307 717 599 717 599 718 307 718 305 718 599 719 305 719 303 719 603 720 315 720 604 720 604 721 315 721 293 721 604 722 293 722 602 722 602 723 293 723 309 723 602 724 309 724 307 724 605 725 329 725 606 725 606 726 329 726 330 726 606 727 330 727 603 727 603 728 330 728 317 728 603 729 317 729 315 729 607 730 322 730 605 730 605 731 322 731 327 731 605 732 327 732 329 732 341 733 343 733 607 733 607 734 343 734 345 734 607 735 345 735 322 735 607 736 608 736 341 736 341 737 608 737 609 737 341 738 609 738 339 738 339 739 609 739 337 739 530 740 524 740 589 740 589 741 524 741 526 741 589 742 526 742 592 742 592 743 526 743 586 743 592 744 586 744 591 744 591 745 586 745 579 745 591 746 579 746 593 746 593 747 579 747 578 747 593 748 578 748 594 748 594 749 578 749 576 749 594 750 576 750 595 750 595 751 576 751 574 751 595 752 574 752 596 752 596 753 574 753 512 753 596 754 512 754 597 754 597 755 512 755 569 755 597 756 569 756 598 756 598 757 569 757 567 757 598 758 567 758 601 758 601 759 567 759 564 759 601 760 564 760 600 760 600 761 564 761 562 761 600 762 562 762 599 762 599 763 562 763 515 763 599 764 515 764 602 764 602 765 515 765 558 765 602 766 558 766 604 766 604 767 558 767 555 767 604 768 555 768 603 768 603 769 555 769 553 769 603 770 553 770 606 770 606 771 553 771 518 771 606 772 518 772 605 772 605 773 518 773 549 773 605 774 549 774 607 774 607 775 549 775 547 775 607 776 547 776 608 776 608 777 547 777 521 777 608 778 521 778 609 778 609 779 521 779 542 779 609 780 542 780 610 780 610 781 542 781 536 781 610 782 536 782 531 782 531 783 536 783 537 783 531 784 537 784 532 784 337 785 609 785 335 785 335 786 609 786 610 786 335 787 610 787 333 787 333 788 610 788 531 788 333 789 531 789 332 789 332 790 531 790 533 790 332 791 533 791 331 791 611 792 612 792 613 792 614 793 615 793 616 793 617 794 618 794 619 794 620 795 621 795 622 795 623 796 624 796 620 796 623 797 620 797 625 797 626 798 627 798 628 798 628 799 627 799 629 799 630 800 631 800 622 800 622 801 631 801 632 801 632 802 633 802 622 802 622 803 633 803 634 803 622 804 634 804 635 804 635 805 636 805 622 805 622 806 636 806 637 806 622 807 637 807 638 807 638 808 639 808 622 808 622 809 639 809 640 809 622 810 640 810 620 810 620 811 640 811 641 811 620 812 641 812 625 812 642 813 643 813 628 813 643 814 644 814 628 814 628 815 644 815 645 815 628 816 645 816 626 816 646 817 647 817 648 817 648 818 647 818 649 818 650 819 651 819 652 819 653 820 654 820 655 820 650 821 652 821 655 821 655 822 652 822 656 822 655 823 656 823 653 823 618 824 657 824 658 824 658 825 657 825 659 825 658 826 659 826 660 826 661 827 662 827 663 827 663 828 662 828 664 828 663 829 664 829 665 829 666 830 667 830 668 830 669 831 670 831 671 831 671 832 672 832 669 832 669 833 672 833 673 833 669 834 673 834 674 834 675 835 676 835 668 835 674 836 677 836 669 836 669 837 677 837 678 837 669 838 678 838 679 838 675 839 668 839 680 839 676 840 681 840 668 840 668 841 681 841 682 841 668 842 682 842 666 842 683 843 684 843 669 843 669 844 684 844 685 844 669 845 685 845 670 845 670 846 685 846 686 846 686 847 687 847 688 847 688 848 689 848 686 848 686 849 689 849 690 849 686 850 690 850 670 850 691 851 692 851 693 851 692 852 694 852 693 852 693 853 694 853 695 853 693 854 695 854 696 854 696 855 697 855 693 855 693 856 697 856 698 856 693 857 698 857 669 857 669 858 698 858 699 858 669 859 699 859 683 859 700 860 701 860 702 860 621 861 703 861 622 861 622 862 703 862 704 862 622 863 704 863 702 863 702 864 704 864 705 864 702 865 705 865 700 865 701 866 706 866 702 866 702 867 706 867 707 867 702 868 707 868 708 868 709 869 710 869 655 869 655 870 710 870 711 870 655 871 711 871 650 871 712 872 713 872 709 872 709 873 713 873 714 873 709 874 714 874 710 874 715 875 716 875 712 875 712 876 716 876 717 876 712 877 717 877 713 877 718 878 719 878 715 878 715 879 719 879 720 879 715 880 720 880 716 880 721 881 722 881 718 881 718 882 722 882 723 882 718 883 723 883 719 883 724 884 725 884 721 884 721 885 725 885 726 885 721 886 726 886 722 886 613 887 727 887 611 887 611 888 727 888 728 888 611 889 728 889 724 889 724 890 728 890 729 890 724 891 729 891 725 891 730 892 731 892 732 892 732 893 733 893 730 893 730 894 733 894 734 894 730 895 734 895 612 895 612 896 734 896 735 896 612 897 735 897 613 897 736 898 737 898 738 898 738 899 739 899 736 899 736 900 739 900 740 900 736 901 740 901 731 901 731 902 740 902 741 902 731 903 741 903 732 903 742 904 743 904 744 904 744 905 745 905 742 905 742 906 745 906 746 906 742 907 746 907 737 907 737 908 746 908 747 908 737 909 747 909 738 909 618 910 658 910 619 910 619 911 658 911 748 911 619 912 748 912 743 912 743 913 748 913 749 913 743 914 749 914 744 914 665 915 617 915 663 915 663 916 617 916 619 916 663 917 619 917 750 917 750 918 619 918 743 918 750 919 743 919 751 919 751 920 743 920 742 920 751 921 742 921 752 921 752 922 742 922 737 922 752 923 737 923 753 923 753 924 737 924 736 924 753 925 736 925 754 925 754 926 736 926 731 926 754 927 731 927 755 927 755 928 731 928 730 928 755 929 730 929 756 929 756 930 730 930 612 930 756 931 612 931 757 931 757 932 612 932 611 932 757 933 611 933 758 933 758 934 611 934 724 934 758 935 724 935 759 935 759 936 724 936 721 936 759 937 721 937 760 937 760 938 721 938 718 938 760 939 718 939 761 939 761 940 718 940 715 940 761 941 715 941 762 941 762 942 715 942 712 942 762 943 712 943 763 943 763 944 712 944 709 944 763 945 709 945 648 945 648 946 709 946 655 946 648 947 655 947 646 947 646 948 655 948 654 948 667 949 661 949 668 949 668 950 661 950 663 950 668 951 663 951 764 951 764 952 663 952 750 952 764 953 750 953 765 953 765 954 750 954 751 954 765 955 751 955 766 955 766 956 751 956 752 956 766 957 752 957 767 957 767 958 752 958 753 958 767 959 753 959 768 959 768 960 753 960 754 960 768 961 754 961 769 961 769 962 754 962 755 962 769 963 755 963 770 963 770 964 755 964 756 964 770 965 756 965 771 965 771 966 756 966 757 966 771 967 757 967 772 967 772 968 757 968 758 968 772 969 758 969 773 969 773 970 758 970 759 970 773 971 759 971 774 971 774 972 759 972 760 972 774 973 760 973 775 973 775 974 760 974 761 974 775 975 761 975 776 975 776 976 761 976 762 976 776 977 762 977 777 977 777 978 762 978 763 978 777 979 763 979 628 979 628 980 763 980 648 980 628 981 648 981 642 981 642 982 648 982 649 982 679 983 680 983 669 983 669 984 680 984 668 984 669 985 668 985 693 985 693 986 668 986 764 986 693 987 764 987 778 987 778 988 764 988 765 988 778 989 765 989 779 989 779 990 765 990 766 990 779 991 766 991 780 991 780 992 766 992 767 992 780 993 767 993 781 993 781 994 767 994 768 994 781 995 768 995 782 995 782 996 768 996 769 996 782 997 769 997 783 997 783 998 769 998 770 998 783 999 770 999 784 999 784 1000 770 1000 771 1000 784 1001 771 1001 785 1001 785 1002 771 1002 772 1002 785 1003 772 1003 786 1003 786 1004 772 1004 773 1004 786 1005 773 1005 787 1005 787 1006 773 1006 774 1006 787 1007 774 1007 788 1007 788 1008 774 1008 775 1008 788 1009 775 1009 789 1009 789 1010 775 1010 776 1010 789 1011 776 1011 702 1011 702 1012 776 1012 777 1012 702 1013 777 1013 622 1013 622 1014 777 1014 628 1014 622 1015 628 1015 630 1015 630 1016 628 1016 629 1016 790 1017 691 1017 791 1017 791 1018 691 1018 693 1018 791 1019 693 1019 792 1019 792 1020 693 1020 778 1020 792 1021 778 1021 793 1021 793 1022 778 1022 779 1022 793 1023 779 1023 794 1023 794 1024 779 1024 780 1024 794 1025 780 1025 795 1025 795 1026 780 1026 781 1026 795 1027 781 1027 796 1027 796 1028 781 1028 782 1028 796 1029 782 1029 797 1029 797 1030 782 1030 783 1030 797 1031 783 1031 798 1031 798 1032 783 1032 784 1032 798 1033 784 1033 799 1033 799 1034 784 1034 785 1034 799 1035 785 1035 800 1035 800 1036 785 1036 786 1036 800 1037 786 1037 801 1037 801 1038 786 1038 787 1038 801 1039 787 1039 802 1039 802 1040 787 1040 788 1040 802 1041 788 1041 803 1041 803 1042 788 1042 789 1042 803 1043 789 1043 616 1043 616 1044 789 1044 702 1044 616 1045 702 1045 614 1045 614 1046 702 1046 708 1046 436 1047 438 1047 804 1047 804 1048 438 1048 805 1048 804 1049 805 1049 806 1049 806 1050 805 1050 807 1050 807 1051 805 1051 808 1051 807 1052 808 1052 809 1052 809 1053 808 1053 810 1053 809 1054 810 1054 811 1054 812 1055 813 1055 814 1055 814 1056 813 1056 815 1056 814 1057 815 1057 810 1057 810 1058 815 1058 816 1058 810 1059 816 1059 811 1059 155 1060 154 1060 812 1060 812 1061 154 1061 817 1061 817 1062 818 1062 812 1062 812 1063 818 1063 819 1063 812 1064 819 1064 813 1064 584 1065 525 1065 820 1065 587 1066 585 1066 821 1066 580 1067 588 1067 822 1067 823 1068 824 1068 825 1068 826 1069 827 1069 828 1069 829 1070 541 1070 539 1070 827 1071 830 1071 831 1071 831 1072 830 1072 832 1072 831 1073 832 1073 829 1073 826 1074 828 1074 824 1074 829 1075 539 1075 831 1075 831 1076 539 1076 538 1076 831 1077 538 1077 833 1077 833 1078 538 1078 545 1078 833 1079 545 1079 834 1079 835 1080 431 1080 836 1080 836 1081 431 1081 430 1081 836 1082 430 1082 825 1082 825 1083 430 1083 429 1083 825 1084 429 1084 823 1084 545 1085 544 1085 834 1085 834 1086 544 1086 543 1086 834 1087 543 1087 837 1087 837 1088 543 1088 520 1088 434 1089 433 1089 835 1089 835 1090 433 1090 432 1090 835 1091 432 1091 431 1091 520 1092 519 1092 837 1092 837 1093 519 1093 546 1093 837 1094 546 1094 838 1094 835 1095 839 1095 434 1095 434 1096 839 1096 840 1096 434 1097 840 1097 435 1097 435 1098 840 1098 841 1098 435 1099 841 1099 426 1099 426 1100 841 1100 427 1100 546 1101 548 1101 838 1101 838 1102 548 1102 550 1102 838 1103 550 1103 842 1103 842 1104 550 1104 551 1104 842 1105 551 1105 843 1105 551 1106 517 1106 843 1106 843 1107 517 1107 516 1107 843 1108 516 1108 844 1108 844 1109 516 1109 552 1109 427 1110 841 1110 428 1110 428 1111 841 1111 845 1111 428 1112 845 1112 846 1112 425 1113 424 1113 846 1113 846 1114 424 1114 423 1114 846 1115 423 1115 428 1115 552 1116 554 1116 844 1116 844 1117 554 1117 556 1117 844 1118 556 1118 847 1118 847 1119 556 1119 557 1119 847 1120 557 1120 848 1120 557 1121 559 1121 848 1121 848 1122 559 1122 560 1122 848 1123 560 1123 849 1123 846 1124 850 1124 425 1124 425 1125 850 1125 851 1125 425 1126 851 1126 420 1126 420 1127 851 1127 852 1127 560 1128 514 1128 849 1128 849 1129 514 1129 513 1129 849 1130 513 1130 853 1130 853 1131 513 1131 561 1131 417 1132 422 1132 852 1132 852 1133 422 1133 421 1133 852 1134 421 1134 420 1134 561 1135 563 1135 853 1135 853 1136 563 1136 565 1136 853 1137 565 1137 854 1137 854 1138 565 1138 566 1138 854 1139 566 1139 855 1139 852 1140 856 1140 417 1140 417 1141 856 1141 857 1141 417 1142 857 1142 419 1142 419 1143 857 1143 858 1143 419 1144 858 1144 418 1144 418 1145 858 1145 413 1145 566 1146 568 1146 855 1146 855 1147 568 1147 572 1147 855 1148 572 1148 859 1148 572 1149 571 1149 859 1149 859 1150 571 1150 570 1150 859 1151 570 1151 860 1151 860 1152 570 1152 511 1152 413 1153 858 1153 414 1153 414 1154 858 1154 861 1154 414 1155 861 1155 862 1155 511 1156 510 1156 860 1156 860 1157 510 1157 573 1157 860 1158 573 1158 863 1158 863 1159 573 1159 575 1159 863 1160 575 1160 864 1160 575 1161 577 1161 864 1161 864 1162 577 1162 583 1162 864 1163 583 1163 865 1163 865 1164 583 1164 582 1164 827 1165 831 1165 828 1165 828 1166 831 1166 833 1166 828 1167 833 1167 866 1167 866 1168 833 1168 834 1168 866 1169 834 1169 867 1169 867 1170 834 1170 837 1170 867 1171 837 1171 868 1171 868 1172 837 1172 838 1172 868 1173 838 1173 869 1173 869 1174 838 1174 842 1174 869 1175 842 1175 870 1175 870 1176 842 1176 843 1176 870 1177 843 1177 871 1177 871 1178 843 1178 844 1178 871 1179 844 1179 872 1179 872 1180 844 1180 847 1180 872 1181 847 1181 873 1181 873 1182 847 1182 848 1182 873 1183 848 1183 874 1183 874 1184 848 1184 849 1184 874 1185 849 1185 875 1185 875 1186 849 1186 853 1186 875 1187 853 1187 876 1187 876 1188 853 1188 854 1188 876 1189 854 1189 877 1189 877 1190 854 1190 855 1190 877 1191 855 1191 878 1191 878 1192 855 1192 859 1192 878 1193 859 1193 879 1193 879 1194 859 1194 860 1194 879 1195 860 1195 880 1195 880 1196 860 1196 863 1196 880 1197 863 1197 881 1197 881 1198 863 1198 864 1198 881 1199 864 1199 882 1199 882 1200 864 1200 865 1200 882 1201 865 1201 883 1201 824 1202 828 1202 825 1202 825 1203 828 1203 866 1203 825 1204 866 1204 836 1204 836 1205 866 1205 867 1205 836 1206 867 1206 835 1206 835 1207 867 1207 868 1207 835 1208 868 1208 839 1208 839 1209 868 1209 869 1209 839 1210 869 1210 840 1210 840 1211 869 1211 870 1211 840 1212 870 1212 841 1212 841 1213 870 1213 871 1213 841 1214 871 1214 845 1214 845 1215 871 1215 872 1215 845 1216 872 1216 846 1216 846 1217 872 1217 873 1217 846 1218 873 1218 850 1218 850 1219 873 1219 874 1219 850 1220 874 1220 851 1220 851 1221 874 1221 875 1221 851 1222 875 1222 852 1222 852 1223 875 1223 876 1223 852 1224 876 1224 856 1224 856 1225 876 1225 877 1225 856 1226 877 1226 857 1226 857 1227 877 1227 878 1227 857 1228 878 1228 858 1228 858 1229 878 1229 879 1229 858 1230 879 1230 861 1230 861 1231 879 1231 880 1231 861 1232 880 1232 862 1232 862 1233 880 1233 881 1233 862 1234 881 1234 884 1234 884 1235 881 1235 882 1235 884 1236 882 1236 885 1236 885 1237 882 1237 883 1237 885 1238 883 1238 886 1238 409 1239 410 1239 886 1239 886 1240 410 1240 411 1240 886 1241 411 1241 885 1241 885 1242 411 1242 412 1242 885 1243 412 1243 884 1243 884 1244 412 1244 416 1244 884 1245 416 1245 862 1245 862 1246 416 1246 415 1246 862 1247 415 1247 414 1247 580 1248 822 1248 581 1248 408 1249 409 1249 887 1249 887 1250 409 1250 886 1250 887 1251 886 1251 888 1251 888 1252 886 1252 883 1252 888 1253 883 1253 822 1253 822 1254 883 1254 865 1254 822 1255 865 1255 581 1255 581 1256 865 1256 582 1256 407 1257 408 1257 889 1257 889 1258 408 1258 887 1258 889 1259 887 1259 890 1259 890 1260 887 1260 888 1260 890 1261 888 1261 821 1261 821 1262 888 1262 822 1262 821 1263 822 1263 587 1263 587 1264 822 1264 588 1264 406 1265 407 1265 891 1265 891 1266 407 1266 889 1266 891 1267 889 1267 892 1267 892 1268 889 1268 890 1268 892 1269 890 1269 820 1269 820 1270 890 1270 821 1270 820 1271 821 1271 584 1271 584 1272 821 1272 585 1272 487 1273 462 1273 893 1273 894 1274 895 1274 896 1274 897 1275 898 1275 899 1275 900 1276 901 1276 902 1276 902 1277 901 1277 903 1277 900 1278 902 1278 904 1278 904 1279 902 1279 905 1279 904 1280 905 1280 906 1280 906 1281 905 1281 896 1281 906 1282 896 1282 899 1282 899 1283 896 1283 895 1283 899 1284 895 1284 897 1284 907 1285 908 1285 894 1285 479 1286 902 1286 468 1286 468 1287 902 1287 903 1287 468 1288 903 1288 469 1288 894 1289 896 1289 907 1289 907 1290 896 1290 905 1290 907 1291 905 1291 909 1291 909 1292 905 1292 902 1292 909 1293 902 1293 910 1293 910 1294 902 1294 479 1294 910 1295 479 1295 487 1295 487 1296 893 1296 910 1296 910 1297 893 1297 911 1297 910 1298 911 1298 909 1298 909 1299 911 1299 912 1299 909 1300 912 1300 907 1300 907 1301 912 1301 913 1301 907 1302 913 1302 908 1302 914 1303 500 1303 501 1303 915 1304 916 1304 917 1304 916 1305 898 1305 917 1305 917 1306 898 1306 897 1306 917 1307 897 1307 895 1307 502 1308 915 1308 501 1308 501 1309 915 1309 917 1309 501 1310 917 1310 914 1310 914 1311 917 1311 895 1311 914 1312 895 1312 894 1312 918 1313 687 1313 686 1313 919 1314 920 1314 921 1314 921 1315 920 1315 918 1315 922 1316 923 1316 924 1316 924 1317 923 1317 919 1317 925 1318 926 1318 927 1318 927 1319 926 1319 928 1319 927 1320 928 1320 922 1320 929 1321 925 1321 930 1321 930 1322 925 1322 931 1322 65 1323 66 1323 932 1323 932 1324 66 1324 933 1324 932 1325 933 1325 934 1325 935 1326 936 1326 937 1326 935 1327 937 1327 938 1327 937 1328 939 1328 938 1328 938 1329 939 1329 940 1329 938 1330 940 1330 933 1330 933 1331 940 1331 941 1331 933 1332 941 1332 934 1332 936 1333 935 1333 942 1333 942 1334 935 1334 943 1334 942 1335 943 1335 944 1335 691 1336 790 1336 943 1336 943 1337 790 1337 945 1337 943 1338 945 1338 944 1338 946 1339 83 1339 947 1339 947 1340 83 1340 82 1340 947 1341 82 1341 931 1341 931 1342 82 1342 948 1342 931 1343 948 1343 930 1343 918 1344 686 1344 921 1344 921 1345 686 1345 685 1345 921 1346 685 1346 949 1346 949 1347 685 1347 684 1347 949 1348 684 1348 950 1348 950 1349 684 1349 683 1349 950 1350 683 1350 951 1350 683 1351 699 1351 951 1351 951 1352 699 1352 698 1352 951 1353 698 1353 952 1353 952 1354 698 1354 697 1354 952 1355 697 1355 953 1355 953 1356 697 1356 696 1356 953 1357 696 1357 954 1357 954 1358 696 1358 695 1358 954 1359 695 1359 955 1359 955 1360 695 1360 694 1360 955 1361 694 1361 956 1361 919 1362 921 1362 924 1362 924 1363 921 1363 949 1363 924 1364 949 1364 957 1364 957 1365 949 1365 950 1365 957 1366 950 1366 958 1366 958 1367 950 1367 951 1367 958 1368 951 1368 959 1368 959 1369 951 1369 952 1369 959 1370 952 1370 960 1370 960 1371 952 1371 953 1371 960 1372 953 1372 961 1372 961 1373 953 1373 954 1373 961 1374 954 1374 962 1374 962 1375 954 1375 955 1375 962 1376 955 1376 963 1376 963 1377 955 1377 956 1377 963 1378 956 1378 964 1378 922 1379 924 1379 927 1379 927 1380 924 1380 957 1380 927 1381 957 1381 965 1381 965 1382 957 1382 958 1382 965 1383 958 1383 966 1383 966 1384 958 1384 959 1384 966 1385 959 1385 967 1385 967 1386 959 1386 960 1386 967 1387 960 1387 968 1387 968 1388 960 1388 961 1388 968 1389 961 1389 969 1389 969 1390 961 1390 962 1390 969 1391 962 1391 970 1391 970 1392 962 1392 963 1392 970 1393 963 1393 971 1393 971 1394 963 1394 964 1394 971 1395 964 1395 972 1395 925 1396 927 1396 931 1396 931 1397 927 1397 965 1397 931 1398 965 1398 947 1398 947 1399 965 1399 966 1399 947 1400 966 1400 946 1400 946 1401 966 1401 967 1401 946 1402 967 1402 973 1402 973 1403 967 1403 968 1403 973 1404 968 1404 974 1404 974 1405 968 1405 969 1405 974 1406 969 1406 975 1406 975 1407 969 1407 970 1407 975 1408 970 1408 976 1408 976 1409 970 1409 971 1409 976 1410 971 1410 977 1410 977 1411 971 1411 972 1411 977 1412 972 1412 978 1412 127 1413 73 1413 978 1413 978 1414 73 1414 72 1414 978 1415 72 1415 977 1415 977 1416 72 1416 70 1416 977 1417 70 1417 976 1417 976 1418 70 1418 69 1418 976 1419 69 1419 975 1419 975 1420 69 1420 74 1420 975 1421 74 1421 974 1421 974 1422 74 1422 76 1422 974 1423 76 1423 973 1423 973 1424 76 1424 77 1424 973 1425 77 1425 946 1425 946 1426 77 1426 84 1426 946 1427 84 1427 83 1427 979 1428 67 1428 68 1428 68 1429 127 1429 979 1429 979 1430 127 1430 978 1430 979 1431 978 1431 980 1431 980 1432 978 1432 972 1432 980 1433 972 1433 981 1433 981 1434 972 1434 964 1434 981 1435 964 1435 982 1435 982 1436 964 1436 956 1436 982 1437 956 1437 692 1437 692 1438 956 1438 694 1438 66 1439 67 1439 933 1439 933 1440 67 1440 979 1440 933 1441 979 1441 938 1441 938 1442 979 1442 980 1442 938 1443 980 1443 935 1443 935 1444 980 1444 981 1444 935 1445 981 1445 943 1445 943 1446 981 1446 982 1446 943 1447 982 1447 691 1447 691 1448 982 1448 692 1448 983 1449 984 1449 985 1449 983 1450 985 1450 986 1450 987 1451 988 1451 989 1451 984 1452 987 1452 985 1452 985 1453 987 1453 989 1453 985 1454 989 1454 990 1454 991 1455 992 1455 993 1455 993 1456 992 1456 994 1456 993 1457 994 1457 995 1457 996 1458 997 1458 166 1458 166 1459 168 1459 996 1459 996 1460 168 1460 173 1460 996 1461 173 1461 172 1461 172 1462 182 1462 996 1462 996 1463 182 1463 181 1463 996 1464 181 1464 179 1464 989 1465 998 1465 990 1465 990 1466 998 1466 999 1466 990 1467 999 1467 996 1467 996 1468 999 1468 1000 1468 996 1469 1000 1469 1001 1469 1001 1470 1002 1470 996 1470 996 1471 1002 1471 1003 1471 996 1472 1003 1472 1004 1472 1005 1473 997 1473 1006 1473 1006 1474 997 1474 996 1474 1006 1475 996 1475 1007 1475 1007 1476 996 1476 1004 1476 986 1477 985 1477 995 1477 995 1478 985 1478 1008 1478 995 1479 1008 1479 993 1479 993 1480 1008 1480 1009 1480 993 1481 1009 1481 1010 1481 1010 1482 1009 1482 1011 1482 1010 1483 1011 1483 1012 1483 1012 1484 1011 1484 1013 1484 1012 1485 1013 1485 1014 1485 1014 1486 1013 1486 1015 1486 1014 1487 1015 1487 1016 1487 1016 1488 1015 1488 1017 1488 1016 1489 1017 1489 1018 1489 1018 1490 1017 1490 1019 1490 1018 1491 1019 1491 1020 1491 1020 1492 1019 1492 143 1492 1020 1493 143 1493 148 1493 1021 1494 1022 1494 1023 1494 984 1495 983 1495 1024 1495 1025 1496 1026 1496 1027 1496 1027 1497 1026 1497 1028 1497 1027 1498 1028 1498 1029 1498 1029 1499 1028 1499 370 1499 1029 1500 370 1500 1030 1500 1031 1501 1032 1501 1033 1501 1032 1502 1034 1502 1033 1502 1033 1503 1034 1503 1035 1503 1033 1504 1035 1504 1036 1504 1033 1505 1025 1505 1031 1505 1031 1506 1025 1506 1027 1506 1031 1507 1027 1507 1037 1507 1037 1508 1027 1508 1038 1508 1039 1509 1040 1509 1029 1509 1029 1510 1040 1510 1041 1510 1041 1511 1042 1511 1029 1511 1029 1512 1042 1512 1043 1512 1029 1513 1043 1513 1027 1513 1027 1514 1043 1514 1044 1514 1027 1515 1044 1515 1038 1515 1045 1516 1046 1516 1047 1516 1047 1517 1046 1517 1048 1517 1047 1518 1048 1518 1049 1518 986 1519 995 1519 1050 1519 1050 1520 995 1520 994 1520 1050 1521 994 1521 1051 1521 1051 1522 994 1522 992 1522 1051 1523 992 1523 991 1523 984 1524 1024 1524 987 1524 1052 1525 1053 1525 1054 1525 1054 1526 1053 1526 1055 1526 1054 1527 1055 1527 1056 1527 1056 1528 1055 1528 1057 1528 1056 1529 1057 1529 1058 1529 1058 1530 1057 1530 1059 1530 1059 1531 1057 1531 1060 1531 1059 1532 1060 1532 1061 1532 1061 1533 1060 1533 1062 1533 1062 1534 1060 1534 1063 1534 1062 1535 1063 1535 1064 1535 1064 1536 1063 1536 1065 1536 1064 1537 1065 1537 1066 1537 364 1538 363 1538 1067 1538 1067 1539 363 1539 1068 1539 1067 1540 1068 1540 1069 1540 1069 1541 1068 1541 1070 1541 1069 1542 1070 1542 1065 1542 1065 1543 1070 1543 1071 1543 1065 1544 1071 1544 1066 1544 369 1545 368 1545 1072 1545 1072 1546 368 1546 367 1546 1072 1547 367 1547 1067 1547 1067 1548 367 1548 366 1548 1067 1549 366 1549 364 1549 1023 1550 1022 1550 1073 1550 1022 1551 1074 1551 1073 1551 1073 1552 1074 1552 1075 1552 1073 1553 1075 1553 1076 1553 1076 1554 1075 1554 1077 1554 1051 1555 1078 1555 1050 1555 1050 1556 1078 1556 1079 1556 1050 1557 1079 1557 1080 1557 1080 1558 1079 1558 1081 1558 1082 1559 1083 1559 1084 1559 1084 1560 1083 1560 1080 1560 1084 1561 1080 1561 1085 1561 1085 1562 1080 1562 1081 1562 1082 1563 1086 1563 1083 1563 1083 1564 1086 1564 1087 1564 1083 1565 1087 1565 1088 1565 1088 1566 1087 1566 1089 1566 1088 1567 1089 1567 1023 1567 1023 1568 1089 1568 1090 1568 1023 1569 1090 1569 1021 1569 1091 1570 1092 1570 1093 1570 1093 1571 1092 1571 1094 1571 1093 1572 1094 1572 1047 1572 1047 1573 1094 1573 1095 1573 1047 1574 1095 1574 1045 1574 983 1575 986 1575 1024 1575 1024 1576 986 1576 1050 1576 1024 1577 1050 1577 1096 1577 1096 1578 1050 1578 1080 1578 1096 1579 1080 1579 1097 1579 1097 1580 1080 1580 1083 1580 1097 1581 1083 1581 1098 1581 1098 1582 1083 1582 1088 1582 1098 1583 1088 1583 1099 1583 1099 1584 1088 1584 1023 1584 1099 1585 1023 1585 1100 1585 1100 1586 1023 1586 1073 1586 1100 1587 1073 1587 1101 1587 1101 1588 1073 1588 1076 1588 1101 1589 1076 1589 1102 1589 1102 1590 1076 1590 1091 1590 1102 1591 1091 1591 1030 1591 1030 1592 1091 1592 1093 1592 1030 1593 1093 1593 1029 1593 1029 1594 1093 1594 1047 1594 1029 1595 1047 1595 1039 1595 1039 1596 1047 1596 1049 1596 1077 1597 1103 1597 1076 1597 1076 1598 1103 1598 1104 1598 1076 1599 1104 1599 1091 1599 1091 1600 1104 1600 1105 1600 1091 1601 1105 1601 1092 1601 370 1602 369 1602 1030 1602 1030 1603 369 1603 1072 1603 1030 1604 1072 1604 1102 1604 1102 1605 1072 1605 1067 1605 1102 1606 1067 1606 1101 1606 1101 1607 1067 1607 1069 1607 1101 1608 1069 1608 1100 1608 1100 1609 1069 1609 1065 1609 1100 1610 1065 1610 1099 1610 1099 1611 1065 1611 1063 1611 1099 1612 1063 1612 1098 1612 1098 1613 1063 1613 1060 1613 1098 1614 1060 1614 1097 1614 1097 1615 1060 1615 1057 1615 1097 1616 1057 1616 1096 1616 1096 1617 1057 1617 1055 1617 1096 1618 1055 1618 1024 1618 1024 1619 1055 1619 1053 1619 1024 1620 1053 1620 987 1620 987 1621 1053 1621 1052 1621 987 1622 1052 1622 988 1622 1048 1623 1106 1623 1107 1623 1108 1624 1109 1624 1110 1624 1111 1625 615 1625 614 1625 1112 1626 1113 1626 1114 1626 1114 1627 1113 1627 1115 1627 1114 1628 1115 1628 1116 1628 1117 1629 1118 1629 1112 1629 1119 1630 1120 1630 1121 1630 1121 1631 1120 1631 1118 1631 624 1632 1122 1632 1123 1632 1123 1633 1122 1633 1124 1633 1123 1634 1124 1634 1119 1634 1125 1635 1126 1635 1127 1635 1127 1636 1126 1636 1128 1636 1106 1637 1129 1637 1130 1637 1129 1638 1106 1638 1131 1638 1131 1639 1106 1639 1048 1639 1131 1640 1048 1640 1046 1640 1116 1641 1036 1641 1114 1641 1114 1642 1036 1642 1035 1642 1114 1643 1035 1643 1132 1643 624 1644 1123 1644 620 1644 620 1645 1123 1645 1133 1645 620 1646 1133 1646 621 1646 1035 1647 1034 1647 1132 1647 1132 1648 1034 1648 1032 1648 1132 1649 1032 1649 1134 1649 1134 1650 1032 1650 1031 1650 1031 1651 1037 1651 1134 1651 1134 1652 1037 1652 1038 1652 1134 1653 1038 1653 1135 1653 1135 1654 1038 1654 1044 1654 1043 1655 1136 1655 1044 1655 1044 1656 1136 1656 1137 1656 1044 1657 1137 1657 1135 1657 1043 1658 1042 1658 1136 1658 1136 1659 1042 1659 1041 1659 1136 1660 1041 1660 1138 1660 1138 1661 1041 1661 1040 1661 1138 1662 1040 1662 1139 1662 1139 1663 1040 1663 1039 1663 1139 1664 1039 1664 1107 1664 1107 1665 1039 1665 1049 1665 1107 1666 1049 1666 1048 1666 1112 1667 1114 1667 1117 1667 1117 1668 1114 1668 1132 1668 1117 1669 1132 1669 1140 1669 1140 1670 1132 1670 1134 1670 1140 1671 1134 1671 1141 1671 1141 1672 1134 1672 1135 1672 1141 1673 1135 1673 1142 1673 1142 1674 1135 1674 1137 1674 1142 1675 1137 1675 1143 1675 1143 1676 1137 1676 1136 1676 1143 1677 1136 1677 1144 1677 1144 1678 1136 1678 1138 1678 1144 1679 1138 1679 1145 1679 1145 1680 1138 1680 1139 1680 1145 1681 1139 1681 1146 1681 1146 1682 1139 1682 1107 1682 1146 1683 1107 1683 1147 1683 1147 1684 1107 1684 1106 1684 1147 1685 1106 1685 1148 1685 1148 1686 1106 1686 1130 1686 1148 1687 1130 1687 1149 1687 1118 1688 1117 1688 1121 1688 1121 1689 1117 1689 1140 1689 1121 1690 1140 1690 1150 1690 1150 1691 1140 1691 1141 1691 1150 1692 1141 1692 1151 1692 1151 1693 1141 1693 1142 1693 1151 1694 1142 1694 1152 1694 1152 1695 1142 1695 1143 1695 1152 1696 1143 1696 1153 1696 1153 1697 1143 1697 1144 1697 1153 1698 1144 1698 1154 1698 1154 1699 1144 1699 1145 1699 1154 1700 1145 1700 1155 1700 1155 1701 1145 1701 1146 1701 1155 1702 1146 1702 1156 1702 1156 1703 1146 1703 1147 1703 1156 1704 1147 1704 1157 1704 1157 1705 1147 1705 1148 1705 1157 1706 1148 1706 1110 1706 1110 1707 1148 1707 1149 1707 1110 1708 1149 1708 1108 1708 1119 1709 1121 1709 1123 1709 1123 1710 1121 1710 1150 1710 1123 1711 1150 1711 1133 1711 1133 1712 1150 1712 1151 1712 1133 1713 1151 1713 1158 1713 1158 1714 1151 1714 1152 1714 1158 1715 1152 1715 1159 1715 1159 1716 1152 1716 1153 1716 1159 1717 1153 1717 1160 1717 1160 1718 1153 1718 1154 1718 1160 1719 1154 1719 1161 1719 1161 1720 1154 1720 1155 1720 1161 1721 1155 1721 1162 1721 1162 1722 1155 1722 1156 1722 1162 1723 1156 1723 1163 1723 1163 1724 1156 1724 1157 1724 1163 1725 1157 1725 1164 1725 1164 1726 1157 1726 1110 1726 1164 1727 1110 1727 1127 1727 1127 1728 1110 1728 1109 1728 1127 1729 1109 1729 1125 1729 621 1730 1133 1730 703 1730 703 1731 1133 1731 1158 1731 703 1732 1158 1732 704 1732 704 1733 1158 1733 1159 1733 704 1734 1159 1734 705 1734 705 1735 1159 1735 1160 1735 705 1736 1160 1736 700 1736 700 1737 1160 1737 1161 1737 700 1738 1161 1738 701 1738 701 1739 1161 1739 1162 1739 701 1740 1162 1740 706 1740 706 1741 1162 1741 1163 1741 706 1742 1163 1742 707 1742 707 1743 1163 1743 1164 1743 707 1744 1164 1744 708 1744 708 1745 1164 1745 1127 1745 708 1746 1127 1746 614 1746 614 1747 1127 1747 1128 1747 614 1748 1128 1748 1111 1748 132 1749 139 1749 1165 1749 132 1750 1165 1750 1166 1750 1166 1751 1165 1751 161 1751 1166 1752 161 1752 160 1752 128 1753 130 1753 1167 1753 1167 1754 130 1754 1168 1754 1167 1755 1168 1755 1169 1755 1170 1756 1171 1756 1172 1756 1172 1757 1173 1757 1170 1757 1170 1758 1173 1758 1174 1758 1170 1759 1174 1759 1168 1759 1168 1760 1174 1760 1175 1760 1168 1761 1175 1761 1169 1761 1176 1762 1177 1762 1178 1762 1178 1763 1177 1763 1179 1763 1179 1764 1180 1764 1178 1764 1178 1765 1180 1765 1181 1765 1178 1766 1181 1766 1170 1766 1170 1767 1181 1767 1182 1767 1170 1768 1182 1768 1171 1768 1183 1769 1184 1769 1185 1769 1186 1770 1183 1770 1187 1770 1183 1771 1185 1771 1187 1771 1187 1772 1185 1772 1188 1772 1187 1773 1188 1773 1189 1773 1178 1774 1190 1774 1176 1774 1176 1775 1190 1775 1187 1775 1176 1776 1187 1776 1191 1776 1191 1777 1187 1777 1189 1777 1186 1778 1187 1778 1192 1778 1192 1779 1187 1779 1190 1779 1192 1780 1190 1780 1193 1780 1193 1781 1190 1781 54 1781 1193 1782 54 1782 55 1782 37 1783 15 1783 53 1783 53 1784 15 1784 14 1784 1194 1785 1195 1785 1196 1785 1196 1786 1195 1786 1197 1786 1196 1787 1197 1787 1198 1787 1198 1788 1197 1788 1199 1788 1198 1789 1199 1789 1200 1789 1200 1790 1199 1790 1201 1790 1200 1791 1201 1791 1202 1791 1202 1792 1201 1792 1203 1792 1202 1793 1203 1793 1204 1793 1204 1794 1203 1794 1205 1794 1204 1795 1205 1795 1206 1795 1206 1796 1205 1796 1207 1796 1206 1797 1207 1797 1208 1797 1208 1798 1207 1798 1209 1798 1208 1799 1209 1799 1210 1799 1210 1800 1209 1800 1211 1800 1210 1801 1211 1801 1212 1801 1212 1802 1211 1802 1213 1802 1212 1803 1213 1803 1214 1803 1214 1804 1213 1804 1215 1804 1214 1805 1215 1805 1216 1805 1216 1806 1215 1806 1217 1806 1216 1807 1217 1807 1194 1807 1194 1808 1217 1808 1195 1808 1218 1809 1219 1809 1220 1809 1221 1810 1222 1810 1223 1810 1223 1811 1222 1811 1224 1811 1223 1812 1224 1812 1225 1812 1225 1813 1224 1813 1226 1813 1225 1814 1226 1814 1227 1814 1220 1815 1219 1815 1223 1815 1223 1816 1219 1816 1228 1816 1223 1817 1228 1817 1221 1817 1229 1818 1230 1818 1231 1818 1231 1819 1230 1819 1232 1819 1231 1820 1232 1820 1233 1820 1229 1821 1234 1821 1230 1821 1230 1822 1234 1822 1235 1822 1230 1823 1235 1823 1220 1823 1220 1824 1235 1824 1236 1824 1220 1825 1236 1825 1218 1825 1227 1826 1237 1826 1225 1826 1225 1827 1237 1827 1238 1827 1225 1828 1238 1828 1239 1828 1239 1829 1238 1829 1240 1829 1239 1830 1240 1830 1241 1830 1241 1831 1240 1831 1242 1831 1241 1832 1242 1832 1243 1832 1243 1833 1242 1833 1244 1833 1243 1834 1244 1834 1245 1834 1245 1835 1244 1835 1246 1835 1245 1836 1246 1836 1247 1836 1247 1837 1246 1837 1248 1837 1247 1838 1248 1838 1249 1838 1249 1839 1248 1839 1250 1839 1249 1840 1250 1840 1251 1840 1251 1841 1250 1841 1252 1841 1251 1842 1252 1842 1232 1842 1232 1843 1252 1843 1253 1843 1232 1844 1253 1844 1233 1844 1254 1845 1255 1845 1256 1845 1256 1846 1255 1846 1257 1846 1256 1847 1257 1847 1258 1847 1258 1848 1257 1848 1259 1848 1258 1849 1259 1849 1260 1849 1260 1850 1259 1850 1261 1850 1260 1851 1261 1851 1262 1851 1262 1852 1261 1852 1263 1852 1262 1853 1263 1853 1264 1853 1264 1854 1263 1854 1265 1854 1264 1855 1265 1855 1266 1855 1266 1856 1265 1856 1267 1856 1266 1857 1267 1857 1268 1857 1268 1858 1267 1858 1269 1858 1268 1859 1269 1859 1270 1859 1270 1860 1269 1860 1271 1860 1270 1861 1271 1861 1272 1861 1272 1862 1271 1862 1273 1862 1272 1863 1273 1863 1274 1863 1274 1864 1273 1864 1275 1864 1274 1865 1275 1865 1276 1865 1276 1866 1275 1866 1277 1866 1276 1867 1277 1867 1254 1867 1254 1868 1277 1868 1255 1868 1278 1869 1279 1869 1280 1869 443 1870 1281 1870 444 1870 444 1871 1281 1871 1278 1871 444 1872 1278 1872 460 1872 460 1873 1278 1873 1280 1873 1278 1874 1281 1874 1282 1874 1278 1875 1282 1875 1283 1875 1283 1876 1282 1876 1284 1876 1283 1877 1284 1877 1285 1877 1285 1878 1284 1878 1286 1878 1285 1879 1286 1879 1287 1879 1287 1880 1286 1880 1288 1880 1287 1881 1288 1881 1289 1881 1289 1882 1288 1882 1290 1882 1289 1883 1290 1883 1291 1883 1291 1884 1290 1884 1292 1884 1291 1885 1292 1885 1293 1885 1293 1886 1292 1886 441 1886 1293 1887 441 1887 440 1887 1294 1888 1295 1888 1296 1888 1297 1889 1298 1889 1299 1889 1300 1890 1301 1890 1302 1890 1303 1891 1304 1891 1305 1891 1305 1892 1304 1892 1294 1892 1306 1893 1307 1893 1308 1893 1301 1894 1309 1894 1302 1894 1302 1895 1309 1895 1310 1895 1302 1896 1310 1896 1306 1896 1306 1897 1310 1897 1311 1897 1306 1898 1311 1898 1307 1898 1312 1899 1313 1899 1314 1899 1315 1900 1316 1900 1317 1900 1317 1901 1318 1901 1315 1901 1315 1902 1318 1902 1297 1902 1315 1903 1297 1903 1319 1903 1319 1904 1297 1904 1299 1904 1319 1905 1299 1905 1320 1905 1296 1906 1321 1906 1322 1906 1322 1907 1323 1907 1296 1907 1296 1908 1323 1908 1324 1908 1296 1909 1324 1909 1299 1909 1299 1910 1324 1910 1325 1910 1299 1911 1325 1911 1320 1911 1326 1912 1327 1912 1295 1912 1295 1913 1327 1913 1328 1913 1295 1914 1328 1914 1296 1914 1296 1915 1328 1915 1329 1915 1329 1916 1330 1916 1296 1916 1296 1917 1330 1917 1331 1917 1296 1918 1331 1918 1332 1918 1332 1919 1333 1919 1296 1919 1296 1920 1333 1920 1334 1920 1296 1921 1334 1921 1335 1921 1335 1922 1336 1922 1296 1922 1296 1923 1336 1923 1337 1923 1296 1924 1337 1924 1338 1924 1338 1925 1339 1925 1296 1925 1296 1926 1339 1926 1340 1926 1296 1927 1340 1927 1341 1927 1341 1928 1342 1928 1296 1928 1296 1929 1342 1929 1343 1929 1296 1930 1343 1930 1344 1930 1344 1931 1345 1931 1296 1931 1296 1932 1345 1932 1346 1932 1296 1933 1346 1933 1321 1933 1304 1934 1347 1934 1294 1934 1294 1935 1347 1935 1348 1935 1294 1936 1348 1936 1295 1936 1295 1937 1348 1937 1349 1937 1295 1938 1349 1938 1326 1938 1326 1939 1349 1939 1350 1939 1326 1940 1350 1940 1351 1940 1351 1941 1350 1941 1352 1941 1351 1942 1352 1942 1353 1942 1314 1943 1300 1943 1312 1943 1312 1944 1300 1944 1302 1944 1312 1945 1302 1945 1354 1945 1354 1946 1302 1946 1355 1946 1298 1947 1355 1947 1299 1947 1299 1948 1355 1948 1302 1948 1299 1949 1302 1949 1296 1949 1296 1950 1302 1950 1306 1950 1296 1951 1306 1951 1294 1951 1294 1952 1306 1952 1308 1952 1294 1953 1308 1953 1305 1953 738 1954 747 1954 1356 1954 740 1955 739 1955 1357 1955 732 1956 741 1956 1358 1956 734 1957 733 1957 1359 1957 613 1958 735 1958 1360 1958 1361 1959 1362 1959 1363 1959 1364 1960 1365 1960 1366 1960 1367 1961 1368 1961 1369 1961 1370 1962 1371 1962 1362 1962 711 1963 1372 1963 1373 1963 711 1964 1373 1964 650 1964 650 1965 1373 1965 1374 1965 650 1966 1374 1966 651 1966 1372 1967 1375 1967 1376 1967 1376 1968 1375 1968 1377 1968 1376 1969 1377 1969 1378 1969 1371 1970 1379 1970 1362 1970 1362 1971 1379 1971 1380 1971 1362 1972 1380 1972 1363 1972 1363 1973 1380 1973 1381 1973 1363 1974 1381 1974 1382 1974 1383 1975 658 1975 1384 1975 1384 1976 658 1976 660 1976 1385 1977 1378 1977 1386 1977 1386 1978 1378 1978 1377 1978 1386 1979 1377 1979 1387 1979 1388 1980 1389 1980 1390 1980 1391 1981 1392 1981 1393 1981 1394 1982 1395 1982 1396 1982 1397 1983 1390 1983 1398 1983 1398 1984 1390 1984 1389 1984 1398 1985 1389 1985 1387 1985 1399 1986 1393 1986 1400 1986 1400 1987 1393 1987 1392 1987 1400 1988 1392 1988 1401 1988 1360 1989 1396 1989 1402 1989 1402 1990 1396 1990 1395 1990 1402 1991 1395 1991 1403 1991 1372 1992 711 1992 1375 1992 1375 1993 711 1993 710 1993 1375 1994 710 1994 714 1994 1387 1995 1377 1995 1398 1995 1398 1996 1377 1996 1375 1996 1398 1997 1375 1997 1397 1997 1397 1998 1375 1998 714 1998 1397 1999 714 1999 713 1999 713 2000 717 2000 1397 2000 1397 2001 717 2001 1367 2001 1397 2002 1367 2002 1390 2002 1390 2003 1367 2003 1369 2003 1390 2004 1369 2004 1388 2004 1388 2005 1369 2005 1401 2005 717 2006 716 2006 1367 2006 1367 2007 716 2007 720 2007 1367 2008 720 2008 1368 2008 1368 2009 720 2009 719 2009 1368 2010 719 2010 723 2010 1401 2011 1369 2011 1400 2011 1400 2012 1369 2012 1368 2012 1400 2013 1368 2013 1399 2013 1399 2014 1368 2014 723 2014 1399 2015 723 2015 722 2015 722 2016 726 2016 1399 2016 1399 2017 726 2017 1364 2017 1399 2018 1364 2018 1393 2018 1393 2019 1364 2019 1366 2019 1393 2020 1366 2020 1391 2020 1391 2021 1366 2021 1403 2021 726 2022 725 2022 1364 2022 1364 2023 725 2023 729 2023 1364 2024 729 2024 1365 2024 1365 2025 729 2025 728 2025 1365 2026 728 2026 727 2026 1403 2027 1366 2027 1402 2027 1402 2028 1366 2028 1365 2028 1402 2029 1365 2029 1360 2029 1360 2030 1365 2030 727 2030 1360 2031 727 2031 613 2031 735 2032 734 2032 1360 2032 1360 2033 734 2033 1359 2033 1360 2034 1359 2034 1396 2034 1396 2035 1359 2035 1404 2035 1396 2036 1404 2036 1394 2036 1394 2037 1404 2037 1405 2037 733 2038 732 2038 1359 2038 1359 2039 732 2039 1358 2039 1359 2040 1358 2040 1404 2040 1404 2041 1358 2041 1406 2041 1404 2042 1406 2042 1405 2042 1405 2043 1406 2043 1407 2043 741 2044 740 2044 1358 2044 1358 2045 740 2045 1357 2045 1358 2046 1357 2046 1406 2046 1406 2047 1357 2047 1408 2047 1406 2048 1408 2048 1407 2048 1407 2049 1408 2049 1409 2049 739 2050 738 2050 1357 2050 1357 2051 738 2051 1356 2051 1357 2052 1356 2052 1408 2052 1408 2053 1356 2053 1410 2053 1408 2054 1410 2054 1409 2054 1409 2055 1410 2055 1411 2055 747 2056 746 2056 1356 2056 1356 2057 746 2057 1361 2057 1356 2058 1361 2058 1410 2058 1410 2059 1361 2059 1363 2059 1410 2060 1363 2060 1411 2060 1411 2061 1363 2061 1382 2061 1411 2062 1382 2062 1412 2062 1383 2063 1413 2063 658 2063 658 2064 1413 2064 1414 2064 658 2065 1414 2065 748 2065 748 2066 1414 2066 1370 2066 748 2067 1370 2067 749 2067 749 2068 1370 2068 1362 2068 749 2069 1362 2069 744 2069 744 2070 1362 2070 1361 2070 744 2071 1361 2071 745 2071 745 2072 1361 2072 746 2072 47 2073 46 2073 1415 2073 1415 2074 46 2074 1416 2074 1170 2075 1168 2075 130 2075 130 2076 1417 2076 1418 2076 130 2077 132 2077 159 2077 159 2078 132 2078 1166 2078 159 2079 1166 2079 160 2079 46 2080 44 2080 49 2080 49 2081 44 2081 42 2081 49 2082 42 2082 40 2082 1178 2083 1170 2083 1190 2083 1190 2084 1170 2084 130 2084 1190 2085 130 2085 54 2085 54 2086 130 2086 1418 2086 54 2087 1418 2087 49 2087 1417 2088 130 2088 1419 2088 1419 2089 130 2089 159 2089 1419 2090 159 2090 1420 2090 1418 2091 1421 2091 49 2091 49 2092 1421 2092 1422 2092 49 2093 1422 2093 46 2093 46 2094 1422 2094 1423 2094 46 2095 1423 2095 1416 2095 40 2096 39 2096 49 2096 49 2097 39 2097 38 2097 49 2098 38 2098 50 2098 1417 2099 1419 2099 1424 2099 1424 2100 1419 2100 1425 2100 1426 2101 1427 2101 1428 2101 1429 2102 1430 2102 1431 2102 1430 2103 1432 2103 1431 2103 1431 2104 1432 2104 1433 2104 1431 2105 1433 2105 1428 2105 1428 2106 1433 2106 1434 2106 1428 2107 1434 2107 1426 2107 1429 2108 1431 2108 1435 2108 1435 2109 1431 2109 1436 2109 1435 2110 1436 2110 1437 2110 1438 2111 1435 2111 1439 2111 1439 2112 1435 2112 1437 2112 1439 2113 1437 2113 1440 2113 1440 2114 1437 2114 1441 2114 1442 2115 1443 2115 1444 2115 1444 2116 1443 2116 1445 2116 1444 2117 1445 2117 1446 2117 1446 2118 1447 2118 1444 2118 1444 2119 1447 2119 1448 2119 1444 2120 1448 2120 1449 2120 1449 2121 1448 2121 1424 2121 1449 2122 1424 2122 1425 2122 1450 2123 1451 2123 1452 2123 1452 2124 1451 2124 1453 2124 1452 2125 1453 2125 1454 2125 1442 2126 1444 2126 1454 2126 1454 2127 1444 2127 1455 2127 1454 2128 1455 2128 1452 2128 1456 2129 1450 2129 1457 2129 1457 2130 1450 2130 1452 2130 1457 2131 1452 2131 1458 2131 1458 2132 1452 2132 1459 2132 1458 2133 1459 2133 1460 2133 1460 2134 1459 2134 1461 2134 1460 2135 1461 2135 1462 2135 1462 2136 1461 2136 1463 2136 1462 2137 1463 2137 1464 2137 1464 2138 1463 2138 1465 2138 1460 2139 1462 2139 1466 2139 1467 2140 1468 2140 1469 2140 1457 2141 1458 2141 1470 2141 1471 2142 1472 2142 1473 2142 1456 2143 1457 2143 1474 2143 1474 2144 1457 2144 1470 2144 1474 2145 1470 2145 1475 2145 1475 2146 1470 2146 1476 2146 1475 2147 1476 2147 1473 2147 1473 2148 1476 2148 1469 2148 1473 2149 1469 2149 1471 2149 1471 2150 1469 2150 1468 2150 1458 2151 1460 2151 1470 2151 1470 2152 1460 2152 1466 2152 1470 2153 1466 2153 1476 2153 1476 2154 1466 2154 1477 2154 1476 2155 1477 2155 1469 2155 1469 2156 1477 2156 1478 2156 1469 2157 1478 2157 1467 2157 1467 2158 1478 2158 1479 2158 1462 2159 1464 2159 1466 2159 1466 2160 1464 2160 1480 2160 1466 2161 1480 2161 1477 2161 1477 2162 1480 2162 1481 2162 1477 2163 1481 2163 1478 2163 1478 2164 1481 2164 1482 2164 1478 2165 1482 2165 1479 2165 1479 2166 1482 2166 1483 2166 1484 2167 1485 2167 1486 2167 1486 2168 1485 2168 1487 2168 1472 2169 1471 2169 1488 2169 1488 2170 1471 2170 1489 2170 1436 2171 1431 2171 1490 2171 1490 2172 1431 2172 1491 2172 1490 2173 1491 2173 1492 2173 1492 2174 1493 2174 1490 2174 1490 2175 1493 2175 1494 2175 1490 2176 1494 2176 1495 2176 1495 2177 1496 2177 1490 2177 1490 2178 1496 2178 1497 2178 1490 2179 1497 2179 1485 2179 1485 2180 1497 2180 1498 2180 1485 2181 1498 2181 1487 2181 1483 2182 1499 2182 1479 2182 1479 2183 1499 2183 1500 2183 1479 2184 1500 2184 1467 2184 1467 2185 1500 2185 1468 2185 1468 2186 1500 2186 1485 2186 1468 2187 1485 2187 1471 2187 1471 2188 1485 2188 1484 2188 1471 2189 1484 2189 1489 2189 1501 2190 1502 2190 1503 2190 913 2191 1504 2191 908 2191 908 2192 1504 2192 894 2192 913 2193 1505 2193 1504 2193 1504 2194 1505 2194 1506 2194 1504 2195 1506 2195 1507 2195 1508 2196 1504 2196 1509 2196 1509 2197 1504 2197 1507 2197 1509 2198 1507 2198 1510 2198 1510 2199 1507 2199 1501 2199 1510 2200 1501 2200 1511 2200 1511 2201 1501 2201 1503 2201 1512 2202 1241 2202 1513 2202 1513 2203 1241 2203 1243 2203 1514 2204 1515 2204 1243 2204 1243 2205 1515 2205 1516 2205 1243 2206 1516 2206 1513 2206 1517 2207 1245 2207 1518 2207 1518 2208 1245 2208 1247 2208 1518 2209 1247 2209 1519 2209 1519 2210 1247 2210 1520 2210 1517 2211 1521 2211 1245 2211 1245 2212 1521 2212 1522 2212 1245 2213 1522 2213 1243 2213 1243 2214 1522 2214 1523 2214 1243 2215 1523 2215 1514 2215 1520 2216 1247 2216 1524 2216 1524 2217 1247 2217 1249 2217 1524 2218 1249 2218 1525 2218 1526 2219 1527 2219 1251 2219 1251 2220 1527 2220 1528 2220 1251 2221 1528 2221 1249 2221 1249 2222 1528 2222 1529 2222 1249 2223 1529 2223 1525 2223 1530 2224 1531 2224 1232 2224 1232 2225 1531 2225 1532 2225 1232 2226 1532 2226 1251 2226 1251 2227 1532 2227 1533 2227 1251 2228 1533 2228 1526 2228 1230 2229 1534 2229 1232 2229 1232 2230 1534 2230 1535 2230 1232 2231 1535 2231 1530 2231 1220 2232 1536 2232 1230 2232 1230 2233 1536 2233 1537 2233 1230 2234 1537 2234 1534 2234 1223 2235 1538 2235 1220 2235 1220 2236 1538 2236 1539 2236 1220 2237 1539 2237 1536 2237 1225 2238 1540 2238 1223 2238 1223 2239 1540 2239 1541 2239 1541 2240 1542 2240 1223 2240 1223 2241 1542 2241 1543 2241 1223 2242 1543 2242 1538 2242 1512 2243 1544 2243 1241 2243 1241 2244 1544 2244 1545 2244 1241 2245 1545 2245 1239 2245 1239 2246 1545 2246 1546 2246 1239 2247 1546 2247 1225 2247 1225 2248 1546 2248 1547 2248 1225 2249 1547 2249 1540 2249 1548 2250 1549 2250 1204 2250 1550 2251 1208 2251 1551 2251 1551 2252 1208 2252 1210 2252 1551 2253 1210 2253 1552 2253 1553 2254 1554 2254 1212 2254 1212 2255 1554 2255 1555 2255 1212 2256 1555 2256 1210 2256 1210 2257 1555 2257 1556 2257 1210 2258 1556 2258 1552 2258 1214 2259 1557 2259 1558 2259 1558 2260 1559 2260 1214 2260 1214 2261 1559 2261 1560 2261 1214 2262 1560 2262 1212 2262 1212 2263 1560 2263 1561 2263 1212 2264 1561 2264 1553 2264 1562 2265 1563 2265 1194 2265 1194 2266 1563 2266 1564 2266 1194 2267 1564 2267 1216 2267 1216 2268 1564 2268 1565 2268 1216 2269 1565 2269 1214 2269 1214 2270 1565 2270 1566 2270 1214 2271 1566 2271 1557 2271 1196 2272 1567 2272 1568 2272 1568 2273 1569 2273 1196 2273 1196 2274 1569 2274 1570 2274 1196 2275 1570 2275 1194 2275 1194 2276 1570 2276 1571 2276 1194 2277 1571 2277 1562 2277 1567 2278 1196 2278 1572 2278 1572 2279 1196 2279 1198 2279 1572 2280 1198 2280 1573 2280 1574 2281 1575 2281 1200 2281 1200 2282 1575 2282 1576 2282 1200 2283 1576 2283 1198 2283 1198 2284 1576 2284 1577 2284 1198 2285 1577 2285 1573 2285 1578 2286 1579 2286 1202 2286 1579 2287 1580 2287 1202 2287 1202 2288 1580 2288 1581 2288 1202 2289 1581 2289 1200 2289 1200 2290 1581 2290 1582 2290 1200 2291 1582 2291 1574 2291 1549 2292 1583 2292 1204 2292 1204 2293 1583 2293 1584 2293 1204 2294 1584 2294 1202 2294 1202 2295 1584 2295 1585 2295 1202 2296 1585 2296 1578 2296 1550 2297 1586 2297 1208 2297 1208 2298 1586 2298 1587 2298 1208 2299 1587 2299 1206 2299 1206 2300 1587 2300 1588 2300 1206 2301 1588 2301 1589 2301 1589 2302 1590 2302 1206 2302 1206 2303 1590 2303 1591 2303 1206 2304 1591 2304 1204 2304 1204 2305 1591 2305 1592 2305 1204 2306 1592 2306 1548 2306 1593 2307 1594 2307 1276 2307 1595 2308 1596 2308 1272 2308 1272 2309 1596 2309 1270 2309 1597 2310 1598 2310 1274 2310 1274 2311 1598 2311 1599 2311 1274 2312 1599 2312 1272 2312 1272 2313 1599 2313 1600 2313 1272 2314 1600 2314 1595 2314 1594 2315 1601 2315 1276 2315 1276 2316 1601 2316 1602 2316 1276 2317 1602 2317 1274 2317 1274 2318 1602 2318 1603 2318 1274 2319 1603 2319 1597 2319 1256 2320 1604 2320 1254 2320 1254 2321 1604 2321 1605 2321 1605 2322 1606 2322 1254 2322 1254 2323 1606 2323 1607 2323 1254 2324 1607 2324 1276 2324 1276 2325 1607 2325 1608 2325 1276 2326 1608 2326 1593 2326 1258 2327 1609 2327 1256 2327 1256 2328 1609 2328 1610 2328 1256 2329 1610 2329 1604 2329 1260 2330 1611 2330 1258 2330 1258 2331 1611 2331 1612 2331 1258 2332 1612 2332 1609 2332 1262 2333 1613 2333 1260 2333 1260 2334 1613 2334 1614 2334 1260 2335 1614 2335 1611 2335 1264 2336 1615 2336 1262 2336 1262 2337 1615 2337 1616 2337 1262 2338 1616 2338 1613 2338 1266 2339 1617 2339 1264 2339 1264 2340 1617 2340 1618 2340 1264 2341 1618 2341 1615 2341 1268 2342 1619 2342 1266 2342 1266 2343 1619 2343 1620 2343 1266 2344 1620 2344 1617 2344 1596 2345 1621 2345 1270 2345 1270 2346 1621 2346 1622 2346 1270 2347 1622 2347 1268 2347 1268 2348 1622 2348 1623 2348 1268 2349 1623 2349 1619 2349 1624 2350 1625 2350 1626 2350 1627 2351 1628 2351 1624 2351 1624 2352 1628 2352 1629 2352 1624 2353 1629 2353 1625 2353 1630 2354 1631 2354 1632 2354 1630 2355 1632 2355 1633 2355 1626 2356 1634 2356 1624 2356 1624 2357 1634 2357 1635 2357 1624 2358 1635 2358 1636 2358 1636 2359 1635 2359 1637 2359 1636 2360 1637 2360 1638 2360 1638 2361 1637 2361 1639 2361 1638 2362 1639 2362 1640 2362 1640 2363 1639 2363 1641 2363 1632 2364 1642 2364 1633 2364 1633 2365 1642 2365 1643 2365 1633 2366 1643 2366 1644 2366 1644 2367 1643 2367 1645 2367 1644 2368 1645 2368 1646 2368 1646 2369 1645 2369 1647 2369 1646 2370 1647 2370 1648 2370 1649 2371 1650 2371 1651 2371 1651 2372 1650 2372 1652 2372 1651 2373 1652 2373 1653 2373 1653 2374 1652 2374 1654 2374 1653 2375 1654 2375 1641 2375 1641 2376 1654 2376 1655 2376 1641 2377 1655 2377 1640 2377 1647 2378 1656 2378 1648 2378 1648 2379 1656 2379 1657 2379 1648 2380 1657 2380 1658 2380 1658 2381 1657 2381 1649 2381 1658 2382 1649 2382 1659 2382 1659 2383 1649 2383 1651 2383 1660 2384 1661 2384 1662 2384 1663 2385 1664 2385 1665 2385 1666 2386 1667 2386 1668 2386 1668 2387 1667 2387 1669 2387 1668 2388 1669 2388 1670 2388 1670 2389 1669 2389 1671 2389 1670 2390 1671 2390 1663 2390 1672 2391 1673 2391 1674 2391 1674 2392 1673 2392 1675 2392 1674 2393 1675 2393 1676 2393 1672 2394 1674 2394 1677 2394 1677 2395 1674 2395 1678 2395 1677 2396 1678 2396 1679 2396 1680 2397 1681 2397 1682 2397 1680 2398 1682 2398 1683 2398 1684 2399 1666 2399 1685 2399 1685 2400 1666 2400 1668 2400 1685 2401 1668 2401 1683 2401 1686 2402 1687 2402 1677 2402 1677 2403 1687 2403 1688 2403 1677 2404 1688 2404 1672 2404 1689 2405 1690 2405 1670 2405 1663 2406 1665 2406 1670 2406 1670 2407 1665 2407 1691 2407 1670 2408 1691 2408 1689 2408 1692 2409 1693 2409 1680 2409 1680 2410 1693 2410 1694 2410 1680 2411 1694 2411 1681 2411 1681 2412 1694 2412 1695 2412 1681 2413 1695 2413 1696 2413 1697 2414 1698 2414 1678 2414 1676 2415 1660 2415 1674 2415 1674 2416 1660 2416 1662 2416 1674 2417 1662 2417 1678 2417 1678 2418 1662 2418 1699 2418 1678 2419 1699 2419 1697 2419 1682 2420 1700 2420 1683 2420 1683 2421 1700 2421 1701 2421 1683 2422 1701 2422 1685 2422 1685 2423 1701 2423 1702 2423 1685 2424 1702 2424 1684 2424 1684 2425 1702 2425 1703 2425 1684 2426 1703 2426 1704 2426 1690 2427 1686 2427 1670 2427 1670 2428 1686 2428 1677 2428 1670 2429 1677 2429 1668 2429 1668 2430 1677 2430 1679 2430 1668 2431 1679 2431 1683 2431 1683 2432 1679 2432 1678 2432 1683 2433 1678 2433 1680 2433 1680 2434 1678 2434 1698 2434 1680 2435 1698 2435 1692 2435 1705 2436 1706 2436 1707 2436 1708 2437 1709 2437 1710 2437 1633 2438 1644 2438 1711 2438 1630 2439 1633 2439 1712 2439 1712 2440 1633 2440 1711 2440 1712 2441 1711 2441 1713 2441 1713 2442 1711 2442 1714 2442 1715 2443 1708 2443 1716 2443 1716 2444 1708 2444 1717 2444 1718 2445 1719 2445 1720 2445 1720 2446 1719 2446 1721 2446 1720 2447 1721 2447 1722 2447 1723 2448 1724 2448 1710 2448 1710 2449 1724 2449 1725 2449 1726 2450 1727 2450 1720 2450 1720 2451 1727 2451 1728 2451 1720 2452 1728 2452 1718 2452 1725 2453 1726 2453 1710 2453 1710 2454 1726 2454 1720 2454 1710 2455 1720 2455 1708 2455 1708 2456 1720 2456 1722 2456 1708 2457 1722 2457 1717 2457 1644 2458 1646 2458 1711 2458 1711 2459 1646 2459 1648 2459 1711 2460 1648 2460 1729 2460 1639 2461 1730 2461 1641 2461 1641 2462 1730 2462 1731 2462 1641 2463 1731 2463 1653 2463 1730 2464 1732 2464 1731 2464 1731 2465 1732 2465 1733 2465 1731 2466 1733 2466 1729 2466 1707 2467 1706 2467 1734 2467 1735 2468 1736 2468 1707 2468 1707 2469 1736 2469 1737 2469 1707 2470 1737 2470 1705 2470 1734 2471 1706 2471 1738 2471 1738 2472 1706 2472 1739 2472 1738 2473 1739 2473 1740 2473 1732 2474 1741 2474 1733 2474 1733 2475 1741 2475 1742 2475 1733 2476 1742 2476 1738 2476 1738 2477 1742 2477 1743 2477 1738 2478 1743 2478 1734 2478 1648 2479 1658 2479 1729 2479 1729 2480 1658 2480 1659 2480 1729 2481 1659 2481 1731 2481 1731 2482 1659 2482 1651 2482 1731 2483 1651 2483 1653 2483 1740 2484 1723 2484 1738 2484 1738 2485 1723 2485 1710 2485 1738 2486 1710 2486 1733 2486 1733 2487 1710 2487 1709 2487 1733 2488 1709 2488 1729 2488 1729 2489 1709 2489 1708 2489 1729 2490 1708 2490 1711 2490 1711 2491 1708 2491 1715 2491 1711 2492 1715 2492 1714 2492 1744 2493 1745 2493 1746 2493 1745 2494 1744 2494 1747 2494 1747 2495 1744 2495 1748 2495 1747 2496 1748 2496 1749 2496 1749 2497 1748 2497 1750 2497 1749 2498 1750 2498 1696 2498 1746 2499 1751 2499 1744 2499 1744 2500 1751 2500 1752 2500 1744 2501 1752 2501 1753 2501 1703 2502 1754 2502 1704 2502 1704 2503 1754 2503 1755 2503 1704 2504 1755 2504 1756 2504 1682 2505 1757 2505 1700 2505 1700 2506 1757 2506 1758 2506 1700 2507 1758 2507 1701 2507 1750 2508 1759 2508 1696 2508 1696 2509 1759 2509 1760 2509 1696 2510 1760 2510 1681 2510 1681 2511 1760 2511 1761 2511 1681 2512 1761 2512 1682 2512 1682 2513 1761 2513 1762 2513 1682 2514 1762 2514 1757 2514 1702 2515 1763 2515 1703 2515 1703 2516 1763 2516 1764 2516 1703 2517 1764 2517 1754 2517 1758 2518 1765 2518 1701 2518 1701 2519 1765 2519 1766 2519 1701 2520 1766 2520 1702 2520 1702 2521 1766 2521 1767 2521 1702 2522 1767 2522 1763 2522 1645 2523 1643 2523 1768 2523 1768 2524 1643 2524 1642 2524 1632 2525 1631 2525 1769 2525 1308 2526 1307 2526 1770 2526 1771 2527 1772 2527 1640 2527 1640 2528 1772 2528 1773 2528 1640 2529 1773 2529 1638 2529 1638 2530 1773 2530 1774 2530 1638 2531 1774 2531 1636 2531 1775 2532 1313 2532 1771 2532 1771 2533 1313 2533 1776 2533 1771 2534 1776 2534 1772 2534 1311 2535 1310 2535 1777 2535 1777 2536 1310 2536 1309 2536 1301 2537 1300 2537 1775 2537 1775 2538 1300 2538 1314 2538 1775 2539 1314 2539 1313 2539 1308 2540 1770 2540 1305 2540 1303 2541 1305 2541 1778 2541 1778 2542 1305 2542 1770 2542 1778 2543 1770 2543 1779 2543 1779 2544 1770 2544 1780 2544 1779 2545 1780 2545 1781 2545 1782 2546 1783 2546 1784 2546 1784 2547 1783 2547 1785 2547 1784 2548 1785 2548 1780 2548 1780 2549 1785 2549 1786 2549 1780 2550 1786 2550 1781 2550 1647 2551 1645 2551 1787 2551 1787 2552 1645 2552 1768 2552 1787 2553 1768 2553 1769 2553 1769 2554 1768 2554 1642 2554 1769 2555 1642 2555 1632 2555 1788 2556 1657 2556 1787 2556 1787 2557 1657 2557 1656 2557 1787 2558 1656 2558 1647 2558 1640 2559 1655 2559 1771 2559 1771 2560 1655 2560 1654 2560 1771 2561 1654 2561 1775 2561 1775 2562 1654 2562 1652 2562 1775 2563 1652 2563 1789 2563 1789 2564 1652 2564 1650 2564 1789 2565 1650 2565 1649 2565 1649 2566 1657 2566 1789 2566 1789 2567 1657 2567 1788 2567 1789 2568 1788 2568 1775 2568 1775 2569 1788 2569 1777 2569 1775 2570 1777 2570 1301 2570 1301 2571 1777 2571 1309 2571 1769 2572 1782 2572 1787 2572 1787 2573 1782 2573 1784 2573 1787 2574 1784 2574 1788 2574 1788 2575 1784 2575 1780 2575 1788 2576 1780 2576 1777 2576 1777 2577 1780 2577 1770 2577 1777 2578 1770 2578 1311 2578 1311 2579 1770 2579 1307 2579 1661 2580 1660 2580 1790 2580 1790 2581 1660 2581 1676 2581 1790 2582 1676 2582 1675 2582 1736 2583 1735 2583 1791 2583 1791 2584 1735 2584 1792 2584 1791 2585 1792 2585 1793 2585 1794 2586 1795 2586 1796 2586 1796 2587 1795 2587 1791 2587 1796 2588 1791 2588 1797 2588 1797 2589 1791 2589 1793 2589 1794 2590 1798 2590 1795 2590 1795 2591 1798 2591 1799 2591 1795 2592 1799 2592 1800 2592 1740 2593 1739 2593 1791 2593 1791 2594 1739 2594 1706 2594 1706 2595 1705 2595 1791 2595 1791 2596 1705 2596 1737 2596 1791 2597 1737 2597 1736 2597 1724 2598 1801 2598 1725 2598 1725 2599 1801 2599 1726 2599 1802 2600 1719 2600 1803 2600 1803 2601 1719 2601 1718 2601 1718 2602 1728 2602 1803 2602 1803 2603 1728 2603 1727 2603 1803 2604 1727 2604 1804 2604 1804 2605 1805 2605 1803 2605 1803 2606 1805 2606 1806 2606 1803 2607 1806 2607 1802 2607 1807 2608 1808 2608 1804 2608 1804 2609 1808 2609 1809 2609 1804 2610 1809 2610 1805 2610 1810 2611 1811 2611 1807 2611 1807 2612 1811 2612 1812 2612 1807 2613 1812 2613 1808 2613 1813 2614 1814 2614 1815 2614 1815 2615 1814 2615 1816 2615 1815 2616 1816 2616 1810 2616 1810 2617 1816 2617 1817 2617 1810 2618 1817 2618 1811 2618 1689 2619 1691 2619 1818 2619 1818 2620 1691 2620 1665 2620 1813 2621 1815 2621 1819 2621 1819 2622 1815 2622 1818 2622 1819 2623 1818 2623 1820 2623 1820 2624 1818 2624 1665 2624 1820 2625 1665 2625 1664 2625 1689 2626 1818 2626 1690 2626 1690 2627 1818 2627 1815 2627 1690 2628 1815 2628 1686 2628 1672 2629 1688 2629 1821 2629 1821 2630 1688 2630 1687 2630 1672 2631 1821 2631 1673 2631 1673 2632 1821 2632 1822 2632 1673 2633 1822 2633 1675 2633 1727 2634 1726 2634 1804 2634 1804 2635 1726 2635 1801 2635 1804 2636 1801 2636 1807 2636 1807 2637 1801 2637 1823 2637 1807 2638 1823 2638 1810 2638 1810 2639 1823 2639 1822 2639 1810 2640 1822 2640 1815 2640 1815 2641 1822 2641 1821 2641 1815 2642 1821 2642 1686 2642 1686 2643 1821 2643 1687 2643 1724 2644 1723 2644 1801 2644 1801 2645 1723 2645 1740 2645 1801 2646 1740 2646 1823 2646 1823 2647 1740 2647 1791 2647 1823 2648 1791 2648 1822 2648 1822 2649 1791 2649 1795 2649 1822 2650 1795 2650 1675 2650 1675 2651 1795 2651 1800 2651 1675 2652 1800 2652 1790 2652 1824 2653 1825 2653 1826 2653 1760 2654 1759 2654 1827 2654 1827 2655 1828 2655 1829 2655 1827 2656 1829 2656 1830 2656 1828 2657 1827 2657 1831 2657 1831 2658 1827 2658 1759 2658 1831 2659 1759 2659 1832 2659 1832 2660 1759 2660 1750 2660 1832 2661 1750 2661 1748 2661 1833 2662 1766 2662 1765 2662 1765 2663 1758 2663 1833 2663 1833 2664 1758 2664 1757 2664 1833 2665 1757 2665 1830 2665 1830 2666 1757 2666 1762 2666 1830 2667 1762 2667 1827 2667 1827 2668 1762 2668 1761 2668 1827 2669 1761 2669 1760 2669 1763 2670 1834 2670 1764 2670 1764 2671 1834 2671 1835 2671 1764 2672 1835 2672 1754 2672 1754 2673 1835 2673 1755 2673 1756 2674 1755 2674 1836 2674 1836 2675 1755 2675 1835 2675 1836 2676 1835 2676 1837 2676 1837 2677 1835 2677 1834 2677 1837 2678 1834 2678 1838 2678 1839 2679 1840 2679 1841 2679 1841 2680 1840 2680 1842 2680 1841 2681 1842 2681 1843 2681 1844 2682 1845 2682 1846 2682 1843 2683 1842 2683 1847 2683 1847 2684 1842 2684 1844 2684 1847 2685 1844 2685 1826 2685 1826 2686 1844 2686 1846 2686 1826 2687 1846 2687 1824 2687 1848 2688 1849 2688 1844 2688 1849 2689 1850 2689 1844 2689 1844 2690 1850 2690 1851 2690 1844 2691 1851 2691 1845 2691 1829 2692 1852 2692 1830 2692 1830 2693 1852 2693 1853 2693 1830 2694 1853 2694 1854 2694 1855 2695 1856 2695 1857 2695 1857 2696 1856 2696 1858 2696 1839 2697 1838 2697 1840 2697 1840 2698 1838 2698 1834 2698 1840 2699 1834 2699 1842 2699 1842 2700 1834 2700 1859 2700 1842 2701 1859 2701 1844 2701 1844 2702 1859 2702 1857 2702 1844 2703 1857 2703 1848 2703 1848 2704 1857 2704 1858 2704 1763 2705 1767 2705 1834 2705 1834 2706 1767 2706 1766 2706 1834 2707 1766 2707 1859 2707 1859 2708 1766 2708 1833 2708 1859 2709 1833 2709 1857 2709 1857 2710 1833 2710 1830 2710 1857 2711 1830 2711 1855 2711 1855 2712 1830 2712 1854 2712 1860 2713 1861 2713 1862 2713 1863 2714 1864 2714 1865 2714 1866 2715 1867 2715 1868 2715 1868 2716 1867 2716 653 2716 1869 2717 1870 2717 1866 2717 1871 2718 1872 2718 1868 2718 1868 2719 1872 2719 1873 2719 1868 2720 1873 2720 1866 2720 1866 2721 1873 2721 1874 2721 1866 2722 1874 2722 1869 2722 1865 2723 1864 2723 1875 2723 1864 2724 1876 2724 1875 2724 1875 2725 1876 2725 1877 2725 1875 2726 1877 2726 1868 2726 1868 2727 1877 2727 1878 2727 1868 2728 1878 2728 1871 2728 1879 2729 1880 2729 1881 2729 1881 2730 1880 2730 1882 2730 1882 2731 1883 2731 1881 2731 1881 2732 1883 2732 1884 2732 1881 2733 1884 2733 1862 2733 1862 2734 1884 2734 1885 2734 1862 2735 1885 2735 1860 2735 1886 2736 1887 2736 1888 2736 1888 2737 1887 2737 1889 2737 1888 2738 1889 2738 1879 2738 1879 2739 1889 2739 1890 2739 1879 2740 1890 2740 1880 2740 1829 2741 1891 2741 1852 2741 1852 2742 1891 2742 1892 2742 1852 2743 1892 2743 1853 2743 1853 2744 1892 2744 1893 2744 1853 2745 1893 2745 1854 2745 1854 2746 1893 2746 1855 2746 1855 2747 1893 2747 1894 2747 1855 2748 1894 2748 1856 2748 1850 2749 1849 2749 1895 2749 1895 2750 1849 2750 1848 2750 1895 2751 1848 2751 1894 2751 1894 2752 1848 2752 1858 2752 1894 2753 1858 2753 1856 2753 1850 2754 1895 2754 1851 2754 1851 2755 1895 2755 1896 2755 1851 2756 1896 2756 1845 2756 1897 2757 1898 2757 1896 2757 1896 2758 1898 2758 1899 2758 1845 2759 1896 2759 1846 2759 1846 2760 1896 2760 1899 2760 1846 2761 1899 2761 1824 2761 1824 2762 1899 2762 1900 2762 1824 2763 1900 2763 1825 2763 1901 2764 1385 2764 1862 2764 1861 2765 1863 2765 1862 2765 1862 2766 1863 2766 1865 2766 1862 2767 1865 2767 1901 2767 1901 2768 1865 2768 1875 2768 1901 2769 1875 2769 1902 2769 653 2770 1903 2770 1868 2770 1868 2771 1903 2771 1904 2771 1868 2772 1904 2772 1875 2772 1875 2773 1904 2773 1905 2773 1875 2774 1905 2774 1902 2774 1906 2775 1907 2775 1888 2775 1888 2776 1907 2776 1908 2776 1888 2777 1908 2777 1886 2777 1886 2778 1908 2778 1909 2778 1886 2779 1909 2779 1910 2779 1385 2780 1897 2780 1862 2780 1862 2781 1897 2781 1896 2781 1862 2782 1896 2782 1881 2782 1881 2783 1896 2783 1895 2783 1881 2784 1895 2784 1879 2784 1879 2785 1895 2785 1894 2785 1879 2786 1894 2786 1888 2786 1888 2787 1894 2787 1893 2787 1888 2788 1893 2788 1906 2788 1906 2789 1893 2789 1892 2789 1911 2790 1912 2790 1913 2790 649 2791 647 2791 1913 2791 1913 2792 647 2792 646 2792 1913 2793 646 2793 1911 2793 1911 2794 646 2794 654 2794 1911 2795 654 2795 653 2795 649 2796 1913 2796 642 2796 642 2797 1913 2797 1914 2797 642 2798 1914 2798 643 2798 1915 2799 632 2799 631 2799 631 2800 630 2800 1915 2800 1915 2801 630 2801 629 2801 1915 2802 629 2802 627 2802 626 2803 645 2803 1914 2803 1914 2804 645 2804 644 2804 1914 2805 644 2805 643 2805 1122 2806 624 2806 1124 2806 1124 2807 624 2807 623 2807 1124 2808 623 2808 1119 2808 623 2809 625 2809 1119 2809 1119 2810 625 2810 641 2810 1119 2811 641 2811 640 2811 1915 2812 639 2812 638 2812 638 2813 637 2813 1915 2813 1915 2814 637 2814 636 2814 1915 2815 636 2815 635 2815 635 2816 634 2816 1915 2816 1915 2817 634 2817 633 2817 1915 2818 633 2818 632 2818 1916 2819 1917 2819 1915 2819 1915 2820 1917 2820 1918 2820 1915 2821 1918 2821 1919 2821 640 2822 639 2822 1119 2822 1119 2823 639 2823 1915 2823 1119 2824 1915 2824 1120 2824 1120 2825 1915 2825 1919 2825 1120 2826 1919 2826 1118 2826 1118 2827 1919 2827 1112 2827 627 2828 626 2828 1915 2828 1915 2829 626 2829 1914 2829 1915 2830 1914 2830 1916 2830 1916 2831 1914 2831 1920 2831 1912 2832 1921 2832 1913 2832 1913 2833 1921 2833 1922 2833 1913 2834 1922 2834 1914 2834 1914 2835 1922 2835 1923 2835 1914 2836 1923 2836 1920 2836 653 2837 656 2837 1924 2837 1924 2838 656 2838 652 2838 1924 2839 652 2839 651 2839 1925 2840 1382 2840 1381 2840 1926 2841 1381 2841 1380 2841 1926 2842 1380 2842 1927 2842 1925 2843 1381 2843 1928 2843 1928 2844 1381 2844 1926 2844 1928 2845 1926 2845 1929 2845 1927 2846 1930 2846 1931 2846 1931 2847 1930 2847 1932 2847 1931 2848 1932 2848 1933 2848 1934 2849 1935 2849 1932 2849 1932 2850 1935 2850 1936 2850 1932 2851 1936 2851 1933 2851 1937 2852 1938 2852 1939 2852 1384 2853 1937 2853 1934 2853 1934 2854 1937 2854 1939 2854 1934 2855 1939 2855 1935 2855 659 2856 657 2856 1940 2856 1384 2857 660 2857 1937 2857 1937 2858 660 2858 659 2858 1937 2859 659 2859 1941 2859 1941 2860 659 2860 1940 2860 1370 2861 1414 2861 1932 2861 1932 2862 1414 2862 1413 2862 1932 2863 1413 2863 1934 2863 1934 2864 1413 2864 1383 2864 1934 2865 1383 2865 1384 2865 1927 2866 1380 2866 1930 2866 1930 2867 1380 2867 1379 2867 1930 2868 1379 2868 1932 2868 1932 2869 1379 2869 1371 2869 1932 2870 1371 2870 1370 2870 1937 2871 1941 2871 1942 2871 1940 2872 657 2872 618 2872 1943 2873 1938 2873 1937 2873 1943 2874 1937 2874 1944 2874 1944 2875 1937 2875 1942 2875 1944 2876 1942 2876 1945 2876 1945 2877 1942 2877 1946 2877 1946 2878 1942 2878 1947 2878 1946 2879 1947 2879 1948 2879 1949 2880 1950 2880 1947 2880 1947 2881 1950 2881 1951 2881 1947 2882 1951 2882 1948 2882 922 2883 928 2883 1952 2883 1952 2884 1953 2884 1949 2884 1949 2885 1953 2885 1954 2885 1949 2886 1954 2886 1950 2886 677 2887 674 2887 1949 2887 670 2888 690 2888 919 2888 674 2889 673 2889 1949 2889 1949 2890 673 2890 672 2890 1949 2891 672 2891 671 2891 922 2892 1952 2892 923 2892 923 2893 1952 2893 1949 2893 923 2894 1949 2894 919 2894 919 2895 1949 2895 671 2895 919 2896 671 2896 670 2896 690 2897 689 2897 919 2897 919 2898 689 2898 688 2898 919 2899 688 2899 920 2899 920 2900 688 2900 687 2900 920 2901 687 2901 918 2901 675 2902 680 2902 1949 2902 666 2903 682 2903 1947 2903 1947 2904 682 2904 681 2904 1947 2905 681 2905 1949 2905 1949 2906 681 2906 676 2906 1949 2907 676 2907 675 2907 680 2908 679 2908 1949 2908 1949 2909 679 2909 678 2909 1949 2910 678 2910 677 2910 1940 2911 618 2911 1941 2911 1941 2912 618 2912 617 2912 1941 2913 617 2913 1942 2913 1942 2914 617 2914 665 2914 1942 2915 665 2915 664 2915 664 2916 662 2916 1942 2916 1942 2917 662 2917 661 2917 1942 2918 661 2918 1947 2918 1947 2919 661 2919 667 2919 1947 2920 667 2920 666 2920 1316 2921 1955 2921 1956 2921 1316 2922 1956 2922 1957 2922 1957 2923 1956 2923 1958 2923 1957 2924 1958 2924 1959 2924 1959 2925 1958 2925 1960 2925 1960 2926 1958 2926 1961 2926 1960 2927 1961 2927 1962 2927 1962 2928 1961 2928 1963 2928 1962 2929 1963 2929 1964 2929 1965 2930 1966 2930 1967 2930 1967 2931 1966 2931 1968 2931 1967 2932 1968 2932 1969 2932 1969 2933 1968 2933 1970 2933 1969 2934 1970 2934 1971 2934 1971 2935 1970 2935 1972 2935 1971 2936 1972 2936 1963 2936 1963 2937 1972 2937 1973 2937 1963 2938 1973 2938 1964 2938 1886 2939 1910 2939 1974 2939 1974 2940 1910 2940 1975 2940 1974 2941 1975 2941 1965 2941 1965 2942 1975 2942 1976 2942 1965 2943 1976 2943 1966 2943 1974 2944 1977 2944 1886 2944 1886 2945 1977 2945 1978 2945 1886 2946 1978 2946 1887 2946 1887 2947 1978 2947 1979 2947 1887 2948 1979 2948 1889 2948 1889 2949 1979 2949 1980 2949 1889 2950 1980 2950 1890 2950 1890 2951 1980 2951 1981 2951 1982 2952 1882 2952 1981 2952 1981 2953 1882 2953 1880 2953 1981 2954 1880 2954 1890 2954 1983 2955 1884 2955 1982 2955 1982 2956 1884 2956 1883 2956 1982 2957 1883 2957 1882 2957 1863 2958 1861 2958 1983 2958 1861 2959 1860 2959 1983 2959 1983 2960 1860 2960 1885 2960 1983 2961 1885 2961 1884 2961 1983 2962 1984 2962 1863 2962 1863 2963 1984 2963 1985 2963 1863 2964 1985 2964 1986 2964 1986 2965 1985 2965 1987 2965 1955 2966 1316 2966 1988 2966 1988 2967 1316 2967 1315 2967 1988 2968 1315 2968 1989 2968 1315 2969 1319 2969 1989 2969 1989 2970 1319 2970 1320 2970 1989 2971 1320 2971 1990 2971 1990 2972 1320 2972 1325 2972 1990 2973 1325 2973 1991 2973 1991 2974 1325 2974 1324 2974 1992 2975 1993 2975 1994 2975 1992 2976 1994 2976 1995 2976 1996 2977 1997 2977 1998 2977 1998 2978 1997 2978 1999 2978 1995 2979 1994 2979 1996 2979 1996 2980 1994 2980 2000 2980 1996 2981 2000 2981 1997 2981 1997 2982 2000 2982 2001 2982 2002 2983 2003 2983 2001 2983 2001 2984 2003 2984 1999 2984 2001 2985 1999 2985 1997 2985 2001 2986 2004 2986 2002 2986 2002 2987 2004 2987 2005 2987 2002 2988 2005 2988 2006 2988 2006 2989 2005 2989 2007 2989 2006 2990 2007 2990 2008 2990 2008 2991 2007 2991 2009 2991 2007 2992 2010 2992 2009 2992 2009 2993 2010 2993 2011 2993 2009 2994 2011 2994 2012 2994 2012 2995 2011 2995 2013 2995 2012 2996 2013 2996 2014 2996 2014 2997 2013 2997 2015 2997 2014 2998 2015 2998 2016 2998 948 2999 2017 2999 930 2999 930 3000 2017 3000 929 3000 82 3001 81 3001 2018 3001 2018 3002 2019 3002 82 3002 82 3003 2019 3003 2014 3003 82 3004 2014 3004 948 3004 948 3005 2014 3005 2016 3005 948 3006 2016 3006 2017 3006 2020 3007 2021 3007 2022 3007 2022 3008 2021 3008 2023 3008 2022 3009 2023 3009 2024 3009 2025 3010 2026 3010 2027 3010 2028 3011 2029 3011 2027 3011 2027 3012 2029 3012 2030 3012 2027 3013 2030 3013 2025 3013 2020 3014 2031 3014 2021 3014 2021 3015 2031 3015 2032 3015 2021 3016 2032 3016 2033 3016 2033 3017 2032 3017 2034 3017 2033 3018 2034 3018 2035 3018 2035 3019 2034 3019 2036 3019 2035 3020 2036 3020 2037 3020 2037 3021 2036 3021 2038 3021 2038 3022 2039 3022 2037 3022 2037 3023 2039 3023 2040 3023 2037 3024 2040 3024 2041 3024 2041 3025 2040 3025 2042 3025 2041 3026 2042 3026 2043 3026 1575 3027 2044 3027 2045 3027 2045 3028 2044 3028 2043 3028 2045 3029 2043 3029 2046 3029 2046 3030 2043 3030 2042 3030 1575 3031 1574 3031 2044 3031 2044 3032 1574 3032 1582 3032 2044 3033 1582 3033 1581 3033 2026 3034 2024 3034 2027 3034 2027 3035 2024 3035 2023 3035 2027 3036 2023 3036 2028 3036 2028 3037 2023 3037 2021 3037 2028 3038 2021 3038 401 3038 401 3039 2021 3039 402 3039 1581 3040 1580 3040 2044 3040 2044 3041 1580 3041 1579 3041 2044 3042 1579 3042 2047 3042 2047 3043 1579 3043 1578 3043 2047 3044 1578 3044 2048 3044 1585 3045 1986 3045 1578 3045 1578 3046 1986 3046 2049 3046 1578 3047 2049 3047 2048 3047 1585 3048 1584 3048 1986 3048 1986 3049 1584 3049 1583 3049 1986 3050 1583 3050 1863 3050 1863 3051 1583 3051 1549 3051 1863 3052 1549 3052 1548 3052 1548 3053 1592 3053 1863 3053 1863 3054 1592 3054 1591 3054 1863 3055 1591 3055 1590 3055 1878 3056 1877 3056 1590 3056 1877 3057 1876 3057 1590 3057 1590 3058 1876 3058 1864 3058 1590 3059 1864 3059 1863 3059 1878 3060 1590 3060 1871 3060 1871 3061 1590 3061 1589 3061 1871 3062 1589 3062 1588 3062 2050 3063 2051 3063 1869 3063 1869 3064 2051 3064 2052 3064 1869 3065 2052 3065 1870 3065 1870 3066 2052 3066 2053 3066 1870 3067 2053 3067 2054 3067 2055 3068 2056 3068 1869 3068 1869 3069 2056 3069 2057 3069 1869 3070 2057 3070 2050 3070 1588 3071 1587 3071 1871 3071 1871 3072 1587 3072 1586 3072 1871 3073 1586 3073 1872 3073 1872 3074 1586 3074 1550 3074 1872 3075 1550 3075 1873 3075 1873 3076 1550 3076 2055 3076 1873 3077 2055 3077 1874 3077 1874 3078 2055 3078 1869 3078 2058 3079 2059 3079 2060 3079 2061 3080 2062 3080 2063 3080 2064 3081 1870 3081 2061 3081 2061 3082 1870 3082 2054 3082 2061 3083 2054 3083 2062 3083 2063 3084 2058 3084 2061 3084 2061 3085 2058 3085 2060 3085 2061 3086 2060 3086 2064 3086 2064 3087 2060 3087 382 3087 2064 3088 382 3088 381 3088 2065 3089 2066 3089 2067 3089 2067 3090 2066 3090 2068 3090 2067 3091 2068 3091 2069 3091 2068 3092 2070 3092 2069 3092 2069 3093 2070 3093 2071 3093 2069 3094 2071 3094 2072 3094 2072 3095 2071 3095 2073 3095 2072 3096 2073 3096 2074 3096 2074 3097 2073 3097 2075 3097 2074 3098 2075 3098 2076 3098 2076 3099 2075 3099 2077 3099 2076 3100 2077 3100 2078 3100 2078 3101 2077 3101 2079 3101 2078 3102 2079 3102 2080 3102 2079 3103 2081 3103 2080 3103 2080 3104 2081 3104 2082 3104 2080 3105 2082 3105 2083 3105 2083 3106 2082 3106 2084 3106 2083 3107 2084 3107 2085 3107 2085 3108 2084 3108 2086 3108 2085 3109 2086 3109 2087 3109 2087 3110 2086 3110 2088 3110 2087 3111 2088 3111 2089 3111 2089 3112 2088 3112 2090 3112 2089 3113 2090 3113 2065 3113 2065 3114 2090 3114 2091 3114 2065 3115 2091 3115 2066 3115 2067 3116 2092 3116 2065 3116 2065 3117 2092 3117 2093 3117 2065 3118 2093 3118 2089 3118 2089 3119 2093 3119 2094 3119 2089 3120 2094 3120 2087 3120 2087 3121 2094 3121 2095 3121 2087 3122 2095 3122 2085 3122 2085 3123 2095 3123 2096 3123 2085 3124 2096 3124 2083 3124 2083 3125 2096 3125 2097 3125 2083 3126 2097 3126 2080 3126 2080 3127 2097 3127 2098 3127 2080 3128 2098 3128 2078 3128 2078 3129 2098 3129 2099 3129 2078 3130 2099 3130 2076 3130 2076 3131 2099 3131 2100 3131 2076 3132 2100 3132 2074 3132 2074 3133 2100 3133 2101 3133 2074 3134 2101 3134 2072 3134 2072 3135 2101 3135 2102 3135 2072 3136 2102 3136 2069 3136 2069 3137 2102 3137 2103 3137 2069 3138 2103 3138 2067 3138 2067 3139 2103 3139 2092 3139 1732 3140 2104 3140 2105 3140 2106 3141 2107 3141 2108 3141 2109 3142 2110 3142 2111 3142 2112 3143 2113 3143 2110 3143 2109 3144 2114 3144 2110 3144 2110 3145 2114 3145 2115 3145 2110 3146 2115 3146 2112 3146 2116 3147 2117 3147 2118 3147 2118 3148 2117 3148 2119 3148 2120 3149 2121 3149 2118 3149 2118 3150 2121 3150 2122 3150 2118 3151 2122 3151 2116 3151 2107 3152 2123 3152 2108 3152 2108 3153 2123 3153 2124 3153 2108 3154 2124 3154 2120 3154 2120 3155 2124 3155 2125 3155 2120 3156 2125 3156 2121 3156 2126 3157 2127 3157 2128 3157 2128 3158 2127 3158 1628 3158 2128 3159 1628 3159 1627 3159 1634 3160 1626 3160 2129 3160 2129 3161 1626 3161 1625 3161 2129 3162 1625 3162 2127 3162 2127 3163 1625 3163 1629 3163 2127 3164 1629 3164 1628 3164 2119 3165 2109 3165 2118 3165 2118 3166 2109 3166 2111 3166 2118 3167 2111 3167 2120 3167 2120 3168 2111 3168 2130 3168 1635 3169 1634 3169 2105 3169 2105 3170 1634 3170 2129 3170 2105 3171 2129 3171 2131 3171 2130 3172 2131 3172 2120 3172 2120 3173 2131 3173 2129 3173 2120 3174 2129 3174 2108 3174 2108 3175 2129 3175 2127 3175 2108 3176 2127 3176 2106 3176 2106 3177 2127 3177 2126 3177 1635 3178 2105 3178 1637 3178 1637 3179 2105 3179 2104 3179 1637 3180 2104 3180 1639 3180 1732 3181 2105 3181 2132 3181 2132 3182 2105 3182 2131 3182 2132 3183 2131 3183 1742 3183 1742 3184 2131 3184 2130 3184 1742 3185 2130 3185 2133 3185 2133 3186 2130 3186 2111 3186 2133 3187 2111 3187 1734 3187 1734 3188 2111 3188 2110 3188 1734 3189 2110 3189 1707 3189 1707 3190 2110 3190 2113 3190 1707 3191 2113 3191 1735 3191 1627 3192 2082 3192 2134 3192 2134 3193 2082 3193 2081 3193 2134 3194 2081 3194 2135 3194 2135 3195 2081 3195 2136 3195 2136 3196 2081 3196 2137 3196 2137 3197 2081 3197 2079 3197 2137 3198 2079 3198 2138 3198 2139 3199 2140 3199 2077 3199 2077 3200 2140 3200 2141 3200 2077 3201 2141 3201 2079 3201 2079 3202 2141 3202 2142 3202 2079 3203 2142 3203 2138 3203 2139 3204 2077 3204 2143 3204 2143 3205 2077 3205 2075 3205 2143 3206 2075 3206 2144 3206 2145 3207 2146 3207 2073 3207 2073 3208 2146 3208 2147 3208 2073 3209 2147 3209 2075 3209 2075 3210 2147 3210 2148 3210 2075 3211 2148 3211 2144 3211 2149 3212 2150 3212 2151 3212 2152 3213 1753 3213 1752 3213 1749 3214 1696 3214 1695 3214 2153 3215 1746 3215 1745 3215 2152 3216 1752 3216 2154 3216 1746 3217 2153 3217 1751 3217 1751 3218 2153 3218 2151 3218 1751 3219 2151 3219 1752 3219 1752 3220 2151 3220 2150 3220 1752 3221 2150 3221 2154 3221 2155 3222 2156 3222 2157 3222 2157 3223 2156 3223 2158 3223 2158 3224 2156 3224 2159 3224 2159 3225 2156 3225 2160 3225 2159 3226 2160 3226 2161 3226 2162 3227 2163 3227 2164 3227 2164 3228 2163 3228 2165 3228 2164 3229 2165 3229 2166 3229 2167 3230 2162 3230 2168 3230 2168 3231 2162 3231 2164 3231 2168 3232 2164 3232 2160 3232 2160 3233 2164 3233 2166 3233 2160 3234 2166 3234 2161 3234 2169 3235 2170 3235 2171 3235 1661 3236 2172 3236 1662 3236 1662 3237 2172 3237 2173 3237 2170 3238 2169 3238 2173 3238 2173 3239 2169 3239 1699 3239 2173 3240 1699 3240 1662 3240 1694 3241 2174 3241 1695 3241 1695 3242 2174 3242 1747 3242 1695 3243 1747 3243 1749 3243 2175 3244 2153 3244 2174 3244 2174 3245 2153 3245 1745 3245 2174 3246 1745 3246 1747 3246 2176 3247 1692 3247 2177 3247 2177 3248 1692 3248 2178 3248 2177 3249 2178 3249 2169 3249 2169 3250 2178 3250 2179 3250 2169 3251 2179 3251 1699 3251 1694 3252 2176 3252 2174 3252 2174 3253 2176 3253 2177 3253 2174 3254 2177 3254 2175 3254 2175 3255 2177 3255 2169 3255 2175 3256 2169 3256 2180 3256 2180 3257 2169 3257 2171 3257 2180 3258 2171 3258 2181 3258 2181 3259 2167 3259 2180 3259 2180 3260 2167 3260 2168 3260 2180 3261 2168 3261 2175 3261 2175 3262 2168 3262 2160 3262 2175 3263 2160 3263 2153 3263 2153 3264 2160 3264 2156 3264 2153 3265 2156 3265 2151 3265 2151 3266 2156 3266 2155 3266 2151 3267 2155 3267 2149 3267 2090 3268 2088 3268 1753 3268 1753 3269 2088 3269 2182 3269 1753 3270 2182 3270 1744 3270 2183 3271 2184 3271 2086 3271 2086 3272 2184 3272 2185 3272 2086 3273 2185 3273 2088 3273 2088 3274 2185 3274 2186 3274 2088 3275 2186 3275 2182 3275 2084 3276 2082 3276 1627 3276 2183 3277 2086 3277 2187 3277 2187 3278 2086 3278 2084 3278 2187 3279 2084 3279 2188 3279 2188 3280 2084 3280 1627 3280 2188 3281 1627 3281 1624 3281 2145 3282 2073 3282 2189 3282 2189 3283 2073 3283 2071 3283 2189 3284 2071 3284 2190 3284 2191 3285 2070 3285 2192 3285 2192 3286 2070 3286 2068 3286 2192 3287 2068 3287 2193 3287 2191 3288 2194 3288 2070 3288 2070 3289 2194 3289 2195 3289 2070 3290 2195 3290 2071 3290 2071 3291 2195 3291 2196 3291 2071 3292 2196 3292 2190 3292 2091 3293 2197 3293 2066 3293 2066 3294 2197 3294 2198 3294 2066 3295 2198 3295 2068 3295 2068 3296 2198 3296 2199 3296 2068 3297 2199 3297 2193 3297 1753 3298 2200 3298 2090 3298 2090 3299 2200 3299 2201 3299 2090 3300 2201 3300 2091 3300 2091 3301 2201 3301 2202 3301 2091 3302 2202 3302 2197 3302 2094 3303 2203 3303 2095 3303 2095 3304 2203 3304 2204 3304 2095 3305 2204 3305 2096 3305 2096 3306 2204 3306 2205 3306 2096 3307 2205 3307 2097 3307 2097 3308 2205 3308 2206 3308 2097 3309 2206 3309 2098 3309 2098 3310 2206 3310 2207 3310 2098 3311 2207 3311 2099 3311 2099 3312 2207 3312 2208 3312 2099 3313 2208 3313 2100 3313 2100 3314 2208 3314 2209 3314 2100 3315 2209 3315 2101 3315 2101 3316 2209 3316 2210 3316 2101 3317 2210 3317 2102 3317 2102 3318 2210 3318 2211 3318 2102 3319 2211 3319 2103 3319 2103 3320 2211 3320 2212 3320 2103 3321 2212 3321 2092 3321 2092 3322 2212 3322 2213 3322 2092 3323 2213 3323 2093 3323 2093 3324 2213 3324 2214 3324 2093 3325 2214 3325 2094 3325 2094 3326 2214 3326 2203 3326 2142 3327 2141 3327 2215 3327 1793 3328 1792 3328 2216 3328 2216 3329 1792 3329 1735 3329 2216 3330 1735 3330 2113 3330 1797 3331 1793 3331 2217 3331 2217 3332 1793 3332 2216 3332 2217 3333 2216 3333 2218 3333 2218 3334 2216 3334 2219 3334 2220 3335 2221 3335 2222 3335 2220 3336 2144 3336 2221 3336 2221 3337 2144 3337 2148 3337 2221 3338 2148 3338 2223 3338 2223 3339 2148 3339 2147 3339 2141 3340 2140 3340 2215 3340 2215 3341 2140 3341 2139 3341 2215 3342 2139 3342 2220 3342 2220 3343 2139 3343 2143 3343 2220 3344 2143 3344 2144 3344 2138 3345 2125 3345 2124 3345 2138 3346 2124 3346 2137 3346 2124 3347 2123 3347 2137 3347 2137 3348 2123 3348 2107 3348 2137 3349 2107 3349 2136 3349 2136 3350 2107 3350 2106 3350 2136 3351 2106 3351 2135 3351 2135 3352 2106 3352 2126 3352 2135 3353 2126 3353 2134 3353 2134 3354 2126 3354 2128 3354 2134 3355 2128 3355 1627 3355 2138 3356 2142 3356 2125 3356 2125 3357 2142 3357 2215 3357 2125 3358 2215 3358 2121 3358 2121 3359 2215 3359 2122 3359 2109 3360 2220 3360 2219 3360 2219 3361 2220 3361 2222 3361 2219 3362 2222 3362 2218 3362 2109 3363 2119 3363 2220 3363 2220 3364 2119 3364 2117 3364 2220 3365 2117 3365 2215 3365 2215 3366 2117 3366 2116 3366 2215 3367 2116 3367 2122 3367 2113 3368 2112 3368 2216 3368 2216 3369 2112 3369 2115 3369 2216 3370 2115 3370 2219 3370 2219 3371 2115 3371 2114 3371 2219 3372 2114 3372 2109 3372 2192 3373 2193 3373 2157 3373 2157 3374 2193 3374 2199 3374 2157 3375 2199 3375 2155 3375 2155 3376 2199 3376 2198 3376 2155 3377 2198 3377 2149 3377 2157 3378 2158 3378 2192 3378 2192 3379 2158 3379 2224 3379 2192 3380 2224 3380 2191 3380 2191 3381 2224 3381 2225 3381 2191 3382 2225 3382 2194 3382 2194 3383 2225 3383 2195 3383 2195 3384 2225 3384 2226 3384 2195 3385 2226 3385 2196 3385 2146 3386 2145 3386 2227 3386 2227 3387 2145 3387 2189 3387 2227 3388 2189 3388 2226 3388 2226 3389 2189 3389 2190 3389 2226 3390 2190 3390 2196 3390 2147 3391 2146 3391 2223 3391 2223 3392 2146 3392 2227 3392 2223 3393 2227 3393 2221 3393 2221 3394 2227 3394 2222 3394 1796 3395 1797 3395 2228 3395 2228 3396 1797 3396 2217 3396 1796 3397 2228 3397 1794 3397 1794 3398 2228 3398 2229 3398 1794 3399 2229 3399 1798 3399 2172 3400 1661 3400 1790 3400 2230 3401 1800 3401 2229 3401 2229 3402 1800 3402 1799 3402 2229 3403 1799 3403 1798 3403 2181 3404 2171 3404 2230 3404 2230 3405 2171 3405 2170 3405 1790 3406 1800 3406 2172 3406 2172 3407 1800 3407 2230 3407 2172 3408 2230 3408 2173 3408 2173 3409 2230 3409 2170 3409 2163 3410 2162 3410 2231 3410 2231 3411 2162 3411 2167 3411 2158 3412 2159 3412 2224 3412 2224 3413 2159 3413 2161 3413 2224 3414 2161 3414 2225 3414 2225 3415 2161 3415 2166 3415 2225 3416 2166 3416 2165 3416 2198 3417 2197 3417 2149 3417 2149 3418 2197 3418 2202 3418 2149 3419 2202 3419 2150 3419 2150 3420 2202 3420 2201 3420 2150 3421 2201 3421 2154 3421 2154 3422 2201 3422 2152 3422 2152 3423 2201 3423 2200 3423 2152 3424 2200 3424 1753 3424 2228 3425 2232 3425 2229 3425 2229 3426 2232 3426 2233 3426 2229 3427 2233 3427 2230 3427 2230 3428 2233 3428 2231 3428 2230 3429 2231 3429 2181 3429 2181 3430 2231 3430 2167 3430 2217 3431 2218 3431 2228 3431 2228 3432 2218 3432 2222 3432 2228 3433 2222 3433 2232 3433 2232 3434 2222 3434 2227 3434 2232 3435 2227 3435 2233 3435 2233 3436 2227 3436 2226 3436 2233 3437 2226 3437 2231 3437 2231 3438 2226 3438 2225 3438 2231 3439 2225 3439 2163 3439 2163 3440 2225 3440 2165 3440 370 3441 1028 3441 365 3441 365 3442 1028 3442 371 3442 1033 3443 1036 3443 2234 3443 1033 3444 2234 3444 1025 3444 1116 3445 2235 3445 1036 3445 1036 3446 2235 3446 2236 3446 1036 3447 2236 3447 2234 3447 2237 3448 375 3448 2238 3448 2238 3449 375 3449 360 3449 1028 3450 1026 3450 371 3450 371 3451 1026 3451 1025 3451 371 3452 1025 3452 362 3452 362 3453 1025 3453 2234 3453 362 3454 2234 3454 360 3454 360 3455 2234 3455 2239 3455 360 3456 2239 3456 2238 3456 388 3457 378 3457 2240 3457 2240 3458 378 3458 2241 3458 2241 3459 378 3459 372 3459 2241 3460 372 3460 2237 3460 2237 3461 372 3461 374 3461 2237 3462 374 3462 375 3462 1866 3463 1870 3463 2064 3463 1866 3464 2064 3464 1867 3464 388 3465 2240 3465 2242 3465 2242 3466 2240 3466 2243 3466 2242 3467 2243 3467 2244 3467 1867 3468 2064 3468 653 3468 653 3469 2064 3469 381 3469 653 3470 381 3470 380 3470 380 3471 2245 3471 653 3471 653 3472 2245 3472 2246 3472 653 3473 2246 3473 2244 3473 2244 3474 2246 3474 2247 3474 2244 3475 2247 3475 2242 3475 1892 3476 1891 3476 2248 3476 2249 3477 2250 3477 2251 3477 1298 3478 1297 3478 2250 3478 1968 3479 1966 3479 2252 3479 1776 3480 2249 3480 1772 3480 1772 3481 2249 3481 1773 3481 1776 3482 1313 3482 1312 3482 1624 3483 2249 3483 2188 3483 2188 3484 2249 3484 2187 3484 1624 3485 1636 3485 2249 3485 2249 3486 1636 3486 1774 3486 2249 3487 1774 3487 1773 3487 1831 3488 1832 3488 2248 3488 2248 3489 1832 3489 1748 3489 1748 3490 1744 3490 2248 3490 2248 3491 1744 3491 2182 3491 2248 3492 2182 3492 2253 3492 2253 3493 2182 3493 2186 3493 2186 3494 2185 3494 2253 3494 2253 3495 2185 3495 2184 3495 2253 3496 2184 3496 2183 3496 1831 3497 2248 3497 1828 3497 1828 3498 2248 3498 1891 3498 1828 3499 1891 3499 1829 3499 1975 3500 1910 3500 1909 3500 1975 3501 1909 3501 1976 3501 1976 3502 1909 3502 1908 3502 1976 3503 1908 3503 1907 3503 1968 3504 2252 3504 1970 3504 1970 3505 2252 3505 1972 3505 1972 3506 2252 3506 2251 3506 1972 3507 2251 3507 1973 3507 2250 3508 1960 3508 1962 3508 2250 3509 1962 3509 2251 3509 2251 3510 1962 3510 1964 3510 2251 3511 1964 3511 1973 3511 1297 3512 1318 3512 1957 3512 1957 3513 1318 3513 1317 3513 1957 3514 1317 3514 1316 3514 1297 3515 1957 3515 2250 3515 2250 3516 1957 3516 1959 3516 2250 3517 1959 3517 1960 3517 1776 3518 1312 3518 2249 3518 2249 3519 1312 3519 1354 3519 2249 3520 1354 3520 2250 3520 2250 3521 1354 3521 1355 3521 2250 3522 1355 3522 1298 3522 1906 3523 2252 3523 1907 3523 1907 3524 2252 3524 1966 3524 1907 3525 1966 3525 1976 3525 1906 3526 1892 3526 2252 3526 2252 3527 1892 3527 2248 3527 2252 3528 2248 3528 2251 3528 2251 3529 2248 3529 2253 3529 2251 3530 2253 3530 2249 3530 2249 3531 2253 3531 2183 3531 2249 3532 2183 3532 2187 3532 388 3533 2242 3533 386 3533 386 3534 2242 3534 2247 3534 386 3535 2247 3535 385 3535 385 3536 2247 3536 2246 3536 385 3537 2246 3537 383 3537 383 3538 2246 3538 2245 3538 383 3539 2245 3539 380 3539 1113 3540 1112 3540 1919 3540 2235 3541 1116 3541 1115 3541 1115 3542 1113 3542 2235 3542 2235 3543 1113 3543 1919 3543 2235 3544 1919 3544 2236 3544 2236 3545 1919 3545 1918 3545 2236 3546 1918 3546 2234 3546 2234 3547 1918 3547 1917 3547 2234 3548 1917 3548 2239 3548 2239 3549 1917 3549 1916 3549 2239 3550 1916 3550 2238 3550 2238 3551 1916 3551 1920 3551 2238 3552 1920 3552 2237 3552 2237 3553 1920 3553 1923 3553 2237 3554 1923 3554 2241 3554 2241 3555 1923 3555 1922 3555 2241 3556 1922 3556 2240 3556 2240 3557 1922 3557 1921 3557 2240 3558 1921 3558 2243 3558 2243 3559 1921 3559 1912 3559 2243 3560 1912 3560 2244 3560 2244 3561 1912 3561 1911 3561 2244 3562 1911 3562 653 3562 653 3563 1924 3563 1903 3563 1903 3564 1924 3564 651 3564 1903 3565 651 3565 1904 3565 651 3566 1374 3566 1904 3566 1904 3567 1374 3567 1373 3567 1904 3568 1373 3568 1905 3568 1905 3569 1373 3569 1372 3569 1905 3570 1372 3570 1902 3570 1902 3571 1372 3571 1376 3571 1902 3572 1376 3572 1901 3572 1901 3573 1376 3573 1378 3573 1901 3574 1378 3574 1385 3574 2254 3575 2213 3575 2255 3575 2255 3576 2213 3576 2212 3576 2255 3577 2212 3577 2256 3577 2256 3578 2212 3578 2211 3578 2256 3579 2211 3579 2257 3579 2257 3580 2211 3580 2210 3580 2257 3581 2210 3581 2258 3581 2258 3582 2210 3582 2209 3582 2258 3583 2209 3583 2259 3583 2259 3584 2209 3584 2208 3584 2259 3585 2208 3585 2260 3585 2260 3586 2208 3586 2207 3586 2260 3587 2207 3587 2261 3587 2261 3588 2207 3588 2206 3588 2261 3589 2206 3589 2262 3589 2262 3590 2206 3590 2205 3590 2262 3591 2205 3591 2263 3591 2263 3592 2205 3592 2204 3592 2263 3593 2204 3593 2264 3593 2264 3594 2204 3594 2203 3594 2264 3595 2203 3595 2265 3595 2265 3596 2203 3596 2214 3596 2265 3597 2214 3597 2254 3597 2254 3598 2214 3598 2213 3598 2266 3599 2267 3599 1931 3599 1931 3600 2267 3600 2268 3600 1931 3601 2268 3601 1927 3601 1927 3602 2268 3602 1353 3602 1927 3603 1353 3603 1926 3603 1926 3604 1353 3604 1352 3604 1926 3605 1352 3605 1929 3605 1931 3606 1933 3606 2266 3606 2266 3607 1933 3607 1936 3607 2266 3608 1936 3608 2269 3608 2269 3609 1936 3609 1993 3609 1936 3610 1935 3610 1993 3610 1993 3611 1935 3611 1939 3611 1993 3612 1939 3612 1994 3612 1994 3613 1939 3613 1938 3613 1994 3614 1938 3614 2000 3614 925 3615 929 3615 2017 3615 2000 3616 1938 3616 2001 3616 2001 3617 1938 3617 1943 3617 2001 3618 1943 3618 2004 3618 2004 3619 1943 3619 1944 3619 2004 3620 1944 3620 2005 3620 2005 3621 1944 3621 1945 3621 2005 3622 1945 3622 2007 3622 2007 3623 1945 3623 1946 3623 2007 3624 1946 3624 2010 3624 2010 3625 1946 3625 1948 3625 2010 3626 1948 3626 2011 3626 2011 3627 1948 3627 1951 3627 2011 3628 1951 3628 2013 3628 2013 3629 1951 3629 1950 3629 2013 3630 1950 3630 2015 3630 1952 3631 928 3631 926 3631 1950 3632 1954 3632 2015 3632 2015 3633 1954 3633 1953 3633 2015 3634 1953 3634 2016 3634 2016 3635 1953 3635 1952 3635 2016 3636 1952 3636 2017 3636 2017 3637 1952 3637 926 3637 2017 3638 926 3638 925 3638 2270 3639 2271 3639 2272 3639 2272 3640 2271 3640 221 3640 2272 3641 221 3641 406 3641 2273 3642 2274 3642 2275 3642 2275 3643 2274 3643 2276 3643 2275 3644 2276 3644 2277 3644 2277 3645 2276 3645 2278 3645 2277 3646 2278 3646 2279 3646 2279 3647 2278 3647 2271 3647 2279 3648 2271 3648 2280 3648 2280 3649 2271 3649 2270 3649 2281 3650 2282 3650 1279 3650 2273 3651 2281 3651 2274 3651 2274 3652 2281 3652 1279 3652 2274 3653 1279 3653 2283 3653 2283 3654 1279 3654 437 3654 2283 3655 437 3655 436 3655 460 3656 1280 3656 462 3656 462 3657 1280 3657 2284 3657 1280 3658 1279 3658 2284 3658 2284 3659 1279 3659 2282 3659 2285 3660 2286 3660 1499 3660 2287 3661 2288 3661 2289 3661 2289 3662 2288 3662 2290 3662 2289 3663 2290 3663 2291 3663 2290 3664 2292 3664 2291 3664 2291 3665 2292 3665 2293 3665 2291 3666 2293 3666 2294 3666 2294 3667 2293 3667 2295 3667 2294 3668 2295 3668 2296 3668 2296 3669 2295 3669 2297 3669 2296 3670 2297 3670 2298 3670 2299 3671 2300 3671 2301 3671 2302 3672 2303 3672 2304 3672 2304 3673 2303 3673 2305 3673 1481 3674 1480 3674 2306 3674 2306 3675 1480 3675 1464 3675 2306 3676 1464 3676 2301 3676 2301 3677 1464 3677 1465 3677 2301 3678 1465 3678 2299 3678 2307 3679 2308 3679 1483 3679 1483 3680 2308 3680 2309 3680 1483 3681 2309 3681 1499 3681 1499 3682 2309 3682 2310 3682 1499 3683 2310 3683 2285 3683 2303 3684 2301 3684 2305 3684 2305 3685 2301 3685 2300 3685 2305 3686 2300 3686 2311 3686 2311 3687 2300 3687 2298 3687 2311 3688 2298 3688 2312 3688 2312 3689 2298 3689 2297 3689 2307 3690 1483 3690 2306 3690 2306 3691 1483 3691 1482 3691 2306 3692 1482 3692 1481 3692 1439 3693 1440 3693 2313 3693 2313 3694 1440 3694 2314 3694 1438 3695 1439 3695 2315 3695 2315 3696 1439 3696 2313 3696 2316 3697 2317 3697 2318 3697 2318 3698 2317 3698 2319 3698 2318 3699 2319 3699 2320 3699 2320 3700 2321 3700 2318 3700 2318 3701 2321 3701 1327 3701 2318 3702 1327 3702 1326 3702 2322 3703 2323 3703 2324 3703 2324 3704 2323 3704 2325 3704 2324 3705 2325 3705 1351 3705 1351 3706 2325 3706 2326 3706 1351 3707 2326 3707 1326 3707 1326 3708 2326 3708 2327 3708 1326 3709 2327 3709 2318 3709 2318 3710 2327 3710 2328 3710 2318 3711 2328 3711 2316 3711 1351 3712 1353 3712 2324 3712 2324 3713 1353 3713 2329 3713 2324 3714 2329 3714 2330 3714 2331 3715 2332 3715 2330 3715 2330 3716 2332 3716 2333 3716 2330 3717 2333 3717 2324 3717 2324 3718 2333 3718 2334 3718 2324 3719 2334 3719 2322 3719 2335 3720 2336 3720 2337 3720 2337 3721 2336 3721 2331 3721 2337 3722 2331 3722 2338 3722 2338 3723 2331 3723 2330 3723 2338 3724 2330 3724 2339 3724 2339 3725 2330 3725 2329 3725 2339 3726 2329 3726 2268 3726 2268 3727 2329 3727 1353 3727 2266 3728 2269 3728 2340 3728 2340 3729 2269 3729 1993 3729 2341 3730 2342 3730 2343 3730 2343 3731 2342 3731 2335 3731 2268 3732 2267 3732 2339 3732 2339 3733 2267 3733 2344 3733 2339 3734 2344 3734 2338 3734 2338 3735 2344 3735 2343 3735 2338 3736 2343 3736 2337 3736 2337 3737 2343 3737 2335 3737 2345 3738 2341 3738 2346 3738 2346 3739 2341 3739 2343 3739 2346 3740 2343 3740 2340 3740 2340 3741 2343 3741 2344 3741 2340 3742 2344 3742 2266 3742 2266 3743 2344 3743 2267 3743 1993 3744 2347 3744 2340 3744 2340 3745 2347 3745 2348 3745 2340 3746 2348 3746 2346 3746 2346 3747 2348 3747 2349 3747 2346 3748 2349 3748 2345 3748 2345 3749 2349 3749 2350 3749 2345 3750 2350 3750 2351 3750 1993 3751 1992 3751 2347 3751 2347 3752 1992 3752 2352 3752 2314 3753 2353 3753 2354 3753 2354 3754 2353 3754 2355 3754 2354 3755 2355 3755 2351 3755 1992 3756 1995 3756 2352 3756 2352 3757 1995 3757 2356 3757 2352 3758 2356 3758 2354 3758 2354 3759 2356 3759 2357 3759 2354 3760 2357 3760 2314 3760 2314 3761 2357 3761 2313 3761 2351 3762 2350 3762 2354 3762 2354 3763 2350 3763 2349 3763 2354 3764 2349 3764 2352 3764 2352 3765 2349 3765 2348 3765 2352 3766 2348 3766 2347 3766 2358 3767 1996 3767 1998 3767 1438 3768 2315 3768 2359 3768 2359 3769 2315 3769 2360 3769 2359 3770 2360 3770 2361 3770 2361 3771 2360 3771 2358 3771 2361 3772 2358 3772 2362 3772 2362 3773 2358 3773 1998 3773 1995 3774 1996 3774 2356 3774 2356 3775 1996 3775 2358 3775 2356 3776 2358 3776 2357 3776 2357 3777 2358 3777 2360 3777 2357 3778 2360 3778 2313 3778 2313 3779 2360 3779 2315 3779 1435 3780 1438 3780 2359 3780 1435 3781 2359 3781 2363 3781 2359 3782 2361 3782 2363 3782 2363 3783 2361 3783 2362 3783 2363 3784 2362 3784 1999 3784 1999 3785 2362 3785 1998 3785 2364 3786 1427 3786 1426 3786 80 3787 79 3787 2365 3787 2365 3788 79 3788 78 3788 2364 3789 1426 3789 78 3789 2018 3790 81 3790 80 3790 80 3791 2365 3791 2018 3791 2018 3792 2365 3792 2366 3792 2018 3793 2366 3793 2019 3793 2019 3794 2366 3794 2014 3794 2014 3795 2366 3795 2367 3795 2014 3796 2367 3796 2012 3796 2012 3797 2367 3797 2009 3797 2009 3798 2367 3798 2368 3798 2009 3799 2368 3799 2008 3799 2008 3800 2368 3800 2369 3800 2008 3801 2369 3801 2006 3801 78 3802 1426 3802 2365 3802 2365 3803 1426 3803 1434 3803 2365 3804 1434 3804 2366 3804 2366 3805 1434 3805 1433 3805 2366 3806 1433 3806 2367 3806 2367 3807 1433 3807 1432 3807 2367 3808 1432 3808 2368 3808 2368 3809 1432 3809 1430 3809 2368 3810 1430 3810 2369 3810 2369 3811 1430 3811 1429 3811 2369 3812 1429 3812 2370 3812 2370 3813 1429 3813 1435 3813 2370 3814 1435 3814 2363 3814 2006 3815 2369 3815 2002 3815 2002 3816 2369 3816 2370 3816 2002 3817 2370 3817 2003 3817 2003 3818 2370 3818 2363 3818 2003 3819 2363 3819 1999 3819 300 3820 1981 3820 1980 3820 290 3821 1978 3821 1977 3821 310 3822 313 3822 2371 3822 2371 3823 313 3823 312 3823 311 3824 2372 3824 312 3824 312 3825 2372 3825 2373 3825 312 3826 2373 3826 2371 3826 1990 3827 1991 3827 2374 3827 1955 3828 1988 3828 254 3828 254 3829 1988 3829 1989 3829 254 3830 1989 3830 260 3830 260 3831 1989 3831 1990 3831 260 3832 1990 3832 262 3832 262 3833 1990 3833 2374 3833 262 3834 2374 3834 263 3834 254 3835 256 3835 1955 3835 1955 3836 256 3836 258 3836 1955 3837 258 3837 1956 3837 1956 3838 258 3838 267 3838 1956 3839 267 3839 1958 3839 1958 3840 267 3840 269 3840 1958 3841 269 3841 1961 3841 1961 3842 269 3842 271 3842 1961 3843 271 3843 1963 3843 1963 3844 271 3844 274 3844 1963 3845 274 3845 1971 3845 1971 3846 274 3846 275 3846 1971 3847 275 3847 1969 3847 275 3848 278 3848 1969 3848 1969 3849 278 3849 279 3849 1969 3850 279 3850 1967 3850 1967 3851 279 3851 281 3851 1967 3852 281 3852 1965 3852 1965 3853 281 3853 283 3853 1965 3854 283 3854 1974 3854 1974 3855 283 3855 285 3855 1974 3856 285 3856 1977 3856 1977 3857 285 3857 288 3857 1977 3858 288 3858 290 3858 1978 3859 290 3859 1979 3859 1979 3860 290 3860 296 3860 1979 3861 296 3861 1980 3861 1980 3862 296 3862 298 3862 1980 3863 298 3863 300 3863 1981 3864 300 3864 1982 3864 1982 3865 300 3865 302 3865 1982 3866 302 3866 1983 3866 302 3867 304 3867 1983 3867 1983 3868 304 3868 306 3868 1983 3869 306 3869 1984 3869 306 3870 308 3870 1984 3870 1984 3871 308 3871 310 3871 1984 3872 310 3872 1985 3872 1985 3873 310 3873 2371 3873 1985 3874 2371 3874 1987 3874 2372 3875 311 3875 295 3875 1986 3876 1987 3876 2049 3876 2049 3877 1987 3877 2371 3877 2049 3878 2371 3878 2373 3878 323 3879 509 3879 324 3879 324 3880 509 3880 325 3880 2033 3881 403 3881 2021 3881 2021 3882 403 3882 402 3882 2372 3883 295 3883 2373 3883 2373 3884 295 3884 294 3884 2373 3885 294 3885 2049 3885 2049 3886 294 3886 292 3886 2049 3887 292 3887 2048 3887 2048 3888 292 3888 291 3888 2048 3889 291 3889 2047 3889 2047 3890 291 3890 314 3890 2047 3891 314 3891 2044 3891 2044 3892 314 3892 316 3892 2044 3893 316 3893 2043 3893 2043 3894 316 3894 319 3894 2043 3895 319 3895 2041 3895 2041 3896 319 3896 318 3896 2041 3897 318 3897 2037 3897 318 3898 328 3898 2037 3898 2037 3899 328 3899 326 3899 2037 3900 326 3900 2035 3900 2035 3901 326 3901 325 3901 2035 3902 325 3902 2033 3902 2033 3903 325 3903 509 3903 2033 3904 509 3904 403 3904 2375 3905 266 3905 265 3905 2375 3906 265 3906 2376 3906 2376 3907 265 3907 2377 3907 2377 3908 265 3908 2378 3908 2377 3909 2378 3909 2379 3909 2295 3910 2293 3910 2379 3910 265 3911 264 3911 2378 3911 2378 3912 264 3912 259 3912 2378 3913 259 3913 2380 3913 2380 3914 259 3914 261 3914 2380 3915 261 3915 2381 3915 2381 3916 261 3916 263 3916 2381 3917 263 3917 2382 3917 2379 3918 2378 3918 2295 3918 2295 3919 2378 3919 2380 3919 2295 3920 2380 3920 2297 3920 2297 3921 2380 3921 2381 3921 2297 3922 2381 3922 2312 3922 2312 3923 2381 3923 2382 3923 2312 3924 2382 3924 2311 3924 2304 3925 2305 3925 2383 3925 2383 3926 2305 3926 2384 3926 2383 3927 2384 3927 2385 3927 2374 3928 1991 3928 2384 3928 2384 3929 1991 3929 2386 3929 2384 3930 2386 3930 2385 3930 263 3931 2374 3931 2382 3931 2382 3932 2374 3932 2384 3932 2382 3933 2384 3933 2311 3933 2311 3934 2384 3934 2305 3934 2387 3935 2388 3935 2286 3935 2286 3936 2388 3936 2389 3936 2286 3937 2389 3937 2390 3937 2390 3938 2391 3938 2286 3938 2286 3939 2391 3939 2392 3939 2286 3940 2392 3940 2393 3940 2393 3941 2394 3941 2286 3941 2286 3942 2394 3942 2395 3942 2286 3943 2395 3943 1499 3943 2387 3944 2286 3944 2396 3944 2396 3945 2286 3945 2397 3945 2396 3946 2397 3946 2398 3946 2398 3947 2399 3947 2396 3947 2396 3948 2399 3948 2400 3948 2396 3949 2400 3949 2401 3949 2402 3950 2403 3950 2383 3950 2383 3951 2403 3951 2404 3951 2302 3952 2304 3952 2405 3952 2405 3953 2304 3953 2383 3953 2405 3954 2383 3954 2406 3954 2406 3955 2383 3955 2404 3955 2407 3956 2408 3956 2386 3956 1340 3957 2409 3957 1341 3957 1341 3958 2409 3958 2410 3958 1341 3959 2410 3959 1342 3959 2407 3960 2386 3960 2411 3960 2401 3961 2402 3961 2396 3961 2396 3962 2402 3962 2383 3962 2396 3963 2383 3963 2408 3963 2408 3964 2383 3964 2385 3964 2408 3965 2385 3965 2386 3965 2386 3966 1991 3966 1324 3966 1324 3967 1323 3967 2386 3967 2386 3968 1323 3968 1322 3968 2386 3969 1322 3969 1321 3969 1321 3970 1346 3970 2386 3970 2386 3971 1346 3971 1345 3971 2386 3972 1345 3972 1344 3972 2410 3973 2411 3973 1342 3973 1342 3974 2411 3974 2386 3974 1342 3975 2386 3975 1343 3975 1343 3976 2386 3976 1344 3976 2412 3977 2413 3977 2414 3977 2413 3978 2415 3978 2414 3978 2414 3979 2415 3979 2416 3979 2414 3980 2416 3980 1437 3980 1437 3981 2416 3981 1441 3981 2412 3982 2414 3982 2417 3982 2417 3983 2414 3983 2418 3983 2417 3984 2418 3984 2419 3984 2420 3985 2421 3985 2422 3985 2420 3986 2422 3986 2418 3986 2418 3987 2422 3987 2423 3987 2418 3988 2423 3988 2419 3988 2394 3989 2424 3989 2395 3989 2395 3990 2424 3990 2425 3990 2395 3991 2425 3991 2420 3991 2420 3992 2425 3992 2426 3992 2420 3993 2426 3993 2421 3993 1437 3994 1436 3994 2414 3994 2414 3995 1436 3995 1490 3995 2414 3996 1490 3996 2418 3996 2418 3997 1490 3997 1485 3997 2418 3998 1485 3998 2420 3998 2420 3999 1485 3999 1500 3999 2420 4000 1500 4000 2395 4000 2395 4001 1500 4001 1499 4001 2422 4002 2427 4002 2428 4002 2417 4003 2429 4003 2430 4003 2431 4004 1441 4004 2416 4004 2431 4005 2416 4005 2432 4005 2432 4006 2416 4006 2415 4006 2432 4007 2415 4007 2433 4007 2433 4008 2415 4008 2434 4008 2434 4009 2415 4009 2413 4009 2434 4010 2413 4010 2430 4010 2430 4011 2413 4011 2412 4011 2430 4012 2412 4012 2417 4012 2429 4013 2417 4013 2435 4013 2435 4014 2417 4014 2419 4014 2435 4015 2419 4015 2428 4015 2428 4016 2419 4016 2423 4016 2428 4017 2423 4017 2422 4017 2427 4018 2422 4018 2436 4018 2436 4019 2422 4019 2421 4019 2436 4020 2421 4020 2437 4020 2421 4021 2426 4021 2437 4021 2437 4022 2426 4022 2425 4022 2437 4023 2425 4023 2438 4023 2438 4024 2425 4024 2424 4024 2438 4025 2424 4025 2439 4025 2439 4026 2424 4026 2394 4026 2431 4027 2314 4027 1441 4027 1441 4028 2314 4028 1440 4028 2433 4029 2434 4029 2440 4029 2353 4030 2314 4030 2431 4030 2433 4031 2440 4031 2432 4031 2393 4032 2392 4032 2441 4032 2436 4033 2437 4033 2442 4033 2442 4034 2437 4034 2438 4034 2442 4035 2438 4035 2393 4035 2393 4036 2438 4036 2439 4036 2393 4037 2439 4037 2394 4037 2436 4038 2442 4038 2427 4038 2427 4039 2442 4039 2443 4039 2427 4040 2443 4040 2428 4040 2434 4041 2430 4041 2440 4041 2440 4042 2430 4042 2429 4042 2440 4043 2429 4043 2443 4043 2443 4044 2429 4044 2435 4044 2443 4045 2435 4045 2428 4045 2393 4046 2441 4046 2442 4046 2442 4047 2441 4047 2444 4047 2442 4048 2444 4048 2443 4048 2444 4049 2445 4049 2443 4049 2443 4050 2445 4050 2446 4050 2443 4051 2446 4051 2440 4051 2440 4052 2446 4052 2447 4052 2440 4053 2447 4053 2351 4053 2431 4054 2432 4054 2353 4054 2353 4055 2432 4055 2440 4055 2353 4056 2440 4056 2355 4056 2355 4057 2440 4057 2351 4057 2392 4058 2391 4058 2441 4058 2441 4059 2391 4059 2448 4059 2441 4060 2448 4060 2444 4060 2444 4061 2448 4061 2445 4061 2445 4062 2448 4062 2449 4062 2445 4063 2449 4063 2446 4063 2449 4064 2341 4064 2345 4064 2446 4065 2449 4065 2447 4065 2447 4066 2449 4066 2345 4066 2447 4067 2345 4067 2351 4067 2450 4068 2449 4068 2451 4068 2451 4069 2449 4069 2448 4069 2451 4070 2448 4070 2390 4070 2390 4071 2448 4071 2391 4071 2450 4072 2335 4072 2449 4072 2449 4073 2335 4073 2342 4073 2449 4074 2342 4074 2341 4074 2336 4075 2335 4075 2452 4075 2452 4076 2335 4076 2450 4076 2452 4077 2450 4077 2453 4077 2453 4078 2450 4078 2451 4078 2388 4079 2453 4079 2389 4079 2389 4080 2453 4080 2451 4080 2389 4081 2451 4081 2390 4081 2331 4082 2336 4082 2454 4082 2454 4083 2336 4083 2452 4083 2454 4084 2452 4084 2455 4084 2455 4085 2452 4085 2453 4085 2455 4086 2453 4086 2456 4086 2456 4087 2453 4087 2388 4087 2320 4088 1329 4088 2321 4088 2321 4089 1329 4089 1328 4089 2321 4090 1328 4090 1327 4090 2317 4091 1332 4091 2319 4091 2319 4092 1332 4092 1331 4092 2319 4093 1331 4093 2320 4093 2320 4094 1331 4094 1330 4094 2320 4095 1330 4095 1329 4095 1338 4096 1337 4096 2457 4096 2457 4097 1337 4097 1336 4097 2457 4098 1336 4098 1335 4098 1338 4099 2457 4099 1339 4099 1339 4100 2457 4100 2458 4100 1339 4101 2458 4101 1340 4101 2459 4102 2460 4102 2326 4102 2326 4103 2460 4103 2458 4103 2326 4104 2458 4104 2327 4104 2327 4105 2458 4105 2457 4105 2327 4106 2457 4106 2328 4106 2328 4107 2457 4107 1335 4107 2328 4108 1335 4108 2316 4108 2316 4109 1335 4109 1334 4109 2316 4110 1334 4110 2317 4110 2317 4111 1334 4111 1333 4111 2317 4112 1333 4112 1332 4112 2326 4113 2325 4113 2459 4113 2459 4114 2325 4114 2323 4114 2459 4115 2323 4115 2322 4115 2334 4116 2461 4116 2322 4116 2322 4117 2461 4117 2462 4117 2322 4118 2462 4118 2459 4118 1340 4119 2458 4119 2409 4119 2409 4120 2458 4120 2460 4120 2409 4121 2460 4121 2410 4121 2410 4122 2460 4122 2459 4122 2410 4123 2459 4123 2411 4123 2411 4124 2459 4124 2462 4124 2411 4125 2462 4125 2407 4125 2407 4126 2462 4126 2461 4126 2407 4127 2461 4127 2408 4127 2334 4128 2333 4128 2461 4128 2461 4129 2333 4129 2332 4129 2461 4130 2332 4130 2463 4130 2463 4131 2332 4131 2331 4131 2331 4132 2454 4132 2463 4132 2463 4133 2454 4133 2455 4133 2463 4134 2455 4134 2456 4134 2408 4135 2461 4135 2396 4135 2396 4136 2461 4136 2463 4136 2396 4137 2463 4137 2387 4137 2387 4138 2463 4138 2456 4138 2387 4139 2456 4139 2388 4139 2464 4140 2288 4140 2287 4140 2464 4141 2287 4141 2465 4141 2287 4142 2466 4142 2465 4142 2465 4143 2466 4143 2467 4143 2465 4144 2467 4144 2468 4144 2468 4145 2467 4145 2469 4145 2468 4146 2469 4146 2470 4146 2469 4147 2471 4147 2470 4147 2470 4148 2471 4148 2472 4148 2470 4149 2472 4149 2473 4149 2473 4150 2472 4150 2474 4150 2475 4151 2476 4151 2477 4151 2477 4152 2476 4152 2478 4152 2477 4153 2478 4153 2474 4153 2474 4154 2478 4154 2479 4154 2474 4155 2479 4155 2473 4155 2475 4156 2480 4156 2476 4156 2476 4157 2480 4157 2481 4157 2476 4158 2481 4158 2482 4158 2482 4159 2481 4159 2483 4159 2483 4160 2484 4160 2482 4160 2482 4161 2484 4161 2485 4161 2482 4162 2485 4162 2486 4162 2486 4163 2485 4163 2487 4163 2488 4164 2489 4164 2490 4164 2490 4165 2489 4165 2491 4165 2490 4166 2491 4166 2482 4166 2482 4167 2491 4167 2492 4167 2482 4168 2492 4168 2476 4168 2488 4169 2493 4169 2489 4169 2489 4170 2493 4170 2494 4170 2489 4171 2494 4171 2495 4171 2495 4172 2494 4172 2496 4172 158 4173 163 4173 2497 4173 2497 4174 163 4174 246 4174 2497 4175 246 4175 2494 4175 2494 4176 246 4176 248 4176 2494 4177 248 4177 2496 4177 2498 4178 2499 4178 2500 4178 2487 4179 2485 4179 2500 4179 2500 4180 2485 4180 2501 4180 2500 4181 2501 4181 2498 4181 2299 4182 1465 4182 2502 4182 2502 4183 1465 4183 2500 4183 2502 4184 2500 4184 2503 4184 2503 4185 2500 4185 2499 4185 1444 4186 1449 4186 2504 4186 2504 4187 1449 4187 1425 4187 2487 4188 2505 4188 2486 4188 2500 4189 1465 4189 1463 4189 2486 4190 2505 4190 2482 4190 2482 4191 2505 4191 2506 4191 2482 4192 2506 4192 2490 4192 2507 4193 2493 4193 2488 4193 2508 4194 2497 4194 2494 4194 2490 4195 2509 4195 2488 4195 2488 4196 2509 4196 2510 4196 2488 4197 2510 4197 2507 4197 2507 4198 2510 4198 2511 4198 2507 4199 2511 4199 2512 4199 2512 4200 2511 4200 1425 4200 1425 4201 2513 4201 2512 4201 2512 4202 2513 4202 2508 4202 2512 4203 2508 4203 2507 4203 2507 4204 2508 4204 2494 4204 2507 4205 2494 4205 2493 4205 158 4206 2497 4206 2514 4206 2514 4207 2497 4207 2508 4207 2514 4208 2508 4208 2515 4208 2515 4209 2508 4209 2513 4209 2515 4210 2513 4210 2516 4210 2516 4211 2513 4211 1425 4211 1444 4212 2504 4212 1455 4212 1455 4213 2504 4213 2517 4213 1455 4214 2517 4214 1452 4214 1452 4215 2517 4215 2506 4215 1452 4216 2506 4216 1459 4216 2490 4217 2506 4217 2509 4217 2509 4218 2506 4218 2517 4218 2509 4219 2517 4219 2510 4219 2510 4220 2517 4220 2504 4220 2510 4221 2504 4221 2511 4221 2511 4222 2504 4222 1425 4222 1459 4223 2506 4223 1461 4223 1461 4224 2506 4224 2505 4224 1461 4225 2505 4225 1463 4225 1463 4226 2505 4226 2487 4226 1463 4227 2487 4227 2500 4227 1425 4228 1419 4228 2516 4228 2516 4229 1419 4229 1420 4229 2516 4230 1420 4230 2515 4230 2515 4231 1420 4231 2514 4231 2514 4232 1420 4232 159 4232 2514 4233 159 4233 158 4233 1508 4234 1509 4234 2518 4234 2518 4235 1509 4235 2519 4235 2520 4236 2521 4236 2522 4236 2522 4237 2521 4237 2523 4237 2522 4238 2523 4238 2519 4238 2519 4239 2523 4239 2524 4239 2519 4240 2524 4240 2518 4240 2525 4241 2526 4241 2527 4241 2527 4242 2528 4242 2525 4242 2525 4243 2528 4243 2529 4243 2525 4244 2529 4244 2530 4244 2530 4245 2529 4245 2531 4245 2530 4246 2531 4246 2520 4246 2520 4247 2531 4247 2532 4247 2520 4248 2532 4248 2521 4248 2526 4249 2525 4249 2533 4249 2533 4250 2525 4250 2293 4250 2533 4251 2293 4251 2292 4251 1502 4252 2534 4252 2535 4252 529 4253 530 4253 2536 4253 2536 4254 530 4254 590 4254 529 4255 2535 4255 528 4255 528 4256 2535 4256 2534 4256 528 4257 2534 4257 527 4257 529 4258 2536 4258 2535 4258 2535 4259 2536 4259 2537 4259 2535 4260 2537 4260 2538 4260 2538 4261 2537 4261 2539 4261 2538 4262 2539 4262 2540 4262 2293 4263 2525 4263 2379 4263 2379 4264 2525 4264 2539 4264 2379 4265 2539 4265 2377 4265 2377 4266 2539 4266 2537 4266 2377 4267 2537 4267 2376 4267 2376 4268 2537 4268 2536 4268 2376 4269 2536 4269 2375 4269 2375 4270 2536 4270 590 4270 2375 4271 590 4271 266 4271 2525 4272 2530 4272 2539 4272 2539 4273 2530 4273 2520 4273 2539 4274 2520 4274 2540 4274 2540 4275 2520 4275 2522 4275 2540 4276 2522 4276 2519 4276 1502 4277 2535 4277 1503 4277 1503 4278 2535 4278 2538 4278 1503 4279 2538 4279 1511 4279 1511 4280 2538 4280 2540 4280 1511 4281 2540 4281 1510 4281 1510 4282 2540 4282 2519 4282 1510 4283 2519 4283 1509 4283 1847 4284 1826 4284 2255 4284 1716 4285 1717 4285 1412 4285 1412 4286 1717 4286 1722 4286 1722 4287 1721 4287 1412 4287 1412 4288 1721 4288 1719 4288 1412 4289 1719 4289 1802 4289 1712 4290 1713 4290 1303 4290 2256 4291 1838 4291 2255 4291 2255 4292 1838 4292 1839 4292 1839 4293 1841 4293 2255 4293 2255 4294 1841 4294 1843 4294 2255 4295 1843 4295 1847 4295 1411 4296 1412 4296 2262 4296 1802 4297 1806 4297 1412 4297 1412 4298 1806 4298 1805 4298 1412 4299 1805 4299 1809 4299 1899 4300 2254 4300 1900 4300 1900 4301 2254 4301 2255 4301 1900 4302 2255 4302 1825 4302 1825 4303 2255 4303 1826 4303 1349 4304 1348 4304 1347 4304 1812 4305 2258 4305 1808 4305 1808 4306 2258 4306 2259 4306 1808 4307 2259 4307 1809 4307 1809 4308 2259 4308 2260 4308 1809 4309 2260 4309 1412 4309 1412 4310 2260 4310 2261 4310 1412 4311 2261 4311 2262 4311 1899 4312 1898 4312 2254 4312 2254 4313 1898 4313 1897 4313 2254 4314 1897 4314 1385 4314 1786 4315 1785 4315 1630 4315 1630 4316 1785 4316 1783 4316 1303 4317 1713 4317 1304 4317 1304 4318 1713 4318 1714 4318 1304 4319 1714 4319 1347 4319 1820 4320 2256 4320 2257 4320 1820 4321 1664 4321 2256 4321 2256 4322 1664 4322 1663 4322 2256 4323 1663 4323 1671 4323 1812 4324 1811 4324 2258 4324 2258 4325 1811 4325 1817 4325 2258 4326 1817 4326 1816 4326 1816 4327 1814 4327 2258 4327 2258 4328 1814 4328 1813 4328 2258 4329 1813 4329 2257 4329 2257 4330 1813 4330 1819 4330 2257 4331 1819 4331 1820 4331 1411 4332 2262 4332 1409 4332 1409 4333 2262 4333 2263 4333 1409 4334 2263 4334 1407 4334 1403 4335 1395 4335 2264 4335 2264 4336 1395 4336 1394 4336 2264 4337 1394 4337 2263 4337 2263 4338 1394 4338 1405 4338 2263 4339 1405 4339 1407 4339 1385 4340 1386 4340 2254 4340 2254 4341 1386 4341 1387 4341 2254 4342 1387 4342 2265 4342 2265 4343 1387 4343 1389 4343 2265 4344 1389 4344 1388 4344 1303 4345 1778 4345 1712 4345 1712 4346 1778 4346 1779 4346 1712 4347 1779 4347 1630 4347 1630 4348 1779 4348 1781 4348 1630 4349 1781 4349 1786 4349 1388 4350 1401 4350 2265 4350 2265 4351 1401 4351 1392 4351 2265 4352 1392 4352 2264 4352 2264 4353 1392 4353 1391 4353 2264 4354 1391 4354 1403 4354 1783 4355 1782 4355 1630 4355 1630 4356 1782 4356 1769 4356 1630 4357 1769 4357 1631 4357 1716 4358 1412 4358 1715 4358 1715 4359 1412 4359 2541 4359 1715 4360 2541 4360 1714 4360 1671 4361 1669 4361 2256 4361 2256 4362 1669 4362 1667 4362 2256 4363 1667 4363 1838 4363 1838 4364 1667 4364 1666 4364 1714 4365 2541 4365 1347 4365 1347 4366 2541 4366 2542 4366 1347 4367 2542 4367 1349 4367 1349 4368 2542 4368 2543 4368 1349 4369 2543 4369 1350 4369 1704 4370 1756 4370 1836 4370 1666 4371 1684 4371 1838 4371 1838 4372 1684 4372 1704 4372 1838 4373 1704 4373 1837 4373 1837 4374 1704 4374 1836 4374 813 4375 819 4375 2544 4375 817 4376 154 4376 156 4376 817 4377 156 4377 818 4377 811 4378 816 4378 2545 4378 2545 4379 816 4379 815 4379 806 4380 807 4380 2546 4380 2546 4381 807 4381 809 4381 806 4382 2546 4382 804 4382 804 4383 2546 4383 2283 4383 804 4384 2283 4384 436 4384 2547 4385 222 4385 221 4385 221 4386 2271 4386 2547 4386 2547 4387 2271 4387 2278 4387 2547 4388 2278 4388 2548 4388 2548 4389 2278 4389 2276 4389 2548 4390 2276 4390 2546 4390 2546 4391 2276 4391 2274 4391 2546 4392 2274 4392 2283 4392 809 4393 811 4393 2546 4393 2546 4394 811 4394 2545 4394 2546 4395 2545 4395 2548 4395 2548 4396 2545 4396 2549 4396 2548 4397 2549 4397 2547 4397 2547 4398 2549 4398 2550 4398 2547 4399 2550 4399 222 4399 222 4400 2550 4400 225 4400 815 4401 813 4401 2545 4401 2545 4402 813 4402 2544 4402 2545 4403 2544 4403 2549 4403 2549 4404 2544 4404 2551 4404 2549 4405 2551 4405 2550 4405 2550 4406 2551 4406 2552 4406 2550 4407 2552 4407 225 4407 225 4408 2552 4408 234 4408 819 4409 818 4409 2544 4409 2544 4410 818 4410 156 4410 2544 4411 156 4411 2551 4411 2551 4412 156 4412 157 4412 2551 4413 157 4413 2552 4413 2552 4414 157 4414 150 4414 2552 4415 150 4415 234 4415 234 4416 150 4416 149 4416 523 4417 522 4417 2553 4417 2272 4418 406 4418 2554 4418 2554 4419 406 4419 891 4419 2554 4420 891 4420 2555 4420 2555 4421 891 4421 892 4421 2555 4422 892 4422 2553 4422 2553 4423 892 4423 820 4423 2553 4424 820 4424 523 4424 523 4425 820 4425 525 4425 2270 4426 2272 4426 2556 4426 2556 4427 2272 4427 2554 4427 2556 4428 2554 4428 2557 4428 2557 4429 2554 4429 2555 4429 2557 4430 2555 4430 2558 4430 2558 4431 2555 4431 2553 4431 2558 4432 2553 4432 527 4432 527 4433 2553 4433 522 4433 2280 4434 2270 4434 2559 4434 2559 4435 2270 4435 2556 4435 2559 4436 2556 4436 2560 4436 2560 4437 2556 4437 2557 4437 2560 4438 2557 4438 2561 4438 2561 4439 2557 4439 2558 4439 2561 4440 2558 4440 2534 4440 2534 4441 2558 4441 527 4441 2279 4442 2280 4442 2562 4442 2562 4443 2280 4443 2559 4443 2562 4444 2559 4444 2563 4444 2563 4445 2559 4445 2560 4445 2563 4446 2560 4446 2564 4446 2564 4447 2560 4447 2561 4447 2564 4448 2561 4448 1502 4448 1502 4449 2561 4449 2534 4449 2277 4450 2279 4450 2562 4450 2273 4451 2275 4451 2565 4451 2566 4452 2567 4452 2568 4452 2568 4453 2567 4453 2569 4453 2568 4454 2569 4454 2570 4454 2570 4455 2569 4455 2571 4455 2571 4456 2569 4456 2572 4456 2571 4457 2572 4457 2573 4457 2573 4458 2572 4458 1507 4458 2573 4459 1507 4459 1506 4459 2566 4460 2282 4460 2567 4460 2567 4461 2282 4461 2281 4461 2567 4462 2281 4462 2273 4462 2277 4463 2562 4463 2275 4463 2273 4464 2565 4464 2567 4464 2567 4465 2565 4465 2574 4465 2567 4466 2574 4466 2569 4466 2569 4467 2574 4467 2575 4467 2569 4468 2575 4468 2572 4468 2572 4469 2575 4469 1501 4469 2572 4470 1501 4470 1507 4470 2275 4471 2562 4471 2565 4471 2565 4472 2562 4472 2563 4472 2565 4473 2563 4473 2574 4473 2574 4474 2563 4474 2564 4474 2574 4475 2564 4475 2575 4475 2575 4476 2564 4476 1502 4476 2575 4477 1502 4477 1501 4477 2571 4478 2576 4478 2570 4478 2570 4479 2576 4479 2577 4479 2570 4480 2577 4480 2568 4480 2568 4481 2577 4481 2578 4481 2568 4482 2578 4482 2566 4482 2566 4483 2578 4483 2284 4483 2566 4484 2284 4484 2282 4484 2571 4485 2573 4485 2576 4485 2576 4486 2573 4486 1506 4486 2576 4487 1506 4487 1505 4487 462 4488 2284 4488 2578 4488 462 4489 2578 4489 893 4489 893 4490 2578 4490 2577 4490 893 4491 2577 4491 911 4491 911 4492 2577 4492 2576 4492 911 4493 2576 4493 912 4493 912 4494 2576 4494 1505 4494 912 4495 1505 4495 913 4495 245 4496 244 4496 2579 4496 2579 4497 244 4497 250 4497 2496 4498 248 4498 247 4498 2580 4499 2581 4499 2582 4499 2583 4500 2584 4500 2585 4500 2585 4501 2584 4501 2586 4501 2585 4502 2586 4502 2587 4502 504 4503 503 4503 2588 4503 247 4504 2589 4504 2496 4504 2496 4505 2589 4505 2590 4505 2496 4506 2590 4506 2495 4506 249 4507 496 4507 250 4507 250 4508 496 4508 495 4508 250 4509 495 4509 2579 4509 2579 4510 495 4510 494 4510 2579 4511 494 4511 2591 4511 2591 4512 494 4512 493 4512 2591 4513 493 4513 2592 4513 2592 4514 493 4514 492 4514 491 4515 2593 4515 492 4515 492 4516 2593 4516 2594 4516 492 4517 2594 4517 2592 4517 2495 4518 2590 4518 2489 4518 2489 4519 2590 4519 2595 4519 2489 4520 2595 4520 2491 4520 2491 4521 2595 4521 2596 4521 2491 4522 2596 4522 2492 4522 491 4523 497 4523 2593 4523 2593 4524 497 4524 499 4524 2593 4525 499 4525 2597 4525 2597 4526 499 4526 508 4526 2597 4527 508 4527 2598 4527 2492 4528 2596 4528 2476 4528 2476 4529 2596 4529 2599 4529 2476 4530 2599 4530 2478 4530 2478 4531 2599 4531 2600 4531 2478 4532 2600 4532 2479 4532 2479 4533 2600 4533 2601 4533 2479 4534 2601 4534 2473 4534 508 4535 507 4535 2598 4535 2598 4536 507 4536 506 4536 2598 4537 506 4537 2602 4537 2602 4538 506 4538 505 4538 2602 4539 505 4539 2603 4539 2603 4540 505 4540 504 4540 2603 4541 504 4541 2585 4541 2585 4542 504 4542 2588 4542 2585 4543 2588 4543 2583 4543 245 4544 2579 4544 247 4544 247 4545 2579 4545 2591 4545 247 4546 2591 4546 2589 4546 2589 4547 2591 4547 2592 4547 2589 4548 2592 4548 2590 4548 2590 4549 2592 4549 2594 4549 2590 4550 2594 4550 2595 4550 2595 4551 2594 4551 2593 4551 2595 4552 2593 4552 2596 4552 2596 4553 2593 4553 2597 4553 2596 4554 2597 4554 2599 4554 2599 4555 2597 4555 2598 4555 2599 4556 2598 4556 2600 4556 2600 4557 2598 4557 2602 4557 2600 4558 2602 4558 2601 4558 2601 4559 2602 4559 2603 4559 2601 4560 2603 4560 2604 4560 2604 4561 2603 4561 2585 4561 2604 4562 2585 4562 2580 4562 2580 4563 2585 4563 2587 4563 2580 4564 2587 4564 2581 4564 2605 4565 2580 4565 2606 4565 2606 4566 2580 4566 2582 4566 2606 4567 2582 4567 2607 4567 2473 4568 2601 4568 2470 4568 2470 4569 2601 4569 2604 4569 2470 4570 2604 4570 2468 4570 2468 4571 2604 4571 2580 4571 2468 4572 2580 4572 2465 4572 2465 4573 2580 4573 2605 4573 2465 4574 2605 4574 2464 4574 2606 4575 2607 4575 2608 4575 2608 4576 2609 4576 2606 4576 2606 4577 2609 4577 2610 4577 2606 4578 2610 4578 2605 4578 2288 4579 2464 4579 2611 4579 2611 4580 2464 4580 2605 4580 2611 4581 2605 4581 2612 4581 2612 4582 2605 4582 2610 4582 2290 4583 2288 4583 2611 4583 2613 4584 2614 4584 2615 4584 2533 4585 2616 4585 2526 4585 2526 4586 2616 4586 2527 4586 2612 4587 2610 4587 2617 4587 2613 4588 2615 4588 2618 4588 2292 4589 2615 4589 2533 4589 2533 4590 2615 4590 2614 4590 2533 4591 2614 4591 2616 4591 2292 4592 2290 4592 2615 4592 2615 4593 2290 4593 2611 4593 2615 4594 2611 4594 2618 4594 2618 4595 2611 4595 2612 4595 2618 4596 2612 4596 2619 4596 2619 4597 2612 4597 2617 4597 894 4598 1504 4598 2620 4598 894 4599 2620 4599 914 4599 914 4600 2620 4600 503 4600 914 4601 503 4601 500 4601 1504 4602 1508 4602 2620 4602 2620 4603 1508 4603 2621 4603 2620 4604 2621 4604 503 4604 503 4605 2621 4605 2588 4605 2614 4606 2613 4606 2622 4606 2609 4607 2608 4607 2622 4607 2609 4608 2622 4608 2610 4608 2617 4609 2610 4609 2619 4609 2619 4610 2610 4610 2622 4610 2619 4611 2622 4611 2618 4611 2618 4612 2622 4612 2613 4612 2614 4613 2622 4613 2616 4613 2616 4614 2622 4614 2528 4614 2616 4615 2528 4615 2527 4615 2529 4616 2528 4616 2623 4616 2623 4617 2528 4617 2622 4617 2623 4618 2622 4618 2607 4618 2607 4619 2622 4619 2608 4619 2529 4620 2623 4620 2531 4620 2531 4621 2623 4621 2624 4621 2531 4622 2624 4622 2532 4622 2581 4623 2587 4623 2625 4623 2521 4624 2532 4624 2625 4624 2625 4625 2532 4625 2624 4625 2625 4626 2624 4626 2581 4626 2581 4627 2624 4627 2623 4627 2581 4628 2623 4628 2582 4628 2582 4629 2623 4629 2607 4629 2587 4630 2586 4630 2625 4630 2625 4631 2586 4631 2584 4631 2625 4632 2584 4632 2626 4632 2626 4633 2584 4633 2583 4633 2626 4634 2583 4634 2627 4634 2627 4635 2583 4635 2588 4635 2627 4636 2588 4636 2621 4636 2521 4637 2625 4637 2523 4637 2523 4638 2625 4638 2626 4638 2523 4639 2626 4639 2524 4639 2524 4640 2626 4640 2627 4640 2524 4641 2627 4641 2518 4641 2518 4642 2627 4642 2621 4642 2518 4643 2621 4643 1508 4643 18 4644 34 4644 32 4644 32 4645 30 4645 20 4645 20 4646 30 4646 28 4646 5 4647 18 4647 6 4647 6 4648 18 4648 32 4648 6 4649 32 4649 19 4649 19 4650 32 4650 20 4650 28 4651 26 4651 20 4651 20 4652 26 4652 24 4652 20 4653 24 4653 22 4653 1015 4654 1013 4654 1011 4654 996 4655 179 4655 177 4655 1008 4656 985 4656 990 4656 990 4657 996 4657 1008 4657 1008 4658 996 4658 177 4658 1008 4659 177 4659 1009 4659 1009 4660 177 4660 176 4660 143 4661 1019 4661 141 4661 141 4662 1019 4662 1017 4662 1017 4663 1015 4663 141 4663 141 4664 1015 4664 1011 4664 141 4665 1011 4665 183 4665 183 4666 1011 4666 1009 4666 183 4667 1009 4667 185 4667 185 4668 1009 4668 176 4668 1416 4669 1423 4669 2628 4669 1428 4670 1415 4670 1431 4670 1431 4671 1415 4671 1416 4671 1431 4672 1416 4672 1491 4672 1491 4673 1416 4673 2628 4673 1448 4674 2629 4674 1424 4674 1424 4675 2629 4675 1418 4675 1424 4676 1418 4676 1417 4676 1450 4677 1456 4677 2630 4677 2630 4678 1456 4678 1474 4678 2630 4679 1474 4679 1475 4679 1475 4680 1473 4680 2630 4680 2630 4681 1473 4681 1472 4681 2630 4682 1472 4682 1488 4682 2631 4683 1445 4683 1443 4683 1443 4684 1442 4684 2631 4684 2631 4685 1442 4685 1454 4685 2631 4686 1454 4686 2632 4686 2632 4687 1454 4687 1453 4687 2632 4688 1453 4688 2633 4688 2633 4689 1453 4689 1451 4689 2633 4690 1451 4690 2634 4690 2634 4691 1451 4691 1450 4691 2634 4692 1450 4692 2630 4692 1445 4693 2631 4693 1446 4693 1446 4694 2631 4694 2635 4694 1446 4695 2635 4695 1447 4695 1447 4696 2635 4696 2629 4696 1447 4697 2629 4697 1448 4697 1491 4698 2628 4698 1492 4698 1492 4699 2628 4699 2636 4699 2636 4700 2637 4700 1498 4700 1498 4701 1497 4701 2636 4701 2636 4702 1497 4702 1496 4702 2636 4703 1496 4703 1495 4703 1495 4704 1494 4704 2636 4704 2636 4705 1494 4705 1493 4705 2636 4706 1493 4706 1492 4706 2630 4707 1488 4707 2638 4707 2638 4708 1488 4708 1489 4708 1489 4709 1484 4709 2638 4709 2638 4710 1484 4710 1486 4710 2638 4711 1486 4711 2637 4711 2637 4712 1486 4712 1487 4712 2637 4713 1487 4713 1498 4713 2628 4714 2639 4714 2640 4714 2640 4715 2639 4715 2641 4715 2640 4716 2641 4716 2642 4716 2642 4717 2641 4717 2643 4717 2642 4718 2643 4718 2644 4718 2645 4719 2646 4719 2641 4719 2641 4720 2646 4720 2647 4720 2641 4721 2647 4721 2643 4721 2643 4722 2647 4722 2648 4722 2643 4723 2648 4723 2629 4723 2628 4724 2649 4724 2636 4724 2636 4725 2649 4725 2650 4725 2636 4726 2650 4726 2637 4726 2637 4727 2650 4727 2651 4727 2637 4728 2651 4728 2638 4728 2638 4729 2651 4729 2634 4729 2638 4730 2634 4730 2630 4730 2628 4731 2640 4731 2649 4731 2649 4732 2640 4732 2642 4732 2649 4733 2642 4733 2650 4733 2650 4734 2642 4734 2644 4734 2650 4735 2644 4735 2651 4735 2651 4736 2644 4736 2633 4736 2651 4737 2633 4737 2634 4737 2645 4738 2641 4738 2652 4738 2652 4739 2641 4739 2639 4739 2652 4740 2639 4740 2628 4740 2629 4741 2635 4741 2643 4741 2643 4742 2635 4742 2631 4742 2643 4743 2631 4743 2644 4743 2644 4744 2631 4744 2632 4744 2644 4745 2632 4745 2633 4745 2629 4746 2648 4746 1418 4746 1418 4747 2648 4747 1421 4747 2648 4748 2647 4748 1421 4748 1421 4749 2647 4749 2646 4749 1421 4750 2646 4750 1422 4750 2628 4751 1423 4751 2652 4751 2652 4752 1423 4752 1422 4752 2652 4753 1422 4753 2645 4753 2645 4754 1422 4754 2646 4754 15 4755 37 4755 7 4755 7 4756 37 4756 36 4756 7 4757 36 4757 8 4757 117 4758 116 4758 41 4758 41 4759 116 4759 115 4759 41 4760 115 4760 36 4760 36 4761 115 4761 61 4761 36 4762 61 4762 8 4762 117 4763 41 4763 113 4763 113 4764 41 4764 43 4764 113 4765 43 4765 114 4765 123 4766 1428 4766 124 4766 124 4767 1428 4767 1427 4767 124 4768 1427 4768 125 4768 125 4769 1427 4769 2364 4769 125 4770 2364 4770 78 4770 123 4771 122 4771 1428 4771 1428 4772 122 4772 45 4772 1428 4773 45 4773 1415 4773 1415 4774 45 4774 47 4774 122 4775 57 4775 45 4775 45 4776 57 4776 56 4776 45 4777 56 4777 43 4777 43 4778 56 4778 107 4778 43 4779 107 4779 114 4779 2285 4780 1596 4780 2286 4780 2286 4781 1596 4781 1595 4781 2303 4782 2302 4782 1610 4782 1610 4783 1609 4783 2303 4783 2303 4784 1609 4784 1612 4784 2303 4785 1612 4785 2301 4785 1612 4786 1611 4786 2301 4786 2301 4787 1611 4787 1614 4787 2301 4788 1614 4788 2306 4788 1614 4789 1613 4789 2306 4789 2306 4790 1613 4790 1616 4790 2306 4791 1616 4791 2307 4791 1616 4792 1615 4792 2307 4792 2307 4793 1615 4793 1618 4793 2307 4794 1618 4794 2308 4794 2308 4795 1618 4795 1617 4795 2308 4796 1617 4796 2309 4796 1617 4797 1620 4797 2309 4797 2309 4798 1620 4798 1619 4798 2309 4799 1619 4799 2310 4799 1619 4800 1623 4800 2310 4800 2310 4801 1623 4801 1622 4801 2310 4802 1622 4802 2285 4802 2285 4803 1622 4803 1621 4803 2285 4804 1621 4804 1596 4804 2403 4805 2402 4805 1593 4805 2286 4806 1595 4806 1600 4806 2286 4807 1600 4807 2397 4807 2397 4808 1600 4808 1599 4808 2397 4809 1599 4809 2398 4809 1610 4810 2302 4810 1604 4810 1604 4811 2302 4811 2405 4811 1604 4812 2405 4812 1605 4812 1605 4813 2405 4813 2406 4813 1605 4814 2406 4814 1606 4814 1606 4815 2406 4815 2404 4815 1606 4816 2404 4816 1607 4816 1607 4817 2404 4817 2403 4817 1607 4818 2403 4818 1608 4818 1608 4819 2403 4819 1593 4819 1599 4820 1598 4820 2398 4820 2398 4821 1598 4821 1597 4821 2398 4822 1597 4822 2399 4822 2399 4823 1597 4823 1603 4823 2399 4824 1603 4824 2400 4824 2400 4825 1603 4825 1602 4825 2400 4826 1602 4826 2401 4826 2401 4827 1602 4827 1601 4827 2401 4828 1601 4828 2402 4828 2402 4829 1601 4829 1594 4829 2402 4830 1594 4830 1593 4830 1534 4831 1537 4831 2299 4831 2299 4832 1537 4832 2300 4832 1512 4833 2287 4833 1544 4833 1544 4834 2287 4834 2289 4834 1537 4835 1536 4835 2300 4835 2300 4836 1536 4836 1539 4836 2300 4837 1539 4837 2298 4837 1539 4838 1538 4838 2298 4838 2298 4839 1538 4839 1543 4839 2298 4840 1543 4840 2296 4840 2296 4841 1543 4841 1542 4841 2296 4842 1542 4842 2294 4842 1542 4843 1541 4843 2294 4843 2294 4844 1541 4844 1540 4844 2294 4845 1540 4845 2291 4845 1540 4846 1547 4846 2291 4846 2291 4847 1547 4847 1546 4847 2291 4848 1546 4848 2289 4848 2289 4849 1546 4849 1545 4849 2289 4850 1545 4850 1544 4850 2467 4851 1515 4851 1514 4851 2467 4852 1514 4852 2469 4852 2469 4853 1514 4853 1523 4853 2469 4854 1523 4854 2471 4854 1523 4855 1522 4855 2471 4855 2471 4856 1522 4856 1521 4856 2471 4857 1521 4857 2472 4857 1534 4858 2299 4858 1535 4858 1535 4859 2299 4859 2502 4859 1515 4860 2467 4860 1516 4860 1516 4861 2467 4861 2466 4861 1516 4862 2466 4862 1513 4862 1513 4863 2466 4863 2287 4863 1513 4864 2287 4864 1512 4864 2472 4865 1521 4865 2474 4865 2474 4866 1521 4866 1517 4866 2474 4867 1517 4867 2477 4867 2477 4868 1517 4868 1518 4868 2477 4869 1518 4869 2475 4869 2475 4870 1518 4870 1519 4870 2475 4871 1519 4871 2480 4871 2480 4872 1519 4872 1520 4872 2480 4873 1520 4873 2481 4873 2481 4874 1520 4874 1524 4874 2481 4875 1524 4875 2483 4875 1524 4876 1525 4876 2483 4876 2483 4877 1525 4877 1529 4877 2483 4878 1529 4878 2484 4878 2484 4879 1529 4879 1528 4879 2484 4880 1528 4880 2485 4880 2485 4881 1528 4881 1527 4881 2485 4882 1527 4882 2501 4882 2501 4883 1527 4883 1526 4883 2501 4884 1526 4884 2498 4884 2498 4885 1526 4885 1533 4885 2498 4886 1533 4886 2499 4886 2499 4887 1533 4887 1532 4887 2499 4888 1532 4888 2503 4888 2503 4889 1532 4889 1531 4889 2503 4890 1531 4890 2502 4890 2502 4891 1531 4891 1530 4891 2502 4892 1530 4892 1535 4892 2045 4893 1576 4893 1575 4893 1576 4894 2045 4894 1577 4894 1552 4895 2653 4895 1551 4895 1551 4896 2653 4896 2055 4896 1551 4897 2055 4897 1550 4897 2654 4898 2057 4898 2653 4898 2653 4899 2057 4899 2056 4899 2653 4900 2056 4900 2055 4900 384 4901 382 4901 2060 4901 2063 4902 2655 4902 2058 4902 2058 4903 2655 4903 2059 4903 2063 4904 2062 4904 2655 4904 2655 4905 2062 4905 2054 4905 2655 4906 2054 4906 2053 4906 2025 4907 2030 4907 2656 4907 2025 4908 2656 4908 2026 4908 2657 4909 2022 4909 2656 4909 2656 4910 2022 4910 2024 4910 2656 4911 2024 4911 2026 4911 2030 4912 2029 4912 398 4912 398 4913 2029 4913 2028 4913 398 4914 2028 4914 401 4914 2032 4915 2031 4915 2657 4915 2657 4916 2031 4916 2020 4916 2657 4917 2020 4917 2022 4917 2036 4918 2034 4918 2658 4918 2658 4919 2034 4919 2032 4919 2039 4920 2038 4920 2659 4920 2659 4921 2038 4921 2036 4921 2659 4922 2036 4922 2660 4922 2046 4923 2042 4923 2661 4923 2661 4924 2042 4924 2040 4924 2045 4925 2046 4925 1577 4925 1577 4926 2046 4926 2661 4926 1577 4927 2661 4927 1573 4927 1573 4928 2661 4928 2662 4928 1568 4929 1567 4929 2662 4929 2662 4930 1567 4930 1572 4930 2662 4931 1572 4931 1573 4931 2662 4932 2663 4932 1568 4932 1568 4933 2663 4933 2664 4933 1568 4934 2664 4934 1569 4934 1569 4935 2664 4935 2665 4935 1562 4936 1571 4936 2665 4936 2665 4937 1571 4937 1570 4937 2665 4938 1570 4938 1569 4938 2665 4939 2666 4939 1562 4939 1562 4940 2666 4940 2667 4940 1562 4941 2667 4941 1563 4941 1563 4942 2667 4942 2668 4942 1566 4943 1565 4943 2668 4943 2668 4944 1565 4944 1564 4944 2668 4945 1564 4945 1563 4945 2668 4946 2669 4946 1566 4946 1566 4947 2669 4947 2670 4947 1566 4948 2670 4948 1557 4948 1557 4949 2670 4949 2671 4949 1557 4950 2671 4950 1558 4950 1558 4951 2671 4951 2672 4951 1561 4952 1560 4952 2672 4952 2672 4953 1560 4953 1559 4953 2672 4954 1559 4954 1558 4954 2030 4955 398 4955 2656 4955 2656 4956 398 4956 397 4956 2656 4957 397 4957 2673 4957 2673 4958 397 4958 396 4958 2673 4959 396 4959 2674 4959 2674 4960 396 4960 395 4960 2674 4961 395 4961 2675 4961 2675 4962 395 4962 394 4962 2675 4963 394 4963 2676 4963 2676 4964 394 4964 391 4964 2676 4965 391 4965 2677 4965 2677 4966 391 4966 377 4966 2677 4967 377 4967 2678 4967 2678 4968 377 4968 376 4968 2678 4969 376 4969 2679 4969 2679 4970 376 4970 379 4970 2679 4971 379 4971 2680 4971 2680 4972 379 4972 390 4972 2680 4973 390 4973 2681 4973 2681 4974 390 4974 389 4974 2681 4975 389 4975 2682 4975 2682 4976 389 4976 387 4976 2682 4977 387 4977 2683 4977 2683 4978 387 4978 384 4978 2683 4979 384 4979 2655 4979 2655 4980 384 4980 2060 4980 2655 4981 2060 4981 2059 4981 2032 4982 2657 4982 2658 4982 2658 4983 2657 4983 2656 4983 2658 4984 2656 4984 2684 4984 2684 4985 2656 4985 2673 4985 2684 4986 2673 4986 2685 4986 2685 4987 2673 4987 2674 4987 2685 4988 2674 4988 2686 4988 2686 4989 2674 4989 2675 4989 2686 4990 2675 4990 2687 4990 2687 4991 2675 4991 2676 4991 2687 4992 2676 4992 2688 4992 2688 4993 2676 4993 2677 4993 2688 4994 2677 4994 2689 4994 2689 4995 2677 4995 2678 4995 2689 4996 2678 4996 2690 4996 2690 4997 2678 4997 2679 4997 2690 4998 2679 4998 2691 4998 2691 4999 2679 4999 2680 4999 2691 5000 2680 5000 2692 5000 2692 5001 2680 5001 2681 5001 2692 5002 2681 5002 2693 5002 2693 5003 2681 5003 2682 5003 2693 5004 2682 5004 2694 5004 2694 5005 2682 5005 2683 5005 2694 5006 2683 5006 2695 5006 2695 5007 2683 5007 2655 5007 2695 5008 2655 5008 2696 5008 2696 5009 2655 5009 2053 5009 2696 5010 2053 5010 2052 5010 2672 5011 2697 5011 1561 5011 1561 5012 2697 5012 2698 5012 1561 5013 2698 5013 1553 5013 1553 5014 2698 5014 2699 5014 1553 5015 2699 5015 1554 5015 2036 5016 2658 5016 2660 5016 2660 5017 2658 5017 2684 5017 2660 5018 2684 5018 2700 5018 2700 5019 2684 5019 2685 5019 2700 5020 2685 5020 2701 5020 2701 5021 2685 5021 2686 5021 2701 5022 2686 5022 2702 5022 2702 5023 2686 5023 2687 5023 2702 5024 2687 5024 2703 5024 2703 5025 2687 5025 2688 5025 2703 5026 2688 5026 2704 5026 2704 5027 2688 5027 2689 5027 2704 5028 2689 5028 2705 5028 2705 5029 2689 5029 2690 5029 2705 5030 2690 5030 2706 5030 2706 5031 2690 5031 2691 5031 2706 5032 2691 5032 2707 5032 2707 5033 2691 5033 2692 5033 2707 5034 2692 5034 2708 5034 2708 5035 2692 5035 2693 5035 2708 5036 2693 5036 2709 5036 2709 5037 2693 5037 2694 5037 2709 5038 2694 5038 2710 5038 2710 5039 2694 5039 2695 5039 2710 5040 2695 5040 2711 5040 2711 5041 2695 5041 2696 5041 2711 5042 2696 5042 2712 5042 2712 5043 2696 5043 2052 5043 2712 5044 2052 5044 2713 5044 2713 5045 2052 5045 2051 5045 2713 5046 2051 5046 2050 5046 2039 5047 2659 5047 2714 5047 2714 5048 2659 5048 2660 5048 2714 5049 2660 5049 2715 5049 2715 5050 2660 5050 2700 5050 2715 5051 2700 5051 2716 5051 2716 5052 2700 5052 2701 5052 2716 5053 2701 5053 2717 5053 2717 5054 2701 5054 2702 5054 2717 5055 2702 5055 2718 5055 2718 5056 2702 5056 2703 5056 2718 5057 2703 5057 2719 5057 2719 5058 2703 5058 2704 5058 2719 5059 2704 5059 2720 5059 2720 5060 2704 5060 2705 5060 2720 5061 2705 5061 2721 5061 2721 5062 2705 5062 2706 5062 2721 5063 2706 5063 2722 5063 2722 5064 2706 5064 2707 5064 2722 5065 2707 5065 2723 5065 2723 5066 2707 5066 2708 5066 2723 5067 2708 5067 2724 5067 2724 5068 2708 5068 2709 5068 2724 5069 2709 5069 2725 5069 2725 5070 2709 5070 2710 5070 2725 5071 2710 5071 2726 5071 2726 5072 2710 5072 2711 5072 2726 5073 2711 5073 2727 5073 2727 5074 2711 5074 2712 5074 2727 5075 2712 5075 2728 5075 2728 5076 2712 5076 2713 5076 2728 5077 2713 5077 2654 5077 2654 5078 2713 5078 2050 5078 2654 5079 2050 5079 2057 5079 1554 5080 2699 5080 1555 5080 1555 5081 2699 5081 2729 5081 1555 5082 2729 5082 1556 5082 1552 5083 1556 5083 2653 5083 2653 5084 1556 5084 2729 5084 2653 5085 2729 5085 2654 5085 2654 5086 2729 5086 2699 5086 2654 5087 2699 5087 2728 5087 2728 5088 2699 5088 2698 5088 2728 5089 2698 5089 2727 5089 2727 5090 2698 5090 2697 5090 2727 5091 2697 5091 2726 5091 2726 5092 2697 5092 2672 5092 2726 5093 2672 5093 2725 5093 2725 5094 2672 5094 2671 5094 2725 5095 2671 5095 2724 5095 2724 5096 2671 5096 2670 5096 2724 5097 2670 5097 2723 5097 2723 5098 2670 5098 2669 5098 2723 5099 2669 5099 2722 5099 2722 5100 2669 5100 2668 5100 2722 5101 2668 5101 2721 5101 2721 5102 2668 5102 2667 5102 2721 5103 2667 5103 2720 5103 2720 5104 2667 5104 2666 5104 2720 5105 2666 5105 2719 5105 2719 5106 2666 5106 2665 5106 2719 5107 2665 5107 2718 5107 2718 5108 2665 5108 2664 5108 2718 5109 2664 5109 2717 5109 2717 5110 2664 5110 2663 5110 2717 5111 2663 5111 2716 5111 2716 5112 2663 5112 2662 5112 2716 5113 2662 5113 2715 5113 2715 5114 2662 5114 2661 5114 2715 5115 2661 5115 2714 5115 2714 5116 2661 5116 2040 5116 2714 5117 2040 5117 2039 5117 2543 5118 2542 5118 1929 5118 1929 5119 2542 5119 1928 5119 1928 5120 2542 5120 1925 5120 1925 5121 2542 5121 2541 5121 1925 5122 2541 5122 1382 5122 1929 5123 1352 5123 2543 5123 2543 5124 1352 5124 1350 5124 2541 5125 1412 5125 1382 5125 1291 5126 1293 5126 440 5126 1289 5127 1291 5127 1278 5127 1278 5128 1291 5128 440 5128 1278 5129 440 5129 1279 5129 1279 5130 440 5130 437 5130 1283 5131 1285 5131 1278 5131 1278 5132 1285 5132 1287 5132 1278 5133 1287 5133 1289 5133 13 5134 21 5134 51 5134 51 5135 21 5135 48 5135 808 5136 805 5136 31 5136 31 5137 805 5137 438 5137 31 5138 438 5138 439 5138 13 5139 51 5139 14 5139 14 5140 51 5140 52 5140 14 5141 52 5141 53 5141 48 5142 21 5142 55 5142 55 5143 21 5143 23 5143 55 5144 23 5144 25 5144 1269 5145 65 5145 932 5145 1267 5146 63 5146 1269 5146 1269 5147 63 5147 62 5147 1269 5148 62 5148 65 5148 25 5149 1286 5149 55 5149 55 5150 1286 5150 1284 5150 55 5151 1284 5151 1193 5151 1193 5152 1284 5152 1282 5152 1193 5153 1282 5153 442 5153 442 5154 1282 5154 1281 5154 442 5155 1281 5155 443 5155 1292 5156 1290 5156 25 5156 25 5157 1290 5157 1288 5157 25 5158 1288 5158 1286 5158 936 5159 942 5159 1269 5159 1269 5160 942 5160 944 5160 1215 5161 1094 5161 1092 5161 1292 5162 25 5162 441 5162 441 5163 25 5163 27 5163 441 5164 27 5164 439 5164 439 5165 27 5165 29 5165 439 5166 29 5166 31 5166 932 5167 934 5167 1269 5167 1269 5168 934 5168 941 5168 1269 5169 941 5169 940 5169 31 5170 33 5170 808 5170 808 5171 33 5171 35 5171 808 5172 35 5172 810 5172 810 5173 35 5173 814 5173 100 5174 99 5174 1261 5174 1215 5175 1092 5175 1217 5175 1094 5176 1215 5176 1095 5176 1095 5177 1215 5177 1213 5177 1095 5178 1213 5178 1045 5178 1082 5179 1084 5179 1199 5179 940 5180 939 5180 1269 5180 1269 5181 939 5181 937 5181 1269 5182 937 5182 936 5182 1259 5183 1 5183 86 5183 1 5184 1259 5184 2 5184 2 5185 1259 5185 1257 5185 2 5186 1257 5186 35 5186 35 5187 1257 5187 814 5187 814 5188 1257 5188 1255 5188 814 5189 1255 5189 812 5189 99 5190 88 5190 1261 5190 1261 5191 88 5191 87 5191 1261 5192 87 5192 1263 5192 1263 5193 87 5193 121 5193 1263 5194 121 5194 1265 5194 1265 5195 121 5195 120 5195 1265 5196 120 5196 1267 5196 1267 5197 120 5197 119 5197 1267 5198 119 5198 63 5198 1103 5199 1195 5199 1104 5199 1104 5200 1195 5200 1217 5200 1104 5201 1217 5201 1105 5201 1105 5202 1217 5202 1092 5202 86 5203 92 5203 1259 5203 1259 5204 92 5204 91 5204 1259 5205 91 5205 97 5205 97 5206 96 5206 1259 5206 1259 5207 96 5207 94 5207 1259 5208 94 5208 1261 5208 1261 5209 94 5209 93 5209 1261 5210 93 5210 100 5210 799 5211 800 5211 1205 5211 1205 5212 800 5212 801 5212 1205 5213 801 5213 1207 5213 1207 5214 801 5214 802 5214 1207 5215 802 5215 1209 5215 1209 5216 802 5216 803 5216 1209 5217 803 5217 1211 5217 1211 5218 803 5218 616 5218 1211 5219 616 5219 1213 5219 1108 5220 1213 5220 1109 5220 1109 5221 1213 5221 1126 5221 1109 5222 1126 5222 1125 5222 1090 5223 1197 5223 1021 5223 1021 5224 1197 5224 1022 5224 1129 5225 1131 5225 1213 5225 1213 5226 1131 5226 1046 5226 1213 5227 1046 5227 1045 5227 1014 5228 798 5228 799 5228 1201 5229 1078 5229 1203 5229 1203 5230 1078 5230 1051 5230 1090 5231 1089 5231 1197 5231 1197 5232 1089 5232 1087 5232 1197 5233 1087 5233 1199 5233 1199 5234 1087 5234 1086 5234 1199 5235 1086 5235 1082 5235 1128 5236 1126 5236 1111 5236 1111 5237 1126 5237 1213 5237 1111 5238 1213 5238 615 5238 615 5239 1213 5239 616 5239 1108 5240 1149 5240 1213 5240 1213 5241 1149 5241 1130 5241 1213 5242 1130 5242 1129 5242 1014 5243 799 5243 1012 5243 1012 5244 799 5244 1205 5244 1012 5245 1205 5245 1010 5245 1010 5246 1205 5246 1203 5246 1010 5247 1203 5247 993 5247 993 5248 1203 5248 1051 5248 993 5249 1051 5249 991 5249 1084 5250 1085 5250 1199 5250 1199 5251 1085 5251 1081 5251 1199 5252 1081 5252 1201 5252 1201 5253 1081 5253 1079 5253 1201 5254 1079 5254 1078 5254 1103 5255 1077 5255 1195 5255 1195 5256 1077 5256 1075 5256 1195 5257 1075 5257 1197 5257 1197 5258 1075 5258 1074 5258 1197 5259 1074 5259 1022 5259 794 5260 795 5260 155 5260 944 5261 945 5261 1269 5261 1269 5262 945 5262 790 5262 1269 5263 790 5263 1271 5263 1271 5264 790 5264 791 5264 1271 5265 791 5265 1273 5265 1273 5266 791 5266 792 5266 1273 5267 792 5267 1275 5267 1275 5268 792 5268 793 5268 1275 5269 793 5269 1277 5269 1277 5270 793 5270 794 5270 1277 5271 794 5271 1255 5271 1255 5272 794 5272 155 5272 1255 5273 155 5273 812 5273 795 5274 796 5274 155 5274 155 5275 796 5275 797 5275 155 5276 797 5276 798 5276 1014 5277 1016 5277 798 5277 798 5278 1016 5278 1018 5278 798 5279 1018 5279 155 5279 155 5280 1018 5280 1020 5280 155 5281 1020 5281 148 5281 1238 5282 1237 5282 470 5282 140 5283 1233 5283 1253 5283 242 5284 162 5284 161 5284 899 5285 898 5285 1242 5285 469 5286 1242 5286 470 5286 470 5287 1242 5287 1240 5287 470 5288 1240 5288 1238 5288 140 5289 1253 5289 139 5289 139 5290 1253 5290 1252 5290 139 5291 1252 5291 1165 5291 1165 5292 1252 5292 1250 5292 1165 5293 1250 5293 161 5293 161 5294 1250 5294 1248 5294 161 5295 1248 5295 242 5295 898 5296 916 5296 1242 5296 1242 5297 916 5297 915 5297 1242 5298 915 5298 1244 5298 1244 5299 915 5299 502 5299 1244 5300 502 5300 1246 5300 1246 5301 502 5301 498 5301 1246 5302 498 5302 1248 5302 1248 5303 498 5303 490 5303 1248 5304 490 5304 242 5304 469 5305 903 5305 1242 5305 1242 5306 903 5306 901 5306 1242 5307 901 5307 900 5307 900 5308 904 5308 1242 5308 1242 5309 904 5309 906 5309 1242 5310 906 5310 899 5310 533 5311 532 5311 429 5311 192 5312 191 5312 350 5312 350 5313 191 5313 195 5313 350 5314 195 5314 194 5314 194 5315 198 5315 350 5315 350 5316 198 5316 197 5316 350 5317 197 5317 1005 5317 1005 5318 197 5318 196 5318 1005 5319 196 5319 997 5319 997 5320 196 5320 164 5320 997 5321 164 5321 166 5321 349 5322 186 5322 350 5322 350 5323 186 5323 188 5323 350 5324 188 5324 192 5324 349 5325 252 5325 186 5325 186 5326 252 5326 251 5326 186 5327 251 5327 429 5327 429 5328 251 5328 331 5328 429 5329 331 5329 533 5329 541 5330 829 5330 832 5330 532 5331 537 5331 429 5331 429 5332 537 5332 535 5332 429 5333 535 5333 534 5333 534 5334 540 5334 541 5334 541 5335 832 5335 534 5335 534 5336 832 5336 830 5336 534 5337 830 5337 827 5337 823 5338 429 5338 824 5338 824 5339 429 5339 534 5339 824 5340 534 5340 826 5340 826 5341 534 5341 827 5341 453 5342 449 5342 1179 5342 453 5343 1179 5343 454 5343 1191 5344 450 5344 1176 5344 1176 5345 450 5345 454 5345 1176 5346 454 5346 1177 5346 1177 5347 454 5347 1179 5347 129 5348 128 5348 1167 5348 1167 5349 1169 5349 446 5349 446 5350 1169 5350 1175 5350 446 5351 1175 5351 1174 5351 1174 5352 1173 5352 446 5352 446 5353 1173 5353 1172 5353 446 5354 1172 5354 1171 5354 448 5355 1181 5355 449 5355 449 5356 1181 5356 1180 5356 449 5357 1180 5357 1179 5357 1171 5358 1182 5358 446 5358 446 5359 1182 5359 1181 5359 446 5360 1181 5360 447 5360 447 5361 1181 5361 448 5361 482 5362 481 5362 138 5362 138 5363 481 5363 480 5363 138 5364 480 5364 134 5364 134 5365 480 5365 478 5365 134 5366 478 5366 477 5366 482 5367 138 5367 483 5367 483 5368 138 5368 137 5368 483 5369 137 5369 484 5369 133 5370 464 5370 489 5370 489 5371 488 5371 133 5371 133 5372 488 5372 486 5372 133 5373 486 5373 137 5373 137 5374 486 5374 485 5374 137 5375 485 5375 484 5375 131 5376 461 5376 133 5376 133 5377 461 5377 463 5377 133 5378 463 5378 464 5378 1167 5379 446 5379 129 5379 129 5380 446 5380 445 5380 129 5381 445 5381 131 5381 131 5382 445 5382 467 5382 131 5383 467 5383 466 5383 466 5384 465 5384 131 5384 131 5385 465 5385 459 5385 131 5386 459 5386 461 5386 475 5387 474 5387 135 5387 1233 5388 140 5388 1231 5388 1231 5389 140 5389 136 5389 471 5390 472 5390 1224 5390 1228 5391 474 5391 1221 5391 1221 5392 474 5392 471 5392 1221 5393 471 5393 1222 5393 1222 5394 471 5394 1224 5394 1228 5395 1219 5395 474 5395 474 5396 1219 5396 1218 5396 474 5397 1218 5397 135 5397 135 5398 1218 5398 1236 5398 1236 5399 1235 5399 135 5399 135 5400 1235 5400 1234 5400 135 5401 1234 5401 136 5401 136 5402 1234 5402 1229 5402 136 5403 1229 5403 1231 5403 470 5404 1237 5404 473 5404 473 5405 1237 5405 1227 5405 473 5406 1227 5406 472 5406 472 5407 1227 5407 1226 5407 472 5408 1226 5408 1224 5408 475 5409 135 5409 476 5409 476 5410 135 5410 134 5410 476 5411 134 5411 477 5411 1183 5412 1186 5412 458 5412 458 5413 1186 5413 442 5413 442 5414 1186 5414 1192 5414 442 5415 1192 5415 1193 5415 452 5416 1185 5416 455 5416 455 5417 1185 5417 1184 5417 455 5418 1184 5418 456 5418 456 5419 1184 5419 1183 5419 456 5420 1183 5420 457 5420 457 5421 1183 5421 458 5421 450 5422 1191 5422 451 5422 451 5423 1191 5423 1189 5423 451 5424 1189 5424 452 5424 452 5425 1189 5425 1188 5425 452 5426 1188 5426 1185 5426 989 5427 988 5427 1052 5427 989 5428 1052 5428 2730 5428 1058 5429 2731 5429 1056 5429 1056 5430 2731 5430 2730 5430 1056 5431 2730 5431 1054 5431 1054 5432 2730 5432 1052 5432 1058 5433 1059 5433 2731 5433 2731 5434 1059 5434 1061 5434 2731 5435 1061 5435 2732 5435 1066 5436 2733 5436 1064 5436 1064 5437 2733 5437 2732 5437 1064 5438 2732 5438 1062 5438 1062 5439 2732 5439 1061 5439 1066 5440 2734 5440 2733 5440 2733 5441 2734 5441 1070 5441 2733 5442 1070 5442 2735 5442 2735 5443 1070 5443 1068 5443 2735 5444 1068 5444 361 5444 361 5445 1068 5445 363 5445 2731 5446 2732 5446 359 5446 2732 5447 2733 5447 359 5447 359 5448 2733 5448 2735 5448 359 5449 2735 5449 361 5449 2731 5450 359 5450 2730 5450 2730 5451 359 5451 998 5451 2730 5452 998 5452 989 5452 998 5453 359 5453 999 5453 999 5454 359 5454 358 5454 999 5455 358 5455 1000 5455 1000 5456 358 5456 357 5456 1000 5457 357 5457 1001 5457 1001 5458 357 5458 356 5458 1001 5459 356 5459 1002 5459 1002 5460 356 5460 355 5460 1002 5461 355 5461 1003 5461 1003 5462 355 5462 351 5462 1003 5463 351 5463 1004 5463 1004 5464 351 5464 353 5464 1004 5465 353 5465 1007 5465 1007 5466 353 5466 354 5466 1007 5467 354 5467 1006 5467 1006 5468 354 5468 350 5468 1006 5469 350 5469 1005 5469 2736 5470 2737 5470 2738 5470 2739 5471 2740 5471 2741 5471 2742 5472 2743 5472 2744 5472 2744 5473 2743 5473 2745 5473 2738 5474 2746 5474 2744 5474 2744 5475 2746 5475 2747 5475 2744 5476 2747 5476 2742 5476 2745 5477 2748 5477 2744 5477 2744 5478 2748 5478 2749 5478 2744 5479 2749 5479 2738 5479 2738 5480 2749 5480 2750 5480 2738 5481 2750 5481 2736 5481 2751 5482 2752 5482 2753 5482 2752 5483 2754 5483 2753 5483 2753 5484 2754 5484 2755 5484 2753 5485 2755 5485 2756 5485 2756 5486 2757 5486 2758 5486 2758 5487 2757 5487 2759 5487 2758 5488 2759 5488 2760 5488 2761 5489 2762 5489 2763 5489 2763 5490 2762 5490 2764 5490 2763 5491 2764 5491 2753 5491 2753 5492 2764 5492 2765 5492 2753 5493 2765 5493 2751 5493 2766 5494 2767 5494 2763 5494 2763 5495 2767 5495 2768 5495 2763 5496 2768 5496 2761 5496 2756 5497 2758 5497 2753 5497 2753 5498 2758 5498 2769 5498 2753 5499 2769 5499 2770 5499 2770 5500 2769 5500 2771 5500 2770 5501 2771 5501 2772 5501 2772 5502 2771 5502 2773 5502 2772 5503 2773 5503 2774 5503 2774 5504 2773 5504 2739 5504 2774 5505 2739 5505 2738 5505 2738 5506 2739 5506 2741 5506 2738 5507 2741 5507 2746 5507 2775 5508 2776 5508 2777 5508 2775 5509 2777 5509 2778 5509 2779 5510 2780 5510 2777 5510 2777 5511 2781 5511 2782 5511 2779 5512 2777 5512 2783 5512 2783 5513 2777 5513 2782 5513 2783 5514 2782 5514 2784 5514 2780 5515 2785 5515 2777 5515 2777 5516 2785 5516 2786 5516 2777 5517 2786 5517 2778 5517 2776 5518 2787 5518 2777 5518 2777 5519 2787 5519 2788 5519 2777 5520 2788 5520 2789 5520 2790 5521 2791 5521 2792 5521 2792 5522 2791 5522 2793 5522 2792 5523 2793 5523 2794 5523 2794 5524 2795 5524 2792 5524 2792 5525 2795 5525 2796 5525 2792 5526 2796 5526 2797 5526 2797 5527 2798 5527 2792 5527 2792 5528 2798 5528 2799 5528 2792 5529 2799 5529 2800 5529 2800 5530 2799 5530 2801 5530 2800 5531 2801 5531 2802 5531 2802 5532 2803 5532 2800 5532 2800 5533 2803 5533 2804 5533 2800 5534 2804 5534 2805 5534 2806 5535 2807 5535 2808 5535 2808 5536 2807 5536 2777 5536 2808 5537 2777 5537 2792 5537 2792 5538 2777 5538 2789 5538 2792 5539 2789 5539 2790 5539 2791 5540 2790 5540 2809 5540 2785 5541 2780 5541 2810 5541 2810 5542 2780 5542 2779 5542 2810 5543 2779 5543 2811 5543 2811 5544 2779 5544 2783 5544 2776 5545 2775 5545 2812 5545 2812 5546 2775 5546 2778 5546 2812 5547 2778 5547 2810 5547 2810 5548 2778 5548 2786 5548 2810 5549 2786 5549 2785 5549 2790 5550 2789 5550 2809 5550 2809 5551 2789 5551 2788 5551 2809 5552 2788 5552 2812 5552 2812 5553 2788 5553 2787 5553 2812 5554 2787 5554 2776 5554 2799 5555 2798 5555 2813 5555 2813 5556 2798 5556 2797 5556 2813 5557 2797 5557 2814 5557 2814 5558 2797 5558 2796 5558 2796 5559 2795 5559 2814 5559 2814 5560 2795 5560 2794 5560 2814 5561 2794 5561 2809 5561 2809 5562 2794 5562 2793 5562 2809 5563 2793 5563 2791 5563 2803 5564 2802 5564 2813 5564 2813 5565 2802 5565 2801 5565 2813 5566 2801 5566 2799 5566 2783 5567 2784 5567 2811 5567 2811 5568 2784 5568 2815 5568 2811 5569 2815 5569 2816 5569 2816 5570 2815 5570 2817 5570 2816 5571 2817 5571 2818 5571 2818 5572 2817 5572 2819 5572 2818 5573 2819 5573 2820 5573 2820 5574 2819 5574 2821 5574 2820 5575 2821 5575 2822 5575 2822 5576 2821 5576 2823 5576 2822 5577 2823 5577 2824 5577 2824 5578 2823 5578 2803 5578 2824 5579 2803 5579 2825 5579 2825 5580 2803 5580 2813 5580 2767 5581 2766 5581 2826 5581 2826 5582 2766 5582 2827 5582 2826 5583 2827 5583 2828 5583 2829 5584 2830 5584 2827 5584 2827 5585 2830 5585 2831 5585 2827 5586 2831 5586 2828 5586 2782 5587 2832 5587 2833 5587 2833 5588 2834 5588 2782 5588 2782 5589 2834 5589 2835 5589 2782 5590 2835 5590 2829 5590 2829 5591 2835 5591 2836 5591 2829 5592 2836 5592 2830 5592 2737 5593 2736 5593 2837 5593 2737 5594 2837 5594 2838 5594 2838 5595 2837 5595 2839 5595 2838 5596 2839 5596 2840 5596 2840 5597 2839 5597 2841 5597 2840 5598 2841 5598 2804 5598 2822 5599 2771 5599 2820 5599 2820 5600 2771 5600 2769 5600 2820 5601 2769 5601 2818 5601 2818 5602 2769 5602 2758 5602 2818 5603 2758 5603 2816 5603 2816 5604 2758 5604 2760 5604 2816 5605 2760 5605 2811 5605 2811 5606 2760 5606 2842 5606 2811 5607 2842 5607 2810 5607 2810 5608 2842 5608 2812 5608 2843 5609 2844 5609 2845 5609 2846 5610 2825 5610 2845 5610 2845 5611 2825 5611 2813 5611 2845 5612 2813 5612 2843 5612 2843 5613 2813 5613 2814 5613 2843 5614 2814 5614 2842 5614 2842 5615 2814 5615 2809 5615 2842 5616 2809 5616 2812 5616 2846 5617 2847 5617 2825 5617 2825 5618 2847 5618 2740 5618 2825 5619 2740 5619 2824 5619 2824 5620 2740 5620 2739 5620 2824 5621 2739 5621 2822 5621 2822 5622 2739 5622 2773 5622 2822 5623 2773 5623 2771 5623 2848 5624 2849 5624 2850 5624 2850 5625 2849 5625 2851 5625 2850 5626 2851 5626 2852 5626 2853 5627 2854 5627 2855 5627 2856 5628 2857 5628 2858 5628 2859 5629 2860 5629 2861 5629 2862 5630 2863 5630 2864 5630 2864 5631 2863 5631 2865 5631 2865 5632 2863 5632 2866 5632 2865 5633 2866 5633 2867 5633 2868 5634 2869 5634 2870 5634 2862 5635 2864 5635 2870 5635 2870 5636 2864 5636 2871 5636 2870 5637 2871 5637 2868 5637 2867 5638 2872 5638 2865 5638 2865 5639 2872 5639 2873 5639 2865 5640 2873 5640 2874 5640 2874 5641 2873 5641 2875 5641 2876 5642 2877 5642 2878 5642 2879 5643 2880 5643 2881 5643 2881 5644 2880 5644 2877 5644 2881 5645 2877 5645 2882 5645 2882 5646 2877 5646 2876 5646 2882 5647 2876 5647 2883 5647 2884 5648 2885 5648 2886 5648 2886 5649 2885 5649 2887 5649 2886 5650 2887 5650 2856 5650 2888 5651 2889 5651 2890 5651 2891 5652 2892 5652 2893 5652 2893 5653 2894 5653 2891 5653 2891 5654 2894 5654 2895 5654 2891 5655 2895 5655 2890 5655 2890 5656 2895 5656 2896 5656 2890 5657 2896 5657 2888 5657 2897 5658 2898 5658 2899 5658 2899 5659 2898 5659 2900 5659 2899 5660 2900 5660 2901 5660 2890 5661 2902 5661 2903 5661 2903 5662 2904 5662 2890 5662 2890 5663 2904 5663 2905 5663 2890 5664 2905 5664 2891 5664 2891 5665 2905 5665 2906 5665 2891 5666 2906 5666 2892 5666 2892 5667 2906 5667 2901 5667 2892 5668 2901 5668 2907 5668 2907 5669 2901 5669 2900 5669 2908 5670 2909 5670 2910 5670 2909 5671 2908 5671 2911 5671 2911 5672 2908 5672 2912 5672 2911 5673 2912 5673 2913 5673 2914 5674 2915 5674 2912 5674 2912 5675 2915 5675 2916 5675 2912 5676 2916 5676 2913 5676 2917 5677 2918 5677 2914 5677 2914 5678 2918 5678 2919 5678 2914 5679 2919 5679 2915 5679 2920 5680 2921 5680 2922 5680 2922 5681 2921 5681 2923 5681 2922 5682 2923 5682 2917 5682 2917 5683 2923 5683 2924 5683 2917 5684 2924 5684 2918 5684 2920 5685 2922 5685 2925 5685 2925 5686 2922 5686 2926 5686 2925 5687 2926 5687 2927 5687 2927 5688 2926 5688 2928 5688 2928 5689 2926 5689 2929 5689 2928 5690 2929 5690 2930 5690 2872 5691 2931 5691 2873 5691 2873 5692 2931 5692 2932 5692 2873 5693 2932 5693 2933 5693 2933 5694 2932 5694 2934 5694 2933 5695 2934 5695 2929 5695 2929 5696 2934 5696 2935 5696 2929 5697 2935 5697 2930 5697 2936 5698 2937 5698 2938 5698 2938 5699 2937 5699 2939 5699 2938 5700 2939 5700 2940 5700 2940 5701 2939 5701 2941 5701 2941 5702 2939 5702 2942 5702 2941 5703 2942 5703 2943 5703 2883 5704 2876 5704 2944 5704 2944 5705 2876 5705 2945 5705 2944 5706 2945 5706 2946 5706 2855 5707 2854 5707 2945 5707 2945 5708 2854 5708 2947 5708 2945 5709 2947 5709 2946 5709 2936 5710 2948 5710 2937 5710 2937 5711 2948 5711 2949 5711 2937 5712 2949 5712 2950 5712 2950 5713 2949 5713 2951 5713 2950 5714 2951 5714 2855 5714 2855 5715 2951 5715 2952 5715 2855 5716 2952 5716 2853 5716 2860 5717 2875 5717 2861 5717 2861 5718 2875 5718 2873 5718 2861 5719 2873 5719 2953 5719 2953 5720 2873 5720 2933 5720 2953 5721 2933 5721 2954 5721 2954 5722 2933 5722 2929 5722 2954 5723 2929 5723 2955 5723 2955 5724 2929 5724 2926 5724 2955 5725 2926 5725 2956 5725 2956 5726 2926 5726 2922 5726 2956 5727 2922 5727 2957 5727 2957 5728 2922 5728 2917 5728 2957 5729 2917 5729 2958 5729 2958 5730 2917 5730 2914 5730 2958 5731 2914 5731 2959 5731 2959 5732 2914 5732 2912 5732 2959 5733 2912 5733 2902 5733 2902 5734 2912 5734 2908 5734 2902 5735 2908 5735 2903 5735 2903 5736 2908 5736 2910 5736 2856 5737 2858 5737 2886 5737 2886 5738 2858 5738 2960 5738 2886 5739 2960 5739 2961 5739 2961 5740 2960 5740 2962 5740 2961 5741 2962 5741 2963 5741 2962 5742 2964 5742 2963 5742 2963 5743 2964 5743 2965 5743 2963 5744 2965 5744 2942 5744 2942 5745 2965 5745 2966 5745 2942 5746 2966 5746 2943 5746 2878 5747 2859 5747 2876 5747 2876 5748 2859 5748 2861 5748 2876 5749 2861 5749 2945 5749 2945 5750 2861 5750 2953 5750 2945 5751 2953 5751 2855 5751 2855 5752 2953 5752 2954 5752 2855 5753 2954 5753 2950 5753 2950 5754 2954 5754 2955 5754 2950 5755 2955 5755 2937 5755 2937 5756 2955 5756 2956 5756 2937 5757 2956 5757 2939 5757 2939 5758 2956 5758 2957 5758 2939 5759 2957 5759 2942 5759 2942 5760 2957 5760 2958 5760 2942 5761 2958 5761 2963 5761 2963 5762 2958 5762 2959 5762 2963 5763 2959 5763 2961 5763 2961 5764 2959 5764 2902 5764 2961 5765 2902 5765 2886 5765 2886 5766 2902 5766 2890 5766 2886 5767 2890 5767 2884 5767 2884 5768 2890 5768 2889 5768 2967 5769 2968 5769 2969 5769 2970 5770 2971 5770 2972 5770 2973 5771 2974 5771 2975 5771 2976 5772 2977 5772 2978 5772 2975 5773 2974 5773 2978 5773 2974 5774 2979 5774 2978 5774 2978 5775 2979 5775 2980 5775 2978 5776 2980 5776 2976 5776 2976 5777 2980 5777 2981 5777 2976 5778 2981 5778 2982 5778 2983 5779 2984 5779 2985 5779 2985 5780 2984 5780 2986 5780 2987 5781 2988 5781 2989 5781 2989 5782 2988 5782 2990 5782 2989 5783 2990 5783 2991 5783 2992 5784 2993 5784 2967 5784 2967 5785 2993 5785 2994 5785 2971 5786 2995 5786 2972 5786 2972 5787 2995 5787 2996 5787 2972 5788 2996 5788 2997 5788 2998 5789 2970 5789 2969 5789 2969 5790 2970 5790 2972 5790 2969 5791 2972 5791 2967 5791 2967 5792 2972 5792 2997 5792 2967 5793 2997 5793 2992 5793 2987 5794 2989 5794 2999 5794 2999 5795 2989 5795 3000 5795 2999 5796 3000 5796 3001 5796 2985 5797 2973 5797 2983 5797 2983 5798 2973 5798 2975 5798 2983 5799 2975 5799 3001 5799 3000 5800 3002 5800 3001 5800 3001 5801 3002 5801 3003 5801 3001 5802 3003 5802 2983 5802 2983 5803 3003 5803 3004 5803 2983 5804 3004 5804 2984 5804 2977 5805 2998 5805 2978 5805 2978 5806 2998 5806 2969 5806 2978 5807 2969 5807 2975 5807 2975 5808 2969 5808 2968 5808 2975 5809 2968 5809 3001 5809 3001 5810 2968 5810 2967 5810 3001 5811 2967 5811 2999 5811 2999 5812 2967 5812 2994 5812 2999 5813 2994 5813 2987 5813 3005 5814 3006 5814 3007 5814 3008 5815 3009 5815 3010 5815 3011 5816 3012 5816 3013 5816 3014 5817 3015 5817 3016 5817 3013 5818 3012 5818 3017 5818 3010 5819 3009 5819 3018 5819 3019 5820 3020 5820 3016 5820 3016 5821 3020 5821 3011 5821 3016 5822 3011 5822 3014 5822 3014 5823 3011 5823 3013 5823 3021 5824 3012 5824 3022 5824 3022 5825 3012 5825 3011 5825 3022 5826 3011 5826 3023 5826 3023 5827 3011 5827 3020 5827 3021 5828 3024 5828 3012 5828 3012 5829 3024 5829 3008 5829 3012 5830 3008 5830 3017 5830 3017 5831 3008 5831 3010 5831 3025 5832 3009 5832 3026 5832 3026 5833 3009 5833 3008 5833 3026 5834 3008 5834 3027 5834 3027 5835 3008 5835 3024 5835 3025 5836 3028 5836 3009 5836 3009 5837 3028 5837 3005 5837 3009 5838 3005 5838 3018 5838 3018 5839 3005 5839 3007 5839 3029 5840 3006 5840 3030 5840 3030 5841 3006 5841 3005 5841 3030 5842 3005 5842 3031 5842 3031 5843 3005 5843 3028 5843 3032 5844 3033 5844 3034 5844 3034 5845 3035 5845 3032 5845 3032 5846 3035 5846 3036 5846 3032 5847 3036 5847 3037 5847 3037 5848 3036 5848 3038 5848 3037 5849 3038 5849 3039 5849 3040 5850 3041 5850 3042 5850 3043 5851 3044 5851 3045 5851 3046 5852 3047 5852 3048 5852 3048 5853 3047 5853 3049 5853 3048 5854 3049 5854 3050 5854 3051 5855 3046 5855 3052 5855 3052 5856 3046 5856 3048 5856 3052 5857 3048 5857 3053 5857 3053 5858 3048 5858 3050 5858 3054 5859 3043 5859 3055 5859 3055 5860 3043 5860 3045 5860 3055 5861 3045 5861 3056 5861 3057 5862 3058 5862 3059 5862 3059 5863 3058 5863 3060 5863 3059 5864 3060 5864 3061 5864 3062 5865 3063 5865 3064 5865 3064 5866 3063 5866 3065 5866 3064 5867 3065 5867 3066 5867 3066 5868 3067 5868 3064 5868 3064 5869 3067 5869 3068 5869 3064 5870 3068 5870 3069 5870 3070 5871 3062 5871 3071 5871 3071 5872 3062 5872 3064 5872 3071 5873 3064 5873 3072 5873 3072 5874 3064 5874 3069 5874 3073 5875 3074 5875 3075 5875 3075 5876 3076 5876 3073 5876 3073 5877 3076 5877 3077 5877 3073 5878 3077 5878 3068 5878 3068 5879 3077 5879 3078 5879 3068 5880 3078 5880 3069 5880 3079 5881 3080 5881 3081 5881 3081 5882 3080 5882 3082 5882 3081 5883 3082 5883 3074 5883 3074 5884 3082 5884 3083 5884 3074 5885 3083 5885 3075 5885 3084 5886 3085 5886 3079 5886 3079 5887 3085 5887 3086 5887 3079 5888 3086 5888 3080 5888 3087 5889 3088 5889 3084 5889 3084 5890 3088 5890 3089 5890 3084 5891 3089 5891 3085 5891 3090 5892 3091 5892 3087 5892 3087 5893 3091 5893 3092 5893 3087 5894 3092 5894 3088 5894 3093 5895 3094 5895 3090 5895 3090 5896 3094 5896 3095 5896 3090 5897 3095 5897 3091 5897 3096 5898 3097 5898 3093 5898 3093 5899 3097 5899 3098 5899 3093 5900 3098 5900 3094 5900 3099 5901 3100 5901 3096 5901 3096 5902 3100 5902 3101 5902 3096 5903 3101 5903 3097 5903 3102 5904 3103 5904 3099 5904 3099 5905 3103 5905 3104 5905 3099 5906 3104 5906 3100 5906 3105 5907 3106 5907 3102 5907 3102 5908 3106 5908 3107 5908 3102 5909 3107 5909 3103 5909 3047 5910 3108 5910 3049 5910 3049 5911 3108 5911 3109 5911 3049 5912 3109 5912 3105 5912 3105 5913 3109 5913 3110 5913 3105 5914 3110 5914 3106 5914 3044 5915 3050 5915 3045 5915 3045 5916 3050 5916 3049 5916 3045 5917 3049 5917 3056 5917 3056 5918 3049 5918 3105 5918 3056 5919 3105 5919 3111 5919 3111 5920 3105 5920 3102 5920 3111 5921 3102 5921 3112 5921 3112 5922 3102 5922 3099 5922 3112 5923 3099 5923 3113 5923 3113 5924 3099 5924 3096 5924 3113 5925 3096 5925 3114 5925 3114 5926 3096 5926 3093 5926 3114 5927 3093 5927 3115 5927 3115 5928 3093 5928 3090 5928 3115 5929 3090 5929 3116 5929 3116 5930 3090 5930 3087 5930 3116 5931 3087 5931 3117 5931 3117 5932 3087 5932 3084 5932 3117 5933 3084 5933 3118 5933 3118 5934 3084 5934 3079 5934 3118 5935 3079 5935 3119 5935 3119 5936 3079 5936 3081 5936 3119 5937 3081 5937 3120 5937 3120 5938 3081 5938 3074 5938 3120 5939 3074 5939 3121 5939 3121 5940 3074 5940 3073 5940 3121 5941 3073 5941 3059 5941 3059 5942 3073 5942 3068 5942 3059 5943 3068 5943 3057 5943 3057 5944 3068 5944 3067 5944 3061 5945 3040 5945 3059 5945 3059 5946 3040 5946 3042 5946 3059 5947 3042 5947 3121 5947 3121 5948 3042 5948 3122 5948 3121 5949 3122 5949 3120 5949 3120 5950 3122 5950 3123 5950 3120 5951 3123 5951 3119 5951 3119 5952 3123 5952 3124 5952 3119 5953 3124 5953 3118 5953 3118 5954 3124 5954 3125 5954 3118 5955 3125 5955 3117 5955 3117 5956 3125 5956 3126 5956 3117 5957 3126 5957 3116 5957 3116 5958 3126 5958 3127 5958 3116 5959 3127 5959 3115 5959 3115 5960 3127 5960 3128 5960 3115 5961 3128 5961 3114 5961 3114 5962 3128 5962 3129 5962 3114 5963 3129 5963 3113 5963 3113 5964 3129 5964 3130 5964 3113 5965 3130 5965 3112 5965 3112 5966 3130 5966 3131 5966 3112 5967 3131 5967 3111 5967 3111 5968 3131 5968 3132 5968 3111 5969 3132 5969 3056 5969 3056 5970 3132 5970 3133 5970 3056 5971 3133 5971 3055 5971 3134 5972 3135 5972 3136 5972 3137 5973 3138 5973 3139 5973 3140 5974 3141 5974 3142 5974 3143 5975 3144 5975 3145 5975 3145 5976 3146 5976 3143 5976 3143 5977 3146 5977 3147 5977 3143 5978 3147 5978 3148 5978 3148 5979 3149 5979 3143 5979 3143 5980 3149 5980 3150 5980 3143 5981 3150 5981 3151 5981 3054 5982 3152 5982 3153 5982 3153 5983 3152 5983 3143 5983 3153 5984 3143 5984 3154 5984 3154 5985 3143 5985 3151 5985 3155 5986 3156 5986 3157 5986 3156 5987 3158 5987 3157 5987 3157 5988 3158 5988 3159 5988 3157 5989 3159 5989 3160 5989 3160 5990 3161 5990 3157 5990 3157 5991 3161 5991 3162 5991 3157 5992 3162 5992 3163 5992 3163 5993 3164 5993 3157 5993 3157 5994 3164 5994 3165 5994 3157 5995 3165 5995 3143 5995 3143 5996 3165 5996 3166 5996 3143 5997 3166 5997 3144 5997 3157 5998 3167 5998 3168 5998 3155 5999 3157 5999 3169 5999 3169 6000 3157 6000 3168 6000 3169 6001 3168 6001 3170 6001 3140 6002 3142 6002 3171 6002 3172 6003 3173 6003 3174 6003 3174 6004 3173 6004 3171 6004 3174 6005 3171 6005 3175 6005 3175 6006 3171 6006 3142 6006 3175 6007 3142 6007 3176 6007 3177 6008 3137 6008 3178 6008 3178 6009 3137 6009 3139 6009 3178 6010 3139 6010 3179 6010 3180 6011 3181 6011 3182 6011 3181 6012 3180 6012 3183 6012 3183 6013 3180 6013 3136 6013 3183 6014 3136 6014 3184 6014 3185 6015 3186 6015 3187 6015 3184 6016 3136 6016 3187 6016 3187 6017 3136 6017 3135 6017 3187 6018 3135 6018 3185 6018 3188 6019 3189 6019 3142 6019 3142 6020 3189 6020 3190 6020 3142 6021 3190 6021 3176 6021 3138 6022 3188 6022 3139 6022 3139 6023 3188 6023 3142 6023 3139 6024 3142 6024 3157 6024 3157 6025 3142 6025 3141 6025 3157 6026 3141 6026 3167 6026 3152 6027 3134 6027 3143 6027 3143 6028 3134 6028 3136 6028 3143 6029 3136 6029 3157 6029 3157 6030 3136 6030 3180 6030 3157 6031 3180 6031 3139 6031 3139 6032 3180 6032 3182 6032 3139 6033 3182 6033 3179 6033 3191 6034 3192 6034 3193 6034 3193 6035 3192 6035 3194 6035 3195 6036 3196 6036 3197 6036 3198 6037 3199 6037 3200 6037 3201 6038 3202 6038 3203 6038 3196 6039 3204 6039 3197 6039 3197 6040 3204 6040 3201 6040 3197 6041 3201 6041 3200 6041 3200 6042 3201 6042 3203 6042 3200 6043 3203 6043 3198 6043 3205 6044 3206 6044 3207 6044 3207 6045 3206 6045 3208 6045 3207 6046 3208 6046 3197 6046 3197 6047 3208 6047 3209 6047 3197 6048 3209 6048 3195 6048 3210 6049 3211 6049 3191 6049 3191 6050 3211 6050 3212 6050 3213 6051 3214 6051 3191 6051 3215 6052 3191 6052 3216 6052 3216 6053 3191 6053 3193 6053 3216 6054 3193 6054 3217 6054 3215 6055 3218 6055 3191 6055 3191 6056 3218 6056 3219 6056 3191 6057 3219 6057 3220 6057 3191 6058 3214 6058 3210 6058 3210 6059 3214 6059 3221 6059 3210 6060 3221 6060 3222 6060 3220 6061 3223 6061 3191 6061 3191 6062 3223 6062 3224 6062 3191 6063 3224 6063 3213 6063 3225 6064 3207 6064 3226 6064 3226 6065 3207 6065 3197 6065 3226 6066 3197 6066 3227 6066 3227 6067 3197 6067 3228 6067 3227 6068 3228 6068 3229 6068 3229 6069 3228 6069 3230 6069 3231 6070 3232 6070 3233 6070 3233 6071 3232 6071 3234 6071 3233 6072 3234 6072 3230 6072 3230 6073 3234 6073 3235 6073 3230 6074 3235 6074 3236 6074 3236 6075 3237 6075 3230 6075 3230 6076 3237 6076 3238 6076 3230 6077 3238 6077 3239 6077 3239 6078 3240 6078 3230 6078 3230 6079 3240 6079 3241 6079 3230 6080 3241 6080 3229 6080 3210 6081 3222 6081 3242 6081 3242 6082 3222 6082 3231 6082 3242 6083 3231 6083 3243 6083 3243 6084 3231 6084 3233 6084 3244 6085 3245 6085 3246 6085 3247 6086 3206 6086 3248 6086 3248 6087 3206 6087 3205 6087 3249 6088 3201 6088 3204 6088 3250 6089 3251 6089 3252 6089 3252 6090 3251 6090 3253 6090 3252 6091 3253 6091 3249 6091 3250 6092 3252 6092 3254 6092 3254 6093 3252 6093 3255 6093 3254 6094 3255 6094 3256 6094 3256 6095 3255 6095 3257 6095 3256 6096 3257 6096 3258 6096 3258 6097 3257 6097 3259 6097 3258 6098 3259 6098 3260 6098 3249 6099 3204 6099 3252 6099 3252 6100 3204 6100 3196 6100 3252 6101 3196 6101 3255 6101 3255 6102 3196 6102 3195 6102 3255 6103 3195 6103 3257 6103 3257 6104 3195 6104 3209 6104 3257 6105 3209 6105 3259 6105 3259 6106 3209 6106 3208 6106 3259 6107 3208 6107 3261 6107 3261 6108 3208 6108 3206 6108 3261 6109 3206 6109 3244 6109 3244 6110 3206 6110 3247 6110 3244 6111 3247 6111 3245 6111 3260 6112 3259 6112 3262 6112 3262 6113 3259 6113 3261 6113 3262 6114 3261 6114 3263 6114 3263 6115 3261 6115 3244 6115 3263 6116 3244 6116 3264 6116 3264 6117 3244 6117 3246 6117 3264 6118 3246 6118 3265 6118 3266 6119 3267 6119 3268 6119 2994 6120 2993 6120 3269 6120 3269 6121 2993 6121 2992 6121 3269 6122 2992 6122 2997 6122 3266 6123 3270 6123 3271 6123 3271 6124 3270 6124 3272 6124 3271 6125 3272 6125 2995 6125 2995 6126 3272 6126 3269 6126 2995 6127 3269 6127 2996 6127 2996 6128 3269 6128 2997 6128 2991 6129 2990 6129 3273 6129 3273 6130 2990 6130 2988 6130 3266 6131 3268 6131 3270 6131 3270 6132 3268 6132 3274 6132 3270 6133 3274 6133 3275 6133 3275 6134 3274 6134 3276 6134 3275 6135 3276 6135 3277 6135 3277 6136 3276 6136 3278 6136 3277 6137 3278 6137 3279 6137 3279 6138 3278 6138 3280 6138 3279 6139 3280 6139 3281 6139 3281 6140 3280 6140 3282 6140 3281 6141 3282 6141 3283 6141 3283 6142 3282 6142 3284 6142 3283 6143 3284 6143 3285 6143 3285 6144 3284 6144 3286 6144 3285 6145 3286 6145 3287 6145 3287 6146 3286 6146 3288 6146 3287 6147 3288 6147 3289 6147 3289 6148 3288 6148 3273 6148 3289 6149 3273 6149 3290 6149 3290 6150 3273 6150 2988 6150 3290 6151 2988 6151 3269 6151 3269 6152 2988 6152 2987 6152 3269 6153 2987 6153 2994 6153 3291 6154 3292 6154 3293 6154 3293 6155 3292 6155 3294 6155 3293 6156 3294 6156 3295 6156 3295 6157 3294 6157 3296 6157 3295 6158 3296 6158 3297 6158 3291 6159 3293 6159 3298 6159 3298 6160 3293 6160 3299 6160 3298 6161 3299 6161 3300 6161 3300 6162 3299 6162 3301 6162 3300 6163 3301 6163 3302 6163 3303 6164 3304 6164 3305 6164 3305 6165 3304 6165 3306 6165 3305 6166 3306 6166 3307 6166 3307 6167 3306 6167 3308 6167 3307 6168 3308 6168 3309 6168 3309 6169 3308 6169 3300 6169 3309 6170 3300 6170 3310 6170 3310 6171 3300 6171 3302 6171 2979 6172 2974 6172 3311 6172 2986 6173 3312 6173 2985 6173 2985 6174 3312 6174 3311 6174 2985 6175 3311 6175 2973 6175 2973 6176 3311 6176 2974 6176 3313 6177 2982 6177 3314 6177 3314 6178 2982 6178 2981 6178 3314 6179 2981 6179 3311 6179 3311 6180 2981 6180 2980 6180 3311 6181 2980 6181 2979 6181 3315 6182 3316 6182 3317 6182 3315 6183 3317 6183 3318 6183 3318 6184 3317 6184 3319 6184 3318 6185 3319 6185 3320 6185 3315 6186 3321 6186 3316 6186 3316 6187 3321 6187 3322 6187 3323 6188 3324 6188 3325 6188 3325 6189 3324 6189 3326 6189 3327 6190 3328 6190 3329 6190 3327 6191 3329 6191 3330 6191 3330 6192 3329 6192 3326 6192 3330 6193 3326 6193 3324 6193 3321 6194 3331 6194 3322 6194 3322 6195 3331 6195 3332 6195 3331 6196 3333 6196 3332 6196 3332 6197 3333 6197 3334 6197 3332 6198 3334 6198 3335 6198 3216 6199 3217 6199 3336 6199 3336 6200 3217 6200 3335 6200 3336 6201 3335 6201 3337 6201 3337 6202 3335 6202 3334 6202 3323 6203 3325 6203 3338 6203 3226 6204 3339 6204 3225 6204 3225 6205 3339 6205 3340 6205 3339 6206 3341 6206 3340 6206 3340 6207 3341 6207 3342 6207 3340 6208 3342 6208 3343 6208 3342 6209 3344 6209 3343 6209 3343 6210 3344 6210 3345 6210 3343 6211 3345 6211 3346 6211 3345 6212 3347 6212 3346 6212 3346 6213 3347 6213 3348 6213 3346 6214 3348 6214 3338 6214 3338 6215 3348 6215 3349 6215 3338 6216 3349 6216 3323 6216 3295 6217 3297 6217 3350 6217 3295 6218 3350 6218 3351 6218 3351 6219 3350 6219 3328 6219 3351 6220 3328 6220 3327 6220 3320 6221 3319 6221 3352 6221 3320 6222 3352 6222 3353 6222 3353 6223 3352 6223 3313 6223 3353 6224 3313 6224 3314 6224 3354 6225 3355 6225 3356 6225 3356 6226 3355 6226 3357 6226 3356 6227 3357 6227 3358 6227 3358 6228 3357 6228 3359 6228 3358 6229 3359 6229 3360 6229 3360 6230 3359 6230 3194 6230 3360 6231 3194 6231 3192 6231 3361 6232 3362 6232 3363 6232 3364 6233 3365 6233 3366 6233 3364 6234 3366 6234 3367 6234 3367 6235 3366 6235 3361 6235 3367 6236 3361 6236 3368 6236 3368 6237 3361 6237 3363 6237 3368 6238 3363 6238 3354 6238 3354 6239 3363 6239 3369 6239 3354 6240 3369 6240 3355 6240 3365 6241 3364 6241 3370 6241 3370 6242 3364 6242 3371 6242 3372 6243 3373 6243 3374 6243 3375 6244 3376 6244 3377 6244 3265 6245 3378 6245 3379 6245 3265 6246 3379 6246 3380 6246 3380 6247 3379 6247 3381 6247 3380 6248 3381 6248 3382 6248 3247 6249 3383 6249 3245 6249 3245 6250 3383 6250 3384 6250 3245 6251 3384 6251 3246 6251 3265 6252 3246 6252 3378 6252 3378 6253 3246 6253 3384 6253 3378 6254 3384 6254 3385 6254 3385 6255 3384 6255 3386 6255 3387 6256 3388 6256 3389 6256 3388 6257 3390 6257 3389 6257 3389 6258 3390 6258 3391 6258 3389 6259 3391 6259 3384 6259 3384 6260 3391 6260 3392 6260 3384 6261 3392 6261 3386 6261 3393 6262 3394 6262 3395 6262 3395 6263 3396 6263 3393 6263 3393 6264 3396 6264 3397 6264 3393 6265 3397 6265 3398 6265 3399 6266 3308 6266 3400 6266 3400 6267 3308 6267 3306 6267 3400 6268 3306 6268 3304 6268 3372 6269 3298 6269 3300 6269 3377 6270 3292 6270 3291 6270 3292 6271 3377 6271 3294 6271 3294 6272 3377 6272 3376 6272 3294 6273 3376 6273 3296 6273 3401 6274 3375 6274 3374 6274 3374 6275 3375 6275 3377 6275 3374 6276 3377 6276 3372 6276 3372 6277 3377 6277 3291 6277 3372 6278 3291 6278 3298 6278 3400 6279 3402 6279 3399 6279 3399 6280 3402 6280 3403 6280 3399 6281 3403 6281 3404 6281 3398 6282 3387 6282 3393 6282 3393 6283 3387 6283 3389 6283 3393 6284 3389 6284 3404 6284 3403 6285 3405 6285 3404 6285 3404 6286 3405 6286 3406 6286 3404 6287 3406 6287 3393 6287 3393 6288 3406 6288 3407 6288 3393 6289 3407 6289 3394 6289 3383 6290 3401 6290 3384 6290 3384 6291 3401 6291 3374 6291 3384 6292 3374 6292 3389 6292 3389 6293 3374 6293 3373 6293 3389 6294 3373 6294 3404 6294 3404 6295 3373 6295 3372 6295 3404 6296 3372 6296 3399 6296 3399 6297 3372 6297 3300 6297 3399 6298 3300 6298 3308 6298 3408 6299 3409 6299 3410 6299 3411 6300 3412 6300 3410 6300 3410 6301 3412 6301 3413 6301 3414 6302 3415 6302 3410 6302 3410 6303 3415 6303 3416 6303 3410 6304 3416 6304 3411 6304 3413 6305 3417 6305 3410 6305 3410 6306 3417 6306 3418 6306 3410 6307 3418 6307 3408 6307 3419 6308 3420 6308 3421 6308 3421 6309 3420 6309 3422 6309 3423 6310 3424 6310 3421 6310 3421 6311 3424 6311 3425 6311 3411 6312 3426 6312 3412 6312 3412 6313 3426 6313 3421 6313 3412 6314 3421 6314 3427 6314 3427 6315 3421 6315 3425 6315 3422 6316 3428 6316 3421 6316 3421 6317 3428 6317 3429 6317 3421 6318 3429 6318 3423 6318 3430 6319 3431 6319 3432 6319 3432 6320 3431 6320 3433 6320 3434 6321 3435 6321 3436 6321 3437 6322 3438 6322 3439 6322 3439 6323 3438 6323 3440 6323 3439 6324 3440 6324 3441 6324 3439 6325 3442 6325 3437 6325 3437 6326 3442 6326 3443 6326 3437 6327 3443 6327 3436 6327 3436 6328 3443 6328 3444 6328 3436 6329 3444 6329 3434 6329 3445 6330 3446 6330 3447 6330 3447 6331 3446 6331 3448 6331 3447 6332 3448 6332 3449 6332 3450 6333 3451 6333 3452 6333 3453 6334 3450 6334 3454 6334 3445 6335 3455 6335 3456 6335 3457 6336 3409 6336 3408 6336 3458 6337 3459 6337 3460 6337 3460 6338 3459 6338 3461 6338 3460 6339 3461 6339 3462 6339 3463 6340 3446 6340 3445 6340 3464 6341 3465 6341 3466 6341 3466 6342 3467 6342 3464 6342 3464 6343 3467 6343 3468 6343 3464 6344 3468 6344 3469 6344 3469 6345 3468 6345 3470 6345 3469 6346 3470 6346 3471 6346 3471 6347 3470 6347 3472 6347 3471 6348 3472 6348 3473 6348 3472 6349 3474 6349 3473 6349 3473 6350 3474 6350 3475 6350 3473 6351 3475 6351 3476 6351 3476 6352 3475 6352 3477 6352 3476 6353 3477 6353 3478 6353 3478 6354 3477 6354 3479 6354 3478 6355 3479 6355 3480 6355 3481 6356 3482 6356 3483 6356 3483 6357 3482 6357 3484 6357 3483 6358 3484 6358 3485 6358 3485 6359 3484 6359 3480 6359 3485 6360 3480 6360 3486 6360 3486 6361 3480 6361 3479 6361 3487 6362 3488 6362 3453 6362 3482 6363 3489 6363 3484 6363 3484 6364 3489 6364 3490 6364 3484 6365 3490 6365 3480 6365 3480 6366 3490 6366 3491 6366 3480 6367 3491 6367 3478 6367 3478 6368 3491 6368 3492 6368 3478 6369 3492 6369 3476 6369 3476 6370 3492 6370 3493 6370 3476 6371 3493 6371 3473 6371 3473 6372 3493 6372 3494 6372 3473 6373 3494 6373 3471 6373 3471 6374 3494 6374 3495 6374 3471 6375 3495 6375 3469 6375 3469 6376 3495 6376 3496 6376 3469 6377 3496 6377 3464 6377 3464 6378 3496 6378 3497 6378 3464 6379 3497 6379 3465 6379 3465 6380 3497 6380 3498 6380 3455 6381 3499 6381 3456 6381 3456 6382 3499 6382 3500 6382 3456 6383 3500 6383 3489 6383 3489 6384 3500 6384 3458 6384 3489 6385 3458 6385 3490 6385 3490 6386 3458 6386 3460 6386 3490 6387 3460 6387 3491 6387 3491 6388 3460 6388 3501 6388 3491 6389 3501 6389 3492 6389 3492 6390 3501 6390 3502 6390 3492 6391 3502 6391 3493 6391 3493 6392 3502 6392 3503 6392 3493 6393 3503 6393 3494 6393 3494 6394 3503 6394 3504 6394 3494 6395 3504 6395 3495 6395 3495 6396 3504 6396 3505 6396 3495 6397 3505 6397 3496 6397 3496 6398 3505 6398 3506 6398 3496 6399 3506 6399 3497 6399 3497 6400 3506 6400 3507 6400 3497 6401 3507 6401 3498 6401 3498 6402 3507 6402 3508 6402 3445 6403 3456 6403 3463 6403 3463 6404 3456 6404 3489 6404 3463 6405 3489 6405 3509 6405 3509 6406 3489 6406 3482 6406 3509 6407 3482 6407 3487 6407 3487 6408 3482 6408 3481 6408 3487 6409 3481 6409 3488 6409 3462 6410 3457 6410 3460 6410 3460 6411 3457 6411 3408 6411 3460 6412 3408 6412 3501 6412 3501 6413 3408 6413 3418 6413 3501 6414 3418 6414 3502 6414 3502 6415 3418 6415 3417 6415 3502 6416 3417 6416 3503 6416 3503 6417 3417 6417 3413 6417 3503 6418 3413 6418 3504 6418 3504 6419 3413 6419 3412 6419 3504 6420 3412 6420 3505 6420 3505 6421 3412 6421 3427 6421 3505 6422 3427 6422 3506 6422 3506 6423 3427 6423 3425 6423 3506 6424 3425 6424 3507 6424 3507 6425 3425 6425 3424 6425 3507 6426 3424 6426 3508 6426 3508 6427 3424 6427 3423 6427 3453 6428 3454 6428 3487 6428 3487 6429 3454 6429 3510 6429 3487 6430 3510 6430 3509 6430 3509 6431 3510 6431 3511 6431 3509 6432 3511 6432 3463 6432 3463 6433 3511 6433 3448 6433 3463 6434 3448 6434 3446 6434 3450 6435 3452 6435 3454 6435 3454 6436 3452 6436 3512 6436 3454 6437 3512 6437 3510 6437 3510 6438 3512 6438 3513 6438 3510 6439 3513 6439 3511 6439 3511 6440 3513 6440 3449 6440 3511 6441 3449 6441 3448 6441 3514 6442 3515 6442 3516 6442 3517 6443 3518 6443 3519 6443 3519 6444 3518 6444 3520 6444 3519 6445 3520 6445 3521 6445 3521 6446 3520 6446 3522 6446 3521 6447 3522 6447 3523 6447 3524 6448 3525 6448 3526 6448 3526 6449 3525 6449 3527 6449 3526 6450 3527 6450 3528 6450 3514 6451 3516 6451 3529 6451 3527 6452 3530 6452 3528 6452 3528 6453 3530 6453 3531 6453 3528 6454 3531 6454 3532 6454 3532 6455 3531 6455 3533 6455 3532 6456 3533 6456 3534 6456 3529 6457 3535 6457 3534 6457 3534 6458 3535 6458 3536 6458 3534 6459 3536 6459 3532 6459 3537 6460 3538 6460 3539 6460 3539 6461 3538 6461 3540 6461 3517 6462 3519 6462 3541 6462 3541 6463 3519 6463 3542 6463 3541 6464 3542 6464 3516 6464 3516 6465 3542 6465 3539 6465 3516 6466 3539 6466 3529 6466 3529 6467 3539 6467 3540 6467 3529 6468 3540 6468 3535 6468 3543 6469 3544 6469 3545 6469 3545 6470 3544 6470 3546 6470 3431 6471 3547 6471 3433 6471 3433 6472 3547 6472 3548 6472 3549 6473 3550 6473 3551 6473 3551 6474 3550 6474 3552 6474 3551 6475 3552 6475 3553 6475 3552 6476 3554 6476 3553 6476 3553 6477 3554 6477 3555 6477 3553 6478 3555 6478 3556 6478 3557 6479 3558 6479 3559 6479 3559 6480 3558 6480 3556 6480 3559 6481 3556 6481 3560 6481 3560 6482 3556 6482 3555 6482 3561 6483 3562 6483 3557 6483 3557 6484 3562 6484 3563 6484 3557 6485 3563 6485 3558 6485 3516 6486 3515 6486 3564 6486 3564 6487 3515 6487 3565 6487 3557 6488 3566 6488 3561 6488 3561 6489 3566 6489 3567 6489 3561 6490 3567 6490 3568 6490 3568 6491 3567 6491 3564 6491 3568 6492 3564 6492 3569 6492 3569 6493 3564 6493 3565 6493 3442 6494 3439 6494 3570 6494 3570 6495 3439 6495 3571 6495 3570 6496 3571 6496 3572 6496 3572 6497 3571 6497 3573 6497 3572 6498 3573 6498 3574 6498 3574 6499 3573 6499 3575 6499 3574 6500 3575 6500 3576 6500 3576 6501 3575 6501 3577 6501 3576 6502 3577 6502 3578 6502 3578 6503 3577 6503 3579 6503 3578 6504 3579 6504 3526 6504 3526 6505 3579 6505 3524 6505 3580 6506 3550 6506 3581 6506 3581 6507 3550 6507 3549 6507 3582 6508 3583 6508 3584 6508 3585 6509 3586 6509 3587 6509 3587 6510 3586 6510 3588 6510 3587 6511 3588 6511 3589 6511 3589 6512 3590 6512 3587 6512 3587 6513 3590 6513 3591 6513 3587 6514 3591 6514 3584 6514 3584 6515 3591 6515 3592 6515 3584 6516 3592 6516 3582 6516 3593 6517 3594 6517 3595 6517 3595 6518 3594 6518 3596 6518 3597 6519 3598 6519 3599 6519 3599 6520 3598 6520 3600 6520 3599 6521 3600 6521 3596 6521 3596 6522 3600 6522 3601 6522 3596 6523 3601 6523 3595 6523 3597 6524 3599 6524 3602 6524 3602 6525 3599 6525 3603 6525 3602 6526 3603 6526 3604 6526 3604 6527 3603 6527 3605 6527 3605 6528 3603 6528 3606 6528 3605 6529 3606 6529 3607 6529 3583 6530 3608 6530 3584 6530 3584 6531 3608 6531 3609 6531 3584 6532 3609 6532 3606 6532 3606 6533 3609 6533 3610 6533 3606 6534 3610 6534 3607 6534 3611 6535 3612 6535 3613 6535 3611 6536 3613 6536 3614 6536 3614 6537 3613 6537 3615 6537 3614 6538 3615 6538 3616 6538 3617 6539 3618 6539 3619 6539 3616 6540 3620 6540 3614 6540 3614 6541 3620 6541 3617 6541 3614 6542 3617 6542 3621 6542 3621 6543 3617 6543 3619 6543 3612 6544 3622 6544 3613 6544 3613 6545 3622 6545 3623 6545 3613 6546 3623 6546 3624 6546 3625 6547 3626 6547 3627 6547 3627 6548 3626 6548 3628 6548 3627 6549 3628 6549 3629 6549 3629 6550 3630 6550 3627 6550 3627 6551 3630 6551 3631 6551 3627 6552 3631 6552 3632 6552 3632 6553 3633 6553 3627 6553 3627 6554 3633 6554 3634 6554 3627 6555 3634 6555 3635 6555 3634 6556 3636 6556 3637 6556 3635 6557 3634 6557 3638 6557 3638 6558 3634 6558 3637 6558 3638 6559 3637 6559 3639 6559 3624 6560 3625 6560 3613 6560 3613 6561 3625 6561 3627 6561 3613 6562 3627 6562 3640 6562 3640 6563 3627 6563 3641 6563 3640 6564 3641 6564 3642 6564 3643 6565 3644 6565 3645 6565 3643 6566 3645 6566 3646 6566 3645 6567 3647 6567 3646 6567 3646 6568 3647 6568 3648 6568 3646 6569 3648 6569 3649 6569 3649 6570 3648 6570 3650 6570 3649 6571 3650 6571 3651 6571 3651 6572 3650 6572 3652 6572 3651 6573 3652 6573 3653 6573 3653 6574 3652 6574 3654 6574 3653 6575 3654 6575 3641 6575 3641 6576 3654 6576 3655 6576 3641 6577 3655 6577 3642 6577 3644 6578 3643 6578 3656 6578 3656 6579 3643 6579 3657 6579 3656 6580 3657 6580 3658 6580 3658 6581 3657 6581 3659 6581 3658 6582 3659 6582 3660 6582 3660 6583 3659 6583 3661 6583 3660 6584 3661 6584 3662 6584 3662 6585 3661 6585 3663 6585 3662 6586 3663 6586 3664 6586 3665 6587 3666 6587 3667 6587 3667 6588 3666 6588 3668 6588 3667 6589 3668 6589 3669 6589 3669 6590 3668 6590 3670 6590 3669 6591 3670 6591 3663 6591 3663 6592 3670 6592 3671 6592 3663 6593 3671 6593 3664 6593 3672 6594 3171 6594 3673 6594 3673 6595 3171 6595 3173 6595 3673 6596 3173 6596 3674 6596 3173 6597 3172 6597 3674 6597 3674 6598 3172 6598 3675 6598 3674 6599 3675 6599 3665 6599 3665 6600 3675 6600 3676 6600 3665 6601 3676 6601 3666 6601 3677 6602 3168 6602 3678 6602 3678 6603 3168 6603 3167 6603 3678 6604 3167 6604 3679 6604 3679 6605 3167 6605 3141 6605 3679 6606 3141 6606 3672 6606 3672 6607 3141 6607 3140 6607 3672 6608 3140 6608 3171 6608 3680 6609 3619 6609 3618 6609 3681 6610 3682 6610 3683 6610 3684 6611 3685 6611 3686 6611 3686 6612 3685 6612 3687 6612 3688 6613 3689 6613 3690 6613 3690 6614 3689 6614 3691 6614 3690 6615 3691 6615 3684 6615 3684 6616 3691 6616 3692 6616 3684 6617 3692 6617 3685 6617 3690 6618 3693 6618 3688 6618 3688 6619 3693 6619 3694 6619 3688 6620 3694 6620 3695 6620 3695 6621 3694 6621 3681 6621 3695 6622 3681 6622 3696 6622 3696 6623 3681 6623 3683 6623 3687 6624 3685 6624 3697 6624 3697 6625 3685 6625 3698 6625 3697 6626 3698 6626 3699 6626 3699 6627 3698 6627 3700 6627 3699 6628 3700 6628 3701 6628 3701 6629 3700 6629 3702 6629 3701 6630 3702 6630 3618 6630 3618 6631 3702 6631 3703 6631 3618 6632 3703 6632 3680 6632 3637 6633 3636 6633 3704 6633 3704 6634 3705 6634 3637 6634 3637 6635 3705 6635 3706 6635 3637 6636 3706 6636 3707 6636 3708 6637 3709 6637 3710 6637 3707 6638 3706 6638 3711 6638 3711 6639 3706 6639 3712 6639 3711 6640 3712 6640 3713 6640 3713 6641 3712 6641 3714 6641 3713 6642 3714 6642 3715 6642 3708 6643 3710 6643 3716 6643 3715 6644 3714 6644 3710 6644 3710 6645 3714 6645 3717 6645 3710 6646 3717 6646 3716 6646 2916 6647 3718 6647 3719 6647 3719 6648 3720 6648 2916 6648 2916 6649 3720 6649 3721 6649 2916 6650 3721 6650 2913 6650 2913 6651 3721 6651 3722 6651 2913 6652 3722 6652 3723 6652 3724 6653 2911 6653 3725 6653 3725 6654 2911 6654 2913 6654 3725 6655 2913 6655 3726 6655 3726 6656 2913 6656 3723 6656 3724 6657 3727 6657 2911 6657 2911 6658 3727 6658 3728 6658 2911 6659 3728 6659 2909 6659 3729 6660 3730 6660 3731 6660 3731 6661 3730 6661 3732 6661 3731 6662 3732 6662 3733 6662 3733 6663 3732 6663 3734 6663 3734 6664 3732 6664 3735 6664 3734 6665 3735 6665 3736 6665 3728 6666 3737 6666 2909 6666 2909 6667 3737 6667 3738 6667 2909 6668 3738 6668 2910 6668 2910 6669 3738 6669 3729 6669 2910 6670 3729 6670 2903 6670 2903 6671 3729 6671 3731 6671 2903 6672 3731 6672 2904 6672 3718 6673 3739 6673 3740 6673 3740 6674 3739 6674 3741 6674 3740 6675 3741 6675 3742 6675 3742 6676 3743 6676 3740 6676 3740 6677 3743 6677 3744 6677 3740 6678 3744 6678 3745 6678 3745 6679 3744 6679 3746 6679 3736 6680 3735 6680 3747 6680 3747 6681 3735 6681 3748 6681 3747 6682 3748 6682 3749 6682 3749 6683 3748 6683 3750 6683 3749 6684 3750 6684 3751 6684 3751 6685 3750 6685 3752 6685 3751 6686 3752 6686 3753 6686 3753 6687 3752 6687 3754 6687 3753 6688 3754 6688 3755 6688 3756 6689 3757 6689 3758 6689 3758 6690 3757 6690 3759 6690 3758 6691 3759 6691 3760 6691 3760 6692 3759 6692 3740 6692 3759 6693 3761 6693 3740 6693 3740 6694 3761 6694 3762 6694 3740 6695 3762 6695 3718 6695 3718 6696 3762 6696 3763 6696 3718 6697 3763 6697 3719 6697 3764 6698 3765 6698 3766 6698 3764 6699 3767 6699 3756 6699 3756 6700 3767 6700 3768 6700 3756 6701 3768 6701 3757 6701 3766 6702 3769 6702 3710 6702 3764 6703 3766 6703 3767 6703 3767 6704 3766 6704 3710 6704 3767 6705 3710 6705 3770 6705 3770 6706 3710 6706 3709 6706 3770 6707 3709 6707 3771 6707 3746 6708 3744 6708 3772 6708 3772 6709 3744 6709 3773 6709 3772 6710 3773 6710 3774 6710 3775 6711 3776 6711 2851 6711 2851 6712 3776 6712 3772 6712 2851 6713 3772 6713 2852 6713 2852 6714 3772 6714 3774 6714 3777 6715 3778 6715 3779 6715 3779 6716 3778 6716 3780 6716 3779 6717 3780 6717 3781 6717 3782 6718 3783 6718 3784 6718 3159 6719 3783 6719 3160 6719 3160 6720 3783 6720 3785 6720 3160 6721 3785 6721 3161 6721 3156 6722 3786 6722 3158 6722 3158 6723 3786 6723 3159 6723 3787 6724 3788 6724 3170 6724 3788 6725 3789 6725 3170 6725 3170 6726 3789 6726 3790 6726 3170 6727 3790 6727 3169 6727 3169 6728 3790 6728 3786 6728 3169 6729 3786 6729 3155 6729 3155 6730 3786 6730 3156 6730 3677 6731 3791 6731 3792 6731 3787 6732 3170 6732 3792 6732 3792 6733 3170 6733 3168 6733 3792 6734 3168 6734 3677 6734 3159 6735 3786 6735 3783 6735 3783 6736 3786 6736 3793 6736 3783 6737 3793 6737 3794 6737 3794 6738 3795 6738 3783 6738 3783 6739 3795 6739 3796 6739 3783 6740 3796 6740 3797 6740 3797 6741 3798 6741 3783 6741 3783 6742 3798 6742 3799 6742 3783 6743 3799 6743 3784 6743 3800 6744 3801 6744 3784 6744 3784 6745 3801 6745 3802 6745 3784 6746 3802 6746 3782 6746 3778 6747 3777 6747 3803 6747 3803 6748 3777 6748 3804 6748 3803 6749 3804 6749 3784 6749 3784 6750 3804 6750 3805 6750 3784 6751 3805 6751 3806 6751 3806 6752 3807 6752 3784 6752 3784 6753 3807 6753 3808 6753 3784 6754 3808 6754 3800 6754 3809 6755 3810 6755 3791 6755 3809 6756 3791 6756 3811 6756 3811 6757 3791 6757 3538 6757 3811 6758 3538 6758 3537 6758 3812 6759 3813 6759 3791 6759 3810 6760 3814 6760 3791 6760 3791 6761 3814 6761 3815 6761 3791 6762 3815 6762 3812 6762 3813 6763 3816 6763 3791 6763 3791 6764 3816 6764 3817 6764 3791 6765 3817 6765 3792 6765 3779 6766 3781 6766 3818 6766 3818 6767 3781 6767 3819 6767 3818 6768 3819 6768 3820 6768 3820 6769 3819 6769 3821 6769 3821 6770 3819 6770 3822 6770 3822 6771 3819 6771 3823 6771 3822 6772 3823 6772 3824 6772 3825 6773 3826 6773 3827 6773 3827 6774 3826 6774 3828 6774 3829 6775 3523 6775 3522 6775 3828 6776 3830 6776 3827 6776 3827 6777 3830 6777 3829 6777 3827 6778 3829 6778 3831 6778 3831 6779 3829 6779 3522 6779 3824 6780 3825 6780 3822 6780 3822 6781 3825 6781 3827 6781 3822 6782 3827 6782 3832 6782 3832 6783 3827 6783 3833 6783 3832 6784 3833 6784 3834 6784 3197 6785 3200 6785 3835 6785 3835 6786 3200 6786 3836 6786 3835 6787 3836 6787 3837 6787 3837 6788 3836 6788 3838 6788 3837 6789 3838 6789 3839 6789 3839 6790 3838 6790 3834 6790 3839 6791 3834 6791 3840 6791 3840 6792 3834 6792 3833 6792 3054 6793 3841 6793 3842 6793 3842 6794 3841 6794 3843 6794 3842 6795 3843 6795 3844 6795 3845 6796 3846 6796 3847 6796 3848 6797 3849 6797 3847 6797 3847 6798 3849 6798 3850 6798 3847 6799 3850 6799 3845 6799 3851 6800 3852 6800 3853 6800 3852 6801 3854 6801 3853 6801 3853 6802 3854 6802 3855 6802 3853 6803 3855 6803 3856 6803 3857 6804 3858 6804 3859 6804 3853 6805 3860 6805 3851 6805 3851 6806 3860 6806 3861 6806 3851 6807 3861 6807 3862 6807 3862 6808 3861 6808 3863 6808 3862 6809 3863 6809 3864 6809 3859 6810 3858 6810 3865 6810 3865 6811 3858 6811 3866 6811 3865 6812 3866 6812 3867 6812 3867 6813 3866 6813 3868 6813 3868 6814 3866 6814 3869 6814 3868 6815 3869 6815 3870 6815 3870 6816 3869 6816 3871 6816 3870 6817 3871 6817 3872 6817 3872 6818 3871 6818 3873 6818 3872 6819 3873 6819 3874 6819 3874 6820 3873 6820 3875 6820 3874 6821 3875 6821 3876 6821 3876 6822 3875 6822 3877 6822 3876 6823 3877 6823 3847 6823 3847 6824 3877 6824 3878 6824 3847 6825 3878 6825 3848 6825 3857 6826 3859 6826 3863 6826 3863 6827 3859 6827 3879 6827 3863 6828 3879 6828 3864 6828 3880 6829 3881 6829 3882 6829 3883 6830 3884 6830 3885 6830 3886 6831 3887 6831 3888 6831 3888 6832 3887 6832 3889 6832 3888 6833 3889 6833 3890 6833 3890 6834 3889 6834 3891 6834 3890 6835 3891 6835 3883 6835 3853 6836 3892 6836 3860 6836 3860 6837 3892 6837 3893 6837 3860 6838 3893 6838 3861 6838 3894 6839 3895 6839 3896 6839 3896 6840 3895 6840 3897 6840 3896 6841 3897 6841 3898 6841 3894 6842 3896 6842 3899 6842 3899 6843 3896 6843 3900 6843 3899 6844 3900 6844 3901 6844 3880 6845 3882 6845 3902 6845 3892 6846 3886 6846 3893 6846 3893 6847 3886 6847 3888 6847 3893 6848 3888 6848 3903 6848 3904 6849 3905 6849 3899 6849 3899 6850 3905 6850 3906 6850 3899 6851 3906 6851 3894 6851 3907 6852 3908 6852 3890 6852 3883 6853 3885 6853 3890 6853 3890 6854 3885 6854 3909 6854 3890 6855 3909 6855 3907 6855 3871 6856 3869 6856 3910 6856 3910 6857 3869 6857 3866 6857 3910 6858 3866 6858 3903 6858 3873 6859 3871 6859 3911 6859 3911 6860 3871 6860 3910 6860 3911 6861 3910 6861 3912 6861 3912 6862 3910 6862 3913 6862 3898 6863 3902 6863 3896 6863 3896 6864 3902 6864 3882 6864 3896 6865 3882 6865 3900 6865 3900 6866 3882 6866 3914 6866 3900 6867 3914 6867 3915 6867 3866 6868 3858 6868 3903 6868 3903 6869 3858 6869 3857 6869 3903 6870 3857 6870 3893 6870 3893 6871 3857 6871 3863 6871 3893 6872 3863 6872 3861 6872 3908 6873 3904 6873 3890 6873 3890 6874 3904 6874 3899 6874 3890 6875 3899 6875 3888 6875 3888 6876 3899 6876 3901 6876 3888 6877 3901 6877 3903 6877 3903 6878 3901 6878 3900 6878 3903 6879 3900 6879 3910 6879 3910 6880 3900 6880 3915 6880 3910 6881 3915 6881 3913 6881 3916 6882 3917 6882 3918 6882 3919 6883 3920 6883 3921 6883 3922 6884 3923 6884 3924 6884 3924 6885 3923 6885 3925 6885 3924 6886 3925 6886 3926 6886 3927 6887 3919 6887 3928 6887 3928 6888 3919 6888 3929 6888 3930 6889 3931 6889 3932 6889 3932 6890 3931 6890 3933 6890 3932 6891 3933 6891 3934 6891 3935 6892 3936 6892 3921 6892 3921 6893 3936 6893 3937 6893 3938 6894 3939 6894 3932 6894 3932 6895 3939 6895 3940 6895 3932 6896 3940 6896 3930 6896 3937 6897 3938 6897 3921 6897 3921 6898 3938 6898 3932 6898 3921 6899 3932 6899 3919 6899 3919 6900 3932 6900 3934 6900 3919 6901 3934 6901 3929 6901 3926 6902 3941 6902 3924 6902 3924 6903 3941 6903 3942 6903 3924 6904 3942 6904 3943 6904 3944 6905 3945 6905 3946 6905 3946 6906 3945 6906 3947 6906 3946 6907 3947 6907 3948 6907 3947 6908 3916 6908 3948 6908 3948 6909 3916 6909 3918 6909 3948 6910 3918 6910 3943 6910 3949 6911 3950 6911 3951 6911 3950 6912 3952 6912 3951 6912 3951 6913 3952 6913 3953 6913 3951 6914 3953 6914 3954 6914 3917 6915 3955 6915 3918 6915 3918 6916 3955 6916 3956 6916 3918 6917 3956 6917 3951 6917 3951 6918 3956 6918 3957 6918 3951 6919 3957 6919 3949 6919 3949 6920 3957 6920 3958 6920 3949 6921 3958 6921 3959 6921 3942 6922 3960 6922 3943 6922 3943 6923 3960 6923 3961 6923 3943 6924 3961 6924 3948 6924 3948 6925 3961 6925 3962 6925 3948 6926 3962 6926 3946 6926 3954 6927 3935 6927 3951 6927 3951 6928 3935 6928 3921 6928 3951 6929 3921 6929 3918 6929 3918 6930 3921 6930 3920 6930 3918 6931 3920 6931 3943 6931 3943 6932 3920 6932 3919 6932 3943 6933 3919 6933 3924 6933 3924 6934 3919 6934 3927 6934 3924 6935 3927 6935 3922 6935 3963 6936 3964 6936 3965 6936 3966 6937 3967 6937 3963 6937 3963 6938 3967 6938 3968 6938 3963 6939 3968 6939 3964 6939 3926 6940 3969 6940 3970 6940 3962 6941 3961 6941 3971 6941 3965 6942 3972 6942 3963 6942 3963 6943 3972 6943 3973 6943 3963 6944 3973 6944 3974 6944 3974 6945 3973 6945 3975 6945 3974 6946 3975 6946 3976 6946 3976 6947 3975 6947 3944 6947 3976 6948 3944 6948 3977 6948 3977 6949 3944 6949 3946 6949 3977 6950 3946 6950 3978 6950 3978 6951 3946 6951 3962 6951 3978 6952 3962 6952 3979 6952 3979 6953 3962 6953 3971 6953 3942 6954 3980 6954 3960 6954 3960 6955 3980 6955 3981 6955 3960 6956 3981 6956 3961 6956 3961 6957 3981 6957 3982 6957 3961 6958 3982 6958 3971 6958 3941 6959 3983 6959 3942 6959 3942 6960 3983 6960 3984 6960 3942 6961 3984 6961 3980 6961 3970 6962 3985 6962 3926 6962 3926 6963 3985 6963 3986 6963 3926 6964 3986 6964 3941 6964 3941 6965 3986 6965 3987 6965 3941 6966 3987 6966 3983 6966 3179 6967 3182 6967 3988 6967 3187 6968 3186 6968 3989 6968 3181 6969 3183 6969 3990 6969 3990 6970 3183 6970 3184 6970 3178 6971 3991 6971 3177 6971 3177 6972 3991 6972 3992 6972 3177 6973 3992 6973 3993 6973 3874 6974 3876 6974 3994 6974 3993 6975 3992 6975 3995 6975 3995 6976 3992 6976 3870 6976 3995 6977 3870 6977 3994 6977 3994 6978 3870 6978 3872 6978 3994 6979 3872 6979 3874 6979 3996 6980 3864 6980 3879 6980 3879 6981 3859 6981 3996 6981 3996 6982 3859 6982 3865 6982 3996 6983 3865 6983 3991 6983 3991 6984 3865 6984 3867 6984 3991 6985 3867 6985 3992 6985 3992 6986 3867 6986 3868 6986 3992 6987 3868 6987 3870 6987 3997 6988 3998 6988 3862 6988 3855 6989 3854 6989 3999 6989 3999 6990 3854 6990 3852 6990 3999 6991 3852 6991 3998 6991 3998 6992 3852 6992 3851 6992 3998 6993 3851 6993 3862 6993 3856 6994 3855 6994 4000 6994 4000 6995 3855 6995 3999 6995 4000 6996 3999 6996 4001 6996 4001 6997 3999 6997 3998 6997 4001 6998 3998 6998 4002 6998 4003 6999 4004 6999 4005 6999 4005 7000 4004 7000 4006 7000 4005 7001 4006 7001 4007 7001 4007 7002 4006 7002 4008 7002 4008 7003 4006 7003 3990 7003 4008 7004 3990 7004 3989 7004 3989 7005 3990 7005 3184 7005 3989 7006 3184 7006 3187 7006 3178 7007 3179 7007 3991 7007 3991 7008 3179 7008 3988 7008 3991 7009 3988 7009 3996 7009 3996 7010 3988 7010 3997 7010 3996 7011 3997 7011 3864 7011 3864 7012 3997 7012 3862 7012 3182 7013 3181 7013 3988 7013 3988 7014 3181 7014 3990 7014 3988 7015 3990 7015 3997 7015 3997 7016 3990 7016 4006 7016 3997 7017 4006 7017 3998 7017 3998 7018 4006 7018 4004 7018 3998 7019 4004 7019 4002 7019 4002 7020 4004 7020 4003 7020 4009 7021 3881 7021 3880 7021 4010 7022 4011 7022 4012 7022 4012 7023 4011 7023 4013 7023 4014 7024 4015 7024 4016 7024 4016 7025 4015 7025 4011 7025 4016 7026 4011 7026 4017 7026 4017 7027 4011 7027 4010 7027 4014 7028 4018 7028 4015 7028 4015 7029 4018 7029 4019 7029 4015 7030 4019 7030 4009 7030 3954 7031 3953 7031 4011 7031 4011 7032 3953 7032 3952 7032 3959 7033 4013 7033 3949 7033 3949 7034 4013 7034 4011 7034 3949 7035 4011 7035 3950 7035 3950 7036 4011 7036 3952 7036 3939 7037 3938 7037 4020 7037 4020 7038 3938 7038 3937 7038 4020 7039 3937 7039 3936 7039 4021 7040 3931 7040 4022 7040 4022 7041 3931 7041 3930 7041 4023 7042 4024 7042 4022 7042 4022 7043 4024 7043 4025 7043 4022 7044 4025 7044 4021 7044 4026 7045 4027 7045 4023 7045 4023 7046 4027 7046 4028 7046 4023 7047 4028 7047 4024 7047 4029 7048 4030 7048 4026 7048 4026 7049 4030 7049 4031 7049 4026 7050 4031 7050 4027 7050 4032 7051 4033 7051 4034 7051 4034 7052 4033 7052 4035 7052 4034 7053 4035 7053 4029 7053 4029 7054 4035 7054 4036 7054 4029 7055 4036 7055 4030 7055 3907 7056 3909 7056 4037 7056 4037 7057 3909 7057 3885 7057 4032 7058 4034 7058 4038 7058 4038 7059 4034 7059 4037 7059 4038 7060 4037 7060 4039 7060 4039 7061 4037 7061 3885 7061 4039 7062 3885 7062 3884 7062 3907 7063 4037 7063 3908 7063 3908 7064 4037 7064 4034 7064 3908 7065 4034 7065 3904 7065 3894 7066 3906 7066 4040 7066 4040 7067 3906 7067 3905 7067 3894 7068 4040 7068 3895 7068 3895 7069 4040 7069 4041 7069 3895 7070 4041 7070 3897 7070 4009 7071 3880 7071 4015 7071 4015 7072 3880 7072 3902 7072 4015 7073 3902 7073 3898 7073 3930 7074 3940 7074 4022 7074 4022 7075 3940 7075 3939 7075 4022 7076 3939 7076 4023 7076 4023 7077 3939 7077 4020 7077 4023 7078 4020 7078 4026 7078 4026 7079 4020 7079 4042 7079 4026 7080 4042 7080 4029 7080 4029 7081 4042 7081 4041 7081 4029 7082 4041 7082 4034 7082 4034 7083 4041 7083 4040 7083 4034 7084 4040 7084 3904 7084 3904 7085 4040 7085 3905 7085 3936 7086 3935 7086 4020 7086 4020 7087 3935 7087 3954 7087 4020 7088 3954 7088 4042 7088 4042 7089 3954 7089 4011 7089 4042 7090 4011 7090 4041 7090 4041 7091 4011 7091 4015 7091 4041 7092 4015 7092 3897 7092 3897 7093 4015 7093 3898 7093 4043 7094 4044 7094 4045 7094 3971 7095 3982 7095 4046 7095 3980 7096 3984 7096 4047 7096 4048 7097 4043 7097 4049 7097 4050 7098 4051 7098 3977 7098 3977 7099 4051 7099 4052 7099 3977 7100 4052 7100 3976 7100 3976 7101 4052 7101 4053 7101 3976 7102 4053 7102 3974 7102 4054 7103 4055 7103 4056 7103 4056 7104 4055 7104 4057 7104 4056 7105 4057 7105 4050 7105 4050 7106 4057 7106 4058 7106 4050 7107 4058 7107 4051 7107 4059 7108 4060 7108 4056 7108 4056 7109 4060 7109 4061 7109 4056 7110 4061 7110 4054 7110 4062 7111 4059 7111 4063 7111 4063 7112 4059 7112 4064 7112 4062 7113 4065 7113 4059 7113 4059 7114 4065 7114 4066 7114 4059 7115 4066 7115 4060 7115 4067 7116 4068 7116 4064 7116 4064 7117 4068 7117 4069 7117 4064 7118 4069 7118 4063 7118 4070 7119 4071 7119 4072 7119 4072 7120 4071 7120 4073 7120 4073 7121 4074 7121 4072 7121 4072 7122 4074 7122 4075 7122 4072 7123 4075 7123 4064 7123 4064 7124 4075 7124 4076 7124 4064 7125 4076 7125 4067 7125 4044 7126 4077 7126 4078 7126 4043 7127 4048 7127 4044 7127 4044 7128 4048 7128 4079 7128 4044 7129 4079 7129 4077 7129 4080 7130 4081 7130 4047 7130 4047 7131 4081 7131 4082 7131 3969 7132 4081 7132 3970 7132 3970 7133 4081 7133 4080 7133 3970 7134 4080 7134 3985 7134 3984 7135 3983 7135 4047 7135 4047 7136 3983 7136 3987 7136 4047 7137 3987 7137 4080 7137 4080 7138 3987 7138 3986 7138 4080 7139 3986 7139 3985 7139 3971 7140 4056 7140 3979 7140 3979 7141 4056 7141 4050 7141 3979 7142 4050 7142 3978 7142 3978 7143 4050 7143 3977 7143 3982 7144 3981 7144 4046 7144 4046 7145 3981 7145 3980 7145 4046 7146 3980 7146 4045 7146 4045 7147 3980 7147 4047 7147 4045 7148 4047 7148 4043 7148 4043 7149 4047 7149 4082 7149 4043 7150 4082 7150 4049 7150 3971 7151 4046 7151 4056 7151 4056 7152 4046 7152 4045 7152 4056 7153 4045 7153 4059 7153 4059 7154 4045 7154 4044 7154 4059 7155 4044 7155 4064 7155 4064 7156 4044 7156 4078 7156 4064 7157 4078 7157 4072 7157 4083 7158 4084 7158 4085 7158 4085 7159 4084 7159 4086 7159 4067 7160 4076 7160 4087 7160 4087 7161 4076 7161 4075 7161 4075 7162 4074 7162 4087 7162 4087 7163 4074 7163 4073 7163 4087 7164 4073 7164 4088 7164 4088 7165 4073 7165 4071 7165 4088 7166 4071 7166 4089 7166 4089 7167 4071 7167 4070 7167 4067 7168 4087 7168 4068 7168 4068 7169 4087 7169 4090 7169 4068 7170 4090 7170 4069 7170 4066 7171 4065 7171 4091 7171 4091 7172 4065 7172 4062 7172 4091 7173 4062 7173 4090 7173 4090 7174 4062 7174 4063 7174 4090 7175 4063 7175 4069 7175 4092 7176 4093 7176 4094 7176 4094 7177 4093 7177 4095 7177 4094 7178 4095 7178 4055 7178 4055 7179 4095 7179 4096 7179 4055 7180 4096 7180 4057 7180 4055 7181 4054 7181 4094 7181 4094 7182 4054 7182 4061 7182 4094 7183 4061 7183 4091 7183 4091 7184 4061 7184 4060 7184 4091 7185 4060 7185 4066 7185 4097 7186 3655 7186 3654 7186 3654 7187 3652 7187 4097 7187 4097 7188 3652 7188 3650 7188 4097 7189 3650 7189 4098 7189 4098 7190 3650 7190 3648 7190 4098 7191 3648 7191 3647 7191 3655 7192 4097 7192 3642 7192 3642 7193 4097 7193 4099 7193 3642 7194 4099 7194 3640 7194 3640 7195 4099 7195 3613 7195 3613 7196 4099 7196 4100 7196 3613 7197 4100 7197 3615 7197 3701 7198 3618 7198 4101 7198 4101 7199 3618 7199 4086 7199 4086 7200 3618 7200 3617 7200 4086 7201 3617 7201 4085 7201 4085 7202 3617 7202 3620 7202 4085 7203 3620 7203 4100 7203 4100 7204 3620 7204 3616 7204 4100 7205 3616 7205 3615 7205 4102 7206 3686 7206 3687 7206 3687 7207 3697 7207 4102 7207 4102 7208 3697 7208 3699 7208 4102 7209 3699 7209 4103 7209 4103 7210 3699 7210 3701 7210 4103 7211 3701 7211 4104 7211 4104 7212 3701 7212 4101 7212 4105 7213 4106 7213 4107 7213 3686 7214 4102 7214 3684 7214 3684 7215 4102 7215 4105 7215 3684 7216 4105 7216 3690 7216 3690 7217 4105 7217 4107 7217 3690 7218 4107 7218 3693 7218 4083 7219 4085 7219 4108 7219 4108 7220 4085 7220 4100 7220 4108 7221 4100 7221 4109 7221 4110 7222 4098 7222 4111 7222 4111 7223 4098 7223 3647 7223 4111 7224 3647 7224 3645 7224 4110 7225 4092 7225 4098 7225 4098 7226 4092 7226 4094 7226 4098 7227 4094 7227 4097 7227 4097 7228 4094 7228 4091 7228 4097 7229 4091 7229 4099 7229 4099 7230 4091 7230 4090 7230 4099 7231 4090 7231 4100 7231 4100 7232 4090 7232 4087 7232 4100 7233 4087 7233 4109 7233 4109 7234 4087 7234 4088 7234 4112 7235 4113 7235 4114 7235 4114 7236 4113 7236 4115 7236 4114 7237 4115 7237 3051 7237 4116 7238 4117 7238 4118 7238 4119 7239 3040 7239 3061 7239 4117 7240 4120 7240 4118 7240 4118 7241 4120 7241 4121 7241 4118 7242 4121 7242 4122 7242 4122 7243 4121 7243 4123 7243 4122 7244 4123 7244 3061 7244 3061 7245 4123 7245 4124 7245 3061 7246 4124 7246 4119 7246 4119 7247 4124 7247 4125 7247 3066 7248 3065 7248 4126 7248 4126 7249 3065 7249 3063 7249 3063 7250 3062 7250 4126 7250 4126 7251 3062 7251 4127 7251 4126 7252 4127 7252 4128 7252 4128 7253 4127 7253 4129 7253 4130 7254 4131 7254 4132 7254 3062 7255 3070 7255 4127 7255 4127 7256 3070 7256 4130 7256 4127 7257 4130 7257 4133 7257 4133 7258 4130 7258 4132 7258 4128 7259 4116 7259 4126 7259 4126 7260 4116 7260 4118 7260 4126 7261 4118 7261 3066 7261 3066 7262 4118 7262 3067 7262 3061 7263 3060 7263 4122 7263 4122 7264 3060 7264 3058 7264 4122 7265 3058 7265 4118 7265 4118 7266 3058 7266 3057 7266 4118 7267 3057 7267 3067 7267 4134 7268 4135 7268 4136 7268 4131 7269 4137 7269 4132 7269 4132 7270 4137 7270 4136 7270 4132 7271 4136 7271 4133 7271 4138 7272 4129 7272 4127 7272 4133 7273 4136 7273 4127 7273 4127 7274 4136 7274 4135 7274 4127 7275 4135 7275 4138 7275 4134 7276 4136 7276 4139 7276 4139 7277 4136 7277 4140 7277 4139 7278 4140 7278 4141 7278 4142 7279 4143 7279 4140 7279 4140 7280 4143 7280 4144 7280 4140 7281 4144 7281 4141 7281 4145 7282 4146 7282 4147 7282 4147 7283 4148 7283 4142 7283 4142 7284 4148 7284 4149 7284 4142 7285 4149 7285 4143 7285 4142 7286 4150 7286 4151 7286 4142 7287 4151 7287 4152 7287 4152 7288 4151 7288 4153 7288 4152 7289 4153 7289 4154 7289 4152 7290 4155 7290 4142 7290 4142 7291 4155 7291 4156 7291 4142 7292 4156 7292 4147 7292 4147 7293 4156 7293 4157 7293 4147 7294 4157 7294 4145 7294 4158 7295 4159 7295 4140 7295 4140 7296 4159 7296 4160 7296 4140 7297 4160 7297 4142 7297 4142 7298 4160 7298 4161 7298 4142 7299 4161 7299 4150 7299 4137 7300 4162 7300 4136 7300 4136 7301 4162 7301 4163 7301 4136 7302 4163 7302 4140 7302 4140 7303 4163 7303 4164 7303 4140 7304 4164 7304 4158 7304 4165 7305 4166 7305 4167 7305 4167 7306 4166 7306 4168 7306 4167 7307 4168 7307 4112 7307 4169 7308 4170 7308 4166 7308 4166 7309 4170 7309 4171 7309 4166 7310 4171 7310 4168 7310 4169 7311 4166 7311 4172 7311 4172 7312 4166 7312 4173 7312 4172 7313 4173 7313 4174 7313 4175 7314 4176 7314 4177 7314 4178 7315 4179 7315 4173 7315 4173 7316 4179 7316 4180 7316 4173 7317 4180 7317 4174 7317 4176 7318 4175 7318 4181 7318 4181 7319 4175 7319 4182 7319 4181 7320 4182 7320 4183 7320 4184 7321 4185 7321 4175 7321 4175 7322 4185 7322 4186 7322 4175 7323 4186 7323 4187 7323 4188 7324 4189 7324 4187 7324 4187 7325 4189 7325 4190 7325 4187 7326 4190 7326 4175 7326 4175 7327 4190 7327 4191 7327 4175 7328 4191 7328 4182 7328 4177 7329 4178 7329 4175 7329 4175 7330 4178 7330 4173 7330 4175 7331 4173 7331 4184 7331 4184 7332 4173 7332 4192 7332 4165 7333 4193 7333 4166 7333 4166 7334 4193 7334 4194 7334 4166 7335 4194 7335 4173 7335 4173 7336 4194 7336 4195 7336 4173 7337 4195 7337 4192 7337 4196 7338 4197 7338 4198 7338 4198 7339 4197 7339 4199 7339 4198 7340 4199 7340 4200 7340 4200 7341 4199 7341 4201 7341 4200 7342 4201 7342 4202 7342 4202 7343 4201 7343 4203 7343 4202 7344 4203 7344 4204 7344 4204 7345 4203 7345 4205 7345 4204 7346 4205 7346 4206 7346 4206 7347 4205 7347 4207 7347 4206 7348 4207 7348 4208 7348 4208 7349 4207 7349 4209 7349 4208 7350 4209 7350 4210 7350 4210 7351 4209 7351 4211 7351 4211 7352 4209 7352 4212 7352 4211 7353 4212 7353 4213 7353 4212 7354 4214 7354 4213 7354 4213 7355 4214 7355 4215 7355 4213 7356 4215 7356 4216 7356 4216 7357 4215 7357 4217 7357 4216 7358 4217 7358 4218 7358 4218 7359 4217 7359 4219 7359 4218 7360 4219 7360 4220 7360 4220 7361 4219 7361 4221 7361 4220 7362 4221 7362 4222 7362 4222 7363 4221 7363 4223 7363 4223 7364 4221 7364 4224 7364 4223 7365 4224 7365 4225 7365 4225 7366 4224 7366 4226 7366 4225 7367 4226 7367 4227 7367 4227 7368 4226 7368 4228 7368 4227 7369 4228 7369 4229 7369 4229 7370 4228 7370 4230 7370 4229 7371 4230 7371 4231 7371 4231 7372 4230 7372 4232 7372 4231 7373 4232 7373 4233 7373 4233 7374 4232 7374 4234 7374 4233 7375 4234 7375 4235 7375 4235 7376 4234 7376 4236 7376 4235 7377 4236 7377 4237 7377 4237 7378 4236 7378 4238 7378 4237 7379 4238 7379 4239 7379 4239 7380 4238 7380 4240 7380 4239 7381 4240 7381 4241 7381 4241 7382 4240 7382 4242 7382 4241 7383 4242 7383 4243 7383 4243 7384 4242 7384 4244 7384 4243 7385 4244 7385 4245 7385 4245 7386 4244 7386 4246 7386 4245 7387 4246 7387 4247 7387 4246 7388 4248 7388 4247 7388 4247 7389 4248 7389 4249 7389 4247 7390 4249 7390 4250 7390 4250 7391 4249 7391 4251 7391 4250 7392 4251 7392 4252 7392 4252 7393 4251 7393 4253 7393 4252 7394 4253 7394 4254 7394 4254 7395 4253 7395 4255 7395 4256 7396 4257 7396 4258 7396 4258 7397 4257 7397 4259 7397 4258 7398 4259 7398 4255 7398 4255 7399 4259 7399 4260 7399 4255 7400 4260 7400 4254 7400 4261 7401 4262 7401 4263 7401 4263 7402 4262 7402 4264 7402 4256 7403 4265 7403 4257 7403 4257 7404 4265 7404 4266 7404 4257 7405 4266 7405 4261 7405 4261 7406 4266 7406 4267 7406 4261 7407 4267 7407 4262 7407 4268 7408 4269 7408 4270 7408 4270 7409 4269 7409 4271 7409 4270 7410 4271 7410 4272 7410 4273 7411 4274 7411 4275 7411 3262 7412 3263 7412 3380 7412 3380 7413 3263 7413 3264 7413 3380 7414 3264 7414 3265 7414 4275 7415 4274 7415 3382 7415 4273 7416 4275 7416 4276 7416 4276 7417 4275 7417 4277 7417 4276 7418 4277 7418 4278 7418 3380 7419 3382 7419 3262 7419 3262 7420 3382 7420 4274 7420 3262 7421 4274 7421 3260 7421 3260 7422 4274 7422 4279 7422 3260 7423 4279 7423 3258 7423 3258 7424 4279 7424 4280 7424 3258 7425 4280 7425 3256 7425 3256 7426 4280 7426 4281 7426 3256 7427 4281 7427 3254 7427 4112 7428 3253 7428 4282 7428 4282 7429 3253 7429 3251 7429 4282 7430 3251 7430 4283 7430 4283 7431 3251 7431 3250 7431 4283 7432 3250 7432 4284 7432 4284 7433 3250 7433 3254 7433 4284 7434 3254 7434 4285 7434 4285 7435 3254 7435 4281 7435 4286 7436 4112 7436 4287 7436 4287 7437 4112 7437 4288 7437 4287 7438 4288 7438 4289 7438 4286 7439 4290 7439 4112 7439 4112 7440 4290 7440 4291 7440 4112 7441 4291 7441 3253 7441 4292 7442 3765 7442 3764 7442 3746 7443 3772 7443 4269 7443 3776 7444 4293 7444 3772 7444 3772 7445 4293 7445 4271 7445 3772 7446 4271 7446 4269 7446 4292 7447 4196 7447 4294 7447 4294 7448 4196 7448 4295 7448 4296 7449 4297 7449 3764 7449 3764 7450 4297 7450 4298 7450 3764 7451 4298 7451 4292 7451 4292 7452 4298 7452 4197 7452 4292 7453 4197 7453 4196 7453 4269 7454 4299 7454 3746 7454 3746 7455 4299 7455 4300 7455 3746 7456 4300 7456 3745 7456 3745 7457 4300 7457 4301 7457 3745 7458 4301 7458 3740 7458 3740 7459 4301 7459 3760 7459 3764 7460 3756 7460 4296 7460 4296 7461 3756 7461 3758 7461 4296 7462 3758 7462 4302 7462 4302 7463 3758 7463 3760 7463 4302 7464 3760 7464 4303 7464 4303 7465 3760 7465 4301 7465 4304 7466 4305 7466 4306 7466 4307 7467 4308 7467 4309 7467 4309 7468 4308 7468 4310 7468 4310 7469 4308 7469 4311 7469 4310 7470 4311 7470 4312 7470 4307 7471 4309 7471 4313 7471 4313 7472 4309 7472 4314 7472 4313 7473 4314 7473 4315 7473 4315 7474 4314 7474 4316 7474 4315 7475 4316 7475 4317 7475 4317 7476 4316 7476 4318 7476 4317 7477 4318 7477 4305 7477 4305 7478 4318 7478 4319 7478 4305 7479 4319 7479 4306 7479 4311 7480 4320 7480 4312 7480 4312 7481 4320 7481 4321 7481 4312 7482 4321 7482 4322 7482 4322 7483 4321 7483 4323 7483 4322 7484 4323 7484 4324 7484 4324 7485 4323 7485 4325 7485 4324 7486 4325 7486 4326 7486 4326 7487 4325 7487 4327 7487 4326 7488 4327 7488 4328 7488 4328 7489 4327 7489 4329 7489 4328 7490 4329 7490 4306 7490 4306 7491 4329 7491 4330 7491 4306 7492 4330 7492 4304 7492 4331 7493 4312 7493 4332 7493 4332 7494 4312 7494 4322 7494 4332 7495 4322 7495 4333 7495 4333 7496 4322 7496 4324 7496 4333 7497 4324 7497 4334 7497 4334 7498 4324 7498 4326 7498 4334 7499 4326 7499 4335 7499 4335 7500 4326 7500 4328 7500 4335 7501 4328 7501 4336 7501 4336 7502 4328 7502 4306 7502 4336 7503 4306 7503 4337 7503 4337 7504 4306 7504 4319 7504 4337 7505 4319 7505 4338 7505 4338 7506 4319 7506 4318 7506 4338 7507 4318 7507 4339 7507 4339 7508 4318 7508 4316 7508 4339 7509 4316 7509 4340 7509 4340 7510 4316 7510 4314 7510 4340 7511 4314 7511 4341 7511 4341 7512 4314 7512 4309 7512 4341 7513 4309 7513 4342 7513 4342 7514 4309 7514 4310 7514 4342 7515 4310 7515 4331 7515 4331 7516 4310 7516 4312 7516 4343 7517 4313 7517 4344 7517 4344 7518 4313 7518 4315 7518 4345 7519 4346 7519 4317 7519 4317 7520 4346 7520 4347 7520 4317 7521 4347 7521 4315 7521 4315 7522 4347 7522 4348 7522 4315 7523 4348 7523 4344 7523 4345 7524 4317 7524 4349 7524 4349 7525 4317 7525 4305 7525 4349 7526 4305 7526 4350 7526 4351 7527 4352 7527 4305 7527 4305 7528 4352 7528 4353 7528 4305 7529 4353 7529 4350 7529 4304 7530 4330 7530 3846 7530 3846 7531 4354 7531 4304 7531 4304 7532 4354 7532 4355 7532 4304 7533 4355 7533 4305 7533 4305 7534 4355 7534 4356 7534 4305 7535 4356 7535 4351 7535 4357 7536 4358 7536 4359 7536 3849 7537 3848 7537 4360 7537 4360 7538 3848 7538 3878 7538 3849 7539 4360 7539 3850 7539 3850 7540 4360 7540 4361 7540 3850 7541 4361 7541 3845 7541 3846 7542 3845 7542 4362 7542 4362 7543 3845 7543 4361 7543 4362 7544 4361 7544 4363 7544 4363 7545 4361 7545 4364 7545 4365 7546 4366 7546 4367 7546 4367 7547 4366 7547 4368 7547 4367 7548 4368 7548 4369 7548 4366 7549 4370 7549 4368 7549 4368 7550 4370 7550 4371 7550 4368 7551 4371 7551 4359 7551 4359 7552 4371 7552 4372 7552 4359 7553 4372 7553 4357 7553 4373 7554 4374 7554 4369 7554 4369 7555 4374 7555 4375 7555 4369 7556 4375 7556 4367 7556 4367 7557 4375 7557 4376 7557 4367 7558 4376 7558 4365 7558 4377 7559 4378 7559 4379 7559 4378 7560 4377 7560 4380 7560 4380 7561 4377 7561 4381 7561 4380 7562 4381 7562 3881 7562 3913 7563 3915 7563 4382 7563 3875 7564 3873 7564 3911 7564 4383 7565 4384 7565 3911 7565 3911 7566 4384 7566 3877 7566 3911 7567 3877 7567 3875 7567 4385 7568 4360 7568 4384 7568 4384 7569 4360 7569 3878 7569 4384 7570 3878 7570 3877 7570 4382 7571 3915 7571 4377 7571 4377 7572 3915 7572 3914 7572 4377 7573 3914 7573 4381 7573 4383 7574 3913 7574 4384 7574 4384 7575 3913 7575 4382 7575 4384 7576 4382 7576 4385 7576 4385 7577 4382 7577 4377 7577 4385 7578 4377 7578 4386 7578 4386 7579 4377 7579 4379 7579 4386 7580 4379 7580 4387 7580 4387 7581 4373 7581 4386 7581 4386 7582 4373 7582 4369 7582 4386 7583 4369 7583 4385 7583 4385 7584 4369 7584 4368 7584 4385 7585 4368 7585 4360 7585 4360 7586 4368 7586 4359 7586 4360 7587 4359 7587 4361 7587 4361 7588 4359 7588 4358 7588 4361 7589 4358 7589 4364 7589 4388 7590 3959 7590 3958 7590 4388 7591 3958 7591 4389 7591 4390 7592 4391 7592 4392 7592 4391 7593 4393 7593 4392 7593 4392 7594 4393 7594 4394 7594 4392 7595 4394 7595 4395 7595 4395 7596 4394 7596 4396 7596 4395 7597 4396 7597 4397 7597 4398 7598 4399 7598 4400 7598 4400 7599 4399 7599 4401 7599 4400 7600 4401 7600 4402 7600 4402 7601 4401 7601 4403 7601 4404 7602 4405 7602 4406 7602 4406 7603 4405 7603 4402 7603 4406 7604 4402 7604 4407 7604 4407 7605 4402 7605 4403 7605 4408 7606 4409 7606 4410 7606 3966 7607 4409 7607 3967 7607 3967 7608 4409 7608 4408 7608 3967 7609 4408 7609 3968 7609 3968 7610 4408 7610 3964 7610 3964 7611 4408 7611 4411 7611 3964 7612 4411 7612 3965 7612 4412 7613 3973 7613 3972 7613 3973 7614 4412 7614 3975 7614 4404 7615 4390 7615 4405 7615 4405 7616 4390 7616 4392 7616 4405 7617 4392 7617 4402 7617 4402 7618 4392 7618 4413 7618 3956 7619 4413 7619 4414 7619 4414 7620 4413 7620 4392 7620 4414 7621 4392 7621 3958 7621 3958 7622 4392 7622 4395 7622 3958 7623 4395 7623 4389 7623 4389 7624 4395 7624 4397 7624 3955 7625 4415 7625 4416 7625 4416 7626 4415 7626 4412 7626 4416 7627 4412 7627 4411 7627 4411 7628 4412 7628 3972 7628 4411 7629 3972 7629 3965 7629 4415 7630 3916 7630 4412 7630 4412 7631 3916 7631 3947 7631 4412 7632 3947 7632 3975 7632 3975 7633 3947 7633 3945 7633 3975 7634 3945 7634 3944 7634 3956 7635 3955 7635 4413 7635 4413 7636 3955 7636 4416 7636 4413 7637 4416 7637 4402 7637 4402 7638 4416 7638 4411 7638 4402 7639 4411 7639 4400 7639 4400 7640 4411 7640 4408 7640 4400 7641 4408 7641 4398 7641 4398 7642 4408 7642 4410 7642 3846 7643 4330 7643 4329 7643 3847 7644 3846 7644 4417 7644 4417 7645 3846 7645 4329 7645 4417 7646 4329 7646 4418 7646 4418 7647 4329 7647 4327 7647 4419 7648 4420 7648 4325 7648 4325 7649 4420 7649 4421 7649 4325 7650 4421 7650 4327 7650 4327 7651 4421 7651 4422 7651 4327 7652 4422 7652 4418 7652 3966 7653 3963 7653 4325 7653 4325 7654 3963 7654 4423 7654 4325 7655 4423 7655 4419 7655 3966 7656 4325 7656 4424 7656 4424 7657 4325 7657 4323 7657 4424 7658 4323 7658 4425 7658 4425 7659 4323 7659 4321 7659 4425 7660 4321 7660 4426 7660 4311 7661 4427 7661 4428 7661 4311 7662 4428 7662 4320 7662 4320 7663 4428 7663 4429 7663 4320 7664 4429 7664 4321 7664 4321 7665 4429 7665 4430 7665 4321 7666 4430 7666 4426 7666 4431 7667 4432 7667 4308 7667 4308 7668 4432 7668 4433 7668 4308 7669 4433 7669 4311 7669 4311 7670 4433 7670 4434 7670 4311 7671 4434 7671 4427 7671 4343 7672 4435 7672 4313 7672 4313 7673 4435 7673 4436 7673 4313 7674 4436 7674 4307 7674 4307 7675 4436 7675 4437 7675 4307 7676 4437 7676 4308 7676 4308 7677 4437 7677 4438 7677 4308 7678 4438 7678 4431 7678 4336 7679 4439 7679 4335 7679 4335 7680 4439 7680 4440 7680 4335 7681 4440 7681 4334 7681 4334 7682 4440 7682 4441 7682 4334 7683 4441 7683 4333 7683 4333 7684 4441 7684 4442 7684 4333 7685 4442 7685 4332 7685 4332 7686 4442 7686 4443 7686 4332 7687 4443 7687 4331 7687 4331 7688 4443 7688 4444 7688 4331 7689 4444 7689 4342 7689 4342 7690 4444 7690 4445 7690 4342 7691 4445 7691 4341 7691 4341 7692 4445 7692 4446 7692 4341 7693 4446 7693 4340 7693 4340 7694 4446 7694 4447 7694 4340 7695 4447 7695 4339 7695 4339 7696 4447 7696 4448 7696 4339 7697 4448 7697 4338 7697 4338 7698 4448 7698 4449 7698 4338 7699 4449 7699 4337 7699 4337 7700 4449 7700 4450 7700 4337 7701 4450 7701 4336 7701 4336 7702 4450 7702 4439 7702 4010 7703 4012 7703 4451 7703 4013 7704 3959 7704 4388 7704 4404 7705 4406 7705 4452 7705 4404 7706 4452 7706 4390 7706 4397 7707 4396 7707 4453 7707 4453 7708 4396 7708 4394 7708 4453 7709 4394 7709 4454 7709 4454 7710 4394 7710 4393 7710 4454 7711 4393 7711 4452 7711 4452 7712 4393 7712 4391 7712 4452 7713 4391 7713 4390 7713 4012 7714 4013 7714 4451 7714 4451 7715 4013 7715 4388 7715 4451 7716 4388 7716 4453 7716 4453 7717 4388 7717 4389 7717 4453 7718 4389 7718 4397 7718 4014 7719 4016 7719 4455 7719 4455 7720 4016 7720 4017 7720 4455 7721 4017 7721 4010 7721 4018 7722 4014 7722 4456 7722 4456 7723 4014 7723 4455 7723 4456 7724 4455 7724 4457 7724 4457 7725 4455 7725 4458 7725 4459 7726 4460 7726 4461 7726 4461 7727 4460 7727 4458 7727 4461 7728 4458 7728 4462 7728 4462 7729 4458 7729 4455 7729 4344 7730 4459 7730 4343 7730 4343 7731 4459 7731 4461 7731 4343 7732 4461 7732 4435 7732 4435 7733 4461 7733 4436 7733 4454 7734 4438 7734 4437 7734 3966 7735 4424 7735 4409 7735 4409 7736 4424 7736 4425 7736 4409 7737 4425 7737 4410 7737 4410 7738 4425 7738 4426 7738 4410 7739 4426 7739 4398 7739 4398 7740 4426 7740 4430 7740 4398 7741 4430 7741 4399 7741 4399 7742 4430 7742 4429 7742 4399 7743 4429 7743 4401 7743 4401 7744 4429 7744 4428 7744 4401 7745 4428 7745 4403 7745 4403 7746 4428 7746 4427 7746 4403 7747 4427 7747 4407 7747 4407 7748 4427 7748 4434 7748 4407 7749 4434 7749 4406 7749 4406 7750 4434 7750 4433 7750 4406 7751 4433 7751 4452 7751 4452 7752 4433 7752 4432 7752 4452 7753 4432 7753 4454 7753 4454 7754 4432 7754 4431 7754 4454 7755 4431 7755 4438 7755 4010 7756 4451 7756 4455 7756 4455 7757 4451 7757 4453 7757 4455 7758 4453 7758 4462 7758 4462 7759 4453 7759 4454 7759 4462 7760 4454 7760 4461 7760 4461 7761 4454 7761 4437 7761 4461 7762 4437 7762 4436 7762 4348 7763 4347 7763 4463 7763 4371 7764 4370 7764 4464 7764 4351 7765 4356 7765 4363 7765 4363 7766 4356 7766 4355 7766 4363 7767 4355 7767 4362 7767 4362 7768 4355 7768 4354 7768 4362 7769 4354 7769 3846 7769 4363 7770 4364 7770 4351 7770 4351 7771 4364 7771 4358 7771 4351 7772 4358 7772 4352 7772 4352 7773 4358 7773 4357 7773 4352 7774 4357 7774 4353 7774 4353 7775 4357 7775 4372 7775 4353 7776 4372 7776 4350 7776 4350 7777 4372 7777 4371 7777 4350 7778 4371 7778 4349 7778 4349 7779 4371 7779 4464 7779 4349 7780 4464 7780 4345 7780 4345 7781 4464 7781 4463 7781 4345 7782 4463 7782 4346 7782 4346 7783 4463 7783 4347 7783 4465 7784 4009 7784 4456 7784 4456 7785 4009 7785 4019 7785 4456 7786 4019 7786 4018 7786 4379 7787 4465 7787 4387 7787 4387 7788 4465 7788 4466 7788 4387 7789 4466 7789 4373 7789 3881 7790 4009 7790 4380 7790 4380 7791 4009 7791 4465 7791 4380 7792 4465 7792 4378 7792 4378 7793 4465 7793 4379 7793 4463 7794 4375 7794 4466 7794 4466 7795 4375 7795 4374 7795 4466 7796 4374 7796 4373 7796 4370 7797 4366 7797 4464 7797 4464 7798 4366 7798 4365 7798 4464 7799 4365 7799 4463 7799 4463 7800 4365 7800 4376 7800 4463 7801 4376 7801 4375 7801 4344 7802 4348 7802 4459 7802 4459 7803 4348 7803 4463 7803 4459 7804 4463 7804 4460 7804 4460 7805 4463 7805 4466 7805 4460 7806 4466 7806 4458 7806 4458 7807 4466 7807 4465 7807 4458 7808 4465 7808 4457 7808 4457 7809 4465 7809 4456 7809 3138 7810 3137 7810 4467 7810 4468 7811 4469 7811 4470 7811 3666 7812 3676 7812 4471 7812 4058 7813 4057 7813 4096 7813 4421 7814 4420 7814 4472 7814 4472 7815 4420 7815 4419 7815 4423 7816 3963 7816 4468 7816 4468 7817 3963 7817 3974 7817 3974 7818 4053 7818 4468 7818 4468 7819 4053 7819 4052 7819 4468 7820 4052 7820 4096 7820 4096 7821 4052 7821 4051 7821 4096 7822 4051 7822 4058 7822 3995 7823 3994 7823 4467 7823 4467 7824 3994 7824 3876 7824 4467 7825 3876 7825 3847 7825 3847 7826 4417 7826 4467 7826 4467 7827 4417 7827 4418 7827 4467 7828 4418 7828 4472 7828 4472 7829 4418 7829 4422 7829 4472 7830 4422 7830 4421 7830 3995 7831 4467 7831 3993 7831 3993 7832 4467 7832 3137 7832 3993 7833 3137 7833 3177 7833 3172 7834 3174 7834 3675 7834 3675 7835 3174 7835 3175 7835 3175 7836 3176 7836 3675 7836 3675 7837 3176 7837 3190 7837 3675 7838 3190 7838 3189 7838 4470 7839 3671 7839 3670 7839 4470 7840 3670 7840 4471 7840 4471 7841 3670 7841 3668 7841 4471 7842 3668 7842 3666 7842 3658 7843 3660 7843 4469 7843 4469 7844 3660 7844 3662 7844 4469 7845 3662 7845 4470 7845 4470 7846 3662 7846 3664 7846 4470 7847 3664 7847 3671 7847 3658 7848 4469 7848 3656 7848 3656 7849 4469 7849 4110 7849 3656 7850 4110 7850 3644 7850 3644 7851 4110 7851 4111 7851 3644 7852 4111 7852 3645 7852 4096 7853 4095 7853 4468 7853 4468 7854 4095 7854 4093 7854 4468 7855 4093 7855 4469 7855 4469 7856 4093 7856 4092 7856 4469 7857 4092 7857 4110 7857 3188 7858 4471 7858 3189 7858 3189 7859 4471 7859 3676 7859 3189 7860 3676 7860 3675 7860 3188 7861 3138 7861 4471 7861 4471 7862 3138 7862 4467 7862 4471 7863 4467 7863 4470 7863 4470 7864 4467 7864 4472 7864 4470 7865 4472 7865 4468 7865 4468 7866 4472 7866 4419 7866 4468 7867 4419 7867 4423 7867 3749 7868 3751 7868 4473 7868 3751 7869 3753 7869 4473 7869 4473 7870 3753 7870 3755 7870 4473 7871 3755 7871 4474 7871 4475 7872 3734 7872 4476 7872 4476 7873 3734 7873 3736 7873 4476 7874 3736 7874 4477 7874 4477 7875 3736 7875 3747 7875 4477 7876 3747 7876 4478 7876 4478 7877 3747 7877 3749 7877 4478 7878 3749 7878 4479 7878 4479 7879 3749 7879 4473 7879 4480 7880 4481 7880 2897 7880 2906 7881 2905 7881 3734 7881 4480 7882 2897 7882 4475 7882 4475 7883 2897 7883 2899 7883 4475 7884 2899 7884 3734 7884 3734 7885 2899 7885 2901 7885 3734 7886 2901 7886 2906 7886 2904 7887 3731 7887 2905 7887 2905 7888 3731 7888 3733 7888 2905 7889 3733 7889 3734 7889 3755 7890 4482 7890 4474 7890 4474 7891 4482 7891 4483 7891 4474 7892 4483 7892 4484 7892 4484 7893 4483 7893 4485 7893 4484 7894 4485 7894 4486 7894 3694 7895 3693 7895 4107 7895 4486 7896 4485 7896 4106 7896 4106 7897 4485 7897 3682 7897 4106 7898 3682 7898 4107 7898 4107 7899 3682 7899 3681 7899 4107 7900 3681 7900 3694 7900 4288 7901 4112 7901 4114 7901 4114 7902 3051 7902 4288 7902 4288 7903 3051 7903 3052 7903 4288 7904 3052 7904 4289 7904 4289 7905 3052 7905 3053 7905 4289 7906 3053 7906 4487 7906 4487 7907 3053 7907 3050 7907 4487 7908 3050 7908 4488 7908 4488 7909 3050 7909 3044 7909 4488 7910 3044 7910 4489 7910 4489 7911 3044 7911 3043 7911 4489 7912 3043 7912 4490 7912 3054 7913 3842 7913 3043 7913 3043 7914 3842 7914 3844 7914 3043 7915 3844 7915 4490 7915 4442 7916 4491 7916 4443 7916 4443 7917 4491 7917 4492 7917 4443 7918 4492 7918 4444 7918 4444 7919 4492 7919 4493 7919 4444 7920 4493 7920 4445 7920 4445 7921 4493 7921 4494 7921 4445 7922 4494 7922 4446 7922 4446 7923 4494 7923 4495 7923 4446 7924 4495 7924 4447 7924 4447 7925 4495 7925 4496 7925 4447 7926 4496 7926 4448 7926 4448 7927 4496 7927 4497 7927 4448 7928 4497 7928 4449 7928 4449 7929 4497 7929 4498 7929 4449 7930 4498 7930 4450 7930 4450 7931 4498 7931 4499 7931 4450 7932 4499 7932 4439 7932 4439 7933 4499 7933 4500 7933 4439 7934 4500 7934 4440 7934 4440 7935 4500 7935 4501 7935 4440 7936 4501 7936 4441 7936 4441 7937 4501 7937 4502 7937 4441 7938 4502 7938 4442 7938 4442 7939 4502 7939 4491 7939 4083 7940 4125 7940 4084 7940 4084 7941 4125 7941 4124 7941 4084 7942 4124 7942 4086 7942 4086 7943 4124 7943 4123 7943 4086 7944 4123 7944 4101 7944 4101 7945 4123 7945 4121 7945 4101 7946 4121 7946 4104 7946 4104 7947 4121 7947 4103 7947 4129 7948 4106 7948 4128 7948 4128 7949 4106 7949 4105 7949 4128 7950 4105 7950 4116 7950 4116 7951 4105 7951 4102 7951 4116 7952 4102 7952 4117 7952 4117 7953 4102 7953 4103 7953 4117 7954 4103 7954 4120 7954 4120 7955 4103 7955 4121 7955 4106 7956 4129 7956 4486 7956 4486 7957 4129 7957 4138 7957 4486 7958 4138 7958 4484 7958 4484 7959 4138 7959 4135 7959 4484 7960 4135 7960 4474 7960 4474 7961 4135 7961 4134 7961 4474 7962 4134 7962 4473 7962 4473 7963 4134 7963 4139 7963 4473 7964 4139 7964 4479 7964 4479 7965 4139 7965 4141 7965 4479 7966 4141 7966 4478 7966 4478 7967 4141 7967 4144 7967 4478 7968 4144 7968 4477 7968 4477 7969 4144 7969 4143 7969 4477 7970 4143 7970 4476 7970 4143 7971 4149 7971 4476 7971 4476 7972 4149 7972 4148 7972 4476 7973 4148 7973 4475 7973 4475 7974 4148 7974 4480 7974 4480 7975 4148 7975 4147 7975 4480 7976 4147 7976 4146 7976 4146 7977 4503 7977 4480 7977 4480 7978 4503 7978 4504 7978 4480 7979 4504 7979 4481 7979 4505 7980 4188 7980 4187 7980 4278 7981 4505 7981 4276 7981 4276 7982 4505 7982 4187 7982 4276 7983 4187 7983 4273 7983 4273 7984 4187 7984 4186 7984 4273 7985 4186 7985 4274 7985 4274 7986 4186 7986 4185 7986 4274 7987 4185 7987 4279 7987 4279 7988 4185 7988 4184 7988 4279 7989 4184 7989 4280 7989 4280 7990 4184 7990 4192 7990 4280 7991 4192 7991 4281 7991 4281 7992 4192 7992 4195 7992 4281 7993 4195 7993 4285 7993 4285 7994 4195 7994 4194 7994 4285 7995 4194 7995 4284 7995 4284 7996 4194 7996 4193 7996 4284 7997 4193 7997 4283 7997 4283 7998 4193 7998 4165 7998 4283 7999 4165 7999 4282 7999 4282 8000 4165 8000 4167 8000 4282 8001 4167 8001 4112 8001 4506 8002 4507 8002 4508 8002 4508 8003 4507 8003 4509 8003 4507 8004 4510 8004 4509 8004 4509 8005 4510 8005 4511 8005 4509 8006 4511 8006 3466 8006 3466 8007 4511 8007 4512 8007 3466 8008 4512 8008 4513 8008 4514 8009 4515 8009 4516 8009 4516 8010 4515 8010 4517 8010 4516 8011 4517 8011 4518 8011 4506 8012 4508 8012 4519 8012 4519 8013 4508 8013 4520 8013 4519 8014 4520 8014 4521 8014 4521 8015 4520 8015 4518 8015 4521 8016 4518 8016 4522 8016 4522 8017 4518 8017 4517 8017 4522 8018 4517 8018 4523 8018 4524 8019 3450 8019 4525 8019 4525 8020 3450 8020 3453 8020 4526 8021 3451 8021 4527 8021 4527 8022 3451 8022 3450 8022 4527 8023 3450 8023 4528 8023 4528 8024 3450 8024 4524 8024 4529 8025 4530 8025 3481 8025 3481 8026 4530 8026 4531 8026 3481 8027 4531 8027 3488 8027 3488 8028 4531 8028 4532 8028 3488 8029 4532 8029 3453 8029 3453 8030 4532 8030 4533 8030 3453 8031 4533 8031 4525 8031 4529 8032 3481 8032 4534 8032 4534 8033 3481 8033 3483 8033 4534 8034 3483 8034 4535 8034 3479 8035 4536 8035 3486 8035 3486 8036 4536 8036 4537 8036 3486 8037 4537 8037 3485 8037 3485 8038 4537 8038 4538 8038 3485 8039 4538 8039 3483 8039 3483 8040 4538 8040 4539 8040 3483 8041 4539 8041 4535 8041 4540 8042 4541 8042 3479 8042 3479 8043 4541 8043 4542 8043 3479 8044 4542 8044 4536 8044 4540 8045 3479 8045 4543 8045 4543 8046 3479 8046 3477 8046 4543 8047 3477 8047 4544 8047 4544 8048 3477 8048 3475 8048 4544 8049 3475 8049 4545 8049 4545 8050 3475 8050 3474 8050 4545 8051 3474 8051 4546 8051 3470 8052 4547 8052 3472 8052 3472 8053 4547 8053 4548 8053 3472 8054 4548 8054 3474 8054 3474 8055 4548 8055 4549 8055 3474 8056 4549 8056 4546 8056 3468 8057 4550 8057 3470 8057 3470 8058 4550 8058 4551 8058 3470 8059 4551 8059 4547 8059 3466 8060 4513 8060 4552 8060 3466 8061 4552 8061 3467 8061 4552 8062 4553 8062 3467 8062 3467 8063 4553 8063 4554 8063 3467 8064 4554 8064 3468 8064 3468 8065 4554 8065 4555 8065 3468 8066 4555 8066 4550 8066 4556 8067 4515 8067 4557 8067 4557 8068 4515 8068 4514 8068 4558 8069 4559 8069 4556 8069 4556 8070 4559 8070 4515 8070 4560 8071 2807 8071 4561 8071 4561 8072 2807 8072 2806 8072 4517 8073 4560 8073 4523 8073 4523 8074 4560 8074 4561 8074 3192 8075 3191 8075 3364 8075 4562 8076 4563 8076 3581 8076 3581 8077 4563 8077 3580 8077 4564 8078 4565 8078 4566 8078 2842 8079 3191 8079 3212 8079 3364 8080 3191 8080 3371 8080 3371 8081 3191 8081 2842 8081 3371 8082 2842 8082 4566 8082 4566 8083 2842 8083 4567 8083 4566 8084 4567 8084 4564 8084 3367 8085 3368 8085 3354 8085 3212 8086 4568 8086 2842 8086 2842 8087 4568 8087 3580 8087 2842 8088 3580 8088 2843 8088 2843 8089 3580 8089 4563 8089 3354 8090 3356 8090 3358 8090 3364 8091 3367 8091 3192 8091 3192 8092 3367 8092 3354 8092 3192 8093 3354 8093 3360 8093 3360 8094 3354 8094 3358 8094 3547 8095 3431 8095 3430 8095 4569 8096 4570 8096 3430 8096 3430 8097 4570 8097 4571 8097 3430 8098 4571 8098 4572 8098 4572 8099 4573 8099 4574 8099 4574 8100 4573 8100 4575 8100 4574 8101 4575 8101 4576 8101 4576 8102 4575 8102 3585 8102 4576 8103 3585 8103 4577 8103 4577 8104 3585 8104 3587 8104 4577 8105 3587 8105 4578 8105 4578 8106 3587 8106 3584 8106 4578 8107 3584 8107 4579 8107 4572 8108 4574 8108 3430 8108 3430 8109 4574 8109 4580 8109 3430 8110 4580 8110 3547 8110 4581 8111 4582 8111 4583 8111 4583 8112 4582 8112 4584 8112 4583 8113 4584 8113 4580 8113 4580 8114 4584 8114 4585 8114 4580 8115 4585 8115 3547 8115 3546 8116 3544 8116 4581 8116 4581 8117 3544 8117 4586 8117 4581 8118 4586 8118 4582 8118 3584 8119 3606 8119 4579 8119 4579 8120 3606 8120 3603 8120 4579 8121 3603 8121 4587 8121 4587 8122 3603 8122 3599 8122 4587 8123 3599 8123 4588 8123 4588 8124 3599 8124 3596 8124 4588 8125 3596 8125 4589 8125 4589 8126 3596 8126 3594 8126 4589 8127 3594 8127 4590 8127 4590 8128 3594 8128 4591 8128 4590 8129 4591 8129 4581 8129 4581 8130 4591 8130 4592 8130 4581 8131 4592 8131 3546 8131 3546 8132 4592 8132 4593 8132 3546 8133 4593 8133 4594 8133 4595 8134 4596 8134 4597 8134 4584 8135 4582 8135 4598 8135 4595 8136 4597 8136 4598 8136 4598 8137 4597 8137 4584 8137 4584 8138 4597 8138 4599 8138 4584 8139 4599 8139 4585 8139 4585 8140 4599 8140 3548 8140 4585 8141 3548 8141 3547 8141 3696 8142 3683 8142 4600 8142 4600 8143 4601 8143 3696 8143 3696 8144 4601 8144 4602 8144 3696 8145 4602 8145 4603 8145 4604 8146 4605 8146 3771 8146 3771 8147 4605 8147 4606 8147 4606 8148 4607 8148 3771 8148 3771 8149 4607 8149 4608 8149 3771 8150 4608 8150 3770 8150 4603 8151 4609 8151 3696 8151 3696 8152 4609 8152 4610 8152 3696 8153 4610 8153 4611 8153 4612 8154 4613 8154 3771 8154 3771 8155 4613 8155 4614 8155 3771 8156 4614 8156 4604 8156 4615 8157 4616 8157 4617 8157 4617 8158 4616 8158 4618 8158 4617 8159 4618 8159 4619 8159 4619 8160 4618 8160 4620 8160 4619 8161 4620 8161 4621 8161 4621 8162 4620 8162 4622 8162 4621 8163 4622 8163 4623 8163 4623 8164 4622 8164 4624 8164 4623 8165 4624 8165 4625 8165 4625 8166 4624 8166 3696 8166 4625 8167 3696 8167 4626 8167 4626 8168 3696 8168 4611 8168 4626 8169 4611 8169 4627 8169 4627 8170 4611 8170 4628 8170 4627 8171 4628 8171 4629 8171 4629 8172 4628 8172 4612 8172 4629 8173 4612 8173 4630 8173 4630 8174 4612 8174 3771 8174 4630 8175 3771 8175 4631 8175 4631 8176 3771 8176 4632 8176 4631 8177 4632 8177 4633 8177 4633 8178 4632 8178 4634 8178 4633 8179 4634 8179 4635 8179 4635 8180 4634 8180 4615 8180 4635 8181 4615 8181 4617 8181 4636 8182 4637 8182 4611 8182 4638 8183 4639 8183 4612 8183 4612 8184 4639 8184 4640 8184 4612 8185 4640 8185 4613 8185 4641 8186 4642 8186 4628 8186 4643 8187 4644 8187 4628 8187 4628 8188 4644 8188 4645 8188 4628 8189 4645 8189 4641 8189 4646 8190 4647 8190 4628 8190 4628 8191 4647 8191 4648 8191 4628 8192 4648 8192 4643 8192 4642 8193 4649 8193 4628 8193 4628 8194 4649 8194 4650 8194 4628 8195 4650 8195 4612 8195 4612 8196 4650 8196 4651 8196 4612 8197 4651 8197 4638 8197 4611 8198 4637 8198 4628 8198 4628 8199 4637 8199 4652 8199 4628 8200 4652 8200 4653 8200 4653 8201 4654 8201 4628 8201 4628 8202 4654 8202 4655 8202 4628 8203 4655 8203 4656 8203 4657 8204 4646 8204 4658 8204 4658 8205 4646 8205 4628 8205 4658 8206 4628 8206 4659 8206 4659 8207 4628 8207 4656 8207 4610 8208 4660 8208 4611 8208 4611 8209 4660 8209 4661 8209 4611 8210 4661 8210 4636 8210 3198 8211 3203 8211 4662 8211 4662 8212 3203 8212 4663 8212 4663 8213 3203 8213 4664 8213 4664 8214 3203 8214 3202 8214 3202 8215 3201 8215 4665 8215 4665 8216 3201 8216 3249 8216 4665 8217 3249 8217 4666 8217 4666 8218 3249 8218 4667 8218 4667 8219 3249 8219 3253 8219 4667 8220 3253 8220 4291 8220 4668 8221 4290 8221 4286 8221 4669 8222 4670 8222 4671 8222 3202 8223 4671 8223 4664 8223 4664 8224 4671 8224 4670 8224 4664 8225 4670 8225 4663 8225 3202 8226 4665 8226 4671 8226 4671 8227 4665 8227 4668 8227 4671 8228 4668 8228 4669 8228 4669 8229 4668 8229 4286 8229 4291 8230 4290 8230 4667 8230 4667 8231 4290 8231 4668 8231 4667 8232 4668 8232 4666 8232 4666 8233 4668 8233 4665 8233 4662 8234 4663 8234 4672 8234 4672 8235 4663 8235 4670 8235 4672 8236 4670 8236 4673 8236 4673 8237 4670 8237 4674 8237 4675 8238 4676 8238 4677 8238 4677 8239 4676 8239 4678 8239 4679 8240 4287 8240 4289 8240 4289 8241 4680 8241 4679 8241 4679 8242 4680 8242 4681 8242 4679 8243 4681 8243 4677 8243 4677 8244 4681 8244 4682 8244 4677 8245 4682 8245 4675 8245 4286 8246 4287 8246 4669 8246 4669 8247 4287 8247 4679 8247 4669 8248 4679 8248 4670 8248 4670 8249 4679 8249 4677 8249 4670 8250 4677 8250 4674 8250 4674 8251 4677 8251 4678 8251 4683 8252 4684 8252 4685 8252 4684 8253 4676 8253 4675 8253 4683 8254 4685 8254 4686 8254 4687 8255 4688 8255 4689 8255 4689 8256 4688 8256 4690 8256 4689 8257 4690 8257 4691 8257 4691 8258 4690 8258 4489 8258 4692 8259 4690 8259 4685 8259 4685 8260 4690 8260 4688 8260 4685 8261 4688 8261 4686 8261 4686 8262 4688 8262 4687 8262 4686 8263 4687 8263 4693 8263 4684 8264 4675 8264 4685 8264 4685 8265 4675 8265 4682 8265 4685 8266 4682 8266 4692 8266 4692 8267 4682 8267 4681 8267 4692 8268 4681 8268 4680 8268 4489 8269 4690 8269 4488 8269 4488 8270 4690 8270 4692 8270 4488 8271 4692 8271 4487 8271 4487 8272 4692 8272 4680 8272 4487 8273 4680 8273 4289 8273 4694 8274 4695 8274 4687 8274 4687 8275 4695 8275 4696 8275 4687 8276 4696 8276 4693 8276 4489 8277 4490 8277 4691 8277 4691 8278 4490 8278 4694 8278 4691 8279 4694 8279 4689 8279 4689 8280 4694 8280 4687 8280 4697 8281 4695 8281 4698 8281 4698 8282 4695 8282 4694 8282 4698 8283 4694 8283 4699 8283 4699 8284 4694 8284 4490 8284 4699 8285 4490 8285 3844 8285 4698 8286 4699 8286 4700 8286 4701 8287 4697 8287 4698 8287 4702 8288 4703 8288 4700 8288 4700 8289 4703 8289 4704 8289 4700 8290 4704 8290 4698 8290 4698 8291 4704 8291 4705 8291 4698 8292 4705 8292 4701 8292 4700 8293 3841 8293 3054 8293 4706 8294 4707 8294 4708 8294 4708 8295 4707 8295 4709 8295 4707 8296 4710 8296 4711 8296 4712 8297 4709 8297 4713 8297 4713 8298 4709 8298 4707 8298 4713 8299 4707 8299 4714 8299 4714 8300 4707 8300 4711 8300 4706 8301 4702 8301 4707 8301 4707 8302 4702 8302 4700 8302 4707 8303 4700 8303 4710 8303 4710 8304 4700 8304 3054 8304 4710 8305 3054 8305 3153 8305 4699 8306 3844 8306 4700 8306 4700 8307 3844 8307 3843 8307 4700 8308 3843 8308 3841 8308 4715 8309 3677 8309 3678 8309 4716 8310 4210 8310 4211 8310 3638 8311 3639 8311 4717 8311 4264 8312 4715 8312 4263 8312 4263 8313 4715 8313 3678 8313 4263 8314 3678 8314 4261 8314 4261 8315 3678 8315 3679 8315 4261 8316 3679 8316 4257 8316 4257 8317 3679 8317 4259 8317 4259 8318 3679 8318 3672 8318 4259 8319 3672 8319 4260 8319 4260 8320 3672 8320 3673 8320 4260 8321 3673 8321 3674 8321 3669 8322 4247 8322 3667 8322 3667 8323 4247 8323 4250 8323 3667 8324 4250 8324 3665 8324 3665 8325 4250 8325 4252 8325 3665 8326 4252 8326 3674 8326 3674 8327 4252 8327 4254 8327 3674 8328 4254 8328 4260 8328 3659 8329 4239 8329 3661 8329 3661 8330 4239 8330 4241 8330 3661 8331 4241 8331 3663 8331 3663 8332 4241 8332 4243 8332 3663 8333 4243 8333 3669 8333 3669 8334 4243 8334 4245 8334 3669 8335 4245 8335 4247 8335 3646 8336 4229 8336 4231 8336 3646 8337 4231 8337 3643 8337 3643 8338 4231 8338 4233 8338 3643 8339 4233 8339 3657 8339 3657 8340 4233 8340 4235 8340 3657 8341 4235 8341 3659 8341 3659 8342 4235 8342 4237 8342 3659 8343 4237 8343 4239 8343 4229 8344 3646 8344 4227 8344 4227 8345 3646 8345 3649 8345 4227 8346 3649 8346 4225 8346 4225 8347 3649 8347 3651 8347 4225 8348 3651 8348 4223 8348 4223 8349 3651 8349 3653 8349 4223 8350 3653 8350 4222 8350 4222 8351 3653 8351 3641 8351 4222 8352 3641 8352 4220 8352 4220 8353 3641 8353 4218 8353 4218 8354 3641 8354 3627 8354 4218 8355 3627 8355 4216 8355 4216 8356 3627 8356 3635 8356 4216 8357 3635 8357 4213 8357 4213 8358 3635 8358 3638 8358 4213 8359 3638 8359 4211 8359 4211 8360 3638 8360 4717 8360 4211 8361 4717 8361 4716 8361 4292 8362 3766 8362 3765 8362 4208 8363 4210 8363 4716 8363 4716 8364 4717 8364 3707 8364 3707 8365 4717 8365 3639 8365 3707 8366 3639 8366 3637 8366 3766 8367 4292 8367 3769 8367 3769 8368 4292 8368 4294 8368 3769 8369 4294 8369 4198 8369 4198 8370 4294 8370 4295 8370 4198 8371 4295 8371 4196 8371 4208 8372 4716 8372 4206 8372 4206 8373 4716 8373 3707 8373 4206 8374 3707 8374 4204 8374 4204 8375 3707 8375 3711 8375 4204 8376 3711 8376 4202 8376 4202 8377 3711 8377 3713 8377 4202 8378 3713 8378 4200 8378 4200 8379 3713 8379 3715 8379 4200 8380 3715 8380 4198 8380 4198 8381 3715 8381 3710 8381 4198 8382 3710 8382 3769 8382 2849 8383 2848 8383 4272 8383 4293 8384 3776 8384 3775 8384 2851 8385 2849 8385 3775 8385 3775 8386 2849 8386 4272 8386 3775 8387 4272 8387 4293 8387 4293 8388 4272 8388 4271 8388 4718 8389 3526 8389 3528 8389 4719 8390 4720 8390 4721 8390 4721 8391 4720 8391 4722 8391 4721 8392 4722 8392 4718 8392 4718 8393 3528 8393 4721 8393 4721 8394 3528 8394 3532 8394 4721 8395 3532 8395 4723 8395 4723 8396 3532 8396 3536 8396 4723 8397 3536 8397 4724 8397 4724 8398 3536 8398 3535 8398 4724 8399 3535 8399 4725 8399 4256 8400 4719 8400 4265 8400 4265 8401 4719 8401 4721 8401 4265 8402 4721 8402 4266 8402 4266 8403 4721 8403 4723 8403 4266 8404 4723 8404 4267 8404 4267 8405 4723 8405 4724 8405 4267 8406 4724 8406 4262 8406 4262 8407 4724 8407 4725 8407 4262 8408 4725 8408 4264 8408 4715 8409 4264 8409 4726 8409 4726 8410 4264 8410 4725 8410 4726 8411 4725 8411 3540 8411 3540 8412 4725 8412 3535 8412 3677 8413 4715 8413 3791 8413 3791 8414 4715 8414 4726 8414 3791 8415 4726 8415 3538 8415 3538 8416 4726 8416 3540 8416 3211 8417 3210 8417 4727 8417 4727 8418 3210 8418 4728 8418 4727 8419 4728 8419 4729 8419 4729 8420 4728 8420 4730 8420 4729 8421 4730 8421 4731 8421 4731 8422 4730 8422 4732 8422 4731 8423 4732 8423 4733 8423 4733 8424 4732 8424 4734 8424 4733 8425 4734 8425 4735 8425 4735 8426 4734 8426 4736 8426 4735 8427 4736 8427 4737 8427 4737 8428 4736 8428 4738 8428 4737 8429 4738 8429 4739 8429 4739 8430 4738 8430 4740 8430 4739 8431 4740 8431 3516 8431 3516 8432 4740 8432 3541 8432 3827 8433 3831 8433 4741 8433 4738 8434 4736 8434 4742 8434 3840 8435 3833 8435 4743 8435 4734 8436 4732 8436 4744 8436 3837 8437 3839 8437 4745 8437 4730 8438 4728 8438 4746 8438 4746 8439 4728 8439 3210 8439 3210 8440 3242 8440 4746 8440 4746 8441 3242 8441 3243 8441 4746 8442 3243 8442 4747 8442 3197 8443 3835 8443 3228 8443 3228 8444 3835 8444 4748 8444 3228 8445 4748 8445 3230 8445 3230 8446 4748 8446 4747 8446 3230 8447 4747 8447 3233 8447 3233 8448 4747 8448 3243 8448 3835 8449 3837 8449 4748 8449 4748 8450 3837 8450 4745 8450 4748 8451 4745 8451 4747 8451 4747 8452 4745 8452 4749 8452 4747 8453 4749 8453 4746 8453 4746 8454 4749 8454 4744 8454 4746 8455 4744 8455 4730 8455 4730 8456 4744 8456 4732 8456 3839 8457 3840 8457 4745 8457 4745 8458 3840 8458 4743 8458 4745 8459 4743 8459 4749 8459 4749 8460 4743 8460 4750 8460 4749 8461 4750 8461 4744 8461 4744 8462 4750 8462 4742 8462 4744 8463 4742 8463 4734 8463 4734 8464 4742 8464 4736 8464 3833 8465 3827 8465 4743 8465 4743 8466 3827 8466 4741 8466 4743 8467 4741 8467 4750 8467 4750 8468 4741 8468 4751 8468 4750 8469 4751 8469 4742 8469 4742 8470 4751 8470 4752 8470 4742 8471 4752 8471 4738 8471 4738 8472 4752 8472 4740 8472 3831 8473 3522 8473 4741 8473 4741 8474 3522 8474 3520 8474 4741 8475 3520 8475 4751 8475 4751 8476 3520 8476 3518 8476 4751 8477 3518 8477 4752 8477 4752 8478 3518 8478 3517 8478 4752 8479 3517 8479 4740 8479 4740 8480 3517 8480 3541 8480 4753 8481 3821 8481 3822 8481 4753 8482 3822 8482 4754 8482 4754 8483 3822 8483 3832 8483 4754 8484 3832 8484 4755 8484 4755 8485 3832 8485 3834 8485 4755 8486 3834 8486 4756 8486 4756 8487 3834 8487 3838 8487 4756 8488 3838 8488 4757 8488 4757 8489 3838 8489 4758 8489 4758 8490 3838 8490 3836 8490 4758 8491 3836 8491 4759 8491 4759 8492 3836 8492 4760 8492 4760 8493 3836 8493 3200 8493 4760 8494 3200 8494 3199 8494 4662 8495 4761 8495 3198 8495 3198 8496 4761 8496 3199 8496 4757 8497 4762 8497 4763 8497 4754 8498 4764 8498 4765 8498 4766 8499 4767 8499 3821 8499 4766 8500 3821 8500 4768 8500 4768 8501 3821 8501 4765 8501 4765 8502 3821 8502 4753 8502 4765 8503 4753 8503 4754 8503 4764 8504 4754 8504 4769 8504 4769 8505 4754 8505 4755 8505 4769 8506 4755 8506 4763 8506 4763 8507 4755 8507 4756 8507 4763 8508 4756 8508 4757 8508 4762 8509 4757 8509 4770 8509 4770 8510 4757 8510 4758 8510 4770 8511 4758 8511 4771 8511 4758 8512 4759 8512 4771 8512 4771 8513 4759 8513 4760 8513 4771 8514 4760 8514 4772 8514 4772 8515 4760 8515 3199 8515 4772 8516 3199 8516 4761 8516 3779 8517 3818 8517 4773 8517 4773 8518 3818 8518 3820 8518 4773 8519 3820 8519 4774 8519 4774 8520 3820 8520 3821 8520 4774 8521 3821 8521 4767 8521 4761 8522 4662 8522 4672 8522 4761 8523 4672 8523 4772 8523 4772 8524 4672 8524 4775 8524 4772 8525 4775 8525 4771 8525 4769 8526 4763 8526 4776 8526 4776 8527 4763 8527 4762 8527 4776 8528 4762 8528 4775 8528 4775 8529 4762 8529 4770 8529 4775 8530 4770 8530 4771 8530 4769 8531 4776 8531 4764 8531 4764 8532 4776 8532 4768 8532 4764 8533 4768 8533 4765 8533 3779 8534 4773 8534 3777 8534 3777 8535 4773 8535 4774 8535 3777 8536 4774 8536 4777 8536 4777 8537 4774 8537 4767 8537 4767 8538 4766 8538 4777 8538 4777 8539 4766 8539 4768 8539 4777 8540 4768 8540 4778 8540 4778 8541 4768 8541 4776 8541 4778 8542 4776 8542 4779 8542 4779 8543 4776 8543 4775 8543 4779 8544 4775 8544 4673 8544 4673 8545 4775 8545 4672 8545 4779 8546 4673 8546 4674 8546 3804 8547 3777 8547 4780 8547 4780 8548 3777 8548 4777 8548 4780 8549 4777 8549 4781 8549 4781 8550 4777 8550 4778 8550 4781 8551 4778 8551 4782 8551 4782 8552 4778 8552 4779 8552 4779 8553 4674 8553 4782 8553 4782 8554 4674 8554 4678 8554 4782 8555 4678 8555 4676 8555 4676 8556 4783 8556 4782 8556 4782 8557 4783 8557 4784 8557 4782 8558 4784 8558 4781 8558 4781 8559 4784 8559 4785 8559 4781 8560 4785 8560 4780 8560 3805 8561 3804 8561 4786 8561 4786 8562 3804 8562 4780 8562 4786 8563 4780 8563 4787 8563 4787 8564 4780 8564 4785 8564 4686 8565 4693 8565 4788 8565 4789 8566 4784 8566 4683 8566 4683 8567 4784 8567 4783 8567 4683 8568 4783 8568 4684 8568 4684 8569 4783 8569 4676 8569 4790 8570 3806 8570 3805 8570 3805 8571 4786 8571 4790 8571 4790 8572 4786 8572 4787 8572 4790 8573 4787 8573 4789 8573 4789 8574 4787 8574 4785 8574 4789 8575 4785 8575 4784 8575 3807 8576 3806 8576 4791 8576 4791 8577 3806 8577 4790 8577 4791 8578 4790 8578 4788 8578 4788 8579 4790 8579 4789 8579 4788 8580 4789 8580 4686 8580 4686 8581 4789 8581 4683 8581 4792 8582 4696 8582 4695 8582 3800 8583 3808 8583 4793 8583 4793 8584 3808 8584 4794 8584 4793 8585 4794 8585 4795 8585 4795 8586 4794 8586 4792 8586 4795 8587 4792 8587 4796 8587 4796 8588 4792 8588 4695 8588 4796 8589 4695 8589 4697 8589 4693 8590 4696 8590 4788 8590 4788 8591 4696 8591 4792 8591 4788 8592 4792 8592 4791 8592 4791 8593 4792 8593 4794 8593 4791 8594 4794 8594 3807 8594 3807 8595 4794 8595 3808 8595 3162 8596 3161 8596 3785 8596 4797 8597 4798 8597 3162 8597 3145 8598 3144 8598 4799 8598 4799 8599 3144 8599 3166 8599 3166 8600 3165 8600 4799 8600 4799 8601 3165 8601 3164 8601 4799 8602 3164 8602 4798 8602 4798 8603 3164 8603 3163 8603 4798 8604 3163 8604 3162 8604 4709 8605 4712 8605 3145 8605 3149 8606 3148 8606 4713 8606 4713 8607 3148 8607 3147 8607 4713 8608 3147 8608 4712 8608 4712 8609 3147 8609 3146 8609 4712 8610 3146 8610 3145 8610 4710 8611 3150 8611 4711 8611 4711 8612 3150 8612 3149 8612 4711 8613 3149 8613 4714 8613 4714 8614 3149 8614 4713 8614 3153 8615 3154 8615 4710 8615 4710 8616 3154 8616 3151 8616 4710 8617 3151 8617 3150 8617 3145 8618 4799 8618 4709 8618 4709 8619 4799 8619 4798 8619 4709 8620 4798 8620 4708 8620 4708 8621 4798 8621 4797 8621 4708 8622 4797 8622 4706 8622 3162 8623 3785 8623 4797 8623 4797 8624 3785 8624 3783 8624 4797 8625 3783 8625 4800 8625 4706 8626 4797 8626 4702 8626 4702 8627 4797 8627 4800 8627 4702 8628 4800 8628 4703 8628 3783 8629 3782 8629 4800 8629 4800 8630 3782 8630 3802 8630 4800 8631 3802 8631 4801 8631 4801 8632 3802 8632 3801 8632 4801 8633 3801 8633 4802 8633 4802 8634 3801 8634 3800 8634 3800 8635 4793 8635 4802 8635 4802 8636 4793 8636 4795 8636 4802 8637 4795 8637 4796 8637 4703 8638 4800 8638 4704 8638 4704 8639 4800 8639 4801 8639 4704 8640 4801 8640 4705 8640 4705 8641 4801 8641 4802 8641 4705 8642 4802 8642 4701 8642 4701 8643 4802 8643 4796 8643 4701 8644 4796 8644 4697 8644 4729 8645 4731 8645 4803 8645 3211 8646 4804 8646 4805 8646 4806 8647 4804 8647 3211 8647 4727 8648 4806 8648 3211 8648 3554 8649 3552 8649 4807 8649 4808 8650 3560 8650 4809 8650 4809 8651 3560 8651 3555 8651 4809 8652 3555 8652 3554 8652 3559 8653 4810 8653 3557 8653 3557 8654 4810 8654 4811 8654 3557 8655 4811 8655 3566 8655 3566 8656 4811 8656 4812 8656 3566 8657 4812 8657 3567 8657 4739 8658 3516 8658 3564 8658 3552 8659 3550 8659 4807 8659 4807 8660 3550 8660 4813 8660 4807 8661 4813 8661 4814 8661 4814 8662 4813 8662 4815 8662 4727 8663 4729 8663 4806 8663 4806 8664 4729 8664 4803 8664 4806 8665 4803 8665 4804 8665 4804 8666 4803 8666 4808 8666 4804 8667 4808 8667 4805 8667 4805 8668 4808 8668 4809 8668 3554 8669 4807 8669 4809 8669 4809 8670 4807 8670 4814 8670 4809 8671 4814 8671 4805 8671 4805 8672 4814 8672 3211 8672 4731 8673 4733 8673 4803 8673 4803 8674 4733 8674 4811 8674 4803 8675 4811 8675 4808 8675 4808 8676 4811 8676 4810 8676 4808 8677 4810 8677 3560 8677 3560 8678 4810 8678 3559 8678 4815 8679 4816 8679 4814 8679 4814 8680 4816 8680 3211 8680 3564 8681 3567 8681 4739 8681 4739 8682 3567 8682 4812 8682 4739 8683 4812 8683 4737 8683 4737 8684 4812 8684 4811 8684 4737 8685 4811 8685 4735 8685 4735 8686 4811 8686 4733 8686 4568 8687 3212 8687 3211 8687 3211 8688 4816 8688 4568 8688 4568 8689 4816 8689 4815 8689 4568 8690 4815 8690 3580 8690 3580 8691 4815 8691 4813 8691 3580 8692 4813 8692 3550 8692 4817 8693 4818 8693 4819 8693 4819 8694 4818 8694 4820 8694 4819 8695 4820 8695 4821 8695 4821 8696 4820 8696 4822 8696 4821 8697 4822 8697 4823 8697 4823 8698 4822 8698 4824 8698 4824 8699 4822 8699 4825 8699 4824 8700 4825 8700 4826 8700 4826 8701 4825 8701 4827 8701 4826 8702 4827 8702 4828 8702 4828 8703 4827 8703 4269 8703 4828 8704 4269 8704 4268 8704 4829 8705 4830 8705 4831 8705 4832 8706 4820 8706 4833 8706 4834 8707 4835 8707 4836 8707 4837 8708 4838 8708 4839 8708 4839 8709 4840 8709 4837 8709 4837 8710 4840 8710 4841 8710 4837 8711 4841 8711 4842 8711 4836 8712 4835 8712 4837 8712 4837 8713 4835 8713 4843 8713 4837 8714 4843 8714 4838 8714 4834 8715 4836 8715 4844 8715 4844 8716 4836 8716 4845 8716 4844 8717 4845 8717 4846 8717 4846 8718 4845 8718 4847 8718 4846 8719 4847 8719 4848 8719 4848 8720 4847 8720 4849 8720 4849 8721 4847 8721 4833 8721 4849 8722 4833 8722 4850 8722 4850 8723 4833 8723 4851 8723 4851 8724 4833 8724 4820 8724 4851 8725 4820 8725 4818 8725 4852 8726 4825 8726 4853 8726 4853 8727 4825 8727 4832 8727 4269 8728 4852 8728 4299 8728 4299 8729 4852 8729 4853 8729 4299 8730 4853 8730 4300 8730 4300 8731 4853 8731 4854 8731 4300 8732 4854 8732 4301 8732 4301 8733 4854 8733 4855 8733 4301 8734 4855 8734 4303 8734 4303 8735 4855 8735 4302 8735 4302 8736 4855 8736 4856 8736 4302 8737 4856 8737 4296 8737 4832 8738 4833 8738 4853 8738 4853 8739 4833 8739 4847 8739 4853 8740 4847 8740 4854 8740 4854 8741 4847 8741 4845 8741 4854 8742 4845 8742 4855 8742 4855 8743 4845 8743 4836 8743 4855 8744 4836 8744 4856 8744 4856 8745 4836 8745 4837 8745 4856 8746 4837 8746 4831 8746 4831 8747 4837 8747 4842 8747 4831 8748 4842 8748 4829 8748 4296 8749 4856 8749 4297 8749 4297 8750 4856 8750 4831 8750 4297 8751 4831 8751 4298 8751 4298 8752 4831 8752 4830 8752 4298 8753 4830 8753 4197 8753 4228 8754 4226 8754 4857 8754 4858 8755 4859 8755 4860 8755 4861 8756 4862 8756 4863 8756 4863 8757 4862 8757 4864 8757 4865 8758 4866 8758 4858 8758 4858 8759 4866 8759 4867 8759 4858 8760 4867 8760 4859 8760 4868 8761 4869 8761 4870 8761 4870 8762 4869 8762 4871 8762 4870 8763 4871 8763 4865 8763 4865 8764 4871 8764 4872 8764 4865 8765 4872 8765 4866 8765 4868 8766 4870 8766 4873 8766 4873 8767 4870 8767 4874 8767 4873 8768 4874 8768 4875 8768 4875 8769 4874 8769 4876 8769 4875 8770 4876 8770 4877 8770 4877 8771 4876 8771 4878 8771 4878 8772 4876 8772 4879 8772 4878 8773 4879 8773 4880 8773 4880 8774 4879 8774 4881 8774 4881 8775 4879 8775 4882 8775 4881 8776 4882 8776 4883 8776 4884 8777 4885 8777 4886 8777 4886 8778 4885 8778 4887 8778 4886 8779 4887 8779 4882 8779 4882 8780 4887 8780 4888 8780 4882 8781 4888 8781 4883 8781 4889 8782 4890 8782 4884 8782 4884 8783 4890 8783 4891 8783 4884 8784 4891 8784 4885 8784 4892 8785 4893 8785 4894 8785 4894 8786 4893 8786 4895 8786 4894 8787 4895 8787 4889 8787 4889 8788 4895 8788 4896 8788 4889 8789 4896 8789 4890 8789 4892 8790 4894 8790 4897 8790 4897 8791 4894 8791 4898 8791 4897 8792 4898 8792 4899 8792 4899 8793 4898 8793 4900 8793 4899 8794 4900 8794 4901 8794 4901 8795 4900 8795 4902 8795 4902 8796 4900 8796 4903 8796 4902 8797 4903 8797 4904 8797 4904 8798 4903 8798 4905 8798 4905 8799 4903 8799 4906 8799 4905 8800 4906 8800 4907 8800 4907 8801 4906 8801 4908 8801 4908 8802 4906 8802 4909 8802 4908 8803 4909 8803 4910 8803 4910 8804 4909 8804 4841 8804 4910 8805 4841 8805 4840 8805 4830 8806 4829 8806 4911 8806 4911 8807 4829 8807 4842 8807 4197 8808 4830 8808 4199 8808 4199 8809 4830 8809 4911 8809 4199 8810 4911 8810 4201 8810 4201 8811 4911 8811 4912 8811 4201 8812 4912 8812 4203 8812 4203 8813 4912 8813 4205 8813 4205 8814 4912 8814 4913 8814 4205 8815 4913 8815 4207 8815 4207 8816 4913 8816 4209 8816 4209 8817 4913 8817 4914 8817 4209 8818 4914 8818 4212 8818 4212 8819 4914 8819 4214 8819 4214 8820 4914 8820 4915 8820 4214 8821 4915 8821 4215 8821 4215 8822 4915 8822 4916 8822 4215 8823 4916 8823 4217 8823 4857 8824 4226 8824 4917 8824 4226 8825 4224 8825 4917 8825 4917 8826 4224 8826 4221 8826 4917 8827 4221 8827 4916 8827 4916 8828 4221 8828 4219 8828 4916 8829 4219 8829 4217 8829 4228 8830 4857 8830 4230 8830 4230 8831 4857 8831 4918 8831 4230 8832 4918 8832 4232 8832 4232 8833 4918 8833 4919 8833 4232 8834 4919 8834 4234 8834 4234 8835 4919 8835 4236 8835 4236 8836 4919 8836 4920 8836 4236 8837 4920 8837 4238 8837 4238 8838 4920 8838 4240 8838 4240 8839 4920 8839 4921 8839 4240 8840 4921 8840 4242 8840 4242 8841 4921 8841 4244 8841 4244 8842 4921 8842 4922 8842 4244 8843 4922 8843 4246 8843 4246 8844 4922 8844 4923 8844 4246 8845 4923 8845 4248 8845 4924 8846 4251 8846 4923 8846 4923 8847 4251 8847 4249 8847 4923 8848 4249 8848 4248 8848 4925 8849 4858 8849 4861 8849 4861 8850 4858 8850 4860 8850 4861 8851 4860 8851 4862 8851 4925 8852 4926 8852 4858 8852 4858 8853 4926 8853 4924 8853 4858 8854 4924 8854 4865 8854 4865 8855 4924 8855 4923 8855 4865 8856 4923 8856 4870 8856 4870 8857 4923 8857 4922 8857 4870 8858 4922 8858 4874 8858 4874 8859 4922 8859 4921 8859 4874 8860 4921 8860 4876 8860 4876 8861 4921 8861 4920 8861 4876 8862 4920 8862 4879 8862 4879 8863 4920 8863 4919 8863 4879 8864 4919 8864 4882 8864 4882 8865 4919 8865 4918 8865 4882 8866 4918 8866 4886 8866 4886 8867 4918 8867 4857 8867 4886 8868 4857 8868 4884 8868 4884 8869 4857 8869 4917 8869 4884 8870 4917 8870 4889 8870 4889 8871 4917 8871 4916 8871 4889 8872 4916 8872 4894 8872 4894 8873 4916 8873 4915 8873 4894 8874 4915 8874 4898 8874 4898 8875 4915 8875 4914 8875 4898 8876 4914 8876 4900 8876 4900 8877 4914 8877 4913 8877 4900 8878 4913 8878 4903 8878 4903 8879 4913 8879 4912 8879 4903 8880 4912 8880 4906 8880 4906 8881 4912 8881 4911 8881 4906 8882 4911 8882 4909 8882 4909 8883 4911 8883 4842 8883 4909 8884 4842 8884 4841 8884 4925 8885 4927 8885 4926 8885 4926 8886 4927 8886 4928 8886 4926 8887 4928 8887 4256 8887 4256 8888 4258 8888 4926 8888 4926 8889 4258 8889 4255 8889 4926 8890 4255 8890 4924 8890 4924 8891 4255 8891 4253 8891 4924 8892 4253 8892 4251 8892 4861 8893 4863 8893 4929 8893 3576 8894 3578 8894 4930 8894 3435 8895 4929 8895 4931 8895 4931 8896 4929 8896 4863 8896 4931 8897 4863 8897 4864 8897 3572 8898 3574 8898 4932 8898 4932 8899 3574 8899 3576 8899 4933 8900 3570 8900 3572 8900 4719 8901 4934 8901 4720 8901 4720 8902 4934 8902 4935 8902 4720 8903 4935 8903 4722 8903 4722 8904 4935 8904 4930 8904 4722 8905 4930 8905 4718 8905 4718 8906 4930 8906 3578 8906 4718 8907 3578 8907 3526 8907 3435 8908 3434 8908 4929 8908 4929 8909 3434 8909 3444 8909 4929 8910 3444 8910 4936 8910 4936 8911 3444 8911 3443 8911 4936 8912 3443 8912 4933 8912 4933 8913 3443 8913 3442 8913 4933 8914 3442 8914 3570 8914 4719 8915 4256 8915 4934 8915 4934 8916 4256 8916 4928 8916 4934 8917 4928 8917 4927 8917 3576 8918 4930 8918 4932 8918 4932 8919 4930 8919 4935 8919 4932 8920 4935 8920 4937 8920 4937 8921 4935 8921 4934 8921 4937 8922 4934 8922 4938 8922 4938 8923 4934 8923 4927 8923 4938 8924 4927 8924 4925 8924 3572 8925 4932 8925 4933 8925 4933 8926 4932 8926 4937 8926 4933 8927 4937 8927 4936 8927 4936 8928 4937 8928 4938 8928 4936 8929 4938 8929 4929 8929 4929 8930 4938 8930 4925 8930 4929 8931 4925 8931 4861 8931 4939 8932 4940 8932 4941 8932 3031 8933 3028 8933 4942 8933 4943 8934 4944 8934 4945 8934 4945 8935 4944 8935 4946 8935 4946 8936 4944 8936 4947 8936 4946 8937 4947 8937 4948 8937 4949 8938 4950 8938 4951 8938 4951 8939 4950 8939 4941 8939 4951 8940 4941 8940 4952 8940 4949 8941 4953 8941 4950 8941 4950 8942 4953 8942 4954 8942 4950 8943 4954 8943 4944 8943 4944 8944 4954 8944 4955 8944 4944 8945 4955 8945 4947 8945 4940 8946 4956 8946 4941 8946 4941 8947 4956 8947 4957 8947 4941 8948 4957 8948 4952 8948 4958 8949 4959 8949 4960 8949 4960 8950 4959 8950 4961 8950 3035 8951 4962 8951 4963 8951 4963 8952 4962 8952 4959 8952 4963 8953 4959 8953 4964 8953 4964 8954 4959 8954 4958 8954 4965 8955 4966 8955 4967 8955 4967 8956 4968 8956 4969 8956 4969 8957 4968 8957 4970 8957 4969 8958 4970 8958 4959 8958 4959 8959 4970 8959 4971 8959 4959 8960 4971 8960 4961 8960 4972 8961 4973 8961 4965 8961 4965 8962 4973 8962 4974 8962 4965 8963 4974 8963 4966 8963 4180 8964 4179 8964 4975 8964 4975 8965 4179 8965 4178 8965 4975 8966 4178 8966 4965 8966 4965 8967 4178 8967 4177 8967 4965 8968 4177 8968 4972 8968 4972 8969 4177 8969 4176 8969 4972 8970 4176 8970 4181 8970 4168 8971 4171 8971 4976 8971 4976 8972 4171 8972 4170 8972 4170 8973 4169 8973 4976 8973 4976 8974 4169 8974 4172 8974 4976 8975 4172 8975 4975 8975 4975 8976 4172 8976 4174 8976 4975 8977 4174 8977 4180 8977 3046 8978 3051 8978 4115 8978 4112 8979 4168 8979 4113 8979 4113 8980 4168 8980 4976 8980 4113 8981 4976 8981 4115 8981 4115 8982 4976 8982 3047 8982 4115 8983 3047 8983 3046 8983 4137 8984 4131 8984 3071 8984 3071 8985 4131 8985 4130 8985 3071 8986 4130 8986 3070 8986 4977 8987 4163 8987 4978 8987 4978 8988 4163 8988 4162 8988 4978 8989 4162 8989 4137 8989 4159 8990 4158 8990 4977 8990 4977 8991 4158 8991 4164 8991 4977 8992 4164 8992 4163 8992 4979 8993 4980 8993 4981 8993 4981 8994 4980 8994 4982 8994 4159 8995 4977 8995 4160 8995 4160 8996 4977 8996 4981 8996 4160 8997 4981 8997 4161 8997 4161 8998 4981 8998 4982 8998 4161 8999 4982 8999 4983 8999 4153 9000 4151 9000 4983 9000 4983 9001 4151 9001 4150 9001 4983 9002 4150 9002 4161 9002 3019 9003 4984 9003 3020 9003 3020 9004 4984 9004 4985 9004 3020 9005 4985 9005 3023 9005 4984 9006 4986 9006 4985 9006 4985 9007 4986 9007 4987 9007 4985 9008 4987 9008 4988 9008 4988 9009 4989 9009 4985 9009 4985 9010 4989 9010 4990 9010 4985 9011 4990 9011 4991 9011 4991 9012 4990 9012 4992 9012 4991 9013 4992 9013 4993 9013 3030 9014 4994 9014 3029 9014 3029 9015 4994 9015 4995 9015 4996 9016 4997 9016 4998 9016 4996 9017 4998 9017 4994 9017 4994 9018 4998 9018 4999 9018 4994 9019 4999 9019 4995 9019 5000 9020 5001 9020 4996 9020 4996 9021 5001 9021 5002 9021 4996 9022 5002 9022 4997 9022 5003 9023 5004 9023 5005 9023 5005 9024 5004 9024 5006 9024 5005 9025 5006 9025 5007 9025 5007 9026 5008 9026 5005 9026 5005 9027 5008 9027 5009 9027 5005 9028 5009 9028 5010 9028 5010 9029 5011 9029 5005 9029 5005 9030 5011 9030 5012 9030 5005 9031 5012 9031 5000 9031 5000 9032 5012 9032 5013 9032 5000 9033 5013 9033 5014 9033 5014 9034 5015 9034 5000 9034 5000 9035 5015 9035 5016 9035 5000 9036 5016 9036 5001 9036 5017 9037 5018 9037 5003 9037 5003 9038 5018 9038 5019 9038 5003 9039 5019 9039 5004 9039 5020 9040 5021 9040 5017 9040 5017 9041 5021 9041 5022 9041 5017 9042 5022 9042 5018 9042 5023 9043 5024 9043 5025 9043 5025 9044 5024 9044 5026 9044 5025 9045 5026 9045 5027 9045 5028 9046 3022 9046 3023 9046 3027 9047 3024 9047 5029 9047 5029 9048 3024 9048 3021 9048 3025 9049 3026 9049 5030 9049 5030 9050 3026 9050 3027 9050 3031 9051 4942 9051 3030 9051 5031 9052 5032 9052 4939 9052 4962 9053 5033 9053 5034 9053 5034 9054 5033 9054 5035 9054 5034 9055 5035 9055 5036 9055 3023 9056 4985 9056 5028 9056 5028 9057 4985 9057 4991 9057 5028 9058 4991 9058 5037 9058 5037 9059 4991 9059 5038 9059 5037 9060 5038 9060 5039 9060 5039 9061 5038 9061 5040 9061 5039 9062 5040 9062 5041 9062 3027 9063 5029 9063 5030 9063 5030 9064 5029 9064 5042 9064 5030 9065 5042 9065 5043 9065 5043 9066 5042 9066 5044 9066 5043 9067 5044 9067 5045 9067 5045 9068 5044 9068 5046 9068 5045 9069 5046 9069 5047 9069 3030 9070 4942 9070 4994 9070 4994 9071 4942 9071 5048 9071 4994 9072 5048 9072 4996 9072 4996 9073 5048 9073 5049 9073 4996 9074 5049 9074 5000 9074 5000 9075 5049 9075 5050 9075 5000 9076 5050 9076 5005 9076 4939 9077 4941 9077 5031 9077 5031 9078 4941 9078 4950 9078 5031 9079 4950 9079 5051 9079 5051 9080 4950 9080 4944 9080 5051 9081 4944 9081 5052 9081 5052 9082 4944 9082 4943 9082 5052 9083 4943 9083 5053 9083 4962 9084 5034 9084 4959 9084 4959 9085 5034 9085 5054 9085 4959 9086 5054 9086 4969 9086 4969 9087 5054 9087 5055 9087 4969 9088 5055 9088 5056 9088 5056 9089 5055 9089 5057 9089 5056 9090 5057 9090 5058 9090 4137 9091 3071 9091 4978 9091 4978 9092 3071 9092 3072 9092 4978 9093 3072 9093 3069 9093 3069 9094 5040 9094 4978 9094 4978 9095 5040 9095 5038 9095 4978 9096 5038 9096 4977 9096 4977 9097 5038 9097 4991 9097 4977 9098 4991 9098 4981 9098 4981 9099 4991 9099 4993 9099 4981 9100 4993 9100 4979 9100 3069 9101 3078 9101 5040 9101 5040 9102 3078 9102 3077 9102 5040 9103 3077 9103 5041 9103 5041 9104 3077 9104 3076 9104 5041 9105 3076 9105 3075 9105 3075 9106 5046 9106 5041 9106 5041 9107 5046 9107 5044 9107 5041 9108 5044 9108 5039 9108 5039 9109 5044 9109 5042 9109 5039 9110 5042 9110 5037 9110 5037 9111 5042 9111 5029 9111 5037 9112 5029 9112 5028 9112 5028 9113 5029 9113 3021 9113 5028 9114 3021 9114 3022 9114 3075 9115 3083 9115 5046 9115 5046 9116 3083 9116 3082 9116 5046 9117 3082 9117 5047 9117 5047 9118 3082 9118 3080 9118 5047 9119 3080 9119 3086 9119 3086 9120 5050 9120 5047 9120 5047 9121 5050 9121 5049 9121 5047 9122 5049 9122 5045 9122 5045 9123 5049 9123 5048 9123 5045 9124 5048 9124 5043 9124 5043 9125 5048 9125 4942 9125 5043 9126 4942 9126 5030 9126 5030 9127 4942 9127 3028 9127 5030 9128 3028 9128 3025 9128 3091 9129 5017 9129 3092 9129 3092 9130 5017 9130 5003 9130 3092 9131 5003 9131 3088 9131 3088 9132 5003 9132 5005 9132 3088 9133 5005 9133 3089 9133 3089 9134 5005 9134 5050 9134 3089 9135 5050 9135 3085 9135 3085 9136 5050 9136 3086 9136 3091 9137 3095 9137 5017 9137 5017 9138 3095 9138 5024 9138 5017 9139 5024 9139 5020 9139 5020 9140 5024 9140 5023 9140 3097 9141 5026 9141 3098 9141 3098 9142 5026 9142 5024 9142 3098 9143 5024 9143 3094 9143 3094 9144 5024 9144 3095 9144 3097 9145 3101 9145 5026 9145 5026 9146 3101 9146 4943 9146 5026 9147 4943 9147 5027 9147 5027 9148 4943 9148 4945 9148 3101 9149 3100 9149 4943 9149 4943 9150 3100 9150 3104 9150 4943 9151 3104 9151 5053 9151 5053 9152 3104 9152 3103 9152 5053 9153 3103 9153 3107 9153 3107 9154 5057 9154 5053 9154 5053 9155 5057 9155 5055 9155 5053 9156 5055 9156 5052 9156 5052 9157 5055 9157 5054 9157 5052 9158 5054 9158 5051 9158 5051 9159 5054 9159 5034 9159 5051 9160 5034 9160 5031 9160 5031 9161 5034 9161 5036 9161 5031 9162 5036 9162 5032 9162 3107 9163 3106 9163 5057 9163 5057 9164 3106 9164 3110 9164 5057 9165 3110 9165 5058 9165 5058 9166 3110 9166 3109 9166 5058 9167 3109 9167 3108 9167 4967 9168 4969 9168 4965 9168 4965 9169 4969 9169 5056 9169 4965 9170 5056 9170 4975 9170 4975 9171 5056 9171 5058 9171 4975 9172 5058 9172 4976 9172 4976 9173 5058 9173 3108 9173 4976 9174 3108 9174 3047 9174 3928 9175 3929 9175 3041 9175 3041 9176 3929 9176 3934 9176 4008 9177 3989 9177 4497 9177 4494 9178 4030 9178 4036 9178 4030 9179 4494 9179 4031 9179 3934 9180 3933 9180 3041 9180 3041 9181 3933 9181 3931 9181 3041 9182 3931 9182 4021 9182 4021 9183 4025 9183 3041 9183 3041 9184 4025 9184 4024 9184 3041 9185 4024 9185 4028 9185 3134 9186 3152 9186 4498 9186 4498 9187 3152 9187 3054 9187 4498 9188 3054 9188 3055 9188 4496 9189 3883 9189 3891 9189 4032 9190 4495 9190 4033 9190 4033 9191 4495 9191 4494 9191 4033 9192 4494 9192 4035 9192 4035 9193 4494 9193 4036 9193 4031 9194 4494 9194 4027 9194 4027 9195 4494 9195 4493 9195 4027 9196 4493 9196 4028 9196 4028 9197 4493 9197 4492 9197 4028 9198 4492 9198 3041 9198 3041 9199 4492 9199 4491 9199 3041 9200 4491 9200 4502 9200 3989 9201 3186 9201 4497 9201 4497 9202 3186 9202 3185 9202 4497 9203 3185 9203 4498 9203 4498 9204 3185 9204 3135 9204 4498 9205 3135 9205 3134 9205 4496 9206 4002 9206 4497 9206 4497 9207 4002 9207 4003 9207 4003 9208 4005 9208 4497 9208 4497 9209 4005 9209 4007 9209 4497 9210 4007 9210 4008 9210 4032 9211 4038 9211 4495 9211 4495 9212 4038 9212 4039 9212 4495 9213 4039 9213 4496 9213 4496 9214 4039 9214 3884 9214 4496 9215 3884 9215 3883 9215 3124 9216 3123 9216 4501 9216 4501 9217 3123 9217 3122 9217 4501 9218 3122 9218 4502 9218 4502 9219 3122 9219 3042 9219 4502 9220 3042 9220 3041 9220 3055 9221 3133 9221 4498 9221 4498 9222 3133 9222 3132 9222 4498 9223 3132 9223 4499 9223 3891 9224 3889 9224 4496 9224 4496 9225 3889 9225 3887 9225 4496 9226 3887 9226 4002 9226 4002 9227 3887 9227 3886 9227 3132 9228 3131 9228 4499 9228 4499 9229 3131 9229 3130 9229 4499 9230 3130 9230 4500 9230 4500 9231 3130 9231 3129 9231 4500 9232 3129 9232 3128 9232 4049 9233 4082 9233 3926 9233 3926 9234 4082 9234 4081 9234 3926 9235 4081 9235 3969 9235 3853 9236 3856 9236 4000 9236 3128 9237 3127 9237 4500 9237 4500 9238 3127 9238 3126 9238 4500 9239 3126 9239 4501 9239 4501 9240 3126 9240 3125 9240 4501 9241 3125 9241 3124 9241 4077 9242 4079 9242 3926 9242 3926 9243 4079 9243 4048 9243 3926 9244 4048 9244 4049 9244 3928 9245 3041 9245 3927 9245 3927 9246 3041 9246 5059 9246 3927 9247 5059 9247 3922 9247 3886 9248 3892 9248 4002 9248 4002 9249 3892 9249 3853 9249 4002 9250 3853 9250 4001 9250 4001 9251 3853 9251 4000 9251 4077 9252 3926 9252 4078 9252 4078 9253 3926 9253 3925 9253 4078 9254 3925 9254 4072 9254 4072 9255 3925 9255 3923 9255 4072 9256 3923 9256 4070 9256 4070 9257 3923 9257 3922 9257 4070 9258 3922 9258 4089 9258 4089 9259 3922 9259 5059 9259 4089 9260 5059 9260 4088 9260 4088 9261 5059 9261 5060 9261 4088 9262 5060 9262 4109 9262 4109 9263 5060 9263 5061 9263 4109 9264 5061 9264 4108 9264 5062 9265 3034 9265 3033 9265 5063 9266 4956 9266 4940 9266 5063 9267 4940 9267 5064 9267 5065 9268 5063 9268 5066 9268 5066 9269 5063 9269 5064 9269 5066 9270 5064 9270 5067 9270 5067 9271 5064 9271 5068 9271 5067 9272 5068 9272 5069 9272 5036 9273 5068 9273 5032 9273 5032 9274 5068 9274 5064 9274 5032 9275 5064 9275 4939 9275 4939 9276 5064 9276 4940 9276 5036 9277 5035 9277 5068 9277 5068 9278 5035 9278 5062 9278 5068 9279 5062 9279 5069 9279 5069 9280 5062 9280 3033 9280 3035 9281 3034 9281 4962 9281 4962 9282 3034 9282 5062 9282 4962 9283 5062 9283 5033 9283 5033 9284 5062 9284 5035 9284 3781 9285 3780 9285 5070 9285 5070 9286 3780 9286 5071 9286 3825 9287 3824 9287 5072 9287 5072 9288 3824 9288 3823 9288 5072 9289 3823 9289 5070 9289 5070 9290 3823 9290 3819 9290 5070 9291 3819 9291 3781 9291 3825 9292 5072 9292 3826 9292 3826 9293 5072 9293 5073 9293 3826 9294 5073 9294 3828 9294 3521 9295 3523 9295 5073 9295 3523 9296 3829 9296 5073 9296 5073 9297 3829 9297 3830 9297 5073 9298 3830 9298 3828 9298 5073 9299 5074 9299 3521 9299 3521 9300 5074 9300 5075 9300 3521 9301 5075 9301 3519 9301 3519 9302 5075 9302 5076 9302 3519 9303 5076 9303 3542 9303 3542 9304 5076 9304 5077 9304 3542 9305 5077 9305 3539 9305 3539 9306 5077 9306 3537 9306 3537 9307 5077 9307 5078 9307 3537 9308 5078 9308 3811 9308 3811 9309 5078 9309 3809 9309 3809 9310 5078 9310 5079 9310 3809 9311 5079 9311 3810 9311 3813 9312 3812 9312 5080 9312 5080 9313 3812 9313 3815 9313 5080 9314 3815 9314 5079 9314 5079 9315 3815 9315 3814 9315 5079 9316 3814 9316 3810 9316 3788 9317 3787 9317 5081 9317 3787 9318 3792 9318 5081 9318 5081 9319 3792 9319 3817 9319 5081 9320 3817 9320 5080 9320 5080 9321 3817 9321 3816 9321 5080 9322 3816 9322 3813 9322 3786 9323 5081 9323 3793 9323 3793 9324 5081 9324 5082 9324 3786 9325 3790 9325 5081 9325 5081 9326 3790 9326 3789 9326 5081 9327 3789 9327 3788 9327 3796 9328 3795 9328 5082 9328 5082 9329 3795 9329 3794 9329 5082 9330 3794 9330 3793 9330 3780 9331 3778 9331 5071 9331 5071 9332 3778 9332 3803 9332 5071 9333 3803 9333 5083 9333 5083 9334 3803 9334 3784 9334 3784 9335 3799 9335 5083 9335 5083 9336 3799 9336 3798 9336 5083 9337 3798 9337 5082 9337 5082 9338 3798 9338 3797 9338 5082 9339 3797 9339 3796 9339 5084 9340 5071 9340 5085 9340 5085 9341 5071 9341 5083 9341 5085 9342 5083 9342 5086 9342 5086 9343 5083 9343 5082 9343 5086 9344 5082 9344 5087 9344 5087 9345 5082 9345 5081 9345 5087 9346 5081 9346 5088 9346 5088 9347 5081 9347 5080 9347 5088 9348 5080 9348 5089 9348 5089 9349 5080 9349 5079 9349 5089 9350 5079 9350 5090 9350 5079 9351 5078 9351 5090 9351 5090 9352 5078 9352 5077 9352 5090 9353 5077 9353 5091 9353 5091 9354 5077 9354 5076 9354 5091 9355 5076 9355 5092 9355 5092 9356 5076 9356 5075 9356 5092 9357 5075 9357 5093 9357 5093 9358 5075 9358 5074 9358 5093 9359 5074 9359 5094 9359 5094 9360 5074 9360 5073 9360 5094 9361 5073 9361 5095 9361 5095 9362 5073 9362 5072 9362 5095 9363 5072 9363 5084 9363 5084 9364 5072 9364 5070 9364 5084 9365 5070 9365 5071 9365 4632 9366 3771 9366 3709 9366 3689 9367 3688 9367 4624 9367 4624 9368 3688 9368 3695 9368 4624 9369 3695 9369 3696 9369 4622 9370 3700 9370 3698 9370 3698 9371 3685 9371 4622 9371 4622 9372 3685 9372 3692 9372 4622 9373 3692 9373 4624 9373 4624 9374 3692 9374 3691 9374 4624 9375 3691 9375 3689 9375 3619 9376 3680 9376 4620 9376 4620 9377 3680 9377 3703 9377 4620 9378 3703 9378 4622 9378 4622 9379 3703 9379 3702 9379 4622 9380 3702 9380 3700 9380 4618 9381 3622 9381 3612 9381 3612 9382 3611 9382 4618 9382 4618 9383 3611 9383 3614 9383 4618 9384 3614 9384 4620 9384 4620 9385 3614 9385 3621 9385 4620 9386 3621 9386 3619 9386 3625 9387 3624 9387 4618 9387 4618 9388 3624 9388 3623 9388 4618 9389 3623 9389 3622 9389 3630 9390 4616 9390 3631 9390 3631 9391 4616 9391 4615 9391 3630 9392 3629 9392 4616 9392 4616 9393 3629 9393 3628 9393 4616 9394 3628 9394 4618 9394 4618 9395 3628 9395 3626 9395 4618 9396 3626 9396 3625 9396 3636 9397 3634 9397 4615 9397 3634 9398 3633 9398 4615 9398 4615 9399 3633 9399 3632 9399 4615 9400 3632 9400 3631 9400 3714 9401 3712 9401 4634 9401 3709 9402 3708 9402 4632 9402 4632 9403 3708 9403 3716 9403 4632 9404 3716 9404 4634 9404 4634 9405 3716 9405 3717 9405 4634 9406 3717 9406 3714 9406 3712 9407 3706 9407 4634 9407 4634 9408 3706 9408 3705 9408 4634 9409 3705 9409 4615 9409 4615 9410 3705 9410 3704 9410 4615 9411 3704 9411 3636 9411 5096 9412 3586 9412 5097 9412 5097 9413 3586 9413 3585 9413 5097 9414 3585 9414 4575 9414 4591 9415 3594 9415 5098 9415 5098 9416 3594 9416 3593 9416 5099 9417 5100 9417 5101 9417 5101 9418 5100 9418 5098 9418 5101 9419 5098 9419 5102 9419 5102 9420 5098 9420 3593 9420 5103 9421 5104 9421 5105 9421 5105 9422 5104 9422 5106 9422 5106 9423 5104 9423 5107 9423 5106 9424 5107 9424 5108 9424 5109 9425 4557 9425 5110 9425 5110 9426 4557 9426 4514 9426 5110 9427 4514 9427 5111 9427 5111 9428 4514 9428 5112 9428 5111 9429 5112 9429 5113 9429 5113 9430 5112 9430 5114 9430 5113 9431 5114 9431 5115 9431 5115 9432 5114 9432 5116 9432 5108 9433 5107 9433 5114 9433 5114 9434 5107 9434 5117 9434 5114 9435 5117 9435 5116 9435 5118 9436 3420 9436 3419 9436 5118 9437 3419 9437 5119 9437 5103 9438 5105 9438 5120 9438 5120 9439 5105 9439 5121 9439 5120 9440 5121 9440 5122 9440 5122 9441 5121 9441 5123 9441 5122 9442 5123 9442 5124 9442 5124 9443 5123 9443 5125 9443 5124 9444 5125 9444 3419 9444 3419 9445 5125 9445 5126 9445 3419 9446 5126 9446 5119 9446 5112 9447 4514 9447 4516 9447 5127 9448 5114 9448 5112 9448 5121 9449 5105 9449 5127 9449 5105 9450 5106 9450 5127 9450 5127 9451 5106 9451 5108 9451 5127 9452 5108 9452 5114 9452 5126 9453 5125 9453 5128 9453 5128 9454 5125 9454 5123 9454 3422 9455 3420 9455 5118 9455 5112 9456 4516 9456 5127 9456 5127 9457 4516 9457 4518 9457 5127 9458 4518 9458 5129 9458 5129 9459 4518 9459 4520 9459 5129 9460 4520 9460 5130 9460 3466 9461 3465 9461 4509 9461 4509 9462 3465 9462 5130 9462 4509 9463 5130 9463 4508 9463 4508 9464 5130 9464 4520 9464 3465 9465 3498 9465 5130 9465 5130 9466 3498 9466 5131 9466 5130 9467 5131 9467 5129 9467 5129 9468 5131 9468 5132 9468 5129 9469 5132 9469 5127 9469 5127 9470 5132 9470 5128 9470 5127 9471 5128 9471 5121 9471 5121 9472 5128 9472 5123 9472 3498 9473 3508 9473 5131 9473 5131 9474 3508 9474 5133 9474 5131 9475 5133 9475 5132 9475 5132 9476 5133 9476 5134 9476 5132 9477 5134 9477 5128 9477 5128 9478 5134 9478 5135 9478 5128 9479 5135 9479 5126 9479 5126 9480 5135 9480 5119 9480 3508 9481 3423 9481 5133 9481 5133 9482 3423 9482 3429 9482 5133 9483 3429 9483 5134 9483 5134 9484 3429 9484 3428 9484 5134 9485 3428 9485 5135 9485 5135 9486 3428 9486 3422 9486 5135 9487 3422 9487 5119 9487 5119 9488 3422 9488 5118 9488 5136 9489 5137 9489 5138 9489 5139 9490 4860 9490 4859 9490 5139 9491 4859 9491 5140 9491 5140 9492 4859 9492 4867 9492 5140 9493 4867 9493 5141 9493 4867 9494 4866 9494 5141 9494 5141 9495 4866 9495 4872 9495 5141 9496 4872 9496 5142 9496 5143 9497 4553 9497 5144 9497 5144 9498 4553 9498 4552 9498 5144 9499 4552 9499 5145 9499 5145 9500 4552 9500 4513 9500 5145 9501 4513 9501 5146 9501 4872 9502 4871 9502 5142 9502 5142 9503 4871 9503 4869 9503 5142 9504 4869 9504 5147 9504 4869 9505 4868 9505 5147 9505 5147 9506 4868 9506 4873 9506 5147 9507 4873 9507 5148 9507 4873 9508 4875 9508 5148 9508 5148 9509 4875 9509 4877 9509 5148 9510 4877 9510 5149 9510 5150 9511 4551 9511 5151 9511 5151 9512 4551 9512 4550 9512 5151 9513 4550 9513 5152 9513 5152 9514 4550 9514 4555 9514 5152 9515 4555 9515 5143 9515 5143 9516 4555 9516 4554 9516 5143 9517 4554 9517 4553 9517 4877 9518 4878 9518 5149 9518 5149 9519 4878 9519 4880 9519 5149 9520 4880 9520 5153 9520 4549 9521 4548 9521 5150 9521 5150 9522 4548 9522 4547 9522 5150 9523 4547 9523 4551 9523 4880 9524 4881 9524 5153 9524 5153 9525 4881 9525 4883 9525 5153 9526 4883 9526 5154 9526 4883 9527 4888 9527 5154 9527 5154 9528 4888 9528 4887 9528 5154 9529 4887 9529 5155 9529 5150 9530 5156 9530 4549 9530 4549 9531 5156 9531 5157 9531 4549 9532 5157 9532 4546 9532 4546 9533 5157 9533 5158 9533 4887 9534 4885 9534 5155 9534 5155 9535 4885 9535 4891 9535 5155 9536 4891 9536 5159 9536 4543 9537 4544 9537 5158 9537 5158 9538 4544 9538 4545 9538 5158 9539 4545 9539 4546 9539 4891 9540 4890 9540 5159 9540 5159 9541 4890 9541 4896 9541 5159 9542 4896 9542 5160 9542 5160 9543 4896 9543 4895 9543 5160 9544 4895 9544 5161 9544 5161 9545 4895 9545 4893 9545 5158 9546 5162 9546 4543 9546 4543 9547 5162 9547 5163 9547 4543 9548 5163 9548 4540 9548 4540 9549 5163 9549 5164 9549 4540 9550 5164 9550 4541 9550 4541 9551 5164 9551 4542 9551 4893 9552 4892 9552 5161 9552 5161 9553 4892 9553 4897 9553 5161 9554 4897 9554 5165 9554 4897 9555 4899 9555 5165 9555 5165 9556 4899 9556 4901 9556 5165 9557 4901 9557 5166 9557 5167 9558 5168 9558 5169 9558 5169 9559 5168 9559 5164 9559 5169 9560 5164 9560 5170 9560 5170 9561 5164 9561 5163 9561 5170 9562 5163 9562 5171 9562 5171 9563 5163 9563 5162 9563 5171 9564 5162 9564 5172 9564 5172 9565 5162 9565 5158 9565 5172 9566 5158 9566 5173 9566 5173 9567 5158 9567 5157 9567 5173 9568 5157 9568 5174 9568 5174 9569 5157 9569 5156 9569 5174 9570 5156 9570 5175 9570 5175 9571 5156 9571 5150 9571 5175 9572 5150 9572 5176 9572 5176 9573 5150 9573 5151 9573 5176 9574 5151 9574 5177 9574 5177 9575 5151 9575 5152 9575 5177 9576 5152 9576 5178 9576 5178 9577 5152 9577 5143 9577 5178 9578 5143 9578 5179 9578 5179 9579 5143 9579 5144 9579 5179 9580 5144 9580 5180 9580 5180 9581 5144 9581 5145 9581 5180 9582 5145 9582 5181 9582 5181 9583 5145 9583 5146 9583 5181 9584 5146 9584 5182 9584 5183 9585 5167 9585 5166 9585 5166 9586 5167 9586 5169 9586 5166 9587 5169 9587 5165 9587 5165 9588 5169 9588 5170 9588 5165 9589 5170 9589 5161 9589 5161 9590 5170 9590 5171 9590 5161 9591 5171 9591 5160 9591 5160 9592 5171 9592 5172 9592 5160 9593 5172 9593 5159 9593 5159 9594 5172 9594 5173 9594 5159 9595 5173 9595 5155 9595 5155 9596 5173 9596 5174 9596 5155 9597 5174 9597 5154 9597 5154 9598 5174 9598 5175 9598 5154 9599 5175 9599 5153 9599 5153 9600 5175 9600 5176 9600 5153 9601 5176 9601 5149 9601 5149 9602 5176 9602 5177 9602 5149 9603 5177 9603 5148 9603 5148 9604 5177 9604 5178 9604 5148 9605 5178 9605 5147 9605 5147 9606 5178 9606 5179 9606 5147 9607 5179 9607 5142 9607 5142 9608 5179 9608 5180 9608 5142 9609 5180 9609 5141 9609 5141 9610 5180 9610 5181 9610 5141 9611 5181 9611 5140 9611 5140 9612 5181 9612 5182 9612 5140 9613 5182 9613 5139 9613 4901 9614 4902 9614 5166 9614 5166 9615 4902 9615 4904 9615 5166 9616 4904 9616 5183 9616 5183 9617 4904 9617 4905 9617 5183 9618 4905 9618 4907 9618 5184 9619 5137 9619 5185 9619 5185 9620 5137 9620 5136 9620 5185 9621 5136 9621 5186 9621 4534 9622 4535 9622 5184 9622 5184 9623 4535 9623 4539 9623 5184 9624 4539 9624 5137 9624 5137 9625 4539 9625 4538 9625 5137 9626 4538 9626 5138 9626 5138 9627 4538 9627 4537 9627 5138 9628 4537 9628 4536 9628 4908 9629 4910 9629 5186 9629 4542 9630 5164 9630 4536 9630 4536 9631 5164 9631 5168 9631 4536 9632 5168 9632 5138 9632 5138 9633 5168 9633 5167 9633 5138 9634 5167 9634 5136 9634 5136 9635 5167 9635 5183 9635 5136 9636 5183 9636 5186 9636 5186 9637 5183 9637 4907 9637 5186 9638 4907 9638 4908 9638 4534 9639 5184 9639 5187 9639 5187 9640 5184 9640 5185 9640 5187 9641 5185 9641 5188 9641 5188 9642 5185 9642 5186 9642 5188 9643 5186 9643 5189 9643 5189 9644 5186 9644 4910 9644 5189 9645 4910 9645 4840 9645 5190 9646 5191 9646 5192 9646 5189 9647 4840 9647 4839 9647 5189 9648 4839 9648 5193 9648 5193 9649 4839 9649 4838 9649 5193 9650 4838 9650 5194 9650 5194 9651 4838 9651 4843 9651 5194 9652 4843 9652 5195 9652 4534 9653 5187 9653 4529 9653 4529 9654 5187 9654 5196 9654 4529 9655 5196 9655 4530 9655 4530 9656 5196 9656 5197 9656 4530 9657 5197 9657 4531 9657 4531 9658 5197 9658 5198 9658 4531 9659 5198 9659 4532 9659 4532 9660 5198 9660 4533 9660 4843 9661 4835 9661 5195 9661 5195 9662 4835 9662 4834 9662 5195 9663 4834 9663 5199 9663 5199 9664 4834 9664 4844 9664 5200 9665 5198 9665 5201 9665 5201 9666 5198 9666 5197 9666 5201 9667 5197 9667 5202 9667 5202 9668 5197 9668 5196 9668 5202 9669 5196 9669 5203 9669 5203 9670 5196 9670 5187 9670 5203 9671 5187 9671 5188 9671 5204 9672 5200 9672 5199 9672 5199 9673 5200 9673 5201 9673 5199 9674 5201 9674 5195 9674 5195 9675 5201 9675 5202 9675 5195 9676 5202 9676 5194 9676 5194 9677 5202 9677 5203 9677 5194 9678 5203 9678 5193 9678 5193 9679 5203 9679 5188 9679 5193 9680 5188 9680 5189 9680 4844 9681 4846 9681 5199 9681 5199 9682 4846 9682 4848 9682 5199 9683 4848 9683 5204 9683 5204 9684 4848 9684 4849 9684 5204 9685 4849 9685 4850 9685 5205 9686 5191 9686 5206 9686 5206 9687 5191 9687 5190 9687 5206 9688 5190 9688 5207 9688 4533 9689 5192 9689 4525 9689 4525 9690 5192 9690 5191 9690 4525 9691 5191 9691 4524 9691 4524 9692 5191 9692 5205 9692 4524 9693 5205 9693 4528 9693 4528 9694 5205 9694 4527 9694 4533 9695 5198 9695 5192 9695 5192 9696 5198 9696 5200 9696 5192 9697 5200 9697 5190 9697 5190 9698 5200 9698 5204 9698 5190 9699 5204 9699 5207 9699 5207 9700 5204 9700 4850 9700 5207 9701 4850 9701 4851 9701 4527 9702 5205 9702 5208 9702 5208 9703 5205 9703 5206 9703 5208 9704 5206 9704 5209 9704 5209 9705 5206 9705 5207 9705 5209 9706 5207 9706 5210 9706 5210 9707 5207 9707 4851 9707 5210 9708 4851 9708 4818 9708 4862 9709 4860 9709 5211 9709 5211 9710 4860 9710 5139 9710 5211 9711 5139 9711 5212 9711 5212 9712 5139 9712 5182 9712 5212 9713 5182 9713 5213 9713 5213 9714 5182 9714 5146 9714 5213 9715 5146 9715 4512 9715 4512 9716 5146 9716 4513 9716 4864 9717 4862 9717 5214 9717 5214 9718 4862 9718 5211 9718 5214 9719 5211 9719 5215 9719 5215 9720 5211 9720 5212 9720 5215 9721 5212 9721 5216 9721 5216 9722 5212 9722 5213 9722 5216 9723 5213 9723 4511 9723 4511 9724 5213 9724 4512 9724 4526 9725 4527 9725 5217 9725 5217 9726 4527 9726 5208 9726 5217 9727 5208 9727 5218 9727 5218 9728 5208 9728 5219 9728 5219 9729 5208 9729 5209 9729 5219 9730 5209 9730 5220 9730 5220 9731 5209 9731 5221 9731 5221 9732 5209 9732 5210 9732 5221 9733 5210 9733 5222 9733 5222 9734 5210 9734 5223 9734 5223 9735 5210 9735 4818 9735 5223 9736 4818 9736 4817 9736 5216 9737 4511 9737 4510 9737 5215 9738 5216 9738 5224 9738 4931 9739 4864 9739 5225 9739 5225 9740 4864 9740 5214 9740 5225 9741 5214 9741 5226 9741 5216 9742 4510 9742 5224 9742 5224 9743 4510 9743 4507 9743 5224 9744 4507 9744 5227 9744 5227 9745 5228 9745 5224 9745 5224 9746 5228 9746 5226 9746 5224 9747 5226 9747 5215 9747 5215 9748 5226 9748 5214 9748 3435 9749 4931 9749 5229 9749 5229 9750 4931 9750 5225 9750 5229 9751 5225 9751 5230 9751 5230 9752 5225 9752 5226 9752 5230 9753 5226 9753 5231 9753 5231 9754 5226 9754 5228 9754 5232 9755 3438 9755 3437 9755 5233 9756 5234 9756 5235 9756 5231 9757 5228 9757 5233 9757 5233 9758 5228 9758 5227 9758 5233 9759 5227 9759 4507 9759 4507 9760 4506 9760 5233 9760 5233 9761 4506 9761 4519 9761 5233 9762 4519 9762 5234 9762 4519 9763 4521 9763 5234 9763 5234 9764 4521 9764 4522 9764 5234 9765 4522 9765 4523 9765 5229 9766 5230 9766 5236 9766 5236 9767 5230 9767 5231 9767 4523 9768 5237 9768 5234 9768 5234 9769 5237 9769 5238 9769 5234 9770 5238 9770 5235 9770 5235 9771 5238 9771 5239 9771 5235 9772 5239 9772 5240 9772 3435 9773 5229 9773 3436 9773 3436 9774 5229 9774 5236 9774 3436 9775 5236 9775 3437 9775 5231 9776 5233 9776 5236 9776 5236 9777 5233 9777 5235 9777 5236 9778 5235 9778 3437 9778 3437 9779 5235 9779 5240 9779 3437 9780 5240 9780 5232 9780 5238 9781 5237 9781 5241 9781 5241 9782 5237 9782 4523 9782 5241 9783 4523 9783 4561 9783 5238 9784 5241 9784 5239 9784 5239 9785 5241 9785 5242 9785 5239 9786 5242 9786 5240 9786 5240 9787 5242 9787 5243 9787 5240 9788 5243 9788 5232 9788 5232 9789 5243 9789 3440 9789 5232 9790 3440 9790 3438 9790 5244 9791 5245 9791 5243 9791 5243 9792 5245 9792 3441 9792 5243 9793 3441 9793 3440 9793 5244 9794 5243 9794 5246 9794 5246 9795 5243 9795 5242 9795 5246 9796 5242 9796 5247 9796 5247 9797 5242 9797 5241 9797 5247 9798 5241 9798 5248 9798 5248 9799 5241 9799 4561 9799 5248 9800 4561 9800 2806 9800 4594 9801 5244 9801 5246 9801 3543 9802 3545 9802 5249 9802 5249 9803 3545 9803 3546 9803 5249 9804 3546 9804 4594 9804 5250 9805 5251 9805 5252 9805 5252 9806 5251 9806 3543 9806 5253 9807 5254 9807 5250 9807 5255 9808 2808 9808 2792 9808 4594 9809 5246 9809 5249 9809 5249 9810 5246 9810 5247 9810 5249 9811 5247 9811 5256 9811 5256 9812 5247 9812 5248 9812 5256 9813 5248 9813 5255 9813 5255 9814 5248 9814 2806 9814 5255 9815 2806 9815 2808 9815 3543 9816 5249 9816 5252 9816 5252 9817 5249 9817 5256 9817 5252 9818 5256 9818 5257 9818 5257 9819 5256 9819 5255 9819 5257 9820 5255 9820 5258 9820 5258 9821 5255 9821 2792 9821 5258 9822 2792 9822 2800 9822 5250 9823 5252 9823 5253 9823 5253 9824 5252 9824 5257 9824 5253 9825 5257 9825 5259 9825 5259 9826 5257 9826 5258 9826 5259 9827 5258 9827 5260 9827 5260 9828 5258 9828 2800 9828 5260 9829 2800 9829 2805 9829 3544 9830 3543 9830 5261 9830 3544 9831 5261 9831 4586 9831 4586 9832 5261 9832 4598 9832 4586 9833 4598 9833 4582 9833 5251 9834 5250 9834 5262 9834 4595 9835 4598 9835 5262 9835 5262 9836 4598 9836 5261 9836 5262 9837 5261 9837 5251 9837 5251 9838 5261 9838 3543 9838 4596 9839 4595 9839 5263 9839 5263 9840 4595 9840 5262 9840 5263 9841 5262 9841 5254 9841 5254 9842 5262 9842 5250 9842 5264 9843 3396 9843 5265 9843 5265 9844 3396 9844 3395 9844 3036 9845 3035 9845 4963 9845 5264 9846 5266 9846 5267 9846 5268 9847 5269 9847 5270 9847 3039 9848 3038 9848 5271 9848 3382 9849 5272 9849 4275 9849 4275 9850 5272 9850 5273 9850 4275 9851 5273 9851 4277 9851 4278 9852 4277 9852 4505 9852 4505 9853 4277 9853 5274 9853 4505 9854 5274 9854 4188 9854 4191 9855 4190 9855 5275 9855 5275 9856 4190 9856 4189 9856 5275 9857 4189 9857 4188 9857 4181 9858 4183 9858 5276 9858 5276 9859 4183 9859 4182 9859 5276 9860 4182 9860 4191 9860 5277 9861 5278 9861 5279 9861 5279 9862 5278 9862 5280 9862 4181 9863 5276 9863 4972 9863 4972 9864 5276 9864 5281 9864 4972 9865 5281 9865 4973 9865 4973 9866 5281 9866 5282 9866 4973 9867 5282 9867 4974 9867 3382 9868 3381 9868 5272 9868 5272 9869 3381 9869 3379 9869 5272 9870 3379 9870 5283 9870 5283 9871 3379 9871 3378 9871 5283 9872 3378 9872 5284 9872 4974 9873 5282 9873 4966 9873 4966 9874 5282 9874 5285 9874 4966 9875 5285 9875 4967 9875 4967 9876 5285 9876 5286 9876 4967 9877 5286 9877 4968 9877 4968 9878 5286 9878 5287 9878 4968 9879 5287 9879 4970 9879 3378 9880 3385 9880 5284 9880 5284 9881 3385 9881 3386 9881 5284 9882 3386 9882 5288 9882 5288 9883 3386 9883 3392 9883 5288 9884 3392 9884 5289 9884 5289 9885 3392 9885 3391 9885 5289 9886 3391 9886 5290 9886 5290 9887 3391 9887 3390 9887 5290 9888 3390 9888 5291 9888 5291 9889 3390 9889 3388 9889 5291 9890 3388 9890 5292 9890 5292 9891 3388 9891 3387 9891 5292 9892 3387 9892 5293 9892 4277 9893 5273 9893 5274 9893 5274 9894 5273 9894 5272 9894 5274 9895 5272 9895 5294 9895 5294 9896 5272 9896 5283 9896 5294 9897 5283 9897 5295 9897 5295 9898 5283 9898 5284 9898 5295 9899 5284 9899 5296 9899 5296 9900 5284 9900 5288 9900 5296 9901 5288 9901 5297 9901 5297 9902 5288 9902 5289 9902 5297 9903 5289 9903 5298 9903 5298 9904 5289 9904 5290 9904 5298 9905 5290 9905 5299 9905 5299 9906 5290 9906 5291 9906 5299 9907 5291 9907 5300 9907 5300 9908 5291 9908 5292 9908 5300 9909 5292 9909 5301 9909 5301 9910 5292 9910 5293 9910 5301 9911 5293 9911 5302 9911 5302 9912 5293 9912 5267 9912 5302 9913 5267 9913 5270 9913 5270 9914 5267 9914 5266 9914 5270 9915 5266 9915 5268 9915 4188 9916 5274 9916 5275 9916 5275 9917 5274 9917 5294 9917 5275 9918 5294 9918 5303 9918 5303 9919 5294 9919 5295 9919 5303 9920 5295 9920 5304 9920 5304 9921 5295 9921 5296 9921 5304 9922 5296 9922 5305 9922 5305 9923 5296 9923 5297 9923 5305 9924 5297 9924 5306 9924 5306 9925 5297 9925 5298 9925 5306 9926 5298 9926 5307 9926 5307 9927 5298 9927 5299 9927 5307 9928 5299 9928 5308 9928 5308 9929 5299 9929 5300 9929 5308 9930 5300 9930 5309 9930 5309 9931 5300 9931 5301 9931 5309 9932 5301 9932 5310 9932 5310 9933 5301 9933 5302 9933 5310 9934 5302 9934 5311 9934 5311 9935 5302 9935 5270 9935 5311 9936 5270 9936 5279 9936 5279 9937 5270 9937 5269 9937 5279 9938 5269 9938 5277 9938 4191 9939 5275 9939 5276 9939 5276 9940 5275 9940 5303 9940 5276 9941 5303 9941 5281 9941 5281 9942 5303 9942 5304 9942 5281 9943 5304 9943 5282 9943 5282 9944 5304 9944 5305 9944 5282 9945 5305 9945 5285 9945 5285 9946 5305 9946 5306 9946 5285 9947 5306 9947 5286 9947 5286 9948 5306 9948 5307 9948 5286 9949 5307 9949 5287 9949 5287 9950 5307 9950 5308 9950 5287 9951 5308 9951 5312 9951 5312 9952 5308 9952 5309 9952 5312 9953 5309 9953 5313 9953 5313 9954 5309 9954 5310 9954 5313 9955 5310 9955 5314 9955 5314 9956 5310 9956 5311 9956 5314 9957 5311 9957 5315 9957 5315 9958 5311 9958 5279 9958 5315 9959 5279 9959 5271 9959 5271 9960 5279 9960 5280 9960 5271 9961 5280 9961 3039 9961 3387 9962 3398 9962 5293 9962 5293 9963 3398 9963 3397 9963 5293 9964 3397 9964 5267 9964 5267 9965 3397 9965 3396 9965 5267 9966 3396 9966 5264 9966 4970 9967 5287 9967 4971 9967 4971 9968 5287 9968 5312 9968 4971 9969 5312 9969 4961 9969 4961 9970 5312 9970 5313 9970 4961 9971 5313 9971 4960 9971 4960 9972 5313 9972 5314 9972 4960 9973 5314 9973 4958 9973 4958 9974 5314 9974 5315 9974 4958 9975 5315 9975 4964 9975 4964 9976 5315 9976 5271 9976 4964 9977 5271 9977 4963 9977 4963 9978 5271 9978 3038 9978 4963 9979 3038 9979 3036 9979 3272 9980 3270 9980 3275 9980 3283 9981 3285 9981 3287 9981 3279 9982 3281 9982 3283 9982 3290 9983 3269 9983 3272 9983 3279 9984 3283 9984 3277 9984 3277 9985 3283 9985 3275 9985 3275 9986 3283 9986 3287 9986 3275 9987 3287 9987 3272 9987 3272 9988 3287 9988 3289 9988 3272 9989 3289 9989 3290 9989 3445 9990 3447 9990 5316 9990 5317 9991 3458 9991 3500 9991 3500 9992 3499 9992 5317 9992 5317 9993 3499 9993 3455 9993 5317 9994 3455 9994 3445 9994 2878 9995 2877 9995 5318 9995 5318 9996 2877 9996 2880 9996 5318 9997 2880 9997 2879 9997 5319 9998 5320 9998 2878 9998 2864 9999 2865 9999 5320 9999 5320 10000 2865 10000 2874 10000 5320 10001 2874 10001 2875 10001 2875 10002 2860 10002 5320 10002 5320 10003 2860 10003 2859 10003 5320 10004 2859 10004 2878 10004 5316 10005 5321 10005 5322 10005 3445 10006 5316 10006 5317 10006 5317 10007 5316 10007 5322 10007 5317 10008 5322 10008 5323 10008 5323 10009 5324 10009 5317 10009 5317 10010 5324 10010 5325 10010 5317 10011 5325 10011 5326 10011 5326 10012 5327 10012 5317 10012 5317 10013 5327 10013 2869 10013 5317 10014 2869 10014 5328 10014 5328 10015 2869 10015 2868 10015 5328 10016 2868 10016 5320 10016 5320 10017 2868 10017 2871 10017 5320 10018 2871 10018 2864 10018 2878 10019 5318 10019 5319 10019 5319 10020 5318 10020 5329 10020 5319 10021 5329 10021 5330 10021 5330 10022 5329 10022 5331 10022 5330 10023 5331 10023 5332 10023 5332 10024 5331 10024 5333 10024 5332 10025 5333 10025 5334 10025 5334 10026 5333 10026 5335 10026 5334 10027 5335 10027 5336 10027 5336 10028 5335 10028 5337 10028 5336 10029 5337 10029 5338 10029 5338 10030 5337 10030 5339 10030 5338 10031 5339 10031 5340 10031 5340 10032 5339 10032 3414 10032 5340 10033 3414 10033 3410 10033 3409 10034 3457 10034 5330 10034 5330 10035 3457 10035 3462 10035 5330 10036 3462 10036 5319 10036 5319 10037 3462 10037 3461 10037 5319 10038 3461 10038 3459 10038 5330 10039 5332 10039 3409 10039 3409 10040 5332 10040 5334 10040 3409 10041 5334 10041 5336 10041 5328 10042 5320 10042 5317 10042 5317 10043 5320 10043 5319 10043 5317 10044 5319 10044 3458 10044 3458 10045 5319 10045 3459 10045 5336 10046 5338 10046 3409 10046 3409 10047 5338 10047 5340 10047 3409 10048 5340 10048 3410 10048 5341 10049 5342 10049 5343 10049 5343 10050 5342 10050 5344 10050 5343 10051 5344 10051 5345 10051 3016 10052 3015 10052 5346 10052 5345 10053 5344 10053 5346 10053 5346 10054 5344 10054 3019 10054 5346 10055 3019 10055 3016 10055 5347 10056 2857 10056 2856 10056 5348 10057 5349 10057 5350 10057 5351 10058 5352 10058 5353 10058 4504 10059 4503 10059 5354 10059 5354 10060 4503 10060 4146 10060 2897 10061 4481 10061 4504 10061 5355 10062 4152 10062 4154 10062 4156 10063 4155 10063 5356 10063 5356 10064 4155 10064 4152 10064 4146 10065 4145 10065 5357 10065 5357 10066 4145 10066 4157 10066 5357 10067 4157 10067 4156 10067 4982 10068 5355 10068 4983 10068 4983 10069 5355 10069 4154 10069 4983 10070 4154 10070 4153 10070 2897 10071 4504 10071 2898 10071 2898 10072 4504 10072 5354 10072 2898 10073 5354 10073 2900 10073 2900 10074 5354 10074 5358 10074 2900 10075 5358 10075 2907 10075 4980 10076 5359 10076 4982 10076 4982 10077 5359 10077 5360 10077 4982 10078 5360 10078 5355 10078 2907 10079 5358 10079 2892 10079 2892 10080 5358 10080 5361 10080 2892 10081 5361 10081 2893 10081 2893 10082 5361 10082 5362 10082 2893 10083 5362 10083 2894 10083 2894 10084 5362 10084 5363 10084 2894 10085 5363 10085 2895 10085 4980 10086 4979 10086 5359 10086 5359 10087 4979 10087 4993 10087 5359 10088 4993 10088 5364 10088 5364 10089 4993 10089 4992 10089 5364 10090 4992 10090 5365 10090 5365 10091 4992 10091 4990 10091 5365 10092 4990 10092 5366 10092 2895 10093 5363 10093 2896 10093 2896 10094 5363 10094 5367 10094 2896 10095 5367 10095 2888 10095 2888 10096 5367 10096 5368 10096 2888 10097 5368 10097 2889 10097 2889 10098 5368 10098 5369 10098 2889 10099 5369 10099 2884 10099 4152 10100 5355 10100 5356 10100 5356 10101 5355 10101 5360 10101 5356 10102 5360 10102 5370 10102 5370 10103 5360 10103 5359 10103 5370 10104 5359 10104 5371 10104 5371 10105 5359 10105 5364 10105 5371 10106 5364 10106 5372 10106 5372 10107 5364 10107 5365 10107 5372 10108 5365 10108 5373 10108 5373 10109 5365 10109 5366 10109 5373 10110 5366 10110 5374 10110 5374 10111 5366 10111 5375 10111 5374 10112 5375 10112 5376 10112 5376 10113 5375 10113 5377 10113 5376 10114 5377 10114 5378 10114 5378 10115 5377 10115 5379 10115 5378 10116 5379 10116 5380 10116 5380 10117 5379 10117 5381 10117 5380 10118 5381 10118 5382 10118 4990 10119 4989 10119 5366 10119 5366 10120 4989 10120 4988 10120 5366 10121 4988 10121 5375 10121 5375 10122 4988 10122 4987 10122 5375 10123 4987 10123 5377 10123 5377 10124 4987 10124 4986 10124 5377 10125 4986 10125 5379 10125 5379 10126 4986 10126 4984 10126 5379 10127 4984 10127 5381 10127 5381 10128 4984 10128 3019 10128 5381 10129 3019 10129 5344 10129 5344 10130 5342 10130 5381 10130 5381 10131 5342 10131 5341 10131 5381 10132 5341 10132 5382 10132 5382 10133 5341 10133 5383 10133 5382 10134 5383 10134 5384 10134 4156 10135 5356 10135 5357 10135 5357 10136 5356 10136 5370 10136 5357 10137 5370 10137 5385 10137 5385 10138 5370 10138 5371 10138 5385 10139 5371 10139 5386 10139 5386 10140 5371 10140 5372 10140 5386 10141 5372 10141 5387 10141 5387 10142 5372 10142 5373 10142 5387 10143 5373 10143 5388 10143 5388 10144 5373 10144 5374 10144 5388 10145 5374 10145 5389 10145 5389 10146 5374 10146 5376 10146 5389 10147 5376 10147 5390 10147 5390 10148 5376 10148 5378 10148 5390 10149 5378 10149 5391 10149 5391 10150 5378 10150 5380 10150 5391 10151 5380 10151 5392 10151 5392 10152 5380 10152 5382 10152 5392 10153 5382 10153 5353 10153 5353 10154 5382 10154 5384 10154 5353 10155 5384 10155 5351 10155 4146 10156 5357 10156 5354 10156 5354 10157 5357 10157 5385 10157 5354 10158 5385 10158 5358 10158 5358 10159 5385 10159 5386 10159 5358 10160 5386 10160 5361 10160 5361 10161 5386 10161 5387 10161 5361 10162 5387 10162 5362 10162 5362 10163 5387 10163 5388 10163 5362 10164 5388 10164 5363 10164 5363 10165 5388 10165 5389 10165 5363 10166 5389 10166 5367 10166 5367 10167 5389 10167 5390 10167 5367 10168 5390 10168 5368 10168 5368 10169 5390 10169 5391 10169 5368 10170 5391 10170 5369 10170 5369 10171 5391 10171 5392 10171 5369 10172 5392 10172 5393 10172 5393 10173 5392 10173 5353 10173 5393 10174 5353 10174 5350 10174 5350 10175 5353 10175 5352 10175 5350 10176 5352 10176 5348 10176 2884 10177 5369 10177 2885 10177 2885 10178 5369 10178 5393 10178 2885 10179 5393 10179 2887 10179 2887 10180 5393 10180 5350 10180 2887 10181 5350 10181 2856 10181 2856 10182 5350 10182 5349 10182 2856 10183 5349 10183 5347 10183 4570 10184 4569 10184 4562 10184 3581 10185 3549 10185 4562 10185 4562 10186 3549 10186 5394 10186 4562 10187 5394 10187 4570 10187 4570 10188 5394 10188 5395 10188 4570 10189 5395 10189 4571 10189 4571 10190 5395 10190 5396 10190 4571 10191 5396 10191 4572 10191 4572 10192 5396 10192 5397 10192 4572 10193 5397 10193 4573 10193 4573 10194 5397 10194 5097 10194 4573 10195 5097 10195 4575 10195 3553 10196 3556 10196 5398 10196 3551 10197 3553 10197 5399 10197 5399 10198 3553 10198 5398 10198 5399 10199 5398 10199 5400 10199 5400 10200 5398 10200 5401 10200 5400 10201 5401 10201 5402 10201 5402 10202 5401 10202 5403 10202 5402 10203 5403 10203 5404 10203 5404 10204 5403 10204 5405 10204 5404 10205 5405 10205 5096 10205 5096 10206 5405 10206 3586 10206 3549 10207 3551 10207 5394 10207 5394 10208 3551 10208 5399 10208 5394 10209 5399 10209 5395 10209 5395 10210 5399 10210 5400 10210 5395 10211 5400 10211 5396 10211 5396 10212 5400 10212 5402 10212 5396 10213 5402 10213 5397 10213 5397 10214 5402 10214 5404 10214 5397 10215 5404 10215 5097 10215 5097 10216 5404 10216 5096 10216 5406 10217 5407 10217 5408 10217 5398 10218 3556 10218 5409 10218 5409 10219 3556 10219 3558 10219 5403 10220 5401 10220 5410 10220 5405 10221 5403 10221 5411 10221 3586 10222 5405 10222 5412 10222 5403 10223 5410 10223 5411 10223 5411 10224 5410 10224 5413 10224 5411 10225 5413 10225 5414 10225 5414 10226 5413 10226 5415 10226 5414 10227 5415 10227 5408 10227 3586 10228 5412 10228 3588 10228 3588 10229 5412 10229 5416 10229 3588 10230 5416 10230 3589 10230 3589 10231 5416 10231 5417 10231 3589 10232 5417 10232 3590 10232 5418 10233 5415 10233 5419 10233 5419 10234 5415 10234 5413 10234 5419 10235 5413 10235 5420 10235 5420 10236 5413 10236 5410 10236 5420 10237 5410 10237 5409 10237 5409 10238 5410 10238 5401 10238 5409 10239 5401 10239 5398 10239 3558 10240 3563 10240 5409 10240 5409 10241 3563 10241 3562 10241 5409 10242 3562 10242 5420 10242 5420 10243 3562 10243 3561 10243 5420 10244 3561 10244 5419 10244 5419 10245 3561 10245 3568 10245 5419 10246 3568 10246 5418 10246 5418 10247 3568 10247 3569 10247 5418 10248 3569 10248 3565 10248 5421 10249 5407 10249 5422 10249 5422 10250 5407 10250 5406 10250 5422 10251 5406 10251 5423 10251 5408 10252 5415 10252 5406 10252 5406 10253 5415 10253 5418 10253 5406 10254 5418 10254 5423 10254 5423 10255 5418 10255 3565 10255 5423 10256 3565 10256 3515 10256 3515 10257 5424 10257 5423 10257 5423 10258 5424 10258 5425 10258 5423 10259 5425 10259 5422 10259 5422 10260 5425 10260 5426 10260 5422 10261 5426 10261 5421 10261 5421 10262 5426 10262 5427 10262 5421 10263 5427 10263 5428 10263 5405 10264 5411 10264 5412 10264 5412 10265 5411 10265 5414 10265 5412 10266 5414 10266 5416 10266 5416 10267 5414 10267 5408 10267 5416 10268 5408 10268 5417 10268 5417 10269 5408 10269 5407 10269 5417 10270 5407 10270 5429 10270 5429 10271 5407 10271 5421 10271 5429 10272 5421 10272 5430 10272 5430 10273 5421 10273 5428 10273 5430 10274 5428 10274 5431 10274 3590 10275 5417 10275 3591 10275 3591 10276 5417 10276 5429 10276 3591 10277 5429 10277 3592 10277 3592 10278 5429 10278 5430 10278 3592 10279 5430 10279 3582 10279 3582 10280 5430 10280 5431 10280 3582 10281 5431 10281 3583 10281 5432 10282 5433 10282 3593 10282 5434 10283 5435 10283 5436 10283 5424 10284 3515 10284 3514 10284 3533 10285 5435 10285 3534 10285 3534 10286 5435 10286 5434 10286 3534 10287 5434 10287 3529 10287 3525 10288 5437 10288 3527 10288 3527 10289 5437 10289 5438 10289 3527 10290 5438 10290 3530 10290 3530 10291 5438 10291 5439 10291 3530 10292 5439 10292 3531 10292 3531 10293 5439 10293 5440 10293 3531 10294 5440 10294 3533 10294 5425 10295 5441 10295 5426 10295 5426 10296 5441 10296 5427 10296 5442 10297 5443 10297 5441 10297 3604 10298 3605 10298 5444 10298 5444 10299 3605 10299 5442 10299 5444 10300 5442 10300 5445 10300 5445 10301 5442 10301 5441 10301 5445 10302 5441 10302 3514 10302 3514 10303 5441 10303 5425 10303 3514 10304 5425 10304 5424 10304 5437 10305 5433 10305 5438 10305 5438 10306 5433 10306 5432 10306 5438 10307 5432 10307 5439 10307 5439 10308 5432 10308 5446 10308 5439 10309 5446 10309 5440 10309 5440 10310 5446 10310 5447 10310 5427 10311 5441 10311 5428 10311 5428 10312 5441 10312 5443 10312 5428 10313 5443 10313 5431 10313 5431 10314 5443 10314 3608 10314 5431 10315 3608 10315 3583 10315 3605 10316 3607 10316 5442 10316 5442 10317 3607 10317 3610 10317 5442 10318 3610 10318 5443 10318 5443 10319 3610 10319 3609 10319 5443 10320 3609 10320 3608 10320 3514 10321 3529 10321 5445 10321 5445 10322 3529 10322 5434 10322 5445 10323 5434 10323 5444 10323 5444 10324 5434 10324 5436 10324 5444 10325 5436 10325 3604 10325 3604 10326 5436 10326 3602 10326 3533 10327 5440 10327 5435 10327 5435 10328 5440 10328 5447 10328 5435 10329 5447 10329 5436 10329 5436 10330 5447 10330 3597 10330 5436 10331 3597 10331 3602 10331 3593 10332 3595 10332 5432 10332 5432 10333 3595 10333 3601 10333 5432 10334 3601 10334 5446 10334 5446 10335 3601 10335 3600 10335 5446 10336 3600 10336 5447 10336 5447 10337 3600 10337 3598 10337 5447 10338 3598 10338 3597 10338 5102 10339 3593 10339 5433 10339 5102 10340 5433 10340 5448 10340 5448 10341 5433 10341 5437 10341 5448 10342 5437 10342 5449 10342 5449 10343 5437 10343 3525 10343 5449 10344 3525 10344 3524 10344 5450 10345 5449 10345 3524 10345 5102 10346 5448 10346 5101 10346 5101 10347 5448 10347 5451 10347 5101 10348 5451 10348 5099 10348 5099 10349 5451 10349 5452 10349 5099 10350 5452 10350 5100 10350 5100 10351 5452 10351 5453 10351 5100 10352 5453 10352 5098 10352 5448 10353 5449 10353 5451 10353 5451 10354 5449 10354 5450 10354 5451 10355 5450 10355 5452 10355 5452 10356 5450 10356 5454 10356 5452 10357 5454 10357 5453 10357 5453 10358 5454 10358 5455 10358 5098 10359 5453 10359 5456 10359 5456 10360 5453 10360 5455 10360 5456 10361 5455 10361 5457 10361 5457 10362 5455 10362 3571 10362 5457 10363 3571 10363 3439 10363 3524 10364 3579 10364 5450 10364 5450 10365 3579 10365 3577 10365 5450 10366 3577 10366 5454 10366 5454 10367 3577 10367 3575 10367 5454 10368 3575 10368 5455 10368 5455 10369 3575 10369 3573 10369 5455 10370 3573 10370 3571 10370 5244 10371 4594 10371 4593 10371 5245 10372 5457 10372 3441 10372 3441 10373 5457 10373 3439 10373 4591 10374 5098 10374 5456 10374 4591 10375 5456 10375 4592 10375 4592 10376 5456 10376 5457 10376 4592 10377 5457 10377 4593 10377 4593 10378 5457 10378 5245 10378 4593 10379 5245 10379 5244 10379 4563 10380 4562 10380 4569 10380 3430 10381 3432 10381 4569 10381 4569 10382 3432 10382 5458 10382 4569 10383 5458 10383 4563 10383 4563 10384 5458 10384 2844 10384 4563 10385 2844 10385 2843 10385 5459 10386 5460 10386 5461 10386 5462 10387 5463 10387 3415 10387 3415 10388 5463 10388 5464 10388 3415 10389 5464 10389 3416 10389 3416 10390 5464 10390 5465 10390 5465 10391 5466 10391 3416 10391 3416 10392 5466 10392 5467 10392 3416 10393 5467 10393 5468 10393 3222 10394 5469 10394 3231 10394 3231 10395 5469 10395 5470 10395 3231 10396 5470 10396 3232 10396 5471 10397 5472 10397 5473 10397 5474 10398 5475 10398 3421 10398 3421 10399 5475 10399 5476 10399 5473 10400 5477 10400 5471 10400 5471 10401 5477 10401 5478 10401 5471 10402 5478 10402 5476 10402 5476 10403 5478 10403 5479 10403 5476 10404 5479 10404 3421 10404 3222 10405 3221 10405 5469 10405 5469 10406 3221 10406 5480 10406 5469 10407 5480 10407 5481 10407 5482 10408 5481 10408 5483 10408 5484 10409 5483 10409 5485 10409 5485 10410 5483 10410 5481 10410 5485 10411 5481 10411 5486 10411 5486 10412 5481 10412 5480 10412 5487 10413 5488 10413 5489 10413 5489 10414 5488 10414 5122 10414 5490 10415 5491 10415 5492 10415 5492 10416 5491 10416 5493 10416 5492 10417 5493 10417 5483 10417 5483 10418 5493 10418 5494 10418 5483 10419 5494 10419 5482 10419 5492 10420 5495 10420 5490 10420 5490 10421 5495 10421 5496 10421 5490 10422 5496 10422 5489 10422 5489 10423 5496 10423 5497 10423 5489 10424 5497 10424 5487 10424 5479 10425 5498 10425 3421 10425 3421 10426 5498 10426 5499 10426 3421 10427 5499 10427 3419 10427 3419 10428 5499 10428 5489 10428 3419 10429 5489 10429 5124 10429 5124 10430 5489 10430 5122 10430 5459 10431 5461 10431 5500 10431 5500 10432 5461 10432 5501 10432 5500 10433 5501 10433 5502 10433 5502 10434 5501 10434 5503 10434 5502 10435 5503 10435 5504 10435 5504 10436 5503 10436 5505 10436 5504 10437 5505 10437 5506 10437 5506 10438 5505 10438 5507 10438 5506 10439 5507 10439 5508 10439 5508 10440 5507 10440 5509 10440 5508 10441 5509 10441 3293 10441 3293 10442 5509 10442 3299 10442 5027 10443 4945 10443 5510 10443 5510 10444 4945 10444 5511 10444 4946 10445 5512 10445 4945 10445 4945 10446 5512 10446 5513 10446 4945 10447 5513 10447 5511 10447 4948 10448 5514 10448 4946 10448 4946 10449 5514 10449 5515 10449 4946 10450 5515 10450 5512 10450 5516 10451 5461 10451 5460 10451 5517 10452 5518 10452 5519 10452 5519 10453 5518 10453 5516 10453 5519 10454 5516 10454 5520 10454 5520 10455 5516 10455 5460 10455 5517 10456 5521 10456 5518 10456 5518 10457 5521 10457 5522 10457 5518 10458 5522 10458 5523 10458 5523 10459 5522 10459 5524 10459 5523 10460 5524 10460 5515 10460 5515 10461 5524 10461 5525 10461 5515 10462 5525 10462 5512 10462 5526 10463 5527 10463 5461 10463 5528 10464 5529 10464 5461 10464 5503 10465 5501 10465 5527 10465 5527 10466 5501 10466 5461 10466 5530 10467 5526 10467 5461 10467 5531 10468 5532 10468 5533 10468 5534 10469 3299 10469 5509 10469 5505 10470 5535 10470 5507 10470 5507 10471 5535 10471 5536 10471 5507 10472 5536 10472 5509 10472 5509 10473 5536 10473 5537 10473 5509 10474 5537 10474 5534 10474 5532 10475 5531 10475 5535 10475 5535 10476 5531 10476 5538 10476 5535 10477 5538 10477 5536 10477 5539 10478 5526 10478 5540 10478 5540 10479 5526 10479 5530 10479 5540 10480 5530 10480 5529 10480 5529 10481 5530 10481 5461 10481 5541 10482 5542 10482 5543 10482 5543 10483 5542 10483 5544 10483 5543 10484 5544 10484 5528 10484 5528 10485 5544 10485 5545 10485 5528 10486 5545 10486 5529 10486 5529 10487 5545 10487 5546 10487 5529 10488 5546 10488 5540 10488 5461 10489 5516 10489 5528 10489 5528 10490 5516 10490 5518 10490 5528 10491 5518 10491 5543 10491 5543 10492 5518 10492 5523 10492 5543 10493 5523 10493 5541 10493 5541 10494 5523 10494 5515 10494 5541 10495 5515 10495 5547 10495 5547 10496 5515 10496 5514 10496 5547 10497 5514 10497 4948 10497 5505 10498 5503 10498 5535 10498 5535 10499 5503 10499 5527 10499 5535 10500 5527 10500 5532 10500 5532 10501 5527 10501 5526 10501 5532 10502 5526 10502 5533 10502 5533 10503 5526 10503 5539 10503 5548 10504 5549 10504 5550 10504 5063 10505 5065 10505 5551 10505 5063 10506 5551 10506 4956 10506 4952 10507 4957 10507 5552 10507 5552 10508 4957 10508 4956 10508 3303 10509 3305 10509 5553 10509 5553 10510 3305 10510 5554 10510 5553 10511 5554 10511 5555 10511 5550 10512 5549 10512 5554 10512 5554 10513 5549 10513 5556 10513 5554 10514 5556 10514 5555 10514 5548 10515 5550 10515 5557 10515 5557 10516 5550 10516 5558 10516 5557 10517 5558 10517 5559 10517 5559 10518 5558 10518 5560 10518 5559 10519 5560 10519 5561 10519 4956 10520 5551 10520 5552 10520 5552 10521 5551 10521 5562 10521 5552 10522 5562 10522 5560 10522 5560 10523 5562 10523 5563 10523 5560 10524 5563 10524 5561 10524 4951 10525 4952 10525 5564 10525 5564 10526 4952 10526 5552 10526 5564 10527 5552 10527 5565 10527 5565 10528 5552 10528 5560 10528 5565 10529 5560 10529 5566 10529 5566 10530 5560 10530 5558 10530 5566 10531 5558 10531 5567 10531 5567 10532 5558 10532 5550 10532 5567 10533 5550 10533 5568 10533 5568 10534 5550 10534 5554 10534 5568 10535 5554 10535 3307 10535 3307 10536 5554 10536 3305 10536 4949 10537 4951 10537 5569 10537 5569 10538 4951 10538 5564 10538 5569 10539 5564 10539 5570 10539 5570 10540 5564 10540 5565 10540 5570 10541 5565 10541 5571 10541 5571 10542 5565 10542 5566 10542 5571 10543 5566 10543 5572 10543 5572 10544 5566 10544 5567 10544 5572 10545 5567 10545 5573 10545 5573 10546 5567 10546 5568 10546 5573 10547 5568 10547 3309 10547 3309 10548 5568 10548 3307 10548 3309 10549 3310 10549 5573 10549 5573 10550 3310 10550 5574 10550 5573 10551 5574 10551 5572 10551 5572 10552 5574 10552 5575 10552 5572 10553 5575 10553 5571 10553 5571 10554 5575 10554 5576 10554 5571 10555 5576 10555 5570 10555 5570 10556 5576 10556 5577 10556 5570 10557 5577 10557 5569 10557 5569 10558 5577 10558 5578 10558 5569 10559 5578 10559 4949 10559 4955 10560 4954 10560 5578 10560 5578 10561 4954 10561 4953 10561 5578 10562 4953 10562 4949 10562 3302 10563 3301 10563 5579 10563 5579 10564 3301 10564 5580 10564 5579 10565 5580 10565 5581 10565 5582 10566 5583 10566 5584 10566 5584 10567 5583 10567 5585 10567 5584 10568 5585 10568 5586 10568 5586 10569 5585 10569 5587 10569 5586 10570 5587 10570 5588 10570 3301 10571 3299 10571 5580 10571 5580 10572 3299 10572 5534 10572 5580 10573 5534 10573 5537 10573 5537 10574 5536 10574 5580 10574 5580 10575 5536 10575 5588 10575 5580 10576 5588 10576 5581 10576 5581 10577 5588 10577 5587 10577 5533 10578 5586 10578 5531 10578 5531 10579 5586 10579 5588 10579 5531 10580 5588 10580 5538 10580 5538 10581 5588 10581 5536 10581 5533 10582 5539 10582 5586 10582 5586 10583 5539 10583 5540 10583 5586 10584 5540 10584 5584 10584 5584 10585 5540 10585 5546 10585 5584 10586 5546 10586 5545 10586 5545 10587 5544 10587 5584 10587 5584 10588 5544 10588 5542 10588 5584 10589 5542 10589 5582 10589 5582 10590 5542 10590 5541 10590 5582 10591 5541 10591 5547 10591 3310 10592 3302 10592 5574 10592 5574 10593 3302 10593 5579 10593 5574 10594 5579 10594 5575 10594 5575 10595 5579 10595 5581 10595 5575 10596 5581 10596 5576 10596 5576 10597 5581 10597 5587 10597 5576 10598 5587 10598 5577 10598 5577 10599 5587 10599 5585 10599 5577 10600 5585 10600 5578 10600 5578 10601 5585 10601 5583 10601 5578 10602 5583 10602 4955 10602 4955 10603 5583 10603 5582 10603 4955 10604 5582 10604 4947 10604 4947 10605 5582 10605 5547 10605 4947 10606 5547 10606 4948 10606 5589 10607 5472 10607 5471 10607 5590 10608 5591 10608 5592 10608 5592 10609 5591 10609 5593 10609 5594 10610 5595 10610 5596 10610 5595 10611 5594 10611 5597 10611 5594 10612 5023 10612 5597 10612 5597 10613 5023 10613 5025 10613 5597 10614 5025 10614 5598 10614 5598 10615 5025 10615 5027 10615 5599 10616 5004 10616 5019 10616 5599 10617 5019 10617 5600 10617 5019 10618 5018 10618 5600 10618 5600 10619 5018 10619 5022 10619 5600 10620 5022 10620 5601 10620 5601 10621 5022 10621 5021 10621 5601 10622 5021 10622 5594 10622 5594 10623 5021 10623 5020 10623 5594 10624 5020 10624 5023 10624 5596 10625 5590 10625 5594 10625 5594 10626 5590 10626 5592 10626 5594 10627 5592 10627 5601 10627 5601 10628 5592 10628 5602 10628 5601 10629 5602 10629 5600 10629 5600 10630 5602 10630 5603 10630 5600 10631 5603 10631 5599 10631 5599 10632 5603 10632 5604 10632 5593 10633 5589 10633 5592 10633 5592 10634 5589 10634 5471 10634 5592 10635 5471 10635 5602 10635 5602 10636 5471 10636 5476 10636 5602 10637 5476 10637 5603 10637 5603 10638 5476 10638 5475 10638 5603 10639 5475 10639 5604 10639 5604 10640 5475 10640 5474 10640 3311 10641 3312 10641 5605 10641 5605 10642 3312 10642 5606 10642 5605 10643 5606 10643 5607 10643 5607 10644 5606 10644 5608 10644 5608 10645 5606 10645 5609 10645 5608 10646 5609 10646 5610 10646 5610 10647 5609 10647 5611 10647 5611 10648 5609 10648 5612 10648 5611 10649 5612 10649 5613 10649 5613 10650 5612 10650 5614 10650 5614 10651 5612 10651 5109 10651 5614 10652 5109 10652 5110 10652 5511 10653 5615 10653 5510 10653 5510 10654 5615 10654 5616 10654 5510 10655 5616 10655 5027 10655 5027 10656 5617 10656 5598 10656 5598 10657 5617 10657 5618 10657 5598 10658 5618 10658 5597 10658 5511 10659 5513 10659 5615 10659 5615 10660 5513 10660 5512 10660 5615 10661 5512 10661 5619 10661 5597 10662 5618 10662 5595 10662 5595 10663 5618 10663 5620 10663 5595 10664 5620 10664 5596 10664 5596 10665 5620 10665 5621 10665 5596 10666 5621 10666 5590 10666 5512 10667 5525 10667 5619 10667 5619 10668 5525 10668 5524 10668 5619 10669 5524 10669 5622 10669 5622 10670 5524 10670 5522 10670 5622 10671 5522 10671 5623 10671 5522 10672 5521 10672 5623 10672 5623 10673 5521 10673 5517 10673 5623 10674 5517 10674 5624 10674 5624 10675 5517 10675 5519 10675 5624 10676 5519 10676 5625 10676 5027 10677 5616 10677 5617 10677 5617 10678 5616 10678 5615 10678 5617 10679 5615 10679 5618 10679 5618 10680 5615 10680 5619 10680 5618 10681 5619 10681 5620 10681 5620 10682 5619 10682 5622 10682 5620 10683 5622 10683 5621 10683 5621 10684 5622 10684 5623 10684 5621 10685 5623 10685 5626 10685 5626 10686 5623 10686 5624 10686 5626 10687 5624 10687 5627 10687 5627 10688 5624 10688 5625 10688 5627 10689 5625 10689 5628 10689 5590 10690 5621 10690 5591 10690 5591 10691 5621 10691 5626 10691 5591 10692 5626 10692 5593 10692 5593 10693 5626 10693 5627 10693 5593 10694 5627 10694 5589 10694 5589 10695 5627 10695 5628 10695 5589 10696 5628 10696 5472 10696 5473 10697 5472 10697 5629 10697 5629 10698 5472 10698 5628 10698 5629 10699 5628 10699 5630 10699 5630 10700 5628 10700 5625 10700 5630 10701 5625 10701 5520 10701 5520 10702 5625 10702 5519 10702 5477 10703 5473 10703 5631 10703 5631 10704 5473 10704 5629 10704 5631 10705 5629 10705 5632 10705 5632 10706 5629 10706 5630 10706 5632 10707 5630 10707 5460 10707 5460 10708 5630 10708 5520 10708 5460 10709 5459 10709 5633 10709 5460 10710 5633 10710 5632 10710 5632 10711 5633 10711 5634 10711 5632 10712 5634 10712 5631 10712 5631 10713 5634 10713 5478 10713 5631 10714 5478 10714 5477 10714 5635 10715 5633 10715 5459 10715 5459 10716 5500 10716 5635 10716 5635 10717 5500 10717 5502 10717 5635 10718 5502 10718 5636 10718 3293 10719 5637 10719 5508 10719 5508 10720 5637 10720 5638 10720 5508 10721 5638 10721 5506 10721 5506 10722 5638 10722 5636 10722 5506 10723 5636 10723 5504 10723 5504 10724 5636 10724 5502 10724 5637 10725 5639 10725 5638 10725 5638 10726 5639 10726 5640 10726 5638 10727 5640 10727 5636 10727 5636 10728 5640 10728 5641 10728 5636 10729 5641 10729 5635 10729 5635 10730 5641 10730 5642 10730 5635 10731 5642 10731 5633 10731 5633 10732 5642 10732 5634 10732 5639 10733 5489 10733 5640 10733 5640 10734 5489 10734 5499 10734 5640 10735 5499 10735 5641 10735 5641 10736 5499 10736 5498 10736 5641 10737 5498 10737 5642 10737 5642 10738 5498 10738 5479 10738 5642 10739 5479 10739 5634 10739 5634 10740 5479 10740 5478 10740 3293 10741 3295 10741 5643 10741 3293 10742 5643 10742 5637 10742 5637 10743 5643 10743 5644 10743 5637 10744 5644 10744 5639 10744 5639 10745 5644 10745 5490 10745 5639 10746 5490 10746 5489 10746 5645 10747 5493 10747 5491 10747 5646 10748 5647 10748 5648 10748 5649 10749 5650 10749 5651 10749 3327 10750 5649 10750 3351 10750 3351 10751 5649 10751 5651 10751 3351 10752 5651 10752 3295 10752 3295 10753 5651 10753 5643 10753 5650 10754 5646 10754 5651 10754 5651 10755 5646 10755 5648 10755 5651 10756 5648 10756 5643 10756 5643 10757 5648 10757 5644 10757 5647 10758 5645 10758 5648 10758 5648 10759 5645 10759 5491 10759 5648 10760 5491 10760 5644 10760 5644 10761 5491 10761 5490 10761 5650 10762 5649 10762 5652 10762 5482 10763 5494 10763 5653 10763 5654 10764 5655 10764 5656 10764 5656 10765 5655 10765 5657 10765 5656 10766 5657 10766 5653 10766 5653 10767 5657 10767 5658 10767 5653 10768 5658 10768 5482 10768 5646 10769 5656 10769 5647 10769 5647 10770 5656 10770 5653 10770 5647 10771 5653 10771 5645 10771 5645 10772 5653 10772 5494 10772 5645 10773 5494 10773 5493 10773 5646 10774 5650 10774 5656 10774 5656 10775 5650 10775 5652 10775 5656 10776 5652 10776 5654 10776 5654 10777 5652 10777 5659 10777 5649 10778 3327 10778 5652 10778 5652 10779 3327 10779 3330 10779 5652 10780 3330 10780 5659 10780 5659 10781 3330 10781 3324 10781 3324 10782 3323 10782 5659 10782 5659 10783 3323 10783 5660 10783 5659 10784 5660 10784 5654 10784 5654 10785 5660 10785 5661 10785 5654 10786 5661 10786 5655 10786 5655 10787 5661 10787 5662 10787 5655 10788 5662 10788 5657 10788 5657 10789 5662 10789 5663 10789 5657 10790 5663 10790 5658 10790 5658 10791 5663 10791 5664 10791 5658 10792 5664 10792 5482 10792 5482 10793 5664 10793 5481 10793 5470 10794 5665 10794 3232 10794 3232 10795 5665 10795 3234 10795 3234 10796 5665 10796 3235 10796 3235 10797 5665 10797 5666 10797 3235 10798 5666 10798 3236 10798 3240 10799 3239 10799 5667 10799 5667 10800 3239 10800 3238 10800 5667 10801 3238 10801 5668 10801 5668 10802 3238 10802 3237 10802 5668 10803 3237 10803 3236 10803 3229 10804 3339 10804 3227 10804 3227 10805 3339 10805 3226 10805 3349 10806 3348 10806 5669 10806 5669 10807 3348 10807 3347 10807 3347 10808 3345 10808 5670 10808 5670 10809 3345 10809 3344 10809 3229 10810 3241 10810 3339 10810 3339 10811 3241 10811 3240 10811 3339 10812 3240 10812 3341 10812 3341 10813 3240 10813 5667 10813 3341 10814 5667 10814 3342 10814 3323 10815 3349 10815 5660 10815 5660 10816 3349 10816 5669 10816 5660 10817 5669 10817 5661 10817 5661 10818 5669 10818 5671 10818 5661 10819 5671 10819 5662 10819 3236 10820 5666 10820 5668 10820 5668 10821 5666 10821 5670 10821 5668 10822 5670 10822 5667 10822 5667 10823 5670 10823 3344 10823 5667 10824 3344 10824 3342 10824 5662 10825 5671 10825 5663 10825 5663 10826 5671 10826 5672 10826 5663 10827 5672 10827 5664 10827 5664 10828 5672 10828 5469 10828 5664 10829 5469 10829 5481 10829 3347 10830 5670 10830 5669 10830 5669 10831 5670 10831 5666 10831 5669 10832 5666 10832 5671 10832 5671 10833 5666 10833 5665 10833 5671 10834 5665 10834 5672 10834 5672 10835 5665 10835 5470 10835 5672 10836 5470 10836 5469 10836 5104 10837 5103 10837 5673 10837 5120 10838 5122 10838 5488 10838 5104 10839 5673 10839 5107 10839 5113 10840 5614 10840 5111 10840 5111 10841 5614 10841 5110 10841 5674 10842 5675 10842 3311 10842 3311 10843 5605 10843 5674 10843 5674 10844 5605 10844 5607 10844 5674 10845 5607 10845 5676 10845 5113 10846 5115 10846 5614 10846 5614 10847 5115 10847 5116 10847 5614 10848 5116 10848 5613 10848 5613 10849 5116 10849 5117 10849 5613 10850 5117 10850 5611 10850 5611 10851 5117 10851 5677 10851 5611 10852 5677 10852 5610 10852 5610 10853 5677 10853 5676 10853 5610 10854 5676 10854 5608 10854 5608 10855 5676 10855 5607 10855 5117 10856 5107 10856 5677 10856 5677 10857 5107 10857 5673 10857 5677 10858 5673 10858 5676 10858 5676 10859 5673 10859 5678 10859 5676 10860 5678 10860 5674 10860 5674 10861 5678 10861 5679 10861 5674 10862 5679 10862 5675 10862 5675 10863 5679 10863 5680 10863 5103 10864 5120 10864 5673 10864 5673 10865 5120 10865 5488 10865 5673 10866 5488 10866 5678 10866 5678 10867 5488 10867 5487 10867 5678 10868 5487 10868 5679 10868 5679 10869 5487 10869 5497 10869 5679 10870 5497 10870 5680 10870 5680 10871 5497 10871 5496 10871 3314 10872 3311 10872 5675 10872 3314 10873 5675 10873 5681 10873 5681 10874 5675 10874 5680 10874 5681 10875 5680 10875 5682 10875 5682 10876 5680 10876 5496 10876 5682 10877 5496 10877 5495 10877 3353 10878 3314 10878 5681 10878 3320 10879 3353 10879 5683 10879 5683 10880 3353 10880 5684 10880 5683 10881 5684 10881 5685 10881 5685 10882 5684 10882 5686 10882 5686 10883 5684 10883 5687 10883 5686 10884 5687 10884 5688 10884 5688 10885 5687 10885 5689 10885 5689 10886 5687 10886 5492 10886 5689 10887 5492 10887 5483 10887 3353 10888 5681 10888 5684 10888 5684 10889 5681 10889 5682 10889 5684 10890 5682 10890 5687 10890 5687 10891 5682 10891 5495 10891 5687 10892 5495 10892 5492 10892 5690 10893 5691 10893 5692 10893 5483 10894 5484 10894 5693 10894 5685 10895 5686 10895 5694 10895 5694 10896 5686 10896 5688 10896 5694 10897 5688 10897 5693 10897 5693 10898 5688 10898 5689 10898 5693 10899 5689 10899 5483 10899 5695 10900 5694 10900 5696 10900 5696 10901 5694 10901 5693 10901 5696 10902 5693 10902 5697 10902 5697 10903 5693 10903 5484 10903 5697 10904 5484 10904 5485 10904 5695 10905 5690 10905 5694 10905 5694 10906 5690 10906 5692 10906 5694 10907 5692 10907 5685 10907 5685 10908 5692 10908 5683 10908 5691 10909 3315 10909 5692 10909 5692 10910 3315 10910 3318 10910 5692 10911 3318 10911 5683 10911 5683 10912 3318 10912 3320 10912 3315 10913 5691 10913 3321 10913 3321 10914 5691 10914 5698 10914 5691 10915 5690 10915 5698 10915 5698 10916 5690 10916 5695 10916 5698 10917 5695 10917 5699 10917 5485 10918 5486 10918 5697 10918 5697 10919 5486 10919 5699 10919 5697 10920 5699 10920 5696 10920 5696 10921 5699 10921 5695 10921 3331 10922 3321 10922 5698 10922 3333 10923 3331 10923 5700 10923 3337 10924 3334 10924 5701 10924 3219 10925 3218 10925 3336 10925 3336 10926 3218 10926 3215 10926 3336 10927 3215 10927 3216 10927 3336 10928 3337 10928 3219 10928 3219 10929 3337 10929 5701 10929 3219 10930 5701 10930 3220 10930 3220 10931 5701 10931 3223 10931 3213 10932 5702 10932 3214 10932 3214 10933 5702 10933 5480 10933 3214 10934 5480 10934 3221 10934 3334 10935 3333 10935 5701 10935 5701 10936 3333 10936 5700 10936 5701 10937 5700 10937 3223 10937 3223 10938 5700 10938 5702 10938 3223 10939 5702 10939 3224 10939 3224 10940 5702 10940 3213 10940 3331 10941 5698 10941 5700 10941 5700 10942 5698 10942 5699 10942 5700 10943 5699 10943 5702 10943 5702 10944 5699 10944 5486 10944 5702 10945 5486 10945 5480 10945 3006 10946 3029 10946 5703 10946 5704 10947 5705 10947 5703 10947 5703 10948 5705 10948 3007 10948 5703 10949 3007 10949 3006 10949 5704 10950 5703 10950 5706 10950 5706 10951 5703 10951 5707 10951 5706 10952 5707 10952 5708 10952 5708 10953 5707 10953 5709 10953 5709 10954 5707 10954 5463 10954 5709 10955 5463 10955 5462 10955 5710 10956 5468 10956 5467 10956 5711 10957 5710 10957 5712 10957 5015 10958 5711 10958 5016 10958 5016 10959 5711 10959 5713 10959 5016 10960 5713 10960 5001 10960 5001 10961 5713 10961 5714 10961 5001 10962 5714 10962 5002 10962 5002 10963 5714 10963 4997 10963 4997 10964 5714 10964 5715 10964 4997 10965 5715 10965 4998 10965 4998 10966 5715 10966 5716 10966 4998 10967 5716 10967 4999 10967 5710 10968 5467 10968 5712 10968 5712 10969 5467 10969 5466 10969 5712 10970 5466 10970 5717 10970 5717 10971 5466 10971 5465 10971 5717 10972 5465 10972 5718 10972 5718 10973 5465 10973 5464 10973 5718 10974 5464 10974 5719 10974 5719 10975 5464 10975 5463 10975 5719 10976 5463 10976 5707 10976 5711 10977 5712 10977 5713 10977 5713 10978 5712 10978 5717 10978 5713 10979 5717 10979 5714 10979 5714 10980 5717 10980 5718 10980 5714 10981 5718 10981 5715 10981 5715 10982 5718 10982 5719 10982 5715 10983 5719 10983 5716 10983 5716 10984 5719 10984 5707 10984 5716 10985 5707 10985 5703 10985 5703 10986 3029 10986 5716 10986 5716 10987 3029 10987 4995 10987 5716 10988 4995 10988 4999 10988 5474 10989 3421 10989 5720 10989 5720 10990 3421 10990 3426 10990 5720 10991 3426 10991 5721 10991 3426 10992 5722 10992 5723 10992 5723 10993 5724 10993 3426 10993 3426 10994 5724 10994 5725 10994 3426 10995 5725 10995 5721 10995 3416 10996 5468 10996 3411 10996 3411 10997 5468 10997 5726 10997 3411 10998 5726 10998 5727 10998 5727 10999 5728 10999 3411 10999 3411 11000 5728 11000 5729 11000 3411 11001 5729 11001 3426 11001 3426 11002 5729 11002 5730 11002 3426 11003 5730 11003 5722 11003 5711 11004 5015 11004 5014 11004 5710 11005 5711 11005 5731 11005 5468 11006 5710 11006 5732 11006 5468 11007 5732 11007 5726 11007 5726 11008 5732 11008 5733 11008 5726 11009 5733 11009 5727 11009 5727 11010 5733 11010 5734 11010 5727 11011 5734 11011 5728 11011 5728 11012 5734 11012 5729 11012 5729 11013 5734 11013 5735 11013 5729 11014 5735 11014 5730 11014 5730 11015 5735 11015 5736 11015 5730 11016 5736 11016 5722 11016 5722 11017 5736 11017 5737 11017 5722 11018 5737 11018 5723 11018 5723 11019 5737 11019 5738 11019 5723 11020 5738 11020 5724 11020 5711 11021 5014 11021 5731 11021 5731 11022 5014 11022 5013 11022 5731 11023 5013 11023 5739 11023 5739 11024 5013 11024 5012 11024 5739 11025 5012 11025 5740 11025 5740 11026 5012 11026 5011 11026 5740 11027 5011 11027 5741 11027 5741 11028 5011 11028 5010 11028 5741 11029 5010 11029 5742 11029 5742 11030 5010 11030 5009 11030 5742 11031 5009 11031 5743 11031 5743 11032 5009 11032 5008 11032 5743 11033 5008 11033 5744 11033 5744 11034 5008 11034 5007 11034 5744 11035 5007 11035 5745 11035 5745 11036 5007 11036 5006 11036 5745 11037 5006 11037 5746 11037 5746 11038 5006 11038 5004 11038 5746 11039 5004 11039 5599 11039 5710 11040 5731 11040 5732 11040 5732 11041 5731 11041 5739 11041 5732 11042 5739 11042 5733 11042 5733 11043 5739 11043 5740 11043 5733 11044 5740 11044 5734 11044 5734 11045 5740 11045 5741 11045 5734 11046 5741 11046 5735 11046 5735 11047 5741 11047 5742 11047 5735 11048 5742 11048 5736 11048 5736 11049 5742 11049 5743 11049 5736 11050 5743 11050 5737 11050 5737 11051 5743 11051 5744 11051 5737 11052 5744 11052 5738 11052 5738 11053 5744 11053 5745 11053 5738 11054 5745 11054 5747 11054 5747 11055 5745 11055 5746 11055 5747 11056 5746 11056 5748 11056 5748 11057 5746 11057 5599 11057 5748 11058 5599 11058 5604 11058 5724 11059 5738 11059 5725 11059 5725 11060 5738 11060 5747 11060 5725 11061 5747 11061 5721 11061 5721 11062 5747 11062 5748 11062 5721 11063 5748 11063 5720 11063 5720 11064 5748 11064 5604 11064 5720 11065 5604 11065 5474 11065 2828 11066 2831 11066 4565 11066 4565 11067 2831 11067 2830 11067 4565 11068 2830 11068 2836 11068 2836 11069 2835 11069 4565 11069 4565 11070 2835 11070 2834 11070 4565 11071 2834 11071 4566 11071 4566 11072 2834 11072 2833 11072 4566 11073 2833 11073 3371 11073 3371 11074 2833 11074 2832 11074 3371 11075 2832 11075 3370 11075 4564 11076 2751 11076 2765 11076 2765 11077 2764 11077 4564 11077 4564 11078 2764 11078 2762 11078 4564 11079 2762 11079 2761 11079 2761 11080 2768 11080 4564 11080 4564 11081 2768 11081 2767 11081 4564 11082 2767 11082 4565 11082 4565 11083 2767 11083 2826 11083 4565 11084 2826 11084 2828 11084 2751 11085 4564 11085 2752 11085 2752 11086 4564 11086 4567 11086 2752 11087 4567 11087 2754 11087 2842 11088 2760 11088 2759 11088 2759 11089 2757 11089 2842 11089 2842 11090 2757 11090 2756 11090 2842 11091 2756 11091 4567 11091 4567 11092 2756 11092 2755 11092 4567 11093 2755 11093 2754 11093 3217 11094 3193 11094 3194 11094 3355 11095 3369 11095 2971 11095 3194 11096 3359 11096 3319 11096 2995 11097 2971 11097 3271 11097 3271 11098 2971 11098 3369 11098 3271 11099 3369 11099 3266 11099 3266 11100 3369 11100 3363 11100 3352 11101 3319 11101 3313 11101 3313 11102 3319 11102 3359 11102 3313 11103 3359 11103 2982 11103 2982 11104 3359 11104 3357 11104 2982 11105 3357 11105 2976 11105 2971 11106 2970 11106 3355 11106 3355 11107 2970 11107 2998 11107 3355 11108 2998 11108 3357 11108 3357 11109 2998 11109 2977 11109 3357 11110 2977 11110 2976 11110 3332 11111 3335 11111 3322 11111 3322 11112 3335 11112 3217 11112 3322 11113 3217 11113 3316 11113 3316 11114 3217 11114 3194 11114 3316 11115 3194 11115 3317 11115 3317 11116 3194 11116 3319 11116 3267 11117 3266 11117 3362 11117 3362 11118 3266 11118 3363 11118 3207 11119 3326 11119 3329 11119 3326 11120 3207 11120 3325 11120 3346 11121 3338 11121 3325 11121 3247 11122 3248 11122 3383 11122 3383 11123 3248 11123 3205 11123 3375 11124 3329 11124 3376 11124 3376 11125 3329 11125 3328 11125 3205 11126 3207 11126 3383 11126 3383 11127 3207 11127 3329 11127 3383 11128 3329 11128 3401 11128 3401 11129 3329 11129 3375 11129 3328 11130 3350 11130 3376 11130 3376 11131 3350 11131 3297 11131 3376 11132 3297 11132 3296 11132 3343 11133 3346 11133 3340 11133 3340 11134 3346 11134 3325 11134 3340 11135 3325 11135 3225 11135 3225 11136 3325 11136 3207 11136 5749 11137 5087 11137 5750 11137 5750 11138 5087 11138 5088 11138 5750 11139 5088 11139 5751 11139 5751 11140 5088 11140 5089 11140 5751 11141 5089 11141 5752 11141 5752 11142 5089 11142 5090 11142 5752 11143 5090 11143 5753 11143 5753 11144 5090 11144 5091 11144 5753 11145 5091 11145 5754 11145 5754 11146 5091 11146 5092 11146 5754 11147 5092 11147 5755 11147 5755 11148 5092 11148 5093 11148 5755 11149 5093 11149 5756 11149 5756 11150 5093 11150 5094 11150 5756 11151 5094 11151 5757 11151 5757 11152 5094 11152 5095 11152 5757 11153 5095 11153 5758 11153 5758 11154 5095 11154 5084 11154 5758 11155 5084 11155 5759 11155 5759 11156 5084 11156 5085 11156 5759 11157 5085 11157 5760 11157 5760 11158 5085 11158 5086 11158 5760 11159 5086 11159 5749 11159 5749 11160 5086 11160 5087 11160 5761 11161 5762 11161 4578 11161 4578 11162 5762 11162 5763 11162 4578 11163 5763 11163 4577 11163 5764 11164 5765 11164 4579 11164 4579 11165 5765 11165 5766 11165 4579 11166 5766 11166 4578 11166 4578 11167 5766 11167 5767 11167 4578 11168 5767 11168 5761 11168 5764 11169 4579 11169 5768 11169 5768 11170 4579 11170 4587 11170 5768 11171 4587 11171 5769 11171 4588 11172 5770 11172 4587 11172 4587 11173 5770 11173 5771 11173 4587 11174 5771 11174 5769 11174 5763 11175 5772 11175 4577 11175 4577 11176 5772 11176 5773 11176 4577 11177 5773 11177 4576 11177 4576 11178 5773 11178 5774 11178 4576 11179 5774 11179 4574 11179 4574 11180 5774 11180 5775 11180 4574 11181 5775 11181 4580 11181 4580 11182 5775 11182 5776 11182 4580 11183 5776 11183 4583 11183 4583 11184 5776 11184 5777 11184 4583 11185 5777 11185 4581 11185 4581 11186 5777 11186 5778 11186 4581 11187 5778 11187 4590 11187 4590 11188 5778 11188 5779 11188 4590 11189 5779 11189 4589 11189 4589 11190 5779 11190 5780 11190 4589 11191 5780 11191 4588 11191 4588 11192 5780 11192 2841 11192 4588 11193 2841 11193 5770 11193 5781 11194 4627 11194 5782 11194 5782 11195 4627 11195 4629 11195 5782 11196 4629 11196 5783 11196 5783 11197 4629 11197 4630 11197 5783 11198 4630 11198 5784 11198 5784 11199 4630 11199 4631 11199 5784 11200 4631 11200 5785 11200 5785 11201 4631 11201 4633 11201 5785 11202 4633 11202 5786 11202 5786 11203 4633 11203 4635 11203 5786 11204 4635 11204 5787 11204 5787 11205 4635 11205 4617 11205 5787 11206 4617 11206 5788 11206 5788 11207 4617 11207 4619 11207 5788 11208 4619 11208 5789 11208 5789 11209 4619 11209 4621 11209 5789 11210 4621 11210 5790 11210 5790 11211 4621 11211 4623 11211 5790 11212 4623 11212 5791 11212 5791 11213 4623 11213 4625 11213 5791 11214 4625 11214 5792 11214 5792 11215 4625 11215 4626 11215 5792 11216 4626 11216 5781 11216 5781 11217 4626 11217 4627 11217 5793 11218 3750 11218 3748 11218 4600 11219 3683 11219 4482 11219 3682 11220 4485 11220 3683 11220 3683 11221 4485 11221 4483 11221 3683 11222 4483 11222 4482 11222 5794 11223 4602 11223 4601 11223 4660 11224 4610 11224 4609 11224 4604 11225 4614 11225 5795 11225 5795 11226 4614 11226 4613 11226 4604 11227 5796 11227 4605 11227 4605 11228 5796 11228 4606 11228 3770 11229 4608 11229 3767 11229 3767 11230 4608 11230 4607 11230 5797 11231 3767 11231 5796 11231 5796 11232 3767 11232 4607 11232 5796 11233 4607 11233 4606 11233 4613 11234 4640 11234 5795 11234 5795 11235 4640 11235 4639 11235 5795 11236 4639 11236 5798 11236 5798 11237 4639 11237 4638 11237 5798 11238 4638 11238 5799 11238 5799 11239 4638 11239 4651 11239 5799 11240 4651 11240 5800 11240 5801 11241 3759 11241 5802 11241 5802 11242 3759 11242 3757 11242 5802 11243 3757 11243 5797 11243 5797 11244 3757 11244 3768 11244 5797 11245 3768 11245 3767 11245 3763 11246 3762 11246 5801 11246 5801 11247 3762 11247 3761 11247 5801 11248 3761 11248 3759 11248 4651 11249 4650 11249 5800 11249 5800 11250 4650 11250 4649 11250 5800 11251 4649 11251 5803 11251 5803 11252 4649 11252 4642 11252 5803 11253 4642 11253 5804 11253 5804 11254 4642 11254 4641 11254 5804 11255 4641 11255 5805 11255 5805 11256 4641 11256 4645 11256 5805 11257 4645 11257 5806 11257 5806 11258 4645 11258 4644 11258 5806 11259 4644 11259 5807 11259 5807 11260 4644 11260 4643 11260 5807 11261 4643 11261 5808 11261 5808 11262 4643 11262 4648 11262 5808 11263 4648 11263 5809 11263 5809 11264 4648 11264 4647 11264 4646 11265 5810 11265 4647 11265 4647 11266 5810 11266 5811 11266 4647 11267 5811 11267 5809 11267 4646 11268 4657 11268 5810 11268 5810 11269 4657 11269 4658 11269 5810 11270 4658 11270 5812 11270 5812 11271 4658 11271 4659 11271 5812 11272 4659 11272 5813 11272 5813 11273 4659 11273 4656 11273 5813 11274 4656 11274 5814 11274 5814 11275 4656 11275 4655 11275 5814 11276 4655 11276 5815 11276 5815 11277 4655 11277 4654 11277 5815 11278 4654 11278 5816 11278 5816 11279 4654 11279 4653 11279 5816 11280 4653 11280 5817 11280 5817 11281 4653 11281 4652 11281 5801 11282 5818 11282 3763 11282 3763 11283 5818 11283 5819 11283 3763 11284 5819 11284 3719 11284 3719 11285 5819 11285 5820 11285 3719 11286 5820 11286 3720 11286 3720 11287 5820 11287 5821 11287 3720 11288 5821 11288 3721 11288 3721 11289 5821 11289 5822 11289 3721 11290 5822 11290 3722 11290 3722 11291 5822 11291 5823 11291 3722 11292 5823 11292 3723 11292 3723 11293 5823 11293 5824 11293 3723 11294 5824 11294 3726 11294 3726 11295 5824 11295 5825 11295 3726 11296 5825 11296 3725 11296 3725 11297 5825 11297 5826 11297 3725 11298 5826 11298 3724 11298 3724 11299 5826 11299 5827 11299 3724 11300 5827 11300 3727 11300 3727 11301 5827 11301 5828 11301 3727 11302 5828 11302 3728 11302 3728 11303 5828 11303 5829 11303 3728 11304 5829 11304 3737 11304 3737 11305 5829 11305 5830 11305 3737 11306 5830 11306 3738 11306 3738 11307 5830 11307 5831 11307 3738 11308 5831 11308 3729 11308 3729 11309 5831 11309 5832 11309 3729 11310 5832 11310 3730 11310 3730 11311 5832 11311 5833 11311 3730 11312 5833 11312 3732 11312 3732 11313 5833 11313 3735 11313 4637 11314 5834 11314 4652 11314 4652 11315 5834 11315 5835 11315 4652 11316 5835 11316 5817 11316 3735 11317 5833 11317 3748 11317 3748 11318 5833 11318 5836 11318 3748 11319 5836 11319 5793 11319 4637 11320 4636 11320 5834 11320 5834 11321 4636 11321 4661 11321 5834 11322 4661 11322 5837 11322 5837 11323 4661 11323 4660 11323 5837 11324 4660 11324 5838 11324 5838 11325 4660 11325 4609 11325 5838 11326 4609 11326 5794 11326 5794 11327 4609 11327 4603 11327 5794 11328 4603 11328 4602 11328 4600 11329 4482 11329 5839 11329 5839 11330 4482 11330 3755 11330 5839 11331 3755 11331 5840 11331 5840 11332 3755 11332 3754 11332 5840 11333 3754 11333 5793 11333 5793 11334 3754 11334 3752 11334 5793 11335 3752 11335 3750 11335 4604 11336 5795 11336 5796 11336 5796 11337 5795 11337 5798 11337 5796 11338 5798 11338 5797 11338 5797 11339 5798 11339 5799 11339 5797 11340 5799 11340 5802 11340 5802 11341 5799 11341 5800 11341 5802 11342 5800 11342 5801 11342 5801 11343 5800 11343 5803 11343 5801 11344 5803 11344 5818 11344 5818 11345 5803 11345 5804 11345 5818 11346 5804 11346 5819 11346 5819 11347 5804 11347 5805 11347 5819 11348 5805 11348 5820 11348 5820 11349 5805 11349 5806 11349 5820 11350 5806 11350 5821 11350 5821 11351 5806 11351 5807 11351 5821 11352 5807 11352 5822 11352 5822 11353 5807 11353 5808 11353 5822 11354 5808 11354 5823 11354 5823 11355 5808 11355 5809 11355 5823 11356 5809 11356 5824 11356 5824 11357 5809 11357 5811 11357 5824 11358 5811 11358 5825 11358 5825 11359 5811 11359 5810 11359 5825 11360 5810 11360 5826 11360 5826 11361 5810 11361 5812 11361 5826 11362 5812 11362 5827 11362 5827 11363 5812 11363 5813 11363 5827 11364 5813 11364 5828 11364 5828 11365 5813 11365 5814 11365 5828 11366 5814 11366 5829 11366 5829 11367 5814 11367 5815 11367 5829 11368 5815 11368 5830 11368 5830 11369 5815 11369 5816 11369 5830 11370 5816 11370 5831 11370 5831 11371 5816 11371 5817 11371 5831 11372 5817 11372 5832 11372 5832 11373 5817 11373 5835 11373 5832 11374 5835 11374 5833 11374 5833 11375 5835 11375 5834 11375 5833 11376 5834 11376 5836 11376 5836 11377 5834 11377 5837 11377 5836 11378 5837 11378 5793 11378 5793 11379 5837 11379 5838 11379 5793 11380 5838 11380 5840 11380 5840 11381 5838 11381 5794 11381 5840 11382 5794 11382 5839 11382 5839 11383 5794 11383 4601 11383 5839 11384 4601 11384 4600 11384 5059 11385 3041 11385 3040 11385 4125 11386 4083 11386 5061 11386 5061 11387 4083 11387 4108 11387 4125 11388 5061 11388 5060 11388 4125 11389 5060 11389 4119 11389 4119 11390 5060 11390 5059 11390 4119 11391 5059 11391 3040 11391 4517 11392 5841 11392 4560 11392 4560 11393 5841 11393 2807 11393 2807 11394 5841 11394 2777 11394 2777 11395 5841 11395 5842 11395 2777 11396 5842 11396 2781 11396 5841 11397 4517 11397 4515 11397 4515 11398 4559 11398 5841 11398 5841 11399 4559 11399 5843 11399 5841 11400 5843 11400 5844 11400 5845 11401 5846 11401 5847 11401 5847 11402 5846 11402 5841 11402 5847 11403 5841 11403 5848 11403 5848 11404 5841 11404 5844 11404 5842 11405 5841 11405 5846 11405 5842 11406 5846 11406 5849 11406 5849 11407 5846 11407 5845 11407 5849 11408 5845 11408 5850 11408 5850 11409 5845 11409 5847 11409 5850 11410 5847 11410 5851 11410 5851 11411 5847 11411 5848 11411 5851 11412 5848 11412 5852 11412 5852 11413 5848 11413 5844 11413 5852 11414 5844 11414 5853 11414 5853 11415 5844 11415 5843 11415 5853 11416 5843 11416 5854 11416 5854 11417 5843 11417 4559 11417 5854 11418 4559 11418 4558 11418 3282 11419 3280 11419 4556 11419 5609 11420 5606 11420 3312 11420 3282 11421 4556 11421 3284 11421 3284 11422 4556 11422 4557 11422 3284 11423 4557 11423 3286 11423 3286 11424 4557 11424 3288 11424 3288 11425 4557 11425 5109 11425 3288 11426 5109 11426 5612 11426 3276 11427 5851 11427 3278 11427 3278 11428 5851 11428 5852 11428 2986 11429 2984 11429 3312 11429 3312 11430 2984 11430 3004 11430 3312 11431 3004 11431 3003 11431 3003 11432 3002 11432 3312 11432 3312 11433 3002 11433 3000 11433 3312 11434 3000 11434 2989 11434 5612 11435 5609 11435 3288 11435 3288 11436 5609 11436 3312 11436 3288 11437 3312 11437 3273 11437 3273 11438 3312 11438 2989 11438 3273 11439 2989 11439 2991 11439 5850 11440 3370 11440 5849 11440 5849 11441 3370 11441 2832 11441 5849 11442 2832 11442 5842 11442 5842 11443 2832 11443 2782 11443 5842 11444 2782 11444 2781 11444 5850 11445 5851 11445 3370 11445 3370 11446 5851 11446 3276 11446 3370 11447 3276 11447 3365 11447 3365 11448 3276 11448 3274 11448 3365 11449 3274 11449 3366 11449 3366 11450 3274 11450 3268 11450 3366 11451 3268 11451 3361 11451 3361 11452 3268 11452 3267 11452 3361 11453 3267 11453 3362 11453 5852 11454 5853 11454 3278 11454 3278 11455 5853 11455 5854 11455 3278 11456 5854 11456 3280 11456 3280 11457 5854 11457 4558 11457 3280 11458 4558 11458 4556 11458 5757 11459 3406 11459 3405 11459 5757 11460 3405 11460 5756 11460 3405 11461 3403 11461 5756 11461 5756 11462 3403 11462 3402 11462 5756 11463 3402 11463 5755 11463 5755 11464 3402 11464 3400 11464 5755 11465 3400 11465 5754 11465 5754 11466 3400 11466 3304 11466 5754 11467 3304 11467 5753 11467 5753 11468 3304 11468 3303 11468 5562 11469 5551 11469 3303 11469 3303 11470 5551 11470 5065 11470 3406 11471 5757 11471 3407 11471 3407 11472 5757 11472 5758 11472 3407 11473 5758 11473 3394 11473 5556 11474 5549 11474 5555 11474 5555 11475 5549 11475 5562 11475 5555 11476 5562 11476 5553 11476 5553 11477 5562 11477 3303 11477 5549 11478 5548 11478 5557 11478 5759 11479 5760 11479 5067 11479 5067 11480 5760 11480 5749 11480 5067 11481 5749 11481 5066 11481 5066 11482 5749 11482 5750 11482 5066 11483 5750 11483 5065 11483 5065 11484 5750 11484 5751 11484 5065 11485 5751 11485 3303 11485 3303 11486 5751 11486 5752 11486 3303 11487 5752 11487 5753 11487 5069 11488 5264 11488 5265 11488 5563 11489 5562 11489 5561 11489 5561 11490 5562 11490 5549 11490 5561 11491 5549 11491 5559 11491 5559 11492 5549 11492 5557 11492 5277 11493 5269 11493 5069 11493 5264 11494 5069 11494 5266 11494 5266 11495 5069 11495 5269 11495 5266 11496 5269 11496 5268 11496 5067 11497 5069 11497 5759 11497 5759 11498 5069 11498 5265 11498 5759 11499 5265 11499 5758 11499 5758 11500 5265 11500 3395 11500 5758 11501 3395 11501 3394 11501 5277 11502 5069 11502 5278 11502 5278 11503 5069 11503 3033 11503 5278 11504 3033 11504 3032 11504 3032 11505 3037 11505 5278 11505 5278 11506 3037 11506 3039 11506 5278 11507 3039 11507 5280 11507 5773 11508 2844 11508 5458 11508 3432 11509 3433 11509 3548 11509 5773 11510 5458 11510 5774 11510 2844 11511 5773 11511 2845 11511 2845 11512 5773 11512 5772 11512 2845 11513 5772 11513 5763 11513 5458 11514 3432 11514 5774 11514 5774 11515 3432 11515 3548 11515 5774 11516 3548 11516 5775 11516 5775 11517 3548 11517 4599 11517 5775 11518 4599 11518 5776 11518 5776 11519 4599 11519 4597 11519 5776 11520 4597 11520 5777 11520 5777 11521 4597 11521 4596 11521 5777 11522 4596 11522 5778 11522 4596 11523 5263 11523 5778 11523 5778 11524 5263 11524 5254 11524 5778 11525 5254 11525 5253 11525 2841 11526 5780 11526 2804 11526 2804 11527 5780 11527 5779 11527 2804 11528 5779 11528 2805 11528 2805 11529 5779 11529 5778 11529 2805 11530 5778 11530 5260 11530 5260 11531 5778 11531 5253 11531 5260 11532 5253 11532 5259 11532 3013 11533 3017 11533 5788 11533 2965 11534 2964 11534 5782 11534 5782 11535 2964 11535 5781 11535 5788 11536 5789 11536 3013 11536 3013 11537 5789 11537 5790 11537 3013 11538 5790 11538 3014 11538 3014 11539 5790 11539 5791 11539 3014 11540 5791 11540 5792 11540 2965 11541 5782 11541 2966 11541 2966 11542 5782 11542 5783 11542 2966 11543 5783 11543 2943 11543 3415 11544 3414 11544 5339 11544 5708 11545 5709 11545 5462 11545 3015 11546 2858 11546 5346 11546 5346 11547 2858 11547 5345 11547 2946 11548 2947 11548 5785 11548 5785 11549 2947 11549 2854 11549 3017 11550 3010 11550 5788 11550 5788 11551 3010 11551 5331 11551 5788 11552 5331 11552 5787 11552 5787 11553 5331 11553 5329 11553 5787 11554 5329 11554 5318 11554 2857 11555 5347 11555 5855 11555 2858 11556 5856 11556 5351 11556 3015 11557 3014 11557 2858 11557 2858 11558 3014 11558 5792 11558 2858 11559 5792 11559 2960 11559 2960 11560 5792 11560 5781 11560 2960 11561 5781 11561 2962 11561 2962 11562 5781 11562 2964 11562 2936 11563 5784 11563 2948 11563 2948 11564 5784 11564 2949 11564 2946 11565 5785 11565 2944 11565 2944 11566 5785 11566 5786 11566 2944 11567 5786 11567 2883 11567 2857 11568 5855 11568 2858 11568 2858 11569 5855 11569 5348 11569 2858 11570 5348 11570 5856 11570 5343 11571 5345 11571 5341 11571 5341 11572 5345 11572 2858 11572 5341 11573 2858 11573 5383 11573 5383 11574 2858 11574 5351 11574 5383 11575 5351 11575 5384 11575 2936 11576 2938 11576 5784 11576 5784 11577 2938 11577 2940 11577 5784 11578 2940 11578 5783 11578 5783 11579 2940 11579 2941 11579 5783 11580 2941 11580 2943 11580 5318 11581 2879 11581 5787 11581 5787 11582 2879 11582 2881 11582 5787 11583 2881 11583 5786 11583 5786 11584 2881 11584 2882 11584 5786 11585 2882 11585 2883 11585 3415 11586 5339 11586 5462 11586 5462 11587 5339 11587 5337 11587 5462 11588 5337 11588 5708 11588 5708 11589 5337 11589 5704 11589 5708 11590 5704 11590 5706 11590 2854 11591 2853 11591 5785 11591 5785 11592 2853 11592 2952 11592 5785 11593 2952 11593 5784 11593 5784 11594 2952 11594 2951 11594 5784 11595 2951 11595 2949 11595 5705 11596 5704 11596 3007 11596 3007 11597 5704 11597 5337 11597 3007 11598 5337 11598 3018 11598 3018 11599 5337 11599 5335 11599 3018 11600 5335 11600 3010 11600 3010 11601 5335 11601 5333 11601 3010 11602 5333 11602 5331 11602 5316 11603 3447 11603 3449 11603 3512 11604 3452 11604 2852 11604 2852 11605 3452 11605 3451 11605 3512 11606 2852 11606 3513 11606 3513 11607 2852 11607 5857 11607 3513 11608 5857 11608 3449 11608 3449 11609 5857 11609 5321 11609 3449 11610 5321 11610 5316 11610 4817 11611 4819 11611 4821 11611 3451 11612 4270 11612 4272 11612 5220 11613 5221 11613 5222 11613 4526 11614 4821 11614 4823 11614 4270 11615 3451 11615 4268 11615 4268 11616 3451 11616 4526 11616 4268 11617 4526 11617 4828 11617 4272 11618 2848 11618 3451 11618 3451 11619 2848 11619 2850 11619 3451 11620 2850 11620 2852 11620 4828 11621 4526 11621 4826 11621 4826 11622 4526 11622 4823 11622 4826 11623 4823 11623 4824 11623 5220 11624 5222 11624 4821 11624 4821 11625 5222 11625 5223 11625 4821 11626 5223 11626 4817 11626 5219 11627 5220 11627 5218 11627 5218 11628 5220 11628 4821 11628 5218 11629 4821 11629 5217 11629 5217 11630 4821 11630 4526 11630 2741 11631 2740 11631 2847 11631 2741 11632 2847 11632 5858 11632 5858 11633 2847 11633 2846 11633 5858 11634 2846 11634 5859 11634 5859 11635 2846 11635 2845 11635 5859 11636 2845 11636 5763 11636 5860 11637 5766 11637 5765 11637 2837 11638 2736 11638 2750 11638 2839 11639 2837 11639 5861 11639 5764 11640 5768 11640 5862 11640 5862 11641 5768 11641 5769 11641 5862 11642 5769 11642 5863 11642 5863 11643 5769 11643 5771 11643 5863 11644 5771 11644 5864 11644 5864 11645 5771 11645 5770 11645 5864 11646 5770 11646 5865 11646 5865 11647 5770 11647 2841 11647 5865 11648 2841 11648 2839 11648 5764 11649 5862 11649 5765 11649 5765 11650 5862 11650 5866 11650 5765 11651 5866 11651 5860 11651 2837 11652 2750 11652 5861 11652 5861 11653 2750 11653 2749 11653 5861 11654 2749 11654 5867 11654 5867 11655 2749 11655 2748 11655 5867 11656 2748 11656 5868 11656 5868 11657 2748 11657 2745 11657 5868 11658 2745 11658 5869 11658 5869 11659 2745 11659 2743 11659 5869 11660 2743 11660 5870 11660 5870 11661 2743 11661 2742 11661 5870 11662 2742 11662 5871 11662 5871 11663 2742 11663 2747 11663 5871 11664 2747 11664 5872 11664 5872 11665 2747 11665 2746 11665 5872 11666 2746 11666 5873 11666 5873 11667 2746 11667 2741 11667 5873 11668 2741 11668 5858 11668 2839 11669 5861 11669 5865 11669 5865 11670 5861 11670 5867 11670 5865 11671 5867 11671 5864 11671 5864 11672 5867 11672 5868 11672 5864 11673 5868 11673 5863 11673 5863 11674 5868 11674 5869 11674 5863 11675 5869 11675 5862 11675 5862 11676 5869 11676 5870 11676 5862 11677 5870 11677 5866 11677 5866 11678 5870 11678 5871 11678 5866 11679 5871 11679 5860 11679 5860 11680 5871 11680 5872 11680 5860 11681 5872 11681 5874 11681 5874 11682 5872 11682 5873 11682 5874 11683 5873 11683 5875 11683 5875 11684 5873 11684 5858 11684 5875 11685 5858 11685 5859 11685 5766 11686 5860 11686 5767 11686 5767 11687 5860 11687 5874 11687 5767 11688 5874 11688 5761 11688 5761 11689 5874 11689 5875 11689 5761 11690 5875 11690 5762 11690 5762 11691 5875 11691 5859 11691 5762 11692 5859 11692 5763 11692 3718 11693 2916 11693 2915 11693 2915 11694 2919 11694 3718 11694 3718 11695 2919 11695 2918 11695 3718 11696 2918 11696 2924 11696 2924 11697 2923 11697 3718 11697 3718 11698 2923 11698 2921 11698 3718 11699 2921 11699 2920 11699 2920 11700 2925 11700 3718 11700 3718 11701 2925 11701 2927 11701 3718 11702 2927 11702 2928 11702 3718 11703 2934 11703 2932 11703 2928 11704 2930 11704 3718 11704 3718 11705 2930 11705 2935 11705 3718 11706 2935 11706 2934 11706 2932 11707 2931 11707 3718 11707 3718 11708 2931 11708 2872 11708 3718 11709 2872 11709 2867 11709 5322 11710 5321 11710 5857 11710 2852 11711 3774 11711 5857 11711 5857 11712 3774 11712 3773 11712 5857 11713 3773 11713 5322 11713 5322 11714 3773 11714 3744 11714 5322 11715 3744 11715 5323 11715 5323 11716 3744 11716 3743 11716 5323 11717 3743 11717 5324 11717 5324 11718 3743 11718 5325 11718 5325 11719 3743 11719 3742 11719 5325 11720 3742 11720 5326 11720 5326 11721 3742 11721 3741 11721 5326 11722 3741 11722 5327 11722 5327 11723 3741 11723 3739 11723 5327 11724 3739 11724 3718 11724 3718 11725 2867 11725 5327 11725 5327 11726 2867 11726 2866 11726 5327 11727 2866 11727 2863 11727 2863 11728 2862 11728 5327 11728 5327 11729 2862 11729 2870 11729 5327 11730 2870 11730 2869 11730 2840 11731 2804 11731 2803 11731 2840 11732 2803 11732 2838 11732 2784 11733 2782 11733 2829 11733 2819 11734 2772 11734 2821 11734 2821 11735 2772 11735 2774 11735 2821 11736 2774 11736 2823 11736 2823 11737 2774 11737 2738 11737 2823 11738 2738 11738 2803 11738 2803 11739 2738 11739 2737 11739 2803 11740 2737 11740 2838 11740 2829 11741 2827 11741 2784 11741 2784 11742 2827 11742 2766 11742 2784 11743 2766 11743 2815 11743 2815 11744 2766 11744 2763 11744 2815 11745 2763 11745 2817 11745 2817 11746 2763 11746 2753 11746 2817 11747 2753 11747 2819 11747 2819 11748 2753 11748 2770 11748 2819 11749 2770 11749 2772 11749

+
+
+ 1 +
+
+ + + + 7.481132 -6.50764 5.343665 + 0 0 1 46.69194 + 0 1 0 0.619768 + 1 0 0 63.5593 + 1 1 1 + + + + 4.076245 1.005454 5.903862 + 0 0 1 106.9363 + 0 1 0 3.163707 + 1 0 0 37.26105 + 1 1 1 + + + + 0 0 0 + 0 0 1 0 + 0 1 0 0 + 1 0 0 0 + 1 1 1 + + + + + + + + + + + + + +
diff --git a/URDFs/sr_description/meshes/components/th_distal/bt_sp/th_distal_bt_sp.dae b/URDFs/sr_description/meshes/components/th_distal/bt_sp/th_distal_bt_sp.dae new file mode 100644 index 0000000..dbefd7b --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_distal/bt_sp/th_distal_bt_sp.dae @@ -0,0 +1,127 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:44:55 + 2022-02-10T09:44:55 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.248 0.68 0.336 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + -6.060435 -6.856817 31.4934 -5.711478 -7.339299 31.33972 -5.503378 -6.999103 31.9875 -5.704554 -6.533328 32.27236 5.524855 -7.517418 31.32837 5.883785 -7.295039 31.18238 5.606808 -6.960788 31.91362 5.323178 -7.038086 32.12879 5.141249 9.27064 30.68693 5.021369 9.384977 30.71047 4.736316 9.302928 31.1447 4.765616 9.233773 31.17805 -4.68266 9.470544 30.9911 -4.94293 9.40548 30.7807 -4.66054 9.313883 31.21692 -4.367012 9.337342 31.49118 6.750377 9.233852 3.909479 6.558131 9.373147 3.927115 6.799475 9.220414 3.934083 6.954756 9.1039 3.926733 -4.303078 9.255423 31.64091 -4.689707 9.248438 31.24872 -6.385512 9.478571 3.924832 -6.6998 9.284896 3.93156 -6.718735 9.284199 3.9799 -6.314303 9.537569 3.977654 -6.731563 9.285437 4.183974 -6.306759 9.553166 4.182718 -6.739906 9.28357 4.914243 -6.311681 9.554842 4.914996 -6.742816 9.283186 6.455601 -6.327002 9.546943 6.456711 -6.751899 9.277586 8.280357 -6.348101 9.534426 8.281122 -6.761276 9.271725 10.15406 -6.369988 9.521289 10.15443 -6.770511 9.265894 12.03288 -6.391217 9.508524 12.0329 -6.776362 9.262539 13.91238 -6.408235 9.498295 13.91187 -6.778128 9.261603 15.79193 -6.414769 9.494248 15.79115 -6.776904 9.26258 17.67136 -6.415832 9.493455 17.67059 -6.771028 9.266652 19.55076 -6.414196 9.494379 19.5501 -6.742671 9.286296 21.43042 -6.40435 9.500905 21.42973 -6.676483 9.331378 23.30037 -6.378015 9.518431 23.30487 -6.642361 9.352777 25.08858 -6.361455 9.526451 25.13548 -6.549948 9.394906 26.62115 -6.289268 9.552003 26.7748 -6.300712 9.47741 27.81159 -6.047638 9.626173 27.99989 -5.964613 9.535658 28.75745 -5.717599 9.68045 28.92291 -5.620296 9.552657 29.51515 -5.43753 9.63414 29.66615 -5.286105 9.493172 30.19323 -5.081292 9.542825 30.38816 6.81094 9.224295 3.982075 7.017493 9.073184 3.982571 6.824099 9.224535 4.186451 7.063918 9.048597 4.198202 6.844911 9.212211 4.918256 7.139003 8.991884 4.942547 6.857423 9.202834 6.455361 7.19087 8.948807 6.460245 6.858919 9.201727 8.279129 7.198411 8.941544 8.276617 6.838202 9.218855 10.15522 7.145939 8.983865 10.15495 6.83562 9.22151 12.03505 7.136717 8.991766 12.03596 6.842121 9.216856 13.91444 7.151994 8.97988 13.91552 6.850221 9.210886 15.79369 7.172531 8.963418 15.7953 6.857894 9.205209 17.6728 7.19258 8.947052 17.67385 6.864271 9.200396 19.55161 7.210043 8.932291 19.54995 6.866117 9.198728 21.42956 7.220966 8.922877 21.42692 6.854619 9.206467 23.29183 7.208854 8.932738 23.27615 6.799426 9.242305 25.06573 7.118436 8.998433 25.00074 6.635129 9.334664 26.57119 6.89242 9.14126 26.42045 6.366415 9.43164 27.76198 6.603698 9.256963 27.57267 6.03769 9.484859 28.72926 6.259784 9.320762 28.57652 5.697114 9.512063 29.4637 5.884479 9.358422 29.3689 5.361867 9.469305 30.12243 5.503316 9.337018 30.08352 3.749603 -7.424206 11.55571 4.077221 -7.231091 11.65466 4.260175 -7.459904 11.91996 3.897033 -7.658255 11.78406 4.545593 -7.662565 12.26144 4.213366 -7.868176 12.13844 4.793221 -7.94671 12.66757 4.488952 -8.177495 12.57163 5.083398 -8.233886 13.16888 4.828902 -8.450116 13.08866 5.46455 -8.449138 13.78286 5.146514 -8.681735 13.6358 5.824744 -8.66168 14.48332 5.48113 -8.947785 14.34182 6.152833 -8.93076 15.35683 5.831051 -9.212912 15.21687 6.51089 -9.150228 16.44121 6.165135 -9.467136 16.27707 6.837463 -9.296822 17.6081 6.48176 -9.641902 17.45741 7.101021 -9.372904 18.83326 6.732831 -9.75522 18.73304 7.281778 -9.395663 20.11477 6.893732 -9.80738 20.05179 7.341123 -9.408266 21.48665 6.930207 -9.845931 21.47352 7.337947 -9.343779 22.85009 6.948084 -9.759576 22.84906 7.300043 -9.173483 24.24869 6.916235 -9.583485 24.20072 7.134812 -9.00104 25.58896 6.727378 -9.421181 25.54651 6.940062 -8.73482 26.90303 6.567935 -9.087926 26.92912 6.704822 -8.411899 28.14903 6.354243 -8.696352 28.25126 6.477396 -8.021765 29.27015 6.095755 -8.307425 29.40707 6.240911 -7.617094 30.27334 5.846453 -7.892374 30.41996 -3.949305 -6.948033 11.42598 -3.847673 -7.430893 11.62265 -4.08022 -7.566821 11.85373 -4.232842 -7.068882 11.67919 -4.330923 -7.750264 12.15145 -4.532977 -7.26377 12.01197 -4.681352 -8.021135 12.62689 -4.908977 -7.550643 12.51351 -4.999553 -8.269129 13.11616 -5.250555 -7.787579 13.00795 -5.388664 -8.495829 13.74605 -5.651011 -8.028944 13.64843 -5.753113 -8.748989 14.48695 -6.042797 -8.268347 14.38664 -6.080098 -9.007992 15.33759 -6.390366 -8.522477 15.22585 -6.400611 -9.254341 16.37347 -6.738542 -8.743311 16.24704 -6.692044 -9.424533 17.48431 -7.088567 -8.905496 17.45565 -6.946936 -9.514085 18.70269 -7.369572 -8.991461 18.70913 -7.096784 -9.591299 20.04969 -7.518794 -9.083984 20.03461 -7.175243 -9.588524 21.46561 -7.622692 -9.063779 21.45008 -7.173246 -9.522822 22.84685 -7.64643 -8.970566 22.90173 -7.099807 -9.392274 24.20629 -7.546189 -8.866636 24.30336 -7.006599 -9.139177 25.57784 -7.405223 -8.63924 25.74836 -6.798972 -8.87808 26.91007 -7.188802 -8.381674 27.08946 -6.573568 -8.500967 28.21663 -6.977148 -7.97314 28.41318 -6.271628 -8.102908 29.4575 -6.699022 -7.564638 29.61185 -5.962 -7.726691 30.4981 -6.362336 -7.220314 30.6332 -5.626229 -8.057197 30.4595 -5.377816 -7.595303 31.38595 -5.257939 -8.280042 30.55054 -4.96476 -7.807878 31.51725 -4.759257 -8.482901 30.76508 -4.468254 -7.982592 31.74434 -4.228487 -8.696809 30.92024 -3.987173 -8.134613 31.91568 -3.631875 -8.908684 31.07432 -3.403933 -8.333392 32.05255 -3.035992 -9.022884 31.28757 -2.864526 -8.457611 32.19528 -2.370163 -9.150816 31.43827 -2.208694 -8.552146 32.36504 -1.675074 -9.274518 31.51088 -1.571371 -8.645359 32.44947 -0.9770766 -9.363148 31.54907 -0.8807256 -8.724827 32.49065 -0.1776664 -9.407164 31.56822 -0.1751362 -8.753647 32.51439 0.5260174 -9.392108 31.5677 0.5244051 -8.725648 32.53054 1.233691 -9.33414 31.54219 1.169325 -8.679126 32.49885 1.951025 -9.222032 31.49579 1.841551 -8.573896 32.46263 2.584576 -9.102884 31.40617 2.441622 -8.487917 32.35141 3.277636 -8.965802 31.22285 3.083619 -8.39519 32.15956 3.837598 -8.838376 31.02613 3.629708 -8.267247 31.99288 4.450076 -8.611638 30.86321 4.217117 -8.090127 31.81078 4.909886 -8.426653 30.70701 4.641833 -7.966743 31.62063 5.44266 -8.161755 30.51791 5.161127 -7.719622 31.44491 -5.922182 -8.420825 29.47254 -5.504665 -8.692241 29.57959 -5.004065 -8.962285 29.72413 -4.469413 -9.215924 29.85128 -3.852311 -9.45678 29.99881 -3.230098 -9.601648 30.20973 -2.518278 -9.771692 30.34497 -1.792638 -9.916419 30.40983 -1.067398 -10.0136 30.45307 -0.1946105 -10.0651 30.47465 0.5459882 -10.05255 30.47047 1.301693 -9.988884 30.44301 2.088224 -9.864732 30.38123 2.762183 -9.728714 30.28088 3.493125 -9.564295 30.08978 4.091719 -9.378118 29.92663 4.699988 -9.112798 29.8018 5.179019 -8.869595 29.68307 5.68568 -8.577409 29.53788 -6.206572 -8.800704 28.29833 -5.763026 -9.090302 28.45622 -5.271738 -9.390965 28.56379 -4.715665 -9.680194 28.69727 -4.090606 -9.963999 28.79792 -3.439785 -10.18602 28.93202 -2.654447 -10.40279 29.05695 -1.916047 -10.56632 29.10955 -1.141184 -10.66878 29.17457 -0.22301 -10.72178 29.20584 0.5722249 -10.70934 29.20125 1.367441 -10.64314 29.16343 2.239068 -10.507 29.07335 2.961461 -10.33426 28.99036 3.6761 -10.11631 28.88573 4.335073 -9.8656 28.74961 4.902833 -9.58819 28.66248 5.453766 -9.284112 28.53203 5.911303 -8.99273 28.42298 -6.460076 -9.176863 26.95447 -6.032281 -9.462993 27.13698 -5.538931 -9.797393 27.21187 -4.954394 -10.10921 27.38918 -4.309488 -10.4335 27.46215 -3.60815 -10.71054 27.5745 -2.792693 -10.94182 27.72366 -2.031463 -11.1254 27.76532 -1.204057 -11.22877 27.86397 -0.2479608 -11.27983 27.91232 0.6056495 -11.26562 27.9086 1.44957 -11.19806 27.85396 2.372051 -11.06513 27.71375 3.141909 -10.86459 27.62895 3.858198 -10.60668 27.57467 4.555209 -10.33013 27.41103 5.113368 -10.0247 27.36529 5.686669 -9.69481 27.22179 6.131393 -9.388463 27.1328 -6.610185 -9.522871 25.5801 -6.165732 -9.854371 25.72014 -5.688848 -10.19436 25.77252 -5.092608 -10.51907 25.97756 -4.466899 -10.82867 26.10047 -3.752847 -11.12714 26.21248 -2.935192 -11.38598 26.31975 -2.129062 -11.59006 26.36351 -1.243186 -11.7317 26.4004 -0.2631477 -11.79592 26.42281 0.6425597 -11.77634 26.4281 1.534845 -11.6829 26.42331 2.4748 -11.51654 26.34607 3.274352 -11.29579 26.2585 3.990195 -11.04029 26.16188 4.703576 -10.74709 25.97467 5.295461 -10.40058 25.94256 5.876072 -10.03558 25.84623 6.304944 -9.731409 25.75247 -6.694352 -9.776134 24.2787 -6.261057 -10.13363 24.3248 -5.810696 -10.46997 24.34234 -5.216545 -10.83033 24.47393 -4.597815 -11.15625 24.58744 -3.851558 -11.48792 24.68562 -3.048969 -11.76974 24.72889 -2.205911 -11.99895 24.74683 -1.263079 -12.17793 24.70861 -0.270954 -12.25321 24.70399 0.6734079 -12.22598 24.72925 1.598912 -12.10479 24.79871 2.534402 -11.91223 24.79174 3.381247 -11.66375 24.70516 4.129431 -11.37475 24.63835 4.847391 -11.04472 24.51119 5.452314 -10.68582 24.44542 6.014451 -10.30588 24.40356 6.493284 -9.93175 24.3553 -6.792602 -9.90361 22.9016 -6.361912 -10.27776 22.90245 -5.886337 -10.65298 22.86478 -5.312183 -11.03426 22.90762 -4.694159 -11.38377 22.98573 -3.942538 -11.73966 23.03973 -3.137412 -12.05304 22.98201 -2.252753 -12.30532 22.99181 -1.267729 -12.48651 23.00297 -0.2739073 -12.56081 23.01508 0.6964336 -12.53487 23.02447 1.642034 -12.4147 23.05548 2.560793 -12.2139 23.07003 3.430502 -11.95024 22.9856 4.210034 -11.62381 23.00664 4.908216 -11.27318 22.95012 5.52113 -10.89764 22.90565 6.060873 -10.50964 22.94495 6.542917 -10.11907 22.91895 -6.789415 -9.993399 21.53753 -6.376781 -10.36397 21.47562 -5.899906 -10.7384 21.40203 -5.333585 -11.13463 21.36536 -4.708672 -11.50247 21.37662 -3.996325 -11.85545 21.39201 -3.172154 -12.18579 21.29852 -2.25401 -12.45445 21.30941 -1.272392 -12.63397 21.34485 -0.2806056 -12.70872 21.35889 0.7078781 -12.68421 21.35511 1.671396 -12.56498 21.34332 2.58225 -12.3619 21.31903 3.436035 -12.09029 21.28229 4.234721 -11.74763 21.36199 4.937636 -11.37589 21.34417 5.526081 -11.00463 21.34226 6.076259 -10.59899 21.40651 6.515899 -10.23719 21.44607 -6.720375 -9.998596 20.15435 -6.304619 -10.37445 20.08012 -5.832485 -10.7341 19.92121 -5.275341 -11.12668 19.85908 -4.665362 -11.49105 19.7819 -3.960477 -11.84682 19.75641 -3.124152 -12.17712 19.65587 -2.218849 -12.44419 19.66357 -1.268685 -12.62063 19.69036 -0.2912805 -12.69301 19.67402 0.6995638 -12.66972 19.66744 1.676512 -12.55031 19.67207 2.585072 -12.34113 19.64123 3.417214 -12.06605 19.63214 4.196251 -11.73443 19.73802 4.906607 -11.35541 19.78021 5.497475 -10.97392 19.84054 6.031188 -10.5799 19.91675 6.46628 -10.21912 20.01859 -6.586903 -9.904167 18.743 -6.183593 -10.26215 18.65373 -5.684423 -10.62465 18.42245 -5.150616 -10.98949 18.31148 -4.545005 -11.35088 18.21466 -3.829967 -11.70696 18.16101 -3.021081 -12.01292 18.04612 -2.163337 -12.26486 18.03686 -1.251978 -12.43559 18.02966 -0.3045237 -12.49642 17.93719 0.668219 -12.47566 17.93148 1.648071 -12.36725 18.0133 2.549417 -12.16002 18.02486 3.362485 -11.88814 18.05147 4.104046 -11.57675 18.17466 4.778047 -11.22963 18.29357 5.364381 -10.85153 18.35747 5.878281 -10.48486 18.4961 6.322704 -10.13534 18.65581 -6.361082 -9.76213 17.43888 -5.947524 -10.09625 17.2812 -5.479129 -10.40982 17.03981 -4.936967 -10.75467 16.87541 -4.336106 -11.10705 16.78603 -3.661682 -11.42328 16.67822 -2.90053 -11.68827 16.52712 -2.081872 -11.91748 16.47871 -1.200132 -12.08378 16.45837 -0.2699958 -12.14013 16.36144 0.6719799 -12.11918 16.3578 1.596492 -12.02538 16.4608 2.460276 -11.83936 16.52767 3.248316 -11.58375 16.60262 3.955826 -11.28719 16.70177 4.5884 -10.97503 16.84113 5.126604 -10.64407 16.92695 5.633206 -10.29555 17.07454 6.082817 -9.967422 17.27439 -6.058223 -9.577259 16.27136 -5.652917 -9.85828 16.05291 -5.185106 -10.14457 15.81293 -4.654511 -10.4476 15.61417 -4.100564 -10.74593 15.49127 -3.483314 -11.02509 15.38468 -2.7622 -11.25228 15.21374 -1.973335 -11.43976 15.09032 -1.130887 -11.59829 15.067 -0.242916 -11.67349 15.04357 0.6431178 -11.65771 15.04703 1.478995 -11.5697 15.10778 2.281965 -11.42019 15.21309 3.02524 -11.18534 15.28586 3.731843 -10.91968 15.42498 4.371718 -10.63335 15.6051 4.901624 -10.34638 15.75935 5.357028 -10.04889 15.89165 5.797178 -9.742889 16.07833 -5.72416 -9.312242 15.19914 -5.312787 -9.569172 14.97143 -4.855438 -9.819863 14.73987 -4.367606 -10.06934 14.54551 -3.851017 -10.33208 14.42917 -3.238978 -10.57051 14.28391 -2.55037 -10.7578 14.10038 -1.822231 -10.91294 13.96812 -1.037533 -11.04392 13.92904 -0.2163228 -11.11756 13.9296 0.590916 -11.1084 13.94041 1.344337 -11.03956 13.99373 2.099847 -10.9097 14.09644 2.80126 -10.70527 14.17404 3.463075 -10.49154 14.33308 4.05022 -10.24991 14.50616 4.591775 -9.99263 14.69694 5.064603 -9.734713 14.88414 5.479724 -9.482069 15.07733 -5.399287 -9.035826 14.34399 -4.995461 -9.257701 14.1189 -4.549493 -9.47027 13.89091 -4.05661 -9.685389 13.6846 -3.52758 -9.889636 13.50999 -2.932779 -10.0705 13.33112 -2.294945 -10.22866 13.17412 -1.632155 -10.38386 13.09624 -0.9044914 -10.46554 13.01856 -0.1757426 -10.51009 13.00001 0.5394815 -10.50467 13.01917 1.239335 -10.46493 13.09459 1.941266 -10.34736 13.17559 2.607653 -10.18694 13.28374 3.22618 -10.0198 13.44706 3.723095 -9.799408 13.54825 4.213345 -9.595162 13.72561 4.68296 -9.383247 13.93365 5.110942 -9.167108 14.14895 -5.046815 -8.75241 13.60673 -4.658829 -8.927417 13.38642 -4.216177 -9.116374 13.17323 -3.763204 -9.263669 12.95977 -3.257062 -9.412467 12.76667 -2.686259 -9.572569 12.60333 -2.111968 -9.715744 12.481 -1.507804 -9.853975 12.42121 -0.8468968 -9.919054 12.34257 -0.1988877 -9.938707 12.30395 0.4556118 -9.923764 12.30636 1.116571 -9.880013 12.35744 1.740066 -9.801761 12.43905 2.331552 -9.685078 12.5461 2.915084 -9.577123 12.72727 3.388182 -9.383573 12.81527 3.882088 -9.21535 12.99732 4.354801 -9.030529 13.20412 4.772593 -8.863752 13.42656 -4.677338 -8.487903 12.98157 -4.321357 -8.595034 12.76402 -3.888265 -8.755472 12.56812 -3.459962 -8.862591 12.36603 -2.971328 -8.981701 12.1845 -2.416957 -9.144406 12.0566 -1.906765 -9.279029 11.97557 -1.365811 -9.360114 11.89664 -0.776319 -9.439207 11.85307 -0.2022624 -9.433592 11.79966 0.4051054 -9.413806 11.79518 1.018497 -9.388008 11.84729 1.57214 -9.326349 11.91604 2.13694 -9.233107 12.0185 2.650608 -9.120422 12.14454 3.099179 -8.970499 12.24419 3.599305 -8.872786 12.47003 4.087193 -8.706972 12.67913 4.496952 -8.573863 12.89371 -4.355754 -8.268849 12.52555 -4.035225 -8.361186 12.34424 -3.632555 -8.477203 12.15957 -3.204858 -8.565999 11.96892 -2.734334 -8.662035 11.79948 -2.219153 -8.760755 11.66033 -1.707152 -8.832037 11.54881 -1.184866 -8.872396 11.45445 -0.6525828 -8.969264 11.44436 -0.1155122 -9.002118 11.43319 0.4302762 -8.979058 11.42909 0.9498187 -8.92146 11.44718 1.453423 -8.878127 11.51483 1.948346 -8.822195 11.61185 2.406033 -8.693531 11.68393 2.833455 -8.599486 11.8021 3.303112 -8.504286 11.98605 3.747081 -8.397445 12.182 4.136501 -8.310042 12.38837 -4.027917 -7.990183 12.07916 -3.776849 -8.084342 11.96754 -3.411072 -8.185404 11.81264 -2.999343 -8.256795 11.63949 -2.535436 -8.355858 11.4941 -2.059785 -8.416158 11.35741 -1.577049 -8.43441 11.22951 -1.070095 -8.467466 11.14209 -0.5982222 -8.556933 11.13799 -0.1014066 -8.59593 11.13806 0.4140221 -8.58814 11.14194 0.8716416 -8.504308 11.13174 1.297767 -8.439827 11.16403 1.718267 -8.411863 11.25036 2.161014 -8.345225 11.34621 2.608882 -8.274932 11.47245 3.055281 -8.202909 11.6325 3.463856 -8.131512 11.81006 3.855576 -8.02672 11.98714 -3.80153 -7.721088 11.75488 -3.550281 -7.78589 11.64071 -3.185051 -7.890507 11.50487 -2.779535 -7.973155 11.35809 -2.356137 -8.028412 11.21795 -1.922828 -8.040047 11.07987 -1.459001 -8.064724 10.97117 -0.9888056 -8.123933 10.91368 -0.5589607 -8.184664 10.89754 -0.1233734 -8.189414 10.87942 0.3641832 -8.218008 10.90406 0.7979204 -8.160264 10.90651 1.207062 -8.123971 10.94668 1.580803 -8.067998 10.99643 1.979847 -8.014266 11.07996 2.407212 -7.981816 11.20997 2.843919 -7.934176 11.36262 3.229135 -7.840428 11.49738 3.588819 -7.751559 11.6448 -3.663806 -7.491449 11.53973 -3.387262 -7.521087 11.40216 -3.018051 -7.581218 11.25126 -2.615397 -7.663262 11.1188 -2.196384 -7.721882 10.99295 -1.781706 -7.723334 10.86482 -1.365109 -7.753639 10.77969 -0.9777077 -7.808016 10.73995 -0.563639 -7.843229 10.70959 -0.1659691 -7.878031 10.70456 0.2701901 -7.886942 10.71372 0.672305 -7.822978 10.71033 1.123377 -7.785036 10.75181 1.50356 -7.761912 10.81175 1.84805 -7.709488 10.87427 2.271649 -7.67137 10.99383 2.735851 -7.626093 11.14719 3.072761 -7.555547 11.26029 3.415955 -7.502146 11.40725 5.197456 9.524806 30.26716 4.809911 9.444361 30.88436 4.950769 9.564962 30.51388 4.532124 9.506029 31.1027 4.532083 9.66627 30.83311 4.13492 9.603761 31.36098 4.039535 9.785856 31.15426 3.644969 9.709327 31.65027 3.652363 9.883639 31.3307 3.262124 9.789504 31.83542 3.220282 9.953066 31.52163 2.875189 9.829595 32.02388 2.677558 10.02455 31.70573 2.424017 9.875535 32.17551 2.166524 10.03231 31.92983 1.969688 9.885705 32.32686 1.565624 10.04986 31.99808 1.424988 9.880923 32.41432 0.7107496 10.05683 32.00879 0.6715171 9.876206 32.44403 -0.3324651 10.05782 32.00857 -0.3170577 9.877185 32.44384 -1.303903 10.05285 32.00395 -1.224963 9.880597 32.42453 -1.94898 10.03232 31.97654 -1.813925 9.872407 32.38386 -2.459617 10.02817 31.81455 -2.272697 9.878569 32.23633 -2.948973 9.983366 31.63779 -2.720086 9.842116 32.0954 -3.395849 9.924839 31.43995 -3.064928 9.804986 31.94777 -3.841734 9.839443 31.22965 -3.452059 9.748904 31.7476 -4.344911 9.71595 30.94505 -3.912256 9.654673 31.49378 -4.753837 9.60559 30.68303 -4.348913 9.550853 31.23212 5.517459 9.610746 29.57972 5.332977 9.655487 29.77741 5.022681 9.718097 30.05833 4.494542 9.816035 30.49622 4.041337 9.925153 30.74599 3.486472 10.0338 31.01971 2.956009 10.11596 31.17018 2.38178 10.13942 31.3837 1.688504 10.15891 31.47139 0.7445032 10.16564 31.4902 -0.3330886 10.16658 31.49061 -1.335051 10.1641 31.47669 -2.053439 10.15178 31.41562 -2.701522 10.12859 31.2514 -3.2602 10.07102 31.06486 -3.848081 9.973217 30.78746 -4.353382 9.86094 30.53663 -4.931309 9.740263 30.1219 -5.240416 9.675644 29.86709 5.812243 9.641545 28.81964 5.609531 9.734734 28.99501 5.401121 9.806333 29.15147 5.122561 9.86682 29.34613 4.720378 9.944521 29.57921 3.930556 10.06272 30.07878 3.225134 10.16014 30.23407 2.43579 10.20641 30.43277 1.693018 10.22427 30.50516 0.7446989 10.22845 30.51737 -0.3369572 10.22893 30.51645 -1.36572 10.22761 30.49942 -2.185679 10.21887 30.41453 -3.001768 10.18565 30.20161 -3.742641 10.1006 30.02898 -4.612666 9.967868 29.58285 -5.050481 9.883671 29.37027 -5.355345 9.81387 29.19918 -5.533877 9.759643 29.06919 6.138761 9.580973 27.93454 5.897151 9.70366 28.11987 5.599365 9.842317 28.24867 5.361591 9.928753 28.2781 5.064696 10.0062 28.26467 4.528094 10.09015 28.34246 3.696507 10.17799 28.30535 2.456147 10.22733 28.67556 1.599048 10.24316 28.85732 0.7090799 10.24634 28.896 -0.3325627 10.24662 28.89587 -1.338621 10.24528 28.85455 -2.247587 10.23704 28.65025 -3.469754 10.20454 28.19978 -4.334615 10.12658 28.20145 -4.957722 10.03084 28.2088 -5.252819 9.961328 28.24868 -5.532311 9.865493 28.2542 -5.778843 9.761568 28.15128 6.370746 9.509299 26.75024 6.130596 9.639935 26.85434 5.769877 9.809453 26.90785 5.406268 9.943609 26.91061 4.982026 10.06923 26.8805 4.512402 10.15237 26.85219 3.812737 10.21398 26.77547 2.80437 10.24125 26.9139 1.812537 10.24832 27.02553 0.7658915 10.24953 27.05805 -0.3454772 10.24962 27.05998 -1.44118 10.24913 27.0359 -2.485455 10.24566 26.9301 -3.590786 10.22948 26.72968 -4.313834 10.18221 26.7776 -4.816732 10.1091 26.84834 -5.165118 10.01679 26.88778 -5.659954 9.842937 26.90078 -5.995816 9.70606 26.86091 6.47328 9.462787 25.12947 6.215061 9.610653 25.15618 5.837322 9.788205 25.17051 5.415077 9.941576 25.17341 4.923252 10.08891 25.16245 4.437403 10.176 25.15061 3.774604 10.22879 25.12249 2.937785 10.24617 25.14668 1.906143 10.24951 25.17763 0.7899746 10.24994 25.18732 -0.351362 10.24996 25.18801 -1.487673 10.24976 25.1819 -2.589965 10.24798 25.15615 -3.598253 10.2374 25.11343 -4.268934 10.20005 25.13383 -4.749927 10.13219 25.1533 -5.137004 10.02768 25.16051 -5.709475 9.828093 25.16213 -6.064319 9.685499 25.15602 6.511173 9.440889 23.30422 6.238665 9.600079 23.30721 5.860359 9.77813 23.31272 5.419673 9.937524 23.31606 4.91218 10.09097 23.31057 4.417077 10.17962 23.30809 3.754235 10.23156 23.30147 2.960694 10.24707 23.3033 1.9235 10.24969 23.30816 0.7941573 10.24998 23.30967 -0.3524922 10.24999 23.30979 -1.496877 10.24981 23.30894 -2.612748 10.24812 23.3055 -3.602941 10.23748 23.30148 -4.278046 10.19976 23.30853 -4.745857 10.13441 23.30779 -5.136883 10.02817 23.30574 -5.719736 9.825489 23.30415 -6.075217 9.682265 23.3057 6.528331 9.429673 21.43209 6.246071 9.595911 21.4312 5.871913 9.771817 21.43546 5.419109 9.935157 21.43853 4.911015 10.09029 21.43391 4.414512 10.17921 21.43311 3.75034 10.23164 21.43058 2.963003 10.24713 21.42992 1.925407 10.24971 21.43032 0.7946642 10.24998 21.43057 -0.3526927 10.24998 21.43065 -1.498163 10.24979 21.43049 -2.617109 10.24788 21.43048 -3.611644 10.23608 21.43214 -4.301953 10.19596 21.43698 -4.754225 10.13323 21.43249 -5.139141 10.02813 21.42888 -5.721877 9.825562 21.42672 -6.080704 9.679222 21.42893 6.532141 9.426572 19.55338 6.243861 9.596659 19.55207 5.872258 9.769828 19.55577 5.395663 9.941056 19.55762 4.903172 10.09221 19.55404 4.414031 10.17872 19.5539 3.750106 10.23139 19.5519 2.963247 10.24709 19.55112 1.925944 10.2497 19.55144 0.7958536 10.24997 19.55304 -0.3535411 10.24997 19.55388 -1.499347 10.24976 19.55201 -2.619258 10.2476 19.5516 -3.621058 10.23453 19.55383 -4.327058 10.19182 19.5587 -4.763678 10.13176 19.55326 -5.141088 10.02826 19.54949 -5.722603 9.826253 19.54732 -6.082438 9.678446 19.54953 6.529291 9.427539 17.67407 6.234991 9.600522 17.67249 5.854123 9.774714 17.67487 5.329032 9.962807 17.67396 4.879427 10.10034 17.67297 4.415025 10.17883 17.67428 3.751625 10.23103 17.67253 2.964156 10.24701 17.6723 1.929781 10.24968 17.67645 0.8054564 10.24991 17.69046 -0.3603534 10.24989 17.6974 -1.507589 10.2497 17.68123 -2.622924 10.24735 17.67379 -3.628619 10.23316 17.67471 -4.345556 10.18825 17.67951 -4.770953 10.13046 17.67363 -5.142607 10.02845 17.66991 -5.723073 9.827075 17.66784 -6.082751 9.678628 17.67005 6.525258 9.429377 15.79467 6.22896 9.603626 15.79308 5.853837 9.773777 15.79502 5.307132 9.970064 15.79292 4.878417 10.10193 15.79307 4.432034 10.17612 15.7952 3.758781 10.22988 15.79359 2.969204 10.24678 15.79667 1.950759 10.24957 15.8211 0.8520026 10.24961 15.89342 -0.392674 10.2495 15.92783 -1.548177 10.24954 15.84697 -2.634929 10.24726 15.80371 -3.625496 10.23289 15.79608 -4.330509 10.18764 15.79929 -4.765843 10.13026 15.79446 -5.141971 10.02883 15.79063 -5.723234 9.827968 15.78839 -6.082405 9.679211 15.79058 6.521088 9.431352 13.91532 6.224298 9.606296 13.91378 5.861984 9.770024 13.91569 5.308392 9.969649 13.91324 4.888154 10.10038 13.91375 4.45689 10.17208 13.91645 3.769213 10.22837 13.91528 2.98071 10.24648 13.92531 1.998628 10.24934 13.98605 0.9477736 10.24897 14.1505 -0.4537072 10.24869 14.22736 -1.628717 10.24926 14.05026 -2.656857 10.24761 13.94382 -3.597806 10.23511 13.91795 -4.247673 10.19325 13.91615 -4.733415 10.13251 13.91379 -5.136002 10.0297 13.911 -5.722435 9.829114 13.90893 -6.080051 9.680958 13.91118 6.517166 9.43313 12.0359 6.219885 9.608874 12.03448 5.871684 9.765747 12.03645 5.314376 9.967658 12.03386 4.899944 10.09825 12.03454 4.48333 10.16776 12.03755 3.778313 10.22678 12.03431 2.976963 10.24623 12.03015 1.973325 10.24945 12.01754 0.9018932 10.24943 11.99174 -0.3991178 10.24927 11.99005 -1.555345 10.24952 12.02399 -2.628652 10.2478 12.03263 -3.580745 10.23589 12.03362 -4.213773 10.19534 12.03464 -4.722842 10.13304 12.03364 -5.134554 10.03024 12.0314 -5.721455 9.830658 12.02948 -6.073669 9.685101 12.0319 6.514833 9.433629 10.15668 6.215659 9.611308 10.15553 5.881552 9.761404 10.15759 5.3209 9.965481 10.15487 4.911839 10.09606 10.1557 4.509585 10.16344 10.15915 3.78728 10.2252 10.15566 2.971992 10.24596 10.15233 1.938963 10.24954 10.14239 0.8264493 10.24983 10.11597 -0.3637627 10.2498 10.10727 -1.509839 10.24973 10.13957 -2.614288 10.24784 10.15176 -3.576776 10.23586 10.1541 -4.209354 10.19506 10.1551 -4.726772 10.13198 10.1542 -5.136504 10.03033 10.15217 -5.720716 9.832271 10.15035 -6.065879 9.690098 10.15301 6.516113 9.431231 8.282351 6.211879 9.613375 8.281705 5.891412 9.757036 8.283862 5.327265 9.9633 8.281023 4.922523 10.09399 8.281918 4.532225 10.1595 8.285624 3.7956 10.22373 8.282011 2.971649 10.24569 8.279928 1.928302 10.24953 8.277645 0.79997 10.24993 8.27157 -0.3543028 10.24994 8.269275 -1.499089 10.24976 8.276803 -2.611428 10.24779 8.279513 -3.576801 10.23561 8.28027 -4.212203 10.19407 8.281091 -4.736245 10.13006 8.280219 -5.140122 10.03012 8.278202 -5.720218 9.833838 8.27641 -6.057895 9.695201 8.279284 6.513191 9.432197 6.457534 6.207679 9.615655 6.456896 5.900773 9.752707 6.458934 5.332291 9.96115 6.455964 4.926331 10.09252 6.456523 4.536379 10.15743 6.459632 3.797291 10.22282 6.456553 2.971752 10.24536 6.454968 1.926627 10.24932 6.454451 0.7952307 10.24974 6.453672 -0.3527624 10.24976 6.453364 -1.497634 10.24956 6.454324 -2.611152 10.24755 6.454693 -3.577403 10.23515 6.455097 -4.216042 10.19279 6.455906 -4.746732 10.12779 6.455155 -5.144028 10.02968 6.453213 -5.719748 9.835207 6.451572 -6.050127 9.700014 6.454569 6.508928 9.433545 4.916153 6.20371 9.616856 4.914882 5.907925 9.748228 4.915997 5.333308 9.958629 4.912987 4.913943 10.09185 4.912258 4.501449 10.15872 4.913053 3.783292 10.22251 4.911867 2.96905 10.24414 4.911324 1.926151 10.24791 4.911214 0.7946813 10.24831 4.911145 -0.3525934 10.24833 4.911118 -1.497499 10.24812 4.911203 -2.611124 10.24609 4.911285 -3.577792 10.23351 4.911615 -4.219227 10.19049 4.912387 -4.755482 10.12471 4.91204 -5.147134 10.02823 4.910791 -5.7191 9.835361 4.909915 -6.043912 9.702784 4.912806 6.504039 9.432389 4.183855 6.200681 9.613817 4.181548 5.910334 9.742017 4.18016 5.333727 9.952685 4.17748 4.908514 10.08651 4.175739 4.48619 10.15406 4.174863 3.777516 10.2169 4.17404 2.968012 10.23807 4.173735 1.926028 10.24175 4.173676 0.7946345 10.24214 4.173665 -0.352577 10.24216 4.173665 -1.497459 10.24195 4.173674 -2.610965 10.23992 4.173711 -3.577557 10.22728 4.173933 -4.220403 10.18407 4.174624 -4.759014 10.11814 4.175326 -5.148245 10.02264 4.176203 -5.717968 9.831029 4.177496 -6.041429 9.699292 4.180201 6.507503 9.419697 3.979277 6.203715 9.600376 3.975528 5.912773 9.728539 3.971804 5.340778 9.936406 3.967789 4.909837 10.07107 3.96445 4.485291 10.13852 3.96213 3.776802 10.20093 3.960772 2.967798 10.22193 3.960319 1.925992 10.22557 3.960232 0.7946286 10.22596 3.960221 -0.3525757 10.22597 3.960221 -1.497454 10.22577 3.960225 -2.611 10.22373 3.960267 -3.578176 10.21109 3.960537 -4.223201 10.1679 3.961545 -4.761772 10.10225 3.963411 -5.155011 10.0063 3.966294 -5.719375 9.817809 3.970015 -6.044704 9.685503 3.97396 6.248672 9.55675 3.920828 5.943402 9.69406 3.912577 5.395359 9.889516 3.901741 4.937326 10.0296 3.892398 4.503285 10.0982 3.885109 3.782606 10.16038 3.881199 2.968774 10.18135 3.880076 1.926087 10.185 3.879884 0.7946338 10.18538 3.87986 -0.3525821 10.1854 3.87986 -1.497559 10.18519 3.87987 -2.612082 10.18309 3.879954 -3.584867 10.17017 3.880589 -4.243821 10.12659 3.883266 -4.783786 10.06111 3.889119 -5.206539 9.959496 3.898028 -5.749541 9.783239 3.909664 -6.089789 9.642333 3.91838 4.497148 9.322045 31.37865 4.434332 9.244003 31.52366 4.205833 9.357832 31.61718 4.132216 9.266599 31.78671 3.837931 9.421615 31.86361 3.778086 9.302422 32.05364 3.379393 9.528442 32.09624 3.370236 9.361475 32.30098 2.999817 9.639484 32.23074 3.01539 9.440694 32.45407 2.618983 9.683638 32.40597 2.575726 9.518414 32.61921 2.271259 9.698877 32.53665 2.199719 9.528762 32.77223 1.819164 9.698905 32.66734 1.79488 9.504847 32.91667 1.278741 9.677324 32.77537 1.262969 9.484271 33.02537 0.6266969 9.66687 32.81324 0.6140107 9.475255 33.06134 -0.2892789 9.665149 32.8167 -0.2847542 9.472434 33.06689 -1.11194 9.670541 32.79306 -1.066343 9.475134 33.05092 -1.676955 9.687118 32.71384 -1.564307 9.498147 32.97099 -2.138151 9.678895 32.6043 -2.025362 9.504014 32.85263 -2.518941 9.674699 32.46619 -2.48009 9.505494 32.67564 -2.841429 9.637367 32.3338 -2.880164 9.433611 32.54372 -3.205434 9.566693 32.17791 -3.210877 9.379272 32.3964 -3.654136 9.457156 31.97256 -3.616896 9.32016 32.16392 -4.073369 9.380944 31.71361 -4.019996 9.278562 31.87709 -6.871703 9.16194 3.922897 -6.631104 9.308598 3.905319 -6.264963 9.514623 3.888523 -5.872105 9.678047 3.855884 -5.365966 9.815587 3.8052 -4.855057 9.923167 3.766065 -4.307976 9.9818 3.740267 -3.607233 10.02315 3.728725 -2.616097 10.0361 3.725989 -1.498 10.03829 3.72561 -0.3526116 10.03851 3.725575 0.7946806 10.0385 3.725579 1.926647 10.03812 3.725665 2.973016 10.03464 3.726451 3.802421 10.01506 3.731233 4.557024 9.957777 3.748404 5.037544 9.890902 3.780832 5.565135 9.750403 3.820604 6.061729 9.594289 3.865641 6.421786 9.429569 3.895089 -5.213908 -7.0969 32.16844 -4.778684 -7.301459 32.32328 -4.294083 -7.487196 32.51292 -3.816165 -7.580624 32.73932 -3.273166 -7.725639 32.90215 -2.738868 -7.883853 32.98905 -2.134377 -7.990716 33.11085 -1.494065 -8.086663 33.18618 -0.8781348 -8.153284 33.226 -0.1380861 -8.170487 33.2656 0.5299795 -8.117165 33.31204 1.144565 -8.083889 33.26922 1.785233 -7.972769 33.24706 2.340598 -7.92034 33.11901 2.951711 -7.830028 32.9497 3.50181 -7.698101 32.79891 4.075457 -7.564325 32.5858 4.481979 -7.448852 32.40942 4.96091 -7.213448 32.26541 3.489688 -6.964821 11.17217 3.908641 -6.73617 11.27633 3.967818 -5.690404 10.74104 4.591396 -5.011586 10.69669 5.130288 -3.178105 9.923955 5.679021 -2.417079 9.780158 5.896538 -1.608061 9.423958 6.160833 -1.324071 9.390853 6.141508 -1.156158 9.28928 6.303969 -1.048392 9.300935 6.292114 -0.9889044 9.269687 6.424798 -0.9013532 9.286279 6.456678 -0.7832643 9.254414 6.563175 -0.6941749 9.269809 6.628588 -0.2371394 9.075638 6.709757 -0.1495463 9.092195 6.783499 1.755569 8.016875 6.837752 1.810284 8.050639 6.865924 6.453672 5.15051 6.902468 6.420884 5.233725 6.891753 8.205541 4.063254 6.937798 8.195343 4.116381 6.902314 8.537422 3.856273 6.975253 8.554911 3.899326 6.918481 8.606597 3.823908 7.018229 8.63811 3.874277 6.9651 8.673828 3.827107 7.094153 8.714678 3.89079 7.013721 8.772754 3.839452 7.138646 8.785964 3.901025 6.97651 8.885603 3.823263 7.129052 8.854166 3.895356 6.908302 8.974142 3.806905 7.087948 8.923613 3.885205 6.830883 9.065443 3.817389 7.035029 8.992608 3.884134 6.666296 9.232606 3.859258 6.936987 9.088419 3.895703 3.073343 -7.152128 11.06543 3.320727 -6.412683 10.81957 4.179699 -4.746725 10.33449 5.465706 -2.251698 9.587088 5.951195 -1.328 9.311028 6.117831 -1.095758 9.258531 6.28472 -0.9090771 9.237658 6.47372 -0.3872149 9.058128 6.67069 1.621922 7.999139 6.790776 6.418036 5.124757 6.809199 8.203084 4.032971 6.781344 8.541879 3.81049 6.75091 8.611503 3.75723 6.739884 8.669156 3.733467 6.70946 8.773861 3.710586 6.588304 8.945696 3.660171 6.461265 9.063796 3.62571 6.362382 9.181203 3.65262 6.220597 9.397729 3.76467 2.688408 -7.284898 10.96317 2.829454 -6.711166 10.75936 3.497829 -5.433558 10.40458 5.043315 -2.631505 9.631821 5.715932 -1.459521 9.314084 5.913366 -1.183549 9.247753 6.048613 -1.035533 9.220623 6.210781 -0.5709084 9.03502 6.413289 1.426203 7.963316 6.546968 6.373629 5.055917 6.523935 8.227462 3.934959 6.410198 8.59056 3.676287 6.292819 8.673422 3.587517 6.224524 8.734258 3.539438 6.153347 8.840091 3.499291 6.030584 9.029001 3.4505 5.925361 9.147454 3.431046 5.839057 9.262001 3.473201 5.724124 9.488559 3.629663 2.25828 -7.341584 10.82982 2.388935 -6.831307 10.65184 2.937684 -5.804156 10.37797 4.404584 -3.298117 9.739353 5.361353 -1.724068 9.355451 5.641824 -1.274086 9.248023 5.721685 -1.132784 9.20748 5.796938 -0.7244367 9.007168 5.908744 1.260899 7.89014 5.927335 6.379838 4.877686 5.836783 8.305797 3.712227 5.70005 8.679238 3.448079 5.572755 8.759685 3.361729 5.50053 8.817739 3.31494 5.462656 8.917976 3.28664 5.417025 9.100571 3.267823 5.34332 9.214962 3.267374 5.259175 9.329604 3.32087 5.158584 9.569848 3.509776 1.837103 -7.372967 10.71198 1.912973 -6.976829 10.56661 2.180302 -6.448405 10.42716 3.113984 -4.880513 10.059 4.513816 -2.449905 9.50313 5.056352 -1.449047 9.275346 5.165824 -1.192942 9.204198 5.188209 -0.7917849 8.989253 5.187131 1.192155 7.824946 5.09256 6.417333 4.701959 4.984349 8.38042 3.507198 4.879477 8.75143 3.256792 4.784001 8.823283 3.188462 4.717153 8.877429 3.148524 4.690512 8.975892 3.125798 4.682717 9.156145 3.120382 4.64513 9.267287 3.132297 4.609599 9.37463 3.19832 4.585343 9.608206 3.412084 1.460745 -7.389551 10.62758 1.49908 -7.038397 10.48978 1.644888 -6.725594 10.41002 2.221784 -5.706338 10.19741 3.39166 -3.271343 9.659324 4.029873 -1.709751 9.323769 4.187263 -1.243479 9.210067 4.207698 -0.8100211 8.982374 4.191989 1.181454 7.789425 4.125175 6.449256 4.59748 4.067142 8.423466 3.389066 4.017537 8.789772 3.151521 3.97173 8.854763 3.098986 3.93338 8.904767 3.068532 3.90889 9.002563 3.048597 3.892662 9.183968 3.044444 3.864382 9.294935 3.06087 3.837131 9.401882 3.13276 3.816385 9.640625 3.35986 1.057637 -7.389522 10.55362 1.077724 -7.070711 10.42234 1.129743 -6.89683 10.37059 1.34171 -6.437595 10.27821 1.945294 -4.849477 9.947548 2.751843 -2.315844 9.438614 3.035781 -1.357405 9.231358 3.085485 -0.8243123 8.982604 3.085439 1.181417 7.777247 3.066894 6.462445 4.55866 3.051916 8.43924 3.345355 3.039532 8.803589 3.112657 3.02795 8.866004 3.066246 3.017513 8.914134 3.040345 3.009555 9.011366 3.022366 3.003232 9.193099 3.019012 2.994247 9.303841 3.037806 2.985292 9.410797 3.112538 2.977657 9.651983 3.344645 0.6287657 -7.42255 10.51336 0.6730046 -7.096138 10.3797 0.7031245 -6.954579 10.33259 0.7736204 -6.682728 10.2781 1.057542 -5.460215 10.04031 1.67165 -2.535322 9.474085 1.900099 -1.3947 9.237362 1.940962 -0.8281282 8.982803 1.944545 1.181738 7.774731 1.941845 6.46547 4.550039 1.939612 8.442706 3.33568 1.937777 8.806628 3.104017 1.936043 8.868497 3.058918 1.934424 8.916188 3.034095 1.93308 9.013238 3.016714 1.931933 9.194982 3.013708 1.930418 9.305608 3.033203 1.928878 9.412497 3.108731 1.927478 9.654078 3.341988 0.2678188 -7.484251 10.5195 0.3158441 -7.120856 10.37322 0.3382737 -6.968619 10.32118 0.3598872 -6.725256 10.27186 0.4532091 -5.574398 10.05317 0.6926574 -2.572677 9.478707 0.7799074 -1.400324 9.238039 0.7949426 -0.8286156 8.982812 0.7964138 1.181805 7.774404 0.7962208 6.465901 4.548825 0.7960118 8.443187 3.334329 0.7958355 8.807049 3.102808 0.7956672 8.868846 3.057884 0.7955065 8.916477 3.033215 0.7953665 9.013496 3.015933 0.7952427 9.195235 3.012997 0.7950853 9.305836 3.032606 0.7949234 9.412704 3.108261 0.79477 9.654318 3.341684 -0.2031546 -7.486951 10.51917 -0.2907731 -7.122528 10.37352 -0.3260288 -6.96902 10.3211 -0.3340752 -6.725419 10.27158 -0.3414832 -5.574432 10.05301 -0.3515272 -2.57268 9.478664 -0.3530916 -1.400324 9.238033 -0.3529126 -0.8286148 8.982809 -0.3527967 1.181813 7.774379 -0.352646 6.465936 4.54873 -0.3526035 8.443224 3.334221 -0.3526074 8.807083 3.102712 -0.3526189 8.868873 3.057805 -0.3526299 8.916498 3.033151 -0.3526396 9.013512 3.015878 -0.3526464 9.19525 3.012949 -0.3526466 9.305851 3.032571 -0.3526435 9.412716 3.108235 -0.3526343 9.654328 3.341667 -0.5867908 -7.431223 10.51434 -0.6578257 -7.098248 10.37955 -0.6902753 -6.955384 10.33161 -0.7384325 -6.684308 10.27621 -0.9350852 -5.460652 10.0394 -1.327427 -2.535382 9.47387 -1.472919 -1.394707 9.237328 -1.499044 -0.8281201 8.98276 -1.501384 1.181826 7.774442 -1.499922 6.465845 4.54899 -1.499259 8.443124 3.334503 -1.499143 8.806985 3.10299 -1.499137 8.86878 3.05808 -1.499128 8.916405 3.033423 -1.499112 9.013422 3.016149 -1.499067 9.195155 3.013215 -1.498909 9.305754 3.032819 -1.498696 9.412609 3.10845 -1.498404 9.654167 3.341801 -1.008215 -7.400808 10.55151 -1.060564 -7.073954 10.42107 -1.10083 -6.902049 10.36757 -1.251893 -6.453171 10.27223 -1.763608 -4.854297 9.944865 -2.389412 -2.316598 9.438027 -2.606741 -1.357514 9.231245 -2.644943 -0.8242937 8.982274 -2.645442 1.181943 7.775172 -2.634315 6.464904 4.551716 -2.628934 8.442058 3.337504 -2.627775 8.805958 3.105927 -2.627593 8.867787 3.060977 -2.627335 8.91545 3.03626 -2.626987 9.012476 3.018921 -2.626368 9.194187 3.015888 -2.624748 9.304781 3.03529 -2.622609 9.411555 3.110566 -2.619813 9.65267 3.343168 -1.40678 -7.386898 10.6151 -1.472317 -7.044035 10.48625 -1.563539 -6.765009 10.40931 -1.968724 -5.824603 10.20283 -3.053059 -3.311355 9.659614 -3.62111 -1.716699 9.323345 -3.759748 -1.244693 9.209745 -3.779097 -0.810573 8.980813 -3.765536 1.182544 7.780542 -3.718122 6.458806 4.569748 -3.691183 8.43486 3.357658 -3.683812 8.799014 3.125609 -3.681676 8.861134 3.080222 -3.678504 8.909135 3.054846 -3.674567 9.006361 3.03676 -3.669067 9.188053 3.032789 -3.658164 9.298748 3.050708 -3.644465 9.405261 3.123748 -3.627929 9.644287 3.352253 -1.808538 -7.380878 10.70832 -1.877678 -7.014356 10.57298 -2.016133 -6.663677 10.47524 -2.626529 -5.474989 10.19577 -4.080924 -2.669033 9.552067 -4.662828 -1.491239 9.282868 -4.795123 -1.201658 9.20394 -4.824142 -0.7985076 8.985114 -4.802534 1.186465 7.804428 -4.704926 6.435809 4.641685 -4.630465 8.405645 3.438822 -4.602082 8.770836 3.204206 -4.588051 8.834577 3.15587 -4.566374 8.884596 3.126121 -4.540681 8.9834 3.103071 -4.510984 9.165863 3.093669 -4.466614 9.277802 3.104931 -4.416403 9.385457 3.170478 -4.365413 9.620865 3.387935 -2.220654 -7.372236 10.83142 -2.310078 -6.945803 10.67702 -2.558443 -6.397048 10.51946 -3.421237 -4.816698 10.11039 -4.811819 -2.327658 9.498806 -5.340088 -1.403641 9.27231 -5.508392 -1.167226 9.206958 -5.597927 -0.7581309 8.998915 -5.645454 1.224196 7.859896 -5.603994 6.395487 4.796332 -5.509122 8.341808 3.614693 -5.445795 8.708646 3.37194 -5.395488 8.777467 3.312925 -5.317802 8.83417 3.268023 -5.229791 8.938985 3.228234 -5.145146 9.125285 3.203249 -5.04992 9.242237 3.199631 -4.962021 9.358416 3.254799 -4.907176 9.597894 3.463362 -2.636747 -7.30153 10.95108 -2.785331 -6.752552 10.76154 -3.319102 -5.656445 10.44134 -4.626884 -3.234844 9.770277 -5.503138 -1.686595 9.363492 -5.772034 -1.24704 9.252329 -5.905435 -1.091502 9.214283 -6.052828 -0.6545011 9.022446 -6.238914 1.347972 7.936196 -6.335633 6.371489 4.990173 -6.277536 8.259501 3.845251 -6.195712 8.621644 3.597602 -6.114199 8.696378 3.526221 -5.997152 8.761659 3.464106 -5.872196 8.873483 3.4063 -5.774176 9.060838 3.369678 -5.669089 9.178733 3.355665 -5.570458 9.296798 3.397287 -5.505463 9.527808 3.580542 -3.049175 -7.162765 11.06078 -3.281423 -6.435309 10.81351 -4.041868 -4.808978 10.30621 -5.285563 -2.39395 9.595683 -5.87098 -1.38145 9.314033 -6.046936 -1.131978 9.254753 -6.159608 -0.9904202 9.22785 -6.333711 -0.5065147 9.045105 -6.566482 1.519388 7.985099 -6.710495 6.392035 5.102272 -6.72447 8.208168 4.00248 -6.702385 8.550582 3.781316 -6.663453 8.620794 3.725208 -6.575793 8.68737 3.670524 -6.463766 8.798798 3.613212 -6.377063 8.97746 3.576985 -6.292996 9.091613 3.564911 -6.17116 9.218551 3.591549 -6.049627 9.452611 3.732095 -3.463025 -7.00126 11.17827 -3.903878 -5.792065 10.76475 -5.053997 -3.225198 9.914263 -5.819841 -1.648548 9.417554 -6.104284 -1.175539 9.285487 -6.241708 -1.024688 9.264208 -6.355778 -0.8686992 9.244319 -6.527087 -0.3464818 9.064707 -6.725219 1.673197 8.009332 -6.83723 6.42834 5.144221 -6.867321 8.200321 4.055218 -6.876209 8.534006 3.846562 -6.88634 8.604121 3.811061 -6.891716 8.668394 3.795776 -6.880172 8.758322 3.780958 -6.868381 8.895797 3.776031 -6.807605 8.995992 3.766591 -6.675996 9.109459 3.766608 -6.508746 9.306822 3.836569 -3.764822 -6.944072 11.31191 -4.256503 -5.549222 10.81782 -5.502648 -2.614773 9.797807 -6.062416 -1.386479 9.380672 -6.258405 -1.071698 9.291972 -6.381093 -0.9321753 9.27921 -6.517524 -0.7307118 9.263136 -6.67195 -0.1867269 9.086059 -6.815532 1.783741 8.045806 -6.887602 6.410355 5.228791 -6.916162 8.185583 4.106677 -6.943274 8.539677 3.884817 -6.998317 8.630767 3.864398 -7.06968 8.709366 3.877934 -7.096063 8.777625 3.879363 -7.09334 8.858768 3.876964 -7.045666 8.938575 3.866573 -6.962574 9.022878 3.862446 -6.836677 9.149098 3.885544 -4.449071 -5.528951 10.9218 -5.722301 -2.55086 9.889149 -6.240205 -1.36114 9.463226 -6.384007 -1.03608 9.339507 -6.511224 -0.847731 9.310461 -6.648951 -0.6063427 9.289097 -6.774658 -0.08031594 9.128055 -6.870508 1.725643 8.202257 -6.926966 6.066209 5.66122 -6.973211 8.014131 4.371354 -7.030661 8.509515 4.024228 -7.11273 8.655145 3.96657 -7.165242 8.730259 3.954099 -7.179623 8.785109 3.940129 -7.174461 8.840535 3.929512 -7.145258 8.900513 3.922169 -7.088079 8.970199 3.91393 -7.006904 9.052042 3.915934 -4.886309 -6.78337 32.81226 -5.294224 -6.589145 32.64414 -5.056309 -6.186297 33.25558 -5.489483 -5.979411 33.04673 -5.26721 -5.569194 33.61104 -5.689762 -5.397609 33.35669 -5.471477 -4.88794 33.94961 -5.893852 -4.731438 33.65639 -5.682377 -4.125351 34.25271 -6.074635 -3.996368 33.94598 -5.852719 -3.303526 34.5307 -6.246477 -3.217896 34.17589 -6.003562 -2.441638 34.73628 -6.382769 -2.364026 34.37287 -6.062964 -1.4772 34.94893 -6.431635 -1.441143 34.57153 -6.111955 -0.5503095 35.03668 -6.462513 -0.5467504 34.65899 -6.09157 0.332523 35.06132 -6.430099 0.3185831 34.68914 -5.992948 1.183489 35.05386 -6.341573 1.113288 34.68626 -5.84258 1.846334 35.04317 -6.238578 1.718161 34.65454 -5.665834 2.155257 35.08771 -6.049253 2.017504 34.74212 -5.403027 2.59107 34.99124 -5.775441 2.440108 34.70169 -4.993057 3.958555 34.27094 -5.337728 3.80876 34.0484 -4.48061 6.632079 32.93817 -4.807913 6.540043 32.68376 -4.244097 8.207445 32.28502 -4.556382 8.150603 32.02513 -4.14184 8.769534 32.08414 -4.450778 8.719491 31.83043 -4.056433 9.135785 31.94436 -4.345328 9.10731 31.70074 -4.396307 -6.996857 32.98591 -4.598978 -6.396502 33.42908 -4.802011 -5.74465 33.85168 -5.011806 -5.060191 34.21706 -5.197453 -4.288689 34.57654 -5.391015 -3.435491 34.87976 -5.565573 -2.538739 35.10487 -5.641755 -1.541531 35.32687 -5.701624 -0.5592283 35.42185 -5.707772 0.3972331 35.42503 -5.606742 1.301878 35.40285 -5.418169 1.989104 35.40209 -5.203856 2.342557 35.41816 -4.925665 2.909769 35.18216 -4.492814 4.425396 34.35614 -4.024821 6.851688 33.17972 -3.817746 8.298546 32.58487 -3.721229 8.856378 32.37554 -3.646139 9.182284 32.24462 -3.919136 -7.088554 33.22799 -4.099427 -6.560276 33.63493 -4.295516 -5.912404 34.08018 -4.499448 -5.212207 34.48944 -4.690543 -4.436921 34.878 -4.876641 -3.6263 35.19281 -5.033212 -2.694891 35.47578 -5.125518 -1.628522 35.72488 -5.182004 -0.5296687 35.85402 -5.193388 0.5128099 35.85394 -5.086657 1.466532 35.815 -4.910243 2.160421 35.76811 -4.687822 2.61257 35.66081 -4.318417 3.547481 35.14462 -3.86051 5.430891 34.0731 -3.532113 7.275538 33.24591 -3.377573 8.429567 32.82202 -3.284486 8.959996 32.62759 -3.235888 9.233222 32.50313 -3.349739 -7.198724 33.45431 -3.536109 -6.667256 33.87913 -3.732763 -6.041539 34.3275 -3.923661 -5.387702 34.73242 -4.136398 -4.606381 35.13695 -4.309979 -3.759291 35.50847 -4.45648 -2.804086 35.83639 -4.571011 -1.719144 36.09762 -4.639247 -0.573368 36.24464 -4.64254 0.5315633 36.25757 -4.531353 1.567591 36.20557 -4.383055 2.293166 36.10757 -4.155304 2.793801 35.93715 -3.783482 3.855685 35.28973 -3.334362 5.877691 34.11204 -3.091521 7.47122 33.40636 -2.96795 8.499679 33.03706 -2.8847 9.033461 32.83274 -2.890581 9.267937 32.68879 -2.822894 -7.374728 33.53178 -2.958149 -6.838342 34.01105 -3.092655 -6.216302 34.51165 -3.280804 -5.523521 34.97556 -3.461391 -4.740592 35.42448 -3.637987 -3.854353 35.84122 -3.789902 -2.894481 36.19204 -3.922238 -1.812329 36.46251 -3.99468 -0.62593 36.63015 -3.99142 0.5486726 36.66077 -3.924972 1.626592 36.56969 -3.770031 2.417 36.43028 -3.560863 2.963913 36.18676 -3.216341 4.015151 35.52305 -2.814553 6.033225 34.31556 -2.61233 7.552068 33.62353 -2.524466 8.517632 33.25739 -2.50084 9.044812 33.02042 -2.507811 9.300572 32.8496 -2.182049 -7.476708 33.67872 -2.283637 -6.964534 34.16246 -2.440299 -6.348526 34.66787 -2.606863 -5.656821 35.16509 -2.724268 -4.886718 35.65449 -2.881737 -3.959776 36.12831 -3.019392 -2.978869 36.51969 -3.145633 -1.885451 36.81578 -3.193293 -0.6404764 37.01687 -3.190104 0.5973986 37.05387 -3.161464 1.705802 36.92758 -3.00954 2.573165 36.71855 -2.796901 3.205862 36.36896 -2.521745 4.175827 35.73785 -2.212402 6.134139 34.53452 -2.07632 7.613927 33.8292 -2.034625 8.53323 33.45407 -2.034566 9.039225 33.20719 -2.02116 9.317183 33.0245 -1.541593 -7.541728 33.79278 -1.6414 -6.981719 34.33584 -1.756513 -6.363763 34.86732 -1.841482 -5.698891 35.37915 -1.924837 -4.957376 35.87083 -2.061365 -4.059 36.35317 -2.171557 -3.05724 36.78332 -2.278958 -1.943221 37.11172 -2.312037 -0.6761121 37.33208 -2.301448 0.6293094 37.37547 -2.284862 1.788555 37.23211 -2.191708 2.694584 36.96603 -2.026662 3.3705 36.53699 -1.829281 4.295123 35.89693 -1.593515 6.208164 34.70103 -1.507075 7.675192 33.98583 -1.494274 8.569823 33.6039 -1.495592 9.035717 33.36394 -1.53599 9.294699 33.17209 -0.9187194 -7.604842 33.84448 -0.9509483 -7.036819 34.41757 -0.9798619 -6.43083 34.96517 -1.009016 -5.77829 35.4872 -1.079367 -5.029307 35.99604 -1.179675 -4.105851 36.51747 -1.264736 -3.101801 36.96706 -1.323475 -1.957382 37.32858 -1.350419 -0.6844536 37.5598 -1.347179 0.6333244 37.60371 -1.31966 1.847505 37.45539 -1.29495 2.780864 37.14774 -1.168414 3.484759 36.66556 -1.043931 4.394368 35.99942 -0.9059072 6.265192 34.81557 -0.8838863 7.697648 34.10668 -0.9109503 8.52663 33.74003 -0.9211207 8.977808 33.49373 -1.016214 9.26039 33.26913 -0.1449308 -7.638699 33.87298 -0.1550835 -7.077343 34.44558 -0.1678006 -6.47586 34.99485 -0.1834295 -5.82545 35.52026 -0.2153744 -5.072381 36.04179 -0.2554709 -4.118824 36.59489 -0.2922344 -3.068367 37.07443 -0.3121677 -1.915463 37.4434 -0.3260616 -0.6370117 37.67415 -0.3348905 0.6651294 37.71502 -0.3430894 1.877606 37.56129 -0.3610529 2.820364 37.23559 -0.2694262 3.537376 36.72368 -0.2194231 4.445413 36.04182 -0.212512 6.29729 34.86672 -0.2265183 7.698643 34.17091 -0.2521685 8.486091 33.81412 -0.2516307 8.932777 33.56003 -0.2778542 9.219862 33.3293 0.4953023 -7.611068 33.88882 0.5029339 -7.063899 34.44305 0.5419853 -6.46691 34.98329 0.5940015 -5.812269 35.50653 0.6409085 -5.052239 36.03066 0.667092 -4.100914 36.58355 0.6816868 -3.06204 37.05727 0.7037181 -1.931428 37.41424 0.708201 -0.6242648 37.64596 0.6919463 0.6937624 37.68778 0.661561 1.90241 37.53602 0.6189922 2.823332 37.22112 0.599494 3.525482 36.71286 0.5456374 4.433837 36.03268 0.4630314 6.293571 34.85541 0.4408956 7.694809 34.16158 0.4561176 8.487196 33.80442 0.529743 8.939712 33.54559 0.5805743 9.229479 33.31605 1.135031 -7.568547 33.85332 1.16828 -7.022162 34.39953 1.242864 -6.438656 34.91534 1.351159 -5.770954 35.43155 1.468137 -4.981725 35.95811 1.550361 -4.051868 36.48393 1.620172 -3.036939 36.92821 1.686947 -1.894447 37.27602 1.709321 -0.6098245 37.49673 1.690195 0.6851252 37.53424 1.634606 1.866688 37.39421 1.555268 2.765139 37.10576 1.438434 3.445226 36.64519 1.30398 4.364666 35.97974 1.149362 6.255475 34.78464 1.0929 7.68303 34.08121 1.090401 8.521057 33.71496 1.170096 8.99132 33.44993 1.234991 9.292177 33.21858 1.819489 -7.473686 33.79847 1.919963 -6.958758 34.28777 2.01336 -6.418663 34.74962 2.11867 -5.746537 35.25828 2.262963 -4.915149 35.79509 2.389621 -4.00237 36.2852 2.501208 -2.952336 36.71968 2.59908 -1.83396 37.03923 2.643386 -0.6042146 37.23502 2.643375 0.6434542 37.2648 2.566879 1.798981 37.14518 2.492794 2.652895 36.89477 2.302134 3.284198 36.52864 2.09238 4.241909 35.86577 1.82035 6.18897 34.65248 1.718712 7.654351 33.93796 1.682727 8.545989 33.56534 1.700752 9.019225 33.32357 1.753716 9.318572 33.10155 2.378895 -7.427197 33.66199 2.550639 -6.906228 34.12047 2.726371 -6.310011 34.59131 2.862139 -5.621294 35.08899 3.018118 -4.823846 35.57654 3.183514 -3.925289 36.02031 3.3263 -2.865485 36.42885 3.440368 -1.771795 36.7205 3.500374 -0.6241585 36.8875 3.498893 0.5649043 36.91413 3.391093 1.692315 36.83212 3.303527 2.493781 36.64743 3.066383 3.051865 36.40327 2.77746 4.09415 35.70355 2.432023 6.103537 34.46709 2.296179 7.597476 33.75209 2.233445 8.528068 33.38264 2.181363 9.033468 33.15841 2.172821 9.327583 32.96303 2.995834 -7.348321 33.47323 3.156681 -6.79087 33.95853 3.350689 -6.156279 34.43417 3.543817 -5.43229 34.91014 3.701402 -4.646908 35.36067 3.892695 -3.750839 35.75858 4.053432 -2.741746 36.10718 4.167912 -1.68019 36.36454 4.229071 -0.5980233 36.5053 4.23417 0.5215892 36.52097 4.123142 1.597448 36.45842 4.001125 2.359559 36.32801 3.741801 2.885012 36.15156 3.37382 3.970909 35.4712 2.96699 6.013453 34.24829 2.801661 7.536762 33.53593 2.718475 8.518013 33.16305 2.656094 9.047832 32.94132 2.620883 9.307434 32.78871 3.591804 -7.192818 33.3132 3.769763 -6.631479 33.77474 3.955525 -6.032274 34.20075 4.149846 -5.317583 34.64414 4.343097 -4.527563 35.05241 4.542111 -3.627306 35.42172 4.690719 -2.648912 35.74142 4.808311 -1.623766 35.96444 4.872155 -0.5816728 36.08259 4.855273 0.518046 36.10627 4.747356 1.531177 36.058 4.576433 2.247686 35.98843 4.344332 2.73955 35.83711 3.961083 3.807886 35.19766 3.482272 5.850924 34.02967 3.290113 7.439645 33.29401 3.179721 8.481617 32.9158 3.096361 9.015894 32.71318 3.066113 9.27106 32.5781 4.123474 -7.058851 33.11884 4.289644 -6.503973 33.55736 4.502231 -5.872113 33.9689 4.696958 -5.156064 34.388 4.923716 -4.386023 34.73369 5.102411 -3.539011 35.06198 5.241266 -2.597669 35.35314 5.373975 -1.617419 35.53366 5.419391 -0.5691964 35.66176 5.408035 0.468267 35.68308 5.302563 1.405393 35.65175 5.105006 2.103312 35.62753 4.850041 2.560089 35.55841 4.479421 3.487793 35.06088 4.035429 5.382914 33.96868 3.772854 7.218736 33.09514 3.586327 8.391493 32.69129 3.472203 8.916245 32.52062 3.413646 9.214944 32.39017 4.589441 -6.91875 32.91527 4.795396 -6.323659 33.34619 5.007857 -5.722755 33.70428 5.223966 -5.002116 34.08164 5.406144 -4.238203 34.43445 5.579781 -3.442774 34.71406 5.716242 -2.528315 34.97579 5.83336 -1.581486 35.1427 5.843563 -0.560004 35.29104 5.810499 0.3943876 35.33391 5.709965 1.278328 35.31608 5.551689 1.948962 35.29384 5.363501 2.29179 35.29669 5.081047 2.856633 35.07273 4.659077 4.378017 34.23841 4.218772 6.80545 33.0442 3.990049 8.266209 32.46514 3.88428 8.816184 32.27156 3.80771 9.161991 32.132 5.041794 -6.697017 32.76719 5.221855 -6.107175 33.18539 5.464677 -5.531104 33.46687 5.67294 -4.870499 33.77565 5.858909 -4.106471 34.09605 6.040306 -3.296242 34.35087 6.163652 -2.410701 34.58903 6.25568 -1.50636 34.74666 6.241088 -0.5561674 34.89591 6.188923 0.3385577 34.9521 6.095082 1.16886 34.94622 5.974681 1.806468 34.91876 5.79815 2.1113 34.97282 5.57748 2.532322 34.84398 5.142654 3.910272 34.14933 4.606505 6.594011 32.83988 4.346094 8.182253 32.20591 4.240307 8.74025 32.01386 4.161337 9.120557 31.86047 5.429238 -6.502557 32.60168 5.641591 -5.911525 32.96493 5.864137 -5.381389 33.19845 6.069928 -4.720762 33.48405 6.243712 -3.978079 33.77821 6.388056 -3.182199 34.04226 6.518858 -2.358736 34.22894 6.626835 -1.504022 34.33942 6.661969 -0.5999769 34.41889 6.621083 0.2752665 34.46182 6.507969 1.068015 34.49545 6.350655 1.681078 34.53654 6.163413 1.975461 34.6299 5.93242 2.384617 34.55762 5.459108 3.767265 33.94231 4.907752 6.508604 32.59858 4.661128 8.126664 31.93286 4.560335 8.699045 31.73508 4.468235 9.094973 31.59018 5.831774 -6.443709 32.22928 6.049046 -5.890642 32.54058 6.269693 -5.311476 32.80501 6.440643 -4.691404 33.08385 6.616197 -3.930377 33.37128 6.784644 -3.119727 33.59991 6.925572 -2.31795 33.74789 7.025098 -1.481765 33.84661 7.061913 -0.6075534 33.9103 7.016503 0.2676468 33.95246 6.889688 1.030342 34.0119 6.726776 1.568015 34.09543 6.570489 1.843445 34.16686 6.293578 2.36238 34.10682 5.779674 3.952869 33.45679 5.238636 6.581993 32.1951 5.012888 8.110035 31.55842 4.909427 8.691046 31.36288 4.820948 9.081381 31.22278 -5.410962 9.373106 30.17526 -5.066912 9.303133 30.7473 -5.59391 9.157422 30.15939 -5.180207 9.130992 30.75857 -5.730879 8.909218 30.16399 -5.278823 8.821721 30.84064 -5.834094 8.465474 30.27919 -5.37748 8.313344 30.99449 -5.964847 7.629196 30.50824 -5.536746 7.196657 31.38222 -6.244376 5.958489 31.07901 -5.930996 5.139434 32.23618 -6.813576 3.534447 32.04288 -6.53923 2.847518 33.25455 -7.322825 2.01857 32.54828 -6.893184 1.867538 33.59393 -7.646289 1.356743 32.6113 -7.130802 1.484625 33.51567 -7.819701 0.9338263 32.53971 -7.286608 1.052901 33.41714 -7.942436 0.2230744 32.46833 -7.403441 0.273533 33.37047 -7.993303 -0.7053858 32.41938 -7.438629 -0.674163 33.34596 -7.963188 -1.690026 32.33293 -7.40444 -1.587205 33.27243 -7.869297 -2.7028 32.15882 -7.314384 -2.499986 33.12774 -7.686496 -3.65902 31.97396 -7.163142 -3.392172 32.94145 -7.46207 -4.524395 31.75757 -6.980569 -4.231141 32.69699 -7.212696 -5.36053 31.44957 -6.780004 -4.968596 32.42517 -6.97138 -6.087885 31.0954 -6.564074 -5.636408 32.13018 -6.700669 -6.680098 30.82911 -6.322534 -6.252354 31.83205 -5.798047 9.398962 29.4576 -6.011436 9.149234 29.44795 -6.178266 8.923334 29.41323 -6.296726 8.58691 29.45188 -6.427612 7.936131 29.56394 -6.624417 6.657017 29.85476 -6.995417 4.745467 30.43617 -7.548762 2.743154 31.08111 -8.029463 1.442996 31.45353 -8.321835 0.7935209 31.44491 -8.49083 0.1573085 31.31984 -8.555476 -0.7667018 31.25326 -8.518516 -1.813816 31.18865 -8.406679 -2.8525 31.05471 -8.218305 -3.853109 30.85703 -7.950477 -4.773244 30.67683 -7.64822 -5.637387 30.4147 -7.375401 -6.374886 30.07854 -7.063413 -7.000185 29.82092 -6.176345 9.372371 28.66341 -6.398105 9.151236 28.59897 -6.591784 8.902363 28.54787 -6.74761 8.584556 28.53223 -6.909037 8.021735 28.5434 -7.069239 7.029152 28.65898 -7.287539 5.561936 28.92954 -7.690883 3.710323 29.36722 -8.288136 1.788232 29.91049 -8.741251 0.6995369 30.04679 -8.997249 -0.01712739 29.94744 -9.08737 -0.9132942 29.85343 -9.059266 -1.975615 29.77075 -8.931812 -3.04201 29.67692 -8.707021 -4.077867 29.55515 -8.397688 -5.060154 29.40501 -8.07618 -5.945748 29.1359 -7.738493 -6.693606 28.89551 -7.346622 -7.387013 28.65984 -6.505267 9.323538 27.70641 -6.737384 9.097544 27.67493 -6.958769 8.843531 27.5685 -7.170643 8.518547 27.4482 -7.36753 8.032049 27.36609 -7.521682 7.200656 27.40472 -7.688028 5.907846 27.53362 -7.963816 4.213226 27.82318 -8.479269 2.141872 28.3168 -8.968689 0.7531077 28.55053 -9.335496 -0.1701024 28.55289 -9.488743 -1.011411 28.41964 -9.497202 -2.090145 28.26634 -9.37396 -3.225601 28.14067 -9.120635 -4.338142 28.06627 -8.798317 -5.341752 27.93663 -8.453392 -6.235448 27.71316 -8.046135 -7.017201 27.56994 -7.615894 -7.74846 27.32588 -6.76989 9.232254 26.54442 -7.027693 8.998641 26.53713 -7.291427 8.724234 26.37746 -7.545079 8.383408 26.19814 -7.769364 7.922636 26.07459 -7.92811 7.216981 26.04975 -8.061161 6.091656 26.0926 -8.222784 4.623546 26.23698 -8.541539 2.832797 26.52348 -9.044487 1.030974 26.84898 -9.527647 -0.2826637 26.98012 -9.760568 -1.159462 26.88699 -9.79811 -2.198484 26.7419 -9.692659 -3.357433 26.56422 -9.444401 -4.502884 26.50438 -9.107453 -5.558301 26.40324 -8.728925 -6.47893 26.25853 -8.313249 -7.268591 26.1241 -7.880385 -7.977451 25.93594 -6.932381 9.141957 25.05384 -7.264732 8.864257 25.02004 -7.571961 8.565276 24.89411 -7.850728 8.216199 24.76892 -8.080856 7.784608 24.65834 -8.244463 7.181832 24.58599 -8.357927 6.199664 24.5888 -8.453886 4.851742 24.65212 -8.599693 3.306407 24.79178 -8.922851 1.575954 25.01831 -9.472398 -0.1513209 25.2404 -9.840967 -1.288504 25.25558 -9.958178 -2.304828 25.1243 -9.876933 -3.459214 24.93997 -9.644454 -4.609395 24.91585 -9.308091 -5.708553 24.82187 -8.917613 -6.655341 24.72926 -8.497531 -7.469639 24.58138 -8.033679 -8.207643 24.45089 -6.988285 9.105113 23.28906 -7.371857 8.790104 23.26999 -7.767789 8.42278 23.21376 -8.057476 8.089466 23.14261 -8.272541 7.727534 23.06538 -8.450022 7.170957 23.00595 -8.559729 6.270277 22.99402 -8.620262 4.973274 23.04195 -8.686902 3.513078 23.12547 -8.87065 1.883868 23.28253 -9.322913 -0.005581617 23.51692 -9.741912 -1.366238 23.57231 -9.960884 -2.415437 23.45783 -9.922377 -3.540861 23.2471 -9.719335 -4.680799 23.18863 -9.401818 -5.778048 23.16973 -9.012182 -6.749231 23.19867 -8.575197 -7.605753 23.0813 -8.110624 -8.340742 23.01121 -7.01951 9.083752 21.42653 -7.400669 8.767858 21.41913 -7.84996 8.357651 21.40973 -8.132565 8.046525 21.39539 -8.365878 7.679769 21.37684 -8.555709 7.136271 21.36 -8.65472 6.313062 21.36445 -8.683328 5.059744 21.43376 -8.694226 3.636758 21.51721 -8.752814 2.116641 21.60335 -9.01021 0.3740852 21.74878 -9.501358 -1.4095 21.88063 -9.822336 -2.620325 21.83872 -9.830265 -3.62922 21.6262 -9.658274 -4.716272 21.5473 -9.370783 -5.790682 21.55559 -8.996294 -6.778289 21.63126 -8.557953 -7.660698 21.57563 -8.09309 -8.416752 21.49748 -7.039966 9.068063 19.54998 -7.427319 8.745844 19.54947 -7.851955 8.356737 19.56042 -8.12595 8.050164 19.59565 -8.357221 7.684494 19.63557 -8.544734 7.146425 19.66221 -8.630656 6.361786 19.69803 -8.63154 5.13444 19.76706 -8.605002 3.732037 19.85482 -8.599987 2.257563 19.9398 -8.746655 0.5612259 20.0748 -9.212727 -1.549761 20.29666 -9.551646 -2.866591 20.30228 -9.611785 -3.746536 20.13507 -9.47093 -4.752109 20.0573 -9.207741 -5.793942 20.04985 -8.856184 -6.761401 20.05921 -8.435691 -7.650513 20.03772 -7.965549 -8.445446 20.0045 -7.045238 9.06415 17.67292 -7.423007 8.750795 17.68171 -7.779763 8.418453 17.71859 -8.045691 8.103729 17.80705 -8.24582 7.76445 17.91775 -8.417445 7.231527 17.99493 -8.490471 6.442312 18.06138 -8.463151 5.219949 18.11425 -8.40415 3.814511 18.18278 -8.359003 2.339397 18.28452 -8.416867 0.6384596 18.41972 -8.75167 -1.511435 18.68435 -9.07454 -2.99229 18.73454 -9.218112 -3.941486 18.62323 -9.128891 -4.795439 18.51678 -8.91075 -5.754022 18.5172 -8.591876 -6.713545 18.54414 -8.200572 -7.617206 18.61157 -7.781908 -8.371459 18.64311 -7.049188 9.061122 15.79375 -7.414365 8.760591 15.80305 -7.676492 8.51572 15.84426 -7.870776 8.263694 15.96553 -8.035778 7.933929 16.12922 -8.186438 7.382431 16.2882 -8.242012 6.540226 16.36937 -8.186572 5.279585 16.34975 -8.106055 3.856421 16.35616 -8.031713 2.401224 16.37648 -8.006349 0.8936436 16.46633 -8.161318 -0.9804469 16.78439 -8.511568 -2.893396 17.12693 -8.721966 -4.130493 17.1732 -8.670385 -4.877988 17.0667 -8.497355 -5.747009 17.11781 -8.211028 -6.684598 17.18438 -7.845354 -7.556882 17.24443 -7.475899 -8.28829 17.35485 -7.05131 9.059351 13.91317 -7.412446 8.764559 13.91649 -7.619285 8.579484 13.93213 -7.726019 8.430298 13.99426 -7.816692 8.161224 14.13036 -7.913221 7.559882 14.33545 -7.938858 6.574482 14.39449 -7.879658 5.213104 14.27626 -7.825722 3.76001 14.20273 -7.784325 2.34585 14.11592 -7.753655 1.082612 14.10046 -7.79474 -0.4008389 14.39742 -8.040814 -2.521587 15.17374 -8.21755 -4.148038 15.70199 -8.153697 -4.934265 15.73177 -7.993532 -5.709983 15.81429 -7.754399 -6.588636 15.93108 -7.423263 -7.425744 16.00351 -7.089042 -8.145793 16.14109 -7.053092 9.05759 12.03244 -7.417499 8.761065 12.032 -7.606317 8.596902 12.03604 -7.675943 8.497574 12.05142 -7.716032 8.288953 12.09335 -7.750555 7.687069 12.16727 -7.75837 6.546035 12.1892 -7.738034 5.138506 12.15226 -7.722308 3.686375 12.14092 -7.709519 2.271782 12.10984 -7.687298 1.043168 12.05941 -7.653089 -0.05212944 12.10197 -7.682662 -1.556531 12.62854 -7.740275 -3.414122 13.66396 -7.642517 -4.416633 14.07697 -7.49712 -5.400551 14.53208 -7.260234 -6.399097 14.80164 -6.949206 -7.261253 14.91306 -6.67642 -7.946162 15.07309 -7.045114 9.063925 10.15367 -7.401502 8.774585 10.15364 -7.597291 8.605777 10.15546 -7.664891 8.513117 10.1588 -7.692181 8.324027 10.16699 -7.705354 7.734151 10.18715 -7.708042 6.559366 10.22243 -7.70398 5.175356 10.29478 -7.700222 3.748334 10.41301 -7.695407 2.294241 10.51477 -7.679672 0.9661827 10.55147 -7.628881 -0.006251752 10.54229 -7.543455 -0.8304433 10.70196 -7.434087 -1.82048 11.17728 -7.254342 -2.784369 11.70684 -7.062458 -4.459343 12.87946 -6.783729 -6.016434 13.70862 -6.50837 -6.989861 13.99793 -6.285955 -7.685542 14.20287 -7.038309 9.069208 8.280364 -7.389363 8.784743 8.284277 -7.589009 8.612881 8.293907 -7.659788 8.519015 8.304288 -7.68668 8.339132 8.315362 -7.696349 7.78992 8.355091 -7.697365 6.714683 8.504708 -7.694252 5.457098 8.821024 -7.689214 4.100167 9.260127 -7.682272 2.575384 9.663081 -7.666851 1.075519 9.912863 -7.617519 0.04489427 10.00479 -7.50765 -0.5890294 10.07422 -7.341896 -1.13129 10.20976 -7.140058 -1.731083 10.46621 -6.87946 -3.050732 11.29327 -6.385102 -5.315768 12.57289 -6.055572 -6.685976 13.17261 -5.84956 -7.475876 13.46193 -7.029647 9.076143 6.4583 -7.361847 8.807808 6.481979 -7.555069 8.641304 6.534574 -7.634323 8.544073 6.589941 -7.668186 8.38938 6.636199 -7.680645 7.973137 6.748579 -7.681296 7.189733 7.104677 -7.675519 6.165019 7.723593 -7.666011 4.86249 8.469081 -7.65117 3.218299 9.159198 -7.629471 1.418797 9.638807 -7.583669 0.2070751 9.830267 -7.477611 -0.4671936 9.906989 -7.306556 -0.9455398 9.970542 -7.119134 -1.3858 10.10117 -6.831935 -2.359995 10.60383 -6.216053 -4.587426 11.76213 -5.715016 -6.256415 12.46395 -5.441082 -7.195019 12.80644 -7.021811 9.082677 4.924295 -7.282598 8.873629 4.991007 -7.438606 8.737456 5.130173 -7.52709 8.639993 5.274058 -7.576147 8.530348 5.376565 -7.603497 8.311757 5.526309 -7.617137 7.875169 5.900933 -7.621917 7.148357 6.5809 -7.61322 6.020238 7.468141 -7.572545 4.28007 8.456079 -7.51298 2.068208 9.2769 -7.447635 0.4451289 9.638779 -7.349276 -0.3484495 9.752569 -7.203994 -0.8303956 9.815896 -7.079215 -1.173922 9.907254 -6.884807 -1.7135 10.13925 -6.406451 -3.074184 10.7623 -5.727824 -5.080904 11.60683 -5.175485 -6.714031 12.219 -6.986993 9.106443 4.189579 -7.165035 8.964893 4.222176 -7.259066 8.878424 4.279445 -7.31094 8.812512 4.338768 -7.34844 8.736985 4.409058 -7.395182 8.613515 4.569357 -7.440703 8.412409 4.847291 -7.474093 8.054158 5.298385 -7.467129 7.302032 6.030605 -7.369004 5.688333 7.155961 -7.222505 3.076107 8.445565 -7.099211 0.7143985 9.220201 -7.004559 -0.2491686 9.441721 -6.920699 -0.6816548 9.528143 -6.884471 -0.9913033 9.653584 -6.808078 -1.342271 9.823634 -6.56434 -2.007664 10.11448 -6.000626 -3.510733 10.70596 -4.973995 -6.044505 11.58941 -6.945818 9.125519 3.978364 -7.084385 9.013787 3.984452 -7.164556 8.936074 4.000144 -7.207927 8.876595 4.013943 -7.230445 8.820199 4.032551 -7.248009 8.752663 4.086884 -7.257813 8.670905 4.173834 -7.249349 8.542587 4.31126 -7.204009 8.222278 4.605498 -7.113981 7.258172 5.370081 -7.011205 4.841888 6.975333 -6.92877 1.302946 8.685552 -6.843214 -0.1256732 9.24381 -6.739913 -0.5956634 9.351644 -6.638899 -0.8657557 9.407608 -6.545563 -1.125935 9.503783 -6.444834 -1.566389 9.732749 -5.972919 -2.820188 10.22772 -4.733452 -5.674521 11.19419 6.574741 -7.129538 30.45536 6.219973 -6.755357 31.41093 6.815526 -6.601132 30.75375 6.421454 -6.228945 31.7351 7.096561 -5.902367 31.0989 6.658514 -5.564808 32.07912 7.302519 -5.235513 31.42578 6.858322 -4.920687 32.36473 7.550701 -4.404022 31.70451 7.059429 -4.154672 32.64027 7.766324 -3.544455 31.91143 7.232616 -3.322553 32.88583 7.950573 -2.638447 32.05513 7.393418 -2.472337 33.03511 8.086397 -1.705899 32.11532 7.504323 -1.599652 33.12802 8.130331 -0.7703885 32.16328 7.543202 -0.7027897 33.18795 8.081095 0.1475437 32.21493 7.50616 0.238505 33.21712 7.943227 0.8616151 32.32475 7.37844 1.019018 33.28458 7.718151 1.312472 32.4951 7.20078 1.453835 33.42396 7.386873 1.98392 32.46165 7.005213 1.816127 33.45888 6.883483 3.498697 31.9449 6.611085 2.813291 33.16801 6.310983 5.925302 30.98373 5.976901 5.115519 32.17901 6.02309 7.597635 30.43135 5.575549 7.17297 31.33975 5.894158 8.433771 30.20865 5.425859 8.283982 30.94876 5.783924 8.87705 30.10927 5.327023 8.779231 30.80836 5.66734 9.128699 30.07965 5.236187 9.102299 30.71155 6.855023 -7.480928 29.49409 7.167125 -6.908222 29.76801 7.492774 -6.226717 30.04508 7.73987 -5.520912 30.36509 8.028752 -4.67957 30.60033 8.289625 -3.74821 30.78908 8.469655 -2.796864 30.96203 8.620931 -1.821894 30.98002 8.676416 -0.8151871 30.99679 8.614392 0.08464717 31.06922 8.441495 0.7097554 31.22204 8.117575 1.378464 31.30073 7.597179 2.710455 31.0012 7.051549 4.713146 30.34024 6.683185 6.621222 29.75678 6.489356 7.895662 29.47331 6.362977 8.534659 29.37265 6.247308 8.875843 29.33247 6.089369 9.111734 29.35193 7.09358 -7.860565 28.39141 7.461663 -7.267931 28.61209 7.831141 -6.601735 28.81897 8.168936 -5.844359 29.04408 8.49547 -4.964169 29.26361 8.776283 -3.974676 29.46991 8.975751 -2.966469 29.61647 9.104317 -1.934736 29.68139 9.131697 -0.9091684 29.75776 9.043341 -0.046422 29.86332 8.797842 0.6410907 29.97653 8.345773 1.73103 29.8461 7.739021 3.670802 29.28454 7.351264 5.518975 28.80038 7.133366 6.983976 28.52851 6.966382 7.976021 28.44674 6.817107 8.51912 28.44953 6.675949 8.830506 28.45108 6.486857 9.094018 28.47814 7.350031 -8.178707 27.13412 7.747487 -7.605379 27.27927 8.133197 -6.954635 27.44339 8.51616 -6.167094 27.62989 8.870965 -5.23529 27.84576 9.172221 -4.235343 28.00279 9.399924 -3.162867 28.10395 9.515028 -2.048356 28.22926 9.50419 -1.001788 28.39258 9.36346 -0.2100133 28.54143 9.034109 0.6374396 28.55031 8.555562 2.039562 28.28163 8.020573 4.156478 27.72705 7.749726 5.865716 27.38503 7.585909 7.156532 27.25196 7.421681 7.976448 27.27075 7.238591 8.437373 27.37699 7.044143 8.76996 27.44391 6.846362 9.023442 27.49086 7.549007 -8.46062 25.7848 7.974019 -7.865383 25.91735 8.391631 -7.177671 26.06072 8.783213 -6.393976 26.21001 9.164058 -5.445863 26.34082 9.488761 -4.399474 26.43321 9.714649 -3.295436 26.53021 9.810392 -2.174475 26.71726 9.77943 -1.183617 26.88016 9.576457 -0.3913293 26.99873 9.153157 0.7748749 26.89245 8.605093 2.711001 26.50231 8.259632 4.573818 26.15349 8.094588 6.057859 25.98682 7.963595 7.180724 25.95261 7.803694 7.879451 26.01275 7.597531 8.319063 26.13728 7.375268 8.64923 26.24449 7.147064 8.906125 26.35767 7.697767 -8.670701 24.3972 8.114658 -8.095598 24.48036 8.561357 -7.369523 24.59013 8.976204 -6.542689 24.70092 9.359443 -5.592928 24.77066 9.687906 -4.504127 24.84717 9.900039 -3.394104 24.94236 9.979766 -2.309091 25.12949 9.90089 -1.409093 25.28724 9.597171 -0.4544456 25.33292 9.14384 1.001165 25.18428 8.692365 3.072114 24.81523 8.486639 4.777538 24.58652 8.3837 6.149307 24.48926 8.273021 7.129099 24.50123 8.118285 7.725717 24.59584 7.9121 8.141674 24.70628 7.676988 8.459689 24.8118 7.404682 8.744668 24.92622 7.768801 -8.817942 22.95745 8.201499 -8.209584 23.04969 8.642007 -7.48338 23.15939 9.069597 -6.6246 23.2235 9.454562 -5.640231 23.22426 9.76453 -4.539857 23.32293 9.95191 -3.461049 23.41855 10.00686 -2.464589 23.54519 9.867903 -1.618745 23.67663 9.487878 -0.3903002 23.6395 8.994408 1.569008 23.36603 8.726527 3.409277 23.12771 8.632872 4.937344 23.01065 8.572117 6.235603 22.94913 8.47041 7.12746 22.96335 8.31651 7.651994 23.03424 8.130622 7.996078 23.10387 7.86625 8.323934 23.17067 7.543092 8.642487 23.24125 7.752262 -8.907339 21.54057 8.191236 -8.28033 21.55736 8.627584 -7.53687 21.6105 9.044857 -6.671953 21.66902 9.423843 -5.655521 21.68517 9.70493 -4.582874 21.7436 9.865207 -3.553399 21.81662 9.871234 -2.677794 21.93786 9.632853 -1.70726 22.00897 9.23552 -0.2084288 21.93802 8.85118 1.86532 21.66209 8.716868 3.580289 21.49414 8.688716 5.04126 21.40156 8.658699 6.29698 21.35602 8.567015 7.113368 21.35282 8.406125 7.619694 21.37256 8.225953 7.930132 21.39029 7.953618 8.253108 21.40387 7.578491 8.612301 21.41959 7.65997 -8.913647 20.1118 8.074069 -8.29878 20.09834 8.503931 -7.532857 20.06034 8.897397 -6.666404 20.06121 9.240808 -5.703351 20.0908 9.498036 -4.689923 20.13495 9.643664 -3.73377 20.22371 9.612236 -2.940479 20.38272 9.289346 -1.67598 20.38686 8.842391 0.350345 20.17902 8.637542 2.187707 19.9853 8.616032 3.723134 19.86619 8.637114 5.137559 19.786 8.635418 6.358179 19.71809 8.554576 7.131689 19.6798 8.392779 7.635735 19.65456 8.21394 7.941307 19.61448 7.940459 8.266884 19.57608 7.571592 8.620398 19.55116 7.48706 -8.854341 18.76454 7.873238 -8.239723 18.67241 8.254699 -7.519861 18.61228 8.620955 -6.645516 18.54063 8.939738 -5.690529 18.54049 9.17113 -4.754397 18.59272 9.288128 -3.971801 18.73266 9.206336 -3.147089 18.87663 8.853425 -1.608903 18.7954 8.47376 0.6068196 18.51294 8.381239 2.341603 18.33961 8.420918 3.831119 18.25562 8.477666 5.234677 18.1877 8.500988 6.442358 18.11598 8.43048 7.215569 18.04302 8.275536 7.721798 17.96725 8.103105 8.033287 17.85635 7.844825 8.354776 17.75205 7.548574 8.643902 17.68718 7.214695 -8.773805 17.53089 7.581371 -8.156885 17.40397 7.921397 -7.444811 17.27795 8.254304 -6.606501 17.20707 8.555418 -5.679813 17.20854 8.764104 -4.802885 17.25905 8.816124 -4.09657 17.36355 8.61344 -2.934878 17.26837 8.22711 -0.9869119 16.83924 8.040765 0.91701 16.53551 8.057624 2.429034 16.47435 8.134531 3.887316 16.49745 8.218791 5.318125 16.52537 8.263422 6.551055 16.47546 8.206773 7.360065 16.36008 8.067091 7.880692 16.18772 7.909765 8.211585 16.02423 7.724254 8.469104 15.87034 7.521237 8.670596 15.80644 6.910839 -8.582329 16.37373 7.284095 -7.960374 16.30251 7.576213 -7.280785 16.15594 7.834367 -6.499495 16.01906 8.094548 -5.626435 15.97597 8.275284 -4.847364 15.94888 8.290477 -4.103526 15.83049 8.106059 -2.490447 15.23126 7.840565 -0.3482138 14.33617 7.773127 1.115594 14.08817 7.797032 2.366787 14.15808 7.845708 3.79616 14.31845 7.915828 5.286981 14.49717 7.96156 6.61206 14.5142 7.928225 7.551428 14.39415 7.830841 8.13335 14.15123 7.743591 8.405298 14.01257 7.654281 8.546709 13.93908 7.503092 8.689023 13.91739 6.499709 -8.428142 15.30736 6.841518 -7.828737 15.24491 7.114023 -7.148241 15.10124 7.34422 -6.335557 14.89927 7.593011 -5.335541 14.66214 7.763458 -4.331579 14.24079 7.794239 -3.374966 13.73352 7.715438 -1.522814 12.64601 7.673039 -0.0157414 12.06844 7.69417 1.059681 12.04801 7.712729 2.278664 12.11829 7.727986 3.698359 12.17553 7.750452 5.166323 12.23006 7.765788 6.560315 12.22842 7.75521 7.684228 12.18504 7.720514 8.278958 12.09673 7.68499 8.48528 12.05433 7.634552 8.571171 12.03786 7.494625 8.696943 12.03468 6.133976 -8.189312 14.43081 6.393197 -7.612134 14.29914 6.650443 -6.904701 14.14809 6.889363 -5.952393 13.81919 7.182671 -4.380232 13.00079 7.37182 -2.677364 11.78468 7.478013 -1.773763 11.20062 7.561379 -0.8002421 10.70563 7.636715 0.01428914 10.53511 7.682194 0.9730548 10.54988 7.696479 2.296184 10.51687 7.701437 3.750729 10.41934 7.706347 5.180708 10.3092 7.709388 6.561902 10.22914 7.706459 7.732727 10.19012 7.694603 8.318815 10.16738 7.673795 8.502367 10.15946 7.631693 8.575158 10.15631 7.496868 8.695198 10.15508 5.75848 -8.00536 13.75093 5.951486 -7.440687 13.55799 6.170943 -6.635429 13.28452 6.498025 -5.262423 12.68188 6.970915 -2.985264 11.36004 7.241876 -1.618356 10.48879 7.387066 -1.068672 10.21535 7.531729 -0.5346097 10.07531 7.628763 0.07805967 10.00618 7.671951 1.085498 9.916917 7.685235 2.578183 9.667513 7.690988 4.101974 9.26397 7.695468 5.458775 8.824809 7.698039 6.715362 8.506653 7.697102 7.788805 8.356234 7.689275 8.334363 8.31673 7.670332 8.507121 8.307709 7.630472 8.576499 8.297612 7.512356 8.682919 8.28586 5.343691 -7.761168 13.08726 5.583218 -7.144272 12.92497 5.847999 -6.205217 12.57844 6.292299 -4.554038 11.82769 6.885902 -2.316579 10.62892 7.205329 -1.289218 10.11029 7.362434 -0.8714982 9.977667 7.515501 -0.4011543 9.913976 7.607933 0.2454845 9.840517 7.645762 1.431288 9.650503 7.662082 3.223789 9.168745 7.671696 4.865886 8.476037 7.679428 6.167237 7.730965 7.684058 7.190627 7.111217 7.683136 7.971513 6.754668 7.6732 8.382969 6.645398 7.649216 8.528643 6.609365 7.597721 8.603954 6.55672 7.477381 8.712581 6.49892 5.014659 -7.503361 12.57333 5.287641 -6.669664 12.29218 5.788978 -5.054893 11.65149 6.438158 -3.061639 10.78486 6.926153 -1.691369 10.15787 7.171042 -1.112232 9.939183 7.295844 -0.7638179 9.853034 7.4231 -0.3061822 9.792978 7.518851 0.4760456 9.685043 7.574094 2.085291 9.31845 7.614677 4.294817 8.484232 7.631094 6.026606 7.48481 7.634165 7.148285 6.604663 7.627853 7.872295 5.927765 7.613521 8.305567 5.55419 7.58899 8.518323 5.410804 7.550206 8.618086 5.328599 7.476189 8.70434 5.190629 7.357081 8.812502 5.040747 4.780692 -7.153186 12.13841 5.222696 -5.901079 11.69007 6.096735 -3.466863 10.75147 6.612595 -2.006442 10.14805 6.874896 -1.34796 9.87378 7.008709 -0.9891285 9.742335 7.069731 -0.6591116 9.629668 7.154712 -0.2251585 9.547496 7.268433 0.7598229 9.33632 7.376932 3.113806 8.549058 7.4832 5.726952 7.229712 7.514841 7.316185 6.071707 7.502512 8.048073 5.354788 7.465872 8.399522 4.912752 7.418108 8.598103 4.633539 7.367584 8.721266 4.461771 7.326315 8.798417 4.374184 7.277822 8.861891 4.306944 7.202867 8.934556 4.243366 4.558117 -6.773694 11.734 5.232516 -5.089315 11.17183 6.190738 -2.629604 10.25427 6.543598 -1.557163 9.792225 6.629822 -1.143098 9.570928 6.707123 -0.8725885 9.459438 6.802156 -0.5901827 9.394916 6.903427 -0.117781 9.286009 7.000108 1.322179 8.733855 7.093311 4.86584 7.029863 7.215397 7.298742 5.436221 7.263656 8.248615 4.644666 7.274715 8.547917 4.341258 7.273005 8.668659 4.203162 7.261036 8.747826 4.115549 7.241591 8.813752 4.055982 7.217946 8.86957 4.028007 7.179213 8.925323 4.010272 7.116618 8.989779 3.991649 4.372828 -6.358643 11.34046 5.334991 -4.145967 10.632 6.143182 -2.035258 9.833215 6.375378 -1.267394 9.486096 6.437441 -1.026804 9.366621 6.544285 -0.8389651 9.326417 6.674829 -0.5958527 9.300402 6.796097 -0.07169961 9.138474 6.891717 1.734497 8.213975 6.955237 6.077067 5.677476 7.028361 8.039872 4.402603 7.100842 8.546382 4.059527 7.143708 8.669754 3.985301 7.179588 8.734208 3.966689 7.193574 8.786602 3.953166 7.187019 8.837507 3.941078 7.161517 8.892675 3.932501 7.116192 8.954284 3.924134 7.056827 9.017855 3.921939 -5.937116 -5.938235 32.61469 -6.126955 -5.359339 32.91787 -6.303464 -4.69793 33.23019 -6.503045 -3.964494 33.48246 -6.666434 -3.183137 33.70641 -6.77094 -2.326532 33.92452 -6.835979 -1.438828 34.08387 -6.868735 -0.5531594 34.15551 -6.82938 0.3220612 34.18643 -6.730796 1.081737 34.20464 -6.626082 1.605808 34.21081 -6.436429 1.898487 34.31404 -6.193993 2.402434 34.20839 -5.723541 3.977126 33.5107 -5.195103 6.604548 32.23408 -4.955546 8.136363 31.611 -4.851158 8.715716 31.41395 -4.75032 9.095843 31.2904 + + + + + + + + + + -0.6095148 -0.6042841 0.5131592 -0.6158658 -0.5872275 0.5252364 0.5933243 -0.6231356 0.5095767 0.5696288 -0.633911 0.5231444 0.638938 0.5617192 0.5255758 0.6510298 0.5353399 0.5381186 -0.5703111 0.6476998 0.5052033 -0.5356618 0.6683431 0.516124 0.4622074 0.7058698 -0.5367609 0.4719233 0.6654313 -0.5783508 -0.5772786 0.5869815 0.5676286 -0.5997266 0.5497899 0.5814287 -0.5179331 0.8338537 -0.190876 -0.5184031 0.8255039 -0.2231629 -0.5306637 0.8467079 -0.03849571 -0.5327441 0.8450966 -0.04467225 -0.5331884 0.8459874 -0.003928065 -0.5351264 0.8447539 -0.005531191 -0.535141 0.8447625 -8.00133e-4 -0.5356407 0.8444455 -9.95535e-4 -0.5356436 0.8444442 -7.45107e-5 -0.5366924 0.843778 -4.18341e-4 -0.5366936 0.8437774 -4.61649e-5 -0.5377374 0.8431123 -3.70758e-4 -0.5377375 0.8431124 -2.59243e-5 -0.5388681 0.8423902 -3.65324e-4 -0.5388673 0.8423907 -1.7418e-4 -0.5393045 0.8421109 -2.99555e-4 -0.5393051 0.8421105 -8.73877e-5 -0.53921 0.8421714 -6.11617e-5 -0.5392094 0.8421719 -8.73676e-5 -0.5387037 0.8424953 5.09112e-5 -0.5387051 0.8424944 -1.40138e-4 -0.53797 0.842964 5.39401e-5 -0.5379735 0.8429616 -6.94705e-4 -0.5356543 0.8444373 -1.26004e-4 -0.5356572 0.8444344 -0.001398026 -0.5310347 0.84735 -4.61416e-4 -0.5310398 0.8473469 -7.09924e-6 -0.5259962 0.8504863 0.001033067 -0.5268694 0.8499047 0.008406817 -0.5202783 0.8539429 0.0096004 -0.5387769 0.8406816 0.05453562 -0.5359321 0.8424873 0.0546984 -0.5856232 0.7948068 0.1591473 -0.5763366 0.8016069 0.1589422 -0.6124742 0.7459543 0.261587 -0.5650417 0.7824658 0.2616778 -0.6131436 0.7012667 0.3637032 -0.5272268 0.7708054 0.3576185 -0.5866095 0.6774427 0.4438025 -0.5363162 0.7197226 0.4408677 0.5815684 0.7878613 -0.2026153 0.5770016 0.787983 -0.2148301 0.5900564 0.8064225 -0.03894084 0.592281 0.8049386 -0.03573679 0.5916207 0.8062099 -0.003247916 0.5995531 0.8003349 4.99272e-4 0.5995793 0.8003153 1.42554e-6 0.6059815 0.7954766 0.00186944 0.6059998 0.7954649 -1.46626e-5 0.6082971 0.7937092 6.48111e-4 0.60829 0.7937147 -5.28902e-4 0.6068984 0.794779 -9.53978e-4 0.6068996 0.7947785 -2.89183e-4 0.6066069 0.7950019 -3.6478e-4 0.6066057 0.7950029 -1.29754e-4 0.6074752 0.7943387 8.64969e-5 0.6074748 0.7943389 -9.50065e-5 0.6089944 0.7931745 2.93413e-4 0.6089956 0.7931737 -9.07843e-5 0.6107586 0.7918168 3.80148e-4 0.6107584 0.791817 -4.53717e-5 0.6127635 0.7902663 5.1407e-4 0.6127609 0.7902685 1.00391e-4 0.6137451 0.7895042 3.87164e-4 0.613746 0.7895035 5.09006e-4 0.6114438 0.791288 -2.15486e-4 0.6115331 0.7912132 0.003043115 0.6075355 0.7942911 0.001594185 0.6095327 0.7925589 0.01789969 0.6070168 0.7945135 0.01670593 0.6280486 0.7741868 0.0786758 0.6319822 0.7707419 0.08096563 0.6760407 0.7117905 0.1905865 0.6617633 0.7276671 0.1804718 0.6908926 0.6596093 0.2959443 0.6907362 0.6598358 0.2958046 0.6937632 0.6039928 0.3922823 0.6848543 0.6193892 0.3838384 0.6684746 0.5765972 0.4697633 0.65832 0.5954329 0.4605156 0.4940624 -0.460219 -0.737632 0.5089495 -0.4151275 -0.754082 0.522157 -0.4670316 -0.7136061 0.5342601 -0.4267516 -0.7296912 0.5519235 -0.4867637 -0.6770832 0.5643068 -0.4586071 -0.6864674 0.5853325 -0.5095221 -0.6306925 0.6028326 -0.4704402 -0.6444215 0.6277003 -0.5258284 -0.5740182 0.637699 -0.5032055 -0.5832016 0.6492453 -0.5677299 -0.5061258 0.6631739 -0.5403292 -0.5179237 0.6749984 -0.5946874 -0.4367197 0.6915978 -0.5664191 -0.4481762 0.6988232 -0.6202492 -0.3562824 0.7171582 -0.5918822 -0.3679125 0.7175397 -0.637369 -0.280887 0.726872 -0.6237723 -0.2873418 0.724372 -0.6607068 -0.1968552 0.7313668 -0.6514382 -0.201819 0.7303992 -0.6732732 -0.1149795 0.7316022 -0.671819 -0.1158345 0.7300788 -0.6823139 -0.03785109 0.7290841 -0.6834105 -0.03723531 0.7281011 -0.6846222 0.03407716 0.7290404 -0.6836532 0.03344309 0.7255214 -0.6805202 0.102524 0.719664 -0.68613 0.1063456 0.7084219 -0.6836729 0.1752992 0.696734 -0.6939957 0.1814713 0.6844755 -0.6881039 0.2408455 0.6762715 -0.6945747 0.2454034 0.6671733 -0.6807642 0.3023905 0.6518926 -0.691923 0.3102881 0.6485344 -0.6684238 0.3641604 0.6381357 -0.675231 0.3699269 0.636065 -0.651873 0.4128959 0.6190081 -0.6614782 0.4234096 0.6162028 -0.6343346 0.4668124 0.5948489 -0.6466431 0.4775013 -0.5080317 -0.4144702 -0.7550618 -0.4989812 -0.418869 -0.758661 -0.5489857 -0.4213075 -0.7218828 -0.5307588 -0.4298532 -0.7304255 -0.5856691 -0.4386594 -0.6815935 -0.576267 -0.4441252 -0.6860533 -0.6233952 -0.4548617 -0.6359869 -0.6101746 -0.4625819 -0.6431992 -0.661767 -0.4752349 -0.5798416 -0.6467288 -0.4862646 -0.5876128 -0.6975824 -0.4994041 -0.5137844 -0.675382 -0.5168434 -0.5260536 -0.7255491 -0.5291218 -0.4400098 -0.6984658 -0.5513543 -0.4562391 -0.7447723 -0.5596107 -0.3635247 -0.7289317 -0.5742348 -0.3727104 -0.7641406 -0.5767663 -0.2888422 -0.7509037 -0.5900379 -0.2966464 -0.7721332 -0.6012379 -0.2057263 -0.7610607 -0.612837 -0.2126442 -0.772521 -0.623225 -0.1216641 -0.7603513 -0.6363654 -0.1300202 -0.7675233 -0.6396907 -0.04127675 -0.7594236 -0.6489343 -0.04647928 -0.7610026 -0.6479631 0.03192102 -0.7575992 -0.6520538 0.02948176 -0.7502257 -0.6530713 0.1032444 -0.7488662 -0.6548076 0.1021103 -0.7351998 -0.6559262 0.1710033 -0.740037 -0.6495579 0.1744126 -0.7174805 -0.6539355 0.2399795 -0.719004 -0.6518051 0.2412126 -0.6910197 -0.65395 0.3079629 -0.6955316 -0.6476542 0.3110947 -0.6664892 -0.6473159 0.3698301 -0.6711594 -0.6401246 0.3738791 -0.6471365 -0.6348697 0.422084 -0.6507939 -0.628257 0.426334 -0.6259217 -0.6207914 0.4720595 -0.6316078 -0.6094487 0.4792117 -0.5859012 -0.6515157 0.4819204 -0.5756483 -0.6641225 0.4770435 -0.5359512 -0.6830638 0.4961656 -0.5170053 -0.7026113 0.4889202 -0.5028957 -0.6999838 0.5070688 -0.4815844 -0.7210131 0.4982134 -0.445678 -0.7288925 0.5196988 -0.4188719 -0.7521446 0.5087485 -0.4020441 -0.7452418 0.5319542 -0.3823518 -0.7618044 0.5229353 -0.341258 -0.7676201 0.5424966 -0.321442 -0.7816104 0.5345655 -0.276361 -0.7846105 0.5549874 -0.2562124 -0.7980631 0.5453903 -0.2015063 -0.8031651 0.5606434 -0.1919379 -0.8087881 0.5558972 -0.1342704 -0.8137937 0.5654302 -0.1275409 -0.8172876 0.561938 -0.05881464 -0.8213137 0.5674369 -0.05264115 -0.8240674 0.5640407 0.0180099 -0.8220941 0.5690667 0.01981323 -0.8226738 0.5681685 0.08752745 -0.8192013 0.5667877 0.08695459 -0.8190588 0.5670817 0.1630751 -0.8108708 0.5620456 0.1572364 -0.8098961 0.5651062 0.2289032 -0.799774 0.5549459 0.2183333 -0.7989764 0.560328 0.2985945 -0.786333 0.540853 0.2786675 -0.785203 0.5529926 0.3609434 -0.7668834 0.530669 0.3446372 -0.7682908 0.5394021 0.4147071 -0.7502756 0.5148829 0.39109 -0.7531182 0.5290197 0.4641842 -0.7289586 0.5031425 0.4433113 -0.7347853 0.5133865 0.521305 -0.6978539 0.491163 0.504249 -0.7028379 0.5017488 0.5647935 -0.6729117 0.4777011 0.5381915 -0.6854712 0.4903868 -0.6181415 -0.6591856 0.4282237 -0.610247 -0.6694445 0.4236068 -0.5660307 -0.697246 0.4398379 -0.5429073 -0.7220528 0.4288257 -0.5209541 -0.7221515 0.4550869 -0.4947425 -0.747595 0.4430933 -0.4671136 -0.7494245 0.4692205 -0.4442483 -0.7694855 0.4588418 -0.4161753 -0.7728067 0.4791325 -0.4007521 -0.785405 0.4717381 -0.3520166 -0.7967386 0.4912148 -0.3280573 -0.81277 0.4814388 -0.290017 -0.8147911 0.5020018 -0.270448 -0.8270452 0.4928025 -0.2118865 -0.834279 0.5090017 -0.2020955 -0.8396151 0.5041866 -0.1439543 -0.8457478 0.5137975 -0.1357681 -0.8495328 0.5097659 -0.06317108 -0.8547275 0.5152187 -0.05944305 -0.8562799 0.5130802 0.01742762 -0.8564968 0.5158581 0.01871323 -0.8568509 0.5152247 0.09054261 -0.8531293 0.5137825 0.08841061 -0.8527014 0.514863 0.1730903 -0.8438448 0.5079032 0.1648623 -0.8428582 0.5122601 0.2422645 -0.8311573 0.5004854 0.2280483 -0.8310531 0.5072914 0.3112083 -0.8146017 0.4894624 0.2933628 -0.8150677 0.4996029 0.3769418 -0.794025 0.476906 0.353199 -0.797828 0.4885909 0.43234 -0.7718256 0.4662268 0.4138935 -0.775688 0.4764454 0.4903759 -0.7455087 0.4513847 0.4618492 -0.7551198 0.4652846 0.5399679 -0.7183877 0.4385815 0.5205329 -0.7252828 0.4505667 0.588353 -0.6870697 0.4263521 0.5701724 -0.6959365 0.43655 -0.6353486 -0.6763402 0.3726878 -0.6334089 -0.6786302 0.3718255 -0.5967299 -0.7032626 0.3864392 -0.5709512 -0.7305295 0.3746219 -0.540663 -0.7408967 0.3984415 -0.5218483 -0.7591676 0.389023 -0.4963082 -0.7635628 0.413098 -0.4687558 -0.787956 0.3992409 -0.4302531 -0.7978134 0.4223461 -0.4151713 -0.809873 0.4144136 -0.3697386 -0.820514 0.4359476 -0.3389028 -0.8407004 0.4223363 -0.3033599 -0.8426184 0.4449349 -0.2866861 -0.8525627 0.4369761 -0.2234214 -0.8632374 0.4526633 -0.2132148 -0.8682548 0.4479656 -0.154191 -0.8756648 0.4576421 -0.1448776 -0.8794891 0.4533316 -0.06677269 -0.885511 0.4597954 -0.06364321 -0.8866476 0.4580455 0.01653867 -0.887872 0.4597933 0.01764422 -0.8881263 0.4592609 0.0953536 -0.8843129 0.4570542 0.09113347 -0.8836671 0.4591594 0.1830326 -0.8739283 0.4502759 0.1736021 -0.8732008 0.4553928 0.2563265 -0.8592247 0.4427525 0.2405714 -0.8599819 0.4500629 0.3203384 -0.8417356 0.4345856 0.3053839 -0.8430454 0.4427361 0.3972024 -0.8159511 0.4200644 0.3732078 -0.8205525 0.4329082 0.4503594 -0.7926632 0.4109278 0.4338801 -0.7971603 0.4198613 0.5137866 -0.7607439 0.3966007 0.4916749 -0.7690504 0.408433 0.5592054 -0.7334741 0.3864002 0.5412486 -0.7416322 0.3962724 0.6114861 -0.6984685 0.3717883 0.5900695 -0.7101995 0.3839725 -0.6503863 -0.6907405 0.3160308 -0.6416221 -0.7003286 0.3128276 -0.6178846 -0.7145935 0.3279861 -0.5951288 -0.7377101 0.3187564 -0.5626689 -0.7544237 0.3380069 -0.5442965 -0.7716497 0.3290866 -0.5213487 -0.7781097 0.3503443 -0.4968773 -0.7991068 0.3384397 -0.4512501 -0.8161984 0.3608233 -0.4333866 -0.8299245 0.3512854 -0.3919475 -0.8407723 0.3734693 -0.3668906 -0.857191 0.3614067 -0.316253 -0.8676707 0.3835774 -0.3016451 -0.8761705 0.3759462 -0.235975 -0.8898991 0.3903785 -0.2256121 -0.8948439 0.3851671 -0.1600691 -0.9049201 0.3943318 -0.1528143 -0.9077596 0.3906668 -0.06893485 -0.9155277 0.3963044 -0.06634062 -0.9163953 0.3947386 0.01701128 -0.9182636 0.3956041 0.01664537 -0.9181846 0.3958031 0.09864878 -0.9140079 0.3935203 0.0948618 -0.9135202 0.3955786 0.1890214 -0.9017772 0.388676 0.1814274 -0.9013166 0.3933352 0.2721406 -0.8838824 0.3803834 0.2562779 -0.8851283 0.3884192 0.3393911 -0.8645974 0.3705202 0.3202897 -0.8675821 0.3804154 0.4157908 -0.8358446 0.3584438 0.3961189 -0.8406041 0.3694248 0.4716947 -0.8097387 0.3490381 0.453693 -0.816156 0.3578437 0.5315263 -0.7767078 0.337942 0.5148338 -0.7837889 0.3473058 0.5795522 -0.7461338 0.3277249 0.5615859 -0.7557995 0.3367321 0.6332164 -0.7082561 0.3121063 0.6097536 -0.7225987 0.3256559 -0.6743684 -0.6952555 0.2486908 -0.6592862 -0.7117982 0.2422501 -0.6286597 -0.732388 0.261524 -0.6104392 -0.7497475 0.2554265 -0.5782256 -0.769083 0.2723353 -0.5680687 -0.7779809 0.2684096 -0.5320329 -0.7977734 0.2837229 -0.5163317 -0.8102684 0.2772486 -0.4696795 -0.8318418 0.2957034 -0.4559742 -0.8417491 0.2890436 -0.4076258 -0.8602038 0.3064159 -0.3916127 -0.8705661 0.2979167 -0.3237553 -0.892127 0.3151063 -0.3113185 -0.8989923 0.3080484 -0.2487918 -0.9140602 0.3203073 -0.2387653 -0.9186154 0.3148602 -0.1624999 -0.9318073 0.3245443 -0.1549626 -0.9344736 0.3205398 -0.06923514 -0.9424046 0.3272312 -0.06684356 -0.9430544 0.3258535 0.01852363 -0.9450285 0.3264629 0.01715415 -0.9448048 0.3271847 0.1002319 -0.9404904 0.3247024 0.09641999 -0.9401851 0.3267338 0.1905599 -0.9278612 0.3205627 0.1831288 -0.9277055 0.3253101 0.2844601 -0.9062771 0.312641 0.2716723 -0.9076376 0.3199816 0.3563767 -0.8833616 0.3044145 0.3427094 -0.8861409 0.3119369 0.4281786 -0.8550665 0.2924455 0.412021 -0.8595626 0.3023095 0.4962195 -0.8216099 0.280577 0.4775825 -0.8293207 0.290073 0.5441108 -0.7938437 0.2715798 0.5304663 -0.8003575 0.2793449 0.5957267 -0.7587621 0.2634192 0.5822675 -0.7668061 0.2701353 0.6490896 -0.7190904 0.2481769 0.627084 -0.7338624 0.2611739 -0.6930133 -0.6979265 0.1806412 -0.6850284 -0.7066968 0.1769632 -0.6365849 -0.746685 0.1929283 -0.6245822 -0.758015 0.1879105 -0.5911819 -0.7811177 0.2008963 -0.5833681 -0.7878226 0.1975277 -0.5407395 -0.8137696 0.2130252 -0.5214048 -0.8285433 0.2040914 -0.4860919 -0.8444752 0.2248924 -0.4667674 -0.8575962 0.2160018 -0.420409 -0.8765614 0.2343005 -0.4056828 -0.885428 0.2268013 -0.3329938 -0.9109309 0.2435569 -0.3213454 -0.9167248 0.2373878 -0.2590525 -0.9333791 0.2483854 -0.2504272 -0.936905 0.2439168 -0.1705082 -0.9522749 0.2531786 -0.1630114 -0.9546356 0.2491954 -0.07193672 -0.9637985 0.2567445 -0.06903094 -0.9644234 0.2551912 0.02101302 -0.9664049 0.2561646 0.01938807 -0.9662237 0.2569748 0.1068262 -0.9613242 0.253858 0.1020348 -0.9612079 0.2562584 0.1970428 -0.9482591 0.2489558 0.1887568 -0.9486605 0.2537997 0.2958162 -0.9247553 0.2394171 0.2829247 -0.9268462 0.2467991 0.3684542 -0.9004024 0.2313375 0.3548492 -0.903976 0.238557 0.4393462 -0.8708893 0.2202881 0.4211142 -0.8770899 0.2310327 0.5155948 -0.8301455 0.2121799 0.5017446 -0.8367111 0.2194699 0.5585701 -0.8039284 0.2042028 0.5450893 -0.8112191 0.2116633 0.6161435 -0.7637308 0.1925681 0.5955967 -0.777273 0.2027593 0.6637054 -0.725845 0.1806767 0.6401615 -0.7436221 0.1929235 -0.7107677 -0.693971 0.1149501 -0.6935459 -0.712587 0.1058951 -0.6510494 -0.749154 0.1220778 -0.6394324 -0.7600497 0.1159773 -0.6080211 -0.7835066 0.1281706 -0.5969105 -0.7928745 0.1226704 -0.5549646 -0.8199003 0.1406345 -0.5351461 -0.8345772 0.1307659 -0.5010124 -0.8521333 0.1511803 -0.4815964 -0.8648121 0.1420031 -0.4318048 -0.8877261 0.1596469 -0.4180657 -0.8955492 0.1523576 -0.3471813 -0.9227679 0.1672261 -0.3347045 -0.92855 0.160524 -0.2718948 -0.9467355 0.1725259 -0.2619692 -0.9504466 0.1674024 -0.1800222 -0.9678631 0.1755939 -0.1768549 -0.9687641 0.1738353 -0.07551968 -0.9809834 0.1787976 -0.07363265 -0.9813192 0.1777383 0.0245673 -0.9836229 0.1785565 0.02356934 -0.9835503 0.1790909 0.1183859 -0.9771297 0.1766419 0.1145576 -0.977228 0.1786118 0.2077367 -0.9629601 0.1719107 0.1997138 -0.9638643 0.1762953 0.3007835 -0.9392915 0.1651081 0.293384 -0.940875 0.169352 0.377776 -0.9123307 0.1579182 0.368136 -0.9153635 0.1630507 0.4533919 -0.8792161 0.1463379 0.4352904 -0.8865271 0.1568189 0.5246855 -0.8398737 0.1389872 0.5164662 -0.84417 0.143666 0.5723213 -0.8094509 0.1312921 0.5616685 -0.8158839 0.1373392 0.6287998 -0.7679557 0.1218801 0.6186019 -0.7752115 0.1279808 0.6702395 -0.733739 0.1113826 0.6568021 -0.7444878 0.1197873 -0.7270876 -0.6851714 0.04340189 -0.7092958 -0.7040654 0.03451758 -0.6629317 -0.7468694 0.05203455 -0.6551102 -0.7540007 0.04810041 -0.6117781 -0.7893337 0.05177021 -0.6158702 -0.7860013 0.05390751 -0.5695303 -0.8196854 0.06124758 -0.5551823 -0.8299986 0.0536189 -0.5070067 -0.859259 0.06795936 -0.4973196 -0.8652615 0.06321173 -0.4440097 -0.8926879 0.07722485 -0.4310072 -0.8996097 0.07025134 -0.3629301 -0.928316 0.08069181 -0.3568415 -0.9309802 0.07707196 -0.2807484 -0.9560145 0.08495163 -0.2741649 -0.9582468 0.08121973 -0.1822657 -0.9793388 0.08760601 -0.1811773 -0.9795976 0.0869686 -0.07611036 -0.9931193 0.08900135 -0.07533478 -0.9932197 0.08854025 0.02502954 -0.9956952 0.08924531 0.02575886 -0.9957147 0.08881884 0.1233936 -0.9883707 0.08886826 0.1226846 -0.9884232 0.08926379 0.2189834 -0.9720329 0.08484333 0.2113208 -0.9733512 0.08905571 0.3052911 -0.9489749 0.07901978 0.2965568 -0.9513103 0.08404064 0.3868332 -0.9190945 0.07500314 0.3833429 -0.9203975 0.07692211 0.467803 -0.8814437 0.06494379 0.4523267 -0.8888017 0.073704 0.5327851 -0.8441593 0.05945789 0.524744 -0.8488582 0.06390208 0.5886093 -0.8066958 0.05273663 0.5799695 -0.81261 0.05744856 0.6319224 -0.7733891 0.05043143 0.6303731 -0.774596 0.05129158 0.6848413 -0.7277631 0.03678661 0.6675018 -0.7431013 0.04734909 -0.7296341 -0.6829994 -0.03385317 -0.7199645 -0.6929401 -0.03853672 -0.6731945 -0.7388864 -0.02926123 -0.6703972 -0.7413679 -0.03067743 -0.6120958 -0.7902083 -0.03016334 -0.6198418 -0.7842906 -0.02616274 -0.5777782 -0.8157588 -0.02664607 -0.5742789 -0.8181628 -0.02852207 -0.5145927 -0.8571989 -0.02011477 -0.5068004 -0.8617253 -0.02414506 -0.4509549 -0.8924275 -0.01459366 -0.4436004 -0.8960345 -0.01846385 -0.3689165 -0.9293303 -0.01568579 -0.3732889 -0.9276231 -0.01307636 -0.2828361 -0.959093 -0.01202106 -0.2806665 -0.9597137 -0.01326733 -0.1823393 -0.9832004 -0.008336603 -0.1795405 -0.9837001 -0.009967088 -0.07399493 -0.9972196 -0.008830904 -0.07503765 -0.997147 -0.008207023 0.02343976 -0.9996874 -0.008699655 0.02474999 -0.9996488 -0.009476661 0.1213588 -0.9925737 -0.008340895 0.1226931 -0.9924028 -0.00912553 0.2239711 -0.9745258 -0.01168596 0.2174048 -0.9760496 -0.007903397 0.3136435 -0.9493792 -0.01752382 0.3026925 -0.9530215 -0.01128935 0.3935469 -0.9191513 -0.01679319 0.3957275 -0.9181915 -0.01800328 0.4716097 -0.8815598 -0.02090048 0.4670647 -0.8840349 -0.01824933 0.544188 -0.8385121 -0.02751302 0.5334181 -0.8455744 -0.02165645 0.5963153 -0.8022507 -0.02832204 0.5953024 -0.8030222 -0.02776038 0.6424085 -0.7656932 -0.03202295 0.636731 -0.7705354 -0.02913713 0.6947654 -0.7182687 -0.03729933 0.6873774 -0.7255468 -0.03307735 -0.7241541 -0.6801523 -0.1139903 -0.7137653 -0.6902072 -0.1189676 -0.6735273 -0.7302188 -0.1146368 -0.6773388 -0.7269879 -0.1126975 -0.6186838 -0.7767517 -0.1178444 -0.6259914 -0.7714743 -0.1138519 -0.5769373 -0.8081994 -0.1181406 -0.5807229 -0.805764 -0.1162117 -0.5225662 -0.8447148 -0.1156797 -0.5201665 -0.8460243 -0.1169184 -0.4497113 -0.8858118 -0.1144435 -0.4509298 -0.8852744 -0.1138055 -0.3658998 -0.9231948 -0.1175963 -0.3766023 -0.9196491 -0.1114284 -0.2811006 -0.9528074 -0.1146325 -0.2801684 -0.9530195 -0.11515 -0.1838458 -0.9767045 -0.110676 -0.1782823 -0.9773731 -0.1138303 -0.0745151 -0.9909559 -0.111597 -0.07524138 -0.990949 -0.11117 0.02055108 -0.9935589 -0.1114378 0.02260178 -0.9933819 -0.1126124 0.1184354 -0.9867464 -0.110927 0.1210795 -0.9862544 -0.1124376 0.2240013 -0.9679691 -0.1133992 0.2194127 -0.9693274 -0.1107369 0.3183919 -0.9407231 -0.116905 0.3107585 -0.9437952 -0.1126044 0.4008045 -0.9088784 -0.1153081 0.4023416 -0.9080932 -0.1161384 0.4707581 -0.8747721 -0.1147209 0.4729214 -0.873437 -0.1159877 0.5472024 -0.8287124 -0.1174958 0.5470947 -0.8287924 -0.1174334 0.5975906 -0.7931627 -0.1173823 0.6006652 -0.790573 -0.1191458 0.6391543 -0.7605683 -0.1140962 0.6501995 -0.7502002 -0.120168 0.6867579 -0.7181751 -0.1121969 0.6936904 -0.7107434 -0.1167795 -0.7132352 -0.6727377 -0.1967734 -0.7099728 -0.6757629 -0.1981998 -0.6608515 -0.723083 -0.2010632 -0.6748834 -0.711859 -0.1943947 -0.6162101 -0.759218 -0.2094596 -0.6346169 -0.7466599 -0.1994002 -0.5696813 -0.7933851 -0.2144842 -0.58104 -0.7867121 -0.2085106 -0.5176457 -0.8276337 -0.2169461 -0.5255592 -0.8236935 -0.2128772 -0.4426317 -0.8701246 -0.2167033 -0.4482769 -0.8679775 -0.2136889 -0.3596207 -0.9062489 -0.2222292 -0.3720781 -0.9029628 -0.2149793 -0.2750315 -0.9352432 -0.2228853 -0.2770025 -0.9349195 -0.2217998 -0.1856842 -0.9575449 -0.2205208 -0.1811973 -0.9578264 -0.223016 -0.08195286 -0.971709 -0.2215077 -0.08389955 -0.971805 -0.2203542 0.02083402 -0.975089 -0.2208336 0.01952266 -0.9752839 -0.2200917 0.1224617 -0.9683893 -0.2173137 0.1253401 -0.9676631 -0.2189017 0.2215319 -0.9507443 -0.2168155 0.2213798 -0.9507998 -0.2167271 0.3198293 -0.9218481 -0.218873 0.315967 -0.9237038 -0.2166477 0.4030209 -0.889476 -0.2154221 0.4084359 -0.8862779 -0.2183847 0.4695953 -0.8571578 -0.211568 0.4768842 -0.8521356 -0.2155147 0.5362142 -0.8181096 -0.2077765 0.5457857 -0.8103204 -0.2133045 0.5946555 -0.7771391 -0.206009 0.6048608 -0.7676309 -0.2118638 0.6341833 -0.7466306 -0.2008839 0.64986 -0.7306572 -0.2093371 0.672321 -0.7139108 -0.1957445 0.6858605 -0.6985512 -0.204014 -0.7012575 -0.6533063 -0.2853577 -0.703462 -0.6513715 -0.2843524 -0.6461813 -0.7052684 -0.2916269 -0.6656994 -0.6908515 -0.2820788 -0.6058924 -0.7351169 -0.3041341 -0.6312068 -0.7190731 -0.2907094 -0.5566211 -0.7699114 -0.312105 -0.5751578 -0.7601816 -0.3021879 -0.5032594 -0.8043292 -0.3158873 -0.5148541 -0.7993016 -0.309907 -0.4357336 -0.8415933 -0.3191505 -0.4437425 -0.8390625 -0.3147488 -0.3537299 -0.8759387 -0.3280345 -0.3675014 -0.873407 -0.3195354 -0.2669651 -0.9046597 -0.3321455 -0.2725995 -0.9041779 -0.3288645 -0.1833115 -0.9253006 -0.3319876 -0.1821863 -0.9252959 -0.3326194 -0.08828628 -0.9383981 -0.3340877 -0.09148579 -0.9387883 -0.3321247 0.01809126 -0.9429721 -0.3323798 0.0196762 -0.9425954 -0.333357 0.1224061 -0.9373067 -0.3263017 0.1317369 -0.9341179 -0.3317668 0.214011 -0.9218898 -0.3229839 0.2230803 -0.9177913 -0.328473 0.3137395 -0.8927811 -0.3232792 0.3195718 -0.8893747 -0.3269348 0.387824 -0.8654536 -0.3171476 0.4039353 -0.8543707 -0.3269358 0.4597206 -0.8319836 -0.3105806 0.4750025 -0.8199917 -0.3193528 0.5205583 -0.797968 -0.3037534 0.5333386 -0.7866731 -0.3109592 0.5811212 -0.7588852 -0.2939241 0.5984882 -0.7411013 -0.3042711 0.6257671 -0.7258046 -0.285698 0.6455579 -0.7034248 -0.2974033 0.6681294 -0.6888527 -0.2812206 0.6813216 -0.672533 -0.2889642 -0.6826815 -0.6309128 -0.3686396 -0.694367 -0.6215566 -0.3626596 -0.6320379 -0.6757028 -0.3794126 -0.6554923 -0.6598534 -0.3673191 -0.5871491 -0.7069492 -0.3943082 -0.6166121 -0.6903262 -0.3784697 -0.5391197 -0.7379459 -0.4059383 -0.5626073 -0.7273689 -0.3929472 -0.4850137 -0.7702552 -0.4140878 -0.5015509 -0.7643665 -0.4052044 -0.4143679 -0.8050754 -0.4244443 -0.4335065 -0.8005337 -0.4137849 -0.3424393 -0.8327672 -0.4350106 -0.3620057 -0.8305106 -0.4233253 -0.2627901 -0.8593062 -0.4387874 -0.2719936 -0.8592012 -0.4333509 -0.1690286 -0.8805302 -0.4428274 -0.1779623 -0.8813309 -0.4377046 -0.07960927 -0.8911652 -0.4466397 -0.08726847 -0.8927299 -0.4420607 0.01612019 -0.8953002 -0.4451717 0.01767796 -0.894794 -0.4461294 0.112492 -0.8918981 -0.4380221 0.1257167 -0.8862365 -0.4458478 0.2096334 -0.8758807 -0.4346113 0.2198486 -0.8703049 -0.4407221 0.2962023 -0.8537142 -0.4282949 0.3096369 -0.844667 -0.4366493 0.3684971 -0.83107 -0.4165725 0.3906708 -0.8138653 -0.430116 0.4477512 -0.7953835 -0.4085142 0.466553 -0.7783871 -0.42005 0.5045713 -0.7642629 -0.4016342 0.5237172 -0.7449973 -0.4131578 0.5551593 -0.7345426 -0.3901864 0.5796148 -0.7073661 -0.4045739 0.6030002 -0.7042499 -0.3747306 0.6314104 -0.6691178 -0.3919216 0.6532119 -0.6634357 -0.3649211 0.6772843 -0.6305404 -0.3790844 -0.6654156 -0.5984195 -0.4462244 -0.6762325 -0.5909489 -0.4398739 -0.6108326 -0.6428326 -0.4622228 -0.6385349 -0.627583 -0.4454357 -0.5651854 -0.6709634 -0.4799727 -0.5945861 -0.6581962 -0.4617847 -0.5134027 -0.6993288 -0.49735 -0.5434179 -0.6889988 -0.4795598 -0.4511419 -0.7317101 -0.5109515 -0.4797874 -0.7236833 -0.4960711 -0.3880296 -0.7589073 -0.5229654 -0.4146586 -0.7543104 -0.5089932 -0.3250615 -0.7797552 -0.5350858 -0.3505344 -0.7782227 -0.521052 -0.2514707 -0.8021491 -0.5415896 -0.2678049 -0.8029253 -0.5325332 -0.1507837 -0.8243175 -0.5456785 -0.1647987 -0.8268758 -0.5376969 -0.06493145 -0.8340422 -0.5478664 -0.07466477 -0.8367586 -0.5424576 0.02103394 -0.8356718 -0.5488264 0.01682007 -0.8373261 -0.5464451 0.1059054 -0.8322243 -0.5442307 0.1145014 -0.8279518 -0.5489858 0.199257 -0.8206962 -0.5354946 0.2134316 -0.8117063 -0.5436728 0.2787986 -0.8023408 -0.5277507 0.2904459 -0.7935961 -0.5346462 0.3474203 -0.7859994 -0.5113747 0.3732066 -0.7641827 -0.5260624 0.4341256 -0.7490138 -0.5005132 0.4516192 -0.7318125 -0.5103828 0.480069 -0.7303665 -0.4858999 0.5090264 -0.698849 -0.5024961 0.5278511 -0.7055476 -0.472838 0.5589038 -0.6681314 -0.4911487 0.5734648 -0.6791164 -0.458191 0.6081624 -0.6334437 -0.4784222 0.6165111 -0.6504729 -0.4436206 0.6475988 -0.6054495 -0.4626518 -0.6377348 -0.5659751 -0.522462 -0.6561939 -0.5541855 -0.5121406 -0.5813511 -0.6076052 -0.5411533 -0.615406 -0.5910814 -0.5214387 -0.5385088 -0.629257 -0.5603962 -0.5709166 -0.6176517 -0.5408888 -0.4856426 -0.6557163 -0.5780896 -0.5169522 -0.647823 -0.5595408 -0.4269831 -0.6823184 -0.593403 -0.4528621 -0.678687 -0.5781868 -0.3708316 -0.7031507 -0.606682 -0.3921959 -0.7025911 -0.5937576 -0.3115882 -0.7226379 -0.6170148 -0.3287943 -0.7238339 -0.6065961 -0.2322153 -0.743861 -0.6266952 -0.2473798 -0.7464836 -0.61771 -0.149966 -0.762582 -0.6292686 -0.1526887 -0.7635195 -0.6274746 -0.06109935 -0.7724853 -0.6320867 -0.06333744 -0.7734569 -0.6306766 0.01999789 -0.7738739 -0.6330241 0.02285867 -0.7723586 -0.6347753 0.09963792 -0.7713078 -0.6286147 0.1118721 -0.7638285 -0.6356498 0.1769851 -0.7671253 -0.6165997 0.1984729 -0.7514053 -0.6292842 0.2581416 -0.751092 -0.6076379 0.2773234 -0.7342472 -0.6196554 0.3207312 -0.7386488 -0.5928993 0.3528812 -0.7068816 -0.6130199 0.3981195 -0.7078456 -0.5834857 0.4232244 -0.6786298 -0.6002855 0.4449083 -0.6950104 -0.5648162 0.48302 -0.6483369 -0.5885159 0.5015719 -0.6686742 -0.5489084 0.534192 -0.6251853 -0.5690188 0.5421288 -0.6534348 -0.5283175 0.5801305 -0.5998812 -0.5509911 0.5905235 -0.6219604 -0.5142444 0.6192882 -0.5770892 -0.5324006 -0.6082681 -0.5353568 -0.5860061 -0.6277118 -0.5234661 -0.5761608 -0.5446199 -0.5805059 -0.6053117 -0.5853096 -0.5625273 -0.5839314 -0.5037558 -0.5939676 -0.6272422 -0.5408365 -0.5841469 -0.605201 -0.4576554 -0.6106638 -0.6462517 -0.4918863 -0.6041803 -0.6269084 -0.4005724 -0.6315107 -0.6638796 -0.4315506 -0.629801 -0.6458443 -0.3466476 -0.6479783 -0.6782032 -0.3719477 -0.6495211 -0.6631571 -0.2851064 -0.6649689 -0.6903122 -0.3105849 -0.6680721 -0.676178 -0.2046893 -0.6844217 -0.6997637 -0.2259055 -0.6898654 -0.6877881 -0.1453536 -0.6959711 -0.7032046 -0.1519811 -0.6987774 -0.6990078 -0.05881077 -0.7055023 -0.7062633 -0.06338882 -0.7080929 -0.7032684 0.01781749 -0.7069583 -0.7070308 0.01872986 -0.7063433 -0.7076217 0.08928298 -0.708285 -0.7002577 0.1009771 -0.6993302 -0.7076306 0.1642181 -0.7031156 -0.6918533 0.1784102 -0.6908804 -0.7006099 0.2378743 -0.6925523 -0.6810193 0.258189 -0.6721824 -0.6939087 0.3121507 -0.6737962 -0.6697468 0.3322005 -0.6522756 -0.6813071 0.3659266 -0.656256 -0.6598681 0.3841992 -0.6339379 -0.6712033 0.4156931 -0.6445505 -0.6416807 0.4485317 -0.6008933 -0.6616241 0.4776543 -0.6180486 -0.6243895 0.506051 -0.5736527 -0.6440769 0.513417 -0.6139228 -0.5995848 0.5526675 -0.5536405 -0.6229294 0.5603501 -0.5943279 -0.5768727 0.5956811 -0.5349395 -0.5991694 -0.5789943 -0.4964355 -0.6467747 -0.5973408 -0.4884649 -0.6360708 -0.5272098 -0.5370334 -0.6585174 -0.5527202 -0.5290424 -0.6439058 -0.4731071 -0.5617175 -0.6787069 -0.5046452 -0.5607971 -0.6563841 -0.4305361 -0.5684086 -0.7011066 -0.4627962 -0.5706678 -0.6783494 -0.377866 -0.5846014 -0.7179545 -0.4036307 -0.5895721 -0.6996335 -0.3137654 -0.5990973 -0.7366369 -0.3435471 -0.6076999 -0.7160142 -0.248849 -0.6083838 -0.7536202 -0.279554 -0.6163024 -0.7362207 -0.1855471 -0.6213483 -0.7612481 -0.2036913 -0.6269569 -0.7519541 -0.1293491 -0.6311149 -0.7648286 -0.1413802 -0.6356349 -0.7589336 -0.05508458 -0.6399171 -0.7664672 -0.06452345 -0.6451424 -0.7613332 0.02149862 -0.644699 -0.7641342 0.01553487 -0.6490939 -0.7605497 0.09745985 -0.6395855 -0.762517 0.0915935 -0.6445112 -0.7590891 0.1562536 -0.6354611 -0.7561575 0.1643969 -0.628077 -0.7605874 0.21712 -0.6344756 -0.7418219 0.2378605 -0.6120759 -0.7541788 0.2892474 -0.6206425 -0.7287927 0.3121882 -0.5920163 -0.7430042 0.3329465 -0.6141428 -0.7155245 0.3569855 -0.5829832 -0.7298576 0.3944098 -0.5986454 -0.6971834 0.4309861 -0.5467239 -0.7178747 0.4399396 -0.5957793 -0.6719377 0.4798105 -0.5313283 -0.6981921 0.4770644 -0.5921581 -0.6494293 0.5229346 -0.5155658 -0.678772 0.5389043 -0.5454407 -0.6419319 0.570104 -0.4876202 -0.6612171 -0.5414082 -0.4746784 -0.6939436 -0.5655128 -0.4645304 -0.6814739 -0.5012655 -0.4964794 -0.7086898 -0.5322153 -0.4852087 -0.693772 -0.4508906 -0.5201596 -0.7253494 -0.475262 -0.5210877 -0.7089385 -0.4055271 -0.5265377 -0.7471987 -0.4343028 -0.5333721 -0.7258756 -0.3545752 -0.5347088 -0.7670482 -0.3803651 -0.544017 -0.747909 -0.2942954 -0.5505945 -0.7811759 -0.3143439 -0.5601942 -0.766401 -0.2316437 -0.5618906 -0.794116 -0.2498168 -0.5715484 -0.7816164 -0.1756067 -0.569608 -0.8029379 -0.1881861 -0.5767685 -0.7949365 -0.1173834 -0.5822675 -0.8044785 -0.1215655 -0.5844248 -0.8022902 -0.04589313 -0.5861444 -0.8089058 -0.05289971 -0.5910714 -0.8048829 0.01500856 -0.5915299 -0.8061435 0.01877462 -0.5881313 -0.8085474 0.09017628 -0.5898832 -0.8024376 0.09307134 -0.5869175 -0.8042797 0.1489448 -0.5851168 -0.7971537 0.1573109 -0.576714 -0.8016573 0.2005094 -0.5819088 -0.7881487 0.2198538 -0.560795 -0.7982314 0.2548599 -0.5747324 -0.7776434 0.2774296 -0.5427983 -0.7927187 0.3047156 -0.5666876 -0.7655153 0.3321785 -0.5256716 -0.7831519 0.3570156 -0.5723884 -0.7381812 0.4017938 -0.5007261 -0.7667042 0.4099263 -0.5649605 -0.7160867 0.4475104 -0.5010012 -0.7407647 0.4624593 -0.5387228 -0.7042083 0.4918751 -0.486261 -0.7222252 0.5164434 -0.5066744 -0.6903385 0.5396732 -0.461771 -0.7039321 -0.5099657 -0.4525317 -0.7315396 -0.5276373 -0.4491184 -0.7210351 -0.4627504 -0.4710769 -0.7509652 -0.4992271 -0.4627728 -0.7325392 -0.4232191 -0.4785488 -0.7693352 -0.4512203 -0.4807762 -0.7518343 -0.3833779 -0.4835707 -0.7868804 -0.4087413 -0.4901708 -0.7698463 -0.330494 -0.4961385 -0.8028825 -0.3544869 -0.5056385 -0.7865549 -0.27446 -0.5042551 -0.8187788 -0.2963916 -0.5156642 -0.8038921 -0.2218999 -0.5099254 -0.8311057 -0.2371453 -0.5194386 -0.820942 -0.1677781 -0.5179862 -0.8387734 -0.1777653 -0.524915 -0.8323845 -0.1066505 -0.5315122 -0.8403098 -0.1082622 -0.5325264 -0.8394612 -0.04089188 -0.5379223 -0.842002 -0.042185 -0.5389401 -0.8412871 0.01090145 -0.5395883 -0.8418584 0.01445484 -0.5361878 -0.843975 0.07594275 -0.5346994 -0.841623 0.0785616 -0.5314832 -0.843418 0.1294697 -0.5366129 -0.8338372 0.1425588 -0.5205632 -0.841838 0.1895905 -0.5330955 -0.824539 0.2051721 -0.5141564 -0.8327952 0.2415251 -0.5245605 -0.8163958 0.2545801 -0.5065496 -0.8237698 0.2840886 -0.5237261 -0.8031218 0.3068979 -0.4889152 -0.8165634 0.3311838 -0.526129 -0.783266 0.3641318 -0.4696649 -0.8042531 0.3919523 -0.50792 -0.7670664 0.4205101 -0.4566199 -0.7840086 0.4311146 -0.5089823 -0.7450352 0.4650281 -0.4463109 -0.7645623 0.4777379 -0.4997745 -0.7224903 0.5072332 -0.4343426 -0.7443528 -0.4847503 -0.4253278 -0.7642732 -0.5018996 -0.4234529 -0.7541781 -0.4375876 -0.4380313 -0.7852679 -0.4630911 -0.4420167 -0.7682239 -0.4001001 -0.4421905 -0.8027375 -0.4216658 -0.4497207 -0.7873687 -0.3603218 -0.4430313 -0.820909 -0.3836157 -0.452827 -0.804852 -0.3140411 -0.4499756 -0.8360025 -0.3325517 -0.4597044 -0.823457 -0.2638005 -0.4586338 -0.8485661 -0.2795398 -0.4691939 -0.8376841 -0.2095623 -0.4658944 -0.8596664 -0.2245223 -0.4769524 -0.8497683 -0.1552679 -0.4718306 -0.86791 -0.1657761 -0.4801595 -0.8613741 -0.1047143 -0.4806856 -0.8706184 -0.1001443 -0.4767392 -0.8733217 -0.05424958 -0.4945487 -0.8674553 -0.04166281 -0.4822548 -0.8750398 0.008077383 -0.4966853 -0.8678931 0.01548814 -0.4879674 -0.8727245 0.0693376 -0.4821464 -0.8733426 0.06915485 -0.4824056 -0.873214 0.120032 -0.4723928 -0.8731766 0.1271878 -0.4628758 -0.877251 0.1650682 -0.47865 -0.8623496 0.1841454 -0.4553483 -0.8710618 0.2266342 -0.4756154 -0.8499571 0.2407534 -0.4561535 -0.8567157 0.2790727 -0.4636172 -0.8409385 0.291369 -0.4453673 -0.8466121 0.3182228 -0.465761 -0.8257126 0.3391411 -0.4332668 -0.835023 0.3677458 -0.4672666 -0.8040056 0.3896679 -0.4320371 -0.8133282 0.4086583 -0.4648434 -0.7854419 0.431221 -0.4254584 -0.7956342 0.4483603 -0.4633468 -0.764384 0.4757748 -0.4109299 -0.7776728 0.6261615 0.6191749 0.4738609 0.549267 0.7215457 0.4215182 0.5890733 0.6473895 0.4836111 0.4921846 0.7683204 0.4091923 0.5372631 0.6894035 0.4858716 0.4579696 0.7914407 0.4048277 0.500724 0.7018665 0.5066153 0.4167135 0.8115181 0.4096196 0.4095988 0.7858836 0.4632666 0.3788091 0.8205865 0.4279506 0.3255419 0.8417802 0.4306145 0.2756804 0.8838103 0.3779942 0.2557789 0.8731302 0.414995 0.2165844 0.9030933 0.3708286 0.1997964 0.882848 0.425042 0.143378 0.9184198 0.3687109 0.07169866 0.9155292 0.3958103 0.05094915 0.9284036 0.3680639 0.01234161 0.9231589 0.3842205 0.009137272 0.9254719 0.3787063 7.95338e-4 0.9236329 0.3832777 8.41031e-4 0.9235981 0.3833613 -0.006536722 0.9249445 0.3800462 -0.004685759 0.9235582 0.3834299 -0.04548788 0.9246454 0.3781028 -0.0394169 0.9220592 0.3850366 -0.1285052 0.9153472 0.3816097 -0.1150544 0.9110828 0.3958418 -0.2217887 0.8949339 0.3871732 -0.2003095 0.8920289 0.4051672 -0.288745 0.8725365 0.3940894 -0.2670341 0.8750679 0.4036693 -0.3557738 0.8378121 0.4141207 -0.3389496 0.8420473 0.4196063 -0.4384601 0.7872225 0.4336285 -0.4094171 0.7953203 0.4470384 -0.4823076 0.7622622 0.4316664 -0.4489328 0.7772914 0.4407692 -0.5344272 0.7217423 0.4398586 -0.4986577 0.7456063 0.4420542 0.6204791 0.6887866 0.3749385 0.5492005 0.7680488 0.3293629 0.5924873 0.7027369 0.3938525 0.4501591 0.8358992 0.3140534 0.4881422 0.7940512 0.3622153 0.4569709 0.8226479 0.3382721 0.4363123 0.833125 0.3399034 0.4153711 0.8515186 0.3199734 0.3834073 0.867598 0.3166587 0.3552691 0.8897885 0.2864615 0.331017 0.8882724 0.318434 0.2550491 0.9376262 0.2362354 0.2229852 0.9350684 0.2755442 0.2136015 0.9404182 0.2645526 0.1283109 0.9624238 0.2393259 0.112899 0.9680436 0.223932 0.05456233 0.975169 0.2146356 0.05259317 0.9758282 0.2121168 0.0110805 0.9784833 0.2060281 0.0105493 0.9786854 0.2050947 9.32238e-4 0.9786574 0.2054965 8.85049e-4 0.9786776 0.205401 -0.005295753 0.97838 0.2067478 -0.005982279 0.9786384 0.205502 -0.03496336 0.9761204 0.2143982 -0.03996133 0.9771967 0.2085419 -0.08843648 0.9733573 0.2115529 -0.07819038 0.9720035 0.2215752 -0.1794682 0.9531964 0.2433269 -0.175984 0.9532678 0.2455812 -0.2767584 0.9249851 0.2603989 -0.2433798 0.9302671 0.274535 -0.3374137 0.8996739 0.2770182 -0.3061895 0.909959 0.2796831 -0.4043302 0.8592362 0.313417 -0.3905399 0.8649598 0.3151556 -0.4532817 0.8235561 0.3410148 -0.4414315 0.8307902 0.3390071 -0.5267661 0.7712023 0.3574419 -0.4705415 0.8099316 0.3501452 0.6201843 0.7363933 0.2703635 0.5822589 0.7763837 0.2412528 0.5932925 0.7524948 0.2859293 0.4303876 0.8796215 0.2025653 0.4968504 0.8189979 0.2870233 0.385914 0.8941767 0.2269769 0.3615829 0.9016472 0.2372561 0.3658618 0.8991468 0.2401674 0.2876968 0.9400681 0.1830373 0.3451963 0.9102413 0.2286927 0.2320597 0.9627026 0.1391116 0.2709411 0.94685 0.1733962 0.1559164 0.9835472 0.09124165 0.1843332 0.9758762 0.1169916 0.07701337 0.9942491 0.07441627 0.06511288 0.9957118 0.06571441 0.03056722 0.997244 0.06760239 0.03716826 0.9966886 0.0723226 0.005227982 0.9979086 0.06443059 0.008458673 0.9976817 0.0675261 3.88159e-4 0.9979584 0.06386762 8.95422e-4 0.9979218 0.06443232 -0.00235486 0.9978874 0.06492495 -0.003358185 0.9979517 0.06388497 -0.01779514 0.9974444 0.06919509 -0.02267932 0.997592 0.06554347 -0.05906033 0.9957253 0.07101428 -0.0543614 0.9957818 0.07391577 -0.1344314 0.9867556 0.09078502 -0.1322469 0.9869875 0.09146904 -0.2155473 0.9674606 0.1325123 -0.2226598 0.9660161 0.1312837 -0.2690078 0.9463155 0.1792255 -0.300438 0.9353818 0.1865425 -0.3369724 0.913558 0.2277311 -0.3537721 0.9068371 0.2291115 -0.4458468 0.858219 0.2543246 -0.3916655 0.88532 0.2506127 -0.5472321 0.7969144 0.2558605 -0.4386512 0.8625609 0.2521385 0.6318798 0.7535081 0.1815314 0.6063401 0.778269 0.1632457 0.5347585 0.832261 0.1462028 0.5029186 0.8549498 0.1270194 0.4662746 0.8739327 0.1372208 0.3860477 0.9176465 0.09429758 0.3530964 0.9261246 0.1327256 0.2766324 0.9558785 0.09884774 0.2462398 0.9629827 0.109683 0.250602 0.9616075 0.1118474 0.1643596 0.9837618 0.0721029 0.2090778 0.9727306 0.1004076 0.1034607 0.9940357 0.03448408 0.1510733 0.9862104 0.06757116 0.04343831 0.9989792 0.01239657 0.06478548 0.9975844 0.02506464 0.02064388 0.9997341 0.01028323 0.0252245 0.9996075 0.01219213 0.004049122 0.9999319 0.01094359 0.004551649 0.9999269 0.01120305 2.67771e-4 0.9999405 0.01091682 4.34134e-4 0.9999392 0.01102429 -0.001772642 0.9999411 0.0107125 -0.001463472 0.9999395 0.01091307 -0.01146864 0.999877 0.01070022 -0.01174902 0.9998754 0.01054745 -0.03288304 0.9993126 0.01711612 -0.04374951 0.9989726 0.01182258 -0.08961141 0.9950407 0.04317313 -0.122711 0.991713 0.03804564 -0.1503877 0.985144 0.08291488 -0.1877348 0.9793724 0.07473564 -0.2144113 0.9709845 0.1059104 -0.236098 0.9661944 0.1035679 -0.3203666 0.9407223 0.1113856 -0.2836103 0.9517677 0.1170622 -0.4264633 0.8970757 0.1156907 -0.3669531 0.9225814 0.1191183 -0.5033832 0.8542645 0.1297599 -0.4775217 0.8690598 0.1292609 0.5800442 0.8120294 0.06447577 0.5813786 0.8110209 0.06514716 0.4930365 0.8687275 0.04720008 0.4767635 0.8781098 0.04024642 0.4290316 0.9027071 0.03243505 0.4341719 0.9001592 0.03476023 0.3462135 0.9379094 0.02149814 0.3438385 0.9388002 0.02071696 0.2820699 0.9590188 0.02682358 0.2515743 0.9676569 0.01873117 0.1718915 0.9843322 0.03928691 0.1594783 0.9865666 0.03540009 0.08443015 0.9959825 0.02984356 0.1031758 0.9938421 0.04040783 0.02889859 0.9994898 0.01360976 0.04781395 0.998488 0.02712249 0.007543504 0.9999647 0.003696203 0.02101898 0.9997065 0.01205396 0.001211345 0.9999977 0.001772761 0.003714919 0.9999879 0.003249049 8.34967e-5 0.9999988 0.001632034 2.68952e-4 0.9999985 0.001744449 -4.94503e-4 0.9999976 0.002143561 -0.001400291 0.9999977 0.001643419 -0.003884375 0.9999771 0.005548298 -0.009662747 0.9999499 0.00266081 -0.0179767 0.9996684 0.01843893 -0.0299521 0.9995095 0.009151935 -0.06267803 0.9973082 0.03804969 -0.08970463 0.9956726 0.02427715 -0.1378597 0.9895338 0.04263317 -0.1513466 0.9878109 0.03638595 -0.2536169 0.9670296 0.02306681 -0.2249693 0.9738169 0.03270375 -0.3310693 0.9434791 0.01550018 -0.3239896 0.9458957 0.01766979 -0.3797429 0.9247789 0.02407115 -0.3961582 0.9179172 0.02206474 -0.4736576 0.8797932 0.04015588 -0.4676564 0.8829751 0.04065293 0.5615974 0.8273267 0.01178598 0.5556638 0.8313512 0.009639382 0.4976706 0.8673109 0.009798705 0.4795668 0.8774904 0.005158424 0.4255511 0.9049181 0.005453348 0.4259919 0.9047098 0.005587935 0.34141 0.9399142 6.32355e-4 0.3461602 0.9381735 0.001964271 0.2869429 0.957947 0.001157701 0.283902 0.9588533 3.18761e-4 0.1763004 0.9843188 0.005899906 0.1740094 0.9847297 0.005326688 0.07909196 0.996842 0.007105529 0.08662301 0.9961908 0.01001775 0.02089124 0.9997723 0.004360616 0.02817261 0.9995687 0.008305251 0.003261566 0.9999944 8.09389e-4 0.007504642 0.9999663 0.003350555 3.87288e-4 1 2.2525e-4 0.001178085 0.9999991 7.0326e-4 1.76574e-5 1 1.83068e-4 8.10447e-5 1 2.20182e-4 -1.781e-4 1 3.4516e-4 -4.51402e-4 0.9999999 1.83204e-4 -0.001647174 0.9999977 0.001405775 -0.003365337 0.9999943 4.23706e-4 -0.01070201 0.9999305 0.004949927 -0.01503425 0.9998846 0.002193331 -0.05531924 0.9984252 0.009325563 -0.06489306 0.9978788 0.005189776 -0.1393768 0.9902073 0.007994592 -0.142921 0.9897106 0.006838202 -0.2606315 0.9654366 0.001844406 -0.2557988 0.9667251 0.003088593 -0.3292024 0.9442585 0.001314818 -0.3314594 0.9434694 5.52906e-4 -0.3729237 0.9278542 0.003793835 -0.3776906 0.9259275 0.002852499 -0.4722858 0.8814173 0.007057309 -0.4666647 0.8843975 0.00808531 0.5637962 0.8259121 0.001795172 0.5601473 0.8283927 6.93116e-4 0.5044187 0.8634579 0.001501619 0.4969252 0.8677935 -9.59043e-5 0.4258516 0.904793 3.7411e-4 0.425396 0.9050073 2.55306e-4 0.3401229 0.9403803 -0.001210272 0.3413988 0.9399181 -8.63946e-4 0.2894276 0.9571996 -6.65788e-4 0.286994 0.9579315 -0.001379966 0.1762511 0.9843453 -1.08379e-5 0.1764404 0.9843114 3.9652e-5 0.07811373 0.9969443 6.42518e-4 0.07934808 0.9968464 0.001084089 0.01954281 0.9998088 7.30475e-4 0.02080267 0.9997829 0.001288473 0.002527236 0.9999969 1.20982e-4 0.003253161 0.9999946 5.27754e-4 2.56742e-4 1 2.07267e-5 3.86211e-4 1 1.00556e-4 8.31869e-6 1 1.72681e-5 1.75601e-5 1 1.86905e-5 -1.57524e-4 1 2.69884e-5 -1.76332e-4 1 1.60865e-5 -0.001514673 0.9999989 9.34908e-5 -0.001615166 0.9999987 3.51105e-5 -0.01074421 0.9999424 7.26095e-5 -0.01050114 0.9999449 2.04529e-4 -0.05578559 0.9984428 1.19631e-4 -0.05559879 0.9984532 1.88037e-4 -0.1383503 0.990383 8.87057e-4 -0.1396775 0.990197 5.3984e-4 -0.2621924 0.9650157 2.36774e-4 -0.2606548 0.9654319 5.86459e-4 -0.3284491 0.9445216 4.89357e-4 -0.3292074 0.9442576 2.28139e-4 -0.3737083 0.9275462 5.79027e-4 -0.3728805 0.9278791 7.58406e-4 -0.4758766 0.879512 4.51984e-4 -0.4719837 0.8816065 0.00123918 0.5643979 0.825503 2.26824e-4 0.5637557 0.8259416 4.86567e-5 0.5074784 0.8616645 8.83581e-5 0.5044041 0.8634677 -5.49658e-4 0.4254592 0.9049776 -4.24443e-4 0.4258416 0.9047977 -3.30118e-4 0.3393201 0.9406701 -0.001286983 0.3401231 0.9403803 -0.001069962 0.2920197 0.9564121 -5.27461e-4 0.2894334 0.9571973 -0.001293361 0.1762875 0.9843387 -4.54852e-4 0.1762526 0.9843449 -4.67789e-4 0.07869631 0.9968987 -1.2075e-4 0.07812303 0.9969437 -3.24366e-4 0.01966947 0.9998065 5.58869e-5 0.01954102 0.9998092 1.28448e-6 0.002487123 0.999997 1.3546e-5 0.002526819 0.9999969 3.43569e-5 2.38684e-4 1 -1.21852e-7 2.56728e-4 1 1.1692e-5 0 1 -5.96168e-6 8.31707e-6 1 0 -1.65678e-4 1 -9.6218e-6 -1.575e-4 1 -4.43475e-6 -0.001707136 0.9999986 -1.23731e-4 -0.001514375 0.9999989 -9.09948e-6 -0.01186496 0.9999294 -6.93786e-4 -0.01074349 0.9999424 -1.03754e-4 -0.05803018 0.9983141 -0.001285731 -0.05579179 0.9984423 -4.87388e-4 -0.1373839 0.990518 -1.04768e-5 -0.1383487 0.9903836 -2.43809e-4 -0.2634078 0.9646847 2.96317e-4 -0.2621952 0.9650148 5.63527e-4 -0.3283452 0.9445577 4.11184e-4 -0.3284485 0.9445219 3.7548e-4 -0.3776346 0.9259546 -3.97289e-4 -0.3737074 0.9275466 4.63234e-4 -0.4825694 0.8758566 -0.001408517 -0.4758745 0.8795132 -3.46856e-5 0.5628673 0.8265474 -2.22192e-4 0.5643976 0.8255031 1.78711e-4 0.5081551 0.8612657 -2.54249e-4 0.5074797 0.8616636 -3.92054e-4 0.4223854 0.9064161 -8.8166e-4 0.4254633 0.9049757 -1.39934e-4 0.3381085 0.9411064 -0.001263082 0.339322 0.9406698 -9.32791e-4 0.2934126 0.9559859 -2.48041e-4 0.2920209 0.9564117 -6.41433e-4 0.1741573 0.9847179 -3.01975e-4 0.1762866 0.9843389 2.69546e-4 0.07908421 0.996868 -1.41431e-4 0.07869666 0.9968987 -2.81075e-4 0.01994794 0.9998011 -1.90135e-5 0.01966971 0.9998066 -1.3537e-4 0.002516329 0.9999969 -5.30082e-6 0.002487063 0.999997 -2.05466e-5 2.38814e-4 1 -5.71669e-6 2.38682e-4 1 -6.28442e-6 0 1 -5.86558e-6 0 1 -4.42705e-6 -1.83083e-4 1 -1.69219e-5 -1.65679e-4 1 -5.32337e-6 -0.001928687 0.9999982 -1.46591e-4 -0.001707136 0.9999986 -1.54263e-5 -0.01304715 0.9999147 -7.61419e-4 -0.011864 0.9999297 -1.33706e-4 -0.06039392 0.9981737 -0.001392602 -0.05802476 0.998315 -5.34531e-4 -0.1362742 0.9906712 -9.06469e-5 -0.1373806 0.9905183 -3.45876e-4 -0.2644761 0.9643923 3.4087e-4 -0.2634097 0.9646839 5.69819e-4 -0.3281463 0.9446269 4.73119e-4 -0.3283445 0.944558 4.05499e-4 -0.3799581 0.9250037 -3.09647e-5 -0.3776299 0.9259565 4.86457e-4 -0.4851558 0.8744276 -4.94506e-4 -0.4825664 0.8758595 8.30807e-5 0.5603773 0.8282374 -4.24015e-4 0.5628682 0.8265466 2.07163e-4 0.5067281 0.8621059 -6.19018e-4 0.5081533 0.8612666 -3.28236e-4 0.415911 0.9094038 -0.001648128 0.4223927 0.9064129 -1.29944e-4 0.337229 0.9414221 -0.001057624 0.3381102 0.9411062 -8.15952e-4 0.2925155 0.9562607 4.40801e-4 0.2934058 0.9559878 6.60593e-4 0.1666502 0.9860162 1.4604e-4 0.1741571 0.9847158 0.002057611 0.07844257 0.9969187 -1.28476e-4 0.0790829 0.996868 9.97974e-5 0.0202884 0.9997942 -3.29465e-5 0.01994818 0.999801 -1.75377e-4 0.002581477 0.9999967 -4.57922e-6 0.002516269 0.9999969 -4.11043e-5 2.04032e-4 1 -3.17022e-5 2.38807e-4 1 -9.00159e-6 -1.74353e-5 1 -4.27272e-5 0 1 -3.29647e-5 -1.64982e-4 1 -3.02176e-5 -1.83041e-4 1 -4.304e-5 -0.002105951 0.9999979 -1.29189e-4 -0.001928746 0.9999982 -2.36699e-5 -0.01410853 0.9999002 -6.7158e-4 -0.01304572 0.999915 -1.06451e-4 -0.06252807 0.9980425 -0.001280725 -0.06038779 0.998175 -4.84327e-4 -0.13461 0.9908987 -1.64674e-4 -0.1362677 0.9906719 -5.40109e-4 -0.2646884 0.964334 3.11573e-4 -0.2644773 0.9643919 3.56549e-4 -0.3277595 0.944761 4.95442e-4 -0.3281455 0.9446271 3.61007e-4 -0.3815041 0.9243671 1.53068e-4 -0.3799542 0.9250053 4.98922e-4 -0.485899 0.8740151 -6.16052e-6 -0.4851555 0.874428 1.6517e-4 0.557963 0.8298658 -3.85369e-4 0.5603807 0.8282352 2.1362e-4 0.5069251 0.8619902 -2.03768e-4 0.5067257 0.8621075 -2.44525e-4 0.4130762 0.9106964 -5.1672e-4 0.4159216 0.9094005 1.67198e-4 0.3379178 0.9411756 -3.04106e-4 0.3372291 0.9414225 -5.19353e-4 0.293993 0.9558075 6.501e-4 0.2925177 0.9562601 2.83605e-4 0.1639543 0.986468 6.13741e-5 0.1666517 0.9860156 7.44272e-4 0.07959789 0.996827 -3.08535e-4 0.078444 0.9969183 -7.2681e-4 0.02139878 0.9997711 -6.51867e-5 0.02028846 0.999794 -5.34862e-4 0.002739191 0.9999963 -2.80028e-5 0.002581059 0.9999967 -1.15025e-4 2.55299e-5 1 -1.65859e-4 2.03713e-4 1 -5.66977e-5 -9.49253e-5 1 -2.20063e-4 -1.81737e-5 1 -1.66634e-4 4.08397e-5 1 -8.82996e-5 -1.6236e-4 1 -2.18027e-4 -0.002095937 0.9999979 -3.48071e-5 -0.002106547 0.9999978 -4.00955e-5 -0.01450395 0.9998949 -1.6746e-4 -0.01410788 0.9999005 4.15759e-5 -0.06405496 0.997946 -8.36028e-4 -0.0625211 0.9980437 -2.47344e-4 -0.1306728 0.9914255 -4.61066e-4 -0.1345938 0.9908999 -0.001398682 -0.2603686 0.9655094 1.05782e-4 -0.2646785 0.9643364 -8.2167e-4 -0.3266121 0.9451584 4.77148e-4 -0.3277585 0.9447616 8.01172e-5 -0.3826465 0.9238949 2.1695e-4 -0.3815028 0.9243676 4.71422e-4 -0.4862805 0.8738029 9.37746e-5 -0.4858972 0.8740161 1.8108e-4 0.555549 0.8314839 -3.58198e-4 0.5579661 0.8298639 2.31324e-4 0.5078007 0.8614746 -3.56398e-5 0.5069239 0.8619909 -2.1849e-4 0.411799 0.9112748 -3.45612e-5 0.4130799 0.9106949 2.69183e-4 0.3392187 0.9407076 2.01139e-5 0.3379181 0.9411755 -4.14955e-4 0.2970487 0.9548621 7.51301e-4 0.2939925 0.9558078 -1.35737e-5 0.1640044 0.9864596 4.79716e-5 0.163954 0.986468 3.58869e-5 0.08158248 0.9966666 -3.47578e-4 0.07959967 0.9968264 -0.001089692 0.02296161 0.9997364 -1.86284e-5 0.02139633 0.9997708 -6.84053e-4 0.002909183 0.9999958 -5.01545e-5 0.002736449 0.9999963 -1.44132e-4 -4.13127e-4 0.9999999 -3.89244e-4 2.82588e-5 1 -1.24136e-4 -2.25729e-4 1 -4.68227e-4 -9.91807e-5 1 -3.70713e-4 5.12257e-4 0.9999999 -1.79022e-4 6.81554e-5 1 -4.77819e-4 -0.001626133 0.9999987 2.06896e-4 -0.002094864 0.9999978 -6.0672e-5 -0.01331114 0.999911 9.85074e-4 -0.014508 0.9998948 3.59238e-4 -0.06427973 0.9979319 1.45503e-4 -0.06405019 0.9979467 2.35051e-4 -0.1240738 0.9922726 -9.51966e-4 -0.1306475 0.991425 -0.002793133 -0.2474321 0.9689052 -3.37826e-4 -0.2603348 0.9655128 -0.003333032 -0.3236359 0.9461816 4.40159e-4 -0.3266078 0.9451598 -5.99777e-4 -0.3827405 0.9238559 3.78949e-4 -0.3826445 0.9238956 4.00056e-4 -0.4863308 0.8737748 1.91057e-4 -0.4862798 0.8738032 2.03447e-4 0.5534614 0.8328748 -3.67184e-4 0.5555493 0.8314837 1.37341e-4 0.5088952 0.8608285 -1.35006e-5 0.5078016 0.861474 -2.45239e-4 0.4107609 0.9117431 4.46407e-5 0.4118014 0.9112735 2.82707e-4 0.3406297 0.9401975 8.87088e-5 0.3392216 0.9407064 -3.90635e-4 0.300544 0.9537676 8.04194e-4 0.2970473 0.9548629 -6.57215e-5 0.1645714 0.9863653 4.89747e-5 0.1640045 0.9864597 -9.05469e-5 0.08342456 0.996514 -4.39258e-4 0.08158385 0.9966659 -0.001143872 0.02426552 0.9997056 -1.79457e-4 0.02295249 0.9997363 -7.3545e-4 0.003207683 0.9999949 1.42421e-5 0.002903699 0.9999959 -1.3628e-4 -2.38316e-5 1 2.13664e-4 -3.42711e-4 1 5.88921e-5 -1.23481e-4 1 2.56491e-4 -1.88163e-4 1 2.15987e-4 2.20094e-4 1 1.36358e-4 4.44658e-4 0.9999999 2.69635e-4 -0.001601397 0.9999988 7.52086e-5 -0.001611888 0.9999988 6.93216e-5 -0.01250845 0.9999218 3.00352e-4 -0.0132814 0.9999119 -9.64688e-5 -0.06392502 0.9979548 -4.30009e-5 -0.0642789 0.997932 -1.6942e-4 -0.1214743 0.9925945 -4.03513e-4 -0.1240732 0.9922724 -0.001132607 -0.2422519 0.9702134 9.32851e-5 -0.2474267 0.9689061 -0.001118123 -0.3219567 0.9467542 6.10153e-4 -0.323635 0.9461821 2.21031e-5 -0.3819296 0.9241912 7.40588e-4 -0.3827397 0.9238561 5.5974e-4 -0.485981 0.8739693 3.55785e-4 -0.4863306 0.8737748 2.74953e-4 0.5532626 0.8330067 -4.65425e-4 0.553461 0.832875 -4.16625e-4 0.5106315 0.8597997 -3.44501e-5 0.5088982 0.8608267 -4.03381e-4 0.4097954 0.9121775 4.52782e-5 0.4107634 0.911742 2.56495e-4 0.3420424 0.9396845 9.91816e-5 0.340632 0.9401966 -3.83616e-4 0.3040998 0.9526398 8.15209e-4 0.3005433 0.9537682 -6.19076e-5 0.1652042 0.9862594 3.99164e-5 0.1645704 0.9863654 -1.08162e-4 0.08519494 0.9963642 -4.32218e-4 0.08342778 0.9965132 -0.001124441 0.02545547 0.9996759 -2.11441e-4 0.02426838 0.9997053 -7.25735e-4 0.003465712 0.999994 -1.58494e-5 0.003209829 0.9999949 -1.52823e-4 2.55782e-4 1 2.01157e-4 -1.9852e-5 1 4.93883e-5 -2.6894e-5 1 2.81586e-4 -1.23432e-4 1 2.1807e-4 -5.76321e-5 1 1.10636e-4 2.24492e-4 1 2.85788e-4 -0.001711308 0.9999985 7.4321e-6 -0.001601397 0.9999988 7.45142e-5 -0.0124461 0.9999226 -4.20147e-5 -0.0125088 0.9999219 -7.3487e-5 -0.06436491 0.9979265 -3.00232e-4 -0.06392532 0.9979547 -1.49584e-4 -0.1210163 0.9926505 -3.05681e-4 -0.1214743 0.9925945 -4.35305e-4 -0.2407919 0.9705767 2.95889e-4 -0.24225 0.970214 -4.06564e-5 -0.3210721 0.9470545 6.85953e-4 -0.3219549 0.9467549 3.7985e-4 -0.3808523 0.9246356 8.80186e-4 -0.3819305 0.9241909 6.43201e-4 -0.4853326 0.8743295 4.57069e-4 -0.4859796 0.87397 3.09431e-4 0.5563155 0.830971 -6.83728e-4 0.5532597 0.8330075 -0.00149548 0.5136759 0.8579844 -8.99089e-5 0.510632 0.8597991 -7.51602e-4 0.4090628 0.9125063 2.52044e-5 0.4097948 0.9121778 1.79246e-4 0.343389 0.9391934 7.34343e-5 0.3420454 0.9396834 -3.90693e-4 0.3072761 0.9516202 7.00179e-4 0.3040987 0.9526406 -7.5856e-5 0.1655316 0.9862046 -7.31614e-5 0.1652034 0.9862596 -1.47257e-4 0.08686727 0.9962198 -3.96104e-4 0.08519816 0.9963635 -0.001065075 0.02664214 0.9996451 -1.48226e-4 0.02545732 0.9996757 -6.71528e-4 0.003680884 0.9999933 -2.5474e-5 0.003466963 0.999994 -1.44955e-4 3.53877e-4 1 5.01256e-5 2.60753e-4 1 -7.35621e-6 8.93672e-6 1 7.72672e-5 -2.52387e-5 1 5.38751e-5 -1.5735e-4 1 1.46678e-5 -5.86037e-5 1 7.60702e-5 -0.00177133 0.9999985 -3.00446e-5 -0.001711308 0.9999986 7.41725e-6 -0.01261532 0.9999205 -1.34623e-4 -0.0124461 0.9999226 -4.55101e-5 -0.06523752 0.9978697 -4.27988e-4 -0.06436461 0.9979265 -1.32476e-4 -0.1212444 0.9926227 -4.03867e-4 -0.1210161 0.9926505 -3.39754e-4 -0.2402091 0.9707211 3.54337e-4 -0.2407901 0.9705772 2.23021e-4 -0.3205131 0.9472438 7.06115e-4 -0.3210716 0.9470549 5.13965e-4 -0.3797893 0.9250726 9.00818e-4 -0.3808529 0.9246354 6.71425e-4 -0.4846034 0.8747339 4.72079e-4 -0.4853327 0.8743295 3.13157e-4 0.5544898 0.8321905 -4.47301e-4 0.5563205 0.830968 4.75328e-5 0.5148074 0.8573059 -1.13141e-4 0.5136748 0.8579849 -3.68463e-4 0.4077494 0.9130939 -7.44125e-5 0.4090652 0.9125052 1.9866e-4 0.3442544 0.9388765 -1.58953e-4 0.3433917 0.9391922 -4.66305e-4 0.3078848 0.9514237 -1.22778e-4 0.3072741 0.9516211 -2.76436e-4 0.1641908 0.9864284 -7.4398e-4 0.1655287 0.9862049 -4.48852e-4 0.08813083 0.9961088 -4.16236e-4 0.08686983 0.9962192 -9.30937e-4 0.02729362 0.9996275 -1.80319e-4 0.02664297 0.9996449 -4.72836e-4 0.003789603 0.9999929 -1.18951e-4 0.003681242 0.9999933 -1.81311e-4 3.70957e-4 1 -1.04375e-4 3.54763e-4 1 -1.16824e-4 1.74718e-5 1 -9.90449e-5 9.296e-6 1 -1.04533e-4 -1.75021e-4 1 -1.08657e-4 -1.58102e-4 1 -1.00009e-4 -0.00180453 0.9999985 -1.31695e-4 -0.001771569 0.9999985 -1.11964e-4 -0.01283276 0.9999176 -2.46657e-4 -0.01261532 0.9999204 -1.33164e-4 -0.06618273 0.9978075 -5.59457e-4 -0.06523716 0.9978698 -2.31404e-4 -0.121574 0.9925823 -5.35911e-4 -0.1212442 0.9926227 -4.42405e-4 -0.2397447 0.9708359 2.79095e-4 -0.2402074 0.9707217 1.73324e-4 -0.3200264 0.9474085 6.28526e-4 -0.320513 0.9472441 4.58226e-4 -0.3787187 0.9255114 8.29771e-4 -0.3797922 0.9250717 5.96302e-4 -0.4838299 0.8751621 4.08458e-4 -0.4846055 0.8747329 2.44973e-4 0.5501256 0.8350816 -7.91009e-4 0.5544947 0.8321872 5.6394e-4 0.5148716 0.8572672 -6.5764e-4 0.5148074 0.8573056 -6.74512e-4 0.4059076 0.9139139 -7.72963e-4 0.4077488 0.9130942 -3.38558e-4 0.3438417 0.9390268 -0.001307547 0.3442583 0.9388743 -0.001128971 0.3027654 0.9530609 -0.002841949 0.3078827 0.9514235 -0.001351475 0.1600185 0.9871101 -0.002790272 0.164183 0.9864284 -0.001746356 0.08847689 0.9960778 -0.001001 0.08813387 0.9961081 -0.001160264 0.02655607 0.999647 -8.37269e-4 0.02729415 0.9996274 -4.48558e-4 0.003614842 0.9999932 -9.15294e-4 0.003789961 0.9999925 -7.95659e-4 3.54059e-4 0.9999996 -9.28995e-4 3.71514e-4 0.9999995 -9.12156e-4 1.74782e-5 0.9999997 -9.27789e-4 1.76928e-5 0.9999996 -9.27387e-4 -1.84156e-4 0.9999995 -9.34397e-4 -1.75706e-4 0.9999996 -9.27925e-4 -0.001822412 0.999998 -9.46894e-4 -0.001804828 0.9999979 -9.31309e-4 -0.01301294 0.9999148 -0.00105971 -0.01283305 0.9999172 -9.47635e-4 -0.06692004 0.9977574 -0.00134927 -0.06618338 0.997807 -0.001043498 -0.1217513 0.9925598 -0.00128889 -0.1215727 0.9925818 -0.001228392 -0.2391898 0.9709728 -4.30863e-4 -0.2397403 0.9708369 -5.78422e-4 -0.3195266 0.9475773 -4.08395e-5 -0.3200245 0.9474093 -2.45213e-4 -0.3778975 0.9258475 1.39349e-4 -0.3787273 0.9255083 -6.75845e-5 -0.4835989 0.8752897 -3.21088e-4 -0.483834 0.8751597 -3.78337e-4 0.5446664 0.8386381 -0.004959106 0.5501291 0.8350782 -0.001584112 0.513298 0.8581917 -0.00567907 0.5148792 0.8572495 -0.004789888 0.4039365 0.9147647 -0.006398916 0.405888 0.9139065 -0.005462527 0.3431915 0.9392364 -0.007394134 0.3438588 0.9389968 -0.006798326 0.3002301 0.9538232 -0.009127199 0.3027654 0.9530354 -0.007531583 0.1579518 0.9874013 -0.009495675 0.1600033 0.9870814 -0.008337914 0.0883333 0.9960567 -0.008261263 0.08848583 0.9960443 -0.008118927 0.02614468 0.999624 -0.008266925 0.02655988 0.9996169 -0.007803976 0.00353223 0.999959 -0.008350193 0.003615498 0.9999596 -0.008234262 3.44827e-4 0.999965 -0.008365452 3.54499e-4 0.9999651 -0.008351325 1.74542e-5 0.9999651 -0.008368194 1.76529e-5 0.9999651 -0.008363127 -1.83323e-4 0.9999651 -0.00836426 -1.84691e-4 0.9999651 -0.00836271 -0.001823604 0.9999634 -0.008369445 -0.001822888 0.9999634 -0.008362174 -0.01307719 0.9998788 -0.008451223 -0.01301497 0.9998804 -0.00836414 -0.06707209 0.9977113 -0.008574604 -0.06692606 0.9977223 -0.00844568 -0.121506 0.9925562 -0.008271455 -0.1217426 0.9925259 -0.008443176 -0.2382996 0.9711663 -0.00702995 -0.239162 0.9709507 -0.007511258 -0.3187825 0.9478083 -0.006097793 -0.3195101 0.9475591 -0.006727576 -0.3772268 0.9261034 -0.005695819 -0.377938 0.9258111 -0.006056964 -0.4824422 0.8759121 -0.00524789 -0.4836238 0.8752567 -0.005812525 0.5411952 0.8398003 -0.04293417 0.5444997 0.837986 -0.03604775 0.5110171 0.8582037 -0.04845684 0.5130166 0.857225 -0.0444923 0.4031161 0.9135324 -0.05436813 0.4035527 0.9133822 -0.05365043 0.3412891 0.9379548 -0.06134092 0.3428519 0.93768 -0.05664825 0.2980607 0.9521428 -0.06770485 0.2998326 0.9518551 -0.06381511 0.1568799 0.9849446 -0.0726152 0.1576842 0.9849339 -0.07100027 0.08764648 0.9933487 -0.07467675 0.08817559 0.9934303 -0.07294827 0.02591735 0.9968161 -0.07540643 0.02609735 0.9968618 -0.07473689 0.003490269 0.9971327 -0.07559305 0.003526151 0.9971458 -0.07541722 3.44448e-4 0.9971404 -0.07557183 3.44562e-4 0.9971383 -0.07559859 8.31323e-6 0.9971349 -0.0756433 1.74038e-5 0.997139 -0.07558929 -1.73896e-4 0.9971397 -0.07558029 -1.83295e-4 0.9971351 -0.07564163 -0.001829445 0.997134 -0.07563394 -0.001820683 0.9971383 -0.07557892 -0.01305156 0.9970526 -0.07560449 -0.01305568 0.9970512 -0.07562166 -0.06673884 0.9949753 -0.07463335 -0.06695568 0.994912 -0.07527977 -0.120929 0.9899975 -0.07267248 -0.1212652 0.9898944 -0.07351177 -0.2369688 0.9691488 -0.0677967 -0.2378604 0.9688063 -0.06954681 -0.3165962 0.9467743 -0.05818319 -0.3182648 0.9458814 -0.06337141 -0.3767163 0.9246444 -0.05583667 -0.3769968 0.9244994 -0.05634278 -0.4809952 0.8753601 -0.04887342 -0.4821572 0.8746097 -0.05081796 0.5259627 0.8209766 -0.222173 0.5324137 0.8239946 -0.1938262 0.497457 0.8297973 -0.2529287 0.4961981 0.8289428 -0.2581497 0.3981599 0.867229 -0.2989692 0.379046 0.8498167 -0.3662456 0.3198932 0.8770872 -0.3583108 0.3225935 0.8810096 -0.3460569 0.2756839 0.8748316 -0.3983317 0.2769808 0.8766297 -0.393449 0.1479039 0.8899874 -0.4313316 0.1423435 0.8803799 -0.4524042 0.07926279 0.8905023 -0.4480214 0.07931554 0.8906578 -0.4477028 0.02361249 0.8922392 -0.4509453 0.02339249 0.8914212 -0.4525716 0.003208458 0.8926562 -0.4507268 0.003155827 0.8923995 -0.4512353 3.09258e-4 0.8926442 -0.4507619 3.11942e-4 0.8926643 -0.450722 1.52944e-5 0.8926836 -0.4506839 7.37051e-6 0.8926637 -0.4507232 -1.67702e-4 0.892628 -0.4507941 -1.56713e-4 0.8926975 -0.4506566 -0.001715302 0.8922781 -0.451483 -0.001652359 0.8926337 -0.45078 -0.01212453 0.8905218 -0.4547792 -0.01178711 0.8922746 -0.4513392 -0.06065511 0.8892877 -0.4533085 -0.06033706 0.8905884 -0.4507902 -0.1120215 0.8830124 -0.4557856 -0.110102 0.8907022 -0.4410523 -0.2192103 0.8739666 -0.4337389 -0.2177553 0.8797399 -0.4226586 -0.295049 0.8852275 -0.3596086 -0.2954779 0.8772169 -0.3783958 -0.3636267 0.8552221 -0.3692843 -0.3600449 0.87572 -0.3216865 -0.4672204 0.8319227 -0.299349 -0.4652904 0.841077 -0.2758522 0.6107619 0.5386489 0.5803684 0.6059801 0.5607055 0.5642673 0.5413137 0.6198764 0.5680958 0.5413004 0.6195442 0.5684707 0.4947755 0.6572319 0.5685451 0.4948099 0.6574792 0.5682291 0.4499473 0.6858969 0.5719203 0.4486405 0.6826657 0.5767923 0.4118883 0.6970701 0.5868914 0.4099197 0.6953253 0.5903292 0.3609692 0.7089567 0.6058728 0.3557098 0.7024665 0.6164507 0.2665341 0.7349571 0.6235365 0.2711476 0.7393976 0.6162551 0.1766482 0.7717331 0.6109202 0.1741322 0.768794 0.6153324 0.09215575 0.7814128 0.6171721 0.09474587 0.7850217 0.6121799 0.02286404 0.7905745 0.611939 0.02292859 0.7906636 0.6118214 8.21894e-4 0.7914164 0.611277 0.001283347 0.7922358 0.6102136 -0.01234322 0.7920546 0.6103256 -0.009615063 0.7961469 0.605027 -0.06231421 0.7901179 0.6097792 -0.06106221 0.7913606 0.6082926 -0.1630934 0.7595825 0.6296308 -0.1476008 0.7758525 0.6134062 -0.2362605 0.7407003 0.6289229 -0.2453009 0.7313643 0.636344 -0.3390432 0.7000738 0.6284476 -0.332857 0.7066064 0.6244307 -0.3928201 0.6950565 0.6021535 -0.3816708 0.7062264 0.5962983 -0.4338449 0.6891685 0.5803667 -0.4321994 0.6913273 0.5790253 -0.4747075 0.669314 0.5715518 -0.4765888 0.6666491 0.5730987 -0.5245893 0.633928 0.5682796 -0.5270458 0.6303982 0.5699307 -0.3544631 0.5489113 -0.7570022 -0.4957436 0.7637583 -0.4134144 -0.3258994 0.5584698 -0.7628245 -0.4283322 0.7163021 -0.5508565 -0.2339378 0.5138309 -0.8253793 -0.3478901 0.7152416 -0.6061369 -0.2224932 0.6367026 -0.7383134 -0.2584238 0.7093164 -0.6558106 -0.1747196 0.6630828 -0.7278696 -0.200923 0.7078768 -0.6771562 -0.09131836 0.6887602 -0.7192152 -0.1096312 0.7226234 -0.6824928 -0.04999142 0.7129395 -0.6994414 -0.05394077 0.7213774 -0.6904384 -0.01000535 0.7191707 -0.6947615 -0.01135736 0.7234025 -0.6903332 -0.001415014 0.7233199 -0.6905117 -0.001652181 0.7241714 -0.6896182 -1.38871e-4 0.7241702 -0.6896213 -1.5976e-4 0.7242476 -0.68954 1.25034e-5 0.7242473 -0.6895404 8.77998e-6 0.7242646 -0.6895222 2.57204e-4 0.7242581 -0.689529 2.96197e-4 0.7241269 -0.6896668 0.002662122 0.7241269 -0.6896616 0.002924025 0.7232323 -0.6905987 0.01959091 0.7233267 -0.6902281 0.02098524 0.7193665 -0.6943137 0.06594312 0.720919 -0.6898748 0.06981223 0.7094432 -0.7012964 0.1247266 0.7162083 -0.6866506 0.1432468 0.681087 -0.7180536 0.2293916 0.705304 -0.6707652 0.234872 0.6874421 -0.6872106 0.2648386 0.7061879 -0.6566271 0.269395 0.6526409 -0.708157 0.3286829 0.6921272 -0.6425943 0.3348579 0.6024261 -0.7245365 0.4239449 0.6946574 -0.5811384 0.4191864 0.6577682 -0.6257985 0.6028705 0.5970556 0.5292181 0.5228146 0.7066817 0.4767243 0.5620496 0.6286119 0.5375383 0.4885029 0.723286 0.4880804 0.5167052 0.660558 0.5446825 0.4639325 0.7284775 0.5040706 0.4762725 0.6787897 0.5589357 0.4359663 0.7323899 0.523009 0.4178559 0.7221334 0.5512894 0.4069921 0.7360565 0.5409052 0.3364571 0.7821733 0.5244059 0.3299642 0.7889509 0.5183438 0.2549886 0.8216438 0.5097867 0.2144072 0.8558496 0.4706922 0.197301 0.8200861 0.5371511 0.1394165 0.8649614 0.482084 0.07479608 0.8553413 0.5126374 0.06595522 0.8622269 0.5022101 0.01405829 0.8690822 0.4944681 0.0148698 0.8683674 0.4956985 7.69209e-4 0.8692947 0.4942936 2.27204e-4 0.8698917 0.4932428 -0.007307231 0.8677936 0.4968713 -0.008524358 0.8689704 0.4947909 -0.04677033 0.8625757 0.5037618 -0.04555094 0.8618091 0.5051833 -0.1540136 0.8437511 0.5141635 -0.1404457 0.8372752 0.5284367 -0.2256087 0.8361677 0.4999244 -0.1986622 0.8291347 0.5225601 -0.3097075 0.7935023 0.5238658 -0.3074253 0.7935828 0.5250867 -0.3869489 0.7483979 0.5386755 -0.3784413 0.7487404 0.5442151 -0.4425819 0.7193673 0.5353803 -0.4266784 0.7187828 0.5489051 -0.4808911 0.703404 0.5234183 -0.4612047 0.7045778 0.5393148 -0.5335632 0.6705768 0.5154001 -0.5021829 0.6842154 0.5288305 -0.5627674 -0.6387227 0.5247153 -0.5468072 -0.656044 0.5202002 -0.5146018 -0.6674966 0.538176 -0.5077081 -0.6745088 0.5359762 -0.4893798 -0.6783003 0.5481023 -0.4773528 -0.690196 0.5438417 -0.424696 -0.7079256 0.5643357 -0.4059308 -0.7235157 0.5583416 -0.3815603 -0.7230009 0.575918 -0.3672516 -0.7346844 0.5704081 -0.3259904 -0.7409237 0.5871647 -0.3163724 -0.7478376 0.5836502 -0.2637165 -0.7578413 0.5967665 -0.2545084 -0.7641839 0.5926622 -0.1931344 -0.7719233 0.6056678 -0.1871411 -0.7757659 0.6026322 -0.126399 -0.7830092 0.6090319 -0.1241352 -0.7843104 0.6078222 -0.05282229 -0.7875527 0.6139793 -0.05112963 -0.7884385 0.612985 0.0173996 -0.7889747 0.6141793 0.02049434 -0.7902426 0.6124513 0.08678597 -0.7869719 0.6108546 0.08520114 -0.7864589 0.6117379 0.1546697 -0.778794 0.6079122 0.1561403 -0.7791694 0.6070547 0.2212419 -0.7699944 0.5984652 0.2117947 -0.7683306 0.603996 0.2851626 -0.7564226 0.5886486 0.2763307 -0.7550143 0.5946384 0.3490969 -0.7384949 0.5768506 0.3371914 -0.7381798 0.5842881 0.3937385 -0.7256495 0.564272 0.3819186 -0.7253183 0.5727578 0.4508991 -0.7014689 0.5519344 0.4415838 -0.7029151 0.5575968 0.5036573 -0.6749208 0.5392693 0.4961342 -0.6762533 0.5445478 0.5354766 -0.6582557 0.5291165 0.5229455 -0.6624948 0.5363103 0.4248996 -0.411143 -0.8064874 0.4490178 -0.4233092 -0.7868878 0.406101 -0.4258795 -0.8085225 0.434227 -0.4367116 -0.7878642 0.4167539 -0.4497536 -0.7899607 0.4439553 -0.4581426 -0.770071 0.372336 -0.4416641 -0.8162714 0.4524524 -0.4694964 -0.7581951 0.3489293 -0.4363222 -0.82938 0.4016937 -0.4657431 -0.7884957 0.3980132 -0.4519454 -0.79833 0.2751194 -0.3165564 -0.9078003 0.4765641 -0.4380277 -0.7622458 0.2914834 -0.267683 -0.9183591 0.5874372 -0.4127812 -0.6960815 0.4380431 -0.3831065 -0.8132328 0.7286015 -0.3646916 -0.5797758 0.585189 -0.4100186 -0.699599 0.8203102 -0.3082862 -0.4817166 0.7285574 -0.3645389 -0.5799273 0.6498447 -0.4076982 -0.6414703 0.8140911 -0.3209638 -0.4839815 0.5304868 -0.4606741 -0.7115921 0.6312814 -0.4479452 -0.6331105 0.5117304 -0.4593025 -0.726067 0.5280787 -0.4830543 -0.6984207 0.4974597 -0.3063324 -0.8116 0.5065473 -0.3305422 -0.7963365 0.4487444 -0.1098741 -0.88688 0.4798611 -0.1761077 -0.8594878 0.4292788 0.01199048 -0.9030926 0.4431044 -0.01218134 -0.8963873 0.4336248 0.1705867 -0.8847993 0.4459426 0.1346055 -0.8848822 0.4177788 0.4451986 -0.7919968 0.4541171 0.3354983 -0.8253597 0.4019542 0.5743767 -0.7131088 0.4280311 0.5266723 -0.7344424 0.3969835 0.616509 -0.6799418 0.4078259 0.5893502 -0.697384 0.3924604 -0.400506 -0.8279915 0.4120929 -0.4120763 -0.8126332 0.3398411 -0.3971471 -0.8525153 0.3993629 -0.4246957 -0.8124918 0.2838979 -0.4001114 -0.8713856 0.4002261 -0.4456274 -0.8007718 0.263117 -0.3987753 -0.8784916 0.3879476 -0.4461726 -0.8064904 0.2602933 -0.3995067 -0.8790005 0.300204 -0.4182379 -0.857295 0.3094391 -0.4153717 -0.8554028 -0.0453003 -0.07592546 -0.996084 0.4097244 -0.4547438 -0.7907806 0.2044447 -0.2341727 -0.9504555 0.5091723 -0.4390652 -0.7402469 0.3689387 -0.3920078 -0.842742 0.6019007 -0.4177442 -0.6805919 0.5058538 -0.4350793 -0.744861 0.4753932 -0.460989 -0.7493267 0.6059917 -0.4220257 -0.6742911 0.3116416 -0.498126 -0.8091664 0.4770158 -0.4685264 -0.7435988 0.2882249 -0.5089448 -0.8111113 0.3095206 -0.5102649 -0.8023881 0.3102582 -0.4883193 -0.8156496 0.2992348 -0.4608477 -0.8355107 0.3723459 -0.2919056 -0.8809937 0.3567821 -0.2040197 -0.9116373 0.3882227 -0.08766859 -0.9173862 0.3841729 -0.07397133 -0.9202932 0.387703 0.002921462 -0.9217797 0.3899938 -0.003505706 -0.9208108 0.3988322 0.1658402 -0.9019035 0.4020445 0.1426301 -0.9044429 0.3947566 0.5079504 -0.7656069 0.4117037 0.4406945 -0.7976769 0.3738041 0.6074757 -0.7008879 0.3943769 0.5690327 -0.7215738 0.3469485 0.634984 -0.6902334 0.3709441 0.5908317 -0.7164624 0.3622564 -0.4029344 -0.8404846 0.3660745 -0.4051799 -0.8377463 0.3406786 -0.3879768 -0.8563949 0.3618547 -0.4008965 -0.8416313 0.3202384 -0.4053059 -0.8562561 0.3613417 -0.4275769 -0.8286195 0.250576 -0.3833627 -0.8889571 0.345497 -0.4282172 -0.8350221 0.1868552 -0.3555235 -0.9157993 0.2699595 -0.4032098 -0.874382 0.2044282 -0.3646093 -0.9084433 0.175258 -0.3350169 -0.9257691 0.2871401 -0.4201492 -0.8608282 0.1563594 -0.2467045 -0.9563937 0.388655 -0.4555747 -0.8008739 0.2777072 -0.4009096 -0.8730121 0.4537245 -0.4566583 -0.7652433 0.3907167 -0.4589023 -0.7979657 0.3183422 -0.4866731 -0.8135157 0.4590182 -0.4651341 -0.7569364 0.2429575 -0.4997157 -0.8314181 0.3184417 -0.4969988 -0.8072096 0.2307519 -0.5155821 -0.8251841 0.2376191 -0.5194636 -0.8207891 0.2253043 -0.545599 -0.8071925 0.226943 -0.5272009 -0.8188749 0.2841235 -0.3775766 -0.8813114 0.2916757 -0.3162834 -0.9027127 0.3392721 -0.1254768 -0.9322822 0.3386157 -0.1059135 -0.9349448 0.3499575 -0.01449036 -0.9366536 0.3523491 -0.02604621 -0.9355062 0.3596895 0.1688001 -0.9176765 0.3653417 0.1237776 -0.9226074 0.3461743 0.5424981 -0.7654145 0.3642722 0.4885318 -0.7928698 0.3083704 0.6415175 -0.7023981 0.3409557 0.598441 -0.724995 0.2731268 0.6695398 -0.6907375 0.3094711 0.6203433 -0.7206953 0.3189253 -0.4116442 -0.8537188 0.321676 -0.4144304 -0.8513355 0.3163884 -0.3836224 -0.8676015 0.3192007 -0.3859434 -0.8655395 0.3009901 -0.3925285 -0.8690951 0.3195524 -0.4050502 -0.8566333 0.2267102 -0.3630133 -0.903783 0.3108195 -0.408158 -0.8583697 0.1131975 -0.2998286 -0.9472535 0.2534564 -0.3859448 -0.8870211 0.09459644 -0.286568 -0.9533784 0.1263485 -0.3163701 -0.9401841 0.1400607 -0.3454082 -0.9279419 0.08332437 -0.2528235 -0.9639177 0.2291933 -0.4624035 -0.8565358 0.1590724 -0.4136219 -0.8964446 0.2785938 -0.4828096 -0.8302291 0.2343104 -0.4780235 -0.8465177 0.2358515 -0.4935123 -0.8371497 0.280695 -0.4919091 -0.8241577 0.2154607 -0.4981253 -0.8399095 0.2346212 -0.5008521 -0.8331267 0.2033895 -0.5146788 -0.8329097 0.2081512 -0.5234255 -0.8262559 0.1827818 -0.570356 -0.8008027 0.1794822 -0.5894898 -0.7875837 0.2219314 -0.4294303 -0.8754063 0.2200871 -0.4406969 -0.8702575 0.2732761 -0.164333 -0.9477947 0.273114 -0.1751455 -0.9459033 0.2822052 -0.028297 -0.9589367 0.2875306 -0.06003206 -0.9558883 0.2855933 0.1803216 -0.9412336 0.2950988 0.1061896 -0.9495476 0.2707525 0.5630735 -0.7807953 0.286949 0.5137454 -0.8085333 0.2453577 0.6606151 -0.7094979 0.2646483 0.6352949 -0.7255079 0.2329423 0.6771354 -0.6980154 0.2451873 0.6639942 -0.7063957 0.27393 -0.4105246 -0.8697309 0.2814043 -0.4181306 -0.8637005 0.2737385 -0.3771193 -0.8847873 0.2754333 -0.3787083 -0.8835817 0.2511902 -0.3637861 -0.8969745 0.2748078 -0.3820723 -0.8823273 0.1404206 -0.3048145 -0.9420033 0.267481 -0.3819969 -0.8846086 0.04130703 -0.2452956 -0.968568 0.1860115 -0.3380769 -0.9225529 0.0247482 -0.2345838 -0.9717808 0.0622974 -0.268329 -0.9613109 0.03615945 -0.2818152 -0.9587872 0.04481589 -0.2988446 -0.9532489 0.07827454 -0.4742314 -0.8769137 0.05372405 -0.4477354 -0.8925508 0.1251407 -0.5021131 -0.8556999 0.0799691 -0.4922 -0.8668011 0.1560733 -0.5046609 -0.8490929 0.1251982 -0.5035314 -0.8548578 0.1593993 -0.5068222 -0.8471856 0.1558498 -0.5060204 -0.8483244 0.1494169 -0.5237892 -0.8386415 0.1535828 -0.5325261 -0.8323631 0.1277955 -0.5890284 -0.7979437 0.1237183 -0.6285013 -0.7679062 0.1509611 -0.4592947 -0.8753623 0.1463519 -0.5039571 -0.8512395 0.1884863 -0.172156 -0.9668688 0.188993 -0.2000243 -0.9613906 0.195288 -0.02101492 -0.9805207 0.2000087 -0.05085295 -0.9784736 0.1994807 0.1709025 -0.9648834 0.2045415 0.1279821 -0.9704553 0.1909558 0.5593424 -0.8066425 0.1991598 0.5306321 -0.823872 0.1676197 0.6749948 -0.7185302 0.183781 0.6539804 -0.7338489 0.1440539 0.69212 -0.7072612 0.1678748 0.6721327 -0.721149 0.2165912 -0.4126921 -0.884745 0.2233926 -0.4175003 -0.8807891 0.2229632 -0.3771007 -0.8989341 0.2186556 -0.3728041 -0.9017799 0.1995905 -0.3284363 -0.9231973 0.2211778 -0.3519155 -0.9095251 0.07702392 -0.2451777 -0.9664136 0.2040469 -0.3373055 -0.9190158 0.033849 -0.2311303 -0.9723338 0.11528 -0.2840735 -0.9518471 0.008067905 -0.2132289 -0.976969 0.044016 -0.2443237 -0.9686942 0.006517887 -0.2389818 -0.9710022 0.02519255 -0.2775683 -0.9603756 0.01486533 -0.465537 -0.8849037 0.01914948 -0.4730333 -0.8808365 0.03612691 -0.5133371 -0.8574263 0.01546132 -0.5060751 -0.8623509 0.07512223 -0.5160617 -0.8532508 0.03613877 -0.5122141 -0.8580972 0.08526766 -0.5183379 -0.8509145 0.07518732 -0.5153964 -0.8536472 0.07895219 -0.5348514 -0.8412495 0.08235299 -0.5414361 -0.8366989 0.06466019 -0.5993732 -0.797854 0.06488716 -0.6410499 -0.7647515 0.0727086 -0.4775038 -0.8756162 0.07223379 -0.5327493 -0.8431848 0.09075379 -0.177038 -0.9800109 0.09256958 -0.2000832 -0.9753962 0.09516966 -0.01427352 -0.9953588 0.09739208 -0.02568131 -0.9949148 0.0957387 0.1695896 -0.9808535 0.0996021 0.1393041 -0.9852278 0.08939743 0.5712254 -0.8159105 0.09552508 0.544258 -0.8334616 0.07794582 0.6906691 -0.718958 0.08590006 0.6774762 -0.7305117 0.06951373 0.7037991 -0.70699 0.07785719 0.6944799 -0.7152874 0.1637438 -0.4200631 -0.8926001 0.1661803 -0.421755 -0.8913512 0.1745702 -0.3842998 -0.9065533 0.1671975 -0.3759219 -0.9114428 0.1805503 -0.3297913 -0.926628 0.1735823 -0.3185267 -0.9318852 0.1175246 -0.2476974 -0.961683 0.1691347 -0.2920849 -0.9413182 0.04644674 -0.2205069 -0.9742789 0.1450293 -0.2794237 -0.9491517 0.006232023 -0.1988403 -0.9800121 0.06161683 -0.2336917 -0.9703565 0.002924084 -0.212185 -0.9772253 0.02973812 -0.2462697 -0.9687451 0.00520116 -0.423246 -0.906 0.02974963 -0.4659318 -0.8843204 0.009451925 -0.5150755 -0.8570929 0.006364643 -0.513835 -0.8578654 0.02483195 -0.5202004 -0.8536831 0.009428739 -0.5181123 -0.8552606 0.02856236 -0.5227308 -0.8520193 0.02479034 -0.5213736 -0.8529685 0.02590179 -0.5374501 -0.8428977 0.02777522 -0.5412353 -0.8404124 0.02081918 -0.5940751 -0.8041402 0.02245736 -0.6188689 -0.7851732 0.02234983 -0.4700324 -0.8823662 0.02386319 -0.5065873 -0.8618584 0.02692323 -0.1796248 -0.9833668 0.02821421 -0.1928669 -0.9808192 0.0283991 -0.01745772 -0.9994443 0.02894997 -0.02028918 -0.9993749 0.02784705 0.1694509 -0.9851452 0.02982062 0.1537983 -0.9876523 0.02543663 0.5740069 -0.8184553 0.02766036 0.5624977 -0.8263362 0.02245426 0.6936108 -0.72 0.02439236 0.690125 -0.723279 0.02075308 0.7062946 -0.7076138 0.02240854 0.7044407 -0.7094091 0.1170925 -0.4280734 -0.8961265 0.1184325 -0.4290401 -0.8954879 0.1206822 -0.3901377 -0.9128134 0.115585 -0.384428 -0.9158904 0.1287637 -0.3376937 -0.9324071 0.119019 -0.3157603 -0.9413447 0.09478169 -0.2192187 -0.9710611 0.1192528 -0.2484165 -0.9612846 0.03418213 -0.1984635 -0.9795121 0.1039429 -0.2404424 -0.9650821 0.006660044 -0.1914031 -0.981489 0.04215538 -0.2096435 -0.9768687 0.001506745 -0.2034972 -0.9790744 0.01153486 -0.2146076 -0.9766323 0.001208782 -0.4099044 -0.9121278 0.009118616 -0.4235337 -0.9058345 0.001746356 -0.5151718 -0.8570852 0.001566708 -0.5150982 -0.8571298 0.005139708 -0.5209408 -0.8535773 0.001737594 -0.5204191 -0.8539093 0.005781114 -0.523333 -0.8521087 0.005124628 -0.5230661 -0.8522768 0.005134284 -0.5369757 -0.8435822 0.005654275 -0.5381129 -0.8428539 0.004078626 -0.5889653 -0.808148 0.004652082 -0.5961431 -0.8028648 0.00424391 -0.4616028 -0.8870766 0.004832565 -0.4730654 -0.8810141 0.00486201 -0.1762177 -0.9843392 0.005330622 -0.1813974 -0.9833955 0.004921138 -0.01650756 -0.9998517 0.005217313 -0.01827126 -0.9998195 0.004549443 0.1736077 -0.9848045 0.005175948 0.167724 -0.9858205 0.003871738 0.5771139 -0.8166545 0.004497647 0.5730071 -0.8195382 0.003205895 0.6946107 -0.7193788 0.003712832 0.6934678 -0.7204781 0.002881884 0.7067715 -0.7074361 0.003200232 0.7063364 -0.7078691 0.05878883 -0.4333849 -0.8992894 0.06164216 -0.4351441 -0.8982483 0.042939 -0.3779526 -0.9248288 0.05000126 -0.3842661 -0.9218674 0.04216212 -0.3287286 -0.9434828 0.03950768 -0.3230795 -0.9455469 0.03547632 -0.2015202 -0.9788417 0.03851252 -0.2059761 -0.9777989 0.01458108 -0.1878044 -0.9820982 0.03519278 -0.1986823 -0.9794319 0.002544999 -0.188162 -0.9821347 0.01562428 -0.1931978 -0.9810355 4.18391e-4 -0.2011221 -0.9795662 0.003154456 -0.203813 -0.9790049 1.64081e-4 -0.4076547 -0.9131363 0.001508176 -0.4099223 -0.9121193 2.15419e-4 -0.5151715 -0.8570872 2.11501e-4 -0.5151705 -0.8570878 7.08994e-4 -0.5210275 -0.8535396 2.12555e-4 -0.5209494 -0.8535876 7.86078e-4 -0.5233796 -0.8520994 7.06034e-4 -0.5233461 -0.85212 6.95501e-4 -0.5368285 -0.8436911 7.7081e-4 -0.5369992 -0.8435825 5.53438e-4 -0.5879902 -0.808868 6.38472e-4 -0.5890435 -0.8081011 5.69617e-4 -0.4599006 -0.8879703 6.62551e-4 -0.4616883 -0.887042 6.36385e-4 -0.175371 -0.9845023 7.15516e-4 -0.1762745 -0.9843409 6.22336e-4 -0.01615297 -0.9998694 6.82514e-4 -0.01653444 -0.9998631 5.52759e-4 0.1745737 -0.9846439 6.54472e-4 0.1735601 -0.9848232 4.43356e-4 0.5778055 -0.8161745 5.4553e-4 0.5770806 -0.8166871 3.40296e-4 0.6948089 -0.7191945 4.245e-4 0.6946067 -0.7193896 2.91704e-4 0.7068424 -0.7073711 3.39656e-4 0.7067716 -0.7074418 0.00308901 -0.4281112 -0.9037209 0.01004153 -0.4343482 -0.9006891 5.64861e-4 -0.3710123 -0.9286278 0.002793014 -0.3737354 -0.9275312 3.0903e-4 -0.3230985 -0.9463653 4.25229e-4 -0.3235145 -0.9462232 4.45426e-4 -0.1991942 -0.97996 2.37053e-4 -0.1986397 -0.9800726 2.05101e-4 -0.1865624 -0.9824432 4.43441e-4 -0.186717 -0.9824137 4.01608e-5 -0.1879279 -0.9821828 2.05755e-4 -0.1879827 -0.9821723 5.62652e-6 -0.2010626 -0.9795784 4.12092e-5 -0.2010951 -0.9795718 2.11933e-6 -0.4076467 -0.9131398 6.72206e-6 -0.4076512 -0.9131377 1.35219e-5 -0.5151767 -0.857084 1.41681e-6 -0.5151713 -0.8570873 5.47883e-5 -0.5210339 -0.8535361 1.39408e-5 -0.5210277 -0.8535398 6.29997e-5 -0.5233835 -0.8520973 5.43744e-5 -0.5233798 -0.8520995 5.52489e-5 -0.5368114 -0.8437023 6.16061e-5 -0.5368317 -0.8436895 4.23562e-5 -0.5879096 -0.8089268 5.06098e-5 -0.5880124 -0.808852 4.14924e-5 -0.4597384 -0.8880545 4.98364e-5 -0.4598965 -0.8879725 4.46011e-5 -0.1752815 -0.9845184 5.21532e-5 -0.175369 -0.9845028 4.18927e-5 -0.01611441 -0.9998703 4.74181e-5 -0.01615375 -0.9998695 3.268e-5 0.1746861 -0.9846243 4.29913e-5 0.1745709 -0.9846447 2.4606e-5 0.577853 -0.816141 3.25231e-5 0.5778003 -0.8161782 1.65969e-5 0.6948269 -0.719177 2.41185e-5 0.6948127 -0.7191907 8.43533e-6 0.7068559 -0.7073576 1.64514e-5 0.7068431 -0.7073705 -0.05112296 -0.4300313 -0.9013654 -0.04916799 -0.4316472 -0.9007015 -0.04046028 -0.3823215 -0.9231432 -0.04353541 -0.3797848 -0.9240499 -0.03945732 -0.3259278 -0.9445709 -0.03736227 -0.3306116 -0.9430271 -0.0320999 -0.2055999 -0.9781095 -0.03575515 -0.200214 -0.9790996 -0.01434117 -0.192203 -0.9812504 -0.03022193 -0.186666 -0.9819585 -0.002444446 -0.1901268 -0.9817566 -0.01350677 -0.1879545 -0.9820849 -4.01185e-4 -0.2030993 -0.9791581 -0.002872645 -0.2010655 -0.9795737 -1.39803e-4 -0.4098398 -0.9121577 -0.001469016 -0.4076459 -0.9131389 -5.52831e-5 -0.5152323 -0.8570505 -1.83042e-4 -0.5151766 -0.857084 -1.52111e-4 -0.5210182 -0.8535456 -5.15011e-5 -0.5210339 -0.853536 -1.63874e-4 -0.5233779 -0.8521007 -1.51169e-4 -0.5233836 -0.8520972 -1.59082e-4 -0.5368167 -0.843699 -1.6055e-4 -0.5368161 -0.8436993 -1.45782e-4 -0.5879126 -0.8089245 -1.47008e-4 -0.5879063 -0.808929 -1.73842e-4 -0.4597817 -0.8880321 -1.75459e-4 -0.4597138 -0.8880673 -2.18784e-4 -0.1752967 -0.9845157 -2.19998e-4 -0.1752843 -0.9845179 -2.3052e-4 -0.0161423 -0.9998698 -2.35691e-4 -0.01611441 -0.9998701 -2.27636e-4 0.174532 -0.9846515 -2.42999e-4 0.1746841 -0.9846245 -2.0689e-4 0.5777226 -0.8162333 -2.25564e-4 0.5778489 -0.8161438 -1.81546e-4 0.6947837 -0.7192188 -2.00631e-4 0.6948282 -0.7191758 -1.56819e-4 0.7068194 -0.7073942 -1.8237e-4 0.7068541 -0.7073594 -0.1098988 -0.4241983 -0.898876 -0.1023696 -0.4306896 -0.8966755 -0.1175836 -0.3842691 -0.9157027 -0.1088914 -0.3928671 -0.9131255 -0.1239604 -0.3212276 -0.9388539 -0.1167073 -0.3396806 -0.933272 -0.1000173 -0.2388129 -0.9659012 -0.1132512 -0.2182159 -0.9693071 -0.04553949 -0.2143468 -0.9756954 -0.08348566 -0.2022532 -0.9757684 -0.007636606 -0.1976603 -0.9802408 -0.02977758 -0.1935755 -0.9806334 -0.001681089 -0.211124 -0.977458 -0.009019315 -0.2041445 -0.9788992 -0.001029431 -0.4231352 -0.906066 -0.008559823 -0.410148 -0.9119789 -5.97134e-4 -0.5155504 -0.8568592 -0.001357018 -0.5152329 -0.8570491 -0.001617908 -0.5208562 -0.853643 -5.97857e-4 -0.5210181 -0.8535454 -0.001769483 -0.523312 -0.8521395 -0.001613974 -0.5233774 -0.8520995 -0.001706779 -0.53688 -0.8436568 -0.001734793 -0.5368162 -0.8436975 -0.00155884 -0.5880283 -0.8088389 -0.001570343 -0.587899 -0.8089329 -0.001842141 -0.4603491 -0.8877361 -0.001875162 -0.4597547 -0.888044 -0.002271234 -0.1759073 -0.9844041 -0.002327322 -0.1752932 -0.9845135 -0.002356171 -0.01668071 -0.9998582 -0.002444088 -0.01614177 -0.9998667 -0.00231105 0.172825 -0.9849499 -0.00248444 0.1745334 -0.9846481 -0.00207889 0.5762346 -0.8172818 -0.002290546 0.5777245 -0.8162287 -0.001803755 0.6942957 -0.7196876 -0.002005636 0.6947839 -0.7192158 -0.001624286 0.7065504 -0.7076609 -0.001805305 0.7068169 -0.7073944 -0.1572954 -0.4191725 -0.8941771 -0.1511555 -0.4244523 -0.8927443 -0.1714578 -0.3751262 -0.910979 -0.15841 -0.3877504 -0.9080507 -0.177421 -0.3150923 -0.9323298 -0.1709309 -0.3290677 -0.9287073 -0.1463176 -0.27188 -0.9511427 -0.1620278 -0.2568901 -0.9527615 -0.07482963 -0.2414093 -0.9675341 -0.1110884 -0.2333449 -0.9660277 -0.01135057 -0.2101914 -0.9775944 -0.0246796 -0.2016448 -0.9791478 -0.004906237 -0.2353519 -0.971898 -0.01306796 -0.2135707 -0.9768403 -0.004507303 -0.4666122 -0.8844506 -0.02464652 -0.4243957 -0.9051414 -0.00438404 -0.515859 -0.8566623 -0.005135536 -0.5155443 -0.8568475 -0.01128864 -0.5197402 -0.8542498 -0.004372656 -0.5208476 -0.8536385 -0.01263093 -0.5226964 -0.8524254 -0.01123279 -0.5232611 -0.8520984 -0.01218581 -0.5371814 -0.8433788 -0.01236826 -0.5368111 -0.8436119 -0.0110225 -0.5896598 -0.8075767 -0.01120764 -0.5879681 -0.8088065 -0.01283293 -0.4666424 -0.8843531 -0.01330232 -0.4602754 -0.8876765 -0.01567775 -0.1822492 -0.9831274 -0.01634776 -0.1758379 -0.9842835 -0.01607704 -0.02136027 -0.9996426 -0.01692676 -0.01662868 -0.9997186 -0.01566398 0.1612809 -0.9867843 -0.01698052 0.1730129 -0.9847732 -0.01411688 0.5667116 -0.8237954 -0.01555544 0.5763453 -0.8170583 -0.01225942 0.6914132 -0.7223555 -0.01355838 0.6943056 -0.7195526 -0.01116973 0.7051262 -0.7089939 -0.01225215 0.7065504 -0.7075567 -0.2110963 -0.4199153 -0.8826718 -0.2109193 -0.4200841 -0.8826338 -0.2201408 -0.3741701 -0.9008523 -0.2145273 -0.3792606 -0.9000775 -0.209404 -0.3383756 -0.9174159 -0.2205573 -0.3256312 -0.9194123 -0.1481552 -0.2977996 -0.9430618 -0.2015916 -0.2921277 -0.9348916 -0.05536544 -0.2504284 -0.9665507 -0.1292188 -0.2624378 -0.9562578 -0.01156759 -0.2282297 -0.9735386 -0.03405845 -0.2178166 -0.9753953 -0.005624532 -0.2653532 -0.9641349 -0.01372522 -0.2377794 -0.9712222 -0.009127199 -0.4775343 -0.8785657 -0.01445138 -0.4669148 -0.8841843 -0.02172595 -0.510918 -0.8593549 -0.009481608 -0.5158154 -0.8566473 -0.05039691 -0.5147271 -0.8558716 -0.02163881 -0.5195839 -0.8541454 -0.05757606 -0.5187077 -0.8530108 -0.04992651 -0.5217165 -0.8516567 -0.05560225 -0.5366162 -0.8419927 -0.05613934 -0.5357364 -0.8425171 -0.04937714 -0.596578 -0.8010348 -0.05104821 -0.5880261 -0.8072296 -0.05612319 -0.4922816 -0.8686249 -0.06021171 -0.4634024 -0.8841 -0.06911808 -0.209568 -0.9753481 -0.0737887 -0.1794991 -0.980987 -0.07102239 -0.03979778 -0.9966806 -0.07581061 -0.01949268 -0.9969317 -0.06965649 0.1271555 -0.989434 -0.07548093 0.1665818 -0.9831343 -0.06464451 0.540792 -0.8386687 -0.06967169 0.5702431 -0.8185161 -0.05690896 0.6840681 -0.7271948 -0.06129884 0.6919331 -0.7193546 -0.05311614 0.7018586 -0.7103332 -0.05658984 0.70529 -0.7066566 -0.2678911 -0.4193231 -0.8674114 -0.269572 -0.4176537 -0.8676961 -0.2727755 -0.3775948 -0.8848817 -0.2722324 -0.3780845 -0.88484 -0.255618 -0.3719149 -0.8923782 -0.2716045 -0.3564035 -0.8939842 -0.1804221 -0.3376332 -0.9238246 -0.2400479 -0.3372822 -0.9102845 -0.05453884 -0.2668889 -0.9621829 -0.1371486 -0.2884765 -0.9476136 -0.01685708 -0.2471217 -0.9688379 -0.04269158 -0.2426107 -0.9691839 -0.01747995 -0.2779366 -0.9604404 -0.02011042 -0.2714553 -0.9622409 -0.0398181 -0.4598476 -0.8871047 -0.02680504 -0.4783653 -0.8777518 -0.07911813 -0.4980657 -0.8635225 -0.04195278 -0.510426 -0.8588978 -0.1242675 -0.5050026 -0.8541253 -0.07920897 -0.5133688 -0.8545049 -0.1331228 -0.5095917 -0.8500558 -0.1229978 -0.5138103 -0.849041 -0.1272116 -0.5320071 -0.8371295 -0.1294721 -0.5288202 -0.8388005 -0.1119822 -0.5984246 -0.7933146 -0.1167281 -0.583656 -0.8035672 -0.1278141 -0.5021783 -0.8552663 -0.1378201 -0.4614831 -0.8763784 -0.1594987 -0.2304741 -0.9599177 -0.1707018 -0.1815388 -0.9684547 -0.1664972 -0.05637621 -0.984429 -0.1773012 -0.02184307 -0.9839143 -0.1655768 0.10448 -0.9806469 -0.1782873 0.1682093 -0.9694944 -0.155686 0.5173697 -0.8414812 -0.1655204 0.5680518 -0.8061763 -0.1303325 0.6679628 -0.7326931 -0.1440072 0.6881222 -0.7111609 -0.1074847 0.6864823 -0.7191587 -0.1272121 0.7031434 -0.699576 -0.3158715 -0.4143886 -0.8535265 -0.3144752 -0.4160145 -0.853251 -0.3108574 -0.3842725 -0.8693115 -0.3147439 -0.3808038 -0.8694394 -0.2994834 -0.3990144 -0.8666586 -0.3126688 -0.3901705 -0.8660285 -0.248946 -0.381173 -0.8903557 -0.2807687 -0.3812747 -0.8807944 -0.09559118 -0.3032055 -0.9481186 -0.1418248 -0.3102115 -0.940029 -0.05600148 -0.2768594 -0.9592773 -0.0645079 -0.2722139 -0.9600721 -0.07410705 -0.296469 -0.9521629 -0.06894677 -0.3110972 -0.9478739 -0.1457626 -0.4384751 -0.8868444 -0.105634 -0.4690323 -0.8768411 -0.2097895 -0.4811986 -0.8511382 -0.1569407 -0.494854 -0.8546866 -0.2068071 -0.4978967 -0.8422172 -0.2118297 -0.4968671 -0.8415766 -0.1983117 -0.5037575 -0.8407741 -0.2063566 -0.5004212 -0.8408302 -0.1888521 -0.5248889 -0.8299558 -0.1945182 -0.5177385 -0.8331325 -0.1722918 -0.5755908 -0.7993815 -0.1777242 -0.5625063 -0.8074657 -0.1997395 -0.4633707 -0.8633607 -0.2178953 -0.4047212 -0.8881006 -0.2395092 -0.2210811 -0.9453881 -0.2602139 -0.1439456 -0.954761 -0.2497646 -0.05826073 -0.9665523 -0.2663186 -0.008257865 -0.9638497 -0.2536041 0.1118493 -0.9608198 -0.2692686 0.190039 -0.944129 -0.2452225 0.4980739 -0.8317381 -0.2555954 0.5656729 -0.7840186 -0.2190349 0.6434666 -0.7334674 -0.2330962 0.6684745 -0.7062635 -0.19462 0.6604669 -0.7251942 -0.2166013 0.6834555 -0.6971173 -0.360488 -0.4085211 -0.8385457 -0.3593189 -0.4099222 -0.8383638 -0.3440726 -0.3987875 -0.8500486 -0.3569312 -0.3897157 -0.8489534 -0.3340536 -0.4194846 -0.8440622 -0.3543843 -0.417065 -0.83694 -0.2812677 -0.4013061 -0.8716892 -0.3211172 -0.4099919 -0.8536923 -0.1701701 -0.3541924 -0.9195597 -0.2286871 -0.3663973 -0.9019175 -0.1436827 -0.3235698 -0.9352315 -0.1430383 -0.3240117 -0.9351772 -0.1758332 -0.317072 -0.9319593 -0.1593659 -0.3614032 -0.9186895 -0.2946997 -0.4285749 -0.8540935 -0.2267668 -0.4546012 -0.8613447 -0.3635556 -0.4643304 -0.8076043 -0.3164402 -0.4748682 -0.8211978 -0.2736509 -0.4957337 -0.824235 -0.3681528 -0.475609 -0.7989115 -0.2342722 -0.5048972 -0.83078 -0.274015 -0.4925002 -0.8260506 -0.2263936 -0.5181301 -0.8247953 -0.2318777 -0.5128495 -0.8265702 -0.2234765 -0.5298703 -0.818105 -0.2196989 -0.5377913 -0.8139491 -0.2682757 -0.3754687 -0.8871592 -0.2741552 -0.3577964 -0.8926482 -0.3054007 -0.1744405 -0.9361096 -0.318334 -0.1297172 -0.9390617 -0.3204442 -0.03642624 -0.9465668 -0.3287117 -0.01261419 -0.9443461 -0.3328788 0.1466223 -0.9315007 -0.3430293 0.1965881 -0.9185227 -0.3257488 0.4831953 -0.8126562 -0.333678 0.5489282 -0.7663791 -0.2905873 0.5989527 -0.7462003 -0.3102269 0.6428582 -0.7003518 -0.2405776 0.605855 -0.7583285 -0.2834424 0.6717124 -0.6844435 -0.3938953 -0.4114194 -0.8219372 -0.401697 -0.4039835 -0.8218497 -0.3668137 -0.4179593 -0.8311184 -0.3926848 -0.4058835 -0.825262 -0.3619254 -0.4352947 -0.8243353 -0.3846566 -0.4339813 -0.8146776 -0.285093 -0.4112417 -0.8657958 -0.3206132 -0.4155408 -0.8511952 -0.2353693 -0.3900803 -0.8901903 -0.2505353 -0.3911858 -0.885554 -0.2311052 -0.3391512 -0.9119029 -0.2100086 -0.3637803 -0.9075023 -0.2715249 -0.3145348 -0.9095836 -0.2450128 -0.365663 -0.8979195 -0.4257347 -0.416033 -0.8035339 -0.3410341 -0.4370115 -0.8322961 -0.5306692 -0.4328476 -0.7287202 -0.4531596 -0.453591 -0.7673993 -0.3965764 -0.4806032 -0.7821431 -0.5372202 -0.441177 -0.7188584 -0.273885 -0.5069452 -0.8173088 -0.396367 -0.4777929 -0.7839689 -0.2570694 -0.5172832 -0.8162925 -0.2732628 -0.5094137 -0.8159812 -0.2876127 -0.4653841 -0.8370762 -0.2588274 -0.5113416 -0.8194743 -0.3446583 -0.2443645 -0.9063646 -0.3211523 -0.3116967 -0.8942632 -0.3626724 -0.1060035 -0.9258683 -0.3602271 -0.1140593 -0.9258655 -0.3753386 -0.001025557 -0.9268872 -0.3730545 -0.007082581 -0.9277824 -0.3845239 0.1473894 -0.9112726 -0.3960632 0.1968113 -0.8968832 -0.3775579 0.4380413 -0.8158247 -0.3926723 0.5340195 -0.7487534 -0.3490454 0.5616835 -0.7501193 -0.3738768 0.6123953 -0.6965545 -0.2894055 0.5375341 -0.7920237 -0.358861 0.650279 -0.669594 -0.4330282 -0.4133091 -0.8010382 -0.4412647 -0.4084553 -0.7990307 -0.4169695 -0.4305323 -0.8004864 -0.4324715 -0.428898 -0.7931048 -0.4031287 -0.4484797 -0.7977176 -0.4286391 -0.4513715 -0.7826446 -0.3499507 -0.4402825 -0.826853 -0.3992856 -0.4462637 -0.8008868 -0.3328192 -0.4419476 -0.8330149 -0.3522335 -0.4421438 -0.8248881 -0.3462609 -0.382829 -0.8564726 -0.3064771 -0.4009876 -0.8632964 -0.378414 -0.3253954 -0.8665568 -0.3276379 -0.351403 -0.8770231 -0.5449989 -0.3953924 -0.7393518 -0.4490987 -0.4187787 -0.7892623 -0.7011514 -0.3721609 -0.6081801 -0.5707818 -0.4235665 -0.70342 -0.7756444 -0.3370144 -0.5336638 -0.7050698 -0.3780891 -0.5999377 -0.5850031 -0.4400511 -0.6812683 -0.7739848 -0.3410236 -0.5335265 -0.4614698 -0.4961363 -0.7354552 -0.5843039 -0.4413954 -0.6809987 -0.468945 -0.4532948 -0.7580333 -0.4705529 -0.4517518 -0.757958 -0.4538317 -0.2655594 -0.8505968 -0.4635426 -0.2415161 -0.8525247 -0.4210571 -0.1439928 -0.8955318 -0.4347184 -0.09181481 -0.8958739 -0.4074895 -0.01332354 -0.9131127 -0.4145413 0.002937018 -0.9100258 -0.410012 0.1273329 -0.9031482 -0.4269014 0.1753697 -0.8871306 -0.3893314 0.3418685 -0.8553053 -0.4349195 0.5045683 -0.7458257 -0.358981 0.5020595 -0.7868095 -0.4107609 0.5934408 -0.6921731 -0.3305319 0.5233823 -0.7853787 -0.4048886 0.6386101 -0.6544024 -0.4717848 -0.4159507 -0.7774345 -0.4838041 -0.4108942 -0.7727221 -0.4625427 -0.4369759 -0.7714315 -0.4662659 -0.4368495 -0.7692584 -0.4516801 -0.4584924 -0.765356 -0.458996 -0.4592754 -0.7605188 -0.4266467 -0.4637113 -0.7764951 -0.4518764 -0.464565 -0.7615689 -0.4263007 -0.4803336 -0.7665164 -0.4247395 -0.4806322 -0.7671957 -0.4667335 -0.4340668 -0.7705492 -0.4246356 -0.4454843 -0.7881803 -0.488718 -0.3495826 -0.7993414 -0.4312598 -0.3581236 -0.8281078 -0.6477648 -0.3602992 -0.6712565 -0.5225547 -0.3943976 -0.7559016 -0.8794065 -0.2533094 -0.4030867 -0.6628553 -0.3867614 -0.6411229 -0.9752317 -0.1210556 -0.1851183 -0.8767262 -0.2600296 -0.4046429 -0.8949682 -0.2608851 -0.3618994 -0.9687259 -0.1435296 -0.2024097 -0.7038215 -0.460592 -0.5408236 -0.8684126 -0.3093094 -0.3875403 -0.6134943 -0.5644092 -0.5523287 -0.6671694 -0.52222 -0.5311981 -0.5990318 -0.5199017 -0.6089854 -0.6397629 -0.4770826 -0.6025743 -0.5728114 -0.3401361 -0.7457846 -0.6368038 -0.2307321 -0.7356926 -0.5220927 -0.1133087 -0.8453286 -0.5883851 -0.004151999 -0.8085702 -0.525735 0.1535494 -0.8366752 -0.565104 0.2345866 -0.7909656 -0.4626286 0.280153 -0.8411238 -0.5592133 0.5195486 -0.6460261 -0.3729224 0.390486 -0.8416945 -0.5061528 0.6154217 -0.6042066 -0.355829 0.4882109 -0.7968915 -0.4908459 0.6973929 -0.5222199 -0.5328741 -0.636723 0.5573412 -0.5058473 -0.6310313 0.5881479 -0.5615092 -0.5903711 0.5798012 -0.5307509 -0.5787673 0.619138 -0.5835705 -0.5457922 0.6012956 -0.5601849 -0.5313866 0.6354694 -0.6121514 -0.4914226 0.6194955 -0.5873342 -0.4748067 0.6554366 -0.6396175 -0.4301117 0.6370977 -0.6175748 -0.4150823 0.6680629 -0.6666498 -0.359117 0.6531563 -0.6459819 -0.3438692 0.6815141 -0.6935269 -0.2797282 0.6639071 -0.6765501 -0.2663667 0.6865339 -0.7110503 -0.192884 0.6761682 -0.6994228 -0.1856048 0.6901873 -0.7295601 -0.1025769 0.6761806 -0.7166752 -0.09233874 0.6912671 -0.7397277 -0.00169897 0.6729042 -0.7329118 0.003750324 0.6803134 -0.7311859 0.09066492 0.6761266 -0.7386736 0.08470869 0.6687194 -0.7178518 0.1737192 0.6741739 -0.731332 0.1593028 0.6631563 -0.6957584 0.304269 0.6506464 -0.7177054 0.2655938 0.6437072 -0.6465099 0.5145437 0.5632672 -0.6742182 0.4897198 0.552815 -0.6123059 0.5042991 0.608904 -0.6505987 0.4864364 0.5831818 -0.624819 0.4409625 0.6443238 -0.6141857 0.4448267 0.6518476 -0.6322546 0.3758161 0.6775075 -0.632281 0.3758036 0.6774898 -0.6260808 0.3609218 0.6912006 -0.6356324 0.3529697 0.6865741 -0.6130146 0.402434 0.679897 -0.6203714 0.3952273 0.6774474 -0.5900118 0.4624054 0.6618666 -0.6037001 0.4405916 0.6643985 -0.4894247 -0.6561291 0.5744198 -0.4796494 -0.6529132 0.5862088 -0.5106591 -0.6155201 0.6003019 -0.4869196 -0.6058163 0.6292027 -0.5367591 -0.5703033 0.6218069 -0.5055404 -0.5538501 0.6615731 -0.5669407 -0.5163869 0.6418122 -0.5391562 -0.4988867 0.6785445 -0.595615 -0.4525516 0.6636564 -0.5690343 -0.434786 0.6979693 -0.6242064 -0.3835117 0.6806505 -0.5989341 -0.365212 0.7126698 -0.6521705 -0.3015423 0.6955185 -0.6285741 -0.2828198 0.7245051 -0.670543 -0.2096519 0.7116307 -0.6564507 -0.2007659 0.7271627 -0.6814279 -0.1114712 0.7233466 -0.6729737 -0.1048877 0.7321919 -0.6872327 -0.006833493 0.7264053 -0.6844519 -0.004542171 0.729044 -0.6831989 0.09405517 0.7241498 -0.6929281 0.08657854 0.7157896 -0.670104 0.1846696 0.7189282 -0.6887568 0.1676201 0.7053493 -0.6347962 0.3536619 0.6869913 -0.6730232 0.2867738 0.6817629 -0.5975279 0.5397725 0.5929639 -0.6276906 0.5089128 0.5890776 -0.5840437 0.5106701 0.6309589 -0.5900076 0.5076067 0.6278747 -0.5771279 0.443734 0.6855827 -0.5449206 0.4554123 0.7040321 -0.5852161 0.3785707 0.7170819 -0.5702884 0.3862044 0.7249947 -0.5792505 0.3723389 0.7251432 -0.5864973 0.3650823 0.7230048 -0.5672319 0.4161767 0.7106652 -0.5756825 0.4052844 0.710165 -0.5333919 0.5086897 0.6758165 -0.5562777 0.4661033 0.6879701 -0.4315744 -0.6795133 0.5933002 -0.4197538 -0.6739457 0.6079506 -0.463012 -0.6346489 0.6187413 -0.4455483 -0.6241704 0.6417928 -0.4861987 -0.5900966 0.6445128 -0.4656147 -0.5789614 0.6693331 -0.5144303 -0.5394526 0.6665977 -0.4883668 -0.522706 0.6987679 -0.5479467 -0.478828 0.6859142 -0.5193389 -0.4604182 0.7199321 -0.5802962 -0.40714 0.7053322 -0.5522847 -0.3876004 0.7380702 -0.6029726 -0.3229762 0.7294591 -0.5749242 -0.302729 0.760143 -0.6182612 -0.2291423 0.7518291 -0.6001027 -0.2172325 0.7698615 -0.6305049 -0.1224865 0.7664598 -0.6185351 -0.1128846 0.7776064 -0.6394748 -0.006923139 0.768781 -0.6392078 -0.006666958 0.7690052 -0.6375585 0.102521 0.7635501 -0.6497442 0.09106701 0.7546783 -0.6170822 0.2081673 0.7588649 -0.64516 0.1778522 0.7430594 -0.5605584 0.4419431 0.7003289 -0.6225416 0.3455453 0.7021684 -0.5493708 0.5596467 0.6204735 -0.5724636 0.5381535 0.6186084 -0.5120347 0.5154224 0.6871393 -0.5033154 0.5199027 0.6901992 -0.4726743 0.429265 0.7696173 -0.3749293 0.4620143 0.8037232 -0.5231003 0.3547021 0.7749532 -0.4469307 0.3941309 0.8030652 -0.5285958 0.3723821 0.7628356 -0.5237823 0.3772355 0.7637706 -0.5190866 0.4290652 0.7392241 -0.5264073 0.4185767 0.7400602 -0.4686824 0.5721157 0.6730679 -0.502144 0.5136875 0.6956844 -0.3775534 -0.6954966 0.6113411 -0.3705726 -0.6923742 0.6191075 -0.4020978 -0.6535581 0.6412326 -0.3872426 -0.6419405 0.6617822 -0.4317888 -0.6110936 0.6634176 -0.4117586 -0.597501 0.6880752 -0.4611284 -0.5605944 0.6878187 -0.4389685 -0.5452637 0.7141388 -0.487369 -0.5024527 0.7141518 -0.4613497 -0.485796 0.7424007 -0.5142295 -0.4306647 0.7416846 -0.486072 -0.4110885 0.7711941 -0.5436433 -0.3459064 0.7647228 -0.5172921 -0.3272072 0.7907872 -0.5680097 -0.2488516 0.7844985 -0.5469052 -0.235041 0.8035238 -0.5858705 -0.1373741 0.7986766 -0.5674742 -0.1248192 0.8138755 -0.5907749 -0.01119959 0.8067587 -0.5844674 -0.006320357 0.8113926 -0.5847159 0.1031377 0.8046551 -0.5903421 0.09877139 0.801087 -0.566825 0.2229701 0.7930913 -0.5877586 0.2023712 0.7833172 -0.527228 0.4788106 0.7019765 -0.5616344 0.4422252 0.699288 -0.5047259 0.5713139 0.647188 -0.5236477 0.5609331 0.6412075 -0.4911381 0.5172931 0.7008504 -0.4888963 0.5181329 0.7017969 -0.4686629 0.4164218 0.7790688 -0.425879 0.4322513 0.7948496 -0.4818132 0.3468473 0.8047068 -0.4562351 0.3600125 0.8137817 -0.4767022 0.378117 0.7935885 -0.48041 0.3749306 0.792864 -0.4563873 0.4571866 0.763342 -0.4731951 0.4335153 0.76691 -0.4025592 0.6172388 0.6759899 -0.4303877 0.5794584 0.6920942 -0.3293101 -0.7135525 0.6183832 -0.3126902 -0.7084562 0.6327044 -0.3481204 -0.6718962 0.6537337 -0.3199569 -0.6574788 0.6821652 -0.3686459 -0.6298819 0.6836293 -0.3440884 -0.6159515 0.7086656 -0.3922871 -0.5829836 0.7115063 -0.366851 -0.5648661 0.7391527 -0.4199916 -0.5223845 0.7421061 -0.3966205 -0.5049262 0.7666432 -0.446351 -0.4520872 0.7722616 -0.4247028 -0.4352038 0.7938672 -0.4761096 -0.3673657 0.7989758 -0.4549382 -0.3507726 0.8185292 -0.5012721 -0.2670134 0.8230615 -0.4819092 -0.2528705 0.8389399 -0.516445 -0.1506471 0.8429651 -0.5005689 -0.1394439 0.8543924 -0.5259709 -0.02070486 0.8502505 -0.5139459 -0.01156812 0.8577447 -0.5194302 0.1036883 0.8481988 -0.5257658 0.09883034 0.8448686 -0.489865 0.2436661 0.837054 -0.5179365 0.2175963 0.8272809 -0.4530119 0.5014602 0.737101 -0.4835274 0.4711033 0.7377418 -0.4441624 0.5778532 0.6846937 -0.4511704 0.574406 0.6830103 -0.4418697 0.5237498 0.7283113 -0.4459075 0.5223768 0.7268349 -0.4323997 0.4208994 0.7974174 -0.4369981 0.4190443 0.7958861 -0.427551 0.3542739 0.8316793 -0.4350232 0.350145 0.8295501 -0.4139566 0.38858 0.8231924 -0.4237561 0.3806889 0.8218922 -0.3699092 0.5090196 0.777217 -0.3983228 0.472625 0.7861073 -0.342476 0.6345224 0.6928864 -0.3457491 0.6303556 0.6950607 -0.261345 -0.7264401 0.6355971 -0.2569433 -0.7243734 0.6397369 -0.2790957 -0.6880329 0.6698629 -0.2650405 -0.6787639 0.68486 -0.2990539 -0.6495702 0.6990174 -0.2803543 -0.6378825 0.7172918 -0.3242644 -0.6023816 0.7293758 -0.2991126 -0.5856868 0.7533279 -0.3464004 -0.5401968 0.7669383 -0.3250551 -0.5257179 0.7861043 -0.3696278 -0.4719346 0.8004081 -0.3462057 -0.4548277 0.8205325 -0.3963612 -0.3876793 0.8322274 -0.3743435 -0.3700092 0.8502706 -0.4191283 -0.2820861 0.8629941 -0.4017101 -0.2679901 0.8756771 -0.4313679 -0.1599248 0.8878884 -0.4210843 -0.1520612 0.8941842 -0.4390199 -0.0257126 0.8981094 -0.4348216 -0.02226138 0.9002414 -0.4313082 0.1131286 0.895084 -0.4431185 0.102566 0.8905764 -0.38999 0.2797341 0.8773009 -0.4323611 0.2381494 0.8696831 -0.3533043 0.5405998 0.7634972 -0.3949874 0.4955153 0.7735953 -0.3601576 0.5784023 0.7319408 -0.3581285 0.5795456 0.732032 -0.3669434 0.5284047 0.7655984 -0.3600456 0.5307551 0.7672459 -0.3664322 0.4275788 0.82638 -0.3713938 0.4254608 0.8252574 -0.3566707 0.3667876 0.8592165 -0.3702001 0.3586338 0.8569328 -0.3343088 0.4133057 0.8470042 -0.3528847 0.3967226 0.8473982 -0.3020937 0.5337139 0.7898665 -0.3118013 0.5218315 0.7940227 -0.2745451 0.6476509 0.7107555 -0.2783173 0.643198 0.7133274 -0.1902598 -0.7376822 0.6477856 -0.1868351 -0.736091 0.6505865 -0.2035153 -0.7000421 0.6844871 -0.193961 -0.6936597 0.693697 -0.2240722 -0.6591457 0.717857 -0.2139135 -0.6515502 0.727821 -0.2442018 -0.6109377 0.7530742 -0.2355363 -0.6040161 0.7613719 -0.2627933 -0.5535475 0.7902689 -0.25334 -0.5460754 0.7985116 -0.2851898 -0.486671 0.8257228 -0.2688038 -0.4742102 0.8383731 -0.3054699 -0.4038703 0.8623092 -0.2869888 -0.3894721 0.8751852 -0.3262695 -0.2960891 0.8977079 -0.3085449 -0.2816557 0.9085538 -0.3379831 -0.1698132 0.9257056 -0.3285335 -0.1628464 0.9303478 -0.3392581 -0.02849966 0.9402616 -0.3376396 -0.02725207 0.9408809 -0.3358879 0.1203333 0.9341837 -0.3416836 0.1151036 0.9327399 -0.3166998 0.2971034 0.9007946 -0.3385554 0.2760834 0.8995323 -0.2892014 0.5623496 0.7746776 -0.3163135 0.5380236 0.7813299 -0.2759717 0.5861994 0.7617151 -0.2899646 0.5783757 0.7624973 -0.278666 0.5335403 0.7985488 -0.2756348 0.5344846 0.7989692 -0.2821425 0.4337924 0.8556984 -0.2821087 0.4338023 0.8557046 -0.2709091 0.3812227 0.883899 -0.283239 0.3733271 0.8834041 -0.2476854 0.4430719 0.8615911 -0.2686519 0.422409 0.8656772 -0.2175304 0.558856 0.8002254 -0.2313984 0.5421075 0.8078208 -0.1742252 0.6798637 0.7123419 -0.1897562 0.6624033 0.7247169 -0.1297966 -0.7460837 0.6530788 -0.1229069 -0.743034 0.6578712 -0.1385025 -0.7072771 0.6932361 -0.1292669 -0.7020964 0.7002505 -0.1495615 -0.6668362 0.7300417 -0.1400299 -0.6605076 0.7376458 -0.1588519 -0.6210788 0.7674811 -0.1506122 -0.6150587 0.7739632 -0.1677095 -0.5647287 0.8080564 -0.1589363 -0.5579501 0.8145127 -0.1843423 -0.4983624 0.847144 -0.1683505 -0.4860188 0.8575803 -0.2002462 -0.4144818 0.8877536 -0.1882489 -0.404914 0.8947665 -0.2151309 -0.3041946 0.9280002 -0.2036583 -0.2948452 0.9335897 -0.2282018 -0.178678 0.9570779 -0.2204326 -0.1727073 0.9599905 -0.2323715 -0.03182119 0.9721065 -0.2305777 -0.03045529 0.9725773 -0.2307956 0.1231332 0.9651796 -0.2313528 0.1226617 0.9651063 -0.217397 0.3107492 0.9252965 -0.2323978 0.2959829 0.926491 -0.195627 0.577912 0.7923054 -0.2159317 0.5603078 0.7996429 -0.1775516 0.597152 0.7822309 -0.1958052 0.5860674 0.7862477 -0.1817849 0.5353609 0.8248291 -0.175555 0.5373117 0.8249101 -0.1863207 0.4380708 0.8794195 -0.1829387 0.4395084 0.8794122 -0.181311 0.3928322 0.9015593 -0.1889277 0.3878428 0.9021555 -0.1489078 0.4712251 0.8693524 -0.1710811 0.4507588 0.8760981 -0.1092511 0.5957015 0.7957411 -0.1239426 0.5781005 0.8064975 -0.08133369 0.7009844 0.7085236 -0.08757889 0.6940928 0.7145384 -0.05708986 -0.7514663 0.657297 -0.0527547 -0.7488742 0.6606092 -0.06089389 -0.7132984 0.6982101 -0.05692142 -0.7106862 0.7012027 -0.06426453 -0.673676 0.7362275 -0.06017297 -0.6708217 0.7391735 -0.06691563 -0.6279586 0.7753646 -0.06310325 -0.6251659 0.7779368 -0.07176035 -0.5699266 0.8185562 -0.06520605 -0.5649462 0.8225473 -0.07916617 -0.502658 0.8608529 -0.07056492 -0.4962559 0.8653039 -0.08563059 -0.4162322 0.9052173 -0.08178472 -0.4130722 0.9070187 -0.09494459 -0.3049173 0.9476345 -0.0941922 -0.3042784 0.9479149 -0.1010371 -0.1777769 0.9788703 -0.1036026 -0.1798806 0.9782175 -0.1082515 -0.03192067 0.9936109 -0.1093859 -0.032835 0.993457 -0.1107543 0.1242709 0.9860478 -0.112289 0.1229948 0.9860342 -0.1021611 0.3230924 0.9408372 -0.1119155 0.3137545 0.9428855 -0.08638548 0.5861734 0.8055672 -0.1007128 0.5745229 0.8122686 -0.07812613 0.6013799 0.7951344 -0.08649462 0.5963031 0.798086 -0.08675187 0.5339941 0.8410258 -0.07646292 0.5371837 0.8399924 -0.08787608 0.4422967 0.8925534 -0.08633267 0.4429482 0.8923809 -0.07705914 0.4094015 0.9090943 -0.08970528 0.4004102 0.9119347 -0.05274021 0.4937976 0.8679761 -0.0692107 0.4768042 0.8762806 -0.02931457 0.6245499 0.7804346 -0.03675514 0.6141829 0.7883073 -0.0116868 0.7202818 0.6935832 -0.01832193 0.7105191 0.7034393 0.0160765 -0.7510874 0.6600071 0.01425242 -0.7522177 0.6587606 0.01722937 -0.7116371 0.702336 0.0134918 -0.7139 0.7001177 0.0205298 -0.6715808 0.7406468 0.01661312 -0.6740458 0.7385028 0.02437222 -0.6253484 0.7799651 0.02059066 -0.6279619 0.7779716 0.0240696 -0.5685523 0.8222951 0.02415865 -0.5684807 0.8223419 0.020379 -0.5027965 0.8641646 0.02302569 -0.500885 0.8652076 0.01871532 -0.4150401 0.9096106 0.01923912 -0.414645 0.90978 0.02262121 -0.3014035 0.9532283 0.0187506 -0.3044578 0.9523413 0.02897548 -0.1745711 0.9842182 0.02545088 -0.1772971 0.9838283 0.0273779 -0.03136444 0.9991331 0.02761894 -0.03117275 0.9991324 0.02185773 0.125095 0.991904 0.02279269 0.1259009 0.9917811 0.01298403 0.3240572 0.9459484 0.01570361 0.3267675 0.9449743 0.01810753 0.5865966 0.8096769 0.01027011 0.580156 0.8144407 0.01863521 0.5999908 0.7997899 0.01816499 0.5997287 0.7999972 0.01708543 0.5353344 0.8444675 0.01819294 0.5356459 0.8442468 0.01509237 0.4438765 0.8959609 0.01742917 0.4447953 0.8954628 0.01183283 0.410707 0.9116906 0.01511836 0.4130726 0.9105727 0.01166307 0.4950355 0.8687945 0.01112949 0.4943963 0.8691655 0.005163013 0.6203758 0.7842878 0.008829236 0.6269146 0.779038 0.002031326 0.7194734 0.6945171 0.002634465 0.720516 0.6934334 0.08622729 -0.746371 0.6599207 0.08639675 -0.7462722 0.6600102 0.09024304 -0.7068506 0.7015828 0.08597445 -0.7095826 0.6993576 0.09852623 -0.6661272 0.7393018 0.09023422 -0.6714857 0.7355031 0.1107735 -0.6190571 0.7774944 0.1002078 -0.6260573 0.7733114 0.1197047 -0.5632254 0.8175867 0.1117281 -0.5688198 0.814838 0.1244544 -0.4967212 0.8589408 0.1179181 -0.5013998 0.8571428 0.1351836 -0.4051139 0.904217 0.1246885 -0.4131067 0.9021063 0.143882 -0.2958925 0.9443228 0.1378281 -0.3006473 0.9437239 0.147691 -0.1699697 0.9743191 0.1434804 -0.1732191 0.974376 0.1517372 -0.02637946 0.9880688 0.1477832 -0.02954465 0.9885784 0.1475405 0.1232433 0.9813476 0.1518677 0.1268963 0.9802213 0.1352948 0.3136869 0.9398382 0.1480442 0.3261016 0.9336705 0.1201225 0.570742 0.8122956 0.1349381 0.5834562 0.8008561 0.1097962 0.5932459 0.7974987 0.1211692 0.599564 0.7911011 0.1159561 0.5374379 0.8352933 0.1073172 0.5351802 0.8378933 0.1175745 0.4426767 0.8889396 0.1162468 0.4422017 0.8893505 0.107213 0.3984236 0.910914 0.119026 0.4061017 0.9060432 0.09212499 0.4769905 0.874067 0.09706044 0.4822103 0.8706621 0.06130075 0.6000924 0.7975784 0.06835997 0.6120903 0.7878277 0.02937358 0.7067178 0.7068855 0.03503102 0.7168699 0.6963263 0.1548645 -0.7372332 0.6576507 0.1510306 -0.7400378 0.6553883 0.1626763 -0.6961576 0.6992145 0.153097 -0.703304 0.6942081 0.1747516 -0.6571884 0.7331885 0.1644056 -0.6650102 0.7285138 0.1927497 -0.6111688 0.7676721 0.1803646 -0.6197504 0.763792 0.2114459 -0.555808 0.8039703 0.1988737 -0.5641381 0.8013722 0.2284891 -0.4849675 0.8441559 0.2141712 -0.4950917 0.8420302 0.2473613 -0.3927866 0.8857377 0.2333012 -0.4033627 0.8847989 0.2584962 -0.2862412 0.9226298 0.246808 -0.2954002 0.9229434 0.2671767 -0.1608958 0.9501207 0.2581215 -0.1679558 0.9514012 0.271012 -0.02296441 0.9623021 0.2698668 -0.02389734 0.9626011 0.2642221 0.1165971 0.957388 0.2749388 0.1258996 0.9531831 0.2431463 0.2923219 0.9248935 0.2662047 0.3158878 0.9106866 0.210376 0.5372292 0.8167783 0.2446677 0.5721615 0.7827956 0.2046275 0.5869818 0.7833135 0.2152557 0.5930233 0.7758791 0.2139211 0.5379743 0.8153659 0.2018925 0.5350247 0.8203585 0.2194937 0.4398446 0.8708383 0.2153131 0.4384769 0.8725699 0.210879 0.3841513 0.8988648 0.2223566 0.390994 0.8931301 0.1858239 0.4414035 0.8778569 0.2000177 0.4551085 0.8676804 0.1528813 0.5711188 0.8065052 0.1597418 0.5798692 0.7988957 0.1201455 0.6858447 0.717762 0.1245124 0.6945638 0.7085745 0.218651 -0.729974 0.6475568 0.2182123 -0.7302498 0.6473938 0.2396069 -0.6847236 0.6882892 0.2245897 -0.6939109 0.6841397 0.258022 -0.6444693 0.7197806 0.2443442 -0.6542687 0.7157014 0.2723767 -0.5982545 0.7535931 0.2592551 -0.6083282 0.7501492 0.2935969 -0.5397784 0.7889488 0.272459 -0.5548424 0.7860764 0.320403 -0.4662257 0.8246062 0.296796 -0.4833859 0.8235596 0.3429234 -0.377744 0.8600658 0.3252501 -0.3908579 0.8610706 0.3583195 -0.2752653 0.8920966 0.3451842 -0.2856506 0.8940088 0.3683227 -0.1527075 0.9170709 0.3600345 -0.1593238 0.9192341 0.377592 -0.02025973 0.9257504 0.3752591 -0.02211302 0.9266562 0.3647577 0.102196 0.9254772 0.3859354 0.1202331 0.9146573 0.3266742 0.2459827 0.9125659 0.3723961 0.2907658 0.8813492 0.2827258 0.4827613 0.8288594 0.3406543 0.5465509 0.7650078 0.304275 0.587656 0.7497181 0.3015941 0.5863958 0.7517852 0.3125374 0.5362112 0.7840906 0.302168 0.5341942 0.7895132 0.3145459 0.4329119 0.8447771 0.3163059 0.4334068 0.8438657 0.3034256 0.369194 0.8784241 0.3172309 0.3765434 0.8703904 0.2849848 0.4131172 0.8649382 0.2974108 0.4253563 0.8547624 0.2535752 0.5403478 0.8023241 0.2578203 0.545732 0.7973114 0.2189961 0.655863 0.7224158 0.2224652 0.6615969 0.7160997 0.2861469 -0.7170141 0.6356184 0.2820669 -0.7200202 0.634042 0.3077582 -0.6737097 0.6718633 0.2919381 -0.6843006 0.6682103 0.3318225 -0.6286308 0.7033613 0.3095358 -0.643839 0.6997565 0.3532524 -0.5778982 0.7356946 0.3308546 -0.5946972 0.7327145 0.3766954 -0.5166457 0.768881 0.3502765 -0.5374941 0.7670766 0.4042519 -0.4419097 0.8008098 0.3739424 -0.4651113 0.8023956 0.4280694 -0.3552592 0.8309919 0.4008266 -0.3760452 0.8354209 0.4506556 -0.255938 0.8552224 0.4277052 -0.2742888 0.8612979 0.4638429 -0.1399989 0.8747857 0.4497392 -0.1515987 0.8802004 0.4708228 -0.01449054 0.8821089 0.4649454 -0.01924133 0.8851303 0.4625846 0.09896087 0.8810349 0.4737002 0.1088648 0.8739317 0.4407605 0.2195027 0.8703728 0.4657947 0.2467175 0.8498035 0.4077335 0.4650981 0.7857717 0.4373126 0.5099075 0.740778 0.3969859 0.5801404 0.7112239 0.4061834 0.5842708 0.702597 0.3961019 0.5284633 0.7508861 0.4007552 0.5291321 0.7479402 0.3986989 0.4236374 0.81337 0.4030715 0.4246457 0.8106846 0.3915846 0.3556774 0.8486195 0.4029995 0.3610394 0.8409768 0.3720736 0.3952774 0.8398317 0.3836766 0.4072609 0.8288129 0.3314969 0.5111397 0.7929981 0.3401544 0.5271755 0.7787047 0.3060691 0.6351957 0.7091178 0.3051224 0.6335314 0.7110121 0.3498937 -0.6981178 0.6246647 0.3396409 -0.7062337 0.6211909 0.3680373 -0.6573578 0.6575936 0.3505406 -0.6704399 0.6539355 0.3909551 -0.6107522 0.6885753 0.3687267 -0.6270431 0.6861906 0.4197832 -0.5581609 0.7157084 0.3944237 -0.5759553 0.7160345 0.4493802 -0.4944344 0.7440378 0.4245496 -0.5131059 0.7459759 0.4794297 -0.4217016 0.7696201 0.4539672 -0.4407759 0.774358 0.5051515 -0.336423 0.794759 0.4828214 -0.3536645 0.8011273 0.529635 -0.237878 0.8141872 0.5090151 -0.2542614 0.8223471 0.5470731 -0.127318 0.8273459 0.5334973 -0.1386761 0.8343558 0.5552244 -0.009385645 0.8316477 0.5494686 -0.0141946 0.8353939 0.544673 0.09770101 0.8329382 0.5526251 0.1050989 0.8267768 0.5268118 0.2057452 0.824705 0.542878 0.2253525 0.8090116 0.4955239 0.4604232 0.7365233 0.511857 0.4896511 0.7058642 0.471503 0.5712633 0.6718208 0.4830862 0.5765593 0.658944 0.4673588 0.5187765 0.7158538 0.4750228 0.5197522 0.7100781 0.4685988 0.417244 0.7786673 0.4632439 0.4161739 0.7824349 0.4644192 0.3452299 0.8155558 0.4707257 0.3479982 0.8107494 0.4475003 0.377306 0.810792 0.4589854 0.3884347 0.7990313 0.4094505 0.4642915 0.7853559 0.4266176 0.5006554 0.7532209 0.3698602 0.6178922 0.6938391 0.3740358 0.6281813 0.6822651 0.3962859 -0.6837693 0.612713 0.3878455 -0.6905111 0.6105493 0.4252288 -0.6361471 0.6438148 0.3995622 -0.6544538 0.6419037 0.4556421 -0.5883738 0.6679869 0.4285756 -0.6080083 0.668318 0.4825174 -0.5364651 0.6923744 0.4572696 -0.5552927 0.6946615 0.5097971 -0.4727786 0.7187401 0.4840211 -0.4922738 0.7234571 0.5388696 -0.4008486 0.7409049 0.5132148 -0.4204042 0.7482453 0.5659306 -0.3186663 0.7603779 0.5459576 -0.3339968 0.7683597 0.5922282 -0.222781 0.7743607 0.5746004 -0.2363743 0.7835571 0.60678 -0.12227 0.7854095 0.6019023 -0.1262767 0.7885226 0.6073176 -0.009677171 0.7944002 0.6096922 -0.007708609 0.7926008 0.6017045 0.09423702 0.79314 0.610498 0.1024446 0.7853645 0.5887524 0.1938862 0.7847157 0.6080043 0.2191369 0.7630923 0.5476734 0.4155918 0.72618 0.5807279 0.4769971 0.6597188 0.5153365 0.5557445 0.6523623 0.5428002 0.5660753 0.6204248 0.5121246 0.5157964 0.6867914 0.5014681 0.5149769 0.6952185 0.5048433 0.4287106 0.7492266 0.4429293 0.4202826 0.7919446 0.5110434 0.3514079 0.7844407 0.4876976 0.3430621 0.8027824 0.499341 0.3642709 0.7861076 0.5104694 0.373398 0.7745934 0.4823532 0.4282783 0.7641422 0.4987835 0.4509639 0.7401667 0.430528 0.5589202 0.7086988 0.4506675 0.6107679 0.6510465 0.4583927 -0.6604386 0.5947244 0.4475522 -0.6686745 0.5937774 0.4802527 -0.6173822 0.6230542 0.4619972 -0.6309335 0.6232828 0.5072404 -0.5664139 0.6495249 0.4811525 -0.5863376 0.6516904 0.5385816 -0.5119401 0.669214 0.5105115 -0.5335209 0.6743394 0.5660271 -0.4530693 0.6887246 0.54207 -0.4718005 0.695388 0.5937253 -0.3791044 0.7097677 0.5685143 -0.3988214 0.7195367 0.619865 -0.3000292 0.7250862 0.5995995 -0.3158834 0.7353218 0.6431927 -0.2093963 0.7365164 0.626169 -0.2223944 0.7472972 0.6551195 -0.1149826 0.7467245 0.6488633 -0.1199367 0.7513932 0.6541032 -0.01131248 0.7563207 0.6581428 -0.008266687 0.7528477 0.6497712 0.08912819 0.7548866 0.6624237 0.09937942 0.7425084 0.6271463 0.1731969 0.7594013 0.659977 0.211825 0.7208055 0.5521523 0.296625 0.7791929 0.6293131 0.4474191 0.6354378 0.5430186 0.5298393 0.6514608 0.5891994 0.5518794 0.5901468 0.5419384 0.5146619 0.6643991 0.525728 0.5138614 0.6779061 0.5039932 0.4531505 0.7352859 0.3572198 0.4424909 0.8225545 0.5390449 0.3819814 0.7506803 0.4237143 0.3544409 0.8335694 0.5447282 0.3696976 0.752725 0.5386105 0.3642413 0.7597545 0.5369037 0.4152615 0.7343652 0.5417088 0.4233311 0.7261835 0.5008729 0.4999111 0.7065517 0.5073878 0.552727 0.661098 0.5037963 -0.641259 0.5787714 0.4933969 -0.6507498 0.5771346 0.5296115 -0.5922299 0.6072689 0.5007957 -0.6146342 0.6094493 0.5552309 -0.5421946 0.6306694 0.526358 -0.5648351 0.6355381 0.5847918 -0.4874392 0.6483994 0.5553486 -0.5103628 0.6565957 0.6177387 -0.4272251 0.6602104 0.5892035 -0.4503435 0.6708428 0.6458361 -0.3568616 0.6749413 0.6223729 -0.376986 0.6859545 0.6689513 -0.2785208 0.6891519 0.6477741 -0.2974089 0.701382 0.6892823 -0.1919139 0.6986122 0.6703892 -0.2084605 0.7121253 0.7019249 -0.09998804 0.7051978 0.6902465 -0.1107347 0.7150509 0.7100393 -0.002825796 0.7041565 0.7049842 -0.007431328 0.7091842 0.7025754 0.08440929 0.7065854 0.7139573 0.09519135 0.6936885 0.684536 0.1598941 0.7112274 0.7076104 0.1895754 0.6806972 0.6424742 0.2431738 0.7267004 0.6830655 0.3697206 0.6298636 0.6111429 0.5064668 0.6082729 0.6358775 0.5375533 0.5538017 0.6008535 0.5028545 0.6213796 0.6107321 0.504216 0.6105511 0.5952761 0.445276 0.6688614 0.5595365 0.4453651 0.6989771 0.6013938 0.3792911 0.7031813 0.5842034 0.3764935 0.7189987 0.5961999 0.3600096 0.7175924 0.6026476 0.3655731 0.7093464 0.5862624 0.4047737 0.7017512 0.5904284 0.411049 0.6945741 0.563883 0.4591432 0.6864572 0.5664386 0.4894579 0.6630071 0.5499365 -0.6113789 0.5690219 0.5221019 -0.6349967 0.5693759 0.5743621 -0.5684118 0.5890808 0.5489264 -0.5884599 0.5936285 0.6020776 -0.5197357 0.6061168 0.5747 -0.5418885 0.6132511 0.6312999 -0.4649872 0.620683 0.6056199 -0.4855949 0.6304144 0.6587791 -0.4052182 0.6338835 0.6345025 -0.4251322 0.6454992 0.6842523 -0.3384118 0.6459693 0.6628761 -0.3556265 0.6588817 0.7057642 -0.2613795 0.6584662 0.68702 -0.2764256 0.6720064 0.727859 -0.1775636 0.6623387 0.712497 -0.1902311 0.6753963 0.7430074 -0.08720588 0.6635776 0.7360841 -0.09398794 0.6703332 0.7503376 0.002627193 0.6610497 0.7499465 0.00218141 0.6614949 0.743793 0.07796823 0.6638472 0.7528657 0.08970445 0.6520327 0.7285769 0.1420398 0.6700749 0.7453517 0.1685296 0.6450183 0.7104244 0.2423398 0.6607334 0.7264784 0.3121315 0.6122117 0.6635822 0.4765048 0.5767164 0.6804546 0.515899 0.5204132 0.6215505 0.4861393 0.614283 0.6612118 0.4934958 0.5650317 0.6341621 0.4394026 0.6362106 0.6223473 0.4401446 0.6472685 0.6444212 0.3728892 0.6675891 0.642208 0.3726722 0.669839 0.6406641 0.3491196 0.6838605 0.6473076 0.3548904 0.6745709 0.6261649 0.3922585 0.673833 0.6308913 0.3993106 0.6652274 0.6096861 0.4345874 0.6628851 0.6108905 0.4506004 0.6509779 0.5924174 -0.5915871 0.5468696 0.5806935 -0.6004657 0.5497601 0.6128025 -0.5565258 0.5610278 0.6039144 -0.5634555 0.5637423 0.6436181 -0.5069753 0.5733514 0.6291792 -0.5189946 0.5786002 0.6713845 -0.4499247 0.5889065 0.6572427 -0.4621298 0.5953723 0.7021646 -0.3875634 0.5972936 0.6865538 -0.4008991 0.6065672 0.7270539 -0.3220825 0.6063461 0.7145186 -0.3336154 0.6149504 0.7504836 -0.2451846 0.6137256 0.7371034 -0.2586227 0.624334 0.7708048 -0.1644085 0.6154916 0.7589441 -0.1768823 0.626671 0.78311 -0.07792562 0.6169817 0.7768234 -0.08503687 0.6239506 0.789945 0.01145404 0.6130707 0.7860965 0.00640583 0.6180707 0.7853419 0.08276557 0.6135048 0.7875803 0.0864951 0.6101113 0.7708183 0.1368997 0.6221717 0.7808304 0.1598832 0.6039381 0.7593266 0.2783135 0.5881877 0.762081 0.3033006 0.57205 0.7104186 0.4424184 0.5473313 0.7184743 0.4924046 0.4912559 0.6514009 0.4577683 0.6050827 0.6973125 0.4768534 0.5351319 0.6574063 0.4316797 0.6176324 0.6681705 0.4314853 0.6061095 0.6869415 0.3636457 0.6291845 0.6867925 0.3636199 0.6293622 0.6900137 0.3382306 0.6399073 0.6925338 0.3415178 0.6354232 0.674224 0.3801006 0.6332027 0.6767728 0.3866986 0.6264525 0.6606553 0.4220904 0.6207852 0.6604053 0.4261938 0.6182425 -0.6479111 0.6043781 0.4636147 -0.6350662 0.6181392 0.463244 -0.6807101 0.5410522 0.4938586 -0.7130069 0.5013598 0.4901627 -0.7314118 0.4136772 0.5421329 -0.7524439 0.3822606 0.5363814 -0.7652175 0.3226215 0.5570976 -0.7691211 0.3171702 0.5548477 -0.8049141 0.2705054 0.528148 -0.7724425 0.3038094 0.5577028 -0.8509466 0.2916194 0.4368616 -0.7477349 0.3716936 0.550215 -0.8477761 0.3555486 0.3935238 -0.7528645 0.4236182 0.5037288 -0.8220467 0.408439 0.3967578 -0.7937851 0.4341955 0.4258868 -0.8080953 0.4329825 0.3993846 -0.8143311 0.4244197 0.3958952 -0.839784 0.2640461 0.4743865 -0.8624327 0.205692 0.4624941 -0.8567785 0.09708738 0.5064629 -0.8563609 0.09801226 0.5069907 -0.8581377 0.01996588 0.5130315 -0.858763 0.01864331 0.5120339 -0.853842 -0.07138669 0.5156142 -0.8546071 -0.07339817 0.5140616 -0.8401913 -0.1666101 0.5160617 -0.8396936 -0.1648654 0.5174304 -0.8189969 -0.2558574 0.5135964 -0.8176183 -0.2471803 0.5200021 -0.7927796 -0.3332176 0.5103593 -0.7921764 -0.3232271 0.5176687 -0.7601353 -0.411836 0.5025789 -0.7609361 -0.3963063 0.5137291 -0.723756 -0.4810329 0.494757 -0.7284554 -0.4598584 0.5078218 -0.6897376 -0.5347815 0.4881299 -0.6970533 -0.5148805 0.4990138 -0.6564456 -0.5842081 0.4772632 -0.6647327 -0.56322 0.4908298 -0.6717944 0.6327366 0.385145 -0.6678968 0.6369116 0.3850423 -0.7025916 0.5846805 0.4056029 -0.7118628 0.574038 0.4046379 -0.7483107 0.4827017 0.4550057 -0.7777014 0.4375359 0.451379 -0.7992496 0.3384789 0.4966208 -0.8123465 0.3161681 0.4900315 -0.834016 0.2522377 0.490707 -0.8242595 0.2658059 0.4999436 -0.8853082 0.2283164 0.4050939 -0.8119387 0.3057331 0.4972755 -0.9124077 0.2705036 0.307148 -0.8044818 0.3727801 0.4624329 -0.8875101 0.3440097 0.3065669 -0.8196231 0.4090756 0.4010925 -0.8576551 0.4070883 0.3141765 -0.8301205 0.4385093 0.3443977 -0.857747 0.3815558 0.3445075 -0.894542 0.3127401 0.3193559 -0.8948661 0.1554517 0.4183894 -0.9083389 0.1165123 0.4016784 -0.9009853 0.03185874 0.4326785 -0.9026767 0.0268107 0.4294835 -0.8955805 -0.05881929 0.4409942 -0.897482 -0.06574195 0.4361242 -0.8803046 -0.1527062 0.4491599 -0.8814912 -0.1582073 0.4449089 -0.8565061 -0.2504073 0.4513245 -0.8565666 -0.2509237 0.4509223 -0.8294993 -0.329728 0.4507887 -0.8294883 -0.3281366 0.4519685 -0.794694 -0.4129279 0.4449181 -0.7951993 -0.4037889 0.4523413 -0.7599635 -0.4805899 0.4375944 -0.7615817 -0.4699616 0.4462394 -0.723608 -0.5387768 0.431406 -0.726684 -0.5291648 0.4380812 -0.680322 -0.5967809 0.4254581 -0.6851903 -0.5859984 0.432574 -0.6620392 0.6901443 0.2922415 -0.6778798 0.6742986 0.292917 -0.7133111 0.6202317 0.3263433 -0.7251317 0.6070489 0.325078 -0.7715234 0.5273399 0.3558993 -0.7772141 0.5193904 0.3552069 -0.8285741 0.3863191 0.405244 -0.8500919 0.3450396 0.3978586 -0.8655971 0.2568037 0.4298762 -0.8700205 0.2483189 0.4259132 -0.8990975 0.1909795 0.3938916 -0.872055 0.2321342 0.4308525 -0.9386212 0.1924434 0.2862792 -0.8628208 0.2927952 0.4120817 -0.940102 0.2575704 0.2233064 -0.8632915 0.3543375 0.3594062 -0.9090011 0.3474996 0.2301325 -0.8634704 0.4052659 0.3002976 -0.8855348 0.3984636 0.238862 -0.8869872 0.3961442 0.2373257 -0.9107608 0.2837417 0.3000088 -0.9425574 0.1973913 0.2694851 -0.9352324 0.0574035 0.3493499 -0.9390587 0.04110425 0.3412907 -0.9310387 -0.0527324 0.3610906 -0.9314452 -0.05507206 0.3596901 -0.9182545 -0.1422638 0.3695535 -0.9186403 -0.1462432 0.3670325 -0.894916 -0.2385386 0.3771271 -0.8949781 -0.2424675 0.3744646 -0.8646991 -0.3301601 0.3785363 -0.8650091 -0.3264119 0.3810704 -0.8278782 -0.4151661 0.377167 -0.8294082 -0.4063842 0.3833198 -0.7948074 -0.4787581 0.3729233 -0.7977547 -0.4682661 0.3798872 -0.7513062 -0.5490465 0.3661787 -0.7578103 -0.5330964 0.3762072 -0.7080861 -0.6018021 0.3693892 -0.7108591 -0.5967721 0.3722131 -0.6498897 0.7369771 0.185764 -0.6504703 0.7364596 0.1857841 -0.6960267 0.6848291 0.2157683 -0.7202329 0.6599431 0.2138687 -0.7792966 0.5712157 0.2577003 -0.7875832 0.5602294 0.2566235 -0.8457036 0.4390894 0.3032921 -0.8626115 0.4082564 0.2987107 -0.8878644 0.3005197 0.3484033 -0.90344 0.2657981 0.3363742 -0.9157887 0.1863315 0.3558252 -0.9144293 0.1892499 0.3577758 -0.9395401 0.1515092 0.3070985 -0.9122598 0.2014942 0.3566262 -0.9530526 0.1947257 0.2318892 -0.9041821 0.2743504 0.3273939 -0.9449115 0.2767809 0.1747418 -0.8938723 0.3551046 0.2736659 -0.9236925 0.3512675 0.1529813 -0.896436 0.3976039 0.1957391 -0.913698 0.3634905 0.1817434 -0.9370943 0.3134356 0.153664 -0.9567169 0.1332943 0.2586995 -0.9709969 0.07379025 0.2274206 -0.9589719 -0.03250265 0.2816323 -0.9610998 -0.04661518 0.2722392 -0.9478133 -0.1348495 0.2889043 -0.9480106 -0.138516 0.2865123 -0.9263347 -0.2308344 0.2976908 -0.92609 -0.2356114 0.2946942 -0.8940148 -0.3267221 0.3065782 -0.8937906 -0.3281863 0.3056669 -0.8580543 -0.408872 0.3107517 -0.8586027 -0.406587 0.3122316 -0.8194073 -0.4833313 0.3081603 -0.8231444 -0.4727765 0.3145085 -0.7720913 -0.55662 0.3066748 -0.7770815 -0.5457285 0.3135681 -0.7329173 -0.6081748 0.3048864 -0.7394697 -0.5970262 0.3110374 -0.6100512 0.7886142 0.07697564 -0.6242871 0.7774081 0.07682675 -0.6692981 0.7352696 0.1068587 -0.701017 0.7054877 0.1042222 -0.7544419 0.639778 0.1466349 -0.7751289 0.6151023 0.1443063 -0.8330877 0.5181855 0.1935168 -0.8531356 0.4860157 0.1896009 -0.8956457 0.3696416 0.247354 -0.91363 0.3295748 0.2380355 -0.9376323 0.2009458 0.2836661 -0.9422936 0.1875976 0.2772904 -0.9567781 0.1231552 0.2634549 -0.9464631 0.1502681 0.2857047 -0.9733711 0.1259913 0.1915071 -0.9421687 0.1993631 0.2693929 -0.9757217 0.1908641 0.1074154 -0.9313349 0.2856037 0.2259333 -0.9551193 0.2826294 0.08870106 -0.9205719 0.3526712 0.167841 -0.9319308 0.3516228 0.08869242 -0.9244738 0.3675673 0.1012065 -0.9597319 0.2393272 0.1470961 -0.9809102 0.1615249 0.1082815 -0.9811494 0.008490562 0.1930646 -0.9841971 -0.0173254 0.1762269 -0.9710921 -0.1199951 0.2063528 -0.9712822 -0.1276455 0.2007924 -0.9509077 -0.2175905 0.2200661 -0.9498749 -0.2304156 0.2112969 -0.9204432 -0.3159152 0.230178 -0.9189388 -0.3241472 0.2246778 -0.8854707 -0.4009872 0.2348424 -0.8855838 -0.4005819 0.2351075 -0.8416975 -0.4838621 0.2396307 -0.8421427 -0.4827445 0.2403197 -0.7979454 -0.5516929 0.2427306 -0.7983312 -0.5508951 0.2432739 -0.7553753 -0.6101233 0.2390769 -0.7593629 -0.6032333 0.2438802 -0.5891115 0.8079074 0.01527762 -0.5976879 0.8016066 0.01400434 -0.642802 0.7653368 0.03264188 -0.6716579 0.7403181 0.02837145 -0.7084606 0.703312 0.05861622 -0.7357344 0.6750201 0.05516278 -0.7946611 0.5987781 0.09989249 -0.8219226 0.5615765 0.09526425 -0.8877516 0.4341737 0.152939 -0.904329 0.4009102 0.1464931 -0.9513891 0.2342253 0.1999938 -0.9591512 0.2090637 0.1905819 -0.9732218 0.1130007 0.2001751 -0.9706584 0.1226405 0.2068374 -0.9849164 0.07738691 0.1547616 -0.9714058 0.12669 0.2007997 -0.9932298 0.09918045 0.06047987 -0.9652651 0.1989188 0.1693946 -0.9832065 0.182159 -0.01110023 -0.9519986 0.2856217 0.1100862 -0.9531818 0.3023063 -0.007447719 -0.936371 0.348545 0.04154455 -0.9509558 0.3085104 0.02246189 -0.9661228 0.2578392 -0.01121556 -0.9905413 0.1024465 0.0912835 -0.9984644 0.02953279 0.04687005 -0.9890987 -0.08841645 0.1177554 -0.9888217 -0.1060404 0.1048195 -0.9705729 -0.1990177 0.1355743 -0.9684816 -0.216351 0.1234334 -0.942065 -0.3009554 0.1481198 -0.939395 -0.3132576 0.1393079 -0.9075074 -0.3896245 0.1569181 -0.9053913 -0.3962377 0.15252 -0.8639562 -0.4757001 0.1651951 -0.8616076 -0.4810935 0.1618065 -0.8206681 -0.5457464 0.1693068 -0.8205487 -0.545969 0.1691677 -0.7732836 -0.6104269 0.1714984 -0.7758626 -0.6064088 0.1740847 -0.5873627 0.809322 0.00170952 -0.5881028 0.8087848 0.001544296 -0.6348268 0.7726303 0.006121933 -0.6414446 0.7671573 0.004302918 -0.6813469 0.7317551 0.01735001 -0.7000128 0.7140193 0.01259642 -0.7588074 0.6497004 0.04583489 -0.7876809 0.6148058 0.03966021 -0.8644469 0.4952656 0.08627706 -0.8878547 0.4535456 0.07752609 -0.949356 0.2897543 0.1215145 -0.962719 0.2484658 0.1069443 -0.9844697 0.1181929 0.1298072 -0.9852576 0.1141865 0.1273936 -0.993051 0.050278 0.1064047 -0.9887601 0.0764268 0.1285008 -0.9971072 0.0488376 0.05824285 -0.9885656 0.103209 0.1099361 -0.9937576 0.1110969 -0.01017802 -0.9784108 0.1925463 0.07508838 -0.9722547 0.2246161 -0.06533455 -0.9516595 0.3060803 0.02567631 -0.9541896 0.2909976 -0.06958901 -0.9499883 0.3071458 -0.05642449 -0.9785729 0.2055473 -0.01205402 -0.9904093 0.1224809 -0.06393808 -0.9988048 -0.03955048 0.02872008 -0.9974409 -0.0712127 0.006345987 -0.982831 -0.1776183 0.04995179 -0.9794008 -0.1987134 0.03587543 -0.9581863 -0.278413 0.0660699 -0.9535618 -0.2963916 0.05359286 -0.9259486 -0.369111 0.07985204 -0.9199205 -0.3860881 0.06842839 -0.8824297 -0.4622114 0.08762687 -0.8794086 -0.4687607 0.08309006 -0.8374162 -0.5383301 0.0945248 -0.835591 -0.5415257 0.09239906 -0.7923594 -0.6015896 0.1012749 -0.7894134 -0.6059545 0.09821218 -0.5904762 0.8070549 6.43133e-4 -0.5873517 0.8093309 0.001277744 -0.6381179 0.7699384 6.78497e-4 -0.6347102 0.7727483 0.001777768 -0.6742972 0.7384489 0.004053354 -0.6802608 0.7329681 0.001780033 -0.7404844 0.6718991 0.01530998 -0.7558717 0.6546308 0.01079511 -0.8440451 0.5353457 0.0315116 -0.8617142 0.5067984 0.02457803 -0.943228 0.3277832 0.05365747 -0.9531587 0.2992206 0.04422265 -0.9909625 0.1195166 0.06090301 -0.9909055 0.1198875 0.06109988 -0.998865 0.02503997 0.04051774 -0.9970443 0.04872906 0.05939894 -0.999955 0.007959842 0.005165517 -0.9979792 0.04793268 0.04171383 -0.9972695 0.03474318 -0.06516665 -0.99347 0.1133239 0.01323866 -0.9805015 0.13274 -0.1449034 -0.9728947 0.2283307 -0.03662055 -0.9569159 0.2529708 -0.1425411 -0.9515075 0.2886797 -0.1062909 -0.959236 0.2582553 -0.1147632 -0.9656343 0.2171186 -0.1428637 -0.9981268 0.02002185 -0.05781251 -0.996384 -0.01856535 -0.08291161 -0.9875341 -0.153818 -0.033414 -0.9838496 -0.1728557 -0.04648685 -0.9658507 -0.258571 -0.01654601 -0.9603013 -0.2773763 -0.02973049 -0.934957 -0.3547493 -0.0029006 -0.9278367 -0.3726883 -0.01492208 -0.8954206 -0.445181 0.005990982 -0.8908023 -0.4543908 -6.05854e-4 -0.8509808 -0.5249376 0.01650232 -0.8448317 -0.5349417 0.009845435 -0.8077315 -0.5890367 0.02461445 -0.8031044 -0.5954824 0.02059924 -0.5940203 0.8044501 -2.50691e-4 -0.5904741 0.8070564 4.72672e-4 -0.6395113 0.7687817 6.41278e-5 -0.6381142 0.7699416 5.19557e-4 -0.6755861 0.737281 3.64413e-4 -0.6742646 0.7384893 9.1623e-4 -0.7456914 0.6662901 -0.001394093 -0.7402306 0.6723529 4.6686e-4 -0.8452857 0.5343075 -0.002752661 -0.8436947 0.5368195 -0.002015054 -0.9443578 0.3288943 -0.004137814 -0.9440276 0.3298448 -0.003798246 -0.9940507 0.1083431 -0.01118677 -0.9928323 0.1193801 -0.005704402 -0.9995157 -0.001030504 -0.03110343 -0.9996616 0.02205789 -0.01379078 -0.9982447 -0.02232193 -0.05485719 -0.9995086 0.005847334 -0.03079503 -0.9957015 -0.008702576 -0.09221047 -0.9980387 0.03554666 -0.0515294 -0.9863852 0.07358002 -0.1470723 -0.9871134 0.1392248 -0.07889038 -0.9623068 0.1922436 -0.1923751 -0.9591341 0.2550637 -0.1224933 -0.9478872 0.2430848 -0.2059608 -0.9463151 0.2576149 -0.1952496 -0.9837484 0.09606033 -0.1516956 -0.982524 0.04572904 -0.1804309 -0.9843342 -0.1285465 -0.1206732 -0.9804797 -0.1455347 -0.1322093 -0.9644696 -0.2429027 -0.1039071 -0.9594476 -0.2576122 -0.1144396 -0.9360291 -0.3409774 -0.08708661 -0.9278216 -0.3594576 -0.09968614 -0.9021801 -0.4248712 -0.07453572 -0.8944992 -0.4390232 -0.08443862 -0.8601465 -0.5060469 -0.06375372 -0.8529639 -0.5170863 -0.07123386 -0.8171175 -0.5741407 -0.05178213 -0.8094913 -0.5842677 -0.05792266 -0.5945765 0.8040391 -6.66029e-6 -0.5940202 0.8044502 1.15357e-4 -0.6384279 0.7696816 5.66536e-4 -0.6395107 0.7687822 1.93103e-4 -0.6817464 0.7315852 -0.002207934 -0.6755859 0.7372813 3.94089e-4 -0.7658398 0.6428539 -0.01511383 -0.7459912 0.6659199 -0.006925463 -0.8655103 0.499812 -0.03286451 -0.8460301 0.5326806 -0.0220111 -0.9526832 0.2984774 -0.05749773 -0.9440071 0.3267011 -0.04601287 -0.9930863 0.08508086 -0.08087497 -0.9919372 0.1054114 -0.07034939 -0.9943565 -0.02666473 -0.1026847 -0.9963265 -0.004093825 -0.08553981 -0.9914592 -0.04754459 -0.1214424 -0.9944009 -0.02523833 -0.1026155 -0.9884775 -0.04031604 -0.1459005 -0.9927497 -0.01027953 -0.1197599 -0.980723 0.01789712 -0.1945819 -0.9873552 0.07422065 -0.1400747 -0.9557452 0.1155366 -0.2705596 -0.9638636 0.1935696 -0.1830245 -0.9341668 0.1935147 -0.2998077 -0.9349655 0.2395177 -0.2616692 -0.9470964 0.1748182 -0.2691603 -0.9468619 0.1213188 -0.2978832 -0.9739178 -0.07506388 -0.2141255 -0.9646701 -0.1168646 -0.2361236 -0.9570762 -0.2178828 -0.1911342 -0.9494779 -0.2383966 -0.2041046 -0.9332395 -0.3149914 -0.1727559 -0.9226074 -0.337072 -0.1875585 -0.901768 -0.4022817 -0.1580637 -0.8925817 -0.4180487 -0.168918 -0.8628388 -0.4849056 -0.1427437 -0.8534631 -0.4983898 -0.1523436 -0.8189727 -0.5586338 -0.1311947 -0.8081687 -0.572044 -0.1401044 -0.594645 0.8039885 -4.6475e-5 -0.5945786 0.8040376 -2.96489e-5 -0.635436 0.7721528 0.001103162 -0.6384347 0.7696762 1.01843e-4 -0.6826191 0.7307744 3.12111e-4 -0.6815886 0.7317353 6.80748e-4 -0.797166 0.6033101 -0.02331084 -0.765017 0.643951 -0.008732259 -0.9051396 0.4198796 -0.06651115 -0.8661813 0.498206 -0.03899592 -0.9663935 0.232216 -0.1102696 -0.9519838 0.2944278 -0.08390003 -0.9885001 0.05152487 -0.142172 -0.9886476 0.08081573 -0.126668 -0.9868948 -0.04097056 -0.1560773 -0.9887515 -0.02845048 -0.1468372 -0.9851625 -0.05646651 -0.162069 -0.9864938 -0.04903489 -0.1562875 -0.9839528 -0.05264818 -0.1704853 -0.985949 -0.04133898 -0.1618505 -0.9774466 -0.02891343 -0.209194 -0.9855139 0.02014112 -0.1683946 -0.9568833 0.03009217 -0.28891 -0.9737527 0.128521 -0.1878512 -0.9397802 0.114397 -0.3220661 -0.9502396 0.199059 -0.2396252 -0.9301019 0.1455755 -0.3372213 -0.9320974 0.1779802 -0.3154641 -0.9535952 -0.02303117 -0.3002098 -0.9468209 -0.0595076 -0.3162106 -0.9387282 -0.203279 -0.2783291 -0.9350302 -0.2129054 -0.2835308 -0.9172751 -0.2988172 -0.2632769 -0.9112274 -0.3104246 -0.2707418 -0.8873011 -0.3890213 -0.2477079 -0.8802245 -0.400188 -0.2550573 -0.8534607 -0.4662575 -0.2328282 -0.84437 -0.4787411 -0.2405126 -0.8099865 -0.5440648 -0.2188957 -0.7998829 -0.5560196 -0.2258973 -0.5943245 0.8042255 -8.74981e-5 -0.5946441 0.8039891 -1.56519e-4 -0.6323559 0.7746775 9.8636e-4 -0.6354524 0.77214 -1.01862e-5 -0.6665958 0.7454032 0.004914999 -0.682574 0.7308161 8.4294e-4 -0.8153929 0.5788044 -0.01095986 -0.7927739 0.6095067 -0.003392577 -0.9556562 0.2854758 -0.0722832 -0.8996502 0.4356309 -0.02924627 -0.9851959 0.1146877 -0.1274201 -0.9671959 0.2415862 -0.07853859 -0.9883287 0.01664072 -0.1514248 -0.9896347 0.05241674 -0.1337003 -0.9889064 -0.03037524 -0.1454018 -0.9874818 -0.0410577 -0.1522957 -0.9913495 -0.03033548 -0.127695 -0.9879007 -0.0565415 -0.1444141 -0.9938739 -0.02244991 -0.108216 -0.9905695 -0.05237317 -0.1266068 -0.9938917 -0.02280992 -0.1079775 -0.9938595 -0.02316945 -0.1081966 -0.9882915 -0.0031659 -0.1525452 -0.9927779 0.06497764 -0.1008466 -0.9729981 0.02908033 -0.2289741 -0.9808289 0.1595484 -0.1118887 -0.9459519 -0.002537965 -0.3242972 -0.9665232 0.1567858 -0.2031041 -0.9301362 -0.08903431 -0.3562579 -0.9458432 -0.01909756 -0.3240619 -0.9066358 -0.2251512 -0.3568174 -0.9160603 -0.2027476 -0.3460158 -0.8921704 -0.2889608 -0.3471797 -0.8880472 -0.2961661 -0.3516502 -0.8662757 -0.3715647 -0.3339253 -0.858021 -0.3832329 -0.3419541 -0.8350039 -0.4484875 -0.3187906 -0.8220734 -0.4648848 -0.3287514 -0.7982366 -0.5216428 -0.3011765 -0.7808286 -0.5410358 -0.3123895 -0.5933592 0.8049378 -1.9147e-4 -0.5943264 0.8042239 -4.14829e-4 -0.6311618 0.7756513 2.54197e-4 -0.6323609 0.7746739 -1.2672e-4 -0.6560861 0.7546821 0.00244534 -0.6667937 0.7452424 4.0607e-4 -0.8189474 0.5738674 -0.001236915 -0.8133301 0.5818024 -2.178e-4 -0.9827111 0.1813722 -0.03718942 -0.9496208 0.3131047 -0.01363366 -0.9962406 0.04831147 -0.07190829 -0.9886124 0.1451387 -0.039752 -0.9966483 0.005256593 -0.0816366 -0.9970598 0.02153331 -0.07354027 -0.9977337 -0.01268029 -0.0660814 -0.9960497 -0.03627443 -0.08105194 -0.9987088 -0.01042687 -0.04971981 -0.9972953 -0.03371208 -0.06531357 -0.9992829 -0.008223533 -0.0369594 -0.9984478 -0.0262112 -0.04914295 -0.9993421 -0.01675462 -0.03216612 -0.9990545 -0.02381044 -0.03637528 -0.9972051 -0.03373521 -0.06666165 -0.9992364 0.02108955 -0.03289407 -0.9878382 -0.03371107 -0.1517869 -0.9940687 0.09835863 -0.04640144 -0.9563549 -0.1190775 -0.2668443 -0.9911023 0.07116508 -0.1124811 -0.9059584 -0.2337619 -0.3529799 -0.9623979 -0.087897 -0.2570301 -0.8568989 -0.3152704 -0.4078346 -0.9088811 -0.2250148 -0.3511463 -0.8486382 -0.3158668 -0.4243127 -0.8668946 -0.2898419 -0.4055682 -0.8363298 -0.3556306 -0.4172283 -0.8290539 -0.3646301 -0.4239274 -0.8183657 -0.4180756 -0.3943229 -0.7936458 -0.447195 -0.4124841 -0.7872496 -0.489983 -0.3743726 -0.7619948 -0.516294 -0.3909021 -0.5907205 0.8068763 2.1214e-4 -0.5933591 0.804938 -4.18581e-4 -0.630297 0.7763543 2.19508e-4 -0.6311616 0.7756514 -6.42866e-5 -0.6529905 0.7573662 4.39923e-4 -0.65612 0.7546566 -1.56278e-4 -0.8078569 0.5893788 1.22015e-4 -0.8189492 0.5738648 -0.001221776 -0.9897581 0.1424278 -0.009661376 -0.9821802 0.1878954 -0.004192233 -0.9995188 0.02156072 -0.02230364 -0.9983736 0.0558716 -0.01134395 -0.9996719 0.001518726 -0.02557033 -0.9997225 0.006411194 -0.02266854 -0.999823 -0.003896236 -0.0184074 -0.9995757 -0.01376831 -0.02567148 -0.9999098 -0.003703474 -0.01291358 -0.9997711 -0.01068174 -0.01854103 -0.9999527 -0.003933668 -0.008902192 -0.999876 -0.008752286 -0.01309424 -0.9999185 -0.01196926 -0.004445731 -0.9998019 -0.01770943 -0.009094834 -0.9985023 -0.05199259 -0.01702725 -0.9995025 -0.03135132 -0.003454148 -0.9850772 -0.1250177 -0.1182946 -0.9997828 0.01436996 -0.01509505 -0.9372168 -0.229573 -0.2625281 -0.9970054 -0.011689 -0.07644462 -0.8395584 -0.3733708 -0.3946341 -0.9516549 -0.1916827 -0.2400224 -0.8045697 -0.3996728 -0.4392372 -0.891067 -0.2922874 -0.3472289 -0.7830153 -0.3957116 -0.4798954 -0.859394 -0.3130181 -0.4043039 -0.7898159 -0.3690258 -0.4899094 -0.8064404 -0.3523008 -0.4749084 -0.7900272 -0.3915504 -0.4717472 -0.7632413 -0.4189195 -0.4919039 -0.761632 -0.4612802 -0.4551233 -0.7317253 -0.4890387 -0.4747835 -0.5883195 0.8086286 1.43686e-4 -0.5907192 0.8068771 -4.31894e-4 -0.62957 0.7769439 1.33417e-4 -0.6302975 0.7763538 -9.98092e-5 -0.6524032 0.7578722 -9.84736e-6 -0.6529927 0.7573642 -1.25813e-4 -0.798466 0.6020399 -2.82623e-4 -0.8078833 0.589341 -0.001344621 -0.9890237 0.1477471 -0.001732945 -0.9897567 0.1427471 -0.002269327 -0.999841 0.01728349 -0.004388272 -0.999749 0.02223271 -0.00278896 -0.9999808 8.05294e-5 -0.006208539 -0.999986 0.002143025 -0.00484997 -0.9999631 -0.004344761 -0.00743103 -0.9999735 -0.003275513 -0.006511986 -0.9999013 -0.007546663 -0.01185083 -0.9999688 -0.003231227 -0.007218301 -0.9997835 -0.009451389 -0.01853859 -0.9999336 -0.004066288 -0.01078867 -0.9996492 -0.01401966 -0.0224694 -0.9997331 -0.01238346 -0.01950615 -0.9984092 -0.05009883 -0.02587211 -0.9982353 -0.05186587 -0.02892053 -0.9750575 -0.1827831 -0.1259099 -0.9935402 -0.109056 -0.03137952 -0.8751339 -0.3508076 -0.3332786 -0.9789429 -0.1655095 -0.1194882 -0.7669614 -0.452591 -0.4548973 -0.8789387 -0.3448877 -0.3294226 -0.7453545 -0.4534651 -0.4886882 -0.8413164 -0.3713594 -0.3927837 -0.7134637 -0.4561846 -0.5318509 -0.8222887 -0.375086 -0.4279626 -0.7244715 -0.4150943 -0.5503072 -0.7811369 -0.3703572 -0.5026538 -0.7393481 -0.3930642 -0.5466855 -0.7351912 -0.3969218 -0.549497 -0.7268561 -0.4390316 -0.5281397 -0.6999862 -0.4633943 -0.5434013 -0.585281 0.8108305 3.0363e-4 -0.5883187 0.8086291 -4.47093e-4 -0.6283482 0.7779322 3.61676e-4 -0.6295701 0.7769438 -3.53325e-5 -0.6528461 0.7574906 -3.56091e-4 -0.65241 0.7578663 -2.61318e-4 -0.7757621 0.6310214 -0.002299606 -0.7987375 0.601653 -0.005688846 -0.977132 0.2125884 -0.004399955 -0.9890446 0.1470836 -0.01254159 -0.9995823 0.02814632 -0.006560981 -0.999803 0.01684129 -0.01050746 -0.999899 -0.005187153 -0.01323598 -0.9999517 -4.22269e-4 -0.009822964 -0.9990846 -0.0261017 -0.03389263 -0.9998922 -0.005862414 -0.01346528 -0.9953026 -0.05346226 -0.08071398 -0.9996295 -0.01166844 -0.02459108 -0.9850786 -0.0740903 -0.1553414 -0.9988424 -0.01649051 -0.04518854 -0.9726613 -0.07068657 -0.2212092 -0.9951782 -0.02598291 -0.09457927 -0.9629046 -0.07724851 -0.2585487 -0.9743096 -0.06584638 -0.215372 -0.9363892 -0.18147 -0.3004062 -0.9116797 -0.1974755 -0.3603383 -0.8445787 -0.3552437 -0.4006104 -0.8375075 -0.3589764 -0.4119678 -0.7479264 -0.4602982 -0.478259 -0.7596392 -0.4545155 -0.4651495 -0.7007454 -0.4792537 -0.5284619 -0.769698 -0.4411912 -0.4614275 -0.6656178 -0.4808382 -0.570743 -0.7473595 -0.4429104 -0.4952618 -0.6673973 -0.449901 -0.5934391 -0.747766 -0.4088199 -0.5231752 -0.6795752 -0.4182537 -0.6026952 -0.7090271 -0.3981125 -0.5820541 -0.6887006 -0.4219506 -0.5896179 -0.6641053 -0.4417958 -0.6031423 -0.5803297 0.8143815 5.04646e-4 -0.5852878 0.8108252 -9.0514e-4 -0.6252648 0.7804119 0.001219332 -0.6283606 0.7779222 1.0413e-4 -0.6591977 0.7519631 -0.003181934 -0.6529898 0.7573658 -0.001275122 -0.74971 0.6616415 -0.01286453 -0.7810464 0.6240842 -0.02203965 -0.9206029 0.3897839 -0.02364438 -0.9786817 0.194636 -0.06556671 -0.9943251 0.1004895 -0.03492164 -0.997371 0.01049637 -0.07170146 -0.9971996 -0.02825838 -0.06924206 -0.996918 -0.03177601 -0.07172721 -0.9616189 -0.1840552 -0.2035019 -0.9946712 -0.05735385 -0.08567345 -0.753178 -0.4102365 -0.5142268 -0.9923322 -0.0667743 -0.1040096 -0.6410132 -0.3902133 -0.6609356 -0.9907557 -0.06000965 -0.1216639 -0.6428445 -0.2816585 -0.7123338 -0.9748492 -0.06829607 -0.212143 -0.6769165 -0.1860346 -0.7121624 -0.8733168 -0.1080665 -0.4750152 -0.680617 -0.1859686 -0.7086439 -0.6756807 -0.1874032 -0.7129766 -0.6814245 -0.2935109 -0.6704566 -0.5987479 -0.3121159 -0.737621 -0.6952262 -0.409606 -0.5906635 -0.5571776 -0.4451756 -0.7009792 -0.628457 -0.4871626 -0.6063947 -0.5496637 -0.5052906 -0.6652453 -0.5792527 -0.4988427 -0.6446878 -0.6226252 -0.4895914 -0.6104409 -0.6037836 -0.4739336 -0.640962 -0.7267012 -0.4399963 -0.5275498 -0.6151033 -0.4505667 -0.6470222 -0.7210099 -0.413358 -0.5561295 -0.634218 -0.4285635 -0.6435067 -0.6432375 -0.4237003 -0.6377488 -0.5738885 0.8189332 -7.07683e-4 -0.5804424 0.8142887 -0.00454539 -0.6225816 0.7825517 -0.002309501 -0.6261481 0.7796915 -0.004452824 -0.6844862 0.7286401 -0.02371346 -0.6639831 0.7476384 -0.01278585 -0.8185049 0.5682745 -0.08434385 -0.7833465 0.6183999 -0.06284815 -0.9341396 0.3235043 -0.1507587 -0.9489912 0.2653045 -0.1703798 -0.9739973 0.1582536 -0.1621271 -0.9705924 -0.04105687 -0.2372016 -0.9846878 -0.01689779 -0.1735064 -0.9421141 -0.2009062 -0.2684356 -0.8393307 -0.3937367 -0.3748273 -0.9202577 -0.2640934 -0.2887569 -0.6501123 -0.5331144 -0.5414269 -0.9437792 -0.2088243 -0.2562677 -0.6579952 -0.4572517 -0.5983003 -0.9584996 -0.1573685 -0.2377264 -0.6448139 -0.3671249 -0.6703987 -0.9463219 -0.1345472 -0.2938914 -0.6489445 -0.267499 -0.7122608 -0.8690553 -0.1407316 -0.4742759 -0.6131469 -0.233711 -0.7546061 -0.6931256 -0.185774 -0.696466 -0.6139372 -0.267448 -0.742666 -0.5975564 -0.2789147 -0.7517534 -0.5963867 -0.3603472 -0.7172677 -0.5445531 -0.3946158 -0.7400949 -0.5817264 -0.4537192 -0.6750803 -0.4872301 -0.4871637 -0.724761 -0.5344584 -0.4951707 -0.6849527 -0.4980585 -0.4996213 -0.7087427 -0.5861012 -0.4774222 -0.65464 -0.6169676 -0.4732694 -0.6287822 -0.5680765 -0.4665532 -0.6779507 -0.6894206 -0.4468672 -0.5700957 -0.5750199 -0.4457507 -0.6860456 -0.6221081 -0.4287829 -0.6550777 -0.572216 0.819243 -0.03754848 -0.5739952 0.8178293 -0.0410462 -0.6282266 0.7761895 -0.05349332 -0.6273036 0.7770302 -0.05209881 -0.7022849 0.7059354 -0.09193062 -0.7043803 0.7035362 -0.09426099 -0.8151375 0.5600351 -0.1480257 -0.8458141 0.501197 -0.1827567 -0.928141 0.2962272 -0.2253966 -0.9395129 0.2317181 -0.2522348 -0.9577897 0.0182693 -0.2868888 -0.9511456 -0.03773587 -0.3064281 -0.9028847 -0.2576707 -0.3441004 -0.8893592 -0.2886806 -0.3545473 -0.7578918 -0.4994629 -0.4196867 -0.8333271 -0.4011793 -0.3802911 -0.6992164 -0.5347961 -0.4744361 -0.8453694 -0.3766207 -0.378824 -0.7041829 -0.4803899 -0.5228308 -0.8822148 -0.3042456 -0.3593491 -0.6461169 -0.441223 -0.6227803 -0.9264111 -0.2071664 -0.3143957 -0.7703287 -0.2919052 -0.5669085 -0.9354096 -0.1533306 -0.3185887 -0.6297148 -0.3151636 -0.710022 -0.8514321 -0.195518 -0.4866583 -0.588784 -0.3014798 -0.7499623 -0.6579187 -0.2681923 -0.7037158 -0.55984 -0.3636519 -0.7445378 -0.5543535 -0.3673906 -0.7468041 -0.5136821 -0.4535028 -0.728331 -0.4974686 -0.4635484 -0.7332448 -0.4965614 -0.4870548 -0.7184737 -0.478861 -0.4929388 -0.7264321 -0.5117357 -0.475179 -0.7157734 -0.5190741 -0.4744488 -0.7109575 -0.4946013 -0.4636787 -0.7350999 -0.5414713 -0.4638687 -0.7011666 -0.5223984 -0.4413313 -0.7296072 -0.5209599 -0.4415972 -0.7304744 -0.5595421 0.7980451 -0.2236887 -0.5593758 0.8025146 -0.207531 -0.6013889 0.7561947 -0.257878 -0.6020815 0.7289159 -0.325852 -0.6670401 0.6696016 -0.3266363 -0.6725658 0.6089074 -0.4205796 -0.7418898 0.5662978 -0.3590353 -0.7524337 0.4336133 -0.4958057 -0.84648 0.3646439 -0.3879519 -0.8341366 0.1587778 -0.5282101 -0.9067255 0.003691077 -0.4217053 -0.8492985 -0.1787459 -0.4967314 -0.8342849 -0.3310298 -0.4408946 -0.7977409 -0.3918111 -0.4583595 -0.6916706 -0.5593826 -0.4568183 -0.7233425 -0.5263564 -0.4469055 -0.6693233 -0.5671961 -0.4798907 -0.7214158 -0.5210905 -0.4560965 -0.8315104 -0.3802168 -0.4050007 -0.7868967 -0.4268759 -0.4456126 -0.9620212 -0.166221 -0.2165317 -0.9142706 -0.2504312 -0.3184234 -0.9524142 -0.163124 -0.2574837 -0.9833714 -0.09707784 -0.1534816 -0.7479073 -0.3338226 -0.5737571 -0.9554442 -0.155307 -0.2510104 -0.5566494 -0.3619509 -0.747752 -0.7650929 -0.2990086 -0.5702868 -0.5290823 -0.3694824 -0.7639076 -0.5565139 -0.3629887 -0.7473497 -0.5000653 -0.4516981 -0.738853 -0.4987503 -0.4522419 -0.7394089 -0.4744254 -0.4885802 -0.7322636 -0.4730767 -0.4891188 -0.7327764 -0.4841261 -0.4740456 -0.7354609 -0.4896478 -0.4733687 -0.7322344 -0.4778825 -0.4631294 -0.7464179 -0.4946789 -0.4636934 -0.7350383 -0.4867541 -0.4396122 -0.7548587 -0.4943761 -0.4385456 -0.7505132 0.633645 -0.6110111 0.4745098 0.6477357 -0.6015103 0.4675723 0.661048 -0.5740736 0.483172 0.6866873 -0.5532366 0.4715824 0.69657 -0.5228495 0.4913436 0.7178083 -0.5046704 0.4796448 0.7264508 -0.4700862 0.5012866 0.7480567 -0.4488129 0.488854 0.7642474 -0.398176 0.5073282 0.7786817 -0.3831482 0.4968423 0.7972092 -0.3227876 0.5101625 0.8026593 -0.3162796 0.5056732 0.8233918 -0.2483761 0.5102307 0.8256179 -0.2453594 0.5080885 0.8491739 -0.1562388 0.5044732 0.8458765 -0.1616133 0.5083053 0.8638671 -0.06617015 0.4993548 0.8615727 -0.07093918 0.5026533 0.867982 0.01863551 0.4962459 0.8680388 0.0187847 0.496141 0.8647419 0.09099608 0.4939041 0.866958 0.09965902 0.4883154 0.8592803 0.2632696 0.4385504 0.8585079 0.1993238 0.4724767 0.8198803 0.423691 0.3850746 0.8232068 0.4061355 0.3967172 0.8136716 0.410737 0.4113802 0.8145156 0.434173 0.3847833 0.794294 0.3763146 0.4769533 0.8204501 0.4010458 0.4074603 0.7865807 0.3115128 0.5331516 0.8148574 0.3480414 0.4635456 0.7883905 0.2689319 0.5532775 0.7959786 0.2935473 0.5293846 0.7734767 0.3155789 0.5496761 0.7734605 0.3109421 0.552335 0.7462577 0.4076687 0.5262183 0.7514471 0.3741322 0.5434633 0.6951097 0.5384571 0.4763261 0.7160415 0.4781939 0.5085422 0.6528239 -0.6299879 0.420638 0.6756138 -0.6146086 0.4071884 0.691757 -0.5816636 0.4279484 0.7171539 -0.560599 0.414028 0.7298803 -0.5261731 0.4363676 0.747074 -0.5106666 0.4255585 0.765403 -0.4681649 0.4415655 0.7796779 -0.4528117 0.4325091 0.8006195 -0.3997027 0.4463702 0.8101491 -0.3888668 0.4386812 0.8334914 -0.3241427 0.4474636 0.8389855 -0.3169394 0.4423269 0.8618636 -0.2439278 0.4446238 0.8606793 -0.2457542 0.4459103 0.8892124 -0.1459692 0.433583 0.8830789 -0.1571553 0.4421244 0.9033639 -0.05687075 0.4250878 0.9003085 -0.06435078 0.4304691 0.9068252 0.02865791 0.4205316 0.9057565 0.02477777 0.4230736 0.9080052 0.1560948 0.3887943 0.9033377 0.1106768 0.4144054 0.8689793 0.3842309 0.3118358 0.8827107 0.3058792 0.3567348 0.853715 0.4066769 0.3252455 0.8472402 0.4333176 0.3072785 0.8641119 0.3536235 0.3581357 0.8607115 0.3954198 0.3206542 0.8546526 0.2955298 0.4268855 0.8701785 0.3447449 0.3520515 0.8429418 0.235768 0.4835935 0.858819 0.2878223 0.4237787 0.8332567 0.243028 0.4966093 0.8346086 0.2582811 0.4865382 0.8104298 0.3316335 0.4829315 0.8119605 0.3124521 0.4930455 0.7652324 0.4766681 0.4326742 0.7810212 0.4165919 0.4652498 0.7183275 0.5690855 0.4001841 0.7218295 0.5608065 0.4055345 0.6770038 -0.6383791 0.3662487 0.6889909 -0.6296768 0.3588854 0.7230668 -0.5855589 0.3664633 0.7379266 -0.5728158 0.3568562 0.7574467 -0.5358999 0.3729425 0.7769749 -0.5171895 0.3589221 0.8002649 -0.4682587 0.3745799 0.8159068 -0.4501535 0.362847 0.8337836 -0.403341 0.3769896 0.8421862 -0.3925273 0.369655 0.8679073 -0.3246845 0.3759215 0.8713877 -0.3195224 0.3722755 0.9005424 -0.2316514 0.3679144 0.8974248 -0.2374238 0.3718314 0.9243006 -0.1375789 0.3560061 0.9191379 -0.1493377 0.3645325 0.9361665 -0.05089956 0.3478528 0.9339984 -0.05735218 0.3526437 0.9425926 0.05625671 0.3291725 0.938899 0.0371766 0.3421792 0.924446 0.2891773 0.2485481 0.9325613 0.1816642 0.3119738 0.8874861 0.3962538 0.2352689 0.8859652 0.4019403 0.2313215 0.8923149 0.3585199 0.274295 0.8860436 0.399184 0.2357522 0.9069175 0.2740945 0.3199577 0.9060199 0.3330413 0.2611737 0.8976082 0.2058407 0.3897812 0.9074754 0.272868 0.3194241 0.8857631 0.1842104 0.4260166 0.8921336 0.2230659 0.3928604 0.8731369 0.2378026 0.4255371 0.8731637 0.239561 0.4244947 0.8398016 0.3787645 0.3889355 0.8474414 0.3357352 0.4112482 0.7792878 0.5238881 0.3438777 0.7892127 0.4988704 0.3581506 0.7352684 0.5975546 0.3198578 0.7386052 0.5911697 0.3240078 0.7011432 -0.6440318 0.3059763 0.713018 -0.6342055 0.2989795 0.7429643 -0.5934358 0.3095774 0.7556749 -0.5815346 0.3012856 0.7813346 -0.541412 0.3104663 0.789851 -0.5325319 0.3042128 0.8238731 -0.4741602 0.3104922 0.8341825 -0.4616976 0.3016205 0.8642454 -0.3998143 0.3053335 0.8662543 -0.3970094 0.3032936 0.8996048 -0.3180244 0.2992854 0.8997966 -0.3177062 0.2990465 0.9302146 -0.2248596 0.2900676 0.9295735 -0.2262227 0.2910609 0.9514276 -0.1296572 0.2792395 0.9491529 -0.1361358 0.2838589 0.9637147 -0.0313881 0.2650827 0.9602773 -0.04613041 0.2752084 0.9671269 0.1309154 0.2180063 0.9637066 0.06707942 0.2583991 0.9218196 0.3566612 0.1517944 0.9342568 0.3025155 0.1888084 0.9169731 0.3497447 0.1919354 0.9069104 0.3940107 0.1492285 0.9179786 0.2999708 0.2594861 0.9197286 0.3429723 0.19097 0.9266843 0.209307 0.312165 0.9323841 0.2611036 0.2499697 0.9246823 0.1532799 0.3485226 0.9303653 0.1958914 0.3099145 0.9180139 0.1757293 0.355485 0.9184538 0.1834782 0.3503975 0.9003077 0.2810124 0.3323826 0.9037188 0.2465955 0.3499757 0.8514016 0.4404783 0.2847703 0.8663118 0.3911718 0.3106262 0.7858006 0.5676425 0.2455598 0.7972034 0.5454999 0.2586438 0.7136097 0.6708364 0.2018412 0.7354407 0.6401758 0.2220406 0.7259378 -0.6439335 0.2415865 0.7319929 -0.6384541 0.2378296 0.7635575 -0.5989418 0.2413482 0.7691675 -0.5933202 0.2373873 0.8073846 -0.539896 0.2379967 0.8082396 -0.5389135 0.2373204 0.8508253 -0.4699135 0.235112 0.8511359 -0.4694977 0.2348182 0.8921292 -0.3898552 0.2282946 0.8905189 -0.3924121 0.2301936 0.9262774 -0.3067587 0.2188822 0.9230001 -0.3131821 0.2235795 0.9543349 -0.2136074 0.2088468 0.9509969 -0.2221924 0.2150244 0.9729015 -0.1164348 0.1997643 0.9710537 -0.1232907 0.2045826 0.9838682 0.001333653 0.1788904 0.9809377 -0.02000391 0.1932905 0.9669392 0.2318143 0.1062583 0.9765659 0.1434051 0.1604807 0.9328404 0.3473259 0.0957784 0.9289405 0.3601187 0.08593142 0.9453933 0.2953781 0.1377803 0.9363731 0.3378369 0.09524577 0.9554443 0.2150485 0.2021886 0.9526205 0.2748664 0.1302414 0.9575273 0.1350989 0.2547349 0.9614808 0.1917635 0.1969304 0.9527578 0.1196541 0.2791693 0.9553586 0.1476268 0.2559222 0.9429985 0.1924318 0.2715212 0.9432025 0.1825605 0.277562 0.9048166 0.3598459 0.2276352 0.9173692 0.3056213 0.2550087 0.842065 0.5079796 0.1813374 0.8623129 0.4628016 0.2055024 0.7700714 0.622428 0.139905 0.7924237 0.5887469 0.1595057 0.6882168 0.7185387 0.1002994 0.7087494 0.6958526 0.1160328 0.7457387 -0.6422456 0.1771847 0.7499536 -0.6380455 0.1745495 0.7855768 -0.5943481 0.1721029 0.7825894 -0.5976174 0.1743767 0.8286297 -0.5348029 0.1654053 0.8269273 -0.5369524 0.1669541 0.8741159 -0.4596165 0.1570804 0.8702358 -0.4655261 0.1611689 0.9131271 -0.3794069 0.149162 0.9092614 -0.3865395 0.1543732 0.9454742 -0.2949342 0.1381758 0.9411722 -0.304916 0.1456752 0.9723842 -0.1966122 0.1257484 0.9682732 -0.2100107 0.1354348 0.989264 -0.0922417 0.1133497 0.987033 -0.1046179 0.1217426 0.9949944 0.07578253 0.06514084 0.9943863 0.01382619 0.1049035 0.9529399 0.3031591 3.63056e-4 0.9693652 0.2424103 0.03960102 0.9531888 0.3003905 0.03459548 0.9400289 0.3410926 -0.001234769 0.968426 0.2287736 0.09906452 0.9600244 0.2781258 0.03160858 0.9772881 0.1393078 0.1596916 0.9757161 0.1983494 0.09292894 0.9771373 0.08707803 0.1939591 0.9792256 0.126683 0.1583307 0.9731322 0.1074369 0.2036446 0.9734495 0.1195096 0.1952275 0.9574152 0.2183591 0.1888794 0.9591963 0.2025306 0.1972913 0.9011898 0.407523 0.1475877 0.9103351 0.3813842 0.1607366 0.8153653 0.5709013 0.09618347 0.8411477 0.5274317 0.1195254 0.7329099 0.6780645 0.05542135 0.7617384 0.6434957 0.0752868 0.6676183 0.7438391 0.03145128 0.6832411 0.729056 0.04073148 0.7589442 -0.6429266 0.1031951 0.7661983 -0.6350734 0.09809225 0.8042706 -0.5865315 0.09555017 0.798651 -0.5934125 0.1000907 0.8455057 -0.5264036 0.08955115 0.8416226 -0.531917 0.09346586 0.889795 -0.4490884 0.08114498 0.8858016 -0.4559845 0.08621925 0.9291241 -0.363412 0.06826692 0.9223988 -0.3780179 0.07926553 0.959808 -0.2752749 0.05470246 0.9538683 -0.2925115 0.06761956 0.9837925 -0.1745241 0.04115611 0.9799439 -0.1918848 0.05375999 0.9980613 -0.0579313 0.02275407 0.9961212 -0.07964581 0.03740751 0.9848321 0.1683297 -0.04208141 0.9962748 0.08580428 0.008616149 0.9545433 0.293767 -0.05047839 0.9504425 0.3052132 -0.05919533 0.9698289 0.243761 -0.003577947 0.9550015 0.292259 -0.05056494 0.9873898 0.1502051 0.04999929 0.977486 0.2104952 -0.0145964 0.9927257 0.06843221 0.09905928 0.9910517 0.1256075 0.0451585 0.9908865 0.05225366 0.1241515 0.9916135 0.08152258 0.1002836 0.9858146 0.1104062 0.1264125 0.9858365 0.1098117 0.1267591 0.9577175 0.2662639 0.1089988 0.9651361 0.2307123 0.1236301 0.8836593 0.4614892 0.07857453 0.9017153 0.421866 0.094545 0.781698 0.6224581 0.03865802 0.8118479 0.5809886 0.05792367 0.7035643 0.7104794 0.01470732 0.7281908 0.6848296 0.02732706 0.6560015 0.7547386 0.005642652 0.6647 0.7470526 0.009297907 0.7709616 -0.6361202 0.03113573 0.7699051 -0.6373587 0.03193879 0.8187274 -0.5737772 0.02157038 0.8126426 -0.5821253 0.02724242 0.8620966 -0.5066556 0.009468972 0.8535833 -0.5206168 0.01881074 0.9006919 -0.4344571 -0.001099884 0.8949437 -0.446123 0.007072746 0.9369583 -0.3491093 -0.0152325 0.9313085 -0.3642122 -0.00372672 0.9673073 -0.2518686 -0.02964323 0.9627938 -0.2697308 -0.01653695 0.9875838 -0.1505784 -0.04477143 0.985208 -0.1682335 -0.03259694 0.9963929 0.004872441 -0.08472156 0.9975104 -0.04850202 -0.05119341 0.9578624 0.2461189 -0.1480709 0.9784384 0.1772227 -0.1060675 0.9614387 0.249386 -0.1159412 0.9459807 0.2881506 -0.1486263 0.9831376 0.1752706 -0.05216073 0.9666233 0.2268257 -0.1191208 0.9969271 0.07830178 0.002302587 0.9888901 0.1362525 -0.05942916 0.9991174 0.02153748 0.03606569 0.9981245 0.06121385 5.06612e-4 0.998138 0.02586323 0.05524307 0.9981089 0.04849731 0.03777194 0.9920238 0.1116389 0.05852818 0.9919781 0.1121975 0.05823451 0.9525638 0.3009153 0.0455228 0.9600788 0.2742311 0.05518978 0.8652429 0.500521 0.02887272 0.8824036 0.4689177 0.03847384 0.7646933 0.6442831 0.01198589 0.7802197 0.6252064 0.0193454 0.6916322 0.7222484 0.001472234 0.70269 0.7114689 0.006227791 0.6558008 0.754934 2.69876e-4 0.6556894 0.7550308 2.30486e-4 0.7856903 -0.6167528 -0.04802936 0.7744545 -0.6314076 -0.03930217 0.8273676 -0.5585132 -0.05937993 0.8187839 -0.5718884 -0.05036401 0.8683773 -0.4908615 -0.07053977 0.8626796 -0.5018205 -0.06293118 0.9072803 -0.4119222 -0.08463281 0.9001868 -0.4293563 -0.07291787 0.9383415 -0.3315951 -0.09777498 0.9338975 -0.3468323 -0.08684962 0.9646986 -0.2401515 -0.1080918 0.9635364 -0.2468716 -0.1032088 0.9829434 -0.1384711 -0.1210288 0.9825655 -0.144694 -0.1167423 0.9815915 0.07416355 -0.1760058 0.9901964 0.01244723 -0.1391267 0.9498739 0.2431933 -0.1964607 0.9480837 0.2475002 -0.199702 0.9681431 0.1977977 -0.1535416 0.9500298 0.2425469 -0.1965059 0.9893153 0.0990172 -0.1070098 0.9731514 0.1581041 -0.1672707 0.9980943 0.009248673 -0.06101071 0.9913074 0.06652021 -0.1135116 0.9993176 -0.01675993 -0.03291809 0.9980513 0.01539927 -0.06046849 0.9998992 5.99351e-4 -0.01418983 0.9992735 0.02277773 -0.03055983 0.9945954 0.1036394 -0.006259799 0.9937081 0.1115587 -0.009955942 0.9522045 0.3054276 -0.004545152 0.952993 0.302969 -0.003767728 0.8632035 0.5048492 -0.002662181 0.8648366 0.5020496 -0.002030551 0.7657508 0.6431371 -6.65876e-4 0.764473 0.6446549 -0.001114487 0.6919031 0.7219903 5.73643e-4 0.6916093 0.7222718 4.63987e-4 0.6531958 0.7571892 -3.35862e-6 0.6558077 0.7549276 8.49747e-4 0.7874037 -0.6030862 -0.1276038 0.7806006 -0.6132073 -0.1209943 0.8289565 -0.5417175 -0.1391883 0.8210926 -0.5558296 -0.1298483 0.8677561 -0.4726606 -0.153595 0.8602671 -0.4898295 -0.1414492 0.9039304 -0.3925591 -0.1697275 0.8990792 -0.4081227 -0.1584067 0.9324073 -0.3112722 -0.1836478 0.929309 -0.3260487 -0.1734277 0.9549842 -0.2252829 -0.1930099 0.9540424 -0.2339987 -0.1872107 0.9708779 -0.1067991 -0.2144529 0.9711346 -0.1293023 -0.2004457 0.9506253 0.142412 -0.2757362 0.9657922 0.08721274 -0.2442114 0.9463685 0.2038927 -0.2506282 0.9290616 0.2381638 -0.2830593 0.970905 0.1417614 -0.1929959 0.9500135 0.1836521 -0.2524803 0.987917 0.03766816 -0.1503376 0.9754027 0.08741348 -0.2023577 0.9919211 -0.03332561 -0.1224016 0.9881139 0.001917898 -0.1537112 0.9937733 -0.04511082 -0.1018808 0.9923335 -0.02168875 -0.1216713 0.9960975 -0.02427577 -0.08485621 0.9950272 -0.004152834 -0.09951728 0.9939346 0.08393496 -0.07105654 0.9919456 0.09980934 -0.07798796 0.9570714 0.285158 -0.05195742 0.9514423 0.3025733 -0.05663019 0.8790503 0.4757508 -0.03052717 0.8645074 0.5014352 -0.0344938 0.7812544 0.624118 -0.01088809 0.7664822 0.6420968 -0.01472806 0.6984035 0.7157041 4.00169e-4 0.6919736 0.7219213 -0.001494109 0.6483367 0.7613538 -4.35688e-5 0.6531925 0.7571904 0.001480877 0.7778944 -0.5921258 -0.2103983 0.7722436 -0.601853 -0.2035014 0.8172116 -0.5315507 -0.2227536 0.8121604 -0.5424846 -0.2147231 0.8588277 -0.4525752 -0.2399809 0.8525871 -0.4707456 -0.2269231 0.8908325 -0.3754038 -0.2559095 0.8872709 -0.3916382 -0.2436597 0.9166791 -0.2974369 -0.2668912 0.9157311 -0.305718 -0.2607164 0.9377863 -0.2071181 -0.2786741 0.9375398 -0.2165499 -0.2722597 0.9457802 -0.02170991 -0.3240813 0.953392 -0.0910924 -0.287656 0.9352084 0.1363965 -0.3267738 0.930295 0.1506469 -0.3344503 0.9554949 0.1313003 -0.2641773 0.9281482 0.1962448 -0.3162735 0.9769322 0.06306934 -0.2040238 0.9555528 0.1300026 -0.2646095 0.984981 -0.01792687 -0.1717303 0.9773914 0.03123241 -0.2091187 0.9855347 -0.04940479 -0.1621128 0.9843591 -0.03594857 -0.1724671 0.9861697 -0.05502492 -0.1563383 0.9856257 -0.04769462 -0.1620723 0.9884212 -0.04168528 -0.1458968 0.987478 -0.02828729 -0.1552 0.990545 0.05120992 -0.1272721 0.9874474 0.07703351 -0.1378895 0.9689331 0.2291584 -0.09303367 0.9553244 0.2769541 -0.1032084 0.9122481 0.4056831 -0.05678731 0.8823738 0.4664859 -0.06170386 0.816115 0.5776336 -0.01719677 0.7828788 0.6217815 -0.02210468 0.7044612 0.7097426 -1.67067e-4 0.6985927 0.7155184 -0.001288652 0.6430785 0.7658003 -1.9221e-4 0.6483082 0.7613768 0.001382887 0.7641866 -0.5733059 -0.2955321 0.7567521 -0.5879856 -0.2856559 0.7998516 -0.5152628 -0.3078014 0.7930074 -0.5322954 -0.2963123 0.8424956 -0.4316558 -0.3222959 0.8366385 -0.4537971 -0.3067644 0.8735264 -0.3482201 -0.3401388 0.870173 -0.3728033 -0.322206 0.8941247 -0.2835642 -0.3466012 0.8938403 -0.2898974 -0.342066 0.9155693 -0.2240168 -0.3339904 0.9153535 -0.1976228 -0.3508179 0.9436709 -0.07072204 -0.3232393 0.9369658 -0.0173763 -0.3489889 0.9712644 0.02304363 -0.2368847 0.9368199 0.1370827 -0.3218336 0.9885414 0.06573551 -0.1358852 0.9669856 0.145723 -0.2090545 0.9939314 0.0277574 -0.1064427 0.9881928 0.07544451 -0.1333538 0.9936879 -0.01275873 -0.1114521 0.9938167 -0.01552754 -0.1099424 0.9912525 -0.0191043 -0.1305894 0.992608 -0.05060052 -0.1103134 0.9886797 -0.02885007 -0.1472415 0.9900869 -0.05579143 -0.1289 0.9877012 -0.03212195 -0.1530184 0.988259 -0.04172354 -0.1469807 0.9901949 0.01742464 -0.138602 0.9874597 0.04767996 -0.1504991 0.9873352 0.1238276 -0.09917658 0.9682791 0.2215062 -0.115632 0.9583231 0.2808933 -0.05211406 0.9120686 0.4062774 -0.05540299 0.8476536 0.5304671 -0.009396314 0.814567 0.5799567 -0.01144093 0.68537 0.7281948 5.19242e-4 0.703951 0.7102421 0.003034949 0.637951 0.7700769 -2.25763e-4 0.6430499 0.7658233 0.001293718 0.7478705 -0.5523746 -0.3682011 0.742273 -0.5654745 -0.3595407 0.7826198 -0.4867191 -0.388086 0.7761851 -0.5085018 -0.3727768 0.8142442 -0.4123386 -0.4086359 0.8108803 -0.4333712 -0.3932717 0.8413175 -0.3422807 -0.4183647 0.8409627 -0.3501443 -0.4125296 0.8636155 -0.3092675 -0.3981479 0.8642816 -0.2782446 -0.4190436 0.8852661 -0.2995938 -0.3557351 0.8938591 -0.220933 -0.3901343 0.9408681 -0.1818457 -0.2858309 0.9498748 -0.0679683 -0.3051531 0.9836521 -0.05820882 -0.1704126 0.9749515 0.02957415 -0.2204429 0.9972804 -1.87527e-4 -0.07370066 0.9898566 0.07134008 -0.1228609 0.9990664 -0.0203545 -0.03810739 0.9970524 0.03430724 -0.06862634 0.9990872 -0.01286292 -0.04073584 0.9991263 -0.016954 -0.03820294 0.9984794 -0.008534133 -0.05446225 0.9987634 -0.02952426 -0.04000264 0.9973195 -0.01258474 -0.07208025 0.9977717 -0.04058098 -0.05296075 0.9963126 -0.01106154 -0.08508133 0.9969182 -0.03349417 -0.07093816 0.9969567 0.006383776 -0.07769668 0.9960093 0.02437263 -0.08585774 0.9974596 0.05077373 -0.04996562 0.9882215 0.1364952 -0.06919115 0.9860157 0.1650902 -0.0227639 0.956194 0.2911182 -0.03071504 0.8625152 0.5060256 -0.002439737 0.8463263 0.532653 -0.003570795 0.6684858 0.7437249 1.22303e-4 0.6852352 0.7283184 0.002260208 0.6358041 0.7718505 -2.86438e-4 0.6379476 0.7700797 3.71091e-4 0.7255021 -0.5244783 -0.4456112 0.7197757 -0.5397198 -0.4366068 0.7633336 -0.4488197 -0.4646319 0.7567268 -0.4779878 -0.4459732 0.7856989 -0.388495 -0.4814032 0.7832487 -0.4119604 -0.4656289 0.8053022 -0.3637325 -0.4681742 0.8052529 -0.3474895 -0.4804363 0.8281908 -0.3724934 -0.4187466 0.8292416 -0.3156692 -0.4612066 0.8477035 -0.3674159 -0.3826282 0.8650879 -0.3117858 -0.3929538 0.9032386 -0.3027427 -0.3041496 0.9481515 -0.1721695 -0.2671452 0.9791674 -0.1521952 -0.1344176 0.986932 -0.04827702 -0.1537353 0.9949238 -0.09735298 -0.02547603 0.9967805 -0.002667903 -0.08013409 0.998867 -0.04730057 -0.005250036 0.9995083 -0.02009749 -0.02407157 0.9998862 -0.01105213 -0.01026701 0.9998649 -0.0148105 -0.007136583 0.999874 -0.004430115 -0.01524752 0.999894 -0.0103318 -0.01025927 0.9997222 -0.005203902 -0.02299362 0.9997707 -0.01472342 -0.01555287 0.9995949 -0.003834843 -0.02820187 0.9996739 -0.01102524 -0.02303618 0.9997012 0.001687943 -0.02438914 0.9995679 0.008319616 -0.0281915 0.9997209 0.01971685 -0.01301872 0.9982304 0.05481183 -0.02306169 0.993647 0.1124367 -0.004856765 0.9857856 0.1677238 -0.009774208 0.8656426 0.5006626 -2.54713e-4 0.8623539 0.5063058 -5.29282e-4 0.6649682 0.7468717 1.00656e-4 0.6684779 0.7437318 5.60371e-4 0.6352705 0.7722899 -1.29027e-4 0.6358047 0.7718501 4.10326e-5 0.695177 -0.4977546 -0.5186225 0.6922235 -0.5099297 -0.5106843 0.7277735 -0.4310236 -0.5334457 0.7271186 -0.4456842 -0.5221727 0.7498064 -0.3866823 -0.5369052 0.7498459 -0.3872147 -0.5364662 0.761404 -0.4039379 -0.5070484 0.7559068 -0.3749881 -0.5366461 0.772572 -0.4310484 -0.4661867 0.759773 -0.4060773 -0.5077857 0.790819 -0.4326815 -0.4328881 0.7927019 -0.4101405 -0.4510084 0.8384103 -0.4036442 -0.3662509 0.8695607 -0.3360691 -0.3618314 0.9389718 -0.2989612 -0.1701592 0.9527173 -0.1985411 -0.2300247 0.9865115 -0.1600944 -0.03413259 0.9894212 -0.1110538 -0.09334319 0.9986974 -0.04495251 -0.02414691 0.9986782 -0.04705399 -0.0206868 0.9997839 -0.01176178 -0.01714015 0.9997715 -0.01124596 -0.01817691 0.9999161 -0.006710708 -0.011083 0.9998825 -0.004393577 -0.01469522 0.9999461 -0.006040573 -0.008459985 0.9999378 -0.004228472 -0.01032888 0.9999688 -0.003799915 -0.006926834 0.9999659 -0.002654731 -0.007826089 0.9999871 1.58608e-4 -0.005097329 0.999977 0.002289116 -0.006384491 0.9998962 0.01414543 -0.002759873 0.9997889 0.02005076 -0.00448805 0.99405 0.1089136 -0.001579165 0.9936431 0.1125602 -0.001915037 0.8671017 0.4981311 -2.1041e-4 0.8656399 0.500667 -3.33062e-4 0.6693257 0.7429689 6.65764e-4 0.664969 0.746871 1.01612e-4 0.6358217 0.771836 3.72061e-4 0.6352705 0.7722897 1.90313e-4 0.6629191 -0.4661762 -0.5858483 0.6605604 -0.4791026 -0.5780318 0.6836589 -0.4220769 -0.5953668 0.6834449 -0.4341316 -0.5868841 0.7076447 -0.4114904 -0.5743821 0.702906 -0.3929173 -0.5929076 0.7209083 -0.4381282 -0.5369684 0.7009051 -0.4200011 -0.5764816 0.723955 -0.4650562 -0.5095214 0.6928253 -0.4641992 -0.5518262 0.737457 -0.4727771 -0.4823268 0.7187741 -0.4693837 -0.5128769 0.7840616 -0.4353475 -0.4424025 0.7824854 -0.4304804 -0.4498927 0.8706491 -0.3324382 -0.3625673 0.8700059 -0.3313843 -0.3650676 0.9429246 -0.1674824 -0.2878243 0.9533358 -0.1784651 -0.243518 0.9830721 -0.05914974 -0.1734088 0.9815245 -0.05822736 -0.1822617 0.9954997 -0.03294491 -0.08885467 0.9897974 -0.03200638 -0.138841 0.9983273 -0.02733629 -0.05094617 0.9966706 -0.02436822 -0.07780867 0.9993082 -0.02277141 -0.02940201 0.9990536 -0.01634579 -0.04030799 0.999805 -0.01334089 -0.01456081 0.9997935 -0.006886899 -0.01912128 0.9999547 -0.002953767 -0.009056866 0.9999478 -5.57561e-4 -0.01020836 0.999723 0.0217573 -0.008982777 0.9998789 0.01382809 -0.007141649 0.9870685 0.1599713 -0.01024508 0.9940581 0.1086638 -0.006400883 0.8276472 0.5612085 -0.006720066 0.8673554 0.4976693 -0.004476547 0.6702712 0.7421158 -8.00496e-4 0.6694111 0.7428917 -8.77643e-4 0.6361138 0.7715952 4.44305e-4 0.6358208 0.7718367 3.67596e-4 0.6324139 -0.4499092 -0.6305828 0.631677 -0.4560593 -0.6268925 0.6549149 -0.4251377 -0.6247755 0.654188 -0.4195573 -0.6292931 0.6712074 -0.4439277 -0.5936404 0.6629949 -0.4164959 -0.6220682 0.6685599 -0.4687516 -0.5773211 0.6593426 -0.4509455 -0.6015942 0.6173062 -0.4983778 -0.6087303 0.6059997 -0.4945731 -0.6230264 0.6014538 -0.4920065 -0.6294306 0.6152226 -0.4992746 -0.6101033 0.6274456 -0.3912187 -0.6732459 0.6743692 -0.4415341 -0.5918395 0.6487302 -0.2735852 -0.7101411 0.6974412 -0.3141945 -0.6440944 0.7135566 -0.1807432 -0.6768818 0.7091898 -0.1788455 -0.6819561 0.8813886 -0.1334842 -0.4531402 0.7696126 -0.1248901 -0.6261783 0.9671149 -0.1051934 -0.2315669 0.8883972 -0.1266797 -0.4412513 0.9823674 -0.100349 -0.1577479 0.9695298 -0.1000109 -0.2236288 0.9854189 -0.1066951 -0.132537 0.9857621 -0.08791816 -0.143331 0.9928534 -0.07676661 -0.09137433 0.9938313 -0.06070345 -0.09281402 0.9977003 -0.02221429 -0.06403696 0.9976044 -0.02775621 -0.06336522 0.9954298 0.07451391 -0.05972594 0.9984267 0.009436547 -0.05527305 0.944159 0.3256368 -0.05024564 0.9873785 0.1499741 -0.05090683 0.7764143 0.6298106 -0.02279078 0.8335446 0.551845 -0.02589845 0.6758796 0.7369933 -0.005257248 0.6714447 0.7410359 -0.005279898 0.6352012 0.7723467 2.14014e-4 0.6361192 0.7715908 3.92744e-4 0.5961141 -0.4377055 -0.6730988 0.5959571 -0.4403923 -0.6714834 0.6227703 -0.4492189 -0.6405933 0.608727 -0.4252014 -0.6698174 0.654081 -0.4649261 -0.5966756 0.6254939 -0.4477251 -0.6389833 0.6256917 -0.4762747 -0.6177964 0.6229703 -0.4735879 -0.6225934 0.520809 -0.496656 -0.6943277 0.5255369 -0.5015895 -0.687182 0.5234481 -0.4583205 -0.7182927 0.5395746 -0.4873949 -0.686517 0.5669825 -0.3580941 -0.7418217 0.5791983 -0.3851188 -0.7184796 0.6074361 -0.2610188 -0.7502603 0.6115117 -0.2677567 -0.7445535 0.6943579 -0.2266042 -0.683021 0.6333599 -0.1813358 -0.7523115 0.8490102 -0.2023674 -0.4880875 0.7259108 -0.1763615 -0.6647934 0.9220484 -0.2036808 -0.3291521 0.8526572 -0.1981804 -0.4834257 0.933856 -0.2225785 -0.2799499 0.9297235 -0.1906422 -0.3150714 0.9183615 -0.2689219 -0.2903329 0.934413 -0.2214624 -0.2789744 0.9245378 -0.2572494 -0.2811631 0.9256191 -0.2541276 -0.2804434 0.9661784 -0.1011393 -0.2372133 0.9524438 -0.1802989 -0.2456486 0.972363 0.1175725 -0.2017104 0.9753492 -0.03443056 -0.2179648 0.9342073 0.3194399 -0.1587918 0.9577658 0.2284855 -0.1745824 0.8354678 0.5419662 -0.09091871 0.8193078 0.5670084 -0.08506637 0.7083524 0.7052612 -0.02904373 0.6896315 0.7237015 -0.02578014 0.6354337 0.7721375 -0.005267798 0.6366138 0.7711662 -0.005080938 0.5537027 -0.4331417 -0.7111974 0.5523353 -0.4277442 -0.7155143 0.54996 -0.454136 -0.7009311 0.5384373 -0.4460633 -0.7149215 0.5493771 -0.4713825 -0.6899154 0.5218308 -0.4635047 -0.7161397 0.526745 -0.4765609 -0.7038676 0.5272979 -0.4768329 -0.7032691 0.4867137 -0.4884297 -0.7242557 0.4889966 -0.4941825 -0.7187948 0.513258 -0.4482969 -0.7318444 0.5141312 -0.4574925 -0.7255135 0.5614619 -0.359256 -0.74545 0.5612491 -0.3584586 -0.7459939 0.6232426 -0.3000934 -0.7221583 0.597895 -0.2606219 -0.7580223 0.7530519 -0.2790445 -0.5958583 0.6527526 -0.2301095 -0.7217782 0.8752849 -0.2280802 -0.4264457 0.7944015 -0.2252635 -0.5640769 0.8681967 -0.3016541 -0.3940042 0.8400633 -0.2713369 -0.4697554 0.8454775 -0.3665618 -0.3883304 0.8639491 -0.3076817 -0.3986526 0.8120499 -0.4299887 -0.3945689 0.846082 -0.3656692 -0.387855 0.817584 -0.4284231 -0.3847208 0.8364719 -0.3930689 -0.3818529 0.9056798 -0.2455663 -0.345603 0.8973773 -0.2723333 -0.3472013 0.9559928 0.0173819 -0.2928748 0.9551291 -0.02029651 -0.2954939 0.9317436 0.2770434 -0.2347358 0.9426926 0.2319885 -0.2398166 0.8338209 0.5269631 -0.1644777 0.8621794 0.476527 -0.1719551 0.7281241 0.6779995 -0.1007574 0.7353899 0.6700493 -0.1011725 0.6457403 0.7617728 -0.05217069 0.6437841 0.7633614 -0.05311745 0.5379789 -0.4410011 -0.7183988 0.5281304 -0.4280508 -0.7333831 0.5426473 -0.4608191 -0.7022675 0.5241608 -0.4509745 -0.7224109 0.5127933 -0.4685851 -0.7193546 0.5111654 -0.4680407 -0.7208661 0.4962353 -0.4777594 -0.7249115 0.4938506 -0.4760049 -0.7276887 0.4808195 -0.4863367 -0.7295815 0.4814023 -0.4890091 -0.7274078 0.5087925 -0.4468962 -0.7358084 0.5092117 -0.4483018 -0.7346625 0.562081 -0.3804098 -0.7344068 0.5456831 -0.3568606 -0.7582087 0.7004268 -0.3535813 -0.6199861 0.5773178 -0.2989354 -0.7598301 0.8944225 -0.2403828 -0.3771266 0.7297891 -0.2869448 -0.6205405 0.9610909 -0.1496687 -0.2321717 0.9208489 -0.1883816 -0.3413938 0.8998407 -0.2606923 -0.3497518 0.9103116 -0.2578054 -0.323835 0.8050394 -0.4073205 -0.4312791 0.8051435 -0.4032878 -0.4348599 0.7275182 -0.5212134 -0.4461547 0.7431593 -0.4896901 -0.4559803 0.7277382 -0.5306141 -0.434564 0.7447172 -0.4978178 -0.4444928 0.8392387 -0.3346654 -0.4285762 0.8363333 -0.3450348 -0.4260255 0.9044156 0.01521646 -0.426381 0.9113309 -0.09344738 -0.4009285 0.8464025 0.3257573 -0.4212898 0.9018145 0.1866999 -0.3897101 0.7664898 0.5110819 -0.3889585 0.8134641 0.4466066 -0.3725841 0.6934757 0.6359019 -0.3387037 0.7236896 0.6089664 -0.3247051 0.6111769 0.7405756 -0.2793039 0.6364231 0.7289176 -0.2522792 -0.578433 -0.6045661 0.5476451 -0.5609424 -0.5945754 0.5760415 -0.5989244 -0.5659092 0.5666007 -0.5958402 -0.5625584 0.5731515 -0.626006 -0.523446 0.5780318 -0.6197489 -0.5138881 0.5931529 -0.6553924 -0.4676195 0.5931213 -0.6489133 -0.4595269 0.6064212 -0.6846724 -0.4066771 0.6048449 -0.6770579 -0.3973075 0.6194671 -0.7136095 -0.3386371 0.613259 -0.7049478 -0.3276975 0.6290175 -0.7404997 -0.2610598 0.6192803 -0.7306482 -0.2508274 0.635011 -0.7582856 -0.175316 0.627907 -0.7520584 -0.1694381 0.636945 -0.7747057 -0.08797711 0.6261719 -0.767529 -0.07983279 0.6360236 -0.7830146 0.007658302 0.6219562 -0.7782819 0.01281911 0.6277842 -0.7775219 0.08886855 0.622545 -0.7798441 0.08633989 0.619991 -0.7632253 0.1627478 0.6253002 -0.7739644 0.1473987 0.6158352 -0.7475623 0.2993471 0.5929098 -0.7568349 0.2825376 0.589384 -0.6815123 0.4932767 0.540573 -0.7194491 0.4559449 0.5239344 -0.6286275 0.4895035 0.6043292 -0.6961091 0.4542813 0.5559323 -0.6497279 0.4368568 0.6221012 -0.6640391 0.4305657 0.6112817 -0.6760495 0.3669039 0.6390138 -0.6788965 0.36525 0.6369396 -0.6775165 0.3476061 0.6481832 -0.6822814 0.3426013 0.6458455 -0.6597881 0.3934874 0.6401932 -0.6672602 0.3843687 0.6379848 -0.6443448 0.4372373 0.6274102 -0.6487635 0.429327 0.6283187 0.4526983 -0.4233037 -0.7847792 0.486229 -0.4372176 -0.756586 0.4418244 -0.4380462 -0.7828837 0.4693196 -0.447763 -0.7610831 0.4662541 -0.4619717 -0.7544465 0.4761582 -0.4648178 -0.7464703 0.4588776 -0.4706891 -0.7535803 0.4772932 -0.4777385 -0.7375345 0.4487456 -0.4790635 -0.7544041 0.4586245 -0.4873138 -0.7430942 0.4936545 -0.478071 -0.7264664 0.454045 -0.4257779 -0.78266 0.5758826 -0.4394192 -0.6893983 0.4512007 -0.3309792 -0.8287767 0.6814281 -0.3861523 -0.6217251 0.5276665 -0.3598062 -0.7694853 0.8666399 -0.2771043 -0.4149078 0.6734827 -0.364744 -0.6429487 0.9587776 -0.1578281 -0.2362961 0.8787337 -0.2502601 -0.4064444 0.8580402 -0.2857846 -0.4267252 0.9359206 -0.21571 -0.2784276 0.7033798 -0.4196135 -0.5737434 0.7650421 -0.4325938 -0.4770466 0.6398952 -0.5049442 -0.5792803 0.6450531 -0.5458464 -0.5347508 0.6352541 -0.5036381 -0.5854922 0.636101 -0.5189894 -0.5709865 0.6562509 -0.3108764 -0.687525 0.6658406 -0.3480765 -0.6599236 0.6231532 0.02267462 -0.7817712 0.6865868 -0.08310604 -0.7222825 0.5942965 0.2395347 -0.7677466 0.6405618 0.1800467 -0.7465011 0.551849 0.4120311 -0.725047 0.606198 0.3489022 -0.7146967 0.4827309 0.5738468 -0.6615669 0.5612791 0.5013962 -0.6584587 0.4667188 0.6551332 -0.5941163 0.4997121 0.6261476 -0.5985208 0.6103218 -0.5994797 0.517814 0.6329533 -0.5849665 0.5071334 0.6303206 -0.5674871 0.5297684 0.6542541 -0.5494982 0.5196185 0.6667854 -0.5163617 0.5373713 0.6852685 -0.5019791 0.5276592 0.6960719 -0.4602586 0.5510408 0.7184801 -0.4402387 0.5384944 0.7277696 -0.3931932 0.5619168 0.7422149 -0.379764 0.5521743 0.756875 -0.3248752 0.5670947 0.7646996 -0.3171096 0.5609599 0.7843192 -0.2481656 0.5685572 0.7892099 -0.2428289 0.5640763 0.8082926 -0.1629559 0.5657811 0.808255 -0.1630042 0.5658212 0.8254886 -0.07318407 0.5596541 0.8238112 -0.07561892 0.5617979 0.8325341 0.01560187 0.5537541 0.8330882 0.0165919 0.5528914 0.8274568 0.08745574 0.5546773 0.8302968 0.09526342 0.5491195 0.8191522 0.1579467 0.5514004 0.8200472 0.1632522 0.5485174 0.7937412 0.3829085 0.4726057 0.798556 0.3210952 0.509123 0.765391 0.4396215 0.4700103 0.7644032 0.460146 0.4516119 0.7544463 0.4233098 0.501617 0.7655359 0.439423 0.4699599 0.7480049 0.3705267 0.5506349 0.7870185 0.390973 0.4772232 0.7442829 0.3087007 0.592239 0.7722465 0.338185 0.5378349 0.7327277 0.3169521 0.6022056 0.7350862 0.3301818 0.5921389 0.7111065 0.3776533 0.5930477 0.7109967 0.3747344 0.5950276 0.6847007 0.467871 0.5588218 0.6948034 0.4230026 0.5816504 -0.6202564 0.5785175 0.5297164 -0.6458365 0.5467531 0.5328755 -0.6678617 0.476965 0.5713714 -0.6970136 0.4329878 0.5715714 -0.7050221 0.3831694 0.5967622 -0.7064946 0.3812164 0.5962713 -0.7352232 0.3230184 0.5959078 -0.7243576 0.3353872 0.6023468 -0.7973957 0.2962657 0.5257252 -0.7209176 0.3548731 0.5952671 -0.8250679 0.3441424 0.4481394 -0.7028251 0.4202352 0.5739681 -0.7750576 0.4167395 0.4749883 -0.7215641 0.4490541 0.5269685 -0.7671301 0.4390459 0.4677074 -0.7446035 0.4596791 0.484005 -0.778441 0.3811313 0.4987672 -0.7994201 0.3443928 0.4922614 -0.808876 0.1629902 0.5649369 -0.8120408 0.1556324 0.5624663 -0.8171345 0.08838152 0.5696313 -0.8151162 0.0920667 0.5719347 -0.8186979 0.01555335 0.5740138 -0.81822 0.01649206 0.5746687 -0.8098886 -0.07715523 0.5814874 -0.8098269 -0.07699453 0.5815945 -0.7963539 -0.1705552 0.5802858 -0.7937381 -0.1633327 0.58592 -0.7787487 -0.2519698 0.57451 -0.7759709 -0.2428895 0.5821288 -0.7528188 -0.3298078 0.5696408 -0.7513535 -0.3221783 0.5759072 -0.7213952 -0.4036195 0.5627435 -0.7206423 -0.3926405 0.5714089 -0.6934176 -0.4667025 0.5489636 -0.6936167 -0.4505202 0.5620743 -0.6647762 -0.5201984 0.5361589 -0.6666613 -0.5054917 0.54776 -0.632891 -0.5687456 0.5253357 -0.6348843 -0.5564475 0.5359926 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 2 1 3 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 9 4 10 4 8 5 10 5 11 5 12 6 13 6 14 6 12 7 14 7 15 7 16 8 17 8 18 8 16 9 18 9 19 9 20 10 15 10 14 10 20 11 14 11 21 11 22 12 23 12 24 12 22 13 24 13 25 13 25 14 24 14 26 14 25 15 26 15 27 15 27 16 26 16 28 16 27 17 28 17 29 17 29 18 28 18 30 18 29 19 30 19 31 19 31 20 30 20 32 20 31 21 32 21 33 21 33 22 32 22 34 22 33 23 34 23 35 23 35 24 34 24 36 24 35 25 36 25 37 25 37 26 36 26 38 26 37 27 38 27 39 27 39 28 38 28 40 28 39 29 40 29 41 29 41 30 40 30 42 30 41 31 42 31 43 31 43 32 42 32 44 32 43 33 44 33 45 33 45 34 44 34 46 34 45 35 46 35 47 35 47 36 46 36 48 36 47 37 48 37 49 37 49 38 48 38 50 38 49 39 50 39 51 39 51 40 50 40 52 40 51 41 52 41 53 41 53 42 52 42 54 42 53 43 54 43 55 43 55 44 54 44 56 44 55 45 56 45 57 45 57 46 56 46 58 46 57 47 58 47 59 47 59 48 58 48 60 48 59 49 60 49 61 49 61 50 60 50 13 50 61 51 13 51 12 51 19 52 18 52 62 52 19 53 62 53 63 53 63 54 62 54 64 54 63 55 64 55 65 55 65 56 64 56 66 56 65 57 66 57 67 57 67 58 66 58 68 58 67 59 68 59 69 59 69 60 68 60 70 60 69 61 70 61 71 61 71 62 70 62 72 62 71 63 72 63 73 63 73 64 72 64 74 64 73 65 74 65 75 65 75 66 74 66 76 66 75 67 76 67 77 67 77 68 76 68 78 68 77 69 78 69 79 69 79 70 78 70 80 70 79 71 80 71 81 71 81 72 80 72 82 72 81 73 82 73 83 73 83 74 82 74 84 74 83 75 84 75 85 75 85 76 84 76 86 76 85 77 86 77 87 77 87 78 86 78 88 78 87 79 88 79 89 79 89 80 88 80 90 80 89 81 90 81 91 81 91 82 90 82 92 82 91 83 92 83 93 83 93 84 92 84 94 84 93 85 94 85 95 85 95 86 94 86 96 86 95 87 96 87 97 87 97 88 96 88 98 88 97 89 98 89 99 89 99 90 98 90 9 90 99 91 9 91 8 91 100 92 101 92 102 92 100 93 102 93 103 93 103 94 102 94 104 94 103 95 104 95 105 95 105 96 104 96 106 96 105 97 106 97 107 97 107 98 106 98 108 98 107 99 108 99 109 99 109 100 108 100 110 100 109 101 110 101 111 101 111 102 110 102 112 102 111 103 112 103 113 103 113 104 112 104 114 104 113 105 114 105 115 105 115 106 114 106 116 106 115 107 116 107 117 107 117 108 116 108 118 108 117 109 118 109 119 109 119 110 118 110 120 110 119 111 120 111 121 111 121 112 120 112 122 112 121 113 122 113 123 113 123 114 122 114 124 114 123 115 124 115 125 115 125 116 124 116 126 116 125 117 126 117 127 117 127 118 126 118 128 118 127 119 128 119 129 119 129 120 128 120 130 120 129 121 130 121 131 121 131 122 130 122 132 122 131 123 132 123 133 123 133 124 132 124 134 124 133 125 134 125 135 125 135 126 134 126 136 126 135 127 136 127 137 127 137 128 136 128 138 128 137 129 138 129 139 129 139 130 138 130 5 130 139 131 5 131 4 131 140 132 141 132 142 132 140 133 142 133 143 133 143 134 142 134 144 134 143 135 144 135 145 135 145 136 144 136 146 136 145 137 146 137 147 137 147 138 146 138 148 138 147 139 148 139 149 139 149 140 148 140 150 140 149 141 150 141 151 141 151 142 150 142 152 142 151 143 152 143 153 143 153 144 152 144 154 144 153 145 154 145 155 145 155 146 154 146 156 146 155 147 156 147 157 147 157 148 156 148 158 148 157 149 158 149 159 149 159 150 158 150 160 150 159 151 160 151 161 151 161 152 160 152 162 152 161 153 162 153 163 153 163 154 162 154 164 154 163 155 164 155 165 155 165 156 164 156 166 156 165 157 166 157 167 157 167 158 166 158 168 158 167 159 168 159 169 159 169 160 168 160 170 160 169 161 170 161 171 161 171 162 170 162 172 162 171 163 172 163 173 163 173 164 172 164 174 164 173 165 174 165 175 165 175 166 174 166 176 166 175 167 176 167 177 167 177 168 176 168 178 168 177 169 178 169 179 169 179 170 178 170 1 170 179 171 1 171 0 171 178 172 180 172 181 172 178 173 181 173 1 173 180 174 182 174 183 174 180 175 183 175 181 175 182 176 184 176 185 176 182 177 185 177 183 177 184 178 186 178 187 178 184 179 187 179 185 179 186 180 188 180 189 180 186 181 189 181 187 181 188 182 190 182 191 182 188 183 191 183 189 183 190 184 192 184 193 184 190 185 193 185 191 185 192 186 194 186 195 186 192 187 195 187 193 187 194 188 196 188 197 188 194 189 197 189 195 189 196 190 198 190 199 190 196 191 199 191 197 191 198 192 200 192 201 192 198 193 201 193 199 193 200 194 202 194 203 194 200 195 203 195 201 195 202 196 204 196 205 196 202 197 205 197 203 197 204 198 206 198 207 198 204 199 207 199 205 199 206 200 208 200 209 200 206 201 209 201 207 201 208 202 210 202 211 202 208 203 211 203 209 203 210 204 212 204 213 204 210 205 213 205 211 205 212 206 214 206 215 206 212 207 215 207 213 207 214 208 216 208 217 208 214 209 217 209 215 209 216 210 139 210 4 210 216 211 4 211 217 211 176 212 218 212 180 212 176 213 180 213 178 213 218 214 219 214 182 214 218 215 182 215 180 215 219 216 220 216 184 216 219 217 184 217 182 217 220 218 221 218 186 218 220 219 186 219 184 219 221 220 222 220 188 220 221 221 188 221 186 221 222 222 223 222 190 222 222 223 190 223 188 223 223 224 224 224 192 224 223 225 192 225 190 225 224 226 225 226 194 226 224 227 194 227 192 227 225 228 226 228 196 228 225 229 196 229 194 229 226 230 227 230 198 230 226 231 198 231 196 231 227 232 228 232 200 232 227 233 200 233 198 233 228 234 229 234 202 234 228 235 202 235 200 235 229 236 230 236 204 236 229 237 204 237 202 237 230 238 231 238 206 238 230 239 206 239 204 239 231 240 232 240 208 240 231 241 208 241 206 241 232 242 233 242 210 242 232 243 210 243 208 243 233 244 234 244 212 244 233 245 212 245 210 245 234 246 235 246 214 246 234 247 214 247 212 247 235 248 236 248 216 248 235 249 216 249 214 249 236 250 137 250 139 250 236 251 139 251 216 251 174 252 237 252 218 252 174 253 218 253 176 253 237 254 238 254 219 254 237 255 219 255 218 255 238 256 239 256 220 256 238 257 220 257 219 257 239 258 240 258 221 258 239 259 221 259 220 259 240 260 241 260 222 260 240 261 222 261 221 261 241 262 242 262 223 262 241 263 223 263 222 263 242 264 243 264 224 264 242 265 224 265 223 265 243 266 244 266 225 266 243 267 225 267 224 267 244 268 245 268 226 268 244 269 226 269 225 269 245 270 246 270 227 270 245 271 227 271 226 271 246 272 247 272 228 272 246 273 228 273 227 273 247 274 248 274 229 274 247 275 229 275 228 275 248 276 249 276 230 276 248 277 230 277 229 277 249 278 250 278 231 278 249 279 231 279 230 279 250 280 251 280 232 280 250 281 232 281 231 281 251 282 252 282 233 282 251 283 233 283 232 283 252 284 253 284 234 284 252 285 234 285 233 285 253 286 254 286 235 286 253 287 235 287 234 287 254 288 255 288 236 288 254 289 236 289 235 289 255 290 135 290 137 290 255 291 137 291 236 291 172 292 256 292 237 292 172 293 237 293 174 293 256 294 257 294 238 294 256 295 238 295 237 295 257 296 258 296 239 296 257 297 239 297 238 297 258 298 259 298 240 298 258 299 240 299 239 299 259 300 260 300 241 300 259 301 241 301 240 301 260 302 261 302 242 302 260 303 242 303 241 303 261 304 262 304 243 304 261 305 243 305 242 305 262 306 263 306 244 306 262 307 244 307 243 307 263 308 264 308 245 308 263 309 245 309 244 309 264 310 265 310 246 310 264 311 246 311 245 311 265 312 266 312 247 312 265 313 247 313 246 313 266 314 267 314 248 314 266 315 248 315 247 315 267 316 268 316 249 316 267 317 249 317 248 317 268 318 269 318 250 318 268 319 250 319 249 319 269 320 270 320 251 320 269 321 251 321 250 321 270 322 271 322 252 322 270 323 252 323 251 323 271 324 272 324 253 324 271 325 253 325 252 325 272 326 273 326 254 326 272 327 254 327 253 327 273 328 274 328 255 328 273 329 255 329 254 329 274 330 133 330 135 330 274 331 135 331 255 331 170 332 275 332 256 332 170 333 256 333 172 333 275 334 276 334 257 334 275 335 257 335 256 335 276 336 277 336 258 336 276 337 258 337 257 337 277 338 278 338 259 338 277 339 259 339 258 339 278 340 279 340 260 340 278 341 260 341 259 341 279 342 280 342 261 342 279 343 261 343 260 343 280 344 281 344 262 344 280 345 262 345 261 345 281 346 282 346 263 346 281 347 263 347 262 347 282 348 283 348 264 348 282 349 264 349 263 349 283 350 284 350 265 350 283 351 265 351 264 351 284 352 285 352 266 352 284 353 266 353 265 353 285 354 286 354 267 354 285 355 267 355 266 355 286 356 287 356 268 356 286 357 268 357 267 357 287 358 288 358 269 358 287 359 269 359 268 359 288 360 289 360 270 360 288 361 270 361 269 361 289 362 290 362 271 362 289 363 271 363 270 363 290 364 291 364 272 364 290 365 272 365 271 365 291 366 292 366 273 366 291 367 273 367 272 367 292 368 293 368 274 368 292 369 274 369 273 369 293 370 131 370 133 370 293 371 133 371 274 371 168 372 294 372 275 372 168 373 275 373 170 373 294 374 295 374 276 374 294 375 276 375 275 375 295 376 296 376 277 376 295 377 277 377 276 377 296 378 297 378 278 378 296 379 278 379 277 379 297 380 298 380 279 380 297 381 279 381 278 381 298 382 299 382 280 382 298 383 280 383 279 383 299 384 300 384 281 384 299 385 281 385 280 385 300 386 301 386 282 386 300 387 282 387 281 387 301 388 302 388 283 388 301 389 283 389 282 389 302 390 303 390 284 390 302 391 284 391 283 391 303 392 304 392 285 392 303 393 285 393 284 393 304 394 305 394 286 394 304 395 286 395 285 395 305 396 306 396 287 396 305 397 287 397 286 397 306 398 307 398 288 398 306 399 288 399 287 399 307 400 308 400 289 400 307 401 289 401 288 401 308 402 309 402 290 402 308 403 290 403 289 403 309 404 310 404 291 404 309 405 291 405 290 405 310 406 311 406 292 406 310 407 292 407 291 407 311 408 312 408 293 408 311 409 293 409 292 409 312 410 129 410 131 410 312 411 131 411 293 411 166 412 313 412 294 412 166 413 294 413 168 413 313 414 314 414 295 414 313 415 295 415 294 415 314 416 315 416 296 416 314 417 296 417 295 417 315 418 316 418 297 418 315 419 297 419 296 419 316 420 317 420 298 420 316 421 298 421 297 421 317 422 318 422 299 422 317 423 299 423 298 423 318 424 319 424 300 424 318 425 300 425 299 425 319 426 320 426 301 426 319 427 301 427 300 427 320 428 321 428 302 428 320 429 302 429 301 429 321 430 322 430 303 430 321 431 303 431 302 431 322 432 323 432 304 432 322 433 304 433 303 433 323 434 324 434 305 434 323 435 305 435 304 435 324 436 325 436 306 436 324 437 306 437 305 437 325 438 326 438 307 438 325 439 307 439 306 439 326 440 327 440 308 440 326 441 308 441 307 441 327 442 328 442 309 442 327 443 309 443 308 443 328 444 329 444 310 444 328 445 310 445 309 445 329 446 330 446 311 446 329 447 311 447 310 447 330 448 331 448 312 448 330 449 312 449 311 449 331 450 127 450 129 450 331 451 129 451 312 451 164 452 332 452 313 452 164 453 313 453 166 453 332 454 333 454 314 454 332 455 314 455 313 455 333 456 334 456 315 456 333 457 315 457 314 457 334 458 335 458 316 458 334 459 316 459 315 459 335 460 336 460 317 460 335 461 317 461 316 461 336 462 337 462 318 462 336 463 318 463 317 463 337 464 338 464 319 464 337 465 319 465 318 465 338 466 339 466 320 466 338 467 320 467 319 467 339 468 340 468 321 468 339 469 321 469 320 469 340 470 341 470 322 470 340 471 322 471 321 471 341 472 342 472 323 472 341 473 323 473 322 473 342 474 343 474 324 474 342 475 324 475 323 475 343 476 344 476 325 476 343 477 325 477 324 477 344 478 345 478 326 478 344 479 326 479 325 479 345 480 346 480 327 480 345 481 327 481 326 481 346 482 347 482 328 482 346 483 328 483 327 483 347 484 348 484 329 484 347 485 329 485 328 485 348 486 349 486 330 486 348 487 330 487 329 487 349 488 350 488 331 488 349 489 331 489 330 489 350 490 125 490 127 490 350 491 127 491 331 491 162 492 351 492 332 492 162 493 332 493 164 493 351 494 352 494 333 494 351 495 333 495 332 495 352 496 353 496 334 496 352 497 334 497 333 497 353 498 354 498 335 498 353 499 335 499 334 499 354 500 355 500 336 500 354 501 336 501 335 501 355 502 356 502 337 502 355 503 337 503 336 503 356 504 357 504 338 504 356 505 338 505 337 505 357 506 358 506 339 506 357 507 339 507 338 507 358 508 359 508 340 508 358 509 340 509 339 509 359 510 360 510 341 510 359 511 341 511 340 511 360 512 361 512 342 512 360 513 342 513 341 513 361 514 362 514 343 514 361 515 343 515 342 515 362 516 363 516 344 516 362 517 344 517 343 517 363 518 364 518 345 518 363 519 345 519 344 519 364 520 365 520 346 520 364 521 346 521 345 521 365 522 366 522 347 522 365 523 347 523 346 523 366 524 367 524 348 524 366 525 348 525 347 525 367 526 368 526 349 526 367 527 349 527 348 527 368 528 369 528 350 528 368 529 350 529 349 529 369 530 123 530 125 530 369 531 125 531 350 531 160 532 370 532 351 532 160 533 351 533 162 533 370 534 371 534 352 534 370 535 352 535 351 535 371 536 372 536 353 536 371 537 353 537 352 537 372 538 373 538 354 538 372 539 354 539 353 539 373 540 374 540 355 540 373 541 355 541 354 541 374 542 375 542 356 542 374 543 356 543 355 543 375 544 376 544 357 544 375 545 357 545 356 545 376 546 377 546 358 546 376 547 358 547 357 547 377 548 378 548 359 548 377 549 359 549 358 549 378 550 379 550 360 550 378 551 360 551 359 551 379 552 380 552 361 552 379 553 361 553 360 553 380 554 381 554 362 554 380 555 362 555 361 555 381 556 382 556 363 556 381 557 363 557 362 557 382 558 383 558 364 558 382 559 364 559 363 559 383 560 384 560 365 560 383 561 365 561 364 561 384 562 385 562 366 562 384 563 366 563 365 563 385 564 386 564 367 564 385 565 367 565 366 565 386 566 387 566 368 566 386 567 368 567 367 567 387 568 388 568 369 568 387 569 369 569 368 569 388 570 121 570 123 570 388 571 123 571 369 571 158 572 389 572 370 572 158 573 370 573 160 573 389 574 390 574 371 574 389 575 371 575 370 575 390 576 391 576 372 576 390 577 372 577 371 577 391 578 392 578 373 578 391 579 373 579 372 579 392 580 393 580 374 580 392 581 374 581 373 581 393 582 394 582 375 582 393 583 375 583 374 583 394 584 395 584 376 584 394 585 376 585 375 585 395 586 396 586 377 586 395 587 377 587 376 587 396 588 397 588 378 588 396 589 378 589 377 589 397 590 398 590 379 590 397 591 379 591 378 591 398 592 399 592 380 592 398 593 380 593 379 593 399 594 400 594 381 594 399 595 381 595 380 595 400 596 401 596 382 596 400 597 382 597 381 597 401 598 402 598 383 598 401 599 383 599 382 599 402 600 403 600 384 600 402 601 384 601 383 601 403 602 404 602 385 602 403 603 385 603 384 603 404 604 405 604 386 604 404 605 386 605 385 605 405 606 406 606 387 606 405 607 387 607 386 607 406 608 407 608 388 608 406 609 388 609 387 609 407 610 119 610 121 610 407 611 121 611 388 611 156 612 408 612 389 612 156 613 389 613 158 613 408 614 409 614 390 614 408 615 390 615 389 615 409 616 410 616 391 616 409 617 391 617 390 617 410 618 411 618 392 618 410 619 392 619 391 619 411 620 412 620 393 620 411 621 393 621 392 621 412 622 413 622 394 622 412 623 394 623 393 623 413 624 414 624 395 624 413 625 395 625 394 625 414 626 415 626 396 626 414 627 396 627 395 627 415 628 416 628 397 628 415 629 397 629 396 629 416 630 417 630 398 630 416 631 398 631 397 631 417 632 418 632 399 632 417 633 399 633 398 633 418 634 419 634 400 634 418 635 400 635 399 635 419 636 420 636 401 636 419 637 401 637 400 637 420 638 421 638 402 638 420 639 402 639 401 639 421 640 422 640 403 640 421 641 403 641 402 641 422 642 423 642 404 642 422 643 404 643 403 643 423 644 424 644 405 644 423 645 405 645 404 645 424 646 425 646 406 646 424 647 406 647 405 647 425 648 426 648 407 648 425 649 407 649 406 649 426 650 117 650 119 650 426 651 119 651 407 651 154 652 427 652 408 652 154 653 408 653 156 653 427 654 428 654 409 654 427 655 409 655 408 655 428 656 429 656 410 656 428 657 410 657 409 657 429 658 430 658 411 658 429 659 411 659 410 659 430 660 431 660 412 660 430 661 412 661 411 661 431 662 432 662 413 662 431 663 413 663 412 663 432 664 433 664 414 664 432 665 414 665 413 665 433 666 434 666 415 666 433 667 415 667 414 667 434 668 435 668 416 668 434 669 416 669 415 669 435 670 436 670 417 670 435 671 417 671 416 671 436 672 437 672 418 672 436 673 418 673 417 673 437 674 438 674 419 674 437 675 419 675 418 675 438 676 439 676 420 676 438 677 420 677 419 677 439 678 440 678 421 678 439 679 421 679 420 679 440 680 441 680 422 680 440 681 422 681 421 681 441 682 442 682 423 682 441 683 423 683 422 683 442 684 443 684 424 684 442 685 424 685 423 685 443 686 444 686 425 686 443 687 425 687 424 687 444 688 445 688 426 688 444 689 426 689 425 689 445 690 115 690 117 690 445 691 117 691 426 691 152 692 446 692 427 692 152 693 427 693 154 693 446 694 447 694 428 694 446 695 428 695 427 695 447 696 448 696 429 696 447 697 429 697 428 697 448 698 449 698 430 698 448 699 430 699 429 699 449 700 450 700 431 700 449 701 431 701 430 701 450 702 451 702 432 702 450 703 432 703 431 703 451 704 452 704 433 704 451 705 433 705 432 705 452 706 453 706 434 706 452 707 434 707 433 707 453 708 454 708 435 708 453 709 435 709 434 709 454 710 455 710 436 710 454 711 436 711 435 711 455 712 456 712 437 712 455 713 437 713 436 713 456 714 457 714 438 714 456 715 438 715 437 715 457 716 458 716 439 716 457 717 439 717 438 717 458 718 459 718 440 718 458 719 440 719 439 719 459 720 460 720 441 720 459 721 441 721 440 721 460 722 461 722 442 722 460 723 442 723 441 723 461 724 462 724 443 724 461 725 443 725 442 725 462 726 463 726 444 726 462 727 444 727 443 727 463 728 464 728 445 728 463 729 445 729 444 729 464 730 113 730 115 730 464 731 115 731 445 731 150 732 465 732 446 732 150 733 446 733 152 733 465 734 466 734 447 734 465 735 447 735 446 735 466 736 467 736 448 736 466 737 448 737 447 737 467 738 468 738 449 738 467 739 449 739 448 739 468 740 469 740 450 740 468 741 450 741 449 741 469 742 470 742 451 742 469 743 451 743 450 743 470 744 471 744 452 744 470 745 452 745 451 745 471 746 472 746 453 746 471 747 453 747 452 747 472 748 473 748 454 748 472 749 454 749 453 749 473 750 474 750 455 750 473 751 455 751 454 751 474 752 475 752 456 752 474 753 456 753 455 753 475 754 476 754 457 754 475 755 457 755 456 755 476 756 477 756 458 756 476 757 458 757 457 757 477 758 478 758 459 758 477 759 459 759 458 759 478 760 479 760 460 760 478 761 460 761 459 761 479 762 480 762 461 762 479 763 461 763 460 763 480 764 481 764 462 764 480 765 462 765 461 765 481 766 482 766 463 766 481 767 463 767 462 767 482 768 483 768 464 768 482 769 464 769 463 769 483 770 111 770 113 770 483 771 113 771 464 771 148 772 484 772 465 772 148 773 465 773 150 773 484 774 485 774 466 774 484 775 466 775 465 775 485 776 486 776 467 776 485 777 467 777 466 777 486 778 487 778 468 778 486 779 468 779 467 779 487 780 488 780 469 780 487 781 469 781 468 781 488 782 489 782 470 782 488 783 470 783 469 783 489 784 490 784 471 784 489 785 471 785 470 785 490 786 491 786 472 786 490 787 472 787 471 787 491 788 492 788 473 788 491 789 473 789 472 789 492 790 493 790 474 790 492 791 474 791 473 791 493 792 494 792 475 792 493 793 475 793 474 793 494 794 495 794 476 794 494 795 476 795 475 795 495 796 496 796 477 796 495 797 477 797 476 797 496 798 497 798 478 798 496 799 478 799 477 799 497 800 498 800 479 800 497 801 479 801 478 801 498 802 499 802 480 802 498 803 480 803 479 803 499 804 500 804 481 804 499 805 481 805 480 805 500 806 501 806 482 806 500 807 482 807 481 807 501 808 502 808 483 808 501 809 483 809 482 809 502 810 109 810 111 810 502 811 111 811 483 811 146 812 503 812 484 812 146 813 484 813 148 813 503 814 504 814 485 814 503 815 485 815 484 815 504 816 505 816 486 816 504 817 486 817 485 817 505 818 506 818 487 818 505 819 487 819 486 819 506 820 507 820 488 820 506 821 488 821 487 821 507 822 508 822 489 822 507 823 489 823 488 823 508 824 509 824 490 824 508 825 490 825 489 825 509 826 510 826 491 826 509 827 491 827 490 827 510 828 511 828 492 828 510 829 492 829 491 829 511 830 512 830 493 830 511 831 493 831 492 831 512 832 513 832 494 832 512 833 494 833 493 833 513 834 514 834 495 834 513 835 495 835 494 835 514 836 515 836 496 836 514 837 496 837 495 837 515 838 516 838 497 838 515 839 497 839 496 839 516 840 517 840 498 840 516 841 498 841 497 841 517 842 518 842 499 842 517 843 499 843 498 843 518 844 519 844 500 844 518 845 500 845 499 845 519 846 520 846 501 846 519 847 501 847 500 847 520 848 521 848 502 848 520 849 502 849 501 849 521 850 107 850 109 850 521 851 109 851 502 851 144 852 522 852 503 852 144 853 503 853 146 853 522 854 523 854 504 854 522 855 504 855 503 855 523 856 524 856 505 856 523 857 505 857 504 857 524 858 525 858 506 858 524 859 506 859 505 859 525 860 526 860 507 860 525 861 507 861 506 861 526 862 527 862 508 862 526 863 508 863 507 863 527 864 528 864 509 864 527 865 509 865 508 865 528 866 529 866 510 866 528 867 510 867 509 867 529 868 530 868 511 868 529 869 511 869 510 869 530 870 531 870 512 870 530 871 512 871 511 871 531 872 532 872 513 872 531 873 513 873 512 873 532 874 533 874 514 874 532 875 514 875 513 875 533 876 534 876 515 876 533 877 515 877 514 877 534 878 535 878 516 878 534 879 516 879 515 879 535 880 536 880 517 880 535 881 517 881 516 881 536 882 537 882 518 882 536 883 518 883 517 883 537 884 538 884 519 884 537 885 519 885 518 885 538 886 539 886 520 886 538 887 520 887 519 887 539 888 540 888 521 888 539 889 521 889 520 889 540 890 105 890 107 890 540 891 107 891 521 891 142 892 541 892 522 892 142 893 522 893 144 893 541 894 542 894 523 894 541 895 523 895 522 895 542 896 543 896 524 896 542 897 524 897 523 897 543 898 544 898 525 898 543 899 525 899 524 899 544 900 545 900 526 900 544 901 526 901 525 901 545 902 546 902 527 902 545 903 527 903 526 903 546 904 547 904 528 904 546 905 528 905 527 905 547 906 548 906 529 906 547 907 529 907 528 907 548 908 549 908 530 908 548 909 530 909 529 909 549 910 550 910 531 910 549 911 531 911 530 911 550 912 551 912 532 912 550 913 532 913 531 913 551 914 552 914 533 914 551 915 533 915 532 915 552 916 553 916 534 916 552 917 534 917 533 917 553 918 554 918 535 918 553 919 535 919 534 919 554 920 555 920 536 920 554 921 536 921 535 921 555 922 556 922 537 922 555 923 537 923 536 923 556 924 557 924 538 924 556 925 538 925 537 925 557 926 558 926 539 926 557 927 539 927 538 927 558 928 559 928 540 928 558 929 540 929 539 929 559 930 103 930 105 930 559 931 105 931 540 931 141 932 560 932 541 932 141 933 541 933 142 933 560 934 561 934 542 934 560 935 542 935 541 935 561 936 562 936 543 936 561 937 543 937 542 937 562 938 563 938 544 938 562 939 544 939 543 939 563 940 564 940 545 940 563 941 545 941 544 941 564 942 565 942 546 942 564 943 546 943 545 943 565 944 566 944 547 944 565 945 547 945 546 945 566 946 567 946 548 946 566 947 548 947 547 947 567 948 568 948 549 948 567 949 549 949 548 949 568 950 569 950 550 950 568 951 550 951 549 951 569 952 570 952 551 952 569 953 551 953 550 953 570 954 571 954 552 954 570 955 552 955 551 955 571 956 572 956 553 956 571 957 553 957 552 957 572 958 573 958 554 958 572 959 554 959 553 959 573 960 574 960 555 960 573 961 555 961 554 961 574 962 575 962 556 962 574 963 556 963 555 963 575 964 576 964 557 964 575 965 557 965 556 965 576 966 577 966 558 966 576 967 558 967 557 967 577 968 578 968 559 968 577 969 559 969 558 969 578 970 100 970 103 970 578 971 103 971 559 971 98 972 579 972 580 972 98 973 580 973 9 973 579 974 581 974 582 974 579 975 582 975 580 975 581 976 583 976 584 976 581 977 584 977 582 977 583 978 585 978 586 978 583 979 586 979 584 979 585 980 587 980 588 980 585 981 588 981 586 981 587 982 589 982 590 982 587 983 590 983 588 983 589 984 591 984 592 984 589 985 592 985 590 985 591 986 593 986 594 986 591 987 594 987 592 987 593 988 595 988 596 988 593 989 596 989 594 989 595 990 597 990 598 990 595 991 598 991 596 991 597 992 599 992 600 992 597 993 600 993 598 993 599 994 601 994 602 994 599 995 602 995 600 995 601 996 603 996 604 996 601 997 604 997 602 997 603 998 605 998 606 998 603 999 606 999 604 999 605 1000 607 1000 608 1000 605 1001 608 1001 606 1001 607 1002 609 1002 610 1002 607 1003 610 1003 608 1003 609 1004 611 1004 612 1004 609 1005 612 1005 610 1005 611 1006 613 1006 614 1006 611 1007 614 1007 612 1007 613 1008 615 1008 616 1008 613 1009 616 1009 614 1009 615 1010 61 1010 12 1010 615 1011 12 1011 616 1011 96 1012 617 1012 579 1012 96 1013 579 1013 98 1013 617 1014 618 1014 581 1014 617 1015 581 1015 579 1015 618 1016 619 1016 583 1016 618 1017 583 1017 581 1017 619 1018 620 1018 585 1018 619 1019 585 1019 583 1019 620 1020 621 1020 587 1020 620 1021 587 1021 585 1021 621 1022 622 1022 589 1022 621 1023 589 1023 587 1023 622 1024 623 1024 591 1024 622 1025 591 1025 589 1025 623 1026 624 1026 593 1026 623 1027 593 1027 591 1027 624 1028 625 1028 595 1028 624 1029 595 1029 593 1029 625 1030 626 1030 597 1030 625 1031 597 1031 595 1031 626 1032 627 1032 599 1032 626 1033 599 1033 597 1033 627 1034 628 1034 601 1034 627 1035 601 1035 599 1035 628 1036 629 1036 603 1036 628 1037 603 1037 601 1037 629 1038 630 1038 605 1038 629 1039 605 1039 603 1039 630 1040 631 1040 607 1040 630 1041 607 1041 605 1041 631 1042 632 1042 609 1042 631 1043 609 1043 607 1043 632 1044 633 1044 611 1044 632 1045 611 1045 609 1045 633 1046 634 1046 613 1046 633 1047 613 1047 611 1047 634 1048 635 1048 615 1048 634 1049 615 1049 613 1049 635 1050 59 1050 61 1050 635 1051 61 1051 615 1051 94 1052 636 1052 617 1052 94 1053 617 1053 96 1053 636 1054 637 1054 618 1054 636 1055 618 1055 617 1055 637 1056 638 1056 619 1056 637 1057 619 1057 618 1057 638 1058 639 1058 620 1058 638 1059 620 1059 619 1059 639 1060 640 1060 621 1060 639 1061 621 1061 620 1061 640 1062 641 1062 622 1062 640 1063 622 1063 621 1063 641 1064 642 1064 623 1064 641 1065 623 1065 622 1065 642 1066 643 1066 624 1066 642 1067 624 1067 623 1067 643 1068 644 1068 625 1068 643 1069 625 1069 624 1069 644 1070 645 1070 626 1070 644 1071 626 1071 625 1071 645 1072 646 1072 627 1072 645 1073 627 1073 626 1073 646 1074 647 1074 628 1074 646 1075 628 1075 627 1075 647 1076 648 1076 629 1076 647 1077 629 1077 628 1077 648 1078 649 1078 630 1078 648 1079 630 1079 629 1079 649 1080 650 1080 631 1080 649 1081 631 1081 630 1081 650 1082 651 1082 632 1082 650 1083 632 1083 631 1083 651 1084 652 1084 633 1084 651 1085 633 1085 632 1085 652 1086 653 1086 634 1086 652 1087 634 1087 633 1087 653 1088 654 1088 635 1088 653 1089 635 1089 634 1089 654 1090 57 1090 59 1090 654 1091 59 1091 635 1091 92 1092 655 1092 636 1092 92 1093 636 1093 94 1093 655 1094 656 1094 637 1094 655 1095 637 1095 636 1095 656 1096 657 1096 638 1096 656 1097 638 1097 637 1097 657 1098 658 1098 639 1098 657 1099 639 1099 638 1099 658 1100 659 1100 640 1100 658 1101 640 1101 639 1101 659 1102 660 1102 641 1102 659 1103 641 1103 640 1103 660 1104 661 1104 642 1104 660 1105 642 1105 641 1105 661 1106 662 1106 643 1106 661 1107 643 1107 642 1107 662 1108 663 1108 644 1108 662 1109 644 1109 643 1109 663 1110 664 1110 645 1110 663 1111 645 1111 644 1111 664 1112 665 1112 646 1112 664 1113 646 1113 645 1113 665 1114 666 1114 647 1114 665 1115 647 1115 646 1115 666 1116 667 1116 648 1116 666 1117 648 1117 647 1117 667 1118 668 1118 649 1118 667 1119 649 1119 648 1119 668 1120 669 1120 650 1120 668 1121 650 1121 649 1121 669 1122 670 1122 651 1122 669 1123 651 1123 650 1123 670 1124 671 1124 652 1124 670 1125 652 1125 651 1125 671 1126 672 1126 653 1126 671 1127 653 1127 652 1127 672 1128 673 1128 654 1128 672 1129 654 1129 653 1129 673 1130 55 1130 57 1130 673 1131 57 1131 654 1131 90 1132 674 1132 655 1132 90 1133 655 1133 92 1133 674 1134 675 1134 656 1134 674 1135 656 1135 655 1135 675 1136 676 1136 657 1136 675 1137 657 1137 656 1137 676 1138 677 1138 658 1138 676 1139 658 1139 657 1139 677 1140 678 1140 659 1140 677 1141 659 1141 658 1141 678 1142 679 1142 660 1142 678 1143 660 1143 659 1143 679 1144 680 1144 661 1144 679 1145 661 1145 660 1145 680 1146 681 1146 662 1146 680 1147 662 1147 661 1147 681 1148 682 1148 663 1148 681 1149 663 1149 662 1149 682 1150 683 1150 664 1150 682 1151 664 1151 663 1151 683 1152 684 1152 665 1152 683 1153 665 1153 664 1153 684 1154 685 1154 666 1154 684 1155 666 1155 665 1155 685 1156 686 1156 667 1156 685 1157 667 1157 666 1157 686 1158 687 1158 668 1158 686 1159 668 1159 667 1159 687 1160 688 1160 669 1160 687 1161 669 1161 668 1161 688 1162 689 1162 670 1162 688 1163 670 1163 669 1163 689 1164 690 1164 671 1164 689 1165 671 1165 670 1165 690 1166 691 1166 672 1166 690 1167 672 1167 671 1167 691 1168 692 1168 673 1168 691 1169 673 1169 672 1169 692 1170 53 1170 55 1170 692 1171 55 1171 673 1171 88 1172 693 1172 674 1172 88 1173 674 1173 90 1173 693 1174 694 1174 675 1174 693 1175 675 1175 674 1175 694 1176 695 1176 676 1176 694 1177 676 1177 675 1177 695 1178 696 1178 677 1178 695 1179 677 1179 676 1179 696 1180 697 1180 678 1180 696 1181 678 1181 677 1181 697 1182 698 1182 679 1182 697 1183 679 1183 678 1183 698 1184 699 1184 680 1184 698 1185 680 1185 679 1185 699 1186 700 1186 681 1186 699 1187 681 1187 680 1187 700 1188 701 1188 682 1188 700 1189 682 1189 681 1189 701 1190 702 1190 683 1190 701 1191 683 1191 682 1191 702 1192 703 1192 684 1192 702 1193 684 1193 683 1193 703 1194 704 1194 685 1194 703 1195 685 1195 684 1195 704 1196 705 1196 686 1196 704 1197 686 1197 685 1197 705 1198 706 1198 687 1198 705 1199 687 1199 686 1199 706 1200 707 1200 688 1200 706 1201 688 1201 687 1201 707 1202 708 1202 689 1202 707 1203 689 1203 688 1203 708 1204 709 1204 690 1204 708 1205 690 1205 689 1205 709 1206 710 1206 691 1206 709 1207 691 1207 690 1207 710 1208 711 1208 692 1208 710 1209 692 1209 691 1209 711 1210 51 1210 53 1210 711 1211 53 1211 692 1211 86 1212 712 1212 693 1212 86 1213 693 1213 88 1213 712 1214 713 1214 694 1214 712 1215 694 1215 693 1215 713 1216 714 1216 695 1216 713 1217 695 1217 694 1217 714 1218 715 1218 696 1218 714 1219 696 1219 695 1219 715 1220 716 1220 697 1220 715 1221 697 1221 696 1221 716 1222 717 1222 698 1222 716 1223 698 1223 697 1223 717 1224 718 1224 699 1224 717 1225 699 1225 698 1225 718 1226 719 1226 700 1226 718 1227 700 1227 699 1227 719 1228 720 1228 701 1228 719 1229 701 1229 700 1229 720 1230 721 1230 702 1230 720 1231 702 1231 701 1231 721 1232 722 1232 703 1232 721 1233 703 1233 702 1233 722 1234 723 1234 704 1234 722 1235 704 1235 703 1235 723 1236 724 1236 705 1236 723 1237 705 1237 704 1237 724 1238 725 1238 706 1238 724 1239 706 1239 705 1239 725 1240 726 1240 707 1240 725 1241 707 1241 706 1241 726 1242 727 1242 708 1242 726 1243 708 1243 707 1243 727 1244 728 1244 709 1244 727 1245 709 1245 708 1245 728 1246 729 1246 710 1246 728 1247 710 1247 709 1247 729 1248 730 1248 711 1248 729 1249 711 1249 710 1249 730 1250 49 1250 51 1250 730 1251 51 1251 711 1251 84 1252 731 1252 712 1252 84 1253 712 1253 86 1253 731 1254 732 1254 713 1254 731 1255 713 1255 712 1255 732 1256 733 1256 714 1256 732 1257 714 1257 713 1257 733 1258 734 1258 715 1258 733 1259 715 1259 714 1259 734 1260 735 1260 716 1260 734 1261 716 1261 715 1261 735 1262 736 1262 717 1262 735 1263 717 1263 716 1263 736 1264 737 1264 718 1264 736 1265 718 1265 717 1265 737 1266 738 1266 719 1266 737 1267 719 1267 718 1267 738 1268 739 1268 720 1268 738 1269 720 1269 719 1269 739 1270 740 1270 721 1270 739 1271 721 1271 720 1271 740 1272 741 1272 722 1272 740 1273 722 1273 721 1273 741 1274 742 1274 723 1274 741 1275 723 1275 722 1275 742 1276 743 1276 724 1276 742 1277 724 1277 723 1277 743 1278 744 1278 725 1278 743 1279 725 1279 724 1279 744 1280 745 1280 726 1280 744 1281 726 1281 725 1281 745 1282 746 1282 727 1282 745 1283 727 1283 726 1283 746 1284 747 1284 728 1284 746 1285 728 1285 727 1285 747 1286 748 1286 729 1286 747 1287 729 1287 728 1287 748 1288 749 1288 730 1288 748 1289 730 1289 729 1289 749 1290 47 1290 49 1290 749 1291 49 1291 730 1291 82 1292 750 1292 731 1292 82 1293 731 1293 84 1293 750 1294 751 1294 732 1294 750 1295 732 1295 731 1295 751 1296 752 1296 733 1296 751 1297 733 1297 732 1297 752 1298 753 1298 734 1298 752 1299 734 1299 733 1299 753 1300 754 1300 735 1300 753 1301 735 1301 734 1301 754 1302 755 1302 736 1302 754 1303 736 1303 735 1303 755 1304 756 1304 737 1304 755 1305 737 1305 736 1305 756 1306 757 1306 738 1306 756 1307 738 1307 737 1307 757 1308 758 1308 739 1308 757 1309 739 1309 738 1309 758 1310 759 1310 740 1310 758 1311 740 1311 739 1311 759 1312 760 1312 741 1312 759 1313 741 1313 740 1313 760 1314 761 1314 742 1314 760 1315 742 1315 741 1315 761 1316 762 1316 743 1316 761 1317 743 1317 742 1317 762 1318 763 1318 744 1318 762 1319 744 1319 743 1319 763 1320 764 1320 745 1320 763 1321 745 1321 744 1321 764 1322 765 1322 746 1322 764 1323 746 1323 745 1323 765 1324 766 1324 747 1324 765 1325 747 1325 746 1325 766 1326 767 1326 748 1326 766 1327 748 1327 747 1327 767 1328 768 1328 749 1328 767 1329 749 1329 748 1329 768 1330 45 1330 47 1330 768 1331 47 1331 749 1331 80 1332 769 1332 750 1332 80 1333 750 1333 82 1333 769 1334 770 1334 751 1334 769 1335 751 1335 750 1335 770 1336 771 1336 752 1336 770 1337 752 1337 751 1337 771 1338 772 1338 753 1338 771 1339 753 1339 752 1339 772 1340 773 1340 754 1340 772 1341 754 1341 753 1341 773 1342 774 1342 755 1342 773 1343 755 1343 754 1343 774 1344 775 1344 756 1344 774 1345 756 1345 755 1345 775 1346 776 1346 757 1346 775 1347 757 1347 756 1347 776 1348 777 1348 758 1348 776 1349 758 1349 757 1349 777 1350 778 1350 759 1350 777 1351 759 1351 758 1351 778 1352 779 1352 760 1352 778 1353 760 1353 759 1353 779 1354 780 1354 761 1354 779 1355 761 1355 760 1355 780 1356 781 1356 762 1356 780 1357 762 1357 761 1357 781 1358 782 1358 763 1358 781 1359 763 1359 762 1359 782 1360 783 1360 764 1360 782 1361 764 1361 763 1361 783 1362 784 1362 765 1362 783 1363 765 1363 764 1363 784 1364 785 1364 766 1364 784 1365 766 1365 765 1365 785 1366 786 1366 767 1366 785 1367 767 1367 766 1367 786 1368 787 1368 768 1368 786 1369 768 1369 767 1369 787 1370 43 1370 45 1370 787 1371 45 1371 768 1371 78 1372 788 1372 769 1372 78 1373 769 1373 80 1373 788 1374 789 1374 770 1374 788 1375 770 1375 769 1375 789 1376 790 1376 771 1376 789 1377 771 1377 770 1377 790 1378 791 1378 772 1378 790 1379 772 1379 771 1379 791 1380 792 1380 773 1380 791 1381 773 1381 772 1381 792 1382 793 1382 774 1382 792 1383 774 1383 773 1383 793 1384 794 1384 775 1384 793 1385 775 1385 774 1385 794 1386 795 1386 776 1386 794 1387 776 1387 775 1387 795 1388 796 1388 777 1388 795 1389 777 1389 776 1389 796 1390 797 1390 778 1390 796 1391 778 1391 777 1391 797 1392 798 1392 779 1392 797 1393 779 1393 778 1393 798 1394 799 1394 780 1394 798 1395 780 1395 779 1395 799 1396 800 1396 781 1396 799 1397 781 1397 780 1397 800 1398 801 1398 782 1398 800 1399 782 1399 781 1399 801 1400 802 1400 783 1400 801 1401 783 1401 782 1401 802 1402 803 1402 784 1402 802 1403 784 1403 783 1403 803 1404 804 1404 785 1404 803 1405 785 1405 784 1405 804 1406 805 1406 786 1406 804 1407 786 1407 785 1407 805 1408 806 1408 787 1408 805 1409 787 1409 786 1409 806 1410 41 1410 43 1410 806 1411 43 1411 787 1411 76 1412 807 1412 788 1412 76 1413 788 1413 78 1413 807 1414 808 1414 789 1414 807 1415 789 1415 788 1415 808 1416 809 1416 790 1416 808 1417 790 1417 789 1417 809 1418 810 1418 791 1418 809 1419 791 1419 790 1419 810 1420 811 1420 792 1420 810 1421 792 1421 791 1421 811 1422 812 1422 793 1422 811 1423 793 1423 792 1423 812 1424 813 1424 794 1424 812 1425 794 1425 793 1425 813 1426 814 1426 795 1426 813 1427 795 1427 794 1427 814 1428 815 1428 796 1428 814 1429 796 1429 795 1429 815 1430 816 1430 797 1430 815 1431 797 1431 796 1431 816 1432 817 1432 798 1432 816 1433 798 1433 797 1433 817 1434 818 1434 799 1434 817 1435 799 1435 798 1435 818 1436 819 1436 800 1436 818 1437 800 1437 799 1437 819 1438 820 1438 801 1438 819 1439 801 1439 800 1439 820 1440 821 1440 802 1440 820 1441 802 1441 801 1441 821 1442 822 1442 803 1442 821 1443 803 1443 802 1443 822 1444 823 1444 804 1444 822 1445 804 1445 803 1445 823 1446 824 1446 805 1446 823 1447 805 1447 804 1447 824 1448 825 1448 806 1448 824 1449 806 1449 805 1449 825 1450 39 1450 41 1450 825 1451 41 1451 806 1451 74 1452 826 1452 807 1452 74 1453 807 1453 76 1453 826 1454 827 1454 808 1454 826 1455 808 1455 807 1455 827 1456 828 1456 809 1456 827 1457 809 1457 808 1457 828 1458 829 1458 810 1458 828 1459 810 1459 809 1459 829 1460 830 1460 811 1460 829 1461 811 1461 810 1461 830 1462 831 1462 812 1462 830 1463 812 1463 811 1463 831 1464 832 1464 813 1464 831 1465 813 1465 812 1465 832 1466 833 1466 814 1466 832 1467 814 1467 813 1467 833 1468 834 1468 815 1468 833 1469 815 1469 814 1469 834 1470 835 1470 816 1470 834 1471 816 1471 815 1471 835 1472 836 1472 817 1472 835 1473 817 1473 816 1473 836 1474 837 1474 818 1474 836 1475 818 1475 817 1475 837 1476 838 1476 819 1476 837 1477 819 1477 818 1477 838 1478 839 1478 820 1478 838 1479 820 1479 819 1479 839 1480 840 1480 821 1480 839 1481 821 1481 820 1481 840 1482 841 1482 822 1482 840 1483 822 1483 821 1483 841 1484 842 1484 823 1484 841 1485 823 1485 822 1485 842 1486 843 1486 824 1486 842 1487 824 1487 823 1487 843 1488 844 1488 825 1488 843 1489 825 1489 824 1489 844 1490 37 1490 39 1490 844 1491 39 1491 825 1491 72 1492 845 1492 826 1492 72 1493 826 1493 74 1493 845 1494 846 1494 827 1494 845 1495 827 1495 826 1495 846 1496 847 1496 828 1496 846 1497 828 1497 827 1497 847 1498 848 1498 829 1498 847 1499 829 1499 828 1499 848 1500 849 1500 830 1500 848 1501 830 1501 829 1501 849 1502 850 1502 831 1502 849 1503 831 1503 830 1503 850 1504 851 1504 832 1504 850 1505 832 1505 831 1505 851 1506 852 1506 833 1506 851 1507 833 1507 832 1507 852 1508 853 1508 834 1508 852 1509 834 1509 833 1509 853 1510 854 1510 835 1510 853 1511 835 1511 834 1511 854 1512 855 1512 836 1512 854 1513 836 1513 835 1513 855 1514 856 1514 837 1514 855 1515 837 1515 836 1515 856 1516 857 1516 838 1516 856 1517 838 1517 837 1517 857 1518 858 1518 839 1518 857 1519 839 1519 838 1519 858 1520 859 1520 840 1520 858 1521 840 1521 839 1521 859 1522 860 1522 841 1522 859 1523 841 1523 840 1523 860 1524 861 1524 842 1524 860 1525 842 1525 841 1525 861 1526 862 1526 843 1526 861 1527 843 1527 842 1527 862 1528 863 1528 844 1528 862 1529 844 1529 843 1529 863 1530 35 1530 37 1530 863 1531 37 1531 844 1531 70 1532 864 1532 845 1532 70 1533 845 1533 72 1533 864 1534 865 1534 846 1534 864 1535 846 1535 845 1535 865 1536 866 1536 847 1536 865 1537 847 1537 846 1537 866 1538 867 1538 848 1538 866 1539 848 1539 847 1539 867 1540 868 1540 849 1540 867 1541 849 1541 848 1541 868 1542 869 1542 850 1542 868 1543 850 1543 849 1543 869 1544 870 1544 851 1544 869 1545 851 1545 850 1545 870 1546 871 1546 852 1546 870 1547 852 1547 851 1547 871 1548 872 1548 853 1548 871 1549 853 1549 852 1549 872 1550 873 1550 854 1550 872 1551 854 1551 853 1551 873 1552 874 1552 855 1552 873 1553 855 1553 854 1553 874 1554 875 1554 856 1554 874 1555 856 1555 855 1555 875 1556 876 1556 857 1556 875 1557 857 1557 856 1557 876 1558 877 1558 858 1558 876 1559 858 1559 857 1559 877 1560 878 1560 859 1560 877 1561 859 1561 858 1561 878 1562 879 1562 860 1562 878 1563 860 1563 859 1563 879 1564 880 1564 861 1564 879 1565 861 1565 860 1565 880 1566 881 1566 862 1566 880 1567 862 1567 861 1567 881 1568 882 1568 863 1568 881 1569 863 1569 862 1569 882 1570 33 1570 35 1570 882 1571 35 1571 863 1571 68 1572 883 1572 864 1572 68 1573 864 1573 70 1573 883 1574 884 1574 865 1574 883 1575 865 1575 864 1575 884 1576 885 1576 866 1576 884 1577 866 1577 865 1577 885 1578 886 1578 867 1578 885 1579 867 1579 866 1579 886 1580 887 1580 868 1580 886 1581 868 1581 867 1581 887 1582 888 1582 869 1582 887 1583 869 1583 868 1583 888 1584 889 1584 870 1584 888 1585 870 1585 869 1585 889 1586 890 1586 871 1586 889 1587 871 1587 870 1587 890 1588 891 1588 872 1588 890 1589 872 1589 871 1589 891 1590 892 1590 873 1590 891 1591 873 1591 872 1591 892 1592 893 1592 874 1592 892 1593 874 1593 873 1593 893 1594 894 1594 875 1594 893 1595 875 1595 874 1595 894 1596 895 1596 876 1596 894 1597 876 1597 875 1597 895 1598 896 1598 877 1598 895 1599 877 1599 876 1599 896 1600 897 1600 878 1600 896 1601 878 1601 877 1601 897 1602 898 1602 879 1602 897 1603 879 1603 878 1603 898 1604 899 1604 880 1604 898 1605 880 1605 879 1605 899 1606 900 1606 881 1606 899 1607 881 1607 880 1607 900 1608 901 1608 882 1608 900 1609 882 1609 881 1609 901 1610 31 1610 33 1610 901 1611 33 1611 882 1611 66 1612 902 1612 883 1612 66 1613 883 1613 68 1613 902 1614 903 1614 884 1614 902 1615 884 1615 883 1615 903 1616 904 1616 885 1616 903 1617 885 1617 884 1617 904 1618 905 1618 886 1618 904 1619 886 1619 885 1619 905 1620 906 1620 887 1620 905 1621 887 1621 886 1621 906 1622 907 1622 888 1622 906 1623 888 1623 887 1623 907 1624 908 1624 889 1624 907 1625 889 1625 888 1625 908 1626 909 1626 890 1626 908 1627 890 1627 889 1627 909 1628 910 1628 891 1628 909 1629 891 1629 890 1629 910 1630 911 1630 892 1630 910 1631 892 1631 891 1631 911 1632 912 1632 893 1632 911 1633 893 1633 892 1633 912 1634 913 1634 894 1634 912 1635 894 1635 893 1635 913 1636 914 1636 895 1636 913 1637 895 1637 894 1637 914 1638 915 1638 896 1638 914 1639 896 1639 895 1639 915 1640 916 1640 897 1640 915 1641 897 1641 896 1641 916 1642 917 1642 898 1642 916 1643 898 1643 897 1643 917 1644 918 1644 899 1644 917 1645 899 1645 898 1645 918 1646 919 1646 900 1646 918 1647 900 1647 899 1647 919 1648 920 1648 901 1648 919 1649 901 1649 900 1649 920 1650 29 1650 31 1650 920 1651 31 1651 901 1651 64 1652 921 1652 902 1652 64 1653 902 1653 66 1653 921 1654 922 1654 903 1654 921 1655 903 1655 902 1655 922 1656 923 1656 904 1656 922 1657 904 1657 903 1657 923 1658 924 1658 905 1658 923 1659 905 1659 904 1659 924 1660 925 1660 906 1660 924 1661 906 1661 905 1661 925 1662 926 1662 907 1662 925 1663 907 1663 906 1663 926 1664 927 1664 908 1664 926 1665 908 1665 907 1665 927 1666 928 1666 909 1666 927 1667 909 1667 908 1667 928 1668 929 1668 910 1668 928 1669 910 1669 909 1669 929 1670 930 1670 911 1670 929 1671 911 1671 910 1671 930 1672 931 1672 912 1672 930 1673 912 1673 911 1673 931 1674 932 1674 913 1674 931 1675 913 1675 912 1675 932 1676 933 1676 914 1676 932 1677 914 1677 913 1677 933 1678 934 1678 915 1678 933 1679 915 1679 914 1679 934 1680 935 1680 916 1680 934 1681 916 1681 915 1681 935 1682 936 1682 917 1682 935 1683 917 1683 916 1683 936 1684 937 1684 918 1684 936 1685 918 1685 917 1685 937 1686 938 1686 919 1686 937 1687 919 1687 918 1687 938 1688 939 1688 920 1688 938 1689 920 1689 919 1689 939 1690 27 1690 29 1690 939 1691 29 1691 920 1691 62 1692 940 1692 921 1692 62 1693 921 1693 64 1693 940 1694 941 1694 922 1694 940 1695 922 1695 921 1695 941 1696 942 1696 923 1696 941 1697 923 1697 922 1697 942 1698 943 1698 924 1698 942 1699 924 1699 923 1699 943 1700 944 1700 925 1700 943 1701 925 1701 924 1701 944 1702 945 1702 926 1702 944 1703 926 1703 925 1703 945 1704 946 1704 927 1704 945 1705 927 1705 926 1705 946 1706 947 1706 928 1706 946 1707 928 1707 927 1707 947 1708 948 1708 929 1708 947 1709 929 1709 928 1709 948 1710 949 1710 930 1710 948 1711 930 1711 929 1711 949 1712 950 1712 931 1712 949 1713 931 1713 930 1713 950 1714 951 1714 932 1714 950 1715 932 1715 931 1715 951 1716 952 1716 933 1716 951 1717 933 1717 932 1717 952 1718 953 1718 934 1718 952 1719 934 1719 933 1719 953 1720 954 1720 935 1720 953 1721 935 1721 934 1721 954 1722 955 1722 936 1722 954 1723 936 1723 935 1723 955 1724 956 1724 937 1724 955 1725 937 1725 936 1725 956 1726 957 1726 938 1726 956 1727 938 1727 937 1727 957 1728 958 1728 939 1728 957 1729 939 1729 938 1729 958 1730 25 1730 27 1730 958 1731 27 1731 939 1731 18 1732 17 1732 940 1732 18 1733 940 1733 62 1733 17 1734 959 1734 941 1734 17 1735 941 1735 940 1735 959 1736 960 1736 942 1736 959 1737 942 1737 941 1737 960 1738 961 1738 943 1738 960 1739 943 1739 942 1739 961 1740 962 1740 944 1740 961 1741 944 1741 943 1741 962 1742 963 1742 945 1742 962 1743 945 1743 944 1743 963 1744 964 1744 946 1744 963 1745 946 1745 945 1745 964 1746 965 1746 947 1746 964 1747 947 1747 946 1747 965 1748 966 1748 948 1748 965 1749 948 1749 947 1749 966 1750 967 1750 949 1750 966 1751 949 1751 948 1751 967 1752 968 1752 950 1752 967 1753 950 1753 949 1753 968 1754 969 1754 951 1754 968 1755 951 1755 950 1755 969 1756 970 1756 952 1756 969 1757 952 1757 951 1757 970 1758 971 1758 953 1758 970 1759 953 1759 952 1759 971 1760 972 1760 954 1760 971 1761 954 1761 953 1761 972 1762 973 1762 955 1762 972 1763 955 1763 954 1763 973 1764 974 1764 956 1764 973 1765 956 1765 955 1765 974 1766 975 1766 957 1766 974 1767 957 1767 956 1767 975 1768 976 1768 958 1768 975 1769 958 1769 957 1769 976 1770 22 1770 25 1770 976 1771 25 1771 958 1771 11 1772 10 1772 977 1772 11 1773 977 1773 978 1773 978 1774 977 1774 979 1774 978 1775 979 1775 980 1775 980 1776 979 1776 981 1776 980 1777 981 1777 982 1777 982 1778 981 1778 983 1778 982 1779 983 1779 984 1779 984 1780 983 1780 985 1780 984 1781 985 1781 986 1781 986 1782 985 1782 987 1782 986 1783 987 1783 988 1783 988 1784 987 1784 989 1784 988 1785 989 1785 990 1785 990 1786 989 1786 991 1786 990 1787 991 1787 992 1787 992 1788 991 1788 993 1788 992 1789 993 1789 994 1789 994 1790 993 1790 995 1790 994 1791 995 1791 996 1791 996 1792 995 1792 997 1792 996 1793 997 1793 998 1793 998 1794 997 1794 999 1794 998 1795 999 1795 1000 1795 1000 1796 999 1796 1001 1796 1000 1797 1001 1797 1002 1797 1002 1798 1001 1798 1003 1798 1002 1799 1003 1799 1004 1799 1004 1800 1003 1800 1005 1800 1004 1801 1005 1801 1006 1801 1006 1802 1005 1802 1007 1802 1006 1803 1007 1803 1008 1803 1008 1804 1007 1804 1009 1804 1008 1805 1009 1805 1010 1805 1010 1806 1009 1806 1011 1806 1010 1807 1011 1807 1012 1807 1012 1808 1011 1808 1013 1808 1012 1809 1013 1809 1014 1809 1014 1810 1013 1810 15 1810 1014 1811 15 1811 20 1811 1015 1812 23 1812 22 1812 1015 1813 22 1813 1016 1813 1016 1814 22 1814 976 1814 1016 1815 976 1815 1017 1815 1017 1816 976 1816 975 1816 1017 1817 975 1817 1018 1817 1018 1818 975 1818 974 1818 1018 1819 974 1819 1019 1819 1019 1820 974 1820 973 1820 1019 1821 973 1821 1020 1821 1020 1822 973 1822 972 1822 1020 1823 972 1823 1021 1823 1021 1824 972 1824 971 1824 1021 1825 971 1825 1022 1825 1022 1826 971 1826 970 1826 1022 1827 970 1827 1023 1827 1023 1828 970 1828 969 1828 1023 1829 969 1829 1024 1829 1024 1830 969 1830 968 1830 1024 1831 968 1831 1025 1831 1025 1832 968 1832 967 1832 1025 1833 967 1833 1026 1833 1026 1834 967 1834 966 1834 1026 1835 966 1835 1027 1835 1027 1836 966 1836 965 1836 1027 1837 965 1837 1028 1837 1028 1838 965 1838 964 1838 1028 1839 964 1839 1029 1839 1029 1840 964 1840 963 1840 1029 1841 963 1841 1030 1841 1030 1842 963 1842 962 1842 1030 1843 962 1843 1031 1843 1031 1844 962 1844 961 1844 1031 1845 961 1845 1032 1845 1032 1846 961 1846 960 1846 1032 1847 960 1847 1033 1847 1033 1848 960 1848 959 1848 1033 1849 959 1849 1034 1849 1034 1850 959 1850 17 1850 1034 1851 17 1851 16 1851 9 1852 580 1852 977 1852 9 1853 977 1853 10 1853 580 1854 582 1854 979 1854 580 1855 979 1855 977 1855 582 1856 584 1856 981 1856 582 1857 981 1857 979 1857 584 1858 586 1858 983 1858 584 1859 983 1859 981 1859 586 1860 588 1860 985 1860 586 1861 985 1861 983 1861 588 1862 590 1862 987 1862 588 1863 987 1863 985 1863 590 1864 592 1864 989 1864 590 1865 989 1865 987 1865 592 1866 594 1866 991 1866 592 1867 991 1867 989 1867 594 1868 596 1868 993 1868 594 1869 993 1869 991 1869 596 1870 598 1870 995 1870 596 1871 995 1871 993 1871 598 1872 600 1872 997 1872 598 1873 997 1873 995 1873 600 1874 602 1874 999 1874 600 1875 999 1875 997 1875 602 1876 604 1876 1001 1876 602 1877 1001 1877 999 1877 604 1878 606 1878 1003 1878 604 1879 1003 1879 1001 1879 606 1880 608 1880 1005 1880 606 1881 1005 1881 1003 1881 608 1882 610 1882 1007 1882 608 1883 1007 1883 1005 1883 610 1884 612 1884 1009 1884 610 1885 1009 1885 1007 1885 612 1886 614 1886 1011 1886 612 1887 1011 1887 1009 1887 614 1888 616 1888 1013 1888 614 1889 1013 1889 1011 1889 616 1890 12 1890 15 1890 616 1891 15 1891 1013 1891 1 1892 181 1892 1035 1892 1 1893 1035 1893 2 1893 181 1894 183 1894 1036 1894 181 1895 1036 1895 1035 1895 183 1896 185 1896 1037 1896 183 1897 1037 1897 1036 1897 185 1898 187 1898 1038 1898 185 1899 1038 1899 1037 1899 187 1900 189 1900 1039 1900 187 1901 1039 1901 1038 1901 189 1902 191 1902 1040 1902 189 1903 1040 1903 1039 1903 191 1904 193 1904 1041 1904 191 1905 1041 1905 1040 1905 193 1906 195 1906 1042 1906 193 1907 1042 1907 1041 1907 195 1908 197 1908 1043 1908 195 1909 1043 1909 1042 1909 197 1910 199 1910 1044 1910 197 1911 1044 1911 1043 1911 199 1912 201 1912 1045 1912 199 1913 1045 1913 1044 1913 201 1914 203 1914 1046 1914 201 1915 1046 1915 1045 1915 203 1916 205 1916 1047 1916 203 1917 1047 1917 1046 1917 205 1918 207 1918 1048 1918 205 1919 1048 1919 1047 1919 207 1920 209 1920 1049 1920 207 1921 1049 1921 1048 1921 209 1922 211 1922 1050 1922 209 1923 1050 1923 1049 1923 211 1924 213 1924 1051 1924 211 1925 1051 1925 1050 1925 213 1926 215 1926 1052 1926 213 1927 1052 1927 1051 1927 215 1928 217 1928 1053 1928 215 1929 1053 1929 1052 1929 217 1930 4 1930 7 1930 217 1931 7 1931 1053 1931 578 1932 1054 1932 1055 1932 578 1933 1055 1933 100 1933 1054 1934 1056 1934 1057 1934 1054 1935 1057 1935 1055 1935 1056 1936 1058 1936 1059 1936 1056 1937 1059 1937 1057 1937 1058 1938 1060 1938 1061 1938 1058 1939 1061 1939 1059 1939 1060 1940 1062 1940 1063 1940 1060 1941 1063 1941 1061 1941 1062 1942 1064 1942 1065 1942 1062 1943 1065 1943 1063 1943 1064 1944 1066 1944 1067 1944 1064 1945 1067 1945 1065 1945 1066 1946 1068 1946 1069 1946 1066 1947 1069 1947 1067 1947 1068 1948 1070 1948 1071 1948 1068 1949 1071 1949 1069 1949 1070 1950 1072 1950 1073 1950 1070 1951 1073 1951 1071 1951 1072 1952 1074 1952 1075 1952 1072 1953 1075 1953 1073 1953 1074 1954 1076 1954 1077 1954 1074 1955 1077 1955 1075 1955 1076 1956 1078 1956 1079 1956 1076 1957 1079 1957 1077 1957 1078 1958 1080 1958 1081 1958 1078 1959 1081 1959 1079 1959 1080 1960 1082 1960 1083 1960 1080 1961 1083 1961 1081 1961 1082 1962 1084 1962 1085 1962 1082 1963 1085 1963 1083 1963 1084 1964 1086 1964 1087 1964 1084 1965 1087 1965 1085 1965 1086 1966 1088 1966 1089 1966 1086 1967 1089 1967 1087 1967 1088 1968 1090 1968 1091 1968 1088 1969 1091 1969 1089 1969 1090 1970 1034 1970 16 1970 1090 1971 16 1971 1091 1971 577 1972 1092 1972 1054 1972 577 1973 1054 1973 578 1973 1092 1974 1093 1974 1056 1974 1092 1975 1056 1975 1054 1975 1093 1976 1094 1976 1058 1976 1093 1977 1058 1977 1056 1977 1094 1978 1095 1978 1060 1978 1094 1979 1060 1979 1058 1979 1095 1980 1096 1980 1062 1980 1095 1981 1062 1981 1060 1981 1096 1982 1097 1982 1064 1982 1096 1983 1064 1983 1062 1983 1097 1984 1098 1984 1066 1984 1097 1985 1066 1985 1064 1985 1098 1986 1099 1986 1068 1986 1098 1987 1068 1987 1066 1987 1099 1988 1100 1988 1070 1988 1099 1989 1070 1989 1068 1989 1100 1990 1101 1990 1072 1990 1100 1991 1072 1991 1070 1991 1101 1992 1102 1992 1074 1992 1101 1993 1074 1993 1072 1993 1102 1994 1103 1994 1076 1994 1102 1995 1076 1995 1074 1995 1103 1996 1104 1996 1078 1996 1103 1997 1078 1997 1076 1997 1104 1998 1105 1998 1080 1998 1104 1999 1080 1999 1078 1999 1105 2000 1106 2000 1082 2000 1105 2001 1082 2001 1080 2001 1106 2002 1107 2002 1084 2002 1106 2003 1084 2003 1082 2003 1107 2004 1108 2004 1086 2004 1107 2005 1086 2005 1084 2005 1108 2006 1109 2006 1088 2006 1108 2007 1088 2007 1086 2007 1109 2008 1110 2008 1090 2008 1109 2009 1090 2009 1088 2009 1110 2010 1033 2010 1034 2010 1110 2011 1034 2011 1090 2011 576 2012 1111 2012 1092 2012 576 2013 1092 2013 577 2013 1111 2014 1112 2014 1093 2014 1111 2015 1093 2015 1092 2015 1112 2016 1113 2016 1094 2016 1112 2017 1094 2017 1093 2017 1113 2018 1114 2018 1095 2018 1113 2019 1095 2019 1094 2019 1114 2020 1115 2020 1096 2020 1114 2021 1096 2021 1095 2021 1115 2022 1116 2022 1097 2022 1115 2023 1097 2023 1096 2023 1116 2024 1117 2024 1098 2024 1116 2025 1098 2025 1097 2025 1117 2026 1118 2026 1099 2026 1117 2027 1099 2027 1098 2027 1118 2028 1119 2028 1100 2028 1118 2029 1100 2029 1099 2029 1119 2030 1120 2030 1101 2030 1119 2031 1101 2031 1100 2031 1120 2032 1121 2032 1102 2032 1120 2033 1102 2033 1101 2033 1121 2034 1122 2034 1103 2034 1121 2035 1103 2035 1102 2035 1122 2036 1123 2036 1104 2036 1122 2037 1104 2037 1103 2037 1123 2038 1124 2038 1105 2038 1123 2039 1105 2039 1104 2039 1124 2040 1125 2040 1106 2040 1124 2041 1106 2041 1105 2041 1125 2042 1126 2042 1107 2042 1125 2043 1107 2043 1106 2043 1126 2044 1127 2044 1108 2044 1126 2045 1108 2045 1107 2045 1127 2046 1128 2046 1109 2046 1127 2047 1109 2047 1108 2047 1128 2048 1129 2048 1110 2048 1128 2049 1110 2049 1109 2049 1129 2050 1032 2050 1033 2050 1129 2051 1033 2051 1110 2051 575 2052 1130 2052 1111 2052 575 2053 1111 2053 576 2053 1130 2054 1131 2054 1112 2054 1130 2055 1112 2055 1111 2055 1131 2056 1132 2056 1113 2056 1131 2057 1113 2057 1112 2057 1132 2058 1133 2058 1114 2058 1132 2059 1114 2059 1113 2059 1133 2060 1134 2060 1115 2060 1133 2061 1115 2061 1114 2061 1134 2062 1135 2062 1116 2062 1134 2063 1116 2063 1115 2063 1135 2064 1136 2064 1117 2064 1135 2065 1117 2065 1116 2065 1136 2066 1137 2066 1118 2066 1136 2067 1118 2067 1117 2067 1137 2068 1138 2068 1119 2068 1137 2069 1119 2069 1118 2069 1138 2070 1139 2070 1120 2070 1138 2071 1120 2071 1119 2071 1139 2072 1140 2072 1121 2072 1139 2073 1121 2073 1120 2073 1140 2074 1141 2074 1122 2074 1140 2075 1122 2075 1121 2075 1141 2076 1142 2076 1123 2076 1141 2077 1123 2077 1122 2077 1142 2078 1143 2078 1124 2078 1142 2079 1124 2079 1123 2079 1143 2080 1144 2080 1125 2080 1143 2081 1125 2081 1124 2081 1144 2082 1145 2082 1126 2082 1144 2083 1126 2083 1125 2083 1145 2084 1146 2084 1127 2084 1145 2085 1127 2085 1126 2085 1146 2086 1147 2086 1128 2086 1146 2087 1128 2087 1127 2087 1147 2088 1148 2088 1129 2088 1147 2089 1129 2089 1128 2089 1148 2090 1031 2090 1032 2090 1148 2091 1032 2091 1129 2091 574 2092 1149 2092 1130 2092 574 2093 1130 2093 575 2093 1149 2094 1150 2094 1131 2094 1149 2095 1131 2095 1130 2095 1150 2096 1151 2096 1132 2096 1150 2097 1132 2097 1131 2097 1151 2098 1152 2098 1133 2098 1151 2099 1133 2099 1132 2099 1152 2100 1153 2100 1134 2100 1152 2101 1134 2101 1133 2101 1153 2102 1154 2102 1135 2102 1153 2103 1135 2103 1134 2103 1154 2104 1155 2104 1136 2104 1154 2105 1136 2105 1135 2105 1155 2106 1156 2106 1137 2106 1155 2107 1137 2107 1136 2107 1156 2108 1157 2108 1138 2108 1156 2109 1138 2109 1137 2109 1157 2110 1158 2110 1139 2110 1157 2111 1139 2111 1138 2111 1158 2112 1159 2112 1140 2112 1158 2113 1140 2113 1139 2113 1159 2114 1160 2114 1141 2114 1159 2115 1141 2115 1140 2115 1160 2116 1161 2116 1142 2116 1160 2117 1142 2117 1141 2117 1161 2118 1162 2118 1143 2118 1161 2119 1143 2119 1142 2119 1162 2120 1163 2120 1144 2120 1162 2121 1144 2121 1143 2121 1163 2122 1164 2122 1145 2122 1163 2123 1145 2123 1144 2123 1164 2124 1165 2124 1146 2124 1164 2125 1146 2125 1145 2125 1165 2126 1166 2126 1147 2126 1165 2127 1147 2127 1146 2127 1166 2128 1167 2128 1148 2128 1166 2129 1148 2129 1147 2129 1167 2130 1030 2130 1031 2130 1167 2131 1031 2131 1148 2131 573 2132 1168 2132 1149 2132 573 2133 1149 2133 574 2133 1168 2134 1169 2134 1150 2134 1168 2135 1150 2135 1149 2135 1169 2136 1170 2136 1151 2136 1169 2137 1151 2137 1150 2137 1170 2138 1171 2138 1152 2138 1170 2139 1152 2139 1151 2139 1171 2140 1172 2140 1153 2140 1171 2141 1153 2141 1152 2141 1172 2142 1173 2142 1154 2142 1172 2143 1154 2143 1153 2143 1173 2144 1174 2144 1155 2144 1173 2145 1155 2145 1154 2145 1174 2146 1175 2146 1156 2146 1174 2147 1156 2147 1155 2147 1175 2148 1176 2148 1157 2148 1175 2149 1157 2149 1156 2149 1176 2150 1177 2150 1158 2150 1176 2151 1158 2151 1157 2151 1177 2152 1178 2152 1159 2152 1177 2153 1159 2153 1158 2153 1178 2154 1179 2154 1160 2154 1178 2155 1160 2155 1159 2155 1179 2156 1180 2156 1161 2156 1179 2157 1161 2157 1160 2157 1180 2158 1181 2158 1162 2158 1180 2159 1162 2159 1161 2159 1181 2160 1182 2160 1163 2160 1181 2161 1163 2161 1162 2161 1182 2162 1183 2162 1164 2162 1182 2163 1164 2163 1163 2163 1183 2164 1184 2164 1165 2164 1183 2165 1165 2165 1164 2165 1184 2166 1185 2166 1166 2166 1184 2167 1166 2167 1165 2167 1185 2168 1186 2168 1167 2168 1185 2169 1167 2169 1166 2169 1186 2170 1029 2170 1030 2170 1186 2171 1030 2171 1167 2171 572 2172 1187 2172 1168 2172 572 2173 1168 2173 573 2173 1187 2174 1188 2174 1169 2174 1187 2175 1169 2175 1168 2175 1188 2176 1189 2176 1170 2176 1188 2177 1170 2177 1169 2177 1189 2178 1190 2178 1171 2178 1189 2179 1171 2179 1170 2179 1190 2180 1191 2180 1172 2180 1190 2181 1172 2181 1171 2181 1191 2182 1192 2182 1173 2182 1191 2183 1173 2183 1172 2183 1192 2184 1193 2184 1174 2184 1192 2185 1174 2185 1173 2185 1193 2186 1194 2186 1175 2186 1193 2187 1175 2187 1174 2187 1194 2188 1195 2188 1176 2188 1194 2189 1176 2189 1175 2189 1195 2190 1196 2190 1177 2190 1195 2191 1177 2191 1176 2191 1196 2192 1197 2192 1178 2192 1196 2193 1178 2193 1177 2193 1197 2194 1198 2194 1179 2194 1197 2195 1179 2195 1178 2195 1198 2196 1199 2196 1180 2196 1198 2197 1180 2197 1179 2197 1199 2198 1200 2198 1181 2198 1199 2199 1181 2199 1180 2199 1200 2200 1201 2200 1182 2200 1200 2201 1182 2201 1181 2201 1201 2202 1202 2202 1183 2202 1201 2203 1183 2203 1182 2203 1202 2204 1203 2204 1184 2204 1202 2205 1184 2205 1183 2205 1203 2206 1204 2206 1185 2206 1203 2207 1185 2207 1184 2207 1204 2208 1205 2208 1186 2208 1204 2209 1186 2209 1185 2209 1205 2210 1028 2210 1029 2210 1205 2211 1029 2211 1186 2211 571 2212 1206 2212 1187 2212 571 2213 1187 2213 572 2213 1206 2214 1207 2214 1188 2214 1206 2215 1188 2215 1187 2215 1207 2216 1208 2216 1189 2216 1207 2217 1189 2217 1188 2217 1208 2218 1209 2218 1190 2218 1208 2219 1190 2219 1189 2219 1209 2220 1210 2220 1191 2220 1209 2221 1191 2221 1190 2221 1210 2222 1211 2222 1192 2222 1210 2223 1192 2223 1191 2223 1211 2224 1212 2224 1193 2224 1211 2225 1193 2225 1192 2225 1212 2226 1213 2226 1194 2226 1212 2227 1194 2227 1193 2227 1213 2228 1214 2228 1195 2228 1213 2229 1195 2229 1194 2229 1214 2230 1215 2230 1196 2230 1214 2231 1196 2231 1195 2231 1215 2232 1216 2232 1197 2232 1215 2233 1197 2233 1196 2233 1216 2234 1217 2234 1198 2234 1216 2235 1198 2235 1197 2235 1217 2236 1218 2236 1199 2236 1217 2237 1199 2237 1198 2237 1218 2238 1219 2238 1200 2238 1218 2239 1200 2239 1199 2239 1219 2240 1220 2240 1201 2240 1219 2241 1201 2241 1200 2241 1220 2242 1221 2242 1202 2242 1220 2243 1202 2243 1201 2243 1221 2244 1222 2244 1203 2244 1221 2245 1203 2245 1202 2245 1222 2246 1223 2246 1204 2246 1222 2247 1204 2247 1203 2247 1223 2248 1224 2248 1205 2248 1223 2249 1205 2249 1204 2249 1224 2250 1027 2250 1028 2250 1224 2251 1028 2251 1205 2251 570 2252 1225 2252 1206 2252 570 2253 1206 2253 571 2253 1225 2254 1226 2254 1207 2254 1225 2255 1207 2255 1206 2255 1226 2256 1227 2256 1208 2256 1226 2257 1208 2257 1207 2257 1227 2258 1228 2258 1209 2258 1227 2259 1209 2259 1208 2259 1228 2260 1229 2260 1210 2260 1228 2261 1210 2261 1209 2261 1229 2262 1230 2262 1211 2262 1229 2263 1211 2263 1210 2263 1230 2264 1231 2264 1212 2264 1230 2265 1212 2265 1211 2265 1231 2266 1232 2266 1213 2266 1231 2267 1213 2267 1212 2267 1232 2268 1233 2268 1214 2268 1232 2269 1214 2269 1213 2269 1233 2270 1234 2270 1215 2270 1233 2271 1215 2271 1214 2271 1234 2272 1235 2272 1216 2272 1234 2273 1216 2273 1215 2273 1235 2274 1236 2274 1217 2274 1235 2275 1217 2275 1216 2275 1236 2276 1237 2276 1218 2276 1236 2277 1218 2277 1217 2277 1237 2278 1238 2278 1219 2278 1237 2279 1219 2279 1218 2279 1238 2280 1239 2280 1220 2280 1238 2281 1220 2281 1219 2281 1239 2282 1240 2282 1221 2282 1239 2283 1221 2283 1220 2283 1240 2284 1241 2284 1222 2284 1240 2285 1222 2285 1221 2285 1241 2286 1242 2286 1223 2286 1241 2287 1223 2287 1222 2287 1242 2288 1243 2288 1224 2288 1242 2289 1224 2289 1223 2289 1243 2290 1026 2290 1027 2290 1243 2291 1027 2291 1224 2291 569 2292 1244 2292 1225 2292 569 2293 1225 2293 570 2293 1244 2294 1245 2294 1226 2294 1244 2295 1226 2295 1225 2295 1245 2296 1246 2296 1227 2296 1245 2297 1227 2297 1226 2297 1246 2298 1247 2298 1228 2298 1246 2299 1228 2299 1227 2299 1247 2300 1248 2300 1229 2300 1247 2301 1229 2301 1228 2301 1248 2302 1249 2302 1230 2302 1248 2303 1230 2303 1229 2303 1249 2304 1250 2304 1231 2304 1249 2305 1231 2305 1230 2305 1250 2306 1251 2306 1232 2306 1250 2307 1232 2307 1231 2307 1251 2308 1252 2308 1233 2308 1251 2309 1233 2309 1232 2309 1252 2310 1253 2310 1234 2310 1252 2311 1234 2311 1233 2311 1253 2312 1254 2312 1235 2312 1253 2313 1235 2313 1234 2313 1254 2314 1255 2314 1236 2314 1254 2315 1236 2315 1235 2315 1255 2316 1256 2316 1237 2316 1255 2317 1237 2317 1236 2317 1256 2318 1257 2318 1238 2318 1256 2319 1238 2319 1237 2319 1257 2320 1258 2320 1239 2320 1257 2321 1239 2321 1238 2321 1258 2322 1259 2322 1240 2322 1258 2323 1240 2323 1239 2323 1259 2324 1260 2324 1241 2324 1259 2325 1241 2325 1240 2325 1260 2326 1261 2326 1242 2326 1260 2327 1242 2327 1241 2327 1261 2328 1262 2328 1243 2328 1261 2329 1243 2329 1242 2329 1262 2330 1025 2330 1026 2330 1262 2331 1026 2331 1243 2331 568 2332 1263 2332 1244 2332 568 2333 1244 2333 569 2333 1263 2334 1264 2334 1245 2334 1263 2335 1245 2335 1244 2335 1264 2336 1265 2336 1246 2336 1264 2337 1246 2337 1245 2337 1265 2338 1266 2338 1247 2338 1265 2339 1247 2339 1246 2339 1266 2340 1267 2340 1248 2340 1266 2341 1248 2341 1247 2341 1267 2342 1268 2342 1249 2342 1267 2343 1249 2343 1248 2343 1268 2344 1269 2344 1250 2344 1268 2345 1250 2345 1249 2345 1269 2346 1270 2346 1251 2346 1269 2347 1251 2347 1250 2347 1270 2348 1271 2348 1252 2348 1270 2349 1252 2349 1251 2349 1271 2350 1272 2350 1253 2350 1271 2351 1253 2351 1252 2351 1272 2352 1273 2352 1254 2352 1272 2353 1254 2353 1253 2353 1273 2354 1274 2354 1255 2354 1273 2355 1255 2355 1254 2355 1274 2356 1275 2356 1256 2356 1274 2357 1256 2357 1255 2357 1275 2358 1276 2358 1257 2358 1275 2359 1257 2359 1256 2359 1276 2360 1277 2360 1258 2360 1276 2361 1258 2361 1257 2361 1277 2362 1278 2362 1259 2362 1277 2363 1259 2363 1258 2363 1278 2364 1279 2364 1260 2364 1278 2365 1260 2365 1259 2365 1279 2366 1280 2366 1261 2366 1279 2367 1261 2367 1260 2367 1280 2368 1281 2368 1262 2368 1280 2369 1262 2369 1261 2369 1281 2370 1024 2370 1025 2370 1281 2371 1025 2371 1262 2371 567 2372 1282 2372 1263 2372 567 2373 1263 2373 568 2373 1282 2374 1283 2374 1264 2374 1282 2375 1264 2375 1263 2375 1283 2376 1284 2376 1265 2376 1283 2377 1265 2377 1264 2377 1284 2378 1285 2378 1266 2378 1284 2379 1266 2379 1265 2379 1285 2380 1286 2380 1267 2380 1285 2381 1267 2381 1266 2381 1286 2382 1287 2382 1268 2382 1286 2383 1268 2383 1267 2383 1287 2384 1288 2384 1269 2384 1287 2385 1269 2385 1268 2385 1288 2386 1289 2386 1270 2386 1288 2387 1270 2387 1269 2387 1289 2388 1290 2388 1271 2388 1289 2389 1271 2389 1270 2389 1290 2390 1291 2390 1272 2390 1290 2391 1272 2391 1271 2391 1291 2392 1292 2392 1273 2392 1291 2393 1273 2393 1272 2393 1292 2394 1293 2394 1274 2394 1292 2395 1274 2395 1273 2395 1293 2396 1294 2396 1275 2396 1293 2397 1275 2397 1274 2397 1294 2398 1295 2398 1276 2398 1294 2399 1276 2399 1275 2399 1295 2400 1296 2400 1277 2400 1295 2401 1277 2401 1276 2401 1296 2402 1297 2402 1278 2402 1296 2403 1278 2403 1277 2403 1297 2404 1298 2404 1279 2404 1297 2405 1279 2405 1278 2405 1298 2406 1299 2406 1280 2406 1298 2407 1280 2407 1279 2407 1299 2408 1300 2408 1281 2408 1299 2409 1281 2409 1280 2409 1300 2410 1023 2410 1024 2410 1300 2411 1024 2411 1281 2411 566 2412 1301 2412 1282 2412 566 2413 1282 2413 567 2413 1301 2414 1302 2414 1283 2414 1301 2415 1283 2415 1282 2415 1302 2416 1303 2416 1284 2416 1302 2417 1284 2417 1283 2417 1303 2418 1304 2418 1285 2418 1303 2419 1285 2419 1284 2419 1304 2420 1305 2420 1286 2420 1304 2421 1286 2421 1285 2421 1305 2422 1306 2422 1287 2422 1305 2423 1287 2423 1286 2423 1306 2424 1307 2424 1288 2424 1306 2425 1288 2425 1287 2425 1307 2426 1308 2426 1289 2426 1307 2427 1289 2427 1288 2427 1308 2428 1309 2428 1290 2428 1308 2429 1290 2429 1289 2429 1309 2430 1310 2430 1291 2430 1309 2431 1291 2431 1290 2431 1310 2432 1311 2432 1292 2432 1310 2433 1292 2433 1291 2433 1311 2434 1312 2434 1293 2434 1311 2435 1293 2435 1292 2435 1312 2436 1313 2436 1294 2436 1312 2437 1294 2437 1293 2437 1313 2438 1314 2438 1295 2438 1313 2439 1295 2439 1294 2439 1314 2440 1315 2440 1296 2440 1314 2441 1296 2441 1295 2441 1315 2442 1316 2442 1297 2442 1315 2443 1297 2443 1296 2443 1316 2444 1317 2444 1298 2444 1316 2445 1298 2445 1297 2445 1317 2446 1318 2446 1299 2446 1317 2447 1299 2447 1298 2447 1318 2448 1319 2448 1300 2448 1318 2449 1300 2449 1299 2449 1319 2450 1022 2450 1023 2450 1319 2451 1023 2451 1300 2451 565 2452 1320 2452 1301 2452 565 2453 1301 2453 566 2453 1320 2454 1321 2454 1302 2454 1320 2455 1302 2455 1301 2455 1321 2456 1322 2456 1303 2456 1321 2457 1303 2457 1302 2457 1322 2458 1323 2458 1304 2458 1322 2459 1304 2459 1303 2459 1323 2460 1324 2460 1305 2460 1323 2461 1305 2461 1304 2461 1324 2462 1325 2462 1306 2462 1324 2463 1306 2463 1305 2463 1325 2464 1326 2464 1307 2464 1325 2465 1307 2465 1306 2465 1326 2466 1327 2466 1308 2466 1326 2467 1308 2467 1307 2467 1327 2468 1328 2468 1309 2468 1327 2469 1309 2469 1308 2469 1328 2470 1329 2470 1310 2470 1328 2471 1310 2471 1309 2471 1329 2472 1330 2472 1311 2472 1329 2473 1311 2473 1310 2473 1330 2474 1331 2474 1312 2474 1330 2475 1312 2475 1311 2475 1331 2476 1332 2476 1313 2476 1331 2477 1313 2477 1312 2477 1332 2478 1333 2478 1314 2478 1332 2479 1314 2479 1313 2479 1333 2480 1334 2480 1315 2480 1333 2481 1315 2481 1314 2481 1334 2482 1335 2482 1316 2482 1334 2483 1316 2483 1315 2483 1335 2484 1336 2484 1317 2484 1335 2485 1317 2485 1316 2485 1336 2486 1337 2486 1318 2486 1336 2487 1318 2487 1317 2487 1337 2488 1338 2488 1319 2488 1337 2489 1319 2489 1318 2489 1338 2490 1021 2490 1022 2490 1338 2491 1022 2491 1319 2491 564 2492 1339 2492 1320 2492 564 2493 1320 2493 565 2493 1339 2494 1340 2494 1321 2494 1339 2495 1321 2495 1320 2495 1340 2496 1341 2496 1322 2496 1340 2497 1322 2497 1321 2497 1341 2498 1342 2498 1323 2498 1341 2499 1323 2499 1322 2499 1342 2500 1343 2500 1324 2500 1342 2501 1324 2501 1323 2501 1343 2502 1344 2502 1325 2502 1343 2503 1325 2503 1324 2503 1344 2504 1345 2504 1326 2504 1344 2505 1326 2505 1325 2505 1345 2506 1346 2506 1327 2506 1345 2507 1327 2507 1326 2507 1346 2508 1347 2508 1328 2508 1346 2509 1328 2509 1327 2509 1347 2510 1348 2510 1329 2510 1347 2511 1329 2511 1328 2511 1348 2512 1349 2512 1330 2512 1348 2513 1330 2513 1329 2513 1349 2514 1350 2514 1331 2514 1349 2515 1331 2515 1330 2515 1350 2516 1351 2516 1332 2516 1350 2517 1332 2517 1331 2517 1351 2518 1352 2518 1333 2518 1351 2519 1333 2519 1332 2519 1352 2520 1353 2520 1334 2520 1352 2521 1334 2521 1333 2521 1353 2522 1354 2522 1335 2522 1353 2523 1335 2523 1334 2523 1354 2524 1355 2524 1336 2524 1354 2525 1336 2525 1335 2525 1355 2526 1356 2526 1337 2526 1355 2527 1337 2527 1336 2527 1356 2528 1357 2528 1338 2528 1356 2529 1338 2529 1337 2529 1357 2530 1020 2530 1021 2530 1357 2531 1021 2531 1338 2531 563 2532 1358 2532 1339 2532 563 2533 1339 2533 564 2533 1358 2534 1359 2534 1340 2534 1358 2535 1340 2535 1339 2535 1359 2536 1360 2536 1341 2536 1359 2537 1341 2537 1340 2537 1360 2538 1361 2538 1342 2538 1360 2539 1342 2539 1341 2539 1361 2540 1362 2540 1343 2540 1361 2541 1343 2541 1342 2541 1362 2542 1363 2542 1344 2542 1362 2543 1344 2543 1343 2543 1363 2544 1364 2544 1345 2544 1363 2545 1345 2545 1344 2545 1364 2546 1365 2546 1346 2546 1364 2547 1346 2547 1345 2547 1365 2548 1366 2548 1347 2548 1365 2549 1347 2549 1346 2549 1366 2550 1367 2550 1348 2550 1366 2551 1348 2551 1347 2551 1367 2552 1368 2552 1349 2552 1367 2553 1349 2553 1348 2553 1368 2554 1369 2554 1350 2554 1368 2555 1350 2555 1349 2555 1369 2556 1370 2556 1351 2556 1369 2557 1351 2557 1350 2557 1370 2558 1371 2558 1352 2558 1370 2559 1352 2559 1351 2559 1371 2560 1372 2560 1353 2560 1371 2561 1353 2561 1352 2561 1372 2562 1373 2562 1354 2562 1372 2563 1354 2563 1353 2563 1373 2564 1374 2564 1355 2564 1373 2565 1355 2565 1354 2565 1374 2566 1375 2566 1356 2566 1374 2567 1356 2567 1355 2567 1375 2568 1376 2568 1357 2568 1375 2569 1357 2569 1356 2569 1376 2570 1019 2570 1020 2570 1376 2571 1020 2571 1357 2571 562 2572 1377 2572 1358 2572 562 2573 1358 2573 563 2573 1377 2574 1378 2574 1359 2574 1377 2575 1359 2575 1358 2575 1378 2576 1379 2576 1360 2576 1378 2577 1360 2577 1359 2577 1379 2578 1380 2578 1361 2578 1379 2579 1361 2579 1360 2579 1380 2580 1381 2580 1362 2580 1380 2581 1362 2581 1361 2581 1381 2582 1382 2582 1363 2582 1381 2583 1363 2583 1362 2583 1382 2584 1383 2584 1364 2584 1382 2585 1364 2585 1363 2585 1383 2586 1384 2586 1365 2586 1383 2587 1365 2587 1364 2587 1384 2588 1385 2588 1366 2588 1384 2589 1366 2589 1365 2589 1385 2590 1386 2590 1367 2590 1385 2591 1367 2591 1366 2591 1386 2592 1387 2592 1368 2592 1386 2593 1368 2593 1367 2593 1387 2594 1388 2594 1369 2594 1387 2595 1369 2595 1368 2595 1388 2596 1389 2596 1370 2596 1388 2597 1370 2597 1369 2597 1389 2598 1390 2598 1371 2598 1389 2599 1371 2599 1370 2599 1390 2600 1391 2600 1372 2600 1390 2601 1372 2601 1371 2601 1391 2602 1392 2602 1373 2602 1391 2603 1373 2603 1372 2603 1392 2604 1393 2604 1374 2604 1392 2605 1374 2605 1373 2605 1393 2606 1394 2606 1375 2606 1393 2607 1375 2607 1374 2607 1394 2608 1395 2608 1376 2608 1394 2609 1376 2609 1375 2609 1395 2610 1018 2610 1019 2610 1395 2611 1019 2611 1376 2611 561 2612 1396 2612 1377 2612 561 2613 1377 2613 562 2613 1396 2614 1397 2614 1378 2614 1396 2615 1378 2615 1377 2615 1397 2616 1398 2616 1379 2616 1397 2617 1379 2617 1378 2617 1398 2618 1399 2618 1380 2618 1398 2619 1380 2619 1379 2619 1399 2620 1400 2620 1381 2620 1399 2621 1381 2621 1380 2621 1400 2622 1401 2622 1382 2622 1400 2623 1382 2623 1381 2623 1401 2624 1402 2624 1383 2624 1401 2625 1383 2625 1382 2625 1402 2626 1403 2626 1384 2626 1402 2627 1384 2627 1383 2627 1403 2628 1404 2628 1385 2628 1403 2629 1385 2629 1384 2629 1404 2630 1405 2630 1386 2630 1404 2631 1386 2631 1385 2631 1405 2632 1406 2632 1387 2632 1405 2633 1387 2633 1386 2633 1406 2634 1407 2634 1388 2634 1406 2635 1388 2635 1387 2635 1407 2636 1408 2636 1389 2636 1407 2637 1389 2637 1388 2637 1408 2638 1409 2638 1390 2638 1408 2639 1390 2639 1389 2639 1409 2640 1410 2640 1391 2640 1409 2641 1391 2641 1390 2641 1410 2642 1411 2642 1392 2642 1410 2643 1392 2643 1391 2643 1411 2644 1412 2644 1393 2644 1411 2645 1393 2645 1392 2645 1412 2646 1413 2646 1394 2646 1412 2647 1394 2647 1393 2647 1413 2648 1414 2648 1395 2648 1413 2649 1395 2649 1394 2649 1414 2650 1017 2650 1018 2650 1414 2651 1018 2651 1395 2651 560 2652 1415 2652 1396 2652 560 2653 1396 2653 561 2653 1415 2654 1416 2654 1397 2654 1415 2655 1397 2655 1396 2655 1416 2656 1417 2656 1398 2656 1416 2657 1398 2657 1397 2657 1417 2658 1418 2658 1399 2658 1417 2659 1399 2659 1398 2659 1418 2660 1419 2660 1400 2660 1418 2661 1400 2661 1399 2661 1419 2662 1420 2662 1401 2662 1419 2663 1401 2663 1400 2663 1420 2664 1421 2664 1402 2664 1420 2665 1402 2665 1401 2665 1421 2666 1422 2666 1403 2666 1421 2667 1403 2667 1402 2667 1422 2668 1423 2668 1404 2668 1422 2669 1404 2669 1403 2669 1423 2670 1424 2670 1405 2670 1423 2671 1405 2671 1404 2671 1424 2672 1425 2672 1406 2672 1424 2673 1406 2673 1405 2673 1425 2674 1426 2674 1407 2674 1425 2675 1407 2675 1406 2675 1426 2676 1427 2676 1408 2676 1426 2677 1408 2677 1407 2677 1427 2678 1428 2678 1409 2678 1427 2679 1409 2679 1408 2679 1428 2680 1429 2680 1410 2680 1428 2681 1410 2681 1409 2681 1429 2682 1430 2682 1411 2682 1429 2683 1411 2683 1410 2683 1430 2684 1431 2684 1412 2684 1430 2685 1412 2685 1411 2685 1431 2686 1432 2686 1413 2686 1431 2687 1413 2687 1412 2687 1432 2688 1433 2688 1414 2688 1432 2689 1414 2689 1413 2689 1433 2690 1016 2690 1017 2690 1433 2691 1017 2691 1414 2691 141 2692 140 2692 1415 2692 141 2693 1415 2693 560 2693 140 2694 1434 2694 1416 2694 140 2695 1416 2695 1415 2695 1434 2696 1435 2696 1417 2696 1434 2697 1417 2697 1416 2697 1435 2698 1436 2698 1418 2698 1435 2699 1418 2699 1417 2699 1436 2700 1437 2700 1419 2700 1436 2701 1419 2701 1418 2701 1437 2702 1438 2702 1420 2702 1437 2703 1420 2703 1419 2703 1438 2704 1439 2704 1421 2704 1438 2705 1421 2705 1420 2705 1439 2706 1440 2706 1422 2706 1439 2707 1422 2707 1421 2707 1440 2708 1441 2708 1423 2708 1440 2709 1423 2709 1422 2709 1441 2710 1442 2710 1424 2710 1441 2711 1424 2711 1423 2711 1442 2712 1443 2712 1425 2712 1442 2713 1425 2713 1424 2713 1443 2714 1444 2714 1426 2714 1443 2715 1426 2715 1425 2715 1444 2716 1445 2716 1427 2716 1444 2717 1427 2717 1426 2717 1445 2718 1446 2718 1428 2718 1445 2719 1428 2719 1427 2719 1446 2720 1447 2720 1429 2720 1446 2721 1429 2721 1428 2721 1447 2722 1448 2722 1430 2722 1447 2723 1430 2723 1429 2723 1448 2724 1449 2724 1431 2724 1448 2725 1431 2725 1430 2725 1449 2726 1450 2726 1432 2726 1449 2727 1432 2727 1431 2727 1450 2728 1451 2728 1433 2728 1450 2729 1433 2729 1432 2729 1451 2730 1015 2730 1016 2730 1451 2731 1016 2731 1433 2731 1036 2732 1452 2732 1453 2732 1036 2733 1453 2733 1035 2733 1452 2734 1454 2734 1455 2734 1452 2735 1455 2735 1453 2735 1454 2736 1456 2736 1457 2736 1454 2737 1457 2737 1455 2737 1456 2738 1458 2738 1459 2738 1456 2739 1459 2739 1457 2739 1458 2740 1460 2740 1461 2740 1458 2741 1461 2741 1459 2741 1460 2742 1462 2742 1463 2742 1460 2743 1463 2743 1461 2743 1462 2744 1464 2744 1465 2744 1462 2745 1465 2745 1463 2745 1464 2746 1466 2746 1467 2746 1464 2747 1467 2747 1465 2747 1466 2748 1468 2748 1469 2748 1466 2749 1469 2749 1467 2749 1468 2750 1470 2750 1471 2750 1468 2751 1471 2751 1469 2751 1470 2752 1472 2752 1473 2752 1470 2753 1473 2753 1471 2753 1472 2754 1474 2754 1475 2754 1472 2755 1475 2755 1473 2755 1474 2756 1476 2756 1477 2756 1474 2757 1477 2757 1475 2757 1476 2758 1478 2758 1479 2758 1476 2759 1479 2759 1477 2759 1478 2760 1480 2760 1481 2760 1478 2761 1481 2761 1479 2761 1480 2762 1482 2762 1483 2762 1480 2763 1483 2763 1481 2763 1482 2764 1484 2764 1485 2764 1482 2765 1485 2765 1483 2765 1484 2766 1486 2766 1487 2766 1484 2767 1487 2767 1485 2767 1486 2768 1488 2768 1489 2768 1486 2769 1489 2769 1487 2769 1488 2770 1014 2770 20 2770 1488 2771 20 2771 1489 2771 1037 2772 1490 2772 1452 2772 1037 2773 1452 2773 1036 2773 1490 2774 1491 2774 1454 2774 1490 2775 1454 2775 1452 2775 1491 2776 1492 2776 1456 2776 1491 2777 1456 2777 1454 2777 1492 2778 1493 2778 1458 2778 1492 2779 1458 2779 1456 2779 1493 2780 1494 2780 1460 2780 1493 2781 1460 2781 1458 2781 1494 2782 1495 2782 1462 2782 1494 2783 1462 2783 1460 2783 1495 2784 1496 2784 1464 2784 1495 2785 1464 2785 1462 2785 1496 2786 1497 2786 1466 2786 1496 2787 1466 2787 1464 2787 1497 2788 1498 2788 1468 2788 1497 2789 1468 2789 1466 2789 1498 2790 1499 2790 1470 2790 1498 2791 1470 2791 1468 2791 1499 2792 1500 2792 1472 2792 1499 2793 1472 2793 1470 2793 1500 2794 1501 2794 1474 2794 1500 2795 1474 2795 1472 2795 1501 2796 1502 2796 1476 2796 1501 2797 1476 2797 1474 2797 1502 2798 1503 2798 1478 2798 1502 2799 1478 2799 1476 2799 1503 2800 1504 2800 1480 2800 1503 2801 1480 2801 1478 2801 1504 2802 1505 2802 1482 2802 1504 2803 1482 2803 1480 2803 1505 2804 1506 2804 1484 2804 1505 2805 1484 2805 1482 2805 1506 2806 1507 2806 1486 2806 1506 2807 1486 2807 1484 2807 1507 2808 1508 2808 1488 2808 1507 2809 1488 2809 1486 2809 1508 2810 1012 2810 1014 2810 1508 2811 1014 2811 1488 2811 1038 2812 1509 2812 1490 2812 1038 2813 1490 2813 1037 2813 1509 2814 1510 2814 1491 2814 1509 2815 1491 2815 1490 2815 1510 2816 1511 2816 1492 2816 1510 2817 1492 2817 1491 2817 1511 2818 1512 2818 1493 2818 1511 2819 1493 2819 1492 2819 1512 2820 1513 2820 1494 2820 1512 2821 1494 2821 1493 2821 1513 2822 1514 2822 1495 2822 1513 2823 1495 2823 1494 2823 1514 2824 1515 2824 1496 2824 1514 2825 1496 2825 1495 2825 1515 2826 1516 2826 1497 2826 1515 2827 1497 2827 1496 2827 1516 2828 1517 2828 1498 2828 1516 2829 1498 2829 1497 2829 1517 2830 1518 2830 1499 2830 1517 2831 1499 2831 1498 2831 1518 2832 1519 2832 1500 2832 1518 2833 1500 2833 1499 2833 1519 2834 1520 2834 1501 2834 1519 2835 1501 2835 1500 2835 1520 2836 1521 2836 1502 2836 1520 2837 1502 2837 1501 2837 1521 2838 1522 2838 1503 2838 1521 2839 1503 2839 1502 2839 1522 2840 1523 2840 1504 2840 1522 2841 1504 2841 1503 2841 1523 2842 1524 2842 1505 2842 1523 2843 1505 2843 1504 2843 1524 2844 1525 2844 1506 2844 1524 2845 1506 2845 1505 2845 1525 2846 1526 2846 1507 2846 1525 2847 1507 2847 1506 2847 1526 2848 1527 2848 1508 2848 1526 2849 1508 2849 1507 2849 1527 2850 1010 2850 1012 2850 1527 2851 1012 2851 1508 2851 1039 2852 1528 2852 1509 2852 1039 2853 1509 2853 1038 2853 1528 2854 1529 2854 1510 2854 1528 2855 1510 2855 1509 2855 1529 2856 1530 2856 1511 2856 1529 2857 1511 2857 1510 2857 1530 2858 1531 2858 1512 2858 1530 2859 1512 2859 1511 2859 1531 2860 1532 2860 1513 2860 1531 2861 1513 2861 1512 2861 1532 2862 1533 2862 1514 2862 1532 2863 1514 2863 1513 2863 1533 2864 1534 2864 1515 2864 1533 2865 1515 2865 1514 2865 1534 2866 1535 2866 1516 2866 1534 2867 1516 2867 1515 2867 1535 2868 1536 2868 1517 2868 1535 2869 1517 2869 1516 2869 1536 2870 1537 2870 1518 2870 1536 2871 1518 2871 1517 2871 1537 2872 1538 2872 1519 2872 1537 2873 1519 2873 1518 2873 1538 2874 1539 2874 1520 2874 1538 2875 1520 2875 1519 2875 1539 2876 1540 2876 1521 2876 1539 2877 1521 2877 1520 2877 1540 2878 1541 2878 1522 2878 1540 2879 1522 2879 1521 2879 1541 2880 1542 2880 1523 2880 1541 2881 1523 2881 1522 2881 1542 2882 1543 2882 1524 2882 1542 2883 1524 2883 1523 2883 1543 2884 1544 2884 1525 2884 1543 2885 1525 2885 1524 2885 1544 2886 1545 2886 1526 2886 1544 2887 1526 2887 1525 2887 1545 2888 1546 2888 1527 2888 1545 2889 1527 2889 1526 2889 1546 2890 1008 2890 1010 2890 1546 2891 1010 2891 1527 2891 1040 2892 1547 2892 1528 2892 1040 2893 1528 2893 1039 2893 1547 2894 1548 2894 1529 2894 1547 2895 1529 2895 1528 2895 1548 2896 1549 2896 1530 2896 1548 2897 1530 2897 1529 2897 1549 2898 1550 2898 1531 2898 1549 2899 1531 2899 1530 2899 1550 2900 1551 2900 1532 2900 1550 2901 1532 2901 1531 2901 1551 2902 1552 2902 1533 2902 1551 2903 1533 2903 1532 2903 1552 2904 1553 2904 1534 2904 1552 2905 1534 2905 1533 2905 1553 2906 1554 2906 1535 2906 1553 2907 1535 2907 1534 2907 1554 2908 1555 2908 1536 2908 1554 2909 1536 2909 1535 2909 1555 2910 1556 2910 1537 2910 1555 2911 1537 2911 1536 2911 1556 2912 1557 2912 1538 2912 1556 2913 1538 2913 1537 2913 1557 2914 1558 2914 1539 2914 1557 2915 1539 2915 1538 2915 1558 2916 1559 2916 1540 2916 1558 2917 1540 2917 1539 2917 1559 2918 1560 2918 1541 2918 1559 2919 1541 2919 1540 2919 1560 2920 1561 2920 1542 2920 1560 2921 1542 2921 1541 2921 1561 2922 1562 2922 1543 2922 1561 2923 1543 2923 1542 2923 1562 2924 1563 2924 1544 2924 1562 2925 1544 2925 1543 2925 1563 2926 1564 2926 1545 2926 1563 2927 1545 2927 1544 2927 1564 2928 1565 2928 1546 2928 1564 2929 1546 2929 1545 2929 1565 2930 1006 2930 1008 2930 1565 2931 1008 2931 1546 2931 1041 2932 1566 2932 1547 2932 1041 2933 1547 2933 1040 2933 1566 2934 1567 2934 1548 2934 1566 2935 1548 2935 1547 2935 1567 2936 1568 2936 1549 2936 1567 2937 1549 2937 1548 2937 1568 2938 1569 2938 1550 2938 1568 2939 1550 2939 1549 2939 1569 2940 1570 2940 1551 2940 1569 2941 1551 2941 1550 2941 1570 2942 1571 2942 1552 2942 1570 2943 1552 2943 1551 2943 1571 2944 1572 2944 1553 2944 1571 2945 1553 2945 1552 2945 1572 2946 1573 2946 1554 2946 1572 2947 1554 2947 1553 2947 1573 2948 1574 2948 1555 2948 1573 2949 1555 2949 1554 2949 1574 2950 1575 2950 1556 2950 1574 2951 1556 2951 1555 2951 1575 2952 1576 2952 1557 2952 1575 2953 1557 2953 1556 2953 1576 2954 1577 2954 1558 2954 1576 2955 1558 2955 1557 2955 1577 2956 1578 2956 1559 2956 1577 2957 1559 2957 1558 2957 1578 2958 1579 2958 1560 2958 1578 2959 1560 2959 1559 2959 1579 2960 1580 2960 1561 2960 1579 2961 1561 2961 1560 2961 1580 2962 1581 2962 1562 2962 1580 2963 1562 2963 1561 2963 1581 2964 1582 2964 1563 2964 1581 2965 1563 2965 1562 2965 1582 2966 1583 2966 1564 2966 1582 2967 1564 2967 1563 2967 1583 2968 1584 2968 1565 2968 1583 2969 1565 2969 1564 2969 1584 2970 1004 2970 1006 2970 1584 2971 1006 2971 1565 2971 1042 2972 1585 2972 1566 2972 1042 2973 1566 2973 1041 2973 1585 2974 1586 2974 1567 2974 1585 2975 1567 2975 1566 2975 1586 2976 1587 2976 1568 2976 1586 2977 1568 2977 1567 2977 1587 2978 1588 2978 1569 2978 1587 2979 1569 2979 1568 2979 1588 2980 1589 2980 1570 2980 1588 2981 1570 2981 1569 2981 1589 2982 1590 2982 1571 2982 1589 2983 1571 2983 1570 2983 1590 2984 1591 2984 1572 2984 1590 2985 1572 2985 1571 2985 1591 2986 1592 2986 1573 2986 1591 2987 1573 2987 1572 2987 1592 2988 1593 2988 1574 2988 1592 2989 1574 2989 1573 2989 1593 2990 1594 2990 1575 2990 1593 2991 1575 2991 1574 2991 1594 2992 1595 2992 1576 2992 1594 2993 1576 2993 1575 2993 1595 2994 1596 2994 1577 2994 1595 2995 1577 2995 1576 2995 1596 2996 1597 2996 1578 2996 1596 2997 1578 2997 1577 2997 1597 2998 1598 2998 1579 2998 1597 2999 1579 2999 1578 2999 1598 3000 1599 3000 1580 3000 1598 3001 1580 3001 1579 3001 1599 3002 1600 3002 1581 3002 1599 3003 1581 3003 1580 3003 1600 3004 1601 3004 1582 3004 1600 3005 1582 3005 1581 3005 1601 3006 1602 3006 1583 3006 1601 3007 1583 3007 1582 3007 1602 3008 1603 3008 1584 3008 1602 3009 1584 3009 1583 3009 1603 3010 1002 3010 1004 3010 1603 3011 1004 3011 1584 3011 1043 3012 1604 3012 1585 3012 1043 3013 1585 3013 1042 3013 1604 3014 1605 3014 1586 3014 1604 3015 1586 3015 1585 3015 1605 3016 1606 3016 1587 3016 1605 3017 1587 3017 1586 3017 1606 3018 1607 3018 1588 3018 1606 3019 1588 3019 1587 3019 1607 3020 1608 3020 1589 3020 1607 3021 1589 3021 1588 3021 1608 3022 1609 3022 1590 3022 1608 3023 1590 3023 1589 3023 1609 3024 1610 3024 1591 3024 1609 3025 1591 3025 1590 3025 1610 3026 1611 3026 1592 3026 1610 3027 1592 3027 1591 3027 1611 3028 1612 3028 1593 3028 1611 3029 1593 3029 1592 3029 1612 3030 1613 3030 1594 3030 1612 3031 1594 3031 1593 3031 1613 3032 1614 3032 1595 3032 1613 3033 1595 3033 1594 3033 1614 3034 1615 3034 1596 3034 1614 3035 1596 3035 1595 3035 1615 3036 1616 3036 1597 3036 1615 3037 1597 3037 1596 3037 1616 3038 1617 3038 1598 3038 1616 3039 1598 3039 1597 3039 1617 3040 1618 3040 1599 3040 1617 3041 1599 3041 1598 3041 1618 3042 1619 3042 1600 3042 1618 3043 1600 3043 1599 3043 1619 3044 1620 3044 1601 3044 1619 3045 1601 3045 1600 3045 1620 3046 1621 3046 1602 3046 1620 3047 1602 3047 1601 3047 1621 3048 1622 3048 1603 3048 1621 3049 1603 3049 1602 3049 1622 3050 1000 3050 1002 3050 1622 3051 1002 3051 1603 3051 1044 3052 1623 3052 1604 3052 1044 3053 1604 3053 1043 3053 1623 3054 1624 3054 1605 3054 1623 3055 1605 3055 1604 3055 1624 3056 1625 3056 1606 3056 1624 3057 1606 3057 1605 3057 1625 3058 1626 3058 1607 3058 1625 3059 1607 3059 1606 3059 1626 3060 1627 3060 1608 3060 1626 3061 1608 3061 1607 3061 1627 3062 1628 3062 1609 3062 1627 3063 1609 3063 1608 3063 1628 3064 1629 3064 1610 3064 1628 3065 1610 3065 1609 3065 1629 3066 1630 3066 1611 3066 1629 3067 1611 3067 1610 3067 1630 3068 1631 3068 1612 3068 1630 3069 1612 3069 1611 3069 1631 3070 1632 3070 1613 3070 1631 3071 1613 3071 1612 3071 1632 3072 1633 3072 1614 3072 1632 3073 1614 3073 1613 3073 1633 3074 1634 3074 1615 3074 1633 3075 1615 3075 1614 3075 1634 3076 1635 3076 1616 3076 1634 3077 1616 3077 1615 3077 1635 3078 1636 3078 1617 3078 1635 3079 1617 3079 1616 3079 1636 3080 1637 3080 1618 3080 1636 3081 1618 3081 1617 3081 1637 3082 1638 3082 1619 3082 1637 3083 1619 3083 1618 3083 1638 3084 1639 3084 1620 3084 1638 3085 1620 3085 1619 3085 1639 3086 1640 3086 1621 3086 1639 3087 1621 3087 1620 3087 1640 3088 1641 3088 1622 3088 1640 3089 1622 3089 1621 3089 1641 3090 998 3090 1000 3090 1641 3091 1000 3091 1622 3091 1045 3092 1642 3092 1623 3092 1045 3093 1623 3093 1044 3093 1642 3094 1643 3094 1624 3094 1642 3095 1624 3095 1623 3095 1643 3096 1644 3096 1625 3096 1643 3097 1625 3097 1624 3097 1644 3098 1645 3098 1626 3098 1644 3099 1626 3099 1625 3099 1645 3100 1646 3100 1627 3100 1645 3101 1627 3101 1626 3101 1646 3102 1647 3102 1628 3102 1646 3103 1628 3103 1627 3103 1647 3104 1648 3104 1629 3104 1647 3105 1629 3105 1628 3105 1648 3106 1649 3106 1630 3106 1648 3107 1630 3107 1629 3107 1649 3108 1650 3108 1631 3108 1649 3109 1631 3109 1630 3109 1650 3110 1651 3110 1632 3110 1650 3111 1632 3111 1631 3111 1651 3112 1652 3112 1633 3112 1651 3113 1633 3113 1632 3113 1652 3114 1653 3114 1634 3114 1652 3115 1634 3115 1633 3115 1653 3116 1654 3116 1635 3116 1653 3117 1635 3117 1634 3117 1654 3118 1655 3118 1636 3118 1654 3119 1636 3119 1635 3119 1655 3120 1656 3120 1637 3120 1655 3121 1637 3121 1636 3121 1656 3122 1657 3122 1638 3122 1656 3123 1638 3123 1637 3123 1657 3124 1658 3124 1639 3124 1657 3125 1639 3125 1638 3125 1658 3126 1659 3126 1640 3126 1658 3127 1640 3127 1639 3127 1659 3128 1660 3128 1641 3128 1659 3129 1641 3129 1640 3129 1660 3130 996 3130 998 3130 1660 3131 998 3131 1641 3131 1046 3132 1661 3132 1642 3132 1046 3133 1642 3133 1045 3133 1661 3134 1662 3134 1643 3134 1661 3135 1643 3135 1642 3135 1662 3136 1663 3136 1644 3136 1662 3137 1644 3137 1643 3137 1663 3138 1664 3138 1645 3138 1663 3139 1645 3139 1644 3139 1664 3140 1665 3140 1646 3140 1664 3141 1646 3141 1645 3141 1665 3142 1666 3142 1647 3142 1665 3143 1647 3143 1646 3143 1666 3144 1667 3144 1648 3144 1666 3145 1648 3145 1647 3145 1667 3146 1668 3146 1649 3146 1667 3147 1649 3147 1648 3147 1668 3148 1669 3148 1650 3148 1668 3149 1650 3149 1649 3149 1669 3150 1670 3150 1651 3150 1669 3151 1651 3151 1650 3151 1670 3152 1671 3152 1652 3152 1670 3153 1652 3153 1651 3153 1671 3154 1672 3154 1653 3154 1671 3155 1653 3155 1652 3155 1672 3156 1673 3156 1654 3156 1672 3157 1654 3157 1653 3157 1673 3158 1674 3158 1655 3158 1673 3159 1655 3159 1654 3159 1674 3160 1675 3160 1656 3160 1674 3161 1656 3161 1655 3161 1675 3162 1676 3162 1657 3162 1675 3163 1657 3163 1656 3163 1676 3164 1677 3164 1658 3164 1676 3165 1658 3165 1657 3165 1677 3166 1678 3166 1659 3166 1677 3167 1659 3167 1658 3167 1678 3168 1679 3168 1660 3168 1678 3169 1660 3169 1659 3169 1679 3170 994 3170 996 3170 1679 3171 996 3171 1660 3171 1047 3172 1680 3172 1661 3172 1047 3173 1661 3173 1046 3173 1680 3174 1681 3174 1662 3174 1680 3175 1662 3175 1661 3175 1681 3176 1682 3176 1663 3176 1681 3177 1663 3177 1662 3177 1682 3178 1683 3178 1664 3178 1682 3179 1664 3179 1663 3179 1683 3180 1684 3180 1665 3180 1683 3181 1665 3181 1664 3181 1684 3182 1685 3182 1666 3182 1684 3183 1666 3183 1665 3183 1685 3184 1686 3184 1667 3184 1685 3185 1667 3185 1666 3185 1686 3186 1687 3186 1668 3186 1686 3187 1668 3187 1667 3187 1687 3188 1688 3188 1669 3188 1687 3189 1669 3189 1668 3189 1688 3190 1689 3190 1670 3190 1688 3191 1670 3191 1669 3191 1689 3192 1690 3192 1671 3192 1689 3193 1671 3193 1670 3193 1690 3194 1691 3194 1672 3194 1690 3195 1672 3195 1671 3195 1691 3196 1692 3196 1673 3196 1691 3197 1673 3197 1672 3197 1692 3198 1693 3198 1674 3198 1692 3199 1674 3199 1673 3199 1693 3200 1694 3200 1675 3200 1693 3201 1675 3201 1674 3201 1694 3202 1695 3202 1676 3202 1694 3203 1676 3203 1675 3203 1695 3204 1696 3204 1677 3204 1695 3205 1677 3205 1676 3205 1696 3206 1697 3206 1678 3206 1696 3207 1678 3207 1677 3207 1697 3208 1698 3208 1679 3208 1697 3209 1679 3209 1678 3209 1698 3210 992 3210 994 3210 1698 3211 994 3211 1679 3211 1048 3212 1699 3212 1680 3212 1048 3213 1680 3213 1047 3213 1699 3214 1700 3214 1681 3214 1699 3215 1681 3215 1680 3215 1700 3216 1701 3216 1682 3216 1700 3217 1682 3217 1681 3217 1701 3218 1702 3218 1683 3218 1701 3219 1683 3219 1682 3219 1702 3220 1703 3220 1684 3220 1702 3221 1684 3221 1683 3221 1703 3222 1704 3222 1685 3222 1703 3223 1685 3223 1684 3223 1704 3224 1705 3224 1686 3224 1704 3225 1686 3225 1685 3225 1705 3226 1706 3226 1687 3226 1705 3227 1687 3227 1686 3227 1706 3228 1707 3228 1688 3228 1706 3229 1688 3229 1687 3229 1707 3230 1708 3230 1689 3230 1707 3231 1689 3231 1688 3231 1708 3232 1709 3232 1690 3232 1708 3233 1690 3233 1689 3233 1709 3234 1710 3234 1691 3234 1709 3235 1691 3235 1690 3235 1710 3236 1711 3236 1692 3236 1710 3237 1692 3237 1691 3237 1711 3238 1712 3238 1693 3238 1711 3239 1693 3239 1692 3239 1712 3240 1713 3240 1694 3240 1712 3241 1694 3241 1693 3241 1713 3242 1714 3242 1695 3242 1713 3243 1695 3243 1694 3243 1714 3244 1715 3244 1696 3244 1714 3245 1696 3245 1695 3245 1715 3246 1716 3246 1697 3246 1715 3247 1697 3247 1696 3247 1716 3248 1717 3248 1698 3248 1716 3249 1698 3249 1697 3249 1717 3250 990 3250 992 3250 1717 3251 992 3251 1698 3251 1049 3252 1718 3252 1699 3252 1049 3253 1699 3253 1048 3253 1718 3254 1719 3254 1700 3254 1718 3255 1700 3255 1699 3255 1719 3256 1720 3256 1701 3256 1719 3257 1701 3257 1700 3257 1720 3258 1721 3258 1702 3258 1720 3259 1702 3259 1701 3259 1721 3260 1722 3260 1703 3260 1721 3261 1703 3261 1702 3261 1722 3262 1723 3262 1704 3262 1722 3263 1704 3263 1703 3263 1723 3264 1724 3264 1705 3264 1723 3265 1705 3265 1704 3265 1724 3266 1725 3266 1706 3266 1724 3267 1706 3267 1705 3267 1725 3268 1726 3268 1707 3268 1725 3269 1707 3269 1706 3269 1726 3270 1727 3270 1708 3270 1726 3271 1708 3271 1707 3271 1727 3272 1728 3272 1709 3272 1727 3273 1709 3273 1708 3273 1728 3274 1729 3274 1710 3274 1728 3275 1710 3275 1709 3275 1729 3276 1730 3276 1711 3276 1729 3277 1711 3277 1710 3277 1730 3278 1731 3278 1712 3278 1730 3279 1712 3279 1711 3279 1731 3280 1732 3280 1713 3280 1731 3281 1713 3281 1712 3281 1732 3282 1733 3282 1714 3282 1732 3283 1714 3283 1713 3283 1733 3284 1734 3284 1715 3284 1733 3285 1715 3285 1714 3285 1734 3286 1735 3286 1716 3286 1734 3287 1716 3287 1715 3287 1735 3288 1736 3288 1717 3288 1735 3289 1717 3289 1716 3289 1736 3290 988 3290 990 3290 1736 3291 990 3291 1717 3291 1050 3292 1737 3292 1718 3292 1050 3293 1718 3293 1049 3293 1737 3294 1738 3294 1719 3294 1737 3295 1719 3295 1718 3295 1738 3296 1739 3296 1720 3296 1738 3297 1720 3297 1719 3297 1739 3298 1740 3298 1721 3298 1739 3299 1721 3299 1720 3299 1740 3300 1741 3300 1722 3300 1740 3301 1722 3301 1721 3301 1741 3302 1742 3302 1723 3302 1741 3303 1723 3303 1722 3303 1742 3304 1743 3304 1724 3304 1742 3305 1724 3305 1723 3305 1743 3306 1744 3306 1725 3306 1743 3307 1725 3307 1724 3307 1744 3308 1745 3308 1726 3308 1744 3309 1726 3309 1725 3309 1745 3310 1746 3310 1727 3310 1745 3311 1727 3311 1726 3311 1746 3312 1747 3312 1728 3312 1746 3313 1728 3313 1727 3313 1747 3314 1748 3314 1729 3314 1747 3315 1729 3315 1728 3315 1748 3316 1749 3316 1730 3316 1748 3317 1730 3317 1729 3317 1749 3318 1750 3318 1731 3318 1749 3319 1731 3319 1730 3319 1750 3320 1751 3320 1732 3320 1750 3321 1732 3321 1731 3321 1751 3322 1752 3322 1733 3322 1751 3323 1733 3323 1732 3323 1752 3324 1753 3324 1734 3324 1752 3325 1734 3325 1733 3325 1753 3326 1754 3326 1735 3326 1753 3327 1735 3327 1734 3327 1754 3328 1755 3328 1736 3328 1754 3329 1736 3329 1735 3329 1755 3330 986 3330 988 3330 1755 3331 988 3331 1736 3331 1051 3332 1756 3332 1737 3332 1051 3333 1737 3333 1050 3333 1756 3334 1757 3334 1738 3334 1756 3335 1738 3335 1737 3335 1757 3336 1758 3336 1739 3336 1757 3337 1739 3337 1738 3337 1758 3338 1759 3338 1740 3338 1758 3339 1740 3339 1739 3339 1759 3340 1760 3340 1741 3340 1759 3341 1741 3341 1740 3341 1760 3342 1761 3342 1742 3342 1760 3343 1742 3343 1741 3343 1761 3344 1762 3344 1743 3344 1761 3345 1743 3345 1742 3345 1762 3346 1763 3346 1744 3346 1762 3347 1744 3347 1743 3347 1763 3348 1764 3348 1745 3348 1763 3349 1745 3349 1744 3349 1764 3350 1765 3350 1746 3350 1764 3351 1746 3351 1745 3351 1765 3352 1766 3352 1747 3352 1765 3353 1747 3353 1746 3353 1766 3354 1767 3354 1748 3354 1766 3355 1748 3355 1747 3355 1767 3356 1768 3356 1749 3356 1767 3357 1749 3357 1748 3357 1768 3358 1769 3358 1750 3358 1768 3359 1750 3359 1749 3359 1769 3360 1770 3360 1751 3360 1769 3361 1751 3361 1750 3361 1770 3362 1771 3362 1752 3362 1770 3363 1752 3363 1751 3363 1771 3364 1772 3364 1753 3364 1771 3365 1753 3365 1752 3365 1772 3366 1773 3366 1754 3366 1772 3367 1754 3367 1753 3367 1773 3368 1774 3368 1755 3368 1773 3369 1755 3369 1754 3369 1774 3370 984 3370 986 3370 1774 3371 986 3371 1755 3371 1052 3372 1775 3372 1756 3372 1052 3373 1756 3373 1051 3373 1775 3374 1776 3374 1757 3374 1775 3375 1757 3375 1756 3375 1776 3376 1777 3376 1758 3376 1776 3377 1758 3377 1757 3377 1777 3378 1778 3378 1759 3378 1777 3379 1759 3379 1758 3379 1778 3380 1779 3380 1760 3380 1778 3381 1760 3381 1759 3381 1779 3382 1780 3382 1761 3382 1779 3383 1761 3383 1760 3383 1780 3384 1781 3384 1762 3384 1780 3385 1762 3385 1761 3385 1781 3386 1782 3386 1763 3386 1781 3387 1763 3387 1762 3387 1782 3388 1783 3388 1764 3388 1782 3389 1764 3389 1763 3389 1783 3390 1784 3390 1765 3390 1783 3391 1765 3391 1764 3391 1784 3392 1785 3392 1766 3392 1784 3393 1766 3393 1765 3393 1785 3394 1786 3394 1767 3394 1785 3395 1767 3395 1766 3395 1786 3396 1787 3396 1768 3396 1786 3397 1768 3397 1767 3397 1787 3398 1788 3398 1769 3398 1787 3399 1769 3399 1768 3399 1788 3400 1789 3400 1770 3400 1788 3401 1770 3401 1769 3401 1789 3402 1790 3402 1771 3402 1789 3403 1771 3403 1770 3403 1790 3404 1791 3404 1772 3404 1790 3405 1772 3405 1771 3405 1791 3406 1792 3406 1773 3406 1791 3407 1773 3407 1772 3407 1792 3408 1793 3408 1774 3408 1792 3409 1774 3409 1773 3409 1793 3410 982 3410 984 3410 1793 3411 984 3411 1774 3411 1053 3412 1794 3412 1775 3412 1053 3413 1775 3413 1052 3413 1794 3414 1795 3414 1776 3414 1794 3415 1776 3415 1775 3415 1795 3416 1796 3416 1777 3416 1795 3417 1777 3417 1776 3417 1796 3418 1797 3418 1778 3418 1796 3419 1778 3419 1777 3419 1797 3420 1798 3420 1779 3420 1797 3421 1779 3421 1778 3421 1798 3422 1799 3422 1780 3422 1798 3423 1780 3423 1779 3423 1799 3424 1800 3424 1781 3424 1799 3425 1781 3425 1780 3425 1800 3426 1801 3426 1782 3426 1800 3427 1782 3427 1781 3427 1801 3428 1802 3428 1783 3428 1801 3429 1783 3429 1782 3429 1802 3430 1803 3430 1784 3430 1802 3431 1784 3431 1783 3431 1803 3432 1804 3432 1785 3432 1803 3433 1785 3433 1784 3433 1804 3434 1805 3434 1786 3434 1804 3435 1786 3435 1785 3435 1805 3436 1806 3436 1787 3436 1805 3437 1787 3437 1786 3437 1806 3438 1807 3438 1788 3438 1806 3439 1788 3439 1787 3439 1807 3440 1808 3440 1789 3440 1807 3441 1789 3441 1788 3441 1808 3442 1809 3442 1790 3442 1808 3443 1790 3443 1789 3443 1809 3444 1810 3444 1791 3444 1809 3445 1791 3445 1790 3445 1810 3446 1811 3446 1792 3446 1810 3447 1792 3447 1791 3447 1811 3448 1812 3448 1793 3448 1811 3449 1793 3449 1792 3449 1812 3450 980 3450 982 3450 1812 3451 982 3451 1793 3451 7 3452 1813 3452 1794 3452 7 3453 1794 3453 1053 3453 1813 3454 1814 3454 1795 3454 1813 3455 1795 3455 1794 3455 1814 3456 1815 3456 1796 3456 1814 3457 1796 3457 1795 3457 1815 3458 1816 3458 1797 3458 1815 3459 1797 3459 1796 3459 1816 3460 1817 3460 1798 3460 1816 3461 1798 3461 1797 3461 1817 3462 1818 3462 1799 3462 1817 3463 1799 3463 1798 3463 1818 3464 1819 3464 1800 3464 1818 3465 1800 3465 1799 3465 1819 3466 1820 3466 1801 3466 1819 3467 1801 3467 1800 3467 1820 3468 1821 3468 1802 3468 1820 3469 1802 3469 1801 3469 1821 3470 1822 3470 1803 3470 1821 3471 1803 3471 1802 3471 1822 3472 1823 3472 1804 3472 1822 3473 1804 3473 1803 3473 1823 3474 1824 3474 1805 3474 1823 3475 1805 3475 1804 3475 1824 3476 1825 3476 1806 3476 1824 3477 1806 3477 1805 3477 1825 3478 1826 3478 1807 3478 1825 3479 1807 3479 1806 3479 1826 3480 1827 3480 1808 3480 1826 3481 1808 3481 1807 3481 1827 3482 1828 3482 1809 3482 1827 3483 1809 3483 1808 3483 1828 3484 1829 3484 1810 3484 1828 3485 1810 3485 1809 3485 1829 3486 1830 3486 1811 3486 1829 3487 1811 3487 1810 3487 1830 3488 1831 3488 1812 3488 1830 3489 1812 3489 1811 3489 1831 3490 978 3490 980 3490 1831 3491 980 3491 1812 3491 6 3492 1832 3492 1813 3492 6 3493 1813 3493 7 3493 1832 3494 1833 3494 1814 3494 1832 3495 1814 3495 1813 3495 1833 3496 1834 3496 1815 3496 1833 3497 1815 3497 1814 3497 1834 3498 1835 3498 1816 3498 1834 3499 1816 3499 1815 3499 1835 3500 1836 3500 1817 3500 1835 3501 1817 3501 1816 3501 1836 3502 1837 3502 1818 3502 1836 3503 1818 3503 1817 3503 1837 3504 1838 3504 1819 3504 1837 3505 1819 3505 1818 3505 1838 3506 1839 3506 1820 3506 1838 3507 1820 3507 1819 3507 1839 3508 1840 3508 1821 3508 1839 3509 1821 3509 1820 3509 1840 3510 1841 3510 1822 3510 1840 3511 1822 3511 1821 3511 1841 3512 1842 3512 1823 3512 1841 3513 1823 3513 1822 3513 1842 3514 1843 3514 1824 3514 1842 3515 1824 3515 1823 3515 1843 3516 1844 3516 1825 3516 1843 3517 1825 3517 1824 3517 1844 3518 1845 3518 1826 3518 1844 3519 1826 3519 1825 3519 1845 3520 1846 3520 1827 3520 1845 3521 1827 3521 1826 3521 1846 3522 1847 3522 1828 3522 1846 3523 1828 3523 1827 3523 1847 3524 1848 3524 1829 3524 1847 3525 1829 3525 1828 3525 1848 3526 1849 3526 1830 3526 1848 3527 1830 3527 1829 3527 1849 3528 1850 3528 1831 3528 1849 3529 1831 3529 1830 3529 1850 3530 11 3530 978 3530 1850 3531 978 3531 1831 3531 60 3532 1851 3532 1852 3532 60 3533 1852 3533 13 3533 1851 3534 1853 3534 1854 3534 1851 3535 1854 3535 1852 3535 1853 3536 1855 3536 1856 3536 1853 3537 1856 3537 1854 3537 1855 3538 1857 3538 1858 3538 1855 3539 1858 3539 1856 3539 1857 3540 1859 3540 1860 3540 1857 3541 1860 3541 1858 3541 1859 3542 1861 3542 1862 3542 1859 3543 1862 3543 1860 3543 1861 3544 1863 3544 1864 3544 1861 3545 1864 3545 1862 3545 1863 3546 1865 3546 1866 3546 1863 3547 1866 3547 1864 3547 1865 3548 1867 3548 1868 3548 1865 3549 1868 3549 1866 3549 1867 3550 1869 3550 1870 3550 1867 3551 1870 3551 1868 3551 1869 3552 1871 3552 1872 3552 1869 3553 1872 3553 1870 3553 1871 3554 1873 3554 1874 3554 1871 3555 1874 3555 1872 3555 1873 3556 1875 3556 1876 3556 1873 3557 1876 3557 1874 3557 1875 3558 1877 3558 1878 3558 1875 3559 1878 3559 1876 3559 1877 3560 1879 3560 1880 3560 1877 3561 1880 3561 1878 3561 1879 3562 1881 3562 1882 3562 1879 3563 1882 3563 1880 3563 1881 3564 1883 3564 1884 3564 1881 3565 1884 3565 1882 3565 1883 3566 1885 3566 1886 3566 1883 3567 1886 3567 1884 3567 1885 3568 1887 3568 1888 3568 1885 3569 1888 3569 1886 3569 1887 3570 179 3570 0 3570 1887 3571 0 3571 1888 3571 58 3572 1889 3572 1851 3572 58 3573 1851 3573 60 3573 1889 3574 1890 3574 1853 3574 1889 3575 1853 3575 1851 3575 1890 3576 1891 3576 1855 3576 1890 3577 1855 3577 1853 3577 1891 3578 1892 3578 1857 3578 1891 3579 1857 3579 1855 3579 1892 3580 1893 3580 1859 3580 1892 3581 1859 3581 1857 3581 1893 3582 1894 3582 1861 3582 1893 3583 1861 3583 1859 3583 1894 3584 1895 3584 1863 3584 1894 3585 1863 3585 1861 3585 1895 3586 1896 3586 1865 3586 1895 3587 1865 3587 1863 3587 1896 3588 1897 3588 1867 3588 1896 3589 1867 3589 1865 3589 1897 3590 1898 3590 1869 3590 1897 3591 1869 3591 1867 3591 1898 3592 1899 3592 1871 3592 1898 3593 1871 3593 1869 3593 1899 3594 1900 3594 1873 3594 1899 3595 1873 3595 1871 3595 1900 3596 1901 3596 1875 3596 1900 3597 1875 3597 1873 3597 1901 3598 1902 3598 1877 3598 1901 3599 1877 3599 1875 3599 1902 3600 1903 3600 1879 3600 1902 3601 1879 3601 1877 3601 1903 3602 1904 3602 1881 3602 1903 3603 1881 3603 1879 3603 1904 3604 1905 3604 1883 3604 1904 3605 1883 3605 1881 3605 1905 3606 1906 3606 1885 3606 1905 3607 1885 3607 1883 3607 1906 3608 1907 3608 1887 3608 1906 3609 1887 3609 1885 3609 1907 3610 177 3610 179 3610 1907 3611 179 3611 1887 3611 56 3612 1908 3612 1889 3612 56 3613 1889 3613 58 3613 1908 3614 1909 3614 1890 3614 1908 3615 1890 3615 1889 3615 1909 3616 1910 3616 1891 3616 1909 3617 1891 3617 1890 3617 1910 3618 1911 3618 1892 3618 1910 3619 1892 3619 1891 3619 1911 3620 1912 3620 1893 3620 1911 3621 1893 3621 1892 3621 1912 3622 1913 3622 1894 3622 1912 3623 1894 3623 1893 3623 1913 3624 1914 3624 1895 3624 1913 3625 1895 3625 1894 3625 1914 3626 1915 3626 1896 3626 1914 3627 1896 3627 1895 3627 1915 3628 1916 3628 1897 3628 1915 3629 1897 3629 1896 3629 1916 3630 1917 3630 1898 3630 1916 3631 1898 3631 1897 3631 1917 3632 1918 3632 1899 3632 1917 3633 1899 3633 1898 3633 1918 3634 1919 3634 1900 3634 1918 3635 1900 3635 1899 3635 1919 3636 1920 3636 1901 3636 1919 3637 1901 3637 1900 3637 1920 3638 1921 3638 1902 3638 1920 3639 1902 3639 1901 3639 1921 3640 1922 3640 1903 3640 1921 3641 1903 3641 1902 3641 1922 3642 1923 3642 1904 3642 1922 3643 1904 3643 1903 3643 1923 3644 1924 3644 1905 3644 1923 3645 1905 3645 1904 3645 1924 3646 1925 3646 1906 3646 1924 3647 1906 3647 1905 3647 1925 3648 1926 3648 1907 3648 1925 3649 1907 3649 1906 3649 1926 3650 175 3650 177 3650 1926 3651 177 3651 1907 3651 54 3652 1927 3652 1908 3652 54 3653 1908 3653 56 3653 1927 3654 1928 3654 1909 3654 1927 3655 1909 3655 1908 3655 1928 3656 1929 3656 1910 3656 1928 3657 1910 3657 1909 3657 1929 3658 1930 3658 1911 3658 1929 3659 1911 3659 1910 3659 1930 3660 1931 3660 1912 3660 1930 3661 1912 3661 1911 3661 1931 3662 1932 3662 1913 3662 1931 3663 1913 3663 1912 3663 1932 3664 1933 3664 1914 3664 1932 3665 1914 3665 1913 3665 1933 3666 1934 3666 1915 3666 1933 3667 1915 3667 1914 3667 1934 3668 1935 3668 1916 3668 1934 3669 1916 3669 1915 3669 1935 3670 1936 3670 1917 3670 1935 3671 1917 3671 1916 3671 1936 3672 1937 3672 1918 3672 1936 3673 1918 3673 1917 3673 1937 3674 1938 3674 1919 3674 1937 3675 1919 3675 1918 3675 1938 3676 1939 3676 1920 3676 1938 3677 1920 3677 1919 3677 1939 3678 1940 3678 1921 3678 1939 3679 1921 3679 1920 3679 1940 3680 1941 3680 1922 3680 1940 3681 1922 3681 1921 3681 1941 3682 1942 3682 1923 3682 1941 3683 1923 3683 1922 3683 1942 3684 1943 3684 1924 3684 1942 3685 1924 3685 1923 3685 1943 3686 1944 3686 1925 3686 1943 3687 1925 3687 1924 3687 1944 3688 1945 3688 1926 3688 1944 3689 1926 3689 1925 3689 1945 3690 173 3690 175 3690 1945 3691 175 3691 1926 3691 52 3692 1946 3692 1927 3692 52 3693 1927 3693 54 3693 1946 3694 1947 3694 1928 3694 1946 3695 1928 3695 1927 3695 1947 3696 1948 3696 1929 3696 1947 3697 1929 3697 1928 3697 1948 3698 1949 3698 1930 3698 1948 3699 1930 3699 1929 3699 1949 3700 1950 3700 1931 3700 1949 3701 1931 3701 1930 3701 1950 3702 1951 3702 1932 3702 1950 3703 1932 3703 1931 3703 1951 3704 1952 3704 1933 3704 1951 3705 1933 3705 1932 3705 1952 3706 1953 3706 1934 3706 1952 3707 1934 3707 1933 3707 1953 3708 1954 3708 1935 3708 1953 3709 1935 3709 1934 3709 1954 3710 1955 3710 1936 3710 1954 3711 1936 3711 1935 3711 1955 3712 1956 3712 1937 3712 1955 3713 1937 3713 1936 3713 1956 3714 1957 3714 1938 3714 1956 3715 1938 3715 1937 3715 1957 3716 1958 3716 1939 3716 1957 3717 1939 3717 1938 3717 1958 3718 1959 3718 1940 3718 1958 3719 1940 3719 1939 3719 1959 3720 1960 3720 1941 3720 1959 3721 1941 3721 1940 3721 1960 3722 1961 3722 1942 3722 1960 3723 1942 3723 1941 3723 1961 3724 1962 3724 1943 3724 1961 3725 1943 3725 1942 3725 1962 3726 1963 3726 1944 3726 1962 3727 1944 3727 1943 3727 1963 3728 1964 3728 1945 3728 1963 3729 1945 3729 1944 3729 1964 3730 171 3730 173 3730 1964 3731 173 3731 1945 3731 50 3732 1965 3732 1946 3732 50 3733 1946 3733 52 3733 1965 3734 1966 3734 1947 3734 1965 3735 1947 3735 1946 3735 1966 3736 1967 3736 1948 3736 1966 3737 1948 3737 1947 3737 1967 3738 1968 3738 1949 3738 1967 3739 1949 3739 1948 3739 1968 3740 1969 3740 1950 3740 1968 3741 1950 3741 1949 3741 1969 3742 1970 3742 1951 3742 1969 3743 1951 3743 1950 3743 1970 3744 1971 3744 1952 3744 1970 3745 1952 3745 1951 3745 1971 3746 1972 3746 1953 3746 1971 3747 1953 3747 1952 3747 1972 3748 1973 3748 1954 3748 1972 3749 1954 3749 1953 3749 1973 3750 1974 3750 1955 3750 1973 3751 1955 3751 1954 3751 1974 3752 1975 3752 1956 3752 1974 3753 1956 3753 1955 3753 1975 3754 1976 3754 1957 3754 1975 3755 1957 3755 1956 3755 1976 3756 1977 3756 1958 3756 1976 3757 1958 3757 1957 3757 1977 3758 1978 3758 1959 3758 1977 3759 1959 3759 1958 3759 1978 3760 1979 3760 1960 3760 1978 3761 1960 3761 1959 3761 1979 3762 1980 3762 1961 3762 1979 3763 1961 3763 1960 3763 1980 3764 1981 3764 1962 3764 1980 3765 1962 3765 1961 3765 1981 3766 1982 3766 1963 3766 1981 3767 1963 3767 1962 3767 1982 3768 1983 3768 1964 3768 1982 3769 1964 3769 1963 3769 1983 3770 169 3770 171 3770 1983 3771 171 3771 1964 3771 48 3772 1984 3772 1965 3772 48 3773 1965 3773 50 3773 1984 3774 1985 3774 1966 3774 1984 3775 1966 3775 1965 3775 1985 3776 1986 3776 1967 3776 1985 3777 1967 3777 1966 3777 1986 3778 1987 3778 1968 3778 1986 3779 1968 3779 1967 3779 1987 3780 1988 3780 1969 3780 1987 3781 1969 3781 1968 3781 1988 3782 1989 3782 1970 3782 1988 3783 1970 3783 1969 3783 1989 3784 1990 3784 1971 3784 1989 3785 1971 3785 1970 3785 1990 3786 1991 3786 1972 3786 1990 3787 1972 3787 1971 3787 1991 3788 1992 3788 1973 3788 1991 3789 1973 3789 1972 3789 1992 3790 1993 3790 1974 3790 1992 3791 1974 3791 1973 3791 1993 3792 1994 3792 1975 3792 1993 3793 1975 3793 1974 3793 1994 3794 1995 3794 1976 3794 1994 3795 1976 3795 1975 3795 1995 3796 1996 3796 1977 3796 1995 3797 1977 3797 1976 3797 1996 3798 1997 3798 1978 3798 1996 3799 1978 3799 1977 3799 1997 3800 1998 3800 1979 3800 1997 3801 1979 3801 1978 3801 1998 3802 1999 3802 1980 3802 1998 3803 1980 3803 1979 3803 1999 3804 2000 3804 1981 3804 1999 3805 1981 3805 1980 3805 2000 3806 2001 3806 1982 3806 2000 3807 1982 3807 1981 3807 2001 3808 2002 3808 1983 3808 2001 3809 1983 3809 1982 3809 2002 3810 167 3810 169 3810 2002 3811 169 3811 1983 3811 46 3812 2003 3812 1984 3812 46 3813 1984 3813 48 3813 2003 3814 2004 3814 1985 3814 2003 3815 1985 3815 1984 3815 2004 3816 2005 3816 1986 3816 2004 3817 1986 3817 1985 3817 2005 3818 2006 3818 1987 3818 2005 3819 1987 3819 1986 3819 2006 3820 2007 3820 1988 3820 2006 3821 1988 3821 1987 3821 2007 3822 2008 3822 1989 3822 2007 3823 1989 3823 1988 3823 2008 3824 2009 3824 1990 3824 2008 3825 1990 3825 1989 3825 2009 3826 2010 3826 1991 3826 2009 3827 1991 3827 1990 3827 2010 3828 2011 3828 1992 3828 2010 3829 1992 3829 1991 3829 2011 3830 2012 3830 1993 3830 2011 3831 1993 3831 1992 3831 2012 3832 2013 3832 1994 3832 2012 3833 1994 3833 1993 3833 2013 3834 2014 3834 1995 3834 2013 3835 1995 3835 1994 3835 2014 3836 2015 3836 1996 3836 2014 3837 1996 3837 1995 3837 2015 3838 2016 3838 1997 3838 2015 3839 1997 3839 1996 3839 2016 3840 2017 3840 1998 3840 2016 3841 1998 3841 1997 3841 2017 3842 2018 3842 1999 3842 2017 3843 1999 3843 1998 3843 2018 3844 2019 3844 2000 3844 2018 3845 2000 3845 1999 3845 2019 3846 2020 3846 2001 3846 2019 3847 2001 3847 2000 3847 2020 3848 2021 3848 2002 3848 2020 3849 2002 3849 2001 3849 2021 3850 165 3850 167 3850 2021 3851 167 3851 2002 3851 44 3852 2022 3852 2003 3852 44 3853 2003 3853 46 3853 2022 3854 2023 3854 2004 3854 2022 3855 2004 3855 2003 3855 2023 3856 2024 3856 2005 3856 2023 3857 2005 3857 2004 3857 2024 3858 2025 3858 2006 3858 2024 3859 2006 3859 2005 3859 2025 3860 2026 3860 2007 3860 2025 3861 2007 3861 2006 3861 2026 3862 2027 3862 2008 3862 2026 3863 2008 3863 2007 3863 2027 3864 2028 3864 2009 3864 2027 3865 2009 3865 2008 3865 2028 3866 2029 3866 2010 3866 2028 3867 2010 3867 2009 3867 2029 3868 2030 3868 2011 3868 2029 3869 2011 3869 2010 3869 2030 3870 2031 3870 2012 3870 2030 3871 2012 3871 2011 3871 2031 3872 2032 3872 2013 3872 2031 3873 2013 3873 2012 3873 2032 3874 2033 3874 2014 3874 2032 3875 2014 3875 2013 3875 2033 3876 2034 3876 2015 3876 2033 3877 2015 3877 2014 3877 2034 3878 2035 3878 2016 3878 2034 3879 2016 3879 2015 3879 2035 3880 2036 3880 2017 3880 2035 3881 2017 3881 2016 3881 2036 3882 2037 3882 2018 3882 2036 3883 2018 3883 2017 3883 2037 3884 2038 3884 2019 3884 2037 3885 2019 3885 2018 3885 2038 3886 2039 3886 2020 3886 2038 3887 2020 3887 2019 3887 2039 3888 2040 3888 2021 3888 2039 3889 2021 3889 2020 3889 2040 3890 163 3890 165 3890 2040 3891 165 3891 2021 3891 42 3892 2041 3892 2022 3892 42 3893 2022 3893 44 3893 2041 3894 2042 3894 2023 3894 2041 3895 2023 3895 2022 3895 2042 3896 2043 3896 2024 3896 2042 3897 2024 3897 2023 3897 2043 3898 2044 3898 2025 3898 2043 3899 2025 3899 2024 3899 2044 3900 2045 3900 2026 3900 2044 3901 2026 3901 2025 3901 2045 3902 2046 3902 2027 3902 2045 3903 2027 3903 2026 3903 2046 3904 2047 3904 2028 3904 2046 3905 2028 3905 2027 3905 2047 3906 2048 3906 2029 3906 2047 3907 2029 3907 2028 3907 2048 3908 2049 3908 2030 3908 2048 3909 2030 3909 2029 3909 2049 3910 2050 3910 2031 3910 2049 3911 2031 3911 2030 3911 2050 3912 2051 3912 2032 3912 2050 3913 2032 3913 2031 3913 2051 3914 2052 3914 2033 3914 2051 3915 2033 3915 2032 3915 2052 3916 2053 3916 2034 3916 2052 3917 2034 3917 2033 3917 2053 3918 2054 3918 2035 3918 2053 3919 2035 3919 2034 3919 2054 3920 2055 3920 2036 3920 2054 3921 2036 3921 2035 3921 2055 3922 2056 3922 2037 3922 2055 3923 2037 3923 2036 3923 2056 3924 2057 3924 2038 3924 2056 3925 2038 3925 2037 3925 2057 3926 2058 3926 2039 3926 2057 3927 2039 3927 2038 3927 2058 3928 2059 3928 2040 3928 2058 3929 2040 3929 2039 3929 2059 3930 161 3930 163 3930 2059 3931 163 3931 2040 3931 40 3932 2060 3932 2041 3932 40 3933 2041 3933 42 3933 2060 3934 2061 3934 2042 3934 2060 3935 2042 3935 2041 3935 2061 3936 2062 3936 2043 3936 2061 3937 2043 3937 2042 3937 2062 3938 2063 3938 2044 3938 2062 3939 2044 3939 2043 3939 2063 3940 2064 3940 2045 3940 2063 3941 2045 3941 2044 3941 2064 3942 2065 3942 2046 3942 2064 3943 2046 3943 2045 3943 2065 3944 2066 3944 2047 3944 2065 3945 2047 3945 2046 3945 2066 3946 2067 3946 2048 3946 2066 3947 2048 3947 2047 3947 2067 3948 2068 3948 2049 3948 2067 3949 2049 3949 2048 3949 2068 3950 2069 3950 2050 3950 2068 3951 2050 3951 2049 3951 2069 3952 2070 3952 2051 3952 2069 3953 2051 3953 2050 3953 2070 3954 2071 3954 2052 3954 2070 3955 2052 3955 2051 3955 2071 3956 2072 3956 2053 3956 2071 3957 2053 3957 2052 3957 2072 3958 2073 3958 2054 3958 2072 3959 2054 3959 2053 3959 2073 3960 2074 3960 2055 3960 2073 3961 2055 3961 2054 3961 2074 3962 2075 3962 2056 3962 2074 3963 2056 3963 2055 3963 2075 3964 2076 3964 2057 3964 2075 3965 2057 3965 2056 3965 2076 3966 2077 3966 2058 3966 2076 3967 2058 3967 2057 3967 2077 3968 2078 3968 2059 3968 2077 3969 2059 3969 2058 3969 2078 3970 159 3970 161 3970 2078 3971 161 3971 2059 3971 38 3972 2079 3972 2060 3972 38 3973 2060 3973 40 3973 2079 3974 2080 3974 2061 3974 2079 3975 2061 3975 2060 3975 2080 3976 2081 3976 2062 3976 2080 3977 2062 3977 2061 3977 2081 3978 2082 3978 2063 3978 2081 3979 2063 3979 2062 3979 2082 3980 2083 3980 2064 3980 2082 3981 2064 3981 2063 3981 2083 3982 2084 3982 2065 3982 2083 3983 2065 3983 2064 3983 2084 3984 2085 3984 2066 3984 2084 3985 2066 3985 2065 3985 2085 3986 2086 3986 2067 3986 2085 3987 2067 3987 2066 3987 2086 3988 2087 3988 2068 3988 2086 3989 2068 3989 2067 3989 2087 3990 2088 3990 2069 3990 2087 3991 2069 3991 2068 3991 2088 3992 2089 3992 2070 3992 2088 3993 2070 3993 2069 3993 2089 3994 2090 3994 2071 3994 2089 3995 2071 3995 2070 3995 2090 3996 2091 3996 2072 3996 2090 3997 2072 3997 2071 3997 2091 3998 2092 3998 2073 3998 2091 3999 2073 3999 2072 3999 2092 4000 2093 4000 2074 4000 2092 4001 2074 4001 2073 4001 2093 4002 2094 4002 2075 4002 2093 4003 2075 4003 2074 4003 2094 4004 2095 4004 2076 4004 2094 4005 2076 4005 2075 4005 2095 4006 2096 4006 2077 4006 2095 4007 2077 4007 2076 4007 2096 4008 2097 4008 2078 4008 2096 4009 2078 4009 2077 4009 2097 4010 157 4010 159 4010 2097 4011 159 4011 2078 4011 36 4012 2098 4012 2079 4012 36 4013 2079 4013 38 4013 2098 4014 2099 4014 2080 4014 2098 4015 2080 4015 2079 4015 2099 4016 2100 4016 2081 4016 2099 4017 2081 4017 2080 4017 2100 4018 2101 4018 2082 4018 2100 4019 2082 4019 2081 4019 2101 4020 2102 4020 2083 4020 2101 4021 2083 4021 2082 4021 2102 4022 2103 4022 2084 4022 2102 4023 2084 4023 2083 4023 2103 4024 2104 4024 2085 4024 2103 4025 2085 4025 2084 4025 2104 4026 2105 4026 2086 4026 2104 4027 2086 4027 2085 4027 2105 4028 2106 4028 2087 4028 2105 4029 2087 4029 2086 4029 2106 4030 2107 4030 2088 4030 2106 4031 2088 4031 2087 4031 2107 4032 2108 4032 2089 4032 2107 4033 2089 4033 2088 4033 2108 4034 2109 4034 2090 4034 2108 4035 2090 4035 2089 4035 2109 4036 2110 4036 2091 4036 2109 4037 2091 4037 2090 4037 2110 4038 2111 4038 2092 4038 2110 4039 2092 4039 2091 4039 2111 4040 2112 4040 2093 4040 2111 4041 2093 4041 2092 4041 2112 4042 2113 4042 2094 4042 2112 4043 2094 4043 2093 4043 2113 4044 2114 4044 2095 4044 2113 4045 2095 4045 2094 4045 2114 4046 2115 4046 2096 4046 2114 4047 2096 4047 2095 4047 2115 4048 2116 4048 2097 4048 2115 4049 2097 4049 2096 4049 2116 4050 155 4050 157 4050 2116 4051 157 4051 2097 4051 34 4052 2117 4052 2098 4052 34 4053 2098 4053 36 4053 2117 4054 2118 4054 2099 4054 2117 4055 2099 4055 2098 4055 2118 4056 2119 4056 2100 4056 2118 4057 2100 4057 2099 4057 2119 4058 2120 4058 2101 4058 2119 4059 2101 4059 2100 4059 2120 4060 2121 4060 2102 4060 2120 4061 2102 4061 2101 4061 2121 4062 2122 4062 2103 4062 2121 4063 2103 4063 2102 4063 2122 4064 2123 4064 2104 4064 2122 4065 2104 4065 2103 4065 2123 4066 2124 4066 2105 4066 2123 4067 2105 4067 2104 4067 2124 4068 2125 4068 2106 4068 2124 4069 2106 4069 2105 4069 2125 4070 2126 4070 2107 4070 2125 4071 2107 4071 2106 4071 2126 4072 2127 4072 2108 4072 2126 4073 2108 4073 2107 4073 2127 4074 2128 4074 2109 4074 2127 4075 2109 4075 2108 4075 2128 4076 2129 4076 2110 4076 2128 4077 2110 4077 2109 4077 2129 4078 2130 4078 2111 4078 2129 4079 2111 4079 2110 4079 2130 4080 2131 4080 2112 4080 2130 4081 2112 4081 2111 4081 2131 4082 2132 4082 2113 4082 2131 4083 2113 4083 2112 4083 2132 4084 2133 4084 2114 4084 2132 4085 2114 4085 2113 4085 2133 4086 2134 4086 2115 4086 2133 4087 2115 4087 2114 4087 2134 4088 2135 4088 2116 4088 2134 4089 2116 4089 2115 4089 2135 4090 153 4090 155 4090 2135 4091 155 4091 2116 4091 32 4092 2136 4092 2117 4092 32 4093 2117 4093 34 4093 2136 4094 2137 4094 2118 4094 2136 4095 2118 4095 2117 4095 2137 4096 2138 4096 2119 4096 2137 4097 2119 4097 2118 4097 2138 4098 2139 4098 2120 4098 2138 4099 2120 4099 2119 4099 2139 4100 2140 4100 2121 4100 2139 4101 2121 4101 2120 4101 2140 4102 2141 4102 2122 4102 2140 4103 2122 4103 2121 4103 2141 4104 2142 4104 2123 4104 2141 4105 2123 4105 2122 4105 2142 4106 2143 4106 2124 4106 2142 4107 2124 4107 2123 4107 2143 4108 2144 4108 2125 4108 2143 4109 2125 4109 2124 4109 2144 4110 2145 4110 2126 4110 2144 4111 2126 4111 2125 4111 2145 4112 2146 4112 2127 4112 2145 4113 2127 4113 2126 4113 2146 4114 2147 4114 2128 4114 2146 4115 2128 4115 2127 4115 2147 4116 2148 4116 2129 4116 2147 4117 2129 4117 2128 4117 2148 4118 2149 4118 2130 4118 2148 4119 2130 4119 2129 4119 2149 4120 2150 4120 2131 4120 2149 4121 2131 4121 2130 4121 2150 4122 2151 4122 2132 4122 2150 4123 2132 4123 2131 4123 2151 4124 2152 4124 2133 4124 2151 4125 2133 4125 2132 4125 2152 4126 2153 4126 2134 4126 2152 4127 2134 4127 2133 4127 2153 4128 2154 4128 2135 4128 2153 4129 2135 4129 2134 4129 2154 4130 151 4130 153 4130 2154 4131 153 4131 2135 4131 30 4132 2155 4132 2136 4132 30 4133 2136 4133 32 4133 2155 4134 2156 4134 2137 4134 2155 4135 2137 4135 2136 4135 2156 4136 2157 4136 2138 4136 2156 4137 2138 4137 2137 4137 2157 4138 2158 4138 2139 4138 2157 4139 2139 4139 2138 4139 2158 4140 2159 4140 2140 4140 2158 4141 2140 4141 2139 4141 2159 4142 2160 4142 2141 4142 2159 4143 2141 4143 2140 4143 2160 4144 2161 4144 2142 4144 2160 4145 2142 4145 2141 4145 2161 4146 2162 4146 2143 4146 2161 4147 2143 4147 2142 4147 2162 4148 2163 4148 2144 4148 2162 4149 2144 4149 2143 4149 2163 4150 2164 4150 2145 4150 2163 4151 2145 4151 2144 4151 2164 4152 2165 4152 2146 4152 2164 4153 2146 4153 2145 4153 2165 4154 2166 4154 2147 4154 2165 4155 2147 4155 2146 4155 2166 4156 2167 4156 2148 4156 2166 4157 2148 4157 2147 4157 2167 4158 2168 4158 2149 4158 2167 4159 2149 4159 2148 4159 2168 4160 2169 4160 2150 4160 2168 4161 2150 4161 2149 4161 2169 4162 2170 4162 2151 4162 2169 4163 2151 4163 2150 4163 2170 4164 2171 4164 2152 4164 2170 4165 2152 4165 2151 4165 2171 4166 2172 4166 2153 4166 2171 4167 2153 4167 2152 4167 2172 4168 2173 4168 2154 4168 2172 4169 2154 4169 2153 4169 2173 4170 149 4170 151 4170 2173 4171 151 4171 2154 4171 28 4172 2174 4172 2155 4172 28 4173 2155 4173 30 4173 2174 4174 2175 4174 2156 4174 2174 4175 2156 4175 2155 4175 2175 4176 2176 4176 2157 4176 2175 4177 2157 4177 2156 4177 2176 4178 2177 4178 2158 4178 2176 4179 2158 4179 2157 4179 2177 4180 2178 4180 2159 4180 2177 4181 2159 4181 2158 4181 2178 4182 2179 4182 2160 4182 2178 4183 2160 4183 2159 4183 2179 4184 2180 4184 2161 4184 2179 4185 2161 4185 2160 4185 2180 4186 2181 4186 2162 4186 2180 4187 2162 4187 2161 4187 2181 4188 2182 4188 2163 4188 2181 4189 2163 4189 2162 4189 2182 4190 2183 4190 2164 4190 2182 4191 2164 4191 2163 4191 2183 4192 2184 4192 2165 4192 2183 4193 2165 4193 2164 4193 2184 4194 2185 4194 2166 4194 2184 4195 2166 4195 2165 4195 2185 4196 2186 4196 2167 4196 2185 4197 2167 4197 2166 4197 2186 4198 2187 4198 2168 4198 2186 4199 2168 4199 2167 4199 2187 4200 2188 4200 2169 4200 2187 4201 2169 4201 2168 4201 2188 4202 2189 4202 2170 4202 2188 4203 2170 4203 2169 4203 2189 4204 2190 4204 2171 4204 2189 4205 2171 4205 2170 4205 2190 4206 2191 4206 2172 4206 2190 4207 2172 4207 2171 4207 2191 4208 2192 4208 2173 4208 2191 4209 2173 4209 2172 4209 2192 4210 147 4210 149 4210 2192 4211 149 4211 2173 4211 26 4212 2193 4212 2174 4212 26 4213 2174 4213 28 4213 2193 4214 2194 4214 2175 4214 2193 4215 2175 4215 2174 4215 2194 4216 2195 4216 2176 4216 2194 4217 2176 4217 2175 4217 2195 4218 2196 4218 2177 4218 2195 4219 2177 4219 2176 4219 2196 4220 2197 4220 2178 4220 2196 4221 2178 4221 2177 4221 2197 4222 2198 4222 2179 4222 2197 4223 2179 4223 2178 4223 2198 4224 2199 4224 2180 4224 2198 4225 2180 4225 2179 4225 2199 4226 2200 4226 2181 4226 2199 4227 2181 4227 2180 4227 2200 4228 2201 4228 2182 4228 2200 4229 2182 4229 2181 4229 2201 4230 2202 4230 2183 4230 2201 4231 2183 4231 2182 4231 2202 4232 2203 4232 2184 4232 2202 4233 2184 4233 2183 4233 2203 4234 2204 4234 2185 4234 2203 4235 2185 4235 2184 4235 2204 4236 2205 4236 2186 4236 2204 4237 2186 4237 2185 4237 2205 4238 2206 4238 2187 4238 2205 4239 2187 4239 2186 4239 2206 4240 2207 4240 2188 4240 2206 4241 2188 4241 2187 4241 2207 4242 2208 4242 2189 4242 2207 4243 2189 4243 2188 4243 2208 4244 2209 4244 2190 4244 2208 4245 2190 4245 2189 4245 2209 4246 2210 4246 2191 4246 2209 4247 2191 4247 2190 4247 2210 4248 2211 4248 2192 4248 2210 4249 2192 4249 2191 4249 2211 4250 145 4250 147 4250 2211 4251 147 4251 2192 4251 24 4252 2212 4252 2193 4252 24 4253 2193 4253 26 4253 2212 4254 2213 4254 2194 4254 2212 4255 2194 4255 2193 4255 2213 4256 2214 4256 2195 4256 2213 4257 2195 4257 2194 4257 2214 4258 2215 4258 2196 4258 2214 4259 2196 4259 2195 4259 2215 4260 2216 4260 2197 4260 2215 4261 2197 4261 2196 4261 2216 4262 2217 4262 2198 4262 2216 4263 2198 4263 2197 4263 2217 4264 2218 4264 2199 4264 2217 4265 2199 4265 2198 4265 2218 4266 2219 4266 2200 4266 2218 4267 2200 4267 2199 4267 2219 4268 2220 4268 2201 4268 2219 4269 2201 4269 2200 4269 2220 4270 2221 4270 2202 4270 2220 4271 2202 4271 2201 4271 2221 4272 2222 4272 2203 4272 2221 4273 2203 4273 2202 4273 2222 4274 2223 4274 2204 4274 2222 4275 2204 4275 2203 4275 2223 4276 2224 4276 2205 4276 2223 4277 2205 4277 2204 4277 2224 4278 2225 4278 2206 4278 2224 4279 2206 4279 2205 4279 2225 4280 2226 4280 2207 4280 2225 4281 2207 4281 2206 4281 2226 4282 2227 4282 2208 4282 2226 4283 2208 4283 2207 4283 2227 4284 2228 4284 2209 4284 2227 4285 2209 4285 2208 4285 2228 4286 2229 4286 2210 4286 2228 4287 2210 4287 2209 4287 2229 4288 2230 4288 2211 4288 2229 4289 2211 4289 2210 4289 2230 4290 143 4290 145 4290 2230 4291 145 4291 2211 4291 23 4292 1015 4292 2212 4292 23 4293 2212 4293 24 4293 1015 4294 1451 4294 2213 4294 1015 4295 2213 4295 2212 4295 1451 4296 1450 4296 2214 4296 1451 4297 2214 4297 2213 4297 1450 4298 1449 4298 2215 4298 1450 4299 2215 4299 2214 4299 1449 4300 1448 4300 2216 4300 1449 4301 2216 4301 2215 4301 1448 4302 1447 4302 2217 4302 1448 4303 2217 4303 2216 4303 1447 4304 1446 4304 2218 4304 1447 4305 2218 4305 2217 4305 1446 4306 1445 4306 2219 4306 1446 4307 2219 4307 2218 4307 1445 4308 1444 4308 2220 4308 1445 4309 2220 4309 2219 4309 1444 4310 1443 4310 2221 4310 1444 4311 2221 4311 2220 4311 1443 4312 1442 4312 2222 4312 1443 4313 2222 4313 2221 4313 1442 4314 1441 4314 2223 4314 1442 4315 2223 4315 2222 4315 1441 4316 1440 4316 2224 4316 1441 4317 2224 4317 2223 4317 1440 4318 1439 4318 2225 4318 1440 4319 2225 4319 2224 4319 1439 4320 1438 4320 2226 4320 1439 4321 2226 4321 2225 4321 1438 4322 1437 4322 2227 4322 1438 4323 2227 4323 2226 4323 1437 4324 1436 4324 2228 4324 1437 4325 2228 4325 2227 4325 1436 4326 1435 4326 2229 4326 1436 4327 2229 4327 2228 4327 1435 4328 1434 4328 2230 4328 1435 4329 2230 4329 2229 4329 1434 4330 140 4330 143 4330 1434 4331 143 4331 2230 4331 138 4332 2231 4332 2232 4332 138 4333 2232 4333 5 4333 2231 4334 2233 4334 2234 4334 2231 4335 2234 4335 2232 4335 2233 4336 2235 4336 2236 4336 2233 4337 2236 4337 2234 4337 2235 4338 2237 4338 2238 4338 2235 4339 2238 4339 2236 4339 2237 4340 2239 4340 2240 4340 2237 4341 2240 4341 2238 4341 2239 4342 2241 4342 2242 4342 2239 4343 2242 4343 2240 4343 2241 4344 2243 4344 2244 4344 2241 4345 2244 4345 2242 4345 2243 4346 2245 4346 2246 4346 2243 4347 2246 4347 2244 4347 2245 4348 2247 4348 2248 4348 2245 4349 2248 4349 2246 4349 2247 4350 2249 4350 2250 4350 2247 4351 2250 4351 2248 4351 2249 4352 2251 4352 2252 4352 2249 4353 2252 4353 2250 4353 2251 4354 2253 4354 2254 4354 2251 4355 2254 4355 2252 4355 2253 4356 2255 4356 2256 4356 2253 4357 2256 4357 2254 4357 2255 4358 2257 4358 2258 4358 2255 4359 2258 4359 2256 4359 2257 4360 2259 4360 2260 4360 2257 4361 2260 4361 2258 4361 2259 4362 2261 4362 2262 4362 2259 4363 2262 4363 2260 4363 2261 4364 2263 4364 2264 4364 2261 4365 2264 4365 2262 4365 2263 4366 2265 4366 2266 4366 2263 4367 2266 4367 2264 4367 2265 4368 2267 4368 2268 4368 2265 4369 2268 4369 2266 4369 2267 4370 99 4370 8 4370 2267 4371 8 4371 2268 4371 136 4372 2269 4372 2231 4372 136 4373 2231 4373 138 4373 2269 4374 2270 4374 2233 4374 2269 4375 2233 4375 2231 4375 2270 4376 2271 4376 2235 4376 2270 4377 2235 4377 2233 4377 2271 4378 2272 4378 2237 4378 2271 4379 2237 4379 2235 4379 2272 4380 2273 4380 2239 4380 2272 4381 2239 4381 2237 4381 2273 4382 2274 4382 2241 4382 2273 4383 2241 4383 2239 4383 2274 4384 2275 4384 2243 4384 2274 4385 2243 4385 2241 4385 2275 4386 2276 4386 2245 4386 2275 4387 2245 4387 2243 4387 2276 4388 2277 4388 2247 4388 2276 4389 2247 4389 2245 4389 2277 4390 2278 4390 2249 4390 2277 4391 2249 4391 2247 4391 2278 4392 2279 4392 2251 4392 2278 4393 2251 4393 2249 4393 2279 4394 2280 4394 2253 4394 2279 4395 2253 4395 2251 4395 2280 4396 2281 4396 2255 4396 2280 4397 2255 4397 2253 4397 2281 4398 2282 4398 2257 4398 2281 4399 2257 4399 2255 4399 2282 4400 2283 4400 2259 4400 2282 4401 2259 4401 2257 4401 2283 4402 2284 4402 2261 4402 2283 4403 2261 4403 2259 4403 2284 4404 2285 4404 2263 4404 2284 4405 2263 4405 2261 4405 2285 4406 2286 4406 2265 4406 2285 4407 2265 4407 2263 4407 2286 4408 2287 4408 2267 4408 2286 4409 2267 4409 2265 4409 2287 4410 97 4410 99 4410 2287 4411 99 4411 2267 4411 134 4412 2288 4412 2269 4412 134 4413 2269 4413 136 4413 2288 4414 2289 4414 2270 4414 2288 4415 2270 4415 2269 4415 2289 4416 2290 4416 2271 4416 2289 4417 2271 4417 2270 4417 2290 4418 2291 4418 2272 4418 2290 4419 2272 4419 2271 4419 2291 4420 2292 4420 2273 4420 2291 4421 2273 4421 2272 4421 2292 4422 2293 4422 2274 4422 2292 4423 2274 4423 2273 4423 2293 4424 2294 4424 2275 4424 2293 4425 2275 4425 2274 4425 2294 4426 2295 4426 2276 4426 2294 4427 2276 4427 2275 4427 2295 4428 2296 4428 2277 4428 2295 4429 2277 4429 2276 4429 2296 4430 2297 4430 2278 4430 2296 4431 2278 4431 2277 4431 2297 4432 2298 4432 2279 4432 2297 4433 2279 4433 2278 4433 2298 4434 2299 4434 2280 4434 2298 4435 2280 4435 2279 4435 2299 4436 2300 4436 2281 4436 2299 4437 2281 4437 2280 4437 2300 4438 2301 4438 2282 4438 2300 4439 2282 4439 2281 4439 2301 4440 2302 4440 2283 4440 2301 4441 2283 4441 2282 4441 2302 4442 2303 4442 2284 4442 2302 4443 2284 4443 2283 4443 2303 4444 2304 4444 2285 4444 2303 4445 2285 4445 2284 4445 2304 4446 2305 4446 2286 4446 2304 4447 2286 4447 2285 4447 2305 4448 2306 4448 2287 4448 2305 4449 2287 4449 2286 4449 2306 4450 95 4450 97 4450 2306 4451 97 4451 2287 4451 132 4452 2307 4452 2288 4452 132 4453 2288 4453 134 4453 2307 4454 2308 4454 2289 4454 2307 4455 2289 4455 2288 4455 2308 4456 2309 4456 2290 4456 2308 4457 2290 4457 2289 4457 2309 4458 2310 4458 2291 4458 2309 4459 2291 4459 2290 4459 2310 4460 2311 4460 2292 4460 2310 4461 2292 4461 2291 4461 2311 4462 2312 4462 2293 4462 2311 4463 2293 4463 2292 4463 2312 4464 2313 4464 2294 4464 2312 4465 2294 4465 2293 4465 2313 4466 2314 4466 2295 4466 2313 4467 2295 4467 2294 4467 2314 4468 2315 4468 2296 4468 2314 4469 2296 4469 2295 4469 2315 4470 2316 4470 2297 4470 2315 4471 2297 4471 2296 4471 2316 4472 2317 4472 2298 4472 2316 4473 2298 4473 2297 4473 2317 4474 2318 4474 2299 4474 2317 4475 2299 4475 2298 4475 2318 4476 2319 4476 2300 4476 2318 4477 2300 4477 2299 4477 2319 4478 2320 4478 2301 4478 2319 4479 2301 4479 2300 4479 2320 4480 2321 4480 2302 4480 2320 4481 2302 4481 2301 4481 2321 4482 2322 4482 2303 4482 2321 4483 2303 4483 2302 4483 2322 4484 2323 4484 2304 4484 2322 4485 2304 4485 2303 4485 2323 4486 2324 4486 2305 4486 2323 4487 2305 4487 2304 4487 2324 4488 2325 4488 2306 4488 2324 4489 2306 4489 2305 4489 2325 4490 93 4490 95 4490 2325 4491 95 4491 2306 4491 130 4492 2326 4492 2307 4492 130 4493 2307 4493 132 4493 2326 4494 2327 4494 2308 4494 2326 4495 2308 4495 2307 4495 2327 4496 2328 4496 2309 4496 2327 4497 2309 4497 2308 4497 2328 4498 2329 4498 2310 4498 2328 4499 2310 4499 2309 4499 2329 4500 2330 4500 2311 4500 2329 4501 2311 4501 2310 4501 2330 4502 2331 4502 2312 4502 2330 4503 2312 4503 2311 4503 2331 4504 2332 4504 2313 4504 2331 4505 2313 4505 2312 4505 2332 4506 2333 4506 2314 4506 2332 4507 2314 4507 2313 4507 2333 4508 2334 4508 2315 4508 2333 4509 2315 4509 2314 4509 2334 4510 2335 4510 2316 4510 2334 4511 2316 4511 2315 4511 2335 4512 2336 4512 2317 4512 2335 4513 2317 4513 2316 4513 2336 4514 2337 4514 2318 4514 2336 4515 2318 4515 2317 4515 2337 4516 2338 4516 2319 4516 2337 4517 2319 4517 2318 4517 2338 4518 2339 4518 2320 4518 2338 4519 2320 4519 2319 4519 2339 4520 2340 4520 2321 4520 2339 4521 2321 4521 2320 4521 2340 4522 2341 4522 2322 4522 2340 4523 2322 4523 2321 4523 2341 4524 2342 4524 2323 4524 2341 4525 2323 4525 2322 4525 2342 4526 2343 4526 2324 4526 2342 4527 2324 4527 2323 4527 2343 4528 2344 4528 2325 4528 2343 4529 2325 4529 2324 4529 2344 4530 91 4530 93 4530 2344 4531 93 4531 2325 4531 128 4532 2345 4532 2326 4532 128 4533 2326 4533 130 4533 2345 4534 2346 4534 2327 4534 2345 4535 2327 4535 2326 4535 2346 4536 2347 4536 2328 4536 2346 4537 2328 4537 2327 4537 2347 4538 2348 4538 2329 4538 2347 4539 2329 4539 2328 4539 2348 4540 2349 4540 2330 4540 2348 4541 2330 4541 2329 4541 2349 4542 2350 4542 2331 4542 2349 4543 2331 4543 2330 4543 2350 4544 2351 4544 2332 4544 2350 4545 2332 4545 2331 4545 2351 4546 2352 4546 2333 4546 2351 4547 2333 4547 2332 4547 2352 4548 2353 4548 2334 4548 2352 4549 2334 4549 2333 4549 2353 4550 2354 4550 2335 4550 2353 4551 2335 4551 2334 4551 2354 4552 2355 4552 2336 4552 2354 4553 2336 4553 2335 4553 2355 4554 2356 4554 2337 4554 2355 4555 2337 4555 2336 4555 2356 4556 2357 4556 2338 4556 2356 4557 2338 4557 2337 4557 2357 4558 2358 4558 2339 4558 2357 4559 2339 4559 2338 4559 2358 4560 2359 4560 2340 4560 2358 4561 2340 4561 2339 4561 2359 4562 2360 4562 2341 4562 2359 4563 2341 4563 2340 4563 2360 4564 2361 4564 2342 4564 2360 4565 2342 4565 2341 4565 2361 4566 2362 4566 2343 4566 2361 4567 2343 4567 2342 4567 2362 4568 2363 4568 2344 4568 2362 4569 2344 4569 2343 4569 2363 4570 89 4570 91 4570 2363 4571 91 4571 2344 4571 126 4572 2364 4572 2345 4572 126 4573 2345 4573 128 4573 2364 4574 2365 4574 2346 4574 2364 4575 2346 4575 2345 4575 2365 4576 2366 4576 2347 4576 2365 4577 2347 4577 2346 4577 2366 4578 2367 4578 2348 4578 2366 4579 2348 4579 2347 4579 2367 4580 2368 4580 2349 4580 2367 4581 2349 4581 2348 4581 2368 4582 2369 4582 2350 4582 2368 4583 2350 4583 2349 4583 2369 4584 2370 4584 2351 4584 2369 4585 2351 4585 2350 4585 2370 4586 2371 4586 2352 4586 2370 4587 2352 4587 2351 4587 2371 4588 2372 4588 2353 4588 2371 4589 2353 4589 2352 4589 2372 4590 2373 4590 2354 4590 2372 4591 2354 4591 2353 4591 2373 4592 2374 4592 2355 4592 2373 4593 2355 4593 2354 4593 2374 4594 2375 4594 2356 4594 2374 4595 2356 4595 2355 4595 2375 4596 2376 4596 2357 4596 2375 4597 2357 4597 2356 4597 2376 4598 2377 4598 2358 4598 2376 4599 2358 4599 2357 4599 2377 4600 2378 4600 2359 4600 2377 4601 2359 4601 2358 4601 2378 4602 2379 4602 2360 4602 2378 4603 2360 4603 2359 4603 2379 4604 2380 4604 2361 4604 2379 4605 2361 4605 2360 4605 2380 4606 2381 4606 2362 4606 2380 4607 2362 4607 2361 4607 2381 4608 2382 4608 2363 4608 2381 4609 2363 4609 2362 4609 2382 4610 87 4610 89 4610 2382 4611 89 4611 2363 4611 124 4612 2383 4612 2364 4612 124 4613 2364 4613 126 4613 2383 4614 2384 4614 2365 4614 2383 4615 2365 4615 2364 4615 2384 4616 2385 4616 2366 4616 2384 4617 2366 4617 2365 4617 2385 4618 2386 4618 2367 4618 2385 4619 2367 4619 2366 4619 2386 4620 2387 4620 2368 4620 2386 4621 2368 4621 2367 4621 2387 4622 2388 4622 2369 4622 2387 4623 2369 4623 2368 4623 2388 4624 2389 4624 2370 4624 2388 4625 2370 4625 2369 4625 2389 4626 2390 4626 2371 4626 2389 4627 2371 4627 2370 4627 2390 4628 2391 4628 2372 4628 2390 4629 2372 4629 2371 4629 2391 4630 2392 4630 2373 4630 2391 4631 2373 4631 2372 4631 2392 4632 2393 4632 2374 4632 2392 4633 2374 4633 2373 4633 2393 4634 2394 4634 2375 4634 2393 4635 2375 4635 2374 4635 2394 4636 2395 4636 2376 4636 2394 4637 2376 4637 2375 4637 2395 4638 2396 4638 2377 4638 2395 4639 2377 4639 2376 4639 2396 4640 2397 4640 2378 4640 2396 4641 2378 4641 2377 4641 2397 4642 2398 4642 2379 4642 2397 4643 2379 4643 2378 4643 2398 4644 2399 4644 2380 4644 2398 4645 2380 4645 2379 4645 2399 4646 2400 4646 2381 4646 2399 4647 2381 4647 2380 4647 2400 4648 2401 4648 2382 4648 2400 4649 2382 4649 2381 4649 2401 4650 85 4650 87 4650 2401 4651 87 4651 2382 4651 122 4652 2402 4652 2383 4652 122 4653 2383 4653 124 4653 2402 4654 2403 4654 2384 4654 2402 4655 2384 4655 2383 4655 2403 4656 2404 4656 2385 4656 2403 4657 2385 4657 2384 4657 2404 4658 2405 4658 2386 4658 2404 4659 2386 4659 2385 4659 2405 4660 2406 4660 2387 4660 2405 4661 2387 4661 2386 4661 2406 4662 2407 4662 2388 4662 2406 4663 2388 4663 2387 4663 2407 4664 2408 4664 2389 4664 2407 4665 2389 4665 2388 4665 2408 4666 2409 4666 2390 4666 2408 4667 2390 4667 2389 4667 2409 4668 2410 4668 2391 4668 2409 4669 2391 4669 2390 4669 2410 4670 2411 4670 2392 4670 2410 4671 2392 4671 2391 4671 2411 4672 2412 4672 2393 4672 2411 4673 2393 4673 2392 4673 2412 4674 2413 4674 2394 4674 2412 4675 2394 4675 2393 4675 2413 4676 2414 4676 2395 4676 2413 4677 2395 4677 2394 4677 2414 4678 2415 4678 2396 4678 2414 4679 2396 4679 2395 4679 2415 4680 2416 4680 2397 4680 2415 4681 2397 4681 2396 4681 2416 4682 2417 4682 2398 4682 2416 4683 2398 4683 2397 4683 2417 4684 2418 4684 2399 4684 2417 4685 2399 4685 2398 4685 2418 4686 2419 4686 2400 4686 2418 4687 2400 4687 2399 4687 2419 4688 2420 4688 2401 4688 2419 4689 2401 4689 2400 4689 2420 4690 83 4690 85 4690 2420 4691 85 4691 2401 4691 120 4692 2421 4692 2402 4692 120 4693 2402 4693 122 4693 2421 4694 2422 4694 2403 4694 2421 4695 2403 4695 2402 4695 2422 4696 2423 4696 2404 4696 2422 4697 2404 4697 2403 4697 2423 4698 2424 4698 2405 4698 2423 4699 2405 4699 2404 4699 2424 4700 2425 4700 2406 4700 2424 4701 2406 4701 2405 4701 2425 4702 2426 4702 2407 4702 2425 4703 2407 4703 2406 4703 2426 4704 2427 4704 2408 4704 2426 4705 2408 4705 2407 4705 2427 4706 2428 4706 2409 4706 2427 4707 2409 4707 2408 4707 2428 4708 2429 4708 2410 4708 2428 4709 2410 4709 2409 4709 2429 4710 2430 4710 2411 4710 2429 4711 2411 4711 2410 4711 2430 4712 2431 4712 2412 4712 2430 4713 2412 4713 2411 4713 2431 4714 2432 4714 2413 4714 2431 4715 2413 4715 2412 4715 2432 4716 2433 4716 2414 4716 2432 4717 2414 4717 2413 4717 2433 4718 2434 4718 2415 4718 2433 4719 2415 4719 2414 4719 2434 4720 2435 4720 2416 4720 2434 4721 2416 4721 2415 4721 2435 4722 2436 4722 2417 4722 2435 4723 2417 4723 2416 4723 2436 4724 2437 4724 2418 4724 2436 4725 2418 4725 2417 4725 2437 4726 2438 4726 2419 4726 2437 4727 2419 4727 2418 4727 2438 4728 2439 4728 2420 4728 2438 4729 2420 4729 2419 4729 2439 4730 81 4730 83 4730 2439 4731 83 4731 2420 4731 118 4732 2440 4732 2421 4732 118 4733 2421 4733 120 4733 2440 4734 2441 4734 2422 4734 2440 4735 2422 4735 2421 4735 2441 4736 2442 4736 2423 4736 2441 4737 2423 4737 2422 4737 2442 4738 2443 4738 2424 4738 2442 4739 2424 4739 2423 4739 2443 4740 2444 4740 2425 4740 2443 4741 2425 4741 2424 4741 2444 4742 2445 4742 2426 4742 2444 4743 2426 4743 2425 4743 2445 4744 2446 4744 2427 4744 2445 4745 2427 4745 2426 4745 2446 4746 2447 4746 2428 4746 2446 4747 2428 4747 2427 4747 2447 4748 2448 4748 2429 4748 2447 4749 2429 4749 2428 4749 2448 4750 2449 4750 2430 4750 2448 4751 2430 4751 2429 4751 2449 4752 2450 4752 2431 4752 2449 4753 2431 4753 2430 4753 2450 4754 2451 4754 2432 4754 2450 4755 2432 4755 2431 4755 2451 4756 2452 4756 2433 4756 2451 4757 2433 4757 2432 4757 2452 4758 2453 4758 2434 4758 2452 4759 2434 4759 2433 4759 2453 4760 2454 4760 2435 4760 2453 4761 2435 4761 2434 4761 2454 4762 2455 4762 2436 4762 2454 4763 2436 4763 2435 4763 2455 4764 2456 4764 2437 4764 2455 4765 2437 4765 2436 4765 2456 4766 2457 4766 2438 4766 2456 4767 2438 4767 2437 4767 2457 4768 2458 4768 2439 4768 2457 4769 2439 4769 2438 4769 2458 4770 79 4770 81 4770 2458 4771 81 4771 2439 4771 116 4772 2459 4772 2440 4772 116 4773 2440 4773 118 4773 2459 4774 2460 4774 2441 4774 2459 4775 2441 4775 2440 4775 2460 4776 2461 4776 2442 4776 2460 4777 2442 4777 2441 4777 2461 4778 2462 4778 2443 4778 2461 4779 2443 4779 2442 4779 2462 4780 2463 4780 2444 4780 2462 4781 2444 4781 2443 4781 2463 4782 2464 4782 2445 4782 2463 4783 2445 4783 2444 4783 2464 4784 2465 4784 2446 4784 2464 4785 2446 4785 2445 4785 2465 4786 2466 4786 2447 4786 2465 4787 2447 4787 2446 4787 2466 4788 2467 4788 2448 4788 2466 4789 2448 4789 2447 4789 2467 4790 2468 4790 2449 4790 2467 4791 2449 4791 2448 4791 2468 4792 2469 4792 2450 4792 2468 4793 2450 4793 2449 4793 2469 4794 2470 4794 2451 4794 2469 4795 2451 4795 2450 4795 2470 4796 2471 4796 2452 4796 2470 4797 2452 4797 2451 4797 2471 4798 2472 4798 2453 4798 2471 4799 2453 4799 2452 4799 2472 4800 2473 4800 2454 4800 2472 4801 2454 4801 2453 4801 2473 4802 2474 4802 2455 4802 2473 4803 2455 4803 2454 4803 2474 4804 2475 4804 2456 4804 2474 4805 2456 4805 2455 4805 2475 4806 2476 4806 2457 4806 2475 4807 2457 4807 2456 4807 2476 4808 2477 4808 2458 4808 2476 4809 2458 4809 2457 4809 2477 4810 77 4810 79 4810 2477 4811 79 4811 2458 4811 114 4812 2478 4812 2459 4812 114 4813 2459 4813 116 4813 2478 4814 2479 4814 2460 4814 2478 4815 2460 4815 2459 4815 2479 4816 2480 4816 2461 4816 2479 4817 2461 4817 2460 4817 2480 4818 2481 4818 2462 4818 2480 4819 2462 4819 2461 4819 2481 4820 2482 4820 2463 4820 2481 4821 2463 4821 2462 4821 2482 4822 2483 4822 2464 4822 2482 4823 2464 4823 2463 4823 2483 4824 2484 4824 2465 4824 2483 4825 2465 4825 2464 4825 2484 4826 2485 4826 2466 4826 2484 4827 2466 4827 2465 4827 2485 4828 2486 4828 2467 4828 2485 4829 2467 4829 2466 4829 2486 4830 2487 4830 2468 4830 2486 4831 2468 4831 2467 4831 2487 4832 2488 4832 2469 4832 2487 4833 2469 4833 2468 4833 2488 4834 2489 4834 2470 4834 2488 4835 2470 4835 2469 4835 2489 4836 2490 4836 2471 4836 2489 4837 2471 4837 2470 4837 2490 4838 2491 4838 2472 4838 2490 4839 2472 4839 2471 4839 2491 4840 2492 4840 2473 4840 2491 4841 2473 4841 2472 4841 2492 4842 2493 4842 2474 4842 2492 4843 2474 4843 2473 4843 2493 4844 2494 4844 2475 4844 2493 4845 2475 4845 2474 4845 2494 4846 2495 4846 2476 4846 2494 4847 2476 4847 2475 4847 2495 4848 2496 4848 2477 4848 2495 4849 2477 4849 2476 4849 2496 4850 75 4850 77 4850 2496 4851 77 4851 2477 4851 112 4852 2497 4852 2478 4852 112 4853 2478 4853 114 4853 2497 4854 2498 4854 2479 4854 2497 4855 2479 4855 2478 4855 2498 4856 2499 4856 2480 4856 2498 4857 2480 4857 2479 4857 2499 4858 2500 4858 2481 4858 2499 4859 2481 4859 2480 4859 2500 4860 2501 4860 2482 4860 2500 4861 2482 4861 2481 4861 2501 4862 2502 4862 2483 4862 2501 4863 2483 4863 2482 4863 2502 4864 2503 4864 2484 4864 2502 4865 2484 4865 2483 4865 2503 4866 2504 4866 2485 4866 2503 4867 2485 4867 2484 4867 2504 4868 2505 4868 2486 4868 2504 4869 2486 4869 2485 4869 2505 4870 2506 4870 2487 4870 2505 4871 2487 4871 2486 4871 2506 4872 2507 4872 2488 4872 2506 4873 2488 4873 2487 4873 2507 4874 2508 4874 2489 4874 2507 4875 2489 4875 2488 4875 2508 4876 2509 4876 2490 4876 2508 4877 2490 4877 2489 4877 2509 4878 2510 4878 2491 4878 2509 4879 2491 4879 2490 4879 2510 4880 2511 4880 2492 4880 2510 4881 2492 4881 2491 4881 2511 4882 2512 4882 2493 4882 2511 4883 2493 4883 2492 4883 2512 4884 2513 4884 2494 4884 2512 4885 2494 4885 2493 4885 2513 4886 2514 4886 2495 4886 2513 4887 2495 4887 2494 4887 2514 4888 2515 4888 2496 4888 2514 4889 2496 4889 2495 4889 2515 4890 73 4890 75 4890 2515 4891 75 4891 2496 4891 110 4892 2516 4892 2497 4892 110 4893 2497 4893 112 4893 2516 4894 2517 4894 2498 4894 2516 4895 2498 4895 2497 4895 2517 4896 2518 4896 2499 4896 2517 4897 2499 4897 2498 4897 2518 4898 2519 4898 2500 4898 2518 4899 2500 4899 2499 4899 2519 4900 2520 4900 2501 4900 2519 4901 2501 4901 2500 4901 2520 4902 2521 4902 2502 4902 2520 4903 2502 4903 2501 4903 2521 4904 2522 4904 2503 4904 2521 4905 2503 4905 2502 4905 2522 4906 2523 4906 2504 4906 2522 4907 2504 4907 2503 4907 2523 4908 2524 4908 2505 4908 2523 4909 2505 4909 2504 4909 2524 4910 2525 4910 2506 4910 2524 4911 2506 4911 2505 4911 2525 4912 2526 4912 2507 4912 2525 4913 2507 4913 2506 4913 2526 4914 2527 4914 2508 4914 2526 4915 2508 4915 2507 4915 2527 4916 2528 4916 2509 4916 2527 4917 2509 4917 2508 4917 2528 4918 2529 4918 2510 4918 2528 4919 2510 4919 2509 4919 2529 4920 2530 4920 2511 4920 2529 4921 2511 4921 2510 4921 2530 4922 2531 4922 2512 4922 2530 4923 2512 4923 2511 4923 2531 4924 2532 4924 2513 4924 2531 4925 2513 4925 2512 4925 2532 4926 2533 4926 2514 4926 2532 4927 2514 4927 2513 4927 2533 4928 2534 4928 2515 4928 2533 4929 2515 4929 2514 4929 2534 4930 71 4930 73 4930 2534 4931 73 4931 2515 4931 108 4932 2535 4932 2516 4932 108 4933 2516 4933 110 4933 2535 4934 2536 4934 2517 4934 2535 4935 2517 4935 2516 4935 2536 4936 2537 4936 2518 4936 2536 4937 2518 4937 2517 4937 2537 4938 2538 4938 2519 4938 2537 4939 2519 4939 2518 4939 2538 4940 2539 4940 2520 4940 2538 4941 2520 4941 2519 4941 2539 4942 2540 4942 2521 4942 2539 4943 2521 4943 2520 4943 2540 4944 2541 4944 2522 4944 2540 4945 2522 4945 2521 4945 2541 4946 2542 4946 2523 4946 2541 4947 2523 4947 2522 4947 2542 4948 2543 4948 2524 4948 2542 4949 2524 4949 2523 4949 2543 4950 2544 4950 2525 4950 2543 4951 2525 4951 2524 4951 2544 4952 2545 4952 2526 4952 2544 4953 2526 4953 2525 4953 2545 4954 2546 4954 2527 4954 2545 4955 2527 4955 2526 4955 2546 4956 2547 4956 2528 4956 2546 4957 2528 4957 2527 4957 2547 4958 2548 4958 2529 4958 2547 4959 2529 4959 2528 4959 2548 4960 2549 4960 2530 4960 2548 4961 2530 4961 2529 4961 2549 4962 2550 4962 2531 4962 2549 4963 2531 4963 2530 4963 2550 4964 2551 4964 2532 4964 2550 4965 2532 4965 2531 4965 2551 4966 2552 4966 2533 4966 2551 4967 2533 4967 2532 4967 2552 4968 2553 4968 2534 4968 2552 4969 2534 4969 2533 4969 2553 4970 69 4970 71 4970 2553 4971 71 4971 2534 4971 106 4972 2554 4972 2535 4972 106 4973 2535 4973 108 4973 2554 4974 2555 4974 2536 4974 2554 4975 2536 4975 2535 4975 2555 4976 2556 4976 2537 4976 2555 4977 2537 4977 2536 4977 2556 4978 2557 4978 2538 4978 2556 4979 2538 4979 2537 4979 2557 4980 2558 4980 2539 4980 2557 4981 2539 4981 2538 4981 2558 4982 2559 4982 2540 4982 2558 4983 2540 4983 2539 4983 2559 4984 2560 4984 2541 4984 2559 4985 2541 4985 2540 4985 2560 4986 2561 4986 2542 4986 2560 4987 2542 4987 2541 4987 2561 4988 2562 4988 2543 4988 2561 4989 2543 4989 2542 4989 2562 4990 2563 4990 2544 4990 2562 4991 2544 4991 2543 4991 2563 4992 2564 4992 2545 4992 2563 4993 2545 4993 2544 4993 2564 4994 2565 4994 2546 4994 2564 4995 2546 4995 2545 4995 2565 4996 2566 4996 2547 4996 2565 4997 2547 4997 2546 4997 2566 4998 2567 4998 2548 4998 2566 4999 2548 4999 2547 4999 2567 5000 2568 5000 2549 5000 2567 5001 2549 5001 2548 5001 2568 5002 2569 5002 2550 5002 2568 5003 2550 5003 2549 5003 2569 5004 2570 5004 2551 5004 2569 5005 2551 5005 2550 5005 2570 5006 2571 5006 2552 5006 2570 5007 2552 5007 2551 5007 2571 5008 2572 5008 2553 5008 2571 5009 2553 5009 2552 5009 2572 5010 67 5010 69 5010 2572 5011 69 5011 2553 5011 104 5012 2573 5012 2554 5012 104 5013 2554 5013 106 5013 2573 5014 2574 5014 2555 5014 2573 5015 2555 5015 2554 5015 2574 5016 2575 5016 2556 5016 2574 5017 2556 5017 2555 5017 2575 5018 2576 5018 2557 5018 2575 5019 2557 5019 2556 5019 2576 5020 2577 5020 2558 5020 2576 5021 2558 5021 2557 5021 2577 5022 2578 5022 2559 5022 2577 5023 2559 5023 2558 5023 2578 5024 2579 5024 2560 5024 2578 5025 2560 5025 2559 5025 2579 5026 2580 5026 2561 5026 2579 5027 2561 5027 2560 5027 2580 5028 2581 5028 2562 5028 2580 5029 2562 5029 2561 5029 2581 5030 2582 5030 2563 5030 2581 5031 2563 5031 2562 5031 2582 5032 2583 5032 2564 5032 2582 5033 2564 5033 2563 5033 2583 5034 2584 5034 2565 5034 2583 5035 2565 5035 2564 5035 2584 5036 2585 5036 2566 5036 2584 5037 2566 5037 2565 5037 2585 5038 2586 5038 2567 5038 2585 5039 2567 5039 2566 5039 2586 5040 2587 5040 2568 5040 2586 5041 2568 5041 2567 5041 2587 5042 2588 5042 2569 5042 2587 5043 2569 5043 2568 5043 2588 5044 2589 5044 2570 5044 2588 5045 2570 5045 2569 5045 2589 5046 2590 5046 2571 5046 2589 5047 2571 5047 2570 5047 2590 5048 2591 5048 2572 5048 2590 5049 2572 5049 2571 5049 2591 5050 65 5050 67 5050 2591 5051 67 5051 2572 5051 102 5052 2592 5052 2573 5052 102 5053 2573 5053 104 5053 2592 5054 2593 5054 2574 5054 2592 5055 2574 5055 2573 5055 2593 5056 2594 5056 2575 5056 2593 5057 2575 5057 2574 5057 2594 5058 2595 5058 2576 5058 2594 5059 2576 5059 2575 5059 2595 5060 2596 5060 2577 5060 2595 5061 2577 5061 2576 5061 2596 5062 2597 5062 2578 5062 2596 5063 2578 5063 2577 5063 2597 5064 2598 5064 2579 5064 2597 5065 2579 5065 2578 5065 2598 5066 2599 5066 2580 5066 2598 5067 2580 5067 2579 5067 2599 5068 2600 5068 2581 5068 2599 5069 2581 5069 2580 5069 2600 5070 2601 5070 2582 5070 2600 5071 2582 5071 2581 5071 2601 5072 2602 5072 2583 5072 2601 5073 2583 5073 2582 5073 2602 5074 2603 5074 2584 5074 2602 5075 2584 5075 2583 5075 2603 5076 2604 5076 2585 5076 2603 5077 2585 5077 2584 5077 2604 5078 2605 5078 2586 5078 2604 5079 2586 5079 2585 5079 2605 5080 2606 5080 2587 5080 2605 5081 2587 5081 2586 5081 2606 5082 2607 5082 2588 5082 2606 5083 2588 5083 2587 5083 2607 5084 2608 5084 2589 5084 2607 5085 2589 5085 2588 5085 2608 5086 2609 5086 2590 5086 2608 5087 2590 5087 2589 5087 2609 5088 2610 5088 2591 5088 2609 5089 2591 5089 2590 5089 2610 5090 63 5090 65 5090 2610 5091 65 5091 2591 5091 101 5092 2611 5092 2592 5092 101 5093 2592 5093 102 5093 2611 5094 2612 5094 2593 5094 2611 5095 2593 5095 2592 5095 2612 5096 2613 5096 2594 5096 2612 5097 2594 5097 2593 5097 2613 5098 2614 5098 2595 5098 2613 5099 2595 5099 2594 5099 2614 5100 2615 5100 2596 5100 2614 5101 2596 5101 2595 5101 2615 5102 2616 5102 2597 5102 2615 5103 2597 5103 2596 5103 2616 5104 2617 5104 2598 5104 2616 5105 2598 5105 2597 5105 2617 5106 2618 5106 2599 5106 2617 5107 2599 5107 2598 5107 2618 5108 2619 5108 2600 5108 2618 5109 2600 5109 2599 5109 2619 5110 2620 5110 2601 5110 2619 5111 2601 5111 2600 5111 2620 5112 2621 5112 2602 5112 2620 5113 2602 5113 2601 5113 2621 5114 2622 5114 2603 5114 2621 5115 2603 5115 2602 5115 2622 5116 2623 5116 2604 5116 2622 5117 2604 5117 2603 5117 2623 5118 2624 5118 2605 5118 2623 5119 2605 5119 2604 5119 2624 5120 2625 5120 2606 5120 2624 5121 2606 5121 2605 5121 2625 5122 2626 5122 2607 5122 2625 5123 2607 5123 2606 5123 2626 5124 2627 5124 2608 5124 2626 5125 2608 5125 2607 5125 2627 5126 2628 5126 2609 5126 2627 5127 2609 5127 2608 5127 2628 5128 2629 5128 2610 5128 2628 5129 2610 5129 2609 5129 2629 5130 19 5130 63 5130 2629 5131 63 5131 2610 5131 1035 5132 1453 5132 3 5132 1035 5133 3 5133 2 5133 1453 5134 1455 5134 2630 5134 1453 5135 2630 5135 3 5135 1455 5136 1457 5136 2631 5136 1455 5137 2631 5137 2630 5137 1457 5138 1459 5138 2632 5138 1457 5139 2632 5139 2631 5139 1459 5140 1461 5140 2633 5140 1459 5141 2633 5141 2632 5141 1461 5142 1463 5142 2634 5142 1461 5143 2634 5143 2633 5143 1463 5144 1465 5144 2635 5144 1463 5145 2635 5145 2634 5145 1465 5146 1467 5146 2636 5146 1465 5147 2636 5147 2635 5147 1467 5148 1469 5148 2637 5148 1467 5149 2637 5149 2636 5149 1469 5150 1471 5150 2638 5150 1469 5151 2638 5151 2637 5151 1471 5152 1473 5152 2639 5152 1471 5153 2639 5153 2638 5153 1473 5154 1475 5154 2640 5154 1473 5155 2640 5155 2639 5155 1475 5156 1477 5156 2641 5156 1475 5157 2641 5157 2640 5157 1477 5158 1479 5158 2642 5158 1477 5159 2642 5159 2641 5159 1479 5160 1481 5160 2643 5160 1479 5161 2643 5161 2642 5161 1481 5162 1483 5162 2644 5162 1481 5163 2644 5163 2643 5163 1483 5164 1485 5164 2645 5164 1483 5165 2645 5165 2644 5165 1485 5166 1487 5166 2646 5166 1485 5167 2646 5167 2645 5167 1487 5168 1489 5168 2647 5168 1487 5169 2647 5169 2646 5169 1489 5170 20 5170 21 5170 1489 5171 21 5171 2647 5171 100 5172 1055 5172 2611 5172 100 5173 2611 5173 101 5173 1055 5174 1057 5174 2612 5174 1055 5175 2612 5175 2611 5175 1057 5176 1059 5176 2613 5176 1057 5177 2613 5177 2612 5177 1059 5178 1061 5178 2614 5178 1059 5179 2614 5179 2613 5179 1061 5180 1063 5180 2615 5180 1061 5181 2615 5181 2614 5181 1063 5182 1065 5182 2616 5182 1063 5183 2616 5183 2615 5183 1065 5184 1067 5184 2617 5184 1065 5185 2617 5185 2616 5185 1067 5186 1069 5186 2618 5186 1067 5187 2618 5187 2617 5187 1069 5188 1071 5188 2619 5188 1069 5189 2619 5189 2618 5189 1071 5190 1073 5190 2620 5190 1071 5191 2620 5191 2619 5191 1073 5192 1075 5192 2621 5192 1073 5193 2621 5193 2620 5193 1075 5194 1077 5194 2622 5194 1075 5195 2622 5195 2621 5195 1077 5196 1079 5196 2623 5196 1077 5197 2623 5197 2622 5197 1079 5198 1081 5198 2624 5198 1079 5199 2624 5199 2623 5199 1081 5200 1083 5200 2625 5200 1081 5201 2625 5201 2624 5201 1083 5202 1085 5202 2626 5202 1083 5203 2626 5203 2625 5203 1085 5204 1087 5204 2627 5204 1085 5205 2627 5205 2626 5205 1087 5206 1089 5206 2628 5206 1087 5207 2628 5207 2627 5207 1089 5208 1091 5208 2629 5208 1089 5209 2629 5209 2628 5209 1091 5210 16 5210 19 5210 1091 5211 19 5211 2629 5211 5 5212 2232 5212 1832 5212 5 5213 1832 5213 6 5213 2232 5214 2234 5214 1833 5214 2232 5215 1833 5215 1832 5215 2234 5216 2236 5216 1834 5216 2234 5217 1834 5217 1833 5217 2236 5218 2238 5218 1835 5218 2236 5219 1835 5219 1834 5219 2238 5220 2240 5220 1836 5220 2238 5221 1836 5221 1835 5221 2240 5222 2242 5222 1837 5222 2240 5223 1837 5223 1836 5223 2242 5224 2244 5224 1838 5224 2242 5225 1838 5225 1837 5225 2244 5226 2246 5226 1839 5226 2244 5227 1839 5227 1838 5227 2246 5228 2248 5228 1840 5228 2246 5229 1840 5229 1839 5229 2248 5230 2250 5230 1841 5230 2248 5231 1841 5231 1840 5231 2250 5232 2252 5232 1842 5232 2250 5233 1842 5233 1841 5233 2252 5234 2254 5234 1843 5234 2252 5235 1843 5235 1842 5235 2254 5236 2256 5236 1844 5236 2254 5237 1844 5237 1843 5237 2256 5238 2258 5238 1845 5238 2256 5239 1845 5239 1844 5239 2258 5240 2260 5240 1846 5240 2258 5241 1846 5241 1845 5241 2260 5242 2262 5242 1847 5242 2260 5243 1847 5243 1846 5243 2262 5244 2264 5244 1848 5244 2262 5245 1848 5245 1847 5245 2264 5246 2266 5246 1849 5246 2264 5247 1849 5247 1848 5247 2266 5248 2268 5248 1850 5248 2266 5249 1850 5249 1849 5249 2268 5250 8 5250 11 5250 2268 5251 11 5251 1850 5251 13 5252 1852 5252 21 5252 13 5253 21 5253 14 5253 1852 5254 1854 5254 2647 5254 1852 5255 2647 5255 21 5255 1854 5256 1856 5256 2646 5256 1854 5257 2646 5257 2647 5257 1856 5258 1858 5258 2645 5258 1856 5259 2645 5259 2646 5259 1858 5260 1860 5260 2644 5260 1858 5261 2644 5261 2645 5261 1860 5262 1862 5262 2643 5262 1860 5263 2643 5263 2644 5263 1862 5264 1864 5264 2642 5264 1862 5265 2642 5265 2643 5265 1864 5266 1866 5266 2641 5266 1864 5267 2641 5267 2642 5267 1866 5268 1868 5268 2640 5268 1866 5269 2640 5269 2641 5269 1868 5270 1870 5270 2639 5270 1868 5271 2639 5271 2640 5271 1870 5272 1872 5272 2638 5272 1870 5273 2638 5273 2639 5273 1872 5274 1874 5274 2637 5274 1872 5275 2637 5275 2638 5275 1874 5276 1876 5276 2636 5276 1874 5277 2636 5277 2637 5277 1876 5278 1878 5278 2635 5278 1876 5279 2635 5279 2636 5279 1878 5280 1880 5280 2634 5280 1878 5281 2634 5281 2635 5281 1880 5282 1882 5282 2633 5282 1880 5283 2633 5283 2634 5283 1882 5284 1884 5284 2632 5284 1882 5285 2632 5285 2633 5285 1884 5286 1886 5286 2631 5286 1884 5287 2631 5287 2632 5287 1886 5288 1888 5288 2630 5288 1886 5289 2630 5289 2631 5289 1888 5290 0 5290 3 5290 1888 5291 3 5291 2630 5291

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_distal/mst/th_distal_mst.dae b/URDFs/sr_description/meshes/components/th_distal/mst/th_distal_mst.dae new file mode 100644 index 0000000..e08019b --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_distal/mst/th_distal_mst.dae @@ -0,0 +1,133 @@ + + + + + + Blender User + Blender 3.3.1 commit date:2022-10-04, commit time:18:35, hash:b292cfe5a936 + + 2022-11-14T13:17:27 + 2022-11-14T13:17:27 + + Z_UP + + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + 10.23391 3.406233 22.7068 10.62085 2.583245 22.9337 11.1416 2.567904 18.72374 11.32456 0.7929431 20.93187 11.00963 0.7677788 23.04967 11.02634 0.3107295 22.98018 11.8879 1.692328 12.40084 11.56798 2.528911 12.37258 11.4732 2.544021 14.49341 4.950852 -8.986525 16.85239 3.932992 -9.324445 15.29745 4.499514 -9.088242 13.90864 5.590802 -8.674137 15.09582 6.659839 -8.085988 16.30838 5.961547 -8.452943 18.43903 4.637456 -8.810386 23.12384 4.249961 -9.115173 22.02416 4.597603 -9.019236 21.56468 3.558855 3.148128 37.29381 3.594331 2.683753 37.48583 4.542427 2.676391 37.02017 0.03688526 -9.968132 23.937 0.03688526 -10.16001 22.48359 0.8340976 -9.963211 22.90321 0.2512317 -9.763237 10.43117 0.5971955 -9.784463 11.87701 0.3158148 -9.812689 12.22046 0.3562062 -9.759766 10.43221 0.4263912 -9.756983 10.43275 0.8462456 -9.755884 11.4984 7.934185 -7.188418 10.4218 7.767426 -7.352389 12.00542 6.652812 -8.048274 11.55073 1.433411 5.015316 36.37413 1.463085 5.252422 36.01083 0.6613027 5.264777 36.11789 2.394429 5.00167 36.1364 2.448292 5.238389 35.76233 2.239739 5.241374 35.82595 4.181961 4.970791 35.34884 3.208629 5.228708 35.47479 3.313112 4.986847 35.79252 6.41447 4.913903 33.48136 5.510271 5.194828 33.98232 5.740191 4.934505 34.18711 4.871778 5.205273 34.50897 4.993491 4.953397 34.81163 4.6371 5.209036 34.6775 3.941303 5.219596 35.1107 7.008585 4.891332 32.70043 6.618313 5.174437 32.75301 6.092003 5.184895 33.39716 7.51457 4.866513 31.85032 7.215883 5.156816 31.82899 6.776658 5.170571 32.53192 7.924153 4.839202 30.9371 7.581311 5.142394 31.09267 7.374232 5.150868 31.53206 8.228715 4.809279 29.96707 7.973263 5.124307 29.98038 7.871278 5.129286 30.32403 8.200071 5.120316 28.80506 8.19234 5.114849 28.89545 8.418174 4.79152 28.96744 8.1565 5.115916 29.1354 8.055299 5.120056 29.65387 8.259684 5.136532 28.24653 8.55787 4.79303 27.98421 8.402045 5.13099 27.13461 8.818743 4.792335 26.01597 8.73223 5.147736 23.99101 9.266376 4.779562 22.07287 8.852327 5.153094 22.67068 9.614418 4.756161 18.12172 9.118603 5.164024 19.15926 9.310262 5.171664 15.60171 9.861748 4.72536 14.16353 9.380406 5.174661 13.71474 11.51419 2.713061 10.46024 11.14893 3.33395 10.46151 11.02273 3.341917 14.40623 10.61695 4.039941 10.46272 11.98681 1.484611 10.4621 11.92901 1.691086 10.46106 11.80313 2.063516 10.46007 12.04919 -1.310972 10.47129 12.15517 -0.5448114 10.47278 12.1037 -0.4508289 12.28915 10.06761 -5.222896 10.44078 10.1907 -5.075067 10.44229 9.762279 -5.563723 12.89703 10.38236 -4.83369 10.44472 10.59451 -4.473195 13.31408 10.91323 -4.076246 10.45203 11.35635 -3.29629 10.4589 9.508934 -5.83487 10.43456 8.810996 -6.523767 12.45758 9.12584 -6.208251 10.4308 8.755062 -6.540075 10.42754 5.480547 -8.614111 11.10823 6.205327 -8.247707 10.41852 7.150449 -7.714784 10.41852 4.207777 -9.078098 10.42748 5.221764 -8.702517 10.42299 5.68662 -8.49908 10.42093 4.229685 -9.077971 10.69445 3.411752 -9.309939 10.43325 2.642091 -9.497483 11.01537 2.326607 -9.547475 10.43906 1.066922 -9.727342 11.10573 1.209398 -9.701998 10.43827 0.4438226 -9.756236 10.43292 0.5135359 -9.753027 10.43359 0.6529026 -9.745574 10.43482 0.03688526 -9.879926 13.34243 0.03688526 -9.768144 10.42808 0.07943797 -9.767374 10.42879 0.2901228 -9.934737 14.61258 0.03688526 -9.906665 13.82304 0.5871123 -9.895728 14.37771 0.03688526 -10.21334 18.39043 0.03688526 -10.13099 16.9338 0.4355709 -10.07914 16.88529 0.03688526 -10.01237 15.41925 0.6734302 -10.14851 20.41415 0.03688526 -10.24615 21.145 0.03688526 -10.25229 19.79242 0.4056916 -8.368584 29.05243 0.03688526 -8.913829 27.85526 0.3927667 -8.846862 27.88506 0.03688526 -9.347161 26.57883 0.3783858 -9.254671 26.69369 0.03688526 -9.699275 25.27219 0.03688526 -7.635967 30.62971 0.03688526 -7.806469 30.31417 0.4172965 -7.821161 30.19133 0.03688526 -8.400096 29.10081 0.4450755 -5.779705 33.3932 0.03688526 -5.694762 33.54835 0.03688526 -6.181386 32.90937 0.03688526 -2.651655 36.66697 0.03688526 -2.886761 36.46828 0.4627699 -3.129871 36.23465 0.03688526 -3.883454 35.55658 0.4692716 -0.2182701 38.20511 0.03688526 -0.9462915 37.90612 0.469271 -0.9555954 37.88731 0.03688526 -1.447795 37.59773 0.4684506 -1.578585 37.48666 0.03688526 -2.019949 37.17277 0.466709 -2.107287 37.08732 0.468241 1.12874 38.44043 0.03688526 0.5418903 38.39829 0.4689517 0.503964 38.38228 0.03688526 0.2437701 38.34317 0.03688526 -0.3637809 38.16566 0.4626119 3.171437 38.0207 0.03688526 3.314017 37.9687 0.03688526 2.727166 38.21035 0.03688526 4.398316 37.22764 0.03688526 4.308663 37.3075 0.4513463 4.394016 37.20948 0.03688526 4.111671 37.46929 0.45994 3.612587 37.78974 0.03688526 3.615555 37.80585 0.03688526 3.581614 37.82563 -0.06211644 5.26503 36.15671 0.4375985 5.027809 36.49929 0.03688526 4.789238 36.82455 0.03688526 4.585125 37.04708 10.28953 2.58755 25.02902 9.910862 2.589473 27.11679 10.12764 1.678408 27.27401 9.484742 2.5889 29.19616 9.668573 1.673287 29.36775 10.19131 1.200118 27.29022 9.723731 1.191182 29.38512 10.22215 0.7184392 27.26055 9.749876 0.6942108 29.35165 10.23123 0.2138672 27.16884 9.755237 0.1657942 29.24884 10.22307 -0.2937427 27.00494 9.675457 -1.298123 28.57111 10.16035 -1.191253 26.56344 9.716367 -0.8513581 28.8281 9.743629 -0.3680073 29.06525 9.135305 -1.408748 30.57347 9.178277 -0.9485751 30.8577 9.209047 -0.4450332 31.12036 9.224358 0.1160299 31.32373 9.222927 0.66923 31.43761 9.201694 1.182052 31.47477 3.421981 4.354057 36.47943 3.517768 3.582474 37.0582 4.319969 4.33791 36.02268 4.442933 3.569501 36.59477 5.159101 4.32028 35.46999 5.307859 3.555007 36.03246 5.931743 4.301055 34.82762 6.104699 3.538926 35.37767 6.630186 4.280081 34.10177 6.825546 3.521165 34.63668 7.246569 4.257175 33.29854 7.462364 3.501629 33.81571 7.77282 4.232159 32.42403 8.006937 3.480248 32.92097 8.200596 4.204915 31.48441 8.450843 3.457022 31.9588 8.521282 4.175466 30.48611 8.785474 3.432078 30.93574 8.732347 4.161654 29.4677 2.568704 3.157193 37.6519 2.540222 3.59397 37.41627 1.518243 3.604007 37.66235 2.472754 4.368786 36.83382 1.479954 4.382112 37.07936 1.533853 3.164951 37.89644 2.593074 2.690064 37.8432 1.546962 2.695385 38.08558 0.4644994 2.699784 38.20629 0.03688526 2.108826 38.37117 5.429189 2.667914 36.45281 6.246494 2.658261 35.79025 6.986201 2.647368 35.03889 7.640082 2.635187 34.2051 8.199793 2.621695 33.29531 8.656862 2.60693 32.316 9.088007 2.138736 31.38759 9.155017 1.668766 31.45649 8.737556 2.148266 32.43624 8.800566 1.670615 32.50921 8.275156 2.156962 33.42141 8.333632 1.671994 33.49798 7.709344 2.164767 34.3363 7.762749 1.672959 34.41594 7.048611 2.171682 35.1743 7.096437 1.673583 35.25641 6.30136 2.177744 35.92893 6.343157 1.673949 36.01285 5.475903 2.183013 36.59374 5.511301 1.674145 36.67877 4.580497 2.187557 37.16226 4.609214 1.674258 37.24767 3.623394 2.191453 37.62797 3.64525 1.674377 37.71303 2.612916 2.194778 37.98423 2.627828 1.674584 38.06825 1.557524 2.197613 38.2244 1.565508 1.674961 38.30669 0.4658815 2.200045 38.34181 0.467047 1.675585 38.42174 0.03688526 1.811316 38.41725 0.03688526 1.17818 38.45111 1.570824 1.130306 38.32614 1.572233 0.5132018 38.26866 1.569713 -0.197036 38.09423 1.563435 -0.9215277 37.78204 1.554414 -1.535333 37.38825 1.545736 -2.057699 36.99405 2.637324 1.132731 38.08841 2.63954 0.523777 38.03207 2.634487 -0.1738125 37.86145 2.622454 -0.8850291 37.55653 2.60581 -1.489604 37.17134 2.590438 -2.005749 36.7835 1.522983 -3.06816 36.14949 0.4580177 -4.089998 35.32413 0.03688526 -4.819911 34.58298 3.658991 1.135971 37.73382 3.66221 0.5356439 37.67903 3.655117 -0.1486603 37.51317 3.638125 -0.8461343 37.21699 3.614689 -1.441383 36.84197 3.592981 -1.951418 36.4617 2.549522 -3.004316 35.95005 1.493278 -4.017604 35.24419 0.4521652 -4.972766 34.37501 0.03688526 -5.078225 34.29129 4.627258 1.139969 37.26895 4.631741 0.5487467 37.21604 4.623243 -0.1216343 37.05576 4.602307 -0.804845 36.76956 4.573125 -1.390596 36.40613 4.545564 -1.894618 36.03456 3.534813 -2.938312 35.64224 2.495732 -3.943306 35.05364 1.456795 -4.891853 34.29735 5.533684 1.144659 36.70035 5.539733 0.5630276 36.64958 5.53056 -0.09277629 36.49549 5.506853 -0.7611213 36.22029 5.473157 -1.337103 35.86965 5.44036 -1.835186 35.5079 4.471324 -2.870049 35.23189 3.458096 -3.867081 34.75824 2.429695 -4.809271 34.11333 1.413854 -5.692396 33.31515 0.4369254 -6.52476 32.36608 0.03688526 -6.944817 31.79337 0.4276822 -7.205985 31.29738 1.365298 -6.432212 32.2859 2.352164 -5.603639 33.13553 3.363897 -4.724998 33.82853 4.373135 -3.788824 34.36365 5.351516 -2.799339 34.72468 6.269447 -1.772884 34.88738 6.306718 -1.280702 35.23826 6.343545 -0.7148914 35.57511 6.368747 -0.06211525 35.83859 6.377818 0.5784288 35.98607 6.369883 1.149964 36.03453 7.127461 1.155797 35.27794 7.1376 0.5948871 35.23186 7.12941 -0.02967637 35.09124 7.10402 -0.6660687 34.83995 7.065555 -1.221153 34.51762 7.02473 -1.707412 34.17861 6.167778 -2.725895 34.12617 5.233617 -3.708339 33.87542 4.252483 -4.638934 33.4484 3.253386 -5.513411 32.85968 2.264652 -6.338427 32.1094 1.311682 -7.109405 31.21372 7.797972 1.162055 34.43705 7.810604 0.6123243 34.39336 7.804023 0.004494726 34.25967 7.779713 -0.6145842 34.02072 7.741148 -1.158217 33.71336 7.69785 -1.638447 33.3871 6.912356 -2.649338 33.44179 6.032266 -3.625324 33.29894 5.088549 -4.550888 32.9783 4.110944 -5.421618 32.49284 3.128733 -6.243379 31.84168 2.168282 -7.011788 31.03941 1.25355 -7.721833 30.10321 6.516999 -7.917005 21.25223 6.93467 -7.717658 20.01033 6.967074 -7.478218 22.1118 7.399051 -7.275188 20.78018 7.399041 -6.987294 22.95365 7.84396 -6.783355 21.53418 6.064826 -8.118608 22.49018 6.497405 -7.683863 23.43921 6.91339 -7.19419 24.36866 5.771393 -8.230825 23.10213 6.188996 -7.800038 24.09612 6.591135 -7.312935 25.06978 7.308945 -6.650384 25.27369 7.808957 -6.444954 23.77336 8.265389 -6.242797 22.26836 5.16369 -8.821393 20.55293 5.619162 -8.497915 21.52646 5.341736 -8.604787 22.09291 5.420975 -8.339502 23.67719 5.817552 -7.912153 24.71241 6.199791 -7.427132 25.72664 6.974107 -6.770314 26.01809 7.680109 -6.053267 26.14945 8.192732 -5.85196 24.56651 8.659154 -5.654206 22.97874 5.01765 -8.445633 24.21257 5.387714 -8.021308 25.28504 5.7446 -7.537959 26.33588 6.56418 -6.885267 26.71465 7.334108 -6.172983 26.93598 8.022644 -5.403961 26.99107 8.545991 -5.209362 25.32869 9.020779 -5.018548 23.66133 4.565469 -8.549911 24.70534 4.904029 -8.128288 25.81078 5.230625 -7.646277 26.89402 6.085033 -6.996457 27.35976 6.907127 -6.287386 27.67127 7.667052 -5.522053 27.81837 8.33189 -4.704182 27.7938 8.863859 -4.51883 26.05557 9.34521 -4.337434 24.31225 4.603821 -9.142582 17.72558 5.092689 -8.916271 18.61157 4.701589 -9.088634 19.57447 4.903203 -8.92155 21.07352 5.013317 -8.708657 22.62621 4.176778 -9.270847 20.49784 4.45888 -9.18072 20.04904 3.505025 -9.447332 21.31005 3.753584 -9.463361 19.43094 4.011637 -9.382146 19.02457 4.235805 -9.299448 18.59599 2.919626 -9.681894 17.33928 3.314187 -9.560579 16.67696 3.630852 -9.442356 15.98825 2.414664 -9.696224 14.87479 2.916474 -9.542243 13.83778 1.953401 -9.657511 12.43921 1.584312 -9.737181 13.14673 4.068502 -8.652814 25.15243 4.371018 -8.233643 26.2863 4.662852 -7.752704 27.39744 5.542266 -7.1048 27.94966 6.405681 -6.397669 28.35141 7.22477 -5.634614 28.59124 7.968474 -4.8192 28.66028 8.603081 -3.955508 28.55313 9.141314 -3.78197 26.74303 9.627199 -3.612493 24.92777 3.441191 -9.303593 22.83843 3.863419 -9.209847 22.44958 3.757796 -9.00961 24.00134 4.217738 -8.910569 23.58315 3.530857 -8.754682 25.55067 3.793218 -8.337762 26.70811 4.046254 -7.857676 27.84239 4.941345 -7.210971 28.48045 5.835922 -6.504776 28.97235 6.702956 -5.742757 29.30542 7.512913 -4.928626 29.46941 8.233797 -4.065979 29.45699 8.829944 -3.154622 29.27508 9.371563 -2.997545 27.39648 9.859459 -2.844574 25.51265 2.956674 -8.85575 25.89682 3.175187 -8.440917 27.07267 3.385806 -7.961501 28.225 4.287678 -7.315452 28.94811 5.203804 -6.609424 29.52996 6.108328 -5.847419 29.95663 6.972989 -5.033421 30.21656 7.767253 -4.170969 30.30089 8.457021 -3.2581 30.21478 9.008338 -2.30321 29.95334 9.550561 -2.167541 28.01019 10.03809 -2.035871 26.06179 2.502813 -9.489165 23.49617 2.986549 -9.396644 23.18817 2.73202 -9.205325 24.70289 3.261314 -9.107794 24.37557 2.350125 -8.956185 26.18758 2.521507 -8.543299 27.37636 2.6865 -8.064392 28.54136 3.586658 -7.418585 29.34849 4.515175 -6.712133 30.01993 5.447332 -5.949334 30.54046 6.355983 -5.134469 30.89719 7.211814 -4.271225 31.07984 7.982184 -3.356369 31.0923 8.634245 -2.39643 30.92704 2.70845 -9.620794 21.99392 1.810215 -9.792529 22.53123 1.715411 -9.056103 26.41958 1.836787 -8.645036 27.61549 1.953351 -8.166488 28.78744 2.843683 -7.520604 29.67736 3.775846 -6.813276 30.43786 4.726261 -6.049055 31.05237 5.668836 -5.232499 31.50664 6.575306 -4.367526 31.78899 7.414295 -3.449913 31.90225 8.154144 -2.485044 31.83683 8.762395 -1.489088 31.57852 8.806838 -1.021744 31.8772 8.841315 -0.503809 32.15445 8.860312 0.07757747 32.36924 8.861921 0.6496731 32.48947 8.843665 1.175339 32.52867 1.993342 -9.581274 23.75979 2.173678 -9.302342 24.98033 1.590078 -9.398949 25.20486 1.056751 -9.155583 26.58943 1.125656 -8.74621 27.78631 1.191394 -8.267872 28.95917 2.064168 -7.621658 29.9304 2.991613 -6.913107 30.77922 3.951332 -6.146979 31.48771 4.918283 -5.328076 32.04016 5.86516 -4.460559 32.42346 6.761688 -3.539359 32.63949 7.577257 -2.569213 32.6769 8.280103 -1.565713 32.51847 8.324643 -1.091737 32.83123 8.36182 -0.5604474 33.12346 8.383921 0.04030406 33.35016 8.388259 0.6306369 33.47702 8.372899 1.168617 33.5184 1.461522 -9.67306 23.97633 0.9850339 -9.495218 25.37343 0.9107614 -9.764583 24.14308 0.3623751 -9.591197 25.48295 0.3444843 -9.85589 24.25729 1.330389 -9.877973 22.73907 3.144881 -9.62293 20.17003 2.784991 -9.736648 19.03486 2.428739 -9.780179 20.79828 2.148819 -9.87486 19.60659 1.625242 -9.936075 21.2999 1.439066 -10.01203 20.07094 1.197183 -10.01368 21.49817 0.7550712 -10.09112 21.65868 2.436484 -9.800943 17.93429 1.878314 -9.918694 18.45132 1.259439 -10.03561 18.8792 0.5946374 -10.15193 19.20656 1.373123 -9.777347 13.49092 1.133457 -9.817083 13.8132 0.869864 -9.85652 14.11002 0.9061997 -10.00365 16.59551 1.348687 -9.927765 16.24249 1.753604 -9.851391 15.83338 2.11182 -9.774342 15.37522 7.68043 -7.319158 17.50992 8.306134 -6.921101 14.99091 8.164663 -6.869426 18.09874 9.266687 -5.969182 15.79473 8.626936 -6.375867 18.67549 7.262003 -7.719088 14.16271 6.158271 -8.361381 13.32776 5.015468 -8.851482 12.51166 5.576529 -8.636407 19.49767 6.052374 -8.303192 20.37937 6.454385 -8.110358 19.22861 3.823581 -9.233257 11.74669 11.61275 2.513445 10.46 10.70833 3.379089 18.56451 11.9523 0.870866 14.5408 12.00015 0.1530686 14.47 12.11184 0.2275223 12.36116 12.1749 0.04472696 10.47215 11.98237 -0.5551249 14.3452 11.89786 -1.25162 14.20212 11.7503 -1.933112 14.04472 11.85536 -2.072011 10.46767 11.5412 -2.602316 13.87649 11.71013 -2.49287 10.46499 11.27316 -3.255566 13.69903 10.95562 -3.879767 13.51116 10.48563 -4.257712 16.91708 10.8143 -3.614416 17.26038 11.09482 -2.937193 17.58482 11.31835 -2.235109 17.89271 11.48174 -1.51133 18.18129 11.58298 -0.7656196 18.4443 11.61812 0.004047691 18.67475 11.61133 0.4087157 18.75986 11.58674 0.8184819 18.80713 11.44565 1.691288 18.81187 11.19403 1.689257 20.93853 10.96949 1.218456 23.07181 10.89044 1.686419 23.05843 12.12386 0.7726897 10.46784 12.05534 0.8978306 12.40118 11.79267 1.692846 14.54206 9.002729 2.59101 31.27392 9.253847 2.587643 30.23242 9.017875 3.423436 29.90335 9.221828 3.423826 28.88013 8.904515 4.162098 28.46258 9.599383 3.421532 26.8285 9.224699 4.159236 26.449 9.769098 4.141381 22.40977 10.18567 4.111343 18.35669 10.47394 4.071987 14.29242 10.0645 4.63007 10.46233 9.45075 5.178372 10.45978 10.53495 1.682794 25.17058 11.0254 -0.1449518 22.85568 10.97531 -0.9779099 22.51963 10.86147 -1.773011 22.13703 10.68772 -2.539195 21.71779 10.45647 -3.274166 21.27092 10.17129 -3.975268 20.80036 9.063204 -5.838954 19.23711 9.706827 -5.436074 16.18212 9.469195 -5.25924 19.7805 10.11466 -4.865381 16.55695 9.840328 -4.637516 20.30258 8.63075e-4 7.249662 32.07006 8.91561e-4 7.250001 32.02505 -0.3736893 7.250001 32.00701 8.27154e-4 7.248263 32.12716 -0.4116432 7.200807 32.54673 5.19428e-4 7.187798 32.63304 -0.4483524 7.054842 33.06875 2.44437e-4 7.046026 33.1128 -7.09711 6.947461 10.73614 -7.242757 6.871234 10.45025 -7.665436 6.586385 10.44986 -6.77662 7.080886 10.45067 -6.457865 7.173387 10.73711 -6.292785 7.206473 10.45112 -5.784213 7.250001 10.73812 -5.783599 7.250001 10.45159 -6.592876 6.785531 28.64093 -6.915172 6.341226 29.45084 -6.32697 6.833873 29.23469 -6.834633 6.363151 29.6014 -6.255624 6.844223 29.37198 -6.450028 6.44867 30.22673 -5.913805 6.884436 29.94472 -6.012559 6.522085 30.80138 -5.523327 6.918761 30.47396 -5.528277 6.583565 31.32649 -5.088155 6.94737 30.96076 -5.2113 6.616075 31.62285 -4.80169 6.962448 31.23701 -4.645731 6.663562 32.07766 -4.287902 6.98441 31.66305 -4.047235 6.703207 32.47352 -3.74131 7.002692 32.03581 -3.389087 6.73752 32.82459 -3.137528 7.018474 32.36799 -2.724381 6.764463 33.10208 -2.525374 7.030842 32.63172 -2.046762 6.785569 33.31404 -1.898696 7.040513 32.83435 -1.363012 6.801342 33.46324 -1.264008 7.047732 32.97797 -1.19326 6.804756 33.48997 -1.107085 7.049293 33.00377 -0.482613 6.816891 33.55595 -4.03329e-6 6.820905 33.57178 -6.831961 6.719707 27.88147 -7.373815 6.166079 28.357 -7.215783 6.239287 28.79693 -7.581799 6.148962 26.35708 -7.575694 6.131596 26.6285 -6.923036 6.734057 26.5797 -7.557334 6.09615 27.2348 -6.901801 6.717024 27.18145 -7.501178 6.090737 27.88765 -7.484774 6.10173 27.95744 -0.9188002 7.250001 31.94146 -1.014558 7.199397 32.48173 -1.047538 7.250001 31.91691 -1.157645 7.199 32.45661 -1.573854 7.250001 31.78197 -1.739187 7.197163 32.3176 -2.086786 7.250001 31.59511 -2.310199 7.194701 32.12315 -2.579868 7.250001 31.35578 -2.864239 7.191549 31.87195 -3.058008 7.250001 31.05817 -3.406926 7.187522 31.55739 -3.481592 7.250001 30.72878 -3.893977 7.182851 31.20661 -3.868756 7.250001 30.35823 -4.346819 7.177229 30.80854 -4.078241 7.250001 30.12156 -4.596436 7.173364 30.55216 -4.384542 7.250001 29.7118 -4.970334 7.166014 30.10385 -4.643586 7.250001 29.27667 -5.298974 7.157172 29.62136 -4.854922 7.250001 28.81697 -5.580228 7.14678 29.10436 -4.896183 7.250001 28.70891 -5.637754 7.144098 28.98142 -5.037459 7.250001 28.25137 -5.847138 7.131544 28.45416 -5.14028 7.250001 27.6846 -6.026175 7.114361 27.7877 -5.200442 7.250001 27.043 -6.091623 7.113657 27.11552 -5.24562 7.250001 26.45427 -6.122894 7.118116 26.51987 -5.466487 7.250001 23.05112 -6.271902 7.139525 23.09529 -7.017997 6.816237 23.13621 -7.649825 6.303946 23.17086 -7.62673 6.24356 24.50716 -7.60923 6.201075 25.35654 -5.639828 7.250001 19.18334 -6.384594 7.155963 19.20978 -7.08267 6.87975 19.23456 -7.699979 6.529645 15.02993 -7.69899 6.486979 17.28266 -7.690293 6.438673 19.25613 -5.750087 7.250001 14.99615 -6.451103 7.166921 15.0083 -7.113292 6.922287 15.01977 -7.669299 6.583761 10.73528 0.05691343 7.201231 32.56233 0.03976875 7.250001 32.02387 6.786055 7.077559 10.45071 6.291522 7.206691 10.45114 6.456853 7.168611 14.12165 5.783602 7.250001 10.45159 7.696248 6.54376 14.13874 7.665486 6.586348 10.44994 7.241637 6.871858 10.45031 0.08899122 6.820542 33.5698 0.07350069 7.056509 33.08329 0.244723 6.819464 33.56573 0.2233039 7.056017 33.07895 0.9417978 6.809726 33.5223 0.8751242 7.051566 33.03524 1.645661 6.795683 33.40977 1.526367 7.045144 32.92656 2.335998 6.777349 33.23265 2.166359 7.036748 32.75651 2.440364 6.774048 33.20003 2.262821 7.035236 32.72533 3.106165 6.749803 32.95214 2.877128 7.024114 32.48914 3.748925 6.719711 32.64319 3.467795 7.010288 32.19624 4.367842 6.682933 32.27161 4.03421 6.993349 31.84557 4.988586 6.635928 31.8122 4.59943 6.971638 31.41426 5.521314 6.583984 31.33252 5.081468 6.947563 30.96665 6.012941 6.521325 30.79935 5.523039 6.918407 30.47258 6.125246 6.504203 30.66228 5.623399 6.910418 30.34616 6.544876 6.428442 30.08145 5.997328 6.874948 29.81223 6.910711 6.340332 29.45206 6.321985 6.833452 29.2369 7.21097 6.24253 28.78308 6.58851 6.787076 28.62708 7.30378 6.20249 28.53565 7.388306 6.158612 28.28621 6.856914 6.716711 27.64608 6.670721 6.767991 28.40301 7.459006 6.114693 28.04876 7.511598 6.0955 27.70958 7.55727 6.117345 26.93604 7.573858 6.166642 26.15856 6.926837 6.752192 26.05503 6.903214 6.727214 26.88792 7.575652 6.169434 26.10309 7.59069 6.195446 25.58879 6.944624 6.764627 25.5436 7.659534 6.355765 21.92687 7.036151 6.840739 21.89643 7.692799 6.469467 18.09613 7.09183 6.894178 18.07758 7.113184 6.928862 14.1307 6.405575 7.159685 18.0564 6.307894 7.145877 21.86088 6.163749 7.126098 25.48899 6.13812 7.122853 25.9966 6.098767 7.116326 26.82873 6.047666 7.113575 27.5676 5.906746 7.126975 28.24294 5.843826 7.131947 28.44044 5.632027 7.14399 28.98474 5.36699 7.154725 29.50231 5.054192 7.163868 29.98761 4.969207 7.165923 30.10317 4.590095 7.173413 30.55791 4.16885 7.179584 30.97396 3.668209 7.185136 31.37819 3.161415 7.189461 31.70914 2.628843 7.192987 31.98723 2.071174 7.19582 32.21291 1.98335 7.196204 32.24285 1.398079 7.19834 32.40692 0.8035975 7.199974 32.51274 0.2003641 7.201107 32.55762 5.762869 7.250001 14.11207 5.675354 7.250001 18.03386 5.525314 7.250001 21.82267 5.312565 7.250001 25.42945 5.276356 7.250001 25.93277 5.215616 7.250001 26.76375 5.157453 7.250001 27.48125 5.074515 7.250001 28.06857 5.035527 7.250001 28.23786 4.889599 7.250001 28.7134 4.693899 7.250001 29.17136 4.45031 7.250001 29.60722 4.38249 7.250001 29.71183 4.072284 7.250001 30.12718 3.717063 7.250001 30.51198 3.285666 7.250001 30.88969 2.842149 7.250001 31.20156 2.370749 7.250001 31.46549 1.872346 7.250001 31.6813 1.793533 7.250001 31.71008 1.265215 7.250001 31.86875 0.7296031 7.250001 31.9722 0.1766514 7.250001 32.01872 -6.139247 6.118822 31.4501 -6.60299 6.132675 30.66662 -6.974275 6.146265 29.83333 -7.243227 6.160497 28.97196 -2.666579 6.058746 34.30193 -3.486445 6.068966 33.90298 -4.253383 6.080235 33.40923 -4.957001 6.092413 32.82958 -5.588457 6.10535 32.17337 -1.804869 6.049688 34.60039 -0.9122511 6.041904 34.7936 -0.4189936 5.256943 36.14844 -0.2983232 5.254923 36.16115 -0.2380096 5.253496 36.16754 -0.2079066 5.252484 36.17107 -0.1929088 5.25177 36.17313 -4.26976e-6 6.040175 34.87047 -8.196226 5.328102 27.14842 -8.013471 5.331378 28.65892 -7.960484 5.335484 29.00322 -7.835094 5.33239 29.63451 -7.550571 5.325636 30.58656 -7.159654 5.317699 31.49483 -6.667614 5.311002 32.34843 -6.082772 5.303604 33.13738 -5.413299 5.297412 33.85073 -4.669497 5.291636 34.48146 -3.858624 5.286251 35.02249 -2.992395 5.279702 35.46682 -2.082051 5.272113 35.80873 -1.139526 5.264225 36.04318 -0.6600115 5.259828 36.11961 -8.425985 5.321771 25.02751 -7.661643 6.202283 24.5373 -7.844691 6.221988 20.97053 -8.754754 5.316602 21.39291 -7.988033 6.226058 17.39645 -9.002065 5.312981 17.75186 -8.089195 6.218632 13.81764 -9.167704 5.310708 14.1066 -8.463363 5.943923 10.45458 -9.251976 5.309351 10.45888 9.180071 5.355895 11.45284 9.194723 5.355411 10.45858 8.429995 5.970772 10.45444 8.173054 5.374787 26.96642 8.158229 5.375741 27.09452 8.013379 5.369795 28.43385 7.945167 5.372205 28.90305 7.893598 5.369786 29.20933 7.766856 5.367555 29.76882 7.185943 6.165552 29.14192 7.5365 5.364545 30.50816 6.899866 6.151835 29.9909 7.237434 5.360424 31.23187 6.51988 6.137983 30.801 6.868804 5.35554 31.93389 6.807956 5.354804 32.036 6.050512 6.124092 31.56166 6.372849 5.350505 32.68315 5.496481 6.110518 32.26443 5.874354 5.347132 33.29139 5.557457 5.345206 33.62487 4.865204 6.097502 32.90084 4.965518 5.341571 34.16297 4.164956 6.085244 33.4619 4.327429 5.337533 34.64297 3.404319 6.073904 33.93874 3.647135 5.333501 35.06034 3.202916 5.331367 35.28657 2.592684 6.063617 34.32349 2.475112 5.327723 35.58974 1.748041 6.054503 34.60869 1.72123 5.323397 35.82393 0.8830307 6.046661 34.79089 0.9438868 5.318888 35.98543 0.6864239 5.317237 36.02209 7.641782 6.208024 24.67224 7.830319 6.227852 21.06957 7.977522 6.231922 17.46137 8.081075 6.224427 13.84902 9.065228 5.35841 15.34226 8.565848 5.367347 23.05013 8.631236 5.366159 22.28976 8.857652 5.362141 19.24497 -0.8282676 -10.00261 16.56816 -1.17991 -10.03591 18.84108 -1.795868 -9.919657 18.41433 -1.381423 -9.684778 23.91544 -1.910705 -9.593265 23.69929 -1.728226 -9.80045 22.47561 -2.417778 -9.501431 23.43634 -2.899274 -9.40919 23.12927 -2.622211 -9.629357 21.93983 -8.975675 3.327797 29.9487 -8.740868 3.335774 30.98248 -8.482506 4.088681 30.54604 -7.763696 5.0847 30.55836 -7.887042 4.764194 31.00955 -7.475079 4.791711 31.92643 -8.176746 5.056889 28.79106 -8.187268 5.056338 28.71572 -8.385834 4.716763 29.03331 -9.244093 -6.025268 10.43264 -9.023267 -6.235013 10.43054 -8.708486 -6.549356 12.4437 -8.4698 -6.717787 10.42585 -7.973591 -7.105356 10.42245 -7.667121 -7.371011 11.99337 -7.631461 -7.3508 10.4206 -6.793745 -7.885352 10.41798 -6.555766 -8.061009 11.54078 -0.3659371 4.954998 36.59686 -0.1788346 5.24928 36.17806 -0.1833996 5.24798 36.17995 -0.1903739 5.246942 36.18125 -0.2046549 5.245497 36.18276 -0.2335158 5.243469 36.18426 -0.2914849 5.240599 36.18497 -0.4075518 5.236489 36.18243 -0.3789625 4.304491 37.28946 -0.3947318 1.000548 38.43544 -0.3935862 1.555152 38.43144 -0.3924353 2.082448 38.36514 -0.3926249 -2.211235 37.00563 -0.394386 -1.686684 37.40715 -0.3954808 -1.097948 37.80733 -0.3955783 -0.3769675 38.14901 -0.3953253 0.3552998 38.35584 -0.3838114 -4.173787 35.23898 -0.3778685 -5.045503 34.29134 -0.3311452 -8.402307 28.97618 -0.3181836 -8.874138 27.81201 -0.3037687 -9.276018 26.62434 -0.2877258 -9.607176 25.41771 -0.2698023 -9.867074 24.19653 -0.5966383 -10.14927 20.3684 -0.5183323 -10.15157 19.16793 -0.2153151 -9.933702 14.59466 -0.3598756 -10.07761 16.85741 -0.3785761 -9.755862 10.43301 -0.3433642 -9.757372 10.43266 -0.7699123 -9.755916 11.49227 -0.201987 -9.762496 10.43145 -2.559145 -9.499186 11.00945 -1.873984 -9.609971 10.43964 -0.9900102 -9.727519 11.10073 -0.7303542 -9.735919 10.43598 -0.4489738 -9.752577 10.43368 -4.140629 -9.082796 10.68915 -4.232065 -9.045784 10.42701 -3.811857 -9.178237 10.42912 -4.835441 -8.828118 10.42433 -5.387127 -8.622427 11.10074 -5.833247 -8.395486 10.41993 -9.949084 -5.27536 10.44025 -9.658994 -5.597354 12.88171 -10.17064 -5.008858 10.44296 -10.49244 -4.515915 13.29784 -10.7235 -4.254908 10.45036 -10.85513 -3.927372 13.49469 -11.1894 -3.475956 10.45739 -11.17506 -3.308202 13.68249 -11.5664 -2.67165 10.46374 -11.44644 -2.659923 13.86005 -11.72602 -2.242557 10.46662 -11.66017 -1.994396 14.02832 -11.94008 -1.479565 10.47065 -11.81282 -1.317061 14.18616 -12.06613 -0.7102823 10.47267 -12.0255 -0.5181607 12.27965 -12.10039 -0.1639051 10.47256 -12.04033 0.1588214 12.35277 -12.07265 0.5720465 10.46945 -11.99129 0.8235837 12.39742 -12.0392 0.8526493 10.46715 -11.95957 1.291274 10.46345 -11.84117 1.596678 12.40059 -11.88247 1.597572 10.46149 -11.79833 1.869819 10.46046 -11.53844 2.433661 12.37536 -11.53336 2.525335 10.46001 -11.0091 3.249302 14.41675 -11.19122 3.152677 10.46109 -10.47278 3.985145 14.30607 -10.6055 3.965643 10.46265 -11.07574 3.333071 10.46151 -10.06757 4.554339 10.46249 -9.869148 4.645704 14.17904 -10.18059 4.024818 18.38313 -9.379745 5.097725 14.18561 -9.615549 4.678227 18.15144 -9.193511 5.090958 18.09305 -9.258139 4.703052 22.11635 -8.910894 5.081085 21.99242 -8.797971 4.716946 26.07255 -8.540869 5.066905 25.79068 -8.5296 4.718082 28.04704 -8.3056 5.054459 27.82284 -8.011596 5.072613 29.69552 -7.424738 5.098372 31.38827 -6.966448 4.816766 32.77998 -6.996016 5.110725 32.186 -6.369426 4.839589 33.56412 -6.482823 5.123703 32.93465 -5.691993 4.860447 34.27283 -4.941901 4.87959 34.90006 -4.854917 5.156594 34.54647 -5.229691 5.150668 34.24602 -5.589603 5.144153 33.9232 -5.893143 5.137866 33.62086 -2.888416 5.187973 35.64844 -3.720394 5.173275 35.26971 -4.126752 4.897228 35.4397 -4.055477 5.168061 35.08286 -4.500451 5.161708 34.80084 -0.6394383 5.230467 36.16876 -1.34034 5.216632 36.07935 -1.366122 4.942363 36.47051 -2.009196 5.20436 35.93341 -2.331356 4.928539 36.23126 -3.254071 4.91351 35.88553 -9.756226 4.055003 22.44841 -9.567209 3.326191 26.86787 -9.200078 4.072939 26.49903 -9.18321 3.328248 28.92356 -8.872497 4.075876 28.51792 -8.696244 4.075495 29.52559 -8.193717 4.734112 30.03566 -8.738519 1.561324 32.51781 -9.093746 1.561363 31.46446 -8.776261 1.062932 32.52498 -9.134951 1.071801 31.47113 -8.789598 0.53015 32.4708 -9.151165 0.5533595 31.41979 -8.784212 -0.04693657 32.33062 -9.148913 -0.004142284 31.28701 -8.761756 -0.6183421 32.0997 -9.13029 -0.5557721 31.06841 -8.725401 -1.117219 31.81753 -9.051524 -1.499285 30.51412 -8.678444 -1.581007 31.51628 -8.919942 -2.386257 29.89036 -9.437 2.486295 29.22358 -8.950487 2.487655 31.3033 -8.404789 3.359882 32.00827 -8.603549 2.502209 32.3472 -7.959167 3.382335 32.97292 -8.145204 2.515681 33.32814 -7.412605 3.403 33.86986 -7.584003 2.527962 34.23937 -6.773534 3.421867 34.69273 -6.928426 2.539019 35.07436 -6.050189 3.438997 35.4353 -6.186833 2.548876 35.82668 -5.250629 3.454475 36.09133 -1.411537 4.292891 37.1593 -2.408206 4.279843 36.91333 -3.361167 4.265368 36.55811 -4.262724 4.249453 36.10018 -5.105234 4.232039 35.54594 -5.881041 4.21302 34.90169 -6.582412 4.192249 34.17362 -7.201468 4.169554 33.36785 -7.730116 4.144771 32.49049 -8.160002 4.117802 31.54775 -4.382791 3.468385 36.65452 -3.454554 3.480794 37.11848 -2.473812 3.491745 37.47668 -1.448557 3.501259 37.72249 -0.386946 3.509346 37.84922 -5.367472 2.55758 36.48994 -4.434267 3.031225 36.87801 -3.494215 3.040956 37.34328 -2.501242 3.049393 37.7013 -1.463517 3.056583 37.94539 -0.3893976 3.06257 38.06884 -4.478515 2.565197 37.0577 -3.528117 2.57179 37.52347 -2.52449 2.577425 37.88063 -1.475979 2.58217 38.12252 -0.3911336 2.5861 38.24243 -3.575511 1.555585 37.72343 -3.555482 2.075549 37.65257 -4.514392 2.072493 37.18687 -8.270707 1.560909 33.50713 -8.304811 1.05417 33.51461 -8.315407 0.5075812 33.45744 -8.307247 -0.08838135 33.30954 -8.281609 -0.6785372 33.06578 -8.243153 -1.188592 32.76885 -8.19626 -1.658913 32.45344 -8.545907 -2.480588 30.86102 -8.737689 -3.229676 29.21027 -7.698848 1.560201 34.42555 -7.729195 1.045685 34.43314 -7.73728 0.4858749 34.37285 -7.726909 -0.1281721 34.21699 -7.699082 -0.7359868 33.96003 -7.659847 -1.25637 33.64838 -7.614389 -1.732862 33.3194 -8.066206 -2.57024 31.7679 -8.365038 -3.333944 30.14686 -8.507576 -4.02252 28.4882 -7.031476 1.559294 35.26639 -7.058004 1.03762 35.27388 -7.063889 0.4651837 35.2104 -7.052032 -0.1661328 35.04648 -7.023255 -0.7905558 34.77624 -6.984667 -1.320552 34.45016 -6.941897 -1.803003 34.1084 -7.490039 -2.655409 32.60524 -7.89086 -3.432962 31.02145 -8.138773 -4.133439 29.38897 -8.234118 -4.763872 27.7284 -6.277066 1.558286 36.02309 -6.299766 1.030089 36.0303 -6.30382 0.4456138 35.96366 -6.291314 -0.2021806 35.79175 -6.262959 -0.8422675 35.50843 -6.226439 -1.381322 35.16849 -6.187458 -1.869635 34.81486 -6.826142 -2.736518 33.36761 -7.323978 -3.527244 31.82868 -7.673123 -4.238869 30.22999 -7.871317 -4.87921 28.59178 -7.92331 -5.45674 26.92575 -5.444025 1.557271 36.68916 -5.462934 1.023187 36.69594 -5.465557 0.4272388 36.62626 -5.453288 -0.2362847 36.44665 -5.426764 -0.8912243 36.15075 -5.393656 -1.438935 35.79774 -5.359397 -1.933098 35.43327 -6.082812 -2.814061 34.0497 -6.672684 -3.617431 32.56345 -7.118939 -4.339576 31.0063 -7.416796 -4.988954 29.39804 -7.568447 -5.575021 27.74997 -7.579859 -6.099417 26.0849 -4.540718 1.556342 37.25812 -4.555907 1.016991 37.26437 -4.557499 0.4101192 37.19186 -4.546349 -0.2684349 37.00505 -4.523015 -0.9375483 36.69737 -4.494539 -1.493646 36.33229 -4.46578 -1.993699 35.95804 -5.268006 -2.888501 34.64617 -5.94484 -3.704151 33.22069 -6.484004 -4.436346 31.71308 -6.878288 -5.09408 30.14259 -7.12732 -5.687783 28.52001 -7.234669 -6.219208 26.86841 -7.208347 -6.690231 25.21056 -3.58707 1.011572 37.72908 -3.588008 0.3943082 37.65408 -3.578801 -0.2986172 37.46075 -3.559907 -0.9813428 37.14237 -3.537129 -1.545664 36.7664 -3.5145 -2.051685 36.38352 -4.389447 -2.960225 35.15161 -5.148 -3.787941 33.79523 -5.77571 -4.529872 32.34547 -6.26303 -5.195478 30.82088 -6.607039 -5.796146 29.23163 -6.808919 -6.333706 27.60093 -6.874378 -6.810133 25.95202 -6.812926 -7.228121 24.30752 -9.609663 1.566676 29.37514 -10.07116 1.572381 27.28065 -9.658235 1.08339 29.3817 -10.12702 1.094708 27.28703 -9.679 0.5830947 29.33541 -10.15213 0.611908 27.24586 -9.680564 0.05145573 29.21554 -10.1573 0.1051539 27.1389 -9.665639 -0.4736742 29.0182 -10.1458 -0.3945425 26.96274 -9.591991 -1.386062 28.51728 -10.07726 -1.276605 26.51511 -9.46221 -2.248382 27.95307 -9.949878 -2.114502 26.01049 -9.279105 -3.070888 27.33769 -9.766927 -2.916189 25.45985 -9.045361 -3.84783 26.68411 -9.530955 -3.677171 24.87484 -8.765447 -4.577667 25.99621 -9.246336 -4.395388 24.25893 -8.445875 -5.261528 25.26941 -8.920077 -5.070068 23.60807 -8.091594 -5.897717 24.50793 -8.557336 -5.699537 22.92611 -7.707394 -6.484614 23.71606 -8.163076 -6.282234 22.21689 -7.29756 -7.021224 22.89816 -7.741678 -6.817251 21.48435 -6.866123 -7.506799 22.0586 -7.297265 -7.303905 20.73241 -6.416959 -7.940635 21.20174 -6.833775 -7.741576 19.96498 -5.953559 -8.32229 20.33195 -5.411537 2.06892 36.61814 -6.238638 2.064754 35.9529 -6.987413 2.059921 35.19765 -7.649528 2.054355 34.35883 -8.216568 2.048013 33.44297 -8.680034 2.04088 32.45667 -9.031391 2.03299 31.40676 -6.397501 -7.712276 23.38059 -5.965847 -8.141921 22.43454 -5.521407 -8.516567 21.4742 -5.067411 -8.835829 20.50439 -2.543158 2.078172 38.00862 -2.55684 1.555083 38.0785 -2.564859 1.006992 38.08355 -2.56547 0.3798634 38.00648 -2.558925 -0.3268009 37.80753 -2.545545 -1.02267 37.47977 -2.529361 -1.595135 37.09423 -2.513357 -2.107221 36.7039 -3.454717 -3.02952 35.56045 -4.289522 -3.86922 34.28183 -5.001191 -4.620717 32.89851 -5.577921 -5.293878 31.4283 -6.014279 -5.90105 29.88056 -6.309078 -6.444107 28.27856 -6.465726 -6.925085 26.64589 -6.491575 -7.346749 25.00582 -6.09001 -7.828257 24.03479 -5.67333 -8.253875 23.04393 -5.244883 -8.623124 22.03826 -4.807796 -8.935627 21.02276 -4.365117 -9.191004 20.00247 -1.485911 2.080443 38.24836 -1.493277 1.554916 38.3167 -1.497833 1.003305 38.3212 -1.498364 0.3668435 38.24257 -1.495042 -0.3529375 38.03907 -1.488022 -1.061546 37.70348 -1.479137 -1.642136 37.30983 -1.470128 -2.160397 36.91328 -1.446783 -3.161495 36.06556 -2.471327 -3.096577 35.86704 -2.416598 -4.025357 34.96947 -3.376653 -3.948293 34.67509 -3.28133 -4.795928 33.74612 -4.167431 -4.709303 33.36714 -4.024844 -5.483798 32.41139 -4.829664 -5.389847 31.9601 -4.636804 -6.103232 30.97266 -5.355447 -6.003228 30.46241 -5.111372 -6.656165 29.45297 -5.741257 -6.551356 28.89728 -5.447415 -7.14469 27.87632 -5.988218 -7.036299 27.28857 -5.647972 -7.571623 26.26698 -6.101523 -7.460858 25.66007 -5.291625 -8.049222 25.21901 -5.71985 -7.940207 24.64862 -4.922408 -8.468242 24.14992 -5.324168 -8.362319 23.61665 -4.543308 -8.828166 23.06501 -4.917675 -8.726703 22.56936 -4.157115 -9.1286 21.96952 -4.503348 -9.032979 21.51189 -4.084097 -9.280763 20.4494 -3.662609 -9.469944 19.38709 -3.225723 -9.563592 16.64654 -4.143046 -9.306827 18.55569 -4.510089 -9.150651 17.68901 -4.997079 -8.927577 18.57117 -5.863364 -8.468458 18.39949 -3.735373 -9.237111 11.73728 -1.872354 -9.658211 12.42818 -0.3886339 -3.224302 36.15011 -1.416566 -4.100512 35.15936 -1.379634 -4.963967 34.21373 -2.349768 -4.880783 34.03013 -2.271659 -5.666697 33.05237 -3.170001 -5.576022 32.77719 -3.044798 -6.298177 31.7597 -3.864535 -6.201458 31.40668 -3.688651 -6.860396 30.35802 -4.425245 -6.759055 29.94135 -4.197602 -7.355492 28.87139 -4.848751 -7.250927 28.40526 -4.570417 -7.786305 27.3247 -5.135951 -7.679901 26.82306 -4.279027 -8.261332 26.2166 -4.809853 -8.156082 25.74278 -3.977206 -8.675054 25.0863 -4.472071 -8.572328 24.64082 -3.667396 -9.026895 23.93923 -4.125345 -8.928094 23.52255 -3.351855 -9.316425 22.78072 -3.772221 -9.222971 22.39329 -3.415175 -9.456556 21.25839 -3.173123 -9.124848 24.31219 -2.646233 -9.222152 24.63853 -3.441895 -8.776754 25.48321 -2.870254 -8.877663 25.82832 -3.703659 -8.365359 26.63701 -3.088279 -8.468433 27.00048 -3.956313 -7.891269 27.76818 -3.298589 -7.995099 28.14966 -3.499336 -7.458722 29.27057 -2.759323 -7.560852 29.5986 -2.90736 -6.960439 30.69849 -2.087151 -7.059346 30.95817 -2.183753 -6.393559 32.02684 -1.287583 -6.487697 32.20315 -1.336366 -5.755919 33.23172 -0.3707152 -5.843709 33.3099 -2.343618 -9.785304 20.74925 -3.056491 -9.62877 20.12324 -2.064868 -9.877088 19.56281 -2.698134 -9.739622 18.99312 -2.090468 -9.31895 24.91527 -1.509598 -9.415344 25.13941 -2.266434 -8.977947 26.11834 -1.634612 -9.07772 26.34995 -2.437448 -8.570742 27.3034 -1.755747 -8.672415 27.54213 -2.602211 -8.098005 28.46521 -1.872167 -8.200127 28.71086 -1.982949 -7.662029 29.85117 -1.175624 -7.76234 30.02392 -1.233824 -7.157204 31.13237 -0.3532193 -7.254038 31.21634 -0.3625108 -6.58061 32.28357 -0.6780547 -10.09485 21.60765 -0.7568612 -9.970499 22.84708 -0.8333202 -9.776032 24.08209 -0.907414 -9.511403 25.30792 -0.9789839 -9.177062 26.51976 -1.047783 -8.773532 27.71292 -1.113466 -8.301548 28.88255 -0.3427898 -7.861816 30.1124 -1.358505 -10.01353 20.02579 -1.543952 -9.940498 21.24943 -6.354706 -8.129874 19.18603 -5.479207 -8.651395 19.45363 -4.606993 -9.099308 19.52994 -3.919662 -9.389118 18.98242 -2.832628 -9.684205 17.30621 -2.351519 -9.802574 17.89902 -1.671832 -9.851323 15.80828 -1.26871 -9.927206 16.21609 -0.7926098 -9.855974 14.09332 -0.5110357 -9.894936 14.3603 -0.2411265 -9.812434 12.2124 -0.5215974 -9.784351 11.86982 -1.055147 -9.816782 13.7974 -1.293909 -9.777296 13.47617 -2.028559 -9.77477 15.35174 -2.330275 -9.697159 14.85321 -3.541464 -9.446037 15.96065 -4.856298 -8.995267 16.81957 -6.560366 -8.10255 16.27792 -7.578323 -7.343645 17.47496 -8.203486 -6.946146 14.96645 -4.922791 -8.85847 12.49837 -2.965212 -9.401456 10.43588 -7.161822 -7.736686 14.14142 -6.061588 -8.372797 13.31013 -5.49495 -8.68422 15.07056 -4.407908 -9.093906 13.88959 -3.842784 -9.328786 15.27269 -2.830592 -9.544154 13.82022 -1.504372 -9.737381 13.13318 -0.05398267 -9.766386 10.42953 -11.8874 0.7919411 14.53547 -11.52014 0.7303043 18.79869 -11.74542 1.595047 14.54292 -11.39644 1.589857 18.81484 -11.44392 2.447494 14.49964 -11.11064 2.469075 18.73669 -10.21173 3.311666 22.73728 -10.69233 3.28548 18.5853 -10.95393 0.213192 22.95699 -11.54052 0.3222145 18.74342 -11.92771 0.08012467 14.4568 -10.58531 2.482497 22.95293 -10.83812 1.58224 23.06336 -10.90754 1.117984 23.06903 -10.94132 0.6704155 23.03811 -11.90323 -0.625016 14.33013 -9.867882 2.487318 27.14167 -10.25063 2.486022 25.05116 -10.48067 1.577579 25.1764 -9.468623 5.102146 10.4603 -10.94964 -0.2361478 22.82316 -11.54395 -0.07781457 18.65189 -10.89321 -1.058095 22.48235 -11.50219 -0.8406488 18.41811 -10.77388 -1.847231 22.09745 -11.3952 -1.581153 18.1535 -10.59544 -2.607359 21.67705 -11.22688 -2.299831 17.86411 -10.3601 -3.336487 21.23007 -10.99896 -2.997158 17.55614 -10.07199 -4.031457 20.75921 -10.71526 -3.668833 17.23151 -9.738985 -4.687741 20.26149 -10.38436 -4.306634 16.88825 -9.366563 -5.303712 19.7399 -10.01194 -4.908985 16.52849 -8.95994 -5.877941 19.19741 -9.603348 -5.4746 16.1543 -8.523593 -6.409687 18.63706 -9.163008 -6.002915 15.76781 -8.061732 -6.898406 18.06191 -3.024927 5.225576 35.53471 -3.905423 5.219711 35.09627 -9.282405 5.197907 14.11158 -9.368814 5.198729 10.46098 -9.114001 5.196362 17.75978 -8.8629 5.193829 21.40381 -8.528305 5.190131 25.0414 -8.110517 5.183227 28.67383 -7.94388 5.182941 29.6482 -7.659985 5.187808 30.61494 -7.264051 5.193401 31.53728 -6.764955 5.198394 32.40314 -6.168833 5.203955 33.20143 -5.842041 5.207256 33.56631 -5.48636 5.21027 33.92051 -4.729451 5.215091 34.5548 -0.6385607 5.242798 36.14931 -0.6641237 5.242588 36.1467 -1.147505 5.239025 36.08135 -2.10074 5.232291 35.86421 -0.420185 5.244855 36.16789 -0.4075946 5.244995 36.16875 -0.2986989 5.246395 36.17504 -0.2916312 5.246501 36.17537 -0.238129 5.247458 36.17744 -0.2336288 5.247554 36.17757 -0.2079394 5.248198 36.17812 -0.2047272 5.248295 36.17816 -0.1929121 5.248721 36.17816 -0.1904176 5.248843 36.17811 -0.1834253 5.249236 36.17787 -9.312627 5.256392 10.45996 0.4649258 -8.754372 9.45159 0.400155 -8.757364 9.45159 8.688623 4.48643 9.45159 -9.361458 3.846321 9.45159 -8.824794 4.337025 9.45159 -9.391529 -4.382029 9.45159 0.5944209 -8.747426 9.45159 -0.3015951 -8.758424 9.45159 -0.3343041 -8.757016 9.45159 -0.3997111 -8.753952 9.45159 8.567957 4.576233 9.45159 -0.6611782 -8.738437 9.45159 -1.724484 -8.621281 9.45159 -2.739852 -8.427307 9.45159 -8.625201 4.530184 9.45159 -7.836353 5.164918 9.45159 -7.03816 5.807591 9.45159 -9.835451 3.327757 9.45159 -5.783599 6.250001 9.45159 5.783602 6.250001 9.45159 10.90109 -1.773504 9.45159 10.77468 -2.139657 9.45159 9.590262 -4.223339 9.45159 9.416578 -4.442097 9.45159 0.3839601 -8.758062 9.45159 0.3191714 -8.76064 9.45159 0.05990064 -8.767826 9.45159 -10.34072 2.62678 9.45159 -9.890663 -3.701394 9.45159 -10.30703 -3.005436 9.45159 -10.24196 2.781059 9.45159 -6.123057 6.220981 9.45159 6.755628 5.997905 9.45159 7.038195 5.807565 9.45159 7.802975 5.191774 9.45159 3.898729 -8.127357 9.45159 3.160605 -8.342164 9.45159 0.03688526 -8.768261 9.45159 -0.1707229 -8.763188 9.45159 -10.6397 -2.296036 9.45159 -10.77907 -1.921519 9.45159 -10.96414 -1.262381 9.45159 10.46343 -2.846138 9.45159 10.06852 -3.541032 9.45159 2.150695 -8.56315 9.45159 1.111652 -8.706876 9.45159 -3.527819 -8.219688 9.45159 -4.47419 -7.896047 9.45159 -5.400345 -7.4946 9.45159 -6.288612 -7.022965 9.45159 -7.061965 -6.529391 9.45159 -7.835033 -5.945512 9.45159 -8.546325 -5.309193 9.45159 -9.190311 -4.624103 9.45159 -10.85056 1.550998 9.45159 -11.10081 -0.1439077 9.45159 -10.98354 1.073933 9.45159 -11.07736 0.4767433 9.45159 -11.07182 -0.6058642 9.45159 -10.6298 2.09695 9.45159 -6.756373 5.997489 9.45159 -6.445614 6.137257 9.45159 6.122216 6.221126 9.45159 6.451905 6.13504 9.45159 7.347043 -6.379482 9.45159 6.623567 -6.865489 9.45159 8.815697 4.405948 9.45159 9.366852 3.913706 9.45159 11.06822 -1.117855 9.45159 11.15854 -0.4655661 9.45159 8.795086 -5.134777 9.45159 8.103401 -5.781947 9.45159 10.31524 2.781813 9.45159 10.62564 2.25436 9.45159 11.1752 0.03172099 9.45159 10.86711 1.711687 9.45159 11.01894 1.23339 9.45159 11.13228 0.6442295 9.45159 5.751183 -7.357392 9.45159 4.837853 -7.779589 9.45159 9.854786 3.392653 9.45159 0.6922578 5.289203 36.07096 0.9518316 5.288301 36.03853 1.736921 5.285924 35.8875 2.50005 5.28373 35.66154 6.90149 5.269014 32.09828 6.458023 5.271533 32.75178 5.951614 5.27356 33.36584 5.629735 5.274678 33.702 5.028066 5.276666 34.24284 4.379141 5.27875 34.72284 3.687807 5.280793 35.13822 3.237313 5.28189 35.36302 7.33974 5.26569 31.28584 6.963618 5.268589 31.99519 7.643245 5.263004 30.5534 7.874469 5.260675 29.80435 8.000881 5.258961 29.23683 8.117839 5.259331 28.44703 8.277883 5.257596 27.10308 8.688351 5.262751 23.05867 8.754128 5.263511 22.29793 8.981501 5.266069 19.2515 9.189353 5.268413 15.34639 9.303993 5.269968 11.4544 9.318601 5.270269 10.45769 9.25506 5.310509 10.45816 -8.985073 4.977538 9.632835 -9.069875 5.082954 9.746813 -8.280382 5.716584 9.745543 -9.182286 5.222692 9.993248 -8.416175 5.885297 10.07098 -8.866127 4.829677 9.528411 -8.076734 5.463571 9.527997 -8.708124 4.633265 9.460371 -7.617376 6.526717 10.06771 -7.581036 6.481598 9.950592 -7.481328 6.357807 9.743872 -7.277958 6.105312 9.527545 -7.351485 6.196599 9.585277 -8.889624 4.809513 9.528516 -9.113197 5.045695 9.747198 -9.152553 5.004308 9.746532 -9.261888 5.20256 10.07389 -9.286829 5.125031 9.99509 -8.724927 4.619844 9.460615 -8.911396 4.787492 9.528614 -9.053388 4.915152 9.634004 -7.177376 6.753783 9.950815 -6.999376 6.434022 9.585341 -6.732172 6.954175 9.951062 -6.27002 7.074288 9.951319 -5.783599 7.116024 9.95159 -6.61103 6.608822 9.585412 -6.207899 6.713593 9.585487 -5.783599 6.75 9.585565 -9.072481 4.631374 9.528547 -9.282046 4.880418 9.74757 -9.421235 5.045829 10.07495 5.783602 6.75 9.585565 5.783602 7.116024 9.95159 0.03688526 -9.718073 10.13831 -0.199429 -9.680731 10.05499 0.03688526 -9.704012 10.09853 0.03688526 -9.56084 9.841654 0.03688526 -9.278458 9.591483 0.03688526 -9.314276 9.613757 -0.1926106 -9.462795 9.737398 0.03688526 -9.534414 9.808784 0.03688526 -8.801299 9.452136 0.03688526 -8.964963 9.47112 -0.1825439 -9.141029 9.525795 0.03688526 -9.006161 9.480291 -0.3399608 -9.675975 10.05583 -0.3749731 -9.674571 10.05607 -0.4449738 -9.671491 10.05653 -0.7247819 -9.65557 10.05811 -1.862096 -9.531348 10.06064 -2.947052 -9.322959 10.05805 -3.788432 -9.099185 10.05339 -4.805169 -8.750014 10.0501 -5.796445 -8.318902 10.04707 -6.750534 -7.811579 10.04574 -7.583154 -7.281125 10.04754 -8.416875 -6.653397 10.05114 -9.187232 -5.966916 10.05581 -9.888875 -5.223683 10.06106 -10.10941 -4.9596 10.06293 -10.65981 -4.21258 10.06806 -11.12371 -3.440926 10.07293 -11.49912 -2.644379 10.07734 -11.65807 -2.219519 10.07935 -11.87121 -1.464236 10.08215 -11.99655 -0.7029751 10.08356 -12.03041 -0.1625053 10.08348 -12.00205 0.5652869 10.08132 -11.88862 1.275475 10.07714 -11.72861 1.846367 10.07506 -11.46678 2.493767 10.07475 -11.12881 3.114089 10.0755 -11.01466 3.292634 10.07579 -10.54935 3.919128 10.07658 -10.01605 4.502676 10.07647 -0.3308547 -9.458194 9.737822 -0.3653223 -9.456834 9.737944 -0.4342373 -9.453846 9.738179 -0.7097156 -9.438322 9.738986 -1.829571 -9.316249 9.740271 -2.897969 -9.110788 9.738952 -3.726445 -8.889995 9.736582 -4.726222 -8.546319 9.734912 -5.701719 -8.121771 9.733376 -6.63994 -7.622767 9.732698 -7.458562 -7.10142 9.733612 -8.278215 -6.484697 9.735441 -9.035112 -5.810804 9.737815 -9.723828 -5.082022 9.740486 -9.94008 -4.823364 9.741439 -10.47921 -4.092548 9.74405 -10.93278 -3.339112 9.746536 -11.29899 -2.563264 9.748792 -11.45376 -2.150253 9.749818 -11.66091 -1.417437 9.751254 -11.78243 -0.6804893 9.751976 -11.81515 -0.1581989 9.751937 -11.7875 0.5447429 9.750827 -11.67782 1.228536 9.748688 -11.52372 1.777445 9.747626 -11.27142 2.401147 9.747467 -10.94499 3.000425 9.747852 -10.83448 3.17334 9.747999 -10.38299 3.781326 9.748405 -9.863498 4.349717 9.748349 -0.3173995 -9.136401 9.52591 -0.3510589 -9.135031 9.525943 -0.4183621 -9.132035 9.526006 -0.6874043 -9.116603 9.526225 -1.781287 -8.996932 9.526572 -2.825286 -8.796607 9.526215 -3.635066 -8.581619 9.525575 -4.610208 -8.246989 9.525124 -5.56292 -7.832924 9.52471 -6.478096 -7.346461 9.524527 -7.275921 -6.83799 9.524774 -8.074249 -6.236547 9.525267 -8.810339 -5.580134 9.525908 -9.478711 -4.871637 9.52663 -9.688138 -4.620665 9.526887 -10.20914 -3.913058 9.527594 -10.64589 -3.186129 9.528266 -10.99696 -2.440841 9.528878 -11.14478 -2.045502 9.529155 -11.34198 -1.346464 9.529544 -11.45725 -0.6463395 9.529741 -11.48826 -0.1516591 9.52973 -11.4624 0.5136134 9.529429 -11.35975 1.157707 9.528849 -11.21521 1.673663 9.528561 -10.97735 2.261724 9.528518 -10.66807 2.829195 9.528623 -10.56296 2.993579 9.528662 -10.13212 3.573509 9.528773 -9.633469 4.119066 9.528758 6.268814 7.074502 9.951332 6.206847 6.713781 9.585491 6.741189 6.951007 9.951081 7.176317 6.754397 9.95085 7.5811 6.481582 9.950636 7.481391 6.357792 9.7439 6.618896 6.606059 9.585418 6.998453 6.434559 9.585351 7.351541 6.196586 9.585289 0.06727612 -9.145163 9.525544 0.07356071 -9.46669 9.736467 0.07782489 -9.684849 10.05316 5.189451 -8.624837 10.04918 4.182149 -8.999258 10.05226 3.391329 -9.231242 10.05623 2.312589 -9.469038 10.06024 1.201588 -9.622481 10.0597 0.6481726 -9.664845 10.05731 0.5095877 -9.671915 10.05647 0.4402676 -9.674919 10.05601 0.4229349 -9.675614 10.05589 0.3531839 -9.67823 10.05552 6.166544 -8.171677 10.04611 7.105455 -7.642258 10.04611 7.884573 -7.120066 10.04836 8.701033 -6.477219 10.0523 9.451148 -5.778196 10.05714 10.12972 -5.025207 10.06247 10.32051 -4.786033 10.06415 10.84904 -4.035573 10.06921 11.29026 -3.262974 10.07398 11.64256 -2.467354 10.07821 11.78717 -2.050681 10.08007 11.98015 -1.29738 10.0826 12.08546 -0.5392682 10.08364 12.10479 0.04381424 10.0832 12.05306 0.7635171 10.0802 11.91608 1.466252 10.0762 11.73417 2.037595 10.07479 0.3331807 -9.138584 9.525868 0.4000158 -9.136049 9.525918 0.4166803 -9.135371 9.525935 0.4833288 -9.132446 9.525999 0.6165772 -9.125583 9.526114 1.14876 -9.084663 9.526442 2.217509 -8.937013 9.526516 3.255666 -8.708473 9.525966 4.015307 -8.485993 9.525421 4.982289 -8.126815 9.524998 5.921595 -7.691471 9.524579 6.821273 -7.184175 9.524579 7.567783 -6.683608 9.524886 8.349226 -6.067935 9.525426 9.065492 -5.399973 9.52609 9.711171 -4.682974 9.526823 9.892136 -4.455947 9.527055 10.39186 -3.745904 9.527753 10.80665 -3.019168 9.528411 11.13559 -2.27593 9.528998 11.26986 -1.88886 9.529256 11.44815 -1.192651 9.529607 11.54489 -0.4962867 9.529751 11.56259 0.03676134 9.52969 11.51551 0.6938774 9.529273 11.3917 1.330143 9.52872 11.22715 1.84702 9.528524 10.96746 2.430819 9.52854 10.6362 2.994382 9.528662 10.14843 3.642037 9.528779 9.635574 4.189639 9.528741 9.059931 4.703013 9.528497 0.3451089 -9.460382 9.737666 0.4136847 -9.457845 9.737854 0.4307484 -9.457171 9.737915 0.4989932 -9.454257 9.738148 0.6354312 -9.447378 9.738577 1.180313 -9.405895 9.73979 2.274311 -9.254852 9.740066 3.336586 -9.020294 9.738029 4.114671 -8.791672 9.736011 5.105518 -8.423062 9.734444 6.06713 -7.976782 9.732888 6.990118 -7.456342 9.732889 7.756165 -6.943151 9.734027 8.558751 -6.311691 9.73603 9.295609 -5.625655 9.738488 9.961437 -4.887608 9.741203 10.14845 -4.653448 9.74206 10.66595 -3.919569 9.74464 11.09714 -3.165613 9.747073 11.44062 -2.391106 9.749237 11.58135 -1.986298 9.75019 11.76881 -1.255775 9.751483 11.87085 -0.5222045 9.752016 11.88948 0.04101377 9.75179 11.8392 0.7358121 9.750254 11.70696 1.411972 9.74821 11.5318 1.961529 9.747488 11.25667 2.580122 9.747547 10.90769 3.174184 9.747999 10.39674 3.852922 9.748429 9.862832 4.422994 9.748291 9.266599 4.954387 9.747386 11.44877 2.67929 10.07491 11.08786 3.293504 10.07579 10.56139 3.992752 10.07663 10.01356 4.577764 10.07636 9.403912 5.121403 10.07459 8.043339 5.490397 9.527984 8.246978 5.743395 9.745492 8.382781 5.912113 10.07088 8.808828 4.875677 9.528382 9.012705 5.129132 9.74696 9.148278 5.29767 10.07376 9.281205 5.205997 10.07314 9.172393 5.018989 9.746645 9.008863 4.737933 9.528296 8.906252 4.803048 9.528341 9.090476 5.071064 9.746809 9.213015 5.24934 10.07346 + + + + + + + + + + 0.887836 0.4472604 0.1081917 0.9890063 0.01377028 0.1472315 0.9328755 0.3580666 0.03913956 0.3424761 -0.9393126 -0.02005249 0.4775096 -0.8786113 0.00517714 0.3988472 -0.9101862 0.1117242 0.4110291 0.3750019 0.8309204 0.1731859 -0.9764173 0.1289027 0.06361109 -0.9975278 -0.02986598 0.03972601 -0.999104 -0.01460528 0.5382718 -0.8422185 -0.03052324 0.08617293 0.8310745 0.5494447 0.1778017 0.8197842 0.5443716 0.2809928 0.8059245 0.5210843 0.2165076 0.8098286 0.5452542 0.4778344 0.7636205 0.4342328 0.4204926 0.7605559 0.4947128 0.4177266 0.7738816 0.4760376 0.3721299 0.7815294 0.5007306 0.3603776 0.774879 0.5193175 0.3264725 0.7990508 0.5049096 0.2800139 0.7912107 0.5436708 0.570478 0.7096289 0.4134995 0.5203161 0.7474677 0.412993 0.4901888 0.7308685 0.4749171 0.6371098 0.6819059 0.3592986 0.5990822 0.7150208 0.3603411 0.573201 0.7162604 0.3980098 0.7046427 0.6445245 0.2967608 0.6737177 0.6733266 0.3045254 0.6455726 0.6884905 0.3304801 0.7621452 0.608694 0.2205142 0.7673404 0.6026867 0.2189924 0.7028419 0.664524 0.2538133 0.8043369 0.5849714 0.1041671 0.8017448 0.5860738 0.1171449 0.8051351 0.5757503 0.1423693 0.7914763 0.5925694 0.1497554 0.7671602 0.6142733 0.1847527 0.804756 0.5846249 0.1028676 0.7915282 0.6005231 0.1133813 0.7872961 0.6087752 0.09776449 0.779149 0.6183101 0.103052 0.7525303 0.653367 0.08252131 0.7503082 0.6558507 0.08305269 0.7208945 0.6896641 0.06837183 0.7141335 0.6975378 0.05877399 0.7008508 0.7111564 0.05536013 0.6813738 0.730934 0.03827816 0.6854304 0.7271888 0.03717064 0.6690392 0.7427706 0.02604985 0.8616356 0.506833 0.02654141 0.7984303 0.6015955 0.02432811 0.9627459 0.2696503 0.02022916 0.9471553 0.3201598 0.01986646 0.9333633 0.3578643 0.02767819 0.9899485 -0.1369939 0.03513991 0.7684313 -0.6398971 0.006728351 0.783008 -0.6218786 0.01286137 0.7914478 -0.6109645 0.01824474 0.8187894 -0.5739773 0.01157629 0.8690219 -0.4939655 0.02826768 0.7385444 -0.6742026 -0.001745283 0.7092674 -0.7049242 0.0046494 0.6979802 -0.7161107 -0.003053545 0.625712 -0.7799127 -0.01486468 0.6198224 -0.7846682 -0.01077455 0.666887 -0.7450559 -0.01238954 0.4393678 -0.8981746 -0.01544344 0.4907586 -0.8703466 -0.0406562 0.5575364 -0.8301525 5.34341e-4 0.3472816 -0.9377058 -0.01017379 0.4005786 -0.9156627 -0.03314584 0.4359413 -0.8997555 -0.01987969 0.2794106 -0.9599087 -0.02247697 0.262069 -0.964385 0.03579831 0.2135595 -0.9763991 -0.03220754 0.1447637 -0.9894444 0.006584942 0.1370083 -0.9905346 -0.008364498 0.04300534 -0.9989486 -0.01588368 0.04612743 -0.9987893 -0.01709657 0.07976841 -0.9964314 -0.02759915 0.05345129 -0.9985534 -0.005852222 0.07817882 -0.9967149 -0.02115875 0.01870071 -0.9990905 -0.03832089 0.0819112 -0.9947316 -0.06164127 0.07562923 -0.9955967 -0.05538594 0.05710381 -0.9973277 -0.04557138 0.09058111 -0.9951971 -0.03712165 0.02446019 -0.9992945 -0.02850073 0.1220551 -0.9909411 -0.05602145 0.1192927 -0.9898278 -0.07752615 0.1566528 -0.9876436 0.004483103 0.1411755 -0.9166284 0.3739813 0.1495641 -0.9362694 0.3178527 0.1464117 -0.9364519 0.3187813 0.1714166 -0.9512633 0.2563483 0.1186921 -0.8735557 0.4720305 0.1066089 -0.8931404 0.4369606 0.06458157 -0.7938998 0.6046093 0.05046558 -0.6446517 0.7628089 0.01949167 -0.6748182 0.7377265 0.03141975 -0.3956232 0.9178754 0.02578121 -0.5236451 0.8515464 0.05246007 -0.5402148 0.8398904 0.02591198 -0.5960661 0.8025173 0.03611081 -0.6023945 0.7973813 0.02875483 -0.09260404 0.9952878 0.02048283 -0.181792 0.9831237 0.05546337 -0.2378496 0.9697172 0.006829738 -0.2804292 0.9598505 0.05355912 -0.4064013 0.9121236 0.01456874 0.3807218 0.9245749 0.03958159 0.6646459 0.7461094 0.05200415 0.6338112 0.7717378 0.09591794 0.5941008 0.7986513 0.03539896 0.5610451 0.8270281 0.0363872 0.5031793 0.8634157 0.02926558 0.8412573 0.5398423 -0.01241052 0.8135148 0.5814117 0.09446769 0.743668 0.6618413 0.07469791 0.7348746 0.6740769 0.03868305 0.6944616 0.7184893 0.9511857 0.2560541 0.1722856 0.9462943 0.2586383 0.1939935 0.9504934 0.2299913 0.2089651 0.9747678 0.04900902 0.217775 0.974694 0.03642779 0.2205554 0.9752425 -0.02243053 0.2199976 0.9744257 -0.03335338 0.2222207 0.9715584 -0.08677107 0.2203297 0.9522757 -0.2129786 0.2186575 0.9613712 -0.1726384 0.2143861 0.9624884 -0.1613175 0.2181581 0.9701039 -0.09753268 0.2222296 0.9412704 -0.2366567 0.24084 0.9445705 -0.2243668 0.2396795 0.9520434 -0.1852137 0.2435352 0.9548354 -0.1725404 0.2419075 0.9623696 -0.1154326 0.2460084 0.9640449 -0.1049346 0.2441439 0.9679415 -0.04823994 0.2465 0.9689602 -0.03770643 0.2443247 0.9692363 0.02236729 0.2451137 0.9695642 0.03469115 0.2423675 0.3758791 0.5854638 0.7182947 0.3674115 0.5925199 0.7168885 0.4577113 0.576912 0.6765153 0.4492468 0.5841616 0.6759679 0.5356523 0.5652347 0.6273646 0.5273316 0.5726761 0.6276652 0.6095868 0.5502131 0.5706747 0.6015211 0.5578703 0.5717982 0.6792303 0.5315452 0.5060693 0.6714668 0.5395047 0.508003 0.7439151 0.5089318 0.4331036 0.7364411 0.5173712 0.4358687 0.8025478 0.4821209 0.3513921 0.7953127 0.4913312 0.3550654 0.8535191 0.451057 0.2608693 0.846456 0.4614774 0.2656143 0.8881677 0.4235054 0.1783294 0.3258882 0.7205111 0.6120954 0.3240372 0.7218032 0.6115554 0.4006396 0.7073811 0.582323 0.3981344 0.7091855 0.5818462 0.4738012 0.6912698 0.5455809 0.4706115 0.6936764 0.545287 0.545264 0.6718193 0.5013443 0.5413148 0.6749889 0.5013666 0.6146764 0.6485927 0.4488881 0.6098939 0.6527371 0.4494039 0.681331 0.6210591 0.3873934 0.6756001 0.6265224 0.3886312 0.7439704 0.5887339 0.3160705 0.7371972 0.5959854 0.3183423 0.8007374 0.5512483 0.2344037 0.7928352 0.5609853 0.2381341 0.8446833 0.5135352 0.1509698 0.8247567 0.5413087 0.1635892 0.8465264 0.5183969 0.1210694 0.3172649 0.382991 0.8675604 0.3044161 0.467551 0.8298959 0.2104381 0.4747461 0.8545947 0.192793 0.6002846 0.7762019 0.2006997 0.5937148 0.7792447 0.1710554 0.739108 0.6515055 0.1717359 0.7386383 0.6518591 0.1492974 0.8172473 0.5566123 0.142431 0.8235223 0.5491124 0.1049577 0.4617531 0.8807769 0.0411396 0.4636181 0.8850795 0.05012178 0.4708968 0.8807634 0.211466 0.3702576 0.9045394 0.109084 0.3740227 0.920982 0.104667 0.3645173 0.9252956 0.03226917 0.3660866 0.9300212 0.0253061 0.2516345 0.9674915 0.08070147 0.8247275 0.5597426 0.09253919 0.7437851 0.6619821 0.0923348 0.743929 0.6618489 0.1077581 0.5934618 0.7976161 0.1004253 0.5997384 0.7938696 0.1091997 0.4706776 0.8755216 0.2067806 0.4660179 0.8602728 0.2154445 0.379673 0.8996846 0.3138639 0.3737951 0.8727926 0.2167478 0.8105249 0.5441231 0.249567 0.7308891 0.6352303 0.2483263 0.7317426 0.6347337 0.2901614 0.5910505 0.7526392 0.2818957 0.5978714 0.7503896 0.3074069 0.4760199 0.8239576 0.4015457 0.4657343 0.7885764 0.4266709 0.4272261 0.7971386 0.500271 0.4171466 0.7587606 0.4902128 0.4270804 0.7597986 0.5835646 0.411543 0.7000606 0.5741101 0.4213345 0.7020506 0.6607989 0.4030264 0.6331782 0.6520997 0.4126392 0.6359992 0.7315911 0.3914323 0.5581715 0.7237209 0.4008877 0.5617094 0.7952917 0.3766201 0.4750458 0.7882589 0.3860063 0.4792149 0.8509157 0.3585332 0.3839225 0.844675 0.3680326 0.3886854 0.8971577 0.3372741 0.2852268 0.9566991 0.170948 0.2355923 0.9336712 0.1786312 0.3104016 0.9338262 0.1711707 0.3141165 0.8908817 0.1811588 0.416547 0.8905859 0.1737466 0.4203199 0.8369212 0.1823923 0.5160387 0.8361583 0.1749773 0.519829 0.7728312 0.1823552 0.6078476 0.7716037 0.1749063 0.6115844 0.6995496 0.1811194 0.6912497 0.6978575 0.1736412 0.6948696 0.6178362 0.1788005 0.765708 0.6157227 0.1713404 0.7691087 0.5283313 0.1755492 0.8306916 0.525857 0.1681534 0.8337859 0.4316094 0.1715024 0.8856073 0.4288612 0.1642616 0.8883109 0.3283375 0.166824 0.9297119 0.325407 0.1598472 0.9319652 0.2193871 0.1616822 0.9621477 0.2164143 0.155065 0.9639086 0.1059614 0.1562291 0.9820208 0.1030681 0.150085 0.983286 0.03723454 0.15064 0.9878873 0.006419658 0.05341327 0.998552 0.1027942 -0.09201294 0.9904378 0.102766 -0.09206819 0.9904356 0.1014682 -0.2376258 0.9660426 0.1019266 -0.2369561 0.9661588 0.09965747 -0.3944875 0.9134814 0.1001734 -0.3938276 0.9137095 0.09729427 -0.5384337 0.8370323 0.09729504 -0.5384352 0.8370313 0.0958569 -0.6006096 0.7937756 0.09622108 -0.6001175 0.7941035 0.09538072 -0.6377082 0.7643499 0.02252817 -0.6403 0.7677946 0.09020388 -0.6224704 0.7774278 0.2168912 -0.08914911 0.9721166 0.2163901 -0.09004998 0.9721453 0.2126298 -0.2336071 0.9487973 0.2125157 -0.23378 0.9487804 0.2048696 -0.3886065 0.8983393 0.2046825 -0.3888465 0.8982782 0.1939561 -0.5309274 0.8249225 0.1932361 -0.5318158 0.8245192 0.1872857 -0.59365 0.7826262 0.187238 -0.5936965 0.7826024 0.183094 -0.6328921 0.7522794 0.09846532 -0.6394975 0.7624616 0.0978651 -0.6850645 0.7218789 0.06272399 -0.6869212 0.72402 0.02914285 -0.7204152 0.6929305 0.3269684 -0.08415514 0.9412809 0.3260048 -0.08591544 0.9414561 0.3202009 -0.2262782 0.9199292 0.3195148 -0.2273167 0.9199118 0.3072881 -0.3782868 0.8731971 0.3063734 -0.3794636 0.873008 0.2889059 -0.5184369 0.8048333 0.2874013 -0.5202844 0.8041796 0.2773987 -0.5818398 0.7645342 0.2768781 -0.5824924 0.7642259 0.2693669 -0.6235775 0.7338887 0.1852799 -0.6341502 0.7506831 0.1801548 -0.6817346 0.7090713 0.1035779 -0.6880629 0.7182209 0.1032365 -0.7286433 0.6770681 0.07116156 -0.730601 0.6790863 0.0563507 -0.7474548 0.6619184 0.4317797 -0.07714414 0.898674 0.4304316 -0.07975077 0.8990931 0.4231419 -0.2157636 0.8799983 0.4219099 -0.2176837 0.8801171 0.4062328 -0.3636115 0.8383088 0.4046083 -0.3657765 0.8381525 0.3818694 -0.5009283 0.7766897 0.3795623 -0.5038119 0.7759549 0.3661583 -0.5650667 0.7393428 0.3650683 -0.5664183 0.7388474 0.354303 -0.6096554 0.7090767 0.2707266 -0.6243616 0.7327208 0.2609621 -0.6743682 0.6907434 0.1848209 -0.6841382 0.7055468 0.1799501 -0.7261614 0.6635569 0.1109139 -0.7323015 0.6718874 0.1106167 -0.7682033 0.6305772 0.06813037 -0.7709991 0.6331815 0.08228963 -0.7669233 0.6364412 0.5304111 -0.06823557 0.84499 0.5287443 -0.07167297 0.8457497 0.5206554 -0.2021878 0.8294807 0.5189569 -0.2049894 0.8298573 0.5011286 -0.3446318 0.7937878 0.498859 -0.3478183 0.7938276 0.4726055 -0.4782634 0.7402082 0.4695068 -0.4822698 0.7395805 0.4534991 -0.5431042 0.7066657 0.451813 -0.5452436 0.7060981 0.4380271 -0.5908539 0.6775131 0.3548924 -0.6100079 0.7084785 0.3405021 -0.6628406 0.6668588 0.2645954 -0.6762396 0.6875241 0.2550992 -0.7201104 0.6452639 0.1864352 -0.7291786 0.6584379 0.1816365 -0.7661269 0.6164882 0.1198683 -0.7721179 0.624072 0.1193827 -0.8041265 0.5823474 0.1010738 -0.8057011 0.5836351 0.05825203 -0.8239585 0.563648 0.1166332 -0.8379541 0.5331319 0.1293708 -0.8366727 0.532205 0.1301806 -0.8079911 0.5746334 0.1845846 -0.802154 0.567871 0.1895538 -0.769383 0.6100159 0.2510367 -0.760944 0.5982849 0.2604105 -0.7225643 0.6403805 0.3290508 -0.7103702 0.6221735 0.343181 -0.6642386 0.6640888 0.4191041 -0.6468643 0.6371172 0.4379339 -0.5908036 0.6776171 0.5205492 -0.5667384 0.6386204 0.5369578 -0.5186089 0.665373 0.5392699 -0.5155439 0.6658848 0.5569261 -0.4554148 0.6945724 0.5607212 -0.4502125 0.6949105 0.5885852 -0.3255766 0.739978 0.5913845 -0.3213478 0.7395945 0.6099769 -0.1893345 0.7694678 0.6120217 -0.185667 0.7687374 0.6202325 -0.06180328 0.7819797 0.6220955 -0.05756378 0.7808224 0.7060956 -0.0452826 0.7066673 0.7041566 -0.05027461 0.7082626 0.6965021 -0.1662927 0.6980198 0.6942331 -0.1708171 0.6991867 0.6762577 -0.2937403 0.6755681 0.6730971 -0.2990019 0.6764157 0.645574 -0.4164693 0.6401464 0.6412326 -0.4229256 0.6402771 0.6229793 -0.4818916 0.6161795 0.6200746 -0.4860108 0.6158743 0.6016629 -0.5366998 0.5915699 0.5198974 -0.5662946 0.6395446 0.4969891 -0.6259532 0.6009862 0.4208748 -0.6478287 0.6349665 0.4022225 -0.696654 0.5940458 0.3332353 -0.7123255 0.6176947 0.3192797 -0.7525422 0.5759695 0.2576658 -0.7636256 0.5920172 0.2481611 -0.797504 0.5499125 0.1939116 -0.8053634 0.560168 0.1886147 -0.8345334 0.5176665 0.1413435 -0.8401657 0.5235874 0.1400437 -0.8658661 0.4802747 0.0324645 -0.8735887 0.4855811 0.1675133 -0.8476319 0.5034477 0.7815907 -0.03155666 0.6229929 0.7797076 -0.03724694 0.6250349 0.7731814 -0.1442032 0.6175726 0.770857 -0.1495249 0.6192107 0.7547405 -0.2618052 0.6015188 0.7514227 -0.2680532 0.6029192 0.7261023 -0.3767147 0.5752057 0.7214475 -0.3844456 0.5759472 0.7037186 -0.4415813 0.5565844 0.7003251 -0.4468734 0.5566408 0.6807386 -0.4999912 0.5353538 0.6005607 -0.5358656 0.5934433 0.5742077 -0.5994126 0.5576648 0.4979382 -0.6265091 0.5996199 0.4750204 -0.6784694 0.5603882 0.4053481 -0.6981576 0.5901433 0.3868765 -0.7406396 0.5493447 0.3246505 -0.7547168 0.5700919 0.310638 -0.7900644 0.5284906 0.2560752 -0.800143 0.5423991 0.2462977 -0.8301267 0.5002272 0.1990208 -0.8374032 0.5090645 0.1932262 -0.8634073 0.4660381 0.1528318 -0.8687425 0.4710934 0.1508921 -0.8915712 0.427004 0.1325596 -0.8938634 0.4282945 0.1279459 -0.9168558 0.3781607 0.6131996 -0.7858579 0.08008497 0.6149994 -0.7844694 0.07989847 0.6566767 -0.7476416 0.09903466 0.6578022 -0.7466685 0.09890645 0.6007416 -0.7943538 0.09006428 0.6017953 -0.7935644 0.08998936 0.6439969 -0.7569932 0.1105869 0.6444399 -0.7566213 0.1105509 0.5614284 -0.8189188 0.1190389 0.5617878 -0.8186832 0.1189645 0.6024003 -0.785103 0.14397 0.602469 -0.7850534 0.1439533 0.6422693 -0.7477133 0.1685674 0.6856538 -0.7161128 0.1306189 0.6859485 -0.7158359 0.1305897 0.6986272 -0.7057585 0.1175801 0.6995188 -0.7048941 0.1174642 0.4767565 -0.8763899 0.06814616 0.5124276 -0.8450722 0.1525482 0.5094209 -0.8468103 0.1529794 0.5494253 -0.8152959 0.1828238 0.5461961 -0.8173525 0.1833158 0.5845075 -0.7831802 0.2120844 0.6422985 -0.7477146 0.1684507 0.6813365 -0.7061477 0.1927071 0.7259057 -0.6712356 0.1500126 0.7264218 -0.6706908 0.1499511 0.7391884 -0.6597142 0.1355651 0.7401961 -0.6586152 0.1354097 0.4677711 -0.8651417 0.1808872 0.4620527 -0.8681113 0.1813566 0.5003568 -0.8385071 0.2157523 0.4944306 -0.8418835 0.2162653 0.5303841 -0.8104114 0.2488496 0.5837033 -0.7831892 0.2142548 0.6204914 -0.7459211 0.242058 0.681435 -0.7061674 0.1922863 0.7196583 -0.6598252 0.2161544 0.7647285 -0.6219145 0.1685611 0.7657433 -0.6207057 0.1684096 0.778282 -0.609047 0.1527707 0.7796739 -0.6073291 0.1525123 0.4267652 -0.8807683 0.2052288 0.4188998 -0.8844945 0.2054085 0.4547105 -0.8565515 0.2440449 0.4466221 -0.8607435 0.244232 0.4796162 -0.8315078 0.280291 0.5285093 -0.8103929 0.2528666 0.5623462 -0.7766708 0.2838123 0.6198732 -0.7458301 0.2439152 0.6563295 -0.7038901 0.2716072 0.7198493 -0.6599263 0.2152078 0.7570536 -0.608235 0.2385792 0.8019185 -0.5677426 0.1859977 0.8036618 -0.5653816 0.1856648 0.8156679 -0.5533028 0.1689434 0.8176629 -0.5504906 0.1684862 0.3521872 -0.9355334 -0.02722972 0.4159433 -0.9093863 0.002780318 0.4130163 -0.9107114 0.004733979 0.4574701 -0.8888239 0.02670782 0.4313244 -0.9011984 0.04243618 0.4744883 -0.8775866 0.06857794 0.4332672 -0.8965371 0.09219974 0.3918183 -0.9179552 0.06194186 0.3592494 -0.9300074 0.07762825 0.3417078 -0.9364691 0.07912904 0.3087311 -0.9498895 0.04893994 0.3760943 -0.9264074 0.01795792 0.3017892 -0.953019 -0.02604132 0.284437 -0.9586751 -0.006151735 0.2322077 -0.9721402 -0.03198421 0.1418778 -0.9889702 -0.04252976 0.1376134 -0.9896919 -0.03965604 0.0829057 -0.9962229 -0.0258187 0.07827734 -0.9966489 -0.0237413 0.07060593 -0.9970879 -0.02882182 0.03326648 -0.9991903 -0.02263051 0.3886687 -0.8931112 0.2264708 0.3790977 -0.8973014 0.2261313 0.4118395 -0.8707352 0.2687162 0.4020168 -0.875431 0.2683343 0.431638 -0.848001 0.3075435 0.4765473 -0.8314062 0.2857733 0.5070083 -0.800554 0.3194617 0.5607541 -0.7764544 0.28753 0.5944947 -0.7382901 0.3185968 0.6559456 -0.7037574 0.2728755 0.6919354 -0.656517 0.3003513 0.7573554 -0.6085281 0.2368682 0.7933101 -0.5506834 0.2596287 0.8372221 -0.5081738 0.2020359 0.8398246 -0.5041193 0.2013914 0.8510245 -0.4919124 0.1837924 0.8537421 -0.4874764 0.1830062 0.3382509 -0.9301208 0.1430448 0.3307842 -0.9328267 0.1428857 0.3527815 -0.9029811 0.2452966 0.3418449 -0.9074558 0.2442668 0.3710377 -0.8819978 0.2905357 0.3598424 -0.8869929 0.2894081 0.385777 -0.8609888 0.3314734 0.4272974 -0.8477655 0.3141823 0.4541115 -0.8192122 0.3502487 0.5042709 -0.8001835 0.3246805 0.5347053 -0.7651562 0.3586453 0.5932545 -0.737935 0.3217158 0.6268405 -0.6946931 0.3528068 0.6918287 -0.6564509 0.3007411 0.7272311 -0.603004 0.3279042 0.7937427 -0.5513356 0.2569081 0.8282011 -0.4860687 0.2789625 0.8705997 -0.4417874 0.2165185 0.8737859 -0.435972 0.2154683 0.884108 -0.4236854 0.1970883 0.8872799 -0.4175654 0.195892 0.3184235 -0.9109627 0.2622089 0.3064035 -0.9156045 0.2603564 0.3316233 -0.8909983 0.3100776 0.3193495 -0.8961656 0.3080636 0.3413092 -0.8712596 0.3527248 0.3800957 -0.8605775 0.3390188 0.4030905 -0.8338406 0.3771311 0.4501392 -0.8186413 0.3566528 0.4768837 -0.7861784 0.393072 0.5324165 -0.7645686 0.3632734 0.5628184 -0.7247623 0.3974357 0.6260225 -0.6943132 0.3550002 0.6594443 -0.6450502 0.3860614 0.7274361 -0.6031852 0.3271152 0.7619957 -0.5424002 0.3537861 0.8287829 -0.4871893 0.2752555 0.8601403 -0.4156864 0.2955731 0.9002011 -0.3706835 0.2285429 0.9038656 -0.3626924 0.2268948 0.9130899 -0.3507154 0.2080038 0.9166129 -0.3424891 0.2062088 0.2869592 -0.9432112 0.167353 0.2771001 -0.946376 0.1660965 0.2849751 -0.9174665 0.2775691 0.2720974 -0.9222026 0.2747824 0.2929426 -0.8982026 0.3277449 0.2798314 -0.9034628 0.3247298 0.2975535 -0.8793564 0.3717451 0.3342491 -0.8706214 0.3609655 0.3532892 -0.8452965 0.4008251 0.397802 -0.8330286 0.3844699 0.4206295 -0.8026237 0.4229255 0.4734257 -0.7853294 0.3989059 0.5001437 -0.748402 0.435604 0.5610703 -0.7240836 0.4011272 0.5915147 -0.6785774 0.4354804 0.6591063 -0.6448381 0.3869919 0.6921534 -0.5885291 0.4178004 0.7625108 -0.5429685 0.3517991 0.7950471 -0.475153 0.3770012 0.8609176 -0.4174428 0.2907962 0.8882688 -0.3401149 0.3087077 0.9251925 -0.2959913 0.2375036 0.929274 -0.2850586 0.2349292 0.9371712 -0.2739735 0.2159831 0.9409631 -0.2628781 0.2132692 0.3612515 -0.9235478 0.1286747 0.3670651 -0.9212771 0.1284985 0.3309108 -0.9391999 0.09166055 0.3040412 -0.9472064 0.1017794 0.2942177 -0.950316 0.1016631 0.302951 -0.94028 0.1552233 0.3117412 -0.9372947 0.1558727 0.2820256 -0.9527124 0.1131396 0.2593733 -0.9583583 0.1194786 0.2546355 -0.9596941 0.1189454 0.2518621 -0.9227791 0.2916235 0.2383304 -0.9275617 0.2877988 0.2543771 -0.9039298 0.3438072 0.2406347 -0.9092346 0.3396872 0.2538425 -0.885652 0.3888247 0.2890456 -0.8784464 0.3805057 0.3040125 -0.8541855 0.4218333 0.34662 -0.8441979 0.4088821 0.3653675 -0.8154196 0.4489961 0.4159069 -0.8014801 0.4297106 0.4386203 -0.7669246 0.4684433 0.497328 -0.7474083 0.4405063 0.5241345 -0.7051583 0.4775299 0.5904201 -0.6779931 0.4378693 0.6207607 -0.6258564 0.4721862 0.6922944 -0.5886408 0.4174095 0.7241995 -0.5249869 0.4471286 0.795931 -0.4763371 0.3736265 0.8256089 -0.4013589 0.3965867 0.8893303 -0.342849 0.3025661 0.9055585 -0.2862227 0.3131137 0.9090023 -0.2771529 0.3112896 0.9192678 -0.2315837 0.3183013 0.9227963 -0.2210146 0.3155941 0.9341873 -0.1501023 0.3236719 0.9364469 -0.1418524 0.3208509 0.9428074 -0.07108837 0.3256695 0.9442687 -0.0640307 0.3228883 0.9457604 0.008630216 0.3247505 0.9467041 0.01588284 0.3217128 0.2292093 -0.9557225 0.1845477 0.2185471 -0.9270963 0.3045157 0.2045415 -0.931895 0.2995575 0.2153338 -0.9083908 0.35841 0.2011576 -0.9137084 0.3530901 0.209553 -0.8903824 0.4041126 0.2438302 -0.8844133 0.3979449 0.2545881 -0.8609124 0.4404712 0.2959061 -0.8527468 0.4304213 0.3104343 -0.825223 0.4718449 0.3593068 -0.8139375 0.4565133 0.3778291 -0.7812953 0.4968129 0.4346428 -0.7655858 0.4743039 0.4574019 -0.7260884 0.5133996 0.5221145 -0.704213 0.4811243 0.5489526 -0.6557863 0.518262 0.6202993 -0.6255556 0.4731903 0.6501356 -0.5660899 0.5068196 0.7249208 -0.5256775 0.4451441 0.7550175 -0.4541378 0.4729772 0.8269979 -0.4035452 0.3914408 0.8455982 -0.3470833 0.4055821 0.8493468 -0.33922 0.4044007 0.8628593 -0.2886154 0.4149399 0.8671364 -0.2787004 0.4127963 0.8838162 -0.1932826 0.4260408 0.8866719 -0.1854617 0.4235764 0.8965569 -0.09934306 0.4316444 0.8984625 -0.09271925 0.4291485 0.901682 -0.007508695 0.4323349 0.90305 -6.69041e-4 0.429535 0.1845355 -0.9305392 0.3162964 0.1702374 -0.9353334 0.310114 0.1752708 -0.9117029 0.3715885 0.1608676 -0.9170136 0.3649764 0.1641258 -0.8936728 0.417626 0.1979684 -0.8887509 0.4134374 0.2043865 -0.8657237 0.4568902 0.2449932 -0.8590697 0.4494192 0.2552026 -0.8324613 0.4918128 0.3029901 -0.8233442 0.4798972 0.317177 -0.7922147 0.5213392 0.3725984 -0.779577 0.5034184 0.3910549 -0.7423679 0.5440276 0.4543455 -0.7247671 0.5179603 0.4771521 -0.6795598 0.5572472 0.5477211 -0.6550925 0.5204377 0.5744526 -0.5995671 0.5572465 0.6504709 -0.5663398 0.5061097 0.679338 -0.4987471 0.5382854 0.7565173 -0.4558305 0.468935 0.7762217 -0.4006805 0.4867599 0.7799339 -0.3941063 0.4861928 0.7960334 -0.3396913 0.5009398 0.8006819 -0.3307762 0.4994956 0.8222296 -0.2327548 0.5193879 0.8254535 -0.2256182 0.5174196 0.8387464 -0.1256183 0.5298343 0.8409461 -0.1195842 0.5277399 0.8459251 -0.02291142 0.5328093 0.8476159 -0.01659268 0.5303509 0.2406356 -0.9523699 0.1873133 0.206272 -0.9593777 0.1924747 0.2182376 -0.9559857 0.1961218 0.1834865 -0.9625341 0.199652 0.1958491 -0.9591223 0.2042736 0.1377202 -0.9685649 0.2071599 0.1987215 -0.9687197 0.1486337 0.1858038 -0.9719456 0.144218 0.2129038 -0.9667423 0.1417087 0.2031429 -0.9692337 0.1389932 0.2301818 -0.9637085 0.1352119 0.2209752 -0.9661418 0.1331918 0.2409022 -0.9618728 0.1294875 0.2634072 -0.9481641 0.1777682 0.2526801 -0.9514446 0.1758013 0.2670263 -0.9636161 0.01187503 0.2338201 -0.9720021 0.0232439 0.2317896 -0.9724982 0.02282106 0.2077411 -0.9777573 0.0288878 0.2078964 -0.9777227 0.02893716 0.1924017 -0.9808114 0.03147476 0.1887903 -0.9815323 0.03086322 0.1841209 -0.9823422 0.03321921 0.1883518 -0.9815503 0.03290516 0.3084094 -0.9499961 0.04889899 0.2648944 -0.9621171 0.06451165 0.2683568 -0.9611012 0.06533914 0.2305736 -0.9701307 0.07538092 0.2362667 -0.9685988 0.07742422 0.2091197 -0.9744305 0.08218425 0.215015 -0.9730488 0.08333545 0.1961359 -0.9768181 0.08577483 0.2025624 -0.9753629 0.08738279 0.1948142 -0.9768818 0.08803194 0.1671048 -0.983904 0.06331789 0.3494142 -0.9364361 0.03157871 0.3456912 -0.9377992 0.03209775 0.2823961 -0.9592182 -0.01237672 0.2750208 -0.9613942 -0.009208261 0.2232319 -0.9746685 -0.01374846 0.205507 -0.9786238 -0.007906019 0.1982191 -0.9801144 -0.009225606 0.1858254 -0.9825631 -0.006230294 0.1804649 -0.983551 -0.007741212 0.1726387 -0.9849636 -0.006534218 0.1684309 -0.9856795 -0.008189976 0.1687237 -0.9856292 -0.008211195 0.1490072 -0.9884546 -0.02746498 0.1098636 -0.9927656 -0.04844105 0.1036265 -0.9935778 -0.0454396 0.05946165 -0.9976757 -0.03327953 0.09232664 -0.9944657 -0.05013763 0.09085446 -0.9946227 -0.0497117 0.1706565 -0.9844108 -0.04256564 0.1340424 -0.9901584 -0.04023641 0.1542028 -0.9873209 -0.03767037 0.1412025 -0.9893373 -0.03568708 0.1622141 -0.9861402 -0.03484499 0.1532564 -0.9876456 -0.03269207 0.1763255 -0.9837552 -0.03369009 0.1709767 -0.9847577 -0.03192728 0.1979128 -0.9795841 -0.03529202 0.1958886 -0.9800214 -0.03443729 0.2295338 -0.9724208 -0.04137575 0.2490362 -0.9671235 -0.05150949 0.3110516 -0.9501808 -0.02008855 0.6518411 -0.7571771 0.04226225 0.6847481 -0.7274945 0.04326623 0.6967076 -0.7153398 0.05373585 0.5060425 -0.8624913 -0.005465447 0.4822056 -0.8760581 -2.00913e-4 0.411448 -0.910969 -0.02908676 0.5120275 -0.8576389 0.04778546 0.5204232 -0.8529012 0.04146426 0.5251519 -0.8500192 0.04102134 0.5368402 -0.843124 0.03073316 0.5747598 -0.8176316 0.03361427 0.5820311 -0.8128018 0.02435672 0.5963548 -0.8024377 0.02132761 0.3559 -0.9340813 -0.02876353 0.3487688 -0.9372016 -0.003703355 0.2461253 -0.9680551 -0.04787212 0.240894 -0.9697757 -0.03879719 0.1638494 -0.9859803 -0.03156471 0.1929585 -0.9798219 -0.05211681 0.1346544 -0.9900343 -0.04123747 0.1631405 -0.9850662 -0.05504453 0.1167125 -0.9921829 -0.04417467 0.1429169 -0.9882358 -0.05445069 0.1005593 -0.9937849 -0.0477451 0.1295545 -0.9899566 -0.05658215 0.08891028 -0.9946182 -0.05319416 0.1217031 -0.9907256 -0.06042683 0.08107584 -0.9948955 -0.06008028 0.1187132 -0.9907795 -0.06529462 0.07678651 -0.9947181 -0.0681166 0.08598941 -0.9939278 -0.06865501 0.09496921 -0.9933048 -0.06577742 0.5080937 -0.8599618 0.04802745 0.4639911 -0.8854493 0.0263049 0.4734752 -0.8805893 0.01959025 0.4701251 -0.8825958 -0.002657294 0.4567505 -0.889557 0.008203387 0.3794703 -0.9248322 -0.02622419 0.3731005 -0.927588 -0.01940816 0.9207919 0.38962 0.01840358 0.8965215 0.4426581 0.01740664 0.8172308 0.5753979 0.03242254 0.8690391 0.4938615 0.02953058 0.8663076 0.4957642 0.06106799 0.9966231 0.06102687 0.0549376 0.9984795 -0.01753377 0.0522623 0.9992682 -0.01570147 0.03487962 0.9989902 -0.03341168 0.03003686 0.9977511 -0.03511303 0.05709469 0.9900593 -0.1307697 0.05178797 0.9874152 -0.1523385 0.04247647 0.9743465 -0.2209001 0.04303705 0.9683171 -0.2468125 0.03802186 0.9508337 -0.3071275 0.03985053 0.9446081 -0.3261855 0.03631156 0.9214411 -0.3870961 0.03321033 0.9147459 -0.4030196 0.02854984 0.8874347 -0.4600475 0.0285654 0.8524265 -0.5227095 0.01199132 0.8442779 -0.5328251 0.05737829 0.8735534 -0.4820882 0.06704783 0.8811215 -0.4682121 0.06635099 0.907946 -0.4122402 0.0754469 0.9153215 -0.395785 0.07443708 0.9385491 -0.3350881 0.08271396 0.9453232 -0.3158316 0.08132934 0.9634998 -0.2527199 0.08832335 0.9693896 -0.229834 0.08637297 0.9818874 -0.1657039 0.09186577 0.9864256 -0.1379815 0.0890268 0.9929739 -0.07317894 0.0929926 0.9952028 -0.04066574 0.08898067 0.9959026 -0.002318143 0.09040325 0.9945588 0.05775594 0.08670127 0.9950607 0.04980409 0.08587098 0.9829551 0.1422745 0.1164355 0.9857692 0.08055907 0.1475442 0.98071 0.1418129 0.1345248 0.975663 0.1688057 0.1399512 0.9816872 0.189161 0.02254712 0.9781246 0.2061522 0.02781552 0.9775779 0.2060472 0.04342979 0.934643 0.3531595 0.04148459 0.9325171 0.3540583 0.07109755 0.8747216 0.4801304 0.06585538 0.8699589 0.483596 0.0964697 0.9130548 0.344026 0.2190369 0.924497 0.3336187 0.1844011 0.865716 0.4697849 0.1727373 0.8709436 0.4646878 0.1597576 0.8536527 0.5030359 0.1350264 0.8554799 0.5012947 0.1298379 0.8199848 0.5620983 0.1080309 0.8247545 0.5581529 0.09080386 0.8008664 0.5937532 0.07791167 0.8051416 0.5904711 0.05559664 0.7945302 0.6051217 0.05049484 0.7972472 0.6031464 0.02472454 0.7298497 0.6832684 0.0215373 0.6661157 0.7456926 0.01524597 0.6733025 0.7391515 0.01785272 0.7273631 0.6858941 0.02218544 0.7252019 0.6873756 0.03996574 0.7393577 0.6717442 0.04593652 0.7360222 0.6742179 0.06084007 0.7641003 0.6408642 0.07378351 0.760644 0.6436771 0.08426547 0.8027141 0.5869414 0.1055935 0.8024733 0.5871697 0.106154 0.8239769 0.5514526 0.1302387 0.8189048 0.556462 0.1405172 0.8882127 0.4334427 0.1523338 0.8716755 0.4507163 0.1924494 0.9244083 0.3213708 0.2054024 0.8916322 0.3471712 0.2906271 0.9481467 0.2805593 0.1493463 0.9412468 0.2839324 0.1828577 0.9726071 0.1358584 0.1886215 0.9676496 0.1360127 0.2124966 0.9689807 0.1186697 0.2167806 0.9641363 0.118853 0.2373079 0.9650565 0.1016242 0.2415339 0.9428012 0.1023337 0.3172596 0.9424231 0.09461319 0.3207601 0.9002012 0.09503555 0.4249778 0.8993531 0.08752626 0.4283729 0.8459741 0.08732205 0.5260254 0.8446999 0.08009904 0.5292129 0.7811722 0.07943868 0.6192412 0.7795369 0.07257312 0.6221379 0.7067852 0.0716077 0.7037948 0.7048921 0.06517928 0.7063136 0.6236724 0.06404721 0.7790577 0.6216208 0.05812072 0.7811592 0.5325779 0.05693674 0.8444638 0.5304924 0.05160635 0.8461174 0.4341976 0.05047696 0.8994023 0.4322007 0.04580026 0.9006137 0.3292948 0.04481685 0.943163 0.3274989 0.0408684 0.9439674 0.2188441 0.04011648 0.9749349 0.2173368 0.03695535 0.9753969 0.1041181 0.036511 0.9938946 0.1029891 0.0341975 0.9940946 0.02866744 0.03420305 0.9990037 0.01522034 -0.08272159 0.9964565 0.8810232 0.4523819 0.13838 0.8864862 0.4426775 0.1348288 0.9039645 0.3950769 0.1635927 0.9033311 0.3956072 0.1657952 0.9143581 0.3588898 0.1874763 0.9093184 0.3631955 0.2030501 0.9497457 0.2303954 0.2118989 0.9495987 0.2148436 0.2282647 0.9474693 0.2335725 0.2185085 0.9202497 0.249332 0.3016193 0.9208813 0.2421078 0.3055511 0.876402 0.2603862 0.4051159 0.8766065 0.2531946 0.4092108 0.8220067 0.2694398 0.5017045 0.8217574 0.262105 0.5059803 0.7581996 0.2763354 0.5905693 0.7574539 0.2687604 0.5950056 0.6859208 0.2810655 0.671204 0.6846318 0.2732033 0.6757509 0.6058838 0.2836927 0.7432518 0.6040395 0.2755256 0.7478115 0.5186284 0.2843099 0.8063451 0.5162132 0.2758809 0.8108106 0.4245906 0.2830451 0.8600049 0.4216338 0.2744091 0.864248 0.3242644 0.280014 0.9035735 0.3208419 0.27126 0.9074572 0.2183217 0.2753455 0.9362267 0.2145389 0.2665994 0.9396265 0.1078192 0.2691891 0.9570331 0.1038126 0.2605834 0.9598538 0.01040023 0.2617425 0.9650818 0.03506773 0.1529465 0.9876121 0.9835823 0.1585296 0.08622252 0.979818 0.1577224 0.1228027 0.9913865 0.04531598 0.1228791 0.9901068 -0.03255856 0.1364864 0.9904941 -0.01221483 0.1370124 0.9895057 -0.0399757 0.1388538 0.9868514 -0.08602404 0.1368362 0.983269 -0.1158435 0.1405783 0.9742035 -0.1801822 0.135875 0.9688746 -0.20529 0.1383402 0.9543393 -0.268023 0.1319108 0.948268 -0.2880661 0.1334388 0.9281935 -0.3504121 0.125173 0.9217548 -0.3666949 0.1261068 0.8966906 -0.4271228 0.1162421 0.890144 -0.4404588 0.1167896 0.8614814 -0.4966328 0.1058573 0.7376924 -0.6716004 0.06901288 0.7440575 -0.6645304 0.06912147 0.7786057 -0.622134 0.08199137 0.7845968 -0.6145581 0.08201485 0.8179102 -0.5675438 0.09443026 0.8552752 -0.5071906 0.1061228 0.8238734 -0.5588675 0.09433937 0.8364707 -0.5449478 0.05786734 0.7983738 -0.6004393 0.04551994 0.7874966 -0.6151955 0.0371977 0.7568011 -0.6525322 0.03813046 0.7052481 -0.7086357 0.02146279 0.6930072 -0.7204934 0.02510458 0.6215705 -0.7833577 0.001007676 0.6041579 -0.7968413 0.006097435 0.5348556 -0.8447456 -0.01828187 0.5086544 -0.8609113 -0.01013398 0.4447994 -0.8949881 -0.03390806 0.4060693 -0.9136242 -0.01996076 0.3330137 -0.9416527 -0.04891115 0.3274593 -0.9440578 -0.03905719 0.2765206 -0.960756 -0.0220102 0.2774 -0.9594514 -0.05002325 0.2712682 -0.9614299 -0.04545593 0.3253373 -0.9454057 -0.01907396 0.3377034 -0.9408716 -0.02677953 0.4028885 -0.9152333 0.005402147 0.3830094 -0.9235941 0.01666599 0.4271573 -0.9031442 0.04321438 0.3926773 -0.9175961 0.0618233 0.4343622 -0.8960224 0.09205049 0.3951088 -0.9117773 0.1120328 0.9971891 0.07007932 0.02650976 0.9961673 0.08217 0.02998536 0.9955121 0.08098232 0.04896563 0.9804648 0.1903336 0.04961907 0.978568 0.1899179 0.07959878 0.9396106 0.3335898 0.07648503 0.9354383 0.3356112 0.1109979 0.9323176 0.3431782 0.1140733 0.9434773 0.3024643 0.1355205 0.9392465 0.3044025 0.158604 0.9719218 0.1688627 0.1638706 0.9786065 0.09790766 0.180952 0.9803177 0.07842081 0.1811832 0.981545 0.05150794 0.1841642 0.9829109 0.007965683 0.1839092 0.9823966 -0.01614278 0.1861091 0.9813191 -0.05258244 0.185062 0.9794756 -0.0760318 0.1866731 0.974014 -0.1326373 0.1835873 0.9693095 -0.1596826 0.1869238 0.9575448 -0.2242638 0.1811457 0.951672 -0.2465347 0.1831422 0.9350239 -0.3080921 0.1755267 0.9290335 -0.3251267 0.1766051 0.9069516 -0.386793 0.166823 0.9011093 -0.3999998 0.1673384 0.8741437 -0.4600441 0.1556677 0.8686802 -0.4702215 0.1558418 0.8382073 -0.5262992 0.1428912 0.8335897 -0.5335891 0.1428668 0.800159 -0.5857983 0.1287866 0.7962385 -0.5911427 0.1286655 0.7605723 -0.639221 0.1136946 0.7570211 -0.6434534 0.1135202 0.7197918 -0.6872541 0.09788578 0.7162094 -0.6910179 0.09766507 0.6780752 -0.730449 0.08159923 0.6739433 -0.734295 0.08131039 0.6354866 -0.7693693 0.0650224 0.6301438 -0.7737847 0.06462228 0.586378 -0.8087305 0.04599952 0.5708889 -0.8187901 0.06056928 0.5679287 -0.820825 0.06085485 0.5577799 -0.8271127 0.06903845 0.555603 -0.828565 0.06917768 0.52003 -0.8489964 0.09367126 0.5189768 -0.8496177 0.09387677 0.4719455 -0.8730633 0.1225893 0.4742797 -0.8718425 0.1222678 0.4291318 -0.8912652 0.1466023 0.4341503 -0.8888984 0.1461957 0.3906317 -0.9052935 0.1668845 0.3977735 -0.9022123 0.1667016 0.3555483 -0.9163041 0.1843153 0.3643722 -0.9127787 0.184575 0.3230794 -0.9250968 0.1995388 0.3332521 -0.9212937 0.2004024 0.2925171 -0.9322293 0.2130312 0.3037726 -0.928255 0.2146273 0.2632539 -0.9380902 0.2251319 0.2753704 -0.9340156 0.2275654 0.234731 -0.9429597 0.236069 0.2475331 -0.9388272 0.2394385 0.2064663 -0.9470277 0.2459886 0.2197797 -0.9428701 0.2503858 0.1780121 -0.9504246 0.2549608 0.191673 -0.9462615 0.2604813 0.1462697 -0.9536101 0.2631215 0.1939413 -0.9617096 0.1936532 -3.62742e-4 0.9999715 0.007552266 -0.003217816 0.9996954 0.02446967 0.006483137 0.9929114 0.1186804 -0.008982658 0.9589671 0.2833752 -0.5577657 0.8275663 0.06349492 -0.4099209 0.91148 -0.03419446 -0.3325792 0.9407415 0.06630772 -0.2510765 0.9674043 -0.03300839 -0.1129354 0.9923627 0.04961568 -0.08517521 0.996366 -1.80737e-4 -0.5855188 0.7860527 0.1982143 -0.5853551 0.7860627 0.1986578 -0.5648459 0.7913622 0.2338697 -0.5631192 0.7913236 0.2381256 -0.5248622 0.8116977 0.2562548 -0.5100109 0.8117372 0.2845551 -0.4741515 0.8291728 0.2960625 -0.4559074 0.8292026 0.3233752 -0.4238278 0.8437655 0.3292868 -0.4100451 0.8438875 0.3460015 -0.3864303 0.8515797 0.3542369 -0.3701722 0.8514837 0.3714138 -0.3441571 0.8626906 0.3705685 -0.3174835 0.8627154 0.3936071 -0.2953177 0.8720547 0.3902666 -0.2649644 0.8720534 0.4114812 -0.246294 0.8801227 0.4058614 -0.2128136 0.8801482 0.4243226 -0.1980921 0.8864774 0.4182313 -0.1630752 0.8864931 0.4330548 -0.1518024 0.8914522 0.4269298 -0.1161273 0.8914681 0.4379488 -0.1080382 0.8951572 0.4324597 -0.08681279 0.8953232 0.4368751 -0.08067172 0.8961246 0.436409 -0.05621021 0.8959209 0.440643 -0.05051839 0.8988051 0.4354278 -0.02182853 0.8989459 0.4375156 -0.02559477 0.897529 0.4402123 -0.645844 0.7508499 0.1382395 -0.6409679 0.760532 0.1036888 -0.6256086 0.7616412 0.1688685 -0.674454 0.7356888 0.06224101 -0.6743513 0.7356814 0.06342929 -0.6850463 0.7271234 0.04475754 -0.6834197 0.7271429 0.06481361 -0.6830713 0.7274212 0.0653606 -0.6838975 0.7281224 0.04606592 -0.681263 0.7285027 0.07186579 -0.02395439 0.9957369 0.08907532 -0.01082283 0.9958819 0.09001255 -0.01215219 0.9957665 0.09111177 -0.01720565 0.9957733 0.09022009 -0.01860886 0.9957409 0.09029901 -0.02292579 0.9957304 0.08941751 -0.02479362 0.9955825 0.09055912 -0.0321601 0.9955761 0.08828389 -0.03477966 0.9953768 0.08952945 -0.04197603 0.9953687 0.08648228 -0.04541087 0.9951139 0.08767133 -0.05223065 0.9951033 0.0839138 -0.05661028 0.9947774 0.08493101 -0.06272387 0.9947662 0.08065885 -0.06794798 0.9943871 0.08110159 -0.07324397 0.9943736 0.07652848 -0.07941675 0.9939165 0.07630902 -0.08250486 0.9939113 0.07302868 -0.088108 0.9935917 0.07080024 -0.09063881 0.9935762 0.06775718 -0.09836024 0.9929763 0.06575322 -0.1018009 0.9929569 0.06060564 -0.1105141 0.9922335 0.05709117 -0.1131732 0.9922121 0.0520277 -0.1225601 0.9913595 0.04674988 -0.1225422 0.9913598 0.04678887 -0.1275555 0.9911011 0.03805696 -0.1271159 0.991111 0.03925007 -0.1371157 0.9900738 0.03087627 -0.138548 0.9900368 0.02513426 -0.1496574 0.9886284 0.0147168 -0.1497347 0.9886265 0.01403945 -0.1501387 0.9885717 0.01358318 -0.1503049 0.9885724 0.01153337 -0.14754 0.9889401 0.01514995 -0.1479549 0.9889475 0.009602248 -0.1352335 0.9907402 0.0120778 -0.02562767 0.9632091 0.2675285 -0.03105205 0.9631584 0.267136 -0.03478193 0.9621006 0.2704676 -0.04967576 0.9621787 0.2678519 -0.05365717 0.9618851 0.2681383 -0.06650912 0.9618152 0.265496 -0.07179248 0.9604617 0.2689967 -0.09346097 0.9604493 0.2623022 -0.1008661 0.9586289 0.2661892 -0.1220735 0.9586142 0.2572103 -0.1317862 0.9562874 0.2610493 -0.1519603 0.9562656 0.2499281 -0.1643433 0.953293 0.2534244 -0.1825165 0.9532799 0.2407179 -0.1972759 0.9498342 0.2426877 -0.213106 0.9498086 0.2290188 -0.2305464 0.9456616 0.229287 -0.2399291 0.9456876 0.2193378 -0.255728 0.942829 0.2137212 -0.2635158 0.9427683 0.2043218 -0.2852891 0.937354 0.1999441 -0.2957619 0.9373195 0.1842749 -0.3203498 0.9308087 0.1759866 -0.3286836 0.9307713 0.1600999 -0.3552115 0.923126 0.1471841 -0.3556015 0.9231253 0.1462445 -0.3695309 0.9210951 0.1226001 -0.3688402 0.921112 0.1245388 -0.397154 0.9118839 0.1036167 -0.4018979 0.9117814 0.08445692 -0.4335908 0.8992049 0.05856239 -0.4355802 0.8991943 0.04146957 -0.4367077 0.8987081 0.04012519 -0.4375551 0.8987011 0.02969855 -0.4298889 0.9019641 0.0406996 -0.4311111 0.9019691 0.02439701 -0.3958564 0.9177258 0.03281849 -0.6276125 0.7771677 0.04596585 -0.6405926 0.7670379 0.0359714 -0.6676443 0.7427379 0.05090737 -0.6736626 0.7368494 0.05684834 -0.135564 0.99075 0.006075441 -0.1249927 0.9921269 0.007822394 -0.3968288 0.9177636 0.0153917 -0.3671895 0.9299041 0.0212239 -0.6288696 0.7771684 0.02307522 -0.5724215 0.8198078 0.01577788 -0.5867785 0.8094376 0.022399 -0.5863198 0.8093695 0.03391569 -0.1176739 0.9930519 9.43129e-4 -0.1130036 0.9935932 0.001683175 -0.3465096 0.9380444 0.001968204 -0.3332301 0.9428358 0.004282176 -0.1251541 0.9921319 0.00329554 -0.1176126 0.9930497 0.004451811 -0.3676584 0.9299244 0.008245289 -0.3463328 0.9380352 0.01198351 -0.5559956 0.8310924 0.01242738 -0.5561508 0.8310769 0.00278306 -0.5364294 0.8439179 0.006801605 -0.5364345 0.8439418 5.00196e-4 0.125943 0.9513481 0.281203 2.27831e-4 0.9999714 0.007563114 0.02037525 0.9994933 0.02445662 0.2526462 0.9675579 -0.001341819 0.08496522 0.9963627 0.006509602 0.558677 0.8293708 0.004916369 0.01336914 0.8998391 0.4360174 0.01762878 0.8998324 0.4358796 0.01558053 0.8995814 0.4364752 0.03968614 0.8993964 0.4353287 0.03566783 0.8970321 0.4405241 0.08718276 0.8969568 0.433437 0.08242225 0.8936985 0.4410327 0.133638 0.8936676 0.4283682 0.1282632 0.8893693 0.4388288 0.1616369 0.8896465 0.4270862 0.1535266 0.8888765 0.4316574 0.188162 0.8885134 0.4184961 0.1823934 0.882836 0.4328201 0.236485 0.8827416 0.4060079 0.2308126 0.8756929 0.4241317 0.285845 0.8755719 0.3894442 0.2808306 0.86695 0.4117426 0.3374475 0.866747 0.3672586 0.33428 0.8557102 0.39499 0.3899625 0.8555887 0.3404368 0.3876295 0.8433833 0.3720861 0.441056 0.8431193 0.3076031 0.4410777 0.8283687 0.3453348 0.4790806 0.8288419 0.2889691 0.466986 0.8248755 0.3185979 0.5048788 0.8239548 0.257286 0.5085568 0.8060997 0.302611 0.5541172 0.8057 0.2092884 0.5621721 0.7848817 0.2606211 0.6005033 0.784488 0.1548367 0.6133568 0.7613286 0.2101716 0.6373984 0.761781 0.1158152 0.6644402 0.7413111 0.09474796 0.6494658 0.7525705 0.1087747 0.6365811 0.7523586 0.1694735 0.6821323 0.7280176 0.06845337 0.6835526 0.7270147 0.06484955 0.6839275 0.7270027 0.06091183 0.6643235 0.7449185 0.06140649 0.679765 0.7322696 0.04124099 0.679027 0.7322968 0.051611 0.6646288 0.744841 0.05899584 0.6647836 0.7448499 0.05710941 0.6588648 0.7511336 0.04117822 0.6585873 0.7511417 0.04526644 0.6127546 0.789631 0.03185588 0.6129063 0.7896321 0.02875953 0.576613 0.8167766 0.0198366 0.5767366 0.8167767 0.01583641 0.5509925 0.8344465 0.01031363 0.5510491 0.8344491 0.006308317 0.4115116 0.9114046 2.46239e-4 0.3430113 0.9393017 0.007462739 0.3430234 0.9393037 0.006601214 0.3605378 0.9326894 0.01014637 0.3604603 0.9326889 0.01264023 0.3856109 0.9224754 0.01853084 0.3855221 0.9224743 0.02034586 0.4182009 0.9078775 0.02944099 0.4183756 0.907875 0.02692759 0.4228121 0.9054732 0.03672224 0.4235197 0.9054806 0.02712959 0.4327588 0.9006534 0.03928571 0.4332092 0.9006775 0.03331381 0.4369126 0.8986524 0.03913104 0.4334617 0.8982408 0.07262659 0.4178181 0.907592 0.04128897 0.4046016 0.9083251 0.1060331 0.4045243 0.9117856 0.07076144 0.3893047 0.9117009 0.1313151 0.3792341 0.9203329 0.09575462 0.3549197 0.9206389 0.1626538 0.3483297 0.9283691 0.1296041 0.319528 0.9286491 0.1884481 0.3161171 0.9352575 0.159259 0.2919126 0.9357188 0.1980339 0.2996611 0.9371671 0.178665 0.2757305 0.9370098 0.2144418 0.2749942 0.9424522 0.1901637 0.241498 0.9426214 0.2305288 0.242479 0.9471149 0.2101843 0.2077034 0.9472115 0.244233 0.2093262 0.9512691 0.2264284 0.1740503 0.9513884 0.2540997 0.1770024 0.9545531 0.2397885 0.1427834 0.9546281 0.2613394 0.1462405 0.9572104 0.2497239 0.1126556 0.9572682 0.2663576 0.1162452 0.9593487 0.2571715 0.09460139 0.9595093 0.2653158 0.09986954 0.9597887 0.2623584 0.07911759 0.9596827 0.2697213 0.08249956 0.9612554 0.2630244 0.05084943 0.9612789 0.2708458 0.05388045 0.9624677 0.2659941 0.02192401 0.9625039 0.270381 0.02448517 0.9633761 0.2670339 0.009634137 0.9634513 0.2677106 0.01090502 0.9635444 0.2673261 -0.02960002 0.9628464 0.2684224 0.04889667 0.8967324 0.4398638 0.1164724 0.9931938 6.59538e-4 0.1164458 0.9931937 0.002598643 0.1226295 0.9924451 0.003849208 0.1225984 0.9924445 0.004854977 0.1315516 0.9912849 0.006975471 0.1315134 0.991284 0.007757306 0.1432793 0.9896202 0.01108747 0.1433326 0.9896209 0.01031148 0.1449614 0.9893432 0.01364505 0.1451861 0.9893475 0.01061123 0.1485773 0.9887904 0.01478183 0.1487776 0.9887972 0.0120601 0.1501341 0.9885656 0.0140655 0.1494491 0.9885442 0.02110356 0.1440897 0.9895097 0.01043218 0.1395705 0.9896902 0.03214883 0.1396825 0.9900028 0.01957476 0.134278 0.9900866 0.04120546 0.1308979 0.9909715 0.0290088 0.1224032 0.9911013 0.05230569 0.1202422 0.9918975 0.04100191 0.1101505 0.9920067 0.06155931 0.109084 0.9926922 0.0516051 0.1005449 0.9927949 0.06518572 0.1033594 0.9929308 0.05835568 0.09497874 0.9929488 0.07093513 0.09481066 0.9935203 0.06267762 0.08312672 0.9935803 0.07673537 0.08353155 0.9940554 0.06983101 0.0714702 0.9940968 0.08162987 0.07207977 0.9945288 0.07561039 0.05988657 0.9945655 0.08516532 0.06094735 0.9949036 0.08032625 0.04913485 0.9949293 0.08775883 0.0503652 0.9952057 0.08383935 0.03878444 0.9952253 0.08956748 0.04005104 0.9954488 0.08647322 0.0325914 0.9954742 0.08926886 0.03443557 0.9955027 0.08825337 0.02727091 0.9954953 0.09080559 0.02845913 0.9956653 0.08854925 0.01762014 0.9956741 0.09122776 0.01868587 0.9958022 0.08960366 0.007666051 0.9958112 0.09111189 0.008563756 0.9959064 0.08998423 0.003396749 0.9959169 0.09021174 0.003823161 0.9959275 0.09007769 0.1768916 0.980708 0.08319377 -0.08743304 0.9891365 0.1181724 0 1 0 0 1 1.99551e-6 0 1 -2.13491e-6 0 1 -1.45183e-5 0 1 7.54082e-7 0 1 1.89776e-6 0 1 4.30472e-6 0 1 -3.45985e-5 0 1 -3.77434e-6 0 1 2.00526e-6 0 1 3.32724e-7 0 1 8.3469e-7 0 1 -2.76861e-6 0 1 3.57125e-7 0 1 1.73096e-7 0 1 -3.212e-7 0 1 2.03646e-7 0 1 -3.11069e-7 0 1 0 0 1 -6.53126e-7 0 1 -8.12044e-7 0 1 5.9211e-6 0 1 7.16105e-7 0 1 -1.38169e-6 0 1 1.52678e-6 0 1 3.00157e-6 0 1 -3.6114e-6 0 1 1.94293e-6 0 1 5.51316e-6 0 1 -4.89153e-6 0 1 1.03127e-5 0 1 -1.47558e-5 0 1 -1.64857e-6 0 1 -6.49922e-7 0 1 -5.85056e-7 -0.561005 0.7523292 0.3453612 -0.6349743 0.7149102 0.2927649 -0.6304999 0.7189044 0.292654 -0.6662918 0.7009746 0.2543421 -0.7065482 0.6686736 0.2316575 -0.6859173 0.6977481 0.2065556 -0.7561857 0.6328675 0.1663187 -0.486638 0.7561316 0.4375482 -0.510055 0.7716215 0.3800585 -0.5785862 0.7385427 0.3461106 -0.2316125 0.8360348 0.4973946 -0.3004386 0.8225651 0.4828285 -0.2985151 0.8234716 0.4824762 -0.358817 0.8114967 0.4612196 -0.3664745 0.8077219 0.4618245 -0.4163603 0.798739 0.4343503 -0.4348751 0.7889916 0.434023 -0.4903985 0.7803694 0.3879859 -0.1351258 0.8366654 0.5307846 -0.1841909 0.8433079 0.5048819 -0.2426168 0.8310526 0.5004886 -0.1638444 0.8510445 0.4988772 -0.1050816 0.8479034 0.5196323 -0.09872102 0.8494473 0.5183565 -0.06233358 0.8554923 0.5140501 -0.039568 0.8582726 0.5116665 -0.03368526 0.8596355 0.5097964 -0.03057903 0.8603852 0.5087261 -0.02906572 0.860785 0.5081381 -0.02385634 0.8620848 0.5062022 -0.04948908 0.8541494 0.5176677 -0.02428412 0.8567567 0.5151488 -0.0240246 0.8568055 0.5150797 -0.770757 0.6330994 0.07154703 -0.779094 0.6199831 0.09291762 -0.7827031 0.616301 0.08688604 -0.7694141 0.6290473 0.1109114 -0.7685259 0.629945 0.1119704 -0.7478724 0.6462741 0.151713 -0.7366827 0.6564505 0.1623932 -0.7047078 0.67601 0.2154008 -0.6874008 0.6902089 0.2260351 -0.6431854 0.7114777 0.2830409 -0.626264 0.7233294 0.29084 -0.5792949 0.7409427 0.3397373 -0.5615856 0.7517423 0.3456954 -0.512821 0.7661509 0.3873338 -0.4949738 0.7757698 0.3913851 -0.4463543 0.787095 0.4257339 -0.4285061 0.7957235 0.4280267 -0.3805891 0.8043922 0.4561857 -0.3623237 0.8123904 0.4568845 -0.3148499 0.8188059 0.4800276 -0.2963275 0.8262063 0.4791379 -0.2491352 0.830656 0.497938 -0.230679 0.8374088 0.4955136 -0.1846044 0.8400362 0.5101573 -0.1664659 0.846135 0.5063049 -0.1215769 0.8471508 0.517257 -0.103373 0.8527845 0.5119304 -0.0746029 0.8526717 0.5170934 -0.05129045 0.8559123 0.5145714 -0.7707146 0.6343094 0.06042098 -0.7716557 0.6334011 0.05788475 -0.7592879 0.6457783 0.08032608 -0.7417785 0.6683735 0.05515003 -0.7407906 0.6699915 0.0483818 -0.7428647 0.6681345 0.04181516 -0.6895032 0.7216804 0.06134277 -0.6982369 0.7152866 0.02881789 -0.65992 0.7500418 0.04407805 -0.6656976 0.7460219 0.01726883 -0.6392595 0.7684603 0.02856862 -0.6267985 0.7790521 0.01419103 -0.6425901 0.7661584 0.008910477 -0.6288017 0.7775391 0.006446599 -0.6271492 0.7788981 -0.001326501 -0.7448098 0.6655024 0.04863172 -0.7471505 0.6632699 0.042885 -0.7535085 0.6560763 0.0422945 -0.6751555 0.7369661 0.03234261 -0.6930943 0.7202787 0.02861756 -0.6653119 0.7462646 0.02119857 -0.6662179 0.745557 0.01728433 -0.6516399 0.758387 0.01464986 -0.6341067 0.773228 0.005213141 0.6268609 0.779081 0.008856475 0.7673181 0.6387305 0.05697625 0.7525665 0.6533623 0.08222764 0.7697118 0.6358652 0.05674064 0.7650562 0.6382522 0.0855754 0.7898989 0.6099029 0.06386089 0.7776585 0.6228688 0.08533447 0.7697399 0.6290397 0.108673 0.7675329 0.6311872 0.1117862 0.7569405 0.6399102 0.1324992 0.7506083 0.6455736 0.1407909 0.7346124 0.6570942 0.1690324 0.7219983 0.6677958 0.1810174 0.6981147 0.6812558 0.2202872 0.6728215 0.7004641 0.2380363 0.6521345 0.7070434 0.2735146 0.6125233 0.7313873 0.2998132 0.6009044 0.7321973 0.3206263 0.5665202 0.7492691 0.3430027 0.5489346 0.7578721 0.3525634 0.5392845 0.7576501 0.367612 0.4853128 0.778689 0.3976367 0.4835307 0.778275 0.4006074 0.4420724 0.7900916 0.4246496 0.4180948 0.7996062 0.4310765 0.4013745 0.7994703 0.4469292 0.3540479 0.8144645 0.4596713 0.3463814 0.8134142 0.4673087 0.2904693 0.8260415 0.4829937 0.2910557 0.8261924 0.4823823 0.2484034 0.8322598 0.4956201 0.224365 0.8389915 0.4957357 0.2065341 0.8375021 0.5058991 0.162076 0.8465526 0.5070306 0.154155 0.845132 0.5118479 0.1018093 0.8518475 0.5138003 0.04033488 0.854932 0.5171697 0.03249055 0.8576076 0.5132775 0.06808549 0.8535441 0.5165529 0.100654 0.8515468 0.514526 0.1010205 0.8504663 0.5162383 0.0402587 0.8554047 0.5163933 0.04422354 0.8540117 0.5183711 0.01941001 0.8567575 0.5153542 0.01495569 0.8569569 0.5151711 0.225758 0.8369066 0.4986187 0.1851651 0.8417215 0.5071673 0.1640595 0.8427013 0.5127758 0.153353 0.8463279 0.5101099 0.09962368 0.8501366 0.5170522 0.4939422 0.7697987 0.4042664 0.4499421 0.7912932 0.4140136 0.4266198 0.7905511 0.4393454 0.3893134 0.8073478 0.4434238 0.3599909 0.8076987 0.466936 0.3296507 0.8199806 0.4679341 0.2935861 0.8220624 0.4878735 0.2726318 0.8301524 0.4863321 0.2186533 0.834562 0.5056651 0.7629938 0.6190621 0.1860175 0.6754922 0.709896 0.1993944 0.7025868 0.6671594 0.2475283 0.6337869 0.7260584 0.2667462 0.6323674 0.710476 0.3087642 0.5806985 0.7477309 0.3220061 0.5630107 0.7434414 0.3609901 0.556237 0.7478877 0.3623043 0.5085808 0.7735822 0.3780425 0.7686659 0.6373068 0.05470728 0.771421 0.634221 0.05170625 0.6304313 0.7748941 0.04577744 0.7245872 0.6879201 0.04170572 0.6842189 0.7287554 0.02757185 0.6769985 0.7354344 0.02844893 0.6631872 0.7482499 0.01745855 0.6451325 0.7639255 0.01490348 0.6195983 0.7847175 0.01778775 0.7380141 0.6708527 0.07274633 0.7286677 0.6820919 0.06159543 0.7024858 0.7105346 0.04067379 0.6946986 0.7175111 0.05071204 0.6730408 0.7390641 0.02829176 0.6660212 0.7451247 0.03471171 0.6459149 0.7632216 0.01693218 0.6517081 0.7583998 0.01031696 0.6424629 0.7662667 0.008779585 0.6271405 0.7788972 0.003762543 -0.1591213 -0.9864856 -0.03907322 -0.2205251 -0.9665756 0.1307681 -0.2584857 -0.9588698 0.1172775 -0.8861732 0.4188963 0.1980479 -0.6853113 0.6689503 0.2878434 -0.8103731 0.5756943 0.108958 -0.6886993 -0.7250261 -0.005521774 -0.6155525 -0.7879859 -0.01316678 -0.5378752 -0.8428354 -0.01785486 -0.07859963 0.7346546 0.6738731 -0.003646492 0.8141865 0.5805922 0.009319841 0.8161988 0.5776961 0.005997121 0.8170935 0.5764742 -0.01614046 0.8213251 0.570232 -0.02329325 0.8226163 0.5681197 -0.02817028 0.8234823 0.5666422 -0.03393465 0.8241616 0.5653372 -0.04152876 0.8245651 0.5642408 -0.09707504 0.5587459 0.8236379 -0.03987681 0.6341648 0.7721689 -0.03904014 0.6646611 0.7461243 0.02871185 0.007145881 0.9995623 -0.05838799 0.1527796 0.986534 -0.02159589 0.124777 0.9919498 -0.02906745 0.2516087 0.9673926 -0.02539074 -0.6248171 0.7803581 -0.04679179 -0.595613 0.8019075 -0.01419186 -0.6077975 0.7939653 -0.08594912 -0.5218807 0.8486774 0.008193075 -0.562124 0.8270124 -0.06583642 -0.4061025 0.9114529 -0.0217446 -0.4281567 0.9034429 -0.02844601 -0.2803223 0.9594844 -0.04186749 -0.2715687 0.961508 -0.01807558 -0.1818005 0.9831693 -0.04459637 -0.1222749 0.9914939 -0.0021317 -0.082731 0.9965697 -0.05814033 0.05332404 0.9968833 -0.02595138 -0.7204788 0.6929912 -0.09087699 -0.6721534 0.7348137 -0.05886489 -0.7473476 0.6618206 -0.1419754 -0.8891605 0.4350136 -0.120359 -0.9205031 0.3717364 -0.1481294 -0.9142553 0.3770876 -0.1432986 -0.9379916 0.3156538 -0.1529913 -0.935773 0.3176833 -0.1641765 -0.9518106 0.259042 -0.1553873 -0.9538272 0.257038 -0.1823968 -0.9622288 0.202107 -0.1541242 -0.9686094 0.195043 -0.1423196 -0.9897933 -0.007384061 -0.1833457 -0.9830384 0.004464149 -0.06279402 -0.9964856 -0.05543839 -0.0947622 -0.9933244 -0.06577861 -0.08548426 -0.9939699 -0.06867682 -0.1182537 -0.9899517 -0.07753491 -0.1255896 -0.9912617 -0.04034376 -0.1867583 -0.9808398 -0.05545115 -0.1484301 -0.9885414 -0.02746921 -0.04301279 -0.9989473 -0.01594501 -0.03633069 -0.999252 -0.01325833 -0.1449995 -0.9892683 0.01798599 -0.1095145 -0.9935256 -0.03022128 -0.05917906 -0.9981921 -0.01050478 -0.3003559 -0.9533605 -0.02983689 -0.3392491 -0.9405854 -0.01446729 -0.3453844 -0.9384542 0.003675341 -0.397224 -0.9166055 -0.04524946 -0.7689208 -0.6393053 0.007046222 -0.7887399 -0.6144866 0.01719313 -0.806318 -0.5913759 0.01122111 -0.8481082 -0.5294345 0.02029001 -0.8579939 -0.5133399 0.01813137 -0.8845541 -0.4655874 0.02815198 -0.9050821 -0.4244351 0.02610272 -0.9185764 -0.3937956 0.03380262 -0.9366211 -0.3486626 0.03428417 -0.9484228 -0.3145438 0.03945219 -0.9621292 -0.2701243 0.03661078 -0.9724004 -0.229259 0.04333263 -0.9860004 -0.1616644 0.04084205 -0.9976179 -0.0625512 0.02908462 -0.9990059 -0.02581399 0.03634446 -0.9989629 0.03777039 0.02542972 -0.9969137 0.07134342 0.03276187 -0.9925974 0.118543 0.02642112 -0.9835162 0.1787772 0.02710264 -0.9812483 0.1904069 0.02995252 -0.9695066 0.2441847 0.02075761 -0.9551928 0.2952755 0.0204764 -0.9397661 0.3407329 0.02721673 -0.927008 0.3747221 0.01547783 -0.862764 0.505133 0.02189022 -0.8775799 0.4785698 0.02871298 -0.8023214 0.5963819 0.02468031 -0.7380214 0.6743913 0.02282333 -0.7359136 0.6767187 0.02197962 -0.733008 0.6786678 0.04592829 -0.6963241 0.7169013 0.03442937 -0.6938841 0.7177428 0.05805486 -0.7264234 0.6850923 0.05438387 -0.7205786 0.6885791 0.08139646 -0.7726078 0.6301211 0.07761919 -0.7602313 0.6414418 0.1029612 -0.7977821 0.5952532 0.09600818 -0.7980722 0.5871257 0.1355149 -0.7276873 0.6230051 0.2869423 -0.6154704 0.7081668 0.3459711 -0.6763546 0.6462157 0.3534824 -0.5451233 0.7402716 0.3934953 -0.6193172 0.6677612 0.4129666 -0.4286709 0.7593908 0.4894558 -0.4311189 0.7350645 0.523275 -0.44573 0.7545029 0.481716 -0.4976854 0.7390666 0.4539712 -0.503674 0.7108727 0.4908896 -0.5157882 0.7421966 0.4279099 -0.2775818 0.7658188 0.5800603 -0.3103419 0.7860538 0.5346097 -0.3594306 0.7764974 0.5175533 -0.3588644 0.7547014 0.5492196 -0.3781579 0.7716221 0.5114646 -0.05469703 0.8234229 0.564786 -0.08983796 0.8104416 0.57889 -0.08216094 0.8185536 0.5685241 -0.1377016 0.8152278 0.5625317 -0.1543334 0.8025572 0.5762665 -0.19236 0.8149766 0.5466361 -0.2257319 0.7914338 0.5680475 -0.2772124 0.8124254 0.5129506 -0.8671745 0.4840852 0.1169189 -0.8527165 0.4976557 0.1587878 -0.8841115 0.4449192 0.1428073 -0.8799818 0.44932 0.1540897 -0.8411892 0.5202829 0.1473312 -0.8389635 0.5225998 0.1517559 -0.8037828 0.5772157 0.1440674 -0.9448181 0.07612973 0.3186268 -0.9431259 0.08376413 0.3217098 -0.9466525 -0.009057641 0.322129 -0.9456236 -0.00263971 0.3252525 -0.9426053 -0.08709883 0.3223496 -0.9419185 -0.08140057 0.3258274 -0.933063 -0.1657005 0.3192757 -0.9326215 -0.1597176 0.3235852 -0.917811 -0.2440162 0.3131757 -0.9176166 -0.2554809 0.3044821 -0.9032661 -0.2942814 0.3122642 -0.8885802 -0.3446823 0.302687 -0.92203 0.3271904 0.2068992 -0.9255995 0.3105952 0.2163242 -0.8990995 0.330705 0.2868 -0.8989282 0.3245903 0.2942267 -0.8533644 0.3503227 0.3860613 -0.8523982 0.3442847 0.3935549 -0.7980341 0.3671638 0.4778413 -0.7962282 0.3609812 0.485503 -0.7344222 0.3810299 0.5616408 -0.7316843 0.374556 0.5695138 -0.663519 0.3919006 0.6373041 -0.6597757 0.3850295 0.6453281 -0.5860067 0.3998466 0.7047829 -0.04986357 0.6941167 0.7181335 -0.09359395 0.7265875 0.6806694 -0.0939604 0.7265663 0.6806416 -0.09503483 0.7273954 0.679606 -0.1746577 0.7221072 0.6693699 -0.1759158 0.7231336 0.6679307 -0.2536885 0.7150195 0.6514518 -0.2550549 0.7162286 0.6495872 -0.33091 0.70528 0.6269599 -0.3323034 0.7066663 0.6246578 -0.4062728 0.6927827 0.5958143 -0.4076361 0.6943459 0.5930571 -0.479769 0.6773115 0.5577372 -0.4810173 0.6790698 0.5545147 -0.5512681 0.6585476 0.512268 -0.5523484 0.6605368 0.5085297 -0.6204436 0.6360762 0.4587559 -0.6212636 0.6383709 0.4544383 -0.6865796 0.6094375 0.3964775 -0.6870543 0.61215 0.3914446 -0.7484647 0.5782157 0.3247573 -0.7484489 0.5815225 0.318835 -0.8043256 0.5421411 0.2431938 -0.855742 0.4458412 0.2625477 -0.8560862 0.4406248 0.2701228 -0.8056448 0.4751618 0.3537765 -0.8052417 0.4703593 0.3610373 -0.7476176 0.5006855 0.436328 -0.7465081 0.4960429 0.4434718 -0.683258 0.5223342 0.5102211 -0.6814392 0.5176711 0.5173561 -0.6136994 0.5402326 0.5757793 -0.6111242 0.5354371 0.5829532 -0.5396132 0.5546067 0.6334264 -0.5362489 0.5495982 0.6406084 -0.4613339 0.5656783 0.683505 -0.4571562 0.5604139 0.6906117 -0.3789763 0.5736321 0.7261703 -0.3740031 0.5680947 0.733069 -0.2925725 0.5785919 0.7613362 -0.2868523 0.5727787 0.7678804 -0.2022537 0.5805968 0.7886704 -0.1958705 0.5745331 0.794699 -0.1083081 0.5796445 0.8076396 -0.1014174 0.573354 0.8130066 -0.06059247 0.5749899 0.8159138 -0.5812033 0.3925213 0.7128322 -0.5181898 0.4028164 0.7544657 -0.4934641 0.4412869 0.7495059 -0.3989587 0.4542174 0.7965667 -0.4051794 0.4447864 0.7987458 -0.3054444 0.4550577 0.8364366 -0.3115257 0.4455218 0.8393225 -0.2070862 0.45313 0.8670574 -0.2128564 0.4435557 0.8706035 -0.1045122 0.4484655 0.8876688 -0.1097974 0.4389712 0.8917673 -0.02527058 0.4411243 0.8970902 -0.03772091 0.5031516 0.8633746 -0.5060136 0.3517072 0.7875611 -0.4123196 0.3615702 0.8362175 -0.4181438 0.3518463 0.8374724 -0.3145843 0.3600432 0.8782971 -0.3203303 0.3502153 0.8801919 -0.2115763 0.3562335 0.9101281 -0.2170561 0.3464319 0.9126181 -0.1041607 0.3502691 0.9308395 -0.1092273 0.3406074 0.9338394 0.01886671 0.3421826 0.9394441 -0.07076191 0.4703069 0.8796615 -0.4330312 0.1380658 0.8907424 -0.9019824 0.06700402 0.4265422 -0.9000383 0.07433092 0.4294253 -0.9025443 -0.02745056 0.4297211 -0.9012945 -0.02143812 0.4326764 -0.8960188 -0.1184645 0.4279212 -0.8950744 -0.1131287 0.4313281 -0.8820223 -0.2121129 0.420767 -0.8812727 -0.2064407 0.4251361 -0.8608009 -0.3029616 0.408945 -0.8605365 -0.2968481 0.4139544 -0.844748 -0.3536155 0.4016928 -0.8447773 -0.3490114 0.4056383 -0.8257283 -0.4065051 0.391058 -0.883939 -0.3533315 0.3062822 -0.8597686 -0.4200189 0.2904864 -0.8474539 0.05776166 0.5277174 -0.8453187 0.06472063 0.5303278 -0.8466906 -0.04487216 0.5301902 -0.8452684 -0.03935617 0.5328908 -0.8378208 -0.1475667 0.5256238 -0.8366568 -0.1426942 0.5288135 -0.8197501 -0.2544435 0.5130969 -0.8187028 -0.2492409 0.5173051 -0.7934046 -0.3556571 0.4939811 -0.7928211 -0.350158 0.4988228 -0.7752754 -0.4072763 0.4827778 -0.7750601 -0.4034354 0.4863352 -0.7548007 -0.4597051 0.4679179 -0.821206 -0.4132226 0.3935326 -0.7941302 -0.480135 0.372596 -0.8556972 -0.4265522 0.292977 -0.827251 -0.4901666 0.2745773 -0.782316 0.04869824 0.620975 -0.7800551 0.05519568 0.6232717 -0.7803355 -0.06099331 0.6223798 -0.7787955 -0.05603998 0.6247698 -0.7695547 -0.1739898 0.6144211 -0.7682368 -0.1696547 0.617276 -0.7483444 -0.2922042 0.5954808 -0.7470536 -0.2875779 0.5993412 -0.7183632 -0.4017295 0.5679505 -0.7174838 -0.3969151 0.5724294 -0.6993113 -0.4534391 0.5525909 -0.6988944 -0.4503135 0.5556657 -0.6787045 -0.5045781 0.5336304 -0.7508704 -0.4645922 0.4694123 -0.7226178 -0.5304053 0.4432764 -0.7909216 -0.4843338 0.3739838 -0.7602319 -0.5471613 0.3502315 -0.8237529 -0.495061 0.2763077 -0.7918967 -0.5544251 0.2559545 -0.7075844 0.04003769 0.7054938 -0.7052818 0.04602473 0.7074315 -0.7046091 -0.07555693 0.7055616 -0.7030534 -0.07123279 0.7075605 -0.6926172 -0.1974717 0.693748 -0.6912305 -0.1937482 0.6961768 -0.6695967 -0.3252248 0.6677343 -0.6681485 -0.3212376 0.6711066 -0.6378729 -0.4412615 0.6311944 -0.6367741 -0.4371393 0.6351599 -0.6190496 -0.4924501 0.6117766 -0.6185115 -0.4899861 0.6142941 -0.5994945 -0.5418161 0.5891026 -0.6756835 -0.5078347 0.5343742 -0.6478701 -0.5717496 0.5033556 -0.7206327 -0.5326139 0.4438592 -0.6894958 -0.5937072 0.4148584 -0.7582288 -0.5494899 0.3509274 -0.7247588 -0.6074661 0.3251303 -0.7891427 -0.5578185 0.2570842 -0.7551821 -0.6117072 0.2356151 -0.6241408 0.03201204 0.7806559 -0.6218914 0.037404 0.7822098 -0.6205285 -0.0883848 0.7791872 -0.6190279 -0.08472651 0.7807855 -0.6081522 -0.2178664 0.7633382 -0.6067888 -0.2147995 0.7652898 -0.584892 -0.3535114 0.7300213 -0.5834012 -0.3502085 0.7328009 -0.5535121 -0.4745677 0.6844047 -0.5522764 -0.4711382 0.6877642 -0.5359564 -0.5248724 0.6612562 -0.535376 -0.5230083 0.6632005 -0.5184069 -0.5722602 0.6354311 -0.5975224 -0.5437061 0.5893647 -0.5715281 -0.6053183 0.5540266 -0.6472517 -0.5723525 0.503466 -0.6172376 -0.6312386 0.4696335 -0.6891863 -0.5940176 0.4149282 -0.6558913 -0.6499413 0.3839049 -0.7239884 -0.6082669 0.3253494 -0.6887634 -0.6607525 0.2983472 -0.753327 -0.6137415 0.2362621 -0.7174267 -0.6630364 0.2137326 -0.5327664 0.0248034 0.8458989 -0.5306539 0.0295456 0.8470735 -0.5288887 -0.09931886 0.8428599 -0.5275398 -0.09637665 0.8440459 -0.5170745 -0.2350846 0.8230244 -0.5158578 -0.2327049 0.824463 -0.4952288 -0.377146 0.7826298 -0.4938372 -0.3745518 0.7847522 -0.4662789 -0.5020533 0.7283726 -0.4650217 -0.4992942 0.731068 -0.4508928 -0.5512957 0.701975 -0.4503391 -0.5499882 0.7033547 -0.4360618 -0.5966917 0.6736536 -0.5175358 -0.5730184 0.6354579 -0.4944392 -0.6322212 0.5965117 -0.5722686 -0.6046676 0.5539727 -0.5446339 -0.6612191 0.5159101 -0.6186046 -0.6300272 0.4694617 -0.5869539 -0.6836678 0.433686 -0.6571389 -0.6488125 0.3836807 -0.6224114 -0.6993612 0.3514229 -0.689331 -0.6602218 0.2982114 -0.6526048 -0.7078874 0.2701897 -0.7163393 -0.6641051 0.2140619 -0.6788681 -0.7090695 0.1906795 -0.4341711 0.01858484 0.9006387 -0.4322703 0.02261716 0.9014604 -0.430426 -0.1082281 0.8961139 -0.4293526 -0.1060346 0.8968908 -0.4201111 -0.2490534 0.8726276 -0.4191495 -0.2473895 0.873563 -0.401306 -0.3962155 0.8258128 -0.4001623 -0.3943527 0.8272581 -0.3767469 -0.5240799 0.7638077 -0.3755851 -0.5219872 0.7658101 -0.3642413 -0.5722394 0.7347588 -0.36383 -0.5714412 0.7355832 -0.352678 -0.6157512 0.7046055 -0.4362615 -0.5965346 0.6736635 -0.4168661 -0.6534214 0.6318728 -0.4964355 -0.6306192 0.5965494 -0.4721504 -0.6849187 0.5549419 -0.5475412 -0.658888 0.5158152 -0.5186784 -0.7102838 0.4758884 -0.5900785 -0.6811458 0.4334143 -0.557244 -0.7296264 0.3963895 -0.625267 -0.6970201 0.3510046 -0.5893763 -0.7427225 0.3178035 -0.6542717 -0.7064792 0.2698442 -0.6163738 -0.7496469 0.2410662 -0.6783643 -0.7095152 0.1908145 -0.6397048 -0.7503029 0.1668034 -0.9715675 0.1005578 0.2143474 -0.9691128 0.1162276 0.2175124 -0.9756365 0.02027928 0.2184541 -0.9747219 0.031843 0.2211415 -0.974384 -0.04673492 0.219981 -0.9741855 -0.03705739 0.2226868 -0.9693374 -0.110109 0.2196844 -0.9696758 -0.1008073 0.2226359 -0.9565848 -0.195764 0.2159219 -0.9570288 -0.186891 0.2217378 -0.9365249 -0.2794663 0.211707 -0.9373649 -0.2728923 0.2165104 -0.911888 -0.3559271 0.2043926 -0.9128203 -0.3513057 0.2081908 -0.882429 -0.4286156 0.1939273 -0.883345 -0.4253318 0.1969635 -0.8490593 -0.4962998 0.1810665 -0.8498578 -0.4940686 0.1834067 -0.8134235 -0.5572766 0.1666895 -0.8139988 -0.5559591 0.1682723 -0.7758498 -0.6126177 0.1508531 -0.7762343 -0.6118738 0.1518914 -0.7366809 -0.6628602 0.133857 -0.736943 -0.6624231 0.1345762 -0.6961675 -0.7084507 0.1159672 -0.6963849 -0.7081347 0.1165907 -0.6544148 -0.7498378 0.09738957 -0.6546678 -0.7495161 0.09816187 -0.6113267 -0.7874992 0.07826125 -0.6116825 -0.7871022 0.07946544 -0.56668 -0.821844 0.05870586 -0.4295828 0.1449431 0.8913193 -0.5303627 0.1424109 0.835724 -0.5268476 0.1496001 0.8366909 -0.6204349 0.1463515 0.7704816 -0.6169465 0.1537765 0.7718354 -0.7026214 0.1497166 0.695635 -0.6992552 0.1572996 0.6973514 -0.7762643 0.1523189 0.6117293 -0.7730861 0.1600348 0.6137807 -0.8405663 0.1540192 0.5193518 -0.8376469 0.161822 0.5216909 -0.8945979 0.1546575 0.4192563 -0.8919736 0.1625583 0.4218506 -0.9373199 0.1541554 0.3125181 -0.9350196 0.1621953 0.3153268 -0.9588931 0.1557924 0.2371766 -0.9673027 0.08467513 0.2390723 -0.9650208 0.1002757 0.2422391 -0.9700141 0.0062716 0.242968 -0.9691926 0.01749712 0.2456822 -0.967742 -0.06206494 0.2441794 -0.9675953 -0.05282789 0.2469182 -0.9613589 -0.1288618 0.2432773 -0.9617416 -0.1198986 0.246328 -0.9461823 -0.2189836 0.2382969 -0.946581 -0.2105191 0.2442668 -0.9246255 -0.3011516 0.2331855 -0.9253728 -0.2950072 0.2380254 -0.8990573 -0.3756416 0.2249211 -0.8998623 -0.3714209 0.2286798 -0.8689546 -0.4465306 0.213374 -0.8697236 -0.4436144 0.2163035 -0.8352658 -0.512429 0.1993685 -0.8359069 -0.510537 0.2015239 -0.7996347 -0.5716567 0.1838283 -0.8000488 -0.570649 0.1851534 -0.7622012 -0.6254947 0.1667509 -0.7624273 -0.6250275 0.1674671 -0.7232444 -0.6744519 0.1484328 -0.7233513 -0.6742617 0.1487756 -0.6829887 -0.7189198 0.1291546 -0.683046 -0.7188299 0.1293518 -0.6414899 -0.7593316 0.1091158 -0.6415663 -0.7592235 0.1094189 -0.5985984 -0.7961515 0.08844697 -0.598751 -0.7959598 0.08913594 -0.5540776 -0.8297421 0.0672748 -0.5543159 -0.8294714 0.06863832 -0.5075207 -0.8604284 0.04566967 -0.329135 0.1334795 0.9348012 -0.3258346 0.1399689 0.9350084 -0.329102 0.01352185 0.9441975 -0.3275151 0.0167762 0.944697 -0.3259164 -0.1150063 0.9383773 -0.3251535 -0.1135766 0.9388161 -0.3179193 -0.2596632 0.9118675 -0.3173516 -0.258763 0.9123211 -0.3036748 -0.4107564 0.8596864 -0.3029035 -0.4096602 0.8604813 -0.285224 -0.540937 0.7912235 -0.2843009 -0.5394922 0.792541 -0.2761568 -0.5880804 0.7601966 -0.2759785 -0.5877698 0.7605016 -0.2681949 -0.6299176 0.7288864 -0.3538571 -0.6148679 0.7047856 -0.3387287 -0.6696535 0.6609289 -0.4199855 -0.6510999 0.6322035 -0.3997463 -0.7033715 0.5877683 -0.4763918 -0.6817859 0.5551748 -0.4511714 -0.7311359 0.5117468 -0.5234308 -0.7067924 0.4758834 -0.4935709 -0.7532951 0.4346659 -0.5621113 -0.7260478 0.3960879 -0.5283418 -0.7697842 0.3581724 -0.5935171 -0.7396345 0.3172985 -0.556728 -0.78084 0.2834482 -0.6188803 -0.7477256 0.240611 -0.5801718 -0.7865881 0.2113758 -0.6395602 -0.7504185 0.1668383 -0.5999016 -0.7873138 0.1423206 -0.5998864 -0.7873151 0.1423775 -0.5592201 -0.8206717 0.1173501 -0.5591186 -0.8207037 0.1176092 -0.5173114 -0.8508372 0.0920068 -0.5170055 -0.8509475 0.0927028 -0.4737258 -0.8781697 0.06634628 -0.4729943 -0.8784558 0.0677641 -0.4277887 -0.9029752 0.04040455 -0.1055948 0.124289 0.9866114 -0.1029312 0.1296895 0.9861977 -0.1037746 0.007383644 0.9945735 -0.1029913 0.008953511 0.994642 -0.1025574 -0.1216987 0.9872546 -0.1026555 -0.121876 0.9872225 -0.1011503 -0.2703939 0.9574214 -0.1016274 -0.2710801 0.9571769 -0.09921902 -0.4261534 0.8991935 -0.09965807 -0.4266925 0.8988893 -0.09687966 -0.5596321 0.8230591 -0.09682184 -0.559566 0.8231109 -0.09575915 -0.6052379 0.7902641 -0.0962671 -0.6059141 0.7896839 -0.09542918 -0.644568 0.7585681 -0.1852927 -0.6375449 0.7477989 -0.1796939 -0.6890623 0.7020707 -0.2646694 -0.6781573 0.685604 -0.2538955 -0.7273267 0.6375994 -0.333429 -0.713216 0.6165616 -0.3171987 -0.7594001 0.5680639 -0.3914099 -0.7426345 0.5434081 -0.3696619 -0.7859472 0.4956179 -0.4391372 -0.766777 0.4682003 -0.4122716 -0.8072029 0.4224401 -0.4774172 -0.7859266 0.3929278 -0.4460515 -0.8236199 0.350269 -0.5073261 -0.800465 0.3191804 -0.4723545 -0.8355745 0.2805293 -0.530182 -0.8107274 0.2482504 -0.494296 -0.8421069 0.2157023 -0.4963333 -0.8419218 0.2117098 -0.4618895 -0.8683122 0.1808094 -0.4639558 -0.8679672 0.1771388 -0.4287726 -0.8915456 0.1459469 -0.4306869 -0.8911193 0.1428824 -0.394376 -0.9122038 0.1111392 -0.39587 -0.9118163 0.1089863 -0.357518 -0.9308089 0.07599985 -0.219551 0.1288352 0.9670569 -0.2165406 0.1348243 0.9669191 -0.2185449 0.0097543 0.9757782 -0.2173304 0.01218008 0.9760222 -0.2162219 -0.1195299 0.9689999 -0.2158712 -0.118896 0.969156 -0.2112975 -0.2668147 0.9402996 -0.2112102 -0.2666947 0.9403532 -0.2027722 -0.4207655 0.8842171 -0.2025473 -0.4204595 0.8844142 -0.1918644 -0.5527718 0.8109448 -0.1913214 -0.5520033 0.8115963 -0.186663 -0.5990454 0.7786537 -0.1867921 -0.5992267 0.7784832 -0.1824861 -0.6394768 0.7468389 -0.2702499 -0.6284493 0.7293947 -0.2597819 -0.6814263 0.6842306 -0.3428211 -0.6667865 0.6617171 -0.3271332 -0.7173331 0.6151562 -0.405124 -0.6996595 0.5885161 -0.3841643 -0.747259 0.5422379 -0.4572964 -0.7269719 0.512242 -0.4311985 -0.7717304 0.4674399 -0.5001259 -0.7488887 0.4347872 -0.4694502 -0.7908332 0.3926823 -0.5345894 -0.7655863 0.3578992 -0.5000749 -0.8049232 0.3194116 -0.5618361 -0.7773668 0.2829152 -0.5244787 -0.8142685 0.2487754 -0.5832143 -0.7844685 0.2108802 -0.5450152 -0.818392 0.182189 -0.5459367 -0.818265 0.1799882 -0.5082372 -0.8477191 0.1518799 -0.5091528 -0.847516 0.1499337 -0.4705927 -0.8739563 0.1214201 -0.4713591 -0.87374 0.1199963 -0.4315639 -0.8974961 0.09084862 -0.4319364 -0.897378 0.09024262 -0.3904404 -0.9186595 0.06017738 -0.3900554 -0.918786 0.06073749 -0.3464288 -0.9376116 0.02952265 -0.3286058 -0.9439605 -0.03093588 -0.4057335 -0.9139636 0.007134437 -0.4631395 -0.8857185 -0.03169864 -0.2193476 -0.9756417 -0.003175377 -0.1414541 -0.989037 -0.0423851 -0.1011428 -0.9947544 -0.01529377 -0.07988655 -0.9964285 -0.02735936 -0.04676246 -0.9987558 -0.01732867 0.009689092 -0.6923264 0.7215195 -0.1041775 -0.6888924 0.7173384 -0.1037875 -0.736492 0.6684368 -0.1871099 -0.7290506 0.6583884 -0.1812499 -0.7735364 0.6072807 -0.2585217 -0.7629095 0.5925672 -0.2467556 -0.8043408 0.5405068 -0.3182829 -0.7911217 0.5223243 -0.3006067 -0.8294581 0.4707815 -0.3666496 -0.8142192 0.450128 -0.3434208 -0.8495135 0.4004859 -0.4044238 -0.8327314 0.3781532 -0.3763474 -0.8650762 0.3316713 -0.4328085 -0.8471488 0.3082463 -0.403151 -0.8747159 0.2689634 -0.4076765 -0.8745963 0.2624526 -0.3801576 -0.8967071 0.2267083 -0.384678 -0.8962921 0.2206431 -0.35638 -0.9159068 0.1846836 -0.3606637 -0.9152874 0.1793627 -0.3312198 -0.9326735 0.1428766 -0.334954 -0.9319818 0.138621 -0.3027349 -0.9478309 0.09984081 -0.2840165 -0.9451315 0.1614345 -0.2780702 -0.9459484 0.1669091 -0.3005654 -0.9308661 0.2077229 -0.2938573 -0.9314991 0.2143765 -0.3150597 -0.914306 0.2545228 -0.3079586 -0.9146047 0.2620303 -0.3282031 -0.8950861 0.301834 -0.3210042 -0.8949497 0.3098732 -0.3430544 -0.8697499 0.3547521 -0.286486 -0.8832032 0.3713192 -0.3056702 -0.8524281 0.424184 -0.2433602 -0.8647508 0.439297 -0.2566354 -0.8305737 0.4942526 -0.1881169 -0.8411471 0.5070344 -0.1950551 -0.8035192 0.5624148 -0.1200718 -0.8116101 0.5717272 -0.1207205 -0.7705668 0.6258221 -0.08497887 -0.7733072 0.628311 -0.06050753 -0.7681234 0.6374366 -0.07520961 -0.7341247 0.6748366 -0.1116518 -0.7317208 0.6723976 -0.1112658 -0.7759665 0.6208832 -0.1904779 -0.7682422 0.6111646 -0.1841614 -0.8092827 0.5578048 -0.2572537 -0.7986665 0.544015 -0.2447823 -0.8364677 0.4903095 -0.3118651 -0.8236603 0.4736286 -0.2934132 -0.8582312 0.4211272 -0.3548588 -0.843837 0.4025102 -0.3310094 -0.8752468 0.3526698 -0.3873134 -0.859771 0.3328397 -0.3613144 -0.8859944 0.29063 -0.3671563 -0.8859808 0.2832566 -0.3432248 -0.9066295 0.2453973 -0.3490202 -0.9062531 0.238517 -0.3242263 -0.9245091 0.2004004 -0.3297181 -0.9238635 0.1943248 -0.3037124 -0.9399666 0.1556333 -0.3085522 -0.9391971 0.1506802 -0.2808988 -0.9532939 0.1110264 -0.2929151 -0.9509247 0.09971487 -0.2647458 -0.9621866 0.06408303 -0.2656959 -0.9620612 0.06200009 -0.2317976 -0.9725422 0.02077537 -0.2310627 -0.9726869 0.0221399 -0.2025372 -0.9792112 -0.01114416 -0.2385151 -0.9543073 0.1800232 -0.2303296 -0.9551446 0.1861373 -0.2453704 -0.9415115 0.2309753 -0.2361332 -0.942035 0.2383509 -0.2497339 -0.926268 0.282242 -0.2398965 -0.9263024 0.29054 -0.2523472 -0.9082477 0.3337773 -0.2422696 -0.907682 0.3426644 -0.2555717 -0.8836789 0.3921669 -0.1972179 -0.8938595 0.4026416 -0.2058308 -0.8634312 0.4605651 -0.1405873 -0.8720893 0.4687168 -0.1423869 -0.837652 0.5273188 -0.1167356 -0.8403861 0.5292674 -0.05955427 -0.8238947 0.5636053 -0.1878535 -0.981715 0.03077161 -0.1672495 -0.9838793 0.06331849 -0.1940703 -0.9772368 0.08570307 -0.1740648 -0.9762634 0.1288843 -0.190909 -0.9714081 0.1411388 -0.1881989 -0.9697856 0.1552318 -0.1950085 -0.9610807 0.1956927 -0.1844484 -0.9618604 0.201999 -0.1910733 -0.9490588 0.2505564 -0.1791182 -0.9493508 0.2581658 -0.1842133 -0.9342532 0.3053466 -0.1714088 -0.9338518 0.3139108 -0.1752514 -0.9163674 0.3599416 -0.1620367 -0.9151537 0.3691041 -0.1653239 -0.891265 0.4222733 -0.09572941 -0.8992677 0.4267944 -0.1234431 -0.8730455 0.4717556 -0.1814212 -0.983387 -0.006043016 -0.1838636 -0.9829093 -0.009142577 -0.2066788 -0.9780335 0.0271027 -0.2067227 -0.9780259 0.02704191 -0.2334603 -0.9696689 0.07237929 -0.2311975 -0.969931 0.07603687 -0.2537315 -0.960204 0.1167418 -0.2402096 -0.9623619 0.1271185 -0.2608217 -0.9500943 0.171152 -0.2537642 -0.9509322 0.1770079 -0.2726226 -0.9366617 0.219868 -0.2646663 -0.9372552 0.2269464 -0.2821589 -0.9208771 0.2690199 -0.2737125 -0.9210627 0.2769931 -0.2901392 -0.9023971 0.3185888 -0.2815345 -0.9020692 0.3271232 -0.299354 -0.8776038 0.3744312 -0.2421 -0.8893275 0.387923 -0.2562062 -0.8588823 0.4434857 -0.1926082 -0.8693292 0.455158 -0.2003285 -0.8352044 0.5121544 -0.1300244 -0.843626 0.5209501 -0.1311369 -0.8057866 0.5775042 -0.1001701 -0.8085988 0.5797706 -0.06358611 -0.7939507 0.604648 -0.5671651 -0.8213699 0.06062549 -0.520111 -0.8532168 0.038805 -0.5078092 -0.8601292 0.04803788 -0.4583293 -0.8884671 0.02367299 -0.4263138 -0.9035587 0.04287785 -0.3787795 -0.9253763 0.01431405 -0.3447917 -0.9381459 0.03163647 -0.2809128 -0.9596422 -0.01323217 -0.2425584 -0.9701317 0.003142714 -0.1923592 -0.9805224 -0.03967297 -0.1573545 -0.9871413 -0.02813684 -0.1245442 -0.990327 -0.06116551 -0.08740961 -0.9947624 -0.05298513 -0.09061181 -0.9946509 -0.04959011 -0.1175148 -0.9909278 -0.06520968 -0.1443592 -0.9890327 -0.03122144 -0.17224 -0.9843247 -0.03792405 -0.1999797 -0.9797752 -0.006980359 -0.2820522 -0.95879 -0.03418481 -0.2653108 -0.9641065 0.01043641 -0.3068307 -0.9505758 0.04754441 -0.3069245 -0.9505615 0.04722732 -0.3400105 -0.9372242 0.07748335 -0.3293653 -0.9399192 0.0898351 -0.3638228 -0.9230583 0.1248858 -0.3612006 -0.9236294 0.1282311 -0.3940706 -0.9046167 0.1624103 -0.3909803 -0.9051688 0.1667459 -0.4227364 -0.883816 0.2004084 -0.4194567 -0.8842267 0.2054251 -0.4504867 -0.8602373 0.2388589 -0.4472338 -0.8604169 0.2442638 -0.4802189 -0.8311449 0.2803356 -0.4232176 -0.8521227 0.3078536 -0.4550336 -0.8185456 0.3506105 -0.3940669 -0.8381831 0.3770421 -0.42162 -0.8018476 0.4234111 -0.356212 -0.8198531 0.4482788 -0.3787071 -0.7806373 0.4971786 -0.3083902 -0.7966566 0.5198401 -0.3253227 -0.7544625 0.5700453 -0.249741 -0.7680581 0.5896747 -0.2609035 -0.7229202 0.6397778 -0.179577 -0.7336667 0.6553513 -0.1852182 -0.6854872 0.7041319 -0.09821331 -0.6927 0.7145075 -0.09886211 -0.6422613 0.7600834 -0.05916434 -0.6442006 0.7625648 -0.05956232 -0.6443285 0.762426 -0.05719602 -0.9973259 -0.04549473 -0.08325886 -0.9947509 -0.05948746 -0.08255666 -0.9947559 -0.06037431 -0.115203 -0.9908458 -0.07037681 -0.1365252 -0.9899957 -0.03562885 -0.1518772 -0.9875055 -0.04202747 -0.1689292 -0.9856044 -0.006841778 -0.1713518 -0.9851661 -0.009283959 -0.1884043 -0.9816324 0.03003126 -0.1877318 -0.981738 0.03078013 -0.2070068 -0.9750425 0.0802533 -0.2032451 -0.9754366 0.08494102 -0.2191669 -0.966925 0.1304684 -0.2038728 -0.9689425 0.1399515 -0.2167038 -0.9579296 0.1881763 -0.2073459 -0.9587494 0.1944409 -0.2183305 -0.9456013 0.2411845 -0.2077614 -0.9460264 0.2487353 -0.2172518 -0.9306834 0.2943301 -0.2059595 -0.9305241 0.3028295 -0.2142254 -0.9128623 0.3475487 -0.202619 -0.9120039 0.3566432 -0.2110854 -0.8881949 0.4081089 -0.1512717 -0.896929 0.4154939 -0.153969 -0.8661795 0.4754225 -0.1331902 -0.8687375 0.4770279 -0.07364672 -0.8574455 0.5092774 -0.103347 -0.9936122 -0.0453242 -0.1087493 -0.9932127 -0.04125928 -0.1553187 -0.9860703 -0.05951118 -0.2039102 -0.9785619 -0.02893561 -0.2478574 -0.9674158 -0.05170542 -0.3178908 -0.94799 -0.01613914 -0.3424654 -0.9390041 -0.03144782 -0.4432389 -0.896255 0.01632004 -0.4639623 -0.885855 -3.56947e-4 -0.5640735 -0.8245992 0.04309731 -0.58457 -0.8111622 0.01714742 -0.4686476 -0.8825356 -0.03873598 -0.4370756 -0.8993254 -0.01337498 -0.4352861 -0.9002617 -0.00742948 -0.3574534 -0.9331232 -0.03883534 -0.3143286 -0.9491397 -0.01820707 -0.297297 -0.9544427 -0.02557069 -0.2350186 -0.9715284 -0.02998369 -0.2550265 -0.9668046 0.01582193 -0.1874595 -0.9816644 -0.03455245 -0.6573383 -0.7534492 -0.01486361 -0.6215704 -0.7833161 -0.008139669 -0.6164548 -0.7873138 0.0109837 -0.5144116 -0.8571814 -0.02491462 -0.496876 -0.867798 0.006415426 -0.3882297 -0.9207819 -0.03792661 -0.3623496 -0.9319863 -0.01021677 -0.2761807 -0.9597965 -0.05014997 -0.5828359 -0.8122456 -0.02365279 -0.5340632 -0.8451325 -0.02296894 -0.5280971 -0.8491814 -0.002141773 -0.4178335 -0.9074954 -0.04321378 -0.3972635 -0.9176675 -0.008271276 -0.3262327 -0.9444806 -0.03909748 -0.2753188 -0.9610995 -0.02208119 -0.1998078 -0.9781526 -0.05739653 -0.1583902 -0.986975 -0.02816277 -0.126322 -0.9909523 -0.04534745 -0.7286035 -0.6849254 -0.003760337 -0.7067649 -0.7074379 0.003872632 -0.7008635 -0.712738 0.02819514 -0.6063837 -0.7951638 -0.003682374 -0.5901484 -0.80681 0.02797406 -0.489257 -0.8720625 -0.01160287 -0.4673621 -0.8839637 0.01345169 -0.3595666 -0.93248 -0.03453826 -0.3329441 -0.9428295 -0.01486265 -0.2700924 -0.9617533 -0.04561543 -0.2310107 -0.97242 -0.03214752 -0.1747438 -0.9827272 -0.06092637 -0.1266524 -0.9912331 -0.03763401 -0.1193347 -0.9919567 -0.04220575 -0.06980925 -0.9971334 -0.0291835 -0.0681349 -0.9972162 -0.03029143 -0.02653443 -0.9994257 -0.02108198 -0.981133 0.1726455 0.08701628 -0.9867812 0.1404902 0.0807811 -0.9387261 0.3359314 0.077093 -0.9465688 0.3141656 0.07285362 -0.8072744 0.5833101 0.08976399 -0.814298 0.5780466 0.05273318 -0.8028489 0.5935603 0.05585753 -0.8059784 0.5913692 0.02610468 -0.8419774 0.5389052 0.02560013 -0.9898741 0.03066128 0.1385976 -0.9955425 0.0380209 0.08631128 -0.9950909 0.04671883 0.08724439 -0.9522087 0.2818415 0.1177458 -0.9403637 0.316708 0.1241466 -0.980493 0.1481964 0.1291181 -0.9819654 0.1389033 0.128257 -0.9885742 0.06522119 0.1358946 -0.990796 0.003329813 0.1353234 -0.9851473 -0.1670095 0.03991031 -0.9888126 -0.1399291 0.0516678 -0.997918 -0.02813166 0.05803668 -0.997693 -0.04393118 0.05175757 -0.995998 0.06972157 0.05591779 -0.9974821 0.05105268 0.04922425 -0.9804539 0.1901695 0.05045562 -0.9838412 0.1735255 0.04410833 -0.9391299 0.3409563 0.04223722 -0.9413901 0.3349747 0.03970694 -0.8769349 0.4792668 0.03589916 -0.8742374 0.4809485 0.06631487 -0.8834041 0.4643443 0.06310051 -0.8765487 0.4691038 0.1077226 -0.8969515 0.4304128 0.1011087 -0.8117865 0.5741837 0.1063758 -0.7893704 0.6028838 0.1158689 -0.8353806 0.5358509 0.1224872 -0.8393349 0.5315749 0.1137762 -0.8005026 0.5852735 0.1290373 -0.8157725 0.5708661 0.09288197 -0.7628278 0.6385205 0.1019082 -0.7745513 0.6290707 0.06588178 -0.7725341 0.5979761 0.2135784 -0.7515475 0.6228197 0.2174218 -0.8035931 0.5463146 0.2361747 -0.8424746 0.5112606 0.1698508 -0.8838599 0.4319201 0.1795459 -0.8840173 0.4317606 0.179154 -0.9203215 0.3438589 0.186466 -0.9244691 0.3400778 0.172349 -0.9037159 0.3850246 0.1872263 -0.9097551 0.3803691 0.166328 -0.9487342 0.2641751 0.1735367 -0.9751051 0.1478312 0.1652758 -0.9511523 0.2631233 0.1614786 -0.9468253 0.2843539 0.1505481 -0.8957523 0.4212068 0.1421711 -0.8892567 0.4363398 0.1372229 -0.823141 0.5535688 0.1264939 -0.8349785 0.5439686 0.08312189 -0.7415602 0.6669623 0.07245689 -0.748247 0.6620674 0.04234766 -0.6782929 0.7338446 0.0372942 -0.6785148 0.734362 0.01817166 -0.6747701 0.7378329 0.01697415 -0.9830532 -0.1236169 0.1353721 -0.9849946 -0.09755003 0.1423719 -0.9681545 -0.2116345 0.1337451 -0.9716238 -0.1904908 0.1402162 -0.9470512 -0.2938664 0.1293708 -0.9512493 -0.2772255 0.1351704 -0.9201292 -0.3720045 0.1223718 -0.9247083 -0.3586283 0.1276731 -0.8882986 -0.4450567 0.1133586 -0.8929839 -0.4342936 0.1181905 -0.8533001 -0.5111346 0.1030551 -0.8577407 -0.5027595 0.1073034 -0.8159112 -0.5708745 0.09160435 -0.8201589 -0.5641116 0.09548634 -0.7766842 -0.6248813 0.07927989 -0.7809224 -0.6190815 0.08305668 -0.7359511 -0.6737807 0.06629848 -0.7404005 -0.6684873 0.0702278 -0.6939826 -0.7180489 0.05285751 -0.6492016 -0.7594866 0.0414431 -0.6821192 -0.7300052 0.04249548 -0.6932723 -0.7204534 0.01790142 -0.7539954 -0.6558131 0.03742039 -0.7846869 -0.6188136 0.03655427 -0.7954997 -0.6042962 0.04479157 -0.8407922 -0.5380688 0.05958604 -0.8344228 -0.5484269 0.05446428 -0.8776568 -0.4743342 0.06874221 -0.8714779 -0.4863079 0.06348979 -0.9119731 -0.4029192 0.07720935 -0.9059596 -0.4172636 0.07161343 -0.9422849 -0.3239678 0.08452337 -0.9367898 -0.3409336 0.07867193 -0.9668412 -0.2389228 0.09018909 -0.9621645 -0.2591882 0.08402913 -0.9845127 -0.1481257 0.09377479 -0.9810809 -0.1728853 0.08712643 -0.9941601 -0.05154448 0.09481012 -0.9928227 -0.08124554 0.08776301 -0.9958094 -0.01218926 0.09063607 -0.9898514 -0.02356958 0.1401382 -0.9893809 -0.05009776 0.1364394 -0.01994645 -0.9990665 -0.03831976 -0.09607023 -0.9947314 -0.03577679 -0.06064313 -0.9976422 -0.03213214 -0.05279308 -0.9978601 -0.03857827 -0.0987426 -0.9941372 -0.04405915 -0.09599447 -0.9942945 -0.04651588 -0.1367806 -0.988847 -0.05893033 -0.1765433 -0.9839215 -0.02703827 -0.2216105 -0.9740482 -0.04603368 -0.2770866 -0.9607871 -0.01055318 -0.3099107 -0.9505322 -0.02107036 -0.3760916 -0.9264032 0.01823037 -0.40583 -0.9139475 0.001414358 -0.4585487 -0.8882447 0.02746802 -0.4710832 -0.8818922 0.0186308 -0.5207144 -0.852708 0.04178184 -0.5532591 -0.832909 0.01292842 -0.5838268 -0.8106287 0.04502564 -0.6318271 -0.7723373 0.06549775 -0.6287661 -0.7750948 0.06229943 -0.6745802 -0.7336661 0.08170437 -0.6721391 -0.7361765 0.07920378 -0.7163169 -0.6908846 0.09781932 -0.7141542 -0.693426 0.09562516 -0.7570316 -0.6434208 0.1136354 -0.7548565 -0.6463572 0.1114192 -0.7965052 -0.5907304 0.1289071 -0.7940784 -0.5945294 0.1263896 -0.8344224 -0.5321456 0.1433884 -0.8315439 -0.5374508 0.1402901 -0.8702621 -0.4669823 0.156753 -0.8668398 -0.4745837 0.1528369 -0.9031565 -0.3948396 0.1685526 -0.8995116 -0.4049679 0.1639509 -0.9314895 -0.3171746 0.1781225 -0.9278689 -0.330444 0.1728184 -0.9543547 -0.2345246 0.1849476 -0.9510145 -0.2522275 0.1787534 -0.9712906 -0.1449065 0.1886713 -0.9689698 -0.1675267 0.1817479 -0.9800325 -0.06530421 0.1878075 -0.9789819 -0.08748489 0.1842305 -0.9823459 -0.006078958 0.186975 -0.9825275 -0.02878129 0.183879 -0.9808614 0.0612623 0.1848186 -0.9826486 0.03558659 0.1820315 -0.980328 0.07677918 0.1818293 -0.9748436 0.1165254 0.1900047 -0.9527977 0.2399448 0.1860192 -0.9473402 0.2422815 0.2093954 -0.9568998 0.2123196 0.198149 -0.9511771 0.2150712 0.2213741 -0.9499796 0.2195815 0.2220876 -0.9225051 0.2340069 0.3069611 -0.9254236 0.225663 0.3044136 -0.8785606 0.2431982 0.411079 -0.8818529 0.2349453 0.4088228 -0.8238937 0.2505348 0.5083616 -0.827568 0.2422332 0.5064132 -0.7596215 0.2559056 0.5979027 -0.7636625 0.2474668 0.5963051 -0.6866891 0.2593018 0.6791323 -0.6910571 0.2507005 0.6779302 -0.605846 0.2607958 0.7516224 -0.6104861 0.2520367 0.7508558 -0.5176712 0.2604871 0.814962 -0.5224786 0.251631 0.8146767 -0.4226732 0.2585091 0.8686314 -0.4275343 0.2496212 0.868852 -0.3214125 0.2549852 0.9119631 -0.3261872 0.2461829 0.9126861 -0.214632 0.2500757 0.9441374 -0.2191732 0.2414547 0.9453374 -0.1034305 0.2439114 0.9642663 -0.1076126 0.2356129 0.9658707 -0.005196511 0.2367345 0.9715605 -0.05611133 0.3801626 0.9232161 -0.2494575 0.8353856 0.4897978 -0.6953698 0.71846 0.01662099 -0.7104907 0.7034818 0.01778542 -0.7038114 0.7095354 0.03477329 -0.7422947 0.6691824 0.03454864 -0.7153494 0.6969917 0.04977703 -0.7739284 0.6306401 0.05768865 -0.7375996 0.6717519 0.06852912 -0.8125001 0.5772631 0.08130824 -0.7635273 0.639144 0.09231019 -0.7982447 0.5951194 0.09294259 -0.8341064 0.5406449 0.1094057 -0.8333534 0.5411862 0.1124266 -0.8178222 0.558276 0.1396244 -0.8160632 0.5608181 0.1397282 -0.7872678 0.5767487 0.2181065 -0.7450941 0.6311402 0.2156313 -0.7498053 0.5915082 0.2964962 -0.6689166 0.6873674 0.2829783 -0.7018144 0.6101103 0.3677257 -0.5948684 0.7289847 0.338693 -0.6445487 0.6315789 0.4308889 -0.5208672 0.7625704 0.3836456 -0.5788903 0.6562886 0.4839125 -0.5113322 0.7313325 0.4513227 -0.4833506 0.7326461 0.4791679 -0.4711186 0.7542744 0.4572936 -0.4588451 0.7367189 0.4966956 -0.3809185 0.8085966 0.4484112 -0.3967742 0.7827216 0.4794967 -0.387951 0.7572697 0.525392 -0.3143622 0.8240045 0.4713736 -0.322483 0.8095172 0.4905982 -0.316012 0.7765717 0.545044 -0.06124889 0.844241 0.5324526 -0.08014732 0.8330327 0.5473874 -0.09582912 0.7687493 0.6323301 -0.1078245 0.888633 0.4457638 -0.1271693 0.8499157 0.5113426 -0.2198836 0.7683376 0.6010896 -0.1755356 0.8523959 0.4925532 -0.281161 0.7582447 0.5882291 -0.05330914 0.8444657 0.5329503 -0.05332636 0.8448225 0.5323827 -0.04521262 0.848398 0.5274244 -0.04145044 0.8485111 0.5275516 -0.041525 0.8493146 0.5262514 -0.03703999 0.8509964 0.5238638 -0.0354833 0.8510113 0.5239473 -0.03582626 0.8519507 0.5223951 -0.03293263 0.8527404 0.5212958 -0.03254061 0.8527882 0.5212422 -0.032889 0.8534244 0.5201779 -0.03097873 0.853946 0.5194387 -0.03157609 0.8538958 0.5194852 -0.03125059 0.8542675 0.5188935 -0.03089201 0.8547764 0.5180763 -0.02988111 0.8547781 0.5181328 -0.03110992 0.8552871 0.5172198 -0.03006511 0.8553845 0.5171204 -0.7159589 0.6979329 0.01710361 -0.0295028 0.8549212 0.5179184 -0.03086394 0.8547396 0.5181388 -0.02418982 0.8630934 0.5044648 -0.03062313 0.8545361 0.5184887 -0.03132045 0.8550386 0.5176178 -0.03106355 0.8550077 0.5176843 -0.03206181 0.8537228 0.5197398 -0.03245556 0.8543231 0.518728 -0.03211188 0.8542656 0.518844 -0.03498744 0.8524913 0.5215694 -0.03537583 0.8534153 0.5200297 -0.03409278 0.8534327 0.5200869 -0.04095435 0.8510282 0.5235208 -0.04110181 0.8519543 0.5220006 -0.03769338 0.8520082 0.5221698 -0.0526359 0.8493603 0.5251825 -0.0526663 0.8496489 0.5247125 -0.04511195 0.8497554 0.5252437 -0.4489367 0.7843215 0.4281304 -0.4641314 0.7571833 0.4596256 -0.4205113 0.755215 0.5028127 -0.4066234 0.7777601 0.479319 -0.3463901 0.7761574 0.5268715 -0.3358867 0.7954759 0.5043792 -0.2726478 0.7940806 0.5432304 -0.2645729 0.8118622 0.5204622 -0.1999686 0.8105951 0.5504074 -0.1942492 0.8267552 0.5279613 -0.1296439 0.8257126 0.5489912 -0.1262183 0.8397839 0.5280455 -0.07803577 0.8394187 0.537854 -0.07747721 0.8463476 0.5269659 -0.06097137 0.8461924 0.5293781 -0.8629447 0.4744942 0.1737288 -0.7949903 0.5911503 0.1361324 -0.7752811 0.5859301 0.2358503 -0.7428724 0.633981 0.2149623 -0.7118389 0.6293032 0.3118701 -0.6822617 0.6716499 0.2888002 -0.6425082 0.6679118 0.3756024 -0.6169577 0.704107 0.351563 -0.5697978 0.7009437 0.4289621 -0.5477486 0.7326784 0.403923 -0.5111873 0.7315059 0.4512059 -0.6575053 0.7533025 0.01490992 -0.7006967 0.7132514 0.01722258 -0.7001408 0.7133155 0.03136932 -0.7199069 0.6932606 0.03352534 -0.7189723 0.6933692 0.04814565 -0.7470872 0.6626938 0.05194032 -0.7457955 0.6628457 0.066518 -0.7837207 0.6168422 0.07271647 -0.7825677 0.6170167 0.08293449 -0.8412553 0.5317246 0.09776777 -0.8278095 0.5522124 0.09895932 -0.8248363 0.5524143 0.120348 -3.66351e-5 0 -1 -3.46704e-6 0 -1 9.2059e-6 0 -1 3.42214e-5 0 -1 3.18826e-6 0 -1 -6.32143e-6 0 -1 -4.16052e-6 0 -1 1.58019e-6 0 -1 -1.45721e-6 0 -1 0 0 -1 1.35735e-6 0 -1 -2.29924e-6 0 -1 3.92804e-6 0 -1 -4.76432e-6 0 -1 -8.64447e-6 0 -1 7.31154e-5 0 -1 8.3127e-6 0 -1 -3.54596e-6 0 -1 2.46464e-6 0 -1 1.70583e-6 0 -1 -1.6945e-6 0 -1 -5.31202e-6 0 -1 8.70624e-7 0 -1 -9.28643e-7 0 -1 3.68497e-6 0 -1 5.06451e-5 0 -1 3.78169e-6 0 -1 -1.14807e-5 0 -1 4.12455e-6 0 -1 -4.18234e-6 0 -1 -1.68693e-6 0 -1 -1.15485e-6 0 -1 4.38866e-6 0 -1 -2.60076e-6 0 -1 -2.83395e-7 0 -1 4.66466e-7 0 -1 1.21917e-6 0 -1 1.99031e-7 0 -1 5.06366e-7 0 -1 -6.46892e-7 0 -1 -1.74223e-6 0 -1 7.56237e-6 0 -1 -4.60671e-6 0 -1 6.63099e-6 0 -1 6.0134e-6 0 -1 -2.86309e-6 0 -1 -1.66476e-6 0 -1 5.81019e-6 0 -1 -4.32408e-6 0 -1 2.12756e-6 0 -1 1.20245e-6 0 -1 4.87741e-6 0 -1 2.52076e-6 0 -1 -2.83673e-6 0 -1 1.4144e-6 0 -1 9.53558e-6 0 -1 7.99841e-6 0 -1 8.85373e-6 0 -1 -4.32184e-5 0 -1 6.97047e-7 0 -1 -1.96728e-6 0 -1 -7.91467e-6 0 -1 1.00186e-6 0 -1 0.02579265 0.8796933 0.4748417 0.06470775 0.8670769 0.4939541 0.08818107 0.8197864 0.5658397 0.08647567 0.8960715 0.4354056 0.1393616 0.8328468 0.5356721 0.1324567 0.8888161 0.438704 0.5568267 0.7609399 0.3330386 0.4813411 0.814652 0.3235012 0.4864133 0.8072642 0.3342552 0.4750666 0.7892152 0.3891671 0.4435252 0.8255243 0.3489915 0.4230244 0.8118928 0.4023435 0.4276909 0.8048142 0.411527 0.35632 0.8475625 0.3932862 0.3759493 0.8157222 0.4396131 0.306244 0.859002 0.4102808 0.3041557 0.8625894 0.4042633 0.3067849 0.8057309 0.5066368 0.2558824 0.8848001 0.3894265 0.2539733 0.8249521 0.5049272 0.242596 0.8503829 0.4669008 0.1888397 0.8670569 0.4610335 0.1937092 0.8536368 0.4835093 0.1560186 0.8683475 0.4707769 0.5614475 0.7773095 0.2838426 0.5377761 0.7945623 0.2819005 0.556288 0.7617495 0.3320867 0.5992534 0.7544145 0.2678695 0.567868 0.7982986 0.2006124 0.6787803 0.6793673 0.2787783 0.6222472 0.7633296 0.1735985 0.6531478 0.7305176 0.1993541 0.6867258 0.7083321 0.1633198 0.6815555 0.7163024 0.1496433 0.7169879 0.6894313 0.1030191 0.7113937 0.6948037 0.1056742 0.7086361 0.6980543 0.1027387 0.7166525 0.6843541 0.1344198 0.7264519 0.6802961 0.09728777 0.7207583 0.6874683 0.08885377 0.7011644 0.7082009 0.08258289 0.7020989 0.707848 0.07751464 0.6335693 0.7709267 0.06528419 0.652665 0.7550702 0.06243014 0.6438344 0.7630813 0.05643105 0.6528732 0.7556899 0.0518608 0.6164357 0.7860211 0.04666882 0.6116194 0.7903932 0.03464764 0.5830388 0.8118327 0.03152012 0.5940757 0.8040699 0.02336037 0.5508829 0.8344184 0.01655983 0.5949382 0.8036535 0.01377385 0.5708112 0.8210363 0.008613348 0.5350579 0.8447768 0.008097112 0.6452248 0.7610971 0.06645375 0.6460076 0.7612285 0.05661648 0.6380328 0.7681368 0.0536673 0.6384191 0.7681725 0.04829406 0.6108629 0.7904915 0.04438114 0.61151 0.7905473 0.03302234 0.5860547 0.8097012 0.03039693 0.5865215 0.8097425 0.01759916 0.5696011 0.8217599 0.01628768 0.5697602 0.821793 0.00545603 0.597034 0.8021718 0.008406281 0.702165 0.7086554 0.06907886 0.6978734 0.712235 0.07545912 0.6975878 0.7121742 0.07860809 0.7368097 0.6681026 0.1036847 0.7160954 0.6898504 0.1063671 0.7188981 0.6899335 0.08471906 0.6976122 0.7058334 0.1230309 0.6893593 0.7067606 0.1589757 0.6720352 0.725681 0.1474983 0.6542353 0.7274677 0.2068022 0.6321631 0.750462 0.1928128 0.6074004 0.7522596 0.2552847 0.5879846 0.7721941 0.2408118 0.5587512 0.7736437 0.2987851 0.5418065 0.7910503 0.2840515 0.5217698 0.7921516 0.3166261 0.5215708 0.7944955 0.3110318 0.5011339 0.7948325 0.3422081 0.4870158 0.809716 0.3273772 0.4505667 0.8107275 0.3737788 0.4386012 0.8238698 0.3589813 0.4075573 0.8247349 0.392058 0.4027143 0.8314158 0.3828433 0.3705931 0.8317758 0.4132915 0.3624712 0.8417195 0.4001537 0.3206509 0.8422541 0.4333488 0.314815 0.8502244 0.4219123 0.271285 0.8506199 0.4503893 0.2672081 0.8570602 0.4405084 0.2302208 0.8574889 0.4601207 0.2287799 0.860985 0.4542737 0.1918522 0.8610548 0.4709323 0.1900666 0.8651654 0.4640728 0.1441705 0.8652922 0.4800879 0.1434415 0.8676567 0.4760217 0.09630024 0.867696 0.4876781 0.09612542 0.8686382 0.4860327 0.06433886 0.8688391 0.4908963 0.06432247 0.86887 0.4908437 0.02842646 0.8684944 0.4948834 -0.4040256 0.5018746 -0.7647778 -0.5066685 0.63012 -0.5884181 -0.5117495 0.6566812 -0.5539696 -0.2758033 0.3965184 -0.8756174 -0.3487043 0.4337056 -0.8308457 -0.1634737 0.2029446 -0.965448 -0.1092439 0.1629394 -0.9805696 -0.04151594 0.05159616 -0.9978047 -0.6226893 0.7472041 -0.2322589 -0.6158191 0.7640053 -0.1925177 -0.6161028 0.7637762 -0.1925181 -0.6143851 0.7641268 -0.196574 -0.5623131 0.6980097 -0.4433807 -0.535207 0.6377371 -0.5539358 -0.4969271 0.617655 -0.6095621 -0.3493559 0.4331826 -0.8308449 -0.1222176 0.1517922 -0.9808273 -0.1227556 0.1521019 -0.9807121 -0.2770411 0.3441987 -0.8970928 -0.4004231 0.4581807 -0.7935565 -0.6888216 -0.5102593 -0.5149371 -0.6001003 0.5795183 -0.5513966 -0.4134972 0.7110316 -0.5687304 -0.8692052 0.461098 -0.1785252 -0.6990153 0.6770719 -0.2301118 -0.6478797 0.738161 -0.1880701 -0.4494218 0.8637291 -0.228018 -0.6773438 0.4937392 -0.5453688 0.5457733 0.6591651 -0.5173324 -0.188354 0.1819311 -0.965103 -0.3988529 0.3906581 -0.82964 0.04724681 0.6666535 -0.7438688 -0.4613974 0.4510494 -0.7639811 -0.5303375 0.6106097 -0.5881309 -0.4242143 0.4853624 -0.7645035 -0.6224552 0.1259707 -0.7724512 -0.316363 0.3641234 -0.8759729 -0.1723012 0.1958008 -0.9653882 -0.5479017 0.8132847 -0.1958875 -0.4435581 0.6583172 -0.6081732 -0.5012985 0.7438073 -0.4420979 -0.2476289 0.3674867 -0.8964561 -0.3406962 0.5054729 -0.7927317 -0.1092881 0.1621708 -0.980692 -0.4964548 0.8282806 -0.259777 -0.3959898 0.8809676 -0.2590142 -0.3963643 0.8808995 -0.2586724 -0.2424625 0.9350299 -0.2587107 -0.2428683 0.9350237 -0.2583521 -0.08204776 0.9625708 -0.258313 -0.08245223 0.9626361 -0.2579409 -0.3314301 0.6241649 -0.7075114 -0.2902453 0.6456898 -0.7062877 -0.2905221 0.6457276 -0.7061395 -0.1777232 0.6853514 -0.7061926 -0.1780146 0.6854341 -0.706039 -0.06015634 0.7056725 -0.7059798 -0.06042945 0.7058145 -0.7058145 -0.08974868 0.2457617 -0.9651666 -0.1063552 0.2366906 -0.9657465 -0.1064666 0.2367129 -0.9657288 -0.06511336 0.2512206 -0.9657373 -0.06521826 0.2512602 -0.9657199 -0.02201455 0.2586967 -0.9657078 -0.0221219 0.2587571 -0.9656891 -0.5709626 0.3194611 -0.7562714 -0.3367398 0.347822 -0.8750008 -0.1366253 0.1413844 -0.9804815 -0.2453967 0.1173605 -0.9622926 -0.04680585 0.04836428 -0.9977325 -0.3900913 0.4007893 -0.8289734 -0.5795788 0.6011759 -0.5501602 -0.6405582 0.4954687 -0.5866821 -0.5788884 0.7936335 -0.1871741 -0.6760029 0.7001776 -0.2297203 0 0.2588198 -0.9659256 0 0.2588205 -0.9659255 0 0.7071079 -0.7071057 0 0.7071066 -0.707107 0 0.9659251 -0.2588217 -0.02178096 -0.9851645 -0.1702247 -0.08768856 -0.9779391 -0.1895942 -0.03146684 -0.9423505 -0.3331449 0.003643333 -0.8734834 -0.4868403 -0.1149981 -0.5245975 -0.8435479 0.02586942 -0.6629039 -0.7482575 -0.04826509 -0.7784457 -0.6258537 -3.99695e-4 -0.01653826 -0.9998633 -0.1532397 -0.1138584 -0.9816078 -0.06870073 -0.2167636 -0.9738038 0.04033666 -0.3777345 -0.9250349 -0.02841222 -0.9767811 -0.2123472 -0.03721415 -0.9764862 -0.2123439 -0.0343154 -0.9768168 -0.2113089 -0.04397708 -0.9764285 -0.2113133 -0.04061758 -0.9766395 -0.2110108 -0.04755747 -0.9763262 -0.2110108 -0.04434734 -0.9766016 -0.2104345 -0.05948936 -0.9757986 -0.2104235 -0.05674028 -0.9763844 -0.2084566 -0.1077261 -0.9721141 -0.2083015 -0.1067185 -0.9728903 -0.2051724 -0.1830124 -0.9614592 -0.2051896 -0.1840013 -0.9605767 -0.208413 -0.2477806 -0.9461209 -0.2084707 -0.2499483 -0.9442577 -0.2142506 -0.2926663 -0.9318885 -0.2143135 -0.3144356 -0.9178705 -0.2421659 -0.3302972 -0.9182713 -0.2183614 -0.3873972 -0.8957019 -0.2182697 -0.3882964 -0.8943852 -0.2220387 -0.4570047 -0.8613087 -0.222023 -0.4573503 -0.8606994 -0.2236677 -0.5247865 -0.8213163 -0.2236934 -0.5243103 -0.8222262 -0.2214565 -0.5692139 -0.7917692 -0.221579 -0.5838198 -0.7739955 -0.2451235 -0.6017955 -0.7685837 -0.2170748 -0.650181 -0.7281439 -0.2169589 -0.6388408 -0.7300307 -0.242771 -0.6741901 -0.7076818 -0.2113153 -0.7132372 -0.668372 -0.2111199 -0.7124966 -0.6711827 -0.204603 -0.7536997 -0.6245 -0.2047841 -0.7523626 -0.6268652 -0.2024617 -0.7906977 -0.5778237 -0.2022795 -0.790111 -0.5808066 -0.1959295 -0.8423513 -0.5020577 -0.1959142 -0.8419852 -0.504982 -0.1898795 -0.8895762 -0.4154626 -0.1898551 -0.8894568 -0.4181714 -0.1843895 -0.9215511 -0.34158 -0.1845723 -0.921221 -0.3437954 -0.1820898 -0.947009 -0.26473 -0.1819123 -0.9471409 -0.2666137 -0.1784417 -0.97108 -0.1586439 -0.1784266 -0.971245 -0.1595918 -0.176674 -0.9823131 -0.06163018 -0.1768126 -0.9823 -0.06157588 -0.1769044 -0.983579 0.03633612 -0.1767823 -0.9830409 0.03776931 -0.1794553 -0.9769761 0.1150076 -0.1796972 -0.9662733 0.1531145 -0.2070552 -0.9672536 0.1740302 -0.1847539 -0.9465106 0.2646182 -0.1846479 -0.9454184 0.2365493 -0.2241177 -0.9386861 0.2893862 -0.1874144 -0.9107856 0.368026 -0.1871541 -0.9106307 0.3682079 -0.1875495 -0.8622028 0.4705582 -0.1875672 -0.8626013 0.4701892 -0.1866576 -0.8271929 0.5299227 -0.1869062 -0.8276042 0.5294058 -0.1865499 -0.7883309 0.5863665 -0.1863031 -0.7887731 0.586077 -0.1853396 -0.7254469 0.6628438 -0.1853782 -0.7253718 0.6628826 -0.185533 -0.663553 0.7247516 -0.1855603 -0.6626186 0.7251186 -0.1874557 -0.09377676 -0.8199655 -0.5646792 -0.03124338 -0.8238254 -0.5659819 -0.02917706 -0.8243266 -0.5653623 -0.03690743 -0.824011 -0.5653704 -0.03452152 -0.8242406 -0.5651866 -0.03997379 -0.8239915 -0.5651904 -0.03766512 -0.8243374 -0.5648446 -0.05007255 -0.8236927 -0.5648215 -0.04812389 -0.8246205 -0.5636357 -0.09094673 -0.8212093 -0.563333 -0.09031051 -0.8225685 -0.5614492 -0.1547895 -0.8128789 -0.5614876 -0.1553489 -0.8114308 -0.5634243 -0.2094096 -0.7991012 -0.5635467 -0.2106011 -0.7963241 -0.567023 -0.2659326 -0.7796995 -0.5668764 -0.2663992 -0.7777372 -0.5693473 -0.3264005 -0.7545061 -0.5693709 -0.326672 -0.752676 -0.5716332 -0.3846022 -0.724804 -0.5716121 -0.3846588 -0.7240062 -0.5725843 -0.4413764 -0.6908585 -0.5726269 -0.4413387 -0.6919921 -0.5712856 -0.4952708 -0.6545173 -0.571239 -0.4954202 -0.6567512 -0.5685392 -0.5492383 -0.6124743 -0.5685178 -0.54964 -0.6153478 -0.565016 -0.6019656 -0.5642944 -0.5649862 -0.6026643 -0.5674736 -0.5610433 -0.6371389 -0.528104 -0.5613914 -0.6366346 -0.5301941 -0.5599917 -0.6690251 -0.4890943 -0.5596357 -0.6699359 -0.4922321 -0.5557819 -0.7140513 -0.4257635 -0.5557484 -0.7151463 -0.4286983 -0.5520721 -0.7554395 -0.3529696 -0.5520179 -0.7566577 -0.3555571 -0.5486787 -0.7836316 -0.2905893 -0.5490714 -0.7840057 -0.2924284 -0.547559 -0.806088 -0.2254415 -0.5471732 -0.8070743 -0.2270726 -0.5450406 -0.8274549 -0.1352338 -0.5450049 -0.8280408 -0.1360158 -0.5439193 -0.8372881 -0.05253541 -0.5442321 -0.8372613 -0.05249267 -0.5442777 -0.8385099 0.03105247 -0.544001 -0.8374135 0.03207701 -0.5456278 -0.8280608 0.129044 -0.545585 -0.8257642 0.1307357 -0.5486544 -0.8054007 0.2237424 -0.5488798 -0.8040798 0.224672 -0.5504346 -0.7741657 0.3128385 -0.5502722 -0.7739409 0.3129391 -0.5505313 -0.7327749 0.3998983 -0.5505656 -0.7332407 0.3997553 -0.5500488 -0.7029337 0.4502837 -0.5505715 -0.7033063 0.4499588 -0.5503612 -0.6702166 0.4984908 -0.5498333 -0.6707141 0.4984336 -0.5492783 -0.6168597 0.5636397 -0.5493583 -0.6167485 0.5636417 -0.549481 -0.5641316 0.6162451 -0.5495432 -0.5631005 0.6161423 -0.5507146 -0.09195142 -0.5451241 -0.8332976 -0.02084028 -0.5488869 -0.8356369 -0.01956057 -0.5493118 -0.8353885 -0.02462863 -0.5491069 -0.8353892 -0.02312499 -0.5492725 -0.8353233 -0.02668082 -0.5491191 -0.8353182 -0.02522689 -0.5493961 -0.8351811 -0.03338932 -0.5489833 -0.8351662 -0.03221213 -0.549774 -0.8346922 -0.06065708 -0.5476678 -0.8344943 -0.06030982 -0.5488507 -0.833742 -0.1032729 -0.5423731 -0.8337664 -0.103548 -0.5411251 -0.8345428 -0.1396149 -0.5328353 -0.8346222 -0.1401833 -0.5305042 -0.8360108 -0.1771744 -0.5194758 -0.8359152 -0.1773127 -0.51783 -0.8369064 -0.2173076 -0.5023397 -0.8369184 -0.2173062 -0.5008314 -0.8378221 -0.2558971 -0.4822763 -0.8378103 -0.2558488 -0.4816379 -0.8381923 -0.2936024 -0.4595472 -0.8382208 -0.2937114 -0.4604488 -0.8376877 -0.3295867 -0.4355527 -0.8376553 -0.3299834 -0.4373199 -0.8365778 -0.3657811 -0.4078853 -0.8365607 -0.3664634 -0.4101335 -0.8351618 -0.4012974 -0.3761723 -0.8351376 -0.4022666 -0.3786337 -0.8335575 -0.4250661 -0.3522996 -0.8337888 -0.4249559 -0.3537592 -0.8332268 -0.446662 -0.32653 -0.8329893 -0.4478106 -0.3288868 -0.8314442 -0.4772501 -0.284564 -0.8314179 -0.4785245 -0.286737 -0.8299375 -0.5054602 -0.2361703 -0.8298997 -0.5067902 -0.2380449 -0.828552 -0.5246211 -0.1945322 -0.8288124 -0.5251134 -0.1957698 -0.828209 -0.5400917 -0.1510494 -0.8279404 -0.5410919 -0.1521777 -0.8270802 -0.5547616 -0.0906732 -0.8270539 -0.5553399 -0.09119826 -0.8266078 -0.5613627 -0.03523129 -0.8268197 -0.5613365 -0.03520143 -0.8268387 -0.5623299 0.02081036 -0.8266511 -0.5613488 0.02144116 -0.8273016 -0.5551089 0.08645057 -0.827273 -0.5531457 0.08741432 -0.8284857 -0.5393576 0.149815 -0.8286429 -0.5382586 0.1503245 -0.8292649 -0.5182896 0.2094522 -0.8291597 -0.5180975 0.209498 -0.829268 -0.490511 0.2677196 -0.829292 -0.4908605 0.2676765 -0.8290992 -0.4703429 0.3013034 -0.8294541 -0.4706145 0.3011183 -0.8293672 -0.4487155 0.3337653 -0.8290086 -0.4490818 0.333793 -0.828799 -0.4130094 0.3773961 -0.8288519 -0.4129005 0.3773779 -0.8289145 -0.3776609 0.4125622 -0.8289541 -0.3768624 0.4123304 -0.8294327 -0.03259652 -0.191628 -0.9809262 -0.007437944 -0.1924833 -0.9812722 -0.007007718 -0.1926439 -0.9812437 -0.008771896 -0.19257 -0.981244 -0.008309185 -0.1926343 -0.9812355 -0.009515702 -0.1925811 -0.9812349 -0.009022951 -0.1926832 -0.9812196 -0.01183968 -0.1925442 -0.981217 -0.01144129 -0.1928475 -0.981162 -0.02133303 -0.1921563 -0.9811325 -0.02122277 -0.1926131 -0.9810453 -0.03619003 -0.1903504 -0.981049 -0.03627228 -0.1898688 -0.9811393 -0.04885888 -0.1869596 -0.9811519 -0.04902732 -0.1860699 -0.9813126 -0.06206923 -0.1822019 -0.9813002 -0.06209433 -0.1815739 -0.9814149 -0.07612514 -0.1761358 -0.981418 -0.07609945 -0.1755633 -0.9815226 -0.08966022 -0.1690468 -0.9815214 -0.08963137 -0.168808 -0.9815652 -0.1029269 -0.1610208 -0.9815694 -0.1029875 -0.1613628 -0.9815068 -0.1155897 -0.1526223 -0.9815016 -0.1157721 -0.1532834 -0.9813771 -0.1283369 -0.1429554 -0.9813733 -0.1286383 -0.1437931 -0.9812114 -0.1408572 -0.1318825 -0.9812065 -0.1412742 -0.1327987 -0.981023 -0.1492394 -0.1235282 -0.9810547 -0.1492376 -0.1240462 -0.9809897 -0.1568808 -0.11453 -0.9809543 -0.1573635 -0.1154001 -0.9807749 -0.1676964 -0.09984803 -0.9807692 -0.1682216 -0.1006428 -0.9805981 -0.1776893 -0.08289462 -0.9805892 -0.1782262 -0.08357787 -0.9804337 -0.1844418 -0.06827747 -0.9804691 -0.184641 -0.06871396 -0.9804011 -0.1899541 -0.0530371 -0.9803594 -0.1903486 -0.05344468 -0.9802608 -0.1951527 -0.0318551 -0.9802555 -0.1953852 -0.03204655 -0.9802029 -0.1974576 -0.01239842 -0.9802331 -0.1974466 -0.01239234 -0.9802354 -0.1978338 0.007244348 -0.9802088 -0.1974591 0.007460951 -0.9802828 -0.1952729 0.03023976 -0.9802826 -0.1945359 0.03056114 -0.9804192 -0.1896399 0.05257892 -0.9804449 -0.1892257 0.05274879 -0.9805158 -0.1822028 0.07362425 -0.9805008 -0.1821177 0.07363939 -0.9805155 -0.1723943 0.09414243 -0.9805189 -0.1725302 0.09413212 -0.9804961 -0.1652653 0.1059038 -0.9805468 -0.165351 0.1058459 -0.9805385 -0.1577212 0.1173587 -0.9804851 -0.1578496 0.1173744 -0.9804626 -0.1451818 0.1326723 -0.9804695 -0.1451353 0.1326608 -0.9804779 -0.1327753 0.1449897 -0.980484 -0.1324753 0.1448842 -0.9805402 0.08186066 0.9626834 -0.2579526 0.06002408 0.7058341 -0.7058296 0.0219677 0.2587567 -0.9656927 0.08223325 0.9625557 -0.2583107 0.2438601 0.934778 -0.2583069 0.2441963 0.9345944 -0.2586532 0.3973156 0.8804643 -0.2586949 0.3975971 0.8802443 -0.2590108 0.5394651 0.8011935 -0.2589721 0.5396864 0.8009474 -0.2592718 0.4434494 0.6584292 -0.6081313 0.06026256 0.7056539 -0.7059894 0.1787842 0.6852905 -0.7059839 0.1789794 0.6850843 -0.7061345 0.2912225 0.6453529 -0.7061935 0.291373 0.6451333 -0.706332 0.3314819 0.6241562 -0.7074947 0.3406149 0.50558 -0.7926983 0.02205806 0.2586852 -0.9657099 0.06550997 0.2512212 -0.9657103 0.06557357 0.2511386 -0.9657275 0.1067192 0.2365569 -0.9657391 0.1067715 0.2364675 -0.9657551 0.1449055 0.2152563 -0.965747 0.1449398 0.2151686 -0.9657613 3.09849e-4 -0.01653867 -0.9998632 0.1426318 -0.1140418 -0.983184 0.4281152 -0.4772367 -0.767439 -0.3308425 -0.3567544 -0.873653 0.4175291 -0.1974404 -0.8869537 0.1995878 -0.7636712 -0.6139798 -0.2437795 -0.6431198 -0.725926 0.4069872 -0.9000959 -0.1555275 0.07173216 -0.9403952 -0.3324325 -0.129597 -0.8661249 -0.4827343 0.339644 -0.9155181 -0.2155658 0.2716134 -0.9379402 -0.2156252 0.2741895 -0.9383073 -0.210712 0.2079617 -0.9551859 -0.2106462 0.2099399 -0.9558349 -0.205682 0.1342191 -0.9693704 -0.2056853 0.1339673 -0.9692634 -0.2063519 0.07765781 -0.9753663 -0.20647 0.07553106 -0.9749023 -0.2094295 0.05405175 -0.976321 -0.2094657 0.05108547 -0.9762549 -0.210515 0.04695755 -0.9764633 -0.2105097 0.04371815 -0.9764894 -0.2110858 0.04398745 -0.9764771 -0.2110868 0.04060292 -0.9765923 -0.2112317 0.04034167 -0.9766032 -0.2112314 0.03774845 -0.9766079 -0.2116889 0.03439688 -0.976731 -0.2116922 0.02530777 -0.9764842 -0.2140985 0.02649521 -0.9763396 -0.2146133 0.02120065 -0.9764662 -0.2146258 0.4192473 -0.8676697 -0.2671725 0.3903244 -0.8941197 -0.2195384 0.3380233 -0.9152078 -0.2193972 0.4095423 -0.8845571 -0.223235 0.4787726 -0.849092 -0.2232033 0.4787756 -0.8490912 -0.2231997 0.5431426 -0.8094165 -0.2232513 0.5444568 -0.8092983 -0.2204613 0.6040609 -0.7658478 -0.2204264 0.6061741 -0.7655736 -0.2155229 0.6522438 -0.7266892 -0.2156407 0.6739836 -0.6888299 -0.2669448 0.6673474 -0.7146746 -0.209494 0.7231993 -0.6580832 -0.209546 0.7251722 -0.6519306 -0.221612 0.7534801 -0.6253282 -0.203058 0.766151 -0.6097419 -0.2030458 0.7681447 -0.6079199 -0.2009654 0.8015726 -0.5631724 -0.2007936 0.804136 -0.561718 -0.1945205 0.8523053 -0.4855343 -0.1945046 0.8545835 -0.4838556 -0.1886023 0.8983359 -0.3967757 -0.1885777 0.9001973 -0.3950115 -0.1833331 0.9289299 -0.3215799 -0.1835096 0.9300071 -0.3197684 -0.1812048 0.9528594 -0.2434911 -0.181028 0.9538058 -0.2420874 -0.1778998 0.9747271 -0.1351545 -0.1778773 0.9750499 -0.1345205 -0.1765847 0.983722 -0.03275501 -0.1766871 0.9836118 -0.03312373 -0.1772302 0.9817073 0.06982815 -0.1771298 0.9811838 0.06773167 -0.1808062 0.9655483 0.1871787 -0.1807775 0.9651721 0.1843025 -0.185676 0.9464058 0.2640258 -0.1860284 0.9328702 0.2965009 -0.2045499 0.9306678 0.3140441 -0.1877065 0.5732257 -0.1467884 -0.8061425 0.005330622 -0.1922268 -0.9813361 0.005958676 -0.1926266 -0.9812541 0.007659077 -0.192563 -0.9812548 0.008062183 -0.1926127 -0.9812418 0.008296728 -0.1926009 -0.9812422 0.008749067 -0.1926012 -0.9812381 0.008895993 -0.1925953 -0.981238 0.009431064 -0.1926574 -0.9812209 0.01032555 -0.1926104 -0.981221 0.01076614 -0.1927334 -0.9811921 0.0150904 -0.19248 -0.9811848 0.01543629 -0.1928722 -0.9811025 0.02652662 -0.1917788 -0.9810796 0.02657634 -0.1918664 -0.9810612 0.04140263 -0.1892161 -0.9810623 0.04099565 -0.1885852 -0.9812008 0.05390745 -0.1852386 -0.9812139 0.05338108 -0.184673 -0.9813493 0.06677347 -0.1803182 -0.9813393 0.06638574 -0.1798758 -0.9814468 0.08044576 -0.1740278 -0.9814494 0.08003139 -0.1736238 -0.9815548 0.09390991 -0.1665449 -0.9815518 0.09390878 -0.1665447 -0.9815518 0.1065935 -0.1586766 -0.9815598 0.1069601 -0.1589087 -0.9814823 0.1187676 -0.1503361 -0.9814752 0.1194214 -0.1507115 -0.9813382 0.13139 -0.1404244 -0.9813346 0.1322234 -0.1408118 -0.9811673 0.1437916 -0.129015 -0.9811621 0.1447548 -0.1293531 -0.980976 0.1519082 -0.1206123 -0.981008 0.1524005 -0.1204746 -0.9809485 0.1592221 -0.1116043 -0.9809143 0.160187 -0.1117768 -0.9807376 0.1698553 -0.09652602 -0.9807303 0.1707755 -0.09658598 -0.9805646 0.1795807 -0.07911998 -0.9805564 0.1804249 -0.0790767 -0.9804049 0.1860352 -0.06422376 -0.9804418 0.1864532 -0.06402051 -0.9803757 0.1912243 -0.048743 -0.9803354 0.1917151 -0.04860407 -0.9802464 0.1959439 -0.02713125 -0.9802397 0.196143 -0.02704519 -0.9802023 0.1977738 -0.006626844 -0.9802253 0.1977035 -0.006679117 -0.9802392 0.1974368 0.01383525 -0.980218 0.1969727 0.01349115 -0.9803162 0.1938829 0.03729814 -0.9803155 0.1933283 0.03676736 -0.980445 0.1874324 0.05949962 -0.9804739 0.1872523 0.05923765 -0.9805242 0.1794933 0.07986748 -0.9805119 0.1794982 0.07987391 -0.9805104 0.1692989 0.09963202 -0.9805159 0.1693676 0.09976518 -0.9804905 0.1570403 0.1183763 -0.980472 0.1570949 0.1184899 -0.9804496 0.1435588 0.1344339 -0.9804685 0.1435341 0.1343606 -0.9804821 0.1309518 0.1466204 -0.9804868 0.1308571 0.1462669 -0.9805521 0.4934275 -0.4703283 -0.7316561 0.01458382 -0.5482549 -0.8361843 0.0164532 -0.5492794 -0.8354769 0.02147006 -0.5490948 -0.8354843 0.02258229 -0.5492182 -0.8353739 0.02315539 -0.5491923 -0.8353752 0.02469325 -0.5491858 -0.8353356 0.0249207 -0.5491714 -0.8353382 0.02629387 -0.5493152 -0.8352015 0.0290156 -0.5491816 -0.8351992 0.03033381 -0.5494937 -0.8349471 0.04270726 -0.5487394 -0.834902 0.04371064 -0.54974 -0.8341915 0.07555812 -0.5465099 -0.8340371 0.07569569 -0.5467367 -0.833876 0.1182435 -0.5391359 -0.8338772 0.1170877 -0.5375307 -0.8350756 0.1540375 -0.5279992 -0.8351584 0.152555 -0.5265779 -0.836327 0.190613 -0.5141552 -0.8362484 0.1895359 -0.5130422 -0.8371762 0.229673 -0.4963535 -0.8371879 0.228528 -0.4953383 -0.8381021 0.2679524 -0.47521 -0.8380793 0.2679543 -0.4752127 -0.8380773 0.3040241 -0.4528829 -0.8381328 0.3050183 -0.4534469 -0.8374664 0.3386036 -0.4290367 -0.8374217 0.3403594 -0.4299454 -0.836243 0.3744176 -0.4006607 -0.8362311 0.3766643 -0.4015774 -0.8347812 0.4095851 -0.3679899 -0.8347596 0.4121584 -0.368763 -0.8331503 0.432609 -0.3439896 -0.833379 0.4339491 -0.3435176 -0.832877 0.4532732 -0.3181926 -0.8326446 0.4558354 -0.3185207 -0.831119 0.4833264 -0.2751066 -0.8310909 0.4857876 -0.2751455 -0.8296418 0.510826 -0.2254258 -0.8296024 0.5130172 -0.2252051 -0.8283091 0.5291424 -0.1829948 -0.8285658 0.5302356 -0.1823813 -0.8280021 0.5436728 -0.1388147 -0.8277381 0.5449703 -0.1383813 -0.8269571 0.5569916 -0.07720142 -0.8269222 0.5575175 -0.07695096 -0.8265911 0.5622511 -0.01876938 -0.8267536 0.5620652 -0.01892071 -0.8268765 0.5611994 0.0396859 -0.8267287 0.5599806 0.03869163 -0.8276019 0.5511678 0.106533 -0.8275656 0.5497197 0.1050097 -0.8287227 0.5331336 0.1694042 -0.8288974 0.5326754 0.168684 -0.8293387 0.5106312 0.2271693 -0.8292466 0.5106436 0.2271971 -0.8292313 0.4817025 0.2833212 -0.8292719 0.4818805 0.283712 -0.8290348 0.4467481 0.3366127 -0.8289198 0.4468935 0.3369446 -0.8287066 0.4083894 0.382421 -0.828838 0.4083411 0.3822352 -0.8289475 0.3724449 0.417225 -0.8289802 0.3722667 0.4162773 -0.8295366 0.4233238 -0.7434144 -0.5178148 0.02162355 -0.8231891 -0.5673554 0.0246694 -0.8243134 -0.5655961 0.03202301 -0.8240593 -0.5655978 0.03391313 -0.8241719 -0.5653237 0.03456437 -0.8241476 -0.5653195 0.03692728 -0.824101 -0.5652378 0.037117 -0.8240947 -0.5652347 0.03947794 -0.8242233 -0.5648873 0.04332959 -0.8240306 -0.564886 0.04549288 -0.8243482 -0.5642521 0.06392532 -0.82317 -0.564185 0.06552082 -0.8242623 -0.5624046 0.1132479 -0.8192301 -0.5621716 0.1134538 -0.8194768 -0.5617706 0.1773492 -0.8080617 -0.5617682 0.1756528 -0.8063386 -0.5647692 0.2312725 -0.7920951 -0.564888 0.229075 -0.790623 -0.567838 0.2862462 -0.7718594 -0.5677115 0.2847294 -0.7707075 -0.5700344 0.3451132 -0.7456148 -0.5700487 0.3435315 -0.7445926 -0.5723357 0.4027782 -0.7143116 -0.5723012 0.4027762 -0.7143124 -0.5723016 0.4569634 -0.6808464 -0.5723921 0.4583081 -0.681354 -0.5707106 0.5086556 -0.6446937 -0.5706484 0.5109661 -0.6454766 -0.5676915 0.5619874 -0.601589 -0.5676803 0.5648924 -0.6022791 -0.5640537 0.6141549 -0.5519856 -0.5640263 0.6174163 -0.5524314 -0.560015 0.6481823 -0.5156145 -0.5603583 0.6500459 -0.5146341 -0.5590994 0.67869 -0.4766228 -0.5587581 0.6818956 -0.4764989 -0.5549479 0.7229235 -0.4116453 -0.5549142 0.7259384 -0.4111748 -0.5513154 0.7632617 -0.3369561 -0.5512642 0.7658953 -0.336215 -0.5480547 0.7902272 -0.273418 -0.5484376 0.7915853 -0.2722915 -0.5470376 0.8113162 -0.2072247 -0.5466479 0.8128193 -0.2063931 -0.5447264 0.8307018 -0.1151565 -0.5446774 0.8312915 -0.1147271 -0.543868 0.8385524 -0.0279566 -0.5441032 0.8383346 -0.02820855 -0.5444259 0.836853 0.05934947 -0.5442011 0.8355244 0.05777901 -0.546407 0.8222942 0.1591753 -0.5463476 0.8207837 0.1568687 -0.549278 0.7962261 0.2530436 -0.5495389 0.7958076 0.2520095 -0.5506192 0.7627781 0.3393083 -0.5504905 0.7628 0.3393699 -0.550422 0.7196442 0.4231753 -0.5504861 0.7197886 0.423734 -0.5498671 0.6672279 0.5026322 -0.5496981 0.6673409 0.5031065 -0.5491265 0.6099605 0.5711343 -0.5493214 0.6099386 0.570921 -0.5495672 0.5563064 0.6232561 -0.5496137 0.5563045 0.6220566 -0.5509728 0.9045975 0.3827365 -0.1876601 0.8934499 0.3974162 -0.2093032 0.8806396 0.4350465 -0.1876394 0.8467829 0.4978374 -0.1873943 0.8466551 0.4984576 -0.1863207 0.7847957 0.5911091 -0.1862418 0.7846748 0.5915868 -0.1852316 0.7173215 0.6716434 -0.1853239 0.7173924 0.6714707 -0.1856752 0.6542703 0.7331081 -0.1856961 0.6547956 0.7320778 -0.1878957 0.1225723 0.1522283 -0.9807153 0.1420227 0.2174897 -0.9656748 0.3624462 0.4224785 -0.8307495 0.3816831 0.4735491 -0.7937692 0.521728 0.6486779 -0.5540912 0.5179046 0.6004298 -0.6093102 0.5873034 0.7861365 -0.1925211 0.6064934 0.7513245 -0.2601491 0.1228416 0.1526641 -0.980614 0.1226843 0.1521386 -0.9807153 0.3494908 0.4346702 -0.8300108 0.3491654 0.4332779 -0.8308753 0.5224405 0.6499433 -0.5519327 0.5223526 0.6481774 -0.5540883 0.6151046 0.7654366 -0.1890857 0.6158083 0.7639828 -0.1926409 0.5626313 0.8047629 -0.1892164 0.5590346 0.8076818 -0.1874315 0.4783798 0.6844792 -0.5501282 0.4748235 0.6860737 -0.5512219 0.3207089 0.4581884 -0.828981 0.3175612 0.4596006 -0.8294108 0.1135929 0.1604614 -0.980484 0.1170324 0.1572598 -0.9805982 0.1169366 0.1574076 -0.9805859 0.3332251 0.4474417 -0.8299139 0.3328174 0.447912 -0.8298237 0.4982355 0.6687208 -0.5518822 0.4973541 0.6695756 -0.5516408 0.5868527 0.7872511 -0.1893138 0.5853936 0.7884247 -0.1889467 0.1048597 0.1655589 -0.9806094 0.1047326 0.1657147 -0.9805967 0.2985721 0.4711012 -0.8300111 0.2981334 0.4715659 -0.829905 0.4465165 0.7041267 -0.5521129 0.4454894 0.7049734 -0.5518621 0.5260537 0.8290208 -0.1897155 0.5243695 0.8301786 -0.1893157 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 11 3 12 4 13 4 14 4 15 5 16 5 17 5 18 6 19 6 20 6 21 7 22 7 23 7 24 8 25 8 26 8 27 9 28 9 29 9 30 10 31 10 32 10 33 11 34 11 35 11 36 12 37 12 38 12 39 13 40 13 41 13 41 14 40 14 37 14 42 15 43 15 44 15 44 16 43 16 45 16 44 17 45 17 46 17 46 18 45 18 47 18 46 19 47 19 39 19 39 20 47 20 48 20 39 21 48 21 40 21 49 22 50 22 42 22 42 23 50 23 51 23 42 24 51 24 43 24 52 25 53 25 49 25 49 26 53 26 54 26 49 27 54 27 50 27 55 28 56 28 52 28 52 29 56 29 57 29 52 30 57 30 53 30 58 31 59 31 55 31 55 32 59 32 60 32 55 33 60 33 56 33 61 34 62 34 63 34 63 35 62 35 64 35 63 36 64 36 58 36 58 37 64 37 65 37 58 38 65 38 59 38 61 39 63 39 66 39 66 40 63 40 67 40 66 41 67 41 68 41 68 42 67 42 69 42 68 43 69 43 70 43 70 44 69 44 71 44 70 45 71 45 72 45 72 46 71 46 73 46 72 47 73 47 74 47 74 48 73 48 75 48 75 49 73 49 76 49 75 50 76 50 77 50 78 51 79 51 80 51 80 52 79 52 81 52 82 53 83 53 6 53 6 54 83 54 84 54 6 55 84 55 7 55 85 56 86 56 87 56 88 57 89 57 90 57 90 58 89 58 91 58 90 59 91 59 92 59 92 60 91 60 93 60 92 61 93 61 94 61 88 62 90 62 95 62 95 63 90 63 96 63 95 64 96 64 97 64 31 65 30 65 96 65 96 66 30 66 98 66 96 67 98 67 97 67 99 68 100 68 32 68 32 69 100 69 101 69 32 70 101 70 30 70 102 71 103 71 99 71 99 72 103 72 104 72 99 73 104 73 100 73 102 74 105 74 106 74 106 75 105 75 107 75 106 76 107 76 108 76 108 77 107 77 109 77 108 78 109 78 110 78 28 79 111 79 29 79 29 80 111 80 112 80 29 81 112 81 109 81 109 82 112 82 113 82 109 83 113 83 110 83 114 84 115 84 116 84 117 85 118 85 119 85 119 86 118 86 114 86 119 87 114 87 26 87 26 88 114 88 116 88 26 89 116 89 24 89 120 90 121 90 122 90 122 91 121 91 123 91 124 92 125 92 126 92 127 93 128 93 129 93 129 94 128 94 130 94 129 95 130 95 131 95 131 96 130 96 132 96 133 97 134 97 135 97 135 98 134 98 136 98 137 99 138 99 139 99 140 100 141 100 142 100 142 101 141 101 143 101 144 102 145 102 146 102 146 103 145 103 147 103 146 104 147 104 148 104 148 105 147 105 149 105 148 106 149 106 150 106 151 107 152 107 153 107 153 108 152 108 154 108 153 109 154 109 144 109 144 110 154 110 155 110 144 111 155 111 145 111 156 112 157 112 158 112 159 113 160 113 161 113 161 114 160 114 162 114 161 115 162 115 163 115 163 116 162 116 164 116 163 117 164 117 165 117 35 118 166 118 167 118 167 119 166 119 168 119 167 120 168 120 161 120 161 121 168 121 169 121 161 122 169 122 159 122 170 123 171 123 172 123 172 124 171 124 173 124 172 125 173 125 174 125 175 126 176 126 177 126 177 127 176 127 178 127 177 128 178 128 179 128 179 129 178 129 180 129 179 130 180 130 181 130 182 131 183 131 184 131 184 132 183 132 181 132 184 133 181 133 185 133 185 134 181 134 180 134 186 135 182 135 187 135 187 136 182 136 184 136 187 137 184 137 188 137 188 138 184 138 185 138 188 139 185 139 189 139 189 140 185 140 180 140 189 141 180 141 190 141 190 142 180 142 178 142 190 143 178 143 191 143 191 144 178 144 176 144 192 145 193 145 194 145 194 146 193 146 195 146 194 147 195 147 196 147 196 148 195 148 197 148 196 149 197 149 198 149 198 150 197 150 199 150 198 151 199 151 200 151 200 152 199 152 201 152 200 153 201 153 202 153 202 154 201 154 203 154 202 155 203 155 204 155 204 156 203 156 205 156 204 157 205 157 206 157 206 158 205 158 207 158 206 159 207 159 208 159 208 160 207 160 209 160 208 161 209 161 210 161 41 162 192 162 39 162 39 163 192 163 194 163 39 164 194 164 46 164 46 165 194 165 196 165 46 166 196 166 44 166 44 167 196 167 198 167 44 168 198 168 42 168 42 169 198 169 200 169 42 170 200 170 49 170 49 171 200 171 202 171 49 172 202 172 52 172 52 173 202 173 204 173 52 174 204 174 55 174 55 175 204 175 206 175 55 176 206 176 58 176 58 177 206 177 208 177 58 178 208 178 63 178 63 179 208 179 210 179 63 180 210 180 67 180 19 181 18 181 211 181 211 182 18 182 212 182 211 183 212 183 213 183 213 184 212 184 214 184 213 185 214 185 215 185 215 186 214 186 36 186 215 187 36 187 33 187 33 188 36 188 38 188 33 189 38 189 34 189 216 190 163 190 156 190 156 191 163 191 165 191 156 192 165 192 157 192 217 193 216 193 218 193 218 194 216 194 156 194 218 195 156 195 219 195 219 196 156 196 158 196 219 197 158 197 220 197 35 198 167 198 33 198 33 199 167 199 161 199 33 200 161 200 215 200 215 201 161 201 163 201 215 202 163 202 213 202 213 203 163 203 216 203 213 204 216 204 211 204 211 205 216 205 217 205 211 206 217 206 19 206 37 207 36 207 41 207 41 208 36 208 214 208 41 209 214 209 192 209 192 210 214 210 212 210 192 211 212 211 193 211 193 212 212 212 18 212 193 213 18 213 195 213 195 214 18 214 20 214 195 215 20 215 197 215 197 216 20 216 221 216 197 217 221 217 199 217 199 218 221 218 222 218 199 219 222 219 201 219 201 220 222 220 223 220 201 221 223 221 203 221 203 222 223 222 224 222 203 223 224 223 205 223 205 224 224 224 225 224 205 225 225 225 207 225 207 226 225 226 226 226 207 227 226 227 209 227 174 228 227 228 228 228 228 229 227 229 229 229 228 230 229 230 230 230 230 231 229 231 231 231 230 232 231 232 232 232 232 233 231 233 233 233 232 234 233 234 234 234 234 235 233 235 235 235 234 236 235 236 236 236 236 237 235 237 237 237 236 238 237 238 238 238 238 239 237 239 239 239 238 240 239 240 240 240 240 241 239 241 241 241 240 242 241 242 242 242 242 243 241 243 243 243 242 244 243 244 244 244 244 245 243 245 245 245 244 246 245 246 246 246 246 247 245 247 247 247 246 248 247 248 248 248 248 249 247 249 249 249 248 250 249 250 250 250 250 251 249 251 251 251 250 252 251 252 252 252 253 253 151 253 254 253 254 254 151 254 153 254 254 255 153 255 255 255 255 256 153 256 144 256 255 257 144 257 256 257 256 258 144 258 146 258 256 259 146 259 257 259 257 260 146 260 148 260 257 261 148 261 258 261 258 262 148 262 150 262 258 263 150 263 142 263 142 264 150 264 149 264 142 265 149 265 140 265 259 266 253 266 260 266 260 267 253 267 254 267 260 268 254 268 261 268 261 269 254 269 255 269 261 270 255 270 262 270 262 271 255 271 256 271 262 272 256 272 263 272 263 273 256 273 257 273 263 274 257 274 264 274 264 275 257 275 258 275 264 276 258 276 265 276 265 277 258 277 142 277 265 278 142 278 266 278 266 279 142 279 143 279 266 280 143 280 267 280 268 281 259 281 269 281 269 282 259 282 260 282 269 283 260 283 270 283 270 284 260 284 261 284 270 285 261 285 271 285 271 286 261 286 262 286 271 287 262 287 272 287 272 288 262 288 263 288 272 289 263 289 273 289 273 290 263 290 264 290 273 291 264 291 274 291 274 292 264 292 265 292 274 293 265 293 275 293 275 294 265 294 266 294 275 295 266 295 276 295 276 296 266 296 267 296 276 297 267 297 277 297 278 298 268 298 279 298 279 299 268 299 269 299 279 300 269 300 280 300 280 301 269 301 270 301 280 302 270 302 281 302 281 303 270 303 271 303 281 304 271 304 282 304 282 305 271 305 272 305 282 306 272 306 283 306 283 307 272 307 273 307 283 308 273 308 284 308 284 309 273 309 274 309 284 310 274 310 285 310 285 311 274 311 275 311 285 312 275 312 286 312 286 313 275 313 276 313 286 314 276 314 137 314 137 315 276 315 277 315 137 316 277 316 138 316 287 317 278 317 288 317 288 318 278 318 279 318 288 319 279 319 289 319 289 320 279 320 280 320 289 321 280 321 290 321 290 322 280 322 281 322 290 323 281 323 291 323 291 324 281 324 282 324 291 325 282 325 292 325 292 326 282 326 283 326 292 327 283 327 293 327 293 328 283 328 284 328 293 329 284 329 294 329 294 330 284 330 285 330 294 331 285 331 295 331 295 332 285 332 286 332 295 333 286 333 296 333 296 334 286 334 137 334 296 335 137 335 297 335 297 336 137 336 139 336 297 337 139 337 298 337 298 338 299 338 297 338 297 339 299 339 300 339 297 340 300 340 296 340 296 341 300 341 301 341 296 342 301 342 295 342 295 343 301 343 302 343 295 344 302 344 294 344 294 345 302 345 303 345 294 346 303 346 293 346 293 347 303 347 304 347 293 348 304 348 292 348 292 349 304 349 305 349 292 350 305 350 291 350 291 351 305 351 306 351 291 352 306 352 290 352 290 353 306 353 307 353 290 354 307 354 289 354 289 355 307 355 308 355 289 356 308 356 288 356 288 357 308 357 309 357 288 358 309 358 287 358 287 359 309 359 310 359 311 360 310 360 312 360 312 361 310 361 309 361 312 362 309 362 313 362 313 363 309 363 308 363 313 364 308 364 314 364 314 365 308 365 307 365 314 366 307 366 315 366 315 367 307 367 306 367 315 368 306 368 316 368 316 369 306 369 305 369 316 370 305 370 317 370 317 371 305 371 304 371 317 372 304 372 318 372 318 373 304 373 303 373 318 374 303 374 319 374 319 375 303 375 302 375 319 376 302 376 320 376 320 377 302 377 301 377 320 378 301 378 321 378 321 379 301 379 300 379 321 380 300 380 322 380 322 381 300 381 299 381 322 382 299 382 135 382 135 383 299 383 298 383 135 384 298 384 133 384 323 385 311 385 324 385 324 386 311 386 312 386 324 387 312 387 325 387 325 388 312 388 313 388 325 389 313 389 326 389 326 390 313 390 314 390 326 391 314 391 327 391 327 392 314 392 315 392 327 393 315 393 328 393 328 394 315 394 316 394 328 395 316 395 329 395 329 396 316 396 317 396 329 397 317 397 330 397 330 398 317 398 318 398 330 399 318 399 331 399 331 400 318 400 319 400 331 401 319 401 332 401 332 402 319 402 320 402 332 403 320 403 333 403 333 404 320 404 321 404 333 405 321 405 334 405 334 406 321 406 322 406 334 407 322 407 335 407 335 408 322 408 135 408 335 409 135 409 127 409 127 410 135 410 136 410 127 411 136 411 128 411 336 412 337 412 338 412 338 413 337 413 339 413 338 414 339 414 340 414 340 415 339 415 341 415 342 416 336 416 343 416 343 417 336 417 338 417 343 418 338 418 344 418 344 419 338 419 340 419 345 420 342 420 346 420 346 421 342 421 343 421 346 422 343 422 347 422 347 423 343 423 344 423 347 424 344 424 348 424 348 425 344 425 340 425 348 426 340 426 349 426 349 427 340 427 341 427 349 428 341 428 350 428 351 429 352 429 353 429 354 430 345 430 355 430 355 431 345 431 346 431 355 432 346 432 356 432 356 433 346 433 347 433 356 434 347 434 357 434 357 435 347 435 348 435 357 436 348 436 358 436 358 437 348 437 349 437 358 438 349 438 359 438 359 439 349 439 350 439 359 440 350 440 360 440 361 441 354 441 362 441 362 442 354 442 355 442 362 443 355 443 363 443 363 444 355 444 356 444 363 445 356 445 364 445 364 446 356 446 357 446 364 447 357 447 365 447 365 448 357 448 358 448 365 449 358 449 366 449 366 450 358 450 359 450 366 451 359 451 367 451 367 452 359 452 360 452 367 453 360 453 368 453 369 454 361 454 370 454 370 455 361 455 362 455 370 456 362 456 371 456 371 457 362 457 363 457 371 458 363 458 372 458 372 459 363 459 364 459 372 460 364 460 373 460 373 461 364 461 365 461 373 462 365 462 374 462 374 463 365 463 366 463 374 464 366 464 375 464 375 465 366 465 367 465 375 466 367 466 376 466 376 467 367 467 368 467 376 468 368 468 377 468 10 469 9 469 378 469 378 470 9 470 379 470 378 471 379 471 380 471 380 472 379 472 351 472 380 473 351 473 381 473 381 474 351 474 353 474 381 475 353 475 382 475 17 476 383 476 384 476 17 477 16 477 383 477 383 478 16 478 385 478 383 479 385 479 386 479 384 480 387 480 388 480 388 481 387 481 389 481 388 482 389 482 390 482 391 483 392 483 393 483 107 484 394 484 109 484 109 485 394 485 395 485 109 486 395 486 29 486 29 487 395 487 25 487 29 488 25 488 27 488 27 489 25 489 24 489 396 490 369 490 397 490 397 491 369 491 370 491 397 492 370 492 398 492 398 493 370 493 371 493 398 494 371 494 399 494 399 495 371 495 372 495 399 496 372 496 400 496 400 497 372 497 373 497 400 498 373 498 401 498 401 499 373 499 374 499 401 500 374 500 402 500 402 501 374 501 375 501 402 502 375 502 403 502 403 503 375 503 376 503 403 504 376 504 404 504 404 505 376 505 377 505 404 506 377 506 405 506 406 507 407 507 408 507 408 508 407 508 409 508 410 509 396 509 411 509 411 510 396 510 397 510 411 511 397 511 412 511 412 512 397 512 398 512 412 513 398 513 413 513 413 514 398 514 399 514 413 515 399 515 414 515 414 516 399 516 400 516 414 517 400 517 415 517 415 518 400 518 401 518 415 519 401 519 416 519 416 520 401 520 402 520 416 521 402 521 417 521 417 522 402 522 403 522 417 523 403 523 418 523 418 524 403 524 404 524 418 525 404 525 419 525 419 526 404 526 405 526 419 527 405 527 420 527 421 528 410 528 422 528 422 529 410 529 411 529 422 530 411 530 423 530 423 531 411 531 412 531 423 532 412 532 424 532 424 533 412 533 413 533 424 534 413 534 425 534 425 535 413 535 414 535 425 536 414 536 426 536 426 537 414 537 415 537 426 538 415 538 427 538 427 539 415 539 416 539 427 540 416 540 428 540 428 541 416 541 417 541 428 542 417 542 429 542 429 543 417 543 418 543 429 544 418 544 430 544 430 545 418 545 419 545 430 546 419 546 431 546 431 547 419 547 420 547 431 548 420 548 432 548 433 549 434 549 435 549 435 550 434 550 436 550 437 551 421 551 438 551 438 552 421 552 422 552 438 553 422 553 439 553 439 554 422 554 423 554 439 555 423 555 440 555 440 556 423 556 424 556 440 557 424 557 441 557 441 558 424 558 425 558 441 559 425 559 442 559 442 560 425 560 426 560 442 561 426 561 443 561 443 562 426 562 427 562 443 563 427 563 444 563 444 564 427 564 428 564 444 565 428 565 445 565 445 566 428 566 429 566 445 567 429 567 446 567 446 568 429 568 430 568 446 569 430 569 186 569 186 570 430 570 431 570 186 571 431 571 182 571 182 572 431 572 432 572 182 573 432 573 183 573 15 574 409 574 16 574 16 575 409 575 407 575 16 576 407 576 385 576 385 577 407 577 406 577 385 578 406 578 447 578 408 579 436 579 406 579 406 580 436 580 434 580 406 581 434 581 447 581 447 582 434 582 433 582 447 583 433 583 448 583 449 584 437 584 450 584 450 585 437 585 438 585 450 586 438 586 451 586 451 587 438 587 439 587 451 588 439 588 452 588 452 589 439 589 440 589 452 590 440 590 453 590 453 591 440 591 441 591 453 592 441 592 454 592 454 593 441 593 442 593 454 594 442 594 455 594 455 595 442 595 443 595 455 596 443 596 456 596 456 597 443 597 444 597 456 598 444 598 457 598 457 599 444 599 445 599 457 600 445 600 458 600 458 601 445 601 446 601 458 602 446 602 459 602 459 603 446 603 186 603 459 604 186 604 460 604 460 605 186 605 187 605 460 606 187 606 461 606 461 607 187 607 188 607 461 608 188 608 462 608 462 609 188 609 189 609 462 610 189 610 463 610 463 611 189 611 190 611 463 612 190 612 464 612 464 613 190 613 191 613 465 614 466 614 467 614 468 615 449 615 469 615 469 616 449 616 450 616 469 617 450 617 470 617 470 618 450 618 451 618 470 619 451 619 471 619 471 620 451 620 452 620 471 621 452 621 472 621 472 622 452 622 453 622 472 623 453 623 473 623 473 624 453 624 454 624 473 625 454 625 474 625 474 626 454 626 455 626 474 627 455 627 475 627 475 628 455 628 456 628 475 629 456 629 476 629 476 630 456 630 457 630 476 631 457 631 477 631 477 632 457 632 458 632 477 633 458 633 478 633 478 634 458 634 459 634 478 635 459 635 479 635 479 636 459 636 460 636 479 637 460 637 480 637 480 638 460 638 461 638 480 639 461 639 481 639 481 640 461 640 462 640 481 641 462 641 482 641 482 642 462 642 463 642 482 643 463 643 483 643 483 644 463 644 464 644 131 645 468 645 129 645 129 646 468 646 469 646 129 647 469 647 127 647 127 648 469 648 470 648 127 649 470 649 335 649 335 650 470 650 471 650 335 651 471 651 334 651 334 652 471 652 472 652 334 653 472 653 333 653 333 654 472 654 473 654 333 655 473 655 332 655 332 656 473 656 474 656 332 657 474 657 331 657 331 658 474 658 475 658 331 659 475 659 330 659 330 660 475 660 476 660 330 661 476 661 329 661 329 662 476 662 477 662 329 663 477 663 328 663 328 664 477 664 478 664 328 665 478 665 327 665 327 666 478 666 479 666 327 667 479 667 326 667 326 668 479 668 480 668 326 669 480 669 325 669 325 670 480 670 481 670 325 671 481 671 324 671 324 672 481 672 482 672 324 673 482 673 323 673 323 674 482 674 483 674 465 675 467 675 484 675 484 676 467 676 485 676 484 677 485 677 486 677 486 678 485 678 487 678 486 679 487 679 488 679 487 680 21 680 488 680 488 681 21 681 23 681 488 682 23 682 486 682 486 683 23 683 489 683 486 684 489 684 484 684 484 685 489 685 448 685 484 686 448 686 465 686 465 687 448 687 433 687 465 688 433 688 466 688 466 689 433 689 435 689 386 690 490 690 491 690 491 691 490 691 492 691 491 692 492 692 493 692 493 693 492 693 494 693 493 694 494 694 495 694 495 695 494 695 496 695 495 696 496 696 124 696 124 697 496 697 497 697 124 698 497 698 125 698 386 699 385 699 490 699 490 700 385 700 447 700 490 701 447 701 492 701 492 702 447 702 448 702 492 703 448 703 494 703 494 704 448 704 489 704 494 705 489 705 496 705 496 706 489 706 23 706 496 707 23 707 497 707 497 708 23 708 22 708 497 709 22 709 125 709 384 710 383 710 387 710 387 711 383 711 386 711 387 712 386 712 389 712 389 713 386 713 491 713 389 714 491 714 498 714 498 715 491 715 493 715 498 716 493 716 499 716 499 717 493 717 495 717 499 718 495 718 500 718 500 719 495 719 124 719 500 720 124 720 501 720 501 721 124 721 126 721 501 722 126 722 120 722 395 723 502 723 25 723 25 724 502 724 503 724 25 725 503 725 26 725 26 726 503 726 504 726 26 727 504 727 119 727 120 728 122 728 501 728 501 729 122 729 505 729 501 730 505 730 500 730 500 731 505 731 506 731 500 732 506 732 499 732 499 733 506 733 507 733 499 734 507 734 498 734 498 735 507 735 508 735 498 736 508 736 389 736 389 737 508 737 392 737 389 738 392 738 390 738 390 739 392 739 391 739 390 740 391 740 388 740 509 741 510 741 511 741 511 742 510 742 512 742 511 743 512 743 513 743 514 744 13 744 515 744 515 745 13 745 12 745 515 746 12 746 516 746 352 747 517 747 518 747 518 748 517 748 14 748 518 749 14 749 519 749 519 750 14 750 13 750 519 751 13 751 509 751 509 752 13 752 514 752 509 753 514 753 510 753 102 754 99 754 105 754 105 755 99 755 520 755 105 756 520 756 107 756 107 757 520 757 393 757 107 758 393 758 394 758 394 759 393 759 392 759 394 760 392 760 395 760 395 761 392 761 508 761 395 762 508 762 502 762 502 763 508 763 507 763 502 764 507 764 503 764 503 765 507 765 506 765 503 766 506 766 504 766 504 767 506 767 505 767 504 768 505 768 119 768 119 769 505 769 122 769 119 770 122 770 117 770 117 771 122 771 123 771 117 772 123 772 118 772 352 773 351 773 517 773 517 774 351 774 379 774 517 775 379 775 14 775 14 776 379 776 9 776 14 777 9 777 12 777 12 778 9 778 11 778 12 779 11 779 516 779 84 780 521 780 7 780 7 781 521 781 78 781 7 782 78 782 8 782 8 783 78 783 80 783 8 784 80 784 522 784 523 785 524 785 525 785 525 786 524 786 87 786 525 787 87 787 526 787 526 788 87 788 86 788 524 789 527 789 87 789 87 790 527 790 528 790 87 791 528 791 85 791 85 792 528 792 529 792 85 793 529 793 530 793 530 794 529 794 531 794 530 795 531 795 532 795 532 796 531 796 533 796 532 797 533 797 94 797 94 798 533 798 534 798 94 799 534 799 92 799 92 800 534 800 535 800 535 801 534 801 536 801 536 802 534 802 533 802 536 803 533 803 537 803 537 804 533 804 531 804 537 805 531 805 538 805 538 806 531 806 529 806 538 807 529 807 539 807 539 808 529 808 528 808 539 809 528 809 540 809 540 810 528 810 527 810 540 811 527 811 541 811 541 812 527 812 524 812 541 813 524 813 542 813 542 814 524 814 523 814 542 815 523 815 543 815 544 816 545 816 3 816 4 817 3 817 546 817 546 818 3 818 545 818 546 819 545 819 547 819 548 820 82 820 549 820 549 821 82 821 6 821 549 822 6 822 550 822 550 823 6 823 8 823 550 824 8 824 2 824 2 825 8 825 522 825 2 826 522 826 0 826 551 827 552 827 553 827 553 828 552 828 554 828 553 829 554 829 555 829 555 830 554 830 556 830 555 831 556 831 557 831 557 832 556 832 0 832 557 833 0 833 558 833 558 834 0 834 522 834 558 835 522 835 559 835 559 836 522 836 80 836 559 837 80 837 560 837 560 838 80 838 81 838 560 839 81 839 561 839 562 840 77 840 561 840 561 841 77 841 76 841 561 842 76 842 560 842 560 843 76 843 73 843 560 844 73 844 559 844 559 845 73 845 71 845 559 846 71 846 558 846 558 847 71 847 69 847 558 848 69 848 557 848 557 849 69 849 67 849 557 850 67 850 555 850 555 851 67 851 210 851 555 852 210 852 553 852 553 853 210 853 209 853 553 854 209 854 551 854 551 855 209 855 226 855 1 856 170 856 563 856 563 857 170 857 172 857 563 858 172 858 175 858 175 859 172 859 174 859 175 860 174 860 176 860 176 861 174 861 228 861 176 862 228 862 191 862 191 863 228 863 230 863 191 864 230 864 464 864 464 865 230 865 232 865 464 866 232 866 483 866 483 867 232 867 234 867 483 868 234 868 323 868 323 869 234 869 236 869 323 870 236 870 311 870 311 871 236 871 238 871 311 872 238 872 310 872 310 873 238 873 240 873 310 874 240 874 287 874 287 875 240 875 242 875 287 876 242 876 278 876 278 877 242 877 244 877 278 878 244 878 268 878 268 879 244 879 246 879 268 880 246 880 259 880 259 881 246 881 248 881 259 882 248 882 253 882 253 883 248 883 250 883 253 884 250 884 151 884 151 885 250 885 252 885 151 886 252 886 152 886 1 887 0 887 170 887 170 888 0 888 556 888 170 889 556 889 171 889 171 890 556 890 554 890 171 891 554 891 173 891 173 892 554 892 552 892 173 893 552 893 174 893 174 894 552 894 551 894 174 895 551 895 227 895 227 896 551 896 226 896 227 897 226 897 229 897 229 898 226 898 225 898 229 899 225 899 231 899 231 900 225 900 224 900 231 901 224 901 233 901 233 902 224 902 223 902 233 903 223 903 235 903 235 904 223 904 222 904 235 905 222 905 237 905 237 906 222 906 221 906 237 907 221 907 239 907 239 908 221 908 20 908 239 909 20 909 241 909 241 910 20 910 19 910 241 911 19 911 243 911 243 912 19 912 217 912 243 913 217 913 245 913 245 914 217 914 218 914 245 915 218 915 247 915 247 916 218 916 219 916 247 917 219 917 249 917 249 918 219 918 220 918 249 919 220 919 251 919 523 920 544 920 543 920 543 921 544 921 3 921 543 922 3 922 542 922 542 923 3 923 5 923 542 924 5 924 541 924 541 925 5 925 564 925 541 926 564 926 540 926 540 927 564 927 565 927 540 928 565 928 539 928 539 929 565 929 566 929 539 930 566 930 538 930 538 931 566 931 567 931 538 932 567 932 537 932 537 933 567 933 568 933 537 934 568 934 536 934 536 935 568 935 569 935 536 936 569 936 535 936 513 937 512 937 570 937 570 938 512 938 571 938 570 939 571 939 572 939 572 940 571 940 573 940 572 941 573 941 574 941 569 942 574 942 535 942 535 943 574 943 573 943 535 944 573 944 92 944 92 945 573 945 571 945 92 946 571 946 90 946 90 947 571 947 512 947 90 948 512 948 96 948 96 949 512 949 510 949 96 950 510 950 31 950 31 951 510 951 514 951 31 952 514 952 32 952 32 953 514 953 515 953 32 954 515 954 99 954 99 955 515 955 516 955 99 956 516 956 520 956 520 957 516 957 11 957 520 958 11 958 393 958 393 959 11 959 10 959 393 960 10 960 391 960 391 961 10 961 378 961 391 962 378 962 388 962 388 963 378 963 380 963 388 964 380 964 384 964 384 965 380 965 381 965 384 966 381 966 17 966 17 967 381 967 382 967 17 968 382 968 15 968 526 969 548 969 525 969 525 970 548 970 549 970 525 971 549 971 523 971 523 972 549 972 550 972 523 973 550 973 544 973 544 974 550 974 2 974 544 975 2 975 545 975 545 976 2 976 1 976 545 977 1 977 547 977 547 978 1 978 563 978 547 979 563 979 546 979 546 980 563 980 175 980 546 981 175 981 4 981 4 982 175 982 177 982 4 983 177 983 5 983 5 984 177 984 179 984 5 985 179 985 564 985 564 986 179 986 181 986 564 987 181 987 565 987 565 988 181 988 183 988 565 989 183 989 566 989 566 990 183 990 432 990 566 991 432 991 567 991 567 992 432 992 420 992 567 993 420 993 568 993 568 994 420 994 405 994 568 995 405 995 569 995 569 996 405 996 377 996 569 997 377 997 574 997 574 998 377 998 368 998 574 999 368 999 572 999 572 1000 368 1000 360 1000 572 1001 360 1001 570 1001 570 1002 360 1002 350 1002 570 1003 350 1003 513 1003 513 1004 350 1004 341 1004 513 1005 341 1005 511 1005 511 1006 341 1006 339 1006 511 1007 339 1007 509 1007 509 1008 339 1008 337 1008 509 1009 337 1009 519 1009 519 1010 337 1010 336 1010 519 1011 336 1011 518 1011 518 1012 336 1012 342 1012 518 1013 342 1013 352 1013 352 1014 342 1014 345 1014 352 1015 345 1015 353 1015 353 1016 345 1016 354 1016 353 1017 354 1017 382 1017 382 1018 354 1018 361 1018 382 1019 361 1019 15 1019 15 1020 361 1020 369 1020 15 1021 369 1021 409 1021 409 1022 369 1022 396 1022 409 1023 396 1023 408 1023 408 1024 396 1024 410 1024 408 1025 410 1025 436 1025 436 1026 410 1026 421 1026 436 1027 421 1027 435 1027 435 1028 421 1028 437 1028 435 1029 437 1029 466 1029 466 1030 437 1030 449 1030 466 1031 449 1031 467 1031 467 1032 449 1032 468 1032 467 1033 468 1033 485 1033 485 1034 468 1034 131 1034 485 1035 131 1035 487 1035 487 1036 131 1036 132 1036 487 1037 132 1037 21 1037 575 1038 576 1038 577 1038 575 1039 577 1039 578 1039 579 1040 580 1040 578 1040 581 1041 582 1041 580 1041 583 1042 584 1042 585 1042 584 1043 583 1043 586 1043 586 1044 583 1044 587 1044 586 1045 587 1045 588 1045 588 1046 587 1046 589 1046 588 1047 589 1047 590 1047 591 1048 592 1048 593 1048 593 1049 592 1049 594 1049 593 1050 594 1050 595 1050 595 1051 594 1051 596 1051 595 1052 596 1052 597 1052 597 1053 596 1053 598 1053 597 1054 598 1054 599 1054 599 1055 598 1055 600 1055 599 1056 600 1056 601 1056 601 1057 600 1057 602 1057 601 1058 602 1058 603 1058 603 1059 602 1059 604 1059 603 1060 604 1060 605 1060 605 1061 604 1061 606 1061 605 1062 606 1062 607 1062 607 1063 606 1063 608 1063 607 1064 608 1064 609 1064 609 1065 608 1065 610 1065 609 1066 610 1066 611 1066 611 1067 610 1067 612 1067 611 1068 612 1068 613 1068 613 1069 612 1069 614 1069 613 1070 614 1070 615 1070 615 1071 614 1071 616 1071 615 1072 616 1072 617 1072 617 1073 616 1073 618 1073 617 1074 618 1074 581 1074 581 1075 618 1075 619 1075 581 1076 619 1076 582 1076 620 1077 621 1077 591 1077 591 1078 621 1078 622 1078 591 1079 622 1079 592 1079 623 1080 624 1080 625 1080 625 1081 624 1081 626 1081 625 1082 626 1082 627 1082 627 1083 626 1083 628 1083 627 1084 628 1084 620 1084 620 1085 628 1085 629 1085 620 1086 629 1086 621 1086 578 1087 577 1087 579 1087 579 1088 577 1088 630 1088 579 1089 630 1089 631 1089 631 1090 630 1090 632 1090 631 1091 632 1091 633 1091 633 1092 632 1092 634 1092 633 1093 634 1093 635 1093 635 1094 634 1094 636 1094 635 1095 636 1095 637 1095 637 1096 636 1096 638 1096 637 1097 638 1097 639 1097 639 1098 638 1098 640 1098 639 1099 640 1099 641 1099 641 1100 640 1100 642 1100 641 1101 642 1101 643 1101 643 1102 642 1102 644 1102 643 1103 644 1103 645 1103 645 1104 644 1104 646 1104 645 1105 646 1105 647 1105 647 1106 646 1106 648 1106 647 1107 648 1107 649 1107 649 1108 648 1108 650 1108 649 1109 650 1109 651 1109 651 1110 650 1110 652 1110 651 1111 652 1111 653 1111 653 1112 652 1112 654 1112 653 1113 654 1113 655 1113 655 1114 654 1114 656 1114 655 1115 656 1115 657 1115 657 1116 656 1116 658 1116 657 1117 658 1117 659 1117 659 1118 658 1118 660 1118 659 1119 660 1119 661 1119 661 1120 660 1120 662 1120 661 1121 662 1121 663 1121 663 1122 662 1122 664 1122 663 1123 664 1123 665 1123 580 1124 579 1124 581 1124 581 1125 579 1125 631 1125 581 1126 631 1126 617 1126 617 1127 631 1127 633 1127 617 1128 633 1128 615 1128 615 1129 633 1129 635 1129 615 1130 635 1130 613 1130 613 1131 635 1131 637 1131 613 1132 637 1132 611 1132 611 1133 637 1133 639 1133 611 1134 639 1134 609 1134 609 1135 639 1135 641 1135 609 1136 641 1136 607 1136 607 1137 641 1137 643 1137 607 1138 643 1138 605 1138 605 1139 643 1139 645 1139 605 1140 645 1140 603 1140 603 1141 645 1141 647 1141 603 1142 647 1142 601 1142 601 1143 647 1143 649 1143 601 1144 649 1144 599 1144 599 1145 649 1145 651 1145 599 1146 651 1146 597 1146 597 1147 651 1147 653 1147 597 1148 653 1148 595 1148 595 1149 653 1149 655 1149 595 1150 655 1150 593 1150 593 1151 655 1151 657 1151 593 1152 657 1152 591 1152 591 1153 657 1153 659 1153 591 1154 659 1154 620 1154 620 1155 659 1155 661 1155 620 1156 661 1156 627 1156 627 1157 661 1157 663 1157 627 1158 663 1158 625 1158 625 1159 663 1159 665 1159 625 1160 665 1160 666 1160 666 1161 667 1161 668 1161 666 1162 668 1162 625 1162 625 1163 668 1163 669 1163 625 1164 669 1164 623 1164 664 1165 670 1165 665 1165 665 1166 670 1166 671 1166 665 1167 671 1167 666 1167 666 1168 671 1168 672 1168 666 1169 672 1169 667 1169 673 1170 674 1170 672 1170 672 1171 674 1171 675 1171 672 1172 675 1172 667 1172 676 1173 589 1173 677 1173 677 1174 589 1174 587 1174 677 1175 587 1175 678 1175 678 1176 587 1176 583 1176 670 1177 676 1177 671 1177 671 1178 676 1178 677 1178 671 1179 677 1179 672 1179 672 1180 677 1180 678 1180 672 1181 678 1181 673 1181 673 1182 678 1182 583 1182 673 1183 583 1183 679 1183 679 1184 583 1184 585 1184 680 1185 580 1185 582 1185 576 1186 575 1186 681 1186 681 1187 575 1187 578 1187 682 1188 683 1188 684 1188 684 1189 683 1189 685 1189 686 1190 687 1190 688 1190 619 1191 689 1191 690 1191 690 1192 689 1192 691 1192 690 1193 691 1193 692 1193 692 1194 691 1194 693 1194 692 1195 693 1195 694 1195 694 1196 693 1196 695 1196 694 1197 695 1197 696 1197 696 1198 695 1198 697 1198 696 1199 697 1199 698 1199 698 1200 697 1200 699 1200 698 1201 699 1201 700 1201 700 1202 699 1202 701 1202 700 1203 701 1203 702 1203 702 1204 701 1204 703 1204 702 1205 703 1205 704 1205 704 1206 703 1206 705 1206 704 1207 705 1207 706 1207 706 1208 705 1208 707 1208 706 1209 707 1209 708 1209 708 1210 707 1210 709 1210 708 1211 709 1211 710 1211 710 1212 709 1212 711 1212 710 1213 711 1213 712 1213 712 1214 711 1214 713 1214 712 1215 713 1215 714 1215 714 1216 713 1216 715 1216 714 1217 715 1217 716 1217 716 1218 715 1218 717 1218 716 1219 717 1219 718 1219 718 1220 717 1220 719 1220 718 1221 719 1221 720 1221 720 1222 719 1222 721 1222 722 1223 723 1223 721 1223 721 1224 723 1224 724 1224 721 1225 724 1225 720 1225 722 1226 725 1226 723 1226 723 1227 725 1227 726 1227 723 1228 726 1228 727 1228 728 1229 729 1229 727 1229 727 1230 729 1230 730 1230 727 1231 730 1231 723 1231 728 1232 731 1232 729 1232 729 1233 731 1233 732 1233 729 1234 732 1234 733 1234 733 1235 732 1235 734 1235 733 1236 734 1236 735 1236 735 1237 734 1237 736 1237 735 1238 736 1238 737 1238 737 1239 736 1239 686 1239 737 1240 686 1240 738 1240 738 1241 686 1241 688 1241 738 1242 688 1242 682 1242 682 1243 684 1243 738 1243 738 1244 684 1244 739 1244 738 1245 739 1245 737 1245 737 1246 739 1246 740 1246 737 1247 740 1247 735 1247 735 1248 740 1248 741 1248 735 1249 741 1249 733 1249 733 1250 741 1250 742 1250 733 1251 742 1251 729 1251 729 1252 742 1252 743 1252 729 1253 743 1253 730 1253 730 1254 743 1254 744 1254 730 1255 744 1255 723 1255 723 1256 744 1256 745 1256 723 1257 745 1257 724 1257 724 1258 745 1258 746 1258 724 1259 746 1259 720 1259 720 1260 746 1260 747 1260 720 1261 747 1261 718 1261 718 1262 747 1262 748 1262 718 1263 748 1263 716 1263 716 1264 748 1264 749 1264 716 1265 749 1265 714 1265 714 1266 749 1266 750 1266 714 1267 750 1267 712 1267 712 1268 750 1268 751 1268 712 1269 751 1269 710 1269 710 1270 751 1270 752 1270 710 1271 752 1271 708 1271 708 1272 752 1272 753 1272 708 1273 753 1273 706 1273 706 1274 753 1274 754 1274 706 1275 754 1275 704 1275 704 1276 754 1276 755 1276 704 1277 755 1277 702 1277 702 1278 755 1278 756 1278 702 1279 756 1279 700 1279 700 1280 756 1280 757 1280 700 1281 757 1281 698 1281 698 1282 757 1282 758 1282 698 1283 758 1283 696 1283 696 1284 758 1284 759 1284 696 1285 759 1285 694 1285 694 1286 759 1286 760 1286 694 1287 760 1287 692 1287 692 1288 760 1288 680 1288 692 1289 680 1289 690 1289 690 1290 680 1290 582 1290 690 1291 582 1291 619 1291 685 1292 761 1292 684 1292 684 1293 761 1293 762 1293 684 1294 762 1294 739 1294 739 1295 762 1295 763 1295 739 1296 763 1296 740 1296 740 1297 763 1297 764 1297 740 1298 764 1298 741 1298 741 1299 764 1299 765 1299 741 1300 765 1300 742 1300 742 1301 765 1301 766 1301 742 1302 766 1302 743 1302 743 1303 766 1303 767 1303 743 1304 767 1304 744 1304 744 1305 767 1305 768 1305 744 1306 768 1306 745 1306 745 1307 768 1307 769 1307 745 1308 769 1308 746 1308 746 1309 769 1309 770 1309 746 1310 770 1310 747 1310 747 1311 770 1311 771 1311 747 1312 771 1312 748 1312 748 1313 771 1313 772 1313 748 1314 772 1314 749 1314 749 1315 772 1315 773 1315 749 1316 773 1316 750 1316 750 1317 773 1317 774 1317 750 1318 774 1318 751 1318 751 1319 774 1319 775 1319 751 1320 775 1320 752 1320 752 1321 775 1321 776 1321 752 1322 776 1322 753 1322 753 1323 776 1323 777 1323 753 1324 777 1324 754 1324 754 1325 777 1325 778 1325 754 1326 778 1326 755 1326 755 1327 778 1327 779 1327 755 1328 779 1328 756 1328 756 1329 779 1329 780 1329 756 1330 780 1330 757 1330 757 1331 780 1331 781 1331 757 1332 781 1332 758 1332 758 1333 781 1333 782 1333 758 1334 782 1334 759 1334 759 1335 782 1335 783 1335 759 1336 783 1336 760 1336 760 1337 783 1337 681 1337 760 1338 681 1338 680 1338 680 1339 681 1339 578 1339 680 1340 578 1340 580 1340 664 1341 662 1341 765 1341 656 1341 654 1341 632 1341 781 1341 780 1341 662 1341 660 1342 630 1342 577 1342 781 1343 662 1343 782 1343 630 1344 660 1344 632 1344 632 1345 660 1345 658 1345 632 1346 658 1346 656 1346 577 1347 576 1347 660 1347 660 1348 576 1348 681 1348 660 1341 681 1341 662 1341 662 1349 681 1349 783 1349 662 1350 783 1350 782 1350 768 1341 767 1341 662 1341 662 1351 767 1351 766 1351 662 1352 766 1352 765 1352 765 1353 764 1353 664 1353 664 1341 764 1341 763 1341 664 1354 763 1354 670 1354 670 1355 763 1355 762 1355 670 1356 762 1356 676 1356 676 1357 762 1357 761 1357 676 1358 761 1358 589 1358 589 1359 761 1359 685 1359 589 1341 685 1341 590 1341 654 1341 652 1341 632 1341 632 1360 652 1360 650 1360 632 1361 650 1361 648 1361 774 1341 773 1341 662 1341 662 1362 773 1362 772 1362 662 1363 772 1363 771 1363 780 1341 779 1341 662 1341 662 1364 779 1364 778 1364 662 1365 778 1365 777 1365 771 1366 770 1366 662 1366 662 1367 770 1367 769 1367 662 1368 769 1368 768 1368 648 1369 646 1369 632 1369 632 1370 646 1370 644 1370 632 1341 644 1341 634 1341 634 1341 644 1341 642 1341 634 1341 642 1341 636 1341 636 1371 642 1371 640 1371 636 1372 640 1372 638 1372 777 1373 776 1373 662 1373 662 1374 776 1374 775 1374 662 1375 775 1375 774 1375 784 1376 596 1376 785 1376 785 1377 596 1377 594 1377 785 1378 594 1378 786 1378 786 1379 594 1379 592 1379 786 1380 592 1380 787 1380 787 1381 592 1381 622 1381 787 1382 622 1382 621 1382 602 1383 600 1383 784 1383 784 1384 600 1384 598 1384 784 1385 598 1385 596 1385 788 1386 608 1386 789 1386 789 1387 608 1387 606 1387 789 1388 606 1388 790 1388 790 1389 606 1389 604 1389 790 1390 604 1390 791 1390 791 1391 604 1391 602 1391 791 1392 602 1392 792 1392 792 1393 602 1393 784 1393 614 1394 612 1394 788 1394 788 1395 612 1395 610 1395 788 1396 610 1396 608 1396 788 1397 793 1397 614 1397 614 1398 793 1398 794 1398 614 1399 794 1399 616 1399 616 1400 794 1400 618 1400 795 1401 796 1401 794 1401 794 1402 796 1402 797 1402 794 1403 797 1403 798 1403 798 1404 799 1404 794 1404 794 1405 799 1405 166 1405 794 1406 166 1406 618 1406 618 1407 166 1407 800 1407 618 1408 800 1408 619 1408 626 1409 801 1409 628 1409 628 1410 801 1410 802 1410 628 1411 802 1411 629 1411 629 1412 802 1412 803 1412 629 1413 803 1413 621 1413 621 1414 803 1414 804 1414 621 1415 804 1415 787 1415 787 1416 804 1416 805 1416 787 1417 805 1417 786 1417 786 1418 805 1418 806 1418 786 1419 806 1419 785 1419 785 1420 806 1420 807 1420 785 1421 807 1421 784 1421 784 1422 807 1422 808 1422 784 1423 808 1423 792 1423 792 1424 808 1424 809 1424 792 1425 809 1425 791 1425 791 1426 809 1426 810 1426 791 1427 810 1427 790 1427 790 1428 810 1428 811 1428 790 1429 811 1429 789 1429 789 1430 811 1430 812 1430 789 1431 812 1431 788 1431 788 1432 812 1432 813 1432 788 1433 813 1433 793 1433 793 1434 813 1434 814 1434 793 1435 814 1435 794 1435 794 1436 814 1436 815 1436 794 1437 815 1437 795 1437 626 1438 624 1438 801 1438 801 1439 624 1439 623 1439 801 1440 623 1440 816 1440 816 1441 623 1441 669 1441 669 1442 817 1442 816 1442 816 1443 817 1443 818 1443 816 1444 818 1444 819 1444 819 1445 818 1445 820 1445 819 1446 820 1446 821 1446 821 1447 820 1447 822 1447 821 1448 822 1448 823 1448 824 1449 825 1449 823 1449 823 1450 822 1450 824 1450 824 1451 822 1451 679 1451 824 1452 679 1452 585 1452 669 1453 668 1453 817 1453 817 1454 668 1454 667 1454 817 1455 667 1455 818 1455 818 1456 667 1456 675 1456 818 1457 675 1457 820 1457 820 1458 675 1458 674 1458 820 1459 674 1459 822 1459 822 1460 674 1460 673 1460 822 1461 673 1461 679 1461 826 1462 827 1462 828 1462 829 1463 731 1463 728 1463 829 1464 728 1464 830 1464 830 1465 728 1465 727 1465 830 1466 727 1466 831 1466 727 1467 726 1467 831 1467 831 1468 726 1468 725 1468 831 1469 725 1469 832 1469 832 1470 725 1470 722 1470 832 1471 722 1471 833 1471 833 1472 722 1472 721 1472 833 1473 721 1473 834 1473 834 1474 721 1474 835 1474 834 1475 835 1475 836 1475 836 1476 835 1476 837 1476 836 1477 837 1477 838 1477 838 1478 837 1478 839 1478 838 1479 839 1479 840 1479 840 1480 839 1480 841 1480 841 1481 839 1481 842 1481 841 1482 842 1482 843 1482 843 1483 842 1483 844 1483 843 1484 844 1484 845 1484 845 1485 844 1485 846 1485 846 1486 844 1486 847 1486 846 1487 847 1487 848 1487 848 1488 847 1488 849 1488 848 1489 849 1489 850 1489 850 1490 849 1490 851 1490 850 1491 851 1491 852 1491 852 1492 851 1492 853 1492 853 1493 851 1493 854 1493 853 1494 854 1494 855 1494 855 1495 854 1495 856 1495 855 1496 856 1496 857 1496 858 1497 859 1497 857 1497 800 1498 166 1498 858 1498 858 1499 166 1499 860 1499 858 1500 860 1500 859 1500 857 1501 856 1501 858 1501 858 1502 856 1502 693 1502 858 1503 693 1503 800 1503 693 1504 691 1504 800 1504 800 1505 691 1505 689 1505 800 1506 689 1506 619 1506 851 1507 699 1507 854 1507 854 1508 699 1508 697 1508 854 1509 697 1509 856 1509 856 1510 697 1510 695 1510 856 1511 695 1511 693 1511 842 1512 709 1512 844 1512 844 1513 709 1513 707 1513 844 1514 707 1514 847 1514 847 1515 707 1515 705 1515 847 1516 705 1516 849 1516 849 1517 705 1517 703 1517 849 1518 703 1518 851 1518 851 1519 703 1519 701 1519 851 1520 701 1520 699 1520 721 1521 719 1521 835 1521 835 1522 719 1522 717 1522 835 1523 717 1523 837 1523 837 1524 717 1524 715 1524 837 1525 715 1525 839 1525 839 1526 715 1526 713 1526 839 1527 713 1527 842 1527 842 1528 713 1528 711 1528 842 1529 711 1529 709 1529 731 1530 829 1530 732 1530 732 1531 829 1531 861 1531 732 1532 861 1532 734 1532 734 1533 861 1533 862 1533 734 1534 862 1534 736 1534 862 1535 863 1535 736 1535 736 1536 863 1536 864 1536 736 1537 864 1537 686 1537 826 1538 828 1538 865 1538 829 1539 866 1539 861 1539 861 1540 866 1540 867 1540 861 1541 867 1541 862 1541 862 1542 867 1542 868 1542 862 1543 868 1543 863 1543 863 1544 868 1544 865 1544 863 1545 865 1545 864 1545 864 1546 865 1546 828 1546 864 1547 828 1547 686 1547 686 1548 828 1548 687 1548 869 1549 870 1549 871 1549 872 1550 873 1550 874 1550 875 1551 876 1551 877 1551 878 1552 879 1552 880 1552 881 1553 882 1553 883 1553 884 1554 885 1554 886 1554 887 1555 888 1555 889 1555 890 1556 891 1556 892 1556 893 1557 894 1557 895 1557 169 1558 168 1558 896 1558 166 1559 897 1559 168 1559 168 1560 897 1560 896 1560 897 1561 898 1561 896 1561 896 1562 898 1562 899 1562 896 1563 899 1563 900 1563 900 1564 901 1564 896 1564 896 1565 901 1565 902 1565 896 1566 902 1566 903 1566 164 1567 162 1567 904 1567 904 1568 162 1568 160 1568 904 1569 160 1569 159 1569 905 1570 251 1570 906 1570 906 1571 251 1571 220 1571 906 1572 220 1572 907 1572 907 1573 220 1573 158 1573 140 1574 149 1574 908 1574 908 1575 149 1575 147 1575 908 1576 147 1576 909 1576 909 1577 147 1577 145 1577 909 1578 145 1578 910 1578 910 1579 145 1579 155 1579 910 1580 155 1580 911 1580 911 1581 155 1581 154 1581 911 1582 154 1582 912 1582 912 1583 154 1583 152 1583 912 1584 152 1584 905 1584 905 1585 152 1585 252 1585 905 1586 252 1586 251 1586 267 1587 143 1587 913 1587 913 1588 143 1588 141 1588 914 1589 277 1589 267 1589 134 1590 915 1590 136 1590 136 1591 915 1591 916 1591 136 1592 916 1592 128 1592 128 1593 916 1593 917 1593 128 1594 917 1594 130 1594 130 1595 917 1595 918 1595 130 1596 918 1596 132 1596 132 1597 918 1597 919 1597 132 1598 919 1598 21 1598 920 1599 921 1599 125 1599 125 1600 921 1600 126 1600 114 1601 118 1601 922 1601 922 1602 118 1602 123 1602 922 1603 123 1603 923 1603 923 1604 123 1604 121 1604 923 1605 121 1605 921 1605 921 1606 121 1606 120 1606 921 1607 120 1607 126 1607 924 1608 925 1608 926 1608 926 1609 925 1609 927 1609 928 1610 929 1610 930 1610 930 1611 929 1611 931 1611 930 1612 931 1612 932 1612 933 1613 934 1613 935 1613 934 1614 933 1614 936 1614 936 1615 933 1615 937 1615 936 1616 937 1616 938 1616 939 1617 940 1617 941 1617 941 1618 940 1618 942 1618 941 1619 942 1619 943 1619 943 1620 942 1620 944 1620 943 1621 944 1621 945 1621 945 1622 944 1622 946 1622 945 1623 946 1623 947 1623 947 1624 946 1624 948 1624 947 1625 948 1625 949 1625 949 1626 948 1626 950 1626 949 1627 950 1627 951 1627 951 1628 950 1628 952 1628 951 1629 952 1629 953 1629 953 1630 954 1630 955 1630 955 1631 954 1631 956 1631 955 1632 956 1632 957 1632 957 1633 956 1633 958 1633 957 1634 958 1634 959 1634 959 1635 958 1635 960 1635 960 1636 958 1636 961 1636 960 1637 961 1637 962 1637 962 1638 961 1638 963 1638 963 1639 961 1639 964 1639 963 1640 964 1640 965 1640 965 1641 964 1641 966 1641 965 1642 966 1642 967 1642 968 1643 969 1643 970 1643 971 1644 969 1644 972 1644 972 1645 969 1645 968 1645 972 1646 968 1646 973 1646 974 1647 975 1647 976 1647 976 1648 975 1648 977 1648 976 1649 977 1649 978 1649 978 1650 977 1650 979 1650 978 1651 979 1651 980 1651 980 1652 979 1652 981 1652 980 1653 981 1653 982 1653 884 1654 886 1654 983 1654 881 1655 883 1655 984 1655 984 1656 883 1656 985 1656 984 1657 985 1657 986 1657 986 1658 985 1658 987 1658 986 1659 987 1659 988 1659 989 1660 990 1660 991 1660 991 1661 992 1661 989 1661 989 1662 992 1662 993 1662 989 1663 993 1663 987 1663 987 1664 993 1664 994 1664 987 1665 994 1665 988 1665 995 1666 996 1666 997 1666 997 1667 996 1667 998 1667 997 1668 998 1668 990 1668 990 1669 998 1669 999 1669 990 1670 999 1670 991 1670 903 1671 1000 1671 896 1671 896 1672 1000 1672 1001 1672 896 1673 1001 1673 1002 1673 1002 1674 1001 1674 1003 1674 1002 1675 1003 1675 1004 1675 1004 1676 1003 1676 995 1676 1004 1677 995 1677 1005 1677 1005 1678 995 1678 997 1678 1006 1679 1007 1679 1008 1679 1008 1680 1007 1680 1009 1680 1008 1681 1009 1681 1010 1681 1010 1682 1009 1682 1011 1682 1010 1683 1011 1683 886 1683 886 1684 1011 1684 1012 1684 886 1685 1012 1685 983 1685 1013 1686 1014 1686 1015 1686 1015 1687 1014 1687 1016 1687 1015 1688 1016 1688 1017 1688 1017 1689 1016 1689 1018 1689 1017 1690 1018 1690 1019 1690 1019 1691 1018 1691 1020 1691 1019 1692 1020 1692 1021 1692 1021 1693 1020 1693 1022 1693 1021 1694 1022 1694 1023 1694 1023 1695 1022 1695 1024 1695 1023 1696 1024 1696 1025 1696 1025 1697 1024 1697 1026 1697 878 1698 1027 1698 879 1698 879 1699 1027 1699 1028 1699 879 1700 1028 1700 1029 1700 1029 1701 1028 1701 1030 1701 1029 1702 1030 1702 1031 1702 1031 1703 1030 1703 1032 1703 1031 1704 1032 1704 1033 1704 1033 1705 1032 1705 1034 1705 1033 1706 1034 1706 1035 1706 1035 1707 1034 1707 1036 1707 1035 1708 1036 1708 1037 1708 1037 1709 1036 1709 1038 1709 1037 1710 1038 1710 1039 1710 159 1711 169 1711 904 1711 904 1712 169 1712 896 1712 904 1713 896 1713 1040 1713 1040 1714 896 1714 1002 1714 1040 1715 1002 1715 1041 1715 1041 1716 1002 1716 1004 1716 1041 1717 1004 1717 1042 1717 1042 1718 1004 1718 1005 1718 1042 1719 1005 1719 1043 1719 1043 1720 1005 1720 997 1720 1043 1721 997 1721 1044 1721 1044 1722 997 1722 990 1722 1044 1723 990 1723 1045 1723 1045 1724 990 1724 989 1724 1045 1725 989 1725 1046 1725 1046 1726 989 1726 987 1726 1046 1727 987 1727 1047 1727 1047 1728 987 1728 985 1728 1047 1729 985 1729 1048 1729 1048 1730 985 1730 883 1730 1048 1731 883 1731 1049 1731 1049 1732 883 1732 882 1732 1049 1733 882 1733 880 1733 880 1734 879 1734 1049 1734 1049 1735 879 1735 1029 1735 1049 1736 1029 1736 1048 1736 1048 1737 1029 1737 1031 1737 1048 1738 1031 1738 1047 1738 1047 1739 1031 1739 1033 1739 1047 1740 1033 1740 1046 1740 1046 1741 1033 1741 1035 1741 1046 1742 1035 1742 1045 1742 1045 1743 1035 1743 1037 1743 1045 1744 1037 1744 1044 1744 1044 1745 1037 1745 1039 1745 1044 1746 1039 1746 1043 1746 1043 1747 1039 1747 1050 1747 1043 1748 1050 1748 1042 1748 1042 1749 1050 1749 1051 1749 1042 1750 1051 1750 1041 1750 1041 1751 1051 1751 1052 1751 1041 1752 1052 1752 1040 1752 1040 1753 1052 1753 1053 1753 1040 1754 1053 1754 904 1754 904 1755 1053 1755 1054 1755 904 1756 1054 1756 164 1756 1038 1757 1055 1757 1039 1757 1039 1758 1055 1758 1056 1758 1039 1759 1056 1759 1050 1759 1050 1760 1056 1760 1057 1760 1050 1761 1057 1761 1051 1761 1051 1762 1057 1762 1058 1762 1051 1763 1058 1763 1052 1763 1052 1764 1058 1764 1059 1764 1052 1765 1059 1765 1053 1765 1053 1766 1059 1766 1060 1766 1053 1767 1060 1767 1054 1767 1054 1768 1060 1768 165 1768 1054 1769 165 1769 164 1769 1055 1770 1061 1770 1056 1770 1056 1771 1061 1771 1062 1771 1056 1772 1062 1772 1057 1772 1057 1773 1062 1773 1063 1773 1057 1774 1063 1774 1058 1774 1058 1775 1063 1775 1064 1775 1058 1776 1064 1776 1059 1776 1059 1777 1064 1777 1065 1777 1059 1778 1065 1778 1060 1778 1060 1779 1065 1779 157 1779 1060 1780 157 1780 165 1780 1066 1781 1067 1781 1068 1781 1069 1782 1013 1782 1070 1782 1070 1783 1013 1783 1015 1783 1070 1784 1015 1784 1071 1784 1071 1785 1015 1785 1017 1785 1071 1786 1017 1786 1072 1786 1072 1787 1017 1787 1019 1787 1072 1788 1019 1788 1073 1788 1073 1789 1019 1789 1021 1789 1073 1790 1021 1790 1074 1790 1074 1791 1021 1791 1023 1791 1074 1792 1023 1792 1075 1792 1075 1793 1023 1793 1025 1793 1075 1794 1025 1794 1076 1794 1076 1795 1025 1795 1026 1795 1076 1796 1026 1796 1077 1796 1078 1797 1069 1797 1079 1797 1079 1798 1069 1798 1070 1798 1079 1799 1070 1799 1080 1799 1080 1800 1070 1800 1071 1800 1080 1801 1071 1801 1081 1801 1081 1802 1071 1802 1072 1802 1081 1803 1072 1803 1082 1803 1082 1804 1072 1804 1073 1804 1082 1805 1073 1805 1083 1805 1083 1806 1073 1806 1074 1806 1083 1807 1074 1807 1084 1807 1084 1808 1074 1808 1075 1808 1084 1809 1075 1809 1085 1809 1085 1810 1075 1810 1076 1810 1085 1811 1076 1811 1086 1811 1086 1812 1076 1812 1077 1812 1086 1813 1077 1813 1087 1813 1088 1814 1078 1814 1089 1814 1089 1815 1078 1815 1079 1815 1089 1816 1079 1816 1090 1816 1090 1817 1079 1817 1080 1817 1090 1818 1080 1818 1091 1818 1091 1819 1080 1819 1081 1819 1091 1820 1081 1820 1092 1820 1092 1821 1081 1821 1082 1821 1092 1822 1082 1822 1093 1822 1093 1823 1082 1823 1083 1823 1093 1824 1083 1824 1094 1824 1094 1825 1083 1825 1084 1825 1094 1826 1084 1826 1095 1826 1095 1827 1084 1827 1085 1827 1095 1828 1085 1828 1096 1828 1096 1829 1085 1829 1086 1829 1096 1830 1086 1830 1097 1830 1097 1831 1086 1831 1087 1831 1097 1832 1087 1832 1098 1832 1099 1833 1088 1833 1100 1833 1100 1834 1088 1834 1089 1834 1100 1835 1089 1835 1101 1835 1101 1836 1089 1836 1090 1836 1101 1837 1090 1837 1102 1837 1102 1838 1090 1838 1091 1838 1102 1839 1091 1839 1103 1839 1103 1840 1091 1840 1092 1840 1103 1841 1092 1841 1104 1841 1104 1842 1092 1842 1093 1842 1104 1843 1093 1843 1105 1843 1105 1844 1093 1844 1094 1844 1105 1845 1094 1845 1106 1845 1106 1846 1094 1846 1095 1846 1106 1847 1095 1847 1107 1847 1107 1848 1095 1848 1096 1848 1107 1849 1096 1849 1108 1849 1108 1850 1096 1850 1097 1850 1108 1851 1097 1851 1109 1851 1109 1852 1097 1852 1098 1852 1109 1853 1098 1853 1110 1853 1111 1854 1099 1854 1112 1854 1112 1855 1099 1855 1100 1855 1112 1856 1100 1856 1113 1856 1113 1857 1100 1857 1101 1857 1113 1858 1101 1858 1114 1858 1114 1859 1101 1859 1102 1859 1114 1860 1102 1860 1115 1860 1115 1861 1102 1861 1103 1861 1115 1862 1103 1862 1116 1862 1116 1863 1103 1863 1104 1863 1116 1864 1104 1864 1117 1864 1117 1865 1104 1865 1105 1865 1117 1866 1105 1866 1118 1866 1118 1867 1105 1867 1106 1867 1118 1868 1106 1868 1119 1868 1119 1869 1106 1869 1107 1869 1119 1870 1107 1870 1120 1870 1120 1871 1107 1871 1108 1871 1120 1872 1108 1872 1121 1872 1121 1873 1108 1873 1109 1873 1121 1874 1109 1874 1122 1874 1122 1875 1109 1875 1110 1875 1122 1876 1110 1876 1123 1876 1124 1877 1111 1877 1125 1877 1125 1878 1111 1878 1112 1878 1125 1879 1112 1879 1126 1879 1126 1880 1112 1880 1113 1880 1126 1881 1113 1881 1127 1881 1127 1882 1113 1882 1114 1882 1127 1883 1114 1883 1128 1883 1128 1884 1114 1884 1115 1884 1128 1885 1115 1885 1129 1885 1129 1886 1115 1886 1116 1886 1129 1887 1116 1887 1130 1887 1130 1888 1116 1888 1117 1888 1130 1889 1117 1889 1131 1889 1131 1890 1117 1890 1118 1890 1131 1891 1118 1891 1132 1891 1132 1892 1118 1892 1119 1892 1132 1893 1119 1893 1133 1893 1133 1894 1119 1894 1120 1894 1133 1895 1120 1895 1134 1895 1134 1896 1120 1896 1121 1896 1134 1897 1121 1897 1135 1897 1135 1898 1121 1898 1122 1898 1135 1899 1122 1899 1136 1899 1136 1900 1122 1900 1123 1900 1136 1901 1123 1901 1137 1901 1066 1902 1124 1902 1138 1902 1138 1903 1124 1903 1125 1903 1138 1904 1125 1904 1139 1904 1139 1905 1125 1905 1126 1905 1139 1906 1126 1906 1140 1906 1140 1907 1126 1907 1127 1907 1140 1908 1127 1908 1141 1908 1141 1909 1127 1909 1128 1909 1141 1910 1128 1910 1142 1910 1142 1911 1128 1911 1129 1911 1142 1912 1129 1912 1143 1912 1143 1913 1129 1913 1130 1913 1143 1914 1130 1914 1144 1914 1144 1915 1130 1915 1131 1915 1144 1916 1131 1916 1145 1916 1145 1917 1131 1917 1132 1917 1145 1918 1132 1918 1146 1918 1146 1919 1132 1919 1133 1919 1146 1920 1133 1920 1147 1920 1147 1921 1133 1921 1134 1921 1147 1922 1134 1922 1148 1922 1148 1923 1134 1923 1135 1923 1148 1924 1135 1924 1149 1924 1149 1925 1135 1925 1136 1925 1149 1926 1136 1926 1150 1926 1150 1927 1136 1927 1137 1927 1150 1928 1137 1928 1151 1928 1152 1929 1153 1929 1154 1929 1154 1930 1153 1930 1155 1930 1154 1931 1155 1931 1156 1931 1156 1932 1155 1932 1157 1932 1156 1933 1157 1933 1158 1933 1158 1934 1157 1934 1159 1934 1158 1935 1159 1935 1160 1935 1160 1936 1159 1936 1161 1936 1160 1937 1161 1937 1162 1937 1162 1938 1161 1938 1163 1938 1162 1939 1163 1939 1164 1939 1164 1940 1163 1940 1165 1940 1164 1941 1165 1941 1166 1941 1166 1942 1165 1942 1167 1942 1166 1943 1167 1943 1168 1943 1168 1944 1167 1944 1169 1944 1168 1945 1169 1945 1170 1945 1170 1946 1169 1946 1171 1946 1170 1947 1171 1947 1172 1947 1172 1948 1171 1948 1173 1948 1172 1949 1173 1949 1174 1949 1174 1950 1173 1950 1175 1950 1174 1951 1175 1951 1176 1951 1176 1952 1175 1952 1177 1952 1176 1953 1177 1953 1178 1953 1178 1954 1177 1954 1179 1954 1178 1955 1179 1955 1180 1955 1180 1956 1179 1956 1181 1956 1180 1957 1181 1957 1182 1957 1182 1958 1181 1958 1183 1958 1182 1959 1183 1959 1184 1959 1066 1960 1068 1960 1124 1960 1124 1961 1068 1961 1185 1961 1124 1962 1185 1962 1111 1962 1111 1963 1185 1963 1186 1963 1111 1964 1186 1964 1099 1964 1099 1965 1186 1965 1187 1965 1099 1966 1187 1966 1088 1966 1088 1967 1187 1967 1188 1967 1088 1968 1188 1968 1078 1968 1078 1969 1188 1969 1189 1969 1078 1970 1189 1970 1069 1970 1069 1971 1189 1971 1190 1971 1069 1972 1190 1972 1013 1972 1013 1973 1190 1973 1191 1973 1013 1974 1191 1974 1014 1974 1014 1975 1191 1975 1152 1975 1014 1976 1152 1976 1016 1976 1016 1977 1152 1977 1154 1977 1016 1978 1154 1978 1018 1978 1018 1979 1154 1979 1156 1979 1018 1980 1156 1980 1020 1980 1020 1981 1156 1981 1158 1981 1020 1982 1158 1982 1022 1982 1022 1983 1158 1983 1160 1983 1022 1984 1160 1984 1024 1984 1024 1985 1160 1985 1162 1985 1024 1986 1162 1986 1026 1986 1026 1987 1162 1987 1164 1987 1026 1988 1164 1988 1077 1988 1077 1989 1164 1989 1166 1989 1077 1990 1166 1990 1087 1990 1087 1991 1166 1991 1168 1991 1087 1992 1168 1992 1098 1992 1098 1993 1168 1993 1170 1993 1098 1994 1170 1994 1110 1994 1110 1995 1170 1995 1172 1995 1110 1996 1172 1996 1123 1996 1123 1997 1172 1997 1174 1997 1123 1998 1174 1998 1137 1998 1137 1999 1174 1999 1176 1999 1137 2000 1176 2000 1151 2000 1151 2001 1176 2001 1178 2001 1151 2002 1178 2002 1192 2002 1192 2003 1178 2003 1180 2003 1192 2004 1180 2004 1193 2004 1193 2005 1180 2005 1182 2005 1193 2006 1182 2006 1194 2006 1194 2007 1182 2007 1184 2007 1194 2008 1184 2008 1195 2008 1196 2009 1067 2009 1197 2009 1197 2010 1067 2010 1066 2010 1197 2011 1066 2011 1198 2011 1198 2012 1066 2012 1138 2012 1198 2013 1138 2013 1199 2013 1199 2014 1138 2014 1139 2014 1199 2015 1139 2015 1200 2015 1200 2016 1139 2016 1140 2016 1200 2017 1140 2017 1201 2017 1201 2018 1140 2018 1141 2018 1201 2019 1141 2019 1202 2019 1202 2020 1141 2020 1142 2020 1202 2021 1142 2021 1203 2021 1203 2022 1142 2022 1143 2022 1203 2023 1143 2023 1204 2023 1204 2024 1143 2024 1144 2024 1204 2025 1144 2025 1205 2025 1205 2026 1144 2026 1145 2026 1205 2027 1145 2027 1206 2027 1206 2028 1145 2028 1146 2028 1206 2029 1146 2029 1207 2029 1207 2030 1146 2030 1147 2030 1207 2031 1147 2031 1208 2031 1208 2032 1147 2032 1148 2032 1208 2033 1148 2033 1209 2033 1209 2034 1148 2034 1149 2034 1209 2035 1149 2035 1210 2035 1210 2036 1149 2036 1150 2036 1210 2037 1150 2037 1211 2037 1211 2038 1150 2038 1151 2038 1211 2039 1151 2039 1212 2039 1212 2040 1151 2040 1192 2040 1212 2041 1192 2041 1213 2041 1213 2042 1192 2042 1193 2042 1213 2043 1193 2043 1214 2043 1214 2044 1193 2044 1194 2044 1214 2045 1194 2045 1215 2045 1215 2046 1194 2046 1195 2046 1215 2047 1195 2047 1216 2047 907 2048 1217 2048 906 2048 906 2049 1217 2049 1218 2049 906 2050 1218 2050 905 2050 905 2051 1218 2051 1219 2051 905 2052 1219 2052 912 2052 912 2053 1219 2053 1220 2053 912 2054 1220 2054 911 2054 911 2055 1220 2055 1221 2055 911 2056 1221 2056 910 2056 910 2057 1221 2057 1222 2057 910 2058 1222 2058 909 2058 909 2059 1222 2059 1223 2059 909 2060 1223 2060 908 2060 908 2061 1223 2061 1224 2061 908 2062 1224 2062 1225 2062 1225 2063 1224 2063 1226 2063 1225 2064 1226 2064 1227 2064 1227 2065 1226 2065 1228 2065 1227 2066 1228 2066 1229 2066 1229 2067 1228 2067 1230 2067 1229 2068 1230 2068 1231 2068 1231 2069 1230 2069 1232 2069 1231 2070 1232 2070 1233 2070 1233 2071 1232 2071 1234 2071 1233 2072 1234 2072 1235 2072 1235 2073 1234 2073 1236 2073 1235 2074 1236 2074 1237 2074 1237 2075 1236 2075 1238 2075 1237 2076 1238 2076 1239 2076 1239 2077 1238 2077 1240 2077 1239 2078 1240 2078 1241 2078 1241 2079 1240 2079 1242 2079 1241 2080 1242 2080 1243 2080 1243 2081 1242 2081 1244 2081 1243 2082 1244 2082 1245 2082 1245 2083 1244 2083 1246 2083 1245 2084 1246 2084 1247 2084 1247 2085 1246 2085 1248 2085 1247 2086 1248 2086 1249 2086 1217 2087 1196 2087 1218 2087 1218 2088 1196 2088 1197 2088 1218 2089 1197 2089 1219 2089 1219 2090 1197 2090 1198 2090 1219 2091 1198 2091 1220 2091 1220 2092 1198 2092 1199 2092 1220 2093 1199 2093 1221 2093 1221 2094 1199 2094 1200 2094 1221 2095 1200 2095 1222 2095 1222 2096 1200 2096 1201 2096 1222 2097 1201 2097 1223 2097 1223 2098 1201 2098 1202 2098 1223 2099 1202 2099 1224 2099 1224 2100 1202 2100 1203 2100 1224 2101 1203 2101 1226 2101 1226 2102 1203 2102 1204 2102 1226 2103 1204 2103 1228 2103 1228 2104 1204 2104 1205 2104 1228 2105 1205 2105 1230 2105 1230 2106 1205 2106 1206 2106 1230 2107 1206 2107 1232 2107 1232 2108 1206 2108 1207 2108 1232 2109 1207 2109 1234 2109 1234 2110 1207 2110 1208 2110 1234 2111 1208 2111 1236 2111 1236 2112 1208 2112 1209 2112 1236 2113 1209 2113 1238 2113 1238 2114 1209 2114 1210 2114 1238 2115 1210 2115 1240 2115 1240 2116 1210 2116 1211 2116 1240 2117 1211 2117 1242 2117 1242 2118 1211 2118 1212 2118 1242 2119 1212 2119 1244 2119 1244 2120 1212 2120 1213 2120 1244 2121 1213 2121 1246 2121 1246 2122 1213 2122 1214 2122 1246 2123 1214 2123 1248 2123 1248 2124 1214 2124 1215 2124 1248 2125 1215 2125 1249 2125 1249 2126 1215 2126 1216 2126 1249 2127 1216 2127 1250 2127 1251 2128 1252 2128 1253 2128 1253 2129 1252 2129 1254 2129 1253 2130 1254 2130 1255 2130 1256 2131 928 2131 1257 2131 1257 2132 928 2132 930 2132 1257 2133 930 2133 926 2133 926 2134 930 2134 932 2134 926 2135 932 2135 924 2135 141 2136 1258 2136 913 2136 913 2137 1258 2137 1259 2137 913 2138 1259 2138 1260 2138 1260 2139 1259 2139 1261 2139 1260 2140 1261 2140 1262 2140 1262 2141 1261 2141 1263 2141 1262 2142 1263 2142 1264 2142 1264 2143 1263 2143 1265 2143 1264 2144 1265 2144 1266 2144 1266 2145 1265 2145 1267 2145 1266 2146 1267 2146 1268 2146 1268 2147 1267 2147 1269 2147 1268 2148 1269 2148 1270 2148 1270 2149 1269 2149 1271 2149 1270 2150 1271 2150 1272 2150 1272 2151 1271 2151 1273 2151 1272 2152 1273 2152 1274 2152 1274 2153 1273 2153 1275 2153 1274 2154 1275 2154 1276 2154 1276 2155 1275 2155 1277 2155 1276 2156 1277 2156 1278 2156 1278 2157 1277 2157 1279 2157 1278 2158 1279 2158 1280 2158 876 2159 875 2159 1281 2159 1281 2160 875 2160 1282 2160 1281 2161 1282 2161 1283 2161 1283 2162 1282 2162 1284 2162 1283 2163 1284 2163 1285 2163 1285 2164 1284 2164 1286 2164 1285 2165 1286 2165 1287 2165 1287 2166 1286 2166 1288 2166 1287 2167 1288 2167 1289 2167 1289 2168 1288 2168 1290 2168 1289 2169 1290 2169 1291 2169 1291 2170 1290 2170 1292 2170 1291 2171 1292 2171 1293 2171 1293 2172 1292 2172 1294 2172 1293 2173 1294 2173 1295 2173 1295 2174 1294 2174 1296 2174 1295 2175 1296 2175 914 2175 914 2176 1296 2176 138 2176 914 2177 138 2177 277 2177 267 2178 913 2178 914 2178 914 2179 913 2179 1260 2179 914 2180 1260 2180 1295 2180 1295 2181 1260 2181 1262 2181 1295 2182 1262 2182 1293 2182 1293 2183 1262 2183 1264 2183 1293 2184 1264 2184 1291 2184 1291 2185 1264 2185 1266 2185 1291 2186 1266 2186 1289 2186 1289 2187 1266 2187 1268 2187 1289 2188 1268 2188 1287 2188 1287 2189 1268 2189 1270 2189 1287 2190 1270 2190 1285 2190 1285 2191 1270 2191 1272 2191 1285 2192 1272 2192 1283 2192 1283 2193 1272 2193 1274 2193 1283 2194 1274 2194 1281 2194 1281 2195 1274 2195 1276 2195 1281 2196 1276 2196 876 2196 876 2197 1276 2197 1278 2197 876 2198 1278 2198 877 2198 877 2199 1278 2199 1280 2199 877 2200 1280 2200 1297 2200 1297 2201 1280 2201 1298 2201 1297 2202 1298 2202 1299 2202 1299 2203 1298 2203 1300 2203 1299 2204 1300 2204 871 2204 873 2205 872 2205 1301 2205 1301 2206 872 2206 1302 2206 1301 2207 1302 2207 1303 2207 1303 2208 1302 2208 1304 2208 1303 2209 1304 2209 1305 2209 1305 2210 1304 2210 1306 2210 1305 2211 1306 2211 1307 2211 1307 2212 1306 2212 1308 2212 1307 2213 1308 2213 1309 2213 1309 2214 1308 2214 1310 2214 1309 2215 1310 2215 1311 2215 1311 2216 1310 2216 1312 2216 1311 2217 1312 2217 1313 2217 1313 2218 1312 2218 298 2218 1313 2219 298 2219 139 2219 920 2220 125 2220 1314 2220 1314 2221 125 2221 22 2221 1314 2222 22 2222 1315 2222 1315 2223 22 2223 21 2223 1315 2224 21 2224 1316 2224 1316 2225 21 2225 919 2225 1316 2226 919 2226 1317 2226 1317 2227 919 2227 918 2227 1317 2228 918 2228 1318 2228 1318 2229 918 2229 917 2229 1318 2230 917 2230 1319 2230 1319 2231 917 2231 916 2231 1319 2232 916 2232 1320 2232 1320 2233 916 2233 915 2233 1320 2234 915 2234 1321 2234 1321 2235 915 2235 134 2235 1321 2236 134 2236 133 2236 871 2237 870 2237 1299 2237 1299 2238 870 2238 1322 2238 1299 2239 1322 2239 1297 2239 1297 2240 1322 2240 1323 2240 1297 2241 1323 2241 877 2241 877 2242 1323 2242 874 2242 877 2243 874 2243 875 2243 875 2244 874 2244 873 2244 875 2245 873 2245 1282 2245 1282 2246 873 2246 1301 2246 1282 2247 1301 2247 1284 2247 1284 2248 1301 2248 1303 2248 1284 2249 1303 2249 1286 2249 1286 2250 1303 2250 1305 2250 1286 2251 1305 2251 1288 2251 1288 2252 1305 2252 1307 2252 1288 2253 1307 2253 1290 2253 1290 2254 1307 2254 1309 2254 1290 2255 1309 2255 1292 2255 1292 2256 1309 2256 1311 2256 1292 2257 1311 2257 1294 2257 1294 2258 1311 2258 1313 2258 1294 2259 1313 2259 1296 2259 1296 2260 1313 2260 139 2260 1296 2261 139 2261 138 2261 1183 2262 1324 2262 1184 2262 1184 2263 1324 2263 1325 2263 1184 2264 1325 2264 1195 2264 1195 2265 1325 2265 1326 2265 1195 2266 1326 2266 1216 2266 1216 2267 1326 2267 1327 2267 1216 2268 1327 2268 1250 2268 1250 2269 1327 2269 1328 2269 1250 2270 1328 2270 1329 2270 1329 2271 1328 2271 1330 2271 1329 2272 1330 2272 1331 2272 1331 2273 1330 2273 1332 2273 1331 2274 1332 2274 1333 2274 1333 2275 1332 2275 1334 2275 1333 2276 869 2276 1331 2276 1331 2277 869 2277 871 2277 1331 2278 871 2278 1329 2278 1329 2279 871 2279 1300 2279 1329 2280 1300 2280 1250 2280 1250 2281 1300 2281 1298 2281 1250 2282 1298 2282 1249 2282 1249 2283 1298 2283 1280 2283 1249 2284 1280 2284 1247 2284 1247 2285 1280 2285 1279 2285 1247 2286 1279 2286 1245 2286 1245 2287 1279 2287 1277 2287 1245 2288 1277 2288 1243 2288 1243 2289 1277 2289 1275 2289 1243 2290 1275 2290 1241 2290 1241 2291 1275 2291 1273 2291 1241 2292 1273 2292 1239 2292 1239 2293 1273 2293 1271 2293 1239 2294 1271 2294 1237 2294 1237 2295 1271 2295 1269 2295 1237 2296 1269 2296 1235 2296 1235 2297 1269 2297 1267 2297 1235 2298 1267 2298 1233 2298 1233 2299 1267 2299 1265 2299 1233 2300 1265 2300 1231 2300 1231 2301 1265 2301 1263 2301 1231 2302 1263 2302 1229 2302 1229 2303 1263 2303 1261 2303 1229 2304 1261 2304 1227 2304 1227 2305 1261 2305 1259 2305 1227 2306 1259 2306 1225 2306 1225 2307 1259 2307 1258 2307 1225 2308 1258 2308 908 2308 908 2309 1258 2309 141 2309 908 2310 141 2310 140 2310 1334 2311 114 2311 1333 2311 1333 2312 114 2312 922 2312 1333 2313 922 2313 869 2313 869 2314 922 2314 923 2314 869 2315 923 2315 870 2315 870 2316 923 2316 921 2316 870 2317 921 2317 1322 2317 1322 2318 921 2318 920 2318 1322 2319 920 2319 1323 2319 1323 2320 920 2320 1314 2320 1323 2321 1314 2321 874 2321 874 2322 1314 2322 1315 2322 874 2323 1315 2323 872 2323 872 2324 1315 2324 1316 2324 872 2325 1316 2325 1302 2325 1302 2326 1316 2326 1317 2326 1302 2327 1317 2327 1304 2327 1304 2328 1317 2328 1318 2328 1304 2329 1318 2329 1306 2329 1306 2330 1318 2330 1319 2330 1306 2331 1319 2331 1308 2331 1308 2332 1319 2332 1320 2332 1308 2333 1320 2333 1310 2333 1310 2334 1320 2334 1321 2334 1310 2335 1321 2335 1312 2335 1312 2336 1321 2336 133 2336 1312 2337 133 2337 298 2337 1335 2338 1336 2338 1337 2338 1337 2339 1336 2339 1338 2339 1337 2340 1338 2340 1339 2340 1339 2341 1338 2341 1251 2341 1339 2342 1251 2342 1340 2342 1340 2343 1251 2343 1253 2343 1340 2344 1253 2344 1341 2344 1341 2345 1253 2345 1255 2345 1341 2346 1255 2346 1342 2346 1342 2347 1255 2347 1343 2347 1342 2348 1343 2348 1344 2348 894 2349 938 2349 895 2349 895 2350 938 2350 937 2350 895 2351 937 2351 1345 2351 1345 2352 937 2352 933 2352 1345 2353 933 2353 1256 2353 1256 2354 933 2354 935 2354 1256 2355 935 2355 928 2355 928 2356 935 2356 1346 2356 928 2357 1346 2357 929 2357 888 2358 890 2358 889 2358 889 2359 890 2359 892 2359 889 2360 892 2360 1347 2360 1347 2361 892 2361 1348 2361 1347 2362 1348 2362 1349 2362 1349 2363 1348 2363 1350 2363 1349 2364 1350 2364 1351 2364 1351 2365 1350 2365 1352 2365 891 2366 893 2366 892 2366 892 2367 893 2367 895 2367 892 2368 895 2368 1348 2368 1348 2369 895 2369 1345 2369 1348 2370 1345 2370 1350 2370 1350 2371 1345 2371 1256 2371 1350 2372 1256 2372 1352 2372 1352 2373 1256 2373 1257 2373 1352 2374 1257 2374 1353 2374 1353 2375 1257 2375 926 2375 939 2376 887 2376 940 2376 940 2377 887 2377 889 2377 940 2378 889 2378 1344 2378 1344 2379 889 2379 1347 2379 1344 2380 1347 2380 1342 2380 1342 2381 1347 2381 1349 2381 1342 2382 1349 2382 1341 2382 1341 2383 1349 2383 1351 2383 1341 2384 1351 2384 1340 2384 1340 2385 1351 2385 1352 2385 1340 2386 1352 2386 1339 2386 1339 2387 1352 2387 1353 2387 1339 2388 1353 2388 1337 2388 1337 2389 1353 2389 926 2389 1337 2390 926 2390 1335 2390 1335 2391 926 2391 927 2391 1335 2392 927 2392 1354 2392 1355 2393 1356 2393 1357 2393 1357 2394 1356 2394 1358 2394 1357 2395 1358 2395 1359 2395 1359 2396 1358 2396 1360 2396 1361 2397 973 2397 1362 2397 1362 2398 973 2398 968 2398 1362 2399 968 2399 966 2399 966 2400 968 2400 970 2400 966 2401 970 2401 967 2401 1363 2402 1356 2402 1364 2402 1364 2403 1356 2403 1355 2403 1364 2404 1355 2404 1365 2404 1366 2405 1360 2405 1367 2405 1367 2406 1360 2406 1358 2406 1367 2407 1358 2407 1368 2407 1368 2408 1358 2408 1356 2408 1368 2409 1356 2409 1369 2409 1369 2410 1356 2410 1363 2410 953 2411 952 2411 954 2411 954 2412 952 2412 1370 2412 954 2413 1370 2413 956 2413 956 2414 1370 2414 1365 2414 956 2415 1365 2415 958 2415 958 2416 1365 2416 1355 2416 958 2417 1355 2417 961 2417 961 2418 1355 2418 1357 2418 961 2419 1357 2419 964 2419 964 2420 1357 2420 1359 2420 964 2421 1359 2421 966 2421 966 2422 1359 2422 1360 2422 966 2423 1360 2423 1362 2423 1362 2424 1360 2424 1366 2424 1362 2425 1366 2425 1361 2425 885 2426 982 2426 886 2426 886 2427 982 2427 981 2427 886 2428 981 2428 1010 2428 1010 2429 981 2429 979 2429 1010 2430 979 2430 1008 2430 1008 2431 979 2431 977 2431 1008 2432 977 2432 1006 2432 1006 2433 977 2433 975 2433 881 2434 983 2434 882 2434 882 2435 983 2435 1012 2435 882 2436 1012 2436 880 2436 880 2437 1012 2437 1011 2437 880 2438 1011 2438 878 2438 878 2439 1011 2439 1009 2439 878 2440 1009 2440 1027 2440 1027 2441 1009 2441 1007 2441 1027 2442 1007 2442 1371 2442 1371 2443 1007 2443 1372 2443 1371 2444 1372 2444 1373 2444 1368 2445 1373 2445 1367 2445 1367 2446 1373 2446 1372 2446 1367 2447 1372 2447 1366 2447 1366 2448 1372 2448 1007 2448 1366 2449 1007 2449 1361 2449 1361 2450 1007 2450 1006 2450 1361 2451 1006 2451 973 2451 973 2452 1006 2452 975 2452 973 2453 975 2453 972 2453 972 2454 975 2454 974 2454 972 2455 974 2455 971 2455 971 2456 974 2456 1374 2456 1375 2457 1376 2457 1377 2457 1377 2458 1376 2458 1378 2458 1377 2459 1378 2459 1379 2459 1379 2460 1378 2460 1380 2460 1379 2461 1380 2461 1381 2461 1381 2462 1380 2462 1382 2462 1381 2463 1382 2463 1383 2463 1383 2464 1382 2464 1384 2464 1383 2465 1384 2465 1385 2465 1385 2466 1384 2466 1386 2466 1385 2467 1386 2467 1387 2467 1387 2468 1386 2468 1388 2468 1387 2469 1388 2469 1389 2469 1389 2470 1388 2470 1390 2470 1389 2471 1390 2471 1391 2471 1391 2472 1390 2472 1392 2472 1391 2473 1392 2473 1393 2473 1393 2474 1392 2474 1394 2474 1393 2475 1394 2475 1395 2475 1343 2476 1395 2476 1344 2476 1344 2477 1395 2477 1394 2477 1344 2478 1394 2478 940 2478 940 2479 1394 2479 1392 2479 940 2480 1392 2480 942 2480 942 2481 1392 2481 1390 2481 942 2482 1390 2482 944 2482 944 2483 1390 2483 1388 2483 944 2484 1388 2484 946 2484 946 2485 1388 2485 1386 2485 946 2486 1386 2486 948 2486 948 2487 1386 2487 1384 2487 948 2488 1384 2488 950 2488 950 2489 1384 2489 1382 2489 950 2490 1382 2490 952 2490 952 2491 1382 2491 1380 2491 952 2492 1380 2492 1370 2492 1370 2493 1380 2493 1378 2493 1370 2494 1378 2494 1365 2494 1365 2495 1378 2495 1376 2495 1365 2496 1376 2496 1364 2496 1364 2497 1376 2497 1375 2497 1364 2498 1375 2498 1363 2498 115 2499 114 2499 1354 2499 1354 2500 114 2500 1334 2500 1354 2501 1334 2501 1335 2501 1335 2502 1334 2502 1332 2502 1335 2503 1332 2503 1336 2503 1336 2504 1332 2504 1330 2504 1336 2505 1330 2505 1338 2505 1338 2506 1330 2506 1328 2506 1338 2507 1328 2507 1251 2507 1251 2508 1328 2508 1327 2508 1251 2509 1327 2509 1252 2509 1252 2510 1327 2510 1326 2510 1252 2511 1326 2511 1254 2511 1254 2512 1326 2512 1325 2512 1254 2513 1325 2513 1255 2513 1255 2514 1325 2514 1324 2514 1255 2515 1324 2515 1343 2515 1343 2516 1324 2516 1183 2516 1343 2517 1183 2517 1395 2517 1395 2518 1183 2518 1181 2518 1395 2519 1181 2519 1393 2519 1393 2520 1181 2520 1179 2520 1393 2521 1179 2521 1391 2521 1391 2522 1179 2522 1177 2522 1391 2523 1177 2523 1389 2523 1389 2524 1177 2524 1175 2524 1389 2525 1175 2525 1387 2525 1387 2526 1175 2526 1173 2526 1387 2527 1173 2527 1385 2527 1385 2528 1173 2528 1171 2528 1385 2529 1171 2529 1383 2529 1383 2530 1171 2530 1169 2530 1383 2531 1169 2531 1381 2531 1381 2532 1169 2532 1167 2532 1381 2533 1167 2533 1379 2533 1379 2534 1167 2534 1165 2534 1379 2535 1165 2535 1377 2535 1377 2536 1165 2536 1163 2536 1377 2537 1163 2537 1375 2537 1375 2538 1163 2538 1161 2538 1375 2539 1161 2539 1363 2539 1363 2540 1161 2540 1159 2540 1363 2541 1159 2541 1369 2541 1369 2542 1159 2542 1157 2542 1369 2543 1157 2543 1368 2543 1368 2544 1157 2544 1155 2544 1368 2545 1155 2545 1373 2545 1373 2546 1155 2546 1153 2546 1373 2547 1153 2547 1371 2547 1371 2548 1153 2548 1152 2548 1371 2549 1152 2549 1027 2549 1027 2550 1152 2550 1191 2550 1027 2551 1191 2551 1028 2551 1028 2552 1191 2552 1190 2552 1028 2553 1190 2553 1030 2553 1030 2554 1190 2554 1189 2554 1030 2555 1189 2555 1032 2555 1032 2556 1189 2556 1188 2556 1032 2557 1188 2557 1034 2557 1034 2558 1188 2558 1187 2558 1034 2559 1187 2559 1036 2559 1036 2560 1187 2560 1186 2560 1036 2561 1186 2561 1038 2561 1038 2562 1186 2562 1185 2562 1038 2563 1185 2563 1055 2563 1055 2564 1185 2564 1068 2564 1055 2565 1068 2565 1061 2565 1061 2566 1068 2566 1067 2566 1061 2567 1067 2567 1062 2567 1062 2568 1067 2568 1196 2568 1062 2569 1196 2569 1063 2569 1063 2570 1196 2570 1217 2570 1063 2571 1217 2571 1064 2571 1064 2572 1217 2572 907 2572 1064 2573 907 2573 1065 2573 1065 2574 907 2574 158 2574 1065 2575 158 2575 157 2575 1396 2576 1397 2576 996 2576 1398 2577 1399 2577 1374 2577 1374 2578 974 2578 1398 2578 1398 2579 974 2579 976 2579 1398 2580 976 2580 1400 2580 1400 2581 976 2581 1401 2581 1401 2582 976 2582 978 2582 1401 2583 978 2583 1402 2583 978 2584 980 2584 1402 2584 1402 2585 980 2585 982 2585 1402 2586 982 2586 1403 2586 1403 2587 982 2587 885 2587 885 2588 884 2588 1403 2588 1403 2589 884 2589 983 2589 1403 2590 983 2590 1404 2590 1404 2591 983 2591 881 2591 1404 2592 881 2592 1405 2592 1405 2593 881 2593 984 2593 1405 2594 984 2594 1406 2594 1406 2595 984 2595 986 2595 1406 2596 986 2596 1407 2596 1407 2597 986 2597 988 2597 1407 2598 988 2598 1408 2598 1408 2599 988 2599 994 2599 1408 2600 994 2600 1409 2600 1409 2601 994 2601 1410 2601 994 2602 993 2602 1410 2602 1410 2603 993 2603 992 2603 1410 2604 992 2604 1411 2604 992 2605 991 2605 1411 2605 1411 2606 991 2606 999 2606 1411 2607 999 2607 1397 2607 1397 2608 999 2608 998 2608 1397 2609 998 2609 996 2609 1412 2610 1413 2610 1000 2610 1000 2611 1413 2611 1414 2611 1000 2612 1414 2612 1001 2612 1001 2613 1414 2613 1415 2613 1001 2614 1415 2614 1003 2614 1003 2615 1415 2615 1396 2615 1003 2616 1396 2616 995 2616 995 2617 1396 2617 996 2617 1412 2618 1000 2618 1416 2618 1416 2619 1000 2619 903 2619 1416 2620 903 2620 1417 2620 1417 2621 903 2621 1418 2621 1418 2622 903 2622 902 2622 1418 2623 902 2623 1419 2623 1419 2624 902 2624 1420 2624 1420 2625 902 2625 901 2625 1420 2626 901 2626 1421 2626 1421 2627 901 2627 1422 2627 1422 2628 901 2628 900 2628 1422 2629 900 2629 1423 2629 1423 2630 900 2630 1424 2630 1424 2631 900 2631 899 2631 1424 2632 899 2632 1425 2632 1425 2633 899 2633 898 2633 1425 2634 898 2634 1426 2634 1426 2635 898 2635 897 2635 1427 2636 1399 2636 1398 2636 1425 2637 1426 2637 799 2637 799 2638 1426 2638 897 2638 799 2639 897 2639 166 2639 798 2640 1423 2640 799 2640 799 2641 1423 2641 1424 2641 799 2642 1424 2642 1425 2642 797 2643 1421 2643 798 2643 798 2644 1421 2644 1422 2644 798 2645 1422 2645 1423 2645 796 2646 1419 2646 797 2646 797 2647 1419 2647 1420 2647 797 2648 1420 2648 1421 2648 795 2649 1417 2649 796 2649 796 2650 1417 2650 1418 2650 796 2651 1418 2651 1419 2651 815 2652 1412 2652 795 2652 795 2653 1412 2653 1416 2653 795 2654 1416 2654 1417 2654 808 2655 1409 2655 809 2655 809 2656 1409 2656 1410 2656 809 2657 1410 2657 810 2657 810 2658 1410 2658 1411 2658 810 2659 1411 2659 811 2659 811 2660 1411 2660 1397 2660 811 2661 1397 2661 812 2661 812 2662 1397 2662 1396 2662 812 2663 1396 2663 813 2663 813 2664 1396 2664 1415 2664 813 2665 1415 2665 814 2665 814 2666 1415 2666 1414 2666 814 2667 1414 2667 815 2667 815 2668 1414 2668 1413 2668 815 2669 1413 2669 1412 2669 803 2670 1403 2670 804 2670 804 2671 1403 2671 1404 2671 804 2672 1404 2672 805 2672 805 2673 1404 2673 1405 2673 805 2674 1405 2674 806 2674 806 2675 1405 2675 1406 2675 806 2676 1406 2676 807 2676 807 2677 1406 2677 1407 2677 807 2678 1407 2678 808 2678 808 2679 1407 2679 1408 2679 808 2680 1408 2680 1409 2680 825 2681 1427 2681 823 2681 823 2682 1427 2682 1398 2682 823 2683 1398 2683 821 2683 821 2684 1398 2684 1400 2684 821 2685 1400 2685 819 2685 819 2686 1400 2686 1401 2686 819 2687 1401 2687 816 2687 816 2688 1401 2688 1402 2688 816 2689 1402 2689 801 2689 801 2690 1402 2690 1403 2690 801 2691 1403 2691 802 2691 802 2692 1403 2692 803 2692 1428 2693 1429 2693 1430 2693 1431 2694 1432 2694 1433 2694 1428 2695 1430 2695 1434 2695 1435 2696 1436 2696 1430 2696 1430 2697 1436 2697 1437 2697 1430 2698 1437 2698 1438 2698 1438 2699 1437 2699 1439 2699 1438 2700 1439 2700 1440 2700 1432 2701 1440 2701 1441 2701 1432 2702 1442 2702 1440 2702 1440 2703 1442 2703 1443 2703 1440 2704 1443 2704 1444 2704 1431 2705 1433 2705 1445 2705 1446 2702 1447 2702 1440 2702 1448 2706 1449 2706 1430 2706 1430 2707 1450 2707 1451 2707 1429 2708 1452 2708 1430 2708 1430 2709 1452 2709 1453 2709 1430 2710 1453 2710 1454 2710 1455 2711 1456 2711 1457 2711 1456 2702 1455 2702 1433 2702 1433 2712 1455 2712 1458 2712 1433 2713 1458 2713 1445 2713 1446 2702 1440 2702 1459 2702 1460 2714 1461 2714 1440 2714 1440 2715 1461 2715 1462 2715 1440 2716 1462 2716 1438 2716 1463 2717 1464 2717 1430 2717 1454 2718 1465 2718 1430 2718 1430 2719 1465 2719 1466 2719 1430 2720 1466 2720 1435 2720 1457 2721 1467 2721 1455 2721 1455 2722 1467 2722 1468 2722 1455 2723 1468 2723 1469 2723 1449 2702 1470 2702 1430 2702 1430 2724 1470 2724 1471 2724 1430 2725 1471 2725 1450 2725 1464 2726 1472 2726 1430 2726 1430 2727 1472 2727 1473 2727 1430 2728 1473 2728 1434 2728 1441 2702 1474 2702 1432 2702 1432 2729 1474 2729 1475 2729 1432 2730 1475 2730 1476 2730 1476 2702 1477 2702 1432 2702 1432 2731 1477 2731 1478 2731 1432 2732 1478 2732 1479 2732 1479 2702 1480 2702 1432 2702 1432 2733 1480 2733 1481 2733 1432 2734 1481 2734 1433 2734 1482 2702 1483 2702 1484 2702 1484 2702 1483 2702 1485 2702 1469 2735 1486 2735 1455 2735 1455 2736 1486 2736 1483 2736 1455 2702 1483 2702 1487 2702 1487 2702 1483 2702 1482 2702 1444 2737 1488 2737 1440 2737 1440 2738 1488 2738 1489 2738 1440 2739 1489 2739 1459 2739 1447 2740 1490 2740 1440 2740 1440 2741 1490 2741 1491 2741 1440 2742 1491 2742 1460 2742 1430 2702 1492 2702 1493 2702 1430 2702 1494 2702 1448 2702 1448 2743 1494 2743 1495 2743 1448 2702 1495 2702 1496 2702 1496 2744 1495 2744 1497 2744 1451 2745 1498 2745 1430 2745 1430 2746 1498 2746 1499 2746 1430 2747 1499 2747 1492 2747 1500 2748 1501 2748 1502 2748 1501 2749 1503 2749 1502 2749 1502 2750 1503 2750 1504 2750 1502 2751 1504 2751 1505 2751 1493 2702 1506 2702 1430 2702 1430 2752 1506 2752 1507 2752 1430 2753 1507 2753 1463 2753 1497 2754 1495 2754 1502 2754 1502 2755 1495 2755 1508 2755 1502 2702 1508 2702 1500 2702 166 2756 35 2756 1509 2756 1509 2757 35 2757 1510 2757 1510 2758 35 2758 34 2758 1510 2759 34 2759 1511 2759 1511 2760 34 2760 38 2760 1511 2761 38 2761 1512 2761 53 2762 1513 2762 54 2762 54 2763 1513 2763 1514 2763 54 2764 1514 2764 50 2764 50 2765 1514 2765 1515 2765 50 2766 1515 2766 51 2766 51 2767 1515 2767 1516 2767 51 2768 1516 2768 43 2768 43 2769 1516 2769 1517 2769 43 2770 1517 2770 45 2770 45 2771 1517 2771 1518 2771 45 2772 1518 2772 47 2772 47 2773 1518 2773 1519 2773 47 2774 1519 2774 48 2774 48 2775 1519 2775 1520 2775 48 2776 1520 2776 40 2776 40 2777 1520 2777 1512 2777 40 2778 1512 2778 37 2778 37 2779 1512 2779 38 2779 57 2780 1521 2780 53 2780 53 2781 1521 2781 1522 2781 53 2782 1522 2782 1513 2782 57 2783 56 2783 1521 2783 1521 2784 56 2784 60 2784 1521 2785 60 2785 1523 2785 1523 2786 60 2786 59 2786 1523 2787 59 2787 1524 2787 1524 2788 59 2788 65 2788 1524 2789 65 2789 1525 2789 61 2790 1526 2790 62 2790 62 2791 1526 2791 1525 2791 62 2792 1525 2792 64 2792 64 2793 1525 2793 65 2793 61 2794 66 2794 1526 2794 1526 2795 66 2795 68 2795 1526 2796 68 2796 1527 2796 1527 2797 68 2797 70 2797 1527 2798 70 2798 1528 2798 1528 2799 70 2799 72 2799 1528 2800 72 2800 1529 2800 1529 2801 72 2801 74 2801 1529 2802 74 2802 1530 2802 1530 2803 74 2803 75 2803 1530 2804 75 2804 1531 2804 1531 2805 75 2805 77 2805 1531 2806 77 2806 1532 2806 1532 2807 77 2807 562 2807 1532 2808 562 2808 1533 2808 1532 2809 1533 2809 1534 2809 1527 2810 1528 2810 866 2810 866 2811 1528 2811 1529 2811 866 2812 1529 2812 867 2812 867 2813 1529 2813 1530 2813 867 2814 1530 2814 868 2814 868 2815 1530 2815 1531 2815 868 2816 1531 2816 865 2816 865 2817 1531 2817 1532 2817 865 2818 1532 2818 826 2818 826 2819 1532 2819 1534 2819 826 2820 1534 2820 827 2820 866 2821 829 2821 1527 2821 1527 2822 829 2822 830 2822 1527 2823 830 2823 831 2823 832 2824 1525 2824 831 2824 831 2825 1525 2825 1526 2825 831 2826 1526 2826 1527 2826 832 2827 833 2827 1525 2827 1525 2828 833 2828 834 2828 1525 2829 834 2829 1524 2829 1524 2830 834 2830 836 2830 1524 2831 836 2831 1523 2831 1523 2832 836 2832 838 2832 1523 2833 838 2833 1521 2833 1521 2834 838 2834 840 2834 1521 2835 840 2835 1522 2835 1522 2836 840 2836 841 2836 1522 2837 841 2837 1513 2837 1513 2838 841 2838 843 2838 1513 2839 843 2839 1514 2839 1514 2840 843 2840 845 2840 1514 2841 845 2841 1515 2841 1515 2842 845 2842 846 2842 1515 2843 846 2843 1516 2843 1516 2844 846 2844 848 2844 1516 2845 848 2845 1517 2845 1517 2846 848 2846 850 2846 1517 2847 850 2847 1518 2847 1518 2848 850 2848 852 2848 1518 2849 852 2849 1519 2849 1519 2850 852 2850 853 2850 1519 2851 853 2851 1520 2851 1520 2852 853 2852 855 2852 1520 2853 855 2853 1512 2853 1512 2854 855 2854 857 2854 1512 2855 857 2855 1511 2855 1511 2856 857 2856 859 2856 1511 2857 859 2857 1510 2857 1510 2858 859 2858 860 2858 1510 2859 860 2859 1509 2859 1509 2860 860 2860 166 2860 1535 2861 1536 2861 1537 2861 1537 2862 1536 2862 1538 2862 1537 2863 1538 2863 1539 2863 1535 2864 1537 2864 1540 2864 1540 2865 1537 2865 1541 2865 1540 2866 1541 2866 1542 2866 1542 2867 1541 2867 1443 2867 1542 2868 1443 2868 1442 2868 1538 2869 825 2869 1539 2869 1539 2870 825 2870 824 2870 1539 2871 824 2871 585 2871 585 2872 1543 2872 1539 2872 1539 2873 1543 2873 1544 2873 1539 2874 1544 2874 1537 2874 1537 2875 1544 2875 1545 2875 1537 2876 1545 2876 1541 2876 1444 2877 1443 2877 1546 2877 1546 2878 1443 2878 1541 2878 1546 2879 1541 2879 1547 2879 1547 2880 1541 2880 1545 2880 1542 2881 1442 2881 1548 2881 1549 2882 1550 2882 1551 2882 1551 2883 1550 2883 1552 2883 1551 2884 1552 2884 1427 2884 1427 2885 1552 2885 1399 2885 1427 2886 825 2886 1551 2886 1551 2887 825 2887 1538 2887 1551 2888 1538 2888 1549 2888 1442 2889 1553 2889 1548 2889 1548 2890 1553 2890 1554 2890 1548 2891 1554 2891 1549 2891 1549 2892 1554 2892 1555 2892 1549 2893 1555 2893 1550 2893 1538 2894 1536 2894 1549 2894 1549 2895 1536 2895 1535 2895 1549 2896 1535 2896 1548 2896 1548 2897 1535 2897 1540 2897 1548 2898 1540 2898 1542 2898 1543 2899 585 2899 584 2899 1545 2900 1544 2900 1556 2900 1556 2901 1544 2901 1543 2901 1546 2902 1547 2902 1557 2902 1557 2903 1547 2903 1545 2903 1488 2904 1444 2904 1546 2904 1543 2905 584 2905 1556 2905 1556 2906 584 2906 586 2906 1556 2907 586 2907 1558 2907 1558 2908 586 2908 588 2908 1558 2909 588 2909 1559 2909 1559 2910 588 2910 590 2910 1559 2911 590 2911 1560 2911 1545 2912 1556 2912 1557 2912 1557 2913 1556 2913 1558 2913 1557 2914 1558 2914 1561 2914 1561 2915 1558 2915 1559 2915 1561 2916 1559 2916 1562 2916 1562 2917 1559 2917 1560 2917 1562 2918 1560 2918 1563 2918 1546 2919 1557 2919 1488 2919 1488 2920 1557 2920 1561 2920 1488 2921 1561 2921 1489 2921 1489 2922 1561 2922 1562 2922 1489 2923 1562 2923 1459 2923 1459 2924 1562 2924 1563 2924 1459 2925 1563 2925 1446 2925 1550 2926 1555 2926 1564 2926 1564 2927 1555 2927 1554 2927 1564 2928 1554 2928 1432 2928 1432 2929 1554 2929 1553 2929 1432 2930 1553 2930 1442 2930 1564 2931 1565 2931 1550 2931 1550 2932 1565 2932 1566 2932 1550 2933 1566 2933 1552 2933 1552 2934 1566 2934 1374 2934 1552 2935 1374 2935 1399 2935 1447 2936 1446 2936 1563 2936 1447 2937 1563 2937 1567 2937 1567 2938 1563 2938 1560 2938 1567 2939 1560 2939 1568 2939 1568 2940 1560 2940 590 2940 1568 2940 590 2940 685 2940 115 2941 1354 2941 1569 2941 1569 2942 1354 2942 1570 2942 1569 2943 1570 2943 1571 2943 1571 2944 1570 2944 1572 2944 1573 2945 1574 2945 1575 2945 1575 2946 1574 2946 1576 2946 1575 2947 1576 2947 1572 2947 1466 2948 1465 2948 1577 2948 1577 2949 1578 2949 1579 2949 1579 2950 1578 2950 1580 2950 1579 2951 1580 2951 1573 2951 1354 2952 927 2952 1570 2952 1570 2953 927 2953 925 2953 1570 2954 925 2954 1581 2954 1581 2955 925 2955 924 2955 1581 2956 924 2956 1582 2956 1582 2957 924 2957 932 2957 1582 2958 932 2958 1583 2958 1583 2959 932 2959 931 2959 1583 2960 931 2960 1584 2960 1584 2961 931 2961 929 2961 1584 2962 929 2962 1585 2962 1585 2963 929 2963 1346 2963 1585 2964 1346 2964 1586 2964 1586 2965 1346 2965 935 2965 1586 2966 935 2966 1587 2966 1587 2967 935 2967 934 2967 1587 2968 934 2968 1588 2968 934 2969 936 2969 1588 2969 1588 2970 936 2970 938 2970 1588 2971 938 2971 1589 2971 1589 2972 938 2972 894 2972 1589 2973 894 2973 1590 2973 1590 2974 894 2974 893 2974 1590 2975 893 2975 1591 2975 1591 2976 893 2976 891 2976 1591 2977 891 2977 1592 2977 1592 2978 891 2978 890 2978 1592 2979 890 2979 1593 2979 1593 2980 890 2980 888 2980 888 2981 887 2981 1593 2981 1593 2982 887 2982 939 2982 1593 2983 939 2983 1594 2983 1594 2984 939 2984 941 2984 1594 2985 941 2985 1595 2985 1595 2986 941 2986 943 2986 1595 2987 943 2987 1596 2987 1596 2988 943 2988 945 2988 1596 2989 945 2989 1597 2989 1597 2990 945 2990 947 2990 1597 2991 947 2991 1598 2991 1598 2992 947 2992 949 2992 1598 2993 949 2993 1599 2993 1599 2994 949 2994 951 2994 1599 2995 951 2995 1600 2995 1600 2996 951 2996 953 2996 1600 2997 953 2997 1601 2997 1601 2998 953 2998 955 2998 1601 2999 955 2999 1602 2999 1602 3000 955 3000 957 3000 1602 3001 957 3001 1603 3001 1603 3002 957 3002 959 3002 1603 3003 959 3003 1604 3003 1604 3004 959 3004 960 3004 1604 3005 960 3005 1605 3005 1605 3006 960 3006 962 3006 962 3007 963 3007 1605 3007 1605 3008 963 3008 965 3008 1605 3009 965 3009 1606 3009 1606 3010 965 3010 967 3010 1606 3011 967 3011 1607 3011 1607 3012 967 3012 970 3012 1607 3013 970 3013 1608 3013 1608 3014 970 3014 969 3014 1608 3015 969 3015 1609 3015 1609 3016 969 3016 971 3016 1609 3017 971 3017 1610 3017 1610 3018 971 3018 1374 3018 1610 3019 1374 3019 1566 3019 1572 3020 1570 3020 1575 3020 1575 3021 1570 3021 1581 3021 1575 3022 1581 3022 1611 3022 1611 3023 1581 3023 1582 3023 1611 3024 1582 3024 1612 3024 1612 3025 1582 3025 1583 3025 1612 3026 1583 3026 1613 3026 1613 3027 1583 3027 1584 3027 1613 3028 1584 3028 1614 3028 1614 3029 1584 3029 1585 3029 1614 3030 1585 3030 1615 3030 1615 3031 1585 3031 1586 3031 1615 3032 1586 3032 1616 3032 1616 3033 1586 3033 1587 3033 1616 3034 1587 3034 1617 3034 1617 3035 1587 3035 1588 3035 1617 3036 1588 3036 1618 3036 1618 3037 1588 3037 1589 3037 1618 3038 1589 3038 1619 3038 1619 3039 1589 3039 1590 3039 1619 3040 1590 3040 1620 3040 1620 3041 1590 3041 1591 3041 1620 3042 1591 3042 1621 3042 1621 3043 1591 3043 1592 3043 1621 3044 1592 3044 1622 3044 1622 3045 1592 3045 1593 3045 1622 3046 1593 3046 1623 3046 1623 3047 1593 3047 1594 3047 1623 3048 1594 3048 1624 3048 1624 3049 1594 3049 1595 3049 1624 3050 1595 3050 1625 3050 1625 3051 1595 3051 1596 3051 1625 3052 1596 3052 1626 3052 1626 3053 1596 3053 1597 3053 1626 3054 1597 3054 1627 3054 1627 3055 1597 3055 1598 3055 1627 3056 1598 3056 1628 3056 1628 3057 1598 3057 1599 3057 1628 3058 1599 3058 1629 3058 1629 3059 1599 3059 1600 3059 1629 3060 1600 3060 1630 3060 1630 3061 1600 3061 1601 3061 1630 3062 1601 3062 1631 3062 1631 3063 1601 3063 1602 3063 1631 3064 1602 3064 1632 3064 1632 3065 1602 3065 1603 3065 1632 3066 1603 3066 1633 3066 1633 3067 1603 3067 1604 3067 1633 3068 1604 3068 1634 3068 1634 3069 1604 3069 1605 3069 1634 3070 1605 3070 1635 3070 1635 3071 1605 3071 1606 3071 1635 3072 1606 3072 1636 3072 1636 3073 1606 3073 1607 3073 1636 3074 1607 3074 1637 3074 1637 3075 1607 3075 1608 3075 1637 3076 1608 3076 1638 3076 1638 3077 1608 3077 1609 3077 1638 3078 1609 3078 1639 3078 1639 3079 1609 3079 1610 3079 1639 3080 1610 3080 1640 3080 1640 3081 1610 3081 1566 3081 1640 3082 1566 3082 1565 3082 1573 3083 1575 3083 1579 3083 1579 3084 1575 3084 1611 3084 1579 3085 1611 3085 1641 3085 1641 3086 1611 3086 1612 3086 1641 3087 1612 3087 1642 3087 1642 3088 1612 3088 1613 3088 1642 3089 1613 3089 1643 3089 1643 3090 1613 3090 1614 3090 1643 3091 1614 3091 1644 3091 1644 3092 1614 3092 1615 3092 1644 3093 1615 3093 1645 3093 1645 3094 1615 3094 1616 3094 1645 3095 1616 3095 1646 3095 1646 3096 1616 3096 1617 3096 1646 3097 1617 3097 1647 3097 1647 3098 1617 3098 1618 3098 1647 3099 1618 3099 1648 3099 1648 3100 1618 3100 1619 3100 1648 3101 1619 3101 1649 3101 1649 3102 1619 3102 1620 3102 1649 3103 1620 3103 1650 3103 1650 3104 1620 3104 1621 3104 1650 3105 1621 3105 1651 3105 1651 3106 1621 3106 1622 3106 1651 3107 1622 3107 1652 3107 1652 3108 1622 3108 1623 3108 1652 3109 1623 3109 1653 3109 1653 3110 1623 3110 1624 3110 1653 3111 1624 3111 1654 3111 1654 3112 1624 3112 1625 3112 1654 3113 1625 3113 1655 3113 1655 3114 1625 3114 1626 3114 1655 3115 1626 3115 1656 3115 1656 3116 1626 3116 1627 3116 1656 3117 1627 3117 1657 3117 1657 3118 1627 3118 1628 3118 1657 3119 1628 3119 1658 3119 1658 3120 1628 3120 1629 3120 1658 3121 1629 3121 1659 3121 1659 3122 1629 3122 1630 3122 1659 3123 1630 3123 1660 3123 1660 3124 1630 3124 1631 3124 1660 3125 1631 3125 1661 3125 1661 3126 1631 3126 1632 3126 1661 3127 1632 3127 1662 3127 1662 3128 1632 3128 1633 3128 1662 3129 1633 3129 1663 3129 1663 3130 1633 3130 1634 3130 1663 3131 1634 3131 1664 3131 1664 3132 1634 3132 1635 3132 1664 3133 1635 3133 1665 3133 1665 3134 1635 3134 1636 3134 1665 3135 1636 3135 1666 3135 1666 3136 1636 3136 1637 3136 1666 3137 1637 3137 1667 3137 1667 3138 1637 3138 1638 3138 1667 3139 1638 3139 1668 3139 1668 3140 1638 3140 1639 3140 1668 3141 1639 3141 1669 3141 1669 3142 1639 3142 1640 3142 1669 3143 1640 3143 1670 3143 1670 3144 1640 3144 1565 3144 1670 3145 1565 3145 1564 3145 1577 3146 1579 3146 1466 3146 1466 3147 1579 3147 1641 3147 1466 3148 1641 3148 1435 3148 1435 3149 1641 3149 1642 3149 1435 3150 1642 3150 1436 3150 1436 3151 1642 3151 1643 3151 1436 3152 1643 3152 1437 3152 1437 3153 1643 3153 1644 3153 1437 3154 1644 3154 1439 3154 1439 3155 1644 3155 1645 3155 1439 3156 1645 3156 1440 3156 1440 3157 1645 3157 1646 3157 1440 3158 1646 3158 1441 3158 1441 3159 1646 3159 1647 3159 1441 3160 1647 3160 1474 3160 1474 3161 1647 3161 1648 3161 1474 3162 1648 3162 1475 3162 1475 3163 1648 3163 1649 3163 1475 3164 1649 3164 1476 3164 1476 3165 1649 3165 1650 3165 1476 3166 1650 3166 1477 3166 1477 3167 1650 3167 1651 3167 1477 3168 1651 3168 1478 3168 1478 3169 1651 3169 1652 3169 1478 3170 1652 3170 1479 3170 1479 3171 1652 3171 1653 3171 1479 3172 1653 3172 1480 3172 1480 3173 1653 3173 1654 3173 1480 3174 1654 3174 1481 3174 1481 3175 1654 3175 1655 3175 1481 3176 1655 3176 1433 3176 1433 3177 1655 3177 1656 3177 1433 3178 1656 3178 1456 3178 1456 3179 1656 3179 1657 3179 1456 3180 1657 3180 1457 3180 1457 3181 1657 3181 1658 3181 1457 3182 1658 3182 1467 3182 1467 3183 1658 3183 1659 3183 1467 3184 1659 3184 1468 3184 1468 3185 1659 3185 1660 3185 1468 3186 1660 3186 1469 3186 1469 3187 1660 3187 1661 3187 1469 3188 1661 3188 1486 3188 1486 3189 1661 3189 1662 3189 1486 3190 1662 3190 1483 3190 1483 3191 1662 3191 1663 3191 1483 3192 1663 3192 1485 3192 1485 3193 1663 3193 1664 3193 1485 3194 1664 3194 1484 3194 1484 3195 1664 3195 1665 3195 1484 3196 1665 3196 1482 3196 1482 3197 1665 3197 1666 3197 1482 3198 1666 3198 1487 3198 1487 3199 1666 3199 1667 3199 1487 3200 1667 3200 1455 3200 1455 3201 1667 3201 1668 3201 1455 3202 1668 3202 1458 3202 1458 3203 1668 3203 1669 3203 1458 3204 1669 3204 1445 3204 1445 3205 1669 3205 1670 3205 1445 3206 1670 3206 1431 3206 1431 3207 1670 3207 1564 3207 1431 3208 1564 3208 1432 3208 1568 3209 685 3209 683 3209 1567 3210 1568 3210 1671 3210 1447 3211 1567 3211 1672 3211 1568 3212 683 3212 1671 3212 1671 3213 683 3213 682 3213 1671 3214 682 3214 1673 3214 1673 3215 682 3215 688 3215 1673 3216 688 3216 1674 3216 688 3217 687 3217 1674 3217 1674 3218 687 3218 1675 3218 1674 3219 1675 3219 1676 3219 1567 3220 1671 3220 1672 3220 1672 3221 1671 3221 1673 3221 1672 3222 1673 3222 1677 3222 1677 3223 1673 3223 1674 3223 1677 3224 1674 3224 1678 3224 1678 3225 1674 3225 1676 3225 1678 3226 1676 3226 1679 3226 1447 3227 1672 3227 1490 3227 1490 3228 1672 3228 1677 3228 1490 3229 1677 3229 1491 3229 1491 3230 1677 3230 1678 3230 1491 3231 1678 3231 1460 3231 1460 3232 1678 3232 1679 3232 1460 3233 1679 3233 1461 3233 1577 3234 1465 3234 1454 3234 1577 3235 1454 3235 1578 3235 1574 3236 1573 3236 1680 3236 1680 3237 1573 3237 1580 3237 1680 3238 1580 3238 1578 3238 1572 3239 1576 3239 1681 3239 1681 3240 1576 3240 1574 3240 115 3241 1569 3241 1682 3241 1682 3242 1569 3242 1571 3242 1682 3243 1571 3243 1572 3243 1683 3244 102 3244 1684 3244 1684 3245 102 3245 106 3245 1684 3246 106 3246 1685 3246 1685 3247 106 3247 108 3247 1685 3248 108 3248 1686 3248 1686 3249 108 3249 110 3249 1686 3250 110 3250 1687 3250 1687 3251 110 3251 113 3251 1687 3252 113 3252 1688 3252 1688 3253 113 3253 112 3253 1688 3254 112 3254 1689 3254 1689 3255 112 3255 111 3255 1689 3256 111 3256 1690 3256 1690 3257 111 3257 28 3257 1690 3258 28 3258 1691 3258 1691 3259 28 3259 27 3259 1691 3260 27 3260 1692 3260 1692 3261 27 3261 24 3261 1692 3262 24 3262 1682 3262 1682 3263 24 3263 116 3263 1682 3264 116 3264 115 3264 100 3265 104 3265 1683 3265 1683 3266 104 3266 103 3266 1683 3267 103 3267 102 3267 1683 3268 1693 3268 100 3268 100 3269 1693 3269 1694 3269 100 3270 1694 3270 101 3270 101 3271 1694 3271 1695 3271 101 3272 1695 3272 30 3272 30 3273 1695 3273 1696 3273 30 3274 1696 3274 98 3274 98 3275 1696 3275 97 3275 97 3276 1696 3276 95 3276 95 3277 1696 3277 1697 3277 95 3278 1697 3278 88 3278 88 3279 1697 3279 1698 3279 88 3280 1698 3280 89 3280 89 3281 1698 3281 1699 3281 89 3282 1699 3282 91 3282 91 3283 1699 3283 1700 3283 91 3284 1700 3284 93 3284 93 3285 1700 3285 1701 3285 93 3286 1701 3286 94 3286 94 3287 1701 3287 1702 3287 94 3288 1702 3288 532 3288 532 3289 1702 3289 1703 3289 532 3290 1703 3290 530 3290 530 3291 1703 3291 1704 3291 530 3292 1704 3292 85 3292 85 3293 1704 3293 1705 3293 85 3294 1705 3294 86 3294 86 3295 1705 3295 1706 3295 86 3296 1706 3296 526 3296 526 3297 1706 3297 1707 3297 526 3298 1707 3298 548 3298 548 3299 1707 3299 1708 3299 548 3300 1708 3300 82 3300 82 3301 1708 3301 83 3301 83 3302 1708 3302 1709 3302 83 3303 1709 3303 84 3303 1578 3304 1454 3304 1680 3304 1680 3305 1454 3305 1453 3305 1680 3306 1453 3306 1710 3306 1710 3307 1453 3307 1452 3307 1710 3308 1452 3308 1711 3308 1711 3309 1452 3309 1429 3309 1711 3310 1429 3310 1712 3310 1712 3311 1429 3311 1428 3311 1712 3312 1428 3312 1713 3312 1713 3313 1428 3313 1434 3313 1713 3314 1434 3314 1714 3314 1714 3315 1434 3315 1473 3315 1714 3316 1473 3316 1715 3316 1715 3317 1473 3317 1472 3317 1715 3318 1472 3318 1716 3318 1716 3319 1472 3319 1464 3319 1716 3320 1464 3320 1717 3320 1717 3321 1464 3321 1463 3321 1717 3322 1463 3322 1718 3322 1718 3323 1463 3323 1507 3323 1718 3324 1507 3324 1719 3324 1719 3325 1507 3325 1506 3325 1719 3326 1506 3326 1720 3326 1720 3327 1506 3327 1493 3327 1720 3328 1493 3328 1721 3328 1721 3329 1493 3329 1492 3329 1721 3330 1492 3330 1722 3330 1722 3331 1492 3331 1499 3331 1722 3332 1499 3332 1723 3332 1723 3333 1499 3333 1498 3333 1723 3334 1498 3334 1724 3334 1724 3335 1498 3335 1451 3335 1724 3336 1451 3336 1725 3336 1725 3337 1451 3337 1450 3337 1725 3338 1450 3338 1726 3338 1726 3339 1450 3339 1471 3339 1726 3340 1471 3340 1727 3340 1727 3341 1471 3341 1470 3341 1727 3342 1470 3342 1728 3342 1728 3343 1470 3343 1449 3343 1728 3344 1449 3344 1729 3344 1729 3345 1449 3345 1448 3345 1729 3346 1448 3346 1730 3346 1730 3347 1448 3347 1496 3347 1730 3348 1496 3348 1731 3348 1731 3349 1496 3349 1497 3349 1731 3350 1497 3350 1732 3350 1732 3351 1497 3351 1502 3351 1732 3352 1502 3352 1733 3352 1733 3353 1502 3353 1505 3353 1733 3354 1505 3354 1734 3354 1734 3355 1505 3355 1504 3355 1734 3356 1504 3356 1735 3356 1735 3357 1504 3357 1503 3357 1735 3358 1503 3358 1736 3358 1736 3359 1503 3359 1501 3359 1736 3360 1501 3360 1737 3360 1737 3361 1501 3361 1500 3361 1737 3362 1500 3362 1738 3362 1738 3363 1500 3363 1508 3363 1738 3364 1508 3364 1739 3364 1739 3365 1508 3365 1495 3365 1739 3366 1495 3366 1740 3366 1740 3367 1495 3367 1494 3367 1740 3368 1494 3368 1741 3368 1574 3369 1680 3369 1681 3369 1681 3370 1680 3370 1710 3370 1681 3371 1710 3371 1742 3371 1742 3372 1710 3372 1711 3372 1742 3373 1711 3373 1743 3373 1743 3374 1711 3374 1712 3374 1743 3375 1712 3375 1744 3375 1744 3376 1712 3376 1713 3376 1744 3377 1713 3377 1745 3377 1745 3378 1713 3378 1714 3378 1745 3379 1714 3379 1746 3379 1746 3380 1714 3380 1715 3380 1746 3381 1715 3381 1747 3381 1747 3382 1715 3382 1716 3382 1747 3383 1716 3383 1748 3383 1748 3384 1716 3384 1717 3384 1748 3385 1717 3385 1749 3385 1749 3386 1717 3386 1718 3386 1749 3387 1718 3387 1750 3387 1750 3388 1718 3388 1719 3388 1750 3389 1719 3389 1751 3389 1751 3390 1719 3390 1720 3390 1751 3391 1720 3391 1752 3391 1752 3392 1720 3392 1721 3392 1752 3393 1721 3393 1753 3393 1753 3394 1721 3394 1722 3394 1753 3395 1722 3395 1754 3395 1754 3396 1722 3396 1723 3396 1754 3397 1723 3397 1755 3397 1755 3398 1723 3398 1724 3398 1755 3399 1724 3399 1756 3399 1756 3400 1724 3400 1725 3400 1756 3401 1725 3401 1757 3401 1757 3402 1725 3402 1726 3402 1757 3403 1726 3403 1758 3403 1758 3404 1726 3404 1727 3404 1758 3405 1727 3405 1759 3405 1759 3406 1727 3406 1728 3406 1759 3407 1728 3407 1760 3407 1760 3408 1728 3408 1729 3408 1760 3409 1729 3409 1761 3409 1761 3410 1729 3410 1730 3410 1761 3411 1730 3411 1762 3411 1762 3412 1730 3412 1731 3412 1762 3413 1731 3413 1763 3413 1763 3414 1731 3414 1732 3414 1763 3415 1732 3415 1764 3415 1764 3416 1732 3416 1733 3416 1764 3417 1733 3417 1765 3417 1765 3418 1733 3418 1734 3418 1765 3419 1734 3419 1766 3419 1766 3420 1734 3420 1735 3420 1766 3421 1735 3421 1767 3421 1767 3422 1735 3422 1736 3422 1767 3423 1736 3423 1768 3423 1768 3424 1736 3424 1737 3424 1768 3425 1737 3425 1769 3425 1769 3426 1737 3426 1738 3426 1769 3427 1738 3427 1770 3427 1770 3428 1738 3428 1739 3428 1770 3429 1739 3429 1771 3429 1771 3430 1739 3430 1740 3430 1771 3431 1740 3431 1772 3431 1772 3432 1740 3432 1741 3432 1772 3433 1741 3433 1773 3433 1572 3434 1681 3434 1682 3434 1682 3435 1681 3435 1742 3435 1682 3436 1742 3436 1692 3436 1692 3437 1742 3437 1743 3437 1692 3438 1743 3438 1691 3438 1691 3439 1743 3439 1744 3439 1691 3440 1744 3440 1690 3440 1690 3441 1744 3441 1745 3441 1690 3442 1745 3442 1689 3442 1689 3443 1745 3443 1746 3443 1689 3444 1746 3444 1688 3444 1688 3445 1746 3445 1747 3445 1688 3446 1747 3446 1687 3446 1687 3447 1747 3447 1748 3447 1687 3448 1748 3448 1686 3448 1686 3449 1748 3449 1749 3449 1686 3450 1749 3450 1685 3450 1685 3451 1749 3451 1750 3451 1685 3452 1750 3452 1684 3452 1684 3453 1750 3453 1751 3453 1684 3454 1751 3454 1683 3454 1683 3455 1751 3455 1752 3455 1683 3456 1752 3456 1693 3456 1693 3457 1752 3457 1753 3457 1693 3458 1753 3458 1694 3458 1694 3459 1753 3459 1754 3459 1694 3460 1754 3460 1695 3460 1695 3461 1754 3461 1755 3461 1695 3462 1755 3462 1696 3462 1696 3463 1755 3463 1756 3463 1696 3464 1756 3464 1697 3464 1697 3465 1756 3465 1757 3465 1697 3466 1757 3466 1698 3466 1698 3467 1757 3467 1758 3467 1698 3468 1758 3468 1699 3468 1699 3469 1758 3469 1759 3469 1699 3470 1759 3470 1700 3470 1700 3471 1759 3471 1760 3471 1700 3472 1760 3472 1701 3472 1701 3473 1760 3473 1761 3473 1701 3474 1761 3474 1702 3474 1702 3475 1761 3475 1762 3475 1702 3476 1762 3476 1703 3476 1703 3477 1762 3477 1763 3477 1703 3478 1763 3478 1704 3478 1704 3479 1763 3479 1764 3479 1704 3480 1764 3480 1705 3480 1705 3481 1764 3481 1765 3481 1705 3482 1765 3482 1706 3482 1706 3483 1765 3483 1766 3483 1706 3484 1766 3484 1707 3484 1707 3485 1766 3485 1767 3485 1707 3486 1767 3486 1708 3486 1708 3487 1767 3487 1768 3487 1708 3488 1768 3488 1709 3488 1709 3489 1768 3489 1769 3489 1709 3490 1769 3490 1774 3490 1774 3491 1769 3491 1770 3491 1774 3492 1770 3492 1775 3492 1775 3493 1770 3493 1771 3493 1775 3494 1771 3494 1776 3494 1776 3495 1771 3495 1772 3495 1776 3496 1772 3496 1777 3496 1777 3497 1772 3497 1773 3497 1777 3498 1773 3498 1778 3498 84 3499 1709 3499 521 3499 521 3500 1709 3500 1774 3500 521 3501 1774 3501 78 3501 78 3502 1774 3502 1775 3502 78 3503 1775 3503 79 3503 79 3504 1775 3504 1776 3504 79 3505 1776 3505 81 3505 81 3506 1776 3506 1777 3506 81 3507 1777 3507 561 3507 561 3508 1777 3508 1778 3508 561 3509 1778 3509 562 3509 1462 3510 1461 3510 1779 3510 1779 3511 1461 3511 1679 3511 1779 3512 1679 3512 1780 3512 1780 3513 1679 3513 1676 3513 1780 3514 1676 3514 1781 3514 1781 3515 1676 3515 1675 3515 1781 3516 1675 3516 828 3516 828 3517 1675 3517 687 3517 1438 3518 1462 3518 1782 3518 1782 3519 1462 3519 1779 3519 1782 3520 1779 3520 1783 3520 1783 3521 1779 3521 1780 3521 1783 3522 1780 3522 1784 3522 1784 3523 1780 3523 1781 3523 1784 3524 1781 3524 827 3524 827 3525 1781 3525 828 3525 1785 3526 1533 3526 562 3526 562 3527 1778 3527 1785 3527 1785 3528 1778 3528 1773 3528 1785 3529 1773 3529 1786 3529 1786 3530 1773 3530 1741 3530 1786 3531 1741 3531 1787 3531 1787 3532 1741 3532 1494 3532 1430 3533 1438 3533 1788 3533 1788 3534 1438 3534 1782 3534 1788 3535 1782 3535 1789 3535 1789 3536 1782 3536 1783 3536 1789 3537 1783 3537 1790 3537 1790 3538 1783 3538 1784 3538 1790 3539 1784 3539 1534 3539 1534 3540 1784 3540 827 3540 1494 3541 1430 3541 1787 3541 1787 3542 1430 3542 1788 3542 1787 3543 1788 3543 1786 3543 1786 3544 1788 3544 1789 3544 1786 3545 1789 3545 1785 3545 1785 3546 1789 3546 1790 3546 1785 3547 1790 3547 1533 3547 1533 3548 1790 3548 1534 3548

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
diff --git a/URDFs/sr_description/meshes/components/th_distal/pst/th_distal_pst.dae b/URDFs/sr_description/meshes/components/th_distal/pst/th_distal_pst.dae new file mode 100644 index 0000000..f1ed0b6 --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_distal/pst/th_distal_pst.dae @@ -0,0 +1,132 @@ + + + + + + Blender User + Blender 3.0.1 commit date:2022-01-25, commit time:17:19, hash:dc2d18018171 + + 2022-02-10T09:45:46 + 2022-02-10T09:45:46 + + Z_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -2.55768 9 19.17331 -2.506939 9 19.86789 -2.034731 9 19.8462 2.034731 9 19.8462 2.506939 9 19.86789 2.557679 9 19.17331 -3.073899 9 10.60533 3.073899 9 10.60534 3.353007 9 3.341558 -3.353007 9 3.341558 5.05 5.8 9.00833 5.05 5.2 9.464127 5.05 5.8 9.482215 5.05 5.2 9.482215 -5.05 5.2 9.464127 -5.05 5.8 9.00833 -5.05 5.2 9.482215 -5.05 5.8 9.482215 7.68301 7.569204 5.82024 7.978376 7.347282 5.685114 7.978376 7.316722 5.745363 6.241808 5.130235 9.482215 6.633532 5.886308 8.801447 6.446928 5.070229 9.482215 6.616663 5 9.482215 7.978376 5 8.52235 7.867467 5 8.654623 7.357062 5.690253 8.574786 7.504492 5 9.002189 7.368324 5 9.105569 6.955405 5 9.34893 6.848075 8.095846 5.768563 7.211372 7.884189 5.852874 7.357062 7.741002 5.962769 7.532063 7.67517 5.851119 6.204217 8.410559 5.417622 6.492428 8.278827 5.606901 6.633532 8.007717 6.099435 5.85709 8.539525 5.14048 5.85709 8.550559 5.110346 5.85709 8.098688 6.146049 5.85709 7.723468 6.808475 6.633532 7.418167 7.088432 5.85709 7.502441 7.146282 5.85709 6.783347 8.062185 6.633532 6.707151 7.994046 5.85709 6.585812 8.276091 5.85709 5.953179 8.878759 5.85709 5.173926 9.482215 7.357062 7.171091 6.918825 7.357062 6.483756 7.794275 7.978376 6.778047 6.649018 7.978376 6.128385 7.476485 7.978376 5.378374 8.214217 -7.121905 5 9.262447 -7.348607 5 9.1195 -7.357062 5.690253 8.574786 -7.735837 5 8.794322 -7.978376 5 8.52235 -7.978376 5.378374 8.214217 -7.708118 7.551095 5.812904 -7.501179 7.696242 5.854852 -7.357062 7.741002 5.962769 -5.85709 8.550559 5.110346 -5.85709 8.539525 5.14048 -5.973025 8.506012 5.22373 -5.85709 8.098688 6.146049 -6.338462 8.350993 5.512583 -6.611372 8.2202 5.669566 -6.633532 8.007717 6.099435 -6.984966 8.019119 5.810189 -7.165114 7.912586 5.846904 -7.05513 5 9.298908 -6.633532 5.886308 8.801447 -6.040488 5.164052 9.482215 -6.246764 5.129094 9.482215 -6.616663 5 9.482215 -5.85709 5.173926 9.482215 -5.85709 5.953179 8.878759 -5.85709 6.585812 8.276091 -6.633532 6.707151 7.994046 -5.85709 6.783347 8.062185 -5.85709 7.502441 7.146282 -6.633532 7.418167 7.088432 -5.85709 7.723468 6.808475 -7.357062 6.483756 7.794275 -7.357062 7.171091 6.918825 -7.978376 7.347282 5.685114 -7.978376 7.316722 5.745363 -7.978376 6.778047 6.649018 -7.978376 6.128385 7.476485 5.672272 8.616906 4.921764 5.076074 5.173926 9.482215 -5.076074 5.173926 9.482215 -4.537463 8.903451 3.877302 -4.17373 8.954113 3.619111 -4.132569 8.925611 3.769185 -3.801269 8.986454 3.429257 -4.912132 8.830914 4.192778 -5.185234 8.764594 4.444037 4.186992 8.952602 3.627434 4.426061 8.921008 3.792208 4.978883 8.815768 4.252799 -3.49215 8.998706 3.350188 3.799371 8.98657 3.428534 3.669031 8.993291 3.385696 -7.106018 -6.954698 9.556375 -6.88518 -6.648028 9.482217 -6.88518 -7.001696 9.546848 -7.054211 -7.458154 9.920858 -7.199854 -7.509562 10.0838 -7.193972 -7.340364 9.830054 -7.458285 -7.467149 10.50655 -7.46886 -7.458564 10.53069 -7.469547 -7.459518 10.48222 -7.447194 -7.475156 10.48222 -6.88518 -7.355135 9.775112 -7.200583 -7.086017 9.640382 -7.130944 -6.989312 9.574954 -7.217886 -7.513106 10.10679 -7.436282 -7.413323 10.14963 -7.347941 -7.290649 9.871569 -7.308287 -7.235582 9.792465 -10.5836 -1.379343 10.48222 -10.58248 -1.379329 10.52961 -10.58249 2 10.52961 -10.53348 -1.379603 10.16967 -10.53555 2 10.17588 -10.52803 2 10.15347 -10.39054 -1.379686 9.891619 -10.30729 2 9.792065 -9.900834 -1.37949 9.533878 -9.961278 -1.379525 9.556289 -9.956752 2 9.554442 -10.17173 -1.379633 9.673468 -10.30726 -1.379678 9.792084 -9.934726 2 9.54588 -9.692791 2 9.488194 -9.583624 -1.3793 9.482217 -9.583624 2 9.482216 6.885144 -7.355135 9.775112 6.885144 -6.648028 9.482217 6.885144 -7.001696 9.546848 6.885144 -7.030712 9.55834 -9.160587 2 28.54651 -9.313948 2 27.90424 -9.258036 1.656066 28.16862 -9.395987 1.656715 27.37881 -9.417464 2 27.17663 -9.417478 1.656942 27.17664 -9.16056 1.656222 28.5465 -9.022455 1.656711 28.97954 -8.648488 2 29.85749 -8.693047 1.656344 29.76741 -8.553046 2 30.04075 -8.287235 1.655893 30.49537 -7.797624 2 31.18073 -7.797616 1.656829 31.18075 -10.40618 -1.188569 13.91877 -10.29674 2 15.76996 -10.52827 -1.340123 11.63759 -9.602179 0.9842647 25.11952 -9.864404 2 21.94757 -9.786968 0.3629639 22.9196 -10.27052 -0.9419808 16.1917 -10.12176 -0.6008241 18.45211 -9.960351 -0.1655673 20.69622 -7.912967 -7.112607 10.53219 -7.911905 -5.728467 9.482217 -7.351424 -6.278915 9.482217 -7.738455 -6.440464 9.556556 -9.917541 -2.158388 9.556494 -8.306256 -5.853429 9.556688 -8.803075 -5.199226 9.556764 -8.407798 -5.105961 9.482217 -9.215053 -4.4964 9.556786 -8.820543 -4.433646 9.482217 -9.541988 -3.746457 9.55675 -9.147785 -3.718481 9.482217 -9.777845 -2.96069 9.556652 -9.38861 -2.959123 9.482217 -9.534358 -2.178216 9.482217 -10.26165 -2.197639 9.792987 -10.47915 -2.222449 10.1507 -10.55018 -2.073874 10.53106 -10.32804 -3.090766 10.15212 -10.43767 -2.844624 10.53347 -10.07282 -3.94121 10.153 -10.22742 -3.657884 10.53491 -9.944076 -4.405148 10.53557 -9.718992 -4.752888 10.15333 -9.767293 -4.777473 10.53569 -8.540571 -6.519673 10.53404 -9.099351 -5.853726 10.53522 -9.273096 -5.513559 10.15314 -9.318212 -5.543732 10.5355 -9.566395 -5.146238 10.53567 -7.972777 -6.695666 9.793264 -8.735357 -6.22158 10.15244 -8.120792 -6.856869 10.15127 -10.11516 -3.040438 9.793683 -9.867554 -3.865903 9.794113 -9.524168 -4.65373 9.794276 -9.091363 -5.392024 9.794182 -8.569369 -6.079169 9.79384 -6.30984 -8.024703 10.59801 -3.033238 -8.828372 11.66256 -3.033239 -8.827215 11.71067 -3.771698 -8.792226 11.68439 -3.033237 -8.535478 10.95545 -3.033238 -8.762089 11.30455 -3.494747 -8.519931 10.9399 -3.616479 -8.739423 11.2823 -6.182973 -7.95259 10.41036 -5.815475 -8.238403 10.80311 -5.295314 -8.420115 10.97738 -4.188136 -8.674197 11.22043 -6.052469 -7.837882 10.25786 -5.791827 -7.958481 10.37846 -5.119175 -8.211536 10.63151 -5.208354 -8.334948 10.78881 -4.720036 -8.325232 10.74521 -4.748785 -8.567212 11.11825 -4.6156 -8.350762 10.77074 -4.098651 -8.452215 10.87219 -3.571331 -8.514329 10.9343 -6.534756 -8.006139 11.0077 -6.422164 -8.046298 10.8064 -5.911201 -8.269398 11.01069 -5.373402 -8.459156 11.18414 -4.261643 -8.730285 11.63274 -4.413202 -8.704799 11.61118 -5.112824 -8.547124 11.47631 -5.437254 -8.450909 11.39338 -6.280738 -8.126557 11.11236 -6.511402 -8.01768 11.01773 -2.17205e-5 2.00001 34.91994 0.3378735 1.999481 34.91412 1.091697 2 34.86021 1.310069 1.99182 34.83379 1.479404 2 34.80994 1.479413 1.989527 34.80992 2.261628 1.975331 34.66074 2.433008 2 34.61948 3.183818 1.950937 34.39958 3.406322 2 34.32193 3.406348 1.943696 34.32192 4.048466 1.91962 34.06375 4.607707 2 33.79516 4.927083 1.878642 33.62186 5.19865 2 33.46245 5.19868 1.863879 33.46242 5.572008 2 33.22374 5.735637 1.831469 33.11156 6.438046 2 32.57186 6.475824 1.779177 32.53986 7.797581 1.656828 31.18075 7.797611 2 31.18073 7.155231 1.721859 31.90586 7.199889 2 31.85981 6.785571 2 32.26543 -5.522164 1.844729 33.25699 -5.198719 1.863726 33.46242 -5.198687 2 33.46245 -1.144362 2 34.85428 -0.9806863 1.995507 34.87175 -1.954542 1.981722 34.72701 -3.406358 2 34.32193 -2.905493 1.959385 34.48852 -2.322046 2 34.64665 -1.479441 2 34.80994 -4.510229 2 33.84511 -4.705033 1.889841 33.74389 -3.846803 1.927776 34.15044 -3.406394 1.94383 34.32192 -6.330498 1.790086 32.66104 -6.359302 2 32.63745 -6.785634 1.754243 32.26539 -6.785606 2 32.26543 -7.083637 1.728368 31.97848 -7.13129 2 31.93032 -7.70561 1.666911 31.29364 -6.877346 -3.194216 29.38893 -7.150277 -3.263176 28.71989 -6.81631 -3.269918 29.36431 -7.083803 -2.97816 29.38412 -7.012401 -3.046917 29.39892 -7.156011 -2.914408 29.35643 -6.943125 -3.119412 29.40054 -7.36389 -2.764672 29.20231 -7.297445 -2.806602 29.26463 -7.42578 -2.731842 29.13055 -7.227703 -2.856837 29.31634 -7.5544 -2.693152 28.9164 -7.509111 -2.700562 29.00548 -7.591505 -2.69619 28.82335 -7.469376 -2.713241 29.07004 -7.572875 0.6759643 31.34976 -7.632837 0.8962656 31.31942 -7.648231 0.2430316 31.15149 -7.638504 -2.733228 28.63243 -7.722838 -2.658569 28.55742 -7.619729 -2.709633 28.72807 -3.008065 -5.027839 29.71681 -3.652929 -4.683132 30.11174 -3.332398 -5.092888 29.44787 -6.600644 -1.875374 31.19039 -6.321682 -2.144001 31.24819 -6.454369 -1.847523 31.3508 -6.29345 -2.097362 31.3106 -6.436793 -3.230548 29.98179 -6.327087 -3.380107 29.90783 -5.394058 -3.244716 30.99721 -5.340269 -3.308763 30.96783 -5.332416 -3.310965 30.97132 -2.354365 -5.289077 29.28506 -2.796555 -5.337832 29.05536 -1.949515 -5.408039 29.00242 -4.449693 -4.927847 29.0619 -3.637283 -5.176255 29.07533 -3.353329 -5.241329 29.0723 -5.951442 -4.19221 28.93905 -5.224036 -4.597813 29.01603 -4.72482 -4.713399 29.30765 -4.739261 -4.815708 29.04875 -6.623913 -3.717874 28.83267 -6.603669 -3.704578 28.90222 -6.013502 -4.095801 29.06192 -8.451062 -1.555357 28.3982 -8.633193 -1.305163 28.15947 -8.218847 -2.002728 28.36966 -9.0206 -0.2574171 28.09246 -8.962262 -0.5753174 27.92988 -9.325829 1.112076 27.72664 -9.355916 0.9428762 27.42537 -9.203601 0.1772285 27.68408 -9.204051 1.265125 28.34701 -9.020977 1.352325 28.96507 -8.780302 1.372031 29.56857 -7.946017 1.12107 30.95766 -8.228796 1.241722 30.56519 -8.486536 1.323967 30.14643 -7.999587 0.4294109 30.74412 -7.042795 -0.8525317 31.38515 -7.02826 -0.7863298 31.43348 -7.378572 -0.6106734 31.13618 -7.046717 -0.746379 31.43407 -7.16517 -0.4781825 31.43362 -7.375931 0.06180053 31.41045 -7.698473 -0.4088028 30.83613 -6.88275 -1.626304 31.08221 -6.774306 -1.294423 31.41061 -7.162839 -1.401381 30.92557 -6.959513 -0.931214 31.42991 -6.651542 -1.516558 31.39119 -8.24708 0.5350082 30.40062 -8.472661 0.6069912 30.03411 -8.729771 0.6490578 29.52836 -8.940417 0.6318106 29.00016 -9.100648 0.5554913 28.45922 -9.20723 0.4215397 27.91626 -8.930212 -0.1438181 28.55292 -8.794324 -0.07909464 29.01167 -8.615685 -0.06446796 29.45961 -8.39764 -0.100143 29.88853 -8.206335 -0.1611889 30.19935 -7.996445 -0.2507418 30.49066 -8.767786 -0.9184575 28.25362 -8.694438 -0.8262742 28.62727 -8.58417 -0.7737524 28.99954 -8.439208 -0.7618831 29.36304 -8.262269 -0.7908328 29.71109 -8.107028 -0.8403702 29.96332 -7.936706 -0.9130406 30.19971 -7.694908 -1.041304 30.48005 -7.435315 -1.205118 30.72354 -5.452261 -3.180903 31.02121 -5.979846 -2.540524 31.21667 -6.558295 -3.079853 30.03079 -6.060556 -2.43149 31.24263 -6.689237 -2.930945 30.0539 -6.596156 -2.484699 30.66901 -6.82714 -2.786635 30.05068 -6.807695 -2.280996 30.62518 -6.969277 -2.649763 30.02123 -7.021619 -2.092124 30.54315 -7.113016 -2.522856 29.96611 -7.234013 -1.921563 30.42436 -7.255728 -2.408253 29.88629 -7.440635 -1.772734 30.27116 -7.394561 -2.308252 29.78335 -7.637486 -1.648513 30.08652 -7.526829 -2.224786 29.65929 -7.820844 -1.551249 29.87394 -7.65003 -2.159432 29.51645 -7.949999 -1.496143 29.69468 -7.736813 -2.122405 29.396 -8.067722 -1.458578 29.50341 -7.815911 -2.097165 29.26749 -8.201896 -1.436625 29.23948 -7.906066 -2.082414 29.09015 -8.311821 -1.445626 28.96384 -7.979928 -2.088462 28.90494 -8.395442 -1.485453 28.68154 -8.036113 -2.115223 28.71526 -8.073486 -2.162193 28.52487 -6.761199 -3.345049 29.32716 -4.883226 -3.75529 30.76896 -5.061544 -3.586657 30.85205 -5.00537 -3.84761 30.56089 -5.158531 -3.584283 30.78419 -6.156449 -3.654662 29.70048 -6.234488 -3.520491 29.81426 -6.675478 -3.482972 29.223 -6.714682 -3.415571 29.28015 -4.280731 -4.257673 30.4642 -4.789827 -4.33524 29.98893 -4.879555 -4.102948 30.29153 -6.046625 -3.90312 29.40905 -6.092343 -3.784762 29.56324 -6.620309 -3.607785 29.0766 -6.643275 -3.548328 29.15405 -4.73792 -4.54003 29.65886 -6.020177 -4.007465 29.24088 -6.607023 -3.660203 28.99211 3.033206 -8.535478 10.95545 6.352292 -7.681999 10.10197 6.052434 -7.837882 10.25786 5.309673 -8.147952 10.56792 5.119142 -8.211534 10.63151 3.571299 -8.514328 10.9343 4.197907 -8.435892 10.85587 7.469511 -7.459518 10.48222 7.468824 -7.458564 10.53069 7.45825 -7.467149 10.50655 7.447158 -7.475156 10.48222 7.360106 -7.512365 10.31689 7.436246 -7.413323 10.14963 7.199819 -7.509562 10.0838 7.347906 -7.290649 9.87157 7.193936 -7.340364 9.830054 7.308252 -7.235582 9.792465 7.200547 -7.086017 9.640382 7.054175 -7.458154 9.920858 7.130909 -6.989313 9.574954 7.105982 -6.954698 9.556375 10.39322 -1.379314 9.895267 10.3039 -1.379311 9.788567 10.3039 2 9.788563 9.896734 -1.379302 9.532511 9.583589 -1.379296 9.482217 9.58557 2 9.482217 9.970494 2 9.560095 9.961281 -1.379303 9.556286 10.17496 -1.379308 9.675816 10.53297 -1.37932 10.16809 10.51964 2 10.13035 10.58319 -1.379326 10.45395 10.58247 2 10.52961 10.58247 -1.379327 10.52961 9.417444 1.656942 27.17664 9.417463 2 27.17663 9.291403 1.65692 28.01645 9.350972 2 27.69619 9.071129 1.656898 28.83693 9.165468 2 28.52923 8.759478 1.656876 29.62725 7.888356 2 31.06541 7.906359 1.656833 31.04197 8.239066 2 30.5705 8.360447 1.656854 30.37725 8.556951 2 30.03342 8.556951 1.656864 30.03342 8.674301 2 29.80564 8.91058 2 29.27655 -2.879983 -8.586277 14.92127 -2.865007 -8.555844 15.21253 -3.520568 -8.54368 15.06146 -2.651017 -8.020078 19.04886 -2.598519 -7.864452 19.91258 -3.200177 -7.853817 19.84025 -2.389026 -7.169461 23.1273 -2.294083 -6.820556 24.48295 -2.824102 -6.784357 24.54407 -2.737164 -8.25639 17.57065 -2.981564 -8.761816 12.84519 -3.658508 -8.744564 12.65362 -4.351964 -8.647517 12.68414 -5.053599 -8.480452 12.71066 -5.753179 -8.240033 12.73243 -6.439465 -7.924884 12.74875 -7.100693 -7.535929 12.75907 -7.725162 -7.076535 12.76299 -8.30187 -6.552497 12.76028 -8.82113 -5.971824 12.75094 -9.275117 -5.344333 12.73519 -9.65824 -4.681107 12.71343 -9.96735 -3.993871 12.68622 -10.20174 -3.294353 12.65429 -10.36297 -2.593711 12.61842 -10.45454 -1.902061 12.57944 -9.551722 0.4343613 25.41033 -9.444695 -0.2270982 25.60858 -9.267971 -0.8971564 25.80344 -5.409749 -5.325562 26.85644 -6.078209 -4.953586 26.79805 -6.711595 -4.514244 26.71546 -7.298798 -4.013081 26.60943 -7.829977 -3.457754 26.48152 -8.297101 -2.857653 26.33396 -8.694337 -2.223378 26.16958 -9.018284 -1.56614 25.99159 -4.014611 -5.85688 26.9014 -4.717964 -5.626953 26.89064 -2.127617 -6.164845 26.73724 -2.616876 -6.109461 26.85866 -3.310871 -6.01665 26.89011 -10.05371 -1.112473 19.06902 -10.19921 -1.460651 16.91775 -9.955695 -1.793899 19.18876 -10.10364 -2.146582 17.01076 -9.788007 -2.484182 19.30525 -9.938411 -2.841429 17.10057 -9.547247 -3.173358 19.41641 -9.700074 -3.535161 17.1855 -9.231965 -3.850435 19.52008 -9.387139 -4.216714 17.26386 -8.842974 -4.503856 19.61417 -9.000383 -4.874455 17.33402 -8.383535 -5.12207 19.69677 -8.543021 -5.496756 17.3945 -7.859333 -5.694159 19.76625 -8.020704 -6.072628 17.44408 -7.278282 -6.210449 19.82137 -7.441311 -6.592331 17.48186 -6.650132 -6.663053 19.86134 -6.814569 -7.047926 17.50731 -5.985927 -7.046257 19.88589 -6.151507 -7.433664 17.52032 -5.297391 -7.356745 19.89521 -5.463837 -7.746205 17.52116 -4.596282 -7.593612 19.88998 -4.76332 -7.984638 17.51046 -3.893813 -7.758205 19.87121 -4.061182 -8.150321 17.48914 -3.367626 -8.246563 17.45832 -10.33296 -1.724017 14.75337 -10.23954 -2.413358 14.81945 -10.07647 -3.111661 14.88237 -9.840253 -3.808844 14.94088 -9.529378 -4.493786 14.99374 -9.144581 -5.154798 15.03977 -8.689041 -5.780195 15.07796 -8.168373 -6.358931 15.10748 -7.59043 -6.881219 15.12777 -6.964918 -7.33908 15.13859 -6.302848 -7.726737 15.13997 -5.61593 -8.040832 15.13225 -4.915924 -8.280451 15.11604 -4.214063 -8.446956 15.09213 -9.729388 -0.1641849 23.3186 -9.896914 -0.6800696 21.20373 -9.625628 -0.8333621 23.491 -9.796164 -1.355906 21.34995 -9.452182 -1.511238 23.66006 -9.625736 -2.040529 21.49287 -9.205737 -2.188027 23.82287 -9.382268 -2.724053 21.63 -8.884933 -2.852933 23.97639 -9.064358 -3.395576 21.75873 -8.490691 -3.494609 24.11763 -8.672869 -4.043638 21.87653 -8.026359 -4.101711 24.2438 -8.211104 -4.656782 21.98104 -7.497715 -4.663517 24.35248 -7.684788 -5.224179 22.07024 -6.91275 -5.170528 24.44176 -7.101877 -5.736236 22.14253 -6.281269 -5.614995 24.51032 -6.472144 -6.185126 22.19688 -5.61436 -5.991312 24.55757 -5.806656 -6.565188 22.23285 -4.923761 -6.296219 24.58359 -5.117141 -6.87313 22.25057 -4.22123 -6.528829 24.58909 -4.415359 -7.108055 22.25073 -3.517959 -6.690464 24.57535 -3.712513 -7.271297 22.23449 -3.018776 -7.366126 22.20337 -2.451235 -7.387192 22.20736 3.033205 -8.827214 11.71067 3.033206 -8.828372 11.66256 3.033207 -8.76209 11.30455 2.31846 -3.611168 32.10023 2.575486 -3.15852 32.4992 1.85084 -3.043654 32.78527 1.794118 -1.012842 34.12355 1.688295 -1.582341 33.86145 2.294321 -1.649486 33.69707 7.043745 -0.752737 31.43402 7.165125 -0.4781855 31.43365 6.738008 -0.2871063 31.93244 0.4985891 -4.580484 31.00749 -4.01732e-5 -4.699768 30.7909 -3.67423e-5 -5.016016 30.07055 0.5922886 -4.243161 31.55832 -4.27969e-5 -4.260136 31.55042 0.8607771 -2.951064 33.01391 -4.42571e-5 -3.142212 32.87957 0.774465 -3.423855 32.56763 -4.41457e-5 -3.737757 32.24987 1.018233 -1.915632 33.76278 -4.1009e-5 -1.769364 33.90387 -4.31885e-5 -2.482814 33.43276 1.297613 0.8387494 34.74554 0.625415 0.8672999 34.81442 -2.29287e-5 1.418356 34.89725 2.788079 0.7013851 34.41259 2.051999 0.7822508 34.60893 2.948326 1.916167 34.47528 4.098738 1.737325 34.03895 4.831561 1.586928 33.66861 7.365623 0.03317159 31.41243 7.572845 0.6759563 31.34978 7.121938 0.8766542 31.87271 7.618001 0.8399161 31.32762 5.521491 1.415657 33.24284 6.590648 1.081631 32.39942 6.212536 -1.416263 31.84749 6.656497 -1.507726 31.39213 5.899229 -1.956638 31.74906 6.208847 -2.222107 31.28728 5.555028 -2.473695 31.61339 5.708537 -2.884302 31.12158 3.474998 -3.366116 31.9751 3.742851 -3.995411 31.11555 4.153999 -3.582976 31.4172 4.566946 -4.031285 30.61348 5.158396 -3.490745 30.89584 2.428715 -4.957456 30.02217 1.619667 -5.2684 29.39012 2.623418 -5.19199 29.46651 1.94948 -5.40804 29.00241 1.240757 -5.156824 29.69404 2.025967 -4.826733 30.36922 2.400837 -4.533337 30.81574 2.024133 -2.551863 33.16144 1.489273 -2.492377 33.30792 1.361625 -2.989115 32.92017 0.9415468 -2.45086 33.40973 2.054818 -4.016922 31.66917 1.665656 -3.507411 32.3601 1.475705 -3.92461 31.90204 0.6859313 -3.850357 32.08782 1.073759 -4.634933 30.86803 1.274793 -4.307533 31.39564 1.496938 -4.702882 30.69268 1.775963 -4.387691 31.19147 3.291272 -4.887399 29.8942 3.941898 -4.498836 30.27816 2.875053 -4.686484 30.41376 3.32112 -4.359729 30.78482 2.77548 -4.184265 31.24145 3.129683 -3.798938 31.62358 2.437985 -1.084027 33.94974 3.191014 -1.790719 33.34892 3.390412 -1.233704 33.58172 3.762922 -1.909678 33.05299 3.997668 -1.359726 33.26903 4.301961 -2.045355 32.71234 4.569853 -1.503403 32.90919 5.138619 -2.31057 32.03631 5.457584 -1.784094 32.19541 2.816007 -2.677077 32.85099 3.038278 -3.255424 32.25573 3.321437 -2.782637 32.58692 3.798139 -2.903136 32.28272 4.538745 -3.138979 31.67842 1.067478 -1.535457 33.97574 1.134438 -0.963128 34.24442 1.195388 -0.3728415 34.46282 0.3830698 -5.028531 30.03739 0.821636 -5.07551 29.9124 -2.67607e-5 0.8758923 34.83512 -2.86549e-5 0.5923631 34.78657 1.890444 -0.4251126 34.33601 2.568755 -0.4999462 34.1537 3.876324 0.5314713 33.9971 3.571913 -0.6572522 33.76777 4.569719 0.3885315 33.64433 4.211345 -0.7896532 33.43994 5.222677 0.225699 33.23865 4.813701 -0.940554 33.0628 6.234866 -0.0920313 32.4347 5.74792 -1.235217 32.31496 -3.36474e-5 -0.2212834 34.58338 -3.77986e-5 -1.012043 34.28848 1.610467 -1.960424 33.65335 2.188663 -2.024583 33.49596 3.044367 -2.159569 33.16249 3.590279 -2.273305 32.87898 4.104941 -2.403066 32.55253 4.904038 -2.656831 31.90445 -1.777025 -1.976788 33.61328 -1.19333 -1.926719 33.73573 -1.251031 -1.547055 33.94749 -0.5541928 -2.432993 33.45346 -0.5066367 -2.934691 33.05416 -0.8039745 -3.857902 32.06901 -0.694254 -4.249697 31.54186 -0.5844669 -4.586008 30.99338 -0.4432862 -5.033125 30.0252 -1.876936 -5.372792 29.10108 -2.617072 -5.032772 29.81945 -3.096342 -4.774475 30.17942 -3.575321 -4.460332 30.51902 -4.02817 -4.107887 30.82014 -4.469653 -3.706971 31.09309 -4.882788 -3.273698 31.3276 -5.275032 -2.801674 31.52844 -5.526926 -2.461873 31.64422 -5.869424 -1.944136 31.78159 -6.181183 -1.403147 31.88155 -6.704056 -0.2729778 31.96903 -7.086087 0.8914972 31.91108 -5.292947 1.475862 33.39299 -4.61265 1.635079 33.78751 -3.902508 1.772598 34.12533 -0.7638393 0.8630836 34.80423 -1.103478 -2.461136 33.38456 -1.00884 -2.960481 32.99074 -0.907709 -3.432349 32.54661 -5.093879 -2.294404 32.0779 -5.410122 -1.76699 32.23931 -1.554052 -5.245959 29.45165 -2.179455 -4.872264 30.24901 -2.581717 -4.586743 30.67639 -2.983734 -4.245508 31.08305 -3.363819 -3.867559 31.44726 -3.734366 -3.441896 31.7814 -4.081119 -2.985583 32.07284 -4.410338 -2.491808 32.32739 -4.621757 -2.138113 32.47746 -3.934381 -2.357429 32.66771 -3.592025 -1.871573 33.14805 -4.12334 -1.997637 32.83253 -4.380266 -1.452877 33.03613 -4.909224 -1.601597 32.66114 -5.170889 -1.043656 32.80287 -5.69798 -1.217267 32.36095 -5.609748 0.1144917 32.95915 -6.180771 -0.07268464 32.48413 -5.930395 1.298722 32.94958 -6.533516 1.101963 32.45126 -1.231317 -5.154537 29.70021 -1.687239 -4.742026 30.591 -2.000968 -4.433786 31.07323 -2.314507 -4.069936 31.53446 -2.610941 -3.670698 31.95002 -2.899935 -3.224374 32.33396 -3.170373 -2.74882 32.67176 -3.427136 -2.236876 32.97005 -2.898311 -2.132929 33.22855 -3.037981 -1.762843 33.41788 -3.816224 -1.319364 33.36946 -4.614131 -0.8874942 33.19583 -5.006366 0.2829445 33.38172 -0.8235594 -5.075955 29.91121 -1.151156 -4.64549 30.84088 -1.366524 -4.319999 31.364 -1.581761 -3.938976 31.86593 -1.785255 -3.523567 32.31978 -1.983643 -3.061546 32.74087 -2.169291 -2.571373 33.11325 -1.862878 -1.599461 33.8196 -1.979611 -1.030994 34.07929 -2.612652 -1.107356 33.89259 -2.752745 -0.5244686 34.09376 -3.400754 -0.6262144 33.8442 -2.987706 0.6748908 34.34804 -3.690678 0.5649891 34.07936 -3.159378 1.888275 34.40748 -4.362573 0.4343 33.7576 -4.0203 -0.7472522 33.54522 -3.22789 -1.204167 33.65462 -2.458745 -1.671495 33.64302 -2.345552 -2.045621 33.44418 -0.6677647 -0.9417198 34.29635 -0.7036513 -0.3503307 34.51731 -1.400903 -0.3857747 34.43147 -1.520678 0.8247688 34.71176 -0.6283397 -1.515269 34.02484 -1.329488 -0.9754278 34.21454 -2.085868 -0.4441968 34.28959 -2.264078 0.7616257 34.55893 -0.5993441 -1.896353 33.80979 6.701805 -7.920675 10.93335 3.616448 -8.739423 11.2823 4.188104 -8.674197 11.22043 4.748752 -8.567212 11.11825 4.857251 -8.612473 11.53242 3.653756 -8.802501 11.69272 3.711912 -8.797657 11.68881 4.317331 -8.721266 11.62512 5.208321 -8.334947 10.78881 6.182938 -7.95259 10.41036 5.815441 -8.238402 10.80311 5.295281 -8.420115 10.97738 5.911168 -8.269398 11.01069 5.373368 -8.459156 11.18414 6.309806 -8.024703 10.59801 6.42213 -8.046298 10.8064 6.511368 -8.01768 11.01773 5.546541 -8.415043 11.3624 7.734836 -6.443743 9.556555 10.47504 -2.259052 10.15073 10.25766 -2.233168 9.793003 9.913732 -2.19221 9.556497 7.479135 -6.164861 9.482217 7.968976 -6.699109 9.793259 8.116877 -6.860417 10.15126 8.154095 -6.901007 10.53289 10.10802 -3.070281 9.793702 9.77104 -2.989098 9.556655 9.858592 -3.89012 9.79412 9.533452 -3.76951 9.556752 9.514845 -4.671916 9.794277 9.206175 -4.513711 9.556786 9.082774 -5.404781 9.794178 8.794898 -5.211371 9.556763 8.562621 -6.086975 9.793834 8.29983 -5.860861 9.556687 10.32068 -3.121512 10.15216 10.06358 -3.966161 10.15301 9.709385 -4.771625 10.15333 9.264245 -5.526704 10.15313 8.728404 -6.229623 10.15243 8.769776 -6.265221 10.53447 9.309305 -5.556976 10.53542 9.757618 -4.796346 10.53569 10.11453 -3.985058 10.53526 10.37385 -3.134321 10.53411 10.52994 -2.265587 10.53217 9.538176 -2.147484 9.482217 8.012791 -5.613881 9.482217 8.480422 -5.00009 9.482217 8.868971 -4.340883 9.482217 9.178275 -3.637757 9.482217 9.402975 -2.900427 9.482217 10.46714 -1.274046 12.81188 10.3585 2 14.74413 10.33815 -1.073791 15.08719 10.09342 2 18.85967 10.04066 -0.3897973 19.60281 10.19586 -0.7789396 17.35185 9.504094 1.335335 26.22749 9.694085 0.6682382 24.04456 9.873218 0.09276801 21.8346 6.832487 -3.44487 29.0105 6.329647 -3.230569 30.11504 6.168084 -3.385858 30.09393 7.258982 -0.9794403 31.0795 6.545813 -1.980984 31.1637 6.637461 -2.085725 30.9868 5.05743 -3.790372 30.59823 5.227555 -3.799712 30.45115 5.799547 -3.635146 30.14857 5.989384 -3.522244 30.10523 5.60495 -3.720773 30.22248 6.580412 -2.884602 30.25059 6.661193 -2.705542 30.36047 6.468645 -3.061592 30.16785 6.72008 -2.365138 30.64614 6.696208 -2.215226 30.81233 6.708277 -2.530428 30.49382 8.087665 -2.191415 28.42472 8.09914 -2.1754 28.42008 8.162555 -2.002663 28.54773 8.547284 -1.465227 28.20853 8.909737 -0.7078565 27.97223 9.179707 0.08755898 27.71381 9.260931 0.6161456 27.79214 9.351037 0.9088993 27.43702 9.154099 1.287025 28.53586 7.019319 -0.8285792 31.42158 6.424025 -2.04039 31.23466 8.239849 1.208231 30.54458 7.786231 1.49377 31.19204 7.477406 0.3144723 31.37279 8.582096 0.8170927 29.88398 8.890625 -0.2263355 28.61183 8.801475 0.3334899 29.23244 5.402661 -4.412044 29.22247 5.023245 -4.692456 29.0321 5.764722 -4.30577 28.96299 4.658059 -4.567789 29.67364 4.322405 -4.549361 29.96383 3.523306 -5.140777 29.23551 5.022221 -4.521498 29.42372 4.248293 -4.997992 29.0692 3.450041 -5.220131 29.07443 2.63867 -5.357726 29.04831 4.026531 -4.466834 30.28456 3.089509 -5.019779 29.70574 2.121703 -5.39245 29.03996 4.907469 -3.748543 30.76079 7.439804 -1.186094 30.73048 7.555712 -1.4416 30.38625 7.602812 -1.737377 30.05835 7.579524 -2.063493 29.75782 7.486629 -2.408994 29.49473 7.327247 -2.762277 29.27793 7.106731 -3.111479 29.11469 5.786602 -4.243102 29.07665 6.161149 -4.020345 28.99115 6.513724 -3.751256 28.96885 5.412127 -3.776249 30.32448 8.298753 -1.496104 28.93346 8.332899 -1.017968 29.37409 8.263841 -0.5843121 29.85483 8.093902 -0.2097003 30.35954 7.828789 0.09328627 30.87125 7.106468 -3.304287 28.7304 6.462685 -3.841286 28.86212 8.846546 -0.8435826 28.04299 7.63262 -2.763062 28.58627 2.128038 -6.166448 26.73203 2.295957 -6.827367 24.4577 2.454283 -7.397593 22.16174 2.602545 -7.876778 19.84673 2.650992 -8.020076 19.04885 2.740246 -8.264365 17.51617 2.866998 -8.559924 15.17413 2.982563 -8.763282 12.8233 3.370429 -8.252662 17.41597 7.838282 -3.486123 26.38955 8.305286 -2.885713 26.24287 8.702394 -2.251112 26.07944 9.026206 -1.593536 25.90246 9.275753 -0.9242088 25.71534 9.452339 -0.2538064 25.52154 9.559225 0.4079931 25.32436 10.45519 -1.902856 12.56658 10.36363 -2.594517 12.6054 10.20241 -3.295169 12.64111 9.968028 -3.994698 12.67289 9.658926 -4.681944 12.69994 9.275814 -5.34518 12.72156 8.821834 -5.972681 12.73718 8.30258 -6.553363 12.74639 6.440192 -7.92577 12.7346 7.101417 -7.53681 12.74499 7.72588 -7.077409 12.749 5.75391 -8.240922 12.71823 5.054332 -8.481348 12.69643 4.352699 -8.648414 12.6699 3.659242 -8.745463 12.63937 2.625646 -6.139193 26.76354 3.319635 -6.046334 26.79498 7.307211 -4.041735 26.51667 6.720104 -4.543156 26.62201 6.0868 -4.982723 26.70403 5.418406 -5.354891 26.76196 4.726673 -5.656436 26.79582 4.023355 -5.886482 26.80637 10.05724 -1.121671 19.01837 9.901665 -0.694037 21.14096 9.959289 -1.803216 19.13749 9.801001 -1.370054 21.2864 9.791666 -2.49362 19.25335 9.630659 -2.054859 21.42855 9.550966 -3.182916 19.36389 9.387274 -2.738566 21.56491 9.23574 -3.860111 19.46696 9.069446 -3.410269 21.6929 8.846807 -4.513646 19.56049 8.678033 -4.058504 21.81001 8.387419 -5.131969 19.64257 8.216341 -4.671813 21.91388 7.863265 -5.704157 19.71159 7.690091 -5.239361 22.00249 7.282255 -6.220539 19.7663 7.107237 -5.751554 22.07428 6.65414 -6.673221 19.80593 6.477554 -6.200565 22.12821 5.989964 -7.056492 19.8302 5.812105 -6.580729 22.16384 5.30145 -7.367034 19.83933 5.122621 -6.888753 22.18131 4.600356 -7.603943 19.83396 4.420859 -7.12374 22.18132 3.897896 -7.768565 19.81513 3.718025 -7.287026 22.16501 3.204261 -7.864194 19.78417 3.024292 -7.38188 22.13389 9.735466 -0.1838827 23.24403 9.631817 -0.8533141 23.41551 9.458483 -1.531448 23.58365 9.212147 -2.208494 23.74555 8.891451 -2.873653 23.8982 8.49731 -3.515573 24.03861 8.033075 -4.122906 24.16403 7.504517 -4.684925 24.27202 6.919627 -5.192129 24.36069 6.288211 -5.636765 24.42876 5.621355 -6.013225 24.47561 4.930796 -6.318248 24.50134 4.228291 -6.550946 24.50665 3.525037 -6.712642 24.49282 2.831185 -6.806571 24.46154 10.33443 -1.726617 14.72774 10.20165 -1.466055 16.8795 10.24104 -2.415992 14.7935 10.10612 -2.152056 16.97204 10.07799 -3.11433 14.8561 9.940932 -2.846974 17.06137 9.841797 -3.811547 14.9143 9.702632 -3.540777 17.14584 9.530945 -4.496523 14.96686 9.389739 -4.2224 17.22375 9.146169 -5.157567 15.0126 9.00302 -4.880208 17.29348 8.690649 -5.782994 15.05052 8.545693 -5.502573 17.35357 8.169999 -6.361758 15.0798 8.023406 -6.078503 17.40279 7.592072 -6.884073 15.09989 7.444041 -6.59826 17.44026 6.966573 -7.341956 15.11054 6.817323 -7.053902 17.46546 6.304514 -7.729632 15.11178 6.154279 -7.43968 17.47826 5.617604 -8.043745 15.10396 5.466623 -7.752252 17.47895 4.917603 -8.283373 15.08768 4.766117 -7.990709 17.46815 4.215746 -8.449889 15.06374 4.063982 -8.156409 17.44678 3.522251 -8.546614 15.03308 5.757081 4.996703 9.484722 5.05 4.996703 9.484722 5.757081 5 9.482215 5.05 5 9.482215 -5.05 4.996703 9.484722 -5.757081 4.996703 9.484722 -5.05 5 9.482215 -5.757081 5 9.482215 5.790845 4.996703 9.484482 5.832741 4.998423 9.482215 5.866478 4.996703 9.482215 5.05 4.996703 9.482215 -5.05 4.996703 9.482215 -5.866478 4.996703 9.482215 -5.832738 4.996703 9.483524 -5.79086 4.999686 9.482215 7.594199 5 30.05288 7.552701 5 30.12014 7.759685 5 30.15811 -7.436732 5 30.23098 -7.502311 5 30.17766 -7.50908 5 30.52744 8.554405 5 27.17295 8.475067 5 27.75125 8.647227 5 28.03084 -7.788485 5 30.11217 8.431587 5 28.77236 7.309093 4.999996 30.78908 -2.784347 5 33.62012 -4.504587 5 32.85228 -4.227823 5 33.28627 8.296163 5 28.48977 8.262027 5 28.59874 8.133687 5 29.48594 7.989101 5 29.30403 7.637675 5 29.97366 6.027138 5 31.74284 4.504655 5 32.85226 5.223129 5 32.70381 2.784419 5 33.6201 0.9419474 5 34.01264 1.180176 5 34.21924 2.280669 5 34.01216 3.333402 5 33.68112 4.319203 5 33.23945 -6.684765 5 31.49137 -5.961116 5 32.15422 -6.027075 5 31.74286 9.917362 5 10.21532 9.895788 5 10.15222 9.699384 5 10.92619 9.778831 5 9.935212 9.747915 5 9.894317 7.436748 5 30.23098 7.433394 5 30.23325 7.400554 5 30.25667 -5.140137 5 32.75887 8.778082 5 27.27201 8.794012 5 27.1187 9.17376 5 19.65027 9.468813 5 18.81595 9.955863 5.000023 10.52572 6.034943 5 32.09275 6.749085 5 31.42529 7.19431 5 30.46373 7.28157 5 30.36141 -3.234869 5 33.71798 -2.176653 5 34.03762 -0.9418745 5 34.01264 -1.07271 5 34.23225 0.05432242 5 34.29368 -7.594205 5 30.05287 -7.637675 5 29.97366 -8.040836 5 29.6702 -7.950747 5 29.38697 -8.300075 5 29.11556 -8.234623 5 28.68177 -8.521121 5 28.50075 -8.237755 5 28.67247 -8.542021 5 28.43129 -9.940589 5 10.3094 -9.949415 5 10.36442 -9.699385 5 10.92618 -7.309387 5 30.78872 -7.194266 5 30.46374 -7.276107 5 30.36706 -9.955893 5.000027 10.52572 -9.671788 5 15.73145 -9.17376 5 19.65026 -9.240181 5 21.89865 -8.554405 5 27.17295 -8.794002 5 27.11882 -8.441944 5 27.92042 -8.716379 5 27.69268 -8.393306 5 28.13497 -8.375681 5 28.20546 -9.747918 5 9.894268 -9.845592 5 10.04231 -9.894966 5 10.14996 6.952164 4.245617 31.62104 7.540059 4.200797 30.97416 7.0929 3.485616 31.75669 7.679929 3.492695 31.08763 7.174028 2.733253 31.83489 7.771409 2.703705 31.16052 6.41492 2.733253 32.54437 5.551993 2.733253 33.19391 4.591154 2.733253 33.76327 3.543283 2.733253 34.23275 2.424267 2.733253 34.58463 -1.14025 2.733253 34.81858 0.05774271 2.733253 34.88388 1.254484 2.733253 34.80475 6.216533 4.245617 32.30858 5.380291 4.245617 32.93803 4.449167 4.245617 33.48978 3.433704 4.245617 33.94474 2.349294 4.245617 34.28574 1.215687 4.245617 34.49906 0.0559569 4.245617 34.57573 -1.104987 4.245617 34.51246 -2.242148 4.245617 34.31197 -3.332205 4.245617 33.98271 -4.355038 4.245617 33.538 -5.294803 4.245617 32.99474 -6.140485 4.245617 32.3719 6.342377 3.485616 32.45815 5.489208 3.485616 33.10034 4.539234 3.485616 33.66327 3.503214 3.485616 34.12744 2.396852 3.485616 34.47534 1.240297 3.485616 34.69298 0.05708968 3.485616 34.7712 -1.127356 3.485616 34.70664 -2.287537 3.485616 34.5021 -3.399661 3.485616 34.16617 -4.443199 3.485616 33.71246 -5.401988 3.485616 33.1582 -6.26479 3.485616 32.52276 -2.313701 2.733253 34.61169 -3.438546 2.733253 34.27193 -4.49402 2.733253 33.81303 -5.463776 2.733253 33.25243 -6.336446 2.733253 32.60971 -7.105658 2.733253 31.90512 -7.025303 3.485616 31.82613 -6.885908 4.245617 31.6891 -7.749413 2.961034 31.14202 -7.681744 3.485616 31.08769 -7.583085 4.012786 31.00848 -9.008378 4.415502 27.25086 -8.623744 4.828749 28.40906 -8.558773 4.52824 28.96997 -8.403203 4.290703 29.54314 -8.161716 4.123295 30.11129 -7.841588 4.031057 30.65733 -9.087821 4.203699 27.14605 -9.29018 3.378822 27.16481 -9.316345 3.080902 27.3851 -9.39835 2.536253 27.17485 -9.221487 2.642161 28.20402 -8.641785 2.050946 29.87035 -8.994355 2.295361 29.04084 -9.042659 3.975044 27.91168 -8.961918 3.601596 28.60874 -8.768588 3.306406 29.32102 -8.468488 3.098365 30.02708 -8.070659 2.98374 30.70565 -10.09566 4.657575 10.52659 -10.36442 3.794658 10.52826 -9.999197 4.093492 15.75163 -10.52823 2.900167 10.52927 -9.567212 4.093492 21.92428 -9.800247 2.980403 21.94254 -10.2325 2.980403 15.766 -9.161569 4.303232 9.482215 -8.849065 5 9.482215 9.161547 4.303157 9.482215 9.394603 3.55509 9.482215 9.536595 2.779814 9.482215 8.849018 5 9.482215 -9.536571 2.780145 9.482215 -9.394565 3.55537 9.482215 10.09564 4.657495 10.52659 10.04462 4.638139 10.15353 9.840523 4.560718 9.794692 9.245085 5 9.546852 9.278842 5 9.558898 9.516253 4.43771 9.556963 9.551599 5 9.705974 9.655819 5 9.793556 8.926917 5 9.484612 10.36445 3.794405 10.52826 10.31196 3.781452 10.15478 10.10018 3.729194 9.795303 9.763239 3.646053 9.557104 10.52825 2.899795 10.52927 10.47489 2.893338 10.15554 10.25842 2.867148 9.795676 9.913743 2.825445 9.557188 -9.526638 5 9.6881 -9.251732 5 9.549117 -9.509901 4.43537 9.554201 -9.837234 4.559543 9.790976 -10.04388 4.637932 10.15122 -10.47406 2.893611 10.15322 -9.170372 5 9.524156 -9.65238 5 9.790235 -9.60809 5 9.750552 -9.906944 2.824972 9.554413 -9.953996 2 9.558612 -10.25488 2.867084 9.79195 -10.52374 2 10.15602 -10.31115 3.781514 10.15246 -10.09671 3.728607 9.791581 -9.756583 3.644689 9.554332 9.739873 4.278199 18.83492 9.935606 3.532323 18.84862 10.05387 2.770234 18.85689 9.398286 2.537157 27.17482 9.290019 3.379702 27.16474 9.087586 4.204388 27.14594 7.738017 3.199301 31.10073 9.304394 2.974366 27.58268 9.158761 3.056716 28.26236 7.49292 4.473202 30.89001 7.927073 4.075831 30.51111 7.993739 4.90986 29.83906 8.309344 4.630016 29.46578 8.583825 4.39662 29.03284 8.810767 4.21513 28.55033 8.984863 4.089792 28.02952 9.10205 4.023526 27.48259 9.172196 2.070817 28.5041 8.930873 2.184998 29.21918 8.599538 2.449973 29.92364 8.198799 2.79073 30.55574 8.942408 3.212476 28.90957 8.660383 3.438018 29.5092 8.319279 3.728064 30.04723 9.911765 5 5.809243 9.281219 5 6.778078 -9.911765 5 5.809243 -9.278203 5 6.782443 2.034731 8.900001 19.9462 2.034731 7.887764 19.9462 2.49777 8.900001 19.96747 2.689377 7.812883 19.98881 3.084287 8.875375 20.05647 3.482128 8.829995 20.15806 3.328908 7.721006 20.11484 3.48165 7.696295 20.15792 3.65364 8.803031 20.21272 3.704549 7.658302 20.23025 3.952094 8.745129 20.32434 4.504903 8.599142 20.59157 4.314069 7.54259 20.48985 4.808104 8.496191 20.7759 4.807131 7.436142 20.77526 5.022738 8.412734 20.92504 4.881688 7.419033 20.82518 5.19709 8.338082 21.05894 5.172589 7.349701 21.03939 5.67179 8.100732 21.49273 5.661937 7.223719 21.48253 5.900462 7.966504 21.74679 5.900049 7.158112 21.7463 6.08845 7.845045 21.98458 6.086176 7.104837 21.98152 6.23056 7.745807 22.18594 6.319882 7.035444 22.32412 6.540252 7.503424 22.71524 7.049653 6.800478 24.402 7.049653 6.967445 24.402 6.948317 6.834787 23.83036 6.949221 7.10133 23.83418 6.858255 6.864819 23.50083 6.78021 7.283542 23.26908 6.669128 6.926487 22.98999 6.668771 7.389961 22.98917 6.629724 6.939099 22.90131 6.324827 7.033945 22.33207 -6.591384 7.459336 22.81918 -6.668967 7.38978 22.98962 -6.66912 6.92649 22.98997 -6.764372 7.299198 23.22617 -7.049653 6.967445 24.402 -7.049653 6.800478 24.402 -6.943249 7.108395 23.8092 -6.934803 6.839321 23.7748 -6.857292 6.865138 23.49773 -6.624532 6.940754 22.88996 -6.316166 7.036569 22.31817 -6.274889 7.713426 22.25329 -6.158389 7.083693 22.08107 -5.900189 7.966672 21.74647 -5.900048 7.158112 21.7463 -5.891183 7.972229 21.73579 -5.742567 7.201821 21.56772 -5.689622 8.090764 21.51133 -5.211322 7.340159 21.07041 -5.242918 8.317397 21.09619 -4.807459 8.496428 20.77548 -4.807126 7.436144 20.77526 -4.671079 7.466675 20.68897 -4.754074 8.51579 20.74088 -4.089976 7.587156 20.38334 -4.186197 8.689623 20.42742 -3.640945 8.805184 20.20844 -3.720977 7.655411 20.23604 -3.482091 8.829999 20.15805 -3.481806 7.696269 20.15797 -3.075376 8.876122 20.05458 -3.092647 7.75712 20.05825 -2.815012 8.892834 20.00684 -2.450377 7.842455 19.96333 -2.49777 8.900001 19.96747 -2.034731 8.900001 19.9462 -2.083067 7.882893 19.94643 -2.034731 7.887764 19.9462 0.812025 7.48167 34.72446 1.620219 7.426873 34.65936 0.6611019 7.487855 20.4462 2.420628 7.336393 34.55168 1.979739 7.390798 20.4462 2.553627 7.31794 20.48459 2.65891 7.302453 34.51121 2.65925 7.302483 20.50012 3.20915 7.211603 34.40272 3.114264 7.228546 20.59815 4.730507 6.867277 21.43115 4.475492 6.934734 21.23816 3.977895 7.054953 20.93603 3.443566 7.167537 20.70213 5.895092 6.50727 32.92352 6.394415 6.325907 32.33312 6.931862 6.111721 30.58539 6.803107 6.164885 31.6728 6.982653 6.090437 31.29218 5.315735 6.697166 33.43423 7.00125 6.082597 29.88433 6.691679 6.20992 27.19901 6.376014 6.332898 24.46083 6.287179 6.36628 23.94579 6.208228 6.3955 23.64888 6.007889 6.467772 23.10873 5.740604 6.560055 22.59584 5.736268 6.561513 22.58868 3.960194 7.05888 34.1817 4.667089 6.884422 33.85635 5.159488 6.7447 21.83041 5.531394 6.629031 22.28 2.63599e-5 7.499949 34.74617 -2.07714e-4 7.5 20.4462 -0.8119659 7.481668 34.72446 -0.6611019 7.487855 20.4462 -1.620146 7.426889 34.65938 -1.979739 7.390798 20.4462 -2.420565 7.3364 34.55169 -2.022112 7.386058 20.44641 -2.34411 7.346713 20.46163 -2.659321 7.302386 34.51113 -2.659909 7.302384 20.50022 -3.209151 7.211609 34.40272 -2.907149 7.263685 20.54716 -3.457968 7.164724 20.70734 -3.781446 7.098314 20.84005 -3.890316 7.074478 34.20734 -4.539033 6.918306 33.92475 -4.290864 6.981089 21.11543 -4.764462 6.857993 21.45911 -5.145971 6.748715 33.55797 -6.376014 6.332898 24.46083 -6.691679 6.20992 27.19901 -6.275332 6.370691 23.89573 -5.230172 6.723394 21.90717 -5.594698 6.608458 22.3697 -5.733011 6.562608 22.58332 -6.003337 6.469382 23.0985 -6.207383 6.39581 23.64609 -6.982442 6.090527 31.29163 -6.920819 6.116339 31.43183 -6.931869 6.111719 30.58502 -6.803375 6.164779 31.67229 -6.609408 6.242643 32.01316 -6.394675 6.325806 32.33277 -6.19296 6.401078 32.59282 -7.00125 6.082597 29.88433 -5.701238 6.573248 33.11148 7.792215 5.142107 29.53572 7.515876 6.499877 27.07679 7.496991 6.521002 27.07504 7.518614 6.363464 27.81862 7.495037 6.253071 28.26558 7.705728 5.981118 28.30332 7.424894 6.136627 28.74558 7.285457 6.045196 29.2293 7.591811 5.902641 28.80416 7.305188 6.052572 29.17667 8.307222 5.134511 28.17957 8.149804 5.567541 27.68398 8.194191 5.61319 27.13959 7.881275 6.033831 27.27363 7.823303 5.657689 28.67348 7.852574 5.373736 29.09057 7.702646 5.48915 29.25154 7.693873 5.358791 29.45289 7.690583 5.325766 29.50288 7.689693 5.317482 29.51535 7.686069 5.857308 28.64814 7.115938 6.861205 24.96144 7.182104 6.749726 25.51988 9.333716 5.94235 5.435857 9.65656 5.456918 5.606717 9.777551 5.25 5.695204 8.686898 6.710738 5.373921 9.002724 6.363401 5.358416 8.307548 7.072832 5.49788 8.627853 6.770734 5.386011 -0.6794659 7.987518 19.9462 0.6794659 7.987518 19.9462 4.885037 8.777506 10.69305 5.11749 8.506149 20.84713 5.297823 8.430488 20.98389 5.425311 8.427044 19.38004 6.687747 7.584551 22.67478 6.936353 7.361698 23.23999 7.330101 7.275433 19.51736 7.468249 6.591223 26.6881 8.133489 6.499877 19.57527 7.111659 7.177024 23.81663 7.216102 7.04133 24.39597 7.283913 6.933654 24.95564 7.351613 6.820669 25.51431 6.420638 7.922616 19.45179 5.78888 8.189931 21.42685 6.220022 7.930788 21.92899 6.367107 7.830209 22.13454 4.366247 8.777506 19.30369 3.266982 8.96621 19.22445 3.113199 8.975044 19.95925 3.701789 8.901721 20.1192 4.010356 8.843036 20.23335 4.581962 8.695075 20.50647 3.78421 8.96621 10.63974 5.945608 8.427044 10.74441 6.942349 7.922616 10.79268 7.853106 7.275433 10.83678 8.657635 6.499877 10.87574 9.338055 5.61319 10.90869 8.812943 5.61319 19.62425 -7.182104 6.749726 25.51988 -7.115938 6.861205 24.96144 -7.68965 5.317091 29.51594 -7.70049 5.712631 28.89136 -7.920138 5.376977 28.92134 -7.686069 5.857308 28.64814 -7.518179 6.212303 28.30293 -7.702237 6.043475 28.14624 -7.504031 6.500246 27.18883 -7.496991 6.521002 27.07504 -7.515876 6.499877 27.07679 -7.861485 5.903813 27.94115 -7.510997 6.473219 27.32676 -7.988945 5.79944 27.69663 -8.079032 5.734928 27.4234 -8.194191 5.61319 27.13959 -7.519564 6.388122 27.71447 -7.518868 6.415221 27.59661 -7.516439 6.441332 27.47866 -7.489571 6.23917 28.32117 -7.497056 6.258647 28.24331 -7.435803 5.976143 29.03395 -7.419602 6.130928 28.77079 -7.295103 6.040818 29.21742 -7.285457 6.045196 29.2293 -7.489192 6.238263 28.3248 -8.193644 5.137113 28.5691 -9.777551 5.25 5.695204 -8.295862 7.083163 5.503351 -8.627265 6.771323 5.386145 -9.494096 5.71201 5.50891 -9.182711 6.142676 5.388345 -8.888588 6.494376 5.354219 -3.784211 8.96621 10.63973 -7.853106 7.275433 10.83677 -7.395191 6.742606 25.89858 -7.351613 6.820669 25.51431 -8.133489 6.499877 19.57527 -7.283913 6.933654 24.95564 -7.216102 7.04133 24.39597 -7.105458 7.184184 23.79114 -7.330102 7.275433 19.51735 -8.812943 5.61319 19.62425 -9.338055 5.61319 10.90868 -8.657636 6.499877 10.87573 -5.945609 8.427044 10.7444 -6.942349 7.922616 10.79267 -4.885038 8.777506 10.69304 -3.266983 8.96621 19.22444 -2.834851 8.992736 19.90837 -3.103988 8.975799 19.95732 -3.688664 8.903903 20.11482 -4.366247 8.777506 19.30368 -4.252408 8.786782 20.33872 -4.839635 8.610598 20.65902 -5.425312 8.427044 19.38003 -5.345226 8.409523 21.02194 -5.80733 8.179827 21.44585 -6.420638 7.922616 19.45179 -6.015882 8.059692 21.675 -6.919937 7.377565 23.19621 -6.740705 7.539867 22.78086 -6.412993 7.797391 22.20328 7.222205 5.969675 30.86247 7.217453 5.972793 30.87106 7.181943 5.987058 30.98599 6.869647 6.119594 31.71644 7.322094 5.775444 30.80142 7.446383 5.723228 30.27557 7.249206 5.811965 31.03414 7.390799 5.813158 30.49244 6.931876 5.949151 31.78411 7.088737 5.870791 31.45255 7.248991 5.805668 31.03498 6.511041 6.119981 32.47278 6.780553 5.99127 32.0606 6.961929 5.921139 31.72576 5.401107 6.512662 33.61912 5.424536 6.44929 33.6089 5.663287 6.376636 33.41124 5.99724 6.311982 33.08766 6.160504 6.214375 32.91591 6.554418 6.075582 32.41406 5.101024 6.542298 33.8433 4.733341 6.710225 34.05829 4.588537 6.67732 34.14799 4.004869 6.893943 34.3969 3.912245 6.832675 34.44569 6.455229 6.284842 32.38789 5.949051 6.470803 32.98789 5.361749 6.665376 33.50673 4.704076 6.857115 33.93554 3.987052 7.035615 34.26609 3.225158 7.190843 34.49272 3.232846 7.132783 34.57561 7.232794 5.907411 31.01473 6.917029 6.042916 31.75684 6.498166 6.211739 32.43857 5.986686 6.401578 33.04745 5.393241 6.600082 33.57382 4.728567 6.79558 34.00882 4.003646 6.977458 34.34418 3.229283 7.047173 34.63 3.218211 6.965622 34.64687 -4.004838 6.893934 34.39691 -3.229938 7.054305 34.6271 -3.232724 7.136324 34.57213 -3.218213 6.965621 34.64688 -7.344358 5.868577 30.6163 -7.351751 5.860637 30.59837 -7.233042 5.907292 31.01402 -7.441158 5.732761 30.30262 -7.249453 5.811841 31.03342 -7.442739 5.729821 30.29467 -7.446322 5.723204 30.27585 -6.869913 6.119484 31.71593 -7.182189 5.986945 30.98529 -7.164622 6.004714 30.96472 -6.455492 6.284736 32.38753 -5.949291 6.470721 32.98765 -5.361948 6.665309 33.50659 -4.704189 6.857088 33.93547 -3.987024 7.035613 34.26609 -4.733454 6.71019 34.05823 -4.459344 6.708992 34.21341 -3.803367 6.855281 34.48386 -5.401308 6.512588 33.61897 -5.085532 6.546595 33.85365 -4.72446 6.64295 34.07441 -6.511306 6.119866 32.47241 -6.108269 6.232123 32.9742 -5.997481 6.311891 33.08742 -5.675296 6.372899 33.40069 -5.394615 6.458153 33.63212 -7.272551 5.795956 30.96362 -7.002211 5.905265 31.6431 -6.932144 5.949033 31.78358 -6.642342 6.043219 32.28361 -6.513127 6.090557 32.47265 -3.224873 7.191695 34.49072 -4.003616 6.977452 34.34419 -4.728681 6.795549 34.00875 -5.393443 6.600012 33.57368 -5.986928 6.401492 33.04721 -6.498432 6.211628 32.4382 -6.917298 6.042802 31.75631 4.000056 6.781846 34.41098 3.198292 6.873101 34.6325 7.456668 5.693719 30.2109 7.459928 5.697363 30.19449 6.772369 5.66487 31.60685 7.022735 5.598309 31.17819 6.802111 5.692776 31.69285 7.171134 5.575102 30.88388 7.297616 5.575005 30.60057 7.211877 5.637923 30.9638 7.162869 5.59281 30.95429 7.025806 5.597666 31.17244 6.857223 5.725242 31.71365 5.846555 6.022741 32.96906 6.113392 5.897445 32.4745 6.342123 5.839003 32.35415 6.685332 5.69254 31.7403 6.744522 5.67712 31.66739 6.736102 5.676196 31.66331 5.409852 6.394167 33.61205 4.73675 6.594873 34.06317 6.520807 5.997767 32.43679 6.008134 6.191016 33.06673 6.937276 5.827291 31.73265 7.247078 5.692389 30.96757 7.305424 5.576233 30.58261 7.33336 5.586339 30.52882 7.397059 5.630666 30.4072 3.906198 6.585622 34.28194 3.862122 6.568444 34.17709 4.61772 6.407304 33.94228 4.558998 6.395719 33.84404 5.268208 6.216094 33.50164 5.196423 6.210682 33.41191 5.763297 6.023734 32.88969 6.395268 5.857597 32.38639 5.894314 6.044576 33.00717 5.309692 6.241255 33.54471 4.652071 6.43568 33.98945 3.932576 6.616917 34.33229 6.446271 5.892653 32.41273 5.940328 6.082493 33.03829 5.349892 6.282119 33.5799 4.68567 6.479393 34.02797 3.958815 6.663224 34.3734 6.903732 5.771923 31.72727 6.48947 5.941275 32.42997 5.979499 6.133268 33.05867 5.384367 6.335114 33.60293 4.714823 6.534546 34.05319 3.982057 6.720345 34.40032 3.171117 6.788252 34.57878 3.142809 6.734119 34.49456 3.120007 6.719614 34.40272 7.418639 5.651019 30.35177 -6.125212 5.893029 32.46128 -6.112517 5.89777 32.47535 -6.339934 5.838563 32.35266 -6.01971 5.932075 32.59387 -5.844583 6.022173 32.96733 -6.765968 5.66685 31.61689 -6.763468 5.667624 31.6208 -6.742136 5.67682 31.66619 -6.418807 5.784875 32.1098 -6.274062 5.837771 32.28952 -6.799976 5.691876 31.69191 -7.025885 5.597642 31.17226 -7.297586 5.574991 30.60063 -7.162277 5.575922 30.90249 -7.16111 5.591544 30.95384 -6.855555 5.723931 31.71302 -7.21072 5.6365 30.96357 -7.324963 5.582283 30.54327 -7.41862 5.651019 30.3518 -7.397037 5.630662 30.40723 -7.246475 5.691076 30.9675 -7.333338 5.586331 30.52886 -7.456651 5.693723 30.21092 -7.459922 5.69738 30.19446 -6.936697 5.825982 31.73256 -6.520275 5.996428 32.43671 -6.007636 6.189673 33.06666 -5.40939 6.392804 33.612 -4.736316 6.593511 34.06312 -3.999599 6.780466 34.41093 -5.266487 6.215381 33.49971 -4.417285 6.433328 33.92239 -4.616271 6.40647 33.94018 -3.786487 6.585448 34.20634 -3.905004 6.584663 34.27972 -5.763164 6.023799 32.8895 -5.565362 6.091465 33.08986 -5.015078 6.266007 33.54866 -3.120008 6.719619 34.40272 -3.147289 6.740376 34.50979 -3.164969 6.773643 34.56284 -6.393306 5.856578 32.38523 -5.89254 6.043452 33.0058 -5.308134 6.240011 33.54321 -4.650745 6.434337 33.98781 -3.931458 6.615469 34.33055 -3.183283 6.821905 34.6064 -6.444735 5.891254 32.41196 -5.93893 6.081025 33.03741 -5.348654 6.280562 33.57893 -4.684599 6.477772 34.02692 -3.957878 6.661528 34.37229 -3.200256 6.880758 34.63513 -6.90263 5.770482 31.72694 -6.488455 5.939778 32.42959 -5.978567 6.131737 33.05825 -5.383529 6.333532 33.60248 -4.714079 6.532934 34.05271 -3.981362 6.71869 34.39982 -3.214182 6.94356 34.64673 -5.233201 6.19921 33.08579 -5.967757 5.951014 32.58582 5.405656 6.144185 32.97706 4.660307 6.368062 33.41282 3.87906 6.564668 33.78201 3.417459 6.66307 33.96257 2.60782 6.804603 34.21778 2.353531 6.840918 34.55165 1.784529 6.908775 34.40245 1.575377 6.92889 34.65933 0.9490149 6.974249 34.51723 0.7895705 6.982174 34.72444 0.2886378 6.997619 34.55797 2.35026e-5 6.999949 34.74616 -0.5665357 6.990827 34.54614 -0.789516 6.982172 34.72444 -1.411486 6.942985 34.46254 -1.575305 6.928905 34.65935 -2.246682 6.855184 34.30776 -2.353465 6.840924 34.55165 -2.639916 6.799735 34.20908 -3.473012 6.651915 33.94222 -4.276812 6.469351 33.60446 -5.050709 6.255308 33.19553 2.436305 7.174602 34.78119 -2.432834 7.316994 34.64257 -1.628456 7.408488 34.75091 -0.8161613 7.463882 34.81639 2.65877e-5 7.482367 34.83824 0.8162206 7.463883 34.81639 1.628529 7.408472 34.7509 2.432897 7.316988 34.64256 3.070333 6.991321 34.67857 2.073096 7.1325 34.85213 1.630959 7.267046 34.89053 1.024495 7.221557 34.96117 -2.436242 7.174609 34.7812 -2.164785 7.121837 34.83905 -1.630886 7.267062 34.89055 -1.095557 7.217442 34.95613 -0.8174268 7.323047 34.95664 -0.03247618 7.25013 34.99611 2.67685e-5 7.341731 34.97869 0.8174862 7.323049 34.95664 2.438875 7.259906 34.72626 1.63262 7.352116 34.8352 0.8182999 7.407973 34.90107 2.67396e-5 7.426607 34.92304 -0.8182404 7.407971 34.90107 -1.632547 7.352132 34.83522 -2.438812 7.259912 34.72627 -2.3924 6.912986 34.72945 -2.413014 6.999332 34.7837 -1.615414 7.090932 34.89307 -0.8096974 7.146408 34.95919 2.43427e-5 7.164922 34.98125 0.8097534 7.146409 34.95919 1.615487 7.090916 34.89305 2.413082 6.999325 34.78369 -2.370864 6.857063 34.6444 -1.587051 6.946251 34.75276 -0.7954345 7.000257 34.81827 2.37745e-5 7.01828 34.84012 0.7954894 7.000258 34.81827 1.587123 6.946236 34.75275 2.37093 6.857057 34.64439 -1.601557 7.00349 34.83843 -0.8027339 7.058298 34.9043 2.40795e-5 7.07659 34.92628 0.8027894 7.0583 34.9043 1.60163 7.003474 34.83841 2.392466 6.91298 34.72944 6.310402 5.201558 31.47558 6.024523 5.283979 31.7452 4.974569 5.668636 32.56057 4.505213 5.821238 32.85194 -5.977282 5.299623 31.78751 -6.413888 5.178084 31.3719 -6.785952 5.133454 30.96931 -6.997823 5.147923 30.71632 -7.202539 5.034943 30.45269 -7.224299 5.217779 30.42344 -7.223484 5.162462 30.42454 -7.222503 5.149814 30.42586 -7.207905 5.05879 30.44549 -4.647925 5.776585 32.76752 -4.815865 5.722089 32.66357 -5.491841 5.480986 32.18993 -5.638727 5.423884 32.07416 -5.807255 5.359689 31.93506 -2.785084 6.243853 33.61987 -3.196046 6.16186 33.47488 -3.935745 5.984513 33.15491 -4.505034 5.821293 32.85203 -0.9421629 6.470882 34.01261 -1.298922 6.444613 33.96779 -2.067513 6.359322 33.82117 -2.429388 6.305457 33.72768 0.2656204 6.497688 34.05819 -0.5213549 6.491089 34.04698 2.78511 6.243848 33.61988 2.399853 6.310185 33.73592 1.642217 6.411382 33.91087 0.873334 6.474984 34.0196 4.288659 5.886118 32.97337 3.569715 6.077106 33.3231 3.144926 6.172697 33.49415 5.62596 5.428908 32.08445 7.207988 5.058948 30.44543 7.222563 5.149874 30.42583 7.012136 5.150406 30.69857 7.223542 5.162512 30.42451 7.224353 5.217827 30.42341 6.785864 5.133465 30.96945 7.202666 5.035291 30.45256 -7.198375 6.083085 29.20048 -7.173313 6.074621 29.28274 -6.928872 6.177609 27.16937 -7.083638 6.063719 29.58831 -7.039104 6.070144 29.7463 -7.002596 6.082033 29.87936 -7.12214 6.064643 29.45508 -7.154124 6.260844 27.14663 -7.324251 6.192383 28.57742 -7.300103 6.157133 28.75115 -7.225198 6.682571 25.90437 -7.331029 6.49116 27.08085 -7.31501 6.440254 27.13608 -7.359165 6.400104 27.59535 -7.348825 6.248883 28.31275 -6.991738 6.568683 24.39846 -6.833652 6.389826 24.40917 -6.611499 6.304754 24.43167 -6.503669 6.345789 23.83651 -2.007235 7.639281 20.01318 -2.013687 7.697583 19.98426 -2.061195 7.692639 19.98433 -1.995846 7.536355 20.09264 -1.983925 7.428627 20.25485 -2.028203 7.423724 20.25495 -2.364716 7.382912 20.2697 -2.422291 7.651504 19.99972 -3.673232 7.45998 20.26283 -3.054165 7.56433 20.0906 -4.037384 7.38974 20.40617 -4.612035 7.265384 20.70472 -5.147949 7.134306 21.0789 -5.676991 6.990386 21.56898 -6.092901 6.866959 22.07727 -6.25121 6.817572 22.31277 -6.561542 6.716873 22.88252 -6.796706 6.63711 23.49052 -6.875214 6.609815 23.76838 -6.719847 6.431962 23.79061 -6.643204 6.459905 23.51799 -6.413772 6.541481 22.92186 -6.111295 6.644309 22.36388 -5.957103 6.694679 22.13344 -5.552307 6.820398 21.63654 -5.0379 6.966712 21.15806 -4.517237 7.099723 20.79316 -3.959282 7.225696 20.50235 -3.605846 7.296748 20.36285 -3.005161 7.402152 20.19544 -2.392189 7.490018 20.10738 -2.041928 7.531388 20.09268 -1.987106 7.457378 20.1962 -6.430997 6.373016 23.57401 -6.213225 6.452564 22.99945 -5.925638 6.552962 22.46081 -5.778848 6.602188 22.23807 -5.392955 6.725179 21.75716 -4.901629 6.868525 21.29316 -4.403468 6.999016 20.93865 -3.868876 7.122753 20.65561 -3.529921 7.19261 20.51963 -2.953417 7.296336 20.35614 2.013687 7.697583 19.98426 0.6702839 7.737687 20.01318 2.007235 7.639281 20.01318 -0.6702839 7.737687 20.01318 -0.6635622 7.554798 20.1962 0.6635622 7.554798 20.1962 1.983925 7.428627 20.25485 1.987106 7.457378 20.1962 1.995846 7.536355 20.09264 6.833652 6.389826 24.40917 6.991738 6.568683 24.39846 6.888913 6.605018 23.82413 6.566779 6.715129 22.89385 6.797681 6.636774 23.49363 6.259909 6.814819 22.32659 6.254942 6.816391 22.31869 6.020542 6.889089 21.97851 5.596542 7.013211 21.48486 5.109462 7.14421 21.04841 4.820739 7.216083 20.83815 4.258799 7.343794 20.51007 3.286815 7.527326 20.14528 3.657031 7.462951 20.2572 6.516347 6.341003 23.88918 6.4319 6.37268 23.57694 6.218076 6.450825 23.01016 5.933702 6.550218 22.47387 5.929098 6.551785 22.4664 5.711736 6.624244 22.14466 5.318273 6.747917 21.67753 4.865868 6.878386 21.26428 4.597519 6.949943 21.0651 4.074903 7.077044 20.75414 3.514838 7.195565 20.5143 3.170107 7.259562 20.40807 2.620194 7.459642 20.13075 2.58373 7.352969 20.29273 3.230883 7.364798 20.24856 3.590124 7.299753 20.35738 4.17423 7.179177 20.60352 4.71996 7.049722 20.92324 5.000497 6.97677 21.1283 5.474051 6.843622 21.55437 5.886647 6.717236 22.03685 6.114931 6.643104 22.36967 6.11977 6.6415 22.3774 6.418879 6.539698 22.93297 6.644155 6.45956 23.52104 6.733223 6.427049 23.84533 6.611499 6.304754 24.43167 2.657339 7.621344 20.0239 7.36326 6.355806 27.81421 7.31501 6.440254 27.13608 7.154124 6.260844 27.14663 7.331029 6.49116 27.08085 6.928872 6.177609 27.16937 7.198375 6.083085 29.20048 7.213627 6.089554 29.149 7.003246 6.081758 29.87962 7.083849 6.063709 29.58757 7.173145 6.074573 29.2833 7.300135 6.551944 26.694 7.303977 6.162016 28.72641 7.324287 6.192444 28.57713 7.352496 6.261523 28.25447 -7.265898 6.042716 29.2734 -7.329549 5.962257 29.33713 -7.345384 5.957099 29.30953 -7.321132 5.965815 29.34833 -7.311732 5.970023 29.35975 -7.177414 6.040854 29.47493 -7.143858 6.044066 29.55206 -7.314384 5.96724 29.36338 -7.057064 6.062513 29.7533 -7.12195 6.047327 29.60262 -7.322184 5.964672 29.3499 -7.472086 5.917469 29.08076 -7.631494 5.560634 29.34526 -7.611929 5.426241 29.58288 -7.54115 5.293451 30.00233 -7.556039 5.134792 30.03274 7.599301 5.453845 29.60162 7.541149 5.293446 30.00234 7.556035 5.134788 30.03275 7.611966 5.426644 29.5823 7.612748 5.435137 29.56997 7.6012 5.459654 29.58754 7.615607 5.46899 29.5206 7.608658 5.482969 29.53118 7.631648 5.561197 29.34391 7.621092 5.523911 29.43286 7.14533 6.026102 29.64709 7.122256 6.047275 29.60191 7.143615 6.044097 29.55262 7.263491 5.991515 29.41721 7.225468 6.03999 29.36512 7.30158 5.97456 29.372 7.2521 6.041425 29.30462 7.311017 5.970343 29.36062 7.258754 6.042 29.28956 7.346093 5.956869 29.30829 7.329885 5.962146 29.33654 7.274427 5.98059 29.4318 7.30595 5.970032 29.37791 7.313775 5.967442 29.36443 -7.439574 5.735966 30.29336 -7.510394 5.577949 29.99975 -7.494734 5.627117 30.03448 -7.478903 5.677937 29.98775 -7.49417 5.628629 30.0363 -7.421071 5.788417 29.97044 -7.483215 5.653025 30.07765 -7.476952 5.665037 30.10433 -7.334968 5.877239 30.59744 -7.302753 5.917681 29.9418 -7.426894 5.888822 29.3258 -7.523382 5.518601 29.99699 -7.591893 5.656352 29.35313 -7.521827 5.781797 29.34311 7.089362 6.045543 29.89535 7.381942 5.840162 29.95836 7.302992 5.917568 29.93982 7.33506 5.877137 30.59682 7.490522 5.637732 30.04902 7.51042 5.57813 29.99901 7.43228 5.771192 29.97156 7.460946 5.69515 30.18779 7.439645 5.735856 30.29203 7.592078 5.656703 29.35175 7.427399 5.888695 29.3245 7.524474 5.512674 29.9967 7.522119 5.781872 29.34175 7.41852 5.072423 30.23601 7.257842 5.22781 30.381 7.391651 5.288003 30.2536 7.393094 5.262676 30.25129 7.407473 5.131344 30.24042 -7.407472 5.131256 30.24041 -7.349219 5.26546 30.2879 -7.393077 5.262679 30.25129 -7.391638 5.287954 30.25359 -7.418505 5.072421 30.236 -7.501354 5.597384 30.03577 -7.494465 5.591039 30.07701 -7.486305 5.562407 30.12053 -7.481917 5.468159 30.1532 -7.462808 5.47608 30.18446 -7.446824 5.428947 30.2074 -7.490703 5.278282 30.14086 -7.503647 5.106745 30.14641 7.503651 5.106743 30.14642 7.490706 5.278275 30.14087 7.494483 5.591038 30.07699 7.486322 5.56241 30.12052 7.482564 5.463471 30.15253 7.462821 5.476108 30.18446 7.446837 5.42899 30.2074 7.501373 5.59738 30.03575 7.479543 5.649642 30.09845 7.465129 5.627859 30.16392 7.42676 5.565787 30.2621 7.403514 5.534566 30.29792 7.330036 5.453598 30.36653 7.247901 5.418614 30.46109 7.254084 5.500223 30.54259 7.226696 5.413187 30.49235 7.21664 5.317674 30.45205 6.555872 5.642415 31.62073 6.354916 5.379256 31.47884 6.440573 5.533094 31.52949 5.828283 5.803676 32.16248 5.703966 5.636791 32.08507 5.974398 5.896661 32.30141 6.928803 5.522816 31.08902 6.803318 5.280047 30.98286 7.016492 5.276296 30.71917 7.045977 5.393983 30.75883 6.852402 5.413748 31.02392 7.098669 5.495797 30.81495 4.352544 6.086254 32.9892 5.046305 5.872308 32.56898 5.156317 6.037935 32.65362 -5.910399 5.854199 32.21247 -5.841175 5.798863 32.15209 -5.690043 5.854518 32.2712 -5.803804 5.759403 32.12394 -5.713952 5.626779 32.07371 -5.568665 5.687919 32.19221 -5.66826 5.524039 32.0645 -5.98759 5.891794 32.29094 -4.885887 5.924869 32.67377 -4.716063 5.978471 32.77958 -3.995187 6.183127 33.17419 -2.467642 6.499415 33.75852 -3.245472 6.357846 33.50049 -2.100283 6.552541 33.854 -1.31972 6.636685 34.00378 -0.5297477 6.682548 34.08471 0.2698996 6.68906 34.09616 0.8873667 6.666655 34.05673 1.668409 6.603897 33.94563 3.193628 6.368527 33.52016 2.437665 6.504078 33.76694 3.624309 6.274331 33.34567 -4.992404 6.090234 32.76 -4.818879 6.143576 32.86742 -4.082276 6.3473 33.26808 -3.316201 6.521292 33.59945 -2.521405 6.662313 33.86152 -2.146037 6.715243 33.95849 -1.348463 6.799087 34.11064 -0.5412843 6.844789 34.19285 0.2757769 6.851279 34.20449 0.9066916 6.828951 34.16442 1.704749 6.766414 34.05157 2.490774 6.666959 33.87007 3.263226 6.531929 33.61943 3.703304 6.438116 33.44222 4.44743 6.250856 33.08024 -6.021718 5.900481 32.32931 -5.832318 5.948311 32.41152 -5.115762 6.187674 32.90634 -4.937639 6.241821 33.01503 -4.181911 6.448561 33.42031 -3.396492 6.625057 33.75532 -2.582068 6.768065 34.02017 -2.197549 6.82173 34.11816 -1.380712 6.906729 34.27186 -0.5542042 6.953056 34.35491 0.282357 6.959634 34.36666 0.9283472 6.937002 34.32619 1.745577 6.873608 34.21219 2.550687 6.772775 34.02881 3.342196 6.635846 33.77551 3.793308 6.540692 33.59638 4.556471 6.350702 33.23033 5.284055 6.134578 32.79869 -7.226645 5.413163 30.4924 -7.216586 5.317638 30.45208 -7.003005 5.275299 30.73642 -6.134033 5.82345 32.12992 -5.993311 5.725123 32.00416 -6.279991 5.757975 31.96345 -6.63903 5.610994 31.50949 -6.928886 5.522789 31.08886 -7.088066 5.496673 30.83271 -7.254042 5.500206 30.54264 -7.03377 5.39419 30.7761 -6.852489 5.413722 31.02377 -6.530946 5.500543 31.42464 -6.146093 5.655153 31.84984 -6.803406 5.280028 30.98272 -6.452654 5.350001 31.37679 -6.039293 5.49344 31.78776 -5.877386 5.560603 31.93504 -7.304395 5.440252 30.39215 -7.330008 5.453576 30.36654 -7.479525 5.649644 30.09847 -7.465112 5.62786 30.16393 -7.426739 5.565773 30.26211 -7.403489 5.534545 30.29794 -7.267566 6.063346 29.22474 -7.246107 6.076217 29.2181 -7.222516 6.082947 29.20983 -7.151553 6.057522 29.46578 -7.103673 6.057802 29.59572 -7.048286 6.066828 29.74983 -7.382158 6.267372 28.32086 -7.480918 6.440674 27.60287 -7.464926 6.543915 27.08121 -7.455637 6.547504 27.08246 -7.426193 6.552529 27.0853 -7.435244 6.446771 27.60487 -7.406237 6.550948 27.08636 -7.386955 6.545474 27.08668 -7.391562 6.432216 27.60217 -7.360978 6.530484 27.08577 -7.353457 6.523872 27.08511 -7.458108 6.261626 28.32738 -7.420528 6.271846 28.326 -7.330913 6.166196 28.75977 -7.363465 6.164533 28.76635 -7.394159 6.152327 28.77016 -7.312513 6.843492 25.52362 -7.357921 6.765599 25.90695 -7.266768 6.846284 25.52961 -7.3139 6.770126 25.9124 -7.22415 6.828448 25.53101 -7.240215 6.724031 25.91096 -7.193765 6.793794 25.52751 -7.271881 6.755287 25.91383 -7.127359 6.904997 24.96861 -7.060843 7.01096 24.40874 -7.157234 6.939595 24.97181 -7.090222 7.045493 24.41166 -7.199288 6.957734 24.97036 -7.131725 7.063915 24.41015 -7.244692 6.955604 24.96456 -7.176786 7.062425 24.40454 -3.07882 8.90713 20.05024 -2.824919 8.973783 19.96649 -2.501549 8.980902 19.92642 -2.829855 8.987936 19.93895 -2.504105 8.995106 19.89866 -2.817114 8.923773 20.00219 -2.498219 8.930902 19.9626 -2.820528 8.951671 19.98829 -2.499521 8.95878 19.94845 -2.500455 8.970711 19.9383 -3.083967 8.935058 20.03662 -3.090306 8.957141 20.01507 -3.097208 8.971186 19.98773 -3.647224 8.836452 20.20513 -3.656127 8.864505 20.1924 -3.66674 8.886462 20.17158 -3.67797 8.900059 20.1448 -4.195037 8.721323 20.42558 -4.207545 8.749576 20.41411 -4.222362 8.771319 20.39426 -4.237879 8.784186 20.36819 -4.821013 8.609907 20.68778 -4.800855 8.59816 20.71288 -4.781527 8.576744 20.73137 -4.765297 8.548169 20.74109 -5.322963 8.411067 21.04984 -5.781584 8.184036 21.4726 -5.298592 8.400651 21.0738 -5.753103 8.175218 21.49513 -5.275223 8.379609 21.09076 -5.725864 8.154607 21.51029 -5.255841 8.350624 21.09856 -5.70367 8.125082 21.51595 -5.988492 8.065353 21.70105 -5.958044 8.057412 21.72274 -5.928983 8.037029 21.7369 -5.905557 8.007182 21.74147 -6.382281 7.806403 22.22737 -6.706946 7.552488 22.80216 -6.347809 7.800493 22.2469 -6.668748 7.54878 22.81889 -6.315109 7.780612 22.25874 -6.632804 7.529396 22.82812 -6.289429 7.749949 22.26099 -6.605416 7.497731 22.82822 -6.884316 7.392682 23.21499 -6.843832 7.390503 23.22935 -6.805974 7.371432 23.23664 -6.777747 7.338996 23.23551 -6.955493 7.15017 23.81791 -6.984481 7.183712 23.82027 -7.024498 7.20241 23.81581 -7.06766 7.202578 23.80542 -2.034731 8.993821 19.88081 -2.034731 8.986603 19.8962 -2.034731 8.970711 19.91691 -2.034731 8.95 19.9328 -2.034731 8.934613 19.94002 2.034731 8.993821 19.88081 2.034731 8.986603 19.8962 2.034731 8.970711 19.91691 2.034731 8.95 19.9328 2.034731 8.934613 19.94002 2.504105 8.995106 19.89866 2.501549 8.980902 19.92642 2.500455 8.970711 19.9383 2.499521 8.95878 19.94845 2.498219 8.930902 19.9626 7.176786 7.062425 24.40454 7.090222 7.045493 24.41166 7.131725 7.063915 24.41015 7.030522 7.195458 23.84089 7.060843 7.01096 24.40874 6.990427 7.176774 23.84522 6.793506 7.323489 23.27842 6.961416 7.143186 23.84283 6.102994 7.880733 21.99132 6.245117 7.782117 22.19342 6.554419 7.541466 22.72411 5.034945 8.44554 20.92639 5.20987 8.371215 21.06109 5.685803 8.135001 21.49725 6.859845 7.375047 23.27258 6.821805 7.356006 23.27966 6.616944 7.592411 22.71394 6.581544 7.572939 22.72364 6.302811 7.832613 22.17874 6.270545 7.812669 22.19089 6.158498 7.931097 21.97484 6.127598 7.910959 21.9879 5.734967 8.18513 21.47625 5.707887 8.164501 21.49149 5.251942 8.421238 21.03597 5.22896 8.400156 21.05309 5.074442 8.495547 20.89998 5.052914 8.474323 20.91768 4.547057 8.681177 20.56113 4.529727 8.659604 20.58027 3.983823 8.826621 20.28945 3.970824 8.804777 20.30975 3.679677 8.884318 20.17593 3.668968 8.862366 20.19674 4.515126 8.631185 20.59081 3.959861 8.776618 20.32181 3.65998 8.834308 20.20943 3.099388 8.956398 20.01699 3.092982 8.934316 20.03852 3.087776 8.906386 20.05213 7.073781 7.195547 23.83069 6.900551 7.377069 23.25848 6.654507 7.596518 22.69665 6.336795 7.838786 22.15891 6.190962 7.938061 21.95415 5.763278 8.19402 21.45366 5.275907 8.431796 21.01189 5.096885 8.506607 20.87546 4.565151 8.693465 20.53557 3.997483 8.839839 20.26305 3.691006 8.897901 20.14917 3.106358 8.970438 19.98966 7.127359 6.904997 24.96861 7.193765 6.793794 25.52751 7.157234 6.939595 24.97181 7.22415 6.828448 25.53101 7.199288 6.957734 24.97036 7.266768 6.846284 25.52961 7.244692 6.955604 24.96456 7.312513 6.843492 25.52362 7.320554 6.587623 26.69892 7.455637 6.547504 27.08246 7.434525 6.614252 26.69492 7.426193 6.552529 27.0853 7.394048 6.621697 26.69942 7.406237 6.550948 27.08636 7.353755 6.612283 26.70084 7.360978 6.530484 27.08577 7.353457 6.523872 27.08511 7.246107 6.076217 29.2181 7.267566 6.063346 29.22474 7.286301 6.071198 29.17259 7.222516 6.082947 29.20983 7.263631 6.084111 29.1663 7.23881 6.09038 29.15824 7.335018 6.171614 28.735 7.399095 6.15816 28.74516 7.367964 6.170279 28.74149 7.463296 6.276643 28.26854 7.424922 6.286549 28.26746 7.48249 6.388374 27.82399 7.438913 6.395743 27.82503 7.385946 6.28123 28.26251 7.3964 6.38413 27.82155 7.103936 6.057782 29.595 + + + + + + + + + + 0 1 0 0 1 1.44897e-6 0 1 0 -1 -6.28893e-7 0 -1 0 0 1 0 0 -0.6593707 -0.670494 -0.3401001 -0.177335 -0.606195 -0.7752934 -0.2432689 -0.5879281 -0.7714669 -0.645142 -0.5396111 -0.540936 -0.5943686 -0.5113024 -0.6207221 -0.5133994 -0.5283601 -0.6762076 -0.4216666 -0.5570525 -0.7154648 -0.3058609 -0.755693 -0.5791177 -0.5143165 -0.7862143 -0.3425573 -0.1040164 -0.8835883 -0.4565659 -0.2657878 -0.8746851 -0.4053183 -0.0741505 -0.9364649 -0.342834 -0.01970183 -0.9156775 -0.4014307 -0.1305154 -0.8874036 -0.4421321 -0.1304116 -0.8626791 -0.4886488 -0.1513627 -0.8490676 -0.5061358 -0.1304938 -0.8296407 -0.5428332 -0.1302619 -0.7798438 -0.6122708 -0.1302608 -0.7798433 -0.6122717 -0.1305075 -0.7283794 -0.6726301 -0.1477429 -0.6935502 -0.7050958 -0.1303782 -0.6838632 -0.7178668 -0.1304657 -0.6252276 -0.7694603 -0.0693643 -0.6108029 -0.7887386 -0.3822849 -0.8007424 -0.4611614 -0.382007 -0.7938205 -0.4732015 -0.3820052 -0.7938205 -0.4732031 -0.3820052 -0.7268931 -0.5707001 -0.3820064 -0.7268934 -0.5706989 -0.3820091 -0.6480627 -0.6588503 -0.3820046 -0.648063 -0.6588527 -0.3825136 -0.5821248 -0.7175056 -0.2988619 -0.5777204 -0.759553 -0.5645943 -0.6597306 -0.4959726 -0.538573 -0.4120931 -0.7349276 -0.6079646 -0.6819876 -0.4065367 -0.6079657 -0.6819863 -0.4065372 -0.6079663 -0.6244864 -0.4902998 -0.6079649 -0.6244885 -0.4902988 -0.6079649 -0.556765 -0.5660313 -0.6079644 -0.5567651 -0.5660318 -0.6085803 -0.5010601 -0.6152795 0 -1 0 0.4449501 -0.5514225 -0.7056577 0.6561536 -0.476518 -0.5851437 0.5670046 -0.6698476 -0.479385 0.02453559 -0.9387272 -0.3437868 -0.0235598 -0.9156008 -0.4013979 0.06219112 -0.9100821 -0.4097352 0.3084924 -0.8589599 -0.4086815 0.3710647 -0.7936355 -0.4821346 0.3888165 -0.5846189 -0.7120692 0.1074103 -0.6338046 -0.7659993 0.2071163 -0.5934528 -0.777764 0.3157921 -0.5741859 -0.7553713 0.03294152 -0.6119446 -0.7902144 0.1304428 -0.6212157 -0.7727068 0.1303777 -0.6838631 -0.717867 0.1477429 -0.6935502 -0.7050958 0.130508 -0.7283795 -0.67263 0.1302608 -0.7798435 -0.6122716 0.130262 -0.7798436 -0.6122709 0.1304935 -0.8296406 -0.5428334 0.1513627 -0.8490676 -0.5061358 0.1304115 -0.862679 -0.4886491 0.1304957 -0.8914529 -0.4339156 0.151975 -0.8731051 -0.4632397 0.3825316 -0.5834261 -0.7164381 0.3820058 -0.6480637 -0.6588513 0.3820074 -0.6480626 -0.6588515 0.3820058 -0.7268924 -0.5707007 0.3820053 -0.7268943 -0.5706986 0.3820065 -0.7938205 -0.4732021 0.3820064 -0.7938202 -0.4732025 0.3602233 -0.9278937 -0.09618985 0.4139997 -0.6659035 -0.6206262 0.6633455 -0.6673667 -0.338518 0.5349704 -0.4028595 -0.7426379 0.6079646 -0.6819871 -0.4065377 0.6079652 -0.6819872 -0.4065365 0.6079655 -0.6244879 -0.4902987 0.6079657 -0.6244869 -0.4902999 0.6079656 -0.5567645 -0.5660312 0.6079641 -0.5567646 -0.5660325 0.6087383 -0.5236164 -0.59604 0.552301 -0.5122532 -0.6576932 0.01374512 -0.93892 -0.3438609 0 -0.5699985 -0.8216458 0 -0.5700075 -0.8216395 0.00206089 -0.612276 -0.7906414 0.01303094 -0.6048606 -0.7962248 -0.01466882 -0.6896767 -0.7239689 0 -0.6817278 -0.731606 0.003674507 -0.9822471 -0.1875559 -0.00860399 -0.9828309 -0.184308 -0.009490728 -0.9720031 -0.2347766 -0.004169404 -0.974241 -0.225471 -0.001833975 -0.96639 -0.2570739 -2.17634e-5 -0.9821152 -0.1882817 7.5078e-5 -0.974857 -0.2228313 0.003771901 -0.9574617 -0.288536 -0.008050262 -0.9829328 -0.1837887 -0.001652836 -0.9846895 -0.1743095 2.85039e-4 -0.9852914 -0.1708827 0 -0.9865333 -0.1635606 0.005058169 -0.9840391 -0.1778807 0.001175463 -0.9873471 -0.1585694 -0.00206089 -0.612276 -0.7906414 -0.01303052 -0.6048607 -0.7962247 0.01466876 -0.6896771 -0.7239686 0 -0.6817288 -0.731605 0 -0.7346585 -0.6784372 0 -0.7346629 -0.6784324 0 -0.7865455 -0.6175325 0 -0.7865449 -0.6175332 0 -0.8367968 -0.5475138 0 -0.8367952 -0.5475161 0 -0.8701099 -0.492858 0 -0.9158554 -0.4015084 0 -0.9158558 -0.4015074 0 -0.9427414 -0.3335249 -2.20358e-4 -0.939005 -0.3439038 4.84502e-4 -0.9522276 -0.3053889 0.7070844 -0.7071291 0 -0.7070844 -0.7071291 0 -0.08043164 -0.1791828 -0.9805225 -0.3170154 -0.7856751 -0.5312401 -0.5961202 -0.8025294 0.02423578 -0.5732133 -0.8193637 0.008351683 -0.1558256 -0.7123869 -0.6842684 -0.1685405 -0.5920597 -0.7880733 -0.1035144 -0.539614 -0.8355247 -0.1233301 -0.4936352 -0.8608798 -0.1240044 -0.3984799 -0.9087556 -0.553777 -0.791608 -0.2582396 -0.4366002 -0.8841203 -0.1664682 -0.4417881 -0.7673587 -0.4647409 -0.4420117 -0.7603671 -0.4758859 -0.386122 -0.763318 -0.517934 -0.3865405 -0.6547315 -0.6495484 -0.2785022 -0.5787913 -0.7664445 -0.9997206 -2.97663e-6 0.02363866 -0.9873818 0.00254482 -0.1583374 -0.99131 -3.65318e-4 -0.1315467 -0.9480383 3.73051e-6 -0.3181562 -0.889362 -7.57725e-4 -0.4572031 -0.8533949 0.005667269 -0.5212342 -0.3476977 -4.70731e-5 -0.9376068 -0.4864718 1.73679e-4 -0.8736963 -0.5610973 0.006539881 -0.827724 -0.6585943 -9.79211e-6 -0.7524982 -0.766946 -1.08715e-5 -0.6417117 -0.3621783 -3.23368e-4 -0.9321088 -0.2319394 0.001128494 -0.9727296 -0.1607372 -0.003446996 -0.9869913 -0.05466073 -3.02491e-7 -0.998505 0 -0.5425271 -0.8400384 0 -0.1797661 -0.9837094 0 -0.1797666 -0.9837094 0 -0.3682168 -0.9297401 -4.76757e-4 -0.5555697 -0.83147 -0.9724532 0.020406 0.2322034 -0.9847075 -0.02788513 0.1719694 -0.9898126 0.02100843 0.140818 -0.9943972 4.9217e-5 0.1057079 -0.9683034 -8.37987e-5 0.2497772 -0.9527217 -8.2394e-5 0.3038443 -0.9281764 0.08386915 0.3625666 -0.9224462 0.01850455 0.385682 -0.886909 -0.00607717 0.4619043 -0.8730252 -0.03141832 0.4866618 -0.8305315 0.08555281 0.5503619 -0.8137007 1.97957e-5 0.581284 -0.9985771 0.003375053 0.05322027 -0.998515 0.001851916 0.05444788 -0.9988053 -3.56162e-6 0.04886829 -0.9959948 4.84541e-5 0.08941256 -0.9963294 0.008718609 0.08515858 -0.9965399 0.002193927 0.08308702 -0.9982213 -3.49619e-4 0.05961656 -0.9978464 5.10409e-4 0.06559264 -0.9975482 0.004881799 0.06981271 -0.9974613 0.003082692 0.07114464 -0.9969568 -8.71687e-4 0.07795244 -0.614323 -0.7886825 0.02423048 -0.1323614 -0.1347737 -0.9819962 -0.4862812 -0.02753555 -0.8733685 -0.3475673 -0.01976382 -0.9374468 -0.1417608 -0.1368958 -0.9803895 -0.1495363 -0.113448 -0.9822263 -0.1555843 -0.1239383 -0.9800168 -0.1627106 -0.09534692 -0.9820562 -0.1687871 -0.1036224 -0.9801905 -0.1735529 -0.07570749 -0.9819104 -0.1795229 -0.08214426 -0.9803183 -0.1817506 -0.05467838 -0.9818234 -0.187266 -0.0593903 -0.9805123 -0.1875926 -0.03285717 -0.9816972 -0.1919651 -0.03582769 -0.9807476 -0.1914566 -0.02438378 -0.9811981 -0.1607269 -0.009911477 -0.9869492 -0.7662165 -0.04343211 -0.6411131 -0.65813 -0.03752726 -0.7519686 -0.9856155 -0.05997699 -0.1580033 -0.8883869 -0.04698669 -0.4566849 -0.9986438 -0.04639399 0.02362757 -0.9851992 -0.0587337 -0.1610378 -0.9784941 -0.1704735 -0.116138 -0.9718897 -0.1424582 -0.1874464 -0.953939 -0.2863715 -0.0893976 -0.9481813 -0.2454889 -0.2017118 -0.9288402 -0.3522952 -0.1146475 -0.9027571 -0.3936007 -0.1735172 -0.8943932 -0.4247106 -0.1402922 -0.7477787 -0.6270586 -0.2182307 -0.8088741 -0.5709491 -0.1404983 -0.8541874 -0.5006795 -0.1402999 -0.8307949 -0.5186328 -0.20199 -0.8694587 -0.4736669 -0.1402907 -0.4794511 -0.5891125 -0.6504408 -0.3083538 -0.3706764 -0.8760805 -0.1232607 -0.1556977 -0.9800843 -0.1218591 -0.1495224 -0.9812204 -0.252462 -0.310171 -0.9165462 -0.7946627 -0.6034763 -0.06578463 -0.708006 -0.6845923 -0.173381 -0.6825653 -0.7221269 -0.1124165 -0.6214378 -0.7639344 -0.1738371 -0.619081 -0.7670475 -0.1684548 -0.8500992 -0.07103389 -0.52181 -0.8406794 -0.1465513 -0.5213263 -0.8412082 -0.1472443 -0.5202767 -0.8179239 -0.2456144 -0.5202636 -0.8182001 -0.246085 -0.5196066 -0.7832025 -0.3414744 -0.5196046 -0.7832816 -0.3416604 -0.5193632 -0.7372418 -0.4321247 -0.5193678 -0.7372105 -0.4320159 -0.5195026 -0.680541 -0.5167163 -0.5194886 -0.6804639 -0.5162951 -0.520008 -0.6140489 -0.5937381 -0.5200183 -0.6140115 -0.5930188 -0.5208826 -0.5533123 -0.6496849 -0.5213013 -0.5550967 -0.681433 -0.4769871 -0.5608258 -0.05901235 -0.8258281 -0.5561864 -0.09700554 -0.8253768 -0.5566865 -0.09743738 -0.8249886 -0.5412794 -0.1625735 -0.8249766 -0.5415472 -0.1628705 -0.8247423 -0.5183755 -0.2260239 -0.8247424 -0.518463 -0.2261524 -0.8246522 -0.4879966 -0.286022 -0.8246519 -0.4879504 -0.2859445 -0.8247061 -0.450457 -0.3419953 -0.8246986 -0.45034 -0.3416926 -0.8248878 -0.4064081 -0.3929076 -0.8248977 -0.4062705 -0.392382 -0.8252155 -0.3760557 -0.4205424 -0.8256672 -0.4023303 -0.4940157 -0.7707651 -0.4156666 -0.8947116 -0.1634401 -0.04816603 -0.9985507 0.02401685 -0.00990951 -0.8387347 -0.5444502 -0.01193726 -0.8398815 -0.5426386 -0.2968827 -0.8808867 -0.3686454 -0.2186409 -0.8522147 -0.4753172 -0.1851371 -0.8688923 -0.4590759 -0.1315968 -0.8560602 -0.4998431 -0.03125298 -0.9828091 -0.1819609 -0.05276042 -0.9872747 -0.1500167 -0.0941317 -0.9817478 -0.1652596 -0.2221538 -0.8551456 -0.4683736 -0.0792663 -0.768391 -0.6350529 -0.0735321 -0.7657524 -0.6389182 -0.05153131 -0.7713201 -0.6343579 -0.0409249 -0.7746978 -0.6310059 -0.0320549 -0.8373928 -0.5456609 -0.07034814 -0.8343899 -0.546667 -0.0604577 -0.8366996 -0.544315 -0.05657994 -0.835246 -0.5469579 -0.03679549 -0.8383651 -0.543866 -0.03430747 -0.8371314 -0.545925 -0.0214653 -0.8381964 -0.544946 -0.5302454 -0.8450924 0.06825578 -0.5209361 -0.8525073 0.04309242 -0.4646133 -0.88152 -0.08400619 -0.3899942 -0.8704352 -0.3004118 -0.2988637 -0.9192205 -0.2563478 -0.2858843 -0.9196852 -0.2691646 -0.2479664 -0.9348937 -0.253942 -0.2372596 -0.9343069 -0.2660426 -0.1080699 -0.982316 -0.1528924 -0.141814 -0.9771678 -0.1582153 -0.15559 -0.9737938 -0.165884 -0.1918171 -0.971318 -0.1405262 -0.2354137 -0.9539654 -0.185824 -0.06330835 -0.7707809 -0.6339472 -0.06267637 -0.7782288 -0.6248453 -0.1600415 -0.8698362 -0.4666603 -0.120497 -0.8826951 -0.4542355 -0.1906644 -0.9489715 -0.2511977 -0.1718402 -0.9850308 -0.01361322 -0.3152289 -0.9471884 -0.05886262 -0.3598062 -0.933022 0.003073811 -0.3760514 -0.9240582 -0.06856954 -0.4096118 -0.9109103 -0.0496056 -0.4228626 -0.9044573 -0.05607378 0.002279102 0.9991366 0.04148364 0.04417312 -0.7911474 0.6100283 0.1253226 0.2237356 0.9665592 0.1395785 -0.002044558 0.9902089 0.1873081 -0.00198698 0.9822993 0.1886305 0.269159 0.9444427 0.2592283 -0.2334619 0.9371746 0.2873362 0.1844262 0.9399068 0.3295212 -4.50623e-5 0.9441483 0.3730269 -1.8356e-5 0.9278206 0.3880406 0.2573966 0.8849698 0.4428216 -0.1059762 0.8903248 0.490081 0.04673361 0.8704233 0.5062382 -8.06433e-5 0.8623937 0.5386723 -7.11442e-5 0.8425155 0.5456159 -0.02777725 0.837575 0.6005713 0.0520243 0.797877 0.6107882 -0.01023095 0.791728 0.7485275 -2.29501e-5 0.6631038 0.7506003 -0.01113063 0.6606627 0.6827185 0.01133894 0.7305936 0.6965433 -0.09284424 0.7114825 0.6613562 0.004455447 0.7500588 -0.536132 -6.90944e-5 0.8441343 -0.02789014 0.8735566 0.4859228 -0.09428828 -0.7063174 0.7015878 -0.2671462 0.3644706 0.892073 -0.2150759 -0.3923742 0.894307 -0.1707822 0.4406899 0.8812639 -0.08873873 -0.736338 0.6707696 -0.4858162 -7.99639e-5 0.8740611 -0.4968985 0.08515679 0.8636205 -0.4238817 -0.07941687 0.9022291 -0.3857247 0.2319771 0.8929743 -0.3628296 4.04157e-5 0.9318555 -0.3156114 8.04095e-6 0.9488886 -0.5906091 0.1939209 0.7833108 -0.5793324 0.01209753 0.8150016 -0.6558237 -0.005151271 0.7548965 -0.6574967 -5.48685e-5 0.7534575 -0.6935696 -4.45594e-5 0.7203897 -0.6960299 0.005195677 0.7179941 -0.7397572 -0.01048988 0.6727923 -0.7472642 0.01874649 0.6642627 -0.7751576 1.8515e-5 0.6317681 -0.6738934 -0.6547017 0.3423936 -0.6874242 -0.6399472 0.3433885 -0.6922277 -0.6355122 0.3419724 -0.6827039 -0.6446854 0.3439423 -0.706389 -0.6247189 0.3327777 -0.7106775 -0.6222302 0.3282792 -0.7018012 -0.6278265 0.3366143 -0.6970348 -0.6314646 0.3396983 -0.7198382 -0.6187982 0.3145185 -0.7226719 -0.6185995 0.3083504 -0.7170087 -0.619483 0.3195925 -0.7141817 -0.6205654 0.3237949 -0.7931259 -0.134047 0.5941236 -0.7379097 -0.649595 0.1830728 -0.726414 -0.6204108 0.2956573 -0.7248003 -0.6192024 0.3020811 -0.1942309 -0.8739026 0.4456104 -0.6010736 -0.4880517 0.6328634 -0.5986567 -0.4877995 0.6353438 -0.53154 -0.6553044 0.5366949 -0.5165945 -0.6753169 0.5263813 -0.4526309 -0.6565954 0.6033306 -0.1229153 -0.9205128 0.370875 -0.1132606 -0.9049705 0.4101223 -0.05887693 -0.9474493 0.3144415 -0.2720886 -0.8673349 0.4167713 -0.2038093 -0.906538 0.3696629 -0.1476539 -0.9169598 0.3706523 -0.4615908 -0.7329857 0.499666 -0.4030208 -0.8432387 0.3557006 -0.3509893 -0.8639941 0.3609998 -0.6574918 -0.6813597 0.3216419 -0.5800209 -0.7522211 0.312633 -0.5821443 -0.7560408 0.2991827 -0.4572179 -0.7970803 0.3944803 -0.8686513 -0.4622471 0.1782487 -0.9029199 -0.3151548 0.2922552 -0.9754795 -0.1354364 0.1734848 -0.993215 -0.04887109 0.1055257 -0.9909459 -0.04743283 0.1256039 -0.9811322 -0.002923429 0.1933164 -0.9834678 -0.05744993 0.1717287 -0.9681127 -0.01972508 0.2497375 -0.9564164 -0.04110723 0.2890982 -0.9525435 -0.01906698 0.3038047 -0.9283843 -0.02214258 0.3709612 -0.9225217 0.01336419 0.3857141 -0.7705579 -0.05110943 0.6353176 -0.8135756 -0.01666611 0.5812204 -0.8136754 -0.01685357 0.5810753 -0.8727204 -0.04113298 0.4864847 -0.8406321 0.08724731 0.5345331 -0.8920464 -0.04100096 0.4500803 -0.7803943 -0.1383705 0.6097855 -0.7008978 -0.3137288 0.6405595 -0.7016498 -0.333438 0.6296878 -0.7021666 -0.3090459 0.6414458 -0.7275072 -0.2566549 0.6362873 -0.7417213 -0.2507927 0.6220551 -0.6704671 -0.3995366 0.6251755 -0.6793351 -0.3797714 0.6279153 -0.6284768 -0.4304631 0.6478569 -0.6296178 -0.4521918 0.6317468 -0.6513285 -0.415463 0.6349501 -0.787313 -0.125395 0.6036674 -0.8220884 -0.1088646 0.5588552 -0.8220919 -0.108869 0.5588492 -0.8559923 -0.09614133 0.5079707 -0.8559925 -0.09614092 0.5079702 -0.8909465 -0.08706188 0.4456846 -0.8909425 -0.08705878 0.4456932 -0.9245173 -0.08527493 0.3714783 -0.9245156 -0.0852788 0.3714815 -0.9511458 -0.09199321 0.2947185 -0.9511464 -0.09199047 0.2947176 -0.9703043 -0.1070932 0.2168886 -0.9703041 -0.1070909 0.2168906 -0.9829188 -0.1342427 0.1258951 -0.9465352 -0.2295091 0.2267087 -0.9650973 -0.2355952 0.1143768 -0.950912 -0.2001318 0.2360377 -0.9509128 -0.2001313 0.2360345 -0.9343851 -0.1871085 0.3031746 -0.9343858 -0.1871103 0.3031715 -0.9114125 -0.1813187 0.3693928 -0.9114133 -0.1813162 0.3693917 -0.8824566 -0.182855 0.433399 -0.8824545 -0.1828472 0.4334062 -0.852269 -0.1907011 0.4871044 -0.8522705 -0.1907023 0.4871014 -0.8230304 -0.2016773 0.530987 -0.823024 -0.2016777 0.5309969 -0.7861781 -0.2189875 0.5779002 -0.7861843 -0.2189871 0.5778918 -0.7482786 -0.2412896 0.6179471 -0.7364526 -0.1715 0.6543894 -0.9372459 -0.3423336 0.06616514 -0.9226178 -0.2911901 0.2529525 -0.9226219 -0.291182 0.2529465 -0.9088778 -0.2803604 0.3087707 -0.9088771 -0.2803555 0.308777 -0.8897778 -0.2755373 0.3638335 -0.8897746 -0.2755343 0.3638434 -0.8656944 -0.2768121 0.4170711 -0.8656986 -0.2768152 0.4170603 -0.8405632 -0.2833555 0.4616959 -0.8405587 -0.2833549 0.4617046 -0.8162484 -0.2924782 0.498192 -0.8162469 -0.2924836 0.4981911 -0.7856375 -0.3068674 0.5372207 -0.7856355 -0.3068693 0.5372226 -0.7481133 -0.3287282 0.5764237 -0.748103 -0.3287299 0.5764361 -0.708301 -0.355663 0.6097652 -0.708303 -0.3556644 0.609762 -0.6870505 -0.3722476 0.6240139 -0.6717089 -0.33494 0.6607742 -0.52087 -0.6727208 0.5254914 -0.5523356 -0.623826 0.5529617 -0.5515006 -0.6245 0.5530342 -0.6000816 -0.5762857 0.5547946 -0.5791532 -0.5956626 0.5565678 -0.5249925 -0.6491799 0.5504075 -0.6239137 -0.5846585 0.5185618 -0.6472834 -0.5611919 0.5158371 -0.6472871 -0.5611916 0.5158329 -0.6711319 -0.5391877 0.5087814 -0.6711462 -0.5391795 0.5087715 -0.6950516 -0.5190227 0.4975128 -0.6950618 -0.5190145 0.497507 -0.718528 -0.5011284 0.4822734 -0.7185422 -0.5011185 0.4822629 -0.7411554 -0.4858169 0.4633257 -0.7411596 -0.4858105 0.4633256 -0.7624707 -0.4733992 0.4410575 -0.7624678 -0.4734057 0.4410556 -0.7798362 -0.4652178 0.4188412 -0.7798279 -0.4652165 0.4188581 -0.7936443 -0.4600343 0.3981172 -0.7936382 -0.4600377 0.3981256 -0.8079617 -0.4563198 0.3727874 -0.807967 -0.4563132 0.3727837 -0.8216401 -0.4555972 0.3425477 -0.8216375 -0.4555988 0.3425517 -0.8324968 -0.4583321 0.3112568 -0.832497 -0.4583329 0.3112554 -0.840305 -0.4644803 0.2795454 -0.840298 -0.4644945 0.279543 -0.8338215 -0.4529498 0.3155601 -0.8086379 -0.5592092 0.1827291 -0.8833732 -0.3756739 0.2802163 -0.8855987 -0.3796724 0.2675142 -0.8855956 -0.3796775 0.2675173 -0.8747805 -0.3711386 0.3114728 -0.8747751 -0.3711459 0.3114792 -0.8597271 -0.36735 0.3548569 -0.8597302 -0.3673513 0.3548479 -0.8407606 -0.3683584 0.3967794 -0.8407608 -0.3683592 0.3967783 -0.8209407 -0.3735123 0.4319085 -0.8209363 -0.3735157 0.431914 -0.8017895 -0.3807007 0.4606525 -0.8017824 -0.3807017 0.4606638 -0.7777022 -0.3920264 0.4914212 -0.777701 -0.3920329 0.4914178 -0.7481532 -0.4092434 0.5222898 -0.7481474 -0.4092466 0.5222955 -0.71678 -0.4304729 0.5485615 -0.7167966 -0.430465 0.5485458 -0.6842377 -0.4552837 0.5696804 -0.6842151 -0.4552928 0.5697003 -0.6510838 -0.4832311 0.5853013 -0.6510813 -0.4832334 0.5853022 -0.6180211 -0.5137412 0.5950798 -0.6180123 -0.5137465 0.5950844 -0.5870977 -0.5448384 0.5987216 -0.5605077 -0.5215311 0.6433013 -0.6781431 -0.6496585 0.3436073 -0.670004 -0.659753 0.3403244 -0.7758576 -0.5251794 0.3496164 -0.7870047 -0.5450844 0.2889754 -0.787021 -0.5450699 0.2889581 -0.7822814 -0.5413817 0.308126 -0.7823023 -0.5413647 0.3081028 -0.7757679 -0.5397055 0.326959 -0.7757423 -0.5397167 0.3270013 -0.7674926 -0.5401404 0.3452587 -0.7674896 -0.5401528 0.345246 -0.7588346 -0.5423897 0.3605323 -0.7588488 -0.5423763 0.3605226 -0.7504875 -0.545528 0.3730521 -0.750496 -0.5455191 0.3730477 -0.7400611 -0.5504384 0.3864288 -0.7400391 -0.5504543 0.3864482 -0.727175 -0.5579424 0.399896 -0.7271755 -0.5579454 0.399891 -0.7135196 -0.5671864 0.4113264 -0.713523 -0.567183 0.4113253 -0.6993227 -0.5780084 0.4205402 -0.6993472 -0.5779923 0.4205216 -0.6849045 -0.5901715 0.4273213 -0.6849163 -0.5901613 0.4273165 -0.6705427 -0.6034228 0.4315708 -0.6705133 -0.6034475 0.4315822 -0.6564041 -0.6176119 0.4332314 -0.6564208 -0.6175978 0.4332261 -0.6428703 -0.6323766 0.432224 -0.6428569 -0.6323909 0.4322232 -0.6301563 -0.6474595 0.4286016 -0.6301699 -0.6474479 0.4285992 -0.6185244 -0.6625756 0.4223992 -0.618512 -0.6625849 0.422403 -0.4153353 -0.7157781 0.5613898 -0.4114678 -0.7167459 0.5630007 -0.4933661 -0.7113936 0.5005087 -0.4933633 -0.7113952 0.5005094 -0.5997633 -0.6910037 0.4034821 -0.5997671 -0.6909897 0.4035007 -0.663736 -0.6692525 0.3339997 -0.4313006 -0.6802157 0.5926944 -0.4485245 -0.6812446 0.5785599 -0.5103729 -0.6840277 0.5211772 -0.5103742 -0.6840284 0.521175 -0.6083584 -0.6771758 0.4139239 -0.6083493 -0.6771853 0.4139217 -0.6665892 -0.6646552 0.3374794 -0.3047472 -0.8326912 0.4623361 -0.3493284 -0.790422 0.5031927 -0.468188 -0.7625117 0.4465155 -0.4681822 -0.7625217 0.4465045 -0.5870358 -0.7168434 0.3761975 -0.5870585 -0.7168172 0.3762122 -0.659475 -0.6779031 0.3248695 -0.3539223 -0.7573546 0.5487741 -0.3612276 -0.7551199 0.5470913 -0.4791313 -0.7377539 0.475555 -0.4791349 -0.7377483 0.4755598 -0.592574 -0.7043211 0.390881 -0.5925592 -0.7043427 0.3908646 -0.661305 -0.6737513 0.3297499 -0.4576959 -0.8039206 0.3797711 -0.4576925 -0.8039295 0.3797566 -0.5817363 -0.7377655 0.342469 -0.5817351 -0.7377516 0.3425011 -0.6577014 -0.6849076 0.3135768 -0.2772285 -0.8559146 0.4365256 -0.278191 -0.8715943 0.40365 -0.2872118 -0.8631271 0.4153565 -0.3044729 -0.8301009 0.4671497 -0.4609951 -0.7847151 0.4143741 -0.461 -0.7847067 0.4143844 -0.583415 -0.728042 0.3599746 -0.5834078 -0.7280585 0.3599528 -0.6582399 -0.6816884 0.3194077 0 -0.7071061 -0.7071075 5.56341e-6 -0.7070952 -0.7071184 -2.92624e-5 -0.7071285 -0.7070851 9.56322e-6 -0.70709 -0.7071235 -2.34931e-5 -0.7071244 -0.7070892 1.99122e-5 -0.7071052 -0.7071085 0 -0.7071056 -0.707108 -5.88624e-6 -0.7070977 -0.7071159 1.7408e-5 -0.7071355 -0.7070781 -9.67939e-6 -0.7070826 -0.707131 3.44715e-5 -0.7072075 -0.707006 -2.58981e-6 -0.707101 -0.7071126 1.97381e-5 -0.7071365 -0.7070772 -6.65312e-6 -0.7071201 -0.7070935 -5.92708e-6 -0.7071158 -0.7070978 9.15473e-7 -0.7070966 -0.707117 0.5961582 -0.8025015 0.02422779 0.5732133 -0.8193637 0.008351683 0.569337 -0.8137886 -0.1166343 0.6233446 -0.7635979 -0.1684041 0.4308389 -0.8487927 -0.3064785 0.4420154 -0.7603673 -0.4758822 0.3861212 -0.7633176 -0.517935 0.3865466 -0.6547315 -0.6495448 0.2785016 -0.57879 -0.7664457 0.3170142 -0.7856746 -0.5312415 0.1558269 -0.7123909 -0.6842641 0.1685407 -0.5920613 -0.7880721 0.1180296 -0.5516874 -0.8256573 0.1398975 -0.483772 -0.8639407 0.1239194 -0.3653849 -0.9225714 0.1240031 -0.3984755 -0.9087578 0.08043164 -0.1791828 -0.9805225 0.7667935 -6.46556e-7 -0.6418939 0.1585788 -9.29854e-5 -0.9873464 0.1983032 0.003672182 -0.980134 0.3456412 1.15548e-4 -0.9383668 0.5652668 -6.11309e-4 -0.8249079 0.4881725 0.01048952 -0.8726842 0.6582682 -7.10448e-7 -0.7527836 0.8899915 0.009129226 -0.455886 0.845624 -0.002626001 -0.5337725 0.9849146 0.001952886 -0.1730306 0.9878365 0.003690838 -0.1554521 0.9999548 0 0.009516239 0.9889244 -4.91028e-5 0.1484201 0.9904822 -0.05364423 0.1267573 0.9631411 0.07414549 0.2585764 0.9734694 -0.07324892 0.2167764 0.9278001 0.07300329 0.3658655 0.7858723 -2.84064e-5 0.6183888 0.7870498 -8.51046e-4 0.616889 0.8159041 0.003307819 0.5781778 0.825455 -0.0255801 0.5638881 0.8604276 0.01755154 0.5092704 0.8682117 0 0.4961941 0.8889608 0 0.4579833 0.8948745 -0.009834289 0.4462096 0.9129907 0.01466381 0.4077168 0.9429138 -0.08652788 0.3216001 -0.04286253 -0.9934412 0.1060069 -0.03895282 -0.9829897 0.1794831 -0.03705179 -0.9671457 0.2515086 -0.06574743 -0.9847206 0.1612533 -0.0472545 -0.9951345 0.0864551 -0.1318106 -0.9892043 0.06403803 -0.1354345 -0.9885731 0.06618773 -0.174137 -0.982742 0.06240624 -0.2288205 -0.971302 0.06491315 -0.2310512 -0.9708654 0.06352669 -0.2991276 -0.9519438 0.06576997 -0.3221234 -0.943906 0.07264965 -0.374893 -0.9252976 0.05726897 -0.453804 -0.8869762 0.08564656 -0.4151104 -0.9073816 0.06589353 -0.464881 -0.8828612 0.06664824 -0.5050642 -0.8604148 0.06779932 -0.5265906 -0.8481685 0.0575549 -0.5908542 -0.8037607 0.06971383 -0.613129 -0.7873578 0.06434893 -0.6711022 -0.7381995 0.06843483 -0.6852923 -0.7255571 0.06278061 -0.7441563 -0.6643284 0.06999492 -0.7645346 -0.6416133 0.06180226 -0.809014 -0.5835483 0.07048225 -0.8149887 -0.5754578 0.06813108 -0.8464607 -0.5285308 0.06449377 -0.8647885 -0.4972702 0.06973654 -0.876281 -0.4773951 0.06500566 -0.9110863 -0.4072725 0.06364619 -0.9010043 -0.4277841 0.07205539 -0.947686 -0.3152589 0.05003255 -0.9326378 -0.3535683 0.07194751 -0.9738746 -0.2215582 0.04980331 -0.9661707 -0.2496661 0.06466251 -0.990433 -0.128256 0.0509206 -0.9878612 -0.1440227 0.05820387 -0.9976514 -0.04631346 0.05046576 -0.9976534 -0.0462886 0.05044972 -0.9932441 -0.04898726 0.1051982 -0.9937891 -0.03539687 0.1055002 -0.9845283 -0.1214429 0.1263156 -0.9789006 -0.1466608 0.1422823 -0.9656071 -0.210147 0.1531052 -0.9527617 -0.248524 0.1745886 -0.4819949 -0.8161296 0.3187686 -0.5808408 -0.755499 0.3030601 -0.5688236 -0.7617646 0.310088 -0.6605997 -0.6932501 0.2881186 -0.6505987 -0.6999892 0.2945105 -0.7340899 -0.6219143 0.2726438 -0.7251662 -0.6292224 0.2796664 -0.8054515 -0.5379663 0.2486771 -0.7916997 -0.5517957 0.2621706 -0.8662676 -0.4478516 0.2213811 -0.8492416 -0.4690144 0.2425166 -0.9159607 -0.3529019 0.1909881 -0.8971543 -0.3822626 0.221336 -0.9370836 -0.2991264 0.179994 -0.2982714 -0.8971818 0.3257288 -0.3542354 -0.8764993 0.3259851 -0.3916285 -0.862548 0.3203722 -0.4060454 -0.8548693 0.3229951 -0.4873282 -0.8139591 0.3161991 -0.02814185 -0.9474211 0.3187499 -0.05777788 -0.943377 0.3266521 -0.1112096 -0.9404418 0.3212501 -0.1516053 -0.9323274 0.3283012 -0.2044894 -0.9236291 0.3241813 -0.2079635 -0.9225845 0.3249448 -0.2809359 -0.900906 0.3308224 -0.9963501 -0.04522556 0.07239669 -0.9967219 -0.03478962 0.07304304 -0.9880782 -0.1267756 0.08734667 -0.9881873 -0.1258174 0.08749878 -0.9705245 -0.2186638 0.1013332 -0.9707214 -0.2177103 0.1015007 -0.943431 -0.3110734 0.1147669 -0.9437144 -0.3101458 0.1149472 -0.90647 -0.4025968 0.1273888 -0.9068384 -0.4017052 0.1275824 -0.8595964 -0.4917196 0.1389466 -0.860048 -0.4908699 0.1391553 -0.8030779 -0.5768918 0.1492035 -0.8036109 -0.5760917 0.1494256 -0.7375163 -0.6565988 0.157949 -0.7381233 -0.6558593 0.1581856 -0.6638156 -0.7294642 0.1650179 -0.6644891 -0.7287942 0.1652675 -0.5831608 -0.794307 0.1702935 -0.5838955 -0.793711 0.1705549 -0.4969428 -0.8502175 0.173719 -0.4977299 -0.8497007 0.1739937 -0.4066814 -0.8965935 0.1753007 -0.4075134 -0.8961601 0.1755847 -0.3139562 -0.9331526 0.1750942 -0.3148183 -0.9328069 0.1753877 -0.2202901 -0.9599328 0.1732091 -0.2211838 -0.9596723 0.173513 -0.1271262 -0.977245 0.1697975 -0.1280263 -0.9770739 0.1701056 -0.04485934 -0.9851732 0.1655944 -0.9968214 -0.04668301 0.06455892 -0.9972607 -0.03388375 0.06574988 -0.9888893 -0.1273918 0.0766108 -0.9889711 -0.1266682 0.07675486 -0.9716554 -0.2198032 0.08701956 -0.9718036 -0.2190856 0.08717417 -0.9448764 -0.3127574 0.09690988 -0.9450887 -0.3120649 0.09707158 -0.9082242 -0.4048163 0.1060786 -0.9085038 -0.4041431 0.1062507 -0.8616499 -0.4944556 0.1143379 -0.86199 -0.4938205 0.1145195 -0.8054101 -0.5801293 0.12151 -0.8058152 -0.5795263 0.121701 -0.7401061 -0.660304 0.1274431 -0.7405661 -0.6597498 0.1276412 -0.6666331 -0.7336018 0.132018 -0.6671454 -0.7330988 0.1322244 -0.5861775 -0.7988288 0.1351613 -0.5867388 -0.7983802 0.135376 -0.5001247 -0.8550723 0.1368455 -0.5007237 -0.8546863 0.1370666 -0.409996 -0.901726 0.1370893 -0.4106264 -0.901405 0.1373139 -0.3173606 -0.9385089 0.1359531 -0.3180202 -0.9382526 0.1361817 -0.2237608 -0.9654529 0.1335357 -0.2244362 -0.9652641 0.1337676 -0.1306157 -0.9828779 0.1299641 -0.1313092 -0.9827542 0.1302008 -0.03777843 -0.9913988 0.1253047 -0.04796719 -0.9905632 0.1283898 -0.997235 -0.04818612 0.05657386 -0.9977464 -0.03287482 0.0584923 -0.9896137 -0.1278034 0.06581228 -0.989669 -0.1273128 0.06593042 -0.9726585 -0.220594 0.07262039 -0.9727565 -0.220122 0.07274061 -0.9461531 -0.313948 0.078938 -0.9463 -0.3134716 0.07906836 -0.9097729 -0.4063871 0.08463436 -0.9099634 -0.405932 0.08476901 -0.8634545 -0.4964103 0.08957272 -0.8636874 -0.4959799 0.0897116 -0.8074634 -0.5824389 0.09363788 -0.807735 -0.582039 0.09378057 -0.74238 -0.6629588 0.09673476 -0.742693 -0.6625868 0.09688168 -0.669108 -0.7365688 0.09879803 -0.6694571 -0.7362311 0.09895014 -0.5888279 -0.8020742 0.09979444 -0.5892047 -0.8017781 0.09994828 -0.5029156 -0.8585637 0.09972208 -0.503324 -0.858306 0.09987938 -0.4128977 -0.9054226 0.09861749 -0.4133299 -0.9052079 0.09877741 -0.3203467 -0.942368 0.09654355 -0.3207897 -0.942201 0.09670227 -0.2267944 -0.9694359 0.09358716 -0.2272569 -0.9693119 0.0937485 -0.1336776 -0.9869427 0.08985853 -0.1341468 -0.9868646 0.09001713 -0.04965925 -0.9950687 0.08586168 -0.0406568 -0.997723 0.05381524 -0.04936301 -0.996994 0.05971819 -0.9952484 -0.04234617 0.08767783 -0.995488 -0.0362398 0.08769553 -0.9862031 -0.1249405 0.1085974 -0.9863691 -0.1235221 0.1087116 -0.9678992 -0.2153223 0.1296445 -0.9681906 -0.2139244 0.1297816 -0.94006 -0.3062138 0.1500681 -0.9404776 -0.3048492 0.1502295 -0.9023656 -0.3962402 0.1694993 -0.9029083 -0.3949216 0.1696865 -0.8547894 -0.4838957 0.1875637 -0.8554523 -0.4826396 0.1877774 -0.7976103 -0.5676627 0.2039047 -0.7983901 -0.5664784 0.2041465 -0.7314395 -0.6460535 0.2182001 -0.7323263 -0.6449569 0.2184695 -0.6571965 -0.7177102 0.2301845 -0.6581793 -0.7167136 0.2304815 -0.5760637 -0.781481 0.2396623 -0.5771366 -0.7805887 0.2399892 -0.4894537 -0.836458 0.2465221 -0.4906032 -0.8356799 0.2468762 -0.3988838 -0.8820559 0.2507376 -0.4000922 -0.8814006 0.2511163 -0.3059285 -0.9179987 0.2523612 -0.3071842 -0.9174681 0.2527652 -0.212122 -0.9443199 0.2515234 -0.21341 -0.9439163 0.251949 -0.11889 -0.9613301 0.2484145 -0.1202049 -0.9610511 0.2488609 -0.05771213 -0.9677221 0.2453225 -0.0377075 -0.9718497 0.2325651 -0.9946232 -0.04096204 0.095115 -0.994798 -0.03674489 0.09501051 -0.985148 -0.1237113 0.1190756 -0.985342 -0.1220885 0.1191447 -0.966415 -0.2131276 0.143592 -0.9667531 -0.2115231 0.1436888 -0.9381465 -0.3030523 0.1674531 -0.9386299 -0.3014811 0.16758 -0.900038 -0.3921015 0.1902313 -0.9006605 -0.3905923 0.1903897 -0.8520592 -0.4788178 0.2114918 -0.8528206 -0.4773749 0.2116846 -0.7944996 -0.5616869 0.2308214 -0.7953944 -0.5603247 0.2310501 -0.7279778 -0.6392357 0.2478427 -0.7289962 -0.6379708 0.2481086 -0.6534241 -0.7101174 0.2622409 -0.6545545 -0.7089633 0.2625442 -0.572021 -0.7731977 0.2737837 -0.573249 -0.772167 0.2741238 -0.4851824 -0.8275803 0.2823279 -0.4865001 -0.8266773 0.2827053 -0.3944326 -0.8726823 0.2878345 -0.3958202 -0.8719173 0.288248 -0.301344 -0.9082323 0.290355 -0.3027873 -0.9076083 0.2908041 -0.2074541 -0.9342619 0.2900307 -0.2089409 -0.933781 0.2905114 -0.1141817 -0.9510803 0.2870699 -0.1156907 -0.9507439 0.287579 -0.03828895 -0.9583911 0.2828791 -0.03304928 -0.9590229 0.2813944 -0.9958249 -0.04375988 0.08011269 -0.9961296 -0.03557986 0.08037304 -0.9871811 -0.1259566 0.09802281 -0.9873185 -0.1247634 0.09816527 -0.9692704 -0.2171661 0.1155588 -0.9695141 -0.2159894 0.1157194 -0.9418232 -0.3088877 0.1325047 -0.9421735 -0.3077403 0.1326845 -0.9045131 -0.3997363 0.1485499 -0.9049696 -0.3986275 0.148749 -0.8573063 -0.4881938 0.1633791 -0.8578646 -0.4871388 0.1635984 -0.8004746 -0.5727301 0.1766938 -0.8011314 -0.5717371 0.1769328 -0.7346213 -0.6518447 0.1882292 -0.7353706 -0.6509239 0.1884892 -0.660665 -0.7241611 0.1977688 -0.661497 -0.7233246 0.1980484 -0.5797824 -0.7885197 0.2051567 -0.580691 -0.7877723 0.2054577 -0.4933807 -0.8440054 0.2103102 -0.4943485 -0.8433594 0.2106289 -0.4029731 -0.8900294 0.2132142 -0.4039961 -0.8894848 0.2135509 -0.3101341 -0.9263107 0.2139284 -0.3112042 -0.9258698 0.2142826 -0.2164034 -0.9528812 0.2125725 -0.2174975 -0.9525498 0.2129407 -0.1232109 -0.9700552 0.2093133 -0.1243239 -0.9698312 0.2096933 -0.03774261 -0.9780862 0.2047509 -0.04204934 -0.9776428 0.2060258 1.59505e-7 -0.9997091 0.02412098 0 -0.9997109 0.02404803 0 -0.9832897 -0.1820482 -1.68779e-7 -0.983289 -0.1820515 0 -0.8387785 -0.5444728 0 -0.8387755 -0.5444775 0.1621091 -0.7026848 0.6927876 0.1895087 -0.4393422 0.878103 0.6673846 -0.294133 0.6841664 0.04439204 -0.9147429 0.4015905 0.01811581 -0.865329 0.500877 0.04033952 -0.689749 0.7229241 0.01254647 -0.7264784 0.6870748 0.0364452 -0.5506671 0.833929 0.09911489 -0.06228256 0.993125 0.01704472 -0.08341485 0.9963691 0.09751319 -0.03880041 0.9944776 0.2480101 -0.08548069 0.9649789 0.1854808 -0.07513922 0.9797709 0.1716385 -0.08203601 0.9817384 0.1381649 -0.07706266 0.9874066 0.08149528 -0.07693231 0.9937002 0.3248288 -0.1772122 0.9290221 0.3162057 -0.2081067 0.925584 0.3721848 -0.02359163 0.9278588 0.4515407 0.003144562 0.892245 0.449169 -0.003898203 0.8934384 0.7149969 -0.1642649 0.6795561 0.7313382 -0.1104582 0.6730108 0.5049781 -0.02710372 0.8627066 0.5160481 -0.04731518 0.8552519 0.5462082 -0.01689159 0.8374791 0.6061848 -0.06185007 0.7929154 0.6075543 -0.05945783 0.7920497 0.6980471 -0.02914249 0.7154586 0.6787 -0.05545651 0.7323189 0.7365824 -0.05545294 0.6740707 0.7458099 -0.04445087 0.6646741 0.6302918 -0.3614102 0.6871063 0.5870791 -0.4615253 0.6650809 0.5878057 -0.4654521 0.6616939 0.5329584 -0.5282264 0.6610085 0.5321602 -0.5607813 0.6342949 0.2775838 -0.7318841 0.6223287 0.3220617 -0.7467099 0.5819801 0.372326 -0.7159133 0.590628 0.0392419 -0.9155864 0.4002022 0.04245334 -0.9279321 0.370324 0.04636931 -0.9176391 0.3947006 0.04333406 -0.9173091 0.3958111 0.1224678 -0.873512 0.471146 0.1930797 -0.6381307 0.7453251 0.1385108 -0.6320214 0.7624722 0.1399587 -0.6313599 0.7627558 0.0960077 -0.6276931 0.7725179 0.1346877 -0.7597456 0.6361178 0.08130419 -0.7534205 0.6524931 0.08298403 -0.7523834 0.6534776 0.0329473 -0.7500129 0.6606021 0.009841203 -0.8011748 0.5983495 -0.02460265 -0.8506681 0.5251271 0.04421639 -0.8552931 0.5162546 0.04205399 -0.8560482 0.5151824 0.071675 -0.8595209 0.5060501 0.06829577 -0.8602001 0.5053627 0.2111665 -0.8427975 0.4950767 0.211064 -0.8453744 0.4907078 0.1724361 -0.8327856 0.5260551 0.230539 -0.7837868 0.5766543 0.1802431 -0.7711837 0.6105638 0.1883357 -0.4401548 0.8779485 0.2612689 -0.44835 0.8548222 0.259464 -0.4500105 0.8544993 0.3298396 -0.4621196 0.8231958 0.3277812 -0.463347 0.8233281 0.3817835 -0.4745326 0.7931333 0.379527 -0.4758022 0.7934555 0.447282 -0.4923152 0.7467025 0.4441257 -0.4948004 0.7469438 0.2410878 -0.6495302 0.7211014 0.2819262 -0.6579834 0.6982661 0.2791618 -0.6589352 0.6984792 0.330546 -0.6714136 0.6632821 0.3267424 -0.6733319 0.6632222 0.3817832 -0.691577 0.6131582 0.4402783 -0.6354995 0.6342676 0.1313359 -0.4338224 0.8913748 0.1305435 -0.4344162 0.891202 0.1423405 -0.3563603 0.9234427 0.01512545 -0.8043202 0.5940038 0.06388002 -0.8068672 0.587269 0.061957 -0.8077717 0.5862306 0.10362 -0.8126848 0.5734165 0.1006102 -0.8135574 0.5727146 0.006568968 -0.9081279 0.4186415 0.02153581 -0.9086129 0.4170839 0.01463872 -0.9094991 0.4154481 0.03699904 -0.9111881 0.410326 0.0229088 -0.9123235 0.408829 0.03458952 -0.9131296 0.4061992 0.09815376 -0.8651596 0.4917976 0.09325599 -0.8662236 0.4908767 0.1418647 -0.8203838 0.5539358 0.03128701 -0.1137335 0.9930186 0.03029596 -0.1686996 0.9852019 0.08531415 -0.2906123 0.9530299 0.07482218 -0.2325888 0.9696928 0.1559097 -0.2369207 0.9589373 0.1570181 -0.2376884 0.9585665 0.2249253 -0.2433692 0.9434936 0.2264387 -0.2445237 0.9428328 0.310103 -0.2540464 0.9161314 0.3117839 -0.2563506 0.9149181 0.3918073 -0.2700175 0.8795327 0.3937988 -0.2720999 0.8780001 0.4537334 -0.2845174 0.8444974 0.45572 -0.2868618 0.8426325 0.5315614 -0.3055233 0.7899988 0.5328547 -0.3094651 0.7875896 0.5990496 -0.3315121 0.7288617 0.1415974 -0.3569808 0.9233174 0.2053698 -0.3623102 0.9091505 0.2042694 -0.363173 0.9090542 0.2831082 -0.3720672 0.8839772 0.281377 -0.3738378 0.883783 0.3574141 -0.386888 0.8500428 0.3555417 -0.3881701 0.8502436 0.4137479 -0.4002301 0.8176972 0.4116091 -0.4016003 0.8181048 0.4845843 -0.419438 0.7676262 0.4816703 -0.4220691 0.7680178 0.06698071 -0.241743 0.9680259 0.05012333 -0.3489845 0.9357871 0.05145287 -0.3512081 0.9348827 0.05407655 -0.4521453 0.8903036 0.03294301 -0.4278793 0.9032353 0.04954028 -0.4929873 0.8686251 0.1206609 -0.4969908 0.859326 0.1210635 -0.4976553 0.8588846 0.1741435 -0.5020951 0.8470978 0.1746029 -0.5030086 0.8464611 0.2402057 -0.5103724 0.8257247 0.2404698 -0.5123081 0.8244482 0.3033052 -0.523137 0.7964506 0.3036773 -0.5247431 0.7952514 0.3512167 -0.5345931 0.7686724 0.3514683 -0.5363823 0.7673097 0.4117746 -0.5510517 0.7257986 0.4110734 -0.5541365 0.723845 0.2823699 -0.7789989 0.5598464 0.2838007 -0.8035347 0.5232487 0.226118 -0.7851476 0.5765534 0.2816992 -0.7302415 0.622409 0.2232352 -0.715629 0.6618468 0.2249267 -0.7348222 0.6398785 0.2055314 -0.7101939 0.673336 0.2435573 -0.6485961 0.7211123 0.1908412 -0.6395087 0.7447202 0.1357678 -0.8948278 0.425265 0.138609 -0.8812701 0.4518303 0.1172038 -0.8741498 0.471302 0.177281 -0.8317831 0.5260308 0.1373622 -0.8218008 0.5529694 0.1842925 -0.7694395 0.6115548 0.1320206 -0.7608115 0.6354026 0.1645563 -0.7014631 0.6934486 0.1009624 -0.693928 0.712931 0.1115909 -0.7124868 0.6927555 0.08168184 -0.691973 0.7172876 0.096996 -0.6271926 0.7728011 0.01595443 -0.6220391 0.7828237 0.271645 0.2066113 0.9399579 0.2531445 -0.08313477 0.9638499 0.3403914 -0.09318858 0.9356546 0.3420038 -0.0955224 0.934831 0.4301349 -0.1104297 0.8959852 0.4320413 -0.1125282 0.894806 0.4980836 -0.1262122 0.8578947 0.5000189 -0.1285802 0.8564159 0.5832501 -0.1492728 0.7984592 0.5846532 -0.153282 0.7966714 0.6575366 -0.1773115 0.7322611 0.6591241 -0.1799719 0.7301818 0.6818495 -0.1886714 0.7067421 0.6892822 -0.2419209 0.6829087 0.6233293 -0.3429477 0.7027429 0.6006178 -0.3341538 0.7263605 0.5432353 -0.4446863 0.7121444 0.5455002 -0.4434552 0.71118 0.5009037 -0.515806 0.6950106 0.5033152 -0.5146882 0.6940965 0.4195321 -0.6281033 0.6553465 0.4800226 -0.5768765 0.6609023 0.4408468 -0.6325445 0.6368216 0.3730206 -0.6102508 0.6988917 0.3765784 -0.6081045 0.6988546 0.318721 -0.5940442 0.738599 0.3212746 -0.59297 0.7383557 0.2752553 -0.5834389 0.7640901 0.277578 -0.5823833 0.7640551 0.2178968 -0.5720978 0.7907118 0.2199586 -0.5706086 0.7912169 0.1581374 -0.5636836 0.8107116 0.1594978 -0.5629447 0.8109586 0.109613 -0.558781 0.8220394 0.1105386 -0.558237 0.8222851 0.03914469 -0.5541047 0.8315262 0.04051721 -0.6421833 0.7654797 -0.1368555 -0.498314 0.8561272 -0.01836377 -0.5509402 0.8343428 -0.02694177 -0.6240707 0.7809033 7.50202e-4 -0.6427113 0.7661081 -0.04596191 -0.7257679 0.6864027 -0.01364147 -0.8038816 0.594633 -0.01942092 -0.8010622 0.598266 -0.01925158 -0.8540549 0.5198267 0.005097568 -0.8654592 0.5009536 -0.03318578 -0.9091978 0.4150399 -0.00578618 -0.9156304 0.4019796 -0.02744561 -0.9347909 0.3541367 0.01052463 -0.8995792 0.4366312 -0.2590521 -0.9143579 0.311194 -0.038136 -0.8794831 0.4744 -0.2678427 -0.8656438 0.4229906 -0.1526665 -0.8544861 0.4965347 -0.2987858 -0.8121125 0.501199 -0.2564362 -0.8123258 0.5238007 -0.3403542 -0.7557129 0.559515 -0.3478448 -0.7546521 0.556331 -0.3861681 -0.7027578 0.5974994 -0.3875302 -0.6964297 0.6039917 -0.4223424 -0.6761331 0.6037144 -0.4380251 -0.6501767 0.6208094 -0.4435754 -0.6368986 0.6305561 -0.4400202 -0.6386875 0.6312373 -0.5241091 -0.5439842 0.6552793 -0.4924704 -0.5985742 0.6318085 -0.5300126 -0.5269099 0.6644191 -0.5467672 -0.5153442 0.6598984 -0.5712218 -0.4755684 0.6689846 -0.5751909 -0.4568476 0.6785616 -0.596297 -0.437397 0.6731373 -0.6884561 -0.2393349 0.684651 -0.6660576 -0.2930215 0.6859343 -0.6511626 -0.3110243 0.6922798 -0.6414405 -0.3215416 0.696538 -0.617807 -0.3406825 0.708696 -0.6205514 -0.3536214 0.6999056 -0.613955 -0.3988482 0.6811604 -0.6741885 -0.1446249 0.7242607 -0.702216 -0.1963214 0.6843615 -0.7307183 -0.1060082 0.6743984 -0.7338194 -0.046624 0.6777428 -0.7718589 -0.05169022 0.6336893 -0.5351271 -0.02116072 0.8445066 -0.5889641 -0.0691123 0.8051986 -0.493875 -0.0302881 0.8690052 -0.4283662 0.007547736 0.9035738 -0.1452623 -0.08658158 0.9855976 -0.06552445 -0.6251917 0.7777158 -0.06603765 -0.6255942 0.7773488 -0.05157411 -0.7136518 0.6985995 -0.04462182 -0.6897512 0.7226702 -0.00498116 -0.7471462 0.6646411 -0.5127928 -0.5919851 0.6217694 -0.459325 -0.572041 0.6795511 -0.4989079 -0.5149908 0.6970477 -0.4986299 -0.5128438 0.6988273 -0.540909 -0.4437307 0.7145072 -0.05272966 -0.922522 0.3823254 -0.04839545 -0.9184787 0.3924982 -0.1286028 -0.8788658 0.4594086 -0.1286975 -0.8762841 0.4642879 -0.1876688 -0.8387402 0.5111708 -0.1880144 -0.835951 0.5155935 -0.2450593 -0.7922781 0.5587858 -0.2456545 -0.789305 0.562718 -0.3001872 -0.7401911 0.6016685 -0.3008671 -0.7370056 0.6052287 -0.3528232 -0.6827355 0.6398344 -0.3535832 -0.6793594 0.6430006 -0.402432 -0.6207144 0.6728761 -0.4031718 -0.6171496 0.6757062 -0.4216415 -0.592723 0.6862201 -0.421947 -0.5560467 0.7160817 -0.4573697 -0.4994243 0.735791 -0.3353397 -0.5322284 0.7773546 -0.3646649 -0.4719739 0.8026582 -0.411933 -0.4830458 0.7726435 -0.4472764 -0.4114851 0.7941183 -0.4953643 -0.4247993 0.7577334 -0.5478194 -0.3123185 0.7761129 -0.5444893 -0.3133967 0.7780193 -0.6008628 -0.1563558 0.7839112 -0.5979292 -0.1575676 0.7859092 -0.6321735 -0.02365761 0.7744656 -0.689531 -0.06086885 0.7216938 -0.3452518 -0.6015534 0.7203712 -0.3815316 -0.5430457 0.7480208 -0.3795602 -0.544295 0.7481157 -0.4125874 -0.4850395 0.7710438 -0.4568918 -0.497305 0.7375214 -0.4958533 -0.4269753 0.7561889 -0.5406017 -0.4415419 0.716094 -0.5975399 -0.3306601 0.7304862 -0.5942801 -0.3316589 0.7326893 -0.6554368 -0.1762753 0.7343907 -0.6525697 -0.1774283 0.7366628 -0.6868787 -0.05634623 0.7245846 -0.7369285 -0.05212193 0.6739582 -0.04443114 -0.9175345 0.3951662 -0.03853887 -0.9141275 0.4035913 -0.1049478 -0.8697212 0.4822561 -0.1041142 -0.8673545 0.4866791 -0.1528717 -0.826238 0.5421818 -0.1523429 -0.8236768 0.5462126 -0.1994329 -0.776526 0.5976906 -0.1992114 -0.7737924 0.6012989 -0.2441878 -0.721331 0.6481158 -0.2440873 -0.7183972 0.6514039 -0.2869108 -0.6609176 0.6934481 -0.2869328 -0.6578283 0.6963703 -0.3173257 -0.6119406 0.7244537 -0.3057941 -0.5891497 0.7479255 -0.3371777 -0.5309907 0.777406 -0.2625522 -0.5806953 0.7706227 -0.2902709 -0.5203915 0.8030787 -0.288677 -0.5215342 0.802912 -0.314023 -0.4604131 0.8303068 -0.363897 -0.470146 0.8040782 -0.3953221 -0.397428 0.8281131 -0.4466386 -0.4094519 0.7955271 -0.4941929 -0.2954646 0.8176026 -0.4909126 -0.2965602 0.8191806 -0.5420073 -0.1380432 0.8289585 -0.5391075 -0.1392564 0.8306449 -0.5735875 0.0138995 0.8190265 -0.649806 -0.08561164 0.7552634 -0.03388208 -0.9134036 0.4056428 -0.02796685 -0.9108104 0.4118766 -0.0779851 -0.8622609 0.5004245 -0.07658982 -0.8604078 0.5038179 -0.1133665 -0.8160794 0.5667119 -0.1122741 -0.8140611 0.5698238 -0.1477448 -0.7637584 0.6283668 -0.1469514 -0.761582 0.6311879 -0.1808012 -0.7060545 0.6846883 -0.1801431 -0.7037237 0.6872564 -0.2123523 -0.6432783 0.7355948 -0.2118371 -0.6408084 0.7378955 -0.2346726 -0.5928034 0.7703979 -0.1361623 -0.4989624 0.8558601 -0.14821 -0.4359493 0.8876835 -0.2044926 -0.4411711 0.8738141 -0.2224935 -0.365418 0.9038619 -0.2819068 -0.3728539 0.8840297 -0.3123248 -0.2551924 0.9150574 -0.3099008 -0.2561783 0.915606 -0.342531 -0.09425401 0.9347667 -0.340336 -0.09530758 0.9354614 -0.4293988 -0.00108087 0.9031144 -0.4099478 -0.1079364 0.9057001 -0.4124748 -0.1067895 0.9046881 -0.3732774 -0.2677872 0.8882309 -0.3761121 -0.2667183 0.8873562 -0.339609 -0.3833202 0.858913 -0.2827132 -0.3742638 0.883176 -0.2599855 -0.4490913 0.8548244 -0.2052558 -0.4422466 0.8730912 -0.1886087 -0.5047805 0.8423916 -0.1896262 -0.5039205 0.8426779 -0.1300251 -0.6290776 0.7663909 -0.1306984 -0.6306542 0.7649792 -0.1105367 -0.6936396 0.7117906 -0.11133 -0.6951109 0.7102299 -0.09012407 -0.7532217 0.6515634 -0.09102207 -0.754584 0.6498599 -0.06879121 -0.8075001 0.5858426 -0.06992149 -0.8087611 0.5839661 -0.04684746 -0.855715 0.5153223 -0.04819709 -0.8568558 0.5132986 -0.01688504 -0.9086704 0.4171726 -0.02153915 -0.9101061 0.4138152 -0.0965752 -0.3534965 0.9304373 -0.1070644 -0.2338176 0.9663677 -0.1062191 -0.2342582 0.9663544 -0.1182143 -0.05739974 0.9913277 -0.0890249 -0.431162 0.8978719 -0.0969659 -0.3539672 0.9302176 -0.1600481 -0.3578339 0.9199671 -0.1774172 -0.2386206 0.9547688 -0.17598 -0.239293 0.9548665 -0.1936557 -0.08550631 0.9773362 -0.2410272 -0.0721789 0.9678307 -0.3620851 -0.02082753 0.9319124 -0.3425904 -0.08190405 0.9359079 -0.3166145 0.05097419 0.9471837 -0.2808451 -0.08656066 0.9558417 -0.2690255 -0.08767837 0.959134 -0.243793 -0.2466173 0.9379472 -0.2457596 -0.2457635 0.9376581 -0.2217589 -0.3643121 0.9044886 -0.1606441 -0.3586437 0.9195479 -0.1475846 -0.4351805 0.8881648 -0.08946597 -0.4316167 0.8976095 -0.08218038 -0.4949633 0.8650189 -0.0825898 -0.4945388 0.8652227 -0.4951976 -0.03507894 0.868072 -0.4762519 -0.1226387 0.8707147 -0.4790324 -0.12142 0.8693591 -0.4336668 -0.2812894 0.8560428 -0.4367786 -0.2801787 0.8548243 -0.3945658 -0.3955382 0.8293777 -0.3404137 -0.3849691 0.8578563 -0.3131874 -0.4588081 0.83151 -0.2608335 -0.4504733 0.8538383 -0.2397273 -0.5123474 0.8246399 -0.2410317 -0.5113341 0.8248886 -0.2184293 -0.5712315 0.7911912 -0.1715237 -0.5653494 0.8068208 -0.1442627 -0.5794165 0.8021627 -0.1239475 -0.5593941 0.8195825 -0.07529896 -0.5564082 0.8274902 -0.07478344 -0.5559701 0.8278313 -0.01332962 -0.5538881 0.8324846 -0.03201961 -0.4930525 0.8694102 -0.01146471 -0.4527779 0.8915497 -0.03461515 -0.429553 0.902378 -0.02573484 -0.3493077 0.9366547 -0.02350342 -0.3511492 0.9360246 -0.04662466 -0.2420229 0.9691497 -0.05997371 -0.2325148 0.970742 -0.0369991 -0.168661 0.9849795 -0.03919184 -0.06695002 0.9969863 -0.09240317 -0.1133016 0.9892545 -0.04886472 -0.03893929 0.9980461 0.5389378 -0.8400127 0.06264919 0.08064663 -0.7674596 -0.6360046 0.03125417 -0.9828097 -0.1819567 0.159209 -0.9760321 -0.1483706 0.04047584 -0.9988908 0.02405893 0.04871463 -0.9865465 -0.1560539 0.07141399 -0.9848747 -0.1578666 0.09443354 -0.982119 -0.1628642 0.1083551 -0.9828948 -0.1489198 0.1672351 -0.971768 -0.1664314 0.0467084 -0.7728684 -0.6328451 0.05891847 -0.7729033 -0.6317825 0.06848651 -0.7682468 -0.6364799 0.0599873 -0.7752639 -0.6287827 0.1483167 -0.8604835 -0.487412 0.1497989 -0.8733325 -0.4635199 0.242867 -0.936788 -0.251881 0.2426577 -0.9324408 -0.2677155 0.01182645 -0.8387171 -0.544439 0.01158362 -0.8389176 -0.5441354 0.036394 -0.8369436 -0.546078 0.03641027 -0.8369256 -0.5461043 0.06024634 -0.8362539 -0.5450229 0.5293631 -0.8475609 0.03762197 0.2233965 -0.8543538 -0.4692267 0.3655245 -0.8931381 -0.2620998 0.3575743 -0.8893672 -0.2848978 0.4736159 -0.8792247 -0.05149859 0.08312958 -0.7712578 -0.6310713 0.2173243 -0.8528992 -0.4746927 0.1851368 -0.8688927 -0.4590752 0.2932519 -0.9217877 -0.2535956 0.2918678 -0.9171024 -0.2715448 0.4528177 -0.8829609 -0.1238396 0.4316732 -0.9000054 -0.06040483 0.386849 -0.9213359 -0.03857487 0.3865033 -0.9220955 0.01884996 0.3121555 -0.9475392 -0.06876599 0.26982 -0.9626141 -0.02390336 0.1303333 -0.9641188 -0.2312752 0.2172822 -0.9625535 -0.1621093 0.1204966 -0.8826922 -0.4542413 0.04960942 -0.8475744 -0.5283528 0.03578484 -0.7762985 -0.629349 0.2523139 -0.3102414 -0.9165632 0.8889367 -0.0495494 -0.4553421 0.9830617 -0.06132823 -0.1727095 0.6577478 -0.03952628 -0.7522006 0.7660204 -0.04481744 -0.6412522 0.4879924 -0.02876985 -0.8723736 0.1217147 -0.1496291 -0.9812221 0.4021545 -0.4941506 -0.7707703 0.6217575 -0.7648854 -0.1684286 0.5548546 -0.681624 -0.476996 0.6308856 -0.775498 0.02421253 0.560853 -0.05901771 -0.8258093 0.5556643 -0.100018 -0.8253689 0.5562884 -0.09977483 -0.8249778 0.5405924 -0.1648911 -0.8249673 0.5409708 -0.1647924 -0.8247388 0.5176149 -0.2277566 -0.8247435 0.5177669 -0.2277354 -0.8246539 0.4873015 -0.2871852 -0.8246587 0.4872067 -0.2871856 -0.8247146 0.4499372 -0.3426501 -0.8247105 0.4496134 -0.3426136 -0.8249022 0.406165 -0.3931205 -0.8249159 0.4056384 -0.3930032 -0.8252309 0.3760185 -0.4205651 -0.8256725 0.3082565 -0.3707602 -0.8760793 0.8500075 -0.07245796 -0.5217635 0.8398732 -0.1511836 -0.5213028 0.8406158 -0.1507003 -0.5202446 0.8168691 -0.2491672 -0.5202313 0.8173486 -0.248935 -0.519589 0.7820557 -0.3441061 -0.5195959 0.782234 -0.3440461 -0.5193673 0.7362075 -0.4338774 -0.5193738 0.73609 -0.4339017 -0.5195197 0.6797848 -0.5176883 -0.5195109 0.6793584 -0.5177299 -0.5200269 0.6137403 -0.5940319 -0.5200472 0.6130225 -0.5940168 -0.5209103 0.5531675 -0.6497976 -0.5213146 0.4792426 -0.5892728 -0.6504492 0.632003 -0.7617234 -0.1426526 0.710782 -0.6888106 -0.1425798 0.7113563 -0.6885047 -0.1411866 0.7873801 -0.6000836 -0.1411817 0.787696 -0.5998659 -0.140343 0.8529382 -0.5027913 -0.1403473 0.85302 -0.5027194 -0.1401076 0.9063531 -0.3986156 -0.1401056 0.9062315 -0.3987523 -0.1405034 0.9471343 -0.2884371 -0.1405016 0.946871 -0.2888149 -0.1414968 0.9744137 -0.1746291 -0.1415014 0.97404 -0.1753306 -0.1431969 0.9870601 -0.07195603 -0.1432994 0.9982046 -0.05913943 0.009498596 0.1585747 -0.009374082 -0.9873026 0.1219435 -0.1497336 -0.9811778 0.1387175 -0.1343536 -0.9811761 0.1388937 -0.1344116 -0.9811432 0.153751 -0.117141 -0.9811415 0.153862 -0.1171612 -0.9811217 0.1665987 -0.0981974 -0.9811229 0.1666339 -0.09819906 -0.9811168 0.1770451 -0.07788193 -0.9811164 0.1770004 -0.07788407 -0.9811244 0.1849725 -0.05637186 -0.9811257 0.1848477 -0.05639481 -0.9811478 0.1901974 -0.0341528 -0.9811517 0.1899924 -0.03421509 -0.9811892 0.1911063 -0.02495664 -0.981252 0.3455362 -0.02045607 -0.9381825 0.9987257 0 0.05046844 0.9985893 0.001815915 0.05306756 0.9983955 -2.89923e-4 0.05662578 0.9979301 -0.002044379 0.06427609 0.99768 0.005300343 0.0678721 0.9980351 3.8599e-4 0.06265693 0.9967136 -5.33038e-5 0.08100748 0.9962819 0.02624905 0.08205741 0.9965308 0.01774621 0.08130997 0.996862 0.007781982 0.07877635 0.9972156 0.001171529 0.07456392 0.6044238 -0.6842994 0.4079293 0.6731531 -0.4286849 0.602573 0.4647465 -0.6690016 0.5800411 0.5155006 -0.6543984 0.5531926 0.5025082 -0.661106 0.5571574 0.5393775 -0.6361694 0.5516889 0.5644785 -0.6015347 0.5652611 0.5579752 -0.6135621 0.5587534 0.5703679 -0.5674868 0.5938345 0.5707747 -0.5781078 0.5831018 0.568789 -0.5896087 0.5734463 0.562507 -0.5501655 0.6171741 0.8171063 -0.5052472 0.2776018 0.8534114 -0.4738214 0.2172151 0.9132311 -0.1934714 0.3585774 0.9797001 -0.1669826 0.1109259 0.965785 0.005593359 0.259284 0.7622765 -0.3361372 0.5531243 0.4732204 -0.288927 0.8322163 0.8293381 -0.4569805 0.3215081 0.5508733 -0.4484947 0.7038403 0.6273215 -0.5986199 0.4981186 0.8067773 -0.05274909 0.5884965 0.7869778 -0.0120728 0.6168633 0.5926303 0.01449906 0.8053441 0.4997144 -0.07704889 0.8627567 0.8711659 -0.06061905 0.4872322 0.8672041 -0.04826486 0.4956082 0.8256677 -0.01157611 0.564038 0.9499095 -0.1516618 0.2732597 0.9301393 -0.08259093 0.3577983 0.9258424 -0.07814693 0.369742 0.9269918 -0.08405011 0.3655432 0.8936817 -0.0525403 0.4456151 0.4626145 -0.8326372 0.304472 0.290092 -0.8734754 0.3910081 0.4295975 -0.8271886 0.3622225 0.3646481 -0.8530267 0.3733328 0.3560879 -0.8583019 0.3694853 0.2685488 -0.8614335 0.4310613 0.2549533 -0.9083474 0.3315177 0.1422933 -0.9120531 0.3845933 0.4114656 -0.8922071 0.1861792 0.01644998 -0.8263583 0.5629045 0.3068462 -0.9479902 0.08461791 0.756977 -0.5637241 -0.330456 0.01078218 -0.4723069 0.8813683 0.6613843 -0.7429638 -0.1028382 0.2402803 -0.7570133 0.6076154 0.30331 -0.8767232 0.3733091 0.9305478 -0.3628088 0.04950231 0.9101558 -0.3724969 -0.1812806 0.7304874 -0.2658954 0.6290373 0.6479084 -0.4166413 0.6376715 0.5949445 -0.3633861 0.7169321 0.6021522 -0.5835041 0.544918 0.6882295 -0.4521579 0.5673565 0.6965212 -0.4801719 0.5331916 0.6965136 -0.4801836 0.533191 0.6977346 -0.5117586 0.5012682 0.6977286 -0.5117658 0.501269 0.6918222 -0.5459067 0.4726181 0.6918219 -0.5459024 0.4726237 0.6790151 -0.5813903 0.4482454 0.6790047 -0.5814049 0.4482422 0.6597002 -0.6171066 0.4289234 0.6597023 -0.6171007 0.4289287 0.4948313 -0.7584285 0.4241794 0.5333735 -0.7385247 0.4124245 0.5333771 -0.7385226 0.4124238 0.5703201 -0.713532 0.4069486 0.4559895 -0.7725762 0.4418142 0.4181602 -0.7804893 0.4647351 0.4181536 -0.780491 0.464738 0.3825881 -0.7819069 0.4921872 0.3825941 -0.7819043 0.4921867 0.4767237 -0.6685227 0.5707995 0.7959722 -0.4873865 0.3590028 0.8056323 -0.4315534 0.4058552 0.8056275 -0.4315524 0.4058657 0.8036466 -0.3798622 0.4581013 0.8036557 -0.379861 0.4580864 0.7900989 -0.3340379 0.5139676 0.7901026 -0.3340265 0.5139691 0.7654312 -0.2956168 0.5715995 0.6345618 -0.6517843 0.4153418 0.6345633 -0.6517837 0.4153404 0.5495209 -0.625226 0.5541834 -0.01443791 -0.8983045 0.4391362 0.06471985 -0.9912883 0.1147127 0.05372565 -0.9025949 0.4271253 0.146383 -0.9170216 0.3710032 0.2375944 -0.8650862 0.4417861 0.237599 -0.8650868 0.4417822 0.3505157 -0.7767755 0.5232194 0.3505057 -0.7767798 0.5232199 0.4539495 -0.6672821 0.5904782 0.6476144 -0.7062416 0.2860395 0.5836747 -0.7364137 0.3420801 0.5626652 -0.8014593 0.2026599 0.537105 -0.7781247 0.3256384 0.4852495 -0.8018391 0.3486934 0.4948298 -0.7584306 0.4241775 0.4559981 -0.7725714 0.4418135 0.4894439 -0.665863 0.5630908 0.7892664 -0.1142131 0.6033358 0.836841 -0.1546676 0.525143 0.8368473 -0.154665 0.5251339 0.8704224 -0.2069603 0.4466904 0.8704203 -0.2069612 0.4466938 0.8888649 -0.2693374 0.3706435 0.8888656 -0.2693373 0.3706418 0.8915601 -0.3397072 0.2995322 0.8915601 -0.3397086 0.2995312 0.9290663 -0.2872725 -0.233046 0.9662466 -0.2565763 -0.0231595 0.7892656 -0.1142148 0.6033366 0.7304801 -0.2658964 0.6290452 0.7654314 -0.2956193 0.5715978 0.6731657 -0.4286742 0.6025665 0.6882303 -0.452159 0.5673546 0.567583 -0.5580564 0.6053286 0.9882797 -0.03610903 0.1483221 0.976214 -0.07867103 0.2020325 0.9784505 -0.06239223 0.1968297 0.9499099 -0.1516618 0.273258 0.9536794 -0.2259482 0.1986029 0.920938 -0.2976236 0.2515822 0.8938103 -0.4450041 -0.05544728 0.8901658 -0.3512506 0.2902205 0.8554587 -0.4390868 0.2745783 0.7959733 -0.4873828 0.3590049 0.7822768 -0.526917 0.3322675 0.7726162 -0.5466706 0.3228241 0.779471 -0.5230509 0.344736 0.7257505 -0.6084166 0.3211162 0.7216322 -0.6189613 0.3100548 0.6757406 -0.6590474 0.3301989 0.6470116 -0.7107033 0.2761827 0.6044273 -0.6842956 0.4079304 0.5703113 -0.7135404 0.4069463 0.5278982 -0.646006 0.5513618 0.03342223 -0.9487206 0.3143444 0.01043069 -0.942791 0.3332211 -0.006192743 -0.948609 0.31639 -7.91806e-4 -0.9410519 0.3382613 4.40846e-4 -0.9373968 0.3482632 -5.97976e-4 -0.9389781 0.3439765 2.44389e-4 -0.9363738 0.3510045 -0.002052724 -0.9384167 0.3454993 -3.90054e-4 -0.9370659 0.3491526 2.351e-4 -0.9363863 0.3509711 0.009670436 -0.9431216 0.3323073 3.16371e-5 -0.9481891 0.3177067 -1.96824e-5 -0.9602755 0.279054 1.11464e-4 -0.960207 0.2792896 -1.13866e-4 -0.9705175 0.2410309 0.004018008 -0.9684999 0.2489817 7.8713e-5 -0.9731174 0.2303102 -1.91556e-4 -0.9792445 0.2026824 2.57637e-4 -0.9790535 0.2036035 -9.4621e-5 -0.9842539 0.176761 7.17327e-7 -0.9841523 0.1773257 6.95364e-7 -0.9875348 0.1574016 1.32282e-4 -0.987463 0.1578509 -1.99176e-4 -0.9921322 0.1251943 1.55627e-7 -0.9983429 0.05754637 -3.48352e-5 -0.9983534 0.057365 6.43793e-5 -0.9964449 0.08424836 7.74974e-4 -0.9962757 0.08622187 -1.17138e-5 -0.9945856 0.1039201 1.37766e-4 -0.9920343 0.1259689 0.04371064 -0.9861925 0.1597307 0.7924184 -0.5539723 0.2553191 0.8201929 -0.516433 0.2461311 0.8500994 -0.4716041 0.2343516 0.8521025 -0.4677789 0.2347434 0.8985229 -0.3864558 0.2081072 0.9059309 -0.3684521 0.2086438 0.9370466 -0.298866 0.1806179 0.9478893 -0.2635675 0.1789923 0.965646 -0.2101792 0.1528156 0.9831553 -0.1169312 0.140474 0.9781569 -0.1588642 0.1340569 0.9929205 -0.04714703 0.1090241 0.9928836 -0.05062115 0.107795 0.9984318 -0.03577113 0.0430637 0.9968492 -0.05893164 0.05309218 0.9900423 -0.1277387 0.05915254 0.974111 -0.2219572 0.04292672 0.9820899 -0.1763066 0.06645035 0.94758 -0.3150842 0.05304825 0.9546049 -0.2908937 0.06411206 0.9112138 -0.4074502 0.06061249 0.9135379 -0.401861 0.06290066 0.8649697 -0.4974992 0.06574124 0.859814 -0.5067961 0.06227093 0.8090848 -0.5836346 0.06893801 0.7939303 -0.6048834 0.0615704 0.7441289 -0.6642912 0.0706374 0.7169613 -0.6944415 0.06097114 0.5056737 -0.8610659 0.05347681 0.629095 -0.7735004 0.0770502 0.5916315 -0.8046398 0.05027014 0.6709969 -0.7380621 0.07090598 0.3999209 -0.9142049 0.06551963 0.4761754 -0.8768185 0.06668007 0.5437378 -0.8357515 0.07660824 0.415686 -0.9079611 0.05302703 0.3221665 -0.943945 0.07194948 0.2882648 -0.9557403 0.0588563 0.2092422 -0.9750286 0.07440984 0.2290703 -0.9715594 0.05999392 0.1355321 -0.9886807 0.064354 0.131325 -0.9894234 0.06160455 0.04236465 -0.9973447 0.05923575 0.04144936 -0.9973463 0.05985361 0.08681976 -0.9944507 0.05941492 0.04777997 -0.9462622 0.3198515 0.03132909 -0.945775 0.3233082 0.1113002 -0.9405003 0.3210478 0.1475331 -0.9325351 0.3295637 0.7901774 -0.5563439 0.2571017 0.7248961 -0.6312977 0.2756609 0.7255884 -0.6304363 0.275811 0.647064 -0.7038306 0.2931395 0.6506786 -0.7000789 0.2941206 0.5577104 -0.7716294 0.3058553 0.5689293 -0.7619443 0.3094518 0.4618307 -0.8293799 0.3143905 0.4817498 -0.8151187 0.3217119 0.3608348 -0.8765285 0.3185847 0.3906541 -0.858973 0.3309908 0.2560881 -0.9127616 0.3182536 0.2972055 -0.8931623 0.3375353 0.2046465 -0.9239442 0.3231826 0.9954252 -0.0448271 0.08437585 0.9962016 -0.03447788 0.07996195 0.9873704 -0.1248555 0.09752404 0.9871817 -0.1258979 0.09809255 0.969576 -0.2161065 0.1149802 0.9692823 -0.2171222 0.1155413 0.9422442 -0.3078835 0.1318476 0.9418436 -0.30887 0.1324014 0.9050492 -0.3987928 0.1478187 0.9045468 -0.399731 0.1483585 0.8579548 -0.4873211 0.1625787 0.8573488 -0.4882116 0.1631033 0.8012294 -0.5719392 0.1758327 0.8005294 -0.5727636 0.1763364 0.7354781 -0.6511415 0.1873151 0.7346819 -0.6519004 0.1877992 0.6616086 -0.7235595 0.1968141 0.6607317 -0.7242361 0.1972706 0.5808083 -0.7880206 0.2041703 0.5798587 -0.7886084 0.2045987 0.4944692 -0.8436191 0.2093018 0.4934591 -0.8441115 0.2096996 0.4041201 -0.8897528 0.2121955 0.4030554 -0.890148 0.2125629 0.3113257 -0.9261454 0.2129106 0.3102256 -0.9264376 0.213245 0.217625 -0.9528278 0.2115621 0.2164936 -0.9530182 0.2118652 0.1244465 -0.970111 0.2083213 0.1232982 -0.9701995 0.2085918 0.04166042 -0.9780927 0.2039586 0.03697055 -0.9781001 0.2048254 0.9946696 -0.04557865 0.09249407 0.9956822 -0.03311657 0.08671903 0.9864348 -0.123664 0.1079525 0.9862058 -0.1248567 0.1086693 0.9682703 -0.2140957 0.1289028 0.9679165 -0.2152644 0.1296107 0.9405683 -0.3050585 0.1492334 0.9400903 -0.3061898 0.1499271 0.9030147 -0.395154 0.1685761 0.9024098 -0.3962449 0.1692529 0.855573 -0.4828979 0.1865596 0.8548473 -0.483928 0.1872163 0.7985201 -0.5667678 0.2028297 0.7976835 -0.5677197 0.2034588 0.7324649 -0.6452733 0.2170662 0.7315196 -0.6461435 0.2176645 0.6583264 -0.7170527 0.2290019 0.6572859 -0.7178263 0.2295665 0.5772947 -0.7809447 0.2384462 0.5761675 -0.7816157 0.2389729 0.4907636 -0.8360542 0.2452847 0.4895619 -0.8366157 0.2457711 0.4002553 -0.8817878 0.2494921 0.3989982 -0.882232 0.2499344 0.3073537 -0.9178634 0.2511186 0.3060432 -0.9181911 0.2515208 0.213579 -0.9443171 0.2502985 0.2122421 -0.9445236 0.250656 0.1203705 -0.9614547 0.2472161 0.1190083 -0.9615432 0.2475317 0.03858107 -0.9693142 0.2427785 0.03591603 -0.9693072 0.2432152 0.9938452 -0.04628634 0.1006447 0.9951289 -0.03173792 0.09333491 0.9854238 -0.1222776 0.1182717 0.9851526 -0.1236098 0.1191432 0.9668515 -0.2117593 0.1426759 0.9664369 -0.2130653 0.1435381 0.9387468 -0.3017544 0.1664291 0.938188 -0.303023 0.1672739 0.9007947 -0.3909064 0.1891061 0.9000946 -0.3921181 0.1899289 0.8529691 -0.4777309 0.2102779 0.852132 -0.4788743 0.21107 0.7955612 -0.5607135 0.2295275 0.7945898 -0.5617781 0.2302883 0.7291712 -0.6383998 0.2464856 0.728082 -0.6393641 0.2472046 0.6547387 -0.7094244 0.2608336 0.6535394 -0.7102822 0.2615063 0.5734499 -0.7726496 0.2723382 0.5721516 -0.7733907 0.2729644 0.4867021 -0.827186 0.2808641 0.4853204 -0.8278025 0.281438 0.3960338 -0.8724405 0.2863653 0.3945754 -0.8729296 0.2868871 0.3029974 -0.9081469 0.2888981 0.3014984 -0.9084977 0.2893626 0.209151 -0.9343277 0.2885959 0.2076056 -0.9345455 0.2890062 0.1159027 -0.9512933 0.2856707 0.1143416 -0.9513757 0.2860252 0.03524249 -0.9590092 0.2811751 0.03471803 -0.9590064 0.2812498 0.9967293 -0.04326534 0.06825792 0.9971339 -0.03697246 0.06600815 0.9889971 -0.1266982 0.07637047 0.9888882 -0.1273629 0.07667344 0.9718323 -0.219133 0.08673495 0.9716582 -0.2197848 0.08703458 0.945123 -0.3121138 0.09657859 0.9448851 -0.3127425 0.09687334 0.9085431 -0.4041983 0.1057037 0.9082385 -0.4048063 0.1059936 0.8620333 -0.4938831 0.113922 0.861666 -0.4944581 0.1142058 0.8058618 -0.5795966 0.1210564 0.8054323 -0.5801357 0.1213326 0.7406144 -0.6598275 0.1269565 0.7401294 -0.6603204 0.1272225 0.6671988 -0.7331798 0.1315042 0.666665 -0.7336194 0.131759 0.5867929 -0.7984673 0.1346263 0.5862116 -0.7988535 0.1348679 0.5007801 -0.8547766 0.1362947 0.5001572 -0.8551047 0.1365238 0.4106863 -0.901497 0.1365283 0.4100301 -0.9017632 0.1367425 0.3180736 -0.9383493 0.1353882 0.3173969 -0.9385496 0.1355875 0.2244959 -0.9653601 0.1329717 0.2237987 -0.9654966 0.1331565 0.1313617 -0.9828518 0.1294082 0.1306568 -0.9829235 0.1295775 0.04709035 -0.9910069 0.1252508 0.03862553 -0.9911289 0.1271679 0.9972782 -0.04246479 0.06027442 0.9975404 -0.03808456 0.05884575 0.9896839 -0.1273247 0.06568413 0.9896128 -0.1277809 0.06586927 0.9727732 -0.2201402 0.07246154 0.9726585 -0.2205864 0.07264542 0.9463191 -0.3134942 0.0787512 0.9461575 -0.3139346 0.07893735 0.909984 -0.4059588 0.0844196 0.9097794 -0.4063792 0.08460187 0.8637138 -0.4960023 0.08933204 0.863463 -0.4964065 0.08951175 0.80776 -0.5820696 0.0933749 0.8074742 -0.5824382 0.09354788 0.7427194 -0.6626199 0.09645122 0.7423921 -0.662962 0.09662038 0.6694876 -0.7362641 0.09849673 0.6691244 -0.7365722 0.09866058 0.5892354 -0.8018141 0.09947854 0.5888438 -0.8020823 0.09963542 0.5033521 -0.8583456 0.09939551 0.5029335 -0.8585737 0.09954482 0.4133617 -0.9052473 0.09828305 0.412918 -0.9054343 0.09842473 0.3208244 -0.9422401 0.09620535 0.3203625 -0.9423835 0.0963391 0.2272862 -0.9693531 0.09324973 0.2268172 -0.969451 0.09337449 0.1341753 -0.9869057 0.08952146 0.1336936 -0.9869605 0.08963912 0.0494433 -0.9951111 0.08549511 0.03916639 -0.9953478 0.08802729 0.9961116 -0.04405301 0.07629674 0.9966871 -0.03575706 0.07305049 0.9882242 -0.1258798 0.08699017 0.9880784 -0.1267287 0.08741325 0.9707654 -0.2177891 0.1009082 0.9705326 -0.2186276 0.101334 0.9437638 -0.3102424 0.1142787 0.9434456 -0.311055 0.1146968 0.9068983 -0.401805 0.1268401 0.9064902 -0.4025949 0.1272518 0.8601118 -0.4909874 0.138344 0.8596277 -0.4917221 0.1387431 0.8036793 -0.5762225 0.14855 0.8031148 -0.5769093 0.1489375 0.7381964 -0.6560012 0.1572533 0.7375587 -0.6566296 0.1576226 0.66457 -0.7289425 0.1642853 0.6638644 -0.7295057 0.1646372 0.5839824 -0.793866 0.1695331 0.5832117 -0.7943611 0.1698669 0.4978135 -0.8498666 0.1729409 0.4969972 -0.8502808 0.1732531 0.4076002 -0.8963305 0.17451 0.406742 -0.8966639 0.1748 0.3149065 -0.9329808 0.1743009 0.3140136 -0.933232 0.1745671 0.2212701 -0.9598492 0.1724209 0.2203526 -0.9600163 0.1726661 0.1281177 -0.9772503 0.1690198 0.1271868 -0.9773337 0.169241 0.05739808 -0.9845339 0.1655253 0.03916281 -0.9830808 0.1789369 0 -0.6051636 -0.7961012 0 -0.605164 -0.7961009 -0.005594849 -0.6051785 -0.7960702 -0.01373082 -0.6581673 -0.7527466 -0.02583396 -0.5065506 -0.8618232 0 0.9999999 -5.0876e-4 0.005593895 -0.6053557 -0.7959353 0.013206 -0.5513489 -0.8341703 0.02765208 -0.7007883 -0.7128333 -9.80637e-7 1 6.4564e-6 0 1 -1.78572e-6 0 1 1.45759e-6 0 1 3.18122e-6 8.36227e-6 1 9.43058e-6 5.48155e-6 1 0 5.82262e-6 1 7.76981e-6 -9.35079e-5 1 -2.71604e-6 -1.71214e-4 1 -5.33135e-5 1.4372e-5 1 5.60492e-6 9.72499e-6 1 8.91064e-6 7.43101e-6 1 8.86839e-6 0 1 -1.79701e-6 0 1 -3.80959e-6 3.47257e-4 1 -1.51829e-4 1.06919e-4 1 -5.85535e-7 0.7059016 0.3470013 0.6174893 0.7272334 0.2463126 0.640673 0.7436456 0.1464877 0.6523287 0.7498158 0.04687279 0.6599843 0.7487112 0.04887521 0.6610922 0.6987274 0.04890137 0.7137147 0.6812843 0.06708431 0.7289386 0.6605732 0.04891926 0.7491662 0.6006665 0.04886019 0.7980053 0.4889339 0.08243107 0.8684174 0.5380229 0.04892188 0.8415094 0.6006723 0.04886114 0.7980009 0.5091757 0.04886656 0.8592743 0.4083846 0.04886198 0.9115014 0.4012993 0.03635519 0.9152252 0.2994326 0.05988305 0.9522365 -0.05434244 0.05331814 0.9970979 0.05456668 0.04475712 0.9975066 0.0658589 0.06071335 0.9959802 0.1284606 0.04641366 0.990628 0.184548 0.06355422 0.9807665 0.195625 0.0488851 0.9794597 0.2920051 0.0488792 0.9551669 0.7031798 0.3499034 0.6189555 0.6396904 0.3497989 0.6844246 0.639687 0.3497952 0.6844297 0.563399 0.3497612 0.7484977 0.5633999 0.3497691 0.7484933 0.4775925 0.3497382 0.8059706 0.4775962 0.3497292 0.8059723 0.3830496 0.349704 0.8549739 0.383053 0.3497042 0.8549721 0.2810362 0.3496819 0.8937233 0.2810404 0.3496802 0.8937226 0.1732492 0.3496649 0.9207167 0.1732558 0.3496709 0.9207131 0.06181824 0.3496627 0.934834 0.06179809 0.349654 0.9348386 -0.05098479 0.3496541 0.9354906 -0.05098664 0.3496599 0.9354884 -0.1626645 0.3496679 0.9226444 -0.1626639 0.3496645 0.9226459 -0.2709022 0.3496795 0.896848 -0.2709061 0.3496759 0.8968483 -0.3735387 0.3496994 0.8591736 -0.3735504 0.3496922 0.8591715 -0.468877 0.3497207 0.8110794 -0.4688753 0.3497263 0.8110781 -0.555566 0.3497563 0.7543321 -0.5555561 0.3497614 0.7543371 0.725275 0.2488776 0.6419005 0.6613582 0.2487692 0.7076152 0.6613532 0.2487726 0.7076187 0.5824867 0.2487445 0.7738446 0.5824829 0.2487419 0.7738483 0.4937641 0.2487174 0.8332687 0.4937686 0.248729 0.8332626 0.3960285 0.2487073 0.8839153 0.3960183 0.248707 0.8839199 0.2905533 0.2486892 0.9239764 0.2905488 0.2486871 0.9239785 0.1791203 0.2486754 0.9518805 0.1791226 0.2486795 0.951879 0.0638985 0.2486734 0.9664775 0.06388938 0.2486695 0.966479 -0.05270332 0.2486689 0.9671537 -0.05271518 0.248659 0.9671556 -0.1681776 0.2486645 0.9538775 -0.1681669 0.2486737 0.953877 -0.2800769 0.2486847 0.9272071 -0.2800693 0.2486822 0.9272101 -0.386197 0.2486988 0.8882572 -0.3861988 0.2486973 0.8882568 -0.4847487 0.248719 0.838545 -0.4847488 0.2487182 0.8385451 -0.5743783 0.2487429 0.7798824 -0.574374 0.2487507 0.7798832 0.742634 0.1479647 0.6531472 0.6753121 0.147919 0.7225466 0.6753107 0.1479165 0.7225484 0.5947703 0.1479013 0.7901732 0.5947768 0.1479066 0.7901673 0.5041841 0.1478919 0.8508388 0.5041787 0.147881 0.8508437 0.4043721 0.1478673 0.9025622 0.4043781 0.1478725 0.9025587 0.2966738 0.1478618 0.9434626 0.2966785 0.1478613 0.9434612 0.1828987 0.1478539 0.9719504 0.1828952 0.1478415 0.9719529 0.06523913 0.1478374 0.9868577 0.06525355 0.1478588 0.9868535 -0.05382752 0.1478589 0.9875426 -0.05382066 0.1478567 0.9875433 -0.1717185 0.1478599 0.9739868 -0.1717253 0.1478469 0.9739876 -0.2859737 0.1478545 0.946762 -0.2859773 0.1478693 0.9467586 -0.3943369 0.1478799 0.9069896 -0.3943423 0.1478769 0.9069877 -0.494972 0.1478888 0.856231 -0.4949735 0.1478897 0.8562301 -0.5864866 0.1479045 0.7963402 -0.5865013 0.1478923 0.7963317 -0.6567251 0.0489372 0.7525407 -0.5786786 0.04883199 0.8140926 -0.592938 0.01622867 0.8050846 -0.4844703 0.07450383 0.8716294 -0.4998836 0.04887902 0.8647122 -0.3960688 0.04886764 0.9169197 -0.3983144 0.04498529 0.9161452 -0.2864892 0.05265545 0.9566354 -0.288803 0.0488708 0.9561405 -0.1900231 0.04891097 0.9805606 -0.173227 0.06855267 0.9824932 -0.131012 0.04894065 0.9901722 -0.05722045 0.04886716 0.997165 -0.695205 0.04894787 0.717143 -0.6739192 0.06737202 0.7357268 -0.6680216 0.147915 0.7292931 -0.6680294 0.1479097 0.729287 -0.6542195 0.248771 0.7142198 -0.6542204 0.2487745 0.7142177 -0.6327855 0.3497884 0.6908188 -0.6327851 0.349792 0.6908174 -0.7458561 0.06412154 0.6630137 -0.7561959 0.04885858 0.6525187 -0.729637 0.1629064 0.6641471 -0.7391622 0.1479305 0.6570813 -0.7267988 0.233096 0.6460881 -0.7178572 0.2488948 0.6501788 -0.7131143 0.3348159 0.6159272 -0.70016 0.3498256 0.6224132 -0.9220737 0.3663651 0.1247261 -0.9283935 0.3159654 0.19558 -0.8925916 0.3986012 0.210707 -0.8830172 0.3868908 0.2656998 -0.8806001 0.3676448 0.2989662 -0.8701905 0.3806357 0.3128657 -0.8558727 0.3525494 0.3784057 -0.8448737 0.3608939 0.3948974 -0.8249494 0.3406571 0.4510115 -0.814665 0.3463521 0.4651466 -0.7872003 0.3346027 0.5180315 -0.7807483 0.3383487 0.5253118 -0.7506837 0.3340199 0.5700041 -0.7486306 0.3349231 0.5721702 -0.831882 0.0639376 0.5512571 -0.9487521 0.2374885 0.2084921 -0.9902637 0.1277906 0.05520415 -0.9833241 0.08624923 0.1601087 -0.8869251 1.03335e-4 0.4619135 -0.9179043 0.02074575 0.3962593 -0.9281332 -0.08441895 0.3625496 -0.9565539 0.06130516 0.2850375 -0.9721695 0.03160935 0.2321366 -0.984519 0.06593805 0.1624026 -0.9893986 0.03573226 0.1407607 -0.9380023 0.3464601 0.01081824 -0.9478712 0.2856513 0.1412223 -0.9205436 0.3454056 0.1824685 -0.9177246 0.2960042 0.2648834 -0.9177243 0.2960025 0.2648863 -0.9010872 0.2554205 0.3504319 -0.9010899 0.2554184 0.3504263 -0.8711371 0.2248713 0.436524 -0.8711345 0.2248741 0.4365277 -0.8287736 0.205289 0.520568 -0.8287723 0.2052904 0.5205692 -0.8065193 0.2020349 0.5556155 -0.7772642 0.2332634 0.5843361 -0.9669123 0.2231273 0.123672 -0.9631696 0.1741591 0.2048729 -0.9631703 0.1741583 0.2048705 -0.9431341 0.1252733 0.307904 -0.943132 0.1252754 0.3079092 -0.9070571 0.08848458 0.4116041 -0.9070591 0.08848351 0.4116 -0.8753948 0.0733397 0.477813 -0.8550496 0.07221561 0.513493 -0.8054401 -0.00561434 0.5926508 -0.7904575 0.1631142 0.5903988 -0.9535575 0.2970863 0.04967707 -0.981953 0.1798937 0.05836725 -0.9246308 0.3775069 0.05046403 -0.9387739 0.3402655 0.05406576 -0.9380376 0.3402585 0.06564748 -0.938037 0.3402603 0.06564772 -0.967969 0.2391971 0.076294 -0.9957293 0.03577607 0.08510732 -0.9963719 0.06550651 0.054331 -0.9954177 0.06550484 0.06966364 -0.9954181 0.06549876 0.06966251 -0.9944822 0.06549811 0.08194661 -0.9879899 0.1278739 0.08674263 -0.9342861 0.3474659 0.07985556 -0.9370184 0.3402651 0.0788424 -0.9749423 0.205509 0.08516836 -0.9762672 0.2055102 0.06832289 -0.9762677 0.2055078 0.06832236 -0.9772709 0.2055079 0.05203986 -0.9966562 0.06009668 0.05536258 0 0 -1 0 0 -1 -1.53386e-6 0 -1 -4.35264e-7 0 -1 -1.73179e-6 -2.54235e-6 -1 6.06767e-7 0 -1 3.0522e-6 0 -1 -1.87082e-6 -1.32165e-7 -1 1.51878e-6 -1.42045e-7 -1 0 -1.63795e-7 -1 0 -1.63795e-7 -1 -4.11896e-6 -1.52914e-7 -1 0 -1.48703e-7 -1 5.5972e-7 0 -1 1.75509e-6 -1.28118e-6 -1 -5.71484e-6 0 -1 -1.79035e-5 0 -1 -1.80476e-6 0 -1 2.78563e-7 0 -1 3.99841e-5 0 -1 -8.79504e-7 0 -1 3.49209e-6 -1.63732e-7 -1 -2.75931e-6 -1.60814e-7 -1 2.4104e-6 -1.58939e-7 -1 -1.71231e-6 -1.54386e-7 -1 2.83864e-6 -1.46454e-7 -1 -8.18039e-7 -1.33848e-7 -1 1.18567e-6 0 -1 -4.58959e-6 0 -1 -4.2628e-6 0 -1 0 -2.82211e-7 -1 0.9199289 0.375105 -0.114136 0.9254369 0.3501691 -0.1447348 0.8821503 0.3617272 -0.301603 0.8281648 0.3390043 -0.4463399 0.8074041 0.2795874 -0.5195475 0.7630128 0.2916791 -0.5768317 0.332628 0.143647 -0.9320538 0.4650896 0.1993402 -0.8625284 0.5344485 0.184959 -0.8247152 0.6213389 0.2593411 -0.7393782 0.7053134 0.294893 -0.6446481 0.03076237 0.01379024 -0.9994317 0.1915327 0.06785947 -0.9791375 0.9448274 0.2939893 -0.1444706 0.9448462 0.2946416 -0.1430109 0.8161788 0.2539396 -0.5190057 0.8165636 0.2546045 -0.5180739 0.540535 0.1681858 -0.8243395 0.5409166 0.1686133 -0.8240017 0.9735661 0.1780966 -0.1430059 0.9736265 0.1784954 -0.1420949 0.8413835 0.1539131 -0.5180586 0.8416554 0.1542732 -0.5175096 0.5573552 0.101956 -0.8239905 0.5576225 0.1021855 -0.8237811 0.9880632 0.05948561 -0.1421008 0.9864133 0.05379086 -0.1552272 0.8536512 0.05735969 -0.5176771 0.8446276 0.04867005 -0.5331376 0.5656315 0.03642505 -0.8238533 0.5649055 0.03593415 -0.8243728 0.1982875 0.0101813 -0.9800911 0.1804413 0.0693745 -0.9811362 0.1849233 0.05751997 -0.9810682 0.1850684 0.05765694 -0.9810328 0.1906961 0.03487247 -0.9810295 0.190785 0.03494232 -0.9810098 0.1935476 0.01215314 -0.9810156 -0.4425686 0.1944755 -0.8753927 -0.8876065 0.2154567 -0.4071034 -0.7890072 0.322695 -0.5228151 -0.8943483 0.3669446 -0.2559157 -0.9316932 0.3310813 -0.1494421 -0.9328774 0.329313 -0.1459202 -0.925247 0.3775347 -0.03722274 -0.9895479 0.05959832 -0.1313132 -0.9875754 0.06432104 -0.1433797 -0.1757733 0.07152694 -0.9818287 -0.2928677 0.05376189 -0.9546404 -0.129214 0.05795401 -0.9899218 -0.7998501 0.2859427 -0.5277088 -0.7039074 0.294341 -0.6464348 -0.5172572 0.2156916 -0.8282042 -0.6605938 0.1415272 -0.7372829 -0.5998439 0.1677433 -0.7823359 -0.05467504 0.003296256 -0.9984988 -0.2317606 0.0389595 -0.9719924 -0.1893763 0.01653295 -0.9817654 -0.551099 0.02718436 -0.833997 -0.5613161 0.02780461 -0.8271343 -0.5509963 0.03319382 -0.8338473 -0.8521488 0.05143779 -0.5207654 -0.8585746 0.04613333 -0.5106089 -0.858575 0.04613429 -0.510608 -0.973513 0.178119 -0.143339 -0.973322 0.1784584 -0.1442112 -0.8397639 0.153632 -0.5207628 -0.8393697 0.1538795 -0.5213249 -0.552574 0.1010923 -0.8273103 -0.5522392 0.1012182 -0.8275184 -0.1872292 0.03424602 -0.9817192 -0.1871159 0.03427559 -0.9817398 -0.9448612 0.2940031 -0.1442202 -0.9444676 0.2945385 -0.1456986 -0.8148172 0.2535287 -0.5213407 -0.8141345 0.2538506 -0.5222498 -0.536076 0.1667975 -0.8275272 -0.5355052 0.1669334 -0.8278692 -0.1816314 0.05650281 -0.9817422 -0.1814432 0.05652964 -0.9817754 0.9342778 0.3522956 0.05488961 0.9243292 0.3773442 0.05680686 0.9656532 0.2543794 0.05296283 0.9530991 0.2969555 0.05847787 0.986547 0.1537004 0.05568945 0.9819383 0.1798544 0.05873388 0.9953958 0.05140364 0.08090037 0.9966128 0.05140542 0.06419122 0.9947873 0.08388924 0.05797272 0.9967868 0.06008374 0.05297178 0.9961892 0.03583073 0.07951951 0.9847161 0.1536999 0.08191806 0.9886169 0.1279866 0.07909584 0.9638297 0.2543885 0.07949149 0.967791 0.2393404 0.07808238 0.932772 0.3522913 0.07633697 0.934612 0.3474629 0.07596009 0.4981539 0.1368609 0.8562195 0.9771065 0.07010793 0.2008677 0.7759229 0.3428058 0.5295544 0.8275263 0.3698635 0.4223757 0.8583169 0.3892778 0.3342977 0.8570609 0.3707079 0.3578022 0.8916561 0.3492975 0.2879944 0.8961324 0.3592118 0.2606025 0.9138598 0.3386636 0.2239807 0.9260461 0.3432846 0.1568262 0.9261359 0.3417102 0.1597072 0.9298959 0.3391929 0.1422734 0.9326688 0.3474728 0.09691047 0.9876683 0.1279922 0.09016382 0.9854668 0.06537222 0.1567853 0.9912739 0.03581756 0.1268591 0.9483339 0.0222091 0.3164961 0.946457 -0.003724634 0.3228083 0.9127731 0.02628856 0.4076201 0.9102244 0.04322636 0.4118531 0.88862 0.02758747 0.4578138 0.8017656 0.1245397 0.5845186 0.8597747 0.04277968 0.5088788 0.8560935 0.05319428 0.5140764 0.8147957 0.05227094 0.5773872 0.8115342 0.05625969 0.5815902 0.7849932 0.04696995 0.6177213 0.7568023 0.3676384 0.5404557 0.5232743 0.3328775 0.7844595 0.7694651 0.3062921 0.560454 0.9759727 -0.01561951 0.2173324 0.9755107 0.06483042 0.2101811 0.947999 0.08792066 0.3058887 0.9510074 0.07936644 0.2988079 0.9146155 0.1072054 0.3898531 0.9146164 0.1072025 0.3898519 0.8691181 0.1448472 0.4729197 0.8691173 0.1448499 0.4729205 0.8155826 0.1914108 0.546065 0.8155825 0.1914158 0.5460634 0.8204531 0.1865635 0.5404171 0.775328 0.2463387 0.5815358 0.950879 0.2379242 0.1980436 0.9788552 0.19475 0.06257122 0.9622147 0.2028994 0.1815894 0.9622159 0.2028977 0.1815855 0.940274 0.2173309 0.2620159 0.9402759 0.2173263 0.2620128 0.9100642 0.2404434 0.3375949 0.9100635 0.2404453 0.3375956 0.8722937 0.2716943 0.4065539 0.8722898 0.2717009 0.4065577 0.8278514 0.3103501 0.4672738 0.8278509 0.3103508 0.4672743 0.8025015 0.3341551 0.4942993 0.7663095 0.4805943 0.426379 0 -1 -1.84868e-6 0 -1 1.22819e-5 -0.04588705 0 0.9989466 -0.06400567 0.008307754 0.997915 -0.1503152 -0.007086753 0.9886128 -0.2441966 0.02904105 0.9692908 -0.1948984 -0.01129555 0.9807584 -0.2714574 -5.3002e-6 0.9624505 -0.3036199 9.49162e-6 0.9527933 -0.3085423 8.46111e-4 0.9512103 -0.350506 -0.001245319 0.9365597 -0.4308459 0.02002608 0.9022033 -0.3945533 -0.0171864 0.9187123 -0.5167334 0.01091372 0.8560768 -0.5009867 -6.31525e-5 0.865455 -0.5706092 2.75278e-5 0.8212218 -0.5570881 -0.004385888 0.830442 -0.6073367 0.006379306 0.7944189 -0.593138 -0.001222491 0.8051 -0.6740128 0.002095639 0.7387168 -0.6713944 -0.001077175 0.7410996 -0.7431177 5.66651e-4 0.6691606 -0.7422881 -2.73852e-5 0.6700809 -0.7844642 2.62616e-5 0.6201743 -0.7842055 -1.56636e-4 0.6205013 -0.8169915 1.25203e-4 0.5766499 -0.82552 0.005974054 0.5643414 -0.8653126 -0.01133018 0.5011044 -0.9846481 0 0.1745511 -0.9846816 8.37893e-4 0.1743605 -0.9646332 -5.02086e-4 0.2635953 -0.9599133 -0.02436804 0.2792359 -0.9368954 0.0185967 0.349115 -0.9290846 -6.151e-5 0.3698673 -0.9138448 1.32561e-5 0.406064 -0.9059531 -0.004040718 0.4233588 -0.8802197 0.01681995 0.4742683 -0.8514893 -0.03612321 0.5231264 0.9101449 1.36317e-5 0.4142901 0.9274131 -2.62369e-5 0.3740389 0.9842698 0 0.176672 0.9835293 0.007786035 0.1805814 0.9566497 -0.007195234 0.2911521 0.9632169 -0.03994023 0.2657405 0.9368175 0.01802062 0.3493542 0.9134922 -0.002859652 0.4068465 0.8795183 0.008719563 0.4757853 0.8740373 -0.00673449 0.4858123 0.8322995 0.002377271 0.5543214 0.806952 -0.012205 0.5904909 0.7916775 9.76199e-6 0.6109392 0.76448 -2.63803e-6 0.6446475 0.7499768 3.71376e-4 0.6614641 0.7445709 -0.002001106 0.6675406 0.6825995 0.005699932 0.7307705 0.6800311 0.002645075 0.7331784 0.5935545 -0.002039313 0.8047913 0.5897285 1.63236e-5 0.8076016 0.5356196 -7.67609e-6 0.8444594 0.543501 0.001464128 0.8394073 0.4665939 -0.006850659 0.8844451 0.4815938 0.006992816 0.8763667 0.3734976 -0.004491746 0.9276203 0.3713015 -0.003555774 0.9285056 0.3021107 0.001856207 0.953271 0.3103111 1.23285e-5 0.9506351 0.2465493 -5.01084e-6 0.9691303 0.2483102 -6.54174e-4 0.9686804 0.1803251 4.4415e-4 0.9836069 0.144982 0.009345293 0.9893901 0.1231163 0.001631677 0.992391 0.04588973 -0.001854896 0.9989449 0.0461778 -0.001967668 0.9989313 0.004763484 0 0.9999887 0.06762337 0.9977109 -2.82578e-4 0.11189 0.9937152 -0.003286898 0.07340526 0.9973011 0.001552164 0.125952 0.9920364 -1.10442e-4 0.1410183 0.9900071 3.46309e-5 0.1447946 0.9894618 5.63682e-6 0.1629053 0.9866417 6.04148e-6 0.1603671 0.9870575 1.09131e-4 0.252907 0.9674825 0.003980576 0.2336784 0.9723119 0.002028822 0.2060164 0.9785486 3.77629e-4 0.1821814 0.9832649 -4.53766e-5 0.3244422 0.9457679 -0.01613497 0.3629563 0.9318026 -0.002580106 0.3834829 0.9235481 2.54471e-4 0.2812252 0.9589081 -0.03752046 0.3304334 0.943807 -0.006505489 0.3500822 0.9367102 0.004055261 0.3439407 0.9389881 0.002521812 0.340941 0.9400823 0.002124011 0.3403066 0.9403124 0.002049863 0.3355981 0.942004 0.001568317 0.325023 0.9457059 7.77362e-4 0.3180553 0.9480721 4.64537e-4 0.1984958 0.980098 -0.002735912 0.2395546 0.9708829 -1.16971e-4 0.2746798 0.9615358 7.51676e-5 0.2774804 0.9607314 1.99228e-4 0.2970822 0.954852 -8.87499e-5 0.3126698 0.949862 2.43048e-4 0.0225107 0.9997466 1.95172e-4 0.01836204 0.9998314 3.22654e-6 -0.02250814 0.9997467 4.02346e-6 -0.01837354 0.9998313 2.39176e-4 -0.06760293 0.9977124 -2.82007e-4 -0.07340532 0.997302 -6.75341e-4 -0.1123789 0.9936654 3.20035e-4 -0.1111746 0.9938009 3.58427e-4 -0.1212841 0.9926179 6.84543e-5 -0.1410332 0.990005 -4.06572e-5 -0.1390081 0.9902913 5.65627e-6 -0.1628961 0.9866433 6.71787e-6 -0.1545781 0.9879806 3.44201e-4 -0.1768741 0.9842336 -1.56047e-4 -0.2009884 0.9795936 2.97961e-4 -0.1973968 0.9803237 1.40417e-4 -0.2339826 0.9722408 -1.72178e-4 -0.2240298 0.9745822 4.36471e-4 -0.2516477 0.9678189 -1.31785e-4 -0.2692298 0.963076 2.09143e-4 -0.340188 0.9403526 0.003015577 -0.3381105 0.9411026 0.002699732 -0.2777268 0.9606601 -8.07813e-5 -0.3005933 0.9537525 9.97434e-5 -0.3137156 0.9495168 6.78599e-4 -0.3238436 0.9461098 0.001278638 -0.3339558 0.9425863 0.002201497 -0.3380262 0.9411329 0.002689063 -0.3863694 0.9223442 8.68612e-6 -0.3811705 0.9245048 -6.94536e-5 -0.370111 0.9289863 -0.001594543 -0.3534277 0.9354429 -0.005958795 -0.335767 0.9418666 -0.01216518 -0.3459739 0.9382329 0.004601001 -0.3254798 0.9455227 -0.007066965 -0.2675639 0.9624655 -0.04549384 -0.3079931 0.9510928 -0.0237227 0.8016278 0.4247388 0.4207018 0.7351817 0.6671699 0.1199676 0.7625639 0.6175318 0.1927458 0.7461047 0.6138356 0.2579413 0.7546554 0.5486557 0.3598228 0.881931 0.420184 0.2136427 0.7723276 0.6263251 0.1059581 0.863308 0.4826427 0.1474975 0.854107 0.5078452 0.112226 0.8141711 0.5692992 0.1141219 0.8112136 0.5082814 0.2891068 0.7925588 0.4955478 0.3553633 0.7785028 0.4989031 0.3808267 0.7759183 0.4985033 0.3865818 0.7579932 0.4927493 0.4273694 0.7626896 0.5754988 0.2951372 0.8242889 0.4487192 0.3452519 0.782107 0.5030273 0.3677937 0.76972 0.5515364 0.3214638 0.7602406 0.5636428 0.323019 0.7829734 0.569925 0.2492754 0.7375021 0.6211492 0.2650744 0.752182 0.6030669 0.2655799 0.7313841 0.6019783 0.3204676 0.7949796 0.6051056 -0.04306662 0.7574604 0.6426064 0.1153723 0.7863005 0.5960275 0.1627354 0.786127 0.5953201 0.1661276 0.8103747 0.5439089 0.2178443 0.8103764 0.5439073 0.2178417 0.8175894 0.5170648 0.2533609 0.8173525 0.5161229 0.2560317 -0.9930539 0 0.1176609 -0.9930537 0 0.1176629 -0.7015266 -0.5471754 -0.4565738 -0.705893 -0.6012574 -0.3744391 -0.7072276 -0.5839646 -0.3985155 -0.7065178 -0.5703872 -0.4189168 -0.7081965 -0.6064425 -0.3615042 -0.6992947 -0.6199694 -0.355844 -0.7008949 -0.6168454 -0.3581175 -0.7074154 -0.6303411 -0.3197399 -0.7069622 -0.6319881 -0.3174832 -0.7069659 -0.6317183 -0.3180114 -0.7202096 -0.4380807 -0.5379438 -0.7033709 -0.4984617 -0.5067598 -0.7114015 -0.5527727 -0.4339935 -6.95175e-7 0 1 0 0 1 6.95175e-7 0 1 0.2670866 0.9636245 0.009616672 0.02111166 0.9997768 8.11199e-4 0.3690428 0.9290103 0.02734088 0.6070116 0.7933712 0.04581964 0.741154 0.6680648 0.06618362 0.6913201 0.7203417 0.05642956 0.6604025 0.7498784 0.03938424 0.6822352 0.7295629 0.0478869 0.6983413 0.7138207 0.05272042 0.7107396 0.7012473 0.05569142 0.7324358 0.6782056 0.05979239 0.4498551 0.8924602 0.03384101 0.4289572 0.9032008 0.0149663 0.4834573 0.8746163 0.0362671 0.5771217 0.8154695 0.04404765 0.5432248 0.8392999 0.02196997 0.5694662 0.8212499 0.03545212 0.167518 0.9855958 0.02321106 0.1345273 0.9900534 -0.04119098 0.1861246 0.9825242 0.001994252 0.3103635 0.9491999 0.05190467 0.2644779 0.9638826 -0.03133672 0.323132 0.9462051 0.01678013 0.04737967 0.9988729 0.002854466 0.1685585 0.9856566 0.008311867 0.1787444 0.9838421 0.01025998 0.1273615 0.9918417 0.005390763 0.04747968 0.9988719 7.88815e-4 0.08392441 0.9964503 0.00661832 0.05044138 0.9987219 0.00323081 0.4494373 0.8930392 0.02207309 0.4064397 0.9135212 0.01690447 0.3132008 0.9496077 0.01226633 0.3556296 0.9343203 0.02393996 0.3218933 0.9466131 0.0175668 0.4974824 0.866864 0.03252834 0.4507979 0.8924524 0.01760804 0.5459768 0.8374785 0.0232194 0.5781104 0.8154727 0.02815586 0.5781892 0.8154172 0.02814596 0.7402034 0.6717276 0.02968144 0.7154778 0.6979669 0.03055608 0.6916442 0.7215359 0.03184747 0.6928825 0.720356 0.03164118 0.6489639 0.7603616 0.02638524 0.6080196 0.793501 0.02585172 0.7827139 0.621475 0.0335834 0.7921739 0.609232 0.03601372 0.8267958 0.5615265 0.03311729 0.8562087 0.5154875 0.03434199 0.8727136 0.4866183 0.0396701 0.8558644 0.5159315 0.03620767 0.858394 0.5080996 0.07067298 0.7523547 0.6558396 0.06194275 0.7903329 0.6092125 0.06506955 0.7903323 0.6092135 0.06506937 0.858393 0.5081014 0.07067316 0.8597432 0.5080929 0.05179923 0.04068285 0.9991677 0.002970099 0.04773044 0.9988582 -0.002021074 0.04737955 0.9988729 0.002854704 0.168469 0.9856547 0.01015025 0.1684694 0.9856547 0.01015025 0.312881 0.9496053 0.01885098 0.312881 0.9496053 0.0188511 0.4503331 0.8924483 0.02713263 0.4503338 0.892448 0.02713257 0.5777755 0.8154532 0.03481096 0.5777748 0.8154535 0.0348109 0.6923721 0.7203338 0.04171538 0.6923726 0.7203333 0.04171538 0.7915765 0.6092061 0.04769241 0.7915763 0.6092064 0.04769241 0.8597441 0.5080917 0.05179959 0.8603354 0.5081201 0.04046285 0.9930537 0 0.1176629 0.9930539 0 0.1176607 -0.7685877 0.5343657 0.3517475 -0.7608059 0.6000967 0.2470999 -0.7402328 0.6680353 0.07605463 -0.7710984 0.621914 0.1364932 -0.7922576 0.6051084 0.07856106 -0.7780323 0.6184283 0.1105095 -0.7847873 0.6144568 0.08094304 -0.7907993 0.6091698 0.05957108 -0.7780856 0.6131729 0.1363893 -0.7863845 0.6063575 0.1180263 -0.7978832 0.5950657 0.09633028 -0.7400204 0.632287 0.2293097 -0.7890774 0.5880709 0.1775656 -0.7471081 0.6363995 0.191899 -0.7651877 0.6205222 0.1715809 -0.7470736 0.5920561 0.3022428 -0.7099609 0.6252554 0.3240544 -0.6912459 0.6463566 0.3231136 -0.7474609 0.6097896 0.2635506 -0.7462595 0.6112567 0.2635565 -0.7406465 0.6296027 0.2346128 -0.7779247 0.471711 0.4151169 -0.7872867 0.5035091 0.3558907 -0.8174235 0.4728047 0.3290508 -0.8176165 0.4911972 0.3003805 -0.8319536 0.4789022 0.2801893 -0.850158 0.4628045 0.2510849 -0.7927055 0.543419 0.2762498 -0.8210195 0.5261359 0.2216034 -0.7989433 0.5483725 0.2469358 -0.7989495 0.5483657 0.2469304 -0.8215839 0.5293245 0.2116969 -0.82407 0.5284878 0.2039834 -0.8231561 0.5292036 0.2058099 -0.8438897 0.5129947 0.1571196 -0.8247471 0.5337013 0.1869635 -0.8521231 0.5074203 0.1281049 -0.8520569 0.5075083 0.128197 0.7201443 -0.438124 -0.5379959 0.6869542 -0.5727956 -0.4472128 0.7074302 -0.6303344 -0.3197202 0.7069557 -0.6319642 -0.3175451 0.7074257 -0.5905882 -0.3882712 0.703321 -0.6104829 -0.3642117 0.70324 -0.6106831 -0.3640325 0.7068651 -0.6235507 -0.3339557 0.7071477 -0.6303185 -0.320376 0.7045924 -0.548839 -0.4498059 0.7114968 -0.5526971 -0.4339336 0.7033351 -0.4984866 -0.5067847 -0.08498746 0.9963776 0.002998471 -0.6096836 0.7922225 0.02587419 -0.7415877 0.6680158 0.06166523 -0.722723 0.6887043 0.05794709 -0.7107396 0.7012473 0.05569142 -0.6983413 0.7138207 0.05272042 -0.6817017 0.7300719 0.04772859 -0.6916719 0.7203565 0.05173683 -0.743071 0.6664104 0.06117832 -0.790332 0.6092138 0.06506931 -0.790333 0.6092125 0.06506961 -0.8597421 0.5080948 0.05179941 -0.8603346 0.5081212 0.0404632 -0.8577308 0.5127958 0.03658342 -0.8737699 0.4850752 0.03504616 -0.7287166 0.6841669 0.02979892 -0.7652257 0.6429975 0.031367 -0.7921692 0.6092305 0.03614288 -0.8053398 0.5918319 0.03410357 -0.8456636 0.5326205 0.03418511 -0.6930972 0.7203422 0.02689993 -0.6519436 0.7572987 0.03831946 -0.6908928 0.7222535 0.03189128 -0.4233746 0.9057634 0.01862388 -0.4664383 0.8841961 0.0251528 -0.4506303 0.8924604 0.02114021 -0.5057265 0.8624376 0.02102965 -0.5782886 0.8154675 0.02439302 -0.540452 0.8407338 0.03283673 -0.5778153 0.8156844 0.02808153 -0.3803255 0.9247291 0.01511603 -0.3130627 0.9496119 0.01513761 -0.3405629 0.9399853 0.0210855 -0.1339619 0.99097 0.005725443 -0.1810915 0.9834042 0.0110448 -0.1685348 0.9856565 0.008800745 -0.2281892 0.9735757 0.008950233 -0.292621 0.9561523 0.0120818 -0.009278237 0.999957 3.56045e-4 -0.04737961 0.9988729 0.002854645 -0.02194941 0.9997578 0.001603484 -0.04818016 0.9988043 -0.008298814 -0.06264877 0.9980353 8.76558e-4 -0.1184899 0.9928653 0.01336276 -0.1699855 0.9853789 -0.01155096 -0.1984275 0.9800289 0.01303994 -0.2763823 0.9608008 0.02178704 -0.3136752 0.9495018 0.007369637 -0.3525087 0.9354139 0.02717661 -0.4224994 0.9058575 0.03027456 -0.4505856 0.8924247 0.02347153 -0.4725034 0.8807578 0.03172141 -0.6394222 0.7672289 0.04999101 -0.6098147 0.7912065 0.04602473 -0.5775387 0.8154678 0.03822934 -0.574223 0.8177784 0.03881448 -0.5126659 0.8576345 0.04045677 -0.0390737 0.9992341 0.00207436 -0.04737663 0.9988729 0.002916634 -0.04737955 0.9988729 0.002854526 -0.1684691 0.9856547 0.01015025 -0.1684694 0.9856547 0.01015025 -0.3128809 0.9496053 0.01885098 -0.3128811 0.9496052 0.0188511 -0.4503341 0.8924478 0.02713268 -0.450333 0.8924484 0.02713239 -0.5777751 0.8154535 0.03481078 -0.5777748 0.8154536 0.03481101 -0.6923726 0.7203333 0.04171532 -0.6923725 0.7203334 0.04171538 -0.7915771 0.6092054 0.04769253 -0.791576 0.6092068 0.04769235 -0.8597431 0.5080931 0.05179941 -0.8583943 0.508099 0.07067322 -0.858393 0.5081014 0.07067286 0.6936907 0.7091217 0.1262531 0.5287598 0.8467674 0.05829244 0.570468 0.815703 0.09589177 0.5988363 0.7984485 0.06225222 0.9674339 -0.01180255 0.2528486 0.7181624 0.6719333 0.1809651 0.9342684 0.01576751 0.356222 0.9545906 0.006997227 0.2978389 0.7802092 0.5198979 0.3478216 0.8684514 -0.08552157 0.4883424 0.9066314 0.1559791 0.3920333 0.654702 0.1217316 0.7460206 0.686553 0.3461406 0.6393995 0.6731099 -0.1487807 0.7244222 0.7703225 0.345917 0.5356722 0.7742987 -0.07461857 0.6284057 0.8483056 0.1621827 0.504058 0.6017831 0.09461724 0.7930351 0.5849265 0.3350298 0.7386583 0.5189605 0.04335892 0.8536978 0.4612364 0.2723468 0.8444455 0.4181339 0.08780688 0.9041317 0.5238388 0.8479332 0.08125448 0.5101882 0.8532953 0.1076812 0.4971668 0.8624819 0.09460502 0.4712996 0.8722422 0.1306535 0.4591007 0.8810051 0.114265 0.4247189 0.8928458 0.1498011 0.4146182 0.9004194 0.1316696 0.3712221 0.9137542 0.1650677 0.364037 0.919694 0.1471061 0.3116232 0.9336849 0.1764189 0.3075483 0.9378686 0.1606754 0.2474668 0.951358 0.1835157 0.2465012 0.9530291 0.1759907 0.3169842 0.7903903 0.5242177 0.7985489 0.5745648 0.1794295 0.7810704 0.5811342 0.2285001 0.7734799 0.5941879 0.2206117 0.7319579 0.6110771 0.3013679 0.7239219 0.6260842 0.2897513 0.6700116 0.6464903 0.3648765 0.6627562 0.6617999 0.3503929 0.5966925 0.6846045 0.4186586 0.5910133 0.6989066 0.4027816 0.512677 0.7230318 0.4630199 0.5090743 0.7353377 0.4473498 0.4186135 0.7595246 0.4978807 0.4169899 0.7691722 0.4842454 0.3164193 0.7917823 0.5224556 0.3398462 0.4942449 0.8001416 0.302116 0.1535841 0.9408177 0.3227061 0.2410191 0.9152981 0.3384171 0.5058635 0.7934583 0.4665272 0.4770419 0.7448379 0.465187 0.4632162 0.754342 0.5812814 0.4321163 0.6894835 0.5805218 0.4151902 0.7004368 0.6831452 0.3835068 0.6214782 0.6831874 0.3644546 0.6327937 0.7720358 0.3336958 0.5409326 0.7729149 0.3140113 0.5513615 0.8476383 0.2856336 0.4471272 0.8491948 0.2669721 0.4556251 0.9085468 0.2427463 0.340025 0.9104065 0.2269043 0.3459398 0.9452024 0.2128832 0.2475345 0.8350625 0.5271303 0.1574938 -0.3402792 0.5155081 0.7864233 -0.3123947 0.1672543 0.9351126 -0.9107119 0.3489858 0.2209362 -0.9634987 0.1188455 0.2398878 -0.9358102 -0.2267303 0.2699123 -0.9226784 -0.2734909 0.2717859 -0.5223982 0.8485329 0.08421498 -0.5512979 0.8294833 0.08960092 -0.5695736 0.816392 0.09534311 -0.6175609 0.7737784 0.1410157 -0.515012 0.8514985 0.09855443 -0.5398082 0.8319394 0.1283897 -0.4903522 0.865258 0.1043237 -0.4791528 0.8694919 0.119985 -0.5015772 0.8502698 0.1595673 -0.4232057 0.9002291 0.1023933 -0.4532014 0.8717764 0.1860498 -0.381352 0.9174106 0.113704 -0.3946281 0.8957614 0.2046467 -0.3374719 0.9327064 0.1271677 -0.3273817 0.9205549 0.2130729 -0.2912389 0.9454345 0.1460603 -0.4648153 0.325181 0.8235315 -0.3889361 0.04281049 0.9202696 -0.3123775 0.3544666 0.8813477 -0.5849367 0.3353999 0.7384822 -0.5418791 0.1274393 0.8307384 -0.4871863 0.1422001 0.8616431 -0.7776253 0.28355 0.561158 -0.6889358 -0.06747645 0.7216747 -0.6863095 0.349578 0.6377888 -0.6510718 0.1016401 0.7521801 -0.6004775 0.1172413 0.7910001 -0.8313258 0.5341556 0.1535426 -0.6565475 -0.658922 0.3671066 -0.8315296 0.4897276 0.2621557 -0.7208341 -0.4727445 0.5068638 -0.8144137 0.4284657 0.3913407 -0.8307789 0.05614864 0.5537634 -0.7843418 0.05376511 0.6179947 -0.2417932 0.9548054 0.1728663 -0.2543219 0.9448389 0.2063975 -0.3161703 0.7918385 0.5225209 -0.4151701 0.7696826 0.4849977 -0.4203753 0.7591331 0.4969926 -0.5070577 0.735981 0.4485805 -0.5146447 0.7225384 0.461605 -0.5890787 0.6996132 0.4043857 -0.5985887 0.684066 0.4168277 -0.6610651 0.6624847 0.3522885 -0.6716836 0.6459444 0.3627634 -0.7226428 0.6266422 0.2917311 -0.7332065 0.6106433 0.2992042 -0.7726743 0.5945755 0.2223835 -0.7818537 0.5808514 0.2265316 -0.8381286 0.402253 -0.36842 -0.7697818 0.619157 0.1551797 -0.945608 0.212625 0.2462036 -0.9112197 0.226588 0.3440009 -0.907796 0.243119 0.3417595 -0.8504776 0.2665253 0.4534889 -0.846424 0.2861728 0.4490787 -0.7746042 0.3134694 0.5492954 -0.7704239 0.3343204 0.5428416 -0.6851327 0.3638525 0.6310346 -0.6812754 0.3841031 0.6231603 -0.5825077 0.4145811 0.6991477 -0.5793552 0.4327479 0.6907075 -0.4669645 0.4628482 0.7534691 -0.4647551 0.4774808 0.745664 -0.3388351 0.5057538 0.7933499 -0.3160909 0.7983626 0.5125464 0.239858 -0.1992076 0.9501497 0.98157 -0.05737608 0.1822869 0.1733786 -0.9528006 0.2492202 0.6107475 -0.7433051 0.2729198 0.3944553 -0.8791462 0.2674083 0.5241369 -0.7778949 0.3466412 0.4580925 -0.8227545 0.3364913 -0.1661384 -0.9735234 0.157004 -0.1795041 -0.9748288 0.1322383 0.102302 -0.9531815 0.2845691 0.005040764 -0.97751 0.2108288 0.009176373 -0.9792512 0.2024422 0.4447119 -0.3559565 0.8219041 0.5224826 0.06458121 0.8502007 0.3457191 -0.2949628 0.8907724 0.4223776 0.1156638 0.8990101 0.2235571 -0.2559859 0.9404752 0.6945672 -0.2955279 0.6559267 0.7041768 -0.009418666 0.7099622 0.5719305 -0.3307339 0.7506735 0.6116338 -0.1182158 0.7822589 0.563965 -0.1033918 0.8193008 0.7712355 -0.3396302 0.5383746 0.8072128 -0.1849132 0.5605485 0.759115 -0.1423308 0.6352059 0.9264609 -0.2039138 0.3163693 0.8928182 -0.2413746 0.3802815 0.8465499 -0.3466937 0.4039269 0.8748375 -0.1973298 0.4424029 0.8471155 -0.1859691 0.4978061 0.7412914 -0.6097629 0.2804931 0.7554684 -0.5917814 0.2811805 0.8539687 -0.432179 0.2897566 -0.1387586 -0.9663398 0.2166412 -0.1443192 -0.9689948 0.2005519 -0.1475242 -0.9681404 0.2023381 -0.1568949 -0.9703157 0.1840423 -0.1558305 -0.970649 0.1831871 -0.1686668 -0.971801 0.1647856 -0.1629776 -0.97377 0.1587777 0.1447315 -0.9547665 0.2597571 0.1253077 -0.9461859 0.2983796 0.1436391 -0.9411325 0.3060025 0.1039118 -0.9260584 0.3627926 0.1224678 -0.9195402 0.3734267 0.08000928 -0.9048557 0.4181324 0.09686362 -0.897189 0.4308938 0.05320817 -0.8837011 0.4650176 0.066612 -0.8756692 0.4782952 0.0222721 -0.8637703 0.5033934 0.03158354 -0.8562091 0.5156633 0.3863656 -0.8635194 0.3241236 0.3454105 -0.8462283 0.4056962 0.3624255 -0.8363255 0.4113482 0.3048452 -0.814446 0.4937077 0.3221268 -0.8027822 0.5017721 0.2582276 -0.7805801 0.5692217 0.2739463 -0.7679968 0.578908 0.2051246 -0.7466779 0.6327686 0.2178507 -0.7341538 0.6430858 0.1446465 -0.7144458 0.6845763 0.1536307 -0.7032464 0.6941485 0.6266135 -0.7352192 0.2584731 0.5912595 -0.719222 0.3648726 0.6035035 -0.7081845 0.3664129 0.544267 -0.6839933 0.4857229 0.5588034 -0.6698581 0.4889059 0.4871858 -0.642573 0.5913966 0.5020012 -0.6265699 0.5961586 0.4207407 -0.598291 0.6819275 0.4343695 -0.5815103 0.6878728 0.3448277 -0.5536938 0.7579692 0.3559322 -0.5376432 0.7643639 0.2585275 -0.5114061 0.8195288 0.266523 -0.4974881 0.8255126 0.1517633 -0.471231 0.8688551 0.07945019 -0.6865649 0.7227145 -0.01283085 -0.8391798 0.5437028 -0.01577979 -0.8454607 0.5338046 -0.1369475 -0.9726521 0.1875984 -0.1320734 -0.967846 0.2140815 0.9657123 -0.1410729 0.2179409 0.963756 -0.1175904 0.2394723 0.9294802 -0.2520737 0.2693057 0.9200543 -0.2772846 0.2767912 0.7992684 -0.5354409 0.2728978 0.7576804 -0.5172266 0.3979915 0.7670035 -0.5033531 0.3979213 0.70138 -0.4764127 0.5301859 0.7123928 -0.4592491 0.5306475 0.6319535 -0.4285072 0.6457681 0.6433825 -0.4093387 0.6469165 0.5507234 -0.3770335 0.7446809 0.561343 -0.3575137 0.7463766 0.4576014 -0.3253027 0.8275139 0.466497 -0.3067989 0.8296114 0.3522092 -0.2759507 0.8943154 0.3586158 -0.2603656 0.89644 0.2343946 -0.2322456 0.9439922 0.1329961 -0.5602476 0.8175786 0.1484482 -0.9699133 0.1929545 0.1756849 -0.9738139 0.1442961 0.1660287 -0.9735405 0.1570143 -0.02516281 -0.9774787 0.2095288 0.1550821 -0.9798861 0.1255896 0.05451321 -0.9785587 0.1986234 0.1485601 -0.9746636 0.1672146 0.1572878 -0.9716902 0.1762917 -0.1638565 -0.9556939 0.2445409 -0.5588765 -0.7897346 0.2529355 -0.4042299 -0.8724599 0.2746126 -0.5253331 -0.7769636 0.346919 -0.7486152 -0.6005383 0.280943 -0.9316482 -0.2364838 0.2758752 -0.8456555 -0.4565414 0.2764719 -0.9680642 -0.0559538 0.2443788 -0.9320173 -0.2504354 0.2619656 -0.9815591 -0.05764347 0.1822612 -0.9351216 -0.2223008 0.2759167 -0.8934772 -0.2074092 0.3983468 -0.8757621 -0.27973 0.3934361 -0.8518202 -0.1318204 0.5069772 -0.7888425 -0.2965725 0.5383052 -0.7951287 -0.1626803 0.5842137 -0.7308164 -0.1943296 0.6543267 -0.710729 -0.269536 0.6497806 -0.6896889 -0.06396943 0.7212747 -0.571676 -0.3314149 0.750567 -0.6142365 -0.1019914 0.7825033 -0.5532304 -0.1282726 0.8230932 -0.4458425 -0.3533769 0.8224046 -0.5055068 -0.07509547 0.8595485 -0.4430348 -0.09731042 0.8912076 -0.3156728 -0.3763849 0.8710255 -0.4140248 0.2264149 0.8816575 0.1486316 -0.9683176 0.2006731 0.1480435 -0.9703689 0.1909644 0.1395186 -0.9665957 0.2150057 0.1684235 -0.9733163 0.1558487 0.1714908 -0.9722591 0.1590702 0.1648877 -0.970966 0.1733124 0.1612848 -0.9710872 0.1760023 0.1610251 -0.9709273 0.177119 0.134265 -0.9691933 0.2064877 0.1315376 -0.9663926 0.2208694 0.01161134 -0.8454068 0.5339969 -0.1341649 -0.9566927 0.2583387 -0.117084 -0.9491508 0.2922398 -0.1338303 -0.9436548 0.3026635 -0.09673005 -0.9296051 0.355637 -0.1132221 -0.9224547 0.3691317 -0.07410705 -0.9089093 0.4103561 -0.08829826 -0.9006706 0.4254363 -0.04834604 -0.8883068 0.4566987 -0.05908203 -0.8796708 0.4718992 -0.01853978 -0.868781 0.4948493 -0.02551573 -0.8607333 0.5084164 0.01666581 -0.8511877 0.5245969 -0.07852536 -0.6842126 0.7250427 -0.3783159 -0.8679208 0.3218548 -0.3386763 -0.851239 0.4008622 -0.3541435 -0.8408058 0.4094243 -0.2990539 -0.8198782 0.488228 -0.3140639 -0.8076599 0.4990485 -0.2533192 -0.786563 0.563159 -0.2665225 -0.7732073 0.5754271 -0.2011781 -0.7529557 0.6265662 -0.2112252 -0.7398324 0.6387738 -0.1415991 -0.7210791 0.678229 -0.1480971 -0.7094143 0.6890563 -0.07352495 -0.6925222 0.7176399 -0.1645554 -0.4706073 0.8668623 -0.6161267 -0.7389349 0.2726962 -0.5858764 -0.7249446 0.3622213 -0.597266 -0.7135177 0.3662867 -0.5396657 -0.6899761 0.4823836 -0.5525995 -0.6753209 0.4884421 -0.4832673 -0.648896 0.5876962 -0.4959046 -0.6322466 0.5952671 -0.4175311 -0.6049553 0.6780096 -0.428642 -0.5873915 0.6864673 -0.3422549 -0.5605634 0.7540758 -0.3507474 -0.5438383 0.7623754 -0.2565497 -0.5184416 0.8157209 -0.2620839 -0.5040361 0.8229579 -0.1599291 -0.4808988 0.8620667 -0.2374117 -0.2271056 0.9444886 -0.2585355 -0.0537424 0.9645057 -0.1948367 -0.3732073 0.9070585 -0.2334745 -0.2384899 0.9426624 -0.3554801 -0.2661123 0.8960013 -0.3512997 -0.2823622 0.8926703 -0.4628268 -0.3124658 0.829552 -0.4563935 -0.3318036 0.8255976 -0.5573085 -0.3631758 0.7466664 -0.5491934 -0.3833108 0.7426033 -0.6393232 -0.4147313 0.6475058 -0.6298789 -0.4347302 0.6436321 -0.7083324 -0.4646707 0.5313628 -0.6988031 -0.4824308 0.5281427 -0.7630416 -0.5087468 0.3986783 -0.7546324 -0.5229244 0.3963334 -0.7920485 -0.5394887 0.2856768 -0.7656384 -0.5778341 0.2826761 0.3070784 -0.9514491 0.02115738 0.3417924 -0.939762 -0.005053579 0.3428999 -0.939366 0.003357291 -0.3137885 -0.9491863 0.02412694 -0.3213177 -0.9469208 -0.009797692 -0.2816371 -0.9594556 0.01120865 -0.2816752 -0.9594987 -0.004632771 -0.2416129 -0.9703573 0.005472302 -0.2410552 -0.9705109 -0.001060485 -0.2083362 -0.9780573 4.16147e-4 -0.2028947 -0.979135 -0.01133364 -0.1682273 -0.9856633 0.01293951 -0.1588849 -0.987203 -0.01363617 -0.1222392 -0.9923897 0.01484102 -0.1144268 -0.9933125 -0.01538681 -0.07589179 -0.9969834 0.01627069 -0.06887048 -0.9975153 -0.01483964 -0.03465324 -0.9993327 0.01155292 -0.02313649 -0.9994653 -0.02310639 0.007607102 -0.9996821 0.02403879 0.02304655 -0.9995403 -0.01970392 0.05456835 -0.9983142 0.0197786 0.06878852 -0.9975315 -0.01411044 0.1020184 -0.9946875 0.01375442 0.1134925 -0.9935035 -0.0083974 0.1389077 -0.9903011 0.002919018 0.1589856 -0.9871782 -0.01425009 0.1702237 -0.9853006 0.01437544 0.1999577 -0.979761 -0.009237885 0.2168068 -0.9761449 0.01166647 0.2367594 -0.9715529 -0.005468189 0.2631458 -0.964731 0.006960332 0.2683188 -0.9633279 0.002111136 0.2942308 -0.9557343 -7.26505e-4 0.3084502 -0.9512062 -0.00808376 0.3086758 -0.9510255 0.01642751 0.2396156 0.5135344 0.8239337 -0.1691869 0.9682719 0.1839174 -0.1361027 0.9724462 0.1892741 -0.1347723 0.973734 0.1835169 -0.08198624 0.9784947 0.1892787 -0.08133035 0.9792288 0.1857325 -0.02728515 0.981661 0.1886723 -0.0271213 0.9818891 0.187505 0.02725732 0.9818856 0.1875038 0.02714568 0.9816606 0.188695 0.08177024 0.9791924 0.1857305 0.08159071 0.9785277 0.1892791 0.1354463 0.9736606 0.1834107 0.1354166 0.9725219 0.1893766 0.1891225 0.963662 0.1886487 0.2052842 0.9466314 0.2484906 0.1691614 0.9682801 0.1838974 0.2342309 0.1663259 0.9578474 0.2159919 0.2137687 0.9527069 0.1820137 0.08098018 0.9799557 0.1581285 0.2467887 0.9560809 0.1096215 0.07741206 0.9909544 -0.1575651 0.2396 0.9580006 -0.1148338 0.07077872 0.99086 -0.09530919 0.2464026 0.9644698 -0.04051715 0.1019237 0.9939668 -0.03093785 0.1973372 0.9798474 0.03723216 0.1739482 0.9840508 0.02918672 0.1039289 0.9941564 0.09487503 0.2366902 0.9669419 -0.2308667 0.814733 0.5318937 -0.1949028 0.9535006 0.2298902 -0.1951854 0.9635135 0.1831514 0.2307567 0.8114519 0.5369331 0.1669844 0.8200638 0.5473679 0.1674405 0.8233305 0.5423012 0.1008805 0.8293477 0.5495504 0.1012283 0.8313625 0.5464333 0.03361666 0.834416 0.5501091 0.03376525 0.8350744 0.5491001 -0.03361326 0.8350876 0.5490892 -0.03377056 0.8344061 0.5501145 -0.1007523 0.8313971 0.5464686 -0.1013044 0.8293664 0.549444 -0.1667041 0.8234626 0.5423277 -0.1677438 0.819985 0.5472538 -0.2305923 0.8114851 0.5369536 -0.2405047 0.5347391 0.8100689 -0.2031306 0.1874843 0.9610347 -0.1981488 0.05360817 0.9787049 -0.2381159 0.5207606 0.8198228 -0.1735334 0.5294961 0.8303735 -0.1729269 0.5346286 0.8272053 -0.1050194 0.5407592 0.8345961 -0.10463 0.5438264 0.8326498 -0.03505885 0.5469563 0.8364269 -0.03491139 0.5479729 0.8357673 0.0350601 0.5479625 0.835768 0.03490561 0.5469721 0.8364229 0.1051094 0.5438023 0.832605 0.1046121 0.5408127 0.8346125 0.1736598 0.5345722 0.8270883 0.1727728 0.5295846 0.8304756 0.2388873 0.5206339 0.8196788 0.2322669 0.8066543 0.5434713 0.03540432 -0.8413268 0.5393661 -0.1738101 -0.03839492 0.9840305 -0.1077069 -0.2198388 0.9695721 -0.1018049 -0.076056 0.9918928 -0.06483614 -0.2189298 0.9735842 -0.03446203 -0.09584385 0.9947997 -0.02267199 -0.1801264 0.9833822 0.0231381 -0.1631653 0.9863275 0.02982032 -0.1113935 0.9933289 0.06539511 -0.2125581 0.9749578 0.09616684 -0.08222222 0.9919635 0.1070156 -0.2245866 0.9685601 0.1557421 -0.1070562 0.9819793 0.1084359 -0.9704061 0.215763 0.1170046 -0.9744924 0.1915057 0.08559125 -0.9787407 0.1863885 0.08396971 -0.9777743 0.1921109 0.05130535 -0.9807183 0.1885724 0.05052268 -0.980076 0.1920902 0.017012 -0.9815842 0.1902716 0.01683086 -0.9813545 0.1914679 -0.01697623 -0.9813567 0.1914443 -0.01686501 -0.9815891 0.1902586 -0.05097776 -0.9800491 0.1921072 -0.05088227 -0.9807569 0.188486 -0.08467656 -0.9776993 0.1921822 -0.08487707 -0.9788255 0.1862706 -0.02710336 -0.8367316 0.5469423 -0.1179737 -0.9743389 0.1916922 -0.1187599 -0.9758018 0.1835942 0.02892196 -0.8318347 0.5542694 0.01843339 -0.8332816 0.5525415 0.01814246 -0.8299313 0.5575707 0.01059156 -0.8306115 0.5567516 0.01068079 -0.8285199 0.5598579 0.003408014 -0.8288483 0.5594633 0.003522634 -0.8281738 0.5604605 -0.003366231 -0.8281723 0.5604636 -0.00356251 -0.8288358 0.5594808 -0.01021039 -0.8285412 0.5598351 -0.01106464 -0.83054 0.5568492 -0.01735979 -0.8299753 0.5575301 -0.01917457 -0.8331638 0.552694 -0.02614605 -0.8322221 0.5538257 0.07285952 -0.550071 0.8319336 -0.1591546 -0.1202535 0.9799025 -0.1503534 -0.211723 0.9656952 -0.09749352 -0.4591444 0.8829959 0.1745724 -0.1877117 0.9665862 0.1518248 -0.2118909 0.9654282 0.07374364 -0.5431115 0.8364161 0.05309748 -0.5403061 0.8397917 0.05488485 -0.5353431 0.8428497 0.03266078 -0.5333386 0.8452711 0.0334652 -0.5303665 0.8471077 0.01100379 -0.5293582 0.8483271 0.01121228 -0.528319 0.848972 -0.01105517 -0.5283211 0.8489727 -0.01115494 -0.5293638 0.8483217 -0.03300768 -0.5303488 0.8471367 -0.03309935 -0.5334082 0.8452102 -0.05411022 -0.5353117 0.8429196 -0.05386078 -0.5403996 0.8396829 -0.06783545 -0.5423238 0.8374266 -0.0363664 -0.6771402 0.7349549 0.6861599 2.74685e-4 0.7274508 0.527424 -2.74582e-5 0.8496022 -0.6904761 0.006952583 0.7233219 -0.718708 -0.144199 0.6801952 -0.7087976 -0.2815787 0.6467761 -0.7667084 -0.07123744 0.638031 -0.7911021 0.006130039 0.6116536 -0.7910233 5.02471e-4 0.6117861 -0.7909702 0.002465665 0.6118499 -0.7909535 0.00510782 0.611855 -0.7911825 0.006599545 0.6115446 -0.5253232 -0.004097521 0.850893 -0.5666249 -0.02905511 0.8234634 -0.5894085 -0.1071983 0.8006912 -0.5864384 -0.09172827 0.8047832 -0.6293593 -0.03029274 0.7765238 -0.6546452 -0.003861725 0.7559265 -0.3327179 -6.15701e-6 0.9430264 -0.3920523 -0.02396297 0.9196308 -0.4071813 -0.04514724 0.9122309 -0.4697018 1.53037e-5 0.8828251 -0.5090456 -1.35499e-5 0.8607397 -0.1246647 -3.84585e-6 0.992199 -0.1857058 -0.01539796 0.9824848 -0.2082353 -0.03475797 0.977461 -0.2484191 -0.01225984 0.9685751 -0.2900568 2.17866e-5 0.9570096 0 -0.03040033 0.9995379 -0.01408785 -0.01905202 0.9997193 -0.08140057 4.7149e-6 0.9966815 0.2883996 7.14521e-6 0.9575102 0.222291 -0.02092242 0.9747559 0.2082616 -0.03284609 0.9775215 0.140178 0.001847088 0.9901247 0.06330192 -0.001765549 0.9979929 0.4890928 8.18366e-6 0.8722318 0.4336211 -0.01743495 0.9009267 0.4071762 -0.04533076 0.9122241 0.3707194 -0.01423007 0.9286359 0.3298768 -1.82279e-5 0.9440241 0.5889202 -0.001292407 0.8081903 0.6008154 -0.1740384 0.7802125 0.5772643 -0.05014801 0.8150161 0.7917394 0.004755318 0.6108406 0.7917306 0.002498924 0.6108655 0.7917897 5.54428e-4 0.6107937 0.7188 -0.09743624 0.6883551 0.7088027 -0.2815682 0.6467753 0.7678415 -0.06507974 0.6373258 0.7919211 0.005789816 0.610596 0.7919259 0.005862593 0.610589 0.1275429 0.9898307 0.0629931 -0.2226278 0.9746294 0.0231167 -0.3312712 0.9435126 0.00658822 -0.3844198 0.9231582 -5.76543e-4 -0.1388516 0.9897905 0.03217309 -0.01328855 0.9980044 0.06173157 -0.1188039 0.992062 0.04121494 0.3377949 0.9373723 0.0850172 0.4500167 0.8853127 0.1170754 0.3116626 0.9463479 0.08539426 0.8838658 0.4425226 0.1515091 0.9005943 0.4168843 0.1230342 0.7345137 0.6662467 0.1288605 0.7353826 0.6651427 0.1296058 0.6123362 0.7828699 0.1102691 0.9630193 0.2387131 0.1249399 0.9760759 0.1674835 0.1386553 0.9498526 0.2863661 0.1255971 0.7404675 0.6615676 0.1184743 0.7358868 0.6668195 0.1175692 0.3488255 0.9333422 0.08481281 0.3380649 0.9374796 0.08272904 -0.1225023 0.9919566 0.03186696 -0.1384164 0.9899638 0.02850496 0.343558 0.9305853 0.1264079 -0.04437208 0.4399891 0.8969063 0.1966613 0.6126987 0.7654572 -0.1075186 0.9748761 0.1950805 -0.1080846 0.9747881 0.1952078 -0.1096432 0.9746106 0.1952246 -0.1098274 0.9745163 0.1955916 0.1167867 0.2024729 0.9722991 0.02019733 0.1900326 0.98157 0.02329546 0.1978855 0.9799484 -0.0185796 0.1932647 0.9809708 -0.01499348 0.1946216 0.9807639 0.2022634 0.2556641 0.9453706 0.2300044 0.2055208 0.9512409 0.1145956 0.1865935 0.9757308 0.2738771 0.1959763 0.9415863 0.3294913 0.2067782 0.9212375 0.32669 0.1940052 0.9250059 0.4196335 0.2138093 0.8821528 0.4193043 0.1924198 0.8872196 0.489669 0.2098574 0.8462767 0.5133806 0.2470476 0.8218321 0.5459396 0.201609 0.813206 0.6338223 0.2256351 0.7398366 0.6355593 0.2015624 0.7452765 0.7036402 0.2222534 0.6749029 0.714035 0.2640998 0.6483867 0.7493408 0.2154425 0.6261572 0.7889671 0.2283905 0.570411 0.7877484 0.219465 0.5755758 0.8380963 0.2364634 0.4916091 0.8398593 0.2198063 0.4963081 0.8756145 0.2322748 0.4234948 0.8880094 0.2620538 0.3778452 0.9035298 0.2285974 0.36246 0.9293719 0.2380056 0.2821726 0.9295198 0.2333499 0.2855537 0.9516927 0.2418004 0.1892449 0.952891 0.2351563 0.191573 0.7299379 0.6599103 0.1780706 0.709629 0.6529854 0.2646447 0.7078089 0.6543821 0.2660652 0.6812403 0.6440625 0.3479872 0.6765838 0.6483446 0.3491184 0.6286174 0.6314472 0.4539985 0.6225134 0.6368745 0.4548276 0.5818054 0.6237859 0.5219135 0.577826 0.6261491 0.5235022 0.533382 0.6111164 0.5848422 0.5257108 0.6179498 0.5846078 0.4526196 0.5956998 0.6635341 0.4438343 0.6040791 0.6618909 0.3646833 0.5825583 0.7263828 0.3565379 0.5905312 0.7239846 0.2776624 0.5712398 0.7723916 0.2699914 0.5794202 0.7690104 0.2051866 0.5658848 0.7985443 0.1997051 0.5705646 0.7966015 0.1340025 0.5573921 0.8193641 0.1278819 0.5654021 0.8148416 0.04369503 0.5516511 0.8329296 0.0387873 0.5592898 0.8280643 -0.02722227 0.55099 0.8340678 -0.03065764 0.5549368 0.8313274 -0.05873268 0.55191 0.8318328 -0.08453035 0.7888564 0.6087368 0.7317603 0.657522 0.1794205 0.3439782 0.9303953 0.1266635 0.3291325 0.9255028 0.1873943 0.3294979 0.9254119 0.1872006 0.3111514 0.9181327 0.2453922 0.3120298 0.9178472 0.2453446 0.2787163 0.9061679 0.3180836 0.2796123 0.9058738 0.318135 0.251175 0.896851 0.3641009 0.2516276 0.8967562 0.364022 0.2221786 0.8867509 0.405351 0.2227939 0.8865294 0.405498 0.1760638 0.8723661 0.4560472 0.1762828 0.8722742 0.4561382 0.1277886 0.8591508 0.4955101 0.1273388 0.8593589 0.495265 0.08133739 0.8481515 0.5234725 0.08030825 0.848721 0.5227077 0.04371559 0.8410738 0.5391513 0.04255211 0.841604 0.5384163 0.007088661 0.8345445 0.5508951 0.005216062 0.8359544 0.5487744 -0.03861933 0.8288152 0.5581881 -0.04067051 0.8307999 0.5550833 -0.0742166 0.8265472 0.5579532 -0.07604068 0.8278866 0.5557173 0.09631186 0.833133 0.5446225 -0.09771478 0.8915209 0.4423149 -0.1128067 0.9741274 0.1958326 -0.1149277 0.9744009 0.1932215 -0.1155444 0.9740754 0.1944909 -0.1197252 0.973392 0.1953813 -0.1196268 0.9743509 0.1906037 -0.1236174 0.9735756 0.1920141 -0.1231427 0.9745138 0.1875066 -0.1255906 0.9739913 0.1885949 -0.127191 0.9754211 0.1799339 -0.1273692 0.9753781 0.1800408 -0.1305744 0.9767699 0.1699143 -0.1272829 0.977663 0.1672541 -0.132917 0.9787921 0.1558819 -0.1266853 0.9806666 0.1491439 -0.1328668 0.9813189 0.1391393 -0.1282884 0.9828249 0.1326553 -0.1299611 0.9833623 0.1269207 -0.1240255 0.9853051 0.1174372 -0.1307254 0.9853305 0.1097037 -0.1219644 0.9883895 0.09061425 -0.1281269 0.9881073 0.08501541 -0.1230357 0.9900265 0.06862819 -0.1249783 0.989989 0.065593 -0.1202314 0.9916521 0.04658955 -0.1239509 0.9913029 0.0442146 0.01432979 0.1946848 0.9807612 0.02848923 0.2578759 0.965758 0.03248208 0.4412687 0.896787 0 0.2589569 0.9658889 -0.01900869 0.2582579 0.965889 -0.02688521 0.1932994 0.9807714 0 0.2589575 0.9658887 0 0.7073592 0.7068543 0 0.7073601 0.7068534 0.07090747 0.9633612 0.2586649 0.08470952 0.9771327 0.1950283 0.06584608 0.8945568 0.4420775 0.05192542 0.7054517 0.7068535 0.08334249 0.7889836 0.6087355 0.04470717 0.6073724 0.7931583 -0.03248208 0.4412687 0.896787 -0.04470717 0.6073724 0.7931583 -0.06467694 0.7046896 0.7065618 -0.05825155 0.7914287 0.6084796 -0.06584608 0.8945568 0.4420775 0.01773655 0.9657728 0.2587823 0 0.9768101 0.2141078 -0.0177477 0.9657728 0.2587817 -0.08050209 0.9626355 0.2585587 -0.07199627 0.9781647 0.1949625 -0.7328382 0.6580849 0.172837 -0.9323233 0.2335518 0.276092 -0.9525182 0.2412247 0.185795 -0.9543868 0.2356613 0.1833294 -0.8927233 0.2672777 0.362778 -0.8986039 0.2268341 0.375576 -0.9300835 0.2382243 0.2796321 -0.8762019 0.2321739 0.4223337 -0.8439403 0.220906 0.4888408 -0.8368703 0.2355718 0.4941195 -0.8075779 0.2256312 0.5448932 -0.8041871 0.2247137 0.5502609 -0.785013 0.218351 0.5797218 -0.7781422 0.2285603 0.5850256 -0.7411134 0.2165909 0.6354836 -0.6985996 0.2618591 0.6658742 -0.6952031 0.223529 0.6831745 -0.6279295 0.2033863 0.7512248 -0.6167106 0.2226029 0.7550603 -0.5484641 0.2040908 0.8108847 -0.5396414 0.214102 0.814216 -0.5111277 0.2068137 0.8342522 -0.4544495 0.2186805 0.8635129 -0.4542886 0.2142548 0.8647062 -0.3536158 0.1914389 0.9155911 -0.2637287 0.2341192 0.935754 -0.2531714 0.1923839 0.9480995 -0.3431787 0.2097868 0.9155424 0.1201528 0.9917995 0.0435574 0.1255932 0.9898537 0.06645399 0.1219637 0.9904015 0.06503772 0.1289371 0.9877805 0.0875501 0.1207672 0.9888159 0.08751195 0.1321418 0.9848313 0.1124536 0.1220932 0.9859755 0.113779 0.129871 0.9834783 0.1261117 0.1277215 0.9841314 0.1231776 0.1329087 0.9823732 0.1314471 0.1251697 0.9833142 0.1320074 0.135246 0.9800624 0.1455549 0.1241912 0.9809113 0.1496319 0.1350412 0.9776993 0.1608347 0.1247264 0.9781562 0.1662944 0.1323598 0.9761025 0.1723513 0.1260831 0.9765123 0.1747193 0.1311509 0.9752182 0.178182 0.1236351 0.9750515 0.1843609 0.1266068 0.9743844 0.1858651 0.1214311 0.9739701 0.1914072 0.1217778 0.9739025 0.1915312 0.1191753 0.9737558 0.1938992 0.02255076 0.8326133 0.5533956 0.02280664 0.8304733 0.5565916 -0.01409798 0.8370857 0.5468901 -0.01380705 0.8360484 0.548482 -0.05145525 0.8431848 0.535156 -0.05171507 0.8420683 0.536886 -0.09842681 0.8525947 0.5132198 -0.09868317 0.8520277 0.5141113 -0.1341834 0.861332 0.490002 -0.1342124 0.8612057 0.490216 -0.1702962 0.8707092 0.4613729 -0.170255 0.8707575 0.4612969 -0.2147942 0.8839878 0.4152457 -0.2144814 0.8842872 0.4147699 -0.248184 0.8954018 0.369676 -0.2479377 0.8956601 0.3692154 -0.2604534 0.8999837 0.3495618 -0.260311 0.9001144 0.3493314 -0.2802236 0.9061172 0.3169012 -0.2796335 0.9065139 0.3162877 -0.3122133 0.9179576 0.2446975 -0.3115819 0.9183149 0.244161 -0.3305791 0.9257475 0.1836005 -0.330305 0.9259119 0.1832644 -0.344488 0.930749 0.1226151 0.1239852 0.9912862 0.04449135 0.1166695 0.9741903 0.1932399 0.1168764 0.9739101 0.1945232 0.1137726 0.9740427 0.1956954 -0.2357442 0.200673 0.9508707 -0.1638672 0.1878163 0.9684382 -0.1560331 0.2031852 0.966628 -0.04250389 0.1869094 0.9814573 -0.03661561 0.1999934 0.9791129 -0.002502381 0.4445967 0.8957275 0.00144428 0.5510655 0.8344609 -0.07498997 0.5616768 0.8239514 -0.07422751 0.5529282 0.8299161 -0.1468197 0.5660215 0.8112113 -0.1455665 0.5602421 0.8154381 -0.2180458 0.5739303 0.7893415 -0.2189221 0.5643362 0.7959886 -0.3061746 0.5840532 0.7517573 -0.3080224 0.5744696 0.7583581 -0.3731736 0.591597 0.7146709 -0.3732908 0.5860511 0.719165 -0.4364485 0.6027428 0.6679925 -0.4395121 0.5937205 0.6740364 -0.5143169 0.6160326 0.5966422 -0.5178095 0.607811 0.6020291 -0.5731602 0.6260516 0.528722 -0.5748477 0.6211587 0.5326462 -0.5958114 0.6285843 0.4998906 -0.5942881 0.628008 0.5024219 -0.6251962 0.6375027 0.4502444 -0.6286756 0.631286 0.454142 -0.6779842 0.6486856 0.3457519 -0.6810382 0.6439253 0.3486362 -0.7098653 0.6550306 0.2588942 -0.7110011 0.6530584 0.2607533 -0.7308493 0.6600534 0.1737496 -0.3440454 0.9308967 0.1227361 0.1106693 0.9745249 0.195073 0.110589 0.9744931 0.1952779 0.0846821 0.8928792 0.4422622 0.05469894 0.8282123 0.5577387 0.06008207 0.7912702 0.6085078 0.02645057 0.6090455 0.7926942 -0.7337094 0.6658914 0.135127 -0.9047731 0.4099534 0.1154294 -0.1809502 0.9810221 0.06966143 0.3857691 0.9225952 -7.73989e-4 0.2691231 0.9629927 0.01476114 0.1394997 0.9895055 0.03766709 0.03182178 0.9984806 0.04499024 -0.1273007 0.989864 0.06295883 -0.9630194 0.2387129 0.1249394 -0.9701422 0.2035868 0.1318202 -0.3332586 0.9385604 0.08968269 -0.4540578 0.8830929 0.1182309 -0.3377945 0.9373737 0.08500289 -0.6234943 0.7738836 0.1111719 -0.7198593 0.6821256 0.1284813 -0.8914407 0.4313045 0.1389599 -0.9177397 0.3766529 0.1260419 -0.7358155 0.6667919 0.1181702 -0.7405403 0.6615945 0.1178673 -0.3379438 0.9374343 0.08373153 -0.3489487 0.9333875 0.08380109 0.1385843 0.9898989 0.02990752 0.1223331 0.9920219 0.03045105 -0.6096641 0.7289387 0.311381 -0.6738816 0.6926288 0.2571948 -0.6474468 0.7168845 0.2586298 -0.6427468 0.7190924 0.2641643 -0.6251043 0.7281345 0.2811848 -0.6006084 0.7659289 0.2293963 -0.3110443 0.9500896 -0.02410989 -0.3655389 0.9306933 0.0138393 -0.5252736 0.8390628 0.1416379 -0.5818904 0.7916634 0.1862061 -0.5818995 0.7916333 0.186306 -0.5798999 0.7934384 0.1848556 -0.5720107 0.7971366 0.1933316 -0.5772962 0.7918861 0.1991116 -0.713063 0.6501937 0.2622772 -0.7032939 0.6551235 0.2760275 -0.6676978 0.6948689 0.26709 -0.6584948 0.6998752 0.2766935 -0.9136167 0.3170432 0.2545355 -0.9700585 0.1303218 0.2049459 -0.8349233 0.3048505 0.4582242 -0.8618777 0.3700006 0.3467944 -0.849823 0.3831527 0.3619324 -0.8540579 0.4194979 0.3075819 -0.8785917 0.396431 0.2663067 -0.7371545 0.5990452 0.3126471 0.972891 0.1281808 0.1924911 0.8349227 0.3048509 0.458225 0.8618769 0.3700295 0.3467656 0.9317516 0.2408347 0.2717311 0.9340468 0.2637105 0.2408594 0.9332455 0.2698227 0.2371677 0.9332571 0.2687489 0.2383387 0.9294189 0.2809918 0.2392159 0.8357669 0.4786386 0.2690707 0.8411315 0.4559207 0.2909199 0.8569385 0.4148212 0.3059082 0.8498478 0.3831526 0.361874 0.8527902 0.4048491 0.3299183 0.8527957 0.4032978 0.3317988 0.8532126 0.4075894 0.3254218 0.8536458 0.4052014 0.3272629 0.8544873 0.4146199 0.3129566 0.9295071 0.2836823 0.2356715 0.3106985 0.9497866 -0.03704053 0.5296845 0.8392621 0.1227749 0.4857897 0.8602171 0.1550325 0.5334364 0.832628 0.1489173 0.6122506 0.7498105 0.2508652 0.619803 0.7464404 0.2422212 0.6096726 0.7392951 0.285906 0.635173 0.7284817 0.2566511 0.6072928 0.7370783 0.2964981 0.7949571 0.5071364 0.3329507 0.6756368 0.6917678 0.2548967 0.6738653 0.6926236 0.2572512 0.5711179 0.8024686 0.1728252 0.5688571 0.80353 0.1753314 0.5749439 0.7968986 0.1854517 0.5777148 0.7955842 0.18246 0.5786985 0.7941293 0.1856526 0.5797714 0.7936594 0.1843095 0.6416877 0.7226941 0.2568076 0.6121373 0.7275274 0.3098253 -0.8883162 0.4591692 0.007611989 -0.9536589 0.3008623 0.004103183 -0.9468234 0.3205869 0.02738165 -0.8497939 0.4792332 0.2195128 -0.9099149 0.414779 -0.003650546 -0.9029867 0.4292614 0.01870602 -0.903652 0.4279227 0.01718491 -0.90471 0.4257237 0.01609987 -0.8954058 0.444759 0.02093279 -0.8416124 0.5386528 0.03926807 -0.7370367 0.6758307 0.005474746 -0.5019453 0.8644245 0.02865624 -0.4782578 0.8781524 0.01085972 -0.8882952 0.4592205 0.006939768 -0.853926 0.5193077 0.03361457 -0.7030466 0.7059123 -0.08610087 -0.7036945 0.7100886 -0.02425283 -0.4938724 0.8568978 0.1477032 -0.5105173 0.8568933 -0.07145631 -0.4217275 0.9067178 -0.002991199 -0.6034407 0.7741194 0.191307 -0.6047686 0.7700483 0.2031762 -0.6044481 0.7703416 0.2030187 -0.9676968 0.2049603 0.1468138 -0.9365997 0.3137166 0.1560859 -0.8602026 0.4913609 0.1364405 -0.8690854 0.476009 0.1345595 -0.7345187 0.6694638 0.1109073 -0.7203085 0.6843714 0.1130997 -0.4712871 0.8803416 0.05373275 -0.9823741 0.08150988 0.1682176 -0.9147468 0.3640542 0.175223 -0.9071193 0.3569776 0.2229387 -0.8365207 0.4872519 0.2506368 -0.6046283 0.7702127 0.2029708 -0.6049824 0.7702888 0.2016224 -0.7143651 0.667585 0.2097924 -0.6727598 0.7014766 0.2352125 0.3876328 0.921814 7.0287e-5 0.6988729 0.7151774 0.009899735 0.9281539 0.3661049 -0.0670638 0.9110949 0.4115022 0.02392244 0.8802848 0.473368 0.03196388 0.9149546 0.3974746 0.06980079 0.896682 0.4417817 0.0281108 0.9124782 0.4085271 0.0221194 0.922834 0.3849769 0.01304733 0.8061271 0.5915113 0.01653778 0.7694026 0.638466 0.01952117 0.8946602 0.3692378 0.2514887 0.1085387 0.9520396 -0.286077 0.509387 0.8600797 0.02806621 0.5019662 0.8643069 0.03168058 0.50288 0.8602265 -0.08439242 0.441224 0.8973849 -0.004684031 0.9069101 0.3574342 0.2230584 0.6836621 0.7223025 0.1043321 0.9681803 0.2027069 0.1467542 0.9815403 0.07913303 0.1741169 0.9805479 0.09536015 0.1715584 0.9802441 0.09955877 0.1709084 0.9547786 0.252777 0.1565303 0.8971812 0.355825 0.261638 0.900626 0.3522526 0.2545412 0.7902582 0.6003218 0.1229064 0.9113606 0.3882865 0.1365859 0.3860232 0.9223704 0.01479816 0.3351005 0.9421809 0.001763284 0.500163 0.8623337 0.0788508 0.4448947 0.8914847 0.08557838 0.5784313 0.8119114 0.07885068 0.6051474 0.7697189 0.2032964 0.6067411 0.7702819 0.1962935 0.6049731 0.7698476 0.2033278 0.6049536 0.7698857 0.2032423 0.7357726 0.6691948 0.1040054 0.7069281 0.6655097 0.2394778 0.8548235 0.4911534 0.1674672 0.8363621 0.4874855 0.2507121 0.5588123 0.0832144 0.8251086 0.7846778 8.22632e-4 0.6199033 0.695412 -0.02586179 0.7181458 0.6899937 0.01565247 0.7236461 0.7121176 0.08987456 0.6962838 0.7088451 0.0186569 0.7051175 0.7097623 0.08069026 0.6998047 0.5783756 0.08787626 0.8110237 0.7014165 0.02917844 0.7121542 0.7056006 0.03940844 0.7075131 0.6417645 -0.2380132 0.7290323 0.7604939 0.02449727 0.6488829 0.7606412 0.02522641 0.6486822 -0.763032 0.02358722 0.6459304 -0.6410466 0.006681203 0.767473 -0.6392348 -0.03354132 0.7682799 -0.6425495 0.1091227 0.7584342 -0.7629825 0.02335739 0.6459971 -0.7610445 0.01779592 0.6484557 -0.6873009 -0.03877699 0.7253372 -0.6997202 0.02032619 0.7141279 -0.7118796 0.08121615 0.6975897 -0.7076743 0.003632783 0.7065296 -0.7213125 0.06923228 0.6891409 -0.9763035 0.1181892 0.1812808 -0.9651427 0.2035619 0.1645055 -0.9621072 0.1070061 0.2507976 -0.961304 0.04920548 0.2710597 -0.8602779 0.1307609 0.4927713 -0.8492245 -0.03143912 0.5270954 -0.7502943 -0.01743817 0.6608741 -0.7458496 -0.07509368 0.6618681 -0.8383022 0.003352642 0.5451955 -0.9386849 0.02107799 0.3441311 -0.9563695 0.08212178 0.2803811 -0.9228466 0.1542419 0.3529359 -0.6162121 0.2141719 0.7579006 -0.6946481 0.125705 0.7082813 -0.70708 0.07995277 0.7025991 -0.7676884 0.3017893 0.5653122 -0.8905445 0.1175068 0.4394574 -0.8973106 0.08174794 0.4337638 -0.7068098 0.07609158 0.7032994 -0.7470395 0.02684092 0.6642376 0.7071045 0.0799781 0.7025716 0.8341629 0.3048285 0.4596214 0.8233121 0.2532593 0.5079538 0.6897702 0.1421908 0.7099288 0.6857694 0.1227694 0.7173898 0.8788796 0.1680368 0.4464687 0.9335872 0.08173733 0.3489043 0.7068161 0.07609671 0.7032924 0.7470735 0.02681809 0.6642003 0.9337834 0.07999408 0.348783 0.7503255 -0.01749348 0.6608371 0.9789611 0.0282002 0.2020893 0.8651872 0.124299 0.4857994 0.8454273 -0.02706891 0.5334043 0.9700834 0.2036298 0.1321867 0.9660612 0.1765571 0.1885558 0.9563848 0.07743203 0.2816601 0.963317 0.0255391 0.2671483 0.8373375 0.002390444 0.5466811 0.7458666 -0.07506483 0.6618522 0.967773 0.2196407 0.1231807 0.972329 -0.05049598 0.2280935 0.9808145 -0.08279758 0.1764864 0.9774774 -0.01394081 0.210579 0.9618715 0.1959131 0.1908439 0.9833205 -0.003356397 0.1818506 0.967967 -0.05100804 0.2458419 0.9494338 -0.1801022 0.2571746 0.9344972 -0.2118986 0.2860313 0.8981148 -0.3025686 0.3191272 0.8805178 -0.3289624 0.34128 0.8219678 -0.4489835 0.3504036 0.9679558 0.1842877 0.170586 0.9543097 0.1482816 0.2594335 0.9547469 0.1326192 0.2662155 0.9212939 0.04198205 0.3865942 0.9214712 0.03565454 0.3868072 0.8662075 -0.07884353 0.493425 0.8718727 -0.05906152 0.4861581 0.7758493 -0.1958535 0.5997493 0.7924456 -0.113807 0.5992313 0.7921235 -0.5267596 0.3083259 0.293194 -0.6866088 0.6652862 0.759558 -0.4875181 0.4305785 0.828352 -0.1795781 0.5306457 0.5061869 -0.3799835 0.7742011 0.7924664 -0.1108149 0.5997644 0.8266876 -0.4437165 0.3459815 0.7117783 -0.5729867 0.4062733 0.7723022 -0.1358439 0.620561 0.7235903 -0.2347511 0.6490833 0.1133259 -0.9540866 0.2772656 0.6480939 -0.1759485 0.7409565 0.6359847 -0.0531302 0.7698706 0.4156318 -0.6188154 0.6665716 0.02195316 -0.9302706 0.3662168 -0.1693006 -0.9755169 0.1403719 0.1371472 -0.8838159 0.447281 0.2650003 -0.7670979 0.5842395 0.3949152 -0.7973665 0.4563428 0.3989495 -0.8629842 0.3099964 0.3049597 -0.8607772 0.4075075 0.1144738 -0.9693512 0.2173802 0.1163406 -0.9567475 0.2666444 0.7635236 -0.1484069 0.6284959 0.7702777 -0.1288526 0.6245552 0.7176187 -0.3770991 0.5855082 0.7029594 -0.1886783 0.6857467 0.71876 -0.1477329 0.6793814 0.6254217 -0.4296438 0.6513478 0.7129238 -0.4314982 0.5527648 0.6245905 -0.5992636 0.5007694 0.5358019 -0.7769307 0.3305983 0.3867063 -0.8631264 0.324763 0.5945204 -0.6761673 0.4351362 0.4874203 -0.6732802 0.5559815 0.5921097 -0.5296489 0.6073536 0.4745391 -0.5022311 0.7228946 0.6122013 -0.2319694 0.75591 0.6964526 -0.646641 0.311142 0.5561817 -0.7731463 0.304806 0.7622696 -0.4863759 0.4270638 0.6876354 -0.5894967 0.4238529 0.7986387 -0.30339 0.519741 0.7704852 -0.3683568 0.5202556 0.8035861 -0.1059306 0.5856862 0.8001958 -0.12372 0.5868391 0.2841805 -0.5792009 0.7640471 -0.1503741 -0.8086882 0.5686923 -0.3821013 -0.5422871 0.7482802 -0.5923885 -0.09756278 0.7997233 -0.5990901 -0.3317436 0.7287231 -0.09305316 -0.9305056 0.3542607 -0.5605716 -0.2169046 0.7991946 -0.5134626 -0.1998111 0.8345249 -0.5107722 -0.2182037 0.8315642 -0.4663944 -0.2043476 0.86065 -0.46863 -0.2094196 0.858213 -0.4502929 -0.2039022 0.8692873 -0.4339669 -0.1753243 0.8837047 -0.4118391 -0.2093469 0.8868836 -0.3500025 -0.1937151 0.9165003 -0.3065394 -0.1307319 0.9428376 -0.2771406 -0.1928815 0.9412703 -0.3493306 -0.207488 0.9137378 -0.252266 -0.2002731 0.9467062 -0.2180223 -0.1950398 0.9562561 -0.2193757 -0.199473 0.9550313 -0.163281 -0.1921106 0.9676947 -0.1639772 -0.1988124 0.9662222 -0.1081472 -0.1944029 0.9749419 -0.09167766 -0.1563852 0.9834322 -0.07046455 -0.1958464 0.9780997 -0.01234912 -0.1938601 0.9809515 -0.01246589 -0.1943401 0.9808551 0.0548737 -0.1955103 0.9791653 0.05551898 -0.1937966 0.9794696 0.1212457 -0.1973199 0.9728127 0.1230096 -0.1925169 0.9735532 0.1950252 -0.1999043 0.9602102 0.2683973 -0.1144015 0.9564911 0.2707036 -0.203319 0.9409468 0.1982864 -0.1924107 0.9610728 0.2886409 -0.196262 0.937106 0.3259067 -0.2036817 0.9232003 0.3307945 -0.197166 0.9228764 -0.2556106 -0.7100759 0.6560912 -0.3863104 -0.6096294 0.6921824 -0.3221428 -0.5869041 0.7428106 -0.3176922 -0.5911936 0.7413244 -0.2905931 -0.5828598 0.7588348 -0.2887026 -0.5835837 0.759 -0.2621975 -0.5754421 0.7746735 -0.2586901 -0.5792809 0.7729898 -0.2146001 -0.5681599 0.794444 -0.2118079 -0.5716148 0.7927132 -0.1671521 -0.5625678 0.8096775 -0.1651517 -0.565454 0.8080759 -0.1321534 -0.5605342 0.8175188 -0.1311214 -0.5615531 0.8169856 -0.09870511 -0.5572326 0.824469 -0.09772694 -0.5590499 0.8233546 -0.05306786 -0.5554289 0.8298691 -0.05265009 -0.5564447 0.829215 -0.007440388 -0.5549762 0.8318329 -0.007394611 -0.555152 0.8317161 0.03309118 -0.5558788 0.8306046 0.03292077 -0.5553119 0.8309903 0.07324963 -0.5574462 0.8269754 0.0730856 -0.5560504 0.8279291 0.1182973 -0.5606906 0.8195316 0.1182636 -0.5584377 0.8210731 0.1635376 -0.5652573 0.8085417 0.1638019 -0.5622218 0.8106021 0.1996862 -0.5694789 0.7973827 0.1996352 -0.5672738 0.7989659 0.2360822 -0.5754494 0.7830219 0.4687837 -0.2006224 0.8602283 0.469147 -0.1777703 0.8650428 0.4305904 -0.2069437 0.8785023 0.1052903 -0.9456431 0.3076899 -0.07484477 -0.8624392 0.5005967 -0.06440478 -0.8585922 0.5085975 -0.0692631 -0.8563098 0.511797 -0.05759972 -0.8527073 0.5192039 -0.05953782 -0.8524254 0.5194482 -0.04947763 -0.84935 0.5255059 -0.05323421 -0.8471626 0.5286604 -0.03891247 -0.8435503 0.5356388 -0.04186451 -0.8414998 0.5386331 -0.02938956 -0.8389734 0.5433782 -0.03149372 -0.8371868 0.5460096 -0.02308881 -0.8359175 0.5483694 -0.02411031 -0.8352876 0.5492845 -0.01686346 -0.8343368 0.5509973 -0.01784497 -0.8331812 0.5527123 -0.009006142 -0.8324633 0.5540072 -0.009429335 -0.831825 0.5549581 -0.001262068 -0.8315572 0.5554379 -0.001313745 -0.8314486 0.5556003 0.005659461 -0.8315638 0.5554004 0.005804777 -0.8319101 0.5548802 0.01275098 -0.8322918 0.5541911 0.01287162 -0.8332155 0.5527986 0.02110815 -0.8340579 0.551273 0.02105325 -0.8355413 0.5490244 0.03011417 -0.8369089 0.5465131 0.02970814 -0.8388853 0.543497 0.03740936 -0.8404261 0.5406336 0.03732579 -0.8418774 0.5383766 0.04628062 -0.8439014 0.5344985 0.04501295 -0.8465227 0.5304463 0.05798137 -0.8501093 0.5234048 0.2254724 -0.9665561 0.1221947 0.1998876 -0.9740463 0.1062017 0.2144593 -0.9597166 0.1815255 0.20283 -0.9638907 0.1725535 0.195774 -0.9620733 0.1899672 0.1827991 -0.9662051 0.1817485 0.1839675 -0.9649154 0.1873347 0.1694035 -0.9692401 0.1785386 0.1648676 -0.96702 0.194142 0.140842 -0.9730755 0.1824487 0.1381167 -0.9708176 0.1960534 0.1110275 -0.9763037 0.1857529 0.1097776 -0.9742491 0.196946 0.08782404 -0.9776914 0.1908053 0.08870732 -0.9767186 0.1953252 0.06618553 -0.9795528 0.1899897 0.06637835 -0.9782116 0.1967132 0.03565323 -0.9807037 0.192222 0.03610688 -0.9799609 0.1958904 0.004986643 -0.980973 0.1940805 0.005099594 -0.9808702 0.1945962 -0.02210611 -0.9804759 0.1953934 -0.02276527 -0.9807987 0.19369 -0.04860007 -0.979358 0.1962038 -0.05050182 -0.9801895 0.1915156 -0.07764077 -0.9774151 0.1965497 -0.08132803 -0.9785262 0.1894003 -0.1058538 -0.9748344 0.1961962 -0.1116786 -0.9759962 0.1869741 -0.1284399 -0.9727092 0.1932356 -0.1340497 -0.9730548 0.1876037 -0.1484462 -0.9697395 0.1938276 -0.1580846 -0.970458 0.1822651 -0.173787 -0.9661243 0.1907932 -0.185752 -0.9662144 0.1786783 -0.1974169 -0.9624316 0.186419 -0.211543 -0.9617117 0.1742423 0.5223359 -0.2180063 0.8244019 0.5324036 -0.2022224 0.8219809 0.3281685 -0.5935208 0.7348732 0.3326678 -0.5893185 0.7362309 0.3823718 -0.2088408 0.9000985 0.3899325 -0.1956446 0.8998199 0.2370907 -0.5712697 0.7857729 0.2826555 -0.5838634 0.761058 0.05606263 -0.8530056 0.518882 0.07221812 -0.858237 0.5081475 0.06730258 -0.8604356 0.505095 -0.7816519 -0.3106054 0.540874 0.2217101 -0.967796 0.1192287 -0.1119078 -0.7931854 0.5986099 -0.02631556 -0.9113649 0.4107577 0.1041525 -0.9460507 0.3068231 -0.3774762 -0.540522 0.7518961 -0.6092799 -0.1038492 0.7861256 0.1949302 -0.9468222 0.2559883 0.1184673 -0.9743435 0.1913645 0.1094904 -0.9539695 0.2792025 0.03307133 -0.9769394 0.2109401 -0.08960419 -0.9246084 0.3702305 -0.1662724 -0.9415792 0.2928859 -0.1558743 -0.9396831 0.3044649 -0.3662741 -0.8628177 0.3484092 -0.421809 -0.8615088 0.2826303 -0.4835295 -0.7881391 0.3808361 -0.5786921 -0.772389 0.261784 -0.6528274 -0.6635169 0.365461 -0.7032908 -0.5909146 0.3952242 -0.6498194 -0.6011765 0.4651038 -0.5673496 -0.6771001 0.4686684 -0.5324044 -0.6765464 0.508754 -0.4035792 -0.7720796 0.4909349 -0.3619767 -0.7642586 0.5337433 -0.2175852 -0.8373917 0.5014298 -0.2077555 -0.8344821 0.5103698 -0.1319316 -0.8471487 0.5147166 -0.1107655 -0.8392961 0.5322718 -0.2749827 -0.7172 0.6403192 -0.7320646 -0.4984484 0.4643605 -0.7795131 -0.370321 0.5051949 -0.7324474 -0.37843 0.5659608 -0.6967281 -0.431683 0.5729047 -0.6560037 -0.4310667 0.6195489 -0.5967383 -0.5078213 0.6213059 -0.5451546 -0.4978914 0.6744706 -0.4714905 -0.5697714 0.6730953 -0.4461244 -0.562011 0.6965032 -0.4025827 -0.5808857 0.7074596 -0.3822911 -0.5737065 0.7243717 -0.5390412 -0.3099197 0.7831887 -0.5405387 -0.1886039 0.8199064 -0.6079645 -0.2121478 0.7650964 -0.6029888 -0.1939285 0.7738193 -0.6518866 -0.2095118 0.7287996 -0.6545876 -0.1685642 0.736954 -0.7184224 -0.1811087 0.6716167 -0.7181322 -0.1477271 0.6800463 -0.7669165 -0.1484469 0.6243417 -0.7637368 -0.1308236 0.6321325 -0.8021439 -0.1247791 0.5839481 -0.798749 -0.1080605 0.5918809 -0.8114432 -0.4769446 0.3377631 -0.6816415 -0.2218632 0.6972386 -0.7512887 -0.1276891 0.6475037 -0.729216 -0.2027863 0.6535454 -0.7421019 -0.1925976 0.642021 -0.7169195 -0.5467848 0.4324962 -0.7281506 -0.631163 0.2672642 -0.6712536 -0.5835258 0.4570736 -0.747061 -0.4927052 0.4462528 -0.7904358 -0.3069722 0.5300749 -0.977829 0.09182667 0.1881976 -0.9674559 0.2207462 0.1236942 -0.9683057 0.2207821 0.116789 -0.9672209 0.2203064 0.1262885 -0.9666953 0.1734736 0.1881679 -0.9645851 0.1730194 0.199098 -0.9515249 0.142847 0.2723878 -0.9563452 0.1392862 0.2569112 -0.9197743 0.03886073 0.390519 -0.9223359 0.03800976 0.3845151 -0.8751658 -0.063331 0.4796606 -0.8642364 -0.0722171 0.4978756 -0.8201619 -0.1392225 0.5549338 -0.7581549 -0.1505503 0.6344571 -0.9832024 0.1083968 0.1468445 -0.977729 -0.01881623 0.2090261 -0.9812394 -0.01126897 0.1924632 -0.9463655 -0.09806281 0.3078573 -0.9659136 -0.1382555 0.2188523 -0.8981403 -0.2752368 0.3429123 -0.9302739 -0.2465037 0.2717101 -0.8212425 -0.4035335 0.4033876 -0.8643266 -0.3978579 0.3076503 -0.6331139 0.704613 0.3204487 -0.6814563 0.6651147 0.3053519 -0.4444337 0.8636782 0.2377789 0.03037816 0.9951871 0.09316515 0.1473118 0.9889979 0.01350706 -0.4639071 0.8523463 0.2414461 -0.488241 0.8546071 0.176826 -0.4849036 0.8565054 0.1768251 -0.452359 0.8809074 0.1391893 -0.4624894 0.8797125 0.1104963 -0.4090734 0.9076643 0.0938335 -0.4265099 0.9033931 0.04438823 -0.3369078 0.9415011 0.008304774 -0.3214225 0.9454985 0.05215382 -0.2692164 0.9622321 0.04040008 -0.2548605 0.963635 0.08033531 -0.2088491 0.9750785 0.07485955 -0.1819295 0.9722582 0.1470232 -0.2197808 0.9629012 0.1565815 0.5055421 0.8521782 0.1349801 -0.5680362 0.8059421 0.1667102 -0.5917049 0.7987397 0.1090878 -0.3774346 0.8977594 0.2270935 -0.5299975 0.833529 0.155988 -0.5181515 0.8438865 0.1391926 -0.4794309 0.8639504 0.1540639 -0.182877 0.9647659 0.1891634 -0.1381934 0.9709721 0.1952332 0.06678289 0.9774919 0.2001242 0.2641853 0.9426141 0.2041686 0.3207815 0.9244834 0.205985 0.4956712 0.8473376 0.1906023 0.7116807 0.6840457 0.1599752 0.8239485 0.5444155 0.1572283 0.6584604 0.731228 0.1781446 -0.5406008 0.8115406 0.2217042 -0.5947393 0.7645673 0.2484393 -0.5944014 0.7634458 0.2526606 0.5093474 0.8435098 0.1704595 0.7117747 0.6866018 0.1481719 0.1419541 0.9652217 0.2195364 0.3206278 0.9219891 0.2171036 -0.2472093 0.9404869 0.2331777 -0.1388083 0.9603701 0.241706 -0.4967963 0.83875 0.2229167 -0.5682311 0.8026703 0.1812015 0.3165965 0.9372316 0.1461637 0.488249 0.8611552 0.1415092 -0.004256904 0.9743276 0.2250949 0.1416761 0.9658336 0.2170102 -0.3280233 0.9071512 0.2635857 -0.243954 0.9327423 0.2654774 -0.6155076 0.7398822 0.2715234 -0.5921673 0.7575405 0.2747189 0.05270361 0.9871661 0.15075 0.3067013 0.9464107 0.1011983 -0.1941085 0.9551944 0.2234404 -0.01077038 0.9808346 0.1945446 -0.4288613 0.8590914 0.2793563 -0.3270198 0.9060924 0.2684302 -0.6351754 0.7052485 0.3149237 -0.6065344 0.7304147 0.314023 -0.08443516 0.978379 0.1888002 -0.1225567 0.9761636 0.1791216 0.3698737 0.9014531 0.2248909 0.9360182 0.3136383 0.1596898 0.9610421 0.2269915 0.1577119 0.6964697 0.6863992 0.2092516 -0.5396757 0.8345887 0.1105074 -0.5392223 0.8354794 0.1058949 -0.5207787 0.8462009 0.1128431 -0.1811856 0.9699149 0.1625946 -0.121748 0.9776728 0.1712702 -0.3731526 0.9172741 0.1391597 -0.5909651 0.8008039 0.09733223 0.06759679 0.9797962 0.1882295 0.320371 0.926338 0.1981422 0.3185746 0.9229359 0.2161006 0.7451607 0.6317384 0.2136406 0.8235335 0.5434933 0.1625049 0.937501 0.3166116 0.1443927 0.6577303 0.7294697 0.1877896 0.6987545 0.6908536 0.1856437 0.4949528 0.8456296 0.1998304 0.2648992 0.9443644 0.1949466 0.9616451 0.2251332 0.1566965 0.9621244 0.223186 0.1565398 0.7497598 0.6281784 0.2079718 0.7536131 0.6235283 0.2080382 0.3804641 0.8993283 0.2155362 0.389459 0.8952032 0.2166405 -0.06874305 0.981668 0.1777704 -0.05496603 0.9820106 0.1806492 -0.50347 0.8579 0.1025953 -0.4881386 0.8661219 0.107488 0.9608777 0.2267155 0.159104 0.9613767 0.22471 0.1589351 0.7450823 0.6316418 0.2141991 0.7490147 0.6269574 0.2142465 0.3700462 0.901726 0.2235085 0.3794014 0.8975477 0.2246398 -0.08399379 0.979143 0.1849974 -0.06996464 0.9796795 0.1879709 -0.5201066 0.8473921 0.1068448 -0.5045517 0.8560885 0.1119833 0.2263578 0.1595973 0.9608803 0.03633797 0.8914834 0.4515939 0.03636085 0.8910157 0.4525142 -0.002511501 0.9878329 0.1554992 -0.00245583 0.9875462 0.1573105 0.1181985 0.1554467 0.9807474 0.1182376 0.1562967 0.9806077 0.09981113 0.4535143 0.8856425 0.09984046 0.4540171 0.8853815 0.07160931 0.7074281 0.7031484 0.07191288 0.6496076 0.756861 0.06335055 0.7602525 0.6465315 0.1685573 0.1549521 0.9734364 0.1686151 0.1576867 0.9729871 0.1328801 0.4541445 0.880963 0.1328548 0.4549894 0.8805307 0.08395218 0.7081809 0.701022 0.08395516 0.7079861 0.7012184 0.02671366 0.8918943 0.4514543 0.02685034 0.8910753 0.4530605 -0.0331766 0.987019 0.1571397 -0.03294682 0.9865314 0.1602198 0.276442 0.1558737 0.9483055 0.2707648 -0.07406938 0.9597917 0.1813762 0.4535033 0.8726039 0.1805545 0.4578227 0.8705163 0.1021423 0.710064 0.6966894 0.1022719 0.7096003 0.6971427 0.01223009 0.8936188 0.4486603 0.01372361 0.890834 0.4541215 -0.0788601 0.9848601 0.154375 -0.07614517 0.9831598 0.1661289 0.3411644 0.1490342 0.9281141 0.3379254 0.1659125 0.9264338 0.2479165 0.4565889 0.8544378 0.2454835 0.464102 0.8510859 0.1275284 0.7147338 0.6876715 0.1277661 0.7142643 0.6881151 -0.006827592 0.8950988 0.4458158 -0.003347039 0.8910602 0.453873 -0.1403858 0.9778361 0.1553335 -0.1340427 0.9757719 0.1729217 -0.1915608 0.9649287 0.1794914 -0.2038412 0.966629 0.1551684 -0.0190919 0.892004 0.4516241 -0.02586823 0.8972707 0.4407222 0.1554691 0.721753 0.6744644 0.1552259 0.7220803 0.6741698 0.3128764 0.4728513 0.8237233 0.3177559 0.4621114 0.8279398 0.4360923 0.1728906 0.8831379 0.5697762 0.0793845 0.8179568 0.4934666 0.1654915 0.8538756 0.4429491 0.1477948 0.8842809 -0.2963934 0.937045 0.1846556 -0.317126 0.9351029 0.1581574 -0.04377913 0.8991842 0.4353749 -0.05541092 0.9040176 0.423889 0.2142928 0.7460935 0.630415 0.2139781 0.7463854 0.6301763 0.4447126 0.4977797 0.7446113 0.4534481 0.4842802 0.7482363 -0.3365558 0.9246066 0.1784183 -0.3475406 0.9230691 0.1647998 -0.05340719 0.9051016 0.4218282 -0.05964988 0.9074249 0.4159591 0.236936 0.7591325 0.6062831 0.2369903 0.7591148 0.6062842 0.4943772 0.5069352 0.7061218 0.4988451 0.4999585 0.7079513 -0.2471158 0.9515663 0.1829083 -0.263405 0.9517409 0.1575029 -0.03317105 0.8947185 0.4453973 -0.04225265 0.8998537 0.4341409 0.1845796 0.7323931 0.655386 0.1843202 0.7327277 0.6550849 0.3803604 0.4840753 0.7880337 0.3871024 0.472042 0.7920406 0.5415097 0.1516087 0.8269113 0.6182149 0.185927 0.7637025 0.6291419 0.1550487 0.7616695 0.6825367 0.1841678 0.7072666 0.7466331 0.1780671 0.6409612 0.7044788 0.1781753 0.6869958 0.6877046 0.1680285 0.7062782 -0.4004228 0.899671 0.173936 -0.4285632 0.8907353 0.1514078 -0.05514878 0.9244844 0.3772099 -0.0712158 0.9270805 0.3680355 0.2984525 0.8004925 0.5197477 0.2982921 0.8006041 0.5196682 0.603807 0.5481439 0.5787535 0.6151648 0.5339252 0.580083 -0.3619332 0.9142854 0.1818978 -0.3887746 0.9080466 0.1559033 -0.05330729 0.9112293 0.4084357 -0.06839245 0.9149954 0.3976253 0.2629858 0.7745586 0.5752369 0.2627615 0.7747402 0.5750951 0.5403522 0.5248068 0.6577214 0.5513755 0.510222 0.6600444 0.7524104 0.165086 0.6376718 0.8120771 0.2084111 0.5450648 0.8240296 0.1741976 0.5391016 0.8576449 0.2020822 0.472872 -0.4326472 0.887254 0.1599898 -0.4510842 0.8802961 0.1469752 -0.05723869 0.939074 0.3389155 -0.06778442 0.9402505 0.3336679 0.3278217 0.8260876 0.4583801 0.3278461 0.8260697 0.4583947 0.6553034 0.5683569 0.497542 0.6625518 0.5592263 0.4982882 0.9029605 0.09500706 0.4190896 0.881347 0.1952574 0.430235 0.917414 0.1967893 0.3458693 0.9096517 0.2235333 0.3500954 0.7059445 0.581705 0.4040564 0.6970424 0.5925381 0.4037706 0.3556706 0.8525322 0.3829981 0.3557169 0.8525102 0.383004 -0.06527739 0.9558596 0.2864813 -0.05191391 0.9551879 0.2914122 -0.4739379 0.8704398 0.1331077 -0.4506027 0.8807449 0.1457588 0.9522572 0.2106242 0.221006 0.9469761 0.2310383 0.2232879 0.7434738 0.609116 0.2760877 0.736721 0.6173033 0.2760052 0.3817553 0.8825515 0.2745282 0.3817801 0.8825422 0.2745237 -0.05917173 0.97451 0.2164003 -0.04891341 0.9744849 0.2190591 -0.4888171 0.8649961 0.1133118 -0.4707696 0.8740149 0.1203087 0.008074104 0.984398 0.1757712 0.008647918 0.9876757 0.1562755 0.01862353 0.9051948 0.4245889 0.01851445 0.8907868 0.4540443 0.02970808 0.7929922 0.6085069 0.02981692 0.7599726 0.6492709 0.03489637 0.6491861 0.7598287 0.03818672 0.6082645 0.7928154 0.03847473 0.4244465 0.9046353 0.0397365 0.4536854 0.8902756 0.04682224 0.1562255 0.986611 0.04517471 0.1755783 0.9834285 0 0.9844335 0.1757582 0 0.9844242 0.1758099 0 0.9054177 0.424522 0 0.9053753 0.4246124 0 0.7933298 0.6087923 0 0.7933644 0.608747 0 0.6087167 0.7933877 0 0.4247258 0.9053221 0 0.1757729 0.9844308 0 0.1757637 0.9844325 -0.007185578 0.9876554 0.1564779 -0.009379684 0.9843931 0.1757336 -0.01970535 0.8907881 0.4539915 -0.01642119 0.9052598 0.424541 -0.03272807 0.7600498 0.6490402 -0.02794861 0.7930243 0.6085487 -0.03489482 0.6491567 0.759854 -0.03818672 0.6082645 0.7928154 -0.03854668 0.4536896 0.8903257 -0.04067289 0.4243616 0.904579 -0.04650539 0.1755807 0.983366 -0.04532605 0.1561984 0.9866852 0.4889368 0.8647848 0.114404 -0.3821162 0.8831744 0.2720116 -0.744092 0.6099897 0.2724699 -0.9202926 0.1984376 0.3371709 -0.947517 0.2301812 0.2218743 -0.9530166 0.2115069 0.2168506 -0.7621906 0.1773731 0.6225787 -0.8008846 0.2052325 0.5625511 -0.8143546 0.1741439 0.5536248 -0.8510422 0.2041137 0.4838025 -0.9182947 -4.8461e-4 0.3958973 -0.8836639 0.1945624 0.4257742 -0.9118923 0.22294 0.3446015 -0.5577949 0.1623514 0.8139453 -0.6106811 0.1856068 0.7698174 -0.6247439 0.1545133 0.7653892 -0.6800678 0.1844838 0.7095587 -0.780957 -0.07693427 0.6198285 -0.7283447 0.1715047 0.6634005 -0.7557886 0.1896008 0.6267656 -0.3821506 0.8831608 0.2720075 -0.3573859 0.8543459 0.3773177 -0.3574034 0.8543427 0.377308 -0.3264595 0.8242417 0.4626553 -0.3265811 0.8241817 0.4626764 -0.292937 0.7962369 0.5293342 -0.2929087 0.7962861 0.529276 -0.2684035 0.7792354 0.5663498 -0.2684972 0.7791985 0.566356 -0.2451654 0.763616 0.5973146 -0.2453733 0.7634528 0.5974377 -0.2119625 0.7452781 0.632165 -0.212279 0.7449697 0.6324222 -0.190312 0.7354749 0.6502754 -0.1903403 0.7354331 0.6503145 -0.1708805 0.7274521 0.66454 -0.1711261 0.7272668 0.6646796 -0.1427489 0.7185449 0.6806732 -0.1431364 0.7180896 0.6810722 -0.1220519 0.7136991 0.6897369 -0.1221334 0.7135275 0.6899001 -0.7374223 0.6174371 0.2738243 -0.7085682 0.583846 0.3963018 -0.6995714 0.593624 0.3977568 -0.6613828 0.5564637 0.5029126 -0.650523 0.5681576 0.5040008 -0.6057813 0.5309389 0.5925647 -0.5942094 0.5436131 0.59279 -0.5597333 0.5193776 0.6457133 -0.5546332 0.5245261 0.6459524 -0.5181747 0.500329 0.6936613 -0.5063797 0.5142157 0.6922152 -0.4497356 0.4833416 0.7510784 -0.4393892 0.4967032 0.7484806 -0.3992345 0.479359 0.7815541 -0.3958177 0.4834077 0.780798 -0.3563031 0.4673043 0.8091199 -0.3493565 0.4783064 0.8057128 -0.2874624 0.4594211 0.8404151 -0.2827299 0.4685475 0.836975 -0.2336663 0.4582749 0.8575455 -0.2320451 0.4615721 0.8562162 -0.2775848 0.1559851 0.9479532 -0.3178148 0.1626777 0.934093 -0.3205841 0.1541366 0.934595 -0.3923174 0.1693849 0.9040995 -0.3993064 0.1488721 0.9046499 -0.4690225 0.1702135 0.8666287 -0.5663191 -0.108917 0.8169578 -0.5208265 0.159282 0.838671 -0.5526447 0.1720473 0.8154653 -0.1025176 0.7102487 0.6964461 -0.1028621 0.7095148 0.6971429 -0.18304 0.453219 0.8724042 -0.1815559 0.4579125 0.8702608 -0.2744252 -0.08878195 0.9575013 -0.2270399 0.1599599 0.9606591 0.4712807 0.8740329 0.1181578 0.4750793 0.869665 0.1340991 0.4517471 0.8806742 0.1426104 0.4534034 0.8790726 0.147162 0.4263617 0.8901158 0.1609646 0.4232017 0.892723 0.1547455 0.3947326 0.9022997 0.1733251 0.3891245 0.9062841 0.165019 0.3771359 0.9099373 0.1725769 0.3665761 0.9168012 0.1584223 0.3386695 0.9230113 0.1826288 0.3153928 0.9356375 0.158461 0.2911983 0.9387888 0.1840632 0.2706772 0.947974 0.1675687 0.262617 0.9487714 0.1756852 0.2378925 0.9584283 0.1575515 0.2212186 0.958318 0.180801 0.1770064 0.9717671 0.1560049 0.1656167 0.970318 0.1762221 0.126851 0.9788766 0.1603415 0.1225831 0.9780089 0.1687362 0.08068108 0.9846854 0.1545488 0.07665151 0.9831229 0.1661142 0.01753175 0.9879738 0.1536247 0.01647871 0.9872187 0.1585172 -0.0315032 0.8922723 0.4503973 -0.01374465 0.8907938 0.4542001 -0.01156681 0.8936136 0.448688 1.57888e-4 0.8916459 0.4527333 0.002567589 0.8936474 0.4487625 0.01189875 0.891629 0.4526105 0.01809167 0.8960503 0.4435839 0.02646255 0.8935135 0.4482558 0.03574383 0.8983048 0.4379167 0.0385102 0.8971894 0.4399638 0.0428158 0.898659 0.4365533 0.04205179 0.8989741 0.4359787 0.05544596 0.9034556 0.425081 0.05000567 0.9064358 0.4193728 0.06565237 0.9100365 0.4092962 0.05884224 0.9145746 0.4001137 0.06548553 0.9154046 0.3971728 0.05516904 0.922632 0.3817154 0.07121688 0.9245175 0.3744273 0.05454415 0.9383379 0.3413898 0.06982034 0.939177 0.3362613 0.05183023 0.9566091 0.2867273 0.06494098 0.9566738 0.2838277 0.04907029 0.9750286 0.2165899 0.05904066 0.974713 0.2155199 -0.1417676 0.1561648 0.9775043 -0.1421601 0.1528295 0.9779744 -0.1153037 0.453843 0.8835903 -0.115565 0.4524698 0.8842601 -0.0878551 0.6495017 0.7552675 -0.07545077 0.7072266 0.7029492 -0.06671988 0.7603399 0.6460897 -0.03209406 0.8909758 0.452915 -0.9613966 0.2247427 0.1587684 -0.9608592 0.2266772 0.1592704 -0.7490786 0.6270466 0.2137612 -0.7450162 0.6315557 0.214682 -0.3795105 0.8977005 0.2238427 -0.3699384 0.901573 0.2243026 0.06984281 0.979902 0.1868531 0.08411288 0.9789232 0.1861035 0.5044361 0.8563434 0.1105453 0.5202273 0.8471368 0.1082726 -0.9621429 0.2232117 0.1563896 -0.9616252 0.2251126 0.1568481 -0.7536639 0.6236227 0.2075709 -0.749713 0.628081 0.2084342 -0.3895338 0.8953573 0.2158672 -0.3803909 0.8991751 0.2163034 0.05480128 0.9822197 0.1795586 0.06891518 0.9814587 0.1788561 0.4879633 0.8663935 0.1060861 0.5036268 0.8576409 0.103982 -0.867308 0.4764497 0.1441267 0.5501558 0.827869 0.1093689 0.5754535 0.8106364 0.1082691 0.1808884 0.9708325 0.1573649 0.1955143 0.9680159 0.157224 -0.06807315 0.9810281 0.1815215 -0.2176033 0.958884 0.1821826 -0.4060349 0.8923192 0.1972365 -0.5933499 0.7850281 0.1779522 -0.6586197 0.7313963 0.17686 -0.8237193 0.5439615 0.1599766 -0.9633333 0.2313918 0.1358189 -0.8646076 0.4704682 0.1763902 -0.7473688 0.6358208 0.1928004 -0.5908118 0.779154 0.2094295 -0.3717562 0.9046493 0.2083435 -0.215678 0.9543383 0.2066916 0.08328425 0.9802916 0.179143 0.196412 0.9659196 0.1685872 0.5206268 0.8464809 0.1114366 0.5749315 0.8118732 0.1015665 0.4275031 0.8586279 0.2828414 0.1982837 0.9567511 0.2128639 -0.04418653 0.9906912 0.1287577 -0.07059526 0.9920934 0.103765 -0.09350782 0.9814882 0.1671448 -0.3177312 0.9435238 0.09386056 0.4177158 0.8664768 0.2733708 0.4135102 0.8647275 0.285054 0.3227913 0.9090029 0.2636658 0.3217046 0.9078205 0.2690134 0.2346748 0.9371914 0.2580697 0.2357338 0.9400483 0.2464525 0.1674199 0.9559211 0.241217 0.1799061 0.9640169 0.1957173 0.1655519 0.9578103 0.2349296 0.002597808 0.9819636 0.1890527 -0.007388174 0.97139 0.2373751 -0.1580638 0.9654963 0.2069609 -0.1603739 0.959469 0.2317316 -0.2736601 0.9380779 0.2124148 0.576326 0.8027108 0.1533102 0.5756301 0.786827 0.222606 0.5945719 0.7727262 0.2222124 0.5902864 0.7611506 0.2687228 0.6144468 0.7414432 0.2696612 0.6064087 0.7326177 0.3090953 0.6315541 0.7090708 0.3136211 0.6253667 0.7066154 0.3310759 0.6279914 0.7029314 0.3339377 0.5526272 0.8187584 0.1556857 0.1835346 0.9624747 0.1998936 0.1679965 0.9649459 0.2016348 -0.06629681 0.9758822 0.2079874 -0.2735763 0.9387895 0.2093567 -0.4060328 0.8923627 0.1970438 -0.6585939 0.7313395 0.1771914 -0.3287671 0.9331417 0.1454607 -0.4893471 0.8596637 0.1466892 -0.5267221 0.8394617 0.1336715 -0.5310896 0.8278483 0.1805853 -0.6611052 0.7368052 0.1416267 -0.6617894 0.7285379 0.1768262 -0.8252092 0.5478636 0.137388 -0.2024461 0.9789878 -0.0244674 -0.03033125 0.9952012 0.09303015 0.7660704 0.5561437 0.3222427 0.6769979 0.6657412 0.3137876 0.6543762 0.6872931 0.3153095 0.6338769 0.7048971 0.3183084 0.2771348 0.9606789 0.01710474 0.2339879 0.9627708 0.1353589 0.2284882 0.964419 0.1330009 0.4504498 0.8650001 0.2210655 0.5373333 0.8078442 0.2422001 0.4526104 0.8807526 0.1393512 0.4690829 0.8783523 0.09197044 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 0 0 2 0 6 0 5 0 7 0 3 0 3 0 7 0 8 0 3 0 8 0 2 0 2 2 8 2 9 2 2 0 9 0 6 0 10 3 11 3 12 3 12 4 11 4 13 4 14 5 15 5 16 5 16 5 15 5 17 5 18 6 19 6 20 6 21 7 22 7 23 7 23 8 22 8 24 8 25 9 26 9 27 9 26 10 28 10 27 10 27 11 28 11 29 11 27 12 29 12 30 12 31 13 32 13 33 13 33 14 32 14 34 14 35 15 36 15 37 15 37 16 36 16 31 16 38 17 39 17 35 17 38 18 35 18 40 18 40 19 35 19 37 19 40 20 37 20 41 20 41 21 37 21 42 21 41 22 42 22 43 22 43 23 42 23 44 23 44 24 42 24 45 24 44 25 45 25 46 25 46 26 45 26 22 26 46 27 22 27 47 27 47 28 22 28 21 28 47 29 21 29 48 29 31 30 33 30 37 30 37 31 33 31 49 31 37 32 49 32 42 32 42 33 49 33 50 33 42 34 50 34 45 34 45 35 50 35 27 35 45 36 27 36 22 36 22 37 27 37 30 37 22 38 30 38 24 38 34 39 18 39 33 39 33 40 18 40 20 40 33 41 20 41 49 41 49 42 20 42 51 42 49 43 51 43 50 43 50 44 51 44 52 44 50 45 52 45 27 45 27 46 52 46 53 46 27 47 53 47 25 47 15 48 10 48 17 48 17 48 10 48 12 48 54 49 55 49 56 49 57 50 58 50 59 50 60 51 61 51 62 51 63 52 64 52 65 52 65 53 64 53 66 53 65 54 66 54 67 54 68 55 69 55 70 55 70 56 69 56 71 56 72 57 54 57 73 57 74 58 75 58 73 58 73 59 75 59 76 59 73 60 76 60 72 60 77 61 74 61 78 61 78 62 74 62 73 62 78 63 73 63 79 63 79 64 73 64 80 64 79 65 80 65 81 65 81 66 80 66 82 66 82 67 80 67 83 67 82 68 83 68 84 68 84 69 83 69 69 69 84 70 69 70 66 70 66 71 69 71 68 71 66 72 68 72 67 72 54 73 56 73 73 73 73 74 56 74 85 74 73 75 85 75 80 75 80 76 85 76 86 76 80 77 86 77 83 77 83 78 86 78 62 78 83 79 62 79 69 79 69 80 62 80 61 80 69 81 61 81 71 81 87 82 60 82 88 82 88 83 60 83 62 83 88 84 62 84 89 84 89 85 62 85 86 85 89 86 86 86 90 86 90 87 86 87 85 87 90 88 85 88 59 88 59 89 85 89 56 89 59 90 56 90 57 90 57 91 56 91 55 91 91 92 39 92 38 92 48 93 92 93 11 93 93 94 77 94 14 94 14 95 77 95 78 95 14 96 78 96 15 96 15 97 78 97 79 97 15 98 79 98 10 98 94 99 95 99 96 99 96 100 95 100 97 100 94 101 96 101 98 101 98 102 96 102 91 102 98 103 91 103 99 103 100 104 101 104 96 104 96 105 101 105 102 105 96 106 102 106 91 106 97 107 103 107 96 107 96 108 103 108 9 108 96 109 9 109 100 109 100 110 9 110 8 110 100 111 8 111 104 111 104 112 8 112 105 112 48 113 11 113 47 113 47 114 11 114 10 114 47 115 10 115 46 115 46 116 10 116 79 116 46 117 79 117 44 117 44 118 79 118 81 118 44 119 81 119 43 119 43 120 81 120 82 120 43 121 82 121 41 121 41 122 82 122 84 122 41 123 84 123 40 123 40 123 84 123 66 123 40 124 66 124 38 124 38 125 66 125 64 125 38 126 64 126 91 126 91 127 64 127 63 127 91 128 63 128 99 128 16 129 93 129 14 129 92 130 13 130 11 130 106 131 107 131 108 131 109 132 110 132 111 132 112 133 113 133 114 133 112 134 114 134 115 134 109 135 111 135 116 135 116 136 111 136 117 136 116 137 117 137 108 137 108 138 117 138 118 138 108 139 118 139 106 139 115 140 114 140 119 140 119 141 114 141 120 141 119 142 120 142 110 142 110 143 120 143 121 143 110 144 121 144 111 144 111 145 121 145 122 145 111 146 122 146 117 146 123 147 124 147 125 147 123 148 125 148 126 148 125 149 127 149 126 149 126 150 127 150 128 150 126 151 128 151 129 151 129 152 128 152 130 152 131 153 132 153 133 153 133 154 132 154 134 154 133 155 134 155 130 155 130 156 134 156 135 156 130 157 135 157 129 157 133 158 136 158 131 158 131 159 136 159 137 159 131 160 137 160 138 160 138 161 137 161 139 161 140 162 116 162 108 162 107 163 141 163 142 163 107 164 142 164 108 164 108 165 142 165 143 165 108 166 143 166 140 166 144 167 145 167 146 167 146 168 145 168 147 168 147 169 145 169 148 169 147 170 148 170 149 170 146 171 150 171 144 171 144 172 150 172 151 172 144 173 151 173 152 173 152 174 151 174 153 174 152 175 153 175 154 175 154 176 153 176 155 176 154 177 155 177 156 177 156 178 155 178 157 178 158 179 159 179 160 179 160 180 159 180 125 180 160 181 125 181 124 181 149 182 148 182 161 182 161 183 148 183 162 183 161 184 162 184 163 184 158 185 164 185 159 185 159 186 164 186 165 186 159 187 165 187 162 187 162 188 165 188 166 188 162 189 166 189 163 189 114 190 113 190 167 190 168 191 169 191 170 191 134 192 132 192 171 192 171 193 132 193 131 193 170 194 172 194 168 194 168 195 172 195 173 195 168 196 173 196 174 196 174 197 173 197 175 197 174 198 175 198 176 198 176 199 175 199 177 199 176 200 177 200 178 200 178 201 177 201 179 201 178 202 179 202 180 202 180 203 179 203 171 203 180 204 171 204 181 204 181 205 171 205 131 205 181 206 131 206 138 206 129 207 135 207 182 207 182 208 135 208 134 208 123 209 126 209 183 209 183 210 126 210 129 210 184 211 124 211 123 211 123 212 183 212 184 212 184 213 183 213 185 213 184 214 185 214 186 214 186 215 185 215 187 215 186 216 187 216 188 216 188 217 187 217 189 217 189 218 187 218 190 218 189 219 190 219 191 219 192 220 193 220 194 220 194 221 193 221 195 221 194 222 195 222 190 222 190 223 195 223 196 223 190 224 196 224 191 224 197 225 122 225 121 225 170 226 118 226 117 226 169 227 107 227 170 227 170 228 107 228 106 228 170 229 106 229 118 229 194 230 198 230 192 230 192 231 198 231 199 231 192 232 199 232 167 232 167 233 199 233 120 233 167 234 120 234 114 234 129 235 182 235 183 235 183 236 182 236 200 236 183 237 200 237 185 237 185 238 200 238 201 238 185 239 201 239 187 239 187 240 201 240 202 240 187 241 202 241 190 241 190 242 202 242 203 242 190 243 203 243 194 243 194 244 203 244 204 244 194 245 204 245 198 245 198 246 204 246 197 246 198 247 197 247 199 247 199 248 197 248 121 248 199 249 121 249 120 249 134 250 171 250 182 250 182 251 171 251 179 251 182 252 179 252 200 252 200 253 179 253 177 253 200 254 177 254 201 254 201 255 177 255 175 255 201 256 175 256 202 256 202 257 175 257 173 257 202 258 173 258 203 258 203 259 173 259 172 259 203 260 172 260 204 260 204 261 172 261 170 261 204 262 170 262 197 262 197 263 170 263 117 263 197 264 117 264 122 264 115 265 119 265 205 265 206 266 207 266 208 266 209 267 210 267 211 267 211 268 210 268 212 268 119 269 110 269 205 269 205 270 110 270 213 270 205 271 213 271 214 271 214 272 213 272 215 272 210 273 206 273 212 273 212 274 206 274 208 274 212 275 208 275 216 275 110 276 109 276 213 276 213 277 109 277 116 277 213 278 116 278 217 278 218 279 219 279 220 279 220 280 219 280 221 280 220 281 221 281 222 281 222 282 221 282 223 282 222 283 223 283 216 283 216 284 223 284 224 284 216 285 224 285 212 285 212 286 224 286 225 286 212 287 225 287 211 287 113 288 112 288 226 288 226 289 112 289 115 289 226 290 115 290 227 290 227 291 115 291 205 291 227 292 205 292 228 292 228 293 205 293 214 293 228 294 214 294 229 294 229 295 214 295 215 295 208 296 230 296 216 296 216 297 230 297 231 297 216 298 231 298 222 298 222 299 231 299 232 299 222 300 232 300 233 300 217 301 218 301 213 301 213 302 218 302 220 302 213 303 220 303 215 303 215 304 220 304 222 304 215 305 222 305 229 305 229 306 222 306 233 306 229 307 233 307 228 307 228 308 233 308 234 308 228 309 234 309 227 309 227 310 234 310 235 310 227 311 235 311 226 311 236 312 237 312 238 312 238 313 237 313 239 313 238 314 239 314 240 314 239 315 241 315 240 315 240 316 241 316 242 316 240 317 242 317 243 317 243 318 242 318 244 318 243 319 244 319 245 319 244 320 246 320 245 320 245 321 246 321 247 321 245 322 247 322 248 322 248 323 247 323 249 323 248 324 249 324 250 324 250 325 249 325 251 325 250 326 251 326 252 326 252 327 251 327 253 327 252 328 253 328 254 328 254 329 253 329 255 329 256 330 257 330 258 330 258 331 257 331 259 331 258 332 259 332 255 332 255 333 259 333 260 333 255 334 260 334 254 334 261 335 262 335 263 335 236 336 264 336 265 336 265 337 264 337 266 337 267 338 268 338 269 338 269 339 268 339 266 339 269 340 266 340 270 340 270 341 266 341 264 341 263 342 262 342 271 342 262 343 272 343 271 343 271 344 272 344 273 344 271 345 273 345 267 345 267 346 273 346 274 346 267 347 274 347 268 347 261 348 263 348 275 348 275 349 263 349 276 349 275 350 276 350 277 350 277 351 276 351 278 351 277 352 278 352 279 352 279 353 278 353 280 353 279 354 280 354 281 354 281 355 280 355 156 355 281 356 156 356 157 356 282 357 283 357 284 357 285 358 283 358 286 358 287 359 283 359 285 359 288 360 286 360 283 360 289 361 283 361 290 361 291 362 283 362 289 362 292 363 290 363 283 363 287 364 292 364 283 364 293 365 283 365 294 365 295 366 283 366 293 366 296 367 294 367 283 367 291 368 296 368 283 368 297 369 298 369 299 369 283 370 300 370 301 370 302 371 300 371 283 371 295 372 302 372 283 372 303 373 304 373 305 373 306 374 307 374 308 374 308 375 307 375 309 375 310 376 311 376 312 376 312 377 311 377 313 377 312 378 313 378 314 378 303 379 305 379 315 379 315 380 305 380 316 380 315 381 316 381 317 381 318 382 319 382 305 382 305 383 319 383 320 383 305 384 320 384 316 384 321 385 322 385 323 385 323 386 322 386 324 386 323 387 324 387 318 387 283 388 325 388 326 388 326 389 325 389 321 389 326 390 321 390 327 390 327 391 321 391 323 391 328 392 329 392 330 392 331 393 332 393 329 393 333 394 334 394 335 394 147 395 149 395 334 395 334 396 333 396 147 396 147 397 333 397 336 397 147 398 336 398 146 398 146 399 336 399 150 399 150 400 336 400 337 400 150 401 337 401 151 401 151 402 337 402 338 402 151 403 338 403 153 403 298 404 157 404 339 404 339 405 157 405 155 405 339 406 155 406 340 406 340 407 155 407 153 407 340 408 153 408 341 408 341 409 153 409 338 409 299 410 298 410 342 410 343 411 344 411 345 411 345 412 344 412 346 412 346 413 347 413 345 413 345 414 347 414 348 414 345 415 348 415 349 415 350 416 351 416 352 416 352 417 351 417 353 417 306 418 308 418 350 418 350 419 308 419 354 419 350 420 354 420 351 420 298 421 339 421 342 421 342 422 339 422 340 422 342 423 340 423 355 423 355 424 340 424 341 424 355 425 341 425 356 425 356 426 341 426 338 426 356 427 338 427 357 427 357 428 338 428 337 428 357 429 337 429 358 429 358 430 337 430 336 430 358 431 336 431 359 431 359 432 336 432 333 432 359 433 333 433 360 433 360 434 333 434 335 434 360 435 335 435 332 435 332 436 331 436 360 436 360 437 331 437 361 437 360 438 361 438 359 438 359 439 361 439 362 439 359 440 362 440 358 440 358 441 362 441 363 441 358 442 363 442 357 442 357 443 363 443 364 443 357 444 364 444 356 444 356 445 364 445 365 445 356 446 365 446 355 446 355 447 365 447 366 447 355 448 366 448 342 448 342 449 366 449 349 449 342 450 349 450 299 450 299 451 349 451 348 451 299 452 348 452 297 452 329 453 367 453 331 453 331 454 367 454 368 454 331 455 368 455 361 455 361 456 368 456 369 456 361 457 369 457 362 457 362 458 369 458 370 458 362 459 370 459 363 459 363 460 370 460 371 460 363 461 371 461 364 461 364 462 371 462 372 462 364 463 372 463 365 463 365 464 372 464 373 464 365 465 373 465 366 465 366 466 373 466 374 466 366 467 374 467 349 467 349 468 374 468 375 468 349 469 375 469 345 469 345 470 375 470 352 470 345 471 352 471 343 471 343 472 352 472 353 472 343 473 353 473 344 473 312 474 376 474 310 474 310 475 376 475 377 475 310 476 377 476 378 476 378 477 377 477 379 477 378 478 379 478 380 478 380 479 379 479 381 479 380 480 381 480 382 480 382 481 381 481 383 481 382 482 383 482 384 482 384 483 383 483 385 483 384 484 385 484 386 484 386 485 385 485 387 485 386 486 387 486 388 486 388 487 387 487 389 487 388 488 389 488 390 488 390 489 389 489 391 489 390 490 391 490 392 490 392 491 391 491 393 491 392 492 393 492 394 492 394 493 393 493 395 493 394 494 395 494 396 494 396 495 395 495 397 495 396 496 397 496 398 496 398 497 397 497 399 497 398 498 399 498 400 498 400 499 399 499 401 499 400 500 401 500 402 500 402 501 401 501 403 501 402 502 403 502 404 502 404 503 403 503 328 503 404 504 328 504 405 504 405 505 328 505 330 505 405 506 330 506 301 506 329 507 328 507 367 507 367 508 328 508 403 508 367 509 403 509 368 509 368 510 403 510 401 510 368 511 401 511 369 511 369 512 401 512 399 512 369 513 399 513 370 513 370 514 399 514 397 514 370 515 397 515 371 515 371 516 397 516 395 516 371 517 395 517 372 517 372 518 395 518 393 518 372 519 393 519 373 519 373 520 393 520 391 520 373 521 391 521 374 521 374 522 391 522 389 522 374 523 389 523 375 523 375 524 389 524 387 524 375 525 387 525 352 525 352 526 387 526 385 526 352 527 385 527 350 527 350 528 385 528 383 528 350 529 383 529 306 529 306 530 383 530 381 530 306 531 381 531 307 531 307 532 381 532 379 532 307 533 379 533 309 533 282 534 288 534 283 534 406 535 284 535 283 535 301 536 300 536 405 536 405 537 300 537 302 537 405 538 302 538 404 538 404 539 302 539 295 539 404 540 295 540 402 540 402 541 295 541 293 541 402 542 293 542 400 542 400 543 293 543 294 543 400 544 294 544 398 544 398 545 294 545 296 545 398 546 296 546 396 546 396 547 296 547 291 547 396 548 291 548 394 548 394 549 291 549 289 549 394 550 289 550 392 550 392 551 289 551 290 551 392 552 290 552 390 552 390 553 290 553 292 553 390 554 292 554 388 554 388 555 292 555 287 555 388 556 287 556 386 556 386 557 287 557 285 557 386 558 285 558 384 558 384 559 285 559 286 559 384 560 286 560 382 560 382 561 286 561 288 561 382 562 288 562 380 562 380 563 288 563 282 563 380 564 282 564 378 564 378 565 282 565 284 565 378 566 284 566 310 566 310 567 284 567 406 567 310 568 406 568 311 568 407 569 408 569 409 569 409 570 408 570 410 570 409 571 410 571 411 571 411 572 410 572 412 572 411 573 412 573 413 573 413 574 412 574 414 574 413 575 414 575 283 575 408 576 314 576 410 576 410 577 314 577 313 577 410 578 313 578 412 578 412 579 313 579 311 579 412 580 311 580 414 580 414 581 311 581 406 581 414 582 406 582 283 582 304 583 415 583 416 583 416 584 415 584 417 584 416 585 417 585 418 585 418 586 417 586 419 586 418 587 419 587 420 587 420 588 419 588 421 588 420 589 421 589 283 589 415 590 407 590 417 590 417 591 407 591 409 591 417 592 409 592 419 592 419 593 409 593 411 593 419 594 411 594 421 594 421 595 411 595 413 595 421 596 413 596 283 596 323 597 422 597 327 597 327 598 422 598 423 598 327 599 423 599 326 599 326 600 423 600 424 600 326 601 424 601 283 601 318 602 305 602 323 602 323 603 305 603 304 603 323 604 304 604 422 604 422 605 304 605 416 605 422 606 416 606 423 606 423 607 416 607 418 607 423 608 418 608 424 608 424 609 418 609 420 609 424 610 420 610 283 610 425 611 209 611 116 611 116 612 209 612 211 612 116 613 211 613 225 613 221 614 219 614 116 614 116 615 219 615 218 615 116 616 218 616 217 616 116 617 140 617 425 617 425 618 140 618 426 618 425 619 426 619 427 619 427 620 428 620 425 620 425 621 428 621 429 621 425 622 429 622 430 622 430 623 429 623 431 623 225 624 224 624 116 624 116 625 224 625 223 625 116 626 223 626 221 626 432 627 433 627 434 627 434 628 435 628 432 628 432 629 435 629 436 629 432 630 436 630 437 630 437 631 436 631 438 631 437 632 438 632 439 632 439 633 438 633 440 633 439 634 440 634 441 634 441 635 440 635 442 635 438 636 443 636 440 636 440 637 443 637 140 637 440 638 140 638 442 638 442 639 140 639 143 639 442 640 143 640 444 640 444 641 143 641 142 641 444 642 142 642 445 642 445 643 142 643 141 643 446 644 447 644 448 644 449 645 450 645 451 645 449 646 451 646 452 646 449 647 452 647 453 647 453 648 452 648 448 648 453 649 448 649 454 649 454 650 448 650 447 650 446 651 448 651 455 651 455 652 448 652 456 652 455 653 456 653 457 653 457 654 456 654 458 654 457 655 458 655 459 655 460 656 461 656 462 656 462 657 461 657 463 657 462 658 463 658 464 658 464 659 463 659 465 659 464 660 465 660 466 660 257 661 256 661 467 661 467 662 256 662 468 662 467 663 468 663 469 663 469 664 468 664 470 664 469 665 470 665 471 665 471 666 470 666 472 666 471 667 472 667 473 667 473 668 472 668 466 668 473 669 466 669 474 669 474 670 466 670 465 670 475 671 476 671 477 671 478 672 479 672 480 672 481 673 482 673 483 673 478 674 480 674 484 674 475 675 477 675 485 675 208 676 486 676 230 676 230 677 486 677 487 677 230 678 487 678 231 678 231 679 487 679 488 679 231 680 488 680 232 680 232 681 488 681 233 681 233 682 488 682 489 682 233 683 489 683 234 683 234 684 489 684 235 684 235 685 489 685 490 685 235 686 490 686 226 686 226 687 490 687 491 687 226 688 491 688 113 688 113 689 491 689 492 689 113 690 492 690 167 690 167 691 492 691 493 691 167 692 493 692 192 692 192 693 493 693 494 693 192 694 494 694 193 694 193 695 494 695 495 695 193 696 495 696 195 696 195 697 495 697 196 697 196 698 495 698 496 698 196 699 496 699 191 699 191 700 496 700 497 700 191 701 497 701 189 701 189 702 497 702 498 702 189 703 498 703 188 703 188 704 498 704 499 704 188 705 499 705 186 705 186 706 499 706 500 706 186 707 500 707 184 707 184 708 500 708 160 708 184 709 160 709 124 709 334 710 149 710 161 710 161 711 501 711 334 711 334 712 501 712 502 712 334 713 502 713 335 713 335 714 502 714 503 714 335 715 503 715 332 715 504 716 321 716 505 716 505 717 321 717 325 717 505 718 325 718 506 718 506 719 325 719 283 719 506 720 283 720 507 720 507 721 283 721 301 721 507 722 301 722 508 722 508 723 301 723 330 723 508 724 330 724 509 724 509 725 330 725 329 725 509 726 329 726 510 726 510 727 329 727 332 727 510 728 332 728 511 728 511 729 332 729 503 729 512 730 318 730 513 730 513 731 318 731 324 731 513 732 324 732 504 732 504 733 324 733 322 733 504 734 322 734 321 734 514 735 317 735 515 735 515 736 317 736 316 736 515 737 316 737 516 737 516 738 316 738 320 738 516 739 320 739 512 739 512 740 320 740 319 740 512 741 319 741 318 741 165 742 164 742 517 742 517 743 164 743 518 743 517 744 518 744 519 744 519 745 518 745 520 745 519 746 520 746 521 746 521 747 520 747 522 747 521 748 522 748 523 748 523 749 522 749 524 749 523 750 524 750 525 750 525 751 524 751 526 751 525 752 526 752 527 752 527 753 526 753 528 753 527 754 528 754 529 754 529 755 528 755 530 755 529 756 530 756 531 756 531 757 530 757 532 757 531 758 532 758 533 758 533 759 532 759 534 759 533 760 534 760 535 760 535 761 534 761 536 761 535 762 536 762 537 762 537 763 536 763 538 763 537 764 538 764 539 764 539 765 538 765 540 765 539 766 540 766 541 766 541 767 540 767 542 767 541 768 542 768 543 768 543 769 542 769 544 769 543 770 544 770 480 770 480 771 544 771 545 771 480 772 545 772 484 772 164 773 158 773 518 773 518 774 158 774 546 774 518 775 546 775 520 775 520 776 546 776 547 776 520 777 547 777 522 777 522 778 547 778 548 778 522 779 548 779 524 779 524 780 548 780 549 780 524 781 549 781 526 781 526 782 549 782 550 782 526 783 550 783 528 783 528 784 550 784 551 784 528 785 551 785 530 785 530 786 551 786 552 786 530 787 552 787 532 787 532 788 552 788 553 788 532 789 553 789 534 789 534 790 553 790 554 790 534 791 554 791 536 791 536 792 554 792 555 792 536 793 555 793 538 793 538 794 555 794 556 794 538 795 556 795 540 795 540 796 556 796 557 796 540 797 557 797 542 797 542 798 557 798 558 798 542 799 558 799 544 799 544 800 558 800 559 800 544 801 559 801 545 801 545 802 559 802 477 802 545 803 477 803 484 803 484 804 477 804 476 804 158 805 160 805 546 805 546 806 160 806 500 806 546 807 500 807 547 807 547 808 500 808 499 808 547 809 499 809 548 809 548 810 499 810 498 810 548 811 498 811 549 811 549 812 498 812 497 812 549 813 497 813 550 813 550 814 497 814 496 814 550 815 496 815 551 815 551 816 496 816 495 816 551 817 495 817 552 817 552 818 495 818 494 818 552 819 494 819 553 819 553 820 494 820 493 820 553 821 493 821 554 821 554 822 493 822 492 822 554 823 492 823 555 823 555 824 492 824 491 824 555 825 491 825 556 825 556 826 491 826 490 826 556 827 490 827 557 827 557 828 490 828 489 828 557 829 489 829 558 829 558 830 489 830 488 830 558 831 488 831 559 831 559 832 488 832 487 832 559 833 487 833 477 833 477 834 487 834 486 834 477 835 486 835 485 835 485 836 486 836 208 836 485 837 208 837 207 837 163 838 166 838 560 838 560 839 166 839 561 839 560 840 561 840 562 840 562 841 561 841 563 841 562 842 563 842 564 842 564 843 563 843 565 843 564 844 565 844 566 844 566 845 565 845 567 845 566 846 567 846 568 846 568 847 567 847 569 847 568 848 569 848 570 848 570 849 569 849 571 849 570 850 571 850 572 850 572 851 571 851 573 851 572 852 573 852 574 852 574 853 573 853 575 853 574 854 575 854 576 854 576 855 575 855 577 855 576 856 577 856 578 856 578 857 577 857 579 857 578 858 579 858 580 858 580 859 579 859 581 859 580 860 581 860 582 860 582 861 581 861 583 861 582 862 583 862 584 862 584 863 583 863 585 863 584 864 585 864 586 864 586 865 585 865 587 865 586 866 587 866 483 866 483 867 587 867 588 867 483 868 588 868 481 868 481 869 588 869 589 869 161 870 163 870 501 870 501 871 163 871 560 871 501 872 560 872 502 872 502 873 560 873 562 873 502 874 562 874 503 874 503 875 562 875 564 875 503 876 564 876 511 876 511 877 564 877 566 877 511 878 566 878 510 878 510 879 566 879 568 879 510 880 568 880 509 880 509 881 568 881 570 881 509 882 570 882 508 882 508 883 570 883 572 883 508 884 572 884 507 884 507 885 572 885 574 885 507 886 574 886 506 886 506 887 574 887 576 887 506 888 576 888 505 888 505 889 576 889 578 889 505 890 578 890 504 890 504 891 578 891 580 891 504 892 580 892 513 892 513 893 580 893 582 893 513 894 582 894 512 894 512 895 582 895 584 895 512 896 584 896 516 896 516 897 584 897 586 897 516 898 586 898 515 898 515 899 586 899 483 899 515 900 483 900 514 900 514 901 483 901 482 901 166 902 165 902 561 902 561 903 165 903 517 903 561 904 517 904 563 904 563 905 517 905 519 905 563 906 519 906 565 906 565 907 519 907 521 907 565 908 521 908 567 908 567 909 521 909 523 909 567 910 523 910 569 910 569 911 523 911 525 911 569 912 525 912 571 912 571 913 525 913 527 913 571 914 527 914 573 914 573 915 527 915 529 915 573 916 529 916 575 916 575 917 529 917 531 917 575 918 531 918 577 918 577 919 531 919 533 919 577 920 533 920 579 920 579 921 533 921 535 921 579 922 535 922 581 922 581 923 535 923 537 923 581 924 537 924 583 924 583 925 537 925 539 925 583 926 539 926 585 926 585 927 539 927 541 927 585 928 541 928 587 928 587 929 541 929 543 929 587 930 543 930 588 930 588 931 543 931 480 931 588 932 480 932 589 932 589 933 480 933 479 933 590 934 207 934 591 934 591 935 207 935 206 935 591 936 206 936 592 936 206 937 210 937 592 937 592 938 210 938 209 938 592 939 209 939 425 939 593 940 594 940 595 940 596 941 597 941 598 941 599 942 600 942 601 942 602 943 603 943 604 943 605 944 606 944 603 944 607 945 608 945 609 945 609 946 608 946 610 946 611 947 612 947 613 947 614 948 237 948 615 948 615 949 237 949 236 949 615 950 236 950 616 950 617 951 242 951 618 951 618 952 242 952 241 952 618 953 241 953 614 953 614 954 241 954 239 954 614 955 239 955 237 955 619 956 620 956 244 956 244 957 620 957 246 957 246 958 620 958 247 958 247 959 620 959 621 959 247 960 621 960 249 960 622 961 623 961 624 961 624 962 623 962 625 962 249 963 621 963 251 963 251 964 621 964 626 964 251 965 626 965 253 965 253 966 626 966 627 966 253 967 627 967 255 967 255 968 627 968 624 968 255 969 624 969 258 969 258 970 624 970 625 970 258 971 625 971 256 971 599 972 628 972 629 972 629 973 628 973 630 973 629 974 630 974 631 974 631 975 630 975 632 975 631 976 632 976 633 976 634 977 635 977 636 977 636 978 635 978 637 978 636 979 637 979 638 979 639 980 640 980 641 980 641 981 640 981 642 981 643 982 640 982 644 982 644 983 640 983 639 983 644 984 639 984 645 984 594 985 646 985 595 985 595 986 646 986 647 986 595 987 647 987 648 987 648 988 647 988 649 988 650 989 651 989 652 989 652 990 651 990 609 990 652 991 609 991 653 991 653 992 609 992 610 992 653 993 610 993 606 993 603 994 602 994 605 994 605 995 602 995 654 995 605 996 654 996 655 996 655 997 654 997 656 997 655 998 656 998 657 998 658 999 659 999 660 999 660 1000 659 1000 661 1000 660 1001 661 1001 662 1001 662 1002 661 1002 663 1002 662 1003 663 1003 593 1003 596 1004 598 1004 664 1004 664 1005 598 1005 665 1005 664 1006 665 1006 666 1006 666 1007 665 1007 667 1007 666 1008 667 1008 668 1008 668 1009 667 1009 669 1009 668 1010 669 1010 670 1010 670 1011 669 1011 671 1011 670 1012 671 1012 672 1012 673 1013 674 1013 675 1013 675 1014 674 1014 634 1014 675 1015 634 1015 676 1015 676 1016 634 1016 636 1016 676 1017 636 1017 677 1017 677 1018 636 1018 638 1018 677 1019 638 1019 633 1019 678 1020 597 1020 679 1020 679 1021 597 1021 596 1021 679 1022 596 1022 680 1022 606 1023 605 1023 653 1023 653 1024 605 1024 655 1024 653 1025 655 1025 652 1025 652 1026 655 1026 657 1026 652 1027 657 1027 650 1027 604 1028 681 1028 602 1028 602 1029 681 1029 682 1029 602 1030 682 1030 654 1030 654 1031 682 1031 643 1031 654 1032 643 1032 656 1032 656 1033 643 1033 644 1033 656 1034 644 1034 657 1034 657 1035 644 1035 645 1035 657 1036 645 1036 650 1036 616 1037 683 1037 615 1037 615 1038 683 1038 684 1038 615 1039 684 1039 614 1039 614 1040 684 1040 680 1040 614 1041 680 1041 618 1041 618 1042 680 1042 685 1042 618 1043 685 1043 617 1043 617 1044 685 1044 686 1044 617 1045 686 1045 687 1045 687 1046 686 1046 688 1046 687 1047 688 1047 689 1047 689 1048 688 1048 690 1048 689 1049 690 1049 691 1049 691 1050 690 1050 692 1050 691 1051 692 1051 693 1051 693 1052 692 1052 694 1052 693 1053 694 1053 601 1053 680 1054 596 1054 685 1054 685 1055 596 1055 664 1055 685 1056 664 1056 686 1056 686 1057 664 1057 666 1057 686 1058 666 1058 688 1058 688 1059 666 1059 668 1059 688 1060 668 1060 690 1060 690 1061 668 1061 670 1061 690 1062 670 1062 692 1062 692 1063 670 1063 672 1063 692 1064 672 1064 694 1064 684 1065 695 1065 680 1065 680 1066 695 1066 696 1066 680 1067 696 1067 679 1067 679 1068 696 1068 612 1068 679 1069 612 1069 678 1069 678 1070 612 1070 611 1070 678 1071 611 1071 597 1071 597 1072 611 1072 697 1072 597 1073 697 1073 598 1073 598 1074 697 1074 698 1074 598 1075 698 1075 665 1075 665 1076 698 1076 699 1076 665 1077 699 1077 667 1077 667 1078 699 1078 700 1078 667 1079 700 1079 669 1079 669 1080 700 1080 701 1080 669 1081 701 1081 671 1081 671 1082 701 1082 702 1082 659 1083 637 1083 661 1083 661 1084 637 1084 635 1084 661 1085 635 1085 663 1085 663 1086 635 1086 634 1086 663 1087 634 1087 593 1087 593 1088 634 1088 674 1088 593 1089 674 1089 594 1089 594 1090 674 1090 673 1090 594 1091 673 1091 646 1091 641 1092 658 1092 639 1092 639 1093 658 1093 660 1093 639 1094 660 1094 645 1094 645 1095 660 1095 662 1095 645 1096 662 1096 650 1096 650 1097 662 1097 593 1097 650 1098 593 1098 651 1098 651 1099 593 1099 595 1099 651 1100 595 1100 609 1100 609 1101 595 1101 648 1101 609 1102 648 1102 607 1102 607 1103 648 1103 649 1103 607 1104 649 1104 608 1104 244 1105 242 1105 619 1105 619 1106 242 1106 617 1106 619 1107 617 1107 620 1107 620 1108 617 1108 687 1108 620 1109 687 1109 621 1109 621 1110 687 1110 689 1110 621 1111 689 1111 626 1111 626 1112 689 1112 691 1112 626 1113 691 1113 627 1113 627 1114 691 1114 693 1114 627 1115 693 1115 624 1115 624 1116 693 1116 601 1116 624 1117 601 1117 622 1117 622 1118 601 1118 600 1118 599 1119 601 1119 628 1119 628 1120 601 1120 694 1120 628 1121 694 1121 630 1121 630 1122 694 1122 672 1122 630 1123 672 1123 632 1123 632 1124 672 1124 671 1124 632 1125 671 1125 633 1125 633 1126 671 1126 702 1126 633 1127 702 1127 677 1127 677 1128 702 1128 701 1128 677 1129 701 1129 676 1129 676 1130 701 1130 700 1130 676 1131 700 1131 675 1131 675 1132 700 1132 699 1132 675 1133 699 1133 673 1133 673 1134 699 1134 698 1134 673 1135 698 1135 646 1135 646 1136 698 1136 697 1136 646 1137 697 1137 647 1137 647 1138 697 1138 611 1138 647 1139 611 1139 649 1139 649 1140 611 1140 613 1140 649 1141 613 1141 608 1141 703 1142 704 1142 705 1142 612 1143 706 1143 613 1143 613 1144 706 1144 707 1144 613 1145 707 1145 608 1145 608 1146 708 1146 610 1146 610 1147 708 1147 709 1147 610 1148 709 1148 606 1148 606 1149 709 1149 710 1149 606 1150 710 1150 603 1150 603 1151 710 1151 711 1151 603 1152 711 1152 604 1152 315 1153 317 1153 712 1153 712 1154 713 1154 315 1154 315 1155 713 1155 714 1155 315 1156 714 1156 303 1156 303 1157 714 1157 715 1157 303 1158 715 1158 304 1158 304 1159 715 1159 716 1159 304 1160 716 1160 415 1160 415 1161 716 1161 717 1161 415 1162 717 1162 407 1162 407 1163 717 1163 408 1163 408 1164 717 1164 718 1164 408 1165 718 1165 314 1165 314 1166 718 1166 312 1166 312 1167 718 1167 719 1167 312 1168 719 1168 376 1168 379 1169 377 1169 720 1169 720 1170 377 1170 376 1170 379 1171 720 1171 721 1171 379 1172 721 1172 309 1172 309 1173 721 1173 308 1173 308 1174 721 1174 722 1174 308 1175 722 1175 354 1175 348 1176 347 1176 723 1176 723 1177 347 1177 346 1177 346 1178 344 1178 723 1178 723 1179 344 1179 353 1179 723 1180 353 1180 722 1180 722 1181 353 1181 351 1181 722 1182 351 1182 354 1182 348 1183 723 1183 297 1183 297 1184 723 1184 724 1184 297 1185 724 1185 298 1185 298 1186 724 1186 281 1186 298 1187 281 1187 157 1187 262 1188 261 1188 725 1188 725 1189 261 1189 275 1189 726 1190 272 1190 262 1190 727 1191 273 1191 272 1191 728 1192 265 1192 266 1192 706 1193 729 1193 707 1193 707 1194 729 1194 730 1194 707 1195 730 1195 608 1195 608 1196 730 1196 731 1196 608 1197 731 1197 708 1197 376 1198 719 1198 720 1198 720 1199 719 1199 732 1199 720 1200 732 1200 721 1200 721 1201 732 1201 733 1201 721 1202 733 1202 722 1202 712 1203 734 1203 713 1203 713 1204 734 1204 735 1204 713 1205 735 1205 714 1205 714 1206 735 1206 736 1206 714 1207 736 1207 715 1207 715 1208 736 1208 737 1208 715 1209 737 1209 716 1209 716 1210 737 1210 738 1210 716 1211 738 1211 717 1211 717 1212 738 1212 739 1212 717 1213 739 1213 718 1213 718 1214 739 1214 740 1214 718 1215 740 1215 719 1215 719 1216 740 1216 741 1216 719 1217 741 1217 732 1217 732 1218 741 1218 742 1218 732 1219 742 1219 733 1219 743 1220 744 1220 745 1220 745 1221 744 1221 746 1221 745 1222 746 1222 747 1222 747 1223 746 1223 748 1223 747 1224 748 1224 749 1224 749 1225 748 1225 750 1225 749 1226 750 1226 751 1226 751 1227 750 1227 752 1227 751 1228 752 1228 753 1228 753 1229 752 1229 277 1229 753 1230 277 1230 279 1230 740 1231 743 1231 741 1231 741 1232 743 1232 745 1232 741 1233 745 1233 742 1233 742 1234 745 1234 747 1234 742 1235 747 1235 733 1235 733 1236 747 1236 749 1236 733 1237 749 1237 722 1237 722 1238 749 1238 751 1238 722 1239 751 1239 723 1239 723 1240 751 1240 753 1240 723 1241 753 1241 724 1241 724 1242 753 1242 279 1242 724 1243 279 1243 281 1243 734 1244 754 1244 735 1244 735 1245 754 1245 755 1245 735 1246 755 1246 736 1246 736 1247 755 1247 756 1247 736 1248 756 1248 737 1248 737 1249 756 1249 757 1249 737 1250 757 1250 738 1250 738 1251 757 1251 758 1251 738 1252 758 1252 739 1252 739 1253 758 1253 759 1253 739 1254 759 1254 740 1254 740 1255 759 1255 760 1255 740 1256 760 1256 743 1256 743 1257 760 1257 761 1257 743 1258 761 1258 744 1258 760 1259 762 1259 761 1259 761 1260 762 1260 763 1260 761 1261 763 1261 744 1261 744 1262 763 1262 764 1262 744 1263 764 1263 746 1263 746 1264 764 1264 765 1264 746 1265 765 1265 748 1265 748 1266 765 1266 766 1266 748 1267 766 1267 750 1267 750 1268 766 1268 725 1268 750 1269 725 1269 752 1269 752 1270 725 1270 275 1270 752 1271 275 1271 277 1271 754 1272 767 1272 755 1272 755 1273 767 1273 768 1273 755 1274 768 1274 756 1274 756 1275 768 1275 769 1275 756 1276 769 1276 757 1276 757 1277 769 1277 770 1277 757 1278 770 1278 758 1278 758 1279 770 1279 771 1279 758 1280 771 1280 759 1280 759 1281 771 1281 772 1281 759 1282 772 1282 760 1282 760 1283 772 1283 773 1283 760 1284 773 1284 762 1284 703 1285 705 1285 774 1285 774 1286 705 1286 775 1286 774 1287 775 1287 776 1287 776 1288 775 1288 777 1288 776 1289 777 1289 778 1289 778 1290 777 1290 779 1290 778 1291 779 1291 780 1291 780 1292 779 1292 781 1292 780 1293 781 1293 727 1293 272 1294 726 1294 727 1294 727 1295 726 1295 782 1295 727 1296 782 1296 780 1296 780 1297 782 1297 783 1297 780 1298 783 1298 778 1298 778 1299 783 1299 784 1299 778 1300 784 1300 776 1300 776 1301 784 1301 785 1301 776 1302 785 1302 774 1302 774 1303 785 1303 786 1303 774 1304 786 1304 703 1304 729 1305 773 1305 730 1305 730 1306 773 1306 772 1306 730 1307 772 1307 731 1307 731 1308 772 1308 771 1308 731 1309 771 1309 708 1309 708 1310 771 1310 770 1310 708 1311 770 1311 709 1311 709 1312 770 1312 769 1312 709 1313 769 1313 710 1313 710 1314 769 1314 768 1314 710 1315 768 1315 711 1315 711 1316 768 1316 767 1316 787 1317 788 1317 789 1317 789 1318 788 1318 728 1318 789 1319 728 1319 790 1319 790 1320 728 1320 266 1320 791 1321 787 1321 792 1321 792 1322 787 1322 789 1322 792 1323 789 1323 793 1323 793 1324 789 1324 790 1324 793 1325 790 1325 794 1325 794 1326 790 1326 266 1326 794 1327 266 1327 268 1327 273 1328 727 1328 274 1328 274 1329 727 1329 781 1329 274 1330 781 1330 268 1330 268 1331 781 1331 779 1331 268 1332 779 1332 794 1332 794 1333 779 1333 777 1333 794 1334 777 1334 793 1334 793 1335 777 1335 775 1335 793 1336 775 1336 792 1336 792 1337 775 1337 705 1337 792 1338 705 1338 791 1338 791 1339 705 1339 704 1339 791 1340 704 1340 795 1340 262 1341 725 1341 726 1341 726 1342 725 1342 766 1342 726 1343 766 1343 782 1343 782 1344 766 1344 765 1344 782 1345 765 1345 783 1345 783 1346 765 1346 764 1346 783 1347 764 1347 784 1347 784 1348 764 1348 763 1348 784 1349 763 1349 785 1349 785 1350 763 1350 762 1350 785 1351 762 1351 786 1351 786 1352 762 1352 773 1352 786 1353 773 1353 703 1353 703 1354 773 1354 729 1354 703 1355 729 1355 704 1355 704 1356 729 1356 706 1356 704 1357 706 1357 795 1357 795 1358 706 1358 612 1358 795 1359 612 1359 791 1359 791 1360 612 1360 696 1360 791 1361 696 1361 787 1361 787 1362 696 1362 695 1362 787 1363 695 1363 788 1363 788 1364 695 1364 684 1364 788 1365 684 1365 728 1365 728 1366 684 1366 683 1366 728 1367 683 1367 265 1367 265 1368 683 1368 616 1368 265 1369 616 1369 236 1369 434 1370 433 1370 796 1370 426 1371 140 1371 443 1371 591 1372 592 1372 797 1372 798 1373 799 1373 800 1373 590 1374 591 1374 801 1374 801 1375 591 1375 797 1375 801 1376 797 1376 802 1376 802 1377 797 1377 798 1377 802 1378 798 1378 803 1378 803 1379 798 1379 800 1379 804 1380 429 1380 428 1380 428 1381 427 1381 805 1381 805 1382 427 1382 426 1382 428 1383 805 1383 804 1383 804 1384 805 1384 806 1384 804 1385 806 1385 807 1385 807 1386 806 1386 808 1386 807 1387 808 1387 809 1387 592 1388 425 1388 797 1388 797 1389 425 1389 430 1389 797 1390 430 1390 798 1390 798 1391 430 1391 431 1391 798 1392 431 1392 799 1392 434 1393 796 1393 435 1393 443 1394 438 1394 810 1394 810 1395 438 1395 436 1395 810 1396 436 1396 811 1396 811 1397 436 1397 435 1397 426 1398 443 1398 805 1398 805 1399 443 1399 810 1399 805 1400 810 1400 806 1400 806 1401 810 1401 811 1401 806 1402 811 1402 808 1402 435 1403 796 1403 811 1403 811 1404 796 1404 812 1404 811 1405 812 1405 808 1405 808 1406 812 1406 813 1406 808 1407 813 1407 809 1407 809 1408 813 1408 800 1408 809 1409 800 1409 807 1409 807 1410 800 1410 799 1410 807 1411 799 1411 804 1411 804 1412 799 1412 431 1412 804 1413 431 1413 429 1413 444 1414 445 1414 814 1414 446 1415 455 1415 815 1415 815 1416 455 1416 457 1416 454 1417 447 1417 816 1417 816 1418 447 1418 446 1418 817 1419 453 1419 454 1419 445 1420 141 1420 818 1420 819 1421 441 1421 442 1421 432 1422 437 1422 820 1422 820 1423 437 1423 439 1423 821 1424 433 1424 432 1424 454 1425 816 1425 817 1425 817 1426 816 1426 822 1426 817 1427 822 1427 823 1427 823 1428 822 1428 824 1428 823 1429 824 1429 825 1429 825 1430 824 1430 826 1430 825 1431 826 1431 827 1431 827 1432 826 1432 828 1432 827 1433 828 1433 829 1433 829 1434 828 1434 830 1434 829 1435 830 1435 831 1435 831 1436 830 1436 819 1436 831 1437 819 1437 814 1437 814 1438 819 1438 442 1438 814 1439 442 1439 444 1439 446 1440 815 1440 816 1440 816 1441 815 1441 832 1441 816 1442 832 1442 822 1442 822 1443 832 1443 833 1443 822 1444 833 1444 824 1444 824 1445 833 1445 834 1445 824 1446 834 1446 826 1446 826 1447 834 1447 835 1447 826 1448 835 1448 828 1448 828 1449 835 1449 836 1449 828 1450 836 1450 830 1450 830 1451 836 1451 820 1451 830 1452 820 1452 819 1452 819 1453 820 1453 439 1453 819 1454 439 1454 441 1454 432 1455 820 1455 821 1455 821 1456 820 1456 836 1456 821 1457 836 1457 837 1457 837 1458 836 1458 835 1458 837 1459 835 1459 838 1459 838 1460 835 1460 834 1460 838 1461 834 1461 839 1461 839 1462 834 1462 833 1462 839 1463 833 1463 840 1463 840 1464 833 1464 832 1464 840 1465 832 1465 841 1465 841 1466 832 1466 815 1466 841 1467 815 1467 842 1467 842 1468 815 1468 457 1468 842 1469 457 1469 459 1469 843 1470 450 1470 449 1470 445 1471 818 1471 814 1471 814 1472 818 1472 844 1472 814 1473 844 1473 831 1473 831 1474 844 1474 845 1474 831 1475 845 1475 829 1475 829 1476 845 1476 846 1476 829 1477 846 1477 827 1477 827 1478 846 1478 847 1478 827 1479 847 1479 825 1479 825 1480 847 1480 848 1480 825 1481 848 1481 823 1481 823 1482 848 1482 843 1482 823 1483 843 1483 817 1483 817 1484 843 1484 449 1484 817 1485 449 1485 453 1485 459 1486 458 1486 849 1486 849 1487 458 1487 850 1487 849 1488 850 1488 851 1488 852 1489 853 1489 850 1489 850 1490 853 1490 854 1490 850 1491 854 1491 851 1491 461 1492 460 1492 852 1492 852 1493 460 1493 855 1493 855 1494 856 1494 852 1494 852 1495 856 1495 857 1495 852 1496 857 1496 853 1496 858 1497 859 1497 860 1497 861 1498 862 1498 863 1498 633 1499 864 1499 865 1499 633 1500 866 1500 867 1500 868 1501 866 1501 633 1501 860 1502 859 1502 633 1502 633 1503 869 1503 870 1503 871 1504 869 1504 633 1504 633 1505 872 1505 873 1505 874 1506 872 1506 633 1506 870 1507 874 1507 633 1507 863 1508 862 1508 633 1508 875 1509 876 1509 877 1509 877 1510 876 1510 878 1510 879 1511 880 1511 881 1511 881 1512 880 1512 882 1512 464 1513 883 1513 462 1513 600 1514 599 1514 884 1514 884 1515 599 1515 629 1515 884 1516 629 1516 885 1516 885 1517 629 1517 631 1517 885 1518 631 1518 633 1518 886 1519 468 1519 887 1519 887 1520 468 1520 256 1520 887 1521 256 1521 625 1521 623 1522 622 1522 888 1522 889 1523 472 1523 886 1523 886 1524 472 1524 470 1524 886 1525 470 1525 468 1525 890 1526 883 1526 891 1526 891 1527 883 1527 464 1527 891 1528 464 1528 889 1528 889 1529 464 1529 466 1529 889 1530 466 1530 472 1530 892 1531 893 1531 894 1531 895 1532 896 1532 897 1532 892 1533 898 1533 893 1533 893 1534 898 1534 895 1534 893 1535 895 1535 899 1535 899 1536 895 1536 897 1536 899 1537 897 1537 900 1537 900 1538 897 1538 901 1538 902 1539 658 1539 903 1539 903 1540 658 1540 641 1540 903 1541 641 1541 904 1541 633 1542 638 1542 905 1542 905 1543 638 1543 637 1543 905 1544 637 1544 902 1544 902 1545 637 1545 659 1545 902 1546 659 1546 658 1546 622 1547 600 1547 888 1547 888 1548 600 1548 884 1548 888 1549 884 1549 861 1549 861 1550 884 1550 885 1550 861 1551 885 1551 862 1551 862 1552 885 1552 633 1552 906 1553 873 1553 907 1553 907 1554 873 1554 872 1554 907 1555 872 1555 908 1555 908 1556 872 1556 874 1556 908 1557 874 1557 909 1557 909 1558 874 1558 870 1558 909 1559 870 1559 910 1559 910 1560 870 1560 869 1560 910 1561 869 1561 911 1561 911 1562 869 1562 871 1562 911 1563 871 1563 912 1563 868 1564 913 1564 866 1564 866 1565 913 1565 914 1565 866 1566 914 1566 867 1566 867 1567 914 1567 915 1567 892 1568 916 1568 898 1568 898 1569 916 1569 865 1569 898 1570 865 1570 895 1570 895 1571 865 1571 864 1571 895 1572 864 1572 896 1572 916 1573 633 1573 865 1573 910 1574 917 1574 909 1574 909 1575 917 1575 918 1575 909 1576 918 1576 908 1576 908 1577 918 1577 919 1577 908 1578 919 1578 907 1578 907 1579 919 1579 920 1579 907 1580 920 1580 906 1580 906 1581 920 1581 921 1581 858 1582 912 1582 859 1582 859 1583 912 1583 871 1583 859 1584 871 1584 633 1584 641 1585 642 1585 904 1585 904 1586 642 1586 901 1586 904 1587 901 1587 903 1587 903 1588 901 1588 897 1588 903 1589 897 1589 902 1589 902 1590 897 1590 896 1590 902 1591 896 1591 905 1591 905 1592 896 1592 864 1592 905 1593 864 1593 633 1593 922 1594 915 1594 923 1594 923 1595 915 1595 914 1595 923 1596 914 1596 894 1596 894 1597 914 1597 913 1597 894 1598 913 1598 892 1598 892 1599 913 1599 868 1599 892 1600 868 1600 916 1600 916 1601 868 1601 633 1601 887 1602 921 1602 886 1602 886 1603 921 1603 920 1603 886 1604 920 1604 889 1604 889 1605 920 1605 919 1605 889 1606 919 1606 891 1606 891 1607 919 1607 918 1607 891 1608 918 1608 890 1608 890 1609 918 1609 917 1609 890 1610 917 1610 924 1610 625 1611 623 1611 887 1611 887 1612 623 1612 888 1612 887 1613 888 1613 921 1613 921 1614 888 1614 861 1614 921 1615 861 1615 906 1615 906 1616 861 1616 863 1616 906 1617 863 1617 873 1617 873 1618 863 1618 633 1618 460 1619 462 1619 882 1619 882 1620 462 1620 883 1620 882 1621 883 1621 881 1621 881 1622 883 1622 890 1622 881 1623 890 1623 879 1623 879 1624 890 1624 924 1624 879 1625 924 1625 878 1625 878 1626 924 1626 917 1626 878 1627 917 1627 877 1627 877 1628 917 1628 910 1628 877 1629 910 1629 875 1629 875 1630 910 1630 911 1630 875 1631 911 1631 925 1631 925 1632 911 1632 912 1632 925 1633 912 1633 922 1633 922 1634 912 1634 858 1634 922 1635 858 1635 915 1635 915 1636 858 1636 860 1636 915 1637 860 1637 867 1637 867 1638 860 1638 633 1638 712 1639 317 1639 514 1639 754 1640 734 1640 926 1640 926 1641 642 1641 754 1641 754 1642 642 1642 640 1642 754 1643 640 1643 767 1643 767 1644 640 1644 643 1644 767 1645 643 1645 711 1645 682 1646 681 1646 643 1646 643 1647 681 1647 604 1647 643 1648 604 1648 711 1648 734 1649 712 1649 926 1649 926 1650 712 1650 514 1650 926 1651 514 1651 927 1651 927 1652 514 1652 482 1652 927 1653 482 1653 928 1653 482 1654 481 1654 928 1654 928 1655 481 1655 589 1655 928 1656 589 1656 929 1656 929 1657 589 1657 479 1657 929 1658 479 1658 930 1658 930 1659 479 1659 478 1659 930 1660 478 1660 931 1660 931 1661 478 1661 484 1661 931 1662 484 1662 932 1662 207 1663 590 1663 485 1663 485 1664 590 1664 933 1664 485 1665 933 1665 475 1665 475 1666 933 1666 932 1666 475 1667 932 1667 476 1667 476 1668 932 1668 484 1668 930 1669 931 1669 934 1669 935 1670 936 1670 875 1670 875 1671 936 1671 876 1671 876 1672 936 1672 937 1672 876 1673 937 1673 878 1673 878 1674 937 1674 938 1674 878 1675 938 1675 879 1675 879 1676 938 1676 939 1676 879 1677 939 1677 880 1677 939 1678 940 1678 880 1678 880 1679 940 1679 941 1679 880 1680 941 1680 882 1680 882 1681 941 1681 855 1681 882 1682 855 1682 460 1682 942 1683 842 1683 849 1683 849 1684 842 1684 459 1684 942 1685 943 1685 842 1685 842 1686 943 1686 944 1686 842 1687 944 1687 841 1687 841 1688 944 1688 945 1688 841 1689 945 1689 840 1689 840 1690 945 1690 946 1690 840 1691 946 1691 839 1691 839 1692 946 1692 947 1692 839 1693 947 1693 838 1693 838 1694 947 1694 948 1694 838 1695 948 1695 837 1695 837 1696 948 1696 949 1696 837 1697 949 1697 821 1697 950 1698 433 1698 951 1698 951 1699 433 1699 821 1699 951 1700 821 1700 952 1700 952 1701 821 1701 949 1701 813 1702 812 1702 950 1702 950 1703 812 1703 796 1703 950 1704 796 1704 433 1704 950 1705 953 1705 813 1705 813 1706 953 1706 954 1706 813 1707 954 1707 800 1707 800 1708 954 1708 803 1708 954 1709 955 1709 803 1709 803 1710 955 1710 956 1710 803 1711 956 1711 802 1711 933 1712 590 1712 956 1712 956 1713 590 1713 801 1713 956 1714 801 1714 802 1714 901 1715 642 1715 926 1715 926 1716 957 1716 901 1716 901 1717 957 1717 958 1717 901 1718 958 1718 900 1718 875 1719 925 1719 935 1719 935 1720 925 1720 922 1720 935 1721 922 1721 959 1721 959 1722 922 1722 923 1722 959 1723 923 1723 960 1723 960 1724 923 1724 894 1724 960 1725 894 1725 961 1725 961 1726 894 1726 893 1726 961 1727 893 1727 962 1727 962 1728 893 1728 899 1728 962 1729 899 1729 963 1729 963 1730 899 1730 900 1730 963 1731 900 1731 964 1731 964 1732 900 1732 958 1732 853 1733 857 1733 965 1733 965 1734 857 1734 966 1734 965 1735 966 1735 967 1735 967 1736 966 1736 968 1736 967 1737 968 1737 969 1737 969 1738 968 1738 970 1738 969 1739 970 1739 971 1739 971 1740 970 1740 972 1740 971 1741 972 1741 973 1741 973 1742 972 1742 974 1742 973 1743 974 1743 975 1743 975 1744 974 1744 976 1744 975 1745 976 1745 977 1745 977 1746 976 1746 978 1746 977 1747 978 1747 979 1747 979 1748 978 1748 980 1748 979 1749 980 1749 981 1749 981 1750 980 1750 982 1750 981 1751 982 1751 983 1751 983 1752 982 1752 984 1752 983 1753 984 1753 985 1753 985 1754 984 1754 986 1754 985 1755 986 1755 987 1755 987 1756 986 1756 988 1756 987 1757 988 1757 989 1757 989 1758 988 1758 990 1758 989 1759 990 1759 991 1759 991 1760 990 1760 992 1760 991 1761 992 1761 993 1761 993 1762 992 1762 994 1762 993 1763 994 1763 929 1763 929 1764 994 1764 928 1764 857 1765 856 1765 966 1765 966 1766 856 1766 995 1766 966 1767 995 1767 968 1767 968 1768 995 1768 996 1768 968 1769 996 1769 970 1769 970 1770 996 1770 997 1770 970 1771 997 1771 972 1771 972 1772 997 1772 998 1772 972 1773 998 1773 974 1773 974 1774 998 1774 999 1774 974 1775 999 1775 976 1775 976 1776 999 1776 1000 1776 976 1777 1000 1777 978 1777 978 1778 1000 1778 1001 1778 978 1779 1001 1779 980 1779 980 1780 1001 1780 1002 1780 980 1781 1002 1781 982 1781 982 1782 1002 1782 1003 1782 982 1783 1003 1783 984 1783 984 1784 1003 1784 1004 1784 984 1785 1004 1785 986 1785 986 1786 1004 1786 1005 1786 986 1787 1005 1787 988 1787 988 1788 1005 1788 1006 1788 988 1789 1006 1789 990 1789 990 1790 1006 1790 1007 1790 990 1791 1007 1791 992 1791 992 1792 1007 1792 1008 1792 992 1793 1008 1793 994 1793 994 1794 1008 1794 1009 1794 994 1795 1009 1795 928 1795 928 1796 1009 1796 927 1796 856 1797 855 1797 995 1797 995 1798 855 1798 941 1798 995 1799 941 1799 996 1799 996 1800 941 1800 940 1800 996 1801 940 1801 997 1801 997 1802 940 1802 939 1802 997 1803 939 1803 998 1803 998 1804 939 1804 938 1804 998 1805 938 1805 999 1805 999 1806 938 1806 937 1806 999 1807 937 1807 1000 1807 1000 1808 937 1808 936 1808 1000 1809 936 1809 1001 1809 1001 1810 936 1810 935 1810 1001 1811 935 1811 1002 1811 1002 1812 935 1812 959 1812 1002 1813 959 1813 1003 1813 1003 1814 959 1814 960 1814 1003 1815 960 1815 1004 1815 1004 1816 960 1816 961 1816 1004 1817 961 1817 1005 1817 1005 1818 961 1818 962 1818 1005 1819 962 1819 1006 1819 1006 1820 962 1820 963 1820 1006 1821 963 1821 1007 1821 1007 1822 963 1822 964 1822 1007 1823 964 1823 1008 1823 1008 1824 964 1824 958 1824 1008 1825 958 1825 1009 1825 1009 1826 958 1826 957 1826 1009 1827 957 1827 927 1827 927 1828 957 1828 926 1828 851 1829 854 1829 1010 1829 1010 1830 854 1830 1011 1830 1010 1831 1011 1831 1012 1831 1012 1832 1011 1832 1013 1832 1012 1833 1013 1833 1014 1833 1014 1834 1013 1834 1015 1834 1014 1835 1015 1835 1016 1835 1016 1836 1015 1836 1017 1836 1016 1837 1017 1837 1018 1837 1018 1838 1017 1838 1019 1838 1018 1839 1019 1839 1020 1839 1020 1840 1019 1840 1021 1840 1020 1841 1021 1841 1022 1841 1022 1842 1021 1842 1023 1842 1022 1843 1023 1843 1024 1843 1024 1844 1023 1844 1025 1844 1024 1845 1025 1845 1026 1845 1026 1846 1025 1846 1027 1846 1026 1847 1027 1847 1028 1847 1028 1848 1027 1848 1029 1848 1028 1849 1029 1849 1030 1849 1030 1850 1029 1850 1031 1850 1030 1851 1031 1851 1032 1851 1032 1852 1031 1852 1033 1852 1032 1853 1033 1853 1034 1853 1034 1854 1033 1854 1035 1854 1034 1855 1035 1855 1036 1855 1036 1856 1035 1856 1037 1856 1036 1857 1037 1857 1038 1857 1038 1858 1037 1858 934 1858 1038 1859 934 1859 932 1859 932 1860 934 1860 931 1860 849 1861 851 1861 942 1861 942 1862 851 1862 1010 1862 942 1863 1010 1863 943 1863 943 1864 1010 1864 1012 1864 943 1865 1012 1865 944 1865 944 1866 1012 1866 1014 1866 944 1867 1014 1867 945 1867 945 1868 1014 1868 1016 1868 945 1869 1016 1869 946 1869 946 1870 1016 1870 1018 1870 946 1871 1018 1871 947 1871 947 1872 1018 1872 1020 1872 947 1873 1020 1873 948 1873 948 1874 1020 1874 1022 1874 948 1875 1022 1875 949 1875 949 1876 1022 1876 1024 1876 949 1877 1024 1877 952 1877 952 1878 1024 1878 1026 1878 952 1879 1026 1879 951 1879 951 1880 1026 1880 1028 1880 951 1881 1028 1881 950 1881 950 1882 1028 1882 1030 1882 950 1883 1030 1883 953 1883 953 1884 1030 1884 1032 1884 953 1885 1032 1885 954 1885 954 1886 1032 1886 1034 1886 954 1887 1034 1887 955 1887 955 1888 1034 1888 1036 1888 955 1889 1036 1889 956 1889 956 1890 1036 1890 1038 1890 956 1891 1038 1891 933 1891 933 1892 1038 1892 932 1892 854 1893 853 1893 1011 1893 1011 1894 853 1894 965 1894 1011 1895 965 1895 1013 1895 1013 1896 965 1896 967 1896 1013 1897 967 1897 1015 1897 1015 1898 967 1898 969 1898 1015 1899 969 1899 1017 1899 1017 1900 969 1900 971 1900 1017 1901 971 1901 1019 1901 1019 1902 971 1902 973 1902 1019 1903 973 1903 1021 1903 1021 1904 973 1904 975 1904 1021 1905 975 1905 1023 1905 1023 1906 975 1906 977 1906 1023 1907 977 1907 1025 1907 1025 1908 977 1908 979 1908 1025 1909 979 1909 1027 1909 1027 1910 979 1910 981 1910 1027 1911 981 1911 1029 1911 1029 1912 981 1912 983 1912 1029 1913 983 1913 1031 1913 1031 1914 983 1914 985 1914 1031 1915 985 1915 1033 1915 1033 1916 985 1916 987 1916 1033 1917 987 1917 1035 1917 1035 1918 987 1918 989 1918 1035 1919 989 1919 1037 1919 1037 1920 989 1920 991 1920 1037 1921 991 1921 934 1921 934 1922 991 1922 993 1922 934 1923 993 1923 930 1923 930 1924 993 1924 929 1924 1039 1925 1040 1925 1041 1925 1041 1926 1040 1926 1042 1926 1043 1926 1044 1926 1045 1926 1045 1925 1044 1925 1046 1925 1039 1927 1041 1927 1047 1927 1047 1928 1041 1928 1048 1928 1047 1929 1048 1929 1049 1929 1047 0 1049 0 1039 0 1039 0 1049 0 1050 0 1039 0 1050 0 1040 0 1043 0 1051 0 1044 0 1044 0 1051 0 1052 0 1044 1930 1052 1930 1053 1930 1046 1931 1044 1931 1054 1931 1054 1932 1044 1932 1053 1932 1054 1933 1053 1933 1052 1933 1055 0 1056 0 1057 0 1058 0 1059 0 1060 0 1061 0 1062 0 1063 0 1060 0 1059 0 1064 0 1063 0 1062 0 1065 0 1057 1934 1056 1934 1066 1934 1067 1935 1068 1935 1069 1935 1062 0 1070 0 1065 0 1065 0 1070 0 1071 0 1065 0 1071 0 1072 0 1072 0 1071 0 1073 0 1072 0 1073 0 1057 0 1057 0 1073 0 1074 0 1057 0 1074 0 1055 0 1075 0 1076 0 1077 0 1078 0 1079 0 1080 0 1080 1936 1081 1936 1078 1936 1078 0 1081 0 1082 0 1078 0 1082 0 1076 0 1076 1937 1082 1937 1083 1937 1076 0 1083 0 1077 0 1084 0 1085 0 1086 0 1087 0 1088 0 1089 0 1089 0 1088 0 1090 0 1089 0 1090 0 1091 0 1056 1938 1092 1938 1066 1938 1066 1939 1092 1939 1093 1939 1066 1940 1093 1940 1094 1940 1086 0 1085 0 1068 0 1068 0 1085 0 1095 0 1068 0 1095 0 1069 0 1063 0 1096 0 1061 0 1061 0 1096 0 1097 0 1061 0 1097 0 1098 0 1098 0 1097 0 1099 0 1098 0 1099 0 1089 0 1089 1941 1099 1941 1100 1941 1089 1942 1100 1942 1087 1942 1077 0 1101 0 1075 0 1075 0 1101 0 1102 0 1075 0 1102 0 1103 0 1103 1943 1102 1943 1066 1943 1103 1944 1066 1944 1104 1944 1104 1945 1066 1945 1094 1945 1069 0 1105 0 1067 0 1067 0 1105 0 1106 0 1067 1946 1106 1946 1107 1946 1107 0 1106 0 1108 0 1107 0 1108 0 1079 0 1079 0 1108 0 1109 0 1079 1947 1109 1947 1080 1947 1059 0 1110 0 1064 0 1064 0 1110 0 1111 0 1064 0 1111 0 1112 0 1112 0 1111 0 1113 0 1112 0 1113 0 1114 0 1114 0 1113 0 1115 0 1114 0 1115 0 1116 0 1116 0 1115 0 1117 0 1116 0 1117 0 1118 0 1119 0 1120 0 1121 0 1084 0 1086 0 1122 0 1122 0 1086 0 1123 0 1122 0 1123 0 1060 0 1060 0 1123 0 1124 0 1060 0 1124 0 1058 0 1120 1948 1125 1948 1121 1948 1121 1949 1125 1949 1126 1949 1121 0 1126 0 1127 0 1127 0 1126 0 1128 0 1127 0 1128 0 1129 0 1129 0 1128 0 1130 0 1129 0 1130 0 1131 0 1131 0 1130 0 1132 0 1131 0 1132 0 1133 0 1133 0 1132 0 1118 0 1133 0 1118 0 1134 0 1134 0 1118 0 1117 0 1135 0 1136 0 1121 0 1121 0 1136 0 1137 0 1121 0 1137 0 1119 0 1138 1950 1139 1950 1066 1950 1140 1951 1141 1951 1139 1951 1142 1952 1143 1952 1141 1952 257 1953 1143 1953 259 1953 259 1954 1143 1954 1142 1954 259 1955 1142 1955 260 1955 260 1956 1142 1956 1144 1956 260 1957 1144 1957 254 1957 254 1958 1144 1958 1145 1958 248 1959 250 1959 1145 1959 1145 1960 250 1960 252 1960 1145 1961 252 1961 254 1961 1145 1962 1146 1962 248 1962 248 1963 1146 1963 1147 1963 248 1964 1147 1964 245 1964 245 1965 1147 1965 1148 1965 1149 1966 236 1966 1150 1966 1150 1967 236 1967 238 1967 1150 1968 238 1968 1151 1968 1151 1969 238 1969 240 1969 1151 1970 240 1970 1148 1970 1148 1971 240 1971 243 1971 1148 1972 243 1972 245 1972 1066 1973 1102 1973 1138 1973 1138 1974 1102 1974 1101 1974 1138 1975 1101 1975 1152 1975 1152 1976 1101 1976 1077 1976 1152 1977 1077 1977 1153 1977 1153 1978 1077 1978 1083 1978 1153 1979 1083 1979 1154 1979 1154 1980 1083 1980 1082 1980 1154 1981 1082 1981 1155 1981 1155 1982 1082 1982 1081 1982 1155 1983 1081 1983 1156 1983 1156 1984 1081 1984 1080 1984 1156 1985 1080 1985 1157 1985 1157 1986 1080 1986 1109 1986 1157 1987 1109 1987 1158 1987 1158 1988 1109 1988 1108 1988 1158 1989 1108 1989 1159 1989 1159 1990 1108 1990 1106 1990 1159 1991 1106 1991 1160 1991 1160 1992 1106 1992 1105 1992 1160 1993 1105 1993 1161 1993 1161 1994 1105 1994 1069 1994 1161 1995 1069 1995 1162 1995 1162 1996 1069 1996 1095 1996 1162 1997 1095 1997 1163 1997 1163 1998 1095 1998 1085 1998 1163 1999 1085 1999 1164 1999 1139 2000 1138 2000 1140 2000 1140 2001 1138 2001 1152 2001 1140 2002 1152 2002 1165 2002 1165 2003 1152 2003 1153 2003 1165 2004 1153 2004 1166 2004 1166 2005 1153 2005 1154 2005 1166 2006 1154 2006 1167 2006 1167 2007 1154 2007 1155 2007 1167 2008 1155 2008 1168 2008 1168 2009 1155 2009 1156 2009 1168 2010 1156 2010 1169 2010 1169 2011 1156 2011 1157 2011 1169 2012 1157 2012 1170 2012 1170 2013 1157 2013 1158 2013 1170 2014 1158 2014 1171 2014 1171 2015 1158 2015 1159 2015 1171 2016 1159 2016 1172 2016 1172 2017 1159 2017 1160 2017 1172 2018 1160 2018 1173 2018 1173 2019 1160 2019 1161 2019 1173 2020 1161 2020 1174 2020 1174 2021 1161 2021 1162 2021 1174 2022 1162 2022 1175 2022 1175 2023 1162 2023 1163 2023 1175 2024 1163 2024 1176 2024 1176 2025 1163 2025 1164 2025 1176 2026 1164 2026 1177 2026 1141 2027 1140 2027 1142 2027 1142 2028 1140 2028 1165 2028 1142 2029 1165 2029 1144 2029 1144 2030 1165 2030 1166 2030 1144 2031 1166 2031 1145 2031 1145 2032 1166 2032 1167 2032 1145 2033 1167 2033 1146 2033 1146 2034 1167 2034 1168 2034 1146 2035 1168 2035 1147 2035 1147 2036 1168 2036 1169 2036 1147 2037 1169 2037 1148 2037 1148 2038 1169 2038 1170 2038 1148 2039 1170 2039 1151 2039 1151 2040 1170 2040 1171 2040 1151 2041 1171 2041 1150 2041 1150 2042 1171 2042 1172 2042 1150 2043 1172 2043 1149 2043 1149 2044 1172 2044 1173 2044 1149 2045 1173 2045 1178 2045 1178 2046 1173 2046 1174 2046 1178 2047 1174 2047 1179 2047 1179 2048 1174 2048 1175 2048 1179 2049 1175 2049 1180 2049 1180 2050 1175 2050 1176 2050 1180 2051 1176 2051 1181 2051 1181 2052 1176 2052 1177 2052 1181 2053 1177 2053 1182 2053 278 2054 276 2054 1182 2054 1182 2055 276 2055 263 2055 1182 2056 263 2056 1181 2056 1181 2057 263 2057 271 2057 1181 2058 271 2058 1180 2058 1180 2059 271 2059 267 2059 1180 2060 267 2060 1179 2060 1179 2061 267 2061 269 2061 1179 2062 269 2062 1178 2062 1178 2063 269 2063 270 2063 1178 2064 270 2064 1149 2064 1149 2065 270 2065 264 2065 1149 2066 264 2066 236 2066 280 2067 278 2067 1183 2067 1183 2068 278 2068 1182 2068 1183 2069 1182 2069 1184 2069 1184 2070 1182 2070 1177 2070 1184 2071 1177 2071 1185 2071 1185 2072 1177 2072 1164 2072 1185 2073 1164 2073 1084 2073 1084 2074 1164 2074 1085 2074 156 2075 280 2075 1186 2075 1186 2076 280 2076 1183 2076 1186 2077 1183 2077 1187 2077 1187 2078 1183 2078 1184 2078 1187 2079 1184 2079 1188 2079 1188 2080 1184 2080 1185 2080 1188 2081 1185 2081 1122 2081 1122 2082 1185 2082 1084 2082 1130 2083 1189 2083 1132 2083 1132 2084 1189 2084 1190 2084 1132 2085 1190 2085 1118 2085 1118 2086 1190 2086 1116 2086 1116 2087 1190 2087 1191 2087 1116 2088 1191 2088 1114 2088 1114 2089 1191 2089 1192 2089 1114 2090 1192 2090 1112 2090 1112 2091 1192 2091 1193 2091 1112 2092 1193 2092 1064 2092 1064 2093 1193 2093 1194 2093 1064 2094 1194 2094 1060 2094 1060 2095 1194 2095 1188 2095 1060 2096 1188 2096 1122 2096 154 2097 156 2097 1186 2097 1195 2098 1196 2098 1197 2098 1197 2099 1196 2099 1198 2099 1197 2100 1198 2100 1199 2100 154 2101 1200 2101 152 2101 152 2102 1200 2102 1201 2102 152 2103 1201 2103 144 2103 144 2104 1201 2104 1199 2104 144 2105 1199 2105 145 2105 145 2106 1199 2106 1198 2106 145 2107 1198 2107 148 2107 1130 2108 1195 2108 1189 2108 1189 2109 1195 2109 1202 2109 1189 2110 1202 2110 1190 2110 1190 2111 1202 2111 1203 2111 1190 2112 1203 2112 1191 2112 1191 2113 1203 2113 1204 2113 1191 2114 1204 2114 1192 2114 1192 2115 1204 2115 1205 2115 1192 2116 1205 2116 1193 2116 1193 2117 1205 2117 1206 2117 1193 2118 1206 2118 1194 2118 1194 2119 1206 2119 1187 2119 1194 2120 1187 2120 1188 2120 1195 2121 1197 2121 1202 2121 1202 2122 1197 2122 1199 2122 1202 2123 1199 2123 1203 2123 1203 2124 1199 2124 1201 2124 1203 2125 1201 2125 1204 2125 1204 2126 1201 2126 1200 2126 1204 2127 1200 2127 1205 2127 1205 2128 1200 2128 154 2128 1205 2129 154 2129 1206 2129 1206 2130 154 2130 1186 2130 1206 2131 1186 2131 1187 2131 1207 2132 1208 2132 1209 2132 1209 2133 1208 2133 1210 2133 1126 2134 1125 2134 1207 2134 1207 2135 1209 2135 1126 2135 1126 2136 1209 2136 1211 2136 1126 2137 1211 2137 1128 2137 1212 2138 1196 2138 1195 2138 162 2139 148 2139 1198 2139 125 2140 159 2140 1213 2140 1213 2141 159 2141 162 2141 1213 2142 162 2142 1212 2142 1212 2143 162 2143 1198 2143 1212 2144 1198 2144 1196 2144 1130 2145 1128 2145 1195 2145 1195 2146 1128 2146 1211 2146 1195 2147 1211 2147 1212 2147 1212 2148 1211 2148 1209 2148 1212 2149 1209 2149 1213 2149 1213 2150 1209 2150 1210 2150 1213 2151 1210 2151 125 2151 1214 2152 1215 2152 76 2152 1049 2152 1216 2152 1217 2152 450 2153 843 2153 1049 2153 1049 2154 843 2154 848 2154 1049 2155 848 2155 847 2155 1217 2152 1218 2152 1049 2152 1049 2156 1218 2156 451 2156 1049 2157 451 2157 450 2157 847 2158 846 2158 1049 2158 1049 2159 846 2159 845 2159 1049 2160 845 2160 844 2160 107 2161 1050 2161 141 2161 141 2162 1050 2162 1049 2162 141 2163 1049 2163 818 2163 818 2164 1049 2164 844 2164 23 2165 24 2165 1049 2165 1049 2152 24 2152 1219 2152 1049 2152 1219 2152 1216 2152 139 2166 1220 2166 76 2166 76 2152 1220 2152 1221 2152 76 2152 1221 2152 1214 2152 1045 2152 12 2152 1051 2152 1051 2152 12 2152 13 2152 1051 2152 13 2152 1042 2152 1042 2167 13 2167 92 2167 1042 2152 92 2152 1041 2152 1041 2152 92 2152 48 2152 1041 2168 48 2168 1048 2168 1046 2152 77 2152 1045 2152 1045 2152 77 2152 93 2152 1045 2152 93 2152 12 2152 12 2169 93 2169 16 2169 12 2152 16 2152 17 2152 1046 2152 1054 2152 77 2152 77 2170 1054 2170 1052 2170 77 2152 1052 2152 74 2152 74 2152 1052 2152 75 2152 1048 2171 48 2171 1049 2171 1049 2172 48 2172 21 2172 1049 2152 21 2152 23 2152 1042 2152 1050 2152 1051 2152 1051 2161 1050 2161 107 2161 1051 2162 107 2162 1052 2162 1052 2173 107 2173 76 2173 1052 2152 76 2152 75 2152 107 2174 169 2174 76 2174 76 2175 169 2175 168 2175 76 2176 168 2176 174 2176 174 2177 176 2177 76 2177 76 2178 176 2178 178 2178 76 2179 178 2179 180 2179 180 2180 181 2180 76 2180 76 2181 181 2181 138 2181 76 2182 138 2182 139 2182 1100 2183 1222 2183 1087 2183 1087 2184 1222 2184 1223 2184 1087 2185 1223 2185 1088 2185 1088 2186 1223 2186 1090 2186 1090 2187 1223 2187 1224 2187 1090 2188 1224 2188 1091 2188 1225 2189 1226 2189 1227 2189 1227 2190 1226 2190 1228 2190 1227 2191 1228 2191 1224 2191 1224 2192 1228 2192 1229 2192 1224 2193 1229 2193 1091 2193 1219 2194 1230 2194 1216 2194 1216 2195 1230 2195 1225 2195 1222 2196 1231 2196 1223 2196 1223 2197 1231 2197 1232 2197 1223 2198 1232 2198 1224 2198 1224 2199 1232 2199 1233 2199 1224 2200 1233 2200 1227 2200 1227 2201 1233 2201 1234 2201 1231 2202 1235 2202 1232 2202 1232 2203 1235 2203 1236 2203 1232 2204 1236 2204 1233 2204 1233 2205 1236 2205 1237 2205 1233 2206 1237 2206 1234 2206 1234 2207 1237 2207 1238 2207 1235 2208 458 2208 1236 2208 1236 2209 458 2209 456 2209 1236 2210 456 2210 1237 2210 1237 2211 456 2211 448 2211 1237 2212 448 2212 1238 2212 1238 2213 448 2213 452 2213 1238 2214 452 2214 451 2214 1225 2215 1227 2215 1216 2215 1216 2216 1227 2216 1234 2216 1216 2217 1234 2217 1217 2217 1217 2218 1234 2218 1238 2218 1217 2219 1238 2219 1218 2219 1218 2220 1238 2220 451 2220 1239 2221 1240 2221 1241 2221 1136 2222 1242 2222 1137 2222 1137 2223 1242 2223 1243 2223 1137 2224 1243 2224 1119 2224 1119 2225 1243 2225 1120 2225 1120 2226 1243 2226 1207 2226 1120 2227 1207 2227 1125 2227 125 2228 1210 2228 127 2228 127 2229 1210 2229 1244 2229 1241 2230 1240 2230 1214 2230 1214 2231 1240 2231 1245 2231 1214 2232 1245 2232 1215 2232 1136 2233 1135 2233 1242 2233 1242 2234 1135 2234 1246 2234 1242 2235 1246 2235 1241 2235 1241 2236 1246 2236 1247 2236 1241 2237 1247 2237 1239 2237 139 2238 137 2238 1220 2238 1220 2239 137 2239 136 2239 1220 2240 136 2240 1248 2240 1248 2241 136 2241 1249 2241 1248 2242 1249 2242 1250 2242 1250 2243 1249 2243 130 2243 1250 2244 130 2244 1244 2244 1244 2245 130 2245 1251 2245 1244 2246 1251 2246 127 2246 1210 2247 1208 2247 1244 2247 1244 2248 1208 2248 1252 2248 1244 2249 1252 2249 1250 2249 1250 2250 1252 2250 1253 2250 1250 2251 1253 2251 1248 2251 1248 2252 1253 2252 1254 2252 1248 2253 1254 2253 1220 2253 1220 2254 1254 2254 1221 2254 1208 2255 1207 2255 1252 2255 1252 2256 1207 2256 1243 2256 1252 2257 1243 2257 1253 2257 1253 2258 1243 2258 1242 2258 1253 2259 1242 2259 1254 2259 1254 2260 1242 2260 1241 2260 1254 2261 1241 2261 1221 2261 1221 2262 1241 2262 1214 2262 1100 2263 1099 2263 1255 2263 1100 2264 1255 2264 1222 2264 1222 2265 1255 2265 1256 2265 1222 2266 1256 2266 1231 2266 1231 2267 1256 2267 1257 2267 1231 2268 1257 2268 1235 2268 461 2269 852 2269 1257 2269 1257 2270 852 2270 850 2270 1257 2271 850 2271 1235 2271 1235 2272 850 2272 458 2272 461 2273 1257 2273 1258 2273 1258 2274 1257 2274 1256 2274 1258 2275 1256 2275 1259 2275 1259 2276 1256 2276 1255 2276 1259 2277 1255 2277 1260 2277 1260 2278 1255 2278 1099 2278 1260 2279 1099 2279 1097 2279 1143 2280 1261 2280 1141 2280 463 2281 1262 2281 1263 2281 1057 2282 1264 2282 1265 2282 1266 2283 1267 2283 1072 2283 1072 2284 1267 2284 1268 2284 1072 2285 1268 2285 1065 2285 1065 2286 1268 2286 1269 2286 1065 2287 1269 2287 1063 2287 1269 2288 1270 2288 1063 2288 1063 2289 1270 2289 1271 2289 1063 2290 1271 2290 1096 2290 1096 2291 1271 2291 1260 2291 1096 2292 1260 2292 1097 2292 1259 2293 1262 2293 1258 2293 1258 2294 1262 2294 463 2294 1258 2295 463 2295 461 2295 1272 2296 1273 2296 465 2296 465 2297 1273 2297 474 2297 474 2298 1273 2298 473 2298 473 2299 1273 2299 1274 2299 473 2300 1274 2300 471 2300 1261 2301 1143 2301 1275 2301 471 2302 1274 2302 469 2302 469 2303 1274 2303 1275 2303 469 2304 1275 2304 467 2304 467 2305 1275 2305 1143 2305 467 2306 1143 2306 257 2306 1057 2307 1066 2307 1264 2307 1264 2308 1066 2308 1139 2308 1264 2309 1139 2309 1265 2309 465 2310 463 2310 1272 2310 1272 2311 463 2311 1263 2311 1272 2312 1263 2312 1273 2312 1273 2313 1263 2313 1276 2313 1273 2314 1276 2314 1274 2314 1274 2315 1276 2315 1277 2315 1274 2316 1277 2316 1275 2316 1275 2317 1277 2317 1278 2317 1275 2318 1278 2318 1261 2318 1261 2319 1278 2319 1265 2319 1261 2320 1265 2320 1141 2320 1141 2321 1265 2321 1139 2321 1259 2322 1260 2322 1262 2322 1262 2323 1260 2323 1271 2323 1262 2324 1271 2324 1263 2324 1263 2325 1271 2325 1270 2325 1263 2326 1270 2326 1276 2326 1276 2327 1270 2327 1269 2327 1276 2328 1269 2328 1277 2328 1277 2329 1269 2329 1268 2329 1277 2330 1268 2330 1278 2330 1278 2331 1268 2331 1267 2331 1278 2332 1267 2332 1265 2332 1265 2333 1267 2333 1266 2333 1265 2334 1266 2334 1057 2334 1057 2335 1266 2335 1072 2335 1042 5 1040 5 1050 5 1043 4 1045 4 1051 4 1228 48 1279 48 1229 48 1229 48 1279 48 1091 48 24 48 30 48 1219 48 1219 2336 30 2336 29 2336 29 48 28 48 1219 48 1219 48 28 48 26 48 1219 48 26 48 1230 48 1228 48 1226 48 1279 48 1279 48 1226 48 1225 48 1279 48 1225 48 1280 48 1280 48 1225 48 1230 48 1280 48 1230 48 25 48 25 48 1230 48 26 48 1240 48 1239 48 1281 48 1240 48 1281 48 1245 48 1239 48 1247 48 1281 48 1281 48 1247 48 1246 48 1281 48 1246 48 1135 48 1281 48 1282 48 1245 48 1245 48 1282 48 58 48 1245 48 58 48 1215 48 1215 48 58 48 57 48 1215 48 57 48 55 48 55 48 54 48 1215 48 1215 2337 54 2337 72 2337 1215 48 72 48 76 48 1283 2338 1284 2338 1285 2338 1285 2339 1284 2339 1286 2339 1285 2340 1286 2340 1287 2340 1287 2341 1286 2341 1288 2341 1286 2342 1289 2342 1288 2342 1288 2343 1289 2343 1290 2343 1288 2344 1290 2344 1291 2344 1291 2345 1290 2345 1292 2345 1291 2346 1292 2346 1293 2346 1293 2347 1292 2347 1294 2347 1294 2348 1292 2348 1295 2348 1294 2349 1295 2349 1296 2349 1296 2350 1295 2350 1297 2350 1296 2351 1297 2351 1298 2351 1298 2352 1297 2352 1299 2352 1298 2353 1299 2353 1300 2353 1300 2354 1299 2354 1301 2354 1300 2355 1301 2355 1302 2355 1302 2356 1301 2356 1303 2356 1302 2357 1303 2357 1304 2357 1304 2358 1303 2358 1305 2358 1304 2359 1305 2359 1306 2359 1306 2360 1305 2360 1307 2360 1306 2361 1307 2361 1308 2361 1308 2362 1307 2362 1309 2362 1308 2363 1309 2363 1310 2363 1311 2364 1312 2364 1313 2364 1313 2365 1312 2365 1314 2365 1313 2366 1314 2366 1315 2366 1315 2367 1314 2367 1316 2367 1315 2368 1316 2368 1317 2368 1317 2369 1316 2369 1318 2369 1317 2370 1318 2370 1319 2370 1319 2371 1318 2371 1310 2371 1319 2372 1310 2372 1320 2372 1320 2373 1310 2373 1309 2373 1321 2374 1322 2374 1323 2374 1323 2375 1322 2375 1324 2375 1325 2376 1326 2376 1327 2376 1327 2377 1326 2377 1328 2377 1327 2378 1328 2378 1324 2378 1324 2379 1328 2379 1329 2379 1324 2380 1329 2380 1323 2380 1323 2381 1330 2381 1321 2381 1321 2382 1330 2382 1331 2382 1321 2383 1331 2383 1332 2383 1332 2384 1331 2384 1333 2384 1332 2385 1333 2385 1334 2385 1334 2386 1333 2386 1335 2386 1334 2387 1335 2387 1336 2387 1336 2388 1335 2388 1337 2388 1336 2389 1337 2389 1338 2389 1338 2390 1337 2390 1339 2390 1338 2391 1339 2391 1340 2391 1340 2392 1339 2392 1341 2392 1339 2393 1342 2393 1341 2393 1341 2394 1342 2394 1343 2394 1341 2395 1343 2395 1344 2395 1344 2396 1343 2396 1345 2396 1344 2397 1345 2397 1346 2397 1346 2398 1345 2398 1347 2398 1347 2399 1345 2399 1348 2399 1347 2400 1348 2400 1349 2400 1349 2401 1348 2401 1350 2401 1349 2402 1350 2402 1351 2402 1351 2403 1350 2403 1352 2403 1351 2404 1352 2404 1353 2404 1353 2405 1352 2405 1354 2405 1353 2406 1354 2406 1355 2406 1355 2407 1354 2407 1356 2407 1356 2408 1354 2408 1357 2408 1356 2409 1357 2409 1358 2409 1359 2410 1360 2410 1361 2410 1361 2411 1360 2411 1362 2411 1361 2412 1362 2412 1363 2412 1363 2413 1362 2413 1364 2413 1364 2414 1362 2414 1365 2414 1364 2415 1365 2415 1366 2415 1366 2416 1365 2416 1367 2416 1366 2417 1367 2417 1368 2417 1369 2418 1370 2418 1367 2418 1370 2419 1371 2419 1367 2419 1367 2420 1371 2420 1372 2420 1367 2421 1372 2421 1368 2421 1373 2422 1374 2422 1375 2422 1375 2423 1374 2423 1376 2423 1375 2424 1376 2424 1377 2424 1373 2425 1375 2425 1378 2425 1378 2426 1375 2426 1379 2426 1378 2427 1379 2427 1380 2427 1380 2428 1381 2428 1378 2428 1378 2429 1381 2429 1382 2429 1378 2430 1382 2430 1383 2430 1383 2431 1384 2431 1378 2431 1378 2432 1384 2432 1385 2432 1378 2433 1385 2433 1386 2433 1367 2434 1387 2434 1369 2434 1369 2435 1387 2435 1388 2435 1369 2436 1388 2436 1389 2436 1389 2437 1388 2437 1378 2437 1389 2438 1378 2438 1390 2438 1390 2439 1378 2439 1386 2439 1359 2440 1361 2440 1391 2440 1391 2441 1361 2441 1392 2441 1391 2442 1392 2442 1393 2442 1393 2443 1392 2443 1394 2443 1393 2444 1394 2444 1395 2444 1395 2445 1394 2445 1396 2445 1395 2446 1396 2446 1397 2446 1396 2447 1398 2447 1397 2447 1397 2448 1398 2448 1399 2448 1397 2449 1399 2449 1400 2449 1400 2450 1399 2450 1401 2450 1400 2451 1401 2451 1402 2451 1402 2452 1401 2452 1403 2452 1403 2453 1404 2453 1402 2453 1402 2454 1404 2454 1405 2454 1402 2455 1405 2455 1406 2455 1406 2456 1405 2456 1407 2456 1405 2457 1408 2457 1407 2457 1407 2458 1408 2458 1409 2458 1407 2459 1409 2459 1410 2459 1411 2460 1412 2460 1410 2460 1411 2461 1410 2461 1413 2461 1409 2462 1414 2462 1410 2462 1410 2463 1414 2463 1415 2463 1410 2464 1415 2464 1416 2464 1416 2465 1417 2465 1410 2465 1410 2466 1417 2466 1418 2466 1410 2467 1418 2467 1413 2467 1419 2468 1420 2468 1421 2468 1421 2469 1420 2469 1422 2469 1422 2470 1423 2470 1421 2470 1421 2471 1423 2471 1424 2471 1421 2472 1424 2472 1425 2472 1412 2473 1426 2473 1410 2473 1410 2474 1426 2474 1421 2474 1410 2475 1421 2475 1427 2475 1427 2476 1421 2476 1425 2476 1073 2477 1428 2477 1074 2477 1429 2478 1430 2478 1431 2478 1431 2479 1432 2479 1433 2479 1433 2480 1432 2480 1434 2480 1435 2481 1436 2481 1437 2481 1070 2482 1062 2482 1438 2482 1438 2483 1062 2483 1061 2483 1438 2484 1061 2484 1439 2484 1439 2485 1061 2485 1440 2485 1439 2486 1440 2486 1441 2486 1442 2487 1443 2487 1071 2487 1444 2488 1445 2488 1428 2488 1445 2489 1446 2489 1428 2489 1428 2490 1446 2490 1447 2490 1428 2491 1447 2491 1074 2491 1073 2492 1071 2492 1428 2492 1428 2493 1071 2493 1443 2493 1428 2494 1443 2494 1444 2494 1444 2495 1443 2495 1442 2495 1444 2496 1442 2496 1448 2496 1448 2497 1442 2497 1433 2497 1448 2498 1433 2498 1436 2498 1436 2499 1433 2499 1434 2499 1436 2500 1434 2500 1437 2500 1440 2501 1429 2501 1441 2501 1441 2502 1429 2502 1431 2502 1441 2503 1431 2503 1439 2503 1439 2504 1431 2504 1433 2504 1439 2505 1433 2505 1438 2505 1438 2506 1433 2506 1442 2506 1438 2507 1442 2507 1070 2507 1070 2508 1442 2508 1071 2508 1312 2509 1311 2509 1449 2509 1449 2510 1311 2510 1450 2510 1279 2511 1280 2511 51 2511 1451 2512 1452 2512 51 2512 51 2513 1452 2513 1453 2513 51 2514 1453 2514 1279 2514 20 2515 1454 2515 51 2515 51 2516 1454 2516 1455 2516 51 2517 1455 2517 1451 2517 19 2518 1456 2518 20 2518 20 2519 1456 2519 1457 2519 20 2520 1457 2520 1454 2520 25 2521 53 2521 1280 2521 1280 2522 53 2522 52 2522 1280 2523 52 2523 51 2523 1356 2524 1358 2524 1458 2524 1356 2525 1458 2525 1283 2525 1283 2525 1458 2525 1459 2525 1283 2526 1459 2526 1284 2526 91 2527 102 2527 1460 2527 105 2528 8 2528 7 2528 1461 2529 1462 2529 1463 2529 1464 2530 1465 2530 1466 2530 1467 2531 1430 2531 1429 2531 1466 2532 1465 2532 1468 2532 1468 2533 1465 2533 1469 2533 1468 2534 1469 2534 1470 2534 1470 2535 1471 2535 1468 2535 1468 2536 1471 2536 1472 2536 1468 2537 1472 2537 1467 2537 1463 2538 1462 2538 1473 2538 1462 2539 1474 2539 1473 2539 1473 2540 1474 2540 1475 2540 1473 2541 1475 2541 1466 2541 1466 2542 1475 2542 1476 2542 1466 2543 1476 2543 1464 2543 1477 2544 1478 2544 1479 2544 1479 2545 1480 2545 1477 2545 1477 2546 1480 2546 1481 2546 1477 2547 1481 2547 1463 2547 1463 2548 1481 2548 1482 2548 1463 2549 1482 2549 1461 2549 1483 2550 7 2550 5 2550 1460 2551 102 2551 1483 2551 102 2552 101 2552 1483 2552 1483 2553 101 2553 100 2553 1483 2554 100 2554 7 2554 7 2555 100 2555 104 2555 7 2556 104 2556 105 2556 31 2557 36 2557 1484 2557 1484 2558 36 2558 35 2558 1484 2559 35 2559 1460 2559 1460 2560 35 2560 39 2560 1460 2561 39 2561 91 2561 31 2562 1484 2562 32 2562 32 2563 1484 2563 1485 2563 32 2564 1485 2564 34 2564 34 2565 1485 2565 1486 2565 34 2566 1486 2566 18 2566 1487 2567 1455 2567 1454 2567 1454 2568 1457 2568 1487 2568 1487 2569 1457 2569 1456 2569 1487 2570 1456 2570 1486 2570 1486 2571 1456 2571 19 2571 1486 2572 19 2572 18 2572 1455 2573 1487 2573 1451 2573 1451 2574 1487 2574 1488 2574 1451 2575 1488 2575 1452 2575 1091 2576 1279 2576 1488 2576 1488 2577 1279 2577 1453 2577 1488 2578 1453 2578 1452 2578 1440 2579 1061 2579 1098 2579 1467 2580 1429 2580 1468 2580 1468 2581 1429 2581 1440 2581 1468 2582 1440 2582 1489 2582 1489 2583 1440 2583 1098 2583 1489 2584 1098 2584 1089 2584 4 2585 1479 2585 5 2585 5 2586 1479 2586 1478 2586 5 2587 1478 2587 1483 2587 1483 2588 1478 2588 1477 2588 1483 2589 1477 2589 1460 2589 1460 2590 1477 2590 1463 2590 1460 2591 1463 2591 1484 2591 1484 2592 1463 2592 1473 2592 1484 2593 1473 2593 1485 2593 1485 2594 1473 2594 1466 2594 1485 2595 1466 2595 1486 2595 1486 2596 1466 2596 1468 2596 1486 2597 1468 2597 1487 2597 1487 2598 1468 2598 1489 2598 1487 2599 1489 2599 1488 2599 1488 2600 1489 2600 1089 2600 1488 2601 1089 2601 1091 2601 1490 2602 1326 2602 1491 2602 1491 2603 1326 2603 1325 2603 1492 2604 1493 2604 1494 2604 1495 2605 1496 2605 1497 2605 1498 2606 1499 2606 1500 2606 1501 2607 1502 2607 1503 2607 1503 2608 1502 2608 1498 2608 1503 2609 1498 2609 1504 2609 1504 2610 1498 2610 1500 2610 1504 2611 1500 2611 1505 2611 1506 2612 1507 2612 1501 2612 1501 2613 1507 2613 1508 2613 1501 2614 1508 2614 1502 2614 1509 2615 1510 2615 1496 2615 1496 2616 1510 2616 1506 2616 1496 2617 1506 2617 1497 2617 1497 2618 1506 2618 1501 2618 1495 2619 1511 2619 1512 2619 1512 2620 1511 2620 1513 2620 1512 2621 1513 2621 1514 2621 1495 2622 1512 2622 1496 2622 1496 2623 1512 2623 1515 2623 1496 2624 1515 2624 1509 2624 1111 2625 1492 2625 1113 2625 1113 2626 1492 2626 1494 2626 1113 2627 1494 2627 1115 2627 1115 2628 1494 2628 1516 2628 1115 2629 1516 2629 1117 2629 1117 2630 1516 2630 1134 2630 1493 2631 1495 2631 1494 2631 1494 2632 1495 2632 1497 2632 1494 2633 1497 2633 1516 2633 1516 2634 1497 2634 1501 2634 1516 2635 1501 2635 1134 2635 1134 2636 1501 2636 1503 2636 1134 2637 1503 2637 1133 2637 1133 2638 1503 2638 1504 2638 1133 2639 1504 2639 1131 2639 1131 2640 1504 2640 1505 2640 1131 2641 1505 2641 1129 2641 59 2642 58 2642 1282 2642 1282 2643 1281 2643 1517 2643 1518 2644 87 2644 88 2644 1518 2645 88 2645 1519 2645 1517 2646 1520 2646 89 2646 89 2647 1520 2647 1521 2647 89 2648 1521 2648 88 2648 88 2649 1521 2649 1522 2649 88 2650 1522 2650 1519 2650 1517 2651 89 2651 1282 2651 1282 2652 89 2652 90 2652 1282 2653 90 2653 59 2653 97 2654 95 2654 1523 2654 60 2655 87 2655 1524 2655 1500 2656 1499 2656 1525 2656 1525 2657 1526 2657 1527 2657 1527 2658 1526 2658 1528 2658 1528 2659 1529 2659 1527 2659 1527 2660 1529 2660 1530 2660 1527 2661 1530 2661 1531 2661 1525 2662 1527 2662 1500 2662 1500 2663 1527 2663 1532 2663 1500 2664 1532 2664 1505 2664 1533 2665 1121 2665 1127 2665 1121 2666 1533 2666 1135 2666 1135 2667 1533 2667 1517 2667 1135 2668 1517 2668 1281 2668 1519 2669 1522 2669 1534 2669 1534 2670 1522 2670 1521 2670 1534 2671 1521 2671 1533 2671 1533 2672 1521 2672 1520 2672 1533 2673 1520 2673 1517 2673 1524 2674 87 2674 1534 2674 1534 2675 87 2675 1518 2675 1534 2676 1518 2676 1519 2676 67 2677 68 2677 1535 2677 1535 2678 68 2678 70 2678 1535 2679 70 2679 1536 2679 1536 2680 70 2680 71 2680 1536 2681 71 2681 1524 2681 1524 2682 71 2682 61 2682 1524 2683 61 2683 60 2683 67 2684 1535 2684 65 2684 65 2685 1535 2685 1537 2685 65 2686 1537 2686 63 2686 95 2687 94 2687 1523 2687 1523 2688 94 2688 98 2688 1523 2689 98 2689 1537 2689 1537 2690 98 2690 99 2690 1537 2691 99 2691 63 2691 6 2692 9 2692 103 2692 1538 2693 0 2693 6 2693 1 2694 0 2694 1539 2694 1539 2695 0 2695 1538 2695 1539 2696 1538 2696 1540 2696 1540 2697 1538 2697 1541 2697 1541 2698 1538 2698 1542 2698 1541 2699 1542 2699 1543 2699 1543 2700 1542 2700 1544 2700 1544 2701 1542 2701 1545 2701 1544 2702 1545 2702 1546 2702 1546 2703 1545 2703 1547 2703 1547 2704 1545 2704 1548 2704 1547 2705 1548 2705 1549 2705 1530 2706 1550 2706 1531 2706 1531 2707 1550 2707 1551 2707 1531 2708 1551 2708 1548 2708 1548 2709 1551 2709 1552 2709 1548 2710 1552 2710 1549 2710 103 2711 97 2711 6 2711 6 2712 97 2712 1523 2712 6 2713 1523 2713 1538 2713 1538 2714 1523 2714 1537 2714 1538 2715 1537 2715 1542 2715 1542 2716 1537 2716 1535 2716 1542 2717 1535 2717 1545 2717 1545 2718 1535 2718 1536 2718 1545 2719 1536 2719 1548 2719 1548 2720 1536 2720 1524 2720 1548 2721 1524 2721 1531 2721 1531 2722 1524 2722 1534 2722 1531 2723 1534 2723 1527 2723 1527 2724 1534 2724 1533 2724 1527 2725 1533 2725 1532 2725 1532 2726 1533 2726 1127 2726 1532 2727 1127 2727 1505 2727 1505 2728 1127 2728 1129 2728 1553 2729 1554 2729 1555 2729 1555 2730 1554 2730 1377 2730 1555 2731 1377 2731 1556 2731 1557 2732 1558 2732 1559 2732 1559 2733 1558 2733 1560 2733 1561 2734 1562 2734 1559 2734 1559 2735 1562 2735 1563 2735 1559 2736 1563 2736 1557 2736 1564 2737 1565 2737 1561 2737 1561 2738 1565 2738 1566 2738 1561 2739 1566 2739 1562 2739 1567 2740 1568 2740 1569 2740 1567 2741 1569 2741 1570 2741 1570 2742 1569 2742 1571 2742 1570 2743 1571 2743 1564 2743 1564 2744 1571 2744 1572 2744 1564 2745 1572 2745 1565 2745 1568 2746 1567 2746 1573 2746 1573 2747 1567 2747 1574 2747 1573 2748 1574 2748 1575 2748 1575 2749 1574 2749 1576 2749 1575 2750 1576 2750 1577 2750 1377 2751 1376 2751 1556 2751 1556 2752 1376 2752 1374 2752 1556 2753 1374 2753 1578 2753 1578 2754 1374 2754 1373 2754 1578 2755 1373 2755 1579 2755 1579 2756 1373 2756 1378 2756 1579 2757 1378 2757 1580 2757 1580 2758 1378 2758 1388 2758 1580 2759 1388 2759 1581 2759 1581 2760 1388 2760 1387 2760 1581 2761 1387 2761 1582 2761 1387 2762 1367 2762 1582 2762 1582 2763 1367 2763 1583 2763 1582 2764 1583 2764 1584 2764 1553 2765 1555 2765 1585 2765 1585 2766 1555 2766 1556 2766 1585 2767 1556 2767 1586 2767 1586 2768 1556 2768 1578 2768 1586 2769 1578 2769 1587 2769 1587 2770 1578 2770 1579 2770 1587 2771 1579 2771 1588 2771 1588 2772 1579 2772 1580 2772 1588 2773 1580 2773 1589 2773 1589 2774 1580 2774 1581 2774 1589 2775 1581 2775 1590 2775 1590 2776 1581 2776 1582 2776 1590 2777 1582 2777 1591 2777 1591 2778 1582 2778 1584 2778 1591 2779 1584 2779 1592 2779 1593 2780 1577 2780 1592 2780 1592 2781 1577 2781 1576 2781 1592 2782 1576 2782 1591 2782 1591 2783 1576 2783 1574 2783 1591 2784 1574 2784 1590 2784 1590 2785 1574 2785 1567 2785 1590 2786 1567 2786 1589 2786 1589 2787 1567 2787 1570 2787 1589 2788 1570 2788 1588 2788 1588 2789 1570 2789 1564 2789 1588 2790 1564 2790 1587 2790 1587 2791 1564 2791 1561 2791 1587 2792 1561 2792 1586 2792 1586 2793 1561 2793 1559 2793 1586 2794 1559 2794 1585 2794 1585 2795 1559 2795 1560 2795 1585 2796 1560 2796 1553 2796 1594 2797 1595 2797 1596 2797 1595 2798 1594 2798 1597 2798 1598 2799 1599 2799 1600 2799 1599 2800 1601 2800 1602 2800 1602 2801 1601 2801 1603 2801 1602 2802 1603 2802 1604 2802 1422 2803 1420 2803 1605 2803 1605 2804 1420 2804 1419 2804 1605 2805 1419 2805 1606 2805 1606 2806 1419 2806 1607 2806 1422 2807 1605 2807 1423 2807 1423 2808 1605 2808 1608 2808 1423 2809 1608 2809 1424 2809 1424 2810 1608 2810 1425 2810 1425 2811 1608 2811 1609 2811 1425 2812 1609 2812 1427 2812 1427 2813 1609 2813 1610 2813 1427 2814 1610 2814 1410 2814 1410 2815 1610 2815 1611 2815 1410 2816 1611 2816 1407 2816 1407 2817 1611 2817 1612 2817 1407 2818 1612 2818 1406 2818 1613 2819 1614 2819 1594 2819 1594 2820 1614 2820 1615 2820 1594 2821 1615 2821 1597 2821 1616 2822 1617 2822 1613 2822 1613 2823 1617 2823 1618 2823 1613 2824 1618 2824 1614 2824 1619 2825 1620 2825 1621 2825 1621 2826 1620 2826 1622 2826 1621 2827 1622 2827 1616 2827 1616 2828 1622 2828 1623 2828 1616 2829 1623 2829 1617 2829 1604 2830 1624 2830 1602 2830 1602 2831 1624 2831 1625 2831 1602 2832 1625 2832 1626 2832 1626 2833 1625 2833 1627 2833 1626 2834 1627 2834 1619 2834 1619 2835 1627 2835 1628 2835 1619 2836 1628 2836 1620 2836 1402 2837 1406 2837 1629 2837 1629 2838 1406 2838 1612 2838 1629 2839 1612 2839 1630 2839 1630 2840 1612 2840 1611 2840 1630 2841 1611 2841 1631 2841 1631 2842 1611 2842 1610 2842 1631 2843 1610 2843 1632 2843 1632 2844 1610 2844 1609 2844 1632 2845 1609 2845 1633 2845 1633 2846 1609 2846 1608 2846 1633 2847 1608 2847 1634 2847 1634 2848 1608 2848 1605 2848 1634 2849 1605 2849 1635 2849 1635 2850 1605 2850 1606 2850 1635 2851 1606 2851 1600 2851 1600 2852 1606 2852 1607 2852 1600 2853 1607 2853 1598 2853 1599 2854 1602 2854 1600 2854 1600 2855 1602 2855 1626 2855 1600 2856 1626 2856 1635 2856 1635 2857 1626 2857 1619 2857 1635 2858 1619 2858 1634 2858 1634 2859 1619 2859 1621 2859 1634 2860 1621 2860 1633 2860 1633 2861 1621 2861 1616 2861 1633 2862 1616 2862 1632 2862 1632 2863 1616 2863 1613 2863 1632 2864 1613 2864 1631 2864 1631 2865 1613 2865 1594 2865 1631 2866 1594 2866 1630 2866 1630 2867 1594 2867 1596 2867 1630 2868 1596 2868 1629 2868 1636 2869 1593 2869 1637 2869 1638 2870 1639 2870 1558 2870 1640 2871 1641 2871 1642 2871 1643 2872 1644 2872 1645 2872 1643 2873 1646 2873 1647 2873 1647 2874 1646 2874 1648 2874 1647 2875 1648 2875 1641 2875 1649 2876 1650 2876 1651 2876 1651 2877 1650 2877 1652 2877 1651 2878 1652 2878 1653 2878 1653 2879 1652 2879 1654 2879 1653 2880 1654 2880 1640 2880 1655 2881 1573 2881 1656 2881 1656 2882 1573 2882 1575 2882 1656 2883 1575 2883 1636 2883 1636 2884 1575 2884 1577 2884 1636 2885 1577 2885 1593 2885 1657 2886 1571 2886 1658 2886 1658 2887 1571 2887 1569 2887 1658 2888 1569 2888 1655 2888 1655 2889 1569 2889 1568 2889 1655 2890 1568 2890 1573 2890 1659 2891 1565 2891 1657 2891 1657 2892 1565 2892 1572 2892 1657 2893 1572 2893 1571 2893 1557 2894 1563 2894 1660 2894 1660 2895 1563 2895 1562 2895 1660 2896 1562 2896 1659 2896 1659 2897 1562 2897 1566 2897 1659 2898 1566 2898 1565 2898 1644 2899 1661 2899 1645 2899 1645 2900 1661 2900 1662 2900 1645 2901 1662 2901 1663 2901 1664 2902 1665 2902 1666 2902 1666 2903 1665 2903 1667 2903 1666 2904 1667 2904 1668 2904 1668 2905 1667 2905 1669 2905 1668 2906 1669 2906 1649 2906 1649 2907 1669 2907 1670 2907 1649 2908 1670 2908 1650 2908 1640 2909 1642 2909 1653 2909 1653 2910 1642 2910 1671 2910 1653 2911 1671 2911 1651 2911 1651 2912 1671 2912 1672 2912 1651 2913 1672 2913 1649 2913 1649 2914 1672 2914 1673 2914 1649 2915 1673 2915 1668 2915 1668 2916 1673 2916 1674 2916 1668 2917 1674 2917 1666 2917 1666 2918 1674 2918 1675 2918 1666 2919 1675 2919 1664 2919 1641 2920 1648 2920 1642 2920 1642 2921 1648 2921 1676 2921 1642 2922 1676 2922 1671 2922 1671 2923 1676 2923 1677 2923 1671 2924 1677 2924 1672 2924 1672 2925 1677 2925 1678 2925 1672 2926 1678 2926 1673 2926 1673 2927 1678 2927 1679 2927 1673 2928 1679 2928 1674 2928 1674 2929 1679 2929 1680 2929 1674 2930 1680 2930 1675 2930 1643 2931 1645 2931 1646 2931 1646 2932 1645 2932 1681 2932 1646 2933 1681 2933 1648 2933 1648 2934 1681 2934 1682 2934 1648 2935 1682 2935 1676 2935 1676 2936 1682 2936 1683 2936 1676 2937 1683 2937 1677 2937 1677 2938 1683 2938 1684 2938 1677 2939 1684 2939 1678 2939 1678 2940 1684 2940 1685 2940 1678 2941 1685 2941 1679 2941 1679 2942 1685 2942 1686 2942 1679 2943 1686 2943 1680 2943 1680 2944 1686 2944 1687 2944 1680 2945 1687 2945 1675 2945 1675 2946 1687 2946 1688 2946 1675 2947 1688 2947 1664 2947 1664 2948 1688 2948 1689 2948 1664 2949 1689 2949 1665 2949 1638 2950 1558 2950 1690 2950 1690 2951 1558 2951 1557 2951 1690 2952 1557 2952 1663 2952 1663 2953 1557 2953 1660 2953 1663 2954 1660 2954 1645 2954 1645 2955 1660 2955 1659 2955 1645 2956 1659 2956 1681 2956 1681 2957 1659 2957 1657 2957 1681 2958 1657 2958 1682 2958 1682 2959 1657 2959 1658 2959 1682 2960 1658 2960 1683 2960 1683 2961 1658 2961 1655 2961 1683 2962 1655 2962 1684 2962 1684 2963 1655 2963 1656 2963 1684 2964 1656 2964 1685 2964 1685 2965 1656 2965 1636 2965 1685 2966 1636 2966 1686 2966 1686 2967 1636 2967 1637 2967 1686 2968 1637 2968 1687 2968 1691 2969 1692 2969 1693 2969 1693 2970 1692 2970 1694 2970 1693 2971 1694 2971 1695 2971 1696 2972 1697 2972 1698 2972 1698 2973 1697 2973 1699 2973 1698 2974 1699 2974 1693 2974 1693 2975 1699 2975 1700 2975 1693 2976 1700 2976 1691 2976 1701 2977 1702 2977 1696 2977 1703 2978 1704 2978 1705 2978 1705 2979 1704 2979 1702 2979 1705 2980 1702 2980 1706 2980 1707 2981 1708 2981 1703 2981 1709 2982 1710 2982 1711 2982 1711 2983 1710 2983 1712 2983 1709 2984 1624 2984 1713 2984 1713 2985 1624 2985 1604 2985 1713 2986 1604 2986 1714 2986 1709 2987 1711 2987 1624 2987 1624 2988 1711 2988 1715 2988 1624 2989 1715 2989 1625 2989 1625 2990 1715 2990 1627 2990 1627 2991 1715 2991 1716 2991 1627 2992 1716 2992 1628 2992 1628 2993 1716 2993 1717 2993 1628 2994 1717 2994 1620 2994 1620 2995 1717 2995 1622 2995 1622 2996 1717 2996 1718 2996 1622 2997 1718 2997 1623 2997 1623 2998 1718 2998 1617 2998 1617 2999 1718 2999 1719 2999 1617 3000 1719 3000 1618 3000 1618 3001 1719 3001 1614 3001 1614 3002 1719 3002 1720 3002 1614 3003 1720 3003 1615 3003 1721 3004 1722 3004 1723 3004 1723 3005 1722 3005 1724 3005 1723 3006 1724 3006 1725 3006 1694 3007 1726 3007 1695 3007 1695 3008 1726 3008 1727 3008 1695 3009 1727 3009 1721 3009 1721 3010 1727 3010 1728 3010 1721 3011 1728 3011 1722 3011 1724 3012 1729 3012 1725 3012 1725 3013 1729 3013 1730 3013 1725 3014 1730 3014 1731 3014 1696 3015 1698 3015 1701 3015 1701 3016 1698 3016 1693 3016 1701 3017 1693 3017 1732 3017 1732 3018 1693 3018 1695 3018 1732 3019 1695 3019 1733 3019 1733 3020 1695 3020 1721 3020 1733 3021 1721 3021 1734 3021 1734 3022 1721 3022 1723 3022 1734 3023 1723 3023 1735 3023 1735 3024 1723 3024 1725 3024 1735 3025 1725 3025 1736 3025 1736 3026 1725 3026 1731 3026 1736 3027 1731 3027 1737 3027 1702 3028 1701 3028 1706 3028 1706 3029 1701 3029 1732 3029 1706 3030 1732 3030 1738 3030 1738 3031 1732 3031 1733 3031 1738 3032 1733 3032 1739 3032 1739 3033 1733 3033 1734 3033 1739 3034 1734 3034 1740 3034 1740 3035 1734 3035 1735 3035 1740 3036 1735 3036 1741 3036 1741 3037 1735 3037 1736 3037 1741 3038 1736 3038 1742 3038 1742 3039 1736 3039 1737 3039 1742 3040 1737 3040 1743 3040 1703 3041 1705 3041 1707 3041 1707 3042 1705 3042 1706 3042 1707 3043 1706 3043 1744 3043 1744 3044 1706 3044 1738 3044 1744 3045 1738 3045 1745 3045 1745 3046 1738 3046 1739 3046 1745 3047 1739 3047 1746 3047 1746 3048 1739 3048 1740 3048 1746 3049 1740 3049 1747 3049 1747 3050 1740 3050 1741 3050 1747 3051 1741 3051 1748 3051 1748 3052 1741 3052 1742 3052 1748 3053 1742 3053 1749 3053 1749 3054 1742 3054 1743 3054 1749 3055 1743 3055 1750 3055 1597 3056 1615 3056 1750 3056 1750 3057 1615 3057 1720 3057 1750 3058 1720 3058 1749 3058 1749 3059 1720 3059 1719 3059 1749 3060 1719 3060 1748 3060 1748 3061 1719 3061 1718 3061 1748 3062 1718 3062 1747 3062 1747 3063 1718 3063 1717 3063 1747 3064 1717 3064 1746 3064 1746 3065 1717 3065 1716 3065 1746 3066 1716 3066 1745 3066 1745 3067 1716 3067 1715 3067 1745 3068 1715 3068 1744 3068 1744 3069 1715 3069 1711 3069 1744 3070 1711 3070 1707 3070 1707 3071 1711 3071 1712 3071 1707 3072 1712 3072 1708 3072 1751 3073 1726 3073 1752 3073 1752 3074 1726 3074 1694 3074 1752 3075 1694 3075 1692 3075 1650 3076 1670 3076 1753 3076 1753 3077 1670 3077 1669 3077 1753 3078 1669 3078 1754 3078 1754 3079 1669 3079 1667 3079 1754 3080 1667 3080 1755 3080 1755 3081 1667 3081 1665 3081 1755 3082 1665 3082 1756 3082 1756 3083 1665 3083 1689 3083 1756 3084 1689 3084 1757 3084 1757 3085 1689 3085 1758 3085 1757 3086 1758 3086 1759 3086 1759 3087 1758 3087 1760 3087 1759 3088 1760 3088 1761 3088 1761 3089 1760 3089 1762 3089 1761 3090 1762 3090 1763 3090 1763 3091 1762 3091 1764 3091 1763 3092 1764 3092 1765 3092 1765 3093 1764 3093 1766 3093 1765 3094 1766 3094 1767 3094 1767 3095 1766 3095 1768 3095 1767 3096 1768 3096 1769 3096 1769 3097 1768 3097 1770 3097 1769 3098 1770 3098 1771 3098 1771 3099 1770 3099 1729 3099 1771 3100 1729 3100 1772 3100 1772 3101 1729 3101 1724 3101 1772 3102 1724 3102 1773 3102 1773 3103 1724 3103 1722 3103 1773 3104 1722 3104 1774 3104 1774 3105 1722 3105 1728 3105 1774 3106 1728 3106 1751 3106 1751 3107 1728 3107 1727 3107 1751 3108 1727 3108 1726 3108 1775 3109 1592 3109 1584 3109 1400 3110 1776 3110 1397 3110 1397 3111 1776 3111 1777 3111 1397 3112 1777 3112 1395 3112 1395 3113 1777 3113 1778 3113 1395 3114 1778 3114 1393 3114 1393 3115 1778 3115 1779 3115 1393 3116 1779 3116 1391 3116 1391 3117 1779 3117 1780 3117 1391 3118 1780 3118 1359 3118 1359 3119 1780 3119 1781 3119 1359 3120 1781 3120 1360 3120 1360 3121 1781 3121 1782 3121 1360 3122 1782 3122 1362 3122 1583 3123 1367 3123 1782 3123 1782 3124 1367 3124 1365 3124 1782 3125 1365 3125 1362 3125 1593 3126 1592 3126 1783 3126 1783 3127 1592 3127 1775 3127 1783 3128 1775 3128 1784 3128 1784 3129 1775 3129 1785 3129 1784 3130 1785 3130 1786 3130 1787 3131 1788 3131 1789 3131 1789 3132 1788 3132 1790 3132 1789 3133 1790 3133 1791 3133 1791 3134 1790 3134 1792 3134 1791 3135 1792 3135 1793 3135 1793 3136 1792 3136 1786 3136 1793 3137 1786 3137 1794 3137 1794 3138 1786 3138 1785 3138 1596 3139 1776 3139 1629 3139 1629 3140 1776 3140 1400 3140 1629 3141 1400 3141 1402 3141 1583 3142 1782 3142 1795 3142 1795 3143 1782 3143 1781 3143 1795 3144 1781 3144 1796 3144 1796 3145 1781 3145 1780 3145 1796 3146 1780 3146 1797 3146 1797 3147 1780 3147 1779 3147 1797 3148 1779 3148 1798 3148 1798 3149 1779 3149 1778 3149 1798 3150 1778 3150 1799 3150 1799 3151 1778 3151 1777 3151 1799 3152 1777 3152 1800 3152 1800 3153 1777 3153 1776 3153 1800 3154 1776 3154 1801 3154 1801 3155 1776 3155 1596 3155 1801 3156 1596 3156 1595 3156 1597 3157 1788 3157 1595 3157 1595 3158 1788 3158 1787 3158 1595 3159 1787 3159 1801 3159 1801 3160 1787 3160 1789 3160 1801 3161 1789 3161 1800 3161 1800 3162 1789 3162 1791 3162 1800 3163 1791 3163 1799 3163 1799 3164 1791 3164 1793 3164 1799 3165 1793 3165 1798 3165 1798 3166 1793 3166 1794 3166 1798 3167 1794 3167 1797 3167 1797 3168 1794 3168 1785 3168 1797 3169 1785 3169 1796 3169 1796 3170 1785 3170 1775 3170 1796 3171 1775 3171 1795 3171 1795 3172 1775 3172 1584 3172 1795 3173 1584 3173 1583 3173 1802 3174 1731 3174 1730 3174 1788 3175 1597 3175 1750 3175 1788 3176 1803 3176 1804 3176 1788 3177 1804 3177 1790 3177 1790 3178 1804 3178 1805 3178 1790 3179 1805 3179 1792 3179 1805 3180 1806 3180 1792 3180 1792 3181 1806 3181 1807 3181 1792 3182 1807 3182 1786 3182 1786 3183 1807 3183 1808 3183 1786 3184 1808 3184 1784 3184 1784 3185 1808 3185 1809 3185 1784 3186 1809 3186 1783 3186 1730 3187 1729 3187 1810 3187 1810 3188 1729 3188 1770 3188 1810 3189 1770 3189 1811 3189 1811 3190 1770 3190 1768 3190 1811 3191 1768 3191 1812 3191 1812 3192 1768 3192 1766 3192 1812 3193 1766 3193 1813 3193 1813 3194 1766 3194 1764 3194 1813 3195 1764 3195 1814 3195 1814 3196 1764 3196 1762 3196 1814 3197 1762 3197 1815 3197 1815 3198 1762 3198 1760 3198 1815 3199 1760 3199 1816 3199 1816 3200 1760 3200 1758 3200 1687 3201 1816 3201 1688 3201 1688 3202 1816 3202 1758 3202 1688 3203 1758 3203 1689 3203 1730 3204 1810 3204 1802 3204 1802 3205 1810 3205 1811 3205 1802 3206 1811 3206 1817 3206 1817 3207 1811 3207 1812 3207 1817 3208 1812 3208 1818 3208 1818 3209 1812 3209 1813 3209 1818 3210 1813 3210 1819 3210 1819 3211 1813 3211 1814 3211 1819 3212 1814 3212 1820 3212 1820 3213 1814 3213 1815 3213 1820 3214 1815 3214 1821 3214 1821 3215 1815 3215 1816 3215 1821 3216 1816 3216 1822 3216 1822 3217 1816 3217 1687 3217 1822 3218 1687 3218 1637 3218 1788 3219 1750 3219 1803 3219 1803 3220 1750 3220 1743 3220 1803 3221 1743 3221 1737 3221 1593 3222 1783 3222 1637 3222 1637 3223 1783 3223 1809 3223 1637 3224 1809 3224 1822 3224 1822 3225 1809 3225 1808 3225 1822 3226 1808 3226 1821 3226 1821 3227 1808 3227 1807 3227 1821 3228 1807 3228 1820 3228 1820 3229 1807 3229 1806 3229 1820 3230 1806 3230 1819 3230 1819 3231 1806 3231 1805 3231 1819 3232 1805 3232 1818 3232 1818 3233 1805 3233 1804 3233 1818 3234 1804 3234 1817 3234 1817 3235 1804 3235 1803 3235 1817 3236 1803 3236 1802 3236 1802 3237 1803 3237 1737 3237 1802 3238 1737 3238 1731 3238 1823 3239 1824 3239 1075 3239 1825 3240 1826 3240 1076 3240 1827 3241 1828 3241 1086 3241 1086 3242 1828 3242 1829 3242 1086 3243 1829 3243 1123 3243 1123 3244 1829 3244 1830 3244 1123 3245 1830 3245 1831 3245 1830 3246 1832 3246 1833 3246 1833 3247 1834 3247 1830 3247 1830 3248 1834 3248 1835 3248 1830 3249 1835 3249 1831 3249 1068 3250 1836 3250 1837 3250 1837 3251 1838 3251 1068 3251 1068 3252 1838 3252 1839 3252 1068 3253 1839 3253 1086 3253 1086 3254 1839 3254 1840 3254 1086 3255 1840 3255 1827 3255 1841 3256 1842 3256 1067 3256 1067 3257 1842 3257 1843 3257 1067 3258 1843 3258 1068 3258 1068 3259 1843 3259 1844 3259 1068 3260 1844 3260 1836 3260 1845 3261 1846 3261 1107 3261 1107 3262 1846 3262 1847 3262 1107 3263 1847 3263 1067 3263 1067 3264 1847 3264 1848 3264 1067 3265 1848 3265 1841 3265 1079 3266 1849 3266 1107 3266 1107 3267 1849 3267 1850 3267 1107 3268 1850 3268 1845 3268 1851 3269 1852 3269 1078 3269 1078 3270 1852 3270 1853 3270 1078 3271 1853 3271 1079 3271 1079 3272 1853 3272 1854 3272 1079 3273 1854 3273 1849 3273 1826 3274 1855 3274 1076 3274 1076 3275 1855 3275 1856 3275 1076 3276 1856 3276 1078 3276 1078 3277 1856 3277 1857 3277 1078 3278 1857 3278 1851 3278 1075 3279 1824 3279 1076 3279 1076 3280 1824 3280 1858 3280 1076 3281 1858 3281 1825 3281 1859 3282 1860 3282 1861 3282 1861 3283 1860 3283 1862 3283 1861 3284 1862 3284 1863 3284 1823 3285 1075 3285 1864 3285 1864 3286 1075 3286 1103 3286 1864 3287 1103 3287 1861 3287 1861 3288 1103 3288 1865 3288 1861 3289 1865 3289 1859 3289 1866 3290 1867 3290 1868 3290 1869 3291 1870 3291 1412 3291 1412 3292 1870 3292 1871 3292 1412 3293 1871 3293 1426 3293 1868 3294 1867 3294 1412 3294 1412 3295 1867 3295 1872 3295 1412 3296 1872 3296 1869 3296 1873 3297 1874 3297 1868 3297 1868 3298 1874 3298 1875 3298 1868 3299 1875 3299 1866 3299 1876 3300 1877 3300 1878 3300 1878 3301 1877 3301 1879 3301 1878 3302 1879 3302 1873 3302 1873 3303 1879 3303 1880 3303 1873 3304 1880 3304 1874 3304 1881 3305 1326 3305 1490 3305 1490 3306 1876 3306 1881 3306 1881 3307 1876 3307 1878 3307 1881 3308 1878 3308 1882 3308 1882 3309 1878 3309 1873 3309 1882 3310 1873 3310 1883 3310 1883 3311 1873 3311 1868 3311 1883 3312 1868 3312 1411 3312 1411 3313 1868 3313 1412 3313 1882 3314 1883 3314 1884 3314 1885 3315 1886 3315 1887 3315 1885 3316 1887 3316 1888 3316 1396 3317 1889 3317 1890 3317 1396 3318 1890 3318 1398 3318 1398 3319 1890 3319 1891 3319 1398 3320 1891 3320 1399 3320 1352 3321 1892 3321 1354 3321 1354 3322 1892 3322 1887 3322 1354 3323 1887 3323 1357 3323 1357 3324 1887 3324 1886 3324 1357 3325 1886 3325 1358 3325 1350 3326 1893 3326 1352 3326 1352 3327 1893 3327 1894 3327 1352 3328 1894 3328 1892 3328 1350 3329 1348 3329 1893 3329 1893 3330 1348 3330 1345 3330 1893 3331 1345 3331 1895 3331 1895 3332 1345 3332 1343 3332 1895 3333 1343 3333 1896 3333 1896 3334 1343 3334 1342 3334 1896 3335 1342 3335 1897 3335 1342 3336 1339 3336 1897 3336 1897 3337 1339 3337 1337 3337 1897 3338 1337 3338 1898 3338 1898 3339 1337 3339 1335 3339 1898 3340 1335 3340 1899 3340 1335 3341 1333 3341 1899 3341 1899 3342 1333 3342 1331 3342 1899 3343 1331 3343 1900 3343 1900 3344 1331 3344 1330 3344 1900 3345 1330 3345 1901 3345 1901 3346 1330 3346 1323 3346 1901 3347 1323 3347 1902 3347 1323 3348 1329 3348 1902 3348 1902 3349 1329 3349 1328 3349 1902 3350 1328 3350 1903 3350 1903 3351 1328 3351 1326 3351 1326 3352 1881 3352 1903 3352 1903 3353 1881 3353 1904 3353 1903 3354 1904 3354 1902 3354 1902 3355 1904 3355 1905 3355 1902 3356 1905 3356 1901 3356 1901 3357 1905 3357 1906 3357 1901 3358 1906 3358 1900 3358 1900 3359 1906 3359 1907 3359 1900 3360 1907 3360 1899 3360 1899 3361 1907 3361 1908 3361 1899 3362 1908 3362 1898 3362 1898 3363 1908 3363 1909 3363 1898 3364 1909 3364 1897 3364 1897 3365 1909 3365 1910 3365 1897 3366 1910 3366 1896 3366 1896 3367 1910 3367 1911 3367 1896 3368 1911 3368 1895 3368 1895 3369 1911 3369 1912 3369 1895 3370 1912 3370 1893 3370 1893 3371 1912 3371 1913 3371 1893 3372 1913 3372 1894 3372 1894 3373 1913 3373 1914 3373 1894 3374 1914 3374 1892 3374 1892 3375 1914 3375 1915 3375 1892 3376 1915 3376 1887 3376 1887 3377 1915 3377 1916 3377 1887 3378 1916 3378 1888 3378 1888 3379 1916 3379 1917 3379 1881 3380 1882 3380 1904 3380 1904 3381 1882 3381 1884 3381 1904 3382 1884 3382 1905 3382 1905 3383 1884 3383 1918 3383 1905 3384 1918 3384 1906 3384 1906 3385 1918 3385 1919 3385 1906 3386 1919 3386 1907 3386 1907 3387 1919 3387 1920 3387 1907 3388 1920 3388 1908 3388 1908 3389 1920 3389 1921 3389 1908 3390 1921 3390 1909 3390 1909 3391 1921 3391 1922 3391 1909 3392 1922 3392 1910 3392 1910 3393 1922 3393 1923 3393 1910 3394 1923 3394 1911 3394 1911 3395 1923 3395 1924 3395 1911 3396 1924 3396 1912 3396 1912 3397 1924 3397 1925 3397 1912 3398 1925 3398 1913 3398 1913 3399 1925 3399 1926 3399 1913 3400 1926 3400 1914 3400 1914 3401 1926 3401 1927 3401 1914 3402 1927 3402 1915 3402 1915 3403 1927 3403 1891 3403 1915 3404 1891 3404 1916 3404 1916 3405 1891 3405 1890 3405 1916 3406 1890 3406 1917 3406 1917 3407 1890 3407 1889 3407 1399 3408 1891 3408 1401 3408 1401 3409 1891 3409 1927 3409 1401 3410 1927 3410 1403 3410 1403 3411 1927 3411 1926 3411 1403 3412 1926 3412 1404 3412 1404 3413 1926 3413 1925 3413 1404 3414 1925 3414 1405 3414 1405 3415 1925 3415 1924 3415 1405 3416 1924 3416 1408 3416 1408 3417 1924 3417 1923 3417 1408 3418 1923 3418 1409 3418 1409 3419 1923 3419 1922 3419 1409 3420 1922 3420 1414 3420 1414 3421 1922 3421 1921 3421 1414 3422 1921 3422 1415 3422 1415 3423 1921 3423 1920 3423 1415 3424 1920 3424 1416 3424 1416 3425 1920 3425 1919 3425 1416 3426 1919 3426 1417 3426 1417 3427 1919 3427 1918 3427 1417 3428 1918 3428 1418 3428 1418 3429 1918 3429 1884 3429 1418 3430 1884 3430 1413 3430 1413 3431 1884 3431 1883 3431 1413 3432 1883 3432 1411 3432 1284 3433 1459 3433 1928 3433 1928 3434 1459 3434 1929 3434 1928 3435 1929 3435 1930 3435 1459 3436 1458 3436 1931 3436 1931 3437 1458 3437 1358 3437 1931 3438 1358 3438 1886 3438 1459 3439 1931 3439 1929 3439 1929 3440 1931 3440 1932 3440 1929 3441 1932 3441 1933 3441 1933 3442 1361 3442 1363 3442 1363 3443 1934 3443 1933 3443 1933 3444 1934 3444 1935 3444 1933 3445 1935 3445 1929 3445 1929 3446 1935 3446 1936 3446 1929 3447 1936 3447 1930 3447 1886 3448 1885 3448 1931 3448 1931 3449 1885 3449 1888 3449 1931 3450 1888 3450 1932 3450 1932 3451 1888 3451 1917 3451 1932 3452 1917 3452 1889 3452 1361 3453 1933 3453 1392 3453 1392 3454 1933 3454 1932 3454 1392 3455 1932 3455 1394 3455 1394 3456 1932 3456 1889 3456 1394 3457 1889 3457 1396 3457 1937 3458 1938 3458 1939 3458 1315 3459 1939 3459 1313 3459 1313 3460 1939 3460 1938 3460 1313 3461 1938 3461 1311 3461 1317 3462 1940 3462 1315 3462 1315 3463 1940 3463 1941 3463 1315 3464 1941 3464 1939 3464 1317 3465 1319 3465 1940 3465 1940 3466 1319 3466 1320 3466 1940 3467 1320 3467 1942 3467 1942 3468 1320 3468 1309 3468 1942 3469 1309 3469 1943 3469 1943 3470 1309 3470 1307 3470 1943 3471 1307 3471 1944 3471 1944 3472 1307 3472 1305 3472 1944 3473 1305 3473 1945 3473 1305 3474 1303 3474 1945 3474 1945 3475 1303 3475 1301 3475 1945 3476 1301 3476 1946 3476 1946 3477 1301 3477 1299 3477 1946 3478 1299 3478 1947 3478 1947 3479 1299 3479 1297 3479 1947 3480 1297 3480 1948 3480 1948 3481 1297 3481 1295 3481 1948 3482 1295 3482 1292 3482 1290 3483 1949 3483 1292 3483 1292 3484 1949 3484 1950 3484 1292 3485 1950 3485 1948 3485 1381 3486 1951 3486 1382 3486 1382 3487 1951 3487 1952 3487 1382 3488 1952 3488 1383 3488 1383 3489 1952 3489 1953 3489 1383 3490 1953 3490 1384 3490 1384 3491 1953 3491 1954 3491 1384 3492 1954 3492 1385 3492 1385 3493 1954 3493 1955 3493 1385 3494 1955 3494 1386 3494 1386 3495 1955 3495 1956 3495 1386 3496 1956 3496 1390 3496 1390 3497 1956 3497 1957 3497 1390 3498 1957 3498 1389 3498 1389 3499 1957 3499 1958 3499 1389 3500 1958 3500 1369 3500 1369 3501 1958 3501 1959 3501 1369 3502 1959 3502 1370 3502 1370 3503 1959 3503 1960 3503 1370 3504 1960 3504 1371 3504 1371 3505 1960 3505 1961 3505 1371 3506 1961 3506 1372 3506 1372 3507 1961 3507 1962 3507 1372 3508 1962 3508 1368 3508 1963 3509 1964 3509 1965 3509 1965 3510 1964 3510 1962 3510 1965 3511 1962 3511 1966 3511 1966 3512 1962 3512 1961 3512 1966 3513 1961 3513 1967 3513 1967 3514 1961 3514 1960 3514 1967 3515 1960 3515 1968 3515 1968 3516 1960 3516 1959 3516 1968 3517 1959 3517 1969 3517 1969 3518 1959 3518 1958 3518 1969 3519 1958 3519 1970 3519 1970 3520 1958 3520 1957 3520 1970 3521 1957 3521 1971 3521 1971 3522 1957 3522 1956 3522 1971 3523 1956 3523 1972 3523 1972 3524 1956 3524 1955 3524 1972 3525 1955 3525 1973 3525 1973 3526 1955 3526 1954 3526 1973 3527 1954 3527 1974 3527 1974 3528 1954 3528 1953 3528 1974 3529 1953 3529 1975 3529 1975 3530 1953 3530 1952 3530 1975 3531 1952 3531 1976 3531 1976 3532 1952 3532 1951 3532 1976 3533 1951 3533 1977 3533 1977 3534 1951 3534 1381 3534 1368 3535 1962 3535 1366 3535 1366 3536 1962 3536 1964 3536 1366 3537 1964 3537 1364 3537 1290 3538 1289 3538 1949 3538 1949 3539 1289 3539 1286 3539 1949 3540 1286 3540 1978 3540 1978 3541 1286 3541 1284 3541 1978 3542 1284 3542 1928 3542 1928 3543 1930 3543 1978 3543 1978 3544 1930 3544 1963 3544 1978 3545 1963 3545 1949 3545 1949 3546 1963 3546 1965 3546 1949 3547 1965 3547 1950 3547 1950 3548 1965 3548 1966 3548 1950 3549 1966 3549 1948 3549 1948 3550 1966 3550 1967 3550 1948 3551 1967 3551 1947 3551 1947 3552 1967 3552 1968 3552 1947 3553 1968 3553 1946 3553 1946 3554 1968 3554 1969 3554 1946 3555 1969 3555 1945 3555 1945 3556 1969 3556 1970 3556 1945 3557 1970 3557 1944 3557 1944 3558 1970 3558 1971 3558 1944 3559 1971 3559 1943 3559 1943 3560 1971 3560 1972 3560 1943 3561 1972 3561 1942 3561 1942 3562 1972 3562 1973 3562 1942 3563 1973 3563 1940 3563 1940 3564 1973 3564 1974 3564 1940 3565 1974 3565 1941 3565 1941 3566 1974 3566 1975 3566 1941 3567 1975 3567 1939 3567 1939 3568 1975 3568 1976 3568 1939 3569 1976 3569 1937 3569 1937 3570 1976 3570 1977 3570 1363 3571 1364 3571 1934 3571 1934 3572 1364 3572 1964 3572 1934 3573 1964 3573 1935 3573 1935 3574 1964 3574 1963 3574 1935 3575 1963 3575 1936 3575 1936 3576 1963 3576 1930 3576 1979 3577 1980 3577 1981 3577 1980 3578 1979 3578 1982 3578 1983 3579 1984 3579 1985 3579 1379 3580 1986 3580 1380 3580 1380 3581 1986 3581 1987 3581 1380 3582 1987 3582 1983 3582 1983 3583 1987 3583 1988 3583 1983 3584 1988 3584 1984 3584 1311 3585 1938 3585 1450 3585 1450 3586 1938 3586 1989 3586 1985 3587 1990 3587 1983 3587 1983 3588 1990 3588 1991 3588 1983 3589 1991 3589 1981 3589 1981 3590 1991 3590 1992 3590 1981 3591 1992 3591 1979 3591 1982 3592 1989 3592 1980 3592 1980 3593 1989 3593 1938 3593 1980 3594 1938 3594 1981 3594 1981 3595 1938 3595 1937 3595 1981 3596 1937 3596 1983 3596 1983 3597 1937 3597 1977 3597 1983 3598 1977 3598 1380 3598 1380 3599 1977 3599 1381 3599 1993 3600 1514 3600 1994 3600 1994 3601 1514 3601 1995 3601 1994 3602 1996 3602 1993 3602 1993 3603 1996 3603 1997 3603 1993 3604 1997 3604 1998 3604 1998 3605 1997 3605 1999 3605 1426 3606 1871 3606 2000 3606 2000 3607 1871 3607 2001 3607 2000 3608 2001 3608 2002 3608 1994 3609 2003 3609 1996 3609 1996 3610 2003 3610 2000 3610 1996 3611 2000 3611 1997 3611 1997 3612 2000 3612 2002 3612 1997 3613 2002 3613 1999 3613 1495 3614 2004 3614 1511 3614 1511 3615 2004 3615 1995 3615 1511 3616 1995 3616 1513 3616 1513 3617 1995 3617 1514 3617 2005 3618 2006 3618 2007 3618 2007 3619 2006 3619 2008 3619 1110 3620 2008 3620 1111 3620 1111 3621 2008 3621 2006 3621 1111 3622 2006 3622 1492 3622 1492 3623 2006 3623 2005 3623 1492 3624 2005 3624 1493 3624 1493 3625 2005 3625 1495 3625 2009 3626 2010 3626 2011 3626 1055 3627 1074 3627 2011 3627 2011 3628 1074 3628 2012 3628 2011 3629 2012 3629 2009 3629 2009 3630 2012 3630 2013 3630 2009 3631 2013 3631 2014 3631 2014 3632 2013 3632 2015 3632 2014 3633 2015 3633 2016 3633 1448 3634 2017 3634 1444 3634 1444 3635 2017 3635 2018 3635 1444 3636 2018 3636 1445 3636 1074 3637 1447 3637 2012 3637 2012 3638 1447 3638 1446 3638 2012 3639 1446 3639 2013 3639 2013 3640 1446 3640 1445 3640 2013 3641 1445 3641 2015 3641 2015 3642 1445 3642 2018 3642 2015 3643 2018 3643 2016 3643 1379 3644 2019 3644 1986 3644 1986 3645 2019 3645 2020 3645 2020 3646 2019 3646 2021 3646 2021 3647 2019 3647 2022 3647 2021 3648 2022 3648 2023 3648 2023 3649 2022 3649 2024 3649 2023 3650 2024 3650 2025 3650 2025 3651 2024 3651 2026 3651 2025 3652 2026 3652 2027 3652 1448 3653 1436 3653 2028 3653 2028 3654 1436 3654 1435 3654 2028 3655 1435 3655 2029 3655 2019 3656 2030 3656 2022 3656 2022 3657 2030 3657 2031 3657 2022 3658 2031 3658 2024 3658 2024 3659 2031 3659 2032 3659 2024 3660 2032 3660 2026 3660 2026 3661 2032 3661 2029 3661 2026 3662 2029 3662 2027 3662 2027 3663 2029 3663 1435 3663 1604 3664 1603 3664 2033 3664 2034 3665 2035 3665 2036 3665 2036 3666 2035 3666 2037 3666 2036 3667 2037 3667 2038 3667 2038 3668 2037 3668 2039 3668 2039 3669 2040 3669 2038 3669 2038 3670 2040 3670 1714 3670 2038 3671 1714 3671 1604 3671 1604 3672 2033 3672 2038 3672 2038 3673 2033 3673 2041 3673 2038 3674 2041 3674 2042 3674 2042 3675 2041 3675 1421 3675 2042 3676 1421 3676 1426 3676 1603 3677 1601 3677 2033 3677 2033 3678 1601 3678 1599 3678 2033 3679 1599 3679 2041 3679 2041 3680 1599 3680 1598 3680 2041 3681 1598 3681 1421 3681 1421 3682 1598 3682 1607 3682 1421 3683 1607 3683 1419 3683 1426 3684 2000 3684 2043 3684 2043 3685 2000 3685 2003 3685 2043 3686 2003 3686 1994 3686 2044 3687 2034 3687 2045 3687 2045 3688 2034 3688 2036 3688 2045 3689 2036 3689 2046 3689 2046 3690 2036 3690 2038 3690 2046 3691 2038 3691 2043 3691 2043 3692 2038 3692 2042 3692 2043 3693 2042 3693 1426 3693 2007 3694 2044 3694 2005 3694 2005 3695 2044 3695 2045 3695 2005 3696 2045 3696 1495 3696 2046 3697 1495 3697 2045 3697 1994 3698 1995 3698 2043 3698 2043 3699 1995 3699 2004 3699 2043 3700 2004 3700 2046 3700 2046 3701 2004 3701 1495 3701 2047 3702 1379 3702 1375 3702 2048 3703 2049 3703 2050 3703 2051 3704 2052 3704 2053 3704 2051 3705 2053 3705 2054 3705 2053 3706 1560 3706 2055 3706 2055 3707 1560 3707 1558 3707 2055 3708 1558 3708 2053 3708 2053 3709 1558 3709 1639 3709 2053 3710 1639 3710 2054 3710 2053 3711 2048 3711 1560 3711 1560 3712 2048 3712 2050 3712 1560 3713 2050 3713 1553 3713 1553 3714 2050 3714 1554 3714 2049 3715 2047 3715 2050 3715 2050 3716 2047 3716 1375 3716 2050 3717 1375 3717 1554 3717 1554 3718 1375 3718 1377 3718 2056 3719 2017 3719 1448 3719 2049 3720 2048 3720 2057 3720 2052 3721 2058 3721 2056 3721 2058 3722 2010 3722 2009 3722 2009 3723 2014 3723 2058 3723 2058 3724 2014 3724 2016 3724 2058 3725 2016 3725 2056 3725 2056 3726 2016 3726 2018 3726 2056 3727 2018 3727 2017 3727 2048 3728 2053 3728 2059 3728 2059 3729 2053 3729 2052 3729 2019 3730 1379 3730 2047 3730 2019 3731 2047 3731 2030 3731 2030 3732 2047 3732 2049 3732 2030 3733 2049 3733 2031 3733 2031 3734 2049 3734 2057 3734 2031 3735 2057 3735 2032 3735 1448 3736 2028 3736 2057 3736 2057 3737 2028 3737 2029 3737 2057 3738 2029 3738 2032 3738 2048 3739 2059 3739 2057 3739 2057 3740 2059 3740 1448 3740 2052 3741 2056 3741 2059 3741 2059 3742 2056 3742 1448 3742 1093 3743 1092 3743 2060 3743 2061 3744 1863 3744 1862 3744 2062 3745 2061 3745 2063 3745 2063 3746 2061 3746 2064 3746 2061 3747 1862 3747 2064 3747 2064 3748 1862 3748 1860 3748 2064 3749 1860 3749 2060 3749 1093 3750 2060 3750 1094 3750 2060 3751 1860 3751 1094 3751 1094 3752 1860 3752 1859 3752 1094 3753 1859 3753 1104 3753 1104 3754 1859 3754 1865 3754 1104 3755 1865 3755 1103 3755 1123 3756 1831 3756 1124 3756 2065 3757 2066 3757 2067 3757 2067 3758 2066 3758 2068 3758 2069 3759 1058 3759 1124 3759 1831 3760 1835 3760 1124 3760 1124 3761 1835 3761 1834 3761 1124 3762 1834 3762 2069 3762 2069 3763 1834 3763 1833 3763 2069 3764 1833 3764 2065 3764 2065 3765 1833 3765 1832 3765 2065 3766 1832 3766 2066 3766 2070 3767 2034 3767 2071 3767 2071 3768 2034 3768 2044 3768 2071 3769 2044 3769 2072 3769 2072 3770 2044 3770 2073 3770 2072 3771 2073 3771 2074 3771 2074 3772 2073 3772 2075 3772 2076 3773 2067 3773 2068 3773 2068 3774 2075 3774 2076 3774 2076 3775 2075 3775 2073 3775 2076 3776 2073 3776 2007 3776 2007 3777 2073 3777 2044 3777 2076 3778 2007 3778 2008 3778 1059 3779 1058 3779 2077 3779 2077 3780 1058 3780 2069 3780 2077 3781 2069 3781 2065 3781 1110 3782 1059 3782 2008 3782 2008 3783 1059 3783 2077 3783 2008 3784 2077 3784 2076 3784 2076 3785 2077 3785 2065 3785 2076 3786 2065 3786 2067 3786 2064 3787 2060 3787 2078 3787 1055 3788 2011 3788 2078 3788 1055 3789 2078 3789 1056 3789 1056 3790 2078 3790 2060 3790 1056 3791 2060 3791 1092 3791 2011 3792 2010 3792 2078 3792 2078 3793 2010 3793 2079 3793 2078 3794 2079 3794 2064 3794 2064 3795 2079 3795 2063 3795 2079 3796 2010 3796 2058 3796 2062 3797 2063 3797 2079 3797 2080 3798 2081 3798 2082 3798 2082 3799 2081 3799 2083 3799 2082 3800 2083 3800 2084 3800 2058 3801 2052 3801 2085 3801 2085 3802 2080 3802 2058 3802 2058 3803 2080 3803 2082 3803 2058 3804 2082 3804 2079 3804 2079 3805 2082 3805 2084 3805 2079 3806 2084 3806 2062 3806 2051 3807 2085 3807 2052 3807 2054 3808 2086 3808 2051 3808 2054 3809 1639 3809 1638 3809 2086 3810 2054 3810 2087 3810 2085 3811 2051 3811 2080 3811 2054 3812 1638 3812 2087 3812 2087 3813 1638 3813 1690 3813 2087 3814 1690 3814 2088 3814 2088 3815 1690 3815 1663 3815 2088 3816 1663 3816 2089 3816 2089 3817 1663 3817 1662 3817 2089 3818 1662 3818 2090 3818 2051 3819 2086 3819 2080 3819 2080 3820 2086 3820 2087 3820 2080 3821 2087 3821 2081 3821 2081 3822 2087 3822 2088 3822 2081 3823 2088 3823 2083 3823 2083 3824 2088 3824 2089 3824 2083 3825 2089 3825 2084 3825 2084 3826 2089 3826 2090 3826 2084 3827 2090 3827 2062 3827 2091 3828 1661 3828 1644 3828 1644 3829 2092 3829 2091 3829 2091 3830 2092 3830 2093 3830 2091 3831 2093 3831 2061 3831 2061 3832 2093 3832 2094 3832 2061 3833 2094 3833 1863 3833 1662 3834 1661 3834 2090 3834 2090 3835 1661 3835 2091 3835 2090 3836 2091 3836 2062 3836 2062 3837 2091 3837 2061 3837 1654 3838 1652 3838 2095 3838 1824 3839 1823 3839 2096 3839 1824 3840 2096 3840 1858 3840 2097 3841 2098 3841 2099 3841 2100 3842 2095 3842 1652 3842 2100 3843 1652 3843 1650 3843 2100 3844 2098 3844 2095 3844 2095 3845 2098 3845 2097 3845 2095 3846 2097 3846 2101 3846 2101 3847 1647 3847 1641 3847 2101 3848 1641 3848 2095 3848 2095 3849 1641 3849 1640 3849 2095 3850 1640 3850 1654 3850 1864 3851 1861 3851 2102 3851 2102 3852 1861 3852 2103 3852 2102 3853 2103 3853 2104 3853 1823 3854 1864 3854 2096 3854 2096 3855 1864 3855 2102 3855 2096 3856 2102 3856 2105 3856 2105 3857 2102 3857 2104 3857 2105 3858 2104 3858 2106 3858 1643 3859 1647 3859 2106 3859 2106 3860 1647 3860 2101 3860 2106 3861 2101 3861 2105 3861 2105 3862 2101 3862 2097 3862 2105 3863 2097 3863 2096 3863 2096 3864 2097 3864 2099 3864 2096 3865 2099 3865 1858 3865 1644 3866 1643 3866 2092 3866 2092 3867 1643 3867 2106 3867 2092 3868 2106 3868 2093 3868 2093 3869 2106 3869 2104 3869 2093 3870 2104 3870 2094 3870 2094 3871 2104 3871 2103 3871 2094 3872 2103 3872 1863 3872 1863 3873 2103 3873 1861 3873 2107 3874 2108 3874 2109 3874 2110 3875 2111 3875 2112 3875 2113 3876 2114 3876 2115 3876 2116 3877 1839 3877 1838 3877 2116 3878 1838 3878 2114 3878 2110 3879 2112 3879 2117 3879 2114 3880 1838 3880 2115 3880 2115 3881 1838 3881 1837 3881 2115 3882 1837 3882 2118 3882 2118 3883 1837 3883 1836 3883 2118 3884 1836 3884 2119 3884 2119 3885 1836 3885 1844 3885 2119 3886 1844 3886 2120 3886 2120 3887 1844 3887 1843 3887 2120 3888 1843 3888 1842 3888 1841 3889 2121 3889 1842 3889 1842 3890 2121 3890 2122 3890 1842 3891 2122 3891 2120 3891 1841 3892 1848 3892 2121 3892 2121 3893 1848 3893 1847 3893 2121 3894 1847 3894 2123 3894 2123 3895 1847 3895 1846 3895 2123 3896 1846 3896 2124 3896 2124 3897 1846 3897 1845 3897 2124 3898 1845 3898 2125 3898 1845 3899 1850 3899 2125 3899 2125 3900 1850 3900 1849 3900 2125 3901 1849 3901 2126 3901 2126 3902 1849 3902 1854 3902 2126 3903 1854 3903 2127 3903 2127 3904 1854 3904 1853 3904 2127 3905 1853 3905 2128 3905 2128 3906 1853 3906 1852 3906 1851 3907 2129 3907 1852 3907 1852 3908 2129 3908 2130 3908 1852 3909 2130 3909 2128 3909 1851 3910 1857 3910 2129 3910 2129 3911 1857 3911 1856 3911 2129 3912 1856 3912 2131 3912 2111 3913 2113 3913 2112 3913 2112 3914 2113 3914 2115 3914 2112 3915 2115 3915 2132 3915 2132 3916 2115 3916 2118 3916 2132 3917 2118 3917 2133 3917 2133 3918 2118 3918 2119 3918 2133 3919 2119 3919 2134 3919 2134 3920 2119 3920 2120 3920 2134 3921 2120 3921 2135 3921 2135 3922 2120 3922 2122 3922 2135 3923 2122 3923 2136 3923 2136 3924 2122 3924 2121 3924 2136 3925 2121 3925 2137 3925 2137 3926 2121 3926 2123 3926 2137 3927 2123 3927 2138 3927 2138 3928 2123 3928 2124 3928 2138 3929 2124 3929 2139 3929 2139 3930 2124 3930 2125 3930 2139 3931 2125 3931 2140 3931 2140 3932 2125 3932 2126 3932 2140 3933 2126 3933 2141 3933 2141 3934 2126 3934 2127 3934 2141 3935 2127 3935 2142 3935 2142 3936 2127 3936 2128 3936 2142 3937 2128 3937 2143 3937 2143 3938 2128 3938 2130 3938 2143 3939 2130 3939 2144 3939 2144 3940 2130 3940 2129 3940 2144 3941 2129 3941 2145 3941 2145 3942 2129 3942 2131 3942 2145 3943 2131 3943 2146 3943 1825 3944 2108 3944 1826 3944 1826 3945 2108 3945 2107 3945 1826 3946 2107 3946 1855 3946 2147 3947 2117 3947 2148 3947 2148 3948 2117 3948 2112 3948 2148 3949 2112 3949 2149 3949 2149 3950 2112 3950 2132 3950 2149 3951 2132 3951 2150 3951 2150 3952 2132 3952 2133 3952 2150 3953 2133 3953 2151 3953 2151 3954 2133 3954 2134 3954 2151 3955 2134 3955 2152 3955 2152 3956 2134 3956 2135 3956 2152 3957 2135 3957 2153 3957 2153 3958 2135 3958 2136 3958 2153 3959 2136 3959 2154 3959 2154 3960 2136 3960 2137 3960 2154 3961 2137 3961 2155 3961 2155 3962 2137 3962 2138 3962 2155 3963 2138 3963 2156 3963 2156 3964 2138 3964 2139 3964 2156 3965 2139 3965 2157 3965 2157 3966 2139 3966 2140 3966 2157 3967 2140 3967 2158 3967 2158 3968 2140 3968 2141 3968 2158 3969 2141 3969 2159 3969 2159 3970 2141 3970 2142 3970 2159 3971 2142 3971 2160 3971 2160 3972 2142 3972 2143 3972 2160 3973 2143 3973 2161 3973 2161 3974 2143 3974 2144 3974 2161 3975 2144 3975 2162 3975 2162 3976 2144 3976 2145 3976 2162 3977 2145 3977 2163 3977 2163 3978 2145 3978 2146 3978 2163 3979 2146 3979 2164 3979 1691 3980 2147 3980 1692 3980 1692 3981 2147 3981 2148 3981 1692 3982 2148 3982 1752 3982 1752 3983 2148 3983 2149 3983 1752 3984 2149 3984 1751 3984 1751 3985 2149 3985 2150 3985 1751 3986 2150 3986 1774 3986 1774 3987 2150 3987 2151 3987 1774 3988 2151 3988 1773 3988 1773 3989 2151 3989 2152 3989 1773 3990 2152 3990 1772 3990 1772 3991 2152 3991 2153 3991 1772 3992 2153 3992 1771 3992 1771 3993 2153 3993 2154 3993 1771 3994 2154 3994 1769 3994 1769 3995 2154 3995 2155 3995 1769 3996 2155 3996 1767 3996 1767 3997 2155 3997 2156 3997 1767 3998 2156 3998 1765 3998 1765 3999 2156 3999 2157 3999 1765 4000 2157 4000 1763 4000 1763 4001 2157 4001 2158 4001 1763 4002 2158 4002 1761 4002 1761 4003 2158 4003 2159 4003 1761 4004 2159 4004 1759 4004 1759 4005 2159 4005 2160 4005 1759 4006 2160 4006 1757 4006 1757 4007 2160 4007 2161 4007 1757 4008 2161 4008 1756 4008 1756 4009 2161 4009 2162 4009 1756 4010 2162 4010 1755 4010 1755 4011 2162 4011 2163 4011 1755 4012 2163 4012 1754 4012 1754 4013 2163 4013 2164 4013 1754 4014 2164 4014 1753 4014 1753 4015 2164 4015 2100 4015 1753 4016 2100 4016 1650 4016 1825 4017 1858 4017 2108 4017 2108 4018 1858 4018 2099 4018 2108 4019 2099 4019 2109 4019 2109 4020 2099 4020 2098 4020 1856 4021 1855 4021 2131 4021 2131 4022 1855 4022 2107 4022 2131 4023 2107 4023 2146 4023 2146 4024 2107 4024 2109 4024 2146 4025 2109 4025 2164 4025 2164 4026 2109 4026 2098 4026 2164 4027 2098 4027 2100 4027 2165 4028 2166 4028 2167 4028 2147 4029 1691 4029 1700 4029 2111 4030 2110 4030 2168 4030 2168 4031 2110 4031 2117 4031 2168 4032 2117 4032 2147 4032 2114 4033 2113 4033 2169 4033 1840 4034 1839 4034 2116 4034 2147 4035 1700 4035 2168 4035 2168 4036 1700 4036 1699 4036 2168 4037 1699 4037 2170 4037 2170 4038 1699 4038 1697 4038 2170 4039 1697 4039 2171 4039 2171 4040 1697 4040 1696 4040 2171 4041 1696 4041 2172 4041 1696 4042 1702 4042 2172 4042 2172 4043 1702 4043 1704 4043 2172 4044 1704 4044 2173 4044 2173 4045 1704 4045 1703 4045 1703 4046 2174 4046 2173 4046 2173 4047 2174 4047 2175 4047 2173 4048 2175 4048 2172 4048 2172 4049 2175 4049 2176 4049 2172 4050 2176 4050 2171 4050 2171 4051 2176 4051 2177 4051 2171 4052 2177 4052 2170 4052 2170 4053 2177 4053 2178 4053 2170 4054 2178 4054 2168 4054 2168 4055 2178 4055 2169 4055 2168 4056 2169 4056 2111 4056 2111 4057 2169 4057 2113 4057 2174 4058 2165 4058 2175 4058 2175 4059 2165 4059 2167 4059 2175 4060 2167 4060 2176 4060 2176 4061 2167 4061 2179 4061 2176 4062 2179 4062 2177 4062 2177 4063 2179 4063 2180 4063 2177 4064 2180 4064 2178 4064 2178 4065 2180 4065 2181 4065 2178 4066 2181 4066 2169 4066 2169 4067 2181 4067 2182 4067 2169 4068 2182 4068 2114 4068 2114 4069 2182 4069 2116 4069 2116 4070 2182 4070 1840 4070 1840 4071 2182 4071 2181 4071 1840 4072 2181 4072 1827 4072 1827 4073 2181 4073 2180 4073 1827 4074 2180 4074 1828 4074 1828 4075 2180 4075 2179 4075 1828 4076 2179 4076 1829 4076 1829 4077 2179 4077 2167 4077 1829 4078 2167 4078 1830 4078 1830 4079 2167 4079 2166 4079 1830 4080 2166 4080 1832 4080 2183 4081 1708 4081 1712 4081 2184 4082 2068 4082 2066 4082 1832 4083 2166 4083 2066 4083 2066 4084 2166 4084 2183 4084 2066 4085 2183 4085 2184 4085 2184 4086 2183 4086 1712 4086 1703 4087 1708 4087 2174 4087 2174 4088 1708 4088 2183 4088 2174 4089 2183 4089 2165 4089 2165 4090 2183 4090 2166 4090 2039 4091 2185 4091 2040 4091 2034 4092 2070 4092 2035 4092 2035 4093 2070 4093 2037 4093 2037 4094 2070 4094 2039 4094 2039 4095 2070 4095 2071 4095 2039 4096 2071 4096 2185 4096 2185 4097 2071 4097 2072 4097 2185 4098 2072 4098 2186 4098 2186 4099 2072 4099 2074 4099 2186 4100 2074 4100 2187 4100 2187 4101 2074 4101 2075 4101 2187 4102 2075 4102 2188 4102 2188 4103 2075 4103 2068 4103 2188 4104 2068 4104 2184 4104 2040 4105 2185 4105 1714 4105 1714 4106 2185 4106 2186 4106 1714 4107 2186 4107 1713 4107 1713 4108 2186 4108 2187 4108 1713 4109 2187 4109 1709 4109 1709 4110 2187 4110 2188 4110 1709 4111 2188 4111 1710 4111 1710 4112 2188 4112 2184 4112 1710 4113 2184 4113 1712 4113 1514 4114 1993 4114 2189 4114 2189 4115 1993 4115 1998 4115 2189 4116 1998 4116 2190 4116 1866 4117 2191 4117 1867 4117 1867 4118 2191 4118 1872 4118 2190 4119 1998 4119 2192 4119 2192 4120 1998 4120 1999 4120 2192 4121 1999 4121 2193 4121 1999 4122 2002 4122 2193 4122 2193 4123 2002 4123 2001 4123 2193 4124 2001 4124 2194 4124 2194 4125 2001 4125 1871 4125 1871 4126 1870 4126 2194 4126 2194 4127 1870 4127 1869 4127 2194 4128 1869 4128 2193 4128 2193 4129 1869 4129 1872 4129 2193 4130 1872 4130 2192 4130 2192 4131 1872 4131 2191 4131 2192 4132 2191 4132 2190 4132 1874 4133 1880 4133 2195 4133 1508 4134 1507 4134 2196 4134 1499 4135 1498 4135 2197 4135 2197 4136 1498 4136 2198 4136 1508 4137 2196 4137 1502 4137 1498 4138 1502 4138 2198 4138 2198 4139 1502 4139 2196 4139 2198 4140 2196 4140 2199 4140 2199 4141 2196 4141 2200 4141 2199 4142 2200 4142 2201 4142 2201 4143 2200 4143 2202 4143 2202 4144 2200 4144 2203 4144 2202 4145 2203 4145 2204 4145 1879 4146 1877 4146 2203 4146 2203 4147 1877 4147 2205 4147 2203 4148 2205 4148 2204 4148 1506 4149 1510 4149 2206 4149 2206 4150 1510 4150 1509 4150 2206 4151 1509 4151 1515 4151 1880 4152 1879 4152 2195 4152 2195 4153 1879 4153 2203 4153 2195 4154 2203 4154 2207 4154 2207 4155 2203 4155 2200 4155 2207 4156 2200 4156 2206 4156 2206 4157 2200 4157 2196 4157 2206 4158 2196 4158 1506 4158 1506 4159 2196 4159 1507 4159 1875 4160 1874 4160 2208 4160 2208 4161 1874 4161 2195 4161 2208 4162 2195 4162 2209 4162 2209 4163 2195 4163 2207 4163 2209 4164 2207 4164 2210 4164 2210 4165 2207 4165 2206 4165 2210 4166 2206 4166 1512 4166 1512 4167 2206 4167 1515 4167 1866 4168 1875 4168 2191 4168 2191 4169 1875 4169 2208 4169 2191 4170 2208 4170 2190 4170 2190 4171 2208 4171 2209 4171 2190 4172 2209 4172 2189 4172 2189 4173 2209 4173 2210 4173 2189 4174 2210 4174 1514 4174 1514 4175 2210 4175 1512 4175 2211 4176 2212 4176 2213 4176 2213 4177 2212 4177 2214 4177 2213 4178 2214 4178 2215 4178 1876 4179 1490 4179 2216 4179 2216 4180 1490 4180 2217 4180 2216 4181 2217 4181 2218 4181 1499 4182 2212 4182 1525 4182 1525 4183 2212 4183 2211 4183 1525 4184 2211 4184 1526 4184 2199 4185 2214 4185 2198 4185 2198 4186 2214 4186 2212 4186 2198 4187 2212 4187 2197 4187 2197 4188 2212 4188 1499 4188 2199 4189 2201 4189 2214 4189 2214 4190 2201 4190 2218 4190 2214 4191 2218 4191 2215 4191 2215 4192 2218 4192 2217 4192 1877 4193 1876 4193 2205 4193 2205 4194 1876 4194 2216 4194 2205 4195 2216 4195 2204 4195 2204 4196 2216 4196 2218 4196 2204 4197 2218 4197 2202 4197 2202 4198 2218 4198 2201 4198 1491 4199 1325 4199 2219 4199 2219 4200 1325 4200 2220 4200 2219 4201 2220 4201 2221 4201 2221 4202 2220 4202 2222 4202 2221 4203 2222 4203 2223 4203 2223 4204 2222 4204 2224 4204 2223 4205 2224 4205 2225 4205 2225 4206 2224 4206 2226 4206 2225 4207 2226 4207 1528 4207 1528 4208 2226 4208 1529 4208 1490 4209 1491 4209 2217 4209 2217 4210 1491 4210 2219 4210 2217 4211 2219 4211 2215 4211 2215 4212 2219 4212 2221 4212 2215 4213 2221 4213 2213 4213 2213 4214 2221 4214 2223 4214 2213 4215 2223 4215 2211 4215 2211 4216 2223 4216 2225 4216 2211 4217 2225 4217 1526 4217 1526 4218 2225 4218 1528 4218 1349 4219 1351 4219 2227 4219 2228 4220 2229 4220 2230 4220 2230 4221 2229 4221 2231 4221 2230 4222 2231 4222 1539 4222 1539 4223 2231 4223 1 4223 1353 4224 1355 4224 2232 4224 2232 4225 1355 4225 2233 4225 2232 4226 2233 4226 2234 4226 2234 4227 2233 4227 2235 4227 2234 4228 2235 4228 2228 4228 2228 4229 2235 4229 2236 4229 2228 4230 2236 4230 2229 4230 1351 4231 1353 4231 2227 4231 2227 4232 1353 4232 2232 4232 2227 4233 2232 4233 2237 4233 2237 4234 2232 4234 2234 4234 2237 4235 2234 4235 2238 4235 2238 4236 2234 4236 2228 4236 2238 4237 2228 4237 2239 4237 2239 4238 2228 4238 2230 4238 2239 4239 2230 4239 1540 4239 1540 4240 2230 4240 1539 4240 1347 4241 1349 4241 2240 4241 2240 4242 1349 4242 2227 4242 2240 4243 2227 4243 2241 4243 2241 4244 2227 4244 2237 4244 2241 4245 2237 4245 2242 4245 2242 4246 2237 4246 2238 4246 2242 4247 2238 4247 2243 4247 2243 4248 2238 4248 2239 4248 2243 4249 2239 4249 1541 4249 1541 4250 2239 4250 1540 4250 1346 4251 1347 4251 2244 4251 2244 4252 1347 4252 2240 4252 2244 4253 2240 4253 2245 4253 2245 4254 2240 4254 2241 4254 2245 4255 2241 4255 2246 4255 2246 4256 2241 4256 2242 4256 2246 4257 2242 4257 2247 4257 2247 4258 2242 4258 2243 4258 2247 4259 2243 4259 1543 4259 1543 4260 2243 4260 1541 4260 1543 4261 1544 4261 2247 4261 2247 4262 1544 4262 2248 4262 2247 4263 2248 4263 2246 4263 2246 4264 2248 4264 2249 4264 2246 4265 2249 4265 2245 4265 2245 4266 2249 4266 2250 4266 2245 4267 2250 4267 2244 4267 2244 4268 2250 4268 2251 4268 2244 4269 2251 4269 1346 4269 1340 4270 1341 4270 2251 4270 2251 4271 1341 4271 1344 4271 2251 4272 1344 4272 1346 4272 1546 4273 1547 4273 2252 4273 2252 4274 1547 4274 2253 4274 2252 4275 2253 4275 2254 4275 2254 4276 2253 4276 2255 4276 2254 4277 2255 4277 2256 4277 2256 4278 2255 4278 2257 4278 2256 4279 2257 4279 2258 4279 2258 4280 2257 4280 2259 4280 1547 4281 1549 4281 2253 4281 2253 4282 1549 4282 2260 4282 2253 4283 2260 4283 2255 4283 2255 4284 2260 4284 2261 4284 2255 4285 2261 4285 2257 4285 2257 4286 2261 4286 2262 4286 2257 4287 2262 4287 2259 4287 2259 4288 2262 4288 2263 4288 1544 4289 1546 4289 2248 4289 2248 4290 1546 4290 2252 4290 2248 4291 2252 4291 2249 4291 2249 4292 2252 4292 2254 4292 2249 4293 2254 4293 2250 4293 2250 4294 2254 4294 2256 4294 2250 4295 2256 4295 2251 4295 2251 4296 2256 4296 2258 4296 2251 4297 2258 4297 1340 4297 1340 4298 2258 4298 2259 4298 1340 4299 2259 4299 1338 4299 1338 4300 2259 4300 2263 4300 1332 4301 1334 4301 2263 4301 2263 4302 1334 4302 1336 4302 2263 4303 1336 4303 1338 4303 1552 4304 1551 4304 2264 4304 2264 4305 1551 4305 2265 4305 2264 4306 2265 4306 2266 4306 2266 4307 2265 4307 2267 4307 2266 4308 2267 4308 2268 4308 2268 4309 2267 4309 2269 4309 2268 4310 2269 4310 2270 4310 2270 4311 2269 4311 2271 4311 1549 4312 1552 4312 2260 4312 2260 4313 1552 4313 2264 4313 2260 4314 2264 4314 2261 4314 2261 4315 2264 4315 2266 4315 2261 4316 2266 4316 2262 4316 2262 4317 2266 4317 2268 4317 2262 4318 2268 4318 2263 4318 2263 4319 2268 4319 2270 4319 2263 4320 2270 4320 1332 4320 1332 4321 2270 4321 2271 4321 1332 4322 2271 4322 1321 4322 1321 4323 2271 4323 1322 4323 1551 4324 1550 4324 2265 4324 2265 4325 1550 4325 2272 4325 2265 4326 2272 4326 2267 4326 2267 4327 2272 4327 2273 4327 2267 4328 2273 4328 2269 4328 2269 4329 2273 4329 2274 4329 2269 4330 2274 4330 2271 4330 2271 4331 2274 4331 2275 4331 2271 4332 2275 4332 1322 4332 1322 4333 2275 4333 1324 4333 1327 4334 1324 4334 2276 4334 2276 4335 1324 4335 2275 4335 2276 4336 2275 4336 2277 4336 2277 4337 2275 4337 2274 4337 2277 4338 2274 4338 2278 4338 2278 4339 2274 4339 2273 4339 2278 4340 2273 4340 2279 4340 2279 4341 2273 4341 2272 4341 2279 4342 2272 4342 1530 4342 1530 4343 2272 4343 1550 4343 1325 4344 1327 4344 2220 4344 2220 4345 1327 4345 2276 4345 2220 4346 2276 4346 2222 4346 2222 4347 2276 4347 2277 4347 2222 4348 2277 4348 2224 4348 2224 4349 2277 4349 2278 4349 2224 4350 2278 4350 2226 4350 2226 4351 2278 4351 2279 4351 2226 4352 2279 4352 1529 4352 1529 4353 2279 4353 1530 4353 2 4354 1 4354 2280 4354 2280 4355 1 4355 2231 4355 2280 4356 2231 4356 2281 4356 2281 4357 2231 4357 2229 4357 2281 4358 2229 4358 2282 4358 2229 4359 2236 4359 2282 4359 2282 4360 2236 4360 2235 4360 2282 4361 2235 4361 2283 4361 2283 4362 2235 4362 2284 4362 2235 4363 2233 4363 2284 4363 2284 4364 2233 4364 1355 4364 2284 4365 1355 4365 1356 4365 3 4366 2 4366 2285 4366 2285 4367 2 4367 2280 4367 2285 4368 2280 4368 2286 4368 2286 4369 2280 4369 2281 4369 2286 4370 2281 4370 2287 4370 2287 4371 2281 4371 2282 4371 2287 4372 2282 4372 2288 4372 2288 4372 2282 4372 2283 4372 2288 4373 2283 4373 2289 4373 2289 4373 2283 4373 2284 4373 2289 4374 2284 4374 1283 4374 1283 4375 2284 4375 1356 4375 4 4376 3 4376 2290 4376 2290 4377 3 4377 2285 4377 2290 4378 2285 4378 2291 4378 2291 4379 2285 4379 2286 4379 2291 4380 2286 4380 2292 4380 2292 4381 2286 4381 2287 4381 2292 4382 2287 4382 2293 4382 2293 4383 2287 4383 2288 4383 2293 4384 2288 4384 2294 4384 2288 4385 2289 4385 2294 4385 2294 4386 2289 4386 1283 4386 2294 4387 1283 4387 1285 4387 2295 4388 1470 4388 1469 4388 2296 4389 2297 4389 2298 4389 2299 4390 2296 4390 2300 4390 2301 4391 1314 4391 2302 4391 2302 4392 1314 4392 1312 4392 2302 4393 1312 4393 2299 4393 2303 4394 1308 4394 2304 4394 2304 4395 1308 4395 1310 4395 2304 4396 1310 4396 2305 4396 2305 4397 1310 4397 1318 4397 2305 4398 1318 4398 2301 4398 2301 4399 1318 4399 1316 4399 2301 4400 1316 4400 1314 4400 2306 4401 1300 4401 2307 4401 2307 4402 1300 4402 1302 4402 2307 4403 1302 4403 2308 4403 2308 4404 1302 4404 1304 4404 2308 4405 1304 4405 2303 4405 2303 4406 1304 4406 1306 4406 2303 4407 1306 4407 1308 4407 2296 4408 2298 4408 2300 4408 2300 4409 2298 4409 2309 4409 2300 4410 2309 4410 2310 4410 2310 4411 2309 4411 2311 4411 2310 4412 2311 4412 2312 4412 2312 4413 2311 4413 2313 4413 2312 4414 2313 4414 2314 4414 2314 4415 2313 4415 2315 4415 2314 4416 2315 4416 2316 4416 2316 4417 2315 4417 2317 4417 2316 4418 2317 4418 2318 4418 2318 4419 2317 4419 2319 4419 2318 4420 2319 4420 2320 4420 2320 4421 2319 4421 2321 4421 2320 4422 2321 4422 2322 4422 2322 4423 2321 4423 2323 4423 2322 4424 2323 4424 2324 4424 2324 4425 2323 4425 2325 4425 2324 4426 2325 4426 2326 4426 2326 4427 2325 4427 2327 4427 2326 4428 2327 4428 2328 4428 2299 4429 2300 4429 2302 4429 2302 4430 2300 4430 2310 4430 2302 4431 2310 4431 2301 4431 2301 4432 2310 4432 2312 4432 2301 4433 2312 4433 2305 4433 2305 4434 2312 4434 2314 4434 2305 4435 2314 4435 2304 4435 2304 4436 2314 4436 2316 4436 2304 4437 2316 4437 2303 4437 2303 4438 2316 4438 2318 4438 2303 4439 2318 4439 2308 4439 2308 4440 2318 4440 2320 4440 2308 4441 2320 4441 2307 4441 2307 4442 2320 4442 2322 4442 2307 4443 2322 4443 2306 4443 2306 4444 2322 4444 2324 4444 2306 4445 2324 4445 2329 4445 2329 4446 2324 4446 2326 4446 2329 4447 2326 4447 2330 4447 2330 4448 2326 4448 2328 4448 2330 4449 2328 4449 2331 4449 1288 4450 1291 4450 2331 4450 2331 4451 1291 4451 1293 4451 2331 4452 1293 4452 2330 4452 2330 4453 1293 4453 1294 4453 2330 4454 1294 4454 2329 4454 2329 4455 1294 4455 1296 4455 2329 4456 1296 4456 2306 4456 2306 4457 1296 4457 1298 4457 2306 4458 1298 4458 1300 4458 2327 4459 2332 4459 2328 4459 2328 4460 2332 4460 2333 4460 2328 4461 2333 4461 2331 4461 2331 4462 2333 4462 2334 4462 2331 4463 2334 4463 1288 4463 1288 4464 2334 4464 1287 4464 2295 4465 1469 4465 2335 4465 2335 4466 1469 4466 1465 4466 2335 4467 1465 4467 2336 4467 2336 4468 1465 4468 1464 4468 2336 4469 1464 4469 2337 4469 2337 4470 1464 4470 1476 4470 2337 4471 1476 4471 2338 4471 2338 4472 1476 4472 1475 4472 2338 4473 1475 4473 2339 4473 2339 4474 1475 4474 1474 4474 2339 4475 1474 4475 2340 4475 2340 4476 1474 4476 1462 4476 2340 4477 1462 4477 2341 4477 2341 4478 1462 4478 1461 4478 2341 4479 1461 4479 2342 4479 2342 4480 1461 4480 1482 4480 2342 4481 1482 4481 2343 4481 2343 4482 1482 4482 1481 4482 2343 4483 1481 4483 2344 4483 2344 4484 1481 4484 1480 4484 2344 4485 1480 4485 2345 4485 2345 4486 1480 4486 1479 4486 2345 4487 1479 4487 2346 4487 2346 4488 1479 4488 4 4488 2346 4489 4 4489 2290 4489 2290 4490 2332 4490 2346 4490 2346 4491 2332 4491 2327 4491 2346 4492 2327 4492 2345 4492 2345 4493 2327 4493 2325 4493 2345 4494 2325 4494 2344 4494 2344 4495 2325 4495 2323 4495 2344 4496 2323 4496 2343 4496 2343 4497 2323 4497 2321 4497 2343 4498 2321 4498 2342 4498 2342 4499 2321 4499 2319 4499 2342 4500 2319 4500 2341 4500 2341 4501 2319 4501 2317 4501 2341 4502 2317 4502 2340 4502 2340 4503 2317 4503 2315 4503 2340 4504 2315 4504 2339 4504 2339 4505 2315 4505 2313 4505 2339 4506 2313 4506 2338 4506 2338 4507 2313 4507 2311 4507 2338 4508 2311 4508 2337 4508 2337 4509 2311 4509 2309 4509 2337 4510 2309 4510 2336 4510 2336 4511 2309 4511 2298 4511 2336 4512 2298 4512 2335 4512 2335 4513 2298 4513 2297 4513 2335 4514 2297 4514 2295 4514 1285 4515 1287 4515 2294 4515 2294 4516 1287 4516 2334 4516 2294 4517 2334 4517 2293 4517 2293 4518 2334 4518 2333 4518 2293 4519 2333 4519 2292 4519 2292 4520 2333 4520 2332 4520 2292 4521 2332 4521 2291 4521 2291 4522 2332 4522 2290 4522 1449 4523 1450 4523 2347 4523 2347 4524 1450 4524 2348 4524 2347 4525 2348 4525 2349 4525 2349 4526 2348 4526 2350 4526 2349 4527 2350 4527 2351 4527 2351 4528 2350 4528 2352 4528 2351 4529 2352 4529 2353 4529 2353 4530 2352 4530 2354 4530 2353 4531 2354 4531 1471 4531 1471 4532 2354 4532 1472 4532 1312 4533 1449 4533 2299 4533 2299 4534 1449 4534 2347 4534 2299 4535 2347 4535 2296 4535 2296 4536 2347 4536 2349 4536 2296 4537 2349 4537 2297 4537 2297 4538 2349 4538 2351 4538 2297 4539 2351 4539 2295 4539 2295 4540 2351 4540 2353 4540 2295 4541 2353 4541 1470 4541 1470 4542 2353 4542 1471 4542 2355 4543 1989 4543 1982 4543 1430 4544 1467 4544 2356 4544 2356 4545 1467 4545 2357 4545 2356 4546 2357 4546 2358 4546 2358 4547 2357 4547 2359 4547 2358 4548 2359 4548 2360 4548 2360 4549 2359 4549 2361 4549 2360 4550 2361 4550 2362 4550 2362 4551 2361 4551 2355 4551 2362 4552 2355 4552 2363 4552 2363 4553 2355 4553 1982 4553 1450 4554 1989 4554 2348 4554 2348 4555 1989 4555 2355 4555 2348 4556 2355 4556 2350 4556 2350 4557 2355 4557 2361 4557 2350 4558 2361 4558 2352 4558 2352 4559 2361 4559 2359 4559 2352 4560 2359 4560 2354 4560 2354 4561 2359 4561 2357 4561 2354 4562 2357 4562 1472 4562 1472 4563 2357 4563 1467 4563 2364 4564 2365 4564 2366 4564 2367 4565 2364 4565 2368 4565 1984 4566 2367 4566 2369 4566 1984 4567 2369 4567 1985 4567 1985 4568 2369 4568 2370 4568 1985 4569 2370 4569 1990 4569 2364 4570 2366 4570 2368 4570 2368 4571 2366 4571 2371 4571 2368 4572 2371 4572 2372 4572 2372 4573 2371 4573 2373 4573 2372 4574 2373 4574 2374 4574 2374 4575 2373 4575 2375 4575 2374 4576 2375 4576 2376 4576 2367 4577 2368 4577 2369 4577 2369 4578 2368 4578 2372 4578 2369 4579 2372 4579 2370 4579 2370 4580 2372 4580 2374 4580 2370 4581 2374 4581 2377 4581 2377 4582 2374 4582 2376 4582 2377 4583 2376 4583 2378 4583 1430 4584 2375 4584 1431 4584 1431 4585 2375 4585 2373 4585 1431 4586 2373 4586 1432 4586 1432 4587 2373 4587 2371 4587 1432 4588 2371 4588 1434 4588 1434 4589 2371 4589 2366 4589 1434 4590 2366 4590 1437 4590 1437 4591 2366 4591 2365 4591 1437 4592 2365 4592 1435 4592 1430 4593 2356 4593 2375 4593 2375 4594 2356 4594 2358 4594 2375 4595 2358 4595 2376 4595 2376 4596 2358 4596 2360 4596 2376 4597 2360 4597 2378 4597 2378 4598 2360 4598 2362 4598 2378 4599 2362 4599 2363 4599 1990 4600 2370 4600 1991 4600 1991 4601 2370 4601 2377 4601 1991 4602 2377 4602 1992 4602 1992 4603 2377 4603 2378 4603 1992 4604 2378 4604 1979 4604 1979 4605 2378 4605 2363 4605 1979 4606 2363 4606 1982 4606 1987 4607 2367 4607 1988 4607 1988 4608 2367 4608 1984 4608 2365 4609 2021 4609 2023 4609 2023 4610 2025 4610 2365 4610 2365 4611 2025 4611 2027 4611 2365 4612 2027 4612 1435 4612 1986 4613 2379 4613 1987 4613 1987 4614 2379 4614 2364 4614 1987 4615 2364 4615 2367 4615 2365 4616 2364 4616 2021 4616 2021 4617 2364 4617 2379 4617 2021 4618 2379 4618 2020 4618 2020 4619 2379 4619 1986 4619

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
diff --git a/URDFs/sr_description/meshes/components/th_distal/pst/th_distal_pst_scaled.dae b/URDFs/sr_description/meshes/components/th_distal/pst/th_distal_pst_scaled.dae new file mode 100644 index 0000000..277c589 --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_distal/pst/th_distal_pst_scaled.dae @@ -0,0 +1,210 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T11:11:51 + 2025-02-20T11:11:51 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -2.55768 9 19.17331 -2.506939 9 19.86789 -2.034731 9 19.8462 2.034731 9 19.8462 2.506939 9 19.86789 2.557679 9 19.17331 -3.073899 9 10.60533 3.073899 9 10.60534 3.353007 9 3.341558 -3.353007 9 3.341558 5.05 5.8 9.00833 5.05 5.2 9.464127 5.05 5.8 9.482215 5.05 5.2 9.482215 -5.05 5.2 9.464127 -5.05 5.8 9.00833 -5.05 5.2 9.482215 -5.05 5.8 9.482215 7.68301 7.569204 5.82024 7.978376 7.347282 5.685114 7.978376 7.316722 5.745363 6.241808 5.130235 9.482215 6.633532 5.886308 8.801447 6.446928 5.070229 9.482215 6.616663 5 9.482215 7.978376 5 8.52235 7.867467 5 8.654623 7.357062 5.690253 8.574787 7.504492 5 9.002189 7.368324 5 9.105569 6.955405 5 9.34893 6.848075 8.095847 5.768563 7.211372 7.884189 5.852874 7.357062 7.741002 5.962769 7.532063 7.67517 5.851119 6.204217 8.410559 5.417622 6.492428 8.278827 5.606901 6.633532 8.007718 6.099435 5.85709 8.539525 5.14048 5.85709 8.550559 5.110346 5.85709 8.098689 6.146049 5.85709 7.723468 6.808475 6.633532 7.418167 7.088432 5.85709 7.502441 7.146282 5.85709 6.783347 8.062186 6.633532 6.707151 7.994046 5.85709 6.585812 8.276091 5.85709 5.953179 8.87876 5.85709 5.173926 9.482215 7.357062 7.171091 6.918825 7.357062 6.483756 7.794275 7.978376 6.778047 6.649018 7.978376 6.128385 7.476485 7.978376 5.378374 8.214218 -7.121905 5 9.262448 -7.348607 5 9.119501 -7.357062 5.690253 8.574787 -7.735837 5 8.794322 -7.978376 5 8.52235 -7.978376 5.378374 8.214218 -7.708118 7.551095 5.812904 -7.501179 7.696242 5.854852 -7.357062 7.741002 5.962769 -5.85709 8.550559 5.110346 -5.85709 8.539525 5.14048 -5.973025 8.506012 5.22373 -5.85709 8.098689 6.146049 -6.338462 8.350994 5.512583 -6.611372 8.2202 5.669566 -6.633532 8.007718 6.099435 -6.984966 8.01912 5.810189 -7.165114 7.912586 5.846904 -7.05513 5 9.298909 -6.633532 5.886308 8.801447 -6.040488 5.164052 9.482215 -6.246764 5.129094 9.482215 -6.616663 5 9.482215 -5.85709 5.173926 9.482215 -5.85709 5.953179 8.87876 -5.85709 6.585812 8.276091 -6.633532 6.707151 7.994046 -5.85709 6.783347 8.062186 -5.85709 7.502441 7.146282 -6.633532 7.418167 7.088432 -5.85709 7.723468 6.808475 -7.357062 6.483756 7.794275 -7.357062 7.171091 6.918825 -7.978376 7.347282 5.685114 -7.978376 7.316722 5.745363 -7.978376 6.778047 6.649018 -7.978376 6.128385 7.476485 5.672272 8.616907 4.921764 5.076074 5.173926 9.482215 -5.076074 5.173926 9.482215 -4.537463 8.903451 3.877302 -4.17373 8.954113 3.619111 -4.132569 8.925611 3.769185 -3.801269 8.986454 3.429257 -4.912132 8.830914 4.192778 -5.185234 8.764595 4.444037 4.186992 8.952603 3.627434 4.426061 8.921009 3.792208 4.978883 8.815769 4.252799 -3.49215 8.998706 3.350188 3.799371 8.98657 3.428534 3.669031 8.993291 3.385696 -7.106018 -6.954698 9.556375 -6.88518 -6.648028 9.482217 -6.88518 -7.001696 9.546849 -7.054211 -7.458154 9.920859 -7.199854 -7.509562 10.0838 -7.193972 -7.340364 9.830055 -7.458285 -7.467149 10.50655 -7.46886 -7.458564 10.53069 -7.469547 -7.459518 10.48222 -7.447194 -7.475156 10.48222 -6.88518 -7.355135 9.775113 -7.200583 -7.086017 9.640382 -7.130944 -6.989312 9.574954 -7.217886 -7.513106 10.10679 -7.436282 -7.413323 10.14963 -7.347941 -7.290649 9.871569 -7.308287 -7.235582 9.792466 -10.5836 -1.379343 10.48222 -10.58248 -1.379329 10.52961 -10.58249 2 10.52961 -10.53348 -1.379603 10.16967 -10.53555 2 10.17588 -10.52803 2 10.15347 -10.39054 -1.379686 9.891619 -10.30729 2 9.792065 -9.900835 -1.37949 9.533879 -9.961278 -1.379525 9.556289 -9.956752 2 9.554443 -10.17173 -1.379633 9.673468 -10.30726 -1.379678 9.792084 -9.934726 2 9.54588 -9.692791 2 9.488194 -9.583624 -1.3793 9.482217 -9.583624 2 9.482216 6.885144 -7.355135 9.775113 6.885144 -6.648028 9.482217 6.885144 -7.001696 9.546849 6.885144 -7.030712 9.558341 -9.160588 2 28.54651 -9.313948 2 27.90424 -9.258036 1.656066 28.16862 -9.395987 1.656715 27.37881 -9.417465 2 27.17663 -9.417478 1.656942 27.17664 -9.16056 1.656222 28.5465 -9.022456 1.656711 28.97954 -8.648488 2 29.85749 -8.693047 1.656344 29.76741 -8.553047 2 30.04075 -8.287236 1.655893 30.49537 -7.797624 2 31.18073 -7.797616 1.656829 31.18075 -10.40618 -1.188569 13.91877 -10.29674 2 15.76996 -10.52827 -1.340123 11.63759 -9.602179 0.9842647 25.11952 -9.864404 2 21.94757 -9.786969 0.3629639 22.9196 -10.27052 -0.9419808 16.1917 -10.12176 -0.6008241 18.45211 -9.960351 -0.1655673 20.69622 -7.912967 -7.112607 10.53219 -7.911905 -5.728467 9.482217 -7.351424 -6.278915 9.482217 -7.738455 -6.440464 9.556556 -9.917541 -2.158388 9.556494 -8.306257 -5.853429 9.556689 -8.803075 -5.199226 9.556764 -8.407798 -5.105961 9.482217 -9.215053 -4.4964 9.556786 -8.820544 -4.433646 9.482217 -9.541989 -3.746457 9.55675 -9.147786 -3.718481 9.482217 -9.777846 -2.96069 9.556653 -9.38861 -2.959123 9.482217 -9.534358 -2.178216 9.482217 -10.26165 -2.197639 9.792987 -10.47915 -2.222449 10.1507 -10.55018 -2.073874 10.53106 -10.32804 -3.090766 10.15212 -10.43767 -2.844624 10.53347 -10.07282 -3.94121 10.153 -10.22742 -3.657884 10.53491 -9.944076 -4.405148 10.53557 -9.718993 -4.752888 10.15333 -9.767293 -4.777473 10.53569 -8.540572 -6.519673 10.53404 -9.099351 -5.853726 10.53522 -9.273097 -5.513559 10.15314 -9.318212 -5.543732 10.5355 -9.566395 -5.146238 10.53567 -7.972777 -6.695666 9.793265 -8.735358 -6.22158 10.15244 -8.120793 -6.856869 10.15127 -10.11516 -3.040438 9.793684 -9.867554 -3.865903 9.794114 -9.524168 -4.65373 9.794277 -9.091363 -5.392024 9.794182 -8.56937 -6.079169 9.79384 -6.30984 -8.024703 10.59801 -3.033238 -8.828372 11.66256 -3.033239 -8.827216 11.71067 -3.771698 -8.792226 11.68439 -3.033237 -8.535478 10.95545 -3.033238 -8.762089 11.30455 -3.494747 -8.519931 10.9399 -3.616479 -8.739423 11.2823 -6.182973 -7.95259 10.41036 -5.815475 -8.238404 10.80311 -5.295314 -8.420115 10.97738 -4.188136 -8.674198 11.22043 -6.052469 -7.837882 10.25786 -5.791827 -7.958481 10.37846 -5.119175 -8.211537 10.63151 -5.208354 -8.334948 10.78881 -4.720036 -8.325232 10.74521 -4.748785 -8.567213 11.11825 -4.6156 -8.350763 10.77074 -4.098651 -8.452216 10.87219 -3.571331 -8.514329 10.9343 -6.534756 -8.006139 11.0077 -6.422164 -8.046298 10.8064 -5.911201 -8.269398 11.01069 -5.373402 -8.459156 11.18414 -4.261643 -8.730285 11.63274 -4.413202 -8.704799 11.61118 -5.112824 -8.547124 11.47631 -5.437254 -8.450909 11.39338 -6.280738 -8.126558 11.11236 -6.511402 -8.017681 11.01773 -2.17205e-5 2.00001 34.91994 0.3378735 1.999481 34.91412 1.091697 2 34.86021 1.310069 1.99182 34.83379 1.479404 2 34.80994 1.479413 1.989527 34.80992 2.261628 1.975331 34.66074 2.433008 2 34.61948 3.183818 1.950937 34.39958 3.406322 2 34.32193 3.406348 1.943696 34.32192 4.048466 1.91962 34.06375 4.607707 2 33.79516 4.927083 1.878642 33.62186 5.19865 2 33.46245 5.19868 1.863879 33.46242 5.572008 2 33.22374 5.735637 1.831469 33.11156 6.438046 2 32.57186 6.475824 1.779177 32.53986 7.797581 1.656828 31.18075 7.797611 2 31.18073 7.155231 1.721859 31.90586 7.199889 2 31.85981 6.785571 2 32.26543 -5.522164 1.844729 33.25699 -5.198719 1.863726 33.46242 -5.198687 2 33.46245 -1.144362 2 34.85428 -0.9806863 1.995507 34.87175 -1.954542 1.981722 34.72701 -3.406358 2 34.32193 -2.905493 1.959385 34.48852 -2.322046 2 34.64665 -1.479441 2 34.80994 -4.510229 2 33.84511 -4.705033 1.889841 33.74389 -3.846803 1.927776 34.15044 -3.406394 1.94383 34.32192 -6.330498 1.790086 32.66104 -6.359302 2 32.63745 -6.785634 1.754243 32.26539 -6.785606 2 32.26543 -7.083637 1.728368 31.97848 -7.13129 2 31.93032 -7.70561 1.666911 31.29364 -6.877346 -3.194216 29.38893 -7.150277 -3.263176 28.71989 -6.81631 -3.269918 29.36431 -7.083803 -2.97816 29.38412 -7.012401 -3.046917 29.39892 -7.156011 -2.914408 29.35643 -6.943125 -3.119412 29.40054 -7.36389 -2.764672 29.20231 -7.297445 -2.806602 29.26463 -7.42578 -2.731842 29.13055 -7.227703 -2.856837 29.31634 -7.5544 -2.693152 28.9164 -7.509111 -2.700562 29.00548 -7.591505 -2.69619 28.82335 -7.469376 -2.713241 29.07004 -7.572875 0.6759643 31.34976 -7.632837 0.8962656 31.31942 -7.648231 0.2430316 31.15149 -7.638504 -2.733228 28.63243 -7.722838 -2.658569 28.55742 -7.619729 -2.709633 28.72807 -3.008065 -5.027839 29.71681 -3.652929 -4.683132 30.11174 -3.332398 -5.092888 29.44787 -6.600644 -1.875374 31.19039 -6.321682 -2.144001 31.24819 -6.454369 -1.847523 31.3508 -6.29345 -2.097362 31.3106 -6.436793 -3.230548 29.98179 -6.327087 -3.380107 29.90783 -5.394058 -3.244716 30.99721 -5.340269 -3.308763 30.96783 -5.332416 -3.310965 30.97132 -2.354365 -5.289077 29.28506 -2.796555 -5.337832 29.05536 -1.949515 -5.408039 29.00242 -4.449693 -4.927847 29.0619 -3.637283 -5.176255 29.07533 -3.353329 -5.241329 29.0723 -5.951442 -4.19221 28.93905 -5.224036 -4.597813 29.01603 -4.72482 -4.713399 29.30765 -4.739261 -4.815708 29.04875 -6.623913 -3.717874 28.83267 -6.603669 -3.704578 28.90222 -6.013502 -4.095801 29.06192 -8.451063 -1.555357 28.3982 -8.633193 -1.305163 28.15947 -8.218848 -2.002728 28.36966 -9.0206 -0.2574171 28.09246 -8.962263 -0.5753174 27.92988 -9.325829 1.112076 27.72664 -9.355916 0.9428762 27.42537 -9.203601 0.1772285 27.68408 -9.204051 1.265125 28.34701 -9.020977 1.352325 28.96507 -8.780303 1.372031 29.56857 -7.946017 1.12107 30.95766 -8.228796 1.241722 30.56519 -8.486536 1.323967 30.14643 -7.999587 0.4294109 30.74412 -7.042795 -0.8525317 31.38515 -7.02826 -0.7863298 31.43348 -7.378572 -0.6106734 31.13618 -7.046717 -0.746379 31.43407 -7.16517 -0.4781825 31.43362 -7.375931 0.06180047 31.41045 -7.698473 -0.4088028 30.83613 -6.88275 -1.626304 31.08221 -6.774306 -1.294423 31.41061 -7.162839 -1.401381 30.92557 -6.959513 -0.931214 31.42991 -6.651542 -1.516558 31.39119 -8.24708 0.5350082 30.40062 -8.472661 0.6069912 30.03411 -8.729771 0.6490578 29.52836 -8.940418 0.6318106 29.00016 -9.100648 0.5554913 28.45922 -9.20723 0.4215397 27.91626 -8.930212 -0.1438181 28.55292 -8.794324 -0.07909464 29.01167 -8.615685 -0.06446796 29.45961 -8.397641 -0.100143 29.88853 -8.206336 -0.1611889 30.19935 -7.996445 -0.2507418 30.49066 -8.767786 -0.9184575 28.25362 -8.694438 -0.8262742 28.62727 -8.58417 -0.7737524 28.99954 -8.439208 -0.7618831 29.36304 -8.262269 -0.7908328 29.71109 -8.107028 -0.8403702 29.96332 -7.936706 -0.9130406 30.19971 -7.694908 -1.041304 30.48005 -7.435315 -1.205118 30.72354 -5.452261 -3.180903 31.02121 -5.979846 -2.540524 31.21667 -6.558295 -3.079853 30.03079 -6.060556 -2.43149 31.24263 -6.689237 -2.930945 30.0539 -6.596156 -2.484699 30.66901 -6.82714 -2.786635 30.05068 -6.807695 -2.280996 30.62518 -6.969277 -2.649763 30.02123 -7.021619 -2.092124 30.54315 -7.113016 -2.522856 29.96611 -7.234013 -1.921563 30.42436 -7.255728 -2.408253 29.88629 -7.440635 -1.772734 30.27116 -7.394561 -2.308252 29.78335 -7.637486 -1.648513 30.08652 -7.526829 -2.224786 29.65929 -7.820844 -1.551249 29.87394 -7.65003 -2.159432 29.51645 -7.949999 -1.496143 29.69468 -7.736813 -2.122405 29.396 -8.067723 -1.458578 29.50341 -7.815911 -2.097165 29.26749 -8.201896 -1.436625 29.23948 -7.906066 -2.082414 29.09015 -8.311821 -1.445626 28.96384 -7.979928 -2.088462 28.90494 -8.395442 -1.485453 28.68154 -8.036113 -2.115223 28.71526 -8.073487 -2.162193 28.52487 -6.761199 -3.345049 29.32716 -4.883226 -3.75529 30.76896 -5.061544 -3.586657 30.85205 -5.00537 -3.84761 30.56089 -5.158531 -3.584283 30.78419 -6.156449 -3.654662 29.70048 -6.234488 -3.520491 29.81426 -6.675478 -3.482972 29.223 -6.714682 -3.415571 29.28015 -4.280731 -4.257673 30.4642 -4.789827 -4.33524 29.98893 -4.879555 -4.102948 30.29153 -6.046625 -3.90312 29.40905 -6.092343 -3.784762 29.56324 -6.620309 -3.607785 29.0766 -6.643275 -3.548328 29.15405 -4.73792 -4.54003 29.65886 -6.020177 -4.007465 29.24088 -6.607023 -3.660203 28.99211 3.033206 -8.535478 10.95545 6.352292 -7.681999 10.10197 6.052434 -7.837882 10.25786 5.309673 -8.147953 10.56792 5.119142 -8.211534 10.63151 3.571299 -8.514328 10.9343 4.197907 -8.435893 10.85587 7.469511 -7.459518 10.48222 7.468824 -7.458564 10.53069 7.45825 -7.467149 10.50655 7.447158 -7.475156 10.48222 7.360106 -7.512365 10.31689 7.436246 -7.413323 10.14963 7.199819 -7.509562 10.0838 7.347906 -7.290649 9.87157 7.193936 -7.340364 9.830055 7.308252 -7.235582 9.792466 7.200547 -7.086017 9.640382 7.054175 -7.458154 9.920859 7.130909 -6.989313 9.574954 7.105982 -6.954698 9.556375 10.39322 -1.379314 9.895267 10.3039 -1.379311 9.788567 10.3039 2 9.788563 9.896735 -1.379302 9.532511 9.583589 -1.379296 9.482217 9.58557 2 9.482217 9.970495 2 9.560095 9.961281 -1.379303 9.556286 10.17496 -1.379308 9.675816 10.53297 -1.37932 10.16809 10.51964 2 10.13035 10.58319 -1.379326 10.45395 10.58247 2 10.52961 10.58247 -1.379327 10.52961 9.417445 1.656942 27.17664 9.417464 2 27.17663 9.291403 1.65692 28.01645 9.350973 2 27.69619 9.071129 1.656898 28.83693 9.165469 2 28.52923 8.759478 1.656876 29.62725 7.888356 2 31.06541 7.906359 1.656833 31.04197 8.239067 2 30.5705 8.360447 1.656854 30.37725 8.556951 2 30.03342 8.556951 1.656864 30.03342 8.674302 2 29.80564 8.91058 2 29.27655 -2.879983 -8.586277 14.92127 -2.865007 -8.555845 15.21253 -3.520568 -8.543681 15.06146 -2.651017 -8.020078 19.04886 -2.598519 -7.864452 19.91258 -3.200177 -7.853817 19.84025 -2.389026 -7.169461 23.1273 -2.294083 -6.820556 24.48295 -2.824102 -6.784357 24.54407 -2.737164 -8.25639 17.57065 -2.981564 -8.761816 12.84519 -3.658508 -8.744565 12.65362 -4.351964 -8.647518 12.68414 -5.053599 -8.480452 12.71066 -5.753179 -8.240034 12.73243 -6.439465 -7.924884 12.74875 -7.100693 -7.535929 12.75907 -7.725162 -7.076535 12.76299 -8.30187 -6.552497 12.76028 -8.82113 -5.971824 12.75094 -9.275117 -5.344333 12.73519 -9.65824 -4.681107 12.71343 -9.96735 -3.993871 12.68622 -10.20174 -3.294353 12.65429 -10.36297 -2.593711 12.61842 -10.45454 -1.902061 12.57944 -9.551722 0.4343613 25.41033 -9.444695 -0.2270982 25.60858 -9.267971 -0.8971564 25.80344 -5.409749 -5.325562 26.85644 -6.078209 -4.953586 26.79805 -6.711595 -4.514244 26.71546 -7.298798 -4.013081 26.60943 -7.829977 -3.457754 26.48152 -8.297101 -2.857653 26.33396 -8.694337 -2.223378 26.16958 -9.018284 -1.56614 25.99159 -4.014611 -5.85688 26.9014 -4.717964 -5.626953 26.89064 -2.127617 -6.164845 26.73724 -2.616876 -6.109461 26.85866 -3.310871 -6.01665 26.89011 -10.05371 -1.112473 19.06902 -10.19921 -1.460651 16.91775 -9.955696 -1.793899 19.18876 -10.10364 -2.146582 17.01076 -9.788007 -2.484182 19.30525 -9.938411 -2.841429 17.10057 -9.547247 -3.173358 19.41641 -9.700075 -3.535161 17.1855 -9.231966 -3.850435 19.52008 -9.38714 -4.216714 17.26386 -8.842974 -4.503856 19.61417 -9.000384 -4.874455 17.33402 -8.383536 -5.12207 19.69677 -8.543022 -5.496756 17.3945 -7.859333 -5.694159 19.76625 -8.020705 -6.072628 17.44408 -7.278282 -6.210449 19.82137 -7.441311 -6.592331 17.48186 -6.650132 -6.663053 19.86134 -6.814569 -7.047926 17.50731 -5.985927 -7.046257 19.88589 -6.151507 -7.433664 17.52032 -5.297391 -7.356745 19.89521 -5.463837 -7.746205 17.52116 -4.596282 -7.593612 19.88998 -4.76332 -7.984638 17.51046 -3.893813 -7.758205 19.87121 -4.061182 -8.150321 17.48914 -3.367626 -8.246563 17.45832 -10.33296 -1.724017 14.75337 -10.23954 -2.413358 14.81945 -10.07647 -3.111661 14.88237 -9.840253 -3.808844 14.94088 -9.529378 -4.493786 14.99374 -9.144581 -5.154798 15.03977 -8.689042 -5.780195 15.07796 -8.168374 -6.358931 15.10748 -7.59043 -6.881219 15.12777 -6.964918 -7.33908 15.13859 -6.302848 -7.726737 15.13997 -5.61593 -8.040832 15.13225 -4.915924 -8.280451 15.11604 -4.214063 -8.446956 15.09213 -9.729389 -0.1641849 23.3186 -9.896914 -0.6800696 21.20373 -9.625628 -0.8333621 23.491 -9.796164 -1.355906 21.34995 -9.452182 -1.511238 23.66006 -9.625737 -2.040529 21.49287 -9.205738 -2.188027 23.82287 -9.382268 -2.724053 21.63 -8.884933 -2.852933 23.97639 -9.064358 -3.395576 21.75873 -8.490692 -3.494609 24.11763 -8.672869 -4.043638 21.87653 -8.026359 -4.101711 24.2438 -8.211105 -4.656782 21.98104 -7.497715 -4.663517 24.35248 -7.684788 -5.224179 22.07024 -6.91275 -5.170528 24.44176 -7.101877 -5.736236 22.14253 -6.281269 -5.614995 24.51032 -6.472144 -6.185126 22.19688 -5.61436 -5.991312 24.55757 -5.806656 -6.565188 22.23285 -4.923761 -6.296219 24.58359 -5.117141 -6.87313 22.25057 -4.22123 -6.528829 24.58909 -4.415359 -7.108055 22.25073 -3.517959 -6.690464 24.57535 -3.712513 -7.271297 22.23449 -3.018776 -7.366126 22.20337 -2.451235 -7.387192 22.20736 3.033205 -8.827215 11.71067 3.033206 -8.828372 11.66256 3.033207 -8.76209 11.30455 2.31846 -3.611168 32.10023 2.575486 -3.15852 32.4992 1.85084 -3.043654 32.78527 1.794118 -1.012842 34.12355 1.688295 -1.582341 33.86145 2.294321 -1.649486 33.69707 7.043745 -0.752737 31.43402 7.165125 -0.4781855 31.43365 6.738008 -0.2871063 31.93244 0.4985891 -4.580484 31.00749 -4.01732e-5 -4.699768 30.7909 -3.67423e-5 -5.016016 30.07055 0.5922886 -4.243161 31.55832 -4.27969e-5 -4.260136 31.55042 0.8607771 -2.951064 33.01391 -4.42571e-5 -3.142212 32.87957 0.774465 -3.423855 32.56763 -4.41457e-5 -3.737757 32.24987 1.018233 -1.915632 33.76278 -4.1009e-5 -1.769364 33.90387 -4.31885e-5 -2.482814 33.43276 1.297613 0.8387494 34.74554 0.625415 0.8672999 34.81442 -2.29287e-5 1.418356 34.89725 2.788079 0.7013851 34.41259 2.051999 0.7822508 34.60893 2.948326 1.916167 34.47528 4.098738 1.737325 34.03895 4.831561 1.586928 33.66861 7.365623 0.03317159 31.41243 7.572845 0.6759563 31.34978 7.121938 0.8766542 31.87271 7.618001 0.8399161 31.32762 5.521491 1.415657 33.24284 6.590648 1.081631 32.39942 6.212536 -1.416263 31.84749 6.656497 -1.507726 31.39213 5.899229 -1.956638 31.74906 6.208847 -2.222107 31.28728 5.555028 -2.473695 31.61339 5.708537 -2.884302 31.12158 3.474998 -3.366116 31.9751 3.742851 -3.995411 31.11555 4.153999 -3.582976 31.4172 4.566946 -4.031285 30.61348 5.158396 -3.490745 30.89584 2.428715 -4.957456 30.02217 1.619667 -5.2684 29.39012 2.623418 -5.19199 29.46651 1.94948 -5.40804 29.00241 1.240757 -5.156824 29.69404 2.025967 -4.826733 30.36922 2.400837 -4.533337 30.81574 2.024133 -2.551863 33.16144 1.489273 -2.492377 33.30792 1.361625 -2.989115 32.92017 0.9415468 -2.45086 33.40973 2.054818 -4.016922 31.66917 1.665656 -3.507411 32.3601 1.475705 -3.92461 31.90204 0.6859313 -3.850357 32.08782 1.073759 -4.634933 30.86803 1.274793 -4.307533 31.39564 1.496938 -4.702882 30.69268 1.775963 -4.387691 31.19147 3.291272 -4.887399 29.8942 3.941898 -4.498836 30.27816 2.875053 -4.686484 30.41376 3.32112 -4.359729 30.78482 2.77548 -4.184265 31.24145 3.129683 -3.798938 31.62358 2.437985 -1.084027 33.94974 3.191014 -1.790719 33.34892 3.390412 -1.233704 33.58172 3.762922 -1.909678 33.05299 3.997668 -1.359726 33.26903 4.301961 -2.045355 32.71234 4.569853 -1.503403 32.90919 5.138619 -2.31057 32.03631 5.457584 -1.784094 32.19541 2.816007 -2.677077 32.85099 3.038278 -3.255424 32.25573 3.321437 -2.782637 32.58692 3.798139 -2.903136 32.28272 4.538745 -3.138979 31.67842 1.067478 -1.535457 33.97574 1.134438 -0.963128 34.24442 1.195388 -0.3728415 34.46282 0.3830698 -5.028531 30.03739 0.821636 -5.07551 29.9124 -2.67607e-5 0.8758923 34.83512 -2.86549e-5 0.5923631 34.78657 1.890444 -0.4251126 34.33601 2.568755 -0.4999462 34.1537 3.876324 0.5314713 33.9971 3.571913 -0.6572522 33.76777 4.569719 0.3885315 33.64433 4.211345 -0.7896532 33.43994 5.222677 0.225699 33.23865 4.813701 -0.940554 33.0628 6.234866 -0.0920313 32.4347 5.74792 -1.235217 32.31496 -3.36474e-5 -0.2212834 34.58338 -3.77986e-5 -1.012043 34.28848 1.610467 -1.960424 33.65335 2.188663 -2.024583 33.49596 3.044367 -2.159569 33.16249 3.590279 -2.273305 32.87898 4.104941 -2.403066 32.55253 4.904038 -2.656831 31.90445 -1.777025 -1.976788 33.61328 -1.19333 -1.926719 33.73573 -1.251031 -1.547055 33.94749 -0.5541928 -2.432993 33.45346 -0.5066367 -2.934691 33.05416 -0.8039745 -3.857902 32.06901 -0.694254 -4.249697 31.54186 -0.5844669 -4.586008 30.99338 -0.4432862 -5.033125 30.0252 -1.876936 -5.372792 29.10108 -2.617072 -5.032772 29.81945 -3.096342 -4.774475 30.17942 -3.575321 -4.460332 30.51902 -4.02817 -4.107887 30.82014 -4.469653 -3.706971 31.09309 -4.882788 -3.273698 31.3276 -5.275032 -2.801674 31.52844 -5.526926 -2.461873 31.64422 -5.869424 -1.944136 31.78159 -6.181183 -1.403147 31.88155 -6.704056 -0.2729778 31.96903 -7.086087 0.8914972 31.91108 -5.292947 1.475862 33.39299 -4.61265 1.635079 33.78751 -3.902508 1.772598 34.12533 -0.7638393 0.8630836 34.80423 -1.103478 -2.461136 33.38456 -1.00884 -2.960481 32.99074 -0.907709 -3.432349 32.54661 -5.093879 -2.294404 32.0779 -5.410122 -1.76699 32.23931 -1.554052 -5.245959 29.45165 -2.179455 -4.872264 30.24901 -2.581717 -4.586743 30.67639 -2.983734 -4.245508 31.08305 -3.363819 -3.867559 31.44726 -3.734366 -3.441896 31.7814 -4.081119 -2.985583 32.07284 -4.410338 -2.491808 32.32739 -4.621757 -2.138113 32.47746 -3.934381 -2.357429 32.66771 -3.592025 -1.871573 33.14805 -4.12334 -1.997637 32.83253 -4.380266 -1.452877 33.03613 -4.909224 -1.601597 32.66114 -5.170889 -1.043656 32.80287 -5.69798 -1.217267 32.36095 -5.609748 0.1144917 32.95915 -6.180771 -0.07268464 32.48413 -5.930395 1.298722 32.94958 -6.533516 1.101963 32.45126 -1.231317 -5.154537 29.70021 -1.687239 -4.742026 30.591 -2.000968 -4.433786 31.07323 -2.314507 -4.069936 31.53446 -2.610941 -3.670698 31.95002 -2.899935 -3.224374 32.33396 -3.170373 -2.74882 32.67176 -3.427136 -2.236876 32.97005 -2.898311 -2.132929 33.22855 -3.037981 -1.762843 33.41788 -3.816224 -1.319364 33.36946 -4.614131 -0.8874942 33.19583 -5.006366 0.2829445 33.38172 -0.8235594 -5.075955 29.91121 -1.151156 -4.64549 30.84088 -1.366524 -4.319999 31.364 -1.581761 -3.938976 31.86593 -1.785255 -3.523567 32.31978 -1.983643 -3.061546 32.74087 -2.169291 -2.571373 33.11325 -1.862878 -1.599461 33.8196 -1.979611 -1.030994 34.07929 -2.612652 -1.107356 33.89259 -2.752745 -0.5244686 34.09376 -3.400754 -0.6262144 33.8442 -2.987706 0.6748908 34.34804 -3.690678 0.5649891 34.07936 -3.159378 1.888275 34.40748 -4.362573 0.4343 33.7576 -4.0203 -0.7472522 33.54522 -3.22789 -1.204167 33.65462 -2.458745 -1.671495 33.64302 -2.345552 -2.045621 33.44418 -0.6677647 -0.9417198 34.29635 -0.7036513 -0.3503307 34.51731 -1.400903 -0.3857747 34.43147 -1.520678 0.8247688 34.71176 -0.6283397 -1.515269 34.02484 -1.329488 -0.9754278 34.21454 -2.085868 -0.4441968 34.28959 -2.264078 0.7616257 34.55893 -0.5993441 -1.896353 33.80979 6.701805 -7.920675 10.93335 3.616448 -8.739423 11.2823 4.188104 -8.674198 11.22043 4.748752 -8.567213 11.11825 4.857251 -8.612473 11.53242 3.653756 -8.802501 11.69272 3.711912 -8.797657 11.68881 4.317331 -8.721266 11.62512 5.208321 -8.334947 10.78881 6.182938 -7.95259 10.41036 5.815441 -8.238403 10.80311 5.295281 -8.420115 10.97738 5.911168 -8.269398 11.01069 5.373368 -8.459156 11.18414 6.309806 -8.024703 10.59801 6.42213 -8.046298 10.8064 6.511368 -8.017681 11.01773 5.546541 -8.415043 11.3624 7.734836 -6.443743 9.556555 10.47504 -2.259052 10.15073 10.25766 -2.233168 9.793004 9.913732 -2.19221 9.556497 7.479135 -6.164861 9.482217 7.968976 -6.699109 9.793259 8.116877 -6.860417 10.15126 8.154095 -6.901007 10.53289 10.10802 -3.070281 9.793703 9.77104 -2.989098 9.556655 9.858592 -3.89012 9.79412 9.533452 -3.76951 9.556753 9.514845 -4.671916 9.794278 9.206175 -4.513711 9.556786 9.082775 -5.404781 9.794178 8.794898 -5.211371 9.556763 8.562622 -6.086975 9.793834 8.29983 -5.860861 9.556688 10.32068 -3.121512 10.15216 10.06358 -3.966161 10.15301 9.709385 -4.771625 10.15333 9.264245 -5.526704 10.15313 8.728404 -6.229623 10.15243 8.769777 -6.265221 10.53447 9.309306 -5.556976 10.53542 9.757618 -4.796346 10.53569 10.11453 -3.985058 10.53526 10.37385 -3.134321 10.53411 10.52994 -2.265587 10.53217 9.538176 -2.147484 9.482217 8.012791 -5.613881 9.482217 8.480422 -5.00009 9.482217 8.868971 -4.340883 9.482217 9.178276 -3.637757 9.482217 9.402976 -2.900427 9.482217 10.46714 -1.274046 12.81188 10.3585 2 14.74413 10.33815 -1.073791 15.08719 10.09342 2 18.85967 10.04066 -0.3897973 19.60281 10.19586 -0.7789396 17.35185 9.504095 1.335335 26.22749 9.694086 0.6682382 24.04456 9.873218 0.09276801 21.8346 6.832487 -3.44487 29.0105 6.329647 -3.230569 30.11504 6.168084 -3.385858 30.09393 7.258982 -0.9794403 31.0795 6.545813 -1.980984 31.1637 6.637461 -2.085725 30.9868 5.05743 -3.790372 30.59823 5.227555 -3.799712 30.45115 5.799547 -3.635146 30.14857 5.989384 -3.522244 30.10523 5.60495 -3.720773 30.22248 6.580412 -2.884602 30.25059 6.661193 -2.705542 30.36047 6.468645 -3.061592 30.16785 6.72008 -2.365138 30.64614 6.696208 -2.215226 30.81233 6.708277 -2.530428 30.49382 8.087665 -2.191415 28.42472 8.099141 -2.1754 28.42008 8.162555 -2.002663 28.54773 8.547285 -1.465227 28.20853 8.909737 -0.7078565 27.97223 9.179707 0.08755898 27.71381 9.260931 0.6161456 27.79214 9.351037 0.9088993 27.43702 9.154099 1.287025 28.53586 7.019319 -0.8285792 31.42158 6.424025 -2.04039 31.23466 8.23985 1.208231 30.54458 7.786231 1.49377 31.19204 7.477406 0.3144723 31.37279 8.582097 0.8170927 29.88398 8.890625 -0.2263355 28.61183 8.801475 0.3334899 29.23244 5.402661 -4.412044 29.22247 5.023245 -4.692456 29.0321 5.764722 -4.30577 28.96299 4.658059 -4.567789 29.67364 4.322405 -4.549361 29.96383 3.523306 -5.140777 29.23551 5.022221 -4.521498 29.42372 4.248293 -4.997992 29.0692 3.450041 -5.220131 29.07443 2.63867 -5.357726 29.04831 4.026531 -4.466834 30.28456 3.089509 -5.019779 29.70574 2.121703 -5.39245 29.03996 4.907469 -3.748543 30.76079 7.439804 -1.186094 30.73048 7.555712 -1.4416 30.38625 7.602812 -1.737377 30.05835 7.579524 -2.063493 29.75782 7.486629 -2.408994 29.49473 7.327247 -2.762277 29.27793 7.106731 -3.111479 29.11469 5.786602 -4.243102 29.07665 6.161149 -4.020345 28.99115 6.513724 -3.751256 28.96885 5.412127 -3.776249 30.32448 8.298753 -1.496104 28.93346 8.3329 -1.017968 29.37409 8.263841 -0.5843121 29.85483 8.093902 -0.2097003 30.35954 7.828789 0.09328627 30.87125 7.106468 -3.304287 28.7304 6.462685 -3.841286 28.86212 8.846547 -0.8435826 28.04299 7.63262 -2.763062 28.58627 2.128038 -6.166448 26.73203 2.295957 -6.827367 24.4577 2.454283 -7.397593 22.16174 2.602545 -7.876778 19.84673 2.650992 -8.020076 19.04885 2.740246 -8.264366 17.51617 2.866998 -8.559925 15.17413 2.982563 -8.763282 12.8233 3.370429 -8.252662 17.41597 7.838282 -3.486123 26.38955 8.305287 -2.885713 26.24287 8.702394 -2.251112 26.07944 9.026206 -1.593536 25.90246 9.275753 -0.9242088 25.71534 9.45234 -0.2538064 25.52154 9.559226 0.4079931 25.32436 10.45519 -1.902856 12.56658 10.36363 -2.594517 12.6054 10.20241 -3.295169 12.64111 9.968029 -3.994698 12.67289 9.658926 -4.681944 12.69994 9.275815 -5.34518 12.72156 8.821834 -5.972681 12.73718 8.30258 -6.553363 12.74639 6.440192 -7.92577 12.7346 7.101417 -7.53681 12.74499 7.72588 -7.077409 12.749 5.75391 -8.240922 12.71823 5.054332 -8.481348 12.69643 4.352699 -8.648414 12.6699 3.659242 -8.745464 12.63937 2.625646 -6.139193 26.76354 3.319635 -6.046334 26.79498 7.307211 -4.041735 26.51667 6.720104 -4.543156 26.62201 6.0868 -4.982723 26.70403 5.418406 -5.354891 26.76196 4.726673 -5.656436 26.79582 4.023355 -5.886482 26.80637 10.05724 -1.121671 19.01837 9.901665 -0.694037 21.14096 9.959289 -1.803216 19.13749 9.801001 -1.370054 21.2864 9.791666 -2.49362 19.25335 9.63066 -2.054859 21.42855 9.550967 -3.182916 19.36389 9.387274 -2.738566 21.56491 9.23574 -3.860111 19.46696 9.069446 -3.410269 21.6929 8.846807 -4.513646 19.56049 8.678033 -4.058504 21.81001 8.387419 -5.131969 19.64257 8.216341 -4.671813 21.91388 7.863265 -5.704157 19.71159 7.690091 -5.239361 22.00249 7.282255 -6.220539 19.7663 7.107237 -5.751554 22.07428 6.65414 -6.673221 19.80593 6.477554 -6.200565 22.12821 5.989964 -7.056492 19.8302 5.812105 -6.580729 22.16384 5.30145 -7.367034 19.83933 5.122621 -6.888753 22.18131 4.600356 -7.603943 19.83396 4.420859 -7.12374 22.18132 3.897896 -7.768565 19.81513 3.718025 -7.287026 22.16501 3.204261 -7.864194 19.78417 3.024292 -7.38188 22.13389 9.735466 -0.1838827 23.24403 9.631817 -0.8533141 23.41551 9.458483 -1.531448 23.58365 9.212147 -2.208494 23.74555 8.891451 -2.873653 23.8982 8.49731 -3.515573 24.03861 8.033076 -4.122906 24.16403 7.504517 -4.684925 24.27202 6.919627 -5.192129 24.36069 6.288211 -5.636765 24.42876 5.621355 -6.013225 24.47561 4.930796 -6.318248 24.50134 4.228291 -6.550946 24.50665 3.525037 -6.712642 24.49282 2.831185 -6.806571 24.46154 10.33443 -1.726617 14.72774 10.20165 -1.466055 16.8795 10.24104 -2.415992 14.7935 10.10612 -2.152056 16.97204 10.07799 -3.11433 14.8561 9.940933 -2.846974 17.06137 9.841797 -3.811547 14.9143 9.702632 -3.540777 17.14584 9.530945 -4.496523 14.96686 9.389739 -4.2224 17.22375 9.146169 -5.157567 15.0126 9.00302 -4.880208 17.29348 8.690649 -5.782994 15.05052 8.545694 -5.502573 17.35357 8.17 -6.361758 15.0798 8.023406 -6.078503 17.40279 7.592072 -6.884073 15.09989 7.444041 -6.59826 17.44026 6.966573 -7.341956 15.11054 6.817323 -7.053902 17.46546 6.304514 -7.729632 15.11178 6.154279 -7.43968 17.47826 5.617604 -8.043745 15.10396 5.466623 -7.752252 17.47895 4.917603 -8.283373 15.08768 4.766117 -7.990709 17.46815 4.215746 -8.44989 15.06374 4.063982 -8.15641 17.44678 3.522251 -8.546614 15.03308 5.757081 4.996703 9.484723 5.05 4.996703 9.484723 5.757081 5 9.482215 5.05 5 9.482215 -5.05 4.996703 9.484723 -5.757081 4.996703 9.484723 -5.05 5 9.482215 -5.757081 5 9.482215 5.790845 4.996703 9.484482 5.832741 4.998423 9.482215 5.866478 4.996703 9.482215 5.05 4.996703 9.482215 -5.05 4.996703 9.482215 -5.866478 4.996703 9.482215 -5.832738 4.996703 9.483525 -5.79086 4.999686 9.482215 7.594199 5 30.05288 7.552701 5 30.12014 7.759685 5 30.15811 -7.436732 5 30.23098 -7.502311 5 30.17766 -7.50908 5 30.52744 8.554406 5 27.17295 8.475068 5 27.75125 8.647228 5 28.03084 -7.788485 5 30.11217 8.431588 5 28.77236 7.309093 4.999996 30.78908 -2.784347 5 33.62012 -4.504587 5 32.85228 -4.227823 5 33.28627 8.296163 5 28.48977 8.262027 5 28.59874 8.133687 5 29.48594 7.989101 5 29.30403 7.637675 5 29.97366 6.027138 5 31.74284 4.504655 5 32.85226 5.223129 5 32.70381 2.784419 5 33.6201 0.9419474 5 34.01264 1.180176 5 34.21924 2.280669 5 34.01216 3.333402 5 33.68112 4.319203 5 33.23945 -6.684765 5 31.49137 -5.961116 5 32.15422 -6.027075 5 31.74286 9.917363 5 10.21532 9.895789 5 10.15222 9.699384 5 10.92619 9.778831 5 9.935213 9.747916 5 9.894317 7.436748 5 30.23098 7.433394 5 30.23325 7.400554 5 30.25667 -5.140137 5 32.75887 8.778082 5 27.27201 8.794013 5 27.1187 9.17376 5 19.65027 9.468813 5 18.81595 9.955863 5.000023 10.52572 6.034943 5 32.09275 6.749085 5 31.42529 7.19431 5 30.46373 7.28157 5 30.36141 -3.234869 5 33.71798 -2.176653 5 34.03762 -0.9418745 5 34.01264 -1.07271 5 34.23225 0.05432242 5 34.29368 -7.594205 5 30.05287 -7.637675 5 29.97366 -8.040837 5 29.6702 -7.950747 5 29.38697 -8.300075 5 29.11556 -8.234623 5 28.68177 -8.521121 5 28.50075 -8.237755 5 28.67247 -8.542021 5 28.43129 -9.940589 5 10.3094 -9.949416 5 10.36442 -9.699385 5 10.92618 -7.309387 5 30.78872 -7.194266 5 30.46374 -7.276107 5 30.36706 -9.955893 5.000027 10.52572 -9.671789 5 15.73145 -9.17376 5 19.65026 -9.240181 5 21.89865 -8.554406 5 27.17295 -8.794002 5 27.11882 -8.441945 5 27.92042 -8.71638 5 27.69268 -8.393306 5 28.13497 -8.375681 5 28.20546 -9.747919 5 9.894268 -9.845592 5 10.04231 -9.894967 5 10.14996 6.952164 4.245617 31.62104 7.540059 4.200797 30.97416 7.0929 3.485616 31.75669 7.679929 3.492695 31.08763 7.174028 2.733253 31.83489 7.771409 2.703705 31.16052 6.41492 2.733253 32.54437 5.551993 2.733253 33.19391 4.591154 2.733253 33.76327 3.543283 2.733253 34.23275 2.424267 2.733253 34.58463 -1.14025 2.733253 34.81858 0.05774271 2.733253 34.88388 1.254484 2.733253 34.80475 6.216533 4.245617 32.30858 5.380291 4.245617 32.93803 4.449167 4.245617 33.48978 3.433704 4.245617 33.94474 2.349294 4.245617 34.28574 1.215687 4.245617 34.49906 0.0559569 4.245617 34.57573 -1.104987 4.245617 34.51246 -2.242148 4.245617 34.31197 -3.332205 4.245617 33.98271 -4.355038 4.245617 33.538 -5.294803 4.245617 32.99474 -6.140485 4.245617 32.3719 6.342377 3.485616 32.45815 5.489208 3.485616 33.10034 4.539234 3.485616 33.66327 3.503214 3.485616 34.12744 2.396852 3.485616 34.47534 1.240297 3.485616 34.69298 0.05708962 3.485616 34.7712 -1.127356 3.485616 34.70664 -2.287537 3.485616 34.5021 -3.399661 3.485616 34.16617 -4.443199 3.485616 33.71246 -5.401988 3.485616 33.1582 -6.26479 3.485616 32.52276 -2.313701 2.733253 34.61169 -3.438546 2.733253 34.27193 -4.49402 2.733253 33.81303 -5.463776 2.733253 33.25243 -6.336446 2.733253 32.60971 -7.105658 2.733253 31.90512 -7.025303 3.485616 31.82613 -6.885908 4.245617 31.6891 -7.749413 2.961034 31.14202 -7.681744 3.485616 31.08769 -7.583085 4.012786 31.00848 -9.008378 4.415502 27.25086 -8.623744 4.828749 28.40906 -8.558773 4.52824 28.96997 -8.403203 4.290703 29.54314 -8.161716 4.123295 30.11129 -7.841588 4.031057 30.65733 -9.087821 4.203699 27.14605 -9.290181 3.378822 27.16481 -9.316346 3.080902 27.3851 -9.39835 2.536253 27.17485 -9.221487 2.642161 28.20402 -8.641785 2.050946 29.87035 -8.994356 2.295361 29.04084 -9.042659 3.975044 27.91168 -8.961918 3.601596 28.60874 -8.768589 3.306406 29.32102 -8.468488 3.098365 30.02708 -8.070659 2.98374 30.70565 -10.09566 4.657575 10.52659 -10.36442 3.794658 10.52826 -9.999197 4.093492 15.75163 -10.52823 2.900167 10.52927 -9.567213 4.093492 21.92428 -9.800248 2.980403 21.94254 -10.2325 2.980403 15.766 -9.161569 4.303232 9.482215 -8.849065 5 9.482215 9.161547 4.303157 9.482215 9.394603 3.55509 9.482215 9.536596 2.779814 9.482215 8.849019 5 9.482215 -9.536571 2.780145 9.482215 -9.394565 3.55537 9.482215 10.09564 4.657495 10.52659 10.04462 4.638139 10.15353 9.840523 4.560718 9.794692 9.245085 5 9.546853 9.278842 5 9.558898 9.516253 4.43771 9.556963 9.551599 5 9.705974 9.655819 5 9.793557 8.926918 5 9.484612 10.36445 3.794405 10.52826 10.31196 3.781452 10.15478 10.10018 3.729194 9.795304 9.763239 3.646053 9.557105 10.52825 2.899795 10.52927 10.47489 2.893338 10.15554 10.25842 2.867148 9.795677 9.913743 2.825445 9.557188 -9.526638 5 9.6881 -9.251732 5 9.549118 -9.509902 4.43537 9.554202 -9.837234 4.559543 9.790976 -10.04388 4.637932 10.15122 -10.47406 2.893611 10.15322 -9.170372 5 9.524156 -9.65238 5 9.790235 -9.60809 5 9.750553 -9.906945 2.824972 9.554413 -9.953996 2 9.558612 -10.25488 2.867084 9.791951 -10.52374 2 10.15602 -10.31115 3.781514 10.15246 -10.09671 3.728607 9.791582 -9.756584 3.644689 9.554332 9.739873 4.278199 18.83492 9.935606 3.532323 18.84862 10.05387 2.770234 18.85689 9.398286 2.537157 27.17482 9.290019 3.379702 27.16474 9.087587 4.204388 27.14594 7.738017 3.199301 31.10073 9.304394 2.974366 27.58268 9.158761 3.056716 28.26236 7.49292 4.473202 30.89001 7.927073 4.075831 30.51111 7.993739 4.90986 29.83906 8.309345 4.630016 29.46578 8.583826 4.39662 29.03284 8.810768 4.21513 28.55033 8.984864 4.089792 28.02952 9.10205 4.023526 27.48259 9.172197 2.070817 28.5041 8.930873 2.184998 29.21918 8.599538 2.449973 29.92364 8.1988 2.79073 30.55574 8.942408 3.212476 28.90957 8.660384 3.438018 29.5092 8.319279 3.728064 30.04723 9.911766 5 5.809243 9.281219 5 6.778078 -9.911766 5 5.809243 -9.278203 5 6.782443 2.034731 8.900001 19.9462 2.034731 7.887764 19.9462 2.49777 8.900001 19.96747 2.689377 7.812883 19.98881 3.084287 8.875375 20.05647 3.482128 8.829996 20.15806 3.328908 7.721006 20.11484 3.48165 7.696295 20.15792 3.65364 8.803031 20.21272 3.704549 7.658302 20.23025 3.952094 8.745129 20.32434 4.504903 8.599143 20.59157 4.314069 7.54259 20.48985 4.808104 8.496191 20.7759 4.807131 7.436142 20.77526 5.022738 8.412734 20.92504 4.881688 7.419033 20.82518 5.19709 8.338083 21.05894 5.172589 7.349701 21.03939 5.67179 8.100732 21.49273 5.661937 7.223719 21.48253 5.900462 7.966504 21.74679 5.900049 7.158112 21.7463 6.08845 7.845045 21.98458 6.086176 7.104837 21.98152 6.23056 7.745807 22.18594 6.319882 7.035444 22.32412 6.540252 7.503424 22.71524 7.049653 6.800478 24.402 7.049653 6.967445 24.402 6.948317 6.834787 23.83036 6.949221 7.10133 23.83418 6.858255 6.864819 23.50083 6.78021 7.283542 23.26908 6.669128 6.926487 22.98999 6.668771 7.389961 22.98917 6.629724 6.939099 22.90131 6.324827 7.033945 22.33207 -6.591384 7.459336 22.81918 -6.668967 7.38978 22.98962 -6.66912 6.92649 22.98997 -6.764372 7.299198 23.22617 -7.049653 6.967445 24.402 -7.049653 6.800478 24.402 -6.943249 7.108395 23.8092 -6.934803 6.839321 23.7748 -6.857292 6.865138 23.49773 -6.624532 6.940754 22.88996 -6.316166 7.036569 22.31817 -6.274889 7.713426 22.25329 -6.158389 7.083693 22.08107 -5.900189 7.966672 21.74647 -5.900048 7.158112 21.7463 -5.891183 7.972229 21.73579 -5.742567 7.201821 21.56772 -5.689622 8.090764 21.51133 -5.211322 7.340159 21.07041 -5.242918 8.317398 21.09619 -4.807459 8.496428 20.77548 -4.807126 7.436144 20.77526 -4.671079 7.466675 20.68897 -4.754074 8.51579 20.74088 -4.089976 7.587156 20.38334 -4.186197 8.689623 20.42742 -3.640945 8.805185 20.20844 -3.720977 7.655411 20.23604 -3.482091 8.829999 20.15805 -3.481806 7.696269 20.15797 -3.075376 8.876122 20.05458 -3.092647 7.75712 20.05825 -2.815012 8.892834 20.00684 -2.450377 7.842455 19.96333 -2.49777 8.900001 19.96747 -2.034731 8.900001 19.9462 -2.083067 7.882893 19.94643 -2.034731 7.887764 19.9462 0.812025 7.48167 34.72446 1.620219 7.426873 34.65936 0.6611019 7.487855 20.4462 2.420628 7.336393 34.55168 1.979739 7.390798 20.4462 2.553627 7.31794 20.48459 2.65891 7.302453 34.51121 2.65925 7.302483 20.50012 3.20915 7.211603 34.40272 3.114264 7.228546 20.59815 4.730507 6.867277 21.43115 4.475492 6.934734 21.23816 3.977895 7.054953 20.93603 3.443566 7.167537 20.70213 5.895092 6.50727 32.92352 6.394415 6.325907 32.33312 6.931862 6.111721 30.58539 6.803107 6.164885 31.6728 6.982653 6.090437 31.29218 5.315735 6.697166 33.43423 7.00125 6.082597 29.88433 6.691679 6.20992 27.19901 6.376014 6.332898 24.46083 6.287179 6.36628 23.94579 6.208228 6.3955 23.64888 6.007889 6.467772 23.10873 5.740604 6.560055 22.59584 5.736268 6.561513 22.58868 3.960194 7.05888 34.1817 4.667089 6.884422 33.85635 5.159488 6.7447 21.83041 5.531394 6.629031 22.28 2.63599e-5 7.499949 34.74617 -2.07714e-4 7.5 20.4462 -0.8119659 7.481668 34.72446 -0.6611019 7.487855 20.4462 -1.620146 7.426889 34.65938 -1.979739 7.390798 20.4462 -2.420565 7.3364 34.55169 -2.022112 7.386058 20.44641 -2.34411 7.346713 20.46163 -2.659321 7.302386 34.51113 -2.659909 7.302384 20.50022 -3.209151 7.211609 34.40272 -2.907149 7.263685 20.54716 -3.457968 7.164724 20.70734 -3.781446 7.098314 20.84005 -3.890316 7.074478 34.20734 -4.539033 6.918306 33.92475 -4.290864 6.981089 21.11543 -4.764462 6.857993 21.45911 -5.145971 6.748715 33.55797 -6.376014 6.332898 24.46083 -6.691679 6.20992 27.19901 -6.275332 6.370691 23.89573 -5.230172 6.723394 21.90717 -5.594698 6.608458 22.3697 -5.733011 6.562608 22.58332 -6.003337 6.469382 23.0985 -6.207383 6.39581 23.64609 -6.982442 6.090527 31.29163 -6.920819 6.116339 31.43183 -6.931869 6.111719 30.58502 -6.803375 6.164779 31.67229 -6.609408 6.242643 32.01316 -6.394675 6.325806 32.33277 -6.19296 6.401078 32.59282 -7.00125 6.082597 29.88433 -5.701238 6.573248 33.11148 7.792215 5.142107 29.53572 7.515876 6.499877 27.07679 7.496991 6.521002 27.07504 7.518614 6.363464 27.81862 7.495037 6.253071 28.26558 7.705728 5.981118 28.30332 7.424894 6.136627 28.74558 7.285457 6.045196 29.2293 7.591811 5.902641 28.80416 7.305188 6.052572 29.17667 8.307223 5.134511 28.17957 8.149805 5.567541 27.68398 8.194191 5.61319 27.13959 7.881275 6.033831 27.27363 7.823303 5.657689 28.67348 7.852574 5.373736 29.09057 7.702646 5.48915 29.25154 7.693873 5.358791 29.45289 7.690583 5.325766 29.50288 7.689693 5.317482 29.51535 7.686069 5.857308 28.64814 7.115938 6.861205 24.96144 7.182104 6.749726 25.51988 9.333717 5.94235 5.435857 9.65656 5.456918 5.606717 9.777551 5.25 5.695204 8.686899 6.710738 5.373921 9.002724 6.363401 5.358416 8.307548 7.072832 5.49788 8.627854 6.770734 5.386011 -0.6794659 7.987518 19.9462 0.6794659 7.987518 19.9462 4.885037 8.777506 10.69305 5.11749 8.50615 20.84713 5.297823 8.430488 20.98389 5.425311 8.427044 19.38004 6.687747 7.584551 22.67478 6.936353 7.361698 23.23999 7.330101 7.275433 19.51736 7.468249 6.591223 26.6881 8.133489 6.499877 19.57527 7.111659 7.177024 23.81663 7.216102 7.04133 24.39597 7.283913 6.933654 24.95564 7.351613 6.820669 25.51431 6.420638 7.922616 19.45179 5.78888 8.189931 21.42685 6.220022 7.930788 21.92899 6.367107 7.830209 22.13454 4.366247 8.777506 19.30369 3.266982 8.96621 19.22445 3.113199 8.975045 19.95925 3.701789 8.901721 20.1192 4.010356 8.843036 20.23335 4.581962 8.695075 20.50647 3.78421 8.96621 10.63974 5.945608 8.427044 10.74441 6.942349 7.922616 10.79268 7.853106 7.275433 10.83678 8.657635 6.499877 10.87574 9.338055 5.61319 10.90869 8.812943 5.61319 19.62425 -7.182104 6.749726 25.51988 -7.115938 6.861205 24.96144 -7.68965 5.317091 29.51594 -7.70049 5.712631 28.89136 -7.920138 5.376977 28.92134 -7.686069 5.857308 28.64814 -7.518179 6.212303 28.30293 -7.702237 6.043475 28.14624 -7.504031 6.500246 27.18883 -7.496991 6.521002 27.07504 -7.515876 6.499877 27.07679 -7.861485 5.903813 27.94115 -7.510997 6.473219 27.32676 -7.988945 5.79944 27.69663 -8.079032 5.734928 27.4234 -8.194191 5.61319 27.13959 -7.519564 6.388122 27.71447 -7.518868 6.415221 27.59661 -7.516439 6.441332 27.47866 -7.489571 6.23917 28.32117 -7.497056 6.258647 28.24331 -7.435803 5.976143 29.03395 -7.419602 6.130928 28.77079 -7.295103 6.040818 29.21742 -7.285457 6.045196 29.2293 -7.489192 6.238263 28.3248 -8.193644 5.137113 28.5691 -9.777551 5.25 5.695204 -8.295863 7.083163 5.503351 -8.627265 6.771323 5.386145 -9.494096 5.71201 5.50891 -9.182711 6.142676 5.388345 -8.888588 6.494376 5.354219 -3.784211 8.96621 10.63973 -7.853106 7.275433 10.83677 -7.395191 6.742606 25.89858 -7.351613 6.820669 25.51431 -8.133489 6.499877 19.57527 -7.283913 6.933654 24.95564 -7.216102 7.04133 24.39597 -7.105458 7.184184 23.79114 -7.330102 7.275433 19.51735 -8.812943 5.61319 19.62425 -9.338055 5.61319 10.90868 -8.657636 6.499877 10.87573 -5.945609 8.427044 10.7444 -6.942349 7.922616 10.79267 -4.885038 8.777506 10.69304 -3.266983 8.96621 19.22444 -2.834851 8.992736 19.90837 -3.103988 8.975799 19.95732 -3.688664 8.903903 20.11482 -4.366247 8.777506 19.30368 -4.252408 8.786783 20.33872 -4.839635 8.610598 20.65902 -5.425312 8.427044 19.38003 -5.345226 8.409523 21.02194 -5.80733 8.179827 21.44585 -6.420638 7.922616 19.45179 -6.015882 8.059693 21.675 -6.919937 7.377565 23.19621 -6.740705 7.539867 22.78086 -6.412993 7.797391 22.20328 7.222205 5.969675 30.86247 7.217453 5.972793 30.87106 7.181943 5.987058 30.98599 6.869647 6.119594 31.71644 7.322094 5.775444 30.80142 7.446383 5.723228 30.27557 7.249206 5.811965 31.03414 7.390799 5.813158 30.49244 6.931876 5.949151 31.78411 7.088737 5.870791 31.45255 7.248991 5.805668 31.03498 6.511041 6.119981 32.47278 6.780553 5.99127 32.0606 6.961929 5.921139 31.72576 5.401107 6.512662 33.61912 5.424536 6.44929 33.6089 5.663287 6.376636 33.41124 5.99724 6.311982 33.08766 6.160504 6.214375 32.91591 6.554418 6.075582 32.41406 5.101024 6.542298 33.8433 4.733341 6.710225 34.05829 4.588537 6.67732 34.14799 4.004869 6.893943 34.3969 3.912245 6.832675 34.44569 6.455229 6.284842 32.38789 5.949051 6.470803 32.98789 5.361749 6.665376 33.50673 4.704076 6.857115 33.93554 3.987052 7.035615 34.26609 3.225158 7.190843 34.49272 3.232846 7.132783 34.57561 7.232794 5.907411 31.01473 6.917029 6.042916 31.75684 6.498166 6.211739 32.43857 5.986686 6.401578 33.04745 5.393241 6.600082 33.57382 4.728567 6.79558 34.00882 4.003646 6.977458 34.34418 3.229283 7.047173 34.63 3.218211 6.965622 34.64687 -4.004838 6.893934 34.39691 -3.229938 7.054305 34.6271 -3.232724 7.136324 34.57213 -3.218213 6.965621 34.64688 -7.344358 5.868577 30.6163 -7.351751 5.860637 30.59837 -7.233042 5.907292 31.01402 -7.441158 5.732761 30.30262 -7.249453 5.811841 31.03342 -7.442739 5.729821 30.29467 -7.446322 5.723204 30.27585 -6.869913 6.119484 31.71593 -7.182189 5.986945 30.98529 -7.164622 6.004714 30.96472 -6.455492 6.284736 32.38753 -5.949291 6.470721 32.98765 -5.361948 6.665309 33.50659 -4.704189 6.857088 33.93547 -3.987024 7.035613 34.26609 -4.733454 6.71019 34.05823 -4.459344 6.708992 34.21341 -3.803367 6.855281 34.48386 -5.401308 6.512588 33.61897 -5.085532 6.546595 33.85365 -4.72446 6.64295 34.07441 -6.511306 6.119866 32.47241 -6.108269 6.232123 32.9742 -5.997481 6.311891 33.08742 -5.675296 6.372899 33.40069 -5.394615 6.458153 33.63212 -7.272551 5.795956 30.96362 -7.002211 5.905265 31.6431 -6.932144 5.949033 31.78358 -6.642342 6.043219 32.28361 -6.513127 6.090557 32.47265 -3.224873 7.191695 34.49072 -4.003616 6.977452 34.34419 -4.728681 6.795549 34.00875 -5.393443 6.600012 33.57368 -5.986928 6.401492 33.04721 -6.498432 6.211628 32.4382 -6.917298 6.042802 31.75631 4.000056 6.781846 34.41098 3.198292 6.873101 34.6325 7.456668 5.693719 30.2109 7.459928 5.697363 30.19449 6.772369 5.66487 31.60685 7.022735 5.598309 31.17819 6.802111 5.692776 31.69285 7.171134 5.575102 30.88388 7.297616 5.575005 30.60057 7.211877 5.637923 30.9638 7.162869 5.59281 30.95429 7.025806 5.597666 31.17244 6.857223 5.725242 31.71365 5.846555 6.022741 32.96906 6.113392 5.897445 32.4745 6.342123 5.839003 32.35415 6.685332 5.69254 31.7403 6.744522 5.67712 31.66739 6.736102 5.676196 31.66331 5.409852 6.394167 33.61205 4.73675 6.594873 34.06317 6.520807 5.997767 32.43679 6.008134 6.191016 33.06673 6.937276 5.827291 31.73265 7.247078 5.692389 30.96757 7.305424 5.576233 30.58261 7.33336 5.586339 30.52882 7.397059 5.630666 30.4072 3.906198 6.585622 34.28194 3.862122 6.568444 34.17709 4.61772 6.407304 33.94228 4.558998 6.395719 33.84404 5.268208 6.216094 33.50164 5.196423 6.210682 33.41191 5.763297 6.023734 32.88969 6.395268 5.857597 32.38639 5.894314 6.044576 33.00717 5.309692 6.241255 33.54471 4.652071 6.43568 33.98945 3.932576 6.616917 34.33229 6.446271 5.892653 32.41273 5.940328 6.082493 33.03829 5.349892 6.282119 33.5799 4.68567 6.479393 34.02797 3.958815 6.663224 34.3734 6.903732 5.771923 31.72727 6.48947 5.941275 32.42997 5.979499 6.133268 33.05867 5.384367 6.335114 33.60293 4.714823 6.534546 34.05319 3.982057 6.720345 34.40032 3.171117 6.788252 34.57878 3.142809 6.734119 34.49456 3.120007 6.719614 34.40272 7.418639 5.651019 30.35177 -6.125212 5.893029 32.46128 -6.112517 5.89777 32.47535 -6.339934 5.838563 32.35266 -6.01971 5.932075 32.59387 -5.844583 6.022173 32.96733 -6.765968 5.66685 31.61689 -6.763468 5.667624 31.6208 -6.742136 5.67682 31.66619 -6.418807 5.784875 32.1098 -6.274062 5.837771 32.28952 -6.799976 5.691876 31.69191 -7.025885 5.597642 31.17226 -7.297586 5.574991 30.60063 -7.162277 5.575922 30.90249 -7.16111 5.591544 30.95384 -6.855555 5.723931 31.71302 -7.21072 5.6365 30.96357 -7.324963 5.582283 30.54327 -7.41862 5.651019 30.3518 -7.397037 5.630662 30.40723 -7.246475 5.691076 30.9675 -7.333338 5.586331 30.52886 -7.456651 5.693723 30.21092 -7.459922 5.69738 30.19446 -6.936697 5.825982 31.73256 -6.520275 5.996428 32.43671 -6.007636 6.189673 33.06666 -5.40939 6.392804 33.612 -4.736316 6.593511 34.06312 -3.999599 6.780466 34.41093 -5.266487 6.215381 33.49971 -4.417285 6.433328 33.92239 -4.616271 6.40647 33.94018 -3.786487 6.585448 34.20634 -3.905004 6.584663 34.27972 -5.763164 6.023799 32.8895 -5.565362 6.091465 33.08986 -5.015078 6.266007 33.54866 -3.120008 6.719619 34.40272 -3.147289 6.740376 34.50979 -3.164969 6.773643 34.56284 -6.393306 5.856578 32.38523 -5.89254 6.043452 33.0058 -5.308134 6.240011 33.54321 -4.650745 6.434337 33.98781 -3.931458 6.615469 34.33055 -3.183283 6.821905 34.6064 -6.444735 5.891254 32.41196 -5.93893 6.081025 33.03741 -5.348654 6.280562 33.57893 -4.684599 6.477772 34.02692 -3.957878 6.661528 34.37229 -3.200256 6.880758 34.63513 -6.90263 5.770482 31.72694 -6.488455 5.939778 32.42959 -5.978567 6.131737 33.05825 -5.383529 6.333532 33.60248 -4.714079 6.532934 34.05271 -3.981362 6.71869 34.39982 -3.214182 6.94356 34.64673 -5.233201 6.19921 33.08579 -5.967757 5.951014 32.58582 5.405656 6.144185 32.97706 4.660307 6.368062 33.41282 3.87906 6.564668 33.78201 3.417459 6.66307 33.96257 2.60782 6.804603 34.21778 2.353531 6.840918 34.55165 1.784529 6.908775 34.40245 1.575377 6.92889 34.65933 0.9490149 6.974249 34.51723 0.7895705 6.982174 34.72444 0.2886378 6.997619 34.55797 2.35026e-5 6.999949 34.74616 -0.5665357 6.990827 34.54614 -0.789516 6.982172 34.72444 -1.411486 6.942985 34.46254 -1.575305 6.928905 34.65935 -2.246682 6.855184 34.30776 -2.353465 6.840924 34.55165 -2.639916 6.799735 34.20908 -3.473012 6.651915 33.94222 -4.276812 6.469351 33.60446 -5.050709 6.255308 33.19553 2.436305 7.174602 34.78119 -2.432834 7.316994 34.64257 -1.628456 7.408488 34.75091 -0.8161613 7.463882 34.81639 2.65877e-5 7.482367 34.83824 0.8162206 7.463883 34.81639 1.628529 7.408472 34.7509 2.432897 7.316988 34.64256 3.070333 6.991321 34.67857 2.073096 7.1325 34.85213 1.630959 7.267046 34.89053 1.024495 7.221557 34.96117 -2.436242 7.174609 34.7812 -2.164785 7.121837 34.83905 -1.630886 7.267062 34.89055 -1.095557 7.217442 34.95613 -0.8174268 7.323047 34.95664 -0.03247612 7.25013 34.99611 2.67685e-5 7.341731 34.97869 0.8174862 7.323049 34.95664 2.438875 7.259906 34.72626 1.63262 7.352116 34.8352 0.8182999 7.407973 34.90107 2.67396e-5 7.426607 34.92304 -0.8182404 7.407971 34.90107 -1.632547 7.352132 34.83522 -2.438812 7.259912 34.72627 -2.3924 6.912986 34.72945 -2.413014 6.999332 34.7837 -1.615414 7.090932 34.89307 -0.8096974 7.146408 34.95919 2.43427e-5 7.164922 34.98125 0.8097534 7.146409 34.95919 1.615487 7.090916 34.89305 2.413082 6.999325 34.78369 -2.370864 6.857063 34.6444 -1.587051 6.946251 34.75276 -0.7954345 7.000257 34.81827 2.37745e-5 7.01828 34.84012 0.7954894 7.000258 34.81827 1.587123 6.946236 34.75275 2.37093 6.857057 34.64439 -1.601557 7.00349 34.83843 -0.8027339 7.058298 34.9043 2.40795e-5 7.07659 34.92628 0.8027894 7.0583 34.9043 1.60163 7.003474 34.83841 2.392466 6.91298 34.72944 6.310402 5.201558 31.47558 6.024523 5.283979 31.7452 4.974569 5.668636 32.56057 4.505213 5.821238 32.85194 -5.977282 5.299623 31.78751 -6.413888 5.178084 31.3719 -6.785952 5.133454 30.96931 -6.997823 5.147923 30.71632 -7.202539 5.034943 30.45269 -7.224299 5.217779 30.42344 -7.223484 5.162462 30.42454 -7.222503 5.149814 30.42586 -7.207905 5.05879 30.44549 -4.647925 5.776585 32.76752 -4.815865 5.722089 32.66357 -5.491841 5.480986 32.18993 -5.638727 5.423884 32.07416 -5.807255 5.359689 31.93506 -2.785084 6.243853 33.61987 -3.196046 6.16186 33.47488 -3.935745 5.984513 33.15491 -4.505034 5.821293 32.85203 -0.9421629 6.470882 34.01261 -1.298922 6.444613 33.96779 -2.067513 6.359322 33.82117 -2.429388 6.305457 33.72768 0.2656204 6.497688 34.05819 -0.5213549 6.491089 34.04698 2.78511 6.243848 33.61988 2.399853 6.310185 33.73592 1.642217 6.411382 33.91087 0.873334 6.474984 34.0196 4.288659 5.886118 32.97337 3.569715 6.077106 33.3231 3.144926 6.172697 33.49415 5.62596 5.428908 32.08445 7.207988 5.058948 30.44543 7.222563 5.149874 30.42583 7.012136 5.150406 30.69857 7.223542 5.162512 30.42451 7.224353 5.217827 30.42341 6.785864 5.133465 30.96945 7.202666 5.035291 30.45256 -7.198375 6.083085 29.20048 -7.173313 6.074621 29.28274 -6.928872 6.177609 27.16937 -7.083638 6.063719 29.58831 -7.039104 6.070144 29.7463 -7.002596 6.082033 29.87936 -7.12214 6.064643 29.45508 -7.154124 6.260844 27.14663 -7.324251 6.192383 28.57742 -7.300103 6.157133 28.75115 -7.225198 6.682571 25.90437 -7.331029 6.49116 27.08085 -7.31501 6.440254 27.13608 -7.359165 6.400104 27.59535 -7.348825 6.248883 28.31275 -6.991738 6.568683 24.39846 -6.833652 6.389826 24.40917 -6.611499 6.304754 24.43167 -6.503669 6.345789 23.83651 -2.007235 7.639281 20.01318 -2.013687 7.697583 19.98426 -2.061195 7.692639 19.98433 -1.995846 7.536355 20.09264 -1.983925 7.428627 20.25485 -2.028203 7.423724 20.25495 -2.364716 7.382912 20.2697 -2.422291 7.651504 19.99972 -3.673232 7.45998 20.26283 -3.054165 7.56433 20.0906 -4.037384 7.38974 20.40617 -4.612035 7.265384 20.70472 -5.147949 7.134306 21.0789 -5.676991 6.990386 21.56898 -6.092901 6.866959 22.07727 -6.25121 6.817572 22.31277 -6.561542 6.716873 22.88252 -6.796706 6.63711 23.49052 -6.875214 6.609815 23.76838 -6.719847 6.431962 23.79061 -6.643204 6.459905 23.51799 -6.413772 6.541481 22.92186 -6.111295 6.644309 22.36388 -5.957103 6.694679 22.13344 -5.552307 6.820398 21.63654 -5.0379 6.966712 21.15806 -4.517237 7.099723 20.79316 -3.959282 7.225696 20.50235 -3.605846 7.296748 20.36285 -3.005161 7.402152 20.19544 -2.392189 7.490018 20.10738 -2.041928 7.531388 20.09268 -1.987106 7.457378 20.1962 -6.430997 6.373016 23.57401 -6.213225 6.452564 22.99945 -5.925638 6.552962 22.46081 -5.778848 6.602188 22.23807 -5.392955 6.725179 21.75716 -4.901629 6.868525 21.29316 -4.403468 6.999016 20.93865 -3.868876 7.122753 20.65561 -3.529921 7.19261 20.51963 -2.953417 7.296336 20.35614 2.013687 7.697583 19.98426 0.6702839 7.737687 20.01318 2.007235 7.639281 20.01318 -0.6702839 7.737687 20.01318 -0.6635622 7.554798 20.1962 0.6635622 7.554798 20.1962 1.983925 7.428627 20.25485 1.987106 7.457378 20.1962 1.995846 7.536355 20.09264 6.833652 6.389826 24.40917 6.991738 6.568683 24.39846 6.888913 6.605018 23.82413 6.566779 6.715129 22.89385 6.797681 6.636774 23.49363 6.259909 6.814819 22.32659 6.254942 6.816391 22.31869 6.020542 6.889089 21.97851 5.596542 7.013211 21.48486 5.109462 7.14421 21.04841 4.820739 7.216083 20.83815 4.258799 7.343794 20.51007 3.286815 7.527326 20.14528 3.657031 7.462951 20.2572 6.516347 6.341003 23.88918 6.4319 6.37268 23.57694 6.218076 6.450825 23.01016 5.933702 6.550218 22.47387 5.929098 6.551785 22.4664 5.711736 6.624244 22.14466 5.318273 6.747917 21.67753 4.865868 6.878386 21.26428 4.597519 6.949943 21.0651 4.074903 7.077044 20.75414 3.514838 7.195565 20.5143 3.170107 7.259562 20.40807 2.620194 7.459642 20.13075 2.58373 7.352969 20.29273 3.230883 7.364798 20.24856 3.590124 7.299753 20.35738 4.17423 7.179177 20.60352 4.71996 7.049722 20.92324 5.000497 6.97677 21.1283 5.474051 6.843622 21.55437 5.886647 6.717236 22.03685 6.114931 6.643104 22.36967 6.11977 6.6415 22.3774 6.418879 6.539698 22.93297 6.644155 6.45956 23.52104 6.733223 6.427049 23.84533 6.611499 6.304754 24.43167 2.657339 7.621344 20.0239 7.36326 6.355806 27.81421 7.31501 6.440254 27.13608 7.154124 6.260844 27.14663 7.331029 6.49116 27.08085 6.928872 6.177609 27.16937 7.198375 6.083085 29.20048 7.213627 6.089554 29.149 7.003246 6.081758 29.87962 7.083849 6.063709 29.58757 7.173145 6.074573 29.2833 7.300135 6.551944 26.694 7.303977 6.162016 28.72641 7.324287 6.192444 28.57713 7.352496 6.261523 28.25447 -7.265898 6.042716 29.2734 -7.329549 5.962257 29.33713 -7.345384 5.957099 29.30953 -7.321132 5.965815 29.34833 -7.311732 5.970023 29.35975 -7.177414 6.040854 29.47493 -7.143858 6.044066 29.55206 -7.314384 5.96724 29.36338 -7.057064 6.062513 29.7533 -7.12195 6.047327 29.60262 -7.322184 5.964672 29.3499 -7.472086 5.917469 29.08076 -7.631494 5.560634 29.34526 -7.611929 5.426241 29.58288 -7.54115 5.293451 30.00233 -7.556039 5.134792 30.03274 7.599301 5.453845 29.60162 7.541149 5.293446 30.00234 7.556035 5.134788 30.03275 7.611966 5.426644 29.5823 7.612748 5.435137 29.56997 7.6012 5.459654 29.58754 7.615607 5.46899 29.5206 7.608658 5.482969 29.53118 7.631648 5.561197 29.34391 7.621092 5.523911 29.43286 7.14533 6.026102 29.64709 7.122256 6.047275 29.60191 7.143615 6.044097 29.55262 7.263491 5.991515 29.41721 7.225468 6.03999 29.36512 7.30158 5.97456 29.372 7.2521 6.041425 29.30462 7.311017 5.970343 29.36062 7.258754 6.042 29.28956 7.346093 5.956869 29.30829 7.329885 5.962146 29.33654 7.274427 5.98059 29.4318 7.30595 5.970032 29.37791 7.313775 5.967442 29.36443 -7.439574 5.735966 30.29336 -7.510394 5.577949 29.99975 -7.494734 5.627117 30.03448 -7.478903 5.677937 29.98775 -7.49417 5.628629 30.0363 -7.421071 5.788417 29.97044 -7.483215 5.653025 30.07765 -7.476952 5.665037 30.10433 -7.334968 5.877239 30.59744 -7.302753 5.917681 29.9418 -7.426894 5.888822 29.3258 -7.523382 5.518601 29.99699 -7.591893 5.656352 29.35313 -7.521827 5.781797 29.34311 7.089362 6.045543 29.89535 7.381942 5.840162 29.95836 7.302992 5.917568 29.93982 7.33506 5.877137 30.59682 7.490522 5.637732 30.04902 7.51042 5.57813 29.99901 7.43228 5.771192 29.97156 7.460946 5.69515 30.18779 7.439645 5.735856 30.29203 7.592078 5.656703 29.35175 7.427399 5.888695 29.3245 7.524474 5.512674 29.9967 7.522119 5.781872 29.34175 7.41852 5.072423 30.23601 7.257842 5.22781 30.381 7.391651 5.288003 30.2536 7.393094 5.262676 30.25129 7.407473 5.131344 30.24042 -7.407472 5.131256 30.24041 -7.349219 5.26546 30.2879 -7.393077 5.262679 30.25129 -7.391638 5.287954 30.25359 -7.418505 5.072421 30.236 -7.501354 5.597384 30.03577 -7.494465 5.591039 30.07701 -7.486305 5.562407 30.12053 -7.481917 5.468159 30.1532 -7.462808 5.47608 30.18446 -7.446824 5.428947 30.2074 -7.490703 5.278282 30.14086 -7.503647 5.106745 30.14641 7.503651 5.106743 30.14642 7.490706 5.278275 30.14087 7.494483 5.591038 30.07699 7.486322 5.56241 30.12052 7.482564 5.463471 30.15253 7.462821 5.476108 30.18446 7.446837 5.42899 30.2074 7.501373 5.59738 30.03575 7.479543 5.649642 30.09845 7.465129 5.627859 30.16392 7.42676 5.565787 30.2621 7.403514 5.534566 30.29792 7.330036 5.453598 30.36653 7.247901 5.418614 30.46109 7.254084 5.500223 30.54259 7.226696 5.413187 30.49235 7.21664 5.317674 30.45205 6.555872 5.642415 31.62073 6.354916 5.379256 31.47884 6.440573 5.533094 31.52949 5.828283 5.803676 32.16248 5.703966 5.636791 32.08507 5.974398 5.896661 32.30141 6.928803 5.522816 31.08902 6.803318 5.280047 30.98286 7.016492 5.276296 30.71917 7.045977 5.393983 30.75883 6.852402 5.413748 31.02392 7.098669 5.495797 30.81495 4.352544 6.086254 32.9892 5.046305 5.872308 32.56898 5.156317 6.037935 32.65362 -5.910399 5.854199 32.21247 -5.841175 5.798863 32.15209 -5.690043 5.854518 32.2712 -5.803804 5.759403 32.12394 -5.713952 5.626779 32.07371 -5.568665 5.687919 32.19221 -5.66826 5.524039 32.0645 -5.98759 5.891794 32.29094 -4.885887 5.924869 32.67377 -4.716063 5.978471 32.77958 -3.995187 6.183127 33.17419 -2.467642 6.499415 33.75852 -3.245472 6.357846 33.50049 -2.100283 6.552541 33.854 -1.31972 6.636685 34.00378 -0.5297477 6.682548 34.08471 0.2698996 6.68906 34.09616 0.8873667 6.666655 34.05673 1.668409 6.603897 33.94563 3.193628 6.368527 33.52016 2.437665 6.504078 33.76694 3.624309 6.274331 33.34567 -4.992404 6.090234 32.76 -4.818879 6.143576 32.86742 -4.082276 6.3473 33.26808 -3.316201 6.521292 33.59945 -2.521405 6.662313 33.86152 -2.146037 6.715243 33.95849 -1.348463 6.799087 34.11064 -0.5412843 6.844789 34.19285 0.2757769 6.851279 34.20449 0.9066916 6.828951 34.16442 1.704749 6.766414 34.05157 2.490774 6.666959 33.87007 3.263226 6.531929 33.61943 3.703304 6.438116 33.44222 4.44743 6.250856 33.08024 -6.021718 5.900481 32.32931 -5.832318 5.948311 32.41152 -5.115762 6.187674 32.90634 -4.937639 6.241821 33.01503 -4.181911 6.448561 33.42031 -3.396492 6.625057 33.75532 -2.582068 6.768065 34.02017 -2.197549 6.82173 34.11816 -1.380712 6.906729 34.27186 -0.5542042 6.953056 34.35491 0.282357 6.959634 34.36666 0.9283472 6.937002 34.32619 1.745577 6.873608 34.21219 2.550687 6.772775 34.02881 3.342196 6.635846 33.77551 3.793308 6.540692 33.59638 4.556471 6.350702 33.23033 5.284055 6.134578 32.79869 -7.226645 5.413163 30.4924 -7.216586 5.317638 30.45208 -7.003005 5.275299 30.73642 -6.134033 5.82345 32.12992 -5.993311 5.725123 32.00416 -6.279991 5.757975 31.96345 -6.63903 5.610994 31.50949 -6.928886 5.522789 31.08886 -7.088066 5.496673 30.83271 -7.254042 5.500206 30.54264 -7.03377 5.39419 30.7761 -6.852489 5.413722 31.02377 -6.530946 5.500543 31.42464 -6.146093 5.655153 31.84984 -6.803406 5.280028 30.98272 -6.452654 5.350001 31.37679 -6.039293 5.49344 31.78776 -5.877386 5.560603 31.93504 -7.304395 5.440252 30.39215 -7.330008 5.453576 30.36654 -7.479525 5.649644 30.09847 -7.465112 5.62786 30.16393 -7.426739 5.565773 30.26211 -7.403489 5.534545 30.29794 -7.267566 6.063346 29.22474 -7.246107 6.076217 29.2181 -7.222516 6.082947 29.20983 -7.151553 6.057522 29.46578 -7.103673 6.057802 29.59572 -7.048286 6.066828 29.74983 -7.382158 6.267372 28.32086 -7.480918 6.440674 27.60287 -7.464926 6.543915 27.08121 -7.455637 6.547504 27.08246 -7.426193 6.552529 27.0853 -7.435244 6.446771 27.60487 -7.406237 6.550948 27.08636 -7.386955 6.545474 27.08668 -7.391562 6.432216 27.60217 -7.360978 6.530484 27.08577 -7.353457 6.523872 27.08511 -7.458108 6.261626 28.32738 -7.420528 6.271846 28.326 -7.330913 6.166196 28.75977 -7.363465 6.164533 28.76635 -7.394159 6.152327 28.77016 -7.312513 6.843492 25.52362 -7.357921 6.765599 25.90695 -7.266768 6.846284 25.52961 -7.3139 6.770126 25.9124 -7.22415 6.828448 25.53101 -7.240215 6.724031 25.91096 -7.193765 6.793794 25.52751 -7.271881 6.755287 25.91383 -7.127359 6.904997 24.96861 -7.060843 7.01096 24.40874 -7.157234 6.939595 24.97181 -7.090222 7.045493 24.41166 -7.199288 6.957734 24.97036 -7.131725 7.063915 24.41015 -7.244692 6.955604 24.96456 -7.176786 7.062425 24.40454 -3.07882 8.907131 20.05024 -2.824919 8.973783 19.96649 -2.501549 8.980902 19.92642 -2.829855 8.987936 19.93895 -2.504105 8.995106 19.89866 -2.817114 8.923773 20.00219 -2.498219 8.930902 19.9626 -2.820528 8.951671 19.98829 -2.499521 8.95878 19.94845 -2.500455 8.970711 19.9383 -3.083967 8.935058 20.03662 -3.090306 8.957141 20.01507 -3.097208 8.971186 19.98773 -3.647224 8.836452 20.20513 -3.656127 8.864505 20.1924 -3.66674 8.886463 20.17158 -3.67797 8.900059 20.1448 -4.195037 8.721323 20.42558 -4.207545 8.749576 20.41411 -4.222362 8.77132 20.39426 -4.237879 8.784187 20.36819 -4.821013 8.609908 20.68778 -4.800855 8.59816 20.71288 -4.781527 8.576745 20.73137 -4.765297 8.54817 20.74109 -5.322963 8.411067 21.04984 -5.781584 8.184037 21.4726 -5.298592 8.400651 21.0738 -5.753103 8.175218 21.49513 -5.275223 8.37961 21.09076 -5.725864 8.154607 21.51029 -5.255841 8.350625 21.09856 -5.70367 8.125082 21.51595 -5.988492 8.065354 21.70105 -5.958044 8.057413 21.72274 -5.928983 8.03703 21.7369 -5.905557 8.007183 21.74147 -6.382281 7.806403 22.22737 -6.706946 7.552488 22.80216 -6.347809 7.800493 22.2469 -6.668748 7.54878 22.81889 -6.315109 7.780612 22.25874 -6.632804 7.529396 22.82812 -6.289429 7.749949 22.26099 -6.605416 7.497731 22.82822 -6.884316 7.392682 23.21499 -6.843832 7.390503 23.22935 -6.805974 7.371432 23.23664 -6.777747 7.338996 23.23551 -6.955493 7.15017 23.81791 -6.984481 7.183712 23.82027 -7.024498 7.20241 23.81581 -7.06766 7.202578 23.80542 -2.034731 8.993822 19.88081 -2.034731 8.986603 19.8962 -2.034731 8.970711 19.91691 -2.034731 8.95 19.9328 -2.034731 8.934614 19.94002 2.034731 8.993822 19.88081 2.034731 8.986603 19.8962 2.034731 8.970711 19.91691 2.034731 8.95 19.9328 2.034731 8.934614 19.94002 2.504105 8.995106 19.89866 2.501549 8.980902 19.92642 2.500455 8.970711 19.9383 2.499521 8.95878 19.94845 2.498219 8.930902 19.9626 7.176786 7.062425 24.40454 7.090222 7.045493 24.41166 7.131725 7.063915 24.41015 7.030522 7.195458 23.84089 7.060843 7.01096 24.40874 6.990427 7.176774 23.84522 6.793506 7.323489 23.27842 6.961416 7.143186 23.84283 6.102994 7.880733 21.99132 6.245117 7.782117 22.19342 6.554419 7.541466 22.72411 5.034945 8.44554 20.92639 5.20987 8.371215 21.06109 5.685803 8.135002 21.49725 6.859845 7.375047 23.27258 6.821805 7.356006 23.27966 6.616944 7.592411 22.71394 6.581544 7.572939 22.72364 6.302811 7.832613 22.17874 6.270545 7.812669 22.19089 6.158498 7.931097 21.97484 6.127598 7.910959 21.9879 5.734967 8.185131 21.47625 5.707887 8.164502 21.49149 5.251942 8.421238 21.03597 5.22896 8.400156 21.05309 5.074442 8.495548 20.89998 5.052914 8.474324 20.91768 4.547057 8.681178 20.56113 4.529727 8.659605 20.58027 3.983823 8.826622 20.28945 3.970824 8.804778 20.30975 3.679677 8.884319 20.17593 3.668968 8.862366 20.19674 4.515126 8.631185 20.59081 3.959861 8.776618 20.32181 3.65998 8.834308 20.20943 3.099388 8.956398 20.01699 3.092982 8.934316 20.03852 3.087776 8.906387 20.05213 7.073781 7.195547 23.83069 6.900551 7.377069 23.25848 6.654507 7.596518 22.69665 6.336795 7.838786 22.15891 6.190962 7.938061 21.95415 5.763278 8.19402 21.45366 5.275907 8.431797 21.01189 5.096885 8.506608 20.87546 4.565151 8.693466 20.53557 3.997483 8.839839 20.26305 3.691006 8.897901 20.14917 3.106358 8.970438 19.98966 7.127359 6.904997 24.96861 7.193765 6.793794 25.52751 7.157234 6.939595 24.97181 7.22415 6.828448 25.53101 7.199288 6.957734 24.97036 7.266768 6.846284 25.52961 7.244692 6.955604 24.96456 7.312513 6.843492 25.52362 7.320554 6.587623 26.69892 7.455637 6.547504 27.08246 7.434525 6.614252 26.69492 7.426193 6.552529 27.0853 7.394048 6.621697 26.69942 7.406237 6.550948 27.08636 7.353755 6.612283 26.70084 7.360978 6.530484 27.08577 7.353457 6.523872 27.08511 7.246107 6.076217 29.2181 7.267566 6.063346 29.22474 7.286301 6.071198 29.17259 7.222516 6.082947 29.20983 7.263631 6.084111 29.1663 7.23881 6.09038 29.15824 7.335018 6.171614 28.735 7.399095 6.15816 28.74516 7.367964 6.170279 28.74149 7.463296 6.276643 28.26854 7.424922 6.286549 28.26746 7.48249 6.388374 27.82399 7.438913 6.395743 27.82503 7.385946 6.28123 28.26251 7.3964 6.38413 27.82155 7.103936 6.057782 29.595 + + + + + + + + + + 0 1 0 0 1 1.44897e-6 0 1 0 -1 -6.28893e-7 0 -1 0 0 1 0 0 -0.6593707 -0.670494 -0.3401001 -0.177335 -0.606195 -0.7752934 -0.2432689 -0.5879281 -0.7714669 -0.6451345 -0.5396152 -0.5409409 -0.594372 -0.5113001 -0.6207207 -0.5133902 -0.5283614 -0.6762136 -0.4216708 -0.5570506 -0.7154638 -0.3058586 -0.7556873 -0.5791264 -0.5143165 -0.7862143 -0.3425573 -0.1040185 -0.8835904 -0.4565615 -0.2657872 -0.8746873 -0.4053138 -0.0741505 -0.9364649 -0.342834 -0.01970183 -0.9156775 -0.4014307 -0.1305155 -0.8874042 -0.4421309 -0.1304115 -0.8626784 -0.4886501 -0.1513627 -0.8490672 -0.5061367 -0.1304938 -0.8296407 -0.5428332 -0.1302608 -0.7798439 -0.6122709 -0.1302629 -0.7798432 -0.6122716 -0.1305078 -0.7283779 -0.6726317 -0.1477429 -0.6935502 -0.7050958 -0.1303781 -0.6838636 -0.7178664 -0.1304657 -0.6252276 -0.7694603 -0.06936436 -0.6108021 -0.7887392 -0.3822865 -0.800742 -0.4611611 -0.382008 -0.7938202 -0.4732012 -0.3820052 -0.7938205 -0.4732031 -0.3820052 -0.7268931 -0.5707001 -0.3820064 -0.7268934 -0.5706989 -0.3820089 -0.6480634 -0.6588499 -0.3820046 -0.648063 -0.6588527 -0.3825115 -0.5821253 -0.7175062 -0.2988619 -0.5777204 -0.759553 -0.5645943 -0.6597306 -0.4959726 -0.538573 -0.4120931 -0.7349276 -0.6079646 -0.6819876 -0.4065367 -0.6079657 -0.6819863 -0.4065372 -0.6079663 -0.6244864 -0.4902998 -0.6079649 -0.6244885 -0.4902988 -0.6079642 -0.5567654 -0.5660316 -0.6079644 -0.5567651 -0.5660318 -0.6085827 -0.5010575 -0.6152793 0 -1 0 0.4449535 -0.5514214 -0.7056564 0.6561554 -0.476517 -0.5851426 0.5670046 -0.6698476 -0.479385 0.02453559 -0.9387272 -0.3437868 -0.0235598 -0.9156015 -0.4013963 0.06218874 -0.9100813 -0.4097372 0.308492 -0.858962 -0.4086773 0.3710672 -0.7936347 -0.4821341 0.3888178 -0.5846151 -0.7120715 0.1074103 -0.6338046 -0.7659993 0.2071163 -0.5934528 -0.777764 0.3157887 -0.5741869 -0.7553721 0.03294157 -0.611943 -0.7902156 0.1304429 -0.6212149 -0.7727074 0.1303776 -0.6838635 -0.7178666 0.1477429 -0.6935502 -0.7050958 0.1305073 -0.7283781 -0.6726316 0.1302618 -0.7798433 -0.6122714 0.130262 -0.7798436 -0.6122709 0.1304935 -0.8296406 -0.5428334 0.1513627 -0.8490672 -0.5061367 0.1304113 -0.8626783 -0.4886503 0.1304965 -0.8914538 -0.4339135 0.1519771 -0.8731049 -0.4632396 0.3825305 -0.5834268 -0.7164382 0.3820055 -0.6480643 -0.6588509 0.3820074 -0.6480626 -0.6588515 0.3820058 -0.7268924 -0.5707007 0.3820053 -0.7268943 -0.5706986 0.3820065 -0.7938205 -0.4732021 0.3820073 -0.7938199 -0.4732023 0.3602233 -0.9278937 -0.09618985 0.4139979 -0.6659005 -0.6206306 0.6633455 -0.6673667 -0.338518 0.5349704 -0.4028595 -0.7426379 0.6079646 -0.6819871 -0.4065377 0.6079652 -0.6819872 -0.4065365 0.6079655 -0.6244879 -0.4902987 0.6079657 -0.6244869 -0.4902999 0.6079637 -0.556766 -0.5660316 0.6079641 -0.5567646 -0.5660325 0.6087399 -0.5236145 -0.5960399 0.552301 -0.5122532 -0.6576932 0.01374548 -0.938946 -0.34379 0 -0.5699985 -0.8216458 0 -0.5700075 -0.8216395 0.002062082 -0.6122757 -0.7906417 0.01302933 -0.6048604 -0.796225 -0.01466876 -0.6896774 -0.7239682 0 -0.6817278 -0.731606 0.003674507 -0.9822471 -0.1875559 -0.00860399 -0.9828309 -0.184308 -0.009490728 -0.9720031 -0.2347766 -0.004169344 -0.9742403 -0.2254738 -0.001834094 -0.9663913 -0.2570692 -2.16488e-5 -0.9821152 -0.1882817 7.51963e-5 -0.974857 -0.2228315 0.00377202 -0.9574623 -0.2885339 -0.008050262 -0.9829328 -0.1837887 -0.001652836 -0.9846895 -0.1743095 2.8515e-4 -0.9852914 -0.1708827 0 -0.9865333 -0.1635606 0.00505656 -0.9840391 -0.1778807 0.001175463 -0.9873471 -0.1585694 -0.002062082 -0.6122757 -0.7906417 -0.01302897 -0.6048602 -0.7962251 0.01466876 -0.6896778 -0.7239679 0 -0.6817288 -0.731605 0 -0.7346569 -0.6784388 0 -0.7346614 -0.678434 0 -0.7865458 -0.617532 0 -0.7865452 -0.6175327 0 -0.8367968 -0.5475138 0 -0.8367952 -0.5475161 0 -0.870109 -0.4928593 0 -0.9158558 -0.4015074 0 -0.9158563 -0.4015064 0 -0.9427378 -0.3335349 -2.20365e-4 -0.9390316 -0.343831 4.84531e-4 -0.9522271 -0.3053908 0.7070844 -0.7071291 0 -0.7070844 -0.7071291 0 -0.08043158 -0.1791856 -0.980522 -0.3170167 -0.785673 -0.5312422 -0.5961202 -0.8025294 0.02423578 -0.5732133 -0.8193637 0.008351683 -0.1558198 -0.7123876 -0.6842691 -0.1685401 -0.5920628 -0.788071 -0.103511 -0.5396135 -0.8355254 -0.1233299 -0.4936384 -0.8608781 -0.1240105 -0.3984797 -0.9087549 -0.553777 -0.791608 -0.2582396 -0.4366002 -0.8841203 -0.1664682 -0.4417881 -0.7673587 -0.4647409 -0.4420117 -0.7603671 -0.4758859 -0.3861223 -0.7633174 -0.5179345 -0.3865343 -0.6547334 -0.6495503 -0.2785082 -0.5787903 -0.7664433 -0.9997206 -2.97663e-6 0.02363866 -0.9873818 0.00254482 -0.1583374 -0.99131 -3.65318e-4 -0.1315467 -0.9480383 3.73051e-6 -0.3181562 -0.889362 -7.57725e-4 -0.4572031 -0.8533949 0.005667269 -0.5212342 -0.3476409 -4.66132e-5 -0.9376279 -0.4864718 1.73972e-4 -0.8736963 -0.5610973 0.00654006 -0.827724 -0.6585943 -9.79211e-6 -0.7524982 -0.766946 -1.08715e-5 -0.6417117 -0.3620315 -3.24092e-4 -0.9321659 -0.3620315 -3.22739e-4 -0.9321659 -0.3620315 -3.22698e-4 -0.9321658 -0.2319394 0.001128315 -0.9727296 -0.1607367 -0.003446996 -0.9869914 -0.05466073 -3.02491e-7 -0.998505 0 -0.5425271 -0.8400384 0 -0.1797686 -0.983709 0 -0.1797692 -0.9837089 0 -0.3682168 -0.9297401 -4.76757e-4 -0.5555697 -0.83147 -0.9724536 0.02040392 0.2322021 -0.9847075 -0.02788513 0.1719694 -0.9898124 0.02100843 0.1408193 -0.9943972 4.9217e-5 0.1057078 -0.9683034 -8.73527e-5 0.2497772 -0.9527223 -8.84973e-5 0.3038426 -0.9281755 0.08387696 0.362567 -0.9224459 0.0185045 0.3856827 -0.8869108 -0.006070494 0.4619011 -0.8730255 -0.03142833 0.4866607 -0.8305305 0.08556079 0.5503621 -0.8137002 1.31971e-5 0.5812849 -0.9985771 0.003375053 0.05322027 -0.998515 0.001851916 0.05444788 -0.9988053 -3.56162e-6 0.04886829 -0.9959946 4.84541e-5 0.08941346 -0.9963294 0.008718609 0.0851584 -0.9965399 0.002194821 0.08308726 -0.9982213 -3.49619e-4 0.05961656 -0.9978464 5.10409e-4 0.06559264 -0.9975482 0.004881799 0.06981271 -0.9974613 0.003082692 0.07114464 -0.9969568 -8.71687e-4 0.07795196 -0.614323 -0.7886825 0.02423048 -0.1323614 -0.1347737 -0.9819962 -0.4862812 -0.02753555 -0.8733685 -0.3475387 -0.01976436 -0.9374574 -0.1417613 -0.136896 -0.9803894 -0.1495387 -0.1134501 -0.9822257 -0.1555843 -0.1239383 -0.9800168 -0.1627106 -0.09534692 -0.9820562 -0.1687873 -0.1036226 -0.9801904 -0.1735533 -0.07570803 -0.9819102 -0.1795229 -0.08214426 -0.9803183 -0.1817563 -0.054677 -0.9818223 -0.1872654 -0.05939048 -0.9805124 -0.1875981 -0.03285878 -0.9816962 -0.1919656 -0.03582823 -0.9807475 -0.1914631 -0.02438247 -0.9811969 -0.1607264 -0.009911894 -0.9869493 -0.7662165 -0.04343211 -0.6411131 -0.65813 -0.03752726 -0.7519686 -0.9856155 -0.05997699 -0.1580033 -0.8883869 -0.04698669 -0.4566849 -0.9986438 -0.04639399 0.02362757 -0.9851992 -0.0587337 -0.1610378 -0.9784941 -0.1704735 -0.116138 -0.9718897 -0.1424582 -0.1874464 -0.953939 -0.2863715 -0.0893976 -0.9481813 -0.2454889 -0.2017118 -0.9288402 -0.3522952 -0.1146475 -0.9027574 -0.3936008 -0.1735159 -0.8943945 -0.4247082 -0.1402908 -0.7477799 -0.6270582 -0.2182279 -0.8088743 -0.5709493 -0.1404968 -0.8541876 -0.5006796 -0.1402986 -0.8307955 -0.5186332 -0.2019863 -0.8694588 -0.473667 -0.1402893 -0.4794441 -0.5891106 -0.6504476 -0.3083538 -0.3706764 -0.8760805 -0.1232607 -0.1556977 -0.9800843 -0.1218591 -0.1495224 -0.9812204 -0.252462 -0.310171 -0.9165462 -0.7946627 -0.6034763 -0.06578463 -0.708006 -0.6845923 -0.173381 -0.6825647 -0.7221278 -0.1124143 -0.6214372 -0.763935 -0.173837 -0.619081 -0.7670475 -0.1684548 -0.8500992 -0.07103389 -0.52181 -0.8406793 -0.1465517 -0.5213263 -0.8412082 -0.1472444 -0.5202769 -0.8179239 -0.2456144 -0.5202636 -0.8182003 -0.2460838 -0.5196068 -0.7831999 -0.3414753 -0.5196081 -0.7832808 -0.3416601 -0.5193647 -0.7372422 -0.4321214 -0.5193699 -0.7372095 -0.4320153 -0.5195045 -0.6805396 -0.5167178 -0.5194888 -0.6804639 -0.5162951 -0.520008 -0.6140486 -0.5937377 -0.5200193 -0.61401 -0.5930185 -0.5208847 -0.5533121 -0.6496831 -0.5213038 -0.5550967 -0.681433 -0.4769871 -0.5608258 -0.05901235 -0.8258281 -0.5561866 -0.09700506 -0.8253766 -0.5566837 -0.09744042 -0.8249902 -0.5412786 -0.1625722 -0.8249775 -0.541546 -0.1628725 -0.8247428 -0.5183784 -0.226024 -0.8247405 -0.518468 -0.226154 -0.8246486 -0.4879966 -0.286022 -0.8246519 -0.4879524 -0.2859441 -0.8247051 -0.4504571 -0.3419951 -0.8246986 -0.4503377 -0.3416925 -0.8248893 -0.4064078 -0.392906 -0.8248985 -0.406273 -0.3923838 -0.8252136 -0.3760579 -0.4205431 -0.8256659 -0.4023296 -0.4940183 -0.7707638 -0.4156666 -0.8947116 -0.1634401 -0.04816603 -0.9985513 0.02399003 -0.00990951 -0.8387347 -0.5444502 -0.01193726 -0.8398815 -0.5426386 -0.2968827 -0.8808867 -0.3686454 -0.2186409 -0.8522147 -0.4753172 -0.1851334 -0.8688914 -0.4590789 -0.131596 -0.8560553 -0.4998519 -0.03125298 -0.9828091 -0.1819609 -0.05276042 -0.9872747 -0.1500167 -0.0941298 -0.9817479 -0.1652596 -0.2221509 -0.8551452 -0.4683755 -0.0792706 -0.7683907 -0.6350527 -0.0735321 -0.7657524 -0.6389182 -0.05153417 -0.7713196 -0.6343583 -0.04092502 -0.7747003 -0.6310029 -0.03205704 -0.8373907 -0.5456641 -0.07034689 -0.83439 -0.546667 -0.0604577 -0.8366996 -0.544315 -0.05657994 -0.835246 -0.5469579 -0.03679364 -0.838367 -0.5438632 -0.0343064 -0.8371314 -0.545925 -0.0214653 -0.8381964 -0.544946 -0.5302454 -0.8450924 0.06825578 -0.5209361 -0.8525073 0.04309242 -0.4646133 -0.88152 -0.08400619 -0.3899942 -0.8704352 -0.3004118 -0.2988637 -0.9192205 -0.2563478 -0.2858914 -0.919685 -0.2691574 -0.2479664 -0.9348937 -0.253942 -0.2372583 -0.934309 -0.2660359 -0.1080705 -0.9823162 -0.1528913 -0.141815 -0.9771682 -0.1582117 -0.1555901 -0.9737941 -0.1658822 -0.1918178 -0.9713178 -0.1405261 -0.2354136 -0.9539648 -0.185827 -0.06330835 -0.7707809 -0.6339472 -0.06267637 -0.7782288 -0.6248453 -0.1600415 -0.8698362 -0.4666603 -0.120497 -0.8826951 -0.4542355 -0.1906666 -0.948973 -0.2511908 -0.1718438 -0.9850302 -0.01361322 -0.3152289 -0.9471884 -0.05886262 -0.3598042 -0.9330228 0.003073811 -0.3760506 -0.9240586 -0.0685696 -0.4096118 -0.9109102 -0.04960936 -0.4228811 -0.9044476 -0.05609166 0.002279102 0.9991366 0.04148364 0.04417312 -0.7911474 0.6100283 0.1253226 0.2237356 0.9665592 0.1395785 -0.002044558 0.9902089 0.1873081 -0.00198698 0.9822993 0.1886305 0.269159 0.9444427 0.2592283 -0.2334619 0.9371746 0.2873362 0.1844262 0.9399068 0.3295212 -4.50623e-5 0.9441483 0.3730269 -1.8356e-5 0.9278206 0.3880406 0.2573966 0.8849698 0.4428216 -0.1059762 0.8903248 0.490081 0.04673361 0.8704233 0.5062382 -8.06433e-5 0.8623937 0.5386723 -7.11442e-5 0.8425155 0.5456159 -0.02777725 0.837575 0.6005713 0.0520243 0.797877 0.6107882 -0.01023095 0.791728 0.7485275 -2.29501e-5 0.6631038 0.7506003 -0.01113063 0.6606627 0.6827185 0.01133894 0.7305936 0.6965433 -0.09284424 0.7114825 0.6613562 0.004455447 0.7500588 -0.536132 -6.90944e-5 0.8441343 -0.02789014 0.8735566 0.4859228 -0.09428828 -0.7063174 0.7015878 -0.2671462 0.3644706 0.892073 -0.2150759 -0.3923742 0.894307 -0.1707822 0.4406899 0.8812639 -0.08873873 -0.736338 0.6707696 -0.4858162 -7.99639e-5 0.8740611 -0.4968985 0.08515679 0.8636205 -0.4238817 -0.07941687 0.9022291 -0.3857247 0.2319771 0.8929743 -0.3628296 4.04157e-5 0.9318555 -0.3156114 8.04095e-6 0.9488886 -0.5906091 0.1939209 0.7833108 -0.5793324 0.01209753 0.8150016 -0.6558237 -0.005151271 0.7548965 -0.6574967 -5.48685e-5 0.7534575 -0.6935696 -4.45594e-5 0.7203897 -0.6960299 0.005195677 0.7179941 -0.7397572 -0.01048988 0.6727923 -0.7472642 0.01874649 0.6642627 -0.7751576 1.8515e-5 0.6317681 -0.6738934 -0.6547017 0.3423936 -0.6874242 -0.6399472 0.3433885 -0.6922277 -0.6355122 0.3419724 -0.6827039 -0.6446854 0.3439423 -0.706389 -0.6247189 0.3327777 -0.7106775 -0.6222302 0.3282792 -0.7018012 -0.6278265 0.3366143 -0.6970348 -0.6314646 0.3396983 -0.7198382 -0.6187982 0.3145185 -0.7226719 -0.6185995 0.3083504 -0.7170087 -0.619483 0.3195925 -0.7141817 -0.6205654 0.3237949 -0.7931259 -0.134047 0.5941236 -0.7379097 -0.649595 0.1830728 -0.726414 -0.6204108 0.2956573 -0.7248003 -0.6192024 0.3020811 -0.1942309 -0.8739026 0.4456104 -0.6010736 -0.4880517 0.6328634 -0.5986567 -0.4877995 0.6353438 -0.53154 -0.6553044 0.5366949 -0.5165945 -0.6753169 0.5263813 -0.4526309 -0.6565954 0.6033306 -0.1229153 -0.9205128 0.370875 -0.1132606 -0.9049705 0.4101223 -0.05887693 -0.9474493 0.3144415 -0.2720886 -0.8673349 0.4167713 -0.2038093 -0.906538 0.3696629 -0.1476539 -0.9169598 0.3706523 -0.4615908 -0.7329857 0.499666 -0.4030208 -0.8432387 0.3557006 -0.3509893 -0.8639941 0.3609998 -0.6574918 -0.6813597 0.3216419 -0.5800209 -0.7522211 0.312633 -0.5821443 -0.7560408 0.2991827 -0.4572179 -0.7970803 0.3944803 -0.8686526 -0.462246 0.1782453 -0.9029186 -0.3151544 0.2922596 -0.9754795 -0.1354364 0.1734848 -0.993215 -0.04887109 0.1055257 -0.9909459 -0.04743283 0.1256039 -0.9811322 -0.002923429 0.1933164 -0.9834678 -0.05744993 0.1717287 -0.9681127 -0.01972508 0.2497375 -0.9564171 -0.04110318 0.2890969 -0.9525443 -0.01906335 0.3038028 -0.9283843 -0.02214741 0.3709612 -0.9225212 0.01336616 0.3857151 -0.7705579 -0.05110943 0.6353176 -0.813575 -0.01666611 0.5812211 -0.8136745 -0.01685291 0.5810765 -0.8727208 -0.04113024 0.4864839 -0.8406322 0.08724361 0.5345336 -0.892046 -0.0410034 0.4500806 -0.7803943 -0.1383705 0.6097855 -0.7008978 -0.3137288 0.6405595 -0.7016498 -0.333438 0.6296878 -0.7021666 -0.3090459 0.6414458 -0.7275072 -0.2566549 0.6362872 -0.7417213 -0.2507927 0.6220551 -0.6704671 -0.3995366 0.6251755 -0.6793351 -0.3797714 0.6279153 -0.6284768 -0.4304631 0.6478569 -0.6296178 -0.4521918 0.6317468 -0.6513285 -0.415463 0.6349501 -0.787313 -0.125395 0.6036674 -0.8220875 -0.1088644 0.5588565 -0.8220922 -0.108869 0.558849 -0.8559922 -0.09614264 0.5079705 -0.8559926 -0.09614169 0.50797 -0.8909466 -0.08705985 0.4456847 -0.8909423 -0.08706122 0.445693 -0.924517 -0.08527696 0.3714783 -0.9245153 -0.08527618 0.3714831 -0.9511462 -0.09199327 0.2947172 -0.9511467 -0.09199279 0.2947159 -0.9703043 -0.1070932 0.2168886 -0.9703041 -0.1070909 0.2168906 -0.9829188 -0.1342427 0.1258951 -0.9465354 -0.2295091 0.2267078 -0.965097 -0.2355951 0.1143805 -0.9509124 -0.200132 0.2360359 -0.9509133 -0.2001294 0.2360343 -0.9343851 -0.1871057 0.3031764 -0.9343863 -0.1871104 0.3031701 -0.911412 -0.1813213 0.3693926 -0.9114127 -0.1813161 0.3693932 -0.8824573 -0.1828551 0.4333974 -0.8824545 -0.1828472 0.4334063 -0.8522692 -0.1906993 0.4871047 -0.8522706 -0.1907016 0.4871016 -0.8230292 -0.201677 0.5309891 -0.823024 -0.2016777 0.5309969 -0.7861781 -0.2189875 0.5779002 -0.7861843 -0.2189871 0.5778918 -0.7482786 -0.2412896 0.6179471 -0.7364526 -0.1715 0.6543894 -0.9372459 -0.3423336 0.06616514 -0.9226178 -0.2911901 0.2529525 -0.9226216 -0.2911846 0.2529448 -0.9088777 -0.2803604 0.308771 -0.908876 -0.2803578 0.3087784 -0.8897785 -0.2755376 0.3638315 -0.8897748 -0.2755337 0.3638435 -0.8656948 -0.2768105 0.4170714 -0.8656993 -0.2768154 0.4170587 -0.8405632 -0.2833555 0.4616959 -0.8405582 -0.2833566 0.4617043 -0.8162472 -0.2924777 0.4981941 -0.8162459 -0.2924832 0.498193 -0.7856375 -0.3068674 0.5372207 -0.7856355 -0.3068693 0.5372226 -0.7481133 -0.3287282 0.5764237 -0.748103 -0.3287299 0.5764361 -0.708301 -0.355663 0.6097652 -0.708303 -0.3556644 0.609762 -0.6870505 -0.3722476 0.6240139 -0.6717089 -0.33494 0.6607742 -0.52087 -0.6727208 0.5254914 -0.5523356 -0.623826 0.5529617 -0.5515006 -0.6245 0.5530342 -0.6000816 -0.5762857 0.5547946 -0.5791532 -0.5956626 0.5565678 -0.5249925 -0.6491799 0.5504075 -0.6239137 -0.5846585 0.5185618 -0.6472834 -0.5611919 0.5158371 -0.6472871 -0.5611916 0.5158329 -0.6711319 -0.5391877 0.5087814 -0.6711462 -0.5391795 0.5087715 -0.6950516 -0.5190227 0.4975128 -0.6950618 -0.5190145 0.497507 -0.718528 -0.5011284 0.4822734 -0.7185422 -0.5011185 0.4822629 -0.7411554 -0.4858169 0.4633257 -0.7411596 -0.4858105 0.4633256 -0.7624707 -0.4733992 0.4410575 -0.7624678 -0.4734057 0.4410556 -0.7798362 -0.4652178 0.4188412 -0.7798279 -0.4652165 0.4188581 -0.793642 -0.4600359 0.39812 -0.7936382 -0.4600378 0.3981251 -0.8079618 -0.4563221 0.3727843 -0.807967 -0.4563132 0.3727837 -0.8216401 -0.4555972 0.3425477 -0.8216375 -0.4555988 0.3425517 -0.8324952 -0.4583334 0.3112593 -0.8324971 -0.4583326 0.3112555 -0.8403033 -0.4644837 0.2795453 -0.8402978 -0.4644927 0.2795463 -0.833822 -0.4529487 0.3155604 -0.8086371 -0.5592113 0.1827262 -0.8833733 -0.3756757 0.2802132 -0.8856002 -0.3796686 0.2675144 -0.8855956 -0.3796777 0.2675172 -0.8747804 -0.3711364 0.3114755 -0.8747751 -0.3711459 0.3114792 -0.8597271 -0.36735 0.3548569 -0.8597311 -0.3673509 0.3548461 -0.840761 -0.3683607 0.3967765 -0.8407608 -0.3683592 0.3967783 -0.8209403 -0.3735091 0.4319122 -0.8209358 -0.3735176 0.4319133 -0.8017896 -0.3807007 0.4606524 -0.8017815 -0.3807012 0.460666 -0.7777022 -0.3920264 0.4914212 -0.777701 -0.3920329 0.4914178 -0.7481532 -0.4092434 0.5222898 -0.7481474 -0.4092466 0.5222955 -0.71678 -0.4304729 0.5485615 -0.7167966 -0.430465 0.5485458 -0.6842377 -0.4552837 0.5696804 -0.6842151 -0.4552928 0.5697003 -0.6510838 -0.4832311 0.5853013 -0.6510813 -0.4832334 0.5853022 -0.6180211 -0.5137412 0.5950798 -0.6180123 -0.5137465 0.5950844 -0.5870977 -0.5448384 0.5987216 -0.5605077 -0.5215311 0.6433013 -0.6781431 -0.6496585 0.3436073 -0.670004 -0.659753 0.3403244 -0.7758565 -0.5251813 0.3496159 -0.787004 -0.5450856 0.2889751 -0.7870203 -0.5450694 0.2889611 -0.7822814 -0.5413817 0.308126 -0.7823023 -0.5413647 0.3081028 -0.7757679 -0.5397055 0.326959 -0.7757423 -0.5397167 0.3270013 -0.7674926 -0.5401404 0.3452587 -0.7674896 -0.5401528 0.345246 -0.7588346 -0.5423897 0.3605323 -0.7588488 -0.5423763 0.3605226 -0.7504875 -0.545528 0.3730521 -0.750496 -0.5455191 0.3730477 -0.7400611 -0.5504384 0.3864288 -0.7400391 -0.5504543 0.3864482 -0.727175 -0.5579424 0.399896 -0.7271755 -0.5579454 0.399891 -0.7135196 -0.5671864 0.4113264 -0.713523 -0.567183 0.4113253 -0.6993227 -0.5780084 0.4205402 -0.6993472 -0.5779923 0.4205216 -0.6849045 -0.5901715 0.4273213 -0.6849163 -0.5901613 0.4273165 -0.6705427 -0.6034228 0.4315708 -0.6705133 -0.6034475 0.4315822 -0.6564041 -0.6176119 0.4332314 -0.6564208 -0.6175978 0.4332261 -0.6428703 -0.6323766 0.432224 -0.6428569 -0.6323909 0.4322232 -0.6301563 -0.6474595 0.4286016 -0.6301699 -0.6474479 0.4285992 -0.6185244 -0.6625756 0.4223992 -0.618512 -0.6625849 0.422403 -0.4153353 -0.7157781 0.5613898 -0.4114678 -0.7167459 0.5630007 -0.4933661 -0.7113936 0.5005087 -0.4933633 -0.7113952 0.5005094 -0.5997633 -0.6910037 0.4034821 -0.5997671 -0.6909897 0.4035007 -0.663736 -0.6692525 0.3339997 -0.4313006 -0.6802157 0.5926944 -0.4485245 -0.6812446 0.5785599 -0.5103729 -0.6840277 0.5211772 -0.5103742 -0.6840284 0.521175 -0.6083584 -0.6771758 0.4139239 -0.6083493 -0.6771853 0.4139217 -0.6665892 -0.6646552 0.3374794 -0.3047472 -0.8326912 0.4623361 -0.3493284 -0.790422 0.5031927 -0.468188 -0.7625117 0.4465155 -0.4681822 -0.7625217 0.4465045 -0.5870358 -0.7168434 0.3761975 -0.5870585 -0.7168172 0.3762122 -0.659475 -0.6779031 0.3248695 -0.3539223 -0.7573546 0.5487741 -0.3612276 -0.7551199 0.5470913 -0.4791313 -0.7377539 0.475555 -0.4791349 -0.7377483 0.4755598 -0.592574 -0.7043211 0.390881 -0.5925592 -0.7043427 0.3908646 -0.661305 -0.6737513 0.3297499 -0.4576959 -0.8039206 0.3797711 -0.4576925 -0.8039295 0.3797566 -0.5817363 -0.7377655 0.342469 -0.5817351 -0.7377516 0.3425011 -0.6577014 -0.6849076 0.3135768 -0.2772285 -0.8559146 0.4365256 -0.278191 -0.8715943 0.40365 -0.2872118 -0.8631271 0.4153565 -0.3044729 -0.8301009 0.4671497 -0.4609951 -0.7847151 0.4143741 -0.461 -0.7847067 0.4143844 -0.583415 -0.728042 0.3599746 -0.5834078 -0.7280585 0.3599528 -0.6582399 -0.6816884 0.3194077 0 -0.7071058 -0.7071078 8.34513e-6 -0.7070945 -0.7071191 -2.92622e-5 -0.7071333 -0.7070803 9.56315e-6 -0.7070853 -0.7071284 -1.82726e-5 -0.7071284 -0.7070853 1.99124e-5 -0.7070986 -0.7071151 0 -0.7071053 -0.7071083 -7.4916e-6 -0.7070958 -0.7071177 1.7408e-5 -0.7071355 -0.7070781 -1.12926e-5 -0.7070826 -0.707131 3.20942e-5 -0.7072075 -0.707006 -2.58981e-6 -0.707101 -0.7071126 1.48034e-5 -0.7071265 -0.707087 -3.32655e-6 -0.707116 -0.7070977 -1.54103e-5 -0.7071134 -0.7071002 3.66208e-5 -0.7071177 -0.7070959 0.5961582 -0.8025015 0.02422779 0.5732133 -0.8193637 0.008351683 0.569337 -0.8137886 -0.1166343 0.6233446 -0.7635979 -0.1684041 0.4308389 -0.8487927 -0.3064785 0.4420154 -0.7603673 -0.4758822 0.3861212 -0.7633176 -0.517935 0.3865476 -0.6547294 -0.6495463 0.2785135 -0.5787879 -0.766443 0.3170155 -0.7856726 -0.5312438 0.1558222 -0.7123914 -0.6842646 0.1685402 -0.5920644 -0.7880699 0.118026 -0.5516864 -0.8256586 0.1398935 -0.4837749 -0.8639397 0.1239043 -0.365384 -0.9225738 0.1240089 -0.3984777 -0.9087559 0.08043158 -0.1791856 -0.980522 0.7667935 -6.46556e-7 -0.6418939 0.1585783 -9.29295e-5 -0.9873465 0.1983027 0.003672182 -0.980134 0.3456457 1.15165e-4 -0.9383651 0.5652679 -6.1131e-4 -0.8249071 0.4881725 0.01048952 -0.8726842 0.6582682 -7.10448e-7 -0.7527836 0.8899915 0.009129226 -0.455886 0.845624 -0.002626001 -0.5337725 0.9849146 0.001952886 -0.1730306 0.9878365 0.003690838 -0.1554521 0.9999548 0 0.009516239 0.9889243 -4.91028e-5 0.1484212 0.9904813 -0.05366009 0.1267572 0.9631406 0.07415199 0.2585763 0.9734683 -0.07326507 0.2167761 0.9277997 0.07300978 0.3658653 0.7858723 -2.84064e-5 0.6183888 0.7870498 -8.51046e-4 0.616889 0.8159034 0.003312408 0.578179 0.8254551 -0.02558356 0.5638877 0.8604282 0.01755154 0.5092694 0.8682117 0 0.4961941 0.8889594 0 0.4579863 0.8948745 -0.009840428 0.4462095 0.9129914 0.01466625 0.4077153 0.9429133 -0.08652788 0.3216013 -0.04286128 -0.9934418 0.1060019 -0.03895282 -0.9829897 0.1794831 -0.03705179 -0.9671457 0.2515086 -0.06574743 -0.9847206 0.1612533 -0.04725307 -0.9951347 0.08645373 -0.1318105 -0.9892045 0.06403601 -0.1354345 -0.9885732 0.06618642 -0.1741356 -0.9827424 0.06240481 -0.2288216 -0.9713016 0.06491434 -0.2310512 -0.9708654 0.06352669 -0.2991276 -0.9519438 0.06576997 -0.322123 -0.9439064 0.07264775 -0.3748917 -0.9252982 0.05726754 -0.4538038 -0.8869758 0.08565175 -0.4151114 -0.9073813 0.06589353 -0.46491 -0.8828459 0.06664705 -0.5050642 -0.8604148 0.06779932 -0.5265906 -0.8481685 0.0575549 -0.5908542 -0.8037607 0.06971383 -0.613129 -0.7873578 0.06434893 -0.6711022 -0.7381995 0.06843483 -0.6852913 -0.7255581 0.06278055 -0.7441563 -0.6643283 0.06999522 -0.7645354 -0.6416121 0.06180232 -0.809014 -0.5835483 0.07048225 -0.8149887 -0.5754578 0.06813108 -0.8464607 -0.5285308 0.06449377 -0.8647885 -0.4972702 0.06973654 -0.876281 -0.4773951 0.06500566 -0.9110863 -0.4072725 0.06364619 -0.9010043 -0.4277841 0.07205539 -0.947686 -0.3152589 0.05003255 -0.9326378 -0.3535683 0.07194751 -0.9738746 -0.2215582 0.04980331 -0.9661707 -0.2496661 0.06466251 -0.990433 -0.128256 0.0509206 -0.9878612 -0.1440227 0.05820387 -0.9976514 -0.04631346 0.05046576 -0.9976534 -0.0462886 0.05044972 -0.9932441 -0.04898726 0.1051982 -0.9937891 -0.03539687 0.1055002 -0.9845283 -0.1214429 0.1263156 -0.9789006 -0.1466608 0.1422823 -0.9656071 -0.210147 0.1531052 -0.9527618 -0.248524 0.174588 -0.4819949 -0.8161296 0.3187686 -0.5808408 -0.755499 0.3030601 -0.5688236 -0.7617646 0.310088 -0.6605997 -0.6932501 0.2881186 -0.6505987 -0.6999892 0.2945105 -0.7340899 -0.6219143 0.2726438 -0.7251662 -0.6292224 0.2796664 -0.8054513 -0.5379661 0.2486776 -0.7916966 -0.5518003 0.26217 -0.86627 -0.4478467 0.2213813 -0.8492426 -0.4690126 0.2425165 -0.9159599 -0.3529037 0.1909884 -0.8971551 -0.3822606 0.2213358 -0.9370837 -0.2991264 0.1799936 -0.2982714 -0.8971818 0.3257288 -0.3542354 -0.8764993 0.3259851 -0.3916285 -0.862548 0.3203722 -0.4060454 -0.8548693 0.3229951 -0.4873282 -0.8139591 0.3161991 -0.02814185 -0.9474211 0.3187499 -0.05777788 -0.943377 0.3266521 -0.1112096 -0.9404418 0.3212501 -0.1516053 -0.9323274 0.3283012 -0.2044894 -0.9236291 0.3241813 -0.2079635 -0.9225845 0.3249448 -0.2809359 -0.900906 0.3308224 -0.9963501 -0.04522556 0.07239669 -0.9967219 -0.03478962 0.07304304 -0.9880786 -0.1267731 0.08734649 -0.988187 -0.1258199 0.0874983 -0.9705245 -0.2186638 0.101333 -0.9707214 -0.2177103 0.1015007 -0.943431 -0.3110734 0.1147669 -0.943715 -0.3101437 0.1149475 -0.90647 -0.4025968 0.1273888 -0.9068384 -0.4017052 0.1275824 -0.8595964 -0.4917196 0.1389466 -0.8600471 -0.4908714 0.1391554 -0.803079 -0.5768905 0.1492037 -0.80361 -0.576093 0.1494255 -0.7375172 -0.6565975 0.1579495 -0.7381233 -0.6558593 0.1581856 -0.6638155 -0.7294642 0.1650184 -0.6644881 -0.7287952 0.1652672 -0.5831608 -0.794307 0.1702935 -0.5838955 -0.793711 0.1705549 -0.4969428 -0.8502175 0.173719 -0.4977299 -0.8497007 0.1739937 -0.4066814 -0.8965935 0.1753007 -0.4075134 -0.8961601 0.1755847 -0.3139562 -0.9331526 0.1750942 -0.3148183 -0.9328069 0.1753877 -0.2202901 -0.9599328 0.1732091 -0.2211848 -0.9596719 0.173514 -0.1271262 -0.9772449 0.1697987 -0.1280252 -0.9770742 0.1701051 -0.04485934 -0.9851732 0.1655944 -0.9968214 -0.04668301 0.06455892 -0.9972607 -0.03388375 0.06574988 -0.9888893 -0.1273918 0.0766108 -0.9889711 -0.1266682 0.07675486 -0.9716554 -0.2198032 0.08701956 -0.9718036 -0.2190856 0.08717417 -0.9448764 -0.3127574 0.09690976 -0.9450894 -0.3120629 0.09707129 -0.9082251 -0.4048144 0.1060783 -0.908504 -0.4041432 0.1062501 -0.861649 -0.4944573 0.1143376 -0.86199 -0.4938205 0.1145192 -0.8054111 -0.5801279 0.1215099 -0.8058152 -0.5795263 0.121701 -0.740105 -0.6603052 0.1274429 -0.7405661 -0.6597498 0.1276412 -0.6666331 -0.7336018 0.132018 -0.6671444 -0.7330998 0.1322245 -0.5861775 -0.7988288 0.1351613 -0.5867388 -0.7983802 0.135376 -0.5001247 -0.8550723 0.1368455 -0.5007237 -0.8546863 0.1370666 -0.409996 -0.901726 0.1370893 -0.4106264 -0.901405 0.1373139 -0.3173606 -0.9385089 0.1359531 -0.3180202 -0.9382526 0.1361817 -0.2237621 -0.9654527 0.1335346 -0.224436 -0.9652641 0.1337676 -0.1306146 -0.9828782 0.1299636 -0.1313102 -0.9827541 0.1302008 -0.03777903 -0.9913988 0.1253054 -0.04796653 -0.990563 0.128391 -0.997235 -0.04818612 0.05657386 -0.9977464 -0.03287482 0.0584923 -0.9896137 -0.1278034 0.06581228 -0.989669 -0.1273128 0.06593042 -0.9726585 -0.220594 0.07262039 -0.9727565 -0.220122 0.07274061 -0.9461531 -0.313948 0.078938 -0.9463 -0.3134716 0.07906836 -0.9097729 -0.4063871 0.08463436 -0.9099634 -0.405932 0.08476901 -0.8634545 -0.4964103 0.08957272 -0.8636874 -0.4959799 0.0897116 -0.8074634 -0.5824389 0.09363788 -0.807735 -0.582039 0.09378027 -0.7423801 -0.6629589 0.09673398 -0.742693 -0.6625868 0.09688168 -0.6691081 -0.7365688 0.09879755 -0.6694571 -0.7362311 0.09895014 -0.5888279 -0.8020742 0.09979444 -0.5892047 -0.8017781 0.09994828 -0.5029156 -0.8585637 0.09972208 -0.503324 -0.858306 0.09987938 -0.4128977 -0.9054226 0.09861749 -0.4133312 -0.9052074 0.09877735 -0.3203465 -0.942368 0.09654462 -0.3207883 -0.9422015 0.09670233 -0.2267944 -0.9694359 0.09358716 -0.2272585 -0.9693116 0.09374845 -0.1336788 -0.9869425 0.08985847 -0.1341468 -0.9868645 0.09001827 -0.04965776 -0.9950687 0.08586227 -0.04065513 -0.9977232 0.05381226 -0.04936426 -0.996994 0.05971932 -0.9952484 -0.04234617 0.08767747 -0.995488 -0.0362398 0.08769518 -0.9862031 -0.1249405 0.1085973 -0.9863691 -0.1235221 0.1087116 -0.9678992 -0.2153223 0.1296445 -0.9681912 -0.213922 0.1297818 -0.9400613 -0.3062096 0.1500685 -0.9404757 -0.3048554 0.150229 -0.9023656 -0.3962402 0.1694993 -0.9029083 -0.3949216 0.1696865 -0.8547913 -0.4838924 0.1875637 -0.8554506 -0.482643 0.1877768 -0.7976103 -0.5676627 0.2039047 -0.798391 -0.5664769 0.2041469 -0.7314394 -0.6460534 0.2182003 -0.7323253 -0.644958 0.2184697 -0.6571965 -0.7177102 0.2301845 -0.6581793 -0.7167136 0.2304815 -0.5760637 -0.781481 0.2396623 -0.5771366 -0.7805887 0.2399892 -0.4894537 -0.836458 0.2465221 -0.4906032 -0.8356799 0.2468762 -0.3988838 -0.8820559 0.2507376 -0.4000922 -0.8814006 0.2511163 -0.3059285 -0.9179987 0.2523612 -0.3071842 -0.9174681 0.2527652 -0.212122 -0.9443199 0.2515234 -0.21341 -0.9439163 0.251949 -0.11889 -0.9613301 0.2484145 -0.1202049 -0.9610511 0.2488609 -0.05771213 -0.9677221 0.2453225 -0.0377075 -0.9718497 0.2325651 -0.9946233 -0.04095929 0.09511536 -0.9947977 -0.03674948 0.09501087 -0.9851483 -0.1237088 0.1190761 -0.9853417 -0.1220909 0.119145 -0.966415 -0.2131276 0.143592 -0.9667531 -0.2115231 0.1436888 -0.9381465 -0.3030523 0.1674531 -0.9386307 -0.3014788 0.1675801 -0.9000372 -0.3921033 0.1902315 -0.9006606 -0.3905921 0.19039 -0.8520584 -0.4788195 0.2114912 -0.8528216 -0.4773732 0.2116846 -0.7944985 -0.5616882 0.2308216 -0.7953944 -0.5603246 0.2310505 -0.7279778 -0.6392357 0.2478427 -0.7289962 -0.6379708 0.2481086 -0.6534241 -0.7101174 0.2622409 -0.6545545 -0.7089633 0.2625442 -0.572021 -0.7731977 0.2737837 -0.573249 -0.772167 0.2741238 -0.4851824 -0.8275803 0.2823279 -0.4865001 -0.8266773 0.2827053 -0.3944326 -0.8726823 0.2878345 -0.3958202 -0.8719173 0.288248 -0.301344 -0.9082323 0.290355 -0.3027873 -0.9076083 0.2908041 -0.2074541 -0.9342619 0.2900307 -0.2089409 -0.933781 0.2905114 -0.1141817 -0.9510803 0.2870699 -0.1156907 -0.9507439 0.287579 -0.03828895 -0.9583911 0.2828791 -0.03304928 -0.9590229 0.2813944 -0.9958249 -0.04375988 0.08011269 -0.9961296 -0.03557986 0.08037304 -0.9871811 -0.1259566 0.09802281 -0.9873184 -0.1247634 0.09816545 -0.9692714 -0.2171615 0.1155589 -0.9695131 -0.2159939 0.1157191 -0.9418232 -0.3088877 0.1325046 -0.9421735 -0.3077403 0.1326845 -0.9045131 -0.3997363 0.1485499 -0.9049696 -0.3986274 0.1487491 -0.8573081 -0.4881905 0.16338 -0.8578628 -0.4871419 0.1635982 -0.8004746 -0.5727301 0.1766936 -0.8011316 -0.5717371 0.1769325 -0.7346222 -0.6518434 0.1882296 -0.7353696 -0.650925 0.1884892 -0.660665 -0.7241611 0.1977688 -0.661497 -0.7233246 0.1980484 -0.5797824 -0.7885197 0.2051567 -0.580691 -0.7877723 0.2054577 -0.4933807 -0.8440054 0.2103102 -0.4943485 -0.8433594 0.2106289 -0.4029731 -0.8900294 0.2132142 -0.4039961 -0.8894848 0.2135509 -0.3101341 -0.9263107 0.2139284 -0.3112042 -0.9258698 0.2142826 -0.2164034 -0.9528812 0.2125725 -0.2174975 -0.9525498 0.2129407 -0.1232109 -0.9700552 0.2093133 -0.1243239 -0.9698312 0.2096933 -0.03774261 -0.9780862 0.2047509 -0.04204934 -0.9776428 0.2060258 1.59505e-7 -0.999711 0.02404266 0 -0.9997109 0.02404803 0 -0.9832897 -0.1820482 -1.68779e-7 -0.983289 -0.1820515 0 -0.8387785 -0.5444728 0 -0.8387755 -0.5444775 0.1621091 -0.7026848 0.6927876 0.1895087 -0.4393422 0.878103 0.6673846 -0.294133 0.6841664 0.04439204 -0.9147429 0.4015905 0.01811581 -0.865329 0.500877 0.04033952 -0.689749 0.7229241 0.01254647 -0.7264784 0.6870748 0.0364452 -0.5506671 0.833929 0.09911489 -0.06228256 0.993125 0.01704472 -0.08341485 0.9963691 0.09751319 -0.03880041 0.9944776 0.2480101 -0.08548069 0.9649789 0.1854808 -0.07513922 0.9797709 0.1716385 -0.08203601 0.9817384 0.1381649 -0.07706266 0.9874066 0.08149528 -0.07693231 0.9937002 0.3248288 -0.1772122 0.9290221 0.3162057 -0.2081067 0.925584 0.3721848 -0.02359163 0.9278588 0.4515407 0.003144562 0.892245 0.449169 -0.003898203 0.8934384 0.7149969 -0.1642649 0.6795561 0.7313382 -0.1104582 0.6730108 0.5049781 -0.02710372 0.8627066 0.5160481 -0.04731518 0.8552519 0.5462082 -0.01689159 0.8374791 0.6061848 -0.06185007 0.7929154 0.6075543 -0.05945783 0.7920497 0.6980471 -0.02914249 0.7154586 0.6787 -0.05545651 0.7323189 0.7365824 -0.05545294 0.6740707 0.7458099 -0.04445087 0.6646741 0.6302918 -0.3614102 0.6871063 0.5870791 -0.4615253 0.6650809 0.5878057 -0.4654521 0.6616939 0.5329584 -0.5282264 0.6610085 0.5321602 -0.5607813 0.6342949 0.2775838 -0.7318841 0.6223287 0.3220617 -0.7467099 0.5819801 0.372326 -0.7159133 0.590628 0.0392419 -0.9155864 0.4002022 0.04245334 -0.9279321 0.370324 0.04636931 -0.9176391 0.3947006 0.04333406 -0.9173091 0.3958111 0.1224678 -0.873512 0.471146 0.1930797 -0.6381307 0.7453251 0.1385108 -0.6320214 0.7624722 0.1399587 -0.6313599 0.7627558 0.0960077 -0.6276931 0.7725179 0.1346877 -0.7597456 0.6361178 0.08130419 -0.7534205 0.6524931 0.08298403 -0.7523834 0.6534776 0.0329473 -0.7500129 0.6606021 0.009841203 -0.8011748 0.5983495 -0.02460265 -0.8506681 0.5251271 0.04421639 -0.8552931 0.5162546 0.04205399 -0.8560482 0.5151824 0.071675 -0.8595209 0.5060501 0.06829577 -0.8602001 0.5053627 0.2111665 -0.8427975 0.4950767 0.211064 -0.8453744 0.4907078 0.1724361 -0.8327856 0.5260551 0.230539 -0.7837868 0.5766543 0.1802431 -0.7711837 0.6105638 0.1883357 -0.4401548 0.8779485 0.2612689 -0.44835 0.8548222 0.259464 -0.4500105 0.8544993 0.3298396 -0.4621196 0.8231958 0.3277812 -0.463347 0.8233281 0.3817835 -0.4745326 0.7931333 0.379527 -0.4758022 0.7934555 0.447282 -0.4923152 0.7467025 0.4441257 -0.4948004 0.7469438 0.2410878 -0.6495302 0.7211014 0.2819262 -0.6579834 0.6982661 0.2791618 -0.6589352 0.6984792 0.330546 -0.6714136 0.6632821 0.3267424 -0.6733319 0.6632222 0.3817832 -0.691577 0.6131582 0.4402783 -0.6354995 0.6342676 0.1313359 -0.4338224 0.8913748 0.1305435 -0.4344162 0.891202 0.1423405 -0.3563603 0.9234427 0.01512545 -0.8043202 0.5940038 0.06388002 -0.8068672 0.587269 0.061957 -0.8077717 0.5862306 0.10362 -0.8126848 0.5734165 0.1006102 -0.8135574 0.5727146 0.006568968 -0.9081279 0.4186415 0.02153581 -0.9086129 0.4170839 0.01463872 -0.9094991 0.4154481 0.03699904 -0.9111881 0.410326 0.0229088 -0.9123235 0.408829 0.03458952 -0.9131296 0.4061992 0.09815376 -0.8651596 0.4917976 0.09325599 -0.8662236 0.4908767 0.1418647 -0.8203838 0.5539358 0.03128701 -0.1137335 0.9930186 0.03029596 -0.1686996 0.9852019 0.08531415 -0.2906123 0.9530299 0.07482218 -0.2325888 0.9696928 0.1559097 -0.2369207 0.9589373 0.1570181 -0.2376884 0.9585665 0.2249253 -0.2433692 0.9434936 0.2264387 -0.2445237 0.9428328 0.310103 -0.2540464 0.9161314 0.3117839 -0.2563506 0.9149181 0.3918073 -0.2700175 0.8795327 0.3937988 -0.2720999 0.8780001 0.4537334 -0.2845174 0.8444974 0.45572 -0.2868618 0.8426325 0.5315614 -0.3055233 0.7899988 0.5328547 -0.3094651 0.7875896 0.5990496 -0.3315121 0.7288617 0.1415974 -0.3569808 0.9233174 0.2053698 -0.3623102 0.9091505 0.2042694 -0.363173 0.9090542 0.2831082 -0.3720672 0.8839772 0.281377 -0.3738378 0.883783 0.3574141 -0.386888 0.8500428 0.3555417 -0.3881701 0.8502436 0.4137479 -0.4002301 0.8176972 0.4116091 -0.4016003 0.8181048 0.4845843 -0.419438 0.7676262 0.4816703 -0.4220691 0.7680178 0.06698071 -0.241743 0.9680259 0.05012333 -0.3489845 0.9357871 0.05145287 -0.3512081 0.9348827 0.05407655 -0.4521453 0.8903036 0.03294301 -0.4278793 0.9032353 0.04954028 -0.4929873 0.8686251 0.1206609 -0.4969908 0.859326 0.1210635 -0.4976553 0.8588846 0.1741435 -0.5020951 0.8470978 0.1746029 -0.5030086 0.8464611 0.2402057 -0.5103724 0.8257247 0.2404698 -0.5123081 0.8244482 0.3033052 -0.523137 0.7964506 0.3036773 -0.5247431 0.7952514 0.3512167 -0.5345931 0.7686724 0.3514683 -0.5363823 0.7673097 0.4117746 -0.5510517 0.7257986 0.4110734 -0.5541365 0.723845 0.2823699 -0.7789989 0.5598464 0.2838007 -0.8035347 0.5232487 0.226118 -0.7851476 0.5765534 0.2816992 -0.7302415 0.622409 0.2232352 -0.715629 0.6618468 0.2249267 -0.7348222 0.6398785 0.2055314 -0.7101939 0.673336 0.2435573 -0.6485961 0.7211123 0.1908412 -0.6395087 0.7447202 0.1357678 -0.8948278 0.425265 0.138609 -0.8812701 0.4518303 0.1172038 -0.8741498 0.471302 0.177281 -0.8317831 0.5260308 0.1373622 -0.8218008 0.5529694 0.1842925 -0.7694395 0.6115548 0.1320206 -0.7608115 0.6354026 0.1645563 -0.7014631 0.6934486 0.1009624 -0.693928 0.712931 0.1115909 -0.7124868 0.6927555 0.08168184 -0.691973 0.7172876 0.096996 -0.6271926 0.7728011 0.01595443 -0.6220391 0.7828237 0.271645 0.2066113 0.9399579 0.2531445 -0.08313477 0.9638499 0.3403914 -0.09318858 0.9356546 0.3420038 -0.0955224 0.934831 0.4301349 -0.1104297 0.8959852 0.4320413 -0.1125282 0.894806 0.4980836 -0.1262122 0.8578947 0.5000189 -0.1285802 0.8564159 0.5832501 -0.1492728 0.7984592 0.5846532 -0.153282 0.7966714 0.6575366 -0.1773115 0.7322611 0.6591241 -0.1799719 0.7301818 0.6818495 -0.1886714 0.7067421 0.6892822 -0.2419209 0.6829087 0.6233293 -0.3429477 0.7027429 0.6006178 -0.3341538 0.7263605 0.5432353 -0.4446863 0.7121444 0.5455002 -0.4434552 0.71118 0.5009037 -0.515806 0.6950106 0.5033152 -0.5146882 0.6940965 0.4195321 -0.6281033 0.6553465 0.4800226 -0.5768765 0.6609023 0.4408468 -0.6325445 0.6368216 0.3730206 -0.6102508 0.6988917 0.3765784 -0.6081045 0.6988546 0.318721 -0.5940442 0.738599 0.3212746 -0.59297 0.7383557 0.2752553 -0.5834389 0.7640901 0.277578 -0.5823833 0.7640551 0.2178968 -0.5720978 0.7907118 0.2199586 -0.5706086 0.7912169 0.1581374 -0.5636836 0.8107116 0.1594978 -0.5629447 0.8109586 0.109613 -0.558781 0.8220394 0.1105386 -0.558237 0.8222851 0.03914469 -0.5541047 0.8315262 0.04051721 -0.6421833 0.7654797 -0.1368555 -0.498314 0.8561272 -0.01836377 -0.5509402 0.8343428 -0.02694177 -0.6240707 0.7809033 7.50202e-4 -0.6427113 0.7661081 -0.04596191 -0.7257679 0.6864027 -0.01364147 -0.8038816 0.594633 -0.01942092 -0.8010622 0.598266 -0.01925158 -0.8540549 0.5198267 0.005097568 -0.8654592 0.5009536 -0.03318578 -0.9091978 0.4150399 -0.00578618 -0.9156304 0.4019796 -0.02744561 -0.9347909 0.3541367 0.01052463 -0.8995792 0.4366312 -0.2590521 -0.9143579 0.311194 -0.038136 -0.8794831 0.4744 -0.2678427 -0.8656438 0.4229906 -0.1526665 -0.8544861 0.4965347 -0.2987858 -0.8121125 0.501199 -0.2564362 -0.8123258 0.5238007 -0.3403542 -0.7557129 0.559515 -0.3478448 -0.7546521 0.556331 -0.3861681 -0.7027578 0.5974994 -0.3875302 -0.6964297 0.6039917 -0.4223424 -0.6761331 0.6037144 -0.4380251 -0.6501767 0.6208094 -0.4435754 -0.6368986 0.6305561 -0.4400202 -0.6386875 0.6312373 -0.5241091 -0.5439842 0.6552793 -0.4924704 -0.5985742 0.6318085 -0.5300126 -0.5269099 0.6644191 -0.5467672 -0.5153442 0.6598984 -0.5712218 -0.4755684 0.6689846 -0.5751909 -0.4568476 0.6785616 -0.596297 -0.437397 0.6731373 -0.6884562 -0.239335 0.6846509 -0.6660576 -0.2930215 0.6859343 -0.6511626 -0.3110243 0.6922798 -0.6414405 -0.3215416 0.696538 -0.617807 -0.3406825 0.708696 -0.6205514 -0.3536214 0.6999056 -0.613955 -0.3988482 0.6811604 -0.6741884 -0.1446249 0.7242608 -0.702216 -0.1963214 0.6843615 -0.7307183 -0.1060082 0.6743984 -0.7338194 -0.046624 0.6777428 -0.7718589 -0.05169022 0.6336893 -0.5351271 -0.02116072 0.8445066 -0.5889641 -0.0691123 0.8051986 -0.493875 -0.0302881 0.8690052 -0.4283662 0.007547736 0.9035738 -0.1452623 -0.08658158 0.9855976 -0.06552445 -0.6251917 0.7777158 -0.06603765 -0.6255942 0.7773488 -0.05157411 -0.7136518 0.6985995 -0.04462182 -0.6897512 0.7226702 -0.00498116 -0.7471462 0.6646411 -0.5127928 -0.5919851 0.6217694 -0.459325 -0.572041 0.6795511 -0.4989079 -0.5149908 0.6970477 -0.4986299 -0.5128438 0.6988273 -0.540909 -0.4437307 0.7145072 -0.05272966 -0.922522 0.3823254 -0.04839545 -0.9184787 0.3924982 -0.1286028 -0.8788658 0.4594086 -0.1286975 -0.8762841 0.4642879 -0.1876688 -0.8387402 0.5111708 -0.1880144 -0.835951 0.5155935 -0.2450593 -0.7922781 0.5587858 -0.2456545 -0.789305 0.562718 -0.3001872 -0.7401911 0.6016685 -0.3008671 -0.7370056 0.6052287 -0.3528232 -0.6827355 0.6398344 -0.3535832 -0.6793594 0.6430006 -0.402432 -0.6207144 0.6728761 -0.4031718 -0.6171496 0.6757062 -0.4216415 -0.592723 0.6862201 -0.421947 -0.5560467 0.7160817 -0.4573697 -0.4994243 0.735791 -0.3353397 -0.5322284 0.7773546 -0.3646649 -0.4719739 0.8026582 -0.411933 -0.4830458 0.7726435 -0.4472764 -0.4114851 0.7941183 -0.4953643 -0.4247993 0.7577334 -0.5478194 -0.3123185 0.7761129 -0.5444893 -0.3133967 0.7780193 -0.6008628 -0.1563558 0.7839112 -0.5979292 -0.1575676 0.7859092 -0.6321735 -0.02365761 0.7744656 -0.689531 -0.06086885 0.7216938 -0.3452518 -0.6015534 0.7203712 -0.3815316 -0.5430457 0.7480208 -0.3795602 -0.544295 0.7481157 -0.4125874 -0.4850395 0.7710438 -0.4568918 -0.497305 0.7375214 -0.4958533 -0.4269753 0.7561889 -0.5406017 -0.4415419 0.716094 -0.5975399 -0.3306601 0.7304862 -0.5942801 -0.3316589 0.7326893 -0.6554368 -0.1762753 0.7343907 -0.6525697 -0.1774283 0.7366628 -0.6868787 -0.05634623 0.7245846 -0.7369285 -0.05212193 0.6739582 -0.04443114 -0.9175345 0.3951662 -0.03853887 -0.9141275 0.4035913 -0.1049478 -0.8697212 0.4822561 -0.1041142 -0.8673545 0.4866791 -0.1528717 -0.826238 0.5421818 -0.1523429 -0.8236768 0.5462126 -0.1994329 -0.776526 0.5976906 -0.1992114 -0.7737924 0.6012989 -0.2441878 -0.721331 0.6481158 -0.2440873 -0.7183972 0.6514039 -0.2869108 -0.6609176 0.6934481 -0.2869328 -0.6578283 0.6963703 -0.3173257 -0.6119406 0.7244537 -0.3057941 -0.5891497 0.7479255 -0.3371777 -0.5309907 0.777406 -0.2625522 -0.5806953 0.7706227 -0.2902709 -0.5203915 0.8030787 -0.288677 -0.5215342 0.802912 -0.314023 -0.4604131 0.8303068 -0.363897 -0.470146 0.8040782 -0.3953221 -0.397428 0.8281131 -0.4466386 -0.4094519 0.7955271 -0.4941929 -0.2954646 0.8176026 -0.4909126 -0.2965602 0.8191806 -0.5420073 -0.1380432 0.8289585 -0.5391075 -0.1392564 0.8306449 -0.5735875 0.0138995 0.8190265 -0.649806 -0.08561164 0.7552634 -0.03388208 -0.9134036 0.4056428 -0.02796685 -0.9108104 0.4118766 -0.0779851 -0.8622609 0.5004245 -0.07658982 -0.8604078 0.5038179 -0.1133665 -0.8160794 0.5667119 -0.1122741 -0.8140611 0.5698238 -0.1477448 -0.7637584 0.6283668 -0.1469514 -0.761582 0.6311879 -0.1808012 -0.7060545 0.6846883 -0.1801431 -0.7037237 0.6872564 -0.2123523 -0.6432783 0.7355948 -0.2118371 -0.6408084 0.7378955 -0.2346726 -0.5928034 0.7703979 -0.1361623 -0.4989624 0.8558601 -0.14821 -0.4359493 0.8876835 -0.2044926 -0.4411711 0.8738141 -0.2224935 -0.365418 0.9038619 -0.2819068 -0.3728539 0.8840297 -0.3123248 -0.2551924 0.9150574 -0.3099008 -0.2561783 0.915606 -0.342531 -0.09425401 0.9347667 -0.340336 -0.09530758 0.9354614 -0.4293988 -0.00108087 0.9031144 -0.4099478 -0.1079364 0.9057001 -0.4124748 -0.1067895 0.9046881 -0.3732774 -0.2677872 0.8882309 -0.3761121 -0.2667183 0.8873562 -0.339609 -0.3833202 0.858913 -0.2827132 -0.3742638 0.883176 -0.2599855 -0.4490913 0.8548244 -0.2052558 -0.4422466 0.8730912 -0.1886087 -0.5047805 0.8423916 -0.1896262 -0.5039205 0.8426779 -0.1300251 -0.6290776 0.7663909 -0.1306984 -0.6306542 0.7649792 -0.1105367 -0.6936396 0.7117906 -0.11133 -0.6951109 0.7102299 -0.09012407 -0.7532217 0.6515634 -0.09102207 -0.754584 0.6498599 -0.06879121 -0.8075001 0.5858426 -0.06992149 -0.8087611 0.5839661 -0.04684746 -0.855715 0.5153223 -0.04819709 -0.8568558 0.5132986 -0.01688504 -0.9086704 0.4171726 -0.02153915 -0.9101061 0.4138152 -0.0965752 -0.3534965 0.9304373 -0.1070644 -0.2338176 0.9663677 -0.1062191 -0.2342582 0.9663544 -0.1182143 -0.05739974 0.9913277 -0.0890249 -0.431162 0.8978719 -0.0969659 -0.3539672 0.9302176 -0.1600481 -0.3578339 0.9199671 -0.1774172 -0.2386206 0.9547688 -0.17598 -0.239293 0.9548665 -0.1936557 -0.08550631 0.9773362 -0.2410272 -0.0721789 0.9678307 -0.3620851 -0.02082753 0.9319124 -0.3425904 -0.08190405 0.9359079 -0.3166145 0.05097419 0.9471837 -0.2808451 -0.08656066 0.9558417 -0.2690255 -0.08767837 0.959134 -0.243793 -0.2466173 0.9379472 -0.2457596 -0.2457635 0.9376581 -0.2217589 -0.3643121 0.9044886 -0.1606441 -0.3586437 0.9195479 -0.1475846 -0.4351805 0.8881648 -0.08946597 -0.4316167 0.8976095 -0.08218038 -0.4949633 0.8650189 -0.0825898 -0.4945388 0.8652227 -0.4951976 -0.03507894 0.868072 -0.4762519 -0.1226387 0.8707147 -0.4790324 -0.12142 0.8693591 -0.4336668 -0.2812894 0.8560428 -0.4367786 -0.2801787 0.8548243 -0.3945658 -0.3955382 0.8293777 -0.3404137 -0.3849691 0.8578563 -0.3131874 -0.4588081 0.83151 -0.2608335 -0.4504733 0.8538383 -0.2397273 -0.5123474 0.8246399 -0.2410317 -0.5113341 0.8248886 -0.2184293 -0.5712315 0.7911912 -0.1715237 -0.5653494 0.8068208 -0.1442627 -0.5794165 0.8021627 -0.1239475 -0.5593941 0.8195825 -0.07529896 -0.5564082 0.8274902 -0.07478344 -0.5559701 0.8278313 -0.01332962 -0.5538881 0.8324846 -0.03201961 -0.4930525 0.8694102 -0.01146471 -0.4527779 0.8915497 -0.03461515 -0.429553 0.902378 -0.02573484 -0.3493077 0.9366547 -0.02350342 -0.3511492 0.9360246 -0.04662466 -0.2420229 0.9691497 -0.05997371 -0.2325148 0.970742 -0.0369991 -0.168661 0.9849795 -0.03919184 -0.06695002 0.9969863 -0.09240317 -0.1133016 0.9892545 -0.04886472 -0.03893929 0.9980461 0.5389378 -0.8400127 0.06264919 0.08064532 -0.7674598 -0.6360048 0.03125417 -0.9828097 -0.1819567 0.1592095 -0.9760321 -0.1483706 0.04047781 -0.9988908 0.02405893 0.04871463 -0.9865465 -0.1560539 0.07141399 -0.9848747 -0.1578666 0.09443145 -0.9821178 -0.1628719 0.1083556 -0.9828953 -0.1489162 0.1672357 -0.9717686 -0.1664275 0.04670327 -0.7728685 -0.6328453 0.05892068 -0.7729008 -0.6317853 0.06848651 -0.7682468 -0.6364799 0.05999177 -0.7752677 -0.6287775 0.1483133 -0.8604832 -0.4874135 0.1497989 -0.8733325 -0.4635199 0.2428666 -0.9367883 -0.2518802 0.2426577 -0.9324408 -0.2677155 0.01182645 -0.8387171 -0.544439 0.01158362 -0.8389176 -0.5441354 0.03639215 -0.8369454 -0.5460752 0.03640937 -0.8369256 -0.5461043 0.06024658 -0.8362575 -0.5450174 0.5293631 -0.8475609 0.03762197 0.2234002 -0.8543485 -0.4692344 0.365525 -0.8931394 -0.2620943 0.3575772 -0.8893662 -0.2848975 0.4736159 -0.8792247 -0.05149859 0.08313333 -0.7712584 -0.6310702 0.2173168 -0.8529016 -0.4746919 0.1851368 -0.8688927 -0.4590752 0.2932527 -0.921788 -0.2535939 0.2918683 -0.9171041 -0.2715383 0.4528177 -0.8829609 -0.1238396 0.4316769 -0.9000036 -0.06040471 0.3868488 -0.9213355 -0.03858876 0.3864998 -0.9220969 0.01885002 0.3121555 -0.9475392 -0.06876599 0.26982 -0.9626141 -0.02390336 0.1303333 -0.9641188 -0.2312752 0.2172846 -0.9625536 -0.1621055 0.1204966 -0.8826922 -0.4542413 0.04960995 -0.847572 -0.5283566 0.03578472 -0.7762964 -0.6293517 0.2523139 -0.3102414 -0.9165632 0.8889367 -0.0495494 -0.4553421 0.9830617 -0.06132823 -0.1727095 0.6577478 -0.0395267 -0.7522006 0.766027 -0.04481488 -0.6412444 0.4879924 -0.02876985 -0.8723736 0.1217147 -0.1496291 -0.9812221 0.4021539 -0.4941533 -0.770769 0.6217575 -0.7648854 -0.1684286 0.5548546 -0.681624 -0.476996 0.6308856 -0.775498 0.02421253 0.560853 -0.05901771 -0.8258093 0.5556606 -0.1000183 -0.8253713 0.5562923 -0.09977447 -0.8249752 0.5405924 -0.1648911 -0.8249673 0.5409707 -0.1647938 -0.8247386 0.5176188 -0.2277556 -0.8247413 0.5177669 -0.2277354 -0.8246539 0.4873015 -0.287185 -0.8246588 0.4872069 -0.2871858 -0.8247143 0.4499374 -0.342649 -0.824711 0.4496125 -0.3426136 -0.8249027 0.4061644 -0.3931185 -0.8249173 0.4056361 -0.393003 -0.825232 0.3760185 -0.4205651 -0.8256725 0.3082565 -0.3707602 -0.8760793 0.8500061 -0.07245826 -0.5217659 0.8398717 -0.1511842 -0.5213051 0.8406175 -0.1506983 -0.5202424 0.8168691 -0.2491672 -0.5202313 0.8173486 -0.248935 -0.519589 0.7820557 -0.3441061 -0.5195959 0.7822318 -0.3440476 -0.5193696 0.7362083 -0.4338752 -0.5193743 0.7360911 -0.4339024 -0.5195178 0.6797861 -0.5176867 -0.5195107 0.6793593 -0.5177307 -0.520025 0.6137397 -0.594034 -0.5200454 0.6130221 -0.5940164 -0.5209113 0.5531675 -0.6497976 -0.5213146 0.4792435 -0.5892688 -0.6504521 0.632003 -0.7617234 -0.1426526 0.710782 -0.6888106 -0.1425798 0.7113561 -0.6885045 -0.1411882 0.7873785 -0.6000851 -0.1411842 0.7876964 -0.5998649 -0.1403443 0.852938 -0.5027912 -0.1403486 0.8530206 -0.5027184 -0.1401076 0.9063531 -0.3986156 -0.1401056 0.9062315 -0.3987523 -0.1405034 0.9471343 -0.2884371 -0.1405016 0.946871 -0.2888149 -0.1414968 0.9744137 -0.1746291 -0.1415014 0.97404 -0.1753306 -0.1431969 0.9870601 -0.07195603 -0.1432994 0.9982046 -0.05913943 0.009498596 0.1585742 -0.00937432 -0.9873026 0.1219435 -0.1497336 -0.9811778 0.1387175 -0.1343536 -0.9811761 0.1388981 -0.1344119 -0.9811426 0.1537573 -0.1171429 -0.9811403 0.1538561 -0.1171628 -0.9811224 0.1665989 -0.09819668 -0.981123 0.1666339 -0.09819906 -0.9811168 0.1770451 -0.07788193 -0.9811164 0.1770014 -0.07788419 -0.9811242 0.1849792 -0.05637311 -0.9811242 0.1848422 -0.05639535 -0.9811488 0.190198 -0.03415292 -0.9811515 0.1899924 -0.03421509 -0.9811892 0.1911062 -0.02495688 -0.9812521 0.3455407 -0.02045583 -0.9381808 0.9987257 0 0.05046844 0.9985893 0.001815915 0.05306756 0.9983955 -2.89923e-4 0.05662578 0.9979301 -0.002044379 0.06427609 0.99768 0.005300343 0.0678721 0.9980351 3.8599e-4 0.06265693 0.9967136 -5.33038e-5 0.08100742 0.9962818 0.02625542 0.08205729 0.996531 0.01774501 0.08130985 0.996862 0.00778073 0.07877606 0.9972156 0.001171529 0.07456392 0.6044238 -0.6842994 0.4079293 0.6731531 -0.4286849 0.602573 0.4647465 -0.6690016 0.5800411 0.5155006 -0.6543984 0.5531926 0.5025082 -0.661106 0.5571574 0.5393775 -0.6361694 0.5516889 0.5644785 -0.6015347 0.5652611 0.5579752 -0.6135621 0.5587534 0.5703679 -0.5674868 0.5938345 0.5707747 -0.5781078 0.5831018 0.568789 -0.5896087 0.5734463 0.562507 -0.5501655 0.6171741 0.8170966 -0.5052412 0.2776413 0.853411 -0.4738195 0.2172206 0.9132311 -0.1934714 0.3585774 0.9796992 -0.1669869 0.1109281 0.965785 0.005593359 0.259284 0.7622765 -0.3361372 0.5531243 0.4732204 -0.288927 0.8322163 0.8293381 -0.4569805 0.3215081 0.5508733 -0.4484947 0.7038403 0.6273215 -0.5986199 0.4981186 0.806777 -0.05273872 0.5884976 0.7869778 -0.0120728 0.6168633 0.5926303 0.01449906 0.8053441 0.4997144 -0.07704889 0.8627567 0.8711664 -0.06061577 0.4872319 0.8672041 -0.04826486 0.4956082 0.8256679 -0.01157611 0.5640378 0.9499095 -0.1516599 0.2732606 0.9301393 -0.08259093 0.3577983 0.9258427 -0.07814693 0.369741 0.9269918 -0.08405011 0.3655432 0.8936817 -0.05253779 0.4456151 0.4626145 -0.8326372 0.304472 0.290092 -0.8734754 0.3910081 0.4295975 -0.8271886 0.3622225 0.3646481 -0.8530267 0.3733328 0.3560879 -0.8583019 0.3694853 0.2685488 -0.8614335 0.4310613 0.2549533 -0.9083474 0.3315177 0.1422933 -0.9120531 0.3845933 0.4114656 -0.8922071 0.1861792 0.01644998 -0.8263583 0.5629045 0.3068462 -0.9479902 0.08461791 0.756977 -0.5637241 -0.330456 0.01078218 -0.4723069 0.8813683 0.6613843 -0.7429638 -0.1028382 0.2402803 -0.7570133 0.6076154 0.30331 -0.8767232 0.3733091 0.9305478 -0.3628088 0.04950231 0.9101558 -0.3724969 -0.1812806 0.7304874 -0.2658954 0.6290373 0.6479084 -0.4166413 0.6376715 0.5949445 -0.3633861 0.7169321 0.6021522 -0.5835041 0.544918 0.6882295 -0.4521579 0.5673565 0.6965212 -0.4801719 0.5331916 0.6965136 -0.4801836 0.533191 0.6977346 -0.5117586 0.5012682 0.6977286 -0.5117658 0.501269 0.6918222 -0.5459067 0.4726181 0.6918219 -0.5459024 0.4726237 0.6790151 -0.5813903 0.4482454 0.6790047 -0.5814049 0.4482422 0.6597002 -0.6171066 0.4289234 0.6597023 -0.6171007 0.4289287 0.4948313 -0.7584285 0.4241794 0.5333735 -0.7385247 0.4124245 0.5333771 -0.7385226 0.4124238 0.5703201 -0.713532 0.4069486 0.4559895 -0.7725762 0.4418142 0.4181602 -0.7804893 0.4647351 0.4181536 -0.780491 0.464738 0.3825881 -0.7819069 0.4921872 0.3825941 -0.7819043 0.4921867 0.4767237 -0.6685227 0.5707995 0.7959722 -0.4873865 0.3590028 0.8056321 -0.4315544 0.4058546 0.8056268 -0.4315538 0.4058658 0.8036463 -0.3798615 0.4581025 0.8036557 -0.379861 0.4580864 0.7900989 -0.3340379 0.5139676 0.7901026 -0.3340265 0.5139691 0.7654312 -0.2956168 0.5715995 0.6345618 -0.6517843 0.4153418 0.6345633 -0.6517837 0.4153404 0.5495209 -0.625226 0.5541834 -0.01443791 -0.8983045 0.4391362 0.06471985 -0.9912883 0.1147127 0.05372565 -0.9025949 0.4271253 0.146383 -0.9170216 0.3710032 0.2375944 -0.8650862 0.4417861 0.237599 -0.8650868 0.4417822 0.3505157 -0.7767755 0.5232194 0.3505057 -0.7767798 0.5232199 0.4539495 -0.6672821 0.5904782 0.6476144 -0.7062416 0.2860395 0.5836747 -0.7364137 0.3420801 0.5626652 -0.8014593 0.2026599 0.537105 -0.7781247 0.3256384 0.4852495 -0.8018391 0.3486934 0.4948298 -0.7584306 0.4241775 0.4559981 -0.7725714 0.4418135 0.4894439 -0.665863 0.5630908 0.7892656 -0.1142148 0.6033364 0.8368408 -0.1546676 0.5251433 0.8368469 -0.1546659 0.525134 0.8704221 -0.2069614 0.4466907 0.8704205 -0.2069622 0.4466931 0.8888647 -0.2693367 0.3706445 0.8888652 -0.2693381 0.3706424 0.8915604 -0.3397073 0.2995314 0.8915593 -0.3397101 0.2995315 0.9290663 -0.2872725 -0.233046 0.9662466 -0.2565763 -0.0231595 0.7892656 -0.1142148 0.6033366 0.7304801 -0.2658964 0.6290452 0.7654314 -0.2956193 0.5715978 0.6731657 -0.4286742 0.6025665 0.6882303 -0.452159 0.5673546 0.567583 -0.5580564 0.6053286 0.9882797 -0.03610455 0.1483232 0.9762136 -0.07867407 0.202033 0.9784503 -0.0623902 0.1968311 0.9499103 -0.1516603 0.2732575 0.9536792 -0.2259501 0.1986016 0.920941 -0.2976173 0.2515785 0.8938091 -0.4450035 -0.05547195 0.8901667 -0.3512471 0.2902219 0.8554569 -0.4390902 0.2745786 0.7959733 -0.4873828 0.3590049 0.7822768 -0.526917 0.3322675 0.7726162 -0.5466706 0.3228241 0.779471 -0.5230509 0.344736 0.7257505 -0.6084166 0.3211162 0.7216322 -0.6189613 0.3100548 0.6757406 -0.6590474 0.3301989 0.6470116 -0.7107033 0.2761827 0.6044273 -0.6842956 0.4079304 0.5703113 -0.7135404 0.4069463 0.5278982 -0.646006 0.5513618 0.03342223 -0.9487206 0.3143444 0.01043069 -0.942791 0.3332211 -0.006192743 -0.948609 0.31639 -7.91806e-4 -0.9410519 0.3382613 4.40846e-4 -0.9373968 0.3482632 -5.97976e-4 -0.9389781 0.3439765 2.44389e-4 -0.9363738 0.3510045 -0.002052724 -0.9384167 0.3454993 -3.90054e-4 -0.9370659 0.3491526 2.351e-4 -0.9363863 0.3509711 0.009670436 -0.9431216 0.3323073 3.16371e-5 -0.9481891 0.3177067 -1.96824e-5 -0.9602755 0.279054 1.11464e-4 -0.960207 0.2792896 -1.13866e-4 -0.9705175 0.2410309 0.004018008 -0.9684999 0.2489817 7.8713e-5 -0.9731174 0.2303102 -1.91556e-4 -0.9792445 0.2026824 2.57637e-4 -0.9790535 0.2036035 -9.4621e-5 -0.9842539 0.176761 7.17327e-7 -0.9841523 0.1773257 5.7947e-7 -0.9875348 0.1574016 1.32166e-4 -0.9874628 0.1578528 -1.99397e-4 -0.9921323 0.1251937 1.55627e-7 -0.9983428 0.05754858 -3.48352e-5 -0.9983533 0.05736613 6.43793e-5 -0.9964449 0.08424836 7.74834e-4 -0.9962759 0.08622074 -1.17138e-5 -0.9945856 0.1039201 1.37766e-4 -0.9920341 0.1259695 0.04371267 -0.9861921 0.1597326 0.7924174 -0.5539736 0.2553194 0.8201904 -0.5164314 0.2461432 0.8501004 -0.4716024 0.2343515 0.8521018 -0.4677804 0.2347428 0.8985237 -0.3864539 0.208107 0.905931 -0.3684522 0.2086434 0.9370466 -0.298866 0.1806179 0.9478893 -0.2635675 0.1789923 0.9656459 -0.2101791 0.1528162 0.9831549 -0.1169332 0.1404744 0.9781566 -0.1588661 0.1340571 0.9929205 -0.04714703 0.1090241 0.9928835 -0.05062353 0.107795 0.9984318 -0.03577113 0.0430637 0.9968492 -0.05893164 0.05309218 0.9900423 -0.1277387 0.05915254 0.974111 -0.2219572 0.04292672 0.9820899 -0.1763066 0.06645035 0.94758 -0.3150842 0.05304825 0.9546049 -0.2908937 0.0641117 0.9112138 -0.4074502 0.06061208 0.9135379 -0.401861 0.06290066 0.8649698 -0.4974993 0.06574094 0.8598149 -0.5067946 0.06227099 0.8090837 -0.583636 0.06893819 0.7939302 -0.6048834 0.06157076 0.74413 -0.6642899 0.07063752 0.7169604 -0.6944425 0.06097131 0.5056737 -0.8610659 0.05347681 0.629095 -0.7735004 0.0770502 0.5916315 -0.8046398 0.05027014 0.6709969 -0.7380621 0.07090598 0.3999205 -0.914205 0.06552064 0.4761789 -0.8768166 0.06667995 0.5437378 -0.8357515 0.07660824 0.415686 -0.9079611 0.05302703 0.3221665 -0.943945 0.07194948 0.2882648 -0.9557403 0.0588563 0.2092422 -0.9750286 0.07440984 0.2290703 -0.9715594 0.05999392 0.135533 -0.9886808 0.06435143 0.131325 -0.9894234 0.06160461 0.0423634 -0.9973447 0.059237 0.04145085 -0.9973463 0.059852 0.08681976 -0.9944507 0.05941492 0.04777997 -0.9462622 0.3198515 0.03132909 -0.945775 0.3233082 0.1113002 -0.9405003 0.3210478 0.1475331 -0.9325351 0.3295637 0.7901774 -0.5563439 0.2571017 0.7248961 -0.6312977 0.2756609 0.7255884 -0.6304363 0.275811 0.647064 -0.7038306 0.2931395 0.6506786 -0.7000789 0.2941206 0.5577104 -0.7716294 0.3058553 0.5689293 -0.7619443 0.3094518 0.4618307 -0.8293799 0.3143905 0.4817498 -0.8151187 0.3217119 0.3608348 -0.8765285 0.3185847 0.3906541 -0.858973 0.3309908 0.2560881 -0.9127616 0.3182536 0.2972055 -0.8931623 0.3375353 0.2046465 -0.9239442 0.3231826 0.9954252 -0.0448271 0.08437585 0.9962016 -0.03447788 0.07996195 0.9873704 -0.1248555 0.09752404 0.9871817 -0.1258979 0.09809255 0.9695761 -0.2161065 0.11498 0.9692829 -0.2171199 0.1155411 0.9422442 -0.3078835 0.1318476 0.9418427 -0.308872 0.1324019 0.905049 -0.3987928 0.1478193 0.9045468 -0.399731 0.1483585 0.8579548 -0.4873211 0.1625787 0.8573488 -0.4882116 0.1631033 0.8012294 -0.5719392 0.1758327 0.8005295 -0.5727638 0.1763356 0.7354781 -0.6511415 0.1873148 0.7346817 -0.6519004 0.1877995 0.6616086 -0.7235595 0.1968141 0.6607317 -0.7242361 0.1972706 0.5808083 -0.7880206 0.2041703 0.5798587 -0.7886084 0.2045987 0.4944692 -0.8436191 0.2093018 0.4934591 -0.8441115 0.2096996 0.4041201 -0.8897528 0.2121955 0.4030554 -0.890148 0.2125629 0.3113257 -0.9261454 0.2129106 0.3102256 -0.9264376 0.213245 0.217625 -0.9528278 0.2115621 0.2164936 -0.9530182 0.2118652 0.1244465 -0.970111 0.2083213 0.1232982 -0.9701995 0.2085918 0.04166042 -0.9780927 0.2039586 0.03697055 -0.9781001 0.2048254 0.9946696 -0.04557865 0.09249347 0.9956824 -0.03311657 0.08671844 0.9864351 -0.1236616 0.1079521 0.9862054 -0.124859 0.1086696 0.9682708 -0.2140935 0.1289026 0.967916 -0.2152667 0.129611 0.9405682 -0.3050585 0.1492341 0.9400903 -0.3061898 0.1499271 0.9030147 -0.395154 0.1685761 0.9024098 -0.3962449 0.1692529 0.855573 -0.4828979 0.1865596 0.8548473 -0.483928 0.1872163 0.7985202 -0.5667679 0.2028297 0.7976855 -0.5677168 0.203459 0.7324628 -0.6452757 0.2170659 0.7315196 -0.6461435 0.2176645 0.6583264 -0.7170527 0.2290019 0.6572859 -0.7178263 0.2295665 0.5772947 -0.7809447 0.2384462 0.5761675 -0.7816157 0.2389729 0.4907636 -0.8360542 0.2452847 0.4895619 -0.8366157 0.2457711 0.4002553 -0.8817878 0.2494921 0.3989982 -0.882232 0.2499344 0.3073537 -0.9178634 0.2511186 0.3060432 -0.9181911 0.2515208 0.213579 -0.9443171 0.2502985 0.2122421 -0.9445236 0.250656 0.1203705 -0.9614547 0.2472161 0.1190083 -0.9615432 0.2475317 0.03858107 -0.9693142 0.2427785 0.03591603 -0.9693072 0.2432152 0.9938451 -0.0462892 0.1006447 0.9951291 -0.03173249 0.09333497 0.9854238 -0.1222776 0.1182721 0.9851523 -0.1236125 0.1191427 0.966852 -0.211757 0.1426756 0.9664363 -0.2130675 0.1435384 0.9387468 -0.3017544 0.1664291 0.938188 -0.303023 0.1672739 0.9007947 -0.3909064 0.1891061 0.9000946 -0.3921181 0.1899289 0.8529691 -0.4777309 0.2102779 0.852133 -0.4788727 0.2110697 0.7955614 -0.5607136 0.2295268 0.7945887 -0.5617794 0.2302888 0.729171 -0.6383996 0.2464863 0.728082 -0.6393641 0.2472046 0.6547387 -0.7094244 0.2608336 0.6535394 -0.7102822 0.2615063 0.5734499 -0.7726496 0.2723382 0.5721516 -0.7733907 0.2729644 0.4867021 -0.827186 0.2808641 0.4853204 -0.8278025 0.281438 0.3960338 -0.8724405 0.2863653 0.3945754 -0.8729296 0.2868871 0.3029974 -0.9081469 0.2888981 0.3014984 -0.9084977 0.2893626 0.209151 -0.9343277 0.2885959 0.2076056 -0.9345455 0.2890062 0.1159027 -0.9512933 0.2856707 0.1143416 -0.9513757 0.2860252 0.03524249 -0.9590092 0.2811751 0.03471803 -0.9590064 0.2812498 0.9967293 -0.04326534 0.06825792 0.9971339 -0.03697246 0.06600815 0.9889971 -0.1266982 0.07637047 0.9888882 -0.1273629 0.07667344 0.9718323 -0.219133 0.08673495 0.9716582 -0.2197849 0.08703398 0.9451245 -0.3121096 0.09657841 0.9448837 -0.3127467 0.09687334 0.9085431 -0.4041983 0.1057037 0.9082395 -0.4048046 0.1059931 0.8620322 -0.4938848 0.1139216 0.861666 -0.4944581 0.114206 0.8058618 -0.5795966 0.1210564 0.8054333 -0.5801343 0.1213322 0.7406144 -0.6598275 0.1269563 0.7401304 -0.6603192 0.1272226 0.6671987 -0.7331797 0.1315047 0.6666629 -0.7336214 0.1317589 0.5867929 -0.7984673 0.1346263 0.5862116 -0.7988535 0.1348679 0.5007801 -0.8547766 0.1362947 0.5001572 -0.8551047 0.1365238 0.4106873 -0.9014967 0.1365277 0.4100301 -0.9017631 0.136743 0.3180727 -0.9383496 0.1353882 0.3173969 -0.9385496 0.1355875 0.2244975 -0.9653598 0.1329717 0.2237997 -0.9654962 0.133157 0.1313601 -0.9828522 0.1294077 0.1306557 -0.9829236 0.129577 0.04709219 -0.991007 0.1252502 0.03862679 -0.9911289 0.1271679 0.9972782 -0.04246479 0.06027442 0.9975404 -0.03808456 0.05884575 0.9896839 -0.1273247 0.06568413 0.9896128 -0.1277809 0.06586927 0.9727732 -0.2201402 0.07246154 0.9726585 -0.2205864 0.07264542 0.9463191 -0.3134942 0.07875108 0.9461582 -0.3139325 0.07893782 0.909983 -0.4059606 0.08442008 0.9097794 -0.4063792 0.08460187 0.8637138 -0.4960023 0.08933204 0.863463 -0.4964065 0.08951205 0.80776 -0.5820696 0.0933752 0.8074742 -0.5824382 0.09354788 0.7427194 -0.6626199 0.09645122 0.7423932 -0.6629608 0.09662002 0.6694866 -0.7362651 0.09849631 0.6691244 -0.7365722 0.09866058 0.5892354 -0.8018141 0.09947854 0.5888438 -0.8020823 0.09963542 0.5033521 -0.8583456 0.09939551 0.5029335 -0.8585737 0.09954482 0.4133617 -0.9052473 0.09828305 0.4129198 -0.9054335 0.09842514 0.3208239 -0.9422402 0.09620481 0.3203613 -0.9423839 0.0963391 0.2272862 -0.9693531 0.09324973 0.2268185 -0.9694507 0.09337449 0.1341767 -0.9869055 0.089522 0.1336922 -0.9869606 0.08963966 0.04944211 -0.9951111 0.08549571 0.03916776 -0.9953478 0.08802729 0.9961116 -0.04405301 0.07629674 0.9966871 -0.03575706 0.07305049 0.9882242 -0.1258798 0.08699017 0.9880784 -0.1267287 0.08741325 0.970766 -0.2177869 0.1009081 0.9705321 -0.2186299 0.1013337 0.9437638 -0.3102424 0.114279 0.9434456 -0.3110551 0.1146964 0.9068983 -0.4018049 0.1268395 0.906491 -0.402593 0.1272525 0.8601109 -0.4909891 0.1383444 0.8596277 -0.4917221 0.1387431 0.8036805 -0.5762211 0.14855 0.8031148 -0.5769093 0.1489378 0.7381954 -0.6560023 0.1572537 0.7375597 -0.6566284 0.1576228 0.664569 -0.7289434 0.1642853 0.6638644 -0.7295057 0.1646372 0.5839824 -0.793866 0.1695331 0.5832117 -0.7943611 0.1698669 0.4978135 -0.8498666 0.1729409 0.4969972 -0.8502808 0.1732531 0.4076002 -0.8963305 0.17451 0.406742 -0.8966639 0.1748 0.3149065 -0.9329808 0.1743009 0.3140136 -0.933232 0.1745671 0.2212722 -0.9598488 0.1724209 0.2203521 -0.9600164 0.1726661 0.1281166 -0.9772503 0.1690204 0.1271868 -0.9773337 0.169241 0.05739808 -0.9845339 0.1655253 0.03916281 -0.9830808 0.1789369 0 -0.6053095 -0.7959902 0 -0.6053099 -0.79599 -0.005647301 -0.6053302 -0.7959544 -0.01373082 -0.6581673 -0.7527466 -0.02583396 -0.5065506 -0.8618232 0 1 -5.0813e-4 0.005619764 -0.6054991 -0.7958262 0.01320403 -0.5515382 -0.8340452 0.02765327 -0.7008073 -0.7128144 0.02765327 -0.7008074 -0.7128144 0.02765327 -0.7008074 -0.7128144 -9.80637e-7 1 6.4564e-6 0 1 -1.78572e-6 0 1 1.45759e-6 0 1 3.18122e-6 8.36227e-6 1 9.43058e-6 5.48155e-6 1 0 5.82262e-6 1 7.76981e-6 -9.35079e-5 1 -2.71604e-6 -1.71213e-4 1 -5.33132e-5 1.4372e-5 1 5.60492e-6 9.72499e-6 1 8.91064e-6 7.43101e-6 1 8.86839e-6 0 1 -1.79701e-6 0 1 -3.80959e-6 3.47257e-4 1 -1.51829e-4 1.06919e-4 1 -5.85539e-7 0.7059016 0.3470013 0.6174893 0.7272334 0.2463126 0.640673 0.7436456 0.1464877 0.6523287 0.7498158 0.04687279 0.6599843 0.7487112 0.04887521 0.6610922 0.6987274 0.04890137 0.7137147 0.6812843 0.06708431 0.7289386 0.6605732 0.04891926 0.7491662 0.6006665 0.04886019 0.7980053 0.4889339 0.08243107 0.8684174 0.5380229 0.04892188 0.8415094 0.6006723 0.04886114 0.7980009 0.5091757 0.04886656 0.8592743 0.4083846 0.04886198 0.9115014 0.4012993 0.03635519 0.9152252 0.2994326 0.05988305 0.9522365 -0.05434244 0.05331814 0.9970979 0.05456668 0.04475712 0.9975066 0.0658589 0.06071335 0.9959802 0.1284606 0.04641366 0.990628 0.184548 0.06355422 0.9807665 0.195625 0.0488851 0.9794597 0.2920051 0.0488792 0.9551669 0.7031798 0.3499034 0.6189555 0.6396904 0.3497989 0.6844246 0.639687 0.3497952 0.6844297 0.563399 0.3497612 0.7484977 0.5633999 0.3497691 0.7484933 0.4775925 0.3497382 0.8059706 0.4775962 0.3497292 0.8059723 0.3830496 0.349704 0.8549739 0.383053 0.3497042 0.8549721 0.2810362 0.3496819 0.8937233 0.2810404 0.3496802 0.8937226 0.1732492 0.3496649 0.9207167 0.1732558 0.3496709 0.9207131 0.06181824 0.3496627 0.934834 0.06179815 0.3496541 0.9348385 -0.05098479 0.3496541 0.9354906 -0.05098664 0.3496599 0.9354884 -0.1626645 0.3496679 0.9226444 -0.1626639 0.3496645 0.9226459 -0.2709022 0.3496795 0.896848 -0.2709061 0.3496759 0.8968483 -0.3735387 0.3496994 0.8591736 -0.3735504 0.3496922 0.8591715 -0.468877 0.3497207 0.8110794 -0.4688753 0.3497263 0.8110781 -0.555566 0.3497563 0.7543321 -0.5555561 0.3497614 0.7543371 0.725275 0.2488776 0.6419005 0.6613582 0.2487692 0.7076152 0.6613532 0.2487726 0.7076187 0.5824867 0.2487445 0.7738446 0.5824829 0.2487419 0.7738483 0.4937641 0.2487174 0.8332687 0.4937686 0.248729 0.8332626 0.3960285 0.2487073 0.8839153 0.3960183 0.248707 0.8839199 0.2905533 0.2486892 0.9239764 0.2905488 0.2486871 0.9239785 0.1791203 0.2486754 0.9518805 0.1791226 0.2486795 0.951879 0.06389844 0.2486732 0.9664775 0.06388938 0.2486695 0.9664791 -0.05270332 0.2486688 0.9671537 -0.05271518 0.248659 0.9671556 -0.1681776 0.2486645 0.9538775 -0.1681669 0.2486737 0.953877 -0.2800769 0.2486847 0.9272071 -0.2800693 0.2486822 0.9272101 -0.386197 0.2486988 0.8882572 -0.3861988 0.2486973 0.8882568 -0.4847487 0.248719 0.838545 -0.4847488 0.2487182 0.8385451 -0.5743783 0.2487429 0.7798824 -0.574374 0.2487507 0.7798832 0.742634 0.1479647 0.6531472 0.6753121 0.147919 0.7225466 0.6753107 0.1479165 0.7225484 0.5947703 0.1479013 0.7901732 0.5947768 0.1479066 0.7901673 0.5041841 0.1478919 0.8508388 0.5041787 0.147881 0.8508437 0.4043721 0.1478673 0.9025622 0.4043781 0.1478725 0.9025587 0.2966738 0.1478618 0.9434626 0.2966785 0.1478613 0.9434612 0.1828987 0.1478539 0.9719504 0.1828952 0.1478415 0.9719529 0.06523913 0.1478374 0.9868577 0.06525355 0.1478589 0.9868535 -0.05382746 0.1478588 0.9875426 -0.05382066 0.1478567 0.9875433 -0.1717185 0.1478599 0.9739868 -0.1717253 0.1478469 0.9739876 -0.2859737 0.1478545 0.946762 -0.2859773 0.1478693 0.9467586 -0.3943369 0.1478799 0.9069896 -0.3943423 0.1478769 0.9069877 -0.494972 0.1478888 0.856231 -0.4949735 0.1478897 0.8562301 -0.5864866 0.1479045 0.7963402 -0.5865013 0.1478923 0.7963317 -0.6567251 0.0489372 0.7525407 -0.5786786 0.04883199 0.8140926 -0.592938 0.01622867 0.8050846 -0.4844703 0.07450383 0.8716294 -0.4998836 0.04887902 0.8647122 -0.3960688 0.04886764 0.9169197 -0.3983144 0.04498529 0.9161452 -0.2864892 0.05265545 0.9566354 -0.288803 0.0488708 0.9561405 -0.1900231 0.04891097 0.9805606 -0.173227 0.06855267 0.9824932 -0.131012 0.04894065 0.9901722 -0.05722045 0.04886716 0.997165 -0.695205 0.04894787 0.717143 -0.6739192 0.06737202 0.7357268 -0.6680216 0.147915 0.7292931 -0.6680294 0.1479097 0.729287 -0.6542195 0.248771 0.7142198 -0.6542204 0.2487745 0.7142177 -0.6327855 0.3497884 0.6908188 -0.6327851 0.349792 0.6908174 -0.7458561 0.06412154 0.6630137 -0.7561959 0.04885858 0.6525187 -0.729637 0.1629064 0.6641471 -0.7391622 0.1479305 0.6570813 -0.7267988 0.233096 0.6460881 -0.7178572 0.2488948 0.6501788 -0.7131143 0.3348159 0.6159272 -0.70016 0.3498256 0.6224132 -0.9220722 0.3663697 0.1247239 -0.9283955 0.3159589 0.1955813 -0.8925913 0.3986011 0.2107082 -0.8830162 0.3868992 0.2656906 -0.8806029 0.3676391 0.298965 -0.8701902 0.3806356 0.312867 -0.8558727 0.3525494 0.3784057 -0.8448749 0.3608924 0.3948964 -0.8249495 0.3406572 0.4510111 -0.8146638 0.3463536 0.4651474 -0.7872003 0.3346027 0.5180315 -0.7807483 0.3383487 0.5253118 -0.7506837 0.3340199 0.5700041 -0.7486306 0.3349231 0.5721702 -0.8318819 0.06393611 0.5512576 -0.9487518 0.2374885 0.2084934 -0.9902641 0.1277881 0.0552026 -0.9833245 0.08624577 0.1601089 -0.8869273 8.06864e-5 0.461909 -0.917903 0.020765 0.3962612 -0.928133 -0.08442121 0.36255 -0.9565542 0.06130301 0.2850368 -0.9721699 0.03160935 0.2321352 -0.984519 0.06593805 0.1624026 -0.9893984 0.03573226 0.1407619 -0.9380024 0.3464602 0.01081198 -0.9478713 0.2856513 0.1412211 -0.9205434 0.3454055 0.1824693 -0.9177246 0.2960042 0.2648834 -0.9177243 0.2960025 0.2648863 -0.9010872 0.2554216 0.350431 -0.9010897 0.2554197 0.3504259 -0.8711365 0.2248712 0.4365252 -0.8711345 0.2248741 0.4365277 -0.8287736 0.205289 0.520568 -0.8287723 0.2052904 0.5205692 -0.8065193 0.2020349 0.5556155 -0.7772642 0.2332634 0.5843361 -0.9669118 0.2231294 0.1236724 -0.9631693 0.17416 0.204874 -0.9631703 0.1741583 0.2048705 -0.9431341 0.1252752 0.3079031 -0.9431325 0.125275 0.3079082 -0.9070568 0.08848267 0.411605 -0.9070586 0.08848458 0.4116009 -0.8753967 0.07334101 0.4778094 -0.8550494 0.07221782 0.5134931 -0.8054398 -0.005610883 0.5926511 -0.7904575 0.1631142 0.5903988 -0.9535575 0.2970863 0.04967707 -0.981953 0.1798937 0.05836725 -0.9246322 0.3775035 0.05046385 -0.9387739 0.3402655 0.0540657 -0.9380372 0.3402596 0.0656473 -0.9380365 0.3402614 0.06564778 -0.9679694 0.2391955 0.076294 -0.9957293 0.03577607 0.08510714 -0.9963719 0.06550651 0.054331 -0.9954177 0.06550484 0.06966364 -0.9954182 0.06549751 0.06966233 -0.9944822 0.06549811 0.08194684 -0.9879902 0.1278722 0.08674269 -0.9342861 0.3474659 0.07985556 -0.9370185 0.3402651 0.07884263 -0.9749417 0.2055114 0.08516842 -0.9762672 0.2055102 0.06832277 -0.9762679 0.2055068 0.06832218 -0.9772709 0.2055079 0.05203986 -0.9966562 0.06009668 0.05536258 0 0 -1 0 0 -1 -1.53386e-6 0 -1 -4.35264e-7 0 -1 -1.73179e-6 -2.54235e-6 -1 6.06767e-7 0 -1 3.05219e-6 0 -1 -1.87083e-6 -1.32165e-7 -1 1.51878e-6 -1.42045e-7 -1 0 -1.63795e-7 -1 0 -1.63795e-7 -1 -4.11896e-6 -1.52914e-7 -1 0 -1.48703e-7 -1 5.5972e-7 0 -1 1.75509e-6 -1.28118e-6 -1 -5.71484e-6 0 -1 -1.79035e-5 0 -1 -1.80476e-6 0 -1 2.78563e-7 0 -1 3.99841e-5 0 -1 -8.79504e-7 0 -1 3.49209e-6 -1.63732e-7 -1 -2.75931e-6 -1.60814e-7 -1 2.4104e-6 -1.58939e-7 -1 -1.71231e-6 -1.54386e-7 -1 2.83864e-6 -1.46454e-7 -1 -8.18039e-7 -1.33848e-7 -1 1.18567e-6 0 -1 -4.58958e-6 0 -1 -4.26281e-6 0 -1 0 -2.82211e-7 -1 0.9199279 0.3751088 -0.1141328 0.9254391 0.3501633 -0.1447351 0.8821503 0.3617272 -0.301603 0.8281638 0.3390039 -0.4463419 0.8074025 0.2795885 -0.5195494 0.7630218 0.2916775 -0.5768207 0.3325868 0.1436392 -0.9320697 0.4650896 0.1993402 -0.8625284 0.5344516 0.1849591 -0.8247132 0.6213481 0.2593404 -0.7393708 0.7053031 0.2948932 -0.6446593 0.03076237 0.01379007 -0.9994317 0.1915414 0.06786012 -0.9791359 0.9448274 0.2939893 -0.1444706 0.9448462 0.2946416 -0.1430109 0.8161782 0.2539389 -0.519007 0.8165602 0.2546066 -0.5180781 0.5405405 0.1681851 -0.824336 0.540919 0.168613 -0.8240002 0.9735661 0.1780966 -0.1430059 0.9736265 0.1784954 -0.1420949 0.841382 0.1539138 -0.5180608 0.8416538 0.1542739 -0.5175119 0.5573623 0.1019554 -0.8239858 0.5576224 0.1021869 -0.8237811 0.9880632 0.05948561 -0.1421008 0.9864133 0.05379086 -0.1552272 0.8536512 0.05735844 -0.5176771 0.8446259 0.0486716 -0.53314 0.5656351 0.03642493 -0.8238509 0.5649067 0.0359342 -0.824372 0.198287 0.01018166 -0.9800912 0.1804374 0.06937605 -0.9811367 0.1849234 0.05751872 -0.9810683 0.1850684 0.05765771 -0.9810328 0.190696 0.03487408 -0.9810295 0.1907853 0.0349428 -0.9810097 0.1935482 0.01215279 -0.9810156 -0.4425729 0.1944751 -0.8753907 -0.8876016 0.2154645 -0.4071101 -0.7890087 0.3226899 -0.5228161 -0.894352 0.3669387 -0.2559112 -0.9316909 0.3310805 -0.1494584 -0.9328776 0.3293131 -0.1459194 -0.9252473 0.3775348 -0.03721874 -0.9895479 0.05959832 -0.1313132 -0.9875754 0.06432104 -0.1433797 -0.1757649 0.07152885 -0.9818301 -0.292897 0.05376034 -0.9546315 -0.129214 0.05795401 -0.9899218 -0.7998474 0.2859489 -0.5277096 -0.7039126 0.2943334 -0.6464325 -0.5172547 0.2156901 -0.8282061 -0.6606111 0.1415178 -0.7372691 -0.5998333 0.167747 -0.7823434 -0.05467504 0.003296256 -0.9984988 -0.2317606 0.0389595 -0.9719924 -0.1893758 0.01653259 -0.9817656 -0.5510987 0.02718436 -0.8339973 -0.561321 0.02780318 -0.8271311 -0.5509926 0.03319519 -0.8338497 -0.8521488 0.05143779 -0.5207654 -0.8585746 0.04613333 -0.5106089 -0.858575 0.04613429 -0.510608 -0.973513 0.178119 -0.143339 -0.973322 0.1784584 -0.1442112 -0.8397639 0.153632 -0.5207628 -0.8393697 0.1538783 -0.5213252 -0.5525748 0.1010937 -0.8273096 -0.5522406 0.1012171 -0.8275178 -0.1872289 0.03424596 -0.9817192 -0.1871153 0.03427547 -0.9817398 -0.9448612 0.2940031 -0.1442202 -0.9444676 0.2945385 -0.1456986 -0.8148156 0.2535298 -0.5213429 -0.8141345 0.2538506 -0.5222498 -0.5360805 0.1667972 -0.8275243 -0.535506 0.166935 -0.8278685 -0.181631 0.05650377 -0.9817421 -0.1814427 0.05652987 -0.9817755 0.9342778 0.3522956 0.05488961 0.9243292 0.3773442 0.05680686 0.9656532 0.2543794 0.05296283 0.9530991 0.2969555 0.05847787 0.986547 0.1537004 0.05568945 0.9819383 0.1798544 0.05873388 0.9953958 0.05140364 0.08090025 0.9966128 0.05140542 0.06419122 0.9947873 0.08388924 0.05797272 0.9967868 0.06008374 0.05297178 0.9961892 0.03583073 0.07951956 0.9847161 0.1536999 0.08191806 0.9886169 0.1279866 0.07909584 0.9638297 0.2543885 0.07949149 0.9677914 0.2393383 0.07808226 0.932772 0.3522913 0.07633686 0.9346114 0.3474648 0.07595992 0.4981539 0.1368609 0.8562195 0.9771068 0.07010936 0.2008661 0.7759229 0.3428058 0.5295544 0.8275247 0.3698655 0.4223771 0.8583161 0.38928 0.3342973 0.8570606 0.3707088 0.357802 0.8916561 0.3492975 0.2879944 0.8961329 0.3592106 0.2606027 0.9138593 0.3386653 0.2239806 0.9260463 0.3432846 0.1568247 0.9261357 0.3417114 0.1597059 0.9298955 0.3391928 0.1422764 0.9326674 0.3474751 0.09691584 0.9876683 0.1279922 0.09016382 0.9854668 0.06537431 0.1567843 0.9912737 0.03582096 0.1268591 0.9483335 0.0222091 0.3164971 0.9464568 -0.003711581 0.3228093 0.9127738 0.02627968 0.4076193 0.9102246 0.04323244 0.4118521 0.8886185 0.02758741 0.4578169 0.8017652 0.1245371 0.5845196 0.8597751 0.04277974 0.5088778 0.8560941 0.05319434 0.5140753 0.814795 0.05227088 0.5773882 0.8115336 0.05625969 0.5815911 0.7849932 0.04696995 0.6177213 0.7568023 0.3676384 0.5404557 0.5232743 0.3328775 0.7844595 0.7694651 0.3062921 0.560454 0.9759735 -0.01557219 0.2173326 0.9755107 0.06482928 0.2101812 0.9479987 0.0879206 0.3058898 0.9510072 0.07936388 0.2988091 0.9146155 0.1072054 0.3898531 0.914617 0.1072013 0.3898512 0.8691185 0.1448473 0.4729191 0.8691168 0.1448511 0.4729208 0.8155824 0.1914108 0.5460654 0.8155825 0.1914158 0.5460634 0.8204531 0.1865635 0.5404171 0.775328 0.2463387 0.5815358 0.9508792 0.2379242 0.1980423 0.9788549 0.19475 0.06257426 0.9622149 0.2028995 0.1815882 0.9622164 0.2028962 0.181584 0.9402735 0.2173308 0.2620172 0.9402759 0.2173263 0.2620128 0.9100644 0.2404435 0.3375939 0.9100644 0.2404408 0.3375959 0.872292 0.2716988 0.4065544 0.8722907 0.2716964 0.4065589 0.8278513 0.3103501 0.467274 0.8278499 0.3103528 0.467275 0.8025015 0.3341551 0.4942993 0.7663089 0.480594 0.4263802 0 -1 1.84868e-6 0 -1 1.22819e-5 -0.04588705 0 0.9989466 -0.06400567 0.008307754 0.997915 -0.1503152 -0.007086753 0.9886128 -0.2441961 0.02904099 0.969291 -0.1948984 -0.01129555 0.9807584 -0.2714574 -5.3002e-6 0.9624505 -0.3036199 9.49162e-6 0.9527933 -0.3085423 8.46111e-4 0.9512103 -0.350506 -0.001245319 0.9365597 -0.430841 0.02002608 0.9022057 -0.3945528 -0.0171864 0.9187125 -0.5167334 0.01091372 0.8560768 -0.5009867 -6.31525e-5 0.865455 -0.5706188 2.75276e-5 0.8212151 -0.5570583 -0.004385948 0.8304619 -0.6073471 0.006379246 0.7944111 -0.593138 -0.001222491 0.8051 -0.6740121 0.002095639 0.7387174 -0.6713944 -0.001077175 0.7410996 -0.7431177 5.66651e-4 0.6691606 -0.7422881 -2.73852e-5 0.6700809 -0.7844642 2.62616e-5 0.6201743 -0.7842055 -1.56636e-4 0.6205013 -0.8169915 1.25203e-4 0.5766499 -0.82552 0.005974054 0.5643414 -0.8653126 -0.01133018 0.5011044 -0.9846481 0 0.1745511 -0.9846816 8.37893e-4 0.1743605 -0.9646332 -5.02086e-4 0.2635953 -0.9599133 -0.02436804 0.2792359 -0.9368954 0.0185967 0.349115 -0.9290846 -6.151e-5 0.3698673 -0.9138448 1.32561e-5 0.406064 -0.9059531 -0.004040718 0.4233588 -0.8802197 0.01681995 0.4742683 -0.8514893 -0.03612321 0.5231264 0.9101449 1.36317e-5 0.4142901 0.9274131 -2.62369e-5 0.3740389 0.9842698 0 0.176672 0.9835293 0.007786035 0.1805814 0.9566497 -0.007195234 0.2911521 0.9632169 -0.03994023 0.2657405 0.9368175 0.01802062 0.3493542 0.9134922 -0.002859652 0.4068465 0.8795183 0.008719563 0.4757853 0.8740373 -0.00673449 0.4858123 0.8322995 0.002377271 0.5543214 0.806952 -0.012205 0.5904909 0.7916775 9.76199e-6 0.6109392 0.76448 -2.63803e-6 0.6446475 0.7499768 3.71376e-4 0.6614641 0.744571 -0.002001106 0.6675404 0.6826003 0.005699872 0.7307698 0.6800345 0.002645075 0.7331754 0.5935545 -0.002039313 0.8047913 0.5897285 1.63236e-5 0.8076016 0.5356196 -7.67609e-6 0.8444594 0.543501 0.001464128 0.8394073 0.4665939 -0.006850659 0.8844451 0.4815938 0.006992816 0.8763667 0.373502 -0.004491686 0.9276185 0.3713015 -0.003555774 0.9285056 0.3021107 0.001856207 0.953271 0.3103111 1.23285e-5 0.9506351 0.2465493 -5.01084e-6 0.9691303 0.2483102 -6.54174e-4 0.9686804 0.1803251 4.4415e-4 0.9836069 0.144982 0.009345293 0.9893901 0.1231163 0.001631677 0.992391 0.04588973 -0.001854896 0.9989449 0.0461778 -0.001967668 0.9989313 0.004763484 0 0.9999887 0.06762337 0.9977109 -2.82578e-4 0.11189 0.9937152 -0.003286898 0.07340526 0.9973011 0.001552164 0.125952 0.9920364 -1.10442e-4 0.1410183 0.9900071 3.46309e-5 0.1447946 0.9894618 5.63682e-6 0.1629053 0.9866417 6.04148e-6 0.1603671 0.9870575 1.09131e-4 0.252907 0.9674825 0.003980576 0.2336784 0.9723119 0.002028822 0.2060164 0.9785486 3.77629e-4 0.1821814 0.9832649 -4.53766e-5 0.3244422 0.9457679 -0.01613497 0.3629563 0.9318026 -0.002580106 0.3834829 0.9235481 2.54471e-4 0.2812252 0.9589081 -0.03752046 0.3304334 0.943807 -0.006505489 0.3500822 0.9367102 0.004055261 0.3439407 0.9389881 0.002521812 0.340941 0.9400823 0.002124011 0.3403066 0.9403124 0.002049863 0.3355981 0.942004 0.001568317 0.325023 0.9457059 7.77362e-4 0.3180553 0.9480721 4.64537e-4 0.1984958 0.980098 -0.002735912 0.2395546 0.9708829 -1.16971e-4 0.2746798 0.9615358 7.51676e-5 0.2774804 0.9607314 1.99228e-4 0.2970822 0.954852 -8.87499e-5 0.3126698 0.949862 2.43048e-4 0.0225107 0.9997466 1.95172e-4 0.01836204 0.9998314 3.22654e-6 -0.02250814 0.9997467 4.02346e-6 -0.01837354 0.9998313 2.39176e-4 -0.06760293 0.9977124 -2.82007e-4 -0.07340532 0.997302 -6.75341e-4 -0.1123789 0.9936654 3.20035e-4 -0.1111746 0.9938009 3.58427e-4 -0.1212841 0.9926179 6.84543e-5 -0.1410332 0.990005 -4.06572e-5 -0.1390081 0.9902913 5.65627e-6 -0.1628961 0.9866433 6.71787e-6 -0.1545781 0.9879806 3.44201e-4 -0.1768741 0.9842336 -1.56047e-4 -0.2009884 0.9795936 2.97961e-4 -0.1973968 0.9803237 1.40417e-4 -0.2339826 0.9722408 -1.72178e-4 -0.2240298 0.9745822 4.36471e-4 -0.2516477 0.9678189 -1.31785e-4 -0.2692298 0.963076 2.09143e-4 -0.340188 0.9403526 0.003015577 -0.3381105 0.9411026 0.002699732 -0.2777268 0.9606601 -8.07813e-5 -0.3005933 0.9537525 9.97434e-5 -0.3137156 0.9495168 6.78599e-4 -0.3238436 0.9461098 0.001278638 -0.3339558 0.9425863 0.002201497 -0.3380262 0.9411329 0.002689063 -0.3863694 0.9223442 8.68612e-6 -0.3811705 0.9245048 -6.94536e-5 -0.370111 0.9289863 -0.001594543 -0.3534277 0.9354429 -0.005958795 -0.335767 0.9418666 -0.01216518 -0.3459739 0.9382329 0.004601001 -0.3254798 0.9455227 -0.007066965 -0.2675639 0.9624655 -0.04549384 -0.3079931 0.9510928 -0.0237227 0.8016278 0.4247388 0.4207018 0.7351817 0.6671699 0.1199676 0.7625639 0.6175318 0.1927458 0.7461047 0.6138356 0.2579413 0.7546554 0.5486557 0.3598228 0.8819355 0.4201735 0.2136449 0.7723321 0.6263194 0.1059588 0.863308 0.4826427 0.1474975 0.8541072 0.5078453 0.1122242 0.8141712 0.5692993 0.114121 0.8112136 0.5082814 0.2891068 0.7925588 0.4955478 0.3553633 0.7785028 0.4989031 0.3808267 0.7759183 0.4985033 0.3865818 0.7579932 0.4927493 0.4273694 0.7626896 0.5754988 0.2951372 0.8242889 0.4487192 0.3452519 0.782107 0.5030273 0.3677937 0.76972 0.5515364 0.3214638 0.7602406 0.5636428 0.323019 0.7829734 0.569925 0.2492754 0.7375021 0.6211492 0.2650744 0.752182 0.6030669 0.2655799 0.7313841 0.6019783 0.3204676 0.7949796 0.6051056 -0.04306662 0.7574604 0.6426064 0.1153723 0.7863004 0.5960279 0.1627345 0.7861269 0.5953201 0.1661285 0.8103729 0.5439114 0.2178447 0.8103753 0.5439087 0.2178425 0.8175894 0.5170631 0.2533643 0.8173525 0.5161229 0.2560317 -0.9930539 0 0.1176609 -0.9930537 0 0.1176629 -0.7015261 -0.5471757 -0.4565742 -0.705893 -0.6012574 -0.3744391 -0.7072276 -0.5839646 -0.3985155 -0.7065186 -0.5703878 -0.4189144 -0.7081963 -0.6064423 -0.361505 -0.6992947 -0.6199694 -0.355844 -0.7008947 -0.6168454 -0.358118 -0.7074154 -0.6303411 -0.3197399 -0.7069575 -0.6319944 -0.3174811 -0.7069861 -0.6316912 -0.3180205 -0.7202103 -0.4380791 -0.5379443 -0.7033712 -0.4984619 -0.506759 -0.7114015 -0.5527727 -0.4339935 -6.95175e-7 0 1 0 0 1 6.95175e-7 0 1 0.2670865 0.9636247 0.009616911 0.02111166 0.9997768 8.11199e-4 0.3690465 0.9290087 0.02733939 0.6070116 0.7933712 0.04581964 0.741154 0.6680648 0.06618362 0.6913201 0.7203417 0.05642956 0.6604025 0.7498784 0.03938424 0.6822352 0.7295629 0.0478869 0.6983413 0.7138207 0.05272042 0.7107396 0.7012473 0.05569142 0.7324358 0.6782056 0.05979239 0.4498551 0.8924602 0.03384101 0.4289572 0.9032008 0.0149663 0.4834573 0.8746163 0.0362671 0.5771217 0.8154695 0.04404765 0.5432248 0.8392999 0.02196997 0.5694662 0.8212499 0.03545212 0.1675179 0.9855959 0.02320879 0.1345289 0.9900532 -0.04118937 0.1861246 0.9825242 0.001994252 0.3103635 0.9491999 0.05190467 0.2644773 0.9638826 -0.03133982 0.323132 0.9462051 0.01678013 0.04737967 0.9988729 0.002854466 0.1685585 0.9856566 0.008312165 0.1787444 0.9838421 0.01025998 0.1273614 0.9918418 0.005390763 0.04747968 0.9988719 7.88815e-4 0.08392208 0.9964504 0.00661832 0.05044138 0.9987219 0.00323081 0.4494355 0.8930401 0.02207219 0.4064397 0.9135212 0.01690447 0.3132008 0.9496077 0.01226633 0.3556296 0.9343203 0.02393996 0.3218971 0.9466117 0.01756751 0.4974841 0.866863 0.03252917 0.4507979 0.8924524 0.01760804 0.5459768 0.8374785 0.0232194 0.5781104 0.8154727 0.02815586 0.5781892 0.8154172 0.02814596 0.7402034 0.6717276 0.02968144 0.7154778 0.6979669 0.0305562 0.6916443 0.7215359 0.03184771 0.6928825 0.720356 0.03164118 0.6489639 0.7603616 0.02638524 0.6080196 0.793501 0.02585172 0.7827115 0.6214781 0.03358328 0.7921745 0.6092312 0.03601372 0.826797 0.5615249 0.03311735 0.856211 0.5154837 0.03434211 0.8727094 0.4866259 0.03966975 0.8558644 0.5159315 0.03620767 0.858394 0.5080996 0.07067286 0.7523547 0.6558396 0.06194275 0.7903329 0.6092125 0.06506955 0.7903323 0.6092135 0.06506937 0.858393 0.5081014 0.07067316 0.8597432 0.5080929 0.05179923 0.0406813 0.9991678 0.002970099 0.04773056 0.9988582 -0.002021074 0.04737955 0.9988729 0.002854704 0.168469 0.9856547 0.01015025 0.1684694 0.9856547 0.01015025 0.312881 0.9496053 0.01885098 0.312881 0.9496053 0.0188511 0.4503331 0.8924483 0.02713263 0.4503338 0.892448 0.02713257 0.5777755 0.8154532 0.03481096 0.5777748 0.8154535 0.0348109 0.6923721 0.7203338 0.04171538 0.6923726 0.7203333 0.04171538 0.7915765 0.6092061 0.04769241 0.7915763 0.6092064 0.04769241 0.8597441 0.5080917 0.05179959 0.8603354 0.50812 0.0404635 0.9930537 0 0.1176629 0.9930539 0 0.1176607 -0.7685877 0.5343657 0.3517475 -0.7608059 0.6000967 0.2470999 -0.7402328 0.6680353 0.07605463 -0.7710984 0.621914 0.1364932 -0.7922576 0.6051084 0.07856106 -0.7780323 0.6184283 0.1105095 -0.7847873 0.6144568 0.08094304 -0.7907993 0.6091698 0.05957108 -0.7780856 0.6131729 0.1363893 -0.7863845 0.6063575 0.1180263 -0.7978832 0.5950657 0.09633028 -0.7400204 0.632287 0.2293097 -0.7890774 0.5880709 0.1775656 -0.7471081 0.6363995 0.191899 -0.7651877 0.6205222 0.1715809 -0.7470736 0.5920561 0.3022428 -0.7099609 0.6252554 0.3240544 -0.6912459 0.6463566 0.3231136 -0.7474609 0.6097896 0.2635506 -0.7462595 0.6112567 0.2635565 -0.7406465 0.6296027 0.2346128 -0.7779247 0.471711 0.4151169 -0.7872867 0.5035091 0.3558907 -0.8174235 0.4728047 0.3290508 -0.8176165 0.4911972 0.3003805 -0.8319536 0.4789022 0.2801893 -0.850158 0.4628045 0.2510849 -0.7927055 0.543419 0.2762498 -0.8210195 0.5261359 0.2216034 -0.7989433 0.5483725 0.2469358 -0.7989495 0.5483657 0.2469304 -0.8215839 0.5293245 0.2116969 -0.82407 0.5284878 0.2039834 -0.8231561 0.5292036 0.2058099 -0.8438897 0.5129947 0.1571196 -0.8247443 0.5337044 0.1869666 -0.8521246 0.5074182 0.1281045 -0.8520553 0.507511 0.1281968 0.7201446 -0.438122 -0.5379971 0.6869539 -0.5727955 -0.4472133 0.7074302 -0.6303344 -0.3197202 0.7069588 -0.63196 -0.3175466 0.7074257 -0.5905882 -0.3882712 0.703321 -0.6104829 -0.3642117 0.70324 -0.6106831 -0.3640325 0.7068651 -0.6235507 -0.3339557 0.7071477 -0.6303185 -0.320376 0.7045921 -0.5488395 -0.4498057 0.7114966 -0.552697 -0.433934 0.7033356 -0.4984869 -0.506784 -0.08498746 0.9963776 0.002998471 -0.6096836 0.7922225 0.02587419 -0.7415877 0.6680158 0.06166523 -0.722723 0.6887043 0.05794709 -0.7107396 0.7012473 0.05569142 -0.6983413 0.7138207 0.05272042 -0.6817017 0.7300719 0.04772859 -0.6916719 0.7203565 0.05173683 -0.743071 0.6664104 0.06117832 -0.790332 0.6092138 0.06506931 -0.790333 0.6092125 0.06506961 -0.8597421 0.5080948 0.05179941 -0.8603358 0.5081193 0.04046392 -0.8577289 0.5127993 0.03658318 -0.87377 0.4850752 0.03504616 -0.7287166 0.6841669 0.02979892 -0.7652257 0.6429975 0.031367 -0.7921692 0.6092305 0.03614288 -0.8053398 0.5918319 0.03410357 -0.8456636 0.5326205 0.03418511 -0.6930972 0.7203422 0.02689993 -0.6519405 0.7573014 0.03831946 -0.6908959 0.7222506 0.03189122 -0.4233771 0.9057622 0.01862502 -0.4664367 0.884197 0.0251528 -0.4506302 0.8924604 0.02114021 -0.5057299 0.8624355 0.02102982 -0.5782886 0.8154675 0.02439302 -0.540452 0.8407338 0.03283673 -0.5778153 0.8156844 0.02808153 -0.3803235 0.9247301 0.01511609 -0.3130627 0.9496119 0.01513761 -0.3405629 0.9399853 0.0210855 -0.1339619 0.99097 0.005725443 -0.1810915 0.9834042 0.0110448 -0.1685348 0.9856565 0.008800745 -0.228186 0.9735764 0.008950471 -0.292622 0.9561519 0.01208198 -0.009278237 0.999957 3.56045e-4 -0.04737961 0.9988729 0.002854645 -0.02194941 0.9997578 0.001603484 -0.04818016 0.9988043 -0.008298814 -0.06264877 0.9980353 8.76558e-4 -0.1184899 0.9928653 0.01336276 -0.1699855 0.9853789 -0.01155096 -0.1984263 0.9800291 0.01303958 -0.2763842 0.9608002 0.02178704 -0.3136752 0.9495018 0.007369637 -0.3525087 0.9354139 0.02717661 -0.4224994 0.9058575 0.03027456 -0.4505856 0.8924247 0.02347153 -0.4725011 0.8807591 0.0317192 -0.6394222 0.7672289 0.04999101 -0.6098147 0.7912065 0.04602473 -0.5775387 0.8154678 0.03822934 -0.574223 0.8177784 0.03881448 -0.5126676 0.8576336 0.04045671 -0.0390737 0.9992341 0.00207436 -0.04737663 0.9988729 0.002916634 -0.04737955 0.9988729 0.002854526 -0.1684691 0.9856547 0.01015025 -0.1684694 0.9856547 0.01015025 -0.3128809 0.9496053 0.01885098 -0.3128811 0.9496052 0.0188511 -0.4503341 0.8924478 0.02713268 -0.450333 0.8924484 0.02713239 -0.5777751 0.8154535 0.03481078 -0.5777748 0.8154536 0.03481101 -0.6923726 0.7203333 0.04171532 -0.6923725 0.7203334 0.04171538 -0.7915771 0.6092054 0.04769253 -0.791576 0.6092068 0.04769235 -0.8597431 0.5080931 0.05179941 -0.8583943 0.508099 0.07067322 -0.858393 0.5081014 0.07067275 0.6936907 0.7091217 0.1262531 0.5287598 0.8467674 0.05829244 0.570468 0.815703 0.09589177 0.5988363 0.7984485 0.06225222 0.9674339 -0.01180255 0.2528486 0.7181624 0.6719333 0.1809651 0.9342684 0.01576751 0.356222 0.9545906 0.006997227 0.2978389 0.7802092 0.5198979 0.3478216 0.8684514 -0.08552157 0.4883424 0.9066314 0.1559791 0.3920333 0.654702 0.1217316 0.7460206 0.686553 0.3461406 0.6393995 0.6731099 -0.1487807 0.7244222 0.7703225 0.345917 0.5356722 0.7742987 -0.07461857 0.6284057 0.8483056 0.1621827 0.504058 0.6017831 0.09461724 0.7930351 0.5849265 0.3350298 0.7386583 0.5189605 0.04335892 0.8536978 0.4612364 0.2723468 0.8444455 0.4181339 0.08780688 0.9041317 0.5238388 0.8479332 0.08125448 0.5101882 0.8532953 0.1076812 0.4971668 0.8624819 0.09460502 0.4712996 0.8722422 0.1306535 0.4591007 0.8810051 0.114265 0.4247189 0.8928458 0.1498011 0.4146182 0.9004194 0.1316696 0.3712221 0.9137542 0.1650677 0.364037 0.919694 0.1471061 0.3116232 0.9336849 0.1764189 0.3075483 0.9378686 0.1606754 0.2474668 0.951358 0.1835157 0.2465012 0.9530291 0.1759907 0.3169842 0.7903903 0.5242177 0.7985489 0.5745648 0.1794295 0.7810704 0.5811342 0.2285001 0.7734799 0.5941879 0.2206117 0.7319579 0.6110771 0.3013679 0.7239219 0.6260842 0.2897513 0.6700116 0.6464903 0.3648765 0.6627562 0.6617999 0.3503929 0.5966925 0.6846045 0.4186586 0.5910133 0.6989066 0.4027816 0.512677 0.7230318 0.4630199 0.5090743 0.7353377 0.4473498 0.4186135 0.7595246 0.4978807 0.4169899 0.7691722 0.4842454 0.3164193 0.7917823 0.5224556 0.3398462 0.4942449 0.8001416 0.302116 0.1535841 0.9408177 0.3227061 0.2410191 0.9152981 0.3384171 0.5058635 0.7934583 0.4665272 0.4770419 0.7448379 0.465187 0.4632162 0.754342 0.5812814 0.4321163 0.6894835 0.5805218 0.4151902 0.7004368 0.6831452 0.3835068 0.6214782 0.6831874 0.3644546 0.6327937 0.7720358 0.3336958 0.5409326 0.7729149 0.3140113 0.5513615 0.8476383 0.2856336 0.4471272 0.8491948 0.2669721 0.4556251 0.9085468 0.2427463 0.340025 0.9104065 0.2269043 0.3459398 0.9452024 0.2128832 0.2475345 0.8350625 0.5271303 0.1574938 -0.3402792 0.5155081 0.7864233 -0.3123947 0.1672543 0.9351126 -0.9107119 0.3489858 0.2209362 -0.9634987 0.1188455 0.2398878 -0.9358102 -0.2267303 0.2699123 -0.9226784 -0.2734909 0.2717859 -0.5223982 0.8485329 0.08421498 -0.5512979 0.8294833 0.08960092 -0.5695736 0.816392 0.09534311 -0.6175609 0.7737784 0.1410157 -0.515012 0.8514985 0.09855443 -0.5398082 0.8319394 0.1283897 -0.4903522 0.865258 0.1043237 -0.4791528 0.8694919 0.119985 -0.5015772 0.8502698 0.1595673 -0.4232057 0.9002291 0.1023933 -0.4532014 0.8717764 0.1860498 -0.381352 0.9174106 0.113704 -0.3946281 0.8957614 0.2046467 -0.3374719 0.9327064 0.1271677 -0.3273817 0.9205549 0.2130729 -0.2912389 0.9454345 0.1460603 -0.4648153 0.325181 0.8235315 -0.3889361 0.04281049 0.9202696 -0.3123775 0.3544666 0.8813477 -0.5849367 0.3353999 0.7384822 -0.5418791 0.1274393 0.8307384 -0.4871863 0.1422001 0.8616431 -0.7776253 0.28355 0.561158 -0.6889358 -0.06747645 0.7216747 -0.6863095 0.349578 0.6377888 -0.6510718 0.1016401 0.7521801 -0.6004775 0.1172413 0.7910001 -0.8313258 0.5341556 0.1535426 -0.6565475 -0.658922 0.3671066 -0.8315296 0.4897276 0.2621557 -0.7208341 -0.4727445 0.5068638 -0.8144137 0.4284657 0.3913407 -0.8307789 0.05614864 0.5537634 -0.7843418 0.05376511 0.6179947 -0.2417932 0.9548054 0.1728663 -0.2543219 0.9448389 0.2063975 -0.3161703 0.7918385 0.5225209 -0.4151701 0.7696826 0.4849977 -0.4203753 0.7591331 0.4969926 -0.5070577 0.735981 0.4485805 -0.5146447 0.7225384 0.461605 -0.5890787 0.6996132 0.4043857 -0.5985887 0.684066 0.4168277 -0.6610651 0.6624847 0.3522885 -0.6716836 0.6459444 0.3627634 -0.7226428 0.6266422 0.2917311 -0.7332065 0.6106433 0.2992042 -0.7726743 0.5945755 0.2223835 -0.7818537 0.5808514 0.2265316 -0.8381286 0.402253 -0.36842 -0.7697818 0.619157 0.1551797 -0.945608 0.212625 0.2462036 -0.9112197 0.226588 0.3440009 -0.907796 0.243119 0.3417595 -0.8504776 0.2665253 0.4534889 -0.846424 0.2861728 0.4490787 -0.7746042 0.3134694 0.5492954 -0.7704239 0.3343204 0.5428416 -0.6851327 0.3638525 0.6310346 -0.6812754 0.3841031 0.6231603 -0.5825077 0.4145811 0.6991477 -0.5793552 0.4327479 0.6907075 -0.4669645 0.4628482 0.7534691 -0.4647551 0.4774808 0.745664 -0.3388351 0.5057538 0.7933499 -0.3160909 0.7983626 0.5125464 0.239858 -0.1992076 0.9501497 0.98157 -0.05737608 0.1822869 0.1733786 -0.9528006 0.2492202 0.6107475 -0.7433051 0.2729198 0.3944553 -0.8791462 0.2674083 0.5241369 -0.7778949 0.3466412 0.4580925 -0.8227545 0.3364913 -0.1661384 -0.9735234 0.157004 -0.1795041 -0.9748288 0.1322383 0.102302 -0.9531815 0.2845691 0.005040764 -0.97751 0.2108288 0.009176373 -0.9792512 0.2024422 0.4447119 -0.3559565 0.8219041 0.5224826 0.06458121 0.8502007 0.3457191 -0.2949628 0.8907724 0.4223776 0.1156638 0.8990101 0.2235571 -0.2559859 0.9404752 0.6945672 -0.2955279 0.6559267 0.7041768 -0.009418666 0.7099622 0.5719305 -0.3307339 0.7506735 0.6116338 -0.1182158 0.7822589 0.563965 -0.1033918 0.8193008 0.7712355 -0.3396302 0.5383746 0.8072128 -0.1849132 0.5605485 0.759115 -0.1423308 0.6352059 0.9264609 -0.2039138 0.3163693 0.8928182 -0.2413746 0.3802815 0.8465499 -0.3466937 0.4039269 0.8748375 -0.1973298 0.4424029 0.8471155 -0.1859691 0.4978061 0.7412914 -0.6097629 0.2804931 0.7554684 -0.5917814 0.2811805 0.8539687 -0.432179 0.2897566 -0.1387586 -0.9663398 0.2166412 -0.1443192 -0.9689948 0.2005519 -0.1475242 -0.9681404 0.2023381 -0.1568949 -0.9703157 0.1840423 -0.1558305 -0.970649 0.1831871 -0.1686668 -0.971801 0.1647856 -0.1629776 -0.97377 0.1587777 0.1447315 -0.9547665 0.2597571 0.1253077 -0.9461859 0.2983796 0.1436391 -0.9411325 0.3060025 0.1039118 -0.9260584 0.3627926 0.1224678 -0.9195402 0.3734267 0.08000928 -0.9048557 0.4181324 0.09686362 -0.897189 0.4308938 0.05320817 -0.8837011 0.4650176 0.066612 -0.8756692 0.4782952 0.0222721 -0.8637703 0.5033934 0.03158354 -0.8562091 0.5156633 0.3863656 -0.8635194 0.3241236 0.3454105 -0.8462283 0.4056962 0.3624255 -0.8363255 0.4113482 0.3048452 -0.814446 0.4937077 0.3221268 -0.8027822 0.5017721 0.2582276 -0.7805801 0.5692217 0.2739463 -0.7679968 0.578908 0.2051246 -0.7466779 0.6327686 0.2178507 -0.7341538 0.6430858 0.1446465 -0.7144458 0.6845763 0.1536307 -0.7032464 0.6941485 0.6266135 -0.7352192 0.2584731 0.5912595 -0.719222 0.3648726 0.6035035 -0.7081845 0.3664129 0.544267 -0.6839933 0.4857229 0.5588034 -0.6698581 0.4889059 0.4871858 -0.642573 0.5913966 0.5020012 -0.6265699 0.5961586 0.4207407 -0.598291 0.6819275 0.4343695 -0.5815103 0.6878728 0.3448277 -0.5536938 0.7579692 0.3559322 -0.5376432 0.7643639 0.2585275 -0.5114061 0.8195288 0.266523 -0.4974881 0.8255126 0.1517633 -0.471231 0.8688551 0.07945019 -0.6865649 0.7227145 -0.01283085 -0.8391798 0.5437028 -0.01577979 -0.8454607 0.5338046 -0.1369475 -0.9726521 0.1875984 -0.1320734 -0.967846 0.2140815 0.9657123 -0.1410729 0.2179409 0.963756 -0.1175904 0.2394723 0.9294802 -0.2520737 0.2693057 0.9200543 -0.2772846 0.2767912 0.7992684 -0.5354409 0.2728978 0.7576804 -0.5172266 0.3979915 0.7670035 -0.5033531 0.3979213 0.70138 -0.4764127 0.5301859 0.7123928 -0.4592491 0.5306475 0.6319535 -0.4285072 0.6457681 0.6433825 -0.4093387 0.6469165 0.5507234 -0.3770335 0.7446809 0.561343 -0.3575137 0.7463766 0.4576014 -0.3253027 0.8275139 0.466497 -0.3067989 0.8296114 0.3522092 -0.2759507 0.8943154 0.3586158 -0.2603656 0.89644 0.2343946 -0.2322456 0.9439922 0.1329961 -0.5602476 0.8175786 0.1484482 -0.9699133 0.1929545 0.1756849 -0.9738139 0.1442961 0.1660287 -0.9735405 0.1570143 -0.02516281 -0.9774787 0.2095288 0.1550821 -0.9798861 0.1255896 0.05451321 -0.9785587 0.1986234 0.1485601 -0.9746636 0.1672146 0.1572878 -0.9716902 0.1762917 -0.1638565 -0.9556939 0.2445409 -0.5588765 -0.7897346 0.2529355 -0.4042299 -0.8724599 0.2746126 -0.5253331 -0.7769636 0.346919 -0.7486152 -0.6005383 0.280943 -0.9316482 -0.2364838 0.2758752 -0.8456555 -0.4565414 0.2764719 -0.9680642 -0.0559538 0.2443788 -0.9320173 -0.2504354 0.2619656 -0.9815591 -0.05764347 0.1822612 -0.9351216 -0.2223008 0.2759167 -0.8934772 -0.2074092 0.3983468 -0.8757621 -0.27973 0.3934361 -0.8518202 -0.1318204 0.5069772 -0.7888425 -0.2965725 0.5383052 -0.7951287 -0.1626803 0.5842137 -0.7308164 -0.1943296 0.6543267 -0.710729 -0.269536 0.6497806 -0.6896889 -0.06396943 0.7212747 -0.571676 -0.3314149 0.750567 -0.6142365 -0.1019914 0.7825033 -0.5532304 -0.1282726 0.8230932 -0.4458425 -0.3533769 0.8224046 -0.5055068 -0.07509547 0.8595485 -0.4430348 -0.09731042 0.8912076 -0.3156728 -0.3763849 0.8710255 -0.4140248 0.2264149 0.8816575 0.1486316 -0.9683176 0.2006731 0.1480435 -0.9703689 0.1909644 0.1395186 -0.9665957 0.2150057 0.1684235 -0.9733163 0.1558487 0.1714908 -0.9722591 0.1590702 0.1648877 -0.970966 0.1733124 0.1612848 -0.9710872 0.1760023 0.1610251 -0.9709273 0.177119 0.134265 -0.9691933 0.2064877 0.1315376 -0.9663926 0.2208694 0.01161134 -0.8454068 0.5339969 -0.1341649 -0.9566927 0.2583387 -0.117084 -0.9491508 0.2922398 -0.1338303 -0.9436548 0.3026635 -0.09673005 -0.9296051 0.355637 -0.1132221 -0.9224547 0.3691317 -0.07410705 -0.9089093 0.4103561 -0.08829826 -0.9006706 0.4254363 -0.04834604 -0.8883068 0.4566987 -0.05908203 -0.8796708 0.4718992 -0.01853978 -0.868781 0.4948493 -0.02551573 -0.8607333 0.5084164 0.01666581 -0.8511877 0.5245969 -0.07852536 -0.6842126 0.7250427 -0.3783159 -0.8679208 0.3218548 -0.3386763 -0.851239 0.4008622 -0.3541435 -0.8408058 0.4094243 -0.2990539 -0.8198782 0.488228 -0.3140639 -0.8076599 0.4990485 -0.2533192 -0.786563 0.563159 -0.2665225 -0.7732073 0.5754271 -0.2011781 -0.7529557 0.6265662 -0.2112252 -0.7398324 0.6387738 -0.1415991 -0.7210791 0.678229 -0.1480971 -0.7094143 0.6890563 -0.07352495 -0.6925222 0.7176399 -0.1645554 -0.4706073 0.8668623 -0.6161267 -0.7389349 0.2726962 -0.5858764 -0.7249446 0.3622213 -0.597266 -0.7135177 0.3662867 -0.5396657 -0.6899761 0.4823836 -0.5525995 -0.6753209 0.4884421 -0.4832673 -0.648896 0.5876962 -0.4959046 -0.6322466 0.5952671 -0.4175311 -0.6049553 0.6780096 -0.428642 -0.5873915 0.6864673 -0.3422549 -0.5605634 0.7540758 -0.3507474 -0.5438383 0.7623754 -0.2565497 -0.5184416 0.8157209 -0.2620839 -0.5040361 0.8229579 -0.1599291 -0.4808988 0.8620667 -0.2374117 -0.2271056 0.9444886 -0.2585355 -0.0537424 0.9645057 -0.1948367 -0.3732073 0.9070585 -0.2334745 -0.2384899 0.9426624 -0.3554801 -0.2661123 0.8960013 -0.3512997 -0.2823622 0.8926703 -0.4628268 -0.3124658 0.829552 -0.4563935 -0.3318036 0.8255976 -0.5573085 -0.3631758 0.7466664 -0.5491934 -0.3833108 0.7426033 -0.6393232 -0.4147313 0.6475058 -0.6298789 -0.4347302 0.6436321 -0.7083324 -0.4646707 0.5313628 -0.6988031 -0.4824308 0.5281427 -0.7630416 -0.5087468 0.3986783 -0.7546324 -0.5229244 0.3963334 -0.7920485 -0.5394887 0.2856768 -0.7656384 -0.5778341 0.2826761 0.3070784 -0.9514491 0.02115738 0.3417924 -0.939762 -0.005053579 0.3428999 -0.939366 0.003357291 -0.3137885 -0.9491863 0.02412694 -0.3213177 -0.9469208 -0.009797692 -0.2816371 -0.9594556 0.01120865 -0.2816752 -0.9594987 -0.004632771 -0.2416129 -0.9703573 0.005472302 -0.2410552 -0.9705109 -0.001060485 -0.2083362 -0.9780573 4.16147e-4 -0.2028947 -0.979135 -0.01133364 -0.1682273 -0.9856633 0.01293951 -0.1588849 -0.987203 -0.01363617 -0.1222392 -0.9923897 0.01484102 -0.1144268 -0.9933125 -0.01538681 -0.07589179 -0.9969834 0.01627069 -0.06887048 -0.9975153 -0.01483964 -0.03465324 -0.9993327 0.01155292 -0.02313649 -0.9994653 -0.02310639 0.007607102 -0.9996821 0.02403879 0.02304655 -0.9995403 -0.01970392 0.05456835 -0.9983142 0.0197786 0.06878852 -0.9975315 -0.01411044 0.1020184 -0.9946875 0.01375442 0.1134925 -0.9935035 -0.0083974 0.1389077 -0.9903011 0.002919018 0.1589856 -0.9871782 -0.01425009 0.1702237 -0.9853006 0.01437544 0.1999577 -0.979761 -0.009237885 0.2168068 -0.9761449 0.01166647 0.2367594 -0.9715529 -0.005468189 0.2631458 -0.964731 0.006960332 0.2683188 -0.9633279 0.002111136 0.2942308 -0.9557343 -7.26505e-4 0.3084502 -0.9512062 -0.00808376 0.3086758 -0.9510255 0.01642751 0.2396156 0.5135344 0.8239337 -0.1691869 0.9682719 0.1839174 -0.1361027 0.9724462 0.1892741 -0.1347723 0.973734 0.1835169 -0.08198624 0.9784947 0.1892787 -0.08133035 0.9792288 0.1857325 -0.02728515 0.981661 0.1886723 -0.0271213 0.9818891 0.187505 0.02725732 0.9818856 0.1875038 0.02714568 0.9816606 0.188695 0.08177024 0.9791924 0.1857305 0.08159071 0.9785277 0.1892791 0.1354463 0.9736606 0.1834107 0.1354166 0.9725219 0.1893766 0.1891225 0.963662 0.1886487 0.2052842 0.9466314 0.2484906 0.1691614 0.9682801 0.1838974 0.2342309 0.1663259 0.9578474 0.2159919 0.2137687 0.9527069 0.1820137 0.08098018 0.9799557 0.1581285 0.2467887 0.9560809 0.1096215 0.07741206 0.9909544 -0.1575651 0.2396 0.9580006 -0.1148338 0.07077872 0.99086 -0.09530919 0.2464026 0.9644698 -0.04051643 0.1019219 0.993967 -0.03093791 0.1973373 0.9798474 0.03723251 0.1739499 0.9840504 0.02918672 0.1039289 0.9941564 0.09487503 0.2366902 0.9669419 -0.2308667 0.814733 0.5318937 -0.1949028 0.9535006 0.2298902 -0.1951854 0.9635135 0.1831514 0.2307567 0.8114519 0.5369331 0.1669844 0.8200638 0.5473679 0.1674405 0.8233305 0.5423012 0.1008805 0.8293477 0.5495504 0.1012283 0.8313625 0.5464333 0.03361666 0.834416 0.5501091 0.03376525 0.8350744 0.5491001 -0.03361326 0.8350876 0.5490892 -0.03377056 0.8344061 0.5501145 -0.1007523 0.8313971 0.5464686 -0.1013044 0.8293664 0.549444 -0.1667041 0.8234626 0.5423277 -0.1677438 0.819985 0.5472538 -0.2305923 0.8114851 0.5369536 -0.2405047 0.5347391 0.8100689 -0.2031306 0.1874843 0.9610347 -0.1981488 0.05360817 0.9787049 -0.2381159 0.5207606 0.8198228 -0.1735334 0.5294961 0.8303735 -0.1729269 0.5346286 0.8272053 -0.1050194 0.5407592 0.8345961 -0.10463 0.5438264 0.8326498 -0.03505885 0.5469563 0.8364269 -0.03491139 0.5479729 0.8357673 0.0350601 0.5479625 0.835768 0.03490561 0.5469721 0.8364229 0.1051094 0.5438023 0.832605 0.1046121 0.5408127 0.8346125 0.1736598 0.5345722 0.8270883 0.1727728 0.5295846 0.8304756 0.2388873 0.5206339 0.8196788 0.2322669 0.8066543 0.5434713 0.03540432 -0.8413268 0.5393661 -0.1738101 -0.03839492 0.9840305 -0.1077069 -0.2198388 0.9695721 -0.1018049 -0.076056 0.9918928 -0.06483614 -0.2189298 0.9735842 -0.03446245 -0.09584498 0.9947996 -0.02267193 -0.1801261 0.9833822 0.0231381 -0.1631653 0.9863275 0.02981996 -0.1113923 0.9933291 0.06539511 -0.2125581 0.9749578 0.09616684 -0.08222222 0.9919635 0.1070156 -0.2245866 0.9685601 0.1557421 -0.1070562 0.9819793 0.1084359 -0.9704061 0.215763 0.1170046 -0.9744924 0.1915057 0.08559125 -0.9787407 0.1863885 0.08396971 -0.9777743 0.1921109 0.05130535 -0.9807183 0.1885724 0.05052268 -0.980076 0.1920902 0.017012 -0.9815842 0.1902716 0.01683086 -0.9813545 0.1914679 -0.01697623 -0.9813567 0.1914443 -0.01686501 -0.9815891 0.1902586 -0.05097776 -0.9800491 0.1921072 -0.05088227 -0.9807569 0.188486 -0.08467656 -0.9776993 0.1921822 -0.08487707 -0.9788255 0.1862706 -0.02710336 -0.8367316 0.5469423 -0.1179737 -0.9743389 0.1916922 -0.1187599 -0.9758018 0.1835942 0.02892196 -0.8318347 0.5542694 0.01843339 -0.8332816 0.5525415 0.01814246 -0.8299313 0.5575707 0.01059156 -0.8306115 0.5567516 0.01068079 -0.8285199 0.5598579 0.003408014 -0.8288483 0.5594633 0.003522634 -0.8281738 0.5604605 -0.003366231 -0.8281723 0.5604636 -0.00356251 -0.8288358 0.5594808 -0.01021039 -0.8285412 0.5598351 -0.01106464 -0.83054 0.5568492 -0.01735979 -0.8299753 0.5575301 -0.01917457 -0.8331638 0.552694 -0.02614605 -0.8322221 0.5538257 0.07285952 -0.550071 0.8319336 -0.1591546 -0.1202535 0.9799025 -0.1503534 -0.211723 0.9656952 -0.09749352 -0.4591444 0.8829959 0.1745724 -0.1877117 0.9665862 0.1518248 -0.2118909 0.9654282 0.07374364 -0.5431115 0.8364161 0.05309748 -0.5403061 0.8397917 0.05488485 -0.5353431 0.8428497 0.03266078 -0.5333386 0.8452711 0.0334652 -0.5303665 0.8471077 0.01100379 -0.5293582 0.8483271 0.01121228 -0.528319 0.848972 -0.01105517 -0.5283211 0.8489727 -0.01115494 -0.5293638 0.8483217 -0.03300768 -0.5303488 0.8471367 -0.03309935 -0.5334082 0.8452102 -0.05411022 -0.5353117 0.8429196 -0.05386078 -0.5403996 0.8396829 -0.06783545 -0.5423238 0.8374266 -0.0363664 -0.6771402 0.7349549 0.6861599 2.74685e-4 0.7274508 0.527424 -2.74582e-5 0.8496022 -0.6904761 0.006952583 0.7233219 -0.718708 -0.144199 0.6801952 -0.7087976 -0.2815787 0.6467761 -0.7667084 -0.07123744 0.638031 -0.7911021 0.006130039 0.6116536 -0.7910233 5.02471e-4 0.6117861 -0.7909702 0.002465665 0.6118499 -0.7909535 0.00510782 0.611855 -0.7911825 0.006599545 0.6115446 -0.5253232 -0.004097521 0.850893 -0.5666249 -0.02905511 0.8234634 -0.5894085 -0.1071983 0.8006912 -0.5864384 -0.09172827 0.8047832 -0.6293593 -0.03029274 0.7765238 -0.6546452 -0.003861725 0.7559265 -0.3327179 -6.15701e-6 0.9430264 -0.3920523 -0.02396297 0.9196308 -0.4071813 -0.04514724 0.9122309 -0.4697018 1.53037e-5 0.8828251 -0.5090456 -1.35499e-5 0.8607397 -0.1246647 -3.84585e-6 0.992199 -0.1857058 -0.01539796 0.9824848 -0.2082353 -0.03475797 0.977461 -0.2484191 -0.01225984 0.9685751 -0.2900568 2.17866e-5 0.9570096 0 -0.03040033 0.9995379 -0.01408785 -0.01905202 0.9997193 -0.08140057 4.7149e-6 0.9966815 0.2883996 7.14521e-6 0.9575102 0.222291 -0.02092242 0.9747559 0.2082616 -0.03284609 0.9775215 0.140178 0.001847088 0.9901247 0.06330192 -0.001765549 0.9979929 0.4890928 8.18366e-6 0.8722318 0.4336211 -0.01743495 0.9009267 0.4071762 -0.04533076 0.9122241 0.3707194 -0.01423007 0.9286359 0.3298768 -1.82279e-5 0.9440241 0.5889202 -0.001292407 0.8081903 0.6008154 -0.1740384 0.7802125 0.5772643 -0.05014801 0.8150161 0.7917394 0.004755318 0.6108406 0.7917306 0.002498924 0.6108655 0.7917897 5.54428e-4 0.6107937 0.7188 -0.09743624 0.6883551 0.7088027 -0.2815682 0.6467753 0.7678415 -0.06507974 0.6373258 0.7919211 0.005789816 0.610596 0.7919259 0.005862593 0.610589 0.1275429 0.9898307 0.0629931 -0.2226278 0.9746294 0.0231167 -0.3312712 0.9435126 0.00658822 -0.3844198 0.9231582 -5.76543e-4 -0.1388516 0.9897905 0.03217309 -0.01328855 0.9980044 0.06173157 -0.1188039 0.992062 0.04121494 0.3377949 0.9373723 0.0850172 0.4500167 0.8853127 0.1170754 0.3116626 0.9463479 0.08539426 0.8838658 0.4425226 0.1515091 0.9005943 0.4168843 0.1230342 0.7345137 0.6662467 0.1288605 0.7353826 0.6651427 0.1296058 0.6123362 0.7828699 0.1102691 0.9630193 0.2387131 0.1249399 0.9760759 0.1674835 0.1386553 0.9498526 0.2863661 0.1255971 0.7404675 0.6615676 0.1184743 0.7358868 0.6668195 0.1175692 0.3488255 0.9333422 0.08481281 0.3380649 0.9374796 0.08272904 -0.1225023 0.9919566 0.03186696 -0.1384164 0.9899638 0.02850496 0.343558 0.9305853 0.1264079 -0.04437208 0.4399891 0.8969063 0.1966613 0.6126987 0.7654572 -0.1075186 0.9748761 0.1950805 -0.1080846 0.9747881 0.1952078 -0.1096432 0.9746106 0.1952246 -0.1098274 0.9745163 0.1955916 0.1167867 0.2024729 0.9722991 0.02019733 0.1900326 0.98157 0.02329546 0.1978855 0.9799484 -0.0185796 0.1932647 0.9809708 -0.01499348 0.1946216 0.9807639 0.2022634 0.2556641 0.9453706 0.2300044 0.2055208 0.9512409 0.1145956 0.1865935 0.9757308 0.2738771 0.1959763 0.9415863 0.3294913 0.2067782 0.9212375 0.32669 0.1940052 0.9250059 0.4196335 0.2138093 0.8821528 0.4193043 0.1924198 0.8872196 0.489669 0.2098574 0.8462767 0.5133806 0.2470476 0.8218321 0.5459396 0.201609 0.813206 0.6338223 0.2256351 0.7398366 0.6355593 0.2015624 0.7452765 0.7036402 0.2222534 0.6749029 0.714035 0.2640998 0.6483867 0.7493408 0.2154425 0.6261572 0.7889671 0.2283905 0.570411 0.7877484 0.219465 0.5755758 0.8380963 0.2364634 0.4916091 0.8398593 0.2198063 0.4963081 0.8756145 0.2322748 0.4234948 0.8880094 0.2620538 0.3778452 0.9035298 0.2285974 0.36246 0.9293719 0.2380056 0.2821726 0.9295198 0.2333499 0.2855537 0.9516927 0.2418004 0.1892449 0.952891 0.2351563 0.191573 0.7299379 0.6599103 0.1780706 0.709629 0.6529854 0.2646447 0.7078089 0.6543821 0.2660652 0.6812403 0.6440625 0.3479872 0.6765838 0.6483446 0.3491184 0.6286174 0.6314472 0.4539985 0.6225134 0.6368745 0.4548276 0.5818054 0.6237859 0.5219135 0.577826 0.6261491 0.5235022 0.533382 0.6111164 0.5848422 0.5257108 0.6179498 0.5846078 0.4526196 0.5956998 0.6635341 0.4438343 0.6040791 0.6618909 0.3646833 0.5825583 0.7263828 0.3565379 0.5905312 0.7239846 0.2776624 0.5712398 0.7723916 0.2699914 0.5794202 0.7690104 0.2051866 0.5658848 0.7985443 0.1997051 0.5705646 0.7966015 0.1340025 0.5573921 0.8193641 0.1278819 0.5654021 0.8148416 0.04369503 0.5516511 0.8329296 0.0387873 0.5592898 0.8280643 -0.02722227 0.55099 0.8340678 -0.03065764 0.5549368 0.8313274 -0.05873268 0.55191 0.8318328 -0.08453035 0.7888564 0.6087368 0.7317603 0.657522 0.1794205 0.3439782 0.9303953 0.1266635 0.3291325 0.9255028 0.1873943 0.3294979 0.9254119 0.1872006 0.3111514 0.9181327 0.2453922 0.3120298 0.9178472 0.2453446 0.2787163 0.9061679 0.3180836 0.2796123 0.9058738 0.318135 0.251175 0.896851 0.3641009 0.2516276 0.8967562 0.364022 0.2221786 0.8867509 0.405351 0.2227939 0.8865294 0.405498 0.1760638 0.8723661 0.4560472 0.1762828 0.8722742 0.4561382 0.1277886 0.8591508 0.4955101 0.1273388 0.8593589 0.495265 0.08133739 0.8481515 0.5234725 0.08030825 0.848721 0.5227077 0.04371559 0.8410738 0.5391513 0.04255211 0.841604 0.5384163 0.007088661 0.8345445 0.5508951 0.005216062 0.8359544 0.5487744 -0.03861933 0.8288152 0.5581881 -0.04067051 0.8307999 0.5550833 -0.0742166 0.8265472 0.5579532 -0.07604068 0.8278866 0.5557173 0.09631186 0.833133 0.5446225 -0.09771478 0.8915209 0.4423149 -0.1128067 0.9741274 0.1958326 -0.1149277 0.9744009 0.1932215 -0.1155444 0.9740754 0.1944909 -0.1197252 0.973392 0.1953813 -0.1196268 0.9743509 0.1906037 -0.1236174 0.9735756 0.1920141 -0.1231427 0.9745138 0.1875066 -0.1255906 0.9739913 0.1885949 -0.127191 0.9754211 0.1799339 -0.1273692 0.9753781 0.1800408 -0.1305744 0.9767699 0.1699143 -0.1272829 0.977663 0.1672541 -0.132917 0.9787921 0.1558819 -0.1266853 0.9806666 0.1491439 -0.1328668 0.9813189 0.1391393 -0.1282884 0.9828249 0.1326553 -0.1299611 0.9833623 0.1269207 -0.1240255 0.9853051 0.1174372 -0.1307254 0.9853305 0.1097037 -0.1219644 0.9883895 0.09061425 -0.1281269 0.9881073 0.08501541 -0.1230357 0.9900265 0.06862819 -0.1249783 0.989989 0.065593 -0.1202314 0.9916521 0.04658955 -0.1239509 0.9913029 0.0442146 0.01432979 0.1946848 0.9807612 0.02848923 0.2578759 0.965758 0.03248208 0.4412687 0.896787 0 0.2589569 0.9658889 -0.01900869 0.2582579 0.965889 -0.02688521 0.1932994 0.9807714 0 0.2589575 0.9658887 0 0.7073592 0.7068543 0 0.7073601 0.7068534 0.07090747 0.9633612 0.2586649 0.08470952 0.9771327 0.1950283 0.06584608 0.8945568 0.4420775 0.05192542 0.7054517 0.7068535 0.08334249 0.7889836 0.6087355 0.04470717 0.6073724 0.7931583 -0.03248208 0.4412687 0.896787 -0.04470717 0.6073724 0.7931583 -0.06467694 0.7046896 0.7065618 -0.05825155 0.7914287 0.6084796 -0.06584608 0.8945568 0.4420775 0.01773655 0.9657728 0.2587823 0 0.9768101 0.2141078 -0.0177477 0.9657728 0.2587817 -0.08050209 0.9626355 0.2585587 -0.07199627 0.9781647 0.1949625 -0.7328382 0.6580849 0.172837 -0.9323233 0.2335518 0.276092 -0.9525182 0.2412247 0.185795 -0.9543868 0.2356613 0.1833294 -0.8927233 0.2672777 0.362778 -0.8986039 0.2268341 0.375576 -0.9300835 0.2382243 0.2796321 -0.8762019 0.2321739 0.4223337 -0.8439403 0.220906 0.4888408 -0.8368703 0.2355718 0.4941195 -0.8075779 0.2256312 0.5448932 -0.8041871 0.2247137 0.5502609 -0.785013 0.218351 0.5797218 -0.7781422 0.2285603 0.5850256 -0.7411134 0.2165909 0.6354836 -0.6985996 0.2618591 0.6658742 -0.6952031 0.223529 0.6831745 -0.6279295 0.2033863 0.7512248 -0.6167106 0.2226029 0.7550603 -0.5484641 0.2040908 0.8108847 -0.5396414 0.214102 0.814216 -0.5111277 0.2068137 0.8342522 -0.4544495 0.2186805 0.8635129 -0.4542886 0.2142548 0.8647062 -0.3536158 0.1914389 0.9155911 -0.2637287 0.2341192 0.935754 -0.2531714 0.1923839 0.9480995 -0.3431787 0.2097868 0.9155424 0.1201528 0.9917995 0.0435574 0.1255932 0.9898537 0.06645399 0.1219637 0.9904015 0.06503772 0.1289371 0.9877805 0.0875501 0.1207672 0.9888159 0.08751195 0.1321418 0.9848313 0.1124536 0.1220932 0.9859755 0.113779 0.129871 0.9834783 0.1261117 0.1277215 0.9841314 0.1231776 0.1329087 0.9823732 0.1314471 0.1251697 0.9833142 0.1320074 0.135246 0.9800624 0.1455549 0.1241912 0.9809113 0.1496319 0.1350412 0.9776993 0.1608347 0.1247264 0.9781562 0.1662944 0.1323598 0.9761025 0.1723513 0.1260831 0.9765123 0.1747193 0.1311509 0.9752182 0.178182 0.1236351 0.9750515 0.1843609 0.1266068 0.9743844 0.1858651 0.1214311 0.9739701 0.1914072 0.1217778 0.9739025 0.1915312 0.1191753 0.9737558 0.1938992 0.02255076 0.8326133 0.5533956 0.02280664 0.8304733 0.5565916 -0.01409798 0.8370857 0.5468901 -0.01380705 0.8360484 0.548482 -0.05145525 0.8431848 0.535156 -0.05171507 0.8420683 0.536886 -0.09842681 0.8525947 0.5132198 -0.09868317 0.8520277 0.5141113 -0.1341834 0.861332 0.490002 -0.1342124 0.8612057 0.490216 -0.1702962 0.8707092 0.4613729 -0.170255 0.8707575 0.4612969 -0.2147942 0.8839878 0.4152457 -0.2144814 0.8842872 0.4147699 -0.248184 0.8954018 0.369676 -0.2479377 0.8956601 0.3692154 -0.2604534 0.8999837 0.3495618 -0.260311 0.9001144 0.3493314 -0.2802236 0.9061172 0.3169012 -0.2796335 0.9065139 0.3162877 -0.3122133 0.9179576 0.2446975 -0.3115819 0.9183149 0.244161 -0.3305791 0.9257475 0.1836005 -0.330305 0.9259119 0.1832644 -0.344488 0.930749 0.1226151 0.1239852 0.9912862 0.04449135 0.1166695 0.9741903 0.1932399 0.1168764 0.9739101 0.1945232 0.1137726 0.9740427 0.1956954 -0.2357442 0.200673 0.9508707 -0.1638672 0.1878163 0.9684382 -0.1560331 0.2031852 0.966628 -0.04250389 0.1869094 0.9814573 -0.03661561 0.1999934 0.9791129 -0.002502381 0.4445967 0.8957275 0.00144428 0.5510655 0.8344609 -0.07498997 0.5616768 0.8239514 -0.07422751 0.5529282 0.8299161 -0.1468197 0.5660215 0.8112113 -0.1455665 0.5602421 0.8154381 -0.2180458 0.5739303 0.7893415 -0.2189221 0.5643362 0.7959886 -0.3061746 0.5840532 0.7517573 -0.3080224 0.5744696 0.7583581 -0.3731736 0.591597 0.7146709 -0.3732908 0.5860511 0.719165 -0.4364485 0.6027428 0.6679925 -0.4395121 0.5937205 0.6740364 -0.5143169 0.6160326 0.5966422 -0.5178095 0.607811 0.6020291 -0.5731602 0.6260516 0.528722 -0.5748477 0.6211587 0.5326462 -0.5958114 0.6285843 0.4998906 -0.5942881 0.628008 0.5024219 -0.6251962 0.6375027 0.4502444 -0.6286756 0.631286 0.454142 -0.6779842 0.6486856 0.3457519 -0.6810382 0.6439253 0.3486362 -0.7098653 0.6550306 0.2588942 -0.7110011 0.6530584 0.2607533 -0.7308493 0.6600534 0.1737496 -0.3440454 0.9308967 0.1227361 0.1106693 0.9745249 0.195073 0.110589 0.9744931 0.1952779 0.0846821 0.8928792 0.4422622 0.05469894 0.8282123 0.5577387 0.06008207 0.7912702 0.6085078 0.02645057 0.6090455 0.7926942 -0.7337094 0.6658914 0.135127 -0.9047731 0.4099534 0.1154294 -0.1809502 0.9810221 0.06966143 0.3857691 0.9225952 -7.73989e-4 0.2691231 0.9629927 0.01476114 0.1394997 0.9895055 0.03766709 0.03182178 0.9984806 0.04499024 -0.1273007 0.989864 0.06295883 -0.9630194 0.2387129 0.1249394 -0.9701422 0.2035868 0.1318202 -0.3332586 0.9385604 0.08968269 -0.4540578 0.8830929 0.1182309 -0.3377945 0.9373737 0.08500289 -0.6234943 0.7738836 0.1111719 -0.7198593 0.6821256 0.1284813 -0.8914407 0.4313045 0.1389599 -0.9177397 0.3766529 0.1260419 -0.7358155 0.6667919 0.1181702 -0.7405403 0.6615945 0.1178673 -0.3379438 0.9374343 0.08373153 -0.3489487 0.9333875 0.08380109 0.1385843 0.9898989 0.02990752 0.1223331 0.9920219 0.03045105 -0.6096641 0.7289387 0.311381 -0.6738816 0.6926288 0.2571948 -0.6474468 0.7168845 0.2586298 -0.6427468 0.7190924 0.2641643 -0.6251043 0.7281345 0.2811848 -0.6006084 0.7659289 0.2293963 -0.3110443 0.9500896 -0.02410989 -0.3655389 0.9306933 0.0138393 -0.5252736 0.8390628 0.1416379 -0.5818904 0.7916634 0.1862061 -0.5818995 0.7916333 0.186306 -0.5798999 0.7934384 0.1848556 -0.5720107 0.7971366 0.1933316 -0.5772962 0.7918861 0.1991116 -0.713063 0.6501937 0.2622772 -0.7032939 0.6551235 0.2760275 -0.6676978 0.6948689 0.26709 -0.6584948 0.6998752 0.2766935 -0.9136167 0.3170432 0.2545355 -0.9700585 0.1303218 0.2049459 -0.8349233 0.3048505 0.4582242 -0.8618777 0.3700006 0.3467944 -0.849823 0.3831527 0.3619324 -0.8540579 0.4194979 0.3075819 -0.8785917 0.396431 0.2663067 -0.7371545 0.5990452 0.3126471 0.972891 0.1281808 0.1924911 0.8349227 0.3048509 0.458225 0.8618769 0.3700295 0.3467656 0.9317516 0.2408347 0.2717311 0.9340468 0.2637105 0.2408594 0.9332455 0.2698227 0.2371677 0.9332571 0.2687489 0.2383387 0.9294189 0.2809918 0.2392159 0.8357669 0.4786386 0.2690707 0.8411315 0.4559207 0.2909199 0.8569385 0.4148212 0.3059082 0.8498478 0.3831526 0.361874 0.8527902 0.4048491 0.3299183 0.8527957 0.4032978 0.3317988 0.8532126 0.4075894 0.3254218 0.8536458 0.4052014 0.3272629 0.8544873 0.4146199 0.3129566 0.9295071 0.2836823 0.2356715 0.3106985 0.9497866 -0.03704053 0.5296845 0.8392621 0.1227749 0.4857897 0.8602171 0.1550325 0.5334364 0.832628 0.1489173 0.6122506 0.7498105 0.2508652 0.619803 0.7464404 0.2422212 0.6096726 0.7392951 0.285906 0.635173 0.7284817 0.2566511 0.6072928 0.7370783 0.2964981 0.7949571 0.5071364 0.3329507 0.6756368 0.6917678 0.2548967 0.6738653 0.6926236 0.2572512 0.5711179 0.8024686 0.1728252 0.5688571 0.80353 0.1753314 0.5749439 0.7968986 0.1854517 0.5777148 0.7955842 0.18246 0.5786985 0.7941293 0.1856526 0.5797714 0.7936594 0.1843095 0.6416877 0.7226941 0.2568076 0.6121373 0.7275274 0.3098253 -0.8883162 0.4591692 0.007611989 -0.9536589 0.3008623 0.004103183 -0.9468234 0.3205869 0.02738165 -0.8497939 0.4792332 0.2195128 -0.9099149 0.414779 -0.003650546 -0.9029867 0.4292614 0.01870602 -0.903652 0.4279227 0.01718491 -0.90471 0.4257237 0.01609987 -0.8954058 0.444759 0.02093279 -0.8416124 0.5386528 0.03926807 -0.7370367 0.6758307 0.005474746 -0.5019453 0.8644245 0.02865624 -0.4782578 0.8781524 0.01085972 -0.8882952 0.4592205 0.006939768 -0.853926 0.5193077 0.03361457 -0.7030466 0.7059123 -0.08610087 -0.7036945 0.7100886 -0.02425283 -0.4938724 0.8568978 0.1477032 -0.5105173 0.8568933 -0.07145631 -0.4217275 0.9067178 -0.002991199 -0.6034407 0.7741194 0.191307 -0.6047686 0.7700483 0.2031762 -0.6044481 0.7703416 0.2030187 -0.9676968 0.2049603 0.1468138 -0.9365997 0.3137166 0.1560859 -0.8602026 0.4913609 0.1364405 -0.8690854 0.476009 0.1345595 -0.7345187 0.6694638 0.1109073 -0.7203085 0.6843714 0.1130997 -0.4712871 0.8803416 0.05373275 -0.9823741 0.08150988 0.1682176 -0.9147468 0.3640542 0.175223 -0.9071193 0.3569776 0.2229387 -0.8365207 0.4872519 0.2506368 -0.6046283 0.7702127 0.2029708 -0.6049824 0.7702888 0.2016224 -0.7143651 0.667585 0.2097924 -0.6727598 0.7014766 0.2352125 0.3876328 0.921814 7.0287e-5 0.6988729 0.7151774 0.009899735 0.9281539 0.3661049 -0.0670638 0.9110949 0.4115022 0.02392244 0.8802848 0.473368 0.03196388 0.9149546 0.3974746 0.06980079 0.896682 0.4417817 0.0281108 0.9124782 0.4085271 0.0221194 0.922834 0.3849769 0.01304733 0.8061271 0.5915113 0.01653778 0.7694026 0.638466 0.01952117 0.8946602 0.3692378 0.2514887 0.1085387 0.9520396 -0.286077 0.509387 0.8600797 0.02806621 0.5019662 0.8643069 0.03168058 0.50288 0.8602265 -0.08439242 0.441224 0.8973849 -0.004684031 0.9069101 0.3574342 0.2230584 0.6836621 0.7223025 0.1043321 0.9681803 0.2027069 0.1467542 0.9815403 0.07913303 0.1741169 0.9805479 0.09536015 0.1715584 0.9802441 0.09955877 0.1709084 0.9547786 0.252777 0.1565303 0.8971812 0.355825 0.261638 0.900626 0.3522526 0.2545412 0.7902582 0.6003218 0.1229064 0.9113606 0.3882865 0.1365859 0.3860232 0.9223704 0.01479816 0.3351005 0.9421809 0.001763284 0.500163 0.8623337 0.0788508 0.4448947 0.8914847 0.08557838 0.5784313 0.8119114 0.07885068 0.6051474 0.7697189 0.2032964 0.6067411 0.7702819 0.1962935 0.6049731 0.7698476 0.2033278 0.6049536 0.7698857 0.2032423 0.7357726 0.6691948 0.1040054 0.7069281 0.6655097 0.2394778 0.8548235 0.4911534 0.1674672 0.8363621 0.4874855 0.2507121 0.5588123 0.0832144 0.8251086 0.7846778 8.22632e-4 0.6199033 0.695412 -0.02586179 0.7181458 0.6899937 0.01565247 0.7236461 0.7121176 0.08987456 0.6962838 0.7088451 0.0186569 0.7051175 0.7097623 0.08069026 0.6998047 0.5783756 0.08787626 0.8110237 0.7014165 0.02917844 0.7121542 0.7056006 0.03940844 0.7075131 0.6417645 -0.2380132 0.7290323 0.7604939 0.02449727 0.6488829 0.7606412 0.02522641 0.6486822 -0.763032 0.02358722 0.6459304 -0.6410466 0.006681203 0.767473 -0.6392348 -0.03354132 0.7682799 -0.6425495 0.1091227 0.7584342 -0.7629825 0.02335739 0.6459971 -0.7610445 0.01779592 0.6484557 -0.6873009 -0.03877699 0.7253372 -0.6997202 0.02032619 0.7141279 -0.7118796 0.08121615 0.6975897 -0.7076743 0.003632783 0.7065296 -0.7213125 0.06923228 0.6891409 -0.9763035 0.1181892 0.1812808 -0.9651427 0.2035619 0.1645055 -0.9621072 0.1070061 0.2507976 -0.961304 0.04920548 0.2710597 -0.8602779 0.1307609 0.4927713 -0.8492245 -0.03143912 0.5270954 -0.7502943 -0.01743817 0.6608741 -0.7458496 -0.07509368 0.6618681 -0.8383022 0.003352642 0.5451955 -0.9386849 0.02107799 0.3441311 -0.9563695 0.08212178 0.2803811 -0.9228466 0.1542419 0.3529359 -0.6162121 0.2141719 0.7579006 -0.6946481 0.125705 0.7082813 -0.70708 0.07995277 0.7025991 -0.7676884 0.3017893 0.5653122 -0.8905445 0.1175068 0.4394574 -0.8973106 0.08174794 0.4337638 -0.7068098 0.07609158 0.7032994 -0.7470395 0.02684092 0.6642376 0.7071045 0.0799781 0.7025716 0.8341629 0.3048285 0.4596214 0.8233121 0.2532593 0.5079538 0.6897702 0.1421908 0.7099288 0.6857694 0.1227694 0.7173898 0.8788796 0.1680368 0.4464687 0.9335872 0.08173733 0.3489043 0.7068161 0.07609671 0.7032924 0.7470735 0.02681809 0.6642003 0.9337834 0.07999408 0.348783 0.7503255 -0.01749348 0.6608371 0.9789611 0.0282002 0.2020893 0.8651872 0.124299 0.4857994 0.8454273 -0.02706891 0.5334043 0.9700834 0.2036298 0.1321867 0.9660612 0.1765571 0.1885558 0.9563848 0.07743203 0.2816601 0.963317 0.0255391 0.2671483 0.8373375 0.002390444 0.5466811 0.7458666 -0.07506483 0.6618522 0.967773 0.2196407 0.1231807 0.972329 -0.05049598 0.2280935 0.9808145 -0.08279758 0.1764864 0.9774774 -0.01394081 0.210579 0.9618715 0.1959131 0.1908439 0.9833205 -0.003356397 0.1818506 0.967967 -0.05100804 0.2458419 0.9494338 -0.1801022 0.2571746 0.9344972 -0.2118986 0.2860313 0.8981148 -0.3025686 0.3191272 0.8805178 -0.3289624 0.34128 0.8219678 -0.4489835 0.3504036 0.9679558 0.1842877 0.170586 0.9543097 0.1482816 0.2594335 0.9547469 0.1326192 0.2662155 0.9212939 0.04198205 0.3865942 0.9214712 0.03565454 0.3868072 0.8662075 -0.07884353 0.493425 0.8718727 -0.05906152 0.4861581 0.7758493 -0.1958535 0.5997493 0.7924456 -0.113807 0.5992313 0.7921235 -0.5267596 0.3083259 0.293194 -0.6866088 0.6652862 0.759558 -0.4875181 0.4305785 0.828352 -0.1795781 0.5306457 0.5061869 -0.3799835 0.7742011 0.7924664 -0.1108149 0.5997644 0.8266876 -0.4437165 0.3459815 0.7117783 -0.5729867 0.4062733 0.7723022 -0.1358439 0.620561 0.7235903 -0.2347511 0.6490833 0.1133259 -0.9540866 0.2772656 0.6480939 -0.1759485 0.7409565 0.6359847 -0.0531302 0.7698706 0.4156318 -0.6188154 0.6665716 0.02195316 -0.9302706 0.3662168 -0.1693006 -0.9755169 0.1403719 0.1371472 -0.8838159 0.447281 0.2650003 -0.7670979 0.5842395 0.3949152 -0.7973665 0.4563428 0.3989495 -0.8629842 0.3099964 0.3049597 -0.8607772 0.4075075 0.1144738 -0.9693512 0.2173802 0.1163406 -0.9567475 0.2666444 0.7635236 -0.1484069 0.6284959 0.7702777 -0.1288526 0.6245552 0.7176187 -0.3770991 0.5855082 0.7029594 -0.1886783 0.6857467 0.71876 -0.1477329 0.6793814 0.6254217 -0.4296438 0.6513478 0.7129238 -0.4314982 0.5527648 0.6245905 -0.5992636 0.5007694 0.5358019 -0.7769307 0.3305983 0.3867063 -0.8631264 0.324763 0.5945204 -0.6761673 0.4351362 0.4874203 -0.6732802 0.5559815 0.5921097 -0.5296489 0.6073536 0.4745391 -0.5022311 0.7228946 0.6122013 -0.2319694 0.75591 0.6964526 -0.646641 0.311142 0.5561817 -0.7731463 0.304806 0.7622696 -0.4863759 0.4270638 0.6876354 -0.5894967 0.4238529 0.7986387 -0.30339 0.519741 0.7704852 -0.3683568 0.5202556 0.8035861 -0.1059306 0.5856862 0.8001958 -0.12372 0.5868391 0.2841805 -0.5792009 0.7640471 -0.1503741 -0.8086882 0.5686923 -0.3821013 -0.5422871 0.7482802 -0.5923885 -0.09756278 0.7997233 -0.5990901 -0.3317436 0.7287231 -0.09305316 -0.9305056 0.3542607 -0.5605716 -0.2169046 0.7991946 -0.5134626 -0.1998111 0.8345249 -0.5107722 -0.2182037 0.8315642 -0.4663944 -0.2043476 0.86065 -0.46863 -0.2094196 0.858213 -0.4502929 -0.2039022 0.8692873 -0.4339669 -0.1753243 0.8837047 -0.4118391 -0.2093469 0.8868836 -0.3500025 -0.1937151 0.9165003 -0.3065394 -0.1307319 0.9428376 -0.2771406 -0.1928815 0.9412703 -0.3493306 -0.207488 0.9137378 -0.252266 -0.2002731 0.9467062 -0.2180223 -0.1950398 0.9562561 -0.2193757 -0.199473 0.9550313 -0.163281 -0.1921106 0.9676947 -0.1639772 -0.1988124 0.9662222 -0.1081472 -0.1944029 0.9749419 -0.09167766 -0.1563852 0.9834322 -0.07046455 -0.1958464 0.9780997 -0.01234912 -0.1938601 0.9809515 -0.01246589 -0.1943401 0.9808551 0.0548737 -0.1955103 0.9791653 0.05551898 -0.1937966 0.9794696 0.1212457 -0.1973199 0.9728127 0.1230096 -0.1925169 0.9735532 0.1950252 -0.1999043 0.9602102 0.2683973 -0.1144015 0.9564911 0.2707036 -0.203319 0.9409468 0.1982864 -0.1924107 0.9610728 0.2886409 -0.196262 0.937106 0.3259067 -0.2036817 0.9232003 0.3307945 -0.197166 0.9228764 -0.2556106 -0.7100759 0.6560912 -0.3863104 -0.6096294 0.6921824 -0.3221428 -0.5869041 0.7428106 -0.3176922 -0.5911936 0.7413244 -0.2905931 -0.5828598 0.7588348 -0.2887026 -0.5835837 0.759 -0.2621975 -0.5754421 0.7746735 -0.2586901 -0.5792809 0.7729898 -0.2146001 -0.5681599 0.794444 -0.2118079 -0.5716148 0.7927132 -0.1671521 -0.5625678 0.8096775 -0.1651517 -0.565454 0.8080759 -0.1321534 -0.5605342 0.8175188 -0.1311214 -0.5615531 0.8169856 -0.09870511 -0.5572326 0.824469 -0.09772694 -0.5590499 0.8233546 -0.05306786 -0.5554289 0.8298691 -0.05265009 -0.5564447 0.829215 -0.007440388 -0.5549762 0.8318329 -0.007394611 -0.555152 0.8317161 0.03309118 -0.5558788 0.8306046 0.03292077 -0.5553119 0.8309903 0.07324963 -0.5574462 0.8269754 0.0730856 -0.5560504 0.8279291 0.1182973 -0.5606906 0.8195316 0.1182636 -0.5584377 0.8210731 0.1635376 -0.5652573 0.8085417 0.1638019 -0.5622218 0.8106021 0.1996862 -0.5694789 0.7973827 0.1996352 -0.5672738 0.7989659 0.2360822 -0.5754494 0.7830219 0.4687837 -0.2006224 0.8602283 0.469147 -0.1777703 0.8650428 0.4305904 -0.2069437 0.8785023 0.1052903 -0.9456431 0.3076899 -0.07484477 -0.8624392 0.5005967 -0.06440478 -0.8585922 0.5085975 -0.0692631 -0.8563098 0.511797 -0.05759972 -0.8527073 0.5192039 -0.05953782 -0.8524254 0.5194482 -0.04947763 -0.84935 0.5255059 -0.05323421 -0.8471626 0.5286604 -0.03891247 -0.8435503 0.5356388 -0.04186451 -0.8414998 0.5386331 -0.02938956 -0.8389734 0.5433782 -0.03149372 -0.8371868 0.5460096 -0.02308881 -0.8359175 0.5483694 -0.02411031 -0.8352876 0.5492845 -0.01686346 -0.8343368 0.5509973 -0.01784497 -0.8331812 0.5527123 -0.009006142 -0.8324633 0.5540072 -0.009429335 -0.831825 0.5549581 -0.001262068 -0.8315572 0.5554379 -0.001313745 -0.8314486 0.5556003 0.005659461 -0.8315638 0.5554004 0.005804777 -0.8319101 0.5548802 0.01275098 -0.8322918 0.5541911 0.01287162 -0.8332155 0.5527986 0.02110815 -0.8340579 0.551273 0.02105325 -0.8355413 0.5490244 0.03011417 -0.8369089 0.5465131 0.02970814 -0.8388853 0.543497 0.03740936 -0.8404261 0.5406336 0.03732579 -0.8418774 0.5383766 0.04628062 -0.8439014 0.5344985 0.04501295 -0.8465227 0.5304463 0.05798137 -0.8501093 0.5234048 0.2254724 -0.9665561 0.1221947 0.1998876 -0.9740463 0.1062017 0.2144593 -0.9597166 0.1815255 0.20283 -0.9638907 0.1725535 0.195774 -0.9620733 0.1899672 0.1827991 -0.9662051 0.1817485 0.1839675 -0.9649154 0.1873347 0.1694035 -0.9692401 0.1785386 0.1648676 -0.96702 0.194142 0.140842 -0.9730755 0.1824487 0.1381167 -0.9708176 0.1960534 0.1110275 -0.9763037 0.1857529 0.1097776 -0.9742491 0.196946 0.08782404 -0.9776914 0.1908053 0.08870732 -0.9767186 0.1953252 0.06618553 -0.9795528 0.1899897 0.06637835 -0.9782116 0.1967132 0.03565323 -0.9807037 0.192222 0.03610688 -0.9799609 0.1958904 0.004986643 -0.980973 0.1940805 0.005099594 -0.9808702 0.1945962 -0.02210611 -0.9804759 0.1953934 -0.02276527 -0.9807987 0.19369 -0.04860007 -0.979358 0.1962038 -0.05050182 -0.9801895 0.1915156 -0.07764077 -0.9774151 0.1965497 -0.08132803 -0.9785262 0.1894003 -0.1058538 -0.9748344 0.1961962 -0.1116786 -0.9759962 0.1869741 -0.1284399 -0.9727092 0.1932356 -0.1340497 -0.9730548 0.1876037 -0.1484462 -0.9697395 0.1938276 -0.1580846 -0.970458 0.1822651 -0.173787 -0.9661243 0.1907932 -0.185752 -0.9662144 0.1786783 -0.1974169 -0.9624316 0.186419 -0.211543 -0.9617117 0.1742423 0.5223359 -0.2180063 0.8244019 0.5324036 -0.2022224 0.8219809 0.3281685 -0.5935208 0.7348732 0.3326678 -0.5893185 0.7362309 0.3823718 -0.2088408 0.9000985 0.3899325 -0.1956446 0.8998199 0.2370907 -0.5712697 0.7857729 0.2826555 -0.5838634 0.761058 0.05606263 -0.8530056 0.518882 0.07221812 -0.858237 0.5081475 0.06730258 -0.8604356 0.505095 -0.7816519 -0.3106054 0.540874 0.2217101 -0.967796 0.1192287 -0.1119078 -0.7931854 0.5986099 -0.02631556 -0.9113649 0.4107577 0.1041525 -0.9460507 0.3068231 -0.3774762 -0.540522 0.7518961 -0.6092799 -0.1038492 0.7861256 0.1949302 -0.9468222 0.2559883 0.1184673 -0.9743435 0.1913645 0.1094904 -0.9539695 0.2792025 0.03307133 -0.9769394 0.2109401 -0.08960419 -0.9246084 0.3702305 -0.1662724 -0.9415792 0.2928859 -0.1558743 -0.9396831 0.3044649 -0.3662741 -0.8628177 0.3484092 -0.421809 -0.8615088 0.2826303 -0.4835295 -0.7881391 0.3808361 -0.5786921 -0.772389 0.261784 -0.6528274 -0.6635169 0.365461 -0.7032908 -0.5909146 0.3952242 -0.6498194 -0.6011765 0.4651038 -0.5673496 -0.6771001 0.4686684 -0.5324044 -0.6765464 0.508754 -0.4035792 -0.7720796 0.4909349 -0.3619767 -0.7642586 0.5337433 -0.2175852 -0.8373917 0.5014298 -0.2077555 -0.8344821 0.5103698 -0.1319316 -0.8471487 0.5147166 -0.1107655 -0.8392961 0.5322718 -0.2749827 -0.7172 0.6403192 -0.7320646 -0.4984484 0.4643605 -0.7795131 -0.370321 0.5051949 -0.7324474 -0.37843 0.5659608 -0.6967281 -0.431683 0.5729047 -0.6560037 -0.4310667 0.6195489 -0.5967383 -0.5078213 0.6213059 -0.5451546 -0.4978914 0.6744706 -0.4714905 -0.5697714 0.6730953 -0.4461244 -0.562011 0.6965032 -0.4025827 -0.5808857 0.7074596 -0.3822911 -0.5737065 0.7243717 -0.5390412 -0.3099197 0.7831887 -0.5405387 -0.1886039 0.8199064 -0.6079645 -0.2121478 0.7650964 -0.6029888 -0.1939285 0.7738193 -0.6518866 -0.2095118 0.7287996 -0.6545876 -0.1685642 0.736954 -0.7184224 -0.1811087 0.6716167 -0.7181322 -0.1477271 0.6800463 -0.7669165 -0.1484469 0.6243417 -0.7637368 -0.1308236 0.6321325 -0.8021439 -0.1247791 0.5839481 -0.798749 -0.1080605 0.5918809 -0.8114432 -0.4769446 0.3377631 -0.6816415 -0.2218632 0.6972386 -0.7512887 -0.1276891 0.6475037 -0.729216 -0.2027863 0.6535454 -0.7421019 -0.1925976 0.642021 -0.7169195 -0.5467848 0.4324962 -0.7281506 -0.631163 0.2672642 -0.6712536 -0.5835258 0.4570736 -0.747061 -0.4927052 0.4462528 -0.7904358 -0.3069722 0.5300749 -0.977829 0.09182667 0.1881976 -0.9674559 0.2207462 0.1236942 -0.9683057 0.2207821 0.116789 -0.9672209 0.2203064 0.1262885 -0.9666953 0.1734736 0.1881679 -0.9645851 0.1730194 0.199098 -0.9515249 0.142847 0.2723878 -0.9563452 0.1392862 0.2569112 -0.9197743 0.03886073 0.390519 -0.9223359 0.03800976 0.3845151 -0.8751658 -0.063331 0.4796606 -0.8642364 -0.0722171 0.4978756 -0.8201619 -0.1392225 0.5549338 -0.7581549 -0.1505503 0.6344571 -0.9832024 0.1083968 0.1468445 -0.977729 -0.01881623 0.2090261 -0.9812394 -0.01126897 0.1924632 -0.9463655 -0.09806281 0.3078573 -0.9659136 -0.1382555 0.2188523 -0.8981403 -0.2752368 0.3429123 -0.9302739 -0.2465037 0.2717101 -0.8212425 -0.4035335 0.4033876 -0.8643266 -0.3978579 0.3076503 -0.6331139 0.704613 0.3204487 -0.6814563 0.6651147 0.3053519 -0.4444337 0.8636782 0.2377789 0.03037816 0.9951871 0.09316515 0.1473118 0.9889979 0.01350706 -0.4639071 0.8523463 0.2414461 -0.488241 0.8546071 0.176826 -0.4849036 0.8565054 0.1768251 -0.452359 0.8809074 0.1391893 -0.4624894 0.8797125 0.1104963 -0.4090734 0.9076643 0.0938335 -0.4265099 0.9033931 0.04438823 -0.3369078 0.9415011 0.008304774 -0.3214225 0.9454985 0.05215382 -0.2692164 0.9622321 0.04040008 -0.2548605 0.963635 0.08033531 -0.2088491 0.9750785 0.07485955 -0.1819295 0.9722582 0.1470232 -0.2197808 0.9629012 0.1565815 0.5055421 0.8521782 0.1349801 -0.5680362 0.8059421 0.1667102 -0.5917049 0.7987397 0.1090878 -0.3774346 0.8977594 0.2270935 -0.5299975 0.833529 0.155988 -0.5181515 0.8438865 0.1391926 -0.4794309 0.8639504 0.1540639 -0.182877 0.9647659 0.1891634 -0.1381934 0.9709721 0.1952332 0.06678289 0.9774919 0.2001242 0.2641853 0.9426141 0.2041686 0.3207815 0.9244834 0.205985 0.4956712 0.8473376 0.1906023 0.7116807 0.6840457 0.1599752 0.8239485 0.5444155 0.1572283 0.6584604 0.731228 0.1781446 -0.5406008 0.8115406 0.2217042 -0.5947393 0.7645673 0.2484393 -0.5944014 0.7634458 0.2526606 0.5093474 0.8435098 0.1704595 0.7117747 0.6866018 0.1481719 0.1419541 0.9652217 0.2195364 0.3206278 0.9219891 0.2171036 -0.2472093 0.9404869 0.2331777 -0.1388083 0.9603701 0.241706 -0.4967963 0.83875 0.2229167 -0.5682311 0.8026703 0.1812015 0.3165965 0.9372316 0.1461637 0.488249 0.8611552 0.1415092 -0.004256904 0.9743276 0.2250949 0.1416761 0.9658336 0.2170102 -0.3280233 0.9071512 0.2635857 -0.243954 0.9327423 0.2654774 -0.6155076 0.7398822 0.2715234 -0.5921673 0.7575405 0.2747189 0.05270361 0.9871661 0.15075 0.3067013 0.9464107 0.1011983 -0.1941085 0.9551944 0.2234404 -0.01077038 0.9808346 0.1945446 -0.4288613 0.8590914 0.2793563 -0.3270198 0.9060924 0.2684302 -0.6351754 0.7052485 0.3149237 -0.6065344 0.7304147 0.314023 -0.08443516 0.978379 0.1888002 -0.1225567 0.9761636 0.1791216 0.3698737 0.9014531 0.2248909 0.9360182 0.3136383 0.1596898 0.9610421 0.2269915 0.1577119 0.6964697 0.6863992 0.2092516 -0.5396757 0.8345887 0.1105074 -0.5392223 0.8354794 0.1058949 -0.5207787 0.8462009 0.1128431 -0.1811856 0.9699149 0.1625946 -0.121748 0.9776728 0.1712702 -0.3731526 0.9172741 0.1391597 -0.5909651 0.8008039 0.09733223 0.06759679 0.9797962 0.1882295 0.320371 0.926338 0.1981422 0.3185746 0.9229359 0.2161006 0.7451607 0.6317384 0.2136406 0.8235335 0.5434933 0.1625049 0.937501 0.3166116 0.1443927 0.6577303 0.7294697 0.1877896 0.6987545 0.6908536 0.1856437 0.4949528 0.8456296 0.1998304 0.2648992 0.9443644 0.1949466 0.9616451 0.2251332 0.1566965 0.9621244 0.223186 0.1565398 0.7497598 0.6281784 0.2079718 0.7536131 0.6235283 0.2080382 0.3804641 0.8993283 0.2155362 0.389459 0.8952032 0.2166405 -0.06874305 0.981668 0.1777704 -0.05496603 0.9820106 0.1806492 -0.50347 0.8579 0.1025953 -0.4881386 0.8661219 0.107488 0.9608777 0.2267155 0.159104 0.9613767 0.22471 0.1589351 0.7450823 0.6316418 0.2141991 0.7490147 0.6269574 0.2142465 0.3700462 0.901726 0.2235085 0.3794014 0.8975477 0.2246398 -0.08399379 0.979143 0.1849974 -0.06996464 0.9796795 0.1879709 -0.5201066 0.8473921 0.1068448 -0.5045517 0.8560885 0.1119833 0.2263492 0.1595975 0.9608823 0.03633797 0.8914834 0.4515939 0.03636085 0.8910157 0.4525142 -0.002511501 0.9878329 0.1554992 -0.00245583 0.9875462 0.1573105 0.1181985 0.1554467 0.9807474 0.1182376 0.1562967 0.9806077 0.09981113 0.4535143 0.8856425 0.09984046 0.4540171 0.8853815 0.07160931 0.7074281 0.7031484 0.07191288 0.6496076 0.756861 0.06335055 0.7602525 0.6465315 0.1685549 0.1549433 0.9734382 0.1686244 0.1576954 0.9729841 0.1328731 0.4541448 0.8809638 0.1328548 0.4549894 0.8805307 0.08395218 0.7081809 0.701022 0.08395516 0.7079861 0.7012184 0.02671366 0.8918943 0.4514543 0.02685034 0.8910753 0.4530605 -0.0331766 0.987019 0.1571397 -0.03294682 0.9865314 0.1602198 0.2764536 0.1558802 0.9483011 0.2707632 -0.07406485 0.9597926 0.1813701 0.4535037 0.8726049 0.1805624 0.4578428 0.8705041 0.1021476 0.7100137 0.6967399 0.1022692 0.7096257 0.6971172 0.01221793 0.8936387 0.4486207 0.01372361 0.890834 0.4541215 -0.0788601 0.9848601 0.154375 -0.07614517 0.9831598 0.1661289 0.3411597 0.1490269 0.928117 0.3379509 0.165928 0.9264217 0.2479052 0.4565902 0.8544404 0.2454835 0.464102 0.8510859 0.1275478 0.7147082 0.6876947 0.127772 0.714263 0.6881154 -0.006827592 0.8950988 0.4458158 -0.003356158 0.8910598 0.4538736 -0.1403868 0.9778433 0.1552874 -0.1340427 0.9757719 0.1729217 -0.1915594 0.9649215 0.1795319 -0.2038547 0.9666262 0.155168 -0.0190919 0.892004 0.4516241 -0.02585214 0.8972879 0.4406885 0.1554647 0.7217322 0.6744875 0.1552127 0.7221024 0.6741492 0.3128681 0.4728711 0.8237151 0.3177559 0.4621114 0.8279398 0.4361097 0.1728889 0.8831295 0.5697726 0.07938033 0.8179597 0.4934445 0.1654841 0.8538897 0.4429167 0.147784 0.8842991 -0.2963934 0.937045 0.1846556 -0.3171614 0.9351043 0.1580781 -0.04373741 0.8991542 0.435441 -0.05541336 0.9040175 0.4238889 0.2142983 0.7461125 0.6303906 0.2139781 0.7463854 0.6301763 0.4446991 0.4977647 0.7446296 0.4534614 0.4842944 0.7482191 -0.3365558 0.9246066 0.1784183 -0.3475398 0.923067 0.1648135 -0.05340677 0.9050942 0.421844 -0.05965036 0.9074321 0.4159433 0.2369755 0.7591345 0.6062653 0.2369849 0.7590971 0.6063084 0.4943693 0.5069471 0.7061188 0.4988552 0.4999495 0.7079505 -0.2471577 0.9515637 0.1828652 -0.2634064 0.9517341 0.1575416 -0.03317171 0.8947355 0.4453629 -0.04222607 0.8998385 0.434175 0.1845587 0.732396 0.6553886 0.1843128 0.7327294 0.6550851 0.3803735 0.4840919 0.7880173 0.3870896 0.4720263 0.7920562 0.5415293 0.1516142 0.8268973 0.6181703 0.1859259 0.7637389 0.6291613 0.1550534 0.7616526 0.6825346 0.1841778 0.7072659 0.7466411 0.1780646 0.6409525 0.7044788 0.1781753 0.6869958 0.6876859 0.168024 0.7062975 -0.4004228 0.899671 0.173936 -0.4285632 0.8907353 0.1514078 -0.05514878 0.9244844 0.3772099 -0.0712158 0.9270805 0.3680355 0.2984525 0.8004925 0.5197477 0.2982921 0.8006041 0.5196682 0.603807 0.5481439 0.5787535 0.6151648 0.5339252 0.580083 -0.3619332 0.9142854 0.1818978 -0.3887746 0.9080466 0.1559033 -0.05330729 0.9112293 0.4084357 -0.06839203 0.9149893 0.3976397 0.2629885 0.7745665 0.575225 0.2627589 0.7747324 0.5751065 0.5403586 0.524813 0.6577112 0.5513817 0.5102278 0.6600348 0.752394 0.1650823 0.637692 0.8120771 0.2084111 0.5450648 0.8240296 0.1741976 0.5391016 0.8576449 0.2020822 0.472872 -0.4326472 0.887254 0.1599898 -0.4510842 0.8802961 0.1469752 -0.05723869 0.939074 0.3389155 -0.06778442 0.9402505 0.3336679 0.3278217 0.8260876 0.4583801 0.3278461 0.8260697 0.4583947 0.6553034 0.5683569 0.497542 0.6625518 0.5592263 0.4982882 0.9029605 0.09500706 0.4190896 0.881347 0.1952574 0.430235 0.917414 0.1967893 0.3458693 0.9096517 0.2235333 0.3500954 0.7059445 0.581705 0.4040564 0.6970424 0.5925381 0.4037706 0.3556706 0.8525322 0.3829981 0.3557169 0.8525102 0.383004 -0.06527739 0.9558596 0.2864813 -0.05191391 0.9551879 0.2914122 -0.4739379 0.8704398 0.1331077 -0.4506027 0.8807449 0.1457588 0.9522572 0.2106242 0.221006 0.9469761 0.2310383 0.2232879 0.7434738 0.609116 0.2760877 0.736721 0.6173033 0.2760052 0.3817553 0.8825515 0.2745282 0.3817801 0.8825422 0.2745237 -0.05917173 0.97451 0.2164003 -0.04891341 0.9744849 0.2190591 -0.4888171 0.8649961 0.1133118 -0.4707696 0.8740149 0.1203087 0.008072316 0.984398 0.1757712 0.008646905 0.9876757 0.1562755 0.01862353 0.9051948 0.4245889 0.01851445 0.8907868 0.4540443 0.02970808 0.7929922 0.6085069 0.02981692 0.7599726 0.6492709 0.03489637 0.6491861 0.7598287 0.03818672 0.6082645 0.7928154 0.03847473 0.4244465 0.9046353 0.03973782 0.453712 0.8902621 0.04681921 0.1562154 0.9866128 0.04517471 0.1755783 0.9834285 0 0.9844335 0.1757582 0 0.9053753 0.4246124 0 0.7933298 0.6087923 0 0.7933644 0.608747 0 0.6087167 0.7933877 0 0.4247258 0.9053221 0 0.4247682 0.9053022 0 0.1757637 0.9844325 -0.007185578 0.9876554 0.1564779 -0.009377002 0.9843931 0.1757336 -0.01970595 0.8908144 0.45394 -0.01642411 0.9052137 0.4246395 -0.03272807 0.7600498 0.6490402 -0.02794861 0.7930243 0.6085487 -0.03489482 0.6491567 0.759854 -0.03818672 0.6082645 0.7928154 -0.03854668 0.4536896 0.8903257 -0.04067546 0.424408 0.904557 -0.0465027 0.1755706 0.983368 -0.04532605 0.1561984 0.9866852 0.4889368 0.8647848 0.114404 -0.3821162 0.8831744 0.2720116 -0.744092 0.6099897 0.2724699 -0.9202926 0.1984376 0.3371709 -0.947517 0.2301812 0.2218743 -0.9530166 0.2115069 0.2168506 -0.7621906 0.1773731 0.6225787 -0.8008846 0.2052325 0.5625511 -0.8143546 0.1741439 0.5536248 -0.8510422 0.2041137 0.4838025 -0.9182947 -4.8461e-4 0.3958973 -0.8836639 0.1945624 0.4257742 -0.9118923 0.22294 0.3446015 -0.557798 0.1623566 0.8139422 -0.6106749 0.1856168 0.7698197 -0.6247488 0.1545053 0.7653868 -0.6800678 0.1844838 0.7095587 -0.780957 -0.07693427 0.6198285 -0.7283447 0.1715047 0.6634005 -0.7557886 0.1896008 0.6267656 -0.3821506 0.8831608 0.2720075 -0.3573859 0.8543459 0.3773177 -0.3574034 0.8543427 0.377308 -0.3264595 0.8242417 0.4626553 -0.3265811 0.8241817 0.4626764 -0.292937 0.7962369 0.5293342 -0.2929087 0.7962861 0.529276 -0.2684035 0.7792354 0.5663498 -0.2684972 0.7791985 0.566356 -0.2451654 0.763616 0.5973146 -0.2454125 0.7634607 0.5974116 -0.2119575 0.7452607 0.6321871 -0.2123214 0.7449818 0.6323937 -0.190281 0.7354652 0.6502953 -0.1903462 0.7354556 0.6502872 -0.17089 0.7274924 0.6644934 -0.1711158 0.7272232 0.6647299 -0.1427575 0.7185882 0.6806257 -0.1431364 0.7180896 0.6810722 -0.1220481 0.7136772 0.6897602 -0.1221482 0.7135474 0.6898768 -0.7374223 0.6174371 0.2738243 -0.7085682 0.583846 0.3963018 -0.6995714 0.593624 0.3977568 -0.6613828 0.5564637 0.5029126 -0.650523 0.5681576 0.5040008 -0.6057813 0.5309389 0.5925647 -0.5942094 0.5436131 0.59279 -0.5597333 0.5193776 0.6457133 -0.5546332 0.5245261 0.6459524 -0.5181685 0.5003229 0.6936704 -0.5063721 0.514208 0.6922265 -0.4497231 0.4833282 0.7510946 -0.4393706 0.4967262 0.7484763 -0.3992256 0.4793483 0.7815652 -0.3958199 0.4833925 0.7808062 -0.3563152 0.4673201 0.8091053 -0.3493775 0.4782825 0.8057179 -0.2874721 0.459401 0.8404228 -0.2827135 0.4685301 0.8369902 -0.2336574 0.4582573 0.8575573 -0.2320451 0.4615721 0.8562162 -0.2775848 0.1559851 0.9479532 -0.3178148 0.1626777 0.934093 -0.3205841 0.1541366 0.934595 -0.3923339 0.1693921 0.904091 -0.3992975 0.148873 0.9046537 -0.4690225 0.1702135 0.8666287 -0.5663191 -0.108917 0.8169578 -0.5208084 0.159284 0.8386819 -0.5526243 0.17205 0.8154785 -0.1025227 0.7101991 0.6964958 -0.1028621 0.7095148 0.6971429 -0.18304 0.453219 0.8724042 -0.1815578 0.4579332 0.8702495 -0.2744035 -0.0887798 0.9575077 -0.2270486 0.1599596 0.9606571 0.4712807 0.8740329 0.1181578 0.4750793 0.869665 0.1340991 0.4517471 0.8806742 0.1426104 0.4534034 0.8790726 0.147162 0.4263617 0.8901158 0.1609646 0.4232017 0.892723 0.1547455 0.3947326 0.9022997 0.1733251 0.3891245 0.9062841 0.165019 0.3771359 0.9099373 0.1725769 0.3665761 0.9168012 0.1584223 0.3386695 0.9230113 0.1826288 0.3153928 0.9356375 0.158461 0.2912003 0.938795 0.1840285 0.2707032 0.9479668 0.1675674 0.2626181 0.9487755 0.1756609 0.2378925 0.9584283 0.1575515 0.2212185 0.9583178 0.1808023 0.1770064 0.9717671 0.1560049 0.1655946 0.9703217 0.1762228 0.126851 0.9788766 0.1603415 0.1225831 0.9780089 0.1687362 0.08068048 0.984678 0.1545962 0.07664918 0.983123 0.1661149 0.01752251 0.9879739 0.1536247 0.01647871 0.9872187 0.1585172 -0.0315032 0.8922723 0.4503973 -0.01375776 0.890834 0.4541205 -0.01155155 0.8936138 0.448688 1.57892e-4 0.8916642 0.4526975 0.002573132 0.8936485 0.4487603 0.01192164 0.8916288 0.4526104 0.01809138 0.8960328 0.4436193 0.02646201 0.8934962 0.4482907 0.03574323 0.89829 0.437947 0.0385102 0.8971894 0.4399638 0.04278254 0.8986284 0.4366196 0.04205179 0.8989741 0.4359787 0.05548024 0.9034547 0.4250783 0.05004209 0.9064342 0.419372 0.06565237 0.9100365 0.4092962 0.05884224 0.9145746 0.4001137 0.06548553 0.9154046 0.3971728 0.05516904 0.922632 0.3817154 0.07121688 0.9245175 0.3744273 0.05454415 0.9383379 0.3413898 0.06982034 0.939177 0.3362613 0.05183023 0.9566091 0.2867273 0.06494098 0.9566738 0.2838277 0.04907029 0.9750286 0.2165899 0.05904066 0.974713 0.2155199 -0.1417676 0.1561648 0.9775043 -0.1421663 0.1528294 0.9779735 -0.1153037 0.453843 0.8835903 -0.1155588 0.4524701 0.8842608 -0.0878551 0.6495017 0.7552675 -0.07545077 0.7072266 0.7029492 -0.06671988 0.7603399 0.6460897 -0.03209406 0.8909758 0.452915 -0.9613966 0.2247427 0.1587684 -0.9608592 0.2266772 0.1592704 -0.7490786 0.6270466 0.2137612 -0.7450162 0.6315557 0.214682 -0.3795105 0.8977005 0.2238427 -0.3699384 0.901573 0.2243026 0.06984281 0.979902 0.1868531 0.08411288 0.9789232 0.1861035 0.5044361 0.8563434 0.1105453 0.5202273 0.8471368 0.1082726 -0.9621429 0.2232117 0.1563896 -0.9616252 0.2251126 0.1568481 -0.7536639 0.6236227 0.2075709 -0.749713 0.628081 0.2084342 -0.3895338 0.8953573 0.2158672 -0.3803909 0.8991751 0.2163034 0.05480128 0.9822197 0.1795586 0.06891518 0.9814587 0.1788561 0.4879633 0.8663935 0.1060861 0.5036268 0.8576409 0.103982 -0.867308 0.4764497 0.1441267 0.5501558 0.827869 0.1093689 0.5754535 0.8106364 0.1082691 0.1808884 0.9708325 0.1573649 0.1955143 0.9680159 0.157224 -0.06807315 0.9810281 0.1815215 -0.2176033 0.958884 0.1821826 -0.4060349 0.8923192 0.1972365 -0.5933499 0.7850281 0.1779522 -0.6586197 0.7313963 0.17686 -0.8237193 0.5439615 0.1599766 -0.9633333 0.2313918 0.1358189 -0.8646076 0.4704682 0.1763902 -0.7473688 0.6358208 0.1928004 -0.5908118 0.779154 0.2094295 -0.3717562 0.9046493 0.2083435 -0.215678 0.9543383 0.2066916 0.08328425 0.9802916 0.179143 0.196412 0.9659196 0.1685872 0.5206268 0.8464809 0.1114366 0.5749315 0.8118732 0.1015665 0.4275031 0.8586279 0.2828414 0.1982837 0.9567511 0.2128639 -0.04418653 0.9906912 0.1287577 -0.07059526 0.9920934 0.103765 -0.09350782 0.9814882 0.1671448 -0.3177312 0.9435238 0.09386056 0.4177158 0.8664768 0.2733708 0.4135102 0.8647275 0.285054 0.3227913 0.9090029 0.2636658 0.3217046 0.9078205 0.2690134 0.2346748 0.9371914 0.2580697 0.2357338 0.9400483 0.2464525 0.1674199 0.9559211 0.241217 0.1799061 0.9640169 0.1957173 0.1655519 0.9578103 0.2349296 0.002597808 0.9819636 0.1890527 -0.007388174 0.97139 0.2373751 -0.1580638 0.9654963 0.2069609 -0.1603739 0.959469 0.2317316 -0.2736601 0.9380779 0.2124148 0.576326 0.8027108 0.1533102 0.5756301 0.786827 0.222606 0.5945719 0.7727262 0.2222124 0.5902864 0.7611506 0.2687228 0.6144468 0.7414432 0.2696612 0.6064087 0.7326177 0.3090953 0.6315541 0.7090708 0.3136211 0.6253667 0.7066154 0.3310759 0.6279914 0.7029314 0.3339377 0.5526272 0.8187584 0.1556857 0.1835346 0.9624747 0.1998936 0.1679965 0.9649459 0.2016348 -0.06629681 0.9758822 0.2079874 -0.2735763 0.9387895 0.2093567 -0.4060328 0.8923627 0.1970438 -0.6585939 0.7313395 0.1771914 -0.3287671 0.9331417 0.1454607 -0.4893471 0.8596637 0.1466892 -0.5267221 0.8394617 0.1336715 -0.5310896 0.8278483 0.1805853 -0.6611052 0.7368052 0.1416267 -0.6617894 0.7285379 0.1768262 -0.8252092 0.5478636 0.137388 -0.2024461 0.9789878 -0.0244674 -0.03033125 0.9952012 0.09303015 0.7660704 0.5561437 0.3222427 0.6769979 0.6657412 0.3137876 0.6543762 0.6872931 0.3153095 0.6338769 0.7048971 0.3183084 0.2771348 0.9606789 0.01710474 0.2339879 0.9627708 0.1353589 0.2284882 0.964419 0.1330009 0.4504498 0.8650001 0.2210655 0.5373333 0.8078442 0.2422001 0.4526104 0.8807526 0.1393512 0.4690829 0.8783523 0.09197044 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 0 0 2 0 6 0 5 0 7 0 3 0 3 0 7 0 8 0 3 0 8 0 2 0 2 2 8 2 9 2 2 0 9 0 6 0 10 3 11 3 12 3 12 4 11 4 13 4 14 5 15 5 16 5 16 5 15 5 17 5 18 6 19 6 20 6 21 7 22 7 23 7 23 8 22 8 24 8 25 9 26 9 27 9 26 10 28 10 27 10 27 11 28 11 29 11 27 12 29 12 30 12 31 13 32 13 33 13 33 14 32 14 34 14 35 15 36 15 37 15 37 16 36 16 31 16 38 17 39 17 35 17 38 18 35 18 40 18 40 19 35 19 37 19 40 20 37 20 41 20 41 21 37 21 42 21 41 22 42 22 43 22 43 23 42 23 44 23 44 24 42 24 45 24 44 25 45 25 46 25 46 26 45 26 22 26 46 27 22 27 47 27 47 28 22 28 21 28 47 29 21 29 48 29 31 30 33 30 37 30 37 31 33 31 49 31 37 32 49 32 42 32 42 33 49 33 50 33 42 34 50 34 45 34 45 35 50 35 27 35 45 36 27 36 22 36 22 37 27 37 30 37 22 38 30 38 24 38 34 39 18 39 33 39 33 40 18 40 20 40 33 41 20 41 49 41 49 42 20 42 51 42 49 43 51 43 50 43 50 44 51 44 52 44 50 45 52 45 27 45 27 46 52 46 53 46 27 47 53 47 25 47 15 48 10 48 17 48 17 48 10 48 12 48 54 49 55 49 56 49 57 50 58 50 59 50 60 51 61 51 62 51 63 52 64 52 65 52 65 53 64 53 66 53 65 54 66 54 67 54 68 55 69 55 70 55 70 56 69 56 71 56 72 57 54 57 73 57 74 58 75 58 73 58 73 59 75 59 76 59 73 60 76 60 72 60 77 61 74 61 78 61 78 62 74 62 73 62 78 63 73 63 79 63 79 64 73 64 80 64 79 65 80 65 81 65 81 66 80 66 82 66 82 67 80 67 83 67 82 68 83 68 84 68 84 69 83 69 69 69 84 70 69 70 66 70 66 71 69 71 68 71 66 72 68 72 67 72 54 73 56 73 73 73 73 74 56 74 85 74 73 75 85 75 80 75 80 76 85 76 86 76 80 77 86 77 83 77 83 78 86 78 62 78 83 79 62 79 69 79 69 80 62 80 61 80 69 81 61 81 71 81 87 82 60 82 88 82 88 83 60 83 62 83 88 84 62 84 89 84 89 85 62 85 86 85 89 86 86 86 90 86 90 87 86 87 85 87 90 88 85 88 59 88 59 89 85 89 56 89 59 90 56 90 57 90 57 91 56 91 55 91 91 92 39 92 38 92 48 93 92 93 11 93 93 94 77 94 14 94 14 95 77 95 78 95 14 96 78 96 15 96 15 97 78 97 79 97 15 98 79 98 10 98 94 99 95 99 96 99 96 100 95 100 97 100 94 101 96 101 98 101 98 102 96 102 91 102 98 103 91 103 99 103 100 104 101 104 96 104 96 105 101 105 102 105 96 106 102 106 91 106 97 107 103 107 96 107 96 108 103 108 9 108 96 109 9 109 100 109 100 110 9 110 8 110 100 111 8 111 104 111 104 112 8 112 105 112 48 113 11 113 47 113 47 114 11 114 10 114 47 115 10 115 46 115 46 116 10 116 79 116 46 117 79 117 44 117 44 118 79 118 81 118 44 119 81 119 43 119 43 120 81 120 82 120 43 121 82 121 41 121 41 122 82 122 84 122 41 123 84 123 40 123 40 123 84 123 66 123 40 124 66 124 38 124 38 125 66 125 64 125 38 126 64 126 91 126 91 127 64 127 63 127 91 128 63 128 99 128 16 129 93 129 14 129 92 130 13 130 11 130 106 131 107 131 108 131 109 132 110 132 111 132 112 133 113 133 114 133 112 134 114 134 115 134 109 135 111 135 116 135 116 136 111 136 117 136 116 137 117 137 108 137 108 138 117 138 118 138 108 139 118 139 106 139 115 140 114 140 119 140 119 141 114 141 120 141 119 142 120 142 110 142 110 143 120 143 121 143 110 144 121 144 111 144 111 145 121 145 122 145 111 146 122 146 117 146 123 147 124 147 125 147 123 148 125 148 126 148 125 149 127 149 126 149 126 150 127 150 128 150 126 151 128 151 129 151 129 152 128 152 130 152 131 153 132 153 133 153 133 154 132 154 134 154 133 155 134 155 130 155 130 156 134 156 135 156 130 157 135 157 129 157 133 158 136 159 131 160 131 161 136 161 137 161 131 162 137 162 138 162 138 163 137 163 139 163 140 164 116 164 108 164 107 165 141 165 142 165 107 166 142 166 108 166 108 167 142 167 143 167 108 168 143 168 140 168 144 169 145 169 146 169 146 170 145 170 147 170 147 171 145 171 148 171 147 172 148 172 149 172 146 173 150 173 144 173 144 174 150 174 151 174 144 175 151 175 152 175 152 176 151 176 153 176 152 177 153 177 154 177 154 178 153 178 155 178 154 179 155 179 156 179 156 180 155 180 157 180 158 181 159 181 160 181 160 182 159 182 125 182 160 183 125 183 124 183 149 184 148 184 161 184 161 185 148 185 162 185 161 186 162 186 163 186 158 187 164 187 159 187 159 188 164 188 165 188 159 189 165 189 162 189 162 190 165 190 166 190 162 191 166 191 163 191 114 192 113 192 167 192 168 193 169 193 170 193 134 194 132 194 171 194 171 195 132 195 131 195 170 196 172 196 168 196 168 197 172 197 173 197 168 198 173 198 174 198 174 199 173 199 175 199 174 200 175 200 176 200 176 201 175 201 177 201 176 202 177 202 178 202 178 203 177 203 179 203 178 204 179 204 180 204 180 205 179 205 171 205 180 206 171 206 181 206 181 207 171 207 131 207 181 208 131 208 138 208 129 209 135 209 182 209 182 210 135 210 134 210 123 211 126 211 183 211 183 212 126 212 129 212 184 213 124 213 123 213 123 214 183 214 184 214 184 215 183 215 185 215 184 216 185 216 186 216 186 217 185 217 187 217 186 218 187 218 188 218 188 219 187 219 189 219 189 220 187 220 190 220 189 221 190 221 191 221 192 222 193 222 194 222 194 223 193 223 195 223 194 224 195 224 190 224 190 225 195 225 196 225 190 226 196 226 191 226 197 227 122 227 121 227 170 228 118 228 117 228 169 229 107 229 170 229 170 230 107 230 106 230 170 231 106 231 118 231 194 232 198 232 192 232 192 233 198 233 199 233 192 234 199 234 167 234 167 235 199 235 120 235 167 236 120 236 114 236 129 237 182 237 183 237 183 238 182 238 200 238 183 239 200 239 185 239 185 240 200 240 201 240 185 241 201 241 187 241 187 242 201 242 202 242 187 243 202 243 190 243 190 244 202 244 203 244 190 245 203 245 194 245 194 246 203 246 204 246 194 247 204 247 198 247 198 248 204 248 197 248 198 249 197 249 199 249 199 250 197 250 121 250 199 251 121 251 120 251 134 252 171 252 182 252 182 253 171 253 179 253 182 254 179 254 200 254 200 255 179 255 177 255 200 256 177 256 201 256 201 257 177 257 175 257 201 258 175 258 202 258 202 259 175 259 173 259 202 260 173 260 203 260 203 261 173 261 172 261 203 262 172 262 204 262 204 263 172 263 170 263 204 264 170 264 197 264 197 265 170 265 117 265 197 266 117 266 122 266 115 267 119 267 205 267 206 268 207 268 208 268 209 269 210 269 211 269 211 270 210 270 212 270 119 271 110 271 205 271 205 272 110 272 213 272 205 273 213 273 214 273 214 274 213 274 215 274 210 275 206 275 212 275 212 276 206 276 208 276 212 277 208 277 216 277 110 278 109 278 213 278 213 279 109 279 116 279 213 280 116 280 217 280 218 281 219 281 220 281 220 282 219 282 221 282 220 283 221 283 222 283 222 284 221 284 223 284 222 285 223 285 216 285 216 286 223 286 224 286 216 287 224 287 212 287 212 288 224 288 225 288 212 289 225 289 211 289 113 290 112 290 226 290 226 291 112 291 115 291 226 292 115 292 227 292 227 293 115 293 205 293 227 294 205 294 228 294 228 295 205 295 214 295 228 296 214 296 229 296 229 297 214 297 215 297 208 298 230 298 216 298 216 299 230 299 231 299 216 300 231 300 222 300 222 301 231 301 232 301 222 302 232 302 233 302 217 303 218 303 213 303 213 304 218 304 220 304 213 305 220 305 215 305 215 306 220 306 222 306 215 307 222 307 229 307 229 308 222 308 233 308 229 309 233 309 228 309 228 310 233 310 234 310 228 311 234 311 227 311 227 312 234 312 235 312 227 313 235 313 226 313 236 314 237 314 238 314 238 315 237 315 239 315 238 316 239 316 240 316 239 317 241 317 240 317 240 318 241 318 242 318 240 319 242 319 243 319 243 320 242 320 244 320 243 321 244 321 245 321 244 322 246 322 245 322 245 323 246 323 247 323 245 324 247 324 248 324 248 325 247 325 249 325 248 326 249 326 250 326 250 327 249 327 251 327 250 328 251 328 252 328 252 329 251 329 253 329 252 330 253 330 254 330 254 331 253 331 255 331 256 332 257 332 258 332 258 333 257 333 259 333 258 334 259 334 255 334 255 335 259 335 260 335 255 336 260 336 254 336 261 337 262 337 263 337 236 338 264 338 265 338 265 339 264 339 266 339 267 340 268 340 269 340 269 341 268 341 266 341 269 342 266 342 270 342 270 343 266 343 264 343 263 344 262 344 271 344 262 345 272 345 271 345 271 346 272 346 273 346 271 347 273 347 267 347 267 348 273 348 274 348 267 349 274 349 268 349 261 350 263 350 275 350 275 351 263 351 276 351 275 352 276 352 277 352 277 353 276 353 278 353 277 354 278 354 279 354 279 355 278 355 280 355 279 356 280 356 281 356 281 357 280 357 156 357 281 358 156 358 157 358 282 359 283 359 284 359 285 360 283 360 286 360 287 361 283 361 285 361 288 362 286 362 283 362 289 363 283 363 290 363 291 364 283 364 289 364 292 365 290 365 283 365 287 366 292 366 283 366 293 367 283 367 294 367 295 368 283 368 293 368 296 369 294 369 283 369 291 370 296 370 283 370 297 371 298 371 299 371 283 372 300 372 301 372 302 373 300 373 283 373 295 374 302 374 283 374 303 375 304 375 305 375 306 376 307 376 308 376 308 377 307 377 309 377 310 378 311 378 312 378 312 379 311 379 313 379 312 380 313 380 314 380 303 381 305 381 315 381 315 382 305 382 316 382 315 383 316 383 317 383 318 384 319 384 305 384 305 385 319 385 320 385 305 386 320 386 316 386 321 387 322 387 323 387 323 388 322 388 324 388 323 389 324 389 318 389 283 390 325 390 326 390 326 391 325 391 321 391 326 392 321 392 327 392 327 393 321 393 323 393 328 394 329 394 330 394 331 395 332 395 329 395 333 396 334 396 335 396 147 397 149 397 334 397 334 398 333 398 147 398 147 399 333 399 336 399 147 400 336 400 146 400 146 401 336 401 150 401 150 402 336 402 337 402 150 403 337 403 151 403 151 404 337 404 338 404 151 405 338 405 153 405 298 406 157 406 339 406 339 407 157 407 155 407 339 408 155 408 340 408 340 409 155 409 153 409 340 410 153 410 341 410 341 411 153 411 338 411 299 412 298 412 342 412 343 413 344 413 345 413 345 414 344 414 346 414 346 415 347 415 345 415 345 416 347 416 348 416 345 417 348 417 349 417 350 418 351 418 352 418 352 419 351 419 353 419 306 420 308 420 350 420 350 421 308 421 354 421 350 422 354 422 351 422 298 423 339 423 342 423 342 424 339 424 340 424 342 425 340 425 355 425 355 426 340 426 341 426 355 427 341 427 356 427 356 428 341 428 338 428 356 429 338 429 357 429 357 430 338 430 337 430 357 431 337 431 358 431 358 432 337 432 336 432 358 433 336 433 359 433 359 434 336 434 333 434 359 435 333 435 360 435 360 436 333 436 335 436 360 437 335 437 332 437 332 438 331 438 360 438 360 439 331 439 361 439 360 440 361 440 359 440 359 441 361 441 362 441 359 442 362 442 358 442 358 443 362 443 363 443 358 444 363 444 357 444 357 445 363 445 364 445 357 446 364 446 356 446 356 447 364 447 365 447 356 448 365 448 355 448 355 449 365 449 366 449 355 450 366 450 342 450 342 451 366 451 349 451 342 452 349 452 299 452 299 453 349 453 348 453 299 454 348 454 297 454 329 455 367 455 331 455 331 456 367 456 368 456 331 457 368 457 361 457 361 458 368 458 369 458 361 459 369 459 362 459 362 460 369 460 370 460 362 461 370 461 363 461 363 462 370 462 371 462 363 463 371 463 364 463 364 464 371 464 372 464 364 465 372 465 365 465 365 466 372 466 373 466 365 467 373 467 366 467 366 468 373 468 374 468 366 469 374 469 349 469 349 470 374 470 375 470 349 471 375 471 345 471 345 472 375 472 352 472 345 473 352 473 343 473 343 474 352 474 353 474 343 475 353 475 344 475 312 476 376 476 310 476 310 477 376 477 377 477 310 478 377 478 378 478 378 479 377 479 379 479 378 480 379 480 380 480 380 481 379 481 381 481 380 482 381 482 382 482 382 483 381 483 383 483 382 484 383 484 384 484 384 485 383 485 385 485 384 486 385 486 386 486 386 487 385 487 387 487 386 488 387 488 388 488 388 489 387 489 389 489 388 490 389 490 390 490 390 491 389 491 391 491 390 492 391 492 392 492 392 493 391 493 393 493 392 494 393 494 394 494 394 495 393 495 395 495 394 496 395 496 396 496 396 497 395 497 397 497 396 498 397 498 398 498 398 499 397 499 399 499 398 500 399 500 400 500 400 501 399 501 401 501 400 502 401 502 402 502 402 503 401 503 403 503 402 504 403 504 404 504 404 505 403 505 328 505 404 506 328 506 405 506 405 507 328 507 330 507 405 508 330 508 301 508 329 509 328 509 367 509 367 510 328 510 403 510 367 511 403 511 368 511 368 512 403 512 401 512 368 513 401 513 369 513 369 514 401 514 399 514 369 515 399 515 370 515 370 516 399 516 397 516 370 517 397 517 371 517 371 518 397 518 395 518 371 519 395 519 372 519 372 520 395 520 393 520 372 521 393 521 373 521 373 522 393 522 391 522 373 523 391 523 374 523 374 524 391 524 389 524 374 525 389 525 375 525 375 526 389 526 387 526 375 527 387 527 352 527 352 528 387 528 385 528 352 529 385 529 350 529 350 530 385 530 383 530 350 531 383 531 306 531 306 532 383 532 381 532 306 533 381 533 307 533 307 534 381 534 379 534 307 535 379 535 309 535 282 536 288 536 283 536 406 537 284 537 283 537 301 538 300 538 405 538 405 539 300 539 302 539 405 540 302 540 404 540 404 541 302 541 295 541 404 542 295 542 402 542 402 543 295 543 293 543 402 544 293 544 400 544 400 545 293 545 294 545 400 546 294 546 398 546 398 547 294 547 296 547 398 548 296 548 396 548 396 549 296 549 291 549 396 550 291 550 394 550 394 551 291 551 289 551 394 552 289 552 392 552 392 553 289 553 290 553 392 554 290 554 390 554 390 555 290 555 292 555 390 556 292 556 388 556 388 557 292 557 287 557 388 558 287 558 386 558 386 559 287 559 285 559 386 560 285 560 384 560 384 561 285 561 286 561 384 562 286 562 382 562 382 563 286 563 288 563 382 564 288 564 380 564 380 565 288 565 282 565 380 566 282 566 378 566 378 567 282 567 284 567 378 568 284 568 310 568 310 569 284 569 406 569 310 570 406 570 311 570 407 571 408 571 409 571 409 572 408 572 410 572 409 573 410 573 411 573 411 574 410 574 412 574 411 575 412 575 413 575 413 576 412 576 414 576 413 577 414 577 283 577 408 578 314 578 410 578 410 579 314 579 313 579 410 580 313 580 412 580 412 581 313 581 311 581 412 582 311 582 414 582 414 583 311 583 406 583 414 584 406 584 283 584 304 585 415 585 416 585 416 586 415 586 417 586 416 587 417 587 418 587 418 588 417 588 419 588 418 589 419 589 420 589 420 590 419 590 421 590 420 591 421 591 283 591 415 592 407 592 417 592 417 593 407 593 409 593 417 594 409 594 419 594 419 595 409 595 411 595 419 596 411 596 421 596 421 597 411 597 413 597 421 598 413 598 283 598 323 599 422 599 327 599 327 600 422 600 423 600 327 601 423 601 326 601 326 602 423 602 424 602 326 603 424 603 283 603 318 604 305 604 323 604 323 605 305 605 304 605 323 606 304 606 422 606 422 607 304 607 416 607 422 608 416 608 423 608 423 609 416 609 418 609 423 610 418 610 424 610 424 611 418 611 420 611 424 612 420 612 283 612 425 613 209 613 116 613 116 614 209 614 211 614 116 615 211 615 225 615 221 616 219 616 116 616 116 617 219 617 218 617 116 618 218 618 217 618 116 619 140 619 425 619 425 620 140 620 426 620 425 621 426 621 427 621 427 622 428 622 425 622 425 623 428 623 429 623 425 624 429 624 430 624 430 625 429 625 431 625 225 626 224 626 116 626 116 627 224 627 223 627 116 628 223 628 221 628 432 629 433 629 434 629 434 630 435 630 432 630 432 631 435 631 436 631 432 632 436 632 437 632 437 633 436 633 438 633 437 634 438 634 439 634 439 635 438 635 440 635 439 636 440 636 441 636 441 637 440 637 442 637 438 638 443 638 440 638 440 639 443 639 140 639 440 640 140 640 442 640 442 641 140 641 143 641 442 642 143 642 444 642 444 643 143 643 142 643 444 644 142 644 445 644 445 645 142 645 141 645 446 646 447 646 448 646 449 647 450 647 451 647 449 648 451 648 452 648 449 649 452 649 453 649 453 650 452 650 448 650 453 651 448 651 454 651 454 652 448 652 447 652 446 653 448 653 455 653 455 654 448 654 456 654 455 655 456 655 457 655 457 656 456 656 458 656 457 657 458 657 459 657 460 658 461 658 462 658 462 659 461 659 463 659 462 660 463 660 464 660 464 661 463 661 465 661 464 662 465 662 466 662 257 663 256 663 467 663 467 664 256 664 468 664 467 665 468 665 469 665 469 666 468 666 470 666 469 667 470 667 471 667 471 668 470 668 472 668 471 669 472 669 473 669 473 670 472 670 466 670 473 671 466 671 474 671 474 672 466 672 465 672 475 673 476 673 477 673 478 674 479 674 480 674 481 675 482 675 483 675 478 676 480 676 484 676 475 677 477 677 485 677 208 678 486 678 230 678 230 679 486 679 487 679 230 680 487 680 231 680 231 681 487 681 488 681 231 682 488 682 232 682 232 683 488 683 233 683 233 684 488 684 489 684 233 685 489 685 234 685 234 686 489 686 235 686 235 687 489 687 490 687 235 688 490 688 226 688 226 689 490 689 491 689 226 690 491 690 113 690 113 691 491 691 492 691 113 692 492 692 167 692 167 693 492 693 493 693 167 694 493 694 192 694 192 695 493 695 494 695 192 696 494 696 193 696 193 697 494 697 495 697 193 698 495 698 195 698 195 699 495 699 196 699 196 700 495 700 496 700 196 701 496 701 191 701 191 702 496 702 497 702 191 703 497 703 189 703 189 704 497 704 498 704 189 705 498 705 188 705 188 706 498 706 499 706 188 707 499 707 186 707 186 708 499 708 500 708 186 709 500 709 184 709 184 710 500 710 160 710 184 711 160 711 124 711 334 712 149 712 161 712 161 713 501 713 334 713 334 714 501 714 502 714 334 715 502 715 335 715 335 716 502 716 503 716 335 717 503 717 332 717 504 718 321 718 505 718 505 719 321 719 325 719 505 720 325 720 506 720 506 721 325 721 283 721 506 722 283 722 507 722 507 723 283 723 301 723 507 724 301 724 508 724 508 725 301 725 330 725 508 726 330 726 509 726 509 727 330 727 329 727 509 728 329 728 510 728 510 729 329 729 332 729 510 730 332 730 511 730 511 731 332 731 503 731 512 732 318 732 513 732 513 733 318 733 324 733 513 734 324 734 504 734 504 735 324 735 322 735 504 736 322 736 321 736 514 737 317 737 515 737 515 738 317 738 316 738 515 739 316 739 516 739 516 740 316 740 320 740 516 741 320 741 512 741 512 742 320 742 319 742 512 743 319 743 318 743 165 744 164 744 517 744 517 745 164 745 518 745 517 746 518 746 519 746 519 747 518 747 520 747 519 748 520 748 521 748 521 749 520 749 522 749 521 750 522 750 523 750 523 751 522 751 524 751 523 752 524 752 525 752 525 753 524 753 526 753 525 754 526 754 527 754 527 755 526 755 528 755 527 756 528 756 529 756 529 757 528 757 530 757 529 758 530 758 531 758 531 759 530 759 532 759 531 760 532 760 533 760 533 761 532 761 534 761 533 762 534 762 535 762 535 763 534 763 536 763 535 764 536 764 537 764 537 765 536 765 538 765 537 766 538 766 539 766 539 767 538 767 540 767 539 768 540 768 541 768 541 769 540 769 542 769 541 770 542 770 543 770 543 771 542 771 544 771 543 772 544 772 480 772 480 773 544 773 545 773 480 774 545 774 484 774 164 775 158 775 518 775 518 776 158 776 546 776 518 777 546 777 520 777 520 778 546 778 547 778 520 779 547 779 522 779 522 780 547 780 548 780 522 781 548 781 524 781 524 782 548 782 549 782 524 783 549 783 526 783 526 784 549 784 550 784 526 785 550 785 528 785 528 786 550 786 551 786 528 787 551 787 530 787 530 788 551 788 552 788 530 789 552 789 532 789 532 790 552 790 553 790 532 791 553 791 534 791 534 792 553 792 554 792 534 793 554 793 536 793 536 794 554 794 555 794 536 795 555 795 538 795 538 796 555 796 556 796 538 797 556 797 540 797 540 798 556 798 557 798 540 799 557 799 542 799 542 800 557 800 558 800 542 801 558 801 544 801 544 802 558 802 559 802 544 803 559 803 545 803 545 804 559 804 477 804 545 805 477 805 484 805 484 806 477 806 476 806 158 807 160 807 546 807 546 808 160 808 500 808 546 809 500 809 547 809 547 810 500 810 499 810 547 811 499 811 548 811 548 812 499 812 498 812 548 813 498 813 549 813 549 814 498 814 497 814 549 815 497 815 550 815 550 816 497 816 496 816 550 817 496 817 551 817 551 818 496 818 495 818 551 819 495 819 552 819 552 820 495 820 494 820 552 821 494 821 553 821 553 822 494 822 493 822 553 823 493 823 554 823 554 824 493 824 492 824 554 825 492 825 555 825 555 826 492 826 491 826 555 827 491 827 556 827 556 828 491 828 490 828 556 829 490 829 557 829 557 830 490 830 489 830 557 831 489 831 558 831 558 832 489 832 488 832 558 833 488 833 559 833 559 834 488 834 487 834 559 835 487 835 477 835 477 836 487 836 486 836 477 837 486 837 485 837 485 838 486 838 208 838 485 839 208 839 207 839 163 840 166 840 560 840 560 841 166 841 561 841 560 842 561 842 562 842 562 843 561 843 563 843 562 844 563 844 564 844 564 845 563 845 565 845 564 846 565 846 566 846 566 847 565 847 567 847 566 848 567 848 568 848 568 849 567 849 569 849 568 850 569 850 570 850 570 851 569 851 571 851 570 852 571 852 572 852 572 853 571 853 573 853 572 854 573 854 574 854 574 855 573 855 575 855 574 856 575 856 576 856 576 857 575 857 577 857 576 858 577 858 578 858 578 859 577 859 579 859 578 860 579 860 580 860 580 861 579 861 581 861 580 862 581 862 582 862 582 863 581 863 583 863 582 864 583 864 584 864 584 865 583 865 585 865 584 866 585 866 586 866 586 867 585 867 587 867 586 868 587 868 483 868 483 869 587 869 588 869 483 870 588 870 481 870 481 871 588 871 589 871 161 872 163 872 501 872 501 873 163 873 560 873 501 874 560 874 502 874 502 875 560 875 562 875 502 876 562 876 503 876 503 877 562 877 564 877 503 878 564 878 511 878 511 879 564 879 566 879 511 880 566 880 510 880 510 881 566 881 568 881 510 882 568 882 509 882 509 883 568 883 570 883 509 884 570 884 508 884 508 885 570 885 572 885 508 886 572 886 507 886 507 887 572 887 574 887 507 888 574 888 506 888 506 889 574 889 576 889 506 890 576 890 505 890 505 891 576 891 578 891 505 892 578 892 504 892 504 893 578 893 580 893 504 894 580 894 513 894 513 895 580 895 582 895 513 896 582 896 512 896 512 897 582 897 584 897 512 898 584 898 516 898 516 899 584 899 586 899 516 900 586 900 515 900 515 901 586 901 483 901 515 902 483 902 514 902 514 903 483 903 482 903 166 904 165 904 561 904 561 905 165 905 517 905 561 906 517 906 563 906 563 907 517 907 519 907 563 908 519 908 565 908 565 909 519 909 521 909 565 910 521 910 567 910 567 911 521 911 523 911 567 912 523 912 569 912 569 913 523 913 525 913 569 914 525 914 571 914 571 915 525 915 527 915 571 916 527 916 573 916 573 917 527 917 529 917 573 918 529 918 575 918 575 919 529 919 531 919 575 920 531 920 577 920 577 921 531 921 533 921 577 922 533 922 579 922 579 923 533 923 535 923 579 924 535 924 581 924 581 925 535 925 537 925 581 926 537 926 583 926 583 927 537 927 539 927 583 928 539 928 585 928 585 929 539 929 541 929 585 930 541 930 587 930 587 931 541 931 543 931 587 932 543 932 588 932 588 933 543 933 480 933 588 934 480 934 589 934 589 935 480 935 479 935 590 936 207 936 591 936 591 937 207 937 206 937 591 938 206 938 592 938 206 939 210 939 592 939 592 940 210 940 209 940 592 941 209 941 425 941 593 942 594 942 595 942 596 943 597 943 598 943 599 944 600 944 601 944 602 945 603 945 604 945 605 946 606 946 603 946 607 947 608 947 609 947 609 948 608 948 610 948 611 949 612 949 613 949 614 950 237 950 615 950 615 951 237 951 236 951 615 952 236 952 616 952 617 953 242 953 618 953 618 954 242 954 241 954 618 955 241 955 614 955 614 956 241 956 239 956 614 957 239 957 237 957 619 958 620 958 244 958 244 959 620 959 246 959 246 960 620 960 247 960 247 961 620 961 621 961 247 962 621 962 249 962 622 963 623 963 624 963 624 964 623 964 625 964 249 965 621 965 251 965 251 966 621 966 626 966 251 967 626 967 253 967 253 968 626 968 627 968 253 969 627 969 255 969 255 970 627 970 624 970 255 971 624 971 258 971 258 972 624 972 625 972 258 973 625 973 256 973 599 974 628 974 629 974 629 975 628 975 630 975 629 976 630 976 631 976 631 977 630 977 632 977 631 978 632 978 633 978 634 979 635 979 636 979 636 980 635 980 637 980 636 981 637 981 638 981 639 982 640 982 641 982 641 983 640 983 642 983 643 984 640 984 644 984 644 985 640 985 639 985 644 986 639 986 645 986 594 987 646 987 595 987 595 988 646 988 647 988 595 989 647 989 648 989 648 990 647 990 649 990 650 991 651 991 652 991 652 992 651 992 609 992 652 993 609 993 653 993 653 994 609 994 610 994 653 995 610 995 606 995 603 996 602 996 605 996 605 997 602 997 654 997 605 998 654 998 655 998 655 999 654 999 656 999 655 1000 656 1000 657 1000 658 1001 659 1001 660 1001 660 1002 659 1002 661 1002 660 1003 661 1003 662 1003 662 1004 661 1004 663 1004 662 1005 663 1005 593 1005 596 1006 598 1006 664 1006 664 1007 598 1007 665 1007 664 1008 665 1008 666 1008 666 1009 665 1009 667 1009 666 1010 667 1010 668 1010 668 1011 667 1011 669 1011 668 1012 669 1012 670 1012 670 1013 669 1013 671 1013 670 1014 671 1014 672 1014 673 1015 674 1015 675 1015 675 1016 674 1016 634 1016 675 1017 634 1017 676 1017 676 1018 634 1018 636 1018 676 1019 636 1019 677 1019 677 1020 636 1020 638 1020 677 1021 638 1021 633 1021 678 1022 597 1022 679 1022 679 1023 597 1023 596 1023 679 1024 596 1024 680 1024 606 1025 605 1025 653 1025 653 1026 605 1026 655 1026 653 1027 655 1027 652 1027 652 1028 655 1028 657 1028 652 1029 657 1029 650 1029 604 1030 681 1030 602 1030 602 1031 681 1031 682 1031 602 1032 682 1032 654 1032 654 1033 682 1033 643 1033 654 1034 643 1034 656 1034 656 1035 643 1035 644 1035 656 1036 644 1036 657 1036 657 1037 644 1037 645 1037 657 1038 645 1038 650 1038 616 1039 683 1039 615 1039 615 1040 683 1040 684 1040 615 1041 684 1041 614 1041 614 1042 684 1042 680 1042 614 1043 680 1043 618 1043 618 1044 680 1044 685 1044 618 1045 685 1045 617 1045 617 1046 685 1046 686 1046 617 1047 686 1047 687 1047 687 1048 686 1048 688 1048 687 1049 688 1049 689 1049 689 1050 688 1050 690 1050 689 1051 690 1051 691 1051 691 1052 690 1052 692 1052 691 1053 692 1053 693 1053 693 1054 692 1054 694 1054 693 1055 694 1055 601 1055 680 1056 596 1056 685 1056 685 1057 596 1057 664 1057 685 1058 664 1058 686 1058 686 1059 664 1059 666 1059 686 1060 666 1060 688 1060 688 1061 666 1061 668 1061 688 1062 668 1062 690 1062 690 1063 668 1063 670 1063 690 1064 670 1064 692 1064 692 1065 670 1065 672 1065 692 1066 672 1066 694 1066 684 1067 695 1067 680 1067 680 1068 695 1068 696 1068 680 1069 696 1069 679 1069 679 1070 696 1070 612 1070 679 1071 612 1071 678 1071 678 1072 612 1072 611 1072 678 1073 611 1073 597 1073 597 1074 611 1074 697 1074 597 1075 697 1075 598 1075 598 1076 697 1076 698 1076 598 1077 698 1077 665 1077 665 1078 698 1078 699 1078 665 1079 699 1079 667 1079 667 1080 699 1080 700 1080 667 1081 700 1081 669 1081 669 1082 700 1082 701 1082 669 1083 701 1083 671 1083 671 1084 701 1084 702 1084 659 1085 637 1085 661 1085 661 1086 637 1086 635 1086 661 1087 635 1087 663 1087 663 1088 635 1088 634 1088 663 1089 634 1089 593 1089 593 1090 634 1090 674 1090 593 1091 674 1091 594 1091 594 1092 674 1092 673 1092 594 1093 673 1093 646 1093 641 1094 658 1094 639 1094 639 1095 658 1095 660 1095 639 1096 660 1096 645 1096 645 1097 660 1097 662 1097 645 1098 662 1098 650 1098 650 1099 662 1099 593 1099 650 1100 593 1100 651 1100 651 1101 593 1101 595 1101 651 1102 595 1102 609 1102 609 1103 595 1103 648 1103 609 1104 648 1104 607 1104 607 1105 648 1105 649 1105 607 1106 649 1106 608 1106 244 1107 242 1107 619 1107 619 1108 242 1108 617 1108 619 1109 617 1109 620 1109 620 1110 617 1110 687 1110 620 1111 687 1111 621 1111 621 1112 687 1112 689 1112 621 1113 689 1113 626 1113 626 1114 689 1114 691 1114 626 1115 691 1115 627 1115 627 1116 691 1116 693 1116 627 1117 693 1117 624 1117 624 1118 693 1118 601 1118 624 1119 601 1119 622 1119 622 1120 601 1120 600 1120 599 1121 601 1121 628 1121 628 1122 601 1122 694 1122 628 1123 694 1123 630 1123 630 1124 694 1124 672 1124 630 1125 672 1125 632 1125 632 1126 672 1126 671 1126 632 1127 671 1127 633 1127 633 1128 671 1128 702 1128 633 1129 702 1129 677 1129 677 1130 702 1130 701 1130 677 1131 701 1131 676 1131 676 1132 701 1132 700 1132 676 1133 700 1133 675 1133 675 1134 700 1134 699 1134 675 1135 699 1135 673 1135 673 1136 699 1136 698 1136 673 1137 698 1137 646 1137 646 1138 698 1138 697 1138 646 1139 697 1139 647 1139 647 1140 697 1140 611 1140 647 1141 611 1141 649 1141 649 1142 611 1142 613 1142 649 1143 613 1143 608 1143 703 1144 704 1144 705 1144 612 1145 706 1145 613 1145 613 1146 706 1146 707 1146 613 1147 707 1147 608 1147 608 1148 708 1148 610 1148 610 1149 708 1149 709 1149 610 1150 709 1150 606 1150 606 1151 709 1151 710 1151 606 1152 710 1152 603 1152 603 1153 710 1153 711 1153 603 1154 711 1154 604 1154 315 1155 317 1155 712 1155 712 1156 713 1156 315 1156 315 1157 713 1157 714 1157 315 1158 714 1158 303 1158 303 1159 714 1159 715 1159 303 1160 715 1160 304 1160 304 1161 715 1161 716 1161 304 1162 716 1162 415 1162 415 1163 716 1163 717 1163 415 1164 717 1164 407 1164 407 1165 717 1165 408 1165 408 1166 717 1166 718 1166 408 1167 718 1167 314 1167 314 1168 718 1168 312 1168 312 1169 718 1169 719 1169 312 1170 719 1170 376 1170 379 1171 377 1171 720 1171 720 1172 377 1172 376 1172 379 1173 720 1173 721 1173 379 1174 721 1174 309 1174 309 1175 721 1175 308 1175 308 1176 721 1176 722 1176 308 1177 722 1177 354 1177 348 1178 347 1178 723 1178 723 1179 347 1179 346 1179 346 1180 344 1180 723 1180 723 1181 344 1181 353 1181 723 1182 353 1182 722 1182 722 1183 353 1183 351 1183 722 1184 351 1184 354 1184 348 1185 723 1185 297 1185 297 1186 723 1186 724 1186 297 1187 724 1187 298 1187 298 1188 724 1188 281 1188 298 1189 281 1189 157 1189 262 1190 261 1190 725 1190 725 1191 261 1191 275 1191 726 1192 272 1192 262 1192 727 1193 273 1193 272 1193 728 1194 265 1194 266 1194 706 1195 729 1195 707 1195 707 1196 729 1196 730 1196 707 1197 730 1197 608 1197 608 1198 730 1198 731 1198 608 1199 731 1199 708 1199 376 1200 719 1200 720 1200 720 1201 719 1201 732 1201 720 1202 732 1202 721 1202 721 1203 732 1203 733 1203 721 1204 733 1204 722 1204 712 1205 734 1205 713 1205 713 1206 734 1206 735 1206 713 1207 735 1207 714 1207 714 1208 735 1208 736 1208 714 1209 736 1209 715 1209 715 1210 736 1210 737 1210 715 1211 737 1211 716 1211 716 1212 737 1212 738 1212 716 1213 738 1213 717 1213 717 1214 738 1214 739 1214 717 1215 739 1215 718 1215 718 1216 739 1216 740 1216 718 1217 740 1217 719 1217 719 1218 740 1218 741 1218 719 1219 741 1219 732 1219 732 1220 741 1220 742 1220 732 1221 742 1221 733 1221 743 1222 744 1222 745 1222 745 1223 744 1223 746 1223 745 1224 746 1224 747 1224 747 1225 746 1225 748 1225 747 1226 748 1226 749 1226 749 1227 748 1227 750 1227 749 1228 750 1228 751 1228 751 1229 750 1229 752 1229 751 1230 752 1230 753 1230 753 1231 752 1231 277 1231 753 1232 277 1232 279 1232 740 1233 743 1233 741 1233 741 1234 743 1234 745 1234 741 1235 745 1235 742 1235 742 1236 745 1236 747 1236 742 1237 747 1237 733 1237 733 1238 747 1238 749 1238 733 1239 749 1239 722 1239 722 1240 749 1240 751 1240 722 1241 751 1241 723 1241 723 1242 751 1242 753 1242 723 1243 753 1243 724 1243 724 1244 753 1244 279 1244 724 1245 279 1245 281 1245 734 1246 754 1246 735 1246 735 1247 754 1247 755 1247 735 1248 755 1248 736 1248 736 1249 755 1249 756 1249 736 1250 756 1250 737 1250 737 1251 756 1251 757 1251 737 1252 757 1252 738 1252 738 1253 757 1253 758 1253 738 1254 758 1254 739 1254 739 1255 758 1255 759 1255 739 1256 759 1256 740 1256 740 1257 759 1257 760 1257 740 1258 760 1258 743 1258 743 1259 760 1259 761 1259 743 1260 761 1260 744 1260 760 1261 762 1261 761 1261 761 1262 762 1262 763 1262 761 1263 763 1263 744 1263 744 1264 763 1264 764 1264 744 1265 764 1265 746 1265 746 1266 764 1266 765 1266 746 1267 765 1267 748 1267 748 1268 765 1268 766 1268 748 1269 766 1269 750 1269 750 1270 766 1270 725 1270 750 1271 725 1271 752 1271 752 1272 725 1272 275 1272 752 1273 275 1273 277 1273 754 1274 767 1274 755 1274 755 1275 767 1275 768 1275 755 1276 768 1276 756 1276 756 1277 768 1277 769 1277 756 1278 769 1278 757 1278 757 1279 769 1279 770 1279 757 1280 770 1280 758 1280 758 1281 770 1281 771 1281 758 1282 771 1282 759 1282 759 1283 771 1283 772 1283 759 1284 772 1284 760 1284 760 1285 772 1285 773 1285 760 1286 773 1286 762 1286 703 1287 705 1287 774 1287 774 1288 705 1288 775 1288 774 1289 775 1289 776 1289 776 1290 775 1290 777 1290 776 1291 777 1291 778 1291 778 1292 777 1292 779 1292 778 1293 779 1293 780 1293 780 1294 779 1294 781 1294 780 1295 781 1295 727 1295 272 1296 726 1296 727 1296 727 1297 726 1297 782 1297 727 1298 782 1298 780 1298 780 1299 782 1299 783 1299 780 1300 783 1300 778 1300 778 1301 783 1301 784 1301 778 1302 784 1302 776 1302 776 1303 784 1303 785 1303 776 1304 785 1304 774 1304 774 1305 785 1305 786 1305 774 1306 786 1306 703 1306 729 1307 773 1307 730 1307 730 1308 773 1308 772 1308 730 1309 772 1309 731 1309 731 1310 772 1310 771 1310 731 1311 771 1311 708 1311 708 1312 771 1312 770 1312 708 1313 770 1313 709 1313 709 1314 770 1314 769 1314 709 1315 769 1315 710 1315 710 1316 769 1316 768 1316 710 1317 768 1317 711 1317 711 1318 768 1318 767 1318 787 1319 788 1319 789 1319 789 1320 788 1320 728 1320 789 1321 728 1321 790 1321 790 1322 728 1322 266 1322 791 1323 787 1323 792 1323 792 1324 787 1324 789 1324 792 1325 789 1325 793 1325 793 1326 789 1326 790 1326 793 1327 790 1327 794 1327 794 1328 790 1328 266 1328 794 1329 266 1329 268 1329 273 1330 727 1330 274 1330 274 1331 727 1331 781 1331 274 1332 781 1332 268 1332 268 1333 781 1333 779 1333 268 1334 779 1334 794 1334 794 1335 779 1335 777 1335 794 1336 777 1336 793 1336 793 1337 777 1337 775 1337 793 1338 775 1338 792 1338 792 1339 775 1339 705 1339 792 1340 705 1340 791 1340 791 1341 705 1341 704 1341 791 1342 704 1342 795 1342 262 1343 725 1343 726 1343 726 1344 725 1344 766 1344 726 1345 766 1345 782 1345 782 1346 766 1346 765 1346 782 1347 765 1347 783 1347 783 1348 765 1348 764 1348 783 1349 764 1349 784 1349 784 1350 764 1350 763 1350 784 1351 763 1351 785 1351 785 1352 763 1352 762 1352 785 1353 762 1353 786 1353 786 1354 762 1354 773 1354 786 1355 773 1355 703 1355 703 1356 773 1356 729 1356 703 1357 729 1357 704 1357 704 1358 729 1358 706 1358 704 1359 706 1359 795 1359 795 1360 706 1360 612 1360 795 1361 612 1361 791 1361 791 1362 612 1362 696 1362 791 1363 696 1363 787 1363 787 1364 696 1364 695 1364 787 1365 695 1365 788 1365 788 1366 695 1366 684 1366 788 1367 684 1367 728 1367 728 1368 684 1368 683 1368 728 1369 683 1369 265 1369 265 1370 683 1370 616 1370 265 1371 616 1371 236 1371 434 1372 433 1372 796 1372 426 1373 140 1373 443 1373 591 1374 592 1374 797 1374 798 1375 799 1375 800 1375 590 1376 591 1376 801 1376 801 1377 591 1377 797 1377 801 1378 797 1378 802 1378 802 1379 797 1379 798 1379 802 1380 798 1380 803 1380 803 1381 798 1381 800 1381 804 1382 429 1382 428 1382 428 1383 427 1383 805 1383 805 1384 427 1384 426 1384 428 1385 805 1385 804 1385 804 1386 805 1386 806 1386 804 1387 806 1387 807 1387 807 1388 806 1388 808 1388 807 1389 808 1389 809 1389 592 1390 425 1390 797 1390 797 1391 425 1391 430 1391 797 1392 430 1392 798 1392 798 1393 430 1393 431 1393 798 1394 431 1394 799 1394 434 1395 796 1395 435 1395 443 1396 438 1396 810 1396 810 1397 438 1397 436 1397 810 1398 436 1398 811 1398 811 1399 436 1399 435 1399 426 1400 443 1400 805 1400 805 1401 443 1401 810 1401 805 1402 810 1402 806 1402 806 1403 810 1403 811 1403 806 1404 811 1404 808 1404 435 1405 796 1405 811 1405 811 1406 796 1406 812 1406 811 1407 812 1407 808 1407 808 1408 812 1408 813 1408 808 1409 813 1409 809 1409 809 1410 813 1410 800 1410 809 1411 800 1411 807 1411 807 1412 800 1412 799 1412 807 1413 799 1413 804 1413 804 1414 799 1414 431 1414 804 1415 431 1415 429 1415 444 1416 445 1416 814 1416 446 1417 455 1417 815 1417 815 1418 455 1418 457 1418 454 1419 447 1419 816 1419 816 1420 447 1420 446 1420 817 1421 453 1421 454 1421 445 1422 141 1422 818 1422 819 1423 441 1423 442 1423 432 1424 437 1424 820 1424 820 1425 437 1425 439 1425 821 1426 433 1426 432 1426 454 1427 816 1427 817 1427 817 1428 816 1428 822 1428 817 1429 822 1429 823 1429 823 1430 822 1430 824 1430 823 1431 824 1431 825 1431 825 1432 824 1432 826 1432 825 1433 826 1433 827 1433 827 1434 826 1434 828 1434 827 1435 828 1435 829 1435 829 1436 828 1436 830 1436 829 1437 830 1437 831 1437 831 1438 830 1438 819 1438 831 1439 819 1439 814 1439 814 1440 819 1440 442 1440 814 1441 442 1441 444 1441 446 1442 815 1442 816 1442 816 1443 815 1443 832 1443 816 1444 832 1444 822 1444 822 1445 832 1445 833 1445 822 1446 833 1446 824 1446 824 1447 833 1447 834 1447 824 1448 834 1448 826 1448 826 1449 834 1449 835 1449 826 1450 835 1450 828 1450 828 1451 835 1451 836 1451 828 1452 836 1452 830 1452 830 1453 836 1453 820 1453 830 1454 820 1454 819 1454 819 1455 820 1455 439 1455 819 1456 439 1456 441 1456 432 1457 820 1457 821 1457 821 1458 820 1458 836 1458 821 1459 836 1459 837 1459 837 1460 836 1460 835 1460 837 1461 835 1461 838 1461 838 1462 835 1462 834 1462 838 1463 834 1463 839 1463 839 1464 834 1464 833 1464 839 1465 833 1465 840 1465 840 1466 833 1466 832 1466 840 1467 832 1467 841 1467 841 1468 832 1468 815 1468 841 1469 815 1469 842 1469 842 1470 815 1470 457 1470 842 1471 457 1471 459 1471 843 1472 450 1472 449 1472 445 1473 818 1473 814 1473 814 1474 818 1474 844 1474 814 1475 844 1475 831 1475 831 1476 844 1476 845 1476 831 1477 845 1477 829 1477 829 1478 845 1478 846 1478 829 1479 846 1479 827 1479 827 1480 846 1480 847 1480 827 1481 847 1481 825 1481 825 1482 847 1482 848 1482 825 1483 848 1483 823 1483 823 1484 848 1484 843 1484 823 1485 843 1485 817 1485 817 1486 843 1486 449 1486 817 1487 449 1487 453 1487 459 1488 458 1488 849 1488 849 1489 458 1489 850 1489 849 1490 850 1490 851 1490 852 1491 853 1491 850 1491 850 1492 853 1492 854 1492 850 1493 854 1493 851 1493 461 1494 460 1494 852 1494 852 1495 460 1495 855 1495 855 1496 856 1496 852 1496 852 1497 856 1497 857 1497 852 1498 857 1498 853 1498 858 1499 859 1499 860 1499 861 1500 862 1500 863 1500 633 1501 864 1501 865 1501 633 1502 866 1502 867 1502 868 1503 866 1503 633 1503 860 1504 859 1504 633 1504 633 1505 869 1505 870 1505 871 1506 869 1506 633 1506 633 1507 872 1507 873 1507 874 1508 872 1508 633 1508 870 1509 874 1509 633 1509 863 1510 862 1510 633 1510 875 1511 876 1511 877 1511 877 1512 876 1512 878 1512 879 1513 880 1513 881 1513 881 1514 880 1514 882 1514 464 1515 883 1515 462 1515 600 1516 599 1516 884 1516 884 1517 599 1517 629 1517 884 1518 629 1518 885 1518 885 1519 629 1519 631 1519 885 1520 631 1520 633 1520 886 1521 468 1521 887 1521 887 1522 468 1522 256 1522 887 1523 256 1523 625 1523 623 1524 622 1524 888 1524 889 1525 472 1525 886 1525 886 1526 472 1526 470 1526 886 1527 470 1527 468 1527 890 1528 883 1528 891 1528 891 1529 883 1529 464 1529 891 1530 464 1530 889 1530 889 1531 464 1531 466 1531 889 1532 466 1532 472 1532 892 1533 893 1533 894 1533 895 1534 896 1534 897 1534 892 1535 898 1535 893 1535 893 1536 898 1536 895 1536 893 1537 895 1537 899 1537 899 1538 895 1538 897 1538 899 1539 897 1539 900 1539 900 1540 897 1540 901 1540 902 1541 658 1541 903 1541 903 1542 658 1542 641 1542 903 1543 641 1543 904 1543 633 1544 638 1544 905 1544 905 1545 638 1545 637 1545 905 1546 637 1546 902 1546 902 1547 637 1547 659 1547 902 1548 659 1548 658 1548 622 1549 600 1549 888 1549 888 1550 600 1550 884 1550 888 1551 884 1551 861 1551 861 1552 884 1552 885 1552 861 1553 885 1553 862 1553 862 1554 885 1554 633 1554 906 1555 873 1555 907 1555 907 1556 873 1556 872 1556 907 1557 872 1557 908 1557 908 1558 872 1558 874 1558 908 1559 874 1559 909 1559 909 1560 874 1560 870 1560 909 1561 870 1561 910 1561 910 1562 870 1562 869 1562 910 1563 869 1563 911 1563 911 1564 869 1564 871 1564 911 1565 871 1565 912 1565 868 1566 913 1566 866 1566 866 1567 913 1567 914 1567 866 1568 914 1568 867 1568 867 1569 914 1569 915 1569 892 1570 916 1570 898 1570 898 1571 916 1571 865 1571 898 1572 865 1572 895 1572 895 1573 865 1573 864 1573 895 1574 864 1574 896 1574 916 1575 633 1575 865 1575 910 1576 917 1576 909 1576 909 1577 917 1577 918 1577 909 1578 918 1578 908 1578 908 1579 918 1579 919 1579 908 1580 919 1580 907 1580 907 1581 919 1581 920 1581 907 1582 920 1582 906 1582 906 1583 920 1583 921 1583 858 1584 912 1584 859 1584 859 1585 912 1585 871 1585 859 1586 871 1586 633 1586 641 1587 642 1587 904 1587 904 1588 642 1588 901 1588 904 1589 901 1589 903 1589 903 1590 901 1590 897 1590 903 1591 897 1591 902 1591 902 1592 897 1592 896 1592 902 1593 896 1593 905 1593 905 1594 896 1594 864 1594 905 1595 864 1595 633 1595 922 1596 915 1596 923 1596 923 1597 915 1597 914 1597 923 1598 914 1598 894 1598 894 1599 914 1599 913 1599 894 1600 913 1600 892 1600 892 1601 913 1601 868 1601 892 1602 868 1602 916 1602 916 1603 868 1603 633 1603 887 1604 921 1604 886 1604 886 1605 921 1605 920 1605 886 1606 920 1606 889 1606 889 1607 920 1607 919 1607 889 1608 919 1608 891 1608 891 1609 919 1609 918 1609 891 1610 918 1610 890 1610 890 1611 918 1611 917 1611 890 1612 917 1612 924 1612 625 1613 623 1613 887 1613 887 1614 623 1614 888 1614 887 1615 888 1615 921 1615 921 1616 888 1616 861 1616 921 1617 861 1617 906 1617 906 1618 861 1618 863 1618 906 1619 863 1619 873 1619 873 1620 863 1620 633 1620 460 1621 462 1621 882 1621 882 1622 462 1622 883 1622 882 1623 883 1623 881 1623 881 1624 883 1624 890 1624 881 1625 890 1625 879 1625 879 1626 890 1626 924 1626 879 1627 924 1627 878 1627 878 1628 924 1628 917 1628 878 1629 917 1629 877 1629 877 1630 917 1630 910 1630 877 1631 910 1631 875 1631 875 1632 910 1632 911 1632 875 1633 911 1633 925 1633 925 1634 911 1634 912 1634 925 1635 912 1635 922 1635 922 1636 912 1636 858 1636 922 1637 858 1637 915 1637 915 1638 858 1638 860 1638 915 1639 860 1639 867 1639 867 1640 860 1640 633 1640 712 1641 317 1641 514 1641 754 1642 734 1642 926 1642 926 1643 642 1643 754 1643 754 1644 642 1644 640 1644 754 1645 640 1645 767 1645 767 1646 640 1646 643 1646 767 1647 643 1647 711 1647 682 1648 681 1648 643 1648 643 1649 681 1649 604 1649 643 1650 604 1650 711 1650 734 1651 712 1651 926 1651 926 1652 712 1652 514 1652 926 1653 514 1653 927 1653 927 1654 514 1654 482 1654 927 1655 482 1655 928 1655 482 1656 481 1656 928 1656 928 1657 481 1657 589 1657 928 1658 589 1658 929 1658 929 1659 589 1659 479 1659 929 1660 479 1660 930 1660 930 1661 479 1661 478 1661 930 1662 478 1662 931 1662 931 1663 478 1663 484 1663 931 1664 484 1664 932 1664 207 1665 590 1665 485 1665 485 1666 590 1666 933 1666 485 1667 933 1667 475 1667 475 1668 933 1668 932 1668 475 1669 932 1669 476 1669 476 1670 932 1670 484 1670 930 1671 931 1671 934 1671 935 1672 936 1672 875 1672 875 1673 936 1673 876 1673 876 1674 936 1674 937 1674 876 1675 937 1675 878 1675 878 1676 937 1676 938 1676 878 1677 938 1677 879 1677 879 1678 938 1678 939 1678 879 1679 939 1679 880 1679 939 1680 940 1680 880 1680 880 1681 940 1681 941 1681 880 1682 941 1682 882 1682 882 1683 941 1683 855 1683 882 1684 855 1684 460 1684 942 1685 842 1685 849 1685 849 1686 842 1686 459 1686 942 1687 943 1687 842 1687 842 1688 943 1688 944 1688 842 1689 944 1689 841 1689 841 1690 944 1690 945 1690 841 1691 945 1691 840 1691 840 1692 945 1692 946 1692 840 1693 946 1693 839 1693 839 1694 946 1694 947 1694 839 1695 947 1695 838 1695 838 1696 947 1696 948 1696 838 1697 948 1697 837 1697 837 1698 948 1698 949 1698 837 1699 949 1699 821 1699 950 1700 433 1700 951 1700 951 1701 433 1701 821 1701 951 1702 821 1702 952 1702 952 1703 821 1703 949 1703 813 1704 812 1704 950 1704 950 1705 812 1705 796 1705 950 1706 796 1706 433 1706 950 1707 953 1707 813 1707 813 1708 953 1708 954 1708 813 1709 954 1709 800 1709 800 1710 954 1710 803 1710 954 1711 955 1711 803 1711 803 1712 955 1712 956 1712 803 1713 956 1713 802 1713 933 1714 590 1714 956 1714 956 1715 590 1715 801 1715 956 1716 801 1716 802 1716 901 1717 642 1717 926 1717 926 1718 957 1718 901 1718 901 1719 957 1719 958 1719 901 1720 958 1720 900 1720 875 1721 925 1721 935 1721 935 1722 925 1722 922 1722 935 1723 922 1723 959 1723 959 1724 922 1724 923 1724 959 1725 923 1725 960 1725 960 1726 923 1726 894 1726 960 1727 894 1727 961 1727 961 1728 894 1728 893 1728 961 1729 893 1729 962 1729 962 1730 893 1730 899 1730 962 1731 899 1731 963 1731 963 1732 899 1732 900 1732 963 1733 900 1733 964 1733 964 1734 900 1734 958 1734 853 1735 857 1735 965 1735 965 1736 857 1736 966 1736 965 1737 966 1737 967 1737 967 1738 966 1738 968 1738 967 1739 968 1739 969 1739 969 1740 968 1740 970 1740 969 1741 970 1741 971 1741 971 1742 970 1742 972 1742 971 1743 972 1743 973 1743 973 1744 972 1744 974 1744 973 1745 974 1745 975 1745 975 1746 974 1746 976 1746 975 1747 976 1747 977 1747 977 1748 976 1748 978 1748 977 1749 978 1749 979 1749 979 1750 978 1750 980 1750 979 1751 980 1751 981 1751 981 1752 980 1752 982 1752 981 1753 982 1753 983 1753 983 1754 982 1754 984 1754 983 1755 984 1755 985 1755 985 1756 984 1756 986 1756 985 1757 986 1757 987 1757 987 1758 986 1758 988 1758 987 1759 988 1759 989 1759 989 1760 988 1760 990 1760 989 1761 990 1761 991 1761 991 1762 990 1762 992 1762 991 1763 992 1763 993 1763 993 1764 992 1764 994 1764 993 1765 994 1765 929 1765 929 1766 994 1766 928 1766 857 1767 856 1767 966 1767 966 1768 856 1768 995 1768 966 1769 995 1769 968 1769 968 1770 995 1770 996 1770 968 1771 996 1771 970 1771 970 1772 996 1772 997 1772 970 1773 997 1773 972 1773 972 1774 997 1774 998 1774 972 1775 998 1775 974 1775 974 1776 998 1776 999 1776 974 1777 999 1777 976 1777 976 1778 999 1778 1000 1778 976 1779 1000 1779 978 1779 978 1780 1000 1780 1001 1780 978 1781 1001 1781 980 1781 980 1782 1001 1782 1002 1782 980 1783 1002 1783 982 1783 982 1784 1002 1784 1003 1784 982 1785 1003 1785 984 1785 984 1786 1003 1786 1004 1786 984 1787 1004 1787 986 1787 986 1788 1004 1788 1005 1788 986 1789 1005 1789 988 1789 988 1790 1005 1790 1006 1790 988 1791 1006 1791 990 1791 990 1792 1006 1792 1007 1792 990 1793 1007 1793 992 1793 992 1794 1007 1794 1008 1794 992 1795 1008 1795 994 1795 994 1796 1008 1796 1009 1796 994 1797 1009 1797 928 1797 928 1798 1009 1798 927 1798 856 1799 855 1799 995 1799 995 1800 855 1800 941 1800 995 1801 941 1801 996 1801 996 1802 941 1802 940 1802 996 1803 940 1803 997 1803 997 1804 940 1804 939 1804 997 1805 939 1805 998 1805 998 1806 939 1806 938 1806 998 1807 938 1807 999 1807 999 1808 938 1808 937 1808 999 1809 937 1809 1000 1809 1000 1810 937 1810 936 1810 1000 1811 936 1811 1001 1811 1001 1812 936 1812 935 1812 1001 1813 935 1813 1002 1813 1002 1814 935 1814 959 1814 1002 1815 959 1815 1003 1815 1003 1816 959 1816 960 1816 1003 1817 960 1817 1004 1817 1004 1818 960 1818 961 1818 1004 1819 961 1819 1005 1819 1005 1820 961 1820 962 1820 1005 1821 962 1821 1006 1821 1006 1822 962 1822 963 1822 1006 1823 963 1823 1007 1823 1007 1824 963 1824 964 1824 1007 1825 964 1825 1008 1825 1008 1826 964 1826 958 1826 1008 1827 958 1827 1009 1827 1009 1828 958 1828 957 1828 1009 1829 957 1829 927 1829 927 1830 957 1830 926 1830 851 1831 854 1831 1010 1831 1010 1832 854 1832 1011 1832 1010 1833 1011 1833 1012 1833 1012 1834 1011 1834 1013 1834 1012 1835 1013 1835 1014 1835 1014 1836 1013 1836 1015 1836 1014 1837 1015 1837 1016 1837 1016 1838 1015 1838 1017 1838 1016 1839 1017 1839 1018 1839 1018 1840 1017 1840 1019 1840 1018 1841 1019 1841 1020 1841 1020 1842 1019 1842 1021 1842 1020 1843 1021 1843 1022 1843 1022 1844 1021 1844 1023 1844 1022 1845 1023 1845 1024 1845 1024 1846 1023 1846 1025 1846 1024 1847 1025 1847 1026 1847 1026 1848 1025 1848 1027 1848 1026 1849 1027 1849 1028 1849 1028 1850 1027 1850 1029 1850 1028 1851 1029 1851 1030 1851 1030 1852 1029 1852 1031 1852 1030 1853 1031 1853 1032 1853 1032 1854 1031 1854 1033 1854 1032 1855 1033 1855 1034 1855 1034 1856 1033 1856 1035 1856 1034 1857 1035 1857 1036 1857 1036 1858 1035 1858 1037 1858 1036 1859 1037 1859 1038 1859 1038 1860 1037 1860 934 1860 1038 1861 934 1861 932 1861 932 1862 934 1862 931 1862 849 1863 851 1863 942 1863 942 1864 851 1864 1010 1864 942 1865 1010 1865 943 1865 943 1866 1010 1866 1012 1866 943 1867 1012 1867 944 1867 944 1868 1012 1868 1014 1868 944 1869 1014 1869 945 1869 945 1870 1014 1870 1016 1870 945 1871 1016 1871 946 1871 946 1872 1016 1872 1018 1872 946 1873 1018 1873 947 1873 947 1874 1018 1874 1020 1874 947 1875 1020 1875 948 1875 948 1876 1020 1876 1022 1876 948 1877 1022 1877 949 1877 949 1878 1022 1878 1024 1878 949 1879 1024 1879 952 1879 952 1880 1024 1880 1026 1880 952 1881 1026 1881 951 1881 951 1882 1026 1882 1028 1882 951 1883 1028 1883 950 1883 950 1884 1028 1884 1030 1884 950 1885 1030 1885 953 1885 953 1886 1030 1886 1032 1886 953 1887 1032 1887 954 1887 954 1888 1032 1888 1034 1888 954 1889 1034 1889 955 1889 955 1890 1034 1890 1036 1890 955 1891 1036 1891 956 1891 956 1892 1036 1892 1038 1892 956 1893 1038 1893 933 1893 933 1894 1038 1894 932 1894 854 1895 853 1895 1011 1895 1011 1896 853 1896 965 1896 1011 1897 965 1897 1013 1897 1013 1898 965 1898 967 1898 1013 1899 967 1899 1015 1899 1015 1900 967 1900 969 1900 1015 1901 969 1901 1017 1901 1017 1902 969 1902 971 1902 1017 1903 971 1903 1019 1903 1019 1904 971 1904 973 1904 1019 1905 973 1905 1021 1905 1021 1906 973 1906 975 1906 1021 1907 975 1907 1023 1907 1023 1908 975 1908 977 1908 1023 1909 977 1909 1025 1909 1025 1910 977 1910 979 1910 1025 1911 979 1911 1027 1911 1027 1912 979 1912 981 1912 1027 1913 981 1913 1029 1913 1029 1914 981 1914 983 1914 1029 1915 983 1915 1031 1915 1031 1916 983 1916 985 1916 1031 1917 985 1917 1033 1917 1033 1918 985 1918 987 1918 1033 1919 987 1919 1035 1919 1035 1920 987 1920 989 1920 1035 1921 989 1921 1037 1921 1037 1922 989 1922 991 1922 1037 1923 991 1923 934 1923 934 1924 991 1924 993 1924 934 1925 993 1925 930 1925 930 1926 993 1926 929 1926 1039 1927 1040 1927 1041 1927 1041 1928 1040 1928 1042 1928 1043 1928 1044 1928 1045 1928 1045 1927 1044 1927 1046 1927 1039 1929 1041 1929 1047 1929 1047 1930 1041 1930 1048 1930 1047 1931 1048 1931 1049 1931 1047 0 1049 0 1039 0 1039 0 1049 0 1050 0 1039 0 1050 0 1040 0 1043 0 1051 0 1044 0 1044 0 1051 0 1052 0 1044 1932 1052 1932 1053 1932 1046 1933 1044 1933 1054 1933 1054 1934 1044 1934 1053 1934 1054 1935 1053 1936 1052 1937 1055 0 1056 0 1057 0 1058 0 1059 0 1060 0 1061 0 1062 0 1063 0 1060 0 1059 0 1064 0 1063 0 1062 0 1065 0 1057 1938 1056 1938 1066 1938 1067 1939 1068 1939 1069 1939 1062 0 1070 0 1065 0 1065 0 1070 0 1071 0 1065 0 1071 0 1072 0 1072 0 1071 0 1073 0 1072 0 1073 0 1057 0 1057 0 1073 0 1074 0 1057 0 1074 0 1055 0 1075 0 1076 0 1077 0 1078 0 1079 0 1080 0 1080 1940 1081 1940 1078 1940 1078 0 1081 0 1082 0 1078 0 1082 0 1076 0 1076 1941 1082 1941 1083 1941 1076 0 1083 0 1077 0 1084 0 1085 0 1086 0 1087 0 1088 0 1089 0 1089 0 1088 0 1090 0 1089 0 1090 0 1091 0 1056 1942 1092 1942 1066 1942 1066 1943 1092 1943 1093 1943 1066 1944 1093 1944 1094 1944 1086 0 1085 0 1068 0 1068 0 1085 0 1095 0 1068 0 1095 0 1069 0 1063 0 1096 0 1061 0 1061 0 1096 0 1097 0 1061 0 1097 0 1098 0 1098 0 1097 0 1099 0 1098 0 1099 0 1089 0 1089 1945 1099 1945 1100 1945 1089 1946 1100 1946 1087 1946 1077 0 1101 0 1075 0 1075 0 1101 0 1102 0 1075 0 1102 0 1103 0 1103 1947 1102 1947 1066 1947 1103 1948 1066 1948 1104 1948 1104 1949 1066 1949 1094 1949 1069 0 1105 0 1067 0 1067 0 1105 0 1106 0 1067 1950 1106 1950 1107 1950 1107 0 1106 0 1108 0 1107 0 1108 0 1079 0 1079 0 1108 0 1109 0 1079 1951 1109 1951 1080 1951 1059 0 1110 0 1064 0 1064 0 1110 0 1111 0 1064 0 1111 0 1112 0 1112 0 1111 0 1113 0 1112 0 1113 0 1114 0 1114 0 1113 0 1115 0 1114 0 1115 0 1116 0 1116 0 1115 0 1117 0 1116 0 1117 0 1118 0 1119 0 1120 0 1121 0 1084 0 1086 0 1122 0 1122 0 1086 0 1123 0 1122 0 1123 0 1060 0 1060 0 1123 0 1124 0 1060 0 1124 0 1058 0 1120 1952 1125 1952 1121 1952 1121 1953 1125 1953 1126 1953 1121 0 1126 0 1127 0 1127 0 1126 0 1128 0 1127 0 1128 0 1129 0 1129 0 1128 0 1130 0 1129 0 1130 0 1131 0 1131 0 1130 0 1132 0 1131 0 1132 0 1133 0 1133 0 1132 0 1118 0 1133 0 1118 0 1134 0 1134 0 1118 0 1117 0 1135 0 1136 0 1121 0 1121 0 1136 0 1137 0 1121 0 1137 0 1119 0 1138 1954 1139 1954 1066 1954 1140 1955 1141 1955 1139 1955 1142 1956 1143 1956 1141 1956 257 1957 1143 1957 259 1957 259 1958 1143 1958 1142 1958 259 1959 1142 1959 260 1959 260 1960 1142 1960 1144 1960 260 1961 1144 1961 254 1961 254 1962 1144 1962 1145 1962 248 1963 250 1963 1145 1963 1145 1964 250 1964 252 1964 1145 1965 252 1965 254 1965 1145 1966 1146 1966 248 1966 248 1967 1146 1967 1147 1967 248 1968 1147 1968 245 1968 245 1969 1147 1969 1148 1969 1149 1970 236 1970 1150 1970 1150 1971 236 1971 238 1971 1150 1972 238 1972 1151 1972 1151 1973 238 1973 240 1973 1151 1974 240 1974 1148 1974 1148 1975 240 1975 243 1975 1148 1976 243 1976 245 1976 1066 1977 1102 1977 1138 1977 1138 1978 1102 1978 1101 1978 1138 1979 1101 1979 1152 1979 1152 1980 1101 1980 1077 1980 1152 1981 1077 1981 1153 1981 1153 1982 1077 1982 1083 1982 1153 1983 1083 1983 1154 1983 1154 1984 1083 1984 1082 1984 1154 1985 1082 1985 1155 1985 1155 1986 1082 1986 1081 1986 1155 1987 1081 1987 1156 1987 1156 1988 1081 1988 1080 1988 1156 1989 1080 1989 1157 1989 1157 1990 1080 1990 1109 1990 1157 1991 1109 1991 1158 1991 1158 1992 1109 1992 1108 1992 1158 1993 1108 1993 1159 1993 1159 1994 1108 1994 1106 1994 1159 1995 1106 1995 1160 1995 1160 1996 1106 1996 1105 1996 1160 1997 1105 1997 1161 1997 1161 1998 1105 1998 1069 1998 1161 1999 1069 1999 1162 1999 1162 2000 1069 2000 1095 2000 1162 2001 1095 2001 1163 2001 1163 2002 1095 2002 1085 2002 1163 2003 1085 2003 1164 2003 1139 2004 1138 2004 1140 2004 1140 2005 1138 2005 1152 2005 1140 2006 1152 2006 1165 2006 1165 2007 1152 2007 1153 2007 1165 2008 1153 2008 1166 2008 1166 2009 1153 2009 1154 2009 1166 2010 1154 2010 1167 2010 1167 2011 1154 2011 1155 2011 1167 2012 1155 2012 1168 2012 1168 2013 1155 2013 1156 2013 1168 2014 1156 2014 1169 2014 1169 2015 1156 2015 1157 2015 1169 2016 1157 2016 1170 2016 1170 2017 1157 2017 1158 2017 1170 2018 1158 2018 1171 2018 1171 2019 1158 2019 1159 2019 1171 2020 1159 2020 1172 2020 1172 2021 1159 2021 1160 2021 1172 2022 1160 2022 1173 2022 1173 2023 1160 2023 1161 2023 1173 2024 1161 2024 1174 2024 1174 2025 1161 2025 1162 2025 1174 2026 1162 2026 1175 2026 1175 2027 1162 2027 1163 2027 1175 2028 1163 2028 1176 2028 1176 2029 1163 2029 1164 2029 1176 2030 1164 2030 1177 2030 1141 2031 1140 2031 1142 2031 1142 2032 1140 2032 1165 2032 1142 2033 1165 2033 1144 2033 1144 2034 1165 2034 1166 2034 1144 2035 1166 2035 1145 2035 1145 2036 1166 2036 1167 2036 1145 2037 1167 2037 1146 2037 1146 2038 1167 2038 1168 2038 1146 2039 1168 2039 1147 2039 1147 2040 1168 2040 1169 2040 1147 2041 1169 2041 1148 2041 1148 2042 1169 2042 1170 2042 1148 2043 1170 2043 1151 2043 1151 2044 1170 2044 1171 2044 1151 2045 1171 2045 1150 2045 1150 2046 1171 2046 1172 2046 1150 2047 1172 2047 1149 2047 1149 2048 1172 2048 1173 2048 1149 2049 1173 2049 1178 2049 1178 2050 1173 2050 1174 2050 1178 2051 1174 2051 1179 2051 1179 2052 1174 2052 1175 2052 1179 2053 1175 2053 1180 2053 1180 2054 1175 2054 1176 2054 1180 2055 1176 2055 1181 2055 1181 2056 1176 2056 1177 2056 1181 2057 1177 2057 1182 2057 278 2058 276 2058 1182 2058 1182 2059 276 2059 263 2059 1182 2060 263 2060 1181 2060 1181 2061 263 2061 271 2061 1181 2062 271 2062 1180 2062 1180 2063 271 2063 267 2063 1180 2064 267 2064 1179 2064 1179 2065 267 2065 269 2065 1179 2066 269 2066 1178 2066 1178 2067 269 2067 270 2067 1178 2068 270 2068 1149 2068 1149 2069 270 2069 264 2069 1149 2070 264 2070 236 2070 280 2071 278 2071 1183 2071 1183 2072 278 2072 1182 2072 1183 2073 1182 2073 1184 2073 1184 2074 1182 2074 1177 2074 1184 2075 1177 2075 1185 2075 1185 2076 1177 2076 1164 2076 1185 2077 1164 2077 1084 2077 1084 2078 1164 2078 1085 2078 156 2079 280 2079 1186 2079 1186 2080 280 2080 1183 2080 1186 2081 1183 2081 1187 2081 1187 2082 1183 2082 1184 2082 1187 2083 1184 2083 1188 2083 1188 2084 1184 2084 1185 2084 1188 2085 1185 2085 1122 2085 1122 2086 1185 2086 1084 2086 1130 2087 1189 2087 1132 2087 1132 2088 1189 2088 1190 2088 1132 2089 1190 2089 1118 2089 1118 2090 1190 2090 1116 2090 1116 2091 1190 2091 1191 2091 1116 2092 1191 2092 1114 2092 1114 2093 1191 2093 1192 2093 1114 2094 1192 2094 1112 2094 1112 2095 1192 2095 1193 2095 1112 2096 1193 2096 1064 2096 1064 2097 1193 2097 1194 2097 1064 2098 1194 2098 1060 2098 1060 2099 1194 2099 1188 2099 1060 2100 1188 2100 1122 2100 154 2101 156 2101 1186 2101 1195 2102 1196 2102 1197 2102 1197 2103 1196 2103 1198 2103 1197 2104 1198 2104 1199 2104 154 2105 1200 2105 152 2105 152 2106 1200 2106 1201 2106 152 2107 1201 2107 144 2107 144 2108 1201 2108 1199 2108 144 2109 1199 2109 145 2109 145 2110 1199 2110 1198 2110 145 2111 1198 2111 148 2111 1130 2112 1195 2112 1189 2112 1189 2113 1195 2113 1202 2113 1189 2114 1202 2114 1190 2114 1190 2115 1202 2115 1203 2115 1190 2116 1203 2116 1191 2116 1191 2117 1203 2117 1204 2117 1191 2118 1204 2118 1192 2118 1192 2119 1204 2119 1205 2119 1192 2120 1205 2120 1193 2120 1193 2121 1205 2121 1206 2121 1193 2122 1206 2122 1194 2122 1194 2123 1206 2123 1187 2123 1194 2124 1187 2124 1188 2124 1195 2125 1197 2125 1202 2125 1202 2126 1197 2126 1199 2126 1202 2127 1199 2127 1203 2127 1203 2128 1199 2128 1201 2128 1203 2129 1201 2129 1204 2129 1204 2130 1201 2130 1200 2130 1204 2131 1200 2131 1205 2131 1205 2132 1200 2132 154 2132 1205 2133 154 2133 1206 2133 1206 2134 154 2134 1186 2134 1206 2135 1186 2135 1187 2135 1207 2136 1208 2136 1209 2136 1209 2137 1208 2137 1210 2137 1126 2138 1125 2138 1207 2138 1207 2139 1209 2139 1126 2139 1126 2140 1209 2140 1211 2140 1126 2141 1211 2141 1128 2141 1212 2142 1196 2142 1195 2142 162 2143 148 2143 1198 2143 125 2144 159 2144 1213 2144 1213 2145 159 2145 162 2145 1213 2146 162 2146 1212 2146 1212 2147 162 2147 1198 2147 1212 2148 1198 2148 1196 2148 1130 2149 1128 2149 1195 2149 1195 2150 1128 2150 1211 2150 1195 2151 1211 2151 1212 2151 1212 2152 1211 2152 1209 2152 1212 2153 1209 2153 1213 2153 1213 2154 1209 2154 1210 2154 1213 2155 1210 2155 125 2155 1214 2156 1215 2156 76 2156 1049 2156 1216 2156 1217 2156 450 2157 843 2157 1049 2157 1049 2158 843 2158 848 2158 1049 2159 848 2159 847 2159 1217 2156 1218 2156 1049 2156 1049 2160 1218 2160 451 2160 1049 2161 451 2161 450 2161 847 2162 846 2162 1049 2162 1049 2163 846 2163 845 2163 1049 2164 845 2164 844 2164 107 2165 1050 2165 141 2165 141 2166 1050 2166 1049 2166 141 2167 1049 2167 818 2167 818 2168 1049 2168 844 2168 23 2169 24 2169 1049 2169 1049 2156 24 2156 1219 2156 1049 2156 1219 2156 1216 2156 139 2170 1220 2170 76 2170 76 2156 1220 2156 1221 2156 76 2156 1221 2156 1214 2156 1045 2156 12 2156 1051 2156 1051 2156 12 2156 13 2156 1051 2156 13 2156 1042 2156 1042 2171 13 2171 92 2171 1042 2156 92 2156 1041 2156 1041 2156 92 2156 48 2156 1041 2172 48 2172 1048 2172 1046 2156 77 2156 1045 2156 1045 2156 77 2156 93 2156 1045 2156 93 2156 12 2156 12 2173 93 2173 16 2173 12 2156 16 2156 17 2156 1046 2156 1054 2156 77 2156 77 2174 1054 2174 1052 2174 77 2156 1052 2156 74 2156 74 2156 1052 2156 75 2156 1048 2175 48 2175 1049 2175 1049 2176 48 2176 21 2176 1049 2156 21 2156 23 2156 1042 2156 1050 2156 1051 2156 1051 2165 1050 2165 107 2165 1051 2166 107 2166 1052 2166 1052 2177 107 2177 76 2177 1052 2156 76 2156 75 2156 107 2178 169 2178 76 2178 76 2179 169 2179 168 2179 76 2180 168 2180 174 2180 174 2181 176 2181 76 2181 76 2182 176 2182 178 2182 76 2183 178 2183 180 2183 180 2184 181 2184 76 2184 76 2185 181 2185 138 2185 76 2186 138 2186 139 2186 1100 2187 1222 2187 1087 2187 1087 2188 1222 2188 1223 2188 1087 2189 1223 2189 1088 2189 1088 2190 1223 2190 1090 2190 1090 2191 1223 2191 1224 2191 1090 2192 1224 2192 1091 2192 1225 2193 1226 2193 1227 2193 1227 2194 1226 2194 1228 2194 1227 2195 1228 2195 1224 2195 1224 2196 1228 2196 1229 2196 1224 2197 1229 2197 1091 2197 1219 2198 1230 2198 1216 2198 1216 2199 1230 2199 1225 2199 1222 2200 1231 2200 1223 2200 1223 2201 1231 2201 1232 2201 1223 2202 1232 2202 1224 2202 1224 2203 1232 2203 1233 2203 1224 2204 1233 2204 1227 2204 1227 2205 1233 2205 1234 2205 1231 2206 1235 2206 1232 2206 1232 2207 1235 2207 1236 2207 1232 2208 1236 2208 1233 2208 1233 2209 1236 2209 1237 2209 1233 2210 1237 2210 1234 2210 1234 2211 1237 2211 1238 2211 1235 2212 458 2212 1236 2212 1236 2213 458 2213 456 2213 1236 2214 456 2214 1237 2214 1237 2215 456 2215 448 2215 1237 2216 448 2216 1238 2216 1238 2217 448 2217 452 2217 1238 2218 452 2218 451 2218 1225 2219 1227 2219 1216 2219 1216 2220 1227 2220 1234 2220 1216 2221 1234 2221 1217 2221 1217 2222 1234 2222 1238 2222 1217 2223 1238 2223 1218 2223 1218 2224 1238 2224 451 2224 1239 2225 1240 2225 1241 2225 1136 2226 1242 2226 1137 2226 1137 2227 1242 2227 1243 2227 1137 2228 1243 2228 1119 2228 1119 2229 1243 2229 1120 2229 1120 2230 1243 2230 1207 2230 1120 2231 1207 2231 1125 2231 125 2232 1210 2232 127 2232 127 2233 1210 2233 1244 2233 1241 2234 1240 2234 1214 2234 1214 2235 1240 2235 1245 2235 1214 2236 1245 2236 1215 2236 1136 2237 1135 2237 1242 2237 1242 2238 1135 2238 1246 2238 1242 2239 1246 2239 1241 2239 1241 2240 1246 2240 1247 2240 1241 2241 1247 2241 1239 2241 139 2242 137 2242 1220 2242 1220 2243 137 2243 136 2243 1220 2244 136 2244 1248 2244 1248 2245 136 2245 1249 2245 1248 2246 1249 2246 1250 2246 1250 2247 1249 2247 130 2247 1250 2248 130 2248 1244 2248 1244 2249 130 2249 1251 2249 1244 2250 1251 2250 127 2250 1210 2251 1208 2251 1244 2251 1244 2252 1208 2252 1252 2252 1244 2253 1252 2253 1250 2253 1250 2254 1252 2254 1253 2254 1250 2255 1253 2255 1248 2255 1248 2256 1253 2256 1254 2256 1248 2257 1254 2257 1220 2257 1220 2258 1254 2258 1221 2258 1208 2259 1207 2259 1252 2259 1252 2260 1207 2260 1243 2260 1252 2261 1243 2261 1253 2261 1253 2262 1243 2262 1242 2262 1253 2263 1242 2263 1254 2263 1254 2264 1242 2264 1241 2264 1254 2265 1241 2265 1221 2265 1221 2266 1241 2266 1214 2266 1100 2267 1099 2267 1255 2267 1100 2268 1255 2268 1222 2268 1222 2269 1255 2269 1256 2269 1222 2270 1256 2270 1231 2270 1231 2271 1256 2271 1257 2271 1231 2272 1257 2272 1235 2272 461 2273 852 2273 1257 2273 1257 2274 852 2274 850 2274 1257 2275 850 2275 1235 2275 1235 2276 850 2276 458 2276 461 2277 1257 2277 1258 2277 1258 2278 1257 2278 1256 2278 1258 2279 1256 2279 1259 2279 1259 2280 1256 2280 1255 2280 1259 2281 1255 2281 1260 2281 1260 2282 1255 2282 1099 2282 1260 2283 1099 2283 1097 2283 1143 2284 1261 2284 1141 2284 463 2285 1262 2285 1263 2285 1057 2286 1264 2286 1265 2286 1266 2287 1267 2287 1072 2287 1072 2288 1267 2288 1268 2288 1072 2289 1268 2289 1065 2289 1065 2290 1268 2290 1269 2290 1065 2291 1269 2291 1063 2291 1269 2292 1270 2292 1063 2292 1063 2293 1270 2293 1271 2293 1063 2294 1271 2294 1096 2294 1096 2295 1271 2295 1260 2295 1096 2296 1260 2296 1097 2296 1259 2297 1262 2297 1258 2297 1258 2298 1262 2298 463 2298 1258 2299 463 2299 461 2299 1272 2300 1273 2300 465 2300 465 2301 1273 2301 474 2301 474 2302 1273 2302 473 2302 473 2303 1273 2303 1274 2303 473 2304 1274 2304 471 2304 1261 2305 1143 2305 1275 2305 471 2306 1274 2306 469 2306 469 2307 1274 2307 1275 2307 469 2308 1275 2308 467 2308 467 2309 1275 2309 1143 2309 467 2310 1143 2310 257 2310 1057 2311 1066 2311 1264 2311 1264 2312 1066 2312 1139 2312 1264 2313 1139 2313 1265 2313 465 2314 463 2314 1272 2314 1272 2315 463 2315 1263 2315 1272 2316 1263 2316 1273 2316 1273 2317 1263 2317 1276 2317 1273 2318 1276 2318 1274 2318 1274 2319 1276 2319 1277 2319 1274 2320 1277 2320 1275 2320 1275 2321 1277 2321 1278 2321 1275 2322 1278 2322 1261 2322 1261 2323 1278 2323 1265 2323 1261 2324 1265 2324 1141 2324 1141 2325 1265 2325 1139 2325 1259 2326 1260 2326 1262 2326 1262 2327 1260 2327 1271 2327 1262 2328 1271 2328 1263 2328 1263 2329 1271 2329 1270 2329 1263 2330 1270 2330 1276 2330 1276 2331 1270 2331 1269 2331 1276 2332 1269 2332 1277 2332 1277 2333 1269 2333 1268 2333 1277 2334 1268 2334 1278 2334 1278 2335 1268 2335 1267 2335 1278 2336 1267 2336 1265 2336 1265 2337 1267 2337 1266 2337 1265 2338 1266 2338 1057 2338 1057 2339 1266 2339 1072 2339 1042 5 1040 5 1050 5 1043 4 1045 4 1051 4 1228 48 1279 48 1229 48 1229 48 1279 48 1091 48 24 48 30 48 1219 48 1219 2340 30 2340 29 2340 29 48 28 48 1219 48 1219 48 28 48 26 48 1219 48 26 48 1230 48 1228 48 1226 48 1279 48 1279 48 1226 48 1225 48 1279 48 1225 48 1280 48 1280 48 1225 48 1230 48 1280 48 1230 48 25 48 25 48 1230 48 26 48 1240 48 1239 48 1281 48 1240 48 1281 48 1245 48 1239 48 1247 48 1281 48 1281 48 1247 48 1246 48 1281 48 1246 48 1135 48 1281 48 1282 48 1245 48 1245 48 1282 48 58 48 1245 48 58 48 1215 48 1215 48 58 48 57 48 1215 48 57 48 55 48 55 48 54 48 1215 48 1215 2341 54 2341 72 2341 1215 48 72 48 76 48 1283 2342 1284 2342 1285 2342 1285 2343 1284 2343 1286 2343 1285 2344 1286 2344 1287 2344 1287 2345 1286 2345 1288 2345 1286 2346 1289 2346 1288 2346 1288 2347 1289 2347 1290 2347 1288 2348 1290 2348 1291 2348 1291 2349 1290 2349 1292 2349 1291 2350 1292 2350 1293 2350 1293 2351 1292 2351 1294 2351 1294 2352 1292 2352 1295 2352 1294 2353 1295 2353 1296 2353 1296 2354 1295 2354 1297 2354 1296 2355 1297 2355 1298 2355 1298 2356 1297 2356 1299 2356 1298 2357 1299 2357 1300 2357 1300 2358 1299 2358 1301 2358 1300 2359 1301 2359 1302 2359 1302 2360 1301 2360 1303 2360 1302 2361 1303 2361 1304 2361 1304 2362 1303 2362 1305 2362 1304 2363 1305 2363 1306 2363 1306 2364 1305 2364 1307 2364 1306 2365 1307 2365 1308 2365 1308 2366 1307 2366 1309 2366 1308 2367 1309 2367 1310 2367 1311 2368 1312 2368 1313 2368 1313 2369 1312 2369 1314 2369 1313 2370 1314 2370 1315 2370 1315 2371 1314 2371 1316 2371 1315 2372 1316 2372 1317 2372 1317 2373 1316 2373 1318 2373 1317 2374 1318 2374 1319 2374 1319 2375 1318 2375 1310 2375 1319 2376 1310 2376 1320 2376 1320 2377 1310 2377 1309 2377 1321 2378 1322 2378 1323 2378 1323 2379 1322 2379 1324 2379 1325 2380 1326 2380 1327 2380 1327 2381 1326 2381 1328 2381 1327 2382 1328 2382 1324 2382 1324 2383 1328 2383 1329 2383 1324 2384 1329 2384 1323 2384 1323 2385 1330 2385 1321 2385 1321 2386 1330 2386 1331 2386 1321 2387 1331 2387 1332 2387 1332 2388 1331 2388 1333 2388 1332 2389 1333 2389 1334 2389 1334 2390 1333 2390 1335 2390 1334 2391 1335 2391 1336 2391 1336 2392 1335 2392 1337 2392 1336 2393 1337 2393 1338 2393 1338 2394 1337 2394 1339 2394 1338 2395 1339 2395 1340 2395 1340 2396 1339 2396 1341 2396 1339 2397 1342 2397 1341 2397 1341 2398 1342 2398 1343 2398 1341 2399 1343 2399 1344 2399 1344 2400 1343 2400 1345 2400 1344 2401 1345 2401 1346 2401 1346 2402 1345 2402 1347 2402 1347 2403 1345 2403 1348 2403 1347 2404 1348 2404 1349 2404 1349 2405 1348 2405 1350 2405 1349 2406 1350 2406 1351 2406 1351 2407 1350 2407 1352 2407 1351 2408 1352 2408 1353 2408 1353 2409 1352 2409 1354 2409 1353 2410 1354 2410 1355 2410 1355 2411 1354 2411 1356 2411 1356 2412 1354 2412 1357 2412 1356 2413 1357 2413 1358 2413 1359 2414 1360 2414 1361 2414 1361 2415 1360 2415 1362 2415 1361 2416 1362 2416 1363 2416 1363 2417 1362 2417 1364 2417 1364 2418 1362 2418 1365 2418 1364 2419 1365 2419 1366 2419 1366 2420 1365 2420 1367 2420 1366 2421 1367 2421 1368 2421 1369 2422 1370 2422 1367 2422 1370 2423 1371 2423 1367 2423 1367 2424 1371 2424 1372 2424 1367 2425 1372 2425 1368 2425 1373 2426 1374 2426 1375 2426 1375 2427 1374 2427 1376 2427 1375 2428 1376 2428 1377 2428 1373 2429 1375 2429 1378 2429 1378 2430 1375 2430 1379 2430 1378 2431 1379 2431 1380 2431 1380 2432 1381 2432 1378 2432 1378 2433 1381 2433 1382 2433 1378 2434 1382 2434 1383 2434 1383 2435 1384 2435 1378 2435 1378 2436 1384 2436 1385 2436 1378 2437 1385 2437 1386 2437 1367 2438 1387 2438 1369 2438 1369 2439 1387 2439 1388 2439 1369 2440 1388 2440 1389 2440 1389 2441 1388 2441 1378 2441 1389 2442 1378 2442 1390 2442 1390 2443 1378 2443 1386 2443 1359 2444 1361 2444 1391 2444 1391 2445 1361 2445 1392 2445 1391 2446 1392 2446 1393 2446 1393 2447 1392 2447 1394 2447 1393 2448 1394 2448 1395 2448 1395 2449 1394 2449 1396 2449 1395 2450 1396 2450 1397 2450 1396 2451 1398 2451 1397 2451 1397 2452 1398 2452 1399 2452 1397 2453 1399 2453 1400 2453 1400 2454 1399 2454 1401 2454 1400 2455 1401 2455 1402 2455 1402 2456 1401 2456 1403 2456 1403 2457 1404 2457 1402 2457 1402 2458 1404 2458 1405 2458 1402 2459 1405 2459 1406 2459 1406 2460 1405 2460 1407 2460 1405 2461 1408 2461 1407 2461 1407 2462 1408 2462 1409 2462 1407 2463 1409 2463 1410 2463 1411 2464 1412 2464 1410 2464 1411 2465 1410 2465 1413 2465 1409 2466 1414 2466 1410 2466 1410 2467 1414 2467 1415 2467 1410 2468 1415 2468 1416 2468 1416 2469 1417 2469 1410 2469 1410 2470 1417 2470 1418 2470 1410 2471 1418 2471 1413 2471 1419 2472 1420 2472 1421 2472 1421 2473 1420 2473 1422 2473 1422 2474 1423 2474 1421 2474 1421 2475 1423 2475 1424 2475 1421 2476 1424 2476 1425 2476 1412 2477 1426 2477 1410 2477 1410 2478 1426 2478 1421 2478 1410 2479 1421 2479 1427 2479 1427 2480 1421 2480 1425 2480 1073 2481 1428 2481 1074 2481 1429 2482 1430 2482 1431 2482 1431 2483 1432 2483 1433 2483 1433 2484 1432 2484 1434 2484 1435 2485 1436 2485 1437 2485 1070 2486 1062 2486 1438 2486 1438 2487 1062 2487 1061 2487 1438 2488 1061 2488 1439 2488 1439 2489 1061 2489 1440 2489 1439 2490 1440 2490 1441 2490 1442 2491 1443 2491 1071 2491 1444 2492 1445 2492 1428 2492 1445 2493 1446 2493 1428 2493 1428 2494 1446 2494 1447 2494 1428 2495 1447 2495 1074 2495 1073 2496 1071 2496 1428 2496 1428 2497 1071 2497 1443 2497 1428 2498 1443 2498 1444 2498 1444 2499 1443 2499 1442 2499 1444 2500 1442 2500 1448 2500 1448 2501 1442 2501 1433 2501 1448 2502 1433 2502 1436 2502 1436 2503 1433 2503 1434 2503 1436 2504 1434 2504 1437 2504 1440 2505 1429 2505 1441 2505 1441 2506 1429 2506 1431 2506 1441 2507 1431 2507 1439 2507 1439 2508 1431 2508 1433 2508 1439 2509 1433 2509 1438 2509 1438 2510 1433 2510 1442 2510 1438 2511 1442 2511 1070 2511 1070 2512 1442 2512 1071 2512 1312 2513 1311 2513 1449 2513 1449 2514 1311 2514 1450 2514 1279 2515 1280 2515 51 2515 1451 2516 1452 2516 51 2516 51 2517 1452 2517 1453 2517 51 2518 1453 2518 1279 2518 20 2519 1454 2519 51 2519 51 2520 1454 2520 1455 2520 51 2521 1455 2521 1451 2521 19 2522 1456 2522 20 2522 20 2523 1456 2523 1457 2523 20 2524 1457 2524 1454 2524 25 2525 53 2525 1280 2525 1280 2526 53 2526 52 2526 1280 2527 52 2527 51 2527 1356 2528 1358 2528 1458 2528 1356 2529 1458 2529 1283 2529 1283 2529 1458 2529 1459 2529 1283 2530 1459 2530 1284 2530 91 2531 102 2531 1460 2531 105 2532 8 2532 7 2532 1461 2533 1462 2533 1463 2533 1464 2534 1465 2534 1466 2534 1467 2535 1430 2535 1429 2535 1466 2536 1465 2536 1468 2536 1468 2537 1465 2537 1469 2537 1468 2538 1469 2538 1470 2538 1470 2539 1471 2539 1468 2539 1468 2540 1471 2540 1472 2540 1468 2541 1472 2541 1467 2541 1463 2542 1462 2542 1473 2542 1462 2543 1474 2543 1473 2543 1473 2544 1474 2544 1475 2544 1473 2545 1475 2545 1466 2545 1466 2546 1475 2546 1476 2546 1466 2547 1476 2547 1464 2547 1477 2548 1478 2548 1479 2548 1479 2549 1480 2549 1477 2549 1477 2550 1480 2550 1481 2550 1477 2551 1481 2551 1463 2551 1463 2552 1481 2552 1482 2552 1463 2553 1482 2553 1461 2553 1483 2554 7 2554 5 2554 1460 2555 102 2555 1483 2555 102 2556 101 2556 1483 2556 1483 2557 101 2557 100 2557 1483 2558 100 2558 7 2558 7 2559 100 2559 104 2559 7 2560 104 2560 105 2560 31 2561 36 2561 1484 2561 1484 2562 36 2562 35 2562 1484 2563 35 2563 1460 2563 1460 2564 35 2564 39 2564 1460 2565 39 2565 91 2565 31 2566 1484 2566 32 2566 32 2567 1484 2567 1485 2567 32 2568 1485 2568 34 2568 34 2569 1485 2569 1486 2569 34 2570 1486 2570 18 2570 1487 2571 1455 2571 1454 2571 1454 2572 1457 2572 1487 2572 1487 2573 1457 2573 1456 2573 1487 2574 1456 2574 1486 2574 1486 2575 1456 2575 19 2575 1486 2576 19 2576 18 2576 1455 2577 1487 2577 1451 2577 1451 2578 1487 2578 1488 2578 1451 2579 1488 2579 1452 2579 1091 2580 1279 2580 1488 2580 1488 2581 1279 2581 1453 2581 1488 2582 1453 2582 1452 2582 1440 2583 1061 2583 1098 2583 1467 2584 1429 2584 1468 2584 1468 2585 1429 2585 1440 2585 1468 2586 1440 2586 1489 2586 1489 2587 1440 2587 1098 2587 1489 2588 1098 2588 1089 2588 4 2589 1479 2589 5 2589 5 2590 1479 2590 1478 2590 5 2591 1478 2591 1483 2591 1483 2592 1478 2592 1477 2592 1483 2593 1477 2593 1460 2593 1460 2594 1477 2594 1463 2594 1460 2595 1463 2595 1484 2595 1484 2596 1463 2596 1473 2596 1484 2597 1473 2597 1485 2597 1485 2598 1473 2598 1466 2598 1485 2599 1466 2599 1486 2599 1486 2600 1466 2600 1468 2600 1486 2601 1468 2601 1487 2601 1487 2602 1468 2602 1489 2602 1487 2603 1489 2603 1488 2603 1488 2604 1489 2604 1089 2604 1488 2605 1089 2605 1091 2605 1490 2606 1326 2606 1491 2606 1491 2607 1326 2607 1325 2607 1492 2608 1493 2608 1494 2608 1495 2609 1496 2609 1497 2609 1498 2610 1499 2610 1500 2610 1501 2611 1502 2611 1503 2611 1503 2612 1502 2612 1498 2612 1503 2613 1498 2613 1504 2613 1504 2614 1498 2614 1500 2614 1504 2615 1500 2615 1505 2615 1506 2616 1507 2616 1501 2616 1501 2617 1507 2617 1508 2617 1501 2618 1508 2618 1502 2618 1509 2619 1510 2619 1496 2619 1496 2620 1510 2620 1506 2620 1496 2621 1506 2621 1497 2621 1497 2622 1506 2622 1501 2622 1495 2623 1511 2623 1512 2623 1512 2624 1511 2624 1513 2624 1512 2625 1513 2625 1514 2625 1495 2626 1512 2626 1496 2626 1496 2627 1512 2627 1515 2627 1496 2628 1515 2628 1509 2628 1111 2629 1492 2629 1113 2629 1113 2630 1492 2630 1494 2630 1113 2631 1494 2631 1115 2631 1115 2632 1494 2632 1516 2632 1115 2633 1516 2633 1117 2633 1117 2634 1516 2634 1134 2634 1493 2635 1495 2635 1494 2635 1494 2636 1495 2636 1497 2636 1494 2637 1497 2637 1516 2637 1516 2638 1497 2638 1501 2638 1516 2639 1501 2639 1134 2639 1134 2640 1501 2640 1503 2640 1134 2641 1503 2641 1133 2641 1133 2642 1503 2642 1504 2642 1133 2643 1504 2643 1131 2643 1131 2644 1504 2644 1505 2644 1131 2645 1505 2645 1129 2645 59 2646 58 2646 1282 2646 1282 2647 1281 2647 1517 2647 1518 2648 87 2648 88 2648 1518 2649 88 2649 1519 2649 1517 2650 1520 2650 89 2650 89 2651 1520 2651 1521 2651 89 2652 1521 2652 88 2652 88 2653 1521 2653 1522 2653 88 2654 1522 2654 1519 2654 1517 2655 89 2655 1282 2655 1282 2656 89 2656 90 2656 1282 2657 90 2657 59 2657 97 2658 95 2658 1523 2658 60 2659 87 2659 1524 2659 1500 2660 1499 2660 1525 2660 1525 2661 1526 2661 1527 2661 1527 2662 1526 2662 1528 2662 1528 2663 1529 2663 1527 2663 1527 2664 1529 2664 1530 2664 1527 2665 1530 2665 1531 2665 1525 2666 1527 2666 1500 2666 1500 2667 1527 2667 1532 2667 1500 2668 1532 2668 1505 2668 1533 2669 1121 2669 1127 2669 1121 2670 1533 2670 1135 2670 1135 2671 1533 2671 1517 2671 1135 2672 1517 2672 1281 2672 1519 2673 1522 2673 1534 2673 1534 2674 1522 2674 1521 2674 1534 2675 1521 2675 1533 2675 1533 2676 1521 2676 1520 2676 1533 2677 1520 2677 1517 2677 1524 2678 87 2678 1534 2678 1534 2679 87 2679 1518 2679 1534 2680 1518 2680 1519 2680 67 2681 68 2681 1535 2681 1535 2682 68 2682 70 2682 1535 2683 70 2683 1536 2683 1536 2684 70 2684 71 2684 1536 2685 71 2685 1524 2685 1524 2686 71 2686 61 2686 1524 2687 61 2687 60 2687 67 2688 1535 2688 65 2688 65 2689 1535 2689 1537 2689 65 2690 1537 2690 63 2690 95 2691 94 2691 1523 2691 1523 2692 94 2692 98 2692 1523 2693 98 2693 1537 2693 1537 2694 98 2694 99 2694 1537 2695 99 2695 63 2695 6 2696 9 2696 103 2696 1538 2697 0 2697 6 2697 1 2698 0 2698 1539 2698 1539 2699 0 2699 1538 2699 1539 2700 1538 2700 1540 2700 1540 2701 1538 2701 1541 2701 1541 2702 1538 2702 1542 2702 1541 2703 1542 2703 1543 2703 1543 2704 1542 2704 1544 2704 1544 2705 1542 2705 1545 2705 1544 2706 1545 2706 1546 2706 1546 2707 1545 2707 1547 2707 1547 2708 1545 2708 1548 2708 1547 2709 1548 2709 1549 2709 1530 2710 1550 2710 1531 2710 1531 2711 1550 2711 1551 2711 1531 2712 1551 2712 1548 2712 1548 2713 1551 2713 1552 2713 1548 2714 1552 2714 1549 2714 103 2715 97 2715 6 2715 6 2716 97 2716 1523 2716 6 2717 1523 2717 1538 2717 1538 2718 1523 2718 1537 2718 1538 2719 1537 2719 1542 2719 1542 2720 1537 2720 1535 2720 1542 2721 1535 2721 1545 2721 1545 2722 1535 2722 1536 2722 1545 2723 1536 2723 1548 2723 1548 2724 1536 2724 1524 2724 1548 2725 1524 2725 1531 2725 1531 2726 1524 2726 1534 2726 1531 2727 1534 2727 1527 2727 1527 2728 1534 2728 1533 2728 1527 2729 1533 2729 1532 2729 1532 2730 1533 2730 1127 2730 1532 2731 1127 2731 1505 2731 1505 2732 1127 2732 1129 2732 1553 2733 1554 2733 1555 2733 1555 2734 1554 2734 1377 2734 1555 2735 1377 2735 1556 2735 1557 2736 1558 2736 1559 2736 1559 2737 1558 2737 1560 2737 1561 2738 1562 2738 1559 2738 1559 2739 1562 2739 1563 2739 1559 2740 1563 2740 1557 2740 1564 2741 1565 2741 1561 2741 1561 2742 1565 2742 1566 2742 1561 2743 1566 2743 1562 2743 1567 2744 1568 2744 1569 2744 1567 2745 1569 2745 1570 2745 1570 2746 1569 2746 1571 2746 1570 2747 1571 2747 1564 2747 1564 2748 1571 2748 1572 2748 1564 2749 1572 2749 1565 2749 1568 2750 1567 2750 1573 2750 1573 2751 1567 2751 1574 2751 1573 2752 1574 2752 1575 2752 1575 2753 1574 2753 1576 2753 1575 2754 1576 2754 1577 2754 1377 2755 1376 2755 1556 2755 1556 2756 1376 2756 1374 2756 1556 2757 1374 2757 1578 2757 1578 2758 1374 2758 1373 2758 1578 2759 1373 2759 1579 2759 1579 2760 1373 2760 1378 2760 1579 2761 1378 2761 1580 2761 1580 2762 1378 2762 1388 2762 1580 2763 1388 2763 1581 2763 1581 2764 1388 2764 1387 2764 1581 2765 1387 2765 1582 2765 1387 2766 1367 2766 1582 2766 1582 2767 1367 2767 1583 2767 1582 2768 1583 2768 1584 2768 1553 2769 1555 2769 1585 2769 1585 2770 1555 2770 1556 2770 1585 2771 1556 2771 1586 2771 1586 2772 1556 2772 1578 2772 1586 2773 1578 2773 1587 2773 1587 2774 1578 2774 1579 2774 1587 2775 1579 2775 1588 2775 1588 2776 1579 2776 1580 2776 1588 2777 1580 2777 1589 2777 1589 2778 1580 2778 1581 2778 1589 2779 1581 2779 1590 2779 1590 2780 1581 2780 1582 2780 1590 2781 1582 2781 1591 2781 1591 2782 1582 2782 1584 2782 1591 2783 1584 2783 1592 2783 1593 2784 1577 2784 1592 2784 1592 2785 1577 2785 1576 2785 1592 2786 1576 2786 1591 2786 1591 2787 1576 2787 1574 2787 1591 2788 1574 2788 1590 2788 1590 2789 1574 2789 1567 2789 1590 2790 1567 2790 1589 2790 1589 2791 1567 2791 1570 2791 1589 2792 1570 2792 1588 2792 1588 2793 1570 2793 1564 2793 1588 2794 1564 2794 1587 2794 1587 2795 1564 2795 1561 2795 1587 2796 1561 2796 1586 2796 1586 2797 1561 2797 1559 2797 1586 2798 1559 2798 1585 2798 1585 2799 1559 2799 1560 2799 1585 2800 1560 2800 1553 2800 1594 2801 1595 2801 1596 2801 1595 2802 1594 2802 1597 2802 1598 2803 1599 2803 1600 2803 1599 2804 1601 2804 1602 2804 1602 2805 1601 2805 1603 2805 1602 2806 1603 2806 1604 2806 1422 2807 1420 2807 1605 2807 1605 2808 1420 2808 1419 2808 1605 2809 1419 2809 1606 2809 1606 2810 1419 2810 1607 2810 1422 2811 1605 2811 1423 2811 1423 2812 1605 2812 1608 2812 1423 2813 1608 2813 1424 2813 1424 2814 1608 2814 1425 2814 1425 2815 1608 2815 1609 2815 1425 2816 1609 2816 1427 2816 1427 2817 1609 2817 1610 2817 1427 2818 1610 2818 1410 2818 1410 2819 1610 2819 1611 2819 1410 2820 1611 2820 1407 2820 1407 2821 1611 2821 1612 2821 1407 2822 1612 2822 1406 2822 1613 2823 1614 2823 1594 2823 1594 2824 1614 2824 1615 2824 1594 2825 1615 2825 1597 2825 1616 2826 1617 2826 1613 2826 1613 2827 1617 2827 1618 2827 1613 2828 1618 2828 1614 2828 1619 2829 1620 2829 1621 2829 1621 2830 1620 2830 1622 2830 1621 2831 1622 2831 1616 2831 1616 2832 1622 2832 1623 2832 1616 2833 1623 2833 1617 2833 1604 2834 1624 2834 1602 2834 1602 2835 1624 2835 1625 2835 1602 2836 1625 2836 1626 2836 1626 2837 1625 2837 1627 2837 1626 2838 1627 2838 1619 2838 1619 2839 1627 2839 1628 2839 1619 2840 1628 2840 1620 2840 1402 2841 1406 2841 1629 2841 1629 2842 1406 2842 1612 2842 1629 2843 1612 2843 1630 2843 1630 2844 1612 2844 1611 2844 1630 2845 1611 2845 1631 2845 1631 2846 1611 2846 1610 2846 1631 2847 1610 2847 1632 2847 1632 2848 1610 2848 1609 2848 1632 2849 1609 2849 1633 2849 1633 2850 1609 2850 1608 2850 1633 2851 1608 2851 1634 2851 1634 2852 1608 2852 1605 2852 1634 2853 1605 2853 1635 2853 1635 2854 1605 2854 1606 2854 1635 2855 1606 2855 1600 2855 1600 2856 1606 2856 1607 2856 1600 2857 1607 2857 1598 2857 1599 2858 1602 2858 1600 2858 1600 2859 1602 2859 1626 2859 1600 2860 1626 2860 1635 2860 1635 2861 1626 2861 1619 2861 1635 2862 1619 2862 1634 2862 1634 2863 1619 2863 1621 2863 1634 2864 1621 2864 1633 2864 1633 2865 1621 2865 1616 2865 1633 2866 1616 2866 1632 2866 1632 2867 1616 2867 1613 2867 1632 2868 1613 2868 1631 2868 1631 2869 1613 2869 1594 2869 1631 2870 1594 2870 1630 2870 1630 2871 1594 2871 1596 2871 1630 2872 1596 2872 1629 2872 1636 2873 1593 2873 1637 2873 1638 2874 1639 2874 1558 2874 1640 2875 1641 2875 1642 2875 1643 2876 1644 2876 1645 2876 1643 2877 1646 2877 1647 2877 1647 2878 1646 2878 1648 2878 1647 2879 1648 2879 1641 2879 1649 2880 1650 2880 1651 2880 1651 2881 1650 2881 1652 2881 1651 2882 1652 2882 1653 2882 1653 2883 1652 2883 1654 2883 1653 2884 1654 2884 1640 2884 1655 2885 1573 2885 1656 2885 1656 2886 1573 2886 1575 2886 1656 2887 1575 2887 1636 2887 1636 2888 1575 2888 1577 2888 1636 2889 1577 2889 1593 2889 1657 2890 1571 2890 1658 2890 1658 2891 1571 2891 1569 2891 1658 2892 1569 2892 1655 2892 1655 2893 1569 2893 1568 2893 1655 2894 1568 2894 1573 2894 1659 2895 1565 2895 1657 2895 1657 2896 1565 2896 1572 2896 1657 2897 1572 2897 1571 2897 1557 2898 1563 2898 1660 2898 1660 2899 1563 2899 1562 2899 1660 2900 1562 2900 1659 2900 1659 2901 1562 2901 1566 2901 1659 2902 1566 2902 1565 2902 1644 2903 1661 2903 1645 2903 1645 2904 1661 2904 1662 2904 1645 2905 1662 2905 1663 2905 1664 2906 1665 2906 1666 2906 1666 2907 1665 2907 1667 2907 1666 2908 1667 2908 1668 2908 1668 2909 1667 2909 1669 2909 1668 2910 1669 2910 1649 2910 1649 2911 1669 2911 1670 2911 1649 2912 1670 2912 1650 2912 1640 2913 1642 2913 1653 2913 1653 2914 1642 2914 1671 2914 1653 2915 1671 2915 1651 2915 1651 2916 1671 2916 1672 2916 1651 2917 1672 2917 1649 2917 1649 2918 1672 2918 1673 2918 1649 2919 1673 2919 1668 2919 1668 2920 1673 2920 1674 2920 1668 2921 1674 2921 1666 2921 1666 2922 1674 2922 1675 2922 1666 2923 1675 2923 1664 2923 1641 2924 1648 2924 1642 2924 1642 2925 1648 2925 1676 2925 1642 2926 1676 2926 1671 2926 1671 2927 1676 2927 1677 2927 1671 2928 1677 2928 1672 2928 1672 2929 1677 2929 1678 2929 1672 2930 1678 2930 1673 2930 1673 2931 1678 2931 1679 2931 1673 2932 1679 2932 1674 2932 1674 2933 1679 2933 1680 2933 1674 2934 1680 2934 1675 2934 1643 2935 1645 2935 1646 2935 1646 2936 1645 2936 1681 2936 1646 2937 1681 2937 1648 2937 1648 2938 1681 2938 1682 2938 1648 2939 1682 2939 1676 2939 1676 2940 1682 2940 1683 2940 1676 2941 1683 2941 1677 2941 1677 2942 1683 2942 1684 2942 1677 2943 1684 2943 1678 2943 1678 2944 1684 2944 1685 2944 1678 2945 1685 2945 1679 2945 1679 2946 1685 2946 1686 2946 1679 2947 1686 2947 1680 2947 1680 2948 1686 2948 1687 2948 1680 2949 1687 2949 1675 2949 1675 2950 1687 2950 1688 2950 1675 2951 1688 2951 1664 2951 1664 2952 1688 2952 1689 2952 1664 2953 1689 2953 1665 2953 1638 2954 1558 2954 1690 2954 1690 2955 1558 2955 1557 2955 1690 2956 1557 2956 1663 2956 1663 2957 1557 2957 1660 2957 1663 2958 1660 2958 1645 2958 1645 2959 1660 2959 1659 2959 1645 2960 1659 2960 1681 2960 1681 2961 1659 2961 1657 2961 1681 2962 1657 2962 1682 2962 1682 2963 1657 2963 1658 2963 1682 2964 1658 2964 1683 2964 1683 2965 1658 2965 1655 2965 1683 2966 1655 2966 1684 2966 1684 2967 1655 2967 1656 2967 1684 2968 1656 2968 1685 2968 1685 2969 1656 2969 1636 2969 1685 2970 1636 2970 1686 2970 1686 2971 1636 2971 1637 2971 1686 2972 1637 2972 1687 2972 1691 2973 1692 2973 1693 2973 1693 2974 1692 2974 1694 2974 1693 2975 1694 2975 1695 2975 1696 2976 1697 2976 1698 2976 1698 2977 1697 2977 1699 2977 1698 2978 1699 2978 1693 2978 1693 2979 1699 2979 1700 2979 1693 2980 1700 2980 1691 2980 1701 2981 1702 2981 1696 2981 1703 2982 1704 2982 1705 2982 1705 2983 1704 2983 1702 2983 1705 2984 1702 2984 1706 2984 1707 2985 1708 2985 1703 2985 1709 2986 1710 2986 1711 2986 1711 2987 1710 2987 1712 2987 1709 2988 1624 2988 1713 2988 1713 2989 1624 2989 1604 2989 1713 2990 1604 2990 1714 2990 1709 2991 1711 2991 1624 2991 1624 2992 1711 2992 1715 2992 1624 2993 1715 2993 1625 2993 1625 2994 1715 2994 1627 2994 1627 2995 1715 2995 1716 2995 1627 2996 1716 2996 1628 2996 1628 2997 1716 2997 1717 2997 1628 2998 1717 2998 1620 2998 1620 2999 1717 2999 1622 2999 1622 3000 1717 3000 1718 3000 1622 3001 1718 3001 1623 3001 1623 3002 1718 3002 1617 3002 1617 3003 1718 3003 1719 3003 1617 3004 1719 3004 1618 3004 1618 3005 1719 3005 1614 3005 1614 3006 1719 3006 1720 3006 1614 3007 1720 3007 1615 3007 1721 3008 1722 3008 1723 3008 1723 3009 1722 3009 1724 3009 1723 3010 1724 3010 1725 3010 1694 3011 1726 3011 1695 3011 1695 3012 1726 3012 1727 3012 1695 3013 1727 3013 1721 3013 1721 3014 1727 3014 1728 3014 1721 3015 1728 3015 1722 3015 1724 3016 1729 3016 1725 3016 1725 3017 1729 3017 1730 3017 1725 3018 1730 3018 1731 3018 1696 3019 1698 3019 1701 3019 1701 3020 1698 3020 1693 3020 1701 3021 1693 3021 1732 3021 1732 3022 1693 3022 1695 3022 1732 3023 1695 3023 1733 3023 1733 3024 1695 3024 1721 3024 1733 3025 1721 3025 1734 3025 1734 3026 1721 3026 1723 3026 1734 3027 1723 3027 1735 3027 1735 3028 1723 3028 1725 3028 1735 3029 1725 3029 1736 3029 1736 3030 1725 3030 1731 3030 1736 3031 1731 3031 1737 3031 1702 3032 1701 3032 1706 3032 1706 3033 1701 3033 1732 3033 1706 3034 1732 3034 1738 3034 1738 3035 1732 3035 1733 3035 1738 3036 1733 3036 1739 3036 1739 3037 1733 3037 1734 3037 1739 3038 1734 3038 1740 3038 1740 3039 1734 3039 1735 3039 1740 3040 1735 3040 1741 3040 1741 3041 1735 3041 1736 3041 1741 3042 1736 3042 1742 3042 1742 3043 1736 3043 1737 3043 1742 3044 1737 3044 1743 3044 1703 3045 1705 3045 1707 3045 1707 3046 1705 3046 1706 3046 1707 3047 1706 3047 1744 3047 1744 3048 1706 3048 1738 3048 1744 3049 1738 3049 1745 3049 1745 3050 1738 3050 1739 3050 1745 3051 1739 3051 1746 3051 1746 3052 1739 3052 1740 3052 1746 3053 1740 3053 1747 3053 1747 3054 1740 3054 1741 3054 1747 3055 1741 3055 1748 3055 1748 3056 1741 3056 1742 3056 1748 3057 1742 3057 1749 3057 1749 3058 1742 3058 1743 3058 1749 3059 1743 3059 1750 3059 1597 3060 1615 3060 1750 3060 1750 3061 1615 3061 1720 3061 1750 3062 1720 3062 1749 3062 1749 3063 1720 3063 1719 3063 1749 3064 1719 3064 1748 3064 1748 3065 1719 3065 1718 3065 1748 3066 1718 3066 1747 3066 1747 3067 1718 3067 1717 3067 1747 3068 1717 3068 1746 3068 1746 3069 1717 3069 1716 3069 1746 3070 1716 3070 1745 3070 1745 3071 1716 3071 1715 3071 1745 3072 1715 3072 1744 3072 1744 3073 1715 3073 1711 3073 1744 3074 1711 3074 1707 3074 1707 3075 1711 3075 1712 3075 1707 3076 1712 3076 1708 3076 1751 3077 1726 3077 1752 3077 1752 3078 1726 3078 1694 3078 1752 3079 1694 3079 1692 3079 1650 3080 1670 3080 1753 3080 1753 3081 1670 3081 1669 3081 1753 3082 1669 3082 1754 3082 1754 3083 1669 3083 1667 3083 1754 3084 1667 3084 1755 3084 1755 3085 1667 3085 1665 3085 1755 3086 1665 3086 1756 3086 1756 3087 1665 3087 1689 3087 1756 3088 1689 3088 1757 3088 1757 3089 1689 3089 1758 3089 1757 3090 1758 3090 1759 3090 1759 3091 1758 3091 1760 3091 1759 3092 1760 3092 1761 3092 1761 3093 1760 3093 1762 3093 1761 3094 1762 3094 1763 3094 1763 3095 1762 3095 1764 3095 1763 3096 1764 3096 1765 3096 1765 3097 1764 3097 1766 3097 1765 3098 1766 3098 1767 3098 1767 3099 1766 3099 1768 3099 1767 3100 1768 3100 1769 3100 1769 3101 1768 3101 1770 3101 1769 3102 1770 3102 1771 3102 1771 3103 1770 3103 1729 3103 1771 3104 1729 3104 1772 3104 1772 3105 1729 3105 1724 3105 1772 3106 1724 3106 1773 3106 1773 3107 1724 3107 1722 3107 1773 3108 1722 3108 1774 3108 1774 3109 1722 3109 1728 3109 1774 3110 1728 3110 1751 3110 1751 3111 1728 3111 1727 3111 1751 3112 1727 3112 1726 3112 1775 3113 1592 3113 1584 3113 1400 3114 1776 3114 1397 3114 1397 3115 1776 3115 1777 3115 1397 3116 1777 3116 1395 3116 1395 3117 1777 3117 1778 3117 1395 3118 1778 3118 1393 3118 1393 3119 1778 3119 1779 3119 1393 3120 1779 3120 1391 3120 1391 3121 1779 3121 1780 3121 1391 3122 1780 3122 1359 3122 1359 3123 1780 3123 1781 3123 1359 3124 1781 3124 1360 3124 1360 3125 1781 3125 1782 3125 1360 3126 1782 3126 1362 3126 1583 3127 1367 3127 1782 3127 1782 3128 1367 3128 1365 3128 1782 3129 1365 3129 1362 3129 1593 3130 1592 3130 1783 3130 1783 3131 1592 3131 1775 3131 1783 3132 1775 3132 1784 3132 1784 3133 1775 3133 1785 3133 1784 3134 1785 3134 1786 3134 1787 3135 1788 3135 1789 3135 1789 3136 1788 3136 1790 3136 1789 3137 1790 3137 1791 3137 1791 3138 1790 3138 1792 3138 1791 3139 1792 3139 1793 3139 1793 3140 1792 3140 1786 3140 1793 3141 1786 3141 1794 3141 1794 3142 1786 3142 1785 3142 1596 3143 1776 3143 1629 3143 1629 3144 1776 3144 1400 3144 1629 3145 1400 3145 1402 3145 1583 3146 1782 3146 1795 3146 1795 3147 1782 3147 1781 3147 1795 3148 1781 3148 1796 3148 1796 3149 1781 3149 1780 3149 1796 3150 1780 3150 1797 3150 1797 3151 1780 3151 1779 3151 1797 3152 1779 3152 1798 3152 1798 3153 1779 3153 1778 3153 1798 3154 1778 3154 1799 3154 1799 3155 1778 3155 1777 3155 1799 3156 1777 3156 1800 3156 1800 3157 1777 3157 1776 3157 1800 3158 1776 3158 1801 3158 1801 3159 1776 3159 1596 3159 1801 3160 1596 3160 1595 3160 1597 3161 1788 3161 1595 3161 1595 3162 1788 3162 1787 3162 1595 3163 1787 3163 1801 3163 1801 3164 1787 3164 1789 3164 1801 3165 1789 3165 1800 3165 1800 3166 1789 3166 1791 3166 1800 3167 1791 3167 1799 3167 1799 3168 1791 3168 1793 3168 1799 3169 1793 3169 1798 3169 1798 3170 1793 3170 1794 3170 1798 3171 1794 3171 1797 3171 1797 3172 1794 3172 1785 3172 1797 3173 1785 3173 1796 3173 1796 3174 1785 3174 1775 3174 1796 3175 1775 3175 1795 3175 1795 3176 1775 3176 1584 3176 1795 3177 1584 3177 1583 3177 1802 3178 1731 3178 1730 3178 1788 3179 1597 3179 1750 3179 1788 3180 1803 3180 1804 3180 1788 3181 1804 3181 1790 3181 1790 3182 1804 3182 1805 3182 1790 3183 1805 3183 1792 3183 1805 3184 1806 3184 1792 3184 1792 3185 1806 3185 1807 3185 1792 3186 1807 3186 1786 3186 1786 3187 1807 3187 1808 3187 1786 3188 1808 3188 1784 3188 1784 3189 1808 3189 1809 3189 1784 3190 1809 3190 1783 3190 1730 3191 1729 3191 1810 3191 1810 3192 1729 3192 1770 3192 1810 3193 1770 3193 1811 3193 1811 3194 1770 3194 1768 3194 1811 3195 1768 3195 1812 3195 1812 3196 1768 3196 1766 3196 1812 3197 1766 3197 1813 3197 1813 3198 1766 3198 1764 3198 1813 3199 1764 3199 1814 3199 1814 3200 1764 3200 1762 3200 1814 3201 1762 3201 1815 3201 1815 3202 1762 3202 1760 3202 1815 3203 1760 3203 1816 3203 1816 3204 1760 3204 1758 3204 1687 3205 1816 3205 1688 3205 1688 3206 1816 3206 1758 3206 1688 3207 1758 3207 1689 3207 1730 3208 1810 3208 1802 3208 1802 3209 1810 3209 1811 3209 1802 3210 1811 3210 1817 3210 1817 3211 1811 3211 1812 3211 1817 3212 1812 3212 1818 3212 1818 3213 1812 3213 1813 3213 1818 3214 1813 3214 1819 3214 1819 3215 1813 3215 1814 3215 1819 3216 1814 3216 1820 3216 1820 3217 1814 3217 1815 3217 1820 3218 1815 3218 1821 3218 1821 3219 1815 3219 1816 3219 1821 3220 1816 3220 1822 3220 1822 3221 1816 3221 1687 3221 1822 3222 1687 3222 1637 3222 1788 3223 1750 3223 1803 3223 1803 3224 1750 3224 1743 3224 1803 3225 1743 3225 1737 3225 1593 3226 1783 3226 1637 3226 1637 3227 1783 3227 1809 3227 1637 3228 1809 3228 1822 3228 1822 3229 1809 3229 1808 3229 1822 3230 1808 3230 1821 3230 1821 3231 1808 3231 1807 3231 1821 3232 1807 3232 1820 3232 1820 3233 1807 3233 1806 3233 1820 3234 1806 3234 1819 3234 1819 3235 1806 3235 1805 3235 1819 3236 1805 3236 1818 3236 1818 3237 1805 3237 1804 3237 1818 3238 1804 3238 1817 3238 1817 3239 1804 3239 1803 3239 1817 3240 1803 3240 1802 3240 1802 3241 1803 3241 1737 3241 1802 3242 1737 3242 1731 3242 1823 3243 1824 3243 1075 3243 1825 3244 1826 3244 1076 3244 1827 3245 1828 3245 1086 3245 1086 3246 1828 3246 1829 3246 1086 3247 1829 3247 1123 3247 1123 3248 1829 3248 1830 3248 1123 3249 1830 3249 1831 3249 1830 3250 1832 3250 1833 3250 1833 3251 1834 3251 1830 3251 1830 3252 1834 3252 1835 3252 1830 3253 1835 3253 1831 3253 1068 3254 1836 3254 1837 3254 1837 3255 1838 3255 1068 3255 1068 3256 1838 3256 1839 3256 1068 3257 1839 3257 1086 3257 1086 3258 1839 3258 1840 3258 1086 3259 1840 3259 1827 3259 1841 3260 1842 3260 1067 3260 1067 3261 1842 3261 1843 3261 1067 3262 1843 3262 1068 3262 1068 3263 1843 3263 1844 3263 1068 3264 1844 3264 1836 3264 1845 3265 1846 3265 1107 3265 1107 3266 1846 3266 1847 3266 1107 3267 1847 3267 1067 3267 1067 3268 1847 3268 1848 3268 1067 3269 1848 3269 1841 3269 1079 3270 1849 3270 1107 3270 1107 3271 1849 3271 1850 3271 1107 3272 1850 3272 1845 3272 1851 3273 1852 3273 1078 3273 1078 3274 1852 3274 1853 3274 1078 3275 1853 3275 1079 3275 1079 3276 1853 3276 1854 3276 1079 3277 1854 3277 1849 3277 1826 3278 1855 3278 1076 3278 1076 3279 1855 3279 1856 3279 1076 3280 1856 3280 1078 3280 1078 3281 1856 3281 1857 3281 1078 3282 1857 3282 1851 3282 1075 3283 1824 3283 1076 3283 1076 3284 1824 3284 1858 3284 1076 3285 1858 3285 1825 3285 1859 3286 1860 3286 1861 3286 1861 3287 1860 3287 1862 3287 1861 3288 1862 3288 1863 3288 1823 3289 1075 3289 1864 3289 1864 3290 1075 3290 1103 3290 1864 3291 1103 3291 1861 3291 1861 3292 1103 3292 1865 3292 1861 3293 1865 3293 1859 3293 1866 3294 1867 3294 1868 3294 1869 3295 1870 3295 1412 3295 1412 3296 1870 3296 1871 3296 1412 3297 1871 3297 1426 3297 1868 3298 1867 3298 1412 3298 1412 3299 1867 3299 1872 3299 1412 3300 1872 3300 1869 3300 1873 3301 1874 3301 1868 3301 1868 3302 1874 3302 1875 3302 1868 3303 1875 3303 1866 3303 1876 3304 1877 3304 1878 3304 1878 3305 1877 3305 1879 3305 1878 3306 1879 3306 1873 3306 1873 3307 1879 3307 1880 3307 1873 3308 1880 3308 1874 3308 1881 3309 1326 3309 1490 3309 1490 3310 1876 3310 1881 3310 1881 3311 1876 3311 1878 3311 1881 3312 1878 3312 1882 3312 1882 3313 1878 3313 1873 3313 1882 3314 1873 3314 1883 3314 1883 3315 1873 3315 1868 3315 1883 3316 1868 3316 1411 3316 1411 3317 1868 3317 1412 3317 1882 3318 1883 3318 1884 3318 1885 3319 1886 3319 1887 3319 1885 3320 1887 3320 1888 3320 1396 3321 1889 3321 1890 3321 1396 3322 1890 3322 1398 3322 1398 3323 1890 3323 1891 3323 1398 3324 1891 3324 1399 3324 1352 3325 1892 3325 1354 3325 1354 3326 1892 3326 1887 3326 1354 3327 1887 3327 1357 3327 1357 3328 1887 3328 1886 3328 1357 3329 1886 3329 1358 3329 1350 3330 1893 3330 1352 3330 1352 3331 1893 3331 1894 3331 1352 3332 1894 3332 1892 3332 1350 3333 1348 3333 1893 3333 1893 3334 1348 3334 1345 3334 1893 3335 1345 3335 1895 3335 1895 3336 1345 3336 1343 3336 1895 3337 1343 3337 1896 3337 1896 3338 1343 3338 1342 3338 1896 3339 1342 3339 1897 3339 1342 3340 1339 3340 1897 3340 1897 3341 1339 3341 1337 3341 1897 3342 1337 3342 1898 3342 1898 3343 1337 3343 1335 3343 1898 3344 1335 3344 1899 3344 1335 3345 1333 3345 1899 3345 1899 3346 1333 3346 1331 3346 1899 3347 1331 3347 1900 3347 1900 3348 1331 3348 1330 3348 1900 3349 1330 3349 1901 3349 1901 3350 1330 3350 1323 3350 1901 3351 1323 3351 1902 3351 1323 3352 1329 3352 1902 3352 1902 3353 1329 3353 1328 3353 1902 3354 1328 3354 1903 3354 1903 3355 1328 3355 1326 3355 1326 3356 1881 3356 1903 3356 1903 3357 1881 3357 1904 3357 1903 3358 1904 3358 1902 3358 1902 3359 1904 3359 1905 3359 1902 3360 1905 3360 1901 3360 1901 3361 1905 3361 1906 3361 1901 3362 1906 3362 1900 3362 1900 3363 1906 3363 1907 3363 1900 3364 1907 3364 1899 3364 1899 3365 1907 3365 1908 3365 1899 3366 1908 3366 1898 3366 1898 3367 1908 3367 1909 3367 1898 3368 1909 3368 1897 3368 1897 3369 1909 3369 1910 3369 1897 3370 1910 3370 1896 3370 1896 3371 1910 3371 1911 3371 1896 3372 1911 3372 1895 3372 1895 3373 1911 3373 1912 3373 1895 3374 1912 3374 1893 3374 1893 3375 1912 3375 1913 3375 1893 3376 1913 3376 1894 3376 1894 3377 1913 3377 1914 3377 1894 3378 1914 3378 1892 3378 1892 3379 1914 3379 1915 3379 1892 3380 1915 3380 1887 3380 1887 3381 1915 3381 1916 3381 1887 3382 1916 3382 1888 3382 1888 3383 1916 3383 1917 3383 1881 3384 1882 3384 1904 3384 1904 3385 1882 3385 1884 3385 1904 3386 1884 3386 1905 3386 1905 3387 1884 3387 1918 3387 1905 3388 1918 3388 1906 3388 1906 3389 1918 3389 1919 3389 1906 3390 1919 3390 1907 3390 1907 3391 1919 3391 1920 3391 1907 3392 1920 3392 1908 3392 1908 3393 1920 3393 1921 3393 1908 3394 1921 3394 1909 3394 1909 3395 1921 3395 1922 3395 1909 3396 1922 3396 1910 3396 1910 3397 1922 3397 1923 3397 1910 3398 1923 3398 1911 3398 1911 3399 1923 3399 1924 3399 1911 3400 1924 3400 1912 3400 1912 3401 1924 3401 1925 3401 1912 3402 1925 3402 1913 3402 1913 3403 1925 3403 1926 3403 1913 3404 1926 3404 1914 3404 1914 3405 1926 3405 1927 3405 1914 3406 1927 3406 1915 3406 1915 3407 1927 3407 1891 3407 1915 3408 1891 3408 1916 3408 1916 3409 1891 3409 1890 3409 1916 3410 1890 3410 1917 3410 1917 3411 1890 3411 1889 3411 1399 3412 1891 3412 1401 3412 1401 3413 1891 3413 1927 3413 1401 3414 1927 3414 1403 3414 1403 3415 1927 3415 1926 3415 1403 3416 1926 3416 1404 3416 1404 3417 1926 3417 1925 3417 1404 3418 1925 3418 1405 3418 1405 3419 1925 3419 1924 3419 1405 3420 1924 3420 1408 3420 1408 3421 1924 3421 1923 3421 1408 3422 1923 3422 1409 3422 1409 3423 1923 3423 1922 3423 1409 3424 1922 3424 1414 3424 1414 3425 1922 3425 1921 3425 1414 3426 1921 3426 1415 3426 1415 3427 1921 3427 1920 3427 1415 3428 1920 3428 1416 3428 1416 3429 1920 3429 1919 3429 1416 3430 1919 3430 1417 3430 1417 3431 1919 3431 1918 3431 1417 3432 1918 3432 1418 3432 1418 3433 1918 3433 1884 3433 1418 3434 1884 3434 1413 3434 1413 3435 1884 3435 1883 3435 1413 3436 1883 3436 1411 3436 1284 3437 1459 3437 1928 3437 1928 3438 1459 3438 1929 3438 1928 3439 1929 3439 1930 3439 1459 3440 1458 3440 1931 3440 1931 3441 1458 3441 1358 3441 1931 3442 1358 3442 1886 3442 1459 3443 1931 3443 1929 3443 1929 3444 1931 3444 1932 3444 1929 3445 1932 3445 1933 3445 1933 3446 1361 3446 1363 3446 1363 3447 1934 3447 1933 3447 1933 3448 1934 3448 1935 3448 1933 3449 1935 3449 1929 3449 1929 3450 1935 3450 1936 3450 1929 3451 1936 3451 1930 3451 1886 3452 1885 3452 1931 3452 1931 3453 1885 3453 1888 3453 1931 3454 1888 3454 1932 3454 1932 3455 1888 3455 1917 3455 1932 3456 1917 3456 1889 3456 1361 3457 1933 3457 1392 3457 1392 3458 1933 3458 1932 3458 1392 3459 1932 3459 1394 3459 1394 3460 1932 3460 1889 3460 1394 3461 1889 3461 1396 3461 1937 3462 1938 3462 1939 3462 1315 3463 1939 3463 1313 3463 1313 3464 1939 3464 1938 3464 1313 3465 1938 3465 1311 3465 1317 3466 1940 3466 1315 3466 1315 3467 1940 3467 1941 3467 1315 3468 1941 3468 1939 3468 1317 3469 1319 3469 1940 3469 1940 3470 1319 3470 1320 3470 1940 3471 1320 3471 1942 3471 1942 3472 1320 3472 1309 3472 1942 3473 1309 3473 1943 3473 1943 3474 1309 3474 1307 3474 1943 3475 1307 3475 1944 3475 1944 3476 1307 3476 1305 3476 1944 3477 1305 3477 1945 3477 1305 3478 1303 3478 1945 3478 1945 3479 1303 3479 1301 3479 1945 3480 1301 3480 1946 3480 1946 3481 1301 3481 1299 3481 1946 3482 1299 3482 1947 3482 1947 3483 1299 3483 1297 3483 1947 3484 1297 3484 1948 3484 1948 3485 1297 3485 1295 3485 1948 3486 1295 3486 1292 3486 1290 3487 1949 3487 1292 3487 1292 3488 1949 3488 1950 3488 1292 3489 1950 3489 1948 3489 1381 3490 1951 3490 1382 3490 1382 3491 1951 3491 1952 3491 1382 3492 1952 3492 1383 3492 1383 3493 1952 3493 1953 3493 1383 3494 1953 3494 1384 3494 1384 3495 1953 3495 1954 3495 1384 3496 1954 3496 1385 3496 1385 3497 1954 3497 1955 3497 1385 3498 1955 3498 1386 3498 1386 3499 1955 3499 1956 3499 1386 3500 1956 3500 1390 3500 1390 3501 1956 3501 1957 3501 1390 3502 1957 3502 1389 3502 1389 3503 1957 3503 1958 3503 1389 3504 1958 3504 1369 3504 1369 3505 1958 3505 1959 3505 1369 3506 1959 3506 1370 3506 1370 3507 1959 3507 1960 3507 1370 3508 1960 3508 1371 3508 1371 3509 1960 3509 1961 3509 1371 3510 1961 3510 1372 3510 1372 3511 1961 3511 1962 3511 1372 3512 1962 3512 1368 3512 1963 3513 1964 3513 1965 3513 1965 3514 1964 3514 1962 3514 1965 3515 1962 3515 1966 3515 1966 3516 1962 3516 1961 3516 1966 3517 1961 3517 1967 3517 1967 3518 1961 3518 1960 3518 1967 3519 1960 3519 1968 3519 1968 3520 1960 3520 1959 3520 1968 3521 1959 3521 1969 3521 1969 3522 1959 3522 1958 3522 1969 3523 1958 3523 1970 3523 1970 3524 1958 3524 1957 3524 1970 3525 1957 3525 1971 3525 1971 3526 1957 3526 1956 3526 1971 3527 1956 3527 1972 3527 1972 3528 1956 3528 1955 3528 1972 3529 1955 3529 1973 3529 1973 3530 1955 3530 1954 3530 1973 3531 1954 3531 1974 3531 1974 3532 1954 3532 1953 3532 1974 3533 1953 3533 1975 3533 1975 3534 1953 3534 1952 3534 1975 3535 1952 3535 1976 3535 1976 3536 1952 3536 1951 3536 1976 3537 1951 3537 1977 3537 1977 3538 1951 3538 1381 3538 1368 3539 1962 3539 1366 3539 1366 3540 1962 3540 1964 3540 1366 3541 1964 3541 1364 3541 1290 3542 1289 3542 1949 3542 1949 3543 1289 3543 1286 3543 1949 3544 1286 3544 1978 3544 1978 3545 1286 3545 1284 3545 1978 3546 1284 3546 1928 3546 1928 3547 1930 3547 1978 3547 1978 3548 1930 3548 1963 3548 1978 3549 1963 3549 1949 3549 1949 3550 1963 3550 1965 3550 1949 3551 1965 3551 1950 3551 1950 3552 1965 3552 1966 3552 1950 3553 1966 3553 1948 3553 1948 3554 1966 3554 1967 3554 1948 3555 1967 3555 1947 3555 1947 3556 1967 3556 1968 3556 1947 3557 1968 3557 1946 3557 1946 3558 1968 3558 1969 3558 1946 3559 1969 3559 1945 3559 1945 3560 1969 3560 1970 3560 1945 3561 1970 3561 1944 3561 1944 3562 1970 3562 1971 3562 1944 3563 1971 3563 1943 3563 1943 3564 1971 3564 1972 3564 1943 3565 1972 3565 1942 3565 1942 3566 1972 3566 1973 3566 1942 3567 1973 3567 1940 3567 1940 3568 1973 3568 1974 3568 1940 3569 1974 3569 1941 3569 1941 3570 1974 3570 1975 3570 1941 3571 1975 3571 1939 3571 1939 3572 1975 3572 1976 3572 1939 3573 1976 3573 1937 3573 1937 3574 1976 3574 1977 3574 1363 3575 1364 3575 1934 3575 1934 3576 1364 3576 1964 3576 1934 3577 1964 3577 1935 3577 1935 3578 1964 3578 1963 3578 1935 3579 1963 3579 1936 3579 1936 3580 1963 3580 1930 3580 1979 3581 1980 3581 1981 3581 1980 3582 1979 3582 1982 3582 1983 3583 1984 3583 1985 3583 1379 3584 1986 3584 1380 3584 1380 3585 1986 3585 1987 3585 1380 3586 1987 3586 1983 3586 1983 3587 1987 3587 1988 3587 1983 3588 1988 3588 1984 3588 1311 3589 1938 3589 1450 3589 1450 3590 1938 3590 1989 3590 1985 3591 1990 3591 1983 3591 1983 3592 1990 3592 1991 3592 1983 3593 1991 3593 1981 3593 1981 3594 1991 3594 1992 3594 1981 3595 1992 3595 1979 3595 1982 3596 1989 3596 1980 3596 1980 3597 1989 3597 1938 3597 1980 3598 1938 3598 1981 3598 1981 3599 1938 3599 1937 3599 1981 3600 1937 3600 1983 3600 1983 3601 1937 3601 1977 3601 1983 3602 1977 3602 1380 3602 1380 3603 1977 3603 1381 3603 1993 3604 1514 3604 1994 3604 1994 3605 1514 3605 1995 3605 1994 3606 1996 3606 1993 3606 1993 3607 1996 3607 1997 3607 1993 3608 1997 3608 1998 3608 1998 3609 1997 3609 1999 3609 1426 3610 1871 3610 2000 3610 2000 3611 1871 3611 2001 3611 2000 3612 2001 3612 2002 3612 1994 3613 2003 3613 1996 3613 1996 3614 2003 3614 2000 3614 1996 3615 2000 3615 1997 3615 1997 3616 2000 3616 2002 3616 1997 3617 2002 3617 1999 3617 1495 3618 2004 3618 1511 3618 1511 3619 2004 3619 1995 3619 1511 3620 1995 3620 1513 3620 1513 3621 1995 3621 1514 3621 2005 3622 2006 3622 2007 3622 2007 3623 2006 3623 2008 3623 1110 3624 2008 3624 1111 3624 1111 3625 2008 3625 2006 3625 1111 3626 2006 3626 1492 3626 1492 3627 2006 3627 2005 3627 1492 3628 2005 3628 1493 3628 1493 3629 2005 3629 1495 3629 2009 3630 2010 3630 2011 3630 1055 3631 1074 3631 2011 3631 2011 3632 1074 3632 2012 3632 2011 3633 2012 3633 2009 3633 2009 3634 2012 3634 2013 3634 2009 3635 2013 3635 2014 3635 2014 3636 2013 3636 2015 3636 2014 3637 2015 3637 2016 3637 1448 3638 2017 3638 1444 3638 1444 3639 2017 3639 2018 3639 1444 3640 2018 3640 1445 3640 1074 3641 1447 3641 2012 3641 2012 3642 1447 3642 1446 3642 2012 3643 1446 3643 2013 3643 2013 3644 1446 3644 1445 3644 2013 3645 1445 3645 2015 3645 2015 3646 1445 3646 2018 3646 2015 3647 2018 3647 2016 3647 1379 3648 2019 3648 1986 3648 1986 3649 2019 3649 2020 3649 2020 3650 2019 3650 2021 3650 2021 3651 2019 3651 2022 3651 2021 3652 2022 3652 2023 3652 2023 3653 2022 3653 2024 3653 2023 3654 2024 3654 2025 3654 2025 3655 2024 3655 2026 3655 2025 3656 2026 3656 2027 3656 1448 3657 1436 3657 2028 3657 2028 3658 1436 3658 1435 3658 2028 3659 1435 3659 2029 3659 2019 3660 2030 3660 2022 3660 2022 3661 2030 3661 2031 3661 2022 3662 2031 3662 2024 3662 2024 3663 2031 3663 2032 3663 2024 3664 2032 3664 2026 3664 2026 3665 2032 3665 2029 3665 2026 3666 2029 3666 2027 3666 2027 3667 2029 3667 1435 3667 1604 3668 1603 3668 2033 3668 2034 3669 2035 3669 2036 3669 2036 3670 2035 3670 2037 3670 2036 3671 2037 3671 2038 3671 2038 3672 2037 3672 2039 3672 2039 3673 2040 3673 2038 3673 2038 3674 2040 3674 1714 3674 2038 3675 1714 3675 1604 3675 1604 3676 2033 3676 2038 3676 2038 3677 2033 3677 2041 3677 2038 3678 2041 3678 2042 3678 2042 3679 2041 3679 1421 3679 2042 3680 1421 3680 1426 3680 1603 3681 1601 3681 2033 3681 2033 3682 1601 3682 1599 3682 2033 3683 1599 3683 2041 3683 2041 3684 1599 3684 1598 3684 2041 3685 1598 3685 1421 3685 1421 3686 1598 3686 1607 3686 1421 3687 1607 3687 1419 3687 1426 3688 2000 3688 2043 3688 2043 3689 2000 3689 2003 3689 2043 3690 2003 3690 1994 3690 2044 3691 2034 3691 2045 3691 2045 3692 2034 3692 2036 3692 2045 3693 2036 3693 2046 3693 2046 3694 2036 3694 2038 3694 2046 3695 2038 3695 2043 3695 2043 3696 2038 3696 2042 3696 2043 3697 2042 3697 1426 3697 2007 3698 2044 3698 2005 3698 2005 3699 2044 3699 2045 3699 2005 3700 2045 3700 1495 3700 2046 3701 1495 3701 2045 3701 1994 3702 1995 3702 2043 3702 2043 3703 1995 3703 2004 3703 2043 3704 2004 3704 2046 3704 2046 3705 2004 3705 1495 3705 2047 3706 1379 3706 1375 3706 2048 3707 2049 3707 2050 3707 2051 3708 2052 3708 2053 3708 2051 3709 2053 3709 2054 3709 2053 3710 1560 3710 2055 3710 2055 3711 1560 3711 1558 3711 2055 3712 1558 3712 2053 3712 2053 3713 1558 3713 1639 3713 2053 3714 1639 3714 2054 3714 2053 3715 2048 3715 1560 3715 1560 3716 2048 3716 2050 3716 1560 3717 2050 3717 1553 3717 1553 3718 2050 3718 1554 3718 2049 3719 2047 3719 2050 3719 2050 3720 2047 3720 1375 3720 2050 3721 1375 3721 1554 3721 1554 3722 1375 3722 1377 3722 2056 3723 2017 3723 1448 3723 2049 3724 2048 3724 2057 3724 2052 3725 2058 3725 2056 3725 2058 3726 2010 3726 2009 3726 2009 3727 2014 3727 2058 3727 2058 3728 2014 3728 2016 3728 2058 3729 2016 3729 2056 3729 2056 3730 2016 3730 2018 3730 2056 3731 2018 3731 2017 3731 2048 3732 2053 3732 2059 3732 2059 3733 2053 3733 2052 3733 2019 3734 1379 3734 2047 3734 2019 3735 2047 3735 2030 3735 2030 3736 2047 3736 2049 3736 2030 3737 2049 3737 2031 3737 2031 3738 2049 3738 2057 3738 2031 3739 2057 3739 2032 3739 1448 3740 2028 3740 2057 3740 2057 3741 2028 3741 2029 3741 2057 3742 2029 3742 2032 3742 2048 3743 2059 3743 2057 3743 2057 3744 2059 3744 1448 3744 2052 3745 2056 3745 2059 3745 2059 3746 2056 3746 1448 3746 1093 3747 1092 3747 2060 3747 2061 3748 1863 3748 1862 3748 2062 3749 2061 3749 2063 3749 2063 3750 2061 3750 2064 3750 2061 3751 1862 3751 2064 3751 2064 3752 1862 3752 1860 3752 2064 3753 1860 3753 2060 3753 1093 3754 2060 3754 1094 3754 2060 3755 1860 3755 1094 3755 1094 3756 1860 3756 1859 3756 1094 3757 1859 3757 1104 3757 1104 3758 1859 3758 1865 3758 1104 3759 1865 3759 1103 3759 1123 3760 1831 3760 1124 3760 2065 3761 2066 3761 2067 3761 2067 3762 2066 3762 2068 3762 2069 3763 1058 3763 1124 3763 1831 3764 1835 3764 1124 3764 1124 3765 1835 3765 1834 3765 1124 3766 1834 3766 2069 3766 2069 3767 1834 3767 1833 3767 2069 3768 1833 3768 2065 3768 2065 3769 1833 3769 1832 3769 2065 3770 1832 3770 2066 3770 2070 3771 2034 3771 2071 3771 2071 3772 2034 3772 2044 3772 2071 3773 2044 3773 2072 3773 2072 3774 2044 3774 2073 3774 2072 3775 2073 3775 2074 3775 2074 3776 2073 3776 2075 3776 2076 3777 2067 3777 2068 3777 2068 3778 2075 3778 2076 3778 2076 3779 2075 3779 2073 3779 2076 3780 2073 3780 2007 3780 2007 3781 2073 3781 2044 3781 2076 3782 2007 3782 2008 3782 1059 3783 1058 3783 2077 3783 2077 3784 1058 3784 2069 3784 2077 3785 2069 3785 2065 3785 1110 3786 1059 3786 2008 3786 2008 3787 1059 3787 2077 3787 2008 3788 2077 3788 2076 3788 2076 3789 2077 3789 2065 3789 2076 3790 2065 3790 2067 3790 2064 3791 2060 3791 2078 3791 1055 3792 2011 3792 2078 3792 1055 3793 2078 3793 1056 3793 1056 3794 2078 3794 2060 3794 1056 3795 2060 3795 1092 3795 2011 3796 2010 3796 2078 3796 2078 3797 2010 3797 2079 3797 2078 3798 2079 3798 2064 3798 2064 3799 2079 3799 2063 3799 2079 3800 2010 3800 2058 3800 2062 3801 2063 3801 2079 3801 2080 3802 2081 3802 2082 3802 2082 3803 2081 3803 2083 3803 2082 3804 2083 3804 2084 3804 2058 3805 2052 3805 2085 3805 2085 3806 2080 3806 2058 3806 2058 3807 2080 3807 2082 3807 2058 3808 2082 3808 2079 3808 2079 3809 2082 3809 2084 3809 2079 3810 2084 3810 2062 3810 2051 3811 2085 3811 2052 3811 2054 3812 2086 3812 2051 3812 2054 3813 1639 3813 1638 3813 2086 3814 2054 3814 2087 3814 2085 3815 2051 3815 2080 3815 2054 3816 1638 3816 2087 3816 2087 3817 1638 3817 1690 3817 2087 3818 1690 3818 2088 3818 2088 3819 1690 3819 1663 3819 2088 3820 1663 3820 2089 3820 2089 3821 1663 3821 1662 3821 2089 3822 1662 3822 2090 3822 2051 3823 2086 3823 2080 3823 2080 3824 2086 3824 2087 3824 2080 3825 2087 3825 2081 3825 2081 3826 2087 3826 2088 3826 2081 3827 2088 3827 2083 3827 2083 3828 2088 3828 2089 3828 2083 3829 2089 3829 2084 3829 2084 3830 2089 3830 2090 3830 2084 3831 2090 3831 2062 3831 2091 3832 1661 3832 1644 3832 1644 3833 2092 3833 2091 3833 2091 3834 2092 3834 2093 3834 2091 3835 2093 3835 2061 3835 2061 3836 2093 3836 2094 3836 2061 3837 2094 3837 1863 3837 1662 3838 1661 3838 2090 3838 2090 3839 1661 3839 2091 3839 2090 3840 2091 3840 2062 3840 2062 3841 2091 3841 2061 3841 1654 3842 1652 3842 2095 3842 1824 3843 1823 3843 2096 3843 1824 3844 2096 3844 1858 3844 2097 3845 2098 3845 2099 3845 2100 3846 2095 3846 1652 3846 2100 3847 1652 3847 1650 3847 2100 3848 2098 3848 2095 3848 2095 3849 2098 3849 2097 3849 2095 3850 2097 3850 2101 3850 2101 3851 1647 3851 1641 3851 2101 3852 1641 3852 2095 3852 2095 3853 1641 3853 1640 3853 2095 3854 1640 3854 1654 3854 1864 3855 1861 3855 2102 3855 2102 3856 1861 3856 2103 3856 2102 3857 2103 3857 2104 3857 1823 3858 1864 3858 2096 3858 2096 3859 1864 3859 2102 3859 2096 3860 2102 3860 2105 3860 2105 3861 2102 3861 2104 3861 2105 3862 2104 3862 2106 3862 1643 3863 1647 3863 2106 3863 2106 3864 1647 3864 2101 3864 2106 3865 2101 3865 2105 3865 2105 3866 2101 3866 2097 3866 2105 3867 2097 3867 2096 3867 2096 3868 2097 3868 2099 3868 2096 3869 2099 3869 1858 3869 1644 3870 1643 3870 2092 3870 2092 3871 1643 3871 2106 3871 2092 3872 2106 3872 2093 3872 2093 3873 2106 3873 2104 3873 2093 3874 2104 3874 2094 3874 2094 3875 2104 3875 2103 3875 2094 3876 2103 3876 1863 3876 1863 3877 2103 3877 1861 3877 2107 3878 2108 3878 2109 3878 2110 3879 2111 3879 2112 3879 2113 3880 2114 3880 2115 3880 2116 3881 1839 3881 1838 3881 2116 3882 1838 3882 2114 3882 2110 3883 2112 3883 2117 3883 2114 3884 1838 3884 2115 3884 2115 3885 1838 3885 1837 3885 2115 3886 1837 3886 2118 3886 2118 3887 1837 3887 1836 3887 2118 3888 1836 3888 2119 3888 2119 3889 1836 3889 1844 3889 2119 3890 1844 3890 2120 3890 2120 3891 1844 3891 1843 3891 2120 3892 1843 3892 1842 3892 1841 3893 2121 3893 1842 3893 1842 3894 2121 3894 2122 3894 1842 3895 2122 3895 2120 3895 1841 3896 1848 3896 2121 3896 2121 3897 1848 3897 1847 3897 2121 3898 1847 3898 2123 3898 2123 3899 1847 3899 1846 3899 2123 3900 1846 3900 2124 3900 2124 3901 1846 3901 1845 3901 2124 3902 1845 3902 2125 3902 1845 3903 1850 3903 2125 3903 2125 3904 1850 3904 1849 3904 2125 3905 1849 3905 2126 3905 2126 3906 1849 3906 1854 3906 2126 3907 1854 3907 2127 3907 2127 3908 1854 3908 1853 3908 2127 3909 1853 3909 2128 3909 2128 3910 1853 3910 1852 3910 1851 3911 2129 3911 1852 3911 1852 3912 2129 3912 2130 3912 1852 3913 2130 3913 2128 3913 1851 3914 1857 3914 2129 3914 2129 3915 1857 3915 1856 3915 2129 3916 1856 3916 2131 3916 2111 3917 2113 3917 2112 3917 2112 3918 2113 3918 2115 3918 2112 3919 2115 3919 2132 3919 2132 3920 2115 3920 2118 3920 2132 3921 2118 3921 2133 3921 2133 3922 2118 3922 2119 3922 2133 3923 2119 3923 2134 3923 2134 3924 2119 3924 2120 3924 2134 3925 2120 3925 2135 3925 2135 3926 2120 3926 2122 3926 2135 3927 2122 3927 2136 3927 2136 3928 2122 3928 2121 3928 2136 3929 2121 3929 2137 3929 2137 3930 2121 3930 2123 3930 2137 3931 2123 3931 2138 3931 2138 3932 2123 3932 2124 3932 2138 3933 2124 3933 2139 3933 2139 3934 2124 3934 2125 3934 2139 3935 2125 3935 2140 3935 2140 3936 2125 3936 2126 3936 2140 3937 2126 3937 2141 3937 2141 3938 2126 3938 2127 3938 2141 3939 2127 3939 2142 3939 2142 3940 2127 3940 2128 3940 2142 3941 2128 3941 2143 3941 2143 3942 2128 3942 2130 3942 2143 3943 2130 3943 2144 3943 2144 3944 2130 3944 2129 3944 2144 3945 2129 3945 2145 3945 2145 3946 2129 3946 2131 3946 2145 3947 2131 3947 2146 3947 1825 3948 2108 3948 1826 3948 1826 3949 2108 3949 2107 3949 1826 3950 2107 3950 1855 3950 2147 3951 2117 3951 2148 3951 2148 3952 2117 3952 2112 3952 2148 3953 2112 3953 2149 3953 2149 3954 2112 3954 2132 3954 2149 3955 2132 3955 2150 3955 2150 3956 2132 3956 2133 3956 2150 3957 2133 3957 2151 3957 2151 3958 2133 3958 2134 3958 2151 3959 2134 3959 2152 3959 2152 3960 2134 3960 2135 3960 2152 3961 2135 3961 2153 3961 2153 3962 2135 3962 2136 3962 2153 3963 2136 3963 2154 3963 2154 3964 2136 3964 2137 3964 2154 3965 2137 3965 2155 3965 2155 3966 2137 3966 2138 3966 2155 3967 2138 3967 2156 3967 2156 3968 2138 3968 2139 3968 2156 3969 2139 3969 2157 3969 2157 3970 2139 3970 2140 3970 2157 3971 2140 3971 2158 3971 2158 3972 2140 3972 2141 3972 2158 3973 2141 3973 2159 3973 2159 3974 2141 3974 2142 3974 2159 3975 2142 3975 2160 3975 2160 3976 2142 3976 2143 3976 2160 3977 2143 3977 2161 3977 2161 3978 2143 3978 2144 3978 2161 3979 2144 3979 2162 3979 2162 3980 2144 3980 2145 3980 2162 3981 2145 3981 2163 3981 2163 3982 2145 3982 2146 3982 2163 3983 2146 3983 2164 3983 1691 3984 2147 3984 1692 3984 1692 3985 2147 3985 2148 3985 1692 3986 2148 3986 1752 3986 1752 3987 2148 3987 2149 3987 1752 3988 2149 3988 1751 3988 1751 3989 2149 3989 2150 3989 1751 3990 2150 3990 1774 3990 1774 3991 2150 3991 2151 3991 1774 3992 2151 3992 1773 3992 1773 3993 2151 3993 2152 3993 1773 3994 2152 3994 1772 3994 1772 3995 2152 3995 2153 3995 1772 3996 2153 3996 1771 3996 1771 3997 2153 3997 2154 3997 1771 3998 2154 3998 1769 3998 1769 3999 2154 3999 2155 3999 1769 4000 2155 4000 1767 4000 1767 4001 2155 4001 2156 4001 1767 4002 2156 4002 1765 4002 1765 4003 2156 4003 2157 4003 1765 4004 2157 4004 1763 4004 1763 4005 2157 4005 2158 4005 1763 4006 2158 4006 1761 4006 1761 4007 2158 4007 2159 4007 1761 4008 2159 4008 1759 4008 1759 4009 2159 4009 2160 4009 1759 4010 2160 4010 1757 4010 1757 4011 2160 4011 2161 4011 1757 4012 2161 4012 1756 4012 1756 4013 2161 4013 2162 4013 1756 4014 2162 4014 1755 4014 1755 4015 2162 4015 2163 4015 1755 4016 2163 4016 1754 4016 1754 4017 2163 4017 2164 4017 1754 4018 2164 4018 1753 4018 1753 4019 2164 4019 2100 4019 1753 4020 2100 4020 1650 4020 1825 4021 1858 4021 2108 4021 2108 4022 1858 4022 2099 4022 2108 4023 2099 4023 2109 4023 2109 4024 2099 4024 2098 4024 1856 4025 1855 4025 2131 4025 2131 4026 1855 4026 2107 4026 2131 4027 2107 4027 2146 4027 2146 4028 2107 4028 2109 4028 2146 4029 2109 4029 2164 4029 2164 4030 2109 4030 2098 4030 2164 4031 2098 4031 2100 4031 2165 4032 2166 4032 2167 4032 2147 4033 1691 4033 1700 4033 2111 4034 2110 4034 2168 4034 2168 4035 2110 4035 2117 4035 2168 4036 2117 4036 2147 4036 2114 4037 2113 4037 2169 4037 1840 4038 1839 4038 2116 4038 2147 4039 1700 4039 2168 4039 2168 4040 1700 4040 1699 4040 2168 4041 1699 4041 2170 4041 2170 4042 1699 4042 1697 4042 2170 4043 1697 4043 2171 4043 2171 4044 1697 4044 1696 4044 2171 4045 1696 4045 2172 4045 1696 4046 1702 4046 2172 4046 2172 4047 1702 4047 1704 4047 2172 4048 1704 4048 2173 4048 2173 4049 1704 4049 1703 4049 1703 4050 2174 4050 2173 4050 2173 4051 2174 4051 2175 4051 2173 4052 2175 4052 2172 4052 2172 4053 2175 4053 2176 4053 2172 4054 2176 4054 2171 4054 2171 4055 2176 4055 2177 4055 2171 4056 2177 4056 2170 4056 2170 4057 2177 4057 2178 4057 2170 4058 2178 4058 2168 4058 2168 4059 2178 4059 2169 4059 2168 4060 2169 4060 2111 4060 2111 4061 2169 4061 2113 4061 2174 4062 2165 4062 2175 4062 2175 4063 2165 4063 2167 4063 2175 4064 2167 4064 2176 4064 2176 4065 2167 4065 2179 4065 2176 4066 2179 4066 2177 4066 2177 4067 2179 4067 2180 4067 2177 4068 2180 4068 2178 4068 2178 4069 2180 4069 2181 4069 2178 4070 2181 4070 2169 4070 2169 4071 2181 4071 2182 4071 2169 4072 2182 4072 2114 4072 2114 4073 2182 4073 2116 4073 2116 4074 2182 4074 1840 4074 1840 4075 2182 4075 2181 4075 1840 4076 2181 4076 1827 4076 1827 4077 2181 4077 2180 4077 1827 4078 2180 4078 1828 4078 1828 4079 2180 4079 2179 4079 1828 4080 2179 4080 1829 4080 1829 4081 2179 4081 2167 4081 1829 4082 2167 4082 1830 4082 1830 4083 2167 4083 2166 4083 1830 4084 2166 4084 1832 4084 2183 4085 1708 4085 1712 4085 2184 4086 2068 4086 2066 4086 1832 4087 2166 4087 2066 4087 2066 4088 2166 4088 2183 4088 2066 4089 2183 4089 2184 4089 2184 4090 2183 4090 1712 4090 1703 4091 1708 4091 2174 4091 2174 4092 1708 4092 2183 4092 2174 4093 2183 4093 2165 4093 2165 4094 2183 4094 2166 4094 2039 4095 2185 4095 2040 4095 2034 4096 2070 4096 2035 4096 2035 4097 2070 4097 2037 4097 2037 4098 2070 4098 2039 4098 2039 4099 2070 4099 2071 4099 2039 4100 2071 4100 2185 4100 2185 4101 2071 4101 2072 4101 2185 4102 2072 4102 2186 4102 2186 4103 2072 4103 2074 4103 2186 4104 2074 4104 2187 4104 2187 4105 2074 4105 2075 4105 2187 4106 2075 4106 2188 4106 2188 4107 2075 4107 2068 4107 2188 4108 2068 4108 2184 4108 2040 4109 2185 4109 1714 4109 1714 4110 2185 4110 2186 4110 1714 4111 2186 4111 1713 4111 1713 4112 2186 4112 2187 4112 1713 4113 2187 4113 1709 4113 1709 4114 2187 4114 2188 4114 1709 4115 2188 4115 1710 4115 1710 4116 2188 4116 2184 4116 1710 4117 2184 4117 1712 4117 1514 4118 1993 4118 2189 4118 2189 4119 1993 4119 1998 4119 2189 4120 1998 4120 2190 4120 1866 4121 2191 4121 1867 4121 1867 4122 2191 4122 1872 4122 2190 4123 1998 4123 2192 4123 2192 4124 1998 4124 1999 4124 2192 4125 1999 4125 2193 4125 1999 4126 2002 4126 2193 4126 2193 4127 2002 4127 2001 4127 2193 4128 2001 4128 2194 4128 2194 4129 2001 4129 1871 4129 1871 4130 1870 4130 2194 4130 2194 4131 1870 4131 1869 4131 2194 4132 1869 4132 2193 4132 2193 4133 1869 4133 1872 4133 2193 4134 1872 4134 2192 4134 2192 4135 1872 4135 2191 4135 2192 4136 2191 4136 2190 4136 1874 4137 1880 4137 2195 4137 1508 4138 1507 4138 2196 4138 1499 4139 1498 4139 2197 4139 2197 4140 1498 4140 2198 4140 1508 4141 2196 4141 1502 4141 1498 4142 1502 4142 2198 4142 2198 4143 1502 4143 2196 4143 2198 4144 2196 4144 2199 4144 2199 4145 2196 4145 2200 4145 2199 4146 2200 4146 2201 4146 2201 4147 2200 4147 2202 4147 2202 4148 2200 4148 2203 4148 2202 4149 2203 4149 2204 4149 1879 4150 1877 4150 2203 4150 2203 4151 1877 4151 2205 4151 2203 4152 2205 4152 2204 4152 1506 4153 1510 4153 2206 4153 2206 4154 1510 4154 1509 4154 2206 4155 1509 4155 1515 4155 1880 4156 1879 4156 2195 4156 2195 4157 1879 4157 2203 4157 2195 4158 2203 4158 2207 4158 2207 4159 2203 4159 2200 4159 2207 4160 2200 4160 2206 4160 2206 4161 2200 4161 2196 4161 2206 4162 2196 4162 1506 4162 1506 4163 2196 4163 1507 4163 1875 4164 1874 4164 2208 4164 2208 4165 1874 4165 2195 4165 2208 4166 2195 4166 2209 4166 2209 4167 2195 4167 2207 4167 2209 4168 2207 4168 2210 4168 2210 4169 2207 4169 2206 4169 2210 4170 2206 4170 1512 4170 1512 4171 2206 4171 1515 4171 1866 4172 1875 4172 2191 4172 2191 4173 1875 4173 2208 4173 2191 4174 2208 4174 2190 4174 2190 4175 2208 4175 2209 4175 2190 4176 2209 4176 2189 4176 2189 4177 2209 4177 2210 4177 2189 4178 2210 4178 1514 4178 1514 4179 2210 4179 1512 4179 2211 4180 2212 4180 2213 4180 2213 4181 2212 4181 2214 4181 2213 4182 2214 4182 2215 4182 1876 4183 1490 4183 2216 4183 2216 4184 1490 4184 2217 4184 2216 4185 2217 4185 2218 4185 1499 4186 2212 4186 1525 4186 1525 4187 2212 4187 2211 4187 1525 4188 2211 4188 1526 4188 2199 4189 2214 4189 2198 4189 2198 4190 2214 4190 2212 4190 2198 4191 2212 4191 2197 4191 2197 4192 2212 4192 1499 4192 2199 4193 2201 4193 2214 4193 2214 4194 2201 4194 2218 4194 2214 4195 2218 4195 2215 4195 2215 4196 2218 4196 2217 4196 1877 4197 1876 4197 2205 4197 2205 4198 1876 4198 2216 4198 2205 4199 2216 4199 2204 4199 2204 4200 2216 4200 2218 4200 2204 4201 2218 4201 2202 4201 2202 4202 2218 4202 2201 4202 1491 4203 1325 4203 2219 4203 2219 4204 1325 4204 2220 4204 2219 4205 2220 4205 2221 4205 2221 4206 2220 4206 2222 4206 2221 4207 2222 4207 2223 4207 2223 4208 2222 4208 2224 4208 2223 4209 2224 4209 2225 4209 2225 4210 2224 4210 2226 4210 2225 4211 2226 4211 1528 4211 1528 4212 2226 4212 1529 4212 1490 4213 1491 4213 2217 4213 2217 4214 1491 4214 2219 4214 2217 4215 2219 4215 2215 4215 2215 4216 2219 4216 2221 4216 2215 4217 2221 4217 2213 4217 2213 4218 2221 4218 2223 4218 2213 4219 2223 4219 2211 4219 2211 4220 2223 4220 2225 4220 2211 4221 2225 4221 1526 4221 1526 4222 2225 4222 1528 4222 1349 4223 1351 4223 2227 4223 2228 4224 2229 4224 2230 4224 2230 4225 2229 4225 2231 4225 2230 4226 2231 4226 1539 4226 1539 4227 2231 4227 1 4227 1353 4228 1355 4228 2232 4228 2232 4229 1355 4229 2233 4229 2232 4230 2233 4230 2234 4230 2234 4231 2233 4231 2235 4231 2234 4232 2235 4232 2228 4232 2228 4233 2235 4233 2236 4233 2228 4234 2236 4234 2229 4234 1351 4235 1353 4235 2227 4235 2227 4236 1353 4236 2232 4236 2227 4237 2232 4237 2237 4237 2237 4238 2232 4238 2234 4238 2237 4239 2234 4239 2238 4239 2238 4240 2234 4240 2228 4240 2238 4241 2228 4241 2239 4241 2239 4242 2228 4242 2230 4242 2239 4243 2230 4243 1540 4243 1540 4244 2230 4244 1539 4244 1347 4245 1349 4245 2240 4245 2240 4246 1349 4246 2227 4246 2240 4247 2227 4247 2241 4247 2241 4248 2227 4248 2237 4248 2241 4249 2237 4249 2242 4249 2242 4250 2237 4250 2238 4250 2242 4251 2238 4251 2243 4251 2243 4252 2238 4252 2239 4252 2243 4253 2239 4253 1541 4253 1541 4254 2239 4254 1540 4254 1346 4255 1347 4255 2244 4255 2244 4256 1347 4256 2240 4256 2244 4257 2240 4257 2245 4257 2245 4258 2240 4258 2241 4258 2245 4259 2241 4259 2246 4259 2246 4260 2241 4260 2242 4260 2246 4261 2242 4261 2247 4261 2247 4262 2242 4262 2243 4262 2247 4263 2243 4263 1543 4263 1543 4264 2243 4264 1541 4264 1543 4265 1544 4265 2247 4265 2247 4266 1544 4266 2248 4266 2247 4267 2248 4267 2246 4267 2246 4268 2248 4268 2249 4268 2246 4269 2249 4269 2245 4269 2245 4270 2249 4270 2250 4270 2245 4271 2250 4271 2244 4271 2244 4272 2250 4272 2251 4272 2244 4273 2251 4273 1346 4273 1340 4274 1341 4274 2251 4274 2251 4275 1341 4275 1344 4275 2251 4276 1344 4276 1346 4276 1546 4277 1547 4277 2252 4277 2252 4278 1547 4278 2253 4278 2252 4279 2253 4279 2254 4279 2254 4280 2253 4280 2255 4280 2254 4281 2255 4281 2256 4281 2256 4282 2255 4282 2257 4282 2256 4283 2257 4283 2258 4283 2258 4284 2257 4284 2259 4284 1547 4285 1549 4285 2253 4285 2253 4286 1549 4286 2260 4286 2253 4287 2260 4287 2255 4287 2255 4288 2260 4288 2261 4288 2255 4289 2261 4289 2257 4289 2257 4290 2261 4290 2262 4290 2257 4291 2262 4291 2259 4291 2259 4292 2262 4292 2263 4292 1544 4293 1546 4293 2248 4293 2248 4294 1546 4294 2252 4294 2248 4295 2252 4295 2249 4295 2249 4296 2252 4296 2254 4296 2249 4297 2254 4297 2250 4297 2250 4298 2254 4298 2256 4298 2250 4299 2256 4299 2251 4299 2251 4300 2256 4300 2258 4300 2251 4301 2258 4301 1340 4301 1340 4302 2258 4302 2259 4302 1340 4303 2259 4303 1338 4303 1338 4304 2259 4304 2263 4304 1332 4305 1334 4305 2263 4305 2263 4306 1334 4306 1336 4306 2263 4307 1336 4307 1338 4307 1552 4308 1551 4308 2264 4308 2264 4309 1551 4309 2265 4309 2264 4310 2265 4310 2266 4310 2266 4311 2265 4311 2267 4311 2266 4312 2267 4312 2268 4312 2268 4313 2267 4313 2269 4313 2268 4314 2269 4314 2270 4314 2270 4315 2269 4315 2271 4315 1549 4316 1552 4316 2260 4316 2260 4317 1552 4317 2264 4317 2260 4318 2264 4318 2261 4318 2261 4319 2264 4319 2266 4319 2261 4320 2266 4320 2262 4320 2262 4321 2266 4321 2268 4321 2262 4322 2268 4322 2263 4322 2263 4323 2268 4323 2270 4323 2263 4324 2270 4324 1332 4324 1332 4325 2270 4325 2271 4325 1332 4326 2271 4326 1321 4326 1321 4327 2271 4327 1322 4327 1551 4328 1550 4328 2265 4328 2265 4329 1550 4329 2272 4329 2265 4330 2272 4330 2267 4330 2267 4331 2272 4331 2273 4331 2267 4332 2273 4332 2269 4332 2269 4333 2273 4333 2274 4333 2269 4334 2274 4334 2271 4334 2271 4335 2274 4335 2275 4335 2271 4336 2275 4336 1322 4336 1322 4337 2275 4337 1324 4337 1327 4338 1324 4338 2276 4338 2276 4339 1324 4339 2275 4339 2276 4340 2275 4340 2277 4340 2277 4341 2275 4341 2274 4341 2277 4342 2274 4342 2278 4342 2278 4343 2274 4343 2273 4343 2278 4344 2273 4344 2279 4344 2279 4345 2273 4345 2272 4345 2279 4346 2272 4346 1530 4346 1530 4347 2272 4347 1550 4347 1325 4348 1327 4348 2220 4348 2220 4349 1327 4349 2276 4349 2220 4350 2276 4350 2222 4350 2222 4351 2276 4351 2277 4351 2222 4352 2277 4352 2224 4352 2224 4353 2277 4353 2278 4353 2224 4354 2278 4354 2226 4354 2226 4355 2278 4355 2279 4355 2226 4356 2279 4356 1529 4356 1529 4357 2279 4357 1530 4357 2 4358 1 4358 2280 4358 2280 4359 1 4359 2231 4359 2280 4360 2231 4360 2281 4360 2281 4361 2231 4361 2229 4361 2281 4362 2229 4362 2282 4362 2229 4363 2236 4363 2282 4363 2282 4364 2236 4364 2235 4364 2282 4365 2235 4365 2283 4365 2283 4366 2235 4366 2284 4366 2235 4367 2233 4367 2284 4367 2284 4368 2233 4368 1355 4368 2284 4369 1355 4369 1356 4369 3 4370 2 4370 2285 4370 2285 4370 2 4370 2280 4370 2285 4371 2280 4371 2286 4371 2286 4371 2280 4371 2281 4371 2286 4372 2281 4372 2287 4372 2287 4373 2281 4373 2282 4373 2287 4374 2282 4374 2288 4374 2288 4374 2282 4374 2283 4374 2288 4375 2283 4375 2289 4375 2289 4376 2283 4376 2284 4376 2289 4377 2284 4377 1283 4377 1283 4377 2284 4377 1356 4377 4 4378 3 4378 2290 4378 2290 4379 3 4379 2285 4379 2290 4380 2285 4380 2291 4380 2291 4381 2285 4381 2286 4381 2291 4382 2286 4382 2292 4382 2292 4383 2286 4383 2287 4383 2292 4384 2287 4384 2293 4384 2293 4385 2287 4385 2288 4385 2293 4386 2288 4386 2294 4386 2288 4387 2289 4387 2294 4387 2294 4388 2289 4388 1283 4388 2294 4389 1283 4389 1285 4389 2295 4390 1470 4390 1469 4390 2296 4391 2297 4391 2298 4391 2299 4392 2296 4392 2300 4392 2301 4393 1314 4393 2302 4393 2302 4394 1314 4394 1312 4394 2302 4395 1312 4395 2299 4395 2303 4396 1308 4396 2304 4396 2304 4397 1308 4397 1310 4397 2304 4398 1310 4398 2305 4398 2305 4399 1310 4399 1318 4399 2305 4400 1318 4400 2301 4400 2301 4401 1318 4401 1316 4401 2301 4402 1316 4402 1314 4402 2306 4403 1300 4403 2307 4403 2307 4404 1300 4404 1302 4404 2307 4405 1302 4405 2308 4405 2308 4406 1302 4406 1304 4406 2308 4407 1304 4407 2303 4407 2303 4408 1304 4408 1306 4408 2303 4409 1306 4409 1308 4409 2296 4410 2298 4410 2300 4410 2300 4411 2298 4411 2309 4411 2300 4412 2309 4412 2310 4412 2310 4413 2309 4413 2311 4413 2310 4414 2311 4414 2312 4414 2312 4415 2311 4415 2313 4415 2312 4416 2313 4416 2314 4416 2314 4417 2313 4417 2315 4417 2314 4418 2315 4418 2316 4418 2316 4419 2315 4419 2317 4419 2316 4420 2317 4420 2318 4420 2318 4421 2317 4421 2319 4421 2318 4422 2319 4422 2320 4422 2320 4423 2319 4423 2321 4423 2320 4424 2321 4424 2322 4424 2322 4425 2321 4425 2323 4425 2322 4426 2323 4426 2324 4426 2324 4427 2323 4427 2325 4427 2324 4428 2325 4428 2326 4428 2326 4429 2325 4429 2327 4429 2326 4430 2327 4430 2328 4430 2299 4431 2300 4431 2302 4431 2302 4432 2300 4432 2310 4432 2302 4433 2310 4433 2301 4433 2301 4434 2310 4434 2312 4434 2301 4435 2312 4435 2305 4435 2305 4436 2312 4436 2314 4436 2305 4437 2314 4437 2304 4437 2304 4438 2314 4438 2316 4438 2304 4439 2316 4439 2303 4439 2303 4440 2316 4440 2318 4440 2303 4441 2318 4441 2308 4441 2308 4442 2318 4442 2320 4442 2308 4443 2320 4443 2307 4443 2307 4444 2320 4444 2322 4444 2307 4445 2322 4445 2306 4445 2306 4446 2322 4446 2324 4446 2306 4447 2324 4447 2329 4447 2329 4448 2324 4448 2326 4448 2329 4449 2326 4449 2330 4449 2330 4450 2326 4450 2328 4450 2330 4451 2328 4451 2331 4451 1288 4452 1291 4452 2331 4452 2331 4453 1291 4453 1293 4453 2331 4454 1293 4454 2330 4454 2330 4455 1293 4455 1294 4455 2330 4456 1294 4456 2329 4456 2329 4457 1294 4457 1296 4457 2329 4458 1296 4458 2306 4458 2306 4459 1296 4459 1298 4459 2306 4460 1298 4460 1300 4460 2327 4461 2332 4461 2328 4461 2328 4462 2332 4462 2333 4462 2328 4463 2333 4463 2331 4463 2331 4464 2333 4464 2334 4464 2331 4465 2334 4465 1288 4465 1288 4466 2334 4466 1287 4466 2295 4467 1469 4467 2335 4467 2335 4468 1469 4468 1465 4468 2335 4469 1465 4469 2336 4469 2336 4470 1465 4470 1464 4470 2336 4471 1464 4471 2337 4471 2337 4472 1464 4472 1476 4472 2337 4473 1476 4473 2338 4473 2338 4474 1476 4474 1475 4474 2338 4475 1475 4475 2339 4475 2339 4476 1475 4476 1474 4476 2339 4477 1474 4477 2340 4477 2340 4478 1474 4478 1462 4478 2340 4479 1462 4479 2341 4479 2341 4480 1462 4480 1461 4480 2341 4481 1461 4481 2342 4481 2342 4482 1461 4482 1482 4482 2342 4483 1482 4483 2343 4483 2343 4484 1482 4484 1481 4484 2343 4485 1481 4485 2344 4485 2344 4486 1481 4486 1480 4486 2344 4487 1480 4487 2345 4487 2345 4488 1480 4488 1479 4488 2345 4489 1479 4489 2346 4489 2346 4490 1479 4490 4 4490 2346 4491 4 4491 2290 4491 2290 4492 2332 4492 2346 4492 2346 4493 2332 4493 2327 4493 2346 4494 2327 4494 2345 4494 2345 4495 2327 4495 2325 4495 2345 4496 2325 4496 2344 4496 2344 4497 2325 4497 2323 4497 2344 4498 2323 4498 2343 4498 2343 4499 2323 4499 2321 4499 2343 4500 2321 4500 2342 4500 2342 4501 2321 4501 2319 4501 2342 4502 2319 4502 2341 4502 2341 4503 2319 4503 2317 4503 2341 4504 2317 4504 2340 4504 2340 4505 2317 4505 2315 4505 2340 4506 2315 4506 2339 4506 2339 4507 2315 4507 2313 4507 2339 4508 2313 4508 2338 4508 2338 4509 2313 4509 2311 4509 2338 4510 2311 4510 2337 4510 2337 4511 2311 4511 2309 4511 2337 4512 2309 4512 2336 4512 2336 4513 2309 4513 2298 4513 2336 4514 2298 4514 2335 4514 2335 4515 2298 4515 2297 4515 2335 4516 2297 4516 2295 4516 1285 4517 1287 4517 2294 4517 2294 4518 1287 4518 2334 4518 2294 4519 2334 4519 2293 4519 2293 4520 2334 4520 2333 4520 2293 4521 2333 4521 2292 4521 2292 4522 2333 4522 2332 4522 2292 4523 2332 4523 2291 4523 2291 4524 2332 4524 2290 4524 1449 4525 1450 4525 2347 4525 2347 4526 1450 4526 2348 4526 2347 4527 2348 4527 2349 4527 2349 4528 2348 4528 2350 4528 2349 4529 2350 4529 2351 4529 2351 4530 2350 4530 2352 4530 2351 4531 2352 4531 2353 4531 2353 4532 2352 4532 2354 4532 2353 4533 2354 4533 1471 4533 1471 4534 2354 4534 1472 4534 1312 4535 1449 4535 2299 4535 2299 4536 1449 4536 2347 4536 2299 4537 2347 4537 2296 4537 2296 4538 2347 4538 2349 4538 2296 4539 2349 4539 2297 4539 2297 4540 2349 4540 2351 4540 2297 4541 2351 4541 2295 4541 2295 4542 2351 4542 2353 4542 2295 4543 2353 4543 1470 4543 1470 4544 2353 4544 1471 4544 2355 4545 1989 4545 1982 4545 1430 4546 1467 4546 2356 4546 2356 4547 1467 4547 2357 4547 2356 4548 2357 4548 2358 4548 2358 4549 2357 4549 2359 4549 2358 4550 2359 4550 2360 4550 2360 4551 2359 4551 2361 4551 2360 4552 2361 4552 2362 4552 2362 4553 2361 4553 2355 4553 2362 4554 2355 4554 2363 4554 2363 4555 2355 4555 1982 4555 1450 4556 1989 4556 2348 4556 2348 4557 1989 4557 2355 4557 2348 4558 2355 4558 2350 4558 2350 4559 2355 4559 2361 4559 2350 4560 2361 4560 2352 4560 2352 4561 2361 4561 2359 4561 2352 4562 2359 4562 2354 4562 2354 4563 2359 4563 2357 4563 2354 4564 2357 4564 1472 4564 1472 4565 2357 4565 1467 4565 2364 4566 2365 4566 2366 4566 2367 4567 2364 4567 2368 4567 1984 4568 2367 4568 2369 4568 1984 4569 2369 4569 1985 4569 1985 4570 2369 4570 2370 4570 1985 4571 2370 4571 1990 4571 2364 4572 2366 4572 2368 4572 2368 4573 2366 4573 2371 4573 2368 4574 2371 4574 2372 4574 2372 4575 2371 4575 2373 4575 2372 4576 2373 4576 2374 4576 2374 4577 2373 4577 2375 4577 2374 4578 2375 4578 2376 4578 2367 4579 2368 4579 2369 4579 2369 4580 2368 4580 2372 4580 2369 4581 2372 4581 2370 4581 2370 4582 2372 4582 2374 4582 2370 4583 2374 4583 2377 4583 2377 4584 2374 4584 2376 4584 2377 4585 2376 4585 2378 4585 1430 4586 2375 4586 1431 4586 1431 4587 2375 4587 2373 4587 1431 4588 2373 4588 1432 4588 1432 4589 2373 4589 2371 4589 1432 4590 2371 4590 1434 4590 1434 4591 2371 4591 2366 4591 1434 4592 2366 4592 1437 4592 1437 4593 2366 4593 2365 4593 1437 4594 2365 4594 1435 4594 1430 4595 2356 4595 2375 4595 2375 4596 2356 4596 2358 4596 2375 4597 2358 4597 2376 4597 2376 4598 2358 4598 2360 4598 2376 4599 2360 4599 2378 4599 2378 4600 2360 4600 2362 4600 2378 4601 2362 4601 2363 4601 1990 4602 2370 4602 1991 4602 1991 4603 2370 4603 2377 4603 1991 4604 2377 4604 1992 4604 1992 4605 2377 4605 2378 4605 1992 4606 2378 4606 1979 4606 1979 4607 2378 4607 2363 4607 1979 4608 2363 4608 1982 4608 1987 4609 2367 4609 1988 4609 1988 4610 2367 4610 1984 4610 2365 4611 2021 4611 2023 4611 2023 4612 2025 4612 2365 4612 2365 4613 2025 4613 2027 4613 2365 4614 2027 4614 1435 4614 1986 4615 2379 4615 1987 4615 1987 4616 2379 4616 2364 4616 1987 4617 2364 4617 2367 4617 2365 4618 2364 4618 2021 4618 2021 4619 2364 4619 2379 4619 2021 4620 2379 4620 2020 4620 2020 4621 2379 4621 1986 4621

+
+
+
+
+ + + + 0.00100001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + -0.2908648 -0.7711008 0.5663932 4.076245 0.9551711 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054209 -0.6141704 -6.925791 -4.01133e-9 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_middle/th_middle_C6M2.dae b/URDFs/sr_description/meshes/components/th_middle/th_middle_C6M2.dae new file mode 100644 index 0000000..df463ac --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_middle/th_middle_C6M2.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:04.601049 + 2012-07-23T02:14:04.601062 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -10.82211 1.89451 0.02984 -10.52279 1.19648 4.40604 -10.43772 3.42460 0.02983 -10.01191 3.48500 4.44190 -9.24738 5.48540 3.30954 -9.53206 5.50770 0.02984 -8.76916 5.54120 6.52921 -9.89934 1.32759 8.78240 -9.34524 3.61260 8.85396 -8.04629 5.52890 11.15913 -9.26471 1.36724 13.15861 -8.71246 3.57270 13.26610 -7.62288 5.23110 15.49638 -8.79618 1.20098 17.53489 -8.36209 3.12530 17.67809 -7.64989 4.79500 18.13671 -8.53313 0.87560 21.91118 -8.31577 2.41180 22.09022 -7.82107 4.31860 20.58139 -8.02359 3.94460 22.84329 -8.30538 -0.79062 26.28739 -8.30538 0.70052 26.28740 -8.18404 3.75820 24.93399 -8.28854 1.69868 26.40406 -8.25863 3.80240 26.86291 -7.06228 8.40020 0.02984 -8.38620 6.91280 2.41682 -7.24683 8.13770 2.46228 -4.47194 9.96990 2.48145 -3.75606 10.29400 0.02976 -5.94010 9.15660 2.50980 -2.75840 10.49580 3.62321 -8.07380 6.89460 4.80358 -6.95048 8.05290 4.89452 -4.28569 9.79750 4.93299 -5.69028 9.01010 4.98983 -7.68404 6.86400 7.19021 -6.59311 7.90890 7.32682 -4.12086 9.51920 7.38459 -2.57576 10.09530 7.41507 -5.41925 8.76810 7.46987 -7.28799 6.80580 9.57691 -6.23702 7.73940 9.75913 -3.95787 9.22070 9.83620 -5.15147 8.50730 9.94991 -2.40556 9.64210 11.24200 -6.95685 6.70500 11.96360 -5.94428 7.57760 12.19143 -3.77749 8.98770 12.28781 -4.91141 8.30410 12.42994 -6.76190 6.54660 14.35030 -5.77712 7.45700 14.62374 -3.56027 8.90580 14.73935 -4.72338 8.23520 14.90998 -2.13855 9.43290 14.94243 -6.77357 6.31590 16.73700 -5.79564 7.41050 17.05605 -3.28867 9.05710 17.19096 -4.61110 8.37220 17.38994 -1.72766 9.64300 18.33506 -7.00006 6.03250 19.12369 -5.99731 7.44970 19.48835 -2.99557 9.42630 19.64257 -4.58613 8.69440 19.86998 -7.34378 5.77480 21.51040 -6.30172 7.56070 21.92059 -2.76823 9.89430 22.09418 -1.33429 10.08770 21.40864 -4.64892 9.10020 22.35008 -7.69641 5.62700 23.89709 -6.62395 7.72770 24.35296 -2.69618 10.33660 24.54579 -1.13835 10.51830 24.18891 -4.79982 9.48510 24.83005 -7.87334 5.89220 26.22347 -6.92828 7.84400 26.71059 -1.22462 10.79640 26.70466 -3.12402 10.54986 26.98725 -5.11937 9.69790 27.34445 -5.42738 9.83580 28.97489 8.61265 5.13360 29.45177 0.06932 10.86760 3.80621 -0.01024 11.00000 0.02977 -1.40119 10.75920 3.81399 1.54101 10.76320 3.81675 2.87009 10.51680 3.52160 3.74599 10.31910 0.02461 3.06080 10.10820 6.97886 0.26646 10.44410 7.58258 -1.22349 10.34610 7.59807 1.75633 10.31870 7.60365 3.19084 9.65190 10.35776 0.40632 9.98440 11.35896 -1.07563 9.89580 11.38229 1.88615 9.84550 11.39063 3.12557 9.35790 13.61293 0.44521 9.74450 15.13533 -0.89992 9.67180 15.16637 1.78511 9.61390 15.17754 2.77768 9.38120 16.66155 0.34961 9.93570 18.91171 -0.65823 9.88990 18.95053 1.34910 9.84460 18.96453 2.21227 9.70760 19.47371 0.17213 10.39810 22.68822 -0.46781 10.38080 22.73461 0.80393 10.35940 22.75151 1.66398 10.14140 22.07601 1.30046 10.53670 24.50004 0.63860 10.78850 26.55730 -0.26995 10.78750 26.46785 1.22529 10.79760 26.75026 7.06210 8.42260 0.02481 8.41345 7.01390 2.18807 9.50643 5.48610 0.02976 7.26406 8.22570 2.23212 4.46815 10.02870 2.27030 5.94975 9.22990 2.28890 9.32640 5.51470 3.95308 8.34041 6.89470 4.35005 7.22057 8.06730 4.43978 4.53342 9.83020 4.51699 5.95696 9.03570 4.55093 8.18244 6.77210 6.51210 7.10496 7.85940 6.64744 4.60456 9.53340 6.76375 5.92833 8.75480 6.81304 9.00644 5.38790 7.87618 7.97886 6.64160 8.67407 6.94847 7.63310 8.85509 4.64917 9.20840 9.01044 5.86525 8.45070 9.07521 7.76899 6.49850 10.83612 6.78223 7.41940 11.06275 4.63475 8.92510 11.25721 5.76895 8.18680 11.33725 8.61378 5.22010 11.68501 7.59222 6.33800 12.99817 6.63741 7.24920 13.27048 4.52889 8.75350 13.50389 5.64082 8.02660 13.59928 7.48771 6.15560 15.16022 8.32521 4.90480 15.26346 6.54521 7.15350 15.47806 4.29922 8.76350 15.75065 5.48222 8.03360 15.86139 7.49153 5.94840 17.32228 6.53255 7.15940 17.68572 3.92877 9.00560 17.99735 5.29914 8.25080 18.12349 8.23527 4.41720 18.53411 7.59137 5.74270 19.48432 6.58862 7.26040 19.89338 3.49200 9.41690 20.24404 5.12194 8.61970 20.38567 7.73767 5.58670 21.64630 8.25740 3.95780 21.48409 6.68360 7.43260 22.10104 3.09609 9.89340 22.49073 4.98816 9.05000 22.64771 8.28384 3.71300 24.13419 7.87952 5.52970 23.80835 6.78704 7.65190 24.30869 2.84803 10.33120 24.73749 4.93555 9.45130 24.90974 7.96324 5.62190 25.97040 8.25683 3.76260 26.51529 6.86779 7.89350 26.51643 2.85645 10.62480 26.98418 5.02005 9.72250 27.17793 5.01206 9.91015 28.28688 10.72605 1.18730 4.35415 10.80892 1.89560 0.02976 10.22011 3.47460 4.38505 10.33368 1.07588 8.67846 10.30603 -1.32513 8.68545 9.83651 3.37060 8.74033 9.82534 0.96963 13.00276 9.78150 -1.36852 13.01323 9.35575 3.19910 13.09561 9.29663 0.82529 17.32708 9.25393 -1.21342 17.34108 8.92802 2.79230 17.45089 8.80583 0.66934 21.65139 8.78052 -0.89296 21.66892 8.60947 2.24530 21.80618 8.35632 -0.05477 25.91333 8.32436 1.64096 26.06027 8.66363 -0.09010 29.62890 8.64029 3.91250 29.54616 10.17118 1.89878 -3.67597 8.94513 5.49330 -3.22971 6.63522 8.42400 -2.39370 3.52367 10.33660 -1.26092 8.28971 1.89878 -6.93474 7.29022 5.49331 -6.09604 5.40599 8.42400 -4.51997 2.86939 10.33660 -2.39137 5.40719 1.89878 -9.35354 4.75482 5.49330 -8.22358 3.52367 8.42400 -6.09781 1.86812 10.33660 -3.23000 1.87124 1.89878 -10.64048 1.64468 5.49331 -9.35552 1.21532 8.42400 -6.93679 0.64044 10.33660 -3.67576 -1.89170 1.89878 -10.64048 -1.66514 5.49330 -9.35552 -1.24074 8.42400 -6.93594 -0.66558 10.33660 -3.67491 -5.42766 1.89878 -9.35354 -4.77529 5.49330 -8.22358 -3.54853 8.42400 -6.09527 -1.89270 10.33660 -3.22759 -8.31018 1.89878 -6.93474 -7.31069 5.49330 -6.09605 -5.42971 8.42400 -4.51615 -2.89297 10.33660 -2.38769 -10.19165 1.89878 -3.67597 -8.96560 5.49330 -3.22971 -6.65746 8.42400 -2.38896 -3.54577 10.33660 -1.25646 -8.65377 3.85249 29.52191 -8.67159 0.00316 29.58427 -8.97734 5.75739 31.26040 -8.62534 5.13799 29.42574 -8.92799 5.75739 33.24101 -8.44687 5.75739 35.16321 -7.55740 5.75739 36.93373 -6.30115 5.75739 38.46575 -4.74085 5.75739 39.68664 -2.95096 5.75739 40.53609 -1.01801 5.75739 40.97280 0.96295 5.75739 40.97697 2.89704 5.75739 40.54733 4.69025 5.75739 39.70474 6.25565 5.75739 38.49036 7.51734 5.75740 36.96280 8.41431 5.75740 35.19623 8.90306 5.75740 33.27615 8.95977 5.75740 31.29569 8.65656 1.84708 29.60358 8.35498 6.41670 28.91394 -7.38982 7.94489 28.76241 -8.31528 6.49310 28.80709 -8.78182 6.90539 32.00492 -8.03264 7.87869 30.76628 -8.10922 7.87869 32.63197 -8.12485 6.90539 35.36077 -7.75793 7.87869 34.46621 -6.99652 7.87869 36.17090 -6.23433 6.90539 38.21012 -5.86572 7.87869 37.65667 -4.42626 7.87869 38.84582 -3.39862 6.90539 40.12094 -2.75254 7.87869 39.67384 -0.04722 6.90539 40.80133 -0.93471 7.87869 40.09867 0.93269 7.87869 40.09620 3.30949 6.90540 40.14902 2.75003 7.87869 39.66762 4.42149 7.87869 38.83535 6.16175 6.90540 38.26267 5.85861 7.87870 37.64331 8.07595 6.90540 35.42908 6.98559 7.87870 36.15457 7.74269 7.87870 34.44783 8.76128 6.90540 32.07895 8.09009 7.87870 32.61324 8.00927 7.87870 30.74782 7.13755 8.03140 28.36388 -5.75442 10.12129 30.77964 -5.88891 10.12129 32.02981 -5.68858 10.12129 33.55129 -5.10133 10.12129 34.96911 -4.16711 10.12129 36.18661 -2.94961 10.12129 37.12083 -1.53171 10.12129 37.70816 -0.01024 10.12129 37.90848 1.51124 10.12129 37.70816 2.92913 10.12129 37.12083 4.14663 10.12129 36.18661 5.08086 10.12129 34.96911 5.66811 10.12129 33.55129 5.86843 10.12130 32.02981 5.73083 10.12130 30.76508 5.32404 10.12150 29.55953 4.88535 10.74795 32.02972 4.52677 10.77160 30.16474 3.59488 11.00000 30.97120 3.74711 11.00000 32.02981 3.15067 11.00000 29.99836 3.48542 10.81730 28.47776 2.45035 11.00000 29.19014 1.55063 11.00000 28.61201 0.52448 11.00000 28.31064 -0.22463 10.94620 27.71228 -0.90310 10.94670 27.80258 -3.41361 10.67647 27.95695 -1.57110 11.00000 28.61201 -2.47082 11.00000 29.19014 -3.75642 10.71769 28.67628 -3.17115 10.99999 29.99836 -4.54689 10.77160 30.16368 -3.61535 10.99999 30.97120 -4.90581 10.74795 32.02974 -3.76759 10.99999 32.02981 -3.61542 10.99999 33.08834 3.59495 11.00000 33.08834 -3.17115 10.99999 34.06111 3.15059 11.00000 34.06118 -2.47075 10.99999 34.86940 2.45028 11.00000 34.86940 -1.57111 10.99999 35.44761 1.55063 10.99999 35.44761 -0.54502 10.99999 35.74890 0.52455 10.99999 35.74890 -4.42986 10.77159 34.15820 -3.06869 10.77160 35.86501 -1.10180 10.77160 36.81225 1.08132 10.77160 36.81225 3.04821 10.77160 35.86501 4.40939 10.77160 34.15820 4.40939 -10.86170 34.15819 3.04822 -10.86170 35.86501 1.08133 -10.86170 36.81224 -1.10180 -10.86170 36.81224 -3.06868 -10.86170 35.86501 -4.42986 -10.86170 34.15819 0.52455 -11.09011 35.74890 -0.54502 -11.09011 35.74890 1.55064 -11.09011 35.44760 -1.57110 -11.09011 35.44760 2.45028 -11.09010 34.86940 -2.47075 -11.09011 34.86940 3.15060 -11.09010 34.06118 -3.17114 -11.09011 34.06110 3.59495 -11.09010 33.08834 -3.61542 -11.09011 33.08834 -3.76759 -11.09011 32.02980 -4.90581 -10.83806 32.02974 -3.61535 -11.09011 30.97119 -4.54689 -10.86171 30.16368 -3.17114 -11.09011 29.99836 -3.75641 -10.80780 28.67628 -2.47082 -11.09010 29.19013 -1.57110 -11.09010 28.61200 -3.41360 -10.76658 27.95695 -0.90309 -11.03680 27.80258 -0.22463 -11.03630 27.71228 0.52448 -11.09010 28.31063 1.55063 -11.09010 28.61200 2.45035 -11.09010 29.19013 3.48542 -10.90741 28.47776 3.15067 -11.09010 29.99836 3.74712 -11.09010 32.02980 3.59488 -11.09010 30.97119 4.52677 -10.86170 30.16474 4.88535 -10.83805 32.02972 5.32404 -10.21160 29.55953 5.73084 -10.21140 30.76507 5.86844 -10.21140 32.02980 5.66811 -10.21140 33.55128 5.08086 -10.21140 34.96910 4.14663 -10.21140 36.18660 2.92914 -10.21141 37.12083 1.51124 -10.21141 37.70815 -0.01023 -10.21141 37.90848 -1.53171 -10.21141 37.70815 -2.94960 -10.21141 37.12083 -4.16710 -10.21141 36.18660 -5.10133 -10.21140 34.96910 -5.68858 -10.21140 33.55128 -5.88891 -10.21140 32.02980 -5.75441 -10.21140 30.77964 7.13755 -8.12150 28.36388 8.00927 -7.96880 30.74782 8.09009 -7.96880 32.61324 8.76128 -6.99550 32.07895 7.74269 -7.96880 34.44782 6.98560 -7.96880 36.15456 8.07595 -6.99550 35.42908 5.85861 -7.96880 37.64331 6.16175 -6.99550 38.26267 4.42149 -7.96880 38.83535 2.75003 -7.96880 39.66762 3.30949 -6.99550 40.14902 0.93269 -7.96880 40.09619 -0.93471 -7.96880 40.09867 -0.04722 -6.99550 40.80132 -2.75254 -7.96880 39.67384 -3.39862 -6.99551 40.12094 -4.42626 -7.96880 38.84582 -5.86571 -7.96881 37.65667 -6.23433 -6.99551 38.21012 -6.99652 -7.96881 36.17090 -7.75793 -7.96880 34.46621 -8.12485 -6.99550 35.36077 -8.10922 -7.96881 32.63197 -8.03264 -7.96881 30.76628 -8.78182 -6.99550 32.00491 -8.31528 -6.58320 28.80709 -7.38981 -8.03500 28.76241 8.35498 -6.50680 28.91394 8.65656 -1.93718 29.60358 8.95977 -5.84750 31.29569 8.90306 -5.84750 33.27615 8.41431 -5.84750 35.19623 7.51734 -5.84750 36.96279 6.25565 -5.84750 38.49036 4.69026 -5.84750 39.70473 2.89704 -5.84750 40.54733 0.96295 -5.84750 40.97696 -1.01800 -5.84750 40.97280 -2.95095 -5.84750 40.53608 -4.74085 -5.84750 39.68664 -6.30115 -5.84750 38.46575 -7.55740 -5.84750 36.93373 -8.44687 -5.84750 35.16320 -8.92799 -5.84750 33.24101 -8.62534 -5.22810 29.42574 -8.65377 -3.94260 29.52191 -8.97734 -5.84750 31.26040 -3.54577 -10.42670 -1.25647 -6.65746 -8.51410 -2.38897 -8.96560 -5.58340 -3.22972 -10.19165 -1.98888 -3.67597 -2.89297 -10.42670 -2.38769 -5.42971 -8.51410 -4.51616 -7.31068 -5.58340 -6.09605 -8.31018 -1.98888 -6.93474 -1.89269 -10.42670 -3.22760 -3.54852 -8.51410 -6.09527 -4.77528 -5.58340 -8.22358 -5.42766 -1.98888 -9.35354 -0.66558 -10.42670 -3.67491 -1.24074 -8.51410 -6.93595 -1.66514 -5.58340 -9.35552 -1.89170 -1.98888 -10.64048 0.64045 -10.42670 -3.67576 1.21532 -8.51410 -6.93680 1.64468 -5.58340 -9.35552 1.87123 -1.98888 -10.64047 1.86813 -10.42670 -3.23000 3.52368 -8.51410 -6.09782 4.75482 -5.58340 -8.22358 5.40719 -1.98888 -9.35354 2.86939 -10.42670 -2.39137 5.40599 -8.51410 -4.51997 7.29022 -5.58340 -6.09604 8.28971 -1.98888 -6.93474 3.52367 -10.42670 -1.26092 6.63523 -8.51410 -2.39370 8.94513 -5.58340 -3.22972 10.17118 -1.98888 -3.67597 8.64029 -4.00260 29.54616 8.32436 -1.73106 26.06027 8.60947 -2.33540 21.80618 8.92802 -2.88240 17.45089 9.35575 -3.28920 13.09561 9.83651 -3.46070 8.74033 10.22011 -3.56470 4.38505 10.80892 -1.98570 0.02976 10.72605 -1.27740 4.35415 5.01207 -10.00026 28.28688 5.02005 -9.81260 27.17792 2.85645 -10.71490 26.98417 6.86779 -7.98360 26.51642 8.25683 -3.85270 26.51529 7.96325 -5.71200 25.97040 4.93555 -9.54140 24.90974 2.84804 -10.42130 24.73748 6.78704 -7.74200 24.30869 7.87952 -5.61980 23.80835 8.28384 -3.80310 24.13419 4.98816 -9.14010 22.64770 3.09609 -9.98350 22.49072 6.68360 -7.52270 22.10104 8.25740 -4.04790 21.48409 7.73768 -5.67680 21.64630 5.12194 -8.70980 20.38566 3.49200 -9.50700 20.24403 6.58863 -7.35050 19.89338 7.59137 -5.83280 19.48432 8.23527 -4.50730 18.53411 5.29915 -8.34090 18.12349 3.92878 -9.09570 17.99734 6.53255 -7.24950 17.68572 7.49153 -6.03850 17.32227 5.48222 -8.12370 15.86138 4.29923 -8.85360 15.75065 6.54521 -7.24360 15.47806 8.32521 -4.99490 15.26346 7.48771 -6.24570 15.16022 5.64083 -8.11670 13.59928 4.52889 -8.84360 13.50389 6.63742 -7.33930 13.27048 7.59222 -6.42810 12.99817 8.61378 -5.31020 11.68500 5.76895 -8.27690 11.33725 4.63475 -9.01520 11.25721 6.78224 -7.50950 11.06275 7.76900 -6.58860 10.83612 5.86526 -8.54080 9.07521 4.64917 -9.29850 9.01044 6.94848 -7.72320 8.85509 7.97887 -6.73170 8.67407 9.00644 -5.47800 7.87617 5.92833 -8.84490 6.81303 4.60456 -9.62350 6.76375 7.10496 -7.94950 6.64743 8.18244 -6.86220 6.51209 5.95697 -9.12580 4.55093 4.53343 -9.92030 4.51699 7.22057 -8.15740 4.43977 8.34041 -6.98480 4.35004 9.32640 -5.60480 3.95307 5.94975 -9.32000 2.28890 4.46815 -10.11880 2.27030 7.26406 -8.31580 2.23212 9.50643 -5.57620 0.02976 8.41345 -7.10400 2.18806 7.06211 -8.51270 0.02481 1.22529 -10.88770 26.75026 -0.26995 -10.87760 26.46784 0.63860 -10.87860 26.55729 1.30046 -10.62680 24.50003 1.66399 -10.23150 22.07600 0.80393 -10.44950 22.75150 -0.46780 -10.47090 22.73461 0.17213 -10.48820 22.68822 2.21228 -9.79770 19.47371 1.34910 -9.93470 18.96452 -0.65823 -9.98000 18.95052 0.34962 -10.02580 18.91170 2.77768 -9.47130 16.66155 1.78511 -9.70400 15.17754 -0.89992 -9.76190 15.16637 0.44522 -9.83460 15.13533 3.12557 -9.44800 13.61292 1.88616 -9.93560 11.39063 -1.07563 -9.98590 11.38229 0.40633 -10.07450 11.35896 3.19084 -9.74200 10.35776 1.75633 -10.40880 7.60365 -1.22349 -10.43620 7.59807 0.26646 -10.53420 7.58258 3.06080 -10.19830 6.97885 3.74599 -10.40920 0.02460 2.87010 -10.60690 3.52160 1.54102 -10.85330 3.81674 -1.40118 -10.84930 3.81398 -0.01023 -11.09010 0.02976 0.06932 -10.95770 3.80620 8.61265 -5.22370 29.45177 -5.42738 -9.92590 28.97489 -5.11936 -9.78800 27.34444 -3.12402 -10.63996 26.98725 -1.22462 -10.88650 26.70466 -6.92828 -7.93410 26.71059 -7.87333 -5.98230 26.22347 -4.79982 -9.57520 24.83005 -1.13835 -10.60840 24.18891 -2.69618 -10.42670 24.54579 -6.62395 -7.81780 24.35296 -7.69641 -5.71710 23.89709 -4.64892 -9.19030 22.35008 -1.33429 -10.17780 21.40864 -2.76823 -9.98440 22.09418 -6.30171 -7.65080 21.92059 -7.34378 -5.86490 21.51039 -4.58613 -8.78450 19.86997 -2.99557 -9.51640 19.64257 -5.99730 -7.53980 19.48835 -7.00006 -6.12260 19.12369 -1.72766 -9.73310 18.33506 -4.61109 -8.46230 17.38994 -3.28867 -9.14720 17.19096 -5.79564 -7.50060 17.05604 -6.77357 -6.40600 16.73700 -2.13855 -9.52300 14.94243 -4.72338 -8.32530 14.90997 -3.56026 -8.99590 14.73935 -5.77711 -7.54710 14.62374 -6.76190 -6.63670 14.35030 -4.91141 -8.39420 12.42994 -3.77749 -9.07780 12.28781 -5.94427 -7.66770 12.19143 -6.95685 -6.79510 11.96360 -2.40556 -9.73220 11.24200 -5.15147 -8.59740 9.94990 -3.95787 -9.31080 9.83620 -6.23701 -7.82950 9.75912 -7.28799 -6.89590 9.57691 -5.41925 -8.85820 7.46987 -2.57576 -10.18540 7.41507 -4.12086 -9.60930 7.38459 -6.59311 -7.99900 7.32682 -7.68404 -6.95410 7.19021 -5.69028 -9.10020 4.98983 -4.28568 -9.88760 4.93298 -6.95048 -8.14300 4.89451 -8.07380 -6.98470 4.80358 -2.75840 -10.58590 3.62321 -5.94010 -9.24670 2.50980 -3.75606 -10.38410 0.02976 -4.47194 -10.06000 2.48144 -7.24683 -8.22780 2.46228 -8.38620 -7.00290 2.41682 -7.06228 -8.49030 0.02983 -8.25863 -3.89250 26.86290 -8.18404 -3.84830 24.93399 -8.28218 -2.23900 26.50221 -8.02359 -4.03470 22.84328 -7.82107 -4.40870 20.58139 -8.31577 -2.50190 22.09022 -8.53313 -0.96570 21.91118 -7.64989 -4.88510 18.13671 -8.36209 -3.21540 17.67809 -8.79618 -1.29108 17.53489 -7.62288 -5.32120 15.49638 -8.71246 -3.66280 13.26609 -9.26471 -1.45734 13.15861 -8.04629 -5.61900 11.15913 -9.34524 -3.70270 8.85396 -9.89934 -1.41769 8.78240 -8.76916 -5.63130 6.52920 -9.53206 -5.59780 0.02983 -9.24738 -5.57550 3.30953 -10.01191 -3.57510 4.44190 -10.43772 -3.51470 0.02983 -10.52279 -1.28658 4.40604 -10.82211 -1.98461 0.02984 + + + + + + + + + + -0.99767 -0.00000 0.06824 -0.99767 0.00000 0.06824 -0.96454 0.24231 0.10462 -0.97224 0.21562 0.09088 -0.91458 0.39600 0.08208 -0.91393 0.39734 0.08277 -0.90059 0.41583 0.12656 -0.99000 0.00000 0.14104 -0.96794 0.21402 0.13148 -0.99000 -0.00000 0.14104 -0.96340 0.22926 0.13894 -0.89990 0.41813 0.12388 -0.88968 0.43458 0.14006 -0.98965 -0.00000 0.14352 -0.96356 0.22934 0.13766 -0.98965 -0.00000 0.14352 -0.96207 0.23408 0.14010 -0.88674 0.44327 0.13118 -0.89489 0.43069 0.11693 -0.99432 -0.00000 0.10645 -0.99432 0.00000 0.10645 -0.96519 0.23621 0.11231 -0.89409 0.43290 0.11490 -0.97228 0.21198 0.09871 -0.92371 0.37938 0.05321 -0.99820 0.00000 0.06000 -0.97395 0.21417 0.07446 -0.99820 0.00000 0.06000 -0.99013 0.13632 0.03244 -0.97187 0.23444 -0.02237 -0.92437 0.37496 0.07034 -0.97592 0.21175 -0.05236 -0.99865 0.00000 0.05197 -0.99865 -0.00000 0.05197 -0.98943 0.13338 0.05683 -0.99703 -0.00430 -0.07690 -0.98471 0.17078 0.03445 -0.99984 0.01582 0.00892 -0.99897 0.02275 -0.03915 -0.76038 0.64925 -0.01717 -0.73242 0.68061 0.01788 -0.48479 0.87424 -0.02599 -0.49664 0.86705 -0.03972 -0.61532 0.78735 0.03828 -0.83204 0.54949 0.07596 -0.31376 0.94890 0.03382 -0.81854 0.56354 0.11144 -0.73035 0.67561 0.10075 -0.71775 0.68733 0.11142 -0.61399 0.78268 0.10210 -0.81869 0.56324 0.11184 -0.48080 0.87136 0.09781 -0.34769 0.93308 0.09203 -0.48346 0.86963 0.10007 -0.60650 0.78777 0.10763 -0.79844 0.58607 0.13791 -0.71708 0.68553 0.12589 -0.69385 0.70563 0.14372 -0.60576 0.78404 0.13542 -0.31946 0.93891 0.12806 -0.48077 0.86705 0.13075 -0.34904 0.93002 0.11504 -0.48920 0.86127 0.13750 -0.59586 0.79039 0.14224 -0.69421 0.70748 0.13245 -0.79949 0.58245 0.14687 -0.77873 0.61514 0.12322 -0.67103 0.72634 0.14886 -0.59586 0.79038 0.14231 -0.34847 0.92739 0.13608 -0.48921 0.86128 0.13739 -0.58832 0.79513 0.14714 -0.49759 0.85543 0.14368 -0.36416 0.92284 0.12548 -0.67093 0.73109 0.12396 -0.77086 0.62291 0.13326 -0.66384 0.73668 0.12890 -0.58747 0.79970 0.12390 -0.35537 0.92771 0.11432 -0.50110 0.85726 0.11834 -0.50168 0.85686 0.11877 -0.58975 0.79824 0.12249 -0.76748 0.63009 0.11819 -0.78791 0.60683 0.10463 -0.66255 0.74185 0.10335 -0.58579 0.80648 0.08025 -0.68882 0.72016 0.08305 -0.50811 0.85814 0.07369 -0.38872 0.91905 0.06515 -0.60457 0.79365 0.06788 -0.49176 0.86856 0.06141 -0.35638 0.93105 0.07835 -0.68723 0.72339 0.06656 -0.81428 0.57815 0.05191 -0.59594 0.80296 0.01081 -0.74673 0.66509 0.00703 -0.34509 0.93836 -0.01968 -0.49928 0.86644 0.00184 -0.62775 0.77828 -0.01457 -0.46303 0.88590 -0.02797 -0.34041 0.94012 -0.01699 -0.82853 0.55376 0.08299 -0.87635 0.48096 -0.02605 -0.74688 0.66491 0.00808 -0.61810 0.78350 -0.06387 -0.80460 0.58891 -0.07620 -0.46761 0.88060 -0.07671 -0.27717 0.95443 -0.11060 -0.42857 0.89652 -0.11216 -0.64455 0.75899 -0.09212 -0.89314 0.44908 0.02497 -0.92670 0.36382 -0.09418 -0.80866 0.58586 -0.05320 -0.63949 0.76019 -0.11473 -0.84324 0.52174 -0.12935 -0.42979 0.89342 -0.13069 -0.18752 0.97526 -0.11710 -0.31463 0.93733 -0.14976 -0.65561 0.74237 -0.13807 -0.40225 0.90184 -0.15774 -0.94397 0.32865 -0.03017 -0.85042 0.51771 -0.09359 -0.95633 0.26423 -0.12493 -0.65566 0.74237 -0.13783 -0.86757 0.47493 -0.14754 -0.14656 0.97906 -0.14130 -0.21004 0.96322 -0.16760 -0.40190 0.90313 -0.15112 -0.66437 0.73138 -0.15394 -0.38910 0.90641 -0.16435 -0.97315 0.22354 -0.05475 -0.97487 0.20055 -0.09700 -0.87795 0.45904 -0.13597 -0.87338 0.47197 -0.12022 -0.14073 0.98352 -0.11355 -0.67173 0.73056 -0.12275 -0.98477 0.16873 -0.04195 -0.38816 0.90972 -0.14748 -0.14417 0.98329 -0.11115 -0.40878 0.90355 -0.12842 -0.68228 0.71609 -0.14731 -0.67028 0.71807 -0.18736 -0.19020 0.98174 -0.00233 -0.07328 0.99664 0.03649 -0.18521 0.98268 -0.00555 0.07048 0.99695 0.03347 0.18002 0.98361 -0.01052 0.17834 0.98390 -0.01153 0.20355 0.97354 0.10383 -0.20453 0.97237 0.11255 0.06958 0.99176 0.10759 -0.07243 0.99073 0.11489 -0.19623 0.97373 0.11551 -0.06407 0.99172 0.11127 0.20613 0.97314 0.10251 0.08178 0.99038 0.11160 0.21505 0.96888 0.12257 0.08164 0.98972 0.11746 -0.06386 0.99036 0.12292 -0.19714 0.97251 0.12394 -0.19850 0.97229 0.12345 -0.05736 0.99109 0.12018 0.23260 0.96602 0.11273 0.09021 0.98861 0.12044 0.21713 0.97179 0.09212 -0.19398 0.97855 0.06932 0.09195 0.99382 0.06219 -0.05856 0.99624 0.06389 -0.05245 0.99673 0.06144 -0.20065 0.97736 0.06717 0.09484 0.99348 0.06329 0.26082 0.96314 0.06586 0.20552 0.97852 0.01598 -0.18248 0.98245 -0.03874 0.09839 0.99400 -0.04784 -0.05509 0.99713 -0.05188 -0.04742 0.99739 -0.05446 -0.20086 0.97865 -0.04358 0.26749 0.96316 -0.02788 0.09327 0.99439 -0.04984 0.19850 0.97734 -0.07353 -0.15618 0.98019 -0.12183 0.09626 0.98851 -0.11651 -0.04980 0.99107 -0.12369 -0.03599 0.99128 -0.12678 -0.14862 0.98160 -0.11986 0.14399 0.98058 -0.13312 0.21395 0.97158 -0.10128 0.07304 0.98959 -0.12401 -0.11159 0.98321 -0.14441 0.13935 0.98044 -0.13899 0.07162 0.99149 -0.10868 -0.03387 0.99478 -0.09629 0.00962 0.99402 -0.10880 -0.02783 0.99389 -0.10680 0.03443 0.99328 -0.11050 -0.01814 0.99371 -0.11047 0.02223 0.99318 -0.11441 0.76708 0.63841 -0.06345 0.72544 0.68827 -0.00498 0.30890 0.95080 0.02362 0.83514 0.54897 0.03432 0.72526 0.68565 0.06231 0.82020 0.56902 0.05908 0.72415 0.68671 0.06354 0.60756 0.79129 0.06875 0.34302 0.93650 0.07278 0.47298 0.87876 0.06390 0.61061 0.78919 0.06581 0.48471 0.87160 0.07328 0.72364 0.68407 0.09166 0.82253 0.56124 0.09192 0.71291 0.69370 0.10266 0.61072 0.78474 0.10588 0.48311 0.86987 0.09962 0.31995 0.94054 0.11412 0.61155 0.78419 0.10512 0.50061 0.85828 0.11291 0.35851 0.92917 0.09004 0.81707 0.57022 0.08507 0.71282 0.69283 0.10894 0.80209 0.58681 0.11095 0.69924 0.70444 0.12177 0.61189 0.78125 0.12345 0.36156 0.92374 0.12645 0.50050 0.85817 0.11420 0.51954 0.84480 0.12805 0.61362 0.78013 0.12198 0.38034 0.91836 0.10938 0.80324 0.58413 0.11663 0.69919 0.70569 0.11458 0.61360 0.78018 0.12173 0.69199 0.71170 0.12100 0.52138 0.84620 0.11005 0.38696 0.91454 0.11780 0.53560 0.83585 0.12032 0.61953 0.77621 0.11693 0.79482 0.59711 0.10825 0.69151 0.71401 0.10954 0.79437 0.59751 0.10931 0.70174 0.70532 0.10041 0.61785 0.77982 0.10065 0.53892 0.83760 0.08937 0.40328 0.91078 0.08857 0.53956 0.83714 0.08985 0.63090 0.77059 0.09031 0.39986 0.91211 0.09040 0.78542 0.61244 0.08963 0.70120 0.70680 0.09352 0.82094 0.55921 0.11547 0.73516 0.67524 0.05998 0.62616 0.77739 0.05985 0.39770 0.91679 0.03657 0.54333 0.83792 0.05181 0.52248 0.85197 0.03400 0.64629 0.76188 0.04296 0.39538 0.91773 0.03811 0.73553 0.67452 0.06334 0.82782 0.55858 0.05207 0.78437 0.62028 0.00284 0.63807 0.76997 0.00160 0.52543 0.85082 -0.00505 0.35396 0.93430 -0.04231 0.48512 0.87331 -0.04459 0.65879 0.75209 -0.01890 0.86262 0.49633 0.09772 0.89950 0.43693 0.00003 0.78701 0.61653 0.02231 0.82761 0.55937 -0.04661 0.65156 0.75687 -0.05118 0.48602 0.87152 -0.06506 0.34986 0.93602 -0.03830 0.28709 0.95058 -0.11821 0.44439 0.88903 -0.11017 0.66556 0.74315 -0.06905 0.83220 0.55424 -0.01632 0.95307 0.30015 0.03959 0.89121 0.45274 -0.02764 0.85760 0.50858 -0.07656 0.66141 0.74501 -0.08656 0.27767 0.95538 -0.10076 0.21481 0.96240 -0.16626 0.44440 0.88902 -0.11024 0.66964 0.73587 -0.10038 0.41286 0.89892 -0.14658 0.95305 0.30225 0.01841 0.97662 0.20684 -0.05862 0.86294 0.50345 -0.04334 0.87706 0.47225 -0.08801 0.66864 0.73621 -0.10446 0.41266 0.90154 -0.13011 0.20498 0.97043 -0.12751 0.15560 0.97267 -0.17235 0.39452 0.90629 -0.15161 0.67313 0.73069 -0.11397 0.88256 0.46708 -0.05410 0.98737 0.15822 0.00791 0.97680 0.20901 -0.04674 0.67546 0.72995 -0.10459 0.88991 0.44878 -0.08166 0.14727 0.98306 -0.10906 0.12275 0.98401 -0.12905 0.39401 0.91117 -0.12055 0.67851 0.72599 -0.11208 0.39136 0.91190 -0.12361 0.67690 0.72654 -0.11807 0.99982 -0.00000 0.01916 0.99982 0.00000 0.01916 0.97513 0.21496 0.05390 0.94005 0.34101 0.00346 0.91222 0.40785 0.03889 0.90555 0.41517 0.08727 0.97237 0.21381 0.09374 0.99591 0.00000 0.09036 0.99528 -0.01118 0.09639 0.97380 0.20853 0.09075 0.90693 0.41161 0.08971 0.90133 0.41858 0.11136 0.97101 0.20716 0.11924 0.99313 -0.01110 0.11647 0.99259 -0.01807 0.12012 0.97296 0.20013 0.11528 0.90348 0.41264 0.11598 0.90609 0.40879 0.10909 0.97184 0.19947 0.12548 0.99252 -0.01807 0.12075 0.99237 -0.01995 0.12169 0.97791 0.17618 0.11249 0.91184 0.39071 0.12604 0.93471 0.34689 0.07742 0.99350 -0.02004 0.11204 0.97742 0.17578 0.11727 0.99384 -0.01487 0.10981 0.98959 0.11478 0.08680 0.93026 0.36352 0.04963 0.97095 0.21812 0.09841 0.97914 0.20299 0.00898 0.99463 -0.01497 0.10236 0.98622 0.11081 0.12284 0.99241 0.09359 0.07981 0.99756 0.01285 0.06868 0.99951 0.02951 0.01072 0.98551 0.00000 -0.16960 0.92804 0.33665 -0.15942 0.98551 -0.00000 -0.16960 0.76218 0.63421 -0.12985 0.92820 0.33635 -0.15910 0.49458 0.86479 -0.08680 0.75944 0.63670 -0.13368 0.17832 0.98382 -0.01744 0.50219 0.86149 -0.07512 0.86602 -0.00000 -0.50000 0.86602 -0.00000 -0.50000 0.81549 0.33661 -0.47083 0.66796 0.63648 -0.38565 0.81548 0.33661 -0.47083 0.66756 0.63673 -0.38593 0.43801 0.86257 -0.25322 0.15254 0.98435 -0.08829 0.43779 0.86263 -0.25339 0.64280 -0.00000 -0.76603 0.64280 0.00000 -0.76603 0.60529 0.33661 -0.72133 0.60529 0.33661 -0.72133 0.49578 0.63649 -0.59083 0.49535 0.63672 -0.59094 0.32501 0.86257 -0.38773 0.32481 0.86262 -0.38779 0.11317 0.98435 -0.13512 0.34201 0.00000 -0.93970 0.34201 -0.00000 -0.93970 0.32205 0.33661 -0.88486 0.32205 0.33662 -0.88486 0.26378 0.63651 -0.72476 0.17282 0.86257 -0.47550 0.26340 0.63671 -0.72472 0.06015 0.98435 -0.16567 0.17265 0.86261 -0.47549 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.33662 -0.94164 0.00000 0.33661 -0.94164 0.00000 0.63652 -0.77126 -0.00027 0.63668 -0.77113 -0.00018 0.86257 -0.50593 -0.00033 0.86261 -0.50586 -0.00011 0.98435 -0.17625 -0.34201 0.00000 -0.93970 -0.34201 0.00000 -0.93970 -0.32205 0.33661 -0.88486 -0.26377 0.63654 -0.72474 -0.32205 0.33661 -0.88486 -0.26394 0.63667 -0.72456 -0.17316 0.86258 -0.47536 -0.06036 0.98435 -0.16559 -0.17325 0.86261 -0.47528 -0.64280 0.00000 -0.76603 -0.64280 0.00000 -0.76603 -0.60529 0.33661 -0.72133 -0.49575 0.63655 -0.59079 -0.60529 0.33661 -0.72133 -0.49581 0.63663 -0.59066 -0.32527 0.86259 -0.38749 -0.32530 0.86260 -0.38742 -0.11334 0.98435 -0.13498 -0.86602 0.00000 -0.50000 -0.81549 0.33661 -0.47083 -0.86602 0.00000 -0.50000 -0.66790 0.63655 -0.38562 -0.81548 0.33661 -0.47083 -0.66791 0.63662 -0.38550 -0.43816 0.86259 -0.25289 -0.43817 0.86260 -0.25285 -0.15265 0.98435 -0.08809 -0.98584 0.00000 -0.16772 -0.98584 0.00000 -0.16772 -0.75928 0.63665 -0.13476 -0.49635 0.86654 -0.05245 -0.18521 0.98270 0.00226 -0.75499 0.64466 -0.12002 -0.50205 0.86153 -0.07555 -0.98281 0.00156 -0.18463 -0.98159 0.00743 -0.19084 -0.98377 0.00000 -0.17946 -0.99969 -0.00000 0.02491 -0.99969 0.00000 0.02491 -0.97007 0.00000 0.24281 -0.97007 -0.00000 0.24281 -0.89358 -0.00000 0.44891 -0.89358 -0.00000 0.44891 -0.77327 -0.00000 0.63408 -0.77327 -0.00000 0.63408 -0.61624 -0.00000 0.78756 -0.61624 -0.00000 0.78756 -0.42875 -0.00000 0.90343 -0.42874 -0.00000 0.90343 -0.22038 -0.00000 0.97541 -0.22038 -0.00000 0.97541 -0.00210 -0.00000 1.00000 -0.00210 -0.00000 1.00000 0.21685 -0.00000 0.97620 0.21685 -0.00000 0.97620 0.42527 -0.00000 0.90507 0.42527 -0.00000 0.90507 0.61295 -0.00000 0.79012 0.61295 0.00000 0.79012 0.77101 0.00000 0.63682 0.77102 -0.00000 0.63682 0.89165 0.00000 0.45273 0.89165 -0.00000 0.45273 0.96910 -0.00000 0.24668 0.96910 -0.00000 0.24668 0.99959 -0.00000 0.02862 0.99959 -0.00000 0.02862 0.98458 0.00000 -0.17493 0.98382 0.00125 -0.17918 0.98323 0.00267 -0.18236 0.98223 0.00774 -0.18752 0.97049 0.10362 -0.21775 -0.96703 0.11833 -0.22548 -0.94612 0.27353 -0.17330 -0.81205 0.58264 -0.03333 -0.98803 0.15231 0.02462 -0.90531 0.35925 0.22660 -0.95379 0.23541 0.18672 -0.86306 0.47728 0.16529 -0.85829 0.48487 0.16803 -0.74132 0.58379 0.33111 -0.88044 0.17084 0.44231 -0.66848 0.54248 0.50877 -0.74356 0.45136 0.49335 -0.78755 0.32668 0.52253 -0.76020 0.18305 0.62336 -0.52676 0.56208 0.63764 -0.60294 0.20667 0.77055 -0.52913 0.32159 0.78524 -0.50053 0.44467 0.74280 -0.36223 0.57679 0.73219 -0.42339 0.15752 0.89215 -0.21293 0.25778 0.94245 -0.18978 0.30012 0.93483 -0.20391 0.44397 0.87253 -0.17194 0.50317 0.84691 -0.00208 0.14945 0.98877 0.00107 0.58598 0.81033 0.20530 0.32205 0.92419 0.18407 0.26251 0.94721 0.19566 0.52283 0.82968 0.16931 0.46073 0.87124 0.41985 0.15917 0.89353 0.36533 0.57289 0.73371 0.56280 0.39615 0.72548 0.53979 0.20603 0.81619 0.49427 0.44401 0.74736 0.52581 0.56716 0.63392 0.75755 0.18606 0.62570 0.72890 0.40527 0.55178 0.70606 0.52343 0.47697 0.78342 0.32584 0.52923 0.87889 0.16852 0.44626 0.74119 0.58526 0.32879 0.85161 0.49875 0.16127 0.86295 0.47345 0.17653 0.94327 0.22931 0.24011 0.93036 0.31338 0.19032 0.98805 0.15153 0.02829 0.81357 0.58039 -0.03525 0.88222 0.43491 -0.18041 0.94711 0.27576 -0.16416 0.81130 0.52202 -0.26323 -0.66164 0.71281 -0.23266 -0.68713 0.69922 -0.19733 -0.69930 0.71086 -0.07523 -0.71425 0.69928 -0.02932 -0.69525 0.71292 0.09154 -0.70041 0.70102 0.13414 -0.65047 0.71014 0.26942 -0.64881 0.70360 0.28980 -0.56351 0.70605 0.42888 -0.56099 0.70709 0.43047 -0.45311 0.70274 0.54849 -0.42808 0.71099 0.55788 -0.31647 0.70044 0.63971 -0.26816 0.71343 0.64739 -0.16274 0.69898 0.69638 -0.09129 0.71479 0.69336 0.00095 0.69850 0.71561 0.09129 0.71478 0.69337 0.16416 0.69891 0.69612 0.26809 0.71360 0.64722 0.31819 0.70029 0.63902 0.42796 0.71119 0.55773 0.45431 0.70258 0.54771 0.56358 0.70736 0.42664 0.56221 0.70556 0.43140 0.64937 0.70381 0.28805 0.65079 0.70980 0.26955 0.70058 0.70113 0.13267 0.69542 0.71275 0.09156 0.71409 0.69937 -0.03094 0.69915 0.71091 -0.07607 0.68564 0.69818 -0.20599 0.66836 0.70886 -0.22541 0.53660 0.84181 -0.05838 0.21287 0.97660 -0.03061 0.21611 0.97593 -0.02917 0.50647 0.85791 -0.08650 0.53558 0.82495 -0.18059 0.17249 0.98186 -0.07876 0.17261 0.98174 -0.07995 0.47616 0.83648 -0.27126 0.10940 0.98947 -0.09480 0.08418 0.98780 -0.13101 0.08169 0.98354 -0.16117 0.05378 0.98162 -0.18311 -0.00960 0.99694 -0.07762 -0.11065 0.97883 -0.17220 -0.16155 0.97786 -0.13303 -0.15943 0.97750 -0.13814 -0.17754 0.97553 -0.12971 -0.17247 0.98186 -0.07875 -0.54893 0.80453 -0.22674 -0.49438 0.86762 -0.05319 -0.53522 0.83965 -0.09230 -0.21436 0.97633 -0.02886 -0.21610 0.97588 -0.03108 -0.01071 0.99716 -0.07451 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.53617 0.84115 0.07059 -0.49467 0.86319 0.10102 -0.22947 0.97276 0.03299 -0.21605 0.97566 0.03747 -0.52918 0.81972 0.21918 -0.17211 0.98194 0.07861 -0.15313 0.97926 0.13268 -0.16699 0.97692 0.13318 -0.42461 0.84472 0.32582 -0.40904 0.85222 0.32620 -0.35041 0.81772 0.45667 -0.10438 0.98119 0.16241 -0.19285 0.86375 0.46556 -0.23759 0.83675 0.49335 -0.09429 0.97610 0.19580 -0.05367 0.98169 0.18276 -0.07403 0.82361 0.56230 -0.00000 0.86006 0.51020 -0.00000 0.97770 0.21000 0.00000 0.97770 0.21000 0.07403 0.82361 0.56230 0.05367 0.98169 0.18276 0.20977 0.83638 0.50643 0.22385 0.85664 0.46482 0.09429 0.97610 0.19580 0.10438 0.98119 0.16241 0.35041 0.81772 0.45666 0.16593 0.97560 0.14378 0.16059 0.97868 0.12807 0.41282 0.85395 0.31677 0.41722 0.84571 0.33273 0.17211 0.98194 0.07861 0.52918 0.81971 0.21918 0.48206 0.87384 0.06347 0.53424 0.83813 0.11015 0.22217 0.97423 0.03886 0.21610 0.97588 0.03106 0.81364 0.55878 -0.16051 0.85073 0.46784 -0.23954 0.64212 0.71513 -0.27617 0.65774 0.73793 -0.15112 0.47006 0.84484 -0.25553 0.45904 0.83586 -0.30104 0.11587 0.99032 -0.07642 0.39198 0.90754 -0.15075 -0.34968 0.91095 -0.21885 -0.41281 0.87590 -0.24976 -0.59330 0.78495 -0.17847 -0.11267 0.98835 -0.10230 -0.41718 0.87682 -0.23907 -0.15198 0.97322 -0.17246 -0.67118 0.71751 -0.18626 -0.97021 0.12813 -0.20560 -0.97355 0.12000 -0.19444 -0.81799 0.51345 -0.25934 -0.85665 0.46863 -0.21574 -0.98905 0.01086 -0.14718 0.99660 0.00256 -0.08240 0.99512 0.02698 -0.09487 0.99559 0.00524 -0.09365 0.99000 0.05900 -0.12817 0.99193 0.01270 -0.12613 0.98012 0.10552 -0.16803 0.97810 0.12744 -0.16458 0.02348 0.99271 -0.11822 0.02315 0.99272 -0.11824 0.01140 0.99185 -0.12690 -0.02193 0.99183 -0.12569 -0.01668 0.99127 -0.13081 -0.11535 0.98039 -0.15976 -0.87838 0.44072 -0.18497 -0.82070 0.51558 -0.24624 -0.92751 0.33656 -0.16267 -0.89470 0.38898 -0.21957 -0.95697 0.24041 -0.16253 0.49539 0.86620 -0.06547 0.60747 0.79420 0.01527 0.47459 0.87935 -0.03890 0.47459 -0.87935 -0.03890 0.60747 -0.79420 0.01527 0.49539 -0.86620 -0.06547 -0.95697 -0.24041 -0.16253 -0.89470 -0.38898 -0.21957 -0.92751 -0.33656 -0.16267 -0.82070 -0.51558 -0.24624 -0.87838 -0.44072 -0.18497 -0.11535 -0.98039 -0.15976 -0.01668 -0.99127 -0.13081 -0.02193 -0.99183 -0.12569 0.01140 -0.99185 -0.12690 0.02315 -0.99272 -0.11824 0.02349 -0.99271 -0.11822 0.97810 -0.12744 -0.16458 0.98012 -0.10552 -0.16803 0.99193 -0.01270 -0.12613 0.99000 -0.05900 -0.12817 0.99559 -0.00524 -0.09365 0.99511 -0.02729 -0.09488 0.99659 -0.00269 -0.08245 -0.98905 -0.01086 -0.14718 -0.85665 -0.46863 -0.21574 -0.81799 -0.51345 -0.25934 -0.97355 -0.12000 -0.19444 -0.97021 -0.12813 -0.20560 -0.67119 -0.71751 -0.18626 -0.15198 -0.97322 -0.17246 -0.41717 -0.87682 -0.23907 -0.11267 -0.98835 -0.10230 -0.59330 -0.78495 -0.17847 -0.41281 -0.87590 -0.24976 -0.34967 -0.91095 -0.21885 0.39198 -0.90754 -0.15075 0.11587 -0.99032 -0.07642 0.45904 -0.83586 -0.30104 0.47006 -0.84484 -0.25553 0.65774 -0.73793 -0.15112 0.64212 -0.71513 -0.27616 0.85073 -0.46784 -0.23954 0.81364 -0.55877 -0.16052 0.21610 -0.97588 0.03106 0.22217 -0.97423 0.03886 0.53424 -0.83813 0.11015 0.48206 -0.87384 0.06347 0.52918 -0.81972 0.21918 0.17211 -0.98194 0.07861 0.41722 -0.84571 0.33273 0.41282 -0.85395 0.31677 0.16059 -0.97868 0.12807 0.16593 -0.97560 0.14378 0.35041 -0.81772 0.45666 0.10438 -0.98119 0.16240 0.09430 -0.97610 0.19580 0.22385 -0.85664 0.46482 0.20977 -0.83638 0.50643 0.05367 -0.98169 0.18276 0.07403 -0.82361 0.56230 0.00000 -0.97770 0.21000 0.00000 -0.97770 0.21000 0.00000 -0.86006 0.51020 -0.07403 -0.82361 0.56230 -0.05367 -0.98169 0.18276 -0.09430 -0.97610 0.19580 -0.23759 -0.83675 0.49335 -0.19284 -0.86375 0.46556 -0.10438 -0.98119 0.16241 -0.35041 -0.81772 0.45666 -0.40904 -0.85222 0.32620 -0.42461 -0.84472 0.32582 -0.16700 -0.97692 0.13318 -0.15313 -0.97926 0.13269 -0.17211 -0.98194 0.07861 -0.52917 -0.81972 0.21918 -0.21605 -0.97566 0.03747 -0.22947 -0.97276 0.03299 -0.49466 -0.86319 0.10102 -0.53617 -0.84115 0.07059 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.01071 -0.99716 -0.07451 -0.21610 -0.97588 -0.03108 -0.21436 -0.97633 -0.02886 -0.53522 -0.83965 -0.09230 -0.49438 -0.86762 -0.05319 -0.54893 -0.80453 -0.22674 -0.17247 -0.98186 -0.07875 -0.17754 -0.97553 -0.12971 -0.15943 -0.97750 -0.13815 -0.16155 -0.97786 -0.13303 -0.11065 -0.97883 -0.17220 -0.00960 -0.99694 -0.07762 0.05378 -0.98162 -0.18311 0.08169 -0.98354 -0.16117 0.08418 -0.98780 -0.13101 0.10940 -0.98947 -0.09480 0.47616 -0.83648 -0.27126 0.17261 -0.98174 -0.07995 0.17249 -0.98186 -0.07876 0.53559 -0.82495 -0.18059 0.50647 -0.85791 -0.08650 0.21611 -0.97593 -0.02917 0.21287 -0.97660 -0.03061 0.53660 -0.84181 -0.05838 0.66836 -0.70886 -0.22541 0.68564 -0.69818 -0.20599 0.69915 -0.71091 -0.07607 0.71409 -0.69937 -0.03094 0.69542 -0.71275 0.09156 0.70058 -0.70113 0.13266 0.65079 -0.70980 0.26955 0.64937 -0.70381 0.28805 0.56221 -0.70555 0.43140 0.56358 -0.70736 0.42664 0.45431 -0.70258 0.54771 0.42796 -0.71119 0.55773 0.31819 -0.70029 0.63902 0.26809 -0.71360 0.64722 0.16416 -0.69891 0.69612 0.09129 -0.71478 0.69337 0.00095 -0.69850 0.71561 -0.09129 -0.71479 0.69336 -0.16274 -0.69898 0.69638 -0.26816 -0.71343 0.64739 -0.31648 -0.70044 0.63971 -0.42808 -0.71099 0.55788 -0.45311 -0.70274 0.54849 -0.56099 -0.70709 0.43047 -0.56351 -0.70605 0.42888 -0.64881 -0.70360 0.28980 -0.65047 -0.71014 0.26942 -0.70041 -0.70102 0.13414 -0.69525 -0.71292 0.09154 -0.71425 -0.69928 -0.02932 -0.69930 -0.71086 -0.07523 -0.68713 -0.69922 -0.19733 -0.66164 -0.71281 -0.23266 0.81130 -0.52202 -0.26323 0.94711 -0.27576 -0.16416 0.88222 -0.43490 -0.18041 0.81357 -0.58039 -0.03525 0.98805 -0.15153 0.02829 0.93036 -0.31338 0.19032 0.94327 -0.22931 0.24011 0.86295 -0.47345 0.17653 0.85161 -0.49875 0.16126 0.74119 -0.58526 0.32879 0.87889 -0.16852 0.44626 0.78342 -0.32584 0.52923 0.70606 -0.52343 0.47697 0.72890 -0.40527 0.55178 0.75755 -0.18606 0.62570 0.52581 -0.56716 0.63392 0.49427 -0.44401 0.74736 0.53979 -0.20603 0.81619 0.56280 -0.39615 0.72548 0.36533 -0.57289 0.73371 0.41985 -0.15917 0.89353 0.16931 -0.46073 0.87124 0.19566 -0.52283 0.82968 0.18407 -0.26251 0.94721 0.20530 -0.32205 0.92419 0.00107 -0.58598 0.81033 -0.00208 -0.14945 0.98877 -0.17194 -0.50317 0.84691 -0.20391 -0.44397 0.87253 -0.18978 -0.30012 0.93483 -0.21293 -0.25778 0.94245 -0.42339 -0.15752 0.89215 -0.36223 -0.57679 0.73219 -0.50053 -0.44467 0.74280 -0.52913 -0.32159 0.78524 -0.60294 -0.20667 0.77055 -0.52676 -0.56208 0.63764 -0.76020 -0.18305 0.62336 -0.78755 -0.32668 0.52254 -0.74356 -0.45136 0.49335 -0.66848 -0.54248 0.50877 -0.88044 -0.17084 0.44231 -0.74131 -0.58380 0.33111 -0.85829 -0.48487 0.16803 -0.86306 -0.47729 0.16529 -0.95379 -0.23540 0.18672 -0.90531 -0.35925 0.22660 -0.98803 -0.15231 0.02462 -0.81205 -0.58264 -0.03333 -0.94612 -0.27353 -0.17330 -0.96703 -0.11833 -0.22549 0.97049 -0.10362 -0.21775 0.98223 -0.00774 -0.18752 0.98323 -0.00267 -0.18236 0.98379 -0.00131 -0.17931 -0.50205 -0.86153 -0.07555 -0.75499 -0.64466 -0.12002 -0.18521 -0.98270 0.00226 -0.49635 -0.86654 -0.05245 -0.75928 -0.63665 -0.13476 -0.15265 -0.98435 -0.08809 -0.43817 -0.86260 -0.25285 -0.43816 -0.86259 -0.25289 -0.66791 -0.63662 -0.38550 -0.81548 -0.33661 -0.47083 -0.66790 -0.63655 -0.38562 -0.81549 -0.33661 -0.47083 -0.11334 -0.98435 -0.13498 -0.32530 -0.86260 -0.38742 -0.32527 -0.86259 -0.38749 -0.49581 -0.63663 -0.59066 -0.60529 -0.33661 -0.72133 -0.49575 -0.63655 -0.59079 -0.60529 -0.33661 -0.72133 -0.17325 -0.86261 -0.47528 -0.06036 -0.98435 -0.16559 -0.17316 -0.86258 -0.47536 -0.26394 -0.63667 -0.72456 -0.32205 -0.33661 -0.88486 -0.26377 -0.63654 -0.72474 -0.32205 -0.33661 -0.88486 -0.00011 -0.98435 -0.17625 -0.00033 -0.86261 -0.50587 -0.00018 -0.86257 -0.50593 -0.00027 -0.63668 -0.77113 0.00000 -0.63652 -0.77126 0.00000 -0.33661 -0.94164 0.00000 -0.33661 -0.94164 0.17265 -0.86261 -0.47549 0.06015 -0.98435 -0.16567 0.26340 -0.63671 -0.72472 0.17282 -0.86257 -0.47550 0.26378 -0.63651 -0.72476 0.32204 -0.33661 -0.88486 0.32205 -0.33661 -0.88486 0.11317 -0.98435 -0.13512 0.32481 -0.86262 -0.38779 0.32501 -0.86257 -0.38773 0.49535 -0.63672 -0.59094 0.49578 -0.63649 -0.59083 0.60529 -0.33661 -0.72133 0.60529 -0.33661 -0.72133 0.43779 -0.86263 -0.25339 0.15254 -0.98435 -0.08829 0.43801 -0.86257 -0.25322 0.66756 -0.63673 -0.38593 0.81548 -0.33661 -0.47083 0.66796 -0.63648 -0.38565 0.81549 -0.33661 -0.47083 0.50219 -0.86149 -0.07512 0.17832 -0.98382 -0.01744 0.75944 -0.63670 -0.13368 0.49458 -0.86479 -0.08680 0.92820 -0.33635 -0.15910 0.76218 -0.63421 -0.12985 0.92804 -0.33665 -0.15942 0.99951 -0.02951 0.01072 0.99755 -0.01300 0.06870 0.99241 -0.09359 0.07981 0.98719 -0.10569 0.11953 0.97914 -0.20299 0.00898 0.97095 -0.21812 0.09841 0.93026 -0.36352 0.04963 0.99028 -0.10923 0.08615 0.97580 -0.18263 0.12026 0.93471 -0.34689 0.07742 0.91184 -0.39071 0.12605 0.97655 -0.18326 0.11302 0.96968 -0.20955 0.12572 0.90609 -0.40879 0.10909 0.90348 -0.41264 0.11598 0.97081 -0.21024 0.11544 0.97075 -0.21046 0.11555 0.90133 -0.41858 0.11136 0.90693 -0.41161 0.08971 0.97313 -0.21162 0.09076 0.97252 -0.21387 0.09195 0.90555 -0.41517 0.08727 0.91222 -0.40785 0.03889 0.94005 -0.34101 0.00346 0.97513 -0.21496 0.05390 0.67690 -0.72654 -0.11807 0.39136 -0.91190 -0.12361 0.67851 -0.72599 -0.11208 0.39401 -0.91117 -0.12055 0.12275 -0.98401 -0.12905 0.14727 -0.98306 -0.10906 0.88991 -0.44878 -0.08166 0.67546 -0.72994 -0.10459 0.97680 -0.20901 -0.04674 0.98737 -0.15822 0.00791 0.88256 -0.46708 -0.05410 0.67313 -0.73069 -0.11397 0.39452 -0.90629 -0.15161 0.15560 -0.97267 -0.17235 0.20498 -0.97043 -0.12751 0.41266 -0.90154 -0.13011 0.66864 -0.73621 -0.10446 0.87706 -0.47225 -0.08801 0.86294 -0.50345 -0.04334 0.97662 -0.20684 -0.05862 0.95305 -0.30225 0.01841 0.41286 -0.89892 -0.14658 0.66964 -0.73587 -0.10038 0.44440 -0.88902 -0.11024 0.21481 -0.96240 -0.16626 0.27767 -0.95538 -0.10076 0.66141 -0.74501 -0.08657 0.85760 -0.50858 -0.07656 0.89121 -0.45274 -0.02764 0.95307 -0.30015 0.03959 0.83220 -0.55424 -0.01632 0.66556 -0.74314 -0.06905 0.44439 -0.88903 -0.11017 0.28709 -0.95058 -0.11821 0.34986 -0.93602 -0.03830 0.48602 -0.87152 -0.06506 0.65156 -0.75687 -0.05118 0.82761 -0.55937 -0.04661 0.78701 -0.61653 0.02231 0.89950 -0.43693 0.00003 0.86262 -0.49633 0.09772 0.65879 -0.75209 -0.01890 0.48512 -0.87331 -0.04459 0.35396 -0.93430 -0.04231 0.52543 -0.85082 -0.00505 0.63807 -0.76997 0.00160 0.78437 -0.62028 0.00284 0.82782 -0.55858 0.05207 0.73553 -0.67452 0.06334 0.39538 -0.91773 0.03810 0.64629 -0.76188 0.04296 0.52248 -0.85197 0.03400 0.54333 -0.83792 0.05181 0.39770 -0.91679 0.03657 0.62616 -0.77739 0.05985 0.73516 -0.67524 0.05998 0.82094 -0.55921 0.11547 0.70120 -0.70680 0.09352 0.78542 -0.61244 0.08963 0.39986 -0.91211 0.09040 0.63090 -0.77059 0.09031 0.53956 -0.83714 0.08985 0.40328 -0.91078 0.08857 0.53892 -0.83760 0.08937 0.61786 -0.77982 0.10065 0.70174 -0.70532 0.10041 0.79437 -0.59751 0.10931 0.69151 -0.71401 0.10954 0.79482 -0.59711 0.10825 0.61953 -0.77621 0.11693 0.53560 -0.83585 0.12032 0.38696 -0.91454 0.11780 0.52138 -0.84620 0.11005 0.69199 -0.71170 0.12100 0.61360 -0.78018 0.12173 0.69919 -0.70570 0.11458 0.80324 -0.58413 0.11663 0.38034 -0.91836 0.10938 0.61362 -0.78013 0.12198 0.51954 -0.84480 0.12805 0.50050 -0.85817 0.11420 0.36156 -0.92374 0.12645 0.61190 -0.78124 0.12345 0.69924 -0.70444 0.12177 0.80209 -0.58681 0.11095 0.71282 -0.69283 0.10894 0.81707 -0.57022 0.08507 0.35851 -0.92917 0.09004 0.50061 -0.85828 0.11291 0.61155 -0.78419 0.10512 0.31995 -0.94054 0.11412 0.48311 -0.86987 0.09962 0.61072 -0.78474 0.10588 0.71291 -0.69370 0.10266 0.82253 -0.56124 0.09192 0.72364 -0.68407 0.09166 0.48471 -0.87160 0.07328 0.61061 -0.78919 0.06581 0.47298 -0.87876 0.06390 0.34302 -0.93650 0.07278 0.60756 -0.79129 0.06874 0.72415 -0.68671 0.06354 0.82020 -0.56902 0.05908 0.72526 -0.68565 0.06230 0.83514 -0.54897 0.03432 0.30890 -0.95080 0.02362 0.72544 -0.68826 -0.00498 0.76708 -0.63841 -0.06345 0.02223 -0.99318 -0.11441 -0.01814 -0.99371 -0.11047 0.03443 -0.99328 -0.11050 -0.02783 -0.99389 -0.10680 0.00962 -0.99402 -0.10880 -0.03387 -0.99478 -0.09629 0.07162 -0.99149 -0.10868 0.13935 -0.98044 -0.13899 -0.11159 -0.98321 -0.14441 0.07304 -0.98959 -0.12401 0.21395 -0.97158 -0.10128 0.14399 -0.98058 -0.13312 -0.14862 -0.98160 -0.11986 -0.03599 -0.99128 -0.12678 -0.04980 -0.99107 -0.12369 0.09626 -0.98851 -0.11651 -0.15618 -0.98019 -0.12183 0.19850 -0.97734 -0.07353 0.09327 -0.99439 -0.04984 0.26749 -0.96316 -0.02788 -0.20087 -0.97865 -0.04358 -0.04742 -0.99739 -0.05446 -0.05509 -0.99713 -0.05188 0.09839 -0.99400 -0.04784 -0.18248 -0.98245 -0.03874 0.20552 -0.97852 0.01597 0.26082 -0.96314 0.06586 0.09484 -0.99348 0.06329 -0.20065 -0.97736 0.06717 -0.05245 -0.99673 0.06144 -0.05856 -0.99624 0.06389 0.09195 -0.99382 0.06219 -0.19398 -0.97855 0.06932 0.21713 -0.97179 0.09212 0.09022 -0.98861 0.12044 0.23259 -0.96602 0.11273 -0.05736 -0.99109 0.12018 -0.19850 -0.97229 0.12345 -0.19714 -0.97251 0.12394 -0.06386 -0.99036 0.12292 0.08164 -0.98972 0.11745 0.21505 -0.96888 0.12256 0.08178 -0.99038 0.11160 0.20613 -0.97314 0.10250 -0.06407 -0.99172 0.11127 -0.19623 -0.97373 0.11551 -0.07243 -0.99073 0.11489 0.06958 -0.99176 0.10759 -0.20453 -0.97237 0.11255 0.20355 -0.97354 0.10383 0.17834 -0.98390 -0.01153 0.18002 -0.98361 -0.01052 0.07048 -0.99695 0.03347 -0.18521 -0.98268 -0.00555 -0.07328 -0.99664 0.03649 -0.19020 -0.98174 -0.00233 -0.67028 -0.71807 -0.18736 -0.68228 -0.71609 -0.14731 -0.40878 -0.90355 -0.12842 -0.14417 -0.98329 -0.11115 -0.38816 -0.90972 -0.14748 -0.98477 -0.16873 -0.04195 -0.67173 -0.73056 -0.12275 -0.14073 -0.98352 -0.11355 -0.87338 -0.47197 -0.12022 -0.87795 -0.45904 -0.13597 -0.97487 -0.20055 -0.09700 -0.97315 -0.22355 -0.05475 -0.38910 -0.90641 -0.16435 -0.66437 -0.73138 -0.15394 -0.40190 -0.90313 -0.15112 -0.21004 -0.96322 -0.16760 -0.14657 -0.97906 -0.14130 -0.86757 -0.47493 -0.14754 -0.65566 -0.74237 -0.13783 -0.95633 -0.26423 -0.12493 -0.85042 -0.51771 -0.09359 -0.94397 -0.32865 -0.03017 -0.40225 -0.90184 -0.15774 -0.65561 -0.74237 -0.13807 -0.31463 -0.93733 -0.14976 -0.18752 -0.97525 -0.11711 -0.42979 -0.89342 -0.13069 -0.84324 -0.52174 -0.12935 -0.63949 -0.76019 -0.11473 -0.80866 -0.58586 -0.05320 -0.92670 -0.36382 -0.09418 -0.89314 -0.44909 0.02497 -0.64455 -0.75899 -0.09212 -0.42857 -0.89652 -0.11216 -0.27717 -0.95443 -0.11060 -0.46761 -0.88060 -0.07671 -0.80460 -0.58891 -0.07620 -0.61810 -0.78350 -0.06387 -0.74688 -0.66491 0.00808 -0.87635 -0.48097 -0.02605 -0.82853 -0.55376 0.08299 -0.34041 -0.94013 -0.01699 -0.46303 -0.88590 -0.02797 -0.62775 -0.77828 -0.01457 -0.49928 -0.86644 0.00184 -0.34509 -0.93836 -0.01968 -0.74673 -0.66509 0.00703 -0.59594 -0.80296 0.01081 -0.81428 -0.57815 0.05191 -0.68723 -0.72339 0.06656 -0.35638 -0.93105 0.07835 -0.49176 -0.86856 0.06141 -0.60457 -0.79365 0.06788 -0.38872 -0.91905 0.06515 -0.50811 -0.85814 0.07369 -0.68882 -0.72016 0.08305 -0.58579 -0.80648 0.08025 -0.66255 -0.74185 0.10335 -0.78791 -0.60683 0.10463 -0.76748 -0.63009 0.11818 -0.58975 -0.79824 0.12249 -0.50168 -0.85686 0.11877 -0.50110 -0.85726 0.11834 -0.35537 -0.92771 0.11432 -0.58747 -0.79970 0.12390 -0.66384 -0.73668 0.12890 -0.77086 -0.62291 0.13326 -0.67093 -0.73109 0.12396 -0.36416 -0.92284 0.12548 -0.49759 -0.85543 0.14368 -0.58832 -0.79513 0.14714 -0.48921 -0.86128 0.13739 -0.34847 -0.92739 0.13608 -0.59586 -0.79038 0.14231 -0.67103 -0.72634 0.14886 -0.77873 -0.61514 0.12322 -0.79949 -0.58245 0.14687 -0.69421 -0.70748 0.13245 -0.59586 -0.79039 0.14224 -0.48920 -0.86127 0.13750 -0.34903 -0.93002 0.11504 -0.48077 -0.86705 0.13075 -0.31946 -0.93891 0.12806 -0.60576 -0.78404 0.13542 -0.69385 -0.70563 0.14372 -0.71707 -0.68553 0.12589 -0.79844 -0.58607 0.13791 -0.60650 -0.78777 0.10763 -0.48346 -0.86963 0.10007 -0.34769 -0.93308 0.09203 -0.48080 -0.87136 0.09780 -0.81869 -0.56324 0.11184 -0.61399 -0.78268 0.10210 -0.71775 -0.68733 0.11142 -0.73035 -0.67561 0.10075 -0.81854 -0.56354 0.11144 -0.31376 -0.94890 0.03382 -0.83204 -0.54949 0.07596 -0.61532 -0.78735 0.03828 -0.49664 -0.86705 -0.03972 -0.48479 -0.87424 -0.02599 -0.73242 -0.68062 0.01788 -0.76038 -0.64925 -0.01717 -0.99897 -0.02277 -0.03915 -0.99986 -0.01475 0.00849 -0.98375 -0.17861 0.01813 -0.99685 0.01506 -0.07784 -0.98943 -0.13338 0.05683 -0.97592 -0.21175 -0.05236 -0.92437 -0.37496 0.07034 -0.97187 -0.23444 -0.02237 -0.99013 -0.13632 0.03244 -0.97395 -0.21417 0.07446 -0.92371 -0.37938 0.05321 -0.97228 -0.21198 0.09871 -0.89409 -0.43290 0.11490 -0.96519 -0.23621 0.11231 -0.89489 -0.43069 0.11693 -0.88674 -0.44327 0.13118 -0.96207 -0.23408 0.14010 -0.96356 -0.22934 0.13766 -0.88968 -0.43458 0.14006 -0.89990 -0.41813 0.12388 -0.96340 -0.22926 0.13894 -0.96794 -0.21402 0.13148 -0.90059 -0.41583 0.12656 -0.91393 -0.39734 0.08277 -0.91458 -0.39600 0.08208 -0.97224 -0.21562 0.09088 -0.96454 -0.24231 0.10462 -0.98159 -0.00743 -0.19084 -0.98281 -0.00152 -0.18459 -0.98795 -0.04629 -0.14768 -0.99234 -0.00253 -0.12354 -0.99420 -0.03119 -0.10292 -0.99389 0.00000 -0.11040 -0.99412 0.02896 -0.10430 -0.99299 0.00268 -0.11817 -0.98795 0.04626 -0.14768 + + + + + + + + + + + + + + +

631 0 0 0 632 0 1 1 0 1 631 1 2 2 0 2 1 2 3 3 2 3 1 3 3 4 4 4 5 4 2 5 3 5 5 5 6 6 4 6 3 6 631 7 625 7 1 7 1 8 7 8 3 8 7 9 1 9 625 9 8 10 3 10 7 10 3 11 8 11 6 11 9 12 6 12 8 12 625 13 622 13 7 13 7 14 10 14 8 14 10 15 7 15 622 15 11 16 8 16 10 16 8 17 11 17 9 17 12 18 9 18 11 18 622 19 619 19 10 19 13 20 10 20 619 20 10 21 13 21 11 21 11 22 14 22 12 22 14 23 11 23 13 23 15 24 12 24 14 24 619 25 616 25 13 25 13 26 16 26 14 26 16 27 13 27 616 27 17 28 14 28 16 28 17 29 18 29 15 29 14 30 17 30 15 30 19 31 18 31 17 31 616 32 20 32 16 32 21 33 16 33 20 33 16 34 21 34 17 34 23 35 22 35 19 35 17 36 23 36 19 36 17 37 21 37 23 37 24 38 22 38 23 38 25 39 5 39 26 39 27 40 25 40 26 40 30 41 28 41 29 41 25 42 30 42 29 42 30 43 25 43 27 43 5 44 4 44 26 44 31 45 29 45 28 45 32 46 26 46 4 46 26 47 32 47 27 47 33 48 27 48 32 48 27 49 33 49 30 49 4 50 6 50 32 50 34 51 28 51 30 51 28 52 34 52 31 52 30 53 35 53 34 53 35 54 30 54 33 54 36 55 32 55 6 55 32 56 36 56 33 56 37 57 33 57 36 57 33 58 37 58 35 58 34 59 38 59 31 59 38 60 34 60 35 60 39 61 31 61 38 61 35 62 40 62 38 62 40 63 35 63 37 63 36 64 41 64 37 64 41 65 36 65 6 65 6 66 9 66 41 66 42 67 37 67 41 67 37 68 42 68 40 68 38 69 43 69 39 69 43 70 38 70 40 70 44 71 40 71 42 71 40 72 44 72 43 72 45 73 39 73 43 73 41 74 46 74 42 74 46 75 41 75 9 75 47 76 42 76 46 76 42 77 47 77 44 77 43 78 48 78 45 78 48 79 43 79 44 79 44 80 49 80 48 80 49 81 44 81 47 81 46 82 9 82 12 82 50 83 46 83 12 83 46 84 50 84 47 84 47 85 51 85 49 85 51 86 47 86 50 86 52 87 48 87 49 87 48 88 52 88 45 88 53 89 49 89 51 89 49 90 53 90 52 90 54 91 45 91 52 91 50 92 55 92 51 92 55 93 50 93 12 93 51 94 56 94 53 94 56 95 51 95 55 95 52 96 57 96 54 96 57 97 52 97 53 97 58 98 53 98 56 98 53 99 58 99 57 99 59 100 54 100 57 100 55 101 12 101 15 101 60 102 55 102 15 102 55 103 60 103 56 103 56 104 61 104 58 104 61 105 56 105 60 105 62 106 57 106 58 106 57 107 62 107 59 107 58 108 63 108 62 108 63 109 58 109 61 109 15 110 18 110 60 110 64 111 60 111 18 111 60 112 64 112 61 112 61 113 65 113 63 113 65 114 61 114 64 114 66 115 62 115 63 115 66 116 67 116 59 116 62 117 66 117 59 117 68 118 63 118 65 118 63 119 68 119 66 119 18 120 19 120 64 120 64 121 69 121 65 121 69 122 64 122 19 122 65 123 70 123 68 123 70 124 65 124 69 124 71 125 72 125 67 125 66 126 71 126 67 126 71 127 66 127 68 127 73 128 68 128 70 128 68 129 73 129 71 129 19 130 22 130 69 130 74 131 69 131 22 131 74 132 75 132 70 132 69 133 74 133 70 133 76 134 72 134 71 134 70 135 75 135 73 135 22 136 24 136 74 136 71 137 73 137 77 137 71 138 77 138 76 138 78 139 77 139 73 139 78 140 73 140 75 140 79 141 78 141 75 141 83 142 29 142 31 142 83 143 81 143 82 143 29 144 83 144 82 144 84 145 82 145 81 145 84 146 85 146 86 146 84 147 86 147 82 147 87 148 85 148 84 148 31 149 39 149 83 149 81 150 88 150 84 150 88 151 81 151 83 151 89 152 83 152 39 152 83 153 89 153 88 153 84 154 90 154 87 154 90 155 84 155 88 155 91 156 87 156 90 156 88 157 92 157 90 157 92 158 88 158 89 158 89 159 39 159 45 159 93 160 89 160 45 160 89 161 93 161 92 161 90 162 94 162 91 162 94 163 90 163 92 163 95 164 91 164 94 164 45 165 54 165 93 165 92 166 96 166 94 166 96 167 92 167 93 167 93 168 97 168 96 168 97 169 93 169 54 169 98 170 94 170 96 170 94 171 98 171 95 171 99 172 95 172 98 172 54 173 59 173 97 173 96 174 100 174 98 174 100 175 96 175 97 175 97 176 101 176 100 176 101 177 97 177 59 177 98 178 102 178 99 178 102 179 98 179 100 179 103 180 99 180 102 180 59 181 67 181 101 181 100 182 104 182 102 182 104 183 100 183 101 183 101 184 105 184 104 184 105 185 101 185 67 185 106 186 107 186 103 186 102 187 106 187 103 187 106 188 102 188 104 188 67 189 72 189 105 189 108 190 107 190 106 190 104 191 109 191 106 191 109 192 104 192 105 192 110 193 109 193 105 193 110 194 105 194 72 194 106 195 109 195 108 195 72 196 76 196 110 196 111 197 108 197 109 197 113 198 114 198 112 198 115 199 113 199 112 199 86 200 85 200 116 200 118 201 114 201 113 201 119 202 113 202 115 202 113 203 119 203 118 203 115 204 120 204 119 204 120 205 115 205 117 205 121 206 116 206 85 206 116 207 121 207 117 207 117 208 122 208 120 208 122 209 117 209 121 209 123 210 119 210 120 210 119 211 123 211 118 211 120 212 124 212 123 212 124 213 120 213 122 213 121 214 125 214 122 214 125 215 121 215 85 215 122 216 126 216 124 216 126 217 122 217 125 217 85 218 87 218 125 218 127 219 118 219 123 219 128 220 123 220 124 220 123 221 128 221 127 221 124 222 129 222 128 222 129 223 124 223 126 223 130 224 125 224 87 224 125 225 130 225 126 225 131 226 126 226 130 226 126 227 131 227 129 227 87 228 91 228 130 228 128 229 132 229 127 229 132 230 128 230 129 230 133 231 129 231 131 231 129 232 133 232 132 232 130 233 134 233 131 233 134 234 130 234 91 234 135 235 131 235 134 235 131 236 135 236 133 236 136 237 127 237 132 237 137 238 132 238 133 238 132 239 137 239 136 239 133 240 138 240 137 240 138 241 133 241 135 241 134 242 139 242 135 242 139 243 134 243 91 243 140 244 135 244 139 244 135 245 140 245 138 245 91 246 95 246 139 246 137 247 141 247 136 247 141 248 137 248 138 248 142 249 136 249 141 249 138 250 143 250 141 250 143 251 138 251 140 251 144 252 139 252 95 252 139 253 144 253 140 253 145 254 140 254 144 254 140 255 145 255 143 255 95 256 99 256 144 256 146 257 141 257 143 257 141 258 146 258 142 258 143 259 147 259 146 259 147 260 143 260 145 260 144 261 148 261 145 261 148 262 144 262 99 262 149 263 145 263 148 263 145 264 149 264 147 264 150 265 142 265 146 265 146 266 151 266 150 266 151 267 146 267 147 267 147 268 152 268 151 268 152 269 147 269 149 269 148 270 153 270 149 270 148 271 99 271 103 271 153 272 148 272 103 272 154 273 149 273 153 273 149 274 154 274 152 274 155 275 151 275 152 275 155 276 156 276 150 276 151 277 155 277 150 277 152 278 157 278 155 278 157 279 152 279 154 279 153 280 103 280 107 280 158 281 153 281 107 281 153 282 158 282 154 282 154 283 159 283 157 283 159 284 154 284 158 284 160 285 156 285 155 285 155 286 161 286 160 286 161 287 155 287 157 287 157 288 162 288 161 288 162 289 157 289 159 289 158 290 163 290 159 290 158 291 107 291 108 291 163 292 158 292 108 292 164 293 159 293 163 293 159 294 164 294 162 294 161 295 162 295 165 295 165 296 166 296 160 296 161 297 165 297 160 297 167 298 162 298 164 298 167 299 165 299 162 299 108 300 111 300 163 300 168 301 163 301 111 301 163 302 168 302 164 302 164 303 169 303 167 303 164 304 168 304 169 304 170 305 167 305 169 305 171 306 462 306 172 306 463 307 462 307 171 307 173 308 171 308 172 308 114 309 173 309 172 309 173 310 114 310 118 310 118 311 127 311 173 311 174 312 171 312 173 312 171 313 174 313 463 313 175 314 463 314 174 314 173 315 176 315 174 315 176 316 173 316 127 316 127 317 136 317 176 317 177 318 174 318 176 318 174 319 177 319 175 319 178 320 175 320 177 320 176 321 179 321 177 321 179 322 176 322 136 322 136 323 142 323 179 323 180 324 177 324 179 324 177 325 180 325 178 325 181 326 178 326 180 326 179 327 182 327 180 327 182 328 179 328 142 328 142 329 150 329 182 329 180 330 183 330 181 330 183 331 180 331 182 331 184 332 181 332 183 332 182 333 185 333 183 333 182 334 150 334 156 334 185 335 182 335 156 335 156 336 160 336 185 336 183 337 186 337 184 337 186 338 183 338 185 338 187 339 185 339 160 339 187 340 186 340 185 340 160 341 166 341 187 341 454 342 172 342 462 342 190 343 114 343 172 343 190 344 172 344 454 344 191 345 112 345 114 345 191 346 114 346 190 346 112 347 192 347 86 347 192 348 112 348 191 348 86 349 193 349 82 349 193 350 86 350 192 350 454 351 450 351 190 351 194 352 190 352 450 352 190 353 194 353 191 353 191 354 195 354 192 354 195 355 191 355 194 355 196 356 192 356 195 356 192 357 196 357 193 357 193 358 197 358 82 358 197 359 193 359 196 359 450 360 446 360 194 360 198 361 194 361 446 361 194 362 198 362 195 362 199 363 195 363 198 363 195 364 199 364 196 364 200 365 196 365 199 365 196 366 200 366 197 366 201 367 197 367 200 367 197 368 201 368 82 368 446 369 442 369 198 369 202 370 198 370 442 370 198 371 202 371 199 371 203 372 199 372 202 372 199 373 203 373 200 373 200 374 204 374 201 374 204 375 200 375 203 375 201 376 205 376 82 376 205 377 201 377 204 377 442 378 438 378 202 378 206 379 202 379 438 379 202 380 206 380 203 380 207 381 203 381 206 381 203 382 207 382 204 382 208 383 204 383 207 383 204 384 208 384 205 384 209 385 205 385 208 385 205 386 209 386 82 386 438 387 434 387 206 387 210 388 206 388 434 388 206 389 210 389 207 389 207 390 211 390 208 390 211 391 207 391 210 391 212 392 208 392 211 392 208 393 212 393 209 393 209 394 213 394 82 394 213 395 209 395 212 395 434 396 430 396 210 396 214 397 210 397 430 397 210 398 214 398 211 398 211 399 215 399 212 399 215 400 211 400 214 400 216 401 212 401 215 401 212 402 216 402 213 402 217 403 213 403 216 403 213 404 217 404 82 404 430 405 426 405 214 405 214 406 218 406 215 406 218 407 214 407 426 407 215 408 219 408 216 408 219 409 215 409 218 409 220 410 216 410 219 410 216 411 220 411 217 411 221 412 217 412 220 412 217 413 221 413 82 413 426 414 632 414 218 414 632 415 0 415 218 415 219 416 5 416 220 416 221 417 25 417 29 417 82 418 221 418 29 418 25 419 220 419 5 419 220 420 25 420 221 420 222 421 223 421 224 421 225 422 222 422 224 422 422 423 224 423 223 423 226 424 224 424 422 424 422 425 419 425 226 425 227 426 226 426 419 426 419 427 418 427 227 427 228 428 227 428 418 428 418 429 417 429 228 429 229 430 228 430 417 430 417 431 416 431 229 431 230 432 229 432 416 432 416 433 415 433 230 433 231 434 230 434 415 434 415 435 414 435 231 435 232 436 231 436 414 436 414 437 413 437 232 437 233 438 232 438 413 438 413 439 412 439 233 439 234 440 233 440 412 440 412 441 411 441 234 441 235 442 234 442 411 442 411 443 410 443 235 443 236 444 235 444 410 444 410 445 409 445 236 445 237 446 236 446 409 446 409 447 408 447 237 447 238 448 237 448 408 448 408 449 407 449 238 449 239 450 238 450 407 450 407 451 406 451 239 451 240 452 239 452 406 452 406 453 405 453 240 453 240 454 405 454 188 454 240 455 188 455 241 455 240 456 241 456 189 456 240 457 189 457 80 457 242 458 240 458 80 458 244 459 225 459 224 459 245 460 244 460 224 460 247 461 246 461 245 461 224 462 226 462 245 462 245 463 226 463 227 463 248 464 245 464 227 464 248 465 249 465 247 465 245 466 248 466 247 466 250 467 249 467 248 467 227 468 228 468 248 468 251 469 252 469 250 469 248 470 251 470 250 470 251 471 248 471 228 471 228 472 229 472 251 472 253 473 252 473 251 473 251 474 229 474 230 474 254 475 251 475 230 475 251 476 254 476 253 476 255 477 253 477 254 477 230 478 231 478 254 478 254 479 231 479 232 479 256 480 254 480 232 480 256 481 257 481 255 481 254 482 256 482 255 482 232 483 233 483 256 483 258 484 257 484 256 484 256 485 233 485 234 485 259 486 256 486 234 486 259 487 260 487 258 487 256 488 259 488 258 488 234 489 235 489 259 489 261 490 260 490 259 490 259 491 235 491 236 491 262 492 259 492 236 492 259 493 262 493 261 493 263 494 261 494 262 494 236 495 237 495 262 495 264 496 265 496 263 496 262 497 264 497 263 497 264 498 262 498 237 498 237 499 238 499 264 499 266 500 265 500 264 500 267 501 268 501 266 501 264 502 267 502 266 502 264 503 238 503 239 503 267 504 264 504 239 504 239 505 240 505 267 505 269 506 268 506 267 506 267 507 242 507 269 507 267 508 240 508 242 508 270 509 269 509 242 509 79 510 243 510 271 510 246 511 271 511 243 511 272 512 271 512 246 512 246 513 247 513 272 513 273 514 272 514 247 514 247 515 249 515 273 515 274 516 273 516 249 516 249 517 250 517 274 517 274 518 250 518 252 518 275 519 274 519 252 519 252 520 253 520 275 520 276 521 275 521 253 521 253 522 255 522 276 522 277 523 276 523 255 523 255 524 257 524 277 524 278 525 277 525 257 525 257 526 258 526 278 526 279 527 278 527 258 527 258 528 260 528 279 528 280 529 279 529 260 529 260 530 261 530 280 530 281 531 280 531 261 531 261 532 263 532 281 532 281 533 263 533 265 533 282 534 281 534 265 534 265 535 266 535 282 535 283 536 282 536 266 536 266 537 268 537 283 537 284 538 283 538 268 538 268 539 269 539 284 539 285 540 284 540 269 540 269 541 270 541 285 541 285 542 270 542 286 542 284 543 285 543 287 543 288 544 289 544 290 544 288 545 290 545 287 545 288 546 287 546 285 546 285 547 286 547 288 547 291 548 289 548 288 548 288 549 292 549 291 549 288 550 286 550 292 550 293 551 291 551 292 551 294 552 293 552 292 552 292 553 168 553 294 553 294 554 168 554 295 554 297 555 295 555 296 555 300 556 299 556 298 556 298 557 301 557 300 557 302 558 300 558 301 558 301 559 303 559 302 559 304 560 302 560 303 560 79 561 271 561 303 561 303 562 271 562 272 562 303 563 272 563 305 563 303 564 305 564 304 564 306 565 304 565 305 565 297 566 299 566 295 566 294 567 295 567 299 567 299 568 300 568 294 568 293 569 294 569 300 569 300 570 302 570 293 570 291 571 293 571 302 571 302 572 304 572 291 572 289 573 291 573 304 573 304 574 306 574 289 574 290 575 289 575 306 575 306 576 307 576 290 576 308 577 290 577 307 577 307 578 309 578 308 578 310 579 308 579 309 579 309 580 311 580 310 580 312 581 310 581 311 581 311 582 313 582 312 582 314 583 312 583 313 583 313 584 315 584 314 584 316 585 314 585 315 585 272 586 273 586 305 586 317 587 305 587 273 587 317 588 307 588 306 588 317 589 306 589 305 589 273 590 274 590 317 590 309 591 307 591 317 591 318 592 311 592 309 592 317 593 318 593 309 593 317 594 274 594 275 594 318 595 317 595 275 595 275 596 276 596 318 596 313 597 311 597 318 597 318 598 276 598 277 598 319 599 318 599 277 599 318 600 319 600 313 600 315 601 313 601 319 601 277 602 278 602 319 602 320 603 319 603 278 603 320 604 316 604 315 604 319 605 320 605 315 605 278 606 279 606 320 606 314 607 316 607 320 607 320 608 279 608 280 608 321 609 320 609 280 609 320 610 321 610 314 610 312 611 314 611 321 611 280 612 281 612 321 612 322 613 310 613 312 613 321 614 322 614 312 614 321 615 281 615 282 615 322 616 321 616 282 616 308 617 310 617 322 617 282 618 283 618 322 618 322 619 283 619 284 619 322 620 284 620 287 620 322 621 287 621 308 621 290 622 308 622 287 622 167 623 270 623 242 623 242 624 165 624 167 624 170 625 286 625 270 625 170 626 270 626 167 626 292 627 286 627 170 627 168 628 292 628 170 628 168 629 111 629 295 629 170 630 169 630 168 630 301 631 298 631 303 631 78 632 303 632 298 632 303 633 78 633 79 633 297 634 76 634 298 634 298 635 77 635 78 635 298 636 76 636 77 636 75 637 243 637 79 637 24 638 225 638 244 638 244 639 74 639 24 639 74 640 244 640 243 640 243 641 75 641 74 641 225 642 24 642 222 642 186 643 241 643 188 643 186 644 187 644 241 644 187 645 189 645 241 645 166 646 189 646 187 646 80 647 189 647 166 647 80 648 166 648 165 648 80 649 165 649 242 649 109 650 295 650 111 650 109 651 296 651 295 651 109 652 110 652 296 652 76 653 296 653 110 653 76 654 297 654 296 654 297 655 298 655 299 655 244 656 245 656 246 656 243 657 244 657 246 657 5 658 219 658 218 658 2 659 5 659 218 659 0 660 2 660 218 660 86 661 117 661 112 661 112 662 117 662 115 662 86 663 116 663 117 663 548 664 517 664 518 664 522 665 519 665 517 665 548 666 522 666 517 666 632 667 426 667 630 667 630 668 426 668 627 668 627 669 426 669 425 669 402 670 399 670 401 670 401 671 399 671 400 671 348 672 346 672 347 672 558 673 349 673 348 673 558 674 524 674 349 674 525 675 349 675 524 675 525 676 350 676 349 676 525 677 523 677 350 677 554 678 403 678 469 678 554 679 469 679 468 679 554 680 468 680 455 680 468 681 456 681 455 681 456 682 404 682 455 682 186 683 404 683 456 683 186 684 188 684 404 684 420 685 421 685 610 685 402 686 560 686 559 686 560 687 402 687 401 687 401 688 610 688 560 688 610 689 401 689 420 689 559 690 555 690 402 690 347 691 557 691 558 691 347 692 556 692 557 692 348 693 347 693 558 693 342 694 555 694 556 694 556 695 347 695 342 695 344 696 342 696 347 696 464 697 466 697 465 697 466 698 350 698 523 698 466 699 464 699 353 699 353 700 464 700 359 700 464 701 467 701 375 701 464 702 375 702 359 702 403 703 467 703 469 703 467 704 403 704 375 704 355 705 358 705 337 705 323 706 337 706 358 706 323 707 358 707 361 707 323 708 361 708 362 708 363 709 323 709 362 709 337 710 323 710 335 710 323 711 363 711 324 711 324 712 363 712 364 712 324 713 333 713 323 713 323 714 333 714 335 714 365 715 324 715 364 715 333 716 324 716 331 716 325 717 331 717 324 717 324 718 365 718 325 718 325 719 365 719 366 719 331 720 325 720 329 720 367 721 325 721 366 721 326 722 330 722 325 722 325 723 330 723 329 723 325 724 367 724 326 724 368 725 326 725 367 725 330 726 326 726 332 726 327 727 332 727 326 727 326 728 368 728 327 728 327 729 368 729 369 729 332 730 327 730 334 730 370 731 327 731 369 731 327 732 370 732 328 732 328 733 370 733 371 733 328 734 336 734 327 734 327 735 336 735 334 735 336 736 328 736 338 736 372 737 328 737 371 737 328 738 340 738 339 738 328 739 339 739 338 739 328 740 372 740 340 740 373 741 340 741 372 741 329 742 330 742 331 742 332 743 331 743 330 743 331 744 332 744 333 744 334 745 333 745 332 745 333 746 334 746 335 746 336 747 335 747 334 747 335 748 336 748 337 748 338 749 337 749 336 749 337 750 338 750 355 750 339 751 355 751 338 751 355 752 339 752 356 752 341 753 356 753 339 753 356 754 341 754 354 754 343 755 354 755 341 755 354 756 343 756 352 756 345 757 352 757 343 757 352 758 345 758 351 758 346 759 351 759 345 759 351 760 346 760 350 760 348 761 350 761 346 761 339 762 340 762 341 762 342 763 341 763 340 763 342 764 340 764 373 764 342 765 373 765 374 765 555 766 342 766 374 766 341 767 342 767 343 767 344 768 343 768 342 768 343 769 344 769 345 769 347 770 345 770 344 770 345 771 347 771 346 771 348 772 349 772 350 772 351 773 350 773 466 773 353 774 351 774 466 774 351 775 353 775 352 775 352 776 353 776 354 776 357 777 353 777 359 777 357 778 354 778 353 778 354 779 357 779 356 779 360 780 357 780 359 780 357 781 360 781 358 781 357 782 358 782 355 782 357 783 355 783 356 783 361 784 358 784 360 784 360 785 359 785 375 785 376 786 360 786 375 786 360 787 376 787 361 787 377 788 361 788 376 788 361 789 377 789 362 789 379 790 362 790 377 790 362 791 379 791 363 791 380 792 363 792 379 792 363 793 380 793 364 793 364 794 380 794 382 794 384 795 364 795 382 795 364 796 384 796 365 796 385 797 365 797 384 797 365 798 385 798 366 798 387 799 366 799 385 799 366 800 387 800 367 800 388 801 367 801 387 801 367 802 388 802 368 802 390 803 368 803 388 803 368 804 390 804 369 804 392 805 369 805 390 805 369 806 392 806 370 806 393 807 370 807 392 807 370 808 393 808 371 808 371 809 393 809 395 809 396 810 371 810 395 810 371 811 396 811 372 811 398 812 372 812 396 812 372 813 398 813 373 813 399 814 373 814 398 814 373 815 399 815 374 815 399 816 402 816 374 816 555 817 374 817 402 817 375 818 403 818 376 818 378 819 403 819 405 819 378 820 376 820 403 820 376 821 378 821 377 821 406 822 378 822 405 822 378 823 406 823 381 823 381 824 406 824 407 824 381 825 379 825 378 825 378 826 379 826 377 826 379 827 381 827 380 827 408 828 381 828 407 828 381 829 408 829 383 829 383 830 382 830 381 830 381 831 382 831 380 831 409 832 383 832 408 832 382 833 383 833 384 833 386 834 384 834 383 834 383 835 409 835 386 835 386 836 409 836 410 836 384 837 386 837 385 837 411 838 386 838 410 838 389 839 387 839 386 839 386 840 387 840 385 840 386 841 411 841 389 841 389 842 411 842 412 842 387 843 389 843 388 843 413 844 389 844 412 844 391 845 390 845 389 845 389 846 390 846 388 846 389 847 413 847 391 847 391 848 413 848 414 848 415 849 391 849 414 849 390 850 391 850 392 850 394 851 392 851 391 851 391 852 415 852 394 852 394 853 415 853 416 853 392 854 394 854 393 854 417 855 394 855 416 855 394 856 417 856 397 856 397 857 395 857 394 857 394 858 395 858 393 858 418 859 397 859 417 859 395 860 397 860 396 860 400 861 398 861 397 861 397 862 398 862 396 862 397 863 418 863 400 863 400 864 418 864 419 864 422 865 400 865 419 865 398 866 400 866 399 866 400 867 422 867 401 867 401 868 422 868 420 868 403 869 554 869 405 869 405 870 554 870 455 870 405 871 455 871 404 871 405 872 404 872 188 872 424 873 423 873 609 873 609 874 627 874 424 874 552 875 605 875 423 875 423 876 605 876 609 876 425 877 424 877 627 877 427 878 552 878 423 878 423 879 424 879 427 879 428 880 427 880 424 880 424 881 425 881 428 881 425 882 426 882 429 882 429 883 428 883 425 883 430 884 429 884 426 884 431 885 552 885 427 885 427 886 428 886 431 886 432 887 431 887 428 887 428 888 429 888 432 888 429 889 430 889 433 889 433 890 432 890 429 890 434 891 433 891 430 891 431 892 432 892 435 892 435 893 552 893 431 893 436 894 435 894 432 894 432 895 433 895 436 895 433 896 434 896 437 896 437 897 436 897 433 897 438 898 437 898 434 898 439 899 552 899 435 899 435 900 436 900 439 900 440 901 439 901 436 901 436 902 437 902 440 902 441 903 440 903 437 903 437 904 438 904 441 904 442 905 441 905 438 905 439 906 440 906 443 906 443 907 552 907 439 907 440 908 441 908 444 908 444 909 443 909 440 909 445 910 444 910 441 910 441 911 442 911 445 911 446 912 445 912 442 912 447 913 552 913 443 913 443 914 444 914 447 914 448 915 447 915 444 915 444 916 445 916 448 916 449 917 448 917 445 917 445 918 446 918 449 918 450 919 449 919 446 919 447 920 448 920 451 920 451 921 552 921 447 921 452 922 451 922 448 922 448 923 449 923 452 923 449 924 450 924 453 924 453 925 452 925 449 925 454 926 453 926 450 926 451 927 452 927 548 927 548 928 552 928 451 928 452 929 453 929 522 929 522 930 548 930 452 930 453 931 454 931 520 931 453 932 520 932 522 932 454 933 462 933 520 933 474 934 456 934 468 934 456 935 457 935 186 935 456 936 474 936 457 936 186 937 457 937 184 937 478 938 457 938 474 938 457 939 478 939 458 939 458 940 478 940 484 940 458 941 184 941 457 941 184 942 458 942 181 942 492 943 458 943 484 943 458 944 492 944 459 944 459 945 181 945 458 945 181 946 459 946 178 946 498 947 459 947 492 947 459 948 498 948 460 948 460 949 178 949 459 949 178 950 460 950 175 950 507 951 460 951 498 951 460 952 507 952 461 952 461 953 175 953 460 953 175 954 461 954 463 954 516 955 461 955 507 955 461 956 516 956 520 956 520 957 462 957 461 957 461 958 462 958 463 958 464 959 465 959 467 959 470 960 465 960 466 960 470 961 467 961 465 961 471 962 470 962 466 962 466 963 523 963 471 963 526 964 471 964 523 964 467 965 472 965 469 965 467 966 470 966 472 966 473 967 474 967 469 967 469 968 474 968 468 968 473 969 469 969 472 969 475 970 472 970 470 970 470 971 471 971 475 971 471 972 526 972 476 972 476 973 526 973 527 973 476 974 475 974 471 974 472 975 475 975 477 975 477 976 473 976 472 976 473 977 477 977 479 977 479 978 474 978 473 978 474 979 479 979 478 979 475 980 476 980 480 980 480 981 477 981 475 981 481 982 480 982 476 982 476 983 527 983 481 983 481 984 527 984 531 984 477 985 480 985 482 985 482 986 479 986 477 986 483 987 484 987 479 987 479 988 484 988 478 988 479 989 482 989 483 989 485 990 482 990 480 990 480 991 481 991 485 991 481 992 531 992 486 992 486 993 531 993 535 993 486 994 485 994 481 994 482 995 485 995 487 995 487 996 483 996 482 996 483 997 487 997 488 997 488 998 484 998 483 998 484 999 488 999 492 999 489 1000 487 1000 485 1000 485 1001 486 1001 489 1001 486 1002 535 1002 490 1002 490 1003 489 1003 486 1003 487 1004 489 1004 491 1004 491 1005 488 1005 487 1005 493 1006 492 1006 488 1006 488 1007 491 1007 493 1007 539 1008 490 1008 535 1008 494 1009 491 1009 489 1009 489 1010 490 1010 494 1010 495 1011 494 1011 490 1011 490 1012 539 1012 495 1012 491 1013 494 1013 496 1013 496 1014 493 1014 491 1014 492 1015 493 1015 498 1015 493 1016 496 1016 497 1016 497 1017 498 1017 493 1017 543 1018 495 1018 539 1018 499 1019 496 1019 494 1019 494 1020 495 1020 499 1020 495 1021 543 1021 500 1021 500 1022 499 1022 495 1022 496 1023 499 1023 501 1023 501 1024 497 1024 496 1024 502 1025 498 1025 497 1025 497 1026 501 1026 502 1026 498 1027 502 1027 507 1027 503 1028 501 1028 499 1028 499 1029 500 1029 503 1029 500 1030 543 1030 504 1030 504 1031 503 1031 500 1031 505 1032 502 1032 501 1032 501 1033 503 1033 505 1033 502 1034 505 1034 506 1034 506 1035 507 1035 502 1035 547 1036 504 1036 543 1036 508 1037 505 1037 503 1037 503 1038 504 1038 508 1038 509 1039 508 1039 504 1039 504 1040 547 1040 509 1040 505 1041 508 1041 510 1041 510 1042 506 1042 505 1042 511 1043 507 1043 506 1043 506 1044 510 1044 511 1044 507 1045 511 1045 516 1045 549 1046 509 1046 547 1046 508 1047 509 1047 512 1047 512 1048 510 1048 508 1048 509 1049 549 1049 513 1049 513 1050 512 1050 509 1050 510 1051 512 1051 514 1051 514 1052 511 1052 510 1052 515 1053 516 1053 511 1053 511 1054 514 1054 515 1054 512 1055 513 1055 517 1055 517 1056 514 1056 512 1056 518 1057 517 1057 513 1057 513 1058 549 1058 518 1058 514 1059 517 1059 519 1059 519 1060 515 1060 514 1060 521 1061 516 1061 515 1061 515 1062 519 1062 521 1062 516 1063 521 1063 520 1063 548 1064 518 1064 549 1064 519 1065 522 1065 521 1065 521 1066 522 1066 520 1066 523 1067 525 1067 526 1067 562 1068 524 1068 558 1068 528 1069 526 1069 525 1069 524 1070 562 1070 529 1070 524 1071 529 1071 525 1071 525 1072 529 1072 530 1072 530 1073 528 1073 525 1073 526 1074 528 1074 527 1074 567 1075 529 1075 562 1075 528 1076 530 1076 532 1076 532 1077 531 1077 528 1077 528 1078 531 1078 527 1078 529 1079 567 1079 533 1079 533 1080 530 1080 529 1080 530 1081 533 1081 534 1081 534 1082 532 1082 530 1082 575 1083 533 1083 567 1083 531 1084 532 1084 535 1084 532 1085 534 1085 536 1085 536 1086 535 1086 532 1086 533 1087 575 1087 537 1087 537 1088 534 1088 533 1088 534 1089 537 1089 538 1089 538 1090 536 1090 534 1090 580 1091 537 1091 575 1091 535 1092 536 1092 539 1092 540 1093 539 1093 536 1093 536 1094 538 1094 540 1094 537 1095 580 1095 541 1095 541 1096 538 1096 537 1096 538 1097 541 1097 542 1097 542 1098 540 1098 538 1098 589 1099 541 1099 580 1099 539 1100 540 1100 543 1100 540 1101 542 1101 544 1101 544 1102 543 1102 540 1102 545 1103 542 1103 541 1103 541 1104 589 1104 545 1104 545 1105 589 1105 595 1105 542 1106 545 1106 546 1106 546 1107 544 1107 542 1107 543 1108 544 1108 547 1108 544 1109 546 1109 550 1109 550 1110 547 1110 544 1110 551 1111 546 1111 545 1111 545 1112 595 1112 551 1112 546 1113 551 1113 553 1113 553 1114 550 1114 546 1114 603 1115 551 1115 595 1115 547 1116 550 1116 549 1116 550 1117 552 1117 548 1117 550 1118 548 1118 549 1118 550 1119 553 1119 552 1119 605 1120 552 1120 551 1120 551 1121 552 1121 553 1121 551 1122 603 1122 605 1122 555 1123 559 1123 556 1123 556 1124 559 1124 561 1124 556 1125 561 1125 557 1125 563 1126 558 1126 557 1126 563 1127 557 1127 561 1127 611 1128 560 1128 610 1128 564 1129 561 1129 559 1129 558 1130 563 1130 562 1130 565 1131 564 1131 560 1131 560 1132 564 1132 559 1132 560 1133 611 1133 565 1133 613 1134 565 1134 611 1134 566 1135 563 1135 561 1135 561 1136 564 1136 566 1136 563 1137 566 1137 568 1137 568 1138 567 1138 563 1138 563 1139 567 1139 562 1139 564 1140 565 1140 569 1140 569 1141 566 1141 564 1141 565 1142 613 1142 570 1142 570 1143 569 1143 565 1143 614 1144 570 1144 613 1144 571 1145 568 1145 566 1145 566 1146 569 1146 571 1146 572 1147 575 1147 568 1147 568 1148 575 1148 567 1148 568 1149 571 1149 572 1149 569 1150 570 1150 573 1150 573 1151 571 1151 569 1151 574 1152 573 1152 570 1152 570 1153 614 1153 574 1153 617 1154 574 1154 614 1154 571 1155 573 1155 576 1155 576 1156 572 1156 571 1156 577 1157 575 1157 572 1157 572 1158 576 1158 577 1158 573 1159 574 1159 578 1159 578 1160 576 1160 573 1160 579 1161 578 1161 574 1161 574 1162 617 1162 579 1162 579 1163 617 1163 620 1163 575 1164 577 1164 580 1164 581 1165 577 1165 576 1165 576 1166 578 1166 581 1166 577 1167 581 1167 582 1167 582 1168 580 1168 577 1168 578 1169 579 1169 583 1169 583 1170 581 1170 578 1170 579 1171 620 1171 584 1171 584 1172 583 1172 579 1172 580 1173 582 1173 589 1173 585 1174 582 1174 581 1174 581 1175 583 1175 585 1175 586 1176 589 1176 582 1176 582 1177 585 1177 586 1177 583 1178 584 1178 587 1178 587 1179 585 1179 583 1179 588 1180 587 1180 584 1180 584 1181 620 1181 588 1181 588 1182 620 1182 623 1182 585 1183 587 1183 590 1183 590 1184 586 1184 585 1184 586 1185 590 1185 591 1185 591 1186 589 1186 586 1186 592 1187 590 1187 587 1187 587 1188 588 1188 592 1188 588 1189 623 1189 593 1189 593 1190 592 1190 588 1190 589 1191 591 1191 595 1191 594 1192 591 1192 590 1192 590 1193 592 1193 594 1193 591 1194 594 1194 596 1194 596 1195 595 1195 591 1195 597 1196 594 1196 592 1196 592 1197 593 1197 597 1197 626 1198 593 1198 623 1198 593 1199 626 1199 598 1199 598 1200 597 1200 593 1200 594 1201 597 1201 599 1201 599 1202 596 1202 594 1202 595 1203 596 1203 603 1203 596 1204 599 1204 600 1204 600 1205 603 1205 596 1205 601 1206 599 1206 597 1206 597 1207 598 1207 601 1207 602 1208 601 1208 598 1208 598 1209 626 1209 602 1209 599 1210 601 1210 604 1210 604 1211 600 1211 599 1211 606 1212 603 1212 600 1212 600 1213 604 1213 606 1213 628 1214 602 1214 626 1214 607 1215 604 1215 601 1215 601 1216 602 1216 607 1216 608 1217 607 1217 602 1217 602 1218 628 1218 608 1218 603 1219 606 1219 605 1219 627 1220 608 1220 628 1220 604 1221 607 1221 609 1221 609 1222 605 1222 604 1222 604 1223 605 1223 606 1223 607 1224 608 1224 609 1224 609 1225 608 1225 627 1225 610 1226 612 1226 611 1226 615 1227 612 1227 20 1227 615 1228 613 1228 612 1228 612 1229 613 1229 611 1229 616 1230 615 1230 20 1230 613 1231 615 1231 614 1231 618 1232 617 1232 615 1232 615 1233 617 1233 614 1233 615 1234 616 1234 618 1234 619 1235 618 1235 616 1235 617 1236 618 1236 620 1236 618 1237 619 1237 621 1237 621 1238 620 1238 618 1238 622 1239 621 1239 619 1239 620 1240 621 1240 623 1240 624 1241 623 1241 621 1241 621 1242 622 1242 624 1242 625 1243 624 1243 622 1243 623 1244 624 1244 626 1244 629 1245 626 1245 624 1245 624 1246 625 1246 629 1246 631 1247 629 1247 625 1247 626 1248 629 1248 628 1248 630 1249 627 1249 629 1249 629 1250 627 1250 628 1250 629 1251 631 1251 630 1251 631 1252 632 1252 630 1252 420 1253 422 1253 421 1253 223 1254 421 1254 422 1254 421 1255 612 1255 610 1255 223 1256 612 1256 421 1256 223 1257 20 1257 612 1257 20 1258 223 1258 21 1258 21 1259 223 1259 23 1259 23 1260 223 1260 222 1260 23 1261 222 1261 24 1261

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_middle/th_middle_E2M3.dae b/URDFs/sr_description/meshes/components/th_middle/th_middle_E2M3.dae new file mode 100644 index 0000000..df463ac --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_middle/th_middle_E2M3.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:04.601049 + 2012-07-23T02:14:04.601062 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -10.82211 1.89451 0.02984 -10.52279 1.19648 4.40604 -10.43772 3.42460 0.02983 -10.01191 3.48500 4.44190 -9.24738 5.48540 3.30954 -9.53206 5.50770 0.02984 -8.76916 5.54120 6.52921 -9.89934 1.32759 8.78240 -9.34524 3.61260 8.85396 -8.04629 5.52890 11.15913 -9.26471 1.36724 13.15861 -8.71246 3.57270 13.26610 -7.62288 5.23110 15.49638 -8.79618 1.20098 17.53489 -8.36209 3.12530 17.67809 -7.64989 4.79500 18.13671 -8.53313 0.87560 21.91118 -8.31577 2.41180 22.09022 -7.82107 4.31860 20.58139 -8.02359 3.94460 22.84329 -8.30538 -0.79062 26.28739 -8.30538 0.70052 26.28740 -8.18404 3.75820 24.93399 -8.28854 1.69868 26.40406 -8.25863 3.80240 26.86291 -7.06228 8.40020 0.02984 -8.38620 6.91280 2.41682 -7.24683 8.13770 2.46228 -4.47194 9.96990 2.48145 -3.75606 10.29400 0.02976 -5.94010 9.15660 2.50980 -2.75840 10.49580 3.62321 -8.07380 6.89460 4.80358 -6.95048 8.05290 4.89452 -4.28569 9.79750 4.93299 -5.69028 9.01010 4.98983 -7.68404 6.86400 7.19021 -6.59311 7.90890 7.32682 -4.12086 9.51920 7.38459 -2.57576 10.09530 7.41507 -5.41925 8.76810 7.46987 -7.28799 6.80580 9.57691 -6.23702 7.73940 9.75913 -3.95787 9.22070 9.83620 -5.15147 8.50730 9.94991 -2.40556 9.64210 11.24200 -6.95685 6.70500 11.96360 -5.94428 7.57760 12.19143 -3.77749 8.98770 12.28781 -4.91141 8.30410 12.42994 -6.76190 6.54660 14.35030 -5.77712 7.45700 14.62374 -3.56027 8.90580 14.73935 -4.72338 8.23520 14.90998 -2.13855 9.43290 14.94243 -6.77357 6.31590 16.73700 -5.79564 7.41050 17.05605 -3.28867 9.05710 17.19096 -4.61110 8.37220 17.38994 -1.72766 9.64300 18.33506 -7.00006 6.03250 19.12369 -5.99731 7.44970 19.48835 -2.99557 9.42630 19.64257 -4.58613 8.69440 19.86998 -7.34378 5.77480 21.51040 -6.30172 7.56070 21.92059 -2.76823 9.89430 22.09418 -1.33429 10.08770 21.40864 -4.64892 9.10020 22.35008 -7.69641 5.62700 23.89709 -6.62395 7.72770 24.35296 -2.69618 10.33660 24.54579 -1.13835 10.51830 24.18891 -4.79982 9.48510 24.83005 -7.87334 5.89220 26.22347 -6.92828 7.84400 26.71059 -1.22462 10.79640 26.70466 -3.12402 10.54986 26.98725 -5.11937 9.69790 27.34445 -5.42738 9.83580 28.97489 8.61265 5.13360 29.45177 0.06932 10.86760 3.80621 -0.01024 11.00000 0.02977 -1.40119 10.75920 3.81399 1.54101 10.76320 3.81675 2.87009 10.51680 3.52160 3.74599 10.31910 0.02461 3.06080 10.10820 6.97886 0.26646 10.44410 7.58258 -1.22349 10.34610 7.59807 1.75633 10.31870 7.60365 3.19084 9.65190 10.35776 0.40632 9.98440 11.35896 -1.07563 9.89580 11.38229 1.88615 9.84550 11.39063 3.12557 9.35790 13.61293 0.44521 9.74450 15.13533 -0.89992 9.67180 15.16637 1.78511 9.61390 15.17754 2.77768 9.38120 16.66155 0.34961 9.93570 18.91171 -0.65823 9.88990 18.95053 1.34910 9.84460 18.96453 2.21227 9.70760 19.47371 0.17213 10.39810 22.68822 -0.46781 10.38080 22.73461 0.80393 10.35940 22.75151 1.66398 10.14140 22.07601 1.30046 10.53670 24.50004 0.63860 10.78850 26.55730 -0.26995 10.78750 26.46785 1.22529 10.79760 26.75026 7.06210 8.42260 0.02481 8.41345 7.01390 2.18807 9.50643 5.48610 0.02976 7.26406 8.22570 2.23212 4.46815 10.02870 2.27030 5.94975 9.22990 2.28890 9.32640 5.51470 3.95308 8.34041 6.89470 4.35005 7.22057 8.06730 4.43978 4.53342 9.83020 4.51699 5.95696 9.03570 4.55093 8.18244 6.77210 6.51210 7.10496 7.85940 6.64744 4.60456 9.53340 6.76375 5.92833 8.75480 6.81304 9.00644 5.38790 7.87618 7.97886 6.64160 8.67407 6.94847 7.63310 8.85509 4.64917 9.20840 9.01044 5.86525 8.45070 9.07521 7.76899 6.49850 10.83612 6.78223 7.41940 11.06275 4.63475 8.92510 11.25721 5.76895 8.18680 11.33725 8.61378 5.22010 11.68501 7.59222 6.33800 12.99817 6.63741 7.24920 13.27048 4.52889 8.75350 13.50389 5.64082 8.02660 13.59928 7.48771 6.15560 15.16022 8.32521 4.90480 15.26346 6.54521 7.15350 15.47806 4.29922 8.76350 15.75065 5.48222 8.03360 15.86139 7.49153 5.94840 17.32228 6.53255 7.15940 17.68572 3.92877 9.00560 17.99735 5.29914 8.25080 18.12349 8.23527 4.41720 18.53411 7.59137 5.74270 19.48432 6.58862 7.26040 19.89338 3.49200 9.41690 20.24404 5.12194 8.61970 20.38567 7.73767 5.58670 21.64630 8.25740 3.95780 21.48409 6.68360 7.43260 22.10104 3.09609 9.89340 22.49073 4.98816 9.05000 22.64771 8.28384 3.71300 24.13419 7.87952 5.52970 23.80835 6.78704 7.65190 24.30869 2.84803 10.33120 24.73749 4.93555 9.45130 24.90974 7.96324 5.62190 25.97040 8.25683 3.76260 26.51529 6.86779 7.89350 26.51643 2.85645 10.62480 26.98418 5.02005 9.72250 27.17793 5.01206 9.91015 28.28688 10.72605 1.18730 4.35415 10.80892 1.89560 0.02976 10.22011 3.47460 4.38505 10.33368 1.07588 8.67846 10.30603 -1.32513 8.68545 9.83651 3.37060 8.74033 9.82534 0.96963 13.00276 9.78150 -1.36852 13.01323 9.35575 3.19910 13.09561 9.29663 0.82529 17.32708 9.25393 -1.21342 17.34108 8.92802 2.79230 17.45089 8.80583 0.66934 21.65139 8.78052 -0.89296 21.66892 8.60947 2.24530 21.80618 8.35632 -0.05477 25.91333 8.32436 1.64096 26.06027 8.66363 -0.09010 29.62890 8.64029 3.91250 29.54616 10.17118 1.89878 -3.67597 8.94513 5.49330 -3.22971 6.63522 8.42400 -2.39370 3.52367 10.33660 -1.26092 8.28971 1.89878 -6.93474 7.29022 5.49331 -6.09604 5.40599 8.42400 -4.51997 2.86939 10.33660 -2.39137 5.40719 1.89878 -9.35354 4.75482 5.49330 -8.22358 3.52367 8.42400 -6.09781 1.86812 10.33660 -3.23000 1.87124 1.89878 -10.64048 1.64468 5.49331 -9.35552 1.21532 8.42400 -6.93679 0.64044 10.33660 -3.67576 -1.89170 1.89878 -10.64048 -1.66514 5.49330 -9.35552 -1.24074 8.42400 -6.93594 -0.66558 10.33660 -3.67491 -5.42766 1.89878 -9.35354 -4.77529 5.49330 -8.22358 -3.54853 8.42400 -6.09527 -1.89270 10.33660 -3.22759 -8.31018 1.89878 -6.93474 -7.31069 5.49330 -6.09605 -5.42971 8.42400 -4.51615 -2.89297 10.33660 -2.38769 -10.19165 1.89878 -3.67597 -8.96560 5.49330 -3.22971 -6.65746 8.42400 -2.38896 -3.54577 10.33660 -1.25646 -8.65377 3.85249 29.52191 -8.67159 0.00316 29.58427 -8.97734 5.75739 31.26040 -8.62534 5.13799 29.42574 -8.92799 5.75739 33.24101 -8.44687 5.75739 35.16321 -7.55740 5.75739 36.93373 -6.30115 5.75739 38.46575 -4.74085 5.75739 39.68664 -2.95096 5.75739 40.53609 -1.01801 5.75739 40.97280 0.96295 5.75739 40.97697 2.89704 5.75739 40.54733 4.69025 5.75739 39.70474 6.25565 5.75739 38.49036 7.51734 5.75740 36.96280 8.41431 5.75740 35.19623 8.90306 5.75740 33.27615 8.95977 5.75740 31.29569 8.65656 1.84708 29.60358 8.35498 6.41670 28.91394 -7.38982 7.94489 28.76241 -8.31528 6.49310 28.80709 -8.78182 6.90539 32.00492 -8.03264 7.87869 30.76628 -8.10922 7.87869 32.63197 -8.12485 6.90539 35.36077 -7.75793 7.87869 34.46621 -6.99652 7.87869 36.17090 -6.23433 6.90539 38.21012 -5.86572 7.87869 37.65667 -4.42626 7.87869 38.84582 -3.39862 6.90539 40.12094 -2.75254 7.87869 39.67384 -0.04722 6.90539 40.80133 -0.93471 7.87869 40.09867 0.93269 7.87869 40.09620 3.30949 6.90540 40.14902 2.75003 7.87869 39.66762 4.42149 7.87869 38.83535 6.16175 6.90540 38.26267 5.85861 7.87870 37.64331 8.07595 6.90540 35.42908 6.98559 7.87870 36.15457 7.74269 7.87870 34.44783 8.76128 6.90540 32.07895 8.09009 7.87870 32.61324 8.00927 7.87870 30.74782 7.13755 8.03140 28.36388 -5.75442 10.12129 30.77964 -5.88891 10.12129 32.02981 -5.68858 10.12129 33.55129 -5.10133 10.12129 34.96911 -4.16711 10.12129 36.18661 -2.94961 10.12129 37.12083 -1.53171 10.12129 37.70816 -0.01024 10.12129 37.90848 1.51124 10.12129 37.70816 2.92913 10.12129 37.12083 4.14663 10.12129 36.18661 5.08086 10.12129 34.96911 5.66811 10.12129 33.55129 5.86843 10.12130 32.02981 5.73083 10.12130 30.76508 5.32404 10.12150 29.55953 4.88535 10.74795 32.02972 4.52677 10.77160 30.16474 3.59488 11.00000 30.97120 3.74711 11.00000 32.02981 3.15067 11.00000 29.99836 3.48542 10.81730 28.47776 2.45035 11.00000 29.19014 1.55063 11.00000 28.61201 0.52448 11.00000 28.31064 -0.22463 10.94620 27.71228 -0.90310 10.94670 27.80258 -3.41361 10.67647 27.95695 -1.57110 11.00000 28.61201 -2.47082 11.00000 29.19014 -3.75642 10.71769 28.67628 -3.17115 10.99999 29.99836 -4.54689 10.77160 30.16368 -3.61535 10.99999 30.97120 -4.90581 10.74795 32.02974 -3.76759 10.99999 32.02981 -3.61542 10.99999 33.08834 3.59495 11.00000 33.08834 -3.17115 10.99999 34.06111 3.15059 11.00000 34.06118 -2.47075 10.99999 34.86940 2.45028 11.00000 34.86940 -1.57111 10.99999 35.44761 1.55063 10.99999 35.44761 -0.54502 10.99999 35.74890 0.52455 10.99999 35.74890 -4.42986 10.77159 34.15820 -3.06869 10.77160 35.86501 -1.10180 10.77160 36.81225 1.08132 10.77160 36.81225 3.04821 10.77160 35.86501 4.40939 10.77160 34.15820 4.40939 -10.86170 34.15819 3.04822 -10.86170 35.86501 1.08133 -10.86170 36.81224 -1.10180 -10.86170 36.81224 -3.06868 -10.86170 35.86501 -4.42986 -10.86170 34.15819 0.52455 -11.09011 35.74890 -0.54502 -11.09011 35.74890 1.55064 -11.09011 35.44760 -1.57110 -11.09011 35.44760 2.45028 -11.09010 34.86940 -2.47075 -11.09011 34.86940 3.15060 -11.09010 34.06118 -3.17114 -11.09011 34.06110 3.59495 -11.09010 33.08834 -3.61542 -11.09011 33.08834 -3.76759 -11.09011 32.02980 -4.90581 -10.83806 32.02974 -3.61535 -11.09011 30.97119 -4.54689 -10.86171 30.16368 -3.17114 -11.09011 29.99836 -3.75641 -10.80780 28.67628 -2.47082 -11.09010 29.19013 -1.57110 -11.09010 28.61200 -3.41360 -10.76658 27.95695 -0.90309 -11.03680 27.80258 -0.22463 -11.03630 27.71228 0.52448 -11.09010 28.31063 1.55063 -11.09010 28.61200 2.45035 -11.09010 29.19013 3.48542 -10.90741 28.47776 3.15067 -11.09010 29.99836 3.74712 -11.09010 32.02980 3.59488 -11.09010 30.97119 4.52677 -10.86170 30.16474 4.88535 -10.83805 32.02972 5.32404 -10.21160 29.55953 5.73084 -10.21140 30.76507 5.86844 -10.21140 32.02980 5.66811 -10.21140 33.55128 5.08086 -10.21140 34.96910 4.14663 -10.21140 36.18660 2.92914 -10.21141 37.12083 1.51124 -10.21141 37.70815 -0.01023 -10.21141 37.90848 -1.53171 -10.21141 37.70815 -2.94960 -10.21141 37.12083 -4.16710 -10.21141 36.18660 -5.10133 -10.21140 34.96910 -5.68858 -10.21140 33.55128 -5.88891 -10.21140 32.02980 -5.75441 -10.21140 30.77964 7.13755 -8.12150 28.36388 8.00927 -7.96880 30.74782 8.09009 -7.96880 32.61324 8.76128 -6.99550 32.07895 7.74269 -7.96880 34.44782 6.98560 -7.96880 36.15456 8.07595 -6.99550 35.42908 5.85861 -7.96880 37.64331 6.16175 -6.99550 38.26267 4.42149 -7.96880 38.83535 2.75003 -7.96880 39.66762 3.30949 -6.99550 40.14902 0.93269 -7.96880 40.09619 -0.93471 -7.96880 40.09867 -0.04722 -6.99550 40.80132 -2.75254 -7.96880 39.67384 -3.39862 -6.99551 40.12094 -4.42626 -7.96880 38.84582 -5.86571 -7.96881 37.65667 -6.23433 -6.99551 38.21012 -6.99652 -7.96881 36.17090 -7.75793 -7.96880 34.46621 -8.12485 -6.99550 35.36077 -8.10922 -7.96881 32.63197 -8.03264 -7.96881 30.76628 -8.78182 -6.99550 32.00491 -8.31528 -6.58320 28.80709 -7.38981 -8.03500 28.76241 8.35498 -6.50680 28.91394 8.65656 -1.93718 29.60358 8.95977 -5.84750 31.29569 8.90306 -5.84750 33.27615 8.41431 -5.84750 35.19623 7.51734 -5.84750 36.96279 6.25565 -5.84750 38.49036 4.69026 -5.84750 39.70473 2.89704 -5.84750 40.54733 0.96295 -5.84750 40.97696 -1.01800 -5.84750 40.97280 -2.95095 -5.84750 40.53608 -4.74085 -5.84750 39.68664 -6.30115 -5.84750 38.46575 -7.55740 -5.84750 36.93373 -8.44687 -5.84750 35.16320 -8.92799 -5.84750 33.24101 -8.62534 -5.22810 29.42574 -8.65377 -3.94260 29.52191 -8.97734 -5.84750 31.26040 -3.54577 -10.42670 -1.25647 -6.65746 -8.51410 -2.38897 -8.96560 -5.58340 -3.22972 -10.19165 -1.98888 -3.67597 -2.89297 -10.42670 -2.38769 -5.42971 -8.51410 -4.51616 -7.31068 -5.58340 -6.09605 -8.31018 -1.98888 -6.93474 -1.89269 -10.42670 -3.22760 -3.54852 -8.51410 -6.09527 -4.77528 -5.58340 -8.22358 -5.42766 -1.98888 -9.35354 -0.66558 -10.42670 -3.67491 -1.24074 -8.51410 -6.93595 -1.66514 -5.58340 -9.35552 -1.89170 -1.98888 -10.64048 0.64045 -10.42670 -3.67576 1.21532 -8.51410 -6.93680 1.64468 -5.58340 -9.35552 1.87123 -1.98888 -10.64047 1.86813 -10.42670 -3.23000 3.52368 -8.51410 -6.09782 4.75482 -5.58340 -8.22358 5.40719 -1.98888 -9.35354 2.86939 -10.42670 -2.39137 5.40599 -8.51410 -4.51997 7.29022 -5.58340 -6.09604 8.28971 -1.98888 -6.93474 3.52367 -10.42670 -1.26092 6.63523 -8.51410 -2.39370 8.94513 -5.58340 -3.22972 10.17118 -1.98888 -3.67597 8.64029 -4.00260 29.54616 8.32436 -1.73106 26.06027 8.60947 -2.33540 21.80618 8.92802 -2.88240 17.45089 9.35575 -3.28920 13.09561 9.83651 -3.46070 8.74033 10.22011 -3.56470 4.38505 10.80892 -1.98570 0.02976 10.72605 -1.27740 4.35415 5.01207 -10.00026 28.28688 5.02005 -9.81260 27.17792 2.85645 -10.71490 26.98417 6.86779 -7.98360 26.51642 8.25683 -3.85270 26.51529 7.96325 -5.71200 25.97040 4.93555 -9.54140 24.90974 2.84804 -10.42130 24.73748 6.78704 -7.74200 24.30869 7.87952 -5.61980 23.80835 8.28384 -3.80310 24.13419 4.98816 -9.14010 22.64770 3.09609 -9.98350 22.49072 6.68360 -7.52270 22.10104 8.25740 -4.04790 21.48409 7.73768 -5.67680 21.64630 5.12194 -8.70980 20.38566 3.49200 -9.50700 20.24403 6.58863 -7.35050 19.89338 7.59137 -5.83280 19.48432 8.23527 -4.50730 18.53411 5.29915 -8.34090 18.12349 3.92878 -9.09570 17.99734 6.53255 -7.24950 17.68572 7.49153 -6.03850 17.32227 5.48222 -8.12370 15.86138 4.29923 -8.85360 15.75065 6.54521 -7.24360 15.47806 8.32521 -4.99490 15.26346 7.48771 -6.24570 15.16022 5.64083 -8.11670 13.59928 4.52889 -8.84360 13.50389 6.63742 -7.33930 13.27048 7.59222 -6.42810 12.99817 8.61378 -5.31020 11.68500 5.76895 -8.27690 11.33725 4.63475 -9.01520 11.25721 6.78224 -7.50950 11.06275 7.76900 -6.58860 10.83612 5.86526 -8.54080 9.07521 4.64917 -9.29850 9.01044 6.94848 -7.72320 8.85509 7.97887 -6.73170 8.67407 9.00644 -5.47800 7.87617 5.92833 -8.84490 6.81303 4.60456 -9.62350 6.76375 7.10496 -7.94950 6.64743 8.18244 -6.86220 6.51209 5.95697 -9.12580 4.55093 4.53343 -9.92030 4.51699 7.22057 -8.15740 4.43977 8.34041 -6.98480 4.35004 9.32640 -5.60480 3.95307 5.94975 -9.32000 2.28890 4.46815 -10.11880 2.27030 7.26406 -8.31580 2.23212 9.50643 -5.57620 0.02976 8.41345 -7.10400 2.18806 7.06211 -8.51270 0.02481 1.22529 -10.88770 26.75026 -0.26995 -10.87760 26.46784 0.63860 -10.87860 26.55729 1.30046 -10.62680 24.50003 1.66399 -10.23150 22.07600 0.80393 -10.44950 22.75150 -0.46780 -10.47090 22.73461 0.17213 -10.48820 22.68822 2.21228 -9.79770 19.47371 1.34910 -9.93470 18.96452 -0.65823 -9.98000 18.95052 0.34962 -10.02580 18.91170 2.77768 -9.47130 16.66155 1.78511 -9.70400 15.17754 -0.89992 -9.76190 15.16637 0.44522 -9.83460 15.13533 3.12557 -9.44800 13.61292 1.88616 -9.93560 11.39063 -1.07563 -9.98590 11.38229 0.40633 -10.07450 11.35896 3.19084 -9.74200 10.35776 1.75633 -10.40880 7.60365 -1.22349 -10.43620 7.59807 0.26646 -10.53420 7.58258 3.06080 -10.19830 6.97885 3.74599 -10.40920 0.02460 2.87010 -10.60690 3.52160 1.54102 -10.85330 3.81674 -1.40118 -10.84930 3.81398 -0.01023 -11.09010 0.02976 0.06932 -10.95770 3.80620 8.61265 -5.22370 29.45177 -5.42738 -9.92590 28.97489 -5.11936 -9.78800 27.34444 -3.12402 -10.63996 26.98725 -1.22462 -10.88650 26.70466 -6.92828 -7.93410 26.71059 -7.87333 -5.98230 26.22347 -4.79982 -9.57520 24.83005 -1.13835 -10.60840 24.18891 -2.69618 -10.42670 24.54579 -6.62395 -7.81780 24.35296 -7.69641 -5.71710 23.89709 -4.64892 -9.19030 22.35008 -1.33429 -10.17780 21.40864 -2.76823 -9.98440 22.09418 -6.30171 -7.65080 21.92059 -7.34378 -5.86490 21.51039 -4.58613 -8.78450 19.86997 -2.99557 -9.51640 19.64257 -5.99730 -7.53980 19.48835 -7.00006 -6.12260 19.12369 -1.72766 -9.73310 18.33506 -4.61109 -8.46230 17.38994 -3.28867 -9.14720 17.19096 -5.79564 -7.50060 17.05604 -6.77357 -6.40600 16.73700 -2.13855 -9.52300 14.94243 -4.72338 -8.32530 14.90997 -3.56026 -8.99590 14.73935 -5.77711 -7.54710 14.62374 -6.76190 -6.63670 14.35030 -4.91141 -8.39420 12.42994 -3.77749 -9.07780 12.28781 -5.94427 -7.66770 12.19143 -6.95685 -6.79510 11.96360 -2.40556 -9.73220 11.24200 -5.15147 -8.59740 9.94990 -3.95787 -9.31080 9.83620 -6.23701 -7.82950 9.75912 -7.28799 -6.89590 9.57691 -5.41925 -8.85820 7.46987 -2.57576 -10.18540 7.41507 -4.12086 -9.60930 7.38459 -6.59311 -7.99900 7.32682 -7.68404 -6.95410 7.19021 -5.69028 -9.10020 4.98983 -4.28568 -9.88760 4.93298 -6.95048 -8.14300 4.89451 -8.07380 -6.98470 4.80358 -2.75840 -10.58590 3.62321 -5.94010 -9.24670 2.50980 -3.75606 -10.38410 0.02976 -4.47194 -10.06000 2.48144 -7.24683 -8.22780 2.46228 -8.38620 -7.00290 2.41682 -7.06228 -8.49030 0.02983 -8.25863 -3.89250 26.86290 -8.18404 -3.84830 24.93399 -8.28218 -2.23900 26.50221 -8.02359 -4.03470 22.84328 -7.82107 -4.40870 20.58139 -8.31577 -2.50190 22.09022 -8.53313 -0.96570 21.91118 -7.64989 -4.88510 18.13671 -8.36209 -3.21540 17.67809 -8.79618 -1.29108 17.53489 -7.62288 -5.32120 15.49638 -8.71246 -3.66280 13.26609 -9.26471 -1.45734 13.15861 -8.04629 -5.61900 11.15913 -9.34524 -3.70270 8.85396 -9.89934 -1.41769 8.78240 -8.76916 -5.63130 6.52920 -9.53206 -5.59780 0.02983 -9.24738 -5.57550 3.30953 -10.01191 -3.57510 4.44190 -10.43772 -3.51470 0.02983 -10.52279 -1.28658 4.40604 -10.82211 -1.98461 0.02984 + + + + + + + + + + -0.99767 -0.00000 0.06824 -0.99767 0.00000 0.06824 -0.96454 0.24231 0.10462 -0.97224 0.21562 0.09088 -0.91458 0.39600 0.08208 -0.91393 0.39734 0.08277 -0.90059 0.41583 0.12656 -0.99000 0.00000 0.14104 -0.96794 0.21402 0.13148 -0.99000 -0.00000 0.14104 -0.96340 0.22926 0.13894 -0.89990 0.41813 0.12388 -0.88968 0.43458 0.14006 -0.98965 -0.00000 0.14352 -0.96356 0.22934 0.13766 -0.98965 -0.00000 0.14352 -0.96207 0.23408 0.14010 -0.88674 0.44327 0.13118 -0.89489 0.43069 0.11693 -0.99432 -0.00000 0.10645 -0.99432 0.00000 0.10645 -0.96519 0.23621 0.11231 -0.89409 0.43290 0.11490 -0.97228 0.21198 0.09871 -0.92371 0.37938 0.05321 -0.99820 0.00000 0.06000 -0.97395 0.21417 0.07446 -0.99820 0.00000 0.06000 -0.99013 0.13632 0.03244 -0.97187 0.23444 -0.02237 -0.92437 0.37496 0.07034 -0.97592 0.21175 -0.05236 -0.99865 0.00000 0.05197 -0.99865 -0.00000 0.05197 -0.98943 0.13338 0.05683 -0.99703 -0.00430 -0.07690 -0.98471 0.17078 0.03445 -0.99984 0.01582 0.00892 -0.99897 0.02275 -0.03915 -0.76038 0.64925 -0.01717 -0.73242 0.68061 0.01788 -0.48479 0.87424 -0.02599 -0.49664 0.86705 -0.03972 -0.61532 0.78735 0.03828 -0.83204 0.54949 0.07596 -0.31376 0.94890 0.03382 -0.81854 0.56354 0.11144 -0.73035 0.67561 0.10075 -0.71775 0.68733 0.11142 -0.61399 0.78268 0.10210 -0.81869 0.56324 0.11184 -0.48080 0.87136 0.09781 -0.34769 0.93308 0.09203 -0.48346 0.86963 0.10007 -0.60650 0.78777 0.10763 -0.79844 0.58607 0.13791 -0.71708 0.68553 0.12589 -0.69385 0.70563 0.14372 -0.60576 0.78404 0.13542 -0.31946 0.93891 0.12806 -0.48077 0.86705 0.13075 -0.34904 0.93002 0.11504 -0.48920 0.86127 0.13750 -0.59586 0.79039 0.14224 -0.69421 0.70748 0.13245 -0.79949 0.58245 0.14687 -0.77873 0.61514 0.12322 -0.67103 0.72634 0.14886 -0.59586 0.79038 0.14231 -0.34847 0.92739 0.13608 -0.48921 0.86128 0.13739 -0.58832 0.79513 0.14714 -0.49759 0.85543 0.14368 -0.36416 0.92284 0.12548 -0.67093 0.73109 0.12396 -0.77086 0.62291 0.13326 -0.66384 0.73668 0.12890 -0.58747 0.79970 0.12390 -0.35537 0.92771 0.11432 -0.50110 0.85726 0.11834 -0.50168 0.85686 0.11877 -0.58975 0.79824 0.12249 -0.76748 0.63009 0.11819 -0.78791 0.60683 0.10463 -0.66255 0.74185 0.10335 -0.58579 0.80648 0.08025 -0.68882 0.72016 0.08305 -0.50811 0.85814 0.07369 -0.38872 0.91905 0.06515 -0.60457 0.79365 0.06788 -0.49176 0.86856 0.06141 -0.35638 0.93105 0.07835 -0.68723 0.72339 0.06656 -0.81428 0.57815 0.05191 -0.59594 0.80296 0.01081 -0.74673 0.66509 0.00703 -0.34509 0.93836 -0.01968 -0.49928 0.86644 0.00184 -0.62775 0.77828 -0.01457 -0.46303 0.88590 -0.02797 -0.34041 0.94012 -0.01699 -0.82853 0.55376 0.08299 -0.87635 0.48096 -0.02605 -0.74688 0.66491 0.00808 -0.61810 0.78350 -0.06387 -0.80460 0.58891 -0.07620 -0.46761 0.88060 -0.07671 -0.27717 0.95443 -0.11060 -0.42857 0.89652 -0.11216 -0.64455 0.75899 -0.09212 -0.89314 0.44908 0.02497 -0.92670 0.36382 -0.09418 -0.80866 0.58586 -0.05320 -0.63949 0.76019 -0.11473 -0.84324 0.52174 -0.12935 -0.42979 0.89342 -0.13069 -0.18752 0.97526 -0.11710 -0.31463 0.93733 -0.14976 -0.65561 0.74237 -0.13807 -0.40225 0.90184 -0.15774 -0.94397 0.32865 -0.03017 -0.85042 0.51771 -0.09359 -0.95633 0.26423 -0.12493 -0.65566 0.74237 -0.13783 -0.86757 0.47493 -0.14754 -0.14656 0.97906 -0.14130 -0.21004 0.96322 -0.16760 -0.40190 0.90313 -0.15112 -0.66437 0.73138 -0.15394 -0.38910 0.90641 -0.16435 -0.97315 0.22354 -0.05475 -0.97487 0.20055 -0.09700 -0.87795 0.45904 -0.13597 -0.87338 0.47197 -0.12022 -0.14073 0.98352 -0.11355 -0.67173 0.73056 -0.12275 -0.98477 0.16873 -0.04195 -0.38816 0.90972 -0.14748 -0.14417 0.98329 -0.11115 -0.40878 0.90355 -0.12842 -0.68228 0.71609 -0.14731 -0.67028 0.71807 -0.18736 -0.19020 0.98174 -0.00233 -0.07328 0.99664 0.03649 -0.18521 0.98268 -0.00555 0.07048 0.99695 0.03347 0.18002 0.98361 -0.01052 0.17834 0.98390 -0.01153 0.20355 0.97354 0.10383 -0.20453 0.97237 0.11255 0.06958 0.99176 0.10759 -0.07243 0.99073 0.11489 -0.19623 0.97373 0.11551 -0.06407 0.99172 0.11127 0.20613 0.97314 0.10251 0.08178 0.99038 0.11160 0.21505 0.96888 0.12257 0.08164 0.98972 0.11746 -0.06386 0.99036 0.12292 -0.19714 0.97251 0.12394 -0.19850 0.97229 0.12345 -0.05736 0.99109 0.12018 0.23260 0.96602 0.11273 0.09021 0.98861 0.12044 0.21713 0.97179 0.09212 -0.19398 0.97855 0.06932 0.09195 0.99382 0.06219 -0.05856 0.99624 0.06389 -0.05245 0.99673 0.06144 -0.20065 0.97736 0.06717 0.09484 0.99348 0.06329 0.26082 0.96314 0.06586 0.20552 0.97852 0.01598 -0.18248 0.98245 -0.03874 0.09839 0.99400 -0.04784 -0.05509 0.99713 -0.05188 -0.04742 0.99739 -0.05446 -0.20086 0.97865 -0.04358 0.26749 0.96316 -0.02788 0.09327 0.99439 -0.04984 0.19850 0.97734 -0.07353 -0.15618 0.98019 -0.12183 0.09626 0.98851 -0.11651 -0.04980 0.99107 -0.12369 -0.03599 0.99128 -0.12678 -0.14862 0.98160 -0.11986 0.14399 0.98058 -0.13312 0.21395 0.97158 -0.10128 0.07304 0.98959 -0.12401 -0.11159 0.98321 -0.14441 0.13935 0.98044 -0.13899 0.07162 0.99149 -0.10868 -0.03387 0.99478 -0.09629 0.00962 0.99402 -0.10880 -0.02783 0.99389 -0.10680 0.03443 0.99328 -0.11050 -0.01814 0.99371 -0.11047 0.02223 0.99318 -0.11441 0.76708 0.63841 -0.06345 0.72544 0.68827 -0.00498 0.30890 0.95080 0.02362 0.83514 0.54897 0.03432 0.72526 0.68565 0.06231 0.82020 0.56902 0.05908 0.72415 0.68671 0.06354 0.60756 0.79129 0.06875 0.34302 0.93650 0.07278 0.47298 0.87876 0.06390 0.61061 0.78919 0.06581 0.48471 0.87160 0.07328 0.72364 0.68407 0.09166 0.82253 0.56124 0.09192 0.71291 0.69370 0.10266 0.61072 0.78474 0.10588 0.48311 0.86987 0.09962 0.31995 0.94054 0.11412 0.61155 0.78419 0.10512 0.50061 0.85828 0.11291 0.35851 0.92917 0.09004 0.81707 0.57022 0.08507 0.71282 0.69283 0.10894 0.80209 0.58681 0.11095 0.69924 0.70444 0.12177 0.61189 0.78125 0.12345 0.36156 0.92374 0.12645 0.50050 0.85817 0.11420 0.51954 0.84480 0.12805 0.61362 0.78013 0.12198 0.38034 0.91836 0.10938 0.80324 0.58413 0.11663 0.69919 0.70569 0.11458 0.61360 0.78018 0.12173 0.69199 0.71170 0.12100 0.52138 0.84620 0.11005 0.38696 0.91454 0.11780 0.53560 0.83585 0.12032 0.61953 0.77621 0.11693 0.79482 0.59711 0.10825 0.69151 0.71401 0.10954 0.79437 0.59751 0.10931 0.70174 0.70532 0.10041 0.61785 0.77982 0.10065 0.53892 0.83760 0.08937 0.40328 0.91078 0.08857 0.53956 0.83714 0.08985 0.63090 0.77059 0.09031 0.39986 0.91211 0.09040 0.78542 0.61244 0.08963 0.70120 0.70680 0.09352 0.82094 0.55921 0.11547 0.73516 0.67524 0.05998 0.62616 0.77739 0.05985 0.39770 0.91679 0.03657 0.54333 0.83792 0.05181 0.52248 0.85197 0.03400 0.64629 0.76188 0.04296 0.39538 0.91773 0.03811 0.73553 0.67452 0.06334 0.82782 0.55858 0.05207 0.78437 0.62028 0.00284 0.63807 0.76997 0.00160 0.52543 0.85082 -0.00505 0.35396 0.93430 -0.04231 0.48512 0.87331 -0.04459 0.65879 0.75209 -0.01890 0.86262 0.49633 0.09772 0.89950 0.43693 0.00003 0.78701 0.61653 0.02231 0.82761 0.55937 -0.04661 0.65156 0.75687 -0.05118 0.48602 0.87152 -0.06506 0.34986 0.93602 -0.03830 0.28709 0.95058 -0.11821 0.44439 0.88903 -0.11017 0.66556 0.74315 -0.06905 0.83220 0.55424 -0.01632 0.95307 0.30015 0.03959 0.89121 0.45274 -0.02764 0.85760 0.50858 -0.07656 0.66141 0.74501 -0.08656 0.27767 0.95538 -0.10076 0.21481 0.96240 -0.16626 0.44440 0.88902 -0.11024 0.66964 0.73587 -0.10038 0.41286 0.89892 -0.14658 0.95305 0.30225 0.01841 0.97662 0.20684 -0.05862 0.86294 0.50345 -0.04334 0.87706 0.47225 -0.08801 0.66864 0.73621 -0.10446 0.41266 0.90154 -0.13011 0.20498 0.97043 -0.12751 0.15560 0.97267 -0.17235 0.39452 0.90629 -0.15161 0.67313 0.73069 -0.11397 0.88256 0.46708 -0.05410 0.98737 0.15822 0.00791 0.97680 0.20901 -0.04674 0.67546 0.72995 -0.10459 0.88991 0.44878 -0.08166 0.14727 0.98306 -0.10906 0.12275 0.98401 -0.12905 0.39401 0.91117 -0.12055 0.67851 0.72599 -0.11208 0.39136 0.91190 -0.12361 0.67690 0.72654 -0.11807 0.99982 -0.00000 0.01916 0.99982 0.00000 0.01916 0.97513 0.21496 0.05390 0.94005 0.34101 0.00346 0.91222 0.40785 0.03889 0.90555 0.41517 0.08727 0.97237 0.21381 0.09374 0.99591 0.00000 0.09036 0.99528 -0.01118 0.09639 0.97380 0.20853 0.09075 0.90693 0.41161 0.08971 0.90133 0.41858 0.11136 0.97101 0.20716 0.11924 0.99313 -0.01110 0.11647 0.99259 -0.01807 0.12012 0.97296 0.20013 0.11528 0.90348 0.41264 0.11598 0.90609 0.40879 0.10909 0.97184 0.19947 0.12548 0.99252 -0.01807 0.12075 0.99237 -0.01995 0.12169 0.97791 0.17618 0.11249 0.91184 0.39071 0.12604 0.93471 0.34689 0.07742 0.99350 -0.02004 0.11204 0.97742 0.17578 0.11727 0.99384 -0.01487 0.10981 0.98959 0.11478 0.08680 0.93026 0.36352 0.04963 0.97095 0.21812 0.09841 0.97914 0.20299 0.00898 0.99463 -0.01497 0.10236 0.98622 0.11081 0.12284 0.99241 0.09359 0.07981 0.99756 0.01285 0.06868 0.99951 0.02951 0.01072 0.98551 0.00000 -0.16960 0.92804 0.33665 -0.15942 0.98551 -0.00000 -0.16960 0.76218 0.63421 -0.12985 0.92820 0.33635 -0.15910 0.49458 0.86479 -0.08680 0.75944 0.63670 -0.13368 0.17832 0.98382 -0.01744 0.50219 0.86149 -0.07512 0.86602 -0.00000 -0.50000 0.86602 -0.00000 -0.50000 0.81549 0.33661 -0.47083 0.66796 0.63648 -0.38565 0.81548 0.33661 -0.47083 0.66756 0.63673 -0.38593 0.43801 0.86257 -0.25322 0.15254 0.98435 -0.08829 0.43779 0.86263 -0.25339 0.64280 -0.00000 -0.76603 0.64280 0.00000 -0.76603 0.60529 0.33661 -0.72133 0.60529 0.33661 -0.72133 0.49578 0.63649 -0.59083 0.49535 0.63672 -0.59094 0.32501 0.86257 -0.38773 0.32481 0.86262 -0.38779 0.11317 0.98435 -0.13512 0.34201 0.00000 -0.93970 0.34201 -0.00000 -0.93970 0.32205 0.33661 -0.88486 0.32205 0.33662 -0.88486 0.26378 0.63651 -0.72476 0.17282 0.86257 -0.47550 0.26340 0.63671 -0.72472 0.06015 0.98435 -0.16567 0.17265 0.86261 -0.47549 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.33662 -0.94164 0.00000 0.33661 -0.94164 0.00000 0.63652 -0.77126 -0.00027 0.63668 -0.77113 -0.00018 0.86257 -0.50593 -0.00033 0.86261 -0.50586 -0.00011 0.98435 -0.17625 -0.34201 0.00000 -0.93970 -0.34201 0.00000 -0.93970 -0.32205 0.33661 -0.88486 -0.26377 0.63654 -0.72474 -0.32205 0.33661 -0.88486 -0.26394 0.63667 -0.72456 -0.17316 0.86258 -0.47536 -0.06036 0.98435 -0.16559 -0.17325 0.86261 -0.47528 -0.64280 0.00000 -0.76603 -0.64280 0.00000 -0.76603 -0.60529 0.33661 -0.72133 -0.49575 0.63655 -0.59079 -0.60529 0.33661 -0.72133 -0.49581 0.63663 -0.59066 -0.32527 0.86259 -0.38749 -0.32530 0.86260 -0.38742 -0.11334 0.98435 -0.13498 -0.86602 0.00000 -0.50000 -0.81549 0.33661 -0.47083 -0.86602 0.00000 -0.50000 -0.66790 0.63655 -0.38562 -0.81548 0.33661 -0.47083 -0.66791 0.63662 -0.38550 -0.43816 0.86259 -0.25289 -0.43817 0.86260 -0.25285 -0.15265 0.98435 -0.08809 -0.98584 0.00000 -0.16772 -0.98584 0.00000 -0.16772 -0.75928 0.63665 -0.13476 -0.49635 0.86654 -0.05245 -0.18521 0.98270 0.00226 -0.75499 0.64466 -0.12002 -0.50205 0.86153 -0.07555 -0.98281 0.00156 -0.18463 -0.98159 0.00743 -0.19084 -0.98377 0.00000 -0.17946 -0.99969 -0.00000 0.02491 -0.99969 0.00000 0.02491 -0.97007 0.00000 0.24281 -0.97007 -0.00000 0.24281 -0.89358 -0.00000 0.44891 -0.89358 -0.00000 0.44891 -0.77327 -0.00000 0.63408 -0.77327 -0.00000 0.63408 -0.61624 -0.00000 0.78756 -0.61624 -0.00000 0.78756 -0.42875 -0.00000 0.90343 -0.42874 -0.00000 0.90343 -0.22038 -0.00000 0.97541 -0.22038 -0.00000 0.97541 -0.00210 -0.00000 1.00000 -0.00210 -0.00000 1.00000 0.21685 -0.00000 0.97620 0.21685 -0.00000 0.97620 0.42527 -0.00000 0.90507 0.42527 -0.00000 0.90507 0.61295 -0.00000 0.79012 0.61295 0.00000 0.79012 0.77101 0.00000 0.63682 0.77102 -0.00000 0.63682 0.89165 0.00000 0.45273 0.89165 -0.00000 0.45273 0.96910 -0.00000 0.24668 0.96910 -0.00000 0.24668 0.99959 -0.00000 0.02862 0.99959 -0.00000 0.02862 0.98458 0.00000 -0.17493 0.98382 0.00125 -0.17918 0.98323 0.00267 -0.18236 0.98223 0.00774 -0.18752 0.97049 0.10362 -0.21775 -0.96703 0.11833 -0.22548 -0.94612 0.27353 -0.17330 -0.81205 0.58264 -0.03333 -0.98803 0.15231 0.02462 -0.90531 0.35925 0.22660 -0.95379 0.23541 0.18672 -0.86306 0.47728 0.16529 -0.85829 0.48487 0.16803 -0.74132 0.58379 0.33111 -0.88044 0.17084 0.44231 -0.66848 0.54248 0.50877 -0.74356 0.45136 0.49335 -0.78755 0.32668 0.52253 -0.76020 0.18305 0.62336 -0.52676 0.56208 0.63764 -0.60294 0.20667 0.77055 -0.52913 0.32159 0.78524 -0.50053 0.44467 0.74280 -0.36223 0.57679 0.73219 -0.42339 0.15752 0.89215 -0.21293 0.25778 0.94245 -0.18978 0.30012 0.93483 -0.20391 0.44397 0.87253 -0.17194 0.50317 0.84691 -0.00208 0.14945 0.98877 0.00107 0.58598 0.81033 0.20530 0.32205 0.92419 0.18407 0.26251 0.94721 0.19566 0.52283 0.82968 0.16931 0.46073 0.87124 0.41985 0.15917 0.89353 0.36533 0.57289 0.73371 0.56280 0.39615 0.72548 0.53979 0.20603 0.81619 0.49427 0.44401 0.74736 0.52581 0.56716 0.63392 0.75755 0.18606 0.62570 0.72890 0.40527 0.55178 0.70606 0.52343 0.47697 0.78342 0.32584 0.52923 0.87889 0.16852 0.44626 0.74119 0.58526 0.32879 0.85161 0.49875 0.16127 0.86295 0.47345 0.17653 0.94327 0.22931 0.24011 0.93036 0.31338 0.19032 0.98805 0.15153 0.02829 0.81357 0.58039 -0.03525 0.88222 0.43491 -0.18041 0.94711 0.27576 -0.16416 0.81130 0.52202 -0.26323 -0.66164 0.71281 -0.23266 -0.68713 0.69922 -0.19733 -0.69930 0.71086 -0.07523 -0.71425 0.69928 -0.02932 -0.69525 0.71292 0.09154 -0.70041 0.70102 0.13414 -0.65047 0.71014 0.26942 -0.64881 0.70360 0.28980 -0.56351 0.70605 0.42888 -0.56099 0.70709 0.43047 -0.45311 0.70274 0.54849 -0.42808 0.71099 0.55788 -0.31647 0.70044 0.63971 -0.26816 0.71343 0.64739 -0.16274 0.69898 0.69638 -0.09129 0.71479 0.69336 0.00095 0.69850 0.71561 0.09129 0.71478 0.69337 0.16416 0.69891 0.69612 0.26809 0.71360 0.64722 0.31819 0.70029 0.63902 0.42796 0.71119 0.55773 0.45431 0.70258 0.54771 0.56358 0.70736 0.42664 0.56221 0.70556 0.43140 0.64937 0.70381 0.28805 0.65079 0.70980 0.26955 0.70058 0.70113 0.13267 0.69542 0.71275 0.09156 0.71409 0.69937 -0.03094 0.69915 0.71091 -0.07607 0.68564 0.69818 -0.20599 0.66836 0.70886 -0.22541 0.53660 0.84181 -0.05838 0.21287 0.97660 -0.03061 0.21611 0.97593 -0.02917 0.50647 0.85791 -0.08650 0.53558 0.82495 -0.18059 0.17249 0.98186 -0.07876 0.17261 0.98174 -0.07995 0.47616 0.83648 -0.27126 0.10940 0.98947 -0.09480 0.08418 0.98780 -0.13101 0.08169 0.98354 -0.16117 0.05378 0.98162 -0.18311 -0.00960 0.99694 -0.07762 -0.11065 0.97883 -0.17220 -0.16155 0.97786 -0.13303 -0.15943 0.97750 -0.13814 -0.17754 0.97553 -0.12971 -0.17247 0.98186 -0.07875 -0.54893 0.80453 -0.22674 -0.49438 0.86762 -0.05319 -0.53522 0.83965 -0.09230 -0.21436 0.97633 -0.02886 -0.21610 0.97588 -0.03108 -0.01071 0.99716 -0.07451 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.53617 0.84115 0.07059 -0.49467 0.86319 0.10102 -0.22947 0.97276 0.03299 -0.21605 0.97566 0.03747 -0.52918 0.81972 0.21918 -0.17211 0.98194 0.07861 -0.15313 0.97926 0.13268 -0.16699 0.97692 0.13318 -0.42461 0.84472 0.32582 -0.40904 0.85222 0.32620 -0.35041 0.81772 0.45667 -0.10438 0.98119 0.16241 -0.19285 0.86375 0.46556 -0.23759 0.83675 0.49335 -0.09429 0.97610 0.19580 -0.05367 0.98169 0.18276 -0.07403 0.82361 0.56230 -0.00000 0.86006 0.51020 -0.00000 0.97770 0.21000 0.00000 0.97770 0.21000 0.07403 0.82361 0.56230 0.05367 0.98169 0.18276 0.20977 0.83638 0.50643 0.22385 0.85664 0.46482 0.09429 0.97610 0.19580 0.10438 0.98119 0.16241 0.35041 0.81772 0.45666 0.16593 0.97560 0.14378 0.16059 0.97868 0.12807 0.41282 0.85395 0.31677 0.41722 0.84571 0.33273 0.17211 0.98194 0.07861 0.52918 0.81971 0.21918 0.48206 0.87384 0.06347 0.53424 0.83813 0.11015 0.22217 0.97423 0.03886 0.21610 0.97588 0.03106 0.81364 0.55878 -0.16051 0.85073 0.46784 -0.23954 0.64212 0.71513 -0.27617 0.65774 0.73793 -0.15112 0.47006 0.84484 -0.25553 0.45904 0.83586 -0.30104 0.11587 0.99032 -0.07642 0.39198 0.90754 -0.15075 -0.34968 0.91095 -0.21885 -0.41281 0.87590 -0.24976 -0.59330 0.78495 -0.17847 -0.11267 0.98835 -0.10230 -0.41718 0.87682 -0.23907 -0.15198 0.97322 -0.17246 -0.67118 0.71751 -0.18626 -0.97021 0.12813 -0.20560 -0.97355 0.12000 -0.19444 -0.81799 0.51345 -0.25934 -0.85665 0.46863 -0.21574 -0.98905 0.01086 -0.14718 0.99660 0.00256 -0.08240 0.99512 0.02698 -0.09487 0.99559 0.00524 -0.09365 0.99000 0.05900 -0.12817 0.99193 0.01270 -0.12613 0.98012 0.10552 -0.16803 0.97810 0.12744 -0.16458 0.02348 0.99271 -0.11822 0.02315 0.99272 -0.11824 0.01140 0.99185 -0.12690 -0.02193 0.99183 -0.12569 -0.01668 0.99127 -0.13081 -0.11535 0.98039 -0.15976 -0.87838 0.44072 -0.18497 -0.82070 0.51558 -0.24624 -0.92751 0.33656 -0.16267 -0.89470 0.38898 -0.21957 -0.95697 0.24041 -0.16253 0.49539 0.86620 -0.06547 0.60747 0.79420 0.01527 0.47459 0.87935 -0.03890 0.47459 -0.87935 -0.03890 0.60747 -0.79420 0.01527 0.49539 -0.86620 -0.06547 -0.95697 -0.24041 -0.16253 -0.89470 -0.38898 -0.21957 -0.92751 -0.33656 -0.16267 -0.82070 -0.51558 -0.24624 -0.87838 -0.44072 -0.18497 -0.11535 -0.98039 -0.15976 -0.01668 -0.99127 -0.13081 -0.02193 -0.99183 -0.12569 0.01140 -0.99185 -0.12690 0.02315 -0.99272 -0.11824 0.02349 -0.99271 -0.11822 0.97810 -0.12744 -0.16458 0.98012 -0.10552 -0.16803 0.99193 -0.01270 -0.12613 0.99000 -0.05900 -0.12817 0.99559 -0.00524 -0.09365 0.99511 -0.02729 -0.09488 0.99659 -0.00269 -0.08245 -0.98905 -0.01086 -0.14718 -0.85665 -0.46863 -0.21574 -0.81799 -0.51345 -0.25934 -0.97355 -0.12000 -0.19444 -0.97021 -0.12813 -0.20560 -0.67119 -0.71751 -0.18626 -0.15198 -0.97322 -0.17246 -0.41717 -0.87682 -0.23907 -0.11267 -0.98835 -0.10230 -0.59330 -0.78495 -0.17847 -0.41281 -0.87590 -0.24976 -0.34967 -0.91095 -0.21885 0.39198 -0.90754 -0.15075 0.11587 -0.99032 -0.07642 0.45904 -0.83586 -0.30104 0.47006 -0.84484 -0.25553 0.65774 -0.73793 -0.15112 0.64212 -0.71513 -0.27616 0.85073 -0.46784 -0.23954 0.81364 -0.55877 -0.16052 0.21610 -0.97588 0.03106 0.22217 -0.97423 0.03886 0.53424 -0.83813 0.11015 0.48206 -0.87384 0.06347 0.52918 -0.81972 0.21918 0.17211 -0.98194 0.07861 0.41722 -0.84571 0.33273 0.41282 -0.85395 0.31677 0.16059 -0.97868 0.12807 0.16593 -0.97560 0.14378 0.35041 -0.81772 0.45666 0.10438 -0.98119 0.16240 0.09430 -0.97610 0.19580 0.22385 -0.85664 0.46482 0.20977 -0.83638 0.50643 0.05367 -0.98169 0.18276 0.07403 -0.82361 0.56230 0.00000 -0.97770 0.21000 0.00000 -0.97770 0.21000 0.00000 -0.86006 0.51020 -0.07403 -0.82361 0.56230 -0.05367 -0.98169 0.18276 -0.09430 -0.97610 0.19580 -0.23759 -0.83675 0.49335 -0.19284 -0.86375 0.46556 -0.10438 -0.98119 0.16241 -0.35041 -0.81772 0.45666 -0.40904 -0.85222 0.32620 -0.42461 -0.84472 0.32582 -0.16700 -0.97692 0.13318 -0.15313 -0.97926 0.13269 -0.17211 -0.98194 0.07861 -0.52917 -0.81972 0.21918 -0.21605 -0.97566 0.03747 -0.22947 -0.97276 0.03299 -0.49466 -0.86319 0.10102 -0.53617 -0.84115 0.07059 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.01071 -0.99716 -0.07451 -0.21610 -0.97588 -0.03108 -0.21436 -0.97633 -0.02886 -0.53522 -0.83965 -0.09230 -0.49438 -0.86762 -0.05319 -0.54893 -0.80453 -0.22674 -0.17247 -0.98186 -0.07875 -0.17754 -0.97553 -0.12971 -0.15943 -0.97750 -0.13815 -0.16155 -0.97786 -0.13303 -0.11065 -0.97883 -0.17220 -0.00960 -0.99694 -0.07762 0.05378 -0.98162 -0.18311 0.08169 -0.98354 -0.16117 0.08418 -0.98780 -0.13101 0.10940 -0.98947 -0.09480 0.47616 -0.83648 -0.27126 0.17261 -0.98174 -0.07995 0.17249 -0.98186 -0.07876 0.53559 -0.82495 -0.18059 0.50647 -0.85791 -0.08650 0.21611 -0.97593 -0.02917 0.21287 -0.97660 -0.03061 0.53660 -0.84181 -0.05838 0.66836 -0.70886 -0.22541 0.68564 -0.69818 -0.20599 0.69915 -0.71091 -0.07607 0.71409 -0.69937 -0.03094 0.69542 -0.71275 0.09156 0.70058 -0.70113 0.13266 0.65079 -0.70980 0.26955 0.64937 -0.70381 0.28805 0.56221 -0.70555 0.43140 0.56358 -0.70736 0.42664 0.45431 -0.70258 0.54771 0.42796 -0.71119 0.55773 0.31819 -0.70029 0.63902 0.26809 -0.71360 0.64722 0.16416 -0.69891 0.69612 0.09129 -0.71478 0.69337 0.00095 -0.69850 0.71561 -0.09129 -0.71479 0.69336 -0.16274 -0.69898 0.69638 -0.26816 -0.71343 0.64739 -0.31648 -0.70044 0.63971 -0.42808 -0.71099 0.55788 -0.45311 -0.70274 0.54849 -0.56099 -0.70709 0.43047 -0.56351 -0.70605 0.42888 -0.64881 -0.70360 0.28980 -0.65047 -0.71014 0.26942 -0.70041 -0.70102 0.13414 -0.69525 -0.71292 0.09154 -0.71425 -0.69928 -0.02932 -0.69930 -0.71086 -0.07523 -0.68713 -0.69922 -0.19733 -0.66164 -0.71281 -0.23266 0.81130 -0.52202 -0.26323 0.94711 -0.27576 -0.16416 0.88222 -0.43490 -0.18041 0.81357 -0.58039 -0.03525 0.98805 -0.15153 0.02829 0.93036 -0.31338 0.19032 0.94327 -0.22931 0.24011 0.86295 -0.47345 0.17653 0.85161 -0.49875 0.16126 0.74119 -0.58526 0.32879 0.87889 -0.16852 0.44626 0.78342 -0.32584 0.52923 0.70606 -0.52343 0.47697 0.72890 -0.40527 0.55178 0.75755 -0.18606 0.62570 0.52581 -0.56716 0.63392 0.49427 -0.44401 0.74736 0.53979 -0.20603 0.81619 0.56280 -0.39615 0.72548 0.36533 -0.57289 0.73371 0.41985 -0.15917 0.89353 0.16931 -0.46073 0.87124 0.19566 -0.52283 0.82968 0.18407 -0.26251 0.94721 0.20530 -0.32205 0.92419 0.00107 -0.58598 0.81033 -0.00208 -0.14945 0.98877 -0.17194 -0.50317 0.84691 -0.20391 -0.44397 0.87253 -0.18978 -0.30012 0.93483 -0.21293 -0.25778 0.94245 -0.42339 -0.15752 0.89215 -0.36223 -0.57679 0.73219 -0.50053 -0.44467 0.74280 -0.52913 -0.32159 0.78524 -0.60294 -0.20667 0.77055 -0.52676 -0.56208 0.63764 -0.76020 -0.18305 0.62336 -0.78755 -0.32668 0.52254 -0.74356 -0.45136 0.49335 -0.66848 -0.54248 0.50877 -0.88044 -0.17084 0.44231 -0.74131 -0.58380 0.33111 -0.85829 -0.48487 0.16803 -0.86306 -0.47729 0.16529 -0.95379 -0.23540 0.18672 -0.90531 -0.35925 0.22660 -0.98803 -0.15231 0.02462 -0.81205 -0.58264 -0.03333 -0.94612 -0.27353 -0.17330 -0.96703 -0.11833 -0.22549 0.97049 -0.10362 -0.21775 0.98223 -0.00774 -0.18752 0.98323 -0.00267 -0.18236 0.98379 -0.00131 -0.17931 -0.50205 -0.86153 -0.07555 -0.75499 -0.64466 -0.12002 -0.18521 -0.98270 0.00226 -0.49635 -0.86654 -0.05245 -0.75928 -0.63665 -0.13476 -0.15265 -0.98435 -0.08809 -0.43817 -0.86260 -0.25285 -0.43816 -0.86259 -0.25289 -0.66791 -0.63662 -0.38550 -0.81548 -0.33661 -0.47083 -0.66790 -0.63655 -0.38562 -0.81549 -0.33661 -0.47083 -0.11334 -0.98435 -0.13498 -0.32530 -0.86260 -0.38742 -0.32527 -0.86259 -0.38749 -0.49581 -0.63663 -0.59066 -0.60529 -0.33661 -0.72133 -0.49575 -0.63655 -0.59079 -0.60529 -0.33661 -0.72133 -0.17325 -0.86261 -0.47528 -0.06036 -0.98435 -0.16559 -0.17316 -0.86258 -0.47536 -0.26394 -0.63667 -0.72456 -0.32205 -0.33661 -0.88486 -0.26377 -0.63654 -0.72474 -0.32205 -0.33661 -0.88486 -0.00011 -0.98435 -0.17625 -0.00033 -0.86261 -0.50587 -0.00018 -0.86257 -0.50593 -0.00027 -0.63668 -0.77113 0.00000 -0.63652 -0.77126 0.00000 -0.33661 -0.94164 0.00000 -0.33661 -0.94164 0.17265 -0.86261 -0.47549 0.06015 -0.98435 -0.16567 0.26340 -0.63671 -0.72472 0.17282 -0.86257 -0.47550 0.26378 -0.63651 -0.72476 0.32204 -0.33661 -0.88486 0.32205 -0.33661 -0.88486 0.11317 -0.98435 -0.13512 0.32481 -0.86262 -0.38779 0.32501 -0.86257 -0.38773 0.49535 -0.63672 -0.59094 0.49578 -0.63649 -0.59083 0.60529 -0.33661 -0.72133 0.60529 -0.33661 -0.72133 0.43779 -0.86263 -0.25339 0.15254 -0.98435 -0.08829 0.43801 -0.86257 -0.25322 0.66756 -0.63673 -0.38593 0.81548 -0.33661 -0.47083 0.66796 -0.63648 -0.38565 0.81549 -0.33661 -0.47083 0.50219 -0.86149 -0.07512 0.17832 -0.98382 -0.01744 0.75944 -0.63670 -0.13368 0.49458 -0.86479 -0.08680 0.92820 -0.33635 -0.15910 0.76218 -0.63421 -0.12985 0.92804 -0.33665 -0.15942 0.99951 -0.02951 0.01072 0.99755 -0.01300 0.06870 0.99241 -0.09359 0.07981 0.98719 -0.10569 0.11953 0.97914 -0.20299 0.00898 0.97095 -0.21812 0.09841 0.93026 -0.36352 0.04963 0.99028 -0.10923 0.08615 0.97580 -0.18263 0.12026 0.93471 -0.34689 0.07742 0.91184 -0.39071 0.12605 0.97655 -0.18326 0.11302 0.96968 -0.20955 0.12572 0.90609 -0.40879 0.10909 0.90348 -0.41264 0.11598 0.97081 -0.21024 0.11544 0.97075 -0.21046 0.11555 0.90133 -0.41858 0.11136 0.90693 -0.41161 0.08971 0.97313 -0.21162 0.09076 0.97252 -0.21387 0.09195 0.90555 -0.41517 0.08727 0.91222 -0.40785 0.03889 0.94005 -0.34101 0.00346 0.97513 -0.21496 0.05390 0.67690 -0.72654 -0.11807 0.39136 -0.91190 -0.12361 0.67851 -0.72599 -0.11208 0.39401 -0.91117 -0.12055 0.12275 -0.98401 -0.12905 0.14727 -0.98306 -0.10906 0.88991 -0.44878 -0.08166 0.67546 -0.72994 -0.10459 0.97680 -0.20901 -0.04674 0.98737 -0.15822 0.00791 0.88256 -0.46708 -0.05410 0.67313 -0.73069 -0.11397 0.39452 -0.90629 -0.15161 0.15560 -0.97267 -0.17235 0.20498 -0.97043 -0.12751 0.41266 -0.90154 -0.13011 0.66864 -0.73621 -0.10446 0.87706 -0.47225 -0.08801 0.86294 -0.50345 -0.04334 0.97662 -0.20684 -0.05862 0.95305 -0.30225 0.01841 0.41286 -0.89892 -0.14658 0.66964 -0.73587 -0.10038 0.44440 -0.88902 -0.11024 0.21481 -0.96240 -0.16626 0.27767 -0.95538 -0.10076 0.66141 -0.74501 -0.08657 0.85760 -0.50858 -0.07656 0.89121 -0.45274 -0.02764 0.95307 -0.30015 0.03959 0.83220 -0.55424 -0.01632 0.66556 -0.74314 -0.06905 0.44439 -0.88903 -0.11017 0.28709 -0.95058 -0.11821 0.34986 -0.93602 -0.03830 0.48602 -0.87152 -0.06506 0.65156 -0.75687 -0.05118 0.82761 -0.55937 -0.04661 0.78701 -0.61653 0.02231 0.89950 -0.43693 0.00003 0.86262 -0.49633 0.09772 0.65879 -0.75209 -0.01890 0.48512 -0.87331 -0.04459 0.35396 -0.93430 -0.04231 0.52543 -0.85082 -0.00505 0.63807 -0.76997 0.00160 0.78437 -0.62028 0.00284 0.82782 -0.55858 0.05207 0.73553 -0.67452 0.06334 0.39538 -0.91773 0.03810 0.64629 -0.76188 0.04296 0.52248 -0.85197 0.03400 0.54333 -0.83792 0.05181 0.39770 -0.91679 0.03657 0.62616 -0.77739 0.05985 0.73516 -0.67524 0.05998 0.82094 -0.55921 0.11547 0.70120 -0.70680 0.09352 0.78542 -0.61244 0.08963 0.39986 -0.91211 0.09040 0.63090 -0.77059 0.09031 0.53956 -0.83714 0.08985 0.40328 -0.91078 0.08857 0.53892 -0.83760 0.08937 0.61786 -0.77982 0.10065 0.70174 -0.70532 0.10041 0.79437 -0.59751 0.10931 0.69151 -0.71401 0.10954 0.79482 -0.59711 0.10825 0.61953 -0.77621 0.11693 0.53560 -0.83585 0.12032 0.38696 -0.91454 0.11780 0.52138 -0.84620 0.11005 0.69199 -0.71170 0.12100 0.61360 -0.78018 0.12173 0.69919 -0.70570 0.11458 0.80324 -0.58413 0.11663 0.38034 -0.91836 0.10938 0.61362 -0.78013 0.12198 0.51954 -0.84480 0.12805 0.50050 -0.85817 0.11420 0.36156 -0.92374 0.12645 0.61190 -0.78124 0.12345 0.69924 -0.70444 0.12177 0.80209 -0.58681 0.11095 0.71282 -0.69283 0.10894 0.81707 -0.57022 0.08507 0.35851 -0.92917 0.09004 0.50061 -0.85828 0.11291 0.61155 -0.78419 0.10512 0.31995 -0.94054 0.11412 0.48311 -0.86987 0.09962 0.61072 -0.78474 0.10588 0.71291 -0.69370 0.10266 0.82253 -0.56124 0.09192 0.72364 -0.68407 0.09166 0.48471 -0.87160 0.07328 0.61061 -0.78919 0.06581 0.47298 -0.87876 0.06390 0.34302 -0.93650 0.07278 0.60756 -0.79129 0.06874 0.72415 -0.68671 0.06354 0.82020 -0.56902 0.05908 0.72526 -0.68565 0.06230 0.83514 -0.54897 0.03432 0.30890 -0.95080 0.02362 0.72544 -0.68826 -0.00498 0.76708 -0.63841 -0.06345 0.02223 -0.99318 -0.11441 -0.01814 -0.99371 -0.11047 0.03443 -0.99328 -0.11050 -0.02783 -0.99389 -0.10680 0.00962 -0.99402 -0.10880 -0.03387 -0.99478 -0.09629 0.07162 -0.99149 -0.10868 0.13935 -0.98044 -0.13899 -0.11159 -0.98321 -0.14441 0.07304 -0.98959 -0.12401 0.21395 -0.97158 -0.10128 0.14399 -0.98058 -0.13312 -0.14862 -0.98160 -0.11986 -0.03599 -0.99128 -0.12678 -0.04980 -0.99107 -0.12369 0.09626 -0.98851 -0.11651 -0.15618 -0.98019 -0.12183 0.19850 -0.97734 -0.07353 0.09327 -0.99439 -0.04984 0.26749 -0.96316 -0.02788 -0.20087 -0.97865 -0.04358 -0.04742 -0.99739 -0.05446 -0.05509 -0.99713 -0.05188 0.09839 -0.99400 -0.04784 -0.18248 -0.98245 -0.03874 0.20552 -0.97852 0.01597 0.26082 -0.96314 0.06586 0.09484 -0.99348 0.06329 -0.20065 -0.97736 0.06717 -0.05245 -0.99673 0.06144 -0.05856 -0.99624 0.06389 0.09195 -0.99382 0.06219 -0.19398 -0.97855 0.06932 0.21713 -0.97179 0.09212 0.09022 -0.98861 0.12044 0.23259 -0.96602 0.11273 -0.05736 -0.99109 0.12018 -0.19850 -0.97229 0.12345 -0.19714 -0.97251 0.12394 -0.06386 -0.99036 0.12292 0.08164 -0.98972 0.11745 0.21505 -0.96888 0.12256 0.08178 -0.99038 0.11160 0.20613 -0.97314 0.10250 -0.06407 -0.99172 0.11127 -0.19623 -0.97373 0.11551 -0.07243 -0.99073 0.11489 0.06958 -0.99176 0.10759 -0.20453 -0.97237 0.11255 0.20355 -0.97354 0.10383 0.17834 -0.98390 -0.01153 0.18002 -0.98361 -0.01052 0.07048 -0.99695 0.03347 -0.18521 -0.98268 -0.00555 -0.07328 -0.99664 0.03649 -0.19020 -0.98174 -0.00233 -0.67028 -0.71807 -0.18736 -0.68228 -0.71609 -0.14731 -0.40878 -0.90355 -0.12842 -0.14417 -0.98329 -0.11115 -0.38816 -0.90972 -0.14748 -0.98477 -0.16873 -0.04195 -0.67173 -0.73056 -0.12275 -0.14073 -0.98352 -0.11355 -0.87338 -0.47197 -0.12022 -0.87795 -0.45904 -0.13597 -0.97487 -0.20055 -0.09700 -0.97315 -0.22355 -0.05475 -0.38910 -0.90641 -0.16435 -0.66437 -0.73138 -0.15394 -0.40190 -0.90313 -0.15112 -0.21004 -0.96322 -0.16760 -0.14657 -0.97906 -0.14130 -0.86757 -0.47493 -0.14754 -0.65566 -0.74237 -0.13783 -0.95633 -0.26423 -0.12493 -0.85042 -0.51771 -0.09359 -0.94397 -0.32865 -0.03017 -0.40225 -0.90184 -0.15774 -0.65561 -0.74237 -0.13807 -0.31463 -0.93733 -0.14976 -0.18752 -0.97525 -0.11711 -0.42979 -0.89342 -0.13069 -0.84324 -0.52174 -0.12935 -0.63949 -0.76019 -0.11473 -0.80866 -0.58586 -0.05320 -0.92670 -0.36382 -0.09418 -0.89314 -0.44909 0.02497 -0.64455 -0.75899 -0.09212 -0.42857 -0.89652 -0.11216 -0.27717 -0.95443 -0.11060 -0.46761 -0.88060 -0.07671 -0.80460 -0.58891 -0.07620 -0.61810 -0.78350 -0.06387 -0.74688 -0.66491 0.00808 -0.87635 -0.48097 -0.02605 -0.82853 -0.55376 0.08299 -0.34041 -0.94013 -0.01699 -0.46303 -0.88590 -0.02797 -0.62775 -0.77828 -0.01457 -0.49928 -0.86644 0.00184 -0.34509 -0.93836 -0.01968 -0.74673 -0.66509 0.00703 -0.59594 -0.80296 0.01081 -0.81428 -0.57815 0.05191 -0.68723 -0.72339 0.06656 -0.35638 -0.93105 0.07835 -0.49176 -0.86856 0.06141 -0.60457 -0.79365 0.06788 -0.38872 -0.91905 0.06515 -0.50811 -0.85814 0.07369 -0.68882 -0.72016 0.08305 -0.58579 -0.80648 0.08025 -0.66255 -0.74185 0.10335 -0.78791 -0.60683 0.10463 -0.76748 -0.63009 0.11818 -0.58975 -0.79824 0.12249 -0.50168 -0.85686 0.11877 -0.50110 -0.85726 0.11834 -0.35537 -0.92771 0.11432 -0.58747 -0.79970 0.12390 -0.66384 -0.73668 0.12890 -0.77086 -0.62291 0.13326 -0.67093 -0.73109 0.12396 -0.36416 -0.92284 0.12548 -0.49759 -0.85543 0.14368 -0.58832 -0.79513 0.14714 -0.48921 -0.86128 0.13739 -0.34847 -0.92739 0.13608 -0.59586 -0.79038 0.14231 -0.67103 -0.72634 0.14886 -0.77873 -0.61514 0.12322 -0.79949 -0.58245 0.14687 -0.69421 -0.70748 0.13245 -0.59586 -0.79039 0.14224 -0.48920 -0.86127 0.13750 -0.34903 -0.93002 0.11504 -0.48077 -0.86705 0.13075 -0.31946 -0.93891 0.12806 -0.60576 -0.78404 0.13542 -0.69385 -0.70563 0.14372 -0.71707 -0.68553 0.12589 -0.79844 -0.58607 0.13791 -0.60650 -0.78777 0.10763 -0.48346 -0.86963 0.10007 -0.34769 -0.93308 0.09203 -0.48080 -0.87136 0.09780 -0.81869 -0.56324 0.11184 -0.61399 -0.78268 0.10210 -0.71775 -0.68733 0.11142 -0.73035 -0.67561 0.10075 -0.81854 -0.56354 0.11144 -0.31376 -0.94890 0.03382 -0.83204 -0.54949 0.07596 -0.61532 -0.78735 0.03828 -0.49664 -0.86705 -0.03972 -0.48479 -0.87424 -0.02599 -0.73242 -0.68062 0.01788 -0.76038 -0.64925 -0.01717 -0.99897 -0.02277 -0.03915 -0.99986 -0.01475 0.00849 -0.98375 -0.17861 0.01813 -0.99685 0.01506 -0.07784 -0.98943 -0.13338 0.05683 -0.97592 -0.21175 -0.05236 -0.92437 -0.37496 0.07034 -0.97187 -0.23444 -0.02237 -0.99013 -0.13632 0.03244 -0.97395 -0.21417 0.07446 -0.92371 -0.37938 0.05321 -0.97228 -0.21198 0.09871 -0.89409 -0.43290 0.11490 -0.96519 -0.23621 0.11231 -0.89489 -0.43069 0.11693 -0.88674 -0.44327 0.13118 -0.96207 -0.23408 0.14010 -0.96356 -0.22934 0.13766 -0.88968 -0.43458 0.14006 -0.89990 -0.41813 0.12388 -0.96340 -0.22926 0.13894 -0.96794 -0.21402 0.13148 -0.90059 -0.41583 0.12656 -0.91393 -0.39734 0.08277 -0.91458 -0.39600 0.08208 -0.97224 -0.21562 0.09088 -0.96454 -0.24231 0.10462 -0.98159 -0.00743 -0.19084 -0.98281 -0.00152 -0.18459 -0.98795 -0.04629 -0.14768 -0.99234 -0.00253 -0.12354 -0.99420 -0.03119 -0.10292 -0.99389 0.00000 -0.11040 -0.99412 0.02896 -0.10430 -0.99299 0.00268 -0.11817 -0.98795 0.04626 -0.14768 + + + + + + + + + + + + + + +

631 0 0 0 632 0 1 1 0 1 631 1 2 2 0 2 1 2 3 3 2 3 1 3 3 4 4 4 5 4 2 5 3 5 5 5 6 6 4 6 3 6 631 7 625 7 1 7 1 8 7 8 3 8 7 9 1 9 625 9 8 10 3 10 7 10 3 11 8 11 6 11 9 12 6 12 8 12 625 13 622 13 7 13 7 14 10 14 8 14 10 15 7 15 622 15 11 16 8 16 10 16 8 17 11 17 9 17 12 18 9 18 11 18 622 19 619 19 10 19 13 20 10 20 619 20 10 21 13 21 11 21 11 22 14 22 12 22 14 23 11 23 13 23 15 24 12 24 14 24 619 25 616 25 13 25 13 26 16 26 14 26 16 27 13 27 616 27 17 28 14 28 16 28 17 29 18 29 15 29 14 30 17 30 15 30 19 31 18 31 17 31 616 32 20 32 16 32 21 33 16 33 20 33 16 34 21 34 17 34 23 35 22 35 19 35 17 36 23 36 19 36 17 37 21 37 23 37 24 38 22 38 23 38 25 39 5 39 26 39 27 40 25 40 26 40 30 41 28 41 29 41 25 42 30 42 29 42 30 43 25 43 27 43 5 44 4 44 26 44 31 45 29 45 28 45 32 46 26 46 4 46 26 47 32 47 27 47 33 48 27 48 32 48 27 49 33 49 30 49 4 50 6 50 32 50 34 51 28 51 30 51 28 52 34 52 31 52 30 53 35 53 34 53 35 54 30 54 33 54 36 55 32 55 6 55 32 56 36 56 33 56 37 57 33 57 36 57 33 58 37 58 35 58 34 59 38 59 31 59 38 60 34 60 35 60 39 61 31 61 38 61 35 62 40 62 38 62 40 63 35 63 37 63 36 64 41 64 37 64 41 65 36 65 6 65 6 66 9 66 41 66 42 67 37 67 41 67 37 68 42 68 40 68 38 69 43 69 39 69 43 70 38 70 40 70 44 71 40 71 42 71 40 72 44 72 43 72 45 73 39 73 43 73 41 74 46 74 42 74 46 75 41 75 9 75 47 76 42 76 46 76 42 77 47 77 44 77 43 78 48 78 45 78 48 79 43 79 44 79 44 80 49 80 48 80 49 81 44 81 47 81 46 82 9 82 12 82 50 83 46 83 12 83 46 84 50 84 47 84 47 85 51 85 49 85 51 86 47 86 50 86 52 87 48 87 49 87 48 88 52 88 45 88 53 89 49 89 51 89 49 90 53 90 52 90 54 91 45 91 52 91 50 92 55 92 51 92 55 93 50 93 12 93 51 94 56 94 53 94 56 95 51 95 55 95 52 96 57 96 54 96 57 97 52 97 53 97 58 98 53 98 56 98 53 99 58 99 57 99 59 100 54 100 57 100 55 101 12 101 15 101 60 102 55 102 15 102 55 103 60 103 56 103 56 104 61 104 58 104 61 105 56 105 60 105 62 106 57 106 58 106 57 107 62 107 59 107 58 108 63 108 62 108 63 109 58 109 61 109 15 110 18 110 60 110 64 111 60 111 18 111 60 112 64 112 61 112 61 113 65 113 63 113 65 114 61 114 64 114 66 115 62 115 63 115 66 116 67 116 59 116 62 117 66 117 59 117 68 118 63 118 65 118 63 119 68 119 66 119 18 120 19 120 64 120 64 121 69 121 65 121 69 122 64 122 19 122 65 123 70 123 68 123 70 124 65 124 69 124 71 125 72 125 67 125 66 126 71 126 67 126 71 127 66 127 68 127 73 128 68 128 70 128 68 129 73 129 71 129 19 130 22 130 69 130 74 131 69 131 22 131 74 132 75 132 70 132 69 133 74 133 70 133 76 134 72 134 71 134 70 135 75 135 73 135 22 136 24 136 74 136 71 137 73 137 77 137 71 138 77 138 76 138 78 139 77 139 73 139 78 140 73 140 75 140 79 141 78 141 75 141 83 142 29 142 31 142 83 143 81 143 82 143 29 144 83 144 82 144 84 145 82 145 81 145 84 146 85 146 86 146 84 147 86 147 82 147 87 148 85 148 84 148 31 149 39 149 83 149 81 150 88 150 84 150 88 151 81 151 83 151 89 152 83 152 39 152 83 153 89 153 88 153 84 154 90 154 87 154 90 155 84 155 88 155 91 156 87 156 90 156 88 157 92 157 90 157 92 158 88 158 89 158 89 159 39 159 45 159 93 160 89 160 45 160 89 161 93 161 92 161 90 162 94 162 91 162 94 163 90 163 92 163 95 164 91 164 94 164 45 165 54 165 93 165 92 166 96 166 94 166 96 167 92 167 93 167 93 168 97 168 96 168 97 169 93 169 54 169 98 170 94 170 96 170 94 171 98 171 95 171 99 172 95 172 98 172 54 173 59 173 97 173 96 174 100 174 98 174 100 175 96 175 97 175 97 176 101 176 100 176 101 177 97 177 59 177 98 178 102 178 99 178 102 179 98 179 100 179 103 180 99 180 102 180 59 181 67 181 101 181 100 182 104 182 102 182 104 183 100 183 101 183 101 184 105 184 104 184 105 185 101 185 67 185 106 186 107 186 103 186 102 187 106 187 103 187 106 188 102 188 104 188 67 189 72 189 105 189 108 190 107 190 106 190 104 191 109 191 106 191 109 192 104 192 105 192 110 193 109 193 105 193 110 194 105 194 72 194 106 195 109 195 108 195 72 196 76 196 110 196 111 197 108 197 109 197 113 198 114 198 112 198 115 199 113 199 112 199 86 200 85 200 116 200 118 201 114 201 113 201 119 202 113 202 115 202 113 203 119 203 118 203 115 204 120 204 119 204 120 205 115 205 117 205 121 206 116 206 85 206 116 207 121 207 117 207 117 208 122 208 120 208 122 209 117 209 121 209 123 210 119 210 120 210 119 211 123 211 118 211 120 212 124 212 123 212 124 213 120 213 122 213 121 214 125 214 122 214 125 215 121 215 85 215 122 216 126 216 124 216 126 217 122 217 125 217 85 218 87 218 125 218 127 219 118 219 123 219 128 220 123 220 124 220 123 221 128 221 127 221 124 222 129 222 128 222 129 223 124 223 126 223 130 224 125 224 87 224 125 225 130 225 126 225 131 226 126 226 130 226 126 227 131 227 129 227 87 228 91 228 130 228 128 229 132 229 127 229 132 230 128 230 129 230 133 231 129 231 131 231 129 232 133 232 132 232 130 233 134 233 131 233 134 234 130 234 91 234 135 235 131 235 134 235 131 236 135 236 133 236 136 237 127 237 132 237 137 238 132 238 133 238 132 239 137 239 136 239 133 240 138 240 137 240 138 241 133 241 135 241 134 242 139 242 135 242 139 243 134 243 91 243 140 244 135 244 139 244 135 245 140 245 138 245 91 246 95 246 139 246 137 247 141 247 136 247 141 248 137 248 138 248 142 249 136 249 141 249 138 250 143 250 141 250 143 251 138 251 140 251 144 252 139 252 95 252 139 253 144 253 140 253 145 254 140 254 144 254 140 255 145 255 143 255 95 256 99 256 144 256 146 257 141 257 143 257 141 258 146 258 142 258 143 259 147 259 146 259 147 260 143 260 145 260 144 261 148 261 145 261 148 262 144 262 99 262 149 263 145 263 148 263 145 264 149 264 147 264 150 265 142 265 146 265 146 266 151 266 150 266 151 267 146 267 147 267 147 268 152 268 151 268 152 269 147 269 149 269 148 270 153 270 149 270 148 271 99 271 103 271 153 272 148 272 103 272 154 273 149 273 153 273 149 274 154 274 152 274 155 275 151 275 152 275 155 276 156 276 150 276 151 277 155 277 150 277 152 278 157 278 155 278 157 279 152 279 154 279 153 280 103 280 107 280 158 281 153 281 107 281 153 282 158 282 154 282 154 283 159 283 157 283 159 284 154 284 158 284 160 285 156 285 155 285 155 286 161 286 160 286 161 287 155 287 157 287 157 288 162 288 161 288 162 289 157 289 159 289 158 290 163 290 159 290 158 291 107 291 108 291 163 292 158 292 108 292 164 293 159 293 163 293 159 294 164 294 162 294 161 295 162 295 165 295 165 296 166 296 160 296 161 297 165 297 160 297 167 298 162 298 164 298 167 299 165 299 162 299 108 300 111 300 163 300 168 301 163 301 111 301 163 302 168 302 164 302 164 303 169 303 167 303 164 304 168 304 169 304 170 305 167 305 169 305 171 306 462 306 172 306 463 307 462 307 171 307 173 308 171 308 172 308 114 309 173 309 172 309 173 310 114 310 118 310 118 311 127 311 173 311 174 312 171 312 173 312 171 313 174 313 463 313 175 314 463 314 174 314 173 315 176 315 174 315 176 316 173 316 127 316 127 317 136 317 176 317 177 318 174 318 176 318 174 319 177 319 175 319 178 320 175 320 177 320 176 321 179 321 177 321 179 322 176 322 136 322 136 323 142 323 179 323 180 324 177 324 179 324 177 325 180 325 178 325 181 326 178 326 180 326 179 327 182 327 180 327 182 328 179 328 142 328 142 329 150 329 182 329 180 330 183 330 181 330 183 331 180 331 182 331 184 332 181 332 183 332 182 333 185 333 183 333 182 334 150 334 156 334 185 335 182 335 156 335 156 336 160 336 185 336 183 337 186 337 184 337 186 338 183 338 185 338 187 339 185 339 160 339 187 340 186 340 185 340 160 341 166 341 187 341 454 342 172 342 462 342 190 343 114 343 172 343 190 344 172 344 454 344 191 345 112 345 114 345 191 346 114 346 190 346 112 347 192 347 86 347 192 348 112 348 191 348 86 349 193 349 82 349 193 350 86 350 192 350 454 351 450 351 190 351 194 352 190 352 450 352 190 353 194 353 191 353 191 354 195 354 192 354 195 355 191 355 194 355 196 356 192 356 195 356 192 357 196 357 193 357 193 358 197 358 82 358 197 359 193 359 196 359 450 360 446 360 194 360 198 361 194 361 446 361 194 362 198 362 195 362 199 363 195 363 198 363 195 364 199 364 196 364 200 365 196 365 199 365 196 366 200 366 197 366 201 367 197 367 200 367 197 368 201 368 82 368 446 369 442 369 198 369 202 370 198 370 442 370 198 371 202 371 199 371 203 372 199 372 202 372 199 373 203 373 200 373 200 374 204 374 201 374 204 375 200 375 203 375 201 376 205 376 82 376 205 377 201 377 204 377 442 378 438 378 202 378 206 379 202 379 438 379 202 380 206 380 203 380 207 381 203 381 206 381 203 382 207 382 204 382 208 383 204 383 207 383 204 384 208 384 205 384 209 385 205 385 208 385 205 386 209 386 82 386 438 387 434 387 206 387 210 388 206 388 434 388 206 389 210 389 207 389 207 390 211 390 208 390 211 391 207 391 210 391 212 392 208 392 211 392 208 393 212 393 209 393 209 394 213 394 82 394 213 395 209 395 212 395 434 396 430 396 210 396 214 397 210 397 430 397 210 398 214 398 211 398 211 399 215 399 212 399 215 400 211 400 214 400 216 401 212 401 215 401 212 402 216 402 213 402 217 403 213 403 216 403 213 404 217 404 82 404 430 405 426 405 214 405 214 406 218 406 215 406 218 407 214 407 426 407 215 408 219 408 216 408 219 409 215 409 218 409 220 410 216 410 219 410 216 411 220 411 217 411 221 412 217 412 220 412 217 413 221 413 82 413 426 414 632 414 218 414 632 415 0 415 218 415 219 416 5 416 220 416 221 417 25 417 29 417 82 418 221 418 29 418 25 419 220 419 5 419 220 420 25 420 221 420 222 421 223 421 224 421 225 422 222 422 224 422 422 423 224 423 223 423 226 424 224 424 422 424 422 425 419 425 226 425 227 426 226 426 419 426 419 427 418 427 227 427 228 428 227 428 418 428 418 429 417 429 228 429 229 430 228 430 417 430 417 431 416 431 229 431 230 432 229 432 416 432 416 433 415 433 230 433 231 434 230 434 415 434 415 435 414 435 231 435 232 436 231 436 414 436 414 437 413 437 232 437 233 438 232 438 413 438 413 439 412 439 233 439 234 440 233 440 412 440 412 441 411 441 234 441 235 442 234 442 411 442 411 443 410 443 235 443 236 444 235 444 410 444 410 445 409 445 236 445 237 446 236 446 409 446 409 447 408 447 237 447 238 448 237 448 408 448 408 449 407 449 238 449 239 450 238 450 407 450 407 451 406 451 239 451 240 452 239 452 406 452 406 453 405 453 240 453 240 454 405 454 188 454 240 455 188 455 241 455 240 456 241 456 189 456 240 457 189 457 80 457 242 458 240 458 80 458 244 459 225 459 224 459 245 460 244 460 224 460 247 461 246 461 245 461 224 462 226 462 245 462 245 463 226 463 227 463 248 464 245 464 227 464 248 465 249 465 247 465 245 466 248 466 247 466 250 467 249 467 248 467 227 468 228 468 248 468 251 469 252 469 250 469 248 470 251 470 250 470 251 471 248 471 228 471 228 472 229 472 251 472 253 473 252 473 251 473 251 474 229 474 230 474 254 475 251 475 230 475 251 476 254 476 253 476 255 477 253 477 254 477 230 478 231 478 254 478 254 479 231 479 232 479 256 480 254 480 232 480 256 481 257 481 255 481 254 482 256 482 255 482 232 483 233 483 256 483 258 484 257 484 256 484 256 485 233 485 234 485 259 486 256 486 234 486 259 487 260 487 258 487 256 488 259 488 258 488 234 489 235 489 259 489 261 490 260 490 259 490 259 491 235 491 236 491 262 492 259 492 236 492 259 493 262 493 261 493 263 494 261 494 262 494 236 495 237 495 262 495 264 496 265 496 263 496 262 497 264 497 263 497 264 498 262 498 237 498 237 499 238 499 264 499 266 500 265 500 264 500 267 501 268 501 266 501 264 502 267 502 266 502 264 503 238 503 239 503 267 504 264 504 239 504 239 505 240 505 267 505 269 506 268 506 267 506 267 507 242 507 269 507 267 508 240 508 242 508 270 509 269 509 242 509 79 510 243 510 271 510 246 511 271 511 243 511 272 512 271 512 246 512 246 513 247 513 272 513 273 514 272 514 247 514 247 515 249 515 273 515 274 516 273 516 249 516 249 517 250 517 274 517 274 518 250 518 252 518 275 519 274 519 252 519 252 520 253 520 275 520 276 521 275 521 253 521 253 522 255 522 276 522 277 523 276 523 255 523 255 524 257 524 277 524 278 525 277 525 257 525 257 526 258 526 278 526 279 527 278 527 258 527 258 528 260 528 279 528 280 529 279 529 260 529 260 530 261 530 280 530 281 531 280 531 261 531 261 532 263 532 281 532 281 533 263 533 265 533 282 534 281 534 265 534 265 535 266 535 282 535 283 536 282 536 266 536 266 537 268 537 283 537 284 538 283 538 268 538 268 539 269 539 284 539 285 540 284 540 269 540 269 541 270 541 285 541 285 542 270 542 286 542 284 543 285 543 287 543 288 544 289 544 290 544 288 545 290 545 287 545 288 546 287 546 285 546 285 547 286 547 288 547 291 548 289 548 288 548 288 549 292 549 291 549 288 550 286 550 292 550 293 551 291 551 292 551 294 552 293 552 292 552 292 553 168 553 294 553 294 554 168 554 295 554 297 555 295 555 296 555 300 556 299 556 298 556 298 557 301 557 300 557 302 558 300 558 301 558 301 559 303 559 302 559 304 560 302 560 303 560 79 561 271 561 303 561 303 562 271 562 272 562 303 563 272 563 305 563 303 564 305 564 304 564 306 565 304 565 305 565 297 566 299 566 295 566 294 567 295 567 299 567 299 568 300 568 294 568 293 569 294 569 300 569 300 570 302 570 293 570 291 571 293 571 302 571 302 572 304 572 291 572 289 573 291 573 304 573 304 574 306 574 289 574 290 575 289 575 306 575 306 576 307 576 290 576 308 577 290 577 307 577 307 578 309 578 308 578 310 579 308 579 309 579 309 580 311 580 310 580 312 581 310 581 311 581 311 582 313 582 312 582 314 583 312 583 313 583 313 584 315 584 314 584 316 585 314 585 315 585 272 586 273 586 305 586 317 587 305 587 273 587 317 588 307 588 306 588 317 589 306 589 305 589 273 590 274 590 317 590 309 591 307 591 317 591 318 592 311 592 309 592 317 593 318 593 309 593 317 594 274 594 275 594 318 595 317 595 275 595 275 596 276 596 318 596 313 597 311 597 318 597 318 598 276 598 277 598 319 599 318 599 277 599 318 600 319 600 313 600 315 601 313 601 319 601 277 602 278 602 319 602 320 603 319 603 278 603 320 604 316 604 315 604 319 605 320 605 315 605 278 606 279 606 320 606 314 607 316 607 320 607 320 608 279 608 280 608 321 609 320 609 280 609 320 610 321 610 314 610 312 611 314 611 321 611 280 612 281 612 321 612 322 613 310 613 312 613 321 614 322 614 312 614 321 615 281 615 282 615 322 616 321 616 282 616 308 617 310 617 322 617 282 618 283 618 322 618 322 619 283 619 284 619 322 620 284 620 287 620 322 621 287 621 308 621 290 622 308 622 287 622 167 623 270 623 242 623 242 624 165 624 167 624 170 625 286 625 270 625 170 626 270 626 167 626 292 627 286 627 170 627 168 628 292 628 170 628 168 629 111 629 295 629 170 630 169 630 168 630 301 631 298 631 303 631 78 632 303 632 298 632 303 633 78 633 79 633 297 634 76 634 298 634 298 635 77 635 78 635 298 636 76 636 77 636 75 637 243 637 79 637 24 638 225 638 244 638 244 639 74 639 24 639 74 640 244 640 243 640 243 641 75 641 74 641 225 642 24 642 222 642 186 643 241 643 188 643 186 644 187 644 241 644 187 645 189 645 241 645 166 646 189 646 187 646 80 647 189 647 166 647 80 648 166 648 165 648 80 649 165 649 242 649 109 650 295 650 111 650 109 651 296 651 295 651 109 652 110 652 296 652 76 653 296 653 110 653 76 654 297 654 296 654 297 655 298 655 299 655 244 656 245 656 246 656 243 657 244 657 246 657 5 658 219 658 218 658 2 659 5 659 218 659 0 660 2 660 218 660 86 661 117 661 112 661 112 662 117 662 115 662 86 663 116 663 117 663 548 664 517 664 518 664 522 665 519 665 517 665 548 666 522 666 517 666 632 667 426 667 630 667 630 668 426 668 627 668 627 669 426 669 425 669 402 670 399 670 401 670 401 671 399 671 400 671 348 672 346 672 347 672 558 673 349 673 348 673 558 674 524 674 349 674 525 675 349 675 524 675 525 676 350 676 349 676 525 677 523 677 350 677 554 678 403 678 469 678 554 679 469 679 468 679 554 680 468 680 455 680 468 681 456 681 455 681 456 682 404 682 455 682 186 683 404 683 456 683 186 684 188 684 404 684 420 685 421 685 610 685 402 686 560 686 559 686 560 687 402 687 401 687 401 688 610 688 560 688 610 689 401 689 420 689 559 690 555 690 402 690 347 691 557 691 558 691 347 692 556 692 557 692 348 693 347 693 558 693 342 694 555 694 556 694 556 695 347 695 342 695 344 696 342 696 347 696 464 697 466 697 465 697 466 698 350 698 523 698 466 699 464 699 353 699 353 700 464 700 359 700 464 701 467 701 375 701 464 702 375 702 359 702 403 703 467 703 469 703 467 704 403 704 375 704 355 705 358 705 337 705 323 706 337 706 358 706 323 707 358 707 361 707 323 708 361 708 362 708 363 709 323 709 362 709 337 710 323 710 335 710 323 711 363 711 324 711 324 712 363 712 364 712 324 713 333 713 323 713 323 714 333 714 335 714 365 715 324 715 364 715 333 716 324 716 331 716 325 717 331 717 324 717 324 718 365 718 325 718 325 719 365 719 366 719 331 720 325 720 329 720 367 721 325 721 366 721 326 722 330 722 325 722 325 723 330 723 329 723 325 724 367 724 326 724 368 725 326 725 367 725 330 726 326 726 332 726 327 727 332 727 326 727 326 728 368 728 327 728 327 729 368 729 369 729 332 730 327 730 334 730 370 731 327 731 369 731 327 732 370 732 328 732 328 733 370 733 371 733 328 734 336 734 327 734 327 735 336 735 334 735 336 736 328 736 338 736 372 737 328 737 371 737 328 738 340 738 339 738 328 739 339 739 338 739 328 740 372 740 340 740 373 741 340 741 372 741 329 742 330 742 331 742 332 743 331 743 330 743 331 744 332 744 333 744 334 745 333 745 332 745 333 746 334 746 335 746 336 747 335 747 334 747 335 748 336 748 337 748 338 749 337 749 336 749 337 750 338 750 355 750 339 751 355 751 338 751 355 752 339 752 356 752 341 753 356 753 339 753 356 754 341 754 354 754 343 755 354 755 341 755 354 756 343 756 352 756 345 757 352 757 343 757 352 758 345 758 351 758 346 759 351 759 345 759 351 760 346 760 350 760 348 761 350 761 346 761 339 762 340 762 341 762 342 763 341 763 340 763 342 764 340 764 373 764 342 765 373 765 374 765 555 766 342 766 374 766 341 767 342 767 343 767 344 768 343 768 342 768 343 769 344 769 345 769 347 770 345 770 344 770 345 771 347 771 346 771 348 772 349 772 350 772 351 773 350 773 466 773 353 774 351 774 466 774 351 775 353 775 352 775 352 776 353 776 354 776 357 777 353 777 359 777 357 778 354 778 353 778 354 779 357 779 356 779 360 780 357 780 359 780 357 781 360 781 358 781 357 782 358 782 355 782 357 783 355 783 356 783 361 784 358 784 360 784 360 785 359 785 375 785 376 786 360 786 375 786 360 787 376 787 361 787 377 788 361 788 376 788 361 789 377 789 362 789 379 790 362 790 377 790 362 791 379 791 363 791 380 792 363 792 379 792 363 793 380 793 364 793 364 794 380 794 382 794 384 795 364 795 382 795 364 796 384 796 365 796 385 797 365 797 384 797 365 798 385 798 366 798 387 799 366 799 385 799 366 800 387 800 367 800 388 801 367 801 387 801 367 802 388 802 368 802 390 803 368 803 388 803 368 804 390 804 369 804 392 805 369 805 390 805 369 806 392 806 370 806 393 807 370 807 392 807 370 808 393 808 371 808 371 809 393 809 395 809 396 810 371 810 395 810 371 811 396 811 372 811 398 812 372 812 396 812 372 813 398 813 373 813 399 814 373 814 398 814 373 815 399 815 374 815 399 816 402 816 374 816 555 817 374 817 402 817 375 818 403 818 376 818 378 819 403 819 405 819 378 820 376 820 403 820 376 821 378 821 377 821 406 822 378 822 405 822 378 823 406 823 381 823 381 824 406 824 407 824 381 825 379 825 378 825 378 826 379 826 377 826 379 827 381 827 380 827 408 828 381 828 407 828 381 829 408 829 383 829 383 830 382 830 381 830 381 831 382 831 380 831 409 832 383 832 408 832 382 833 383 833 384 833 386 834 384 834 383 834 383 835 409 835 386 835 386 836 409 836 410 836 384 837 386 837 385 837 411 838 386 838 410 838 389 839 387 839 386 839 386 840 387 840 385 840 386 841 411 841 389 841 389 842 411 842 412 842 387 843 389 843 388 843 413 844 389 844 412 844 391 845 390 845 389 845 389 846 390 846 388 846 389 847 413 847 391 847 391 848 413 848 414 848 415 849 391 849 414 849 390 850 391 850 392 850 394 851 392 851 391 851 391 852 415 852 394 852 394 853 415 853 416 853 392 854 394 854 393 854 417 855 394 855 416 855 394 856 417 856 397 856 397 857 395 857 394 857 394 858 395 858 393 858 418 859 397 859 417 859 395 860 397 860 396 860 400 861 398 861 397 861 397 862 398 862 396 862 397 863 418 863 400 863 400 864 418 864 419 864 422 865 400 865 419 865 398 866 400 866 399 866 400 867 422 867 401 867 401 868 422 868 420 868 403 869 554 869 405 869 405 870 554 870 455 870 405 871 455 871 404 871 405 872 404 872 188 872 424 873 423 873 609 873 609 874 627 874 424 874 552 875 605 875 423 875 423 876 605 876 609 876 425 877 424 877 627 877 427 878 552 878 423 878 423 879 424 879 427 879 428 880 427 880 424 880 424 881 425 881 428 881 425 882 426 882 429 882 429 883 428 883 425 883 430 884 429 884 426 884 431 885 552 885 427 885 427 886 428 886 431 886 432 887 431 887 428 887 428 888 429 888 432 888 429 889 430 889 433 889 433 890 432 890 429 890 434 891 433 891 430 891 431 892 432 892 435 892 435 893 552 893 431 893 436 894 435 894 432 894 432 895 433 895 436 895 433 896 434 896 437 896 437 897 436 897 433 897 438 898 437 898 434 898 439 899 552 899 435 899 435 900 436 900 439 900 440 901 439 901 436 901 436 902 437 902 440 902 441 903 440 903 437 903 437 904 438 904 441 904 442 905 441 905 438 905 439 906 440 906 443 906 443 907 552 907 439 907 440 908 441 908 444 908 444 909 443 909 440 909 445 910 444 910 441 910 441 911 442 911 445 911 446 912 445 912 442 912 447 913 552 913 443 913 443 914 444 914 447 914 448 915 447 915 444 915 444 916 445 916 448 916 449 917 448 917 445 917 445 918 446 918 449 918 450 919 449 919 446 919 447 920 448 920 451 920 451 921 552 921 447 921 452 922 451 922 448 922 448 923 449 923 452 923 449 924 450 924 453 924 453 925 452 925 449 925 454 926 453 926 450 926 451 927 452 927 548 927 548 928 552 928 451 928 452 929 453 929 522 929 522 930 548 930 452 930 453 931 454 931 520 931 453 932 520 932 522 932 454 933 462 933 520 933 474 934 456 934 468 934 456 935 457 935 186 935 456 936 474 936 457 936 186 937 457 937 184 937 478 938 457 938 474 938 457 939 478 939 458 939 458 940 478 940 484 940 458 941 184 941 457 941 184 942 458 942 181 942 492 943 458 943 484 943 458 944 492 944 459 944 459 945 181 945 458 945 181 946 459 946 178 946 498 947 459 947 492 947 459 948 498 948 460 948 460 949 178 949 459 949 178 950 460 950 175 950 507 951 460 951 498 951 460 952 507 952 461 952 461 953 175 953 460 953 175 954 461 954 463 954 516 955 461 955 507 955 461 956 516 956 520 956 520 957 462 957 461 957 461 958 462 958 463 958 464 959 465 959 467 959 470 960 465 960 466 960 470 961 467 961 465 961 471 962 470 962 466 962 466 963 523 963 471 963 526 964 471 964 523 964 467 965 472 965 469 965 467 966 470 966 472 966 473 967 474 967 469 967 469 968 474 968 468 968 473 969 469 969 472 969 475 970 472 970 470 970 470 971 471 971 475 971 471 972 526 972 476 972 476 973 526 973 527 973 476 974 475 974 471 974 472 975 475 975 477 975 477 976 473 976 472 976 473 977 477 977 479 977 479 978 474 978 473 978 474 979 479 979 478 979 475 980 476 980 480 980 480 981 477 981 475 981 481 982 480 982 476 982 476 983 527 983 481 983 481 984 527 984 531 984 477 985 480 985 482 985 482 986 479 986 477 986 483 987 484 987 479 987 479 988 484 988 478 988 479 989 482 989 483 989 485 990 482 990 480 990 480 991 481 991 485 991 481 992 531 992 486 992 486 993 531 993 535 993 486 994 485 994 481 994 482 995 485 995 487 995 487 996 483 996 482 996 483 997 487 997 488 997 488 998 484 998 483 998 484 999 488 999 492 999 489 1000 487 1000 485 1000 485 1001 486 1001 489 1001 486 1002 535 1002 490 1002 490 1003 489 1003 486 1003 487 1004 489 1004 491 1004 491 1005 488 1005 487 1005 493 1006 492 1006 488 1006 488 1007 491 1007 493 1007 539 1008 490 1008 535 1008 494 1009 491 1009 489 1009 489 1010 490 1010 494 1010 495 1011 494 1011 490 1011 490 1012 539 1012 495 1012 491 1013 494 1013 496 1013 496 1014 493 1014 491 1014 492 1015 493 1015 498 1015 493 1016 496 1016 497 1016 497 1017 498 1017 493 1017 543 1018 495 1018 539 1018 499 1019 496 1019 494 1019 494 1020 495 1020 499 1020 495 1021 543 1021 500 1021 500 1022 499 1022 495 1022 496 1023 499 1023 501 1023 501 1024 497 1024 496 1024 502 1025 498 1025 497 1025 497 1026 501 1026 502 1026 498 1027 502 1027 507 1027 503 1028 501 1028 499 1028 499 1029 500 1029 503 1029 500 1030 543 1030 504 1030 504 1031 503 1031 500 1031 505 1032 502 1032 501 1032 501 1033 503 1033 505 1033 502 1034 505 1034 506 1034 506 1035 507 1035 502 1035 547 1036 504 1036 543 1036 508 1037 505 1037 503 1037 503 1038 504 1038 508 1038 509 1039 508 1039 504 1039 504 1040 547 1040 509 1040 505 1041 508 1041 510 1041 510 1042 506 1042 505 1042 511 1043 507 1043 506 1043 506 1044 510 1044 511 1044 507 1045 511 1045 516 1045 549 1046 509 1046 547 1046 508 1047 509 1047 512 1047 512 1048 510 1048 508 1048 509 1049 549 1049 513 1049 513 1050 512 1050 509 1050 510 1051 512 1051 514 1051 514 1052 511 1052 510 1052 515 1053 516 1053 511 1053 511 1054 514 1054 515 1054 512 1055 513 1055 517 1055 517 1056 514 1056 512 1056 518 1057 517 1057 513 1057 513 1058 549 1058 518 1058 514 1059 517 1059 519 1059 519 1060 515 1060 514 1060 521 1061 516 1061 515 1061 515 1062 519 1062 521 1062 516 1063 521 1063 520 1063 548 1064 518 1064 549 1064 519 1065 522 1065 521 1065 521 1066 522 1066 520 1066 523 1067 525 1067 526 1067 562 1068 524 1068 558 1068 528 1069 526 1069 525 1069 524 1070 562 1070 529 1070 524 1071 529 1071 525 1071 525 1072 529 1072 530 1072 530 1073 528 1073 525 1073 526 1074 528 1074 527 1074 567 1075 529 1075 562 1075 528 1076 530 1076 532 1076 532 1077 531 1077 528 1077 528 1078 531 1078 527 1078 529 1079 567 1079 533 1079 533 1080 530 1080 529 1080 530 1081 533 1081 534 1081 534 1082 532 1082 530 1082 575 1083 533 1083 567 1083 531 1084 532 1084 535 1084 532 1085 534 1085 536 1085 536 1086 535 1086 532 1086 533 1087 575 1087 537 1087 537 1088 534 1088 533 1088 534 1089 537 1089 538 1089 538 1090 536 1090 534 1090 580 1091 537 1091 575 1091 535 1092 536 1092 539 1092 540 1093 539 1093 536 1093 536 1094 538 1094 540 1094 537 1095 580 1095 541 1095 541 1096 538 1096 537 1096 538 1097 541 1097 542 1097 542 1098 540 1098 538 1098 589 1099 541 1099 580 1099 539 1100 540 1100 543 1100 540 1101 542 1101 544 1101 544 1102 543 1102 540 1102 545 1103 542 1103 541 1103 541 1104 589 1104 545 1104 545 1105 589 1105 595 1105 542 1106 545 1106 546 1106 546 1107 544 1107 542 1107 543 1108 544 1108 547 1108 544 1109 546 1109 550 1109 550 1110 547 1110 544 1110 551 1111 546 1111 545 1111 545 1112 595 1112 551 1112 546 1113 551 1113 553 1113 553 1114 550 1114 546 1114 603 1115 551 1115 595 1115 547 1116 550 1116 549 1116 550 1117 552 1117 548 1117 550 1118 548 1118 549 1118 550 1119 553 1119 552 1119 605 1120 552 1120 551 1120 551 1121 552 1121 553 1121 551 1122 603 1122 605 1122 555 1123 559 1123 556 1123 556 1124 559 1124 561 1124 556 1125 561 1125 557 1125 563 1126 558 1126 557 1126 563 1127 557 1127 561 1127 611 1128 560 1128 610 1128 564 1129 561 1129 559 1129 558 1130 563 1130 562 1130 565 1131 564 1131 560 1131 560 1132 564 1132 559 1132 560 1133 611 1133 565 1133 613 1134 565 1134 611 1134 566 1135 563 1135 561 1135 561 1136 564 1136 566 1136 563 1137 566 1137 568 1137 568 1138 567 1138 563 1138 563 1139 567 1139 562 1139 564 1140 565 1140 569 1140 569 1141 566 1141 564 1141 565 1142 613 1142 570 1142 570 1143 569 1143 565 1143 614 1144 570 1144 613 1144 571 1145 568 1145 566 1145 566 1146 569 1146 571 1146 572 1147 575 1147 568 1147 568 1148 575 1148 567 1148 568 1149 571 1149 572 1149 569 1150 570 1150 573 1150 573 1151 571 1151 569 1151 574 1152 573 1152 570 1152 570 1153 614 1153 574 1153 617 1154 574 1154 614 1154 571 1155 573 1155 576 1155 576 1156 572 1156 571 1156 577 1157 575 1157 572 1157 572 1158 576 1158 577 1158 573 1159 574 1159 578 1159 578 1160 576 1160 573 1160 579 1161 578 1161 574 1161 574 1162 617 1162 579 1162 579 1163 617 1163 620 1163 575 1164 577 1164 580 1164 581 1165 577 1165 576 1165 576 1166 578 1166 581 1166 577 1167 581 1167 582 1167 582 1168 580 1168 577 1168 578 1169 579 1169 583 1169 583 1170 581 1170 578 1170 579 1171 620 1171 584 1171 584 1172 583 1172 579 1172 580 1173 582 1173 589 1173 585 1174 582 1174 581 1174 581 1175 583 1175 585 1175 586 1176 589 1176 582 1176 582 1177 585 1177 586 1177 583 1178 584 1178 587 1178 587 1179 585 1179 583 1179 588 1180 587 1180 584 1180 584 1181 620 1181 588 1181 588 1182 620 1182 623 1182 585 1183 587 1183 590 1183 590 1184 586 1184 585 1184 586 1185 590 1185 591 1185 591 1186 589 1186 586 1186 592 1187 590 1187 587 1187 587 1188 588 1188 592 1188 588 1189 623 1189 593 1189 593 1190 592 1190 588 1190 589 1191 591 1191 595 1191 594 1192 591 1192 590 1192 590 1193 592 1193 594 1193 591 1194 594 1194 596 1194 596 1195 595 1195 591 1195 597 1196 594 1196 592 1196 592 1197 593 1197 597 1197 626 1198 593 1198 623 1198 593 1199 626 1199 598 1199 598 1200 597 1200 593 1200 594 1201 597 1201 599 1201 599 1202 596 1202 594 1202 595 1203 596 1203 603 1203 596 1204 599 1204 600 1204 600 1205 603 1205 596 1205 601 1206 599 1206 597 1206 597 1207 598 1207 601 1207 602 1208 601 1208 598 1208 598 1209 626 1209 602 1209 599 1210 601 1210 604 1210 604 1211 600 1211 599 1211 606 1212 603 1212 600 1212 600 1213 604 1213 606 1213 628 1214 602 1214 626 1214 607 1215 604 1215 601 1215 601 1216 602 1216 607 1216 608 1217 607 1217 602 1217 602 1218 628 1218 608 1218 603 1219 606 1219 605 1219 627 1220 608 1220 628 1220 604 1221 607 1221 609 1221 609 1222 605 1222 604 1222 604 1223 605 1223 606 1223 607 1224 608 1224 609 1224 609 1225 608 1225 627 1225 610 1226 612 1226 611 1226 615 1227 612 1227 20 1227 615 1228 613 1228 612 1228 612 1229 613 1229 611 1229 616 1230 615 1230 20 1230 613 1231 615 1231 614 1231 618 1232 617 1232 615 1232 615 1233 617 1233 614 1233 615 1234 616 1234 618 1234 619 1235 618 1235 616 1235 617 1236 618 1236 620 1236 618 1237 619 1237 621 1237 621 1238 620 1238 618 1238 622 1239 621 1239 619 1239 620 1240 621 1240 623 1240 624 1241 623 1241 621 1241 621 1242 622 1242 624 1242 625 1243 624 1243 622 1243 623 1244 624 1244 626 1244 629 1245 626 1245 624 1245 624 1246 625 1246 629 1246 631 1247 629 1247 625 1247 626 1248 629 1248 628 1248 630 1249 627 1249 629 1249 629 1250 627 1250 628 1250 629 1251 631 1251 630 1251 631 1252 632 1252 630 1252 420 1253 422 1253 421 1253 223 1254 421 1254 422 1254 421 1255 612 1255 610 1255 223 1256 612 1256 421 1256 223 1257 20 1257 612 1257 20 1258 223 1258 21 1258 21 1259 223 1259 23 1259 23 1260 223 1260 222 1260 23 1261 222 1261 24 1261

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_middle/th_middle_E3M5.dae b/URDFs/sr_description/meshes/components/th_middle/th_middle_E3M5.dae new file mode 100644 index 0000000..df463ac --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_middle/th_middle_E3M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:04.601049 + 2012-07-23T02:14:04.601062 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -10.82211 1.89451 0.02984 -10.52279 1.19648 4.40604 -10.43772 3.42460 0.02983 -10.01191 3.48500 4.44190 -9.24738 5.48540 3.30954 -9.53206 5.50770 0.02984 -8.76916 5.54120 6.52921 -9.89934 1.32759 8.78240 -9.34524 3.61260 8.85396 -8.04629 5.52890 11.15913 -9.26471 1.36724 13.15861 -8.71246 3.57270 13.26610 -7.62288 5.23110 15.49638 -8.79618 1.20098 17.53489 -8.36209 3.12530 17.67809 -7.64989 4.79500 18.13671 -8.53313 0.87560 21.91118 -8.31577 2.41180 22.09022 -7.82107 4.31860 20.58139 -8.02359 3.94460 22.84329 -8.30538 -0.79062 26.28739 -8.30538 0.70052 26.28740 -8.18404 3.75820 24.93399 -8.28854 1.69868 26.40406 -8.25863 3.80240 26.86291 -7.06228 8.40020 0.02984 -8.38620 6.91280 2.41682 -7.24683 8.13770 2.46228 -4.47194 9.96990 2.48145 -3.75606 10.29400 0.02976 -5.94010 9.15660 2.50980 -2.75840 10.49580 3.62321 -8.07380 6.89460 4.80358 -6.95048 8.05290 4.89452 -4.28569 9.79750 4.93299 -5.69028 9.01010 4.98983 -7.68404 6.86400 7.19021 -6.59311 7.90890 7.32682 -4.12086 9.51920 7.38459 -2.57576 10.09530 7.41507 -5.41925 8.76810 7.46987 -7.28799 6.80580 9.57691 -6.23702 7.73940 9.75913 -3.95787 9.22070 9.83620 -5.15147 8.50730 9.94991 -2.40556 9.64210 11.24200 -6.95685 6.70500 11.96360 -5.94428 7.57760 12.19143 -3.77749 8.98770 12.28781 -4.91141 8.30410 12.42994 -6.76190 6.54660 14.35030 -5.77712 7.45700 14.62374 -3.56027 8.90580 14.73935 -4.72338 8.23520 14.90998 -2.13855 9.43290 14.94243 -6.77357 6.31590 16.73700 -5.79564 7.41050 17.05605 -3.28867 9.05710 17.19096 -4.61110 8.37220 17.38994 -1.72766 9.64300 18.33506 -7.00006 6.03250 19.12369 -5.99731 7.44970 19.48835 -2.99557 9.42630 19.64257 -4.58613 8.69440 19.86998 -7.34378 5.77480 21.51040 -6.30172 7.56070 21.92059 -2.76823 9.89430 22.09418 -1.33429 10.08770 21.40864 -4.64892 9.10020 22.35008 -7.69641 5.62700 23.89709 -6.62395 7.72770 24.35296 -2.69618 10.33660 24.54579 -1.13835 10.51830 24.18891 -4.79982 9.48510 24.83005 -7.87334 5.89220 26.22347 -6.92828 7.84400 26.71059 -1.22462 10.79640 26.70466 -3.12402 10.54986 26.98725 -5.11937 9.69790 27.34445 -5.42738 9.83580 28.97489 8.61265 5.13360 29.45177 0.06932 10.86760 3.80621 -0.01024 11.00000 0.02977 -1.40119 10.75920 3.81399 1.54101 10.76320 3.81675 2.87009 10.51680 3.52160 3.74599 10.31910 0.02461 3.06080 10.10820 6.97886 0.26646 10.44410 7.58258 -1.22349 10.34610 7.59807 1.75633 10.31870 7.60365 3.19084 9.65190 10.35776 0.40632 9.98440 11.35896 -1.07563 9.89580 11.38229 1.88615 9.84550 11.39063 3.12557 9.35790 13.61293 0.44521 9.74450 15.13533 -0.89992 9.67180 15.16637 1.78511 9.61390 15.17754 2.77768 9.38120 16.66155 0.34961 9.93570 18.91171 -0.65823 9.88990 18.95053 1.34910 9.84460 18.96453 2.21227 9.70760 19.47371 0.17213 10.39810 22.68822 -0.46781 10.38080 22.73461 0.80393 10.35940 22.75151 1.66398 10.14140 22.07601 1.30046 10.53670 24.50004 0.63860 10.78850 26.55730 -0.26995 10.78750 26.46785 1.22529 10.79760 26.75026 7.06210 8.42260 0.02481 8.41345 7.01390 2.18807 9.50643 5.48610 0.02976 7.26406 8.22570 2.23212 4.46815 10.02870 2.27030 5.94975 9.22990 2.28890 9.32640 5.51470 3.95308 8.34041 6.89470 4.35005 7.22057 8.06730 4.43978 4.53342 9.83020 4.51699 5.95696 9.03570 4.55093 8.18244 6.77210 6.51210 7.10496 7.85940 6.64744 4.60456 9.53340 6.76375 5.92833 8.75480 6.81304 9.00644 5.38790 7.87618 7.97886 6.64160 8.67407 6.94847 7.63310 8.85509 4.64917 9.20840 9.01044 5.86525 8.45070 9.07521 7.76899 6.49850 10.83612 6.78223 7.41940 11.06275 4.63475 8.92510 11.25721 5.76895 8.18680 11.33725 8.61378 5.22010 11.68501 7.59222 6.33800 12.99817 6.63741 7.24920 13.27048 4.52889 8.75350 13.50389 5.64082 8.02660 13.59928 7.48771 6.15560 15.16022 8.32521 4.90480 15.26346 6.54521 7.15350 15.47806 4.29922 8.76350 15.75065 5.48222 8.03360 15.86139 7.49153 5.94840 17.32228 6.53255 7.15940 17.68572 3.92877 9.00560 17.99735 5.29914 8.25080 18.12349 8.23527 4.41720 18.53411 7.59137 5.74270 19.48432 6.58862 7.26040 19.89338 3.49200 9.41690 20.24404 5.12194 8.61970 20.38567 7.73767 5.58670 21.64630 8.25740 3.95780 21.48409 6.68360 7.43260 22.10104 3.09609 9.89340 22.49073 4.98816 9.05000 22.64771 8.28384 3.71300 24.13419 7.87952 5.52970 23.80835 6.78704 7.65190 24.30869 2.84803 10.33120 24.73749 4.93555 9.45130 24.90974 7.96324 5.62190 25.97040 8.25683 3.76260 26.51529 6.86779 7.89350 26.51643 2.85645 10.62480 26.98418 5.02005 9.72250 27.17793 5.01206 9.91015 28.28688 10.72605 1.18730 4.35415 10.80892 1.89560 0.02976 10.22011 3.47460 4.38505 10.33368 1.07588 8.67846 10.30603 -1.32513 8.68545 9.83651 3.37060 8.74033 9.82534 0.96963 13.00276 9.78150 -1.36852 13.01323 9.35575 3.19910 13.09561 9.29663 0.82529 17.32708 9.25393 -1.21342 17.34108 8.92802 2.79230 17.45089 8.80583 0.66934 21.65139 8.78052 -0.89296 21.66892 8.60947 2.24530 21.80618 8.35632 -0.05477 25.91333 8.32436 1.64096 26.06027 8.66363 -0.09010 29.62890 8.64029 3.91250 29.54616 10.17118 1.89878 -3.67597 8.94513 5.49330 -3.22971 6.63522 8.42400 -2.39370 3.52367 10.33660 -1.26092 8.28971 1.89878 -6.93474 7.29022 5.49331 -6.09604 5.40599 8.42400 -4.51997 2.86939 10.33660 -2.39137 5.40719 1.89878 -9.35354 4.75482 5.49330 -8.22358 3.52367 8.42400 -6.09781 1.86812 10.33660 -3.23000 1.87124 1.89878 -10.64048 1.64468 5.49331 -9.35552 1.21532 8.42400 -6.93679 0.64044 10.33660 -3.67576 -1.89170 1.89878 -10.64048 -1.66514 5.49330 -9.35552 -1.24074 8.42400 -6.93594 -0.66558 10.33660 -3.67491 -5.42766 1.89878 -9.35354 -4.77529 5.49330 -8.22358 -3.54853 8.42400 -6.09527 -1.89270 10.33660 -3.22759 -8.31018 1.89878 -6.93474 -7.31069 5.49330 -6.09605 -5.42971 8.42400 -4.51615 -2.89297 10.33660 -2.38769 -10.19165 1.89878 -3.67597 -8.96560 5.49330 -3.22971 -6.65746 8.42400 -2.38896 -3.54577 10.33660 -1.25646 -8.65377 3.85249 29.52191 -8.67159 0.00316 29.58427 -8.97734 5.75739 31.26040 -8.62534 5.13799 29.42574 -8.92799 5.75739 33.24101 -8.44687 5.75739 35.16321 -7.55740 5.75739 36.93373 -6.30115 5.75739 38.46575 -4.74085 5.75739 39.68664 -2.95096 5.75739 40.53609 -1.01801 5.75739 40.97280 0.96295 5.75739 40.97697 2.89704 5.75739 40.54733 4.69025 5.75739 39.70474 6.25565 5.75739 38.49036 7.51734 5.75740 36.96280 8.41431 5.75740 35.19623 8.90306 5.75740 33.27615 8.95977 5.75740 31.29569 8.65656 1.84708 29.60358 8.35498 6.41670 28.91394 -7.38982 7.94489 28.76241 -8.31528 6.49310 28.80709 -8.78182 6.90539 32.00492 -8.03264 7.87869 30.76628 -8.10922 7.87869 32.63197 -8.12485 6.90539 35.36077 -7.75793 7.87869 34.46621 -6.99652 7.87869 36.17090 -6.23433 6.90539 38.21012 -5.86572 7.87869 37.65667 -4.42626 7.87869 38.84582 -3.39862 6.90539 40.12094 -2.75254 7.87869 39.67384 -0.04722 6.90539 40.80133 -0.93471 7.87869 40.09867 0.93269 7.87869 40.09620 3.30949 6.90540 40.14902 2.75003 7.87869 39.66762 4.42149 7.87869 38.83535 6.16175 6.90540 38.26267 5.85861 7.87870 37.64331 8.07595 6.90540 35.42908 6.98559 7.87870 36.15457 7.74269 7.87870 34.44783 8.76128 6.90540 32.07895 8.09009 7.87870 32.61324 8.00927 7.87870 30.74782 7.13755 8.03140 28.36388 -5.75442 10.12129 30.77964 -5.88891 10.12129 32.02981 -5.68858 10.12129 33.55129 -5.10133 10.12129 34.96911 -4.16711 10.12129 36.18661 -2.94961 10.12129 37.12083 -1.53171 10.12129 37.70816 -0.01024 10.12129 37.90848 1.51124 10.12129 37.70816 2.92913 10.12129 37.12083 4.14663 10.12129 36.18661 5.08086 10.12129 34.96911 5.66811 10.12129 33.55129 5.86843 10.12130 32.02981 5.73083 10.12130 30.76508 5.32404 10.12150 29.55953 4.88535 10.74795 32.02972 4.52677 10.77160 30.16474 3.59488 11.00000 30.97120 3.74711 11.00000 32.02981 3.15067 11.00000 29.99836 3.48542 10.81730 28.47776 2.45035 11.00000 29.19014 1.55063 11.00000 28.61201 0.52448 11.00000 28.31064 -0.22463 10.94620 27.71228 -0.90310 10.94670 27.80258 -3.41361 10.67647 27.95695 -1.57110 11.00000 28.61201 -2.47082 11.00000 29.19014 -3.75642 10.71769 28.67628 -3.17115 10.99999 29.99836 -4.54689 10.77160 30.16368 -3.61535 10.99999 30.97120 -4.90581 10.74795 32.02974 -3.76759 10.99999 32.02981 -3.61542 10.99999 33.08834 3.59495 11.00000 33.08834 -3.17115 10.99999 34.06111 3.15059 11.00000 34.06118 -2.47075 10.99999 34.86940 2.45028 11.00000 34.86940 -1.57111 10.99999 35.44761 1.55063 10.99999 35.44761 -0.54502 10.99999 35.74890 0.52455 10.99999 35.74890 -4.42986 10.77159 34.15820 -3.06869 10.77160 35.86501 -1.10180 10.77160 36.81225 1.08132 10.77160 36.81225 3.04821 10.77160 35.86501 4.40939 10.77160 34.15820 4.40939 -10.86170 34.15819 3.04822 -10.86170 35.86501 1.08133 -10.86170 36.81224 -1.10180 -10.86170 36.81224 -3.06868 -10.86170 35.86501 -4.42986 -10.86170 34.15819 0.52455 -11.09011 35.74890 -0.54502 -11.09011 35.74890 1.55064 -11.09011 35.44760 -1.57110 -11.09011 35.44760 2.45028 -11.09010 34.86940 -2.47075 -11.09011 34.86940 3.15060 -11.09010 34.06118 -3.17114 -11.09011 34.06110 3.59495 -11.09010 33.08834 -3.61542 -11.09011 33.08834 -3.76759 -11.09011 32.02980 -4.90581 -10.83806 32.02974 -3.61535 -11.09011 30.97119 -4.54689 -10.86171 30.16368 -3.17114 -11.09011 29.99836 -3.75641 -10.80780 28.67628 -2.47082 -11.09010 29.19013 -1.57110 -11.09010 28.61200 -3.41360 -10.76658 27.95695 -0.90309 -11.03680 27.80258 -0.22463 -11.03630 27.71228 0.52448 -11.09010 28.31063 1.55063 -11.09010 28.61200 2.45035 -11.09010 29.19013 3.48542 -10.90741 28.47776 3.15067 -11.09010 29.99836 3.74712 -11.09010 32.02980 3.59488 -11.09010 30.97119 4.52677 -10.86170 30.16474 4.88535 -10.83805 32.02972 5.32404 -10.21160 29.55953 5.73084 -10.21140 30.76507 5.86844 -10.21140 32.02980 5.66811 -10.21140 33.55128 5.08086 -10.21140 34.96910 4.14663 -10.21140 36.18660 2.92914 -10.21141 37.12083 1.51124 -10.21141 37.70815 -0.01023 -10.21141 37.90848 -1.53171 -10.21141 37.70815 -2.94960 -10.21141 37.12083 -4.16710 -10.21141 36.18660 -5.10133 -10.21140 34.96910 -5.68858 -10.21140 33.55128 -5.88891 -10.21140 32.02980 -5.75441 -10.21140 30.77964 7.13755 -8.12150 28.36388 8.00927 -7.96880 30.74782 8.09009 -7.96880 32.61324 8.76128 -6.99550 32.07895 7.74269 -7.96880 34.44782 6.98560 -7.96880 36.15456 8.07595 -6.99550 35.42908 5.85861 -7.96880 37.64331 6.16175 -6.99550 38.26267 4.42149 -7.96880 38.83535 2.75003 -7.96880 39.66762 3.30949 -6.99550 40.14902 0.93269 -7.96880 40.09619 -0.93471 -7.96880 40.09867 -0.04722 -6.99550 40.80132 -2.75254 -7.96880 39.67384 -3.39862 -6.99551 40.12094 -4.42626 -7.96880 38.84582 -5.86571 -7.96881 37.65667 -6.23433 -6.99551 38.21012 -6.99652 -7.96881 36.17090 -7.75793 -7.96880 34.46621 -8.12485 -6.99550 35.36077 -8.10922 -7.96881 32.63197 -8.03264 -7.96881 30.76628 -8.78182 -6.99550 32.00491 -8.31528 -6.58320 28.80709 -7.38981 -8.03500 28.76241 8.35498 -6.50680 28.91394 8.65656 -1.93718 29.60358 8.95977 -5.84750 31.29569 8.90306 -5.84750 33.27615 8.41431 -5.84750 35.19623 7.51734 -5.84750 36.96279 6.25565 -5.84750 38.49036 4.69026 -5.84750 39.70473 2.89704 -5.84750 40.54733 0.96295 -5.84750 40.97696 -1.01800 -5.84750 40.97280 -2.95095 -5.84750 40.53608 -4.74085 -5.84750 39.68664 -6.30115 -5.84750 38.46575 -7.55740 -5.84750 36.93373 -8.44687 -5.84750 35.16320 -8.92799 -5.84750 33.24101 -8.62534 -5.22810 29.42574 -8.65377 -3.94260 29.52191 -8.97734 -5.84750 31.26040 -3.54577 -10.42670 -1.25647 -6.65746 -8.51410 -2.38897 -8.96560 -5.58340 -3.22972 -10.19165 -1.98888 -3.67597 -2.89297 -10.42670 -2.38769 -5.42971 -8.51410 -4.51616 -7.31068 -5.58340 -6.09605 -8.31018 -1.98888 -6.93474 -1.89269 -10.42670 -3.22760 -3.54852 -8.51410 -6.09527 -4.77528 -5.58340 -8.22358 -5.42766 -1.98888 -9.35354 -0.66558 -10.42670 -3.67491 -1.24074 -8.51410 -6.93595 -1.66514 -5.58340 -9.35552 -1.89170 -1.98888 -10.64048 0.64045 -10.42670 -3.67576 1.21532 -8.51410 -6.93680 1.64468 -5.58340 -9.35552 1.87123 -1.98888 -10.64047 1.86813 -10.42670 -3.23000 3.52368 -8.51410 -6.09782 4.75482 -5.58340 -8.22358 5.40719 -1.98888 -9.35354 2.86939 -10.42670 -2.39137 5.40599 -8.51410 -4.51997 7.29022 -5.58340 -6.09604 8.28971 -1.98888 -6.93474 3.52367 -10.42670 -1.26092 6.63523 -8.51410 -2.39370 8.94513 -5.58340 -3.22972 10.17118 -1.98888 -3.67597 8.64029 -4.00260 29.54616 8.32436 -1.73106 26.06027 8.60947 -2.33540 21.80618 8.92802 -2.88240 17.45089 9.35575 -3.28920 13.09561 9.83651 -3.46070 8.74033 10.22011 -3.56470 4.38505 10.80892 -1.98570 0.02976 10.72605 -1.27740 4.35415 5.01207 -10.00026 28.28688 5.02005 -9.81260 27.17792 2.85645 -10.71490 26.98417 6.86779 -7.98360 26.51642 8.25683 -3.85270 26.51529 7.96325 -5.71200 25.97040 4.93555 -9.54140 24.90974 2.84804 -10.42130 24.73748 6.78704 -7.74200 24.30869 7.87952 -5.61980 23.80835 8.28384 -3.80310 24.13419 4.98816 -9.14010 22.64770 3.09609 -9.98350 22.49072 6.68360 -7.52270 22.10104 8.25740 -4.04790 21.48409 7.73768 -5.67680 21.64630 5.12194 -8.70980 20.38566 3.49200 -9.50700 20.24403 6.58863 -7.35050 19.89338 7.59137 -5.83280 19.48432 8.23527 -4.50730 18.53411 5.29915 -8.34090 18.12349 3.92878 -9.09570 17.99734 6.53255 -7.24950 17.68572 7.49153 -6.03850 17.32227 5.48222 -8.12370 15.86138 4.29923 -8.85360 15.75065 6.54521 -7.24360 15.47806 8.32521 -4.99490 15.26346 7.48771 -6.24570 15.16022 5.64083 -8.11670 13.59928 4.52889 -8.84360 13.50389 6.63742 -7.33930 13.27048 7.59222 -6.42810 12.99817 8.61378 -5.31020 11.68500 5.76895 -8.27690 11.33725 4.63475 -9.01520 11.25721 6.78224 -7.50950 11.06275 7.76900 -6.58860 10.83612 5.86526 -8.54080 9.07521 4.64917 -9.29850 9.01044 6.94848 -7.72320 8.85509 7.97887 -6.73170 8.67407 9.00644 -5.47800 7.87617 5.92833 -8.84490 6.81303 4.60456 -9.62350 6.76375 7.10496 -7.94950 6.64743 8.18244 -6.86220 6.51209 5.95697 -9.12580 4.55093 4.53343 -9.92030 4.51699 7.22057 -8.15740 4.43977 8.34041 -6.98480 4.35004 9.32640 -5.60480 3.95307 5.94975 -9.32000 2.28890 4.46815 -10.11880 2.27030 7.26406 -8.31580 2.23212 9.50643 -5.57620 0.02976 8.41345 -7.10400 2.18806 7.06211 -8.51270 0.02481 1.22529 -10.88770 26.75026 -0.26995 -10.87760 26.46784 0.63860 -10.87860 26.55729 1.30046 -10.62680 24.50003 1.66399 -10.23150 22.07600 0.80393 -10.44950 22.75150 -0.46780 -10.47090 22.73461 0.17213 -10.48820 22.68822 2.21228 -9.79770 19.47371 1.34910 -9.93470 18.96452 -0.65823 -9.98000 18.95052 0.34962 -10.02580 18.91170 2.77768 -9.47130 16.66155 1.78511 -9.70400 15.17754 -0.89992 -9.76190 15.16637 0.44522 -9.83460 15.13533 3.12557 -9.44800 13.61292 1.88616 -9.93560 11.39063 -1.07563 -9.98590 11.38229 0.40633 -10.07450 11.35896 3.19084 -9.74200 10.35776 1.75633 -10.40880 7.60365 -1.22349 -10.43620 7.59807 0.26646 -10.53420 7.58258 3.06080 -10.19830 6.97885 3.74599 -10.40920 0.02460 2.87010 -10.60690 3.52160 1.54102 -10.85330 3.81674 -1.40118 -10.84930 3.81398 -0.01023 -11.09010 0.02976 0.06932 -10.95770 3.80620 8.61265 -5.22370 29.45177 -5.42738 -9.92590 28.97489 -5.11936 -9.78800 27.34444 -3.12402 -10.63996 26.98725 -1.22462 -10.88650 26.70466 -6.92828 -7.93410 26.71059 -7.87333 -5.98230 26.22347 -4.79982 -9.57520 24.83005 -1.13835 -10.60840 24.18891 -2.69618 -10.42670 24.54579 -6.62395 -7.81780 24.35296 -7.69641 -5.71710 23.89709 -4.64892 -9.19030 22.35008 -1.33429 -10.17780 21.40864 -2.76823 -9.98440 22.09418 -6.30171 -7.65080 21.92059 -7.34378 -5.86490 21.51039 -4.58613 -8.78450 19.86997 -2.99557 -9.51640 19.64257 -5.99730 -7.53980 19.48835 -7.00006 -6.12260 19.12369 -1.72766 -9.73310 18.33506 -4.61109 -8.46230 17.38994 -3.28867 -9.14720 17.19096 -5.79564 -7.50060 17.05604 -6.77357 -6.40600 16.73700 -2.13855 -9.52300 14.94243 -4.72338 -8.32530 14.90997 -3.56026 -8.99590 14.73935 -5.77711 -7.54710 14.62374 -6.76190 -6.63670 14.35030 -4.91141 -8.39420 12.42994 -3.77749 -9.07780 12.28781 -5.94427 -7.66770 12.19143 -6.95685 -6.79510 11.96360 -2.40556 -9.73220 11.24200 -5.15147 -8.59740 9.94990 -3.95787 -9.31080 9.83620 -6.23701 -7.82950 9.75912 -7.28799 -6.89590 9.57691 -5.41925 -8.85820 7.46987 -2.57576 -10.18540 7.41507 -4.12086 -9.60930 7.38459 -6.59311 -7.99900 7.32682 -7.68404 -6.95410 7.19021 -5.69028 -9.10020 4.98983 -4.28568 -9.88760 4.93298 -6.95048 -8.14300 4.89451 -8.07380 -6.98470 4.80358 -2.75840 -10.58590 3.62321 -5.94010 -9.24670 2.50980 -3.75606 -10.38410 0.02976 -4.47194 -10.06000 2.48144 -7.24683 -8.22780 2.46228 -8.38620 -7.00290 2.41682 -7.06228 -8.49030 0.02983 -8.25863 -3.89250 26.86290 -8.18404 -3.84830 24.93399 -8.28218 -2.23900 26.50221 -8.02359 -4.03470 22.84328 -7.82107 -4.40870 20.58139 -8.31577 -2.50190 22.09022 -8.53313 -0.96570 21.91118 -7.64989 -4.88510 18.13671 -8.36209 -3.21540 17.67809 -8.79618 -1.29108 17.53489 -7.62288 -5.32120 15.49638 -8.71246 -3.66280 13.26609 -9.26471 -1.45734 13.15861 -8.04629 -5.61900 11.15913 -9.34524 -3.70270 8.85396 -9.89934 -1.41769 8.78240 -8.76916 -5.63130 6.52920 -9.53206 -5.59780 0.02983 -9.24738 -5.57550 3.30953 -10.01191 -3.57510 4.44190 -10.43772 -3.51470 0.02983 -10.52279 -1.28658 4.40604 -10.82211 -1.98461 0.02984 + + + + + + + + + + -0.99767 -0.00000 0.06824 -0.99767 0.00000 0.06824 -0.96454 0.24231 0.10462 -0.97224 0.21562 0.09088 -0.91458 0.39600 0.08208 -0.91393 0.39734 0.08277 -0.90059 0.41583 0.12656 -0.99000 0.00000 0.14104 -0.96794 0.21402 0.13148 -0.99000 -0.00000 0.14104 -0.96340 0.22926 0.13894 -0.89990 0.41813 0.12388 -0.88968 0.43458 0.14006 -0.98965 -0.00000 0.14352 -0.96356 0.22934 0.13766 -0.98965 -0.00000 0.14352 -0.96207 0.23408 0.14010 -0.88674 0.44327 0.13118 -0.89489 0.43069 0.11693 -0.99432 -0.00000 0.10645 -0.99432 0.00000 0.10645 -0.96519 0.23621 0.11231 -0.89409 0.43290 0.11490 -0.97228 0.21198 0.09871 -0.92371 0.37938 0.05321 -0.99820 0.00000 0.06000 -0.97395 0.21417 0.07446 -0.99820 0.00000 0.06000 -0.99013 0.13632 0.03244 -0.97187 0.23444 -0.02237 -0.92437 0.37496 0.07034 -0.97592 0.21175 -0.05236 -0.99865 0.00000 0.05197 -0.99865 -0.00000 0.05197 -0.98943 0.13338 0.05683 -0.99703 -0.00430 -0.07690 -0.98471 0.17078 0.03445 -0.99984 0.01582 0.00892 -0.99897 0.02275 -0.03915 -0.76038 0.64925 -0.01717 -0.73242 0.68061 0.01788 -0.48479 0.87424 -0.02599 -0.49664 0.86705 -0.03972 -0.61532 0.78735 0.03828 -0.83204 0.54949 0.07596 -0.31376 0.94890 0.03382 -0.81854 0.56354 0.11144 -0.73035 0.67561 0.10075 -0.71775 0.68733 0.11142 -0.61399 0.78268 0.10210 -0.81869 0.56324 0.11184 -0.48080 0.87136 0.09781 -0.34769 0.93308 0.09203 -0.48346 0.86963 0.10007 -0.60650 0.78777 0.10763 -0.79844 0.58607 0.13791 -0.71708 0.68553 0.12589 -0.69385 0.70563 0.14372 -0.60576 0.78404 0.13542 -0.31946 0.93891 0.12806 -0.48077 0.86705 0.13075 -0.34904 0.93002 0.11504 -0.48920 0.86127 0.13750 -0.59586 0.79039 0.14224 -0.69421 0.70748 0.13245 -0.79949 0.58245 0.14687 -0.77873 0.61514 0.12322 -0.67103 0.72634 0.14886 -0.59586 0.79038 0.14231 -0.34847 0.92739 0.13608 -0.48921 0.86128 0.13739 -0.58832 0.79513 0.14714 -0.49759 0.85543 0.14368 -0.36416 0.92284 0.12548 -0.67093 0.73109 0.12396 -0.77086 0.62291 0.13326 -0.66384 0.73668 0.12890 -0.58747 0.79970 0.12390 -0.35537 0.92771 0.11432 -0.50110 0.85726 0.11834 -0.50168 0.85686 0.11877 -0.58975 0.79824 0.12249 -0.76748 0.63009 0.11819 -0.78791 0.60683 0.10463 -0.66255 0.74185 0.10335 -0.58579 0.80648 0.08025 -0.68882 0.72016 0.08305 -0.50811 0.85814 0.07369 -0.38872 0.91905 0.06515 -0.60457 0.79365 0.06788 -0.49176 0.86856 0.06141 -0.35638 0.93105 0.07835 -0.68723 0.72339 0.06656 -0.81428 0.57815 0.05191 -0.59594 0.80296 0.01081 -0.74673 0.66509 0.00703 -0.34509 0.93836 -0.01968 -0.49928 0.86644 0.00184 -0.62775 0.77828 -0.01457 -0.46303 0.88590 -0.02797 -0.34041 0.94012 -0.01699 -0.82853 0.55376 0.08299 -0.87635 0.48096 -0.02605 -0.74688 0.66491 0.00808 -0.61810 0.78350 -0.06387 -0.80460 0.58891 -0.07620 -0.46761 0.88060 -0.07671 -0.27717 0.95443 -0.11060 -0.42857 0.89652 -0.11216 -0.64455 0.75899 -0.09212 -0.89314 0.44908 0.02497 -0.92670 0.36382 -0.09418 -0.80866 0.58586 -0.05320 -0.63949 0.76019 -0.11473 -0.84324 0.52174 -0.12935 -0.42979 0.89342 -0.13069 -0.18752 0.97526 -0.11710 -0.31463 0.93733 -0.14976 -0.65561 0.74237 -0.13807 -0.40225 0.90184 -0.15774 -0.94397 0.32865 -0.03017 -0.85042 0.51771 -0.09359 -0.95633 0.26423 -0.12493 -0.65566 0.74237 -0.13783 -0.86757 0.47493 -0.14754 -0.14656 0.97906 -0.14130 -0.21004 0.96322 -0.16760 -0.40190 0.90313 -0.15112 -0.66437 0.73138 -0.15394 -0.38910 0.90641 -0.16435 -0.97315 0.22354 -0.05475 -0.97487 0.20055 -0.09700 -0.87795 0.45904 -0.13597 -0.87338 0.47197 -0.12022 -0.14073 0.98352 -0.11355 -0.67173 0.73056 -0.12275 -0.98477 0.16873 -0.04195 -0.38816 0.90972 -0.14748 -0.14417 0.98329 -0.11115 -0.40878 0.90355 -0.12842 -0.68228 0.71609 -0.14731 -0.67028 0.71807 -0.18736 -0.19020 0.98174 -0.00233 -0.07328 0.99664 0.03649 -0.18521 0.98268 -0.00555 0.07048 0.99695 0.03347 0.18002 0.98361 -0.01052 0.17834 0.98390 -0.01153 0.20355 0.97354 0.10383 -0.20453 0.97237 0.11255 0.06958 0.99176 0.10759 -0.07243 0.99073 0.11489 -0.19623 0.97373 0.11551 -0.06407 0.99172 0.11127 0.20613 0.97314 0.10251 0.08178 0.99038 0.11160 0.21505 0.96888 0.12257 0.08164 0.98972 0.11746 -0.06386 0.99036 0.12292 -0.19714 0.97251 0.12394 -0.19850 0.97229 0.12345 -0.05736 0.99109 0.12018 0.23260 0.96602 0.11273 0.09021 0.98861 0.12044 0.21713 0.97179 0.09212 -0.19398 0.97855 0.06932 0.09195 0.99382 0.06219 -0.05856 0.99624 0.06389 -0.05245 0.99673 0.06144 -0.20065 0.97736 0.06717 0.09484 0.99348 0.06329 0.26082 0.96314 0.06586 0.20552 0.97852 0.01598 -0.18248 0.98245 -0.03874 0.09839 0.99400 -0.04784 -0.05509 0.99713 -0.05188 -0.04742 0.99739 -0.05446 -0.20086 0.97865 -0.04358 0.26749 0.96316 -0.02788 0.09327 0.99439 -0.04984 0.19850 0.97734 -0.07353 -0.15618 0.98019 -0.12183 0.09626 0.98851 -0.11651 -0.04980 0.99107 -0.12369 -0.03599 0.99128 -0.12678 -0.14862 0.98160 -0.11986 0.14399 0.98058 -0.13312 0.21395 0.97158 -0.10128 0.07304 0.98959 -0.12401 -0.11159 0.98321 -0.14441 0.13935 0.98044 -0.13899 0.07162 0.99149 -0.10868 -0.03387 0.99478 -0.09629 0.00962 0.99402 -0.10880 -0.02783 0.99389 -0.10680 0.03443 0.99328 -0.11050 -0.01814 0.99371 -0.11047 0.02223 0.99318 -0.11441 0.76708 0.63841 -0.06345 0.72544 0.68827 -0.00498 0.30890 0.95080 0.02362 0.83514 0.54897 0.03432 0.72526 0.68565 0.06231 0.82020 0.56902 0.05908 0.72415 0.68671 0.06354 0.60756 0.79129 0.06875 0.34302 0.93650 0.07278 0.47298 0.87876 0.06390 0.61061 0.78919 0.06581 0.48471 0.87160 0.07328 0.72364 0.68407 0.09166 0.82253 0.56124 0.09192 0.71291 0.69370 0.10266 0.61072 0.78474 0.10588 0.48311 0.86987 0.09962 0.31995 0.94054 0.11412 0.61155 0.78419 0.10512 0.50061 0.85828 0.11291 0.35851 0.92917 0.09004 0.81707 0.57022 0.08507 0.71282 0.69283 0.10894 0.80209 0.58681 0.11095 0.69924 0.70444 0.12177 0.61189 0.78125 0.12345 0.36156 0.92374 0.12645 0.50050 0.85817 0.11420 0.51954 0.84480 0.12805 0.61362 0.78013 0.12198 0.38034 0.91836 0.10938 0.80324 0.58413 0.11663 0.69919 0.70569 0.11458 0.61360 0.78018 0.12173 0.69199 0.71170 0.12100 0.52138 0.84620 0.11005 0.38696 0.91454 0.11780 0.53560 0.83585 0.12032 0.61953 0.77621 0.11693 0.79482 0.59711 0.10825 0.69151 0.71401 0.10954 0.79437 0.59751 0.10931 0.70174 0.70532 0.10041 0.61785 0.77982 0.10065 0.53892 0.83760 0.08937 0.40328 0.91078 0.08857 0.53956 0.83714 0.08985 0.63090 0.77059 0.09031 0.39986 0.91211 0.09040 0.78542 0.61244 0.08963 0.70120 0.70680 0.09352 0.82094 0.55921 0.11547 0.73516 0.67524 0.05998 0.62616 0.77739 0.05985 0.39770 0.91679 0.03657 0.54333 0.83792 0.05181 0.52248 0.85197 0.03400 0.64629 0.76188 0.04296 0.39538 0.91773 0.03811 0.73553 0.67452 0.06334 0.82782 0.55858 0.05207 0.78437 0.62028 0.00284 0.63807 0.76997 0.00160 0.52543 0.85082 -0.00505 0.35396 0.93430 -0.04231 0.48512 0.87331 -0.04459 0.65879 0.75209 -0.01890 0.86262 0.49633 0.09772 0.89950 0.43693 0.00003 0.78701 0.61653 0.02231 0.82761 0.55937 -0.04661 0.65156 0.75687 -0.05118 0.48602 0.87152 -0.06506 0.34986 0.93602 -0.03830 0.28709 0.95058 -0.11821 0.44439 0.88903 -0.11017 0.66556 0.74315 -0.06905 0.83220 0.55424 -0.01632 0.95307 0.30015 0.03959 0.89121 0.45274 -0.02764 0.85760 0.50858 -0.07656 0.66141 0.74501 -0.08656 0.27767 0.95538 -0.10076 0.21481 0.96240 -0.16626 0.44440 0.88902 -0.11024 0.66964 0.73587 -0.10038 0.41286 0.89892 -0.14658 0.95305 0.30225 0.01841 0.97662 0.20684 -0.05862 0.86294 0.50345 -0.04334 0.87706 0.47225 -0.08801 0.66864 0.73621 -0.10446 0.41266 0.90154 -0.13011 0.20498 0.97043 -0.12751 0.15560 0.97267 -0.17235 0.39452 0.90629 -0.15161 0.67313 0.73069 -0.11397 0.88256 0.46708 -0.05410 0.98737 0.15822 0.00791 0.97680 0.20901 -0.04674 0.67546 0.72995 -0.10459 0.88991 0.44878 -0.08166 0.14727 0.98306 -0.10906 0.12275 0.98401 -0.12905 0.39401 0.91117 -0.12055 0.67851 0.72599 -0.11208 0.39136 0.91190 -0.12361 0.67690 0.72654 -0.11807 0.99982 -0.00000 0.01916 0.99982 0.00000 0.01916 0.97513 0.21496 0.05390 0.94005 0.34101 0.00346 0.91222 0.40785 0.03889 0.90555 0.41517 0.08727 0.97237 0.21381 0.09374 0.99591 0.00000 0.09036 0.99528 -0.01118 0.09639 0.97380 0.20853 0.09075 0.90693 0.41161 0.08971 0.90133 0.41858 0.11136 0.97101 0.20716 0.11924 0.99313 -0.01110 0.11647 0.99259 -0.01807 0.12012 0.97296 0.20013 0.11528 0.90348 0.41264 0.11598 0.90609 0.40879 0.10909 0.97184 0.19947 0.12548 0.99252 -0.01807 0.12075 0.99237 -0.01995 0.12169 0.97791 0.17618 0.11249 0.91184 0.39071 0.12604 0.93471 0.34689 0.07742 0.99350 -0.02004 0.11204 0.97742 0.17578 0.11727 0.99384 -0.01487 0.10981 0.98959 0.11478 0.08680 0.93026 0.36352 0.04963 0.97095 0.21812 0.09841 0.97914 0.20299 0.00898 0.99463 -0.01497 0.10236 0.98622 0.11081 0.12284 0.99241 0.09359 0.07981 0.99756 0.01285 0.06868 0.99951 0.02951 0.01072 0.98551 0.00000 -0.16960 0.92804 0.33665 -0.15942 0.98551 -0.00000 -0.16960 0.76218 0.63421 -0.12985 0.92820 0.33635 -0.15910 0.49458 0.86479 -0.08680 0.75944 0.63670 -0.13368 0.17832 0.98382 -0.01744 0.50219 0.86149 -0.07512 0.86602 -0.00000 -0.50000 0.86602 -0.00000 -0.50000 0.81549 0.33661 -0.47083 0.66796 0.63648 -0.38565 0.81548 0.33661 -0.47083 0.66756 0.63673 -0.38593 0.43801 0.86257 -0.25322 0.15254 0.98435 -0.08829 0.43779 0.86263 -0.25339 0.64280 -0.00000 -0.76603 0.64280 0.00000 -0.76603 0.60529 0.33661 -0.72133 0.60529 0.33661 -0.72133 0.49578 0.63649 -0.59083 0.49535 0.63672 -0.59094 0.32501 0.86257 -0.38773 0.32481 0.86262 -0.38779 0.11317 0.98435 -0.13512 0.34201 0.00000 -0.93970 0.34201 -0.00000 -0.93970 0.32205 0.33661 -0.88486 0.32205 0.33662 -0.88486 0.26378 0.63651 -0.72476 0.17282 0.86257 -0.47550 0.26340 0.63671 -0.72472 0.06015 0.98435 -0.16567 0.17265 0.86261 -0.47549 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.33662 -0.94164 0.00000 0.33661 -0.94164 0.00000 0.63652 -0.77126 -0.00027 0.63668 -0.77113 -0.00018 0.86257 -0.50593 -0.00033 0.86261 -0.50586 -0.00011 0.98435 -0.17625 -0.34201 0.00000 -0.93970 -0.34201 0.00000 -0.93970 -0.32205 0.33661 -0.88486 -0.26377 0.63654 -0.72474 -0.32205 0.33661 -0.88486 -0.26394 0.63667 -0.72456 -0.17316 0.86258 -0.47536 -0.06036 0.98435 -0.16559 -0.17325 0.86261 -0.47528 -0.64280 0.00000 -0.76603 -0.64280 0.00000 -0.76603 -0.60529 0.33661 -0.72133 -0.49575 0.63655 -0.59079 -0.60529 0.33661 -0.72133 -0.49581 0.63663 -0.59066 -0.32527 0.86259 -0.38749 -0.32530 0.86260 -0.38742 -0.11334 0.98435 -0.13498 -0.86602 0.00000 -0.50000 -0.81549 0.33661 -0.47083 -0.86602 0.00000 -0.50000 -0.66790 0.63655 -0.38562 -0.81548 0.33661 -0.47083 -0.66791 0.63662 -0.38550 -0.43816 0.86259 -0.25289 -0.43817 0.86260 -0.25285 -0.15265 0.98435 -0.08809 -0.98584 0.00000 -0.16772 -0.98584 0.00000 -0.16772 -0.75928 0.63665 -0.13476 -0.49635 0.86654 -0.05245 -0.18521 0.98270 0.00226 -0.75499 0.64466 -0.12002 -0.50205 0.86153 -0.07555 -0.98281 0.00156 -0.18463 -0.98159 0.00743 -0.19084 -0.98377 0.00000 -0.17946 -0.99969 -0.00000 0.02491 -0.99969 0.00000 0.02491 -0.97007 0.00000 0.24281 -0.97007 -0.00000 0.24281 -0.89358 -0.00000 0.44891 -0.89358 -0.00000 0.44891 -0.77327 -0.00000 0.63408 -0.77327 -0.00000 0.63408 -0.61624 -0.00000 0.78756 -0.61624 -0.00000 0.78756 -0.42875 -0.00000 0.90343 -0.42874 -0.00000 0.90343 -0.22038 -0.00000 0.97541 -0.22038 -0.00000 0.97541 -0.00210 -0.00000 1.00000 -0.00210 -0.00000 1.00000 0.21685 -0.00000 0.97620 0.21685 -0.00000 0.97620 0.42527 -0.00000 0.90507 0.42527 -0.00000 0.90507 0.61295 -0.00000 0.79012 0.61295 0.00000 0.79012 0.77101 0.00000 0.63682 0.77102 -0.00000 0.63682 0.89165 0.00000 0.45273 0.89165 -0.00000 0.45273 0.96910 -0.00000 0.24668 0.96910 -0.00000 0.24668 0.99959 -0.00000 0.02862 0.99959 -0.00000 0.02862 0.98458 0.00000 -0.17493 0.98382 0.00125 -0.17918 0.98323 0.00267 -0.18236 0.98223 0.00774 -0.18752 0.97049 0.10362 -0.21775 -0.96703 0.11833 -0.22548 -0.94612 0.27353 -0.17330 -0.81205 0.58264 -0.03333 -0.98803 0.15231 0.02462 -0.90531 0.35925 0.22660 -0.95379 0.23541 0.18672 -0.86306 0.47728 0.16529 -0.85829 0.48487 0.16803 -0.74132 0.58379 0.33111 -0.88044 0.17084 0.44231 -0.66848 0.54248 0.50877 -0.74356 0.45136 0.49335 -0.78755 0.32668 0.52253 -0.76020 0.18305 0.62336 -0.52676 0.56208 0.63764 -0.60294 0.20667 0.77055 -0.52913 0.32159 0.78524 -0.50053 0.44467 0.74280 -0.36223 0.57679 0.73219 -0.42339 0.15752 0.89215 -0.21293 0.25778 0.94245 -0.18978 0.30012 0.93483 -0.20391 0.44397 0.87253 -0.17194 0.50317 0.84691 -0.00208 0.14945 0.98877 0.00107 0.58598 0.81033 0.20530 0.32205 0.92419 0.18407 0.26251 0.94721 0.19566 0.52283 0.82968 0.16931 0.46073 0.87124 0.41985 0.15917 0.89353 0.36533 0.57289 0.73371 0.56280 0.39615 0.72548 0.53979 0.20603 0.81619 0.49427 0.44401 0.74736 0.52581 0.56716 0.63392 0.75755 0.18606 0.62570 0.72890 0.40527 0.55178 0.70606 0.52343 0.47697 0.78342 0.32584 0.52923 0.87889 0.16852 0.44626 0.74119 0.58526 0.32879 0.85161 0.49875 0.16127 0.86295 0.47345 0.17653 0.94327 0.22931 0.24011 0.93036 0.31338 0.19032 0.98805 0.15153 0.02829 0.81357 0.58039 -0.03525 0.88222 0.43491 -0.18041 0.94711 0.27576 -0.16416 0.81130 0.52202 -0.26323 -0.66164 0.71281 -0.23266 -0.68713 0.69922 -0.19733 -0.69930 0.71086 -0.07523 -0.71425 0.69928 -0.02932 -0.69525 0.71292 0.09154 -0.70041 0.70102 0.13414 -0.65047 0.71014 0.26942 -0.64881 0.70360 0.28980 -0.56351 0.70605 0.42888 -0.56099 0.70709 0.43047 -0.45311 0.70274 0.54849 -0.42808 0.71099 0.55788 -0.31647 0.70044 0.63971 -0.26816 0.71343 0.64739 -0.16274 0.69898 0.69638 -0.09129 0.71479 0.69336 0.00095 0.69850 0.71561 0.09129 0.71478 0.69337 0.16416 0.69891 0.69612 0.26809 0.71360 0.64722 0.31819 0.70029 0.63902 0.42796 0.71119 0.55773 0.45431 0.70258 0.54771 0.56358 0.70736 0.42664 0.56221 0.70556 0.43140 0.64937 0.70381 0.28805 0.65079 0.70980 0.26955 0.70058 0.70113 0.13267 0.69542 0.71275 0.09156 0.71409 0.69937 -0.03094 0.69915 0.71091 -0.07607 0.68564 0.69818 -0.20599 0.66836 0.70886 -0.22541 0.53660 0.84181 -0.05838 0.21287 0.97660 -0.03061 0.21611 0.97593 -0.02917 0.50647 0.85791 -0.08650 0.53558 0.82495 -0.18059 0.17249 0.98186 -0.07876 0.17261 0.98174 -0.07995 0.47616 0.83648 -0.27126 0.10940 0.98947 -0.09480 0.08418 0.98780 -0.13101 0.08169 0.98354 -0.16117 0.05378 0.98162 -0.18311 -0.00960 0.99694 -0.07762 -0.11065 0.97883 -0.17220 -0.16155 0.97786 -0.13303 -0.15943 0.97750 -0.13814 -0.17754 0.97553 -0.12971 -0.17247 0.98186 -0.07875 -0.54893 0.80453 -0.22674 -0.49438 0.86762 -0.05319 -0.53522 0.83965 -0.09230 -0.21436 0.97633 -0.02886 -0.21610 0.97588 -0.03108 -0.01071 0.99716 -0.07451 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.53617 0.84115 0.07059 -0.49467 0.86319 0.10102 -0.22947 0.97276 0.03299 -0.21605 0.97566 0.03747 -0.52918 0.81972 0.21918 -0.17211 0.98194 0.07861 -0.15313 0.97926 0.13268 -0.16699 0.97692 0.13318 -0.42461 0.84472 0.32582 -0.40904 0.85222 0.32620 -0.35041 0.81772 0.45667 -0.10438 0.98119 0.16241 -0.19285 0.86375 0.46556 -0.23759 0.83675 0.49335 -0.09429 0.97610 0.19580 -0.05367 0.98169 0.18276 -0.07403 0.82361 0.56230 -0.00000 0.86006 0.51020 -0.00000 0.97770 0.21000 0.00000 0.97770 0.21000 0.07403 0.82361 0.56230 0.05367 0.98169 0.18276 0.20977 0.83638 0.50643 0.22385 0.85664 0.46482 0.09429 0.97610 0.19580 0.10438 0.98119 0.16241 0.35041 0.81772 0.45666 0.16593 0.97560 0.14378 0.16059 0.97868 0.12807 0.41282 0.85395 0.31677 0.41722 0.84571 0.33273 0.17211 0.98194 0.07861 0.52918 0.81971 0.21918 0.48206 0.87384 0.06347 0.53424 0.83813 0.11015 0.22217 0.97423 0.03886 0.21610 0.97588 0.03106 0.81364 0.55878 -0.16051 0.85073 0.46784 -0.23954 0.64212 0.71513 -0.27617 0.65774 0.73793 -0.15112 0.47006 0.84484 -0.25553 0.45904 0.83586 -0.30104 0.11587 0.99032 -0.07642 0.39198 0.90754 -0.15075 -0.34968 0.91095 -0.21885 -0.41281 0.87590 -0.24976 -0.59330 0.78495 -0.17847 -0.11267 0.98835 -0.10230 -0.41718 0.87682 -0.23907 -0.15198 0.97322 -0.17246 -0.67118 0.71751 -0.18626 -0.97021 0.12813 -0.20560 -0.97355 0.12000 -0.19444 -0.81799 0.51345 -0.25934 -0.85665 0.46863 -0.21574 -0.98905 0.01086 -0.14718 0.99660 0.00256 -0.08240 0.99512 0.02698 -0.09487 0.99559 0.00524 -0.09365 0.99000 0.05900 -0.12817 0.99193 0.01270 -0.12613 0.98012 0.10552 -0.16803 0.97810 0.12744 -0.16458 0.02348 0.99271 -0.11822 0.02315 0.99272 -0.11824 0.01140 0.99185 -0.12690 -0.02193 0.99183 -0.12569 -0.01668 0.99127 -0.13081 -0.11535 0.98039 -0.15976 -0.87838 0.44072 -0.18497 -0.82070 0.51558 -0.24624 -0.92751 0.33656 -0.16267 -0.89470 0.38898 -0.21957 -0.95697 0.24041 -0.16253 0.49539 0.86620 -0.06547 0.60747 0.79420 0.01527 0.47459 0.87935 -0.03890 0.47459 -0.87935 -0.03890 0.60747 -0.79420 0.01527 0.49539 -0.86620 -0.06547 -0.95697 -0.24041 -0.16253 -0.89470 -0.38898 -0.21957 -0.92751 -0.33656 -0.16267 -0.82070 -0.51558 -0.24624 -0.87838 -0.44072 -0.18497 -0.11535 -0.98039 -0.15976 -0.01668 -0.99127 -0.13081 -0.02193 -0.99183 -0.12569 0.01140 -0.99185 -0.12690 0.02315 -0.99272 -0.11824 0.02349 -0.99271 -0.11822 0.97810 -0.12744 -0.16458 0.98012 -0.10552 -0.16803 0.99193 -0.01270 -0.12613 0.99000 -0.05900 -0.12817 0.99559 -0.00524 -0.09365 0.99511 -0.02729 -0.09488 0.99659 -0.00269 -0.08245 -0.98905 -0.01086 -0.14718 -0.85665 -0.46863 -0.21574 -0.81799 -0.51345 -0.25934 -0.97355 -0.12000 -0.19444 -0.97021 -0.12813 -0.20560 -0.67119 -0.71751 -0.18626 -0.15198 -0.97322 -0.17246 -0.41717 -0.87682 -0.23907 -0.11267 -0.98835 -0.10230 -0.59330 -0.78495 -0.17847 -0.41281 -0.87590 -0.24976 -0.34967 -0.91095 -0.21885 0.39198 -0.90754 -0.15075 0.11587 -0.99032 -0.07642 0.45904 -0.83586 -0.30104 0.47006 -0.84484 -0.25553 0.65774 -0.73793 -0.15112 0.64212 -0.71513 -0.27616 0.85073 -0.46784 -0.23954 0.81364 -0.55877 -0.16052 0.21610 -0.97588 0.03106 0.22217 -0.97423 0.03886 0.53424 -0.83813 0.11015 0.48206 -0.87384 0.06347 0.52918 -0.81972 0.21918 0.17211 -0.98194 0.07861 0.41722 -0.84571 0.33273 0.41282 -0.85395 0.31677 0.16059 -0.97868 0.12807 0.16593 -0.97560 0.14378 0.35041 -0.81772 0.45666 0.10438 -0.98119 0.16240 0.09430 -0.97610 0.19580 0.22385 -0.85664 0.46482 0.20977 -0.83638 0.50643 0.05367 -0.98169 0.18276 0.07403 -0.82361 0.56230 0.00000 -0.97770 0.21000 0.00000 -0.97770 0.21000 0.00000 -0.86006 0.51020 -0.07403 -0.82361 0.56230 -0.05367 -0.98169 0.18276 -0.09430 -0.97610 0.19580 -0.23759 -0.83675 0.49335 -0.19284 -0.86375 0.46556 -0.10438 -0.98119 0.16241 -0.35041 -0.81772 0.45666 -0.40904 -0.85222 0.32620 -0.42461 -0.84472 0.32582 -0.16700 -0.97692 0.13318 -0.15313 -0.97926 0.13269 -0.17211 -0.98194 0.07861 -0.52917 -0.81972 0.21918 -0.21605 -0.97566 0.03747 -0.22947 -0.97276 0.03299 -0.49466 -0.86319 0.10102 -0.53617 -0.84115 0.07059 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.01071 -0.99716 -0.07451 -0.21610 -0.97588 -0.03108 -0.21436 -0.97633 -0.02886 -0.53522 -0.83965 -0.09230 -0.49438 -0.86762 -0.05319 -0.54893 -0.80453 -0.22674 -0.17247 -0.98186 -0.07875 -0.17754 -0.97553 -0.12971 -0.15943 -0.97750 -0.13815 -0.16155 -0.97786 -0.13303 -0.11065 -0.97883 -0.17220 -0.00960 -0.99694 -0.07762 0.05378 -0.98162 -0.18311 0.08169 -0.98354 -0.16117 0.08418 -0.98780 -0.13101 0.10940 -0.98947 -0.09480 0.47616 -0.83648 -0.27126 0.17261 -0.98174 -0.07995 0.17249 -0.98186 -0.07876 0.53559 -0.82495 -0.18059 0.50647 -0.85791 -0.08650 0.21611 -0.97593 -0.02917 0.21287 -0.97660 -0.03061 0.53660 -0.84181 -0.05838 0.66836 -0.70886 -0.22541 0.68564 -0.69818 -0.20599 0.69915 -0.71091 -0.07607 0.71409 -0.69937 -0.03094 0.69542 -0.71275 0.09156 0.70058 -0.70113 0.13266 0.65079 -0.70980 0.26955 0.64937 -0.70381 0.28805 0.56221 -0.70555 0.43140 0.56358 -0.70736 0.42664 0.45431 -0.70258 0.54771 0.42796 -0.71119 0.55773 0.31819 -0.70029 0.63902 0.26809 -0.71360 0.64722 0.16416 -0.69891 0.69612 0.09129 -0.71478 0.69337 0.00095 -0.69850 0.71561 -0.09129 -0.71479 0.69336 -0.16274 -0.69898 0.69638 -0.26816 -0.71343 0.64739 -0.31648 -0.70044 0.63971 -0.42808 -0.71099 0.55788 -0.45311 -0.70274 0.54849 -0.56099 -0.70709 0.43047 -0.56351 -0.70605 0.42888 -0.64881 -0.70360 0.28980 -0.65047 -0.71014 0.26942 -0.70041 -0.70102 0.13414 -0.69525 -0.71292 0.09154 -0.71425 -0.69928 -0.02932 -0.69930 -0.71086 -0.07523 -0.68713 -0.69922 -0.19733 -0.66164 -0.71281 -0.23266 0.81130 -0.52202 -0.26323 0.94711 -0.27576 -0.16416 0.88222 -0.43490 -0.18041 0.81357 -0.58039 -0.03525 0.98805 -0.15153 0.02829 0.93036 -0.31338 0.19032 0.94327 -0.22931 0.24011 0.86295 -0.47345 0.17653 0.85161 -0.49875 0.16126 0.74119 -0.58526 0.32879 0.87889 -0.16852 0.44626 0.78342 -0.32584 0.52923 0.70606 -0.52343 0.47697 0.72890 -0.40527 0.55178 0.75755 -0.18606 0.62570 0.52581 -0.56716 0.63392 0.49427 -0.44401 0.74736 0.53979 -0.20603 0.81619 0.56280 -0.39615 0.72548 0.36533 -0.57289 0.73371 0.41985 -0.15917 0.89353 0.16931 -0.46073 0.87124 0.19566 -0.52283 0.82968 0.18407 -0.26251 0.94721 0.20530 -0.32205 0.92419 0.00107 -0.58598 0.81033 -0.00208 -0.14945 0.98877 -0.17194 -0.50317 0.84691 -0.20391 -0.44397 0.87253 -0.18978 -0.30012 0.93483 -0.21293 -0.25778 0.94245 -0.42339 -0.15752 0.89215 -0.36223 -0.57679 0.73219 -0.50053 -0.44467 0.74280 -0.52913 -0.32159 0.78524 -0.60294 -0.20667 0.77055 -0.52676 -0.56208 0.63764 -0.76020 -0.18305 0.62336 -0.78755 -0.32668 0.52254 -0.74356 -0.45136 0.49335 -0.66848 -0.54248 0.50877 -0.88044 -0.17084 0.44231 -0.74131 -0.58380 0.33111 -0.85829 -0.48487 0.16803 -0.86306 -0.47729 0.16529 -0.95379 -0.23540 0.18672 -0.90531 -0.35925 0.22660 -0.98803 -0.15231 0.02462 -0.81205 -0.58264 -0.03333 -0.94612 -0.27353 -0.17330 -0.96703 -0.11833 -0.22549 0.97049 -0.10362 -0.21775 0.98223 -0.00774 -0.18752 0.98323 -0.00267 -0.18236 0.98379 -0.00131 -0.17931 -0.50205 -0.86153 -0.07555 -0.75499 -0.64466 -0.12002 -0.18521 -0.98270 0.00226 -0.49635 -0.86654 -0.05245 -0.75928 -0.63665 -0.13476 -0.15265 -0.98435 -0.08809 -0.43817 -0.86260 -0.25285 -0.43816 -0.86259 -0.25289 -0.66791 -0.63662 -0.38550 -0.81548 -0.33661 -0.47083 -0.66790 -0.63655 -0.38562 -0.81549 -0.33661 -0.47083 -0.11334 -0.98435 -0.13498 -0.32530 -0.86260 -0.38742 -0.32527 -0.86259 -0.38749 -0.49581 -0.63663 -0.59066 -0.60529 -0.33661 -0.72133 -0.49575 -0.63655 -0.59079 -0.60529 -0.33661 -0.72133 -0.17325 -0.86261 -0.47528 -0.06036 -0.98435 -0.16559 -0.17316 -0.86258 -0.47536 -0.26394 -0.63667 -0.72456 -0.32205 -0.33661 -0.88486 -0.26377 -0.63654 -0.72474 -0.32205 -0.33661 -0.88486 -0.00011 -0.98435 -0.17625 -0.00033 -0.86261 -0.50587 -0.00018 -0.86257 -0.50593 -0.00027 -0.63668 -0.77113 0.00000 -0.63652 -0.77126 0.00000 -0.33661 -0.94164 0.00000 -0.33661 -0.94164 0.17265 -0.86261 -0.47549 0.06015 -0.98435 -0.16567 0.26340 -0.63671 -0.72472 0.17282 -0.86257 -0.47550 0.26378 -0.63651 -0.72476 0.32204 -0.33661 -0.88486 0.32205 -0.33661 -0.88486 0.11317 -0.98435 -0.13512 0.32481 -0.86262 -0.38779 0.32501 -0.86257 -0.38773 0.49535 -0.63672 -0.59094 0.49578 -0.63649 -0.59083 0.60529 -0.33661 -0.72133 0.60529 -0.33661 -0.72133 0.43779 -0.86263 -0.25339 0.15254 -0.98435 -0.08829 0.43801 -0.86257 -0.25322 0.66756 -0.63673 -0.38593 0.81548 -0.33661 -0.47083 0.66796 -0.63648 -0.38565 0.81549 -0.33661 -0.47083 0.50219 -0.86149 -0.07512 0.17832 -0.98382 -0.01744 0.75944 -0.63670 -0.13368 0.49458 -0.86479 -0.08680 0.92820 -0.33635 -0.15910 0.76218 -0.63421 -0.12985 0.92804 -0.33665 -0.15942 0.99951 -0.02951 0.01072 0.99755 -0.01300 0.06870 0.99241 -0.09359 0.07981 0.98719 -0.10569 0.11953 0.97914 -0.20299 0.00898 0.97095 -0.21812 0.09841 0.93026 -0.36352 0.04963 0.99028 -0.10923 0.08615 0.97580 -0.18263 0.12026 0.93471 -0.34689 0.07742 0.91184 -0.39071 0.12605 0.97655 -0.18326 0.11302 0.96968 -0.20955 0.12572 0.90609 -0.40879 0.10909 0.90348 -0.41264 0.11598 0.97081 -0.21024 0.11544 0.97075 -0.21046 0.11555 0.90133 -0.41858 0.11136 0.90693 -0.41161 0.08971 0.97313 -0.21162 0.09076 0.97252 -0.21387 0.09195 0.90555 -0.41517 0.08727 0.91222 -0.40785 0.03889 0.94005 -0.34101 0.00346 0.97513 -0.21496 0.05390 0.67690 -0.72654 -0.11807 0.39136 -0.91190 -0.12361 0.67851 -0.72599 -0.11208 0.39401 -0.91117 -0.12055 0.12275 -0.98401 -0.12905 0.14727 -0.98306 -0.10906 0.88991 -0.44878 -0.08166 0.67546 -0.72994 -0.10459 0.97680 -0.20901 -0.04674 0.98737 -0.15822 0.00791 0.88256 -0.46708 -0.05410 0.67313 -0.73069 -0.11397 0.39452 -0.90629 -0.15161 0.15560 -0.97267 -0.17235 0.20498 -0.97043 -0.12751 0.41266 -0.90154 -0.13011 0.66864 -0.73621 -0.10446 0.87706 -0.47225 -0.08801 0.86294 -0.50345 -0.04334 0.97662 -0.20684 -0.05862 0.95305 -0.30225 0.01841 0.41286 -0.89892 -0.14658 0.66964 -0.73587 -0.10038 0.44440 -0.88902 -0.11024 0.21481 -0.96240 -0.16626 0.27767 -0.95538 -0.10076 0.66141 -0.74501 -0.08657 0.85760 -0.50858 -0.07656 0.89121 -0.45274 -0.02764 0.95307 -0.30015 0.03959 0.83220 -0.55424 -0.01632 0.66556 -0.74314 -0.06905 0.44439 -0.88903 -0.11017 0.28709 -0.95058 -0.11821 0.34986 -0.93602 -0.03830 0.48602 -0.87152 -0.06506 0.65156 -0.75687 -0.05118 0.82761 -0.55937 -0.04661 0.78701 -0.61653 0.02231 0.89950 -0.43693 0.00003 0.86262 -0.49633 0.09772 0.65879 -0.75209 -0.01890 0.48512 -0.87331 -0.04459 0.35396 -0.93430 -0.04231 0.52543 -0.85082 -0.00505 0.63807 -0.76997 0.00160 0.78437 -0.62028 0.00284 0.82782 -0.55858 0.05207 0.73553 -0.67452 0.06334 0.39538 -0.91773 0.03810 0.64629 -0.76188 0.04296 0.52248 -0.85197 0.03400 0.54333 -0.83792 0.05181 0.39770 -0.91679 0.03657 0.62616 -0.77739 0.05985 0.73516 -0.67524 0.05998 0.82094 -0.55921 0.11547 0.70120 -0.70680 0.09352 0.78542 -0.61244 0.08963 0.39986 -0.91211 0.09040 0.63090 -0.77059 0.09031 0.53956 -0.83714 0.08985 0.40328 -0.91078 0.08857 0.53892 -0.83760 0.08937 0.61786 -0.77982 0.10065 0.70174 -0.70532 0.10041 0.79437 -0.59751 0.10931 0.69151 -0.71401 0.10954 0.79482 -0.59711 0.10825 0.61953 -0.77621 0.11693 0.53560 -0.83585 0.12032 0.38696 -0.91454 0.11780 0.52138 -0.84620 0.11005 0.69199 -0.71170 0.12100 0.61360 -0.78018 0.12173 0.69919 -0.70570 0.11458 0.80324 -0.58413 0.11663 0.38034 -0.91836 0.10938 0.61362 -0.78013 0.12198 0.51954 -0.84480 0.12805 0.50050 -0.85817 0.11420 0.36156 -0.92374 0.12645 0.61190 -0.78124 0.12345 0.69924 -0.70444 0.12177 0.80209 -0.58681 0.11095 0.71282 -0.69283 0.10894 0.81707 -0.57022 0.08507 0.35851 -0.92917 0.09004 0.50061 -0.85828 0.11291 0.61155 -0.78419 0.10512 0.31995 -0.94054 0.11412 0.48311 -0.86987 0.09962 0.61072 -0.78474 0.10588 0.71291 -0.69370 0.10266 0.82253 -0.56124 0.09192 0.72364 -0.68407 0.09166 0.48471 -0.87160 0.07328 0.61061 -0.78919 0.06581 0.47298 -0.87876 0.06390 0.34302 -0.93650 0.07278 0.60756 -0.79129 0.06874 0.72415 -0.68671 0.06354 0.82020 -0.56902 0.05908 0.72526 -0.68565 0.06230 0.83514 -0.54897 0.03432 0.30890 -0.95080 0.02362 0.72544 -0.68826 -0.00498 0.76708 -0.63841 -0.06345 0.02223 -0.99318 -0.11441 -0.01814 -0.99371 -0.11047 0.03443 -0.99328 -0.11050 -0.02783 -0.99389 -0.10680 0.00962 -0.99402 -0.10880 -0.03387 -0.99478 -0.09629 0.07162 -0.99149 -0.10868 0.13935 -0.98044 -0.13899 -0.11159 -0.98321 -0.14441 0.07304 -0.98959 -0.12401 0.21395 -0.97158 -0.10128 0.14399 -0.98058 -0.13312 -0.14862 -0.98160 -0.11986 -0.03599 -0.99128 -0.12678 -0.04980 -0.99107 -0.12369 0.09626 -0.98851 -0.11651 -0.15618 -0.98019 -0.12183 0.19850 -0.97734 -0.07353 0.09327 -0.99439 -0.04984 0.26749 -0.96316 -0.02788 -0.20087 -0.97865 -0.04358 -0.04742 -0.99739 -0.05446 -0.05509 -0.99713 -0.05188 0.09839 -0.99400 -0.04784 -0.18248 -0.98245 -0.03874 0.20552 -0.97852 0.01597 0.26082 -0.96314 0.06586 0.09484 -0.99348 0.06329 -0.20065 -0.97736 0.06717 -0.05245 -0.99673 0.06144 -0.05856 -0.99624 0.06389 0.09195 -0.99382 0.06219 -0.19398 -0.97855 0.06932 0.21713 -0.97179 0.09212 0.09022 -0.98861 0.12044 0.23259 -0.96602 0.11273 -0.05736 -0.99109 0.12018 -0.19850 -0.97229 0.12345 -0.19714 -0.97251 0.12394 -0.06386 -0.99036 0.12292 0.08164 -0.98972 0.11745 0.21505 -0.96888 0.12256 0.08178 -0.99038 0.11160 0.20613 -0.97314 0.10250 -0.06407 -0.99172 0.11127 -0.19623 -0.97373 0.11551 -0.07243 -0.99073 0.11489 0.06958 -0.99176 0.10759 -0.20453 -0.97237 0.11255 0.20355 -0.97354 0.10383 0.17834 -0.98390 -0.01153 0.18002 -0.98361 -0.01052 0.07048 -0.99695 0.03347 -0.18521 -0.98268 -0.00555 -0.07328 -0.99664 0.03649 -0.19020 -0.98174 -0.00233 -0.67028 -0.71807 -0.18736 -0.68228 -0.71609 -0.14731 -0.40878 -0.90355 -0.12842 -0.14417 -0.98329 -0.11115 -0.38816 -0.90972 -0.14748 -0.98477 -0.16873 -0.04195 -0.67173 -0.73056 -0.12275 -0.14073 -0.98352 -0.11355 -0.87338 -0.47197 -0.12022 -0.87795 -0.45904 -0.13597 -0.97487 -0.20055 -0.09700 -0.97315 -0.22355 -0.05475 -0.38910 -0.90641 -0.16435 -0.66437 -0.73138 -0.15394 -0.40190 -0.90313 -0.15112 -0.21004 -0.96322 -0.16760 -0.14657 -0.97906 -0.14130 -0.86757 -0.47493 -0.14754 -0.65566 -0.74237 -0.13783 -0.95633 -0.26423 -0.12493 -0.85042 -0.51771 -0.09359 -0.94397 -0.32865 -0.03017 -0.40225 -0.90184 -0.15774 -0.65561 -0.74237 -0.13807 -0.31463 -0.93733 -0.14976 -0.18752 -0.97525 -0.11711 -0.42979 -0.89342 -0.13069 -0.84324 -0.52174 -0.12935 -0.63949 -0.76019 -0.11473 -0.80866 -0.58586 -0.05320 -0.92670 -0.36382 -0.09418 -0.89314 -0.44909 0.02497 -0.64455 -0.75899 -0.09212 -0.42857 -0.89652 -0.11216 -0.27717 -0.95443 -0.11060 -0.46761 -0.88060 -0.07671 -0.80460 -0.58891 -0.07620 -0.61810 -0.78350 -0.06387 -0.74688 -0.66491 0.00808 -0.87635 -0.48097 -0.02605 -0.82853 -0.55376 0.08299 -0.34041 -0.94013 -0.01699 -0.46303 -0.88590 -0.02797 -0.62775 -0.77828 -0.01457 -0.49928 -0.86644 0.00184 -0.34509 -0.93836 -0.01968 -0.74673 -0.66509 0.00703 -0.59594 -0.80296 0.01081 -0.81428 -0.57815 0.05191 -0.68723 -0.72339 0.06656 -0.35638 -0.93105 0.07835 -0.49176 -0.86856 0.06141 -0.60457 -0.79365 0.06788 -0.38872 -0.91905 0.06515 -0.50811 -0.85814 0.07369 -0.68882 -0.72016 0.08305 -0.58579 -0.80648 0.08025 -0.66255 -0.74185 0.10335 -0.78791 -0.60683 0.10463 -0.76748 -0.63009 0.11818 -0.58975 -0.79824 0.12249 -0.50168 -0.85686 0.11877 -0.50110 -0.85726 0.11834 -0.35537 -0.92771 0.11432 -0.58747 -0.79970 0.12390 -0.66384 -0.73668 0.12890 -0.77086 -0.62291 0.13326 -0.67093 -0.73109 0.12396 -0.36416 -0.92284 0.12548 -0.49759 -0.85543 0.14368 -0.58832 -0.79513 0.14714 -0.48921 -0.86128 0.13739 -0.34847 -0.92739 0.13608 -0.59586 -0.79038 0.14231 -0.67103 -0.72634 0.14886 -0.77873 -0.61514 0.12322 -0.79949 -0.58245 0.14687 -0.69421 -0.70748 0.13245 -0.59586 -0.79039 0.14224 -0.48920 -0.86127 0.13750 -0.34903 -0.93002 0.11504 -0.48077 -0.86705 0.13075 -0.31946 -0.93891 0.12806 -0.60576 -0.78404 0.13542 -0.69385 -0.70563 0.14372 -0.71707 -0.68553 0.12589 -0.79844 -0.58607 0.13791 -0.60650 -0.78777 0.10763 -0.48346 -0.86963 0.10007 -0.34769 -0.93308 0.09203 -0.48080 -0.87136 0.09780 -0.81869 -0.56324 0.11184 -0.61399 -0.78268 0.10210 -0.71775 -0.68733 0.11142 -0.73035 -0.67561 0.10075 -0.81854 -0.56354 0.11144 -0.31376 -0.94890 0.03382 -0.83204 -0.54949 0.07596 -0.61532 -0.78735 0.03828 -0.49664 -0.86705 -0.03972 -0.48479 -0.87424 -0.02599 -0.73242 -0.68062 0.01788 -0.76038 -0.64925 -0.01717 -0.99897 -0.02277 -0.03915 -0.99986 -0.01475 0.00849 -0.98375 -0.17861 0.01813 -0.99685 0.01506 -0.07784 -0.98943 -0.13338 0.05683 -0.97592 -0.21175 -0.05236 -0.92437 -0.37496 0.07034 -0.97187 -0.23444 -0.02237 -0.99013 -0.13632 0.03244 -0.97395 -0.21417 0.07446 -0.92371 -0.37938 0.05321 -0.97228 -0.21198 0.09871 -0.89409 -0.43290 0.11490 -0.96519 -0.23621 0.11231 -0.89489 -0.43069 0.11693 -0.88674 -0.44327 0.13118 -0.96207 -0.23408 0.14010 -0.96356 -0.22934 0.13766 -0.88968 -0.43458 0.14006 -0.89990 -0.41813 0.12388 -0.96340 -0.22926 0.13894 -0.96794 -0.21402 0.13148 -0.90059 -0.41583 0.12656 -0.91393 -0.39734 0.08277 -0.91458 -0.39600 0.08208 -0.97224 -0.21562 0.09088 -0.96454 -0.24231 0.10462 -0.98159 -0.00743 -0.19084 -0.98281 -0.00152 -0.18459 -0.98795 -0.04629 -0.14768 -0.99234 -0.00253 -0.12354 -0.99420 -0.03119 -0.10292 -0.99389 0.00000 -0.11040 -0.99412 0.02896 -0.10430 -0.99299 0.00268 -0.11817 -0.98795 0.04626 -0.14768 + + + + + + + + + + + + + + +

631 0 0 0 632 0 1 1 0 1 631 1 2 2 0 2 1 2 3 3 2 3 1 3 3 4 4 4 5 4 2 5 3 5 5 5 6 6 4 6 3 6 631 7 625 7 1 7 1 8 7 8 3 8 7 9 1 9 625 9 8 10 3 10 7 10 3 11 8 11 6 11 9 12 6 12 8 12 625 13 622 13 7 13 7 14 10 14 8 14 10 15 7 15 622 15 11 16 8 16 10 16 8 17 11 17 9 17 12 18 9 18 11 18 622 19 619 19 10 19 13 20 10 20 619 20 10 21 13 21 11 21 11 22 14 22 12 22 14 23 11 23 13 23 15 24 12 24 14 24 619 25 616 25 13 25 13 26 16 26 14 26 16 27 13 27 616 27 17 28 14 28 16 28 17 29 18 29 15 29 14 30 17 30 15 30 19 31 18 31 17 31 616 32 20 32 16 32 21 33 16 33 20 33 16 34 21 34 17 34 23 35 22 35 19 35 17 36 23 36 19 36 17 37 21 37 23 37 24 38 22 38 23 38 25 39 5 39 26 39 27 40 25 40 26 40 30 41 28 41 29 41 25 42 30 42 29 42 30 43 25 43 27 43 5 44 4 44 26 44 31 45 29 45 28 45 32 46 26 46 4 46 26 47 32 47 27 47 33 48 27 48 32 48 27 49 33 49 30 49 4 50 6 50 32 50 34 51 28 51 30 51 28 52 34 52 31 52 30 53 35 53 34 53 35 54 30 54 33 54 36 55 32 55 6 55 32 56 36 56 33 56 37 57 33 57 36 57 33 58 37 58 35 58 34 59 38 59 31 59 38 60 34 60 35 60 39 61 31 61 38 61 35 62 40 62 38 62 40 63 35 63 37 63 36 64 41 64 37 64 41 65 36 65 6 65 6 66 9 66 41 66 42 67 37 67 41 67 37 68 42 68 40 68 38 69 43 69 39 69 43 70 38 70 40 70 44 71 40 71 42 71 40 72 44 72 43 72 45 73 39 73 43 73 41 74 46 74 42 74 46 75 41 75 9 75 47 76 42 76 46 76 42 77 47 77 44 77 43 78 48 78 45 78 48 79 43 79 44 79 44 80 49 80 48 80 49 81 44 81 47 81 46 82 9 82 12 82 50 83 46 83 12 83 46 84 50 84 47 84 47 85 51 85 49 85 51 86 47 86 50 86 52 87 48 87 49 87 48 88 52 88 45 88 53 89 49 89 51 89 49 90 53 90 52 90 54 91 45 91 52 91 50 92 55 92 51 92 55 93 50 93 12 93 51 94 56 94 53 94 56 95 51 95 55 95 52 96 57 96 54 96 57 97 52 97 53 97 58 98 53 98 56 98 53 99 58 99 57 99 59 100 54 100 57 100 55 101 12 101 15 101 60 102 55 102 15 102 55 103 60 103 56 103 56 104 61 104 58 104 61 105 56 105 60 105 62 106 57 106 58 106 57 107 62 107 59 107 58 108 63 108 62 108 63 109 58 109 61 109 15 110 18 110 60 110 64 111 60 111 18 111 60 112 64 112 61 112 61 113 65 113 63 113 65 114 61 114 64 114 66 115 62 115 63 115 66 116 67 116 59 116 62 117 66 117 59 117 68 118 63 118 65 118 63 119 68 119 66 119 18 120 19 120 64 120 64 121 69 121 65 121 69 122 64 122 19 122 65 123 70 123 68 123 70 124 65 124 69 124 71 125 72 125 67 125 66 126 71 126 67 126 71 127 66 127 68 127 73 128 68 128 70 128 68 129 73 129 71 129 19 130 22 130 69 130 74 131 69 131 22 131 74 132 75 132 70 132 69 133 74 133 70 133 76 134 72 134 71 134 70 135 75 135 73 135 22 136 24 136 74 136 71 137 73 137 77 137 71 138 77 138 76 138 78 139 77 139 73 139 78 140 73 140 75 140 79 141 78 141 75 141 83 142 29 142 31 142 83 143 81 143 82 143 29 144 83 144 82 144 84 145 82 145 81 145 84 146 85 146 86 146 84 147 86 147 82 147 87 148 85 148 84 148 31 149 39 149 83 149 81 150 88 150 84 150 88 151 81 151 83 151 89 152 83 152 39 152 83 153 89 153 88 153 84 154 90 154 87 154 90 155 84 155 88 155 91 156 87 156 90 156 88 157 92 157 90 157 92 158 88 158 89 158 89 159 39 159 45 159 93 160 89 160 45 160 89 161 93 161 92 161 90 162 94 162 91 162 94 163 90 163 92 163 95 164 91 164 94 164 45 165 54 165 93 165 92 166 96 166 94 166 96 167 92 167 93 167 93 168 97 168 96 168 97 169 93 169 54 169 98 170 94 170 96 170 94 171 98 171 95 171 99 172 95 172 98 172 54 173 59 173 97 173 96 174 100 174 98 174 100 175 96 175 97 175 97 176 101 176 100 176 101 177 97 177 59 177 98 178 102 178 99 178 102 179 98 179 100 179 103 180 99 180 102 180 59 181 67 181 101 181 100 182 104 182 102 182 104 183 100 183 101 183 101 184 105 184 104 184 105 185 101 185 67 185 106 186 107 186 103 186 102 187 106 187 103 187 106 188 102 188 104 188 67 189 72 189 105 189 108 190 107 190 106 190 104 191 109 191 106 191 109 192 104 192 105 192 110 193 109 193 105 193 110 194 105 194 72 194 106 195 109 195 108 195 72 196 76 196 110 196 111 197 108 197 109 197 113 198 114 198 112 198 115 199 113 199 112 199 86 200 85 200 116 200 118 201 114 201 113 201 119 202 113 202 115 202 113 203 119 203 118 203 115 204 120 204 119 204 120 205 115 205 117 205 121 206 116 206 85 206 116 207 121 207 117 207 117 208 122 208 120 208 122 209 117 209 121 209 123 210 119 210 120 210 119 211 123 211 118 211 120 212 124 212 123 212 124 213 120 213 122 213 121 214 125 214 122 214 125 215 121 215 85 215 122 216 126 216 124 216 126 217 122 217 125 217 85 218 87 218 125 218 127 219 118 219 123 219 128 220 123 220 124 220 123 221 128 221 127 221 124 222 129 222 128 222 129 223 124 223 126 223 130 224 125 224 87 224 125 225 130 225 126 225 131 226 126 226 130 226 126 227 131 227 129 227 87 228 91 228 130 228 128 229 132 229 127 229 132 230 128 230 129 230 133 231 129 231 131 231 129 232 133 232 132 232 130 233 134 233 131 233 134 234 130 234 91 234 135 235 131 235 134 235 131 236 135 236 133 236 136 237 127 237 132 237 137 238 132 238 133 238 132 239 137 239 136 239 133 240 138 240 137 240 138 241 133 241 135 241 134 242 139 242 135 242 139 243 134 243 91 243 140 244 135 244 139 244 135 245 140 245 138 245 91 246 95 246 139 246 137 247 141 247 136 247 141 248 137 248 138 248 142 249 136 249 141 249 138 250 143 250 141 250 143 251 138 251 140 251 144 252 139 252 95 252 139 253 144 253 140 253 145 254 140 254 144 254 140 255 145 255 143 255 95 256 99 256 144 256 146 257 141 257 143 257 141 258 146 258 142 258 143 259 147 259 146 259 147 260 143 260 145 260 144 261 148 261 145 261 148 262 144 262 99 262 149 263 145 263 148 263 145 264 149 264 147 264 150 265 142 265 146 265 146 266 151 266 150 266 151 267 146 267 147 267 147 268 152 268 151 268 152 269 147 269 149 269 148 270 153 270 149 270 148 271 99 271 103 271 153 272 148 272 103 272 154 273 149 273 153 273 149 274 154 274 152 274 155 275 151 275 152 275 155 276 156 276 150 276 151 277 155 277 150 277 152 278 157 278 155 278 157 279 152 279 154 279 153 280 103 280 107 280 158 281 153 281 107 281 153 282 158 282 154 282 154 283 159 283 157 283 159 284 154 284 158 284 160 285 156 285 155 285 155 286 161 286 160 286 161 287 155 287 157 287 157 288 162 288 161 288 162 289 157 289 159 289 158 290 163 290 159 290 158 291 107 291 108 291 163 292 158 292 108 292 164 293 159 293 163 293 159 294 164 294 162 294 161 295 162 295 165 295 165 296 166 296 160 296 161 297 165 297 160 297 167 298 162 298 164 298 167 299 165 299 162 299 108 300 111 300 163 300 168 301 163 301 111 301 163 302 168 302 164 302 164 303 169 303 167 303 164 304 168 304 169 304 170 305 167 305 169 305 171 306 462 306 172 306 463 307 462 307 171 307 173 308 171 308 172 308 114 309 173 309 172 309 173 310 114 310 118 310 118 311 127 311 173 311 174 312 171 312 173 312 171 313 174 313 463 313 175 314 463 314 174 314 173 315 176 315 174 315 176 316 173 316 127 316 127 317 136 317 176 317 177 318 174 318 176 318 174 319 177 319 175 319 178 320 175 320 177 320 176 321 179 321 177 321 179 322 176 322 136 322 136 323 142 323 179 323 180 324 177 324 179 324 177 325 180 325 178 325 181 326 178 326 180 326 179 327 182 327 180 327 182 328 179 328 142 328 142 329 150 329 182 329 180 330 183 330 181 330 183 331 180 331 182 331 184 332 181 332 183 332 182 333 185 333 183 333 182 334 150 334 156 334 185 335 182 335 156 335 156 336 160 336 185 336 183 337 186 337 184 337 186 338 183 338 185 338 187 339 185 339 160 339 187 340 186 340 185 340 160 341 166 341 187 341 454 342 172 342 462 342 190 343 114 343 172 343 190 344 172 344 454 344 191 345 112 345 114 345 191 346 114 346 190 346 112 347 192 347 86 347 192 348 112 348 191 348 86 349 193 349 82 349 193 350 86 350 192 350 454 351 450 351 190 351 194 352 190 352 450 352 190 353 194 353 191 353 191 354 195 354 192 354 195 355 191 355 194 355 196 356 192 356 195 356 192 357 196 357 193 357 193 358 197 358 82 358 197 359 193 359 196 359 450 360 446 360 194 360 198 361 194 361 446 361 194 362 198 362 195 362 199 363 195 363 198 363 195 364 199 364 196 364 200 365 196 365 199 365 196 366 200 366 197 366 201 367 197 367 200 367 197 368 201 368 82 368 446 369 442 369 198 369 202 370 198 370 442 370 198 371 202 371 199 371 203 372 199 372 202 372 199 373 203 373 200 373 200 374 204 374 201 374 204 375 200 375 203 375 201 376 205 376 82 376 205 377 201 377 204 377 442 378 438 378 202 378 206 379 202 379 438 379 202 380 206 380 203 380 207 381 203 381 206 381 203 382 207 382 204 382 208 383 204 383 207 383 204 384 208 384 205 384 209 385 205 385 208 385 205 386 209 386 82 386 438 387 434 387 206 387 210 388 206 388 434 388 206 389 210 389 207 389 207 390 211 390 208 390 211 391 207 391 210 391 212 392 208 392 211 392 208 393 212 393 209 393 209 394 213 394 82 394 213 395 209 395 212 395 434 396 430 396 210 396 214 397 210 397 430 397 210 398 214 398 211 398 211 399 215 399 212 399 215 400 211 400 214 400 216 401 212 401 215 401 212 402 216 402 213 402 217 403 213 403 216 403 213 404 217 404 82 404 430 405 426 405 214 405 214 406 218 406 215 406 218 407 214 407 426 407 215 408 219 408 216 408 219 409 215 409 218 409 220 410 216 410 219 410 216 411 220 411 217 411 221 412 217 412 220 412 217 413 221 413 82 413 426 414 632 414 218 414 632 415 0 415 218 415 219 416 5 416 220 416 221 417 25 417 29 417 82 418 221 418 29 418 25 419 220 419 5 419 220 420 25 420 221 420 222 421 223 421 224 421 225 422 222 422 224 422 422 423 224 423 223 423 226 424 224 424 422 424 422 425 419 425 226 425 227 426 226 426 419 426 419 427 418 427 227 427 228 428 227 428 418 428 418 429 417 429 228 429 229 430 228 430 417 430 417 431 416 431 229 431 230 432 229 432 416 432 416 433 415 433 230 433 231 434 230 434 415 434 415 435 414 435 231 435 232 436 231 436 414 436 414 437 413 437 232 437 233 438 232 438 413 438 413 439 412 439 233 439 234 440 233 440 412 440 412 441 411 441 234 441 235 442 234 442 411 442 411 443 410 443 235 443 236 444 235 444 410 444 410 445 409 445 236 445 237 446 236 446 409 446 409 447 408 447 237 447 238 448 237 448 408 448 408 449 407 449 238 449 239 450 238 450 407 450 407 451 406 451 239 451 240 452 239 452 406 452 406 453 405 453 240 453 240 454 405 454 188 454 240 455 188 455 241 455 240 456 241 456 189 456 240 457 189 457 80 457 242 458 240 458 80 458 244 459 225 459 224 459 245 460 244 460 224 460 247 461 246 461 245 461 224 462 226 462 245 462 245 463 226 463 227 463 248 464 245 464 227 464 248 465 249 465 247 465 245 466 248 466 247 466 250 467 249 467 248 467 227 468 228 468 248 468 251 469 252 469 250 469 248 470 251 470 250 470 251 471 248 471 228 471 228 472 229 472 251 472 253 473 252 473 251 473 251 474 229 474 230 474 254 475 251 475 230 475 251 476 254 476 253 476 255 477 253 477 254 477 230 478 231 478 254 478 254 479 231 479 232 479 256 480 254 480 232 480 256 481 257 481 255 481 254 482 256 482 255 482 232 483 233 483 256 483 258 484 257 484 256 484 256 485 233 485 234 485 259 486 256 486 234 486 259 487 260 487 258 487 256 488 259 488 258 488 234 489 235 489 259 489 261 490 260 490 259 490 259 491 235 491 236 491 262 492 259 492 236 492 259 493 262 493 261 493 263 494 261 494 262 494 236 495 237 495 262 495 264 496 265 496 263 496 262 497 264 497 263 497 264 498 262 498 237 498 237 499 238 499 264 499 266 500 265 500 264 500 267 501 268 501 266 501 264 502 267 502 266 502 264 503 238 503 239 503 267 504 264 504 239 504 239 505 240 505 267 505 269 506 268 506 267 506 267 507 242 507 269 507 267 508 240 508 242 508 270 509 269 509 242 509 79 510 243 510 271 510 246 511 271 511 243 511 272 512 271 512 246 512 246 513 247 513 272 513 273 514 272 514 247 514 247 515 249 515 273 515 274 516 273 516 249 516 249 517 250 517 274 517 274 518 250 518 252 518 275 519 274 519 252 519 252 520 253 520 275 520 276 521 275 521 253 521 253 522 255 522 276 522 277 523 276 523 255 523 255 524 257 524 277 524 278 525 277 525 257 525 257 526 258 526 278 526 279 527 278 527 258 527 258 528 260 528 279 528 280 529 279 529 260 529 260 530 261 530 280 530 281 531 280 531 261 531 261 532 263 532 281 532 281 533 263 533 265 533 282 534 281 534 265 534 265 535 266 535 282 535 283 536 282 536 266 536 266 537 268 537 283 537 284 538 283 538 268 538 268 539 269 539 284 539 285 540 284 540 269 540 269 541 270 541 285 541 285 542 270 542 286 542 284 543 285 543 287 543 288 544 289 544 290 544 288 545 290 545 287 545 288 546 287 546 285 546 285 547 286 547 288 547 291 548 289 548 288 548 288 549 292 549 291 549 288 550 286 550 292 550 293 551 291 551 292 551 294 552 293 552 292 552 292 553 168 553 294 553 294 554 168 554 295 554 297 555 295 555 296 555 300 556 299 556 298 556 298 557 301 557 300 557 302 558 300 558 301 558 301 559 303 559 302 559 304 560 302 560 303 560 79 561 271 561 303 561 303 562 271 562 272 562 303 563 272 563 305 563 303 564 305 564 304 564 306 565 304 565 305 565 297 566 299 566 295 566 294 567 295 567 299 567 299 568 300 568 294 568 293 569 294 569 300 569 300 570 302 570 293 570 291 571 293 571 302 571 302 572 304 572 291 572 289 573 291 573 304 573 304 574 306 574 289 574 290 575 289 575 306 575 306 576 307 576 290 576 308 577 290 577 307 577 307 578 309 578 308 578 310 579 308 579 309 579 309 580 311 580 310 580 312 581 310 581 311 581 311 582 313 582 312 582 314 583 312 583 313 583 313 584 315 584 314 584 316 585 314 585 315 585 272 586 273 586 305 586 317 587 305 587 273 587 317 588 307 588 306 588 317 589 306 589 305 589 273 590 274 590 317 590 309 591 307 591 317 591 318 592 311 592 309 592 317 593 318 593 309 593 317 594 274 594 275 594 318 595 317 595 275 595 275 596 276 596 318 596 313 597 311 597 318 597 318 598 276 598 277 598 319 599 318 599 277 599 318 600 319 600 313 600 315 601 313 601 319 601 277 602 278 602 319 602 320 603 319 603 278 603 320 604 316 604 315 604 319 605 320 605 315 605 278 606 279 606 320 606 314 607 316 607 320 607 320 608 279 608 280 608 321 609 320 609 280 609 320 610 321 610 314 610 312 611 314 611 321 611 280 612 281 612 321 612 322 613 310 613 312 613 321 614 322 614 312 614 321 615 281 615 282 615 322 616 321 616 282 616 308 617 310 617 322 617 282 618 283 618 322 618 322 619 283 619 284 619 322 620 284 620 287 620 322 621 287 621 308 621 290 622 308 622 287 622 167 623 270 623 242 623 242 624 165 624 167 624 170 625 286 625 270 625 170 626 270 626 167 626 292 627 286 627 170 627 168 628 292 628 170 628 168 629 111 629 295 629 170 630 169 630 168 630 301 631 298 631 303 631 78 632 303 632 298 632 303 633 78 633 79 633 297 634 76 634 298 634 298 635 77 635 78 635 298 636 76 636 77 636 75 637 243 637 79 637 24 638 225 638 244 638 244 639 74 639 24 639 74 640 244 640 243 640 243 641 75 641 74 641 225 642 24 642 222 642 186 643 241 643 188 643 186 644 187 644 241 644 187 645 189 645 241 645 166 646 189 646 187 646 80 647 189 647 166 647 80 648 166 648 165 648 80 649 165 649 242 649 109 650 295 650 111 650 109 651 296 651 295 651 109 652 110 652 296 652 76 653 296 653 110 653 76 654 297 654 296 654 297 655 298 655 299 655 244 656 245 656 246 656 243 657 244 657 246 657 5 658 219 658 218 658 2 659 5 659 218 659 0 660 2 660 218 660 86 661 117 661 112 661 112 662 117 662 115 662 86 663 116 663 117 663 548 664 517 664 518 664 522 665 519 665 517 665 548 666 522 666 517 666 632 667 426 667 630 667 630 668 426 668 627 668 627 669 426 669 425 669 402 670 399 670 401 670 401 671 399 671 400 671 348 672 346 672 347 672 558 673 349 673 348 673 558 674 524 674 349 674 525 675 349 675 524 675 525 676 350 676 349 676 525 677 523 677 350 677 554 678 403 678 469 678 554 679 469 679 468 679 554 680 468 680 455 680 468 681 456 681 455 681 456 682 404 682 455 682 186 683 404 683 456 683 186 684 188 684 404 684 420 685 421 685 610 685 402 686 560 686 559 686 560 687 402 687 401 687 401 688 610 688 560 688 610 689 401 689 420 689 559 690 555 690 402 690 347 691 557 691 558 691 347 692 556 692 557 692 348 693 347 693 558 693 342 694 555 694 556 694 556 695 347 695 342 695 344 696 342 696 347 696 464 697 466 697 465 697 466 698 350 698 523 698 466 699 464 699 353 699 353 700 464 700 359 700 464 701 467 701 375 701 464 702 375 702 359 702 403 703 467 703 469 703 467 704 403 704 375 704 355 705 358 705 337 705 323 706 337 706 358 706 323 707 358 707 361 707 323 708 361 708 362 708 363 709 323 709 362 709 337 710 323 710 335 710 323 711 363 711 324 711 324 712 363 712 364 712 324 713 333 713 323 713 323 714 333 714 335 714 365 715 324 715 364 715 333 716 324 716 331 716 325 717 331 717 324 717 324 718 365 718 325 718 325 719 365 719 366 719 331 720 325 720 329 720 367 721 325 721 366 721 326 722 330 722 325 722 325 723 330 723 329 723 325 724 367 724 326 724 368 725 326 725 367 725 330 726 326 726 332 726 327 727 332 727 326 727 326 728 368 728 327 728 327 729 368 729 369 729 332 730 327 730 334 730 370 731 327 731 369 731 327 732 370 732 328 732 328 733 370 733 371 733 328 734 336 734 327 734 327 735 336 735 334 735 336 736 328 736 338 736 372 737 328 737 371 737 328 738 340 738 339 738 328 739 339 739 338 739 328 740 372 740 340 740 373 741 340 741 372 741 329 742 330 742 331 742 332 743 331 743 330 743 331 744 332 744 333 744 334 745 333 745 332 745 333 746 334 746 335 746 336 747 335 747 334 747 335 748 336 748 337 748 338 749 337 749 336 749 337 750 338 750 355 750 339 751 355 751 338 751 355 752 339 752 356 752 341 753 356 753 339 753 356 754 341 754 354 754 343 755 354 755 341 755 354 756 343 756 352 756 345 757 352 757 343 757 352 758 345 758 351 758 346 759 351 759 345 759 351 760 346 760 350 760 348 761 350 761 346 761 339 762 340 762 341 762 342 763 341 763 340 763 342 764 340 764 373 764 342 765 373 765 374 765 555 766 342 766 374 766 341 767 342 767 343 767 344 768 343 768 342 768 343 769 344 769 345 769 347 770 345 770 344 770 345 771 347 771 346 771 348 772 349 772 350 772 351 773 350 773 466 773 353 774 351 774 466 774 351 775 353 775 352 775 352 776 353 776 354 776 357 777 353 777 359 777 357 778 354 778 353 778 354 779 357 779 356 779 360 780 357 780 359 780 357 781 360 781 358 781 357 782 358 782 355 782 357 783 355 783 356 783 361 784 358 784 360 784 360 785 359 785 375 785 376 786 360 786 375 786 360 787 376 787 361 787 377 788 361 788 376 788 361 789 377 789 362 789 379 790 362 790 377 790 362 791 379 791 363 791 380 792 363 792 379 792 363 793 380 793 364 793 364 794 380 794 382 794 384 795 364 795 382 795 364 796 384 796 365 796 385 797 365 797 384 797 365 798 385 798 366 798 387 799 366 799 385 799 366 800 387 800 367 800 388 801 367 801 387 801 367 802 388 802 368 802 390 803 368 803 388 803 368 804 390 804 369 804 392 805 369 805 390 805 369 806 392 806 370 806 393 807 370 807 392 807 370 808 393 808 371 808 371 809 393 809 395 809 396 810 371 810 395 810 371 811 396 811 372 811 398 812 372 812 396 812 372 813 398 813 373 813 399 814 373 814 398 814 373 815 399 815 374 815 399 816 402 816 374 816 555 817 374 817 402 817 375 818 403 818 376 818 378 819 403 819 405 819 378 820 376 820 403 820 376 821 378 821 377 821 406 822 378 822 405 822 378 823 406 823 381 823 381 824 406 824 407 824 381 825 379 825 378 825 378 826 379 826 377 826 379 827 381 827 380 827 408 828 381 828 407 828 381 829 408 829 383 829 383 830 382 830 381 830 381 831 382 831 380 831 409 832 383 832 408 832 382 833 383 833 384 833 386 834 384 834 383 834 383 835 409 835 386 835 386 836 409 836 410 836 384 837 386 837 385 837 411 838 386 838 410 838 389 839 387 839 386 839 386 840 387 840 385 840 386 841 411 841 389 841 389 842 411 842 412 842 387 843 389 843 388 843 413 844 389 844 412 844 391 845 390 845 389 845 389 846 390 846 388 846 389 847 413 847 391 847 391 848 413 848 414 848 415 849 391 849 414 849 390 850 391 850 392 850 394 851 392 851 391 851 391 852 415 852 394 852 394 853 415 853 416 853 392 854 394 854 393 854 417 855 394 855 416 855 394 856 417 856 397 856 397 857 395 857 394 857 394 858 395 858 393 858 418 859 397 859 417 859 395 860 397 860 396 860 400 861 398 861 397 861 397 862 398 862 396 862 397 863 418 863 400 863 400 864 418 864 419 864 422 865 400 865 419 865 398 866 400 866 399 866 400 867 422 867 401 867 401 868 422 868 420 868 403 869 554 869 405 869 405 870 554 870 455 870 405 871 455 871 404 871 405 872 404 872 188 872 424 873 423 873 609 873 609 874 627 874 424 874 552 875 605 875 423 875 423 876 605 876 609 876 425 877 424 877 627 877 427 878 552 878 423 878 423 879 424 879 427 879 428 880 427 880 424 880 424 881 425 881 428 881 425 882 426 882 429 882 429 883 428 883 425 883 430 884 429 884 426 884 431 885 552 885 427 885 427 886 428 886 431 886 432 887 431 887 428 887 428 888 429 888 432 888 429 889 430 889 433 889 433 890 432 890 429 890 434 891 433 891 430 891 431 892 432 892 435 892 435 893 552 893 431 893 436 894 435 894 432 894 432 895 433 895 436 895 433 896 434 896 437 896 437 897 436 897 433 897 438 898 437 898 434 898 439 899 552 899 435 899 435 900 436 900 439 900 440 901 439 901 436 901 436 902 437 902 440 902 441 903 440 903 437 903 437 904 438 904 441 904 442 905 441 905 438 905 439 906 440 906 443 906 443 907 552 907 439 907 440 908 441 908 444 908 444 909 443 909 440 909 445 910 444 910 441 910 441 911 442 911 445 911 446 912 445 912 442 912 447 913 552 913 443 913 443 914 444 914 447 914 448 915 447 915 444 915 444 916 445 916 448 916 449 917 448 917 445 917 445 918 446 918 449 918 450 919 449 919 446 919 447 920 448 920 451 920 451 921 552 921 447 921 452 922 451 922 448 922 448 923 449 923 452 923 449 924 450 924 453 924 453 925 452 925 449 925 454 926 453 926 450 926 451 927 452 927 548 927 548 928 552 928 451 928 452 929 453 929 522 929 522 930 548 930 452 930 453 931 454 931 520 931 453 932 520 932 522 932 454 933 462 933 520 933 474 934 456 934 468 934 456 935 457 935 186 935 456 936 474 936 457 936 186 937 457 937 184 937 478 938 457 938 474 938 457 939 478 939 458 939 458 940 478 940 484 940 458 941 184 941 457 941 184 942 458 942 181 942 492 943 458 943 484 943 458 944 492 944 459 944 459 945 181 945 458 945 181 946 459 946 178 946 498 947 459 947 492 947 459 948 498 948 460 948 460 949 178 949 459 949 178 950 460 950 175 950 507 951 460 951 498 951 460 952 507 952 461 952 461 953 175 953 460 953 175 954 461 954 463 954 516 955 461 955 507 955 461 956 516 956 520 956 520 957 462 957 461 957 461 958 462 958 463 958 464 959 465 959 467 959 470 960 465 960 466 960 470 961 467 961 465 961 471 962 470 962 466 962 466 963 523 963 471 963 526 964 471 964 523 964 467 965 472 965 469 965 467 966 470 966 472 966 473 967 474 967 469 967 469 968 474 968 468 968 473 969 469 969 472 969 475 970 472 970 470 970 470 971 471 971 475 971 471 972 526 972 476 972 476 973 526 973 527 973 476 974 475 974 471 974 472 975 475 975 477 975 477 976 473 976 472 976 473 977 477 977 479 977 479 978 474 978 473 978 474 979 479 979 478 979 475 980 476 980 480 980 480 981 477 981 475 981 481 982 480 982 476 982 476 983 527 983 481 983 481 984 527 984 531 984 477 985 480 985 482 985 482 986 479 986 477 986 483 987 484 987 479 987 479 988 484 988 478 988 479 989 482 989 483 989 485 990 482 990 480 990 480 991 481 991 485 991 481 992 531 992 486 992 486 993 531 993 535 993 486 994 485 994 481 994 482 995 485 995 487 995 487 996 483 996 482 996 483 997 487 997 488 997 488 998 484 998 483 998 484 999 488 999 492 999 489 1000 487 1000 485 1000 485 1001 486 1001 489 1001 486 1002 535 1002 490 1002 490 1003 489 1003 486 1003 487 1004 489 1004 491 1004 491 1005 488 1005 487 1005 493 1006 492 1006 488 1006 488 1007 491 1007 493 1007 539 1008 490 1008 535 1008 494 1009 491 1009 489 1009 489 1010 490 1010 494 1010 495 1011 494 1011 490 1011 490 1012 539 1012 495 1012 491 1013 494 1013 496 1013 496 1014 493 1014 491 1014 492 1015 493 1015 498 1015 493 1016 496 1016 497 1016 497 1017 498 1017 493 1017 543 1018 495 1018 539 1018 499 1019 496 1019 494 1019 494 1020 495 1020 499 1020 495 1021 543 1021 500 1021 500 1022 499 1022 495 1022 496 1023 499 1023 501 1023 501 1024 497 1024 496 1024 502 1025 498 1025 497 1025 497 1026 501 1026 502 1026 498 1027 502 1027 507 1027 503 1028 501 1028 499 1028 499 1029 500 1029 503 1029 500 1030 543 1030 504 1030 504 1031 503 1031 500 1031 505 1032 502 1032 501 1032 501 1033 503 1033 505 1033 502 1034 505 1034 506 1034 506 1035 507 1035 502 1035 547 1036 504 1036 543 1036 508 1037 505 1037 503 1037 503 1038 504 1038 508 1038 509 1039 508 1039 504 1039 504 1040 547 1040 509 1040 505 1041 508 1041 510 1041 510 1042 506 1042 505 1042 511 1043 507 1043 506 1043 506 1044 510 1044 511 1044 507 1045 511 1045 516 1045 549 1046 509 1046 547 1046 508 1047 509 1047 512 1047 512 1048 510 1048 508 1048 509 1049 549 1049 513 1049 513 1050 512 1050 509 1050 510 1051 512 1051 514 1051 514 1052 511 1052 510 1052 515 1053 516 1053 511 1053 511 1054 514 1054 515 1054 512 1055 513 1055 517 1055 517 1056 514 1056 512 1056 518 1057 517 1057 513 1057 513 1058 549 1058 518 1058 514 1059 517 1059 519 1059 519 1060 515 1060 514 1060 521 1061 516 1061 515 1061 515 1062 519 1062 521 1062 516 1063 521 1063 520 1063 548 1064 518 1064 549 1064 519 1065 522 1065 521 1065 521 1066 522 1066 520 1066 523 1067 525 1067 526 1067 562 1068 524 1068 558 1068 528 1069 526 1069 525 1069 524 1070 562 1070 529 1070 524 1071 529 1071 525 1071 525 1072 529 1072 530 1072 530 1073 528 1073 525 1073 526 1074 528 1074 527 1074 567 1075 529 1075 562 1075 528 1076 530 1076 532 1076 532 1077 531 1077 528 1077 528 1078 531 1078 527 1078 529 1079 567 1079 533 1079 533 1080 530 1080 529 1080 530 1081 533 1081 534 1081 534 1082 532 1082 530 1082 575 1083 533 1083 567 1083 531 1084 532 1084 535 1084 532 1085 534 1085 536 1085 536 1086 535 1086 532 1086 533 1087 575 1087 537 1087 537 1088 534 1088 533 1088 534 1089 537 1089 538 1089 538 1090 536 1090 534 1090 580 1091 537 1091 575 1091 535 1092 536 1092 539 1092 540 1093 539 1093 536 1093 536 1094 538 1094 540 1094 537 1095 580 1095 541 1095 541 1096 538 1096 537 1096 538 1097 541 1097 542 1097 542 1098 540 1098 538 1098 589 1099 541 1099 580 1099 539 1100 540 1100 543 1100 540 1101 542 1101 544 1101 544 1102 543 1102 540 1102 545 1103 542 1103 541 1103 541 1104 589 1104 545 1104 545 1105 589 1105 595 1105 542 1106 545 1106 546 1106 546 1107 544 1107 542 1107 543 1108 544 1108 547 1108 544 1109 546 1109 550 1109 550 1110 547 1110 544 1110 551 1111 546 1111 545 1111 545 1112 595 1112 551 1112 546 1113 551 1113 553 1113 553 1114 550 1114 546 1114 603 1115 551 1115 595 1115 547 1116 550 1116 549 1116 550 1117 552 1117 548 1117 550 1118 548 1118 549 1118 550 1119 553 1119 552 1119 605 1120 552 1120 551 1120 551 1121 552 1121 553 1121 551 1122 603 1122 605 1122 555 1123 559 1123 556 1123 556 1124 559 1124 561 1124 556 1125 561 1125 557 1125 563 1126 558 1126 557 1126 563 1127 557 1127 561 1127 611 1128 560 1128 610 1128 564 1129 561 1129 559 1129 558 1130 563 1130 562 1130 565 1131 564 1131 560 1131 560 1132 564 1132 559 1132 560 1133 611 1133 565 1133 613 1134 565 1134 611 1134 566 1135 563 1135 561 1135 561 1136 564 1136 566 1136 563 1137 566 1137 568 1137 568 1138 567 1138 563 1138 563 1139 567 1139 562 1139 564 1140 565 1140 569 1140 569 1141 566 1141 564 1141 565 1142 613 1142 570 1142 570 1143 569 1143 565 1143 614 1144 570 1144 613 1144 571 1145 568 1145 566 1145 566 1146 569 1146 571 1146 572 1147 575 1147 568 1147 568 1148 575 1148 567 1148 568 1149 571 1149 572 1149 569 1150 570 1150 573 1150 573 1151 571 1151 569 1151 574 1152 573 1152 570 1152 570 1153 614 1153 574 1153 617 1154 574 1154 614 1154 571 1155 573 1155 576 1155 576 1156 572 1156 571 1156 577 1157 575 1157 572 1157 572 1158 576 1158 577 1158 573 1159 574 1159 578 1159 578 1160 576 1160 573 1160 579 1161 578 1161 574 1161 574 1162 617 1162 579 1162 579 1163 617 1163 620 1163 575 1164 577 1164 580 1164 581 1165 577 1165 576 1165 576 1166 578 1166 581 1166 577 1167 581 1167 582 1167 582 1168 580 1168 577 1168 578 1169 579 1169 583 1169 583 1170 581 1170 578 1170 579 1171 620 1171 584 1171 584 1172 583 1172 579 1172 580 1173 582 1173 589 1173 585 1174 582 1174 581 1174 581 1175 583 1175 585 1175 586 1176 589 1176 582 1176 582 1177 585 1177 586 1177 583 1178 584 1178 587 1178 587 1179 585 1179 583 1179 588 1180 587 1180 584 1180 584 1181 620 1181 588 1181 588 1182 620 1182 623 1182 585 1183 587 1183 590 1183 590 1184 586 1184 585 1184 586 1185 590 1185 591 1185 591 1186 589 1186 586 1186 592 1187 590 1187 587 1187 587 1188 588 1188 592 1188 588 1189 623 1189 593 1189 593 1190 592 1190 588 1190 589 1191 591 1191 595 1191 594 1192 591 1192 590 1192 590 1193 592 1193 594 1193 591 1194 594 1194 596 1194 596 1195 595 1195 591 1195 597 1196 594 1196 592 1196 592 1197 593 1197 597 1197 626 1198 593 1198 623 1198 593 1199 626 1199 598 1199 598 1200 597 1200 593 1200 594 1201 597 1201 599 1201 599 1202 596 1202 594 1202 595 1203 596 1203 603 1203 596 1204 599 1204 600 1204 600 1205 603 1205 596 1205 601 1206 599 1206 597 1206 597 1207 598 1207 601 1207 602 1208 601 1208 598 1208 598 1209 626 1209 602 1209 599 1210 601 1210 604 1210 604 1211 600 1211 599 1211 606 1212 603 1212 600 1212 600 1213 604 1213 606 1213 628 1214 602 1214 626 1214 607 1215 604 1215 601 1215 601 1216 602 1216 607 1216 608 1217 607 1217 602 1217 602 1218 628 1218 608 1218 603 1219 606 1219 605 1219 627 1220 608 1220 628 1220 604 1221 607 1221 609 1221 609 1222 605 1222 604 1222 604 1223 605 1223 606 1223 607 1224 608 1224 609 1224 609 1225 608 1225 627 1225 610 1226 612 1226 611 1226 615 1227 612 1227 20 1227 615 1228 613 1228 612 1228 612 1229 613 1229 611 1229 616 1230 615 1230 20 1230 613 1231 615 1231 614 1231 618 1232 617 1232 615 1232 615 1233 617 1233 614 1233 615 1234 616 1234 618 1234 619 1235 618 1235 616 1235 617 1236 618 1236 620 1236 618 1237 619 1237 621 1237 621 1238 620 1238 618 1238 622 1239 621 1239 619 1239 620 1240 621 1240 623 1240 624 1241 623 1241 621 1241 621 1242 622 1242 624 1242 625 1243 624 1243 622 1243 623 1244 624 1244 626 1244 629 1245 626 1245 624 1245 624 1246 625 1246 629 1246 631 1247 629 1247 625 1247 626 1248 629 1248 628 1248 630 1249 627 1249 629 1249 629 1250 627 1250 628 1250 629 1251 631 1251 630 1251 631 1252 632 1252 630 1252 420 1253 422 1253 421 1253 223 1254 421 1254 422 1254 421 1255 612 1255 610 1255 223 1256 612 1256 421 1256 223 1257 20 1257 612 1257 20 1258 223 1258 21 1258 21 1259 223 1259 23 1259 23 1260 223 1260 222 1260 23 1261 222 1261 24 1261

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_middle/th_middle_E3M5_no_rot_scaled.dae b/URDFs/sr_description/meshes/components/th_middle/th_middle_E3M5_no_rot_scaled.dae new file mode 100644 index 0000000..e03b895 --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_middle/th_middle_E3M5_no_rot_scaled.dae @@ -0,0 +1,210 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T11:08:55 + 2025-02-20T11:08:55 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -10.82211 1.89451 0.02983999 -10.52279 1.19648 4.40604 -10.43772 3.4246 0.02982997 -10.01191 3.485 4.4419 -9.24738 5.4854 3.30954 -9.53206 5.5077 0.02983999 -8.76916 5.5412 6.52921 -9.89934 1.32759 8.782401 -9.34524 3.6126 8.85396 -8.04629 5.5289 11.15913 -9.26471 1.36724 13.15861 -8.71246 3.5727 13.2661 -7.62288 5.2311 15.49638 -8.79618 1.20098 17.53489 -8.362091 3.1253 17.67809 -7.64989 4.795 18.13671 -8.53313 0.8756 21.91118 -8.315771 2.4118 22.09022 -7.82107 4.3186 20.58139 -8.023591 3.9446 22.84329 -8.30538 -0.79062 26.28739 -8.30538 0.70052 26.2874 -8.184041 3.7582 24.93399 -8.28854 1.69868 26.40406 -8.25863 3.8024 26.86291 -7.06228 8.4002 0.02983999 -8.3862 6.9128 2.41682 -7.24683 8.137701 2.46228 -4.47194 9.969901 2.48145 -3.75606 10.294 0.02976 -5.9401 9.1566 2.5098 -2.7584 10.4958 3.62321 -8.073801 6.8946 4.80358 -6.95048 8.0529 4.89452 -4.28569 9.7975 4.93299 -5.69028 9.0101 4.98983 -7.68404 6.864 7.19021 -6.59311 7.9089 7.32682 -4.12086 9.5192 7.38459 -2.57576 10.0953 7.41507 -5.41925 8.7681 7.46987 -7.28799 6.8058 9.57691 -6.23702 7.7394 9.75913 -3.95787 9.2207 9.8362 -5.15147 8.5073 9.949911 -2.40556 9.6421 11.242 -6.95685 6.705 11.9636 -5.94428 7.5776 12.19143 -3.77749 8.9877 12.28781 -4.91141 8.3041 12.42994 -6.7619 6.5466 14.3503 -5.77712 7.457 14.62374 -3.56027 8.9058 14.73935 -4.72338 8.2352 14.90998 -2.13855 9.4329 14.94243 -6.77357 6.3159 16.737 -5.79564 7.4105 17.05605 -3.28867 9.0571 17.19096 -4.6111 8.3722 17.38994 -1.72766 9.643 18.33506 -7.00006 6.0325 19.12369 -5.99731 7.4497 19.48835 -2.99557 9.426301 19.64257 -4.58613 8.6944 19.86998 -7.34378 5.7748 21.5104 -6.30172 7.5607 21.92059 -2.76823 9.8943 22.09418 -1.33429 10.0877 21.40864 -4.64892 9.1002 22.35008 -7.69641 5.627 23.89709 -6.62395 7.7277 24.35296 -2.69618 10.3366 24.54579 -1.13835 10.5183 24.18891 -4.79982 9.4851 24.83005 -7.87334 5.8922 26.22347 -6.92828 7.844 26.71059 -1.22462 10.7964 26.70466 -3.12402 10.54986 26.98725 -5.11937 9.6979 27.34445 -5.42738 9.835801 28.97489 8.61265 5.1336 29.45177 0.06931996 10.8676 3.80621 -0.01023995 11 0.02976995 -1.40119 10.7592 3.81399 1.54101 10.7632 3.81675 2.87009 10.5168 3.5216 3.74599 10.3191 0.02460998 3.0608 10.1082 6.97886 0.26646 10.4441 7.58258 -1.22349 10.3461 7.59807 1.75633 10.3187 7.60365 3.19084 9.6519 10.35776 0.40632 9.9844 11.35896 -1.07563 9.8958 11.38229 1.88615 9.8455 11.39063 3.12557 9.3579 13.61293 0.44521 9.744501 15.13533 -0.89992 9.6718 15.16637 1.78511 9.613901 15.17754 2.77768 9.3812 16.66155 0.34961 9.9357 18.91171 -0.65823 9.889901 18.95053 1.3491 9.8446 18.96453 2.21227 9.7076 19.47371 0.1721299 10.3981 22.68822 -0.46781 10.3808 22.73461 0.80393 10.3594 22.75151 1.66398 10.1414 22.07601 1.30046 10.5367 24.50004 0.6386 10.7885 26.5573 -0.26995 10.7875 26.46785 1.22529 10.7976 26.75026 7.0621 8.4226 0.02480995 8.413451 7.0139 2.18807 9.50643 5.4861 0.02976 7.26406 8.2257 2.23212 4.46815 10.0287 2.2703 5.94975 9.2299 2.2889 9.3264 5.5147 3.95308 8.340411 6.8947 4.35005 7.22057 8.0673 4.43978 4.53342 9.830201 4.51699 5.95696 9.0357 4.55093 8.18244 6.7721 6.5121 7.10496 7.8594 6.64744 4.60456 9.5334 6.76375 5.92833 8.7548 6.81304 9.006441 5.3879 7.87618 7.97886 6.6416 8.67407 6.94847 7.6331 8.855091 4.64917 9.2084 9.01044 5.86525 8.4507 9.07521 7.76899 6.4985 10.83612 6.78223 7.4194 11.06275 4.63475 8.9251 11.25721 5.76895 8.1868 11.33725 8.61378 5.2201 11.68501 7.59222 6.338 12.99817 6.63741 7.2492 13.27048 4.52889 8.7535 13.50389 5.64082 8.0266 13.59928 7.48771 6.1556 15.16022 8.32521 4.9048 15.26346 6.54521 7.1535 15.47806 4.29922 8.763501 15.75065 5.48222 8.0336 15.86139 7.49153 5.9484 17.32228 6.53255 7.1594 17.68572 3.92877 9.0056 17.99735 5.29914 8.250801 18.12349 8.23527 4.4172 18.53411 7.59137 5.7427 19.48432 6.58862 7.2604 19.89338 3.492 9.4169 20.24404 5.12194 8.6197 20.38567 7.73767 5.5867 21.6463 8.2574 3.9578 21.48409 6.6836 7.4326 22.10104 3.09609 9.893401 22.49073 4.98816 9.050001 22.64771 8.283841 3.713 24.13419 7.87952 5.5297 23.80835 6.78704 7.6519 24.30869 2.84803 10.3312 24.73749 4.93555 9.4513 24.90974 7.96324 5.6219 25.9704 8.256831 3.7626 26.51529 6.86779 7.8935 26.51643 2.85645 10.6248 26.98418 5.02005 9.7225 27.17793 5.01206 9.91015 28.28688 10.72605 1.1873 4.35415 10.80892 1.8956 0.02976 10.22011 3.4746 4.38505 10.33368 1.07588 8.678461 10.30603 -1.32513 8.68545 9.83651 3.3706 8.74033 9.82534 0.96963 13.00276 9.7815 -1.36852 13.01323 9.355751 3.1991 13.09561 9.29663 0.82529 17.32708 9.253931 -1.21342 17.34108 8.92802 2.7923 17.45089 8.80583 0.66934 21.65139 8.78052 -0.89296 21.66892 8.60947 2.2453 21.80618 8.35632 -0.05476999 25.91333 8.32436 1.64096 26.06027 8.66363 -0.09009999 29.6289 8.64029 3.9125 29.54616 10.17118 1.89878 -3.67597 8.94513 5.4933 -3.22971 6.63522 8.424 -2.3937 3.52367 10.3366 -1.26092 8.28971 1.89878 -6.93474 7.29022 5.49331 -6.09604 5.40599 8.424 -4.51997 2.86939 10.3366 -2.39137 5.40719 1.89878 -9.35354 4.75482 5.4933 -8.22358 3.52367 8.424 -6.09781 1.86812 10.3366 -3.23 1.87124 1.89878 -10.64048 1.64468 5.49331 -9.35552 1.21532 8.424 -6.93679 0.64044 10.3366 -3.67576 -1.8917 1.89878 -10.64048 -1.66514 5.4933 -9.35552 -1.24074 8.424 -6.93594 -0.66558 10.3366 -3.67491 -5.42766 1.89878 -9.35354 -4.77529 5.4933 -8.22358 -3.54853 8.424 -6.09527 -1.8927 10.3366 -3.22759 -8.31018 1.89878 -6.93474 -7.31069 5.4933 -6.09605 -5.42971 8.424 -4.51615 -2.89297 10.3366 -2.38769 -10.19165 1.89878 -3.67597 -8.9656 5.4933 -3.22971 -6.65746 8.424 -2.38896 -3.54577 10.3366 -1.25646 -8.65377 3.85249 29.52191 -8.67159 0.003159999 29.58427 -8.97734 5.75739 31.2604 -8.62534 5.13799 29.42574 -8.92799 5.75739 33.24101 -8.44687 5.75739 35.16321 -7.5574 5.75739 36.93373 -6.30115 5.75739 38.46575 -4.74085 5.75739 39.68664 -2.95096 5.75739 40.53609 -1.01801 5.75739 40.9728 0.96295 5.75739 40.97697 2.89704 5.75739 40.54733 4.69025 5.75739 39.70474 6.25565 5.75739 38.49036 7.51734 5.7574 36.9628 8.41431 5.7574 35.19623 8.90306 5.7574 33.27615 8.959771 5.7574 31.29569 8.65656 1.84708 29.60358 8.35498 6.4167 28.91394 -7.38982 7.94489 28.76241 -8.31528 6.4931 28.80709 -8.78182 6.90539 32.00492 -8.03264 7.87869 30.76628 -8.10922 7.87869 32.63197 -8.12485 6.90539 35.36077 -7.75793 7.87869 34.46621 -6.99652 7.87869 36.1709 -6.23433 6.90539 38.21012 -5.86572 7.87869 37.65667 -4.42626 7.87869 38.84582 -3.39862 6.90539 40.12094 -2.75254 7.87869 39.67384 -0.04721999 6.90539 40.80133 -0.93471 7.87869 40.09867 0.93269 7.87869 40.0962 3.30949 6.9054 40.14902 2.75003 7.87869 39.66762 4.42149 7.87869 38.83535 6.16175 6.9054 38.26267 5.85861 7.8787 37.64331 8.07595 6.9054 35.42908 6.98559 7.8787 36.15457 7.74269 7.8787 34.44783 8.761281 6.9054 32.07895 8.09009 7.8787 32.61324 8.00927 7.8787 30.74782 7.13755 8.0314 28.36388 -5.75442 10.12129 30.77964 -5.88891 10.12129 32.02981 -5.68858 10.12129 33.55129 -5.10133 10.12129 34.96911 -4.16711 10.12129 36.18661 -2.94961 10.12129 37.12083 -1.53171 10.12129 37.70816 -0.01023995 10.12129 37.90848 1.51124 10.12129 37.70816 2.92913 10.12129 37.12083 4.14663 10.12129 36.18661 5.08086 10.12129 34.96911 5.66811 10.12129 33.55129 5.86843 10.1213 32.02981 5.73083 10.1213 30.76508 5.32404 10.1215 29.55953 4.88535 10.74795 32.02972 4.52677 10.7716 30.16474 3.59488 11 30.9712 3.74711 11 32.02981 3.15067 11 29.99836 3.48542 10.8173 28.47776 2.45035 11 29.19014 1.55063 11 28.61201 0.52448 11 28.31064 -0.2246299 10.9462 27.71228 -0.9031 10.9467 27.80258 -3.41361 10.67647 27.95695 -1.5711 11 28.61201 -2.47082 11 29.19014 -3.75642 10.71769 28.67628 -3.17115 10.99999 29.99836 -4.54689 10.7716 30.16368 -3.61535 10.99999 30.9712 -4.90581 10.74795 32.02974 -3.76759 10.99999 32.02981 -3.61542 10.99999 33.08834 3.59495 11 33.08834 -3.17115 10.99999 34.06111 3.15059 11 34.06118 -2.47075 10.99999 34.8694 2.45028 11 34.8694 -1.57111 10.99999 35.44761 1.55063 10.99999 35.44761 -0.54502 10.99999 35.7489 0.52455 10.99999 35.7489 -4.42986 10.77159 34.1582 -3.06869 10.7716 35.86501 -1.1018 10.7716 36.81225 1.08132 10.7716 36.81225 3.04821 10.7716 35.86501 4.40939 10.7716 34.1582 4.40939 -10.8617 34.15819 3.04822 -10.8617 35.86501 1.08133 -10.8617 36.81224 -1.1018 -10.8617 36.81224 -3.06868 -10.8617 35.86501 -4.42986 -10.8617 34.15819 0.52455 -11.09011 35.7489 -0.54502 -11.09011 35.7489 1.55064 -11.09011 35.4476 -1.5711 -11.09011 35.4476 2.45028 -11.0901 34.8694 -2.47075 -11.09011 34.8694 3.1506 -11.0901 34.06118 -3.17114 -11.09011 34.0611 3.59495 -11.0901 33.08834 -3.61542 -11.09011 33.08834 -3.76759 -11.09011 32.0298 -4.90581 -10.83806 32.02974 -3.61535 -11.09011 30.97119 -4.54689 -10.86171 30.16368 -3.17114 -11.09011 29.99836 -3.75641 -10.8078 28.67628 -2.47082 -11.0901 29.19013 -1.5711 -11.0901 28.612 -3.4136 -10.76658 27.95695 -0.90309 -11.0368 27.80258 -0.2246299 -11.0363 27.71228 0.52448 -11.0901 28.31063 1.55063 -11.0901 28.612 2.45035 -11.0901 29.19013 3.48542 -10.90741 28.47776 3.15067 -11.0901 29.99836 3.74712 -11.0901 32.0298 3.59488 -11.0901 30.97119 4.52677 -10.8617 30.16474 4.88535 -10.83805 32.02972 5.32404 -10.2116 29.55953 5.73084 -10.2114 30.76507 5.86844 -10.2114 32.0298 5.66811 -10.2114 33.55128 5.08086 -10.2114 34.9691 4.14663 -10.2114 36.1866 2.92914 -10.21141 37.12083 1.51124 -10.21141 37.70815 -0.01023 -10.21141 37.90848 -1.53171 -10.21141 37.70815 -2.9496 -10.21141 37.12083 -4.1671 -10.21141 36.1866 -5.10133 -10.2114 34.9691 -5.68858 -10.2114 33.55128 -5.88891 -10.2114 32.0298 -5.75441 -10.2114 30.77964 7.13755 -8.1215 28.36388 8.00927 -7.9688 30.74782 8.09009 -7.9688 32.61324 8.761281 -6.9955 32.07895 7.74269 -7.9688 34.44782 6.9856 -7.9688 36.15456 8.07595 -6.9955 35.42908 5.85861 -7.9688 37.64331 6.16175 -6.9955 38.26267 4.42149 -7.9688 38.83535 2.75003 -7.9688 39.66762 3.30949 -6.9955 40.14902 0.93269 -7.9688 40.09619 -0.93471 -7.9688 40.09867 -0.04721999 -6.9955 40.80132 -2.75254 -7.9688 39.67384 -3.39862 -6.99551 40.12094 -4.42626 -7.9688 38.84582 -5.86571 -7.96881 37.65667 -6.23433 -6.99551 38.21012 -6.99652 -7.96881 36.1709 -7.75793 -7.9688 34.46621 -8.12485 -6.9955 35.36077 -8.10922 -7.96881 32.63197 -8.03264 -7.96881 30.76628 -8.78182 -6.9955 32.00491 -8.31528 -6.5832 28.80709 -7.38981 -8.035 28.76241 8.35498 -6.5068 28.91394 8.65656 -1.93718 29.60358 8.959771 -5.8475 31.29569 8.90306 -5.8475 33.27615 8.41431 -5.8475 35.19623 7.51734 -5.8475 36.96279 6.25565 -5.8475 38.49036 4.69026 -5.8475 39.70473 2.89704 -5.8475 40.54733 0.96295 -5.8475 40.97696 -1.018 -5.8475 40.9728 -2.95095 -5.8475 40.53608 -4.74085 -5.8475 39.68664 -6.30115 -5.8475 38.46575 -7.5574 -5.8475 36.93373 -8.44687 -5.8475 35.1632 -8.92799 -5.8475 33.24101 -8.62534 -5.2281 29.42574 -8.65377 -3.9426 29.52191 -8.97734 -5.8475 31.2604 -3.54577 -10.4267 -1.25647 -6.65746 -8.514101 -2.38897 -8.9656 -5.5834 -3.22972 -10.19165 -1.98888 -3.67597 -2.89297 -10.4267 -2.38769 -5.42971 -8.514101 -4.51616 -7.31068 -5.5834 -6.09605 -8.31018 -1.98888 -6.93474 -1.89269 -10.4267 -3.2276 -3.54852 -8.514101 -6.09527 -4.77528 -5.5834 -8.22358 -5.42766 -1.98888 -9.35354 -0.66558 -10.4267 -3.67491 -1.24074 -8.514101 -6.93595 -1.66514 -5.5834 -9.35552 -1.8917 -1.98888 -10.64048 0.64045 -10.4267 -3.67576 1.21532 -8.514101 -6.9368 1.64468 -5.5834 -9.35552 1.87123 -1.98888 -10.64047 1.86813 -10.4267 -3.23 3.52368 -8.514101 -6.09782 4.75482 -5.5834 -8.22358 5.40719 -1.98888 -9.35354 2.86939 -10.4267 -2.39137 5.40599 -8.514101 -4.51997 7.29022 -5.5834 -6.09604 8.28971 -1.98888 -6.93474 3.52367 -10.4267 -1.26092 6.63523 -8.514101 -2.3937 8.94513 -5.5834 -3.22972 10.17118 -1.98888 -3.67597 8.64029 -4.0026 29.54616 8.32436 -1.73106 26.06027 8.60947 -2.3354 21.80618 8.92802 -2.8824 17.45089 9.355751 -3.2892 13.09561 9.83651 -3.4607 8.74033 10.22011 -3.5647 4.38505 10.80892 -1.9857 0.02976 10.72605 -1.2774 4.35415 5.01207 -10.00026 28.28688 5.02005 -9.812601 27.17792 2.85645 -10.7149 26.98417 6.86779 -7.9836 26.51642 8.256831 -3.8527 26.51529 7.96325 -5.712 25.9704 4.93555 -9.5414 24.90974 2.84804 -10.4213 24.73748 6.78704 -7.742 24.30869 7.87952 -5.6198 23.80835 8.283841 -3.8031 24.13419 4.98816 -9.1401 22.6477 3.09609 -9.9835 22.49072 6.6836 -7.5227 22.10104 8.2574 -4.0479 21.48409 7.73768 -5.6768 21.6463 5.12194 -8.7098 20.38566 3.492 -9.507 20.24403 6.58863 -7.3505 19.89338 7.59137 -5.8328 19.48432 8.23527 -4.5073 18.53411 5.29915 -8.3409 18.12349 3.92878 -9.0957 17.99734 6.53255 -7.2495 17.68572 7.49153 -6.0385 17.32227 5.48222 -8.123701 15.86138 4.29923 -8.8536 15.75065 6.54521 -7.2436 15.47806 8.32521 -4.9949 15.26346 7.48771 -6.2457 15.16022 5.64083 -8.116701 13.59928 4.52889 -8.8436 13.50389 6.63742 -7.3393 13.27048 7.59222 -6.4281 12.99817 8.61378 -5.3102 11.685 5.76895 -8.2769 11.33725 4.63475 -9.0152 11.25721 6.78224 -7.5095 11.06275 7.769 -6.5886 10.83612 5.86526 -8.540801 9.07521 4.64917 -9.298501 9.01044 6.94848 -7.7232 8.855091 7.97887 -6.7317 8.67407 9.006441 -5.478 7.87617 5.92833 -8.844901 6.81303 4.60456 -9.6235 6.76375 7.10496 -7.9495 6.64743 8.18244 -6.8622 6.51209 5.95697 -9.125801 4.55093 4.53343 -9.9203 4.51699 7.22057 -8.157401 4.43977 8.340411 -6.9848 4.35004 9.3264 -5.6048 3.95307 5.94975 -9.32 2.2889 4.46815 -10.1188 2.2703 7.26406 -8.3158 2.23212 9.50643 -5.5762 0.02976 8.413451 -7.104 2.18806 7.06211 -8.512701 0.02480995 1.22529 -10.8877 26.75026 -0.26995 -10.8776 26.46784 0.6386 -10.8786 26.55729 1.30046 -10.6268 24.50003 1.66399 -10.2315 22.076 0.80393 -10.4495 22.7515 -0.4678 -10.4709 22.73461 0.1721299 -10.4882 22.68822 2.21228 -9.7977 19.47371 1.3491 -9.9347 18.96452 -0.65823 -9.98 18.95052 0.34962 -10.0258 18.9117 2.77768 -9.471301 16.66155 1.78511 -9.704 15.17754 -0.89992 -9.7619 15.16637 0.44522 -9.8346 15.13533 3.12557 -9.448 13.61292 1.88616 -9.9356 11.39063 -1.07563 -9.9859 11.38229 0.40633 -10.0745 11.35896 3.19084 -9.742 10.35776 1.75633 -10.4088 7.60365 -1.22349 -10.4362 7.59807 0.26646 -10.5342 7.58258 3.0608 -10.1983 6.97885 3.74599 -10.4092 0.02459996 2.8701 -10.6069 3.5216 1.54102 -10.8533 3.81674 -1.40118 -10.8493 3.81398 -0.01023 -11.0901 0.02976 0.06931996 -10.9577 3.8062 8.61265 -5.2237 29.45177 -5.42738 -9.9259 28.97489 -5.11936 -9.788001 27.34444 -3.12402 -10.63996 26.98725 -1.22462 -10.8865 26.70466 -6.92828 -7.9341 26.71059 -7.87333 -5.9823 26.22347 -4.79982 -9.575201 24.83005 -1.13835 -10.6084 24.18891 -2.69618 -10.4267 24.54579 -6.62395 -7.8178 24.35296 -7.69641 -5.7171 23.89709 -4.64892 -9.1903 22.35008 -1.33429 -10.1778 21.40864 -2.76823 -9.9844 22.09418 -6.30171 -7.6508 21.92059 -7.34378 -5.8649 21.51039 -4.58613 -8.784501 19.86997 -2.99557 -9.5164 19.64257 -5.9973 -7.5398 19.48835 -7.00006 -6.1226 19.12369 -1.72766 -9.7331 18.33506 -4.61109 -8.4623 17.38994 -3.28867 -9.1472 17.19096 -5.79564 -7.5006 17.05604 -6.77357 -6.406 16.737 -2.13855 -9.523 14.94243 -4.72338 -8.325301 14.90997 -3.56026 -8.995901 14.73935 -5.77711 -7.5471 14.62374 -6.7619 -6.6367 14.3503 -4.91141 -8.3942 12.42994 -3.77749 -9.0778 12.28781 -5.94427 -7.6677 12.19143 -6.95685 -6.7951 11.9636 -2.40556 -9.7322 11.242 -5.15147 -8.5974 9.9499 -3.95787 -9.3108 9.8362 -6.23701 -7.8295 9.75912 -7.28799 -6.8959 9.57691 -5.41925 -8.858201 7.46987 -2.57576 -10.1854 7.41507 -4.12086 -9.6093 7.38459 -6.59311 -7.999 7.32682 -7.68404 -6.9541 7.19021 -5.69028 -9.1002 4.98983 -4.28568 -9.8876 4.93298 -6.95048 -8.143 4.89451 -8.073801 -6.9847 4.80358 -2.7584 -10.5859 3.62321 -5.9401 -9.2467 2.5098 -3.75606 -10.3841 0.02976 -4.47194 -10.06 2.48144 -7.24683 -8.2278 2.46228 -8.3862 -7.0029 2.41682 -7.06228 -8.490301 0.02982997 -8.25863 -3.8925 26.8629 -8.184041 -3.8483 24.93399 -8.28218 -2.239 26.50221 -8.023591 -4.0347 22.84328 -7.82107 -4.4087 20.58139 -8.315771 -2.5019 22.09022 -8.53313 -0.9657 21.91118 -7.64989 -4.8851 18.13671 -8.362091 -3.2154 17.67809 -8.79618 -1.29108 17.53489 -7.62288 -5.3212 15.49638 -8.71246 -3.6628 13.26609 -9.26471 -1.45734 13.15861 -8.04629 -5.619 11.15913 -9.34524 -3.7027 8.85396 -9.89934 -1.41769 8.782401 -8.76916 -5.6313 6.5292 -9.53206 -5.5978 0.02982997 -9.24738 -5.5755 3.30953 -10.01191 -3.5751 4.4419 -10.43772 -3.5147 0.02982997 -10.52279 -1.28658 4.40604 -10.82211 -1.98461 0.02983999 + + + + + + + + + + -0.9976691 0 0.06823784 -0.9976692 0 0.06823784 -0.9645408 0.2423126 0.1046224 -0.9722402 0.2156157 0.09087938 -0.9145741 0.3960019 0.08207815 -0.9139295 0.397345 0.08276396 -0.9005906 0.415836 0.1265586 -0.9900047 0 0.1410347 -0.9679405 0.2140197 0.1314797 -0.9900047 0 0.1410347 -0.9633963 0.2292665 0.1389403 -0.8998986 0.4181334 0.1238835 -0.8896764 0.4345793 0.1400597 -0.9896479 0 0.143517 -0.9635617 0.2293461 0.137656 -0.9896479 0 0.1435169 -0.9620717 0.2340756 0.1400951 -0.8867389 0.4432665 0.1311827 -0.894891 0.4306937 0.1169325 -0.9943178 0 0.1064528 -0.9651898 0.2362111 0.1123083 -0.8940891 0.4329002 0.1149008 -0.972276 0.2119817 0.09870749 -0.9237072 0.3793855 0.05321323 -0.9981985 0 0.0599997 -0.9739551 0.2141646 0.07446569 -0.9981985 0 0.05999964 -0.9901344 0.1363146 0.03243869 -0.971872 0.2344455 -0.02236485 -0.9243676 0.3749626 0.07034081 -0.9759188 0.2117555 -0.05236595 -0.9986486 0 0.05197238 -0.9986486 -1.16758e-6 0.05197221 -0.9894352 0.1333738 0.05682861 -0.9970296 -0.004301607 -0.0769003 -0.9847071 0.1707791 0.03444725 -0.9998349 0.01582503 0.008927226 -0.9989746 0.02274221 -0.03915059 -0.7603783 0.6492537 -0.01716786 -0.7324221 0.6806162 0.01787984 -0.4847958 0.8742412 -0.02598774 -0.4966436 0.8670452 -0.03972256 -0.6153151 0.7873512 0.03828394 -0.8320395 0.5494912 0.07595783 -0.3137616 0.9488992 0.03382235 -0.8185413 0.5635357 0.1114351 -0.7303449 0.6756084 0.1007457 -0.7177514 0.6873278 0.1114165 -0.6139934 0.7826801 0.102099 -0.8186939 0.5632338 0.1118397 -0.480806 0.8713552 0.09780466 -0.3476933 0.9330807 0.09203249 -0.4834569 0.8696294 0.1000706 -0.606498 0.7877667 0.1076288 -0.7984409 0.5860663 0.1379077 -0.7170732 0.6855338 0.125895 -0.6938531 0.7056289 0.1437209 -0.6057653 0.7840344 0.1354207 -0.3194596 0.9389067 0.1280615 -0.4807665 0.8670458 0.1307483 -0.3490338 0.930022 0.1150414 -0.4891984 0.8612653 0.1375032 -0.5958572 0.7903929 0.1422435 -0.6942134 0.7074777 0.1324502 -0.7994903 0.582447 0.1468704 -0.7787319 0.6151375 0.1232178 -0.671029 0.7263351 0.1488543 -0.5958572 0.7903805 0.1423123 -0.348468 0.9273897 0.1360831 -0.4892113 0.861276 0.1373901 -0.5883194 0.7951293 0.1471385 -0.4975912 0.8554285 0.1436845 -0.3641607 0.9228441 0.1254824 -0.6709311 0.7310842 0.1239649 -0.7708613 0.6229081 0.1332606 -0.6638464 0.7366766 0.1289017 -0.5874715 0.7997034 0.1239027 -0.3553683 0.9277098 0.1143153 -0.5010995 0.8572598 0.1183425 -0.501683 0.8568597 0.1187674 -0.5897518 0.7982412 0.1224897 -0.7674787 0.6300866 0.1181849 -0.787911 0.6068349 0.1046323 -0.6625556 0.7418478 0.1033539 -0.5857918 0.8064792 0.08024603 -0.6888231 0.720157 0.08304661 -0.5081037 0.8581379 0.07368916 -0.3887199 0.91905 0.0651462 -0.6045669 0.7936565 0.06788539 -0.491765 0.8685595 0.06141465 -0.356377 0.9310514 0.07835042 -0.6872289 0.723385 0.06656247 -0.8142758 0.5781531 0.05190318 -0.5959342 0.8029605 0.01081293 -0.7467307 0.6650895 0.007028639 -0.3450855 0.9383651 -0.0196799 -0.4992816 0.8664379 0.001840829 -0.6277554 0.7782743 -0.01457244 -0.4630271 0.8859025 -0.02797579 -0.3404068 0.9401248 -0.0169931 -0.8285298 0.5537611 0.08298856 -0.8763527 0.480965 -0.02605223 -0.7468762 0.664914 0.008076965 -0.6180995 0.7835006 -0.06387531 -0.804599 0.588909 -0.07620286 -0.4676126 0.8805988 -0.07670962 -0.2771728 0.9544338 -0.1105959 -0.4285718 0.8965193 -0.1121585 -0.644545 0.7589967 -0.09211784 -0.8931404 0.449084 0.02497506 -0.926697 0.3638186 -0.09417504 -0.8086622 0.5858627 -0.05320143 -0.639486 0.7601941 -0.1147285 -0.8432439 0.5217363 -0.1293479 -0.4297939 0.8934184 -0.1306933 -0.1875213 0.9752551 -0.1171042 -0.3146312 0.9373264 -0.1497547 -0.655606 0.7423733 -0.1380674 -0.4022541 0.9018362 -0.1577447 -0.9439698 0.3286496 -0.03017705 -0.8504216 0.5177109 -0.09358859 -0.9563325 0.2642348 -0.1249333 -0.6556621 0.7423682 -0.1378285 -0.8675665 0.4749323 -0.1475395 -0.1465658 0.9790564 -0.1413051 -0.2100406 0.9632197 -0.1676033 -0.4018971 0.9031282 -0.1511234 -0.6643658 0.7313832 -0.1539377 -0.3891031 0.9064142 -0.1643546 -0.9731537 0.2235485 -0.05475372 -0.9748687 0.2005524 -0.09700477 -0.8779498 0.4590378 -0.1359724 -0.8733781 0.4719708 -0.1202269 -0.140727 0.9835156 -0.1135467 -0.6717287 0.7305573 -0.1227464 -0.9847707 0.1687231 -0.04194629 -0.3881579 0.9097153 -0.1474843 -0.1441671 0.9832909 -0.1111532 -0.4087816 0.9035518 -0.1284209 -0.6822821 0.7160932 -0.147315 -0.6702782 0.7180702 -0.1873565 -0.1902043 0.9817419 -0.002326488 -0.07327508 0.9966442 0.03648614 -0.1852129 0.9826828 -0.005547702 0.07048267 0.9969514 0.03346747 0.1800163 0.9836074 -0.01051932 0.1783383 0.9839017 -0.01152819 0.2035444 0.9735444 0.1038313 -0.2045332 0.9723671 0.1125545 0.06958341 0.9917576 0.1075877 -0.0724247 0.990735 0.1148862 -0.1962264 0.9737307 0.1155152 -0.06407243 0.9917222 0.1112738 0.20613 0.9731408 0.1025056 0.08178037 0.9903826 0.1115992 0.2150503 0.9688815 0.1225647 0.08164143 0.9897168 0.1174545 -0.06386166 0.9903596 0.1229221 -0.1971392 0.9725102 0.1239359 -0.1984999 0.9722948 0.1234532 -0.05736166 0.9910941 0.1201756 0.2325934 0.9660181 0.1127353 0.09021562 0.988613 0.1204394 0.2171319 0.9717856 0.09212291 -0.1939828 0.9785529 0.06931835 0.09195107 0.9938198 0.06218636 -0.05855542 0.9962375 0.06389051 -0.05245274 0.9967318 0.06143742 -0.2006517 0.977357 0.06717228 0.09484052 0.9934786 0.0632897 0.260816 0.9631392 0.06586307 0.2055233 0.9785218 0.0159738 -0.1824846 0.9824452 -0.03874039 0.09839177 0.9939974 -0.04783582 -0.05508947 0.9971327 -0.05187916 -0.04742175 0.9973895 -0.05445659 -0.2008639 0.9786496 -0.0435751 0.267486 0.9631584 -0.02787786 0.09326881 0.9943928 -0.04983925 0.1984953 0.9773399 -0.07352799 -0.1561822 0.9801861 -0.1218293 0.09625619 0.9885141 -0.1165105 -0.04980105 0.9910707 -0.1236882 -0.03598946 0.9912771 -0.126785 -0.1486172 0.9816038 -0.119862 0.1439943 0.9805835 -0.1331228 0.2139492 0.9715807 -0.101276 0.07303857 0.9895893 -0.12401 -0.1115908 0.9832054 -0.1444121 0.139353 0.9804403 -0.138988 0.07161951 0.9914936 -0.1086792 -0.03387415 0.9947766 -0.09629219 0.009616971 0.9940175 -0.1087973 -0.02782618 0.9938911 -0.1067999 0.0344333 0.99328 -0.1104959 -0.01813787 0.9937139 -0.110471 0.02222442 0.9931849 -0.1144116 0.7670791 0.6384067 -0.06345504 0.7254439 0.6882633 -0.004979372 0.3088989 0.9508017 0.0236172 0.8351379 0.548969 0.03432023 0.7252638 0.6856461 0.06230509 0.8201969 0.5690225 0.05908209 0.7241514 0.686708 0.06353718 0.6075592 0.791294 0.06874424 0.3430236 0.9365033 0.07277715 0.4729763 0.8787551 0.06389838 0.6106078 0.7891944 0.06580716 0.4847071 0.8716011 0.07328432 0.7236384 0.6840653 0.091663 0.8225308 0.5612425 0.09192383 0.7129138 0.6936965 0.1026603 0.6107177 0.7847374 0.1058826 0.4831145 0.8698722 0.0996142 0.3199503 0.9405368 0.1141155 0.6115527 0.7841898 0.1051173 0.5006081 0.8582787 0.112913 0.3585126 0.9291727 0.09003895 0.8170706 0.570227 0.08506906 0.712826 0.6928281 0.108943 0.8020876 0.58681 0.1109488 0.6992425 0.7044366 0.1217755 0.6118931 0.7812459 0.1234577 0.3615608 0.9237346 0.1264452 0.5004975 0.8581724 0.1142032 0.5195438 0.8447941 0.1280514 0.6136161 0.7801254 0.1219822 0.3803402 0.9183557 0.1093813 0.8032343 0.5841335 0.1166316 0.6991889 0.7056958 0.1145786 0.6136021 0.7801765 0.1217254 0.6919865 0.7116979 0.1209992 0.5213791 0.8461997 0.1100456 0.3869584 0.9145418 0.1177995 0.5356028 0.8358551 0.1203157 0.6195351 0.776211 0.1169317 0.7948218 0.5971108 0.1082459 0.6915131 0.7140098 0.1095432 0.7943721 0.5975161 0.1093047 0.7017414 0.7053209 0.1004069 0.6178582 0.7798213 0.1006478 0.5389229 0.8376009 0.08936852 0.4032769 0.9107819 0.08856689 0.5395553 0.8371422 0.08985 0.6309016 0.7705888 0.09031081 0.3998619 0.9121069 0.0903967 0.7854179 0.6124414 0.08963412 0.7011973 0.7068067 0.09352427 0.8209438 0.5592111 0.1154744 0.7351557 0.6752399 0.05997616 0.62616 0.7773941 0.05985236 0.3976961 0.9167881 0.036574 0.5433276 0.8379205 0.0518105 0.5224784 0.8519746 0.03399533 0.6462892 0.7618826 0.04295468 0.3953813 0.9177263 0.03810447 0.7355318 0.6745227 0.06334257 0.8278155 0.558579 0.05206847 0.784372 0.6202843 0.002840518 0.6380747 0.7699728 0.00160098 0.525425 0.8508251 -0.005048453 0.3539654 0.9343008 -0.04231363 0.4851233 0.8733081 -0.04459035 0.6587907 0.7520891 -0.01889491 0.8626178 0.4963287 0.09771543 0.8994946 0.4369319 3.32062e-5 0.7870138 0.6165319 0.02231466 0.8276093 0.5593661 -0.04661029 0.6515615 0.7568679 -0.05117458 0.4860231 0.8715209 -0.06506192 0.3498649 0.936017 -0.03829836 0.2870883 0.9505822 -0.1182106 0.4443952 0.8890312 -0.1101658 0.6655583 0.7431446 -0.06905227 0.8321991 0.5542367 -0.01632326 0.9530698 0.3001505 0.0395928 0.891211 0.4527462 -0.0276395 0.8576024 0.5085822 -0.07656693 0.661411 0.7450111 -0.08656781 0.2776711 0.9553779 -0.1007564 0.2148071 0.9624007 -0.1662617 0.444398 0.8890203 -0.1102421 0.6696359 0.7358747 -0.1003804 0.4128597 0.8989219 -0.1465826 0.9530497 0.3022539 0.01841157 0.976617 0.2068397 -0.0586217 0.86294 0.5034442 -0.04334348 0.8770618 0.4722474 -0.08800637 0.6686413 0.736211 -0.1044616 0.4126634 0.9015433 -0.130111 0.2049744 0.9704256 -0.1275138 0.1556046 0.9726675 -0.1723523 0.3945168 0.9062957 -0.151607 0.6731318 0.7306872 -0.1139731 0.8825579 0.4670819 -0.05409324 0.9873712 0.1582266 0.007904231 0.9767959 0.2090111 -0.04673707 0.6754569 0.7299451 -0.1045858 0.8899058 0.4487754 -0.08165973 0.1472735 0.9830648 -0.1090608 0.1227496 0.9840112 -0.1290524 0.3940086 0.911167 -0.1205489 0.6785058 0.7259943 -0.1120819 0.3913639 0.911896 -0.1236125 0.676903 0.726542 -0.1180644 0.9998165 0 0.01915997 0.9998164 0 0.01915997 0.9751331 0.2149664 0.05389672 0.9400522 0.3410134 0.003455996 0.9122198 0.4078519 0.03888583 0.9055465 0.4151734 0.08727353 0.9723661 0.2138164 0.09373748 0.9959088 0 0.09036445 0.9952807 -0.01118212 0.09639233 0.9737958 0.2085343 0.0907486 0.9069341 0.4116103 0.0897088 0.9013277 0.4185778 0.1113604 0.9710131 0.2071626 0.119237 0.9931318 -0.01109766 0.1164745 0.9925947 -0.01807349 0.1201218 0.972963 0.2001326 0.1152817 0.9034783 0.4126446 0.1159796 0.9060854 0.4087902 0.1090867 0.9718368 0.1994708 0.1254788 0.992519 -0.01806974 0.1207463 0.9923683 -0.01994746 0.1216857 0.9779096 0.1761755 0.1124957 0.9118414 0.3907146 0.1260459 0.9347066 0.3468863 0.07741856 0.993502 -0.02003782 0.1120378 0.9774188 0.1757822 0.1172742 0.9938409 -0.0148701 0.1098144 0.9895926 0.1147753 0.08679497 0.9302644 0.3635175 0.04963177 0.9709464 0.2181251 0.0984112 0.9791399 0.2029887 0.008981823 0.9946347 -0.01496511 0.1023624 0.9862198 0.1108141 0.1228449 0.9924069 0.09359234 0.07980698 0.997556 0.01285028 0.06868177 0.9995069 0.02951335 0.01072305 0.9855126 0 -0.1696024 0.928035 0.336654 -0.1594219 0.7621762 0.6342132 -0.1298505 0.9282004 0.3363506 -0.1590986 0.4945811 0.8647868 -0.08679562 0.7594357 0.6367012 -0.1336757 0.1783151 0.9838188 -0.01744586 0.5021891 0.8614888 -0.07512146 0.8660234 0 -0.5000036 0.8660233 0 -0.5000036 0.8154869 0.3366065 -0.470826 0.6679577 0.6364793 -0.3856511 0.8154844 0.3366094 -0.4708285 0.6675559 0.6367352 -0.3859245 0.4380135 0.8625676 -0.2532219 0.1525405 0.9843459 -0.08828669 0.4377942 0.8626307 -0.2533863 0.6427998 0 -0.7660344 0.6427999 0 -0.7660343 0.6052885 0.3366113 -0.7213312 0.605291 0.3366088 -0.7213302 0.4957825 0.6364907 -0.5908294 0.4953498 0.6367255 -0.5909393 0.3250133 0.8625721 -0.3877317 0.3248045 0.8626223 -0.387795 0.1131681 0.9843459 -0.1351159 0.3420078 0 -0.9396972 0.3420104 -3.45517e-6 -0.9396962 0.3220527 0.3366104 -0.884859 0.3220467 0.3366149 -0.8848596 0.2637791 0.6365106 -0.7247586 0.1728222 0.8625735 -0.4754991 0.2634028 0.6367093 -0.7247208 0.06015145 0.984346 -0.1656645 0.172646 0.8626143 -0.4754893 3.12915e-6 -2.6984e-6 -1 0 0 -1 0 0.3366152 -0.9416424 -1.2077e-6 0.336616 -0.9416421 -1.81985e-6 0.6365255 -0.7712558 -2.67272e-4 0.6366802 -0.7711279 -1.75024e-4 0.8625736 -0.5059316 -3.29489e-4 0.8626121 -0.5058657 -1.14701e-4 0.9843459 -0.1762474 -0.34201 0 -0.9396963 -0.3220508 0.3366156 -0.8848578 -0.2637682 0.6365388 -0.7247378 -0.3220455 0.33661 -0.8848618 -0.2639398 0.636668 -0.7245617 -0.1731628 0.8625801 -0.4753634 -0.06036216 0.9843456 -0.1655906 -0.1732525 0.8626087 -0.4752789 -0.6428 0 -0.7660341 -0.6427998 0 -0.7660343 -0.6052888 0.3366092 -0.7213319 -0.495749 0.6365538 -0.5907896 -0.6052899 0.3366106 -0.7213304 -0.4958111 0.6366332 -0.5906518 -0.3252691 0.8625856 -0.3874871 -0.325304 0.8626036 -0.3874177 -0.1133358 0.9843458 -0.1349757 -0.8660233 0 -0.5000036 -0.8154862 0.3366089 -0.4708256 -0.8660234 0 -0.5000036 -0.6679027 0.6365557 -0.3856202 -0.8154855 0.336606 -0.4708288 -0.667912 0.6366199 -0.3854982 -0.4381639 0.8625873 -0.2528945 -0.4381682 0.8625966 -0.2528554 -0.152653 0.9843459 -0.08809304 -0.9858351 0 -0.1677178 -0.9858351 0 -0.1677178 -0.759284 0.6366525 -0.1347647 -0.4963521 0.8665355 -0.05245059 -0.1852153 0.9826954 0.002266943 -0.7549933 0.644656 -0.1200158 -0.5020465 0.8615348 -0.0755468 -0.9828069 0.001558601 -0.18463 -0.9815933 0.007431566 -0.1908388 -0.9837667 0 -0.1794525 -0.9996898 0 0.02490878 -0.9996898 0 0.02490866 -0.9700748 0 0.2428061 -0.9700746 -2.01148e-7 0.2428074 -0.8935751 -2.96546e-7 0.4489136 -0.8935768 0 0.4489105 -0.7732695 0 0.6340775 -0.6162423 0 0.7875567 -0.616239 0 0.7875592 -0.4287515 0 0.9034225 -0.4287452 -1.2517e-6 0.9034255 -0.2203733 -1.14862e-6 0.9754157 -0.2203758 -1.91796e-7 0.9754151 -0.002105355 0 0.9999979 -0.002102732 -9.86142e-7 0.9999979 0.2168536 -9.59779e-7 0.9762042 0.2168536 0 0.9762042 0.4252698 0 0.9050667 0.4252722 -5.41941e-7 0.9050655 0.6129508 -2.6687e-7 0.7901211 0.612945 0 0.7901256 0.7710134 0 0.636819 0.7710153 -5.97957e-7 0.6368167 0.8916477 -4.80477e-7 0.45273 0.8916456 0 0.4527342 0.9690967 0 0.2466811 0.969097 0 0.2466805 0.9995903 0 0.02862304 0.9995903 0 0.02862316 0.9845807 0 -0.1749312 0.983816 0.001248896 -0.1791777 0.9832268 0.002674937 -0.1823678 0.9822299 0.007736563 -0.1875227 0.9704887 0.103618 -0.2177499 -0.9670349 0.1183249 -0.2254834 -0.9461239 0.273528 -0.1732978 -0.8120455 0.5826416 -0.03333175 -0.9880262 0.15231 0.02461814 -0.9053133 0.3592519 0.2265965 -0.9537907 0.2354103 0.1867225 -0.8630645 0.4772822 0.165292 -0.8582925 0.4848723 0.1680266 -0.7413155 0.5837932 0.3311146 -0.8804384 0.1708482 0.4423113 -0.6684874 0.5424721 0.5087718 -0.7435618 0.4513583 0.4933475 -0.7875515 0.3266808 0.5225346 -0.7602033 0.1830554 0.6233631 -0.5267606 0.5620798 0.6376437 -0.6029381 0.2066767 0.770552 -0.5291271 0.3215878 0.7852427 -0.5005259 0.4446654 0.7427964 -0.3622298 0.5767899 0.7321906 -0.4233977 0.1575248 0.8921437 -0.2129262 0.2577893 0.9424474 -0.1897869 0.3001187 0.9348315 -0.2039051 0.443979 0.8725283 -0.1719389 0.5031719 0.8469091 -0.00208646 0.1494451 0.9887678 0.001068055 0.5859814 0.8103238 0.2053034 0.3220515 0.9241934 0.184071 0.2625102 0.9472097 0.1956626 0.5228342 0.8296751 0.1693071 0.4607339 0.8712401 0.4198479 0.1591759 0.8935272 0.3653319 0.5728966 0.7337043 0.5628039 0.3961439 0.7254804 0.539792 0.2060324 0.8161957 0.4942678 0.4440166 0.7473612 0.5258113 0.5671601 0.633918 0.7575498 0.1860603 0.6256995 0.7288986 0.4052748 0.5517783 0.7060611 0.5234274 0.4769713 0.7834184 0.3258401 0.5292294 0.8788941 0.1685283 0.4462549 0.7411932 0.5852612 0.3287887 0.8516128 0.4987486 0.1612622 0.8629491 0.4734505 0.176532 0.9432718 0.2293183 0.2401074 0.9303605 0.3133795 0.1903226 0.9880475 0.1515316 0.02829247 0.8135731 0.5803933 -0.03524875 0.8822185 0.4349075 -0.1804053 0.9471049 0.2757596 -0.1641616 0.8112989 0.522022 -0.2632247 -0.6616416 0.7128127 -0.2326554 -0.687133 0.6992217 -0.1973254 -0.6993024 0.7108565 -0.07522851 -0.7142482 0.6992782 -0.02931791 -0.6952483 0.7129166 0.09154176 -0.7004091 0.7010232 0.13414 -0.6504708 0.7101407 0.2694219 -0.6488144 0.7036034 0.289797 -0.5635156 0.7060523 0.4288827 -0.5609962 0.7070934 0.4304675 -0.4531106 0.7027438 0.5484906 -0.4280797 0.7109931 0.5578859 -0.3164772 0.7004408 0.6397068 -0.268165 0.7134283 0.6473852 -0.1627425 0.6989808 0.6963769 -0.09128528 0.7147869 0.693359 9.4388e-4 0.6984974 0.7156119 0.09128856 0.7147808 0.6933649 0.164164 0.6989089 0.6961154 0.2680964 0.7136015 0.6472228 0.3181897 0.7002888 0.6390234 0.4279596 0.7111881 0.5577294 0.4543022 0.7025831 0.5477102 0.5635842 0.7073597 0.4266326 0.5622105 0.7055563 0.4314042 0.649367 0.7038078 0.2880575 0.6507924 0.7097964 0.2695522 0.7005811 0.7011324 0.132663 0.6954188 0.7127473 0.09156459 0.71409 0.69937 -0.03093814 0.6991512 0.7109159 -0.07606703 0.6856424 0.6981843 -0.2059933 0.6683627 0.7088604 -0.225407 0.5366033 0.8418127 -0.05838066 0.2128682 0.9766013 -0.03061091 0.2161068 0.9759338 -0.02917528 0.5064749 0.8579049 -0.08650124 0.5355858 0.8249467 -0.1805851 0.1724878 0.981858 -0.07875996 0.172613 0.9817393 -0.07995569 0.4761528 0.8364779 -0.2712622 0.1094056 0.9894662 -0.09480029 0.08418643 0.9877993 -0.1310166 0.0816918 0.9835408 -0.1611647 0.05377924 0.9816195 -0.1831148 -0.009595513 0.9969363 -0.07762759 -0.1106515 0.9788274 -0.1722013 -0.1615605 0.9778555 -0.1330297 -0.159438 0.9774954 -0.1381392 -0.1775366 0.9755288 -0.1297094 -0.1724646 0.9818629 -0.07874828 -0.5489325 0.8045262 -0.2267398 -0.4943814 0.8676166 -0.05318516 -0.5352255 0.839651 -0.09230333 -0.2143563 0.9763292 -0.02885651 -0.2160906 0.9758787 -0.03107583 -0.01071459 0.9971631 -0.07450455 0 1 8.1095e-6 0 1 -4.22735e-6 0 1 -2.68161e-6 0 1 1.53455e-5 -1.6594e-6 1 2.9864e-6 -1.6594e-6 1 -2.48106e-6 -1.45494e-6 1 0 -1.45494e-6 1 0 -1.39598e-6 1 -1.91811e-6 -1.39599e-6 1 1.91825e-6 -1.45491e-6 1 0 -1.45491e-6 1 0 -1.6594e-6 1 -2.48108e-6 -1.65945e-6 1 2.9862e-6 -2.13176e-6 1 -3.83649e-6 -2.13175e-6 1 5.36265e-6 0 1 1.69071e-5 0 1 0 -0.5361717 0.8411516 0.07059723 -0.4946666 0.863191 0.101026 -0.2294663 0.9727575 0.03298646 -0.2160459 0.9756639 0.03747481 -0.5291742 0.8197162 0.2191811 -0.1721152 0.9819356 0.07860559 -0.1531177 0.9792605 0.1326795 -0.1669956 0.9769226 0.1331722 -0.4246094 0.8447196 0.3258154 -0.4090434 0.852218 0.3262026 -0.3504155 0.8177166 0.4566712 -0.1043761 0.9811899 0.1623952 -0.1928471 0.8637467 0.4655661 -0.2375966 0.8367503 0.4933527 -0.09429097 0.9761019 0.1957915 -0.05366015 0.9816933 0.1827533 -0.0740329 0.8236103 0.5623036 0 0.8600541 0.5102029 0 0.9777029 0.2099933 0 0.9777023 0.2099962 0.07403242 0.8236108 0.562303 0.05366075 0.9816934 0.1827531 0.2097791 0.8363748 0.5064285 0.223854 0.8566375 0.4648243 0.09429097 0.9761023 0.1957895 0.1043725 0.9811877 0.1624101 0.3504157 0.8177168 0.4566707 0.1659359 0.9755986 0.1437802 0.1605893 0.9786772 0.1280707 0.4128261 0.8539481 0.3167766 0.417223 0.8457032 0.3327327 0.1721063 0.9819366 0.07861232 0.5291797 0.8197119 0.219183 0.4820663 0.8738325 0.06347358 0.5342407 0.8381249 0.1101527 0.2221711 0.9742332 0.03885543 0.2160995 0.9758771 0.03106421 0.8136374 0.558775 -0.1605139 0.8507349 0.4678353 -0.2395423 0.6421198 0.7151295 -0.2761737 0.6577405 0.7379291 -0.1511226 0.4700604 0.8448343 -0.2555354 0.4590393 0.8358588 -0.301037 0.1158702 0.9903206 -0.07641518 0.3919759 0.907541 -0.1507453 -0.3495913 0.9110046 -0.2187618 -0.4128099 0.875904 -0.2497603 -0.5932972 0.7849501 -0.178471 -0.1126762 0.9883513 -0.1023032 -0.4171755 0.8768188 -0.2390679 -0.1519806 0.9732214 -0.1724591 -0.6711868 0.717507 -0.1862584 -0.9702122 0.1281293 -0.2055993 -0.9735475 0.1199956 -0.1944383 -0.8179889 0.5134557 -0.2593409 -0.8566463 0.46863 -0.2157384 -0.9890498 0.01086366 -0.147182 0.9965959 0.002560496 -0.08240276 0.9951245 0.02697557 -0.09486621 0.9955919 0.005239009 -0.09364569 0.9899958 0.05899906 -0.12817 0.991933 0.01270186 -0.1261256 0.980118 0.1055217 -0.1680294 0.9780973 0.1274349 -0.1645789 0.02348494 0.9927098 -0.1182196 0.02315002 0.9927152 -0.1182407 0.01140129 0.9918496 -0.1269041 -0.02193015 0.9918274 -0.1256875 -0.01668 0.9912667 -0.1308134 -0.1153519 0.9803938 -0.1597567 -0.8783807 0.4407196 -0.18497 -0.8206953 0.5155838 -0.2462373 -0.9275057 0.3365574 -0.162673 -0.8946962 0.3889836 -0.2195686 -0.956968 0.2404088 -0.1625297 0.4953884 0.8662007 -0.06547373 0.6074672 0.7941982 0.01526433 0.474587 0.8793486 -0.0389021 0.4745869 -0.8793485 -0.03890448 0.6074675 -0.794198 0.01526689 0.4953874 -0.8662015 -0.0654717 -0.956968 -0.2404088 -0.1625297 -0.8946967 -0.3889831 -0.2195683 -0.9275058 -0.3365569 -0.162673 -0.8206936 -0.515584 -0.2462425 -0.8783813 -0.4407171 -0.1849722 -0.1153477 -0.9803947 -0.1597531 -0.01668208 -0.9912665 -0.1308151 -0.02193236 -0.9918276 -0.1256871 0.01140201 -0.9918497 -0.1269026 0.02314984 -0.992715 -0.1182422 0.02348673 -0.9927099 -0.1182176 0.9780977 -0.1274352 -0.1645763 0.9801189 -0.1055171 -0.1680274 0.991933 -0.01270186 -0.1261252 0.9899957 -0.05899924 -0.1281703 0.9955918 -0.005239009 -0.09364563 0.9951143 -0.02728974 -0.09488362 0.9965915 -0.002684712 -0.08245247 -0.9890499 -0.0108636 -0.1471815 -0.8566483 -0.4686269 -0.2157371 -0.8179868 -0.5134572 -0.259344 -0.9735463 -0.1199988 -0.1944429 -0.9702121 -0.1281304 -0.2055994 -0.6711866 -0.717507 -0.1862588 -0.1519817 -0.9732195 -0.172469 -0.4171754 -0.8768174 -0.2390734 -0.1126723 -0.9883517 -0.1023031 -0.5932994 -0.7849479 -0.1784732 -0.4128118 -0.8759026 -0.2497625 -0.3495562 -0.9110019 -0.2188286 0.3919765 -0.9075391 -0.1507554 0.1158695 -0.9903205 -0.0764175 0.4590364 -0.835859 -0.3010407 0.470061 -0.8448374 -0.2555239 0.6577435 -0.7379266 -0.1511228 0.6421235 -0.7151305 -0.2761626 0.8507345 -0.467837 -0.2395398 0.8136369 -0.558776 -0.1605131 0.216098 -0.9758774 0.03106576 0.222171 -0.9742332 0.03885656 0.5342362 -0.8381281 0.1101504 0.4820604 -0.8738359 0.06347215 0.5291731 -0.8197168 0.2191806 0.1721076 -0.9819365 0.07861185 0.4172198 -0.8457068 0.3327279 0.4128239 -0.8539494 0.316776 0.1605896 -0.9786775 0.1280685 0.1659356 -0.9755983 0.143783 0.3504224 -0.8177193 0.4566611 0.1043854 -0.9811876 0.1624025 0.09429848 -0.9760987 0.1958044 0.22385 -0.8566437 0.464815 0.2097671 -0.8363816 0.5064224 0.05366748 -0.9816899 0.1827693 0.07403588 -0.8236185 0.5622912 0 -0.9776985 0.2100136 0 -0.9776985 0.2100135 0 -0.8600612 0.5101909 -0.07403534 -0.8236182 0.5622917 -0.0536679 -0.9816899 0.1827693 -0.09429866 -0.9760987 0.1958039 -0.2375901 -0.8367561 0.4933459 -0.1928423 -0.8637539 0.4655547 -0.104382 -0.981186 0.1624146 -0.3504142 -0.8177233 0.4566601 -0.4090322 -0.8522236 0.3262016 -0.4246124 -0.8447187 0.3258141 -0.1670014 -0.9769202 0.1331818 -0.1531338 -0.9792564 0.1326915 -0.1721197 -0.9819344 0.07861149 -0.5291737 -0.8197164 0.2191808 -0.2160547 -0.9756618 0.03747564 -0.2294762 -0.9727551 0.03298842 -0.4946666 -0.8631911 0.1010265 -0.5361738 -0.8411504 0.07059609 0 -1 -1.18373e-5 0 -1 -4.05568e-6 0 -1 -1.26806e-5 2.13175e-6 -1 0 2.13176e-6 -1 0 1.65944e-6 -1 1.49309e-6 1.6594e-6 -1 0 1.45492e-6 -1 -2.17549e-6 1.4549e-6 -1 0 1.39598e-6 -1 0 1.39598e-6 -1 -1.9181e-6 1.45494e-6 -1 0 1.45493e-6 -1 0 1.6594e-6 -1 0 1.6594e-6 -1 -1.49318e-6 0 -1 -1.34272e-5 0 -1 0 0 -1 -8.45474e-6 0 -1 8.1095e-6 -0.01071494 -0.9971631 -0.07450568 -0.2160986 -0.9758769 -0.03107732 -0.2143663 -0.9763271 -0.0288574 -0.5352263 -0.8396505 -0.09230405 -0.4943848 -0.8676144 -0.05318981 -0.548938 -0.8045223 -0.2267402 -0.1724702 -0.9818615 -0.07875293 -0.1775438 -0.975527 -0.129713 -0.1594243 -0.9774956 -0.1381533 -0.1615555 -0.9778563 -0.1330295 -0.1106505 -0.9788279 -0.1721988 -0.009596765 -0.9969365 -0.07762563 0.05377835 -0.9816198 -0.183113 0.08168762 -0.9835405 -0.1611683 0.0841813 -0.9878007 -0.131009 0.1094005 -0.9894674 -0.09479343 0.4761555 -0.8364771 -0.2712604 0.1726118 -0.9817399 -0.07994991 0.1724867 -0.9818581 -0.07875931 0.5355837 -0.8249468 -0.1805905 0.5064696 -0.8579083 -0.08649897 0.2161087 -0.9759334 -0.02917551 0.2128669 -0.9766015 -0.03061324 0.5366023 -0.8418133 -0.05838125 0.6683603 -0.7088602 -0.2254146 0.6856434 -0.6981834 -0.2059932 0.6991544 -0.7109127 -0.07606697 0.7140905 -0.6993696 -0.03093832 0.6954211 -0.7127449 0.09156531 0.7005831 -0.7011302 0.132664 0.6507924 -0.7097958 0.2695538 0.6493695 -0.7038072 0.288053 0.5622131 -0.7055541 0.4314045 0.5635823 -0.70736 0.4266344 0.4543058 -0.7025827 0.5477077 0.427967 -0.7111868 0.5577254 0.3181919 -0.7002866 0.6390247 0.2680886 -0.7136015 0.647226 0.1641635 -0.6989079 0.6961165 0.09129524 -0.7147783 0.6933665 9.46487e-4 -0.698495 0.7156143 -0.09129047 -0.714786 0.6933593 -0.1627443 -0.698981 0.6963763 -0.2681602 -0.7134284 0.6473871 -0.3164764 -0.7004404 0.6397077 -0.428083 -0.7109924 0.5578843 -0.4531111 -0.7027441 0.5484898 -0.5609963 -0.707094 0.4304664 -0.56351 -0.7060555 0.4288846 -0.6488148 -0.703605 0.289792 -0.650474 -0.7101382 0.2694206 -0.7004057 -0.7010256 0.1341455 -0.695245 -0.71292 0.09154057 -0.714247 -0.6992794 -0.02931666 -0.6993008 -0.7108573 -0.07523536 -0.6871283 -0.6992247 -0.1973313 -0.6616411 -0.7128133 -0.2326553 0.8112989 -0.522022 -0.2632246 0.9471049 -0.2757596 -0.1641616 0.8822185 -0.4349075 -0.1804053 0.8135731 -0.5803933 -0.03524875 0.9880475 -0.1515316 0.02829247 0.9303605 -0.3133795 0.1903223 0.9432718 -0.2293183 0.2401071 0.8629484 -0.473452 0.1765315 0.8516128 -0.4987483 0.1612633 0.7411947 -0.5852614 0.3287851 0.8788935 -0.1685272 0.4462565 0.783419 -0.3258355 0.5292315 0.7060611 -0.5234274 0.4769713 0.7288987 -0.4052718 0.5517804 0.7575526 -0.1860619 0.6256957 0.5258138 -0.5671591 0.6339168 0.494268 -0.4440131 0.747363 0.5397926 -0.2060341 0.8161948 0.5628018 -0.3961438 0.7254821 0.3653355 -0.5728915 0.7337067 0.419852 -0.1591756 0.8935254 0.1693046 -0.4607356 0.8712399 0.1956582 -0.5228289 0.8296794 0.1840686 -0.2625134 0.9472094 0.2052946 -0.3220478 0.9241967 0.00107485 -0.585978 0.8103264 -0.002076506 -0.1494501 0.9887672 -0.1719342 -0.5031735 0.8469092 -0.2039098 -0.4439707 0.8725312 -0.1897827 -0.300123 0.9348309 -0.2129314 -0.2577745 0.9424503 -0.4233908 -0.1575149 0.8921487 -0.362229 -0.5767941 0.7321877 -0.5005237 -0.444669 0.7427958 -0.5291283 -0.3215852 0.7852428 -0.6029371 -0.2066752 0.7705532 -0.5267584 -0.5620841 0.6376419 -0.760203 -0.1830537 0.6233641 -0.7875527 -0.3266797 0.5225336 -0.7435637 -0.4513557 0.4933468 -0.6684823 -0.5424777 0.5087724 -0.8804386 -0.1708466 0.4423116 -0.7413174 -0.583792 0.3311125 -0.8582949 -0.4848679 0.1680269 -0.8630634 -0.4772835 0.1652939 -0.9537914 -0.2354082 0.1867217 -0.9053117 -0.3592553 0.2265979 -0.9880262 -0.1523103 0.02461802 -0.8120495 -0.5826359 -0.03333187 -0.9461239 -0.273527 -0.1732991 -0.9670348 -0.1183256 -0.2254835 0.9704887 -0.103618 -0.21775 0.9822299 -0.007736563 -0.1875227 0.9832268 -0.002674937 -0.1823682 0.9837923 -0.001307904 -0.1793072 -0.5020465 -0.8615348 -0.0755468 -0.7549934 -0.644656 -0.1200157 -0.1852146 -0.9826956 0.002265095 -0.496352 -0.8665354 -0.05245172 -0.7592841 -0.6366524 -0.1347644 -0.1526523 -0.984346 -0.08809196 -0.4381678 -0.8625966 -0.2528557 -0.4381631 -0.8625876 -0.2528949 -0.6679117 -0.6366196 -0.3854988 -0.8154839 -0.336605 -0.4708325 -0.6679025 -0.6365536 -0.3856239 -0.8154856 -0.3366107 -0.4708253 -0.1133358 -0.9843459 -0.134975 -0.3253042 -0.8626042 -0.3874161 -0.3252668 -0.8625851 -0.38749 -0.4958091 -0.6366308 -0.5906562 -0.6052897 -0.3366119 -0.72133 -0.4957491 -0.6365538 -0.5907896 -0.6052885 -0.3366107 -0.7213316 -0.1732512 -0.8626077 -0.475281 -0.06036138 -0.9843454 -0.1655915 -0.1731652 -0.8625805 -0.4753618 -0.2639433 -0.6366684 -0.7245602 -0.3220466 -0.3366108 -0.8848611 -0.2637699 -0.6365371 -0.7247387 -0.3220508 -0.3366156 -0.8848578 -1.14701e-4 -0.984346 -0.1762475 -3.29099e-4 -0.8626126 -0.5058651 -1.75229e-4 -0.8625744 -0.5059303 -2.67273e-4 -0.6366785 -0.7711294 0 -0.6365226 -0.7712581 0 -0.336616 -0.9416421 2.6557e-6 -0.3366137 -0.9416428 0.1726461 -0.8626146 -0.4754888 0.06015157 -0.984346 -0.1656649 0.2634033 -0.6367065 -0.7247231 0.1728214 -0.8625741 -0.4754985 0.2637777 -0.6365082 -0.7247611 0.3220461 -0.3366128 -0.8848606 0.3220493 -0.3366103 -0.8848603 0.1131689 -0.9843457 -0.1351163 0.3248053 -0.8626229 -0.387793 0.3250154 -0.862572 -0.38773 0.4953551 -0.6367228 -0.5909378 0.4957845 -0.6364895 -0.590829 0.6052917 -0.3366089 -0.7213296 0.6052883 -0.3366121 -0.721331 0.4377943 -0.8626309 -0.2533856 0.1525408 -0.9843457 -0.08828854 0.438012 -0.8625679 -0.2532235 0.6675555 -0.6367338 -0.3859274 0.8154829 -0.3366106 -0.4708303 0.6679567 -0.6364784 -0.385654 0.8154873 -0.3366054 -0.4708265 0.5021881 -0.8614894 -0.0751211 0.1783154 -0.9838188 -0.01744294 0.7594361 -0.6367006 -0.133676 0.4945802 -0.8647873 -0.08679544 0.9282006 -0.3363503 -0.1590982 0.7621778 -0.6342114 -0.12985 0.9280349 -0.336654 -0.1594219 0.9995069 -0.02951335 0.01072305 0.9975526 -0.01299744 0.06870239 0.9924069 -0.09359222 0.07980692 0.9871886 -0.1056891 0.1195346 0.97914 -0.2029886 0.008981704 0.9709464 -0.2181251 0.0984112 0.9302642 -0.3635177 0.04963189 0.9902762 -0.109232 0.08614879 0.9757974 -0.1826369 0.1202633 0.9347066 -0.3468863 0.07741856 0.9118414 -0.3907146 0.1260459 0.9765459 -0.1832592 0.1130232 0.9696817 -0.2095541 0.1257152 0.9060853 -0.4087905 0.1090863 0.903478 -0.4126453 0.1159798 0.9708094 -0.2102431 0.1154422 0.9707509 -0.2104565 0.1155455 0.9013273 -0.4185785 0.1113603 0.9069341 -0.4116103 0.08970898 0.9731294 -0.2116158 0.09076356 0.9725236 -0.2138757 0.0919519 0.9055464 -0.4151738 0.08727329 0.9122197 -0.4078521 0.03888607 0.9400521 -0.3410134 0.003455996 0.9751331 -0.2149664 0.05389672 0.6769034 -0.7265397 -0.118076 0.3913635 -0.9118961 -0.123613 0.6785051 -0.7259948 -0.1120821 0.3940109 -0.9111663 -0.1205471 0.1227491 -0.9840115 -0.1290513 0.1472724 -0.983065 -0.1090607 0.889904 -0.448779 -0.08166044 0.6754565 -0.7299454 -0.1045867 0.976796 -0.2090097 -0.04674148 0.9873721 -0.1582217 0.007904291 0.8825573 -0.4670826 -0.05409747 0.6731318 -0.7306872 -0.1139733 0.3945201 -0.9062942 -0.1516069 0.1556034 -0.9726675 -0.1723531 0.2049766 -0.9704253 -0.1275123 0.4126616 -0.9015436 -0.1301141 0.6686414 -0.7362109 -0.1044616 0.8770618 -0.4722474 -0.08800601 0.8629379 -0.503448 -0.04333996 0.9766174 -0.2068394 -0.05861723 0.9530511 -0.3022495 0.01841104 0.4128604 -0.8989217 -0.1465817 0.6696367 -0.7358741 -0.1003796 0.4443975 -0.8890208 -0.1102403 0.2148087 -0.9624003 -0.1662618 0.2776719 -0.9553777 -0.1007565 0.6614102 -0.7450122 -0.08656489 0.8576011 -0.5085848 -0.07656276 0.89121 -0.452748 -0.02764338 0.9530714 -0.3001458 0.03959196 0.8322009 -0.5542339 -0.01632708 0.6655569 -0.7431462 -0.06905013 0.4443961 -0.8890307 -0.1101654 0.2870899 -0.950582 -0.118209 0.3498631 -0.9360176 -0.0382989 0.4860231 -0.8715209 -0.06506073 0.6515638 -0.7568657 -0.05117738 0.8276111 -0.5593631 -0.04661399 0.7870139 -0.6165317 0.02231454 0.8994948 -0.4369316 3.30659e-5 0.8626176 -0.4963291 0.09771591 0.658793 -0.7520869 -0.01889753 0.4851221 -0.8733087 -0.04459226 0.3539637 -0.9343014 -0.04231476 0.5254269 -0.8508239 -0.005047321 0.638075 -0.7699726 0.001601576 0.7843716 -0.6202848 0.00284022 0.8278153 -0.5585793 0.05206871 0.7355315 -0.6745228 0.06334316 0.3953796 -0.9177272 0.03810411 0.6462896 -0.7618822 0.04295802 0.5224813 -0.8519728 0.03399807 0.5433241 -0.837923 0.05180895 0.3976965 -0.916788 0.0365712 0.6261612 -0.7773929 0.05985438 0.7351559 -0.6752395 0.05997902 0.8209436 -0.5592114 0.115474 0.701201 -0.706803 0.0935238 0.7854182 -0.6124412 0.08963376 0.3998622 -0.9121068 0.09039694 0.6309009 -0.7705897 0.09030848 0.5395516 -0.837145 0.08984702 0.4032764 -0.9107821 0.08856689 0.5389234 -0.8376007 0.08936852 0.617854 -0.7798246 0.1006482 0.7017451 -0.7053171 0.1004071 0.794374 -0.597513 0.1093083 0.6915139 -0.7140085 0.1095464 0.7948254 -0.597106 0.1082458 0.6195315 -0.7762134 0.1169341 0.5356032 -0.8358545 0.1203192 0.3869583 -0.9145416 0.1178011 0.5213761 -0.8462015 0.1100456 0.6919864 -0.7116981 0.1209995 0.6136022 -0.7801766 0.1217254 0.6991898 -0.705695 0.1145781 0.8032374 -0.584129 0.1166323 0.3803396 -0.9183561 0.1093801 0.6136158 -0.7801262 0.1219785 0.5195409 -0.8447962 0.1280495 0.5004982 -0.8581722 0.1142026 0.3615593 -0.9237351 0.1264458 0.6118932 -0.7812464 0.1234536 0.6992428 -0.7044367 0.1217723 0.8020898 -0.5868079 0.1109449 0.712826 -0.6928287 0.1089388 0.8170707 -0.570227 0.08506876 0.3585116 -0.9291729 0.09004026 0.5006082 -0.8582782 0.1129161 0.6115528 -0.7841893 0.1051211 0.3199496 -0.9405369 0.1141172 0.4831141 -0.869872 0.09961682 0.6107214 -0.7847347 0.105882 0.7129135 -0.6936968 0.1026604 0.8225308 -0.5612425 0.09192383 0.7236385 -0.6840652 0.09166353 0.4847069 -0.8716015 0.07328134 0.6106111 -0.7891919 0.06580483 0.4729762 -0.8787552 0.06389784 0.3430244 -0.9365031 0.07277542 0.6075589 -0.7912942 0.06874454 0.7241518 -0.6867076 0.06353694 0.8201968 -0.5690226 0.05908238 0.7252641 -0.6856458 0.06230562 0.835138 -0.5489689 0.03432035 0.3088998 -0.9508013 0.0236172 0.7254441 -0.6882631 -0.004976272 0.7670806 -0.6384053 -0.06345361 0.02222645 -0.9931849 -0.1144109 -0.01814037 -0.9937139 -0.1104702 0.03443288 -0.99328 -0.1104955 -0.02782738 -0.9938911 -0.1067999 0.009616971 -0.9940173 -0.1087987 -0.0338748 -0.9947766 -0.09629166 0.07161802 -0.9914938 -0.1086788 0.1393508 -0.9804408 -0.1389868 -0.1115906 -0.9832054 -0.1444115 0.07303559 -0.9895896 -0.1240096 0.2139483 -0.9715809 -0.1012759 0.143993 -0.9805835 -0.1331246 -0.1486166 -0.9816039 -0.1198623 -0.03598916 -0.9912773 -0.1267839 -0.04980212 -0.9910705 -0.1236891 0.09625786 -0.9885139 -0.1165113 -0.1561824 -0.9801861 -0.1218292 0.1984947 -0.97734 -0.07352858 0.0932697 -0.9943928 -0.04983836 0.2674854 -0.9631586 -0.02787792 -0.2008634 -0.9786497 -0.04357546 -0.0474224 -0.9973896 -0.05445468 -0.05508828 -0.9971328 -0.05188006 0.09839272 -0.9939973 -0.04783594 -0.1824846 -0.9824452 -0.03873944 0.2055225 -0.9785221 0.01597428 0.2608166 -0.9631391 0.06586253 0.09484124 -0.9934785 0.06329017 -0.2006517 -0.9773572 0.06717145 -0.05245167 -0.9967318 0.06143701 -0.058555 -0.9962376 0.06389075 0.09195166 -0.9938198 0.06218707 -0.1939828 -0.9785529 0.06931871 0.2171327 -0.9717853 0.09212386 0.09021621 -0.988613 0.1204387 0.2325942 -0.9660182 0.1127341 -0.0573613 -0.9910942 0.1201757 -0.1984999 -0.9722948 0.1234532 -0.1971392 -0.9725101 0.1239367 -0.06386166 -0.9903596 0.1229217 0.08164143 -0.9897166 0.1174555 0.2150517 -0.9688811 0.1225651 0.08178043 -0.9903826 0.1115995 0.2061313 -0.9731406 0.1025049 -0.06407248 -0.9917224 0.1112725 -0.1962262 -0.9737309 0.1155134 -0.07242578 -0.990735 0.114886 0.06958287 -0.9917576 0.1075877 -0.204531 -0.9723676 0.112554 0.2035446 -0.9735443 0.1038326 0.1783385 -0.9839017 -0.01152926 0.1800171 -0.9836072 -0.01051759 0.07048219 -0.9969515 0.03346687 -0.1852122 -0.982683 -0.005546748 -0.07327622 -0.996644 0.03648602 -0.190203 -0.981742 -0.002326846 -0.670276 -0.7180715 -0.1873593 -0.6822823 -0.7160937 -0.1473118 -0.4087826 -0.9035514 -0.1284198 -0.1441673 -0.9832908 -0.1111532 -0.3881579 -0.9097153 -0.1474843 -0.9847697 -0.1687281 -0.04194658 -0.6717287 -0.7305572 -0.122747 -0.1407263 -0.9835157 -0.1135477 -0.8733788 -0.4719702 -0.1202231 -0.8779516 -0.4590344 -0.1359722 -0.9748687 -0.200554 -0.09700083 -0.9731539 -0.2235477 -0.05475324 -0.3891031 -0.9064142 -0.1643546 -0.6643658 -0.7313831 -0.1539383 -0.4018971 -0.9031282 -0.1511234 -0.2100407 -0.9632198 -0.1676028 -0.1465646 -0.9790568 -0.1413035 -0.8675655 -0.4749327 -0.147543 -0.6556645 -0.7423657 -0.1378308 -0.9563325 -0.2642347 -0.1249327 -0.8504195 -0.5177144 -0.0935871 -0.9439692 -0.3286511 -0.03017717 -0.4022539 -0.9018362 -0.1577448 -0.6556087 -0.7423712 -0.1380667 -0.3146321 -0.9373261 -0.1497547 -0.1875213 -0.9752549 -0.1171053 -0.4297931 -0.8934189 -0.1306938 -0.8432412 -0.5217408 -0.129348 -0.6394886 -0.760192 -0.1147286 -0.8086596 -0.5858665 -0.0532006 -0.926697 -0.3638182 -0.09417545 -0.8931409 -0.4490832 0.024975 -0.6445479 -0.7589939 -0.09212017 -0.4285711 -0.8965194 -0.1121607 -0.2771731 -0.9544337 -0.1105964 -0.467616 -0.8805971 -0.07670795 -0.8045976 -0.5889114 -0.07619917 -0.6180959 -0.7835036 -0.06387215 -0.7468765 -0.6649137 0.008076965 -0.8763524 -0.4809654 -0.02605253 -0.8285298 -0.5537611 0.08298844 -0.3404068 -0.9401248 -0.01699233 -0.4630301 -0.8859011 -0.02797377 -0.6277521 -0.778277 -0.01456981 -0.4992783 -0.8664398 0.00183916 -0.3450877 -0.9383642 -0.0196821 -0.7467299 -0.6650904 0.007026314 -0.5959373 -0.8029583 0.01081061 -0.8142758 -0.5781531 0.05190289 -0.6872254 -0.7233883 0.0665633 -0.3563792 -0.9310505 0.07835125 -0.4917621 -0.8685612 0.06141287 -0.6045702 -0.793654 0.06788551 -0.3887188 -0.9190504 0.06514698 -0.5081037 -0.8581376 0.07369196 -0.6888192 -0.7201607 0.08304613 -0.5857957 -0.8064764 0.08024561 -0.6625515 -0.7418515 0.1033535 -0.7879109 -0.6068348 0.1046324 -0.7674785 -0.6300867 0.1181849 -0.5897548 -0.7982391 0.1224893 -0.5016837 -0.8568593 0.1187675 -0.5011004 -0.8572592 0.1183425 -0.3553683 -0.9277096 0.1143163 -0.5874758 -0.7997003 0.1239023 -0.663843 -0.7366797 0.1289016 -0.7708612 -0.6229084 0.1332606 -0.6709275 -0.7310877 0.1239641 -0.3641606 -0.9228441 0.1254827 -0.4975917 -0.8554283 0.1436836 -0.5883231 -0.7951263 0.1471402 -0.4892113 -0.861276 0.1373901 -0.3484679 -0.9273896 0.1360835 -0.5958569 -0.7903802 0.1423155 -0.6710246 -0.7263384 0.1488577 -0.7787315 -0.6151381 0.1232174 -0.7994905 -0.5824465 0.146871 -0.6942135 -0.7074778 0.1324496 -0.5958575 -0.7903929 0.1422432 -0.4891984 -0.8612653 0.1375037 -0.349034 -0.9300221 0.1150406 -0.4807637 -0.8670477 0.1307467 -0.3194627 -0.9389059 0.1280599 -0.6057654 -0.7840343 0.1354199 -0.6938535 -0.7056286 0.1437206 -0.7170727 -0.6855343 0.1258946 -0.7984415 -0.5860655 0.1379073 -0.6064985 -0.7877663 0.1076288 -0.4834536 -0.8696313 0.1000705 -0.3476943 -0.9330801 0.09203362 -0.4808058 -0.8713552 0.09780561 -0.8186941 -0.5632335 0.11184 -0.6139933 -0.78268 0.1020994 -0.7177509 -0.6873282 0.1114168 -0.7303447 -0.6756086 0.1007456 -0.8185417 -0.5635352 0.1114349 -0.3137619 -0.9488991 0.03382259 -0.8320398 -0.5494911 0.07595771 -0.6153153 -0.787351 0.0382837 -0.4966435 -0.8670454 -0.03972125 -0.4847958 -0.8742413 -0.02598762 -0.732422 -0.6806162 0.01788026 -0.7603782 -0.6492537 -0.01716756 -0.9989739 -0.02276909 -0.03915131 -0.9998551 -0.01475757 0.008491575 -0.9837526 -0.1786119 0.0181328 -0.9968516 0.0150671 -0.0778461 -0.9894355 -0.133372 0.05682879 -0.9759188 -0.2117553 -0.05236631 -0.9243676 -0.3749623 0.07034075 -0.9718721 -0.2344453 -0.02236479 -0.9901344 -0.1363146 0.03243869 -0.9739551 -0.2141646 0.07446569 -0.9237072 -0.3793855 0.05321329 -0.972276 -0.211982 0.09870713 -0.8940894 -0.4328998 0.1149004 -0.9651897 -0.2362111 0.1123083 -0.8948912 -0.4306931 0.1169326 -0.8867391 -0.4432659 0.1311832 -0.9620714 -0.234077 0.1400954 -0.9635618 -0.229346 0.137656 -0.8896767 -0.434579 0.1400594 -0.8998984 -0.4181339 0.1238834 -0.9633963 -0.2292665 0.1389403 -0.9679405 -0.2140197 0.1314797 -0.9005904 -0.4158365 0.1265586 -0.9139295 -0.397345 0.08276391 -0.9145741 -0.3960018 0.08207815 -0.9722402 -0.2156157 0.09087938 -0.9645407 -0.2423125 0.1046224 -0.9815933 -0.007431566 -0.1908388 -0.9828144 -0.00152117 -0.1845902 -0.9879508 -0.04628658 -0.1476857 -0.9923365 -0.002529203 -0.123539 -0.9942002 -0.03119117 -0.1029238 -0.9938874 7.71217e-7 -0.110399 -0.9941242 0.0289638 -0.1042997 -0.9929894 0.002681851 -0.1181734 -0.9879519 0.04625946 -0.1476857 + + + + + + + + + + + + + + +

631 0 0 0 632 0 1 1 0 1 631 1 2 2 0 2 1 2 3 3 2 3 1 3 3 4 4 4 5 4 2 5 3 5 5 5 6 6 4 6 3 6 631 7 625 7 1 7 1 8 7 8 3 8 7 9 1 9 625 9 8 10 3 10 7 10 3 11 8 11 6 11 9 12 6 12 8 12 625 13 622 13 7 13 7 14 10 14 8 14 10 15 7 15 622 15 11 16 8 16 10 16 8 17 11 17 9 17 12 18 9 18 11 18 622 19 619 19 10 19 13 19 10 19 619 19 10 20 13 20 11 20 11 21 14 21 12 21 14 22 11 22 13 22 15 23 12 23 14 23 619 24 616 24 13 24 13 25 16 25 14 25 16 26 13 26 616 26 17 27 14 27 16 27 17 28 18 28 15 28 14 29 17 29 15 29 19 30 18 30 17 30 616 31 20 31 16 31 21 32 16 32 20 32 16 33 21 33 17 33 23 34 22 34 19 34 17 35 23 35 19 35 17 36 21 36 23 36 24 37 22 37 23 37 25 38 5 38 26 38 27 39 25 39 26 39 30 40 28 40 29 40 25 41 30 41 29 41 30 42 25 42 27 42 5 43 4 43 26 43 31 44 29 44 28 44 32 45 26 45 4 45 26 46 32 46 27 46 33 47 27 47 32 47 27 48 33 48 30 48 4 49 6 49 32 49 34 50 28 50 30 50 28 51 34 51 31 51 30 52 35 52 34 52 35 53 30 53 33 53 36 54 32 54 6 54 32 55 36 55 33 55 37 56 33 56 36 56 33 57 37 57 35 57 34 58 38 58 31 58 38 59 34 59 35 59 39 60 31 60 38 60 35 61 40 61 38 61 40 62 35 62 37 62 36 63 41 63 37 63 41 64 36 64 6 64 6 65 9 65 41 65 42 66 37 66 41 66 37 67 42 67 40 67 38 68 43 68 39 68 43 69 38 69 40 69 44 70 40 70 42 70 40 71 44 71 43 71 45 72 39 72 43 72 41 73 46 73 42 73 46 74 41 74 9 74 47 75 42 75 46 75 42 76 47 76 44 76 43 77 48 77 45 77 48 78 43 78 44 78 44 79 49 79 48 79 49 80 44 80 47 80 46 81 9 81 12 81 50 82 46 82 12 82 46 83 50 83 47 83 47 84 51 84 49 84 51 85 47 85 50 85 52 86 48 86 49 86 48 87 52 87 45 87 53 88 49 88 51 88 49 89 53 89 52 89 54 90 45 90 52 90 50 91 55 91 51 91 55 92 50 92 12 92 51 93 56 93 53 93 56 94 51 94 55 94 52 95 57 95 54 95 57 96 52 96 53 96 58 97 53 97 56 97 53 98 58 98 57 98 59 99 54 99 57 99 55 100 12 100 15 100 60 101 55 101 15 101 55 102 60 102 56 102 56 103 61 103 58 103 61 104 56 104 60 104 62 105 57 105 58 105 57 106 62 106 59 106 58 107 63 107 62 107 63 108 58 108 61 108 15 109 18 109 60 109 64 110 60 110 18 110 60 111 64 111 61 111 61 112 65 112 63 112 65 113 61 113 64 113 66 114 62 114 63 114 66 115 67 115 59 115 62 116 66 116 59 116 68 117 63 117 65 117 63 118 68 118 66 118 18 119 19 119 64 119 64 120 69 120 65 120 69 121 64 121 19 121 65 122 70 122 68 122 70 123 65 123 69 123 71 124 72 124 67 124 66 125 71 125 67 125 71 126 66 126 68 126 73 127 68 127 70 127 68 128 73 128 71 128 19 129 22 129 69 129 74 130 69 130 22 130 74 131 75 131 70 131 69 132 74 132 70 132 76 133 72 133 71 133 70 134 75 134 73 134 22 135 24 135 74 135 71 136 73 136 77 136 71 137 77 137 76 137 78 138 77 138 73 138 78 139 73 139 75 139 79 140 78 140 75 140 83 141 29 141 31 141 83 142 81 142 82 142 29 143 83 143 82 143 84 144 82 144 81 144 84 145 85 145 86 145 84 146 86 146 82 146 87 147 85 147 84 147 31 148 39 148 83 148 81 149 88 149 84 149 88 150 81 150 83 150 89 151 83 151 39 151 83 152 89 152 88 152 84 153 90 153 87 153 90 154 84 154 88 154 91 155 87 155 90 155 88 156 92 156 90 156 92 157 88 157 89 157 89 158 39 158 45 158 93 159 89 159 45 159 89 160 93 160 92 160 90 161 94 161 91 161 94 162 90 162 92 162 95 163 91 163 94 163 45 164 54 164 93 164 92 165 96 165 94 165 96 166 92 166 93 166 93 167 97 167 96 167 97 168 93 168 54 168 98 169 94 169 96 169 94 170 98 170 95 170 99 171 95 171 98 171 54 172 59 172 97 172 96 173 100 173 98 173 100 174 96 174 97 174 97 175 101 175 100 175 101 176 97 176 59 176 98 177 102 177 99 177 102 178 98 178 100 178 103 179 99 179 102 179 59 180 67 180 101 180 100 181 104 181 102 181 104 182 100 182 101 182 101 183 105 183 104 183 105 184 101 184 67 184 106 185 107 185 103 185 102 186 106 186 103 186 106 187 102 187 104 187 67 188 72 188 105 188 108 189 107 189 106 189 104 190 109 190 106 190 109 191 104 191 105 191 110 192 109 192 105 192 110 193 105 193 72 193 106 194 109 194 108 194 72 195 76 195 110 195 111 196 108 196 109 196 113 197 114 197 112 197 115 198 113 198 112 198 86 199 85 199 116 199 118 200 114 200 113 200 119 201 113 201 115 201 113 202 119 202 118 202 115 203 120 203 119 203 120 204 115 204 117 204 121 205 116 205 85 205 116 206 121 206 117 206 117 207 122 207 120 207 122 208 117 208 121 208 123 209 119 209 120 209 119 210 123 210 118 210 120 211 124 211 123 211 124 212 120 212 122 212 121 213 125 213 122 213 125 214 121 214 85 214 122 215 126 215 124 215 126 216 122 216 125 216 85 217 87 217 125 217 127 218 118 218 123 218 128 219 123 219 124 219 123 220 128 220 127 220 124 221 129 221 128 221 129 222 124 222 126 222 130 223 125 223 87 223 125 224 130 224 126 224 131 225 126 225 130 225 126 226 131 226 129 226 87 227 91 227 130 227 128 228 132 228 127 228 132 229 128 229 129 229 133 230 129 230 131 230 129 231 133 231 132 231 130 232 134 232 131 232 134 233 130 233 91 233 135 234 131 234 134 234 131 235 135 235 133 235 136 236 127 236 132 236 137 237 132 237 133 237 132 238 137 238 136 238 133 239 138 239 137 239 138 240 133 240 135 240 134 241 139 241 135 241 139 242 134 242 91 242 140 243 135 243 139 243 135 244 140 244 138 244 91 245 95 245 139 245 137 246 141 246 136 246 141 247 137 247 138 247 142 248 136 248 141 248 138 249 143 249 141 249 143 250 138 250 140 250 144 251 139 251 95 251 139 252 144 252 140 252 145 253 140 253 144 253 140 254 145 254 143 254 95 255 99 255 144 255 146 256 141 256 143 256 141 257 146 257 142 257 143 258 147 258 146 258 147 259 143 259 145 259 144 260 148 260 145 260 148 261 144 261 99 261 149 262 145 262 148 262 145 263 149 263 147 263 150 264 142 264 146 264 146 265 151 265 150 265 151 266 146 266 147 266 147 267 152 267 151 267 152 268 147 268 149 268 148 269 153 269 149 269 148 270 99 270 103 270 153 271 148 271 103 271 154 272 149 272 153 272 149 273 154 273 152 273 155 274 151 274 152 274 155 275 156 275 150 275 151 276 155 276 150 276 152 277 157 277 155 277 157 278 152 278 154 278 153 279 103 279 107 279 158 280 153 280 107 280 153 281 158 281 154 281 154 282 159 282 157 282 159 283 154 283 158 283 160 284 156 284 155 284 155 285 161 285 160 285 161 286 155 286 157 286 157 287 162 287 161 287 162 288 157 288 159 288 158 289 163 289 159 289 158 290 107 290 108 290 163 291 158 291 108 291 164 292 159 292 163 292 159 293 164 293 162 293 161 294 162 294 165 294 165 295 166 295 160 295 161 296 165 296 160 296 167 297 162 297 164 297 167 298 165 298 162 298 108 299 111 299 163 299 168 300 163 300 111 300 163 301 168 301 164 301 164 302 169 302 167 302 164 303 168 303 169 303 170 304 167 304 169 304 171 305 462 305 172 305 463 306 462 306 171 306 173 307 171 307 172 307 114 308 173 308 172 308 173 309 114 309 118 309 118 310 127 310 173 310 174 311 171 311 173 311 171 312 174 312 463 312 175 313 463 313 174 313 173 314 176 314 174 314 176 315 173 315 127 315 127 316 136 316 176 316 177 317 174 317 176 317 174 318 177 318 175 318 178 319 175 319 177 319 176 320 179 320 177 320 179 321 176 321 136 321 136 322 142 322 179 322 180 323 177 323 179 323 177 324 180 324 178 324 181 325 178 325 180 325 179 326 182 326 180 326 182 327 179 327 142 327 142 328 150 328 182 328 180 329 183 329 181 329 183 330 180 330 182 330 184 331 181 331 183 331 182 332 185 332 183 332 182 333 150 333 156 333 185 334 182 334 156 334 156 335 160 335 185 335 183 336 186 336 184 336 186 337 183 337 185 337 187 338 185 338 160 338 187 339 186 339 185 339 160 340 166 340 187 340 454 341 172 341 462 341 190 342 114 342 172 342 190 341 172 341 454 341 191 343 112 343 114 343 191 344 114 344 190 344 112 345 192 345 86 345 192 346 112 346 191 346 86 347 193 347 82 347 193 348 86 348 192 348 454 349 450 349 190 349 194 350 190 350 450 350 190 351 194 351 191 351 191 352 195 352 192 352 195 353 191 353 194 353 196 354 192 354 195 354 192 355 196 355 193 355 193 356 197 356 82 356 197 357 193 357 196 357 450 358 446 358 194 358 198 359 194 359 446 359 194 360 198 360 195 360 199 361 195 361 198 361 195 362 199 362 196 362 200 363 196 363 199 363 196 364 200 364 197 364 201 365 197 365 200 365 197 366 201 366 82 366 446 367 442 367 198 367 202 368 198 368 442 368 198 369 202 369 199 369 203 370 199 370 202 370 199 371 203 371 200 371 200 372 204 372 201 372 204 373 200 373 203 373 201 374 205 374 82 374 205 375 201 375 204 375 442 376 438 376 202 376 206 377 202 377 438 377 202 378 206 378 203 378 207 379 203 379 206 379 203 380 207 380 204 380 208 381 204 381 207 381 204 382 208 382 205 382 209 383 205 383 208 383 205 384 209 384 82 384 438 385 434 385 206 385 210 385 206 385 434 385 206 386 210 386 207 386 207 387 211 387 208 387 211 388 207 388 210 388 212 389 208 389 211 389 208 390 212 390 209 390 209 391 213 391 82 391 213 392 209 392 212 392 434 393 430 393 210 393 214 394 210 394 430 394 210 395 214 395 211 395 211 396 215 396 212 396 215 397 211 397 214 397 216 398 212 398 215 398 212 399 216 399 213 399 217 400 213 400 216 400 213 401 217 401 82 401 430 402 426 402 214 402 214 403 218 403 215 403 218 404 214 404 426 404 215 405 219 405 216 405 219 406 215 406 218 406 220 407 216 407 219 407 216 408 220 408 217 408 221 409 217 409 220 409 217 410 221 410 82 410 426 411 632 411 218 411 632 412 0 412 218 412 219 413 5 413 220 413 221 414 25 414 29 414 82 415 221 415 29 415 25 416 220 416 5 416 220 417 25 417 221 417 222 418 223 418 224 418 225 419 222 419 224 419 422 420 224 420 223 420 226 421 224 421 422 421 422 422 419 422 226 422 227 423 226 423 419 423 419 424 418 424 227 424 228 425 227 425 418 425 418 426 417 426 228 426 229 427 228 427 417 427 417 427 416 427 229 427 230 428 229 428 416 428 416 429 415 429 230 429 231 430 230 430 415 430 415 431 414 431 231 431 232 432 231 432 414 432 414 433 413 433 232 433 233 434 232 434 413 434 413 435 412 435 233 435 234 436 233 436 412 436 412 437 411 437 234 437 235 438 234 438 411 438 411 439 410 439 235 439 236 440 235 440 410 440 410 441 409 441 236 441 237 442 236 442 409 442 409 443 408 443 237 443 238 444 237 444 408 444 408 445 407 445 238 445 239 446 238 446 407 446 407 447 406 447 239 447 240 448 239 448 406 448 406 449 405 449 240 449 240 450 405 450 188 450 240 451 188 451 241 451 240 452 241 452 189 452 240 453 189 453 80 453 242 454 240 454 80 454 244 455 225 455 224 455 245 456 244 456 224 456 247 457 246 457 245 457 224 458 226 458 245 458 245 459 226 459 227 459 248 460 245 460 227 460 248 461 249 461 247 461 245 462 248 462 247 462 250 463 249 463 248 463 227 464 228 464 248 464 251 465 252 465 250 465 248 466 251 466 250 466 251 467 248 467 228 467 228 468 229 468 251 468 253 469 252 469 251 469 251 470 229 470 230 470 254 471 251 471 230 471 251 472 254 472 253 472 255 473 253 473 254 473 230 474 231 474 254 474 254 475 231 475 232 475 256 476 254 476 232 476 256 477 257 477 255 477 254 478 256 478 255 478 232 479 233 479 256 479 258 480 257 480 256 480 256 481 233 481 234 481 259 482 256 482 234 482 259 483 260 483 258 483 256 484 259 484 258 484 234 485 235 485 259 485 261 486 260 486 259 486 259 487 235 487 236 487 262 488 259 488 236 488 259 489 262 489 261 489 263 490 261 490 262 490 236 491 237 491 262 491 264 492 265 492 263 492 262 493 264 493 263 493 264 494 262 494 237 494 237 495 238 495 264 495 266 496 265 496 264 496 267 497 268 497 266 497 264 498 267 498 266 498 264 499 238 499 239 499 267 500 264 500 239 500 239 501 240 501 267 501 269 502 268 502 267 502 267 503 242 503 269 503 267 504 240 504 242 504 270 505 269 505 242 505 79 506 243 506 271 506 246 507 271 507 243 507 272 508 271 508 246 508 246 509 247 509 272 509 273 510 272 510 247 510 247 511 249 511 273 511 274 512 273 512 249 512 249 513 250 513 274 513 274 514 250 514 252 514 275 515 274 515 252 515 252 516 253 516 275 516 276 517 275 517 253 517 253 518 255 518 276 518 277 519 276 519 255 519 255 520 257 520 277 520 278 521 277 521 257 521 257 522 258 522 278 522 279 523 278 523 258 523 258 524 260 524 279 524 280 525 279 525 260 525 260 526 261 526 280 526 281 527 280 527 261 527 261 528 263 528 281 528 281 529 263 529 265 529 282 530 281 530 265 530 265 531 266 531 282 531 283 532 282 532 266 532 266 533 268 533 283 533 284 534 283 534 268 534 268 535 269 535 284 535 285 536 284 536 269 536 269 537 270 537 285 537 285 538 270 538 286 538 284 539 285 539 287 539 288 540 289 540 290 540 288 541 290 541 287 541 288 542 287 542 285 542 285 543 286 543 288 543 291 544 289 544 288 544 288 545 292 545 291 545 288 546 286 546 292 546 293 547 291 547 292 547 294 548 293 548 292 548 292 549 168 549 294 549 294 550 168 550 295 550 297 551 295 551 296 551 300 552 299 552 298 552 298 553 301 553 300 553 302 554 300 554 301 554 301 555 303 555 302 555 304 556 302 556 303 556 79 557 271 557 303 557 303 558 271 558 272 558 303 559 272 559 305 559 303 560 305 560 304 560 306 561 304 561 305 561 297 562 299 562 295 562 294 563 295 563 299 563 299 564 300 564 294 564 293 565 294 565 300 565 300 566 302 566 293 566 291 567 293 567 302 567 302 568 304 568 291 568 289 569 291 569 304 569 304 570 306 570 289 570 290 571 289 571 306 571 306 572 307 572 290 572 308 573 290 573 307 573 307 574 309 574 308 574 310 575 308 575 309 575 309 576 311 576 310 576 312 577 310 577 311 577 311 578 313 578 312 578 314 579 312 579 313 579 313 580 315 580 314 580 316 580 314 580 315 580 272 581 273 581 305 581 317 582 305 582 273 582 317 583 307 583 306 583 317 584 306 584 305 584 273 585 274 585 317 585 309 586 307 586 317 586 318 587 311 587 309 587 317 588 318 588 309 588 317 589 274 589 275 589 318 590 317 590 275 590 275 591 276 591 318 591 313 592 311 592 318 592 318 593 276 593 277 593 319 594 318 594 277 594 318 595 319 595 313 595 315 596 313 596 319 596 277 597 278 597 319 597 320 598 319 598 278 598 320 599 316 599 315 599 319 600 320 600 315 600 278 601 279 601 320 601 314 602 316 602 320 602 320 603 279 603 280 603 321 604 320 604 280 604 320 605 321 605 314 605 312 606 314 606 321 606 280 607 281 607 321 607 322 608 310 608 312 608 321 609 322 609 312 609 321 610 281 610 282 610 322 611 321 611 282 611 308 612 310 612 322 612 282 613 283 613 322 613 322 614 283 614 284 614 322 615 284 615 287 615 322 616 287 616 308 616 290 617 308 617 287 617 167 618 270 618 242 618 242 619 165 619 167 619 170 620 286 620 270 620 170 621 270 621 167 621 292 622 286 622 170 622 168 623 292 623 170 623 168 624 111 624 295 624 170 625 169 625 168 625 301 626 298 626 303 626 78 627 303 627 298 627 303 628 78 628 79 628 297 629 76 629 298 629 298 630 77 630 78 630 298 631 76 631 77 631 75 632 243 632 79 632 24 633 225 633 244 633 244 634 74 634 24 634 74 635 244 635 243 635 243 636 75 636 74 636 225 637 24 637 222 637 186 638 241 638 188 638 186 639 187 639 241 639 187 640 189 640 241 640 166 641 189 641 187 641 80 642 189 642 166 642 80 643 166 643 165 643 80 644 165 644 242 644 109 645 295 645 111 645 109 646 296 646 295 646 109 647 110 647 296 647 76 648 296 648 110 648 76 649 297 649 296 649 297 650 298 650 299 650 244 651 245 651 246 651 243 652 244 652 246 652 5 653 219 653 218 653 2 654 5 654 218 654 0 655 2 655 218 655 86 656 117 656 112 656 112 657 117 657 115 657 86 658 116 658 117 658 548 659 517 659 518 659 522 660 519 660 517 660 548 661 522 661 517 661 632 662 426 662 630 662 630 663 426 663 627 663 627 664 426 664 425 664 402 665 399 665 401 665 401 666 399 666 400 666 348 667 346 667 347 667 558 668 349 668 348 668 558 669 524 669 349 669 525 670 349 670 524 670 525 671 350 671 349 671 525 672 523 672 350 672 554 673 403 673 469 673 554 674 469 674 468 674 554 675 468 675 455 675 468 676 456 676 455 676 456 677 404 677 455 677 186 678 404 678 456 678 186 679 188 679 404 679 420 680 421 680 610 680 402 681 560 681 559 681 560 682 402 682 401 682 401 683 610 683 560 683 610 684 401 684 420 684 559 685 555 685 402 685 347 686 557 686 558 686 347 687 556 687 557 687 348 688 347 688 558 688 342 689 555 689 556 689 556 690 347 690 342 690 344 691 342 691 347 691 464 692 466 692 465 692 466 693 350 693 523 693 466 694 464 694 353 694 353 695 464 695 359 695 464 696 467 696 375 696 464 697 375 697 359 697 403 698 467 698 469 698 467 699 403 699 375 699 355 700 358 700 337 700 323 701 337 701 358 701 323 702 358 702 361 702 323 703 361 703 362 703 363 704 323 704 362 704 337 705 323 705 335 705 323 706 363 706 324 706 324 707 363 707 364 707 324 708 333 708 323 708 323 709 333 709 335 709 365 710 324 710 364 710 333 711 324 711 331 711 325 712 331 712 324 712 324 713 365 713 325 713 325 714 365 714 366 714 331 715 325 715 329 715 367 716 325 716 366 716 326 717 330 717 325 717 325 718 330 718 329 718 325 719 367 719 326 719 368 720 326 720 367 720 330 721 326 721 332 721 327 722 332 722 326 722 326 723 368 723 327 723 327 724 368 724 369 724 332 725 327 725 334 725 370 726 327 726 369 726 327 727 370 727 328 727 328 728 370 728 371 728 328 729 336 729 327 729 327 730 336 730 334 730 336 731 328 731 338 731 372 732 328 732 371 732 328 733 340 733 339 733 328 734 339 734 338 734 328 735 372 735 340 735 373 736 340 736 372 736 329 737 330 737 331 737 332 738 331 738 330 738 331 739 332 739 333 739 334 740 333 740 332 740 333 741 334 741 335 741 336 742 335 742 334 742 335 743 336 743 337 743 338 744 337 744 336 744 337 745 338 745 355 745 339 746 355 746 338 746 355 747 339 747 356 747 341 748 356 748 339 748 356 749 341 749 354 749 343 750 354 750 341 750 354 751 343 751 352 751 345 752 352 752 343 752 352 753 345 753 351 753 346 754 351 754 345 754 351 755 346 755 350 755 348 756 350 756 346 756 339 757 340 757 341 757 342 758 341 758 340 758 342 759 340 759 373 759 342 760 373 760 374 760 555 761 342 761 374 761 341 762 342 762 343 762 344 763 343 763 342 763 343 764 344 764 345 764 347 765 345 765 344 765 345 766 347 766 346 766 348 767 349 767 350 767 351 768 350 768 466 768 353 769 351 769 466 769 351 770 353 770 352 770 352 771 353 771 354 771 357 772 353 772 359 772 357 773 354 773 353 773 354 774 357 774 356 774 360 775 357 775 359 775 357 776 360 776 358 776 357 777 358 777 355 777 357 778 355 778 356 778 361 779 358 779 360 779 360 780 359 780 375 780 376 781 360 781 375 781 360 782 376 782 361 782 377 783 361 783 376 783 361 784 377 784 362 784 379 785 362 785 377 785 362 786 379 786 363 786 380 787 363 787 379 787 363 788 380 788 364 788 364 789 380 789 382 789 384 790 364 790 382 790 364 791 384 791 365 791 385 792 365 792 384 792 365 793 385 793 366 793 387 794 366 794 385 794 366 795 387 795 367 795 388 796 367 796 387 796 367 797 388 797 368 797 390 798 368 798 388 798 368 799 390 799 369 799 392 800 369 800 390 800 369 801 392 801 370 801 393 802 370 802 392 802 370 803 393 803 371 803 371 804 393 804 395 804 396 805 371 805 395 805 371 806 396 806 372 806 398 807 372 807 396 807 372 808 398 808 373 808 399 809 373 809 398 809 373 810 399 810 374 810 399 811 402 811 374 811 555 812 374 812 402 812 375 813 403 813 376 813 378 814 403 814 405 814 378 815 376 815 403 815 376 816 378 816 377 816 406 817 378 817 405 817 378 818 406 818 381 818 381 819 406 819 407 819 381 820 379 820 378 820 378 821 379 821 377 821 379 822 381 822 380 822 408 823 381 823 407 823 381 824 408 824 383 824 383 825 382 825 381 825 381 826 382 826 380 826 409 827 383 827 408 827 382 828 383 828 384 828 386 829 384 829 383 829 383 830 409 830 386 830 386 831 409 831 410 831 384 832 386 832 385 832 411 833 386 833 410 833 389 834 387 834 386 834 386 835 387 835 385 835 386 836 411 836 389 836 389 837 411 837 412 837 387 838 389 838 388 838 413 839 389 839 412 839 391 840 390 840 389 840 389 841 390 841 388 841 389 842 413 842 391 842 391 843 413 843 414 843 415 844 391 844 414 844 390 845 391 845 392 845 394 846 392 846 391 846 391 847 415 847 394 847 394 848 415 848 416 848 392 849 394 849 393 849 417 850 394 850 416 850 394 851 417 851 397 851 397 852 395 852 394 852 394 853 395 853 393 853 418 854 397 854 417 854 395 855 397 855 396 855 400 856 398 856 397 856 397 857 398 857 396 857 397 858 418 858 400 858 400 859 418 859 419 859 422 860 400 860 419 860 398 861 400 861 399 861 400 862 422 862 401 862 401 863 422 863 420 863 403 864 554 864 405 864 405 865 554 865 455 865 405 866 455 866 404 866 405 867 404 867 188 867 424 868 423 868 609 868 609 869 627 869 424 869 552 870 605 870 423 870 423 871 605 871 609 871 425 872 424 872 627 872 427 873 552 873 423 873 423 874 424 874 427 874 428 875 427 875 424 875 424 876 425 876 428 876 425 877 426 877 429 877 429 878 428 878 425 878 430 879 429 879 426 879 431 880 552 880 427 880 427 881 428 881 431 881 432 882 431 882 428 882 428 883 429 883 432 883 429 884 430 884 433 884 433 885 432 885 429 885 434 886 433 886 430 886 431 887 432 887 435 887 435 888 552 888 431 888 436 889 435 889 432 889 432 890 433 890 436 890 433 891 434 891 437 891 437 892 436 892 433 892 438 893 437 893 434 893 439 894 552 894 435 894 435 895 436 895 439 895 440 896 439 896 436 896 436 897 437 897 440 897 441 898 440 898 437 898 437 899 438 899 441 899 442 900 441 900 438 900 439 901 440 901 443 901 443 902 552 902 439 902 440 903 441 903 444 903 444 904 443 904 440 904 445 905 444 905 441 905 441 906 442 906 445 906 446 907 445 907 442 907 447 908 552 908 443 908 443 909 444 909 447 909 448 910 447 910 444 910 444 911 445 911 448 911 449 912 448 912 445 912 445 913 446 913 449 913 450 914 449 914 446 914 447 915 448 915 451 915 451 916 552 916 447 916 452 917 451 917 448 917 448 918 449 918 452 918 449 919 450 919 453 919 453 920 452 920 449 920 454 921 453 921 450 921 451 922 452 922 548 922 548 923 552 923 451 923 452 924 453 924 522 924 522 925 548 925 452 925 453 926 454 926 520 926 453 927 520 927 522 927 454 928 462 928 520 928 474 929 456 929 468 929 456 930 457 930 186 930 456 931 474 931 457 931 186 932 457 932 184 932 478 933 457 933 474 933 457 934 478 934 458 934 458 935 478 935 484 935 458 936 184 936 457 936 184 937 458 937 181 937 492 938 458 938 484 938 458 939 492 939 459 939 459 940 181 940 458 940 181 941 459 941 178 941 498 942 459 942 492 942 459 943 498 943 460 943 460 944 178 944 459 944 178 945 460 945 175 945 507 946 460 946 498 946 460 947 507 947 461 947 461 948 175 948 460 948 175 949 461 949 463 949 516 950 461 950 507 950 461 951 516 951 520 951 520 952 462 952 461 952 461 953 462 953 463 953 464 954 465 954 467 954 470 955 465 955 466 955 470 956 467 956 465 956 471 957 470 957 466 957 466 958 523 958 471 958 526 959 471 959 523 959 467 960 472 960 469 960 467 961 470 961 472 961 473 962 474 962 469 962 469 963 474 963 468 963 473 964 469 964 472 964 475 965 472 965 470 965 470 966 471 966 475 966 471 967 526 967 476 967 476 968 526 968 527 968 476 969 475 969 471 969 472 970 475 970 477 970 477 971 473 971 472 971 473 972 477 972 479 972 479 973 474 973 473 973 474 974 479 974 478 974 475 975 476 975 480 975 480 976 477 976 475 976 481 977 480 977 476 977 476 978 527 978 481 978 481 979 527 979 531 979 477 980 480 980 482 980 482 981 479 981 477 981 483 982 484 982 479 982 479 983 484 983 478 983 479 984 482 984 483 984 485 985 482 985 480 985 480 986 481 986 485 986 481 987 531 987 486 987 486 988 531 988 535 988 486 989 485 989 481 989 482 990 485 990 487 990 487 991 483 991 482 991 483 992 487 992 488 992 488 993 484 993 483 993 484 994 488 994 492 994 489 995 487 995 485 995 485 996 486 996 489 996 486 997 535 997 490 997 490 998 489 998 486 998 487 999 489 999 491 999 491 1000 488 1000 487 1000 493 1001 492 1001 488 1001 488 1002 491 1002 493 1002 539 1003 490 1003 535 1003 494 1004 491 1004 489 1004 489 1005 490 1005 494 1005 495 1006 494 1006 490 1006 490 1007 539 1007 495 1007 491 1008 494 1008 496 1008 496 1009 493 1009 491 1009 492 1010 493 1010 498 1010 493 1011 496 1011 497 1011 497 1012 498 1012 493 1012 543 1013 495 1013 539 1013 499 1014 496 1014 494 1014 494 1015 495 1015 499 1015 495 1016 543 1016 500 1016 500 1017 499 1017 495 1017 496 1018 499 1018 501 1018 501 1019 497 1019 496 1019 502 1020 498 1020 497 1020 497 1021 501 1021 502 1021 498 1022 502 1022 507 1022 503 1023 501 1023 499 1023 499 1024 500 1024 503 1024 500 1025 543 1025 504 1025 504 1026 503 1026 500 1026 505 1027 502 1027 501 1027 501 1028 503 1028 505 1028 502 1029 505 1029 506 1029 506 1030 507 1030 502 1030 547 1031 504 1031 543 1031 508 1032 505 1032 503 1032 503 1033 504 1033 508 1033 509 1034 508 1034 504 1034 504 1035 547 1035 509 1035 505 1036 508 1036 510 1036 510 1037 506 1037 505 1037 511 1038 507 1038 506 1038 506 1039 510 1039 511 1039 507 1040 511 1040 516 1040 549 1041 509 1041 547 1041 508 1042 509 1042 512 1042 512 1043 510 1043 508 1043 509 1044 549 1044 513 1044 513 1045 512 1045 509 1045 510 1046 512 1046 514 1046 514 1047 511 1047 510 1047 515 1048 516 1048 511 1048 511 1049 514 1049 515 1049 512 1050 513 1050 517 1050 517 1051 514 1051 512 1051 518 1052 517 1052 513 1052 513 1053 549 1053 518 1053 514 1054 517 1054 519 1054 519 1055 515 1055 514 1055 521 1056 516 1056 515 1056 515 1057 519 1057 521 1057 516 1058 521 1058 520 1058 548 1059 518 1059 549 1059 519 1060 522 1060 521 1060 521 1061 522 1061 520 1061 523 1062 525 1062 526 1062 562 1063 524 1063 558 1063 528 1064 526 1064 525 1064 524 1065 562 1065 529 1065 524 1066 529 1066 525 1066 525 1067 529 1067 530 1067 530 1068 528 1068 525 1068 526 1069 528 1069 527 1069 567 1070 529 1070 562 1070 528 1071 530 1071 532 1071 532 1072 531 1072 528 1072 528 1073 531 1073 527 1073 529 1074 567 1074 533 1074 533 1075 530 1075 529 1075 530 1076 533 1076 534 1076 534 1077 532 1077 530 1077 575 1078 533 1078 567 1078 531 1079 532 1079 535 1079 532 1080 534 1080 536 1080 536 1081 535 1081 532 1081 533 1082 575 1082 537 1082 537 1083 534 1083 533 1083 534 1084 537 1084 538 1084 538 1085 536 1085 534 1085 580 1086 537 1086 575 1086 535 1087 536 1087 539 1087 540 1088 539 1088 536 1088 536 1089 538 1089 540 1089 537 1090 580 1090 541 1090 541 1091 538 1091 537 1091 538 1092 541 1092 542 1092 542 1093 540 1093 538 1093 589 1094 541 1094 580 1094 539 1095 540 1095 543 1095 540 1096 542 1096 544 1096 544 1097 543 1097 540 1097 545 1098 542 1098 541 1098 541 1099 589 1099 545 1099 545 1100 589 1100 595 1100 542 1101 545 1101 546 1101 546 1102 544 1102 542 1102 543 1103 544 1103 547 1103 544 1104 546 1104 550 1104 550 1105 547 1105 544 1105 551 1106 546 1106 545 1106 545 1107 595 1107 551 1107 546 1108 551 1108 553 1108 553 1109 550 1109 546 1109 603 1110 551 1110 595 1110 547 1111 550 1111 549 1111 550 1112 552 1112 548 1112 550 1113 548 1113 549 1113 550 1114 553 1114 552 1114 605 1115 552 1115 551 1115 551 1116 552 1116 553 1116 551 1117 603 1117 605 1117 555 1118 559 1118 556 1118 556 1119 559 1119 561 1119 556 1120 561 1120 557 1120 563 1121 558 1121 557 1121 563 1122 557 1122 561 1122 611 1123 560 1123 610 1123 564 1124 561 1124 559 1124 558 1125 563 1125 562 1125 565 1126 564 1126 560 1126 560 1127 564 1127 559 1127 560 1128 611 1128 565 1128 613 1129 565 1129 611 1129 566 1130 563 1130 561 1130 561 1131 564 1131 566 1131 563 1132 566 1132 568 1132 568 1133 567 1133 563 1133 563 1134 567 1134 562 1134 564 1135 565 1135 569 1135 569 1136 566 1136 564 1136 565 1137 613 1137 570 1137 570 1138 569 1138 565 1138 614 1139 570 1139 613 1139 571 1140 568 1140 566 1140 566 1141 569 1141 571 1141 572 1142 575 1142 568 1142 568 1143 575 1143 567 1143 568 1144 571 1144 572 1144 569 1145 570 1145 573 1145 573 1146 571 1146 569 1146 574 1147 573 1147 570 1147 570 1148 614 1148 574 1148 617 1149 574 1149 614 1149 571 1150 573 1150 576 1150 576 1151 572 1151 571 1151 577 1152 575 1152 572 1152 572 1153 576 1153 577 1153 573 1154 574 1154 578 1154 578 1155 576 1155 573 1155 579 1156 578 1156 574 1156 574 1157 617 1157 579 1157 579 1158 617 1158 620 1158 575 1159 577 1159 580 1159 581 1160 577 1160 576 1160 576 1161 578 1161 581 1161 577 1162 581 1162 582 1162 582 1163 580 1163 577 1163 578 1164 579 1164 583 1164 583 1165 581 1165 578 1165 579 1166 620 1166 584 1166 584 1167 583 1167 579 1167 580 1168 582 1168 589 1168 585 1169 582 1169 581 1169 581 1170 583 1170 585 1170 586 1171 589 1171 582 1171 582 1172 585 1172 586 1172 583 1173 584 1173 587 1173 587 1174 585 1174 583 1174 588 1175 587 1175 584 1175 584 1176 620 1176 588 1176 588 1177 620 1177 623 1177 585 1178 587 1178 590 1178 590 1179 586 1179 585 1179 586 1180 590 1180 591 1180 591 1181 589 1181 586 1181 592 1182 590 1182 587 1182 587 1183 588 1183 592 1183 588 1184 623 1184 593 1184 593 1185 592 1185 588 1185 589 1186 591 1186 595 1186 594 1187 591 1187 590 1187 590 1188 592 1188 594 1188 591 1189 594 1189 596 1189 596 1190 595 1190 591 1190 597 1191 594 1191 592 1191 592 1192 593 1192 597 1192 626 1193 593 1193 623 1193 593 1194 626 1194 598 1194 598 1195 597 1195 593 1195 594 1196 597 1196 599 1196 599 1197 596 1197 594 1197 595 1198 596 1198 603 1198 596 1199 599 1199 600 1199 600 1200 603 1200 596 1200 601 1201 599 1201 597 1201 597 1202 598 1202 601 1202 602 1203 601 1203 598 1203 598 1204 626 1204 602 1204 599 1205 601 1205 604 1205 604 1206 600 1206 599 1206 606 1207 603 1207 600 1207 600 1208 604 1208 606 1208 628 1209 602 1209 626 1209 607 1210 604 1210 601 1210 601 1211 602 1211 607 1211 608 1212 607 1212 602 1212 602 1213 628 1213 608 1213 603 1214 606 1214 605 1214 627 1215 608 1215 628 1215 604 1216 607 1216 609 1216 609 1217 605 1217 604 1217 604 1218 605 1218 606 1218 607 1219 608 1219 609 1219 609 1220 608 1220 627 1220 610 1221 612 1221 611 1221 615 1222 612 1222 20 1222 615 1223 613 1223 612 1223 612 1224 613 1224 611 1224 616 1225 615 1225 20 1225 613 1226 615 1226 614 1226 618 1227 617 1227 615 1227 615 1228 617 1228 614 1228 615 1229 616 1229 618 1229 619 1230 618 1230 616 1230 617 1231 618 1231 620 1231 618 1232 619 1232 621 1232 621 1233 620 1233 618 1233 622 1234 621 1234 619 1234 620 1235 621 1235 623 1235 624 1236 623 1236 621 1236 621 1237 622 1237 624 1237 625 1238 624 1238 622 1238 623 1239 624 1239 626 1239 629 1240 626 1240 624 1240 624 1241 625 1241 629 1241 631 1242 629 1242 625 1242 626 1243 629 1243 628 1243 630 1244 627 1244 629 1244 629 1245 627 1245 628 1245 629 1246 631 1246 630 1246 631 1247 632 1247 630 1247 420 1248 422 1248 421 1248 223 1249 421 1249 422 1249 421 1250 612 1250 610 1250 223 1251 612 1251 421 1251 223 1252 20 1252 612 1252 20 1253 223 1253 21 1253 21 1254 223 1254 23 1254 23 1255 223 1255 222 1255 23 1256 222 1256 24 1256

+
+
+
+
+ + + + 9.99999e-4 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + -0.2908648 -0.7711008 0.5663932 4.076245 0.9551711 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054209 -0.6141704 -6.925791 -4.01133e-9 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_middle/th_middle_E4.dae b/URDFs/sr_description/meshes/components/th_middle/th_middle_E4.dae new file mode 100644 index 0000000..33d02f2 --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_middle/th_middle_E4.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:04.601049 + 2012-07-23T02:14:04.601062 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -10.82211 1.89451 0.02984 -10.52279 1.19648 4.40604 -10.43772 3.42460 0.02983 -10.01191 3.48500 4.44190 -9.24738 5.48540 3.30954 -9.53206 5.50770 0.02984 -8.76916 5.54120 6.52921 -9.89934 1.32759 8.78240 -9.34524 3.61260 8.85396 -8.04629 5.52890 11.15913 -9.26471 1.36724 13.15861 -8.71246 3.57270 13.26610 -7.62288 5.23110 15.49638 -8.79618 1.20098 17.53489 -8.36209 3.12530 17.67809 -7.64989 4.79500 18.13671 -8.53313 0.87560 21.91118 -8.31577 2.41180 22.09022 -7.82107 4.31860 20.58139 -8.02359 3.94460 22.84329 -8.30538 -0.79062 26.28739 -8.30538 0.70052 26.28740 -8.18404 3.75820 24.93399 -8.28854 1.69868 26.40406 -8.25863 3.80240 26.86291 -7.06228 8.40020 0.02984 -8.38620 6.91280 2.41682 -7.24683 8.13770 2.46228 -4.47194 9.96990 2.48145 -3.75606 10.29400 0.02976 -5.94010 9.15660 2.50980 -2.75840 10.49580 3.62321 -8.07380 6.89460 4.80358 -6.95048 8.05290 4.89452 -4.28569 9.79750 4.93299 -5.69028 9.01010 4.98983 -7.68404 6.86400 7.19021 -6.59311 7.90890 7.32682 -4.12086 9.51920 7.38459 -2.57576 10.09530 7.41507 -5.41925 8.76810 7.46987 -7.28799 6.80580 9.57691 -6.23702 7.73940 9.75913 -3.95787 9.22070 9.83620 -5.15147 8.50730 9.94991 -2.40556 9.64210 11.24200 -6.95685 6.70500 11.96360 -5.94428 7.57760 12.19143 -3.77749 8.98770 12.28781 -4.91141 8.30410 12.42994 -6.76190 6.54660 14.35030 -5.77712 7.45700 14.62374 -3.56027 8.90580 14.73935 -4.72338 8.23520 14.90998 -2.13855 9.43290 14.94243 -6.77357 6.31590 16.73700 -5.79564 7.41050 17.05605 -3.28867 9.05710 17.19096 -4.61110 8.37220 17.38994 -1.72766 9.64300 18.33506 -7.00006 6.03250 19.12369 -5.99731 7.44970 19.48835 -2.99557 9.42630 19.64257 -4.58613 8.69440 19.86998 -7.34378 5.77480 21.51040 -6.30172 7.56070 21.92059 -2.76823 9.89430 22.09418 -1.33429 10.08770 21.40864 -4.64892 9.10020 22.35008 -7.69641 5.62700 23.89709 -6.62395 7.72770 24.35296 -2.69618 10.33660 24.54579 -1.13835 10.51830 24.18891 -4.79982 9.48510 24.83005 -7.87334 5.89220 26.22347 -6.92828 7.84400 26.71059 -1.22462 10.79640 26.70466 -3.12402 10.54986 26.98725 -5.11937 9.69790 27.34445 -5.42738 9.83580 28.97489 8.61265 5.13360 29.45177 0.06932 10.86760 3.80621 -0.01024 11.00000 0.02977 -1.40119 10.75920 3.81399 1.54101 10.76320 3.81675 2.87009 10.51680 3.52160 3.74599 10.31910 0.02461 3.06080 10.10820 6.97886 0.26646 10.44410 7.58258 -1.22349 10.34610 7.59807 1.75633 10.31870 7.60365 3.19084 9.65190 10.35776 0.40632 9.98440 11.35896 -1.07563 9.89580 11.38229 1.88615 9.84550 11.39063 3.12557 9.35790 13.61293 0.44521 9.74450 15.13533 -0.89992 9.67180 15.16637 1.78511 9.61390 15.17754 2.77768 9.38120 16.66155 0.34961 9.93570 18.91171 -0.65823 9.88990 18.95053 1.34910 9.84460 18.96453 2.21227 9.70760 19.47371 0.17213 10.39810 22.68822 -0.46781 10.38080 22.73461 0.80393 10.35940 22.75151 1.66398 10.14140 22.07601 1.30046 10.53670 24.50004 0.63860 10.78850 26.55730 -0.26995 10.78750 26.46785 1.22529 10.79760 26.75026 7.06210 8.42260 0.02481 8.41345 7.01390 2.18807 9.50643 5.48610 0.02976 7.26406 8.22570 2.23212 4.46815 10.02870 2.27030 5.94975 9.22990 2.28890 9.32640 5.51470 3.95308 8.34041 6.89470 4.35005 7.22057 8.06730 4.43978 4.53342 9.83020 4.51699 5.95696 9.03570 4.55093 8.18244 6.77210 6.51210 7.10496 7.85940 6.64744 4.60456 9.53340 6.76375 5.92833 8.75480 6.81304 9.00644 5.38790 7.87618 7.97886 6.64160 8.67407 6.94847 7.63310 8.85509 4.64917 9.20840 9.01044 5.86525 8.45070 9.07521 7.76899 6.49850 10.83612 6.78223 7.41940 11.06275 4.63475 8.92510 11.25721 5.76895 8.18680 11.33725 8.61378 5.22010 11.68501 7.59222 6.33800 12.99817 6.63741 7.24920 13.27048 4.52889 8.75350 13.50389 5.64082 8.02660 13.59928 7.48771 6.15560 15.16022 8.32521 4.90480 15.26346 6.54521 7.15350 15.47806 4.29922 8.76350 15.75065 5.48222 8.03360 15.86139 7.49153 5.94840 17.32228 6.53255 7.15940 17.68572 3.92877 9.00560 17.99735 5.29914 8.25080 18.12349 8.23527 4.41720 18.53411 7.59137 5.74270 19.48432 6.58862 7.26040 19.89338 3.49200 9.41690 20.24404 5.12194 8.61970 20.38567 7.73767 5.58670 21.64630 8.25740 3.95780 21.48409 6.68360 7.43260 22.10104 3.09609 9.89340 22.49073 4.98816 9.05000 22.64771 8.28384 3.71300 24.13419 7.87952 5.52970 23.80835 6.78704 7.65190 24.30869 2.84803 10.33120 24.73749 4.93555 9.45130 24.90974 7.96324 5.62190 25.97040 8.25683 3.76260 26.51529 6.86779 7.89350 26.51643 2.85645 10.62480 26.98418 5.02005 9.72250 27.17793 5.01206 9.91015 28.28688 10.72605 1.18730 4.35415 10.80892 1.89560 0.02976 10.22011 3.47460 4.38505 10.33368 1.07588 8.67846 10.30603 -1.32513 8.68545 9.83651 3.37060 8.74033 9.82534 0.96963 13.00276 9.78150 -1.36852 13.01323 9.35575 3.19910 13.09561 9.29663 0.82529 17.32708 9.25393 -1.21342 17.34108 8.92802 2.79230 17.45089 8.80583 0.66934 21.65139 8.78052 -0.89296 21.66892 8.60947 2.24530 21.80618 8.35632 -0.05477 25.91333 8.32436 1.64096 26.06027 8.66363 -0.09010 29.62890 8.64029 3.91250 29.54616 10.17118 1.89878 -3.67597 8.94513 5.49330 -3.22971 6.63522 8.42400 -2.39370 3.52367 10.33660 -1.26092 8.28971 1.89878 -6.93474 7.29022 5.49331 -6.09604 5.40599 8.42400 -4.51997 2.86939 10.33660 -2.39137 5.40719 1.89878 -9.35354 4.75482 5.49330 -8.22358 3.52367 8.42400 -6.09781 1.86812 10.33660 -3.23000 1.87124 1.89878 -10.64048 1.64468 5.49331 -9.35552 1.21532 8.42400 -6.93679 0.64044 10.33660 -3.67576 -1.89170 1.89878 -10.64048 -1.66514 5.49330 -9.35552 -1.24074 8.42400 -6.93594 -0.66558 10.33660 -3.67491 -5.42766 1.89878 -9.35354 -4.77529 5.49330 -8.22358 -3.54853 8.42400 -6.09527 -1.89270 10.33660 -3.22759 -8.31018 1.89878 -6.93474 -7.31069 5.49330 -6.09605 -5.42971 8.42400 -4.51615 -2.89297 10.33660 -2.38769 -10.19165 1.89878 -3.67597 -8.96560 5.49330 -3.22971 -6.65746 8.42400 -2.38896 -3.54577 10.33660 -1.25646 -8.65377 3.85249 29.52191 -8.67159 0.00316 29.58427 -8.97734 5.75739 31.26040 -8.62534 5.13799 29.42574 -8.92799 5.75739 33.24101 -8.44687 5.75739 35.16321 -7.55740 5.75739 36.93373 -6.30115 5.75739 38.46575 -4.74085 5.75739 39.68664 -2.95096 5.75739 40.53609 -1.01801 5.75739 40.97280 0.96295 5.75739 40.97697 2.89704 5.75739 40.54733 4.69025 5.75739 39.70474 6.25565 5.75739 38.49036 7.51734 5.75740 36.96280 8.41431 5.75740 35.19623 8.90306 5.75740 33.27615 8.95977 5.75740 31.29569 8.65656 1.84708 29.60358 8.35498 6.41670 28.91394 -7.38982 7.94489 28.76241 -8.31528 6.49310 28.80709 -8.78182 6.90539 32.00492 -8.03264 7.87869 30.76628 -8.10922 7.87869 32.63197 -8.12485 6.90539 35.36077 -7.75793 7.87869 34.46621 -6.99652 7.87869 36.17090 -6.23433 6.90539 38.21012 -5.86572 7.87869 37.65667 -4.42626 7.87869 38.84582 -3.39862 6.90539 40.12094 -2.75254 7.87869 39.67384 -0.04722 6.90539 40.80133 -0.93471 7.87869 40.09867 0.93269 7.87869 40.09620 3.30949 6.90540 40.14902 2.75003 7.87869 39.66762 4.42149 7.87869 38.83535 6.16175 6.90540 38.26267 5.85861 7.87870 37.64331 8.07595 6.90540 35.42908 6.98559 7.87870 36.15457 7.74269 7.87870 34.44783 8.76128 6.90540 32.07895 8.09009 7.87870 32.61324 8.00927 7.87870 30.74782 7.13755 8.03140 28.36388 -5.75442 10.12129 30.77964 -5.88891 10.12129 32.02981 -5.68858 10.12129 33.55129 -5.10133 10.12129 34.96911 -4.16711 10.12129 36.18661 -2.94961 10.12129 37.12083 -1.53171 10.12129 37.70816 -0.01024 10.12129 37.90848 1.51124 10.12129 37.70816 2.92913 10.12129 37.12083 4.14663 10.12129 36.18661 5.08086 10.12129 34.96911 5.66811 10.12129 33.55129 5.86843 10.12130 32.02981 5.73083 10.12130 30.76508 5.32404 10.12150 29.55953 4.88535 10.74795 32.02972 4.52677 10.77160 30.16474 3.59488 11.00000 30.97120 3.74711 11.00000 32.02981 3.15067 11.00000 29.99836 3.48542 10.81730 28.47776 2.45035 11.00000 29.19014 1.55063 11.00000 28.61201 0.52448 11.00000 28.31064 -0.22463 10.94620 27.71228 -0.90310 10.94670 27.80258 -3.41361 10.67647 27.95695 -1.57110 11.00000 28.61201 -2.47082 11.00000 29.19014 -3.75642 10.71769 28.67628 -3.17115 10.99999 29.99836 -4.54689 10.77160 30.16368 -3.61535 10.99999 30.97120 -4.90581 10.74795 32.02974 -3.76759 10.99999 32.02981 -3.61542 10.99999 33.08834 3.59495 11.00000 33.08834 -3.17115 10.99999 34.06111 3.15059 11.00000 34.06118 -2.47075 10.99999 34.86940 2.45028 11.00000 34.86940 -1.57111 10.99999 35.44761 1.55063 10.99999 35.44761 -0.54502 10.99999 35.74890 0.52455 10.99999 35.74890 -4.42986 10.77159 34.15820 -3.06869 10.77160 35.86501 -1.10180 10.77160 36.81225 1.08132 10.77160 36.81225 3.04821 10.77160 35.86501 4.40939 10.77160 34.15820 4.40939 -10.86170 34.15819 3.04822 -10.86170 35.86501 1.08133 -10.86170 36.81224 -1.10180 -10.86170 36.81224 -3.06868 -10.86170 35.86501 -4.42986 -10.86170 34.15819 0.52455 -11.09011 35.74890 -0.54502 -11.09011 35.74890 1.55064 -11.09011 35.44760 -1.57110 -11.09011 35.44760 2.45028 -11.09010 34.86940 -2.47075 -11.09011 34.86940 3.15060 -11.09010 34.06118 -3.17114 -11.09011 34.06110 3.59495 -11.09010 33.08834 -3.61542 -11.09011 33.08834 -3.76759 -11.09011 32.02980 -4.90581 -10.83806 32.02974 -3.61535 -11.09011 30.97119 -4.54689 -10.86171 30.16368 -3.17114 -11.09011 29.99836 -3.75641 -10.80780 28.67628 -2.47082 -11.09010 29.19013 -1.57110 -11.09010 28.61200 -3.41360 -10.76658 27.95695 -0.90309 -11.03680 27.80258 -0.22463 -11.03630 27.71228 0.52448 -11.09010 28.31063 1.55063 -11.09010 28.61200 2.45035 -11.09010 29.19013 3.48542 -10.90741 28.47776 3.15067 -11.09010 29.99836 3.74712 -11.09010 32.02980 3.59488 -11.09010 30.97119 4.52677 -10.86170 30.16474 4.88535 -10.83805 32.02972 5.32404 -10.21160 29.55953 5.73084 -10.21140 30.76507 5.86844 -10.21140 32.02980 5.66811 -10.21140 33.55128 5.08086 -10.21140 34.96910 4.14663 -10.21140 36.18660 2.92914 -10.21141 37.12083 1.51124 -10.21141 37.70815 -0.01023 -10.21141 37.90848 -1.53171 -10.21141 37.70815 -2.94960 -10.21141 37.12083 -4.16710 -10.21141 36.18660 -5.10133 -10.21140 34.96910 -5.68858 -10.21140 33.55128 -5.88891 -10.21140 32.02980 -5.75441 -10.21140 30.77964 7.13755 -8.12150 28.36388 8.00927 -7.96880 30.74782 8.09009 -7.96880 32.61324 8.76128 -6.99550 32.07895 7.74269 -7.96880 34.44782 6.98560 -7.96880 36.15456 8.07595 -6.99550 35.42908 5.85861 -7.96880 37.64331 6.16175 -6.99550 38.26267 4.42149 -7.96880 38.83535 2.75003 -7.96880 39.66762 3.30949 -6.99550 40.14902 0.93269 -7.96880 40.09619 -0.93471 -7.96880 40.09867 -0.04722 -6.99550 40.80132 -2.75254 -7.96880 39.67384 -3.39862 -6.99551 40.12094 -4.42626 -7.96880 38.84582 -5.86571 -7.96881 37.65667 -6.23433 -6.99551 38.21012 -6.99652 -7.96881 36.17090 -7.75793 -7.96880 34.46621 -8.12485 -6.99550 35.36077 -8.10922 -7.96881 32.63197 -8.03264 -7.96881 30.76628 -8.78182 -6.99550 32.00491 -8.31528 -6.58320 28.80709 -7.38981 -8.03500 28.76241 8.35498 -6.50680 28.91394 8.65656 -1.93718 29.60358 8.95977 -5.84750 31.29569 8.90306 -5.84750 33.27615 8.41431 -5.84750 35.19623 7.51734 -5.84750 36.96279 6.25565 -5.84750 38.49036 4.69026 -5.84750 39.70473 2.89704 -5.84750 40.54733 0.96295 -5.84750 40.97696 -1.01800 -5.84750 40.97280 -2.95095 -5.84750 40.53608 -4.74085 -5.84750 39.68664 -6.30115 -5.84750 38.46575 -7.55740 -5.84750 36.93373 -8.44687 -5.84750 35.16320 -8.92799 -5.84750 33.24101 -8.62534 -5.22810 29.42574 -8.65377 -3.94260 29.52191 -8.97734 -5.84750 31.26040 -3.54577 -10.42670 -1.25647 -6.65746 -8.51410 -2.38897 -8.96560 -5.58340 -3.22972 -10.19165 -1.98888 -3.67597 -2.89297 -10.42670 -2.38769 -5.42971 -8.51410 -4.51616 -7.31068 -5.58340 -6.09605 -8.31018 -1.98888 -6.93474 -1.89269 -10.42670 -3.22760 -3.54852 -8.51410 -6.09527 -4.77528 -5.58340 -8.22358 -5.42766 -1.98888 -9.35354 -0.66558 -10.42670 -3.67491 -1.24074 -8.51410 -6.93595 -1.66514 -5.58340 -9.35552 -1.89170 -1.98888 -10.64048 0.64045 -10.42670 -3.67576 1.21532 -8.51410 -6.93680 1.64468 -5.58340 -9.35552 1.87123 -1.98888 -10.64047 1.86813 -10.42670 -3.23000 3.52368 -8.51410 -6.09782 4.75482 -5.58340 -8.22358 5.40719 -1.98888 -9.35354 2.86939 -10.42670 -2.39137 5.40599 -8.51410 -4.51997 7.29022 -5.58340 -6.09604 8.28971 -1.98888 -6.93474 3.52367 -10.42670 -1.26092 6.63523 -8.51410 -2.39370 8.94513 -5.58340 -3.22972 10.17118 -1.98888 -3.67597 8.64029 -4.00260 29.54616 8.32436 -1.73106 26.06027 8.60947 -2.33540 21.80618 8.92802 -2.88240 17.45089 9.35575 -3.28920 13.09561 9.83651 -3.46070 8.74033 10.22011 -3.56470 4.38505 10.80892 -1.98570 0.02976 10.72605 -1.27740 4.35415 5.01207 -10.00026 28.28688 5.02005 -9.81260 27.17792 2.85645 -10.71490 26.98417 6.86779 -7.98360 26.51642 8.25683 -3.85270 26.51529 7.96325 -5.71200 25.97040 4.93555 -9.54140 24.90974 2.84804 -10.42130 24.73748 6.78704 -7.74200 24.30869 7.87952 -5.61980 23.80835 8.28384 -3.80310 24.13419 4.98816 -9.14010 22.64770 3.09609 -9.98350 22.49072 6.68360 -7.52270 22.10104 8.25740 -4.04790 21.48409 7.73768 -5.67680 21.64630 5.12194 -8.70980 20.38566 3.49200 -9.50700 20.24403 6.58863 -7.35050 19.89338 7.59137 -5.83280 19.48432 8.23527 -4.50730 18.53411 5.29915 -8.34090 18.12349 3.92878 -9.09570 17.99734 6.53255 -7.24950 17.68572 7.49153 -6.03850 17.32227 5.48222 -8.12370 15.86138 4.29923 -8.85360 15.75065 6.54521 -7.24360 15.47806 8.32521 -4.99490 15.26346 7.48771 -6.24570 15.16022 5.64083 -8.11670 13.59928 4.52889 -8.84360 13.50389 6.63742 -7.33930 13.27048 7.59222 -6.42810 12.99817 8.61378 -5.31020 11.68500 5.76895 -8.27690 11.33725 4.63475 -9.01520 11.25721 6.78224 -7.50950 11.06275 7.76900 -6.58860 10.83612 5.86526 -8.54080 9.07521 4.64917 -9.29850 9.01044 6.94848 -7.72320 8.85509 7.97887 -6.73170 8.67407 9.00644 -5.47800 7.87617 5.92833 -8.84490 6.81303 4.60456 -9.62350 6.76375 7.10496 -7.94950 6.64743 8.18244 -6.86220 6.51209 5.95697 -9.12580 4.55093 4.53343 -9.92030 4.51699 7.22057 -8.15740 4.43977 8.34041 -6.98480 4.35004 9.32640 -5.60480 3.95307 5.94975 -9.32000 2.28890 4.46815 -10.11880 2.27030 7.26406 -8.31580 2.23212 9.50643 -5.57620 0.02976 8.41345 -7.10400 2.18806 7.06211 -8.51270 0.02481 1.22529 -10.88770 26.75026 -0.26995 -10.87760 26.46784 0.63860 -10.87860 26.55729 1.30046 -10.62680 24.50003 1.66399 -10.23150 22.07600 0.80393 -10.44950 22.75150 -0.46780 -10.47090 22.73461 0.17213 -10.48820 22.68822 2.21228 -9.79770 19.47371 1.34910 -9.93470 18.96452 -0.65823 -9.98000 18.95052 0.34962 -10.02580 18.91170 2.77768 -9.47130 16.66155 1.78511 -9.70400 15.17754 -0.89992 -9.76190 15.16637 0.44522 -9.83460 15.13533 3.12557 -9.44800 13.61292 1.88616 -9.93560 11.39063 -1.07563 -9.98590 11.38229 0.40633 -10.07450 11.35896 3.19084 -9.74200 10.35776 1.75633 -10.40880 7.60365 -1.22349 -10.43620 7.59807 0.26646 -10.53420 7.58258 3.06080 -10.19830 6.97885 3.74599 -10.40920 0.02460 2.87010 -10.60690 3.52160 1.54102 -10.85330 3.81674 -1.40118 -10.84930 3.81398 -0.01023 -11.09010 0.02976 0.06932 -10.95770 3.80620 8.61265 -5.22370 29.45177 -5.42738 -9.92590 28.97489 -5.11936 -9.78800 27.34444 -3.12402 -10.63996 26.98725 -1.22462 -10.88650 26.70466 -6.92828 -7.93410 26.71059 -7.87333 -5.98230 26.22347 -4.79982 -9.57520 24.83005 -1.13835 -10.60840 24.18891 -2.69618 -10.42670 24.54579 -6.62395 -7.81780 24.35296 -7.69641 -5.71710 23.89709 -4.64892 -9.19030 22.35008 -1.33429 -10.17780 21.40864 -2.76823 -9.98440 22.09418 -6.30171 -7.65080 21.92059 -7.34378 -5.86490 21.51039 -4.58613 -8.78450 19.86997 -2.99557 -9.51640 19.64257 -5.99730 -7.53980 19.48835 -7.00006 -6.12260 19.12369 -1.72766 -9.73310 18.33506 -4.61109 -8.46230 17.38994 -3.28867 -9.14720 17.19096 -5.79564 -7.50060 17.05604 -6.77357 -6.40600 16.73700 -2.13855 -9.52300 14.94243 -4.72338 -8.32530 14.90997 -3.56026 -8.99590 14.73935 -5.77711 -7.54710 14.62374 -6.76190 -6.63670 14.35030 -4.91141 -8.39420 12.42994 -3.77749 -9.07780 12.28781 -5.94427 -7.66770 12.19143 -6.95685 -6.79510 11.96360 -2.40556 -9.73220 11.24200 -5.15147 -8.59740 9.94990 -3.95787 -9.31080 9.83620 -6.23701 -7.82950 9.75912 -7.28799 -6.89590 9.57691 -5.41925 -8.85820 7.46987 -2.57576 -10.18540 7.41507 -4.12086 -9.60930 7.38459 -6.59311 -7.99900 7.32682 -7.68404 -6.95410 7.19021 -5.69028 -9.10020 4.98983 -4.28568 -9.88760 4.93298 -6.95048 -8.14300 4.89451 -8.07380 -6.98470 4.80358 -2.75840 -10.58590 3.62321 -5.94010 -9.24670 2.50980 -3.75606 -10.38410 0.02976 -4.47194 -10.06000 2.48144 -7.24683 -8.22780 2.46228 -8.38620 -7.00290 2.41682 -7.06228 -8.49030 0.02983 -8.25863 -3.89250 26.86290 -8.18404 -3.84830 24.93399 -8.28218 -2.23900 26.50221 -8.02359 -4.03470 22.84328 -7.82107 -4.40870 20.58139 -8.31577 -2.50190 22.09022 -8.53313 -0.96570 21.91118 -7.64989 -4.88510 18.13671 -8.36209 -3.21540 17.67809 -8.79618 -1.29108 17.53489 -7.62288 -5.32120 15.49638 -8.71246 -3.66280 13.26609 -9.26471 -1.45734 13.15861 -8.04629 -5.61900 11.15913 -9.34524 -3.70270 8.85396 -9.89934 -1.41769 8.78240 -8.76916 -5.63130 6.52920 -9.53206 -5.59780 0.02983 -9.24738 -5.57550 3.30953 -10.01191 -3.57510 4.44190 -10.43772 -3.51470 0.02983 -10.52279 -1.28658 4.40604 -10.82211 -1.98461 0.02984 + + + + + + + + + + -0.99767 -0.00000 0.06824 -0.99767 0.00000 0.06824 -0.96454 0.24231 0.10462 -0.97224 0.21562 0.09088 -0.91458 0.39600 0.08208 -0.91393 0.39734 0.08277 -0.90059 0.41583 0.12656 -0.99000 0.00000 0.14104 -0.96794 0.21402 0.13148 -0.99000 -0.00000 0.14104 -0.96340 0.22926 0.13894 -0.89990 0.41813 0.12388 -0.88968 0.43458 0.14006 -0.98965 -0.00000 0.14352 -0.96356 0.22934 0.13766 -0.98965 -0.00000 0.14352 -0.96207 0.23408 0.14010 -0.88674 0.44327 0.13118 -0.89489 0.43069 0.11693 -0.99432 -0.00000 0.10645 -0.99432 0.00000 0.10645 -0.96519 0.23621 0.11231 -0.89409 0.43290 0.11490 -0.97228 0.21198 0.09871 -0.92371 0.37938 0.05321 -0.99820 0.00000 0.06000 -0.97395 0.21417 0.07446 -0.99820 0.00000 0.06000 -0.99013 0.13632 0.03244 -0.97187 0.23444 -0.02237 -0.92437 0.37496 0.07034 -0.97592 0.21175 -0.05236 -0.99865 0.00000 0.05197 -0.99865 -0.00000 0.05197 -0.98943 0.13338 0.05683 -0.99703 -0.00430 -0.07690 -0.98471 0.17078 0.03445 -0.99984 0.01582 0.00892 -0.99897 0.02275 -0.03915 -0.76038 0.64925 -0.01717 -0.73242 0.68061 0.01788 -0.48479 0.87424 -0.02599 -0.49664 0.86705 -0.03972 -0.61532 0.78735 0.03828 -0.83204 0.54949 0.07596 -0.31376 0.94890 0.03382 -0.81854 0.56354 0.11144 -0.73035 0.67561 0.10075 -0.71775 0.68733 0.11142 -0.61399 0.78268 0.10210 -0.81869 0.56324 0.11184 -0.48080 0.87136 0.09781 -0.34769 0.93308 0.09203 -0.48346 0.86963 0.10007 -0.60650 0.78777 0.10763 -0.79844 0.58607 0.13791 -0.71708 0.68553 0.12589 -0.69385 0.70563 0.14372 -0.60576 0.78404 0.13542 -0.31946 0.93891 0.12806 -0.48077 0.86705 0.13075 -0.34904 0.93002 0.11504 -0.48920 0.86127 0.13750 -0.59586 0.79039 0.14224 -0.69421 0.70748 0.13245 -0.79949 0.58245 0.14687 -0.77873 0.61514 0.12322 -0.67103 0.72634 0.14886 -0.59586 0.79038 0.14231 -0.34847 0.92739 0.13608 -0.48921 0.86128 0.13739 -0.58832 0.79513 0.14714 -0.49759 0.85543 0.14368 -0.36416 0.92284 0.12548 -0.67093 0.73109 0.12396 -0.77086 0.62291 0.13326 -0.66384 0.73668 0.12890 -0.58747 0.79970 0.12390 -0.35537 0.92771 0.11432 -0.50110 0.85726 0.11834 -0.50168 0.85686 0.11877 -0.58975 0.79824 0.12249 -0.76748 0.63009 0.11819 -0.78791 0.60683 0.10463 -0.66255 0.74185 0.10335 -0.58579 0.80648 0.08025 -0.68882 0.72016 0.08305 -0.50811 0.85814 0.07369 -0.38872 0.91905 0.06515 -0.60457 0.79365 0.06788 -0.49176 0.86856 0.06141 -0.35638 0.93105 0.07835 -0.68723 0.72339 0.06656 -0.81428 0.57815 0.05191 -0.59594 0.80296 0.01081 -0.74673 0.66509 0.00703 -0.34509 0.93836 -0.01968 -0.49928 0.86644 0.00184 -0.62775 0.77828 -0.01457 -0.46303 0.88590 -0.02797 -0.34041 0.94012 -0.01699 -0.82853 0.55376 0.08299 -0.87635 0.48096 -0.02605 -0.74688 0.66491 0.00808 -0.61810 0.78350 -0.06387 -0.80460 0.58891 -0.07620 -0.46761 0.88060 -0.07671 -0.27717 0.95443 -0.11060 -0.42857 0.89652 -0.11216 -0.64455 0.75899 -0.09212 -0.89314 0.44908 0.02497 -0.92670 0.36382 -0.09418 -0.80866 0.58586 -0.05320 -0.63949 0.76019 -0.11473 -0.84324 0.52174 -0.12935 -0.42979 0.89342 -0.13069 -0.18752 0.97526 -0.11710 -0.31463 0.93733 -0.14976 -0.65561 0.74237 -0.13807 -0.40225 0.90184 -0.15774 -0.94397 0.32865 -0.03017 -0.85042 0.51771 -0.09359 -0.95633 0.26423 -0.12493 -0.65566 0.74237 -0.13783 -0.86757 0.47493 -0.14754 -0.14656 0.97906 -0.14130 -0.21004 0.96322 -0.16760 -0.40190 0.90313 -0.15112 -0.66437 0.73138 -0.15394 -0.38910 0.90641 -0.16435 -0.97315 0.22354 -0.05475 -0.97487 0.20055 -0.09700 -0.87795 0.45904 -0.13597 -0.87338 0.47197 -0.12022 -0.14073 0.98352 -0.11355 -0.67173 0.73056 -0.12275 -0.98477 0.16873 -0.04195 -0.38816 0.90972 -0.14748 -0.14417 0.98329 -0.11115 -0.40878 0.90355 -0.12842 -0.68228 0.71609 -0.14731 -0.67028 0.71807 -0.18736 -0.19020 0.98174 -0.00233 -0.07328 0.99664 0.03649 -0.18521 0.98268 -0.00555 0.07048 0.99695 0.03347 0.18002 0.98361 -0.01052 0.17834 0.98390 -0.01153 0.20355 0.97354 0.10383 -0.20453 0.97237 0.11255 0.06958 0.99176 0.10759 -0.07243 0.99073 0.11489 -0.19623 0.97373 0.11551 -0.06407 0.99172 0.11127 0.20613 0.97314 0.10251 0.08178 0.99038 0.11160 0.21505 0.96888 0.12257 0.08164 0.98972 0.11746 -0.06386 0.99036 0.12292 -0.19714 0.97251 0.12394 -0.19850 0.97229 0.12345 -0.05736 0.99109 0.12018 0.23260 0.96602 0.11273 0.09021 0.98861 0.12044 0.21713 0.97179 0.09212 -0.19398 0.97855 0.06932 0.09195 0.99382 0.06219 -0.05856 0.99624 0.06389 -0.05245 0.99673 0.06144 -0.20065 0.97736 0.06717 0.09484 0.99348 0.06329 0.26082 0.96314 0.06586 0.20552 0.97852 0.01598 -0.18248 0.98245 -0.03874 0.09839 0.99400 -0.04784 -0.05509 0.99713 -0.05188 -0.04742 0.99739 -0.05446 -0.20086 0.97865 -0.04358 0.26749 0.96316 -0.02788 0.09327 0.99439 -0.04984 0.19850 0.97734 -0.07353 -0.15618 0.98019 -0.12183 0.09626 0.98851 -0.11651 -0.04980 0.99107 -0.12369 -0.03599 0.99128 -0.12678 -0.14862 0.98160 -0.11986 0.14399 0.98058 -0.13312 0.21395 0.97158 -0.10128 0.07304 0.98959 -0.12401 -0.11159 0.98321 -0.14441 0.13935 0.98044 -0.13899 0.07162 0.99149 -0.10868 -0.03387 0.99478 -0.09629 0.00962 0.99402 -0.10880 -0.02783 0.99389 -0.10680 0.03443 0.99328 -0.11050 -0.01814 0.99371 -0.11047 0.02223 0.99318 -0.11441 0.76708 0.63841 -0.06345 0.72544 0.68827 -0.00498 0.30890 0.95080 0.02362 0.83514 0.54897 0.03432 0.72526 0.68565 0.06231 0.82020 0.56902 0.05908 0.72415 0.68671 0.06354 0.60756 0.79129 0.06875 0.34302 0.93650 0.07278 0.47298 0.87876 0.06390 0.61061 0.78919 0.06581 0.48471 0.87160 0.07328 0.72364 0.68407 0.09166 0.82253 0.56124 0.09192 0.71291 0.69370 0.10266 0.61072 0.78474 0.10588 0.48311 0.86987 0.09962 0.31995 0.94054 0.11412 0.61155 0.78419 0.10512 0.50061 0.85828 0.11291 0.35851 0.92917 0.09004 0.81707 0.57022 0.08507 0.71282 0.69283 0.10894 0.80209 0.58681 0.11095 0.69924 0.70444 0.12177 0.61189 0.78125 0.12345 0.36156 0.92374 0.12645 0.50050 0.85817 0.11420 0.51954 0.84480 0.12805 0.61362 0.78013 0.12198 0.38034 0.91836 0.10938 0.80324 0.58413 0.11663 0.69919 0.70569 0.11458 0.61360 0.78018 0.12173 0.69199 0.71170 0.12100 0.52138 0.84620 0.11005 0.38696 0.91454 0.11780 0.53560 0.83585 0.12032 0.61953 0.77621 0.11693 0.79482 0.59711 0.10825 0.69151 0.71401 0.10954 0.79437 0.59751 0.10931 0.70174 0.70532 0.10041 0.61785 0.77982 0.10065 0.53892 0.83760 0.08937 0.40328 0.91078 0.08857 0.53956 0.83714 0.08985 0.63090 0.77059 0.09031 0.39986 0.91211 0.09040 0.78542 0.61244 0.08963 0.70120 0.70680 0.09352 0.82094 0.55921 0.11547 0.73516 0.67524 0.05998 0.62616 0.77739 0.05985 0.39770 0.91679 0.03657 0.54333 0.83792 0.05181 0.52248 0.85197 0.03400 0.64629 0.76188 0.04296 0.39538 0.91773 0.03811 0.73553 0.67452 0.06334 0.82782 0.55858 0.05207 0.78437 0.62028 0.00284 0.63807 0.76997 0.00160 0.52543 0.85082 -0.00505 0.35396 0.93430 -0.04231 0.48512 0.87331 -0.04459 0.65879 0.75209 -0.01890 0.86262 0.49633 0.09772 0.89950 0.43693 0.00003 0.78701 0.61653 0.02231 0.82761 0.55937 -0.04661 0.65156 0.75687 -0.05118 0.48602 0.87152 -0.06506 0.34986 0.93602 -0.03830 0.28709 0.95058 -0.11821 0.44439 0.88903 -0.11017 0.66556 0.74315 -0.06905 0.83220 0.55424 -0.01632 0.95307 0.30015 0.03959 0.89121 0.45274 -0.02764 0.85760 0.50858 -0.07656 0.66141 0.74501 -0.08656 0.27767 0.95538 -0.10076 0.21481 0.96240 -0.16626 0.44440 0.88902 -0.11024 0.66964 0.73587 -0.10038 0.41286 0.89892 -0.14658 0.95305 0.30225 0.01841 0.97662 0.20684 -0.05862 0.86294 0.50345 -0.04334 0.87706 0.47225 -0.08801 0.66864 0.73621 -0.10446 0.41266 0.90154 -0.13011 0.20498 0.97043 -0.12751 0.15560 0.97267 -0.17235 0.39452 0.90629 -0.15161 0.67313 0.73069 -0.11397 0.88256 0.46708 -0.05410 0.98737 0.15822 0.00791 0.97680 0.20901 -0.04674 0.67546 0.72995 -0.10459 0.88991 0.44878 -0.08166 0.14727 0.98306 -0.10906 0.12275 0.98401 -0.12905 0.39401 0.91117 -0.12055 0.67851 0.72599 -0.11208 0.39136 0.91190 -0.12361 0.67690 0.72654 -0.11807 0.99982 -0.00000 0.01916 0.99982 0.00000 0.01916 0.97513 0.21496 0.05390 0.94005 0.34101 0.00346 0.91222 0.40785 0.03889 0.90555 0.41517 0.08727 0.97237 0.21381 0.09374 0.99591 0.00000 0.09036 0.99528 -0.01118 0.09639 0.97380 0.20853 0.09075 0.90693 0.41161 0.08971 0.90133 0.41858 0.11136 0.97101 0.20716 0.11924 0.99313 -0.01110 0.11647 0.99259 -0.01807 0.12012 0.97296 0.20013 0.11528 0.90348 0.41264 0.11598 0.90609 0.40879 0.10909 0.97184 0.19947 0.12548 0.99252 -0.01807 0.12075 0.99237 -0.01995 0.12169 0.97791 0.17618 0.11249 0.91184 0.39071 0.12604 0.93471 0.34689 0.07742 0.99350 -0.02004 0.11204 0.97742 0.17578 0.11727 0.99384 -0.01487 0.10981 0.98959 0.11478 0.08680 0.93026 0.36352 0.04963 0.97095 0.21812 0.09841 0.97914 0.20299 0.00898 0.99463 -0.01497 0.10236 0.98622 0.11081 0.12284 0.99241 0.09359 0.07981 0.99756 0.01285 0.06868 0.99951 0.02951 0.01072 0.98551 0.00000 -0.16960 0.92804 0.33665 -0.15942 0.98551 -0.00000 -0.16960 0.76218 0.63421 -0.12985 0.92820 0.33635 -0.15910 0.49458 0.86479 -0.08680 0.75944 0.63670 -0.13368 0.17832 0.98382 -0.01744 0.50219 0.86149 -0.07512 0.86602 -0.00000 -0.50000 0.86602 -0.00000 -0.50000 0.81549 0.33661 -0.47083 0.66796 0.63648 -0.38565 0.81548 0.33661 -0.47083 0.66756 0.63673 -0.38593 0.43801 0.86257 -0.25322 0.15254 0.98435 -0.08829 0.43779 0.86263 -0.25339 0.64280 -0.00000 -0.76603 0.64280 0.00000 -0.76603 0.60529 0.33661 -0.72133 0.60529 0.33661 -0.72133 0.49578 0.63649 -0.59083 0.49535 0.63672 -0.59094 0.32501 0.86257 -0.38773 0.32481 0.86262 -0.38779 0.11317 0.98435 -0.13512 0.34201 0.00000 -0.93970 0.34201 -0.00000 -0.93970 0.32205 0.33661 -0.88486 0.32205 0.33662 -0.88486 0.26378 0.63651 -0.72476 0.17282 0.86257 -0.47550 0.26340 0.63671 -0.72472 0.06015 0.98435 -0.16567 0.17265 0.86261 -0.47549 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.33662 -0.94164 0.00000 0.33661 -0.94164 0.00000 0.63652 -0.77126 -0.00027 0.63668 -0.77113 -0.00018 0.86257 -0.50593 -0.00033 0.86261 -0.50586 -0.00011 0.98435 -0.17625 -0.34201 0.00000 -0.93970 -0.34201 0.00000 -0.93970 -0.32205 0.33661 -0.88486 -0.26377 0.63654 -0.72474 -0.32205 0.33661 -0.88486 -0.26394 0.63667 -0.72456 -0.17316 0.86258 -0.47536 -0.06036 0.98435 -0.16559 -0.17325 0.86261 -0.47528 -0.64280 0.00000 -0.76603 -0.64280 0.00000 -0.76603 -0.60529 0.33661 -0.72133 -0.49575 0.63655 -0.59079 -0.60529 0.33661 -0.72133 -0.49581 0.63663 -0.59066 -0.32527 0.86259 -0.38749 -0.32530 0.86260 -0.38742 -0.11334 0.98435 -0.13498 -0.86602 0.00000 -0.50000 -0.81549 0.33661 -0.47083 -0.86602 0.00000 -0.50000 -0.66790 0.63655 -0.38562 -0.81548 0.33661 -0.47083 -0.66791 0.63662 -0.38550 -0.43816 0.86259 -0.25289 -0.43817 0.86260 -0.25285 -0.15265 0.98435 -0.08809 -0.98584 0.00000 -0.16772 -0.98584 0.00000 -0.16772 -0.75928 0.63665 -0.13476 -0.49635 0.86654 -0.05245 -0.18521 0.98270 0.00226 -0.75499 0.64466 -0.12002 -0.50205 0.86153 -0.07555 -0.98281 0.00156 -0.18463 -0.98159 0.00743 -0.19084 -0.98377 0.00000 -0.17946 -0.99969 -0.00000 0.02491 -0.99969 0.00000 0.02491 -0.97007 0.00000 0.24281 -0.97007 -0.00000 0.24281 -0.89358 -0.00000 0.44891 -0.89358 -0.00000 0.44891 -0.77327 -0.00000 0.63408 -0.77327 -0.00000 0.63408 -0.61624 -0.00000 0.78756 -0.61624 -0.00000 0.78756 -0.42875 -0.00000 0.90343 -0.42874 -0.00000 0.90343 -0.22038 -0.00000 0.97541 -0.22038 -0.00000 0.97541 -0.00210 -0.00000 1.00000 -0.00210 -0.00000 1.00000 0.21685 -0.00000 0.97620 0.21685 -0.00000 0.97620 0.42527 -0.00000 0.90507 0.42527 -0.00000 0.90507 0.61295 -0.00000 0.79012 0.61295 0.00000 0.79012 0.77101 0.00000 0.63682 0.77102 -0.00000 0.63682 0.89165 0.00000 0.45273 0.89165 -0.00000 0.45273 0.96910 -0.00000 0.24668 0.96910 -0.00000 0.24668 0.99959 -0.00000 0.02862 0.99959 -0.00000 0.02862 0.98458 0.00000 -0.17493 0.98382 0.00125 -0.17918 0.98323 0.00267 -0.18236 0.98223 0.00774 -0.18752 0.97049 0.10362 -0.21775 -0.96703 0.11833 -0.22548 -0.94612 0.27353 -0.17330 -0.81205 0.58264 -0.03333 -0.98803 0.15231 0.02462 -0.90531 0.35925 0.22660 -0.95379 0.23541 0.18672 -0.86306 0.47728 0.16529 -0.85829 0.48487 0.16803 -0.74132 0.58379 0.33111 -0.88044 0.17084 0.44231 -0.66848 0.54248 0.50877 -0.74356 0.45136 0.49335 -0.78755 0.32668 0.52253 -0.76020 0.18305 0.62336 -0.52676 0.56208 0.63764 -0.60294 0.20667 0.77055 -0.52913 0.32159 0.78524 -0.50053 0.44467 0.74280 -0.36223 0.57679 0.73219 -0.42339 0.15752 0.89215 -0.21293 0.25778 0.94245 -0.18978 0.30012 0.93483 -0.20391 0.44397 0.87253 -0.17194 0.50317 0.84691 -0.00208 0.14945 0.98877 0.00107 0.58598 0.81033 0.20530 0.32205 0.92419 0.18407 0.26251 0.94721 0.19566 0.52283 0.82968 0.16931 0.46073 0.87124 0.41985 0.15917 0.89353 0.36533 0.57289 0.73371 0.56280 0.39615 0.72548 0.53979 0.20603 0.81619 0.49427 0.44401 0.74736 0.52581 0.56716 0.63392 0.75755 0.18606 0.62570 0.72890 0.40527 0.55178 0.70606 0.52343 0.47697 0.78342 0.32584 0.52923 0.87889 0.16852 0.44626 0.74119 0.58526 0.32879 0.85161 0.49875 0.16127 0.86295 0.47345 0.17653 0.94327 0.22931 0.24011 0.93036 0.31338 0.19032 0.98805 0.15153 0.02829 0.81357 0.58039 -0.03525 0.88222 0.43491 -0.18041 0.94711 0.27576 -0.16416 0.81130 0.52202 -0.26323 -0.66164 0.71281 -0.23266 -0.68713 0.69922 -0.19733 -0.69930 0.71086 -0.07523 -0.71425 0.69928 -0.02932 -0.69525 0.71292 0.09154 -0.70041 0.70102 0.13414 -0.65047 0.71014 0.26942 -0.64881 0.70360 0.28980 -0.56351 0.70605 0.42888 -0.56099 0.70709 0.43047 -0.45311 0.70274 0.54849 -0.42808 0.71099 0.55788 -0.31647 0.70044 0.63971 -0.26816 0.71343 0.64739 -0.16274 0.69898 0.69638 -0.09129 0.71479 0.69336 0.00095 0.69850 0.71561 0.09129 0.71478 0.69337 0.16416 0.69891 0.69612 0.26809 0.71360 0.64722 0.31819 0.70029 0.63902 0.42796 0.71119 0.55773 0.45431 0.70258 0.54771 0.56358 0.70736 0.42664 0.56221 0.70556 0.43140 0.64937 0.70381 0.28805 0.65079 0.70980 0.26955 0.70058 0.70113 0.13267 0.69542 0.71275 0.09156 0.71409 0.69937 -0.03094 0.69915 0.71091 -0.07607 0.68564 0.69818 -0.20599 0.66836 0.70886 -0.22541 0.53660 0.84181 -0.05838 0.21287 0.97660 -0.03061 0.21611 0.97593 -0.02917 0.50647 0.85791 -0.08650 0.53558 0.82495 -0.18059 0.17249 0.98186 -0.07876 0.17261 0.98174 -0.07995 0.47616 0.83648 -0.27126 0.10940 0.98947 -0.09480 0.08418 0.98780 -0.13101 0.08169 0.98354 -0.16117 0.05378 0.98162 -0.18311 -0.00960 0.99694 -0.07762 -0.11065 0.97883 -0.17220 -0.16155 0.97786 -0.13303 -0.15943 0.97750 -0.13814 -0.17754 0.97553 -0.12971 -0.17247 0.98186 -0.07875 -0.54893 0.80453 -0.22674 -0.49438 0.86762 -0.05319 -0.53522 0.83965 -0.09230 -0.21436 0.97633 -0.02886 -0.21610 0.97588 -0.03108 -0.01071 0.99716 -0.07451 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.53617 0.84115 0.07059 -0.49467 0.86319 0.10102 -0.22947 0.97276 0.03299 -0.21605 0.97566 0.03747 -0.52918 0.81972 0.21918 -0.17211 0.98194 0.07861 -0.15313 0.97926 0.13268 -0.16699 0.97692 0.13318 -0.42461 0.84472 0.32582 -0.40904 0.85222 0.32620 -0.35041 0.81772 0.45667 -0.10438 0.98119 0.16241 -0.19285 0.86375 0.46556 -0.23759 0.83675 0.49335 -0.09429 0.97610 0.19580 -0.05367 0.98169 0.18276 -0.07403 0.82361 0.56230 -0.00000 0.86006 0.51020 -0.00000 0.97770 0.21000 0.00000 0.97770 0.21000 0.07403 0.82361 0.56230 0.05367 0.98169 0.18276 0.20977 0.83638 0.50643 0.22385 0.85664 0.46482 0.09429 0.97610 0.19580 0.10438 0.98119 0.16241 0.35041 0.81772 0.45666 0.16593 0.97560 0.14378 0.16059 0.97868 0.12807 0.41282 0.85395 0.31677 0.41722 0.84571 0.33273 0.17211 0.98194 0.07861 0.52918 0.81971 0.21918 0.48206 0.87384 0.06347 0.53424 0.83813 0.11015 0.22217 0.97423 0.03886 0.21610 0.97588 0.03106 0.81364 0.55878 -0.16051 0.85073 0.46784 -0.23954 0.64212 0.71513 -0.27617 0.65774 0.73793 -0.15112 0.47006 0.84484 -0.25553 0.45904 0.83586 -0.30104 0.11587 0.99032 -0.07642 0.39198 0.90754 -0.15075 -0.34968 0.91095 -0.21885 -0.41281 0.87590 -0.24976 -0.59330 0.78495 -0.17847 -0.11267 0.98835 -0.10230 -0.41718 0.87682 -0.23907 -0.15198 0.97322 -0.17246 -0.67118 0.71751 -0.18626 -0.97021 0.12813 -0.20560 -0.97355 0.12000 -0.19444 -0.81799 0.51345 -0.25934 -0.85665 0.46863 -0.21574 -0.98905 0.01086 -0.14718 0.99660 0.00256 -0.08240 0.99512 0.02698 -0.09487 0.99559 0.00524 -0.09365 0.99000 0.05900 -0.12817 0.99193 0.01270 -0.12613 0.98012 0.10552 -0.16803 0.97810 0.12744 -0.16458 0.02348 0.99271 -0.11822 0.02315 0.99272 -0.11824 0.01140 0.99185 -0.12690 -0.02193 0.99183 -0.12569 -0.01668 0.99127 -0.13081 -0.11535 0.98039 -0.15976 -0.87838 0.44072 -0.18497 -0.82070 0.51558 -0.24624 -0.92751 0.33656 -0.16267 -0.89470 0.38898 -0.21957 -0.95697 0.24041 -0.16253 0.49539 0.86620 -0.06547 0.60747 0.79420 0.01527 0.47459 0.87935 -0.03890 0.47459 -0.87935 -0.03890 0.60747 -0.79420 0.01527 0.49539 -0.86620 -0.06547 -0.95697 -0.24041 -0.16253 -0.89470 -0.38898 -0.21957 -0.92751 -0.33656 -0.16267 -0.82070 -0.51558 -0.24624 -0.87838 -0.44072 -0.18497 -0.11535 -0.98039 -0.15976 -0.01668 -0.99127 -0.13081 -0.02193 -0.99183 -0.12569 0.01140 -0.99185 -0.12690 0.02315 -0.99272 -0.11824 0.02349 -0.99271 -0.11822 0.97810 -0.12744 -0.16458 0.98012 -0.10552 -0.16803 0.99193 -0.01270 -0.12613 0.99000 -0.05900 -0.12817 0.99559 -0.00524 -0.09365 0.99511 -0.02729 -0.09488 0.99659 -0.00269 -0.08245 -0.98905 -0.01086 -0.14718 -0.85665 -0.46863 -0.21574 -0.81799 -0.51345 -0.25934 -0.97355 -0.12000 -0.19444 -0.97021 -0.12813 -0.20560 -0.67119 -0.71751 -0.18626 -0.15198 -0.97322 -0.17246 -0.41717 -0.87682 -0.23907 -0.11267 -0.98835 -0.10230 -0.59330 -0.78495 -0.17847 -0.41281 -0.87590 -0.24976 -0.34967 -0.91095 -0.21885 0.39198 -0.90754 -0.15075 0.11587 -0.99032 -0.07642 0.45904 -0.83586 -0.30104 0.47006 -0.84484 -0.25553 0.65774 -0.73793 -0.15112 0.64212 -0.71513 -0.27616 0.85073 -0.46784 -0.23954 0.81364 -0.55877 -0.16052 0.21610 -0.97588 0.03106 0.22217 -0.97423 0.03886 0.53424 -0.83813 0.11015 0.48206 -0.87384 0.06347 0.52918 -0.81972 0.21918 0.17211 -0.98194 0.07861 0.41722 -0.84571 0.33273 0.41282 -0.85395 0.31677 0.16059 -0.97868 0.12807 0.16593 -0.97560 0.14378 0.35041 -0.81772 0.45666 0.10438 -0.98119 0.16240 0.09430 -0.97610 0.19580 0.22385 -0.85664 0.46482 0.20977 -0.83638 0.50643 0.05367 -0.98169 0.18276 0.07403 -0.82361 0.56230 0.00000 -0.97770 0.21000 0.00000 -0.97770 0.21000 0.00000 -0.86006 0.51020 -0.07403 -0.82361 0.56230 -0.05367 -0.98169 0.18276 -0.09430 -0.97610 0.19580 -0.23759 -0.83675 0.49335 -0.19284 -0.86375 0.46556 -0.10438 -0.98119 0.16241 -0.35041 -0.81772 0.45666 -0.40904 -0.85222 0.32620 -0.42461 -0.84472 0.32582 -0.16700 -0.97692 0.13318 -0.15313 -0.97926 0.13269 -0.17211 -0.98194 0.07861 -0.52917 -0.81972 0.21918 -0.21605 -0.97566 0.03747 -0.22947 -0.97276 0.03299 -0.49466 -0.86319 0.10102 -0.53617 -0.84115 0.07059 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.01071 -0.99716 -0.07451 -0.21610 -0.97588 -0.03108 -0.21436 -0.97633 -0.02886 -0.53522 -0.83965 -0.09230 -0.49438 -0.86762 -0.05319 -0.54893 -0.80453 -0.22674 -0.17247 -0.98186 -0.07875 -0.17754 -0.97553 -0.12971 -0.15943 -0.97750 -0.13815 -0.16155 -0.97786 -0.13303 -0.11065 -0.97883 -0.17220 -0.00960 -0.99694 -0.07762 0.05378 -0.98162 -0.18311 0.08169 -0.98354 -0.16117 0.08418 -0.98780 -0.13101 0.10940 -0.98947 -0.09480 0.47616 -0.83648 -0.27126 0.17261 -0.98174 -0.07995 0.17249 -0.98186 -0.07876 0.53559 -0.82495 -0.18059 0.50647 -0.85791 -0.08650 0.21611 -0.97593 -0.02917 0.21287 -0.97660 -0.03061 0.53660 -0.84181 -0.05838 0.66836 -0.70886 -0.22541 0.68564 -0.69818 -0.20599 0.69915 -0.71091 -0.07607 0.71409 -0.69937 -0.03094 0.69542 -0.71275 0.09156 0.70058 -0.70113 0.13266 0.65079 -0.70980 0.26955 0.64937 -0.70381 0.28805 0.56221 -0.70555 0.43140 0.56358 -0.70736 0.42664 0.45431 -0.70258 0.54771 0.42796 -0.71119 0.55773 0.31819 -0.70029 0.63902 0.26809 -0.71360 0.64722 0.16416 -0.69891 0.69612 0.09129 -0.71478 0.69337 0.00095 -0.69850 0.71561 -0.09129 -0.71479 0.69336 -0.16274 -0.69898 0.69638 -0.26816 -0.71343 0.64739 -0.31648 -0.70044 0.63971 -0.42808 -0.71099 0.55788 -0.45311 -0.70274 0.54849 -0.56099 -0.70709 0.43047 -0.56351 -0.70605 0.42888 -0.64881 -0.70360 0.28980 -0.65047 -0.71014 0.26942 -0.70041 -0.70102 0.13414 -0.69525 -0.71292 0.09154 -0.71425 -0.69928 -0.02932 -0.69930 -0.71086 -0.07523 -0.68713 -0.69922 -0.19733 -0.66164 -0.71281 -0.23266 0.81130 -0.52202 -0.26323 0.94711 -0.27576 -0.16416 0.88222 -0.43490 -0.18041 0.81357 -0.58039 -0.03525 0.98805 -0.15153 0.02829 0.93036 -0.31338 0.19032 0.94327 -0.22931 0.24011 0.86295 -0.47345 0.17653 0.85161 -0.49875 0.16126 0.74119 -0.58526 0.32879 0.87889 -0.16852 0.44626 0.78342 -0.32584 0.52923 0.70606 -0.52343 0.47697 0.72890 -0.40527 0.55178 0.75755 -0.18606 0.62570 0.52581 -0.56716 0.63392 0.49427 -0.44401 0.74736 0.53979 -0.20603 0.81619 0.56280 -0.39615 0.72548 0.36533 -0.57289 0.73371 0.41985 -0.15917 0.89353 0.16931 -0.46073 0.87124 0.19566 -0.52283 0.82968 0.18407 -0.26251 0.94721 0.20530 -0.32205 0.92419 0.00107 -0.58598 0.81033 -0.00208 -0.14945 0.98877 -0.17194 -0.50317 0.84691 -0.20391 -0.44397 0.87253 -0.18978 -0.30012 0.93483 -0.21293 -0.25778 0.94245 -0.42339 -0.15752 0.89215 -0.36223 -0.57679 0.73219 -0.50053 -0.44467 0.74280 -0.52913 -0.32159 0.78524 -0.60294 -0.20667 0.77055 -0.52676 -0.56208 0.63764 -0.76020 -0.18305 0.62336 -0.78755 -0.32668 0.52254 -0.74356 -0.45136 0.49335 -0.66848 -0.54248 0.50877 -0.88044 -0.17084 0.44231 -0.74131 -0.58380 0.33111 -0.85829 -0.48487 0.16803 -0.86306 -0.47729 0.16529 -0.95379 -0.23540 0.18672 -0.90531 -0.35925 0.22660 -0.98803 -0.15231 0.02462 -0.81205 -0.58264 -0.03333 -0.94612 -0.27353 -0.17330 -0.96703 -0.11833 -0.22549 0.97049 -0.10362 -0.21775 0.98223 -0.00774 -0.18752 0.98323 -0.00267 -0.18236 0.98379 -0.00131 -0.17931 -0.50205 -0.86153 -0.07555 -0.75499 -0.64466 -0.12002 -0.18521 -0.98270 0.00226 -0.49635 -0.86654 -0.05245 -0.75928 -0.63665 -0.13476 -0.15265 -0.98435 -0.08809 -0.43817 -0.86260 -0.25285 -0.43816 -0.86259 -0.25289 -0.66791 -0.63662 -0.38550 -0.81548 -0.33661 -0.47083 -0.66790 -0.63655 -0.38562 -0.81549 -0.33661 -0.47083 -0.11334 -0.98435 -0.13498 -0.32530 -0.86260 -0.38742 -0.32527 -0.86259 -0.38749 -0.49581 -0.63663 -0.59066 -0.60529 -0.33661 -0.72133 -0.49575 -0.63655 -0.59079 -0.60529 -0.33661 -0.72133 -0.17325 -0.86261 -0.47528 -0.06036 -0.98435 -0.16559 -0.17316 -0.86258 -0.47536 -0.26394 -0.63667 -0.72456 -0.32205 -0.33661 -0.88486 -0.26377 -0.63654 -0.72474 -0.32205 -0.33661 -0.88486 -0.00011 -0.98435 -0.17625 -0.00033 -0.86261 -0.50587 -0.00018 -0.86257 -0.50593 -0.00027 -0.63668 -0.77113 0.00000 -0.63652 -0.77126 0.00000 -0.33661 -0.94164 0.00000 -0.33661 -0.94164 0.17265 -0.86261 -0.47549 0.06015 -0.98435 -0.16567 0.26340 -0.63671 -0.72472 0.17282 -0.86257 -0.47550 0.26378 -0.63651 -0.72476 0.32204 -0.33661 -0.88486 0.32205 -0.33661 -0.88486 0.11317 -0.98435 -0.13512 0.32481 -0.86262 -0.38779 0.32501 -0.86257 -0.38773 0.49535 -0.63672 -0.59094 0.49578 -0.63649 -0.59083 0.60529 -0.33661 -0.72133 0.60529 -0.33661 -0.72133 0.43779 -0.86263 -0.25339 0.15254 -0.98435 -0.08829 0.43801 -0.86257 -0.25322 0.66756 -0.63673 -0.38593 0.81548 -0.33661 -0.47083 0.66796 -0.63648 -0.38565 0.81549 -0.33661 -0.47083 0.50219 -0.86149 -0.07512 0.17832 -0.98382 -0.01744 0.75944 -0.63670 -0.13368 0.49458 -0.86479 -0.08680 0.92820 -0.33635 -0.15910 0.76218 -0.63421 -0.12985 0.92804 -0.33665 -0.15942 0.99951 -0.02951 0.01072 0.99755 -0.01300 0.06870 0.99241 -0.09359 0.07981 0.98719 -0.10569 0.11953 0.97914 -0.20299 0.00898 0.97095 -0.21812 0.09841 0.93026 -0.36352 0.04963 0.99028 -0.10923 0.08615 0.97580 -0.18263 0.12026 0.93471 -0.34689 0.07742 0.91184 -0.39071 0.12605 0.97655 -0.18326 0.11302 0.96968 -0.20955 0.12572 0.90609 -0.40879 0.10909 0.90348 -0.41264 0.11598 0.97081 -0.21024 0.11544 0.97075 -0.21046 0.11555 0.90133 -0.41858 0.11136 0.90693 -0.41161 0.08971 0.97313 -0.21162 0.09076 0.97252 -0.21387 0.09195 0.90555 -0.41517 0.08727 0.91222 -0.40785 0.03889 0.94005 -0.34101 0.00346 0.97513 -0.21496 0.05390 0.67690 -0.72654 -0.11807 0.39136 -0.91190 -0.12361 0.67851 -0.72599 -0.11208 0.39401 -0.91117 -0.12055 0.12275 -0.98401 -0.12905 0.14727 -0.98306 -0.10906 0.88991 -0.44878 -0.08166 0.67546 -0.72994 -0.10459 0.97680 -0.20901 -0.04674 0.98737 -0.15822 0.00791 0.88256 -0.46708 -0.05410 0.67313 -0.73069 -0.11397 0.39452 -0.90629 -0.15161 0.15560 -0.97267 -0.17235 0.20498 -0.97043 -0.12751 0.41266 -0.90154 -0.13011 0.66864 -0.73621 -0.10446 0.87706 -0.47225 -0.08801 0.86294 -0.50345 -0.04334 0.97662 -0.20684 -0.05862 0.95305 -0.30225 0.01841 0.41286 -0.89892 -0.14658 0.66964 -0.73587 -0.10038 0.44440 -0.88902 -0.11024 0.21481 -0.96240 -0.16626 0.27767 -0.95538 -0.10076 0.66141 -0.74501 -0.08657 0.85760 -0.50858 -0.07656 0.89121 -0.45274 -0.02764 0.95307 -0.30015 0.03959 0.83220 -0.55424 -0.01632 0.66556 -0.74314 -0.06905 0.44439 -0.88903 -0.11017 0.28709 -0.95058 -0.11821 0.34986 -0.93602 -0.03830 0.48602 -0.87152 -0.06506 0.65156 -0.75687 -0.05118 0.82761 -0.55937 -0.04661 0.78701 -0.61653 0.02231 0.89950 -0.43693 0.00003 0.86262 -0.49633 0.09772 0.65879 -0.75209 -0.01890 0.48512 -0.87331 -0.04459 0.35396 -0.93430 -0.04231 0.52543 -0.85082 -0.00505 0.63807 -0.76997 0.00160 0.78437 -0.62028 0.00284 0.82782 -0.55858 0.05207 0.73553 -0.67452 0.06334 0.39538 -0.91773 0.03810 0.64629 -0.76188 0.04296 0.52248 -0.85197 0.03400 0.54333 -0.83792 0.05181 0.39770 -0.91679 0.03657 0.62616 -0.77739 0.05985 0.73516 -0.67524 0.05998 0.82094 -0.55921 0.11547 0.70120 -0.70680 0.09352 0.78542 -0.61244 0.08963 0.39986 -0.91211 0.09040 0.63090 -0.77059 0.09031 0.53956 -0.83714 0.08985 0.40328 -0.91078 0.08857 0.53892 -0.83760 0.08937 0.61786 -0.77982 0.10065 0.70174 -0.70532 0.10041 0.79437 -0.59751 0.10931 0.69151 -0.71401 0.10954 0.79482 -0.59711 0.10825 0.61953 -0.77621 0.11693 0.53560 -0.83585 0.12032 0.38696 -0.91454 0.11780 0.52138 -0.84620 0.11005 0.69199 -0.71170 0.12100 0.61360 -0.78018 0.12173 0.69919 -0.70570 0.11458 0.80324 -0.58413 0.11663 0.38034 -0.91836 0.10938 0.61362 -0.78013 0.12198 0.51954 -0.84480 0.12805 0.50050 -0.85817 0.11420 0.36156 -0.92374 0.12645 0.61190 -0.78124 0.12345 0.69924 -0.70444 0.12177 0.80209 -0.58681 0.11095 0.71282 -0.69283 0.10894 0.81707 -0.57022 0.08507 0.35851 -0.92917 0.09004 0.50061 -0.85828 0.11291 0.61155 -0.78419 0.10512 0.31995 -0.94054 0.11412 0.48311 -0.86987 0.09962 0.61072 -0.78474 0.10588 0.71291 -0.69370 0.10266 0.82253 -0.56124 0.09192 0.72364 -0.68407 0.09166 0.48471 -0.87160 0.07328 0.61061 -0.78919 0.06581 0.47298 -0.87876 0.06390 0.34302 -0.93650 0.07278 0.60756 -0.79129 0.06874 0.72415 -0.68671 0.06354 0.82020 -0.56902 0.05908 0.72526 -0.68565 0.06230 0.83514 -0.54897 0.03432 0.30890 -0.95080 0.02362 0.72544 -0.68826 -0.00498 0.76708 -0.63841 -0.06345 0.02223 -0.99318 -0.11441 -0.01814 -0.99371 -0.11047 0.03443 -0.99328 -0.11050 -0.02783 -0.99389 -0.10680 0.00962 -0.99402 -0.10880 -0.03387 -0.99478 -0.09629 0.07162 -0.99149 -0.10868 0.13935 -0.98044 -0.13899 -0.11159 -0.98321 -0.14441 0.07304 -0.98959 -0.12401 0.21395 -0.97158 -0.10128 0.14399 -0.98058 -0.13312 -0.14862 -0.98160 -0.11986 -0.03599 -0.99128 -0.12678 -0.04980 -0.99107 -0.12369 0.09626 -0.98851 -0.11651 -0.15618 -0.98019 -0.12183 0.19850 -0.97734 -0.07353 0.09327 -0.99439 -0.04984 0.26749 -0.96316 -0.02788 -0.20087 -0.97865 -0.04358 -0.04742 -0.99739 -0.05446 -0.05509 -0.99713 -0.05188 0.09839 -0.99400 -0.04784 -0.18248 -0.98245 -0.03874 0.20552 -0.97852 0.01597 0.26082 -0.96314 0.06586 0.09484 -0.99348 0.06329 -0.20065 -0.97736 0.06717 -0.05245 -0.99673 0.06144 -0.05856 -0.99624 0.06389 0.09195 -0.99382 0.06219 -0.19398 -0.97855 0.06932 0.21713 -0.97179 0.09212 0.09022 -0.98861 0.12044 0.23259 -0.96602 0.11273 -0.05736 -0.99109 0.12018 -0.19850 -0.97229 0.12345 -0.19714 -0.97251 0.12394 -0.06386 -0.99036 0.12292 0.08164 -0.98972 0.11745 0.21505 -0.96888 0.12256 0.08178 -0.99038 0.11160 0.20613 -0.97314 0.10250 -0.06407 -0.99172 0.11127 -0.19623 -0.97373 0.11551 -0.07243 -0.99073 0.11489 0.06958 -0.99176 0.10759 -0.20453 -0.97237 0.11255 0.20355 -0.97354 0.10383 0.17834 -0.98390 -0.01153 0.18002 -0.98361 -0.01052 0.07048 -0.99695 0.03347 -0.18521 -0.98268 -0.00555 -0.07328 -0.99664 0.03649 -0.19020 -0.98174 -0.00233 -0.67028 -0.71807 -0.18736 -0.68228 -0.71609 -0.14731 -0.40878 -0.90355 -0.12842 -0.14417 -0.98329 -0.11115 -0.38816 -0.90972 -0.14748 -0.98477 -0.16873 -0.04195 -0.67173 -0.73056 -0.12275 -0.14073 -0.98352 -0.11355 -0.87338 -0.47197 -0.12022 -0.87795 -0.45904 -0.13597 -0.97487 -0.20055 -0.09700 -0.97315 -0.22355 -0.05475 -0.38910 -0.90641 -0.16435 -0.66437 -0.73138 -0.15394 -0.40190 -0.90313 -0.15112 -0.21004 -0.96322 -0.16760 -0.14657 -0.97906 -0.14130 -0.86757 -0.47493 -0.14754 -0.65566 -0.74237 -0.13783 -0.95633 -0.26423 -0.12493 -0.85042 -0.51771 -0.09359 -0.94397 -0.32865 -0.03017 -0.40225 -0.90184 -0.15774 -0.65561 -0.74237 -0.13807 -0.31463 -0.93733 -0.14976 -0.18752 -0.97525 -0.11711 -0.42979 -0.89342 -0.13069 -0.84324 -0.52174 -0.12935 -0.63949 -0.76019 -0.11473 -0.80866 -0.58586 -0.05320 -0.92670 -0.36382 -0.09418 -0.89314 -0.44909 0.02497 -0.64455 -0.75899 -0.09212 -0.42857 -0.89652 -0.11216 -0.27717 -0.95443 -0.11060 -0.46761 -0.88060 -0.07671 -0.80460 -0.58891 -0.07620 -0.61810 -0.78350 -0.06387 -0.74688 -0.66491 0.00808 -0.87635 -0.48097 -0.02605 -0.82853 -0.55376 0.08299 -0.34041 -0.94013 -0.01699 -0.46303 -0.88590 -0.02797 -0.62775 -0.77828 -0.01457 -0.49928 -0.86644 0.00184 -0.34509 -0.93836 -0.01968 -0.74673 -0.66509 0.00703 -0.59594 -0.80296 0.01081 -0.81428 -0.57815 0.05191 -0.68723 -0.72339 0.06656 -0.35638 -0.93105 0.07835 -0.49176 -0.86856 0.06141 -0.60457 -0.79365 0.06788 -0.38872 -0.91905 0.06515 -0.50811 -0.85814 0.07369 -0.68882 -0.72016 0.08305 -0.58579 -0.80648 0.08025 -0.66255 -0.74185 0.10335 -0.78791 -0.60683 0.10463 -0.76748 -0.63009 0.11818 -0.58975 -0.79824 0.12249 -0.50168 -0.85686 0.11877 -0.50110 -0.85726 0.11834 -0.35537 -0.92771 0.11432 -0.58747 -0.79970 0.12390 -0.66384 -0.73668 0.12890 -0.77086 -0.62291 0.13326 -0.67093 -0.73109 0.12396 -0.36416 -0.92284 0.12548 -0.49759 -0.85543 0.14368 -0.58832 -0.79513 0.14714 -0.48921 -0.86128 0.13739 -0.34847 -0.92739 0.13608 -0.59586 -0.79038 0.14231 -0.67103 -0.72634 0.14886 -0.77873 -0.61514 0.12322 -0.79949 -0.58245 0.14687 -0.69421 -0.70748 0.13245 -0.59586 -0.79039 0.14224 -0.48920 -0.86127 0.13750 -0.34903 -0.93002 0.11504 -0.48077 -0.86705 0.13075 -0.31946 -0.93891 0.12806 -0.60576 -0.78404 0.13542 -0.69385 -0.70563 0.14372 -0.71707 -0.68553 0.12589 -0.79844 -0.58607 0.13791 -0.60650 -0.78777 0.10763 -0.48346 -0.86963 0.10007 -0.34769 -0.93308 0.09203 -0.48080 -0.87136 0.09780 -0.81869 -0.56324 0.11184 -0.61399 -0.78268 0.10210 -0.71775 -0.68733 0.11142 -0.73035 -0.67561 0.10075 -0.81854 -0.56354 0.11144 -0.31376 -0.94890 0.03382 -0.83204 -0.54949 0.07596 -0.61532 -0.78735 0.03828 -0.49664 -0.86705 -0.03972 -0.48479 -0.87424 -0.02599 -0.73242 -0.68062 0.01788 -0.76038 -0.64925 -0.01717 -0.99897 -0.02277 -0.03915 -0.99986 -0.01475 0.00849 -0.98375 -0.17861 0.01813 -0.99685 0.01506 -0.07784 -0.98943 -0.13338 0.05683 -0.97592 -0.21175 -0.05236 -0.92437 -0.37496 0.07034 -0.97187 -0.23444 -0.02237 -0.99013 -0.13632 0.03244 -0.97395 -0.21417 0.07446 -0.92371 -0.37938 0.05321 -0.97228 -0.21198 0.09871 -0.89409 -0.43290 0.11490 -0.96519 -0.23621 0.11231 -0.89489 -0.43069 0.11693 -0.88674 -0.44327 0.13118 -0.96207 -0.23408 0.14010 -0.96356 -0.22934 0.13766 -0.88968 -0.43458 0.14006 -0.89990 -0.41813 0.12388 -0.96340 -0.22926 0.13894 -0.96794 -0.21402 0.13148 -0.90059 -0.41583 0.12656 -0.91393 -0.39734 0.08277 -0.91458 -0.39600 0.08208 -0.97224 -0.21562 0.09088 -0.96454 -0.24231 0.10462 -0.98159 -0.00743 -0.19084 -0.98281 -0.00152 -0.18459 -0.98795 -0.04629 -0.14768 -0.99234 -0.00253 -0.12354 -0.99420 -0.03119 -0.10292 -0.99389 0.00000 -0.11040 -0.99412 0.02896 -0.10430 -0.99299 0.00268 -0.11817 -0.98795 0.04626 -0.14768 + + + + + + + + + + + + + + +

631 0 0 0 632 0 1 1 0 1 631 1 2 2 0 2 1 2 3 3 2 3 1 3 3 4 4 4 5 4 2 5 3 5 5 5 6 6 4 6 3 6 631 7 625 7 1 7 1 8 7 8 3 8 7 9 1 9 625 9 8 10 3 10 7 10 3 11 8 11 6 11 9 12 6 12 8 12 625 13 622 13 7 13 7 14 10 14 8 14 10 15 7 15 622 15 11 16 8 16 10 16 8 17 11 17 9 17 12 18 9 18 11 18 622 19 619 19 10 19 13 20 10 20 619 20 10 21 13 21 11 21 11 22 14 22 12 22 14 23 11 23 13 23 15 24 12 24 14 24 619 25 616 25 13 25 13 26 16 26 14 26 16 27 13 27 616 27 17 28 14 28 16 28 17 29 18 29 15 29 14 30 17 30 15 30 19 31 18 31 17 31 616 32 20 32 16 32 21 33 16 33 20 33 16 34 21 34 17 34 23 35 22 35 19 35 17 36 23 36 19 36 17 37 21 37 23 37 24 38 22 38 23 38 25 39 5 39 26 39 27 40 25 40 26 40 30 41 28 41 29 41 25 42 30 42 29 42 30 43 25 43 27 43 5 44 4 44 26 44 31 45 29 45 28 45 32 46 26 46 4 46 26 47 32 47 27 47 33 48 27 48 32 48 27 49 33 49 30 49 4 50 6 50 32 50 34 51 28 51 30 51 28 52 34 52 31 52 30 53 35 53 34 53 35 54 30 54 33 54 36 55 32 55 6 55 32 56 36 56 33 56 37 57 33 57 36 57 33 58 37 58 35 58 34 59 38 59 31 59 38 60 34 60 35 60 39 61 31 61 38 61 35 62 40 62 38 62 40 63 35 63 37 63 36 64 41 64 37 64 41 65 36 65 6 65 6 66 9 66 41 66 42 67 37 67 41 67 37 68 42 68 40 68 38 69 43 69 39 69 43 70 38 70 40 70 44 71 40 71 42 71 40 72 44 72 43 72 45 73 39 73 43 73 41 74 46 74 42 74 46 75 41 75 9 75 47 76 42 76 46 76 42 77 47 77 44 77 43 78 48 78 45 78 48 79 43 79 44 79 44 80 49 80 48 80 49 81 44 81 47 81 46 82 9 82 12 82 50 83 46 83 12 83 46 84 50 84 47 84 47 85 51 85 49 85 51 86 47 86 50 86 52 87 48 87 49 87 48 88 52 88 45 88 53 89 49 89 51 89 49 90 53 90 52 90 54 91 45 91 52 91 50 92 55 92 51 92 55 93 50 93 12 93 51 94 56 94 53 94 56 95 51 95 55 95 52 96 57 96 54 96 57 97 52 97 53 97 58 98 53 98 56 98 53 99 58 99 57 99 59 100 54 100 57 100 55 101 12 101 15 101 60 102 55 102 15 102 55 103 60 103 56 103 56 104 61 104 58 104 61 105 56 105 60 105 62 106 57 106 58 106 57 107 62 107 59 107 58 108 63 108 62 108 63 109 58 109 61 109 15 110 18 110 60 110 64 111 60 111 18 111 60 112 64 112 61 112 61 113 65 113 63 113 65 114 61 114 64 114 66 115 62 115 63 115 66 116 67 116 59 116 62 117 66 117 59 117 68 118 63 118 65 118 63 119 68 119 66 119 18 120 19 120 64 120 64 121 69 121 65 121 69 122 64 122 19 122 65 123 70 123 68 123 70 124 65 124 69 124 71 125 72 125 67 125 66 126 71 126 67 126 71 127 66 127 68 127 73 128 68 128 70 128 68 129 73 129 71 129 19 130 22 130 69 130 74 131 69 131 22 131 74 132 75 132 70 132 69 133 74 133 70 133 76 134 72 134 71 134 70 135 75 135 73 135 22 136 24 136 74 136 71 137 73 137 77 137 71 138 77 138 76 138 78 139 77 139 73 139 78 140 73 140 75 140 79 141 78 141 75 141 83 142 29 142 31 142 83 143 81 143 82 143 29 144 83 144 82 144 84 145 82 145 81 145 84 146 85 146 86 146 84 147 86 147 82 147 87 148 85 148 84 148 31 149 39 149 83 149 81 150 88 150 84 150 88 151 81 151 83 151 89 152 83 152 39 152 83 153 89 153 88 153 84 154 90 154 87 154 90 155 84 155 88 155 91 156 87 156 90 156 88 157 92 157 90 157 92 158 88 158 89 158 89 159 39 159 45 159 93 160 89 160 45 160 89 161 93 161 92 161 90 162 94 162 91 162 94 163 90 163 92 163 95 164 91 164 94 164 45 165 54 165 93 165 92 166 96 166 94 166 96 167 92 167 93 167 93 168 97 168 96 168 97 169 93 169 54 169 98 170 94 170 96 170 94 171 98 171 95 171 99 172 95 172 98 172 54 173 59 173 97 173 96 174 100 174 98 174 100 175 96 175 97 175 97 176 101 176 100 176 101 177 97 177 59 177 98 178 102 178 99 178 102 179 98 179 100 179 103 180 99 180 102 180 59 181 67 181 101 181 100 182 104 182 102 182 104 183 100 183 101 183 101 184 105 184 104 184 105 185 101 185 67 185 106 186 107 186 103 186 102 187 106 187 103 187 106 188 102 188 104 188 67 189 72 189 105 189 108 190 107 190 106 190 104 191 109 191 106 191 109 192 104 192 105 192 110 193 109 193 105 193 110 194 105 194 72 194 106 195 109 195 108 195 72 196 76 196 110 196 111 197 108 197 109 197 113 198 114 198 112 198 115 199 113 199 112 199 86 200 85 200 116 200 118 201 114 201 113 201 119 202 113 202 115 202 113 203 119 203 118 203 115 204 120 204 119 204 120 205 115 205 117 205 121 206 116 206 85 206 116 207 121 207 117 207 117 208 122 208 120 208 122 209 117 209 121 209 123 210 119 210 120 210 119 211 123 211 118 211 120 212 124 212 123 212 124 213 120 213 122 213 121 214 125 214 122 214 125 215 121 215 85 215 122 216 126 216 124 216 126 217 122 217 125 217 85 218 87 218 125 218 127 219 118 219 123 219 128 220 123 220 124 220 123 221 128 221 127 221 124 222 129 222 128 222 129 223 124 223 126 223 130 224 125 224 87 224 125 225 130 225 126 225 131 226 126 226 130 226 126 227 131 227 129 227 87 228 91 228 130 228 128 229 132 229 127 229 132 230 128 230 129 230 133 231 129 231 131 231 129 232 133 232 132 232 130 233 134 233 131 233 134 234 130 234 91 234 135 235 131 235 134 235 131 236 135 236 133 236 136 237 127 237 132 237 137 238 132 238 133 238 132 239 137 239 136 239 133 240 138 240 137 240 138 241 133 241 135 241 134 242 139 242 135 242 139 243 134 243 91 243 140 244 135 244 139 244 135 245 140 245 138 245 91 246 95 246 139 246 137 247 141 247 136 247 141 248 137 248 138 248 142 249 136 249 141 249 138 250 143 250 141 250 143 251 138 251 140 251 144 252 139 252 95 252 139 253 144 253 140 253 145 254 140 254 144 254 140 255 145 255 143 255 95 256 99 256 144 256 146 257 141 257 143 257 141 258 146 258 142 258 143 259 147 259 146 259 147 260 143 260 145 260 144 261 148 261 145 261 148 262 144 262 99 262 149 263 145 263 148 263 145 264 149 264 147 264 150 265 142 265 146 265 146 266 151 266 150 266 151 267 146 267 147 267 147 268 152 268 151 268 152 269 147 269 149 269 148 270 153 270 149 270 148 271 99 271 103 271 153 272 148 272 103 272 154 273 149 273 153 273 149 274 154 274 152 274 155 275 151 275 152 275 155 276 156 276 150 276 151 277 155 277 150 277 152 278 157 278 155 278 157 279 152 279 154 279 153 280 103 280 107 280 158 281 153 281 107 281 153 282 158 282 154 282 154 283 159 283 157 283 159 284 154 284 158 284 160 285 156 285 155 285 155 286 161 286 160 286 161 287 155 287 157 287 157 288 162 288 161 288 162 289 157 289 159 289 158 290 163 290 159 290 158 291 107 291 108 291 163 292 158 292 108 292 164 293 159 293 163 293 159 294 164 294 162 294 161 295 162 295 165 295 165 296 166 296 160 296 161 297 165 297 160 297 167 298 162 298 164 298 167 299 165 299 162 299 108 300 111 300 163 300 168 301 163 301 111 301 163 302 168 302 164 302 164 303 169 303 167 303 164 304 168 304 169 304 170 305 167 305 169 305 171 306 462 306 172 306 463 307 462 307 171 307 173 308 171 308 172 308 114 309 173 309 172 309 173 310 114 310 118 310 118 311 127 311 173 311 174 312 171 312 173 312 171 313 174 313 463 313 175 314 463 314 174 314 173 315 176 315 174 315 176 316 173 316 127 316 127 317 136 317 176 317 177 318 174 318 176 318 174 319 177 319 175 319 178 320 175 320 177 320 176 321 179 321 177 321 179 322 176 322 136 322 136 323 142 323 179 323 180 324 177 324 179 324 177 325 180 325 178 325 181 326 178 326 180 326 179 327 182 327 180 327 182 328 179 328 142 328 142 329 150 329 182 329 180 330 183 330 181 330 183 331 180 331 182 331 184 332 181 332 183 332 182 333 185 333 183 333 182 334 150 334 156 334 185 335 182 335 156 335 156 336 160 336 185 336 183 337 186 337 184 337 186 338 183 338 185 338 187 339 185 339 160 339 187 340 186 340 185 340 160 341 166 341 187 341 454 342 172 342 462 342 190 343 114 343 172 343 190 344 172 344 454 344 191 345 112 345 114 345 191 346 114 346 190 346 112 347 192 347 86 347 192 348 112 348 191 348 86 349 193 349 82 349 193 350 86 350 192 350 454 351 450 351 190 351 194 352 190 352 450 352 190 353 194 353 191 353 191 354 195 354 192 354 195 355 191 355 194 355 196 356 192 356 195 356 192 357 196 357 193 357 193 358 197 358 82 358 197 359 193 359 196 359 450 360 446 360 194 360 198 361 194 361 446 361 194 362 198 362 195 362 199 363 195 363 198 363 195 364 199 364 196 364 200 365 196 365 199 365 196 366 200 366 197 366 201 367 197 367 200 367 197 368 201 368 82 368 446 369 442 369 198 369 202 370 198 370 442 370 198 371 202 371 199 371 203 372 199 372 202 372 199 373 203 373 200 373 200 374 204 374 201 374 204 375 200 375 203 375 201 376 205 376 82 376 205 377 201 377 204 377 442 378 438 378 202 378 206 379 202 379 438 379 202 380 206 380 203 380 207 381 203 381 206 381 203 382 207 382 204 382 208 383 204 383 207 383 204 384 208 384 205 384 209 385 205 385 208 385 205 386 209 386 82 386 438 387 434 387 206 387 210 388 206 388 434 388 206 389 210 389 207 389 207 390 211 390 208 390 211 391 207 391 210 391 212 392 208 392 211 392 208 393 212 393 209 393 209 394 213 394 82 394 213 395 209 395 212 395 434 396 430 396 210 396 214 397 210 397 430 397 210 398 214 398 211 398 211 399 215 399 212 399 215 400 211 400 214 400 216 401 212 401 215 401 212 402 216 402 213 402 217 403 213 403 216 403 213 404 217 404 82 404 430 405 426 405 214 405 214 406 218 406 215 406 218 407 214 407 426 407 215 408 219 408 216 408 219 409 215 409 218 409 220 410 216 410 219 410 216 411 220 411 217 411 221 412 217 412 220 412 217 413 221 413 82 413 426 414 632 414 218 414 632 415 0 415 218 415 219 416 5 416 220 416 221 417 25 417 29 417 82 418 221 418 29 418 25 419 220 419 5 419 220 420 25 420 221 420 222 421 223 421 224 421 225 422 222 422 224 422 422 423 224 423 223 423 226 424 224 424 422 424 422 425 419 425 226 425 227 426 226 426 419 426 419 427 418 427 227 427 228 428 227 428 418 428 418 429 417 429 228 429 229 430 228 430 417 430 417 431 416 431 229 431 230 432 229 432 416 432 416 433 415 433 230 433 231 434 230 434 415 434 415 435 414 435 231 435 232 436 231 436 414 436 414 437 413 437 232 437 233 438 232 438 413 438 413 439 412 439 233 439 234 440 233 440 412 440 412 441 411 441 234 441 235 442 234 442 411 442 411 443 410 443 235 443 236 444 235 444 410 444 410 445 409 445 236 445 237 446 236 446 409 446 409 447 408 447 237 447 238 448 237 448 408 448 408 449 407 449 238 449 239 450 238 450 407 450 407 451 406 451 239 451 240 452 239 452 406 452 406 453 405 453 240 453 240 454 405 454 188 454 240 455 188 455 241 455 240 456 241 456 189 456 240 457 189 457 80 457 242 458 240 458 80 458 244 459 225 459 224 459 245 460 244 460 224 460 247 461 246 461 245 461 224 462 226 462 245 462 245 463 226 463 227 463 248 464 245 464 227 464 248 465 249 465 247 465 245 466 248 466 247 466 250 467 249 467 248 467 227 468 228 468 248 468 251 469 252 469 250 469 248 470 251 470 250 470 251 471 248 471 228 471 228 472 229 472 251 472 253 473 252 473 251 473 251 474 229 474 230 474 254 475 251 475 230 475 251 476 254 476 253 476 255 477 253 477 254 477 230 478 231 478 254 478 254 479 231 479 232 479 256 480 254 480 232 480 256 481 257 481 255 481 254 482 256 482 255 482 232 483 233 483 256 483 258 484 257 484 256 484 256 485 233 485 234 485 259 486 256 486 234 486 259 487 260 487 258 487 256 488 259 488 258 488 234 489 235 489 259 489 261 490 260 490 259 490 259 491 235 491 236 491 262 492 259 492 236 492 259 493 262 493 261 493 263 494 261 494 262 494 236 495 237 495 262 495 264 496 265 496 263 496 262 497 264 497 263 497 264 498 262 498 237 498 237 499 238 499 264 499 266 500 265 500 264 500 267 501 268 501 266 501 264 502 267 502 266 502 264 503 238 503 239 503 267 504 264 504 239 504 239 505 240 505 267 505 269 506 268 506 267 506 267 507 242 507 269 507 267 508 240 508 242 508 270 509 269 509 242 509 79 510 243 510 271 510 246 511 271 511 243 511 272 512 271 512 246 512 246 513 247 513 272 513 273 514 272 514 247 514 247 515 249 515 273 515 274 516 273 516 249 516 249 517 250 517 274 517 274 518 250 518 252 518 275 519 274 519 252 519 252 520 253 520 275 520 276 521 275 521 253 521 253 522 255 522 276 522 277 523 276 523 255 523 255 524 257 524 277 524 278 525 277 525 257 525 257 526 258 526 278 526 279 527 278 527 258 527 258 528 260 528 279 528 280 529 279 529 260 529 260 530 261 530 280 530 281 531 280 531 261 531 261 532 263 532 281 532 281 533 263 533 265 533 282 534 281 534 265 534 265 535 266 535 282 535 283 536 282 536 266 536 266 537 268 537 283 537 284 538 283 538 268 538 268 539 269 539 284 539 285 540 284 540 269 540 269 541 270 541 285 541 285 542 270 542 286 542 284 543 285 543 287 543 288 544 289 544 290 544 288 545 290 545 287 545 288 546 287 546 285 546 285 547 286 547 288 547 291 548 289 548 288 548 288 549 292 549 291 549 288 550 286 550 292 550 293 551 291 551 292 551 294 552 293 552 292 552 292 553 168 553 294 553 294 554 168 554 295 554 297 555 295 555 296 555 300 556 299 556 298 556 298 557 301 557 300 557 302 558 300 558 301 558 301 559 303 559 302 559 304 560 302 560 303 560 79 561 271 561 303 561 303 562 271 562 272 562 303 563 272 563 305 563 303 564 305 564 304 564 306 565 304 565 305 565 297 566 299 566 295 566 294 567 295 567 299 567 299 568 300 568 294 568 293 569 294 569 300 569 300 570 302 570 293 570 291 571 293 571 302 571 302 572 304 572 291 572 289 573 291 573 304 573 304 574 306 574 289 574 290 575 289 575 306 575 306 576 307 576 290 576 308 577 290 577 307 577 307 578 309 578 308 578 310 579 308 579 309 579 309 580 311 580 310 580 312 581 310 581 311 581 311 582 313 582 312 582 314 583 312 583 313 583 313 584 315 584 314 584 316 585 314 585 315 585 272 586 273 586 305 586 317 587 305 587 273 587 317 588 307 588 306 588 317 589 306 589 305 589 273 590 274 590 317 590 309 591 307 591 317 591 318 592 311 592 309 592 317 593 318 593 309 593 317 594 274 594 275 594 318 595 317 595 275 595 275 596 276 596 318 596 313 597 311 597 318 597 318 598 276 598 277 598 319 599 318 599 277 599 318 600 319 600 313 600 315 601 313 601 319 601 277 602 278 602 319 602 320 603 319 603 278 603 320 604 316 604 315 604 319 605 320 605 315 605 278 606 279 606 320 606 314 607 316 607 320 607 320 608 279 608 280 608 321 609 320 609 280 609 320 610 321 610 314 610 312 611 314 611 321 611 280 612 281 612 321 612 322 613 310 613 312 613 321 614 322 614 312 614 321 615 281 615 282 615 322 616 321 616 282 616 308 617 310 617 322 617 282 618 283 618 322 618 322 619 283 619 284 619 322 620 284 620 287 620 322 621 287 621 308 621 290 622 308 622 287 622 167 623 270 623 242 623 242 624 165 624 167 624 170 625 286 625 270 625 170 626 270 626 167 626 292 627 286 627 170 627 168 628 292 628 170 628 168 629 111 629 295 629 170 630 169 630 168 630 301 631 298 631 303 631 78 632 303 632 298 632 303 633 78 633 79 633 297 634 76 634 298 634 298 635 77 635 78 635 298 636 76 636 77 636 75 637 243 637 79 637 24 638 225 638 244 638 244 639 74 639 24 639 74 640 244 640 243 640 243 641 75 641 74 641 225 642 24 642 222 642 186 643 241 643 188 643 186 644 187 644 241 644 187 645 189 645 241 645 166 646 189 646 187 646 80 647 189 647 166 647 80 648 166 648 165 648 80 649 165 649 242 649 109 650 295 650 111 650 109 651 296 651 295 651 109 652 110 652 296 652 76 653 296 653 110 653 76 654 297 654 296 654 297 655 298 655 299 655 244 656 245 656 246 656 243 657 244 657 246 657 5 658 219 658 218 658 2 659 5 659 218 659 0 660 2 660 218 660 86 661 117 661 112 661 112 662 117 662 115 662 86 663 116 663 117 663 548 664 517 664 518 664 522 665 519 665 517 665 548 666 522 666 517 666 632 667 426 667 630 667 630 668 426 668 627 668 627 669 426 669 425 669 402 670 399 670 401 670 401 671 399 671 400 671 348 672 346 672 347 672 558 673 349 673 348 673 558 674 524 674 349 674 525 675 349 675 524 675 525 676 350 676 349 676 525 677 523 677 350 677 554 678 403 678 469 678 554 679 469 679 468 679 554 680 468 680 455 680 468 681 456 681 455 681 456 682 404 682 455 682 186 683 404 683 456 683 186 684 188 684 404 684 420 685 421 685 610 685 402 686 560 686 559 686 560 687 402 687 401 687 401 688 610 688 560 688 610 689 401 689 420 689 559 690 555 690 402 690 347 691 557 691 558 691 347 692 556 692 557 692 348 693 347 693 558 693 342 694 555 694 556 694 556 695 347 695 342 695 344 696 342 696 347 696 464 697 466 697 465 697 466 698 350 698 523 698 466 699 464 699 353 699 353 700 464 700 359 700 464 701 467 701 375 701 464 702 375 702 359 702 403 703 467 703 469 703 467 704 403 704 375 704 355 705 358 705 337 705 323 706 337 706 358 706 323 707 358 707 361 707 323 708 361 708 362 708 363 709 323 709 362 709 337 710 323 710 335 710 323 711 363 711 324 711 324 712 363 712 364 712 324 713 333 713 323 713 323 714 333 714 335 714 365 715 324 715 364 715 333 716 324 716 331 716 325 717 331 717 324 717 324 718 365 718 325 718 325 719 365 719 366 719 331 720 325 720 329 720 367 721 325 721 366 721 326 722 330 722 325 722 325 723 330 723 329 723 325 724 367 724 326 724 368 725 326 725 367 725 330 726 326 726 332 726 327 727 332 727 326 727 326 728 368 728 327 728 327 729 368 729 369 729 332 730 327 730 334 730 370 731 327 731 369 731 327 732 370 732 328 732 328 733 370 733 371 733 328 734 336 734 327 734 327 735 336 735 334 735 336 736 328 736 338 736 372 737 328 737 371 737 328 738 340 738 339 738 328 739 339 739 338 739 328 740 372 740 340 740 373 741 340 741 372 741 329 742 330 742 331 742 332 743 331 743 330 743 331 744 332 744 333 744 334 745 333 745 332 745 333 746 334 746 335 746 336 747 335 747 334 747 335 748 336 748 337 748 338 749 337 749 336 749 337 750 338 750 355 750 339 751 355 751 338 751 355 752 339 752 356 752 341 753 356 753 339 753 356 754 341 754 354 754 343 755 354 755 341 755 354 756 343 756 352 756 345 757 352 757 343 757 352 758 345 758 351 758 346 759 351 759 345 759 351 760 346 760 350 760 348 761 350 761 346 761 339 762 340 762 341 762 342 763 341 763 340 763 342 764 340 764 373 764 342 765 373 765 374 765 555 766 342 766 374 766 341 767 342 767 343 767 344 768 343 768 342 768 343 769 344 769 345 769 347 770 345 770 344 770 345 771 347 771 346 771 348 772 349 772 350 772 351 773 350 773 466 773 353 774 351 774 466 774 351 775 353 775 352 775 352 776 353 776 354 776 357 777 353 777 359 777 357 778 354 778 353 778 354 779 357 779 356 779 360 780 357 780 359 780 357 781 360 781 358 781 357 782 358 782 355 782 357 783 355 783 356 783 361 784 358 784 360 784 360 785 359 785 375 785 376 786 360 786 375 786 360 787 376 787 361 787 377 788 361 788 376 788 361 789 377 789 362 789 379 790 362 790 377 790 362 791 379 791 363 791 380 792 363 792 379 792 363 793 380 793 364 793 364 794 380 794 382 794 384 795 364 795 382 795 364 796 384 796 365 796 385 797 365 797 384 797 365 798 385 798 366 798 387 799 366 799 385 799 366 800 387 800 367 800 388 801 367 801 387 801 367 802 388 802 368 802 390 803 368 803 388 803 368 804 390 804 369 804 392 805 369 805 390 805 369 806 392 806 370 806 393 807 370 807 392 807 370 808 393 808 371 808 371 809 393 809 395 809 396 810 371 810 395 810 371 811 396 811 372 811 398 812 372 812 396 812 372 813 398 813 373 813 399 814 373 814 398 814 373 815 399 815 374 815 399 816 402 816 374 816 555 817 374 817 402 817 375 818 403 818 376 818 378 819 403 819 405 819 378 820 376 820 403 820 376 821 378 821 377 821 406 822 378 822 405 822 378 823 406 823 381 823 381 824 406 824 407 824 381 825 379 825 378 825 378 826 379 826 377 826 379 827 381 827 380 827 408 828 381 828 407 828 381 829 408 829 383 829 383 830 382 830 381 830 381 831 382 831 380 831 409 832 383 832 408 832 382 833 383 833 384 833 386 834 384 834 383 834 383 835 409 835 386 835 386 836 409 836 410 836 384 837 386 837 385 837 411 838 386 838 410 838 389 839 387 839 386 839 386 840 387 840 385 840 386 841 411 841 389 841 389 842 411 842 412 842 387 843 389 843 388 843 413 844 389 844 412 844 391 845 390 845 389 845 389 846 390 846 388 846 389 847 413 847 391 847 391 848 413 848 414 848 415 849 391 849 414 849 390 850 391 850 392 850 394 851 392 851 391 851 391 852 415 852 394 852 394 853 415 853 416 853 392 854 394 854 393 854 417 855 394 855 416 855 394 856 417 856 397 856 397 857 395 857 394 857 394 858 395 858 393 858 418 859 397 859 417 859 395 860 397 860 396 860 400 861 398 861 397 861 397 862 398 862 396 862 397 863 418 863 400 863 400 864 418 864 419 864 422 865 400 865 419 865 398 866 400 866 399 866 400 867 422 867 401 867 401 868 422 868 420 868 403 869 554 869 405 869 405 870 554 870 455 870 405 871 455 871 404 871 405 872 404 872 188 872 424 873 423 873 609 873 609 874 627 874 424 874 552 875 605 875 423 875 423 876 605 876 609 876 425 877 424 877 627 877 427 878 552 878 423 878 423 879 424 879 427 879 428 880 427 880 424 880 424 881 425 881 428 881 425 882 426 882 429 882 429 883 428 883 425 883 430 884 429 884 426 884 431 885 552 885 427 885 427 886 428 886 431 886 432 887 431 887 428 887 428 888 429 888 432 888 429 889 430 889 433 889 433 890 432 890 429 890 434 891 433 891 430 891 431 892 432 892 435 892 435 893 552 893 431 893 436 894 435 894 432 894 432 895 433 895 436 895 433 896 434 896 437 896 437 897 436 897 433 897 438 898 437 898 434 898 439 899 552 899 435 899 435 900 436 900 439 900 440 901 439 901 436 901 436 902 437 902 440 902 441 903 440 903 437 903 437 904 438 904 441 904 442 905 441 905 438 905 439 906 440 906 443 906 443 907 552 907 439 907 440 908 441 908 444 908 444 909 443 909 440 909 445 910 444 910 441 910 441 911 442 911 445 911 446 912 445 912 442 912 447 913 552 913 443 913 443 914 444 914 447 914 448 915 447 915 444 915 444 916 445 916 448 916 449 917 448 917 445 917 445 918 446 918 449 918 450 919 449 919 446 919 447 920 448 920 451 920 451 921 552 921 447 921 452 922 451 922 448 922 448 923 449 923 452 923 449 924 450 924 453 924 453 925 452 925 449 925 454 926 453 926 450 926 451 927 452 927 548 927 548 928 552 928 451 928 452 929 453 929 522 929 522 930 548 930 452 930 453 931 454 931 520 931 453 932 520 932 522 932 454 933 462 933 520 933 474 934 456 934 468 934 456 935 457 935 186 935 456 936 474 936 457 936 186 937 457 937 184 937 478 938 457 938 474 938 457 939 478 939 458 939 458 940 478 940 484 940 458 941 184 941 457 941 184 942 458 942 181 942 492 943 458 943 484 943 458 944 492 944 459 944 459 945 181 945 458 945 181 946 459 946 178 946 498 947 459 947 492 947 459 948 498 948 460 948 460 949 178 949 459 949 178 950 460 950 175 950 507 951 460 951 498 951 460 952 507 952 461 952 461 953 175 953 460 953 175 954 461 954 463 954 516 955 461 955 507 955 461 956 516 956 520 956 520 957 462 957 461 957 461 958 462 958 463 958 464 959 465 959 467 959 470 960 465 960 466 960 470 961 467 961 465 961 471 962 470 962 466 962 466 963 523 963 471 963 526 964 471 964 523 964 467 965 472 965 469 965 467 966 470 966 472 966 473 967 474 967 469 967 469 968 474 968 468 968 473 969 469 969 472 969 475 970 472 970 470 970 470 971 471 971 475 971 471 972 526 972 476 972 476 973 526 973 527 973 476 974 475 974 471 974 472 975 475 975 477 975 477 976 473 976 472 976 473 977 477 977 479 977 479 978 474 978 473 978 474 979 479 979 478 979 475 980 476 980 480 980 480 981 477 981 475 981 481 982 480 982 476 982 476 983 527 983 481 983 481 984 527 984 531 984 477 985 480 985 482 985 482 986 479 986 477 986 483 987 484 987 479 987 479 988 484 988 478 988 479 989 482 989 483 989 485 990 482 990 480 990 480 991 481 991 485 991 481 992 531 992 486 992 486 993 531 993 535 993 486 994 485 994 481 994 482 995 485 995 487 995 487 996 483 996 482 996 483 997 487 997 488 997 488 998 484 998 483 998 484 999 488 999 492 999 489 1000 487 1000 485 1000 485 1001 486 1001 489 1001 486 1002 535 1002 490 1002 490 1003 489 1003 486 1003 487 1004 489 1004 491 1004 491 1005 488 1005 487 1005 493 1006 492 1006 488 1006 488 1007 491 1007 493 1007 539 1008 490 1008 535 1008 494 1009 491 1009 489 1009 489 1010 490 1010 494 1010 495 1011 494 1011 490 1011 490 1012 539 1012 495 1012 491 1013 494 1013 496 1013 496 1014 493 1014 491 1014 492 1015 493 1015 498 1015 493 1016 496 1016 497 1016 497 1017 498 1017 493 1017 543 1018 495 1018 539 1018 499 1019 496 1019 494 1019 494 1020 495 1020 499 1020 495 1021 543 1021 500 1021 500 1022 499 1022 495 1022 496 1023 499 1023 501 1023 501 1024 497 1024 496 1024 502 1025 498 1025 497 1025 497 1026 501 1026 502 1026 498 1027 502 1027 507 1027 503 1028 501 1028 499 1028 499 1029 500 1029 503 1029 500 1030 543 1030 504 1030 504 1031 503 1031 500 1031 505 1032 502 1032 501 1032 501 1033 503 1033 505 1033 502 1034 505 1034 506 1034 506 1035 507 1035 502 1035 547 1036 504 1036 543 1036 508 1037 505 1037 503 1037 503 1038 504 1038 508 1038 509 1039 508 1039 504 1039 504 1040 547 1040 509 1040 505 1041 508 1041 510 1041 510 1042 506 1042 505 1042 511 1043 507 1043 506 1043 506 1044 510 1044 511 1044 507 1045 511 1045 516 1045 549 1046 509 1046 547 1046 508 1047 509 1047 512 1047 512 1048 510 1048 508 1048 509 1049 549 1049 513 1049 513 1050 512 1050 509 1050 510 1051 512 1051 514 1051 514 1052 511 1052 510 1052 515 1053 516 1053 511 1053 511 1054 514 1054 515 1054 512 1055 513 1055 517 1055 517 1056 514 1056 512 1056 518 1057 517 1057 513 1057 513 1058 549 1058 518 1058 514 1059 517 1059 519 1059 519 1060 515 1060 514 1060 521 1061 516 1061 515 1061 515 1062 519 1062 521 1062 516 1063 521 1063 520 1063 548 1064 518 1064 549 1064 519 1065 522 1065 521 1065 521 1066 522 1066 520 1066 523 1067 525 1067 526 1067 562 1068 524 1068 558 1068 528 1069 526 1069 525 1069 524 1070 562 1070 529 1070 524 1071 529 1071 525 1071 525 1072 529 1072 530 1072 530 1073 528 1073 525 1073 526 1074 528 1074 527 1074 567 1075 529 1075 562 1075 528 1076 530 1076 532 1076 532 1077 531 1077 528 1077 528 1078 531 1078 527 1078 529 1079 567 1079 533 1079 533 1080 530 1080 529 1080 530 1081 533 1081 534 1081 534 1082 532 1082 530 1082 575 1083 533 1083 567 1083 531 1084 532 1084 535 1084 532 1085 534 1085 536 1085 536 1086 535 1086 532 1086 533 1087 575 1087 537 1087 537 1088 534 1088 533 1088 534 1089 537 1089 538 1089 538 1090 536 1090 534 1090 580 1091 537 1091 575 1091 535 1092 536 1092 539 1092 540 1093 539 1093 536 1093 536 1094 538 1094 540 1094 537 1095 580 1095 541 1095 541 1096 538 1096 537 1096 538 1097 541 1097 542 1097 542 1098 540 1098 538 1098 589 1099 541 1099 580 1099 539 1100 540 1100 543 1100 540 1101 542 1101 544 1101 544 1102 543 1102 540 1102 545 1103 542 1103 541 1103 541 1104 589 1104 545 1104 545 1105 589 1105 595 1105 542 1106 545 1106 546 1106 546 1107 544 1107 542 1107 543 1108 544 1108 547 1108 544 1109 546 1109 550 1109 550 1110 547 1110 544 1110 551 1111 546 1111 545 1111 545 1112 595 1112 551 1112 546 1113 551 1113 553 1113 553 1114 550 1114 546 1114 603 1115 551 1115 595 1115 547 1116 550 1116 549 1116 550 1117 552 1117 548 1117 550 1118 548 1118 549 1118 550 1119 553 1119 552 1119 605 1120 552 1120 551 1120 551 1121 552 1121 553 1121 551 1122 603 1122 605 1122 555 1123 559 1123 556 1123 556 1124 559 1124 561 1124 556 1125 561 1125 557 1125 563 1126 558 1126 557 1126 563 1127 557 1127 561 1127 611 1128 560 1128 610 1128 564 1129 561 1129 559 1129 558 1130 563 1130 562 1130 565 1131 564 1131 560 1131 560 1132 564 1132 559 1132 560 1133 611 1133 565 1133 613 1134 565 1134 611 1134 566 1135 563 1135 561 1135 561 1136 564 1136 566 1136 563 1137 566 1137 568 1137 568 1138 567 1138 563 1138 563 1139 567 1139 562 1139 564 1140 565 1140 569 1140 569 1141 566 1141 564 1141 565 1142 613 1142 570 1142 570 1143 569 1143 565 1143 614 1144 570 1144 613 1144 571 1145 568 1145 566 1145 566 1146 569 1146 571 1146 572 1147 575 1147 568 1147 568 1148 575 1148 567 1148 568 1149 571 1149 572 1149 569 1150 570 1150 573 1150 573 1151 571 1151 569 1151 574 1152 573 1152 570 1152 570 1153 614 1153 574 1153 617 1154 574 1154 614 1154 571 1155 573 1155 576 1155 576 1156 572 1156 571 1156 577 1157 575 1157 572 1157 572 1158 576 1158 577 1158 573 1159 574 1159 578 1159 578 1160 576 1160 573 1160 579 1161 578 1161 574 1161 574 1162 617 1162 579 1162 579 1163 617 1163 620 1163 575 1164 577 1164 580 1164 581 1165 577 1165 576 1165 576 1166 578 1166 581 1166 577 1167 581 1167 582 1167 582 1168 580 1168 577 1168 578 1169 579 1169 583 1169 583 1170 581 1170 578 1170 579 1171 620 1171 584 1171 584 1172 583 1172 579 1172 580 1173 582 1173 589 1173 585 1174 582 1174 581 1174 581 1175 583 1175 585 1175 586 1176 589 1176 582 1176 582 1177 585 1177 586 1177 583 1178 584 1178 587 1178 587 1179 585 1179 583 1179 588 1180 587 1180 584 1180 584 1181 620 1181 588 1181 588 1182 620 1182 623 1182 585 1183 587 1183 590 1183 590 1184 586 1184 585 1184 586 1185 590 1185 591 1185 591 1186 589 1186 586 1186 592 1187 590 1187 587 1187 587 1188 588 1188 592 1188 588 1189 623 1189 593 1189 593 1190 592 1190 588 1190 589 1191 591 1191 595 1191 594 1192 591 1192 590 1192 590 1193 592 1193 594 1193 591 1194 594 1194 596 1194 596 1195 595 1195 591 1195 597 1196 594 1196 592 1196 592 1197 593 1197 597 1197 626 1198 593 1198 623 1198 593 1199 626 1199 598 1199 598 1200 597 1200 593 1200 594 1201 597 1201 599 1201 599 1202 596 1202 594 1202 595 1203 596 1203 603 1203 596 1204 599 1204 600 1204 600 1205 603 1205 596 1205 601 1206 599 1206 597 1206 597 1207 598 1207 601 1207 602 1208 601 1208 598 1208 598 1209 626 1209 602 1209 599 1210 601 1210 604 1210 604 1211 600 1211 599 1211 606 1212 603 1212 600 1212 600 1213 604 1213 606 1213 628 1214 602 1214 626 1214 607 1215 604 1215 601 1215 601 1216 602 1216 607 1216 608 1217 607 1217 602 1217 602 1218 628 1218 608 1218 603 1219 606 1219 605 1219 627 1220 608 1220 628 1220 604 1221 607 1221 609 1221 609 1222 605 1222 604 1222 604 1223 605 1223 606 1223 607 1224 608 1224 609 1224 609 1225 608 1225 627 1225 610 1226 612 1226 611 1226 615 1227 612 1227 20 1227 615 1228 613 1228 612 1228 612 1229 613 1229 611 1229 616 1230 615 1230 20 1230 613 1231 615 1231 614 1231 618 1232 617 1232 615 1232 615 1233 617 1233 614 1233 615 1234 616 1234 618 1234 619 1235 618 1235 616 1235 617 1236 618 1236 620 1236 618 1237 619 1237 621 1237 621 1238 620 1238 618 1238 622 1239 621 1239 619 1239 620 1240 621 1240 623 1240 624 1241 623 1241 621 1241 621 1242 622 1242 624 1242 625 1243 624 1243 622 1243 623 1244 624 1244 626 1244 629 1245 626 1245 624 1245 624 1246 625 1246 629 1246 631 1247 629 1247 625 1247 626 1248 629 1248 628 1248 630 1249 627 1249 629 1249 629 1250 627 1250 628 1250 629 1251 631 1251 630 1251 631 1252 632 1252 630 1252 420 1253 422 1253 421 1253 223 1254 421 1254 422 1254 421 1255 612 1255 610 1255 223 1256 612 1256 421 1256 223 1257 20 1257 612 1257 20 1258 223 1258 21 1258 21 1259 223 1259 23 1259 23 1260 223 1260 222 1260 23 1261 222 1261 24 1261

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_middle/th_middle_G1M5.dae b/URDFs/sr_description/meshes/components/th_middle/th_middle_G1M5.dae new file mode 100644 index 0000000..df463ac --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_middle/th_middle_G1M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:04.601049 + 2012-07-23T02:14:04.601062 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -10.82211 1.89451 0.02984 -10.52279 1.19648 4.40604 -10.43772 3.42460 0.02983 -10.01191 3.48500 4.44190 -9.24738 5.48540 3.30954 -9.53206 5.50770 0.02984 -8.76916 5.54120 6.52921 -9.89934 1.32759 8.78240 -9.34524 3.61260 8.85396 -8.04629 5.52890 11.15913 -9.26471 1.36724 13.15861 -8.71246 3.57270 13.26610 -7.62288 5.23110 15.49638 -8.79618 1.20098 17.53489 -8.36209 3.12530 17.67809 -7.64989 4.79500 18.13671 -8.53313 0.87560 21.91118 -8.31577 2.41180 22.09022 -7.82107 4.31860 20.58139 -8.02359 3.94460 22.84329 -8.30538 -0.79062 26.28739 -8.30538 0.70052 26.28740 -8.18404 3.75820 24.93399 -8.28854 1.69868 26.40406 -8.25863 3.80240 26.86291 -7.06228 8.40020 0.02984 -8.38620 6.91280 2.41682 -7.24683 8.13770 2.46228 -4.47194 9.96990 2.48145 -3.75606 10.29400 0.02976 -5.94010 9.15660 2.50980 -2.75840 10.49580 3.62321 -8.07380 6.89460 4.80358 -6.95048 8.05290 4.89452 -4.28569 9.79750 4.93299 -5.69028 9.01010 4.98983 -7.68404 6.86400 7.19021 -6.59311 7.90890 7.32682 -4.12086 9.51920 7.38459 -2.57576 10.09530 7.41507 -5.41925 8.76810 7.46987 -7.28799 6.80580 9.57691 -6.23702 7.73940 9.75913 -3.95787 9.22070 9.83620 -5.15147 8.50730 9.94991 -2.40556 9.64210 11.24200 -6.95685 6.70500 11.96360 -5.94428 7.57760 12.19143 -3.77749 8.98770 12.28781 -4.91141 8.30410 12.42994 -6.76190 6.54660 14.35030 -5.77712 7.45700 14.62374 -3.56027 8.90580 14.73935 -4.72338 8.23520 14.90998 -2.13855 9.43290 14.94243 -6.77357 6.31590 16.73700 -5.79564 7.41050 17.05605 -3.28867 9.05710 17.19096 -4.61110 8.37220 17.38994 -1.72766 9.64300 18.33506 -7.00006 6.03250 19.12369 -5.99731 7.44970 19.48835 -2.99557 9.42630 19.64257 -4.58613 8.69440 19.86998 -7.34378 5.77480 21.51040 -6.30172 7.56070 21.92059 -2.76823 9.89430 22.09418 -1.33429 10.08770 21.40864 -4.64892 9.10020 22.35008 -7.69641 5.62700 23.89709 -6.62395 7.72770 24.35296 -2.69618 10.33660 24.54579 -1.13835 10.51830 24.18891 -4.79982 9.48510 24.83005 -7.87334 5.89220 26.22347 -6.92828 7.84400 26.71059 -1.22462 10.79640 26.70466 -3.12402 10.54986 26.98725 -5.11937 9.69790 27.34445 -5.42738 9.83580 28.97489 8.61265 5.13360 29.45177 0.06932 10.86760 3.80621 -0.01024 11.00000 0.02977 -1.40119 10.75920 3.81399 1.54101 10.76320 3.81675 2.87009 10.51680 3.52160 3.74599 10.31910 0.02461 3.06080 10.10820 6.97886 0.26646 10.44410 7.58258 -1.22349 10.34610 7.59807 1.75633 10.31870 7.60365 3.19084 9.65190 10.35776 0.40632 9.98440 11.35896 -1.07563 9.89580 11.38229 1.88615 9.84550 11.39063 3.12557 9.35790 13.61293 0.44521 9.74450 15.13533 -0.89992 9.67180 15.16637 1.78511 9.61390 15.17754 2.77768 9.38120 16.66155 0.34961 9.93570 18.91171 -0.65823 9.88990 18.95053 1.34910 9.84460 18.96453 2.21227 9.70760 19.47371 0.17213 10.39810 22.68822 -0.46781 10.38080 22.73461 0.80393 10.35940 22.75151 1.66398 10.14140 22.07601 1.30046 10.53670 24.50004 0.63860 10.78850 26.55730 -0.26995 10.78750 26.46785 1.22529 10.79760 26.75026 7.06210 8.42260 0.02481 8.41345 7.01390 2.18807 9.50643 5.48610 0.02976 7.26406 8.22570 2.23212 4.46815 10.02870 2.27030 5.94975 9.22990 2.28890 9.32640 5.51470 3.95308 8.34041 6.89470 4.35005 7.22057 8.06730 4.43978 4.53342 9.83020 4.51699 5.95696 9.03570 4.55093 8.18244 6.77210 6.51210 7.10496 7.85940 6.64744 4.60456 9.53340 6.76375 5.92833 8.75480 6.81304 9.00644 5.38790 7.87618 7.97886 6.64160 8.67407 6.94847 7.63310 8.85509 4.64917 9.20840 9.01044 5.86525 8.45070 9.07521 7.76899 6.49850 10.83612 6.78223 7.41940 11.06275 4.63475 8.92510 11.25721 5.76895 8.18680 11.33725 8.61378 5.22010 11.68501 7.59222 6.33800 12.99817 6.63741 7.24920 13.27048 4.52889 8.75350 13.50389 5.64082 8.02660 13.59928 7.48771 6.15560 15.16022 8.32521 4.90480 15.26346 6.54521 7.15350 15.47806 4.29922 8.76350 15.75065 5.48222 8.03360 15.86139 7.49153 5.94840 17.32228 6.53255 7.15940 17.68572 3.92877 9.00560 17.99735 5.29914 8.25080 18.12349 8.23527 4.41720 18.53411 7.59137 5.74270 19.48432 6.58862 7.26040 19.89338 3.49200 9.41690 20.24404 5.12194 8.61970 20.38567 7.73767 5.58670 21.64630 8.25740 3.95780 21.48409 6.68360 7.43260 22.10104 3.09609 9.89340 22.49073 4.98816 9.05000 22.64771 8.28384 3.71300 24.13419 7.87952 5.52970 23.80835 6.78704 7.65190 24.30869 2.84803 10.33120 24.73749 4.93555 9.45130 24.90974 7.96324 5.62190 25.97040 8.25683 3.76260 26.51529 6.86779 7.89350 26.51643 2.85645 10.62480 26.98418 5.02005 9.72250 27.17793 5.01206 9.91015 28.28688 10.72605 1.18730 4.35415 10.80892 1.89560 0.02976 10.22011 3.47460 4.38505 10.33368 1.07588 8.67846 10.30603 -1.32513 8.68545 9.83651 3.37060 8.74033 9.82534 0.96963 13.00276 9.78150 -1.36852 13.01323 9.35575 3.19910 13.09561 9.29663 0.82529 17.32708 9.25393 -1.21342 17.34108 8.92802 2.79230 17.45089 8.80583 0.66934 21.65139 8.78052 -0.89296 21.66892 8.60947 2.24530 21.80618 8.35632 -0.05477 25.91333 8.32436 1.64096 26.06027 8.66363 -0.09010 29.62890 8.64029 3.91250 29.54616 10.17118 1.89878 -3.67597 8.94513 5.49330 -3.22971 6.63522 8.42400 -2.39370 3.52367 10.33660 -1.26092 8.28971 1.89878 -6.93474 7.29022 5.49331 -6.09604 5.40599 8.42400 -4.51997 2.86939 10.33660 -2.39137 5.40719 1.89878 -9.35354 4.75482 5.49330 -8.22358 3.52367 8.42400 -6.09781 1.86812 10.33660 -3.23000 1.87124 1.89878 -10.64048 1.64468 5.49331 -9.35552 1.21532 8.42400 -6.93679 0.64044 10.33660 -3.67576 -1.89170 1.89878 -10.64048 -1.66514 5.49330 -9.35552 -1.24074 8.42400 -6.93594 -0.66558 10.33660 -3.67491 -5.42766 1.89878 -9.35354 -4.77529 5.49330 -8.22358 -3.54853 8.42400 -6.09527 -1.89270 10.33660 -3.22759 -8.31018 1.89878 -6.93474 -7.31069 5.49330 -6.09605 -5.42971 8.42400 -4.51615 -2.89297 10.33660 -2.38769 -10.19165 1.89878 -3.67597 -8.96560 5.49330 -3.22971 -6.65746 8.42400 -2.38896 -3.54577 10.33660 -1.25646 -8.65377 3.85249 29.52191 -8.67159 0.00316 29.58427 -8.97734 5.75739 31.26040 -8.62534 5.13799 29.42574 -8.92799 5.75739 33.24101 -8.44687 5.75739 35.16321 -7.55740 5.75739 36.93373 -6.30115 5.75739 38.46575 -4.74085 5.75739 39.68664 -2.95096 5.75739 40.53609 -1.01801 5.75739 40.97280 0.96295 5.75739 40.97697 2.89704 5.75739 40.54733 4.69025 5.75739 39.70474 6.25565 5.75739 38.49036 7.51734 5.75740 36.96280 8.41431 5.75740 35.19623 8.90306 5.75740 33.27615 8.95977 5.75740 31.29569 8.65656 1.84708 29.60358 8.35498 6.41670 28.91394 -7.38982 7.94489 28.76241 -8.31528 6.49310 28.80709 -8.78182 6.90539 32.00492 -8.03264 7.87869 30.76628 -8.10922 7.87869 32.63197 -8.12485 6.90539 35.36077 -7.75793 7.87869 34.46621 -6.99652 7.87869 36.17090 -6.23433 6.90539 38.21012 -5.86572 7.87869 37.65667 -4.42626 7.87869 38.84582 -3.39862 6.90539 40.12094 -2.75254 7.87869 39.67384 -0.04722 6.90539 40.80133 -0.93471 7.87869 40.09867 0.93269 7.87869 40.09620 3.30949 6.90540 40.14902 2.75003 7.87869 39.66762 4.42149 7.87869 38.83535 6.16175 6.90540 38.26267 5.85861 7.87870 37.64331 8.07595 6.90540 35.42908 6.98559 7.87870 36.15457 7.74269 7.87870 34.44783 8.76128 6.90540 32.07895 8.09009 7.87870 32.61324 8.00927 7.87870 30.74782 7.13755 8.03140 28.36388 -5.75442 10.12129 30.77964 -5.88891 10.12129 32.02981 -5.68858 10.12129 33.55129 -5.10133 10.12129 34.96911 -4.16711 10.12129 36.18661 -2.94961 10.12129 37.12083 -1.53171 10.12129 37.70816 -0.01024 10.12129 37.90848 1.51124 10.12129 37.70816 2.92913 10.12129 37.12083 4.14663 10.12129 36.18661 5.08086 10.12129 34.96911 5.66811 10.12129 33.55129 5.86843 10.12130 32.02981 5.73083 10.12130 30.76508 5.32404 10.12150 29.55953 4.88535 10.74795 32.02972 4.52677 10.77160 30.16474 3.59488 11.00000 30.97120 3.74711 11.00000 32.02981 3.15067 11.00000 29.99836 3.48542 10.81730 28.47776 2.45035 11.00000 29.19014 1.55063 11.00000 28.61201 0.52448 11.00000 28.31064 -0.22463 10.94620 27.71228 -0.90310 10.94670 27.80258 -3.41361 10.67647 27.95695 -1.57110 11.00000 28.61201 -2.47082 11.00000 29.19014 -3.75642 10.71769 28.67628 -3.17115 10.99999 29.99836 -4.54689 10.77160 30.16368 -3.61535 10.99999 30.97120 -4.90581 10.74795 32.02974 -3.76759 10.99999 32.02981 -3.61542 10.99999 33.08834 3.59495 11.00000 33.08834 -3.17115 10.99999 34.06111 3.15059 11.00000 34.06118 -2.47075 10.99999 34.86940 2.45028 11.00000 34.86940 -1.57111 10.99999 35.44761 1.55063 10.99999 35.44761 -0.54502 10.99999 35.74890 0.52455 10.99999 35.74890 -4.42986 10.77159 34.15820 -3.06869 10.77160 35.86501 -1.10180 10.77160 36.81225 1.08132 10.77160 36.81225 3.04821 10.77160 35.86501 4.40939 10.77160 34.15820 4.40939 -10.86170 34.15819 3.04822 -10.86170 35.86501 1.08133 -10.86170 36.81224 -1.10180 -10.86170 36.81224 -3.06868 -10.86170 35.86501 -4.42986 -10.86170 34.15819 0.52455 -11.09011 35.74890 -0.54502 -11.09011 35.74890 1.55064 -11.09011 35.44760 -1.57110 -11.09011 35.44760 2.45028 -11.09010 34.86940 -2.47075 -11.09011 34.86940 3.15060 -11.09010 34.06118 -3.17114 -11.09011 34.06110 3.59495 -11.09010 33.08834 -3.61542 -11.09011 33.08834 -3.76759 -11.09011 32.02980 -4.90581 -10.83806 32.02974 -3.61535 -11.09011 30.97119 -4.54689 -10.86171 30.16368 -3.17114 -11.09011 29.99836 -3.75641 -10.80780 28.67628 -2.47082 -11.09010 29.19013 -1.57110 -11.09010 28.61200 -3.41360 -10.76658 27.95695 -0.90309 -11.03680 27.80258 -0.22463 -11.03630 27.71228 0.52448 -11.09010 28.31063 1.55063 -11.09010 28.61200 2.45035 -11.09010 29.19013 3.48542 -10.90741 28.47776 3.15067 -11.09010 29.99836 3.74712 -11.09010 32.02980 3.59488 -11.09010 30.97119 4.52677 -10.86170 30.16474 4.88535 -10.83805 32.02972 5.32404 -10.21160 29.55953 5.73084 -10.21140 30.76507 5.86844 -10.21140 32.02980 5.66811 -10.21140 33.55128 5.08086 -10.21140 34.96910 4.14663 -10.21140 36.18660 2.92914 -10.21141 37.12083 1.51124 -10.21141 37.70815 -0.01023 -10.21141 37.90848 -1.53171 -10.21141 37.70815 -2.94960 -10.21141 37.12083 -4.16710 -10.21141 36.18660 -5.10133 -10.21140 34.96910 -5.68858 -10.21140 33.55128 -5.88891 -10.21140 32.02980 -5.75441 -10.21140 30.77964 7.13755 -8.12150 28.36388 8.00927 -7.96880 30.74782 8.09009 -7.96880 32.61324 8.76128 -6.99550 32.07895 7.74269 -7.96880 34.44782 6.98560 -7.96880 36.15456 8.07595 -6.99550 35.42908 5.85861 -7.96880 37.64331 6.16175 -6.99550 38.26267 4.42149 -7.96880 38.83535 2.75003 -7.96880 39.66762 3.30949 -6.99550 40.14902 0.93269 -7.96880 40.09619 -0.93471 -7.96880 40.09867 -0.04722 -6.99550 40.80132 -2.75254 -7.96880 39.67384 -3.39862 -6.99551 40.12094 -4.42626 -7.96880 38.84582 -5.86571 -7.96881 37.65667 -6.23433 -6.99551 38.21012 -6.99652 -7.96881 36.17090 -7.75793 -7.96880 34.46621 -8.12485 -6.99550 35.36077 -8.10922 -7.96881 32.63197 -8.03264 -7.96881 30.76628 -8.78182 -6.99550 32.00491 -8.31528 -6.58320 28.80709 -7.38981 -8.03500 28.76241 8.35498 -6.50680 28.91394 8.65656 -1.93718 29.60358 8.95977 -5.84750 31.29569 8.90306 -5.84750 33.27615 8.41431 -5.84750 35.19623 7.51734 -5.84750 36.96279 6.25565 -5.84750 38.49036 4.69026 -5.84750 39.70473 2.89704 -5.84750 40.54733 0.96295 -5.84750 40.97696 -1.01800 -5.84750 40.97280 -2.95095 -5.84750 40.53608 -4.74085 -5.84750 39.68664 -6.30115 -5.84750 38.46575 -7.55740 -5.84750 36.93373 -8.44687 -5.84750 35.16320 -8.92799 -5.84750 33.24101 -8.62534 -5.22810 29.42574 -8.65377 -3.94260 29.52191 -8.97734 -5.84750 31.26040 -3.54577 -10.42670 -1.25647 -6.65746 -8.51410 -2.38897 -8.96560 -5.58340 -3.22972 -10.19165 -1.98888 -3.67597 -2.89297 -10.42670 -2.38769 -5.42971 -8.51410 -4.51616 -7.31068 -5.58340 -6.09605 -8.31018 -1.98888 -6.93474 -1.89269 -10.42670 -3.22760 -3.54852 -8.51410 -6.09527 -4.77528 -5.58340 -8.22358 -5.42766 -1.98888 -9.35354 -0.66558 -10.42670 -3.67491 -1.24074 -8.51410 -6.93595 -1.66514 -5.58340 -9.35552 -1.89170 -1.98888 -10.64048 0.64045 -10.42670 -3.67576 1.21532 -8.51410 -6.93680 1.64468 -5.58340 -9.35552 1.87123 -1.98888 -10.64047 1.86813 -10.42670 -3.23000 3.52368 -8.51410 -6.09782 4.75482 -5.58340 -8.22358 5.40719 -1.98888 -9.35354 2.86939 -10.42670 -2.39137 5.40599 -8.51410 -4.51997 7.29022 -5.58340 -6.09604 8.28971 -1.98888 -6.93474 3.52367 -10.42670 -1.26092 6.63523 -8.51410 -2.39370 8.94513 -5.58340 -3.22972 10.17118 -1.98888 -3.67597 8.64029 -4.00260 29.54616 8.32436 -1.73106 26.06027 8.60947 -2.33540 21.80618 8.92802 -2.88240 17.45089 9.35575 -3.28920 13.09561 9.83651 -3.46070 8.74033 10.22011 -3.56470 4.38505 10.80892 -1.98570 0.02976 10.72605 -1.27740 4.35415 5.01207 -10.00026 28.28688 5.02005 -9.81260 27.17792 2.85645 -10.71490 26.98417 6.86779 -7.98360 26.51642 8.25683 -3.85270 26.51529 7.96325 -5.71200 25.97040 4.93555 -9.54140 24.90974 2.84804 -10.42130 24.73748 6.78704 -7.74200 24.30869 7.87952 -5.61980 23.80835 8.28384 -3.80310 24.13419 4.98816 -9.14010 22.64770 3.09609 -9.98350 22.49072 6.68360 -7.52270 22.10104 8.25740 -4.04790 21.48409 7.73768 -5.67680 21.64630 5.12194 -8.70980 20.38566 3.49200 -9.50700 20.24403 6.58863 -7.35050 19.89338 7.59137 -5.83280 19.48432 8.23527 -4.50730 18.53411 5.29915 -8.34090 18.12349 3.92878 -9.09570 17.99734 6.53255 -7.24950 17.68572 7.49153 -6.03850 17.32227 5.48222 -8.12370 15.86138 4.29923 -8.85360 15.75065 6.54521 -7.24360 15.47806 8.32521 -4.99490 15.26346 7.48771 -6.24570 15.16022 5.64083 -8.11670 13.59928 4.52889 -8.84360 13.50389 6.63742 -7.33930 13.27048 7.59222 -6.42810 12.99817 8.61378 -5.31020 11.68500 5.76895 -8.27690 11.33725 4.63475 -9.01520 11.25721 6.78224 -7.50950 11.06275 7.76900 -6.58860 10.83612 5.86526 -8.54080 9.07521 4.64917 -9.29850 9.01044 6.94848 -7.72320 8.85509 7.97887 -6.73170 8.67407 9.00644 -5.47800 7.87617 5.92833 -8.84490 6.81303 4.60456 -9.62350 6.76375 7.10496 -7.94950 6.64743 8.18244 -6.86220 6.51209 5.95697 -9.12580 4.55093 4.53343 -9.92030 4.51699 7.22057 -8.15740 4.43977 8.34041 -6.98480 4.35004 9.32640 -5.60480 3.95307 5.94975 -9.32000 2.28890 4.46815 -10.11880 2.27030 7.26406 -8.31580 2.23212 9.50643 -5.57620 0.02976 8.41345 -7.10400 2.18806 7.06211 -8.51270 0.02481 1.22529 -10.88770 26.75026 -0.26995 -10.87760 26.46784 0.63860 -10.87860 26.55729 1.30046 -10.62680 24.50003 1.66399 -10.23150 22.07600 0.80393 -10.44950 22.75150 -0.46780 -10.47090 22.73461 0.17213 -10.48820 22.68822 2.21228 -9.79770 19.47371 1.34910 -9.93470 18.96452 -0.65823 -9.98000 18.95052 0.34962 -10.02580 18.91170 2.77768 -9.47130 16.66155 1.78511 -9.70400 15.17754 -0.89992 -9.76190 15.16637 0.44522 -9.83460 15.13533 3.12557 -9.44800 13.61292 1.88616 -9.93560 11.39063 -1.07563 -9.98590 11.38229 0.40633 -10.07450 11.35896 3.19084 -9.74200 10.35776 1.75633 -10.40880 7.60365 -1.22349 -10.43620 7.59807 0.26646 -10.53420 7.58258 3.06080 -10.19830 6.97885 3.74599 -10.40920 0.02460 2.87010 -10.60690 3.52160 1.54102 -10.85330 3.81674 -1.40118 -10.84930 3.81398 -0.01023 -11.09010 0.02976 0.06932 -10.95770 3.80620 8.61265 -5.22370 29.45177 -5.42738 -9.92590 28.97489 -5.11936 -9.78800 27.34444 -3.12402 -10.63996 26.98725 -1.22462 -10.88650 26.70466 -6.92828 -7.93410 26.71059 -7.87333 -5.98230 26.22347 -4.79982 -9.57520 24.83005 -1.13835 -10.60840 24.18891 -2.69618 -10.42670 24.54579 -6.62395 -7.81780 24.35296 -7.69641 -5.71710 23.89709 -4.64892 -9.19030 22.35008 -1.33429 -10.17780 21.40864 -2.76823 -9.98440 22.09418 -6.30171 -7.65080 21.92059 -7.34378 -5.86490 21.51039 -4.58613 -8.78450 19.86997 -2.99557 -9.51640 19.64257 -5.99730 -7.53980 19.48835 -7.00006 -6.12260 19.12369 -1.72766 -9.73310 18.33506 -4.61109 -8.46230 17.38994 -3.28867 -9.14720 17.19096 -5.79564 -7.50060 17.05604 -6.77357 -6.40600 16.73700 -2.13855 -9.52300 14.94243 -4.72338 -8.32530 14.90997 -3.56026 -8.99590 14.73935 -5.77711 -7.54710 14.62374 -6.76190 -6.63670 14.35030 -4.91141 -8.39420 12.42994 -3.77749 -9.07780 12.28781 -5.94427 -7.66770 12.19143 -6.95685 -6.79510 11.96360 -2.40556 -9.73220 11.24200 -5.15147 -8.59740 9.94990 -3.95787 -9.31080 9.83620 -6.23701 -7.82950 9.75912 -7.28799 -6.89590 9.57691 -5.41925 -8.85820 7.46987 -2.57576 -10.18540 7.41507 -4.12086 -9.60930 7.38459 -6.59311 -7.99900 7.32682 -7.68404 -6.95410 7.19021 -5.69028 -9.10020 4.98983 -4.28568 -9.88760 4.93298 -6.95048 -8.14300 4.89451 -8.07380 -6.98470 4.80358 -2.75840 -10.58590 3.62321 -5.94010 -9.24670 2.50980 -3.75606 -10.38410 0.02976 -4.47194 -10.06000 2.48144 -7.24683 -8.22780 2.46228 -8.38620 -7.00290 2.41682 -7.06228 -8.49030 0.02983 -8.25863 -3.89250 26.86290 -8.18404 -3.84830 24.93399 -8.28218 -2.23900 26.50221 -8.02359 -4.03470 22.84328 -7.82107 -4.40870 20.58139 -8.31577 -2.50190 22.09022 -8.53313 -0.96570 21.91118 -7.64989 -4.88510 18.13671 -8.36209 -3.21540 17.67809 -8.79618 -1.29108 17.53489 -7.62288 -5.32120 15.49638 -8.71246 -3.66280 13.26609 -9.26471 -1.45734 13.15861 -8.04629 -5.61900 11.15913 -9.34524 -3.70270 8.85396 -9.89934 -1.41769 8.78240 -8.76916 -5.63130 6.52920 -9.53206 -5.59780 0.02983 -9.24738 -5.57550 3.30953 -10.01191 -3.57510 4.44190 -10.43772 -3.51470 0.02983 -10.52279 -1.28658 4.40604 -10.82211 -1.98461 0.02984 + + + + + + + + + + -0.99767 -0.00000 0.06824 -0.99767 0.00000 0.06824 -0.96454 0.24231 0.10462 -0.97224 0.21562 0.09088 -0.91458 0.39600 0.08208 -0.91393 0.39734 0.08277 -0.90059 0.41583 0.12656 -0.99000 0.00000 0.14104 -0.96794 0.21402 0.13148 -0.99000 -0.00000 0.14104 -0.96340 0.22926 0.13894 -0.89990 0.41813 0.12388 -0.88968 0.43458 0.14006 -0.98965 -0.00000 0.14352 -0.96356 0.22934 0.13766 -0.98965 -0.00000 0.14352 -0.96207 0.23408 0.14010 -0.88674 0.44327 0.13118 -0.89489 0.43069 0.11693 -0.99432 -0.00000 0.10645 -0.99432 0.00000 0.10645 -0.96519 0.23621 0.11231 -0.89409 0.43290 0.11490 -0.97228 0.21198 0.09871 -0.92371 0.37938 0.05321 -0.99820 0.00000 0.06000 -0.97395 0.21417 0.07446 -0.99820 0.00000 0.06000 -0.99013 0.13632 0.03244 -0.97187 0.23444 -0.02237 -0.92437 0.37496 0.07034 -0.97592 0.21175 -0.05236 -0.99865 0.00000 0.05197 -0.99865 -0.00000 0.05197 -0.98943 0.13338 0.05683 -0.99703 -0.00430 -0.07690 -0.98471 0.17078 0.03445 -0.99984 0.01582 0.00892 -0.99897 0.02275 -0.03915 -0.76038 0.64925 -0.01717 -0.73242 0.68061 0.01788 -0.48479 0.87424 -0.02599 -0.49664 0.86705 -0.03972 -0.61532 0.78735 0.03828 -0.83204 0.54949 0.07596 -0.31376 0.94890 0.03382 -0.81854 0.56354 0.11144 -0.73035 0.67561 0.10075 -0.71775 0.68733 0.11142 -0.61399 0.78268 0.10210 -0.81869 0.56324 0.11184 -0.48080 0.87136 0.09781 -0.34769 0.93308 0.09203 -0.48346 0.86963 0.10007 -0.60650 0.78777 0.10763 -0.79844 0.58607 0.13791 -0.71708 0.68553 0.12589 -0.69385 0.70563 0.14372 -0.60576 0.78404 0.13542 -0.31946 0.93891 0.12806 -0.48077 0.86705 0.13075 -0.34904 0.93002 0.11504 -0.48920 0.86127 0.13750 -0.59586 0.79039 0.14224 -0.69421 0.70748 0.13245 -0.79949 0.58245 0.14687 -0.77873 0.61514 0.12322 -0.67103 0.72634 0.14886 -0.59586 0.79038 0.14231 -0.34847 0.92739 0.13608 -0.48921 0.86128 0.13739 -0.58832 0.79513 0.14714 -0.49759 0.85543 0.14368 -0.36416 0.92284 0.12548 -0.67093 0.73109 0.12396 -0.77086 0.62291 0.13326 -0.66384 0.73668 0.12890 -0.58747 0.79970 0.12390 -0.35537 0.92771 0.11432 -0.50110 0.85726 0.11834 -0.50168 0.85686 0.11877 -0.58975 0.79824 0.12249 -0.76748 0.63009 0.11819 -0.78791 0.60683 0.10463 -0.66255 0.74185 0.10335 -0.58579 0.80648 0.08025 -0.68882 0.72016 0.08305 -0.50811 0.85814 0.07369 -0.38872 0.91905 0.06515 -0.60457 0.79365 0.06788 -0.49176 0.86856 0.06141 -0.35638 0.93105 0.07835 -0.68723 0.72339 0.06656 -0.81428 0.57815 0.05191 -0.59594 0.80296 0.01081 -0.74673 0.66509 0.00703 -0.34509 0.93836 -0.01968 -0.49928 0.86644 0.00184 -0.62775 0.77828 -0.01457 -0.46303 0.88590 -0.02797 -0.34041 0.94012 -0.01699 -0.82853 0.55376 0.08299 -0.87635 0.48096 -0.02605 -0.74688 0.66491 0.00808 -0.61810 0.78350 -0.06387 -0.80460 0.58891 -0.07620 -0.46761 0.88060 -0.07671 -0.27717 0.95443 -0.11060 -0.42857 0.89652 -0.11216 -0.64455 0.75899 -0.09212 -0.89314 0.44908 0.02497 -0.92670 0.36382 -0.09418 -0.80866 0.58586 -0.05320 -0.63949 0.76019 -0.11473 -0.84324 0.52174 -0.12935 -0.42979 0.89342 -0.13069 -0.18752 0.97526 -0.11710 -0.31463 0.93733 -0.14976 -0.65561 0.74237 -0.13807 -0.40225 0.90184 -0.15774 -0.94397 0.32865 -0.03017 -0.85042 0.51771 -0.09359 -0.95633 0.26423 -0.12493 -0.65566 0.74237 -0.13783 -0.86757 0.47493 -0.14754 -0.14656 0.97906 -0.14130 -0.21004 0.96322 -0.16760 -0.40190 0.90313 -0.15112 -0.66437 0.73138 -0.15394 -0.38910 0.90641 -0.16435 -0.97315 0.22354 -0.05475 -0.97487 0.20055 -0.09700 -0.87795 0.45904 -0.13597 -0.87338 0.47197 -0.12022 -0.14073 0.98352 -0.11355 -0.67173 0.73056 -0.12275 -0.98477 0.16873 -0.04195 -0.38816 0.90972 -0.14748 -0.14417 0.98329 -0.11115 -0.40878 0.90355 -0.12842 -0.68228 0.71609 -0.14731 -0.67028 0.71807 -0.18736 -0.19020 0.98174 -0.00233 -0.07328 0.99664 0.03649 -0.18521 0.98268 -0.00555 0.07048 0.99695 0.03347 0.18002 0.98361 -0.01052 0.17834 0.98390 -0.01153 0.20355 0.97354 0.10383 -0.20453 0.97237 0.11255 0.06958 0.99176 0.10759 -0.07243 0.99073 0.11489 -0.19623 0.97373 0.11551 -0.06407 0.99172 0.11127 0.20613 0.97314 0.10251 0.08178 0.99038 0.11160 0.21505 0.96888 0.12257 0.08164 0.98972 0.11746 -0.06386 0.99036 0.12292 -0.19714 0.97251 0.12394 -0.19850 0.97229 0.12345 -0.05736 0.99109 0.12018 0.23260 0.96602 0.11273 0.09021 0.98861 0.12044 0.21713 0.97179 0.09212 -0.19398 0.97855 0.06932 0.09195 0.99382 0.06219 -0.05856 0.99624 0.06389 -0.05245 0.99673 0.06144 -0.20065 0.97736 0.06717 0.09484 0.99348 0.06329 0.26082 0.96314 0.06586 0.20552 0.97852 0.01598 -0.18248 0.98245 -0.03874 0.09839 0.99400 -0.04784 -0.05509 0.99713 -0.05188 -0.04742 0.99739 -0.05446 -0.20086 0.97865 -0.04358 0.26749 0.96316 -0.02788 0.09327 0.99439 -0.04984 0.19850 0.97734 -0.07353 -0.15618 0.98019 -0.12183 0.09626 0.98851 -0.11651 -0.04980 0.99107 -0.12369 -0.03599 0.99128 -0.12678 -0.14862 0.98160 -0.11986 0.14399 0.98058 -0.13312 0.21395 0.97158 -0.10128 0.07304 0.98959 -0.12401 -0.11159 0.98321 -0.14441 0.13935 0.98044 -0.13899 0.07162 0.99149 -0.10868 -0.03387 0.99478 -0.09629 0.00962 0.99402 -0.10880 -0.02783 0.99389 -0.10680 0.03443 0.99328 -0.11050 -0.01814 0.99371 -0.11047 0.02223 0.99318 -0.11441 0.76708 0.63841 -0.06345 0.72544 0.68827 -0.00498 0.30890 0.95080 0.02362 0.83514 0.54897 0.03432 0.72526 0.68565 0.06231 0.82020 0.56902 0.05908 0.72415 0.68671 0.06354 0.60756 0.79129 0.06875 0.34302 0.93650 0.07278 0.47298 0.87876 0.06390 0.61061 0.78919 0.06581 0.48471 0.87160 0.07328 0.72364 0.68407 0.09166 0.82253 0.56124 0.09192 0.71291 0.69370 0.10266 0.61072 0.78474 0.10588 0.48311 0.86987 0.09962 0.31995 0.94054 0.11412 0.61155 0.78419 0.10512 0.50061 0.85828 0.11291 0.35851 0.92917 0.09004 0.81707 0.57022 0.08507 0.71282 0.69283 0.10894 0.80209 0.58681 0.11095 0.69924 0.70444 0.12177 0.61189 0.78125 0.12345 0.36156 0.92374 0.12645 0.50050 0.85817 0.11420 0.51954 0.84480 0.12805 0.61362 0.78013 0.12198 0.38034 0.91836 0.10938 0.80324 0.58413 0.11663 0.69919 0.70569 0.11458 0.61360 0.78018 0.12173 0.69199 0.71170 0.12100 0.52138 0.84620 0.11005 0.38696 0.91454 0.11780 0.53560 0.83585 0.12032 0.61953 0.77621 0.11693 0.79482 0.59711 0.10825 0.69151 0.71401 0.10954 0.79437 0.59751 0.10931 0.70174 0.70532 0.10041 0.61785 0.77982 0.10065 0.53892 0.83760 0.08937 0.40328 0.91078 0.08857 0.53956 0.83714 0.08985 0.63090 0.77059 0.09031 0.39986 0.91211 0.09040 0.78542 0.61244 0.08963 0.70120 0.70680 0.09352 0.82094 0.55921 0.11547 0.73516 0.67524 0.05998 0.62616 0.77739 0.05985 0.39770 0.91679 0.03657 0.54333 0.83792 0.05181 0.52248 0.85197 0.03400 0.64629 0.76188 0.04296 0.39538 0.91773 0.03811 0.73553 0.67452 0.06334 0.82782 0.55858 0.05207 0.78437 0.62028 0.00284 0.63807 0.76997 0.00160 0.52543 0.85082 -0.00505 0.35396 0.93430 -0.04231 0.48512 0.87331 -0.04459 0.65879 0.75209 -0.01890 0.86262 0.49633 0.09772 0.89950 0.43693 0.00003 0.78701 0.61653 0.02231 0.82761 0.55937 -0.04661 0.65156 0.75687 -0.05118 0.48602 0.87152 -0.06506 0.34986 0.93602 -0.03830 0.28709 0.95058 -0.11821 0.44439 0.88903 -0.11017 0.66556 0.74315 -0.06905 0.83220 0.55424 -0.01632 0.95307 0.30015 0.03959 0.89121 0.45274 -0.02764 0.85760 0.50858 -0.07656 0.66141 0.74501 -0.08656 0.27767 0.95538 -0.10076 0.21481 0.96240 -0.16626 0.44440 0.88902 -0.11024 0.66964 0.73587 -0.10038 0.41286 0.89892 -0.14658 0.95305 0.30225 0.01841 0.97662 0.20684 -0.05862 0.86294 0.50345 -0.04334 0.87706 0.47225 -0.08801 0.66864 0.73621 -0.10446 0.41266 0.90154 -0.13011 0.20498 0.97043 -0.12751 0.15560 0.97267 -0.17235 0.39452 0.90629 -0.15161 0.67313 0.73069 -0.11397 0.88256 0.46708 -0.05410 0.98737 0.15822 0.00791 0.97680 0.20901 -0.04674 0.67546 0.72995 -0.10459 0.88991 0.44878 -0.08166 0.14727 0.98306 -0.10906 0.12275 0.98401 -0.12905 0.39401 0.91117 -0.12055 0.67851 0.72599 -0.11208 0.39136 0.91190 -0.12361 0.67690 0.72654 -0.11807 0.99982 -0.00000 0.01916 0.99982 0.00000 0.01916 0.97513 0.21496 0.05390 0.94005 0.34101 0.00346 0.91222 0.40785 0.03889 0.90555 0.41517 0.08727 0.97237 0.21381 0.09374 0.99591 0.00000 0.09036 0.99528 -0.01118 0.09639 0.97380 0.20853 0.09075 0.90693 0.41161 0.08971 0.90133 0.41858 0.11136 0.97101 0.20716 0.11924 0.99313 -0.01110 0.11647 0.99259 -0.01807 0.12012 0.97296 0.20013 0.11528 0.90348 0.41264 0.11598 0.90609 0.40879 0.10909 0.97184 0.19947 0.12548 0.99252 -0.01807 0.12075 0.99237 -0.01995 0.12169 0.97791 0.17618 0.11249 0.91184 0.39071 0.12604 0.93471 0.34689 0.07742 0.99350 -0.02004 0.11204 0.97742 0.17578 0.11727 0.99384 -0.01487 0.10981 0.98959 0.11478 0.08680 0.93026 0.36352 0.04963 0.97095 0.21812 0.09841 0.97914 0.20299 0.00898 0.99463 -0.01497 0.10236 0.98622 0.11081 0.12284 0.99241 0.09359 0.07981 0.99756 0.01285 0.06868 0.99951 0.02951 0.01072 0.98551 0.00000 -0.16960 0.92804 0.33665 -0.15942 0.98551 -0.00000 -0.16960 0.76218 0.63421 -0.12985 0.92820 0.33635 -0.15910 0.49458 0.86479 -0.08680 0.75944 0.63670 -0.13368 0.17832 0.98382 -0.01744 0.50219 0.86149 -0.07512 0.86602 -0.00000 -0.50000 0.86602 -0.00000 -0.50000 0.81549 0.33661 -0.47083 0.66796 0.63648 -0.38565 0.81548 0.33661 -0.47083 0.66756 0.63673 -0.38593 0.43801 0.86257 -0.25322 0.15254 0.98435 -0.08829 0.43779 0.86263 -0.25339 0.64280 -0.00000 -0.76603 0.64280 0.00000 -0.76603 0.60529 0.33661 -0.72133 0.60529 0.33661 -0.72133 0.49578 0.63649 -0.59083 0.49535 0.63672 -0.59094 0.32501 0.86257 -0.38773 0.32481 0.86262 -0.38779 0.11317 0.98435 -0.13512 0.34201 0.00000 -0.93970 0.34201 -0.00000 -0.93970 0.32205 0.33661 -0.88486 0.32205 0.33662 -0.88486 0.26378 0.63651 -0.72476 0.17282 0.86257 -0.47550 0.26340 0.63671 -0.72472 0.06015 0.98435 -0.16567 0.17265 0.86261 -0.47549 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.33662 -0.94164 0.00000 0.33661 -0.94164 0.00000 0.63652 -0.77126 -0.00027 0.63668 -0.77113 -0.00018 0.86257 -0.50593 -0.00033 0.86261 -0.50586 -0.00011 0.98435 -0.17625 -0.34201 0.00000 -0.93970 -0.34201 0.00000 -0.93970 -0.32205 0.33661 -0.88486 -0.26377 0.63654 -0.72474 -0.32205 0.33661 -0.88486 -0.26394 0.63667 -0.72456 -0.17316 0.86258 -0.47536 -0.06036 0.98435 -0.16559 -0.17325 0.86261 -0.47528 -0.64280 0.00000 -0.76603 -0.64280 0.00000 -0.76603 -0.60529 0.33661 -0.72133 -0.49575 0.63655 -0.59079 -0.60529 0.33661 -0.72133 -0.49581 0.63663 -0.59066 -0.32527 0.86259 -0.38749 -0.32530 0.86260 -0.38742 -0.11334 0.98435 -0.13498 -0.86602 0.00000 -0.50000 -0.81549 0.33661 -0.47083 -0.86602 0.00000 -0.50000 -0.66790 0.63655 -0.38562 -0.81548 0.33661 -0.47083 -0.66791 0.63662 -0.38550 -0.43816 0.86259 -0.25289 -0.43817 0.86260 -0.25285 -0.15265 0.98435 -0.08809 -0.98584 0.00000 -0.16772 -0.98584 0.00000 -0.16772 -0.75928 0.63665 -0.13476 -0.49635 0.86654 -0.05245 -0.18521 0.98270 0.00226 -0.75499 0.64466 -0.12002 -0.50205 0.86153 -0.07555 -0.98281 0.00156 -0.18463 -0.98159 0.00743 -0.19084 -0.98377 0.00000 -0.17946 -0.99969 -0.00000 0.02491 -0.99969 0.00000 0.02491 -0.97007 0.00000 0.24281 -0.97007 -0.00000 0.24281 -0.89358 -0.00000 0.44891 -0.89358 -0.00000 0.44891 -0.77327 -0.00000 0.63408 -0.77327 -0.00000 0.63408 -0.61624 -0.00000 0.78756 -0.61624 -0.00000 0.78756 -0.42875 -0.00000 0.90343 -0.42874 -0.00000 0.90343 -0.22038 -0.00000 0.97541 -0.22038 -0.00000 0.97541 -0.00210 -0.00000 1.00000 -0.00210 -0.00000 1.00000 0.21685 -0.00000 0.97620 0.21685 -0.00000 0.97620 0.42527 -0.00000 0.90507 0.42527 -0.00000 0.90507 0.61295 -0.00000 0.79012 0.61295 0.00000 0.79012 0.77101 0.00000 0.63682 0.77102 -0.00000 0.63682 0.89165 0.00000 0.45273 0.89165 -0.00000 0.45273 0.96910 -0.00000 0.24668 0.96910 -0.00000 0.24668 0.99959 -0.00000 0.02862 0.99959 -0.00000 0.02862 0.98458 0.00000 -0.17493 0.98382 0.00125 -0.17918 0.98323 0.00267 -0.18236 0.98223 0.00774 -0.18752 0.97049 0.10362 -0.21775 -0.96703 0.11833 -0.22548 -0.94612 0.27353 -0.17330 -0.81205 0.58264 -0.03333 -0.98803 0.15231 0.02462 -0.90531 0.35925 0.22660 -0.95379 0.23541 0.18672 -0.86306 0.47728 0.16529 -0.85829 0.48487 0.16803 -0.74132 0.58379 0.33111 -0.88044 0.17084 0.44231 -0.66848 0.54248 0.50877 -0.74356 0.45136 0.49335 -0.78755 0.32668 0.52253 -0.76020 0.18305 0.62336 -0.52676 0.56208 0.63764 -0.60294 0.20667 0.77055 -0.52913 0.32159 0.78524 -0.50053 0.44467 0.74280 -0.36223 0.57679 0.73219 -0.42339 0.15752 0.89215 -0.21293 0.25778 0.94245 -0.18978 0.30012 0.93483 -0.20391 0.44397 0.87253 -0.17194 0.50317 0.84691 -0.00208 0.14945 0.98877 0.00107 0.58598 0.81033 0.20530 0.32205 0.92419 0.18407 0.26251 0.94721 0.19566 0.52283 0.82968 0.16931 0.46073 0.87124 0.41985 0.15917 0.89353 0.36533 0.57289 0.73371 0.56280 0.39615 0.72548 0.53979 0.20603 0.81619 0.49427 0.44401 0.74736 0.52581 0.56716 0.63392 0.75755 0.18606 0.62570 0.72890 0.40527 0.55178 0.70606 0.52343 0.47697 0.78342 0.32584 0.52923 0.87889 0.16852 0.44626 0.74119 0.58526 0.32879 0.85161 0.49875 0.16127 0.86295 0.47345 0.17653 0.94327 0.22931 0.24011 0.93036 0.31338 0.19032 0.98805 0.15153 0.02829 0.81357 0.58039 -0.03525 0.88222 0.43491 -0.18041 0.94711 0.27576 -0.16416 0.81130 0.52202 -0.26323 -0.66164 0.71281 -0.23266 -0.68713 0.69922 -0.19733 -0.69930 0.71086 -0.07523 -0.71425 0.69928 -0.02932 -0.69525 0.71292 0.09154 -0.70041 0.70102 0.13414 -0.65047 0.71014 0.26942 -0.64881 0.70360 0.28980 -0.56351 0.70605 0.42888 -0.56099 0.70709 0.43047 -0.45311 0.70274 0.54849 -0.42808 0.71099 0.55788 -0.31647 0.70044 0.63971 -0.26816 0.71343 0.64739 -0.16274 0.69898 0.69638 -0.09129 0.71479 0.69336 0.00095 0.69850 0.71561 0.09129 0.71478 0.69337 0.16416 0.69891 0.69612 0.26809 0.71360 0.64722 0.31819 0.70029 0.63902 0.42796 0.71119 0.55773 0.45431 0.70258 0.54771 0.56358 0.70736 0.42664 0.56221 0.70556 0.43140 0.64937 0.70381 0.28805 0.65079 0.70980 0.26955 0.70058 0.70113 0.13267 0.69542 0.71275 0.09156 0.71409 0.69937 -0.03094 0.69915 0.71091 -0.07607 0.68564 0.69818 -0.20599 0.66836 0.70886 -0.22541 0.53660 0.84181 -0.05838 0.21287 0.97660 -0.03061 0.21611 0.97593 -0.02917 0.50647 0.85791 -0.08650 0.53558 0.82495 -0.18059 0.17249 0.98186 -0.07876 0.17261 0.98174 -0.07995 0.47616 0.83648 -0.27126 0.10940 0.98947 -0.09480 0.08418 0.98780 -0.13101 0.08169 0.98354 -0.16117 0.05378 0.98162 -0.18311 -0.00960 0.99694 -0.07762 -0.11065 0.97883 -0.17220 -0.16155 0.97786 -0.13303 -0.15943 0.97750 -0.13814 -0.17754 0.97553 -0.12971 -0.17247 0.98186 -0.07875 -0.54893 0.80453 -0.22674 -0.49438 0.86762 -0.05319 -0.53522 0.83965 -0.09230 -0.21436 0.97633 -0.02886 -0.21610 0.97588 -0.03108 -0.01071 0.99716 -0.07451 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.53617 0.84115 0.07059 -0.49467 0.86319 0.10102 -0.22947 0.97276 0.03299 -0.21605 0.97566 0.03747 -0.52918 0.81972 0.21918 -0.17211 0.98194 0.07861 -0.15313 0.97926 0.13268 -0.16699 0.97692 0.13318 -0.42461 0.84472 0.32582 -0.40904 0.85222 0.32620 -0.35041 0.81772 0.45667 -0.10438 0.98119 0.16241 -0.19285 0.86375 0.46556 -0.23759 0.83675 0.49335 -0.09429 0.97610 0.19580 -0.05367 0.98169 0.18276 -0.07403 0.82361 0.56230 -0.00000 0.86006 0.51020 -0.00000 0.97770 0.21000 0.00000 0.97770 0.21000 0.07403 0.82361 0.56230 0.05367 0.98169 0.18276 0.20977 0.83638 0.50643 0.22385 0.85664 0.46482 0.09429 0.97610 0.19580 0.10438 0.98119 0.16241 0.35041 0.81772 0.45666 0.16593 0.97560 0.14378 0.16059 0.97868 0.12807 0.41282 0.85395 0.31677 0.41722 0.84571 0.33273 0.17211 0.98194 0.07861 0.52918 0.81971 0.21918 0.48206 0.87384 0.06347 0.53424 0.83813 0.11015 0.22217 0.97423 0.03886 0.21610 0.97588 0.03106 0.81364 0.55878 -0.16051 0.85073 0.46784 -0.23954 0.64212 0.71513 -0.27617 0.65774 0.73793 -0.15112 0.47006 0.84484 -0.25553 0.45904 0.83586 -0.30104 0.11587 0.99032 -0.07642 0.39198 0.90754 -0.15075 -0.34968 0.91095 -0.21885 -0.41281 0.87590 -0.24976 -0.59330 0.78495 -0.17847 -0.11267 0.98835 -0.10230 -0.41718 0.87682 -0.23907 -0.15198 0.97322 -0.17246 -0.67118 0.71751 -0.18626 -0.97021 0.12813 -0.20560 -0.97355 0.12000 -0.19444 -0.81799 0.51345 -0.25934 -0.85665 0.46863 -0.21574 -0.98905 0.01086 -0.14718 0.99660 0.00256 -0.08240 0.99512 0.02698 -0.09487 0.99559 0.00524 -0.09365 0.99000 0.05900 -0.12817 0.99193 0.01270 -0.12613 0.98012 0.10552 -0.16803 0.97810 0.12744 -0.16458 0.02348 0.99271 -0.11822 0.02315 0.99272 -0.11824 0.01140 0.99185 -0.12690 -0.02193 0.99183 -0.12569 -0.01668 0.99127 -0.13081 -0.11535 0.98039 -0.15976 -0.87838 0.44072 -0.18497 -0.82070 0.51558 -0.24624 -0.92751 0.33656 -0.16267 -0.89470 0.38898 -0.21957 -0.95697 0.24041 -0.16253 0.49539 0.86620 -0.06547 0.60747 0.79420 0.01527 0.47459 0.87935 -0.03890 0.47459 -0.87935 -0.03890 0.60747 -0.79420 0.01527 0.49539 -0.86620 -0.06547 -0.95697 -0.24041 -0.16253 -0.89470 -0.38898 -0.21957 -0.92751 -0.33656 -0.16267 -0.82070 -0.51558 -0.24624 -0.87838 -0.44072 -0.18497 -0.11535 -0.98039 -0.15976 -0.01668 -0.99127 -0.13081 -0.02193 -0.99183 -0.12569 0.01140 -0.99185 -0.12690 0.02315 -0.99272 -0.11824 0.02349 -0.99271 -0.11822 0.97810 -0.12744 -0.16458 0.98012 -0.10552 -0.16803 0.99193 -0.01270 -0.12613 0.99000 -0.05900 -0.12817 0.99559 -0.00524 -0.09365 0.99511 -0.02729 -0.09488 0.99659 -0.00269 -0.08245 -0.98905 -0.01086 -0.14718 -0.85665 -0.46863 -0.21574 -0.81799 -0.51345 -0.25934 -0.97355 -0.12000 -0.19444 -0.97021 -0.12813 -0.20560 -0.67119 -0.71751 -0.18626 -0.15198 -0.97322 -0.17246 -0.41717 -0.87682 -0.23907 -0.11267 -0.98835 -0.10230 -0.59330 -0.78495 -0.17847 -0.41281 -0.87590 -0.24976 -0.34967 -0.91095 -0.21885 0.39198 -0.90754 -0.15075 0.11587 -0.99032 -0.07642 0.45904 -0.83586 -0.30104 0.47006 -0.84484 -0.25553 0.65774 -0.73793 -0.15112 0.64212 -0.71513 -0.27616 0.85073 -0.46784 -0.23954 0.81364 -0.55877 -0.16052 0.21610 -0.97588 0.03106 0.22217 -0.97423 0.03886 0.53424 -0.83813 0.11015 0.48206 -0.87384 0.06347 0.52918 -0.81972 0.21918 0.17211 -0.98194 0.07861 0.41722 -0.84571 0.33273 0.41282 -0.85395 0.31677 0.16059 -0.97868 0.12807 0.16593 -0.97560 0.14378 0.35041 -0.81772 0.45666 0.10438 -0.98119 0.16240 0.09430 -0.97610 0.19580 0.22385 -0.85664 0.46482 0.20977 -0.83638 0.50643 0.05367 -0.98169 0.18276 0.07403 -0.82361 0.56230 0.00000 -0.97770 0.21000 0.00000 -0.97770 0.21000 0.00000 -0.86006 0.51020 -0.07403 -0.82361 0.56230 -0.05367 -0.98169 0.18276 -0.09430 -0.97610 0.19580 -0.23759 -0.83675 0.49335 -0.19284 -0.86375 0.46556 -0.10438 -0.98119 0.16241 -0.35041 -0.81772 0.45666 -0.40904 -0.85222 0.32620 -0.42461 -0.84472 0.32582 -0.16700 -0.97692 0.13318 -0.15313 -0.97926 0.13269 -0.17211 -0.98194 0.07861 -0.52917 -0.81972 0.21918 -0.21605 -0.97566 0.03747 -0.22947 -0.97276 0.03299 -0.49466 -0.86319 0.10102 -0.53617 -0.84115 0.07059 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.01071 -0.99716 -0.07451 -0.21610 -0.97588 -0.03108 -0.21436 -0.97633 -0.02886 -0.53522 -0.83965 -0.09230 -0.49438 -0.86762 -0.05319 -0.54893 -0.80453 -0.22674 -0.17247 -0.98186 -0.07875 -0.17754 -0.97553 -0.12971 -0.15943 -0.97750 -0.13815 -0.16155 -0.97786 -0.13303 -0.11065 -0.97883 -0.17220 -0.00960 -0.99694 -0.07762 0.05378 -0.98162 -0.18311 0.08169 -0.98354 -0.16117 0.08418 -0.98780 -0.13101 0.10940 -0.98947 -0.09480 0.47616 -0.83648 -0.27126 0.17261 -0.98174 -0.07995 0.17249 -0.98186 -0.07876 0.53559 -0.82495 -0.18059 0.50647 -0.85791 -0.08650 0.21611 -0.97593 -0.02917 0.21287 -0.97660 -0.03061 0.53660 -0.84181 -0.05838 0.66836 -0.70886 -0.22541 0.68564 -0.69818 -0.20599 0.69915 -0.71091 -0.07607 0.71409 -0.69937 -0.03094 0.69542 -0.71275 0.09156 0.70058 -0.70113 0.13266 0.65079 -0.70980 0.26955 0.64937 -0.70381 0.28805 0.56221 -0.70555 0.43140 0.56358 -0.70736 0.42664 0.45431 -0.70258 0.54771 0.42796 -0.71119 0.55773 0.31819 -0.70029 0.63902 0.26809 -0.71360 0.64722 0.16416 -0.69891 0.69612 0.09129 -0.71478 0.69337 0.00095 -0.69850 0.71561 -0.09129 -0.71479 0.69336 -0.16274 -0.69898 0.69638 -0.26816 -0.71343 0.64739 -0.31648 -0.70044 0.63971 -0.42808 -0.71099 0.55788 -0.45311 -0.70274 0.54849 -0.56099 -0.70709 0.43047 -0.56351 -0.70605 0.42888 -0.64881 -0.70360 0.28980 -0.65047 -0.71014 0.26942 -0.70041 -0.70102 0.13414 -0.69525 -0.71292 0.09154 -0.71425 -0.69928 -0.02932 -0.69930 -0.71086 -0.07523 -0.68713 -0.69922 -0.19733 -0.66164 -0.71281 -0.23266 0.81130 -0.52202 -0.26323 0.94711 -0.27576 -0.16416 0.88222 -0.43490 -0.18041 0.81357 -0.58039 -0.03525 0.98805 -0.15153 0.02829 0.93036 -0.31338 0.19032 0.94327 -0.22931 0.24011 0.86295 -0.47345 0.17653 0.85161 -0.49875 0.16126 0.74119 -0.58526 0.32879 0.87889 -0.16852 0.44626 0.78342 -0.32584 0.52923 0.70606 -0.52343 0.47697 0.72890 -0.40527 0.55178 0.75755 -0.18606 0.62570 0.52581 -0.56716 0.63392 0.49427 -0.44401 0.74736 0.53979 -0.20603 0.81619 0.56280 -0.39615 0.72548 0.36533 -0.57289 0.73371 0.41985 -0.15917 0.89353 0.16931 -0.46073 0.87124 0.19566 -0.52283 0.82968 0.18407 -0.26251 0.94721 0.20530 -0.32205 0.92419 0.00107 -0.58598 0.81033 -0.00208 -0.14945 0.98877 -0.17194 -0.50317 0.84691 -0.20391 -0.44397 0.87253 -0.18978 -0.30012 0.93483 -0.21293 -0.25778 0.94245 -0.42339 -0.15752 0.89215 -0.36223 -0.57679 0.73219 -0.50053 -0.44467 0.74280 -0.52913 -0.32159 0.78524 -0.60294 -0.20667 0.77055 -0.52676 -0.56208 0.63764 -0.76020 -0.18305 0.62336 -0.78755 -0.32668 0.52254 -0.74356 -0.45136 0.49335 -0.66848 -0.54248 0.50877 -0.88044 -0.17084 0.44231 -0.74131 -0.58380 0.33111 -0.85829 -0.48487 0.16803 -0.86306 -0.47729 0.16529 -0.95379 -0.23540 0.18672 -0.90531 -0.35925 0.22660 -0.98803 -0.15231 0.02462 -0.81205 -0.58264 -0.03333 -0.94612 -0.27353 -0.17330 -0.96703 -0.11833 -0.22549 0.97049 -0.10362 -0.21775 0.98223 -0.00774 -0.18752 0.98323 -0.00267 -0.18236 0.98379 -0.00131 -0.17931 -0.50205 -0.86153 -0.07555 -0.75499 -0.64466 -0.12002 -0.18521 -0.98270 0.00226 -0.49635 -0.86654 -0.05245 -0.75928 -0.63665 -0.13476 -0.15265 -0.98435 -0.08809 -0.43817 -0.86260 -0.25285 -0.43816 -0.86259 -0.25289 -0.66791 -0.63662 -0.38550 -0.81548 -0.33661 -0.47083 -0.66790 -0.63655 -0.38562 -0.81549 -0.33661 -0.47083 -0.11334 -0.98435 -0.13498 -0.32530 -0.86260 -0.38742 -0.32527 -0.86259 -0.38749 -0.49581 -0.63663 -0.59066 -0.60529 -0.33661 -0.72133 -0.49575 -0.63655 -0.59079 -0.60529 -0.33661 -0.72133 -0.17325 -0.86261 -0.47528 -0.06036 -0.98435 -0.16559 -0.17316 -0.86258 -0.47536 -0.26394 -0.63667 -0.72456 -0.32205 -0.33661 -0.88486 -0.26377 -0.63654 -0.72474 -0.32205 -0.33661 -0.88486 -0.00011 -0.98435 -0.17625 -0.00033 -0.86261 -0.50587 -0.00018 -0.86257 -0.50593 -0.00027 -0.63668 -0.77113 0.00000 -0.63652 -0.77126 0.00000 -0.33661 -0.94164 0.00000 -0.33661 -0.94164 0.17265 -0.86261 -0.47549 0.06015 -0.98435 -0.16567 0.26340 -0.63671 -0.72472 0.17282 -0.86257 -0.47550 0.26378 -0.63651 -0.72476 0.32204 -0.33661 -0.88486 0.32205 -0.33661 -0.88486 0.11317 -0.98435 -0.13512 0.32481 -0.86262 -0.38779 0.32501 -0.86257 -0.38773 0.49535 -0.63672 -0.59094 0.49578 -0.63649 -0.59083 0.60529 -0.33661 -0.72133 0.60529 -0.33661 -0.72133 0.43779 -0.86263 -0.25339 0.15254 -0.98435 -0.08829 0.43801 -0.86257 -0.25322 0.66756 -0.63673 -0.38593 0.81548 -0.33661 -0.47083 0.66796 -0.63648 -0.38565 0.81549 -0.33661 -0.47083 0.50219 -0.86149 -0.07512 0.17832 -0.98382 -0.01744 0.75944 -0.63670 -0.13368 0.49458 -0.86479 -0.08680 0.92820 -0.33635 -0.15910 0.76218 -0.63421 -0.12985 0.92804 -0.33665 -0.15942 0.99951 -0.02951 0.01072 0.99755 -0.01300 0.06870 0.99241 -0.09359 0.07981 0.98719 -0.10569 0.11953 0.97914 -0.20299 0.00898 0.97095 -0.21812 0.09841 0.93026 -0.36352 0.04963 0.99028 -0.10923 0.08615 0.97580 -0.18263 0.12026 0.93471 -0.34689 0.07742 0.91184 -0.39071 0.12605 0.97655 -0.18326 0.11302 0.96968 -0.20955 0.12572 0.90609 -0.40879 0.10909 0.90348 -0.41264 0.11598 0.97081 -0.21024 0.11544 0.97075 -0.21046 0.11555 0.90133 -0.41858 0.11136 0.90693 -0.41161 0.08971 0.97313 -0.21162 0.09076 0.97252 -0.21387 0.09195 0.90555 -0.41517 0.08727 0.91222 -0.40785 0.03889 0.94005 -0.34101 0.00346 0.97513 -0.21496 0.05390 0.67690 -0.72654 -0.11807 0.39136 -0.91190 -0.12361 0.67851 -0.72599 -0.11208 0.39401 -0.91117 -0.12055 0.12275 -0.98401 -0.12905 0.14727 -0.98306 -0.10906 0.88991 -0.44878 -0.08166 0.67546 -0.72994 -0.10459 0.97680 -0.20901 -0.04674 0.98737 -0.15822 0.00791 0.88256 -0.46708 -0.05410 0.67313 -0.73069 -0.11397 0.39452 -0.90629 -0.15161 0.15560 -0.97267 -0.17235 0.20498 -0.97043 -0.12751 0.41266 -0.90154 -0.13011 0.66864 -0.73621 -0.10446 0.87706 -0.47225 -0.08801 0.86294 -0.50345 -0.04334 0.97662 -0.20684 -0.05862 0.95305 -0.30225 0.01841 0.41286 -0.89892 -0.14658 0.66964 -0.73587 -0.10038 0.44440 -0.88902 -0.11024 0.21481 -0.96240 -0.16626 0.27767 -0.95538 -0.10076 0.66141 -0.74501 -0.08657 0.85760 -0.50858 -0.07656 0.89121 -0.45274 -0.02764 0.95307 -0.30015 0.03959 0.83220 -0.55424 -0.01632 0.66556 -0.74314 -0.06905 0.44439 -0.88903 -0.11017 0.28709 -0.95058 -0.11821 0.34986 -0.93602 -0.03830 0.48602 -0.87152 -0.06506 0.65156 -0.75687 -0.05118 0.82761 -0.55937 -0.04661 0.78701 -0.61653 0.02231 0.89950 -0.43693 0.00003 0.86262 -0.49633 0.09772 0.65879 -0.75209 -0.01890 0.48512 -0.87331 -0.04459 0.35396 -0.93430 -0.04231 0.52543 -0.85082 -0.00505 0.63807 -0.76997 0.00160 0.78437 -0.62028 0.00284 0.82782 -0.55858 0.05207 0.73553 -0.67452 0.06334 0.39538 -0.91773 0.03810 0.64629 -0.76188 0.04296 0.52248 -0.85197 0.03400 0.54333 -0.83792 0.05181 0.39770 -0.91679 0.03657 0.62616 -0.77739 0.05985 0.73516 -0.67524 0.05998 0.82094 -0.55921 0.11547 0.70120 -0.70680 0.09352 0.78542 -0.61244 0.08963 0.39986 -0.91211 0.09040 0.63090 -0.77059 0.09031 0.53956 -0.83714 0.08985 0.40328 -0.91078 0.08857 0.53892 -0.83760 0.08937 0.61786 -0.77982 0.10065 0.70174 -0.70532 0.10041 0.79437 -0.59751 0.10931 0.69151 -0.71401 0.10954 0.79482 -0.59711 0.10825 0.61953 -0.77621 0.11693 0.53560 -0.83585 0.12032 0.38696 -0.91454 0.11780 0.52138 -0.84620 0.11005 0.69199 -0.71170 0.12100 0.61360 -0.78018 0.12173 0.69919 -0.70570 0.11458 0.80324 -0.58413 0.11663 0.38034 -0.91836 0.10938 0.61362 -0.78013 0.12198 0.51954 -0.84480 0.12805 0.50050 -0.85817 0.11420 0.36156 -0.92374 0.12645 0.61190 -0.78124 0.12345 0.69924 -0.70444 0.12177 0.80209 -0.58681 0.11095 0.71282 -0.69283 0.10894 0.81707 -0.57022 0.08507 0.35851 -0.92917 0.09004 0.50061 -0.85828 0.11291 0.61155 -0.78419 0.10512 0.31995 -0.94054 0.11412 0.48311 -0.86987 0.09962 0.61072 -0.78474 0.10588 0.71291 -0.69370 0.10266 0.82253 -0.56124 0.09192 0.72364 -0.68407 0.09166 0.48471 -0.87160 0.07328 0.61061 -0.78919 0.06581 0.47298 -0.87876 0.06390 0.34302 -0.93650 0.07278 0.60756 -0.79129 0.06874 0.72415 -0.68671 0.06354 0.82020 -0.56902 0.05908 0.72526 -0.68565 0.06230 0.83514 -0.54897 0.03432 0.30890 -0.95080 0.02362 0.72544 -0.68826 -0.00498 0.76708 -0.63841 -0.06345 0.02223 -0.99318 -0.11441 -0.01814 -0.99371 -0.11047 0.03443 -0.99328 -0.11050 -0.02783 -0.99389 -0.10680 0.00962 -0.99402 -0.10880 -0.03387 -0.99478 -0.09629 0.07162 -0.99149 -0.10868 0.13935 -0.98044 -0.13899 -0.11159 -0.98321 -0.14441 0.07304 -0.98959 -0.12401 0.21395 -0.97158 -0.10128 0.14399 -0.98058 -0.13312 -0.14862 -0.98160 -0.11986 -0.03599 -0.99128 -0.12678 -0.04980 -0.99107 -0.12369 0.09626 -0.98851 -0.11651 -0.15618 -0.98019 -0.12183 0.19850 -0.97734 -0.07353 0.09327 -0.99439 -0.04984 0.26749 -0.96316 -0.02788 -0.20087 -0.97865 -0.04358 -0.04742 -0.99739 -0.05446 -0.05509 -0.99713 -0.05188 0.09839 -0.99400 -0.04784 -0.18248 -0.98245 -0.03874 0.20552 -0.97852 0.01597 0.26082 -0.96314 0.06586 0.09484 -0.99348 0.06329 -0.20065 -0.97736 0.06717 -0.05245 -0.99673 0.06144 -0.05856 -0.99624 0.06389 0.09195 -0.99382 0.06219 -0.19398 -0.97855 0.06932 0.21713 -0.97179 0.09212 0.09022 -0.98861 0.12044 0.23259 -0.96602 0.11273 -0.05736 -0.99109 0.12018 -0.19850 -0.97229 0.12345 -0.19714 -0.97251 0.12394 -0.06386 -0.99036 0.12292 0.08164 -0.98972 0.11745 0.21505 -0.96888 0.12256 0.08178 -0.99038 0.11160 0.20613 -0.97314 0.10250 -0.06407 -0.99172 0.11127 -0.19623 -0.97373 0.11551 -0.07243 -0.99073 0.11489 0.06958 -0.99176 0.10759 -0.20453 -0.97237 0.11255 0.20355 -0.97354 0.10383 0.17834 -0.98390 -0.01153 0.18002 -0.98361 -0.01052 0.07048 -0.99695 0.03347 -0.18521 -0.98268 -0.00555 -0.07328 -0.99664 0.03649 -0.19020 -0.98174 -0.00233 -0.67028 -0.71807 -0.18736 -0.68228 -0.71609 -0.14731 -0.40878 -0.90355 -0.12842 -0.14417 -0.98329 -0.11115 -0.38816 -0.90972 -0.14748 -0.98477 -0.16873 -0.04195 -0.67173 -0.73056 -0.12275 -0.14073 -0.98352 -0.11355 -0.87338 -0.47197 -0.12022 -0.87795 -0.45904 -0.13597 -0.97487 -0.20055 -0.09700 -0.97315 -0.22355 -0.05475 -0.38910 -0.90641 -0.16435 -0.66437 -0.73138 -0.15394 -0.40190 -0.90313 -0.15112 -0.21004 -0.96322 -0.16760 -0.14657 -0.97906 -0.14130 -0.86757 -0.47493 -0.14754 -0.65566 -0.74237 -0.13783 -0.95633 -0.26423 -0.12493 -0.85042 -0.51771 -0.09359 -0.94397 -0.32865 -0.03017 -0.40225 -0.90184 -0.15774 -0.65561 -0.74237 -0.13807 -0.31463 -0.93733 -0.14976 -0.18752 -0.97525 -0.11711 -0.42979 -0.89342 -0.13069 -0.84324 -0.52174 -0.12935 -0.63949 -0.76019 -0.11473 -0.80866 -0.58586 -0.05320 -0.92670 -0.36382 -0.09418 -0.89314 -0.44909 0.02497 -0.64455 -0.75899 -0.09212 -0.42857 -0.89652 -0.11216 -0.27717 -0.95443 -0.11060 -0.46761 -0.88060 -0.07671 -0.80460 -0.58891 -0.07620 -0.61810 -0.78350 -0.06387 -0.74688 -0.66491 0.00808 -0.87635 -0.48097 -0.02605 -0.82853 -0.55376 0.08299 -0.34041 -0.94013 -0.01699 -0.46303 -0.88590 -0.02797 -0.62775 -0.77828 -0.01457 -0.49928 -0.86644 0.00184 -0.34509 -0.93836 -0.01968 -0.74673 -0.66509 0.00703 -0.59594 -0.80296 0.01081 -0.81428 -0.57815 0.05191 -0.68723 -0.72339 0.06656 -0.35638 -0.93105 0.07835 -0.49176 -0.86856 0.06141 -0.60457 -0.79365 0.06788 -0.38872 -0.91905 0.06515 -0.50811 -0.85814 0.07369 -0.68882 -0.72016 0.08305 -0.58579 -0.80648 0.08025 -0.66255 -0.74185 0.10335 -0.78791 -0.60683 0.10463 -0.76748 -0.63009 0.11818 -0.58975 -0.79824 0.12249 -0.50168 -0.85686 0.11877 -0.50110 -0.85726 0.11834 -0.35537 -0.92771 0.11432 -0.58747 -0.79970 0.12390 -0.66384 -0.73668 0.12890 -0.77086 -0.62291 0.13326 -0.67093 -0.73109 0.12396 -0.36416 -0.92284 0.12548 -0.49759 -0.85543 0.14368 -0.58832 -0.79513 0.14714 -0.48921 -0.86128 0.13739 -0.34847 -0.92739 0.13608 -0.59586 -0.79038 0.14231 -0.67103 -0.72634 0.14886 -0.77873 -0.61514 0.12322 -0.79949 -0.58245 0.14687 -0.69421 -0.70748 0.13245 -0.59586 -0.79039 0.14224 -0.48920 -0.86127 0.13750 -0.34903 -0.93002 0.11504 -0.48077 -0.86705 0.13075 -0.31946 -0.93891 0.12806 -0.60576 -0.78404 0.13542 -0.69385 -0.70563 0.14372 -0.71707 -0.68553 0.12589 -0.79844 -0.58607 0.13791 -0.60650 -0.78777 0.10763 -0.48346 -0.86963 0.10007 -0.34769 -0.93308 0.09203 -0.48080 -0.87136 0.09780 -0.81869 -0.56324 0.11184 -0.61399 -0.78268 0.10210 -0.71775 -0.68733 0.11142 -0.73035 -0.67561 0.10075 -0.81854 -0.56354 0.11144 -0.31376 -0.94890 0.03382 -0.83204 -0.54949 0.07596 -0.61532 -0.78735 0.03828 -0.49664 -0.86705 -0.03972 -0.48479 -0.87424 -0.02599 -0.73242 -0.68062 0.01788 -0.76038 -0.64925 -0.01717 -0.99897 -0.02277 -0.03915 -0.99986 -0.01475 0.00849 -0.98375 -0.17861 0.01813 -0.99685 0.01506 -0.07784 -0.98943 -0.13338 0.05683 -0.97592 -0.21175 -0.05236 -0.92437 -0.37496 0.07034 -0.97187 -0.23444 -0.02237 -0.99013 -0.13632 0.03244 -0.97395 -0.21417 0.07446 -0.92371 -0.37938 0.05321 -0.97228 -0.21198 0.09871 -0.89409 -0.43290 0.11490 -0.96519 -0.23621 0.11231 -0.89489 -0.43069 0.11693 -0.88674 -0.44327 0.13118 -0.96207 -0.23408 0.14010 -0.96356 -0.22934 0.13766 -0.88968 -0.43458 0.14006 -0.89990 -0.41813 0.12388 -0.96340 -0.22926 0.13894 -0.96794 -0.21402 0.13148 -0.90059 -0.41583 0.12656 -0.91393 -0.39734 0.08277 -0.91458 -0.39600 0.08208 -0.97224 -0.21562 0.09088 -0.96454 -0.24231 0.10462 -0.98159 -0.00743 -0.19084 -0.98281 -0.00152 -0.18459 -0.98795 -0.04629 -0.14768 -0.99234 -0.00253 -0.12354 -0.99420 -0.03119 -0.10292 -0.99389 0.00000 -0.11040 -0.99412 0.02896 -0.10430 -0.99299 0.00268 -0.11817 -0.98795 0.04626 -0.14768 + + + + + + + + + + + + + + +

631 0 0 0 632 0 1 1 0 1 631 1 2 2 0 2 1 2 3 3 2 3 1 3 3 4 4 4 5 4 2 5 3 5 5 5 6 6 4 6 3 6 631 7 625 7 1 7 1 8 7 8 3 8 7 9 1 9 625 9 8 10 3 10 7 10 3 11 8 11 6 11 9 12 6 12 8 12 625 13 622 13 7 13 7 14 10 14 8 14 10 15 7 15 622 15 11 16 8 16 10 16 8 17 11 17 9 17 12 18 9 18 11 18 622 19 619 19 10 19 13 20 10 20 619 20 10 21 13 21 11 21 11 22 14 22 12 22 14 23 11 23 13 23 15 24 12 24 14 24 619 25 616 25 13 25 13 26 16 26 14 26 16 27 13 27 616 27 17 28 14 28 16 28 17 29 18 29 15 29 14 30 17 30 15 30 19 31 18 31 17 31 616 32 20 32 16 32 21 33 16 33 20 33 16 34 21 34 17 34 23 35 22 35 19 35 17 36 23 36 19 36 17 37 21 37 23 37 24 38 22 38 23 38 25 39 5 39 26 39 27 40 25 40 26 40 30 41 28 41 29 41 25 42 30 42 29 42 30 43 25 43 27 43 5 44 4 44 26 44 31 45 29 45 28 45 32 46 26 46 4 46 26 47 32 47 27 47 33 48 27 48 32 48 27 49 33 49 30 49 4 50 6 50 32 50 34 51 28 51 30 51 28 52 34 52 31 52 30 53 35 53 34 53 35 54 30 54 33 54 36 55 32 55 6 55 32 56 36 56 33 56 37 57 33 57 36 57 33 58 37 58 35 58 34 59 38 59 31 59 38 60 34 60 35 60 39 61 31 61 38 61 35 62 40 62 38 62 40 63 35 63 37 63 36 64 41 64 37 64 41 65 36 65 6 65 6 66 9 66 41 66 42 67 37 67 41 67 37 68 42 68 40 68 38 69 43 69 39 69 43 70 38 70 40 70 44 71 40 71 42 71 40 72 44 72 43 72 45 73 39 73 43 73 41 74 46 74 42 74 46 75 41 75 9 75 47 76 42 76 46 76 42 77 47 77 44 77 43 78 48 78 45 78 48 79 43 79 44 79 44 80 49 80 48 80 49 81 44 81 47 81 46 82 9 82 12 82 50 83 46 83 12 83 46 84 50 84 47 84 47 85 51 85 49 85 51 86 47 86 50 86 52 87 48 87 49 87 48 88 52 88 45 88 53 89 49 89 51 89 49 90 53 90 52 90 54 91 45 91 52 91 50 92 55 92 51 92 55 93 50 93 12 93 51 94 56 94 53 94 56 95 51 95 55 95 52 96 57 96 54 96 57 97 52 97 53 97 58 98 53 98 56 98 53 99 58 99 57 99 59 100 54 100 57 100 55 101 12 101 15 101 60 102 55 102 15 102 55 103 60 103 56 103 56 104 61 104 58 104 61 105 56 105 60 105 62 106 57 106 58 106 57 107 62 107 59 107 58 108 63 108 62 108 63 109 58 109 61 109 15 110 18 110 60 110 64 111 60 111 18 111 60 112 64 112 61 112 61 113 65 113 63 113 65 114 61 114 64 114 66 115 62 115 63 115 66 116 67 116 59 116 62 117 66 117 59 117 68 118 63 118 65 118 63 119 68 119 66 119 18 120 19 120 64 120 64 121 69 121 65 121 69 122 64 122 19 122 65 123 70 123 68 123 70 124 65 124 69 124 71 125 72 125 67 125 66 126 71 126 67 126 71 127 66 127 68 127 73 128 68 128 70 128 68 129 73 129 71 129 19 130 22 130 69 130 74 131 69 131 22 131 74 132 75 132 70 132 69 133 74 133 70 133 76 134 72 134 71 134 70 135 75 135 73 135 22 136 24 136 74 136 71 137 73 137 77 137 71 138 77 138 76 138 78 139 77 139 73 139 78 140 73 140 75 140 79 141 78 141 75 141 83 142 29 142 31 142 83 143 81 143 82 143 29 144 83 144 82 144 84 145 82 145 81 145 84 146 85 146 86 146 84 147 86 147 82 147 87 148 85 148 84 148 31 149 39 149 83 149 81 150 88 150 84 150 88 151 81 151 83 151 89 152 83 152 39 152 83 153 89 153 88 153 84 154 90 154 87 154 90 155 84 155 88 155 91 156 87 156 90 156 88 157 92 157 90 157 92 158 88 158 89 158 89 159 39 159 45 159 93 160 89 160 45 160 89 161 93 161 92 161 90 162 94 162 91 162 94 163 90 163 92 163 95 164 91 164 94 164 45 165 54 165 93 165 92 166 96 166 94 166 96 167 92 167 93 167 93 168 97 168 96 168 97 169 93 169 54 169 98 170 94 170 96 170 94 171 98 171 95 171 99 172 95 172 98 172 54 173 59 173 97 173 96 174 100 174 98 174 100 175 96 175 97 175 97 176 101 176 100 176 101 177 97 177 59 177 98 178 102 178 99 178 102 179 98 179 100 179 103 180 99 180 102 180 59 181 67 181 101 181 100 182 104 182 102 182 104 183 100 183 101 183 101 184 105 184 104 184 105 185 101 185 67 185 106 186 107 186 103 186 102 187 106 187 103 187 106 188 102 188 104 188 67 189 72 189 105 189 108 190 107 190 106 190 104 191 109 191 106 191 109 192 104 192 105 192 110 193 109 193 105 193 110 194 105 194 72 194 106 195 109 195 108 195 72 196 76 196 110 196 111 197 108 197 109 197 113 198 114 198 112 198 115 199 113 199 112 199 86 200 85 200 116 200 118 201 114 201 113 201 119 202 113 202 115 202 113 203 119 203 118 203 115 204 120 204 119 204 120 205 115 205 117 205 121 206 116 206 85 206 116 207 121 207 117 207 117 208 122 208 120 208 122 209 117 209 121 209 123 210 119 210 120 210 119 211 123 211 118 211 120 212 124 212 123 212 124 213 120 213 122 213 121 214 125 214 122 214 125 215 121 215 85 215 122 216 126 216 124 216 126 217 122 217 125 217 85 218 87 218 125 218 127 219 118 219 123 219 128 220 123 220 124 220 123 221 128 221 127 221 124 222 129 222 128 222 129 223 124 223 126 223 130 224 125 224 87 224 125 225 130 225 126 225 131 226 126 226 130 226 126 227 131 227 129 227 87 228 91 228 130 228 128 229 132 229 127 229 132 230 128 230 129 230 133 231 129 231 131 231 129 232 133 232 132 232 130 233 134 233 131 233 134 234 130 234 91 234 135 235 131 235 134 235 131 236 135 236 133 236 136 237 127 237 132 237 137 238 132 238 133 238 132 239 137 239 136 239 133 240 138 240 137 240 138 241 133 241 135 241 134 242 139 242 135 242 139 243 134 243 91 243 140 244 135 244 139 244 135 245 140 245 138 245 91 246 95 246 139 246 137 247 141 247 136 247 141 248 137 248 138 248 142 249 136 249 141 249 138 250 143 250 141 250 143 251 138 251 140 251 144 252 139 252 95 252 139 253 144 253 140 253 145 254 140 254 144 254 140 255 145 255 143 255 95 256 99 256 144 256 146 257 141 257 143 257 141 258 146 258 142 258 143 259 147 259 146 259 147 260 143 260 145 260 144 261 148 261 145 261 148 262 144 262 99 262 149 263 145 263 148 263 145 264 149 264 147 264 150 265 142 265 146 265 146 266 151 266 150 266 151 267 146 267 147 267 147 268 152 268 151 268 152 269 147 269 149 269 148 270 153 270 149 270 148 271 99 271 103 271 153 272 148 272 103 272 154 273 149 273 153 273 149 274 154 274 152 274 155 275 151 275 152 275 155 276 156 276 150 276 151 277 155 277 150 277 152 278 157 278 155 278 157 279 152 279 154 279 153 280 103 280 107 280 158 281 153 281 107 281 153 282 158 282 154 282 154 283 159 283 157 283 159 284 154 284 158 284 160 285 156 285 155 285 155 286 161 286 160 286 161 287 155 287 157 287 157 288 162 288 161 288 162 289 157 289 159 289 158 290 163 290 159 290 158 291 107 291 108 291 163 292 158 292 108 292 164 293 159 293 163 293 159 294 164 294 162 294 161 295 162 295 165 295 165 296 166 296 160 296 161 297 165 297 160 297 167 298 162 298 164 298 167 299 165 299 162 299 108 300 111 300 163 300 168 301 163 301 111 301 163 302 168 302 164 302 164 303 169 303 167 303 164 304 168 304 169 304 170 305 167 305 169 305 171 306 462 306 172 306 463 307 462 307 171 307 173 308 171 308 172 308 114 309 173 309 172 309 173 310 114 310 118 310 118 311 127 311 173 311 174 312 171 312 173 312 171 313 174 313 463 313 175 314 463 314 174 314 173 315 176 315 174 315 176 316 173 316 127 316 127 317 136 317 176 317 177 318 174 318 176 318 174 319 177 319 175 319 178 320 175 320 177 320 176 321 179 321 177 321 179 322 176 322 136 322 136 323 142 323 179 323 180 324 177 324 179 324 177 325 180 325 178 325 181 326 178 326 180 326 179 327 182 327 180 327 182 328 179 328 142 328 142 329 150 329 182 329 180 330 183 330 181 330 183 331 180 331 182 331 184 332 181 332 183 332 182 333 185 333 183 333 182 334 150 334 156 334 185 335 182 335 156 335 156 336 160 336 185 336 183 337 186 337 184 337 186 338 183 338 185 338 187 339 185 339 160 339 187 340 186 340 185 340 160 341 166 341 187 341 454 342 172 342 462 342 190 343 114 343 172 343 190 344 172 344 454 344 191 345 112 345 114 345 191 346 114 346 190 346 112 347 192 347 86 347 192 348 112 348 191 348 86 349 193 349 82 349 193 350 86 350 192 350 454 351 450 351 190 351 194 352 190 352 450 352 190 353 194 353 191 353 191 354 195 354 192 354 195 355 191 355 194 355 196 356 192 356 195 356 192 357 196 357 193 357 193 358 197 358 82 358 197 359 193 359 196 359 450 360 446 360 194 360 198 361 194 361 446 361 194 362 198 362 195 362 199 363 195 363 198 363 195 364 199 364 196 364 200 365 196 365 199 365 196 366 200 366 197 366 201 367 197 367 200 367 197 368 201 368 82 368 446 369 442 369 198 369 202 370 198 370 442 370 198 371 202 371 199 371 203 372 199 372 202 372 199 373 203 373 200 373 200 374 204 374 201 374 204 375 200 375 203 375 201 376 205 376 82 376 205 377 201 377 204 377 442 378 438 378 202 378 206 379 202 379 438 379 202 380 206 380 203 380 207 381 203 381 206 381 203 382 207 382 204 382 208 383 204 383 207 383 204 384 208 384 205 384 209 385 205 385 208 385 205 386 209 386 82 386 438 387 434 387 206 387 210 388 206 388 434 388 206 389 210 389 207 389 207 390 211 390 208 390 211 391 207 391 210 391 212 392 208 392 211 392 208 393 212 393 209 393 209 394 213 394 82 394 213 395 209 395 212 395 434 396 430 396 210 396 214 397 210 397 430 397 210 398 214 398 211 398 211 399 215 399 212 399 215 400 211 400 214 400 216 401 212 401 215 401 212 402 216 402 213 402 217 403 213 403 216 403 213 404 217 404 82 404 430 405 426 405 214 405 214 406 218 406 215 406 218 407 214 407 426 407 215 408 219 408 216 408 219 409 215 409 218 409 220 410 216 410 219 410 216 411 220 411 217 411 221 412 217 412 220 412 217 413 221 413 82 413 426 414 632 414 218 414 632 415 0 415 218 415 219 416 5 416 220 416 221 417 25 417 29 417 82 418 221 418 29 418 25 419 220 419 5 419 220 420 25 420 221 420 222 421 223 421 224 421 225 422 222 422 224 422 422 423 224 423 223 423 226 424 224 424 422 424 422 425 419 425 226 425 227 426 226 426 419 426 419 427 418 427 227 427 228 428 227 428 418 428 418 429 417 429 228 429 229 430 228 430 417 430 417 431 416 431 229 431 230 432 229 432 416 432 416 433 415 433 230 433 231 434 230 434 415 434 415 435 414 435 231 435 232 436 231 436 414 436 414 437 413 437 232 437 233 438 232 438 413 438 413 439 412 439 233 439 234 440 233 440 412 440 412 441 411 441 234 441 235 442 234 442 411 442 411 443 410 443 235 443 236 444 235 444 410 444 410 445 409 445 236 445 237 446 236 446 409 446 409 447 408 447 237 447 238 448 237 448 408 448 408 449 407 449 238 449 239 450 238 450 407 450 407 451 406 451 239 451 240 452 239 452 406 452 406 453 405 453 240 453 240 454 405 454 188 454 240 455 188 455 241 455 240 456 241 456 189 456 240 457 189 457 80 457 242 458 240 458 80 458 244 459 225 459 224 459 245 460 244 460 224 460 247 461 246 461 245 461 224 462 226 462 245 462 245 463 226 463 227 463 248 464 245 464 227 464 248 465 249 465 247 465 245 466 248 466 247 466 250 467 249 467 248 467 227 468 228 468 248 468 251 469 252 469 250 469 248 470 251 470 250 470 251 471 248 471 228 471 228 472 229 472 251 472 253 473 252 473 251 473 251 474 229 474 230 474 254 475 251 475 230 475 251 476 254 476 253 476 255 477 253 477 254 477 230 478 231 478 254 478 254 479 231 479 232 479 256 480 254 480 232 480 256 481 257 481 255 481 254 482 256 482 255 482 232 483 233 483 256 483 258 484 257 484 256 484 256 485 233 485 234 485 259 486 256 486 234 486 259 487 260 487 258 487 256 488 259 488 258 488 234 489 235 489 259 489 261 490 260 490 259 490 259 491 235 491 236 491 262 492 259 492 236 492 259 493 262 493 261 493 263 494 261 494 262 494 236 495 237 495 262 495 264 496 265 496 263 496 262 497 264 497 263 497 264 498 262 498 237 498 237 499 238 499 264 499 266 500 265 500 264 500 267 501 268 501 266 501 264 502 267 502 266 502 264 503 238 503 239 503 267 504 264 504 239 504 239 505 240 505 267 505 269 506 268 506 267 506 267 507 242 507 269 507 267 508 240 508 242 508 270 509 269 509 242 509 79 510 243 510 271 510 246 511 271 511 243 511 272 512 271 512 246 512 246 513 247 513 272 513 273 514 272 514 247 514 247 515 249 515 273 515 274 516 273 516 249 516 249 517 250 517 274 517 274 518 250 518 252 518 275 519 274 519 252 519 252 520 253 520 275 520 276 521 275 521 253 521 253 522 255 522 276 522 277 523 276 523 255 523 255 524 257 524 277 524 278 525 277 525 257 525 257 526 258 526 278 526 279 527 278 527 258 527 258 528 260 528 279 528 280 529 279 529 260 529 260 530 261 530 280 530 281 531 280 531 261 531 261 532 263 532 281 532 281 533 263 533 265 533 282 534 281 534 265 534 265 535 266 535 282 535 283 536 282 536 266 536 266 537 268 537 283 537 284 538 283 538 268 538 268 539 269 539 284 539 285 540 284 540 269 540 269 541 270 541 285 541 285 542 270 542 286 542 284 543 285 543 287 543 288 544 289 544 290 544 288 545 290 545 287 545 288 546 287 546 285 546 285 547 286 547 288 547 291 548 289 548 288 548 288 549 292 549 291 549 288 550 286 550 292 550 293 551 291 551 292 551 294 552 293 552 292 552 292 553 168 553 294 553 294 554 168 554 295 554 297 555 295 555 296 555 300 556 299 556 298 556 298 557 301 557 300 557 302 558 300 558 301 558 301 559 303 559 302 559 304 560 302 560 303 560 79 561 271 561 303 561 303 562 271 562 272 562 303 563 272 563 305 563 303 564 305 564 304 564 306 565 304 565 305 565 297 566 299 566 295 566 294 567 295 567 299 567 299 568 300 568 294 568 293 569 294 569 300 569 300 570 302 570 293 570 291 571 293 571 302 571 302 572 304 572 291 572 289 573 291 573 304 573 304 574 306 574 289 574 290 575 289 575 306 575 306 576 307 576 290 576 308 577 290 577 307 577 307 578 309 578 308 578 310 579 308 579 309 579 309 580 311 580 310 580 312 581 310 581 311 581 311 582 313 582 312 582 314 583 312 583 313 583 313 584 315 584 314 584 316 585 314 585 315 585 272 586 273 586 305 586 317 587 305 587 273 587 317 588 307 588 306 588 317 589 306 589 305 589 273 590 274 590 317 590 309 591 307 591 317 591 318 592 311 592 309 592 317 593 318 593 309 593 317 594 274 594 275 594 318 595 317 595 275 595 275 596 276 596 318 596 313 597 311 597 318 597 318 598 276 598 277 598 319 599 318 599 277 599 318 600 319 600 313 600 315 601 313 601 319 601 277 602 278 602 319 602 320 603 319 603 278 603 320 604 316 604 315 604 319 605 320 605 315 605 278 606 279 606 320 606 314 607 316 607 320 607 320 608 279 608 280 608 321 609 320 609 280 609 320 610 321 610 314 610 312 611 314 611 321 611 280 612 281 612 321 612 322 613 310 613 312 613 321 614 322 614 312 614 321 615 281 615 282 615 322 616 321 616 282 616 308 617 310 617 322 617 282 618 283 618 322 618 322 619 283 619 284 619 322 620 284 620 287 620 322 621 287 621 308 621 290 622 308 622 287 622 167 623 270 623 242 623 242 624 165 624 167 624 170 625 286 625 270 625 170 626 270 626 167 626 292 627 286 627 170 627 168 628 292 628 170 628 168 629 111 629 295 629 170 630 169 630 168 630 301 631 298 631 303 631 78 632 303 632 298 632 303 633 78 633 79 633 297 634 76 634 298 634 298 635 77 635 78 635 298 636 76 636 77 636 75 637 243 637 79 637 24 638 225 638 244 638 244 639 74 639 24 639 74 640 244 640 243 640 243 641 75 641 74 641 225 642 24 642 222 642 186 643 241 643 188 643 186 644 187 644 241 644 187 645 189 645 241 645 166 646 189 646 187 646 80 647 189 647 166 647 80 648 166 648 165 648 80 649 165 649 242 649 109 650 295 650 111 650 109 651 296 651 295 651 109 652 110 652 296 652 76 653 296 653 110 653 76 654 297 654 296 654 297 655 298 655 299 655 244 656 245 656 246 656 243 657 244 657 246 657 5 658 219 658 218 658 2 659 5 659 218 659 0 660 2 660 218 660 86 661 117 661 112 661 112 662 117 662 115 662 86 663 116 663 117 663 548 664 517 664 518 664 522 665 519 665 517 665 548 666 522 666 517 666 632 667 426 667 630 667 630 668 426 668 627 668 627 669 426 669 425 669 402 670 399 670 401 670 401 671 399 671 400 671 348 672 346 672 347 672 558 673 349 673 348 673 558 674 524 674 349 674 525 675 349 675 524 675 525 676 350 676 349 676 525 677 523 677 350 677 554 678 403 678 469 678 554 679 469 679 468 679 554 680 468 680 455 680 468 681 456 681 455 681 456 682 404 682 455 682 186 683 404 683 456 683 186 684 188 684 404 684 420 685 421 685 610 685 402 686 560 686 559 686 560 687 402 687 401 687 401 688 610 688 560 688 610 689 401 689 420 689 559 690 555 690 402 690 347 691 557 691 558 691 347 692 556 692 557 692 348 693 347 693 558 693 342 694 555 694 556 694 556 695 347 695 342 695 344 696 342 696 347 696 464 697 466 697 465 697 466 698 350 698 523 698 466 699 464 699 353 699 353 700 464 700 359 700 464 701 467 701 375 701 464 702 375 702 359 702 403 703 467 703 469 703 467 704 403 704 375 704 355 705 358 705 337 705 323 706 337 706 358 706 323 707 358 707 361 707 323 708 361 708 362 708 363 709 323 709 362 709 337 710 323 710 335 710 323 711 363 711 324 711 324 712 363 712 364 712 324 713 333 713 323 713 323 714 333 714 335 714 365 715 324 715 364 715 333 716 324 716 331 716 325 717 331 717 324 717 324 718 365 718 325 718 325 719 365 719 366 719 331 720 325 720 329 720 367 721 325 721 366 721 326 722 330 722 325 722 325 723 330 723 329 723 325 724 367 724 326 724 368 725 326 725 367 725 330 726 326 726 332 726 327 727 332 727 326 727 326 728 368 728 327 728 327 729 368 729 369 729 332 730 327 730 334 730 370 731 327 731 369 731 327 732 370 732 328 732 328 733 370 733 371 733 328 734 336 734 327 734 327 735 336 735 334 735 336 736 328 736 338 736 372 737 328 737 371 737 328 738 340 738 339 738 328 739 339 739 338 739 328 740 372 740 340 740 373 741 340 741 372 741 329 742 330 742 331 742 332 743 331 743 330 743 331 744 332 744 333 744 334 745 333 745 332 745 333 746 334 746 335 746 336 747 335 747 334 747 335 748 336 748 337 748 338 749 337 749 336 749 337 750 338 750 355 750 339 751 355 751 338 751 355 752 339 752 356 752 341 753 356 753 339 753 356 754 341 754 354 754 343 755 354 755 341 755 354 756 343 756 352 756 345 757 352 757 343 757 352 758 345 758 351 758 346 759 351 759 345 759 351 760 346 760 350 760 348 761 350 761 346 761 339 762 340 762 341 762 342 763 341 763 340 763 342 764 340 764 373 764 342 765 373 765 374 765 555 766 342 766 374 766 341 767 342 767 343 767 344 768 343 768 342 768 343 769 344 769 345 769 347 770 345 770 344 770 345 771 347 771 346 771 348 772 349 772 350 772 351 773 350 773 466 773 353 774 351 774 466 774 351 775 353 775 352 775 352 776 353 776 354 776 357 777 353 777 359 777 357 778 354 778 353 778 354 779 357 779 356 779 360 780 357 780 359 780 357 781 360 781 358 781 357 782 358 782 355 782 357 783 355 783 356 783 361 784 358 784 360 784 360 785 359 785 375 785 376 786 360 786 375 786 360 787 376 787 361 787 377 788 361 788 376 788 361 789 377 789 362 789 379 790 362 790 377 790 362 791 379 791 363 791 380 792 363 792 379 792 363 793 380 793 364 793 364 794 380 794 382 794 384 795 364 795 382 795 364 796 384 796 365 796 385 797 365 797 384 797 365 798 385 798 366 798 387 799 366 799 385 799 366 800 387 800 367 800 388 801 367 801 387 801 367 802 388 802 368 802 390 803 368 803 388 803 368 804 390 804 369 804 392 805 369 805 390 805 369 806 392 806 370 806 393 807 370 807 392 807 370 808 393 808 371 808 371 809 393 809 395 809 396 810 371 810 395 810 371 811 396 811 372 811 398 812 372 812 396 812 372 813 398 813 373 813 399 814 373 814 398 814 373 815 399 815 374 815 399 816 402 816 374 816 555 817 374 817 402 817 375 818 403 818 376 818 378 819 403 819 405 819 378 820 376 820 403 820 376 821 378 821 377 821 406 822 378 822 405 822 378 823 406 823 381 823 381 824 406 824 407 824 381 825 379 825 378 825 378 826 379 826 377 826 379 827 381 827 380 827 408 828 381 828 407 828 381 829 408 829 383 829 383 830 382 830 381 830 381 831 382 831 380 831 409 832 383 832 408 832 382 833 383 833 384 833 386 834 384 834 383 834 383 835 409 835 386 835 386 836 409 836 410 836 384 837 386 837 385 837 411 838 386 838 410 838 389 839 387 839 386 839 386 840 387 840 385 840 386 841 411 841 389 841 389 842 411 842 412 842 387 843 389 843 388 843 413 844 389 844 412 844 391 845 390 845 389 845 389 846 390 846 388 846 389 847 413 847 391 847 391 848 413 848 414 848 415 849 391 849 414 849 390 850 391 850 392 850 394 851 392 851 391 851 391 852 415 852 394 852 394 853 415 853 416 853 392 854 394 854 393 854 417 855 394 855 416 855 394 856 417 856 397 856 397 857 395 857 394 857 394 858 395 858 393 858 418 859 397 859 417 859 395 860 397 860 396 860 400 861 398 861 397 861 397 862 398 862 396 862 397 863 418 863 400 863 400 864 418 864 419 864 422 865 400 865 419 865 398 866 400 866 399 866 400 867 422 867 401 867 401 868 422 868 420 868 403 869 554 869 405 869 405 870 554 870 455 870 405 871 455 871 404 871 405 872 404 872 188 872 424 873 423 873 609 873 609 874 627 874 424 874 552 875 605 875 423 875 423 876 605 876 609 876 425 877 424 877 627 877 427 878 552 878 423 878 423 879 424 879 427 879 428 880 427 880 424 880 424 881 425 881 428 881 425 882 426 882 429 882 429 883 428 883 425 883 430 884 429 884 426 884 431 885 552 885 427 885 427 886 428 886 431 886 432 887 431 887 428 887 428 888 429 888 432 888 429 889 430 889 433 889 433 890 432 890 429 890 434 891 433 891 430 891 431 892 432 892 435 892 435 893 552 893 431 893 436 894 435 894 432 894 432 895 433 895 436 895 433 896 434 896 437 896 437 897 436 897 433 897 438 898 437 898 434 898 439 899 552 899 435 899 435 900 436 900 439 900 440 901 439 901 436 901 436 902 437 902 440 902 441 903 440 903 437 903 437 904 438 904 441 904 442 905 441 905 438 905 439 906 440 906 443 906 443 907 552 907 439 907 440 908 441 908 444 908 444 909 443 909 440 909 445 910 444 910 441 910 441 911 442 911 445 911 446 912 445 912 442 912 447 913 552 913 443 913 443 914 444 914 447 914 448 915 447 915 444 915 444 916 445 916 448 916 449 917 448 917 445 917 445 918 446 918 449 918 450 919 449 919 446 919 447 920 448 920 451 920 451 921 552 921 447 921 452 922 451 922 448 922 448 923 449 923 452 923 449 924 450 924 453 924 453 925 452 925 449 925 454 926 453 926 450 926 451 927 452 927 548 927 548 928 552 928 451 928 452 929 453 929 522 929 522 930 548 930 452 930 453 931 454 931 520 931 453 932 520 932 522 932 454 933 462 933 520 933 474 934 456 934 468 934 456 935 457 935 186 935 456 936 474 936 457 936 186 937 457 937 184 937 478 938 457 938 474 938 457 939 478 939 458 939 458 940 478 940 484 940 458 941 184 941 457 941 184 942 458 942 181 942 492 943 458 943 484 943 458 944 492 944 459 944 459 945 181 945 458 945 181 946 459 946 178 946 498 947 459 947 492 947 459 948 498 948 460 948 460 949 178 949 459 949 178 950 460 950 175 950 507 951 460 951 498 951 460 952 507 952 461 952 461 953 175 953 460 953 175 954 461 954 463 954 516 955 461 955 507 955 461 956 516 956 520 956 520 957 462 957 461 957 461 958 462 958 463 958 464 959 465 959 467 959 470 960 465 960 466 960 470 961 467 961 465 961 471 962 470 962 466 962 466 963 523 963 471 963 526 964 471 964 523 964 467 965 472 965 469 965 467 966 470 966 472 966 473 967 474 967 469 967 469 968 474 968 468 968 473 969 469 969 472 969 475 970 472 970 470 970 470 971 471 971 475 971 471 972 526 972 476 972 476 973 526 973 527 973 476 974 475 974 471 974 472 975 475 975 477 975 477 976 473 976 472 976 473 977 477 977 479 977 479 978 474 978 473 978 474 979 479 979 478 979 475 980 476 980 480 980 480 981 477 981 475 981 481 982 480 982 476 982 476 983 527 983 481 983 481 984 527 984 531 984 477 985 480 985 482 985 482 986 479 986 477 986 483 987 484 987 479 987 479 988 484 988 478 988 479 989 482 989 483 989 485 990 482 990 480 990 480 991 481 991 485 991 481 992 531 992 486 992 486 993 531 993 535 993 486 994 485 994 481 994 482 995 485 995 487 995 487 996 483 996 482 996 483 997 487 997 488 997 488 998 484 998 483 998 484 999 488 999 492 999 489 1000 487 1000 485 1000 485 1001 486 1001 489 1001 486 1002 535 1002 490 1002 490 1003 489 1003 486 1003 487 1004 489 1004 491 1004 491 1005 488 1005 487 1005 493 1006 492 1006 488 1006 488 1007 491 1007 493 1007 539 1008 490 1008 535 1008 494 1009 491 1009 489 1009 489 1010 490 1010 494 1010 495 1011 494 1011 490 1011 490 1012 539 1012 495 1012 491 1013 494 1013 496 1013 496 1014 493 1014 491 1014 492 1015 493 1015 498 1015 493 1016 496 1016 497 1016 497 1017 498 1017 493 1017 543 1018 495 1018 539 1018 499 1019 496 1019 494 1019 494 1020 495 1020 499 1020 495 1021 543 1021 500 1021 500 1022 499 1022 495 1022 496 1023 499 1023 501 1023 501 1024 497 1024 496 1024 502 1025 498 1025 497 1025 497 1026 501 1026 502 1026 498 1027 502 1027 507 1027 503 1028 501 1028 499 1028 499 1029 500 1029 503 1029 500 1030 543 1030 504 1030 504 1031 503 1031 500 1031 505 1032 502 1032 501 1032 501 1033 503 1033 505 1033 502 1034 505 1034 506 1034 506 1035 507 1035 502 1035 547 1036 504 1036 543 1036 508 1037 505 1037 503 1037 503 1038 504 1038 508 1038 509 1039 508 1039 504 1039 504 1040 547 1040 509 1040 505 1041 508 1041 510 1041 510 1042 506 1042 505 1042 511 1043 507 1043 506 1043 506 1044 510 1044 511 1044 507 1045 511 1045 516 1045 549 1046 509 1046 547 1046 508 1047 509 1047 512 1047 512 1048 510 1048 508 1048 509 1049 549 1049 513 1049 513 1050 512 1050 509 1050 510 1051 512 1051 514 1051 514 1052 511 1052 510 1052 515 1053 516 1053 511 1053 511 1054 514 1054 515 1054 512 1055 513 1055 517 1055 517 1056 514 1056 512 1056 518 1057 517 1057 513 1057 513 1058 549 1058 518 1058 514 1059 517 1059 519 1059 519 1060 515 1060 514 1060 521 1061 516 1061 515 1061 515 1062 519 1062 521 1062 516 1063 521 1063 520 1063 548 1064 518 1064 549 1064 519 1065 522 1065 521 1065 521 1066 522 1066 520 1066 523 1067 525 1067 526 1067 562 1068 524 1068 558 1068 528 1069 526 1069 525 1069 524 1070 562 1070 529 1070 524 1071 529 1071 525 1071 525 1072 529 1072 530 1072 530 1073 528 1073 525 1073 526 1074 528 1074 527 1074 567 1075 529 1075 562 1075 528 1076 530 1076 532 1076 532 1077 531 1077 528 1077 528 1078 531 1078 527 1078 529 1079 567 1079 533 1079 533 1080 530 1080 529 1080 530 1081 533 1081 534 1081 534 1082 532 1082 530 1082 575 1083 533 1083 567 1083 531 1084 532 1084 535 1084 532 1085 534 1085 536 1085 536 1086 535 1086 532 1086 533 1087 575 1087 537 1087 537 1088 534 1088 533 1088 534 1089 537 1089 538 1089 538 1090 536 1090 534 1090 580 1091 537 1091 575 1091 535 1092 536 1092 539 1092 540 1093 539 1093 536 1093 536 1094 538 1094 540 1094 537 1095 580 1095 541 1095 541 1096 538 1096 537 1096 538 1097 541 1097 542 1097 542 1098 540 1098 538 1098 589 1099 541 1099 580 1099 539 1100 540 1100 543 1100 540 1101 542 1101 544 1101 544 1102 543 1102 540 1102 545 1103 542 1103 541 1103 541 1104 589 1104 545 1104 545 1105 589 1105 595 1105 542 1106 545 1106 546 1106 546 1107 544 1107 542 1107 543 1108 544 1108 547 1108 544 1109 546 1109 550 1109 550 1110 547 1110 544 1110 551 1111 546 1111 545 1111 545 1112 595 1112 551 1112 546 1113 551 1113 553 1113 553 1114 550 1114 546 1114 603 1115 551 1115 595 1115 547 1116 550 1116 549 1116 550 1117 552 1117 548 1117 550 1118 548 1118 549 1118 550 1119 553 1119 552 1119 605 1120 552 1120 551 1120 551 1121 552 1121 553 1121 551 1122 603 1122 605 1122 555 1123 559 1123 556 1123 556 1124 559 1124 561 1124 556 1125 561 1125 557 1125 563 1126 558 1126 557 1126 563 1127 557 1127 561 1127 611 1128 560 1128 610 1128 564 1129 561 1129 559 1129 558 1130 563 1130 562 1130 565 1131 564 1131 560 1131 560 1132 564 1132 559 1132 560 1133 611 1133 565 1133 613 1134 565 1134 611 1134 566 1135 563 1135 561 1135 561 1136 564 1136 566 1136 563 1137 566 1137 568 1137 568 1138 567 1138 563 1138 563 1139 567 1139 562 1139 564 1140 565 1140 569 1140 569 1141 566 1141 564 1141 565 1142 613 1142 570 1142 570 1143 569 1143 565 1143 614 1144 570 1144 613 1144 571 1145 568 1145 566 1145 566 1146 569 1146 571 1146 572 1147 575 1147 568 1147 568 1148 575 1148 567 1148 568 1149 571 1149 572 1149 569 1150 570 1150 573 1150 573 1151 571 1151 569 1151 574 1152 573 1152 570 1152 570 1153 614 1153 574 1153 617 1154 574 1154 614 1154 571 1155 573 1155 576 1155 576 1156 572 1156 571 1156 577 1157 575 1157 572 1157 572 1158 576 1158 577 1158 573 1159 574 1159 578 1159 578 1160 576 1160 573 1160 579 1161 578 1161 574 1161 574 1162 617 1162 579 1162 579 1163 617 1163 620 1163 575 1164 577 1164 580 1164 581 1165 577 1165 576 1165 576 1166 578 1166 581 1166 577 1167 581 1167 582 1167 582 1168 580 1168 577 1168 578 1169 579 1169 583 1169 583 1170 581 1170 578 1170 579 1171 620 1171 584 1171 584 1172 583 1172 579 1172 580 1173 582 1173 589 1173 585 1174 582 1174 581 1174 581 1175 583 1175 585 1175 586 1176 589 1176 582 1176 582 1177 585 1177 586 1177 583 1178 584 1178 587 1178 587 1179 585 1179 583 1179 588 1180 587 1180 584 1180 584 1181 620 1181 588 1181 588 1182 620 1182 623 1182 585 1183 587 1183 590 1183 590 1184 586 1184 585 1184 586 1185 590 1185 591 1185 591 1186 589 1186 586 1186 592 1187 590 1187 587 1187 587 1188 588 1188 592 1188 588 1189 623 1189 593 1189 593 1190 592 1190 588 1190 589 1191 591 1191 595 1191 594 1192 591 1192 590 1192 590 1193 592 1193 594 1193 591 1194 594 1194 596 1194 596 1195 595 1195 591 1195 597 1196 594 1196 592 1196 592 1197 593 1197 597 1197 626 1198 593 1198 623 1198 593 1199 626 1199 598 1199 598 1200 597 1200 593 1200 594 1201 597 1201 599 1201 599 1202 596 1202 594 1202 595 1203 596 1203 603 1203 596 1204 599 1204 600 1204 600 1205 603 1205 596 1205 601 1206 599 1206 597 1206 597 1207 598 1207 601 1207 602 1208 601 1208 598 1208 598 1209 626 1209 602 1209 599 1210 601 1210 604 1210 604 1211 600 1211 599 1211 606 1212 603 1212 600 1212 600 1213 604 1213 606 1213 628 1214 602 1214 626 1214 607 1215 604 1215 601 1215 601 1216 602 1216 607 1216 608 1217 607 1217 602 1217 602 1218 628 1218 608 1218 603 1219 606 1219 605 1219 627 1220 608 1220 628 1220 604 1221 607 1221 609 1221 609 1222 605 1222 604 1222 604 1223 605 1223 606 1223 607 1224 608 1224 609 1224 609 1225 608 1225 627 1225 610 1226 612 1226 611 1226 615 1227 612 1227 20 1227 615 1228 613 1228 612 1228 612 1229 613 1229 611 1229 616 1230 615 1230 20 1230 613 1231 615 1231 614 1231 618 1232 617 1232 615 1232 615 1233 617 1233 614 1233 615 1234 616 1234 618 1234 619 1235 618 1235 616 1235 617 1236 618 1236 620 1236 618 1237 619 1237 621 1237 621 1238 620 1238 618 1238 622 1239 621 1239 619 1239 620 1240 621 1240 623 1240 624 1241 623 1241 621 1241 621 1242 622 1242 624 1242 625 1243 624 1243 622 1243 623 1244 624 1244 626 1244 629 1245 626 1245 624 1245 624 1246 625 1246 629 1246 631 1247 629 1247 625 1247 626 1248 629 1248 628 1248 630 1249 627 1249 629 1249 629 1250 627 1250 628 1250 629 1251 631 1251 630 1251 631 1252 632 1252 630 1252 420 1253 422 1253 421 1253 223 1254 421 1254 422 1254 421 1255 612 1255 610 1255 223 1256 612 1256 421 1256 223 1257 20 1257 612 1257 20 1258 223 1258 21 1258 21 1259 223 1259 23 1259 23 1260 223 1260 222 1260 23 1261 222 1261 24 1261

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_middle/th_middle_G4.dae b/URDFs/sr_description/meshes/components/th_middle/th_middle_G4.dae new file mode 100644 index 0000000..6412d37 --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_middle/th_middle_G4.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:04.601049 + 2012-07-23T02:14:04.601062 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -10.82211 1.89451 0.02984 -10.52279 1.19648 4.40604 -10.43772 3.42460 0.02983 -10.01191 3.48500 4.44190 -9.24738 5.48540 3.30954 -9.53206 5.50770 0.02984 -8.76916 5.54120 6.52921 -9.89934 1.32759 8.78240 -9.34524 3.61260 8.85396 -8.04629 5.52890 11.15913 -9.26471 1.36724 13.15861 -8.71246 3.57270 13.26610 -7.62288 5.23110 15.49638 -8.79618 1.20098 17.53489 -8.36209 3.12530 17.67809 -7.64989 4.79500 18.13671 -8.53313 0.87560 21.91118 -8.31577 2.41180 22.09022 -7.82107 4.31860 20.58139 -8.02359 3.94460 22.84329 -8.30538 -0.79062 26.28739 -8.30538 0.70052 26.28740 -8.18404 3.75820 24.93399 -8.28854 1.69868 26.40406 -8.25863 3.80240 26.86291 -7.06228 8.40020 0.02984 -8.38620 6.91280 2.41682 -7.24683 8.13770 2.46228 -4.47194 9.96990 2.48145 -3.75606 10.29400 0.02976 -5.94010 9.15660 2.50980 -2.75840 10.49580 3.62321 -8.07380 6.89460 4.80358 -6.95048 8.05290 4.89452 -4.28569 9.79750 4.93299 -5.69028 9.01010 4.98983 -7.68404 6.86400 7.19021 -6.59311 7.90890 7.32682 -4.12086 9.51920 7.38459 -2.57576 10.09530 7.41507 -5.41925 8.76810 7.46987 -7.28799 6.80580 9.57691 -6.23702 7.73940 9.75913 -3.95787 9.22070 9.83620 -5.15147 8.50730 9.94991 -2.40556 9.64210 11.24200 -6.95685 6.70500 11.96360 -5.94428 7.57760 12.19143 -3.77749 8.98770 12.28781 -4.91141 8.30410 12.42994 -6.76190 6.54660 14.35030 -5.77712 7.45700 14.62374 -3.56027 8.90580 14.73935 -4.72338 8.23520 14.90998 -2.13855 9.43290 14.94243 -6.77357 6.31590 16.73700 -5.79564 7.41050 17.05605 -3.28867 9.05710 17.19096 -4.61110 8.37220 17.38994 -1.72766 9.64300 18.33506 -7.00006 6.03250 19.12369 -5.99731 7.44970 19.48835 -2.99557 9.42630 19.64257 -4.58613 8.69440 19.86998 -7.34378 5.77480 21.51040 -6.30172 7.56070 21.92059 -2.76823 9.89430 22.09418 -1.33429 10.08770 21.40864 -4.64892 9.10020 22.35008 -7.69641 5.62700 23.89709 -6.62395 7.72770 24.35296 -2.69618 10.33660 24.54579 -1.13835 10.51830 24.18891 -4.79982 9.48510 24.83005 -7.87334 5.89220 26.22347 -6.92828 7.84400 26.71059 -1.22462 10.79640 26.70466 -3.12402 10.54986 26.98725 -5.11937 9.69790 27.34445 -5.42738 9.83580 28.97489 8.61265 5.13360 29.45177 0.06932 10.86760 3.80621 -0.01024 11.00000 0.02977 -1.40119 10.75920 3.81399 1.54101 10.76320 3.81675 2.87009 10.51680 3.52160 3.74599 10.31910 0.02461 3.06080 10.10820 6.97886 0.26646 10.44410 7.58258 -1.22349 10.34610 7.59807 1.75633 10.31870 7.60365 3.19084 9.65190 10.35776 0.40632 9.98440 11.35896 -1.07563 9.89580 11.38229 1.88615 9.84550 11.39063 3.12557 9.35790 13.61293 0.44521 9.74450 15.13533 -0.89992 9.67180 15.16637 1.78511 9.61390 15.17754 2.77768 9.38120 16.66155 0.34961 9.93570 18.91171 -0.65823 9.88990 18.95053 1.34910 9.84460 18.96453 2.21227 9.70760 19.47371 0.17213 10.39810 22.68822 -0.46781 10.38080 22.73461 0.80393 10.35940 22.75151 1.66398 10.14140 22.07601 1.30046 10.53670 24.50004 0.63860 10.78850 26.55730 -0.26995 10.78750 26.46785 1.22529 10.79760 26.75026 7.06210 8.42260 0.02481 8.41345 7.01390 2.18807 9.50643 5.48610 0.02976 7.26406 8.22570 2.23212 4.46815 10.02870 2.27030 5.94975 9.22990 2.28890 9.32640 5.51470 3.95308 8.34041 6.89470 4.35005 7.22057 8.06730 4.43978 4.53342 9.83020 4.51699 5.95696 9.03570 4.55093 8.18244 6.77210 6.51210 7.10496 7.85940 6.64744 4.60456 9.53340 6.76375 5.92833 8.75480 6.81304 9.00644 5.38790 7.87618 7.97886 6.64160 8.67407 6.94847 7.63310 8.85509 4.64917 9.20840 9.01044 5.86525 8.45070 9.07521 7.76899 6.49850 10.83612 6.78223 7.41940 11.06275 4.63475 8.92510 11.25721 5.76895 8.18680 11.33725 8.61378 5.22010 11.68501 7.59222 6.33800 12.99817 6.63741 7.24920 13.27048 4.52889 8.75350 13.50389 5.64082 8.02660 13.59928 7.48771 6.15560 15.16022 8.32521 4.90480 15.26346 6.54521 7.15350 15.47806 4.29922 8.76350 15.75065 5.48222 8.03360 15.86139 7.49153 5.94840 17.32228 6.53255 7.15940 17.68572 3.92877 9.00560 17.99735 5.29914 8.25080 18.12349 8.23527 4.41720 18.53411 7.59137 5.74270 19.48432 6.58862 7.26040 19.89338 3.49200 9.41690 20.24404 5.12194 8.61970 20.38567 7.73767 5.58670 21.64630 8.25740 3.95780 21.48409 6.68360 7.43260 22.10104 3.09609 9.89340 22.49073 4.98816 9.05000 22.64771 8.28384 3.71300 24.13419 7.87952 5.52970 23.80835 6.78704 7.65190 24.30869 2.84803 10.33120 24.73749 4.93555 9.45130 24.90974 7.96324 5.62190 25.97040 8.25683 3.76260 26.51529 6.86779 7.89350 26.51643 2.85645 10.62480 26.98418 5.02005 9.72250 27.17793 5.01206 9.91015 28.28688 10.72605 1.18730 4.35415 10.80892 1.89560 0.02976 10.22011 3.47460 4.38505 10.33368 1.07588 8.67846 10.30603 -1.32513 8.68545 9.83651 3.37060 8.74033 9.82534 0.96963 13.00276 9.78150 -1.36852 13.01323 9.35575 3.19910 13.09561 9.29663 0.82529 17.32708 9.25393 -1.21342 17.34108 8.92802 2.79230 17.45089 8.80583 0.66934 21.65139 8.78052 -0.89296 21.66892 8.60947 2.24530 21.80618 8.35632 -0.05477 25.91333 8.32436 1.64096 26.06027 8.66363 -0.09010 29.62890 8.64029 3.91250 29.54616 10.17118 1.89878 -3.67597 8.94513 5.49330 -3.22971 6.63522 8.42400 -2.39370 3.52367 10.33660 -1.26092 8.28971 1.89878 -6.93474 7.29022 5.49331 -6.09604 5.40599 8.42400 -4.51997 2.86939 10.33660 -2.39137 5.40719 1.89878 -9.35354 4.75482 5.49330 -8.22358 3.52367 8.42400 -6.09781 1.86812 10.33660 -3.23000 1.87124 1.89878 -10.64048 1.64468 5.49331 -9.35552 1.21532 8.42400 -6.93679 0.64044 10.33660 -3.67576 -1.89170 1.89878 -10.64048 -1.66514 5.49330 -9.35552 -1.24074 8.42400 -6.93594 -0.66558 10.33660 -3.67491 -5.42766 1.89878 -9.35354 -4.77529 5.49330 -8.22358 -3.54853 8.42400 -6.09527 -1.89270 10.33660 -3.22759 -8.31018 1.89878 -6.93474 -7.31069 5.49330 -6.09605 -5.42971 8.42400 -4.51615 -2.89297 10.33660 -2.38769 -10.19165 1.89878 -3.67597 -8.96560 5.49330 -3.22971 -6.65746 8.42400 -2.38896 -3.54577 10.33660 -1.25646 -8.65377 3.85249 29.52191 -8.67159 0.00316 29.58427 -8.97734 5.75739 31.26040 -8.62534 5.13799 29.42574 -8.92799 5.75739 33.24101 -8.44687 5.75739 35.16321 -7.55740 5.75739 36.93373 -6.30115 5.75739 38.46575 -4.74085 5.75739 39.68664 -2.95096 5.75739 40.53609 -1.01801 5.75739 40.97280 0.96295 5.75739 40.97697 2.89704 5.75739 40.54733 4.69025 5.75739 39.70474 6.25565 5.75739 38.49036 7.51734 5.75740 36.96280 8.41431 5.75740 35.19623 8.90306 5.75740 33.27615 8.95977 5.75740 31.29569 8.65656 1.84708 29.60358 8.35498 6.41670 28.91394 -7.38982 7.94489 28.76241 -8.31528 6.49310 28.80709 -8.78182 6.90539 32.00492 -8.03264 7.87869 30.76628 -8.10922 7.87869 32.63197 -8.12485 6.90539 35.36077 -7.75793 7.87869 34.46621 -6.99652 7.87869 36.17090 -6.23433 6.90539 38.21012 -5.86572 7.87869 37.65667 -4.42626 7.87869 38.84582 -3.39862 6.90539 40.12094 -2.75254 7.87869 39.67384 -0.04722 6.90539 40.80133 -0.93471 7.87869 40.09867 0.93269 7.87869 40.09620 3.30949 6.90540 40.14902 2.75003 7.87869 39.66762 4.42149 7.87869 38.83535 6.16175 6.90540 38.26267 5.85861 7.87870 37.64331 8.07595 6.90540 35.42908 6.98559 7.87870 36.15457 7.74269 7.87870 34.44783 8.76128 6.90540 32.07895 8.09009 7.87870 32.61324 8.00927 7.87870 30.74782 7.13755 8.03140 28.36388 -5.75442 10.12129 30.77964 -5.88891 10.12129 32.02981 -5.68858 10.12129 33.55129 -5.10133 10.12129 34.96911 -4.16711 10.12129 36.18661 -2.94961 10.12129 37.12083 -1.53171 10.12129 37.70816 -0.01024 10.12129 37.90848 1.51124 10.12129 37.70816 2.92913 10.12129 37.12083 4.14663 10.12129 36.18661 5.08086 10.12129 34.96911 5.66811 10.12129 33.55129 5.86843 10.12130 32.02981 5.73083 10.12130 30.76508 5.32404 10.12150 29.55953 4.88535 10.74795 32.02972 4.52677 10.77160 30.16474 3.59488 11.00000 30.97120 3.74711 11.00000 32.02981 3.15067 11.00000 29.99836 3.48542 10.81730 28.47776 2.45035 11.00000 29.19014 1.55063 11.00000 28.61201 0.52448 11.00000 28.31064 -0.22463 10.94620 27.71228 -0.90310 10.94670 27.80258 -3.41361 10.67647 27.95695 -1.57110 11.00000 28.61201 -2.47082 11.00000 29.19014 -3.75642 10.71769 28.67628 -3.17115 10.99999 29.99836 -4.54689 10.77160 30.16368 -3.61535 10.99999 30.97120 -4.90581 10.74795 32.02974 -3.76759 10.99999 32.02981 -3.61542 10.99999 33.08834 3.59495 11.00000 33.08834 -3.17115 10.99999 34.06111 3.15059 11.00000 34.06118 -2.47075 10.99999 34.86940 2.45028 11.00000 34.86940 -1.57111 10.99999 35.44761 1.55063 10.99999 35.44761 -0.54502 10.99999 35.74890 0.52455 10.99999 35.74890 -4.42986 10.77159 34.15820 -3.06869 10.77160 35.86501 -1.10180 10.77160 36.81225 1.08132 10.77160 36.81225 3.04821 10.77160 35.86501 4.40939 10.77160 34.15820 4.40939 -10.86170 34.15819 3.04822 -10.86170 35.86501 1.08133 -10.86170 36.81224 -1.10180 -10.86170 36.81224 -3.06868 -10.86170 35.86501 -4.42986 -10.86170 34.15819 0.52455 -11.09011 35.74890 -0.54502 -11.09011 35.74890 1.55064 -11.09011 35.44760 -1.57110 -11.09011 35.44760 2.45028 -11.09010 34.86940 -2.47075 -11.09011 34.86940 3.15060 -11.09010 34.06118 -3.17114 -11.09011 34.06110 3.59495 -11.09010 33.08834 -3.61542 -11.09011 33.08834 -3.76759 -11.09011 32.02980 -4.90581 -10.83806 32.02974 -3.61535 -11.09011 30.97119 -4.54689 -10.86171 30.16368 -3.17114 -11.09011 29.99836 -3.75641 -10.80780 28.67628 -2.47082 -11.09010 29.19013 -1.57110 -11.09010 28.61200 -3.41360 -10.76658 27.95695 -0.90309 -11.03680 27.80258 -0.22463 -11.03630 27.71228 0.52448 -11.09010 28.31063 1.55063 -11.09010 28.61200 2.45035 -11.09010 29.19013 3.48542 -10.90741 28.47776 3.15067 -11.09010 29.99836 3.74712 -11.09010 32.02980 3.59488 -11.09010 30.97119 4.52677 -10.86170 30.16474 4.88535 -10.83805 32.02972 5.32404 -10.21160 29.55953 5.73084 -10.21140 30.76507 5.86844 -10.21140 32.02980 5.66811 -10.21140 33.55128 5.08086 -10.21140 34.96910 4.14663 -10.21140 36.18660 2.92914 -10.21141 37.12083 1.51124 -10.21141 37.70815 -0.01023 -10.21141 37.90848 -1.53171 -10.21141 37.70815 -2.94960 -10.21141 37.12083 -4.16710 -10.21141 36.18660 -5.10133 -10.21140 34.96910 -5.68858 -10.21140 33.55128 -5.88891 -10.21140 32.02980 -5.75441 -10.21140 30.77964 7.13755 -8.12150 28.36388 8.00927 -7.96880 30.74782 8.09009 -7.96880 32.61324 8.76128 -6.99550 32.07895 7.74269 -7.96880 34.44782 6.98560 -7.96880 36.15456 8.07595 -6.99550 35.42908 5.85861 -7.96880 37.64331 6.16175 -6.99550 38.26267 4.42149 -7.96880 38.83535 2.75003 -7.96880 39.66762 3.30949 -6.99550 40.14902 0.93269 -7.96880 40.09619 -0.93471 -7.96880 40.09867 -0.04722 -6.99550 40.80132 -2.75254 -7.96880 39.67384 -3.39862 -6.99551 40.12094 -4.42626 -7.96880 38.84582 -5.86571 -7.96881 37.65667 -6.23433 -6.99551 38.21012 -6.99652 -7.96881 36.17090 -7.75793 -7.96880 34.46621 -8.12485 -6.99550 35.36077 -8.10922 -7.96881 32.63197 -8.03264 -7.96881 30.76628 -8.78182 -6.99550 32.00491 -8.31528 -6.58320 28.80709 -7.38981 -8.03500 28.76241 8.35498 -6.50680 28.91394 8.65656 -1.93718 29.60358 8.95977 -5.84750 31.29569 8.90306 -5.84750 33.27615 8.41431 -5.84750 35.19623 7.51734 -5.84750 36.96279 6.25565 -5.84750 38.49036 4.69026 -5.84750 39.70473 2.89704 -5.84750 40.54733 0.96295 -5.84750 40.97696 -1.01800 -5.84750 40.97280 -2.95095 -5.84750 40.53608 -4.74085 -5.84750 39.68664 -6.30115 -5.84750 38.46575 -7.55740 -5.84750 36.93373 -8.44687 -5.84750 35.16320 -8.92799 -5.84750 33.24101 -8.62534 -5.22810 29.42574 -8.65377 -3.94260 29.52191 -8.97734 -5.84750 31.26040 -3.54577 -10.42670 -1.25647 -6.65746 -8.51410 -2.38897 -8.96560 -5.58340 -3.22972 -10.19165 -1.98888 -3.67597 -2.89297 -10.42670 -2.38769 -5.42971 -8.51410 -4.51616 -7.31068 -5.58340 -6.09605 -8.31018 -1.98888 -6.93474 -1.89269 -10.42670 -3.22760 -3.54852 -8.51410 -6.09527 -4.77528 -5.58340 -8.22358 -5.42766 -1.98888 -9.35354 -0.66558 -10.42670 -3.67491 -1.24074 -8.51410 -6.93595 -1.66514 -5.58340 -9.35552 -1.89170 -1.98888 -10.64048 0.64045 -10.42670 -3.67576 1.21532 -8.51410 -6.93680 1.64468 -5.58340 -9.35552 1.87123 -1.98888 -10.64047 1.86813 -10.42670 -3.23000 3.52368 -8.51410 -6.09782 4.75482 -5.58340 -8.22358 5.40719 -1.98888 -9.35354 2.86939 -10.42670 -2.39137 5.40599 -8.51410 -4.51997 7.29022 -5.58340 -6.09604 8.28971 -1.98888 -6.93474 3.52367 -10.42670 -1.26092 6.63523 -8.51410 -2.39370 8.94513 -5.58340 -3.22972 10.17118 -1.98888 -3.67597 8.64029 -4.00260 29.54616 8.32436 -1.73106 26.06027 8.60947 -2.33540 21.80618 8.92802 -2.88240 17.45089 9.35575 -3.28920 13.09561 9.83651 -3.46070 8.74033 10.22011 -3.56470 4.38505 10.80892 -1.98570 0.02976 10.72605 -1.27740 4.35415 5.01207 -10.00026 28.28688 5.02005 -9.81260 27.17792 2.85645 -10.71490 26.98417 6.86779 -7.98360 26.51642 8.25683 -3.85270 26.51529 7.96325 -5.71200 25.97040 4.93555 -9.54140 24.90974 2.84804 -10.42130 24.73748 6.78704 -7.74200 24.30869 7.87952 -5.61980 23.80835 8.28384 -3.80310 24.13419 4.98816 -9.14010 22.64770 3.09609 -9.98350 22.49072 6.68360 -7.52270 22.10104 8.25740 -4.04790 21.48409 7.73768 -5.67680 21.64630 5.12194 -8.70980 20.38566 3.49200 -9.50700 20.24403 6.58863 -7.35050 19.89338 7.59137 -5.83280 19.48432 8.23527 -4.50730 18.53411 5.29915 -8.34090 18.12349 3.92878 -9.09570 17.99734 6.53255 -7.24950 17.68572 7.49153 -6.03850 17.32227 5.48222 -8.12370 15.86138 4.29923 -8.85360 15.75065 6.54521 -7.24360 15.47806 8.32521 -4.99490 15.26346 7.48771 -6.24570 15.16022 5.64083 -8.11670 13.59928 4.52889 -8.84360 13.50389 6.63742 -7.33930 13.27048 7.59222 -6.42810 12.99817 8.61378 -5.31020 11.68500 5.76895 -8.27690 11.33725 4.63475 -9.01520 11.25721 6.78224 -7.50950 11.06275 7.76900 -6.58860 10.83612 5.86526 -8.54080 9.07521 4.64917 -9.29850 9.01044 6.94848 -7.72320 8.85509 7.97887 -6.73170 8.67407 9.00644 -5.47800 7.87617 5.92833 -8.84490 6.81303 4.60456 -9.62350 6.76375 7.10496 -7.94950 6.64743 8.18244 -6.86220 6.51209 5.95697 -9.12580 4.55093 4.53343 -9.92030 4.51699 7.22057 -8.15740 4.43977 8.34041 -6.98480 4.35004 9.32640 -5.60480 3.95307 5.94975 -9.32000 2.28890 4.46815 -10.11880 2.27030 7.26406 -8.31580 2.23212 9.50643 -5.57620 0.02976 8.41345 -7.10400 2.18806 7.06211 -8.51270 0.02481 1.22529 -10.88770 26.75026 -0.26995 -10.87760 26.46784 0.63860 -10.87860 26.55729 1.30046 -10.62680 24.50003 1.66399 -10.23150 22.07600 0.80393 -10.44950 22.75150 -0.46780 -10.47090 22.73461 0.17213 -10.48820 22.68822 2.21228 -9.79770 19.47371 1.34910 -9.93470 18.96452 -0.65823 -9.98000 18.95052 0.34962 -10.02580 18.91170 2.77768 -9.47130 16.66155 1.78511 -9.70400 15.17754 -0.89992 -9.76190 15.16637 0.44522 -9.83460 15.13533 3.12557 -9.44800 13.61292 1.88616 -9.93560 11.39063 -1.07563 -9.98590 11.38229 0.40633 -10.07450 11.35896 3.19084 -9.74200 10.35776 1.75633 -10.40880 7.60365 -1.22349 -10.43620 7.59807 0.26646 -10.53420 7.58258 3.06080 -10.19830 6.97885 3.74599 -10.40920 0.02460 2.87010 -10.60690 3.52160 1.54102 -10.85330 3.81674 -1.40118 -10.84930 3.81398 -0.01023 -11.09010 0.02976 0.06932 -10.95770 3.80620 8.61265 -5.22370 29.45177 -5.42738 -9.92590 28.97489 -5.11936 -9.78800 27.34444 -3.12402 -10.63996 26.98725 -1.22462 -10.88650 26.70466 -6.92828 -7.93410 26.71059 -7.87333 -5.98230 26.22347 -4.79982 -9.57520 24.83005 -1.13835 -10.60840 24.18891 -2.69618 -10.42670 24.54579 -6.62395 -7.81780 24.35296 -7.69641 -5.71710 23.89709 -4.64892 -9.19030 22.35008 -1.33429 -10.17780 21.40864 -2.76823 -9.98440 22.09418 -6.30171 -7.65080 21.92059 -7.34378 -5.86490 21.51039 -4.58613 -8.78450 19.86997 -2.99557 -9.51640 19.64257 -5.99730 -7.53980 19.48835 -7.00006 -6.12260 19.12369 -1.72766 -9.73310 18.33506 -4.61109 -8.46230 17.38994 -3.28867 -9.14720 17.19096 -5.79564 -7.50060 17.05604 -6.77357 -6.40600 16.73700 -2.13855 -9.52300 14.94243 -4.72338 -8.32530 14.90997 -3.56026 -8.99590 14.73935 -5.77711 -7.54710 14.62374 -6.76190 -6.63670 14.35030 -4.91141 -8.39420 12.42994 -3.77749 -9.07780 12.28781 -5.94427 -7.66770 12.19143 -6.95685 -6.79510 11.96360 -2.40556 -9.73220 11.24200 -5.15147 -8.59740 9.94990 -3.95787 -9.31080 9.83620 -6.23701 -7.82950 9.75912 -7.28799 -6.89590 9.57691 -5.41925 -8.85820 7.46987 -2.57576 -10.18540 7.41507 -4.12086 -9.60930 7.38459 -6.59311 -7.99900 7.32682 -7.68404 -6.95410 7.19021 -5.69028 -9.10020 4.98983 -4.28568 -9.88760 4.93298 -6.95048 -8.14300 4.89451 -8.07380 -6.98470 4.80358 -2.75840 -10.58590 3.62321 -5.94010 -9.24670 2.50980 -3.75606 -10.38410 0.02976 -4.47194 -10.06000 2.48144 -7.24683 -8.22780 2.46228 -8.38620 -7.00290 2.41682 -7.06228 -8.49030 0.02983 -8.25863 -3.89250 26.86290 -8.18404 -3.84830 24.93399 -8.28218 -2.23900 26.50221 -8.02359 -4.03470 22.84328 -7.82107 -4.40870 20.58139 -8.31577 -2.50190 22.09022 -8.53313 -0.96570 21.91118 -7.64989 -4.88510 18.13671 -8.36209 -3.21540 17.67809 -8.79618 -1.29108 17.53489 -7.62288 -5.32120 15.49638 -8.71246 -3.66280 13.26609 -9.26471 -1.45734 13.15861 -8.04629 -5.61900 11.15913 -9.34524 -3.70270 8.85396 -9.89934 -1.41769 8.78240 -8.76916 -5.63130 6.52920 -9.53206 -5.59780 0.02983 -9.24738 -5.57550 3.30953 -10.01191 -3.57510 4.44190 -10.43772 -3.51470 0.02983 -10.52279 -1.28658 4.40604 -10.82211 -1.98461 0.02984 + + + + + + + + + + -0.99767 -0.00000 0.06824 -0.99767 0.00000 0.06824 -0.96454 0.24231 0.10462 -0.97224 0.21562 0.09088 -0.91458 0.39600 0.08208 -0.91393 0.39734 0.08277 -0.90059 0.41583 0.12656 -0.99000 0.00000 0.14104 -0.96794 0.21402 0.13148 -0.99000 -0.00000 0.14104 -0.96340 0.22926 0.13894 -0.89990 0.41813 0.12388 -0.88968 0.43458 0.14006 -0.98965 -0.00000 0.14352 -0.96356 0.22934 0.13766 -0.98965 -0.00000 0.14352 -0.96207 0.23408 0.14010 -0.88674 0.44327 0.13118 -0.89489 0.43069 0.11693 -0.99432 -0.00000 0.10645 -0.99432 0.00000 0.10645 -0.96519 0.23621 0.11231 -0.89409 0.43290 0.11490 -0.97228 0.21198 0.09871 -0.92371 0.37938 0.05321 -0.99820 0.00000 0.06000 -0.97395 0.21417 0.07446 -0.99820 0.00000 0.06000 -0.99013 0.13632 0.03244 -0.97187 0.23444 -0.02237 -0.92437 0.37496 0.07034 -0.97592 0.21175 -0.05236 -0.99865 0.00000 0.05197 -0.99865 -0.00000 0.05197 -0.98943 0.13338 0.05683 -0.99703 -0.00430 -0.07690 -0.98471 0.17078 0.03445 -0.99984 0.01582 0.00892 -0.99897 0.02275 -0.03915 -0.76038 0.64925 -0.01717 -0.73242 0.68061 0.01788 -0.48479 0.87424 -0.02599 -0.49664 0.86705 -0.03972 -0.61532 0.78735 0.03828 -0.83204 0.54949 0.07596 -0.31376 0.94890 0.03382 -0.81854 0.56354 0.11144 -0.73035 0.67561 0.10075 -0.71775 0.68733 0.11142 -0.61399 0.78268 0.10210 -0.81869 0.56324 0.11184 -0.48080 0.87136 0.09781 -0.34769 0.93308 0.09203 -0.48346 0.86963 0.10007 -0.60650 0.78777 0.10763 -0.79844 0.58607 0.13791 -0.71708 0.68553 0.12589 -0.69385 0.70563 0.14372 -0.60576 0.78404 0.13542 -0.31946 0.93891 0.12806 -0.48077 0.86705 0.13075 -0.34904 0.93002 0.11504 -0.48920 0.86127 0.13750 -0.59586 0.79039 0.14224 -0.69421 0.70748 0.13245 -0.79949 0.58245 0.14687 -0.77873 0.61514 0.12322 -0.67103 0.72634 0.14886 -0.59586 0.79038 0.14231 -0.34847 0.92739 0.13608 -0.48921 0.86128 0.13739 -0.58832 0.79513 0.14714 -0.49759 0.85543 0.14368 -0.36416 0.92284 0.12548 -0.67093 0.73109 0.12396 -0.77086 0.62291 0.13326 -0.66384 0.73668 0.12890 -0.58747 0.79970 0.12390 -0.35537 0.92771 0.11432 -0.50110 0.85726 0.11834 -0.50168 0.85686 0.11877 -0.58975 0.79824 0.12249 -0.76748 0.63009 0.11819 -0.78791 0.60683 0.10463 -0.66255 0.74185 0.10335 -0.58579 0.80648 0.08025 -0.68882 0.72016 0.08305 -0.50811 0.85814 0.07369 -0.38872 0.91905 0.06515 -0.60457 0.79365 0.06788 -0.49176 0.86856 0.06141 -0.35638 0.93105 0.07835 -0.68723 0.72339 0.06656 -0.81428 0.57815 0.05191 -0.59594 0.80296 0.01081 -0.74673 0.66509 0.00703 -0.34509 0.93836 -0.01968 -0.49928 0.86644 0.00184 -0.62775 0.77828 -0.01457 -0.46303 0.88590 -0.02797 -0.34041 0.94012 -0.01699 -0.82853 0.55376 0.08299 -0.87635 0.48096 -0.02605 -0.74688 0.66491 0.00808 -0.61810 0.78350 -0.06387 -0.80460 0.58891 -0.07620 -0.46761 0.88060 -0.07671 -0.27717 0.95443 -0.11060 -0.42857 0.89652 -0.11216 -0.64455 0.75899 -0.09212 -0.89314 0.44908 0.02497 -0.92670 0.36382 -0.09418 -0.80866 0.58586 -0.05320 -0.63949 0.76019 -0.11473 -0.84324 0.52174 -0.12935 -0.42979 0.89342 -0.13069 -0.18752 0.97526 -0.11710 -0.31463 0.93733 -0.14976 -0.65561 0.74237 -0.13807 -0.40225 0.90184 -0.15774 -0.94397 0.32865 -0.03017 -0.85042 0.51771 -0.09359 -0.95633 0.26423 -0.12493 -0.65566 0.74237 -0.13783 -0.86757 0.47493 -0.14754 -0.14656 0.97906 -0.14130 -0.21004 0.96322 -0.16760 -0.40190 0.90313 -0.15112 -0.66437 0.73138 -0.15394 -0.38910 0.90641 -0.16435 -0.97315 0.22354 -0.05475 -0.97487 0.20055 -0.09700 -0.87795 0.45904 -0.13597 -0.87338 0.47197 -0.12022 -0.14073 0.98352 -0.11355 -0.67173 0.73056 -0.12275 -0.98477 0.16873 -0.04195 -0.38816 0.90972 -0.14748 -0.14417 0.98329 -0.11115 -0.40878 0.90355 -0.12842 -0.68228 0.71609 -0.14731 -0.67028 0.71807 -0.18736 -0.19020 0.98174 -0.00233 -0.07328 0.99664 0.03649 -0.18521 0.98268 -0.00555 0.07048 0.99695 0.03347 0.18002 0.98361 -0.01052 0.17834 0.98390 -0.01153 0.20355 0.97354 0.10383 -0.20453 0.97237 0.11255 0.06958 0.99176 0.10759 -0.07243 0.99073 0.11489 -0.19623 0.97373 0.11551 -0.06407 0.99172 0.11127 0.20613 0.97314 0.10251 0.08178 0.99038 0.11160 0.21505 0.96888 0.12257 0.08164 0.98972 0.11746 -0.06386 0.99036 0.12292 -0.19714 0.97251 0.12394 -0.19850 0.97229 0.12345 -0.05736 0.99109 0.12018 0.23260 0.96602 0.11273 0.09021 0.98861 0.12044 0.21713 0.97179 0.09212 -0.19398 0.97855 0.06932 0.09195 0.99382 0.06219 -0.05856 0.99624 0.06389 -0.05245 0.99673 0.06144 -0.20065 0.97736 0.06717 0.09484 0.99348 0.06329 0.26082 0.96314 0.06586 0.20552 0.97852 0.01598 -0.18248 0.98245 -0.03874 0.09839 0.99400 -0.04784 -0.05509 0.99713 -0.05188 -0.04742 0.99739 -0.05446 -0.20086 0.97865 -0.04358 0.26749 0.96316 -0.02788 0.09327 0.99439 -0.04984 0.19850 0.97734 -0.07353 -0.15618 0.98019 -0.12183 0.09626 0.98851 -0.11651 -0.04980 0.99107 -0.12369 -0.03599 0.99128 -0.12678 -0.14862 0.98160 -0.11986 0.14399 0.98058 -0.13312 0.21395 0.97158 -0.10128 0.07304 0.98959 -0.12401 -0.11159 0.98321 -0.14441 0.13935 0.98044 -0.13899 0.07162 0.99149 -0.10868 -0.03387 0.99478 -0.09629 0.00962 0.99402 -0.10880 -0.02783 0.99389 -0.10680 0.03443 0.99328 -0.11050 -0.01814 0.99371 -0.11047 0.02223 0.99318 -0.11441 0.76708 0.63841 -0.06345 0.72544 0.68827 -0.00498 0.30890 0.95080 0.02362 0.83514 0.54897 0.03432 0.72526 0.68565 0.06231 0.82020 0.56902 0.05908 0.72415 0.68671 0.06354 0.60756 0.79129 0.06875 0.34302 0.93650 0.07278 0.47298 0.87876 0.06390 0.61061 0.78919 0.06581 0.48471 0.87160 0.07328 0.72364 0.68407 0.09166 0.82253 0.56124 0.09192 0.71291 0.69370 0.10266 0.61072 0.78474 0.10588 0.48311 0.86987 0.09962 0.31995 0.94054 0.11412 0.61155 0.78419 0.10512 0.50061 0.85828 0.11291 0.35851 0.92917 0.09004 0.81707 0.57022 0.08507 0.71282 0.69283 0.10894 0.80209 0.58681 0.11095 0.69924 0.70444 0.12177 0.61189 0.78125 0.12345 0.36156 0.92374 0.12645 0.50050 0.85817 0.11420 0.51954 0.84480 0.12805 0.61362 0.78013 0.12198 0.38034 0.91836 0.10938 0.80324 0.58413 0.11663 0.69919 0.70569 0.11458 0.61360 0.78018 0.12173 0.69199 0.71170 0.12100 0.52138 0.84620 0.11005 0.38696 0.91454 0.11780 0.53560 0.83585 0.12032 0.61953 0.77621 0.11693 0.79482 0.59711 0.10825 0.69151 0.71401 0.10954 0.79437 0.59751 0.10931 0.70174 0.70532 0.10041 0.61785 0.77982 0.10065 0.53892 0.83760 0.08937 0.40328 0.91078 0.08857 0.53956 0.83714 0.08985 0.63090 0.77059 0.09031 0.39986 0.91211 0.09040 0.78542 0.61244 0.08963 0.70120 0.70680 0.09352 0.82094 0.55921 0.11547 0.73516 0.67524 0.05998 0.62616 0.77739 0.05985 0.39770 0.91679 0.03657 0.54333 0.83792 0.05181 0.52248 0.85197 0.03400 0.64629 0.76188 0.04296 0.39538 0.91773 0.03811 0.73553 0.67452 0.06334 0.82782 0.55858 0.05207 0.78437 0.62028 0.00284 0.63807 0.76997 0.00160 0.52543 0.85082 -0.00505 0.35396 0.93430 -0.04231 0.48512 0.87331 -0.04459 0.65879 0.75209 -0.01890 0.86262 0.49633 0.09772 0.89950 0.43693 0.00003 0.78701 0.61653 0.02231 0.82761 0.55937 -0.04661 0.65156 0.75687 -0.05118 0.48602 0.87152 -0.06506 0.34986 0.93602 -0.03830 0.28709 0.95058 -0.11821 0.44439 0.88903 -0.11017 0.66556 0.74315 -0.06905 0.83220 0.55424 -0.01632 0.95307 0.30015 0.03959 0.89121 0.45274 -0.02764 0.85760 0.50858 -0.07656 0.66141 0.74501 -0.08656 0.27767 0.95538 -0.10076 0.21481 0.96240 -0.16626 0.44440 0.88902 -0.11024 0.66964 0.73587 -0.10038 0.41286 0.89892 -0.14658 0.95305 0.30225 0.01841 0.97662 0.20684 -0.05862 0.86294 0.50345 -0.04334 0.87706 0.47225 -0.08801 0.66864 0.73621 -0.10446 0.41266 0.90154 -0.13011 0.20498 0.97043 -0.12751 0.15560 0.97267 -0.17235 0.39452 0.90629 -0.15161 0.67313 0.73069 -0.11397 0.88256 0.46708 -0.05410 0.98737 0.15822 0.00791 0.97680 0.20901 -0.04674 0.67546 0.72995 -0.10459 0.88991 0.44878 -0.08166 0.14727 0.98306 -0.10906 0.12275 0.98401 -0.12905 0.39401 0.91117 -0.12055 0.67851 0.72599 -0.11208 0.39136 0.91190 -0.12361 0.67690 0.72654 -0.11807 0.99982 -0.00000 0.01916 0.99982 0.00000 0.01916 0.97513 0.21496 0.05390 0.94005 0.34101 0.00346 0.91222 0.40785 0.03889 0.90555 0.41517 0.08727 0.97237 0.21381 0.09374 0.99591 0.00000 0.09036 0.99528 -0.01118 0.09639 0.97380 0.20853 0.09075 0.90693 0.41161 0.08971 0.90133 0.41858 0.11136 0.97101 0.20716 0.11924 0.99313 -0.01110 0.11647 0.99259 -0.01807 0.12012 0.97296 0.20013 0.11528 0.90348 0.41264 0.11598 0.90609 0.40879 0.10909 0.97184 0.19947 0.12548 0.99252 -0.01807 0.12075 0.99237 -0.01995 0.12169 0.97791 0.17618 0.11249 0.91184 0.39071 0.12604 0.93471 0.34689 0.07742 0.99350 -0.02004 0.11204 0.97742 0.17578 0.11727 0.99384 -0.01487 0.10981 0.98959 0.11478 0.08680 0.93026 0.36352 0.04963 0.97095 0.21812 0.09841 0.97914 0.20299 0.00898 0.99463 -0.01497 0.10236 0.98622 0.11081 0.12284 0.99241 0.09359 0.07981 0.99756 0.01285 0.06868 0.99951 0.02951 0.01072 0.98551 0.00000 -0.16960 0.92804 0.33665 -0.15942 0.98551 -0.00000 -0.16960 0.76218 0.63421 -0.12985 0.92820 0.33635 -0.15910 0.49458 0.86479 -0.08680 0.75944 0.63670 -0.13368 0.17832 0.98382 -0.01744 0.50219 0.86149 -0.07512 0.86602 -0.00000 -0.50000 0.86602 -0.00000 -0.50000 0.81549 0.33661 -0.47083 0.66796 0.63648 -0.38565 0.81548 0.33661 -0.47083 0.66756 0.63673 -0.38593 0.43801 0.86257 -0.25322 0.15254 0.98435 -0.08829 0.43779 0.86263 -0.25339 0.64280 -0.00000 -0.76603 0.64280 0.00000 -0.76603 0.60529 0.33661 -0.72133 0.60529 0.33661 -0.72133 0.49578 0.63649 -0.59083 0.49535 0.63672 -0.59094 0.32501 0.86257 -0.38773 0.32481 0.86262 -0.38779 0.11317 0.98435 -0.13512 0.34201 0.00000 -0.93970 0.34201 -0.00000 -0.93970 0.32205 0.33661 -0.88486 0.32205 0.33662 -0.88486 0.26378 0.63651 -0.72476 0.17282 0.86257 -0.47550 0.26340 0.63671 -0.72472 0.06015 0.98435 -0.16567 0.17265 0.86261 -0.47549 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.33662 -0.94164 0.00000 0.33661 -0.94164 0.00000 0.63652 -0.77126 -0.00027 0.63668 -0.77113 -0.00018 0.86257 -0.50593 -0.00033 0.86261 -0.50586 -0.00011 0.98435 -0.17625 -0.34201 0.00000 -0.93970 -0.34201 0.00000 -0.93970 -0.32205 0.33661 -0.88486 -0.26377 0.63654 -0.72474 -0.32205 0.33661 -0.88486 -0.26394 0.63667 -0.72456 -0.17316 0.86258 -0.47536 -0.06036 0.98435 -0.16559 -0.17325 0.86261 -0.47528 -0.64280 0.00000 -0.76603 -0.64280 0.00000 -0.76603 -0.60529 0.33661 -0.72133 -0.49575 0.63655 -0.59079 -0.60529 0.33661 -0.72133 -0.49581 0.63663 -0.59066 -0.32527 0.86259 -0.38749 -0.32530 0.86260 -0.38742 -0.11334 0.98435 -0.13498 -0.86602 0.00000 -0.50000 -0.81549 0.33661 -0.47083 -0.86602 0.00000 -0.50000 -0.66790 0.63655 -0.38562 -0.81548 0.33661 -0.47083 -0.66791 0.63662 -0.38550 -0.43816 0.86259 -0.25289 -0.43817 0.86260 -0.25285 -0.15265 0.98435 -0.08809 -0.98584 0.00000 -0.16772 -0.98584 0.00000 -0.16772 -0.75928 0.63665 -0.13476 -0.49635 0.86654 -0.05245 -0.18521 0.98270 0.00226 -0.75499 0.64466 -0.12002 -0.50205 0.86153 -0.07555 -0.98281 0.00156 -0.18463 -0.98159 0.00743 -0.19084 -0.98377 0.00000 -0.17946 -0.99969 -0.00000 0.02491 -0.99969 0.00000 0.02491 -0.97007 0.00000 0.24281 -0.97007 -0.00000 0.24281 -0.89358 -0.00000 0.44891 -0.89358 -0.00000 0.44891 -0.77327 -0.00000 0.63408 -0.77327 -0.00000 0.63408 -0.61624 -0.00000 0.78756 -0.61624 -0.00000 0.78756 -0.42875 -0.00000 0.90343 -0.42874 -0.00000 0.90343 -0.22038 -0.00000 0.97541 -0.22038 -0.00000 0.97541 -0.00210 -0.00000 1.00000 -0.00210 -0.00000 1.00000 0.21685 -0.00000 0.97620 0.21685 -0.00000 0.97620 0.42527 -0.00000 0.90507 0.42527 -0.00000 0.90507 0.61295 -0.00000 0.79012 0.61295 0.00000 0.79012 0.77101 0.00000 0.63682 0.77102 -0.00000 0.63682 0.89165 0.00000 0.45273 0.89165 -0.00000 0.45273 0.96910 -0.00000 0.24668 0.96910 -0.00000 0.24668 0.99959 -0.00000 0.02862 0.99959 -0.00000 0.02862 0.98458 0.00000 -0.17493 0.98382 0.00125 -0.17918 0.98323 0.00267 -0.18236 0.98223 0.00774 -0.18752 0.97049 0.10362 -0.21775 -0.96703 0.11833 -0.22548 -0.94612 0.27353 -0.17330 -0.81205 0.58264 -0.03333 -0.98803 0.15231 0.02462 -0.90531 0.35925 0.22660 -0.95379 0.23541 0.18672 -0.86306 0.47728 0.16529 -0.85829 0.48487 0.16803 -0.74132 0.58379 0.33111 -0.88044 0.17084 0.44231 -0.66848 0.54248 0.50877 -0.74356 0.45136 0.49335 -0.78755 0.32668 0.52253 -0.76020 0.18305 0.62336 -0.52676 0.56208 0.63764 -0.60294 0.20667 0.77055 -0.52913 0.32159 0.78524 -0.50053 0.44467 0.74280 -0.36223 0.57679 0.73219 -0.42339 0.15752 0.89215 -0.21293 0.25778 0.94245 -0.18978 0.30012 0.93483 -0.20391 0.44397 0.87253 -0.17194 0.50317 0.84691 -0.00208 0.14945 0.98877 0.00107 0.58598 0.81033 0.20530 0.32205 0.92419 0.18407 0.26251 0.94721 0.19566 0.52283 0.82968 0.16931 0.46073 0.87124 0.41985 0.15917 0.89353 0.36533 0.57289 0.73371 0.56280 0.39615 0.72548 0.53979 0.20603 0.81619 0.49427 0.44401 0.74736 0.52581 0.56716 0.63392 0.75755 0.18606 0.62570 0.72890 0.40527 0.55178 0.70606 0.52343 0.47697 0.78342 0.32584 0.52923 0.87889 0.16852 0.44626 0.74119 0.58526 0.32879 0.85161 0.49875 0.16127 0.86295 0.47345 0.17653 0.94327 0.22931 0.24011 0.93036 0.31338 0.19032 0.98805 0.15153 0.02829 0.81357 0.58039 -0.03525 0.88222 0.43491 -0.18041 0.94711 0.27576 -0.16416 0.81130 0.52202 -0.26323 -0.66164 0.71281 -0.23266 -0.68713 0.69922 -0.19733 -0.69930 0.71086 -0.07523 -0.71425 0.69928 -0.02932 -0.69525 0.71292 0.09154 -0.70041 0.70102 0.13414 -0.65047 0.71014 0.26942 -0.64881 0.70360 0.28980 -0.56351 0.70605 0.42888 -0.56099 0.70709 0.43047 -0.45311 0.70274 0.54849 -0.42808 0.71099 0.55788 -0.31647 0.70044 0.63971 -0.26816 0.71343 0.64739 -0.16274 0.69898 0.69638 -0.09129 0.71479 0.69336 0.00095 0.69850 0.71561 0.09129 0.71478 0.69337 0.16416 0.69891 0.69612 0.26809 0.71360 0.64722 0.31819 0.70029 0.63902 0.42796 0.71119 0.55773 0.45431 0.70258 0.54771 0.56358 0.70736 0.42664 0.56221 0.70556 0.43140 0.64937 0.70381 0.28805 0.65079 0.70980 0.26955 0.70058 0.70113 0.13267 0.69542 0.71275 0.09156 0.71409 0.69937 -0.03094 0.69915 0.71091 -0.07607 0.68564 0.69818 -0.20599 0.66836 0.70886 -0.22541 0.53660 0.84181 -0.05838 0.21287 0.97660 -0.03061 0.21611 0.97593 -0.02917 0.50647 0.85791 -0.08650 0.53558 0.82495 -0.18059 0.17249 0.98186 -0.07876 0.17261 0.98174 -0.07995 0.47616 0.83648 -0.27126 0.10940 0.98947 -0.09480 0.08418 0.98780 -0.13101 0.08169 0.98354 -0.16117 0.05378 0.98162 -0.18311 -0.00960 0.99694 -0.07762 -0.11065 0.97883 -0.17220 -0.16155 0.97786 -0.13303 -0.15943 0.97750 -0.13814 -0.17754 0.97553 -0.12971 -0.17247 0.98186 -0.07875 -0.54893 0.80453 -0.22674 -0.49438 0.86762 -0.05319 -0.53522 0.83965 -0.09230 -0.21436 0.97633 -0.02886 -0.21610 0.97588 -0.03108 -0.01071 0.99716 -0.07451 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.53617 0.84115 0.07059 -0.49467 0.86319 0.10102 -0.22947 0.97276 0.03299 -0.21605 0.97566 0.03747 -0.52918 0.81972 0.21918 -0.17211 0.98194 0.07861 -0.15313 0.97926 0.13268 -0.16699 0.97692 0.13318 -0.42461 0.84472 0.32582 -0.40904 0.85222 0.32620 -0.35041 0.81772 0.45667 -0.10438 0.98119 0.16241 -0.19285 0.86375 0.46556 -0.23759 0.83675 0.49335 -0.09429 0.97610 0.19580 -0.05367 0.98169 0.18276 -0.07403 0.82361 0.56230 -0.00000 0.86006 0.51020 -0.00000 0.97770 0.21000 0.00000 0.97770 0.21000 0.07403 0.82361 0.56230 0.05367 0.98169 0.18276 0.20977 0.83638 0.50643 0.22385 0.85664 0.46482 0.09429 0.97610 0.19580 0.10438 0.98119 0.16241 0.35041 0.81772 0.45666 0.16593 0.97560 0.14378 0.16059 0.97868 0.12807 0.41282 0.85395 0.31677 0.41722 0.84571 0.33273 0.17211 0.98194 0.07861 0.52918 0.81971 0.21918 0.48206 0.87384 0.06347 0.53424 0.83813 0.11015 0.22217 0.97423 0.03886 0.21610 0.97588 0.03106 0.81364 0.55878 -0.16051 0.85073 0.46784 -0.23954 0.64212 0.71513 -0.27617 0.65774 0.73793 -0.15112 0.47006 0.84484 -0.25553 0.45904 0.83586 -0.30104 0.11587 0.99032 -0.07642 0.39198 0.90754 -0.15075 -0.34968 0.91095 -0.21885 -0.41281 0.87590 -0.24976 -0.59330 0.78495 -0.17847 -0.11267 0.98835 -0.10230 -0.41718 0.87682 -0.23907 -0.15198 0.97322 -0.17246 -0.67118 0.71751 -0.18626 -0.97021 0.12813 -0.20560 -0.97355 0.12000 -0.19444 -0.81799 0.51345 -0.25934 -0.85665 0.46863 -0.21574 -0.98905 0.01086 -0.14718 0.99660 0.00256 -0.08240 0.99512 0.02698 -0.09487 0.99559 0.00524 -0.09365 0.99000 0.05900 -0.12817 0.99193 0.01270 -0.12613 0.98012 0.10552 -0.16803 0.97810 0.12744 -0.16458 0.02348 0.99271 -0.11822 0.02315 0.99272 -0.11824 0.01140 0.99185 -0.12690 -0.02193 0.99183 -0.12569 -0.01668 0.99127 -0.13081 -0.11535 0.98039 -0.15976 -0.87838 0.44072 -0.18497 -0.82070 0.51558 -0.24624 -0.92751 0.33656 -0.16267 -0.89470 0.38898 -0.21957 -0.95697 0.24041 -0.16253 0.49539 0.86620 -0.06547 0.60747 0.79420 0.01527 0.47459 0.87935 -0.03890 0.47459 -0.87935 -0.03890 0.60747 -0.79420 0.01527 0.49539 -0.86620 -0.06547 -0.95697 -0.24041 -0.16253 -0.89470 -0.38898 -0.21957 -0.92751 -0.33656 -0.16267 -0.82070 -0.51558 -0.24624 -0.87838 -0.44072 -0.18497 -0.11535 -0.98039 -0.15976 -0.01668 -0.99127 -0.13081 -0.02193 -0.99183 -0.12569 0.01140 -0.99185 -0.12690 0.02315 -0.99272 -0.11824 0.02349 -0.99271 -0.11822 0.97810 -0.12744 -0.16458 0.98012 -0.10552 -0.16803 0.99193 -0.01270 -0.12613 0.99000 -0.05900 -0.12817 0.99559 -0.00524 -0.09365 0.99511 -0.02729 -0.09488 0.99659 -0.00269 -0.08245 -0.98905 -0.01086 -0.14718 -0.85665 -0.46863 -0.21574 -0.81799 -0.51345 -0.25934 -0.97355 -0.12000 -0.19444 -0.97021 -0.12813 -0.20560 -0.67119 -0.71751 -0.18626 -0.15198 -0.97322 -0.17246 -0.41717 -0.87682 -0.23907 -0.11267 -0.98835 -0.10230 -0.59330 -0.78495 -0.17847 -0.41281 -0.87590 -0.24976 -0.34967 -0.91095 -0.21885 0.39198 -0.90754 -0.15075 0.11587 -0.99032 -0.07642 0.45904 -0.83586 -0.30104 0.47006 -0.84484 -0.25553 0.65774 -0.73793 -0.15112 0.64212 -0.71513 -0.27616 0.85073 -0.46784 -0.23954 0.81364 -0.55877 -0.16052 0.21610 -0.97588 0.03106 0.22217 -0.97423 0.03886 0.53424 -0.83813 0.11015 0.48206 -0.87384 0.06347 0.52918 -0.81972 0.21918 0.17211 -0.98194 0.07861 0.41722 -0.84571 0.33273 0.41282 -0.85395 0.31677 0.16059 -0.97868 0.12807 0.16593 -0.97560 0.14378 0.35041 -0.81772 0.45666 0.10438 -0.98119 0.16240 0.09430 -0.97610 0.19580 0.22385 -0.85664 0.46482 0.20977 -0.83638 0.50643 0.05367 -0.98169 0.18276 0.07403 -0.82361 0.56230 0.00000 -0.97770 0.21000 0.00000 -0.97770 0.21000 0.00000 -0.86006 0.51020 -0.07403 -0.82361 0.56230 -0.05367 -0.98169 0.18276 -0.09430 -0.97610 0.19580 -0.23759 -0.83675 0.49335 -0.19284 -0.86375 0.46556 -0.10438 -0.98119 0.16241 -0.35041 -0.81772 0.45666 -0.40904 -0.85222 0.32620 -0.42461 -0.84472 0.32582 -0.16700 -0.97692 0.13318 -0.15313 -0.97926 0.13269 -0.17211 -0.98194 0.07861 -0.52917 -0.81972 0.21918 -0.21605 -0.97566 0.03747 -0.22947 -0.97276 0.03299 -0.49466 -0.86319 0.10102 -0.53617 -0.84115 0.07059 0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.01071 -0.99716 -0.07451 -0.21610 -0.97588 -0.03108 -0.21436 -0.97633 -0.02886 -0.53522 -0.83965 -0.09230 -0.49438 -0.86762 -0.05319 -0.54893 -0.80453 -0.22674 -0.17247 -0.98186 -0.07875 -0.17754 -0.97553 -0.12971 -0.15943 -0.97750 -0.13815 -0.16155 -0.97786 -0.13303 -0.11065 -0.97883 -0.17220 -0.00960 -0.99694 -0.07762 0.05378 -0.98162 -0.18311 0.08169 -0.98354 -0.16117 0.08418 -0.98780 -0.13101 0.10940 -0.98947 -0.09480 0.47616 -0.83648 -0.27126 0.17261 -0.98174 -0.07995 0.17249 -0.98186 -0.07876 0.53559 -0.82495 -0.18059 0.50647 -0.85791 -0.08650 0.21611 -0.97593 -0.02917 0.21287 -0.97660 -0.03061 0.53660 -0.84181 -0.05838 0.66836 -0.70886 -0.22541 0.68564 -0.69818 -0.20599 0.69915 -0.71091 -0.07607 0.71409 -0.69937 -0.03094 0.69542 -0.71275 0.09156 0.70058 -0.70113 0.13266 0.65079 -0.70980 0.26955 0.64937 -0.70381 0.28805 0.56221 -0.70555 0.43140 0.56358 -0.70736 0.42664 0.45431 -0.70258 0.54771 0.42796 -0.71119 0.55773 0.31819 -0.70029 0.63902 0.26809 -0.71360 0.64722 0.16416 -0.69891 0.69612 0.09129 -0.71478 0.69337 0.00095 -0.69850 0.71561 -0.09129 -0.71479 0.69336 -0.16274 -0.69898 0.69638 -0.26816 -0.71343 0.64739 -0.31648 -0.70044 0.63971 -0.42808 -0.71099 0.55788 -0.45311 -0.70274 0.54849 -0.56099 -0.70709 0.43047 -0.56351 -0.70605 0.42888 -0.64881 -0.70360 0.28980 -0.65047 -0.71014 0.26942 -0.70041 -0.70102 0.13414 -0.69525 -0.71292 0.09154 -0.71425 -0.69928 -0.02932 -0.69930 -0.71086 -0.07523 -0.68713 -0.69922 -0.19733 -0.66164 -0.71281 -0.23266 0.81130 -0.52202 -0.26323 0.94711 -0.27576 -0.16416 0.88222 -0.43490 -0.18041 0.81357 -0.58039 -0.03525 0.98805 -0.15153 0.02829 0.93036 -0.31338 0.19032 0.94327 -0.22931 0.24011 0.86295 -0.47345 0.17653 0.85161 -0.49875 0.16126 0.74119 -0.58526 0.32879 0.87889 -0.16852 0.44626 0.78342 -0.32584 0.52923 0.70606 -0.52343 0.47697 0.72890 -0.40527 0.55178 0.75755 -0.18606 0.62570 0.52581 -0.56716 0.63392 0.49427 -0.44401 0.74736 0.53979 -0.20603 0.81619 0.56280 -0.39615 0.72548 0.36533 -0.57289 0.73371 0.41985 -0.15917 0.89353 0.16931 -0.46073 0.87124 0.19566 -0.52283 0.82968 0.18407 -0.26251 0.94721 0.20530 -0.32205 0.92419 0.00107 -0.58598 0.81033 -0.00208 -0.14945 0.98877 -0.17194 -0.50317 0.84691 -0.20391 -0.44397 0.87253 -0.18978 -0.30012 0.93483 -0.21293 -0.25778 0.94245 -0.42339 -0.15752 0.89215 -0.36223 -0.57679 0.73219 -0.50053 -0.44467 0.74280 -0.52913 -0.32159 0.78524 -0.60294 -0.20667 0.77055 -0.52676 -0.56208 0.63764 -0.76020 -0.18305 0.62336 -0.78755 -0.32668 0.52254 -0.74356 -0.45136 0.49335 -0.66848 -0.54248 0.50877 -0.88044 -0.17084 0.44231 -0.74131 -0.58380 0.33111 -0.85829 -0.48487 0.16803 -0.86306 -0.47729 0.16529 -0.95379 -0.23540 0.18672 -0.90531 -0.35925 0.22660 -0.98803 -0.15231 0.02462 -0.81205 -0.58264 -0.03333 -0.94612 -0.27353 -0.17330 -0.96703 -0.11833 -0.22549 0.97049 -0.10362 -0.21775 0.98223 -0.00774 -0.18752 0.98323 -0.00267 -0.18236 0.98379 -0.00131 -0.17931 -0.50205 -0.86153 -0.07555 -0.75499 -0.64466 -0.12002 -0.18521 -0.98270 0.00226 -0.49635 -0.86654 -0.05245 -0.75928 -0.63665 -0.13476 -0.15265 -0.98435 -0.08809 -0.43817 -0.86260 -0.25285 -0.43816 -0.86259 -0.25289 -0.66791 -0.63662 -0.38550 -0.81548 -0.33661 -0.47083 -0.66790 -0.63655 -0.38562 -0.81549 -0.33661 -0.47083 -0.11334 -0.98435 -0.13498 -0.32530 -0.86260 -0.38742 -0.32527 -0.86259 -0.38749 -0.49581 -0.63663 -0.59066 -0.60529 -0.33661 -0.72133 -0.49575 -0.63655 -0.59079 -0.60529 -0.33661 -0.72133 -0.17325 -0.86261 -0.47528 -0.06036 -0.98435 -0.16559 -0.17316 -0.86258 -0.47536 -0.26394 -0.63667 -0.72456 -0.32205 -0.33661 -0.88486 -0.26377 -0.63654 -0.72474 -0.32205 -0.33661 -0.88486 -0.00011 -0.98435 -0.17625 -0.00033 -0.86261 -0.50587 -0.00018 -0.86257 -0.50593 -0.00027 -0.63668 -0.77113 0.00000 -0.63652 -0.77126 0.00000 -0.33661 -0.94164 0.00000 -0.33661 -0.94164 0.17265 -0.86261 -0.47549 0.06015 -0.98435 -0.16567 0.26340 -0.63671 -0.72472 0.17282 -0.86257 -0.47550 0.26378 -0.63651 -0.72476 0.32204 -0.33661 -0.88486 0.32205 -0.33661 -0.88486 0.11317 -0.98435 -0.13512 0.32481 -0.86262 -0.38779 0.32501 -0.86257 -0.38773 0.49535 -0.63672 -0.59094 0.49578 -0.63649 -0.59083 0.60529 -0.33661 -0.72133 0.60529 -0.33661 -0.72133 0.43779 -0.86263 -0.25339 0.15254 -0.98435 -0.08829 0.43801 -0.86257 -0.25322 0.66756 -0.63673 -0.38593 0.81548 -0.33661 -0.47083 0.66796 -0.63648 -0.38565 0.81549 -0.33661 -0.47083 0.50219 -0.86149 -0.07512 0.17832 -0.98382 -0.01744 0.75944 -0.63670 -0.13368 0.49458 -0.86479 -0.08680 0.92820 -0.33635 -0.15910 0.76218 -0.63421 -0.12985 0.92804 -0.33665 -0.15942 0.99951 -0.02951 0.01072 0.99755 -0.01300 0.06870 0.99241 -0.09359 0.07981 0.98719 -0.10569 0.11953 0.97914 -0.20299 0.00898 0.97095 -0.21812 0.09841 0.93026 -0.36352 0.04963 0.99028 -0.10923 0.08615 0.97580 -0.18263 0.12026 0.93471 -0.34689 0.07742 0.91184 -0.39071 0.12605 0.97655 -0.18326 0.11302 0.96968 -0.20955 0.12572 0.90609 -0.40879 0.10909 0.90348 -0.41264 0.11598 0.97081 -0.21024 0.11544 0.97075 -0.21046 0.11555 0.90133 -0.41858 0.11136 0.90693 -0.41161 0.08971 0.97313 -0.21162 0.09076 0.97252 -0.21387 0.09195 0.90555 -0.41517 0.08727 0.91222 -0.40785 0.03889 0.94005 -0.34101 0.00346 0.97513 -0.21496 0.05390 0.67690 -0.72654 -0.11807 0.39136 -0.91190 -0.12361 0.67851 -0.72599 -0.11208 0.39401 -0.91117 -0.12055 0.12275 -0.98401 -0.12905 0.14727 -0.98306 -0.10906 0.88991 -0.44878 -0.08166 0.67546 -0.72994 -0.10459 0.97680 -0.20901 -0.04674 0.98737 -0.15822 0.00791 0.88256 -0.46708 -0.05410 0.67313 -0.73069 -0.11397 0.39452 -0.90629 -0.15161 0.15560 -0.97267 -0.17235 0.20498 -0.97043 -0.12751 0.41266 -0.90154 -0.13011 0.66864 -0.73621 -0.10446 0.87706 -0.47225 -0.08801 0.86294 -0.50345 -0.04334 0.97662 -0.20684 -0.05862 0.95305 -0.30225 0.01841 0.41286 -0.89892 -0.14658 0.66964 -0.73587 -0.10038 0.44440 -0.88902 -0.11024 0.21481 -0.96240 -0.16626 0.27767 -0.95538 -0.10076 0.66141 -0.74501 -0.08657 0.85760 -0.50858 -0.07656 0.89121 -0.45274 -0.02764 0.95307 -0.30015 0.03959 0.83220 -0.55424 -0.01632 0.66556 -0.74314 -0.06905 0.44439 -0.88903 -0.11017 0.28709 -0.95058 -0.11821 0.34986 -0.93602 -0.03830 0.48602 -0.87152 -0.06506 0.65156 -0.75687 -0.05118 0.82761 -0.55937 -0.04661 0.78701 -0.61653 0.02231 0.89950 -0.43693 0.00003 0.86262 -0.49633 0.09772 0.65879 -0.75209 -0.01890 0.48512 -0.87331 -0.04459 0.35396 -0.93430 -0.04231 0.52543 -0.85082 -0.00505 0.63807 -0.76997 0.00160 0.78437 -0.62028 0.00284 0.82782 -0.55858 0.05207 0.73553 -0.67452 0.06334 0.39538 -0.91773 0.03810 0.64629 -0.76188 0.04296 0.52248 -0.85197 0.03400 0.54333 -0.83792 0.05181 0.39770 -0.91679 0.03657 0.62616 -0.77739 0.05985 0.73516 -0.67524 0.05998 0.82094 -0.55921 0.11547 0.70120 -0.70680 0.09352 0.78542 -0.61244 0.08963 0.39986 -0.91211 0.09040 0.63090 -0.77059 0.09031 0.53956 -0.83714 0.08985 0.40328 -0.91078 0.08857 0.53892 -0.83760 0.08937 0.61786 -0.77982 0.10065 0.70174 -0.70532 0.10041 0.79437 -0.59751 0.10931 0.69151 -0.71401 0.10954 0.79482 -0.59711 0.10825 0.61953 -0.77621 0.11693 0.53560 -0.83585 0.12032 0.38696 -0.91454 0.11780 0.52138 -0.84620 0.11005 0.69199 -0.71170 0.12100 0.61360 -0.78018 0.12173 0.69919 -0.70570 0.11458 0.80324 -0.58413 0.11663 0.38034 -0.91836 0.10938 0.61362 -0.78013 0.12198 0.51954 -0.84480 0.12805 0.50050 -0.85817 0.11420 0.36156 -0.92374 0.12645 0.61190 -0.78124 0.12345 0.69924 -0.70444 0.12177 0.80209 -0.58681 0.11095 0.71282 -0.69283 0.10894 0.81707 -0.57022 0.08507 0.35851 -0.92917 0.09004 0.50061 -0.85828 0.11291 0.61155 -0.78419 0.10512 0.31995 -0.94054 0.11412 0.48311 -0.86987 0.09962 0.61072 -0.78474 0.10588 0.71291 -0.69370 0.10266 0.82253 -0.56124 0.09192 0.72364 -0.68407 0.09166 0.48471 -0.87160 0.07328 0.61061 -0.78919 0.06581 0.47298 -0.87876 0.06390 0.34302 -0.93650 0.07278 0.60756 -0.79129 0.06874 0.72415 -0.68671 0.06354 0.82020 -0.56902 0.05908 0.72526 -0.68565 0.06230 0.83514 -0.54897 0.03432 0.30890 -0.95080 0.02362 0.72544 -0.68826 -0.00498 0.76708 -0.63841 -0.06345 0.02223 -0.99318 -0.11441 -0.01814 -0.99371 -0.11047 0.03443 -0.99328 -0.11050 -0.02783 -0.99389 -0.10680 0.00962 -0.99402 -0.10880 -0.03387 -0.99478 -0.09629 0.07162 -0.99149 -0.10868 0.13935 -0.98044 -0.13899 -0.11159 -0.98321 -0.14441 0.07304 -0.98959 -0.12401 0.21395 -0.97158 -0.10128 0.14399 -0.98058 -0.13312 -0.14862 -0.98160 -0.11986 -0.03599 -0.99128 -0.12678 -0.04980 -0.99107 -0.12369 0.09626 -0.98851 -0.11651 -0.15618 -0.98019 -0.12183 0.19850 -0.97734 -0.07353 0.09327 -0.99439 -0.04984 0.26749 -0.96316 -0.02788 -0.20087 -0.97865 -0.04358 -0.04742 -0.99739 -0.05446 -0.05509 -0.99713 -0.05188 0.09839 -0.99400 -0.04784 -0.18248 -0.98245 -0.03874 0.20552 -0.97852 0.01597 0.26082 -0.96314 0.06586 0.09484 -0.99348 0.06329 -0.20065 -0.97736 0.06717 -0.05245 -0.99673 0.06144 -0.05856 -0.99624 0.06389 0.09195 -0.99382 0.06219 -0.19398 -0.97855 0.06932 0.21713 -0.97179 0.09212 0.09022 -0.98861 0.12044 0.23259 -0.96602 0.11273 -0.05736 -0.99109 0.12018 -0.19850 -0.97229 0.12345 -0.19714 -0.97251 0.12394 -0.06386 -0.99036 0.12292 0.08164 -0.98972 0.11745 0.21505 -0.96888 0.12256 0.08178 -0.99038 0.11160 0.20613 -0.97314 0.10250 -0.06407 -0.99172 0.11127 -0.19623 -0.97373 0.11551 -0.07243 -0.99073 0.11489 0.06958 -0.99176 0.10759 -0.20453 -0.97237 0.11255 0.20355 -0.97354 0.10383 0.17834 -0.98390 -0.01153 0.18002 -0.98361 -0.01052 0.07048 -0.99695 0.03347 -0.18521 -0.98268 -0.00555 -0.07328 -0.99664 0.03649 -0.19020 -0.98174 -0.00233 -0.67028 -0.71807 -0.18736 -0.68228 -0.71609 -0.14731 -0.40878 -0.90355 -0.12842 -0.14417 -0.98329 -0.11115 -0.38816 -0.90972 -0.14748 -0.98477 -0.16873 -0.04195 -0.67173 -0.73056 -0.12275 -0.14073 -0.98352 -0.11355 -0.87338 -0.47197 -0.12022 -0.87795 -0.45904 -0.13597 -0.97487 -0.20055 -0.09700 -0.97315 -0.22355 -0.05475 -0.38910 -0.90641 -0.16435 -0.66437 -0.73138 -0.15394 -0.40190 -0.90313 -0.15112 -0.21004 -0.96322 -0.16760 -0.14657 -0.97906 -0.14130 -0.86757 -0.47493 -0.14754 -0.65566 -0.74237 -0.13783 -0.95633 -0.26423 -0.12493 -0.85042 -0.51771 -0.09359 -0.94397 -0.32865 -0.03017 -0.40225 -0.90184 -0.15774 -0.65561 -0.74237 -0.13807 -0.31463 -0.93733 -0.14976 -0.18752 -0.97525 -0.11711 -0.42979 -0.89342 -0.13069 -0.84324 -0.52174 -0.12935 -0.63949 -0.76019 -0.11473 -0.80866 -0.58586 -0.05320 -0.92670 -0.36382 -0.09418 -0.89314 -0.44909 0.02497 -0.64455 -0.75899 -0.09212 -0.42857 -0.89652 -0.11216 -0.27717 -0.95443 -0.11060 -0.46761 -0.88060 -0.07671 -0.80460 -0.58891 -0.07620 -0.61810 -0.78350 -0.06387 -0.74688 -0.66491 0.00808 -0.87635 -0.48097 -0.02605 -0.82853 -0.55376 0.08299 -0.34041 -0.94013 -0.01699 -0.46303 -0.88590 -0.02797 -0.62775 -0.77828 -0.01457 -0.49928 -0.86644 0.00184 -0.34509 -0.93836 -0.01968 -0.74673 -0.66509 0.00703 -0.59594 -0.80296 0.01081 -0.81428 -0.57815 0.05191 -0.68723 -0.72339 0.06656 -0.35638 -0.93105 0.07835 -0.49176 -0.86856 0.06141 -0.60457 -0.79365 0.06788 -0.38872 -0.91905 0.06515 -0.50811 -0.85814 0.07369 -0.68882 -0.72016 0.08305 -0.58579 -0.80648 0.08025 -0.66255 -0.74185 0.10335 -0.78791 -0.60683 0.10463 -0.76748 -0.63009 0.11818 -0.58975 -0.79824 0.12249 -0.50168 -0.85686 0.11877 -0.50110 -0.85726 0.11834 -0.35537 -0.92771 0.11432 -0.58747 -0.79970 0.12390 -0.66384 -0.73668 0.12890 -0.77086 -0.62291 0.13326 -0.67093 -0.73109 0.12396 -0.36416 -0.92284 0.12548 -0.49759 -0.85543 0.14368 -0.58832 -0.79513 0.14714 -0.48921 -0.86128 0.13739 -0.34847 -0.92739 0.13608 -0.59586 -0.79038 0.14231 -0.67103 -0.72634 0.14886 -0.77873 -0.61514 0.12322 -0.79949 -0.58245 0.14687 -0.69421 -0.70748 0.13245 -0.59586 -0.79039 0.14224 -0.48920 -0.86127 0.13750 -0.34903 -0.93002 0.11504 -0.48077 -0.86705 0.13075 -0.31946 -0.93891 0.12806 -0.60576 -0.78404 0.13542 -0.69385 -0.70563 0.14372 -0.71707 -0.68553 0.12589 -0.79844 -0.58607 0.13791 -0.60650 -0.78777 0.10763 -0.48346 -0.86963 0.10007 -0.34769 -0.93308 0.09203 -0.48080 -0.87136 0.09780 -0.81869 -0.56324 0.11184 -0.61399 -0.78268 0.10210 -0.71775 -0.68733 0.11142 -0.73035 -0.67561 0.10075 -0.81854 -0.56354 0.11144 -0.31376 -0.94890 0.03382 -0.83204 -0.54949 0.07596 -0.61532 -0.78735 0.03828 -0.49664 -0.86705 -0.03972 -0.48479 -0.87424 -0.02599 -0.73242 -0.68062 0.01788 -0.76038 -0.64925 -0.01717 -0.99897 -0.02277 -0.03915 -0.99986 -0.01475 0.00849 -0.98375 -0.17861 0.01813 -0.99685 0.01506 -0.07784 -0.98943 -0.13338 0.05683 -0.97592 -0.21175 -0.05236 -0.92437 -0.37496 0.07034 -0.97187 -0.23444 -0.02237 -0.99013 -0.13632 0.03244 -0.97395 -0.21417 0.07446 -0.92371 -0.37938 0.05321 -0.97228 -0.21198 0.09871 -0.89409 -0.43290 0.11490 -0.96519 -0.23621 0.11231 -0.89489 -0.43069 0.11693 -0.88674 -0.44327 0.13118 -0.96207 -0.23408 0.14010 -0.96356 -0.22934 0.13766 -0.88968 -0.43458 0.14006 -0.89990 -0.41813 0.12388 -0.96340 -0.22926 0.13894 -0.96794 -0.21402 0.13148 -0.90059 -0.41583 0.12656 -0.91393 -0.39734 0.08277 -0.91458 -0.39600 0.08208 -0.97224 -0.21562 0.09088 -0.96454 -0.24231 0.10462 -0.98159 -0.00743 -0.19084 -0.98281 -0.00152 -0.18459 -0.98795 -0.04629 -0.14768 -0.99234 -0.00253 -0.12354 -0.99420 -0.03119 -0.10292 -0.99389 0.00000 -0.11040 -0.99412 0.02896 -0.10430 -0.99299 0.00268 -0.11817 -0.98795 0.04626 -0.14768 + + + + + + + + + + + + + + +

631 0 0 0 632 0 1 1 0 1 631 1 2 2 0 2 1 2 3 3 2 3 1 3 3 4 4 4 5 4 2 5 3 5 5 5 6 6 4 6 3 6 631 7 625 7 1 7 1 8 7 8 3 8 7 9 1 9 625 9 8 10 3 10 7 10 3 11 8 11 6 11 9 12 6 12 8 12 625 13 622 13 7 13 7 14 10 14 8 14 10 15 7 15 622 15 11 16 8 16 10 16 8 17 11 17 9 17 12 18 9 18 11 18 622 19 619 19 10 19 13 20 10 20 619 20 10 21 13 21 11 21 11 22 14 22 12 22 14 23 11 23 13 23 15 24 12 24 14 24 619 25 616 25 13 25 13 26 16 26 14 26 16 27 13 27 616 27 17 28 14 28 16 28 17 29 18 29 15 29 14 30 17 30 15 30 19 31 18 31 17 31 616 32 20 32 16 32 21 33 16 33 20 33 16 34 21 34 17 34 23 35 22 35 19 35 17 36 23 36 19 36 17 37 21 37 23 37 24 38 22 38 23 38 25 39 5 39 26 39 27 40 25 40 26 40 30 41 28 41 29 41 25 42 30 42 29 42 30 43 25 43 27 43 5 44 4 44 26 44 31 45 29 45 28 45 32 46 26 46 4 46 26 47 32 47 27 47 33 48 27 48 32 48 27 49 33 49 30 49 4 50 6 50 32 50 34 51 28 51 30 51 28 52 34 52 31 52 30 53 35 53 34 53 35 54 30 54 33 54 36 55 32 55 6 55 32 56 36 56 33 56 37 57 33 57 36 57 33 58 37 58 35 58 34 59 38 59 31 59 38 60 34 60 35 60 39 61 31 61 38 61 35 62 40 62 38 62 40 63 35 63 37 63 36 64 41 64 37 64 41 65 36 65 6 65 6 66 9 66 41 66 42 67 37 67 41 67 37 68 42 68 40 68 38 69 43 69 39 69 43 70 38 70 40 70 44 71 40 71 42 71 40 72 44 72 43 72 45 73 39 73 43 73 41 74 46 74 42 74 46 75 41 75 9 75 47 76 42 76 46 76 42 77 47 77 44 77 43 78 48 78 45 78 48 79 43 79 44 79 44 80 49 80 48 80 49 81 44 81 47 81 46 82 9 82 12 82 50 83 46 83 12 83 46 84 50 84 47 84 47 85 51 85 49 85 51 86 47 86 50 86 52 87 48 87 49 87 48 88 52 88 45 88 53 89 49 89 51 89 49 90 53 90 52 90 54 91 45 91 52 91 50 92 55 92 51 92 55 93 50 93 12 93 51 94 56 94 53 94 56 95 51 95 55 95 52 96 57 96 54 96 57 97 52 97 53 97 58 98 53 98 56 98 53 99 58 99 57 99 59 100 54 100 57 100 55 101 12 101 15 101 60 102 55 102 15 102 55 103 60 103 56 103 56 104 61 104 58 104 61 105 56 105 60 105 62 106 57 106 58 106 57 107 62 107 59 107 58 108 63 108 62 108 63 109 58 109 61 109 15 110 18 110 60 110 64 111 60 111 18 111 60 112 64 112 61 112 61 113 65 113 63 113 65 114 61 114 64 114 66 115 62 115 63 115 66 116 67 116 59 116 62 117 66 117 59 117 68 118 63 118 65 118 63 119 68 119 66 119 18 120 19 120 64 120 64 121 69 121 65 121 69 122 64 122 19 122 65 123 70 123 68 123 70 124 65 124 69 124 71 125 72 125 67 125 66 126 71 126 67 126 71 127 66 127 68 127 73 128 68 128 70 128 68 129 73 129 71 129 19 130 22 130 69 130 74 131 69 131 22 131 74 132 75 132 70 132 69 133 74 133 70 133 76 134 72 134 71 134 70 135 75 135 73 135 22 136 24 136 74 136 71 137 73 137 77 137 71 138 77 138 76 138 78 139 77 139 73 139 78 140 73 140 75 140 79 141 78 141 75 141 83 142 29 142 31 142 83 143 81 143 82 143 29 144 83 144 82 144 84 145 82 145 81 145 84 146 85 146 86 146 84 147 86 147 82 147 87 148 85 148 84 148 31 149 39 149 83 149 81 150 88 150 84 150 88 151 81 151 83 151 89 152 83 152 39 152 83 153 89 153 88 153 84 154 90 154 87 154 90 155 84 155 88 155 91 156 87 156 90 156 88 157 92 157 90 157 92 158 88 158 89 158 89 159 39 159 45 159 93 160 89 160 45 160 89 161 93 161 92 161 90 162 94 162 91 162 94 163 90 163 92 163 95 164 91 164 94 164 45 165 54 165 93 165 92 166 96 166 94 166 96 167 92 167 93 167 93 168 97 168 96 168 97 169 93 169 54 169 98 170 94 170 96 170 94 171 98 171 95 171 99 172 95 172 98 172 54 173 59 173 97 173 96 174 100 174 98 174 100 175 96 175 97 175 97 176 101 176 100 176 101 177 97 177 59 177 98 178 102 178 99 178 102 179 98 179 100 179 103 180 99 180 102 180 59 181 67 181 101 181 100 182 104 182 102 182 104 183 100 183 101 183 101 184 105 184 104 184 105 185 101 185 67 185 106 186 107 186 103 186 102 187 106 187 103 187 106 188 102 188 104 188 67 189 72 189 105 189 108 190 107 190 106 190 104 191 109 191 106 191 109 192 104 192 105 192 110 193 109 193 105 193 110 194 105 194 72 194 106 195 109 195 108 195 72 196 76 196 110 196 111 197 108 197 109 197 113 198 114 198 112 198 115 199 113 199 112 199 86 200 85 200 116 200 118 201 114 201 113 201 119 202 113 202 115 202 113 203 119 203 118 203 115 204 120 204 119 204 120 205 115 205 117 205 121 206 116 206 85 206 116 207 121 207 117 207 117 208 122 208 120 208 122 209 117 209 121 209 123 210 119 210 120 210 119 211 123 211 118 211 120 212 124 212 123 212 124 213 120 213 122 213 121 214 125 214 122 214 125 215 121 215 85 215 122 216 126 216 124 216 126 217 122 217 125 217 85 218 87 218 125 218 127 219 118 219 123 219 128 220 123 220 124 220 123 221 128 221 127 221 124 222 129 222 128 222 129 223 124 223 126 223 130 224 125 224 87 224 125 225 130 225 126 225 131 226 126 226 130 226 126 227 131 227 129 227 87 228 91 228 130 228 128 229 132 229 127 229 132 230 128 230 129 230 133 231 129 231 131 231 129 232 133 232 132 232 130 233 134 233 131 233 134 234 130 234 91 234 135 235 131 235 134 235 131 236 135 236 133 236 136 237 127 237 132 237 137 238 132 238 133 238 132 239 137 239 136 239 133 240 138 240 137 240 138 241 133 241 135 241 134 242 139 242 135 242 139 243 134 243 91 243 140 244 135 244 139 244 135 245 140 245 138 245 91 246 95 246 139 246 137 247 141 247 136 247 141 248 137 248 138 248 142 249 136 249 141 249 138 250 143 250 141 250 143 251 138 251 140 251 144 252 139 252 95 252 139 253 144 253 140 253 145 254 140 254 144 254 140 255 145 255 143 255 95 256 99 256 144 256 146 257 141 257 143 257 141 258 146 258 142 258 143 259 147 259 146 259 147 260 143 260 145 260 144 261 148 261 145 261 148 262 144 262 99 262 149 263 145 263 148 263 145 264 149 264 147 264 150 265 142 265 146 265 146 266 151 266 150 266 151 267 146 267 147 267 147 268 152 268 151 268 152 269 147 269 149 269 148 270 153 270 149 270 148 271 99 271 103 271 153 272 148 272 103 272 154 273 149 273 153 273 149 274 154 274 152 274 155 275 151 275 152 275 155 276 156 276 150 276 151 277 155 277 150 277 152 278 157 278 155 278 157 279 152 279 154 279 153 280 103 280 107 280 158 281 153 281 107 281 153 282 158 282 154 282 154 283 159 283 157 283 159 284 154 284 158 284 160 285 156 285 155 285 155 286 161 286 160 286 161 287 155 287 157 287 157 288 162 288 161 288 162 289 157 289 159 289 158 290 163 290 159 290 158 291 107 291 108 291 163 292 158 292 108 292 164 293 159 293 163 293 159 294 164 294 162 294 161 295 162 295 165 295 165 296 166 296 160 296 161 297 165 297 160 297 167 298 162 298 164 298 167 299 165 299 162 299 108 300 111 300 163 300 168 301 163 301 111 301 163 302 168 302 164 302 164 303 169 303 167 303 164 304 168 304 169 304 170 305 167 305 169 305 171 306 462 306 172 306 463 307 462 307 171 307 173 308 171 308 172 308 114 309 173 309 172 309 173 310 114 310 118 310 118 311 127 311 173 311 174 312 171 312 173 312 171 313 174 313 463 313 175 314 463 314 174 314 173 315 176 315 174 315 176 316 173 316 127 316 127 317 136 317 176 317 177 318 174 318 176 318 174 319 177 319 175 319 178 320 175 320 177 320 176 321 179 321 177 321 179 322 176 322 136 322 136 323 142 323 179 323 180 324 177 324 179 324 177 325 180 325 178 325 181 326 178 326 180 326 179 327 182 327 180 327 182 328 179 328 142 328 142 329 150 329 182 329 180 330 183 330 181 330 183 331 180 331 182 331 184 332 181 332 183 332 182 333 185 333 183 333 182 334 150 334 156 334 185 335 182 335 156 335 156 336 160 336 185 336 183 337 186 337 184 337 186 338 183 338 185 338 187 339 185 339 160 339 187 340 186 340 185 340 160 341 166 341 187 341 454 342 172 342 462 342 190 343 114 343 172 343 190 344 172 344 454 344 191 345 112 345 114 345 191 346 114 346 190 346 112 347 192 347 86 347 192 348 112 348 191 348 86 349 193 349 82 349 193 350 86 350 192 350 454 351 450 351 190 351 194 352 190 352 450 352 190 353 194 353 191 353 191 354 195 354 192 354 195 355 191 355 194 355 196 356 192 356 195 356 192 357 196 357 193 357 193 358 197 358 82 358 197 359 193 359 196 359 450 360 446 360 194 360 198 361 194 361 446 361 194 362 198 362 195 362 199 363 195 363 198 363 195 364 199 364 196 364 200 365 196 365 199 365 196 366 200 366 197 366 201 367 197 367 200 367 197 368 201 368 82 368 446 369 442 369 198 369 202 370 198 370 442 370 198 371 202 371 199 371 203 372 199 372 202 372 199 373 203 373 200 373 200 374 204 374 201 374 204 375 200 375 203 375 201 376 205 376 82 376 205 377 201 377 204 377 442 378 438 378 202 378 206 379 202 379 438 379 202 380 206 380 203 380 207 381 203 381 206 381 203 382 207 382 204 382 208 383 204 383 207 383 204 384 208 384 205 384 209 385 205 385 208 385 205 386 209 386 82 386 438 387 434 387 206 387 210 388 206 388 434 388 206 389 210 389 207 389 207 390 211 390 208 390 211 391 207 391 210 391 212 392 208 392 211 392 208 393 212 393 209 393 209 394 213 394 82 394 213 395 209 395 212 395 434 396 430 396 210 396 214 397 210 397 430 397 210 398 214 398 211 398 211 399 215 399 212 399 215 400 211 400 214 400 216 401 212 401 215 401 212 402 216 402 213 402 217 403 213 403 216 403 213 404 217 404 82 404 430 405 426 405 214 405 214 406 218 406 215 406 218 407 214 407 426 407 215 408 219 408 216 408 219 409 215 409 218 409 220 410 216 410 219 410 216 411 220 411 217 411 221 412 217 412 220 412 217 413 221 413 82 413 426 414 632 414 218 414 632 415 0 415 218 415 219 416 5 416 220 416 221 417 25 417 29 417 82 418 221 418 29 418 25 419 220 419 5 419 220 420 25 420 221 420 222 421 223 421 224 421 225 422 222 422 224 422 422 423 224 423 223 423 226 424 224 424 422 424 422 425 419 425 226 425 227 426 226 426 419 426 419 427 418 427 227 427 228 428 227 428 418 428 418 429 417 429 228 429 229 430 228 430 417 430 417 431 416 431 229 431 230 432 229 432 416 432 416 433 415 433 230 433 231 434 230 434 415 434 415 435 414 435 231 435 232 436 231 436 414 436 414 437 413 437 232 437 233 438 232 438 413 438 413 439 412 439 233 439 234 440 233 440 412 440 412 441 411 441 234 441 235 442 234 442 411 442 411 443 410 443 235 443 236 444 235 444 410 444 410 445 409 445 236 445 237 446 236 446 409 446 409 447 408 447 237 447 238 448 237 448 408 448 408 449 407 449 238 449 239 450 238 450 407 450 407 451 406 451 239 451 240 452 239 452 406 452 406 453 405 453 240 453 240 454 405 454 188 454 240 455 188 455 241 455 240 456 241 456 189 456 240 457 189 457 80 457 242 458 240 458 80 458 244 459 225 459 224 459 245 460 244 460 224 460 247 461 246 461 245 461 224 462 226 462 245 462 245 463 226 463 227 463 248 464 245 464 227 464 248 465 249 465 247 465 245 466 248 466 247 466 250 467 249 467 248 467 227 468 228 468 248 468 251 469 252 469 250 469 248 470 251 470 250 470 251 471 248 471 228 471 228 472 229 472 251 472 253 473 252 473 251 473 251 474 229 474 230 474 254 475 251 475 230 475 251 476 254 476 253 476 255 477 253 477 254 477 230 478 231 478 254 478 254 479 231 479 232 479 256 480 254 480 232 480 256 481 257 481 255 481 254 482 256 482 255 482 232 483 233 483 256 483 258 484 257 484 256 484 256 485 233 485 234 485 259 486 256 486 234 486 259 487 260 487 258 487 256 488 259 488 258 488 234 489 235 489 259 489 261 490 260 490 259 490 259 491 235 491 236 491 262 492 259 492 236 492 259 493 262 493 261 493 263 494 261 494 262 494 236 495 237 495 262 495 264 496 265 496 263 496 262 497 264 497 263 497 264 498 262 498 237 498 237 499 238 499 264 499 266 500 265 500 264 500 267 501 268 501 266 501 264 502 267 502 266 502 264 503 238 503 239 503 267 504 264 504 239 504 239 505 240 505 267 505 269 506 268 506 267 506 267 507 242 507 269 507 267 508 240 508 242 508 270 509 269 509 242 509 79 510 243 510 271 510 246 511 271 511 243 511 272 512 271 512 246 512 246 513 247 513 272 513 273 514 272 514 247 514 247 515 249 515 273 515 274 516 273 516 249 516 249 517 250 517 274 517 274 518 250 518 252 518 275 519 274 519 252 519 252 520 253 520 275 520 276 521 275 521 253 521 253 522 255 522 276 522 277 523 276 523 255 523 255 524 257 524 277 524 278 525 277 525 257 525 257 526 258 526 278 526 279 527 278 527 258 527 258 528 260 528 279 528 280 529 279 529 260 529 260 530 261 530 280 530 281 531 280 531 261 531 261 532 263 532 281 532 281 533 263 533 265 533 282 534 281 534 265 534 265 535 266 535 282 535 283 536 282 536 266 536 266 537 268 537 283 537 284 538 283 538 268 538 268 539 269 539 284 539 285 540 284 540 269 540 269 541 270 541 285 541 285 542 270 542 286 542 284 543 285 543 287 543 288 544 289 544 290 544 288 545 290 545 287 545 288 546 287 546 285 546 285 547 286 547 288 547 291 548 289 548 288 548 288 549 292 549 291 549 288 550 286 550 292 550 293 551 291 551 292 551 294 552 293 552 292 552 292 553 168 553 294 553 294 554 168 554 295 554 297 555 295 555 296 555 300 556 299 556 298 556 298 557 301 557 300 557 302 558 300 558 301 558 301 559 303 559 302 559 304 560 302 560 303 560 79 561 271 561 303 561 303 562 271 562 272 562 303 563 272 563 305 563 303 564 305 564 304 564 306 565 304 565 305 565 297 566 299 566 295 566 294 567 295 567 299 567 299 568 300 568 294 568 293 569 294 569 300 569 300 570 302 570 293 570 291 571 293 571 302 571 302 572 304 572 291 572 289 573 291 573 304 573 304 574 306 574 289 574 290 575 289 575 306 575 306 576 307 576 290 576 308 577 290 577 307 577 307 578 309 578 308 578 310 579 308 579 309 579 309 580 311 580 310 580 312 581 310 581 311 581 311 582 313 582 312 582 314 583 312 583 313 583 313 584 315 584 314 584 316 585 314 585 315 585 272 586 273 586 305 586 317 587 305 587 273 587 317 588 307 588 306 588 317 589 306 589 305 589 273 590 274 590 317 590 309 591 307 591 317 591 318 592 311 592 309 592 317 593 318 593 309 593 317 594 274 594 275 594 318 595 317 595 275 595 275 596 276 596 318 596 313 597 311 597 318 597 318 598 276 598 277 598 319 599 318 599 277 599 318 600 319 600 313 600 315 601 313 601 319 601 277 602 278 602 319 602 320 603 319 603 278 603 320 604 316 604 315 604 319 605 320 605 315 605 278 606 279 606 320 606 314 607 316 607 320 607 320 608 279 608 280 608 321 609 320 609 280 609 320 610 321 610 314 610 312 611 314 611 321 611 280 612 281 612 321 612 322 613 310 613 312 613 321 614 322 614 312 614 321 615 281 615 282 615 322 616 321 616 282 616 308 617 310 617 322 617 282 618 283 618 322 618 322 619 283 619 284 619 322 620 284 620 287 620 322 621 287 621 308 621 290 622 308 622 287 622 167 623 270 623 242 623 242 624 165 624 167 624 170 625 286 625 270 625 170 626 270 626 167 626 292 627 286 627 170 627 168 628 292 628 170 628 168 629 111 629 295 629 170 630 169 630 168 630 301 631 298 631 303 631 78 632 303 632 298 632 303 633 78 633 79 633 297 634 76 634 298 634 298 635 77 635 78 635 298 636 76 636 77 636 75 637 243 637 79 637 24 638 225 638 244 638 244 639 74 639 24 639 74 640 244 640 243 640 243 641 75 641 74 641 225 642 24 642 222 642 186 643 241 643 188 643 186 644 187 644 241 644 187 645 189 645 241 645 166 646 189 646 187 646 80 647 189 647 166 647 80 648 166 648 165 648 80 649 165 649 242 649 109 650 295 650 111 650 109 651 296 651 295 651 109 652 110 652 296 652 76 653 296 653 110 653 76 654 297 654 296 654 297 655 298 655 299 655 244 656 245 656 246 656 243 657 244 657 246 657 5 658 219 658 218 658 2 659 5 659 218 659 0 660 2 660 218 660 86 661 117 661 112 661 112 662 117 662 115 662 86 663 116 663 117 663 548 664 517 664 518 664 522 665 519 665 517 665 548 666 522 666 517 666 632 667 426 667 630 667 630 668 426 668 627 668 627 669 426 669 425 669 402 670 399 670 401 670 401 671 399 671 400 671 348 672 346 672 347 672 558 673 349 673 348 673 558 674 524 674 349 674 525 675 349 675 524 675 525 676 350 676 349 676 525 677 523 677 350 677 554 678 403 678 469 678 554 679 469 679 468 679 554 680 468 680 455 680 468 681 456 681 455 681 456 682 404 682 455 682 186 683 404 683 456 683 186 684 188 684 404 684 420 685 421 685 610 685 402 686 560 686 559 686 560 687 402 687 401 687 401 688 610 688 560 688 610 689 401 689 420 689 559 690 555 690 402 690 347 691 557 691 558 691 347 692 556 692 557 692 348 693 347 693 558 693 342 694 555 694 556 694 556 695 347 695 342 695 344 696 342 696 347 696 464 697 466 697 465 697 466 698 350 698 523 698 466 699 464 699 353 699 353 700 464 700 359 700 464 701 467 701 375 701 464 702 375 702 359 702 403 703 467 703 469 703 467 704 403 704 375 704 355 705 358 705 337 705 323 706 337 706 358 706 323 707 358 707 361 707 323 708 361 708 362 708 363 709 323 709 362 709 337 710 323 710 335 710 323 711 363 711 324 711 324 712 363 712 364 712 324 713 333 713 323 713 323 714 333 714 335 714 365 715 324 715 364 715 333 716 324 716 331 716 325 717 331 717 324 717 324 718 365 718 325 718 325 719 365 719 366 719 331 720 325 720 329 720 367 721 325 721 366 721 326 722 330 722 325 722 325 723 330 723 329 723 325 724 367 724 326 724 368 725 326 725 367 725 330 726 326 726 332 726 327 727 332 727 326 727 326 728 368 728 327 728 327 729 368 729 369 729 332 730 327 730 334 730 370 731 327 731 369 731 327 732 370 732 328 732 328 733 370 733 371 733 328 734 336 734 327 734 327 735 336 735 334 735 336 736 328 736 338 736 372 737 328 737 371 737 328 738 340 738 339 738 328 739 339 739 338 739 328 740 372 740 340 740 373 741 340 741 372 741 329 742 330 742 331 742 332 743 331 743 330 743 331 744 332 744 333 744 334 745 333 745 332 745 333 746 334 746 335 746 336 747 335 747 334 747 335 748 336 748 337 748 338 749 337 749 336 749 337 750 338 750 355 750 339 751 355 751 338 751 355 752 339 752 356 752 341 753 356 753 339 753 356 754 341 754 354 754 343 755 354 755 341 755 354 756 343 756 352 756 345 757 352 757 343 757 352 758 345 758 351 758 346 759 351 759 345 759 351 760 346 760 350 760 348 761 350 761 346 761 339 762 340 762 341 762 342 763 341 763 340 763 342 764 340 764 373 764 342 765 373 765 374 765 555 766 342 766 374 766 341 767 342 767 343 767 344 768 343 768 342 768 343 769 344 769 345 769 347 770 345 770 344 770 345 771 347 771 346 771 348 772 349 772 350 772 351 773 350 773 466 773 353 774 351 774 466 774 351 775 353 775 352 775 352 776 353 776 354 776 357 777 353 777 359 777 357 778 354 778 353 778 354 779 357 779 356 779 360 780 357 780 359 780 357 781 360 781 358 781 357 782 358 782 355 782 357 783 355 783 356 783 361 784 358 784 360 784 360 785 359 785 375 785 376 786 360 786 375 786 360 787 376 787 361 787 377 788 361 788 376 788 361 789 377 789 362 789 379 790 362 790 377 790 362 791 379 791 363 791 380 792 363 792 379 792 363 793 380 793 364 793 364 794 380 794 382 794 384 795 364 795 382 795 364 796 384 796 365 796 385 797 365 797 384 797 365 798 385 798 366 798 387 799 366 799 385 799 366 800 387 800 367 800 388 801 367 801 387 801 367 802 388 802 368 802 390 803 368 803 388 803 368 804 390 804 369 804 392 805 369 805 390 805 369 806 392 806 370 806 393 807 370 807 392 807 370 808 393 808 371 808 371 809 393 809 395 809 396 810 371 810 395 810 371 811 396 811 372 811 398 812 372 812 396 812 372 813 398 813 373 813 399 814 373 814 398 814 373 815 399 815 374 815 399 816 402 816 374 816 555 817 374 817 402 817 375 818 403 818 376 818 378 819 403 819 405 819 378 820 376 820 403 820 376 821 378 821 377 821 406 822 378 822 405 822 378 823 406 823 381 823 381 824 406 824 407 824 381 825 379 825 378 825 378 826 379 826 377 826 379 827 381 827 380 827 408 828 381 828 407 828 381 829 408 829 383 829 383 830 382 830 381 830 381 831 382 831 380 831 409 832 383 832 408 832 382 833 383 833 384 833 386 834 384 834 383 834 383 835 409 835 386 835 386 836 409 836 410 836 384 837 386 837 385 837 411 838 386 838 410 838 389 839 387 839 386 839 386 840 387 840 385 840 386 841 411 841 389 841 389 842 411 842 412 842 387 843 389 843 388 843 413 844 389 844 412 844 391 845 390 845 389 845 389 846 390 846 388 846 389 847 413 847 391 847 391 848 413 848 414 848 415 849 391 849 414 849 390 850 391 850 392 850 394 851 392 851 391 851 391 852 415 852 394 852 394 853 415 853 416 853 392 854 394 854 393 854 417 855 394 855 416 855 394 856 417 856 397 856 397 857 395 857 394 857 394 858 395 858 393 858 418 859 397 859 417 859 395 860 397 860 396 860 400 861 398 861 397 861 397 862 398 862 396 862 397 863 418 863 400 863 400 864 418 864 419 864 422 865 400 865 419 865 398 866 400 866 399 866 400 867 422 867 401 867 401 868 422 868 420 868 403 869 554 869 405 869 405 870 554 870 455 870 405 871 455 871 404 871 405 872 404 872 188 872 424 873 423 873 609 873 609 874 627 874 424 874 552 875 605 875 423 875 423 876 605 876 609 876 425 877 424 877 627 877 427 878 552 878 423 878 423 879 424 879 427 879 428 880 427 880 424 880 424 881 425 881 428 881 425 882 426 882 429 882 429 883 428 883 425 883 430 884 429 884 426 884 431 885 552 885 427 885 427 886 428 886 431 886 432 887 431 887 428 887 428 888 429 888 432 888 429 889 430 889 433 889 433 890 432 890 429 890 434 891 433 891 430 891 431 892 432 892 435 892 435 893 552 893 431 893 436 894 435 894 432 894 432 895 433 895 436 895 433 896 434 896 437 896 437 897 436 897 433 897 438 898 437 898 434 898 439 899 552 899 435 899 435 900 436 900 439 900 440 901 439 901 436 901 436 902 437 902 440 902 441 903 440 903 437 903 437 904 438 904 441 904 442 905 441 905 438 905 439 906 440 906 443 906 443 907 552 907 439 907 440 908 441 908 444 908 444 909 443 909 440 909 445 910 444 910 441 910 441 911 442 911 445 911 446 912 445 912 442 912 447 913 552 913 443 913 443 914 444 914 447 914 448 915 447 915 444 915 444 916 445 916 448 916 449 917 448 917 445 917 445 918 446 918 449 918 450 919 449 919 446 919 447 920 448 920 451 920 451 921 552 921 447 921 452 922 451 922 448 922 448 923 449 923 452 923 449 924 450 924 453 924 453 925 452 925 449 925 454 926 453 926 450 926 451 927 452 927 548 927 548 928 552 928 451 928 452 929 453 929 522 929 522 930 548 930 452 930 453 931 454 931 520 931 453 932 520 932 522 932 454 933 462 933 520 933 474 934 456 934 468 934 456 935 457 935 186 935 456 936 474 936 457 936 186 937 457 937 184 937 478 938 457 938 474 938 457 939 478 939 458 939 458 940 478 940 484 940 458 941 184 941 457 941 184 942 458 942 181 942 492 943 458 943 484 943 458 944 492 944 459 944 459 945 181 945 458 945 181 946 459 946 178 946 498 947 459 947 492 947 459 948 498 948 460 948 460 949 178 949 459 949 178 950 460 950 175 950 507 951 460 951 498 951 460 952 507 952 461 952 461 953 175 953 460 953 175 954 461 954 463 954 516 955 461 955 507 955 461 956 516 956 520 956 520 957 462 957 461 957 461 958 462 958 463 958 464 959 465 959 467 959 470 960 465 960 466 960 470 961 467 961 465 961 471 962 470 962 466 962 466 963 523 963 471 963 526 964 471 964 523 964 467 965 472 965 469 965 467 966 470 966 472 966 473 967 474 967 469 967 469 968 474 968 468 968 473 969 469 969 472 969 475 970 472 970 470 970 470 971 471 971 475 971 471 972 526 972 476 972 476 973 526 973 527 973 476 974 475 974 471 974 472 975 475 975 477 975 477 976 473 976 472 976 473 977 477 977 479 977 479 978 474 978 473 978 474 979 479 979 478 979 475 980 476 980 480 980 480 981 477 981 475 981 481 982 480 982 476 982 476 983 527 983 481 983 481 984 527 984 531 984 477 985 480 985 482 985 482 986 479 986 477 986 483 987 484 987 479 987 479 988 484 988 478 988 479 989 482 989 483 989 485 990 482 990 480 990 480 991 481 991 485 991 481 992 531 992 486 992 486 993 531 993 535 993 486 994 485 994 481 994 482 995 485 995 487 995 487 996 483 996 482 996 483 997 487 997 488 997 488 998 484 998 483 998 484 999 488 999 492 999 489 1000 487 1000 485 1000 485 1001 486 1001 489 1001 486 1002 535 1002 490 1002 490 1003 489 1003 486 1003 487 1004 489 1004 491 1004 491 1005 488 1005 487 1005 493 1006 492 1006 488 1006 488 1007 491 1007 493 1007 539 1008 490 1008 535 1008 494 1009 491 1009 489 1009 489 1010 490 1010 494 1010 495 1011 494 1011 490 1011 490 1012 539 1012 495 1012 491 1013 494 1013 496 1013 496 1014 493 1014 491 1014 492 1015 493 1015 498 1015 493 1016 496 1016 497 1016 497 1017 498 1017 493 1017 543 1018 495 1018 539 1018 499 1019 496 1019 494 1019 494 1020 495 1020 499 1020 495 1021 543 1021 500 1021 500 1022 499 1022 495 1022 496 1023 499 1023 501 1023 501 1024 497 1024 496 1024 502 1025 498 1025 497 1025 497 1026 501 1026 502 1026 498 1027 502 1027 507 1027 503 1028 501 1028 499 1028 499 1029 500 1029 503 1029 500 1030 543 1030 504 1030 504 1031 503 1031 500 1031 505 1032 502 1032 501 1032 501 1033 503 1033 505 1033 502 1034 505 1034 506 1034 506 1035 507 1035 502 1035 547 1036 504 1036 543 1036 508 1037 505 1037 503 1037 503 1038 504 1038 508 1038 509 1039 508 1039 504 1039 504 1040 547 1040 509 1040 505 1041 508 1041 510 1041 510 1042 506 1042 505 1042 511 1043 507 1043 506 1043 506 1044 510 1044 511 1044 507 1045 511 1045 516 1045 549 1046 509 1046 547 1046 508 1047 509 1047 512 1047 512 1048 510 1048 508 1048 509 1049 549 1049 513 1049 513 1050 512 1050 509 1050 510 1051 512 1051 514 1051 514 1052 511 1052 510 1052 515 1053 516 1053 511 1053 511 1054 514 1054 515 1054 512 1055 513 1055 517 1055 517 1056 514 1056 512 1056 518 1057 517 1057 513 1057 513 1058 549 1058 518 1058 514 1059 517 1059 519 1059 519 1060 515 1060 514 1060 521 1061 516 1061 515 1061 515 1062 519 1062 521 1062 516 1063 521 1063 520 1063 548 1064 518 1064 549 1064 519 1065 522 1065 521 1065 521 1066 522 1066 520 1066 523 1067 525 1067 526 1067 562 1068 524 1068 558 1068 528 1069 526 1069 525 1069 524 1070 562 1070 529 1070 524 1071 529 1071 525 1071 525 1072 529 1072 530 1072 530 1073 528 1073 525 1073 526 1074 528 1074 527 1074 567 1075 529 1075 562 1075 528 1076 530 1076 532 1076 532 1077 531 1077 528 1077 528 1078 531 1078 527 1078 529 1079 567 1079 533 1079 533 1080 530 1080 529 1080 530 1081 533 1081 534 1081 534 1082 532 1082 530 1082 575 1083 533 1083 567 1083 531 1084 532 1084 535 1084 532 1085 534 1085 536 1085 536 1086 535 1086 532 1086 533 1087 575 1087 537 1087 537 1088 534 1088 533 1088 534 1089 537 1089 538 1089 538 1090 536 1090 534 1090 580 1091 537 1091 575 1091 535 1092 536 1092 539 1092 540 1093 539 1093 536 1093 536 1094 538 1094 540 1094 537 1095 580 1095 541 1095 541 1096 538 1096 537 1096 538 1097 541 1097 542 1097 542 1098 540 1098 538 1098 589 1099 541 1099 580 1099 539 1100 540 1100 543 1100 540 1101 542 1101 544 1101 544 1102 543 1102 540 1102 545 1103 542 1103 541 1103 541 1104 589 1104 545 1104 545 1105 589 1105 595 1105 542 1106 545 1106 546 1106 546 1107 544 1107 542 1107 543 1108 544 1108 547 1108 544 1109 546 1109 550 1109 550 1110 547 1110 544 1110 551 1111 546 1111 545 1111 545 1112 595 1112 551 1112 546 1113 551 1113 553 1113 553 1114 550 1114 546 1114 603 1115 551 1115 595 1115 547 1116 550 1116 549 1116 550 1117 552 1117 548 1117 550 1118 548 1118 549 1118 550 1119 553 1119 552 1119 605 1120 552 1120 551 1120 551 1121 552 1121 553 1121 551 1122 603 1122 605 1122 555 1123 559 1123 556 1123 556 1124 559 1124 561 1124 556 1125 561 1125 557 1125 563 1126 558 1126 557 1126 563 1127 557 1127 561 1127 611 1128 560 1128 610 1128 564 1129 561 1129 559 1129 558 1130 563 1130 562 1130 565 1131 564 1131 560 1131 560 1132 564 1132 559 1132 560 1133 611 1133 565 1133 613 1134 565 1134 611 1134 566 1135 563 1135 561 1135 561 1136 564 1136 566 1136 563 1137 566 1137 568 1137 568 1138 567 1138 563 1138 563 1139 567 1139 562 1139 564 1140 565 1140 569 1140 569 1141 566 1141 564 1141 565 1142 613 1142 570 1142 570 1143 569 1143 565 1143 614 1144 570 1144 613 1144 571 1145 568 1145 566 1145 566 1146 569 1146 571 1146 572 1147 575 1147 568 1147 568 1148 575 1148 567 1148 568 1149 571 1149 572 1149 569 1150 570 1150 573 1150 573 1151 571 1151 569 1151 574 1152 573 1152 570 1152 570 1153 614 1153 574 1153 617 1154 574 1154 614 1154 571 1155 573 1155 576 1155 576 1156 572 1156 571 1156 577 1157 575 1157 572 1157 572 1158 576 1158 577 1158 573 1159 574 1159 578 1159 578 1160 576 1160 573 1160 579 1161 578 1161 574 1161 574 1162 617 1162 579 1162 579 1163 617 1163 620 1163 575 1164 577 1164 580 1164 581 1165 577 1165 576 1165 576 1166 578 1166 581 1166 577 1167 581 1167 582 1167 582 1168 580 1168 577 1168 578 1169 579 1169 583 1169 583 1170 581 1170 578 1170 579 1171 620 1171 584 1171 584 1172 583 1172 579 1172 580 1173 582 1173 589 1173 585 1174 582 1174 581 1174 581 1175 583 1175 585 1175 586 1176 589 1176 582 1176 582 1177 585 1177 586 1177 583 1178 584 1178 587 1178 587 1179 585 1179 583 1179 588 1180 587 1180 584 1180 584 1181 620 1181 588 1181 588 1182 620 1182 623 1182 585 1183 587 1183 590 1183 590 1184 586 1184 585 1184 586 1185 590 1185 591 1185 591 1186 589 1186 586 1186 592 1187 590 1187 587 1187 587 1188 588 1188 592 1188 588 1189 623 1189 593 1189 593 1190 592 1190 588 1190 589 1191 591 1191 595 1191 594 1192 591 1192 590 1192 590 1193 592 1193 594 1193 591 1194 594 1194 596 1194 596 1195 595 1195 591 1195 597 1196 594 1196 592 1196 592 1197 593 1197 597 1197 626 1198 593 1198 623 1198 593 1199 626 1199 598 1199 598 1200 597 1200 593 1200 594 1201 597 1201 599 1201 599 1202 596 1202 594 1202 595 1203 596 1203 603 1203 596 1204 599 1204 600 1204 600 1205 603 1205 596 1205 601 1206 599 1206 597 1206 597 1207 598 1207 601 1207 602 1208 601 1208 598 1208 598 1209 626 1209 602 1209 599 1210 601 1210 604 1210 604 1211 600 1211 599 1211 606 1212 603 1212 600 1212 600 1213 604 1213 606 1213 628 1214 602 1214 626 1214 607 1215 604 1215 601 1215 601 1216 602 1216 607 1216 608 1217 607 1217 602 1217 602 1218 628 1218 608 1218 603 1219 606 1219 605 1219 627 1220 608 1220 628 1220 604 1221 607 1221 609 1221 609 1222 605 1222 604 1222 604 1223 605 1223 606 1223 607 1224 608 1224 609 1224 609 1225 608 1225 627 1225 610 1226 612 1226 611 1226 615 1227 612 1227 20 1227 615 1228 613 1228 612 1228 612 1229 613 1229 611 1229 616 1230 615 1230 20 1230 613 1231 615 1231 614 1231 618 1232 617 1232 615 1232 615 1233 617 1233 614 1233 615 1234 616 1234 618 1234 619 1235 618 1235 616 1235 617 1236 618 1236 620 1236 618 1237 619 1237 621 1237 621 1238 620 1238 618 1238 622 1239 621 1239 619 1239 620 1240 621 1240 623 1240 624 1241 623 1241 621 1241 621 1242 622 1242 624 1242 625 1243 624 1243 622 1243 623 1244 624 1244 626 1244 629 1245 626 1245 624 1245 624 1246 625 1246 629 1246 631 1247 629 1247 625 1247 626 1248 629 1248 628 1248 630 1249 627 1249 629 1249 629 1250 627 1250 628 1250 629 1251 631 1251 630 1251 631 1252 632 1252 630 1252 420 1253 422 1253 421 1253 223 1254 421 1254 422 1254 421 1255 612 1255 610 1255 223 1256 612 1256 421 1256 223 1257 20 1257 612 1257 20 1258 223 1258 21 1258 21 1259 223 1259 23 1259 23 1260 223 1260 222 1260 23 1261 222 1261 24 1261

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_proximal/th_proximal_C6M2.dae b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_C6M2.dae new file mode 100644 index 0000000..5e7a25d --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_C6M2.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:18.666034 + 2012-07-23T02:14:18.666047 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + 6.56299 -2.38277 47.24268 5.35263 -4.47927 47.24261 8.87247 -3.22337 44.39990 6.60916 0.00113 47.53578 2.84679 -2.37657 49.09227 2.54221 1.39790 49.16618 10.14795 -3.68767 40.89576 10.66138 2.26448 37.15411 10.65737 -0.00554 41.13606 12.34216 2.62174 3.91527 11.52786 5.12782 3.91527 11.01634 0.00113 12.12860 9.95809 4.42892 37.15411 10.15396 0.00113 28.83627 8.87557 6.44006 12.12189 10.19228 0.00113 20.46215 8.19527 5.94582 20.45875 8.17780 5.93308 28.83789 8.44714 9.36806 3.91528 6.45203 8.86355 12.12188 5.95784 8.18330 20.45874 5.94505 8.16576 28.83790 7.29732 8.09110 37.15418 6.31535 10.91690 3.91528 3.39832 10.41953 12.12189 3.90808 11.98867 3.91527 3.13846 9.61985 20.45875 3.13175 9.59923 28.83789 3.37712 10.35445 37.15417 1.33067 12.53653 3.91528 -3.37208 10.41953 12.12189 -3.11222 9.61985 20.45875 -3.10550 9.59923 28.83789 -1.30443 12.53653 3.91528 -1.12475 10.82762 37.15418 -3.88184 11.98867 3.91527 -6.28911 10.91690 3.91528 -6.42579 8.86355 12.12189 -5.93160 8.18330 20.45875 -5.91880 8.16576 28.83789 -7.27106 8.09110 37.15418 -8.42090 9.36806 3.91528 -11.50162 5.12782 3.91528 -8.84933 6.44006 12.12189 -8.16902 5.94582 20.45875 -8.15156 5.93308 28.83789 -9.93184 4.42892 37.15411 -10.99010 0.00113 12.12860 -10.16603 0.00113 20.46214 -10.12771 0.00113 28.83627 -12.59134 0.00113 3.91535 -10.63514 2.26448 37.15411 3.49825 -6.03527 47.24268 7.23523 -6.05897 44.39990 9.67970 -0.00886 44.25639 12.91713 1.09479 -0.14384 9.76257 3.16892 -7.26175 8.30649 6.02662 -7.26175 4.71547 5.68328 -9.95829 6.03859 8.29450 -7.26168 4.72706 -8.16367 44.39983 8.27510 -6.93147 40.89576 7.16706 9.84777 -3.83483 7.64245 10.50204 0.00908 3.18089 9.75057 -7.26168 3.77422 11.57655 -3.83483 4.02411 12.34569 0.00914 -2.27218 7.03446 -9.95872 -3.11307 2.27245 -11.67954 -3.15472 9.75057 -7.26175 0.01312 12.17225 -3.83483 0.01312 12.98097 0.00914 -3.74798 11.57655 -3.83482 -3.99787 12.34569 0.00915 -5.64170 4.78556 -9.95684 -6.01242 8.29450 -7.26175 -7.14089 9.84777 -3.83490 -7.61621 10.50204 0.00908 -8.28025 6.02662 -7.26175 -9.83349 7.15513 -3.83482 -10.48777 7.63049 0.00908 -6.82884 2.31377 -9.95810 -9.73633 3.16892 -7.26175 -11.56236 3.76221 -3.83482 -12.33148 4.01212 0.00908 -12.08549 0.03693 -3.51346 -12.75930 -0.06820 -0.00748 8.27510 6.93376 40.89576 7.23524 6.06125 44.39990 5.35263 4.48149 47.24261 5.40581 9.34144 40.89576 4.72706 8.16591 44.39983 3.49824 6.03750 47.24268 1.88597 10.62254 40.89576 1.65022 9.28577 44.39990 -1.85971 10.62254 40.89576 -1.62397 9.28577 44.39990 -1.19723 6.86544 47.24269 -2.82054 2.37884 49.09227 -5.37955 9.34144 40.89577 -4.70088 8.16591 44.39990 -8.24885 6.93376 40.89577 -7.20898 6.06125 44.39991 -5.32638 4.48149 47.24262 -10.61057 1.65543 40.89317 -9.63732 1.11884 44.52992 -6.58291 0.00113 47.53579 9.95809 -4.42667 37.15411 10.66138 -2.26227 37.15411 -12.31592 -2.61947 3.91528 -10.40525 -3.38397 12.12189 -9.60558 -3.12417 20.45875 -9.58500 -3.11747 28.83789 -10.63514 -2.26227 37.15411 -11.50162 -5.12557 3.91528 -9.93184 -4.42667 37.15411 -8.84933 -6.43777 12.12189 -8.16902 -5.94357 20.45875 -8.15156 -5.93087 28.83789 -8.42090 -9.36577 3.91528 -6.42579 -8.86127 12.12189 -5.93160 -8.18107 20.45875 -5.91880 -8.16347 28.83789 -7.27106 -8.08887 37.15418 -6.28911 -10.91467 3.91528 -3.37208 -10.41727 12.12189 -3.88184 -11.98637 3.91528 -3.11222 -9.61757 20.45875 -3.10550 -9.59697 28.83789 -3.35086 -10.35217 37.15417 -1.30443 -12.53427 3.91528 1.33067 -12.53427 3.91528 1.15100 -10.82537 37.15418 3.39832 -10.41727 12.12189 3.90808 -11.98637 3.91528 3.13846 -9.61757 20.45875 3.13175 -9.59697 28.83789 6.31535 -10.91467 3.91528 6.45203 -8.86127 12.12188 5.95784 -8.18107 20.45874 5.94505 -8.16347 28.83790 7.29732 -8.08887 37.15418 8.44714 -9.36577 3.91528 11.52786 -5.12557 3.91527 8.87557 -6.43777 12.12189 8.19527 -5.94357 20.45875 8.17780 -5.93087 28.83789 10.43149 -3.38397 12.12188 9.63183 -3.12417 20.45875 9.61125 -3.11747 28.83790 12.34216 -2.61947 3.91527 -3.66193 -1.19297 -11.67954 -6.96572 -1.29969 -9.95652 -9.73633 -3.16667 -7.26174 -11.64271 -3.81134 -3.89589 -12.33148 -4.00987 0.00908 -5.96978 -4.34567 -9.95872 -8.28025 -6.02437 -7.26175 -9.83349 -7.15287 -3.83482 -10.48777 -7.62827 0.00908 -6.01242 -8.29227 -7.26175 -7.14089 -9.84547 -3.83490 -7.61621 -10.49977 0.00908 0.01312 -7.39417 -9.95865 0.01312 -10.25007 -7.26175 -3.74798 -11.57427 -3.83482 -3.99787 -12.34347 0.00915 0.01312 -12.16997 -3.83483 0.01312 -12.97867 0.00915 3.13931 -2.27017 -11.67954 2.29842 -7.03217 -9.95873 3.18089 -9.74827 -7.26168 3.77422 -11.57427 -3.83483 4.02411 -12.34347 0.00915 5.99602 -4.34567 -9.95873 6.03859 -8.29227 -7.26168 7.16706 -9.84547 -3.83483 7.64245 -10.49977 0.00908 8.30649 -6.02437 -7.26175 9.85972 -7.15287 -3.83483 10.51401 -7.62827 0.00907 7.04650 -2.28417 -9.95872 9.76257 -3.16667 -7.26175 11.58860 -3.75997 -3.83483 12.35772 -4.00987 0.00907 -10.12170 -3.68767 40.89577 -8.84622 -3.22337 44.39991 -6.53674 -2.38277 47.24269 -3.46287 -1.26402 49.09227 -8.24885 -6.93147 40.89577 -7.20898 -6.05897 44.39991 -5.32638 -4.47927 47.24262 -5.37955 -9.33917 40.89577 -4.70088 -8.16367 44.39991 -3.47199 -6.03527 47.24269 -1.85971 -10.62027 40.89576 -1.62397 -9.28347 44.39991 1.88597 -10.62027 40.89576 1.65022 -9.28347 44.39990 5.40581 -9.33917 40.89576 -3.19907 -6.56849 -9.78374 -3.78335 -9.39795 -7.68514 9.97586 6.39629 -3.98794 10.94574 6.09801 -0.28748 11.56665 1.44050 -3.96156 1.44190 7.54037 -9.95509 7.22986 1.88477 -9.95264 + + + + + + + + + + 0.65940 -0.38071 0.64827 0.44231 -0.11788 0.88908 0.37567 0.01217 0.92667 0.92219 0.29965 0.24447 0.94159 0.30595 -0.14069 0.94475 0.31420 0.09342 0.91917 0.30586 0.24816 0.94793 0.31844 0.00434 0.94357 0.31703 0.09579 0.93878 0.31278 -0.14440 0.94874 0.31606 0.00246 0.79790 0.57971 0.16518 0.69125 0.69126 0.21055 0.70362 0.70363 0.09913 0.70363 0.70362 0.09912 0.70711 0.70710 0.00255 0.70709 0.70712 0.00256 0.80264 0.58316 -0.12528 0.70690 0.70692 -0.02347 0.57718 0.79441 0.18915 0.45176 0.88661 0.09912 0.39708 0.89187 0.21654 0.44530 0.87394 0.19476 0.45399 0.89100 0.00256 0.45176 0.88662 0.09913 0.45302 0.88908 -0.06568 0.45399 0.89100 0.00256 0.49784 0.86227 -0.09299 0.20388 0.95916 0.19606 -0.00000 0.96830 0.24979 -0.00000 0.99543 0.09548 -0.00000 1.00000 0.00246 -0.00000 0.99543 0.09548 -0.00000 0.99590 -0.09044 -0.00000 1.00000 0.00246 -0.00000 0.96830 0.24979 0.10302 0.98016 -0.16932 -0.20388 0.95916 0.19606 -0.39884 0.89582 0.19606 -0.45176 0.88661 0.09913 -0.44382 0.87103 0.21055 -0.45176 0.88662 0.09912 -0.45399 0.89100 0.00256 -0.45399 0.89100 0.00256 -0.40606 0.91202 -0.05784 -0.45387 0.89076 -0.02347 -0.57718 0.79441 0.18915 -0.78794 0.57248 0.22675 -0.70243 0.70245 0.11470 -0.70362 0.70363 0.09912 -0.70363 0.70362 0.09913 -0.70711 0.70710 0.00256 -0.70296 0.70298 -0.10799 -0.70709 0.70712 0.00255 -0.80721 0.58648 -0.06672 -0.91917 0.30586 0.24816 -0.94454 0.31413 0.09570 -0.94379 0.31710 0.09333 -0.94794 0.31844 0.00246 -0.93878 0.31278 -0.14440 -0.94873 0.31606 0.00434 -0.96083 0.20424 0.18732 -0.94159 0.30595 -0.14069 0.48944 -0.58327 0.64826 0.43121 -0.24898 0.86722 0.72633 -0.09772 0.68037 0.92235 -0.15082 0.35571 0.95089 0.30897 0.01846 0.55814 0.28439 -0.77949 0.49213 0.49216 -0.71804 0.60058 -0.71572 0.35643 0.80901 0.58778 0.00398 0.58402 0.80383 0.11304 0.39723 0.77961 -0.48418 0.30759 0.60369 -0.73549 0.39723 0.77960 -0.48418 0.44450 0.87237 -0.20346 0.44450 0.87237 -0.20345 0.45319 0.88943 0.05951 0.40489 0.90940 0.09515 0.00000 0.88253 -0.47025 0.00001 0.70460 -0.70960 0.15316 0.96703 -0.20345 0.11963 0.75532 -0.64434 0.20774 0.97732 0.04113 0.15573 0.98327 0.09450 0.15316 0.96703 -0.20345 0.00000 0.99359 0.11305 -0.13688 0.86420 -0.48417 -0.15316 0.96703 -0.20345 -0.15616 0.98594 0.05951 -0.15316 0.96703 -0.20345 -0.20697 0.97371 0.09515 -0.24580 0.36753 -0.89694 -0.38907 0.58234 -0.71379 -0.28744 0.56414 -0.77403 -0.39723 0.77961 -0.48417 -0.44449 0.87237 -0.20345 -0.39722 0.77961 -0.48417 -0.44450 0.87237 -0.20345 -0.40639 0.91278 0.04112 -0.45196 0.88702 0.09450 -0.58402 0.80383 0.11304 -0.61871 0.61869 -0.48417 -0.49555 0.49554 -0.71335 -0.61871 0.61869 -0.48417 -0.69233 0.69231 -0.20344 -0.69232 0.69232 -0.20346 -0.70585 0.70585 0.05950 -0.79802 0.57979 0.16434 -0.61172 0.29417 -0.73435 -0.41027 0.19750 -0.89032 -0.59794 0.30467 -0.74138 -0.77961 0.39723 -0.48417 -0.77959 0.39724 -0.48418 -0.87236 0.44451 -0.20346 -0.88942 0.45320 0.05951 -0.87237 0.44451 -0.20345 -0.96755 0.20566 0.14681 -0.87370 0.08131 -0.47963 -0.97207 0.11906 -0.20224 -0.99374 0.10403 0.04071 -0.97735 0.10322 -0.18474 0.93079 -0.22073 0.29140 0.93648 0.30429 0.17441 0.92480 0.32437 0.19882 0.90394 0.32014 0.28356 0.70371 0.26783 0.65808 0.87353 0.34362 0.34478 0.41766 0.17547 0.89150 0.73848 0.24813 0.62696 0.80866 0.58753 -0.02959 0.60058 0.71572 0.35643 0.64127 0.76422 0.06880 0.48942 0.58328 0.64827 0.60057 0.71573 0.35644 0.26933 0.32094 0.90800 0.48945 0.58327 0.64825 0.49967 0.86544 -0.03661 0.34121 0.93747 0.06881 0.31955 0.87797 0.35644 0.26043 0.71550 0.64826 0.31956 0.87797 0.35643 -0.00000 0.93432 0.35643 0.10448 0.99409 -0.02959 0.00000 0.99850 0.05473 -0.00000 0.65858 0.75251 0.00000 0.93432 0.35643 0.13478 0.76436 0.63054 0.06535 0.37063 0.92648 0.05375 0.36390 0.92989 -0.31955 0.87798 0.35643 -0.40656 0.91314 -0.02981 -0.33866 0.93047 -0.13974 -0.26041 0.71550 0.64826 -0.31955 0.87798 0.35643 -0.60058 0.71573 0.35642 -0.64127 0.76422 0.06880 -0.42333 0.50448 0.75252 -0.60059 0.71572 0.35644 -0.38808 0.67216 0.63055 -0.25780 0.44650 0.85684 -0.80866 0.58754 -0.02959 -0.90435 0.40457 0.13593 -0.85543 0.38258 0.34911 -0.67924 0.35069 0.64471 -0.85533 0.42793 0.29204 -0.63950 0.22740 0.73439 -0.47521 0.18950 0.85922 -0.94953 0.30853 0.05650 0.74314 -0.15758 0.65032 0.95097 -0.30900 0.01278 -0.97634 -0.10261 0.19035 0.65940 -0.38073 0.64826 -0.98072 -0.16963 0.09698 -0.96361 -0.16690 0.20880 -0.97940 -0.17574 0.09942 -0.98429 -0.17652 0.00451 -0.98519 -0.17144 0.00256 -0.99212 -0.00000 -0.12528 -0.98510 -0.17144 -0.01345 0.80914 -0.46717 0.35644 -0.93388 -0.30345 0.18916 -0.94736 -0.30783 -0.08797 -0.88663 -0.45174 0.09912 -0.87104 -0.44380 0.21055 -0.89100 -0.45399 0.00255 -0.88662 -0.45175 0.09913 -0.88580 -0.45132 -0.10799 -0.89101 -0.45398 0.00255 -0.79790 -0.57972 0.16518 -0.69125 -0.69126 0.21054 -0.70362 -0.70363 0.09913 -0.70712 -0.70709 0.00255 -0.70364 -0.70361 0.09912 -0.70708 -0.70713 0.00257 -0.80264 -0.58316 -0.12528 -0.70689 -0.70694 -0.02346 -0.57719 -0.79440 0.18916 -0.45177 -0.88661 0.09912 -0.39706 -0.89188 0.21655 -0.44531 -0.87394 0.19476 -0.45174 -0.88662 0.09913 -0.45398 -0.89101 0.00257 -0.45302 -0.88908 -0.06569 -0.45400 -0.89100 0.00255 -0.49783 -0.86228 -0.09299 -0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.10408 -0.99021 -0.09299 0.00000 -0.99543 0.09549 0.00000 -1.00000 0.00246 0.00000 -0.99543 0.09549 0.00000 -0.98927 -0.14612 0.00000 -1.00000 0.00246 0.39882 -0.89583 0.19605 0.44383 -0.87103 0.21055 0.45177 -0.88661 0.09913 0.45398 -0.89101 0.00255 0.45174 -0.88662 0.09912 0.45400 -0.89100 0.00256 0.40605 -0.91202 -0.05785 0.45388 -0.89075 -0.02347 0.57719 -0.79440 0.18916 0.78794 -0.57248 0.22675 0.70243 -0.70245 0.11470 0.70362 -0.70363 0.09912 0.70711 -0.70709 0.00256 0.70363 -0.70361 0.09913 0.70295 -0.70300 -0.10800 0.70708 -0.70713 0.00255 0.80721 -0.58648 -0.06672 0.88663 -0.45174 0.09913 0.87104 -0.44380 0.21055 0.89100 -0.45399 0.00255 0.88662 -0.45176 0.09912 0.88580 -0.45132 -0.10799 0.89101 -0.45398 0.00255 0.93388 -0.30345 0.18916 0.94737 -0.30783 -0.08797 0.97395 0.00000 0.22676 0.98001 -0.16953 0.10411 0.86472 -0.49926 0.05473 0.98049 -0.16960 0.09933 0.98429 -0.17651 0.00256 0.97965 -0.17578 0.09687 0.97962 -0.17053 -0.10616 0.80914 -0.46718 0.35642 0.98518 -0.17144 0.00451 0.99814 0.00000 -0.06089 -0.41883 0.06633 -0.90564 -0.46278 0.01714 -0.88630 -0.67576 0.02528 -0.73669 -0.84734 -0.00000 -0.53105 -0.69723 -0.00000 -0.71685 -0.86492 -0.04989 -0.49943 -0.97720 -0.09349 -0.19061 -0.99368 -0.10443 0.04113 -0.99320 -0.10761 0.04443 -0.97821 -0.10692 -0.17798 -0.94496 -0.30704 0.11305 -0.45359 -0.14768 -0.87889 -0.61097 -0.19921 -0.76618 -0.76686 -0.39073 -0.50918 -0.61575 -0.31374 -0.72279 -0.86424 -0.47115 -0.17639 -0.76482 -0.42298 -0.48594 -0.87236 -0.44450 -0.20346 -0.88942 -0.45319 0.05951 -0.61871 -0.61869 -0.48417 -0.48867 -0.48865 -0.72279 -0.69232 -0.69231 -0.20346 -0.61871 -0.61870 -0.48416 -0.69231 -0.69232 -0.20345 -0.58403 -0.80382 0.11304 -0.44450 -0.87237 -0.20345 -0.45320 -0.88942 0.05950 -0.44450 -0.87236 -0.20346 -0.40486 -0.90941 0.09517 -0.15316 -0.96703 -0.20346 -0.13688 -0.86421 -0.48416 -0.15314 -0.96703 -0.20345 -0.20776 -0.97732 0.04111 -0.15571 -0.98327 0.09452 0.00000 -0.99359 0.11304 -0.04633 -0.29252 -0.95514 -0.00000 0.00000 -1.00000 0.05508 -0.34793 -0.93590 0.10810 -0.68256 -0.72280 0.13691 -0.86420 -0.48416 0.10814 -0.68257 -0.72277 0.15316 -0.96703 -0.20345 0.13688 -0.86419 -0.48418 0.15314 -0.96703 -0.20346 0.15614 -0.98594 0.05950 0.20699 -0.97370 0.09517 0.26805 -0.36893 -0.88996 0.41417 -0.57005 -0.70959 0.39721 -0.77961 -0.48419 0.27533 -0.54039 -0.79510 0.44451 -0.87236 -0.20346 0.39724 -0.77960 -0.48416 0.44450 -0.87236 -0.20347 0.40636 -0.91279 0.04111 0.45197 -0.88701 0.09452 0.58403 -0.80382 0.11304 0.48865 -0.48867 -0.72279 0.61869 -0.61871 -0.48416 0.61870 -0.61871 -0.48416 0.69231 -0.69232 -0.20347 0.69231 -0.69232 -0.20346 0.70585 -0.70586 0.05951 0.79801 -0.57980 0.16435 0.39424 -0.20089 -0.89678 0.61573 -0.31376 -0.72279 0.77961 -0.39723 -0.48416 0.61576 -0.31374 -0.72278 0.77959 -0.39725 -0.48418 0.87236 -0.44452 -0.20346 0.88942 -0.45319 0.05951 0.87237 -0.44450 -0.20345 0.94496 -0.30704 0.11305 0.13383 0.18421 -0.97373 0.88253 -0.00000 -0.47026 0.97289 -0.11267 -0.20199 0.99330 -0.10759 0.04225 0.99012 -0.00000 0.14025 -0.99998 0.00000 0.00657 -0.96541 -0.08821 0.24534 -0.99071 -0.09060 0.10143 0.32007 -0.38142 0.86722 -0.72094 -0.15159 0.67621 -0.91692 -0.17775 0.35730 -0.75895 -0.09392 0.64434 0.80866 -0.58753 -0.02958 -0.53838 0.09493 0.83734 -0.95097 -0.30901 0.01278 -0.86472 -0.49926 0.05473 -0.80914 -0.46717 0.35642 -0.65939 -0.38072 0.64827 -0.80913 -0.46718 0.35644 -0.65941 -0.38071 0.64826 -0.43120 -0.24897 0.86722 -0.80866 -0.58753 -0.02958 -0.64128 -0.76422 0.06881 -0.60058 -0.71572 0.35643 -0.60060 -0.71571 0.35642 -0.48945 -0.58326 0.64826 -0.28989 -0.34544 0.89254 -0.48944 -0.58327 0.64827 -0.49966 -0.86545 -0.03660 -0.31955 -0.87798 0.35642 -0.34121 -0.93747 0.06881 -0.26040 -0.71550 0.64827 -0.31953 -0.87798 0.35644 -0.10449 -0.99409 -0.02959 0.00000 -0.99850 0.05473 0.00000 -0.93432 0.35644 0.00000 -0.93432 0.35644 0.00000 -0.65858 0.75251 0.00000 -0.65858 0.75251 0.00000 -0.36144 0.93239 -0.08131 -0.46116 0.88358 -0.00000 -0.00000 1.00000 0.31955 -0.87797 0.35644 0.31954 -0.87798 0.35643 0.26042 -0.71551 0.64825 0.64128 -0.76422 0.06882 0.60058 -0.71572 0.35644 0.48944 -0.58328 0.64825 1.00000 0.00000 0.00101 0.98655 -0.14180 0.08135 0.34197 -0.93958 -0.01567 0.40473 -0.90904 -0.09916 -0.70585 -0.70586 0.05951 -0.79801 -0.57980 0.16435 -0.36980 -0.52149 -0.76896 -0.13804 -0.33996 -0.93025 -0.21598 -0.34123 -0.91483 -0.13938 -0.86261 -0.48629 -0.07283 -0.68476 -0.72513 -0.40615 -0.79712 -0.44682 -0.46051 -0.74162 -0.48778 -0.18784 -0.55980 -0.80706 -0.39250 -0.49426 -0.77566 0.67080 0.56710 -0.47794 0.92989 0.36512 -0.04451 0.80056 0.59863 0.02731 0.78489 0.59931 -0.15741 0.75565 0.62380 -0.19963 0.87564 -0.00807 -0.48290 0.94263 -0.00416 -0.33382 0.89592 0.28578 -0.34009 0.79515 0.40515 -0.45121 0.64712 0.64714 -0.40305 0.91159 0.35315 -0.21046 0.91005 0.29055 -0.29561 0.34281 0.60552 -0.71822 -0.10863 0.80172 -0.58775 -0.04631 0.34671 -0.93683 0.12016 0.21348 -0.96953 0.24246 0.15907 -0.95703 0.40296 -0.01639 -0.91507 0.69942 -0.02972 -0.71409 0.72819 -0.00000 -0.68538 0.57603 0.38022 -0.72362 0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.01762 -0.02100 0.99962 -0.31268 -0.12187 0.94201 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 3 1 4 1 5 2 4 2 3 2 9 3 10 3 11 3 12 4 7 4 13 4 11 5 14 5 15 5 14 6 11 6 10 6 15 7 16 7 13 7 16 8 15 8 14 8 13 9 17 9 12 9 17 10 13 10 16 10 10 11 18 11 14 11 19 12 14 12 18 12 14 13 19 13 16 13 20 14 16 14 19 14 16 15 20 15 17 15 21 16 17 16 20 16 21 17 22 17 12 17 17 18 21 18 12 18 18 19 23 19 19 19 19 20 24 20 20 20 19 21 23 21 25 21 24 22 19 22 25 22 20 23 26 23 21 23 26 24 20 24 24 24 21 25 27 25 22 25 27 26 21 26 26 26 28 27 22 27 27 27 25 28 29 28 24 28 30 29 24 29 29 29 24 30 30 30 26 30 26 31 31 31 27 31 31 32 26 32 30 32 27 33 32 33 28 33 32 34 27 34 31 34 29 35 33 35 30 35 34 36 28 36 32 36 30 37 33 37 35 37 35 38 36 38 30 38 30 39 37 39 31 39 37 40 30 40 36 40 38 41 31 41 37 41 31 42 38 42 32 42 39 43 32 43 38 43 39 44 40 44 34 44 32 45 39 45 34 45 36 46 41 46 37 46 37 47 41 47 42 47 43 48 37 48 42 48 37 49 43 49 38 49 44 50 38 50 43 50 38 51 44 51 39 51 39 52 45 52 40 52 45 53 39 53 44 53 46 54 40 54 45 54 47 55 43 55 42 55 43 56 47 56 44 56 48 57 44 57 47 57 44 58 48 58 45 58 45 59 49 59 46 59 49 60 45 60 48 60 42 61 50 61 47 61 51 62 46 62 49 62 1 63 52 63 53 63 1 64 0 64 4 64 3 65 0 65 54 65 6 66 8 66 2 66 10 67 9 67 55 67 57 68 56 68 58 68 59 69 57 69 58 69 53 70 60 70 61 70 63 71 18 71 10 71 23 72 18 72 63 72 59 73 64 73 62 73 64 74 59 74 58 74 65 75 62 75 64 75 62 76 65 76 63 76 66 77 63 77 65 77 63 78 66 78 23 78 25 79 23 79 66 79 64 80 69 80 65 80 69 81 64 81 67 81 65 82 70 82 66 82 70 83 65 83 69 83 71 84 29 84 25 84 66 85 71 85 25 85 71 86 66 86 70 86 33 87 29 87 71 87 72 88 70 88 69 88 70 89 72 89 71 89 71 90 73 90 33 90 73 91 71 91 72 91 35 92 33 92 73 92 74 93 67 93 68 93 67 94 74 94 69 94 75 95 69 95 74 95 69 96 75 96 72 96 72 97 76 97 73 97 76 98 72 98 75 98 77 99 73 99 76 99 77 100 36 100 35 100 73 101 77 101 35 101 41 102 36 102 77 102 75 103 78 103 76 103 78 104 75 104 74 104 79 105 76 105 78 105 76 106 79 106 77 106 80 107 77 107 79 107 77 108 80 108 41 108 42 109 41 109 80 109 74 110 81 110 78 110 81 111 74 111 68 111 82 112 78 112 81 112 78 113 82 113 79 113 83 114 79 114 82 114 79 115 83 115 80 115 80 116 84 116 42 116 84 117 80 117 83 117 50 118 42 118 84 118 85 119 83 119 82 119 83 120 85 120 84 120 84 121 86 121 50 121 86 122 84 122 85 122 2 123 8 123 54 123 7 124 12 124 8 124 87 125 8 125 12 125 8 126 87 126 54 126 54 127 88 127 3 127 88 128 54 128 87 128 3 129 89 129 5 129 89 130 3 130 88 130 12 131 22 131 87 131 87 132 90 132 88 132 90 133 87 133 22 133 88 134 91 134 89 134 91 135 88 135 90 135 89 136 92 136 5 136 92 137 89 137 91 137 22 138 28 138 90 138 93 139 90 139 28 139 90 140 93 140 91 140 91 141 94 141 92 141 94 142 91 142 93 142 93 143 95 143 94 143 93 144 28 144 34 144 95 145 93 145 34 145 94 146 96 146 92 146 96 147 94 147 95 147 97 148 92 148 96 148 92 149 97 149 5 149 98 150 5 150 97 150 95 151 99 151 96 151 95 152 34 152 40 152 99 153 95 153 40 153 96 154 100 154 97 154 100 155 96 155 99 155 99 156 101 156 100 156 101 157 99 157 40 157 100 158 102 158 97 158 102 159 100 159 101 159 103 160 97 160 102 160 97 161 103 161 98 161 40 162 46 162 101 162 104 163 101 163 46 163 101 164 104 164 102 164 102 165 105 165 103 165 105 166 102 166 104 166 106 167 103 167 105 167 103 168 106 168 98 168 46 169 51 169 104 169 54 170 0 170 2 170 107 171 108 171 6 171 50 172 109 172 47 172 53 173 2 173 1 173 47 174 110 174 48 174 110 175 47 175 109 175 111 176 48 176 110 176 111 177 49 177 48 177 112 178 49 178 111 178 112 179 113 179 51 179 112 180 51 180 49 180 61 181 6 181 53 181 109 182 114 182 110 182 115 183 113 183 112 183 110 184 116 184 111 184 116 185 110 185 114 185 111 186 117 186 112 186 117 187 111 187 116 187 112 188 118 188 115 188 118 189 112 189 117 189 114 190 119 190 116 190 120 191 116 191 119 191 116 192 120 192 117 192 117 193 121 193 118 193 121 194 117 194 120 194 122 195 118 195 121 195 122 196 123 196 115 196 118 197 122 197 115 197 119 198 124 198 120 198 120 199 125 199 121 199 120 200 124 200 126 200 125 201 120 201 126 201 127 202 121 202 125 202 121 203 127 203 122 203 122 204 128 204 123 204 128 205 122 205 127 205 129 206 123 206 128 206 126 207 130 207 125 207 130 208 131 208 125 208 132 209 129 209 128 209 125 210 133 210 127 210 127 211 135 211 128 211 135 212 127 212 133 212 128 213 136 213 132 213 136 214 128 214 135 214 134 215 137 215 133 215 138 216 133 216 137 216 133 217 138 217 135 217 135 218 139 218 136 218 139 219 135 219 138 219 140 220 136 220 139 220 140 221 141 221 132 221 136 222 140 222 132 222 137 223 142 223 138 223 138 224 142 224 143 224 144 225 138 225 143 225 138 226 144 226 139 226 139 227 145 227 140 227 145 228 139 228 144 228 140 229 146 229 141 229 146 230 140 230 145 230 107 231 141 231 146 231 144 232 147 232 145 232 147 233 144 233 143 233 145 234 148 234 146 234 148 235 145 235 147 235 146 236 149 236 107 236 149 237 146 237 148 237 143 238 150 238 147 238 108 239 107 239 149 239 147 240 150 240 9 240 147 241 9 241 11 241 6 242 61 242 107 242 147 243 11 243 148 243 148 244 15 244 149 244 148 245 11 245 15 245 149 246 13 246 108 246 2 247 53 247 6 247 13 248 149 248 15 248 7 249 108 249 13 249 68 250 151 250 81 250 152 251 81 251 151 251 81 252 152 252 82 252 153 253 85 253 82 253 153 254 82 254 152 254 154 255 85 255 153 255 154 256 86 256 85 256 155 257 109 257 50 257 155 258 50 258 86 258 155 259 86 259 154 259 114 260 109 260 155 260 156 261 152 261 151 261 152 262 156 262 153 262 153 263 157 263 154 263 157 264 153 264 156 264 154 265 158 265 155 265 158 266 154 266 157 266 159 267 155 267 158 267 155 268 159 268 114 268 157 269 160 269 158 269 160 270 157 270 156 270 158 271 161 271 159 271 161 272 158 272 160 272 162 273 159 273 161 273 124 274 119 274 162 274 161 275 165 275 162 275 162 276 166 276 124 276 166 277 162 277 165 277 126 278 124 278 166 278 165 279 167 279 166 279 167 280 165 280 164 280 168 281 166 281 167 281 168 282 130 282 126 282 166 283 168 283 126 283 131 284 130 284 168 284 151 285 169 285 163 285 169 286 151 286 68 286 170 287 163 287 169 287 163 288 170 288 164 288 164 289 171 289 167 289 171 290 164 290 170 290 167 291 172 291 168 291 172 292 167 292 171 292 173 293 168 293 172 293 168 294 173 294 131 294 134 295 131 295 173 295 174 296 170 296 169 296 170 297 174 297 171 297 171 298 175 298 172 298 175 299 171 299 174 299 172 300 176 300 173 300 176 301 172 301 175 301 177 302 173 302 176 302 177 303 137 303 134 303 173 304 177 304 134 304 142 305 137 305 177 305 178 306 175 306 174 306 175 307 178 307 176 307 179 308 176 308 178 308 176 309 179 309 177 309 180 310 177 310 179 310 177 311 180 311 142 311 143 312 142 312 180 312 181 313 174 313 169 313 174 314 181 314 178 314 178 315 182 315 179 315 182 316 178 316 181 316 183 317 179 317 182 317 179 318 183 318 180 318 180 319 184 319 143 319 184 320 180 320 183 320 150 321 143 321 184 321 169 322 68 322 58 322 182 323 56 323 183 323 183 324 55 324 184 324 184 325 55 325 150 325 9 326 150 326 55 326 51 327 113 327 104 327 185 328 105 328 104 328 185 329 104 329 113 329 52 330 1 330 4 330 105 331 186 331 106 331 186 332 105 332 185 332 187 333 106 333 186 333 141 334 107 334 61 334 188 335 98 335 187 335 113 336 115 336 185 336 189 337 185 337 115 337 185 338 189 338 186 338 186 339 190 339 187 339 190 340 186 340 189 340 191 341 187 341 190 341 187 342 191 342 188 342 115 343 123 343 189 343 192 344 189 344 123 344 189 345 192 345 190 345 193 346 190 346 192 346 190 347 193 347 191 347 191 348 194 348 188 348 194 349 191 349 193 349 123 350 129 350 192 350 192 351 195 351 193 351 195 352 192 352 129 352 193 353 196 353 194 353 196 354 193 354 195 354 195 355 129 355 132 355 197 356 195 356 132 356 195 357 197 357 196 357 198 358 196 358 197 358 196 359 198 359 194 359 52 360 194 360 198 360 194 361 52 361 188 361 4 362 188 362 52 362 188 363 4 363 98 363 197 364 199 364 198 364 60 365 198 365 199 365 198 366 60 366 52 366 61 367 199 367 141 367 199 368 61 368 60 368 60 369 53 369 52 369 7 370 8 370 108 370 6 371 108 371 8 371 132 372 199 372 197 372 132 373 141 373 199 373 119 374 159 374 162 374 114 375 159 375 119 375 156 376 200 376 160 376 163 377 200 377 151 377 200 378 156 378 151 378 164 379 165 379 201 379 163 380 164 380 201 380 161 381 201 381 165 381 160 382 201 382 161 382 163 383 201 383 200 383 160 384 200 384 201 384 62 385 202 385 59 385 55 386 203 386 10 386 203 387 63 387 10 387 63 388 203 388 202 388 63 389 202 389 62 389 56 390 204 390 183 390 204 391 55 391 183 391 56 392 202 392 204 392 56 393 57 393 202 393 57 394 59 394 202 394 55 395 202 395 203 395 55 396 204 396 202 396 58 397 205 397 64 397 205 398 67 398 64 398 67 399 205 399 68 399 205 400 58 400 68 400 58 401 206 401 169 401 206 402 181 402 169 402 181 403 206 403 182 403 182 404 206 404 56 404 206 405 58 405 56 405 131 406 134 406 133 406 125 407 131 407 133 407 4 408 5 408 98 408 98 409 106 409 187 409

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E2M3.dae b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E2M3.dae new file mode 100644 index 0000000..5e7a25d --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E2M3.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:18.666034 + 2012-07-23T02:14:18.666047 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + 6.56299 -2.38277 47.24268 5.35263 -4.47927 47.24261 8.87247 -3.22337 44.39990 6.60916 0.00113 47.53578 2.84679 -2.37657 49.09227 2.54221 1.39790 49.16618 10.14795 -3.68767 40.89576 10.66138 2.26448 37.15411 10.65737 -0.00554 41.13606 12.34216 2.62174 3.91527 11.52786 5.12782 3.91527 11.01634 0.00113 12.12860 9.95809 4.42892 37.15411 10.15396 0.00113 28.83627 8.87557 6.44006 12.12189 10.19228 0.00113 20.46215 8.19527 5.94582 20.45875 8.17780 5.93308 28.83789 8.44714 9.36806 3.91528 6.45203 8.86355 12.12188 5.95784 8.18330 20.45874 5.94505 8.16576 28.83790 7.29732 8.09110 37.15418 6.31535 10.91690 3.91528 3.39832 10.41953 12.12189 3.90808 11.98867 3.91527 3.13846 9.61985 20.45875 3.13175 9.59923 28.83789 3.37712 10.35445 37.15417 1.33067 12.53653 3.91528 -3.37208 10.41953 12.12189 -3.11222 9.61985 20.45875 -3.10550 9.59923 28.83789 -1.30443 12.53653 3.91528 -1.12475 10.82762 37.15418 -3.88184 11.98867 3.91527 -6.28911 10.91690 3.91528 -6.42579 8.86355 12.12189 -5.93160 8.18330 20.45875 -5.91880 8.16576 28.83789 -7.27106 8.09110 37.15418 -8.42090 9.36806 3.91528 -11.50162 5.12782 3.91528 -8.84933 6.44006 12.12189 -8.16902 5.94582 20.45875 -8.15156 5.93308 28.83789 -9.93184 4.42892 37.15411 -10.99010 0.00113 12.12860 -10.16603 0.00113 20.46214 -10.12771 0.00113 28.83627 -12.59134 0.00113 3.91535 -10.63514 2.26448 37.15411 3.49825 -6.03527 47.24268 7.23523 -6.05897 44.39990 9.67970 -0.00886 44.25639 12.91713 1.09479 -0.14384 9.76257 3.16892 -7.26175 8.30649 6.02662 -7.26175 4.71547 5.68328 -9.95829 6.03859 8.29450 -7.26168 4.72706 -8.16367 44.39983 8.27510 -6.93147 40.89576 7.16706 9.84777 -3.83483 7.64245 10.50204 0.00908 3.18089 9.75057 -7.26168 3.77422 11.57655 -3.83483 4.02411 12.34569 0.00914 -2.27218 7.03446 -9.95872 -3.11307 2.27245 -11.67954 -3.15472 9.75057 -7.26175 0.01312 12.17225 -3.83483 0.01312 12.98097 0.00914 -3.74798 11.57655 -3.83482 -3.99787 12.34569 0.00915 -5.64170 4.78556 -9.95684 -6.01242 8.29450 -7.26175 -7.14089 9.84777 -3.83490 -7.61621 10.50204 0.00908 -8.28025 6.02662 -7.26175 -9.83349 7.15513 -3.83482 -10.48777 7.63049 0.00908 -6.82884 2.31377 -9.95810 -9.73633 3.16892 -7.26175 -11.56236 3.76221 -3.83482 -12.33148 4.01212 0.00908 -12.08549 0.03693 -3.51346 -12.75930 -0.06820 -0.00748 8.27510 6.93376 40.89576 7.23524 6.06125 44.39990 5.35263 4.48149 47.24261 5.40581 9.34144 40.89576 4.72706 8.16591 44.39983 3.49824 6.03750 47.24268 1.88597 10.62254 40.89576 1.65022 9.28577 44.39990 -1.85971 10.62254 40.89576 -1.62397 9.28577 44.39990 -1.19723 6.86544 47.24269 -2.82054 2.37884 49.09227 -5.37955 9.34144 40.89577 -4.70088 8.16591 44.39990 -8.24885 6.93376 40.89577 -7.20898 6.06125 44.39991 -5.32638 4.48149 47.24262 -10.61057 1.65543 40.89317 -9.63732 1.11884 44.52992 -6.58291 0.00113 47.53579 9.95809 -4.42667 37.15411 10.66138 -2.26227 37.15411 -12.31592 -2.61947 3.91528 -10.40525 -3.38397 12.12189 -9.60558 -3.12417 20.45875 -9.58500 -3.11747 28.83789 -10.63514 -2.26227 37.15411 -11.50162 -5.12557 3.91528 -9.93184 -4.42667 37.15411 -8.84933 -6.43777 12.12189 -8.16902 -5.94357 20.45875 -8.15156 -5.93087 28.83789 -8.42090 -9.36577 3.91528 -6.42579 -8.86127 12.12189 -5.93160 -8.18107 20.45875 -5.91880 -8.16347 28.83789 -7.27106 -8.08887 37.15418 -6.28911 -10.91467 3.91528 -3.37208 -10.41727 12.12189 -3.88184 -11.98637 3.91528 -3.11222 -9.61757 20.45875 -3.10550 -9.59697 28.83789 -3.35086 -10.35217 37.15417 -1.30443 -12.53427 3.91528 1.33067 -12.53427 3.91528 1.15100 -10.82537 37.15418 3.39832 -10.41727 12.12189 3.90808 -11.98637 3.91528 3.13846 -9.61757 20.45875 3.13175 -9.59697 28.83789 6.31535 -10.91467 3.91528 6.45203 -8.86127 12.12188 5.95784 -8.18107 20.45874 5.94505 -8.16347 28.83790 7.29732 -8.08887 37.15418 8.44714 -9.36577 3.91528 11.52786 -5.12557 3.91527 8.87557 -6.43777 12.12189 8.19527 -5.94357 20.45875 8.17780 -5.93087 28.83789 10.43149 -3.38397 12.12188 9.63183 -3.12417 20.45875 9.61125 -3.11747 28.83790 12.34216 -2.61947 3.91527 -3.66193 -1.19297 -11.67954 -6.96572 -1.29969 -9.95652 -9.73633 -3.16667 -7.26174 -11.64271 -3.81134 -3.89589 -12.33148 -4.00987 0.00908 -5.96978 -4.34567 -9.95872 -8.28025 -6.02437 -7.26175 -9.83349 -7.15287 -3.83482 -10.48777 -7.62827 0.00908 -6.01242 -8.29227 -7.26175 -7.14089 -9.84547 -3.83490 -7.61621 -10.49977 0.00908 0.01312 -7.39417 -9.95865 0.01312 -10.25007 -7.26175 -3.74798 -11.57427 -3.83482 -3.99787 -12.34347 0.00915 0.01312 -12.16997 -3.83483 0.01312 -12.97867 0.00915 3.13931 -2.27017 -11.67954 2.29842 -7.03217 -9.95873 3.18089 -9.74827 -7.26168 3.77422 -11.57427 -3.83483 4.02411 -12.34347 0.00915 5.99602 -4.34567 -9.95873 6.03859 -8.29227 -7.26168 7.16706 -9.84547 -3.83483 7.64245 -10.49977 0.00908 8.30649 -6.02437 -7.26175 9.85972 -7.15287 -3.83483 10.51401 -7.62827 0.00907 7.04650 -2.28417 -9.95872 9.76257 -3.16667 -7.26175 11.58860 -3.75997 -3.83483 12.35772 -4.00987 0.00907 -10.12170 -3.68767 40.89577 -8.84622 -3.22337 44.39991 -6.53674 -2.38277 47.24269 -3.46287 -1.26402 49.09227 -8.24885 -6.93147 40.89577 -7.20898 -6.05897 44.39991 -5.32638 -4.47927 47.24262 -5.37955 -9.33917 40.89577 -4.70088 -8.16367 44.39991 -3.47199 -6.03527 47.24269 -1.85971 -10.62027 40.89576 -1.62397 -9.28347 44.39991 1.88597 -10.62027 40.89576 1.65022 -9.28347 44.39990 5.40581 -9.33917 40.89576 -3.19907 -6.56849 -9.78374 -3.78335 -9.39795 -7.68514 9.97586 6.39629 -3.98794 10.94574 6.09801 -0.28748 11.56665 1.44050 -3.96156 1.44190 7.54037 -9.95509 7.22986 1.88477 -9.95264 + + + + + + + + + + 0.65940 -0.38071 0.64827 0.44231 -0.11788 0.88908 0.37567 0.01217 0.92667 0.92219 0.29965 0.24447 0.94159 0.30595 -0.14069 0.94475 0.31420 0.09342 0.91917 0.30586 0.24816 0.94793 0.31844 0.00434 0.94357 0.31703 0.09579 0.93878 0.31278 -0.14440 0.94874 0.31606 0.00246 0.79790 0.57971 0.16518 0.69125 0.69126 0.21055 0.70362 0.70363 0.09913 0.70363 0.70362 0.09912 0.70711 0.70710 0.00255 0.70709 0.70712 0.00256 0.80264 0.58316 -0.12528 0.70690 0.70692 -0.02347 0.57718 0.79441 0.18915 0.45176 0.88661 0.09912 0.39708 0.89187 0.21654 0.44530 0.87394 0.19476 0.45399 0.89100 0.00256 0.45176 0.88662 0.09913 0.45302 0.88908 -0.06568 0.45399 0.89100 0.00256 0.49784 0.86227 -0.09299 0.20388 0.95916 0.19606 -0.00000 0.96830 0.24979 -0.00000 0.99543 0.09548 -0.00000 1.00000 0.00246 -0.00000 0.99543 0.09548 -0.00000 0.99590 -0.09044 -0.00000 1.00000 0.00246 -0.00000 0.96830 0.24979 0.10302 0.98016 -0.16932 -0.20388 0.95916 0.19606 -0.39884 0.89582 0.19606 -0.45176 0.88661 0.09913 -0.44382 0.87103 0.21055 -0.45176 0.88662 0.09912 -0.45399 0.89100 0.00256 -0.45399 0.89100 0.00256 -0.40606 0.91202 -0.05784 -0.45387 0.89076 -0.02347 -0.57718 0.79441 0.18915 -0.78794 0.57248 0.22675 -0.70243 0.70245 0.11470 -0.70362 0.70363 0.09912 -0.70363 0.70362 0.09913 -0.70711 0.70710 0.00256 -0.70296 0.70298 -0.10799 -0.70709 0.70712 0.00255 -0.80721 0.58648 -0.06672 -0.91917 0.30586 0.24816 -0.94454 0.31413 0.09570 -0.94379 0.31710 0.09333 -0.94794 0.31844 0.00246 -0.93878 0.31278 -0.14440 -0.94873 0.31606 0.00434 -0.96083 0.20424 0.18732 -0.94159 0.30595 -0.14069 0.48944 -0.58327 0.64826 0.43121 -0.24898 0.86722 0.72633 -0.09772 0.68037 0.92235 -0.15082 0.35571 0.95089 0.30897 0.01846 0.55814 0.28439 -0.77949 0.49213 0.49216 -0.71804 0.60058 -0.71572 0.35643 0.80901 0.58778 0.00398 0.58402 0.80383 0.11304 0.39723 0.77961 -0.48418 0.30759 0.60369 -0.73549 0.39723 0.77960 -0.48418 0.44450 0.87237 -0.20346 0.44450 0.87237 -0.20345 0.45319 0.88943 0.05951 0.40489 0.90940 0.09515 0.00000 0.88253 -0.47025 0.00001 0.70460 -0.70960 0.15316 0.96703 -0.20345 0.11963 0.75532 -0.64434 0.20774 0.97732 0.04113 0.15573 0.98327 0.09450 0.15316 0.96703 -0.20345 0.00000 0.99359 0.11305 -0.13688 0.86420 -0.48417 -0.15316 0.96703 -0.20345 -0.15616 0.98594 0.05951 -0.15316 0.96703 -0.20345 -0.20697 0.97371 0.09515 -0.24580 0.36753 -0.89694 -0.38907 0.58234 -0.71379 -0.28744 0.56414 -0.77403 -0.39723 0.77961 -0.48417 -0.44449 0.87237 -0.20345 -0.39722 0.77961 -0.48417 -0.44450 0.87237 -0.20345 -0.40639 0.91278 0.04112 -0.45196 0.88702 0.09450 -0.58402 0.80383 0.11304 -0.61871 0.61869 -0.48417 -0.49555 0.49554 -0.71335 -0.61871 0.61869 -0.48417 -0.69233 0.69231 -0.20344 -0.69232 0.69232 -0.20346 -0.70585 0.70585 0.05950 -0.79802 0.57979 0.16434 -0.61172 0.29417 -0.73435 -0.41027 0.19750 -0.89032 -0.59794 0.30467 -0.74138 -0.77961 0.39723 -0.48417 -0.77959 0.39724 -0.48418 -0.87236 0.44451 -0.20346 -0.88942 0.45320 0.05951 -0.87237 0.44451 -0.20345 -0.96755 0.20566 0.14681 -0.87370 0.08131 -0.47963 -0.97207 0.11906 -0.20224 -0.99374 0.10403 0.04071 -0.97735 0.10322 -0.18474 0.93079 -0.22073 0.29140 0.93648 0.30429 0.17441 0.92480 0.32437 0.19882 0.90394 0.32014 0.28356 0.70371 0.26783 0.65808 0.87353 0.34362 0.34478 0.41766 0.17547 0.89150 0.73848 0.24813 0.62696 0.80866 0.58753 -0.02959 0.60058 0.71572 0.35643 0.64127 0.76422 0.06880 0.48942 0.58328 0.64827 0.60057 0.71573 0.35644 0.26933 0.32094 0.90800 0.48945 0.58327 0.64825 0.49967 0.86544 -0.03661 0.34121 0.93747 0.06881 0.31955 0.87797 0.35644 0.26043 0.71550 0.64826 0.31956 0.87797 0.35643 -0.00000 0.93432 0.35643 0.10448 0.99409 -0.02959 0.00000 0.99850 0.05473 -0.00000 0.65858 0.75251 0.00000 0.93432 0.35643 0.13478 0.76436 0.63054 0.06535 0.37063 0.92648 0.05375 0.36390 0.92989 -0.31955 0.87798 0.35643 -0.40656 0.91314 -0.02981 -0.33866 0.93047 -0.13974 -0.26041 0.71550 0.64826 -0.31955 0.87798 0.35643 -0.60058 0.71573 0.35642 -0.64127 0.76422 0.06880 -0.42333 0.50448 0.75252 -0.60059 0.71572 0.35644 -0.38808 0.67216 0.63055 -0.25780 0.44650 0.85684 -0.80866 0.58754 -0.02959 -0.90435 0.40457 0.13593 -0.85543 0.38258 0.34911 -0.67924 0.35069 0.64471 -0.85533 0.42793 0.29204 -0.63950 0.22740 0.73439 -0.47521 0.18950 0.85922 -0.94953 0.30853 0.05650 0.74314 -0.15758 0.65032 0.95097 -0.30900 0.01278 -0.97634 -0.10261 0.19035 0.65940 -0.38073 0.64826 -0.98072 -0.16963 0.09698 -0.96361 -0.16690 0.20880 -0.97940 -0.17574 0.09942 -0.98429 -0.17652 0.00451 -0.98519 -0.17144 0.00256 -0.99212 -0.00000 -0.12528 -0.98510 -0.17144 -0.01345 0.80914 -0.46717 0.35644 -0.93388 -0.30345 0.18916 -0.94736 -0.30783 -0.08797 -0.88663 -0.45174 0.09912 -0.87104 -0.44380 0.21055 -0.89100 -0.45399 0.00255 -0.88662 -0.45175 0.09913 -0.88580 -0.45132 -0.10799 -0.89101 -0.45398 0.00255 -0.79790 -0.57972 0.16518 -0.69125 -0.69126 0.21054 -0.70362 -0.70363 0.09913 -0.70712 -0.70709 0.00255 -0.70364 -0.70361 0.09912 -0.70708 -0.70713 0.00257 -0.80264 -0.58316 -0.12528 -0.70689 -0.70694 -0.02346 -0.57719 -0.79440 0.18916 -0.45177 -0.88661 0.09912 -0.39706 -0.89188 0.21655 -0.44531 -0.87394 0.19476 -0.45174 -0.88662 0.09913 -0.45398 -0.89101 0.00257 -0.45302 -0.88908 -0.06569 -0.45400 -0.89100 0.00255 -0.49783 -0.86228 -0.09299 -0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.10408 -0.99021 -0.09299 0.00000 -0.99543 0.09549 0.00000 -1.00000 0.00246 0.00000 -0.99543 0.09549 0.00000 -0.98927 -0.14612 0.00000 -1.00000 0.00246 0.39882 -0.89583 0.19605 0.44383 -0.87103 0.21055 0.45177 -0.88661 0.09913 0.45398 -0.89101 0.00255 0.45174 -0.88662 0.09912 0.45400 -0.89100 0.00256 0.40605 -0.91202 -0.05785 0.45388 -0.89075 -0.02347 0.57719 -0.79440 0.18916 0.78794 -0.57248 0.22675 0.70243 -0.70245 0.11470 0.70362 -0.70363 0.09912 0.70711 -0.70709 0.00256 0.70363 -0.70361 0.09913 0.70295 -0.70300 -0.10800 0.70708 -0.70713 0.00255 0.80721 -0.58648 -0.06672 0.88663 -0.45174 0.09913 0.87104 -0.44380 0.21055 0.89100 -0.45399 0.00255 0.88662 -0.45176 0.09912 0.88580 -0.45132 -0.10799 0.89101 -0.45398 0.00255 0.93388 -0.30345 0.18916 0.94737 -0.30783 -0.08797 0.97395 0.00000 0.22676 0.98001 -0.16953 0.10411 0.86472 -0.49926 0.05473 0.98049 -0.16960 0.09933 0.98429 -0.17651 0.00256 0.97965 -0.17578 0.09687 0.97962 -0.17053 -0.10616 0.80914 -0.46718 0.35642 0.98518 -0.17144 0.00451 0.99814 0.00000 -0.06089 -0.41883 0.06633 -0.90564 -0.46278 0.01714 -0.88630 -0.67576 0.02528 -0.73669 -0.84734 -0.00000 -0.53105 -0.69723 -0.00000 -0.71685 -0.86492 -0.04989 -0.49943 -0.97720 -0.09349 -0.19061 -0.99368 -0.10443 0.04113 -0.99320 -0.10761 0.04443 -0.97821 -0.10692 -0.17798 -0.94496 -0.30704 0.11305 -0.45359 -0.14768 -0.87889 -0.61097 -0.19921 -0.76618 -0.76686 -0.39073 -0.50918 -0.61575 -0.31374 -0.72279 -0.86424 -0.47115 -0.17639 -0.76482 -0.42298 -0.48594 -0.87236 -0.44450 -0.20346 -0.88942 -0.45319 0.05951 -0.61871 -0.61869 -0.48417 -0.48867 -0.48865 -0.72279 -0.69232 -0.69231 -0.20346 -0.61871 -0.61870 -0.48416 -0.69231 -0.69232 -0.20345 -0.58403 -0.80382 0.11304 -0.44450 -0.87237 -0.20345 -0.45320 -0.88942 0.05950 -0.44450 -0.87236 -0.20346 -0.40486 -0.90941 0.09517 -0.15316 -0.96703 -0.20346 -0.13688 -0.86421 -0.48416 -0.15314 -0.96703 -0.20345 -0.20776 -0.97732 0.04111 -0.15571 -0.98327 0.09452 0.00000 -0.99359 0.11304 -0.04633 -0.29252 -0.95514 -0.00000 0.00000 -1.00000 0.05508 -0.34793 -0.93590 0.10810 -0.68256 -0.72280 0.13691 -0.86420 -0.48416 0.10814 -0.68257 -0.72277 0.15316 -0.96703 -0.20345 0.13688 -0.86419 -0.48418 0.15314 -0.96703 -0.20346 0.15614 -0.98594 0.05950 0.20699 -0.97370 0.09517 0.26805 -0.36893 -0.88996 0.41417 -0.57005 -0.70959 0.39721 -0.77961 -0.48419 0.27533 -0.54039 -0.79510 0.44451 -0.87236 -0.20346 0.39724 -0.77960 -0.48416 0.44450 -0.87236 -0.20347 0.40636 -0.91279 0.04111 0.45197 -0.88701 0.09452 0.58403 -0.80382 0.11304 0.48865 -0.48867 -0.72279 0.61869 -0.61871 -0.48416 0.61870 -0.61871 -0.48416 0.69231 -0.69232 -0.20347 0.69231 -0.69232 -0.20346 0.70585 -0.70586 0.05951 0.79801 -0.57980 0.16435 0.39424 -0.20089 -0.89678 0.61573 -0.31376 -0.72279 0.77961 -0.39723 -0.48416 0.61576 -0.31374 -0.72278 0.77959 -0.39725 -0.48418 0.87236 -0.44452 -0.20346 0.88942 -0.45319 0.05951 0.87237 -0.44450 -0.20345 0.94496 -0.30704 0.11305 0.13383 0.18421 -0.97373 0.88253 -0.00000 -0.47026 0.97289 -0.11267 -0.20199 0.99330 -0.10759 0.04225 0.99012 -0.00000 0.14025 -0.99998 0.00000 0.00657 -0.96541 -0.08821 0.24534 -0.99071 -0.09060 0.10143 0.32007 -0.38142 0.86722 -0.72094 -0.15159 0.67621 -0.91692 -0.17775 0.35730 -0.75895 -0.09392 0.64434 0.80866 -0.58753 -0.02958 -0.53838 0.09493 0.83734 -0.95097 -0.30901 0.01278 -0.86472 -0.49926 0.05473 -0.80914 -0.46717 0.35642 -0.65939 -0.38072 0.64827 -0.80913 -0.46718 0.35644 -0.65941 -0.38071 0.64826 -0.43120 -0.24897 0.86722 -0.80866 -0.58753 -0.02958 -0.64128 -0.76422 0.06881 -0.60058 -0.71572 0.35643 -0.60060 -0.71571 0.35642 -0.48945 -0.58326 0.64826 -0.28989 -0.34544 0.89254 -0.48944 -0.58327 0.64827 -0.49966 -0.86545 -0.03660 -0.31955 -0.87798 0.35642 -0.34121 -0.93747 0.06881 -0.26040 -0.71550 0.64827 -0.31953 -0.87798 0.35644 -0.10449 -0.99409 -0.02959 0.00000 -0.99850 0.05473 0.00000 -0.93432 0.35644 0.00000 -0.93432 0.35644 0.00000 -0.65858 0.75251 0.00000 -0.65858 0.75251 0.00000 -0.36144 0.93239 -0.08131 -0.46116 0.88358 -0.00000 -0.00000 1.00000 0.31955 -0.87797 0.35644 0.31954 -0.87798 0.35643 0.26042 -0.71551 0.64825 0.64128 -0.76422 0.06882 0.60058 -0.71572 0.35644 0.48944 -0.58328 0.64825 1.00000 0.00000 0.00101 0.98655 -0.14180 0.08135 0.34197 -0.93958 -0.01567 0.40473 -0.90904 -0.09916 -0.70585 -0.70586 0.05951 -0.79801 -0.57980 0.16435 -0.36980 -0.52149 -0.76896 -0.13804 -0.33996 -0.93025 -0.21598 -0.34123 -0.91483 -0.13938 -0.86261 -0.48629 -0.07283 -0.68476 -0.72513 -0.40615 -0.79712 -0.44682 -0.46051 -0.74162 -0.48778 -0.18784 -0.55980 -0.80706 -0.39250 -0.49426 -0.77566 0.67080 0.56710 -0.47794 0.92989 0.36512 -0.04451 0.80056 0.59863 0.02731 0.78489 0.59931 -0.15741 0.75565 0.62380 -0.19963 0.87564 -0.00807 -0.48290 0.94263 -0.00416 -0.33382 0.89592 0.28578 -0.34009 0.79515 0.40515 -0.45121 0.64712 0.64714 -0.40305 0.91159 0.35315 -0.21046 0.91005 0.29055 -0.29561 0.34281 0.60552 -0.71822 -0.10863 0.80172 -0.58775 -0.04631 0.34671 -0.93683 0.12016 0.21348 -0.96953 0.24246 0.15907 -0.95703 0.40296 -0.01639 -0.91507 0.69942 -0.02972 -0.71409 0.72819 -0.00000 -0.68538 0.57603 0.38022 -0.72362 0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.01762 -0.02100 0.99962 -0.31268 -0.12187 0.94201 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 3 1 4 1 5 2 4 2 3 2 9 3 10 3 11 3 12 4 7 4 13 4 11 5 14 5 15 5 14 6 11 6 10 6 15 7 16 7 13 7 16 8 15 8 14 8 13 9 17 9 12 9 17 10 13 10 16 10 10 11 18 11 14 11 19 12 14 12 18 12 14 13 19 13 16 13 20 14 16 14 19 14 16 15 20 15 17 15 21 16 17 16 20 16 21 17 22 17 12 17 17 18 21 18 12 18 18 19 23 19 19 19 19 20 24 20 20 20 19 21 23 21 25 21 24 22 19 22 25 22 20 23 26 23 21 23 26 24 20 24 24 24 21 25 27 25 22 25 27 26 21 26 26 26 28 27 22 27 27 27 25 28 29 28 24 28 30 29 24 29 29 29 24 30 30 30 26 30 26 31 31 31 27 31 31 32 26 32 30 32 27 33 32 33 28 33 32 34 27 34 31 34 29 35 33 35 30 35 34 36 28 36 32 36 30 37 33 37 35 37 35 38 36 38 30 38 30 39 37 39 31 39 37 40 30 40 36 40 38 41 31 41 37 41 31 42 38 42 32 42 39 43 32 43 38 43 39 44 40 44 34 44 32 45 39 45 34 45 36 46 41 46 37 46 37 47 41 47 42 47 43 48 37 48 42 48 37 49 43 49 38 49 44 50 38 50 43 50 38 51 44 51 39 51 39 52 45 52 40 52 45 53 39 53 44 53 46 54 40 54 45 54 47 55 43 55 42 55 43 56 47 56 44 56 48 57 44 57 47 57 44 58 48 58 45 58 45 59 49 59 46 59 49 60 45 60 48 60 42 61 50 61 47 61 51 62 46 62 49 62 1 63 52 63 53 63 1 64 0 64 4 64 3 65 0 65 54 65 6 66 8 66 2 66 10 67 9 67 55 67 57 68 56 68 58 68 59 69 57 69 58 69 53 70 60 70 61 70 63 71 18 71 10 71 23 72 18 72 63 72 59 73 64 73 62 73 64 74 59 74 58 74 65 75 62 75 64 75 62 76 65 76 63 76 66 77 63 77 65 77 63 78 66 78 23 78 25 79 23 79 66 79 64 80 69 80 65 80 69 81 64 81 67 81 65 82 70 82 66 82 70 83 65 83 69 83 71 84 29 84 25 84 66 85 71 85 25 85 71 86 66 86 70 86 33 87 29 87 71 87 72 88 70 88 69 88 70 89 72 89 71 89 71 90 73 90 33 90 73 91 71 91 72 91 35 92 33 92 73 92 74 93 67 93 68 93 67 94 74 94 69 94 75 95 69 95 74 95 69 96 75 96 72 96 72 97 76 97 73 97 76 98 72 98 75 98 77 99 73 99 76 99 77 100 36 100 35 100 73 101 77 101 35 101 41 102 36 102 77 102 75 103 78 103 76 103 78 104 75 104 74 104 79 105 76 105 78 105 76 106 79 106 77 106 80 107 77 107 79 107 77 108 80 108 41 108 42 109 41 109 80 109 74 110 81 110 78 110 81 111 74 111 68 111 82 112 78 112 81 112 78 113 82 113 79 113 83 114 79 114 82 114 79 115 83 115 80 115 80 116 84 116 42 116 84 117 80 117 83 117 50 118 42 118 84 118 85 119 83 119 82 119 83 120 85 120 84 120 84 121 86 121 50 121 86 122 84 122 85 122 2 123 8 123 54 123 7 124 12 124 8 124 87 125 8 125 12 125 8 126 87 126 54 126 54 127 88 127 3 127 88 128 54 128 87 128 3 129 89 129 5 129 89 130 3 130 88 130 12 131 22 131 87 131 87 132 90 132 88 132 90 133 87 133 22 133 88 134 91 134 89 134 91 135 88 135 90 135 89 136 92 136 5 136 92 137 89 137 91 137 22 138 28 138 90 138 93 139 90 139 28 139 90 140 93 140 91 140 91 141 94 141 92 141 94 142 91 142 93 142 93 143 95 143 94 143 93 144 28 144 34 144 95 145 93 145 34 145 94 146 96 146 92 146 96 147 94 147 95 147 97 148 92 148 96 148 92 149 97 149 5 149 98 150 5 150 97 150 95 151 99 151 96 151 95 152 34 152 40 152 99 153 95 153 40 153 96 154 100 154 97 154 100 155 96 155 99 155 99 156 101 156 100 156 101 157 99 157 40 157 100 158 102 158 97 158 102 159 100 159 101 159 103 160 97 160 102 160 97 161 103 161 98 161 40 162 46 162 101 162 104 163 101 163 46 163 101 164 104 164 102 164 102 165 105 165 103 165 105 166 102 166 104 166 106 167 103 167 105 167 103 168 106 168 98 168 46 169 51 169 104 169 54 170 0 170 2 170 107 171 108 171 6 171 50 172 109 172 47 172 53 173 2 173 1 173 47 174 110 174 48 174 110 175 47 175 109 175 111 176 48 176 110 176 111 177 49 177 48 177 112 178 49 178 111 178 112 179 113 179 51 179 112 180 51 180 49 180 61 181 6 181 53 181 109 182 114 182 110 182 115 183 113 183 112 183 110 184 116 184 111 184 116 185 110 185 114 185 111 186 117 186 112 186 117 187 111 187 116 187 112 188 118 188 115 188 118 189 112 189 117 189 114 190 119 190 116 190 120 191 116 191 119 191 116 192 120 192 117 192 117 193 121 193 118 193 121 194 117 194 120 194 122 195 118 195 121 195 122 196 123 196 115 196 118 197 122 197 115 197 119 198 124 198 120 198 120 199 125 199 121 199 120 200 124 200 126 200 125 201 120 201 126 201 127 202 121 202 125 202 121 203 127 203 122 203 122 204 128 204 123 204 128 205 122 205 127 205 129 206 123 206 128 206 126 207 130 207 125 207 130 208 131 208 125 208 132 209 129 209 128 209 125 210 133 210 127 210 127 211 135 211 128 211 135 212 127 212 133 212 128 213 136 213 132 213 136 214 128 214 135 214 134 215 137 215 133 215 138 216 133 216 137 216 133 217 138 217 135 217 135 218 139 218 136 218 139 219 135 219 138 219 140 220 136 220 139 220 140 221 141 221 132 221 136 222 140 222 132 222 137 223 142 223 138 223 138 224 142 224 143 224 144 225 138 225 143 225 138 226 144 226 139 226 139 227 145 227 140 227 145 228 139 228 144 228 140 229 146 229 141 229 146 230 140 230 145 230 107 231 141 231 146 231 144 232 147 232 145 232 147 233 144 233 143 233 145 234 148 234 146 234 148 235 145 235 147 235 146 236 149 236 107 236 149 237 146 237 148 237 143 238 150 238 147 238 108 239 107 239 149 239 147 240 150 240 9 240 147 241 9 241 11 241 6 242 61 242 107 242 147 243 11 243 148 243 148 244 15 244 149 244 148 245 11 245 15 245 149 246 13 246 108 246 2 247 53 247 6 247 13 248 149 248 15 248 7 249 108 249 13 249 68 250 151 250 81 250 152 251 81 251 151 251 81 252 152 252 82 252 153 253 85 253 82 253 153 254 82 254 152 254 154 255 85 255 153 255 154 256 86 256 85 256 155 257 109 257 50 257 155 258 50 258 86 258 155 259 86 259 154 259 114 260 109 260 155 260 156 261 152 261 151 261 152 262 156 262 153 262 153 263 157 263 154 263 157 264 153 264 156 264 154 265 158 265 155 265 158 266 154 266 157 266 159 267 155 267 158 267 155 268 159 268 114 268 157 269 160 269 158 269 160 270 157 270 156 270 158 271 161 271 159 271 161 272 158 272 160 272 162 273 159 273 161 273 124 274 119 274 162 274 161 275 165 275 162 275 162 276 166 276 124 276 166 277 162 277 165 277 126 278 124 278 166 278 165 279 167 279 166 279 167 280 165 280 164 280 168 281 166 281 167 281 168 282 130 282 126 282 166 283 168 283 126 283 131 284 130 284 168 284 151 285 169 285 163 285 169 286 151 286 68 286 170 287 163 287 169 287 163 288 170 288 164 288 164 289 171 289 167 289 171 290 164 290 170 290 167 291 172 291 168 291 172 292 167 292 171 292 173 293 168 293 172 293 168 294 173 294 131 294 134 295 131 295 173 295 174 296 170 296 169 296 170 297 174 297 171 297 171 298 175 298 172 298 175 299 171 299 174 299 172 300 176 300 173 300 176 301 172 301 175 301 177 302 173 302 176 302 177 303 137 303 134 303 173 304 177 304 134 304 142 305 137 305 177 305 178 306 175 306 174 306 175 307 178 307 176 307 179 308 176 308 178 308 176 309 179 309 177 309 180 310 177 310 179 310 177 311 180 311 142 311 143 312 142 312 180 312 181 313 174 313 169 313 174 314 181 314 178 314 178 315 182 315 179 315 182 316 178 316 181 316 183 317 179 317 182 317 179 318 183 318 180 318 180 319 184 319 143 319 184 320 180 320 183 320 150 321 143 321 184 321 169 322 68 322 58 322 182 323 56 323 183 323 183 324 55 324 184 324 184 325 55 325 150 325 9 326 150 326 55 326 51 327 113 327 104 327 185 328 105 328 104 328 185 329 104 329 113 329 52 330 1 330 4 330 105 331 186 331 106 331 186 332 105 332 185 332 187 333 106 333 186 333 141 334 107 334 61 334 188 335 98 335 187 335 113 336 115 336 185 336 189 337 185 337 115 337 185 338 189 338 186 338 186 339 190 339 187 339 190 340 186 340 189 340 191 341 187 341 190 341 187 342 191 342 188 342 115 343 123 343 189 343 192 344 189 344 123 344 189 345 192 345 190 345 193 346 190 346 192 346 190 347 193 347 191 347 191 348 194 348 188 348 194 349 191 349 193 349 123 350 129 350 192 350 192 351 195 351 193 351 195 352 192 352 129 352 193 353 196 353 194 353 196 354 193 354 195 354 195 355 129 355 132 355 197 356 195 356 132 356 195 357 197 357 196 357 198 358 196 358 197 358 196 359 198 359 194 359 52 360 194 360 198 360 194 361 52 361 188 361 4 362 188 362 52 362 188 363 4 363 98 363 197 364 199 364 198 364 60 365 198 365 199 365 198 366 60 366 52 366 61 367 199 367 141 367 199 368 61 368 60 368 60 369 53 369 52 369 7 370 8 370 108 370 6 371 108 371 8 371 132 372 199 372 197 372 132 373 141 373 199 373 119 374 159 374 162 374 114 375 159 375 119 375 156 376 200 376 160 376 163 377 200 377 151 377 200 378 156 378 151 378 164 379 165 379 201 379 163 380 164 380 201 380 161 381 201 381 165 381 160 382 201 382 161 382 163 383 201 383 200 383 160 384 200 384 201 384 62 385 202 385 59 385 55 386 203 386 10 386 203 387 63 387 10 387 63 388 203 388 202 388 63 389 202 389 62 389 56 390 204 390 183 390 204 391 55 391 183 391 56 392 202 392 204 392 56 393 57 393 202 393 57 394 59 394 202 394 55 395 202 395 203 395 55 396 204 396 202 396 58 397 205 397 64 397 205 398 67 398 64 398 67 399 205 399 68 399 205 400 58 400 68 400 58 401 206 401 169 401 206 402 181 402 169 402 181 403 206 403 182 403 182 404 206 404 56 404 206 405 58 405 56 405 131 406 134 406 133 406 125 407 131 407 133 407 4 408 5 408 98 408 98 409 106 409 187 409

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E3M5.dae b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E3M5.dae new file mode 100644 index 0000000..5e7a25d --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E3M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:18.666034 + 2012-07-23T02:14:18.666047 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + 6.56299 -2.38277 47.24268 5.35263 -4.47927 47.24261 8.87247 -3.22337 44.39990 6.60916 0.00113 47.53578 2.84679 -2.37657 49.09227 2.54221 1.39790 49.16618 10.14795 -3.68767 40.89576 10.66138 2.26448 37.15411 10.65737 -0.00554 41.13606 12.34216 2.62174 3.91527 11.52786 5.12782 3.91527 11.01634 0.00113 12.12860 9.95809 4.42892 37.15411 10.15396 0.00113 28.83627 8.87557 6.44006 12.12189 10.19228 0.00113 20.46215 8.19527 5.94582 20.45875 8.17780 5.93308 28.83789 8.44714 9.36806 3.91528 6.45203 8.86355 12.12188 5.95784 8.18330 20.45874 5.94505 8.16576 28.83790 7.29732 8.09110 37.15418 6.31535 10.91690 3.91528 3.39832 10.41953 12.12189 3.90808 11.98867 3.91527 3.13846 9.61985 20.45875 3.13175 9.59923 28.83789 3.37712 10.35445 37.15417 1.33067 12.53653 3.91528 -3.37208 10.41953 12.12189 -3.11222 9.61985 20.45875 -3.10550 9.59923 28.83789 -1.30443 12.53653 3.91528 -1.12475 10.82762 37.15418 -3.88184 11.98867 3.91527 -6.28911 10.91690 3.91528 -6.42579 8.86355 12.12189 -5.93160 8.18330 20.45875 -5.91880 8.16576 28.83789 -7.27106 8.09110 37.15418 -8.42090 9.36806 3.91528 -11.50162 5.12782 3.91528 -8.84933 6.44006 12.12189 -8.16902 5.94582 20.45875 -8.15156 5.93308 28.83789 -9.93184 4.42892 37.15411 -10.99010 0.00113 12.12860 -10.16603 0.00113 20.46214 -10.12771 0.00113 28.83627 -12.59134 0.00113 3.91535 -10.63514 2.26448 37.15411 3.49825 -6.03527 47.24268 7.23523 -6.05897 44.39990 9.67970 -0.00886 44.25639 12.91713 1.09479 -0.14384 9.76257 3.16892 -7.26175 8.30649 6.02662 -7.26175 4.71547 5.68328 -9.95829 6.03859 8.29450 -7.26168 4.72706 -8.16367 44.39983 8.27510 -6.93147 40.89576 7.16706 9.84777 -3.83483 7.64245 10.50204 0.00908 3.18089 9.75057 -7.26168 3.77422 11.57655 -3.83483 4.02411 12.34569 0.00914 -2.27218 7.03446 -9.95872 -3.11307 2.27245 -11.67954 -3.15472 9.75057 -7.26175 0.01312 12.17225 -3.83483 0.01312 12.98097 0.00914 -3.74798 11.57655 -3.83482 -3.99787 12.34569 0.00915 -5.64170 4.78556 -9.95684 -6.01242 8.29450 -7.26175 -7.14089 9.84777 -3.83490 -7.61621 10.50204 0.00908 -8.28025 6.02662 -7.26175 -9.83349 7.15513 -3.83482 -10.48777 7.63049 0.00908 -6.82884 2.31377 -9.95810 -9.73633 3.16892 -7.26175 -11.56236 3.76221 -3.83482 -12.33148 4.01212 0.00908 -12.08549 0.03693 -3.51346 -12.75930 -0.06820 -0.00748 8.27510 6.93376 40.89576 7.23524 6.06125 44.39990 5.35263 4.48149 47.24261 5.40581 9.34144 40.89576 4.72706 8.16591 44.39983 3.49824 6.03750 47.24268 1.88597 10.62254 40.89576 1.65022 9.28577 44.39990 -1.85971 10.62254 40.89576 -1.62397 9.28577 44.39990 -1.19723 6.86544 47.24269 -2.82054 2.37884 49.09227 -5.37955 9.34144 40.89577 -4.70088 8.16591 44.39990 -8.24885 6.93376 40.89577 -7.20898 6.06125 44.39991 -5.32638 4.48149 47.24262 -10.61057 1.65543 40.89317 -9.63732 1.11884 44.52992 -6.58291 0.00113 47.53579 9.95809 -4.42667 37.15411 10.66138 -2.26227 37.15411 -12.31592 -2.61947 3.91528 -10.40525 -3.38397 12.12189 -9.60558 -3.12417 20.45875 -9.58500 -3.11747 28.83789 -10.63514 -2.26227 37.15411 -11.50162 -5.12557 3.91528 -9.93184 -4.42667 37.15411 -8.84933 -6.43777 12.12189 -8.16902 -5.94357 20.45875 -8.15156 -5.93087 28.83789 -8.42090 -9.36577 3.91528 -6.42579 -8.86127 12.12189 -5.93160 -8.18107 20.45875 -5.91880 -8.16347 28.83789 -7.27106 -8.08887 37.15418 -6.28911 -10.91467 3.91528 -3.37208 -10.41727 12.12189 -3.88184 -11.98637 3.91528 -3.11222 -9.61757 20.45875 -3.10550 -9.59697 28.83789 -3.35086 -10.35217 37.15417 -1.30443 -12.53427 3.91528 1.33067 -12.53427 3.91528 1.15100 -10.82537 37.15418 3.39832 -10.41727 12.12189 3.90808 -11.98637 3.91528 3.13846 -9.61757 20.45875 3.13175 -9.59697 28.83789 6.31535 -10.91467 3.91528 6.45203 -8.86127 12.12188 5.95784 -8.18107 20.45874 5.94505 -8.16347 28.83790 7.29732 -8.08887 37.15418 8.44714 -9.36577 3.91528 11.52786 -5.12557 3.91527 8.87557 -6.43777 12.12189 8.19527 -5.94357 20.45875 8.17780 -5.93087 28.83789 10.43149 -3.38397 12.12188 9.63183 -3.12417 20.45875 9.61125 -3.11747 28.83790 12.34216 -2.61947 3.91527 -3.66193 -1.19297 -11.67954 -6.96572 -1.29969 -9.95652 -9.73633 -3.16667 -7.26174 -11.64271 -3.81134 -3.89589 -12.33148 -4.00987 0.00908 -5.96978 -4.34567 -9.95872 -8.28025 -6.02437 -7.26175 -9.83349 -7.15287 -3.83482 -10.48777 -7.62827 0.00908 -6.01242 -8.29227 -7.26175 -7.14089 -9.84547 -3.83490 -7.61621 -10.49977 0.00908 0.01312 -7.39417 -9.95865 0.01312 -10.25007 -7.26175 -3.74798 -11.57427 -3.83482 -3.99787 -12.34347 0.00915 0.01312 -12.16997 -3.83483 0.01312 -12.97867 0.00915 3.13931 -2.27017 -11.67954 2.29842 -7.03217 -9.95873 3.18089 -9.74827 -7.26168 3.77422 -11.57427 -3.83483 4.02411 -12.34347 0.00915 5.99602 -4.34567 -9.95873 6.03859 -8.29227 -7.26168 7.16706 -9.84547 -3.83483 7.64245 -10.49977 0.00908 8.30649 -6.02437 -7.26175 9.85972 -7.15287 -3.83483 10.51401 -7.62827 0.00907 7.04650 -2.28417 -9.95872 9.76257 -3.16667 -7.26175 11.58860 -3.75997 -3.83483 12.35772 -4.00987 0.00907 -10.12170 -3.68767 40.89577 -8.84622 -3.22337 44.39991 -6.53674 -2.38277 47.24269 -3.46287 -1.26402 49.09227 -8.24885 -6.93147 40.89577 -7.20898 -6.05897 44.39991 -5.32638 -4.47927 47.24262 -5.37955 -9.33917 40.89577 -4.70088 -8.16367 44.39991 -3.47199 -6.03527 47.24269 -1.85971 -10.62027 40.89576 -1.62397 -9.28347 44.39991 1.88597 -10.62027 40.89576 1.65022 -9.28347 44.39990 5.40581 -9.33917 40.89576 -3.19907 -6.56849 -9.78374 -3.78335 -9.39795 -7.68514 9.97586 6.39629 -3.98794 10.94574 6.09801 -0.28748 11.56665 1.44050 -3.96156 1.44190 7.54037 -9.95509 7.22986 1.88477 -9.95264 + + + + + + + + + + 0.65940 -0.38071 0.64827 0.44231 -0.11788 0.88908 0.37567 0.01217 0.92667 0.92219 0.29965 0.24447 0.94159 0.30595 -0.14069 0.94475 0.31420 0.09342 0.91917 0.30586 0.24816 0.94793 0.31844 0.00434 0.94357 0.31703 0.09579 0.93878 0.31278 -0.14440 0.94874 0.31606 0.00246 0.79790 0.57971 0.16518 0.69125 0.69126 0.21055 0.70362 0.70363 0.09913 0.70363 0.70362 0.09912 0.70711 0.70710 0.00255 0.70709 0.70712 0.00256 0.80264 0.58316 -0.12528 0.70690 0.70692 -0.02347 0.57718 0.79441 0.18915 0.45176 0.88661 0.09912 0.39708 0.89187 0.21654 0.44530 0.87394 0.19476 0.45399 0.89100 0.00256 0.45176 0.88662 0.09913 0.45302 0.88908 -0.06568 0.45399 0.89100 0.00256 0.49784 0.86227 -0.09299 0.20388 0.95916 0.19606 -0.00000 0.96830 0.24979 -0.00000 0.99543 0.09548 -0.00000 1.00000 0.00246 -0.00000 0.99543 0.09548 -0.00000 0.99590 -0.09044 -0.00000 1.00000 0.00246 -0.00000 0.96830 0.24979 0.10302 0.98016 -0.16932 -0.20388 0.95916 0.19606 -0.39884 0.89582 0.19606 -0.45176 0.88661 0.09913 -0.44382 0.87103 0.21055 -0.45176 0.88662 0.09912 -0.45399 0.89100 0.00256 -0.45399 0.89100 0.00256 -0.40606 0.91202 -0.05784 -0.45387 0.89076 -0.02347 -0.57718 0.79441 0.18915 -0.78794 0.57248 0.22675 -0.70243 0.70245 0.11470 -0.70362 0.70363 0.09912 -0.70363 0.70362 0.09913 -0.70711 0.70710 0.00256 -0.70296 0.70298 -0.10799 -0.70709 0.70712 0.00255 -0.80721 0.58648 -0.06672 -0.91917 0.30586 0.24816 -0.94454 0.31413 0.09570 -0.94379 0.31710 0.09333 -0.94794 0.31844 0.00246 -0.93878 0.31278 -0.14440 -0.94873 0.31606 0.00434 -0.96083 0.20424 0.18732 -0.94159 0.30595 -0.14069 0.48944 -0.58327 0.64826 0.43121 -0.24898 0.86722 0.72633 -0.09772 0.68037 0.92235 -0.15082 0.35571 0.95089 0.30897 0.01846 0.55814 0.28439 -0.77949 0.49213 0.49216 -0.71804 0.60058 -0.71572 0.35643 0.80901 0.58778 0.00398 0.58402 0.80383 0.11304 0.39723 0.77961 -0.48418 0.30759 0.60369 -0.73549 0.39723 0.77960 -0.48418 0.44450 0.87237 -0.20346 0.44450 0.87237 -0.20345 0.45319 0.88943 0.05951 0.40489 0.90940 0.09515 0.00000 0.88253 -0.47025 0.00001 0.70460 -0.70960 0.15316 0.96703 -0.20345 0.11963 0.75532 -0.64434 0.20774 0.97732 0.04113 0.15573 0.98327 0.09450 0.15316 0.96703 -0.20345 0.00000 0.99359 0.11305 -0.13688 0.86420 -0.48417 -0.15316 0.96703 -0.20345 -0.15616 0.98594 0.05951 -0.15316 0.96703 -0.20345 -0.20697 0.97371 0.09515 -0.24580 0.36753 -0.89694 -0.38907 0.58234 -0.71379 -0.28744 0.56414 -0.77403 -0.39723 0.77961 -0.48417 -0.44449 0.87237 -0.20345 -0.39722 0.77961 -0.48417 -0.44450 0.87237 -0.20345 -0.40639 0.91278 0.04112 -0.45196 0.88702 0.09450 -0.58402 0.80383 0.11304 -0.61871 0.61869 -0.48417 -0.49555 0.49554 -0.71335 -0.61871 0.61869 -0.48417 -0.69233 0.69231 -0.20344 -0.69232 0.69232 -0.20346 -0.70585 0.70585 0.05950 -0.79802 0.57979 0.16434 -0.61172 0.29417 -0.73435 -0.41027 0.19750 -0.89032 -0.59794 0.30467 -0.74138 -0.77961 0.39723 -0.48417 -0.77959 0.39724 -0.48418 -0.87236 0.44451 -0.20346 -0.88942 0.45320 0.05951 -0.87237 0.44451 -0.20345 -0.96755 0.20566 0.14681 -0.87370 0.08131 -0.47963 -0.97207 0.11906 -0.20224 -0.99374 0.10403 0.04071 -0.97735 0.10322 -0.18474 0.93079 -0.22073 0.29140 0.93648 0.30429 0.17441 0.92480 0.32437 0.19882 0.90394 0.32014 0.28356 0.70371 0.26783 0.65808 0.87353 0.34362 0.34478 0.41766 0.17547 0.89150 0.73848 0.24813 0.62696 0.80866 0.58753 -0.02959 0.60058 0.71572 0.35643 0.64127 0.76422 0.06880 0.48942 0.58328 0.64827 0.60057 0.71573 0.35644 0.26933 0.32094 0.90800 0.48945 0.58327 0.64825 0.49967 0.86544 -0.03661 0.34121 0.93747 0.06881 0.31955 0.87797 0.35644 0.26043 0.71550 0.64826 0.31956 0.87797 0.35643 -0.00000 0.93432 0.35643 0.10448 0.99409 -0.02959 0.00000 0.99850 0.05473 -0.00000 0.65858 0.75251 0.00000 0.93432 0.35643 0.13478 0.76436 0.63054 0.06535 0.37063 0.92648 0.05375 0.36390 0.92989 -0.31955 0.87798 0.35643 -0.40656 0.91314 -0.02981 -0.33866 0.93047 -0.13974 -0.26041 0.71550 0.64826 -0.31955 0.87798 0.35643 -0.60058 0.71573 0.35642 -0.64127 0.76422 0.06880 -0.42333 0.50448 0.75252 -0.60059 0.71572 0.35644 -0.38808 0.67216 0.63055 -0.25780 0.44650 0.85684 -0.80866 0.58754 -0.02959 -0.90435 0.40457 0.13593 -0.85543 0.38258 0.34911 -0.67924 0.35069 0.64471 -0.85533 0.42793 0.29204 -0.63950 0.22740 0.73439 -0.47521 0.18950 0.85922 -0.94953 0.30853 0.05650 0.74314 -0.15758 0.65032 0.95097 -0.30900 0.01278 -0.97634 -0.10261 0.19035 0.65940 -0.38073 0.64826 -0.98072 -0.16963 0.09698 -0.96361 -0.16690 0.20880 -0.97940 -0.17574 0.09942 -0.98429 -0.17652 0.00451 -0.98519 -0.17144 0.00256 -0.99212 -0.00000 -0.12528 -0.98510 -0.17144 -0.01345 0.80914 -0.46717 0.35644 -0.93388 -0.30345 0.18916 -0.94736 -0.30783 -0.08797 -0.88663 -0.45174 0.09912 -0.87104 -0.44380 0.21055 -0.89100 -0.45399 0.00255 -0.88662 -0.45175 0.09913 -0.88580 -0.45132 -0.10799 -0.89101 -0.45398 0.00255 -0.79790 -0.57972 0.16518 -0.69125 -0.69126 0.21054 -0.70362 -0.70363 0.09913 -0.70712 -0.70709 0.00255 -0.70364 -0.70361 0.09912 -0.70708 -0.70713 0.00257 -0.80264 -0.58316 -0.12528 -0.70689 -0.70694 -0.02346 -0.57719 -0.79440 0.18916 -0.45177 -0.88661 0.09912 -0.39706 -0.89188 0.21655 -0.44531 -0.87394 0.19476 -0.45174 -0.88662 0.09913 -0.45398 -0.89101 0.00257 -0.45302 -0.88908 -0.06569 -0.45400 -0.89100 0.00255 -0.49783 -0.86228 -0.09299 -0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.10408 -0.99021 -0.09299 0.00000 -0.99543 0.09549 0.00000 -1.00000 0.00246 0.00000 -0.99543 0.09549 0.00000 -0.98927 -0.14612 0.00000 -1.00000 0.00246 0.39882 -0.89583 0.19605 0.44383 -0.87103 0.21055 0.45177 -0.88661 0.09913 0.45398 -0.89101 0.00255 0.45174 -0.88662 0.09912 0.45400 -0.89100 0.00256 0.40605 -0.91202 -0.05785 0.45388 -0.89075 -0.02347 0.57719 -0.79440 0.18916 0.78794 -0.57248 0.22675 0.70243 -0.70245 0.11470 0.70362 -0.70363 0.09912 0.70711 -0.70709 0.00256 0.70363 -0.70361 0.09913 0.70295 -0.70300 -0.10800 0.70708 -0.70713 0.00255 0.80721 -0.58648 -0.06672 0.88663 -0.45174 0.09913 0.87104 -0.44380 0.21055 0.89100 -0.45399 0.00255 0.88662 -0.45176 0.09912 0.88580 -0.45132 -0.10799 0.89101 -0.45398 0.00255 0.93388 -0.30345 0.18916 0.94737 -0.30783 -0.08797 0.97395 0.00000 0.22676 0.98001 -0.16953 0.10411 0.86472 -0.49926 0.05473 0.98049 -0.16960 0.09933 0.98429 -0.17651 0.00256 0.97965 -0.17578 0.09687 0.97962 -0.17053 -0.10616 0.80914 -0.46718 0.35642 0.98518 -0.17144 0.00451 0.99814 0.00000 -0.06089 -0.41883 0.06633 -0.90564 -0.46278 0.01714 -0.88630 -0.67576 0.02528 -0.73669 -0.84734 -0.00000 -0.53105 -0.69723 -0.00000 -0.71685 -0.86492 -0.04989 -0.49943 -0.97720 -0.09349 -0.19061 -0.99368 -0.10443 0.04113 -0.99320 -0.10761 0.04443 -0.97821 -0.10692 -0.17798 -0.94496 -0.30704 0.11305 -0.45359 -0.14768 -0.87889 -0.61097 -0.19921 -0.76618 -0.76686 -0.39073 -0.50918 -0.61575 -0.31374 -0.72279 -0.86424 -0.47115 -0.17639 -0.76482 -0.42298 -0.48594 -0.87236 -0.44450 -0.20346 -0.88942 -0.45319 0.05951 -0.61871 -0.61869 -0.48417 -0.48867 -0.48865 -0.72279 -0.69232 -0.69231 -0.20346 -0.61871 -0.61870 -0.48416 -0.69231 -0.69232 -0.20345 -0.58403 -0.80382 0.11304 -0.44450 -0.87237 -0.20345 -0.45320 -0.88942 0.05950 -0.44450 -0.87236 -0.20346 -0.40486 -0.90941 0.09517 -0.15316 -0.96703 -0.20346 -0.13688 -0.86421 -0.48416 -0.15314 -0.96703 -0.20345 -0.20776 -0.97732 0.04111 -0.15571 -0.98327 0.09452 0.00000 -0.99359 0.11304 -0.04633 -0.29252 -0.95514 -0.00000 0.00000 -1.00000 0.05508 -0.34793 -0.93590 0.10810 -0.68256 -0.72280 0.13691 -0.86420 -0.48416 0.10814 -0.68257 -0.72277 0.15316 -0.96703 -0.20345 0.13688 -0.86419 -0.48418 0.15314 -0.96703 -0.20346 0.15614 -0.98594 0.05950 0.20699 -0.97370 0.09517 0.26805 -0.36893 -0.88996 0.41417 -0.57005 -0.70959 0.39721 -0.77961 -0.48419 0.27533 -0.54039 -0.79510 0.44451 -0.87236 -0.20346 0.39724 -0.77960 -0.48416 0.44450 -0.87236 -0.20347 0.40636 -0.91279 0.04111 0.45197 -0.88701 0.09452 0.58403 -0.80382 0.11304 0.48865 -0.48867 -0.72279 0.61869 -0.61871 -0.48416 0.61870 -0.61871 -0.48416 0.69231 -0.69232 -0.20347 0.69231 -0.69232 -0.20346 0.70585 -0.70586 0.05951 0.79801 -0.57980 0.16435 0.39424 -0.20089 -0.89678 0.61573 -0.31376 -0.72279 0.77961 -0.39723 -0.48416 0.61576 -0.31374 -0.72278 0.77959 -0.39725 -0.48418 0.87236 -0.44452 -0.20346 0.88942 -0.45319 0.05951 0.87237 -0.44450 -0.20345 0.94496 -0.30704 0.11305 0.13383 0.18421 -0.97373 0.88253 -0.00000 -0.47026 0.97289 -0.11267 -0.20199 0.99330 -0.10759 0.04225 0.99012 -0.00000 0.14025 -0.99998 0.00000 0.00657 -0.96541 -0.08821 0.24534 -0.99071 -0.09060 0.10143 0.32007 -0.38142 0.86722 -0.72094 -0.15159 0.67621 -0.91692 -0.17775 0.35730 -0.75895 -0.09392 0.64434 0.80866 -0.58753 -0.02958 -0.53838 0.09493 0.83734 -0.95097 -0.30901 0.01278 -0.86472 -0.49926 0.05473 -0.80914 -0.46717 0.35642 -0.65939 -0.38072 0.64827 -0.80913 -0.46718 0.35644 -0.65941 -0.38071 0.64826 -0.43120 -0.24897 0.86722 -0.80866 -0.58753 -0.02958 -0.64128 -0.76422 0.06881 -0.60058 -0.71572 0.35643 -0.60060 -0.71571 0.35642 -0.48945 -0.58326 0.64826 -0.28989 -0.34544 0.89254 -0.48944 -0.58327 0.64827 -0.49966 -0.86545 -0.03660 -0.31955 -0.87798 0.35642 -0.34121 -0.93747 0.06881 -0.26040 -0.71550 0.64827 -0.31953 -0.87798 0.35644 -0.10449 -0.99409 -0.02959 0.00000 -0.99850 0.05473 0.00000 -0.93432 0.35644 0.00000 -0.93432 0.35644 0.00000 -0.65858 0.75251 0.00000 -0.65858 0.75251 0.00000 -0.36144 0.93239 -0.08131 -0.46116 0.88358 -0.00000 -0.00000 1.00000 0.31955 -0.87797 0.35644 0.31954 -0.87798 0.35643 0.26042 -0.71551 0.64825 0.64128 -0.76422 0.06882 0.60058 -0.71572 0.35644 0.48944 -0.58328 0.64825 1.00000 0.00000 0.00101 0.98655 -0.14180 0.08135 0.34197 -0.93958 -0.01567 0.40473 -0.90904 -0.09916 -0.70585 -0.70586 0.05951 -0.79801 -0.57980 0.16435 -0.36980 -0.52149 -0.76896 -0.13804 -0.33996 -0.93025 -0.21598 -0.34123 -0.91483 -0.13938 -0.86261 -0.48629 -0.07283 -0.68476 -0.72513 -0.40615 -0.79712 -0.44682 -0.46051 -0.74162 -0.48778 -0.18784 -0.55980 -0.80706 -0.39250 -0.49426 -0.77566 0.67080 0.56710 -0.47794 0.92989 0.36512 -0.04451 0.80056 0.59863 0.02731 0.78489 0.59931 -0.15741 0.75565 0.62380 -0.19963 0.87564 -0.00807 -0.48290 0.94263 -0.00416 -0.33382 0.89592 0.28578 -0.34009 0.79515 0.40515 -0.45121 0.64712 0.64714 -0.40305 0.91159 0.35315 -0.21046 0.91005 0.29055 -0.29561 0.34281 0.60552 -0.71822 -0.10863 0.80172 -0.58775 -0.04631 0.34671 -0.93683 0.12016 0.21348 -0.96953 0.24246 0.15907 -0.95703 0.40296 -0.01639 -0.91507 0.69942 -0.02972 -0.71409 0.72819 -0.00000 -0.68538 0.57603 0.38022 -0.72362 0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.01762 -0.02100 0.99962 -0.31268 -0.12187 0.94201 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 3 1 4 1 5 2 4 2 3 2 9 3 10 3 11 3 12 4 7 4 13 4 11 5 14 5 15 5 14 6 11 6 10 6 15 7 16 7 13 7 16 8 15 8 14 8 13 9 17 9 12 9 17 10 13 10 16 10 10 11 18 11 14 11 19 12 14 12 18 12 14 13 19 13 16 13 20 14 16 14 19 14 16 15 20 15 17 15 21 16 17 16 20 16 21 17 22 17 12 17 17 18 21 18 12 18 18 19 23 19 19 19 19 20 24 20 20 20 19 21 23 21 25 21 24 22 19 22 25 22 20 23 26 23 21 23 26 24 20 24 24 24 21 25 27 25 22 25 27 26 21 26 26 26 28 27 22 27 27 27 25 28 29 28 24 28 30 29 24 29 29 29 24 30 30 30 26 30 26 31 31 31 27 31 31 32 26 32 30 32 27 33 32 33 28 33 32 34 27 34 31 34 29 35 33 35 30 35 34 36 28 36 32 36 30 37 33 37 35 37 35 38 36 38 30 38 30 39 37 39 31 39 37 40 30 40 36 40 38 41 31 41 37 41 31 42 38 42 32 42 39 43 32 43 38 43 39 44 40 44 34 44 32 45 39 45 34 45 36 46 41 46 37 46 37 47 41 47 42 47 43 48 37 48 42 48 37 49 43 49 38 49 44 50 38 50 43 50 38 51 44 51 39 51 39 52 45 52 40 52 45 53 39 53 44 53 46 54 40 54 45 54 47 55 43 55 42 55 43 56 47 56 44 56 48 57 44 57 47 57 44 58 48 58 45 58 45 59 49 59 46 59 49 60 45 60 48 60 42 61 50 61 47 61 51 62 46 62 49 62 1 63 52 63 53 63 1 64 0 64 4 64 3 65 0 65 54 65 6 66 8 66 2 66 10 67 9 67 55 67 57 68 56 68 58 68 59 69 57 69 58 69 53 70 60 70 61 70 63 71 18 71 10 71 23 72 18 72 63 72 59 73 64 73 62 73 64 74 59 74 58 74 65 75 62 75 64 75 62 76 65 76 63 76 66 77 63 77 65 77 63 78 66 78 23 78 25 79 23 79 66 79 64 80 69 80 65 80 69 81 64 81 67 81 65 82 70 82 66 82 70 83 65 83 69 83 71 84 29 84 25 84 66 85 71 85 25 85 71 86 66 86 70 86 33 87 29 87 71 87 72 88 70 88 69 88 70 89 72 89 71 89 71 90 73 90 33 90 73 91 71 91 72 91 35 92 33 92 73 92 74 93 67 93 68 93 67 94 74 94 69 94 75 95 69 95 74 95 69 96 75 96 72 96 72 97 76 97 73 97 76 98 72 98 75 98 77 99 73 99 76 99 77 100 36 100 35 100 73 101 77 101 35 101 41 102 36 102 77 102 75 103 78 103 76 103 78 104 75 104 74 104 79 105 76 105 78 105 76 106 79 106 77 106 80 107 77 107 79 107 77 108 80 108 41 108 42 109 41 109 80 109 74 110 81 110 78 110 81 111 74 111 68 111 82 112 78 112 81 112 78 113 82 113 79 113 83 114 79 114 82 114 79 115 83 115 80 115 80 116 84 116 42 116 84 117 80 117 83 117 50 118 42 118 84 118 85 119 83 119 82 119 83 120 85 120 84 120 84 121 86 121 50 121 86 122 84 122 85 122 2 123 8 123 54 123 7 124 12 124 8 124 87 125 8 125 12 125 8 126 87 126 54 126 54 127 88 127 3 127 88 128 54 128 87 128 3 129 89 129 5 129 89 130 3 130 88 130 12 131 22 131 87 131 87 132 90 132 88 132 90 133 87 133 22 133 88 134 91 134 89 134 91 135 88 135 90 135 89 136 92 136 5 136 92 137 89 137 91 137 22 138 28 138 90 138 93 139 90 139 28 139 90 140 93 140 91 140 91 141 94 141 92 141 94 142 91 142 93 142 93 143 95 143 94 143 93 144 28 144 34 144 95 145 93 145 34 145 94 146 96 146 92 146 96 147 94 147 95 147 97 148 92 148 96 148 92 149 97 149 5 149 98 150 5 150 97 150 95 151 99 151 96 151 95 152 34 152 40 152 99 153 95 153 40 153 96 154 100 154 97 154 100 155 96 155 99 155 99 156 101 156 100 156 101 157 99 157 40 157 100 158 102 158 97 158 102 159 100 159 101 159 103 160 97 160 102 160 97 161 103 161 98 161 40 162 46 162 101 162 104 163 101 163 46 163 101 164 104 164 102 164 102 165 105 165 103 165 105 166 102 166 104 166 106 167 103 167 105 167 103 168 106 168 98 168 46 169 51 169 104 169 54 170 0 170 2 170 107 171 108 171 6 171 50 172 109 172 47 172 53 173 2 173 1 173 47 174 110 174 48 174 110 175 47 175 109 175 111 176 48 176 110 176 111 177 49 177 48 177 112 178 49 178 111 178 112 179 113 179 51 179 112 180 51 180 49 180 61 181 6 181 53 181 109 182 114 182 110 182 115 183 113 183 112 183 110 184 116 184 111 184 116 185 110 185 114 185 111 186 117 186 112 186 117 187 111 187 116 187 112 188 118 188 115 188 118 189 112 189 117 189 114 190 119 190 116 190 120 191 116 191 119 191 116 192 120 192 117 192 117 193 121 193 118 193 121 194 117 194 120 194 122 195 118 195 121 195 122 196 123 196 115 196 118 197 122 197 115 197 119 198 124 198 120 198 120 199 125 199 121 199 120 200 124 200 126 200 125 201 120 201 126 201 127 202 121 202 125 202 121 203 127 203 122 203 122 204 128 204 123 204 128 205 122 205 127 205 129 206 123 206 128 206 126 207 130 207 125 207 130 208 131 208 125 208 132 209 129 209 128 209 125 210 133 210 127 210 127 211 135 211 128 211 135 212 127 212 133 212 128 213 136 213 132 213 136 214 128 214 135 214 134 215 137 215 133 215 138 216 133 216 137 216 133 217 138 217 135 217 135 218 139 218 136 218 139 219 135 219 138 219 140 220 136 220 139 220 140 221 141 221 132 221 136 222 140 222 132 222 137 223 142 223 138 223 138 224 142 224 143 224 144 225 138 225 143 225 138 226 144 226 139 226 139 227 145 227 140 227 145 228 139 228 144 228 140 229 146 229 141 229 146 230 140 230 145 230 107 231 141 231 146 231 144 232 147 232 145 232 147 233 144 233 143 233 145 234 148 234 146 234 148 235 145 235 147 235 146 236 149 236 107 236 149 237 146 237 148 237 143 238 150 238 147 238 108 239 107 239 149 239 147 240 150 240 9 240 147 241 9 241 11 241 6 242 61 242 107 242 147 243 11 243 148 243 148 244 15 244 149 244 148 245 11 245 15 245 149 246 13 246 108 246 2 247 53 247 6 247 13 248 149 248 15 248 7 249 108 249 13 249 68 250 151 250 81 250 152 251 81 251 151 251 81 252 152 252 82 252 153 253 85 253 82 253 153 254 82 254 152 254 154 255 85 255 153 255 154 256 86 256 85 256 155 257 109 257 50 257 155 258 50 258 86 258 155 259 86 259 154 259 114 260 109 260 155 260 156 261 152 261 151 261 152 262 156 262 153 262 153 263 157 263 154 263 157 264 153 264 156 264 154 265 158 265 155 265 158 266 154 266 157 266 159 267 155 267 158 267 155 268 159 268 114 268 157 269 160 269 158 269 160 270 157 270 156 270 158 271 161 271 159 271 161 272 158 272 160 272 162 273 159 273 161 273 124 274 119 274 162 274 161 275 165 275 162 275 162 276 166 276 124 276 166 277 162 277 165 277 126 278 124 278 166 278 165 279 167 279 166 279 167 280 165 280 164 280 168 281 166 281 167 281 168 282 130 282 126 282 166 283 168 283 126 283 131 284 130 284 168 284 151 285 169 285 163 285 169 286 151 286 68 286 170 287 163 287 169 287 163 288 170 288 164 288 164 289 171 289 167 289 171 290 164 290 170 290 167 291 172 291 168 291 172 292 167 292 171 292 173 293 168 293 172 293 168 294 173 294 131 294 134 295 131 295 173 295 174 296 170 296 169 296 170 297 174 297 171 297 171 298 175 298 172 298 175 299 171 299 174 299 172 300 176 300 173 300 176 301 172 301 175 301 177 302 173 302 176 302 177 303 137 303 134 303 173 304 177 304 134 304 142 305 137 305 177 305 178 306 175 306 174 306 175 307 178 307 176 307 179 308 176 308 178 308 176 309 179 309 177 309 180 310 177 310 179 310 177 311 180 311 142 311 143 312 142 312 180 312 181 313 174 313 169 313 174 314 181 314 178 314 178 315 182 315 179 315 182 316 178 316 181 316 183 317 179 317 182 317 179 318 183 318 180 318 180 319 184 319 143 319 184 320 180 320 183 320 150 321 143 321 184 321 169 322 68 322 58 322 182 323 56 323 183 323 183 324 55 324 184 324 184 325 55 325 150 325 9 326 150 326 55 326 51 327 113 327 104 327 185 328 105 328 104 328 185 329 104 329 113 329 52 330 1 330 4 330 105 331 186 331 106 331 186 332 105 332 185 332 187 333 106 333 186 333 141 334 107 334 61 334 188 335 98 335 187 335 113 336 115 336 185 336 189 337 185 337 115 337 185 338 189 338 186 338 186 339 190 339 187 339 190 340 186 340 189 340 191 341 187 341 190 341 187 342 191 342 188 342 115 343 123 343 189 343 192 344 189 344 123 344 189 345 192 345 190 345 193 346 190 346 192 346 190 347 193 347 191 347 191 348 194 348 188 348 194 349 191 349 193 349 123 350 129 350 192 350 192 351 195 351 193 351 195 352 192 352 129 352 193 353 196 353 194 353 196 354 193 354 195 354 195 355 129 355 132 355 197 356 195 356 132 356 195 357 197 357 196 357 198 358 196 358 197 358 196 359 198 359 194 359 52 360 194 360 198 360 194 361 52 361 188 361 4 362 188 362 52 362 188 363 4 363 98 363 197 364 199 364 198 364 60 365 198 365 199 365 198 366 60 366 52 366 61 367 199 367 141 367 199 368 61 368 60 368 60 369 53 369 52 369 7 370 8 370 108 370 6 371 108 371 8 371 132 372 199 372 197 372 132 373 141 373 199 373 119 374 159 374 162 374 114 375 159 375 119 375 156 376 200 376 160 376 163 377 200 377 151 377 200 378 156 378 151 378 164 379 165 379 201 379 163 380 164 380 201 380 161 381 201 381 165 381 160 382 201 382 161 382 163 383 201 383 200 383 160 384 200 384 201 384 62 385 202 385 59 385 55 386 203 386 10 386 203 387 63 387 10 387 63 388 203 388 202 388 63 389 202 389 62 389 56 390 204 390 183 390 204 391 55 391 183 391 56 392 202 392 204 392 56 393 57 393 202 393 57 394 59 394 202 394 55 395 202 395 203 395 55 396 204 396 202 396 58 397 205 397 64 397 205 398 67 398 64 398 67 399 205 399 68 399 205 400 58 400 68 400 58 401 206 401 169 401 206 402 181 402 169 402 181 403 206 403 182 403 182 404 206 404 56 404 206 405 58 405 56 405 131 406 134 406 133 406 125 407 131 407 133 407 4 408 5 408 98 408 98 409 106 409 187 409

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E3M5_no_rot_scaled.dae b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E3M5_no_rot_scaled.dae new file mode 100644 index 0000000..0ae9e8b --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E3M5_no_rot_scaled.dae @@ -0,0 +1,210 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T11:05:42 + 2025-02-20T11:05:42 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.16355 0.16355 0.16355 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + 6.56299 -2.38277 47.24268 5.35263 -4.47927 47.24261 8.87247 -3.22337 44.3999 6.60916 0.001129984 47.53578 2.84679 -2.37657 49.09227 2.54221 1.3979 49.16618 10.14795 -3.68767 40.89576 10.66138 2.26448 37.15411 10.65737 -0.005539953 41.13606 12.34216 2.62174 3.91527 11.52786 5.12782 3.91527 11.01634 0.001129984 12.1286 9.95809 4.42892 37.15411 10.15396 0.001129984 28.83627 8.87557 6.44006 12.12189 10.19228 0.001129984 20.46215 8.19527 5.94582 20.45875 8.177801 5.93308 28.83789 8.44714 9.368061 3.91528 6.45203 8.863551 12.12188 5.95784 8.1833 20.45874 5.94505 8.16576 28.8379 7.29732 8.0911 37.15418 6.31535 10.9169 3.91528 3.39832 10.41953 12.12189 3.90808 11.98867 3.91527 3.13846 9.619851 20.45875 3.13175 9.59923 28.83789 3.37712 10.35445 37.15417 1.33067 12.53653 3.91528 -3.37208 10.41953 12.12189 -3.11222 9.619851 20.45875 -3.1055 9.59923 28.83789 -1.30443 12.53653 3.91528 -1.12475 10.82762 37.15418 -3.88184 11.98867 3.91527 -6.28911 10.9169 3.91528 -6.42579 8.863551 12.12189 -5.9316 8.1833 20.45875 -5.9188 8.16576 28.83789 -7.27106 8.0911 37.15418 -8.4209 9.368061 3.91528 -11.50162 5.12782 3.91528 -8.84933 6.44006 12.12189 -8.16902 5.94582 20.45875 -8.15156 5.93308 28.83789 -9.93184 4.42892 37.15411 -10.9901 0.001129984 12.1286 -10.16603 0.001129984 20.46214 -10.12771 0.001129984 28.83627 -12.59134 0.001129984 3.91535 -10.63514 2.26448 37.15411 3.49825 -6.03527 47.24268 7.23523 -6.05897 44.3999 9.6797 -0.008859992 44.25639 12.91713 1.09479 -0.14384 9.76257 3.16892 -7.26175 8.30649 6.02662 -7.26175 4.71547 5.68328 -9.958291 6.03859 8.2945 -7.26168 4.72706 -8.16367 44.39983 8.2751 -6.93147 40.89576 7.16706 9.84777 -3.83483 7.64245 10.50204 0.009079992 3.18089 9.75057 -7.26168 3.77422 11.57655 -3.83483 4.02411 12.34569 0.009139955 -2.27218 7.03446 -9.958721 -3.11307 2.27245 -11.67954 -3.15472 9.75057 -7.26175 0.01311999 12.17225 -3.83483 0.01311999 12.98097 0.009139955 -3.74798 11.57655 -3.83482 -3.99787 12.34569 0.009149968 -5.6417 4.78556 -9.95684 -6.01242 8.2945 -7.26175 -7.14089 9.84777 -3.8349 -7.61621 10.50204 0.009079992 -8.28025 6.02662 -7.26175 -9.83349 7.15513 -3.83482 -10.48777 7.63049 0.009079992 -6.82884 2.31377 -9.9581 -9.73633 3.16892 -7.26175 -11.56236 3.76221 -3.83482 -12.33148 4.01212 0.009079992 -12.08549 0.03692996 -3.51346 -12.7593 -0.06819999 -0.007479965 8.2751 6.93376 40.89576 7.23524 6.06125 44.3999 5.35263 4.48149 47.24261 5.40581 9.341441 40.89576 4.72706 8.16591 44.39983 3.49824 6.0375 47.24268 1.88597 10.62254 40.89576 1.65022 9.28577 44.3999 -1.85971 10.62254 40.89576 -1.62397 9.28577 44.3999 -1.19723 6.86544 47.24269 -2.82054 2.37884 49.09227 -5.37955 9.341441 40.89577 -4.70088 8.16591 44.3999 -8.24885 6.93376 40.89577 -7.20898 6.06125 44.39991 -5.32638 4.48149 47.24262 -10.61057 1.65543 40.89317 -9.63732 1.11884 44.52992 -6.58291 0.001129984 47.53579 9.95809 -4.42667 37.15411 10.66138 -2.26227 37.15411 -12.31592 -2.61947 3.91528 -10.40525 -3.38397 12.12189 -9.60558 -3.12417 20.45875 -9.585 -3.11747 28.83789 -10.63514 -2.26227 37.15411 -11.50162 -5.12557 3.91528 -9.93184 -4.42667 37.15411 -8.84933 -6.43777 12.12189 -8.16902 -5.94357 20.45875 -8.15156 -5.93087 28.83789 -8.4209 -9.36577 3.91528 -6.42579 -8.86127 12.12189 -5.9316 -8.18107 20.45875 -5.9188 -8.163471 28.83789 -7.27106 -8.088871 37.15418 -6.28911 -10.91467 3.91528 -3.37208 -10.41727 12.12189 -3.88184 -11.98637 3.91528 -3.11222 -9.61757 20.45875 -3.1055 -9.59697 28.83789 -3.35086 -10.35217 37.15417 -1.30443 -12.53427 3.91528 1.33067 -12.53427 3.91528 1.151 -10.82537 37.15418 3.39832 -10.41727 12.12189 3.90808 -11.98637 3.91528 3.13846 -9.61757 20.45875 3.13175 -9.59697 28.83789 6.31535 -10.91467 3.91528 6.45203 -8.86127 12.12188 5.95784 -8.18107 20.45874 5.94505 -8.163471 28.8379 7.29732 -8.088871 37.15418 8.44714 -9.36577 3.91528 11.52786 -5.12557 3.91527 8.87557 -6.43777 12.12189 8.19527 -5.94357 20.45875 8.177801 -5.93087 28.83789 10.43149 -3.38397 12.12188 9.631831 -3.12417 20.45875 9.61125 -3.11747 28.8379 12.34216 -2.61947 3.91527 -3.66193 -1.19297 -11.67954 -6.96572 -1.29969 -9.956521 -9.73633 -3.16667 -7.26174 -11.64271 -3.81134 -3.89589 -12.33148 -4.00987 0.009079992 -5.96978 -4.34567 -9.958721 -8.28025 -6.02437 -7.26175 -9.83349 -7.15287 -3.83482 -10.48777 -7.62827 0.009079992 -6.01242 -8.29227 -7.26175 -7.14089 -9.84547 -3.8349 -7.61621 -10.49977 0.009079992 0.01311999 -7.39417 -9.95865 0.01311999 -10.25007 -7.26175 -3.74798 -11.57427 -3.83482 -3.99787 -12.34347 0.009149968 0.01311999 -12.16997 -3.83483 0.01311999 -12.97867 0.009149968 3.13931 -2.27017 -11.67954 2.29842 -7.03217 -9.95873 3.18089 -9.74827 -7.26168 3.77422 -11.57427 -3.83483 4.02411 -12.34347 0.009149968 5.99602 -4.34567 -9.95873 6.03859 -8.29227 -7.26168 7.16706 -9.84547 -3.83483 7.64245 -10.49977 0.009079992 8.30649 -6.02437 -7.26175 9.85972 -7.15287 -3.83483 10.51401 -7.62827 0.009069979 7.0465 -2.28417 -9.958721 9.76257 -3.16667 -7.26175 11.5886 -3.75997 -3.83483 12.35772 -4.00987 0.009069979 -10.1217 -3.68767 40.89577 -8.84622 -3.22337 44.39991 -6.53674 -2.38277 47.24269 -3.46287 -1.26402 49.09227 -8.24885 -6.93147 40.89577 -7.20898 -6.05897 44.39991 -5.32638 -4.47927 47.24262 -5.37955 -9.33917 40.89577 -4.70088 -8.16367 44.39991 -3.47199 -6.03527 47.24269 -1.85971 -10.62027 40.89576 -1.62397 -9.283471 44.39991 1.88597 -10.62027 40.89576 1.65022 -9.283471 44.3999 5.40581 -9.33917 40.89576 -3.19907 -6.56849 -9.78374 -3.78335 -9.397951 -7.68514 9.97586 6.39629 -3.98794 10.94574 6.09801 -0.28748 11.56665 1.4405 -3.96156 1.4419 7.54037 -9.95509 7.22986 1.88477 -9.95264 + + + + + + + + + + 0.6593989 -0.3807087 0.64827 0.4423103 -0.1178782 0.8890818 0.3756723 0.0121693 0.9266727 0.9221954 0.2996486 0.2444717 0.9415943 0.3059508 -0.1406927 0.944749 0.3142005 0.0934211 0.9191676 0.305857 0.2481583 0.9479322 0.318443 0.004337787 0.9435662 0.3170287 0.09579098 0.9387844 0.3127841 -0.144396 0.9487362 0.3160595 0.002458512 0.7979038 0.579712 0.1651778 0.6912493 0.6912633 0.210546 0.7036164 0.7036315 0.09912997 0.7036326 0.7036164 0.09912163 0.7071124 0.7070966 0.00254929 0.7070931 0.7071158 0.002559483 0.8026378 0.5831621 -0.1252778 0.706901 0.7069231 -0.0234676 0.5771749 0.7944115 0.1891546 0.4517635 0.886614 0.09912347 0.3970806 0.8918731 0.2165398 0.4453058 0.8739399 0.1947611 0.4539902 0.8910031 0.002558231 0.4517556 0.8866177 0.09912627 0.4530158 0.8890798 -0.06568104 0.4539945 0.8910009 0.002556085 0.4978375 0.8622704 -0.09299302 0.2038825 0.9591623 0.1960602 0 0.9683013 0.2497853 0 0.9954311 0.095483 0 0.999997 0.002460896 0 0.9954311 0.09548258 0 0.995902 -0.09043991 0 0.999997 0.002460896 0 0.9683011 0.2497858 0.1030201 0.9801628 -0.1693157 -0.2038826 0.9591623 0.1960602 -0.3988372 0.8958182 0.1960582 -0.4517629 0.886614 0.09912639 -0.4438223 0.8710295 0.2105456 -0.4517561 0.8866179 0.09912288 -0.4539902 0.8910031 0.00255692 -0.4539945 0.8910009 0.002558529 -0.4060568 0.9120158 -0.05783867 -0.4538711 0.8907582 -0.02347129 -0.5771751 0.7944114 0.1891544 -0.7879439 0.572476 0.2267506 -0.7024335 0.7024471 0.1146972 -0.7036172 0.7036318 0.09912198 -0.7036335 0.7036142 0.09913116 -0.7071139 0.7070952 0.002560257 -0.7029588 0.702984 -0.1079926 -0.7070919 0.7071172 0.002548515 -0.8072081 0.5864836 -0.06672406 -0.9191675 0.3058571 0.2481585 -0.9445427 0.3141345 0.09570032 -0.9437884 0.3171017 0.0933274 -0.9479386 0.3184439 0.002459406 -0.938785 0.3127827 -0.1443954 -0.9487307 0.316056 0.004341423 -0.9608321 0.204236 0.187322 -0.9415926 0.3059548 -0.1406946 0.4894447 -0.5832687 0.6482605 0.4312075 -0.2489774 0.8672199 0.7263273 -0.097718 0.6803675 0.9223467 -0.1508198 0.3557106 0.9508917 0.3089725 0.0184642 0.5581381 0.2843872 -0.7794907 0.492132 0.4921584 -0.7180434 0.6005796 -0.7157229 0.3564337 0.8090102 0.5877811 0.003975749 0.5840184 0.8038306 0.1130443 0.3972281 0.7796048 -0.484176 0.3075933 0.6036858 -0.735493 0.3972343 0.7795976 -0.4841822 0.4445031 0.8723657 -0.2034583 0.4444956 0.8723717 -0.2034488 0.4531894 0.889426 0.05950546 0.404886 0.9094034 0.09514653 5.1946e-6 0.8825315 -0.4702534 7.86518e-6 0.7046036 -0.7096011 0.1531628 0.9670312 -0.2034501 0.119631 0.7553203 -0.6443446 0.2077413 0.9773188 0.04112797 0.1557347 0.9832687 0.09449619 0.153163 0.9670313 -0.2034499 0 0.9935892 0.1130506 -0.1368774 0.8642011 -0.4841705 -0.1531633 0.9670311 -0.2034501 -0.1561574 0.985938 0.05950814 -0.1531634 0.9670308 -0.2034513 -0.2069742 0.9737091 0.09514468 -0.245797 0.3675269 -0.8969436 -0.3890693 0.5823439 -0.7137932 -0.2874424 0.5641378 -0.7740321 -0.3972303 0.7796086 -0.4841678 -0.4444929 0.8723731 -0.2034482 -0.3972205 0.7796089 -0.4841755 -0.4444953 0.8723722 -0.2034468 -0.4063875 0.9127749 0.04112571 -0.451963 0.8870173 0.09449887 -0.5840182 0.8038307 0.1130444 -0.6187058 0.6186923 -0.4841725 -0.4955528 0.4955418 -0.7133483 -0.6187129 0.6186896 -0.484167 -0.6923268 0.6923107 -0.2034443 -0.692316 0.6923177 -0.2034572 -0.7058529 0.7058549 0.05950379 -0.7980163 0.5797939 0.164345 -0.6117191 0.2941678 -0.7343466 -0.4102714 0.1974971 -0.8903215 -0.5979368 0.304666 -0.7413841 -0.7796087 0.3972334 -0.4841652 -0.7795951 0.3972442 -0.4841783 -0.8723605 0.4445134 -0.2034581 -0.8894217 0.4531971 0.05951142 -0.8723656 0.444507 -0.2034497 -0.9675481 0.205663 0.1468108 -0.8736976 0.08131557 -0.4796252 -0.9720719 0.1190589 -0.202241 -0.993741 0.1040272 0.04070925 -0.9773514 0.1032246 -0.1847407 0.930786 -0.2207314 0.2914018 0.936477 0.3042886 0.1744114 0.924799 0.3243695 0.198825 0.9039361 0.320142 0.2835642 0.703707 0.2678281 0.6580764 0.8735277 0.3436217 0.3447803 0.417657 0.1754685 0.8915008 0.7384807 0.2481334 0.6269579 0.8086584 0.587534 -0.02958983 0.6005778 0.7157241 0.3564342 0.6412733 0.7642216 0.06880521 0.4894261 0.5832784 0.6482656 0.6005709 0.7157266 0.3564408 0.2693349 0.3209407 0.9079955 0.4894467 0.5832739 0.6482543 0.4996678 0.8654432 -0.0366075 0.3412052 0.9374669 0.06881082 0.319552 0.8779743 0.3564376 0.2604311 0.7154988 0.648257 0.3195583 0.8779744 0.3564316 0 0.9343227 0.3564282 0.1044835 0.9940865 -0.02958756 0 0.9985013 0.05472898 0 0.6585759 0.7525144 0 0.9343227 0.3564283 0.1347788 0.7643639 0.6305416 0.06535506 0.3706347 0.9264764 0.05374711 0.363896 0.9298876 -0.319552 0.8779768 0.3564313 -0.4065571 0.913139 -0.02980965 -0.3386593 0.9304752 -0.1397346 -0.2604114 0.7155007 0.6482629 -0.3195463 0.8779814 0.356425 -0.6005801 0.7157275 0.3564237 -0.6412732 0.7642217 0.06880384 -0.4233302 0.5044816 0.7525224 -0.6005869 0.7157156 0.356436 -0.3880816 0.6721636 0.6305465 -0.2578036 0.446504 0.8568381 -0.8086575 0.5875352 -0.02959114 -0.9043475 0.4045709 0.1359345 -0.8554264 0.3825787 0.3491122 -0.6792389 0.350686 0.6447123 -0.8553299 0.4279298 0.2920395 -0.6395013 0.2274048 0.7343877 -0.475214 0.1894984 0.8592218 -0.9495338 0.3085349 0.05649626 0.7431346 -0.1575835 0.6503218 0.9509746 -0.3090052 0.01277583 -0.9763393 -0.1026172 0.1903453 0.6593963 -0.3807278 0.6482616 -0.9807239 -0.1696341 0.09697979 -0.9636114 -0.1668987 0.2088012 -0.9794033 -0.1757406 0.09942072 -0.9842877 -0.1765144 0.004504144 -0.9851904 -0.1714451 0.002556681 -0.9921213 0 -0.1252811 -0.9851033 -0.1714377 -0.01344662 0.8091393 -0.4671683 0.3564372 -0.9338844 -0.3034446 0.1891599 -0.9473637 -0.3078356 -0.08797293 -0.8866267 -0.4517388 0.09912258 -0.8710409 -0.4437979 0.2105498 -0.8910036 -0.4539892 0.002551317 -0.8866174 -0.4517556 0.09912991 -0.8858031 -0.4513207 -0.1079939 -0.8910111 -0.4539745 0.002544701 -0.7979011 -0.5797153 0.1651793 -0.6912506 -0.6912621 0.2105453 -0.7036183 -0.70363 0.09912747 -0.707117 -0.707092 0.002545118 -0.7036374 -0.7036123 0.09911733 -0.7070792 -0.7071297 0.002565324 -0.8026382 -0.5831611 -0.1252808 -0.706887 -0.7069375 -0.023458 -0.5771898 -0.7944004 0.1891562 -0.4517679 -0.8866124 0.09911811 -0.3970593 -0.8918808 0.2165468 -0.4453101 -0.8739385 0.1947575 -0.4517433 -0.8866237 0.09912872 -0.4539777 -0.8910094 0.002565026 -0.4530228 -0.8890757 -0.06568759 -0.454002 -0.890997 0.002554476 -0.4978291 -0.8622754 -0.09299087 -0.2038959 -0.9591603 0.1960563 0 -0.9683011 0.249786 -0.1040832 -0.9902119 -0.09299141 0 -0.9954309 0.09548515 0 -0.999997 0.002458691 0 -0.995431 0.09548503 0 -0.9892662 -0.1461248 0 -0.9999971 0.002458453 0.3988167 -0.8958281 0.1960548 0.4438267 -0.8710262 0.2105503 0.4517678 -0.8866112 0.09912824 0.4539778 -0.8910094 0.002554178 0.4517438 -0.8866246 0.09911757 0.4540021 -0.890997 0.002564132 0.4060533 -0.9120168 -0.05784517 0.4538787 -0.8907544 -0.02346998 0.5771896 -0.7944005 0.1891564 0.7879419 -0.5724788 0.22675 0.7024338 -0.702446 0.1147012 0.703619 -0.7036306 0.09911787 0.7071154 -0.7070935 0.00256443 0.7036351 -0.7036132 0.09912699 0.702947 -0.7029953 -0.1079967 0.7070806 -0.7071285 0.002545893 0.8072107 -0.5864802 -0.06672328 0.8866261 -0.4517385 0.0991286 0.8710411 -0.4437977 0.2105497 0.891003 -0.4539902 0.002545654 0.8866181 -0.4517561 0.09912091 0.8858022 -0.4513223 -0.1079943 0.8910099 -0.4539768 0.002551436 0.9338846 -0.303444 0.1891598 0.9473651 -0.3078317 -0.08797258 0.9739516 0 0.2267562 0.9800119 -0.1695249 0.1041064 0.8647228 -0.4992587 0.0547288 0.9804944 -0.1695991 0.09933269 0.984295 -0.1765134 0.002558648 0.9796512 -0.1757819 0.09687232 0.9796162 -0.1705318 -0.1061645 0.809137 -0.4671842 0.3564214 0.9851838 -0.1714423 0.004508256 0.9981445 0 -0.06089073 -0.4188265 0.06633448 -0.9056401 -0.4627861 0.01714318 -0.8863041 -0.6757581 0.025276 -0.7366901 -0.8473391 -8.16675e-7 -0.5310522 -0.6972286 -1.09049e-6 -0.7168489 -0.8649153 -0.04988414 -0.4994328 -0.9772033 -0.09349417 -0.190611 -0.9936808 -0.1044356 0.04113161 -0.9931998 -0.107612 0.04442656 -0.9782091 -0.1069203 -0.1779753 -0.9449568 -0.3070427 0.1130549 -0.4535944 -0.1476762 -0.8788879 -0.6109691 -0.1992141 -0.7661792 -0.7668552 -0.3907334 -0.5091763 -0.6157476 -0.3137389 -0.7227883 -0.8642356 -0.4711511 -0.17639 -0.7648199 -0.4229807 -0.4859402 -0.8723648 -0.4445029 -0.2034621 -0.8894231 -0.4531942 0.05951267 -0.6187113 -0.6186922 -0.4841656 -0.4886661 -0.4886504 -0.7227907 -0.6923192 -0.6923124 -0.2034646 -0.6187098 -0.6186959 -0.4841629 -0.6923106 -0.6923252 -0.2034499 -0.5840334 -0.8038199 0.1130424 -0.4444968 -0.87237 -0.2034534 -0.4531995 -0.8894212 0.05949991 -0.4445034 -0.8723649 -0.2034611 -0.4048638 -0.9094113 0.09516513 -0.1531628 -0.9670281 -0.2034648 -0.1368782 -0.8642052 -0.4841632 -0.1531445 -0.9670349 -0.2034459 -0.2077554 -0.9773165 0.04111248 -0.1557155 -0.9832697 0.09451687 0 -0.9935904 0.1130408 -0.04632937 -0.292516 -0.9551377 0 0 -1 0.05507928 -0.3479267 -0.9359024 0.1080937 -0.682555 -0.7227963 0.136907 -0.864202 -0.4841606 0.1081407 -0.68257 -0.7227751 0.1531629 -0.9670321 -0.2034452 0.1368751 -0.8641934 -0.4841849 0.1531439 -0.9670314 -0.2034633 0.1561385 -0.9859412 0.05950415 0.2069876 -0.9737042 0.09516537 0.2680498 -0.3689333 -0.889965 0.4141677 -0.5700455 -0.7095867 0.3972101 -0.7796066 -0.4841877 0.2753279 -0.5403872 -0.7950953 0.444507 -0.8723631 -0.2034606 0.3972426 -0.7796048 -0.484164 0.4445031 -0.8723641 -0.2034648 0.4063658 -0.9127854 0.04110807 0.4519719 -0.8870109 0.09451562 0.5840336 -0.8038198 0.1130425 0.4886493 -0.4886718 -0.7227875 0.618695 -0.6187095 -0.4841645 0.6186957 -0.6187095 -0.4841634 0.692308 -0.6923232 -0.2034657 0.6923079 -0.6923233 -0.2034654 0.7058465 -0.7058607 0.05951023 0.7980129 -0.5797966 0.1643518 0.3942439 -0.2008908 -0.8967801 0.6157368 -0.3137584 -0.7227891 0.7796096 -0.3972331 -0.4841638 0.6157552 -0.3137447 -0.7227793 0.7795922 -0.3972477 -0.4841801 0.8723573 -0.4445165 -0.2034648 0.8894233 -0.4531938 0.05951243 0.8723676 -0.4445039 -0.2034485 0.9449569 -0.3070427 0.1130548 0.1338349 0.1842083 -0.9737328 0.8825304 0 -0.4702554 0.972886 -0.1126672 -0.2019878 0.9932975 -0.1075873 0.04225236 0.9901163 0 0.1402493 -0.9999785 0 0.006570875 -0.9654142 -0.08821219 0.2453446 -0.9907086 -0.09059548 0.1014343 0.3200755 -0.381416 0.8672218 -0.7209408 -0.1515929 0.676213 -0.9169182 -0.1777502 0.3573039 -0.7589473 -0.09392189 0.6443429 0.8086605 -0.5875315 -0.02958154 -0.5383825 0.0949313 0.8373364 -0.9509733 -0.3090088 0.01277679 -0.8647227 -0.4992588 0.05472892 -0.8091453 -0.4671693 0.3564219 -0.6593903 -0.380724 0.6482698 -0.809131 -0.4671823 0.3564377 -0.6594068 -0.380713 0.6482594 -0.4312026 -0.2489727 0.8672238 -0.8086591 -0.5875334 -0.02958285 -0.6412753 -0.7642191 0.06881439 -0.60058 -0.7157227 0.3564333 -0.6005992 -0.7157152 0.3564162 -0.4894518 -0.5832617 0.6482613 -0.2898886 -0.3454419 0.8925438 -0.4894351 -0.5832662 0.64827 -0.4996597 -0.8654482 -0.03660398 -0.3195534 -0.8779819 0.3564177 -0.3412055 -0.937467 0.06880861 -0.2603982 -0.7155027 0.648266 -0.31953 -0.8779822 0.3564379 -0.1044902 -0.9940858 -0.02958762 0 -0.998501 0.0547344 0 -0.9343204 0.3564344 1.2426e-6 -0.9343202 0.356435 2.15931e-6 -0.6585825 0.7525085 1.01431e-6 -0.6585843 0.7525069 1.7112e-6 -0.3614439 0.9323939 -0.08131402 -0.4611588 0.8835841 -2.57534e-6 0 1 0.3195523 -0.8779739 0.3564383 0.3195444 -0.8779802 0.3564298 0.2604187 -0.715506 0.6482542 0.641276 -0.7642183 0.0688157 0.6005813 -0.7157208 0.356435 0.4894374 -0.5832837 0.6482524 0.9999996 0 0.00100708 0.9865469 -0.1417971 0.08135575 0.3419739 -0.9395788 -0.01567059 0.40473 -0.9090436 -0.09916311 -0.7058464 -0.7058607 0.05951052 -0.7980126 -0.5797968 0.1643521 -0.3698022 -0.5214855 -0.76896 -0.1380395 -0.339961 -0.9302536 -0.2159814 -0.3412325 -0.9148293 -0.1393804 -0.8626082 -0.4862923 -0.0728262 -0.6847548 -0.7251257 -0.4061464 -0.7971161 -0.4468235 -0.4605127 -0.7416178 -0.4877818 -0.1878403 -0.5598013 -0.8070555 -0.3924956 -0.4942581 -0.775665 0.6708008 0.5670965 -0.4779414 0.9298946 0.3651232 -0.04451161 0.8005602 0.59863 0.02730649 0.7848865 0.5993127 -0.1574082 0.7556552 0.6238048 -0.199632 0.8756369 -0.008072137 -0.4829027 0.9426273 -0.004156291 -0.3338213 0.8959184 0.2857763 -0.3400918 0.7951498 0.4051514 -0.4512085 0.6471197 0.6471375 -0.40305 0.9115894 0.3531455 -0.2104593 0.9100521 0.2905497 -0.2956113 0.342806 0.6055166 -0.7182157 -0.108631 0.8017177 -0.5877483 -0.04631084 0.3467136 -0.9368271 0.1201583 0.2134788 -0.9695303 0.2424564 0.1590682 -0.957033 0.4029604 -0.01638835 -0.9150707 0.6994171 -0.0297209 -0.7140955 0.7281855 0 -0.6853801 0.5760294 0.3802212 -0.7236173 0.2038958 -0.9591603 0.1960561 0 -0.9683013 0.2497854 -0.01761543 -0.02099573 0.9996244 -0.3126854 -0.1218762 0.9420053 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 3 1 4 1 5 2 4 2 3 2 9 3 10 3 11 3 12 4 7 4 13 4 11 5 14 5 15 5 14 6 11 6 10 6 15 7 16 7 13 7 16 8 15 8 14 8 13 9 17 9 12 9 17 10 13 10 16 10 10 11 18 11 14 11 19 12 14 12 18 12 14 13 19 13 16 13 20 14 16 14 19 14 16 15 20 15 17 15 21 16 17 16 20 16 21 17 22 17 12 17 17 18 21 18 12 18 18 19 23 19 19 19 19 20 24 20 20 20 19 21 23 21 25 21 24 22 19 22 25 22 20 23 26 23 21 23 26 24 20 24 24 24 21 25 27 25 22 25 27 26 21 26 26 26 28 27 22 27 27 27 25 28 29 28 24 28 30 29 24 29 29 29 24 30 30 30 26 30 26 31 31 31 27 31 31 32 26 32 30 32 27 33 32 33 28 33 32 34 27 34 31 34 29 35 33 35 30 35 34 36 28 36 32 36 30 37 33 37 35 37 35 38 36 38 30 38 30 39 37 39 31 39 37 40 30 40 36 40 38 41 31 41 37 41 31 42 38 42 32 42 39 43 32 43 38 43 39 44 40 44 34 44 32 45 39 45 34 45 36 46 41 46 37 46 37 47 41 47 42 47 43 48 37 48 42 48 37 49 43 49 38 49 44 50 38 50 43 50 38 51 44 51 39 51 39 52 45 52 40 52 45 53 39 53 44 53 46 54 40 54 45 54 47 55 43 55 42 55 43 56 47 56 44 56 48 57 44 57 47 57 44 58 48 58 45 58 45 59 49 59 46 59 49 60 45 60 48 60 42 61 50 61 47 61 51 62 46 62 49 62 1 63 52 63 53 63 1 64 0 64 4 64 3 65 0 65 54 65 6 66 8 66 2 66 10 67 9 67 55 67 57 68 56 68 58 68 59 69 57 69 58 69 53 70 60 70 61 70 63 71 18 71 10 71 23 72 18 72 63 72 59 73 64 73 62 73 64 74 59 74 58 74 65 75 62 75 64 75 62 76 65 76 63 76 66 77 63 77 65 77 63 78 66 78 23 78 25 79 23 79 66 79 64 80 69 80 65 80 69 81 64 81 67 81 65 82 70 82 66 82 70 83 65 83 69 83 71 84 29 84 25 84 66 85 71 85 25 85 71 86 66 86 70 86 33 87 29 87 71 87 72 88 70 88 69 88 70 89 72 89 71 89 71 90 73 90 33 90 73 91 71 91 72 91 35 92 33 92 73 92 74 93 67 93 68 93 67 94 74 94 69 94 75 95 69 95 74 95 69 96 75 96 72 96 72 97 76 97 73 97 76 98 72 98 75 98 77 99 73 99 76 99 77 100 36 100 35 100 73 101 77 101 35 101 41 102 36 102 77 102 75 103 78 103 76 103 78 104 75 104 74 104 79 105 76 105 78 105 76 106 79 106 77 106 80 107 77 107 79 107 77 108 80 108 41 108 42 109 41 109 80 109 74 110 81 110 78 110 81 111 74 111 68 111 82 112 78 112 81 112 78 113 82 113 79 113 83 114 79 114 82 114 79 115 83 115 80 115 80 116 84 116 42 116 84 117 80 117 83 117 50 118 42 118 84 118 85 119 83 119 82 119 83 120 85 120 84 120 84 121 86 121 50 121 86 122 84 122 85 122 2 123 8 123 54 123 7 124 12 124 8 124 87 125 8 125 12 125 8 126 87 126 54 126 54 127 88 127 3 127 88 128 54 128 87 128 3 129 89 129 5 129 89 130 3 130 88 130 12 131 22 131 87 131 87 132 90 132 88 132 90 133 87 133 22 133 88 134 91 134 89 134 91 135 88 135 90 135 89 136 92 136 5 136 92 137 89 137 91 137 22 138 28 138 90 138 93 139 90 139 28 139 90 140 93 140 91 140 91 141 94 141 92 141 94 142 91 142 93 142 93 143 95 143 94 143 93 144 28 144 34 144 95 145 93 145 34 145 94 146 96 146 92 146 96 147 94 147 95 147 97 148 92 148 96 148 92 149 97 149 5 149 98 150 5 150 97 150 95 151 99 151 96 151 95 152 34 152 40 152 99 153 95 153 40 153 96 154 100 154 97 154 100 155 96 155 99 155 99 156 101 156 100 156 101 157 99 157 40 157 100 158 102 158 97 158 102 159 100 159 101 159 103 160 97 160 102 160 97 161 103 161 98 161 40 162 46 162 101 162 104 163 101 163 46 163 101 164 104 164 102 164 102 165 105 165 103 165 105 166 102 166 104 166 106 167 103 167 105 167 103 168 106 168 98 168 46 169 51 169 104 169 54 170 0 170 2 170 107 171 108 171 6 171 50 172 109 172 47 172 53 173 2 173 1 173 47 174 110 174 48 174 110 175 47 175 109 175 111 176 48 176 110 176 111 177 49 177 48 177 112 178 49 178 111 178 112 179 113 179 51 179 112 180 51 180 49 180 61 181 6 181 53 181 109 182 114 182 110 182 115 183 113 183 112 183 110 184 116 184 111 184 116 185 110 185 114 185 111 186 117 186 112 186 117 187 111 187 116 187 112 188 118 188 115 188 118 189 112 189 117 189 114 190 119 190 116 190 120 191 116 191 119 191 116 192 120 192 117 192 117 193 121 193 118 193 121 194 117 194 120 194 122 195 118 195 121 195 122 196 123 196 115 196 118 197 122 197 115 197 119 198 124 198 120 198 120 199 125 199 121 199 120 200 124 200 126 200 125 201 120 201 126 201 127 202 121 202 125 202 121 203 127 203 122 203 122 204 128 204 123 204 128 205 122 205 127 205 129 206 123 206 128 206 126 207 130 207 125 207 130 208 131 208 125 208 132 209 129 209 128 209 125 210 133 210 127 210 127 211 135 211 128 211 135 212 127 212 133 212 128 213 136 213 132 213 136 214 128 214 135 214 134 215 137 215 133 215 138 216 133 216 137 216 133 217 138 217 135 217 135 218 139 218 136 218 139 219 135 219 138 219 140 220 136 220 139 220 140 221 141 221 132 221 136 222 140 222 132 222 137 223 142 223 138 223 138 224 142 224 143 224 144 225 138 225 143 225 138 226 144 226 139 226 139 227 145 227 140 227 145 228 139 228 144 228 140 229 146 229 141 229 146 230 140 230 145 230 107 231 141 231 146 231 144 232 147 232 145 232 147 233 144 233 143 233 145 234 148 234 146 234 148 235 145 235 147 235 146 236 149 236 107 236 149 237 146 237 148 237 143 238 150 238 147 238 108 239 107 239 149 239 147 240 150 240 9 240 147 241 9 241 11 241 6 242 61 242 107 242 147 243 11 243 148 243 148 244 15 244 149 244 148 245 11 245 15 245 149 246 13 246 108 246 2 247 53 247 6 247 13 248 149 248 15 248 7 249 108 249 13 249 68 250 151 250 81 250 152 251 81 251 151 251 81 252 152 252 82 252 153 253 85 253 82 253 153 254 82 254 152 254 154 255 85 255 153 255 154 256 86 256 85 256 155 257 109 257 50 257 155 258 50 258 86 258 155 259 86 259 154 259 114 260 109 260 155 260 156 261 152 261 151 261 152 262 156 262 153 262 153 263 157 263 154 263 157 264 153 264 156 264 154 265 158 265 155 265 158 266 154 266 157 266 159 267 155 267 158 267 155 268 159 268 114 268 157 269 160 269 158 269 160 270 157 270 156 270 158 271 161 271 159 271 161 272 158 272 160 272 162 273 159 273 161 273 124 274 119 274 162 274 161 275 165 275 162 275 162 276 166 276 124 276 166 277 162 277 165 277 126 278 124 278 166 278 165 279 167 279 166 279 167 280 165 280 164 280 168 281 166 281 167 281 168 282 130 282 126 282 166 283 168 283 126 283 131 284 130 284 168 284 151 285 169 285 163 285 169 286 151 286 68 286 170 287 163 287 169 287 163 288 170 288 164 288 164 289 171 289 167 289 171 290 164 290 170 290 167 291 172 291 168 291 172 292 167 292 171 292 173 293 168 293 172 293 168 294 173 294 131 294 134 295 131 295 173 295 174 296 170 296 169 296 170 297 174 297 171 297 171 298 175 298 172 298 175 299 171 299 174 299 172 300 176 300 173 300 176 301 172 301 175 301 177 302 173 302 176 302 177 303 137 303 134 303 173 304 177 304 134 304 142 305 137 305 177 305 178 306 175 306 174 306 175 307 178 307 176 307 179 308 176 308 178 308 176 309 179 309 177 309 180 310 177 310 179 310 177 311 180 311 142 311 143 312 142 312 180 312 181 313 174 313 169 313 174 314 181 314 178 314 178 315 182 315 179 315 182 316 178 316 181 316 183 317 179 317 182 317 179 318 183 318 180 318 180 319 184 319 143 319 184 320 180 320 183 320 150 321 143 321 184 321 169 322 68 322 58 322 182 323 56 323 183 323 183 324 55 324 184 324 184 325 55 325 150 325 9 326 150 326 55 326 51 327 113 327 104 327 185 328 105 328 104 328 185 329 104 329 113 329 52 330 1 330 4 330 105 331 186 331 106 331 186 332 105 332 185 332 187 333 106 333 186 333 141 334 107 334 61 334 188 335 98 335 187 335 113 336 115 336 185 336 189 337 185 337 115 337 185 338 189 338 186 338 186 339 190 339 187 339 190 340 186 340 189 340 191 341 187 341 190 341 187 342 191 342 188 342 115 343 123 343 189 343 192 344 189 344 123 344 189 345 192 345 190 345 193 346 190 346 192 346 190 347 193 347 191 347 191 348 194 348 188 348 194 349 191 349 193 349 123 350 129 350 192 350 192 351 195 351 193 351 195 352 192 352 129 352 193 353 196 353 194 353 196 354 193 354 195 354 195 355 129 355 132 355 197 356 195 356 132 356 195 357 197 357 196 357 198 358 196 358 197 358 196 359 198 359 194 359 52 360 194 360 198 360 194 361 52 361 188 361 4 362 188 362 52 362 188 363 4 363 98 363 197 364 199 364 198 364 60 365 198 365 199 365 198 366 60 366 52 366 61 367 199 367 141 367 199 368 61 368 60 368 60 369 53 369 52 369 7 370 8 370 108 370 6 371 108 371 8 371 132 372 199 372 197 372 132 373 141 373 199 373 119 374 159 374 162 374 114 375 159 375 119 375 156 376 200 376 160 376 163 377 200 377 151 377 200 378 156 378 151 378 164 379 165 379 201 379 163 380 164 380 201 380 161 381 201 381 165 381 160 382 201 382 161 382 163 383 201 383 200 383 160 384 200 384 201 384 62 385 202 385 59 385 55 386 203 386 10 386 203 387 63 387 10 387 63 388 203 388 202 388 63 389 202 389 62 389 56 390 204 390 183 390 204 391 55 391 183 391 56 392 202 392 204 392 56 393 57 393 202 393 57 394 59 394 202 394 55 395 202 395 203 395 55 396 204 396 202 396 58 397 205 397 64 397 205 398 67 398 64 398 67 399 205 399 68 399 205 400 58 400 68 400 58 401 206 401 169 401 206 402 181 402 169 402 181 403 206 403 182 403 182 404 206 404 56 404 206 405 58 405 56 405 131 406 134 406 133 406 125 407 131 407 133 407 4 408 5 408 98 408 98 409 106 409 187 409

+
+
+
+
+ + + + 9.99983e-4 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + -0.2908648 -0.7711008 0.5663932 4.076245 0.9551711 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054209 -0.6141704 -6.925791 -4.01133e-9 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E4.dae b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E4.dae new file mode 100644 index 0000000..907da45 --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_E4.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:18.666034 + 2012-07-23T02:14:18.666047 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + 6.56299 -2.38277 47.24268 5.35263 -4.47927 47.24261 8.87247 -3.22337 44.39990 6.60916 0.00113 47.53578 2.84679 -2.37657 49.09227 2.54221 1.39790 49.16618 10.14795 -3.68767 40.89576 10.66138 2.26448 37.15411 10.65737 -0.00554 41.13606 12.34216 2.62174 3.91527 11.52786 5.12782 3.91527 11.01634 0.00113 12.12860 9.95809 4.42892 37.15411 10.15396 0.00113 28.83627 8.87557 6.44006 12.12189 10.19228 0.00113 20.46215 8.19527 5.94582 20.45875 8.17780 5.93308 28.83789 8.44714 9.36806 3.91528 6.45203 8.86355 12.12188 5.95784 8.18330 20.45874 5.94505 8.16576 28.83790 7.29732 8.09110 37.15418 6.31535 10.91690 3.91528 3.39832 10.41953 12.12189 3.90808 11.98867 3.91527 3.13846 9.61985 20.45875 3.13175 9.59923 28.83789 3.37712 10.35445 37.15417 1.33067 12.53653 3.91528 -3.37208 10.41953 12.12189 -3.11222 9.61985 20.45875 -3.10550 9.59923 28.83789 -1.30443 12.53653 3.91528 -1.12475 10.82762 37.15418 -3.88184 11.98867 3.91527 -6.28911 10.91690 3.91528 -6.42579 8.86355 12.12189 -5.93160 8.18330 20.45875 -5.91880 8.16576 28.83789 -7.27106 8.09110 37.15418 -8.42090 9.36806 3.91528 -11.50162 5.12782 3.91528 -8.84933 6.44006 12.12189 -8.16902 5.94582 20.45875 -8.15156 5.93308 28.83789 -9.93184 4.42892 37.15411 -10.99010 0.00113 12.12860 -10.16603 0.00113 20.46214 -10.12771 0.00113 28.83627 -12.59134 0.00113 3.91535 -10.63514 2.26448 37.15411 3.49825 -6.03527 47.24268 7.23523 -6.05897 44.39990 9.67970 -0.00886 44.25639 12.91713 1.09479 -0.14384 9.76257 3.16892 -7.26175 8.30649 6.02662 -7.26175 4.71547 5.68328 -9.95829 6.03859 8.29450 -7.26168 4.72706 -8.16367 44.39983 8.27510 -6.93147 40.89576 7.16706 9.84777 -3.83483 7.64245 10.50204 0.00908 3.18089 9.75057 -7.26168 3.77422 11.57655 -3.83483 4.02411 12.34569 0.00914 -2.27218 7.03446 -9.95872 -3.11307 2.27245 -11.67954 -3.15472 9.75057 -7.26175 0.01312 12.17225 -3.83483 0.01312 12.98097 0.00914 -3.74798 11.57655 -3.83482 -3.99787 12.34569 0.00915 -5.64170 4.78556 -9.95684 -6.01242 8.29450 -7.26175 -7.14089 9.84777 -3.83490 -7.61621 10.50204 0.00908 -8.28025 6.02662 -7.26175 -9.83349 7.15513 -3.83482 -10.48777 7.63049 0.00908 -6.82884 2.31377 -9.95810 -9.73633 3.16892 -7.26175 -11.56236 3.76221 -3.83482 -12.33148 4.01212 0.00908 -12.08549 0.03693 -3.51346 -12.75930 -0.06820 -0.00748 8.27510 6.93376 40.89576 7.23524 6.06125 44.39990 5.35263 4.48149 47.24261 5.40581 9.34144 40.89576 4.72706 8.16591 44.39983 3.49824 6.03750 47.24268 1.88597 10.62254 40.89576 1.65022 9.28577 44.39990 -1.85971 10.62254 40.89576 -1.62397 9.28577 44.39990 -1.19723 6.86544 47.24269 -2.82054 2.37884 49.09227 -5.37955 9.34144 40.89577 -4.70088 8.16591 44.39990 -8.24885 6.93376 40.89577 -7.20898 6.06125 44.39991 -5.32638 4.48149 47.24262 -10.61057 1.65543 40.89317 -9.63732 1.11884 44.52992 -6.58291 0.00113 47.53579 9.95809 -4.42667 37.15411 10.66138 -2.26227 37.15411 -12.31592 -2.61947 3.91528 -10.40525 -3.38397 12.12189 -9.60558 -3.12417 20.45875 -9.58500 -3.11747 28.83789 -10.63514 -2.26227 37.15411 -11.50162 -5.12557 3.91528 -9.93184 -4.42667 37.15411 -8.84933 -6.43777 12.12189 -8.16902 -5.94357 20.45875 -8.15156 -5.93087 28.83789 -8.42090 -9.36577 3.91528 -6.42579 -8.86127 12.12189 -5.93160 -8.18107 20.45875 -5.91880 -8.16347 28.83789 -7.27106 -8.08887 37.15418 -6.28911 -10.91467 3.91528 -3.37208 -10.41727 12.12189 -3.88184 -11.98637 3.91528 -3.11222 -9.61757 20.45875 -3.10550 -9.59697 28.83789 -3.35086 -10.35217 37.15417 -1.30443 -12.53427 3.91528 1.33067 -12.53427 3.91528 1.15100 -10.82537 37.15418 3.39832 -10.41727 12.12189 3.90808 -11.98637 3.91528 3.13846 -9.61757 20.45875 3.13175 -9.59697 28.83789 6.31535 -10.91467 3.91528 6.45203 -8.86127 12.12188 5.95784 -8.18107 20.45874 5.94505 -8.16347 28.83790 7.29732 -8.08887 37.15418 8.44714 -9.36577 3.91528 11.52786 -5.12557 3.91527 8.87557 -6.43777 12.12189 8.19527 -5.94357 20.45875 8.17780 -5.93087 28.83789 10.43149 -3.38397 12.12188 9.63183 -3.12417 20.45875 9.61125 -3.11747 28.83790 12.34216 -2.61947 3.91527 -3.66193 -1.19297 -11.67954 -6.96572 -1.29969 -9.95652 -9.73633 -3.16667 -7.26174 -11.64271 -3.81134 -3.89589 -12.33148 -4.00987 0.00908 -5.96978 -4.34567 -9.95872 -8.28025 -6.02437 -7.26175 -9.83349 -7.15287 -3.83482 -10.48777 -7.62827 0.00908 -6.01242 -8.29227 -7.26175 -7.14089 -9.84547 -3.83490 -7.61621 -10.49977 0.00908 0.01312 -7.39417 -9.95865 0.01312 -10.25007 -7.26175 -3.74798 -11.57427 -3.83482 -3.99787 -12.34347 0.00915 0.01312 -12.16997 -3.83483 0.01312 -12.97867 0.00915 3.13931 -2.27017 -11.67954 2.29842 -7.03217 -9.95873 3.18089 -9.74827 -7.26168 3.77422 -11.57427 -3.83483 4.02411 -12.34347 0.00915 5.99602 -4.34567 -9.95873 6.03859 -8.29227 -7.26168 7.16706 -9.84547 -3.83483 7.64245 -10.49977 0.00908 8.30649 -6.02437 -7.26175 9.85972 -7.15287 -3.83483 10.51401 -7.62827 0.00907 7.04650 -2.28417 -9.95872 9.76257 -3.16667 -7.26175 11.58860 -3.75997 -3.83483 12.35772 -4.00987 0.00907 -10.12170 -3.68767 40.89577 -8.84622 -3.22337 44.39991 -6.53674 -2.38277 47.24269 -3.46287 -1.26402 49.09227 -8.24885 -6.93147 40.89577 -7.20898 -6.05897 44.39991 -5.32638 -4.47927 47.24262 -5.37955 -9.33917 40.89577 -4.70088 -8.16367 44.39991 -3.47199 -6.03527 47.24269 -1.85971 -10.62027 40.89576 -1.62397 -9.28347 44.39991 1.88597 -10.62027 40.89576 1.65022 -9.28347 44.39990 5.40581 -9.33917 40.89576 -3.19907 -6.56849 -9.78374 -3.78335 -9.39795 -7.68514 9.97586 6.39629 -3.98794 10.94574 6.09801 -0.28748 11.56665 1.44050 -3.96156 1.44190 7.54037 -9.95509 7.22986 1.88477 -9.95264 + + + + + + + + + + 0.65940 -0.38071 0.64827 0.44231 -0.11788 0.88908 0.37567 0.01217 0.92667 0.92219 0.29965 0.24447 0.94159 0.30595 -0.14069 0.94475 0.31420 0.09342 0.91917 0.30586 0.24816 0.94793 0.31844 0.00434 0.94357 0.31703 0.09579 0.93878 0.31278 -0.14440 0.94874 0.31606 0.00246 0.79790 0.57971 0.16518 0.69125 0.69126 0.21055 0.70362 0.70363 0.09913 0.70363 0.70362 0.09912 0.70711 0.70710 0.00255 0.70709 0.70712 0.00256 0.80264 0.58316 -0.12528 0.70690 0.70692 -0.02347 0.57718 0.79441 0.18915 0.45176 0.88661 0.09912 0.39708 0.89187 0.21654 0.44530 0.87394 0.19476 0.45399 0.89100 0.00256 0.45176 0.88662 0.09913 0.45302 0.88908 -0.06568 0.45399 0.89100 0.00256 0.49784 0.86227 -0.09299 0.20388 0.95916 0.19606 -0.00000 0.96830 0.24979 -0.00000 0.99543 0.09548 -0.00000 1.00000 0.00246 -0.00000 0.99543 0.09548 -0.00000 0.99590 -0.09044 -0.00000 1.00000 0.00246 -0.00000 0.96830 0.24979 0.10302 0.98016 -0.16932 -0.20388 0.95916 0.19606 -0.39884 0.89582 0.19606 -0.45176 0.88661 0.09913 -0.44382 0.87103 0.21055 -0.45176 0.88662 0.09912 -0.45399 0.89100 0.00256 -0.45399 0.89100 0.00256 -0.40606 0.91202 -0.05784 -0.45387 0.89076 -0.02347 -0.57718 0.79441 0.18915 -0.78794 0.57248 0.22675 -0.70243 0.70245 0.11470 -0.70362 0.70363 0.09912 -0.70363 0.70362 0.09913 -0.70711 0.70710 0.00256 -0.70296 0.70298 -0.10799 -0.70709 0.70712 0.00255 -0.80721 0.58648 -0.06672 -0.91917 0.30586 0.24816 -0.94454 0.31413 0.09570 -0.94379 0.31710 0.09333 -0.94794 0.31844 0.00246 -0.93878 0.31278 -0.14440 -0.94873 0.31606 0.00434 -0.96083 0.20424 0.18732 -0.94159 0.30595 -0.14069 0.48944 -0.58327 0.64826 0.43121 -0.24898 0.86722 0.72633 -0.09772 0.68037 0.92235 -0.15082 0.35571 0.95089 0.30897 0.01846 0.55814 0.28439 -0.77949 0.49213 0.49216 -0.71804 0.60058 -0.71572 0.35643 0.80901 0.58778 0.00398 0.58402 0.80383 0.11304 0.39723 0.77961 -0.48418 0.30759 0.60369 -0.73549 0.39723 0.77960 -0.48418 0.44450 0.87237 -0.20346 0.44450 0.87237 -0.20345 0.45319 0.88943 0.05951 0.40489 0.90940 0.09515 0.00000 0.88253 -0.47025 0.00001 0.70460 -0.70960 0.15316 0.96703 -0.20345 0.11963 0.75532 -0.64434 0.20774 0.97732 0.04113 0.15573 0.98327 0.09450 0.15316 0.96703 -0.20345 0.00000 0.99359 0.11305 -0.13688 0.86420 -0.48417 -0.15316 0.96703 -0.20345 -0.15616 0.98594 0.05951 -0.15316 0.96703 -0.20345 -0.20697 0.97371 0.09515 -0.24580 0.36753 -0.89694 -0.38907 0.58234 -0.71379 -0.28744 0.56414 -0.77403 -0.39723 0.77961 -0.48417 -0.44449 0.87237 -0.20345 -0.39722 0.77961 -0.48417 -0.44450 0.87237 -0.20345 -0.40639 0.91278 0.04112 -0.45196 0.88702 0.09450 -0.58402 0.80383 0.11304 -0.61871 0.61869 -0.48417 -0.49555 0.49554 -0.71335 -0.61871 0.61869 -0.48417 -0.69233 0.69231 -0.20344 -0.69232 0.69232 -0.20346 -0.70585 0.70585 0.05950 -0.79802 0.57979 0.16434 -0.61172 0.29417 -0.73435 -0.41027 0.19750 -0.89032 -0.59794 0.30467 -0.74138 -0.77961 0.39723 -0.48417 -0.77959 0.39724 -0.48418 -0.87236 0.44451 -0.20346 -0.88942 0.45320 0.05951 -0.87237 0.44451 -0.20345 -0.96755 0.20566 0.14681 -0.87370 0.08131 -0.47963 -0.97207 0.11906 -0.20224 -0.99374 0.10403 0.04071 -0.97735 0.10322 -0.18474 0.93079 -0.22073 0.29140 0.93648 0.30429 0.17441 0.92480 0.32437 0.19882 0.90394 0.32014 0.28356 0.70371 0.26783 0.65808 0.87353 0.34362 0.34478 0.41766 0.17547 0.89150 0.73848 0.24813 0.62696 0.80866 0.58753 -0.02959 0.60058 0.71572 0.35643 0.64127 0.76422 0.06880 0.48942 0.58328 0.64827 0.60057 0.71573 0.35644 0.26933 0.32094 0.90800 0.48945 0.58327 0.64825 0.49967 0.86544 -0.03661 0.34121 0.93747 0.06881 0.31955 0.87797 0.35644 0.26043 0.71550 0.64826 0.31956 0.87797 0.35643 -0.00000 0.93432 0.35643 0.10448 0.99409 -0.02959 0.00000 0.99850 0.05473 -0.00000 0.65858 0.75251 0.00000 0.93432 0.35643 0.13478 0.76436 0.63054 0.06535 0.37063 0.92648 0.05375 0.36390 0.92989 -0.31955 0.87798 0.35643 -0.40656 0.91314 -0.02981 -0.33866 0.93047 -0.13974 -0.26041 0.71550 0.64826 -0.31955 0.87798 0.35643 -0.60058 0.71573 0.35642 -0.64127 0.76422 0.06880 -0.42333 0.50448 0.75252 -0.60059 0.71572 0.35644 -0.38808 0.67216 0.63055 -0.25780 0.44650 0.85684 -0.80866 0.58754 -0.02959 -0.90435 0.40457 0.13593 -0.85543 0.38258 0.34911 -0.67924 0.35069 0.64471 -0.85533 0.42793 0.29204 -0.63950 0.22740 0.73439 -0.47521 0.18950 0.85922 -0.94953 0.30853 0.05650 0.74314 -0.15758 0.65032 0.95097 -0.30900 0.01278 -0.97634 -0.10261 0.19035 0.65940 -0.38073 0.64826 -0.98072 -0.16963 0.09698 -0.96361 -0.16690 0.20880 -0.97940 -0.17574 0.09942 -0.98429 -0.17652 0.00451 -0.98519 -0.17144 0.00256 -0.99212 -0.00000 -0.12528 -0.98510 -0.17144 -0.01345 0.80914 -0.46717 0.35644 -0.93388 -0.30345 0.18916 -0.94736 -0.30783 -0.08797 -0.88663 -0.45174 0.09912 -0.87104 -0.44380 0.21055 -0.89100 -0.45399 0.00255 -0.88662 -0.45175 0.09913 -0.88580 -0.45132 -0.10799 -0.89101 -0.45398 0.00255 -0.79790 -0.57972 0.16518 -0.69125 -0.69126 0.21054 -0.70362 -0.70363 0.09913 -0.70712 -0.70709 0.00255 -0.70364 -0.70361 0.09912 -0.70708 -0.70713 0.00257 -0.80264 -0.58316 -0.12528 -0.70689 -0.70694 -0.02346 -0.57719 -0.79440 0.18916 -0.45177 -0.88661 0.09912 -0.39706 -0.89188 0.21655 -0.44531 -0.87394 0.19476 -0.45174 -0.88662 0.09913 -0.45398 -0.89101 0.00257 -0.45302 -0.88908 -0.06569 -0.45400 -0.89100 0.00255 -0.49783 -0.86228 -0.09299 -0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.10408 -0.99021 -0.09299 0.00000 -0.99543 0.09549 0.00000 -1.00000 0.00246 0.00000 -0.99543 0.09549 0.00000 -0.98927 -0.14612 0.00000 -1.00000 0.00246 0.39882 -0.89583 0.19605 0.44383 -0.87103 0.21055 0.45177 -0.88661 0.09913 0.45398 -0.89101 0.00255 0.45174 -0.88662 0.09912 0.45400 -0.89100 0.00256 0.40605 -0.91202 -0.05785 0.45388 -0.89075 -0.02347 0.57719 -0.79440 0.18916 0.78794 -0.57248 0.22675 0.70243 -0.70245 0.11470 0.70362 -0.70363 0.09912 0.70711 -0.70709 0.00256 0.70363 -0.70361 0.09913 0.70295 -0.70300 -0.10800 0.70708 -0.70713 0.00255 0.80721 -0.58648 -0.06672 0.88663 -0.45174 0.09913 0.87104 -0.44380 0.21055 0.89100 -0.45399 0.00255 0.88662 -0.45176 0.09912 0.88580 -0.45132 -0.10799 0.89101 -0.45398 0.00255 0.93388 -0.30345 0.18916 0.94737 -0.30783 -0.08797 0.97395 0.00000 0.22676 0.98001 -0.16953 0.10411 0.86472 -0.49926 0.05473 0.98049 -0.16960 0.09933 0.98429 -0.17651 0.00256 0.97965 -0.17578 0.09687 0.97962 -0.17053 -0.10616 0.80914 -0.46718 0.35642 0.98518 -0.17144 0.00451 0.99814 0.00000 -0.06089 -0.41883 0.06633 -0.90564 -0.46278 0.01714 -0.88630 -0.67576 0.02528 -0.73669 -0.84734 -0.00000 -0.53105 -0.69723 -0.00000 -0.71685 -0.86492 -0.04989 -0.49943 -0.97720 -0.09349 -0.19061 -0.99368 -0.10443 0.04113 -0.99320 -0.10761 0.04443 -0.97821 -0.10692 -0.17798 -0.94496 -0.30704 0.11305 -0.45359 -0.14768 -0.87889 -0.61097 -0.19921 -0.76618 -0.76686 -0.39073 -0.50918 -0.61575 -0.31374 -0.72279 -0.86424 -0.47115 -0.17639 -0.76482 -0.42298 -0.48594 -0.87236 -0.44450 -0.20346 -0.88942 -0.45319 0.05951 -0.61871 -0.61869 -0.48417 -0.48867 -0.48865 -0.72279 -0.69232 -0.69231 -0.20346 -0.61871 -0.61870 -0.48416 -0.69231 -0.69232 -0.20345 -0.58403 -0.80382 0.11304 -0.44450 -0.87237 -0.20345 -0.45320 -0.88942 0.05950 -0.44450 -0.87236 -0.20346 -0.40486 -0.90941 0.09517 -0.15316 -0.96703 -0.20346 -0.13688 -0.86421 -0.48416 -0.15314 -0.96703 -0.20345 -0.20776 -0.97732 0.04111 -0.15571 -0.98327 0.09452 0.00000 -0.99359 0.11304 -0.04633 -0.29252 -0.95514 -0.00000 0.00000 -1.00000 0.05508 -0.34793 -0.93590 0.10810 -0.68256 -0.72280 0.13691 -0.86420 -0.48416 0.10814 -0.68257 -0.72277 0.15316 -0.96703 -0.20345 0.13688 -0.86419 -0.48418 0.15314 -0.96703 -0.20346 0.15614 -0.98594 0.05950 0.20699 -0.97370 0.09517 0.26805 -0.36893 -0.88996 0.41417 -0.57005 -0.70959 0.39721 -0.77961 -0.48419 0.27533 -0.54039 -0.79510 0.44451 -0.87236 -0.20346 0.39724 -0.77960 -0.48416 0.44450 -0.87236 -0.20347 0.40636 -0.91279 0.04111 0.45197 -0.88701 0.09452 0.58403 -0.80382 0.11304 0.48865 -0.48867 -0.72279 0.61869 -0.61871 -0.48416 0.61870 -0.61871 -0.48416 0.69231 -0.69232 -0.20347 0.69231 -0.69232 -0.20346 0.70585 -0.70586 0.05951 0.79801 -0.57980 0.16435 0.39424 -0.20089 -0.89678 0.61573 -0.31376 -0.72279 0.77961 -0.39723 -0.48416 0.61576 -0.31374 -0.72278 0.77959 -0.39725 -0.48418 0.87236 -0.44452 -0.20346 0.88942 -0.45319 0.05951 0.87237 -0.44450 -0.20345 0.94496 -0.30704 0.11305 0.13383 0.18421 -0.97373 0.88253 -0.00000 -0.47026 0.97289 -0.11267 -0.20199 0.99330 -0.10759 0.04225 0.99012 -0.00000 0.14025 -0.99998 0.00000 0.00657 -0.96541 -0.08821 0.24534 -0.99071 -0.09060 0.10143 0.32007 -0.38142 0.86722 -0.72094 -0.15159 0.67621 -0.91692 -0.17775 0.35730 -0.75895 -0.09392 0.64434 0.80866 -0.58753 -0.02958 -0.53838 0.09493 0.83734 -0.95097 -0.30901 0.01278 -0.86472 -0.49926 0.05473 -0.80914 -0.46717 0.35642 -0.65939 -0.38072 0.64827 -0.80913 -0.46718 0.35644 -0.65941 -0.38071 0.64826 -0.43120 -0.24897 0.86722 -0.80866 -0.58753 -0.02958 -0.64128 -0.76422 0.06881 -0.60058 -0.71572 0.35643 -0.60060 -0.71571 0.35642 -0.48945 -0.58326 0.64826 -0.28989 -0.34544 0.89254 -0.48944 -0.58327 0.64827 -0.49966 -0.86545 -0.03660 -0.31955 -0.87798 0.35642 -0.34121 -0.93747 0.06881 -0.26040 -0.71550 0.64827 -0.31953 -0.87798 0.35644 -0.10449 -0.99409 -0.02959 0.00000 -0.99850 0.05473 0.00000 -0.93432 0.35644 0.00000 -0.93432 0.35644 0.00000 -0.65858 0.75251 0.00000 -0.65858 0.75251 0.00000 -0.36144 0.93239 -0.08131 -0.46116 0.88358 -0.00000 -0.00000 1.00000 0.31955 -0.87797 0.35644 0.31954 -0.87798 0.35643 0.26042 -0.71551 0.64825 0.64128 -0.76422 0.06882 0.60058 -0.71572 0.35644 0.48944 -0.58328 0.64825 1.00000 0.00000 0.00101 0.98655 -0.14180 0.08135 0.34197 -0.93958 -0.01567 0.40473 -0.90904 -0.09916 -0.70585 -0.70586 0.05951 -0.79801 -0.57980 0.16435 -0.36980 -0.52149 -0.76896 -0.13804 -0.33996 -0.93025 -0.21598 -0.34123 -0.91483 -0.13938 -0.86261 -0.48629 -0.07283 -0.68476 -0.72513 -0.40615 -0.79712 -0.44682 -0.46051 -0.74162 -0.48778 -0.18784 -0.55980 -0.80706 -0.39250 -0.49426 -0.77566 0.67080 0.56710 -0.47794 0.92989 0.36512 -0.04451 0.80056 0.59863 0.02731 0.78489 0.59931 -0.15741 0.75565 0.62380 -0.19963 0.87564 -0.00807 -0.48290 0.94263 -0.00416 -0.33382 0.89592 0.28578 -0.34009 0.79515 0.40515 -0.45121 0.64712 0.64714 -0.40305 0.91159 0.35315 -0.21046 0.91005 0.29055 -0.29561 0.34281 0.60552 -0.71822 -0.10863 0.80172 -0.58775 -0.04631 0.34671 -0.93683 0.12016 0.21348 -0.96953 0.24246 0.15907 -0.95703 0.40296 -0.01639 -0.91507 0.69942 -0.02972 -0.71409 0.72819 -0.00000 -0.68538 0.57603 0.38022 -0.72362 0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.01762 -0.02100 0.99962 -0.31268 -0.12187 0.94201 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 3 1 4 1 5 2 4 2 3 2 9 3 10 3 11 3 12 4 7 4 13 4 11 5 14 5 15 5 14 6 11 6 10 6 15 7 16 7 13 7 16 8 15 8 14 8 13 9 17 9 12 9 17 10 13 10 16 10 10 11 18 11 14 11 19 12 14 12 18 12 14 13 19 13 16 13 20 14 16 14 19 14 16 15 20 15 17 15 21 16 17 16 20 16 21 17 22 17 12 17 17 18 21 18 12 18 18 19 23 19 19 19 19 20 24 20 20 20 19 21 23 21 25 21 24 22 19 22 25 22 20 23 26 23 21 23 26 24 20 24 24 24 21 25 27 25 22 25 27 26 21 26 26 26 28 27 22 27 27 27 25 28 29 28 24 28 30 29 24 29 29 29 24 30 30 30 26 30 26 31 31 31 27 31 31 32 26 32 30 32 27 33 32 33 28 33 32 34 27 34 31 34 29 35 33 35 30 35 34 36 28 36 32 36 30 37 33 37 35 37 35 38 36 38 30 38 30 39 37 39 31 39 37 40 30 40 36 40 38 41 31 41 37 41 31 42 38 42 32 42 39 43 32 43 38 43 39 44 40 44 34 44 32 45 39 45 34 45 36 46 41 46 37 46 37 47 41 47 42 47 43 48 37 48 42 48 37 49 43 49 38 49 44 50 38 50 43 50 38 51 44 51 39 51 39 52 45 52 40 52 45 53 39 53 44 53 46 54 40 54 45 54 47 55 43 55 42 55 43 56 47 56 44 56 48 57 44 57 47 57 44 58 48 58 45 58 45 59 49 59 46 59 49 60 45 60 48 60 42 61 50 61 47 61 51 62 46 62 49 62 1 63 52 63 53 63 1 64 0 64 4 64 3 65 0 65 54 65 6 66 8 66 2 66 10 67 9 67 55 67 57 68 56 68 58 68 59 69 57 69 58 69 53 70 60 70 61 70 63 71 18 71 10 71 23 72 18 72 63 72 59 73 64 73 62 73 64 74 59 74 58 74 65 75 62 75 64 75 62 76 65 76 63 76 66 77 63 77 65 77 63 78 66 78 23 78 25 79 23 79 66 79 64 80 69 80 65 80 69 81 64 81 67 81 65 82 70 82 66 82 70 83 65 83 69 83 71 84 29 84 25 84 66 85 71 85 25 85 71 86 66 86 70 86 33 87 29 87 71 87 72 88 70 88 69 88 70 89 72 89 71 89 71 90 73 90 33 90 73 91 71 91 72 91 35 92 33 92 73 92 74 93 67 93 68 93 67 94 74 94 69 94 75 95 69 95 74 95 69 96 75 96 72 96 72 97 76 97 73 97 76 98 72 98 75 98 77 99 73 99 76 99 77 100 36 100 35 100 73 101 77 101 35 101 41 102 36 102 77 102 75 103 78 103 76 103 78 104 75 104 74 104 79 105 76 105 78 105 76 106 79 106 77 106 80 107 77 107 79 107 77 108 80 108 41 108 42 109 41 109 80 109 74 110 81 110 78 110 81 111 74 111 68 111 82 112 78 112 81 112 78 113 82 113 79 113 83 114 79 114 82 114 79 115 83 115 80 115 80 116 84 116 42 116 84 117 80 117 83 117 50 118 42 118 84 118 85 119 83 119 82 119 83 120 85 120 84 120 84 121 86 121 50 121 86 122 84 122 85 122 2 123 8 123 54 123 7 124 12 124 8 124 87 125 8 125 12 125 8 126 87 126 54 126 54 127 88 127 3 127 88 128 54 128 87 128 3 129 89 129 5 129 89 130 3 130 88 130 12 131 22 131 87 131 87 132 90 132 88 132 90 133 87 133 22 133 88 134 91 134 89 134 91 135 88 135 90 135 89 136 92 136 5 136 92 137 89 137 91 137 22 138 28 138 90 138 93 139 90 139 28 139 90 140 93 140 91 140 91 141 94 141 92 141 94 142 91 142 93 142 93 143 95 143 94 143 93 144 28 144 34 144 95 145 93 145 34 145 94 146 96 146 92 146 96 147 94 147 95 147 97 148 92 148 96 148 92 149 97 149 5 149 98 150 5 150 97 150 95 151 99 151 96 151 95 152 34 152 40 152 99 153 95 153 40 153 96 154 100 154 97 154 100 155 96 155 99 155 99 156 101 156 100 156 101 157 99 157 40 157 100 158 102 158 97 158 102 159 100 159 101 159 103 160 97 160 102 160 97 161 103 161 98 161 40 162 46 162 101 162 104 163 101 163 46 163 101 164 104 164 102 164 102 165 105 165 103 165 105 166 102 166 104 166 106 167 103 167 105 167 103 168 106 168 98 168 46 169 51 169 104 169 54 170 0 170 2 170 107 171 108 171 6 171 50 172 109 172 47 172 53 173 2 173 1 173 47 174 110 174 48 174 110 175 47 175 109 175 111 176 48 176 110 176 111 177 49 177 48 177 112 178 49 178 111 178 112 179 113 179 51 179 112 180 51 180 49 180 61 181 6 181 53 181 109 182 114 182 110 182 115 183 113 183 112 183 110 184 116 184 111 184 116 185 110 185 114 185 111 186 117 186 112 186 117 187 111 187 116 187 112 188 118 188 115 188 118 189 112 189 117 189 114 190 119 190 116 190 120 191 116 191 119 191 116 192 120 192 117 192 117 193 121 193 118 193 121 194 117 194 120 194 122 195 118 195 121 195 122 196 123 196 115 196 118 197 122 197 115 197 119 198 124 198 120 198 120 199 125 199 121 199 120 200 124 200 126 200 125 201 120 201 126 201 127 202 121 202 125 202 121 203 127 203 122 203 122 204 128 204 123 204 128 205 122 205 127 205 129 206 123 206 128 206 126 207 130 207 125 207 130 208 131 208 125 208 132 209 129 209 128 209 125 210 133 210 127 210 127 211 135 211 128 211 135 212 127 212 133 212 128 213 136 213 132 213 136 214 128 214 135 214 134 215 137 215 133 215 138 216 133 216 137 216 133 217 138 217 135 217 135 218 139 218 136 218 139 219 135 219 138 219 140 220 136 220 139 220 140 221 141 221 132 221 136 222 140 222 132 222 137 223 142 223 138 223 138 224 142 224 143 224 144 225 138 225 143 225 138 226 144 226 139 226 139 227 145 227 140 227 145 228 139 228 144 228 140 229 146 229 141 229 146 230 140 230 145 230 107 231 141 231 146 231 144 232 147 232 145 232 147 233 144 233 143 233 145 234 148 234 146 234 148 235 145 235 147 235 146 236 149 236 107 236 149 237 146 237 148 237 143 238 150 238 147 238 108 239 107 239 149 239 147 240 150 240 9 240 147 241 9 241 11 241 6 242 61 242 107 242 147 243 11 243 148 243 148 244 15 244 149 244 148 245 11 245 15 245 149 246 13 246 108 246 2 247 53 247 6 247 13 248 149 248 15 248 7 249 108 249 13 249 68 250 151 250 81 250 152 251 81 251 151 251 81 252 152 252 82 252 153 253 85 253 82 253 153 254 82 254 152 254 154 255 85 255 153 255 154 256 86 256 85 256 155 257 109 257 50 257 155 258 50 258 86 258 155 259 86 259 154 259 114 260 109 260 155 260 156 261 152 261 151 261 152 262 156 262 153 262 153 263 157 263 154 263 157 264 153 264 156 264 154 265 158 265 155 265 158 266 154 266 157 266 159 267 155 267 158 267 155 268 159 268 114 268 157 269 160 269 158 269 160 270 157 270 156 270 158 271 161 271 159 271 161 272 158 272 160 272 162 273 159 273 161 273 124 274 119 274 162 274 161 275 165 275 162 275 162 276 166 276 124 276 166 277 162 277 165 277 126 278 124 278 166 278 165 279 167 279 166 279 167 280 165 280 164 280 168 281 166 281 167 281 168 282 130 282 126 282 166 283 168 283 126 283 131 284 130 284 168 284 151 285 169 285 163 285 169 286 151 286 68 286 170 287 163 287 169 287 163 288 170 288 164 288 164 289 171 289 167 289 171 290 164 290 170 290 167 291 172 291 168 291 172 292 167 292 171 292 173 293 168 293 172 293 168 294 173 294 131 294 134 295 131 295 173 295 174 296 170 296 169 296 170 297 174 297 171 297 171 298 175 298 172 298 175 299 171 299 174 299 172 300 176 300 173 300 176 301 172 301 175 301 177 302 173 302 176 302 177 303 137 303 134 303 173 304 177 304 134 304 142 305 137 305 177 305 178 306 175 306 174 306 175 307 178 307 176 307 179 308 176 308 178 308 176 309 179 309 177 309 180 310 177 310 179 310 177 311 180 311 142 311 143 312 142 312 180 312 181 313 174 313 169 313 174 314 181 314 178 314 178 315 182 315 179 315 182 316 178 316 181 316 183 317 179 317 182 317 179 318 183 318 180 318 180 319 184 319 143 319 184 320 180 320 183 320 150 321 143 321 184 321 169 322 68 322 58 322 182 323 56 323 183 323 183 324 55 324 184 324 184 325 55 325 150 325 9 326 150 326 55 326 51 327 113 327 104 327 185 328 105 328 104 328 185 329 104 329 113 329 52 330 1 330 4 330 105 331 186 331 106 331 186 332 105 332 185 332 187 333 106 333 186 333 141 334 107 334 61 334 188 335 98 335 187 335 113 336 115 336 185 336 189 337 185 337 115 337 185 338 189 338 186 338 186 339 190 339 187 339 190 340 186 340 189 340 191 341 187 341 190 341 187 342 191 342 188 342 115 343 123 343 189 343 192 344 189 344 123 344 189 345 192 345 190 345 193 346 190 346 192 346 190 347 193 347 191 347 191 348 194 348 188 348 194 349 191 349 193 349 123 350 129 350 192 350 192 351 195 351 193 351 195 352 192 352 129 352 193 353 196 353 194 353 196 354 193 354 195 354 195 355 129 355 132 355 197 356 195 356 132 356 195 357 197 357 196 357 198 358 196 358 197 358 196 359 198 359 194 359 52 360 194 360 198 360 194 361 52 361 188 361 4 362 188 362 52 362 188 363 4 363 98 363 197 364 199 364 198 364 60 365 198 365 199 365 198 366 60 366 52 366 61 367 199 367 141 367 199 368 61 368 60 368 60 369 53 369 52 369 7 370 8 370 108 370 6 371 108 371 8 371 132 372 199 372 197 372 132 373 141 373 199 373 119 374 159 374 162 374 114 375 159 375 119 375 156 376 200 376 160 376 163 377 200 377 151 377 200 378 156 378 151 378 164 379 165 379 201 379 163 380 164 380 201 380 161 381 201 381 165 381 160 382 201 382 161 382 163 383 201 383 200 383 160 384 200 384 201 384 62 385 202 385 59 385 55 386 203 386 10 386 203 387 63 387 10 387 63 388 203 388 202 388 63 389 202 389 62 389 56 390 204 390 183 390 204 391 55 391 183 391 56 392 202 392 204 392 56 393 57 393 202 393 57 394 59 394 202 394 55 395 202 395 203 395 55 396 204 396 202 396 58 397 205 397 64 397 205 398 67 398 64 398 67 399 205 399 68 399 205 400 58 400 68 400 58 401 206 401 169 401 206 402 181 402 169 402 181 403 206 403 182 403 182 404 206 404 56 404 206 405 58 405 56 405 131 406 134 406 133 406 125 407 131 407 133 407 4 408 5 408 98 408 98 409 106 409 187 409

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_proximal/th_proximal_G1M5.dae b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_G1M5.dae new file mode 100644 index 0000000..5e7a25d --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_G1M5.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:18.666034 + 2012-07-23T02:14:18.666047 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + 6.56299 -2.38277 47.24268 5.35263 -4.47927 47.24261 8.87247 -3.22337 44.39990 6.60916 0.00113 47.53578 2.84679 -2.37657 49.09227 2.54221 1.39790 49.16618 10.14795 -3.68767 40.89576 10.66138 2.26448 37.15411 10.65737 -0.00554 41.13606 12.34216 2.62174 3.91527 11.52786 5.12782 3.91527 11.01634 0.00113 12.12860 9.95809 4.42892 37.15411 10.15396 0.00113 28.83627 8.87557 6.44006 12.12189 10.19228 0.00113 20.46215 8.19527 5.94582 20.45875 8.17780 5.93308 28.83789 8.44714 9.36806 3.91528 6.45203 8.86355 12.12188 5.95784 8.18330 20.45874 5.94505 8.16576 28.83790 7.29732 8.09110 37.15418 6.31535 10.91690 3.91528 3.39832 10.41953 12.12189 3.90808 11.98867 3.91527 3.13846 9.61985 20.45875 3.13175 9.59923 28.83789 3.37712 10.35445 37.15417 1.33067 12.53653 3.91528 -3.37208 10.41953 12.12189 -3.11222 9.61985 20.45875 -3.10550 9.59923 28.83789 -1.30443 12.53653 3.91528 -1.12475 10.82762 37.15418 -3.88184 11.98867 3.91527 -6.28911 10.91690 3.91528 -6.42579 8.86355 12.12189 -5.93160 8.18330 20.45875 -5.91880 8.16576 28.83789 -7.27106 8.09110 37.15418 -8.42090 9.36806 3.91528 -11.50162 5.12782 3.91528 -8.84933 6.44006 12.12189 -8.16902 5.94582 20.45875 -8.15156 5.93308 28.83789 -9.93184 4.42892 37.15411 -10.99010 0.00113 12.12860 -10.16603 0.00113 20.46214 -10.12771 0.00113 28.83627 -12.59134 0.00113 3.91535 -10.63514 2.26448 37.15411 3.49825 -6.03527 47.24268 7.23523 -6.05897 44.39990 9.67970 -0.00886 44.25639 12.91713 1.09479 -0.14384 9.76257 3.16892 -7.26175 8.30649 6.02662 -7.26175 4.71547 5.68328 -9.95829 6.03859 8.29450 -7.26168 4.72706 -8.16367 44.39983 8.27510 -6.93147 40.89576 7.16706 9.84777 -3.83483 7.64245 10.50204 0.00908 3.18089 9.75057 -7.26168 3.77422 11.57655 -3.83483 4.02411 12.34569 0.00914 -2.27218 7.03446 -9.95872 -3.11307 2.27245 -11.67954 -3.15472 9.75057 -7.26175 0.01312 12.17225 -3.83483 0.01312 12.98097 0.00914 -3.74798 11.57655 -3.83482 -3.99787 12.34569 0.00915 -5.64170 4.78556 -9.95684 -6.01242 8.29450 -7.26175 -7.14089 9.84777 -3.83490 -7.61621 10.50204 0.00908 -8.28025 6.02662 -7.26175 -9.83349 7.15513 -3.83482 -10.48777 7.63049 0.00908 -6.82884 2.31377 -9.95810 -9.73633 3.16892 -7.26175 -11.56236 3.76221 -3.83482 -12.33148 4.01212 0.00908 -12.08549 0.03693 -3.51346 -12.75930 -0.06820 -0.00748 8.27510 6.93376 40.89576 7.23524 6.06125 44.39990 5.35263 4.48149 47.24261 5.40581 9.34144 40.89576 4.72706 8.16591 44.39983 3.49824 6.03750 47.24268 1.88597 10.62254 40.89576 1.65022 9.28577 44.39990 -1.85971 10.62254 40.89576 -1.62397 9.28577 44.39990 -1.19723 6.86544 47.24269 -2.82054 2.37884 49.09227 -5.37955 9.34144 40.89577 -4.70088 8.16591 44.39990 -8.24885 6.93376 40.89577 -7.20898 6.06125 44.39991 -5.32638 4.48149 47.24262 -10.61057 1.65543 40.89317 -9.63732 1.11884 44.52992 -6.58291 0.00113 47.53579 9.95809 -4.42667 37.15411 10.66138 -2.26227 37.15411 -12.31592 -2.61947 3.91528 -10.40525 -3.38397 12.12189 -9.60558 -3.12417 20.45875 -9.58500 -3.11747 28.83789 -10.63514 -2.26227 37.15411 -11.50162 -5.12557 3.91528 -9.93184 -4.42667 37.15411 -8.84933 -6.43777 12.12189 -8.16902 -5.94357 20.45875 -8.15156 -5.93087 28.83789 -8.42090 -9.36577 3.91528 -6.42579 -8.86127 12.12189 -5.93160 -8.18107 20.45875 -5.91880 -8.16347 28.83789 -7.27106 -8.08887 37.15418 -6.28911 -10.91467 3.91528 -3.37208 -10.41727 12.12189 -3.88184 -11.98637 3.91528 -3.11222 -9.61757 20.45875 -3.10550 -9.59697 28.83789 -3.35086 -10.35217 37.15417 -1.30443 -12.53427 3.91528 1.33067 -12.53427 3.91528 1.15100 -10.82537 37.15418 3.39832 -10.41727 12.12189 3.90808 -11.98637 3.91528 3.13846 -9.61757 20.45875 3.13175 -9.59697 28.83789 6.31535 -10.91467 3.91528 6.45203 -8.86127 12.12188 5.95784 -8.18107 20.45874 5.94505 -8.16347 28.83790 7.29732 -8.08887 37.15418 8.44714 -9.36577 3.91528 11.52786 -5.12557 3.91527 8.87557 -6.43777 12.12189 8.19527 -5.94357 20.45875 8.17780 -5.93087 28.83789 10.43149 -3.38397 12.12188 9.63183 -3.12417 20.45875 9.61125 -3.11747 28.83790 12.34216 -2.61947 3.91527 -3.66193 -1.19297 -11.67954 -6.96572 -1.29969 -9.95652 -9.73633 -3.16667 -7.26174 -11.64271 -3.81134 -3.89589 -12.33148 -4.00987 0.00908 -5.96978 -4.34567 -9.95872 -8.28025 -6.02437 -7.26175 -9.83349 -7.15287 -3.83482 -10.48777 -7.62827 0.00908 -6.01242 -8.29227 -7.26175 -7.14089 -9.84547 -3.83490 -7.61621 -10.49977 0.00908 0.01312 -7.39417 -9.95865 0.01312 -10.25007 -7.26175 -3.74798 -11.57427 -3.83482 -3.99787 -12.34347 0.00915 0.01312 -12.16997 -3.83483 0.01312 -12.97867 0.00915 3.13931 -2.27017 -11.67954 2.29842 -7.03217 -9.95873 3.18089 -9.74827 -7.26168 3.77422 -11.57427 -3.83483 4.02411 -12.34347 0.00915 5.99602 -4.34567 -9.95873 6.03859 -8.29227 -7.26168 7.16706 -9.84547 -3.83483 7.64245 -10.49977 0.00908 8.30649 -6.02437 -7.26175 9.85972 -7.15287 -3.83483 10.51401 -7.62827 0.00907 7.04650 -2.28417 -9.95872 9.76257 -3.16667 -7.26175 11.58860 -3.75997 -3.83483 12.35772 -4.00987 0.00907 -10.12170 -3.68767 40.89577 -8.84622 -3.22337 44.39991 -6.53674 -2.38277 47.24269 -3.46287 -1.26402 49.09227 -8.24885 -6.93147 40.89577 -7.20898 -6.05897 44.39991 -5.32638 -4.47927 47.24262 -5.37955 -9.33917 40.89577 -4.70088 -8.16367 44.39991 -3.47199 -6.03527 47.24269 -1.85971 -10.62027 40.89576 -1.62397 -9.28347 44.39991 1.88597 -10.62027 40.89576 1.65022 -9.28347 44.39990 5.40581 -9.33917 40.89576 -3.19907 -6.56849 -9.78374 -3.78335 -9.39795 -7.68514 9.97586 6.39629 -3.98794 10.94574 6.09801 -0.28748 11.56665 1.44050 -3.96156 1.44190 7.54037 -9.95509 7.22986 1.88477 -9.95264 + + + + + + + + + + 0.65940 -0.38071 0.64827 0.44231 -0.11788 0.88908 0.37567 0.01217 0.92667 0.92219 0.29965 0.24447 0.94159 0.30595 -0.14069 0.94475 0.31420 0.09342 0.91917 0.30586 0.24816 0.94793 0.31844 0.00434 0.94357 0.31703 0.09579 0.93878 0.31278 -0.14440 0.94874 0.31606 0.00246 0.79790 0.57971 0.16518 0.69125 0.69126 0.21055 0.70362 0.70363 0.09913 0.70363 0.70362 0.09912 0.70711 0.70710 0.00255 0.70709 0.70712 0.00256 0.80264 0.58316 -0.12528 0.70690 0.70692 -0.02347 0.57718 0.79441 0.18915 0.45176 0.88661 0.09912 0.39708 0.89187 0.21654 0.44530 0.87394 0.19476 0.45399 0.89100 0.00256 0.45176 0.88662 0.09913 0.45302 0.88908 -0.06568 0.45399 0.89100 0.00256 0.49784 0.86227 -0.09299 0.20388 0.95916 0.19606 -0.00000 0.96830 0.24979 -0.00000 0.99543 0.09548 -0.00000 1.00000 0.00246 -0.00000 0.99543 0.09548 -0.00000 0.99590 -0.09044 -0.00000 1.00000 0.00246 -0.00000 0.96830 0.24979 0.10302 0.98016 -0.16932 -0.20388 0.95916 0.19606 -0.39884 0.89582 0.19606 -0.45176 0.88661 0.09913 -0.44382 0.87103 0.21055 -0.45176 0.88662 0.09912 -0.45399 0.89100 0.00256 -0.45399 0.89100 0.00256 -0.40606 0.91202 -0.05784 -0.45387 0.89076 -0.02347 -0.57718 0.79441 0.18915 -0.78794 0.57248 0.22675 -0.70243 0.70245 0.11470 -0.70362 0.70363 0.09912 -0.70363 0.70362 0.09913 -0.70711 0.70710 0.00256 -0.70296 0.70298 -0.10799 -0.70709 0.70712 0.00255 -0.80721 0.58648 -0.06672 -0.91917 0.30586 0.24816 -0.94454 0.31413 0.09570 -0.94379 0.31710 0.09333 -0.94794 0.31844 0.00246 -0.93878 0.31278 -0.14440 -0.94873 0.31606 0.00434 -0.96083 0.20424 0.18732 -0.94159 0.30595 -0.14069 0.48944 -0.58327 0.64826 0.43121 -0.24898 0.86722 0.72633 -0.09772 0.68037 0.92235 -0.15082 0.35571 0.95089 0.30897 0.01846 0.55814 0.28439 -0.77949 0.49213 0.49216 -0.71804 0.60058 -0.71572 0.35643 0.80901 0.58778 0.00398 0.58402 0.80383 0.11304 0.39723 0.77961 -0.48418 0.30759 0.60369 -0.73549 0.39723 0.77960 -0.48418 0.44450 0.87237 -0.20346 0.44450 0.87237 -0.20345 0.45319 0.88943 0.05951 0.40489 0.90940 0.09515 0.00000 0.88253 -0.47025 0.00001 0.70460 -0.70960 0.15316 0.96703 -0.20345 0.11963 0.75532 -0.64434 0.20774 0.97732 0.04113 0.15573 0.98327 0.09450 0.15316 0.96703 -0.20345 0.00000 0.99359 0.11305 -0.13688 0.86420 -0.48417 -0.15316 0.96703 -0.20345 -0.15616 0.98594 0.05951 -0.15316 0.96703 -0.20345 -0.20697 0.97371 0.09515 -0.24580 0.36753 -0.89694 -0.38907 0.58234 -0.71379 -0.28744 0.56414 -0.77403 -0.39723 0.77961 -0.48417 -0.44449 0.87237 -0.20345 -0.39722 0.77961 -0.48417 -0.44450 0.87237 -0.20345 -0.40639 0.91278 0.04112 -0.45196 0.88702 0.09450 -0.58402 0.80383 0.11304 -0.61871 0.61869 -0.48417 -0.49555 0.49554 -0.71335 -0.61871 0.61869 -0.48417 -0.69233 0.69231 -0.20344 -0.69232 0.69232 -0.20346 -0.70585 0.70585 0.05950 -0.79802 0.57979 0.16434 -0.61172 0.29417 -0.73435 -0.41027 0.19750 -0.89032 -0.59794 0.30467 -0.74138 -0.77961 0.39723 -0.48417 -0.77959 0.39724 -0.48418 -0.87236 0.44451 -0.20346 -0.88942 0.45320 0.05951 -0.87237 0.44451 -0.20345 -0.96755 0.20566 0.14681 -0.87370 0.08131 -0.47963 -0.97207 0.11906 -0.20224 -0.99374 0.10403 0.04071 -0.97735 0.10322 -0.18474 0.93079 -0.22073 0.29140 0.93648 0.30429 0.17441 0.92480 0.32437 0.19882 0.90394 0.32014 0.28356 0.70371 0.26783 0.65808 0.87353 0.34362 0.34478 0.41766 0.17547 0.89150 0.73848 0.24813 0.62696 0.80866 0.58753 -0.02959 0.60058 0.71572 0.35643 0.64127 0.76422 0.06880 0.48942 0.58328 0.64827 0.60057 0.71573 0.35644 0.26933 0.32094 0.90800 0.48945 0.58327 0.64825 0.49967 0.86544 -0.03661 0.34121 0.93747 0.06881 0.31955 0.87797 0.35644 0.26043 0.71550 0.64826 0.31956 0.87797 0.35643 -0.00000 0.93432 0.35643 0.10448 0.99409 -0.02959 0.00000 0.99850 0.05473 -0.00000 0.65858 0.75251 0.00000 0.93432 0.35643 0.13478 0.76436 0.63054 0.06535 0.37063 0.92648 0.05375 0.36390 0.92989 -0.31955 0.87798 0.35643 -0.40656 0.91314 -0.02981 -0.33866 0.93047 -0.13974 -0.26041 0.71550 0.64826 -0.31955 0.87798 0.35643 -0.60058 0.71573 0.35642 -0.64127 0.76422 0.06880 -0.42333 0.50448 0.75252 -0.60059 0.71572 0.35644 -0.38808 0.67216 0.63055 -0.25780 0.44650 0.85684 -0.80866 0.58754 -0.02959 -0.90435 0.40457 0.13593 -0.85543 0.38258 0.34911 -0.67924 0.35069 0.64471 -0.85533 0.42793 0.29204 -0.63950 0.22740 0.73439 -0.47521 0.18950 0.85922 -0.94953 0.30853 0.05650 0.74314 -0.15758 0.65032 0.95097 -0.30900 0.01278 -0.97634 -0.10261 0.19035 0.65940 -0.38073 0.64826 -0.98072 -0.16963 0.09698 -0.96361 -0.16690 0.20880 -0.97940 -0.17574 0.09942 -0.98429 -0.17652 0.00451 -0.98519 -0.17144 0.00256 -0.99212 -0.00000 -0.12528 -0.98510 -0.17144 -0.01345 0.80914 -0.46717 0.35644 -0.93388 -0.30345 0.18916 -0.94736 -0.30783 -0.08797 -0.88663 -0.45174 0.09912 -0.87104 -0.44380 0.21055 -0.89100 -0.45399 0.00255 -0.88662 -0.45175 0.09913 -0.88580 -0.45132 -0.10799 -0.89101 -0.45398 0.00255 -0.79790 -0.57972 0.16518 -0.69125 -0.69126 0.21054 -0.70362 -0.70363 0.09913 -0.70712 -0.70709 0.00255 -0.70364 -0.70361 0.09912 -0.70708 -0.70713 0.00257 -0.80264 -0.58316 -0.12528 -0.70689 -0.70694 -0.02346 -0.57719 -0.79440 0.18916 -0.45177 -0.88661 0.09912 -0.39706 -0.89188 0.21655 -0.44531 -0.87394 0.19476 -0.45174 -0.88662 0.09913 -0.45398 -0.89101 0.00257 -0.45302 -0.88908 -0.06569 -0.45400 -0.89100 0.00255 -0.49783 -0.86228 -0.09299 -0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.10408 -0.99021 -0.09299 0.00000 -0.99543 0.09549 0.00000 -1.00000 0.00246 0.00000 -0.99543 0.09549 0.00000 -0.98927 -0.14612 0.00000 -1.00000 0.00246 0.39882 -0.89583 0.19605 0.44383 -0.87103 0.21055 0.45177 -0.88661 0.09913 0.45398 -0.89101 0.00255 0.45174 -0.88662 0.09912 0.45400 -0.89100 0.00256 0.40605 -0.91202 -0.05785 0.45388 -0.89075 -0.02347 0.57719 -0.79440 0.18916 0.78794 -0.57248 0.22675 0.70243 -0.70245 0.11470 0.70362 -0.70363 0.09912 0.70711 -0.70709 0.00256 0.70363 -0.70361 0.09913 0.70295 -0.70300 -0.10800 0.70708 -0.70713 0.00255 0.80721 -0.58648 -0.06672 0.88663 -0.45174 0.09913 0.87104 -0.44380 0.21055 0.89100 -0.45399 0.00255 0.88662 -0.45176 0.09912 0.88580 -0.45132 -0.10799 0.89101 -0.45398 0.00255 0.93388 -0.30345 0.18916 0.94737 -0.30783 -0.08797 0.97395 0.00000 0.22676 0.98001 -0.16953 0.10411 0.86472 -0.49926 0.05473 0.98049 -0.16960 0.09933 0.98429 -0.17651 0.00256 0.97965 -0.17578 0.09687 0.97962 -0.17053 -0.10616 0.80914 -0.46718 0.35642 0.98518 -0.17144 0.00451 0.99814 0.00000 -0.06089 -0.41883 0.06633 -0.90564 -0.46278 0.01714 -0.88630 -0.67576 0.02528 -0.73669 -0.84734 -0.00000 -0.53105 -0.69723 -0.00000 -0.71685 -0.86492 -0.04989 -0.49943 -0.97720 -0.09349 -0.19061 -0.99368 -0.10443 0.04113 -0.99320 -0.10761 0.04443 -0.97821 -0.10692 -0.17798 -0.94496 -0.30704 0.11305 -0.45359 -0.14768 -0.87889 -0.61097 -0.19921 -0.76618 -0.76686 -0.39073 -0.50918 -0.61575 -0.31374 -0.72279 -0.86424 -0.47115 -0.17639 -0.76482 -0.42298 -0.48594 -0.87236 -0.44450 -0.20346 -0.88942 -0.45319 0.05951 -0.61871 -0.61869 -0.48417 -0.48867 -0.48865 -0.72279 -0.69232 -0.69231 -0.20346 -0.61871 -0.61870 -0.48416 -0.69231 -0.69232 -0.20345 -0.58403 -0.80382 0.11304 -0.44450 -0.87237 -0.20345 -0.45320 -0.88942 0.05950 -0.44450 -0.87236 -0.20346 -0.40486 -0.90941 0.09517 -0.15316 -0.96703 -0.20346 -0.13688 -0.86421 -0.48416 -0.15314 -0.96703 -0.20345 -0.20776 -0.97732 0.04111 -0.15571 -0.98327 0.09452 0.00000 -0.99359 0.11304 -0.04633 -0.29252 -0.95514 -0.00000 0.00000 -1.00000 0.05508 -0.34793 -0.93590 0.10810 -0.68256 -0.72280 0.13691 -0.86420 -0.48416 0.10814 -0.68257 -0.72277 0.15316 -0.96703 -0.20345 0.13688 -0.86419 -0.48418 0.15314 -0.96703 -0.20346 0.15614 -0.98594 0.05950 0.20699 -0.97370 0.09517 0.26805 -0.36893 -0.88996 0.41417 -0.57005 -0.70959 0.39721 -0.77961 -0.48419 0.27533 -0.54039 -0.79510 0.44451 -0.87236 -0.20346 0.39724 -0.77960 -0.48416 0.44450 -0.87236 -0.20347 0.40636 -0.91279 0.04111 0.45197 -0.88701 0.09452 0.58403 -0.80382 0.11304 0.48865 -0.48867 -0.72279 0.61869 -0.61871 -0.48416 0.61870 -0.61871 -0.48416 0.69231 -0.69232 -0.20347 0.69231 -0.69232 -0.20346 0.70585 -0.70586 0.05951 0.79801 -0.57980 0.16435 0.39424 -0.20089 -0.89678 0.61573 -0.31376 -0.72279 0.77961 -0.39723 -0.48416 0.61576 -0.31374 -0.72278 0.77959 -0.39725 -0.48418 0.87236 -0.44452 -0.20346 0.88942 -0.45319 0.05951 0.87237 -0.44450 -0.20345 0.94496 -0.30704 0.11305 0.13383 0.18421 -0.97373 0.88253 -0.00000 -0.47026 0.97289 -0.11267 -0.20199 0.99330 -0.10759 0.04225 0.99012 -0.00000 0.14025 -0.99998 0.00000 0.00657 -0.96541 -0.08821 0.24534 -0.99071 -0.09060 0.10143 0.32007 -0.38142 0.86722 -0.72094 -0.15159 0.67621 -0.91692 -0.17775 0.35730 -0.75895 -0.09392 0.64434 0.80866 -0.58753 -0.02958 -0.53838 0.09493 0.83734 -0.95097 -0.30901 0.01278 -0.86472 -0.49926 0.05473 -0.80914 -0.46717 0.35642 -0.65939 -0.38072 0.64827 -0.80913 -0.46718 0.35644 -0.65941 -0.38071 0.64826 -0.43120 -0.24897 0.86722 -0.80866 -0.58753 -0.02958 -0.64128 -0.76422 0.06881 -0.60058 -0.71572 0.35643 -0.60060 -0.71571 0.35642 -0.48945 -0.58326 0.64826 -0.28989 -0.34544 0.89254 -0.48944 -0.58327 0.64827 -0.49966 -0.86545 -0.03660 -0.31955 -0.87798 0.35642 -0.34121 -0.93747 0.06881 -0.26040 -0.71550 0.64827 -0.31953 -0.87798 0.35644 -0.10449 -0.99409 -0.02959 0.00000 -0.99850 0.05473 0.00000 -0.93432 0.35644 0.00000 -0.93432 0.35644 0.00000 -0.65858 0.75251 0.00000 -0.65858 0.75251 0.00000 -0.36144 0.93239 -0.08131 -0.46116 0.88358 -0.00000 -0.00000 1.00000 0.31955 -0.87797 0.35644 0.31954 -0.87798 0.35643 0.26042 -0.71551 0.64825 0.64128 -0.76422 0.06882 0.60058 -0.71572 0.35644 0.48944 -0.58328 0.64825 1.00000 0.00000 0.00101 0.98655 -0.14180 0.08135 0.34197 -0.93958 -0.01567 0.40473 -0.90904 -0.09916 -0.70585 -0.70586 0.05951 -0.79801 -0.57980 0.16435 -0.36980 -0.52149 -0.76896 -0.13804 -0.33996 -0.93025 -0.21598 -0.34123 -0.91483 -0.13938 -0.86261 -0.48629 -0.07283 -0.68476 -0.72513 -0.40615 -0.79712 -0.44682 -0.46051 -0.74162 -0.48778 -0.18784 -0.55980 -0.80706 -0.39250 -0.49426 -0.77566 0.67080 0.56710 -0.47794 0.92989 0.36512 -0.04451 0.80056 0.59863 0.02731 0.78489 0.59931 -0.15741 0.75565 0.62380 -0.19963 0.87564 -0.00807 -0.48290 0.94263 -0.00416 -0.33382 0.89592 0.28578 -0.34009 0.79515 0.40515 -0.45121 0.64712 0.64714 -0.40305 0.91159 0.35315 -0.21046 0.91005 0.29055 -0.29561 0.34281 0.60552 -0.71822 -0.10863 0.80172 -0.58775 -0.04631 0.34671 -0.93683 0.12016 0.21348 -0.96953 0.24246 0.15907 -0.95703 0.40296 -0.01639 -0.91507 0.69942 -0.02972 -0.71409 0.72819 -0.00000 -0.68538 0.57603 0.38022 -0.72362 0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.01762 -0.02100 0.99962 -0.31268 -0.12187 0.94201 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 3 1 4 1 5 2 4 2 3 2 9 3 10 3 11 3 12 4 7 4 13 4 11 5 14 5 15 5 14 6 11 6 10 6 15 7 16 7 13 7 16 8 15 8 14 8 13 9 17 9 12 9 17 10 13 10 16 10 10 11 18 11 14 11 19 12 14 12 18 12 14 13 19 13 16 13 20 14 16 14 19 14 16 15 20 15 17 15 21 16 17 16 20 16 21 17 22 17 12 17 17 18 21 18 12 18 18 19 23 19 19 19 19 20 24 20 20 20 19 21 23 21 25 21 24 22 19 22 25 22 20 23 26 23 21 23 26 24 20 24 24 24 21 25 27 25 22 25 27 26 21 26 26 26 28 27 22 27 27 27 25 28 29 28 24 28 30 29 24 29 29 29 24 30 30 30 26 30 26 31 31 31 27 31 31 32 26 32 30 32 27 33 32 33 28 33 32 34 27 34 31 34 29 35 33 35 30 35 34 36 28 36 32 36 30 37 33 37 35 37 35 38 36 38 30 38 30 39 37 39 31 39 37 40 30 40 36 40 38 41 31 41 37 41 31 42 38 42 32 42 39 43 32 43 38 43 39 44 40 44 34 44 32 45 39 45 34 45 36 46 41 46 37 46 37 47 41 47 42 47 43 48 37 48 42 48 37 49 43 49 38 49 44 50 38 50 43 50 38 51 44 51 39 51 39 52 45 52 40 52 45 53 39 53 44 53 46 54 40 54 45 54 47 55 43 55 42 55 43 56 47 56 44 56 48 57 44 57 47 57 44 58 48 58 45 58 45 59 49 59 46 59 49 60 45 60 48 60 42 61 50 61 47 61 51 62 46 62 49 62 1 63 52 63 53 63 1 64 0 64 4 64 3 65 0 65 54 65 6 66 8 66 2 66 10 67 9 67 55 67 57 68 56 68 58 68 59 69 57 69 58 69 53 70 60 70 61 70 63 71 18 71 10 71 23 72 18 72 63 72 59 73 64 73 62 73 64 74 59 74 58 74 65 75 62 75 64 75 62 76 65 76 63 76 66 77 63 77 65 77 63 78 66 78 23 78 25 79 23 79 66 79 64 80 69 80 65 80 69 81 64 81 67 81 65 82 70 82 66 82 70 83 65 83 69 83 71 84 29 84 25 84 66 85 71 85 25 85 71 86 66 86 70 86 33 87 29 87 71 87 72 88 70 88 69 88 70 89 72 89 71 89 71 90 73 90 33 90 73 91 71 91 72 91 35 92 33 92 73 92 74 93 67 93 68 93 67 94 74 94 69 94 75 95 69 95 74 95 69 96 75 96 72 96 72 97 76 97 73 97 76 98 72 98 75 98 77 99 73 99 76 99 77 100 36 100 35 100 73 101 77 101 35 101 41 102 36 102 77 102 75 103 78 103 76 103 78 104 75 104 74 104 79 105 76 105 78 105 76 106 79 106 77 106 80 107 77 107 79 107 77 108 80 108 41 108 42 109 41 109 80 109 74 110 81 110 78 110 81 111 74 111 68 111 82 112 78 112 81 112 78 113 82 113 79 113 83 114 79 114 82 114 79 115 83 115 80 115 80 116 84 116 42 116 84 117 80 117 83 117 50 118 42 118 84 118 85 119 83 119 82 119 83 120 85 120 84 120 84 121 86 121 50 121 86 122 84 122 85 122 2 123 8 123 54 123 7 124 12 124 8 124 87 125 8 125 12 125 8 126 87 126 54 126 54 127 88 127 3 127 88 128 54 128 87 128 3 129 89 129 5 129 89 130 3 130 88 130 12 131 22 131 87 131 87 132 90 132 88 132 90 133 87 133 22 133 88 134 91 134 89 134 91 135 88 135 90 135 89 136 92 136 5 136 92 137 89 137 91 137 22 138 28 138 90 138 93 139 90 139 28 139 90 140 93 140 91 140 91 141 94 141 92 141 94 142 91 142 93 142 93 143 95 143 94 143 93 144 28 144 34 144 95 145 93 145 34 145 94 146 96 146 92 146 96 147 94 147 95 147 97 148 92 148 96 148 92 149 97 149 5 149 98 150 5 150 97 150 95 151 99 151 96 151 95 152 34 152 40 152 99 153 95 153 40 153 96 154 100 154 97 154 100 155 96 155 99 155 99 156 101 156 100 156 101 157 99 157 40 157 100 158 102 158 97 158 102 159 100 159 101 159 103 160 97 160 102 160 97 161 103 161 98 161 40 162 46 162 101 162 104 163 101 163 46 163 101 164 104 164 102 164 102 165 105 165 103 165 105 166 102 166 104 166 106 167 103 167 105 167 103 168 106 168 98 168 46 169 51 169 104 169 54 170 0 170 2 170 107 171 108 171 6 171 50 172 109 172 47 172 53 173 2 173 1 173 47 174 110 174 48 174 110 175 47 175 109 175 111 176 48 176 110 176 111 177 49 177 48 177 112 178 49 178 111 178 112 179 113 179 51 179 112 180 51 180 49 180 61 181 6 181 53 181 109 182 114 182 110 182 115 183 113 183 112 183 110 184 116 184 111 184 116 185 110 185 114 185 111 186 117 186 112 186 117 187 111 187 116 187 112 188 118 188 115 188 118 189 112 189 117 189 114 190 119 190 116 190 120 191 116 191 119 191 116 192 120 192 117 192 117 193 121 193 118 193 121 194 117 194 120 194 122 195 118 195 121 195 122 196 123 196 115 196 118 197 122 197 115 197 119 198 124 198 120 198 120 199 125 199 121 199 120 200 124 200 126 200 125 201 120 201 126 201 127 202 121 202 125 202 121 203 127 203 122 203 122 204 128 204 123 204 128 205 122 205 127 205 129 206 123 206 128 206 126 207 130 207 125 207 130 208 131 208 125 208 132 209 129 209 128 209 125 210 133 210 127 210 127 211 135 211 128 211 135 212 127 212 133 212 128 213 136 213 132 213 136 214 128 214 135 214 134 215 137 215 133 215 138 216 133 216 137 216 133 217 138 217 135 217 135 218 139 218 136 218 139 219 135 219 138 219 140 220 136 220 139 220 140 221 141 221 132 221 136 222 140 222 132 222 137 223 142 223 138 223 138 224 142 224 143 224 144 225 138 225 143 225 138 226 144 226 139 226 139 227 145 227 140 227 145 228 139 228 144 228 140 229 146 229 141 229 146 230 140 230 145 230 107 231 141 231 146 231 144 232 147 232 145 232 147 233 144 233 143 233 145 234 148 234 146 234 148 235 145 235 147 235 146 236 149 236 107 236 149 237 146 237 148 237 143 238 150 238 147 238 108 239 107 239 149 239 147 240 150 240 9 240 147 241 9 241 11 241 6 242 61 242 107 242 147 243 11 243 148 243 148 244 15 244 149 244 148 245 11 245 15 245 149 246 13 246 108 246 2 247 53 247 6 247 13 248 149 248 15 248 7 249 108 249 13 249 68 250 151 250 81 250 152 251 81 251 151 251 81 252 152 252 82 252 153 253 85 253 82 253 153 254 82 254 152 254 154 255 85 255 153 255 154 256 86 256 85 256 155 257 109 257 50 257 155 258 50 258 86 258 155 259 86 259 154 259 114 260 109 260 155 260 156 261 152 261 151 261 152 262 156 262 153 262 153 263 157 263 154 263 157 264 153 264 156 264 154 265 158 265 155 265 158 266 154 266 157 266 159 267 155 267 158 267 155 268 159 268 114 268 157 269 160 269 158 269 160 270 157 270 156 270 158 271 161 271 159 271 161 272 158 272 160 272 162 273 159 273 161 273 124 274 119 274 162 274 161 275 165 275 162 275 162 276 166 276 124 276 166 277 162 277 165 277 126 278 124 278 166 278 165 279 167 279 166 279 167 280 165 280 164 280 168 281 166 281 167 281 168 282 130 282 126 282 166 283 168 283 126 283 131 284 130 284 168 284 151 285 169 285 163 285 169 286 151 286 68 286 170 287 163 287 169 287 163 288 170 288 164 288 164 289 171 289 167 289 171 290 164 290 170 290 167 291 172 291 168 291 172 292 167 292 171 292 173 293 168 293 172 293 168 294 173 294 131 294 134 295 131 295 173 295 174 296 170 296 169 296 170 297 174 297 171 297 171 298 175 298 172 298 175 299 171 299 174 299 172 300 176 300 173 300 176 301 172 301 175 301 177 302 173 302 176 302 177 303 137 303 134 303 173 304 177 304 134 304 142 305 137 305 177 305 178 306 175 306 174 306 175 307 178 307 176 307 179 308 176 308 178 308 176 309 179 309 177 309 180 310 177 310 179 310 177 311 180 311 142 311 143 312 142 312 180 312 181 313 174 313 169 313 174 314 181 314 178 314 178 315 182 315 179 315 182 316 178 316 181 316 183 317 179 317 182 317 179 318 183 318 180 318 180 319 184 319 143 319 184 320 180 320 183 320 150 321 143 321 184 321 169 322 68 322 58 322 182 323 56 323 183 323 183 324 55 324 184 324 184 325 55 325 150 325 9 326 150 326 55 326 51 327 113 327 104 327 185 328 105 328 104 328 185 329 104 329 113 329 52 330 1 330 4 330 105 331 186 331 106 331 186 332 105 332 185 332 187 333 106 333 186 333 141 334 107 334 61 334 188 335 98 335 187 335 113 336 115 336 185 336 189 337 185 337 115 337 185 338 189 338 186 338 186 339 190 339 187 339 190 340 186 340 189 340 191 341 187 341 190 341 187 342 191 342 188 342 115 343 123 343 189 343 192 344 189 344 123 344 189 345 192 345 190 345 193 346 190 346 192 346 190 347 193 347 191 347 191 348 194 348 188 348 194 349 191 349 193 349 123 350 129 350 192 350 192 351 195 351 193 351 195 352 192 352 129 352 193 353 196 353 194 353 196 354 193 354 195 354 195 355 129 355 132 355 197 356 195 356 132 356 195 357 197 357 196 357 198 358 196 358 197 358 196 359 198 359 194 359 52 360 194 360 198 360 194 361 52 361 188 361 4 362 188 362 52 362 188 363 4 363 98 363 197 364 199 364 198 364 60 365 198 365 199 365 198 366 60 366 52 366 61 367 199 367 141 367 199 368 61 368 60 368 60 369 53 369 52 369 7 370 8 370 108 370 6 371 108 371 8 371 132 372 199 372 197 372 132 373 141 373 199 373 119 374 159 374 162 374 114 375 159 375 119 375 156 376 200 376 160 376 163 377 200 377 151 377 200 378 156 378 151 378 164 379 165 379 201 379 163 380 164 380 201 380 161 381 201 381 165 381 160 382 201 382 161 382 163 383 201 383 200 383 160 384 200 384 201 384 62 385 202 385 59 385 55 386 203 386 10 386 203 387 63 387 10 387 63 388 203 388 202 388 63 389 202 389 62 389 56 390 204 390 183 390 204 391 55 391 183 391 56 392 202 392 204 392 56 393 57 393 202 393 57 394 59 394 202 394 55 395 202 395 203 395 55 396 204 396 202 396 58 397 205 397 64 397 205 398 67 398 64 398 67 399 205 399 68 399 205 400 58 400 68 400 58 401 206 401 169 401 206 402 181 402 169 402 181 403 206 403 182 403 182 404 206 404 56 404 206 405 58 405 56 405 131 406 134 406 133 406 125 407 131 407 133 407 4 408 5 408 98 408 98 409 106 409 187 409

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/th_proximal/th_proximal_G4.dae b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_G4.dae new file mode 100644 index 0000000..84feb8e --- /dev/null +++ b/URDFs/sr_description/meshes/components/th_proximal/th_proximal_G4.dae @@ -0,0 +1,139 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:18.666034 + 2012-07-23T02:14:18.666047 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.05997 0.05997 0.05997 1 + + + 0.16355 0.16355 0.16355 1 + + + 0.36585 0.36585 0.36585 1 + + + 12.5 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + 6.56299 -2.38277 47.24268 5.35263 -4.47927 47.24261 8.87247 -3.22337 44.39990 6.60916 0.00113 47.53578 2.84679 -2.37657 49.09227 2.54221 1.39790 49.16618 10.14795 -3.68767 40.89576 10.66138 2.26448 37.15411 10.65737 -0.00554 41.13606 12.34216 2.62174 3.91527 11.52786 5.12782 3.91527 11.01634 0.00113 12.12860 9.95809 4.42892 37.15411 10.15396 0.00113 28.83627 8.87557 6.44006 12.12189 10.19228 0.00113 20.46215 8.19527 5.94582 20.45875 8.17780 5.93308 28.83789 8.44714 9.36806 3.91528 6.45203 8.86355 12.12188 5.95784 8.18330 20.45874 5.94505 8.16576 28.83790 7.29732 8.09110 37.15418 6.31535 10.91690 3.91528 3.39832 10.41953 12.12189 3.90808 11.98867 3.91527 3.13846 9.61985 20.45875 3.13175 9.59923 28.83789 3.37712 10.35445 37.15417 1.33067 12.53653 3.91528 -3.37208 10.41953 12.12189 -3.11222 9.61985 20.45875 -3.10550 9.59923 28.83789 -1.30443 12.53653 3.91528 -1.12475 10.82762 37.15418 -3.88184 11.98867 3.91527 -6.28911 10.91690 3.91528 -6.42579 8.86355 12.12189 -5.93160 8.18330 20.45875 -5.91880 8.16576 28.83789 -7.27106 8.09110 37.15418 -8.42090 9.36806 3.91528 -11.50162 5.12782 3.91528 -8.84933 6.44006 12.12189 -8.16902 5.94582 20.45875 -8.15156 5.93308 28.83789 -9.93184 4.42892 37.15411 -10.99010 0.00113 12.12860 -10.16603 0.00113 20.46214 -10.12771 0.00113 28.83627 -12.59134 0.00113 3.91535 -10.63514 2.26448 37.15411 3.49825 -6.03527 47.24268 7.23523 -6.05897 44.39990 9.67970 -0.00886 44.25639 12.91713 1.09479 -0.14384 9.76257 3.16892 -7.26175 8.30649 6.02662 -7.26175 4.71547 5.68328 -9.95829 6.03859 8.29450 -7.26168 4.72706 -8.16367 44.39983 8.27510 -6.93147 40.89576 7.16706 9.84777 -3.83483 7.64245 10.50204 0.00908 3.18089 9.75057 -7.26168 3.77422 11.57655 -3.83483 4.02411 12.34569 0.00914 -2.27218 7.03446 -9.95872 -3.11307 2.27245 -11.67954 -3.15472 9.75057 -7.26175 0.01312 12.17225 -3.83483 0.01312 12.98097 0.00914 -3.74798 11.57655 -3.83482 -3.99787 12.34569 0.00915 -5.64170 4.78556 -9.95684 -6.01242 8.29450 -7.26175 -7.14089 9.84777 -3.83490 -7.61621 10.50204 0.00908 -8.28025 6.02662 -7.26175 -9.83349 7.15513 -3.83482 -10.48777 7.63049 0.00908 -6.82884 2.31377 -9.95810 -9.73633 3.16892 -7.26175 -11.56236 3.76221 -3.83482 -12.33148 4.01212 0.00908 -12.08549 0.03693 -3.51346 -12.75930 -0.06820 -0.00748 8.27510 6.93376 40.89576 7.23524 6.06125 44.39990 5.35263 4.48149 47.24261 5.40581 9.34144 40.89576 4.72706 8.16591 44.39983 3.49824 6.03750 47.24268 1.88597 10.62254 40.89576 1.65022 9.28577 44.39990 -1.85971 10.62254 40.89576 -1.62397 9.28577 44.39990 -1.19723 6.86544 47.24269 -2.82054 2.37884 49.09227 -5.37955 9.34144 40.89577 -4.70088 8.16591 44.39990 -8.24885 6.93376 40.89577 -7.20898 6.06125 44.39991 -5.32638 4.48149 47.24262 -10.61057 1.65543 40.89317 -9.63732 1.11884 44.52992 -6.58291 0.00113 47.53579 9.95809 -4.42667 37.15411 10.66138 -2.26227 37.15411 -12.31592 -2.61947 3.91528 -10.40525 -3.38397 12.12189 -9.60558 -3.12417 20.45875 -9.58500 -3.11747 28.83789 -10.63514 -2.26227 37.15411 -11.50162 -5.12557 3.91528 -9.93184 -4.42667 37.15411 -8.84933 -6.43777 12.12189 -8.16902 -5.94357 20.45875 -8.15156 -5.93087 28.83789 -8.42090 -9.36577 3.91528 -6.42579 -8.86127 12.12189 -5.93160 -8.18107 20.45875 -5.91880 -8.16347 28.83789 -7.27106 -8.08887 37.15418 -6.28911 -10.91467 3.91528 -3.37208 -10.41727 12.12189 -3.88184 -11.98637 3.91528 -3.11222 -9.61757 20.45875 -3.10550 -9.59697 28.83789 -3.35086 -10.35217 37.15417 -1.30443 -12.53427 3.91528 1.33067 -12.53427 3.91528 1.15100 -10.82537 37.15418 3.39832 -10.41727 12.12189 3.90808 -11.98637 3.91528 3.13846 -9.61757 20.45875 3.13175 -9.59697 28.83789 6.31535 -10.91467 3.91528 6.45203 -8.86127 12.12188 5.95784 -8.18107 20.45874 5.94505 -8.16347 28.83790 7.29732 -8.08887 37.15418 8.44714 -9.36577 3.91528 11.52786 -5.12557 3.91527 8.87557 -6.43777 12.12189 8.19527 -5.94357 20.45875 8.17780 -5.93087 28.83789 10.43149 -3.38397 12.12188 9.63183 -3.12417 20.45875 9.61125 -3.11747 28.83790 12.34216 -2.61947 3.91527 -3.66193 -1.19297 -11.67954 -6.96572 -1.29969 -9.95652 -9.73633 -3.16667 -7.26174 -11.64271 -3.81134 -3.89589 -12.33148 -4.00987 0.00908 -5.96978 -4.34567 -9.95872 -8.28025 -6.02437 -7.26175 -9.83349 -7.15287 -3.83482 -10.48777 -7.62827 0.00908 -6.01242 -8.29227 -7.26175 -7.14089 -9.84547 -3.83490 -7.61621 -10.49977 0.00908 0.01312 -7.39417 -9.95865 0.01312 -10.25007 -7.26175 -3.74798 -11.57427 -3.83482 -3.99787 -12.34347 0.00915 0.01312 -12.16997 -3.83483 0.01312 -12.97867 0.00915 3.13931 -2.27017 -11.67954 2.29842 -7.03217 -9.95873 3.18089 -9.74827 -7.26168 3.77422 -11.57427 -3.83483 4.02411 -12.34347 0.00915 5.99602 -4.34567 -9.95873 6.03859 -8.29227 -7.26168 7.16706 -9.84547 -3.83483 7.64245 -10.49977 0.00908 8.30649 -6.02437 -7.26175 9.85972 -7.15287 -3.83483 10.51401 -7.62827 0.00907 7.04650 -2.28417 -9.95872 9.76257 -3.16667 -7.26175 11.58860 -3.75997 -3.83483 12.35772 -4.00987 0.00907 -10.12170 -3.68767 40.89577 -8.84622 -3.22337 44.39991 -6.53674 -2.38277 47.24269 -3.46287 -1.26402 49.09227 -8.24885 -6.93147 40.89577 -7.20898 -6.05897 44.39991 -5.32638 -4.47927 47.24262 -5.37955 -9.33917 40.89577 -4.70088 -8.16367 44.39991 -3.47199 -6.03527 47.24269 -1.85971 -10.62027 40.89576 -1.62397 -9.28347 44.39991 1.88597 -10.62027 40.89576 1.65022 -9.28347 44.39990 5.40581 -9.33917 40.89576 -3.19907 -6.56849 -9.78374 -3.78335 -9.39795 -7.68514 9.97586 6.39629 -3.98794 10.94574 6.09801 -0.28748 11.56665 1.44050 -3.96156 1.44190 7.54037 -9.95509 7.22986 1.88477 -9.95264 + + + + + + + + + + 0.65940 -0.38071 0.64827 0.44231 -0.11788 0.88908 0.37567 0.01217 0.92667 0.92219 0.29965 0.24447 0.94159 0.30595 -0.14069 0.94475 0.31420 0.09342 0.91917 0.30586 0.24816 0.94793 0.31844 0.00434 0.94357 0.31703 0.09579 0.93878 0.31278 -0.14440 0.94874 0.31606 0.00246 0.79790 0.57971 0.16518 0.69125 0.69126 0.21055 0.70362 0.70363 0.09913 0.70363 0.70362 0.09912 0.70711 0.70710 0.00255 0.70709 0.70712 0.00256 0.80264 0.58316 -0.12528 0.70690 0.70692 -0.02347 0.57718 0.79441 0.18915 0.45176 0.88661 0.09912 0.39708 0.89187 0.21654 0.44530 0.87394 0.19476 0.45399 0.89100 0.00256 0.45176 0.88662 0.09913 0.45302 0.88908 -0.06568 0.45399 0.89100 0.00256 0.49784 0.86227 -0.09299 0.20388 0.95916 0.19606 -0.00000 0.96830 0.24979 -0.00000 0.99543 0.09548 -0.00000 1.00000 0.00246 -0.00000 0.99543 0.09548 -0.00000 0.99590 -0.09044 -0.00000 1.00000 0.00246 -0.00000 0.96830 0.24979 0.10302 0.98016 -0.16932 -0.20388 0.95916 0.19606 -0.39884 0.89582 0.19606 -0.45176 0.88661 0.09913 -0.44382 0.87103 0.21055 -0.45176 0.88662 0.09912 -0.45399 0.89100 0.00256 -0.45399 0.89100 0.00256 -0.40606 0.91202 -0.05784 -0.45387 0.89076 -0.02347 -0.57718 0.79441 0.18915 -0.78794 0.57248 0.22675 -0.70243 0.70245 0.11470 -0.70362 0.70363 0.09912 -0.70363 0.70362 0.09913 -0.70711 0.70710 0.00256 -0.70296 0.70298 -0.10799 -0.70709 0.70712 0.00255 -0.80721 0.58648 -0.06672 -0.91917 0.30586 0.24816 -0.94454 0.31413 0.09570 -0.94379 0.31710 0.09333 -0.94794 0.31844 0.00246 -0.93878 0.31278 -0.14440 -0.94873 0.31606 0.00434 -0.96083 0.20424 0.18732 -0.94159 0.30595 -0.14069 0.48944 -0.58327 0.64826 0.43121 -0.24898 0.86722 0.72633 -0.09772 0.68037 0.92235 -0.15082 0.35571 0.95089 0.30897 0.01846 0.55814 0.28439 -0.77949 0.49213 0.49216 -0.71804 0.60058 -0.71572 0.35643 0.80901 0.58778 0.00398 0.58402 0.80383 0.11304 0.39723 0.77961 -0.48418 0.30759 0.60369 -0.73549 0.39723 0.77960 -0.48418 0.44450 0.87237 -0.20346 0.44450 0.87237 -0.20345 0.45319 0.88943 0.05951 0.40489 0.90940 0.09515 0.00000 0.88253 -0.47025 0.00001 0.70460 -0.70960 0.15316 0.96703 -0.20345 0.11963 0.75532 -0.64434 0.20774 0.97732 0.04113 0.15573 0.98327 0.09450 0.15316 0.96703 -0.20345 0.00000 0.99359 0.11305 -0.13688 0.86420 -0.48417 -0.15316 0.96703 -0.20345 -0.15616 0.98594 0.05951 -0.15316 0.96703 -0.20345 -0.20697 0.97371 0.09515 -0.24580 0.36753 -0.89694 -0.38907 0.58234 -0.71379 -0.28744 0.56414 -0.77403 -0.39723 0.77961 -0.48417 -0.44449 0.87237 -0.20345 -0.39722 0.77961 -0.48417 -0.44450 0.87237 -0.20345 -0.40639 0.91278 0.04112 -0.45196 0.88702 0.09450 -0.58402 0.80383 0.11304 -0.61871 0.61869 -0.48417 -0.49555 0.49554 -0.71335 -0.61871 0.61869 -0.48417 -0.69233 0.69231 -0.20344 -0.69232 0.69232 -0.20346 -0.70585 0.70585 0.05950 -0.79802 0.57979 0.16434 -0.61172 0.29417 -0.73435 -0.41027 0.19750 -0.89032 -0.59794 0.30467 -0.74138 -0.77961 0.39723 -0.48417 -0.77959 0.39724 -0.48418 -0.87236 0.44451 -0.20346 -0.88942 0.45320 0.05951 -0.87237 0.44451 -0.20345 -0.96755 0.20566 0.14681 -0.87370 0.08131 -0.47963 -0.97207 0.11906 -0.20224 -0.99374 0.10403 0.04071 -0.97735 0.10322 -0.18474 0.93079 -0.22073 0.29140 0.93648 0.30429 0.17441 0.92480 0.32437 0.19882 0.90394 0.32014 0.28356 0.70371 0.26783 0.65808 0.87353 0.34362 0.34478 0.41766 0.17547 0.89150 0.73848 0.24813 0.62696 0.80866 0.58753 -0.02959 0.60058 0.71572 0.35643 0.64127 0.76422 0.06880 0.48942 0.58328 0.64827 0.60057 0.71573 0.35644 0.26933 0.32094 0.90800 0.48945 0.58327 0.64825 0.49967 0.86544 -0.03661 0.34121 0.93747 0.06881 0.31955 0.87797 0.35644 0.26043 0.71550 0.64826 0.31956 0.87797 0.35643 -0.00000 0.93432 0.35643 0.10448 0.99409 -0.02959 0.00000 0.99850 0.05473 -0.00000 0.65858 0.75251 0.00000 0.93432 0.35643 0.13478 0.76436 0.63054 0.06535 0.37063 0.92648 0.05375 0.36390 0.92989 -0.31955 0.87798 0.35643 -0.40656 0.91314 -0.02981 -0.33866 0.93047 -0.13974 -0.26041 0.71550 0.64826 -0.31955 0.87798 0.35643 -0.60058 0.71573 0.35642 -0.64127 0.76422 0.06880 -0.42333 0.50448 0.75252 -0.60059 0.71572 0.35644 -0.38808 0.67216 0.63055 -0.25780 0.44650 0.85684 -0.80866 0.58754 -0.02959 -0.90435 0.40457 0.13593 -0.85543 0.38258 0.34911 -0.67924 0.35069 0.64471 -0.85533 0.42793 0.29204 -0.63950 0.22740 0.73439 -0.47521 0.18950 0.85922 -0.94953 0.30853 0.05650 0.74314 -0.15758 0.65032 0.95097 -0.30900 0.01278 -0.97634 -0.10261 0.19035 0.65940 -0.38073 0.64826 -0.98072 -0.16963 0.09698 -0.96361 -0.16690 0.20880 -0.97940 -0.17574 0.09942 -0.98429 -0.17652 0.00451 -0.98519 -0.17144 0.00256 -0.99212 -0.00000 -0.12528 -0.98510 -0.17144 -0.01345 0.80914 -0.46717 0.35644 -0.93388 -0.30345 0.18916 -0.94736 -0.30783 -0.08797 -0.88663 -0.45174 0.09912 -0.87104 -0.44380 0.21055 -0.89100 -0.45399 0.00255 -0.88662 -0.45175 0.09913 -0.88580 -0.45132 -0.10799 -0.89101 -0.45398 0.00255 -0.79790 -0.57972 0.16518 -0.69125 -0.69126 0.21054 -0.70362 -0.70363 0.09913 -0.70712 -0.70709 0.00255 -0.70364 -0.70361 0.09912 -0.70708 -0.70713 0.00257 -0.80264 -0.58316 -0.12528 -0.70689 -0.70694 -0.02346 -0.57719 -0.79440 0.18916 -0.45177 -0.88661 0.09912 -0.39706 -0.89188 0.21655 -0.44531 -0.87394 0.19476 -0.45174 -0.88662 0.09913 -0.45398 -0.89101 0.00257 -0.45302 -0.88908 -0.06569 -0.45400 -0.89100 0.00255 -0.49783 -0.86228 -0.09299 -0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.10408 -0.99021 -0.09299 0.00000 -0.99543 0.09549 0.00000 -1.00000 0.00246 0.00000 -0.99543 0.09549 0.00000 -0.98927 -0.14612 0.00000 -1.00000 0.00246 0.39882 -0.89583 0.19605 0.44383 -0.87103 0.21055 0.45177 -0.88661 0.09913 0.45398 -0.89101 0.00255 0.45174 -0.88662 0.09912 0.45400 -0.89100 0.00256 0.40605 -0.91202 -0.05785 0.45388 -0.89075 -0.02347 0.57719 -0.79440 0.18916 0.78794 -0.57248 0.22675 0.70243 -0.70245 0.11470 0.70362 -0.70363 0.09912 0.70711 -0.70709 0.00256 0.70363 -0.70361 0.09913 0.70295 -0.70300 -0.10800 0.70708 -0.70713 0.00255 0.80721 -0.58648 -0.06672 0.88663 -0.45174 0.09913 0.87104 -0.44380 0.21055 0.89100 -0.45399 0.00255 0.88662 -0.45176 0.09912 0.88580 -0.45132 -0.10799 0.89101 -0.45398 0.00255 0.93388 -0.30345 0.18916 0.94737 -0.30783 -0.08797 0.97395 0.00000 0.22676 0.98001 -0.16953 0.10411 0.86472 -0.49926 0.05473 0.98049 -0.16960 0.09933 0.98429 -0.17651 0.00256 0.97965 -0.17578 0.09687 0.97962 -0.17053 -0.10616 0.80914 -0.46718 0.35642 0.98518 -0.17144 0.00451 0.99814 0.00000 -0.06089 -0.41883 0.06633 -0.90564 -0.46278 0.01714 -0.88630 -0.67576 0.02528 -0.73669 -0.84734 -0.00000 -0.53105 -0.69723 -0.00000 -0.71685 -0.86492 -0.04989 -0.49943 -0.97720 -0.09349 -0.19061 -0.99368 -0.10443 0.04113 -0.99320 -0.10761 0.04443 -0.97821 -0.10692 -0.17798 -0.94496 -0.30704 0.11305 -0.45359 -0.14768 -0.87889 -0.61097 -0.19921 -0.76618 -0.76686 -0.39073 -0.50918 -0.61575 -0.31374 -0.72279 -0.86424 -0.47115 -0.17639 -0.76482 -0.42298 -0.48594 -0.87236 -0.44450 -0.20346 -0.88942 -0.45319 0.05951 -0.61871 -0.61869 -0.48417 -0.48867 -0.48865 -0.72279 -0.69232 -0.69231 -0.20346 -0.61871 -0.61870 -0.48416 -0.69231 -0.69232 -0.20345 -0.58403 -0.80382 0.11304 -0.44450 -0.87237 -0.20345 -0.45320 -0.88942 0.05950 -0.44450 -0.87236 -0.20346 -0.40486 -0.90941 0.09517 -0.15316 -0.96703 -0.20346 -0.13688 -0.86421 -0.48416 -0.15314 -0.96703 -0.20345 -0.20776 -0.97732 0.04111 -0.15571 -0.98327 0.09452 0.00000 -0.99359 0.11304 -0.04633 -0.29252 -0.95514 -0.00000 0.00000 -1.00000 0.05508 -0.34793 -0.93590 0.10810 -0.68256 -0.72280 0.13691 -0.86420 -0.48416 0.10814 -0.68257 -0.72277 0.15316 -0.96703 -0.20345 0.13688 -0.86419 -0.48418 0.15314 -0.96703 -0.20346 0.15614 -0.98594 0.05950 0.20699 -0.97370 0.09517 0.26805 -0.36893 -0.88996 0.41417 -0.57005 -0.70959 0.39721 -0.77961 -0.48419 0.27533 -0.54039 -0.79510 0.44451 -0.87236 -0.20346 0.39724 -0.77960 -0.48416 0.44450 -0.87236 -0.20347 0.40636 -0.91279 0.04111 0.45197 -0.88701 0.09452 0.58403 -0.80382 0.11304 0.48865 -0.48867 -0.72279 0.61869 -0.61871 -0.48416 0.61870 -0.61871 -0.48416 0.69231 -0.69232 -0.20347 0.69231 -0.69232 -0.20346 0.70585 -0.70586 0.05951 0.79801 -0.57980 0.16435 0.39424 -0.20089 -0.89678 0.61573 -0.31376 -0.72279 0.77961 -0.39723 -0.48416 0.61576 -0.31374 -0.72278 0.77959 -0.39725 -0.48418 0.87236 -0.44452 -0.20346 0.88942 -0.45319 0.05951 0.87237 -0.44450 -0.20345 0.94496 -0.30704 0.11305 0.13383 0.18421 -0.97373 0.88253 -0.00000 -0.47026 0.97289 -0.11267 -0.20199 0.99330 -0.10759 0.04225 0.99012 -0.00000 0.14025 -0.99998 0.00000 0.00657 -0.96541 -0.08821 0.24534 -0.99071 -0.09060 0.10143 0.32007 -0.38142 0.86722 -0.72094 -0.15159 0.67621 -0.91692 -0.17775 0.35730 -0.75895 -0.09392 0.64434 0.80866 -0.58753 -0.02958 -0.53838 0.09493 0.83734 -0.95097 -0.30901 0.01278 -0.86472 -0.49926 0.05473 -0.80914 -0.46717 0.35642 -0.65939 -0.38072 0.64827 -0.80913 -0.46718 0.35644 -0.65941 -0.38071 0.64826 -0.43120 -0.24897 0.86722 -0.80866 -0.58753 -0.02958 -0.64128 -0.76422 0.06881 -0.60058 -0.71572 0.35643 -0.60060 -0.71571 0.35642 -0.48945 -0.58326 0.64826 -0.28989 -0.34544 0.89254 -0.48944 -0.58327 0.64827 -0.49966 -0.86545 -0.03660 -0.31955 -0.87798 0.35642 -0.34121 -0.93747 0.06881 -0.26040 -0.71550 0.64827 -0.31953 -0.87798 0.35644 -0.10449 -0.99409 -0.02959 0.00000 -0.99850 0.05473 0.00000 -0.93432 0.35644 0.00000 -0.93432 0.35644 0.00000 -0.65858 0.75251 0.00000 -0.65858 0.75251 0.00000 -0.36144 0.93239 -0.08131 -0.46116 0.88358 -0.00000 -0.00000 1.00000 0.31955 -0.87797 0.35644 0.31954 -0.87798 0.35643 0.26042 -0.71551 0.64825 0.64128 -0.76422 0.06882 0.60058 -0.71572 0.35644 0.48944 -0.58328 0.64825 1.00000 0.00000 0.00101 0.98655 -0.14180 0.08135 0.34197 -0.93958 -0.01567 0.40473 -0.90904 -0.09916 -0.70585 -0.70586 0.05951 -0.79801 -0.57980 0.16435 -0.36980 -0.52149 -0.76896 -0.13804 -0.33996 -0.93025 -0.21598 -0.34123 -0.91483 -0.13938 -0.86261 -0.48629 -0.07283 -0.68476 -0.72513 -0.40615 -0.79712 -0.44682 -0.46051 -0.74162 -0.48778 -0.18784 -0.55980 -0.80706 -0.39250 -0.49426 -0.77566 0.67080 0.56710 -0.47794 0.92989 0.36512 -0.04451 0.80056 0.59863 0.02731 0.78489 0.59931 -0.15741 0.75565 0.62380 -0.19963 0.87564 -0.00807 -0.48290 0.94263 -0.00416 -0.33382 0.89592 0.28578 -0.34009 0.79515 0.40515 -0.45121 0.64712 0.64714 -0.40305 0.91159 0.35315 -0.21046 0.91005 0.29055 -0.29561 0.34281 0.60552 -0.71822 -0.10863 0.80172 -0.58775 -0.04631 0.34671 -0.93683 0.12016 0.21348 -0.96953 0.24246 0.15907 -0.95703 0.40296 -0.01639 -0.91507 0.69942 -0.02972 -0.71409 0.72819 -0.00000 -0.68538 0.57603 0.38022 -0.72362 0.20390 -0.95916 0.19606 0.00000 -0.96830 0.24979 -0.01762 -0.02100 0.99962 -0.31268 -0.12187 0.94201 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 3 1 4 1 5 2 4 2 3 2 9 3 10 3 11 3 12 4 7 4 13 4 11 5 14 5 15 5 14 6 11 6 10 6 15 7 16 7 13 7 16 8 15 8 14 8 13 9 17 9 12 9 17 10 13 10 16 10 10 11 18 11 14 11 19 12 14 12 18 12 14 13 19 13 16 13 20 14 16 14 19 14 16 15 20 15 17 15 21 16 17 16 20 16 21 17 22 17 12 17 17 18 21 18 12 18 18 19 23 19 19 19 19 20 24 20 20 20 19 21 23 21 25 21 24 22 19 22 25 22 20 23 26 23 21 23 26 24 20 24 24 24 21 25 27 25 22 25 27 26 21 26 26 26 28 27 22 27 27 27 25 28 29 28 24 28 30 29 24 29 29 29 24 30 30 30 26 30 26 31 31 31 27 31 31 32 26 32 30 32 27 33 32 33 28 33 32 34 27 34 31 34 29 35 33 35 30 35 34 36 28 36 32 36 30 37 33 37 35 37 35 38 36 38 30 38 30 39 37 39 31 39 37 40 30 40 36 40 38 41 31 41 37 41 31 42 38 42 32 42 39 43 32 43 38 43 39 44 40 44 34 44 32 45 39 45 34 45 36 46 41 46 37 46 37 47 41 47 42 47 43 48 37 48 42 48 37 49 43 49 38 49 44 50 38 50 43 50 38 51 44 51 39 51 39 52 45 52 40 52 45 53 39 53 44 53 46 54 40 54 45 54 47 55 43 55 42 55 43 56 47 56 44 56 48 57 44 57 47 57 44 58 48 58 45 58 45 59 49 59 46 59 49 60 45 60 48 60 42 61 50 61 47 61 51 62 46 62 49 62 1 63 52 63 53 63 1 64 0 64 4 64 3 65 0 65 54 65 6 66 8 66 2 66 10 67 9 67 55 67 57 68 56 68 58 68 59 69 57 69 58 69 53 70 60 70 61 70 63 71 18 71 10 71 23 72 18 72 63 72 59 73 64 73 62 73 64 74 59 74 58 74 65 75 62 75 64 75 62 76 65 76 63 76 66 77 63 77 65 77 63 78 66 78 23 78 25 79 23 79 66 79 64 80 69 80 65 80 69 81 64 81 67 81 65 82 70 82 66 82 70 83 65 83 69 83 71 84 29 84 25 84 66 85 71 85 25 85 71 86 66 86 70 86 33 87 29 87 71 87 72 88 70 88 69 88 70 89 72 89 71 89 71 90 73 90 33 90 73 91 71 91 72 91 35 92 33 92 73 92 74 93 67 93 68 93 67 94 74 94 69 94 75 95 69 95 74 95 69 96 75 96 72 96 72 97 76 97 73 97 76 98 72 98 75 98 77 99 73 99 76 99 77 100 36 100 35 100 73 101 77 101 35 101 41 102 36 102 77 102 75 103 78 103 76 103 78 104 75 104 74 104 79 105 76 105 78 105 76 106 79 106 77 106 80 107 77 107 79 107 77 108 80 108 41 108 42 109 41 109 80 109 74 110 81 110 78 110 81 111 74 111 68 111 82 112 78 112 81 112 78 113 82 113 79 113 83 114 79 114 82 114 79 115 83 115 80 115 80 116 84 116 42 116 84 117 80 117 83 117 50 118 42 118 84 118 85 119 83 119 82 119 83 120 85 120 84 120 84 121 86 121 50 121 86 122 84 122 85 122 2 123 8 123 54 123 7 124 12 124 8 124 87 125 8 125 12 125 8 126 87 126 54 126 54 127 88 127 3 127 88 128 54 128 87 128 3 129 89 129 5 129 89 130 3 130 88 130 12 131 22 131 87 131 87 132 90 132 88 132 90 133 87 133 22 133 88 134 91 134 89 134 91 135 88 135 90 135 89 136 92 136 5 136 92 137 89 137 91 137 22 138 28 138 90 138 93 139 90 139 28 139 90 140 93 140 91 140 91 141 94 141 92 141 94 142 91 142 93 142 93 143 95 143 94 143 93 144 28 144 34 144 95 145 93 145 34 145 94 146 96 146 92 146 96 147 94 147 95 147 97 148 92 148 96 148 92 149 97 149 5 149 98 150 5 150 97 150 95 151 99 151 96 151 95 152 34 152 40 152 99 153 95 153 40 153 96 154 100 154 97 154 100 155 96 155 99 155 99 156 101 156 100 156 101 157 99 157 40 157 100 158 102 158 97 158 102 159 100 159 101 159 103 160 97 160 102 160 97 161 103 161 98 161 40 162 46 162 101 162 104 163 101 163 46 163 101 164 104 164 102 164 102 165 105 165 103 165 105 166 102 166 104 166 106 167 103 167 105 167 103 168 106 168 98 168 46 169 51 169 104 169 54 170 0 170 2 170 107 171 108 171 6 171 50 172 109 172 47 172 53 173 2 173 1 173 47 174 110 174 48 174 110 175 47 175 109 175 111 176 48 176 110 176 111 177 49 177 48 177 112 178 49 178 111 178 112 179 113 179 51 179 112 180 51 180 49 180 61 181 6 181 53 181 109 182 114 182 110 182 115 183 113 183 112 183 110 184 116 184 111 184 116 185 110 185 114 185 111 186 117 186 112 186 117 187 111 187 116 187 112 188 118 188 115 188 118 189 112 189 117 189 114 190 119 190 116 190 120 191 116 191 119 191 116 192 120 192 117 192 117 193 121 193 118 193 121 194 117 194 120 194 122 195 118 195 121 195 122 196 123 196 115 196 118 197 122 197 115 197 119 198 124 198 120 198 120 199 125 199 121 199 120 200 124 200 126 200 125 201 120 201 126 201 127 202 121 202 125 202 121 203 127 203 122 203 122 204 128 204 123 204 128 205 122 205 127 205 129 206 123 206 128 206 126 207 130 207 125 207 130 208 131 208 125 208 132 209 129 209 128 209 125 210 133 210 127 210 127 211 135 211 128 211 135 212 127 212 133 212 128 213 136 213 132 213 136 214 128 214 135 214 134 215 137 215 133 215 138 216 133 216 137 216 133 217 138 217 135 217 135 218 139 218 136 218 139 219 135 219 138 219 140 220 136 220 139 220 140 221 141 221 132 221 136 222 140 222 132 222 137 223 142 223 138 223 138 224 142 224 143 224 144 225 138 225 143 225 138 226 144 226 139 226 139 227 145 227 140 227 145 228 139 228 144 228 140 229 146 229 141 229 146 230 140 230 145 230 107 231 141 231 146 231 144 232 147 232 145 232 147 233 144 233 143 233 145 234 148 234 146 234 148 235 145 235 147 235 146 236 149 236 107 236 149 237 146 237 148 237 143 238 150 238 147 238 108 239 107 239 149 239 147 240 150 240 9 240 147 241 9 241 11 241 6 242 61 242 107 242 147 243 11 243 148 243 148 244 15 244 149 244 148 245 11 245 15 245 149 246 13 246 108 246 2 247 53 247 6 247 13 248 149 248 15 248 7 249 108 249 13 249 68 250 151 250 81 250 152 251 81 251 151 251 81 252 152 252 82 252 153 253 85 253 82 253 153 254 82 254 152 254 154 255 85 255 153 255 154 256 86 256 85 256 155 257 109 257 50 257 155 258 50 258 86 258 155 259 86 259 154 259 114 260 109 260 155 260 156 261 152 261 151 261 152 262 156 262 153 262 153 263 157 263 154 263 157 264 153 264 156 264 154 265 158 265 155 265 158 266 154 266 157 266 159 267 155 267 158 267 155 268 159 268 114 268 157 269 160 269 158 269 160 270 157 270 156 270 158 271 161 271 159 271 161 272 158 272 160 272 162 273 159 273 161 273 124 274 119 274 162 274 161 275 165 275 162 275 162 276 166 276 124 276 166 277 162 277 165 277 126 278 124 278 166 278 165 279 167 279 166 279 167 280 165 280 164 280 168 281 166 281 167 281 168 282 130 282 126 282 166 283 168 283 126 283 131 284 130 284 168 284 151 285 169 285 163 285 169 286 151 286 68 286 170 287 163 287 169 287 163 288 170 288 164 288 164 289 171 289 167 289 171 290 164 290 170 290 167 291 172 291 168 291 172 292 167 292 171 292 173 293 168 293 172 293 168 294 173 294 131 294 134 295 131 295 173 295 174 296 170 296 169 296 170 297 174 297 171 297 171 298 175 298 172 298 175 299 171 299 174 299 172 300 176 300 173 300 176 301 172 301 175 301 177 302 173 302 176 302 177 303 137 303 134 303 173 304 177 304 134 304 142 305 137 305 177 305 178 306 175 306 174 306 175 307 178 307 176 307 179 308 176 308 178 308 176 309 179 309 177 309 180 310 177 310 179 310 177 311 180 311 142 311 143 312 142 312 180 312 181 313 174 313 169 313 174 314 181 314 178 314 178 315 182 315 179 315 182 316 178 316 181 316 183 317 179 317 182 317 179 318 183 318 180 318 180 319 184 319 143 319 184 320 180 320 183 320 150 321 143 321 184 321 169 322 68 322 58 322 182 323 56 323 183 323 183 324 55 324 184 324 184 325 55 325 150 325 9 326 150 326 55 326 51 327 113 327 104 327 185 328 105 328 104 328 185 329 104 329 113 329 52 330 1 330 4 330 105 331 186 331 106 331 186 332 105 332 185 332 187 333 106 333 186 333 141 334 107 334 61 334 188 335 98 335 187 335 113 336 115 336 185 336 189 337 185 337 115 337 185 338 189 338 186 338 186 339 190 339 187 339 190 340 186 340 189 340 191 341 187 341 190 341 187 342 191 342 188 342 115 343 123 343 189 343 192 344 189 344 123 344 189 345 192 345 190 345 193 346 190 346 192 346 190 347 193 347 191 347 191 348 194 348 188 348 194 349 191 349 193 349 123 350 129 350 192 350 192 351 195 351 193 351 195 352 192 352 129 352 193 353 196 353 194 353 196 354 193 354 195 354 195 355 129 355 132 355 197 356 195 356 132 356 195 357 197 357 196 357 198 358 196 358 197 358 196 359 198 359 194 359 52 360 194 360 198 360 194 361 52 361 188 361 4 362 188 362 52 362 188 363 4 363 98 363 197 364 199 364 198 364 60 365 198 365 199 365 198 366 60 366 52 366 61 367 199 367 141 367 199 368 61 368 60 368 60 369 53 369 52 369 7 370 8 370 108 370 6 371 108 371 8 371 132 372 199 372 197 372 132 373 141 373 199 373 119 374 159 374 162 374 114 375 159 375 119 375 156 376 200 376 160 376 163 377 200 377 151 377 200 378 156 378 151 378 164 379 165 379 201 379 163 380 164 380 201 380 161 381 201 381 165 381 160 382 201 382 161 382 163 383 201 383 200 383 160 384 200 384 201 384 62 385 202 385 59 385 55 386 203 386 10 386 203 387 63 387 10 387 63 388 203 388 202 388 63 389 202 389 62 389 56 390 204 390 183 390 204 391 55 391 183 391 56 392 202 392 204 392 56 393 57 393 202 393 57 394 59 394 202 394 55 395 202 395 203 395 55 396 204 396 202 396 58 397 205 397 64 397 205 398 67 398 64 398 67 399 205 399 68 399 205 400 58 400 68 400 58 401 206 401 169 401 206 402 181 402 169 402 181 403 206 403 182 403 182 404 206 404 56 404 206 405 58 405 56 405 131 406 134 406 133 406 125 407 131 407 133 407 4 408 5 408 98 408 98 409 106 409 187 409

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/wrist/wrist_C6M2.dae b/URDFs/sr_description/meshes/components/wrist/wrist_C6M2.dae new file mode 100644 index 0000000..5f1f221 --- /dev/null +++ b/URDFs/sr_description/meshes/components/wrist/wrist_C6M2.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:55.555034 + 2012-07-23T02:14:55.555052 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -12.60386 -0.00040 -4.55191 -0.54290 13.89959 -4.46761 0.54193 13.89959 -4.46761 -1.59620 13.89959 -4.20799 1.59524 13.89959 -4.20799 -2.55677 13.89959 -3.70385 2.55581 13.89959 -3.70385 -3.36878 13.89959 -2.98447 3.36782 13.89959 -2.98447 -3.98503 13.89959 -2.09167 3.98407 13.89959 -2.09167 -4.36972 13.89959 -1.07734 4.36876 13.89959 -1.07734 -4.50048 13.89959 -0.00042 4.49952 13.89959 -0.00042 -4.36972 13.89959 1.07650 4.36876 13.89959 1.07650 -3.98503 13.89959 2.09083 3.98407 13.89959 2.09083 -3.36878 13.89959 2.98363 3.36782 13.89959 2.98363 -2.55677 13.89959 3.70301 2.55581 13.89959 3.70301 -1.59621 13.89959 4.20715 -0.54290 13.89959 4.46677 1.59524 13.89959 4.20715 0.54193 13.89959 4.46677 2.31715 10.59960 -7.13334 2.31714 10.59959 7.13250 0.78348 10.59960 -7.45934 0.78348 10.59959 7.45849 -0.78445 10.59960 -7.45934 -0.78445 10.59959 7.45849 -2.31811 10.59960 -7.13334 -2.31811 10.59959 7.13250 -3.75048 10.59960 -6.49561 -3.75048 10.59959 6.49477 -5.01896 10.59959 5.57317 -5.01896 10.59960 -5.57401 -6.06811 10.59960 -4.40881 -6.06811 10.59959 4.40797 -6.85207 10.59960 -3.05095 -6.85207 10.59960 3.05010 -7.33659 10.59960 1.55892 -7.33659 10.59960 -1.55976 -7.50048 10.59960 -0.00042 -7.33659 -10.60041 1.55892 -7.50049 -10.60041 -0.00042 -7.33659 -10.60041 -1.55976 -6.85208 -10.60040 -3.05095 -6.85208 -10.60041 3.05010 -6.06812 -10.60041 4.40797 -6.06811 -10.60041 -4.40881 -5.01897 -10.60041 -5.57401 -5.01897 -10.60041 5.57317 -3.75049 -10.60041 6.49477 -3.75048 -10.60041 -6.49561 -2.31811 -10.60041 7.13250 -2.31811 -10.60041 -7.13334 -0.78445 -10.60041 7.45849 -0.78445 -10.60041 -7.45934 0.78348 -10.60041 7.45849 0.78348 -10.60041 -7.45934 2.31714 -10.60041 7.13250 2.31714 -10.60041 -7.13334 -14.48772 7.22568 1.21112 -13.95641 7.52509 0.93113 -14.19300 7.34965 1.09963 -13.90642 5.60705 -0.55767 -13.79636 3.38683 -1.54026 -13.62562 5.80287 -0.82700 -13.37415 3.55958 -2.00872 -13.63172 7.84658 0.62766 -13.42834 6.02566 -1.14744 -13.47899 8.13542 0.34559 -13.59057 1.00859 -2.05556 -13.29065 0.99960 -2.43023 -13.81941 -3.37846 -1.52380 -14.03224 -5.53306 -0.46171 -13.55213 -0.99182 -2.09744 -13.25895 -1.00324 -2.49002 -13.38795 -3.54875 -1.98317 -13.58612 -5.82680 -0.86263 -14.26401 -7.32159 1.13379 -13.91214 -7.54561 0.91654 -13.62985 -7.86254 0.60894 -13.45037 -8.20210 0.28867 -13.43177 -8.35835 0.13871 -13.33815 -8.96163 6.94725 -14.02152 -9.25673 4.06271 -12.62189 -7.88431 7.72702 -13.68860 -9.47942 5.55454 -12.17220 -7.98916 7.62231 -12.79561 -9.12583 6.73785 -13.52762 -9.55666 3.80315 -13.12857 -9.80029 5.34117 -11.80590 -8.10198 7.60052 -12.36982 -9.38179 6.66783 -11.38435 -8.27721 7.68078 -12.05107 -9.64642 6.67054 -13.18897 -10.02901 3.50122 -12.65820 -10.25672 5.20334 -12.34419 -10.50040 5.65164 -13.10623 -10.46706 3.30983 -10.99744 -8.47381 7.83888 -11.76268 -9.96988 6.73570 -12.25473 -6.40498 7.99782 -11.72898 -6.40560 7.93281 -11.17216 -6.40683 8.02417 -10.64307 -6.40915 8.28321 -14.26038 9.15721 4.16294 -12.29217 6.40601 8.00338 -13.74552 9.47000 5.58112 -12.55224 7.89330 7.70474 -13.03981 9.03588 6.82450 -13.85801 9.33975 3.98340 -13.33376 9.66441 5.42183 -12.56829 9.24682 6.69359 -13.50539 9.60548 3.77503 -11.92678 8.05235 7.58945 -13.02474 9.90194 5.30744 -11.80182 6.40682 7.93720 -12.21385 9.49928 6.66542 -13.26845 9.92961 3.56703 -11.13580 6.40570 8.03591 -13.11173 10.18750 3.41007 -11.28393 8.31322 7.69886 -10.73077 6.40590 8.22361 -12.64398 10.38079 5.24346 -11.84269 9.83655 6.69265 -12.47477 10.49960 5.26739 -10.75736 8.63854 8.05253 -24.88471 -9.35137 23.00377 -24.13114 -9.40305 23.00179 -23.38857 -9.26547 23.01383 -22.12126 -8.46693 23.01970 -22.70383 -8.94547 23.00735 -21.39638 -7.15635 23.02859 -21.67562 -7.85566 23.01203 -23.87215 -9.40192 20.17845 -23.19525 -9.38724 17.47330 -21.99669 -8.94589 18.29033 -20.99868 -7.85505 18.54457 -21.94929 -9.39938 14.24081 -20.17987 -8.94589 13.92521 -19.26540 -7.85505 14.39999 -19.93711 -9.40192 10.96064 -17.36017 -8.94589 10.12988 -16.57709 -7.85505 10.80070 -17.34748 -9.40192 8.11977 -13.71346 -8.96542 7.08199 -13.04990 -7.81858 7.94862 -14.23772 -9.38277 5.85688 -24.88455 9.34945 22.99273 -23.38881 9.26415 22.99850 -24.13438 9.40093 22.94129 -22.70510 8.94655 22.96461 -22.12062 8.46669 23.00962 -21.39598 7.15553 23.02449 -21.67454 7.85688 22.98570 -21.99899 8.94669 18.28904 -21.00004 7.85689 18.54399 -23.36385 9.40128 17.86201 -20.18188 8.94669 13.92356 -19.26665 7.85689 14.39923 -21.37263 9.40128 13.12622 -17.36185 8.94669 10.12793 -16.57822 7.85689 10.79978 -13.63308 8.92521 7.04131 -18.28204 9.40128 9.02243 -12.95601 7.82493 7.86842 -14.24571 9.39143 5.82465 -28.29540 7.12390 23.04268 -30.07768 4.28939 23.02099 -30.54342 2.67371 23.01016 -29.31952 5.79025 23.03187 -25.59235 9.09639 23.03309 -27.04103 8.24381 23.05341 -25.28474 9.10898 19.71424 -27.61936 7.12429 17.71068 -29.29788 4.28653 17.06409 -24.50582 9.10898 16.57668 -23.27924 9.10898 13.58126 -25.81796 7.12429 12.64688 -27.20717 4.28652 11.43173 -21.63284 9.10898 10.79699 -22.97470 7.12429 8.08584 -23.91240 4.28652 6.40789 -19.60074 9.10898 8.28056 -14.54596 9.10868 4.25243 -17.22583 9.10898 6.08501 -19.22128 7.12429 4.23888 -14.43425 5.40799 -0.30267 -14.73110 7.12708 1.28862 -19.57969 4.28652 2.24588 -14.20562 3.28901 -1.33376 -30.07768 -4.29019 23.02099 -29.31952 -5.79105 23.03187 -30.54342 -2.67451 23.01016 -28.29363 -7.12628 23.04270 -27.04103 -8.24461 23.05341 -25.60065 -9.11085 23.01348 -25.46428 -9.10979 20.96733 -25.15497 -9.10979 19.02628 -24.67524 -9.10978 17.11820 -27.61719 -7.12757 17.71145 -29.29673 -4.29047 17.06458 -25.81612 -7.12757 12.64832 -23.24655 -9.10978 13.51576 -27.20625 -4.29047 11.43263 -21.96199 -9.10978 11.28491 -20.42908 -9.10979 9.21762 -22.97337 -7.12757 8.08786 -23.91183 -4.29047 6.40911 -18.66796 -9.10979 7.34085 -16.70228 -9.10979 5.67980 -14.44149 -9.10329 4.22508 -19.22062 -7.12757 4.24131 -14.62641 -7.17487 1.26451 -14.47512 -5.33858 -0.21095 -19.57957 -4.29047 2.24733 -14.24722 -3.28159 -1.25828 -13.08897 10.47856 3.10286 -13.40044 10.49960 0.03300 -13.40676 8.41941 0.07982 -13.40044 -10.50040 0.03300 -13.32003 -6.17464 -1.36950 -13.32796 6.25340 -1.48803 -13.20270 10.49960 -2.29430 -13.09723 3.74191 -2.54411 -13.05894 0.99960 -3.00666 -13.09158 -1.00050 -2.92509 -13.19020 -3.70530 -2.44498 -13.20271 -10.50040 -2.29430 -12.60386 10.49960 -4.55191 -12.60386 -10.50040 -4.55191 -11.62209 10.49960 -6.67124 -11.62209 -10.50040 -6.67124 -10.28724 10.49960 -8.58790 -10.28724 -10.50040 -8.58790 -8.63985 10.49960 -10.24366 -8.63985 -10.50040 -10.24366 -6.72998 10.49960 -11.58821 -6.72998 -10.50040 -11.58821 -4.61565 10.49959 -12.58070 -4.61565 -10.50041 -12.58070 -2.36111 10.49959 -13.19098 -2.36110 -10.50041 -13.19098 -0.03484 10.49959 -13.40051 -0.03483 -10.50041 -13.40051 2.29247 10.49959 -13.20291 2.29248 -10.50041 -13.20291 2.15348 10.49959 13.22520 2.15348 -10.50041 13.22520 -0.07688 10.49959 13.39923 -0.07689 -10.50041 13.39923 -2.30523 10.49959 13.19976 -2.30524 -10.50041 13.19976 -4.46929 10.49959 12.63234 -4.46930 -10.50041 12.63233 -6.50868 10.49959 11.71284 -6.50869 -10.50041 11.71283 -8.36659 10.49959 10.46694 -8.36661 -10.50041 10.46692 -11.33783 10.49960 7.14268 -10.58126 8.76704 8.21934 -9.99129 10.49960 8.92939 -11.34845 -10.49318 7.12164 -10.66137 -8.70710 8.12063 -10.28659 -6.40669 8.60038 -10.25925 6.40596 8.62536 -9.99131 -10.50040 8.92937 -0.00049 -15.40040 -7.50042 1.46269 -15.40040 -7.35631 -1.46366 -15.40040 -7.35631 2.86964 -15.40040 -6.92952 -2.87061 -15.40040 -6.92952 4.16629 -15.40041 -6.23644 -4.16726 -15.40040 -6.23644 5.30282 -15.40041 -5.30372 -5.30379 -15.40040 -5.30372 6.23554 -15.40041 -4.16720 -6.23651 -15.40040 -4.16720 6.92861 -15.40041 -2.87055 -6.92958 -15.40040 -2.87055 7.35540 -15.40041 -1.46360 -7.35638 -15.40040 -1.46360 7.49951 -15.40041 -0.00042 -7.50049 -15.40040 -0.00042 7.35540 -15.40041 1.46276 -7.35638 -15.40040 1.46276 6.92861 -15.40041 2.86971 -6.92958 -15.40040 2.86971 6.23553 -15.40041 4.16636 -6.23651 -15.40041 4.16636 5.30281 -15.40041 5.30288 -5.30379 -15.40041 5.30288 4.16629 -15.40041 6.23560 -4.16727 -15.40041 6.23560 2.86964 -15.40041 6.92868 -2.87061 -15.40041 6.92868 -1.46367 -15.40041 7.35547 -0.00049 -15.40041 7.49958 1.46269 -15.40041 7.35547 -0.00048 15.39959 7.49958 1.46269 15.39959 7.35547 -1.46366 15.39959 7.35547 2.86964 15.39959 6.92868 -2.87061 15.39959 6.92868 4.16629 15.39959 6.23560 -4.16726 15.39959 6.23560 5.30282 15.39959 5.30288 -0.00048 15.39959 4.49958 -5.30378 15.39959 5.30288 1.00086 15.39959 4.38676 -1.00183 15.39959 4.38676 6.23554 15.39959 4.16636 1.95199 15.39959 4.05394 -1.95296 15.39959 4.05394 -6.23651 15.39959 4.16636 -2.80619 15.39959 3.51782 -3.51872 15.39959 2.80528 -6.92958 15.39959 2.86971 -4.05484 15.39959 1.95206 -4.38766 15.39959 1.00093 -7.35637 15.39959 1.46276 -4.50048 15.39959 -0.00042 -7.50048 15.39959 -0.00042 -4.38766 15.39959 -1.00176 -4.05484 15.39959 -1.95290 -7.35637 15.39959 -1.46360 -3.51872 15.39959 -2.80612 -2.80619 15.39959 -3.51866 -6.92958 15.39960 -2.87055 1.95200 15.39959 -4.05478 -1.95296 15.39959 -4.05478 1.00086 15.39959 -4.38760 -0.00048 15.39959 -4.50042 -1.00182 15.39959 -4.38760 -6.23650 15.39959 -4.16720 5.30282 15.39959 -5.30372 -5.30378 15.39959 -5.30372 4.16630 15.39959 -6.23644 -4.16726 15.39959 -6.23644 2.86965 15.39959 -6.92952 -2.87061 15.39959 -6.92952 -1.46366 15.39959 -7.35631 -0.00048 15.39959 -7.50042 1.46270 15.39959 -7.35631 -21.30162 -6.40750 23.03941 -21.30144 6.40653 23.02324 -21.05293 -6.40666 20.48503 -21.05293 6.40585 20.48503 -20.45402 -6.40666 18.02602 -20.45402 6.40585 18.02602 -19.51434 -6.40666 15.67261 -19.51434 6.40585 15.67261 -18.25390 -6.40666 13.47585 -18.25390 6.40585 13.47586 -16.69758 -6.40666 11.47834 -16.69758 6.40585 11.47835 -14.87602 -6.40666 9.71929 -12.82573 -6.40666 8.23382 -14.87602 6.40585 9.71929 -12.82573 6.40585 8.23383 -30.41643 -1.00040 19.53470 -29.69563 0.99960 16.13403 -28.54962 0.99960 12.85194 -26.99694 0.99960 9.74162 -26.99669 -1.00040 9.74117 -25.06267 0.99960 6.85320 -25.06223 -1.00040 6.85262 -22.77773 0.99960 4.23294 -22.77734 -1.00040 4.23257 -20.17892 0.99960 1.92327 -20.17875 -1.00040 1.92313 -17.30873 0.99960 -0.03817 -14.21282 0.99960 -1.62019 -17.30859 -1.00040 -0.03825 -14.21282 -1.00040 -1.62019 -30.69927 0.99943 23.04174 -30.70291 -1.00075 23.02165 -30.41645 0.99960 19.53490 -29.69556 -1.00040 16.13377 -28.54948 -1.00040 12.85162 35.56442 -1.00041 18.82635 35.89960 1.00018 23.02512 35.89865 -1.00030 23.04285 35.60408 0.99999 18.94442 34.68587 -1.00041 14.73265 34.68535 0.99959 14.73082 33.27864 -1.00041 10.78832 33.27790 0.99959 10.78664 31.36698 -1.00041 7.06207 31.36615 0.99959 7.06070 28.98425 -1.00041 3.61868 28.98302 0.99959 3.61714 26.17130 -1.00041 0.51695 26.16953 0.99959 0.51526 22.97604 -1.00041 -2.19013 22.97423 0.99959 -2.19147 19.45300 -1.00041 -4.45602 19.45189 0.99959 -4.45665 15.66376 -1.00041 -6.24092 15.66357 0.99959 -6.24101 11.64083 -0.99333 -7.51363 11.67386 0.99959 -7.51412 26.49701 -6.40790 23.00487 26.50031 6.40680 23.03065 26.24158 -6.40714 20.03259 26.24143 6.40632 20.03162 25.59420 -6.40714 17.12513 25.59365 6.40632 17.12325 24.56920 -6.40714 14.32965 24.56801 6.40632 14.32697 23.18434 -6.40714 11.69390 23.18226 6.40632 11.69051 21.45901 -6.40714 9.25799 21.45568 6.40632 9.25390 19.44430 -6.40714 7.08838 19.44081 6.40632 7.08509 17.34859 -6.40714 5.33769 17.34648 6.40632 5.33613 15.28735 6.40805 3.98648 15.28216 -6.40734 3.98093 6.23554 15.39959 -4.16720 2.80522 15.39959 -3.51866 6.92861 15.39959 -2.87055 3.51776 15.39959 -2.80612 4.05388 15.39959 -1.95290 7.35541 15.39959 -1.46360 4.38669 15.39959 -1.00176 4.49952 15.39959 -0.00042 7.49952 15.39959 -0.00042 4.38669 15.39959 1.00093 7.35541 15.39959 1.46276 4.05388 15.39959 1.95206 3.51776 15.39959 2.80528 6.92861 15.39959 2.86971 2.80522 15.39959 3.51782 4.32370 -10.50041 12.68256 4.32371 10.49959 12.68256 6.37333 -10.50041 11.78650 6.37333 10.49959 11.78649 8.24526 -10.50041 10.56201 8.24527 10.49959 10.56200 9.88738 -10.50041 9.04324 9.88738 10.49959 9.04324 11.25394 -10.50041 7.27254 11.25394 10.49959 7.27254 12.30691 -10.50041 5.29925 12.30692 10.49959 5.29925 12.48335 -6.40739 4.90258 12.71416 -9.07247 4.22862 12.43964 6.40632 4.97975 12.68775 9.13363 4.25919 13.25704 10.50525 2.32517 13.18964 -10.50041 -2.36255 12.57940 -10.50041 -4.61647 12.89855 -9.67272 -3.62335 12.57939 10.49959 -4.61647 13.18965 10.49959 -2.36255 12.88448 9.63719 -3.66647 12.21337 7.94797 -5.50560 11.58678 -10.50041 -6.73074 12.21218 -7.94114 -5.51293 11.58677 10.49959 -6.73074 11.51189 -6.06881 -6.85762 11.51664 6.08266 -6.85008 10.24212 -10.50041 -8.64053 10.67074 0.99921 -8.11293 10.66506 -1.00030 -8.11141 10.83492 -3.55577 -7.89054 10.88949 3.53806 -7.81976 10.24211 10.49959 -8.64054 8.58626 -10.50041 -10.28782 8.58625 10.49959 -10.28783 6.66952 -10.50041 -11.62256 6.66951 10.49959 -11.62256 4.55013 -10.50041 -12.60420 4.55012 10.49959 -12.60420 35.67098 -2.91176 23.41162 35.10701 -4.69323 24.05084 34.51861 -5.79096 22.99116 32.24020 -8.24452 23.00877 30.79715 -9.11441 22.99093 33.49187 -7.12698 22.99789 30.45738 -9.11051 19.15825 32.79480 -7.12707 17.06920 34.46150 -4.29016 16.35134 29.44318 -9.13203 15.42730 30.91869 -7.12707 11.40214 32.25470 -4.29016 10.03840 27.71212 -9.11051 10.95918 27.94042 -7.12707 6.22863 26.26256 -9.11051 8.52879 28.75688 -4.29016 4.33854 24.56230 -9.11051 6.26149 22.66412 -9.11051 4.21714 23.98184 -7.12707 1.76040 24.12780 -4.29015 -0.48793 20.67170 -9.11051 2.46631 18.69316 -9.11050 1.03600 19.20498 -7.12707 -1.81966 16.78089 -9.11050 -0.10730 18.57887 -4.29015 -4.22057 14.85429 -9.11536 -1.01545 14.19183 -8.09903 -3.02073 13.46651 -6.75450 -4.84491 11.88470 -3.19872 -7.20780 12.61154 -4.96985 -6.29130 35.27751 4.28659 23.01634 34.51856 5.79020 23.02481 33.49437 7.12394 23.03323 32.24012 8.24375 23.04163 30.79967 9.11036 23.00775 32.80304 7.12410 17.09722 30.54383 9.10968 19.72866 34.46772 4.28640 16.37301 29.90321 9.10968 16.56613 30.92986 7.12410 11.42224 28.88781 9.10968 13.50447 32.26332 4.28640 10.05390 27.51255 9.10968 10.58758 27.95177 7.12410 6.24101 25.79234 9.10968 7.85021 28.76567 4.28640 4.34804 23.75453 9.10968 5.33895 23.99086 7.12410 1.76602 21.51544 9.10968 3.16539 24.13470 4.28640 -0.48361 19.20959 7.12411 -1.81921 19.24568 9.10968 1.40820 17.04753 9.10969 0.03941 18.58228 4.28640 -4.22007 13.79232 7.10996 -4.35238 14.33083 8.00472 -3.01229 14.93884 9.10969 -1.01760 11.98112 3.17161 -7.16036 12.80422 5.00471 -6.27410 29.33309 9.40134 22.94975 30.08383 9.35425 22.99638 26.59515 7.15561 23.01965 26.87466 7.85676 23.00244 26.29238 7.85724 18.31521 27.27739 8.94702 18.00122 27.31973 8.46639 23.00948 27.90369 8.94572 22.99972 28.63104 9.40172 17.51563 28.58735 9.26455 23.00108 24.77109 7.85724 13.86825 25.63348 8.94702 13.27911 26.77773 9.40172 12.35932 22.37364 7.85724 9.82570 23.04388 8.94702 9.00187 23.85976 9.40172 7.72165 19.20110 7.85724 6.35800 19.62173 8.94702 5.35638 20.01346 9.40172 3.81929 15.35070 7.89198 3.53765 15.50805 9.08422 2.16505 15.18956 9.39706 0.20453 29.33042 -9.40730 22.97453 26.87267 -7.85526 22.99909 26.29455 -7.85542 18.33118 27.31945 -8.46778 23.01072 27.90180 -8.94608 22.98559 27.27926 -8.94623 18.02046 28.13668 -9.43483 15.71140 28.58736 -9.26600 22.99869 24.77486 -7.85542 13.87991 25.63741 -8.94623 13.29348 25.54921 -9.40238 10.13518 22.37741 -7.85541 9.83324 23.04801 -8.94623 9.01154 22.76218 -9.40238 6.43190 19.20344 -7.85541 6.36204 19.62439 -8.94623 5.36206 19.34743 -9.40238 3.29801 15.38655 -7.90337 3.56958 15.48328 -9.08043 2.17480 15.21953 -9.38465 0.20242 12.71159 -6.40639 4.50438 12.74383 6.40694 4.46699 13.11625 -6.40706 4.10916 13.17147 6.40534 4.06695 13.67181 -6.40729 3.82388 13.63432 6.40488 3.83865 14.16679 -6.40621 3.72869 14.16567 6.40517 3.73141 14.74828 -6.40559 3.77486 14.78990 6.40795 3.78526 12.58938 6.40624 4.72038 12.84993 8.84319 3.96175 13.47079 10.08159 2.14671 13.19677 8.55461 3.61157 13.69240 10.33885 0.10007 13.57160 8.34648 3.40352 13.86713 9.62944 2.02199 13.98212 8.18787 3.28635 14.07981 9.87364 0.14741 14.31560 9.33661 1.97631 14.40984 8.07622 3.25155 14.50780 6.40489 3.75358 14.52968 9.59005 0.18204 14.90134 9.13856 1.99861 14.85833 8.01625 3.30744 14.85845 9.46198 0.19548 13.48269 10.32783 -1.34628 13.95208 9.60692 -1.10757 14.66569 9.18686 -1.01369 12.93925 9.41483 -3.53728 12.36359 7.69195 -5.23325 13.11882 9.01344 -3.32705 13.65545 9.95317 -1.21632 11.60970 5.81624 -6.70498 12.71295 7.44038 -4.91488 13.41292 8.65007 -3.17383 11.93168 5.52365 -6.44411 10.94455 0.99738 -7.87140 11.28216 3.39613 -7.43880 13.14305 7.23847 -4.66389 13.77247 8.35124 -3.08141 14.29804 9.36786 -1.04865 12.31590 5.27040 -6.28185 11.73384 3.19752 -7.16874 11.35846 0.99781 -7.62773 14.18860 8.09826 -3.03375 10.90901 -0.99577 -7.89165 11.23977 -0.99918 -7.68268 13.55432 -10.50586 -0.44094 12.95099 -9.37372 -3.50425 12.34374 -7.74751 -5.26691 13.12794 -9.02062 -3.32480 11.63522 -5.80562 -6.68770 12.61567 -7.37134 -5.02173 13.92358 -9.63900 -1.11594 13.37768 -8.69748 -3.18544 11.02792 -3.52860 -7.64708 11.90387 -5.55691 -6.46360 14.30893 -9.34458 -1.04496 13.69316 -8.41773 -3.09304 11.37410 -3.36257 -7.37211 13.06867 -6.99306 -4.85521 12.23053 -5.32839 -6.30559 13.73215 -10.26075 0.11352 13.65034 -9.95749 -1.21899 14.04955 -9.92929 0.15063 14.42913 -9.63355 0.17846 14.87790 -9.45857 0.19826 12.84600 -8.85458 3.98163 13.32162 -10.49276 2.06913 13.08870 -8.63163 3.70309 12.92298 -6.40751 4.29738 13.47838 -10.08774 2.15254 13.44063 -8.41393 3.46980 13.38458 -6.40547 3.96435 13.77817 -9.70742 2.04130 13.80434 -8.24599 3.32269 14.08722 -9.47522 1.99617 14.36399 -8.07932 3.24406 14.45476 -9.27130 1.97544 14.96485 -9.12934 2.00828 14.97332 -8.00720 3.33362 7.49951 -10.60041 -0.00042 7.33562 -10.60041 -1.55976 6.85111 -10.60041 -3.05095 6.85110 -10.60041 3.05010 7.33562 -10.60041 1.55892 6.06714 -10.60041 4.40797 6.06714 -10.60041 -4.40881 5.01799 -10.60041 -5.57401 5.01799 -10.60041 5.57317 3.74951 -10.60041 6.49477 3.74952 -10.60041 -6.49561 3.74952 10.59959 -6.49561 3.74952 10.59959 6.49477 5.01800 10.59959 -5.57401 5.01800 10.59959 5.57317 6.06715 10.59959 -4.40881 6.06714 10.59959 4.40797 6.85111 10.59959 3.05010 6.85111 10.59959 -3.05095 7.33562 10.59959 -1.55976 7.49952 10.59959 -0.00042 7.33562 10.59959 1.55892 13.44627 10.50242 -0.01869 35.69546 3.05739 23.43314 -25.69792 -8.06854 26.52259 -26.35478 -8.04488 26.51994 -25.26371 -8.17598 26.64023 -24.16000 -9.02968 27.71689 -24.45500 -8.67075 27.23014 -24.83796 -8.37893 26.87214 -24.45243 8.67238 27.23327 -24.16008 9.02875 27.71671 -24.83342 8.38089 26.87540 -25.25692 8.17761 26.64293 -25.69196 8.06858 26.52351 -26.35262 8.04343 26.51944 30.89098 -8.06940 26.52353 31.55164 -8.04425 26.51945 30.45594 -8.17842 26.64295 30.03244 -8.38171 26.87541 29.65145 -8.67320 27.23329 29.35909 -9.02957 27.71672 29.35902 9.02887 27.71690 29.65402 8.66993 27.23016 30.03698 8.37811 26.87215 30.46273 8.17516 26.64024 30.89694 8.06772 26.52260 31.55380 8.04406 26.51995 30.30964 -9.28881 26.71105 29.51329 -9.40195 27.42233 29.85156 -9.38048 27.02176 29.21206 -9.39401 28.27592 29.30267 -9.39645 27.86289 28.81621 -9.33038 28.16568 28.36078 -9.18566 27.93929 27.89046 -8.94547 27.58514 27.52685 -8.66804 27.22668 27.16869 -8.30602 26.77394 26.87688 -7.86445 26.30823 26.71915 -7.53458 25.98483 26.60021 -7.17856 25.66446 26.52537 -6.80088 25.35357 -25.11475 -9.28649 26.70846 -24.73201 -9.37661 26.95330 -24.45204 -9.39816 27.23272 -24.18235 -9.39973 27.66239 -24.01589 -9.38310 28.21809 -23.61292 -9.32953 28.16398 -23.27349 -9.22654 28.00972 -22.92326 -9.07597 27.77525 -22.57237 -8.86007 27.47989 -22.32934 -8.66934 27.22835 -22.09323 -8.43956 26.94403 -21.87564 -8.17419 26.63824 -21.68406 -7.87555 26.31960 -21.52446 -7.54521 25.99483 -21.40323 -7.18620 25.67105 -21.32681 -6.80432 25.35626 30.31377 9.28566 26.70846 29.93103 9.37579 26.95331 29.65106 9.39735 27.23273 29.38137 9.39891 27.66240 29.21495 9.38221 28.21792 28.80724 9.32764 28.16212 28.46433 9.22273 28.00512 28.10902 9.06841 27.76509 27.75194 8.84543 27.46115 27.50480 8.64778 27.20188 27.26728 8.41127 26.91131 27.05169 8.14141 26.60291 26.86490 7.84184 26.28602 26.64308 7.35032 25.80266 26.52453 6.79367 25.34855 -25.11072 9.28798 26.71104 -24.31433 9.40116 27.42237 -24.65256 9.37968 27.02179 -24.01304 9.39320 28.27591 -24.10299 9.39558 27.86508 -23.61179 9.32847 28.16351 -23.15257 9.18113 27.93344 -22.80202 9.00596 27.68408 -22.55539 8.84721 27.46354 -22.30408 8.64627 27.19994 -22.06303 8.40544 26.90438 -21.84580 8.13166 26.59218 -21.57421 7.67631 26.10763 -21.39569 7.15675 25.64643 -21.32504 6.79000 25.34565 -25.60049 9.11070 26.53998 -26.06235 8.87196 26.50053 -26.53616 8.59014 26.57264 -26.98871 8.28209 26.76077 -27.93840 7.48716 25.94127 -28.70745 6.64783 25.23596 -29.35557 5.73244 24.61157 -29.90789 4.69264 24.05094 -30.33595 3.53512 23.58323 -30.60797 2.28678 23.23998 30.79951 9.11069 26.53999 31.73488 8.59032 26.57257 31.26123 8.87203 26.50054 32.18773 8.28208 26.76079 33.13742 7.48715 25.94128 33.90647 6.64782 25.23597 34.55459 5.73243 24.61159 35.10691 4.69263 24.05095 30.79951 -9.11152 26.54000 31.26137 -8.87278 26.50054 31.73518 -8.59096 26.57266 32.18773 -8.28291 26.76079 33.13676 -7.48862 25.94187 33.90627 -6.64890 25.23616 34.55468 -5.73310 24.61150 -25.60049 -9.11151 26.53998 -26.53586 -8.59113 26.57256 -26.06221 -8.87285 26.50052 -26.98871 -8.28290 26.76077 -27.93774 -7.48861 25.94185 -28.70725 -6.64889 25.23615 -29.35566 -5.73309 24.61148 -29.90799 -4.69322 24.05083 -30.33597 -3.53584 23.58320 -30.70049 10.98821 34.50007 -30.70049 10.88394 32.40859 -30.70049 10.69424 36.57342 -30.70049 10.38520 30.37476 -30.70050 10.01268 38.55349 -30.70049 9.51008 28.47230 -30.70050 8.96824 40.36852 -30.70049 8.29029 26.77015 -30.70050 7.59876 41.95273 -30.70049 6.77003 25.33001 -30.70050 5.95388 43.24871 -30.70049 5.00440 24.20407 -30.70050 4.09320 44.20949 -30.70049 3.05740 23.43312 -30.70050 2.08417 44.80024 -30.70050 -0.00040 44.99957 -30.70050 -2.08498 44.80024 -30.70049 -3.05820 23.43312 -30.70050 -4.09401 44.20949 -30.70049 -5.00521 24.20407 -30.70050 -5.95468 43.24871 -30.70049 -6.77083 25.33001 -30.70050 -7.59957 41.95274 -30.70049 -8.29109 26.77015 -30.70050 -8.96904 40.36852 -30.70049 -9.51088 28.47230 -30.70050 -10.01348 38.55350 -30.70049 -10.38600 30.37476 -30.70049 -10.88474 32.40859 -30.70049 -10.69504 36.57343 -30.70049 -10.98901 34.50008 -21.30049 6.40700 25.05836 -21.30049 -6.40781 25.05836 -21.30049 7.95500 26.40277 -21.30049 -7.95582 26.40277 -21.30049 9.22661 28.01107 -21.30049 -9.22742 28.01107 -21.30049 10.17766 29.82740 -21.30049 -10.17846 29.82740 -21.30049 10.77512 31.78865 -21.30049 -10.77592 31.78866 -21.30049 10.99824 33.82669 -21.30049 -10.99904 33.82669 -21.30049 10.83929 35.87072 -21.30049 -10.84009 35.87072 -21.30049 10.30379 37.84973 -21.30049 -10.30459 37.84973 -21.30049 9.41035 39.69498 -21.30049 -9.41116 39.69498 -21.30049 8.19002 41.34239 -21.30049 -8.19083 41.34239 -21.30049 6.68519 42.73472 -21.30049 -6.68600 42.73473 -21.30049 4.94813 43.82362 -21.30049 -4.94894 43.82363 -21.30050 3.03919 44.57127 -21.30050 1.02466 44.95171 -21.30050 -3.04000 44.57127 -21.30050 -1.02547 44.95171 26.49950 1.02465 44.95172 26.49950 -1.02548 44.95172 26.49950 3.03918 44.57128 26.49950 -3.04001 44.57129 26.49951 4.94812 43.82364 26.49951 -4.94895 43.82364 26.49951 6.68518 42.73473 26.49951 -6.68601 42.73474 26.49951 8.19001 41.34240 26.49951 -8.19084 41.34240 26.49951 9.41034 39.69499 26.49951 -9.41117 39.69500 26.49951 10.30378 37.84974 26.49951 -10.30460 37.84974 26.49951 10.83928 35.87073 26.49951 -10.84010 35.87073 26.49951 10.99823 33.82670 26.49951 -10.99905 33.82671 26.49951 10.77511 31.78867 26.49951 -10.77593 31.78867 26.49951 10.17765 29.82741 26.49951 -10.17847 29.82741 26.49951 9.22661 28.01108 26.49951 -9.22743 28.01108 26.49951 7.95500 26.40278 26.49951 -7.95582 26.40278 26.49951 6.40699 25.05838 26.49951 -6.40781 25.05838 35.89951 10.98820 34.50008 35.89951 10.88393 32.40860 35.89951 10.69423 36.57343 35.89951 10.38519 30.37477 35.89951 10.01267 38.55351 35.89951 9.51007 28.47231 35.89951 8.96823 40.36853 35.89951 8.29028 26.77017 35.89951 7.59875 41.95275 35.89951 6.77002 25.33003 35.89951 5.95387 43.24872 35.89951 5.00439 24.20408 35.89951 4.09319 44.20951 35.89951 3.05739 23.43314 35.89951 2.08416 44.80026 35.89951 -0.00041 44.99959 35.89951 -2.08499 44.80026 35.89951 -3.05821 23.43314 35.89951 -4.09402 44.20951 35.89951 -5.00522 24.20408 35.89951 -5.95470 43.24872 35.89951 -6.77085 25.33003 35.89951 -7.59958 41.95275 35.89951 -8.29110 26.77017 35.89951 -8.96905 40.36853 35.89951 -9.51089 28.47231 35.89951 -10.01349 38.55351 35.89951 -10.38601 30.37477 35.89951 -10.88475 32.40860 35.89951 -10.98902 34.50009 35.89951 -10.69505 36.57344 -30.60796 -2.28766 23.24000 + + + + + + + + + + 0.00351 -0.99986 0.01651 0.00000 -0.99986 0.01683 -0.88619 0.44850 -0.11622 -0.78877 0.60651 -0.09996 -0.83885 0.52713 -0.13587 -0.65725 0.73765 -0.15457 -0.50717 0.86073 -0.04374 -0.00723 -0.99986 -0.01540 -0.00979 -0.99986 -0.01391 -0.00995 -0.99986 -0.01370 -0.01209 -0.99985 -0.01203 -0.01357 -0.99986 -0.00945 -0.01317 -0.99984 -0.01186 -0.01514 -0.99986 -0.00702 -0.01511 -0.99985 -0.00872 -0.01626 -0.99986 -0.00431 -0.01638 -0.99985 -0.00532 -0.01682 -0.99986 -0.00177 -0.01696 -0.99986 -0.00144 -0.01694 -0.99985 0.00178 -0.01949 -0.99974 0.01192 -0.02103 -0.99976 0.00683 -0.02161 -0.99974 -0.00720 -0.01202 -0.99984 0.01306 -0.01566 -0.99984 0.00904 -0.01613 -0.99984 0.00811 -0.01251 -0.99986 0.01126 -0.01174 -0.99985 0.01240 -0.00939 -0.99986 0.01401 -0.01006 -0.99985 0.01384 -0.00698 -0.99986 0.01547 -0.00939 0.99986 0.01401 -0.01174 0.99985 0.01240 -0.01251 0.99986 0.01126 -0.01364 0.99985 0.01028 -0.01460 0.99986 0.00843 -0.01435 0.99986 0.00870 -0.01944 0.99980 -0.00420 -0.01935 0.99979 0.00629 -0.01869 0.99979 0.00875 -0.01694 0.99985 0.00178 -0.01695 0.99986 -0.00144 -0.01682 0.99986 -0.00177 -0.01650 0.99985 -0.00438 -0.01602 0.99986 -0.00521 -0.01551 0.99985 -0.00718 -0.01457 0.99986 -0.00842 -0.01402 0.99985 -0.00977 -0.01253 0.99986 -0.01128 -0.01209 0.99985 -0.01203 -0.00975 0.99986 -0.01385 -0.95927 0.00000 -0.28251 -0.95855 0.00402 -0.28490 -0.95788 0.00000 -0.28717 -0.90737 0.00000 -0.42034 -0.90737 0.00000 -0.42034 -0.96656 -0.00572 -0.25638 -0.46377 -0.36064 -0.80923 -0.45318 -0.53536 -0.71275 -0.99676 0.00262 -0.08039 -0.99223 -0.09399 -0.08153 -0.94714 -0.27414 -0.16666 -0.99664 -0.00000 -0.08188 -0.97827 0.00001 -0.20735 -0.18189 -0.98107 -0.06642 -0.16835 -0.98346 -0.06677 -0.97827 -0.00001 -0.20736 -0.94410 0.00001 -0.32965 -0.94410 -0.00001 -0.32967 0.99529 0.00011 0.09690 0.99524 0.00000 0.09744 0.97160 -0.00000 0.23664 0.97160 0.00000 0.23664 0.92871 -0.00000 0.37082 0.20791 -0.00842 -0.97811 0.09802 0.00749 -0.99516 0.00000 -0.00856 -0.99996 -0.09801 0.00749 -0.99516 -0.20791 -0.00842 -0.97811 -0.29027 0.00722 -0.95692 -0.40672 -0.00803 -0.91352 -0.47139 0.00669 -0.88190 -0.58777 -0.00735 -0.80900 -0.63438 0.00589 -0.77300 -0.74313 -0.00642 -0.66912 -0.77300 0.00481 -0.63439 -0.86601 -0.00521 -0.49999 -0.88192 0.00348 -0.47139 -0.95105 -0.00374 -0.30901 -0.95694 0.00187 -0.29029 -0.99452 -0.00200 -0.10453 -0.99518 0.00000 -0.09802 -0.33023 -0.01785 0.94373 -0.23926 0.02143 0.97072 -0.11194 -0.01875 0.99354 0.00000 0.02187 0.99976 0.11194 -0.01875 0.99354 0.23926 0.02143 0.97072 0.33023 -0.01785 0.94373 0.46462 0.02008 0.88528 0.53196 -0.01607 0.84662 0.66302 0.01785 0.74839 0.70705 -0.01339 0.70704 0.82289 0.01472 0.56800 0.84668 -0.00982 0.53201 0.93496 0.01071 0.35459 0.94387 -0.00535 0.33027 0.99271 -0.00000 0.12054 0.99369 0.00624 0.11196 0.99371 0.00000 -0.11196 0.99269 0.00580 -0.12054 0.94387 -0.00535 -0.33028 0.93496 0.01071 -0.35459 0.84668 -0.00981 -0.53201 0.82290 0.01472 -0.56800 0.70704 -0.01339 -0.70704 0.66302 0.01785 -0.74839 0.53196 -0.01607 -0.84661 0.46463 0.02008 -0.88528 0.33023 -0.01785 -0.94373 0.23926 0.02143 -0.97072 0.11194 -0.01875 -0.99354 0.00000 0.02187 -0.99976 -0.11194 -0.01875 -0.99354 -0.23926 0.02143 -0.97072 -0.33023 -0.01785 -0.94373 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.99452 -0.00000 0.10453 -0.99518 -0.00214 0.09802 -0.95694 0.00187 0.29028 -0.95105 -0.00374 0.30902 -0.88192 0.00348 0.47139 -0.86601 -0.00521 0.49999 -0.77300 0.00481 0.63439 -0.74313 -0.00642 0.66912 -0.63438 0.00588 0.77300 -0.58777 -0.00735 0.80900 -0.47139 0.00669 0.88190 -0.40672 -0.00803 0.91352 -0.29028 0.00722 0.95692 -0.20790 -0.00843 0.97811 -0.09801 0.00749 0.99516 0.00000 -0.00856 0.99996 0.09801 0.00749 0.99516 0.20790 -0.00843 0.97811 0.00350 0.99986 -0.01649 0.00351 0.99986 0.01650 0.00145 0.99985 -0.01703 0.00133 0.99985 0.01702 0.00000 0.99986 -0.01683 -0.00000 0.99986 0.01683 -0.00153 0.99985 -0.01702 -0.00350 0.99986 -0.01648 -0.00152 0.99985 0.01701 -0.00432 0.99985 0.01649 -0.00350 0.99986 0.01649 -0.00446 0.99985 -0.01647 -0.00688 0.99986 -0.01545 -0.00689 0.99986 0.01548 -0.00698 0.99986 0.01547 -0.00723 0.99986 -0.01540 -0.01001 0.99985 -0.01378 -0.01006 0.99985 0.01384 0.20790 0.00843 0.97811 0.09801 -0.00749 0.99516 -0.00000 0.00856 0.99996 -0.09801 -0.00749 0.99516 -0.20791 0.00843 0.97811 -0.29028 -0.00722 0.95692 -0.40672 0.00803 0.91352 -0.47139 -0.00669 0.88190 -0.58777 0.00735 0.80900 -0.63438 -0.00588 0.77300 -0.74313 0.00642 0.66912 -0.77300 -0.00481 0.63439 -0.86601 0.00521 0.49999 -0.88192 -0.00348 0.47139 -0.95105 0.00374 0.30902 -0.95694 -0.00187 0.29028 -0.99452 0.00200 0.10453 -0.99518 -0.00000 0.09802 -0.99452 0.00000 -0.10453 -0.99518 0.00214 -0.09802 -0.95694 -0.00187 -0.29029 -0.95105 0.00374 -0.30902 -0.88192 -0.00348 -0.47139 -0.86601 0.00521 -0.49999 -0.77300 -0.00481 -0.63439 -0.74313 0.00642 -0.66912 -0.63438 -0.00589 -0.77300 -0.58777 0.00735 -0.80900 -0.47139 -0.00669 -0.88190 -0.40672 0.00803 -0.91352 -0.29027 -0.00722 -0.95692 -0.20791 0.00842 -0.97811 -0.09802 -0.00749 -0.99516 0.00000 0.00856 -0.99996 0.09802 -0.00749 -0.99516 0.20791 0.00842 -0.97811 -0.00428 -0.99987 -0.01582 -0.00432 -0.99985 0.01649 -0.00689 -0.99986 0.01548 -0.00733 -0.99984 -0.01645 -0.00350 -0.99986 0.01649 -0.00149 -0.99986 -0.01650 -0.00368 -0.99984 -0.01729 -0.00152 -0.99985 0.01701 0.00000 -0.99986 -0.01683 0.00133 -0.99985 0.01702 0.00145 -0.99985 -0.01703 0.00350 -0.99986 -0.01649 -0.29843 0.80194 -0.51753 -0.45546 0.76061 -0.46263 -0.48572 0.74811 -0.45212 -0.52648 0.72710 -0.44062 -0.70516 0.61922 -0.34541 -0.68729 0.63389 -0.35471 -0.79346 0.54430 -0.27233 -0.85010 0.47351 -0.23050 -0.92476 0.35495 -0.13725 -0.88546 0.42818 -0.18060 -0.97510 0.21969 -0.03025 -0.99355 0.10933 0.02998 -0.99487 0.00529 0.10098 -0.44914 0.56393 -0.69301 -0.48712 0.33907 -0.80483 -0.46872 0.11111 -0.87633 -0.48781 0.55012 -0.67779 -0.56989 0.12661 -0.81191 -0.50827 0.32733 -0.79656 -0.52244 0.54094 -0.65912 -0.71199 0.41889 -0.56357 -0.76447 0.38273 -0.51875 -0.75314 0.23466 -0.61459 -0.75445 0.07598 -0.65194 -0.76357 0.23187 -0.60266 -0.80030 0.34611 -0.48961 -0.77744 0.07742 -0.62418 -0.89245 0.25985 -0.36881 -0.88324 0.13720 -0.44841 -0.89344 0.04446 -0.44698 -0.89802 0.12735 -0.42112 -0.93206 0.19411 -0.30591 -0.92669 0.04989 -0.37250 -0.96319 0.02410 -0.26775 -0.97120 0.12167 -0.20487 -0.98112 0.08870 -0.17186 -0.57327 0.00000 -0.81936 -0.58559 0.00572 -0.81059 -0.78071 -0.00192 -0.62489 -0.80115 0.00518 -0.59844 -0.92784 -0.00355 -0.37297 -0.93332 0.00059 -0.35905 -0.54334 -0.12355 -0.83037 -0.55062 -0.32950 -0.76697 -0.56899 -0.31769 -0.75850 -0.58230 -0.47952 -0.65650 -0.47157 -0.55221 -0.68752 -0.57960 -0.12850 -0.80470 -0.65890 -0.45141 -0.60174 -0.74087 -0.07739 -0.66717 -0.75046 -0.23110 -0.61920 -0.73276 -0.24796 -0.63370 -0.74409 -0.40715 -0.52968 -0.79988 -0.07795 -0.59507 -0.83756 -0.30814 -0.45116 -0.93299 -0.02422 -0.35908 -0.92289 -0.03443 -0.38352 -0.92643 -0.09817 -0.36343 -0.91099 -0.12348 -0.39350 -0.91770 -0.21960 -0.33106 -0.92934 -0.19612 -0.31285 -0.99452 -0.01997 -0.10259 -0.47080 -0.75241 -0.46069 -0.45668 -0.75918 -0.46378 -0.65213 -0.65623 -0.37958 -0.61916 -0.68060 -0.39169 -0.82908 -0.50451 -0.24104 -0.85407 -0.47034 -0.22212 -0.92231 -0.36337 -0.13159 -0.99192 -0.12653 0.00876 -0.98384 -0.17818 -0.01749 -0.99580 -0.01898 0.08960 0.25602 -0.67271 0.69420 0.10951 -0.95426 0.27821 -0.24299 -0.96070 -0.13420 0.02366 -0.93898 0.34315 0.41629 -0.24307 0.87614 0.25610 -0.67271 0.69417 -0.36230 -0.93025 -0.05802 0.36996 -0.25534 0.89327 0.10702 -0.62868 0.77027 -0.13311 -0.91757 0.37463 -0.52306 -0.85223 -0.01049 0.03553 -0.62578 0.77919 0.17265 -0.21866 0.96041 -0.49931 -0.86639 -0.00769 -0.29615 -0.83056 0.47167 0.11936 -0.22311 0.96746 -0.12565 -0.56539 0.81519 -0.00082 -0.19219 0.98136 -0.17977 -0.52640 0.83101 -0.39503 -0.78686 0.47414 -0.77611 -0.62215 0.10282 -0.67472 -0.72940 0.11282 -0.51628 -0.68662 0.51187 -0.15957 -0.18279 0.97011 -0.24409 -0.14826 0.95835 -0.34379 -0.44941 0.82452 -0.55399 -0.66213 0.50466 -0.36494 -0.43114 0.82519 -0.42580 -0.11643 0.89729 -0.49952 -0.34354 0.79527 -0.52836 -0.31199 0.78962 -0.69334 -0.51702 0.50197 -0.92543 -0.28426 0.25055 -0.79022 -0.55988 0.24917 -0.43711 -0.11689 0.89178 -0.84444 -0.13410 0.51859 -0.80441 -0.23405 0.54603 -0.69684 -0.15924 0.69933 -0.66097 -0.04772 0.74889 -0.66379 -0.04752 0.74641 -0.73766 -0.09046 0.66908 0.38198 -0.00000 0.92417 0.39651 0.00076 0.91803 0.12271 -0.00007 0.99244 0.13374 0.00042 0.99102 -0.16191 -0.00126 0.98680 -0.14660 -0.00049 0.98920 -0.43971 0.00043 0.89814 -0.42046 0.00134 0.90731 -0.66472 -0.00107 0.74709 -0.64854 -0.00010 0.76118 -0.20688 0.96904 -0.13476 -0.21729 0.96682 -0.13436 0.02220 0.93724 0.34797 0.18340 0.66030 0.72826 0.32370 0.26370 0.90867 -0.04563 0.93478 0.35228 0.15402 0.64342 0.74986 0.38427 0.24588 0.88988 -0.42875 0.90238 -0.04338 0.13021 0.21703 0.96744 -0.23944 0.86631 0.43837 -0.43986 0.89707 -0.04216 0.12412 0.21418 0.96888 -0.00829 0.60805 0.79386 -0.26215 0.85896 0.43984 -0.03777 0.58651 0.80906 -0.58919 0.80734 0.03251 -0.40605 0.76730 0.49635 -0.60111 0.79844 0.03407 -0.27437 0.47832 0.83423 -0.47610 0.72411 0.49900 -0.76444 0.63397 0.11712 -0.23688 0.18363 0.95403 -0.32759 0.46151 0.82444 -0.76955 0.62765 0.11774 -0.62231 0.56695 0.53971 -0.14442 0.16129 0.97628 -0.41513 0.39049 0.82170 -0.58425 0.59872 0.54789 -0.80418 0.57658 0.14438 -0.41713 0.12663 0.89998 -0.57940 0.81267 0.06214 -0.90601 0.33872 0.25379 -0.58005 0.05536 0.81270 -0.64048 0.24568 0.72761 -0.64772 0.05054 0.76020 -0.53358 0.65124 0.53960 -0.73246 0.10072 0.67332 -0.81922 0.28667 0.49668 -0.69807 0.02783 0.71549 -0.72391 0.10738 0.68148 -0.31865 -0.94762 -0.02173 -0.06834 -0.99280 -0.09833 -0.18893 -0.98183 -0.01773 0.18189 -0.98318 0.01629 0.42299 -0.90569 -0.02856 0.63070 -0.77024 0.09462 0.80590 -0.58653 0.08063 0.27517 -0.96051 0.04134 0.98733 -0.12632 0.09608 0.92845 -0.37112 0.01598 0.97574 -0.16150 0.14783 0.72060 -0.68471 0.10910 -0.19528 -0.98025 -0.03112 0.30206 -0.95068 0.07043 -0.17277 -0.98376 -0.04857 -0.18246 -0.98214 -0.04587 0.93546 -0.27020 0.22784 0.26518 -0.95786 0.11037 0.27646 -0.95469 0.11015 0.67463 -0.68266 0.28079 0.90310 -0.20439 0.37768 0.91614 -0.16395 0.36580 0.67176 -0.68543 0.28093 0.83344 -0.27693 0.47821 0.27276 -0.94729 0.16805 -0.15712 -0.98294 -0.09563 -0.16577 -0.98153 -0.09545 0.22350 -0.96046 0.16605 0.58707 -0.68199 0.43616 0.58285 -0.68612 0.43533 0.78883 -0.17497 0.58918 0.77010 -0.21665 0.60001 -0.16041 -0.97986 -0.11895 -0.14122 -0.98157 -0.12873 -0.13494 -0.98273 -0.12662 0.23734 -0.94703 0.21635 0.66915 -0.26852 0.69292 0.46707 -0.68165 0.56321 0.45988 -0.68920 0.55992 0.17772 -0.95945 0.21879 0.62189 -0.15765 0.76707 -0.12771 -0.98023 -0.15113 -0.09872 -0.98464 -0.14399 0.18438 -0.95175 0.24532 0.56828 -0.24866 0.78436 -0.09765 -0.98290 -0.15615 -0.33794 0.94076 -0.02775 -0.07269 0.99529 -0.06413 0.30268 0.95198 0.04598 0.18138 0.98333 -0.01276 0.42303 0.90386 0.06391 -0.17534 0.98415 -0.02653 0.62732 0.77298 0.09476 0.80600 0.58643 0.08040 0.98750 0.12448 0.09665 0.92894 0.36986 0.01630 0.71988 0.68544 0.10932 0.97551 0.16260 0.14814 0.93534 0.27064 0.22781 -0.19594 0.97941 -0.04864 0.28073 0.95265 0.11685 0.67397 0.68342 0.28054 0.90780 0.17821 0.37965 0.90756 0.21216 0.36238 0.67114 0.68614 0.28068 0.28346 0.95155 0.11918 -0.17073 0.98270 -0.07179 -0.16712 0.98356 -0.06843 0.83334 0.27735 0.47815 -0.17478 0.97917 -0.10335 0.58650 0.68275 0.43575 0.24297 0.95309 0.18052 0.78346 0.20920 0.58517 0.77899 0.15747 0.60694 0.58231 0.68684 0.43493 -0.14277 0.98390 -0.10752 -0.14957 0.98135 -0.12078 0.24668 0.95112 0.18578 0.66906 0.26896 0.69283 -0.13505 0.98001 -0.14608 0.45976 0.69678 0.55056 0.46368 0.68205 0.56552 0.19541 0.95351 0.22943 0.62196 0.15862 0.76681 -0.10524 0.98512 -0.13587 0.20648 0.94390 0.25772 0.56750 0.25380 0.78328 -0.10671 0.98194 -0.15621 -0.60667 0.79123 -0.07686 -0.56817 0.81074 -0.14105 -0.79584 0.53524 -0.28311 -0.57820 0.78954 -0.20569 -0.80107 0.51949 -0.29735 -0.91713 0.20731 -0.34044 -0.91737 0.23627 -0.32032 -0.54765 0.80610 -0.22425 -0.88170 0.16993 -0.44015 -0.51831 0.79181 -0.32310 -0.51464 0.80158 -0.30432 -0.71413 0.54022 -0.44517 -0.71686 0.51486 -0.47014 -0.81520 0.22276 -0.53463 -0.81227 0.21056 -0.54395 -0.45559 0.81060 -0.36791 -0.74244 0.17211 -0.64743 -0.60027 0.54466 -0.58568 -0.43952 0.78926 -0.42883 -0.67393 0.23158 -0.70157 -0.65209 0.19089 -0.73372 -0.59561 0.51069 -0.62004 -0.40107 0.80680 -0.43384 -0.33502 0.79280 -0.50914 -0.33830 0.80043 -0.49484 -0.45934 0.54863 -0.69858 -0.55491 0.18086 -0.81201 -0.47588 0.34278 -0.80996 -0.46281 0.55781 -0.68895 -0.51130 0.22340 -0.82986 -0.45217 0.11213 -0.88486 -0.88620 -0.44851 -0.11617 -0.78284 -0.60273 -0.15456 -0.84468 -0.52445 -0.10705 -0.96417 -0.23323 -0.12640 -0.66324 -0.74368 -0.08398 -0.51400 -0.84905 -0.12211 -0.64066 -0.76661 -0.04310 -0.59317 -0.79951 -0.09452 -0.57276 -0.80697 -0.14400 -0.57500 -0.79218 -0.20454 -0.54901 -0.80696 -0.21773 -0.79566 -0.53556 -0.28303 -0.80089 -0.51981 -0.29728 -0.91311 -0.22662 -0.33893 -0.88166 -0.17013 -0.44014 -0.71397 -0.54053 -0.44505 -0.50961 -0.79962 -0.31766 -0.54216 -0.78013 -0.31218 -0.71671 -0.51519 -0.47002 -0.81695 -0.21343 -0.53576 -0.80918 -0.22706 -0.54191 -0.47347 -0.80782 -0.35108 -0.74240 -0.17231 -0.64742 -0.43291 -0.79637 -0.42235 -0.45040 -0.78645 -0.42265 -0.60015 -0.54497 -0.58551 -0.59549 -0.51101 -0.61988 -0.67968 -0.19350 -0.70752 -0.64206 -0.25654 -0.72245 -0.37976 -0.80859 -0.44940 -0.33611 -0.79429 -0.50610 -0.32117 -0.80258 -0.50271 -0.45843 -0.54912 -0.69879 -0.55489 -0.18107 -0.81198 -0.50368 -0.23068 -0.83252 -0.45098 -0.13321 -0.88254 -0.99641 0.00112 -0.08466 -0.99729 0.01576 -0.07190 -0.99637 -0.00893 -0.08466 -0.99602 -0.01019 -0.08855 -0.99255 -0.00087 -0.12183 -0.98077 -0.00810 -0.19502 -0.96656 -0.00561 -0.25638 -0.98287 0.01723 -0.18351 -0.97605 -0.00303 -0.21754 -0.90737 0.00000 -0.42034 -0.82060 0.00000 -0.57150 -0.82060 0.00000 -0.57150 -0.70890 0.00000 -0.70531 -0.70890 0.00000 -0.70531 -0.57566 0.00000 -0.81769 -0.57566 0.00000 -0.81769 -0.42492 0.00000 -0.90523 -0.42492 0.00000 -0.90523 -0.26128 0.00000 -0.96526 -0.26128 0.00000 -0.96526 -0.08971 0.00000 -0.99597 -0.08971 0.00000 -0.99597 0.08460 0.00000 -0.99642 0.08460 0.00000 -0.99642 0.07779 -0.00000 0.99697 0.07779 -0.00000 0.99697 -0.08916 -0.00000 0.99602 -0.08916 -0.00000 0.99602 -0.25363 0.00000 0.96730 -0.25363 -0.00000 0.96730 -0.41102 -0.00000 0.91162 -0.41102 -0.00000 0.91162 -0.55695 -0.00000 0.83054 -0.55696 -0.00000 0.83054 -0.68736 -0.00000 0.72632 -0.68736 -0.00000 0.72632 -0.79835 0.02528 0.60167 -0.77337 0.00354 0.63395 -0.75022 -0.00000 0.66119 -0.79945 -0.02809 0.60007 -0.77570 -0.00524 0.63108 -0.74247 0.00028 0.66988 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.92871 -0.00000 0.37082 0.86737 -0.00000 0.49767 0.86737 -0.00000 0.49767 0.78883 -0.00000 0.61461 0.78883 -0.00000 0.61461 0.69466 -0.00000 0.71934 0.69466 -0.00000 0.71934 0.58671 -0.00000 0.80980 0.58671 -0.00000 0.80980 -0.89471 0.00001 -0.44664 -0.89471 -0.00001 -0.44665 -0.83090 0.00002 -0.55642 -0.83089 -0.00002 -0.55644 -0.75368 0.00002 -0.65724 -0.75367 -0.00002 -0.65725 -0.66430 0.00001 -0.74746 -0.66430 -0.00001 -0.74747 -0.56422 0.00001 -0.82563 -0.56421 -0.00001 -0.82563 -0.45503 0.00000 -0.89047 -0.45503 0.00000 -0.89047 -0.95313 0.27559 -0.12490 -0.97949 0.08775 -0.18137 -0.96015 0.26855 -0.07742 -0.96329 0.17434 -0.20417 -0.96325 -0.17453 -0.20417 -0.92437 -0.20337 -0.32278 0.94185 -0.00006 -0.33603 0.94183 0.00006 -0.33608 0.88974 -0.00006 -0.45646 0.88972 0.00006 -0.45651 0.82232 -0.00005 -0.56902 0.82229 0.00006 -0.56907 0.74075 -0.00006 -0.67178 0.74070 0.00008 -0.67184 0.64642 -0.00008 -0.76298 0.64636 0.00007 -0.76303 0.54094 -0.00007 -0.84106 0.54089 0.00004 -0.84109 0.42613 -0.00004 -0.90466 0.42611 0.00000 -0.90467 0.30163 -0.00001 -0.95343 0.30399 -0.00527 -0.95266 -0.93888 0.00001 0.34425 -0.93884 -0.00001 0.34435 -0.88525 0.00002 0.46512 -0.88518 -0.00002 0.46526 -0.81604 0.00002 0.57799 -0.81592 -0.00003 0.57816 -0.73278 0.00003 0.68046 -0.73263 -0.00002 0.68063 -0.64110 0.00002 0.76745 -0.64098 -0.00001 0.76756 -0.54819 0.00001 0.83635 -0.54884 -0.00014 0.83592 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.24257 -0.00000 0.97013 0.24257 -0.00000 0.97013 0.40057 -0.00000 0.91626 0.40058 0.00000 0.91626 0.54742 0.00000 0.83686 0.54742 0.00000 0.83686 0.67900 0.00000 0.73414 0.67900 -0.00000 0.73414 0.79165 -0.00000 0.61097 0.79165 -0.00000 0.61097 0.88225 -0.00000 0.47078 0.88225 -0.00000 0.47078 0.91370 -0.00000 0.40640 0.93759 -0.00672 0.34768 0.92759 0.00091 0.37360 0.94072 0.00403 0.33917 0.95201 0.03380 0.30420 0.96359 -0.05853 -0.26089 0.96386 0.05350 -0.26097 0.94569 -0.02266 -0.32427 0.92463 -0.04605 -0.37807 0.89371 0.15883 -0.41958 0.90505 0.01824 -0.42491 0.88798 0.00184 -0.45989 0.88884 -0.00173 -0.45821 0.80446 -0.00273 -0.59399 0.78816 -0.00081 -0.61547 0.82555 -0.00953 -0.56425 0.81766 -0.00267 -0.57570 0.83796 0.00144 -0.54573 0.77615 0.00000 -0.63054 0.79321 0.00197 -0.60894 0.81763 0.00816 -0.57568 0.70527 -0.00000 -0.70894 0.70527 -0.00000 -0.70894 0.57146 -0.00000 -0.82063 0.57145 0.00000 -0.82064 0.42028 0.00000 -0.90740 0.42028 0.00000 -0.90739 0.25633 0.00000 -0.96659 0.25633 0.00000 -0.96659 0.92086 -0.35182 -0.16806 0.98805 -0.13279 -0.07831 0.96310 -0.25221 -0.09395 0.55997 -0.81528 -0.14752 0.96392 -0.16753 -0.20687 0.57062 -0.79919 -0.18891 0.80059 -0.53741 -0.26504 0.80832 -0.51650 -0.28256 0.92052 -0.21165 -0.32842 0.92062 -0.22114 -0.32182 0.53512 -0.81793 -0.21126 0.87674 -0.17035 -0.44979 0.72731 -0.54379 -0.41870 0.53027 -0.78663 -0.31627 0.52543 -0.79526 -0.30248 0.82817 -0.23633 -0.50822 0.73286 -0.51055 -0.44973 0.80912 -0.17844 -0.55989 0.47111 -0.80823 -0.35329 0.45570 -0.78314 -0.42312 0.45228 -0.79679 -0.40070 0.62550 -0.54923 -0.55416 0.71779 -0.24703 -0.65096 0.70751 -0.19739 -0.67858 0.62275 -0.50540 -0.59728 0.38937 -0.80750 -0.44309 0.63743 -0.16613 -0.75238 0.36311 -0.78476 -0.50229 0.36445 -0.79417 -0.48628 0.49937 -0.55376 -0.66631 0.30281 -0.80734 -0.50648 0.53003 -0.19982 -0.82410 0.54348 -0.22777 -0.80793 0.48302 -0.50109 -0.71805 0.41954 -0.17523 -0.89066 0.26108 -0.79358 -0.54961 0.27943 -0.81607 -0.50592 0.29119 -0.71113 -0.63993 0.35931 -0.55539 -0.74996 0.36493 -0.23060 -0.90203 0.33497 -0.49119 -0.80407 0.34295 -0.31685 -0.88430 0.30001 -0.09841 -0.94885 0.62652 0.77786 -0.04904 0.51423 0.85038 -0.11147 0.66372 0.74398 -0.07728 0.84714 0.52213 -0.09865 0.78461 0.60341 -0.14241 0.88724 0.44844 -0.10816 0.96334 0.24121 -0.11743 0.57557 0.80940 -0.11659 0.96304 0.16869 -0.21000 0.80089 0.53729 -0.26436 0.57696 0.79404 -0.19135 0.57814 0.79331 -0.19083 0.91781 0.22441 -0.32751 0.92253 0.21302 -0.32182 0.80874 0.51608 -0.28213 0.53139 0.80923 -0.25054 0.87672 0.17034 -0.44984 0.72768 0.54363 -0.41826 0.50348 0.80399 -0.31640 0.53307 0.78864 -0.30640 0.82842 0.23633 -0.50781 0.73327 0.51016 -0.44949 0.80915 0.17803 -0.55998 0.46106 0.80464 -0.37414 0.46060 0.78844 -0.40769 0.62585 0.54904 -0.55396 0.40986 0.80854 -0.42222 0.62310 0.50504 -0.59722 0.72654 0.19459 -0.65899 0.70254 0.23030 -0.67335 0.63740 0.16593 -0.75245 0.37795 0.78665 -0.48819 0.36371 0.79527 -0.48504 0.49963 0.55355 -0.66630 0.31162 0.80775 -0.50043 0.48326 0.50075 -0.71813 0.52523 0.23894 -0.81673 0.54666 0.20310 -0.81235 0.41953 0.17511 -0.89069 0.35011 0.55871 -0.75184 0.36262 0.23283 -0.90238 0.30210 0.11146 -0.94674 0.06650 0.99566 -0.06516 0.32275 0.94614 -0.02538 -0.92863 0.37061 0.01700 -0.98830 0.12644 0.08529 -0.97655 0.17783 0.12133 -0.72577 0.68200 0.09023 -0.80640 0.58798 0.06324 -0.63167 0.77117 0.07935 -0.30573 0.95134 0.03855 -0.42260 0.90611 0.01929 -0.17883 0.98361 0.02317 0.17655 0.98403 -0.02274 0.19541 0.97992 -0.03958 -0.93709 0.27982 0.20872 -0.68650 0.68817 0.23485 -0.91286 0.23363 0.33482 -0.92958 0.18642 0.31801 -0.28472 0.95347 0.09912 -0.69326 0.67908 0.24134 -0.29299 0.95030 0.10531 0.18065 0.98172 -0.05991 0.16914 0.98372 -0.06079 0.18218 0.97951 -0.08589 -0.85436 0.26155 0.44906 -0.62159 0.69118 0.36864 -0.84706 0.17357 0.50235 -0.25513 0.95449 0.15447 -0.63028 0.67611 0.38160 0.15533 0.98303 -0.09761 0.15505 0.98308 -0.09755 -0.26621 0.94925 0.16750 -0.78398 0.27707 0.55553 0.15646 0.97949 -0.12696 -0.71551 0.21489 0.66473 -0.72337 0.19685 0.66180 -0.53117 0.69405 0.48596 -0.21531 0.95540 0.20212 -0.53911 0.67323 0.50608 -0.22613 0.94825 0.22289 0.12238 0.98444 -0.12606 0.13364 0.98224 -0.13172 -0.61744 0.26850 0.73937 0.12196 0.97995 -0.15753 -0.52822 0.26640 0.80623 -0.57997 0.18211 0.79402 -0.41981 0.69669 0.58171 -0.41718 0.70927 0.56824 -0.15676 0.95722 0.24322 0.09262 0.98453 -0.14874 -0.05901 0.99778 -0.03079 0.16281 0.97811 0.12963 0.12607 0.95961 -0.25151 0.19599 -0.98043 -0.01837 -0.96452 -0.25067 0.08283 -0.97660 -0.17782 0.12096 -0.80479 -0.58513 0.09969 -0.63328 -0.77302 0.03754 -0.72616 -0.68147 0.09107 0.21458 -0.97528 -0.05270 -0.42311 -0.90452 0.05308 -0.18723 -0.98222 -0.01389 -0.36096 -0.93046 0.06285 0.17465 -0.98431 -0.02497 -0.93721 -0.27943 0.20868 -0.68737 -0.68736 0.23467 -0.92600 -0.16505 0.33953 -0.92133 -0.22851 0.31455 -0.28110 -0.95470 0.09764 -0.69403 -0.67839 0.24106 0.20738 -0.97456 -0.08504 -0.85461 -0.26080 0.44902 0.16380 -0.98310 -0.08173 -0.32234 -0.93559 0.14413 0.17112 -0.97995 -0.10206 -0.62240 -0.69040 0.36874 -0.84740 -0.17285 0.50204 -0.24032 -0.95975 0.14533 -0.63104 -0.67540 0.38160 -0.78419 -0.27666 0.55543 -0.26047 -0.94537 0.19603 0.14875 -0.98256 -0.11155 0.14917 -0.98242 -0.11226 0.14605 -0.97994 -0.13561 -0.53184 -0.69329 0.48630 -0.71932 -0.19083 0.66796 -0.72141 -0.21084 0.65963 -0.20511 -0.95964 0.19242 -0.53977 -0.67249 0.50636 -0.21885 -0.94617 0.23847 0.12617 -0.98156 -0.14358 0.12393 -0.98306 -0.13504 -0.61764 -0.26808 0.73936 0.11562 -0.98033 -0.15994 -0.41812 -0.69623 0.58347 -0.54545 -0.11098 0.83077 -0.56890 -0.25471 0.78197 -0.14761 -0.96138 0.23227 -0.41545 -0.70916 0.56965 -0.13028 -0.97712 0.16813 0.12770 -0.96854 -0.21358 0.11576 -0.98031 -0.15997 0.11951 -0.96126 -0.24840 0.86759 -0.00004 0.49729 0.86005 -0.00067 0.51021 0.69871 0.00033 0.71540 0.68315 -0.00054 0.73028 0.45680 0.00096 0.88957 0.44236 0.00026 0.89684 0.18885 -0.00058 0.98201 0.19784 -0.00019 0.98023 -0.07915 -0.00022 0.99686 -0.08595 -0.00053 0.99630 -0.36010 0.00041 0.93291 -0.37498 -0.00025 0.92703 0.86482 0.05323 0.49925 0.89424 0.04308 0.44551 0.91976 0.13689 0.36782 0.85166 0.07061 0.51932 0.85668 0.23985 0.45669 0.74796 0.10340 0.65564 0.79318 0.34142 0.50427 0.67621 0.14507 0.72228 0.90664 0.39515 0.14784 0.54784 0.16722 0.81970 0.61468 0.48582 0.62140 0.76377 0.62501 0.16126 0.69118 0.44984 0.56560 0.43262 0.21045 0.87667 0.42687 0.61530 0.66271 0.34421 0.21590 0.91373 0.19110 0.25623 0.94754 0.74895 0.64085 0.16846 0.46141 0.60552 0.64842 0.55087 0.81731 0.16897 0.14403 0.25363 0.95652 0.23745 0.69961 0.67392 -0.06179 0.28381 0.95689 0.51464 0.83834 0.17982 0.30991 0.93560 0.16913 0.21181 0.70288 0.67904 0.02029 0.75864 0.65120 -0.08136 0.28235 0.95585 -0.10996 0.28736 0.95149 0.35288 0.92239 0.15705 -0.11065 0.75626 0.64485 -0.34752 0.28060 0.89470 0.18518 0.96802 0.16923 -0.35957 0.28417 0.88879 -0.10909 0.75662 0.64469 0.04733 0.98757 0.14990 0.91677 0.37563 -0.13579 0.76266 0.61462 -0.20148 0.77416 0.59853 -0.20600 0.53176 0.81577 -0.22750 0.57893 0.77639 -0.24914 0.36133 0.90335 -0.23110 0.44603 0.85471 -0.26558 0.19295 0.94965 -0.24683 0.25813 0.92732 -0.27101 0.95845 0.07640 -0.27484 0.96167 0.06620 -0.26611 0.93288 0.02087 -0.35958 0.90762 0.09845 -0.40808 0.87723 0.15437 -0.45457 0.91474 0.23838 -0.32622 0.88053 0.01263 -0.47382 0.88988 0.28746 -0.35422 0.87002 0.03612 -0.49170 0.84090 -0.00101 -0.54120 0.75048 0.51149 -0.41852 0.75650 0.35756 -0.54760 0.73658 0.20873 -0.64334 0.74511 0.36872 -0.55575 0.78441 0.45895 -0.41721 0.72747 0.22157 -0.64938 0.69223 0.12864 -0.71011 0.66133 0.02956 -0.74951 0.70152 0.02967 -0.71203 0.71199 0.10709 -0.69398 0.58847 0.34393 -0.73172 0.59922 0.52419 -0.60512 0.59434 0.52732 -0.60720 0.63549 0.62397 -0.45477 0.55202 0.67988 -0.48274 0.50514 0.23415 -0.83067 0.55892 0.37367 -0.74026 0.50506 0.09286 -0.85807 0.53614 0.07615 -0.84069 0.56324 0.18628 -0.80502 0.42201 0.76248 -0.49044 0.45764 0.44194 -0.77153 0.42960 0.64938 -0.62750 0.49092 0.71323 -0.50030 0.45921 0.63909 -0.61700 0.19847 0.33790 -0.92002 0.31436 0.55529 -0.76996 0.52807 0.68920 -0.49613 0.49723 0.61593 -0.61106 0.33651 0.10481 -0.93583 0.05364 0.19518 -0.97930 0.22468 0.82174 -0.52369 0.66150 -0.00244 -0.74994 0.66936 -0.00439 -0.74293 0.50732 -0.00029 -0.86175 0.53404 -0.00848 -0.84541 0.33887 0.00575 -0.94082 0.38850 -0.00667 -0.92143 0.98063 0.06166 -0.18593 0.97165 -0.08208 -0.22171 0.93339 -0.02097 -0.35826 0.90822 -0.10105 -0.40612 0.86034 -0.19098 -0.47259 0.90628 -0.30599 -0.29159 0.88367 -0.00565 -0.46808 0.51136 -0.73088 -0.45202 0.85364 -0.06651 -0.51659 0.81975 -0.01450 -0.57254 0.77556 -0.16320 -0.60981 0.82147 -0.26460 -0.50515 0.75267 -0.51166 -0.41435 0.79853 -0.43998 -0.41081 0.75471 -0.34177 -0.56001 0.78536 -0.05049 -0.61697 0.78371 -0.00159 -0.62112 0.69609 -0.11307 -0.70899 0.73667 -0.21935 -0.63969 0.66919 -0.04023 -0.74200 0.59143 -0.66370 -0.45795 0.61722 -0.49367 -0.61265 0.65964 -0.59015 -0.46540 0.63442 -0.04473 -0.77169 0.65752 -0.14718 -0.73892 0.62728 -0.48184 -0.61185 0.57209 -0.36087 -0.73653 0.53978 -0.20746 -0.81584 0.59136 -0.33954 -0.73144 0.53179 -0.08056 -0.84303 0.47428 -0.59486 -0.64900 0.52137 -0.70758 -0.47697 0.33173 -0.51922 -0.78763 0.40674 -0.65063 -0.64128 0.35598 -0.78086 -0.51336 0.43567 -0.43150 -0.78994 0.34217 -0.32854 -0.88033 0.37782 -0.29848 -0.87645 0.33477 -0.10404 -0.93654 0.38808 -0.08436 -0.91776 0.92358 -0.35766 -0.13810 0.71913 -0.66669 -0.19588 0.77454 -0.59541 -0.21350 0.60812 -0.75847 -0.23432 0.61697 -0.75020 -0.23781 0.36141 -0.89887 -0.24782 0.38620 -0.88561 -0.25795 0.20676 -0.94041 -0.26995 0.89427 -0.03537 0.44612 0.95299 -0.04742 0.29926 0.92124 -0.15104 0.35848 0.86617 -0.05843 0.49633 0.82569 -0.31028 0.47112 0.78480 -0.08791 0.61348 0.69262 -0.13759 0.70806 0.72992 -0.39709 0.55635 0.69118 -0.13805 0.70938 0.66984 -0.44980 0.59075 0.60896 -0.14973 0.77894 0.46632 -0.19921 0.86189 0.92280 -0.37521 0.08751 0.61946 -0.77197 0.14259 0.79731 -0.58492 0.14886 0.72790 -0.41384 0.54672 0.44603 -0.20223 0.87187 0.52025 -0.56828 0.63749 0.42858 -0.20872 0.87906 0.60685 -0.76770 0.20587 0.52011 -0.56833 0.63756 0.70465 -0.69221 0.15593 0.18355 -0.24618 0.95169 0.20724 -0.24957 0.94592 0.29503 -0.66866 0.68253 0.39902 -0.65383 0.64288 0.48397 -0.85199 0.19974 0.60082 -0.78524 0.14972 -0.07555 -0.28563 0.95536 0.25210 -0.94931 0.18777 0.15490 -0.71443 0.68235 -0.00465 -0.76317 0.64619 -0.10740 -0.27806 0.95454 0.35331 -0.92324 0.15096 -0.13451 -0.75583 0.64080 0.03589 -0.98353 0.17717 0.20848 -0.97041 0.12180 -0.34502 -0.29404 0.89135 -0.16838 -0.75905 0.62888 -0.42627 -0.26736 0.86418 0.01280 -0.99985 -0.01152 0.00967 -0.99986 -0.01389 0.00680 -0.99987 -0.01467 0.00679 -0.99986 0.01553 0.01086 -0.99983 -0.01494 0.00689 -0.99986 -0.01547 0.00437 -0.99985 -0.01649 0.00739 -0.99983 0.01661 0.00395 -0.99987 0.01579 0.99518 0.00000 -0.09802 0.99452 0.00200 -0.10453 0.95694 -0.00187 -0.29028 0.95105 0.00374 -0.30901 0.88192 -0.00348 -0.47139 0.86601 0.00521 -0.49999 0.77300 -0.00481 -0.63439 0.74313 0.00642 -0.66912 0.63438 -0.00589 -0.77300 0.58777 0.00735 -0.80900 0.47139 -0.00669 -0.88190 0.40672 0.00803 -0.91352 0.29027 -0.00722 -0.95692 0.29027 -0.00722 0.95692 0.40672 0.00803 0.91352 0.47139 -0.00669 0.88190 0.58777 0.00735 0.80900 0.63438 -0.00588 0.77300 0.74313 0.00642 0.66912 0.77300 -0.00481 0.63439 0.86601 0.00521 0.49999 0.88192 -0.00348 0.47139 0.95105 0.00374 0.30902 0.95694 -0.00187 0.29028 0.99518 0.00214 0.09802 0.99452 -0.00000 0.10453 0.00413 0.99985 0.01652 0.99518 -0.00000 0.09802 0.99452 -0.00200 0.10453 0.95694 0.00187 0.29028 0.95105 -0.00374 0.30902 0.88192 0.00348 0.47139 0.86601 -0.00521 0.49999 0.77300 0.00481 0.63439 0.74313 -0.00642 0.66912 0.63438 0.00588 0.77300 0.58777 -0.00735 0.80900 0.47139 0.00669 0.88190 0.40672 -0.00803 0.91352 0.29027 0.00722 0.95692 -0.99369 0.00624 -0.11196 -0.99271 0.00000 -0.12054 -0.94387 -0.00535 -0.33028 -0.93496 0.01071 -0.35459 -0.84668 -0.00981 -0.53201 -0.82290 0.01472 -0.56800 -0.70704 -0.01339 -0.70704 -0.66302 0.01785 -0.74839 -0.53196 -0.01607 -0.84661 -0.46462 0.02008 -0.88528 -0.46462 0.02008 0.88528 -0.53196 -0.01607 0.84662 -0.66302 0.01785 0.74839 -0.70705 -0.01339 0.70704 -0.82290 0.01472 0.56800 -0.84668 -0.00982 0.53201 -0.93496 0.01071 0.35458 -0.94387 -0.00535 0.33027 -0.99269 0.00580 0.12054 -0.99371 -0.00000 0.11197 0.29027 0.00722 -0.95692 0.40672 -0.00803 -0.91352 0.47139 0.00669 -0.88190 0.58777 -0.00735 -0.80900 0.63438 0.00589 -0.77300 0.74313 -0.00642 -0.66912 0.77300 0.00481 -0.63439 0.86601 -0.00521 -0.49999 0.88192 0.00348 -0.47139 0.95105 -0.00374 -0.30901 0.95694 0.00187 -0.29028 0.99518 -0.00214 -0.09802 0.99452 0.00000 -0.10453 0.97704 0.00006 -0.21303 0.97771 -0.00700 -0.20983 0.99727 -0.01551 -0.07222 0.99687 -0.00117 -0.07902 -0.97608 -0.00001 0.21740 -0.97610 0.00001 0.21734 -0.99630 -0.00001 0.08600 -0.99633 0.00008 0.08562 0.26455 0.80715 -0.52776 0.34054 0.54168 -0.76851 0.35220 0.27446 -0.89478 0.07352 0.40715 -0.91040 0.00437 0.99985 -0.01649 0.00689 0.99986 -0.01547 0.00715 0.99986 -0.01543 0.01002 0.99985 -0.01379 0.00967 0.99986 -0.01389 0.01280 0.99985 -0.01152 0.01186 0.99986 -0.01192 0.01398 0.99985 -0.00984 0.01458 0.99986 -0.00841 0.01547 0.99985 -0.00726 0.01603 0.99986 -0.00521 0.01647 0.99985 -0.00446 0.01684 0.99986 -0.00177 0.01572 0.99988 0.00165 0.01506 0.99986 0.00672 0.68740 0.72228 -0.07613 0.01634 0.99987 0.00011 0.01633 0.99986 -0.00300 0.58113 0.80877 -0.09042 0.53871 0.84142 0.04248 0.27493 0.79940 -0.53420 0.28266 0.74141 -0.60862 0.01616 0.99986 0.00525 0.01502 0.99986 0.00802 0.01462 0.99986 0.00844 0.00680 0.99986 0.01556 0.00689 0.99986 0.01548 0.00933 0.99985 0.01427 0.00991 0.99986 0.01363 0.01160 0.99985 0.01254 0.01251 0.99986 0.01126 0.01352 0.99985 0.01043 0.01186 -0.99986 -0.01192 0.01398 -0.99985 -0.00984 0.01457 -0.99986 -0.00842 0.01547 -0.99985 -0.00726 0.01603 -0.99986 -0.00521 0.01647 -0.99985 -0.00446 0.01684 -0.99986 -0.00177 0.01520 -0.99987 -0.00572 0.01573 -0.99987 0.00165 0.01740 -0.99983 0.00683 0.01709 -0.99985 0.00300 0.01750 -0.99983 0.00568 0.01480 -0.99985 0.00855 0.01489 -0.99986 0.00794 0.01287 -0.99985 0.01159 0.01325 -0.99986 0.01022 0.01037 -0.99984 0.01427 0.01124 -0.99986 0.01216 0.00933 -0.99985 0.01427 0.91325 -0.39561 -0.09728 0.84105 -0.52604 -0.12613 0.78926 -0.60701 -0.09279 0.66360 -0.74401 -0.07801 0.59337 -0.79930 -0.09497 0.51613 -0.85524 -0.04663 0.99105 0.11258 -0.07178 0.95071 0.27410 -0.14499 0.01716 0.80299 -0.59575 0.03822 0.78970 -0.61230 0.07553 0.77517 -0.62722 0.03867 0.78385 -0.61975 0.94370 0.32976 0.02619 0.00000 0.19454 -0.98089 0.00000 0.35343 -0.93546 -1.00000 -0.00059 -0.00003 -1.00000 -0.00001 -0.00006 -1.00000 0.00182 0.00003 -1.00000 -0.00001 0.00011 -1.00000 -0.00116 0.00005 -0.36527 0.03145 0.93037 -0.17217 -0.03776 0.98434 0.00495 0.02519 0.99967 0.08047 -0.00910 0.99672 0.26345 0.00853 0.96464 0.32287 -0.01482 0.94633 0.48232 0.01089 0.87593 0.53692 -0.01160 0.84355 0.68298 0.00020 0.73043 0.70697 0.01756 0.70702 0.86223 0.02244 0.50602 0.84699 0.00157 0.53161 0.95795 -0.01567 0.28651 0.97465 -0.06454 0.21420 0.90187 0.03293 0.43075 0.86639 -0.03503 0.49814 0.76322 0.02282 0.64573 0.69250 -0.01974 0.72115 0.55842 0.02039 0.82931 0.48494 -0.01025 0.87449 0.26660 -0.00817 0.96377 0.32472 0.01522 0.94569 0.08066 0.00867 0.99670 0.00713 -0.02531 0.99965 -0.17237 0.03793 0.98430 -0.36502 -0.03199 0.93045 0.36527 -0.03146 0.93037 0.17216 0.03776 0.98435 -0.00495 -0.02519 0.99967 -0.08047 0.00910 0.99672 -0.26345 -0.00853 0.96464 -0.32289 0.01483 0.94632 -0.48232 -0.01087 0.87593 -0.53689 0.01160 0.84357 -0.68299 -0.00020 0.73043 -0.70698 -0.01757 0.70702 -0.86223 -0.02245 0.50601 -0.84699 -0.00157 0.53161 -0.95795 0.01566 0.28649 -0.97470 0.06523 0.21378 -0.90210 -0.03361 0.43023 -0.86636 0.03490 0.49819 -0.76326 -0.02290 0.64568 -0.69248 0.01969 0.72116 -0.55840 -0.02044 0.82932 -0.48492 0.01021 0.87450 -0.26660 0.00817 0.96377 -0.32477 -0.01524 0.94567 -0.08066 -0.00867 0.99670 -0.00713 0.02531 0.99965 0.17236 -0.03793 0.98430 0.36502 0.03199 0.93045 -0.03482 -0.36793 -0.92920 -0.20097 -0.42995 -0.88020 0.01380 -0.46884 -0.88318 -0.00681 -0.53767 -0.84313 -0.08527 -0.60194 -0.79397 0.79985 -0.39356 -0.45316 0.27119 -0.64396 -0.71538 0.07550 -0.68176 -0.72767 0.00718 -0.70281 -0.71135 0.00314 -0.64168 -0.76696 -0.00032 -0.68772 -0.72598 -0.04496 -0.74263 -0.66820 -0.00389 -0.72847 -0.68507 0.04387 -0.78368 -0.61962 0.06918 -0.77730 -0.62532 0.03512 -0.79133 -0.61038 0.01595 -0.80410 -0.59429 0.00894 -0.81231 -0.58316 -0.00000 -0.84144 -0.54036 -0.02572 -0.78358 -0.62076 -0.00610 -0.70315 -0.71101 0.00055 -0.75203 -0.65913 0.00002 -0.75715 -0.65324 -0.00661 -0.81282 -0.58248 -0.00927 -0.81847 -0.57447 -0.00547 -0.80640 -0.59134 -0.00063 -0.77545 -0.63141 0.00001 -0.83170 -0.55522 0.00844 -0.88587 -0.46385 0.04678 -0.86190 -0.50491 0.00027 -0.89631 -0.44344 -0.00428 -0.90848 -0.41790 0.00415 -0.95659 -0.29141 -0.00446 -0.97121 -0.23816 0.00433 -0.99405 -0.10883 -0.00463 -0.99875 -0.04979 0.00449 -0.99698 0.07753 -0.00478 -0.99009 0.14038 0.00463 -0.96528 0.26119 -0.00492 -0.94554 0.32546 0.00475 -0.90004 0.43578 -0.00503 -0.86673 0.49875 0.00486 -0.80354 0.59523 -0.00512 -0.75651 0.65397 0.00494 -0.67913 0.73400 -0.00520 -0.61887 0.78548 0.00501 -0.53113 0.84728 -0.00525 -0.45880 0.88852 0.00505 -0.36468 0.93112 -0.00529 -0.28210 0.95937 0.00508 -0.18556 0.98262 -0.00531 -0.09519 0.99545 0.00509 0.00000 0.99999 -0.00531 0.09519 0.99545 0.00508 0.18556 0.98262 -0.00529 0.28210 0.95937 0.00505 0.36468 0.93112 -0.00525 0.45880 0.88852 0.00501 0.53113 0.84728 -0.00520 0.61887 0.78548 0.00494 0.67913 0.73400 -0.00512 0.75651 0.65397 0.00486 0.80354 0.59523 -0.00503 0.86673 0.49875 0.00475 0.90004 0.43578 -0.00492 0.94554 0.32546 0.00463 0.96528 0.26119 -0.00478 0.99009 0.14038 0.00449 0.99698 0.07753 -0.00463 0.99875 -0.04979 0.00433 0.99405 -0.10883 -0.00446 0.97121 -0.23816 0.00415 0.95659 -0.29141 -0.00428 0.90848 -0.41790 0.00911 0.88587 -0.46385 0.00223 0.89084 -0.45432 0.00699 0.87717 -0.48014 -0.00210 0.81283 -0.58249 -0.01778 0.78442 -0.61998 -0.00873 0.80742 -0.58992 -0.00138 0.83795 -0.54575 0.00178 0.84372 -0.53678 0.00642 0.81498 -0.57945 0.00379 0.82076 -0.57125 0.00056 0.75227 -0.65886 0.00002 0.75727 -0.65311 -0.01789 0.68761 -0.72586 -0.00017 0.71789 -0.69616 -0.00596 0.70312 -0.71104 -0.02600 0.78362 -0.62069 -0.00222 0.72810 -0.68547 0.81263 0.38213 -0.44001 0.29066 0.63961 -0.71163 0.09412 0.67880 -0.72826 0.00314 0.64164 -0.76700 -0.03556 0.53734 -0.84262 -0.00425 0.56554 -0.82471 0.01379 0.46886 -0.88317 -0.09912 0.36634 -0.92519 -0.02762 0.38325 -0.92323 -0.02688 -0.18627 -0.98213 -0.14677 -0.36417 -0.91970 0.04336 -0.34955 -0.93591 -0.01380 -0.46884 -0.88318 0.03556 -0.53734 -0.84262 0.00424 -0.56554 -0.82471 -0.80318 -0.39063 -0.44979 -0.27622 -0.64286 -0.71445 -0.07857 -0.68121 -0.72786 -0.00840 -0.70209 -0.71204 -0.00314 -0.64168 -0.76696 0.01789 -0.68761 -0.72586 0.00018 -0.71792 -0.69613 0.00286 -0.72476 -0.68899 -0.03089 -0.78406 -0.61992 -0.00293 -0.82941 -0.55863 -0.34197 -0.87867 -0.33316 -0.11643 -0.81859 -0.56245 0.02600 -0.78362 -0.62069 0.00596 -0.70312 -0.71104 -0.00056 -0.75227 -0.65885 -0.00002 -0.75727 -0.65310 0.00210 -0.81283 -0.58249 0.01778 -0.78442 -0.61998 0.00873 -0.80742 -0.58992 0.00138 -0.83795 -0.54575 -0.00911 -0.88587 -0.46385 -0.00223 -0.89084 -0.45432 -0.00683 -0.87649 -0.48137 -0.00173 -0.84413 -0.53614 0.00428 -0.90848 -0.41790 -0.00415 -0.95659 -0.29141 0.00446 -0.97121 -0.23816 -0.00433 -0.99405 -0.10883 0.00463 -0.99875 -0.04979 -0.00449 -0.99698 0.07753 0.00478 -0.99009 0.14038 -0.00463 -0.96528 0.26119 0.00492 -0.94554 0.32546 -0.00475 -0.90004 0.43578 0.00503 -0.86673 0.49875 -0.00486 -0.80354 0.59523 0.00512 -0.75651 0.65396 -0.00494 -0.67913 0.73400 0.00520 -0.61887 0.78548 -0.00501 -0.53113 0.84728 0.00525 -0.45880 0.88852 -0.00506 -0.36468 0.93112 0.00529 -0.28210 0.95937 -0.00508 -0.18556 0.98262 0.00531 -0.09519 0.99545 -0.00509 0.00000 0.99999 0.00531 0.09519 0.99545 -0.00508 0.18556 0.98262 0.00529 0.28210 0.95937 -0.00506 0.36468 0.93112 0.00525 0.45880 0.88852 -0.00501 0.53113 0.84728 0.00520 0.61887 0.78548 -0.00494 0.67913 0.73400 0.00512 0.75651 0.65397 -0.00486 0.80354 0.59523 0.00503 0.86673 0.49875 -0.00475 0.90004 0.43578 0.00492 0.94554 0.32546 -0.00463 0.96528 0.26119 0.00478 0.99009 0.14038 -0.00449 0.99698 0.07753 0.00463 0.99875 -0.04979 -0.00433 0.99405 -0.10883 0.00446 0.97121 -0.23816 -0.00415 0.95659 -0.29141 0.00428 0.90848 -0.41790 -0.00843 0.88587 -0.46385 -0.04636 0.86225 -0.50436 -0.00027 0.89631 -0.44343 0.00662 0.81282 -0.58248 0.00926 0.81843 -0.57453 0.00547 0.80640 -0.59134 0.00063 0.77545 -0.63141 -0.00005 0.83149 -0.55554 -0.03999 0.78381 -0.61972 -0.07421 0.77562 -0.62682 -0.03783 0.78992 -0.61204 -0.01720 0.80299 -0.59575 -0.00952 0.81155 -0.58420 0.00002 0.84114 -0.54082 -0.00055 0.75203 -0.65913 -0.00002 0.75714 -0.65325 0.00032 0.68772 -0.72598 0.04491 0.74257 -0.66826 0.00610 0.70316 -0.71101 0.02572 0.78358 -0.62076 0.00465 0.72532 -0.68840 -0.80926 0.38520 -0.44353 -0.27998 0.64195 -0.71380 -0.00936 0.70328 -0.71086 -0.00314 0.64164 -0.76700 0.00682 0.53767 -0.84313 0.08527 0.60194 -0.79398 -0.01379 0.46886 -0.88317 0.03480 0.36793 -0.92920 0.34049 -0.94025 0.00054 0.19600 -0.98039 -0.02028 0.18490 -0.98260 -0.01730 -0.02176 -0.99976 0.00210 0.06177 -0.99809 -0.00134 -0.18694 -0.98236 -0.00396 -0.15842 -0.98737 -0.00106 -0.01721 -0.99985 0.00212 -0.30356 -0.95281 0.00157 -0.42286 -0.90620 -0.00092 -0.45111 -0.89244 -0.00618 -0.63482 -0.77264 -0.00547 -0.60572 -0.79568 -0.00139 -0.71193 -0.70225 0.00167 -0.80791 -0.58931 -0.00061 -0.82973 -0.55809 -0.00925 -0.90215 -0.43142 -0.00005 -0.96736 -0.25093 -0.03518 -0.94470 -0.32765 -0.01338 -0.97672 -0.21321 -0.02388 -0.99790 -0.06474 0.00122 -0.31846 -0.94794 -0.00016 -0.33754 -0.94130 -0.00448 -0.23083 -0.97299 0.00271 -0.06843 -0.99765 -0.00373 -0.07245 -0.99736 -0.00434 -0.00682 -0.99998 0.00064 0.09367 -0.99560 0.00174 0.18217 -0.98327 -0.00026 0.13090 -0.99137 -0.00663 0.29065 -0.95683 0.00076 0.42336 -0.90596 -0.00269 0.39087 -0.92042 -0.00720 0.52456 -0.85137 0.00084 0.63479 -0.77267 -0.00390 0.61239 -0.79052 -0.00774 0.69745 -0.71663 0.00002 0.80804 -0.58912 -0.00166 0.76504 -0.64382 -0.01435 0.84115 -0.54080 -0.00111 0.90029 -0.43528 -0.00032 0.92873 -0.37065 -0.00849 0.94712 -0.32087 -0.00117 0.98061 -0.19596 0.00033 0.99205 -0.12537 -0.01069 0.99778 -0.06666 -0.00057 0.32250 0.94657 -0.00007 0.33781 0.94121 -0.00354 0.23142 0.97285 0.00364 0.06278 0.99802 -0.00301 0.07235 0.99737 -0.00444 0.00652 0.99998 0.00045 -0.09498 0.99548 0.00148 -0.18045 0.98358 -0.00048 -0.13177 0.99126 -0.00651 -0.29289 0.95615 0.00079 -0.42264 0.90629 -0.00282 -0.39459 0.91883 -0.00665 -0.53028 0.84782 0.00102 -0.63450 0.77291 -0.00421 -0.62037 0.78428 -0.00655 -0.70591 0.70830 0.00052 -0.80765 0.58966 -0.00253 -0.77455 0.63240 -0.01191 -0.84850 0.52920 -0.00012 -0.92892 0.37028 -0.00108 -0.90617 0.42268 -0.01397 -0.97846 0.20642 0.00241 -0.99204 0.12550 -0.01058 -0.99789 0.06487 -0.00040 -0.33892 0.94081 -0.00463 -0.33691 0.94152 -0.00493 -0.19894 0.98000 0.00410 -0.06835 0.99766 0.00152 0.06944 0.99737 -0.02058 -0.05851 0.99828 -0.00412 0.18077 0.98351 -0.00444 0.15865 0.98733 -0.00218 0.02216 0.99975 0.00095 0.30613 0.95199 0.00136 0.42117 0.90698 -0.00277 0.44349 0.89626 -0.00615 0.54157 0.84065 0.00054 0.63478 0.77268 -0.00532 0.62230 0.78277 -0.00342 0.70719 0.70703 0.00066 0.80697 0.59056 -0.00668 0.78238 0.62280 -0.00177 0.85973 0.51074 0.00191 0.92938 0.36912 -0.00027 0.94263 0.33365 -0.01100 0.98192 0.18931 -0.00020 0.99213 0.12523 -0.00049 0.99682 0.07758 -0.01825 -0.50725 0.86179 -0.00470 -0.45677 0.88900 -0.03232 -0.51241 0.85867 -0.01099 -0.56287 0.82655 -0.00059 -0.64245 0.76633 0.00115 -0.66589 0.74596 -0.01147 -0.74016 0.67239 0.00690 -0.79296 0.60905 -0.01677 -0.81693 0.57673 0.00246 -0.89256 0.45091 -0.00387 -0.87127 0.48848 -0.04762 -0.94060 0.33878 0.02242 -0.95846 0.27675 -0.06901 0.45917 0.88835 -0.00006 0.51555 0.85686 -0.00157 0.57094 0.82044 -0.03009 0.51219 0.85882 -0.00908 0.64245 0.76633 0.00115 0.66591 0.74594 -0.01143 0.74015 0.67241 0.00687 0.79297 0.60904 -0.01671 0.81693 0.57673 0.00245 0.89226 0.45054 -0.02969 0.88249 0.47033 -0.00291 0.51627 -0.85643 0.00036 0.45680 -0.88900 -0.03190 0.51240 -0.85868 -0.01086 0.56287 -0.82655 -0.00059 0.64240 -0.76637 0.00114 0.66591 -0.74595 -0.01131 0.74001 -0.67256 0.00665 0.79275 -0.60932 -0.01663 0.81691 -0.57676 0.00241 0.88251 -0.47028 -0.00285 -0.45917 -0.88835 -0.00014 -0.51541 -0.85694 -0.00158 -0.57098 -0.82041 -0.03023 -0.51220 -0.85882 -0.00918 -0.64241 -0.76636 0.00115 -0.66590 -0.74596 -0.01148 -0.74008 -0.67248 0.00681 -0.79279 -0.60926 -0.01689 -0.81693 -0.57673 0.00247 -0.89211 -0.45086 -0.02945 -0.88249 -0.47032 -0.00293 -0.94061 -0.33876 0.02242 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00001 -0.00047 1.00000 0.00000 -0.00056 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00039 -1.00000 0.00025 0.00122 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00004 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00047 -0.00002 1.00000 0.00000 -0.00004 1.00000 0.00042 -0.00002 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 -0.37891 -0.18191 -0.90738 0.06951 -0.25037 -0.96565 0.06953 0.25037 -0.96565 -0.44514 0.16704 -0.87974 -0.97863 0.19743 0.05752 -0.98789 0.08957 -0.12668 -0.95846 -0.27675 -0.06899 -0.97863 -0.19744 0.05752 -0.98833 -0.09335 -0.12041 + + + + + + + + + + + + + + +

253 0 61 0 63 0 255 1 59 1 61 1 180 2 173 2 175 2 179 3 175 3 172 3 180 4 175 4 179 4 178 5 172 5 177 5 178 6 177 6 176 6 245 7 56 7 243 7 243 8 56 8 241 8 241 9 56 9 53 9 241 10 53 10 239 10 239 11 53 11 237 11 237 12 53 12 52 12 237 13 52 13 235 13 235 14 52 14 49 14 235 15 49 15 233 15 233 16 49 16 48 16 233 17 48 17 47 17 233 18 47 18 225 18 225 19 47 19 46 19 225 20 46 20 103 20 103 21 46 21 50 21 103 22 50 22 102 22 267 23 102 23 50 23 267 24 50 24 51 24 271 25 267 25 51 25 271 26 51 26 54 26 271 27 54 27 263 27 263 28 54 28 261 28 261 29 54 29 55 29 261 30 55 30 259 30 262 31 260 31 37 31 266 32 262 32 37 32 266 33 37 33 40 33 266 34 40 34 264 34 264 35 40 35 42 35 264 36 42 36 130 36 222 37 130 37 42 37 222 38 42 38 43 38 223 39 222 39 43 39 223 40 43 40 45 40 228 41 223 41 45 41 228 42 45 42 44 42 234 43 228 43 44 43 234 44 44 44 41 44 236 45 234 45 41 45 236 46 41 46 39 46 238 47 236 47 39 47 238 48 39 48 38 48 240 49 238 49 38 49 242 50 240 50 38 50 234 51 0 51 230 51 230 52 0 52 231 52 0 53 235 53 231 53 0 54 234 54 236 54 235 55 0 55 236 55 235 56 233 56 231 56 221 57 219 57 220 57 220 58 219 58 218 58 382 59 381 59 380 59 381 60 365 60 198 60 365 61 196 61 198 61 382 62 365 62 381 62 382 63 366 63 365 63 208 64 143 64 140 64 208 65 140 65 204 65 383 66 365 66 366 66 367 67 383 67 366 67 384 68 383 68 367 68 351 69 350 69 349 69 352 70 350 70 351 70 353 71 352 71 351 71 354 72 352 72 353 72 355 73 354 73 353 73 27 74 29 74 348 74 347 75 348 75 29 75 29 76 31 76 347 76 346 77 347 77 31 77 31 78 33 78 346 78 345 79 346 79 33 79 33 80 35 80 345 80 343 81 345 81 35 81 35 82 38 82 343 82 341 83 343 83 38 83 38 84 39 84 341 84 339 85 341 85 39 85 39 86 41 86 339 86 333 87 339 87 41 87 41 88 44 88 333 88 330 89 333 89 44 89 44 90 45 90 330 90 327 91 330 91 45 91 334 92 336 92 4 92 2 93 4 93 336 93 336 94 337 94 2 94 1 95 2 95 337 95 337 96 338 96 1 96 3 97 1 97 338 97 338 98 335 98 3 98 5 99 3 99 335 99 335 100 332 100 5 100 7 101 5 101 332 101 332 102 331 102 7 102 9 103 7 103 331 103 331 104 329 104 9 104 11 105 9 105 329 105 329 106 328 106 11 106 13 107 11 107 326 107 11 108 328 108 326 108 326 109 324 109 13 109 15 110 13 110 324 110 324 111 323 111 15 111 17 112 15 112 323 112 323 113 321 113 17 113 19 114 17 114 321 114 321 115 320 115 19 115 21 116 19 116 320 116 320 117 318 117 21 117 23 118 21 118 318 118 318 119 315 119 23 119 24 120 23 120 315 120 315 121 312 121 24 121 26 122 24 122 312 122 312 123 314 123 26 123 25 124 26 124 314 124 314 125 317 125 25 125 1 126 3 126 2 126 4 127 2 127 3 127 3 128 5 128 4 128 6 129 4 129 5 129 5 130 7 130 6 130 8 131 6 131 7 131 7 132 9 132 8 132 10 133 8 133 9 133 9 134 11 134 10 134 12 135 10 135 11 135 11 136 13 136 12 136 14 137 12 137 13 137 13 138 15 138 14 138 16 139 14 139 15 139 15 140 17 140 16 140 18 141 16 141 17 141 17 142 19 142 18 142 20 143 18 143 19 143 19 144 21 144 20 144 22 145 20 145 21 145 21 146 23 146 22 146 25 147 22 147 23 147 23 148 24 148 25 148 26 149 25 149 24 149 45 150 43 150 327 150 43 151 325 151 327 151 322 152 325 152 43 152 43 153 42 153 322 153 319 154 322 154 42 154 42 155 40 155 319 155 313 156 319 156 40 156 40 157 37 157 313 157 310 158 313 158 37 158 37 159 36 159 310 159 308 160 310 160 36 160 36 161 34 161 308 161 306 162 308 162 34 162 34 163 32 163 306 163 304 164 306 164 32 164 32 165 30 165 304 165 305 166 304 166 30 166 30 167 28 167 305 167 29 168 27 168 250 168 28 169 30 169 252 169 250 170 248 170 29 170 254 171 252 171 30 171 31 172 29 172 248 172 30 173 32 173 254 173 248 174 246 174 31 174 246 175 33 175 31 175 256 176 254 176 32 176 258 177 256 177 34 177 256 178 32 178 34 178 246 179 244 179 33 179 35 180 33 180 244 180 34 181 36 181 258 181 260 182 258 182 36 182 244 183 242 183 35 183 242 184 38 184 35 184 36 185 37 185 260 185 63 186 61 186 303 186 302 187 303 187 61 187 61 188 59 188 302 188 301 189 302 189 59 189 59 190 57 190 301 190 300 191 301 191 57 191 57 192 55 192 300 192 298 193 300 193 55 193 55 194 54 194 298 194 296 195 298 195 54 195 54 196 51 196 296 196 294 197 296 197 51 197 51 198 50 198 294 198 292 199 294 199 50 199 50 200 46 200 292 200 290 201 292 201 46 201 46 202 47 202 290 202 288 203 290 203 47 203 47 204 48 204 288 204 48 205 286 205 288 205 284 206 286 206 48 206 48 207 49 207 284 207 282 208 284 208 49 208 49 209 52 209 282 209 280 210 282 210 52 210 52 211 53 211 280 211 278 212 280 212 53 212 53 213 56 213 278 213 276 214 278 214 56 214 56 215 58 215 276 215 274 216 276 216 58 216 58 217 60 217 274 217 272 218 274 218 60 218 60 219 62 219 272 219 273 220 272 220 62 220 62 221 64 221 273 221 245 222 247 222 56 222 257 223 259 223 57 223 259 224 55 224 57 224 58 225 56 225 247 225 57 226 59 226 257 226 247 227 249 227 58 227 249 228 60 228 58 228 255 229 257 229 59 229 62 230 60 230 249 230 253 231 255 231 61 231 249 232 251 232 62 232 64 233 62 233 251 233 189 234 110 234 193 234 110 235 65 235 193 235 67 236 65 236 110 236 110 237 115 237 67 237 66 238 67 238 115 238 115 239 118 239 66 239 72 240 66 240 118 240 118 241 123 241 72 241 74 242 72 242 123 242 123 243 125 243 74 243 224 244 74 244 125 244 125 245 222 245 224 245 223 246 224 246 222 246 193 247 65 247 192 247 69 248 195 248 192 248 195 249 69 249 377 249 65 250 67 250 192 250 75 251 377 251 69 251 192 252 68 252 69 252 68 253 192 253 67 253 67 254 66 254 68 254 70 255 68 255 66 255 68 256 70 256 69 256 69 257 71 257 75 257 71 258 69 258 70 258 66 259 72 259 70 259 76 260 75 260 71 260 73 261 70 261 72 261 70 262 73 262 71 262 71 263 229 263 76 263 229 264 71 264 73 264 72 265 74 265 73 265 230 266 76 266 229 266 73 267 227 267 229 267 227 268 73 268 74 268 74 269 224 269 227 269 377 270 75 270 379 270 79 271 379 271 75 271 75 272 76 272 79 272 80 273 79 273 76 273 76 274 230 274 80 274 231 275 80 275 230 275 77 276 221 276 379 276 221 277 77 277 219 277 78 278 219 278 77 278 219 279 78 279 218 279 83 280 218 280 78 280 379 281 79 281 77 281 84 282 83 282 78 282 81 283 77 283 79 283 77 284 81 284 78 284 82 285 78 285 81 285 78 286 82 286 84 286 79 287 80 287 81 287 85 288 84 288 82 288 80 289 231 289 81 289 232 290 81 290 231 290 81 291 232 291 82 291 226 292 82 292 232 292 82 293 226 293 85 293 86 294 85 294 226 294 86 295 226 295 87 295 218 296 83 296 216 296 89 297 216 297 83 297 83 298 84 298 89 298 94 299 89 299 84 299 84 300 85 300 94 300 85 301 100 301 94 301 85 302 86 302 100 302 86 303 87 303 100 303 103 304 100 304 87 304 225 305 103 305 87 305 150 306 88 306 151 306 88 307 150 307 152 307 91 308 152 308 216 308 152 309 91 309 88 309 151 310 90 310 362 310 90 311 151 311 88 311 216 312 89 312 91 312 106 313 362 313 90 313 88 314 93 314 90 314 93 315 88 315 91 315 89 316 94 316 91 316 92 317 90 317 93 317 90 318 92 318 106 318 95 319 91 319 94 319 91 320 95 320 93 320 107 321 106 321 92 321 96 322 92 322 93 322 92 323 96 323 107 323 93 324 97 324 96 324 97 325 93 325 95 325 94 326 100 326 95 326 101 327 95 327 100 327 95 328 101 328 97 328 108 329 107 329 96 329 96 330 98 330 108 330 98 331 96 331 97 331 99 332 97 332 101 332 97 333 99 333 98 333 98 334 104 334 108 334 104 335 98 335 99 335 99 336 105 336 104 336 105 337 99 337 101 337 100 338 103 338 101 338 101 339 103 339 102 339 109 340 108 340 104 340 101 341 102 341 105 341 102 342 267 342 105 342 268 343 104 343 105 343 104 344 268 344 109 344 269 345 109 345 268 345 105 346 267 346 268 346 362 347 106 347 364 347 111 348 364 348 106 348 106 349 107 349 111 349 121 350 111 350 107 350 107 351 108 351 121 351 124 352 121 352 108 352 108 353 109 353 124 353 127 354 124 354 109 354 109 355 269 355 127 355 270 356 127 356 269 356 110 357 189 357 171 357 171 358 112 358 110 358 112 359 171 359 168 359 170 360 113 360 168 360 113 361 170 361 364 361 168 362 114 362 112 362 114 363 168 363 113 363 364 364 111 364 113 364 115 365 110 365 112 365 111 366 121 366 113 366 116 367 112 367 114 367 112 368 116 368 115 368 119 369 113 369 121 369 113 370 119 370 114 370 114 371 117 371 116 371 117 372 114 372 119 372 118 373 115 373 116 373 120 374 116 374 117 374 116 375 120 375 118 375 122 376 117 376 119 376 117 377 122 377 120 377 123 378 118 378 120 378 126 379 119 379 121 379 119 380 126 380 122 380 120 381 128 381 123 381 128 382 120 382 122 382 121 383 124 383 126 383 129 384 122 384 126 384 122 385 129 385 128 385 125 386 123 386 128 386 124 387 127 387 126 387 128 388 130 388 125 388 130 389 222 389 125 389 131 390 126 390 127 390 126 391 131 391 129 391 127 392 270 392 131 392 130 393 128 393 129 393 264 394 129 394 131 394 129 395 264 395 130 395 270 396 265 396 131 396 131 397 265 397 264 397 201 398 202 398 132 398 202 399 133 399 132 399 139 400 133 400 202 400 133 401 139 401 134 401 139 402 136 402 134 402 136 403 141 403 135 403 141 404 138 404 135 404 141 405 136 405 139 405 351 406 349 406 137 406 137 407 138 407 351 407 138 408 142 408 351 408 142 409 138 409 141 409 202 410 203 410 139 410 139 411 140 411 141 411 139 412 204 412 140 412 139 413 203 413 204 413 353 414 351 414 142 414 144 415 141 415 143 415 141 416 140 416 143 416 141 417 144 417 142 417 142 418 145 418 353 418 145 419 355 419 353 419 145 420 142 420 144 420 357 421 355 421 145 421 143 422 146 422 144 422 146 423 143 423 210 423 210 424 143 424 208 424 147 425 144 425 146 425 144 426 147 426 145 426 148 427 145 427 147 427 145 428 148 428 357 428 148 429 359 429 357 429 210 430 211 430 146 430 149 431 146 431 214 431 146 432 211 432 214 432 146 433 149 433 147 433 361 434 359 434 148 434 147 435 150 435 148 435 150 436 151 436 148 436 150 437 147 437 149 437 148 438 151 438 361 438 214 439 215 439 149 439 152 440 149 440 215 440 152 441 150 441 149 441 361 442 151 442 362 442 216 443 152 443 215 443 178 444 176 444 153 444 153 445 155 445 178 445 162 446 155 446 160 446 155 447 154 447 160 447 154 448 156 448 160 448 155 449 162 449 178 449 160 450 156 450 157 450 157 451 159 451 160 451 350 452 352 452 158 452 352 453 159 453 158 453 159 454 161 454 160 454 161 455 159 455 352 455 352 456 354 456 161 456 181 457 178 457 162 457 160 458 163 458 162 458 163 459 160 459 161 459 164 460 161 460 356 460 161 461 354 461 356 461 161 462 164 462 163 462 165 463 162 463 163 463 162 464 165 464 181 464 165 465 182 465 181 465 356 466 358 466 164 466 185 467 182 467 165 467 166 468 163 468 164 468 163 469 166 469 165 469 167 470 164 470 360 470 164 471 358 471 360 471 164 472 167 472 166 472 165 473 169 473 185 473 169 474 188 474 185 474 169 475 165 475 166 475 360 476 363 476 167 476 190 477 188 477 169 477 168 478 166 478 170 478 166 479 167 479 170 479 166 480 168 480 169 480 170 481 167 481 363 481 169 482 171 482 190 482 169 483 168 483 171 483 363 484 364 484 170 484 189 485 190 485 171 485 179 486 172 486 178 486 178 487 181 487 179 487 179 488 183 488 180 488 183 489 179 489 181 489 184 490 180 490 183 490 180 491 184 491 366 491 184 492 367 492 366 492 181 493 182 493 183 493 368 494 367 494 184 494 186 495 183 495 185 495 183 496 182 496 185 496 183 497 186 497 184 497 187 498 184 498 186 498 184 499 187 499 368 499 187 500 370 500 368 500 185 501 188 501 186 501 372 502 370 502 187 502 186 503 191 503 187 503 191 504 186 504 188 504 187 505 194 505 372 505 194 506 374 506 372 506 194 507 187 507 191 507 188 508 190 508 191 508 191 509 189 509 193 509 191 510 190 510 189 510 191 511 193 511 194 511 376 512 374 512 194 512 195 513 194 513 192 513 194 514 193 514 192 514 194 515 195 515 376 515 377 516 376 516 195 516 196 517 206 517 197 517 206 518 199 518 197 518 206 519 205 519 199 519 206 520 196 520 365 520 199 521 205 521 200 521 205 522 201 522 200 522 205 523 202 523 201 523 205 524 203 524 202 524 204 525 203 525 205 525 205 526 207 526 204 526 207 527 208 527 204 527 207 528 205 528 206 528 206 529 209 529 207 529 206 530 384 530 209 530 384 531 369 531 209 531 212 532 207 532 209 532 207 533 212 533 208 533 212 534 210 534 208 534 209 535 213 535 212 535 213 536 209 536 371 536 209 537 369 537 371 537 211 538 210 538 212 538 371 539 373 539 213 539 212 540 217 540 211 540 217 541 214 541 211 541 217 542 212 542 213 542 213 543 220 543 217 543 220 544 213 544 375 544 213 545 373 545 375 545 215 546 214 546 217 546 217 547 218 547 215 547 218 548 216 548 215 548 218 549 217 549 220 549 375 550 378 550 220 550 221 551 220 551 378 551 378 552 379 552 221 552 223 553 228 553 224 553 228 554 227 554 224 554 233 555 225 555 226 555 225 556 87 556 226 556 226 557 232 557 233 557 229 558 227 558 228 558 228 559 234 559 229 559 234 560 230 560 229 560 233 561 232 561 231 561 237 562 235 562 236 562 236 563 238 563 237 563 239 564 237 564 238 564 238 565 240 565 239 565 241 566 239 566 240 566 240 567 242 567 241 567 243 568 241 568 242 568 242 569 244 569 243 569 245 570 243 570 244 570 244 571 246 571 245 571 247 572 245 572 246 572 246 573 248 573 247 573 249 574 247 574 248 574 248 575 250 575 249 575 251 576 249 576 250 576 252 577 254 577 253 577 255 578 253 578 254 578 254 579 256 579 255 579 257 580 255 580 256 580 256 581 258 581 257 581 259 582 257 582 258 582 258 583 260 583 259 583 261 584 259 584 260 584 260 585 262 585 261 585 263 586 261 586 262 586 262 587 266 587 263 587 271 588 263 588 266 588 266 589 264 589 265 589 265 590 270 590 266 590 270 591 271 591 266 591 271 592 268 592 267 592 271 593 269 593 268 593 271 594 270 594 269 594 274 595 272 595 273 595 273 596 275 596 274 596 276 597 274 597 275 597 275 598 277 598 276 598 278 599 276 599 277 599 277 600 279 600 278 600 280 601 278 601 279 601 279 602 281 602 280 602 282 603 280 603 281 603 281 604 283 604 282 604 284 605 282 605 283 605 283 606 285 606 284 606 286 607 284 607 285 607 285 608 287 608 286 608 288 609 286 609 287 609 287 610 289 610 288 610 290 611 288 611 289 611 289 612 291 612 290 612 292 613 290 613 291 613 291 614 293 614 292 614 294 615 292 615 293 615 293 616 295 616 294 616 296 617 294 617 295 617 295 618 297 618 296 618 298 619 296 619 297 619 297 620 299 620 298 620 300 621 298 621 299 621 299 622 303 622 300 622 301 623 300 623 303 623 303 624 302 624 301 624 306 625 304 625 305 625 305 626 307 626 306 626 308 627 306 627 307 627 307 628 309 628 308 628 310 629 308 629 309 629 309 630 311 630 310 630 313 631 310 631 311 631 316 632 312 632 313 632 319 633 313 633 315 633 313 634 312 634 315 634 315 635 318 635 319 635 322 636 319 636 320 636 319 637 318 637 320 637 320 638 321 638 322 638 325 639 322 639 323 639 322 640 321 640 323 640 323 641 324 641 325 641 327 642 325 642 326 642 325 643 324 643 326 643 326 644 328 644 327 644 330 645 327 645 328 645 328 646 329 646 330 646 333 647 330 647 331 647 330 648 329 648 331 648 331 649 332 649 333 649 339 650 333 650 335 650 333 651 332 651 335 651 335 652 338 652 339 652 341 653 339 653 340 653 339 654 337 654 340 654 339 655 338 655 337 655 340 656 342 656 341 656 343 657 341 657 342 657 342 658 344 658 343 658 345 659 343 659 344 659 344 660 348 660 345 660 346 661 345 661 348 661 348 662 347 662 346 662 356 663 354 663 355 663 355 664 357 664 356 664 358 665 356 665 357 665 357 666 359 666 358 666 360 667 358 667 359 667 359 668 361 668 360 668 363 669 360 669 361 669 361 670 362 670 363 670 364 671 363 671 362 671 368 672 384 672 367 672 369 673 384 673 368 673 368 674 370 674 369 674 371 675 369 675 370 675 370 676 372 676 371 676 373 677 371 677 372 677 372 678 374 678 373 678 375 679 373 679 374 679 374 680 376 680 375 680 378 681 375 681 376 681 376 682 377 682 378 682 379 683 378 683 377 683 173 684 180 684 174 684 180 685 380 685 174 685 180 686 382 686 380 686 366 687 382 687 180 687 365 688 383 688 206 688 383 689 384 689 206 689 389 690 391 690 390 690 392 691 390 691 391 691 391 692 393 692 392 692 394 693 392 693 393 693 393 694 395 694 394 694 396 695 394 695 395 695 395 696 397 696 396 696 398 697 396 697 397 697 397 698 399 698 398 698 400 699 398 699 399 699 399 700 401 700 400 700 402 701 400 701 401 701 401 702 403 702 402 702 404 703 402 703 403 703 403 704 405 704 404 704 406 705 404 705 405 705 413 706 411 706 412 706 412 707 414 707 413 707 415 708 413 708 414 708 414 709 416 709 415 709 417 710 415 710 416 710 416 711 418 711 417 711 419 712 417 712 418 712 418 713 420 713 419 713 421 714 419 714 420 714 420 715 422 715 421 715 421 716 422 716 423 716 424 717 421 717 423 717 340 718 337 718 336 718 425 719 340 719 336 719 336 720 334 720 425 720 425 721 334 721 426 721 427 722 425 722 426 722 426 723 428 723 427 723 427 724 428 724 429 724 430 725 427 725 429 725 429 726 431 726 430 726 430 727 431 727 432 727 433 728 430 728 432 728 432 729 434 729 433 729 435 730 433 730 434 730 434 731 436 731 435 731 435 732 436 732 437 732 438 733 435 733 437 733 437 734 439 734 438 734 438 735 439 735 317 735 316 736 438 736 317 736 317 737 314 737 316 737 316 738 314 738 312 738 311 739 316 739 313 739 253 740 440 740 252 740 441 741 252 741 440 741 440 742 442 742 441 742 443 743 441 743 442 743 442 744 444 744 443 744 445 745 443 745 444 745 444 746 446 746 445 746 447 747 445 747 446 747 446 748 448 748 447 748 449 749 447 749 448 749 448 750 450 750 449 750 451 751 449 751 450 751 452 752 451 752 450 752 453 753 452 753 450 753 451 754 452 754 454 754 451 755 454 755 455 755 456 756 451 756 455 756 457 757 458 757 459 757 460 758 461 758 462 758 462 759 463 759 460 759 464 760 465 760 459 760 458 761 464 761 459 761 466 762 460 762 463 762 467 763 465 763 464 763 463 764 468 764 466 764 469 765 470 765 471 765 469 766 471 766 472 766 469 767 472 767 467 767 464 768 469 768 467 768 466 769 468 769 473 769 470 770 469 770 474 770 473 771 470 771 474 771 474 772 466 772 473 772 469 773 475 773 474 773 476 774 474 774 475 774 475 775 477 775 476 775 478 776 476 776 477 776 477 777 479 777 478 777 480 778 478 778 479 778 479 779 251 779 480 779 250 780 480 780 251 780 482 781 385 781 481 781 385 782 387 782 481 782 489 783 385 783 482 783 487 784 490 784 488 784 389 785 385 785 489 785 491 786 488 786 490 786 488 787 491 787 489 787 492 788 489 788 491 788 492 789 391 789 389 789 489 790 492 790 389 790 490 791 493 791 491 791 393 792 391 792 492 792 491 793 494 793 492 793 491 794 493 794 495 794 494 795 491 795 495 795 492 796 496 796 393 796 496 797 492 797 494 797 395 798 393 798 496 798 495 799 497 799 494 799 494 800 497 800 498 800 499 801 494 801 498 801 494 802 499 802 496 802 500 803 397 803 395 803 496 804 500 804 395 804 500 805 496 805 499 805 498 806 501 806 499 806 399 807 397 807 500 807 499 808 501 808 502 808 503 809 499 809 502 809 499 810 503 810 500 810 502 811 504 811 503 811 505 812 401 812 399 812 500 813 505 813 399 813 505 814 500 814 503 814 403 815 401 815 505 815 503 816 504 816 506 816 503 817 506 817 507 817 508 818 503 818 507 818 503 819 508 819 505 819 505 820 509 820 403 820 505 821 508 821 510 821 509 822 505 822 510 822 403 823 509 823 405 823 516 824 517 824 515 824 516 825 515 825 514 825 513 826 516 826 514 826 518 827 516 827 513 827 518 828 513 828 512 828 511 829 518 829 512 829 518 830 511 830 388 830 519 831 517 831 516 831 388 832 390 832 518 832 520 833 516 833 518 833 520 834 521 834 519 834 516 835 520 835 519 835 518 836 390 836 392 836 522 837 518 837 392 837 518 838 522 838 520 838 523 839 521 839 520 839 392 840 394 840 522 840 524 841 520 841 522 841 524 842 525 842 523 842 520 843 524 843 523 843 526 844 522 844 394 844 522 845 526 845 524 845 394 846 396 846 526 846 527 847 525 847 524 847 524 848 528 848 527 848 528 849 524 849 526 849 529 850 527 850 528 850 526 851 530 851 528 851 526 852 396 852 398 852 530 853 526 853 398 853 398 854 400 854 530 854 531 855 532 855 529 855 528 856 531 856 529 856 531 857 528 857 530 857 533 858 532 858 531 858 530 859 534 859 531 859 530 860 400 860 402 860 534 861 530 861 402 861 402 862 404 862 534 862 535 863 531 863 534 863 538 864 534 864 404 864 404 865 406 865 538 865 517 866 540 866 541 866 515 867 517 867 541 867 542 868 543 868 410 868 410 869 408 869 542 869 543 870 544 870 410 870 545 871 544 871 543 871 545 872 543 872 546 872 547 873 545 873 546 873 548 874 545 874 547 874 548 875 547 875 549 875 540 876 548 876 549 876 548 877 540 877 517 877 517 878 519 878 548 878 412 879 410 879 544 879 550 880 544 880 545 880 550 881 414 881 412 881 544 882 550 882 412 882 551 883 545 883 548 883 545 884 551 884 550 884 548 885 552 885 551 885 548 886 519 886 521 886 552 887 548 887 521 887 521 888 523 888 552 888 416 889 414 889 550 889 553 890 550 890 551 890 550 891 553 891 416 891 554 892 551 892 552 892 551 893 554 893 553 893 552 894 523 894 525 894 555 895 552 895 525 895 552 896 555 896 554 896 418 897 416 897 553 897 525 898 527 898 555 898 556 899 420 899 418 899 553 900 556 900 418 900 556 901 553 901 554 901 557 902 554 902 555 902 554 903 557 903 556 903 555 904 558 904 557 904 555 905 527 905 529 905 558 906 555 906 529 906 422 907 420 907 556 907 529 908 532 908 558 908 559 909 423 909 422 909 556 910 559 910 422 910 559 911 556 911 557 911 560 912 559 912 557 912 560 913 557 913 558 913 558 914 532 914 533 914 560 915 558 915 533 915 561 916 560 916 533 916 537 917 561 917 533 917 487 918 485 918 562 918 563 919 407 919 409 919 564 920 563 920 409 920 565 921 563 921 564 921 566 922 565 922 564 922 567 923 566 923 564 923 487 924 568 924 490 924 569 925 566 925 567 925 562 926 569 926 567 926 568 927 562 927 567 927 562 928 568 928 487 928 409 929 411 929 564 929 564 930 570 930 567 930 564 931 411 931 413 931 570 932 564 932 413 932 567 933 571 933 568 933 571 934 567 934 570 934 493 935 490 935 568 935 413 936 415 936 570 936 572 937 493 937 568 937 572 938 568 938 571 938 495 939 493 939 572 939 570 940 573 940 571 940 573 941 570 941 415 941 571 942 574 942 572 942 574 943 571 943 573 943 415 944 417 944 573 944 575 945 572 945 574 945 575 946 497 946 495 946 572 947 575 947 495 947 498 948 497 948 575 948 573 949 576 949 574 949 573 950 417 950 419 950 576 951 573 951 419 951 574 952 577 952 575 952 577 953 574 953 576 953 578 954 575 954 577 954 578 955 501 955 498 955 575 956 578 956 498 956 419 957 421 957 576 957 502 958 501 958 578 958 576 959 579 959 577 959 576 960 421 960 424 960 576 961 424 961 579 961 577 962 580 962 578 962 577 963 579 963 580 963 578 964 580 964 581 964 581 965 504 965 502 965 578 966 581 966 502 966 506 967 504 967 581 967 452 968 582 968 454 968 583 969 454 969 582 969 582 970 584 970 583 970 585 971 583 971 584 971 584 972 586 972 585 972 587 973 585 973 586 973 586 974 588 974 587 974 589 975 587 975 588 975 588 976 590 976 589 976 591 977 589 977 590 977 590 978 424 978 591 978 423 979 591 979 424 979 454 980 592 980 455 980 593 981 455 981 592 981 455 982 593 982 456 982 592 983 583 983 593 983 594 984 456 984 593 984 595 985 593 985 583 985 593 986 595 986 594 986 583 987 585 987 595 987 596 988 456 988 594 988 597 989 595 989 585 989 595 990 597 990 594 990 594 991 598 991 596 991 598 992 594 992 597 992 585 993 587 993 597 993 597 994 599 994 598 994 599 995 597 995 587 995 587 996 589 996 599 996 600 997 596 997 598 997 601 998 598 998 599 998 598 999 601 999 600 999 602 1000 599 1000 589 1000 599 1001 602 1001 601 1001 589 1002 603 1002 602 1002 604 1003 600 1003 601 1003 601 1004 605 1004 604 1004 605 1005 601 1005 602 1005 602 1006 606 1006 605 1006 606 1007 602 1007 603 1007 603 1008 591 1008 606 1008 607 1009 604 1009 605 1009 606 1010 559 1010 605 1010 559 1011 606 1011 591 1011 561 1012 607 1012 605 1012 591 1013 423 1013 559 1013 560 1014 605 1014 559 1014 605 1015 560 1015 561 1015 614 1016 608 1016 596 1016 596 1017 600 1017 614 1017 609 1018 614 1018 600 1018 600 1019 604 1019 609 1019 623 1020 609 1020 604 1020 604 1021 607 1021 623 1021 610 1022 623 1022 607 1022 607 1023 561 1023 610 1023 610 1024 561 1024 537 1024 611 1025 462 1025 461 1025 461 1026 608 1026 611 1026 463 1027 462 1027 611 1027 612 1028 463 1028 611 1028 611 1029 613 1029 612 1029 613 1030 611 1030 608 1030 468 1031 463 1031 612 1031 608 1032 614 1032 613 1032 612 1033 615 1033 468 1033 473 1034 468 1034 615 1034 614 1035 609 1035 613 1035 616 1036 612 1036 613 1036 612 1037 616 1037 615 1037 613 1038 617 1038 616 1038 617 1039 613 1039 609 1039 618 1040 615 1040 616 1040 615 1041 618 1041 473 1041 619 1042 470 1042 473 1042 473 1043 620 1043 619 1043 620 1044 473 1044 618 1044 616 1045 621 1045 618 1045 621 1046 616 1046 617 1046 617 1047 622 1047 621 1047 622 1048 617 1048 609 1048 609 1049 623 1049 622 1049 618 1050 624 1050 620 1050 624 1051 618 1051 621 1051 625 1052 626 1052 619 1052 620 1053 625 1053 619 1053 625 1054 620 1054 624 1054 623 1055 610 1055 622 1055 621 1056 535 1056 624 1056 535 1057 621 1057 622 1057 627 1058 622 1058 610 1058 622 1059 627 1059 535 1059 624 1060 539 1060 625 1060 539 1061 624 1061 535 1061 627 1062 610 1062 536 1062 535 1063 627 1063 536 1063 538 1064 406 1064 626 1064 625 1065 538 1065 626 1065 610 1066 537 1066 536 1066 470 1067 619 1067 471 1067 628 1068 471 1068 619 1068 619 1069 626 1069 628 1069 629 1070 628 1070 626 1070 626 1071 406 1071 629 1071 405 1072 629 1072 406 1072 630 1073 457 1073 459 1073 459 1074 631 1074 630 1074 459 1075 465 1075 631 1075 465 1076 632 1076 631 1076 633 1077 631 1077 632 1077 631 1078 633 1078 630 1078 465 1079 467 1079 632 1079 646 1080 630 1080 633 1080 467 1081 634 1081 632 1081 467 1082 472 1082 634 1082 635 1083 632 1083 634 1083 632 1084 635 1084 633 1084 636 1085 646 1085 633 1085 633 1086 637 1086 636 1086 637 1087 633 1087 635 1087 472 1088 638 1088 634 1088 472 1089 471 1089 638 1089 639 1090 634 1090 638 1090 634 1091 639 1091 635 1091 471 1092 628 1092 638 1092 640 1093 636 1093 637 1093 641 1094 637 1094 635 1094 637 1095 641 1095 640 1095 642 1096 638 1096 628 1096 638 1097 642 1097 639 1097 635 1098 643 1098 641 1098 643 1099 635 1099 639 1099 644 1100 639 1100 642 1100 639 1101 644 1101 643 1101 628 1102 629 1102 642 1102 507 1103 641 1103 643 1103 641 1104 507 1104 640 1104 508 1105 643 1105 644 1105 643 1106 508 1106 507 1106 506 1107 640 1107 507 1107 644 1108 510 1108 508 1108 510 1109 644 1109 642 1109 642 1110 509 1110 510 1110 509 1111 642 1111 629 1111 629 1112 405 1112 509 1112 630 1113 646 1113 645 1113 647 1114 645 1114 646 1114 646 1115 636 1115 647 1115 648 1116 647 1116 636 1116 636 1117 640 1117 648 1117 649 1118 648 1118 640 1118 640 1119 506 1119 649 1119 581 1120 649 1120 506 1120 453 1121 650 1121 452 1121 453 1122 450 1122 651 1122 650 1123 453 1123 651 1123 582 1124 452 1124 650 1124 652 1125 650 1125 651 1125 650 1126 652 1126 582 1126 653 1127 582 1127 652 1127 651 1128 654 1128 652 1128 584 1129 653 1129 652 1129 655 1130 652 1130 654 1130 652 1131 655 1131 584 1131 656 1132 584 1132 655 1132 651 1133 630 1133 654 1133 654 1134 630 1134 645 1134 657 1135 654 1135 645 1135 654 1136 657 1136 655 1136 655 1137 658 1137 656 1137 658 1138 655 1138 657 1138 586 1139 656 1139 658 1139 659 1140 657 1140 645 1140 657 1141 659 1141 658 1141 645 1142 647 1142 659 1142 588 1143 586 1143 658 1143 658 1144 660 1144 588 1144 660 1145 658 1145 659 1145 659 1146 661 1146 660 1146 661 1147 659 1147 647 1147 647 1148 648 1148 661 1148 590 1149 588 1149 660 1149 662 1150 661 1150 648 1150 661 1151 662 1151 660 1151 663 1152 660 1152 662 1152 660 1153 663 1153 590 1153 648 1154 649 1154 662 1154 662 1155 580 1155 663 1155 580 1156 662 1156 649 1156 649 1157 581 1157 580 1157 424 1158 590 1158 663 1158 579 1159 663 1159 580 1159 663 1160 579 1160 424 1160 475 1161 670 1161 671 1161 477 1162 475 1162 671 1162 479 1163 477 1163 671 1163 442 1164 440 1164 673 1164 671 1165 674 1165 479 1165 479 1166 674 1166 64 1166 251 1167 479 1167 64 1167 253 1168 63 1168 673 1168 440 1169 253 1169 673 1169 287 1170 285 1170 664 1170 665 1171 664 1171 285 1171 285 1172 283 1172 665 1172 666 1173 665 1173 283 1173 283 1174 281 1174 666 1174 670 1175 666 1175 281 1175 281 1176 279 1176 670 1176 671 1177 670 1177 279 1177 279 1178 277 1178 671 1178 674 1179 671 1179 277 1179 277 1180 275 1180 674 1180 64 1181 674 1181 275 1181 275 1182 273 1182 64 1182 303 1183 299 1183 63 1183 673 1184 63 1184 299 1184 299 1185 297 1185 673 1185 672 1186 673 1186 297 1186 297 1187 295 1187 672 1187 669 1188 672 1188 295 1188 295 1189 293 1189 669 1189 667 1190 669 1190 293 1190 293 1191 291 1191 667 1191 668 1192 667 1192 291 1192 291 1193 289 1193 668 1193 668 1194 289 1194 287 1194 664 1195 668 1195 287 1195 252 1196 441 1196 28 1196 433 1197 435 1197 684 1197 685 1198 684 1198 435 1198 435 1199 438 1199 685 1199 681 1200 685 1200 438 1200 438 1201 316 1201 681 1201 680 1202 681 1202 316 1202 316 1203 311 1203 680 1203 678 1204 680 1204 311 1204 311 1205 309 1205 678 1205 676 1206 678 1206 309 1206 309 1207 307 1207 676 1207 28 1208 676 1208 307 1208 307 1209 305 1209 28 1209 16 1210 434 1210 432 1210 14 1211 16 1211 432 1211 436 1212 434 1212 16 1212 16 1213 18 1213 436 1213 437 1214 436 1214 18 1214 18 1215 20 1215 437 1215 439 1216 437 1216 20 1216 20 1217 22 1217 439 1217 317 1218 439 1218 22 1218 22 1219 25 1219 317 1219 4 1220 6 1220 334 1220 426 1221 334 1221 6 1221 6 1222 8 1222 426 1222 428 1223 426 1223 8 1223 8 1224 10 1224 428 1224 429 1225 428 1225 10 1225 10 1226 12 1226 429 1226 431 1227 429 1227 12 1227 12 1228 14 1228 431 1228 432 1229 431 1229 14 1229 348 1230 344 1230 27 1230 675 1231 27 1231 344 1231 344 1232 342 1232 675 1232 677 1233 675 1233 342 1233 342 1234 340 1234 677 1234 679 1235 677 1235 340 1235 340 1236 425 1236 679 1236 682 1237 679 1237 425 1237 425 1238 427 1238 682 1238 683 1239 682 1239 427 1239 427 1240 430 1240 683 1240 683 1241 430 1241 433 1241 684 1242 683 1242 433 1242 388 1243 389 1243 390 1243 385 1244 389 1244 388 1244 385 1245 388 1245 386 1245 385 1246 386 1246 387 1246 410 1247 412 1247 411 1247 409 1248 410 1248 411 1248 408 1249 410 1249 409 1249 407 1250 408 1250 409 1250 533 1251 536 1251 537 1251 534 1252 539 1252 535 1252 534 1253 538 1253 539 1253 538 1254 625 1254 539 1254 480 1255 250 1255 27 1255 480 1256 27 1256 675 1256 478 1257 480 1257 675 1257 478 1258 675 1258 677 1258 476 1259 478 1259 677 1259 476 1260 677 1260 679 1260 474 1261 476 1261 679 1261 466 1262 474 1262 679 1262 466 1263 679 1263 682 1263 460 1264 466 1264 682 1264 460 1265 682 1265 683 1265 460 1266 683 1266 461 1266 461 1267 683 1267 684 1267 456 1268 684 1268 685 1268 451 1269 456 1269 685 1269 461 1270 686 1270 608 1270 456 1271 686 1271 684 1271 686 1272 461 1272 684 1272 596 1273 608 1273 686 1273 456 1274 596 1274 686 1274 531 1275 536 1275 533 1275 531 1276 535 1276 536 1276 451 1277 685 1277 681 1277 449 1278 451 1278 681 1278 449 1279 681 1279 680 1279 441 1280 443 1280 28 1280 443 1281 676 1281 28 1281 443 1282 445 1282 676 1282 445 1283 678 1283 676 1283 445 1284 447 1284 678 1284 447 1285 680 1285 678 1285 447 1286 449 1286 680 1286 469 1287 670 1287 475 1287 464 1288 670 1288 469 1288 464 1289 666 1289 670 1289 458 1290 666 1290 464 1290 458 1291 665 1291 666 1291 457 1292 665 1292 458 1292 457 1293 664 1293 665 1293 457 1294 630 1294 664 1294 630 1295 668 1295 664 1295 630 1296 651 1296 668 1296 450 1297 667 1297 651 1297 651 1298 667 1298 668 1298 450 1299 669 1299 667 1299 448 1300 669 1300 450 1300 448 1301 672 1301 669 1301 446 1302 672 1302 448 1302 446 1303 673 1303 672 1303 444 1304 673 1304 446 1304 442 1305 673 1305 444 1305 482 1306 483 1306 489 1306 483 1307 488 1307 489 1307 483 1308 486 1308 488 1308 484 1309 488 1309 486 1309 484 1310 487 1310 488 1310 484 1311 485 1311 487 1311 386 1312 388 1312 687 1312 388 1313 511 1313 687 1313 841 1314 766 1314 765 1314 841 1315 767 1315 766 1315 841 1316 768 1316 767 1316 841 1317 839 1317 768 1317 789 1318 687 1318 511 1318 386 1319 687 1319 906 1319 906 1320 687 1320 789 1320 380 1321 820 1321 819 1321 380 1322 821 1322 820 1322 381 1323 821 1323 380 1323 381 1324 822 1324 821 1324 381 1325 823 1325 822 1325 785 1326 783 1326 711 1326 783 1327 784 1327 711 1327 710 1328 711 1328 784 1328 784 1329 782 1329 710 1329 709 1330 710 1330 782 1330 782 1331 742 1331 709 1331 708 1332 709 1332 742 1332 742 1333 743 1333 708 1333 707 1334 708 1334 744 1334 708 1335 743 1335 744 1335 706 1336 707 1336 745 1336 707 1337 744 1337 745 1337 706 1338 745 1338 746 1338 705 1339 715 1339 716 1339 716 1340 713 1340 705 1340 704 1341 705 1341 713 1341 713 1342 714 1342 704 1342 703 1343 704 1343 714 1343 714 1344 712 1344 703 1344 702 1345 703 1345 712 1345 700 1346 702 1346 790 1346 702 1347 712 1347 790 1347 790 1348 791 1348 700 1348 701 1349 700 1349 791 1349 791 1350 792 1350 701 1350 792 1351 793 1351 701 1351 800 1352 798 1352 689 1352 798 1353 799 1353 689 1353 688 1354 689 1354 799 1354 799 1355 797 1355 688 1355 690 1356 688 1356 797 1356 797 1357 726 1357 690 1357 693 1358 690 1358 726 1358 726 1359 727 1359 693 1359 692 1360 693 1360 728 1360 693 1361 727 1361 728 1361 691 1362 692 1362 729 1362 692 1363 728 1363 729 1363 691 1364 729 1364 730 1364 695 1365 760 1365 761 1365 761 1366 758 1366 695 1366 694 1367 695 1367 758 1367 758 1368 759 1368 694 1368 696 1369 694 1369 759 1369 759 1370 757 1370 696 1370 697 1371 696 1371 757 1371 698 1372 697 1372 772 1372 697 1373 757 1373 772 1373 772 1374 773 1374 698 1374 699 1375 698 1375 773 1375 773 1376 774 1376 699 1376 774 1377 775 1377 699 1377 825 1378 823 1378 804 1378 823 1379 805 1379 804 1379 804 1380 803 1380 825 1380 827 1381 825 1381 802 1381 825 1382 803 1382 802 1382 838 1383 840 1383 741 1383 840 1384 740 1384 741 1384 840 1385 739 1385 740 1385 840 1386 738 1386 739 1386 802 1387 801 1387 827 1387 829 1388 827 1388 800 1388 827 1389 801 1389 800 1389 737 1390 738 1390 840 1390 840 1391 842 1391 737 1391 842 1392 736 1392 737 1392 842 1393 735 1393 736 1393 842 1394 734 1394 735 1394 842 1395 733 1395 734 1395 842 1396 732 1396 733 1396 688 1397 690 1397 689 1397 800 1398 689 1398 690 1398 690 1399 693 1399 800 1399 693 1400 829 1400 800 1400 831 1401 829 1401 730 1401 829 1402 691 1402 730 1402 829 1403 692 1403 691 1403 829 1404 693 1404 692 1404 731 1405 732 1405 842 1405 842 1406 844 1406 731 1406 844 1407 730 1407 731 1407 844 1408 831 1408 730 1408 833 1409 831 1409 844 1409 844 1410 846 1410 833 1410 834 1411 833 1411 846 1411 846 1412 848 1412 834 1412 836 1413 834 1413 848 1413 848 1414 850 1414 836 1414 835 1415 836 1415 850 1415 850 1416 852 1416 835 1416 832 1417 835 1417 852 1417 852 1418 854 1418 832 1418 830 1419 832 1419 854 1419 854 1420 856 1420 830 1420 828 1421 830 1421 856 1421 856 1422 858 1422 828 1422 826 1423 828 1423 858 1423 858 1424 860 1424 826 1424 824 1425 826 1425 860 1425 860 1426 863 1426 824 1426 822 1427 824 1427 863 1427 863 1428 864 1428 822 1428 821 1429 822 1429 864 1429 864 1430 862 1430 821 1430 820 1431 821 1431 862 1431 862 1432 861 1432 820 1432 818 1433 820 1433 861 1433 861 1434 859 1434 818 1434 816 1435 818 1435 859 1435 859 1436 857 1436 816 1436 814 1437 816 1437 857 1437 857 1438 855 1438 814 1438 812 1439 814 1439 855 1439 855 1440 853 1440 812 1440 810 1441 812 1441 853 1441 853 1442 851 1442 810 1442 808 1443 810 1443 851 1443 851 1444 849 1444 808 1444 806 1445 808 1445 849 1445 849 1446 847 1446 806 1446 807 1447 806 1447 847 1447 847 1448 845 1448 807 1448 809 1449 807 1449 845 1449 845 1450 843 1450 809 1450 811 1451 809 1451 843 1451 843 1452 841 1452 760 1452 760 1453 811 1453 843 1453 841 1454 762 1454 760 1454 813 1455 811 1455 696 1455 811 1456 694 1456 696 1456 811 1457 695 1457 694 1457 811 1458 760 1458 695 1458 763 1459 762 1459 841 1459 765 1460 764 1460 841 1460 764 1461 763 1461 841 1461 696 1462 697 1462 775 1462 775 1463 813 1463 696 1463 815 1464 813 1464 776 1464 813 1465 775 1465 776 1465 699 1466 775 1466 697 1466 697 1467 698 1467 699 1467 769 1468 768 1468 839 1468 839 1469 837 1469 771 1469 771 1470 770 1470 839 1470 770 1471 769 1471 839 1471 776 1472 777 1472 815 1472 817 1473 815 1473 778 1473 815 1474 777 1474 778 1474 778 1475 779 1475 817 1475 819 1476 817 1476 780 1476 817 1477 779 1477 780 1477 387 1478 910 1478 481 1478 910 1479 912 1479 481 1479 912 1480 482 1480 481 1480 796 1481 482 1481 912 1481 912 1482 914 1482 796 1482 914 1483 795 1483 796 1483 890 1484 892 1484 725 1484 725 1485 724 1485 890 1485 724 1486 723 1486 890 1486 723 1487 722 1487 890 1487 794 1488 795 1488 914 1488 914 1489 916 1489 794 1489 916 1490 793 1490 794 1490 722 1491 721 1491 890 1491 888 1492 890 1492 719 1492 719 1493 718 1493 888 1493 890 1494 720 1494 719 1494 890 1495 721 1495 720 1495 702 1496 700 1496 701 1496 701 1497 793 1497 702 1497 703 1498 702 1498 793 1498 793 1499 916 1499 703 1499 916 1500 918 1500 703 1500 918 1501 704 1501 703 1501 918 1502 705 1502 704 1502 918 1503 715 1503 705 1503 886 1504 888 1504 715 1504 715 1505 918 1505 886 1505 888 1506 717 1506 715 1506 888 1507 718 1507 717 1507 918 1508 920 1508 886 1508 884 1509 886 1509 920 1509 920 1510 921 1510 884 1510 882 1511 884 1511 921 1511 921 1512 922 1512 882 1512 880 1513 882 1513 922 1513 922 1514 923 1514 880 1514 878 1515 880 1515 923 1515 923 1516 919 1516 878 1516 876 1517 878 1517 919 1517 919 1518 917 1518 876 1518 874 1519 876 1519 917 1519 917 1520 915 1520 874 1520 872 1521 874 1521 915 1521 915 1522 913 1522 872 1522 870 1523 872 1523 913 1523 913 1524 911 1524 870 1524 868 1525 870 1525 911 1525 911 1526 909 1526 868 1526 866 1527 868 1527 909 1527 909 1528 908 1528 866 1528 865 1529 866 1529 908 1529 908 1530 907 1530 865 1530 867 1531 865 1531 907 1531 907 1532 905 1532 867 1532 869 1533 867 1533 905 1533 905 1534 903 1534 869 1534 871 1535 869 1535 903 1535 903 1536 901 1536 871 1536 873 1537 871 1537 901 1537 901 1538 899 1538 873 1538 875 1539 873 1539 899 1539 899 1540 897 1540 875 1540 877 1541 875 1541 897 1541 897 1542 895 1542 877 1542 879 1543 877 1543 895 1543 895 1544 893 1544 879 1544 881 1545 879 1545 893 1545 893 1546 894 1546 881 1546 883 1547 881 1547 894 1547 894 1548 896 1548 883 1548 885 1549 883 1549 896 1549 896 1550 898 1550 885 1550 887 1551 885 1551 747 1551 885 1552 746 1552 747 1552 885 1553 898 1553 746 1553 898 1554 900 1554 746 1554 900 1555 706 1555 746 1555 900 1556 707 1556 706 1556 900 1557 708 1557 707 1557 747 1558 748 1558 887 1558 889 1559 887 1559 753 1559 887 1560 752 1560 753 1560 887 1561 751 1561 752 1561 887 1562 750 1562 751 1562 887 1563 749 1563 750 1563 887 1564 748 1564 749 1564 709 1565 708 1565 785 1565 708 1566 900 1566 785 1566 900 1567 902 1567 785 1567 902 1568 786 1568 785 1568 785 1569 711 1569 709 1569 710 1570 709 1570 711 1570 753 1571 754 1571 889 1571 891 1572 889 1572 756 1572 889 1573 755 1573 756 1573 889 1574 754 1574 755 1574 787 1575 786 1575 902 1575 902 1576 904 1576 787 1576 904 1577 788 1577 787 1577 789 1578 788 1578 904 1578 904 1579 906 1579 789 1579 790 1580 712 1580 485 1580 562 1581 485 1581 712 1581 712 1582 714 1582 562 1582 562 1583 713 1583 716 1583 562 1584 714 1584 713 1584 569 1585 562 1585 717 1585 562 1586 715 1586 717 1586 562 1587 716 1587 715 1587 717 1588 718 1588 569 1588 566 1589 569 1589 719 1589 569 1590 718 1590 719 1590 565 1591 566 1591 720 1591 566 1592 719 1592 720 1592 720 1593 721 1593 565 1593 563 1594 565 1594 722 1594 565 1595 721 1595 722 1595 722 1596 723 1596 563 1596 407 1597 563 1597 724 1597 563 1598 723 1598 724 1598 724 1599 725 1599 407 1599 407 1600 725 1600 892 1600 201 1601 132 1601 797 1601 132 1602 726 1602 797 1602 727 1603 726 1603 132 1603 132 1604 133 1604 727 1604 133 1605 728 1605 727 1605 133 1606 729 1606 728 1606 730 1607 729 1607 133 1607 133 1608 134 1608 730 1608 134 1609 731 1609 730 1609 732 1610 731 1610 134 1610 134 1611 136 1611 732 1611 136 1612 733 1612 732 1612 734 1613 733 1613 136 1613 136 1614 135 1614 734 1614 135 1615 735 1615 734 1615 736 1616 735 1616 135 1616 135 1617 138 1617 736 1617 138 1618 737 1618 736 1618 138 1619 738 1619 737 1619 739 1620 738 1620 138 1620 138 1621 137 1621 739 1621 137 1622 740 1622 739 1622 741 1623 740 1623 137 1623 137 1624 349 1624 741 1624 838 1625 741 1625 349 1625 515 1626 541 1626 782 1626 541 1627 742 1627 782 1627 743 1628 742 1628 541 1628 541 1629 540 1629 743 1629 540 1630 744 1630 743 1630 540 1631 745 1631 744 1631 746 1632 745 1632 540 1632 540 1633 549 1633 746 1633 549 1634 747 1634 746 1634 748 1635 747 1635 549 1635 549 1636 547 1636 748 1636 547 1637 749 1637 748 1637 750 1638 749 1638 547 1638 547 1639 546 1639 750 1639 546 1640 751 1640 750 1640 752 1641 751 1641 546 1641 546 1642 543 1642 752 1642 543 1643 753 1643 752 1643 754 1644 753 1644 543 1644 543 1645 542 1645 754 1645 542 1646 755 1646 754 1646 756 1647 755 1647 542 1647 542 1648 408 1648 756 1648 891 1649 756 1649 408 1649 772 1650 757 1650 176 1650 153 1651 176 1651 757 1651 757 1652 759 1652 153 1652 155 1653 153 1653 761 1653 153 1654 758 1654 761 1654 153 1655 759 1655 758 1655 154 1656 155 1656 762 1656 155 1657 760 1657 762 1657 155 1658 761 1658 760 1658 762 1659 763 1659 154 1659 156 1660 154 1660 764 1660 154 1661 763 1661 764 1661 764 1662 765 1662 156 1662 157 1663 156 1663 766 1663 156 1664 765 1664 766 1664 766 1665 767 1665 157 1665 159 1666 157 1666 768 1666 157 1667 767 1667 768 1667 768 1668 769 1668 159 1668 158 1669 159 1669 770 1669 159 1670 769 1670 770 1670 770 1671 771 1671 158 1671 350 1672 158 1672 837 1672 158 1673 771 1673 837 1673 176 1674 177 1674 772 1674 177 1675 773 1675 772 1675 177 1676 774 1676 773 1676 177 1677 775 1677 774 1677 776 1678 775 1678 177 1678 177 1679 172 1679 776 1679 777 1680 776 1680 172 1680 172 1681 175 1681 777 1681 778 1682 777 1682 175 1682 175 1683 173 1683 778 1683 173 1684 779 1684 778 1684 780 1685 779 1685 173 1685 173 1686 174 1686 780 1686 782 1687 784 1687 515 1687 514 1688 515 1688 785 1688 515 1689 783 1689 785 1689 515 1690 784 1690 783 1690 785 1691 786 1691 514 1691 513 1692 514 1692 786 1692 786 1693 787 1693 513 1693 512 1694 513 1694 787 1694 787 1695 788 1695 512 1695 511 1696 512 1696 789 1696 512 1697 788 1697 789 1697 485 1698 484 1698 790 1698 484 1699 791 1699 790 1699 484 1700 792 1700 791 1700 484 1701 793 1701 792 1701 794 1702 793 1702 484 1702 484 1703 486 1703 794 1703 795 1704 794 1704 486 1704 486 1705 483 1705 795 1705 796 1706 795 1706 483 1706 483 1707 482 1707 796 1707 797 1708 799 1708 201 1708 200 1709 201 1709 800 1709 201 1710 798 1710 800 1710 201 1711 799 1711 798 1711 800 1712 801 1712 200 1712 199 1713 200 1713 801 1713 801 1714 802 1714 199 1714 197 1715 199 1715 802 1715 802 1716 803 1716 197 1716 196 1717 197 1717 804 1717 197 1718 803 1718 804 1718 804 1719 805 1719 196 1719 808 1720 806 1720 807 1720 807 1721 809 1721 808 1721 810 1722 808 1722 809 1722 809 1723 811 1723 810 1723 812 1724 810 1724 811 1724 811 1725 813 1725 812 1725 814 1726 812 1726 813 1726 813 1727 815 1727 814 1727 816 1728 814 1728 815 1728 815 1729 817 1729 816 1729 818 1730 816 1730 817 1730 817 1731 819 1731 818 1731 820 1732 818 1732 819 1732 824 1733 822 1733 823 1733 823 1734 825 1734 824 1734 826 1735 824 1735 825 1735 825 1736 827 1736 826 1736 828 1737 826 1737 827 1737 827 1738 829 1738 828 1738 830 1739 828 1739 829 1739 829 1740 831 1740 830 1740 832 1741 830 1741 831 1741 831 1742 833 1742 832 1742 835 1743 832 1743 833 1743 833 1744 834 1744 835 1744 836 1745 835 1745 834 1745 350 1746 837 1746 349 1746 838 1747 349 1747 837 1747 837 1748 839 1748 838 1748 840 1749 838 1749 839 1749 839 1750 841 1750 840 1750 842 1751 840 1751 841 1751 841 1752 843 1752 842 1752 844 1753 842 1753 843 1753 843 1754 845 1754 844 1754 846 1755 844 1755 845 1755 845 1756 847 1756 846 1756 848 1757 846 1757 847 1757 847 1758 849 1758 848 1758 850 1759 848 1759 849 1759 849 1760 851 1760 850 1760 852 1761 850 1761 851 1761 851 1762 853 1762 852 1762 854 1763 852 1763 853 1763 853 1764 855 1764 854 1764 856 1765 854 1765 855 1765 855 1766 857 1766 856 1766 858 1767 856 1767 857 1767 857 1768 859 1768 858 1768 860 1769 858 1769 859 1769 859 1770 861 1770 860 1770 863 1771 860 1771 861 1771 861 1772 862 1772 863 1772 864 1773 863 1773 862 1773 865 1774 867 1774 866 1774 868 1775 866 1775 867 1775 867 1776 869 1776 868 1776 870 1777 868 1777 869 1777 869 1778 871 1778 870 1778 872 1779 870 1779 871 1779 871 1780 873 1780 872 1780 874 1781 872 1781 873 1781 873 1782 875 1782 874 1782 876 1783 874 1783 875 1783 875 1784 877 1784 876 1784 878 1785 876 1785 877 1785 877 1786 879 1786 878 1786 880 1787 878 1787 879 1787 879 1788 881 1788 880 1788 882 1789 880 1789 881 1789 881 1790 883 1790 882 1790 884 1791 882 1791 883 1791 883 1792 885 1792 884 1792 886 1793 884 1793 885 1793 885 1794 887 1794 886 1794 888 1795 886 1795 887 1795 887 1796 889 1796 888 1796 890 1797 888 1797 889 1797 889 1798 891 1798 890 1798 892 1799 890 1799 891 1799 891 1800 408 1800 892 1800 407 1801 892 1801 408 1801 893 1802 895 1802 894 1802 896 1803 894 1803 895 1803 895 1804 897 1804 896 1804 898 1805 896 1805 897 1805 897 1806 899 1806 898 1806 900 1807 898 1807 899 1807 899 1808 901 1808 900 1808 902 1809 900 1809 901 1809 901 1810 903 1810 902 1810 904 1811 902 1811 903 1811 903 1812 905 1812 904 1812 906 1813 904 1813 905 1813 905 1814 907 1814 906 1814 386 1815 906 1815 907 1815 907 1816 908 1816 386 1816 386 1817 908 1817 387 1817 908 1818 909 1818 387 1818 910 1819 387 1819 909 1819 909 1820 911 1820 910 1820 912 1821 910 1821 911 1821 911 1822 913 1822 912 1822 914 1823 912 1823 913 1823 913 1824 915 1824 914 1824 916 1825 914 1825 915 1825 915 1826 917 1826 916 1826 918 1827 916 1827 917 1827 917 1828 919 1828 918 1828 920 1829 918 1829 919 1829 919 1830 923 1830 920 1830 921 1831 920 1831 923 1831 923 1832 922 1832 921 1832 823 1833 381 1833 924 1833 924 1834 805 1834 823 1834 780 1835 781 1835 819 1835 380 1836 819 1836 781 1836 781 1837 780 1837 174 1837 174 1838 380 1838 781 1838 198 1839 196 1839 805 1839 805 1840 924 1840 198 1840 198 1841 924 1841 381 1841

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/wrist/wrist_E2M3.dae b/URDFs/sr_description/meshes/components/wrist/wrist_E2M3.dae new file mode 100644 index 0000000..5f1f221 --- /dev/null +++ b/URDFs/sr_description/meshes/components/wrist/wrist_E2M3.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:55.555034 + 2012-07-23T02:14:55.555052 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -12.60386 -0.00040 -4.55191 -0.54290 13.89959 -4.46761 0.54193 13.89959 -4.46761 -1.59620 13.89959 -4.20799 1.59524 13.89959 -4.20799 -2.55677 13.89959 -3.70385 2.55581 13.89959 -3.70385 -3.36878 13.89959 -2.98447 3.36782 13.89959 -2.98447 -3.98503 13.89959 -2.09167 3.98407 13.89959 -2.09167 -4.36972 13.89959 -1.07734 4.36876 13.89959 -1.07734 -4.50048 13.89959 -0.00042 4.49952 13.89959 -0.00042 -4.36972 13.89959 1.07650 4.36876 13.89959 1.07650 -3.98503 13.89959 2.09083 3.98407 13.89959 2.09083 -3.36878 13.89959 2.98363 3.36782 13.89959 2.98363 -2.55677 13.89959 3.70301 2.55581 13.89959 3.70301 -1.59621 13.89959 4.20715 -0.54290 13.89959 4.46677 1.59524 13.89959 4.20715 0.54193 13.89959 4.46677 2.31715 10.59960 -7.13334 2.31714 10.59959 7.13250 0.78348 10.59960 -7.45934 0.78348 10.59959 7.45849 -0.78445 10.59960 -7.45934 -0.78445 10.59959 7.45849 -2.31811 10.59960 -7.13334 -2.31811 10.59959 7.13250 -3.75048 10.59960 -6.49561 -3.75048 10.59959 6.49477 -5.01896 10.59959 5.57317 -5.01896 10.59960 -5.57401 -6.06811 10.59960 -4.40881 -6.06811 10.59959 4.40797 -6.85207 10.59960 -3.05095 -6.85207 10.59960 3.05010 -7.33659 10.59960 1.55892 -7.33659 10.59960 -1.55976 -7.50048 10.59960 -0.00042 -7.33659 -10.60041 1.55892 -7.50049 -10.60041 -0.00042 -7.33659 -10.60041 -1.55976 -6.85208 -10.60040 -3.05095 -6.85208 -10.60041 3.05010 -6.06812 -10.60041 4.40797 -6.06811 -10.60041 -4.40881 -5.01897 -10.60041 -5.57401 -5.01897 -10.60041 5.57317 -3.75049 -10.60041 6.49477 -3.75048 -10.60041 -6.49561 -2.31811 -10.60041 7.13250 -2.31811 -10.60041 -7.13334 -0.78445 -10.60041 7.45849 -0.78445 -10.60041 -7.45934 0.78348 -10.60041 7.45849 0.78348 -10.60041 -7.45934 2.31714 -10.60041 7.13250 2.31714 -10.60041 -7.13334 -14.48772 7.22568 1.21112 -13.95641 7.52509 0.93113 -14.19300 7.34965 1.09963 -13.90642 5.60705 -0.55767 -13.79636 3.38683 -1.54026 -13.62562 5.80287 -0.82700 -13.37415 3.55958 -2.00872 -13.63172 7.84658 0.62766 -13.42834 6.02566 -1.14744 -13.47899 8.13542 0.34559 -13.59057 1.00859 -2.05556 -13.29065 0.99960 -2.43023 -13.81941 -3.37846 -1.52380 -14.03224 -5.53306 -0.46171 -13.55213 -0.99182 -2.09744 -13.25895 -1.00324 -2.49002 -13.38795 -3.54875 -1.98317 -13.58612 -5.82680 -0.86263 -14.26401 -7.32159 1.13379 -13.91214 -7.54561 0.91654 -13.62985 -7.86254 0.60894 -13.45037 -8.20210 0.28867 -13.43177 -8.35835 0.13871 -13.33815 -8.96163 6.94725 -14.02152 -9.25673 4.06271 -12.62189 -7.88431 7.72702 -13.68860 -9.47942 5.55454 -12.17220 -7.98916 7.62231 -12.79561 -9.12583 6.73785 -13.52762 -9.55666 3.80315 -13.12857 -9.80029 5.34117 -11.80590 -8.10198 7.60052 -12.36982 -9.38179 6.66783 -11.38435 -8.27721 7.68078 -12.05107 -9.64642 6.67054 -13.18897 -10.02901 3.50122 -12.65820 -10.25672 5.20334 -12.34419 -10.50040 5.65164 -13.10623 -10.46706 3.30983 -10.99744 -8.47381 7.83888 -11.76268 -9.96988 6.73570 -12.25473 -6.40498 7.99782 -11.72898 -6.40560 7.93281 -11.17216 -6.40683 8.02417 -10.64307 -6.40915 8.28321 -14.26038 9.15721 4.16294 -12.29217 6.40601 8.00338 -13.74552 9.47000 5.58112 -12.55224 7.89330 7.70474 -13.03981 9.03588 6.82450 -13.85801 9.33975 3.98340 -13.33376 9.66441 5.42183 -12.56829 9.24682 6.69359 -13.50539 9.60548 3.77503 -11.92678 8.05235 7.58945 -13.02474 9.90194 5.30744 -11.80182 6.40682 7.93720 -12.21385 9.49928 6.66542 -13.26845 9.92961 3.56703 -11.13580 6.40570 8.03591 -13.11173 10.18750 3.41007 -11.28393 8.31322 7.69886 -10.73077 6.40590 8.22361 -12.64398 10.38079 5.24346 -11.84269 9.83655 6.69265 -12.47477 10.49960 5.26739 -10.75736 8.63854 8.05253 -24.88471 -9.35137 23.00377 -24.13114 -9.40305 23.00179 -23.38857 -9.26547 23.01383 -22.12126 -8.46693 23.01970 -22.70383 -8.94547 23.00735 -21.39638 -7.15635 23.02859 -21.67562 -7.85566 23.01203 -23.87215 -9.40192 20.17845 -23.19525 -9.38724 17.47330 -21.99669 -8.94589 18.29033 -20.99868 -7.85505 18.54457 -21.94929 -9.39938 14.24081 -20.17987 -8.94589 13.92521 -19.26540 -7.85505 14.39999 -19.93711 -9.40192 10.96064 -17.36017 -8.94589 10.12988 -16.57709 -7.85505 10.80070 -17.34748 -9.40192 8.11977 -13.71346 -8.96542 7.08199 -13.04990 -7.81858 7.94862 -14.23772 -9.38277 5.85688 -24.88455 9.34945 22.99273 -23.38881 9.26415 22.99850 -24.13438 9.40093 22.94129 -22.70510 8.94655 22.96461 -22.12062 8.46669 23.00962 -21.39598 7.15553 23.02449 -21.67454 7.85688 22.98570 -21.99899 8.94669 18.28904 -21.00004 7.85689 18.54399 -23.36385 9.40128 17.86201 -20.18188 8.94669 13.92356 -19.26665 7.85689 14.39923 -21.37263 9.40128 13.12622 -17.36185 8.94669 10.12793 -16.57822 7.85689 10.79978 -13.63308 8.92521 7.04131 -18.28204 9.40128 9.02243 -12.95601 7.82493 7.86842 -14.24571 9.39143 5.82465 -28.29540 7.12390 23.04268 -30.07768 4.28939 23.02099 -30.54342 2.67371 23.01016 -29.31952 5.79025 23.03187 -25.59235 9.09639 23.03309 -27.04103 8.24381 23.05341 -25.28474 9.10898 19.71424 -27.61936 7.12429 17.71068 -29.29788 4.28653 17.06409 -24.50582 9.10898 16.57668 -23.27924 9.10898 13.58126 -25.81796 7.12429 12.64688 -27.20717 4.28652 11.43173 -21.63284 9.10898 10.79699 -22.97470 7.12429 8.08584 -23.91240 4.28652 6.40789 -19.60074 9.10898 8.28056 -14.54596 9.10868 4.25243 -17.22583 9.10898 6.08501 -19.22128 7.12429 4.23888 -14.43425 5.40799 -0.30267 -14.73110 7.12708 1.28862 -19.57969 4.28652 2.24588 -14.20562 3.28901 -1.33376 -30.07768 -4.29019 23.02099 -29.31952 -5.79105 23.03187 -30.54342 -2.67451 23.01016 -28.29363 -7.12628 23.04270 -27.04103 -8.24461 23.05341 -25.60065 -9.11085 23.01348 -25.46428 -9.10979 20.96733 -25.15497 -9.10979 19.02628 -24.67524 -9.10978 17.11820 -27.61719 -7.12757 17.71145 -29.29673 -4.29047 17.06458 -25.81612 -7.12757 12.64832 -23.24655 -9.10978 13.51576 -27.20625 -4.29047 11.43263 -21.96199 -9.10978 11.28491 -20.42908 -9.10979 9.21762 -22.97337 -7.12757 8.08786 -23.91183 -4.29047 6.40911 -18.66796 -9.10979 7.34085 -16.70228 -9.10979 5.67980 -14.44149 -9.10329 4.22508 -19.22062 -7.12757 4.24131 -14.62641 -7.17487 1.26451 -14.47512 -5.33858 -0.21095 -19.57957 -4.29047 2.24733 -14.24722 -3.28159 -1.25828 -13.08897 10.47856 3.10286 -13.40044 10.49960 0.03300 -13.40676 8.41941 0.07982 -13.40044 -10.50040 0.03300 -13.32003 -6.17464 -1.36950 -13.32796 6.25340 -1.48803 -13.20270 10.49960 -2.29430 -13.09723 3.74191 -2.54411 -13.05894 0.99960 -3.00666 -13.09158 -1.00050 -2.92509 -13.19020 -3.70530 -2.44498 -13.20271 -10.50040 -2.29430 -12.60386 10.49960 -4.55191 -12.60386 -10.50040 -4.55191 -11.62209 10.49960 -6.67124 -11.62209 -10.50040 -6.67124 -10.28724 10.49960 -8.58790 -10.28724 -10.50040 -8.58790 -8.63985 10.49960 -10.24366 -8.63985 -10.50040 -10.24366 -6.72998 10.49960 -11.58821 -6.72998 -10.50040 -11.58821 -4.61565 10.49959 -12.58070 -4.61565 -10.50041 -12.58070 -2.36111 10.49959 -13.19098 -2.36110 -10.50041 -13.19098 -0.03484 10.49959 -13.40051 -0.03483 -10.50041 -13.40051 2.29247 10.49959 -13.20291 2.29248 -10.50041 -13.20291 2.15348 10.49959 13.22520 2.15348 -10.50041 13.22520 -0.07688 10.49959 13.39923 -0.07689 -10.50041 13.39923 -2.30523 10.49959 13.19976 -2.30524 -10.50041 13.19976 -4.46929 10.49959 12.63234 -4.46930 -10.50041 12.63233 -6.50868 10.49959 11.71284 -6.50869 -10.50041 11.71283 -8.36659 10.49959 10.46694 -8.36661 -10.50041 10.46692 -11.33783 10.49960 7.14268 -10.58126 8.76704 8.21934 -9.99129 10.49960 8.92939 -11.34845 -10.49318 7.12164 -10.66137 -8.70710 8.12063 -10.28659 -6.40669 8.60038 -10.25925 6.40596 8.62536 -9.99131 -10.50040 8.92937 -0.00049 -15.40040 -7.50042 1.46269 -15.40040 -7.35631 -1.46366 -15.40040 -7.35631 2.86964 -15.40040 -6.92952 -2.87061 -15.40040 -6.92952 4.16629 -15.40041 -6.23644 -4.16726 -15.40040 -6.23644 5.30282 -15.40041 -5.30372 -5.30379 -15.40040 -5.30372 6.23554 -15.40041 -4.16720 -6.23651 -15.40040 -4.16720 6.92861 -15.40041 -2.87055 -6.92958 -15.40040 -2.87055 7.35540 -15.40041 -1.46360 -7.35638 -15.40040 -1.46360 7.49951 -15.40041 -0.00042 -7.50049 -15.40040 -0.00042 7.35540 -15.40041 1.46276 -7.35638 -15.40040 1.46276 6.92861 -15.40041 2.86971 -6.92958 -15.40040 2.86971 6.23553 -15.40041 4.16636 -6.23651 -15.40041 4.16636 5.30281 -15.40041 5.30288 -5.30379 -15.40041 5.30288 4.16629 -15.40041 6.23560 -4.16727 -15.40041 6.23560 2.86964 -15.40041 6.92868 -2.87061 -15.40041 6.92868 -1.46367 -15.40041 7.35547 -0.00049 -15.40041 7.49958 1.46269 -15.40041 7.35547 -0.00048 15.39959 7.49958 1.46269 15.39959 7.35547 -1.46366 15.39959 7.35547 2.86964 15.39959 6.92868 -2.87061 15.39959 6.92868 4.16629 15.39959 6.23560 -4.16726 15.39959 6.23560 5.30282 15.39959 5.30288 -0.00048 15.39959 4.49958 -5.30378 15.39959 5.30288 1.00086 15.39959 4.38676 -1.00183 15.39959 4.38676 6.23554 15.39959 4.16636 1.95199 15.39959 4.05394 -1.95296 15.39959 4.05394 -6.23651 15.39959 4.16636 -2.80619 15.39959 3.51782 -3.51872 15.39959 2.80528 -6.92958 15.39959 2.86971 -4.05484 15.39959 1.95206 -4.38766 15.39959 1.00093 -7.35637 15.39959 1.46276 -4.50048 15.39959 -0.00042 -7.50048 15.39959 -0.00042 -4.38766 15.39959 -1.00176 -4.05484 15.39959 -1.95290 -7.35637 15.39959 -1.46360 -3.51872 15.39959 -2.80612 -2.80619 15.39959 -3.51866 -6.92958 15.39960 -2.87055 1.95200 15.39959 -4.05478 -1.95296 15.39959 -4.05478 1.00086 15.39959 -4.38760 -0.00048 15.39959 -4.50042 -1.00182 15.39959 -4.38760 -6.23650 15.39959 -4.16720 5.30282 15.39959 -5.30372 -5.30378 15.39959 -5.30372 4.16630 15.39959 -6.23644 -4.16726 15.39959 -6.23644 2.86965 15.39959 -6.92952 -2.87061 15.39959 -6.92952 -1.46366 15.39959 -7.35631 -0.00048 15.39959 -7.50042 1.46270 15.39959 -7.35631 -21.30162 -6.40750 23.03941 -21.30144 6.40653 23.02324 -21.05293 -6.40666 20.48503 -21.05293 6.40585 20.48503 -20.45402 -6.40666 18.02602 -20.45402 6.40585 18.02602 -19.51434 -6.40666 15.67261 -19.51434 6.40585 15.67261 -18.25390 -6.40666 13.47585 -18.25390 6.40585 13.47586 -16.69758 -6.40666 11.47834 -16.69758 6.40585 11.47835 -14.87602 -6.40666 9.71929 -12.82573 -6.40666 8.23382 -14.87602 6.40585 9.71929 -12.82573 6.40585 8.23383 -30.41643 -1.00040 19.53470 -29.69563 0.99960 16.13403 -28.54962 0.99960 12.85194 -26.99694 0.99960 9.74162 -26.99669 -1.00040 9.74117 -25.06267 0.99960 6.85320 -25.06223 -1.00040 6.85262 -22.77773 0.99960 4.23294 -22.77734 -1.00040 4.23257 -20.17892 0.99960 1.92327 -20.17875 -1.00040 1.92313 -17.30873 0.99960 -0.03817 -14.21282 0.99960 -1.62019 -17.30859 -1.00040 -0.03825 -14.21282 -1.00040 -1.62019 -30.69927 0.99943 23.04174 -30.70291 -1.00075 23.02165 -30.41645 0.99960 19.53490 -29.69556 -1.00040 16.13377 -28.54948 -1.00040 12.85162 35.56442 -1.00041 18.82635 35.89960 1.00018 23.02512 35.89865 -1.00030 23.04285 35.60408 0.99999 18.94442 34.68587 -1.00041 14.73265 34.68535 0.99959 14.73082 33.27864 -1.00041 10.78832 33.27790 0.99959 10.78664 31.36698 -1.00041 7.06207 31.36615 0.99959 7.06070 28.98425 -1.00041 3.61868 28.98302 0.99959 3.61714 26.17130 -1.00041 0.51695 26.16953 0.99959 0.51526 22.97604 -1.00041 -2.19013 22.97423 0.99959 -2.19147 19.45300 -1.00041 -4.45602 19.45189 0.99959 -4.45665 15.66376 -1.00041 -6.24092 15.66357 0.99959 -6.24101 11.64083 -0.99333 -7.51363 11.67386 0.99959 -7.51412 26.49701 -6.40790 23.00487 26.50031 6.40680 23.03065 26.24158 -6.40714 20.03259 26.24143 6.40632 20.03162 25.59420 -6.40714 17.12513 25.59365 6.40632 17.12325 24.56920 -6.40714 14.32965 24.56801 6.40632 14.32697 23.18434 -6.40714 11.69390 23.18226 6.40632 11.69051 21.45901 -6.40714 9.25799 21.45568 6.40632 9.25390 19.44430 -6.40714 7.08838 19.44081 6.40632 7.08509 17.34859 -6.40714 5.33769 17.34648 6.40632 5.33613 15.28735 6.40805 3.98648 15.28216 -6.40734 3.98093 6.23554 15.39959 -4.16720 2.80522 15.39959 -3.51866 6.92861 15.39959 -2.87055 3.51776 15.39959 -2.80612 4.05388 15.39959 -1.95290 7.35541 15.39959 -1.46360 4.38669 15.39959 -1.00176 4.49952 15.39959 -0.00042 7.49952 15.39959 -0.00042 4.38669 15.39959 1.00093 7.35541 15.39959 1.46276 4.05388 15.39959 1.95206 3.51776 15.39959 2.80528 6.92861 15.39959 2.86971 2.80522 15.39959 3.51782 4.32370 -10.50041 12.68256 4.32371 10.49959 12.68256 6.37333 -10.50041 11.78650 6.37333 10.49959 11.78649 8.24526 -10.50041 10.56201 8.24527 10.49959 10.56200 9.88738 -10.50041 9.04324 9.88738 10.49959 9.04324 11.25394 -10.50041 7.27254 11.25394 10.49959 7.27254 12.30691 -10.50041 5.29925 12.30692 10.49959 5.29925 12.48335 -6.40739 4.90258 12.71416 -9.07247 4.22862 12.43964 6.40632 4.97975 12.68775 9.13363 4.25919 13.25704 10.50525 2.32517 13.18964 -10.50041 -2.36255 12.57940 -10.50041 -4.61647 12.89855 -9.67272 -3.62335 12.57939 10.49959 -4.61647 13.18965 10.49959 -2.36255 12.88448 9.63719 -3.66647 12.21337 7.94797 -5.50560 11.58678 -10.50041 -6.73074 12.21218 -7.94114 -5.51293 11.58677 10.49959 -6.73074 11.51189 -6.06881 -6.85762 11.51664 6.08266 -6.85008 10.24212 -10.50041 -8.64053 10.67074 0.99921 -8.11293 10.66506 -1.00030 -8.11141 10.83492 -3.55577 -7.89054 10.88949 3.53806 -7.81976 10.24211 10.49959 -8.64054 8.58626 -10.50041 -10.28782 8.58625 10.49959 -10.28783 6.66952 -10.50041 -11.62256 6.66951 10.49959 -11.62256 4.55013 -10.50041 -12.60420 4.55012 10.49959 -12.60420 35.67098 -2.91176 23.41162 35.10701 -4.69323 24.05084 34.51861 -5.79096 22.99116 32.24020 -8.24452 23.00877 30.79715 -9.11441 22.99093 33.49187 -7.12698 22.99789 30.45738 -9.11051 19.15825 32.79480 -7.12707 17.06920 34.46150 -4.29016 16.35134 29.44318 -9.13203 15.42730 30.91869 -7.12707 11.40214 32.25470 -4.29016 10.03840 27.71212 -9.11051 10.95918 27.94042 -7.12707 6.22863 26.26256 -9.11051 8.52879 28.75688 -4.29016 4.33854 24.56230 -9.11051 6.26149 22.66412 -9.11051 4.21714 23.98184 -7.12707 1.76040 24.12780 -4.29015 -0.48793 20.67170 -9.11051 2.46631 18.69316 -9.11050 1.03600 19.20498 -7.12707 -1.81966 16.78089 -9.11050 -0.10730 18.57887 -4.29015 -4.22057 14.85429 -9.11536 -1.01545 14.19183 -8.09903 -3.02073 13.46651 -6.75450 -4.84491 11.88470 -3.19872 -7.20780 12.61154 -4.96985 -6.29130 35.27751 4.28659 23.01634 34.51856 5.79020 23.02481 33.49437 7.12394 23.03323 32.24012 8.24375 23.04163 30.79967 9.11036 23.00775 32.80304 7.12410 17.09722 30.54383 9.10968 19.72866 34.46772 4.28640 16.37301 29.90321 9.10968 16.56613 30.92986 7.12410 11.42224 28.88781 9.10968 13.50447 32.26332 4.28640 10.05390 27.51255 9.10968 10.58758 27.95177 7.12410 6.24101 25.79234 9.10968 7.85021 28.76567 4.28640 4.34804 23.75453 9.10968 5.33895 23.99086 7.12410 1.76602 21.51544 9.10968 3.16539 24.13470 4.28640 -0.48361 19.20959 7.12411 -1.81921 19.24568 9.10968 1.40820 17.04753 9.10969 0.03941 18.58228 4.28640 -4.22007 13.79232 7.10996 -4.35238 14.33083 8.00472 -3.01229 14.93884 9.10969 -1.01760 11.98112 3.17161 -7.16036 12.80422 5.00471 -6.27410 29.33309 9.40134 22.94975 30.08383 9.35425 22.99638 26.59515 7.15561 23.01965 26.87466 7.85676 23.00244 26.29238 7.85724 18.31521 27.27739 8.94702 18.00122 27.31973 8.46639 23.00948 27.90369 8.94572 22.99972 28.63104 9.40172 17.51563 28.58735 9.26455 23.00108 24.77109 7.85724 13.86825 25.63348 8.94702 13.27911 26.77773 9.40172 12.35932 22.37364 7.85724 9.82570 23.04388 8.94702 9.00187 23.85976 9.40172 7.72165 19.20110 7.85724 6.35800 19.62173 8.94702 5.35638 20.01346 9.40172 3.81929 15.35070 7.89198 3.53765 15.50805 9.08422 2.16505 15.18956 9.39706 0.20453 29.33042 -9.40730 22.97453 26.87267 -7.85526 22.99909 26.29455 -7.85542 18.33118 27.31945 -8.46778 23.01072 27.90180 -8.94608 22.98559 27.27926 -8.94623 18.02046 28.13668 -9.43483 15.71140 28.58736 -9.26600 22.99869 24.77486 -7.85542 13.87991 25.63741 -8.94623 13.29348 25.54921 -9.40238 10.13518 22.37741 -7.85541 9.83324 23.04801 -8.94623 9.01154 22.76218 -9.40238 6.43190 19.20344 -7.85541 6.36204 19.62439 -8.94623 5.36206 19.34743 -9.40238 3.29801 15.38655 -7.90337 3.56958 15.48328 -9.08043 2.17480 15.21953 -9.38465 0.20242 12.71159 -6.40639 4.50438 12.74383 6.40694 4.46699 13.11625 -6.40706 4.10916 13.17147 6.40534 4.06695 13.67181 -6.40729 3.82388 13.63432 6.40488 3.83865 14.16679 -6.40621 3.72869 14.16567 6.40517 3.73141 14.74828 -6.40559 3.77486 14.78990 6.40795 3.78526 12.58938 6.40624 4.72038 12.84993 8.84319 3.96175 13.47079 10.08159 2.14671 13.19677 8.55461 3.61157 13.69240 10.33885 0.10007 13.57160 8.34648 3.40352 13.86713 9.62944 2.02199 13.98212 8.18787 3.28635 14.07981 9.87364 0.14741 14.31560 9.33661 1.97631 14.40984 8.07622 3.25155 14.50780 6.40489 3.75358 14.52968 9.59005 0.18204 14.90134 9.13856 1.99861 14.85833 8.01625 3.30744 14.85845 9.46198 0.19548 13.48269 10.32783 -1.34628 13.95208 9.60692 -1.10757 14.66569 9.18686 -1.01369 12.93925 9.41483 -3.53728 12.36359 7.69195 -5.23325 13.11882 9.01344 -3.32705 13.65545 9.95317 -1.21632 11.60970 5.81624 -6.70498 12.71295 7.44038 -4.91488 13.41292 8.65007 -3.17383 11.93168 5.52365 -6.44411 10.94455 0.99738 -7.87140 11.28216 3.39613 -7.43880 13.14305 7.23847 -4.66389 13.77247 8.35124 -3.08141 14.29804 9.36786 -1.04865 12.31590 5.27040 -6.28185 11.73384 3.19752 -7.16874 11.35846 0.99781 -7.62773 14.18860 8.09826 -3.03375 10.90901 -0.99577 -7.89165 11.23977 -0.99918 -7.68268 13.55432 -10.50586 -0.44094 12.95099 -9.37372 -3.50425 12.34374 -7.74751 -5.26691 13.12794 -9.02062 -3.32480 11.63522 -5.80562 -6.68770 12.61567 -7.37134 -5.02173 13.92358 -9.63900 -1.11594 13.37768 -8.69748 -3.18544 11.02792 -3.52860 -7.64708 11.90387 -5.55691 -6.46360 14.30893 -9.34458 -1.04496 13.69316 -8.41773 -3.09304 11.37410 -3.36257 -7.37211 13.06867 -6.99306 -4.85521 12.23053 -5.32839 -6.30559 13.73215 -10.26075 0.11352 13.65034 -9.95749 -1.21899 14.04955 -9.92929 0.15063 14.42913 -9.63355 0.17846 14.87790 -9.45857 0.19826 12.84600 -8.85458 3.98163 13.32162 -10.49276 2.06913 13.08870 -8.63163 3.70309 12.92298 -6.40751 4.29738 13.47838 -10.08774 2.15254 13.44063 -8.41393 3.46980 13.38458 -6.40547 3.96435 13.77817 -9.70742 2.04130 13.80434 -8.24599 3.32269 14.08722 -9.47522 1.99617 14.36399 -8.07932 3.24406 14.45476 -9.27130 1.97544 14.96485 -9.12934 2.00828 14.97332 -8.00720 3.33362 7.49951 -10.60041 -0.00042 7.33562 -10.60041 -1.55976 6.85111 -10.60041 -3.05095 6.85110 -10.60041 3.05010 7.33562 -10.60041 1.55892 6.06714 -10.60041 4.40797 6.06714 -10.60041 -4.40881 5.01799 -10.60041 -5.57401 5.01799 -10.60041 5.57317 3.74951 -10.60041 6.49477 3.74952 -10.60041 -6.49561 3.74952 10.59959 -6.49561 3.74952 10.59959 6.49477 5.01800 10.59959 -5.57401 5.01800 10.59959 5.57317 6.06715 10.59959 -4.40881 6.06714 10.59959 4.40797 6.85111 10.59959 3.05010 6.85111 10.59959 -3.05095 7.33562 10.59959 -1.55976 7.49952 10.59959 -0.00042 7.33562 10.59959 1.55892 13.44627 10.50242 -0.01869 35.69546 3.05739 23.43314 -25.69792 -8.06854 26.52259 -26.35478 -8.04488 26.51994 -25.26371 -8.17598 26.64023 -24.16000 -9.02968 27.71689 -24.45500 -8.67075 27.23014 -24.83796 -8.37893 26.87214 -24.45243 8.67238 27.23327 -24.16008 9.02875 27.71671 -24.83342 8.38089 26.87540 -25.25692 8.17761 26.64293 -25.69196 8.06858 26.52351 -26.35262 8.04343 26.51944 30.89098 -8.06940 26.52353 31.55164 -8.04425 26.51945 30.45594 -8.17842 26.64295 30.03244 -8.38171 26.87541 29.65145 -8.67320 27.23329 29.35909 -9.02957 27.71672 29.35902 9.02887 27.71690 29.65402 8.66993 27.23016 30.03698 8.37811 26.87215 30.46273 8.17516 26.64024 30.89694 8.06772 26.52260 31.55380 8.04406 26.51995 30.30964 -9.28881 26.71105 29.51329 -9.40195 27.42233 29.85156 -9.38048 27.02176 29.21206 -9.39401 28.27592 29.30267 -9.39645 27.86289 28.81621 -9.33038 28.16568 28.36078 -9.18566 27.93929 27.89046 -8.94547 27.58514 27.52685 -8.66804 27.22668 27.16869 -8.30602 26.77394 26.87688 -7.86445 26.30823 26.71915 -7.53458 25.98483 26.60021 -7.17856 25.66446 26.52537 -6.80088 25.35357 -25.11475 -9.28649 26.70846 -24.73201 -9.37661 26.95330 -24.45204 -9.39816 27.23272 -24.18235 -9.39973 27.66239 -24.01589 -9.38310 28.21809 -23.61292 -9.32953 28.16398 -23.27349 -9.22654 28.00972 -22.92326 -9.07597 27.77525 -22.57237 -8.86007 27.47989 -22.32934 -8.66934 27.22835 -22.09323 -8.43956 26.94403 -21.87564 -8.17419 26.63824 -21.68406 -7.87555 26.31960 -21.52446 -7.54521 25.99483 -21.40323 -7.18620 25.67105 -21.32681 -6.80432 25.35626 30.31377 9.28566 26.70846 29.93103 9.37579 26.95331 29.65106 9.39735 27.23273 29.38137 9.39891 27.66240 29.21495 9.38221 28.21792 28.80724 9.32764 28.16212 28.46433 9.22273 28.00512 28.10902 9.06841 27.76509 27.75194 8.84543 27.46115 27.50480 8.64778 27.20188 27.26728 8.41127 26.91131 27.05169 8.14141 26.60291 26.86490 7.84184 26.28602 26.64308 7.35032 25.80266 26.52453 6.79367 25.34855 -25.11072 9.28798 26.71104 -24.31433 9.40116 27.42237 -24.65256 9.37968 27.02179 -24.01304 9.39320 28.27591 -24.10299 9.39558 27.86508 -23.61179 9.32847 28.16351 -23.15257 9.18113 27.93344 -22.80202 9.00596 27.68408 -22.55539 8.84721 27.46354 -22.30408 8.64627 27.19994 -22.06303 8.40544 26.90438 -21.84580 8.13166 26.59218 -21.57421 7.67631 26.10763 -21.39569 7.15675 25.64643 -21.32504 6.79000 25.34565 -25.60049 9.11070 26.53998 -26.06235 8.87196 26.50053 -26.53616 8.59014 26.57264 -26.98871 8.28209 26.76077 -27.93840 7.48716 25.94127 -28.70745 6.64783 25.23596 -29.35557 5.73244 24.61157 -29.90789 4.69264 24.05094 -30.33595 3.53512 23.58323 -30.60797 2.28678 23.23998 30.79951 9.11069 26.53999 31.73488 8.59032 26.57257 31.26123 8.87203 26.50054 32.18773 8.28208 26.76079 33.13742 7.48715 25.94128 33.90647 6.64782 25.23597 34.55459 5.73243 24.61159 35.10691 4.69263 24.05095 30.79951 -9.11152 26.54000 31.26137 -8.87278 26.50054 31.73518 -8.59096 26.57266 32.18773 -8.28291 26.76079 33.13676 -7.48862 25.94187 33.90627 -6.64890 25.23616 34.55468 -5.73310 24.61150 -25.60049 -9.11151 26.53998 -26.53586 -8.59113 26.57256 -26.06221 -8.87285 26.50052 -26.98871 -8.28290 26.76077 -27.93774 -7.48861 25.94185 -28.70725 -6.64889 25.23615 -29.35566 -5.73309 24.61148 -29.90799 -4.69322 24.05083 -30.33597 -3.53584 23.58320 -30.70049 10.98821 34.50007 -30.70049 10.88394 32.40859 -30.70049 10.69424 36.57342 -30.70049 10.38520 30.37476 -30.70050 10.01268 38.55349 -30.70049 9.51008 28.47230 -30.70050 8.96824 40.36852 -30.70049 8.29029 26.77015 -30.70050 7.59876 41.95273 -30.70049 6.77003 25.33001 -30.70050 5.95388 43.24871 -30.70049 5.00440 24.20407 -30.70050 4.09320 44.20949 -30.70049 3.05740 23.43312 -30.70050 2.08417 44.80024 -30.70050 -0.00040 44.99957 -30.70050 -2.08498 44.80024 -30.70049 -3.05820 23.43312 -30.70050 -4.09401 44.20949 -30.70049 -5.00521 24.20407 -30.70050 -5.95468 43.24871 -30.70049 -6.77083 25.33001 -30.70050 -7.59957 41.95274 -30.70049 -8.29109 26.77015 -30.70050 -8.96904 40.36852 -30.70049 -9.51088 28.47230 -30.70050 -10.01348 38.55350 -30.70049 -10.38600 30.37476 -30.70049 -10.88474 32.40859 -30.70049 -10.69504 36.57343 -30.70049 -10.98901 34.50008 -21.30049 6.40700 25.05836 -21.30049 -6.40781 25.05836 -21.30049 7.95500 26.40277 -21.30049 -7.95582 26.40277 -21.30049 9.22661 28.01107 -21.30049 -9.22742 28.01107 -21.30049 10.17766 29.82740 -21.30049 -10.17846 29.82740 -21.30049 10.77512 31.78865 -21.30049 -10.77592 31.78866 -21.30049 10.99824 33.82669 -21.30049 -10.99904 33.82669 -21.30049 10.83929 35.87072 -21.30049 -10.84009 35.87072 -21.30049 10.30379 37.84973 -21.30049 -10.30459 37.84973 -21.30049 9.41035 39.69498 -21.30049 -9.41116 39.69498 -21.30049 8.19002 41.34239 -21.30049 -8.19083 41.34239 -21.30049 6.68519 42.73472 -21.30049 -6.68600 42.73473 -21.30049 4.94813 43.82362 -21.30049 -4.94894 43.82363 -21.30050 3.03919 44.57127 -21.30050 1.02466 44.95171 -21.30050 -3.04000 44.57127 -21.30050 -1.02547 44.95171 26.49950 1.02465 44.95172 26.49950 -1.02548 44.95172 26.49950 3.03918 44.57128 26.49950 -3.04001 44.57129 26.49951 4.94812 43.82364 26.49951 -4.94895 43.82364 26.49951 6.68518 42.73473 26.49951 -6.68601 42.73474 26.49951 8.19001 41.34240 26.49951 -8.19084 41.34240 26.49951 9.41034 39.69499 26.49951 -9.41117 39.69500 26.49951 10.30378 37.84974 26.49951 -10.30460 37.84974 26.49951 10.83928 35.87073 26.49951 -10.84010 35.87073 26.49951 10.99823 33.82670 26.49951 -10.99905 33.82671 26.49951 10.77511 31.78867 26.49951 -10.77593 31.78867 26.49951 10.17765 29.82741 26.49951 -10.17847 29.82741 26.49951 9.22661 28.01108 26.49951 -9.22743 28.01108 26.49951 7.95500 26.40278 26.49951 -7.95582 26.40278 26.49951 6.40699 25.05838 26.49951 -6.40781 25.05838 35.89951 10.98820 34.50008 35.89951 10.88393 32.40860 35.89951 10.69423 36.57343 35.89951 10.38519 30.37477 35.89951 10.01267 38.55351 35.89951 9.51007 28.47231 35.89951 8.96823 40.36853 35.89951 8.29028 26.77017 35.89951 7.59875 41.95275 35.89951 6.77002 25.33003 35.89951 5.95387 43.24872 35.89951 5.00439 24.20408 35.89951 4.09319 44.20951 35.89951 3.05739 23.43314 35.89951 2.08416 44.80026 35.89951 -0.00041 44.99959 35.89951 -2.08499 44.80026 35.89951 -3.05821 23.43314 35.89951 -4.09402 44.20951 35.89951 -5.00522 24.20408 35.89951 -5.95470 43.24872 35.89951 -6.77085 25.33003 35.89951 -7.59958 41.95275 35.89951 -8.29110 26.77017 35.89951 -8.96905 40.36853 35.89951 -9.51089 28.47231 35.89951 -10.01349 38.55351 35.89951 -10.38601 30.37477 35.89951 -10.88475 32.40860 35.89951 -10.98902 34.50009 35.89951 -10.69505 36.57344 -30.60796 -2.28766 23.24000 + + + + + + + + + + 0.00351 -0.99986 0.01651 0.00000 -0.99986 0.01683 -0.88619 0.44850 -0.11622 -0.78877 0.60651 -0.09996 -0.83885 0.52713 -0.13587 -0.65725 0.73765 -0.15457 -0.50717 0.86073 -0.04374 -0.00723 -0.99986 -0.01540 -0.00979 -0.99986 -0.01391 -0.00995 -0.99986 -0.01370 -0.01209 -0.99985 -0.01203 -0.01357 -0.99986 -0.00945 -0.01317 -0.99984 -0.01186 -0.01514 -0.99986 -0.00702 -0.01511 -0.99985 -0.00872 -0.01626 -0.99986 -0.00431 -0.01638 -0.99985 -0.00532 -0.01682 -0.99986 -0.00177 -0.01696 -0.99986 -0.00144 -0.01694 -0.99985 0.00178 -0.01949 -0.99974 0.01192 -0.02103 -0.99976 0.00683 -0.02161 -0.99974 -0.00720 -0.01202 -0.99984 0.01306 -0.01566 -0.99984 0.00904 -0.01613 -0.99984 0.00811 -0.01251 -0.99986 0.01126 -0.01174 -0.99985 0.01240 -0.00939 -0.99986 0.01401 -0.01006 -0.99985 0.01384 -0.00698 -0.99986 0.01547 -0.00939 0.99986 0.01401 -0.01174 0.99985 0.01240 -0.01251 0.99986 0.01126 -0.01364 0.99985 0.01028 -0.01460 0.99986 0.00843 -0.01435 0.99986 0.00870 -0.01944 0.99980 -0.00420 -0.01935 0.99979 0.00629 -0.01869 0.99979 0.00875 -0.01694 0.99985 0.00178 -0.01695 0.99986 -0.00144 -0.01682 0.99986 -0.00177 -0.01650 0.99985 -0.00438 -0.01602 0.99986 -0.00521 -0.01551 0.99985 -0.00718 -0.01457 0.99986 -0.00842 -0.01402 0.99985 -0.00977 -0.01253 0.99986 -0.01128 -0.01209 0.99985 -0.01203 -0.00975 0.99986 -0.01385 -0.95927 0.00000 -0.28251 -0.95855 0.00402 -0.28490 -0.95788 0.00000 -0.28717 -0.90737 0.00000 -0.42034 -0.90737 0.00000 -0.42034 -0.96656 -0.00572 -0.25638 -0.46377 -0.36064 -0.80923 -0.45318 -0.53536 -0.71275 -0.99676 0.00262 -0.08039 -0.99223 -0.09399 -0.08153 -0.94714 -0.27414 -0.16666 -0.99664 -0.00000 -0.08188 -0.97827 0.00001 -0.20735 -0.18189 -0.98107 -0.06642 -0.16835 -0.98346 -0.06677 -0.97827 -0.00001 -0.20736 -0.94410 0.00001 -0.32965 -0.94410 -0.00001 -0.32967 0.99529 0.00011 0.09690 0.99524 0.00000 0.09744 0.97160 -0.00000 0.23664 0.97160 0.00000 0.23664 0.92871 -0.00000 0.37082 0.20791 -0.00842 -0.97811 0.09802 0.00749 -0.99516 0.00000 -0.00856 -0.99996 -0.09801 0.00749 -0.99516 -0.20791 -0.00842 -0.97811 -0.29027 0.00722 -0.95692 -0.40672 -0.00803 -0.91352 -0.47139 0.00669 -0.88190 -0.58777 -0.00735 -0.80900 -0.63438 0.00589 -0.77300 -0.74313 -0.00642 -0.66912 -0.77300 0.00481 -0.63439 -0.86601 -0.00521 -0.49999 -0.88192 0.00348 -0.47139 -0.95105 -0.00374 -0.30901 -0.95694 0.00187 -0.29029 -0.99452 -0.00200 -0.10453 -0.99518 0.00000 -0.09802 -0.33023 -0.01785 0.94373 -0.23926 0.02143 0.97072 -0.11194 -0.01875 0.99354 0.00000 0.02187 0.99976 0.11194 -0.01875 0.99354 0.23926 0.02143 0.97072 0.33023 -0.01785 0.94373 0.46462 0.02008 0.88528 0.53196 -0.01607 0.84662 0.66302 0.01785 0.74839 0.70705 -0.01339 0.70704 0.82289 0.01472 0.56800 0.84668 -0.00982 0.53201 0.93496 0.01071 0.35459 0.94387 -0.00535 0.33027 0.99271 -0.00000 0.12054 0.99369 0.00624 0.11196 0.99371 0.00000 -0.11196 0.99269 0.00580 -0.12054 0.94387 -0.00535 -0.33028 0.93496 0.01071 -0.35459 0.84668 -0.00981 -0.53201 0.82290 0.01472 -0.56800 0.70704 -0.01339 -0.70704 0.66302 0.01785 -0.74839 0.53196 -0.01607 -0.84661 0.46463 0.02008 -0.88528 0.33023 -0.01785 -0.94373 0.23926 0.02143 -0.97072 0.11194 -0.01875 -0.99354 0.00000 0.02187 -0.99976 -0.11194 -0.01875 -0.99354 -0.23926 0.02143 -0.97072 -0.33023 -0.01785 -0.94373 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.99452 -0.00000 0.10453 -0.99518 -0.00214 0.09802 -0.95694 0.00187 0.29028 -0.95105 -0.00374 0.30902 -0.88192 0.00348 0.47139 -0.86601 -0.00521 0.49999 -0.77300 0.00481 0.63439 -0.74313 -0.00642 0.66912 -0.63438 0.00588 0.77300 -0.58777 -0.00735 0.80900 -0.47139 0.00669 0.88190 -0.40672 -0.00803 0.91352 -0.29028 0.00722 0.95692 -0.20790 -0.00843 0.97811 -0.09801 0.00749 0.99516 0.00000 -0.00856 0.99996 0.09801 0.00749 0.99516 0.20790 -0.00843 0.97811 0.00350 0.99986 -0.01649 0.00351 0.99986 0.01650 0.00145 0.99985 -0.01703 0.00133 0.99985 0.01702 0.00000 0.99986 -0.01683 -0.00000 0.99986 0.01683 -0.00153 0.99985 -0.01702 -0.00350 0.99986 -0.01648 -0.00152 0.99985 0.01701 -0.00432 0.99985 0.01649 -0.00350 0.99986 0.01649 -0.00446 0.99985 -0.01647 -0.00688 0.99986 -0.01545 -0.00689 0.99986 0.01548 -0.00698 0.99986 0.01547 -0.00723 0.99986 -0.01540 -0.01001 0.99985 -0.01378 -0.01006 0.99985 0.01384 0.20790 0.00843 0.97811 0.09801 -0.00749 0.99516 -0.00000 0.00856 0.99996 -0.09801 -0.00749 0.99516 -0.20791 0.00843 0.97811 -0.29028 -0.00722 0.95692 -0.40672 0.00803 0.91352 -0.47139 -0.00669 0.88190 -0.58777 0.00735 0.80900 -0.63438 -0.00588 0.77300 -0.74313 0.00642 0.66912 -0.77300 -0.00481 0.63439 -0.86601 0.00521 0.49999 -0.88192 -0.00348 0.47139 -0.95105 0.00374 0.30902 -0.95694 -0.00187 0.29028 -0.99452 0.00200 0.10453 -0.99518 -0.00000 0.09802 -0.99452 0.00000 -0.10453 -0.99518 0.00214 -0.09802 -0.95694 -0.00187 -0.29029 -0.95105 0.00374 -0.30902 -0.88192 -0.00348 -0.47139 -0.86601 0.00521 -0.49999 -0.77300 -0.00481 -0.63439 -0.74313 0.00642 -0.66912 -0.63438 -0.00589 -0.77300 -0.58777 0.00735 -0.80900 -0.47139 -0.00669 -0.88190 -0.40672 0.00803 -0.91352 -0.29027 -0.00722 -0.95692 -0.20791 0.00842 -0.97811 -0.09802 -0.00749 -0.99516 0.00000 0.00856 -0.99996 0.09802 -0.00749 -0.99516 0.20791 0.00842 -0.97811 -0.00428 -0.99987 -0.01582 -0.00432 -0.99985 0.01649 -0.00689 -0.99986 0.01548 -0.00733 -0.99984 -0.01645 -0.00350 -0.99986 0.01649 -0.00149 -0.99986 -0.01650 -0.00368 -0.99984 -0.01729 -0.00152 -0.99985 0.01701 0.00000 -0.99986 -0.01683 0.00133 -0.99985 0.01702 0.00145 -0.99985 -0.01703 0.00350 -0.99986 -0.01649 -0.29843 0.80194 -0.51753 -0.45546 0.76061 -0.46263 -0.48572 0.74811 -0.45212 -0.52648 0.72710 -0.44062 -0.70516 0.61922 -0.34541 -0.68729 0.63389 -0.35471 -0.79346 0.54430 -0.27233 -0.85010 0.47351 -0.23050 -0.92476 0.35495 -0.13725 -0.88546 0.42818 -0.18060 -0.97510 0.21969 -0.03025 -0.99355 0.10933 0.02998 -0.99487 0.00529 0.10098 -0.44914 0.56393 -0.69301 -0.48712 0.33907 -0.80483 -0.46872 0.11111 -0.87633 -0.48781 0.55012 -0.67779 -0.56989 0.12661 -0.81191 -0.50827 0.32733 -0.79656 -0.52244 0.54094 -0.65912 -0.71199 0.41889 -0.56357 -0.76447 0.38273 -0.51875 -0.75314 0.23466 -0.61459 -0.75445 0.07598 -0.65194 -0.76357 0.23187 -0.60266 -0.80030 0.34611 -0.48961 -0.77744 0.07742 -0.62418 -0.89245 0.25985 -0.36881 -0.88324 0.13720 -0.44841 -0.89344 0.04446 -0.44698 -0.89802 0.12735 -0.42112 -0.93206 0.19411 -0.30591 -0.92669 0.04989 -0.37250 -0.96319 0.02410 -0.26775 -0.97120 0.12167 -0.20487 -0.98112 0.08870 -0.17186 -0.57327 0.00000 -0.81936 -0.58559 0.00572 -0.81059 -0.78071 -0.00192 -0.62489 -0.80115 0.00518 -0.59844 -0.92784 -0.00355 -0.37297 -0.93332 0.00059 -0.35905 -0.54334 -0.12355 -0.83037 -0.55062 -0.32950 -0.76697 -0.56899 -0.31769 -0.75850 -0.58230 -0.47952 -0.65650 -0.47157 -0.55221 -0.68752 -0.57960 -0.12850 -0.80470 -0.65890 -0.45141 -0.60174 -0.74087 -0.07739 -0.66717 -0.75046 -0.23110 -0.61920 -0.73276 -0.24796 -0.63370 -0.74409 -0.40715 -0.52968 -0.79988 -0.07795 -0.59507 -0.83756 -0.30814 -0.45116 -0.93299 -0.02422 -0.35908 -0.92289 -0.03443 -0.38352 -0.92643 -0.09817 -0.36343 -0.91099 -0.12348 -0.39350 -0.91770 -0.21960 -0.33106 -0.92934 -0.19612 -0.31285 -0.99452 -0.01997 -0.10259 -0.47080 -0.75241 -0.46069 -0.45668 -0.75918 -0.46378 -0.65213 -0.65623 -0.37958 -0.61916 -0.68060 -0.39169 -0.82908 -0.50451 -0.24104 -0.85407 -0.47034 -0.22212 -0.92231 -0.36337 -0.13159 -0.99192 -0.12653 0.00876 -0.98384 -0.17818 -0.01749 -0.99580 -0.01898 0.08960 0.25602 -0.67271 0.69420 0.10951 -0.95426 0.27821 -0.24299 -0.96070 -0.13420 0.02366 -0.93898 0.34315 0.41629 -0.24307 0.87614 0.25610 -0.67271 0.69417 -0.36230 -0.93025 -0.05802 0.36996 -0.25534 0.89327 0.10702 -0.62868 0.77027 -0.13311 -0.91757 0.37463 -0.52306 -0.85223 -0.01049 0.03553 -0.62578 0.77919 0.17265 -0.21866 0.96041 -0.49931 -0.86639 -0.00769 -0.29615 -0.83056 0.47167 0.11936 -0.22311 0.96746 -0.12565 -0.56539 0.81519 -0.00082 -0.19219 0.98136 -0.17977 -0.52640 0.83101 -0.39503 -0.78686 0.47414 -0.77611 -0.62215 0.10282 -0.67472 -0.72940 0.11282 -0.51628 -0.68662 0.51187 -0.15957 -0.18279 0.97011 -0.24409 -0.14826 0.95835 -0.34379 -0.44941 0.82452 -0.55399 -0.66213 0.50466 -0.36494 -0.43114 0.82519 -0.42580 -0.11643 0.89729 -0.49952 -0.34354 0.79527 -0.52836 -0.31199 0.78962 -0.69334 -0.51702 0.50197 -0.92543 -0.28426 0.25055 -0.79022 -0.55988 0.24917 -0.43711 -0.11689 0.89178 -0.84444 -0.13410 0.51859 -0.80441 -0.23405 0.54603 -0.69684 -0.15924 0.69933 -0.66097 -0.04772 0.74889 -0.66379 -0.04752 0.74641 -0.73766 -0.09046 0.66908 0.38198 -0.00000 0.92417 0.39651 0.00076 0.91803 0.12271 -0.00007 0.99244 0.13374 0.00042 0.99102 -0.16191 -0.00126 0.98680 -0.14660 -0.00049 0.98920 -0.43971 0.00043 0.89814 -0.42046 0.00134 0.90731 -0.66472 -0.00107 0.74709 -0.64854 -0.00010 0.76118 -0.20688 0.96904 -0.13476 -0.21729 0.96682 -0.13436 0.02220 0.93724 0.34797 0.18340 0.66030 0.72826 0.32370 0.26370 0.90867 -0.04563 0.93478 0.35228 0.15402 0.64342 0.74986 0.38427 0.24588 0.88988 -0.42875 0.90238 -0.04338 0.13021 0.21703 0.96744 -0.23944 0.86631 0.43837 -0.43986 0.89707 -0.04216 0.12412 0.21418 0.96888 -0.00829 0.60805 0.79386 -0.26215 0.85896 0.43984 -0.03777 0.58651 0.80906 -0.58919 0.80734 0.03251 -0.40605 0.76730 0.49635 -0.60111 0.79844 0.03407 -0.27437 0.47832 0.83423 -0.47610 0.72411 0.49900 -0.76444 0.63397 0.11712 -0.23688 0.18363 0.95403 -0.32759 0.46151 0.82444 -0.76955 0.62765 0.11774 -0.62231 0.56695 0.53971 -0.14442 0.16129 0.97628 -0.41513 0.39049 0.82170 -0.58425 0.59872 0.54789 -0.80418 0.57658 0.14438 -0.41713 0.12663 0.89998 -0.57940 0.81267 0.06214 -0.90601 0.33872 0.25379 -0.58005 0.05536 0.81270 -0.64048 0.24568 0.72761 -0.64772 0.05054 0.76020 -0.53358 0.65124 0.53960 -0.73246 0.10072 0.67332 -0.81922 0.28667 0.49668 -0.69807 0.02783 0.71549 -0.72391 0.10738 0.68148 -0.31865 -0.94762 -0.02173 -0.06834 -0.99280 -0.09833 -0.18893 -0.98183 -0.01773 0.18189 -0.98318 0.01629 0.42299 -0.90569 -0.02856 0.63070 -0.77024 0.09462 0.80590 -0.58653 0.08063 0.27517 -0.96051 0.04134 0.98733 -0.12632 0.09608 0.92845 -0.37112 0.01598 0.97574 -0.16150 0.14783 0.72060 -0.68471 0.10910 -0.19528 -0.98025 -0.03112 0.30206 -0.95068 0.07043 -0.17277 -0.98376 -0.04857 -0.18246 -0.98214 -0.04587 0.93546 -0.27020 0.22784 0.26518 -0.95786 0.11037 0.27646 -0.95469 0.11015 0.67463 -0.68266 0.28079 0.90310 -0.20439 0.37768 0.91614 -0.16395 0.36580 0.67176 -0.68543 0.28093 0.83344 -0.27693 0.47821 0.27276 -0.94729 0.16805 -0.15712 -0.98294 -0.09563 -0.16577 -0.98153 -0.09545 0.22350 -0.96046 0.16605 0.58707 -0.68199 0.43616 0.58285 -0.68612 0.43533 0.78883 -0.17497 0.58918 0.77010 -0.21665 0.60001 -0.16041 -0.97986 -0.11895 -0.14122 -0.98157 -0.12873 -0.13494 -0.98273 -0.12662 0.23734 -0.94703 0.21635 0.66915 -0.26852 0.69292 0.46707 -0.68165 0.56321 0.45988 -0.68920 0.55992 0.17772 -0.95945 0.21879 0.62189 -0.15765 0.76707 -0.12771 -0.98023 -0.15113 -0.09872 -0.98464 -0.14399 0.18438 -0.95175 0.24532 0.56828 -0.24866 0.78436 -0.09765 -0.98290 -0.15615 -0.33794 0.94076 -0.02775 -0.07269 0.99529 -0.06413 0.30268 0.95198 0.04598 0.18138 0.98333 -0.01276 0.42303 0.90386 0.06391 -0.17534 0.98415 -0.02653 0.62732 0.77298 0.09476 0.80600 0.58643 0.08040 0.98750 0.12448 0.09665 0.92894 0.36986 0.01630 0.71988 0.68544 0.10932 0.97551 0.16260 0.14814 0.93534 0.27064 0.22781 -0.19594 0.97941 -0.04864 0.28073 0.95265 0.11685 0.67397 0.68342 0.28054 0.90780 0.17821 0.37965 0.90756 0.21216 0.36238 0.67114 0.68614 0.28068 0.28346 0.95155 0.11918 -0.17073 0.98270 -0.07179 -0.16712 0.98356 -0.06843 0.83334 0.27735 0.47815 -0.17478 0.97917 -0.10335 0.58650 0.68275 0.43575 0.24297 0.95309 0.18052 0.78346 0.20920 0.58517 0.77899 0.15747 0.60694 0.58231 0.68684 0.43493 -0.14277 0.98390 -0.10752 -0.14957 0.98135 -0.12078 0.24668 0.95112 0.18578 0.66906 0.26896 0.69283 -0.13505 0.98001 -0.14608 0.45976 0.69678 0.55056 0.46368 0.68205 0.56552 0.19541 0.95351 0.22943 0.62196 0.15862 0.76681 -0.10524 0.98512 -0.13587 0.20648 0.94390 0.25772 0.56750 0.25380 0.78328 -0.10671 0.98194 -0.15621 -0.60667 0.79123 -0.07686 -0.56817 0.81074 -0.14105 -0.79584 0.53524 -0.28311 -0.57820 0.78954 -0.20569 -0.80107 0.51949 -0.29735 -0.91713 0.20731 -0.34044 -0.91737 0.23627 -0.32032 -0.54765 0.80610 -0.22425 -0.88170 0.16993 -0.44015 -0.51831 0.79181 -0.32310 -0.51464 0.80158 -0.30432 -0.71413 0.54022 -0.44517 -0.71686 0.51486 -0.47014 -0.81520 0.22276 -0.53463 -0.81227 0.21056 -0.54395 -0.45559 0.81060 -0.36791 -0.74244 0.17211 -0.64743 -0.60027 0.54466 -0.58568 -0.43952 0.78926 -0.42883 -0.67393 0.23158 -0.70157 -0.65209 0.19089 -0.73372 -0.59561 0.51069 -0.62004 -0.40107 0.80680 -0.43384 -0.33502 0.79280 -0.50914 -0.33830 0.80043 -0.49484 -0.45934 0.54863 -0.69858 -0.55491 0.18086 -0.81201 -0.47588 0.34278 -0.80996 -0.46281 0.55781 -0.68895 -0.51130 0.22340 -0.82986 -0.45217 0.11213 -0.88486 -0.88620 -0.44851 -0.11617 -0.78284 -0.60273 -0.15456 -0.84468 -0.52445 -0.10705 -0.96417 -0.23323 -0.12640 -0.66324 -0.74368 -0.08398 -0.51400 -0.84905 -0.12211 -0.64066 -0.76661 -0.04310 -0.59317 -0.79951 -0.09452 -0.57276 -0.80697 -0.14400 -0.57500 -0.79218 -0.20454 -0.54901 -0.80696 -0.21773 -0.79566 -0.53556 -0.28303 -0.80089 -0.51981 -0.29728 -0.91311 -0.22662 -0.33893 -0.88166 -0.17013 -0.44014 -0.71397 -0.54053 -0.44505 -0.50961 -0.79962 -0.31766 -0.54216 -0.78013 -0.31218 -0.71671 -0.51519 -0.47002 -0.81695 -0.21343 -0.53576 -0.80918 -0.22706 -0.54191 -0.47347 -0.80782 -0.35108 -0.74240 -0.17231 -0.64742 -0.43291 -0.79637 -0.42235 -0.45040 -0.78645 -0.42265 -0.60015 -0.54497 -0.58551 -0.59549 -0.51101 -0.61988 -0.67968 -0.19350 -0.70752 -0.64206 -0.25654 -0.72245 -0.37976 -0.80859 -0.44940 -0.33611 -0.79429 -0.50610 -0.32117 -0.80258 -0.50271 -0.45843 -0.54912 -0.69879 -0.55489 -0.18107 -0.81198 -0.50368 -0.23068 -0.83252 -0.45098 -0.13321 -0.88254 -0.99641 0.00112 -0.08466 -0.99729 0.01576 -0.07190 -0.99637 -0.00893 -0.08466 -0.99602 -0.01019 -0.08855 -0.99255 -0.00087 -0.12183 -0.98077 -0.00810 -0.19502 -0.96656 -0.00561 -0.25638 -0.98287 0.01723 -0.18351 -0.97605 -0.00303 -0.21754 -0.90737 0.00000 -0.42034 -0.82060 0.00000 -0.57150 -0.82060 0.00000 -0.57150 -0.70890 0.00000 -0.70531 -0.70890 0.00000 -0.70531 -0.57566 0.00000 -0.81769 -0.57566 0.00000 -0.81769 -0.42492 0.00000 -0.90523 -0.42492 0.00000 -0.90523 -0.26128 0.00000 -0.96526 -0.26128 0.00000 -0.96526 -0.08971 0.00000 -0.99597 -0.08971 0.00000 -0.99597 0.08460 0.00000 -0.99642 0.08460 0.00000 -0.99642 0.07779 -0.00000 0.99697 0.07779 -0.00000 0.99697 -0.08916 -0.00000 0.99602 -0.08916 -0.00000 0.99602 -0.25363 0.00000 0.96730 -0.25363 -0.00000 0.96730 -0.41102 -0.00000 0.91162 -0.41102 -0.00000 0.91162 -0.55695 -0.00000 0.83054 -0.55696 -0.00000 0.83054 -0.68736 -0.00000 0.72632 -0.68736 -0.00000 0.72632 -0.79835 0.02528 0.60167 -0.77337 0.00354 0.63395 -0.75022 -0.00000 0.66119 -0.79945 -0.02809 0.60007 -0.77570 -0.00524 0.63108 -0.74247 0.00028 0.66988 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.92871 -0.00000 0.37082 0.86737 -0.00000 0.49767 0.86737 -0.00000 0.49767 0.78883 -0.00000 0.61461 0.78883 -0.00000 0.61461 0.69466 -0.00000 0.71934 0.69466 -0.00000 0.71934 0.58671 -0.00000 0.80980 0.58671 -0.00000 0.80980 -0.89471 0.00001 -0.44664 -0.89471 -0.00001 -0.44665 -0.83090 0.00002 -0.55642 -0.83089 -0.00002 -0.55644 -0.75368 0.00002 -0.65724 -0.75367 -0.00002 -0.65725 -0.66430 0.00001 -0.74746 -0.66430 -0.00001 -0.74747 -0.56422 0.00001 -0.82563 -0.56421 -0.00001 -0.82563 -0.45503 0.00000 -0.89047 -0.45503 0.00000 -0.89047 -0.95313 0.27559 -0.12490 -0.97949 0.08775 -0.18137 -0.96015 0.26855 -0.07742 -0.96329 0.17434 -0.20417 -0.96325 -0.17453 -0.20417 -0.92437 -0.20337 -0.32278 0.94185 -0.00006 -0.33603 0.94183 0.00006 -0.33608 0.88974 -0.00006 -0.45646 0.88972 0.00006 -0.45651 0.82232 -0.00005 -0.56902 0.82229 0.00006 -0.56907 0.74075 -0.00006 -0.67178 0.74070 0.00008 -0.67184 0.64642 -0.00008 -0.76298 0.64636 0.00007 -0.76303 0.54094 -0.00007 -0.84106 0.54089 0.00004 -0.84109 0.42613 -0.00004 -0.90466 0.42611 0.00000 -0.90467 0.30163 -0.00001 -0.95343 0.30399 -0.00527 -0.95266 -0.93888 0.00001 0.34425 -0.93884 -0.00001 0.34435 -0.88525 0.00002 0.46512 -0.88518 -0.00002 0.46526 -0.81604 0.00002 0.57799 -0.81592 -0.00003 0.57816 -0.73278 0.00003 0.68046 -0.73263 -0.00002 0.68063 -0.64110 0.00002 0.76745 -0.64098 -0.00001 0.76756 -0.54819 0.00001 0.83635 -0.54884 -0.00014 0.83592 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.24257 -0.00000 0.97013 0.24257 -0.00000 0.97013 0.40057 -0.00000 0.91626 0.40058 0.00000 0.91626 0.54742 0.00000 0.83686 0.54742 0.00000 0.83686 0.67900 0.00000 0.73414 0.67900 -0.00000 0.73414 0.79165 -0.00000 0.61097 0.79165 -0.00000 0.61097 0.88225 -0.00000 0.47078 0.88225 -0.00000 0.47078 0.91370 -0.00000 0.40640 0.93759 -0.00672 0.34768 0.92759 0.00091 0.37360 0.94072 0.00403 0.33917 0.95201 0.03380 0.30420 0.96359 -0.05853 -0.26089 0.96386 0.05350 -0.26097 0.94569 -0.02266 -0.32427 0.92463 -0.04605 -0.37807 0.89371 0.15883 -0.41958 0.90505 0.01824 -0.42491 0.88798 0.00184 -0.45989 0.88884 -0.00173 -0.45821 0.80446 -0.00273 -0.59399 0.78816 -0.00081 -0.61547 0.82555 -0.00953 -0.56425 0.81766 -0.00267 -0.57570 0.83796 0.00144 -0.54573 0.77615 0.00000 -0.63054 0.79321 0.00197 -0.60894 0.81763 0.00816 -0.57568 0.70527 -0.00000 -0.70894 0.70527 -0.00000 -0.70894 0.57146 -0.00000 -0.82063 0.57145 0.00000 -0.82064 0.42028 0.00000 -0.90740 0.42028 0.00000 -0.90739 0.25633 0.00000 -0.96659 0.25633 0.00000 -0.96659 0.92086 -0.35182 -0.16806 0.98805 -0.13279 -0.07831 0.96310 -0.25221 -0.09395 0.55997 -0.81528 -0.14752 0.96392 -0.16753 -0.20687 0.57062 -0.79919 -0.18891 0.80059 -0.53741 -0.26504 0.80832 -0.51650 -0.28256 0.92052 -0.21165 -0.32842 0.92062 -0.22114 -0.32182 0.53512 -0.81793 -0.21126 0.87674 -0.17035 -0.44979 0.72731 -0.54379 -0.41870 0.53027 -0.78663 -0.31627 0.52543 -0.79526 -0.30248 0.82817 -0.23633 -0.50822 0.73286 -0.51055 -0.44973 0.80912 -0.17844 -0.55989 0.47111 -0.80823 -0.35329 0.45570 -0.78314 -0.42312 0.45228 -0.79679 -0.40070 0.62550 -0.54923 -0.55416 0.71779 -0.24703 -0.65096 0.70751 -0.19739 -0.67858 0.62275 -0.50540 -0.59728 0.38937 -0.80750 -0.44309 0.63743 -0.16613 -0.75238 0.36311 -0.78476 -0.50229 0.36445 -0.79417 -0.48628 0.49937 -0.55376 -0.66631 0.30281 -0.80734 -0.50648 0.53003 -0.19982 -0.82410 0.54348 -0.22777 -0.80793 0.48302 -0.50109 -0.71805 0.41954 -0.17523 -0.89066 0.26108 -0.79358 -0.54961 0.27943 -0.81607 -0.50592 0.29119 -0.71113 -0.63993 0.35931 -0.55539 -0.74996 0.36493 -0.23060 -0.90203 0.33497 -0.49119 -0.80407 0.34295 -0.31685 -0.88430 0.30001 -0.09841 -0.94885 0.62652 0.77786 -0.04904 0.51423 0.85038 -0.11147 0.66372 0.74398 -0.07728 0.84714 0.52213 -0.09865 0.78461 0.60341 -0.14241 0.88724 0.44844 -0.10816 0.96334 0.24121 -0.11743 0.57557 0.80940 -0.11659 0.96304 0.16869 -0.21000 0.80089 0.53729 -0.26436 0.57696 0.79404 -0.19135 0.57814 0.79331 -0.19083 0.91781 0.22441 -0.32751 0.92253 0.21302 -0.32182 0.80874 0.51608 -0.28213 0.53139 0.80923 -0.25054 0.87672 0.17034 -0.44984 0.72768 0.54363 -0.41826 0.50348 0.80399 -0.31640 0.53307 0.78864 -0.30640 0.82842 0.23633 -0.50781 0.73327 0.51016 -0.44949 0.80915 0.17803 -0.55998 0.46106 0.80464 -0.37414 0.46060 0.78844 -0.40769 0.62585 0.54904 -0.55396 0.40986 0.80854 -0.42222 0.62310 0.50504 -0.59722 0.72654 0.19459 -0.65899 0.70254 0.23030 -0.67335 0.63740 0.16593 -0.75245 0.37795 0.78665 -0.48819 0.36371 0.79527 -0.48504 0.49963 0.55355 -0.66630 0.31162 0.80775 -0.50043 0.48326 0.50075 -0.71813 0.52523 0.23894 -0.81673 0.54666 0.20310 -0.81235 0.41953 0.17511 -0.89069 0.35011 0.55871 -0.75184 0.36262 0.23283 -0.90238 0.30210 0.11146 -0.94674 0.06650 0.99566 -0.06516 0.32275 0.94614 -0.02538 -0.92863 0.37061 0.01700 -0.98830 0.12644 0.08529 -0.97655 0.17783 0.12133 -0.72577 0.68200 0.09023 -0.80640 0.58798 0.06324 -0.63167 0.77117 0.07935 -0.30573 0.95134 0.03855 -0.42260 0.90611 0.01929 -0.17883 0.98361 0.02317 0.17655 0.98403 -0.02274 0.19541 0.97992 -0.03958 -0.93709 0.27982 0.20872 -0.68650 0.68817 0.23485 -0.91286 0.23363 0.33482 -0.92958 0.18642 0.31801 -0.28472 0.95347 0.09912 -0.69326 0.67908 0.24134 -0.29299 0.95030 0.10531 0.18065 0.98172 -0.05991 0.16914 0.98372 -0.06079 0.18218 0.97951 -0.08589 -0.85436 0.26155 0.44906 -0.62159 0.69118 0.36864 -0.84706 0.17357 0.50235 -0.25513 0.95449 0.15447 -0.63028 0.67611 0.38160 0.15533 0.98303 -0.09761 0.15505 0.98308 -0.09755 -0.26621 0.94925 0.16750 -0.78398 0.27707 0.55553 0.15646 0.97949 -0.12696 -0.71551 0.21489 0.66473 -0.72337 0.19685 0.66180 -0.53117 0.69405 0.48596 -0.21531 0.95540 0.20212 -0.53911 0.67323 0.50608 -0.22613 0.94825 0.22289 0.12238 0.98444 -0.12606 0.13364 0.98224 -0.13172 -0.61744 0.26850 0.73937 0.12196 0.97995 -0.15753 -0.52822 0.26640 0.80623 -0.57997 0.18211 0.79402 -0.41981 0.69669 0.58171 -0.41718 0.70927 0.56824 -0.15676 0.95722 0.24322 0.09262 0.98453 -0.14874 -0.05901 0.99778 -0.03079 0.16281 0.97811 0.12963 0.12607 0.95961 -0.25151 0.19599 -0.98043 -0.01837 -0.96452 -0.25067 0.08283 -0.97660 -0.17782 0.12096 -0.80479 -0.58513 0.09969 -0.63328 -0.77302 0.03754 -0.72616 -0.68147 0.09107 0.21458 -0.97528 -0.05270 -0.42311 -0.90452 0.05308 -0.18723 -0.98222 -0.01389 -0.36096 -0.93046 0.06285 0.17465 -0.98431 -0.02497 -0.93721 -0.27943 0.20868 -0.68737 -0.68736 0.23467 -0.92600 -0.16505 0.33953 -0.92133 -0.22851 0.31455 -0.28110 -0.95470 0.09764 -0.69403 -0.67839 0.24106 0.20738 -0.97456 -0.08504 -0.85461 -0.26080 0.44902 0.16380 -0.98310 -0.08173 -0.32234 -0.93559 0.14413 0.17112 -0.97995 -0.10206 -0.62240 -0.69040 0.36874 -0.84740 -0.17285 0.50204 -0.24032 -0.95975 0.14533 -0.63104 -0.67540 0.38160 -0.78419 -0.27666 0.55543 -0.26047 -0.94537 0.19603 0.14875 -0.98256 -0.11155 0.14917 -0.98242 -0.11226 0.14605 -0.97994 -0.13561 -0.53184 -0.69329 0.48630 -0.71932 -0.19083 0.66796 -0.72141 -0.21084 0.65963 -0.20511 -0.95964 0.19242 -0.53977 -0.67249 0.50636 -0.21885 -0.94617 0.23847 0.12617 -0.98156 -0.14358 0.12393 -0.98306 -0.13504 -0.61764 -0.26808 0.73936 0.11562 -0.98033 -0.15994 -0.41812 -0.69623 0.58347 -0.54545 -0.11098 0.83077 -0.56890 -0.25471 0.78197 -0.14761 -0.96138 0.23227 -0.41545 -0.70916 0.56965 -0.13028 -0.97712 0.16813 0.12770 -0.96854 -0.21358 0.11576 -0.98031 -0.15997 0.11951 -0.96126 -0.24840 0.86759 -0.00004 0.49729 0.86005 -0.00067 0.51021 0.69871 0.00033 0.71540 0.68315 -0.00054 0.73028 0.45680 0.00096 0.88957 0.44236 0.00026 0.89684 0.18885 -0.00058 0.98201 0.19784 -0.00019 0.98023 -0.07915 -0.00022 0.99686 -0.08595 -0.00053 0.99630 -0.36010 0.00041 0.93291 -0.37498 -0.00025 0.92703 0.86482 0.05323 0.49925 0.89424 0.04308 0.44551 0.91976 0.13689 0.36782 0.85166 0.07061 0.51932 0.85668 0.23985 0.45669 0.74796 0.10340 0.65564 0.79318 0.34142 0.50427 0.67621 0.14507 0.72228 0.90664 0.39515 0.14784 0.54784 0.16722 0.81970 0.61468 0.48582 0.62140 0.76377 0.62501 0.16126 0.69118 0.44984 0.56560 0.43262 0.21045 0.87667 0.42687 0.61530 0.66271 0.34421 0.21590 0.91373 0.19110 0.25623 0.94754 0.74895 0.64085 0.16846 0.46141 0.60552 0.64842 0.55087 0.81731 0.16897 0.14403 0.25363 0.95652 0.23745 0.69961 0.67392 -0.06179 0.28381 0.95689 0.51464 0.83834 0.17982 0.30991 0.93560 0.16913 0.21181 0.70288 0.67904 0.02029 0.75864 0.65120 -0.08136 0.28235 0.95585 -0.10996 0.28736 0.95149 0.35288 0.92239 0.15705 -0.11065 0.75626 0.64485 -0.34752 0.28060 0.89470 0.18518 0.96802 0.16923 -0.35957 0.28417 0.88879 -0.10909 0.75662 0.64469 0.04733 0.98757 0.14990 0.91677 0.37563 -0.13579 0.76266 0.61462 -0.20148 0.77416 0.59853 -0.20600 0.53176 0.81577 -0.22750 0.57893 0.77639 -0.24914 0.36133 0.90335 -0.23110 0.44603 0.85471 -0.26558 0.19295 0.94965 -0.24683 0.25813 0.92732 -0.27101 0.95845 0.07640 -0.27484 0.96167 0.06620 -0.26611 0.93288 0.02087 -0.35958 0.90762 0.09845 -0.40808 0.87723 0.15437 -0.45457 0.91474 0.23838 -0.32622 0.88053 0.01263 -0.47382 0.88988 0.28746 -0.35422 0.87002 0.03612 -0.49170 0.84090 -0.00101 -0.54120 0.75048 0.51149 -0.41852 0.75650 0.35756 -0.54760 0.73658 0.20873 -0.64334 0.74511 0.36872 -0.55575 0.78441 0.45895 -0.41721 0.72747 0.22157 -0.64938 0.69223 0.12864 -0.71011 0.66133 0.02956 -0.74951 0.70152 0.02967 -0.71203 0.71199 0.10709 -0.69398 0.58847 0.34393 -0.73172 0.59922 0.52419 -0.60512 0.59434 0.52732 -0.60720 0.63549 0.62397 -0.45477 0.55202 0.67988 -0.48274 0.50514 0.23415 -0.83067 0.55892 0.37367 -0.74026 0.50506 0.09286 -0.85807 0.53614 0.07615 -0.84069 0.56324 0.18628 -0.80502 0.42201 0.76248 -0.49044 0.45764 0.44194 -0.77153 0.42960 0.64938 -0.62750 0.49092 0.71323 -0.50030 0.45921 0.63909 -0.61700 0.19847 0.33790 -0.92002 0.31436 0.55529 -0.76996 0.52807 0.68920 -0.49613 0.49723 0.61593 -0.61106 0.33651 0.10481 -0.93583 0.05364 0.19518 -0.97930 0.22468 0.82174 -0.52369 0.66150 -0.00244 -0.74994 0.66936 -0.00439 -0.74293 0.50732 -0.00029 -0.86175 0.53404 -0.00848 -0.84541 0.33887 0.00575 -0.94082 0.38850 -0.00667 -0.92143 0.98063 0.06166 -0.18593 0.97165 -0.08208 -0.22171 0.93339 -0.02097 -0.35826 0.90822 -0.10105 -0.40612 0.86034 -0.19098 -0.47259 0.90628 -0.30599 -0.29159 0.88367 -0.00565 -0.46808 0.51136 -0.73088 -0.45202 0.85364 -0.06651 -0.51659 0.81975 -0.01450 -0.57254 0.77556 -0.16320 -0.60981 0.82147 -0.26460 -0.50515 0.75267 -0.51166 -0.41435 0.79853 -0.43998 -0.41081 0.75471 -0.34177 -0.56001 0.78536 -0.05049 -0.61697 0.78371 -0.00159 -0.62112 0.69609 -0.11307 -0.70899 0.73667 -0.21935 -0.63969 0.66919 -0.04023 -0.74200 0.59143 -0.66370 -0.45795 0.61722 -0.49367 -0.61265 0.65964 -0.59015 -0.46540 0.63442 -0.04473 -0.77169 0.65752 -0.14718 -0.73892 0.62728 -0.48184 -0.61185 0.57209 -0.36087 -0.73653 0.53978 -0.20746 -0.81584 0.59136 -0.33954 -0.73144 0.53179 -0.08056 -0.84303 0.47428 -0.59486 -0.64900 0.52137 -0.70758 -0.47697 0.33173 -0.51922 -0.78763 0.40674 -0.65063 -0.64128 0.35598 -0.78086 -0.51336 0.43567 -0.43150 -0.78994 0.34217 -0.32854 -0.88033 0.37782 -0.29848 -0.87645 0.33477 -0.10404 -0.93654 0.38808 -0.08436 -0.91776 0.92358 -0.35766 -0.13810 0.71913 -0.66669 -0.19588 0.77454 -0.59541 -0.21350 0.60812 -0.75847 -0.23432 0.61697 -0.75020 -0.23781 0.36141 -0.89887 -0.24782 0.38620 -0.88561 -0.25795 0.20676 -0.94041 -0.26995 0.89427 -0.03537 0.44612 0.95299 -0.04742 0.29926 0.92124 -0.15104 0.35848 0.86617 -0.05843 0.49633 0.82569 -0.31028 0.47112 0.78480 -0.08791 0.61348 0.69262 -0.13759 0.70806 0.72992 -0.39709 0.55635 0.69118 -0.13805 0.70938 0.66984 -0.44980 0.59075 0.60896 -0.14973 0.77894 0.46632 -0.19921 0.86189 0.92280 -0.37521 0.08751 0.61946 -0.77197 0.14259 0.79731 -0.58492 0.14886 0.72790 -0.41384 0.54672 0.44603 -0.20223 0.87187 0.52025 -0.56828 0.63749 0.42858 -0.20872 0.87906 0.60685 -0.76770 0.20587 0.52011 -0.56833 0.63756 0.70465 -0.69221 0.15593 0.18355 -0.24618 0.95169 0.20724 -0.24957 0.94592 0.29503 -0.66866 0.68253 0.39902 -0.65383 0.64288 0.48397 -0.85199 0.19974 0.60082 -0.78524 0.14972 -0.07555 -0.28563 0.95536 0.25210 -0.94931 0.18777 0.15490 -0.71443 0.68235 -0.00465 -0.76317 0.64619 -0.10740 -0.27806 0.95454 0.35331 -0.92324 0.15096 -0.13451 -0.75583 0.64080 0.03589 -0.98353 0.17717 0.20848 -0.97041 0.12180 -0.34502 -0.29404 0.89135 -0.16838 -0.75905 0.62888 -0.42627 -0.26736 0.86418 0.01280 -0.99985 -0.01152 0.00967 -0.99986 -0.01389 0.00680 -0.99987 -0.01467 0.00679 -0.99986 0.01553 0.01086 -0.99983 -0.01494 0.00689 -0.99986 -0.01547 0.00437 -0.99985 -0.01649 0.00739 -0.99983 0.01661 0.00395 -0.99987 0.01579 0.99518 0.00000 -0.09802 0.99452 0.00200 -0.10453 0.95694 -0.00187 -0.29028 0.95105 0.00374 -0.30901 0.88192 -0.00348 -0.47139 0.86601 0.00521 -0.49999 0.77300 -0.00481 -0.63439 0.74313 0.00642 -0.66912 0.63438 -0.00589 -0.77300 0.58777 0.00735 -0.80900 0.47139 -0.00669 -0.88190 0.40672 0.00803 -0.91352 0.29027 -0.00722 -0.95692 0.29027 -0.00722 0.95692 0.40672 0.00803 0.91352 0.47139 -0.00669 0.88190 0.58777 0.00735 0.80900 0.63438 -0.00588 0.77300 0.74313 0.00642 0.66912 0.77300 -0.00481 0.63439 0.86601 0.00521 0.49999 0.88192 -0.00348 0.47139 0.95105 0.00374 0.30902 0.95694 -0.00187 0.29028 0.99518 0.00214 0.09802 0.99452 -0.00000 0.10453 0.00413 0.99985 0.01652 0.99518 -0.00000 0.09802 0.99452 -0.00200 0.10453 0.95694 0.00187 0.29028 0.95105 -0.00374 0.30902 0.88192 0.00348 0.47139 0.86601 -0.00521 0.49999 0.77300 0.00481 0.63439 0.74313 -0.00642 0.66912 0.63438 0.00588 0.77300 0.58777 -0.00735 0.80900 0.47139 0.00669 0.88190 0.40672 -0.00803 0.91352 0.29027 0.00722 0.95692 -0.99369 0.00624 -0.11196 -0.99271 0.00000 -0.12054 -0.94387 -0.00535 -0.33028 -0.93496 0.01071 -0.35459 -0.84668 -0.00981 -0.53201 -0.82290 0.01472 -0.56800 -0.70704 -0.01339 -0.70704 -0.66302 0.01785 -0.74839 -0.53196 -0.01607 -0.84661 -0.46462 0.02008 -0.88528 -0.46462 0.02008 0.88528 -0.53196 -0.01607 0.84662 -0.66302 0.01785 0.74839 -0.70705 -0.01339 0.70704 -0.82290 0.01472 0.56800 -0.84668 -0.00982 0.53201 -0.93496 0.01071 0.35458 -0.94387 -0.00535 0.33027 -0.99269 0.00580 0.12054 -0.99371 -0.00000 0.11197 0.29027 0.00722 -0.95692 0.40672 -0.00803 -0.91352 0.47139 0.00669 -0.88190 0.58777 -0.00735 -0.80900 0.63438 0.00589 -0.77300 0.74313 -0.00642 -0.66912 0.77300 0.00481 -0.63439 0.86601 -0.00521 -0.49999 0.88192 0.00348 -0.47139 0.95105 -0.00374 -0.30901 0.95694 0.00187 -0.29028 0.99518 -0.00214 -0.09802 0.99452 0.00000 -0.10453 0.97704 0.00006 -0.21303 0.97771 -0.00700 -0.20983 0.99727 -0.01551 -0.07222 0.99687 -0.00117 -0.07902 -0.97608 -0.00001 0.21740 -0.97610 0.00001 0.21734 -0.99630 -0.00001 0.08600 -0.99633 0.00008 0.08562 0.26455 0.80715 -0.52776 0.34054 0.54168 -0.76851 0.35220 0.27446 -0.89478 0.07352 0.40715 -0.91040 0.00437 0.99985 -0.01649 0.00689 0.99986 -0.01547 0.00715 0.99986 -0.01543 0.01002 0.99985 -0.01379 0.00967 0.99986 -0.01389 0.01280 0.99985 -0.01152 0.01186 0.99986 -0.01192 0.01398 0.99985 -0.00984 0.01458 0.99986 -0.00841 0.01547 0.99985 -0.00726 0.01603 0.99986 -0.00521 0.01647 0.99985 -0.00446 0.01684 0.99986 -0.00177 0.01572 0.99988 0.00165 0.01506 0.99986 0.00672 0.68740 0.72228 -0.07613 0.01634 0.99987 0.00011 0.01633 0.99986 -0.00300 0.58113 0.80877 -0.09042 0.53871 0.84142 0.04248 0.27493 0.79940 -0.53420 0.28266 0.74141 -0.60862 0.01616 0.99986 0.00525 0.01502 0.99986 0.00802 0.01462 0.99986 0.00844 0.00680 0.99986 0.01556 0.00689 0.99986 0.01548 0.00933 0.99985 0.01427 0.00991 0.99986 0.01363 0.01160 0.99985 0.01254 0.01251 0.99986 0.01126 0.01352 0.99985 0.01043 0.01186 -0.99986 -0.01192 0.01398 -0.99985 -0.00984 0.01457 -0.99986 -0.00842 0.01547 -0.99985 -0.00726 0.01603 -0.99986 -0.00521 0.01647 -0.99985 -0.00446 0.01684 -0.99986 -0.00177 0.01520 -0.99987 -0.00572 0.01573 -0.99987 0.00165 0.01740 -0.99983 0.00683 0.01709 -0.99985 0.00300 0.01750 -0.99983 0.00568 0.01480 -0.99985 0.00855 0.01489 -0.99986 0.00794 0.01287 -0.99985 0.01159 0.01325 -0.99986 0.01022 0.01037 -0.99984 0.01427 0.01124 -0.99986 0.01216 0.00933 -0.99985 0.01427 0.91325 -0.39561 -0.09728 0.84105 -0.52604 -0.12613 0.78926 -0.60701 -0.09279 0.66360 -0.74401 -0.07801 0.59337 -0.79930 -0.09497 0.51613 -0.85524 -0.04663 0.99105 0.11258 -0.07178 0.95071 0.27410 -0.14499 0.01716 0.80299 -0.59575 0.03822 0.78970 -0.61230 0.07553 0.77517 -0.62722 0.03867 0.78385 -0.61975 0.94370 0.32976 0.02619 0.00000 0.19454 -0.98089 0.00000 0.35343 -0.93546 -1.00000 -0.00059 -0.00003 -1.00000 -0.00001 -0.00006 -1.00000 0.00182 0.00003 -1.00000 -0.00001 0.00011 -1.00000 -0.00116 0.00005 -0.36527 0.03145 0.93037 -0.17217 -0.03776 0.98434 0.00495 0.02519 0.99967 0.08047 -0.00910 0.99672 0.26345 0.00853 0.96464 0.32287 -0.01482 0.94633 0.48232 0.01089 0.87593 0.53692 -0.01160 0.84355 0.68298 0.00020 0.73043 0.70697 0.01756 0.70702 0.86223 0.02244 0.50602 0.84699 0.00157 0.53161 0.95795 -0.01567 0.28651 0.97465 -0.06454 0.21420 0.90187 0.03293 0.43075 0.86639 -0.03503 0.49814 0.76322 0.02282 0.64573 0.69250 -0.01974 0.72115 0.55842 0.02039 0.82931 0.48494 -0.01025 0.87449 0.26660 -0.00817 0.96377 0.32472 0.01522 0.94569 0.08066 0.00867 0.99670 0.00713 -0.02531 0.99965 -0.17237 0.03793 0.98430 -0.36502 -0.03199 0.93045 0.36527 -0.03146 0.93037 0.17216 0.03776 0.98435 -0.00495 -0.02519 0.99967 -0.08047 0.00910 0.99672 -0.26345 -0.00853 0.96464 -0.32289 0.01483 0.94632 -0.48232 -0.01087 0.87593 -0.53689 0.01160 0.84357 -0.68299 -0.00020 0.73043 -0.70698 -0.01757 0.70702 -0.86223 -0.02245 0.50601 -0.84699 -0.00157 0.53161 -0.95795 0.01566 0.28649 -0.97470 0.06523 0.21378 -0.90210 -0.03361 0.43023 -0.86636 0.03490 0.49819 -0.76326 -0.02290 0.64568 -0.69248 0.01969 0.72116 -0.55840 -0.02044 0.82932 -0.48492 0.01021 0.87450 -0.26660 0.00817 0.96377 -0.32477 -0.01524 0.94567 -0.08066 -0.00867 0.99670 -0.00713 0.02531 0.99965 0.17236 -0.03793 0.98430 0.36502 0.03199 0.93045 -0.03482 -0.36793 -0.92920 -0.20097 -0.42995 -0.88020 0.01380 -0.46884 -0.88318 -0.00681 -0.53767 -0.84313 -0.08527 -0.60194 -0.79397 0.79985 -0.39356 -0.45316 0.27119 -0.64396 -0.71538 0.07550 -0.68176 -0.72767 0.00718 -0.70281 -0.71135 0.00314 -0.64168 -0.76696 -0.00032 -0.68772 -0.72598 -0.04496 -0.74263 -0.66820 -0.00389 -0.72847 -0.68507 0.04387 -0.78368 -0.61962 0.06918 -0.77730 -0.62532 0.03512 -0.79133 -0.61038 0.01595 -0.80410 -0.59429 0.00894 -0.81231 -0.58316 -0.00000 -0.84144 -0.54036 -0.02572 -0.78358 -0.62076 -0.00610 -0.70315 -0.71101 0.00055 -0.75203 -0.65913 0.00002 -0.75715 -0.65324 -0.00661 -0.81282 -0.58248 -0.00927 -0.81847 -0.57447 -0.00547 -0.80640 -0.59134 -0.00063 -0.77545 -0.63141 0.00001 -0.83170 -0.55522 0.00844 -0.88587 -0.46385 0.04678 -0.86190 -0.50491 0.00027 -0.89631 -0.44344 -0.00428 -0.90848 -0.41790 0.00415 -0.95659 -0.29141 -0.00446 -0.97121 -0.23816 0.00433 -0.99405 -0.10883 -0.00463 -0.99875 -0.04979 0.00449 -0.99698 0.07753 -0.00478 -0.99009 0.14038 0.00463 -0.96528 0.26119 -0.00492 -0.94554 0.32546 0.00475 -0.90004 0.43578 -0.00503 -0.86673 0.49875 0.00486 -0.80354 0.59523 -0.00512 -0.75651 0.65397 0.00494 -0.67913 0.73400 -0.00520 -0.61887 0.78548 0.00501 -0.53113 0.84728 -0.00525 -0.45880 0.88852 0.00505 -0.36468 0.93112 -0.00529 -0.28210 0.95937 0.00508 -0.18556 0.98262 -0.00531 -0.09519 0.99545 0.00509 0.00000 0.99999 -0.00531 0.09519 0.99545 0.00508 0.18556 0.98262 -0.00529 0.28210 0.95937 0.00505 0.36468 0.93112 -0.00525 0.45880 0.88852 0.00501 0.53113 0.84728 -0.00520 0.61887 0.78548 0.00494 0.67913 0.73400 -0.00512 0.75651 0.65397 0.00486 0.80354 0.59523 -0.00503 0.86673 0.49875 0.00475 0.90004 0.43578 -0.00492 0.94554 0.32546 0.00463 0.96528 0.26119 -0.00478 0.99009 0.14038 0.00449 0.99698 0.07753 -0.00463 0.99875 -0.04979 0.00433 0.99405 -0.10883 -0.00446 0.97121 -0.23816 0.00415 0.95659 -0.29141 -0.00428 0.90848 -0.41790 0.00911 0.88587 -0.46385 0.00223 0.89084 -0.45432 0.00699 0.87717 -0.48014 -0.00210 0.81283 -0.58249 -0.01778 0.78442 -0.61998 -0.00873 0.80742 -0.58992 -0.00138 0.83795 -0.54575 0.00178 0.84372 -0.53678 0.00642 0.81498 -0.57945 0.00379 0.82076 -0.57125 0.00056 0.75227 -0.65886 0.00002 0.75727 -0.65311 -0.01789 0.68761 -0.72586 -0.00017 0.71789 -0.69616 -0.00596 0.70312 -0.71104 -0.02600 0.78362 -0.62069 -0.00222 0.72810 -0.68547 0.81263 0.38213 -0.44001 0.29066 0.63961 -0.71163 0.09412 0.67880 -0.72826 0.00314 0.64164 -0.76700 -0.03556 0.53734 -0.84262 -0.00425 0.56554 -0.82471 0.01379 0.46886 -0.88317 -0.09912 0.36634 -0.92519 -0.02762 0.38325 -0.92323 -0.02688 -0.18627 -0.98213 -0.14677 -0.36417 -0.91970 0.04336 -0.34955 -0.93591 -0.01380 -0.46884 -0.88318 0.03556 -0.53734 -0.84262 0.00424 -0.56554 -0.82471 -0.80318 -0.39063 -0.44979 -0.27622 -0.64286 -0.71445 -0.07857 -0.68121 -0.72786 -0.00840 -0.70209 -0.71204 -0.00314 -0.64168 -0.76696 0.01789 -0.68761 -0.72586 0.00018 -0.71792 -0.69613 0.00286 -0.72476 -0.68899 -0.03089 -0.78406 -0.61992 -0.00293 -0.82941 -0.55863 -0.34197 -0.87867 -0.33316 -0.11643 -0.81859 -0.56245 0.02600 -0.78362 -0.62069 0.00596 -0.70312 -0.71104 -0.00056 -0.75227 -0.65885 -0.00002 -0.75727 -0.65310 0.00210 -0.81283 -0.58249 0.01778 -0.78442 -0.61998 0.00873 -0.80742 -0.58992 0.00138 -0.83795 -0.54575 -0.00911 -0.88587 -0.46385 -0.00223 -0.89084 -0.45432 -0.00683 -0.87649 -0.48137 -0.00173 -0.84413 -0.53614 0.00428 -0.90848 -0.41790 -0.00415 -0.95659 -0.29141 0.00446 -0.97121 -0.23816 -0.00433 -0.99405 -0.10883 0.00463 -0.99875 -0.04979 -0.00449 -0.99698 0.07753 0.00478 -0.99009 0.14038 -0.00463 -0.96528 0.26119 0.00492 -0.94554 0.32546 -0.00475 -0.90004 0.43578 0.00503 -0.86673 0.49875 -0.00486 -0.80354 0.59523 0.00512 -0.75651 0.65396 -0.00494 -0.67913 0.73400 0.00520 -0.61887 0.78548 -0.00501 -0.53113 0.84728 0.00525 -0.45880 0.88852 -0.00506 -0.36468 0.93112 0.00529 -0.28210 0.95937 -0.00508 -0.18556 0.98262 0.00531 -0.09519 0.99545 -0.00509 0.00000 0.99999 0.00531 0.09519 0.99545 -0.00508 0.18556 0.98262 0.00529 0.28210 0.95937 -0.00506 0.36468 0.93112 0.00525 0.45880 0.88852 -0.00501 0.53113 0.84728 0.00520 0.61887 0.78548 -0.00494 0.67913 0.73400 0.00512 0.75651 0.65397 -0.00486 0.80354 0.59523 0.00503 0.86673 0.49875 -0.00475 0.90004 0.43578 0.00492 0.94554 0.32546 -0.00463 0.96528 0.26119 0.00478 0.99009 0.14038 -0.00449 0.99698 0.07753 0.00463 0.99875 -0.04979 -0.00433 0.99405 -0.10883 0.00446 0.97121 -0.23816 -0.00415 0.95659 -0.29141 0.00428 0.90848 -0.41790 -0.00843 0.88587 -0.46385 -0.04636 0.86225 -0.50436 -0.00027 0.89631 -0.44343 0.00662 0.81282 -0.58248 0.00926 0.81843 -0.57453 0.00547 0.80640 -0.59134 0.00063 0.77545 -0.63141 -0.00005 0.83149 -0.55554 -0.03999 0.78381 -0.61972 -0.07421 0.77562 -0.62682 -0.03783 0.78992 -0.61204 -0.01720 0.80299 -0.59575 -0.00952 0.81155 -0.58420 0.00002 0.84114 -0.54082 -0.00055 0.75203 -0.65913 -0.00002 0.75714 -0.65325 0.00032 0.68772 -0.72598 0.04491 0.74257 -0.66826 0.00610 0.70316 -0.71101 0.02572 0.78358 -0.62076 0.00465 0.72532 -0.68840 -0.80926 0.38520 -0.44353 -0.27998 0.64195 -0.71380 -0.00936 0.70328 -0.71086 -0.00314 0.64164 -0.76700 0.00682 0.53767 -0.84313 0.08527 0.60194 -0.79398 -0.01379 0.46886 -0.88317 0.03480 0.36793 -0.92920 0.34049 -0.94025 0.00054 0.19600 -0.98039 -0.02028 0.18490 -0.98260 -0.01730 -0.02176 -0.99976 0.00210 0.06177 -0.99809 -0.00134 -0.18694 -0.98236 -0.00396 -0.15842 -0.98737 -0.00106 -0.01721 -0.99985 0.00212 -0.30356 -0.95281 0.00157 -0.42286 -0.90620 -0.00092 -0.45111 -0.89244 -0.00618 -0.63482 -0.77264 -0.00547 -0.60572 -0.79568 -0.00139 -0.71193 -0.70225 0.00167 -0.80791 -0.58931 -0.00061 -0.82973 -0.55809 -0.00925 -0.90215 -0.43142 -0.00005 -0.96736 -0.25093 -0.03518 -0.94470 -0.32765 -0.01338 -0.97672 -0.21321 -0.02388 -0.99790 -0.06474 0.00122 -0.31846 -0.94794 -0.00016 -0.33754 -0.94130 -0.00448 -0.23083 -0.97299 0.00271 -0.06843 -0.99765 -0.00373 -0.07245 -0.99736 -0.00434 -0.00682 -0.99998 0.00064 0.09367 -0.99560 0.00174 0.18217 -0.98327 -0.00026 0.13090 -0.99137 -0.00663 0.29065 -0.95683 0.00076 0.42336 -0.90596 -0.00269 0.39087 -0.92042 -0.00720 0.52456 -0.85137 0.00084 0.63479 -0.77267 -0.00390 0.61239 -0.79052 -0.00774 0.69745 -0.71663 0.00002 0.80804 -0.58912 -0.00166 0.76504 -0.64382 -0.01435 0.84115 -0.54080 -0.00111 0.90029 -0.43528 -0.00032 0.92873 -0.37065 -0.00849 0.94712 -0.32087 -0.00117 0.98061 -0.19596 0.00033 0.99205 -0.12537 -0.01069 0.99778 -0.06666 -0.00057 0.32250 0.94657 -0.00007 0.33781 0.94121 -0.00354 0.23142 0.97285 0.00364 0.06278 0.99802 -0.00301 0.07235 0.99737 -0.00444 0.00652 0.99998 0.00045 -0.09498 0.99548 0.00148 -0.18045 0.98358 -0.00048 -0.13177 0.99126 -0.00651 -0.29289 0.95615 0.00079 -0.42264 0.90629 -0.00282 -0.39459 0.91883 -0.00665 -0.53028 0.84782 0.00102 -0.63450 0.77291 -0.00421 -0.62037 0.78428 -0.00655 -0.70591 0.70830 0.00052 -0.80765 0.58966 -0.00253 -0.77455 0.63240 -0.01191 -0.84850 0.52920 -0.00012 -0.92892 0.37028 -0.00108 -0.90617 0.42268 -0.01397 -0.97846 0.20642 0.00241 -0.99204 0.12550 -0.01058 -0.99789 0.06487 -0.00040 -0.33892 0.94081 -0.00463 -0.33691 0.94152 -0.00493 -0.19894 0.98000 0.00410 -0.06835 0.99766 0.00152 0.06944 0.99737 -0.02058 -0.05851 0.99828 -0.00412 0.18077 0.98351 -0.00444 0.15865 0.98733 -0.00218 0.02216 0.99975 0.00095 0.30613 0.95199 0.00136 0.42117 0.90698 -0.00277 0.44349 0.89626 -0.00615 0.54157 0.84065 0.00054 0.63478 0.77268 -0.00532 0.62230 0.78277 -0.00342 0.70719 0.70703 0.00066 0.80697 0.59056 -0.00668 0.78238 0.62280 -0.00177 0.85973 0.51074 0.00191 0.92938 0.36912 -0.00027 0.94263 0.33365 -0.01100 0.98192 0.18931 -0.00020 0.99213 0.12523 -0.00049 0.99682 0.07758 -0.01825 -0.50725 0.86179 -0.00470 -0.45677 0.88900 -0.03232 -0.51241 0.85867 -0.01099 -0.56287 0.82655 -0.00059 -0.64245 0.76633 0.00115 -0.66589 0.74596 -0.01147 -0.74016 0.67239 0.00690 -0.79296 0.60905 -0.01677 -0.81693 0.57673 0.00246 -0.89256 0.45091 -0.00387 -0.87127 0.48848 -0.04762 -0.94060 0.33878 0.02242 -0.95846 0.27675 -0.06901 0.45917 0.88835 -0.00006 0.51555 0.85686 -0.00157 0.57094 0.82044 -0.03009 0.51219 0.85882 -0.00908 0.64245 0.76633 0.00115 0.66591 0.74594 -0.01143 0.74015 0.67241 0.00687 0.79297 0.60904 -0.01671 0.81693 0.57673 0.00245 0.89226 0.45054 -0.02969 0.88249 0.47033 -0.00291 0.51627 -0.85643 0.00036 0.45680 -0.88900 -0.03190 0.51240 -0.85868 -0.01086 0.56287 -0.82655 -0.00059 0.64240 -0.76637 0.00114 0.66591 -0.74595 -0.01131 0.74001 -0.67256 0.00665 0.79275 -0.60932 -0.01663 0.81691 -0.57676 0.00241 0.88251 -0.47028 -0.00285 -0.45917 -0.88835 -0.00014 -0.51541 -0.85694 -0.00158 -0.57098 -0.82041 -0.03023 -0.51220 -0.85882 -0.00918 -0.64241 -0.76636 0.00115 -0.66590 -0.74596 -0.01148 -0.74008 -0.67248 0.00681 -0.79279 -0.60926 -0.01689 -0.81693 -0.57673 0.00247 -0.89211 -0.45086 -0.02945 -0.88249 -0.47032 -0.00293 -0.94061 -0.33876 0.02242 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00001 -0.00047 1.00000 0.00000 -0.00056 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00039 -1.00000 0.00025 0.00122 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00004 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00047 -0.00002 1.00000 0.00000 -0.00004 1.00000 0.00042 -0.00002 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 -0.37891 -0.18191 -0.90738 0.06951 -0.25037 -0.96565 0.06953 0.25037 -0.96565 -0.44514 0.16704 -0.87974 -0.97863 0.19743 0.05752 -0.98789 0.08957 -0.12668 -0.95846 -0.27675 -0.06899 -0.97863 -0.19744 0.05752 -0.98833 -0.09335 -0.12041 + + + + + + + + + + + + + + +

253 0 61 0 63 0 255 1 59 1 61 1 180 2 173 2 175 2 179 3 175 3 172 3 180 4 175 4 179 4 178 5 172 5 177 5 178 6 177 6 176 6 245 7 56 7 243 7 243 8 56 8 241 8 241 9 56 9 53 9 241 10 53 10 239 10 239 11 53 11 237 11 237 12 53 12 52 12 237 13 52 13 235 13 235 14 52 14 49 14 235 15 49 15 233 15 233 16 49 16 48 16 233 17 48 17 47 17 233 18 47 18 225 18 225 19 47 19 46 19 225 20 46 20 103 20 103 21 46 21 50 21 103 22 50 22 102 22 267 23 102 23 50 23 267 24 50 24 51 24 271 25 267 25 51 25 271 26 51 26 54 26 271 27 54 27 263 27 263 28 54 28 261 28 261 29 54 29 55 29 261 30 55 30 259 30 262 31 260 31 37 31 266 32 262 32 37 32 266 33 37 33 40 33 266 34 40 34 264 34 264 35 40 35 42 35 264 36 42 36 130 36 222 37 130 37 42 37 222 38 42 38 43 38 223 39 222 39 43 39 223 40 43 40 45 40 228 41 223 41 45 41 228 42 45 42 44 42 234 43 228 43 44 43 234 44 44 44 41 44 236 45 234 45 41 45 236 46 41 46 39 46 238 47 236 47 39 47 238 48 39 48 38 48 240 49 238 49 38 49 242 50 240 50 38 50 234 51 0 51 230 51 230 52 0 52 231 52 0 53 235 53 231 53 0 54 234 54 236 54 235 55 0 55 236 55 235 56 233 56 231 56 221 57 219 57 220 57 220 58 219 58 218 58 382 59 381 59 380 59 381 60 365 60 198 60 365 61 196 61 198 61 382 62 365 62 381 62 382 63 366 63 365 63 208 64 143 64 140 64 208 65 140 65 204 65 383 66 365 66 366 66 367 67 383 67 366 67 384 68 383 68 367 68 351 69 350 69 349 69 352 70 350 70 351 70 353 71 352 71 351 71 354 72 352 72 353 72 355 73 354 73 353 73 27 74 29 74 348 74 347 75 348 75 29 75 29 76 31 76 347 76 346 77 347 77 31 77 31 78 33 78 346 78 345 79 346 79 33 79 33 80 35 80 345 80 343 81 345 81 35 81 35 82 38 82 343 82 341 83 343 83 38 83 38 84 39 84 341 84 339 85 341 85 39 85 39 86 41 86 339 86 333 87 339 87 41 87 41 88 44 88 333 88 330 89 333 89 44 89 44 90 45 90 330 90 327 91 330 91 45 91 334 92 336 92 4 92 2 93 4 93 336 93 336 94 337 94 2 94 1 95 2 95 337 95 337 96 338 96 1 96 3 97 1 97 338 97 338 98 335 98 3 98 5 99 3 99 335 99 335 100 332 100 5 100 7 101 5 101 332 101 332 102 331 102 7 102 9 103 7 103 331 103 331 104 329 104 9 104 11 105 9 105 329 105 329 106 328 106 11 106 13 107 11 107 326 107 11 108 328 108 326 108 326 109 324 109 13 109 15 110 13 110 324 110 324 111 323 111 15 111 17 112 15 112 323 112 323 113 321 113 17 113 19 114 17 114 321 114 321 115 320 115 19 115 21 116 19 116 320 116 320 117 318 117 21 117 23 118 21 118 318 118 318 119 315 119 23 119 24 120 23 120 315 120 315 121 312 121 24 121 26 122 24 122 312 122 312 123 314 123 26 123 25 124 26 124 314 124 314 125 317 125 25 125 1 126 3 126 2 126 4 127 2 127 3 127 3 128 5 128 4 128 6 129 4 129 5 129 5 130 7 130 6 130 8 131 6 131 7 131 7 132 9 132 8 132 10 133 8 133 9 133 9 134 11 134 10 134 12 135 10 135 11 135 11 136 13 136 12 136 14 137 12 137 13 137 13 138 15 138 14 138 16 139 14 139 15 139 15 140 17 140 16 140 18 141 16 141 17 141 17 142 19 142 18 142 20 143 18 143 19 143 19 144 21 144 20 144 22 145 20 145 21 145 21 146 23 146 22 146 25 147 22 147 23 147 23 148 24 148 25 148 26 149 25 149 24 149 45 150 43 150 327 150 43 151 325 151 327 151 322 152 325 152 43 152 43 153 42 153 322 153 319 154 322 154 42 154 42 155 40 155 319 155 313 156 319 156 40 156 40 157 37 157 313 157 310 158 313 158 37 158 37 159 36 159 310 159 308 160 310 160 36 160 36 161 34 161 308 161 306 162 308 162 34 162 34 163 32 163 306 163 304 164 306 164 32 164 32 165 30 165 304 165 305 166 304 166 30 166 30 167 28 167 305 167 29 168 27 168 250 168 28 169 30 169 252 169 250 170 248 170 29 170 254 171 252 171 30 171 31 172 29 172 248 172 30 173 32 173 254 173 248 174 246 174 31 174 246 175 33 175 31 175 256 176 254 176 32 176 258 177 256 177 34 177 256 178 32 178 34 178 246 179 244 179 33 179 35 180 33 180 244 180 34 181 36 181 258 181 260 182 258 182 36 182 244 183 242 183 35 183 242 184 38 184 35 184 36 185 37 185 260 185 63 186 61 186 303 186 302 187 303 187 61 187 61 188 59 188 302 188 301 189 302 189 59 189 59 190 57 190 301 190 300 191 301 191 57 191 57 192 55 192 300 192 298 193 300 193 55 193 55 194 54 194 298 194 296 195 298 195 54 195 54 196 51 196 296 196 294 197 296 197 51 197 51 198 50 198 294 198 292 199 294 199 50 199 50 200 46 200 292 200 290 201 292 201 46 201 46 202 47 202 290 202 288 203 290 203 47 203 47 204 48 204 288 204 48 205 286 205 288 205 284 206 286 206 48 206 48 207 49 207 284 207 282 208 284 208 49 208 49 209 52 209 282 209 280 210 282 210 52 210 52 211 53 211 280 211 278 212 280 212 53 212 53 213 56 213 278 213 276 214 278 214 56 214 56 215 58 215 276 215 274 216 276 216 58 216 58 217 60 217 274 217 272 218 274 218 60 218 60 219 62 219 272 219 273 220 272 220 62 220 62 221 64 221 273 221 245 222 247 222 56 222 257 223 259 223 57 223 259 224 55 224 57 224 58 225 56 225 247 225 57 226 59 226 257 226 247 227 249 227 58 227 249 228 60 228 58 228 255 229 257 229 59 229 62 230 60 230 249 230 253 231 255 231 61 231 249 232 251 232 62 232 64 233 62 233 251 233 189 234 110 234 193 234 110 235 65 235 193 235 67 236 65 236 110 236 110 237 115 237 67 237 66 238 67 238 115 238 115 239 118 239 66 239 72 240 66 240 118 240 118 241 123 241 72 241 74 242 72 242 123 242 123 243 125 243 74 243 224 244 74 244 125 244 125 245 222 245 224 245 223 246 224 246 222 246 193 247 65 247 192 247 69 248 195 248 192 248 195 249 69 249 377 249 65 250 67 250 192 250 75 251 377 251 69 251 192 252 68 252 69 252 68 253 192 253 67 253 67 254 66 254 68 254 70 255 68 255 66 255 68 256 70 256 69 256 69 257 71 257 75 257 71 258 69 258 70 258 66 259 72 259 70 259 76 260 75 260 71 260 73 261 70 261 72 261 70 262 73 262 71 262 71 263 229 263 76 263 229 264 71 264 73 264 72 265 74 265 73 265 230 266 76 266 229 266 73 267 227 267 229 267 227 268 73 268 74 268 74 269 224 269 227 269 377 270 75 270 379 270 79 271 379 271 75 271 75 272 76 272 79 272 80 273 79 273 76 273 76 274 230 274 80 274 231 275 80 275 230 275 77 276 221 276 379 276 221 277 77 277 219 277 78 278 219 278 77 278 219 279 78 279 218 279 83 280 218 280 78 280 379 281 79 281 77 281 84 282 83 282 78 282 81 283 77 283 79 283 77 284 81 284 78 284 82 285 78 285 81 285 78 286 82 286 84 286 79 287 80 287 81 287 85 288 84 288 82 288 80 289 231 289 81 289 232 290 81 290 231 290 81 291 232 291 82 291 226 292 82 292 232 292 82 293 226 293 85 293 86 294 85 294 226 294 86 295 226 295 87 295 218 296 83 296 216 296 89 297 216 297 83 297 83 298 84 298 89 298 94 299 89 299 84 299 84 300 85 300 94 300 85 301 100 301 94 301 85 302 86 302 100 302 86 303 87 303 100 303 103 304 100 304 87 304 225 305 103 305 87 305 150 306 88 306 151 306 88 307 150 307 152 307 91 308 152 308 216 308 152 309 91 309 88 309 151 310 90 310 362 310 90 311 151 311 88 311 216 312 89 312 91 312 106 313 362 313 90 313 88 314 93 314 90 314 93 315 88 315 91 315 89 316 94 316 91 316 92 317 90 317 93 317 90 318 92 318 106 318 95 319 91 319 94 319 91 320 95 320 93 320 107 321 106 321 92 321 96 322 92 322 93 322 92 323 96 323 107 323 93 324 97 324 96 324 97 325 93 325 95 325 94 326 100 326 95 326 101 327 95 327 100 327 95 328 101 328 97 328 108 329 107 329 96 329 96 330 98 330 108 330 98 331 96 331 97 331 99 332 97 332 101 332 97 333 99 333 98 333 98 334 104 334 108 334 104 335 98 335 99 335 99 336 105 336 104 336 105 337 99 337 101 337 100 338 103 338 101 338 101 339 103 339 102 339 109 340 108 340 104 340 101 341 102 341 105 341 102 342 267 342 105 342 268 343 104 343 105 343 104 344 268 344 109 344 269 345 109 345 268 345 105 346 267 346 268 346 362 347 106 347 364 347 111 348 364 348 106 348 106 349 107 349 111 349 121 350 111 350 107 350 107 351 108 351 121 351 124 352 121 352 108 352 108 353 109 353 124 353 127 354 124 354 109 354 109 355 269 355 127 355 270 356 127 356 269 356 110 357 189 357 171 357 171 358 112 358 110 358 112 359 171 359 168 359 170 360 113 360 168 360 113 361 170 361 364 361 168 362 114 362 112 362 114 363 168 363 113 363 364 364 111 364 113 364 115 365 110 365 112 365 111 366 121 366 113 366 116 367 112 367 114 367 112 368 116 368 115 368 119 369 113 369 121 369 113 370 119 370 114 370 114 371 117 371 116 371 117 372 114 372 119 372 118 373 115 373 116 373 120 374 116 374 117 374 116 375 120 375 118 375 122 376 117 376 119 376 117 377 122 377 120 377 123 378 118 378 120 378 126 379 119 379 121 379 119 380 126 380 122 380 120 381 128 381 123 381 128 382 120 382 122 382 121 383 124 383 126 383 129 384 122 384 126 384 122 385 129 385 128 385 125 386 123 386 128 386 124 387 127 387 126 387 128 388 130 388 125 388 130 389 222 389 125 389 131 390 126 390 127 390 126 391 131 391 129 391 127 392 270 392 131 392 130 393 128 393 129 393 264 394 129 394 131 394 129 395 264 395 130 395 270 396 265 396 131 396 131 397 265 397 264 397 201 398 202 398 132 398 202 399 133 399 132 399 139 400 133 400 202 400 133 401 139 401 134 401 139 402 136 402 134 402 136 403 141 403 135 403 141 404 138 404 135 404 141 405 136 405 139 405 351 406 349 406 137 406 137 407 138 407 351 407 138 408 142 408 351 408 142 409 138 409 141 409 202 410 203 410 139 410 139 411 140 411 141 411 139 412 204 412 140 412 139 413 203 413 204 413 353 414 351 414 142 414 144 415 141 415 143 415 141 416 140 416 143 416 141 417 144 417 142 417 142 418 145 418 353 418 145 419 355 419 353 419 145 420 142 420 144 420 357 421 355 421 145 421 143 422 146 422 144 422 146 423 143 423 210 423 210 424 143 424 208 424 147 425 144 425 146 425 144 426 147 426 145 426 148 427 145 427 147 427 145 428 148 428 357 428 148 429 359 429 357 429 210 430 211 430 146 430 149 431 146 431 214 431 146 432 211 432 214 432 146 433 149 433 147 433 361 434 359 434 148 434 147 435 150 435 148 435 150 436 151 436 148 436 150 437 147 437 149 437 148 438 151 438 361 438 214 439 215 439 149 439 152 440 149 440 215 440 152 441 150 441 149 441 361 442 151 442 362 442 216 443 152 443 215 443 178 444 176 444 153 444 153 445 155 445 178 445 162 446 155 446 160 446 155 447 154 447 160 447 154 448 156 448 160 448 155 449 162 449 178 449 160 450 156 450 157 450 157 451 159 451 160 451 350 452 352 452 158 452 352 453 159 453 158 453 159 454 161 454 160 454 161 455 159 455 352 455 352 456 354 456 161 456 181 457 178 457 162 457 160 458 163 458 162 458 163 459 160 459 161 459 164 460 161 460 356 460 161 461 354 461 356 461 161 462 164 462 163 462 165 463 162 463 163 463 162 464 165 464 181 464 165 465 182 465 181 465 356 466 358 466 164 466 185 467 182 467 165 467 166 468 163 468 164 468 163 469 166 469 165 469 167 470 164 470 360 470 164 471 358 471 360 471 164 472 167 472 166 472 165 473 169 473 185 473 169 474 188 474 185 474 169 475 165 475 166 475 360 476 363 476 167 476 190 477 188 477 169 477 168 478 166 478 170 478 166 479 167 479 170 479 166 480 168 480 169 480 170 481 167 481 363 481 169 482 171 482 190 482 169 483 168 483 171 483 363 484 364 484 170 484 189 485 190 485 171 485 179 486 172 486 178 486 178 487 181 487 179 487 179 488 183 488 180 488 183 489 179 489 181 489 184 490 180 490 183 490 180 491 184 491 366 491 184 492 367 492 366 492 181 493 182 493 183 493 368 494 367 494 184 494 186 495 183 495 185 495 183 496 182 496 185 496 183 497 186 497 184 497 187 498 184 498 186 498 184 499 187 499 368 499 187 500 370 500 368 500 185 501 188 501 186 501 372 502 370 502 187 502 186 503 191 503 187 503 191 504 186 504 188 504 187 505 194 505 372 505 194 506 374 506 372 506 194 507 187 507 191 507 188 508 190 508 191 508 191 509 189 509 193 509 191 510 190 510 189 510 191 511 193 511 194 511 376 512 374 512 194 512 195 513 194 513 192 513 194 514 193 514 192 514 194 515 195 515 376 515 377 516 376 516 195 516 196 517 206 517 197 517 206 518 199 518 197 518 206 519 205 519 199 519 206 520 196 520 365 520 199 521 205 521 200 521 205 522 201 522 200 522 205 523 202 523 201 523 205 524 203 524 202 524 204 525 203 525 205 525 205 526 207 526 204 526 207 527 208 527 204 527 207 528 205 528 206 528 206 529 209 529 207 529 206 530 384 530 209 530 384 531 369 531 209 531 212 532 207 532 209 532 207 533 212 533 208 533 212 534 210 534 208 534 209 535 213 535 212 535 213 536 209 536 371 536 209 537 369 537 371 537 211 538 210 538 212 538 371 539 373 539 213 539 212 540 217 540 211 540 217 541 214 541 211 541 217 542 212 542 213 542 213 543 220 543 217 543 220 544 213 544 375 544 213 545 373 545 375 545 215 546 214 546 217 546 217 547 218 547 215 547 218 548 216 548 215 548 218 549 217 549 220 549 375 550 378 550 220 550 221 551 220 551 378 551 378 552 379 552 221 552 223 553 228 553 224 553 228 554 227 554 224 554 233 555 225 555 226 555 225 556 87 556 226 556 226 557 232 557 233 557 229 558 227 558 228 558 228 559 234 559 229 559 234 560 230 560 229 560 233 561 232 561 231 561 237 562 235 562 236 562 236 563 238 563 237 563 239 564 237 564 238 564 238 565 240 565 239 565 241 566 239 566 240 566 240 567 242 567 241 567 243 568 241 568 242 568 242 569 244 569 243 569 245 570 243 570 244 570 244 571 246 571 245 571 247 572 245 572 246 572 246 573 248 573 247 573 249 574 247 574 248 574 248 575 250 575 249 575 251 576 249 576 250 576 252 577 254 577 253 577 255 578 253 578 254 578 254 579 256 579 255 579 257 580 255 580 256 580 256 581 258 581 257 581 259 582 257 582 258 582 258 583 260 583 259 583 261 584 259 584 260 584 260 585 262 585 261 585 263 586 261 586 262 586 262 587 266 587 263 587 271 588 263 588 266 588 266 589 264 589 265 589 265 590 270 590 266 590 270 591 271 591 266 591 271 592 268 592 267 592 271 593 269 593 268 593 271 594 270 594 269 594 274 595 272 595 273 595 273 596 275 596 274 596 276 597 274 597 275 597 275 598 277 598 276 598 278 599 276 599 277 599 277 600 279 600 278 600 280 601 278 601 279 601 279 602 281 602 280 602 282 603 280 603 281 603 281 604 283 604 282 604 284 605 282 605 283 605 283 606 285 606 284 606 286 607 284 607 285 607 285 608 287 608 286 608 288 609 286 609 287 609 287 610 289 610 288 610 290 611 288 611 289 611 289 612 291 612 290 612 292 613 290 613 291 613 291 614 293 614 292 614 294 615 292 615 293 615 293 616 295 616 294 616 296 617 294 617 295 617 295 618 297 618 296 618 298 619 296 619 297 619 297 620 299 620 298 620 300 621 298 621 299 621 299 622 303 622 300 622 301 623 300 623 303 623 303 624 302 624 301 624 306 625 304 625 305 625 305 626 307 626 306 626 308 627 306 627 307 627 307 628 309 628 308 628 310 629 308 629 309 629 309 630 311 630 310 630 313 631 310 631 311 631 316 632 312 632 313 632 319 633 313 633 315 633 313 634 312 634 315 634 315 635 318 635 319 635 322 636 319 636 320 636 319 637 318 637 320 637 320 638 321 638 322 638 325 639 322 639 323 639 322 640 321 640 323 640 323 641 324 641 325 641 327 642 325 642 326 642 325 643 324 643 326 643 326 644 328 644 327 644 330 645 327 645 328 645 328 646 329 646 330 646 333 647 330 647 331 647 330 648 329 648 331 648 331 649 332 649 333 649 339 650 333 650 335 650 333 651 332 651 335 651 335 652 338 652 339 652 341 653 339 653 340 653 339 654 337 654 340 654 339 655 338 655 337 655 340 656 342 656 341 656 343 657 341 657 342 657 342 658 344 658 343 658 345 659 343 659 344 659 344 660 348 660 345 660 346 661 345 661 348 661 348 662 347 662 346 662 356 663 354 663 355 663 355 664 357 664 356 664 358 665 356 665 357 665 357 666 359 666 358 666 360 667 358 667 359 667 359 668 361 668 360 668 363 669 360 669 361 669 361 670 362 670 363 670 364 671 363 671 362 671 368 672 384 672 367 672 369 673 384 673 368 673 368 674 370 674 369 674 371 675 369 675 370 675 370 676 372 676 371 676 373 677 371 677 372 677 372 678 374 678 373 678 375 679 373 679 374 679 374 680 376 680 375 680 378 681 375 681 376 681 376 682 377 682 378 682 379 683 378 683 377 683 173 684 180 684 174 684 180 685 380 685 174 685 180 686 382 686 380 686 366 687 382 687 180 687 365 688 383 688 206 688 383 689 384 689 206 689 389 690 391 690 390 690 392 691 390 691 391 691 391 692 393 692 392 692 394 693 392 693 393 693 393 694 395 694 394 694 396 695 394 695 395 695 395 696 397 696 396 696 398 697 396 697 397 697 397 698 399 698 398 698 400 699 398 699 399 699 399 700 401 700 400 700 402 701 400 701 401 701 401 702 403 702 402 702 404 703 402 703 403 703 403 704 405 704 404 704 406 705 404 705 405 705 413 706 411 706 412 706 412 707 414 707 413 707 415 708 413 708 414 708 414 709 416 709 415 709 417 710 415 710 416 710 416 711 418 711 417 711 419 712 417 712 418 712 418 713 420 713 419 713 421 714 419 714 420 714 420 715 422 715 421 715 421 716 422 716 423 716 424 717 421 717 423 717 340 718 337 718 336 718 425 719 340 719 336 719 336 720 334 720 425 720 425 721 334 721 426 721 427 722 425 722 426 722 426 723 428 723 427 723 427 724 428 724 429 724 430 725 427 725 429 725 429 726 431 726 430 726 430 727 431 727 432 727 433 728 430 728 432 728 432 729 434 729 433 729 435 730 433 730 434 730 434 731 436 731 435 731 435 732 436 732 437 732 438 733 435 733 437 733 437 734 439 734 438 734 438 735 439 735 317 735 316 736 438 736 317 736 317 737 314 737 316 737 316 738 314 738 312 738 311 739 316 739 313 739 253 740 440 740 252 740 441 741 252 741 440 741 440 742 442 742 441 742 443 743 441 743 442 743 442 744 444 744 443 744 445 745 443 745 444 745 444 746 446 746 445 746 447 747 445 747 446 747 446 748 448 748 447 748 449 749 447 749 448 749 448 750 450 750 449 750 451 751 449 751 450 751 452 752 451 752 450 752 453 753 452 753 450 753 451 754 452 754 454 754 451 755 454 755 455 755 456 756 451 756 455 756 457 757 458 757 459 757 460 758 461 758 462 758 462 759 463 759 460 759 464 760 465 760 459 760 458 761 464 761 459 761 466 762 460 762 463 762 467 763 465 763 464 763 463 764 468 764 466 764 469 765 470 765 471 765 469 766 471 766 472 766 469 767 472 767 467 767 464 768 469 768 467 768 466 769 468 769 473 769 470 770 469 770 474 770 473 771 470 771 474 771 474 772 466 772 473 772 469 773 475 773 474 773 476 774 474 774 475 774 475 775 477 775 476 775 478 776 476 776 477 776 477 777 479 777 478 777 480 778 478 778 479 778 479 779 251 779 480 779 250 780 480 780 251 780 482 781 385 781 481 781 385 782 387 782 481 782 489 783 385 783 482 783 487 784 490 784 488 784 389 785 385 785 489 785 491 786 488 786 490 786 488 787 491 787 489 787 492 788 489 788 491 788 492 789 391 789 389 789 489 790 492 790 389 790 490 791 493 791 491 791 393 792 391 792 492 792 491 793 494 793 492 793 491 794 493 794 495 794 494 795 491 795 495 795 492 796 496 796 393 796 496 797 492 797 494 797 395 798 393 798 496 798 495 799 497 799 494 799 494 800 497 800 498 800 499 801 494 801 498 801 494 802 499 802 496 802 500 803 397 803 395 803 496 804 500 804 395 804 500 805 496 805 499 805 498 806 501 806 499 806 399 807 397 807 500 807 499 808 501 808 502 808 503 809 499 809 502 809 499 810 503 810 500 810 502 811 504 811 503 811 505 812 401 812 399 812 500 813 505 813 399 813 505 814 500 814 503 814 403 815 401 815 505 815 503 816 504 816 506 816 503 817 506 817 507 817 508 818 503 818 507 818 503 819 508 819 505 819 505 820 509 820 403 820 505 821 508 821 510 821 509 822 505 822 510 822 403 823 509 823 405 823 516 824 517 824 515 824 516 825 515 825 514 825 513 826 516 826 514 826 518 827 516 827 513 827 518 828 513 828 512 828 511 829 518 829 512 829 518 830 511 830 388 830 519 831 517 831 516 831 388 832 390 832 518 832 520 833 516 833 518 833 520 834 521 834 519 834 516 835 520 835 519 835 518 836 390 836 392 836 522 837 518 837 392 837 518 838 522 838 520 838 523 839 521 839 520 839 392 840 394 840 522 840 524 841 520 841 522 841 524 842 525 842 523 842 520 843 524 843 523 843 526 844 522 844 394 844 522 845 526 845 524 845 394 846 396 846 526 846 527 847 525 847 524 847 524 848 528 848 527 848 528 849 524 849 526 849 529 850 527 850 528 850 526 851 530 851 528 851 526 852 396 852 398 852 530 853 526 853 398 853 398 854 400 854 530 854 531 855 532 855 529 855 528 856 531 856 529 856 531 857 528 857 530 857 533 858 532 858 531 858 530 859 534 859 531 859 530 860 400 860 402 860 534 861 530 861 402 861 402 862 404 862 534 862 535 863 531 863 534 863 538 864 534 864 404 864 404 865 406 865 538 865 517 866 540 866 541 866 515 867 517 867 541 867 542 868 543 868 410 868 410 869 408 869 542 869 543 870 544 870 410 870 545 871 544 871 543 871 545 872 543 872 546 872 547 873 545 873 546 873 548 874 545 874 547 874 548 875 547 875 549 875 540 876 548 876 549 876 548 877 540 877 517 877 517 878 519 878 548 878 412 879 410 879 544 879 550 880 544 880 545 880 550 881 414 881 412 881 544 882 550 882 412 882 551 883 545 883 548 883 545 884 551 884 550 884 548 885 552 885 551 885 548 886 519 886 521 886 552 887 548 887 521 887 521 888 523 888 552 888 416 889 414 889 550 889 553 890 550 890 551 890 550 891 553 891 416 891 554 892 551 892 552 892 551 893 554 893 553 893 552 894 523 894 525 894 555 895 552 895 525 895 552 896 555 896 554 896 418 897 416 897 553 897 525 898 527 898 555 898 556 899 420 899 418 899 553 900 556 900 418 900 556 901 553 901 554 901 557 902 554 902 555 902 554 903 557 903 556 903 555 904 558 904 557 904 555 905 527 905 529 905 558 906 555 906 529 906 422 907 420 907 556 907 529 908 532 908 558 908 559 909 423 909 422 909 556 910 559 910 422 910 559 911 556 911 557 911 560 912 559 912 557 912 560 913 557 913 558 913 558 914 532 914 533 914 560 915 558 915 533 915 561 916 560 916 533 916 537 917 561 917 533 917 487 918 485 918 562 918 563 919 407 919 409 919 564 920 563 920 409 920 565 921 563 921 564 921 566 922 565 922 564 922 567 923 566 923 564 923 487 924 568 924 490 924 569 925 566 925 567 925 562 926 569 926 567 926 568 927 562 927 567 927 562 928 568 928 487 928 409 929 411 929 564 929 564 930 570 930 567 930 564 931 411 931 413 931 570 932 564 932 413 932 567 933 571 933 568 933 571 934 567 934 570 934 493 935 490 935 568 935 413 936 415 936 570 936 572 937 493 937 568 937 572 938 568 938 571 938 495 939 493 939 572 939 570 940 573 940 571 940 573 941 570 941 415 941 571 942 574 942 572 942 574 943 571 943 573 943 415 944 417 944 573 944 575 945 572 945 574 945 575 946 497 946 495 946 572 947 575 947 495 947 498 948 497 948 575 948 573 949 576 949 574 949 573 950 417 950 419 950 576 951 573 951 419 951 574 952 577 952 575 952 577 953 574 953 576 953 578 954 575 954 577 954 578 955 501 955 498 955 575 956 578 956 498 956 419 957 421 957 576 957 502 958 501 958 578 958 576 959 579 959 577 959 576 960 421 960 424 960 576 961 424 961 579 961 577 962 580 962 578 962 577 963 579 963 580 963 578 964 580 964 581 964 581 965 504 965 502 965 578 966 581 966 502 966 506 967 504 967 581 967 452 968 582 968 454 968 583 969 454 969 582 969 582 970 584 970 583 970 585 971 583 971 584 971 584 972 586 972 585 972 587 973 585 973 586 973 586 974 588 974 587 974 589 975 587 975 588 975 588 976 590 976 589 976 591 977 589 977 590 977 590 978 424 978 591 978 423 979 591 979 424 979 454 980 592 980 455 980 593 981 455 981 592 981 455 982 593 982 456 982 592 983 583 983 593 983 594 984 456 984 593 984 595 985 593 985 583 985 593 986 595 986 594 986 583 987 585 987 595 987 596 988 456 988 594 988 597 989 595 989 585 989 595 990 597 990 594 990 594 991 598 991 596 991 598 992 594 992 597 992 585 993 587 993 597 993 597 994 599 994 598 994 599 995 597 995 587 995 587 996 589 996 599 996 600 997 596 997 598 997 601 998 598 998 599 998 598 999 601 999 600 999 602 1000 599 1000 589 1000 599 1001 602 1001 601 1001 589 1002 603 1002 602 1002 604 1003 600 1003 601 1003 601 1004 605 1004 604 1004 605 1005 601 1005 602 1005 602 1006 606 1006 605 1006 606 1007 602 1007 603 1007 603 1008 591 1008 606 1008 607 1009 604 1009 605 1009 606 1010 559 1010 605 1010 559 1011 606 1011 591 1011 561 1012 607 1012 605 1012 591 1013 423 1013 559 1013 560 1014 605 1014 559 1014 605 1015 560 1015 561 1015 614 1016 608 1016 596 1016 596 1017 600 1017 614 1017 609 1018 614 1018 600 1018 600 1019 604 1019 609 1019 623 1020 609 1020 604 1020 604 1021 607 1021 623 1021 610 1022 623 1022 607 1022 607 1023 561 1023 610 1023 610 1024 561 1024 537 1024 611 1025 462 1025 461 1025 461 1026 608 1026 611 1026 463 1027 462 1027 611 1027 612 1028 463 1028 611 1028 611 1029 613 1029 612 1029 613 1030 611 1030 608 1030 468 1031 463 1031 612 1031 608 1032 614 1032 613 1032 612 1033 615 1033 468 1033 473 1034 468 1034 615 1034 614 1035 609 1035 613 1035 616 1036 612 1036 613 1036 612 1037 616 1037 615 1037 613 1038 617 1038 616 1038 617 1039 613 1039 609 1039 618 1040 615 1040 616 1040 615 1041 618 1041 473 1041 619 1042 470 1042 473 1042 473 1043 620 1043 619 1043 620 1044 473 1044 618 1044 616 1045 621 1045 618 1045 621 1046 616 1046 617 1046 617 1047 622 1047 621 1047 622 1048 617 1048 609 1048 609 1049 623 1049 622 1049 618 1050 624 1050 620 1050 624 1051 618 1051 621 1051 625 1052 626 1052 619 1052 620 1053 625 1053 619 1053 625 1054 620 1054 624 1054 623 1055 610 1055 622 1055 621 1056 535 1056 624 1056 535 1057 621 1057 622 1057 627 1058 622 1058 610 1058 622 1059 627 1059 535 1059 624 1060 539 1060 625 1060 539 1061 624 1061 535 1061 627 1062 610 1062 536 1062 535 1063 627 1063 536 1063 538 1064 406 1064 626 1064 625 1065 538 1065 626 1065 610 1066 537 1066 536 1066 470 1067 619 1067 471 1067 628 1068 471 1068 619 1068 619 1069 626 1069 628 1069 629 1070 628 1070 626 1070 626 1071 406 1071 629 1071 405 1072 629 1072 406 1072 630 1073 457 1073 459 1073 459 1074 631 1074 630 1074 459 1075 465 1075 631 1075 465 1076 632 1076 631 1076 633 1077 631 1077 632 1077 631 1078 633 1078 630 1078 465 1079 467 1079 632 1079 646 1080 630 1080 633 1080 467 1081 634 1081 632 1081 467 1082 472 1082 634 1082 635 1083 632 1083 634 1083 632 1084 635 1084 633 1084 636 1085 646 1085 633 1085 633 1086 637 1086 636 1086 637 1087 633 1087 635 1087 472 1088 638 1088 634 1088 472 1089 471 1089 638 1089 639 1090 634 1090 638 1090 634 1091 639 1091 635 1091 471 1092 628 1092 638 1092 640 1093 636 1093 637 1093 641 1094 637 1094 635 1094 637 1095 641 1095 640 1095 642 1096 638 1096 628 1096 638 1097 642 1097 639 1097 635 1098 643 1098 641 1098 643 1099 635 1099 639 1099 644 1100 639 1100 642 1100 639 1101 644 1101 643 1101 628 1102 629 1102 642 1102 507 1103 641 1103 643 1103 641 1104 507 1104 640 1104 508 1105 643 1105 644 1105 643 1106 508 1106 507 1106 506 1107 640 1107 507 1107 644 1108 510 1108 508 1108 510 1109 644 1109 642 1109 642 1110 509 1110 510 1110 509 1111 642 1111 629 1111 629 1112 405 1112 509 1112 630 1113 646 1113 645 1113 647 1114 645 1114 646 1114 646 1115 636 1115 647 1115 648 1116 647 1116 636 1116 636 1117 640 1117 648 1117 649 1118 648 1118 640 1118 640 1119 506 1119 649 1119 581 1120 649 1120 506 1120 453 1121 650 1121 452 1121 453 1122 450 1122 651 1122 650 1123 453 1123 651 1123 582 1124 452 1124 650 1124 652 1125 650 1125 651 1125 650 1126 652 1126 582 1126 653 1127 582 1127 652 1127 651 1128 654 1128 652 1128 584 1129 653 1129 652 1129 655 1130 652 1130 654 1130 652 1131 655 1131 584 1131 656 1132 584 1132 655 1132 651 1133 630 1133 654 1133 654 1134 630 1134 645 1134 657 1135 654 1135 645 1135 654 1136 657 1136 655 1136 655 1137 658 1137 656 1137 658 1138 655 1138 657 1138 586 1139 656 1139 658 1139 659 1140 657 1140 645 1140 657 1141 659 1141 658 1141 645 1142 647 1142 659 1142 588 1143 586 1143 658 1143 658 1144 660 1144 588 1144 660 1145 658 1145 659 1145 659 1146 661 1146 660 1146 661 1147 659 1147 647 1147 647 1148 648 1148 661 1148 590 1149 588 1149 660 1149 662 1150 661 1150 648 1150 661 1151 662 1151 660 1151 663 1152 660 1152 662 1152 660 1153 663 1153 590 1153 648 1154 649 1154 662 1154 662 1155 580 1155 663 1155 580 1156 662 1156 649 1156 649 1157 581 1157 580 1157 424 1158 590 1158 663 1158 579 1159 663 1159 580 1159 663 1160 579 1160 424 1160 475 1161 670 1161 671 1161 477 1162 475 1162 671 1162 479 1163 477 1163 671 1163 442 1164 440 1164 673 1164 671 1165 674 1165 479 1165 479 1166 674 1166 64 1166 251 1167 479 1167 64 1167 253 1168 63 1168 673 1168 440 1169 253 1169 673 1169 287 1170 285 1170 664 1170 665 1171 664 1171 285 1171 285 1172 283 1172 665 1172 666 1173 665 1173 283 1173 283 1174 281 1174 666 1174 670 1175 666 1175 281 1175 281 1176 279 1176 670 1176 671 1177 670 1177 279 1177 279 1178 277 1178 671 1178 674 1179 671 1179 277 1179 277 1180 275 1180 674 1180 64 1181 674 1181 275 1181 275 1182 273 1182 64 1182 303 1183 299 1183 63 1183 673 1184 63 1184 299 1184 299 1185 297 1185 673 1185 672 1186 673 1186 297 1186 297 1187 295 1187 672 1187 669 1188 672 1188 295 1188 295 1189 293 1189 669 1189 667 1190 669 1190 293 1190 293 1191 291 1191 667 1191 668 1192 667 1192 291 1192 291 1193 289 1193 668 1193 668 1194 289 1194 287 1194 664 1195 668 1195 287 1195 252 1196 441 1196 28 1196 433 1197 435 1197 684 1197 685 1198 684 1198 435 1198 435 1199 438 1199 685 1199 681 1200 685 1200 438 1200 438 1201 316 1201 681 1201 680 1202 681 1202 316 1202 316 1203 311 1203 680 1203 678 1204 680 1204 311 1204 311 1205 309 1205 678 1205 676 1206 678 1206 309 1206 309 1207 307 1207 676 1207 28 1208 676 1208 307 1208 307 1209 305 1209 28 1209 16 1210 434 1210 432 1210 14 1211 16 1211 432 1211 436 1212 434 1212 16 1212 16 1213 18 1213 436 1213 437 1214 436 1214 18 1214 18 1215 20 1215 437 1215 439 1216 437 1216 20 1216 20 1217 22 1217 439 1217 317 1218 439 1218 22 1218 22 1219 25 1219 317 1219 4 1220 6 1220 334 1220 426 1221 334 1221 6 1221 6 1222 8 1222 426 1222 428 1223 426 1223 8 1223 8 1224 10 1224 428 1224 429 1225 428 1225 10 1225 10 1226 12 1226 429 1226 431 1227 429 1227 12 1227 12 1228 14 1228 431 1228 432 1229 431 1229 14 1229 348 1230 344 1230 27 1230 675 1231 27 1231 344 1231 344 1232 342 1232 675 1232 677 1233 675 1233 342 1233 342 1234 340 1234 677 1234 679 1235 677 1235 340 1235 340 1236 425 1236 679 1236 682 1237 679 1237 425 1237 425 1238 427 1238 682 1238 683 1239 682 1239 427 1239 427 1240 430 1240 683 1240 683 1241 430 1241 433 1241 684 1242 683 1242 433 1242 388 1243 389 1243 390 1243 385 1244 389 1244 388 1244 385 1245 388 1245 386 1245 385 1246 386 1246 387 1246 410 1247 412 1247 411 1247 409 1248 410 1248 411 1248 408 1249 410 1249 409 1249 407 1250 408 1250 409 1250 533 1251 536 1251 537 1251 534 1252 539 1252 535 1252 534 1253 538 1253 539 1253 538 1254 625 1254 539 1254 480 1255 250 1255 27 1255 480 1256 27 1256 675 1256 478 1257 480 1257 675 1257 478 1258 675 1258 677 1258 476 1259 478 1259 677 1259 476 1260 677 1260 679 1260 474 1261 476 1261 679 1261 466 1262 474 1262 679 1262 466 1263 679 1263 682 1263 460 1264 466 1264 682 1264 460 1265 682 1265 683 1265 460 1266 683 1266 461 1266 461 1267 683 1267 684 1267 456 1268 684 1268 685 1268 451 1269 456 1269 685 1269 461 1270 686 1270 608 1270 456 1271 686 1271 684 1271 686 1272 461 1272 684 1272 596 1273 608 1273 686 1273 456 1274 596 1274 686 1274 531 1275 536 1275 533 1275 531 1276 535 1276 536 1276 451 1277 685 1277 681 1277 449 1278 451 1278 681 1278 449 1279 681 1279 680 1279 441 1280 443 1280 28 1280 443 1281 676 1281 28 1281 443 1282 445 1282 676 1282 445 1283 678 1283 676 1283 445 1284 447 1284 678 1284 447 1285 680 1285 678 1285 447 1286 449 1286 680 1286 469 1287 670 1287 475 1287 464 1288 670 1288 469 1288 464 1289 666 1289 670 1289 458 1290 666 1290 464 1290 458 1291 665 1291 666 1291 457 1292 665 1292 458 1292 457 1293 664 1293 665 1293 457 1294 630 1294 664 1294 630 1295 668 1295 664 1295 630 1296 651 1296 668 1296 450 1297 667 1297 651 1297 651 1298 667 1298 668 1298 450 1299 669 1299 667 1299 448 1300 669 1300 450 1300 448 1301 672 1301 669 1301 446 1302 672 1302 448 1302 446 1303 673 1303 672 1303 444 1304 673 1304 446 1304 442 1305 673 1305 444 1305 482 1306 483 1306 489 1306 483 1307 488 1307 489 1307 483 1308 486 1308 488 1308 484 1309 488 1309 486 1309 484 1310 487 1310 488 1310 484 1311 485 1311 487 1311 386 1312 388 1312 687 1312 388 1313 511 1313 687 1313 841 1314 766 1314 765 1314 841 1315 767 1315 766 1315 841 1316 768 1316 767 1316 841 1317 839 1317 768 1317 789 1318 687 1318 511 1318 386 1319 687 1319 906 1319 906 1320 687 1320 789 1320 380 1321 820 1321 819 1321 380 1322 821 1322 820 1322 381 1323 821 1323 380 1323 381 1324 822 1324 821 1324 381 1325 823 1325 822 1325 785 1326 783 1326 711 1326 783 1327 784 1327 711 1327 710 1328 711 1328 784 1328 784 1329 782 1329 710 1329 709 1330 710 1330 782 1330 782 1331 742 1331 709 1331 708 1332 709 1332 742 1332 742 1333 743 1333 708 1333 707 1334 708 1334 744 1334 708 1335 743 1335 744 1335 706 1336 707 1336 745 1336 707 1337 744 1337 745 1337 706 1338 745 1338 746 1338 705 1339 715 1339 716 1339 716 1340 713 1340 705 1340 704 1341 705 1341 713 1341 713 1342 714 1342 704 1342 703 1343 704 1343 714 1343 714 1344 712 1344 703 1344 702 1345 703 1345 712 1345 700 1346 702 1346 790 1346 702 1347 712 1347 790 1347 790 1348 791 1348 700 1348 701 1349 700 1349 791 1349 791 1350 792 1350 701 1350 792 1351 793 1351 701 1351 800 1352 798 1352 689 1352 798 1353 799 1353 689 1353 688 1354 689 1354 799 1354 799 1355 797 1355 688 1355 690 1356 688 1356 797 1356 797 1357 726 1357 690 1357 693 1358 690 1358 726 1358 726 1359 727 1359 693 1359 692 1360 693 1360 728 1360 693 1361 727 1361 728 1361 691 1362 692 1362 729 1362 692 1363 728 1363 729 1363 691 1364 729 1364 730 1364 695 1365 760 1365 761 1365 761 1366 758 1366 695 1366 694 1367 695 1367 758 1367 758 1368 759 1368 694 1368 696 1369 694 1369 759 1369 759 1370 757 1370 696 1370 697 1371 696 1371 757 1371 698 1372 697 1372 772 1372 697 1373 757 1373 772 1373 772 1374 773 1374 698 1374 699 1375 698 1375 773 1375 773 1376 774 1376 699 1376 774 1377 775 1377 699 1377 825 1378 823 1378 804 1378 823 1379 805 1379 804 1379 804 1380 803 1380 825 1380 827 1381 825 1381 802 1381 825 1382 803 1382 802 1382 838 1383 840 1383 741 1383 840 1384 740 1384 741 1384 840 1385 739 1385 740 1385 840 1386 738 1386 739 1386 802 1387 801 1387 827 1387 829 1388 827 1388 800 1388 827 1389 801 1389 800 1389 737 1390 738 1390 840 1390 840 1391 842 1391 737 1391 842 1392 736 1392 737 1392 842 1393 735 1393 736 1393 842 1394 734 1394 735 1394 842 1395 733 1395 734 1395 842 1396 732 1396 733 1396 688 1397 690 1397 689 1397 800 1398 689 1398 690 1398 690 1399 693 1399 800 1399 693 1400 829 1400 800 1400 831 1401 829 1401 730 1401 829 1402 691 1402 730 1402 829 1403 692 1403 691 1403 829 1404 693 1404 692 1404 731 1405 732 1405 842 1405 842 1406 844 1406 731 1406 844 1407 730 1407 731 1407 844 1408 831 1408 730 1408 833 1409 831 1409 844 1409 844 1410 846 1410 833 1410 834 1411 833 1411 846 1411 846 1412 848 1412 834 1412 836 1413 834 1413 848 1413 848 1414 850 1414 836 1414 835 1415 836 1415 850 1415 850 1416 852 1416 835 1416 832 1417 835 1417 852 1417 852 1418 854 1418 832 1418 830 1419 832 1419 854 1419 854 1420 856 1420 830 1420 828 1421 830 1421 856 1421 856 1422 858 1422 828 1422 826 1423 828 1423 858 1423 858 1424 860 1424 826 1424 824 1425 826 1425 860 1425 860 1426 863 1426 824 1426 822 1427 824 1427 863 1427 863 1428 864 1428 822 1428 821 1429 822 1429 864 1429 864 1430 862 1430 821 1430 820 1431 821 1431 862 1431 862 1432 861 1432 820 1432 818 1433 820 1433 861 1433 861 1434 859 1434 818 1434 816 1435 818 1435 859 1435 859 1436 857 1436 816 1436 814 1437 816 1437 857 1437 857 1438 855 1438 814 1438 812 1439 814 1439 855 1439 855 1440 853 1440 812 1440 810 1441 812 1441 853 1441 853 1442 851 1442 810 1442 808 1443 810 1443 851 1443 851 1444 849 1444 808 1444 806 1445 808 1445 849 1445 849 1446 847 1446 806 1446 807 1447 806 1447 847 1447 847 1448 845 1448 807 1448 809 1449 807 1449 845 1449 845 1450 843 1450 809 1450 811 1451 809 1451 843 1451 843 1452 841 1452 760 1452 760 1453 811 1453 843 1453 841 1454 762 1454 760 1454 813 1455 811 1455 696 1455 811 1456 694 1456 696 1456 811 1457 695 1457 694 1457 811 1458 760 1458 695 1458 763 1459 762 1459 841 1459 765 1460 764 1460 841 1460 764 1461 763 1461 841 1461 696 1462 697 1462 775 1462 775 1463 813 1463 696 1463 815 1464 813 1464 776 1464 813 1465 775 1465 776 1465 699 1466 775 1466 697 1466 697 1467 698 1467 699 1467 769 1468 768 1468 839 1468 839 1469 837 1469 771 1469 771 1470 770 1470 839 1470 770 1471 769 1471 839 1471 776 1472 777 1472 815 1472 817 1473 815 1473 778 1473 815 1474 777 1474 778 1474 778 1475 779 1475 817 1475 819 1476 817 1476 780 1476 817 1477 779 1477 780 1477 387 1478 910 1478 481 1478 910 1479 912 1479 481 1479 912 1480 482 1480 481 1480 796 1481 482 1481 912 1481 912 1482 914 1482 796 1482 914 1483 795 1483 796 1483 890 1484 892 1484 725 1484 725 1485 724 1485 890 1485 724 1486 723 1486 890 1486 723 1487 722 1487 890 1487 794 1488 795 1488 914 1488 914 1489 916 1489 794 1489 916 1490 793 1490 794 1490 722 1491 721 1491 890 1491 888 1492 890 1492 719 1492 719 1493 718 1493 888 1493 890 1494 720 1494 719 1494 890 1495 721 1495 720 1495 702 1496 700 1496 701 1496 701 1497 793 1497 702 1497 703 1498 702 1498 793 1498 793 1499 916 1499 703 1499 916 1500 918 1500 703 1500 918 1501 704 1501 703 1501 918 1502 705 1502 704 1502 918 1503 715 1503 705 1503 886 1504 888 1504 715 1504 715 1505 918 1505 886 1505 888 1506 717 1506 715 1506 888 1507 718 1507 717 1507 918 1508 920 1508 886 1508 884 1509 886 1509 920 1509 920 1510 921 1510 884 1510 882 1511 884 1511 921 1511 921 1512 922 1512 882 1512 880 1513 882 1513 922 1513 922 1514 923 1514 880 1514 878 1515 880 1515 923 1515 923 1516 919 1516 878 1516 876 1517 878 1517 919 1517 919 1518 917 1518 876 1518 874 1519 876 1519 917 1519 917 1520 915 1520 874 1520 872 1521 874 1521 915 1521 915 1522 913 1522 872 1522 870 1523 872 1523 913 1523 913 1524 911 1524 870 1524 868 1525 870 1525 911 1525 911 1526 909 1526 868 1526 866 1527 868 1527 909 1527 909 1528 908 1528 866 1528 865 1529 866 1529 908 1529 908 1530 907 1530 865 1530 867 1531 865 1531 907 1531 907 1532 905 1532 867 1532 869 1533 867 1533 905 1533 905 1534 903 1534 869 1534 871 1535 869 1535 903 1535 903 1536 901 1536 871 1536 873 1537 871 1537 901 1537 901 1538 899 1538 873 1538 875 1539 873 1539 899 1539 899 1540 897 1540 875 1540 877 1541 875 1541 897 1541 897 1542 895 1542 877 1542 879 1543 877 1543 895 1543 895 1544 893 1544 879 1544 881 1545 879 1545 893 1545 893 1546 894 1546 881 1546 883 1547 881 1547 894 1547 894 1548 896 1548 883 1548 885 1549 883 1549 896 1549 896 1550 898 1550 885 1550 887 1551 885 1551 747 1551 885 1552 746 1552 747 1552 885 1553 898 1553 746 1553 898 1554 900 1554 746 1554 900 1555 706 1555 746 1555 900 1556 707 1556 706 1556 900 1557 708 1557 707 1557 747 1558 748 1558 887 1558 889 1559 887 1559 753 1559 887 1560 752 1560 753 1560 887 1561 751 1561 752 1561 887 1562 750 1562 751 1562 887 1563 749 1563 750 1563 887 1564 748 1564 749 1564 709 1565 708 1565 785 1565 708 1566 900 1566 785 1566 900 1567 902 1567 785 1567 902 1568 786 1568 785 1568 785 1569 711 1569 709 1569 710 1570 709 1570 711 1570 753 1571 754 1571 889 1571 891 1572 889 1572 756 1572 889 1573 755 1573 756 1573 889 1574 754 1574 755 1574 787 1575 786 1575 902 1575 902 1576 904 1576 787 1576 904 1577 788 1577 787 1577 789 1578 788 1578 904 1578 904 1579 906 1579 789 1579 790 1580 712 1580 485 1580 562 1581 485 1581 712 1581 712 1582 714 1582 562 1582 562 1583 713 1583 716 1583 562 1584 714 1584 713 1584 569 1585 562 1585 717 1585 562 1586 715 1586 717 1586 562 1587 716 1587 715 1587 717 1588 718 1588 569 1588 566 1589 569 1589 719 1589 569 1590 718 1590 719 1590 565 1591 566 1591 720 1591 566 1592 719 1592 720 1592 720 1593 721 1593 565 1593 563 1594 565 1594 722 1594 565 1595 721 1595 722 1595 722 1596 723 1596 563 1596 407 1597 563 1597 724 1597 563 1598 723 1598 724 1598 724 1599 725 1599 407 1599 407 1600 725 1600 892 1600 201 1601 132 1601 797 1601 132 1602 726 1602 797 1602 727 1603 726 1603 132 1603 132 1604 133 1604 727 1604 133 1605 728 1605 727 1605 133 1606 729 1606 728 1606 730 1607 729 1607 133 1607 133 1608 134 1608 730 1608 134 1609 731 1609 730 1609 732 1610 731 1610 134 1610 134 1611 136 1611 732 1611 136 1612 733 1612 732 1612 734 1613 733 1613 136 1613 136 1614 135 1614 734 1614 135 1615 735 1615 734 1615 736 1616 735 1616 135 1616 135 1617 138 1617 736 1617 138 1618 737 1618 736 1618 138 1619 738 1619 737 1619 739 1620 738 1620 138 1620 138 1621 137 1621 739 1621 137 1622 740 1622 739 1622 741 1623 740 1623 137 1623 137 1624 349 1624 741 1624 838 1625 741 1625 349 1625 515 1626 541 1626 782 1626 541 1627 742 1627 782 1627 743 1628 742 1628 541 1628 541 1629 540 1629 743 1629 540 1630 744 1630 743 1630 540 1631 745 1631 744 1631 746 1632 745 1632 540 1632 540 1633 549 1633 746 1633 549 1634 747 1634 746 1634 748 1635 747 1635 549 1635 549 1636 547 1636 748 1636 547 1637 749 1637 748 1637 750 1638 749 1638 547 1638 547 1639 546 1639 750 1639 546 1640 751 1640 750 1640 752 1641 751 1641 546 1641 546 1642 543 1642 752 1642 543 1643 753 1643 752 1643 754 1644 753 1644 543 1644 543 1645 542 1645 754 1645 542 1646 755 1646 754 1646 756 1647 755 1647 542 1647 542 1648 408 1648 756 1648 891 1649 756 1649 408 1649 772 1650 757 1650 176 1650 153 1651 176 1651 757 1651 757 1652 759 1652 153 1652 155 1653 153 1653 761 1653 153 1654 758 1654 761 1654 153 1655 759 1655 758 1655 154 1656 155 1656 762 1656 155 1657 760 1657 762 1657 155 1658 761 1658 760 1658 762 1659 763 1659 154 1659 156 1660 154 1660 764 1660 154 1661 763 1661 764 1661 764 1662 765 1662 156 1662 157 1663 156 1663 766 1663 156 1664 765 1664 766 1664 766 1665 767 1665 157 1665 159 1666 157 1666 768 1666 157 1667 767 1667 768 1667 768 1668 769 1668 159 1668 158 1669 159 1669 770 1669 159 1670 769 1670 770 1670 770 1671 771 1671 158 1671 350 1672 158 1672 837 1672 158 1673 771 1673 837 1673 176 1674 177 1674 772 1674 177 1675 773 1675 772 1675 177 1676 774 1676 773 1676 177 1677 775 1677 774 1677 776 1678 775 1678 177 1678 177 1679 172 1679 776 1679 777 1680 776 1680 172 1680 172 1681 175 1681 777 1681 778 1682 777 1682 175 1682 175 1683 173 1683 778 1683 173 1684 779 1684 778 1684 780 1685 779 1685 173 1685 173 1686 174 1686 780 1686 782 1687 784 1687 515 1687 514 1688 515 1688 785 1688 515 1689 783 1689 785 1689 515 1690 784 1690 783 1690 785 1691 786 1691 514 1691 513 1692 514 1692 786 1692 786 1693 787 1693 513 1693 512 1694 513 1694 787 1694 787 1695 788 1695 512 1695 511 1696 512 1696 789 1696 512 1697 788 1697 789 1697 485 1698 484 1698 790 1698 484 1699 791 1699 790 1699 484 1700 792 1700 791 1700 484 1701 793 1701 792 1701 794 1702 793 1702 484 1702 484 1703 486 1703 794 1703 795 1704 794 1704 486 1704 486 1705 483 1705 795 1705 796 1706 795 1706 483 1706 483 1707 482 1707 796 1707 797 1708 799 1708 201 1708 200 1709 201 1709 800 1709 201 1710 798 1710 800 1710 201 1711 799 1711 798 1711 800 1712 801 1712 200 1712 199 1713 200 1713 801 1713 801 1714 802 1714 199 1714 197 1715 199 1715 802 1715 802 1716 803 1716 197 1716 196 1717 197 1717 804 1717 197 1718 803 1718 804 1718 804 1719 805 1719 196 1719 808 1720 806 1720 807 1720 807 1721 809 1721 808 1721 810 1722 808 1722 809 1722 809 1723 811 1723 810 1723 812 1724 810 1724 811 1724 811 1725 813 1725 812 1725 814 1726 812 1726 813 1726 813 1727 815 1727 814 1727 816 1728 814 1728 815 1728 815 1729 817 1729 816 1729 818 1730 816 1730 817 1730 817 1731 819 1731 818 1731 820 1732 818 1732 819 1732 824 1733 822 1733 823 1733 823 1734 825 1734 824 1734 826 1735 824 1735 825 1735 825 1736 827 1736 826 1736 828 1737 826 1737 827 1737 827 1738 829 1738 828 1738 830 1739 828 1739 829 1739 829 1740 831 1740 830 1740 832 1741 830 1741 831 1741 831 1742 833 1742 832 1742 835 1743 832 1743 833 1743 833 1744 834 1744 835 1744 836 1745 835 1745 834 1745 350 1746 837 1746 349 1746 838 1747 349 1747 837 1747 837 1748 839 1748 838 1748 840 1749 838 1749 839 1749 839 1750 841 1750 840 1750 842 1751 840 1751 841 1751 841 1752 843 1752 842 1752 844 1753 842 1753 843 1753 843 1754 845 1754 844 1754 846 1755 844 1755 845 1755 845 1756 847 1756 846 1756 848 1757 846 1757 847 1757 847 1758 849 1758 848 1758 850 1759 848 1759 849 1759 849 1760 851 1760 850 1760 852 1761 850 1761 851 1761 851 1762 853 1762 852 1762 854 1763 852 1763 853 1763 853 1764 855 1764 854 1764 856 1765 854 1765 855 1765 855 1766 857 1766 856 1766 858 1767 856 1767 857 1767 857 1768 859 1768 858 1768 860 1769 858 1769 859 1769 859 1770 861 1770 860 1770 863 1771 860 1771 861 1771 861 1772 862 1772 863 1772 864 1773 863 1773 862 1773 865 1774 867 1774 866 1774 868 1775 866 1775 867 1775 867 1776 869 1776 868 1776 870 1777 868 1777 869 1777 869 1778 871 1778 870 1778 872 1779 870 1779 871 1779 871 1780 873 1780 872 1780 874 1781 872 1781 873 1781 873 1782 875 1782 874 1782 876 1783 874 1783 875 1783 875 1784 877 1784 876 1784 878 1785 876 1785 877 1785 877 1786 879 1786 878 1786 880 1787 878 1787 879 1787 879 1788 881 1788 880 1788 882 1789 880 1789 881 1789 881 1790 883 1790 882 1790 884 1791 882 1791 883 1791 883 1792 885 1792 884 1792 886 1793 884 1793 885 1793 885 1794 887 1794 886 1794 888 1795 886 1795 887 1795 887 1796 889 1796 888 1796 890 1797 888 1797 889 1797 889 1798 891 1798 890 1798 892 1799 890 1799 891 1799 891 1800 408 1800 892 1800 407 1801 892 1801 408 1801 893 1802 895 1802 894 1802 896 1803 894 1803 895 1803 895 1804 897 1804 896 1804 898 1805 896 1805 897 1805 897 1806 899 1806 898 1806 900 1807 898 1807 899 1807 899 1808 901 1808 900 1808 902 1809 900 1809 901 1809 901 1810 903 1810 902 1810 904 1811 902 1811 903 1811 903 1812 905 1812 904 1812 906 1813 904 1813 905 1813 905 1814 907 1814 906 1814 386 1815 906 1815 907 1815 907 1816 908 1816 386 1816 386 1817 908 1817 387 1817 908 1818 909 1818 387 1818 910 1819 387 1819 909 1819 909 1820 911 1820 910 1820 912 1821 910 1821 911 1821 911 1822 913 1822 912 1822 914 1823 912 1823 913 1823 913 1824 915 1824 914 1824 916 1825 914 1825 915 1825 915 1826 917 1826 916 1826 918 1827 916 1827 917 1827 917 1828 919 1828 918 1828 920 1829 918 1829 919 1829 919 1830 923 1830 920 1830 921 1831 920 1831 923 1831 923 1832 922 1832 921 1832 823 1833 381 1833 924 1833 924 1834 805 1834 823 1834 780 1835 781 1835 819 1835 380 1836 819 1836 781 1836 781 1837 780 1837 174 1837 174 1838 380 1838 781 1838 198 1839 196 1839 805 1839 805 1840 924 1840 198 1840 198 1841 924 1841 381 1841

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/wrist/wrist_E3M5.dae b/URDFs/sr_description/meshes/components/wrist/wrist_E3M5.dae new file mode 100644 index 0000000..5f1f221 --- /dev/null +++ b/URDFs/sr_description/meshes/components/wrist/wrist_E3M5.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:55.555034 + 2012-07-23T02:14:55.555052 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -12.60386 -0.00040 -4.55191 -0.54290 13.89959 -4.46761 0.54193 13.89959 -4.46761 -1.59620 13.89959 -4.20799 1.59524 13.89959 -4.20799 -2.55677 13.89959 -3.70385 2.55581 13.89959 -3.70385 -3.36878 13.89959 -2.98447 3.36782 13.89959 -2.98447 -3.98503 13.89959 -2.09167 3.98407 13.89959 -2.09167 -4.36972 13.89959 -1.07734 4.36876 13.89959 -1.07734 -4.50048 13.89959 -0.00042 4.49952 13.89959 -0.00042 -4.36972 13.89959 1.07650 4.36876 13.89959 1.07650 -3.98503 13.89959 2.09083 3.98407 13.89959 2.09083 -3.36878 13.89959 2.98363 3.36782 13.89959 2.98363 -2.55677 13.89959 3.70301 2.55581 13.89959 3.70301 -1.59621 13.89959 4.20715 -0.54290 13.89959 4.46677 1.59524 13.89959 4.20715 0.54193 13.89959 4.46677 2.31715 10.59960 -7.13334 2.31714 10.59959 7.13250 0.78348 10.59960 -7.45934 0.78348 10.59959 7.45849 -0.78445 10.59960 -7.45934 -0.78445 10.59959 7.45849 -2.31811 10.59960 -7.13334 -2.31811 10.59959 7.13250 -3.75048 10.59960 -6.49561 -3.75048 10.59959 6.49477 -5.01896 10.59959 5.57317 -5.01896 10.59960 -5.57401 -6.06811 10.59960 -4.40881 -6.06811 10.59959 4.40797 -6.85207 10.59960 -3.05095 -6.85207 10.59960 3.05010 -7.33659 10.59960 1.55892 -7.33659 10.59960 -1.55976 -7.50048 10.59960 -0.00042 -7.33659 -10.60041 1.55892 -7.50049 -10.60041 -0.00042 -7.33659 -10.60041 -1.55976 -6.85208 -10.60040 -3.05095 -6.85208 -10.60041 3.05010 -6.06812 -10.60041 4.40797 -6.06811 -10.60041 -4.40881 -5.01897 -10.60041 -5.57401 -5.01897 -10.60041 5.57317 -3.75049 -10.60041 6.49477 -3.75048 -10.60041 -6.49561 -2.31811 -10.60041 7.13250 -2.31811 -10.60041 -7.13334 -0.78445 -10.60041 7.45849 -0.78445 -10.60041 -7.45934 0.78348 -10.60041 7.45849 0.78348 -10.60041 -7.45934 2.31714 -10.60041 7.13250 2.31714 -10.60041 -7.13334 -14.48772 7.22568 1.21112 -13.95641 7.52509 0.93113 -14.19300 7.34965 1.09963 -13.90642 5.60705 -0.55767 -13.79636 3.38683 -1.54026 -13.62562 5.80287 -0.82700 -13.37415 3.55958 -2.00872 -13.63172 7.84658 0.62766 -13.42834 6.02566 -1.14744 -13.47899 8.13542 0.34559 -13.59057 1.00859 -2.05556 -13.29065 0.99960 -2.43023 -13.81941 -3.37846 -1.52380 -14.03224 -5.53306 -0.46171 -13.55213 -0.99182 -2.09744 -13.25895 -1.00324 -2.49002 -13.38795 -3.54875 -1.98317 -13.58612 -5.82680 -0.86263 -14.26401 -7.32159 1.13379 -13.91214 -7.54561 0.91654 -13.62985 -7.86254 0.60894 -13.45037 -8.20210 0.28867 -13.43177 -8.35835 0.13871 -13.33815 -8.96163 6.94725 -14.02152 -9.25673 4.06271 -12.62189 -7.88431 7.72702 -13.68860 -9.47942 5.55454 -12.17220 -7.98916 7.62231 -12.79561 -9.12583 6.73785 -13.52762 -9.55666 3.80315 -13.12857 -9.80029 5.34117 -11.80590 -8.10198 7.60052 -12.36982 -9.38179 6.66783 -11.38435 -8.27721 7.68078 -12.05107 -9.64642 6.67054 -13.18897 -10.02901 3.50122 -12.65820 -10.25672 5.20334 -12.34419 -10.50040 5.65164 -13.10623 -10.46706 3.30983 -10.99744 -8.47381 7.83888 -11.76268 -9.96988 6.73570 -12.25473 -6.40498 7.99782 -11.72898 -6.40560 7.93281 -11.17216 -6.40683 8.02417 -10.64307 -6.40915 8.28321 -14.26038 9.15721 4.16294 -12.29217 6.40601 8.00338 -13.74552 9.47000 5.58112 -12.55224 7.89330 7.70474 -13.03981 9.03588 6.82450 -13.85801 9.33975 3.98340 -13.33376 9.66441 5.42183 -12.56829 9.24682 6.69359 -13.50539 9.60548 3.77503 -11.92678 8.05235 7.58945 -13.02474 9.90194 5.30744 -11.80182 6.40682 7.93720 -12.21385 9.49928 6.66542 -13.26845 9.92961 3.56703 -11.13580 6.40570 8.03591 -13.11173 10.18750 3.41007 -11.28393 8.31322 7.69886 -10.73077 6.40590 8.22361 -12.64398 10.38079 5.24346 -11.84269 9.83655 6.69265 -12.47477 10.49960 5.26739 -10.75736 8.63854 8.05253 -24.88471 -9.35137 23.00377 -24.13114 -9.40305 23.00179 -23.38857 -9.26547 23.01383 -22.12126 -8.46693 23.01970 -22.70383 -8.94547 23.00735 -21.39638 -7.15635 23.02859 -21.67562 -7.85566 23.01203 -23.87215 -9.40192 20.17845 -23.19525 -9.38724 17.47330 -21.99669 -8.94589 18.29033 -20.99868 -7.85505 18.54457 -21.94929 -9.39938 14.24081 -20.17987 -8.94589 13.92521 -19.26540 -7.85505 14.39999 -19.93711 -9.40192 10.96064 -17.36017 -8.94589 10.12988 -16.57709 -7.85505 10.80070 -17.34748 -9.40192 8.11977 -13.71346 -8.96542 7.08199 -13.04990 -7.81858 7.94862 -14.23772 -9.38277 5.85688 -24.88455 9.34945 22.99273 -23.38881 9.26415 22.99850 -24.13438 9.40093 22.94129 -22.70510 8.94655 22.96461 -22.12062 8.46669 23.00962 -21.39598 7.15553 23.02449 -21.67454 7.85688 22.98570 -21.99899 8.94669 18.28904 -21.00004 7.85689 18.54399 -23.36385 9.40128 17.86201 -20.18188 8.94669 13.92356 -19.26665 7.85689 14.39923 -21.37263 9.40128 13.12622 -17.36185 8.94669 10.12793 -16.57822 7.85689 10.79978 -13.63308 8.92521 7.04131 -18.28204 9.40128 9.02243 -12.95601 7.82493 7.86842 -14.24571 9.39143 5.82465 -28.29540 7.12390 23.04268 -30.07768 4.28939 23.02099 -30.54342 2.67371 23.01016 -29.31952 5.79025 23.03187 -25.59235 9.09639 23.03309 -27.04103 8.24381 23.05341 -25.28474 9.10898 19.71424 -27.61936 7.12429 17.71068 -29.29788 4.28653 17.06409 -24.50582 9.10898 16.57668 -23.27924 9.10898 13.58126 -25.81796 7.12429 12.64688 -27.20717 4.28652 11.43173 -21.63284 9.10898 10.79699 -22.97470 7.12429 8.08584 -23.91240 4.28652 6.40789 -19.60074 9.10898 8.28056 -14.54596 9.10868 4.25243 -17.22583 9.10898 6.08501 -19.22128 7.12429 4.23888 -14.43425 5.40799 -0.30267 -14.73110 7.12708 1.28862 -19.57969 4.28652 2.24588 -14.20562 3.28901 -1.33376 -30.07768 -4.29019 23.02099 -29.31952 -5.79105 23.03187 -30.54342 -2.67451 23.01016 -28.29363 -7.12628 23.04270 -27.04103 -8.24461 23.05341 -25.60065 -9.11085 23.01348 -25.46428 -9.10979 20.96733 -25.15497 -9.10979 19.02628 -24.67524 -9.10978 17.11820 -27.61719 -7.12757 17.71145 -29.29673 -4.29047 17.06458 -25.81612 -7.12757 12.64832 -23.24655 -9.10978 13.51576 -27.20625 -4.29047 11.43263 -21.96199 -9.10978 11.28491 -20.42908 -9.10979 9.21762 -22.97337 -7.12757 8.08786 -23.91183 -4.29047 6.40911 -18.66796 -9.10979 7.34085 -16.70228 -9.10979 5.67980 -14.44149 -9.10329 4.22508 -19.22062 -7.12757 4.24131 -14.62641 -7.17487 1.26451 -14.47512 -5.33858 -0.21095 -19.57957 -4.29047 2.24733 -14.24722 -3.28159 -1.25828 -13.08897 10.47856 3.10286 -13.40044 10.49960 0.03300 -13.40676 8.41941 0.07982 -13.40044 -10.50040 0.03300 -13.32003 -6.17464 -1.36950 -13.32796 6.25340 -1.48803 -13.20270 10.49960 -2.29430 -13.09723 3.74191 -2.54411 -13.05894 0.99960 -3.00666 -13.09158 -1.00050 -2.92509 -13.19020 -3.70530 -2.44498 -13.20271 -10.50040 -2.29430 -12.60386 10.49960 -4.55191 -12.60386 -10.50040 -4.55191 -11.62209 10.49960 -6.67124 -11.62209 -10.50040 -6.67124 -10.28724 10.49960 -8.58790 -10.28724 -10.50040 -8.58790 -8.63985 10.49960 -10.24366 -8.63985 -10.50040 -10.24366 -6.72998 10.49960 -11.58821 -6.72998 -10.50040 -11.58821 -4.61565 10.49959 -12.58070 -4.61565 -10.50041 -12.58070 -2.36111 10.49959 -13.19098 -2.36110 -10.50041 -13.19098 -0.03484 10.49959 -13.40051 -0.03483 -10.50041 -13.40051 2.29247 10.49959 -13.20291 2.29248 -10.50041 -13.20291 2.15348 10.49959 13.22520 2.15348 -10.50041 13.22520 -0.07688 10.49959 13.39923 -0.07689 -10.50041 13.39923 -2.30523 10.49959 13.19976 -2.30524 -10.50041 13.19976 -4.46929 10.49959 12.63234 -4.46930 -10.50041 12.63233 -6.50868 10.49959 11.71284 -6.50869 -10.50041 11.71283 -8.36659 10.49959 10.46694 -8.36661 -10.50041 10.46692 -11.33783 10.49960 7.14268 -10.58126 8.76704 8.21934 -9.99129 10.49960 8.92939 -11.34845 -10.49318 7.12164 -10.66137 -8.70710 8.12063 -10.28659 -6.40669 8.60038 -10.25925 6.40596 8.62536 -9.99131 -10.50040 8.92937 -0.00049 -15.40040 -7.50042 1.46269 -15.40040 -7.35631 -1.46366 -15.40040 -7.35631 2.86964 -15.40040 -6.92952 -2.87061 -15.40040 -6.92952 4.16629 -15.40041 -6.23644 -4.16726 -15.40040 -6.23644 5.30282 -15.40041 -5.30372 -5.30379 -15.40040 -5.30372 6.23554 -15.40041 -4.16720 -6.23651 -15.40040 -4.16720 6.92861 -15.40041 -2.87055 -6.92958 -15.40040 -2.87055 7.35540 -15.40041 -1.46360 -7.35638 -15.40040 -1.46360 7.49951 -15.40041 -0.00042 -7.50049 -15.40040 -0.00042 7.35540 -15.40041 1.46276 -7.35638 -15.40040 1.46276 6.92861 -15.40041 2.86971 -6.92958 -15.40040 2.86971 6.23553 -15.40041 4.16636 -6.23651 -15.40041 4.16636 5.30281 -15.40041 5.30288 -5.30379 -15.40041 5.30288 4.16629 -15.40041 6.23560 -4.16727 -15.40041 6.23560 2.86964 -15.40041 6.92868 -2.87061 -15.40041 6.92868 -1.46367 -15.40041 7.35547 -0.00049 -15.40041 7.49958 1.46269 -15.40041 7.35547 -0.00048 15.39959 7.49958 1.46269 15.39959 7.35547 -1.46366 15.39959 7.35547 2.86964 15.39959 6.92868 -2.87061 15.39959 6.92868 4.16629 15.39959 6.23560 -4.16726 15.39959 6.23560 5.30282 15.39959 5.30288 -0.00048 15.39959 4.49958 -5.30378 15.39959 5.30288 1.00086 15.39959 4.38676 -1.00183 15.39959 4.38676 6.23554 15.39959 4.16636 1.95199 15.39959 4.05394 -1.95296 15.39959 4.05394 -6.23651 15.39959 4.16636 -2.80619 15.39959 3.51782 -3.51872 15.39959 2.80528 -6.92958 15.39959 2.86971 -4.05484 15.39959 1.95206 -4.38766 15.39959 1.00093 -7.35637 15.39959 1.46276 -4.50048 15.39959 -0.00042 -7.50048 15.39959 -0.00042 -4.38766 15.39959 -1.00176 -4.05484 15.39959 -1.95290 -7.35637 15.39959 -1.46360 -3.51872 15.39959 -2.80612 -2.80619 15.39959 -3.51866 -6.92958 15.39960 -2.87055 1.95200 15.39959 -4.05478 -1.95296 15.39959 -4.05478 1.00086 15.39959 -4.38760 -0.00048 15.39959 -4.50042 -1.00182 15.39959 -4.38760 -6.23650 15.39959 -4.16720 5.30282 15.39959 -5.30372 -5.30378 15.39959 -5.30372 4.16630 15.39959 -6.23644 -4.16726 15.39959 -6.23644 2.86965 15.39959 -6.92952 -2.87061 15.39959 -6.92952 -1.46366 15.39959 -7.35631 -0.00048 15.39959 -7.50042 1.46270 15.39959 -7.35631 -21.30162 -6.40750 23.03941 -21.30144 6.40653 23.02324 -21.05293 -6.40666 20.48503 -21.05293 6.40585 20.48503 -20.45402 -6.40666 18.02602 -20.45402 6.40585 18.02602 -19.51434 -6.40666 15.67261 -19.51434 6.40585 15.67261 -18.25390 -6.40666 13.47585 -18.25390 6.40585 13.47586 -16.69758 -6.40666 11.47834 -16.69758 6.40585 11.47835 -14.87602 -6.40666 9.71929 -12.82573 -6.40666 8.23382 -14.87602 6.40585 9.71929 -12.82573 6.40585 8.23383 -30.41643 -1.00040 19.53470 -29.69563 0.99960 16.13403 -28.54962 0.99960 12.85194 -26.99694 0.99960 9.74162 -26.99669 -1.00040 9.74117 -25.06267 0.99960 6.85320 -25.06223 -1.00040 6.85262 -22.77773 0.99960 4.23294 -22.77734 -1.00040 4.23257 -20.17892 0.99960 1.92327 -20.17875 -1.00040 1.92313 -17.30873 0.99960 -0.03817 -14.21282 0.99960 -1.62019 -17.30859 -1.00040 -0.03825 -14.21282 -1.00040 -1.62019 -30.69927 0.99943 23.04174 -30.70291 -1.00075 23.02165 -30.41645 0.99960 19.53490 -29.69556 -1.00040 16.13377 -28.54948 -1.00040 12.85162 35.56442 -1.00041 18.82635 35.89960 1.00018 23.02512 35.89865 -1.00030 23.04285 35.60408 0.99999 18.94442 34.68587 -1.00041 14.73265 34.68535 0.99959 14.73082 33.27864 -1.00041 10.78832 33.27790 0.99959 10.78664 31.36698 -1.00041 7.06207 31.36615 0.99959 7.06070 28.98425 -1.00041 3.61868 28.98302 0.99959 3.61714 26.17130 -1.00041 0.51695 26.16953 0.99959 0.51526 22.97604 -1.00041 -2.19013 22.97423 0.99959 -2.19147 19.45300 -1.00041 -4.45602 19.45189 0.99959 -4.45665 15.66376 -1.00041 -6.24092 15.66357 0.99959 -6.24101 11.64083 -0.99333 -7.51363 11.67386 0.99959 -7.51412 26.49701 -6.40790 23.00487 26.50031 6.40680 23.03065 26.24158 -6.40714 20.03259 26.24143 6.40632 20.03162 25.59420 -6.40714 17.12513 25.59365 6.40632 17.12325 24.56920 -6.40714 14.32965 24.56801 6.40632 14.32697 23.18434 -6.40714 11.69390 23.18226 6.40632 11.69051 21.45901 -6.40714 9.25799 21.45568 6.40632 9.25390 19.44430 -6.40714 7.08838 19.44081 6.40632 7.08509 17.34859 -6.40714 5.33769 17.34648 6.40632 5.33613 15.28735 6.40805 3.98648 15.28216 -6.40734 3.98093 6.23554 15.39959 -4.16720 2.80522 15.39959 -3.51866 6.92861 15.39959 -2.87055 3.51776 15.39959 -2.80612 4.05388 15.39959 -1.95290 7.35541 15.39959 -1.46360 4.38669 15.39959 -1.00176 4.49952 15.39959 -0.00042 7.49952 15.39959 -0.00042 4.38669 15.39959 1.00093 7.35541 15.39959 1.46276 4.05388 15.39959 1.95206 3.51776 15.39959 2.80528 6.92861 15.39959 2.86971 2.80522 15.39959 3.51782 4.32370 -10.50041 12.68256 4.32371 10.49959 12.68256 6.37333 -10.50041 11.78650 6.37333 10.49959 11.78649 8.24526 -10.50041 10.56201 8.24527 10.49959 10.56200 9.88738 -10.50041 9.04324 9.88738 10.49959 9.04324 11.25394 -10.50041 7.27254 11.25394 10.49959 7.27254 12.30691 -10.50041 5.29925 12.30692 10.49959 5.29925 12.48335 -6.40739 4.90258 12.71416 -9.07247 4.22862 12.43964 6.40632 4.97975 12.68775 9.13363 4.25919 13.25704 10.50525 2.32517 13.18964 -10.50041 -2.36255 12.57940 -10.50041 -4.61647 12.89855 -9.67272 -3.62335 12.57939 10.49959 -4.61647 13.18965 10.49959 -2.36255 12.88448 9.63719 -3.66647 12.21337 7.94797 -5.50560 11.58678 -10.50041 -6.73074 12.21218 -7.94114 -5.51293 11.58677 10.49959 -6.73074 11.51189 -6.06881 -6.85762 11.51664 6.08266 -6.85008 10.24212 -10.50041 -8.64053 10.67074 0.99921 -8.11293 10.66506 -1.00030 -8.11141 10.83492 -3.55577 -7.89054 10.88949 3.53806 -7.81976 10.24211 10.49959 -8.64054 8.58626 -10.50041 -10.28782 8.58625 10.49959 -10.28783 6.66952 -10.50041 -11.62256 6.66951 10.49959 -11.62256 4.55013 -10.50041 -12.60420 4.55012 10.49959 -12.60420 35.67098 -2.91176 23.41162 35.10701 -4.69323 24.05084 34.51861 -5.79096 22.99116 32.24020 -8.24452 23.00877 30.79715 -9.11441 22.99093 33.49187 -7.12698 22.99789 30.45738 -9.11051 19.15825 32.79480 -7.12707 17.06920 34.46150 -4.29016 16.35134 29.44318 -9.13203 15.42730 30.91869 -7.12707 11.40214 32.25470 -4.29016 10.03840 27.71212 -9.11051 10.95918 27.94042 -7.12707 6.22863 26.26256 -9.11051 8.52879 28.75688 -4.29016 4.33854 24.56230 -9.11051 6.26149 22.66412 -9.11051 4.21714 23.98184 -7.12707 1.76040 24.12780 -4.29015 -0.48793 20.67170 -9.11051 2.46631 18.69316 -9.11050 1.03600 19.20498 -7.12707 -1.81966 16.78089 -9.11050 -0.10730 18.57887 -4.29015 -4.22057 14.85429 -9.11536 -1.01545 14.19183 -8.09903 -3.02073 13.46651 -6.75450 -4.84491 11.88470 -3.19872 -7.20780 12.61154 -4.96985 -6.29130 35.27751 4.28659 23.01634 34.51856 5.79020 23.02481 33.49437 7.12394 23.03323 32.24012 8.24375 23.04163 30.79967 9.11036 23.00775 32.80304 7.12410 17.09722 30.54383 9.10968 19.72866 34.46772 4.28640 16.37301 29.90321 9.10968 16.56613 30.92986 7.12410 11.42224 28.88781 9.10968 13.50447 32.26332 4.28640 10.05390 27.51255 9.10968 10.58758 27.95177 7.12410 6.24101 25.79234 9.10968 7.85021 28.76567 4.28640 4.34804 23.75453 9.10968 5.33895 23.99086 7.12410 1.76602 21.51544 9.10968 3.16539 24.13470 4.28640 -0.48361 19.20959 7.12411 -1.81921 19.24568 9.10968 1.40820 17.04753 9.10969 0.03941 18.58228 4.28640 -4.22007 13.79232 7.10996 -4.35238 14.33083 8.00472 -3.01229 14.93884 9.10969 -1.01760 11.98112 3.17161 -7.16036 12.80422 5.00471 -6.27410 29.33309 9.40134 22.94975 30.08383 9.35425 22.99638 26.59515 7.15561 23.01965 26.87466 7.85676 23.00244 26.29238 7.85724 18.31521 27.27739 8.94702 18.00122 27.31973 8.46639 23.00948 27.90369 8.94572 22.99972 28.63104 9.40172 17.51563 28.58735 9.26455 23.00108 24.77109 7.85724 13.86825 25.63348 8.94702 13.27911 26.77773 9.40172 12.35932 22.37364 7.85724 9.82570 23.04388 8.94702 9.00187 23.85976 9.40172 7.72165 19.20110 7.85724 6.35800 19.62173 8.94702 5.35638 20.01346 9.40172 3.81929 15.35070 7.89198 3.53765 15.50805 9.08422 2.16505 15.18956 9.39706 0.20453 29.33042 -9.40730 22.97453 26.87267 -7.85526 22.99909 26.29455 -7.85542 18.33118 27.31945 -8.46778 23.01072 27.90180 -8.94608 22.98559 27.27926 -8.94623 18.02046 28.13668 -9.43483 15.71140 28.58736 -9.26600 22.99869 24.77486 -7.85542 13.87991 25.63741 -8.94623 13.29348 25.54921 -9.40238 10.13518 22.37741 -7.85541 9.83324 23.04801 -8.94623 9.01154 22.76218 -9.40238 6.43190 19.20344 -7.85541 6.36204 19.62439 -8.94623 5.36206 19.34743 -9.40238 3.29801 15.38655 -7.90337 3.56958 15.48328 -9.08043 2.17480 15.21953 -9.38465 0.20242 12.71159 -6.40639 4.50438 12.74383 6.40694 4.46699 13.11625 -6.40706 4.10916 13.17147 6.40534 4.06695 13.67181 -6.40729 3.82388 13.63432 6.40488 3.83865 14.16679 -6.40621 3.72869 14.16567 6.40517 3.73141 14.74828 -6.40559 3.77486 14.78990 6.40795 3.78526 12.58938 6.40624 4.72038 12.84993 8.84319 3.96175 13.47079 10.08159 2.14671 13.19677 8.55461 3.61157 13.69240 10.33885 0.10007 13.57160 8.34648 3.40352 13.86713 9.62944 2.02199 13.98212 8.18787 3.28635 14.07981 9.87364 0.14741 14.31560 9.33661 1.97631 14.40984 8.07622 3.25155 14.50780 6.40489 3.75358 14.52968 9.59005 0.18204 14.90134 9.13856 1.99861 14.85833 8.01625 3.30744 14.85845 9.46198 0.19548 13.48269 10.32783 -1.34628 13.95208 9.60692 -1.10757 14.66569 9.18686 -1.01369 12.93925 9.41483 -3.53728 12.36359 7.69195 -5.23325 13.11882 9.01344 -3.32705 13.65545 9.95317 -1.21632 11.60970 5.81624 -6.70498 12.71295 7.44038 -4.91488 13.41292 8.65007 -3.17383 11.93168 5.52365 -6.44411 10.94455 0.99738 -7.87140 11.28216 3.39613 -7.43880 13.14305 7.23847 -4.66389 13.77247 8.35124 -3.08141 14.29804 9.36786 -1.04865 12.31590 5.27040 -6.28185 11.73384 3.19752 -7.16874 11.35846 0.99781 -7.62773 14.18860 8.09826 -3.03375 10.90901 -0.99577 -7.89165 11.23977 -0.99918 -7.68268 13.55432 -10.50586 -0.44094 12.95099 -9.37372 -3.50425 12.34374 -7.74751 -5.26691 13.12794 -9.02062 -3.32480 11.63522 -5.80562 -6.68770 12.61567 -7.37134 -5.02173 13.92358 -9.63900 -1.11594 13.37768 -8.69748 -3.18544 11.02792 -3.52860 -7.64708 11.90387 -5.55691 -6.46360 14.30893 -9.34458 -1.04496 13.69316 -8.41773 -3.09304 11.37410 -3.36257 -7.37211 13.06867 -6.99306 -4.85521 12.23053 -5.32839 -6.30559 13.73215 -10.26075 0.11352 13.65034 -9.95749 -1.21899 14.04955 -9.92929 0.15063 14.42913 -9.63355 0.17846 14.87790 -9.45857 0.19826 12.84600 -8.85458 3.98163 13.32162 -10.49276 2.06913 13.08870 -8.63163 3.70309 12.92298 -6.40751 4.29738 13.47838 -10.08774 2.15254 13.44063 -8.41393 3.46980 13.38458 -6.40547 3.96435 13.77817 -9.70742 2.04130 13.80434 -8.24599 3.32269 14.08722 -9.47522 1.99617 14.36399 -8.07932 3.24406 14.45476 -9.27130 1.97544 14.96485 -9.12934 2.00828 14.97332 -8.00720 3.33362 7.49951 -10.60041 -0.00042 7.33562 -10.60041 -1.55976 6.85111 -10.60041 -3.05095 6.85110 -10.60041 3.05010 7.33562 -10.60041 1.55892 6.06714 -10.60041 4.40797 6.06714 -10.60041 -4.40881 5.01799 -10.60041 -5.57401 5.01799 -10.60041 5.57317 3.74951 -10.60041 6.49477 3.74952 -10.60041 -6.49561 3.74952 10.59959 -6.49561 3.74952 10.59959 6.49477 5.01800 10.59959 -5.57401 5.01800 10.59959 5.57317 6.06715 10.59959 -4.40881 6.06714 10.59959 4.40797 6.85111 10.59959 3.05010 6.85111 10.59959 -3.05095 7.33562 10.59959 -1.55976 7.49952 10.59959 -0.00042 7.33562 10.59959 1.55892 13.44627 10.50242 -0.01869 35.69546 3.05739 23.43314 -25.69792 -8.06854 26.52259 -26.35478 -8.04488 26.51994 -25.26371 -8.17598 26.64023 -24.16000 -9.02968 27.71689 -24.45500 -8.67075 27.23014 -24.83796 -8.37893 26.87214 -24.45243 8.67238 27.23327 -24.16008 9.02875 27.71671 -24.83342 8.38089 26.87540 -25.25692 8.17761 26.64293 -25.69196 8.06858 26.52351 -26.35262 8.04343 26.51944 30.89098 -8.06940 26.52353 31.55164 -8.04425 26.51945 30.45594 -8.17842 26.64295 30.03244 -8.38171 26.87541 29.65145 -8.67320 27.23329 29.35909 -9.02957 27.71672 29.35902 9.02887 27.71690 29.65402 8.66993 27.23016 30.03698 8.37811 26.87215 30.46273 8.17516 26.64024 30.89694 8.06772 26.52260 31.55380 8.04406 26.51995 30.30964 -9.28881 26.71105 29.51329 -9.40195 27.42233 29.85156 -9.38048 27.02176 29.21206 -9.39401 28.27592 29.30267 -9.39645 27.86289 28.81621 -9.33038 28.16568 28.36078 -9.18566 27.93929 27.89046 -8.94547 27.58514 27.52685 -8.66804 27.22668 27.16869 -8.30602 26.77394 26.87688 -7.86445 26.30823 26.71915 -7.53458 25.98483 26.60021 -7.17856 25.66446 26.52537 -6.80088 25.35357 -25.11475 -9.28649 26.70846 -24.73201 -9.37661 26.95330 -24.45204 -9.39816 27.23272 -24.18235 -9.39973 27.66239 -24.01589 -9.38310 28.21809 -23.61292 -9.32953 28.16398 -23.27349 -9.22654 28.00972 -22.92326 -9.07597 27.77525 -22.57237 -8.86007 27.47989 -22.32934 -8.66934 27.22835 -22.09323 -8.43956 26.94403 -21.87564 -8.17419 26.63824 -21.68406 -7.87555 26.31960 -21.52446 -7.54521 25.99483 -21.40323 -7.18620 25.67105 -21.32681 -6.80432 25.35626 30.31377 9.28566 26.70846 29.93103 9.37579 26.95331 29.65106 9.39735 27.23273 29.38137 9.39891 27.66240 29.21495 9.38221 28.21792 28.80724 9.32764 28.16212 28.46433 9.22273 28.00512 28.10902 9.06841 27.76509 27.75194 8.84543 27.46115 27.50480 8.64778 27.20188 27.26728 8.41127 26.91131 27.05169 8.14141 26.60291 26.86490 7.84184 26.28602 26.64308 7.35032 25.80266 26.52453 6.79367 25.34855 -25.11072 9.28798 26.71104 -24.31433 9.40116 27.42237 -24.65256 9.37968 27.02179 -24.01304 9.39320 28.27591 -24.10299 9.39558 27.86508 -23.61179 9.32847 28.16351 -23.15257 9.18113 27.93344 -22.80202 9.00596 27.68408 -22.55539 8.84721 27.46354 -22.30408 8.64627 27.19994 -22.06303 8.40544 26.90438 -21.84580 8.13166 26.59218 -21.57421 7.67631 26.10763 -21.39569 7.15675 25.64643 -21.32504 6.79000 25.34565 -25.60049 9.11070 26.53998 -26.06235 8.87196 26.50053 -26.53616 8.59014 26.57264 -26.98871 8.28209 26.76077 -27.93840 7.48716 25.94127 -28.70745 6.64783 25.23596 -29.35557 5.73244 24.61157 -29.90789 4.69264 24.05094 -30.33595 3.53512 23.58323 -30.60797 2.28678 23.23998 30.79951 9.11069 26.53999 31.73488 8.59032 26.57257 31.26123 8.87203 26.50054 32.18773 8.28208 26.76079 33.13742 7.48715 25.94128 33.90647 6.64782 25.23597 34.55459 5.73243 24.61159 35.10691 4.69263 24.05095 30.79951 -9.11152 26.54000 31.26137 -8.87278 26.50054 31.73518 -8.59096 26.57266 32.18773 -8.28291 26.76079 33.13676 -7.48862 25.94187 33.90627 -6.64890 25.23616 34.55468 -5.73310 24.61150 -25.60049 -9.11151 26.53998 -26.53586 -8.59113 26.57256 -26.06221 -8.87285 26.50052 -26.98871 -8.28290 26.76077 -27.93774 -7.48861 25.94185 -28.70725 -6.64889 25.23615 -29.35566 -5.73309 24.61148 -29.90799 -4.69322 24.05083 -30.33597 -3.53584 23.58320 -30.70049 10.98821 34.50007 -30.70049 10.88394 32.40859 -30.70049 10.69424 36.57342 -30.70049 10.38520 30.37476 -30.70050 10.01268 38.55349 -30.70049 9.51008 28.47230 -30.70050 8.96824 40.36852 -30.70049 8.29029 26.77015 -30.70050 7.59876 41.95273 -30.70049 6.77003 25.33001 -30.70050 5.95388 43.24871 -30.70049 5.00440 24.20407 -30.70050 4.09320 44.20949 -30.70049 3.05740 23.43312 -30.70050 2.08417 44.80024 -30.70050 -0.00040 44.99957 -30.70050 -2.08498 44.80024 -30.70049 -3.05820 23.43312 -30.70050 -4.09401 44.20949 -30.70049 -5.00521 24.20407 -30.70050 -5.95468 43.24871 -30.70049 -6.77083 25.33001 -30.70050 -7.59957 41.95274 -30.70049 -8.29109 26.77015 -30.70050 -8.96904 40.36852 -30.70049 -9.51088 28.47230 -30.70050 -10.01348 38.55350 -30.70049 -10.38600 30.37476 -30.70049 -10.88474 32.40859 -30.70049 -10.69504 36.57343 -30.70049 -10.98901 34.50008 -21.30049 6.40700 25.05836 -21.30049 -6.40781 25.05836 -21.30049 7.95500 26.40277 -21.30049 -7.95582 26.40277 -21.30049 9.22661 28.01107 -21.30049 -9.22742 28.01107 -21.30049 10.17766 29.82740 -21.30049 -10.17846 29.82740 -21.30049 10.77512 31.78865 -21.30049 -10.77592 31.78866 -21.30049 10.99824 33.82669 -21.30049 -10.99904 33.82669 -21.30049 10.83929 35.87072 -21.30049 -10.84009 35.87072 -21.30049 10.30379 37.84973 -21.30049 -10.30459 37.84973 -21.30049 9.41035 39.69498 -21.30049 -9.41116 39.69498 -21.30049 8.19002 41.34239 -21.30049 -8.19083 41.34239 -21.30049 6.68519 42.73472 -21.30049 -6.68600 42.73473 -21.30049 4.94813 43.82362 -21.30049 -4.94894 43.82363 -21.30050 3.03919 44.57127 -21.30050 1.02466 44.95171 -21.30050 -3.04000 44.57127 -21.30050 -1.02547 44.95171 26.49950 1.02465 44.95172 26.49950 -1.02548 44.95172 26.49950 3.03918 44.57128 26.49950 -3.04001 44.57129 26.49951 4.94812 43.82364 26.49951 -4.94895 43.82364 26.49951 6.68518 42.73473 26.49951 -6.68601 42.73474 26.49951 8.19001 41.34240 26.49951 -8.19084 41.34240 26.49951 9.41034 39.69499 26.49951 -9.41117 39.69500 26.49951 10.30378 37.84974 26.49951 -10.30460 37.84974 26.49951 10.83928 35.87073 26.49951 -10.84010 35.87073 26.49951 10.99823 33.82670 26.49951 -10.99905 33.82671 26.49951 10.77511 31.78867 26.49951 -10.77593 31.78867 26.49951 10.17765 29.82741 26.49951 -10.17847 29.82741 26.49951 9.22661 28.01108 26.49951 -9.22743 28.01108 26.49951 7.95500 26.40278 26.49951 -7.95582 26.40278 26.49951 6.40699 25.05838 26.49951 -6.40781 25.05838 35.89951 10.98820 34.50008 35.89951 10.88393 32.40860 35.89951 10.69423 36.57343 35.89951 10.38519 30.37477 35.89951 10.01267 38.55351 35.89951 9.51007 28.47231 35.89951 8.96823 40.36853 35.89951 8.29028 26.77017 35.89951 7.59875 41.95275 35.89951 6.77002 25.33003 35.89951 5.95387 43.24872 35.89951 5.00439 24.20408 35.89951 4.09319 44.20951 35.89951 3.05739 23.43314 35.89951 2.08416 44.80026 35.89951 -0.00041 44.99959 35.89951 -2.08499 44.80026 35.89951 -3.05821 23.43314 35.89951 -4.09402 44.20951 35.89951 -5.00522 24.20408 35.89951 -5.95470 43.24872 35.89951 -6.77085 25.33003 35.89951 -7.59958 41.95275 35.89951 -8.29110 26.77017 35.89951 -8.96905 40.36853 35.89951 -9.51089 28.47231 35.89951 -10.01349 38.55351 35.89951 -10.38601 30.37477 35.89951 -10.88475 32.40860 35.89951 -10.98902 34.50009 35.89951 -10.69505 36.57344 -30.60796 -2.28766 23.24000 + + + + + + + + + + 0.00351 -0.99986 0.01651 0.00000 -0.99986 0.01683 -0.88619 0.44850 -0.11622 -0.78877 0.60651 -0.09996 -0.83885 0.52713 -0.13587 -0.65725 0.73765 -0.15457 -0.50717 0.86073 -0.04374 -0.00723 -0.99986 -0.01540 -0.00979 -0.99986 -0.01391 -0.00995 -0.99986 -0.01370 -0.01209 -0.99985 -0.01203 -0.01357 -0.99986 -0.00945 -0.01317 -0.99984 -0.01186 -0.01514 -0.99986 -0.00702 -0.01511 -0.99985 -0.00872 -0.01626 -0.99986 -0.00431 -0.01638 -0.99985 -0.00532 -0.01682 -0.99986 -0.00177 -0.01696 -0.99986 -0.00144 -0.01694 -0.99985 0.00178 -0.01949 -0.99974 0.01192 -0.02103 -0.99976 0.00683 -0.02161 -0.99974 -0.00720 -0.01202 -0.99984 0.01306 -0.01566 -0.99984 0.00904 -0.01613 -0.99984 0.00811 -0.01251 -0.99986 0.01126 -0.01174 -0.99985 0.01240 -0.00939 -0.99986 0.01401 -0.01006 -0.99985 0.01384 -0.00698 -0.99986 0.01547 -0.00939 0.99986 0.01401 -0.01174 0.99985 0.01240 -0.01251 0.99986 0.01126 -0.01364 0.99985 0.01028 -0.01460 0.99986 0.00843 -0.01435 0.99986 0.00870 -0.01944 0.99980 -0.00420 -0.01935 0.99979 0.00629 -0.01869 0.99979 0.00875 -0.01694 0.99985 0.00178 -0.01695 0.99986 -0.00144 -0.01682 0.99986 -0.00177 -0.01650 0.99985 -0.00438 -0.01602 0.99986 -0.00521 -0.01551 0.99985 -0.00718 -0.01457 0.99986 -0.00842 -0.01402 0.99985 -0.00977 -0.01253 0.99986 -0.01128 -0.01209 0.99985 -0.01203 -0.00975 0.99986 -0.01385 -0.95927 0.00000 -0.28251 -0.95855 0.00402 -0.28490 -0.95788 0.00000 -0.28717 -0.90737 0.00000 -0.42034 -0.90737 0.00000 -0.42034 -0.96656 -0.00572 -0.25638 -0.46377 -0.36064 -0.80923 -0.45318 -0.53536 -0.71275 -0.99676 0.00262 -0.08039 -0.99223 -0.09399 -0.08153 -0.94714 -0.27414 -0.16666 -0.99664 -0.00000 -0.08188 -0.97827 0.00001 -0.20735 -0.18189 -0.98107 -0.06642 -0.16835 -0.98346 -0.06677 -0.97827 -0.00001 -0.20736 -0.94410 0.00001 -0.32965 -0.94410 -0.00001 -0.32967 0.99529 0.00011 0.09690 0.99524 0.00000 0.09744 0.97160 -0.00000 0.23664 0.97160 0.00000 0.23664 0.92871 -0.00000 0.37082 0.20791 -0.00842 -0.97811 0.09802 0.00749 -0.99516 0.00000 -0.00856 -0.99996 -0.09801 0.00749 -0.99516 -0.20791 -0.00842 -0.97811 -0.29027 0.00722 -0.95692 -0.40672 -0.00803 -0.91352 -0.47139 0.00669 -0.88190 -0.58777 -0.00735 -0.80900 -0.63438 0.00589 -0.77300 -0.74313 -0.00642 -0.66912 -0.77300 0.00481 -0.63439 -0.86601 -0.00521 -0.49999 -0.88192 0.00348 -0.47139 -0.95105 -0.00374 -0.30901 -0.95694 0.00187 -0.29029 -0.99452 -0.00200 -0.10453 -0.99518 0.00000 -0.09802 -0.33023 -0.01785 0.94373 -0.23926 0.02143 0.97072 -0.11194 -0.01875 0.99354 0.00000 0.02187 0.99976 0.11194 -0.01875 0.99354 0.23926 0.02143 0.97072 0.33023 -0.01785 0.94373 0.46462 0.02008 0.88528 0.53196 -0.01607 0.84662 0.66302 0.01785 0.74839 0.70705 -0.01339 0.70704 0.82289 0.01472 0.56800 0.84668 -0.00982 0.53201 0.93496 0.01071 0.35459 0.94387 -0.00535 0.33027 0.99271 -0.00000 0.12054 0.99369 0.00624 0.11196 0.99371 0.00000 -0.11196 0.99269 0.00580 -0.12054 0.94387 -0.00535 -0.33028 0.93496 0.01071 -0.35459 0.84668 -0.00981 -0.53201 0.82290 0.01472 -0.56800 0.70704 -0.01339 -0.70704 0.66302 0.01785 -0.74839 0.53196 -0.01607 -0.84661 0.46463 0.02008 -0.88528 0.33023 -0.01785 -0.94373 0.23926 0.02143 -0.97072 0.11194 -0.01875 -0.99354 0.00000 0.02187 -0.99976 -0.11194 -0.01875 -0.99354 -0.23926 0.02143 -0.97072 -0.33023 -0.01785 -0.94373 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.99452 -0.00000 0.10453 -0.99518 -0.00214 0.09802 -0.95694 0.00187 0.29028 -0.95105 -0.00374 0.30902 -0.88192 0.00348 0.47139 -0.86601 -0.00521 0.49999 -0.77300 0.00481 0.63439 -0.74313 -0.00642 0.66912 -0.63438 0.00588 0.77300 -0.58777 -0.00735 0.80900 -0.47139 0.00669 0.88190 -0.40672 -0.00803 0.91352 -0.29028 0.00722 0.95692 -0.20790 -0.00843 0.97811 -0.09801 0.00749 0.99516 0.00000 -0.00856 0.99996 0.09801 0.00749 0.99516 0.20790 -0.00843 0.97811 0.00350 0.99986 -0.01649 0.00351 0.99986 0.01650 0.00145 0.99985 -0.01703 0.00133 0.99985 0.01702 0.00000 0.99986 -0.01683 -0.00000 0.99986 0.01683 -0.00153 0.99985 -0.01702 -0.00350 0.99986 -0.01648 -0.00152 0.99985 0.01701 -0.00432 0.99985 0.01649 -0.00350 0.99986 0.01649 -0.00446 0.99985 -0.01647 -0.00688 0.99986 -0.01545 -0.00689 0.99986 0.01548 -0.00698 0.99986 0.01547 -0.00723 0.99986 -0.01540 -0.01001 0.99985 -0.01378 -0.01006 0.99985 0.01384 0.20790 0.00843 0.97811 0.09801 -0.00749 0.99516 -0.00000 0.00856 0.99996 -0.09801 -0.00749 0.99516 -0.20791 0.00843 0.97811 -0.29028 -0.00722 0.95692 -0.40672 0.00803 0.91352 -0.47139 -0.00669 0.88190 -0.58777 0.00735 0.80900 -0.63438 -0.00588 0.77300 -0.74313 0.00642 0.66912 -0.77300 -0.00481 0.63439 -0.86601 0.00521 0.49999 -0.88192 -0.00348 0.47139 -0.95105 0.00374 0.30902 -0.95694 -0.00187 0.29028 -0.99452 0.00200 0.10453 -0.99518 -0.00000 0.09802 -0.99452 0.00000 -0.10453 -0.99518 0.00214 -0.09802 -0.95694 -0.00187 -0.29029 -0.95105 0.00374 -0.30902 -0.88192 -0.00348 -0.47139 -0.86601 0.00521 -0.49999 -0.77300 -0.00481 -0.63439 -0.74313 0.00642 -0.66912 -0.63438 -0.00589 -0.77300 -0.58777 0.00735 -0.80900 -0.47139 -0.00669 -0.88190 -0.40672 0.00803 -0.91352 -0.29027 -0.00722 -0.95692 -0.20791 0.00842 -0.97811 -0.09802 -0.00749 -0.99516 0.00000 0.00856 -0.99996 0.09802 -0.00749 -0.99516 0.20791 0.00842 -0.97811 -0.00428 -0.99987 -0.01582 -0.00432 -0.99985 0.01649 -0.00689 -0.99986 0.01548 -0.00733 -0.99984 -0.01645 -0.00350 -0.99986 0.01649 -0.00149 -0.99986 -0.01650 -0.00368 -0.99984 -0.01729 -0.00152 -0.99985 0.01701 0.00000 -0.99986 -0.01683 0.00133 -0.99985 0.01702 0.00145 -0.99985 -0.01703 0.00350 -0.99986 -0.01649 -0.29843 0.80194 -0.51753 -0.45546 0.76061 -0.46263 -0.48572 0.74811 -0.45212 -0.52648 0.72710 -0.44062 -0.70516 0.61922 -0.34541 -0.68729 0.63389 -0.35471 -0.79346 0.54430 -0.27233 -0.85010 0.47351 -0.23050 -0.92476 0.35495 -0.13725 -0.88546 0.42818 -0.18060 -0.97510 0.21969 -0.03025 -0.99355 0.10933 0.02998 -0.99487 0.00529 0.10098 -0.44914 0.56393 -0.69301 -0.48712 0.33907 -0.80483 -0.46872 0.11111 -0.87633 -0.48781 0.55012 -0.67779 -0.56989 0.12661 -0.81191 -0.50827 0.32733 -0.79656 -0.52244 0.54094 -0.65912 -0.71199 0.41889 -0.56357 -0.76447 0.38273 -0.51875 -0.75314 0.23466 -0.61459 -0.75445 0.07598 -0.65194 -0.76357 0.23187 -0.60266 -0.80030 0.34611 -0.48961 -0.77744 0.07742 -0.62418 -0.89245 0.25985 -0.36881 -0.88324 0.13720 -0.44841 -0.89344 0.04446 -0.44698 -0.89802 0.12735 -0.42112 -0.93206 0.19411 -0.30591 -0.92669 0.04989 -0.37250 -0.96319 0.02410 -0.26775 -0.97120 0.12167 -0.20487 -0.98112 0.08870 -0.17186 -0.57327 0.00000 -0.81936 -0.58559 0.00572 -0.81059 -0.78071 -0.00192 -0.62489 -0.80115 0.00518 -0.59844 -0.92784 -0.00355 -0.37297 -0.93332 0.00059 -0.35905 -0.54334 -0.12355 -0.83037 -0.55062 -0.32950 -0.76697 -0.56899 -0.31769 -0.75850 -0.58230 -0.47952 -0.65650 -0.47157 -0.55221 -0.68752 -0.57960 -0.12850 -0.80470 -0.65890 -0.45141 -0.60174 -0.74087 -0.07739 -0.66717 -0.75046 -0.23110 -0.61920 -0.73276 -0.24796 -0.63370 -0.74409 -0.40715 -0.52968 -0.79988 -0.07795 -0.59507 -0.83756 -0.30814 -0.45116 -0.93299 -0.02422 -0.35908 -0.92289 -0.03443 -0.38352 -0.92643 -0.09817 -0.36343 -0.91099 -0.12348 -0.39350 -0.91770 -0.21960 -0.33106 -0.92934 -0.19612 -0.31285 -0.99452 -0.01997 -0.10259 -0.47080 -0.75241 -0.46069 -0.45668 -0.75918 -0.46378 -0.65213 -0.65623 -0.37958 -0.61916 -0.68060 -0.39169 -0.82908 -0.50451 -0.24104 -0.85407 -0.47034 -0.22212 -0.92231 -0.36337 -0.13159 -0.99192 -0.12653 0.00876 -0.98384 -0.17818 -0.01749 -0.99580 -0.01898 0.08960 0.25602 -0.67271 0.69420 0.10951 -0.95426 0.27821 -0.24299 -0.96070 -0.13420 0.02366 -0.93898 0.34315 0.41629 -0.24307 0.87614 0.25610 -0.67271 0.69417 -0.36230 -0.93025 -0.05802 0.36996 -0.25534 0.89327 0.10702 -0.62868 0.77027 -0.13311 -0.91757 0.37463 -0.52306 -0.85223 -0.01049 0.03553 -0.62578 0.77919 0.17265 -0.21866 0.96041 -0.49931 -0.86639 -0.00769 -0.29615 -0.83056 0.47167 0.11936 -0.22311 0.96746 -0.12565 -0.56539 0.81519 -0.00082 -0.19219 0.98136 -0.17977 -0.52640 0.83101 -0.39503 -0.78686 0.47414 -0.77611 -0.62215 0.10282 -0.67472 -0.72940 0.11282 -0.51628 -0.68662 0.51187 -0.15957 -0.18279 0.97011 -0.24409 -0.14826 0.95835 -0.34379 -0.44941 0.82452 -0.55399 -0.66213 0.50466 -0.36494 -0.43114 0.82519 -0.42580 -0.11643 0.89729 -0.49952 -0.34354 0.79527 -0.52836 -0.31199 0.78962 -0.69334 -0.51702 0.50197 -0.92543 -0.28426 0.25055 -0.79022 -0.55988 0.24917 -0.43711 -0.11689 0.89178 -0.84444 -0.13410 0.51859 -0.80441 -0.23405 0.54603 -0.69684 -0.15924 0.69933 -0.66097 -0.04772 0.74889 -0.66379 -0.04752 0.74641 -0.73766 -0.09046 0.66908 0.38198 -0.00000 0.92417 0.39651 0.00076 0.91803 0.12271 -0.00007 0.99244 0.13374 0.00042 0.99102 -0.16191 -0.00126 0.98680 -0.14660 -0.00049 0.98920 -0.43971 0.00043 0.89814 -0.42046 0.00134 0.90731 -0.66472 -0.00107 0.74709 -0.64854 -0.00010 0.76118 -0.20688 0.96904 -0.13476 -0.21729 0.96682 -0.13436 0.02220 0.93724 0.34797 0.18340 0.66030 0.72826 0.32370 0.26370 0.90867 -0.04563 0.93478 0.35228 0.15402 0.64342 0.74986 0.38427 0.24588 0.88988 -0.42875 0.90238 -0.04338 0.13021 0.21703 0.96744 -0.23944 0.86631 0.43837 -0.43986 0.89707 -0.04216 0.12412 0.21418 0.96888 -0.00829 0.60805 0.79386 -0.26215 0.85896 0.43984 -0.03777 0.58651 0.80906 -0.58919 0.80734 0.03251 -0.40605 0.76730 0.49635 -0.60111 0.79844 0.03407 -0.27437 0.47832 0.83423 -0.47610 0.72411 0.49900 -0.76444 0.63397 0.11712 -0.23688 0.18363 0.95403 -0.32759 0.46151 0.82444 -0.76955 0.62765 0.11774 -0.62231 0.56695 0.53971 -0.14442 0.16129 0.97628 -0.41513 0.39049 0.82170 -0.58425 0.59872 0.54789 -0.80418 0.57658 0.14438 -0.41713 0.12663 0.89998 -0.57940 0.81267 0.06214 -0.90601 0.33872 0.25379 -0.58005 0.05536 0.81270 -0.64048 0.24568 0.72761 -0.64772 0.05054 0.76020 -0.53358 0.65124 0.53960 -0.73246 0.10072 0.67332 -0.81922 0.28667 0.49668 -0.69807 0.02783 0.71549 -0.72391 0.10738 0.68148 -0.31865 -0.94762 -0.02173 -0.06834 -0.99280 -0.09833 -0.18893 -0.98183 -0.01773 0.18189 -0.98318 0.01629 0.42299 -0.90569 -0.02856 0.63070 -0.77024 0.09462 0.80590 -0.58653 0.08063 0.27517 -0.96051 0.04134 0.98733 -0.12632 0.09608 0.92845 -0.37112 0.01598 0.97574 -0.16150 0.14783 0.72060 -0.68471 0.10910 -0.19528 -0.98025 -0.03112 0.30206 -0.95068 0.07043 -0.17277 -0.98376 -0.04857 -0.18246 -0.98214 -0.04587 0.93546 -0.27020 0.22784 0.26518 -0.95786 0.11037 0.27646 -0.95469 0.11015 0.67463 -0.68266 0.28079 0.90310 -0.20439 0.37768 0.91614 -0.16395 0.36580 0.67176 -0.68543 0.28093 0.83344 -0.27693 0.47821 0.27276 -0.94729 0.16805 -0.15712 -0.98294 -0.09563 -0.16577 -0.98153 -0.09545 0.22350 -0.96046 0.16605 0.58707 -0.68199 0.43616 0.58285 -0.68612 0.43533 0.78883 -0.17497 0.58918 0.77010 -0.21665 0.60001 -0.16041 -0.97986 -0.11895 -0.14122 -0.98157 -0.12873 -0.13494 -0.98273 -0.12662 0.23734 -0.94703 0.21635 0.66915 -0.26852 0.69292 0.46707 -0.68165 0.56321 0.45988 -0.68920 0.55992 0.17772 -0.95945 0.21879 0.62189 -0.15765 0.76707 -0.12771 -0.98023 -0.15113 -0.09872 -0.98464 -0.14399 0.18438 -0.95175 0.24532 0.56828 -0.24866 0.78436 -0.09765 -0.98290 -0.15615 -0.33794 0.94076 -0.02775 -0.07269 0.99529 -0.06413 0.30268 0.95198 0.04598 0.18138 0.98333 -0.01276 0.42303 0.90386 0.06391 -0.17534 0.98415 -0.02653 0.62732 0.77298 0.09476 0.80600 0.58643 0.08040 0.98750 0.12448 0.09665 0.92894 0.36986 0.01630 0.71988 0.68544 0.10932 0.97551 0.16260 0.14814 0.93534 0.27064 0.22781 -0.19594 0.97941 -0.04864 0.28073 0.95265 0.11685 0.67397 0.68342 0.28054 0.90780 0.17821 0.37965 0.90756 0.21216 0.36238 0.67114 0.68614 0.28068 0.28346 0.95155 0.11918 -0.17073 0.98270 -0.07179 -0.16712 0.98356 -0.06843 0.83334 0.27735 0.47815 -0.17478 0.97917 -0.10335 0.58650 0.68275 0.43575 0.24297 0.95309 0.18052 0.78346 0.20920 0.58517 0.77899 0.15747 0.60694 0.58231 0.68684 0.43493 -0.14277 0.98390 -0.10752 -0.14957 0.98135 -0.12078 0.24668 0.95112 0.18578 0.66906 0.26896 0.69283 -0.13505 0.98001 -0.14608 0.45976 0.69678 0.55056 0.46368 0.68205 0.56552 0.19541 0.95351 0.22943 0.62196 0.15862 0.76681 -0.10524 0.98512 -0.13587 0.20648 0.94390 0.25772 0.56750 0.25380 0.78328 -0.10671 0.98194 -0.15621 -0.60667 0.79123 -0.07686 -0.56817 0.81074 -0.14105 -0.79584 0.53524 -0.28311 -0.57820 0.78954 -0.20569 -0.80107 0.51949 -0.29735 -0.91713 0.20731 -0.34044 -0.91737 0.23627 -0.32032 -0.54765 0.80610 -0.22425 -0.88170 0.16993 -0.44015 -0.51831 0.79181 -0.32310 -0.51464 0.80158 -0.30432 -0.71413 0.54022 -0.44517 -0.71686 0.51486 -0.47014 -0.81520 0.22276 -0.53463 -0.81227 0.21056 -0.54395 -0.45559 0.81060 -0.36791 -0.74244 0.17211 -0.64743 -0.60027 0.54466 -0.58568 -0.43952 0.78926 -0.42883 -0.67393 0.23158 -0.70157 -0.65209 0.19089 -0.73372 -0.59561 0.51069 -0.62004 -0.40107 0.80680 -0.43384 -0.33502 0.79280 -0.50914 -0.33830 0.80043 -0.49484 -0.45934 0.54863 -0.69858 -0.55491 0.18086 -0.81201 -0.47588 0.34278 -0.80996 -0.46281 0.55781 -0.68895 -0.51130 0.22340 -0.82986 -0.45217 0.11213 -0.88486 -0.88620 -0.44851 -0.11617 -0.78284 -0.60273 -0.15456 -0.84468 -0.52445 -0.10705 -0.96417 -0.23323 -0.12640 -0.66324 -0.74368 -0.08398 -0.51400 -0.84905 -0.12211 -0.64066 -0.76661 -0.04310 -0.59317 -0.79951 -0.09452 -0.57276 -0.80697 -0.14400 -0.57500 -0.79218 -0.20454 -0.54901 -0.80696 -0.21773 -0.79566 -0.53556 -0.28303 -0.80089 -0.51981 -0.29728 -0.91311 -0.22662 -0.33893 -0.88166 -0.17013 -0.44014 -0.71397 -0.54053 -0.44505 -0.50961 -0.79962 -0.31766 -0.54216 -0.78013 -0.31218 -0.71671 -0.51519 -0.47002 -0.81695 -0.21343 -0.53576 -0.80918 -0.22706 -0.54191 -0.47347 -0.80782 -0.35108 -0.74240 -0.17231 -0.64742 -0.43291 -0.79637 -0.42235 -0.45040 -0.78645 -0.42265 -0.60015 -0.54497 -0.58551 -0.59549 -0.51101 -0.61988 -0.67968 -0.19350 -0.70752 -0.64206 -0.25654 -0.72245 -0.37976 -0.80859 -0.44940 -0.33611 -0.79429 -0.50610 -0.32117 -0.80258 -0.50271 -0.45843 -0.54912 -0.69879 -0.55489 -0.18107 -0.81198 -0.50368 -0.23068 -0.83252 -0.45098 -0.13321 -0.88254 -0.99641 0.00112 -0.08466 -0.99729 0.01576 -0.07190 -0.99637 -0.00893 -0.08466 -0.99602 -0.01019 -0.08855 -0.99255 -0.00087 -0.12183 -0.98077 -0.00810 -0.19502 -0.96656 -0.00561 -0.25638 -0.98287 0.01723 -0.18351 -0.97605 -0.00303 -0.21754 -0.90737 0.00000 -0.42034 -0.82060 0.00000 -0.57150 -0.82060 0.00000 -0.57150 -0.70890 0.00000 -0.70531 -0.70890 0.00000 -0.70531 -0.57566 0.00000 -0.81769 -0.57566 0.00000 -0.81769 -0.42492 0.00000 -0.90523 -0.42492 0.00000 -0.90523 -0.26128 0.00000 -0.96526 -0.26128 0.00000 -0.96526 -0.08971 0.00000 -0.99597 -0.08971 0.00000 -0.99597 0.08460 0.00000 -0.99642 0.08460 0.00000 -0.99642 0.07779 -0.00000 0.99697 0.07779 -0.00000 0.99697 -0.08916 -0.00000 0.99602 -0.08916 -0.00000 0.99602 -0.25363 0.00000 0.96730 -0.25363 -0.00000 0.96730 -0.41102 -0.00000 0.91162 -0.41102 -0.00000 0.91162 -0.55695 -0.00000 0.83054 -0.55696 -0.00000 0.83054 -0.68736 -0.00000 0.72632 -0.68736 -0.00000 0.72632 -0.79835 0.02528 0.60167 -0.77337 0.00354 0.63395 -0.75022 -0.00000 0.66119 -0.79945 -0.02809 0.60007 -0.77570 -0.00524 0.63108 -0.74247 0.00028 0.66988 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.92871 -0.00000 0.37082 0.86737 -0.00000 0.49767 0.86737 -0.00000 0.49767 0.78883 -0.00000 0.61461 0.78883 -0.00000 0.61461 0.69466 -0.00000 0.71934 0.69466 -0.00000 0.71934 0.58671 -0.00000 0.80980 0.58671 -0.00000 0.80980 -0.89471 0.00001 -0.44664 -0.89471 -0.00001 -0.44665 -0.83090 0.00002 -0.55642 -0.83089 -0.00002 -0.55644 -0.75368 0.00002 -0.65724 -0.75367 -0.00002 -0.65725 -0.66430 0.00001 -0.74746 -0.66430 -0.00001 -0.74747 -0.56422 0.00001 -0.82563 -0.56421 -0.00001 -0.82563 -0.45503 0.00000 -0.89047 -0.45503 0.00000 -0.89047 -0.95313 0.27559 -0.12490 -0.97949 0.08775 -0.18137 -0.96015 0.26855 -0.07742 -0.96329 0.17434 -0.20417 -0.96325 -0.17453 -0.20417 -0.92437 -0.20337 -0.32278 0.94185 -0.00006 -0.33603 0.94183 0.00006 -0.33608 0.88974 -0.00006 -0.45646 0.88972 0.00006 -0.45651 0.82232 -0.00005 -0.56902 0.82229 0.00006 -0.56907 0.74075 -0.00006 -0.67178 0.74070 0.00008 -0.67184 0.64642 -0.00008 -0.76298 0.64636 0.00007 -0.76303 0.54094 -0.00007 -0.84106 0.54089 0.00004 -0.84109 0.42613 -0.00004 -0.90466 0.42611 0.00000 -0.90467 0.30163 -0.00001 -0.95343 0.30399 -0.00527 -0.95266 -0.93888 0.00001 0.34425 -0.93884 -0.00001 0.34435 -0.88525 0.00002 0.46512 -0.88518 -0.00002 0.46526 -0.81604 0.00002 0.57799 -0.81592 -0.00003 0.57816 -0.73278 0.00003 0.68046 -0.73263 -0.00002 0.68063 -0.64110 0.00002 0.76745 -0.64098 -0.00001 0.76756 -0.54819 0.00001 0.83635 -0.54884 -0.00014 0.83592 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.24257 -0.00000 0.97013 0.24257 -0.00000 0.97013 0.40057 -0.00000 0.91626 0.40058 0.00000 0.91626 0.54742 0.00000 0.83686 0.54742 0.00000 0.83686 0.67900 0.00000 0.73414 0.67900 -0.00000 0.73414 0.79165 -0.00000 0.61097 0.79165 -0.00000 0.61097 0.88225 -0.00000 0.47078 0.88225 -0.00000 0.47078 0.91370 -0.00000 0.40640 0.93759 -0.00672 0.34768 0.92759 0.00091 0.37360 0.94072 0.00403 0.33917 0.95201 0.03380 0.30420 0.96359 -0.05853 -0.26089 0.96386 0.05350 -0.26097 0.94569 -0.02266 -0.32427 0.92463 -0.04605 -0.37807 0.89371 0.15883 -0.41958 0.90505 0.01824 -0.42491 0.88798 0.00184 -0.45989 0.88884 -0.00173 -0.45821 0.80446 -0.00273 -0.59399 0.78816 -0.00081 -0.61547 0.82555 -0.00953 -0.56425 0.81766 -0.00267 -0.57570 0.83796 0.00144 -0.54573 0.77615 0.00000 -0.63054 0.79321 0.00197 -0.60894 0.81763 0.00816 -0.57568 0.70527 -0.00000 -0.70894 0.70527 -0.00000 -0.70894 0.57146 -0.00000 -0.82063 0.57145 0.00000 -0.82064 0.42028 0.00000 -0.90740 0.42028 0.00000 -0.90739 0.25633 0.00000 -0.96659 0.25633 0.00000 -0.96659 0.92086 -0.35182 -0.16806 0.98805 -0.13279 -0.07831 0.96310 -0.25221 -0.09395 0.55997 -0.81528 -0.14752 0.96392 -0.16753 -0.20687 0.57062 -0.79919 -0.18891 0.80059 -0.53741 -0.26504 0.80832 -0.51650 -0.28256 0.92052 -0.21165 -0.32842 0.92062 -0.22114 -0.32182 0.53512 -0.81793 -0.21126 0.87674 -0.17035 -0.44979 0.72731 -0.54379 -0.41870 0.53027 -0.78663 -0.31627 0.52543 -0.79526 -0.30248 0.82817 -0.23633 -0.50822 0.73286 -0.51055 -0.44973 0.80912 -0.17844 -0.55989 0.47111 -0.80823 -0.35329 0.45570 -0.78314 -0.42312 0.45228 -0.79679 -0.40070 0.62550 -0.54923 -0.55416 0.71779 -0.24703 -0.65096 0.70751 -0.19739 -0.67858 0.62275 -0.50540 -0.59728 0.38937 -0.80750 -0.44309 0.63743 -0.16613 -0.75238 0.36311 -0.78476 -0.50229 0.36445 -0.79417 -0.48628 0.49937 -0.55376 -0.66631 0.30281 -0.80734 -0.50648 0.53003 -0.19982 -0.82410 0.54348 -0.22777 -0.80793 0.48302 -0.50109 -0.71805 0.41954 -0.17523 -0.89066 0.26108 -0.79358 -0.54961 0.27943 -0.81607 -0.50592 0.29119 -0.71113 -0.63993 0.35931 -0.55539 -0.74996 0.36493 -0.23060 -0.90203 0.33497 -0.49119 -0.80407 0.34295 -0.31685 -0.88430 0.30001 -0.09841 -0.94885 0.62652 0.77786 -0.04904 0.51423 0.85038 -0.11147 0.66372 0.74398 -0.07728 0.84714 0.52213 -0.09865 0.78461 0.60341 -0.14241 0.88724 0.44844 -0.10816 0.96334 0.24121 -0.11743 0.57557 0.80940 -0.11659 0.96304 0.16869 -0.21000 0.80089 0.53729 -0.26436 0.57696 0.79404 -0.19135 0.57814 0.79331 -0.19083 0.91781 0.22441 -0.32751 0.92253 0.21302 -0.32182 0.80874 0.51608 -0.28213 0.53139 0.80923 -0.25054 0.87672 0.17034 -0.44984 0.72768 0.54363 -0.41826 0.50348 0.80399 -0.31640 0.53307 0.78864 -0.30640 0.82842 0.23633 -0.50781 0.73327 0.51016 -0.44949 0.80915 0.17803 -0.55998 0.46106 0.80464 -0.37414 0.46060 0.78844 -0.40769 0.62585 0.54904 -0.55396 0.40986 0.80854 -0.42222 0.62310 0.50504 -0.59722 0.72654 0.19459 -0.65899 0.70254 0.23030 -0.67335 0.63740 0.16593 -0.75245 0.37795 0.78665 -0.48819 0.36371 0.79527 -0.48504 0.49963 0.55355 -0.66630 0.31162 0.80775 -0.50043 0.48326 0.50075 -0.71813 0.52523 0.23894 -0.81673 0.54666 0.20310 -0.81235 0.41953 0.17511 -0.89069 0.35011 0.55871 -0.75184 0.36262 0.23283 -0.90238 0.30210 0.11146 -0.94674 0.06650 0.99566 -0.06516 0.32275 0.94614 -0.02538 -0.92863 0.37061 0.01700 -0.98830 0.12644 0.08529 -0.97655 0.17783 0.12133 -0.72577 0.68200 0.09023 -0.80640 0.58798 0.06324 -0.63167 0.77117 0.07935 -0.30573 0.95134 0.03855 -0.42260 0.90611 0.01929 -0.17883 0.98361 0.02317 0.17655 0.98403 -0.02274 0.19541 0.97992 -0.03958 -0.93709 0.27982 0.20872 -0.68650 0.68817 0.23485 -0.91286 0.23363 0.33482 -0.92958 0.18642 0.31801 -0.28472 0.95347 0.09912 -0.69326 0.67908 0.24134 -0.29299 0.95030 0.10531 0.18065 0.98172 -0.05991 0.16914 0.98372 -0.06079 0.18218 0.97951 -0.08589 -0.85436 0.26155 0.44906 -0.62159 0.69118 0.36864 -0.84706 0.17357 0.50235 -0.25513 0.95449 0.15447 -0.63028 0.67611 0.38160 0.15533 0.98303 -0.09761 0.15505 0.98308 -0.09755 -0.26621 0.94925 0.16750 -0.78398 0.27707 0.55553 0.15646 0.97949 -0.12696 -0.71551 0.21489 0.66473 -0.72337 0.19685 0.66180 -0.53117 0.69405 0.48596 -0.21531 0.95540 0.20212 -0.53911 0.67323 0.50608 -0.22613 0.94825 0.22289 0.12238 0.98444 -0.12606 0.13364 0.98224 -0.13172 -0.61744 0.26850 0.73937 0.12196 0.97995 -0.15753 -0.52822 0.26640 0.80623 -0.57997 0.18211 0.79402 -0.41981 0.69669 0.58171 -0.41718 0.70927 0.56824 -0.15676 0.95722 0.24322 0.09262 0.98453 -0.14874 -0.05901 0.99778 -0.03079 0.16281 0.97811 0.12963 0.12607 0.95961 -0.25151 0.19599 -0.98043 -0.01837 -0.96452 -0.25067 0.08283 -0.97660 -0.17782 0.12096 -0.80479 -0.58513 0.09969 -0.63328 -0.77302 0.03754 -0.72616 -0.68147 0.09107 0.21458 -0.97528 -0.05270 -0.42311 -0.90452 0.05308 -0.18723 -0.98222 -0.01389 -0.36096 -0.93046 0.06285 0.17465 -0.98431 -0.02497 -0.93721 -0.27943 0.20868 -0.68737 -0.68736 0.23467 -0.92600 -0.16505 0.33953 -0.92133 -0.22851 0.31455 -0.28110 -0.95470 0.09764 -0.69403 -0.67839 0.24106 0.20738 -0.97456 -0.08504 -0.85461 -0.26080 0.44902 0.16380 -0.98310 -0.08173 -0.32234 -0.93559 0.14413 0.17112 -0.97995 -0.10206 -0.62240 -0.69040 0.36874 -0.84740 -0.17285 0.50204 -0.24032 -0.95975 0.14533 -0.63104 -0.67540 0.38160 -0.78419 -0.27666 0.55543 -0.26047 -0.94537 0.19603 0.14875 -0.98256 -0.11155 0.14917 -0.98242 -0.11226 0.14605 -0.97994 -0.13561 -0.53184 -0.69329 0.48630 -0.71932 -0.19083 0.66796 -0.72141 -0.21084 0.65963 -0.20511 -0.95964 0.19242 -0.53977 -0.67249 0.50636 -0.21885 -0.94617 0.23847 0.12617 -0.98156 -0.14358 0.12393 -0.98306 -0.13504 -0.61764 -0.26808 0.73936 0.11562 -0.98033 -0.15994 -0.41812 -0.69623 0.58347 -0.54545 -0.11098 0.83077 -0.56890 -0.25471 0.78197 -0.14761 -0.96138 0.23227 -0.41545 -0.70916 0.56965 -0.13028 -0.97712 0.16813 0.12770 -0.96854 -0.21358 0.11576 -0.98031 -0.15997 0.11951 -0.96126 -0.24840 0.86759 -0.00004 0.49729 0.86005 -0.00067 0.51021 0.69871 0.00033 0.71540 0.68315 -0.00054 0.73028 0.45680 0.00096 0.88957 0.44236 0.00026 0.89684 0.18885 -0.00058 0.98201 0.19784 -0.00019 0.98023 -0.07915 -0.00022 0.99686 -0.08595 -0.00053 0.99630 -0.36010 0.00041 0.93291 -0.37498 -0.00025 0.92703 0.86482 0.05323 0.49925 0.89424 0.04308 0.44551 0.91976 0.13689 0.36782 0.85166 0.07061 0.51932 0.85668 0.23985 0.45669 0.74796 0.10340 0.65564 0.79318 0.34142 0.50427 0.67621 0.14507 0.72228 0.90664 0.39515 0.14784 0.54784 0.16722 0.81970 0.61468 0.48582 0.62140 0.76377 0.62501 0.16126 0.69118 0.44984 0.56560 0.43262 0.21045 0.87667 0.42687 0.61530 0.66271 0.34421 0.21590 0.91373 0.19110 0.25623 0.94754 0.74895 0.64085 0.16846 0.46141 0.60552 0.64842 0.55087 0.81731 0.16897 0.14403 0.25363 0.95652 0.23745 0.69961 0.67392 -0.06179 0.28381 0.95689 0.51464 0.83834 0.17982 0.30991 0.93560 0.16913 0.21181 0.70288 0.67904 0.02029 0.75864 0.65120 -0.08136 0.28235 0.95585 -0.10996 0.28736 0.95149 0.35288 0.92239 0.15705 -0.11065 0.75626 0.64485 -0.34752 0.28060 0.89470 0.18518 0.96802 0.16923 -0.35957 0.28417 0.88879 -0.10909 0.75662 0.64469 0.04733 0.98757 0.14990 0.91677 0.37563 -0.13579 0.76266 0.61462 -0.20148 0.77416 0.59853 -0.20600 0.53176 0.81577 -0.22750 0.57893 0.77639 -0.24914 0.36133 0.90335 -0.23110 0.44603 0.85471 -0.26558 0.19295 0.94965 -0.24683 0.25813 0.92732 -0.27101 0.95845 0.07640 -0.27484 0.96167 0.06620 -0.26611 0.93288 0.02087 -0.35958 0.90762 0.09845 -0.40808 0.87723 0.15437 -0.45457 0.91474 0.23838 -0.32622 0.88053 0.01263 -0.47382 0.88988 0.28746 -0.35422 0.87002 0.03612 -0.49170 0.84090 -0.00101 -0.54120 0.75048 0.51149 -0.41852 0.75650 0.35756 -0.54760 0.73658 0.20873 -0.64334 0.74511 0.36872 -0.55575 0.78441 0.45895 -0.41721 0.72747 0.22157 -0.64938 0.69223 0.12864 -0.71011 0.66133 0.02956 -0.74951 0.70152 0.02967 -0.71203 0.71199 0.10709 -0.69398 0.58847 0.34393 -0.73172 0.59922 0.52419 -0.60512 0.59434 0.52732 -0.60720 0.63549 0.62397 -0.45477 0.55202 0.67988 -0.48274 0.50514 0.23415 -0.83067 0.55892 0.37367 -0.74026 0.50506 0.09286 -0.85807 0.53614 0.07615 -0.84069 0.56324 0.18628 -0.80502 0.42201 0.76248 -0.49044 0.45764 0.44194 -0.77153 0.42960 0.64938 -0.62750 0.49092 0.71323 -0.50030 0.45921 0.63909 -0.61700 0.19847 0.33790 -0.92002 0.31436 0.55529 -0.76996 0.52807 0.68920 -0.49613 0.49723 0.61593 -0.61106 0.33651 0.10481 -0.93583 0.05364 0.19518 -0.97930 0.22468 0.82174 -0.52369 0.66150 -0.00244 -0.74994 0.66936 -0.00439 -0.74293 0.50732 -0.00029 -0.86175 0.53404 -0.00848 -0.84541 0.33887 0.00575 -0.94082 0.38850 -0.00667 -0.92143 0.98063 0.06166 -0.18593 0.97165 -0.08208 -0.22171 0.93339 -0.02097 -0.35826 0.90822 -0.10105 -0.40612 0.86034 -0.19098 -0.47259 0.90628 -0.30599 -0.29159 0.88367 -0.00565 -0.46808 0.51136 -0.73088 -0.45202 0.85364 -0.06651 -0.51659 0.81975 -0.01450 -0.57254 0.77556 -0.16320 -0.60981 0.82147 -0.26460 -0.50515 0.75267 -0.51166 -0.41435 0.79853 -0.43998 -0.41081 0.75471 -0.34177 -0.56001 0.78536 -0.05049 -0.61697 0.78371 -0.00159 -0.62112 0.69609 -0.11307 -0.70899 0.73667 -0.21935 -0.63969 0.66919 -0.04023 -0.74200 0.59143 -0.66370 -0.45795 0.61722 -0.49367 -0.61265 0.65964 -0.59015 -0.46540 0.63442 -0.04473 -0.77169 0.65752 -0.14718 -0.73892 0.62728 -0.48184 -0.61185 0.57209 -0.36087 -0.73653 0.53978 -0.20746 -0.81584 0.59136 -0.33954 -0.73144 0.53179 -0.08056 -0.84303 0.47428 -0.59486 -0.64900 0.52137 -0.70758 -0.47697 0.33173 -0.51922 -0.78763 0.40674 -0.65063 -0.64128 0.35598 -0.78086 -0.51336 0.43567 -0.43150 -0.78994 0.34217 -0.32854 -0.88033 0.37782 -0.29848 -0.87645 0.33477 -0.10404 -0.93654 0.38808 -0.08436 -0.91776 0.92358 -0.35766 -0.13810 0.71913 -0.66669 -0.19588 0.77454 -0.59541 -0.21350 0.60812 -0.75847 -0.23432 0.61697 -0.75020 -0.23781 0.36141 -0.89887 -0.24782 0.38620 -0.88561 -0.25795 0.20676 -0.94041 -0.26995 0.89427 -0.03537 0.44612 0.95299 -0.04742 0.29926 0.92124 -0.15104 0.35848 0.86617 -0.05843 0.49633 0.82569 -0.31028 0.47112 0.78480 -0.08791 0.61348 0.69262 -0.13759 0.70806 0.72992 -0.39709 0.55635 0.69118 -0.13805 0.70938 0.66984 -0.44980 0.59075 0.60896 -0.14973 0.77894 0.46632 -0.19921 0.86189 0.92280 -0.37521 0.08751 0.61946 -0.77197 0.14259 0.79731 -0.58492 0.14886 0.72790 -0.41384 0.54672 0.44603 -0.20223 0.87187 0.52025 -0.56828 0.63749 0.42858 -0.20872 0.87906 0.60685 -0.76770 0.20587 0.52011 -0.56833 0.63756 0.70465 -0.69221 0.15593 0.18355 -0.24618 0.95169 0.20724 -0.24957 0.94592 0.29503 -0.66866 0.68253 0.39902 -0.65383 0.64288 0.48397 -0.85199 0.19974 0.60082 -0.78524 0.14972 -0.07555 -0.28563 0.95536 0.25210 -0.94931 0.18777 0.15490 -0.71443 0.68235 -0.00465 -0.76317 0.64619 -0.10740 -0.27806 0.95454 0.35331 -0.92324 0.15096 -0.13451 -0.75583 0.64080 0.03589 -0.98353 0.17717 0.20848 -0.97041 0.12180 -0.34502 -0.29404 0.89135 -0.16838 -0.75905 0.62888 -0.42627 -0.26736 0.86418 0.01280 -0.99985 -0.01152 0.00967 -0.99986 -0.01389 0.00680 -0.99987 -0.01467 0.00679 -0.99986 0.01553 0.01086 -0.99983 -0.01494 0.00689 -0.99986 -0.01547 0.00437 -0.99985 -0.01649 0.00739 -0.99983 0.01661 0.00395 -0.99987 0.01579 0.99518 0.00000 -0.09802 0.99452 0.00200 -0.10453 0.95694 -0.00187 -0.29028 0.95105 0.00374 -0.30901 0.88192 -0.00348 -0.47139 0.86601 0.00521 -0.49999 0.77300 -0.00481 -0.63439 0.74313 0.00642 -0.66912 0.63438 -0.00589 -0.77300 0.58777 0.00735 -0.80900 0.47139 -0.00669 -0.88190 0.40672 0.00803 -0.91352 0.29027 -0.00722 -0.95692 0.29027 -0.00722 0.95692 0.40672 0.00803 0.91352 0.47139 -0.00669 0.88190 0.58777 0.00735 0.80900 0.63438 -0.00588 0.77300 0.74313 0.00642 0.66912 0.77300 -0.00481 0.63439 0.86601 0.00521 0.49999 0.88192 -0.00348 0.47139 0.95105 0.00374 0.30902 0.95694 -0.00187 0.29028 0.99518 0.00214 0.09802 0.99452 -0.00000 0.10453 0.00413 0.99985 0.01652 0.99518 -0.00000 0.09802 0.99452 -0.00200 0.10453 0.95694 0.00187 0.29028 0.95105 -0.00374 0.30902 0.88192 0.00348 0.47139 0.86601 -0.00521 0.49999 0.77300 0.00481 0.63439 0.74313 -0.00642 0.66912 0.63438 0.00588 0.77300 0.58777 -0.00735 0.80900 0.47139 0.00669 0.88190 0.40672 -0.00803 0.91352 0.29027 0.00722 0.95692 -0.99369 0.00624 -0.11196 -0.99271 0.00000 -0.12054 -0.94387 -0.00535 -0.33028 -0.93496 0.01071 -0.35459 -0.84668 -0.00981 -0.53201 -0.82290 0.01472 -0.56800 -0.70704 -0.01339 -0.70704 -0.66302 0.01785 -0.74839 -0.53196 -0.01607 -0.84661 -0.46462 0.02008 -0.88528 -0.46462 0.02008 0.88528 -0.53196 -0.01607 0.84662 -0.66302 0.01785 0.74839 -0.70705 -0.01339 0.70704 -0.82290 0.01472 0.56800 -0.84668 -0.00982 0.53201 -0.93496 0.01071 0.35458 -0.94387 -0.00535 0.33027 -0.99269 0.00580 0.12054 -0.99371 -0.00000 0.11197 0.29027 0.00722 -0.95692 0.40672 -0.00803 -0.91352 0.47139 0.00669 -0.88190 0.58777 -0.00735 -0.80900 0.63438 0.00589 -0.77300 0.74313 -0.00642 -0.66912 0.77300 0.00481 -0.63439 0.86601 -0.00521 -0.49999 0.88192 0.00348 -0.47139 0.95105 -0.00374 -0.30901 0.95694 0.00187 -0.29028 0.99518 -0.00214 -0.09802 0.99452 0.00000 -0.10453 0.97704 0.00006 -0.21303 0.97771 -0.00700 -0.20983 0.99727 -0.01551 -0.07222 0.99687 -0.00117 -0.07902 -0.97608 -0.00001 0.21740 -0.97610 0.00001 0.21734 -0.99630 -0.00001 0.08600 -0.99633 0.00008 0.08562 0.26455 0.80715 -0.52776 0.34054 0.54168 -0.76851 0.35220 0.27446 -0.89478 0.07352 0.40715 -0.91040 0.00437 0.99985 -0.01649 0.00689 0.99986 -0.01547 0.00715 0.99986 -0.01543 0.01002 0.99985 -0.01379 0.00967 0.99986 -0.01389 0.01280 0.99985 -0.01152 0.01186 0.99986 -0.01192 0.01398 0.99985 -0.00984 0.01458 0.99986 -0.00841 0.01547 0.99985 -0.00726 0.01603 0.99986 -0.00521 0.01647 0.99985 -0.00446 0.01684 0.99986 -0.00177 0.01572 0.99988 0.00165 0.01506 0.99986 0.00672 0.68740 0.72228 -0.07613 0.01634 0.99987 0.00011 0.01633 0.99986 -0.00300 0.58113 0.80877 -0.09042 0.53871 0.84142 0.04248 0.27493 0.79940 -0.53420 0.28266 0.74141 -0.60862 0.01616 0.99986 0.00525 0.01502 0.99986 0.00802 0.01462 0.99986 0.00844 0.00680 0.99986 0.01556 0.00689 0.99986 0.01548 0.00933 0.99985 0.01427 0.00991 0.99986 0.01363 0.01160 0.99985 0.01254 0.01251 0.99986 0.01126 0.01352 0.99985 0.01043 0.01186 -0.99986 -0.01192 0.01398 -0.99985 -0.00984 0.01457 -0.99986 -0.00842 0.01547 -0.99985 -0.00726 0.01603 -0.99986 -0.00521 0.01647 -0.99985 -0.00446 0.01684 -0.99986 -0.00177 0.01520 -0.99987 -0.00572 0.01573 -0.99987 0.00165 0.01740 -0.99983 0.00683 0.01709 -0.99985 0.00300 0.01750 -0.99983 0.00568 0.01480 -0.99985 0.00855 0.01489 -0.99986 0.00794 0.01287 -0.99985 0.01159 0.01325 -0.99986 0.01022 0.01037 -0.99984 0.01427 0.01124 -0.99986 0.01216 0.00933 -0.99985 0.01427 0.91325 -0.39561 -0.09728 0.84105 -0.52604 -0.12613 0.78926 -0.60701 -0.09279 0.66360 -0.74401 -0.07801 0.59337 -0.79930 -0.09497 0.51613 -0.85524 -0.04663 0.99105 0.11258 -0.07178 0.95071 0.27410 -0.14499 0.01716 0.80299 -0.59575 0.03822 0.78970 -0.61230 0.07553 0.77517 -0.62722 0.03867 0.78385 -0.61975 0.94370 0.32976 0.02619 0.00000 0.19454 -0.98089 0.00000 0.35343 -0.93546 -1.00000 -0.00059 -0.00003 -1.00000 -0.00001 -0.00006 -1.00000 0.00182 0.00003 -1.00000 -0.00001 0.00011 -1.00000 -0.00116 0.00005 -0.36527 0.03145 0.93037 -0.17217 -0.03776 0.98434 0.00495 0.02519 0.99967 0.08047 -0.00910 0.99672 0.26345 0.00853 0.96464 0.32287 -0.01482 0.94633 0.48232 0.01089 0.87593 0.53692 -0.01160 0.84355 0.68298 0.00020 0.73043 0.70697 0.01756 0.70702 0.86223 0.02244 0.50602 0.84699 0.00157 0.53161 0.95795 -0.01567 0.28651 0.97465 -0.06454 0.21420 0.90187 0.03293 0.43075 0.86639 -0.03503 0.49814 0.76322 0.02282 0.64573 0.69250 -0.01974 0.72115 0.55842 0.02039 0.82931 0.48494 -0.01025 0.87449 0.26660 -0.00817 0.96377 0.32472 0.01522 0.94569 0.08066 0.00867 0.99670 0.00713 -0.02531 0.99965 -0.17237 0.03793 0.98430 -0.36502 -0.03199 0.93045 0.36527 -0.03146 0.93037 0.17216 0.03776 0.98435 -0.00495 -0.02519 0.99967 -0.08047 0.00910 0.99672 -0.26345 -0.00853 0.96464 -0.32289 0.01483 0.94632 -0.48232 -0.01087 0.87593 -0.53689 0.01160 0.84357 -0.68299 -0.00020 0.73043 -0.70698 -0.01757 0.70702 -0.86223 -0.02245 0.50601 -0.84699 -0.00157 0.53161 -0.95795 0.01566 0.28649 -0.97470 0.06523 0.21378 -0.90210 -0.03361 0.43023 -0.86636 0.03490 0.49819 -0.76326 -0.02290 0.64568 -0.69248 0.01969 0.72116 -0.55840 -0.02044 0.82932 -0.48492 0.01021 0.87450 -0.26660 0.00817 0.96377 -0.32477 -0.01524 0.94567 -0.08066 -0.00867 0.99670 -0.00713 0.02531 0.99965 0.17236 -0.03793 0.98430 0.36502 0.03199 0.93045 -0.03482 -0.36793 -0.92920 -0.20097 -0.42995 -0.88020 0.01380 -0.46884 -0.88318 -0.00681 -0.53767 -0.84313 -0.08527 -0.60194 -0.79397 0.79985 -0.39356 -0.45316 0.27119 -0.64396 -0.71538 0.07550 -0.68176 -0.72767 0.00718 -0.70281 -0.71135 0.00314 -0.64168 -0.76696 -0.00032 -0.68772 -0.72598 -0.04496 -0.74263 -0.66820 -0.00389 -0.72847 -0.68507 0.04387 -0.78368 -0.61962 0.06918 -0.77730 -0.62532 0.03512 -0.79133 -0.61038 0.01595 -0.80410 -0.59429 0.00894 -0.81231 -0.58316 -0.00000 -0.84144 -0.54036 -0.02572 -0.78358 -0.62076 -0.00610 -0.70315 -0.71101 0.00055 -0.75203 -0.65913 0.00002 -0.75715 -0.65324 -0.00661 -0.81282 -0.58248 -0.00927 -0.81847 -0.57447 -0.00547 -0.80640 -0.59134 -0.00063 -0.77545 -0.63141 0.00001 -0.83170 -0.55522 0.00844 -0.88587 -0.46385 0.04678 -0.86190 -0.50491 0.00027 -0.89631 -0.44344 -0.00428 -0.90848 -0.41790 0.00415 -0.95659 -0.29141 -0.00446 -0.97121 -0.23816 0.00433 -0.99405 -0.10883 -0.00463 -0.99875 -0.04979 0.00449 -0.99698 0.07753 -0.00478 -0.99009 0.14038 0.00463 -0.96528 0.26119 -0.00492 -0.94554 0.32546 0.00475 -0.90004 0.43578 -0.00503 -0.86673 0.49875 0.00486 -0.80354 0.59523 -0.00512 -0.75651 0.65397 0.00494 -0.67913 0.73400 -0.00520 -0.61887 0.78548 0.00501 -0.53113 0.84728 -0.00525 -0.45880 0.88852 0.00505 -0.36468 0.93112 -0.00529 -0.28210 0.95937 0.00508 -0.18556 0.98262 -0.00531 -0.09519 0.99545 0.00509 0.00000 0.99999 -0.00531 0.09519 0.99545 0.00508 0.18556 0.98262 -0.00529 0.28210 0.95937 0.00505 0.36468 0.93112 -0.00525 0.45880 0.88852 0.00501 0.53113 0.84728 -0.00520 0.61887 0.78548 0.00494 0.67913 0.73400 -0.00512 0.75651 0.65397 0.00486 0.80354 0.59523 -0.00503 0.86673 0.49875 0.00475 0.90004 0.43578 -0.00492 0.94554 0.32546 0.00463 0.96528 0.26119 -0.00478 0.99009 0.14038 0.00449 0.99698 0.07753 -0.00463 0.99875 -0.04979 0.00433 0.99405 -0.10883 -0.00446 0.97121 -0.23816 0.00415 0.95659 -0.29141 -0.00428 0.90848 -0.41790 0.00911 0.88587 -0.46385 0.00223 0.89084 -0.45432 0.00699 0.87717 -0.48014 -0.00210 0.81283 -0.58249 -0.01778 0.78442 -0.61998 -0.00873 0.80742 -0.58992 -0.00138 0.83795 -0.54575 0.00178 0.84372 -0.53678 0.00642 0.81498 -0.57945 0.00379 0.82076 -0.57125 0.00056 0.75227 -0.65886 0.00002 0.75727 -0.65311 -0.01789 0.68761 -0.72586 -0.00017 0.71789 -0.69616 -0.00596 0.70312 -0.71104 -0.02600 0.78362 -0.62069 -0.00222 0.72810 -0.68547 0.81263 0.38213 -0.44001 0.29066 0.63961 -0.71163 0.09412 0.67880 -0.72826 0.00314 0.64164 -0.76700 -0.03556 0.53734 -0.84262 -0.00425 0.56554 -0.82471 0.01379 0.46886 -0.88317 -0.09912 0.36634 -0.92519 -0.02762 0.38325 -0.92323 -0.02688 -0.18627 -0.98213 -0.14677 -0.36417 -0.91970 0.04336 -0.34955 -0.93591 -0.01380 -0.46884 -0.88318 0.03556 -0.53734 -0.84262 0.00424 -0.56554 -0.82471 -0.80318 -0.39063 -0.44979 -0.27622 -0.64286 -0.71445 -0.07857 -0.68121 -0.72786 -0.00840 -0.70209 -0.71204 -0.00314 -0.64168 -0.76696 0.01789 -0.68761 -0.72586 0.00018 -0.71792 -0.69613 0.00286 -0.72476 -0.68899 -0.03089 -0.78406 -0.61992 -0.00293 -0.82941 -0.55863 -0.34197 -0.87867 -0.33316 -0.11643 -0.81859 -0.56245 0.02600 -0.78362 -0.62069 0.00596 -0.70312 -0.71104 -0.00056 -0.75227 -0.65885 -0.00002 -0.75727 -0.65310 0.00210 -0.81283 -0.58249 0.01778 -0.78442 -0.61998 0.00873 -0.80742 -0.58992 0.00138 -0.83795 -0.54575 -0.00911 -0.88587 -0.46385 -0.00223 -0.89084 -0.45432 -0.00683 -0.87649 -0.48137 -0.00173 -0.84413 -0.53614 0.00428 -0.90848 -0.41790 -0.00415 -0.95659 -0.29141 0.00446 -0.97121 -0.23816 -0.00433 -0.99405 -0.10883 0.00463 -0.99875 -0.04979 -0.00449 -0.99698 0.07753 0.00478 -0.99009 0.14038 -0.00463 -0.96528 0.26119 0.00492 -0.94554 0.32546 -0.00475 -0.90004 0.43578 0.00503 -0.86673 0.49875 -0.00486 -0.80354 0.59523 0.00512 -0.75651 0.65396 -0.00494 -0.67913 0.73400 0.00520 -0.61887 0.78548 -0.00501 -0.53113 0.84728 0.00525 -0.45880 0.88852 -0.00506 -0.36468 0.93112 0.00529 -0.28210 0.95937 -0.00508 -0.18556 0.98262 0.00531 -0.09519 0.99545 -0.00509 0.00000 0.99999 0.00531 0.09519 0.99545 -0.00508 0.18556 0.98262 0.00529 0.28210 0.95937 -0.00506 0.36468 0.93112 0.00525 0.45880 0.88852 -0.00501 0.53113 0.84728 0.00520 0.61887 0.78548 -0.00494 0.67913 0.73400 0.00512 0.75651 0.65397 -0.00486 0.80354 0.59523 0.00503 0.86673 0.49875 -0.00475 0.90004 0.43578 0.00492 0.94554 0.32546 -0.00463 0.96528 0.26119 0.00478 0.99009 0.14038 -0.00449 0.99698 0.07753 0.00463 0.99875 -0.04979 -0.00433 0.99405 -0.10883 0.00446 0.97121 -0.23816 -0.00415 0.95659 -0.29141 0.00428 0.90848 -0.41790 -0.00843 0.88587 -0.46385 -0.04636 0.86225 -0.50436 -0.00027 0.89631 -0.44343 0.00662 0.81282 -0.58248 0.00926 0.81843 -0.57453 0.00547 0.80640 -0.59134 0.00063 0.77545 -0.63141 -0.00005 0.83149 -0.55554 -0.03999 0.78381 -0.61972 -0.07421 0.77562 -0.62682 -0.03783 0.78992 -0.61204 -0.01720 0.80299 -0.59575 -0.00952 0.81155 -0.58420 0.00002 0.84114 -0.54082 -0.00055 0.75203 -0.65913 -0.00002 0.75714 -0.65325 0.00032 0.68772 -0.72598 0.04491 0.74257 -0.66826 0.00610 0.70316 -0.71101 0.02572 0.78358 -0.62076 0.00465 0.72532 -0.68840 -0.80926 0.38520 -0.44353 -0.27998 0.64195 -0.71380 -0.00936 0.70328 -0.71086 -0.00314 0.64164 -0.76700 0.00682 0.53767 -0.84313 0.08527 0.60194 -0.79398 -0.01379 0.46886 -0.88317 0.03480 0.36793 -0.92920 0.34049 -0.94025 0.00054 0.19600 -0.98039 -0.02028 0.18490 -0.98260 -0.01730 -0.02176 -0.99976 0.00210 0.06177 -0.99809 -0.00134 -0.18694 -0.98236 -0.00396 -0.15842 -0.98737 -0.00106 -0.01721 -0.99985 0.00212 -0.30356 -0.95281 0.00157 -0.42286 -0.90620 -0.00092 -0.45111 -0.89244 -0.00618 -0.63482 -0.77264 -0.00547 -0.60572 -0.79568 -0.00139 -0.71193 -0.70225 0.00167 -0.80791 -0.58931 -0.00061 -0.82973 -0.55809 -0.00925 -0.90215 -0.43142 -0.00005 -0.96736 -0.25093 -0.03518 -0.94470 -0.32765 -0.01338 -0.97672 -0.21321 -0.02388 -0.99790 -0.06474 0.00122 -0.31846 -0.94794 -0.00016 -0.33754 -0.94130 -0.00448 -0.23083 -0.97299 0.00271 -0.06843 -0.99765 -0.00373 -0.07245 -0.99736 -0.00434 -0.00682 -0.99998 0.00064 0.09367 -0.99560 0.00174 0.18217 -0.98327 -0.00026 0.13090 -0.99137 -0.00663 0.29065 -0.95683 0.00076 0.42336 -0.90596 -0.00269 0.39087 -0.92042 -0.00720 0.52456 -0.85137 0.00084 0.63479 -0.77267 -0.00390 0.61239 -0.79052 -0.00774 0.69745 -0.71663 0.00002 0.80804 -0.58912 -0.00166 0.76504 -0.64382 -0.01435 0.84115 -0.54080 -0.00111 0.90029 -0.43528 -0.00032 0.92873 -0.37065 -0.00849 0.94712 -0.32087 -0.00117 0.98061 -0.19596 0.00033 0.99205 -0.12537 -0.01069 0.99778 -0.06666 -0.00057 0.32250 0.94657 -0.00007 0.33781 0.94121 -0.00354 0.23142 0.97285 0.00364 0.06278 0.99802 -0.00301 0.07235 0.99737 -0.00444 0.00652 0.99998 0.00045 -0.09498 0.99548 0.00148 -0.18045 0.98358 -0.00048 -0.13177 0.99126 -0.00651 -0.29289 0.95615 0.00079 -0.42264 0.90629 -0.00282 -0.39459 0.91883 -0.00665 -0.53028 0.84782 0.00102 -0.63450 0.77291 -0.00421 -0.62037 0.78428 -0.00655 -0.70591 0.70830 0.00052 -0.80765 0.58966 -0.00253 -0.77455 0.63240 -0.01191 -0.84850 0.52920 -0.00012 -0.92892 0.37028 -0.00108 -0.90617 0.42268 -0.01397 -0.97846 0.20642 0.00241 -0.99204 0.12550 -0.01058 -0.99789 0.06487 -0.00040 -0.33892 0.94081 -0.00463 -0.33691 0.94152 -0.00493 -0.19894 0.98000 0.00410 -0.06835 0.99766 0.00152 0.06944 0.99737 -0.02058 -0.05851 0.99828 -0.00412 0.18077 0.98351 -0.00444 0.15865 0.98733 -0.00218 0.02216 0.99975 0.00095 0.30613 0.95199 0.00136 0.42117 0.90698 -0.00277 0.44349 0.89626 -0.00615 0.54157 0.84065 0.00054 0.63478 0.77268 -0.00532 0.62230 0.78277 -0.00342 0.70719 0.70703 0.00066 0.80697 0.59056 -0.00668 0.78238 0.62280 -0.00177 0.85973 0.51074 0.00191 0.92938 0.36912 -0.00027 0.94263 0.33365 -0.01100 0.98192 0.18931 -0.00020 0.99213 0.12523 -0.00049 0.99682 0.07758 -0.01825 -0.50725 0.86179 -0.00470 -0.45677 0.88900 -0.03232 -0.51241 0.85867 -0.01099 -0.56287 0.82655 -0.00059 -0.64245 0.76633 0.00115 -0.66589 0.74596 -0.01147 -0.74016 0.67239 0.00690 -0.79296 0.60905 -0.01677 -0.81693 0.57673 0.00246 -0.89256 0.45091 -0.00387 -0.87127 0.48848 -0.04762 -0.94060 0.33878 0.02242 -0.95846 0.27675 -0.06901 0.45917 0.88835 -0.00006 0.51555 0.85686 -0.00157 0.57094 0.82044 -0.03009 0.51219 0.85882 -0.00908 0.64245 0.76633 0.00115 0.66591 0.74594 -0.01143 0.74015 0.67241 0.00687 0.79297 0.60904 -0.01671 0.81693 0.57673 0.00245 0.89226 0.45054 -0.02969 0.88249 0.47033 -0.00291 0.51627 -0.85643 0.00036 0.45680 -0.88900 -0.03190 0.51240 -0.85868 -0.01086 0.56287 -0.82655 -0.00059 0.64240 -0.76637 0.00114 0.66591 -0.74595 -0.01131 0.74001 -0.67256 0.00665 0.79275 -0.60932 -0.01663 0.81691 -0.57676 0.00241 0.88251 -0.47028 -0.00285 -0.45917 -0.88835 -0.00014 -0.51541 -0.85694 -0.00158 -0.57098 -0.82041 -0.03023 -0.51220 -0.85882 -0.00918 -0.64241 -0.76636 0.00115 -0.66590 -0.74596 -0.01148 -0.74008 -0.67248 0.00681 -0.79279 -0.60926 -0.01689 -0.81693 -0.57673 0.00247 -0.89211 -0.45086 -0.02945 -0.88249 -0.47032 -0.00293 -0.94061 -0.33876 0.02242 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00001 -0.00047 1.00000 0.00000 -0.00056 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00039 -1.00000 0.00025 0.00122 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00004 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00047 -0.00002 1.00000 0.00000 -0.00004 1.00000 0.00042 -0.00002 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 -0.37891 -0.18191 -0.90738 0.06951 -0.25037 -0.96565 0.06953 0.25037 -0.96565 -0.44514 0.16704 -0.87974 -0.97863 0.19743 0.05752 -0.98789 0.08957 -0.12668 -0.95846 -0.27675 -0.06899 -0.97863 -0.19744 0.05752 -0.98833 -0.09335 -0.12041 + + + + + + + + + + + + + + +

253 0 61 0 63 0 255 1 59 1 61 1 180 2 173 2 175 2 179 3 175 3 172 3 180 4 175 4 179 4 178 5 172 5 177 5 178 6 177 6 176 6 245 7 56 7 243 7 243 8 56 8 241 8 241 9 56 9 53 9 241 10 53 10 239 10 239 11 53 11 237 11 237 12 53 12 52 12 237 13 52 13 235 13 235 14 52 14 49 14 235 15 49 15 233 15 233 16 49 16 48 16 233 17 48 17 47 17 233 18 47 18 225 18 225 19 47 19 46 19 225 20 46 20 103 20 103 21 46 21 50 21 103 22 50 22 102 22 267 23 102 23 50 23 267 24 50 24 51 24 271 25 267 25 51 25 271 26 51 26 54 26 271 27 54 27 263 27 263 28 54 28 261 28 261 29 54 29 55 29 261 30 55 30 259 30 262 31 260 31 37 31 266 32 262 32 37 32 266 33 37 33 40 33 266 34 40 34 264 34 264 35 40 35 42 35 264 36 42 36 130 36 222 37 130 37 42 37 222 38 42 38 43 38 223 39 222 39 43 39 223 40 43 40 45 40 228 41 223 41 45 41 228 42 45 42 44 42 234 43 228 43 44 43 234 44 44 44 41 44 236 45 234 45 41 45 236 46 41 46 39 46 238 47 236 47 39 47 238 48 39 48 38 48 240 49 238 49 38 49 242 50 240 50 38 50 234 51 0 51 230 51 230 52 0 52 231 52 0 53 235 53 231 53 0 54 234 54 236 54 235 55 0 55 236 55 235 56 233 56 231 56 221 57 219 57 220 57 220 58 219 58 218 58 382 59 381 59 380 59 381 60 365 60 198 60 365 61 196 61 198 61 382 62 365 62 381 62 382 63 366 63 365 63 208 64 143 64 140 64 208 65 140 65 204 65 383 66 365 66 366 66 367 67 383 67 366 67 384 68 383 68 367 68 351 69 350 69 349 69 352 70 350 70 351 70 353 71 352 71 351 71 354 72 352 72 353 72 355 73 354 73 353 73 27 74 29 74 348 74 347 75 348 75 29 75 29 76 31 76 347 76 346 77 347 77 31 77 31 78 33 78 346 78 345 79 346 79 33 79 33 80 35 80 345 80 343 81 345 81 35 81 35 82 38 82 343 82 341 83 343 83 38 83 38 84 39 84 341 84 339 85 341 85 39 85 39 86 41 86 339 86 333 87 339 87 41 87 41 88 44 88 333 88 330 89 333 89 44 89 44 90 45 90 330 90 327 91 330 91 45 91 334 92 336 92 4 92 2 93 4 93 336 93 336 94 337 94 2 94 1 95 2 95 337 95 337 96 338 96 1 96 3 97 1 97 338 97 338 98 335 98 3 98 5 99 3 99 335 99 335 100 332 100 5 100 7 101 5 101 332 101 332 102 331 102 7 102 9 103 7 103 331 103 331 104 329 104 9 104 11 105 9 105 329 105 329 106 328 106 11 106 13 107 11 107 326 107 11 108 328 108 326 108 326 109 324 109 13 109 15 110 13 110 324 110 324 111 323 111 15 111 17 112 15 112 323 112 323 113 321 113 17 113 19 114 17 114 321 114 321 115 320 115 19 115 21 116 19 116 320 116 320 117 318 117 21 117 23 118 21 118 318 118 318 119 315 119 23 119 24 120 23 120 315 120 315 121 312 121 24 121 26 122 24 122 312 122 312 123 314 123 26 123 25 124 26 124 314 124 314 125 317 125 25 125 1 126 3 126 2 126 4 127 2 127 3 127 3 128 5 128 4 128 6 129 4 129 5 129 5 130 7 130 6 130 8 131 6 131 7 131 7 132 9 132 8 132 10 133 8 133 9 133 9 134 11 134 10 134 12 135 10 135 11 135 11 136 13 136 12 136 14 137 12 137 13 137 13 138 15 138 14 138 16 139 14 139 15 139 15 140 17 140 16 140 18 141 16 141 17 141 17 142 19 142 18 142 20 143 18 143 19 143 19 144 21 144 20 144 22 145 20 145 21 145 21 146 23 146 22 146 25 147 22 147 23 147 23 148 24 148 25 148 26 149 25 149 24 149 45 150 43 150 327 150 43 151 325 151 327 151 322 152 325 152 43 152 43 153 42 153 322 153 319 154 322 154 42 154 42 155 40 155 319 155 313 156 319 156 40 156 40 157 37 157 313 157 310 158 313 158 37 158 37 159 36 159 310 159 308 160 310 160 36 160 36 161 34 161 308 161 306 162 308 162 34 162 34 163 32 163 306 163 304 164 306 164 32 164 32 165 30 165 304 165 305 166 304 166 30 166 30 167 28 167 305 167 29 168 27 168 250 168 28 169 30 169 252 169 250 170 248 170 29 170 254 171 252 171 30 171 31 172 29 172 248 172 30 173 32 173 254 173 248 174 246 174 31 174 246 175 33 175 31 175 256 176 254 176 32 176 258 177 256 177 34 177 256 178 32 178 34 178 246 179 244 179 33 179 35 180 33 180 244 180 34 181 36 181 258 181 260 182 258 182 36 182 244 183 242 183 35 183 242 184 38 184 35 184 36 185 37 185 260 185 63 186 61 186 303 186 302 187 303 187 61 187 61 188 59 188 302 188 301 189 302 189 59 189 59 190 57 190 301 190 300 191 301 191 57 191 57 192 55 192 300 192 298 193 300 193 55 193 55 194 54 194 298 194 296 195 298 195 54 195 54 196 51 196 296 196 294 197 296 197 51 197 51 198 50 198 294 198 292 199 294 199 50 199 50 200 46 200 292 200 290 201 292 201 46 201 46 202 47 202 290 202 288 203 290 203 47 203 47 204 48 204 288 204 48 205 286 205 288 205 284 206 286 206 48 206 48 207 49 207 284 207 282 208 284 208 49 208 49 209 52 209 282 209 280 210 282 210 52 210 52 211 53 211 280 211 278 212 280 212 53 212 53 213 56 213 278 213 276 214 278 214 56 214 56 215 58 215 276 215 274 216 276 216 58 216 58 217 60 217 274 217 272 218 274 218 60 218 60 219 62 219 272 219 273 220 272 220 62 220 62 221 64 221 273 221 245 222 247 222 56 222 257 223 259 223 57 223 259 224 55 224 57 224 58 225 56 225 247 225 57 226 59 226 257 226 247 227 249 227 58 227 249 228 60 228 58 228 255 229 257 229 59 229 62 230 60 230 249 230 253 231 255 231 61 231 249 232 251 232 62 232 64 233 62 233 251 233 189 234 110 234 193 234 110 235 65 235 193 235 67 236 65 236 110 236 110 237 115 237 67 237 66 238 67 238 115 238 115 239 118 239 66 239 72 240 66 240 118 240 118 241 123 241 72 241 74 242 72 242 123 242 123 243 125 243 74 243 224 244 74 244 125 244 125 245 222 245 224 245 223 246 224 246 222 246 193 247 65 247 192 247 69 248 195 248 192 248 195 249 69 249 377 249 65 250 67 250 192 250 75 251 377 251 69 251 192 252 68 252 69 252 68 253 192 253 67 253 67 254 66 254 68 254 70 255 68 255 66 255 68 256 70 256 69 256 69 257 71 257 75 257 71 258 69 258 70 258 66 259 72 259 70 259 76 260 75 260 71 260 73 261 70 261 72 261 70 262 73 262 71 262 71 263 229 263 76 263 229 264 71 264 73 264 72 265 74 265 73 265 230 266 76 266 229 266 73 267 227 267 229 267 227 268 73 268 74 268 74 269 224 269 227 269 377 270 75 270 379 270 79 271 379 271 75 271 75 272 76 272 79 272 80 273 79 273 76 273 76 274 230 274 80 274 231 275 80 275 230 275 77 276 221 276 379 276 221 277 77 277 219 277 78 278 219 278 77 278 219 279 78 279 218 279 83 280 218 280 78 280 379 281 79 281 77 281 84 282 83 282 78 282 81 283 77 283 79 283 77 284 81 284 78 284 82 285 78 285 81 285 78 286 82 286 84 286 79 287 80 287 81 287 85 288 84 288 82 288 80 289 231 289 81 289 232 290 81 290 231 290 81 291 232 291 82 291 226 292 82 292 232 292 82 293 226 293 85 293 86 294 85 294 226 294 86 295 226 295 87 295 218 296 83 296 216 296 89 297 216 297 83 297 83 298 84 298 89 298 94 299 89 299 84 299 84 300 85 300 94 300 85 301 100 301 94 301 85 302 86 302 100 302 86 303 87 303 100 303 103 304 100 304 87 304 225 305 103 305 87 305 150 306 88 306 151 306 88 307 150 307 152 307 91 308 152 308 216 308 152 309 91 309 88 309 151 310 90 310 362 310 90 311 151 311 88 311 216 312 89 312 91 312 106 313 362 313 90 313 88 314 93 314 90 314 93 315 88 315 91 315 89 316 94 316 91 316 92 317 90 317 93 317 90 318 92 318 106 318 95 319 91 319 94 319 91 320 95 320 93 320 107 321 106 321 92 321 96 322 92 322 93 322 92 323 96 323 107 323 93 324 97 324 96 324 97 325 93 325 95 325 94 326 100 326 95 326 101 327 95 327 100 327 95 328 101 328 97 328 108 329 107 329 96 329 96 330 98 330 108 330 98 331 96 331 97 331 99 332 97 332 101 332 97 333 99 333 98 333 98 334 104 334 108 334 104 335 98 335 99 335 99 336 105 336 104 336 105 337 99 337 101 337 100 338 103 338 101 338 101 339 103 339 102 339 109 340 108 340 104 340 101 341 102 341 105 341 102 342 267 342 105 342 268 343 104 343 105 343 104 344 268 344 109 344 269 345 109 345 268 345 105 346 267 346 268 346 362 347 106 347 364 347 111 348 364 348 106 348 106 349 107 349 111 349 121 350 111 350 107 350 107 351 108 351 121 351 124 352 121 352 108 352 108 353 109 353 124 353 127 354 124 354 109 354 109 355 269 355 127 355 270 356 127 356 269 356 110 357 189 357 171 357 171 358 112 358 110 358 112 359 171 359 168 359 170 360 113 360 168 360 113 361 170 361 364 361 168 362 114 362 112 362 114 363 168 363 113 363 364 364 111 364 113 364 115 365 110 365 112 365 111 366 121 366 113 366 116 367 112 367 114 367 112 368 116 368 115 368 119 369 113 369 121 369 113 370 119 370 114 370 114 371 117 371 116 371 117 372 114 372 119 372 118 373 115 373 116 373 120 374 116 374 117 374 116 375 120 375 118 375 122 376 117 376 119 376 117 377 122 377 120 377 123 378 118 378 120 378 126 379 119 379 121 379 119 380 126 380 122 380 120 381 128 381 123 381 128 382 120 382 122 382 121 383 124 383 126 383 129 384 122 384 126 384 122 385 129 385 128 385 125 386 123 386 128 386 124 387 127 387 126 387 128 388 130 388 125 388 130 389 222 389 125 389 131 390 126 390 127 390 126 391 131 391 129 391 127 392 270 392 131 392 130 393 128 393 129 393 264 394 129 394 131 394 129 395 264 395 130 395 270 396 265 396 131 396 131 397 265 397 264 397 201 398 202 398 132 398 202 399 133 399 132 399 139 400 133 400 202 400 133 401 139 401 134 401 139 402 136 402 134 402 136 403 141 403 135 403 141 404 138 404 135 404 141 405 136 405 139 405 351 406 349 406 137 406 137 407 138 407 351 407 138 408 142 408 351 408 142 409 138 409 141 409 202 410 203 410 139 410 139 411 140 411 141 411 139 412 204 412 140 412 139 413 203 413 204 413 353 414 351 414 142 414 144 415 141 415 143 415 141 416 140 416 143 416 141 417 144 417 142 417 142 418 145 418 353 418 145 419 355 419 353 419 145 420 142 420 144 420 357 421 355 421 145 421 143 422 146 422 144 422 146 423 143 423 210 423 210 424 143 424 208 424 147 425 144 425 146 425 144 426 147 426 145 426 148 427 145 427 147 427 145 428 148 428 357 428 148 429 359 429 357 429 210 430 211 430 146 430 149 431 146 431 214 431 146 432 211 432 214 432 146 433 149 433 147 433 361 434 359 434 148 434 147 435 150 435 148 435 150 436 151 436 148 436 150 437 147 437 149 437 148 438 151 438 361 438 214 439 215 439 149 439 152 440 149 440 215 440 152 441 150 441 149 441 361 442 151 442 362 442 216 443 152 443 215 443 178 444 176 444 153 444 153 445 155 445 178 445 162 446 155 446 160 446 155 447 154 447 160 447 154 448 156 448 160 448 155 449 162 449 178 449 160 450 156 450 157 450 157 451 159 451 160 451 350 452 352 452 158 452 352 453 159 453 158 453 159 454 161 454 160 454 161 455 159 455 352 455 352 456 354 456 161 456 181 457 178 457 162 457 160 458 163 458 162 458 163 459 160 459 161 459 164 460 161 460 356 460 161 461 354 461 356 461 161 462 164 462 163 462 165 463 162 463 163 463 162 464 165 464 181 464 165 465 182 465 181 465 356 466 358 466 164 466 185 467 182 467 165 467 166 468 163 468 164 468 163 469 166 469 165 469 167 470 164 470 360 470 164 471 358 471 360 471 164 472 167 472 166 472 165 473 169 473 185 473 169 474 188 474 185 474 169 475 165 475 166 475 360 476 363 476 167 476 190 477 188 477 169 477 168 478 166 478 170 478 166 479 167 479 170 479 166 480 168 480 169 480 170 481 167 481 363 481 169 482 171 482 190 482 169 483 168 483 171 483 363 484 364 484 170 484 189 485 190 485 171 485 179 486 172 486 178 486 178 487 181 487 179 487 179 488 183 488 180 488 183 489 179 489 181 489 184 490 180 490 183 490 180 491 184 491 366 491 184 492 367 492 366 492 181 493 182 493 183 493 368 494 367 494 184 494 186 495 183 495 185 495 183 496 182 496 185 496 183 497 186 497 184 497 187 498 184 498 186 498 184 499 187 499 368 499 187 500 370 500 368 500 185 501 188 501 186 501 372 502 370 502 187 502 186 503 191 503 187 503 191 504 186 504 188 504 187 505 194 505 372 505 194 506 374 506 372 506 194 507 187 507 191 507 188 508 190 508 191 508 191 509 189 509 193 509 191 510 190 510 189 510 191 511 193 511 194 511 376 512 374 512 194 512 195 513 194 513 192 513 194 514 193 514 192 514 194 515 195 515 376 515 377 516 376 516 195 516 196 517 206 517 197 517 206 518 199 518 197 518 206 519 205 519 199 519 206 520 196 520 365 520 199 521 205 521 200 521 205 522 201 522 200 522 205 523 202 523 201 523 205 524 203 524 202 524 204 525 203 525 205 525 205 526 207 526 204 526 207 527 208 527 204 527 207 528 205 528 206 528 206 529 209 529 207 529 206 530 384 530 209 530 384 531 369 531 209 531 212 532 207 532 209 532 207 533 212 533 208 533 212 534 210 534 208 534 209 535 213 535 212 535 213 536 209 536 371 536 209 537 369 537 371 537 211 538 210 538 212 538 371 539 373 539 213 539 212 540 217 540 211 540 217 541 214 541 211 541 217 542 212 542 213 542 213 543 220 543 217 543 220 544 213 544 375 544 213 545 373 545 375 545 215 546 214 546 217 546 217 547 218 547 215 547 218 548 216 548 215 548 218 549 217 549 220 549 375 550 378 550 220 550 221 551 220 551 378 551 378 552 379 552 221 552 223 553 228 553 224 553 228 554 227 554 224 554 233 555 225 555 226 555 225 556 87 556 226 556 226 557 232 557 233 557 229 558 227 558 228 558 228 559 234 559 229 559 234 560 230 560 229 560 233 561 232 561 231 561 237 562 235 562 236 562 236 563 238 563 237 563 239 564 237 564 238 564 238 565 240 565 239 565 241 566 239 566 240 566 240 567 242 567 241 567 243 568 241 568 242 568 242 569 244 569 243 569 245 570 243 570 244 570 244 571 246 571 245 571 247 572 245 572 246 572 246 573 248 573 247 573 249 574 247 574 248 574 248 575 250 575 249 575 251 576 249 576 250 576 252 577 254 577 253 577 255 578 253 578 254 578 254 579 256 579 255 579 257 580 255 580 256 580 256 581 258 581 257 581 259 582 257 582 258 582 258 583 260 583 259 583 261 584 259 584 260 584 260 585 262 585 261 585 263 586 261 586 262 586 262 587 266 587 263 587 271 588 263 588 266 588 266 589 264 589 265 589 265 590 270 590 266 590 270 591 271 591 266 591 271 592 268 592 267 592 271 593 269 593 268 593 271 594 270 594 269 594 274 595 272 595 273 595 273 596 275 596 274 596 276 597 274 597 275 597 275 598 277 598 276 598 278 599 276 599 277 599 277 600 279 600 278 600 280 601 278 601 279 601 279 602 281 602 280 602 282 603 280 603 281 603 281 604 283 604 282 604 284 605 282 605 283 605 283 606 285 606 284 606 286 607 284 607 285 607 285 608 287 608 286 608 288 609 286 609 287 609 287 610 289 610 288 610 290 611 288 611 289 611 289 612 291 612 290 612 292 613 290 613 291 613 291 614 293 614 292 614 294 615 292 615 293 615 293 616 295 616 294 616 296 617 294 617 295 617 295 618 297 618 296 618 298 619 296 619 297 619 297 620 299 620 298 620 300 621 298 621 299 621 299 622 303 622 300 622 301 623 300 623 303 623 303 624 302 624 301 624 306 625 304 625 305 625 305 626 307 626 306 626 308 627 306 627 307 627 307 628 309 628 308 628 310 629 308 629 309 629 309 630 311 630 310 630 313 631 310 631 311 631 316 632 312 632 313 632 319 633 313 633 315 633 313 634 312 634 315 634 315 635 318 635 319 635 322 636 319 636 320 636 319 637 318 637 320 637 320 638 321 638 322 638 325 639 322 639 323 639 322 640 321 640 323 640 323 641 324 641 325 641 327 642 325 642 326 642 325 643 324 643 326 643 326 644 328 644 327 644 330 645 327 645 328 645 328 646 329 646 330 646 333 647 330 647 331 647 330 648 329 648 331 648 331 649 332 649 333 649 339 650 333 650 335 650 333 651 332 651 335 651 335 652 338 652 339 652 341 653 339 653 340 653 339 654 337 654 340 654 339 655 338 655 337 655 340 656 342 656 341 656 343 657 341 657 342 657 342 658 344 658 343 658 345 659 343 659 344 659 344 660 348 660 345 660 346 661 345 661 348 661 348 662 347 662 346 662 356 663 354 663 355 663 355 664 357 664 356 664 358 665 356 665 357 665 357 666 359 666 358 666 360 667 358 667 359 667 359 668 361 668 360 668 363 669 360 669 361 669 361 670 362 670 363 670 364 671 363 671 362 671 368 672 384 672 367 672 369 673 384 673 368 673 368 674 370 674 369 674 371 675 369 675 370 675 370 676 372 676 371 676 373 677 371 677 372 677 372 678 374 678 373 678 375 679 373 679 374 679 374 680 376 680 375 680 378 681 375 681 376 681 376 682 377 682 378 682 379 683 378 683 377 683 173 684 180 684 174 684 180 685 380 685 174 685 180 686 382 686 380 686 366 687 382 687 180 687 365 688 383 688 206 688 383 689 384 689 206 689 389 690 391 690 390 690 392 691 390 691 391 691 391 692 393 692 392 692 394 693 392 693 393 693 393 694 395 694 394 694 396 695 394 695 395 695 395 696 397 696 396 696 398 697 396 697 397 697 397 698 399 698 398 698 400 699 398 699 399 699 399 700 401 700 400 700 402 701 400 701 401 701 401 702 403 702 402 702 404 703 402 703 403 703 403 704 405 704 404 704 406 705 404 705 405 705 413 706 411 706 412 706 412 707 414 707 413 707 415 708 413 708 414 708 414 709 416 709 415 709 417 710 415 710 416 710 416 711 418 711 417 711 419 712 417 712 418 712 418 713 420 713 419 713 421 714 419 714 420 714 420 715 422 715 421 715 421 716 422 716 423 716 424 717 421 717 423 717 340 718 337 718 336 718 425 719 340 719 336 719 336 720 334 720 425 720 425 721 334 721 426 721 427 722 425 722 426 722 426 723 428 723 427 723 427 724 428 724 429 724 430 725 427 725 429 725 429 726 431 726 430 726 430 727 431 727 432 727 433 728 430 728 432 728 432 729 434 729 433 729 435 730 433 730 434 730 434 731 436 731 435 731 435 732 436 732 437 732 438 733 435 733 437 733 437 734 439 734 438 734 438 735 439 735 317 735 316 736 438 736 317 736 317 737 314 737 316 737 316 738 314 738 312 738 311 739 316 739 313 739 253 740 440 740 252 740 441 741 252 741 440 741 440 742 442 742 441 742 443 743 441 743 442 743 442 744 444 744 443 744 445 745 443 745 444 745 444 746 446 746 445 746 447 747 445 747 446 747 446 748 448 748 447 748 449 749 447 749 448 749 448 750 450 750 449 750 451 751 449 751 450 751 452 752 451 752 450 752 453 753 452 753 450 753 451 754 452 754 454 754 451 755 454 755 455 755 456 756 451 756 455 756 457 757 458 757 459 757 460 758 461 758 462 758 462 759 463 759 460 759 464 760 465 760 459 760 458 761 464 761 459 761 466 762 460 762 463 762 467 763 465 763 464 763 463 764 468 764 466 764 469 765 470 765 471 765 469 766 471 766 472 766 469 767 472 767 467 767 464 768 469 768 467 768 466 769 468 769 473 769 470 770 469 770 474 770 473 771 470 771 474 771 474 772 466 772 473 772 469 773 475 773 474 773 476 774 474 774 475 774 475 775 477 775 476 775 478 776 476 776 477 776 477 777 479 777 478 777 480 778 478 778 479 778 479 779 251 779 480 779 250 780 480 780 251 780 482 781 385 781 481 781 385 782 387 782 481 782 489 783 385 783 482 783 487 784 490 784 488 784 389 785 385 785 489 785 491 786 488 786 490 786 488 787 491 787 489 787 492 788 489 788 491 788 492 789 391 789 389 789 489 790 492 790 389 790 490 791 493 791 491 791 393 792 391 792 492 792 491 793 494 793 492 793 491 794 493 794 495 794 494 795 491 795 495 795 492 796 496 796 393 796 496 797 492 797 494 797 395 798 393 798 496 798 495 799 497 799 494 799 494 800 497 800 498 800 499 801 494 801 498 801 494 802 499 802 496 802 500 803 397 803 395 803 496 804 500 804 395 804 500 805 496 805 499 805 498 806 501 806 499 806 399 807 397 807 500 807 499 808 501 808 502 808 503 809 499 809 502 809 499 810 503 810 500 810 502 811 504 811 503 811 505 812 401 812 399 812 500 813 505 813 399 813 505 814 500 814 503 814 403 815 401 815 505 815 503 816 504 816 506 816 503 817 506 817 507 817 508 818 503 818 507 818 503 819 508 819 505 819 505 820 509 820 403 820 505 821 508 821 510 821 509 822 505 822 510 822 403 823 509 823 405 823 516 824 517 824 515 824 516 825 515 825 514 825 513 826 516 826 514 826 518 827 516 827 513 827 518 828 513 828 512 828 511 829 518 829 512 829 518 830 511 830 388 830 519 831 517 831 516 831 388 832 390 832 518 832 520 833 516 833 518 833 520 834 521 834 519 834 516 835 520 835 519 835 518 836 390 836 392 836 522 837 518 837 392 837 518 838 522 838 520 838 523 839 521 839 520 839 392 840 394 840 522 840 524 841 520 841 522 841 524 842 525 842 523 842 520 843 524 843 523 843 526 844 522 844 394 844 522 845 526 845 524 845 394 846 396 846 526 846 527 847 525 847 524 847 524 848 528 848 527 848 528 849 524 849 526 849 529 850 527 850 528 850 526 851 530 851 528 851 526 852 396 852 398 852 530 853 526 853 398 853 398 854 400 854 530 854 531 855 532 855 529 855 528 856 531 856 529 856 531 857 528 857 530 857 533 858 532 858 531 858 530 859 534 859 531 859 530 860 400 860 402 860 534 861 530 861 402 861 402 862 404 862 534 862 535 863 531 863 534 863 538 864 534 864 404 864 404 865 406 865 538 865 517 866 540 866 541 866 515 867 517 867 541 867 542 868 543 868 410 868 410 869 408 869 542 869 543 870 544 870 410 870 545 871 544 871 543 871 545 872 543 872 546 872 547 873 545 873 546 873 548 874 545 874 547 874 548 875 547 875 549 875 540 876 548 876 549 876 548 877 540 877 517 877 517 878 519 878 548 878 412 879 410 879 544 879 550 880 544 880 545 880 550 881 414 881 412 881 544 882 550 882 412 882 551 883 545 883 548 883 545 884 551 884 550 884 548 885 552 885 551 885 548 886 519 886 521 886 552 887 548 887 521 887 521 888 523 888 552 888 416 889 414 889 550 889 553 890 550 890 551 890 550 891 553 891 416 891 554 892 551 892 552 892 551 893 554 893 553 893 552 894 523 894 525 894 555 895 552 895 525 895 552 896 555 896 554 896 418 897 416 897 553 897 525 898 527 898 555 898 556 899 420 899 418 899 553 900 556 900 418 900 556 901 553 901 554 901 557 902 554 902 555 902 554 903 557 903 556 903 555 904 558 904 557 904 555 905 527 905 529 905 558 906 555 906 529 906 422 907 420 907 556 907 529 908 532 908 558 908 559 909 423 909 422 909 556 910 559 910 422 910 559 911 556 911 557 911 560 912 559 912 557 912 560 913 557 913 558 913 558 914 532 914 533 914 560 915 558 915 533 915 561 916 560 916 533 916 537 917 561 917 533 917 487 918 485 918 562 918 563 919 407 919 409 919 564 920 563 920 409 920 565 921 563 921 564 921 566 922 565 922 564 922 567 923 566 923 564 923 487 924 568 924 490 924 569 925 566 925 567 925 562 926 569 926 567 926 568 927 562 927 567 927 562 928 568 928 487 928 409 929 411 929 564 929 564 930 570 930 567 930 564 931 411 931 413 931 570 932 564 932 413 932 567 933 571 933 568 933 571 934 567 934 570 934 493 935 490 935 568 935 413 936 415 936 570 936 572 937 493 937 568 937 572 938 568 938 571 938 495 939 493 939 572 939 570 940 573 940 571 940 573 941 570 941 415 941 571 942 574 942 572 942 574 943 571 943 573 943 415 944 417 944 573 944 575 945 572 945 574 945 575 946 497 946 495 946 572 947 575 947 495 947 498 948 497 948 575 948 573 949 576 949 574 949 573 950 417 950 419 950 576 951 573 951 419 951 574 952 577 952 575 952 577 953 574 953 576 953 578 954 575 954 577 954 578 955 501 955 498 955 575 956 578 956 498 956 419 957 421 957 576 957 502 958 501 958 578 958 576 959 579 959 577 959 576 960 421 960 424 960 576 961 424 961 579 961 577 962 580 962 578 962 577 963 579 963 580 963 578 964 580 964 581 964 581 965 504 965 502 965 578 966 581 966 502 966 506 967 504 967 581 967 452 968 582 968 454 968 583 969 454 969 582 969 582 970 584 970 583 970 585 971 583 971 584 971 584 972 586 972 585 972 587 973 585 973 586 973 586 974 588 974 587 974 589 975 587 975 588 975 588 976 590 976 589 976 591 977 589 977 590 977 590 978 424 978 591 978 423 979 591 979 424 979 454 980 592 980 455 980 593 981 455 981 592 981 455 982 593 982 456 982 592 983 583 983 593 983 594 984 456 984 593 984 595 985 593 985 583 985 593 986 595 986 594 986 583 987 585 987 595 987 596 988 456 988 594 988 597 989 595 989 585 989 595 990 597 990 594 990 594 991 598 991 596 991 598 992 594 992 597 992 585 993 587 993 597 993 597 994 599 994 598 994 599 995 597 995 587 995 587 996 589 996 599 996 600 997 596 997 598 997 601 998 598 998 599 998 598 999 601 999 600 999 602 1000 599 1000 589 1000 599 1001 602 1001 601 1001 589 1002 603 1002 602 1002 604 1003 600 1003 601 1003 601 1004 605 1004 604 1004 605 1005 601 1005 602 1005 602 1006 606 1006 605 1006 606 1007 602 1007 603 1007 603 1008 591 1008 606 1008 607 1009 604 1009 605 1009 606 1010 559 1010 605 1010 559 1011 606 1011 591 1011 561 1012 607 1012 605 1012 591 1013 423 1013 559 1013 560 1014 605 1014 559 1014 605 1015 560 1015 561 1015 614 1016 608 1016 596 1016 596 1017 600 1017 614 1017 609 1018 614 1018 600 1018 600 1019 604 1019 609 1019 623 1020 609 1020 604 1020 604 1021 607 1021 623 1021 610 1022 623 1022 607 1022 607 1023 561 1023 610 1023 610 1024 561 1024 537 1024 611 1025 462 1025 461 1025 461 1026 608 1026 611 1026 463 1027 462 1027 611 1027 612 1028 463 1028 611 1028 611 1029 613 1029 612 1029 613 1030 611 1030 608 1030 468 1031 463 1031 612 1031 608 1032 614 1032 613 1032 612 1033 615 1033 468 1033 473 1034 468 1034 615 1034 614 1035 609 1035 613 1035 616 1036 612 1036 613 1036 612 1037 616 1037 615 1037 613 1038 617 1038 616 1038 617 1039 613 1039 609 1039 618 1040 615 1040 616 1040 615 1041 618 1041 473 1041 619 1042 470 1042 473 1042 473 1043 620 1043 619 1043 620 1044 473 1044 618 1044 616 1045 621 1045 618 1045 621 1046 616 1046 617 1046 617 1047 622 1047 621 1047 622 1048 617 1048 609 1048 609 1049 623 1049 622 1049 618 1050 624 1050 620 1050 624 1051 618 1051 621 1051 625 1052 626 1052 619 1052 620 1053 625 1053 619 1053 625 1054 620 1054 624 1054 623 1055 610 1055 622 1055 621 1056 535 1056 624 1056 535 1057 621 1057 622 1057 627 1058 622 1058 610 1058 622 1059 627 1059 535 1059 624 1060 539 1060 625 1060 539 1061 624 1061 535 1061 627 1062 610 1062 536 1062 535 1063 627 1063 536 1063 538 1064 406 1064 626 1064 625 1065 538 1065 626 1065 610 1066 537 1066 536 1066 470 1067 619 1067 471 1067 628 1068 471 1068 619 1068 619 1069 626 1069 628 1069 629 1070 628 1070 626 1070 626 1071 406 1071 629 1071 405 1072 629 1072 406 1072 630 1073 457 1073 459 1073 459 1074 631 1074 630 1074 459 1075 465 1075 631 1075 465 1076 632 1076 631 1076 633 1077 631 1077 632 1077 631 1078 633 1078 630 1078 465 1079 467 1079 632 1079 646 1080 630 1080 633 1080 467 1081 634 1081 632 1081 467 1082 472 1082 634 1082 635 1083 632 1083 634 1083 632 1084 635 1084 633 1084 636 1085 646 1085 633 1085 633 1086 637 1086 636 1086 637 1087 633 1087 635 1087 472 1088 638 1088 634 1088 472 1089 471 1089 638 1089 639 1090 634 1090 638 1090 634 1091 639 1091 635 1091 471 1092 628 1092 638 1092 640 1093 636 1093 637 1093 641 1094 637 1094 635 1094 637 1095 641 1095 640 1095 642 1096 638 1096 628 1096 638 1097 642 1097 639 1097 635 1098 643 1098 641 1098 643 1099 635 1099 639 1099 644 1100 639 1100 642 1100 639 1101 644 1101 643 1101 628 1102 629 1102 642 1102 507 1103 641 1103 643 1103 641 1104 507 1104 640 1104 508 1105 643 1105 644 1105 643 1106 508 1106 507 1106 506 1107 640 1107 507 1107 644 1108 510 1108 508 1108 510 1109 644 1109 642 1109 642 1110 509 1110 510 1110 509 1111 642 1111 629 1111 629 1112 405 1112 509 1112 630 1113 646 1113 645 1113 647 1114 645 1114 646 1114 646 1115 636 1115 647 1115 648 1116 647 1116 636 1116 636 1117 640 1117 648 1117 649 1118 648 1118 640 1118 640 1119 506 1119 649 1119 581 1120 649 1120 506 1120 453 1121 650 1121 452 1121 453 1122 450 1122 651 1122 650 1123 453 1123 651 1123 582 1124 452 1124 650 1124 652 1125 650 1125 651 1125 650 1126 652 1126 582 1126 653 1127 582 1127 652 1127 651 1128 654 1128 652 1128 584 1129 653 1129 652 1129 655 1130 652 1130 654 1130 652 1131 655 1131 584 1131 656 1132 584 1132 655 1132 651 1133 630 1133 654 1133 654 1134 630 1134 645 1134 657 1135 654 1135 645 1135 654 1136 657 1136 655 1136 655 1137 658 1137 656 1137 658 1138 655 1138 657 1138 586 1139 656 1139 658 1139 659 1140 657 1140 645 1140 657 1141 659 1141 658 1141 645 1142 647 1142 659 1142 588 1143 586 1143 658 1143 658 1144 660 1144 588 1144 660 1145 658 1145 659 1145 659 1146 661 1146 660 1146 661 1147 659 1147 647 1147 647 1148 648 1148 661 1148 590 1149 588 1149 660 1149 662 1150 661 1150 648 1150 661 1151 662 1151 660 1151 663 1152 660 1152 662 1152 660 1153 663 1153 590 1153 648 1154 649 1154 662 1154 662 1155 580 1155 663 1155 580 1156 662 1156 649 1156 649 1157 581 1157 580 1157 424 1158 590 1158 663 1158 579 1159 663 1159 580 1159 663 1160 579 1160 424 1160 475 1161 670 1161 671 1161 477 1162 475 1162 671 1162 479 1163 477 1163 671 1163 442 1164 440 1164 673 1164 671 1165 674 1165 479 1165 479 1166 674 1166 64 1166 251 1167 479 1167 64 1167 253 1168 63 1168 673 1168 440 1169 253 1169 673 1169 287 1170 285 1170 664 1170 665 1171 664 1171 285 1171 285 1172 283 1172 665 1172 666 1173 665 1173 283 1173 283 1174 281 1174 666 1174 670 1175 666 1175 281 1175 281 1176 279 1176 670 1176 671 1177 670 1177 279 1177 279 1178 277 1178 671 1178 674 1179 671 1179 277 1179 277 1180 275 1180 674 1180 64 1181 674 1181 275 1181 275 1182 273 1182 64 1182 303 1183 299 1183 63 1183 673 1184 63 1184 299 1184 299 1185 297 1185 673 1185 672 1186 673 1186 297 1186 297 1187 295 1187 672 1187 669 1188 672 1188 295 1188 295 1189 293 1189 669 1189 667 1190 669 1190 293 1190 293 1191 291 1191 667 1191 668 1192 667 1192 291 1192 291 1193 289 1193 668 1193 668 1194 289 1194 287 1194 664 1195 668 1195 287 1195 252 1196 441 1196 28 1196 433 1197 435 1197 684 1197 685 1198 684 1198 435 1198 435 1199 438 1199 685 1199 681 1200 685 1200 438 1200 438 1201 316 1201 681 1201 680 1202 681 1202 316 1202 316 1203 311 1203 680 1203 678 1204 680 1204 311 1204 311 1205 309 1205 678 1205 676 1206 678 1206 309 1206 309 1207 307 1207 676 1207 28 1208 676 1208 307 1208 307 1209 305 1209 28 1209 16 1210 434 1210 432 1210 14 1211 16 1211 432 1211 436 1212 434 1212 16 1212 16 1213 18 1213 436 1213 437 1214 436 1214 18 1214 18 1215 20 1215 437 1215 439 1216 437 1216 20 1216 20 1217 22 1217 439 1217 317 1218 439 1218 22 1218 22 1219 25 1219 317 1219 4 1220 6 1220 334 1220 426 1221 334 1221 6 1221 6 1222 8 1222 426 1222 428 1223 426 1223 8 1223 8 1224 10 1224 428 1224 429 1225 428 1225 10 1225 10 1226 12 1226 429 1226 431 1227 429 1227 12 1227 12 1228 14 1228 431 1228 432 1229 431 1229 14 1229 348 1230 344 1230 27 1230 675 1231 27 1231 344 1231 344 1232 342 1232 675 1232 677 1233 675 1233 342 1233 342 1234 340 1234 677 1234 679 1235 677 1235 340 1235 340 1236 425 1236 679 1236 682 1237 679 1237 425 1237 425 1238 427 1238 682 1238 683 1239 682 1239 427 1239 427 1240 430 1240 683 1240 683 1241 430 1241 433 1241 684 1242 683 1242 433 1242 388 1243 389 1243 390 1243 385 1244 389 1244 388 1244 385 1245 388 1245 386 1245 385 1246 386 1246 387 1246 410 1247 412 1247 411 1247 409 1248 410 1248 411 1248 408 1249 410 1249 409 1249 407 1250 408 1250 409 1250 533 1251 536 1251 537 1251 534 1252 539 1252 535 1252 534 1253 538 1253 539 1253 538 1254 625 1254 539 1254 480 1255 250 1255 27 1255 480 1256 27 1256 675 1256 478 1257 480 1257 675 1257 478 1258 675 1258 677 1258 476 1259 478 1259 677 1259 476 1260 677 1260 679 1260 474 1261 476 1261 679 1261 466 1262 474 1262 679 1262 466 1263 679 1263 682 1263 460 1264 466 1264 682 1264 460 1265 682 1265 683 1265 460 1266 683 1266 461 1266 461 1267 683 1267 684 1267 456 1268 684 1268 685 1268 451 1269 456 1269 685 1269 461 1270 686 1270 608 1270 456 1271 686 1271 684 1271 686 1272 461 1272 684 1272 596 1273 608 1273 686 1273 456 1274 596 1274 686 1274 531 1275 536 1275 533 1275 531 1276 535 1276 536 1276 451 1277 685 1277 681 1277 449 1278 451 1278 681 1278 449 1279 681 1279 680 1279 441 1280 443 1280 28 1280 443 1281 676 1281 28 1281 443 1282 445 1282 676 1282 445 1283 678 1283 676 1283 445 1284 447 1284 678 1284 447 1285 680 1285 678 1285 447 1286 449 1286 680 1286 469 1287 670 1287 475 1287 464 1288 670 1288 469 1288 464 1289 666 1289 670 1289 458 1290 666 1290 464 1290 458 1291 665 1291 666 1291 457 1292 665 1292 458 1292 457 1293 664 1293 665 1293 457 1294 630 1294 664 1294 630 1295 668 1295 664 1295 630 1296 651 1296 668 1296 450 1297 667 1297 651 1297 651 1298 667 1298 668 1298 450 1299 669 1299 667 1299 448 1300 669 1300 450 1300 448 1301 672 1301 669 1301 446 1302 672 1302 448 1302 446 1303 673 1303 672 1303 444 1304 673 1304 446 1304 442 1305 673 1305 444 1305 482 1306 483 1306 489 1306 483 1307 488 1307 489 1307 483 1308 486 1308 488 1308 484 1309 488 1309 486 1309 484 1310 487 1310 488 1310 484 1311 485 1311 487 1311 386 1312 388 1312 687 1312 388 1313 511 1313 687 1313 841 1314 766 1314 765 1314 841 1315 767 1315 766 1315 841 1316 768 1316 767 1316 841 1317 839 1317 768 1317 789 1318 687 1318 511 1318 386 1319 687 1319 906 1319 906 1320 687 1320 789 1320 380 1321 820 1321 819 1321 380 1322 821 1322 820 1322 381 1323 821 1323 380 1323 381 1324 822 1324 821 1324 381 1325 823 1325 822 1325 785 1326 783 1326 711 1326 783 1327 784 1327 711 1327 710 1328 711 1328 784 1328 784 1329 782 1329 710 1329 709 1330 710 1330 782 1330 782 1331 742 1331 709 1331 708 1332 709 1332 742 1332 742 1333 743 1333 708 1333 707 1334 708 1334 744 1334 708 1335 743 1335 744 1335 706 1336 707 1336 745 1336 707 1337 744 1337 745 1337 706 1338 745 1338 746 1338 705 1339 715 1339 716 1339 716 1340 713 1340 705 1340 704 1341 705 1341 713 1341 713 1342 714 1342 704 1342 703 1343 704 1343 714 1343 714 1344 712 1344 703 1344 702 1345 703 1345 712 1345 700 1346 702 1346 790 1346 702 1347 712 1347 790 1347 790 1348 791 1348 700 1348 701 1349 700 1349 791 1349 791 1350 792 1350 701 1350 792 1351 793 1351 701 1351 800 1352 798 1352 689 1352 798 1353 799 1353 689 1353 688 1354 689 1354 799 1354 799 1355 797 1355 688 1355 690 1356 688 1356 797 1356 797 1357 726 1357 690 1357 693 1358 690 1358 726 1358 726 1359 727 1359 693 1359 692 1360 693 1360 728 1360 693 1361 727 1361 728 1361 691 1362 692 1362 729 1362 692 1363 728 1363 729 1363 691 1364 729 1364 730 1364 695 1365 760 1365 761 1365 761 1366 758 1366 695 1366 694 1367 695 1367 758 1367 758 1368 759 1368 694 1368 696 1369 694 1369 759 1369 759 1370 757 1370 696 1370 697 1371 696 1371 757 1371 698 1372 697 1372 772 1372 697 1373 757 1373 772 1373 772 1374 773 1374 698 1374 699 1375 698 1375 773 1375 773 1376 774 1376 699 1376 774 1377 775 1377 699 1377 825 1378 823 1378 804 1378 823 1379 805 1379 804 1379 804 1380 803 1380 825 1380 827 1381 825 1381 802 1381 825 1382 803 1382 802 1382 838 1383 840 1383 741 1383 840 1384 740 1384 741 1384 840 1385 739 1385 740 1385 840 1386 738 1386 739 1386 802 1387 801 1387 827 1387 829 1388 827 1388 800 1388 827 1389 801 1389 800 1389 737 1390 738 1390 840 1390 840 1391 842 1391 737 1391 842 1392 736 1392 737 1392 842 1393 735 1393 736 1393 842 1394 734 1394 735 1394 842 1395 733 1395 734 1395 842 1396 732 1396 733 1396 688 1397 690 1397 689 1397 800 1398 689 1398 690 1398 690 1399 693 1399 800 1399 693 1400 829 1400 800 1400 831 1401 829 1401 730 1401 829 1402 691 1402 730 1402 829 1403 692 1403 691 1403 829 1404 693 1404 692 1404 731 1405 732 1405 842 1405 842 1406 844 1406 731 1406 844 1407 730 1407 731 1407 844 1408 831 1408 730 1408 833 1409 831 1409 844 1409 844 1410 846 1410 833 1410 834 1411 833 1411 846 1411 846 1412 848 1412 834 1412 836 1413 834 1413 848 1413 848 1414 850 1414 836 1414 835 1415 836 1415 850 1415 850 1416 852 1416 835 1416 832 1417 835 1417 852 1417 852 1418 854 1418 832 1418 830 1419 832 1419 854 1419 854 1420 856 1420 830 1420 828 1421 830 1421 856 1421 856 1422 858 1422 828 1422 826 1423 828 1423 858 1423 858 1424 860 1424 826 1424 824 1425 826 1425 860 1425 860 1426 863 1426 824 1426 822 1427 824 1427 863 1427 863 1428 864 1428 822 1428 821 1429 822 1429 864 1429 864 1430 862 1430 821 1430 820 1431 821 1431 862 1431 862 1432 861 1432 820 1432 818 1433 820 1433 861 1433 861 1434 859 1434 818 1434 816 1435 818 1435 859 1435 859 1436 857 1436 816 1436 814 1437 816 1437 857 1437 857 1438 855 1438 814 1438 812 1439 814 1439 855 1439 855 1440 853 1440 812 1440 810 1441 812 1441 853 1441 853 1442 851 1442 810 1442 808 1443 810 1443 851 1443 851 1444 849 1444 808 1444 806 1445 808 1445 849 1445 849 1446 847 1446 806 1446 807 1447 806 1447 847 1447 847 1448 845 1448 807 1448 809 1449 807 1449 845 1449 845 1450 843 1450 809 1450 811 1451 809 1451 843 1451 843 1452 841 1452 760 1452 760 1453 811 1453 843 1453 841 1454 762 1454 760 1454 813 1455 811 1455 696 1455 811 1456 694 1456 696 1456 811 1457 695 1457 694 1457 811 1458 760 1458 695 1458 763 1459 762 1459 841 1459 765 1460 764 1460 841 1460 764 1461 763 1461 841 1461 696 1462 697 1462 775 1462 775 1463 813 1463 696 1463 815 1464 813 1464 776 1464 813 1465 775 1465 776 1465 699 1466 775 1466 697 1466 697 1467 698 1467 699 1467 769 1468 768 1468 839 1468 839 1469 837 1469 771 1469 771 1470 770 1470 839 1470 770 1471 769 1471 839 1471 776 1472 777 1472 815 1472 817 1473 815 1473 778 1473 815 1474 777 1474 778 1474 778 1475 779 1475 817 1475 819 1476 817 1476 780 1476 817 1477 779 1477 780 1477 387 1478 910 1478 481 1478 910 1479 912 1479 481 1479 912 1480 482 1480 481 1480 796 1481 482 1481 912 1481 912 1482 914 1482 796 1482 914 1483 795 1483 796 1483 890 1484 892 1484 725 1484 725 1485 724 1485 890 1485 724 1486 723 1486 890 1486 723 1487 722 1487 890 1487 794 1488 795 1488 914 1488 914 1489 916 1489 794 1489 916 1490 793 1490 794 1490 722 1491 721 1491 890 1491 888 1492 890 1492 719 1492 719 1493 718 1493 888 1493 890 1494 720 1494 719 1494 890 1495 721 1495 720 1495 702 1496 700 1496 701 1496 701 1497 793 1497 702 1497 703 1498 702 1498 793 1498 793 1499 916 1499 703 1499 916 1500 918 1500 703 1500 918 1501 704 1501 703 1501 918 1502 705 1502 704 1502 918 1503 715 1503 705 1503 886 1504 888 1504 715 1504 715 1505 918 1505 886 1505 888 1506 717 1506 715 1506 888 1507 718 1507 717 1507 918 1508 920 1508 886 1508 884 1509 886 1509 920 1509 920 1510 921 1510 884 1510 882 1511 884 1511 921 1511 921 1512 922 1512 882 1512 880 1513 882 1513 922 1513 922 1514 923 1514 880 1514 878 1515 880 1515 923 1515 923 1516 919 1516 878 1516 876 1517 878 1517 919 1517 919 1518 917 1518 876 1518 874 1519 876 1519 917 1519 917 1520 915 1520 874 1520 872 1521 874 1521 915 1521 915 1522 913 1522 872 1522 870 1523 872 1523 913 1523 913 1524 911 1524 870 1524 868 1525 870 1525 911 1525 911 1526 909 1526 868 1526 866 1527 868 1527 909 1527 909 1528 908 1528 866 1528 865 1529 866 1529 908 1529 908 1530 907 1530 865 1530 867 1531 865 1531 907 1531 907 1532 905 1532 867 1532 869 1533 867 1533 905 1533 905 1534 903 1534 869 1534 871 1535 869 1535 903 1535 903 1536 901 1536 871 1536 873 1537 871 1537 901 1537 901 1538 899 1538 873 1538 875 1539 873 1539 899 1539 899 1540 897 1540 875 1540 877 1541 875 1541 897 1541 897 1542 895 1542 877 1542 879 1543 877 1543 895 1543 895 1544 893 1544 879 1544 881 1545 879 1545 893 1545 893 1546 894 1546 881 1546 883 1547 881 1547 894 1547 894 1548 896 1548 883 1548 885 1549 883 1549 896 1549 896 1550 898 1550 885 1550 887 1551 885 1551 747 1551 885 1552 746 1552 747 1552 885 1553 898 1553 746 1553 898 1554 900 1554 746 1554 900 1555 706 1555 746 1555 900 1556 707 1556 706 1556 900 1557 708 1557 707 1557 747 1558 748 1558 887 1558 889 1559 887 1559 753 1559 887 1560 752 1560 753 1560 887 1561 751 1561 752 1561 887 1562 750 1562 751 1562 887 1563 749 1563 750 1563 887 1564 748 1564 749 1564 709 1565 708 1565 785 1565 708 1566 900 1566 785 1566 900 1567 902 1567 785 1567 902 1568 786 1568 785 1568 785 1569 711 1569 709 1569 710 1570 709 1570 711 1570 753 1571 754 1571 889 1571 891 1572 889 1572 756 1572 889 1573 755 1573 756 1573 889 1574 754 1574 755 1574 787 1575 786 1575 902 1575 902 1576 904 1576 787 1576 904 1577 788 1577 787 1577 789 1578 788 1578 904 1578 904 1579 906 1579 789 1579 790 1580 712 1580 485 1580 562 1581 485 1581 712 1581 712 1582 714 1582 562 1582 562 1583 713 1583 716 1583 562 1584 714 1584 713 1584 569 1585 562 1585 717 1585 562 1586 715 1586 717 1586 562 1587 716 1587 715 1587 717 1588 718 1588 569 1588 566 1589 569 1589 719 1589 569 1590 718 1590 719 1590 565 1591 566 1591 720 1591 566 1592 719 1592 720 1592 720 1593 721 1593 565 1593 563 1594 565 1594 722 1594 565 1595 721 1595 722 1595 722 1596 723 1596 563 1596 407 1597 563 1597 724 1597 563 1598 723 1598 724 1598 724 1599 725 1599 407 1599 407 1600 725 1600 892 1600 201 1601 132 1601 797 1601 132 1602 726 1602 797 1602 727 1603 726 1603 132 1603 132 1604 133 1604 727 1604 133 1605 728 1605 727 1605 133 1606 729 1606 728 1606 730 1607 729 1607 133 1607 133 1608 134 1608 730 1608 134 1609 731 1609 730 1609 732 1610 731 1610 134 1610 134 1611 136 1611 732 1611 136 1612 733 1612 732 1612 734 1613 733 1613 136 1613 136 1614 135 1614 734 1614 135 1615 735 1615 734 1615 736 1616 735 1616 135 1616 135 1617 138 1617 736 1617 138 1618 737 1618 736 1618 138 1619 738 1619 737 1619 739 1620 738 1620 138 1620 138 1621 137 1621 739 1621 137 1622 740 1622 739 1622 741 1623 740 1623 137 1623 137 1624 349 1624 741 1624 838 1625 741 1625 349 1625 515 1626 541 1626 782 1626 541 1627 742 1627 782 1627 743 1628 742 1628 541 1628 541 1629 540 1629 743 1629 540 1630 744 1630 743 1630 540 1631 745 1631 744 1631 746 1632 745 1632 540 1632 540 1633 549 1633 746 1633 549 1634 747 1634 746 1634 748 1635 747 1635 549 1635 549 1636 547 1636 748 1636 547 1637 749 1637 748 1637 750 1638 749 1638 547 1638 547 1639 546 1639 750 1639 546 1640 751 1640 750 1640 752 1641 751 1641 546 1641 546 1642 543 1642 752 1642 543 1643 753 1643 752 1643 754 1644 753 1644 543 1644 543 1645 542 1645 754 1645 542 1646 755 1646 754 1646 756 1647 755 1647 542 1647 542 1648 408 1648 756 1648 891 1649 756 1649 408 1649 772 1650 757 1650 176 1650 153 1651 176 1651 757 1651 757 1652 759 1652 153 1652 155 1653 153 1653 761 1653 153 1654 758 1654 761 1654 153 1655 759 1655 758 1655 154 1656 155 1656 762 1656 155 1657 760 1657 762 1657 155 1658 761 1658 760 1658 762 1659 763 1659 154 1659 156 1660 154 1660 764 1660 154 1661 763 1661 764 1661 764 1662 765 1662 156 1662 157 1663 156 1663 766 1663 156 1664 765 1664 766 1664 766 1665 767 1665 157 1665 159 1666 157 1666 768 1666 157 1667 767 1667 768 1667 768 1668 769 1668 159 1668 158 1669 159 1669 770 1669 159 1670 769 1670 770 1670 770 1671 771 1671 158 1671 350 1672 158 1672 837 1672 158 1673 771 1673 837 1673 176 1674 177 1674 772 1674 177 1675 773 1675 772 1675 177 1676 774 1676 773 1676 177 1677 775 1677 774 1677 776 1678 775 1678 177 1678 177 1679 172 1679 776 1679 777 1680 776 1680 172 1680 172 1681 175 1681 777 1681 778 1682 777 1682 175 1682 175 1683 173 1683 778 1683 173 1684 779 1684 778 1684 780 1685 779 1685 173 1685 173 1686 174 1686 780 1686 782 1687 784 1687 515 1687 514 1688 515 1688 785 1688 515 1689 783 1689 785 1689 515 1690 784 1690 783 1690 785 1691 786 1691 514 1691 513 1692 514 1692 786 1692 786 1693 787 1693 513 1693 512 1694 513 1694 787 1694 787 1695 788 1695 512 1695 511 1696 512 1696 789 1696 512 1697 788 1697 789 1697 485 1698 484 1698 790 1698 484 1699 791 1699 790 1699 484 1700 792 1700 791 1700 484 1701 793 1701 792 1701 794 1702 793 1702 484 1702 484 1703 486 1703 794 1703 795 1704 794 1704 486 1704 486 1705 483 1705 795 1705 796 1706 795 1706 483 1706 483 1707 482 1707 796 1707 797 1708 799 1708 201 1708 200 1709 201 1709 800 1709 201 1710 798 1710 800 1710 201 1711 799 1711 798 1711 800 1712 801 1712 200 1712 199 1713 200 1713 801 1713 801 1714 802 1714 199 1714 197 1715 199 1715 802 1715 802 1716 803 1716 197 1716 196 1717 197 1717 804 1717 197 1718 803 1718 804 1718 804 1719 805 1719 196 1719 808 1720 806 1720 807 1720 807 1721 809 1721 808 1721 810 1722 808 1722 809 1722 809 1723 811 1723 810 1723 812 1724 810 1724 811 1724 811 1725 813 1725 812 1725 814 1726 812 1726 813 1726 813 1727 815 1727 814 1727 816 1728 814 1728 815 1728 815 1729 817 1729 816 1729 818 1730 816 1730 817 1730 817 1731 819 1731 818 1731 820 1732 818 1732 819 1732 824 1733 822 1733 823 1733 823 1734 825 1734 824 1734 826 1735 824 1735 825 1735 825 1736 827 1736 826 1736 828 1737 826 1737 827 1737 827 1738 829 1738 828 1738 830 1739 828 1739 829 1739 829 1740 831 1740 830 1740 832 1741 830 1741 831 1741 831 1742 833 1742 832 1742 835 1743 832 1743 833 1743 833 1744 834 1744 835 1744 836 1745 835 1745 834 1745 350 1746 837 1746 349 1746 838 1747 349 1747 837 1747 837 1748 839 1748 838 1748 840 1749 838 1749 839 1749 839 1750 841 1750 840 1750 842 1751 840 1751 841 1751 841 1752 843 1752 842 1752 844 1753 842 1753 843 1753 843 1754 845 1754 844 1754 846 1755 844 1755 845 1755 845 1756 847 1756 846 1756 848 1757 846 1757 847 1757 847 1758 849 1758 848 1758 850 1759 848 1759 849 1759 849 1760 851 1760 850 1760 852 1761 850 1761 851 1761 851 1762 853 1762 852 1762 854 1763 852 1763 853 1763 853 1764 855 1764 854 1764 856 1765 854 1765 855 1765 855 1766 857 1766 856 1766 858 1767 856 1767 857 1767 857 1768 859 1768 858 1768 860 1769 858 1769 859 1769 859 1770 861 1770 860 1770 863 1771 860 1771 861 1771 861 1772 862 1772 863 1772 864 1773 863 1773 862 1773 865 1774 867 1774 866 1774 868 1775 866 1775 867 1775 867 1776 869 1776 868 1776 870 1777 868 1777 869 1777 869 1778 871 1778 870 1778 872 1779 870 1779 871 1779 871 1780 873 1780 872 1780 874 1781 872 1781 873 1781 873 1782 875 1782 874 1782 876 1783 874 1783 875 1783 875 1784 877 1784 876 1784 878 1785 876 1785 877 1785 877 1786 879 1786 878 1786 880 1787 878 1787 879 1787 879 1788 881 1788 880 1788 882 1789 880 1789 881 1789 881 1790 883 1790 882 1790 884 1791 882 1791 883 1791 883 1792 885 1792 884 1792 886 1793 884 1793 885 1793 885 1794 887 1794 886 1794 888 1795 886 1795 887 1795 887 1796 889 1796 888 1796 890 1797 888 1797 889 1797 889 1798 891 1798 890 1798 892 1799 890 1799 891 1799 891 1800 408 1800 892 1800 407 1801 892 1801 408 1801 893 1802 895 1802 894 1802 896 1803 894 1803 895 1803 895 1804 897 1804 896 1804 898 1805 896 1805 897 1805 897 1806 899 1806 898 1806 900 1807 898 1807 899 1807 899 1808 901 1808 900 1808 902 1809 900 1809 901 1809 901 1810 903 1810 902 1810 904 1811 902 1811 903 1811 903 1812 905 1812 904 1812 906 1813 904 1813 905 1813 905 1814 907 1814 906 1814 386 1815 906 1815 907 1815 907 1816 908 1816 386 1816 386 1817 908 1817 387 1817 908 1818 909 1818 387 1818 910 1819 387 1819 909 1819 909 1820 911 1820 910 1820 912 1821 910 1821 911 1821 911 1822 913 1822 912 1822 914 1823 912 1823 913 1823 913 1824 915 1824 914 1824 916 1825 914 1825 915 1825 915 1826 917 1826 916 1826 918 1827 916 1827 917 1827 917 1828 919 1828 918 1828 920 1829 918 1829 919 1829 919 1830 923 1830 920 1830 921 1831 920 1831 923 1831 923 1832 922 1832 921 1832 823 1833 381 1833 924 1833 924 1834 805 1834 823 1834 780 1835 781 1835 819 1835 380 1836 819 1836 781 1836 781 1837 780 1837 174 1837 174 1838 380 1838 781 1838 198 1839 196 1839 805 1839 805 1840 924 1840 198 1840 198 1841 924 1841 381 1841

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/wrist/wrist_E3M5_no_rot.dae b/URDFs/sr_description/meshes/components/wrist/wrist_E3M5_no_rot.dae new file mode 100644 index 0000000..cc3c6cc --- /dev/null +++ b/URDFs/sr_description/meshes/components/wrist/wrist_E3M5_no_rot.dae @@ -0,0 +1,153 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:08:15 + 2025-02-20T09:08:15 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.9 0.9 0.9 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -12.60386 -4e-4 -4.55191 -0.5429 13.89959 -4.46761 0.54193 13.89959 -4.46761 -1.5962 13.89959 -4.20799 1.59524 13.89959 -4.20799 -2.55677 13.89959 -3.70385 2.55581 13.89959 -3.70385 -3.36878 13.89959 -2.98447 3.36782 13.89959 -2.98447 -3.98503 13.89959 -2.09167 3.98407 13.89959 -2.09167 -4.36972 13.89959 -1.07734 4.36876 13.89959 -1.07734 -4.50048 13.89959 -4.2e-4 4.49952 13.89959 -4.2e-4 -4.36972 13.89959 1.0765 4.36876 13.89959 1.0765 -3.98503 13.89959 2.09083 3.98407 13.89959 2.09083 -3.36878 13.89959 2.98363 3.36782 13.89959 2.98363 -2.55677 13.89959 3.70301 2.55581 13.89959 3.70301 -1.59621 13.89959 4.20715 -0.5429 13.89959 4.46677 1.59524 13.89959 4.20715 0.54193 13.89959 4.46677 2.31715 10.5996 -7.13334 2.31714 10.59959 7.1325 0.78348 10.5996 -7.45934 0.78348 10.59959 7.45849 -0.78445 10.5996 -7.45934 -0.78445 10.59959 7.45849 -2.31811 10.5996 -7.13334 -2.31811 10.59959 7.1325 -3.75048 10.5996 -6.49561 -3.75048 10.59959 6.49477 -5.01896 10.59959 5.57317 -5.01896 10.5996 -5.57401 -6.06811 10.5996 -4.40881 -6.06811 10.59959 4.40797 -6.85207 10.5996 -3.05095 -6.85207 10.5996 3.0501 -7.33659 10.5996 1.55892 -7.33659 10.5996 -1.55976 -7.50048 10.5996 -4.2e-4 -7.33659 -10.60041 1.55892 -7.50049 -10.60041 -4.2e-4 -7.33659 -10.60041 -1.55976 -6.85208 -10.6004 -3.05095 -6.85208 -10.60041 3.0501 -6.06812 -10.60041 4.40797 -6.06811 -10.60041 -4.40881 -5.01897 -10.60041 -5.57401 -5.01897 -10.60041 5.57317 -3.75049 -10.60041 6.49477 -3.75048 -10.60041 -6.49561 -2.31811 -10.60041 7.1325 -2.31811 -10.60041 -7.13334 -0.78445 -10.60041 7.45849 -0.78445 -10.60041 -7.45934 0.78348 -10.60041 7.45849 0.78348 -10.60041 -7.45934 2.31714 -10.60041 7.1325 2.31714 -10.60041 -7.13334 -14.48772 7.22568 1.21112 -13.95641 7.52509 0.93113 -14.193 7.34965 1.09963 -13.90642 5.60705 -0.55767 -13.79636 3.38683 -1.54026 -13.62562 5.80287 -0.827 -13.37415 3.55958 -2.00872 -13.63172 7.84658 0.62766 -13.42834 6.02566 -1.14744 -13.47899 8.13542 0.34559 -13.59057 1.00859 -2.05556 -13.29065 0.9996 -2.43023 -13.81941 -3.37846 -1.5238 -14.03224 -5.53306 -0.46171 -13.55213 -0.99182 -2.09744 -13.25895 -1.00324 -2.49002 -13.38795 -3.54875 -1.98317 -13.58612 -5.8268 -0.86263 -14.26401 -7.32159 1.13379 -13.91214 -7.54561 0.91654 -13.62985 -7.86254 0.60894 -13.45037 -8.2021 0.28867 -13.43177 -8.35835 0.13871 -13.33815 -8.96163 6.94725 -14.02152 -9.256731 4.06271 -12.62189 -7.88431 7.72702 -13.6886 -9.47942 5.55454 -12.1722 -7.98916 7.62231 -12.79561 -9.12583 6.73785 -13.52762 -9.55666 3.80315 -13.12857 -9.800291 5.34117 -11.8059 -8.101981 7.60052 -12.36982 -9.381791 6.66783 -11.38435 -8.277211 7.68078 -12.05107 -9.64642 6.67054 -13.18897 -10.02901 3.50122 -12.6582 -10.25672 5.20334 -12.34419 -10.5004 5.65164 -13.10623 -10.46706 3.30983 -10.99744 -8.473811 7.83888 -11.76268 -9.969881 6.7357 -12.25473 -6.40498 7.99782 -11.72898 -6.4056 7.93281 -11.17216 -6.40683 8.02417 -10.64307 -6.40915 8.28321 -14.26038 9.15721 4.16294 -12.29217 6.40601 8.00338 -13.74552 9.47 5.58112 -12.55224 7.8933 7.70474 -13.03981 9.035881 6.8245 -13.85801 9.33975 3.9834 -13.33376 9.66441 5.42183 -12.56829 9.24682 6.69359 -13.50539 9.605481 3.77503 -11.92678 8.05235 7.58945 -13.02474 9.90194 5.30744 -11.80182 6.40682 7.9372 -12.21385 9.49928 6.66542 -13.26845 9.92961 3.56703 -11.1358 6.4057 8.03591 -13.11173 10.1875 3.41007 -11.28393 8.31322 7.69886 -10.73077 6.4059 8.22361 -12.64398 10.38079 5.24346 -11.84269 9.83655 6.69265 -12.47477 10.4996 5.26739 -10.75736 8.63854 8.05253 -24.88471 -9.35137 23.00377 -24.13114 -9.40305 23.00179 -23.38857 -9.26547 23.01383 -22.12126 -8.46693 23.0197 -22.70383 -8.94547 23.00735 -21.39638 -7.15635 23.02859 -21.67562 -7.85566 23.01203 -23.87215 -9.40192 20.17845 -23.19525 -9.38724 17.4733 -21.99669 -8.94589 18.29033 -20.99868 -7.85505 18.54457 -21.94929 -9.39938 14.24081 -20.17987 -8.94589 13.92521 -19.2654 -7.85505 14.39999 -19.93711 -9.40192 10.96064 -17.36017 -8.94589 10.12988 -16.57709 -7.85505 10.8007 -17.34748 -9.40192 8.119771 -13.71346 -8.96542 7.08199 -13.0499 -7.81858 7.94862 -14.23772 -9.38277 5.85688 -24.88455 9.349451 22.99273 -23.38881 9.26415 22.9985 -24.13438 9.40093 22.94129 -22.7051 8.94655 22.96461 -22.12062 8.466691 23.00962 -21.39598 7.15553 23.02449 -21.67454 7.85688 22.9857 -21.99899 8.94669 18.28904 -21.00004 7.85689 18.54399 -23.36385 9.40128 17.86201 -20.18188 8.94669 13.92356 -19.26665 7.85689 14.39923 -21.37263 9.40128 13.12622 -17.36185 8.94669 10.12793 -16.57822 7.85689 10.79978 -13.63308 8.92521 7.04131 -18.28204 9.40128 9.02243 -12.95601 7.82493 7.86842 -14.24571 9.39143 5.82465 -28.2954 7.1239 23.04268 -30.07768 4.28939 23.02099 -30.54342 2.67371 23.01016 -29.31952 5.79025 23.03187 -25.59235 9.09639 23.03309 -27.04103 8.24381 23.05341 -25.28474 9.108981 19.71424 -27.61936 7.12429 17.71068 -29.29788 4.28653 17.06409 -24.50582 9.108981 16.57668 -23.27924 9.108981 13.58126 -25.81796 7.12429 12.64688 -27.20717 4.28652 11.43173 -21.63284 9.108981 10.79699 -22.9747 7.12429 8.085841 -23.9124 4.28652 6.40789 -19.60074 9.108981 8.28056 -14.54596 9.10868 4.25243 -17.22583 9.108981 6.08501 -19.22128 7.12429 4.23888 -14.43425 5.40799 -0.30267 -14.7311 7.12708 1.28862 -19.57969 4.28652 2.24588 -14.20562 3.28901 -1.33376 -30.07768 -4.29019 23.02099 -29.31952 -5.79105 23.03187 -30.54342 -2.67451 23.01016 -28.29363 -7.12628 23.0427 -27.04103 -8.24461 23.05341 -25.60065 -9.11085 23.01348 -25.46428 -9.10979 20.96733 -25.15497 -9.10979 19.02628 -24.67524 -9.10978 17.1182 -27.61719 -7.12757 17.71145 -29.29673 -4.29047 17.06458 -25.81612 -7.12757 12.64832 -23.24655 -9.10978 13.51576 -27.20625 -4.29047 11.43263 -21.96199 -9.10978 11.28491 -20.42908 -9.10979 9.21762 -22.97337 -7.12757 8.087861 -23.91183 -4.29047 6.40911 -18.66796 -9.10979 7.34085 -16.70228 -9.10979 5.6798 -14.44149 -9.10329 4.22508 -19.22062 -7.12757 4.24131 -14.62641 -7.17487 1.26451 -14.47512 -5.33858 -0.21095 -19.57957 -4.29047 2.24733 -14.24722 -3.28159 -1.25828 -13.08897 10.47856 3.10286 -13.40044 10.4996 0.03299999 -13.40676 8.41941 0.07981997 -13.40044 -10.5004 0.03299999 -13.32003 -6.17464 -1.3695 -13.32796 6.2534 -1.48803 -13.2027 10.4996 -2.2943 -13.09723 3.74191 -2.54411 -13.05894 0.9996 -3.00666 -13.09158 -1.0005 -2.92509 -13.1902 -3.7053 -2.44498 -13.20271 -10.5004 -2.2943 -12.60386 10.4996 -4.55191 -12.60386 -10.5004 -4.55191 -11.62209 10.4996 -6.67124 -11.62209 -10.5004 -6.67124 -10.28724 10.4996 -8.587901 -10.28724 -10.5004 -8.587901 -8.63985 10.4996 -10.24366 -8.63985 -10.5004 -10.24366 -6.72998 10.4996 -11.58821 -6.72998 -10.5004 -11.58821 -4.61565 10.49959 -12.5807 -4.61565 -10.50041 -12.5807 -2.36111 10.49959 -13.19098 -2.3611 -10.50041 -13.19098 -0.03483998 10.49959 -13.40051 -0.03482997 -10.50041 -13.40051 2.29247 10.49959 -13.20291 2.29248 -10.50041 -13.20291 2.15348 10.49959 13.2252 2.15348 -10.50041 13.2252 -0.07687997 10.49959 13.39923 -0.07688999 -10.50041 13.39923 -2.30523 10.49959 13.19976 -2.30524 -10.50041 13.19976 -4.46929 10.49959 12.63234 -4.4693 -10.50041 12.63233 -6.50868 10.49959 11.71284 -6.50869 -10.50041 11.71283 -8.36659 10.49959 10.46694 -8.36661 -10.50041 10.46692 -11.33783 10.4996 7.14268 -10.58126 8.767041 8.21934 -9.991291 10.4996 8.92939 -11.34845 -10.49318 7.12164 -10.66137 -8.7071 8.120631 -10.28659 -6.40669 8.60038 -10.25925 6.40596 8.62536 -9.991311 -10.5004 8.92937 -4.9e-4 -15.4004 -7.50042 1.46269 -15.4004 -7.35631 -1.46366 -15.4004 -7.35631 2.86964 -15.4004 -6.92952 -2.87061 -15.4004 -6.92952 4.16629 -15.40041 -6.23644 -4.16726 -15.4004 -6.23644 5.30282 -15.40041 -5.30372 -5.30379 -15.4004 -5.30372 6.23554 -15.40041 -4.1672 -6.23651 -15.4004 -4.1672 6.92861 -15.40041 -2.87055 -6.92958 -15.4004 -2.87055 7.3554 -15.40041 -1.4636 -7.35638 -15.4004 -1.4636 7.49951 -15.40041 -4.2e-4 -7.50049 -15.4004 -4.2e-4 7.3554 -15.40041 1.46276 -7.35638 -15.4004 1.46276 6.92861 -15.40041 2.86971 -6.92958 -15.4004 2.86971 6.23553 -15.40041 4.16636 -6.23651 -15.40041 4.16636 5.30281 -15.40041 5.30288 -5.30379 -15.40041 5.30288 4.16629 -15.40041 6.2356 -4.16727 -15.40041 6.2356 2.86964 -15.40041 6.92868 -2.87061 -15.40041 6.92868 -1.46367 -15.40041 7.35547 -4.9e-4 -15.40041 7.49958 1.46269 -15.40041 7.35547 -4.8e-4 15.39959 7.49958 1.46269 15.39959 7.35547 -1.46366 15.39959 7.35547 2.86964 15.39959 6.92868 -2.87061 15.39959 6.92868 4.16629 15.39959 6.2356 -4.16726 15.39959 6.2356 5.30282 15.39959 5.30288 -4.8e-4 15.39959 4.49958 -5.30378 15.39959 5.30288 1.00086 15.39959 4.38676 -1.00183 15.39959 4.38676 6.23554 15.39959 4.16636 1.95199 15.39959 4.05394 -1.95296 15.39959 4.05394 -6.23651 15.39959 4.16636 -2.80619 15.39959 3.51782 -3.51872 15.39959 2.80528 -6.92958 15.39959 2.86971 -4.05484 15.39959 1.95206 -4.38766 15.39959 1.00093 -7.35637 15.39959 1.46276 -4.50048 15.39959 -4.2e-4 -7.50048 15.39959 -4.2e-4 -4.38766 15.39959 -1.00176 -4.05484 15.39959 -1.9529 -7.35637 15.39959 -1.4636 -3.51872 15.39959 -2.80612 -2.80619 15.39959 -3.51866 -6.92958 15.3996 -2.87055 1.952 15.39959 -4.05478 -1.95296 15.39959 -4.05478 1.00086 15.39959 -4.3876 -4.8e-4 15.39959 -4.50042 -1.00182 15.39959 -4.3876 -6.2365 15.39959 -4.1672 5.30282 15.39959 -5.30372 -5.30378 15.39959 -5.30372 4.1663 15.39959 -6.23644 -4.16726 15.39959 -6.23644 2.86965 15.39959 -6.92952 -2.87061 15.39959 -6.92952 -1.46366 15.39959 -7.35631 -4.8e-4 15.39959 -7.50042 1.4627 15.39959 -7.35631 -21.30162 -6.4075 23.03941 -21.30144 6.40653 23.02324 -21.05293 -6.40666 20.48503 -21.05293 6.40585 20.48503 -20.45402 -6.40666 18.02602 -20.45402 6.40585 18.02602 -19.51434 -6.40666 15.67261 -19.51434 6.40585 15.67261 -18.2539 -6.40666 13.47585 -18.2539 6.40585 13.47586 -16.69758 -6.40666 11.47834 -16.69758 6.40585 11.47835 -14.87602 -6.40666 9.71929 -12.82573 -6.40666 8.23382 -14.87602 6.40585 9.71929 -12.82573 6.40585 8.23383 -30.41643 -1.0004 19.5347 -29.69563 0.9996 16.13403 -28.54962 0.9996 12.85194 -26.99694 0.9996 9.741621 -26.99669 -1.0004 9.74117 -25.06267 0.9996 6.8532 -25.06223 -1.0004 6.85262 -22.77773 0.9996 4.23294 -22.77734 -1.0004 4.23257 -20.17892 0.9996 1.92327 -20.17875 -1.0004 1.92313 -17.30873 0.9996 -0.03816998 -14.21282 0.9996 -1.62019 -17.30859 -1.0004 -0.03824996 -14.21282 -1.0004 -1.62019 -30.69927 0.99943 23.04174 -30.70291 -1.00075 23.02165 -30.41645 0.9996 19.5349 -29.69556 -1.0004 16.13377 -28.54948 -1.0004 12.85162 35.56442 -1.00041 18.82635 35.8996 1.00018 23.02512 35.89865 -1.0003 23.04285 35.60408 0.99999 18.94442 34.68587 -1.00041 14.73265 34.68535 0.99959 14.73082 33.27864 -1.00041 10.78832 33.2779 0.99959 10.78664 31.36698 -1.00041 7.06207 31.36615 0.99959 7.0607 28.98425 -1.00041 3.61868 28.98302 0.99959 3.61714 26.1713 -1.00041 0.51695 26.16953 0.99959 0.51526 22.97604 -1.00041 -2.19013 22.97423 0.99959 -2.19147 19.453 -1.00041 -4.45602 19.45189 0.99959 -4.45665 15.66376 -1.00041 -6.24092 15.66357 0.99959 -6.24101 11.64083 -0.99333 -7.51363 11.67386 0.99959 -7.51412 26.49701 -6.4079 23.00487 26.50031 6.4068 23.03065 26.24158 -6.40714 20.03259 26.24143 6.40632 20.03162 25.5942 -6.40714 17.12513 25.59365 6.40632 17.12325 24.5692 -6.40714 14.32965 24.56801 6.40632 14.32697 23.18434 -6.40714 11.6939 23.18226 6.40632 11.69051 21.45901 -6.40714 9.25799 21.45568 6.40632 9.2539 19.4443 -6.40714 7.08838 19.44081 6.40632 7.08509 17.34859 -6.40714 5.33769 17.34648 6.40632 5.33613 15.28735 6.40805 3.98648 15.28216 -6.40734 3.98093 6.23554 15.39959 -4.1672 2.80522 15.39959 -3.51866 6.92861 15.39959 -2.87055 3.51776 15.39959 -2.80612 4.05388 15.39959 -1.9529 7.35541 15.39959 -1.4636 4.38669 15.39959 -1.00176 4.49952 15.39959 -4.2e-4 7.49952 15.39959 -4.2e-4 4.38669 15.39959 1.00093 7.35541 15.39959 1.46276 4.05388 15.39959 1.95206 3.51776 15.39959 2.80528 6.92861 15.39959 2.86971 2.80522 15.39959 3.51782 4.3237 -10.50041 12.68256 4.32371 10.49959 12.68256 6.37333 -10.50041 11.7865 6.37333 10.49959 11.78649 8.245261 -10.50041 10.56201 8.24527 10.49959 10.562 9.88738 -10.50041 9.04324 9.88738 10.49959 9.04324 11.25394 -10.50041 7.27254 11.25394 10.49959 7.27254 12.30691 -10.50041 5.29925 12.30692 10.49959 5.29925 12.48335 -6.40739 4.90258 12.71416 -9.07247 4.22862 12.43964 6.40632 4.97975 12.68775 9.13363 4.25919 13.25704 10.50525 2.32517 13.18964 -10.50041 -2.36255 12.5794 -10.50041 -4.61647 12.89855 -9.67272 -3.62335 12.57939 10.49959 -4.61647 13.18965 10.49959 -2.36255 12.88448 9.63719 -3.66647 12.21337 7.94797 -5.5056 11.58678 -10.50041 -6.73074 12.21218 -7.94114 -5.51293 11.58677 10.49959 -6.73074 11.51189 -6.06881 -6.85762 11.51664 6.08266 -6.85008 10.24212 -10.50041 -8.64053 10.67074 0.99921 -8.11293 10.66506 -1.0003 -8.111411 10.83492 -3.55577 -7.89054 10.88949 3.53806 -7.81976 10.24211 10.49959 -8.640541 8.58626 -10.50041 -10.28782 8.58625 10.49959 -10.28783 6.66952 -10.50041 -11.62256 6.66951 10.49959 -11.62256 4.55013 -10.50041 -12.6042 4.55012 10.49959 -12.6042 35.67098 -2.91176 23.41162 35.10701 -4.69323 24.05084 34.51861 -5.79096 22.99116 32.2402 -8.244521 23.00877 30.79715 -9.11441 22.99093 33.49187 -7.12698 22.99789 30.45738 -9.11051 19.15825 32.7948 -7.12707 17.0692 34.4615 -4.29016 16.35134 29.44318 -9.13203 15.4273 30.91869 -7.12707 11.40214 32.2547 -4.29016 10.0384 27.71212 -9.11051 10.95918 27.94042 -7.12707 6.22863 26.26256 -9.11051 8.52879 28.75688 -4.29016 4.33854 24.5623 -9.11051 6.26149 22.66412 -9.11051 4.21714 23.98184 -7.12707 1.7604 24.1278 -4.29015 -0.48793 20.6717 -9.11051 2.46631 18.69316 -9.1105 1.036 19.20498 -7.12707 -1.81966 16.78089 -9.1105 -0.1073 18.57887 -4.29015 -4.22057 14.85429 -9.11536 -1.01545 14.19183 -8.09903 -3.02073 13.46651 -6.7545 -4.84491 11.8847 -3.19872 -7.2078 12.61154 -4.96985 -6.2913 35.27751 4.28659 23.01634 34.51856 5.7902 23.02481 33.49437 7.12394 23.03323 32.24012 8.24375 23.04163 30.79967 9.110361 23.00775 32.80304 7.1241 17.09722 30.54383 9.109681 19.72866 34.46772 4.2864 16.37301 29.90321 9.109681 16.56613 30.92986 7.1241 11.42224 28.88781 9.109681 13.50447 32.26332 4.2864 10.0539 27.51255 9.109681 10.58758 27.95177 7.1241 6.24101 25.79234 9.109681 7.85021 28.76567 4.2864 4.34804 23.75453 9.109681 5.33895 23.99086 7.1241 1.76602 21.51544 9.109681 3.16539 24.1347 4.2864 -0.48361 19.20959 7.12411 -1.81921 19.24568 9.109681 1.4082 17.04753 9.10969 0.03940999 18.58228 4.2864 -4.22007 13.79232 7.10996 -4.35238 14.33083 8.00472 -3.01229 14.93884 9.10969 -1.0176 11.98112 3.17161 -7.16036 12.80422 5.00471 -6.2741 29.33309 9.40134 22.94975 30.08383 9.35425 22.99638 26.59515 7.15561 23.01965 26.87466 7.85676 23.00244 26.29238 7.85724 18.31521 27.27739 8.94702 18.00122 27.31973 8.46639 23.00948 27.90369 8.94572 22.99972 28.63104 9.401721 17.51563 28.58735 9.264551 23.00108 24.77109 7.85724 13.86825 25.63348 8.94702 13.27911 26.77773 9.401721 12.35932 22.37364 7.85724 9.8257 23.04388 8.94702 9.001871 23.85976 9.401721 7.72165 19.2011 7.85724 6.358 19.62173 8.94702 5.35638 20.01346 9.401721 3.81929 15.3507 7.89198 3.53765 15.50805 9.08422 2.16505 15.18956 9.39706 0.20453 29.33042 -9.4073 22.97453 26.87267 -7.85526 22.99909 26.29455 -7.85542 18.33118 27.31945 -8.467781 23.01072 27.9018 -8.946081 22.98559 27.27926 -8.94623 18.02046 28.13668 -9.43483 15.7114 28.58736 -9.266 22.99869 24.77486 -7.85542 13.87991 25.63741 -8.94623 13.29348 25.54921 -9.40238 10.13518 22.37741 -7.85541 9.83324 23.04801 -8.94623 9.01154 22.76218 -9.40238 6.4319 19.20344 -7.85541 6.36204 19.62439 -8.94623 5.36206 19.34743 -9.40238 3.29801 15.38655 -7.90337 3.56958 15.48328 -9.08043 2.1748 15.21953 -9.384651 0.2024199 12.71159 -6.40639 4.50438 12.74383 6.40694 4.46699 13.11625 -6.40706 4.10916 13.17147 6.40534 4.06695 13.67181 -6.40729 3.82388 13.63432 6.40488 3.83865 14.16679 -6.40621 3.72869 14.16567 6.40517 3.73141 14.74828 -6.40559 3.77486 14.7899 6.40795 3.78526 12.58938 6.40624 4.72038 12.84993 8.843191 3.96175 13.47079 10.08159 2.14671 13.19677 8.554611 3.61157 13.6924 10.33885 0.1000699 13.5716 8.34648 3.40352 13.86713 9.62944 2.02199 13.98212 8.18787 3.28635 14.07981 9.873641 0.14741 14.3156 9.33661 1.97631 14.40984 8.07622 3.25155 14.5078 6.40489 3.75358 14.52968 9.59005 0.18204 14.90134 9.13856 1.99861 14.85833 8.01625 3.30744 14.85845 9.46198 0.1954799 13.48269 10.32783 -1.34628 13.95208 9.60692 -1.10757 14.66569 9.186861 -1.01369 12.93925 9.414831 -3.53728 12.36359 7.69195 -5.23325 13.11882 9.013441 -3.32705 13.65545 9.95317 -1.21632 11.6097 5.81624 -6.70498 12.71295 7.44038 -4.91488 13.41292 8.650071 -3.17383 11.93168 5.52365 -6.44411 10.94455 0.99738 -7.8714 11.28216 3.39613 -7.4388 13.14305 7.23847 -4.66389 13.77247 8.351241 -3.08141 14.29804 9.36786 -1.04865 12.3159 5.2704 -6.28185 11.73384 3.19752 -7.16874 11.35846 0.99781 -7.62773 14.1886 8.09826 -3.03375 10.90901 -0.99577 -7.89165 11.23977 -0.99918 -7.68268 13.55432 -10.50586 -0.44094 12.95099 -9.373721 -3.50425 12.34374 -7.74751 -5.26691 13.12794 -9.02062 -3.3248 11.63522 -5.80562 -6.6877 12.61567 -7.37134 -5.02173 13.92358 -9.639 -1.11594 13.37768 -8.697481 -3.18544 11.02792 -3.5286 -7.64708 11.90387 -5.55691 -6.4636 14.30893 -9.34458 -1.04496 13.69316 -8.41773 -3.09304 11.3741 -3.36257 -7.37211 13.06867 -6.99306 -4.85521 12.23053 -5.32839 -6.30559 13.73215 -10.26075 0.11352 13.65034 -9.95749 -1.21899 14.04955 -9.92929 0.1506299 14.42913 -9.63355 0.17846 14.8779 -9.45857 0.19826 12.846 -8.85458 3.98163 13.32162 -10.49276 2.06913 13.0887 -8.63163 3.70309 12.92298 -6.40751 4.29738 13.47838 -10.08774 2.15254 13.44063 -8.41393 3.4698 13.38458 -6.40547 3.96435 13.77817 -9.70742 2.0413 13.80434 -8.24599 3.32269 14.08722 -9.47522 1.99617 14.36399 -8.07932 3.24406 14.45476 -9.2713 1.97544 14.96485 -9.129341 2.00828 14.97332 -8.007201 3.33362 7.49951 -10.60041 -4.2e-4 7.33562 -10.60041 -1.55976 6.85111 -10.60041 -3.05095 6.8511 -10.60041 3.0501 7.33562 -10.60041 1.55892 6.06714 -10.60041 4.40797 6.06714 -10.60041 -4.40881 5.01799 -10.60041 -5.57401 5.01799 -10.60041 5.57317 3.74951 -10.60041 6.49477 3.74952 -10.60041 -6.49561 3.74952 10.59959 -6.49561 3.74952 10.59959 6.49477 5.018 10.59959 -5.57401 5.018 10.59959 5.57317 6.06715 10.59959 -4.40881 6.06714 10.59959 4.40797 6.85111 10.59959 3.0501 6.85111 10.59959 -3.05095 7.33562 10.59959 -1.55976 7.49952 10.59959 -4.2e-4 7.33562 10.59959 1.55892 13.44627 10.50242 -0.01868999 35.69546 3.05739 23.43314 -25.69792 -8.06854 26.52259 -26.35478 -8.04488 26.51994 -25.26371 -8.17598 26.64023 -24.16 -9.02968 27.71689 -24.455 -8.67075 27.23014 -24.83796 -8.378931 26.87214 -24.45243 8.67238 27.23327 -24.16008 9.02875 27.71671 -24.83342 8.38089 26.8754 -25.25692 8.17761 26.64293 -25.69196 8.06858 26.52351 -26.35262 8.04343 26.51944 30.89098 -8.0694 26.52353 31.55164 -8.04425 26.51945 30.45594 -8.178421 26.64295 30.03244 -8.381711 26.87541 29.65145 -8.6732 27.23329 29.35909 -9.02957 27.71672 29.35902 9.02887 27.7169 29.65402 8.66993 27.23016 30.03698 8.37811 26.87215 30.46273 8.17516 26.64024 30.89694 8.06772 26.5226 31.5538 8.04406 26.51995 30.30964 -9.28881 26.71105 29.51329 -9.40195 27.42233 29.85156 -9.38048 27.02176 29.21206 -9.39401 28.27592 29.30267 -9.39645 27.86289 28.81621 -9.33038 28.16568 28.36078 -9.18566 27.93929 27.89046 -8.94547 27.58514 27.52685 -8.66804 27.22668 27.16869 -8.30602 26.77394 26.87688 -7.86445 26.30823 26.71915 -7.53458 25.98483 26.60021 -7.17856 25.66446 26.52537 -6.80088 25.35357 -25.11475 -9.28649 26.70846 -24.73201 -9.37661 26.9533 -24.45204 -9.39816 27.23272 -24.18235 -9.39973 27.66239 -24.01589 -9.3831 28.21809 -23.61292 -9.32953 28.16398 -23.27349 -9.22654 28.00972 -22.92326 -9.07597 27.77525 -22.57237 -8.860071 27.47989 -22.32934 -8.669341 27.22835 -22.09323 -8.43956 26.94403 -21.87564 -8.17419 26.63824 -21.68406 -7.87555 26.3196 -21.52446 -7.54521 25.99483 -21.40323 -7.1862 25.67105 -21.32681 -6.80432 25.35626 30.31377 9.28566 26.70846 29.93103 9.37579 26.95331 29.65106 9.39735 27.23273 29.38137 9.39891 27.6624 29.21495 9.38221 28.21792 28.80724 9.32764 28.16212 28.46433 9.22273 28.00512 28.10902 9.06841 27.76509 27.75194 8.84543 27.46115 27.5048 8.64778 27.20188 27.26728 8.411271 26.91131 27.05169 8.14141 26.60291 26.8649 7.84184 26.28602 26.64308 7.35032 25.80266 26.52453 6.79367 25.34855 -25.11072 9.287981 26.71104 -24.31433 9.40116 27.42237 -24.65256 9.37968 27.02179 -24.01304 9.3932 28.27591 -24.10299 9.39558 27.86508 -23.61179 9.328471 28.16351 -23.15257 9.18113 27.93344 -22.80202 9.00596 27.68408 -22.55539 8.84721 27.46354 -22.30408 8.64627 27.19994 -22.06303 8.40544 26.90438 -21.8458 8.13166 26.59218 -21.57421 7.67631 26.10763 -21.39569 7.15675 25.64643 -21.32504 6.79 25.34565 -25.60049 9.1107 26.53998 -26.06235 8.87196 26.50053 -26.53616 8.59014 26.57264 -26.98871 8.282091 26.76077 -27.9384 7.48716 25.94127 -28.70745 6.64783 25.23596 -29.35557 5.73244 24.61157 -29.90789 4.69264 24.05094 -30.33595 3.53512 23.58323 -30.60797 2.28678 23.23998 30.79951 9.110691 26.53999 31.73488 8.59032 26.57257 31.26123 8.87203 26.50054 32.18773 8.28208 26.76079 33.13742 7.48715 25.94128 33.90647 6.64782 25.23597 34.55459 5.73243 24.61159 35.10691 4.69263 24.05095 30.79951 -9.11152 26.54 31.26137 -8.87278 26.50054 31.73518 -8.59096 26.57266 32.18773 -8.28291 26.76079 33.13676 -7.48862 25.94187 33.90627 -6.6489 25.23616 34.55468 -5.7331 24.6115 -25.60049 -9.11151 26.53998 -26.53586 -8.591131 26.57256 -26.06221 -8.87285 26.50052 -26.98871 -8.2829 26.76077 -27.93774 -7.48861 25.94185 -28.70725 -6.64889 25.23615 -29.35566 -5.73309 24.61148 -29.90799 -4.69322 24.05083 -30.33597 -3.53584 23.5832 -30.70049 10.98821 34.50007 -30.70049 10.88394 32.40859 -30.70049 10.69424 36.57342 -30.70049 10.3852 30.37476 -30.7005 10.01268 38.55349 -30.70049 9.51008 28.4723 -30.7005 8.96824 40.36852 -30.70049 8.29029 26.77015 -30.7005 7.59876 41.95273 -30.70049 6.77003 25.33001 -30.7005 5.95388 43.24871 -30.70049 5.0044 24.20407 -30.7005 4.0932 44.20949 -30.70049 3.0574 23.43312 -30.7005 2.08417 44.80024 -30.7005 -4e-4 44.99957 -30.7005 -2.08498 44.80024 -30.70049 -3.0582 23.43312 -30.7005 -4.09401 44.20949 -30.70049 -5.00521 24.20407 -30.7005 -5.95468 43.24871 -30.70049 -6.77083 25.33001 -30.7005 -7.59957 41.95274 -30.70049 -8.29109 26.77015 -30.7005 -8.96904 40.36852 -30.70049 -9.51088 28.4723 -30.7005 -10.01348 38.5535 -30.70049 -10.386 30.37476 -30.70049 -10.88474 32.40859 -30.70049 -10.69504 36.57343 -30.70049 -10.98901 34.50008 -21.30049 6.407 25.05836 -21.30049 -6.40781 25.05836 -21.30049 7.955 26.40277 -21.30049 -7.95582 26.40277 -21.30049 9.226611 28.01107 -21.30049 -9.22742 28.01107 -21.30049 10.17766 29.8274 -21.30049 -10.17846 29.8274 -21.30049 10.77512 31.78865 -21.30049 -10.77592 31.78866 -21.30049 10.99824 33.82669 -21.30049 -10.99904 33.82669 -21.30049 10.83929 35.87072 -21.30049 -10.84009 35.87072 -21.30049 10.30379 37.84973 -21.30049 -10.30459 37.84973 -21.30049 9.41035 39.69498 -21.30049 -9.41116 39.69498 -21.30049 8.19002 41.34239 -21.30049 -8.190831 41.34239 -21.30049 6.68519 42.73472 -21.30049 -6.686 42.73473 -21.30049 4.94813 43.82362 -21.30049 -4.94894 43.82363 -21.3005 3.03919 44.57127 -21.3005 1.02466 44.95171 -21.3005 -3.04 44.57127 -21.3005 -1.02547 44.95171 26.4995 1.02465 44.95172 26.4995 -1.02548 44.95172 26.4995 3.03918 44.57128 26.4995 -3.04001 44.57129 26.49951 4.94812 43.82364 26.49951 -4.94895 43.82364 26.49951 6.68518 42.73473 26.49951 -6.68601 42.73474 26.49951 8.190011 41.3424 26.49951 -8.19084 41.3424 26.49951 9.41034 39.69499 26.49951 -9.41117 39.695 26.49951 10.30378 37.84974 26.49951 -10.3046 37.84974 26.49951 10.83928 35.87073 26.49951 -10.8401 35.87073 26.49951 10.99823 33.8267 26.49951 -10.99905 33.82671 26.49951 10.77511 31.78867 26.49951 -10.77593 31.78867 26.49951 10.17765 29.82741 26.49951 -10.17847 29.82741 26.49951 9.226611 28.01108 26.49951 -9.22743 28.01108 26.49951 7.955 26.40278 26.49951 -7.95582 26.40278 26.49951 6.40699 25.05838 26.49951 -6.40781 25.05838 35.89951 10.9882 34.50008 35.89951 10.88393 32.4086 35.89951 10.69423 36.57343 35.89951 10.38519 30.37477 35.89951 10.01267 38.55351 35.89951 9.51007 28.47231 35.89951 8.968231 40.36853 35.89951 8.29028 26.77017 35.89951 7.59875 41.95275 35.89951 6.77002 25.33003 35.89951 5.95387 43.24872 35.89951 5.00439 24.20408 35.89951 4.09319 44.20951 35.89951 3.05739 23.43314 35.89951 2.08416 44.80026 35.89951 -4.1e-4 44.99959 35.89951 -2.08499 44.80026 35.89951 -3.05821 23.43314 35.89951 -4.09402 44.20951 35.89951 -5.00522 24.20408 35.89951 -5.9547 43.24872 35.89951 -6.77085 25.33003 35.89951 -7.59958 41.95275 35.89951 -8.2911 26.77017 35.89951 -8.96905 40.36853 35.89951 -9.51089 28.47231 35.89951 -10.01349 38.55351 35.89951 -10.38601 30.37477 35.89951 -10.88475 32.4086 35.89951 -10.98902 34.50009 35.89951 -10.69505 36.57344 -30.60796 -2.28766 23.24 + + + + + + + + + + 0.00350815 -0.9998577 0.01650494 0 -0.9998584 0.0168308 -0.8861943 0.4484995 -0.1162241 -0.7887651 0.6065123 -0.09996247 -0.838851 0.5271334 -0.135865 -0.6572538 0.7376483 -0.1545717 -0.5071755 0.8607322 -0.04374182 -0.00723499 -0.9998553 -0.01540267 -0.009790718 -0.9998555 -0.01390749 -0.009951591 -0.9998568 -0.01369655 -0.0120958 -0.9998545 -0.01203477 -0.01357299 -0.9998632 -0.009452879 -0.01317262 -0.999843 -0.01186043 -0.01514619 -0.9998607 -0.007015526 -0.01510882 -0.9998479 -0.008716523 -0.01625812 -0.9998585 -0.004312992 -0.01637899 -0.9998518 -0.005328536 -0.01682484 -0.999857 -0.001767635 -0.01695668 -0.9998553 -0.001440644 -0.01693838 -0.999855 0.001779556 -0.01948839 -0.9997391 0.01192146 -0.02103269 -0.9997555 0.006833195 -0.02161514 -0.9997406 -0.007198333 -0.01202285 -0.9998426 0.01305478 -0.01565819 -0.9998366 0.009039998 -0.01613229 -0.999837 0.008118152 -0.01250839 -0.9998584 0.01126235 -0.01174086 -0.9998542 0.01240038 -0.00939244 -0.9998579 0.01400572 -0.01005852 -0.9998537 0.01384472 -0.006976544 -0.9998559 0.01547336 -0.00939238 0.9998579 0.01400589 -0.01173341 0.9998543 0.01240563 -0.01250588 0.9998584 0.01126009 -0.01363784 0.9998542 0.01027768 -0.01459485 0.9998579 0.008432984 -0.01435142 0.9998592 0.008700788 -0.0194388 0.9998022 -0.004202723 -0.01934993 0.999793 0.006287813 -0.01868921 0.9997872 0.008748412 -0.01693677 0.999855 0.001779913 -0.01695501 0.9998552 -0.001440107 -0.01682329 0.999857 -0.001768827 -0.01649671 0.9998544 -0.004375696 -0.0160247 0.9998582 -0.005206704 -0.01550859 0.999854 -0.007184088 -0.01457482 0.9998584 -0.008414924 -0.01402395 0.999854 -0.009766757 -0.01252645 0.999858 -0.01127904 -0.01209461 0.9998545 -0.0120331 -0.009751021 0.9998566 -0.01385134 -0.9592655 0 -0.2825061 -0.9585492 0.004022836 -0.2848988 -0.9578792 0 -0.2871714 -0.907369 0 -0.4203348 -0.9073691 0 -0.4203347 -0.9665573 -0.005717277 -0.2563872 -0.4637726 -0.3606431 -0.8092291 -0.4531846 -0.5353585 -0.7127517 -0.9967604 0.002623558 -0.08038651 -0.9922292 -0.09399092 -0.0815289 -0.9471392 -0.2741383 -0.1666598 -0.9966421 -2.18064e-6 -0.08188188 -0.9782678 1.31677e-5 -0.2073454 -0.1818892 -0.981073 -0.06642472 -0.1683539 -0.9834628 -0.06676733 -0.9782656 -8.77827e-6 -0.2073558 -0.9441022 1.02054e-5 -0.3296529 -0.9440979 -1.5362e-5 -0.3296655 0.9952941 1.08613e-4 0.09690004 0.9952412 0 0.09744167 0.9715976 0 0.2366393 0.9715974 0 0.2366398 0.9287056 0 0.3708179 0.2079085 -0.008425295 -0.978112 0.09801393 0.00749123 -0.9951569 0 -0.008558034 -0.9999634 -0.09801393 0.007491409 -0.9951568 -0.2079097 -0.008425056 -0.9781118 -0.2902754 0.007221221 -0.9569159 -0.4067223 -0.008025169 -0.9135166 -0.4713894 0.006686806 -0.8818999 -0.5877675 -0.007354557 -0.8089966 -0.6343831 0.005885124 -0.7729964 -0.7431297 -0.006417155 -0.6691167 -0.773001 0.004814386 -0.6343864 -0.8660139 -0.005213677 -0.4999928 -0.881914 0.003475725 -0.4713974 -0.9510494 -0.00374341 -0.3090164 -0.9569393 0.001871824 -0.2902821 -0.9945201 -0.002004384 -0.1045261 -0.9951848 0 -0.0980165 -0.3302282 -0.01785123 0.9437324 -0.2392624 0.02142524 0.9707186 -0.1119418 -0.01874649 0.9935379 0 0.02186822 0.9997609 0.1119421 -0.01874727 0.9935379 0.2392645 0.02142429 0.970718 0.3302282 -0.01785123 0.9437324 0.4646253 0.02008414 0.8852797 0.5319637 -0.0160681 0.8466148 0.6630181 0.01785045 0.7483906 0.7070486 -0.01339 0.7070382 0.8228966 0.01472157 0.5680004 0.8466804 -0.009813487 0.5320113 0.9349611 0.01070916 0.3545886 0.9438694 -0.005353271 0.3302758 0.9927091 0 0.1205348 0.9936934 0.006243646 0.1119581 0.9937129 0 -0.1119592 0.9926924 0.005800187 -0.1205328 0.9438682 -0.005350887 -0.3302791 0.934961 0.01070976 -0.354589 0.8466803 -0.009813427 -0.5320115 0.8228967 0.01472151 -0.5680004 0.7070484 -0.01339 -0.7070384 0.6630188 0.01785051 -0.74839 0.5319623 -0.01606804 -0.8466156 0.4646296 0.02008199 -0.8852775 0.3302319 -0.0178529 -0.943731 0.2392618 0.02142506 -0.9707188 0.1119404 -0.01874685 -0.9935382 0 0.02186822 -0.9997609 -0.1119412 -0.01874649 -0.993538 -0.2392618 0.02142506 -0.9707188 -0.3302319 -0.0178529 -0.943731 0 1 -1.35444e-5 0 1 0 0 1 2.96005e-6 0 1 -4.14879e-6 0 1 3.14863e-6 0 1 -2.53703e-6 0 1 -1.88769e-6 0 1 3.44298e-6 0 1 -1.62144e-6 0 1 -1.57432e-6 0 1 1.57432e-6 0 1 1.62144e-6 0 1 -1.72149e-6 0 1 2.53703e-6 0 1 -3.14863e-6 0 1 4.14879e-6 0 1 -4.74188e-6 0 1 4.60399e-6 -0.9945222 0 0.1045263 -0.9951825 -0.002137541 0.09801632 -0.9569393 0.001871824 0.290282 -0.9510488 -0.003744125 0.3090184 -0.881917 0.003474175 0.4713919 -0.8660154 -0.005215585 0.4999902 -0.7729975 0.004813015 0.6343908 -0.7431295 -0.006417274 0.6691169 -0.6343833 0.005885064 0.7729963 -0.5877676 -0.007354617 0.8089964 -0.4713899 0.006686747 0.8818997 -0.4067223 -0.008025228 0.9135166 -0.2902748 0.007221162 0.9569162 -0.2079044 -0.008426129 0.9781129 -0.09801375 0.007489383 0.9951569 0 -0.008560061 0.9999634 0.09801441 0.007489264 0.9951568 0.2079045 -0.008426129 0.9781129 0.003504931 0.9998579 -0.01648938 0.00350815 0.9998577 0.01650536 0.001445889 0.999854 -0.01702976 0.001328229 0.9998542 0.01702266 0 0.9998584 -0.01683098 0 0.9998584 0.01683038 -0.001533389 0.999854 -0.01702469 -0.003503561 0.9998581 -0.01648247 -0.001522779 0.9998542 0.01701128 -0.004323303 0.9998548 0.01648855 -0.003504395 0.999858 0.01648741 -0.004459738 0.9998544 -0.01647555 -0.00688076 0.999857 -0.01545435 -0.006893575 0.9998564 0.01548337 -0.006976544 0.9998559 0.0154733 -0.007226884 0.9998553 -0.01540541 -0.0100097 0.9998551 -0.01377695 -0.01005852 0.9998537 0.01384472 0.2079044 0.008426129 0.9781129 0.09801375 -0.007489383 0.9951569 0 0.008560061 0.9999635 -0.09801369 -0.007489144 0.9951569 -0.2079043 0.008426547 0.9781129 -0.2902768 -0.007220864 0.9569156 -0.4067199 0.00802493 0.9135177 -0.4713869 -0.006687045 0.8819012 -0.5877676 0.007354617 0.8089964 -0.6343833 -0.005884826 0.7729963 -0.7431295 0.006417155 0.6691169 -0.773001 -0.004814207 0.6343865 -0.8660156 0.005213618 0.4999901 -0.8819171 -0.003476142 0.4713918 -0.9510506 0.003742396 0.3090127 -0.9569375 -0.001869976 0.2902883 -0.9945195 0.002005875 0.1045324 -0.9951848 0 0.09801644 -0.9945215 0 -0.1045327 -0.9951826 0.002139151 -0.09801626 -0.9569374 -0.001870036 -0.2902882 -0.9510512 0.003741919 -0.3090107 -0.8819172 -0.003476977 -0.4713918 -0.8660111 0.00521481 -0.4999976 -0.7730011 -0.004812657 -0.6343864 -0.7431327 0.006417691 -0.6691133 -0.6343798 -0.005885183 -0.7729991 -0.5877645 0.00735408 -0.8089988 -0.4713893 -0.006686806 -0.8819 -0.4067223 0.008025169 -0.9135167 -0.2902754 -0.007221221 -0.9569159 -0.2079097 0.008425056 -0.9781118 -0.09801459 -0.00749129 -0.9951568 0 0.008558034 -0.9999634 0.09801393 -0.007491409 -0.9951569 0.2079098 0.008425056 -0.9781118 -0.004282891 -0.9998657 -0.01582223 -0.004323363 -0.9998548 0.01648819 -0.006893515 -0.9998565 0.01548361 -0.00732547 -0.9998379 -0.0164535 -0.003504395 -0.999858 0.016487 -0.001485705 -0.9998629 -0.01649475 -0.003675758 -0.9998438 -0.01729327 -0.001522779 -0.9998542 0.01701158 0 -0.9998584 -0.01682955 0.001328229 -0.9998543 0.01702272 0.00144577 -0.999854 -0.01702809 0.003504574 -0.999858 -0.01648753 -0.2984481 0.8019328 -0.5175254 -0.4554609 0.7606101 -0.4626312 -0.4857169 0.7481086 -0.4521201 -0.5264675 0.7271069 -0.4406218 -0.7051679 0.6192191 -0.345407 -0.6872929 0.6338862 -0.3547065 -0.7934599 0.5442967 -0.2723283 -0.8500958 0.4735066 -0.2304971 -0.9247553 0.3549501 -0.1372517 -0.8854649 0.4281756 -0.1806033 -0.9751008 0.2196887 -0.03025478 -0.9935533 0.1093322 0.02997362 -0.9948747 0.005295991 0.100977 -0.4491389 0.5639278 -0.6930078 -0.4871312 0.3390627 -0.8048229 -0.4687258 0.1111125 -0.8763277 -0.4878064 0.5501279 -0.6777936 -0.569895 0.1266049 -0.8119057 -0.5082737 0.3273341 -0.7965615 -0.5224338 0.5409433 -0.6591232 -0.7119902 0.4188854 -0.5635645 -0.764467 0.3827379 -0.5187504 -0.7531337 0.2346612 -0.6145923 -0.7544483 0.07597589 -0.6519474 -0.7635596 0.2318788 -0.6026682 -0.8003073 0.3461047 -0.4896121 -0.7774317 0.07741588 -0.6241848 -0.8924574 0.2598313 -0.3687921 -0.8832469 0.1371927 -0.4483894 -0.8934412 0.04445493 -0.446975 -0.8980227 0.1273427 -0.4211166 -0.9320635 0.1941064 -0.305909 -0.9266886 0.0498926 -0.3725039 -0.9631852 0.0241028 -0.2677562 -0.971196 0.12167 -0.2048773 -0.9811193 0.08870989 -0.171859 -0.5732806 0 -0.8193592 -0.5855988 0.005717098 -0.8105809 -0.7807027 -0.00191915 -0.6248998 -0.8011443 0.005185604 -0.5984489 -0.9278382 -0.003551661 -0.3729662 -0.9333211 5.88303e-4 -0.3590424 -0.5433428 -0.123545 -0.8303706 -0.5506269 -0.3295007 -0.7669675 -0.5689785 -0.3176949 -0.7585075 -0.5822882 -0.4795234 -0.6565043 -0.4715623 -0.5522114 -0.6875258 -0.5796076 -0.1285027 -0.8047 -0.6589052 -0.451404 -0.6017295 -0.740873 -0.07738822 -0.6671719 -0.7504606 -0.2310968 -0.6191957 -0.732761 -0.2479657 -0.6336989 -0.7440915 -0.407143 -0.5296814 -0.7998749 -0.07795441 -0.5950827 -0.8375594 -0.3081373 -0.4511605 -0.9329957 -0.02421343 -0.3590723 -0.9228914 -0.03442484 -0.3835186 -0.9264361 -0.09816944 -0.3634265 -0.9109933 -0.1234872 -0.3935 -0.9176995 -0.2196041 -0.3310616 -0.9293307 -0.1961244 -0.3128574 -0.9945257 -0.01995509 -0.1025692 -0.4707908 -0.7524104 -0.4606893 -0.4566836 -0.7591754 -0.463781 -0.6521437 -0.6562253 -0.3795748 -0.6191553 -0.680607 -0.3916897 -0.8290764 -0.5045095 -0.2410447 -0.8540728 -0.4703419 -0.222122 -0.9223013 -0.3633765 -0.1315976 -0.9919279 -0.1265001 0.008773028 -0.983841 -0.1781883 -0.0174914 -0.9957969 -0.01898676 0.08960056 0.2560158 -0.672714 0.6941987 0.109518 -0.9542554 0.278213 -0.2429814 -0.9607034 -0.1341981 0.02366286 -0.9389835 0.3431477 0.4162893 -0.2430703 0.8761392 0.2560964 -0.6727097 0.6941731 -0.3623047 -0.9302528 -0.05801039 0.3699505 -0.2553385 0.8932743 0.1070245 -0.6286798 0.7702646 -0.133108 -0.9175689 0.3746326 -0.5230501 -0.8522375 -0.01049059 0.03552567 -0.6257822 0.7791884 0.1726493 -0.2186573 0.9604069 -0.499325 -0.8663808 -0.007686674 -0.2961571 -0.8305491 0.471677 0.1193649 -0.223105 0.9674586 -0.1256514 -0.565398 0.8151914 -8.16971e-4 -0.1921932 0.9813568 -0.1797854 -0.5263983 0.8310127 -0.3950389 -0.7868479 0.4741463 -0.7761132 -0.6221554 0.1028163 -0.6747218 -0.7293988 0.1128178 -0.5162795 -0.6866183 0.5118699 -0.1595748 -0.1827924 0.970115 -0.2440925 -0.1482558 0.9583523 -0.343793 -0.4494062 0.8245244 -0.5539909 -0.6621258 0.5046619 -0.3649521 -0.4311376 0.8251851 -0.4258116 -0.1164296 0.8972896 -0.4995225 -0.3435369 0.7952734 -0.5283548 -0.3119998 0.7896186 -0.6933276 -0.5170346 0.5019682 -0.9254299 -0.2842633 0.2505476 -0.7902184 -0.5598818 0.2491729 -0.437119 -0.1168908 0.8917756 -0.8444396 -0.1340951 0.5185945 -0.8044067 -0.2340397 0.5460361 -0.6968379 -0.159244 0.6993272 -0.6609716 -0.04771953 0.7488922 -0.6637812 -0.0475223 0.7464156 -0.7376637 -0.09046155 0.6690807 0.3819711 -7.22828e-7 0.9241744 0.3965061 7.60365e-4 0.9180318 0.1227198 -7.20704e-5 0.9924414 0.1337493 4.2087e-4 0.9910152 -0.1619142 -0.001258552 0.9868041 -0.1466082 -4.90301e-4 0.9891946 -0.4397201 4.24911e-4 0.8981349 -0.4204719 0.001342177 0.9073047 -0.6647083 -0.001074433 0.7471023 -0.648543 -1.0015e-4 0.7611782 -0.206902 0.9690359 -0.1347627 -0.2172821 0.9668179 -0.1343567 0.02219647 0.9372424 0.3479714 0.1834079 0.6603112 0.7282519 0.3237043 0.2636983 0.9086687 -0.04563754 0.9347833 0.3522748 0.1540132 0.6434141 0.7498655 0.384272 0.2458761 0.8898764 -0.4287358 0.9023879 -0.04337888 0.1302115 0.2170269 0.9674422 -0.2394427 0.8663118 0.4383732 -0.4398618 0.8970752 -0.04216361 0.1241286 0.2141786 0.9688755 -0.008292436 0.6080462 0.7938585 -0.262155 0.8589636 0.4398369 -0.03776174 0.5865172 0.8090561 -0.589191 0.8073394 0.03251588 -0.4060549 0.7673041 0.4963506 -0.6011077 0.7984413 0.03407537 -0.2743896 0.4783094 0.8342245 -0.4761054 0.7240994 0.4990028 -0.764437 0.6339702 0.1171244 -0.236887 0.1836252 0.9540264 -0.3275945 0.4615032 0.8244372 -0.7695494 0.6276398 0.117738 -0.6223166 0.5669509 0.5397117 -0.1444238 0.161289 0.9762826 -0.41512 0.3904941 0.8216994 -0.5842485 0.5987233 0.5478907 -0.8041855 0.5765752 0.1443846 -0.4171338 0.1266295 0.8999802 -0.5793961 0.8126741 0.06213933 -0.9060109 0.3387217 0.2537952 -0.5800501 0.05536693 0.8126971 -0.6404827 0.2456837 0.7276135 -0.6477202 0.05053836 0.7602003 -0.5335773 0.6512458 0.5396056 -0.7324658 0.1007164 0.6733129 -0.8192276 0.2866684 0.4966763 -0.6980654 0.02783477 0.7154929 -0.7239002 0.1073809 0.6814968 -0.3186507 -0.9476232 -0.02172809 -0.06834524 -0.9928048 -0.09832316 -0.1889311 -0.9818304 -0.01772433 0.1818957 -0.9831829 0.0162931 0.422985 -0.9056866 -0.02855604 0.6306977 -0.7702388 0.09461784 0.8059071 -0.5865262 0.0806272 0.2751687 -0.9605069 0.04133677 0.9873241 -0.1263303 0.09608256 0.9284509 -0.3711114 0.01598298 0.9757366 -0.1615083 0.1478279 0.7206049 -0.684709 0.1090974 -0.195279 -0.9802539 -0.03111875 0.3020653 -0.9506823 0.07042551 -0.1727765 -0.9837628 -0.04857188 -0.1824528 -0.9821437 -0.04587745 0.9354574 -0.2702029 0.2278372 0.26518 -0.9578612 0.1103708 0.2764629 -0.9546915 0.1101479 0.6746319 -0.6826627 0.2807907 0.9030972 -0.2043875 0.3776788 0.9161384 -0.163953 0.3658003 0.6717641 -0.6854261 0.2809345 0.8334445 -0.2769265 0.4782074 0.2727586 -0.9472911 0.168055 -0.1571276 -0.9829376 -0.095627 -0.165768 -0.9815345 -0.09545195 0.2234979 -0.960457 0.1660452 0.5870745 -0.6819878 0.4361607 0.5828528 -0.6861251 0.4353332 0.7888312 -0.1749705 0.5891782 0.7700992 -0.2166517 0.6000077 -0.1604171 -0.9798563 -0.1189462 -0.1412186 -0.9815732 -0.1287299 -0.1349348 -0.982731 -0.1266193 0.2373388 -0.9470288 0.2163493 0.6691443 -0.2685232 0.6929222 0.4670732 -0.6816459 0.5632065 0.4598788 -0.6892016 0.5599222 0.177725 -0.9594498 0.2187919 0.621885 -0.1576557 0.767075 -0.1277081 -0.9802299 -0.1511296 -0.09871518 -0.984643 -0.1439914 0.1843772 -0.9517462 0.2453249 0.5682827 -0.2486628 0.7843607 -0.09764832 -0.9828952 -0.1561471 -0.3379319 0.9407613 -0.02775228 -0.07269829 0.9952903 -0.0641281 0.3026863 0.9519804 0.04598337 0.1813766 0.983331 -0.01275897 0.4230324 0.9038577 0.06391394 -0.1753398 0.9841504 -0.02653163 0.6273187 0.7729758 0.09476143 0.8059977 0.5864335 0.08039742 0.9875035 0.1244807 0.09665125 0.9289439 0.3698613 0.0163024 0.7198753 0.6854408 0.1093187 0.975508 0.1626023 0.1481371 0.9353369 0.2706447 0.2278077 -0.1959398 0.9794088 -0.04864311 0.2807338 0.9526457 0.1168538 0.6739727 0.6834173 0.2805379 0.9078018 0.1782103 0.379654 0.9075641 0.2121579 0.3623763 0.6711404 0.6861412 0.2806793 0.2834624 0.9515482 0.1191853 -0.1707338 0.9826987 -0.07178694 -0.1671203 0.9835588 -0.06843322 0.8333356 0.2773566 0.4781476 -0.1747813 0.9791681 -0.1033516 0.5864992 0.6827449 0.4357501 0.2429765 0.9530864 0.1805241 0.783462 0.2092035 0.5851678 0.7789935 0.1574747 0.6069357 0.5823108 0.686842 0.434928 -0.1427707 0.9838982 -0.1075215 -0.1495715 0.9813458 -0.1207842 0.2466812 0.9511232 0.1857774 0.6690608 0.2689626 0.6928324 -0.1350464 0.9800121 -0.1460787 0.4597575 0.6967856 0.550557 0.4636777 0.6820488 0.5655196 0.1954131 0.9535067 0.2294317 0.6219615 0.1586229 0.7668134 -0.105238 0.9851216 -0.1358694 0.2064859 0.9438965 0.2577264 0.5674986 0.253795 0.7832839 -0.1067141 0.9819416 -0.1562141 -0.6066713 0.7912285 -0.07686132 -0.5681663 0.8107353 -0.1410506 -0.7958402 0.5352433 -0.2831131 -0.5781996 0.7895423 -0.2056894 -0.8010701 0.519487 -0.2973552 -0.9171295 0.2073097 -0.3404353 -0.9173722 0.2362705 -0.3203193 -0.5476459 0.8060985 -0.2242527 -0.8817001 0.1699264 -0.4401476 -0.5183122 0.7918053 -0.3231052 -0.5146442 0.80158 -0.3043205 -0.7141284 0.5402234 -0.4451733 -0.7168599 0.5148631 -0.470136 -0.8151984 0.2227632 -0.5346291 -0.8122706 0.210564 -0.5439479 -0.4555949 0.8106031 -0.3679077 -0.7424394 0.1721071 -0.647428 -0.6002739 0.5446585 -0.5856778 -0.439521 0.7892548 -0.4288338 -0.6739257 0.2315804 -0.7015659 -0.652086 0.1908945 -0.7337187 -0.5956103 0.5106862 -0.6200388 -0.4010734 0.8067991 -0.433838 -0.3350217 0.7928034 -0.5091398 -0.3382989 0.8004279 -0.4948425 -0.4593387 0.5486338 -0.6985765 -0.5549139 0.1808622 -0.8120096 -0.4758856 0.3427787 -0.8099604 -0.4628149 0.5578113 -0.6889477 -0.5112981 0.2234018 -0.829859 -0.4521654 0.1121273 -0.8848581 -0.8861982 -0.4485061 -0.1161689 -0.7828376 -0.6027254 -0.1545557 -0.8446827 -0.5244539 -0.1070482 -0.9641706 -0.2332326 -0.126402 -0.6632422 -0.7436789 -0.08397364 -0.5140025 -0.8490536 -0.122105 -0.6406605 -0.766614 -0.04309511 -0.5931729 -0.799507 -0.09452265 -0.5727578 -0.806976 -0.144008 -0.5749945 -0.7921777 -0.2045384 -0.5490038 -0.8069628 -0.2177292 -0.7956581 -0.5355561 -0.2830334 -0.8008924 -0.5198054 -0.2972771 -0.9131111 -0.2266145 -0.3389308 -0.8816649 -0.1701236 -0.4401423 -0.7139686 -0.5405357 -0.4450506 -0.5096048 -0.7996216 -0.3176608 -0.5421572 -0.7801331 -0.3121829 -0.7167063 -0.5151871 -0.4700154 -0.8169524 -0.2134327 -0.5357568 -0.8091834 -0.2270603 -0.5419095 -0.4734688 -0.8078194 -0.3510771 -0.7423943 -0.1723093 -0.6474259 -0.4329056 -0.7963756 -0.4223491 -0.450401 -0.7864533 -0.4226464 -0.600148 -0.5449741 -0.5855132 -0.5954914 -0.5110121 -0.6198845 -0.6796821 -0.1934995 -0.707524 -0.6420646 -0.2565413 -0.7224539 -0.3797549 -0.8085949 -0.4494003 -0.3361052 -0.7942876 -0.5061034 -0.3211666 -0.802578 -0.5027133 -0.4584302 -0.5491243 -0.6987877 -0.5548851 -0.1810666 -0.8119838 -0.5036754 -0.2306827 -0.8325242 -0.4509774 -0.133214 -0.8825381 -0.9964093 0.001121938 -0.08466017 -0.997287 0.01576596 -0.0719043 -0.9963706 -0.00892508 -0.08465278 -0.9960189 -0.0101971 -0.08855795 -0.9925512 -8.74183e-4 -0.1218256 -0.9807664 -0.008097887 -0.1950177 -0.9665589 -0.005607903 -0.2563834 -0.9828649 0.01723152 -0.1835206 -0.9760454 -0.003027379 -0.2175456 -0.9073691 0 -0.4203349 -0.8206001 0 -0.571503 -0.8205999 0 -0.5715033 -0.7088963 0 -0.7053128 -0.708896 0 -0.705313 -0.5756566 0 -0.8176916 -0.5756558 0 -0.8176922 -0.4249238 0 -0.9052292 -0.4249249 0 -0.9052287 -0.2612856 0 -0.9652615 -0.2612857 -1.2638e-7 -0.9652615 -0.08970713 0 -0.9959682 -0.08970838 0 -0.9959681 0.08460044 0 -0.996415 0.08460044 0 -0.996415 0.07779198 0 0.9969697 0.07779037 0 0.9969698 -0.08915758 0 0.9960176 -0.08915889 0 0.9960175 -0.2536271 0 0.9673021 -0.2536332 -3.14633e-7 0.9673005 -0.4110243 -2.436e-7 0.9116244 -0.4110233 -2.639e-7 0.9116249 -0.556956 -1.21806e-7 0.830542 -0.5569556 -2.84213e-7 0.8305422 -0.6873589 0 0.7263181 -0.6873575 0 0.7263194 -0.7983469 0.02527248 0.6016674 -0.7733715 0.003540873 0.6339434 -0.75021 1.27145e-7 0.6611996 -0.799453 -0.02809339 0.6000715 -0.7757022 -0.005235314 0.6310774 -0.742483 2.78284e-4 0.6698649 0 -1 0 0 -1 1.22174e-5 0 -1 -1.15061e-5 -1.25882e-6 -1 -2.64184e-6 -1.25882e-6 -1 0 -9.89045e-7 -1 0 -9.89045e-7 -1 0 -8.41114e-7 -1 0 -8.41114e-7 -1 1.88708e-6 -7.56983e-7 -1 -1.69832e-6 -7.56983e-7 -1 1.56518e-6 -7.13062e-7 -1 -1.47437e-6 -7.13062e-7 -1 0 -6.99361e-7 -1 0 -6.99361e-7 -1 0 -7.13063e-7 -1 -1.47437e-6 -7.56983e-7 -1 0 0 -1 -9.43539e-6 0 -1 2.53161e-6 0 -1 -2.64184e-6 0 -1 9.0456e-6 0 1 -1.22174e-5 0 1 6.22838e-6 0 1 -3.83536e-6 0 1 3.92617e-6 0 1 -3.08477e-6 0 1 -2.71953e-6 0 1 3.98624e-6 0 1 -3.15283e-7 2.91803e-6 1 7.9038e-6 3.01858e-6 1 3.08099e-6 2.09392e-7 1 -1.08369e-5 3.39284e-6 1 8.05446e-6 0 1 -2.53161e-6 0 1 4.70627e-6 0 1 2.06266e-5 0 1 2.64184e-6 0 1 3.83535e-6 0 1 -6.22836e-6 0.9287059 0 0.3708173 0.8673657 0 0.4976714 0.8673652 -4.70226e-7 0.4976723 0.7888354 -7.05464e-7 0.6146047 0.7888354 -2.35155e-7 0.6146048 0.6946561 -4.70303e-7 0.719342 0.6946583 0 0.7193399 0.5867114 0 0.8097962 0.5867086 -7.05567e-7 0.8097982 -0.8947124 9.90305e-6 -0.4466429 -0.8947072 -1.31674e-5 -0.4466532 -0.8308994 1.97524e-5 -0.5564228 -0.8308856 -1.97512e-5 -0.5564435 -0.7536857 2.41395e-5 -0.6572352 -0.7536669 -2.41409e-5 -0.6572566 -0.6643021 8.7774e-6 -0.7474642 -0.6642966 -5.48637e-6 -0.7474691 -0.5642187 1.09732e-5 -0.8256254 -0.564211 -6.58402e-6 -0.8256307 -0.455035 4.38887e-6 -0.8904737 -0.455033 0 -0.8904746 -0.9531254 0.2755929 -0.1249027 -0.9794912 0.0877524 -0.1813738 -0.9601501 0.2685475 -0.07742124 -0.9632864 0.1743384 -0.2041701 -0.9632509 -0.1745313 -0.2041733 -0.9243677 -0.2033714 -0.3227761 0.9418526 -6.1941e-5 -0.3360264 0.9418317 6.55857e-5 -0.3360849 0.8897434 -5.46518e-5 -0.456461 0.8897193 5.82985e-5 -0.4565082 0.8223212 -4.91937e-5 -0.5690236 0.8222897 6.92294e-5 -0.5690692 0.7407484 -6.19492e-5 -0.6717826 0.7407004 8.5626e-5 -0.6718355 0.6464152 -7.2872e-5 -0.7629859 0.6463618 7.28754e-5 -0.7630312 0.5409396 -7.37658e-5 -0.8410614 0.5408959 3.6436e-5 -0.8410895 0.4261348 -4.73584e-5 -0.9046598 0.426114 -9.10969e-7 -0.9046695 0.3016293 -1.40132e-5 -0.9534254 0.3039923 -0.00527209 -0.9526599 -0.9388772 9.9599e-6 0.3442524 -0.9388399 -1.50819e-5 0.3443541 -0.8852472 1.50871e-5 0.465121 -0.8851754 -2.08221e-5 0.4652578 -0.8160412 2.01779e-5 0.5779938 -0.8159223 -2.72429e-5 0.5781617 -0.7327815 2.66735e-5 0.680464 -0.7326294 -2.47804e-5 0.6806279 -0.6411057 2.25028e-5 0.7674527 -0.640981 -1.20329e-5 0.7675569 -0.5481868 1.14875e-5 0.8363559 -0.5488448 -1.39679e-4 0.8359242 0 1 -8.15864e-6 0 1 2.65659e-6 0 1 9.95631e-6 0 1 -3.98625e-6 0 1 -1.55784e-6 0 1 3.081e-6 0 1 -5.51748e-7 0 1 -3.081e-6 0 1 5.75319e-6 0 1 2.70922e-6 0 1 -9.9563e-6 0 1 -1.03133e-5 0.2425703 0 0.9701339 0.2425705 0 0.9701338 0.4005749 -2.03014e-7 0.9162641 0.4005782 4.46632e-7 0.9162627 0.5474176 4.06045e-7 0.8368597 0.5474151 1.62417e-7 0.8368612 0.678996 0 0.734142 0.6789957 0 0.7341423 0.7916545 0 0.610969 0.7916543 0 0.6109693 0.8822511 0 0.4707792 0.8822491 -4.87295e-7 0.4707829 0.9136914 -4.18419e-7 0.4064088 0.9375899 -0.006723105 0.3476781 0.9275861 9.14359e-4 0.3736082 0.9407186 0.004027783 0.3391643 0.9520086 0.03379708 0.3041998 0.9635934 -0.05852192 -0.2608892 0.9638628 0.05350559 -0.2609707 0.945691 -0.02265989 -0.3242762 0.9246335 -0.0460512 -0.3780637 0.8937101 0.1588427 -0.4195848 0.9050523 0.01823645 -0.4249094 0.8879781 0.001839101 -0.4598822 0.8888434 -0.001732528 -0.458208 0.804514 -0.002736449 -0.5939275 0.7881537 -8.08617e-4 -0.615478 0.8255476 -0.00953263 -0.564252 0.8176557 -0.002665221 -0.5757014 0.8379554 0.001439869 -0.5457369 0.7761533 0 -0.6305444 0.7932206 0.00197041 -0.6089312 0.8176327 0.008160591 -0.5756823 0.7052695 0 -0.7089394 0.7052698 0 -0.7089391 0.5714557 0 -0.8206331 0.5714527 2.72205e-7 -0.820635 0.420279 2.13874e-7 -0.907395 0.4202795 1.94431e-7 -0.9073947 0.2563307 0 -0.9665892 0.2563319 1.2638e-7 -0.9665889 0.9208595 -0.3518167 -0.1680559 0.9880447 -0.1327944 -0.07831573 0.9631019 -0.2522073 -0.0939477 0.5599685 -0.8152756 -0.1475159 0.9639189 -0.1675301 -0.2068673 0.570622 -0.7991899 -0.1889074 0.8005868 -0.5374156 -0.2650385 0.8083215 -0.5165022 -0.282563 0.920516 -0.2116465 -0.3284145 0.9206155 -0.2211356 -0.3218172 0.5351208 -0.8179338 -0.2112586 0.876738 -0.1703543 -0.4497889 0.727312 -0.5437929 -0.4186964 0.5302655 -0.7866347 -0.3162664 0.5254297 -0.7952552 -0.3024777 0.8281685 -0.2363247 -0.5082203 0.7328581 -0.5105494 -0.4497315 0.8091242 -0.178436 -0.5598915 0.4711115 -0.8082331 -0.3532891 0.4556998 -0.7831408 -0.4231175 0.4522848 -0.7967941 -0.4006966 0.6255046 -0.5492281 -0.5541592 0.7177909 -0.2470303 -0.6509626 0.7075119 -0.1973845 -0.6785767 0.6227517 -0.5054029 -0.597284 0.3893655 -0.8075047 -0.4430923 0.637432 -0.1661342 -0.7523828 0.3631115 -0.7847606 -0.5022957 0.3644473 -0.794172 -0.4862809 0.4993739 -0.553762 -0.6663133 0.3028078 -0.8073372 -0.5064724 0.5300306 -0.199818 -0.8240997 0.5434771 -0.2277708 -0.8079314 0.4830182 -0.5010921 -0.7180531 0.419542 -0.1752237 -0.8906633 0.2610754 -0.7935776 -0.5496129 0.2794304 -0.8160675 -0.5059175 0.2911909 -0.7111284 -0.6399253 0.3593085 -0.5553945 -0.7499563 0.3649265 -0.2305986 -0.9020271 0.3349695 -0.4911932 -0.8040676 0.3429527 -0.3168542 -0.8843002 0.3000082 -0.09840589 -0.9488475 0.6265229 0.7778586 -0.04904359 0.5142297 0.8503771 -0.1114756 0.6637175 0.7439806 -0.07727891 0.8471395 0.5221336 -0.09864687 0.7846115 0.6034102 -0.1424117 0.8872438 0.4484407 -0.1081633 0.9633399 0.2412178 -0.117433 0.5755681 0.8094 -0.11659 0.9630403 0.1686855 -0.2099968 0.800893 0.5372954 -0.2643563 0.5769647 0.7940382 -0.1913502 0.5781443 0.7933047 -0.1908321 0.9178107 0.2244073 -0.3275132 0.9225258 0.2130216 -0.32182 0.8087443 0.5160785 -0.2821275 0.5313869 0.8092329 -0.2505396 0.8767161 0.1703425 -0.449836 0.727684 0.5436299 -0.4182614 0.5034835 0.8039883 -0.3163974 0.5330663 0.7886446 -0.3063983 0.8284174 0.2363247 -0.5078142 0.733274 0.510163 -0.4494918 0.8091536 0.178031 -0.5599783 0.461058 0.8046423 -0.3741341 0.4606045 0.7884363 -0.4076908 0.6258526 0.5490373 -0.5539554 0.4098629 0.8085438 -0.4222198 0.6231032 0.5050417 -0.597223 0.7265417 0.1945898 -0.6589932 0.7025352 0.2302966 -0.6733556 0.6374009 0.1659365 -0.7524529 0.3779461 0.7866544 -0.4881923 0.3637068 0.7952706 -0.4850382 0.499627 0.5535468 -0.6663023 0.3116215 0.807751 -0.5004302 0.4832604 0.5007482 -0.7181301 0.5252288 0.2389376 -0.8167273 0.5466631 0.2031045 -0.8123473 0.4195301 0.1751081 -0.8906916 0.3501106 0.5587062 -0.7518445 0.3626192 0.2328345 -0.9023833 0.3021023 0.1114598 -0.9467371 0.06649881 0.9956569 -0.06515657 0.3227581 0.9461412 -0.025379 -0.928634 0.3706079 0.01699507 -0.9883024 0.1264276 0.08529084 -0.9765535 0.1778249 0.1213324 -0.7257716 0.6819928 0.09022986 -0.806388 0.5879954 0.06324464 -0.6316712 0.7711651 0.07934713 -0.3057295 0.9513376 0.03855454 -0.4226096 0.9061065 0.01929217 -0.1788262 0.9836078 0.0231719 0.1765484 0.9840293 -0.02274 0.1954081 0.9799228 -0.03958326 -0.9370915 0.2798147 0.2087183 -0.6864973 0.6881625 0.2348484 -0.9128589 0.2336261 0.3348247 -0.9295812 0.186415 0.3180065 -0.2847213 0.9534721 0.09912037 -0.693257 0.6790788 0.2413436 -0.2929812 0.9503015 0.105305 0.1806477 0.9817215 -0.0599119 0.1691415 0.9837151 -0.06079417 0.1821812 0.9795061 -0.08589482 -0.8543611 0.2615554 0.4490611 -0.6215923 0.6911795 0.368638 -0.8470616 0.1735745 0.5023532 -0.2551292 0.9544894 0.1544649 -0.6302831 0.6761119 0.3815968 0.1553309 0.9830281 -0.09761244 0.1550467 0.9830788 -0.09755331 -0.2662087 0.9492514 0.1674954 -0.7839775 0.2770741 0.555526 0.1564607 0.9794899 -0.1269635 -0.7155124 0.2148982 0.6647261 -0.7233737 0.1968467 0.6618021 -0.5311703 0.6940478 0.4859588 -0.2153081 0.955401 0.2021172 -0.5391131 0.6732278 0.5060845 -0.2261306 0.9482555 0.2228824 0.1223753 0.9844451 -0.1260648 0.1336385 0.9822377 -0.131719 -0.617443 0.2685053 0.7393707 0.1219563 0.9799545 -0.1575309 -0.5282191 0.2664032 0.8062345 -0.579966 0.1821101 0.7940248 -0.4198074 0.6966882 0.5817108 -0.4171802 0.7092665 0.5682445 -0.1567567 0.9572223 0.243214 0.09262841 0.9845276 -0.1487461 -0.05901187 0.9977826 -0.03078252 0.1628026 0.9781064 0.1296278 0.1260702 0.9596108 -0.2515026 0.1959879 -0.9804342 -0.01837182 -0.9645221 -0.250674 0.08282452 -0.9766012 -0.177818 0.120958 -0.80479 -0.5851278 0.09969294 -0.6332775 -0.7730137 0.03754234 -0.7261575 -0.6814704 0.09106814 0.2145757 -0.9752844 -0.05270326 -0.4231177 -0.9045187 0.05307883 -0.187228 -0.9822183 -0.01389414 -0.3609591 -0.9304613 0.06285256 0.1746521 -0.9843135 -0.02497422 -0.937213 -0.2794358 0.2086809 -0.6873674 -0.6873539 0.2346718 -0.9260014 -0.1650446 0.3395316 -0.921327 -0.22851 0.314547 -0.2810991 -0.9546993 0.0976358 -0.6940259 -0.6783936 0.2410606 0.2073763 -0.9745582 -0.08503699 -0.8546127 -0.2607932 0.4490256 0.1637979 -0.9831027 -0.08172655 -0.3223407 -0.9355874 0.144128 0.1711198 -0.9799498 -0.1020604 -0.6224007 -0.6903973 0.3687399 -0.8473958 -0.1728508 0.5020389 -0.2403193 -0.9597534 0.1453275 -0.631039 -0.6754016 0.381605 -0.7841886 -0.2766645 0.5554323 -0.2604733 -0.9453713 0.1960276 0.1487525 -0.9825627 -0.1115496 0.149165 -0.9824193 -0.1122596 0.1460494 -0.979939 -0.1356065 -0.5318452 -0.693288 0.4863049 -0.7193152 -0.1908304 0.6679591 -0.7214063 -0.2108439 0.6596346 -0.205111 -0.9596381 0.192417 -0.5397677 -0.6724941 0.5063622 -0.2188532 -0.9461694 0.2384678 0.1261659 -0.9815644 -0.1435741 0.123932 -0.9830591 -0.1350396 -0.6176376 -0.2680874 0.7393599 0.1156169 -0.9803327 -0.1599392 -0.4181205 -0.6962329 0.5834681 -0.545447 -0.1109793 0.8307655 -0.5688957 -0.2547076 0.781973 -0.1476152 -0.9613841 0.232272 -0.4154543 -0.7091551 0.5696462 -0.1302823 -0.9771175 0.1681308 0.1276941 -0.9685439 -0.2135812 0.1157599 -0.9803097 -0.1599767 0.1195099 -0.9612591 -0.2483913 0.8675884 -3.5512e-5 0.4972832 0.8600473 -6.75126e-4 0.5102138 0.6987131 3.29349e-4 0.715402 0.6831467 -5.38177e-4 0.7302809 0.4567947 9.61997e-4 0.8895716 0.4423633 2.60477e-4 0.8968359 0.1888509 -5.79431e-4 0.9820057 0.1978377 -1.90815e-4 0.9802349 -0.07915014 -2.18571e-4 0.9968628 -0.08594459 -5.29465e-4 0.9962999 -0.3600918 4.12403e-4 0.9329169 -0.3749856 -2.49693e-4 0.9270306 0.8648149 0.05323189 0.4992609 0.8942369 0.04307973 0.4455161 0.9197621 0.136901 0.3678258 0.8516618 0.07060909 0.5193137 0.8566829 0.2398521 0.4566897 0.7479698 0.1033938 0.6556303 0.7931901 0.3414126 0.5042688 0.6762103 0.1450744 0.7222833 0.9066412 0.3951513 0.1478417 0.547834 0.167226 0.8197034 0.6146758 0.4858223 0.62141 0.7637742 0.6250141 0.1612653 0.6911783 0.4498481 0.5656052 0.4326233 0.2104462 0.8766696 0.4268761 0.6152982 0.6627104 0.34421 0.2158957 0.9137334 0.1910982 0.2562329 0.9475369 0.7489585 0.6408461 0.1684559 0.4614194 0.6055127 0.6484184 0.5508722 0.8173061 0.1689697 0.144031 0.2536283 0.9565187 0.237454 0.6996122 0.6739129 -0.06177407 0.2838089 0.956889 0.5146325 0.8383432 0.179817 0.3099076 0.9356028 0.1691291 0.2118057 0.7028797 0.6790423 0.0202912 0.7586418 0.651192 -0.08136272 0.2823493 0.9558552 -0.1099696 0.2873629 0.951488 0.3528895 0.9223903 0.1570516 -0.11063 0.7562593 0.644851 -0.3475047 0.2806005 0.8947088 0.1851736 0.9680254 0.1692262 -0.3595757 0.2841763 0.8887909 -0.1090933 0.7566189 0.6446909 0.04732912 0.987568 0.149898 0.9167674 0.3756324 -0.1357868 0.7626612 0.6146171 -0.201479 0.7741692 0.5985209 -0.2059974 0.5317589 0.8157681 -0.2274971 0.5789197 0.7763919 -0.2491338 0.3613376 0.9033424 -0.2311011 0.4460378 0.8547053 -0.2655734 0.1929444 0.9496561 -0.2468313 0.2581099 0.9273276 -0.2710033 0.9584494 0.07639372 -0.2748434 0.9616676 0.06619489 -0.2661086 0.9328809 0.02086287 -0.3595803 0.9076241 0.09844696 -0.408077 0.8772331 0.1543616 -0.4545708 0.9147472 0.2383688 -0.3262177 0.8805348 0.01261878 -0.4738137 0.889881 0.287464 -0.3542265 0.8700232 0.03611052 -0.4916867 0.840904 -0.001019418 -0.5411834 0.7504833 0.5114819 -0.4185228 0.756496 0.3575577 -0.5476007 0.7365769 0.2087323 -0.6433392 0.7451047 0.3687261 -0.5557518 0.7844079 0.4589518 -0.417214 0.7274734 0.2215697 -0.649376 0.6922348 0.1286408 -0.7101145 0.6613398 0.02956604 -0.7495036 0.7015225 0.02967506 -0.7120293 0.7119903 0.1070923 -0.6939749 0.5884644 0.3439354 -0.7317227 0.5992075 0.5241954 -0.6051195 0.5943452 0.5273184 -0.6071978 0.6354895 0.6239697 -0.4547692 0.5520155 0.6798809 -0.4827432 0.505134 0.2341517 -0.83067 0.5589152 0.3736678 -0.7402609 0.505055 0.09285813 -0.8580775 0.5361363 0.07615554 -0.8406891 0.5632351 0.1862765 -0.8050263 0.4220147 0.7624782 -0.4904391 0.4576408 0.4419385 -0.771528 0.4295969 0.6493761 -0.6275008 0.4909052 0.7132392 -0.5003019 0.4591979 0.6391 -0.6169996 0.1984543 0.3379086 -0.9200183 0.3143507 0.5552933 -0.7699565 0.5281068 0.6891759 -0.4961247 0.497257 0.6159142 -0.6110526 0.3365056 0.1048168 -0.9358298 0.05363345 0.1951863 -0.9792987 0.2246634 0.8217506 -0.5236911 0.6615064 -0.002448618 -0.7499355 0.6693488 -0.004387497 -0.7429354 0.5073215 -2.90891e-4 -0.8617569 0.5340367 -0.008476912 -0.8454189 0.3388589 0.005748033 -0.9408196 0.3884877 -0.006664872 -0.9214299 0.9806271 0.0616573 -0.1859269 0.9716504 -0.08209836 -0.2217105 0.9333803 -0.02099263 -0.3582745 0.9082117 -0.101065 -0.4061248 0.860344 -0.1909751 -0.4725852 0.9062876 -0.3059781 -0.2915823 0.8836669 -0.005661785 -0.4680818 0.5113495 -0.7308865 -0.4520251 0.8536478 -0.0664972 -0.5165886 0.8197537 -0.01449519 -0.5725328 0.7755681 -0.1631935 -0.6098049 0.8214744 -0.2645864 -0.5051475 0.7526702 -0.5116595 -0.4143578 0.7985289 -0.4399876 -0.4108074 0.754711 -0.3417695 -0.5600045 0.7853736 -0.05047816 -0.6169605 0.7837224 -0.001588404 -0.6211094 0.6960932 -0.1130678 -0.7089923 0.7366726 -0.219344 -0.6396887 0.6691811 -0.04023212 -0.7420096 0.5914347 -0.6636883 -0.4579551 0.6172037 -0.4936785 -0.612651 0.6596296 -0.5901649 -0.465397 0.6344137 -0.04473155 -0.7716984 0.6575179 -0.1471911 -0.7389215 0.6272737 -0.4818364 -0.6118509 0.5720919 -0.3608697 -0.7365351 0.5397716 -0.2074646 -0.8158462 0.5913491 -0.3395509 -0.7314448 0.5317882 -0.08055609 -0.8430374 0.4742809 -0.5948544 -0.6490039 0.5213782 -0.7075769 -0.4769694 0.3317344 -0.5192199 -0.7876313 0.4067437 -0.6506295 -0.6412807 0.3559807 -0.780858 -0.5133599 0.4356734 -0.4314932 -0.7899383 0.3421756 -0.3285353 -0.8803298 0.3778221 -0.2984805 -0.8764474 0.3347618 -0.1040422 -0.9365414 0.3880741 -0.08435642 -0.9177596 0.9235781 -0.3576746 -0.1381035 0.71913 -0.6666952 -0.1958814 0.7745379 -0.5954064 -0.2135 0.6081224 -0.7584728 -0.2343208 0.6169751 -0.750192 -0.2378104 0.3614151 -0.8988685 -0.2478199 0.3861916 -0.885618 -0.2579476 0.2067673 -0.9404114 -0.2699515 0.8942644 -0.0353741 0.446139 0.9529924 -0.04741704 0.299261 0.9212335 -0.1510512 0.3584861 0.8661698 -0.05842304 0.4963233 0.8257032 -0.3102735 0.4711099 0.7848117 -0.08790242 0.6134687 0.692623 -0.1375883 0.7080557 0.7299321 -0.3970834 0.5563487 0.6911692 -0.1380513 0.709385 0.6698424 -0.449806 0.5907501 0.6089661 -0.149728 0.7789364 0.4663214 -0.1992135 0.8618923 0.9228067 -0.3751937 0.08750802 0.619444 -0.7719815 0.1425964 0.7973023 -0.5849354 0.1488621 0.727887 -0.4138479 0.5467271 0.4460279 -0.2022367 0.8718713 0.5202478 -0.5682764 0.6374984 0.4285829 -0.2087212 0.8790634 0.606853 -0.7676913 0.2058628 0.5201077 -0.5683352 0.6375603 0.7046481 -0.6922121 0.1559281 0.1835555 -0.2461794 0.9516844 0.2072256 -0.24957 0.9459241 0.2950289 -0.6686604 0.682533 0.3990198 -0.6538267 0.6428794 0.4839653 -0.8519869 0.1997395 0.6008239 -0.7852342 0.1497268 -0.07555049 -0.2856312 0.955357 0.2521055 -0.9493071 0.1877738 0.1548969 -0.7144262 0.6823505 -0.004649758 -0.7631657 0.6461862 -0.1073881 -0.2780622 0.9545415 0.3533195 -0.9232429 0.1509566 -0.1345198 -0.7558286 0.6408022 0.03588056 -0.9835258 0.1771716 0.2084887 -0.9704112 0.121798 -0.3450116 -0.2940414 0.8913511 -0.1683807 -0.759045 0.6288869 -0.4262799 -0.2673607 0.8641781 0.01279783 -0.9998518 -0.01152378 0.009672045 -0.9998568 -0.01388949 0.006796896 -0.9998693 -0.01467442 0.00678873 -0.9998565 0.01552838 0.01085782 -0.9998295 -0.01494443 0.006885588 -0.9998568 -0.01546579 0.004373252 -0.9998546 -0.01649069 0.007394731 -0.9998348 0.01660889 0.003948628 -0.9998676 0.01579225 0.9951848 0 -0.09801679 0.9945202 0.002004384 -0.1045261 0.9569394 -0.001871824 -0.2902817 0.9510512 0.00374186 -0.3090108 0.8819172 -0.003477096 -0.4713916 0.8660109 0.005215048 -0.499998 0.773001 -0.004812479 -0.6343867 0.7431296 0.006418883 -0.6691168 0.6343797 -0.005883991 -0.7729994 0.5877708 0.007353723 -0.8089941 0.4713891 -0.0066877 -0.8819001 0.4067199 0.008024871 -0.9135177 0.2902755 -0.007221221 -0.956916 0.2902749 -0.007221162 0.9569162 0.4067223 0.008025228 0.9135167 0.4713897 -0.006686687 0.8818998 0.5877677 0.007354557 0.8089964 0.6343834 -0.005885004 0.7729963 0.7431295 0.006417214 0.6691169 0.7730008 -0.004814147 0.6343868 0.8660153 0.005213558 0.4999903 0.8819142 -0.003474593 0.4713971 0.9510487 0.003744006 0.3090185 0.9569394 -0.001871883 0.2902817 0.9951825 0.002137541 0.09801656 0.9945222 0 0.1045264 0.004131019 0.9998551 0.01652127 0.9951848 0 0.09801685 0.9945195 -0.002005875 0.1045324 0.9569376 0.001870214 0.290288 0.9510506 -0.003742396 0.3090127 0.881917 0.003476142 0.4713919 0.8660126 -0.005215406 0.4999949 0.7730007 0.004812598 0.6343869 0.7431327 -0.006417393 0.6691133 0.6343801 0.005885422 0.7729989 0.5877676 -0.007353425 0.8089964 0.4713899 0.0066877 0.8818997 0.4067199 -0.00802493 0.9135177 0.2902749 0.007221162 0.9569162 -0.9936924 0.006236016 -0.1119673 -0.9927091 0 -0.1205348 -0.9438714 -0.005356848 -0.33027 -0.9349607 0.01070863 -0.3545897 -0.8466807 -0.009813547 -0.532011 -0.8228972 0.01472145 -0.5679996 -0.7070434 -0.01339137 -0.7070434 -0.6630185 0.01784586 -0.7483903 -0.5319625 -0.01607173 -0.8466154 -0.4646253 0.02008074 -0.8852798 -0.4646248 0.02008396 0.88528 -0.5319681 -0.01607048 0.8466119 -0.6630179 0.01784586 0.7483909 -0.7070437 -0.01339149 0.7070431 -0.8228971 0.01472157 0.5679998 -0.8466806 -0.009813487 0.5320111 -0.9349609 0.01070857 0.3545894 -0.9438723 -0.005359351 0.3302671 -0.9926925 0.005791962 0.1205328 -0.9937115 0 0.1119706 0.2902754 0.007221221 -0.9569159 0.4067227 -0.008025228 -0.9135165 0.4713889 0.006686687 -0.8819001 0.5877676 -0.007354676 -0.8089964 0.6343833 0.005884945 -0.7729964 0.7431295 -0.006417214 -0.6691169 0.7730009 0.004814267 -0.6343867 0.8660138 -0.005213677 -0.499993 0.8819171 0.003477156 -0.4713918 0.9510512 -0.0037418 -0.3090108 0.9569376 0.001870095 -0.290288 0.9951826 -0.002139151 -0.09801661 0.9945214 0 -0.1045327 0.9770447 6.05207e-5 -0.2130344 0.9777134 -0.006995677 -0.2098277 0.9972681 -0.01551347 -0.07222056 0.9968725 -0.001173198 -0.07901883 -0.9760821 -9.95265e-6 0.2174027 -0.9760963 5.59707e-6 0.2173388 -0.9962952 -5.40837e-6 0.08600109 -0.9963277 8.46175e-5 0.08562195 0.2645474 0.8071457 -0.5277599 0.3405374 0.5416844 -0.768513 0.3522021 0.2744581 -0.8947773 0.07351666 0.4071478 -0.9103989 0.004373729 0.9998545 -0.01649272 0.006892561 0.9998567 -0.01546442 0.007147252 0.9998555 -0.01543098 0.01002186 0.9998547 -0.01379406 0.009672045 0.9998568 -0.01388955 0.01279783 0.9998518 -0.01152276 0.01186245 0.9998586 -0.01192414 0.01397514 0.999854 -0.009839892 0.0145747 0.9998584 -0.008414328 0.01546967 0.999854 -0.007262527 0.01603114 0.999858 -0.005208611 0.01646816 0.9998545 -0.004458963 0.016837 0.9998568 -0.001769781 0.01571613 0.9998752 0.001651585 0.01506084 0.9998641 0.006714105 0.6873788 0.7222982 -0.07613068 0.0163381 0.9998666 1.11676e-4 0.01632851 0.9998622 -0.002995371 0.5811165 0.8087819 -0.09041988 0.5386953 0.8414294 0.04247468 0.2749276 0.7994042 -0.5341984 0.2826585 0.741411 -0.6086164 0.01616156 0.9998557 0.005251824 0.01502174 0.9998551 0.008015513 0.01461625 0.9998576 0.008438885 0.006801009 0.9998559 0.01555591 0.006891071 0.9998565 0.01547807 0.009332537 0.9998548 0.01426732 0.009905517 0.999858 0.01363438 0.01159739 0.9998542 0.01253855 0.01250779 0.9998584 0.01126259 0.01351588 0.9998543 0.01043063 0.01186245 -0.9998586 -0.01192384 0.01397508 -0.999854 -0.009839892 0.01457464 -0.9998584 -0.008414447 0.01546967 -0.999854 -0.007263123 0.01603108 -0.999858 -0.00520879 0.01646822 -0.9998545 -0.004458427 0.01683706 -0.9998568 -0.001769244 0.01519751 -0.9998682 -0.005720138 0.01573401 -0.999875 0.001652598 0.01739823 -0.9998254 0.006831169 0.0170893 -0.9998496 0.003000676 0.01749598 -0.9998308 0.005684733 0.01480299 -0.999854 0.008545637 0.014889 -0.9998576 0.007945239 0.01287448 -0.99985 0.01159238 0.01324754 -0.9998601 0.01022416 0.01036578 -0.9998445 0.01426678 0.01124274 -0.999863 0.01215618 0.009332537 -0.9998548 0.01426732 0.9132494 -0.3956173 -0.09727549 0.841054 -0.52604 -0.1261351 0.7892561 -0.6070134 -0.09278821 0.6636012 -0.7440078 -0.07801234 0.5933754 -0.7993035 -0.09497243 0.5161261 -0.8552426 -0.04662495 0.991047 0.112579 -0.07177603 0.9507106 0.274096 -0.1449857 0.01715689 0.802989 -0.595747 0.03822487 0.789702 -0.6122987 0.07552975 0.7751671 -0.6272251 0.03866523 0.7838457 -0.6197509 0.9437015 0.3297599 0.02619171 0 0.1945436 -0.9808939 0 0.3534243 -0.9354631 -0.9999999 -5.8897e-4 -2.72277e-5 -1 -2.86688e-6 -5.62724e-5 -0.9999983 0.001822412 2.68506e-5 -1 -1.05162e-5 1.10176e-4 -0.9999994 -0.001169443 5.2657e-5 -0.3652787 0.03146511 0.9303663 -0.1721546 -0.03775429 0.9843462 0.004943072 0.02518033 0.9996707 0.08046394 -0.009102642 0.996716 0.2634489 0.008526742 0.9646357 0.3228787 -0.0148245 0.9463242 0.4823169 0.01088726 0.8759292 0.5369122 -0.01160466 0.8435583 0.6829942 1.95649e-4 0.7304239 0.7069792 0.01756274 0.7070163 0.8622258 0.02245211 0.5060262 0.8469814 0.001566112 0.5316203 0.9579504 -0.01565957 0.2865062 0.9746547 -0.06454974 0.2141997 0.9018718 0.03292375 0.4307477 0.8663946 -0.03503572 0.4981296 0.7632144 0.02281022 0.6457426 0.6925061 -0.01974886 0.7211418 0.5584239 0.02038311 0.8293053 0.4849378 -0.01026314 0.8744884 0.266604 -0.008169412 0.9637716 0.3247047 0.01521676 0.9456931 0.08067214 0.008671283 0.996703 0.007138431 -0.02531516 0.9996541 -0.172376 0.03792792 0.9843008 -0.3650306 -0.03198736 0.9304459 0.3652645 -0.03145712 0.9303721 0.1721559 0.03774923 0.9843462 -0.004943072 -0.02519321 0.9996704 -0.08047193 0.009101271 0.9967153 -0.263457 -0.008527219 0.9646335 -0.3228912 0.01483058 0.94632 -0.4823057 -0.01087868 0.8759354 -0.5369053 0.01160687 0.8435628 -0.6829802 -1.85622e-4 0.7304369 -0.7069783 -0.01756256 0.7070173 -0.8622291 -0.02244311 0.5060212 -0.8469825 -0.001560986 0.5316186 -0.9579558 0.01567173 0.2864876 -0.9747015 0.06521481 0.2137851 -0.9020975 -0.03361105 0.4302216 -0.8663679 0.03490734 0.498185 -0.7632591 -0.02290868 0.6456864 -0.6924782 0.01969426 0.72117 -0.5583975 -0.02043694 0.8293219 -0.4849364 0.01020979 0.8744899 -0.2665979 0.008169472 0.9637733 -0.3247669 -0.01524555 0.9456712 -0.08065557 -0.008673131 0.9967044 -0.007117271 0.02531027 0.9996544 0.172347 -0.0379191 0.9843062 0.3650158 0.03200197 0.9304512 -0.0348258 -0.3679337 -0.9291996 -0.2009971 -0.4299558 -0.8801921 0.01379847 -0.4688369 -0.8831771 -0.006810367 -0.5376665 -0.8431302 -0.08526945 -0.6019422 -0.793974 0.7998824 -0.393535 -0.453121 0.2711328 -0.6439873 -0.7153792 0.07550173 -0.6817546 -0.7276746 0.007157325 -0.7028079 -0.7113437 0.003139913 -0.64168 -0.7669662 -3.17041e-4 -0.6877177 -0.7259781 -0.04496437 -0.7426302 -0.6681906 -0.003902077 -0.7284586 -0.6850787 0.04387223 -0.7836796 -0.6196143 0.06918358 -0.7772935 -0.6253228 0.03510981 -0.7913367 -0.6103717 0.01595443 -0.8040902 -0.5942932 0.00893414 -0.8123072 -0.5831614 -6.93143e-6 -0.8414359 -0.5403571 -0.0257253 -0.7836049 -0.6207267 -0.006099164 -0.7031544 -0.7110111 5.52156e-4 -0.7520241 -0.6591355 1.99335e-5 -0.7571453 -0.6532465 -0.006613194 -0.812819 -0.5824788 -0.009271204 -0.818469 -0.574476 -0.00546807 -0.8064086 -0.5913335 -6.34422e-4 -0.7754448 -0.6314151 9.59539e-6 -0.831687 -0.5552449 0.008444845 -0.8858742 -0.4638489 0.04678064 -0.8619065 -0.5049048 2.70036e-4 -0.8963077 -0.4434328 -0.004276156 -0.9084839 -0.417898 0.004151761 -0.9565906 -0.2914057 -0.004463434 -0.9712147 -0.2381641 0.004330575 -0.9940513 -0.1088266 -0.004632651 -0.9987489 -0.04979175 0.004490196 -0.9969801 0.07752799 -0.00478363 -0.9900862 0.1403796 0.004630982 -0.9652754 0.2611936 -0.004915475 -0.9455413 0.3254655 0.004753172 -0.9000412 0.435779 -0.005028665 -0.8667296 0.498753 0.004856288 -0.803541 0.5952296 -0.005122244 -0.7565109 0.6539611 0.004942238 -0.6791319 0.7339996 -0.005199372 -0.6188631 0.7854818 0.00500679 -0.5311265 0.8472778 -0.005254805 -0.4587992 0.8885245 0.005054295 -0.3646765 0.9311206 -0.005292356 -0.2821009 0.9593701 0.005082011 -0.1855655 0.9826188 -0.005312919 -0.09518533 0.9954455 0.005091547 0 0.9999871 -0.005311787 0.09518575 0.9954454 0.005082786 0.1855655 0.9826188 -0.005292356 0.282101 0.9593701 0.005055069 0.3646796 0.9311195 -0.005253195 0.4587972 0.8885256 0.005007982 0.531128 0.8472769 -0.005197048 0.6188687 0.7854773 0.004941821 0.679129 0.7340024 -0.00512278 0.7565059 0.6539669 0.004857063 0.8035414 0.595229 -0.005027651 0.8667303 0.4987519 0.004753053 0.900039 0.4357835 -0.004915535 0.9455419 0.3254635 0.004630625 0.9652754 0.2611936 -0.004783809 0.9900862 0.1403796 0.004490017 0.99698 0.07752877 -0.004632592 0.9987488 -0.04979276 0.004330575 0.9940514 -0.108826 -0.004463851 0.9712149 -0.2381634 0.004151642 0.9565896 -0.2914087 -0.004276096 0.9084848 -0.417896 0.00911653 0.8858672 -0.4638493 0.002228081 0.8908359 -0.4543198 0.006986856 0.8771333 -0.4801962 -0.002102255 0.812835 -0.5824903 -0.01777905 0.7844115 -0.619986 -0.008729457 0.8074182 -0.5899151 -0.001382112 0.8379461 -0.5457513 0.001779973 0.8437194 -0.5367816 0.006426632 0.8149762 -0.5794589 0.003789305 0.8207705 -0.5712455 5.5493e-4 0.7522848 -0.6588378 2.26847e-5 0.757261 -0.6531123 -0.01788985 0.6876075 -0.7258622 -1.73249e-4 0.7178849 -0.6961619 -0.005963921 0.7031094 -0.7110568 -0.02600586 0.7836159 -0.6207011 -0.002218961 0.7281021 -0.6854651 0.8126284 0.3821204 -0.440022 0.2906079 0.6396347 -0.711628 0.09412133 0.6788026 -0.7282638 0.003147482 0.6416426 -0.7669973 -0.03557026 0.537336 -0.8426179 -0.00424236 0.5655413 -0.8247092 0.01379019 0.4688525 -0.8831688 -0.09910261 0.3663465 -0.925186 -0.02761763 0.3832573 -0.9232286 -0.02687859 -0.1862754 -0.9821298 -0.1467528 -0.3641619 -0.9197009 0.04336619 -0.3495492 -0.9359139 -0.01380264 -0.4688457 -0.8831722 0.03555768 -0.5373386 -0.8426167 0.004237115 -0.5655334 -0.8247146 -0.8031979 -0.390627 -0.4497597 -0.2763197 -0.6428384 -0.7144272 -0.07854759 -0.6812183 -0.7278543 -0.008409023 -0.7020885 -0.7120401 -0.00314176 -0.6416849 -0.7669619 0.01789361 -0.6876108 -0.725859 1.74279e-4 -0.7179194 -0.6961262 0.002862155 -0.7247695 -0.6889855 -0.03089529 -0.784057 -0.6199194 -0.002934515 -0.8294119 -0.5586298 -0.3419213 -0.8786791 -0.333186 -0.1164273 -0.8185908 -0.5624535 0.02599561 -0.7836416 -0.6206691 0.005957901 -0.7031366 -0.71103 -5.54138e-4 -0.7522583 -0.6588681 -2.02557e-5 -0.7572544 -0.6531201 0.002104759 -0.8128327 -0.5824936 0.01777589 -0.7844176 -0.6199783 0.008731842 -0.8074145 -0.5899199 0.001381278 -0.8379511 -0.5457438 -0.009114325 -0.8858692 -0.4638456 -0.002227723 -0.8908371 -0.4543175 -0.006827712 -0.8764697 -0.4814085 -0.001733899 -0.8441401 -0.53612 0.004275619 -0.9084842 -0.4178974 -0.004151821 -0.9565904 -0.2914066 0.004463613 -0.9712151 -0.2381625 -0.004330635 -0.9940513 -0.1088277 0.004632711 -0.9987489 -0.04979181 -0.004490017 -0.99698 0.07752925 0.004783511 -0.9900863 0.1403793 -0.004630804 -0.9652755 0.2611932 0.004914999 -0.9455413 0.3254655 -0.004752635 -0.9000419 0.4357774 0.005028843 -0.8667294 0.4987534 -0.00485593 -0.8035399 0.5952312 0.005122601 -0.7565101 0.6539619 -0.004942417 -0.6791308 0.7340007 0.005198597 -0.6188657 0.7854797 -0.00500679 -0.5311279 0.8472769 0.005254745 -0.4588016 0.8885232 -0.005054295 -0.3646796 0.9311195 0.005292356 -0.2821012 0.9593701 -0.005082368 -0.1855601 0.9826199 0.005311369 -0.09518533 0.9954454 -0.005093514 0 0.9999871 0.00530982 0.09518581 0.9954454 -0.005082786 0.1855655 0.9826188 0.005291223 0.2821011 0.9593701 -0.005055129 0.3646749 0.9311212 0.005254745 0.4588018 0.8885232 -0.00500679 0.5311304 0.8472753 0.005197465 0.6188653 0.78548 -0.004942238 0.6791288 0.7340026 0.005122423 0.7565075 0.653965 -0.00485748 0.8035418 0.5952286 0.005027294 0.8667305 0.4987516 -0.004753351 0.9000384 0.4357848 0.004915356 0.945542 0.3254634 -0.004630684 0.9652751 0.2611947 0.00478363 0.9900862 0.1403796 -0.004490017 0.9969801 0.07752799 0.004632592 0.9987488 -0.04979276 -0.004330635 0.9940512 -0.1088275 0.004463672 0.971215 -0.2381633 -0.004151761 0.9565904 -0.2914066 0.00427556 0.9084845 -0.4178967 -0.008423328 0.8858743 -0.4638488 -0.04637968 0.8622346 -0.5043814 -2.68803e-4 0.8963106 -0.4434269 0.006619513 0.8128165 -0.5824823 0.00925976 0.8184305 -0.574531 0.005465447 0.8063946 -0.5913527 6.34047e-4 0.7754531 -0.631405 -4.3174e-5 0.8315046 -0.5555179 -0.0399878 0.7838042 -0.6197193 -0.07420319 0.7756202 -0.6268231 -0.03782457 0.7899224 -0.6120393 -0.01719844 0.8029849 -0.5957512 -0.009518921 0.811553 -0.5842013 2.03196e-5 0.8411417 -0.5408149 -5.50563e-4 0.7520279 -0.6591312 -2.13395e-5 0.7571007 -0.6532984 3.15078e-4 0.6877191 -0.725977 0.04491257 0.7425752 -0.6682552 0.006103038 0.7031669 -0.7109987 0.02571594 0.7835975 -0.6207364 0.004652559 0.7253066 -0.6884104 -0.8092633 0.3852366 -0.4434928 -0.2799863 0.6419379 -0.7138091 -0.009346008 0.7032766 -0.710855 -0.003143072 0.6416438 -0.7669965 0.006823778 0.5376672 -0.8431296 0.08527046 0.6019358 -0.7939789 -0.01379269 0.4688608 -0.8831645 0.03480333 0.3679276 -0.9292029 0.3404776 -0.9402525 5.38847e-4 0.1960013 -0.9803941 -0.02027571 0.1849024 -0.9826046 -0.01729738 -0.02172231 -0.9997619 0.00209546 0.06176429 -0.99809 -0.001338064 -0.186935 -0.9823643 -0.003960192 -0.1584157 -0.987372 -0.001061737 -0.01726132 -0.9998488 0.002121627 -0.3035533 -0.9528132 0.001572787 -0.4228625 -0.9061934 -9.22475e-4 -0.4511135 -0.8924453 -0.006176352 -0.6348224 -0.7726388 -0.005470633 -0.6057264 -0.7956719 -0.001387953 -0.7119249 -0.7022538 0.001665174 -0.8079098 -0.5893059 -6.08804e-4 -0.8297327 -0.5580843 -0.009250998 -0.9021481 -0.4314267 -5.05805e-5 -0.9673652 -0.2509329 -0.03517633 -0.9447019 -0.3276575 -0.01338392 -0.9767124 -0.2132201 -0.02387833 -0.9979025 -0.0647248 0.001217961 -0.3184613 -0.9479359 -1.62918e-4 -0.3375368 -0.9413018 -0.004474103 -0.2308323 -0.9729899 0.002706766 -0.06842827 -0.9976491 -0.003730177 -0.07243692 -0.9973636 -0.004340708 -0.006835579 -0.9999765 6.37179e-4 0.09366077 -0.9956027 0.00173825 0.1821781 -0.9832655 -2.64694e-4 0.1309012 -0.9913733 -0.00662887 0.2906643 -0.9568248 7.60719e-4 0.4233564 -0.9059593 -0.002692222 0.390883 -0.9204122 -0.007203221 0.5245506 -0.8513789 8.38469e-4 0.6347829 -0.7726807 -0.003904223 0.6123924 -0.7905161 -0.007741868 0.6974469 -0.7166365 1.62716e-5 0.808045 -0.5891184 -0.001662731 0.7650355 -0.6438281 -0.01435613 0.8411607 -0.5407842 -0.001105666 0.9002945 -0.4352813 -3.20378e-4 0.9287329 -0.3706524 -0.008488059 0.9471211 -0.3208745 -0.001169919 0.9806119 -0.1959601 3.28112e-4 0.9920501 -0.1253895 -0.01068848 0.9977764 -0.06664806 -5.68277e-4 0.3225018 0.946569 -7.3188e-5 0.3378092 0.941208 -0.003534138 0.2314224 0.9728466 0.003640949 0.06278699 0.9980225 -0.003008663 0.07236969 0.997368 -0.004443228 0.006500422 0.9999788 4.48883e-4 -0.0949344 0.9954825 0.001485943 -0.1804498 0.9835841 -4.74915e-4 -0.1317845 0.9912571 -0.006502926 -0.2928839 0.9561477 7.90593e-4 -0.422652 0.9062877 -0.002816319 -0.3945801 0.9188375 -0.006654798 -0.530289 0.8478164 0.001021504 -0.6344994 0.772912 -0.004207074 -0.6203556 0.7842935 -0.006547808 -0.7059158 0.7082957 5.16472e-4 -0.8076458 0.5896627 -0.0025267 -0.7745497 0.632401 -0.01191318 -0.8485016 0.5291931 -1.17483e-4 -0.92892 0.370279 -0.001078665 -0.9061692 0.422685 -0.0139662 -0.9784603 0.2064217 0.002409338 -0.9920381 0.1254931 -0.01057952 -0.9978933 0.06487607 -3.99346e-4 -0.3389233 0.9408027 -0.004626035 -0.3369066 0.9415252 -0.004927277 -0.1989254 0.9800061 0.004101395 -0.06835865 0.9976597 0.001519858 0.06945031 0.9973731 -0.02058351 -0.05851674 0.9982779 -0.004119813 0.1807733 0.9835148 -0.004443764 0.158665 0.9873301 -0.002178251 0.02212929 0.9997547 9.44864e-4 0.3061259 0.9519901 0.001360476 0.4211769 0.9069743 -0.002768099 0.4434825 0.8962619 -0.006151795 0.5415888 0.8406435 5.39751e-4 0.634779 0.7726755 -0.005322217 0.6222914 0.7827782 -0.003423452 0.7071837 0.7070296 6.62683e-4 0.8069666 0.5905597 -0.006674647 0.7823856 0.6227918 -0.001773655 0.8597264 0.5107515 0.001911878 0.9293829 0.3691173 -2.74727e-4 0.9426348 0.3336451 -0.01099556 0.9819151 0.1893216 -1.96666e-4 0.9921281 0.1252267 -4.91999e-4 0.9968192 0.0775792 -0.01824772 -0.5072469 0.8617881 -0.004694104 -0.4567707 0.8889974 -0.03231394 -0.5124111 0.8586699 -0.01099312 -0.5628667 0.8265475 -5.91089e-4 -0.6424475 0.7663288 0.001153767 -0.6658976 0.7459551 -0.01147109 -0.7401616 0.6723937 0.006894588 -0.7929539 0.6090509 -0.01677179 -0.8169323 0.5767284 0.002462148 -0.8925614 0.4509094 -0.003868162 -0.8712773 0.4884756 -0.04761809 -0.9405977 0.3387823 0.02241861 -0.9584614 0.2767496 -0.06900465 0.4591742 0.8883463 -6.23354e-5 0.515546 0.8568606 -0.001568436 0.57095 0.8204329 -0.03009933 0.5121834 0.8588281 -0.009080052 0.6424422 0.7663332 0.001151978 0.6659112 0.7459434 -0.01142984 0.7401551 0.6724011 0.006868362 0.7929698 0.6090317 -0.01671034 0.8169206 0.5767451 0.002447962 0.8922665 0.450532 -0.02969157 0.8824866 0.4703286 -0.002914488 0.5162627 -0.8564302 3.53721e-4 0.4568036 -0.8889956 -0.03189831 0.5123932 -0.8586822 -0.01086246 0.5628718 -0.8265441 -5.85243e-4 0.6423994 -0.7663693 0.00114268 0.6659089 -0.7459474 -0.01130837 0.7400187 -0.6725536 0.006645381 0.7927504 -0.6093197 -0.01662546 0.8169183 -0.5767486 0.002408623 0.882509 -0.4702869 -0.002852857 -0.4591718 -0.8883476 -1.45688e-4 -0.5154054 -0.8569452 -0.001576602 -0.570977 -0.8204092 -0.03023338 -0.5122026 -0.8588157 -0.009181201 -0.6424036 -0.7663657 0.001150846 -0.6658959 -0.7459564 -0.01148456 -0.7400822 -0.672482 0.006804227 -0.7927922 -0.6092581 -0.01689589 -0.8169325 -0.5767281 0.002470612 -0.8921082 -0.4508609 -0.02945131 -0.8824915 -0.4703193 -0.002933382 -0.9406032 -0.3387676 0.02240896 -1 1.83615e-5 0 -1 0 0 -1 1.26192e-5 -6.09354e-7 -1 0 -1.06099e-6 -1 0 -8.70568e-7 -1 3.9548e-6 -7.53754e-7 -1 0 -6.63074e-7 -1 0 -6.02156e-7 -1 2.14789e-6 -5.52033e-7 -1 0 -5.172e-7 -1 0 -4.8819e-7 -1 0 -4.68263e-7 -1 0 -4.52387e-7 -1 0 -4.52387e-7 -1 0 -4.68263e-7 -1 0 -4.8819e-7 -1 0 -5.172e-7 -1 0 -5.52033e-7 -1 -2.53496e-6 -6.02155e-7 -1 3.09877e-6 -6.63074e-7 -1 -3.9548e-6 -7.53754e-7 -1 5.33457e-6 -8.7057e-7 -1 0 -1.06098e-6 -1 -1.26192e-5 -6.09352e-7 -1 -1.83614e-5 0 1 -1.4628e-5 -4.6673e-4 0.9999999 0 -5.59276e-4 1 0 0 1 2.57766e-7 1.27556e-5 1 0 1.27558e-5 -1 0 -1.2756e-5 -1 0 -1.27556e-5 -1 2.46058e-7 0 -1 -2.19675e-7 0 -1 0 -3.94124e-4 -0.9999992 2.54843e-4 0.001217663 1 1.23905e-5 0 1 3.74946e-6 0 1 4.1283e-5 2.00889e-6 1 2.67652e-6 4.18454e-6 0.9999999 -4.77817e-4 -1.7548e-5 1 5.35734e-6 -3.94363e-5 1 4.15604e-4 -1.89179e-5 1 -3.74947e-6 0 1 3.09877e-6 0 1 6.3096e-6 0 1 -1.23905e-5 0 1 1.83614e-5 0 -0.3788934 -0.1819113 -0.9073854 0.06949824 -0.2503689 -0.9656528 0.06953316 0.2503681 -0.9656506 -0.4451729 0.1670483 -0.8797249 -0.9786284 0.1974263 0.05752742 -0.9878927 0.08956426 -0.1266747 -0.9584616 -0.2767487 -0.06900477 -0.9786264 -0.1974409 0.05750989 -0.9883262 -0.09334677 -0.1204072 + + + + + + + + + + + + + + +

253 0 61 0 63 0 255 1 59 1 61 1 180 2 173 2 175 2 179 3 175 3 172 3 180 4 175 4 179 4 178 5 172 5 177 5 178 6 177 6 176 6 245 7 56 7 243 7 243 8 56 8 241 8 241 9 56 9 53 9 241 10 53 10 239 10 239 11 53 11 237 11 237 12 53 12 52 12 237 13 52 13 235 13 235 14 52 14 49 14 235 15 49 15 233 15 233 16 49 16 48 16 233 17 48 17 47 17 233 18 47 18 225 18 225 19 47 19 46 19 225 20 46 20 103 20 103 21 46 21 50 21 103 22 50 22 102 22 267 23 102 23 50 23 267 24 50 24 51 24 271 25 267 25 51 25 271 26 51 26 54 26 271 27 54 27 263 27 263 28 54 28 261 28 261 29 54 29 55 29 261 30 55 30 259 30 262 31 260 31 37 31 266 32 262 32 37 32 266 33 37 33 40 33 266 34 40 34 264 34 264 35 40 35 42 35 264 36 42 36 130 36 222 37 130 37 42 37 222 38 42 38 43 38 223 39 222 39 43 39 223 40 43 40 45 40 228 41 223 41 45 41 228 42 45 42 44 42 234 43 228 43 44 43 234 44 44 44 41 44 236 45 234 45 41 45 236 46 41 46 39 46 238 47 236 47 39 47 238 48 39 48 38 48 240 49 238 49 38 49 242 50 240 50 38 50 234 51 0 51 230 51 230 52 0 52 231 52 0 53 235 53 231 53 0 54 234 54 236 54 235 55 0 55 236 55 235 56 233 56 231 56 221 57 219 57 220 57 220 58 219 58 218 58 382 59 381 59 380 59 381 60 365 60 198 60 365 61 196 61 198 61 382 62 365 62 381 62 382 63 366 63 365 63 208 64 143 64 140 64 208 65 140 65 204 65 383 66 365 66 366 66 367 67 383 67 366 67 384 68 383 68 367 68 351 69 350 69 349 69 352 70 350 70 351 70 353 71 352 71 351 71 354 72 352 72 353 72 355 73 354 73 353 73 27 74 29 74 348 74 347 75 348 75 29 75 29 76 31 76 347 76 346 77 347 77 31 77 31 78 33 78 346 78 345 79 346 79 33 79 33 80 35 80 345 80 343 81 345 81 35 81 35 82 38 82 343 82 341 83 343 83 38 83 38 84 39 84 341 84 339 85 341 85 39 85 39 86 41 86 339 86 333 87 339 87 41 87 41 88 44 88 333 88 330 89 333 89 44 89 44 90 45 90 330 90 327 91 330 91 45 91 334 92 336 92 4 92 2 93 4 93 336 93 336 94 337 94 2 94 1 95 2 95 337 95 337 96 338 96 1 96 3 97 1 97 338 97 338 98 335 98 3 98 5 99 3 99 335 99 335 100 332 100 5 100 7 101 5 101 332 101 332 102 331 102 7 102 9 103 7 103 331 103 331 104 329 104 9 104 11 105 9 105 329 105 329 106 328 106 11 106 13 107 11 107 326 107 11 108 328 108 326 108 326 109 324 109 13 109 15 110 13 110 324 110 324 111 323 111 15 111 17 112 15 112 323 112 323 113 321 113 17 113 19 114 17 114 321 114 321 115 320 115 19 115 21 116 19 116 320 116 320 117 318 117 21 117 23 118 21 118 318 118 318 119 315 119 23 119 24 120 23 120 315 120 315 121 312 121 24 121 26 122 24 122 312 122 312 123 314 123 26 123 25 124 26 124 314 124 314 125 317 125 25 125 1 126 3 126 2 126 4 127 2 127 3 127 3 127 5 127 4 127 6 128 4 128 5 128 5 129 7 129 6 129 8 130 6 130 7 130 7 131 9 131 8 131 10 127 8 127 9 127 9 132 11 132 10 132 12 133 10 133 11 133 11 134 13 134 12 134 14 135 12 135 13 135 13 136 15 136 14 136 16 137 14 137 15 137 15 138 17 138 16 138 18 127 16 127 17 127 17 127 19 127 18 127 20 139 18 139 19 139 19 140 21 140 20 140 22 141 20 141 21 141 21 127 23 127 22 127 25 142 22 142 23 142 23 143 24 143 25 143 26 127 25 127 24 127 45 144 43 144 327 144 43 145 325 145 327 145 322 146 325 146 43 146 43 147 42 147 322 147 319 148 322 148 42 148 42 149 40 149 319 149 313 150 319 150 40 150 40 151 37 151 313 151 310 152 313 152 37 152 37 153 36 153 310 153 308 154 310 154 36 154 36 155 34 155 308 155 306 156 308 156 34 156 34 157 32 157 306 157 304 158 306 158 32 158 32 159 30 159 304 159 305 160 304 160 30 160 30 161 28 161 305 161 29 162 27 162 250 162 28 163 30 163 252 163 250 164 248 164 29 164 254 165 252 165 30 165 31 166 29 166 248 166 30 167 32 167 254 167 248 168 246 168 31 168 246 169 33 169 31 169 256 170 254 170 32 170 258 171 256 171 34 171 256 172 32 172 34 172 246 173 244 173 33 173 35 174 33 174 244 174 34 175 36 175 258 175 260 176 258 176 36 176 244 177 242 177 35 177 242 178 38 178 35 178 36 179 37 179 260 179 63 180 61 180 303 180 302 181 303 181 61 181 61 182 59 182 302 182 301 183 302 183 59 183 59 184 57 184 301 184 300 185 301 185 57 185 57 186 55 186 300 186 298 187 300 187 55 187 55 188 54 188 298 188 296 189 298 189 54 189 54 190 51 190 296 190 294 191 296 191 51 191 51 192 50 192 294 192 292 193 294 193 50 193 50 194 46 194 292 194 290 195 292 195 46 195 46 196 47 196 290 196 288 197 290 197 47 197 47 198 48 198 288 198 48 199 286 199 288 199 284 200 286 200 48 200 48 201 49 201 284 201 282 202 284 202 49 202 49 203 52 203 282 203 280 204 282 204 52 204 52 205 53 205 280 205 278 206 280 206 53 206 53 207 56 207 278 207 276 208 278 208 56 208 56 209 58 209 276 209 274 210 276 210 58 210 58 211 60 211 274 211 272 212 274 212 60 212 60 213 62 213 272 213 273 214 272 214 62 214 62 215 64 215 273 215 245 216 247 216 56 216 257 217 259 217 57 217 259 218 55 218 57 218 58 219 56 219 247 219 57 220 59 220 257 220 247 221 249 221 58 221 249 222 60 222 58 222 255 223 257 223 59 223 62 224 60 224 249 224 253 225 255 225 61 225 249 226 251 226 62 226 64 227 62 227 251 227 189 228 110 228 193 228 110 229 65 229 193 229 67 230 65 230 110 230 110 231 115 231 67 231 66 232 67 232 115 232 115 233 118 233 66 233 72 234 66 234 118 234 118 235 123 235 72 235 74 236 72 236 123 236 123 237 125 237 74 237 224 238 74 238 125 238 125 239 222 239 224 239 223 240 224 240 222 240 193 241 65 241 192 241 69 242 195 242 192 242 195 243 69 243 377 243 65 244 67 244 192 244 75 245 377 245 69 245 192 246 68 246 69 246 68 247 192 247 67 247 67 248 66 248 68 248 70 249 68 249 66 249 68 250 70 250 69 250 69 251 71 251 75 251 71 252 69 252 70 252 66 253 72 253 70 253 76 254 75 254 71 254 73 255 70 255 72 255 70 256 73 256 71 256 71 257 229 257 76 257 229 258 71 258 73 258 72 259 74 259 73 259 230 260 76 260 229 260 73 261 227 261 229 261 227 262 73 262 74 262 74 263 224 263 227 263 377 264 75 264 379 264 79 265 379 265 75 265 75 266 76 266 79 266 80 267 79 267 76 267 76 268 230 268 80 268 231 269 80 269 230 269 77 270 221 270 379 270 221 271 77 271 219 271 78 272 219 272 77 272 219 273 78 273 218 273 83 274 218 274 78 274 379 275 79 275 77 275 84 276 83 276 78 276 81 277 77 277 79 277 77 278 81 278 78 278 82 279 78 279 81 279 78 280 82 280 84 280 79 281 80 281 81 281 85 282 84 282 82 282 80 283 231 283 81 283 232 284 81 284 231 284 81 285 232 285 82 285 226 286 82 286 232 286 82 287 226 287 85 287 86 288 85 288 226 288 86 289 226 289 87 289 218 290 83 290 216 290 89 291 216 291 83 291 83 292 84 292 89 292 94 293 89 293 84 293 84 294 85 294 94 294 85 295 100 295 94 295 85 296 86 296 100 296 86 297 87 297 100 297 103 298 100 298 87 298 225 299 103 299 87 299 150 300 88 300 151 300 88 301 150 301 152 301 91 302 152 302 216 302 152 303 91 303 88 303 151 304 90 304 362 304 90 305 151 305 88 305 216 306 89 306 91 306 106 307 362 307 90 307 88 308 93 308 90 308 93 309 88 309 91 309 89 310 94 310 91 310 92 311 90 311 93 311 90 312 92 312 106 312 95 313 91 313 94 313 91 314 95 314 93 314 107 315 106 315 92 315 96 316 92 316 93 316 92 317 96 317 107 317 93 318 97 318 96 318 97 319 93 319 95 319 94 320 100 320 95 320 101 321 95 321 100 321 95 322 101 322 97 322 108 323 107 323 96 323 96 324 98 324 108 324 98 325 96 325 97 325 99 326 97 326 101 326 97 327 99 327 98 327 98 328 104 328 108 328 104 329 98 329 99 329 99 330 105 330 104 330 105 331 99 331 101 331 100 332 103 332 101 332 101 333 103 333 102 333 109 334 108 334 104 334 101 335 102 335 105 335 102 336 267 336 105 336 268 337 104 337 105 337 104 338 268 338 109 338 269 339 109 339 268 339 105 340 267 340 268 340 362 341 106 341 364 341 111 342 364 342 106 342 106 343 107 343 111 343 121 344 111 344 107 344 107 345 108 345 121 345 124 346 121 346 108 346 108 347 109 347 124 347 127 348 124 348 109 348 109 349 269 349 127 349 270 350 127 350 269 350 110 351 189 351 171 351 171 352 112 352 110 352 112 353 171 353 168 353 170 354 113 354 168 354 113 355 170 355 364 355 168 356 114 356 112 356 114 357 168 357 113 357 364 358 111 358 113 358 115 359 110 359 112 359 111 360 121 360 113 360 116 361 112 361 114 361 112 362 116 362 115 362 119 363 113 363 121 363 113 364 119 364 114 364 114 365 117 365 116 365 117 366 114 366 119 366 118 367 115 367 116 367 120 368 116 368 117 368 116 369 120 369 118 369 122 370 117 370 119 370 117 371 122 371 120 371 123 372 118 372 120 372 126 373 119 373 121 373 119 374 126 374 122 374 120 375 128 375 123 375 128 376 120 376 122 376 121 377 124 377 126 377 129 378 122 378 126 378 122 379 129 379 128 379 125 380 123 380 128 380 124 381 127 381 126 381 128 382 130 382 125 382 130 383 222 383 125 383 131 384 126 384 127 384 126 385 131 385 129 385 127 386 270 386 131 386 130 387 128 387 129 387 264 388 129 388 131 388 129 389 264 389 130 389 270 390 265 390 131 390 131 391 265 391 264 391 201 392 202 392 132 392 202 393 133 393 132 393 139 394 133 394 202 394 133 395 139 395 134 395 139 396 136 396 134 396 136 397 141 397 135 397 141 398 138 398 135 398 141 399 136 399 139 399 351 400 349 400 137 400 137 401 138 401 351 401 138 402 142 402 351 402 142 403 138 403 141 403 202 404 203 404 139 404 139 405 140 405 141 405 139 406 204 406 140 406 139 407 203 407 204 407 353 408 351 408 142 408 144 409 141 409 143 409 141 410 140 410 143 410 141 411 144 411 142 411 142 412 145 412 353 412 145 413 355 413 353 413 145 414 142 414 144 414 357 415 355 415 145 415 143 416 146 416 144 416 146 417 143 417 210 417 210 418 143 418 208 418 147 419 144 419 146 419 144 420 147 420 145 420 148 421 145 421 147 421 145 422 148 422 357 422 148 423 359 423 357 423 210 424 211 424 146 424 149 425 146 425 214 425 146 426 211 426 214 426 146 427 149 427 147 427 361 428 359 428 148 428 147 429 150 429 148 429 150 430 151 430 148 430 150 431 147 431 149 431 148 432 151 432 361 432 214 433 215 433 149 433 152 434 149 434 215 434 152 435 150 435 149 435 361 436 151 436 362 436 216 437 152 437 215 437 178 438 176 438 153 438 153 439 155 439 178 439 162 440 155 440 160 440 155 441 154 441 160 441 154 442 156 442 160 442 155 443 162 443 178 443 160 444 156 444 157 444 157 445 159 445 160 445 350 446 352 446 158 446 352 447 159 447 158 447 159 448 161 448 160 448 161 449 159 449 352 449 352 450 354 450 161 450 181 451 178 451 162 451 160 452 163 452 162 452 163 453 160 453 161 453 164 454 161 454 356 454 161 455 354 455 356 455 161 456 164 456 163 456 165 457 162 457 163 457 162 458 165 458 181 458 165 459 182 459 181 459 356 460 358 460 164 460 185 461 182 461 165 461 166 462 163 462 164 462 163 463 166 463 165 463 167 464 164 464 360 464 164 465 358 465 360 465 164 466 167 466 166 466 165 467 169 467 185 467 169 468 188 468 185 468 169 469 165 469 166 469 360 470 363 470 167 470 190 471 188 471 169 471 168 472 166 472 170 472 166 473 167 473 170 473 166 474 168 474 169 474 170 475 167 475 363 475 169 476 171 476 190 476 169 477 168 477 171 477 363 478 364 478 170 478 189 479 190 479 171 479 179 480 172 480 178 480 178 481 181 481 179 481 179 482 183 482 180 482 183 483 179 483 181 483 184 484 180 484 183 484 180 485 184 485 366 485 184 486 367 486 366 486 181 487 182 487 183 487 368 488 367 488 184 488 186 489 183 489 185 489 183 490 182 490 185 490 183 491 186 491 184 491 187 492 184 492 186 492 184 493 187 493 368 493 187 494 370 494 368 494 185 495 188 495 186 495 372 496 370 496 187 496 186 497 191 497 187 497 191 498 186 498 188 498 187 499 194 499 372 499 194 500 374 500 372 500 194 501 187 501 191 501 188 502 190 502 191 502 191 503 189 503 193 503 191 504 190 504 189 504 191 505 193 505 194 505 376 506 374 506 194 506 195 507 194 507 192 507 194 508 193 508 192 508 194 509 195 509 376 509 377 510 376 510 195 510 196 511 206 511 197 511 206 512 199 512 197 512 206 513 205 513 199 513 206 514 196 514 365 514 199 515 205 515 200 515 205 516 201 516 200 516 205 517 202 517 201 517 205 518 203 518 202 518 204 519 203 519 205 519 205 520 207 520 204 520 207 521 208 521 204 521 207 522 205 522 206 522 206 523 209 523 207 523 206 524 384 524 209 524 384 525 369 525 209 525 212 526 207 526 209 526 207 527 212 527 208 527 212 528 210 528 208 528 209 529 213 529 212 529 213 530 209 530 371 530 209 531 369 531 371 531 211 532 210 532 212 532 371 533 373 533 213 533 212 534 217 534 211 534 217 535 214 535 211 535 217 536 212 536 213 536 213 537 220 537 217 537 220 538 213 538 375 538 213 539 373 539 375 539 215 540 214 540 217 540 217 541 218 541 215 541 218 542 216 542 215 542 218 543 217 543 220 543 375 544 378 544 220 544 221 545 220 545 378 545 378 546 379 546 221 546 223 547 228 547 224 547 228 548 227 548 224 548 233 549 225 549 226 549 225 550 87 550 226 550 226 551 232 551 233 551 229 552 227 552 228 552 228 553 234 553 229 553 234 554 230 554 229 554 233 555 232 555 231 555 237 556 235 556 236 556 236 557 238 557 237 557 239 558 237 558 238 558 238 559 240 559 239 559 241 560 239 560 240 560 240 561 242 561 241 561 243 562 241 562 242 562 242 563 244 563 243 563 245 564 243 564 244 564 244 565 246 565 245 565 247 566 245 566 246 566 246 567 248 567 247 567 249 568 247 568 248 568 248 569 250 569 249 569 251 570 249 570 250 570 252 571 254 571 253 571 255 572 253 572 254 572 254 573 256 573 255 573 257 574 255 574 256 574 256 575 258 575 257 575 259 576 257 576 258 576 258 577 260 577 259 577 261 578 259 578 260 578 260 579 262 579 261 579 263 580 261 580 262 580 262 581 266 581 263 581 271 582 263 582 266 582 266 583 264 583 265 583 265 584 270 584 266 584 270 585 271 585 266 585 271 586 268 586 267 586 271 587 269 587 268 587 271 588 270 588 269 588 274 589 272 589 273 589 273 590 275 590 274 590 276 589 274 589 275 589 275 591 277 591 276 591 278 592 276 592 277 592 277 593 279 593 278 593 280 594 278 594 279 594 279 595 281 595 280 595 282 596 280 596 281 596 281 597 283 597 282 597 284 598 282 598 283 598 283 599 285 599 284 599 286 600 284 600 285 600 285 601 287 601 286 601 288 602 286 602 287 602 287 603 289 603 288 603 290 601 288 601 289 601 289 604 291 604 290 604 292 599 290 599 291 599 291 605 293 605 292 605 294 606 292 606 293 606 293 589 295 589 294 589 296 607 294 607 295 607 295 589 297 589 296 589 298 589 296 589 297 589 297 608 299 608 298 608 300 589 298 589 299 589 299 589 303 589 300 589 301 589 300 589 303 589 303 609 302 609 301 609 306 127 304 127 305 127 305 610 307 610 306 610 308 611 306 611 307 611 307 612 309 612 308 612 310 127 308 127 309 127 309 613 311 613 310 613 313 614 310 614 311 614 316 127 312 127 313 127 319 127 313 127 315 127 313 615 312 615 315 615 315 127 318 127 319 127 322 127 319 127 320 127 319 616 318 616 320 616 320 127 321 127 322 127 325 127 322 127 323 127 322 127 321 127 323 127 323 127 324 127 325 127 327 127 325 127 326 127 325 617 324 617 326 617 326 127 328 127 327 127 330 127 327 127 328 127 328 127 329 127 330 127 333 618 330 618 331 618 330 127 329 127 331 127 331 619 332 619 333 619 339 620 333 620 335 620 333 621 332 621 335 621 335 127 338 127 339 127 341 622 339 622 340 622 339 623 337 623 340 623 339 624 338 624 337 624 340 127 342 127 341 127 343 127 341 127 342 127 342 625 344 625 343 625 345 626 343 626 344 626 344 627 348 627 345 627 346 127 345 127 348 127 348 127 347 127 346 127 356 628 354 628 355 628 355 629 357 629 356 629 358 630 356 630 357 630 357 631 359 631 358 631 360 632 358 632 359 632 359 633 361 633 360 633 363 634 360 634 361 634 361 635 362 635 363 635 364 636 363 636 362 636 368 637 384 637 367 637 369 638 384 638 368 638 368 639 370 639 369 639 371 640 369 640 370 640 370 641 372 641 371 641 373 642 371 642 372 642 372 643 374 643 373 643 375 644 373 644 374 644 374 645 376 645 375 645 378 646 375 646 376 646 376 647 377 647 378 647 379 648 378 648 377 648 173 649 180 649 174 649 180 650 380 650 174 650 180 651 382 651 380 651 366 652 382 652 180 652 365 653 383 653 206 653 383 654 384 654 206 654 389 655 391 655 390 655 392 656 390 656 391 656 391 657 393 657 392 657 394 658 392 658 393 658 393 659 395 659 394 659 396 660 394 660 395 660 395 661 397 661 396 661 398 662 396 662 397 662 397 663 399 663 398 663 400 664 398 664 399 664 399 665 401 665 400 665 402 666 400 666 401 666 401 667 403 667 402 667 404 668 402 668 403 668 403 669 405 669 404 669 406 670 404 670 405 670 413 671 411 671 412 671 412 672 414 672 413 672 415 673 413 673 414 673 414 674 416 674 415 674 417 675 415 675 416 675 416 676 418 676 417 676 419 677 417 677 418 677 418 678 420 678 419 678 421 679 419 679 420 679 420 680 422 680 421 680 421 681 422 681 423 681 424 682 421 682 423 682 340 683 337 683 336 683 425 684 340 684 336 684 336 685 334 685 425 685 425 686 334 686 426 686 427 687 425 687 426 687 426 688 428 688 427 688 427 127 428 127 429 127 430 127 427 127 429 127 429 127 431 127 430 127 430 689 431 689 432 689 433 127 430 127 432 127 432 127 434 127 433 127 435 127 433 127 434 127 434 127 436 127 435 127 435 127 436 127 437 127 438 127 435 127 437 127 437 690 439 690 438 690 438 691 439 691 317 691 316 692 438 692 317 692 317 693 314 693 316 693 316 694 314 694 312 694 311 127 316 127 313 127 253 695 440 695 252 695 441 696 252 696 440 696 440 697 442 697 441 697 443 698 441 698 442 698 442 699 444 699 443 699 445 700 443 700 444 700 444 701 446 701 445 701 447 702 445 702 446 702 446 703 448 703 447 703 449 704 447 704 448 704 448 705 450 705 449 705 451 706 449 706 450 706 452 707 451 707 450 707 453 708 452 708 450 708 451 709 452 709 454 709 451 710 454 710 455 710 456 711 451 711 455 711 457 712 458 712 459 712 460 713 461 713 462 713 462 714 463 714 460 714 464 715 465 715 459 715 458 716 464 716 459 716 466 717 460 717 463 717 467 718 465 718 464 718 463 719 468 719 466 719 469 720 470 720 471 720 469 721 471 721 472 721 469 722 472 722 467 722 464 723 469 723 467 723 466 724 468 724 473 724 470 725 469 725 474 725 473 726 470 726 474 726 474 727 466 727 473 727 469 728 475 728 474 728 476 729 474 729 475 729 475 730 477 730 476 730 478 731 476 731 477 731 477 732 479 732 478 732 480 733 478 733 479 733 479 734 251 734 480 734 250 735 480 735 251 735 482 736 385 736 481 736 385 737 387 737 481 737 489 738 385 738 482 738 487 739 490 739 488 739 389 740 385 740 489 740 491 741 488 741 490 741 488 742 491 742 489 742 492 743 489 743 491 743 492 744 391 744 389 744 489 745 492 745 389 745 490 746 493 746 491 746 393 747 391 747 492 747 491 748 494 748 492 748 491 749 493 749 495 749 494 750 491 750 495 750 492 751 496 751 393 751 496 752 492 752 494 752 395 753 393 753 496 753 495 754 497 754 494 754 494 755 497 755 498 755 499 756 494 756 498 756 494 757 499 757 496 757 500 758 397 758 395 758 496 759 500 759 395 759 500 760 496 760 499 760 498 761 501 761 499 761 399 762 397 762 500 762 499 763 501 763 502 763 503 764 499 764 502 764 499 765 503 765 500 765 502 766 504 766 503 766 505 767 401 767 399 767 500 768 505 768 399 768 505 769 500 769 503 769 403 770 401 770 505 770 503 771 504 771 506 771 503 772 506 772 507 772 508 773 503 773 507 773 503 774 508 774 505 774 505 775 509 775 403 775 505 776 508 776 510 776 509 777 505 777 510 777 403 778 509 778 405 778 516 779 517 779 515 779 516 780 515 780 514 780 513 781 516 781 514 781 518 782 516 782 513 782 518 783 513 783 512 783 511 784 518 784 512 784 518 785 511 785 388 785 519 786 517 786 516 786 388 787 390 787 518 787 520 788 516 788 518 788 520 789 521 789 519 789 516 790 520 790 519 790 518 791 390 791 392 791 522 792 518 792 392 792 518 793 522 793 520 793 523 794 521 794 520 794 392 795 394 795 522 795 524 796 520 796 522 796 524 797 525 797 523 797 520 798 524 798 523 798 526 799 522 799 394 799 522 800 526 800 524 800 394 801 396 801 526 801 527 802 525 802 524 802 524 803 528 803 527 803 528 804 524 804 526 804 529 805 527 805 528 805 526 806 530 806 528 806 526 807 396 807 398 807 530 808 526 808 398 808 398 809 400 809 530 809 531 810 532 810 529 810 528 811 531 811 529 811 531 812 528 812 530 812 533 813 532 813 531 813 530 814 534 814 531 814 530 815 400 815 402 815 534 816 530 816 402 816 402 817 404 817 534 817 535 818 531 818 534 818 538 819 534 819 404 819 404 820 406 820 538 820 517 821 540 821 541 821 515 822 517 822 541 822 542 823 543 823 410 823 410 824 408 824 542 824 543 825 544 825 410 825 545 826 544 826 543 826 545 827 543 827 546 827 547 828 545 828 546 828 548 829 545 829 547 829 548 830 547 830 549 830 540 831 548 831 549 831 548 832 540 832 517 832 517 833 519 833 548 833 412 834 410 834 544 834 550 835 544 835 545 835 550 836 414 836 412 836 544 837 550 837 412 837 551 838 545 838 548 838 545 839 551 839 550 839 548 840 552 840 551 840 548 841 519 841 521 841 552 842 548 842 521 842 521 843 523 843 552 843 416 844 414 844 550 844 553 845 550 845 551 845 550 846 553 846 416 846 554 847 551 847 552 847 551 848 554 848 553 848 552 849 523 849 525 849 555 850 552 850 525 850 552 851 555 851 554 851 418 852 416 852 553 852 525 853 527 853 555 853 556 854 420 854 418 854 553 855 556 855 418 855 556 856 553 856 554 856 557 857 554 857 555 857 554 858 557 858 556 858 555 859 558 859 557 859 555 860 527 860 529 860 558 861 555 861 529 861 422 862 420 862 556 862 529 863 532 863 558 863 559 864 423 864 422 864 556 865 559 865 422 865 559 866 556 866 557 866 560 867 559 867 557 867 560 868 557 868 558 868 558 869 532 869 533 869 560 870 558 870 533 870 561 871 560 871 533 871 537 872 561 872 533 872 487 873 485 873 562 873 563 874 407 874 409 874 564 875 563 875 409 875 565 876 563 876 564 876 566 877 565 877 564 877 567 878 566 878 564 878 487 879 568 879 490 879 569 880 566 880 567 880 562 881 569 881 567 881 568 882 562 882 567 882 562 883 568 883 487 883 409 884 411 884 564 884 564 885 570 885 567 885 564 886 411 886 413 886 570 887 564 887 413 887 567 888 571 888 568 888 571 889 567 889 570 889 493 890 490 890 568 890 413 891 415 891 570 891 572 892 493 892 568 892 572 893 568 893 571 893 495 894 493 894 572 894 570 895 573 895 571 895 573 896 570 896 415 896 571 897 574 897 572 897 574 898 571 898 573 898 415 899 417 899 573 899 575 900 572 900 574 900 575 901 497 901 495 901 572 902 575 902 495 902 498 903 497 903 575 903 573 904 576 904 574 904 573 905 417 905 419 905 576 906 573 906 419 906 574 907 577 907 575 907 577 908 574 908 576 908 578 909 575 909 577 909 578 910 501 910 498 910 575 911 578 911 498 911 419 912 421 912 576 912 502 913 501 913 578 913 576 914 579 914 577 914 576 915 421 915 424 915 576 916 424 916 579 916 577 917 580 917 578 917 577 918 579 918 580 918 578 919 580 919 581 919 581 920 504 920 502 920 578 921 581 921 502 921 506 922 504 922 581 922 452 923 582 923 454 923 583 924 454 924 582 924 582 925 584 925 583 925 585 926 583 926 584 926 584 927 586 927 585 927 587 928 585 928 586 928 586 929 588 929 587 929 589 930 587 930 588 930 588 931 590 931 589 931 591 932 589 932 590 932 590 933 424 933 591 933 423 934 591 934 424 934 454 935 592 935 455 935 593 936 455 936 592 936 455 937 593 937 456 937 592 938 583 938 593 938 594 939 456 939 593 939 595 940 593 940 583 940 593 941 595 941 594 941 583 942 585 942 595 942 596 943 456 943 594 943 597 944 595 944 585 944 595 945 597 945 594 945 594 946 598 946 596 946 598 947 594 947 597 947 585 948 587 948 597 948 597 949 599 949 598 949 599 950 597 950 587 950 587 951 589 951 599 951 600 952 596 952 598 952 601 953 598 953 599 953 598 954 601 954 600 954 602 955 599 955 589 955 599 956 602 956 601 956 589 957 603 957 602 957 604 958 600 958 601 958 601 959 605 959 604 959 605 960 601 960 602 960 602 961 606 961 605 961 606 962 602 962 603 962 603 963 591 963 606 963 607 964 604 964 605 964 606 965 559 965 605 965 559 966 606 966 591 966 561 967 607 967 605 967 591 968 423 968 559 968 560 969 605 969 559 969 605 970 560 970 561 970 614 971 608 971 596 971 596 972 600 972 614 972 609 973 614 973 600 973 600 974 604 974 609 974 623 975 609 975 604 975 604 976 607 976 623 976 610 977 623 977 607 977 607 978 561 978 610 978 610 979 561 979 537 979 611 980 462 980 461 980 461 981 608 981 611 981 463 982 462 982 611 982 612 983 463 983 611 983 611 984 613 984 612 984 613 985 611 985 608 985 468 986 463 986 612 986 608 987 614 987 613 987 612 988 615 988 468 988 473 989 468 989 615 989 614 990 609 990 613 990 616 991 612 991 613 991 612 992 616 992 615 992 613 993 617 993 616 993 617 994 613 994 609 994 618 995 615 995 616 995 615 996 618 996 473 996 619 997 470 997 473 997 473 998 620 998 619 998 620 999 473 999 618 999 616 1000 621 1000 618 1000 621 1001 616 1001 617 1001 617 1002 622 1002 621 1002 622 1003 617 1003 609 1003 609 1004 623 1004 622 1004 618 1005 624 1005 620 1005 624 1006 618 1006 621 1006 625 1007 626 1007 619 1007 620 1008 625 1008 619 1008 625 1009 620 1009 624 1009 623 1010 610 1010 622 1010 621 1011 535 1011 624 1011 535 1012 621 1012 622 1012 627 1013 622 1013 610 1013 622 1014 627 1014 535 1014 624 1015 539 1015 625 1015 539 1016 624 1016 535 1016 627 1017 610 1017 536 1017 535 1018 627 1018 536 1018 538 1019 406 1019 626 1019 625 1020 538 1020 626 1020 610 1021 537 1021 536 1021 470 1022 619 1022 471 1022 628 1023 471 1023 619 1023 619 1024 626 1024 628 1024 629 1025 628 1025 626 1025 626 1026 406 1026 629 1026 405 1027 629 1027 406 1027 630 1028 457 1028 459 1028 459 1029 631 1029 630 1029 459 1030 465 1030 631 1030 465 1031 632 1031 631 1031 633 1032 631 1032 632 1032 631 1033 633 1033 630 1033 465 1034 467 1034 632 1034 646 1035 630 1035 633 1035 467 1036 634 1036 632 1036 467 1037 472 1037 634 1037 635 1038 632 1038 634 1038 632 1039 635 1039 633 1039 636 1040 646 1040 633 1040 633 1041 637 1041 636 1041 637 1042 633 1042 635 1042 472 1043 638 1043 634 1043 472 1044 471 1044 638 1044 639 1045 634 1045 638 1045 634 1046 639 1046 635 1046 471 1047 628 1047 638 1047 640 1048 636 1048 637 1048 641 1049 637 1049 635 1049 637 1050 641 1050 640 1050 642 1051 638 1051 628 1051 638 1052 642 1052 639 1052 635 1053 643 1053 641 1053 643 1054 635 1054 639 1054 644 1055 639 1055 642 1055 639 1056 644 1056 643 1056 628 1057 629 1057 642 1057 507 1058 641 1058 643 1058 641 1059 507 1059 640 1059 508 1060 643 1060 644 1060 643 1061 508 1061 507 1061 506 1062 640 1062 507 1062 644 1063 510 1063 508 1063 510 1064 644 1064 642 1064 642 1065 509 1065 510 1065 509 1066 642 1066 629 1066 629 1067 405 1067 509 1067 630 1068 646 1068 645 1068 647 1069 645 1069 646 1069 646 1070 636 1070 647 1070 648 1071 647 1071 636 1071 636 1072 640 1072 648 1072 649 1073 648 1073 640 1073 640 1074 506 1074 649 1074 581 1075 649 1075 506 1075 453 1076 650 1076 452 1076 453 1077 450 1077 651 1077 650 1078 453 1078 651 1078 582 1079 452 1079 650 1079 652 1080 650 1080 651 1080 650 1081 652 1081 582 1081 653 1082 582 1082 652 1082 651 1083 654 1083 652 1083 584 1084 653 1084 652 1084 655 1085 652 1085 654 1085 652 1086 655 1086 584 1086 656 1087 584 1087 655 1087 651 1088 630 1088 654 1088 654 1089 630 1089 645 1089 657 1090 654 1090 645 1090 654 1091 657 1091 655 1091 655 1092 658 1092 656 1092 658 1093 655 1093 657 1093 586 1094 656 1094 658 1094 659 1095 657 1095 645 1095 657 1096 659 1096 658 1096 645 1097 647 1097 659 1097 588 1098 586 1098 658 1098 658 1099 660 1099 588 1099 660 1100 658 1100 659 1100 659 1101 661 1101 660 1101 661 1102 659 1102 647 1102 647 1103 648 1103 661 1103 590 1104 588 1104 660 1104 662 1105 661 1105 648 1105 661 1106 662 1106 660 1106 663 1107 660 1107 662 1107 660 1108 663 1108 590 1108 648 1109 649 1109 662 1109 662 1110 580 1110 663 1110 580 1111 662 1111 649 1111 649 1112 581 1112 580 1112 424 1113 590 1113 663 1113 579 1114 663 1114 580 1114 663 1115 579 1115 424 1115 475 1116 670 1116 671 1116 477 1117 475 1117 671 1117 479 1118 477 1118 671 1118 442 1119 440 1119 673 1119 671 1120 674 1120 479 1120 479 1121 674 1121 64 1121 251 1122 479 1122 64 1122 253 1123 63 1123 673 1123 440 1124 253 1124 673 1124 287 1125 285 1125 664 1125 665 1126 664 1126 285 1126 285 1127 283 1127 665 1127 666 1128 665 1128 283 1128 283 1129 281 1129 666 1129 670 1130 666 1130 281 1130 281 1131 279 1131 670 1131 671 1132 670 1132 279 1132 279 1133 277 1133 671 1133 674 1134 671 1134 277 1134 277 1135 275 1135 674 1135 64 1136 674 1136 275 1136 275 1137 273 1137 64 1137 303 1138 299 1138 63 1138 673 1139 63 1139 299 1139 299 1140 297 1140 673 1140 672 1141 673 1141 297 1141 297 1142 295 1142 672 1142 669 1143 672 1143 295 1143 295 1144 293 1144 669 1144 667 1145 669 1145 293 1145 293 1146 291 1146 667 1146 668 1147 667 1147 291 1147 291 1148 289 1148 668 1148 668 1149 289 1149 287 1149 664 1150 668 1150 287 1150 252 1151 441 1151 28 1151 433 1152 435 1152 684 1152 685 1153 684 1153 435 1153 435 1154 438 1154 685 1154 681 1155 685 1155 438 1155 438 1156 316 1156 681 1156 680 1157 681 1157 316 1157 316 1158 311 1158 680 1158 678 1159 680 1159 311 1159 311 1160 309 1160 678 1160 676 1161 678 1161 309 1161 309 1162 307 1162 676 1162 28 1163 676 1163 307 1163 307 1164 305 1164 28 1164 16 1165 434 1165 432 1165 14 1166 16 1166 432 1166 436 1167 434 1167 16 1167 16 1168 18 1168 436 1168 437 1169 436 1169 18 1169 18 1170 20 1170 437 1170 439 1171 437 1171 20 1171 20 1172 22 1172 439 1172 317 1173 439 1173 22 1173 22 1174 25 1174 317 1174 4 1175 6 1175 334 1175 426 1176 334 1176 6 1176 6 1177 8 1177 426 1177 428 1178 426 1178 8 1178 8 1179 10 1179 428 1179 429 1180 428 1180 10 1180 10 1181 12 1181 429 1181 431 1182 429 1182 12 1182 12 1183 14 1183 431 1183 432 1184 431 1184 14 1184 348 1185 344 1185 27 1185 675 1186 27 1186 344 1186 344 1187 342 1187 675 1187 677 1188 675 1188 342 1188 342 1189 340 1189 677 1189 679 1190 677 1190 340 1190 340 1191 425 1191 679 1191 682 1192 679 1192 425 1192 425 1193 427 1193 682 1193 683 1194 682 1194 427 1194 427 1195 430 1195 683 1195 683 1196 430 1196 433 1196 684 1197 683 1197 433 1197 388 1198 389 1198 390 1198 385 1199 389 1199 388 1199 385 1200 388 1200 386 1200 385 1201 386 1201 387 1201 410 1202 412 1202 411 1202 409 1203 410 1203 411 1203 408 1204 410 1204 409 1204 407 1205 408 1205 409 1205 533 1206 536 1206 537 1206 534 1207 539 1207 535 1207 534 1208 538 1208 539 1208 538 1209 625 1209 539 1209 480 1210 250 1210 27 1210 480 1211 27 1211 675 1211 478 1212 480 1212 675 1212 478 1213 675 1213 677 1213 476 1214 478 1214 677 1214 476 1215 677 1215 679 1215 474 1216 476 1216 679 1216 466 1217 474 1217 679 1217 466 1218 679 1218 682 1218 460 1219 466 1219 682 1219 460 1220 682 1220 683 1220 460 1221 683 1221 461 1221 461 1222 683 1222 684 1222 456 1223 684 1223 685 1223 451 1224 456 1224 685 1224 461 1225 686 1225 608 1225 456 1226 686 1226 684 1226 686 1227 461 1227 684 1227 596 1228 608 1228 686 1228 456 1229 596 1229 686 1229 531 1230 536 1230 533 1230 531 1231 535 1231 536 1231 451 1232 685 1232 681 1232 449 1233 451 1233 681 1233 449 1234 681 1234 680 1234 441 1235 443 1235 28 1235 443 1236 676 1236 28 1236 443 1237 445 1237 676 1237 445 1238 678 1238 676 1238 445 1239 447 1239 678 1239 447 1240 680 1240 678 1240 447 1241 449 1241 680 1241 469 1242 670 1242 475 1242 464 1243 670 1243 469 1243 464 1244 666 1244 670 1244 458 1245 666 1245 464 1245 458 1246 665 1246 666 1246 457 1247 665 1247 458 1247 457 1248 664 1248 665 1248 457 1249 630 1249 664 1249 630 1250 668 1250 664 1250 630 1251 651 1251 668 1251 450 1252 667 1252 651 1252 651 1253 667 1253 668 1253 450 1254 669 1254 667 1254 448 1255 669 1255 450 1255 448 1256 672 1256 669 1256 446 1257 672 1257 448 1257 446 1258 673 1258 672 1258 444 1259 673 1259 446 1259 442 1260 673 1260 444 1260 482 1261 483 1261 489 1261 483 1262 488 1262 489 1262 483 1263 486 1263 488 1263 484 1264 488 1264 486 1264 484 1265 487 1265 488 1265 484 1266 485 1266 487 1266 386 1267 388 1267 687 1267 388 1268 511 1268 687 1268 841 1269 766 1269 765 1269 841 1270 767 1270 766 1270 841 1271 768 1271 767 1271 841 1272 839 1272 768 1272 789 1273 687 1273 511 1273 386 1274 687 1274 906 1274 906 1275 687 1275 789 1275 380 1276 820 1276 819 1276 380 1277 821 1277 820 1277 381 1278 821 1278 380 1278 381 1279 822 1279 821 1279 381 1280 823 1280 822 1280 785 1281 783 1281 711 1281 783 1282 784 1282 711 1282 710 1283 711 1283 784 1283 784 1284 782 1284 710 1284 709 1285 710 1285 782 1285 782 1286 742 1286 709 1286 708 1287 709 1287 742 1287 742 1288 743 1288 708 1288 707 1289 708 1289 744 1289 708 1290 743 1290 744 1290 706 1291 707 1291 745 1291 707 1292 744 1292 745 1292 706 1293 745 1293 746 1293 705 1294 715 1294 716 1294 716 1295 713 1295 705 1295 704 1296 705 1296 713 1296 713 1297 714 1297 704 1297 703 1298 704 1298 714 1298 714 1299 712 1299 703 1299 702 1300 703 1300 712 1300 700 1301 702 1301 790 1301 702 1302 712 1302 790 1302 790 1303 791 1303 700 1303 701 1304 700 1304 791 1304 791 1305 792 1305 701 1305 792 1306 793 1306 701 1306 800 1307 798 1307 689 1307 798 1308 799 1308 689 1308 688 1309 689 1309 799 1309 799 1310 797 1310 688 1310 690 1311 688 1311 797 1311 797 1312 726 1312 690 1312 693 1313 690 1313 726 1313 726 1314 727 1314 693 1314 692 1315 693 1315 728 1315 693 1316 727 1316 728 1316 691 1317 692 1317 729 1317 692 1318 728 1318 729 1318 691 1319 729 1319 730 1319 695 1320 760 1320 761 1320 761 1321 758 1321 695 1321 694 1322 695 1322 758 1322 758 1323 759 1323 694 1323 696 1324 694 1324 759 1324 759 1325 757 1325 696 1325 697 1326 696 1326 757 1326 698 1327 697 1327 772 1327 697 1328 757 1328 772 1328 772 1329 773 1329 698 1329 699 1330 698 1330 773 1330 773 1331 774 1331 699 1331 774 1332 775 1332 699 1332 825 1333 823 1333 804 1333 823 1334 805 1334 804 1334 804 1335 803 1335 825 1335 827 1336 825 1336 802 1336 825 1337 803 1337 802 1337 838 1338 840 1338 741 1338 840 1339 740 1339 741 1339 840 1340 739 1340 740 1340 840 1341 738 1341 739 1341 802 1342 801 1342 827 1342 829 1343 827 1343 800 1343 827 1344 801 1344 800 1344 737 1345 738 1345 840 1345 840 1346 842 1346 737 1346 842 1347 736 1347 737 1347 842 1348 735 1348 736 1348 842 1349 734 1349 735 1349 842 1350 733 1350 734 1350 842 1351 732 1351 733 1351 688 1352 690 1352 689 1352 800 1353 689 1353 690 1353 690 1354 693 1354 800 1354 693 1355 829 1355 800 1355 831 1356 829 1356 730 1356 829 1357 691 1357 730 1357 829 1358 692 1358 691 1358 829 1359 693 1359 692 1359 731 1360 732 1360 842 1360 842 1361 844 1361 731 1361 844 1362 730 1362 731 1362 844 1363 831 1363 730 1363 833 1364 831 1364 844 1364 844 1365 846 1365 833 1365 834 1366 833 1366 846 1366 846 1367 848 1367 834 1367 836 1368 834 1368 848 1368 848 1369 850 1369 836 1369 835 1370 836 1370 850 1370 850 1371 852 1371 835 1371 832 1372 835 1372 852 1372 852 1373 854 1373 832 1373 830 1374 832 1374 854 1374 854 1375 856 1375 830 1375 828 1376 830 1376 856 1376 856 1377 858 1377 828 1377 826 1378 828 1378 858 1378 858 1379 860 1379 826 1379 824 1380 826 1380 860 1380 860 1381 863 1381 824 1381 822 1382 824 1382 863 1382 863 1383 864 1383 822 1383 821 1384 822 1384 864 1384 864 1385 862 1385 821 1385 820 1386 821 1386 862 1386 862 1387 861 1387 820 1387 818 1388 820 1388 861 1388 861 1389 859 1389 818 1389 816 1390 818 1390 859 1390 859 1391 857 1391 816 1391 814 1392 816 1392 857 1392 857 1393 855 1393 814 1393 812 1394 814 1394 855 1394 855 1395 853 1395 812 1395 810 1396 812 1396 853 1396 853 1397 851 1397 810 1397 808 1398 810 1398 851 1398 851 1399 849 1399 808 1399 806 1400 808 1400 849 1400 849 1401 847 1401 806 1401 807 1402 806 1402 847 1402 847 1403 845 1403 807 1403 809 1404 807 1404 845 1404 845 1405 843 1405 809 1405 811 1406 809 1406 843 1406 843 1407 841 1407 760 1407 760 1408 811 1408 843 1408 841 1409 762 1409 760 1409 813 1410 811 1410 696 1410 811 1411 694 1411 696 1411 811 1412 695 1412 694 1412 811 1413 760 1413 695 1413 763 1414 762 1414 841 1414 765 1415 764 1415 841 1415 764 1416 763 1416 841 1416 696 1417 697 1417 775 1417 775 1418 813 1418 696 1418 815 1419 813 1419 776 1419 813 1420 775 1420 776 1420 699 1421 775 1421 697 1421 697 1422 698 1422 699 1422 769 1423 768 1423 839 1423 839 1424 837 1424 771 1424 771 1425 770 1425 839 1425 770 1426 769 1426 839 1426 776 1427 777 1427 815 1427 817 1428 815 1428 778 1428 815 1429 777 1429 778 1429 778 1430 779 1430 817 1430 819 1431 817 1431 780 1431 817 1432 779 1432 780 1432 387 1433 910 1433 481 1433 910 1434 912 1434 481 1434 912 1435 482 1435 481 1435 796 1436 482 1436 912 1436 912 1437 914 1437 796 1437 914 1438 795 1438 796 1438 890 1439 892 1439 725 1439 725 1440 724 1440 890 1440 724 1441 723 1441 890 1441 723 1442 722 1442 890 1442 794 1443 795 1443 914 1443 914 1444 916 1444 794 1444 916 1445 793 1445 794 1445 722 1446 721 1446 890 1446 888 1447 890 1447 719 1447 719 1448 718 1448 888 1448 890 1449 720 1449 719 1449 890 1450 721 1450 720 1450 702 1451 700 1451 701 1451 701 1452 793 1452 702 1452 703 1453 702 1453 793 1453 793 1454 916 1454 703 1454 916 1455 918 1455 703 1455 918 1456 704 1456 703 1456 918 1457 705 1457 704 1457 918 1458 715 1458 705 1458 886 1459 888 1459 715 1459 715 1460 918 1460 886 1460 888 1461 717 1461 715 1461 888 1462 718 1462 717 1462 918 1463 920 1463 886 1463 884 1464 886 1464 920 1464 920 1465 921 1465 884 1465 882 1466 884 1466 921 1466 921 1467 922 1467 882 1467 880 1468 882 1468 922 1468 922 1469 923 1469 880 1469 878 1470 880 1470 923 1470 923 1471 919 1471 878 1471 876 1472 878 1472 919 1472 919 1473 917 1473 876 1473 874 1474 876 1474 917 1474 917 1475 915 1475 874 1475 872 1476 874 1476 915 1476 915 1477 913 1477 872 1477 870 1478 872 1478 913 1478 913 1479 911 1479 870 1479 868 1480 870 1480 911 1480 911 1481 909 1481 868 1481 866 1482 868 1482 909 1482 909 1483 908 1483 866 1483 865 1484 866 1484 908 1484 908 1485 907 1485 865 1485 867 1486 865 1486 907 1486 907 1487 905 1487 867 1487 869 1488 867 1488 905 1488 905 1489 903 1489 869 1489 871 1490 869 1490 903 1490 903 1491 901 1491 871 1491 873 1492 871 1492 901 1492 901 1493 899 1493 873 1493 875 1494 873 1494 899 1494 899 1495 897 1495 875 1495 877 1496 875 1496 897 1496 897 1497 895 1497 877 1497 879 1498 877 1498 895 1498 895 1499 893 1499 879 1499 881 1500 879 1500 893 1500 893 1501 894 1501 881 1501 883 1502 881 1502 894 1502 894 1503 896 1503 883 1503 885 1504 883 1504 896 1504 896 1505 898 1505 885 1505 887 1506 885 1506 747 1506 885 1507 746 1507 747 1507 885 1508 898 1508 746 1508 898 1509 900 1509 746 1509 900 1510 706 1510 746 1510 900 1511 707 1511 706 1511 900 1512 708 1512 707 1512 747 1513 748 1513 887 1513 889 1514 887 1514 753 1514 887 1515 752 1515 753 1515 887 1516 751 1516 752 1516 887 1517 750 1517 751 1517 887 1518 749 1518 750 1518 887 1519 748 1519 749 1519 709 1520 708 1520 785 1520 708 1521 900 1521 785 1521 900 1522 902 1522 785 1522 902 1523 786 1523 785 1523 785 1524 711 1524 709 1524 710 1525 709 1525 711 1525 753 1526 754 1526 889 1526 891 1527 889 1527 756 1527 889 1528 755 1528 756 1528 889 1529 754 1529 755 1529 787 1530 786 1530 902 1530 902 1531 904 1531 787 1531 904 1532 788 1532 787 1532 789 1533 788 1533 904 1533 904 1534 906 1534 789 1534 790 1535 712 1535 485 1535 562 1536 485 1536 712 1536 712 1537 714 1537 562 1537 562 1538 713 1538 716 1538 562 1539 714 1539 713 1539 569 1540 562 1540 717 1540 562 1541 715 1541 717 1541 562 1542 716 1542 715 1542 717 1543 718 1543 569 1543 566 1544 569 1544 719 1544 569 1545 718 1545 719 1545 565 1546 566 1546 720 1546 566 1547 719 1547 720 1547 720 1548 721 1548 565 1548 563 1549 565 1549 722 1549 565 1550 721 1550 722 1550 722 1551 723 1551 563 1551 407 1552 563 1552 724 1552 563 1553 723 1553 724 1553 724 1554 725 1554 407 1554 407 1555 725 1555 892 1555 201 1556 132 1556 797 1556 132 1557 726 1557 797 1557 727 1558 726 1558 132 1558 132 1559 133 1559 727 1559 133 1560 728 1560 727 1560 133 1561 729 1561 728 1561 730 1562 729 1562 133 1562 133 1563 134 1563 730 1563 134 1564 731 1564 730 1564 732 1565 731 1565 134 1565 134 1566 136 1566 732 1566 136 1567 733 1567 732 1567 734 1568 733 1568 136 1568 136 1569 135 1569 734 1569 135 1570 735 1570 734 1570 736 1571 735 1571 135 1571 135 1572 138 1572 736 1572 138 1573 737 1573 736 1573 138 1574 738 1574 737 1574 739 1575 738 1575 138 1575 138 1576 137 1576 739 1576 137 1577 740 1577 739 1577 741 1578 740 1578 137 1578 137 1579 349 1579 741 1579 838 1580 741 1580 349 1580 515 1581 541 1581 782 1581 541 1582 742 1582 782 1582 743 1583 742 1583 541 1583 541 1584 540 1584 743 1584 540 1585 744 1585 743 1585 540 1586 745 1586 744 1586 746 1587 745 1587 540 1587 540 1588 549 1588 746 1588 549 1589 747 1589 746 1589 748 1590 747 1590 549 1590 549 1591 547 1591 748 1591 547 1592 749 1592 748 1592 750 1593 749 1593 547 1593 547 1594 546 1594 750 1594 546 1595 751 1595 750 1595 752 1596 751 1596 546 1596 546 1597 543 1597 752 1597 543 1598 753 1598 752 1598 754 1599 753 1599 543 1599 543 1600 542 1600 754 1600 542 1601 755 1601 754 1601 756 1602 755 1602 542 1602 542 1603 408 1603 756 1603 891 1604 756 1604 408 1604 772 1605 757 1605 176 1605 153 1606 176 1606 757 1606 757 1607 759 1607 153 1607 155 1608 153 1608 761 1608 153 1609 758 1609 761 1609 153 1610 759 1610 758 1610 154 1611 155 1611 762 1611 155 1612 760 1612 762 1612 155 1613 761 1613 760 1613 762 1614 763 1614 154 1614 156 1615 154 1615 764 1615 154 1616 763 1616 764 1616 764 1617 765 1617 156 1617 157 1618 156 1618 766 1618 156 1619 765 1619 766 1619 766 1620 767 1620 157 1620 159 1621 157 1621 768 1621 157 1622 767 1622 768 1622 768 1623 769 1623 159 1623 158 1624 159 1624 770 1624 159 1625 769 1625 770 1625 770 1626 771 1626 158 1626 350 1627 158 1627 837 1627 158 1628 771 1628 837 1628 176 1629 177 1629 772 1629 177 1630 773 1630 772 1630 177 1631 774 1631 773 1631 177 1632 775 1632 774 1632 776 1633 775 1633 177 1633 177 1634 172 1634 776 1634 777 1635 776 1635 172 1635 172 1636 175 1636 777 1636 778 1637 777 1637 175 1637 175 1638 173 1638 778 1638 173 1639 779 1639 778 1639 780 1640 779 1640 173 1640 173 1641 174 1641 780 1641 782 1642 784 1642 515 1642 514 1643 515 1643 785 1643 515 1644 783 1644 785 1644 515 1645 784 1645 783 1645 785 1646 786 1646 514 1646 513 1647 514 1647 786 1647 786 1648 787 1648 513 1648 512 1649 513 1649 787 1649 787 1650 788 1650 512 1650 511 1651 512 1651 789 1651 512 1652 788 1652 789 1652 485 1653 484 1653 790 1653 484 1654 791 1654 790 1654 484 1655 792 1655 791 1655 484 1656 793 1656 792 1656 794 1657 793 1657 484 1657 484 1658 486 1658 794 1658 795 1659 794 1659 486 1659 486 1660 483 1660 795 1660 796 1661 795 1661 483 1661 483 1662 482 1662 796 1662 797 1663 799 1663 201 1663 200 1664 201 1664 800 1664 201 1665 798 1665 800 1665 201 1666 799 1666 798 1666 800 1667 801 1667 200 1667 199 1668 200 1668 801 1668 801 1669 802 1669 199 1669 197 1670 199 1670 802 1670 802 1671 803 1671 197 1671 196 1672 197 1672 804 1672 197 1673 803 1673 804 1673 804 1674 805 1674 196 1674 808 1675 806 1675 807 1675 807 1676 809 1676 808 1676 810 1677 808 1677 809 1677 809 1678 811 1678 810 1678 812 1679 810 1679 811 1679 811 1680 813 1680 812 1680 814 1681 812 1681 813 1681 813 1682 815 1682 814 1682 816 1683 814 1683 815 1683 815 1684 817 1684 816 1684 818 1685 816 1685 817 1685 817 1686 819 1686 818 1686 820 1687 818 1687 819 1687 824 1688 822 1688 823 1688 823 1689 825 1689 824 1689 826 1690 824 1690 825 1690 825 1691 827 1691 826 1691 828 1692 826 1692 827 1692 827 1693 829 1693 828 1693 830 1694 828 1694 829 1694 829 1695 831 1695 830 1695 832 1696 830 1696 831 1696 831 1697 833 1697 832 1697 835 1698 832 1698 833 1698 833 1676 834 1676 835 1676 836 1699 835 1699 834 1699 350 1700 837 1700 349 1700 838 1701 349 1701 837 1701 837 1702 839 1702 838 1702 840 1702 838 1702 839 1702 839 1702 841 1702 840 1702 842 1702 840 1702 841 1702 841 1702 843 1702 842 1702 844 1702 842 1702 843 1702 843 1702 845 1702 844 1702 846 1702 844 1702 845 1702 845 1702 847 1702 846 1702 848 1702 846 1702 847 1702 847 1702 849 1702 848 1702 850 1702 848 1702 849 1702 849 1702 851 1702 850 1702 852 1702 850 1702 851 1702 851 1702 853 1702 852 1702 854 1702 852 1702 853 1702 853 1702 855 1702 854 1702 856 1702 854 1702 855 1702 855 1702 857 1702 856 1702 858 1702 856 1702 857 1702 857 1702 859 1702 858 1702 860 1702 858 1702 859 1702 859 1703 861 1703 860 1703 863 1704 860 1704 861 1704 861 1702 862 1702 863 1702 864 1702 863 1702 862 1702 865 1676 867 1676 866 1676 868 1676 866 1676 867 1676 867 1705 869 1705 868 1705 870 1706 868 1706 869 1706 869 1676 871 1676 870 1676 872 1676 870 1676 871 1676 871 1676 873 1676 872 1676 874 1676 872 1676 873 1676 873 1676 875 1676 874 1676 876 1707 874 1707 875 1707 875 1708 877 1708 876 1708 878 1676 876 1676 877 1676 877 1676 879 1676 878 1676 880 1676 878 1676 879 1676 879 1676 881 1676 880 1676 882 1676 880 1676 881 1676 881 1676 883 1676 882 1676 884 1676 882 1676 883 1676 883 1676 885 1676 884 1676 886 1676 884 1676 885 1676 885 1676 887 1676 886 1676 888 1676 886 1676 887 1676 887 1676 889 1676 888 1676 890 1676 888 1676 889 1676 889 1676 891 1676 890 1676 892 1676 890 1676 891 1676 891 1709 408 1709 892 1709 407 1710 892 1710 408 1710 893 1702 895 1702 894 1702 896 1711 894 1711 895 1711 895 1702 897 1702 896 1702 898 1702 896 1702 897 1702 897 1702 899 1702 898 1702 900 1702 898 1702 899 1702 899 1702 901 1702 900 1702 902 1702 900 1702 901 1702 901 1702 903 1702 902 1702 904 1712 902 1712 903 1712 903 1702 905 1702 904 1702 906 1702 904 1702 905 1702 905 1702 907 1702 906 1702 386 1713 906 1713 907 1713 907 1714 908 1714 386 1714 386 1715 908 1715 387 1715 908 1716 909 1716 387 1716 910 1717 387 1717 909 1717 909 1702 911 1702 910 1702 912 1702 910 1702 911 1702 911 1702 913 1702 912 1702 914 1718 912 1718 913 1718 913 1702 915 1702 914 1702 916 1702 914 1702 915 1702 915 1719 917 1719 916 1719 918 1702 916 1702 917 1702 917 1702 919 1702 918 1702 920 1702 918 1702 919 1702 919 1720 923 1720 920 1720 921 1721 920 1721 923 1721 923 1722 922 1722 921 1722 823 1723 381 1723 924 1723 924 1724 805 1724 823 1724 780 1725 781 1725 819 1725 380 1726 819 1726 781 1726 781 1727 780 1727 174 1727 174 1728 380 1728 781 1728 198 1729 196 1729 805 1729 805 1730 924 1730 198 1730 198 1731 924 1731 381 1731

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/wrist/wrist_E3M5_no_rot_scaled.dae b/URDFs/sr_description/meshes/components/wrist/wrist_E3M5_no_rot_scaled.dae new file mode 100644 index 0000000..56b8098 --- /dev/null +++ b/URDFs/sr_description/meshes/components/wrist/wrist_E3M5_no_rot_scaled.dae @@ -0,0 +1,153 @@ + + + + + Blender User + Blender 4.3.2 commit date:2024-12-16, commit time:21:10, hash:32f5fdce0a0a + + 2025-02-20T09:24:30 + 2025-02-20T09:24:30 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0 + + + + + 0 + 0 + 2097153 + 1 + 1 + 1 + 1000 + 75 + 0.15 + 0.04999995 + 40 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0.9 0.9 0.9 1 + + + 0 0 0 0 + + + 1.5 + + + + + + + + + + + + + + + + + -12.60386 -4e-4 -4.55191 -0.5429 13.89959 -4.46761 0.54193 13.89959 -4.46761 -1.5962 13.89959 -4.20799 1.59524 13.89959 -4.20799 -2.55677 13.89959 -3.70385 2.55581 13.89959 -3.70385 -3.36878 13.89959 -2.98447 3.36782 13.89959 -2.98447 -3.98503 13.89959 -2.09167 3.98407 13.89959 -2.09167 -4.36972 13.89959 -1.07734 4.36876 13.89959 -1.07734 -4.50048 13.89959 -4.2e-4 4.49952 13.89959 -4.2e-4 -4.36972 13.89959 1.0765 4.36876 13.89959 1.0765 -3.98503 13.89959 2.09083 3.98407 13.89959 2.09083 -3.36878 13.89959 2.98363 3.36782 13.89959 2.98363 -2.55677 13.89959 3.70301 2.55581 13.89959 3.70301 -1.59621 13.89959 4.20715 -0.5429 13.89959 4.46677 1.59524 13.89959 4.20715 0.54193 13.89959 4.46677 2.31715 10.5996 -7.13334 2.31714 10.59959 7.1325 0.78348 10.5996 -7.45934 0.78348 10.59959 7.45849 -0.78445 10.5996 -7.45934 -0.78445 10.59959 7.45849 -2.31811 10.5996 -7.13334 -2.31811 10.59959 7.1325 -3.75048 10.5996 -6.49561 -3.75048 10.59959 6.49477 -5.01896 10.59959 5.57317 -5.01896 10.5996 -5.57401 -6.06811 10.5996 -4.40881 -6.06811 10.59959 4.40797 -6.85207 10.5996 -3.05095 -6.85207 10.5996 3.0501 -7.33659 10.5996 1.55892 -7.33659 10.5996 -1.55976 -7.50048 10.5996 -4.2e-4 -7.33659 -10.60041 1.55892 -7.50049 -10.60041 -4.2e-4 -7.33659 -10.60041 -1.55976 -6.85208 -10.6004 -3.05095 -6.85208 -10.60041 3.0501 -6.06812 -10.60041 4.40797 -6.06811 -10.60041 -4.40881 -5.01897 -10.60041 -5.57401 -5.01897 -10.60041 5.57317 -3.75049 -10.60041 6.49477 -3.75048 -10.60041 -6.49561 -2.31811 -10.60041 7.1325 -2.31811 -10.60041 -7.13334 -0.78445 -10.60041 7.45849 -0.78445 -10.60041 -7.45934 0.78348 -10.60041 7.45849 0.78348 -10.60041 -7.45934 2.31714 -10.60041 7.1325 2.31714 -10.60041 -7.13334 -14.48772 7.22568 1.21112 -13.95641 7.52509 0.93113 -14.193 7.34965 1.09963 -13.90642 5.60705 -0.55767 -13.79636 3.38683 -1.54026 -13.62562 5.80287 -0.827 -13.37415 3.55958 -2.00872 -13.63172 7.84658 0.62766 -13.42834 6.02566 -1.14744 -13.47899 8.13542 0.34559 -13.59057 1.00859 -2.05556 -13.29065 0.9996 -2.43023 -13.81941 -3.37846 -1.5238 -14.03224 -5.53306 -0.46171 -13.55213 -0.99182 -2.09744 -13.25895 -1.00324 -2.49002 -13.38795 -3.54875 -1.98317 -13.58612 -5.8268 -0.86263 -14.26401 -7.32159 1.13379 -13.91214 -7.54561 0.91654 -13.62985 -7.86254 0.60894 -13.45037 -8.2021 0.28867 -13.43177 -8.35835 0.13871 -13.33815 -8.96163 6.94725 -14.02152 -9.256731 4.06271 -12.62189 -7.88431 7.72702 -13.6886 -9.47942 5.55454 -12.1722 -7.98916 7.62231 -12.79561 -9.12583 6.73785 -13.52762 -9.55666 3.80315 -13.12857 -9.800291 5.34117 -11.8059 -8.101981 7.60052 -12.36982 -9.381791 6.66783 -11.38435 -8.277211 7.68078 -12.05107 -9.64642 6.67054 -13.18897 -10.02901 3.50122 -12.6582 -10.25672 5.20334 -12.34419 -10.5004 5.65164 -13.10623 -10.46706 3.30983 -10.99744 -8.473811 7.83888 -11.76268 -9.969881 6.7357 -12.25473 -6.40498 7.99782 -11.72898 -6.4056 7.93281 -11.17216 -6.40683 8.02417 -10.64307 -6.40915 8.28321 -14.26038 9.15721 4.16294 -12.29217 6.40601 8.00338 -13.74552 9.47 5.58112 -12.55224 7.8933 7.70474 -13.03981 9.035881 6.8245 -13.85801 9.33975 3.9834 -13.33376 9.66441 5.42183 -12.56829 9.24682 6.69359 -13.50539 9.605481 3.77503 -11.92678 8.05235 7.58945 -13.02474 9.90194 5.30744 -11.80182 6.40682 7.9372 -12.21385 9.49928 6.66542 -13.26845 9.92961 3.56703 -11.1358 6.4057 8.03591 -13.11173 10.1875 3.41007 -11.28393 8.31322 7.69886 -10.73077 6.4059 8.22361 -12.64398 10.38079 5.24346 -11.84269 9.83655 6.69265 -12.47477 10.4996 5.26739 -10.75736 8.63854 8.05253 -24.88471 -9.35137 23.00377 -24.13114 -9.40305 23.00179 -23.38857 -9.26547 23.01383 -22.12126 -8.46693 23.0197 -22.70383 -8.94547 23.00735 -21.39638 -7.15635 23.02859 -21.67562 -7.85566 23.01203 -23.87215 -9.40192 20.17845 -23.19525 -9.38724 17.4733 -21.99669 -8.94589 18.29033 -20.99868 -7.85505 18.54457 -21.94929 -9.39938 14.24081 -20.17987 -8.94589 13.92521 -19.2654 -7.85505 14.39999 -19.93711 -9.40192 10.96064 -17.36017 -8.94589 10.12988 -16.57709 -7.85505 10.8007 -17.34748 -9.40192 8.119771 -13.71346 -8.96542 7.08199 -13.0499 -7.81858 7.94862 -14.23772 -9.38277 5.85688 -24.88455 9.349451 22.99273 -23.38881 9.26415 22.9985 -24.13438 9.40093 22.94129 -22.7051 8.94655 22.96461 -22.12062 8.466691 23.00962 -21.39598 7.15553 23.02449 -21.67454 7.85688 22.9857 -21.99899 8.94669 18.28904 -21.00004 7.85689 18.54399 -23.36385 9.40128 17.86201 -20.18188 8.94669 13.92356 -19.26665 7.85689 14.39923 -21.37263 9.40128 13.12622 -17.36185 8.94669 10.12793 -16.57822 7.85689 10.79978 -13.63308 8.92521 7.04131 -18.28204 9.40128 9.02243 -12.95601 7.82493 7.86842 -14.24571 9.39143 5.82465 -28.2954 7.1239 23.04268 -30.07768 4.28939 23.02099 -30.54342 2.67371 23.01016 -29.31952 5.79025 23.03187 -25.59235 9.09639 23.03309 -27.04103 8.24381 23.05341 -25.28474 9.108981 19.71424 -27.61936 7.12429 17.71068 -29.29788 4.28653 17.06409 -24.50582 9.108981 16.57668 -23.27924 9.108981 13.58126 -25.81796 7.12429 12.64688 -27.20717 4.28652 11.43173 -21.63284 9.108981 10.79699 -22.9747 7.12429 8.085841 -23.9124 4.28652 6.40789 -19.60074 9.108981 8.28056 -14.54596 9.10868 4.25243 -17.22583 9.108981 6.08501 -19.22128 7.12429 4.23888 -14.43425 5.40799 -0.30267 -14.7311 7.12708 1.28862 -19.57969 4.28652 2.24588 -14.20562 3.28901 -1.33376 -30.07768 -4.29019 23.02099 -29.31952 -5.79105 23.03187 -30.54342 -2.67451 23.01016 -28.29363 -7.12628 23.0427 -27.04103 -8.24461 23.05341 -25.60065 -9.11085 23.01348 -25.46428 -9.10979 20.96733 -25.15497 -9.10979 19.02628 -24.67524 -9.10978 17.1182 -27.61719 -7.12757 17.71145 -29.29673 -4.29047 17.06458 -25.81612 -7.12757 12.64832 -23.24655 -9.10978 13.51576 -27.20625 -4.29047 11.43263 -21.96199 -9.10978 11.28491 -20.42908 -9.10979 9.21762 -22.97337 -7.12757 8.087861 -23.91183 -4.29047 6.40911 -18.66796 -9.10979 7.34085 -16.70228 -9.10979 5.6798 -14.44149 -9.10329 4.22508 -19.22062 -7.12757 4.24131 -14.62641 -7.17487 1.26451 -14.47512 -5.33858 -0.21095 -19.57957 -4.29047 2.24733 -14.24722 -3.28159 -1.25828 -13.08897 10.47856 3.10286 -13.40044 10.4996 0.03299999 -13.40676 8.41941 0.07981997 -13.40044 -10.5004 0.03299999 -13.32003 -6.17464 -1.3695 -13.32796 6.2534 -1.48803 -13.2027 10.4996 -2.2943 -13.09723 3.74191 -2.54411 -13.05894 0.9996 -3.00666 -13.09158 -1.0005 -2.92509 -13.1902 -3.7053 -2.44498 -13.20271 -10.5004 -2.2943 -12.60386 10.4996 -4.55191 -12.60386 -10.5004 -4.55191 -11.62209 10.4996 -6.67124 -11.62209 -10.5004 -6.67124 -10.28724 10.4996 -8.587901 -10.28724 -10.5004 -8.587901 -8.63985 10.4996 -10.24366 -8.63985 -10.5004 -10.24366 -6.72998 10.4996 -11.58821 -6.72998 -10.5004 -11.58821 -4.61565 10.49959 -12.5807 -4.61565 -10.50041 -12.5807 -2.36111 10.49959 -13.19098 -2.3611 -10.50041 -13.19098 -0.03483998 10.49959 -13.40051 -0.03482997 -10.50041 -13.40051 2.29247 10.49959 -13.20291 2.29248 -10.50041 -13.20291 2.15348 10.49959 13.2252 2.15348 -10.50041 13.2252 -0.07687997 10.49959 13.39923 -0.07688999 -10.50041 13.39923 -2.30523 10.49959 13.19976 -2.30524 -10.50041 13.19976 -4.46929 10.49959 12.63234 -4.4693 -10.50041 12.63233 -6.50868 10.49959 11.71284 -6.50869 -10.50041 11.71283 -8.36659 10.49959 10.46694 -8.36661 -10.50041 10.46692 -11.33783 10.4996 7.14268 -10.58126 8.767041 8.21934 -9.991291 10.4996 8.92939 -11.34845 -10.49318 7.12164 -10.66137 -8.7071 8.120631 -10.28659 -6.40669 8.60038 -10.25925 6.40596 8.62536 -9.991311 -10.5004 8.92937 -4.9e-4 -15.4004 -7.50042 1.46269 -15.4004 -7.35631 -1.46366 -15.4004 -7.35631 2.86964 -15.4004 -6.92952 -2.87061 -15.4004 -6.92952 4.16629 -15.40041 -6.23644 -4.16726 -15.4004 -6.23644 5.30282 -15.40041 -5.30372 -5.30379 -15.4004 -5.30372 6.23554 -15.40041 -4.1672 -6.23651 -15.4004 -4.1672 6.92861 -15.40041 -2.87055 -6.92958 -15.4004 -2.87055 7.3554 -15.40041 -1.4636 -7.35638 -15.4004 -1.4636 7.49951 -15.40041 -4.2e-4 -7.50049 -15.4004 -4.2e-4 7.3554 -15.40041 1.46276 -7.35638 -15.4004 1.46276 6.92861 -15.40041 2.86971 -6.92958 -15.4004 2.86971 6.23553 -15.40041 4.16636 -6.23651 -15.40041 4.16636 5.30281 -15.40041 5.30288 -5.30379 -15.40041 5.30288 4.16629 -15.40041 6.2356 -4.16727 -15.40041 6.2356 2.86964 -15.40041 6.92868 -2.87061 -15.40041 6.92868 -1.46367 -15.40041 7.35547 -4.9e-4 -15.40041 7.49958 1.46269 -15.40041 7.35547 -4.8e-4 15.39959 7.49958 1.46269 15.39959 7.35547 -1.46366 15.39959 7.35547 2.86964 15.39959 6.92868 -2.87061 15.39959 6.92868 4.16629 15.39959 6.2356 -4.16726 15.39959 6.2356 5.30282 15.39959 5.30288 -4.8e-4 15.39959 4.49958 -5.30378 15.39959 5.30288 1.00086 15.39959 4.38676 -1.00183 15.39959 4.38676 6.23554 15.39959 4.16636 1.95199 15.39959 4.05394 -1.95296 15.39959 4.05394 -6.23651 15.39959 4.16636 -2.80619 15.39959 3.51782 -3.51872 15.39959 2.80528 -6.92958 15.39959 2.86971 -4.05484 15.39959 1.95206 -4.38766 15.39959 1.00093 -7.35637 15.39959 1.46276 -4.50048 15.39959 -4.2e-4 -7.50048 15.39959 -4.2e-4 -4.38766 15.39959 -1.00176 -4.05484 15.39959 -1.9529 -7.35637 15.39959 -1.4636 -3.51872 15.39959 -2.80612 -2.80619 15.39959 -3.51866 -6.92958 15.3996 -2.87055 1.952 15.39959 -4.05478 -1.95296 15.39959 -4.05478 1.00086 15.39959 -4.3876 -4.8e-4 15.39959 -4.50042 -1.00182 15.39959 -4.3876 -6.2365 15.39959 -4.1672 5.30282 15.39959 -5.30372 -5.30378 15.39959 -5.30372 4.1663 15.39959 -6.23644 -4.16726 15.39959 -6.23644 2.86965 15.39959 -6.92952 -2.87061 15.39959 -6.92952 -1.46366 15.39959 -7.35631 -4.8e-4 15.39959 -7.50042 1.4627 15.39959 -7.35631 -21.30162 -6.4075 23.03941 -21.30144 6.40653 23.02324 -21.05293 -6.40666 20.48503 -21.05293 6.40585 20.48503 -20.45402 -6.40666 18.02602 -20.45402 6.40585 18.02602 -19.51434 -6.40666 15.67261 -19.51434 6.40585 15.67261 -18.2539 -6.40666 13.47585 -18.2539 6.40585 13.47586 -16.69758 -6.40666 11.47834 -16.69758 6.40585 11.47835 -14.87602 -6.40666 9.71929 -12.82573 -6.40666 8.23382 -14.87602 6.40585 9.71929 -12.82573 6.40585 8.23383 -30.41643 -1.0004 19.5347 -29.69563 0.9996 16.13403 -28.54962 0.9996 12.85194 -26.99694 0.9996 9.741621 -26.99669 -1.0004 9.74117 -25.06267 0.9996 6.8532 -25.06223 -1.0004 6.85262 -22.77773 0.9996 4.23294 -22.77734 -1.0004 4.23257 -20.17892 0.9996 1.92327 -20.17875 -1.0004 1.92313 -17.30873 0.9996 -0.03816998 -14.21282 0.9996 -1.62019 -17.30859 -1.0004 -0.03824996 -14.21282 -1.0004 -1.62019 -30.69927 0.99943 23.04174 -30.70291 -1.00075 23.02165 -30.41645 0.9996 19.5349 -29.69556 -1.0004 16.13377 -28.54948 -1.0004 12.85162 35.56442 -1.00041 18.82635 35.8996 1.00018 23.02512 35.89865 -1.0003 23.04285 35.60408 0.99999 18.94442 34.68587 -1.00041 14.73265 34.68535 0.99959 14.73082 33.27864 -1.00041 10.78832 33.2779 0.99959 10.78664 31.36698 -1.00041 7.06207 31.36615 0.99959 7.0607 28.98425 -1.00041 3.61868 28.98302 0.99959 3.61714 26.1713 -1.00041 0.51695 26.16953 0.99959 0.51526 22.97604 -1.00041 -2.19013 22.97423 0.99959 -2.19147 19.453 -1.00041 -4.45602 19.45189 0.99959 -4.45665 15.66376 -1.00041 -6.24092 15.66357 0.99959 -6.24101 11.64083 -0.99333 -7.51363 11.67386 0.99959 -7.51412 26.49701 -6.4079 23.00487 26.50031 6.4068 23.03065 26.24158 -6.40714 20.03259 26.24143 6.40632 20.03162 25.5942 -6.40714 17.12513 25.59365 6.40632 17.12325 24.5692 -6.40714 14.32965 24.56801 6.40632 14.32697 23.18434 -6.40714 11.6939 23.18226 6.40632 11.69051 21.45901 -6.40714 9.25799 21.45568 6.40632 9.2539 19.4443 -6.40714 7.08838 19.44081 6.40632 7.08509 17.34859 -6.40714 5.33769 17.34648 6.40632 5.33613 15.28735 6.40805 3.98648 15.28216 -6.40734 3.98093 6.23554 15.39959 -4.1672 2.80522 15.39959 -3.51866 6.92861 15.39959 -2.87055 3.51776 15.39959 -2.80612 4.05388 15.39959 -1.9529 7.35541 15.39959 -1.4636 4.38669 15.39959 -1.00176 4.49952 15.39959 -4.2e-4 7.49952 15.39959 -4.2e-4 4.38669 15.39959 1.00093 7.35541 15.39959 1.46276 4.05388 15.39959 1.95206 3.51776 15.39959 2.80528 6.92861 15.39959 2.86971 2.80522 15.39959 3.51782 4.3237 -10.50041 12.68256 4.32371 10.49959 12.68256 6.37333 -10.50041 11.7865 6.37333 10.49959 11.78649 8.245261 -10.50041 10.56201 8.24527 10.49959 10.562 9.88738 -10.50041 9.04324 9.88738 10.49959 9.04324 11.25394 -10.50041 7.27254 11.25394 10.49959 7.27254 12.30691 -10.50041 5.29925 12.30692 10.49959 5.29925 12.48335 -6.40739 4.90258 12.71416 -9.07247 4.22862 12.43964 6.40632 4.97975 12.68775 9.13363 4.25919 13.25704 10.50525 2.32517 13.18964 -10.50041 -2.36255 12.5794 -10.50041 -4.61647 12.89855 -9.67272 -3.62335 12.57939 10.49959 -4.61647 13.18965 10.49959 -2.36255 12.88448 9.63719 -3.66647 12.21337 7.94797 -5.5056 11.58678 -10.50041 -6.73074 12.21218 -7.94114 -5.51293 11.58677 10.49959 -6.73074 11.51189 -6.06881 -6.85762 11.51664 6.08266 -6.85008 10.24212 -10.50041 -8.64053 10.67074 0.99921 -8.11293 10.66506 -1.0003 -8.111411 10.83492 -3.55577 -7.89054 10.88949 3.53806 -7.81976 10.24211 10.49959 -8.640541 8.58626 -10.50041 -10.28782 8.58625 10.49959 -10.28783 6.66952 -10.50041 -11.62256 6.66951 10.49959 -11.62256 4.55013 -10.50041 -12.6042 4.55012 10.49959 -12.6042 35.67098 -2.91176 23.41162 35.10701 -4.69323 24.05084 34.51861 -5.79096 22.99116 32.2402 -8.244521 23.00877 30.79715 -9.11441 22.99093 33.49187 -7.12698 22.99789 30.45738 -9.11051 19.15825 32.7948 -7.12707 17.0692 34.4615 -4.29016 16.35134 29.44318 -9.13203 15.4273 30.91869 -7.12707 11.40214 32.2547 -4.29016 10.0384 27.71212 -9.11051 10.95918 27.94042 -7.12707 6.22863 26.26256 -9.11051 8.52879 28.75688 -4.29016 4.33854 24.5623 -9.11051 6.26149 22.66412 -9.11051 4.21714 23.98184 -7.12707 1.7604 24.1278 -4.29015 -0.48793 20.6717 -9.11051 2.46631 18.69316 -9.1105 1.036 19.20498 -7.12707 -1.81966 16.78089 -9.1105 -0.1073 18.57887 -4.29015 -4.22057 14.85429 -9.11536 -1.01545 14.19183 -8.09903 -3.02073 13.46651 -6.7545 -4.84491 11.8847 -3.19872 -7.2078 12.61154 -4.96985 -6.2913 35.27751 4.28659 23.01634 34.51856 5.7902 23.02481 33.49437 7.12394 23.03323 32.24012 8.24375 23.04163 30.79967 9.110361 23.00775 32.80304 7.1241 17.09722 30.54383 9.109681 19.72866 34.46772 4.2864 16.37301 29.90321 9.109681 16.56613 30.92986 7.1241 11.42224 28.88781 9.109681 13.50447 32.26332 4.2864 10.0539 27.51255 9.109681 10.58758 27.95177 7.1241 6.24101 25.79234 9.109681 7.85021 28.76567 4.2864 4.34804 23.75453 9.109681 5.33895 23.99086 7.1241 1.76602 21.51544 9.109681 3.16539 24.1347 4.2864 -0.48361 19.20959 7.12411 -1.81921 19.24568 9.109681 1.4082 17.04753 9.10969 0.03940999 18.58228 4.2864 -4.22007 13.79232 7.10996 -4.35238 14.33083 8.00472 -3.01229 14.93884 9.10969 -1.0176 11.98112 3.17161 -7.16036 12.80422 5.00471 -6.2741 29.33309 9.40134 22.94975 30.08383 9.35425 22.99638 26.59515 7.15561 23.01965 26.87466 7.85676 23.00244 26.29238 7.85724 18.31521 27.27739 8.94702 18.00122 27.31973 8.46639 23.00948 27.90369 8.94572 22.99972 28.63104 9.401721 17.51563 28.58735 9.264551 23.00108 24.77109 7.85724 13.86825 25.63348 8.94702 13.27911 26.77773 9.401721 12.35932 22.37364 7.85724 9.8257 23.04388 8.94702 9.001871 23.85976 9.401721 7.72165 19.2011 7.85724 6.358 19.62173 8.94702 5.35638 20.01346 9.401721 3.81929 15.3507 7.89198 3.53765 15.50805 9.08422 2.16505 15.18956 9.39706 0.20453 29.33042 -9.4073 22.97453 26.87267 -7.85526 22.99909 26.29455 -7.85542 18.33118 27.31945 -8.467781 23.01072 27.9018 -8.946081 22.98559 27.27926 -8.94623 18.02046 28.13668 -9.43483 15.7114 28.58736 -9.266 22.99869 24.77486 -7.85542 13.87991 25.63741 -8.94623 13.29348 25.54921 -9.40238 10.13518 22.37741 -7.85541 9.83324 23.04801 -8.94623 9.01154 22.76218 -9.40238 6.4319 19.20344 -7.85541 6.36204 19.62439 -8.94623 5.36206 19.34743 -9.40238 3.29801 15.38655 -7.90337 3.56958 15.48328 -9.08043 2.1748 15.21953 -9.384651 0.2024199 12.71159 -6.40639 4.50438 12.74383 6.40694 4.46699 13.11625 -6.40706 4.10916 13.17147 6.40534 4.06695 13.67181 -6.40729 3.82388 13.63432 6.40488 3.83865 14.16679 -6.40621 3.72869 14.16567 6.40517 3.73141 14.74828 -6.40559 3.77486 14.7899 6.40795 3.78526 12.58938 6.40624 4.72038 12.84993 8.843191 3.96175 13.47079 10.08159 2.14671 13.19677 8.554611 3.61157 13.6924 10.33885 0.1000699 13.5716 8.34648 3.40352 13.86713 9.62944 2.02199 13.98212 8.18787 3.28635 14.07981 9.873641 0.14741 14.3156 9.33661 1.97631 14.40984 8.07622 3.25155 14.5078 6.40489 3.75358 14.52968 9.59005 0.18204 14.90134 9.13856 1.99861 14.85833 8.01625 3.30744 14.85845 9.46198 0.1954799 13.48269 10.32783 -1.34628 13.95208 9.60692 -1.10757 14.66569 9.186861 -1.01369 12.93925 9.414831 -3.53728 12.36359 7.69195 -5.23325 13.11882 9.013441 -3.32705 13.65545 9.95317 -1.21632 11.6097 5.81624 -6.70498 12.71295 7.44038 -4.91488 13.41292 8.650071 -3.17383 11.93168 5.52365 -6.44411 10.94455 0.99738 -7.8714 11.28216 3.39613 -7.4388 13.14305 7.23847 -4.66389 13.77247 8.351241 -3.08141 14.29804 9.36786 -1.04865 12.3159 5.2704 -6.28185 11.73384 3.19752 -7.16874 11.35846 0.99781 -7.62773 14.1886 8.09826 -3.03375 10.90901 -0.99577 -7.89165 11.23977 -0.99918 -7.68268 13.55432 -10.50586 -0.44094 12.95099 -9.373721 -3.50425 12.34374 -7.74751 -5.26691 13.12794 -9.02062 -3.3248 11.63522 -5.80562 -6.6877 12.61567 -7.37134 -5.02173 13.92358 -9.639 -1.11594 13.37768 -8.697481 -3.18544 11.02792 -3.5286 -7.64708 11.90387 -5.55691 -6.4636 14.30893 -9.34458 -1.04496 13.69316 -8.41773 -3.09304 11.3741 -3.36257 -7.37211 13.06867 -6.99306 -4.85521 12.23053 -5.32839 -6.30559 13.73215 -10.26075 0.11352 13.65034 -9.95749 -1.21899 14.04955 -9.92929 0.1506299 14.42913 -9.63355 0.17846 14.8779 -9.45857 0.19826 12.846 -8.85458 3.98163 13.32162 -10.49276 2.06913 13.0887 -8.63163 3.70309 12.92298 -6.40751 4.29738 13.47838 -10.08774 2.15254 13.44063 -8.41393 3.4698 13.38458 -6.40547 3.96435 13.77817 -9.70742 2.0413 13.80434 -8.24599 3.32269 14.08722 -9.47522 1.99617 14.36399 -8.07932 3.24406 14.45476 -9.2713 1.97544 14.96485 -9.129341 2.00828 14.97332 -8.007201 3.33362 7.49951 -10.60041 -4.2e-4 7.33562 -10.60041 -1.55976 6.85111 -10.60041 -3.05095 6.8511 -10.60041 3.0501 7.33562 -10.60041 1.55892 6.06714 -10.60041 4.40797 6.06714 -10.60041 -4.40881 5.01799 -10.60041 -5.57401 5.01799 -10.60041 5.57317 3.74951 -10.60041 6.49477 3.74952 -10.60041 -6.49561 3.74952 10.59959 -6.49561 3.74952 10.59959 6.49477 5.018 10.59959 -5.57401 5.018 10.59959 5.57317 6.06715 10.59959 -4.40881 6.06714 10.59959 4.40797 6.85111 10.59959 3.0501 6.85111 10.59959 -3.05095 7.33562 10.59959 -1.55976 7.49952 10.59959 -4.2e-4 7.33562 10.59959 1.55892 13.44627 10.50242 -0.01868999 35.69546 3.05739 23.43314 -25.69792 -8.06854 26.52259 -26.35478 -8.04488 26.51994 -25.26371 -8.17598 26.64023 -24.16 -9.02968 27.71689 -24.455 -8.67075 27.23014 -24.83796 -8.378931 26.87214 -24.45243 8.67238 27.23327 -24.16008 9.02875 27.71671 -24.83342 8.38089 26.8754 -25.25692 8.17761 26.64293 -25.69196 8.06858 26.52351 -26.35262 8.04343 26.51944 30.89098 -8.0694 26.52353 31.55164 -8.04425 26.51945 30.45594 -8.178421 26.64295 30.03244 -8.381711 26.87541 29.65145 -8.6732 27.23329 29.35909 -9.02957 27.71672 29.35902 9.02887 27.7169 29.65402 8.66993 27.23016 30.03698 8.37811 26.87215 30.46273 8.17516 26.64024 30.89694 8.06772 26.5226 31.5538 8.04406 26.51995 30.30964 -9.28881 26.71105 29.51329 -9.40195 27.42233 29.85156 -9.38048 27.02176 29.21206 -9.39401 28.27592 29.30267 -9.39645 27.86289 28.81621 -9.33038 28.16568 28.36078 -9.18566 27.93929 27.89046 -8.94547 27.58514 27.52685 -8.66804 27.22668 27.16869 -8.30602 26.77394 26.87688 -7.86445 26.30823 26.71915 -7.53458 25.98483 26.60021 -7.17856 25.66446 26.52537 -6.80088 25.35357 -25.11475 -9.28649 26.70846 -24.73201 -9.37661 26.9533 -24.45204 -9.39816 27.23272 -24.18235 -9.39973 27.66239 -24.01589 -9.3831 28.21809 -23.61292 -9.32953 28.16398 -23.27349 -9.22654 28.00972 -22.92326 -9.07597 27.77525 -22.57237 -8.860071 27.47989 -22.32934 -8.669341 27.22835 -22.09323 -8.43956 26.94403 -21.87564 -8.17419 26.63824 -21.68406 -7.87555 26.3196 -21.52446 -7.54521 25.99483 -21.40323 -7.1862 25.67105 -21.32681 -6.80432 25.35626 30.31377 9.28566 26.70846 29.93103 9.37579 26.95331 29.65106 9.39735 27.23273 29.38137 9.39891 27.6624 29.21495 9.38221 28.21792 28.80724 9.32764 28.16212 28.46433 9.22273 28.00512 28.10902 9.06841 27.76509 27.75194 8.84543 27.46115 27.5048 8.64778 27.20188 27.26728 8.411271 26.91131 27.05169 8.14141 26.60291 26.8649 7.84184 26.28602 26.64308 7.35032 25.80266 26.52453 6.79367 25.34855 -25.11072 9.287981 26.71104 -24.31433 9.40116 27.42237 -24.65256 9.37968 27.02179 -24.01304 9.3932 28.27591 -24.10299 9.39558 27.86508 -23.61179 9.328471 28.16351 -23.15257 9.18113 27.93344 -22.80202 9.00596 27.68408 -22.55539 8.84721 27.46354 -22.30408 8.64627 27.19994 -22.06303 8.40544 26.90438 -21.8458 8.13166 26.59218 -21.57421 7.67631 26.10763 -21.39569 7.15675 25.64643 -21.32504 6.79 25.34565 -25.60049 9.1107 26.53998 -26.06235 8.87196 26.50053 -26.53616 8.59014 26.57264 -26.98871 8.282091 26.76077 -27.9384 7.48716 25.94127 -28.70745 6.64783 25.23596 -29.35557 5.73244 24.61157 -29.90789 4.69264 24.05094 -30.33595 3.53512 23.58323 -30.60797 2.28678 23.23998 30.79951 9.110691 26.53999 31.73488 8.59032 26.57257 31.26123 8.87203 26.50054 32.18773 8.28208 26.76079 33.13742 7.48715 25.94128 33.90647 6.64782 25.23597 34.55459 5.73243 24.61159 35.10691 4.69263 24.05095 30.79951 -9.11152 26.54 31.26137 -8.87278 26.50054 31.73518 -8.59096 26.57266 32.18773 -8.28291 26.76079 33.13676 -7.48862 25.94187 33.90627 -6.6489 25.23616 34.55468 -5.7331 24.6115 -25.60049 -9.11151 26.53998 -26.53586 -8.591131 26.57256 -26.06221 -8.87285 26.50052 -26.98871 -8.2829 26.76077 -27.93774 -7.48861 25.94185 -28.70725 -6.64889 25.23615 -29.35566 -5.73309 24.61148 -29.90799 -4.69322 24.05083 -30.33597 -3.53584 23.5832 -30.70049 10.98821 34.50007 -30.70049 10.88394 32.40859 -30.70049 10.69424 36.57342 -30.70049 10.3852 30.37476 -30.7005 10.01268 38.55349 -30.70049 9.51008 28.4723 -30.7005 8.96824 40.36852 -30.70049 8.29029 26.77015 -30.7005 7.59876 41.95273 -30.70049 6.77003 25.33001 -30.7005 5.95388 43.24871 -30.70049 5.0044 24.20407 -30.7005 4.0932 44.20949 -30.70049 3.0574 23.43312 -30.7005 2.08417 44.80024 -30.7005 -4e-4 44.99957 -30.7005 -2.08498 44.80024 -30.70049 -3.0582 23.43312 -30.7005 -4.09401 44.20949 -30.70049 -5.00521 24.20407 -30.7005 -5.95468 43.24871 -30.70049 -6.77083 25.33001 -30.7005 -7.59957 41.95274 -30.70049 -8.29109 26.77015 -30.7005 -8.96904 40.36852 -30.70049 -9.51088 28.4723 -30.7005 -10.01348 38.5535 -30.70049 -10.386 30.37476 -30.70049 -10.88474 32.40859 -30.70049 -10.69504 36.57343 -30.70049 -10.98901 34.50008 -21.30049 6.407 25.05836 -21.30049 -6.40781 25.05836 -21.30049 7.955 26.40277 -21.30049 -7.95582 26.40277 -21.30049 9.226611 28.01107 -21.30049 -9.22742 28.01107 -21.30049 10.17766 29.8274 -21.30049 -10.17846 29.8274 -21.30049 10.77512 31.78865 -21.30049 -10.77592 31.78866 -21.30049 10.99824 33.82669 -21.30049 -10.99904 33.82669 -21.30049 10.83929 35.87072 -21.30049 -10.84009 35.87072 -21.30049 10.30379 37.84973 -21.30049 -10.30459 37.84973 -21.30049 9.41035 39.69498 -21.30049 -9.41116 39.69498 -21.30049 8.19002 41.34239 -21.30049 -8.190831 41.34239 -21.30049 6.68519 42.73472 -21.30049 -6.686 42.73473 -21.30049 4.94813 43.82362 -21.30049 -4.94894 43.82363 -21.3005 3.03919 44.57127 -21.3005 1.02466 44.95171 -21.3005 -3.04 44.57127 -21.3005 -1.02547 44.95171 26.4995 1.02465 44.95172 26.4995 -1.02548 44.95172 26.4995 3.03918 44.57128 26.4995 -3.04001 44.57129 26.49951 4.94812 43.82364 26.49951 -4.94895 43.82364 26.49951 6.68518 42.73473 26.49951 -6.68601 42.73474 26.49951 8.190011 41.3424 26.49951 -8.19084 41.3424 26.49951 9.41034 39.69499 26.49951 -9.41117 39.695 26.49951 10.30378 37.84974 26.49951 -10.3046 37.84974 26.49951 10.83928 35.87073 26.49951 -10.8401 35.87073 26.49951 10.99823 33.8267 26.49951 -10.99905 33.82671 26.49951 10.77511 31.78867 26.49951 -10.77593 31.78867 26.49951 10.17765 29.82741 26.49951 -10.17847 29.82741 26.49951 9.226611 28.01108 26.49951 -9.22743 28.01108 26.49951 7.955 26.40278 26.49951 -7.95582 26.40278 26.49951 6.40699 25.05838 26.49951 -6.40781 25.05838 35.89951 10.9882 34.50008 35.89951 10.88393 32.4086 35.89951 10.69423 36.57343 35.89951 10.38519 30.37477 35.89951 10.01267 38.55351 35.89951 9.51007 28.47231 35.89951 8.968231 40.36853 35.89951 8.29028 26.77017 35.89951 7.59875 41.95275 35.89951 6.77002 25.33003 35.89951 5.95387 43.24872 35.89951 5.00439 24.20408 35.89951 4.09319 44.20951 35.89951 3.05739 23.43314 35.89951 2.08416 44.80026 35.89951 -4.1e-4 44.99959 35.89951 -2.08499 44.80026 35.89951 -3.05821 23.43314 35.89951 -4.09402 44.20951 35.89951 -5.00522 24.20408 35.89951 -5.9547 43.24872 35.89951 -6.77085 25.33003 35.89951 -7.59958 41.95275 35.89951 -8.2911 26.77017 35.89951 -8.96905 40.36853 35.89951 -9.51089 28.47231 35.89951 -10.01349 38.55351 35.89951 -10.38601 30.37477 35.89951 -10.88475 32.4086 35.89951 -10.98902 34.50009 35.89951 -10.69505 36.57344 -30.60796 -2.28766 23.24 + + + + + + + + + + 0.00350815 -0.9998577 0.01650494 0 -0.9998584 0.0168308 -0.8861943 0.4484995 -0.1162241 -0.7887651 0.6065123 -0.09996247 -0.838851 0.5271334 -0.135865 -0.6572538 0.7376483 -0.1545717 -0.5071755 0.8607322 -0.04374182 -0.00723499 -0.9998553 -0.01540267 -0.009790718 -0.9998555 -0.01390749 -0.009951591 -0.9998568 -0.01369655 -0.0120958 -0.9998545 -0.01203477 -0.01357299 -0.9998632 -0.009452879 -0.01317262 -0.999843 -0.01186043 -0.01514619 -0.9998607 -0.007015526 -0.01510882 -0.9998479 -0.008716523 -0.01625812 -0.9998585 -0.004312992 -0.01637899 -0.9998518 -0.005328536 -0.01682484 -0.999857 -0.001767635 -0.01695668 -0.9998553 -0.001440644 -0.01693838 -0.999855 0.001779556 -0.01948839 -0.9997391 0.01192146 -0.02103269 -0.9997555 0.006833195 -0.02161514 -0.9997406 -0.007198333 -0.01202285 -0.9998426 0.01305478 -0.01565819 -0.9998366 0.009039998 -0.01613229 -0.999837 0.008118152 -0.01250839 -0.9998584 0.01126235 -0.01174086 -0.9998542 0.01240038 -0.00939244 -0.9998579 0.01400572 -0.01005852 -0.9998537 0.01384472 -0.006976544 -0.9998559 0.01547336 -0.00939238 0.9998579 0.01400589 -0.01173341 0.9998543 0.01240563 -0.01250588 0.9998584 0.01126009 -0.01363784 0.9998542 0.01027768 -0.01459485 0.9998579 0.008432984 -0.01435142 0.9998592 0.008700788 -0.0194388 0.9998022 -0.004202723 -0.01934993 0.999793 0.006287813 -0.01868921 0.9997872 0.008748412 -0.01693677 0.999855 0.001779913 -0.01695501 0.9998552 -0.001440107 -0.01682329 0.999857 -0.001768827 -0.01649671 0.9998544 -0.004375696 -0.0160247 0.9998582 -0.005206704 -0.01550859 0.999854 -0.007184088 -0.01457482 0.9998584 -0.008414924 -0.01402395 0.999854 -0.009766757 -0.01252645 0.999858 -0.01127904 -0.01209461 0.9998545 -0.0120331 -0.009751021 0.9998566 -0.01385134 -0.9592655 0 -0.2825061 -0.9585492 0.004022836 -0.2848988 -0.9578792 0 -0.2871714 -0.907369 0 -0.4203348 -0.9073691 0 -0.4203347 -0.9665573 -0.005717277 -0.2563872 -0.4637726 -0.3606431 -0.8092291 -0.4531846 -0.5353585 -0.7127517 -0.9967604 0.002623558 -0.08038651 -0.9922292 -0.09399092 -0.0815289 -0.9471392 -0.2741383 -0.1666598 -0.9966421 -2.18064e-6 -0.08188188 -0.9782678 1.31677e-5 -0.2073454 -0.1818892 -0.981073 -0.06642472 -0.1683539 -0.9834628 -0.06676733 -0.9782656 -8.77827e-6 -0.2073558 -0.9441022 1.02054e-5 -0.3296529 -0.9440979 -1.5362e-5 -0.3296655 0.9952941 1.08613e-4 0.09690004 0.9952412 0 0.09744167 0.9715976 0 0.2366393 0.9715974 0 0.2366398 0.9287056 0 0.3708179 0.2079085 -0.008425295 -0.978112 0.09801393 0.00749123 -0.9951569 0 -0.008558034 -0.9999634 -0.09801393 0.007491409 -0.9951568 -0.2079097 -0.008425056 -0.9781118 -0.2902754 0.007221221 -0.9569159 -0.4067223 -0.008025169 -0.9135166 -0.4713894 0.006686806 -0.8818999 -0.5877675 -0.007354557 -0.8089966 -0.6343831 0.005885124 -0.7729964 -0.7431297 -0.006417155 -0.6691167 -0.773001 0.004814386 -0.6343864 -0.8660139 -0.005213677 -0.4999928 -0.881914 0.003475725 -0.4713974 -0.9510494 -0.00374341 -0.3090164 -0.9569393 0.001871824 -0.2902821 -0.9945201 -0.002004384 -0.1045261 -0.9951848 0 -0.0980165 -0.3302282 -0.01785123 0.9437324 -0.2392624 0.02142524 0.9707186 -0.1119418 -0.01874649 0.9935379 0 0.02186822 0.9997609 0.1119421 -0.01874727 0.9935379 0.2392645 0.02142429 0.970718 0.3302282 -0.01785123 0.9437324 0.4646253 0.02008414 0.8852797 0.5319637 -0.0160681 0.8466148 0.6630181 0.01785045 0.7483906 0.7070486 -0.01339 0.7070382 0.8228966 0.01472157 0.5680004 0.8466804 -0.009813487 0.5320113 0.9349611 0.01070916 0.3545886 0.9438694 -0.005353271 0.3302758 0.9927091 0 0.1205348 0.9936934 0.006243646 0.1119581 0.9937129 0 -0.1119592 0.9926924 0.005800187 -0.1205328 0.9438682 -0.005350887 -0.3302791 0.934961 0.01070976 -0.354589 0.8466803 -0.009813427 -0.5320115 0.8228967 0.01472151 -0.5680004 0.7070484 -0.01339 -0.7070384 0.6630188 0.01785051 -0.74839 0.5319623 -0.01606804 -0.8466156 0.4646296 0.02008199 -0.8852775 0.3302319 -0.0178529 -0.943731 0.2392618 0.02142506 -0.9707188 0.1119404 -0.01874685 -0.9935382 0 0.02186822 -0.9997609 -0.1119412 -0.01874649 -0.993538 -0.2392618 0.02142506 -0.9707188 -0.3302319 -0.0178529 -0.943731 0 1 -1.35444e-5 0 1 0 0 1 2.96005e-6 0 1 -4.14879e-6 0 1 3.14863e-6 0 1 -2.53703e-6 0 1 -1.88769e-6 0 1 3.44298e-6 0 1 -1.62144e-6 0 1 -1.57432e-6 0 1 1.57432e-6 0 1 1.62144e-6 0 1 -1.72149e-6 0 1 2.53703e-6 0 1 -3.14863e-6 0 1 4.14879e-6 0 1 -4.74188e-6 0 1 4.60399e-6 -0.9945222 0 0.1045263 -0.9951825 -0.002137541 0.09801632 -0.9569393 0.001871824 0.290282 -0.9510488 -0.003744125 0.3090184 -0.881917 0.003474175 0.4713919 -0.8660154 -0.005215585 0.4999902 -0.7729975 0.004813015 0.6343908 -0.7431295 -0.006417274 0.6691169 -0.6343833 0.005885064 0.7729963 -0.5877676 -0.007354617 0.8089964 -0.4713899 0.006686747 0.8818997 -0.4067223 -0.008025228 0.9135166 -0.2902748 0.007221162 0.9569162 -0.2079044 -0.008426129 0.9781129 -0.09801375 0.007489383 0.9951569 0 -0.008560061 0.9999634 0.09801441 0.007489264 0.9951568 0.2079045 -0.008426129 0.9781129 0.003504931 0.9998579 -0.01648938 0.00350815 0.9998577 0.01650536 0.001445889 0.999854 -0.01702976 0.001328229 0.9998542 0.01702266 0 0.9998584 -0.01683098 0 0.9998584 0.01683038 -0.001533389 0.999854 -0.01702469 -0.003503561 0.9998581 -0.01648247 -0.001522779 0.9998542 0.01701128 -0.004323303 0.9998548 0.01648855 -0.003504395 0.999858 0.01648741 -0.004459738 0.9998544 -0.01647555 -0.00688076 0.999857 -0.01545435 -0.006893575 0.9998564 0.01548337 -0.006976544 0.9998559 0.0154733 -0.007226884 0.9998553 -0.01540541 -0.0100097 0.9998551 -0.01377695 -0.01005852 0.9998537 0.01384472 0.2079044 0.008426129 0.9781129 0.09801375 -0.007489383 0.9951569 0 0.008560061 0.9999635 -0.09801369 -0.007489144 0.9951569 -0.2079043 0.008426547 0.9781129 -0.2902768 -0.007220864 0.9569156 -0.4067199 0.00802493 0.9135177 -0.4713869 -0.006687045 0.8819012 -0.5877676 0.007354617 0.8089964 -0.6343833 -0.005884826 0.7729963 -0.7431295 0.006417155 0.6691169 -0.773001 -0.004814207 0.6343865 -0.8660156 0.005213618 0.4999901 -0.8819171 -0.003476142 0.4713918 -0.9510506 0.003742396 0.3090127 -0.9569375 -0.001869976 0.2902883 -0.9945195 0.002005875 0.1045324 -0.9951848 0 0.09801644 -0.9945215 0 -0.1045327 -0.9951826 0.002139151 -0.09801626 -0.9569374 -0.001870036 -0.2902882 -0.9510512 0.003741919 -0.3090107 -0.8819172 -0.003476977 -0.4713918 -0.8660111 0.00521481 -0.4999976 -0.7730011 -0.004812657 -0.6343864 -0.7431327 0.006417691 -0.6691133 -0.6343798 -0.005885183 -0.7729991 -0.5877645 0.00735408 -0.8089988 -0.4713893 -0.006686806 -0.8819 -0.4067223 0.008025169 -0.9135167 -0.2902754 -0.007221221 -0.9569159 -0.2079097 0.008425056 -0.9781118 -0.09801459 -0.00749129 -0.9951568 0 0.008558034 -0.9999634 0.09801393 -0.007491409 -0.9951569 0.2079098 0.008425056 -0.9781118 -0.004282891 -0.9998657 -0.01582223 -0.004323363 -0.9998548 0.01648819 -0.006893515 -0.9998565 0.01548361 -0.00732547 -0.9998379 -0.0164535 -0.003504395 -0.999858 0.016487 -0.001485705 -0.9998629 -0.01649475 -0.003675758 -0.9998438 -0.01729327 -0.001522779 -0.9998542 0.01701158 0 -0.9998584 -0.01682955 0.001328229 -0.9998543 0.01702272 0.00144577 -0.999854 -0.01702809 0.003504574 -0.999858 -0.01648753 -0.2984481 0.8019328 -0.5175254 -0.4554609 0.7606101 -0.4626312 -0.4857169 0.7481086 -0.4521201 -0.5264675 0.7271069 -0.4406218 -0.7051679 0.6192191 -0.345407 -0.6872929 0.6338862 -0.3547065 -0.7934599 0.5442967 -0.2723283 -0.8500958 0.4735066 -0.2304971 -0.9247553 0.3549501 -0.1372517 -0.8854649 0.4281756 -0.1806033 -0.9751008 0.2196887 -0.03025478 -0.9935533 0.1093322 0.02997362 -0.9948747 0.005295991 0.100977 -0.4491389 0.5639278 -0.6930078 -0.4871312 0.3390627 -0.8048229 -0.4687258 0.1111125 -0.8763277 -0.4878064 0.5501279 -0.6777936 -0.569895 0.1266049 -0.8119057 -0.5082737 0.3273341 -0.7965615 -0.5224338 0.5409433 -0.6591232 -0.7119902 0.4188854 -0.5635645 -0.764467 0.3827379 -0.5187504 -0.7531337 0.2346612 -0.6145923 -0.7544483 0.07597589 -0.6519474 -0.7635596 0.2318788 -0.6026682 -0.8003073 0.3461047 -0.4896121 -0.7774317 0.07741588 -0.6241848 -0.8924574 0.2598313 -0.3687921 -0.8832469 0.1371927 -0.4483894 -0.8934412 0.04445493 -0.446975 -0.8980227 0.1273427 -0.4211166 -0.9320635 0.1941064 -0.305909 -0.9266886 0.0498926 -0.3725039 -0.9631852 0.0241028 -0.2677562 -0.971196 0.12167 -0.2048773 -0.9811193 0.08870989 -0.171859 -0.5732806 0 -0.8193592 -0.5855988 0.005717098 -0.8105809 -0.7807027 -0.00191915 -0.6248998 -0.8011443 0.005185604 -0.5984489 -0.9278382 -0.003551661 -0.3729662 -0.9333211 5.88303e-4 -0.3590424 -0.5433428 -0.123545 -0.8303706 -0.5506269 -0.3295007 -0.7669675 -0.5689785 -0.3176949 -0.7585075 -0.5822882 -0.4795234 -0.6565043 -0.4715623 -0.5522114 -0.6875258 -0.5796076 -0.1285027 -0.8047 -0.6589052 -0.451404 -0.6017295 -0.740873 -0.07738822 -0.6671719 -0.7504606 -0.2310968 -0.6191957 -0.732761 -0.2479657 -0.6336989 -0.7440915 -0.407143 -0.5296814 -0.7998749 -0.07795441 -0.5950827 -0.8375594 -0.3081373 -0.4511605 -0.9329957 -0.02421343 -0.3590723 -0.9228914 -0.03442484 -0.3835186 -0.9264361 -0.09816944 -0.3634265 -0.9109933 -0.1234872 -0.3935 -0.9176995 -0.2196041 -0.3310616 -0.9293307 -0.1961244 -0.3128574 -0.9945257 -0.01995509 -0.1025692 -0.4707908 -0.7524104 -0.4606893 -0.4566836 -0.7591754 -0.463781 -0.6521437 -0.6562253 -0.3795748 -0.6191553 -0.680607 -0.3916897 -0.8290764 -0.5045095 -0.2410447 -0.8540728 -0.4703419 -0.222122 -0.9223013 -0.3633765 -0.1315976 -0.9919279 -0.1265001 0.008773028 -0.983841 -0.1781883 -0.0174914 -0.9957969 -0.01898676 0.08960056 0.2560158 -0.672714 0.6941987 0.109518 -0.9542554 0.278213 -0.2429814 -0.9607034 -0.1341981 0.02366286 -0.9389835 0.3431477 0.4162893 -0.2430703 0.8761392 0.2560964 -0.6727097 0.6941731 -0.3623047 -0.9302528 -0.05801039 0.3699505 -0.2553385 0.8932743 0.1070245 -0.6286798 0.7702646 -0.133108 -0.9175689 0.3746326 -0.5230501 -0.8522375 -0.01049059 0.03552567 -0.6257822 0.7791884 0.1726493 -0.2186573 0.9604069 -0.499325 -0.8663808 -0.007686674 -0.2961571 -0.8305491 0.471677 0.1193649 -0.223105 0.9674586 -0.1256514 -0.565398 0.8151914 -8.16971e-4 -0.1921932 0.9813568 -0.1797854 -0.5263983 0.8310127 -0.3950389 -0.7868479 0.4741463 -0.7761132 -0.6221554 0.1028163 -0.6747218 -0.7293988 0.1128178 -0.5162795 -0.6866183 0.5118699 -0.1595748 -0.1827924 0.970115 -0.2440925 -0.1482558 0.9583523 -0.343793 -0.4494062 0.8245244 -0.5539909 -0.6621258 0.5046619 -0.3649521 -0.4311376 0.8251851 -0.4258116 -0.1164296 0.8972896 -0.4995225 -0.3435369 0.7952734 -0.5283548 -0.3119998 0.7896186 -0.6933276 -0.5170346 0.5019682 -0.9254299 -0.2842633 0.2505476 -0.7902184 -0.5598818 0.2491729 -0.437119 -0.1168908 0.8917756 -0.8444396 -0.1340951 0.5185945 -0.8044067 -0.2340397 0.5460361 -0.6968379 -0.159244 0.6993272 -0.6609716 -0.04771953 0.7488922 -0.6637812 -0.0475223 0.7464156 -0.7376637 -0.09046155 0.6690807 0.3819711 -7.22828e-7 0.9241744 0.3965061 7.60365e-4 0.9180318 0.1227198 -7.20704e-5 0.9924414 0.1337493 4.2087e-4 0.9910152 -0.1619142 -0.001258552 0.9868041 -0.1466082 -4.90301e-4 0.9891946 -0.4397201 4.24911e-4 0.8981349 -0.4204719 0.001342177 0.9073047 -0.6647083 -0.001074433 0.7471023 -0.648543 -1.0015e-4 0.7611782 -0.206902 0.9690359 -0.1347627 -0.2172821 0.9668179 -0.1343567 0.02219647 0.9372424 0.3479714 0.1834079 0.6603112 0.7282519 0.3237043 0.2636983 0.9086687 -0.04563754 0.9347833 0.3522748 0.1540132 0.6434141 0.7498655 0.384272 0.2458761 0.8898764 -0.4287358 0.9023879 -0.04337888 0.1302115 0.2170269 0.9674422 -0.2394427 0.8663118 0.4383732 -0.4398618 0.8970752 -0.04216361 0.1241286 0.2141786 0.9688755 -0.008292436 0.6080462 0.7938585 -0.262155 0.8589636 0.4398369 -0.03776174 0.5865172 0.8090561 -0.589191 0.8073394 0.03251588 -0.4060549 0.7673041 0.4963506 -0.6011077 0.7984413 0.03407537 -0.2743896 0.4783094 0.8342245 -0.4761054 0.7240994 0.4990028 -0.764437 0.6339702 0.1171244 -0.236887 0.1836252 0.9540264 -0.3275945 0.4615032 0.8244372 -0.7695494 0.6276398 0.117738 -0.6223166 0.5669509 0.5397117 -0.1444238 0.161289 0.9762826 -0.41512 0.3904941 0.8216994 -0.5842485 0.5987233 0.5478907 -0.8041855 0.5765752 0.1443846 -0.4171338 0.1266295 0.8999802 -0.5793961 0.8126741 0.06213933 -0.9060109 0.3387217 0.2537952 -0.5800501 0.05536693 0.8126971 -0.6404827 0.2456837 0.7276135 -0.6477202 0.05053836 0.7602003 -0.5335773 0.6512458 0.5396056 -0.7324658 0.1007164 0.6733129 -0.8192276 0.2866684 0.4966763 -0.6980654 0.02783477 0.7154929 -0.7239002 0.1073809 0.6814968 -0.3186507 -0.9476232 -0.02172809 -0.06834524 -0.9928048 -0.09832316 -0.1889311 -0.9818304 -0.01772433 0.1818957 -0.9831829 0.0162931 0.422985 -0.9056866 -0.02855604 0.6306977 -0.7702388 0.09461784 0.8059071 -0.5865262 0.0806272 0.2751687 -0.9605069 0.04133677 0.9873241 -0.1263303 0.09608256 0.9284509 -0.3711114 0.01598298 0.9757366 -0.1615083 0.1478279 0.7206049 -0.684709 0.1090974 -0.195279 -0.9802539 -0.03111875 0.3020653 -0.9506823 0.07042551 -0.1727765 -0.9837628 -0.04857188 -0.1824528 -0.9821437 -0.04587745 0.9354574 -0.2702029 0.2278372 0.26518 -0.9578612 0.1103708 0.2764629 -0.9546915 0.1101479 0.6746319 -0.6826627 0.2807907 0.9030972 -0.2043875 0.3776788 0.9161384 -0.163953 0.3658003 0.6717641 -0.6854261 0.2809345 0.8334445 -0.2769265 0.4782074 0.2727586 -0.9472911 0.168055 -0.1571276 -0.9829376 -0.095627 -0.165768 -0.9815345 -0.09545195 0.2234979 -0.960457 0.1660452 0.5870745 -0.6819878 0.4361607 0.5828528 -0.6861251 0.4353332 0.7888312 -0.1749705 0.5891782 0.7700992 -0.2166517 0.6000077 -0.1604171 -0.9798563 -0.1189462 -0.1412186 -0.9815732 -0.1287299 -0.1349348 -0.982731 -0.1266193 0.2373388 -0.9470288 0.2163493 0.6691443 -0.2685232 0.6929222 0.4670732 -0.6816459 0.5632065 0.4598788 -0.6892016 0.5599222 0.177725 -0.9594498 0.2187919 0.621885 -0.1576557 0.767075 -0.1277081 -0.9802299 -0.1511296 -0.09871518 -0.984643 -0.1439914 0.1843772 -0.9517462 0.2453249 0.5682827 -0.2486628 0.7843607 -0.09764832 -0.9828952 -0.1561471 -0.3379319 0.9407613 -0.02775228 -0.07269829 0.9952903 -0.0641281 0.3026863 0.9519804 0.04598337 0.1813766 0.983331 -0.01275897 0.4230324 0.9038577 0.06391394 -0.1753398 0.9841504 -0.02653163 0.6273187 0.7729758 0.09476143 0.8059977 0.5864335 0.08039742 0.9875035 0.1244807 0.09665125 0.9289439 0.3698613 0.0163024 0.7198753 0.6854408 0.1093187 0.975508 0.1626023 0.1481371 0.9353369 0.2706447 0.2278077 -0.1959398 0.9794088 -0.04864311 0.2807338 0.9526457 0.1168538 0.6739727 0.6834173 0.2805379 0.9078018 0.1782103 0.379654 0.9075641 0.2121579 0.3623763 0.6711404 0.6861412 0.2806793 0.2834624 0.9515482 0.1191853 -0.1707338 0.9826987 -0.07178694 -0.1671203 0.9835588 -0.06843322 0.8333356 0.2773566 0.4781476 -0.1747813 0.9791681 -0.1033516 0.5864992 0.6827449 0.4357501 0.2429765 0.9530864 0.1805241 0.783462 0.2092035 0.5851678 0.7789935 0.1574747 0.6069357 0.5823108 0.686842 0.434928 -0.1427707 0.9838982 -0.1075215 -0.1495715 0.9813458 -0.1207842 0.2466812 0.9511232 0.1857774 0.6690608 0.2689626 0.6928324 -0.1350464 0.9800121 -0.1460787 0.4597575 0.6967856 0.550557 0.4636777 0.6820488 0.5655196 0.1954131 0.9535067 0.2294317 0.6219615 0.1586229 0.7668134 -0.105238 0.9851216 -0.1358694 0.2064859 0.9438965 0.2577264 0.5674986 0.253795 0.7832839 -0.1067141 0.9819416 -0.1562141 -0.6066713 0.7912285 -0.07686132 -0.5681663 0.8107353 -0.1410506 -0.7958402 0.5352433 -0.2831131 -0.5781996 0.7895423 -0.2056894 -0.8010701 0.519487 -0.2973552 -0.9171295 0.2073097 -0.3404353 -0.9173722 0.2362705 -0.3203193 -0.5476459 0.8060985 -0.2242527 -0.8817001 0.1699264 -0.4401476 -0.5183122 0.7918053 -0.3231052 -0.5146442 0.80158 -0.3043205 -0.7141284 0.5402234 -0.4451733 -0.7168599 0.5148631 -0.470136 -0.8151984 0.2227632 -0.5346291 -0.8122706 0.210564 -0.5439479 -0.4555949 0.8106031 -0.3679077 -0.7424394 0.1721071 -0.647428 -0.6002739 0.5446585 -0.5856778 -0.439521 0.7892548 -0.4288338 -0.6739257 0.2315804 -0.7015659 -0.652086 0.1908945 -0.7337187 -0.5956103 0.5106862 -0.6200388 -0.4010734 0.8067991 -0.433838 -0.3350217 0.7928034 -0.5091398 -0.3382989 0.8004279 -0.4948425 -0.4593387 0.5486338 -0.6985765 -0.5549139 0.1808622 -0.8120096 -0.4758856 0.3427787 -0.8099604 -0.4628149 0.5578113 -0.6889477 -0.5112981 0.2234018 -0.829859 -0.4521654 0.1121273 -0.8848581 -0.8861982 -0.4485061 -0.1161689 -0.7828376 -0.6027254 -0.1545557 -0.8446827 -0.5244539 -0.1070482 -0.9641706 -0.2332326 -0.126402 -0.6632422 -0.7436789 -0.08397364 -0.5140025 -0.8490536 -0.122105 -0.6406605 -0.766614 -0.04309511 -0.5931729 -0.799507 -0.09452265 -0.5727578 -0.806976 -0.144008 -0.5749945 -0.7921777 -0.2045384 -0.5490038 -0.8069628 -0.2177292 -0.7956581 -0.5355561 -0.2830334 -0.8008924 -0.5198054 -0.2972771 -0.9131111 -0.2266145 -0.3389308 -0.8816649 -0.1701236 -0.4401423 -0.7139686 -0.5405357 -0.4450506 -0.5096048 -0.7996216 -0.3176608 -0.5421572 -0.7801331 -0.3121829 -0.7167063 -0.5151871 -0.4700154 -0.8169524 -0.2134327 -0.5357568 -0.8091834 -0.2270603 -0.5419095 -0.4734688 -0.8078194 -0.3510771 -0.7423943 -0.1723093 -0.6474259 -0.4329056 -0.7963756 -0.4223491 -0.450401 -0.7864533 -0.4226464 -0.600148 -0.5449741 -0.5855132 -0.5954914 -0.5110121 -0.6198845 -0.6796821 -0.1934995 -0.707524 -0.6420646 -0.2565413 -0.7224539 -0.3797549 -0.8085949 -0.4494003 -0.3361052 -0.7942876 -0.5061034 -0.3211666 -0.802578 -0.5027133 -0.4584302 -0.5491243 -0.6987877 -0.5548851 -0.1810666 -0.8119838 -0.5036754 -0.2306827 -0.8325242 -0.4509774 -0.133214 -0.8825381 -0.9964093 0.001121938 -0.08466017 -0.997287 0.01576596 -0.0719043 -0.9963706 -0.00892508 -0.08465278 -0.9960189 -0.0101971 -0.08855795 -0.9925512 -8.74183e-4 -0.1218256 -0.9807664 -0.008097887 -0.1950177 -0.9665589 -0.005607903 -0.2563834 -0.9828649 0.01723152 -0.1835206 -0.9760454 -0.003027379 -0.2175456 -0.9073691 0 -0.4203349 -0.8206001 0 -0.571503 -0.8205999 0 -0.5715033 -0.7088963 0 -0.7053128 -0.708896 0 -0.705313 -0.5756566 0 -0.8176916 -0.5756558 0 -0.8176922 -0.4249238 0 -0.9052292 -0.4249249 0 -0.9052287 -0.2612856 0 -0.9652615 -0.2612857 -1.2638e-7 -0.9652615 -0.08970713 0 -0.9959682 -0.08970838 0 -0.9959681 0.08460044 0 -0.996415 0.08460044 0 -0.996415 0.07779198 0 0.9969697 0.07779037 0 0.9969698 -0.08915758 0 0.9960176 -0.08915889 0 0.9960175 -0.2536271 0 0.9673021 -0.2536332 -3.14633e-7 0.9673005 -0.4110243 -2.436e-7 0.9116244 -0.4110233 -2.639e-7 0.9116249 -0.556956 -1.21806e-7 0.830542 -0.5569556 -2.84213e-7 0.8305422 -0.6873589 0 0.7263181 -0.6873575 0 0.7263194 -0.7983469 0.02527248 0.6016674 -0.7733715 0.003540873 0.6339434 -0.75021 1.27145e-7 0.6611996 -0.799453 -0.02809339 0.6000715 -0.7757022 -0.005235314 0.6310774 -0.742483 2.78284e-4 0.6698649 0 -1 0 0 -1 1.22174e-5 0 -1 -1.15061e-5 -1.25882e-6 -1 -2.64184e-6 -1.25882e-6 -1 0 -9.89045e-7 -1 0 -9.89045e-7 -1 0 -8.41114e-7 -1 0 -8.41114e-7 -1 1.88708e-6 -7.56983e-7 -1 -1.69832e-6 -7.56983e-7 -1 1.56518e-6 -7.13062e-7 -1 -1.47437e-6 -7.13062e-7 -1 0 -6.99361e-7 -1 0 -6.99361e-7 -1 0 -7.13063e-7 -1 -1.47437e-6 -7.56983e-7 -1 0 0 -1 -9.43539e-6 0 -1 2.53161e-6 0 -1 -2.64184e-6 0 -1 9.0456e-6 0 1 -1.22174e-5 0 1 6.22838e-6 0 1 -3.83536e-6 0 1 3.92617e-6 0 1 -3.08477e-6 0 1 -2.71953e-6 0 1 3.98624e-6 0 1 -3.15283e-7 2.91803e-6 1 7.9038e-6 3.01858e-6 1 3.08099e-6 2.09392e-7 1 -1.08369e-5 3.39284e-6 1 8.05446e-6 0 1 -2.53161e-6 0 1 4.70627e-6 0 1 2.06266e-5 0 1 2.64184e-6 0 1 3.83535e-6 0 1 -6.22836e-6 0.9287059 0 0.3708173 0.8673657 0 0.4976714 0.8673652 -4.70226e-7 0.4976723 0.7888354 -7.05464e-7 0.6146047 0.7888354 -2.35155e-7 0.6146048 0.6946561 -4.70303e-7 0.719342 0.6946583 0 0.7193399 0.5867114 0 0.8097962 0.5867086 -7.05567e-7 0.8097982 -0.8947124 9.90305e-6 -0.4466429 -0.8947072 -1.31674e-5 -0.4466532 -0.8308994 1.97524e-5 -0.5564228 -0.8308856 -1.97512e-5 -0.5564435 -0.7536857 2.41395e-5 -0.6572352 -0.7536669 -2.41409e-5 -0.6572566 -0.6643021 8.7774e-6 -0.7474642 -0.6642966 -5.48637e-6 -0.7474691 -0.5642187 1.09732e-5 -0.8256254 -0.564211 -6.58402e-6 -0.8256307 -0.455035 4.38887e-6 -0.8904737 -0.455033 0 -0.8904746 -0.9531254 0.2755929 -0.1249027 -0.9794912 0.0877524 -0.1813738 -0.9601501 0.2685475 -0.07742124 -0.9632864 0.1743384 -0.2041701 -0.9632509 -0.1745313 -0.2041733 -0.9243677 -0.2033714 -0.3227761 0.9418526 -6.1941e-5 -0.3360264 0.9418317 6.55857e-5 -0.3360849 0.8897434 -5.46518e-5 -0.456461 0.8897193 5.82985e-5 -0.4565082 0.8223212 -4.91937e-5 -0.5690236 0.8222897 6.92294e-5 -0.5690692 0.7407484 -6.19492e-5 -0.6717826 0.7407004 8.5626e-5 -0.6718355 0.6464152 -7.2872e-5 -0.7629859 0.6463618 7.28754e-5 -0.7630312 0.5409396 -7.37658e-5 -0.8410614 0.5408959 3.6436e-5 -0.8410895 0.4261348 -4.73584e-5 -0.9046598 0.426114 -9.10969e-7 -0.9046695 0.3016293 -1.40132e-5 -0.9534254 0.3039923 -0.00527209 -0.9526599 -0.9388772 9.9599e-6 0.3442524 -0.9388399 -1.50819e-5 0.3443541 -0.8852472 1.50871e-5 0.465121 -0.8851754 -2.08221e-5 0.4652578 -0.8160412 2.01779e-5 0.5779938 -0.8159223 -2.72429e-5 0.5781617 -0.7327815 2.66735e-5 0.680464 -0.7326294 -2.47804e-5 0.6806279 -0.6411057 2.25028e-5 0.7674527 -0.640981 -1.20329e-5 0.7675569 -0.5481868 1.14875e-5 0.8363559 -0.5488448 -1.39679e-4 0.8359242 0 1 -8.15864e-6 0 1 2.65659e-6 0 1 9.95631e-6 0 1 -3.98625e-6 0 1 -1.55784e-6 0 1 3.081e-6 0 1 -5.51748e-7 0 1 -3.081e-6 0 1 5.75319e-6 0 1 2.70922e-6 0 1 -9.9563e-6 0 1 -1.03133e-5 0.2425703 0 0.9701339 0.2425705 0 0.9701338 0.4005749 -2.03014e-7 0.9162641 0.4005782 4.46632e-7 0.9162627 0.5474176 4.06045e-7 0.8368597 0.5474151 1.62417e-7 0.8368612 0.678996 0 0.734142 0.6789957 0 0.7341423 0.7916545 0 0.610969 0.7916543 0 0.6109693 0.8822511 0 0.4707792 0.8822491 -4.87295e-7 0.4707829 0.9136914 -4.18419e-7 0.4064088 0.9375899 -0.006723105 0.3476781 0.9275861 9.14359e-4 0.3736082 0.9407186 0.004027783 0.3391643 0.9520086 0.03379708 0.3041998 0.9635934 -0.05852192 -0.2608892 0.9638628 0.05350559 -0.2609707 0.945691 -0.02265989 -0.3242762 0.9246335 -0.0460512 -0.3780637 0.8937101 0.1588427 -0.4195848 0.9050523 0.01823645 -0.4249094 0.8879781 0.001839101 -0.4598822 0.8888434 -0.001732528 -0.458208 0.804514 -0.002736449 -0.5939275 0.7881537 -8.08617e-4 -0.615478 0.8255476 -0.00953263 -0.564252 0.8176557 -0.002665221 -0.5757014 0.8379554 0.001439869 -0.5457369 0.7761533 0 -0.6305444 0.7932206 0.00197041 -0.6089312 0.8176327 0.008160591 -0.5756823 0.7052695 0 -0.7089394 0.7052698 0 -0.7089391 0.5714557 0 -0.8206331 0.5714527 2.72205e-7 -0.820635 0.420279 2.13874e-7 -0.907395 0.4202795 1.94431e-7 -0.9073947 0.2563307 0 -0.9665892 0.2563319 1.2638e-7 -0.9665889 0.9208595 -0.3518167 -0.1680559 0.9880447 -0.1327944 -0.07831573 0.9631019 -0.2522073 -0.0939477 0.5599685 -0.8152756 -0.1475159 0.9639189 -0.1675301 -0.2068673 0.570622 -0.7991899 -0.1889074 0.8005868 -0.5374156 -0.2650385 0.8083215 -0.5165022 -0.282563 0.920516 -0.2116465 -0.3284145 0.9206155 -0.2211356 -0.3218172 0.5351208 -0.8179338 -0.2112586 0.876738 -0.1703543 -0.4497889 0.727312 -0.5437929 -0.4186964 0.5302655 -0.7866347 -0.3162664 0.5254297 -0.7952552 -0.3024777 0.8281685 -0.2363247 -0.5082203 0.7328581 -0.5105494 -0.4497315 0.8091242 -0.178436 -0.5598915 0.4711115 -0.8082331 -0.3532891 0.4556998 -0.7831408 -0.4231175 0.4522848 -0.7967941 -0.4006966 0.6255046 -0.5492281 -0.5541592 0.7177909 -0.2470303 -0.6509626 0.7075119 -0.1973845 -0.6785767 0.6227517 -0.5054029 -0.597284 0.3893655 -0.8075047 -0.4430923 0.637432 -0.1661342 -0.7523828 0.3631115 -0.7847606 -0.5022957 0.3644473 -0.794172 -0.4862809 0.4993739 -0.553762 -0.6663133 0.3028078 -0.8073372 -0.5064724 0.5300306 -0.199818 -0.8240997 0.5434771 -0.2277708 -0.8079314 0.4830182 -0.5010921 -0.7180531 0.419542 -0.1752237 -0.8906633 0.2610754 -0.7935776 -0.5496129 0.2794304 -0.8160675 -0.5059175 0.2911909 -0.7111284 -0.6399253 0.3593085 -0.5553945 -0.7499563 0.3649265 -0.2305986 -0.9020271 0.3349695 -0.4911932 -0.8040676 0.3429527 -0.3168542 -0.8843002 0.3000082 -0.09840589 -0.9488475 0.6265229 0.7778586 -0.04904359 0.5142297 0.8503771 -0.1114756 0.6637175 0.7439806 -0.07727891 0.8471395 0.5221336 -0.09864687 0.7846115 0.6034102 -0.1424117 0.8872438 0.4484407 -0.1081633 0.9633399 0.2412178 -0.117433 0.5755681 0.8094 -0.11659 0.9630403 0.1686855 -0.2099968 0.800893 0.5372954 -0.2643563 0.5769647 0.7940382 -0.1913502 0.5781443 0.7933047 -0.1908321 0.9178107 0.2244073 -0.3275132 0.9225258 0.2130216 -0.32182 0.8087443 0.5160785 -0.2821275 0.5313869 0.8092329 -0.2505396 0.8767161 0.1703425 -0.449836 0.727684 0.5436299 -0.4182614 0.5034835 0.8039883 -0.3163974 0.5330663 0.7886446 -0.3063983 0.8284174 0.2363247 -0.5078142 0.733274 0.510163 -0.4494918 0.8091536 0.178031 -0.5599783 0.461058 0.8046423 -0.3741341 0.4606045 0.7884363 -0.4076908 0.6258526 0.5490373 -0.5539554 0.4098629 0.8085438 -0.4222198 0.6231032 0.5050417 -0.597223 0.7265417 0.1945898 -0.6589932 0.7025352 0.2302966 -0.6733556 0.6374009 0.1659365 -0.7524529 0.3779461 0.7866544 -0.4881923 0.3637068 0.7952706 -0.4850382 0.499627 0.5535468 -0.6663023 0.3116215 0.807751 -0.5004302 0.4832604 0.5007482 -0.7181301 0.5252288 0.2389376 -0.8167273 0.5466631 0.2031045 -0.8123473 0.4195301 0.1751081 -0.8906916 0.3501106 0.5587062 -0.7518445 0.3626192 0.2328345 -0.9023833 0.3021023 0.1114598 -0.9467371 0.06649881 0.9956569 -0.06515657 0.3227581 0.9461412 -0.025379 -0.928634 0.3706079 0.01699507 -0.9883024 0.1264276 0.08529084 -0.9765535 0.1778249 0.1213324 -0.7257716 0.6819928 0.09022986 -0.806388 0.5879954 0.06324464 -0.6316712 0.7711651 0.07934713 -0.3057295 0.9513376 0.03855454 -0.4226096 0.9061065 0.01929217 -0.1788262 0.9836078 0.0231719 0.1765484 0.9840293 -0.02274 0.1954081 0.9799228 -0.03958326 -0.9370915 0.2798147 0.2087183 -0.6864973 0.6881625 0.2348484 -0.9128589 0.2336261 0.3348247 -0.9295812 0.186415 0.3180065 -0.2847213 0.9534721 0.09912037 -0.693257 0.6790788 0.2413436 -0.2929812 0.9503015 0.105305 0.1806477 0.9817215 -0.0599119 0.1691415 0.9837151 -0.06079417 0.1821812 0.9795061 -0.08589482 -0.8543611 0.2615554 0.4490611 -0.6215923 0.6911795 0.368638 -0.8470616 0.1735745 0.5023532 -0.2551292 0.9544894 0.1544649 -0.6302831 0.6761119 0.3815968 0.1553309 0.9830281 -0.09761244 0.1550467 0.9830788 -0.09755331 -0.2662087 0.9492514 0.1674954 -0.7839775 0.2770741 0.555526 0.1564607 0.9794899 -0.1269635 -0.7155124 0.2148982 0.6647261 -0.7233737 0.1968467 0.6618021 -0.5311703 0.6940478 0.4859588 -0.2153081 0.955401 0.2021172 -0.5391131 0.6732278 0.5060845 -0.2261306 0.9482555 0.2228824 0.1223753 0.9844451 -0.1260648 0.1336385 0.9822377 -0.131719 -0.617443 0.2685053 0.7393707 0.1219563 0.9799545 -0.1575309 -0.5282191 0.2664032 0.8062345 -0.579966 0.1821101 0.7940248 -0.4198074 0.6966882 0.5817108 -0.4171802 0.7092665 0.5682445 -0.1567567 0.9572223 0.243214 0.09262841 0.9845276 -0.1487461 -0.05901187 0.9977826 -0.03078252 0.1628026 0.9781064 0.1296278 0.1260702 0.9596108 -0.2515026 0.1959879 -0.9804342 -0.01837182 -0.9645221 -0.250674 0.08282452 -0.9766012 -0.177818 0.120958 -0.80479 -0.5851278 0.09969294 -0.6332775 -0.7730137 0.03754234 -0.7261575 -0.6814704 0.09106814 0.2145757 -0.9752844 -0.05270326 -0.4231177 -0.9045187 0.05307883 -0.187228 -0.9822183 -0.01389414 -0.3609591 -0.9304613 0.06285256 0.1746521 -0.9843135 -0.02497422 -0.937213 -0.2794358 0.2086809 -0.6873674 -0.6873539 0.2346718 -0.9260014 -0.1650446 0.3395316 -0.921327 -0.22851 0.314547 -0.2810991 -0.9546993 0.0976358 -0.6940259 -0.6783936 0.2410606 0.2073763 -0.9745582 -0.08503699 -0.8546127 -0.2607932 0.4490256 0.1637979 -0.9831027 -0.08172655 -0.3223407 -0.9355874 0.144128 0.1711198 -0.9799498 -0.1020604 -0.6224007 -0.6903973 0.3687399 -0.8473958 -0.1728508 0.5020389 -0.2403193 -0.9597534 0.1453275 -0.631039 -0.6754016 0.381605 -0.7841886 -0.2766645 0.5554323 -0.2604733 -0.9453713 0.1960276 0.1487525 -0.9825627 -0.1115496 0.149165 -0.9824193 -0.1122596 0.1460494 -0.979939 -0.1356065 -0.5318452 -0.693288 0.4863049 -0.7193152 -0.1908304 0.6679591 -0.7214063 -0.2108439 0.6596346 -0.205111 -0.9596381 0.192417 -0.5397677 -0.6724941 0.5063622 -0.2188532 -0.9461694 0.2384678 0.1261659 -0.9815644 -0.1435741 0.123932 -0.9830591 -0.1350396 -0.6176376 -0.2680874 0.7393599 0.1156169 -0.9803327 -0.1599392 -0.4181205 -0.6962329 0.5834681 -0.545447 -0.1109793 0.8307655 -0.5688957 -0.2547076 0.781973 -0.1476152 -0.9613841 0.232272 -0.4154543 -0.7091551 0.5696462 -0.1302823 -0.9771175 0.1681308 0.1276941 -0.9685439 -0.2135812 0.1157599 -0.9803097 -0.1599767 0.1195099 -0.9612591 -0.2483913 0.8675884 -3.5512e-5 0.4972832 0.8600473 -6.75126e-4 0.5102138 0.6987131 3.29349e-4 0.715402 0.6831467 -5.38177e-4 0.7302809 0.4567947 9.61997e-4 0.8895716 0.4423633 2.60477e-4 0.8968359 0.1888509 -5.79431e-4 0.9820057 0.1978377 -1.90815e-4 0.9802349 -0.07915014 -2.18571e-4 0.9968628 -0.08594459 -5.29465e-4 0.9962999 -0.3600918 4.12403e-4 0.9329169 -0.3749856 -2.49693e-4 0.9270306 0.8648149 0.05323189 0.4992609 0.8942369 0.04307973 0.4455161 0.9197621 0.136901 0.3678258 0.8516618 0.07060909 0.5193137 0.8566829 0.2398521 0.4566897 0.7479698 0.1033938 0.6556303 0.7931901 0.3414126 0.5042688 0.6762103 0.1450744 0.7222833 0.9066412 0.3951513 0.1478417 0.547834 0.167226 0.8197034 0.6146758 0.4858223 0.62141 0.7637742 0.6250141 0.1612653 0.6911783 0.4498481 0.5656052 0.4326233 0.2104462 0.8766696 0.4268761 0.6152982 0.6627104 0.34421 0.2158957 0.9137334 0.1910982 0.2562329 0.9475369 0.7489585 0.6408461 0.1684559 0.4614194 0.6055127 0.6484184 0.5508722 0.8173061 0.1689697 0.144031 0.2536283 0.9565187 0.237454 0.6996122 0.6739129 -0.06177407 0.2838089 0.956889 0.5146325 0.8383432 0.179817 0.3099076 0.9356028 0.1691291 0.2118057 0.7028797 0.6790423 0.0202912 0.7586418 0.651192 -0.08136272 0.2823493 0.9558552 -0.1099696 0.2873629 0.951488 0.3528895 0.9223903 0.1570516 -0.11063 0.7562593 0.644851 -0.3475047 0.2806005 0.8947088 0.1851736 0.9680254 0.1692262 -0.3595757 0.2841763 0.8887909 -0.1090933 0.7566189 0.6446909 0.04732912 0.987568 0.149898 0.9167674 0.3756324 -0.1357868 0.7626612 0.6146171 -0.201479 0.7741692 0.5985209 -0.2059974 0.5317589 0.8157681 -0.2274971 0.5789197 0.7763919 -0.2491338 0.3613376 0.9033424 -0.2311011 0.4460378 0.8547053 -0.2655734 0.1929444 0.9496561 -0.2468313 0.2581099 0.9273276 -0.2710033 0.9584494 0.07639372 -0.2748434 0.9616676 0.06619489 -0.2661086 0.9328809 0.02086287 -0.3595803 0.9076241 0.09844696 -0.408077 0.8772331 0.1543616 -0.4545708 0.9147472 0.2383688 -0.3262177 0.8805348 0.01261878 -0.4738137 0.889881 0.287464 -0.3542265 0.8700232 0.03611052 -0.4916867 0.840904 -0.001019418 -0.5411834 0.7504833 0.5114819 -0.4185228 0.756496 0.3575577 -0.5476007 0.7365769 0.2087323 -0.6433392 0.7451047 0.3687261 -0.5557518 0.7844079 0.4589518 -0.417214 0.7274734 0.2215697 -0.649376 0.6922348 0.1286408 -0.7101145 0.6613398 0.02956604 -0.7495036 0.7015225 0.02967506 -0.7120293 0.7119903 0.1070923 -0.6939749 0.5884644 0.3439354 -0.7317227 0.5992075 0.5241954 -0.6051195 0.5943452 0.5273184 -0.6071978 0.6354895 0.6239697 -0.4547692 0.5520155 0.6798809 -0.4827432 0.505134 0.2341517 -0.83067 0.5589152 0.3736678 -0.7402609 0.505055 0.09285813 -0.8580775 0.5361363 0.07615554 -0.8406891 0.5632351 0.1862765 -0.8050263 0.4220147 0.7624782 -0.4904391 0.4576408 0.4419385 -0.771528 0.4295969 0.6493761 -0.6275008 0.4909052 0.7132392 -0.5003019 0.4591979 0.6391 -0.6169996 0.1984543 0.3379086 -0.9200183 0.3143507 0.5552933 -0.7699565 0.5281068 0.6891759 -0.4961247 0.497257 0.6159142 -0.6110526 0.3365056 0.1048168 -0.9358298 0.05363345 0.1951863 -0.9792987 0.2246634 0.8217506 -0.5236911 0.6615064 -0.002448618 -0.7499355 0.6693488 -0.004387497 -0.7429354 0.5073215 -2.90891e-4 -0.8617569 0.5340367 -0.008476912 -0.8454189 0.3388589 0.005748033 -0.9408196 0.3884877 -0.006664872 -0.9214299 0.9806271 0.0616573 -0.1859269 0.9716504 -0.08209836 -0.2217105 0.9333803 -0.02099263 -0.3582745 0.9082117 -0.101065 -0.4061248 0.860344 -0.1909751 -0.4725852 0.9062876 -0.3059781 -0.2915823 0.8836669 -0.005661785 -0.4680818 0.5113495 -0.7308865 -0.4520251 0.8536478 -0.0664972 -0.5165886 0.8197537 -0.01449519 -0.5725328 0.7755681 -0.1631935 -0.6098049 0.8214744 -0.2645864 -0.5051475 0.7526702 -0.5116595 -0.4143578 0.7985289 -0.4399876 -0.4108074 0.754711 -0.3417695 -0.5600045 0.7853736 -0.05047816 -0.6169605 0.7837224 -0.001588404 -0.6211094 0.6960932 -0.1130678 -0.7089923 0.7366726 -0.219344 -0.6396887 0.6691811 -0.04023212 -0.7420096 0.5914347 -0.6636883 -0.4579551 0.6172037 -0.4936785 -0.612651 0.6596296 -0.5901649 -0.465397 0.6344137 -0.04473155 -0.7716984 0.6575179 -0.1471911 -0.7389215 0.6272737 -0.4818364 -0.6118509 0.5720919 -0.3608697 -0.7365351 0.5397716 -0.2074646 -0.8158462 0.5913491 -0.3395509 -0.7314448 0.5317882 -0.08055609 -0.8430374 0.4742809 -0.5948544 -0.6490039 0.5213782 -0.7075769 -0.4769694 0.3317344 -0.5192199 -0.7876313 0.4067437 -0.6506295 -0.6412807 0.3559807 -0.780858 -0.5133599 0.4356734 -0.4314932 -0.7899383 0.3421756 -0.3285353 -0.8803298 0.3778221 -0.2984805 -0.8764474 0.3347618 -0.1040422 -0.9365414 0.3880741 -0.08435642 -0.9177596 0.9235781 -0.3576746 -0.1381035 0.71913 -0.6666952 -0.1958814 0.7745379 -0.5954064 -0.2135 0.6081224 -0.7584728 -0.2343208 0.6169751 -0.750192 -0.2378104 0.3614151 -0.8988685 -0.2478199 0.3861916 -0.885618 -0.2579476 0.2067673 -0.9404114 -0.2699515 0.8942644 -0.0353741 0.446139 0.9529924 -0.04741704 0.299261 0.9212335 -0.1510512 0.3584861 0.8661698 -0.05842304 0.4963233 0.8257032 -0.3102735 0.4711099 0.7848117 -0.08790242 0.6134687 0.692623 -0.1375883 0.7080557 0.7299321 -0.3970834 0.5563487 0.6911692 -0.1380513 0.709385 0.6698424 -0.449806 0.5907501 0.6089661 -0.149728 0.7789364 0.4663214 -0.1992135 0.8618923 0.9228067 -0.3751937 0.08750802 0.619444 -0.7719815 0.1425964 0.7973023 -0.5849354 0.1488621 0.727887 -0.4138479 0.5467271 0.4460279 -0.2022367 0.8718713 0.5202478 -0.5682764 0.6374984 0.4285829 -0.2087212 0.8790634 0.606853 -0.7676913 0.2058628 0.5201077 -0.5683352 0.6375603 0.7046481 -0.6922121 0.1559281 0.1835555 -0.2461794 0.9516844 0.2072256 -0.24957 0.9459241 0.2950289 -0.6686604 0.682533 0.3990198 -0.6538267 0.6428794 0.4839653 -0.8519869 0.1997395 0.6008239 -0.7852342 0.1497268 -0.07555049 -0.2856312 0.955357 0.2521055 -0.9493071 0.1877738 0.1548969 -0.7144262 0.6823505 -0.004649758 -0.7631657 0.6461862 -0.1073881 -0.2780622 0.9545415 0.3533195 -0.9232429 0.1509566 -0.1345198 -0.7558286 0.6408022 0.03588056 -0.9835258 0.1771716 0.2084887 -0.9704112 0.121798 -0.3450116 -0.2940414 0.8913511 -0.1683807 -0.759045 0.6288869 -0.4262799 -0.2673607 0.8641781 0.01279783 -0.9998518 -0.01152378 0.009672045 -0.9998568 -0.01388949 0.006796896 -0.9998693 -0.01467442 0.00678873 -0.9998565 0.01552838 0.01085782 -0.9998295 -0.01494443 0.006885588 -0.9998568 -0.01546579 0.004373252 -0.9998546 -0.01649069 0.007394731 -0.9998348 0.01660889 0.003948628 -0.9998676 0.01579225 0.9951848 0 -0.09801679 0.9945202 0.002004384 -0.1045261 0.9569394 -0.001871824 -0.2902817 0.9510512 0.00374186 -0.3090108 0.8819172 -0.003477096 -0.4713916 0.8660109 0.005215048 -0.499998 0.773001 -0.004812479 -0.6343867 0.7431296 0.006418883 -0.6691168 0.6343797 -0.005883991 -0.7729994 0.5877708 0.007353723 -0.8089941 0.4713891 -0.0066877 -0.8819001 0.4067199 0.008024871 -0.9135177 0.2902755 -0.007221221 -0.956916 0.2902749 -0.007221162 0.9569162 0.4067223 0.008025228 0.9135167 0.4713897 -0.006686687 0.8818998 0.5877677 0.007354557 0.8089964 0.6343834 -0.005885004 0.7729963 0.7431295 0.006417214 0.6691169 0.7730008 -0.004814147 0.6343868 0.8660153 0.005213558 0.4999903 0.8819142 -0.003474593 0.4713971 0.9510487 0.003744006 0.3090185 0.9569394 -0.001871883 0.2902817 0.9951825 0.002137541 0.09801656 0.9945222 0 0.1045264 0.004131019 0.9998551 0.01652127 0.9951848 0 0.09801685 0.9945195 -0.002005875 0.1045324 0.9569376 0.001870214 0.290288 0.9510506 -0.003742396 0.3090127 0.881917 0.003476142 0.4713919 0.8660126 -0.005215406 0.4999949 0.7730007 0.004812598 0.6343869 0.7431327 -0.006417393 0.6691133 0.6343801 0.005885422 0.7729989 0.5877676 -0.007353425 0.8089964 0.4713899 0.0066877 0.8818997 0.4067199 -0.00802493 0.9135177 0.2902749 0.007221162 0.9569162 -0.9936924 0.006236016 -0.1119673 -0.9927091 0 -0.1205348 -0.9438714 -0.005356848 -0.33027 -0.9349607 0.01070863 -0.3545897 -0.8466807 -0.009813547 -0.532011 -0.8228972 0.01472145 -0.5679996 -0.7070434 -0.01339137 -0.7070434 -0.6630185 0.01784586 -0.7483903 -0.5319625 -0.01607173 -0.8466154 -0.4646253 0.02008074 -0.8852798 -0.4646248 0.02008396 0.88528 -0.5319681 -0.01607048 0.8466119 -0.6630179 0.01784586 0.7483909 -0.7070437 -0.01339149 0.7070431 -0.8228971 0.01472157 0.5679998 -0.8466806 -0.009813487 0.5320111 -0.9349609 0.01070857 0.3545894 -0.9438723 -0.005359351 0.3302671 -0.9926925 0.005791962 0.1205328 -0.9937115 0 0.1119706 0.2902754 0.007221221 -0.9569159 0.4067227 -0.008025228 -0.9135165 0.4713889 0.006686687 -0.8819001 0.5877676 -0.007354676 -0.8089964 0.6343833 0.005884945 -0.7729964 0.7431295 -0.006417214 -0.6691169 0.7730009 0.004814267 -0.6343867 0.8660138 -0.005213677 -0.499993 0.8819171 0.003477156 -0.4713918 0.9510512 -0.0037418 -0.3090108 0.9569376 0.001870095 -0.290288 0.9951826 -0.002139151 -0.09801661 0.9945214 0 -0.1045327 0.9770447 6.05207e-5 -0.2130344 0.9777134 -0.006995677 -0.2098277 0.9972681 -0.01551347 -0.07222056 0.9968725 -0.001173198 -0.07901883 -0.9760821 -9.95265e-6 0.2174027 -0.9760963 5.59707e-6 0.2173388 -0.9962952 -5.40837e-6 0.08600109 -0.9963277 8.46175e-5 0.08562195 0.2645474 0.8071457 -0.5277599 0.3405374 0.5416844 -0.768513 0.3522021 0.2744581 -0.8947773 0.07351666 0.4071478 -0.9103989 0.004373729 0.9998545 -0.01649272 0.006892561 0.9998567 -0.01546442 0.007147252 0.9998555 -0.01543098 0.01002186 0.9998547 -0.01379406 0.009672045 0.9998568 -0.01388955 0.01279783 0.9998518 -0.01152276 0.01186245 0.9998586 -0.01192414 0.01397514 0.999854 -0.009839892 0.0145747 0.9998584 -0.008414328 0.01546967 0.999854 -0.007262527 0.01603114 0.999858 -0.005208611 0.01646816 0.9998545 -0.004458963 0.016837 0.9998568 -0.001769781 0.01571613 0.9998752 0.001651585 0.01506084 0.9998641 0.006714105 0.6873788 0.7222982 -0.07613068 0.0163381 0.9998666 1.11676e-4 0.01632851 0.9998622 -0.002995371 0.5811165 0.8087819 -0.09041988 0.5386953 0.8414294 0.04247468 0.2749276 0.7994042 -0.5341984 0.2826585 0.741411 -0.6086164 0.01616156 0.9998557 0.005251824 0.01502174 0.9998551 0.008015513 0.01461625 0.9998576 0.008438885 0.006801009 0.9998559 0.01555591 0.006891071 0.9998565 0.01547807 0.009332537 0.9998548 0.01426732 0.009905517 0.999858 0.01363438 0.01159739 0.9998542 0.01253855 0.01250779 0.9998584 0.01126259 0.01351588 0.9998543 0.01043063 0.01186245 -0.9998586 -0.01192384 0.01397508 -0.999854 -0.009839892 0.01457464 -0.9998584 -0.008414447 0.01546967 -0.999854 -0.007263123 0.01603108 -0.999858 -0.00520879 0.01646822 -0.9998545 -0.004458427 0.01683706 -0.9998568 -0.001769244 0.01519751 -0.9998682 -0.005720138 0.01573401 -0.999875 0.001652598 0.01739823 -0.9998254 0.006831169 0.0170893 -0.9998496 0.003000676 0.01749598 -0.9998308 0.005684733 0.01480299 -0.999854 0.008545637 0.014889 -0.9998576 0.007945239 0.01287448 -0.99985 0.01159238 0.01324754 -0.9998601 0.01022416 0.01036578 -0.9998445 0.01426678 0.01124274 -0.999863 0.01215618 0.009332537 -0.9998548 0.01426732 0.9132494 -0.3956173 -0.09727549 0.841054 -0.52604 -0.1261351 0.7892561 -0.6070134 -0.09278821 0.6636012 -0.7440078 -0.07801234 0.5933754 -0.7993035 -0.09497243 0.5161261 -0.8552426 -0.04662495 0.991047 0.112579 -0.07177603 0.9507106 0.274096 -0.1449857 0.01715689 0.802989 -0.595747 0.03822487 0.789702 -0.6122987 0.07552975 0.7751671 -0.6272251 0.03866523 0.7838457 -0.6197509 0.9437015 0.3297599 0.02619171 0 0.1945436 -0.9808939 0 0.3534243 -0.9354631 -0.9999999 -5.8897e-4 -2.72277e-5 -1 -2.86688e-6 -5.62724e-5 -0.9999983 0.001822412 2.68506e-5 -1 -1.05162e-5 1.10176e-4 -0.9999994 -0.001169443 5.2657e-5 -0.3652787 0.03146511 0.9303663 -0.1721546 -0.03775429 0.9843462 0.004943072 0.02518033 0.9996707 0.08046394 -0.009102642 0.996716 0.2634489 0.008526742 0.9646357 0.3228787 -0.0148245 0.9463242 0.4823169 0.01088726 0.8759292 0.5369122 -0.01160466 0.8435583 0.6829942 1.95649e-4 0.7304239 0.7069792 0.01756274 0.7070163 0.8622258 0.02245211 0.5060262 0.8469814 0.001566112 0.5316203 0.9579504 -0.01565957 0.2865062 0.9746547 -0.06454974 0.2141997 0.9018718 0.03292375 0.4307477 0.8663946 -0.03503572 0.4981296 0.7632144 0.02281022 0.6457426 0.6925061 -0.01974886 0.7211418 0.5584239 0.02038311 0.8293053 0.4849378 -0.01026314 0.8744884 0.266604 -0.008169412 0.9637716 0.3247047 0.01521676 0.9456931 0.08067214 0.008671283 0.996703 0.007138431 -0.02531516 0.9996541 -0.172376 0.03792792 0.9843008 -0.3650306 -0.03198736 0.9304459 0.3652645 -0.03145712 0.9303721 0.1721559 0.03774923 0.9843462 -0.004943072 -0.02519321 0.9996704 -0.08047193 0.009101271 0.9967153 -0.263457 -0.008527219 0.9646335 -0.3228912 0.01483058 0.94632 -0.4823057 -0.01087868 0.8759354 -0.5369053 0.01160687 0.8435628 -0.6829802 -1.85622e-4 0.7304369 -0.7069783 -0.01756256 0.7070173 -0.8622291 -0.02244311 0.5060212 -0.8469825 -0.001560986 0.5316186 -0.9579558 0.01567173 0.2864876 -0.9747015 0.06521481 0.2137851 -0.9020975 -0.03361105 0.4302216 -0.8663679 0.03490734 0.498185 -0.7632591 -0.02290868 0.6456864 -0.6924782 0.01969426 0.72117 -0.5583975 -0.02043694 0.8293219 -0.4849364 0.01020979 0.8744899 -0.2665979 0.008169472 0.9637733 -0.3247669 -0.01524555 0.9456712 -0.08065557 -0.008673131 0.9967044 -0.007117271 0.02531027 0.9996544 0.172347 -0.0379191 0.9843062 0.3650158 0.03200197 0.9304512 -0.0348258 -0.3679337 -0.9291996 -0.2009971 -0.4299558 -0.8801921 0.01379847 -0.4688369 -0.8831771 -0.006810367 -0.5376665 -0.8431302 -0.08526945 -0.6019422 -0.793974 0.7998824 -0.393535 -0.453121 0.2711328 -0.6439873 -0.7153792 0.07550173 -0.6817546 -0.7276746 0.007157325 -0.7028079 -0.7113437 0.003139913 -0.64168 -0.7669662 -3.17041e-4 -0.6877177 -0.7259781 -0.04496437 -0.7426302 -0.6681906 -0.003902077 -0.7284586 -0.6850787 0.04387223 -0.7836796 -0.6196143 0.06918358 -0.7772935 -0.6253228 0.03510981 -0.7913367 -0.6103717 0.01595443 -0.8040902 -0.5942932 0.00893414 -0.8123072 -0.5831614 -6.93143e-6 -0.8414359 -0.5403571 -0.0257253 -0.7836049 -0.6207267 -0.006099164 -0.7031544 -0.7110111 5.52156e-4 -0.7520241 -0.6591355 1.99335e-5 -0.7571453 -0.6532465 -0.006613194 -0.812819 -0.5824788 -0.009271204 -0.818469 -0.574476 -0.00546807 -0.8064086 -0.5913335 -6.34422e-4 -0.7754448 -0.6314151 9.59539e-6 -0.831687 -0.5552449 0.008444845 -0.8858742 -0.4638489 0.04678064 -0.8619065 -0.5049048 2.70036e-4 -0.8963077 -0.4434328 -0.004276156 -0.9084839 -0.417898 0.004151761 -0.9565906 -0.2914057 -0.004463434 -0.9712147 -0.2381641 0.004330575 -0.9940513 -0.1088266 -0.004632651 -0.9987489 -0.04979175 0.004490196 -0.9969801 0.07752799 -0.00478363 -0.9900862 0.1403796 0.004630982 -0.9652754 0.2611936 -0.004915475 -0.9455413 0.3254655 0.004753172 -0.9000412 0.435779 -0.005028665 -0.8667296 0.498753 0.004856288 -0.803541 0.5952296 -0.005122244 -0.7565109 0.6539611 0.004942238 -0.6791319 0.7339996 -0.005199372 -0.6188631 0.7854818 0.00500679 -0.5311265 0.8472778 -0.005254805 -0.4587992 0.8885245 0.005054295 -0.3646765 0.9311206 -0.005292356 -0.2821009 0.9593701 0.005082011 -0.1855655 0.9826188 -0.005312919 -0.09518533 0.9954455 0.005091547 0 0.9999871 -0.005311787 0.09518575 0.9954454 0.005082786 0.1855655 0.9826188 -0.005292356 0.282101 0.9593701 0.005055069 0.3646796 0.9311195 -0.005253195 0.4587972 0.8885256 0.005007982 0.531128 0.8472769 -0.005197048 0.6188687 0.7854773 0.004941821 0.679129 0.7340024 -0.00512278 0.7565059 0.6539669 0.004857063 0.8035414 0.595229 -0.005027651 0.8667303 0.4987519 0.004753053 0.900039 0.4357835 -0.004915535 0.9455419 0.3254635 0.004630625 0.9652754 0.2611936 -0.004783809 0.9900862 0.1403796 0.004490017 0.99698 0.07752877 -0.004632592 0.9987488 -0.04979276 0.004330575 0.9940514 -0.108826 -0.004463851 0.9712149 -0.2381634 0.004151642 0.9565896 -0.2914087 -0.004276096 0.9084848 -0.417896 0.00911653 0.8858672 -0.4638493 0.002228081 0.8908359 -0.4543198 0.006986856 0.8771333 -0.4801962 -0.002102255 0.812835 -0.5824903 -0.01777905 0.7844115 -0.619986 -0.008729457 0.8074182 -0.5899151 -0.001382112 0.8379461 -0.5457513 0.001779973 0.8437194 -0.5367816 0.006426632 0.8149762 -0.5794589 0.003789305 0.8207705 -0.5712455 5.5493e-4 0.7522848 -0.6588378 2.26847e-5 0.757261 -0.6531123 -0.01788985 0.6876075 -0.7258622 -1.73249e-4 0.7178849 -0.6961619 -0.005963921 0.7031094 -0.7110568 -0.02600586 0.7836159 -0.6207011 -0.002218961 0.7281021 -0.6854651 0.8126284 0.3821204 -0.440022 0.2906079 0.6396347 -0.711628 0.09412133 0.6788026 -0.7282638 0.003147482 0.6416426 -0.7669973 -0.03557026 0.537336 -0.8426179 -0.00424236 0.5655413 -0.8247092 0.01379019 0.4688525 -0.8831688 -0.09910261 0.3663465 -0.925186 -0.02761763 0.3832573 -0.9232286 -0.02687859 -0.1862754 -0.9821298 -0.1467528 -0.3641619 -0.9197009 0.04336619 -0.3495492 -0.9359139 -0.01380264 -0.4688457 -0.8831722 0.03555768 -0.5373386 -0.8426167 0.004237115 -0.5655334 -0.8247146 -0.8031979 -0.390627 -0.4497597 -0.2763197 -0.6428384 -0.7144272 -0.07854759 -0.6812183 -0.7278543 -0.008409023 -0.7020885 -0.7120401 -0.00314176 -0.6416849 -0.7669619 0.01789361 -0.6876108 -0.725859 1.74279e-4 -0.7179194 -0.6961262 0.002862155 -0.7247695 -0.6889855 -0.03089529 -0.784057 -0.6199194 -0.002934515 -0.8294119 -0.5586298 -0.3419213 -0.8786791 -0.333186 -0.1164273 -0.8185908 -0.5624535 0.02599561 -0.7836416 -0.6206691 0.005957901 -0.7031366 -0.71103 -5.54138e-4 -0.7522583 -0.6588681 -2.02557e-5 -0.7572544 -0.6531201 0.002104759 -0.8128327 -0.5824936 0.01777589 -0.7844176 -0.6199783 0.008731842 -0.8074145 -0.5899199 0.001381278 -0.8379511 -0.5457438 -0.009114325 -0.8858692 -0.4638456 -0.002227723 -0.8908371 -0.4543175 -0.006827712 -0.8764697 -0.4814085 -0.001733899 -0.8441401 -0.53612 0.004275619 -0.9084842 -0.4178974 -0.004151821 -0.9565904 -0.2914066 0.004463613 -0.9712151 -0.2381625 -0.004330635 -0.9940513 -0.1088277 0.004632711 -0.9987489 -0.04979181 -0.004490017 -0.99698 0.07752925 0.004783511 -0.9900863 0.1403793 -0.004630804 -0.9652755 0.2611932 0.004914999 -0.9455413 0.3254655 -0.004752635 -0.9000419 0.4357774 0.005028843 -0.8667294 0.4987534 -0.00485593 -0.8035399 0.5952312 0.005122601 -0.7565101 0.6539619 -0.004942417 -0.6791308 0.7340007 0.005198597 -0.6188657 0.7854797 -0.00500679 -0.5311279 0.8472769 0.005254745 -0.4588016 0.8885232 -0.005054295 -0.3646796 0.9311195 0.005292356 -0.2821012 0.9593701 -0.005082368 -0.1855601 0.9826199 0.005311369 -0.09518533 0.9954454 -0.005093514 0 0.9999871 0.00530982 0.09518581 0.9954454 -0.005082786 0.1855655 0.9826188 0.005291223 0.2821011 0.9593701 -0.005055129 0.3646749 0.9311212 0.005254745 0.4588018 0.8885232 -0.00500679 0.5311304 0.8472753 0.005197465 0.6188653 0.78548 -0.004942238 0.6791288 0.7340026 0.005122423 0.7565075 0.653965 -0.00485748 0.8035418 0.5952286 0.005027294 0.8667305 0.4987516 -0.004753351 0.9000384 0.4357848 0.004915356 0.945542 0.3254634 -0.004630684 0.9652751 0.2611947 0.00478363 0.9900862 0.1403796 -0.004490017 0.9969801 0.07752799 0.004632592 0.9987488 -0.04979276 -0.004330635 0.9940512 -0.1088275 0.004463672 0.971215 -0.2381633 -0.004151761 0.9565904 -0.2914066 0.00427556 0.9084845 -0.4178967 -0.008423328 0.8858743 -0.4638488 -0.04637968 0.8622346 -0.5043814 -2.68803e-4 0.8963106 -0.4434269 0.006619513 0.8128165 -0.5824823 0.00925976 0.8184305 -0.574531 0.005465447 0.8063946 -0.5913527 6.34047e-4 0.7754531 -0.631405 -4.3174e-5 0.8315046 -0.5555179 -0.0399878 0.7838042 -0.6197193 -0.07420319 0.7756202 -0.6268231 -0.03782457 0.7899224 -0.6120393 -0.01719844 0.8029849 -0.5957512 -0.009518921 0.811553 -0.5842013 2.03196e-5 0.8411417 -0.5408149 -5.50563e-4 0.7520279 -0.6591312 -2.13395e-5 0.7571007 -0.6532984 3.15078e-4 0.6877191 -0.725977 0.04491257 0.7425752 -0.6682552 0.006103038 0.7031669 -0.7109987 0.02571594 0.7835975 -0.6207364 0.004652559 0.7253066 -0.6884104 -0.8092633 0.3852366 -0.4434928 -0.2799863 0.6419379 -0.7138091 -0.009346008 0.7032766 -0.710855 -0.003143072 0.6416438 -0.7669965 0.006823778 0.5376672 -0.8431296 0.08527046 0.6019358 -0.7939789 -0.01379269 0.4688608 -0.8831645 0.03480333 0.3679276 -0.9292029 0.3404776 -0.9402525 5.38847e-4 0.1960013 -0.9803941 -0.02027571 0.1849024 -0.9826046 -0.01729738 -0.02172231 -0.9997619 0.00209546 0.06176429 -0.99809 -0.001338064 -0.186935 -0.9823643 -0.003960192 -0.1584157 -0.987372 -0.001061737 -0.01726132 -0.9998488 0.002121627 -0.3035533 -0.9528132 0.001572787 -0.4228625 -0.9061934 -9.22475e-4 -0.4511135 -0.8924453 -0.006176352 -0.6348224 -0.7726388 -0.005470633 -0.6057264 -0.7956719 -0.001387953 -0.7119249 -0.7022538 0.001665174 -0.8079098 -0.5893059 -6.08804e-4 -0.8297327 -0.5580843 -0.009250998 -0.9021481 -0.4314267 -5.05805e-5 -0.9673652 -0.2509329 -0.03517633 -0.9447019 -0.3276575 -0.01338392 -0.9767124 -0.2132201 -0.02387833 -0.9979025 -0.0647248 0.001217961 -0.3184613 -0.9479359 -1.62918e-4 -0.3375368 -0.9413018 -0.004474103 -0.2308323 -0.9729899 0.002706766 -0.06842827 -0.9976491 -0.003730177 -0.07243692 -0.9973636 -0.004340708 -0.006835579 -0.9999765 6.37179e-4 0.09366077 -0.9956027 0.00173825 0.1821781 -0.9832655 -2.64694e-4 0.1309012 -0.9913733 -0.00662887 0.2906643 -0.9568248 7.60719e-4 0.4233564 -0.9059593 -0.002692222 0.390883 -0.9204122 -0.007203221 0.5245506 -0.8513789 8.38469e-4 0.6347829 -0.7726807 -0.003904223 0.6123924 -0.7905161 -0.007741868 0.6974469 -0.7166365 1.62716e-5 0.808045 -0.5891184 -0.001662731 0.7650355 -0.6438281 -0.01435613 0.8411607 -0.5407842 -0.001105666 0.9002945 -0.4352813 -3.20378e-4 0.9287329 -0.3706524 -0.008488059 0.9471211 -0.3208745 -0.001169919 0.9806119 -0.1959601 3.28112e-4 0.9920501 -0.1253895 -0.01068848 0.9977764 -0.06664806 -5.68277e-4 0.3225018 0.946569 -7.3188e-5 0.3378092 0.941208 -0.003534138 0.2314224 0.9728466 0.003640949 0.06278699 0.9980225 -0.003008663 0.07236969 0.997368 -0.004443228 0.006500422 0.9999788 4.48883e-4 -0.0949344 0.9954825 0.001485943 -0.1804498 0.9835841 -4.74915e-4 -0.1317845 0.9912571 -0.006502926 -0.2928839 0.9561477 7.90593e-4 -0.422652 0.9062877 -0.002816319 -0.3945801 0.9188375 -0.006654798 -0.530289 0.8478164 0.001021504 -0.6344994 0.772912 -0.004207074 -0.6203556 0.7842935 -0.006547808 -0.7059158 0.7082957 5.16472e-4 -0.8076458 0.5896627 -0.0025267 -0.7745497 0.632401 -0.01191318 -0.8485016 0.5291931 -1.17483e-4 -0.92892 0.370279 -0.001078665 -0.9061692 0.422685 -0.0139662 -0.9784603 0.2064217 0.002409338 -0.9920381 0.1254931 -0.01057952 -0.9978933 0.06487607 -3.99346e-4 -0.3389233 0.9408027 -0.004626035 -0.3369066 0.9415252 -0.004927277 -0.1989254 0.9800061 0.004101395 -0.06835865 0.9976597 0.001519858 0.06945031 0.9973731 -0.02058351 -0.05851674 0.9982779 -0.004119813 0.1807733 0.9835148 -0.004443764 0.158665 0.9873301 -0.002178251 0.02212929 0.9997547 9.44864e-4 0.3061259 0.9519901 0.001360476 0.4211769 0.9069743 -0.002768099 0.4434825 0.8962619 -0.006151795 0.5415888 0.8406435 5.39751e-4 0.634779 0.7726755 -0.005322217 0.6222914 0.7827782 -0.003423452 0.7071837 0.7070296 6.62683e-4 0.8069666 0.5905597 -0.006674647 0.7823856 0.6227918 -0.001773655 0.8597264 0.5107515 0.001911878 0.9293829 0.3691173 -2.74727e-4 0.9426348 0.3336451 -0.01099556 0.9819151 0.1893216 -1.96666e-4 0.9921281 0.1252267 -4.91999e-4 0.9968192 0.0775792 -0.01824772 -0.5072469 0.8617881 -0.004694104 -0.4567707 0.8889974 -0.03231394 -0.5124111 0.8586699 -0.01099312 -0.5628667 0.8265475 -5.91089e-4 -0.6424475 0.7663288 0.001153767 -0.6658976 0.7459551 -0.01147109 -0.7401616 0.6723937 0.006894588 -0.7929539 0.6090509 -0.01677179 -0.8169323 0.5767284 0.002462148 -0.8925614 0.4509094 -0.003868162 -0.8712773 0.4884756 -0.04761809 -0.9405977 0.3387823 0.02241861 -0.9584614 0.2767496 -0.06900465 0.4591742 0.8883463 -6.23354e-5 0.515546 0.8568606 -0.001568436 0.57095 0.8204329 -0.03009933 0.5121834 0.8588281 -0.009080052 0.6424422 0.7663332 0.001151978 0.6659112 0.7459434 -0.01142984 0.7401551 0.6724011 0.006868362 0.7929698 0.6090317 -0.01671034 0.8169206 0.5767451 0.002447962 0.8922665 0.450532 -0.02969157 0.8824866 0.4703286 -0.002914488 0.5162627 -0.8564302 3.53721e-4 0.4568036 -0.8889956 -0.03189831 0.5123932 -0.8586822 -0.01086246 0.5628718 -0.8265441 -5.85243e-4 0.6423994 -0.7663693 0.00114268 0.6659089 -0.7459474 -0.01130837 0.7400187 -0.6725536 0.006645381 0.7927504 -0.6093197 -0.01662546 0.8169183 -0.5767486 0.002408623 0.882509 -0.4702869 -0.002852857 -0.4591718 -0.8883476 -1.45688e-4 -0.5154054 -0.8569452 -0.001576602 -0.570977 -0.8204092 -0.03023338 -0.5122026 -0.8588157 -0.009181201 -0.6424036 -0.7663657 0.001150846 -0.6658959 -0.7459564 -0.01148456 -0.7400822 -0.672482 0.006804227 -0.7927922 -0.6092581 -0.01689589 -0.8169325 -0.5767281 0.002470612 -0.8921082 -0.4508609 -0.02945131 -0.8824915 -0.4703193 -0.002933382 -0.9406032 -0.3387676 0.02240896 -1 1.83615e-5 0 -1 0 0 -1 1.26192e-5 -6.09354e-7 -1 0 -1.06099e-6 -1 0 -8.70568e-7 -1 3.9548e-6 -7.53754e-7 -1 0 -6.63074e-7 -1 0 -6.02156e-7 -1 2.14789e-6 -5.52033e-7 -1 0 -5.172e-7 -1 0 -4.8819e-7 -1 0 -4.68263e-7 -1 0 -4.52387e-7 -1 0 -4.52387e-7 -1 0 -4.68263e-7 -1 0 -4.8819e-7 -1 0 -5.172e-7 -1 0 -5.52033e-7 -1 -2.53496e-6 -6.02155e-7 -1 3.09877e-6 -6.63074e-7 -1 -3.9548e-6 -7.53754e-7 -1 5.33457e-6 -8.7057e-7 -1 0 -1.06098e-6 -1 -1.26192e-5 -6.09352e-7 -1 -1.83614e-5 0 1 -1.4628e-5 -4.6673e-4 0.9999999 0 -5.59276e-4 1 0 0 1 2.57766e-7 1.27556e-5 1 0 1.27558e-5 -1 0 -1.2756e-5 -1 0 -1.27556e-5 -1 2.46058e-7 0 -1 -2.19675e-7 0 -1 0 -3.94124e-4 -0.9999992 2.54843e-4 0.001217663 1 1.23905e-5 0 1 3.74946e-6 0 1 4.1283e-5 2.00889e-6 1 2.67652e-6 4.18454e-6 0.9999999 -4.77817e-4 -1.7548e-5 1 5.35734e-6 -3.94363e-5 1 4.15604e-4 -1.89179e-5 1 -3.74947e-6 0 1 3.09877e-6 0 1 6.3096e-6 0 1 -1.23905e-5 0 1 1.83614e-5 0 -0.3788934 -0.1819113 -0.9073854 0.06949824 -0.2503689 -0.9656528 0.06953316 0.2503681 -0.9656506 -0.4451729 0.1670483 -0.8797249 -0.9786284 0.1974263 0.05752742 -0.9878927 0.08956426 -0.1266747 -0.9584616 -0.2767487 -0.06900477 -0.9786264 -0.1974409 0.05750989 -0.9883262 -0.09334677 -0.1204072 + + + + + + + + + + + + + + +

253 0 61 0 63 0 255 1 59 1 61 1 180 2 173 2 175 2 179 3 175 3 172 3 180 4 175 4 179 4 178 5 172 5 177 5 178 6 177 6 176 6 245 7 56 7 243 7 243 8 56 8 241 8 241 9 56 9 53 9 241 10 53 10 239 10 239 11 53 11 237 11 237 12 53 12 52 12 237 13 52 13 235 13 235 14 52 14 49 14 235 15 49 15 233 15 233 16 49 16 48 16 233 17 48 17 47 17 233 18 47 18 225 18 225 19 47 19 46 19 225 20 46 20 103 20 103 21 46 21 50 21 103 22 50 22 102 22 267 23 102 23 50 23 267 24 50 24 51 24 271 25 267 25 51 25 271 26 51 26 54 26 271 27 54 27 263 27 263 28 54 28 261 28 261 29 54 29 55 29 261 30 55 30 259 30 262 31 260 31 37 31 266 32 262 32 37 32 266 33 37 33 40 33 266 34 40 34 264 34 264 35 40 35 42 35 264 36 42 36 130 36 222 37 130 37 42 37 222 38 42 38 43 38 223 39 222 39 43 39 223 40 43 40 45 40 228 41 223 41 45 41 228 42 45 42 44 42 234 43 228 43 44 43 234 44 44 44 41 44 236 45 234 45 41 45 236 46 41 46 39 46 238 47 236 47 39 47 238 48 39 48 38 48 240 49 238 49 38 49 242 50 240 50 38 50 234 51 0 51 230 51 230 52 0 52 231 52 0 53 235 53 231 53 0 54 234 54 236 54 235 55 0 55 236 55 235 56 233 56 231 56 221 57 219 57 220 57 220 58 219 58 218 58 382 59 381 59 380 59 381 60 365 60 198 60 365 61 196 61 198 61 382 62 365 62 381 62 382 63 366 63 365 63 208 64 143 64 140 64 208 65 140 65 204 65 383 66 365 66 366 66 367 67 383 67 366 67 384 68 383 68 367 68 351 69 350 69 349 69 352 70 350 70 351 70 353 71 352 71 351 71 354 72 352 72 353 72 355 73 354 73 353 73 27 74 29 74 348 74 347 75 348 75 29 75 29 76 31 76 347 76 346 77 347 77 31 77 31 78 33 78 346 78 345 79 346 79 33 79 33 80 35 80 345 80 343 81 345 81 35 81 35 82 38 82 343 82 341 83 343 83 38 83 38 84 39 84 341 84 339 85 341 85 39 85 39 86 41 86 339 86 333 87 339 87 41 87 41 88 44 88 333 88 330 89 333 89 44 89 44 90 45 90 330 90 327 91 330 91 45 91 334 92 336 92 4 92 2 93 4 93 336 93 336 94 337 94 2 94 1 95 2 95 337 95 337 96 338 96 1 96 3 97 1 97 338 97 338 98 335 98 3 98 5 99 3 99 335 99 335 100 332 100 5 100 7 101 5 101 332 101 332 102 331 102 7 102 9 103 7 103 331 103 331 104 329 104 9 104 11 105 9 105 329 105 329 106 328 106 11 106 13 107 11 107 326 107 11 108 328 108 326 108 326 109 324 109 13 109 15 110 13 110 324 110 324 111 323 111 15 111 17 112 15 112 323 112 323 113 321 113 17 113 19 114 17 114 321 114 321 115 320 115 19 115 21 116 19 116 320 116 320 117 318 117 21 117 23 118 21 118 318 118 318 119 315 119 23 119 24 120 23 120 315 120 315 121 312 121 24 121 26 122 24 122 312 122 312 123 314 123 26 123 25 124 26 124 314 124 314 125 317 125 25 125 1 126 3 126 2 126 4 127 2 127 3 127 3 127 5 127 4 127 6 128 4 128 5 128 5 129 7 129 6 129 8 130 6 130 7 130 7 131 9 131 8 131 10 127 8 127 9 127 9 132 11 132 10 132 12 133 10 133 11 133 11 134 13 134 12 134 14 135 12 135 13 135 13 136 15 136 14 136 16 137 14 137 15 137 15 138 17 138 16 138 18 127 16 127 17 127 17 127 19 127 18 127 20 139 18 139 19 139 19 140 21 140 20 140 22 141 20 141 21 141 21 127 23 127 22 127 25 142 22 142 23 142 23 143 24 143 25 143 26 127 25 127 24 127 45 144 43 144 327 144 43 145 325 145 327 145 322 146 325 146 43 146 43 147 42 147 322 147 319 148 322 148 42 148 42 149 40 149 319 149 313 150 319 150 40 150 40 151 37 151 313 151 310 152 313 152 37 152 37 153 36 153 310 153 308 154 310 154 36 154 36 155 34 155 308 155 306 156 308 156 34 156 34 157 32 157 306 157 304 158 306 158 32 158 32 159 30 159 304 159 305 160 304 160 30 160 30 161 28 161 305 161 29 162 27 162 250 162 28 163 30 163 252 163 250 164 248 164 29 164 254 165 252 165 30 165 31 166 29 166 248 166 30 167 32 167 254 167 248 168 246 168 31 168 246 169 33 169 31 169 256 170 254 170 32 170 258 171 256 171 34 171 256 172 32 172 34 172 246 173 244 173 33 173 35 174 33 174 244 174 34 175 36 175 258 175 260 176 258 176 36 176 244 177 242 177 35 177 242 178 38 178 35 178 36 179 37 179 260 179 63 180 61 180 303 180 302 181 303 181 61 181 61 182 59 182 302 182 301 183 302 183 59 183 59 184 57 184 301 184 300 185 301 185 57 185 57 186 55 186 300 186 298 187 300 187 55 187 55 188 54 188 298 188 296 189 298 189 54 189 54 190 51 190 296 190 294 191 296 191 51 191 51 192 50 192 294 192 292 193 294 193 50 193 50 194 46 194 292 194 290 195 292 195 46 195 46 196 47 196 290 196 288 197 290 197 47 197 47 198 48 198 288 198 48 199 286 199 288 199 284 200 286 200 48 200 48 201 49 201 284 201 282 202 284 202 49 202 49 203 52 203 282 203 280 204 282 204 52 204 52 205 53 205 280 205 278 206 280 206 53 206 53 207 56 207 278 207 276 208 278 208 56 208 56 209 58 209 276 209 274 210 276 210 58 210 58 211 60 211 274 211 272 212 274 212 60 212 60 213 62 213 272 213 273 214 272 214 62 214 62 215 64 215 273 215 245 216 247 216 56 216 257 217 259 217 57 217 259 218 55 218 57 218 58 219 56 219 247 219 57 220 59 220 257 220 247 221 249 221 58 221 249 222 60 222 58 222 255 223 257 223 59 223 62 224 60 224 249 224 253 225 255 225 61 225 249 226 251 226 62 226 64 227 62 227 251 227 189 228 110 228 193 228 110 229 65 229 193 229 67 230 65 230 110 230 110 231 115 231 67 231 66 232 67 232 115 232 115 233 118 233 66 233 72 234 66 234 118 234 118 235 123 235 72 235 74 236 72 236 123 236 123 237 125 237 74 237 224 238 74 238 125 238 125 239 222 239 224 239 223 240 224 240 222 240 193 241 65 241 192 241 69 242 195 242 192 242 195 243 69 243 377 243 65 244 67 244 192 244 75 245 377 245 69 245 192 246 68 246 69 246 68 247 192 247 67 247 67 248 66 248 68 248 70 249 68 249 66 249 68 250 70 250 69 250 69 251 71 251 75 251 71 252 69 252 70 252 66 253 72 253 70 253 76 254 75 254 71 254 73 255 70 255 72 255 70 256 73 256 71 256 71 257 229 257 76 257 229 258 71 258 73 258 72 259 74 259 73 259 230 260 76 260 229 260 73 261 227 261 229 261 227 262 73 262 74 262 74 263 224 263 227 263 377 264 75 264 379 264 79 265 379 265 75 265 75 266 76 266 79 266 80 267 79 267 76 267 76 268 230 268 80 268 231 269 80 269 230 269 77 270 221 270 379 270 221 271 77 271 219 271 78 272 219 272 77 272 219 273 78 273 218 273 83 274 218 274 78 274 379 275 79 275 77 275 84 276 83 276 78 276 81 277 77 277 79 277 77 278 81 278 78 278 82 279 78 279 81 279 78 280 82 280 84 280 79 281 80 281 81 281 85 282 84 282 82 282 80 283 231 283 81 283 232 284 81 284 231 284 81 285 232 285 82 285 226 286 82 286 232 286 82 287 226 287 85 287 86 288 85 288 226 288 86 289 226 289 87 289 218 290 83 290 216 290 89 291 216 291 83 291 83 292 84 292 89 292 94 293 89 293 84 293 84 294 85 294 94 294 85 295 100 295 94 295 85 296 86 296 100 296 86 297 87 297 100 297 103 298 100 298 87 298 225 299 103 299 87 299 150 300 88 300 151 300 88 301 150 301 152 301 91 302 152 302 216 302 152 303 91 303 88 303 151 304 90 304 362 304 90 305 151 305 88 305 216 306 89 306 91 306 106 307 362 307 90 307 88 308 93 308 90 308 93 309 88 309 91 309 89 310 94 310 91 310 92 311 90 311 93 311 90 312 92 312 106 312 95 313 91 313 94 313 91 314 95 314 93 314 107 315 106 315 92 315 96 316 92 316 93 316 92 317 96 317 107 317 93 318 97 318 96 318 97 319 93 319 95 319 94 320 100 320 95 320 101 321 95 321 100 321 95 322 101 322 97 322 108 323 107 323 96 323 96 324 98 324 108 324 98 325 96 325 97 325 99 326 97 326 101 326 97 327 99 327 98 327 98 328 104 328 108 328 104 329 98 329 99 329 99 330 105 330 104 330 105 331 99 331 101 331 100 332 103 332 101 332 101 333 103 333 102 333 109 334 108 334 104 334 101 335 102 335 105 335 102 336 267 336 105 336 268 337 104 337 105 337 104 338 268 338 109 338 269 339 109 339 268 339 105 340 267 340 268 340 362 341 106 341 364 341 111 342 364 342 106 342 106 343 107 343 111 343 121 344 111 344 107 344 107 345 108 345 121 345 124 346 121 346 108 346 108 347 109 347 124 347 127 348 124 348 109 348 109 349 269 349 127 349 270 350 127 350 269 350 110 351 189 351 171 351 171 352 112 352 110 352 112 353 171 353 168 353 170 354 113 354 168 354 113 355 170 355 364 355 168 356 114 356 112 356 114 357 168 357 113 357 364 358 111 358 113 358 115 359 110 359 112 359 111 360 121 360 113 360 116 361 112 361 114 361 112 362 116 362 115 362 119 363 113 363 121 363 113 364 119 364 114 364 114 365 117 365 116 365 117 366 114 366 119 366 118 367 115 367 116 367 120 368 116 368 117 368 116 369 120 369 118 369 122 370 117 370 119 370 117 371 122 371 120 371 123 372 118 372 120 372 126 373 119 373 121 373 119 374 126 374 122 374 120 375 128 375 123 375 128 376 120 376 122 376 121 377 124 377 126 377 129 378 122 378 126 378 122 379 129 379 128 379 125 380 123 380 128 380 124 381 127 381 126 381 128 382 130 382 125 382 130 383 222 383 125 383 131 384 126 384 127 384 126 385 131 385 129 385 127 386 270 386 131 386 130 387 128 387 129 387 264 388 129 388 131 388 129 389 264 389 130 389 270 390 265 390 131 390 131 391 265 391 264 391 201 392 202 392 132 392 202 393 133 393 132 393 139 394 133 394 202 394 133 395 139 395 134 395 139 396 136 396 134 396 136 397 141 397 135 397 141 398 138 398 135 398 141 399 136 399 139 399 351 400 349 400 137 400 137 401 138 401 351 401 138 402 142 402 351 402 142 403 138 403 141 403 202 404 203 404 139 404 139 405 140 405 141 405 139 406 204 406 140 406 139 407 203 407 204 407 353 408 351 408 142 408 144 409 141 409 143 409 141 410 140 410 143 410 141 411 144 411 142 411 142 412 145 412 353 412 145 413 355 413 353 413 145 414 142 414 144 414 357 415 355 415 145 415 143 416 146 416 144 416 146 417 143 417 210 417 210 418 143 418 208 418 147 419 144 419 146 419 144 420 147 420 145 420 148 421 145 421 147 421 145 422 148 422 357 422 148 423 359 423 357 423 210 424 211 424 146 424 149 425 146 425 214 425 146 426 211 426 214 426 146 427 149 427 147 427 361 428 359 428 148 428 147 429 150 429 148 429 150 430 151 430 148 430 150 431 147 431 149 431 148 432 151 432 361 432 214 433 215 433 149 433 152 434 149 434 215 434 152 435 150 435 149 435 361 436 151 436 362 436 216 437 152 437 215 437 178 438 176 438 153 438 153 439 155 439 178 439 162 440 155 440 160 440 155 441 154 441 160 441 154 442 156 442 160 442 155 443 162 443 178 443 160 444 156 444 157 444 157 445 159 445 160 445 350 446 352 446 158 446 352 447 159 447 158 447 159 448 161 448 160 448 161 449 159 449 352 449 352 450 354 450 161 450 181 451 178 451 162 451 160 452 163 452 162 452 163 453 160 453 161 453 164 454 161 454 356 454 161 455 354 455 356 455 161 456 164 456 163 456 165 457 162 457 163 457 162 458 165 458 181 458 165 459 182 459 181 459 356 460 358 460 164 460 185 461 182 461 165 461 166 462 163 462 164 462 163 463 166 463 165 463 167 464 164 464 360 464 164 465 358 465 360 465 164 466 167 466 166 466 165 467 169 467 185 467 169 468 188 468 185 468 169 469 165 469 166 469 360 470 363 470 167 470 190 471 188 471 169 471 168 472 166 472 170 472 166 473 167 473 170 473 166 474 168 474 169 474 170 475 167 475 363 475 169 476 171 476 190 476 169 477 168 477 171 477 363 478 364 478 170 478 189 479 190 479 171 479 179 480 172 480 178 480 178 481 181 481 179 481 179 482 183 482 180 482 183 483 179 483 181 483 184 484 180 484 183 484 180 485 184 485 366 485 184 486 367 486 366 486 181 487 182 487 183 487 368 488 367 488 184 488 186 489 183 489 185 489 183 490 182 490 185 490 183 491 186 491 184 491 187 492 184 492 186 492 184 493 187 493 368 493 187 494 370 494 368 494 185 495 188 495 186 495 372 496 370 496 187 496 186 497 191 497 187 497 191 498 186 498 188 498 187 499 194 499 372 499 194 500 374 500 372 500 194 501 187 501 191 501 188 502 190 502 191 502 191 503 189 503 193 503 191 504 190 504 189 504 191 505 193 505 194 505 376 506 374 506 194 506 195 507 194 507 192 507 194 508 193 508 192 508 194 509 195 509 376 509 377 510 376 510 195 510 196 511 206 511 197 511 206 512 199 512 197 512 206 513 205 513 199 513 206 514 196 514 365 514 199 515 205 515 200 515 205 516 201 516 200 516 205 517 202 517 201 517 205 518 203 518 202 518 204 519 203 519 205 519 205 520 207 520 204 520 207 521 208 521 204 521 207 522 205 522 206 522 206 523 209 523 207 523 206 524 384 524 209 524 384 525 369 525 209 525 212 526 207 526 209 526 207 527 212 527 208 527 212 528 210 528 208 528 209 529 213 529 212 529 213 530 209 530 371 530 209 531 369 531 371 531 211 532 210 532 212 532 371 533 373 533 213 533 212 534 217 534 211 534 217 535 214 535 211 535 217 536 212 536 213 536 213 537 220 537 217 537 220 538 213 538 375 538 213 539 373 539 375 539 215 540 214 540 217 540 217 541 218 541 215 541 218 542 216 542 215 542 218 543 217 543 220 543 375 544 378 544 220 544 221 545 220 545 378 545 378 546 379 546 221 546 223 547 228 547 224 547 228 548 227 548 224 548 233 549 225 549 226 549 225 550 87 550 226 550 226 551 232 551 233 551 229 552 227 552 228 552 228 553 234 553 229 553 234 554 230 554 229 554 233 555 232 555 231 555 237 556 235 556 236 556 236 557 238 557 237 557 239 558 237 558 238 558 238 559 240 559 239 559 241 560 239 560 240 560 240 561 242 561 241 561 243 562 241 562 242 562 242 563 244 563 243 563 245 564 243 564 244 564 244 565 246 565 245 565 247 566 245 566 246 566 246 567 248 567 247 567 249 568 247 568 248 568 248 569 250 569 249 569 251 570 249 570 250 570 252 571 254 571 253 571 255 572 253 572 254 572 254 573 256 573 255 573 257 574 255 574 256 574 256 575 258 575 257 575 259 576 257 576 258 576 258 577 260 577 259 577 261 578 259 578 260 578 260 579 262 579 261 579 263 580 261 580 262 580 262 581 266 581 263 581 271 582 263 582 266 582 266 583 264 583 265 583 265 584 270 584 266 584 270 585 271 585 266 585 271 586 268 586 267 586 271 587 269 587 268 587 271 588 270 588 269 588 274 589 272 589 273 589 273 590 275 590 274 590 276 589 274 589 275 589 275 591 277 591 276 591 278 592 276 592 277 592 277 593 279 593 278 593 280 594 278 594 279 594 279 595 281 595 280 595 282 596 280 596 281 596 281 597 283 597 282 597 284 598 282 598 283 598 283 599 285 599 284 599 286 600 284 600 285 600 285 601 287 601 286 601 288 602 286 602 287 602 287 603 289 603 288 603 290 601 288 601 289 601 289 604 291 604 290 604 292 599 290 599 291 599 291 605 293 605 292 605 294 606 292 606 293 606 293 589 295 589 294 589 296 607 294 607 295 607 295 589 297 589 296 589 298 589 296 589 297 589 297 608 299 608 298 608 300 589 298 589 299 589 299 589 303 589 300 589 301 589 300 589 303 589 303 609 302 609 301 609 306 127 304 127 305 127 305 610 307 610 306 610 308 611 306 611 307 611 307 612 309 612 308 612 310 127 308 127 309 127 309 613 311 613 310 613 313 614 310 614 311 614 316 127 312 127 313 127 319 127 313 127 315 127 313 615 312 615 315 615 315 127 318 127 319 127 322 127 319 127 320 127 319 616 318 616 320 616 320 127 321 127 322 127 325 127 322 127 323 127 322 127 321 127 323 127 323 127 324 127 325 127 327 127 325 127 326 127 325 617 324 617 326 617 326 127 328 127 327 127 330 127 327 127 328 127 328 127 329 127 330 127 333 618 330 618 331 618 330 127 329 127 331 127 331 619 332 619 333 619 339 620 333 620 335 620 333 621 332 621 335 621 335 127 338 127 339 127 341 622 339 622 340 622 339 623 337 623 340 623 339 624 338 624 337 624 340 127 342 127 341 127 343 127 341 127 342 127 342 625 344 625 343 625 345 626 343 626 344 626 344 627 348 627 345 627 346 127 345 127 348 127 348 127 347 127 346 127 356 628 354 628 355 628 355 629 357 629 356 629 358 630 356 630 357 630 357 631 359 631 358 631 360 632 358 632 359 632 359 633 361 633 360 633 363 634 360 634 361 634 361 635 362 635 363 635 364 636 363 636 362 636 368 637 384 637 367 637 369 638 384 638 368 638 368 639 370 639 369 639 371 640 369 640 370 640 370 641 372 641 371 641 373 642 371 642 372 642 372 643 374 643 373 643 375 644 373 644 374 644 374 645 376 645 375 645 378 646 375 646 376 646 376 647 377 647 378 647 379 648 378 648 377 648 173 649 180 649 174 649 180 650 380 650 174 650 180 651 382 651 380 651 366 652 382 652 180 652 365 653 383 653 206 653 383 654 384 654 206 654 389 655 391 655 390 655 392 656 390 656 391 656 391 657 393 657 392 657 394 658 392 658 393 658 393 659 395 659 394 659 396 660 394 660 395 660 395 661 397 661 396 661 398 662 396 662 397 662 397 663 399 663 398 663 400 664 398 664 399 664 399 665 401 665 400 665 402 666 400 666 401 666 401 667 403 667 402 667 404 668 402 668 403 668 403 669 405 669 404 669 406 670 404 670 405 670 413 671 411 671 412 671 412 672 414 672 413 672 415 673 413 673 414 673 414 674 416 674 415 674 417 675 415 675 416 675 416 676 418 676 417 676 419 677 417 677 418 677 418 678 420 678 419 678 421 679 419 679 420 679 420 680 422 680 421 680 421 681 422 681 423 681 424 682 421 682 423 682 340 683 337 683 336 683 425 684 340 684 336 684 336 685 334 685 425 685 425 686 334 686 426 686 427 687 425 687 426 687 426 688 428 688 427 688 427 127 428 127 429 127 430 127 427 127 429 127 429 127 431 127 430 127 430 689 431 689 432 689 433 127 430 127 432 127 432 127 434 127 433 127 435 127 433 127 434 127 434 127 436 127 435 127 435 127 436 127 437 127 438 127 435 127 437 127 437 690 439 690 438 690 438 691 439 691 317 691 316 692 438 692 317 692 317 693 314 693 316 693 316 694 314 694 312 694 311 127 316 127 313 127 253 695 440 695 252 695 441 696 252 696 440 696 440 697 442 697 441 697 443 698 441 698 442 698 442 699 444 699 443 699 445 700 443 700 444 700 444 701 446 701 445 701 447 702 445 702 446 702 446 703 448 703 447 703 449 704 447 704 448 704 448 705 450 705 449 705 451 706 449 706 450 706 452 707 451 707 450 707 453 708 452 708 450 708 451 709 452 709 454 709 451 710 454 710 455 710 456 711 451 711 455 711 457 712 458 712 459 712 460 713 461 713 462 713 462 714 463 714 460 714 464 715 465 715 459 715 458 716 464 716 459 716 466 717 460 717 463 717 467 718 465 718 464 718 463 719 468 719 466 719 469 720 470 720 471 720 469 721 471 721 472 721 469 722 472 722 467 722 464 723 469 723 467 723 466 724 468 724 473 724 470 725 469 725 474 725 473 726 470 726 474 726 474 727 466 727 473 727 469 728 475 728 474 728 476 729 474 729 475 729 475 730 477 730 476 730 478 731 476 731 477 731 477 732 479 732 478 732 480 733 478 733 479 733 479 734 251 734 480 734 250 735 480 735 251 735 482 736 385 736 481 736 385 737 387 737 481 737 489 738 385 738 482 738 487 739 490 739 488 739 389 740 385 740 489 740 491 741 488 741 490 741 488 742 491 742 489 742 492 743 489 743 491 743 492 744 391 744 389 744 489 745 492 745 389 745 490 746 493 746 491 746 393 747 391 747 492 747 491 748 494 748 492 748 491 749 493 749 495 749 494 750 491 750 495 750 492 751 496 751 393 751 496 752 492 752 494 752 395 753 393 753 496 753 495 754 497 754 494 754 494 755 497 755 498 755 499 756 494 756 498 756 494 757 499 757 496 757 500 758 397 758 395 758 496 759 500 759 395 759 500 760 496 760 499 760 498 761 501 761 499 761 399 762 397 762 500 762 499 763 501 763 502 763 503 764 499 764 502 764 499 765 503 765 500 765 502 766 504 766 503 766 505 767 401 767 399 767 500 768 505 768 399 768 505 769 500 769 503 769 403 770 401 770 505 770 503 771 504 771 506 771 503 772 506 772 507 772 508 773 503 773 507 773 503 774 508 774 505 774 505 775 509 775 403 775 505 776 508 776 510 776 509 777 505 777 510 777 403 778 509 778 405 778 516 779 517 779 515 779 516 780 515 780 514 780 513 781 516 781 514 781 518 782 516 782 513 782 518 783 513 783 512 783 511 784 518 784 512 784 518 785 511 785 388 785 519 786 517 786 516 786 388 787 390 787 518 787 520 788 516 788 518 788 520 789 521 789 519 789 516 790 520 790 519 790 518 791 390 791 392 791 522 792 518 792 392 792 518 793 522 793 520 793 523 794 521 794 520 794 392 795 394 795 522 795 524 796 520 796 522 796 524 797 525 797 523 797 520 798 524 798 523 798 526 799 522 799 394 799 522 800 526 800 524 800 394 801 396 801 526 801 527 802 525 802 524 802 524 803 528 803 527 803 528 804 524 804 526 804 529 805 527 805 528 805 526 806 530 806 528 806 526 807 396 807 398 807 530 808 526 808 398 808 398 809 400 809 530 809 531 810 532 810 529 810 528 811 531 811 529 811 531 812 528 812 530 812 533 813 532 813 531 813 530 814 534 814 531 814 530 815 400 815 402 815 534 816 530 816 402 816 402 817 404 817 534 817 535 818 531 818 534 818 538 819 534 819 404 819 404 820 406 820 538 820 517 821 540 821 541 821 515 822 517 822 541 822 542 823 543 823 410 823 410 824 408 824 542 824 543 825 544 825 410 825 545 826 544 826 543 826 545 827 543 827 546 827 547 828 545 828 546 828 548 829 545 829 547 829 548 830 547 830 549 830 540 831 548 831 549 831 548 832 540 832 517 832 517 833 519 833 548 833 412 834 410 834 544 834 550 835 544 835 545 835 550 836 414 836 412 836 544 837 550 837 412 837 551 838 545 838 548 838 545 839 551 839 550 839 548 840 552 840 551 840 548 841 519 841 521 841 552 842 548 842 521 842 521 843 523 843 552 843 416 844 414 844 550 844 553 845 550 845 551 845 550 846 553 846 416 846 554 847 551 847 552 847 551 848 554 848 553 848 552 849 523 849 525 849 555 850 552 850 525 850 552 851 555 851 554 851 418 852 416 852 553 852 525 853 527 853 555 853 556 854 420 854 418 854 553 855 556 855 418 855 556 856 553 856 554 856 557 857 554 857 555 857 554 858 557 858 556 858 555 859 558 859 557 859 555 860 527 860 529 860 558 861 555 861 529 861 422 862 420 862 556 862 529 863 532 863 558 863 559 864 423 864 422 864 556 865 559 865 422 865 559 866 556 866 557 866 560 867 559 867 557 867 560 868 557 868 558 868 558 869 532 869 533 869 560 870 558 870 533 870 561 871 560 871 533 871 537 872 561 872 533 872 487 873 485 873 562 873 563 874 407 874 409 874 564 875 563 875 409 875 565 876 563 876 564 876 566 877 565 877 564 877 567 878 566 878 564 878 487 879 568 879 490 879 569 880 566 880 567 880 562 881 569 881 567 881 568 882 562 882 567 882 562 883 568 883 487 883 409 884 411 884 564 884 564 885 570 885 567 885 564 886 411 886 413 886 570 887 564 887 413 887 567 888 571 888 568 888 571 889 567 889 570 889 493 890 490 890 568 890 413 891 415 891 570 891 572 892 493 892 568 892 572 893 568 893 571 893 495 894 493 894 572 894 570 895 573 895 571 895 573 896 570 896 415 896 571 897 574 897 572 897 574 898 571 898 573 898 415 899 417 899 573 899 575 900 572 900 574 900 575 901 497 901 495 901 572 902 575 902 495 902 498 903 497 903 575 903 573 904 576 904 574 904 573 905 417 905 419 905 576 906 573 906 419 906 574 907 577 907 575 907 577 908 574 908 576 908 578 909 575 909 577 909 578 910 501 910 498 910 575 911 578 911 498 911 419 912 421 912 576 912 502 913 501 913 578 913 576 914 579 914 577 914 576 915 421 915 424 915 576 916 424 916 579 916 577 917 580 917 578 917 577 918 579 918 580 918 578 919 580 919 581 919 581 920 504 920 502 920 578 921 581 921 502 921 506 922 504 922 581 922 452 923 582 923 454 923 583 924 454 924 582 924 582 925 584 925 583 925 585 926 583 926 584 926 584 927 586 927 585 927 587 928 585 928 586 928 586 929 588 929 587 929 589 930 587 930 588 930 588 931 590 931 589 931 591 932 589 932 590 932 590 933 424 933 591 933 423 934 591 934 424 934 454 935 592 935 455 935 593 936 455 936 592 936 455 937 593 937 456 937 592 938 583 938 593 938 594 939 456 939 593 939 595 940 593 940 583 940 593 941 595 941 594 941 583 942 585 942 595 942 596 943 456 943 594 943 597 944 595 944 585 944 595 945 597 945 594 945 594 946 598 946 596 946 598 947 594 947 597 947 585 948 587 948 597 948 597 949 599 949 598 949 599 950 597 950 587 950 587 951 589 951 599 951 600 952 596 952 598 952 601 953 598 953 599 953 598 954 601 954 600 954 602 955 599 955 589 955 599 956 602 956 601 956 589 957 603 957 602 957 604 958 600 958 601 958 601 959 605 959 604 959 605 960 601 960 602 960 602 961 606 961 605 961 606 962 602 962 603 962 603 963 591 963 606 963 607 964 604 964 605 964 606 965 559 965 605 965 559 966 606 966 591 966 561 967 607 967 605 967 591 968 423 968 559 968 560 969 605 969 559 969 605 970 560 970 561 970 614 971 608 971 596 971 596 972 600 972 614 972 609 973 614 973 600 973 600 974 604 974 609 974 623 975 609 975 604 975 604 976 607 976 623 976 610 977 623 977 607 977 607 978 561 978 610 978 610 979 561 979 537 979 611 980 462 980 461 980 461 981 608 981 611 981 463 982 462 982 611 982 612 983 463 983 611 983 611 984 613 984 612 984 613 985 611 985 608 985 468 986 463 986 612 986 608 987 614 987 613 987 612 988 615 988 468 988 473 989 468 989 615 989 614 990 609 990 613 990 616 991 612 991 613 991 612 992 616 992 615 992 613 993 617 993 616 993 617 994 613 994 609 994 618 995 615 995 616 995 615 996 618 996 473 996 619 997 470 997 473 997 473 998 620 998 619 998 620 999 473 999 618 999 616 1000 621 1000 618 1000 621 1001 616 1001 617 1001 617 1002 622 1002 621 1002 622 1003 617 1003 609 1003 609 1004 623 1004 622 1004 618 1005 624 1005 620 1005 624 1006 618 1006 621 1006 625 1007 626 1007 619 1007 620 1008 625 1008 619 1008 625 1009 620 1009 624 1009 623 1010 610 1010 622 1010 621 1011 535 1011 624 1011 535 1012 621 1012 622 1012 627 1013 622 1013 610 1013 622 1014 627 1014 535 1014 624 1015 539 1015 625 1015 539 1016 624 1016 535 1016 627 1017 610 1017 536 1017 535 1018 627 1018 536 1018 538 1019 406 1019 626 1019 625 1020 538 1020 626 1020 610 1021 537 1021 536 1021 470 1022 619 1022 471 1022 628 1023 471 1023 619 1023 619 1024 626 1024 628 1024 629 1025 628 1025 626 1025 626 1026 406 1026 629 1026 405 1027 629 1027 406 1027 630 1028 457 1028 459 1028 459 1029 631 1029 630 1029 459 1030 465 1030 631 1030 465 1031 632 1031 631 1031 633 1032 631 1032 632 1032 631 1033 633 1033 630 1033 465 1034 467 1034 632 1034 646 1035 630 1035 633 1035 467 1036 634 1036 632 1036 467 1037 472 1037 634 1037 635 1038 632 1038 634 1038 632 1039 635 1039 633 1039 636 1040 646 1040 633 1040 633 1041 637 1041 636 1041 637 1042 633 1042 635 1042 472 1043 638 1043 634 1043 472 1044 471 1044 638 1044 639 1045 634 1045 638 1045 634 1046 639 1046 635 1046 471 1047 628 1047 638 1047 640 1048 636 1048 637 1048 641 1049 637 1049 635 1049 637 1050 641 1050 640 1050 642 1051 638 1051 628 1051 638 1052 642 1052 639 1052 635 1053 643 1053 641 1053 643 1054 635 1054 639 1054 644 1055 639 1055 642 1055 639 1056 644 1056 643 1056 628 1057 629 1057 642 1057 507 1058 641 1058 643 1058 641 1059 507 1059 640 1059 508 1060 643 1060 644 1060 643 1061 508 1061 507 1061 506 1062 640 1062 507 1062 644 1063 510 1063 508 1063 510 1064 644 1064 642 1064 642 1065 509 1065 510 1065 509 1066 642 1066 629 1066 629 1067 405 1067 509 1067 630 1068 646 1068 645 1068 647 1069 645 1069 646 1069 646 1070 636 1070 647 1070 648 1071 647 1071 636 1071 636 1072 640 1072 648 1072 649 1073 648 1073 640 1073 640 1074 506 1074 649 1074 581 1075 649 1075 506 1075 453 1076 650 1076 452 1076 453 1077 450 1077 651 1077 650 1078 453 1078 651 1078 582 1079 452 1079 650 1079 652 1080 650 1080 651 1080 650 1081 652 1081 582 1081 653 1082 582 1082 652 1082 651 1083 654 1083 652 1083 584 1084 653 1084 652 1084 655 1085 652 1085 654 1085 652 1086 655 1086 584 1086 656 1087 584 1087 655 1087 651 1088 630 1088 654 1088 654 1089 630 1089 645 1089 657 1090 654 1090 645 1090 654 1091 657 1091 655 1091 655 1092 658 1092 656 1092 658 1093 655 1093 657 1093 586 1094 656 1094 658 1094 659 1095 657 1095 645 1095 657 1096 659 1096 658 1096 645 1097 647 1097 659 1097 588 1098 586 1098 658 1098 658 1099 660 1099 588 1099 660 1100 658 1100 659 1100 659 1101 661 1101 660 1101 661 1102 659 1102 647 1102 647 1103 648 1103 661 1103 590 1104 588 1104 660 1104 662 1105 661 1105 648 1105 661 1106 662 1106 660 1106 663 1107 660 1107 662 1107 660 1108 663 1108 590 1108 648 1109 649 1109 662 1109 662 1110 580 1110 663 1110 580 1111 662 1111 649 1111 649 1112 581 1112 580 1112 424 1113 590 1113 663 1113 579 1114 663 1114 580 1114 663 1115 579 1115 424 1115 475 1116 670 1116 671 1116 477 1117 475 1117 671 1117 479 1118 477 1118 671 1118 442 1119 440 1119 673 1119 671 1120 674 1120 479 1120 479 1121 674 1121 64 1121 251 1122 479 1122 64 1122 253 1123 63 1123 673 1123 440 1124 253 1124 673 1124 287 1125 285 1125 664 1125 665 1126 664 1126 285 1126 285 1127 283 1127 665 1127 666 1128 665 1128 283 1128 283 1129 281 1129 666 1129 670 1130 666 1130 281 1130 281 1131 279 1131 670 1131 671 1132 670 1132 279 1132 279 1133 277 1133 671 1133 674 1134 671 1134 277 1134 277 1135 275 1135 674 1135 64 1136 674 1136 275 1136 275 1137 273 1137 64 1137 303 1138 299 1138 63 1138 673 1139 63 1139 299 1139 299 1140 297 1140 673 1140 672 1141 673 1141 297 1141 297 1142 295 1142 672 1142 669 1143 672 1143 295 1143 295 1144 293 1144 669 1144 667 1145 669 1145 293 1145 293 1146 291 1146 667 1146 668 1147 667 1147 291 1147 291 1148 289 1148 668 1148 668 1149 289 1149 287 1149 664 1150 668 1150 287 1150 252 1151 441 1151 28 1151 433 1152 435 1152 684 1152 685 1153 684 1153 435 1153 435 1154 438 1154 685 1154 681 1155 685 1155 438 1155 438 1156 316 1156 681 1156 680 1157 681 1157 316 1157 316 1158 311 1158 680 1158 678 1159 680 1159 311 1159 311 1160 309 1160 678 1160 676 1161 678 1161 309 1161 309 1162 307 1162 676 1162 28 1163 676 1163 307 1163 307 1164 305 1164 28 1164 16 1165 434 1165 432 1165 14 1166 16 1166 432 1166 436 1167 434 1167 16 1167 16 1168 18 1168 436 1168 437 1169 436 1169 18 1169 18 1170 20 1170 437 1170 439 1171 437 1171 20 1171 20 1172 22 1172 439 1172 317 1173 439 1173 22 1173 22 1174 25 1174 317 1174 4 1175 6 1175 334 1175 426 1176 334 1176 6 1176 6 1177 8 1177 426 1177 428 1178 426 1178 8 1178 8 1179 10 1179 428 1179 429 1180 428 1180 10 1180 10 1181 12 1181 429 1181 431 1182 429 1182 12 1182 12 1183 14 1183 431 1183 432 1184 431 1184 14 1184 348 1185 344 1185 27 1185 675 1186 27 1186 344 1186 344 1187 342 1187 675 1187 677 1188 675 1188 342 1188 342 1189 340 1189 677 1189 679 1190 677 1190 340 1190 340 1191 425 1191 679 1191 682 1192 679 1192 425 1192 425 1193 427 1193 682 1193 683 1194 682 1194 427 1194 427 1195 430 1195 683 1195 683 1196 430 1196 433 1196 684 1197 683 1197 433 1197 388 1198 389 1198 390 1198 385 1199 389 1199 388 1199 385 1200 388 1200 386 1200 385 1201 386 1201 387 1201 410 1202 412 1202 411 1202 409 1203 410 1203 411 1203 408 1204 410 1204 409 1204 407 1205 408 1205 409 1205 533 1206 536 1206 537 1206 534 1207 539 1207 535 1207 534 1208 538 1208 539 1208 538 1209 625 1209 539 1209 480 1210 250 1210 27 1210 480 1211 27 1211 675 1211 478 1212 480 1212 675 1212 478 1213 675 1213 677 1213 476 1214 478 1214 677 1214 476 1215 677 1215 679 1215 474 1216 476 1216 679 1216 466 1217 474 1217 679 1217 466 1218 679 1218 682 1218 460 1219 466 1219 682 1219 460 1220 682 1220 683 1220 460 1221 683 1221 461 1221 461 1222 683 1222 684 1222 456 1223 684 1223 685 1223 451 1224 456 1224 685 1224 461 1225 686 1225 608 1225 456 1226 686 1226 684 1226 686 1227 461 1227 684 1227 596 1228 608 1228 686 1228 456 1229 596 1229 686 1229 531 1230 536 1230 533 1230 531 1231 535 1231 536 1231 451 1232 685 1232 681 1232 449 1233 451 1233 681 1233 449 1234 681 1234 680 1234 441 1235 443 1235 28 1235 443 1236 676 1236 28 1236 443 1237 445 1237 676 1237 445 1238 678 1238 676 1238 445 1239 447 1239 678 1239 447 1240 680 1240 678 1240 447 1241 449 1241 680 1241 469 1242 670 1242 475 1242 464 1243 670 1243 469 1243 464 1244 666 1244 670 1244 458 1245 666 1245 464 1245 458 1246 665 1246 666 1246 457 1247 665 1247 458 1247 457 1248 664 1248 665 1248 457 1249 630 1249 664 1249 630 1250 668 1250 664 1250 630 1251 651 1251 668 1251 450 1252 667 1252 651 1252 651 1253 667 1253 668 1253 450 1254 669 1254 667 1254 448 1255 669 1255 450 1255 448 1256 672 1256 669 1256 446 1257 672 1257 448 1257 446 1258 673 1258 672 1258 444 1259 673 1259 446 1259 442 1260 673 1260 444 1260 482 1261 483 1261 489 1261 483 1262 488 1262 489 1262 483 1263 486 1263 488 1263 484 1264 488 1264 486 1264 484 1265 487 1265 488 1265 484 1266 485 1266 487 1266 386 1267 388 1267 687 1267 388 1268 511 1268 687 1268 841 1269 766 1269 765 1269 841 1270 767 1270 766 1270 841 1271 768 1271 767 1271 841 1272 839 1272 768 1272 789 1273 687 1273 511 1273 386 1274 687 1274 906 1274 906 1275 687 1275 789 1275 380 1276 820 1276 819 1276 380 1277 821 1277 820 1277 381 1278 821 1278 380 1278 381 1279 822 1279 821 1279 381 1280 823 1280 822 1280 785 1281 783 1281 711 1281 783 1282 784 1282 711 1282 710 1283 711 1283 784 1283 784 1284 782 1284 710 1284 709 1285 710 1285 782 1285 782 1286 742 1286 709 1286 708 1287 709 1287 742 1287 742 1288 743 1288 708 1288 707 1289 708 1289 744 1289 708 1290 743 1290 744 1290 706 1291 707 1291 745 1291 707 1292 744 1292 745 1292 706 1293 745 1293 746 1293 705 1294 715 1294 716 1294 716 1295 713 1295 705 1295 704 1296 705 1296 713 1296 713 1297 714 1297 704 1297 703 1298 704 1298 714 1298 714 1299 712 1299 703 1299 702 1300 703 1300 712 1300 700 1301 702 1301 790 1301 702 1302 712 1302 790 1302 790 1303 791 1303 700 1303 701 1304 700 1304 791 1304 791 1305 792 1305 701 1305 792 1306 793 1306 701 1306 800 1307 798 1307 689 1307 798 1308 799 1308 689 1308 688 1309 689 1309 799 1309 799 1310 797 1310 688 1310 690 1311 688 1311 797 1311 797 1312 726 1312 690 1312 693 1313 690 1313 726 1313 726 1314 727 1314 693 1314 692 1315 693 1315 728 1315 693 1316 727 1316 728 1316 691 1317 692 1317 729 1317 692 1318 728 1318 729 1318 691 1319 729 1319 730 1319 695 1320 760 1320 761 1320 761 1321 758 1321 695 1321 694 1322 695 1322 758 1322 758 1323 759 1323 694 1323 696 1324 694 1324 759 1324 759 1325 757 1325 696 1325 697 1326 696 1326 757 1326 698 1327 697 1327 772 1327 697 1328 757 1328 772 1328 772 1329 773 1329 698 1329 699 1330 698 1330 773 1330 773 1331 774 1331 699 1331 774 1332 775 1332 699 1332 825 1333 823 1333 804 1333 823 1334 805 1334 804 1334 804 1335 803 1335 825 1335 827 1336 825 1336 802 1336 825 1337 803 1337 802 1337 838 1338 840 1338 741 1338 840 1339 740 1339 741 1339 840 1340 739 1340 740 1340 840 1341 738 1341 739 1341 802 1342 801 1342 827 1342 829 1343 827 1343 800 1343 827 1344 801 1344 800 1344 737 1345 738 1345 840 1345 840 1346 842 1346 737 1346 842 1347 736 1347 737 1347 842 1348 735 1348 736 1348 842 1349 734 1349 735 1349 842 1350 733 1350 734 1350 842 1351 732 1351 733 1351 688 1352 690 1352 689 1352 800 1353 689 1353 690 1353 690 1354 693 1354 800 1354 693 1355 829 1355 800 1355 831 1356 829 1356 730 1356 829 1357 691 1357 730 1357 829 1358 692 1358 691 1358 829 1359 693 1359 692 1359 731 1360 732 1360 842 1360 842 1361 844 1361 731 1361 844 1362 730 1362 731 1362 844 1363 831 1363 730 1363 833 1364 831 1364 844 1364 844 1365 846 1365 833 1365 834 1366 833 1366 846 1366 846 1367 848 1367 834 1367 836 1368 834 1368 848 1368 848 1369 850 1369 836 1369 835 1370 836 1370 850 1370 850 1371 852 1371 835 1371 832 1372 835 1372 852 1372 852 1373 854 1373 832 1373 830 1374 832 1374 854 1374 854 1375 856 1375 830 1375 828 1376 830 1376 856 1376 856 1377 858 1377 828 1377 826 1378 828 1378 858 1378 858 1379 860 1379 826 1379 824 1380 826 1380 860 1380 860 1381 863 1381 824 1381 822 1382 824 1382 863 1382 863 1383 864 1383 822 1383 821 1384 822 1384 864 1384 864 1385 862 1385 821 1385 820 1386 821 1386 862 1386 862 1387 861 1387 820 1387 818 1388 820 1388 861 1388 861 1389 859 1389 818 1389 816 1390 818 1390 859 1390 859 1391 857 1391 816 1391 814 1392 816 1392 857 1392 857 1393 855 1393 814 1393 812 1394 814 1394 855 1394 855 1395 853 1395 812 1395 810 1396 812 1396 853 1396 853 1397 851 1397 810 1397 808 1398 810 1398 851 1398 851 1399 849 1399 808 1399 806 1400 808 1400 849 1400 849 1401 847 1401 806 1401 807 1402 806 1402 847 1402 847 1403 845 1403 807 1403 809 1404 807 1404 845 1404 845 1405 843 1405 809 1405 811 1406 809 1406 843 1406 843 1407 841 1407 760 1407 760 1408 811 1408 843 1408 841 1409 762 1409 760 1409 813 1410 811 1410 696 1410 811 1411 694 1411 696 1411 811 1412 695 1412 694 1412 811 1413 760 1413 695 1413 763 1414 762 1414 841 1414 765 1415 764 1415 841 1415 764 1416 763 1416 841 1416 696 1417 697 1417 775 1417 775 1418 813 1418 696 1418 815 1419 813 1419 776 1419 813 1420 775 1420 776 1420 699 1421 775 1421 697 1421 697 1422 698 1422 699 1422 769 1423 768 1423 839 1423 839 1424 837 1424 771 1424 771 1425 770 1425 839 1425 770 1426 769 1426 839 1426 776 1427 777 1427 815 1427 817 1428 815 1428 778 1428 815 1429 777 1429 778 1429 778 1430 779 1430 817 1430 819 1431 817 1431 780 1431 817 1432 779 1432 780 1432 387 1433 910 1433 481 1433 910 1434 912 1434 481 1434 912 1435 482 1435 481 1435 796 1436 482 1436 912 1436 912 1437 914 1437 796 1437 914 1438 795 1438 796 1438 890 1439 892 1439 725 1439 725 1440 724 1440 890 1440 724 1441 723 1441 890 1441 723 1442 722 1442 890 1442 794 1443 795 1443 914 1443 914 1444 916 1444 794 1444 916 1445 793 1445 794 1445 722 1446 721 1446 890 1446 888 1447 890 1447 719 1447 719 1448 718 1448 888 1448 890 1449 720 1449 719 1449 890 1450 721 1450 720 1450 702 1451 700 1451 701 1451 701 1452 793 1452 702 1452 703 1453 702 1453 793 1453 793 1454 916 1454 703 1454 916 1455 918 1455 703 1455 918 1456 704 1456 703 1456 918 1457 705 1457 704 1457 918 1458 715 1458 705 1458 886 1459 888 1459 715 1459 715 1460 918 1460 886 1460 888 1461 717 1461 715 1461 888 1462 718 1462 717 1462 918 1463 920 1463 886 1463 884 1464 886 1464 920 1464 920 1465 921 1465 884 1465 882 1466 884 1466 921 1466 921 1467 922 1467 882 1467 880 1468 882 1468 922 1468 922 1469 923 1469 880 1469 878 1470 880 1470 923 1470 923 1471 919 1471 878 1471 876 1472 878 1472 919 1472 919 1473 917 1473 876 1473 874 1474 876 1474 917 1474 917 1475 915 1475 874 1475 872 1476 874 1476 915 1476 915 1477 913 1477 872 1477 870 1478 872 1478 913 1478 913 1479 911 1479 870 1479 868 1480 870 1480 911 1480 911 1481 909 1481 868 1481 866 1482 868 1482 909 1482 909 1483 908 1483 866 1483 865 1484 866 1484 908 1484 908 1485 907 1485 865 1485 867 1486 865 1486 907 1486 907 1487 905 1487 867 1487 869 1488 867 1488 905 1488 905 1489 903 1489 869 1489 871 1490 869 1490 903 1490 903 1491 901 1491 871 1491 873 1492 871 1492 901 1492 901 1493 899 1493 873 1493 875 1494 873 1494 899 1494 899 1495 897 1495 875 1495 877 1496 875 1496 897 1496 897 1497 895 1497 877 1497 879 1498 877 1498 895 1498 895 1499 893 1499 879 1499 881 1500 879 1500 893 1500 893 1501 894 1501 881 1501 883 1502 881 1502 894 1502 894 1503 896 1503 883 1503 885 1504 883 1504 896 1504 896 1505 898 1505 885 1505 887 1506 885 1506 747 1506 885 1507 746 1507 747 1507 885 1508 898 1508 746 1508 898 1509 900 1509 746 1509 900 1510 706 1510 746 1510 900 1511 707 1511 706 1511 900 1512 708 1512 707 1512 747 1513 748 1513 887 1513 889 1514 887 1514 753 1514 887 1515 752 1515 753 1515 887 1516 751 1516 752 1516 887 1517 750 1517 751 1517 887 1518 749 1518 750 1518 887 1519 748 1519 749 1519 709 1520 708 1520 785 1520 708 1521 900 1521 785 1521 900 1522 902 1522 785 1522 902 1523 786 1523 785 1523 785 1524 711 1524 709 1524 710 1525 709 1525 711 1525 753 1526 754 1526 889 1526 891 1527 889 1527 756 1527 889 1528 755 1528 756 1528 889 1529 754 1529 755 1529 787 1530 786 1530 902 1530 902 1531 904 1531 787 1531 904 1532 788 1532 787 1532 789 1533 788 1533 904 1533 904 1534 906 1534 789 1534 790 1535 712 1535 485 1535 562 1536 485 1536 712 1536 712 1537 714 1537 562 1537 562 1538 713 1538 716 1538 562 1539 714 1539 713 1539 569 1540 562 1540 717 1540 562 1541 715 1541 717 1541 562 1542 716 1542 715 1542 717 1543 718 1543 569 1543 566 1544 569 1544 719 1544 569 1545 718 1545 719 1545 565 1546 566 1546 720 1546 566 1547 719 1547 720 1547 720 1548 721 1548 565 1548 563 1549 565 1549 722 1549 565 1550 721 1550 722 1550 722 1551 723 1551 563 1551 407 1552 563 1552 724 1552 563 1553 723 1553 724 1553 724 1554 725 1554 407 1554 407 1555 725 1555 892 1555 201 1556 132 1556 797 1556 132 1557 726 1557 797 1557 727 1558 726 1558 132 1558 132 1559 133 1559 727 1559 133 1560 728 1560 727 1560 133 1561 729 1561 728 1561 730 1562 729 1562 133 1562 133 1563 134 1563 730 1563 134 1564 731 1564 730 1564 732 1565 731 1565 134 1565 134 1566 136 1566 732 1566 136 1567 733 1567 732 1567 734 1568 733 1568 136 1568 136 1569 135 1569 734 1569 135 1570 735 1570 734 1570 736 1571 735 1571 135 1571 135 1572 138 1572 736 1572 138 1573 737 1573 736 1573 138 1574 738 1574 737 1574 739 1575 738 1575 138 1575 138 1576 137 1576 739 1576 137 1577 740 1577 739 1577 741 1578 740 1578 137 1578 137 1579 349 1579 741 1579 838 1580 741 1580 349 1580 515 1581 541 1581 782 1581 541 1582 742 1582 782 1582 743 1583 742 1583 541 1583 541 1584 540 1584 743 1584 540 1585 744 1585 743 1585 540 1586 745 1586 744 1586 746 1587 745 1587 540 1587 540 1588 549 1588 746 1588 549 1589 747 1589 746 1589 748 1590 747 1590 549 1590 549 1591 547 1591 748 1591 547 1592 749 1592 748 1592 750 1593 749 1593 547 1593 547 1594 546 1594 750 1594 546 1595 751 1595 750 1595 752 1596 751 1596 546 1596 546 1597 543 1597 752 1597 543 1598 753 1598 752 1598 754 1599 753 1599 543 1599 543 1600 542 1600 754 1600 542 1601 755 1601 754 1601 756 1602 755 1602 542 1602 542 1603 408 1603 756 1603 891 1604 756 1604 408 1604 772 1605 757 1605 176 1605 153 1606 176 1606 757 1606 757 1607 759 1607 153 1607 155 1608 153 1608 761 1608 153 1609 758 1609 761 1609 153 1610 759 1610 758 1610 154 1611 155 1611 762 1611 155 1612 760 1612 762 1612 155 1613 761 1613 760 1613 762 1614 763 1614 154 1614 156 1615 154 1615 764 1615 154 1616 763 1616 764 1616 764 1617 765 1617 156 1617 157 1618 156 1618 766 1618 156 1619 765 1619 766 1619 766 1620 767 1620 157 1620 159 1621 157 1621 768 1621 157 1622 767 1622 768 1622 768 1623 769 1623 159 1623 158 1624 159 1624 770 1624 159 1625 769 1625 770 1625 770 1626 771 1626 158 1626 350 1627 158 1627 837 1627 158 1628 771 1628 837 1628 176 1629 177 1629 772 1629 177 1630 773 1630 772 1630 177 1631 774 1631 773 1631 177 1632 775 1632 774 1632 776 1633 775 1633 177 1633 177 1634 172 1634 776 1634 777 1635 776 1635 172 1635 172 1636 175 1636 777 1636 778 1637 777 1637 175 1637 175 1638 173 1638 778 1638 173 1639 779 1639 778 1639 780 1640 779 1640 173 1640 173 1641 174 1641 780 1641 782 1642 784 1642 515 1642 514 1643 515 1643 785 1643 515 1644 783 1644 785 1644 515 1645 784 1645 783 1645 785 1646 786 1646 514 1646 513 1647 514 1647 786 1647 786 1648 787 1648 513 1648 512 1649 513 1649 787 1649 787 1650 788 1650 512 1650 511 1651 512 1651 789 1651 512 1652 788 1652 789 1652 485 1653 484 1653 790 1653 484 1654 791 1654 790 1654 484 1655 792 1655 791 1655 484 1656 793 1656 792 1656 794 1657 793 1657 484 1657 484 1658 486 1658 794 1658 795 1659 794 1659 486 1659 486 1660 483 1660 795 1660 796 1661 795 1661 483 1661 483 1662 482 1662 796 1662 797 1663 799 1663 201 1663 200 1664 201 1664 800 1664 201 1665 798 1665 800 1665 201 1666 799 1666 798 1666 800 1667 801 1667 200 1667 199 1668 200 1668 801 1668 801 1669 802 1669 199 1669 197 1670 199 1670 802 1670 802 1671 803 1671 197 1671 196 1672 197 1672 804 1672 197 1673 803 1673 804 1673 804 1674 805 1674 196 1674 808 1675 806 1675 807 1675 807 1676 809 1676 808 1676 810 1677 808 1677 809 1677 809 1678 811 1678 810 1678 812 1679 810 1679 811 1679 811 1680 813 1680 812 1680 814 1681 812 1681 813 1681 813 1682 815 1682 814 1682 816 1683 814 1683 815 1683 815 1684 817 1684 816 1684 818 1685 816 1685 817 1685 817 1686 819 1686 818 1686 820 1687 818 1687 819 1687 824 1688 822 1688 823 1688 823 1689 825 1689 824 1689 826 1690 824 1690 825 1690 825 1691 827 1691 826 1691 828 1692 826 1692 827 1692 827 1693 829 1693 828 1693 830 1694 828 1694 829 1694 829 1695 831 1695 830 1695 832 1696 830 1696 831 1696 831 1697 833 1697 832 1697 835 1698 832 1698 833 1698 833 1676 834 1676 835 1676 836 1699 835 1699 834 1699 350 1700 837 1700 349 1700 838 1701 349 1701 837 1701 837 1702 839 1702 838 1702 840 1702 838 1702 839 1702 839 1702 841 1702 840 1702 842 1702 840 1702 841 1702 841 1702 843 1702 842 1702 844 1702 842 1702 843 1702 843 1702 845 1702 844 1702 846 1702 844 1702 845 1702 845 1702 847 1702 846 1702 848 1702 846 1702 847 1702 847 1702 849 1702 848 1702 850 1702 848 1702 849 1702 849 1702 851 1702 850 1702 852 1702 850 1702 851 1702 851 1702 853 1702 852 1702 854 1702 852 1702 853 1702 853 1702 855 1702 854 1702 856 1702 854 1702 855 1702 855 1702 857 1702 856 1702 858 1702 856 1702 857 1702 857 1702 859 1702 858 1702 860 1702 858 1702 859 1702 859 1703 861 1703 860 1703 863 1704 860 1704 861 1704 861 1702 862 1702 863 1702 864 1702 863 1702 862 1702 865 1676 867 1676 866 1676 868 1676 866 1676 867 1676 867 1705 869 1705 868 1705 870 1706 868 1706 869 1706 869 1676 871 1676 870 1676 872 1676 870 1676 871 1676 871 1676 873 1676 872 1676 874 1676 872 1676 873 1676 873 1676 875 1676 874 1676 876 1707 874 1707 875 1707 875 1708 877 1708 876 1708 878 1676 876 1676 877 1676 877 1676 879 1676 878 1676 880 1676 878 1676 879 1676 879 1676 881 1676 880 1676 882 1676 880 1676 881 1676 881 1676 883 1676 882 1676 884 1676 882 1676 883 1676 883 1676 885 1676 884 1676 886 1676 884 1676 885 1676 885 1676 887 1676 886 1676 888 1676 886 1676 887 1676 887 1676 889 1676 888 1676 890 1676 888 1676 889 1676 889 1676 891 1676 890 1676 892 1676 890 1676 891 1676 891 1709 408 1709 892 1709 407 1710 892 1710 408 1710 893 1702 895 1702 894 1702 896 1711 894 1711 895 1711 895 1702 897 1702 896 1702 898 1702 896 1702 897 1702 897 1702 899 1702 898 1702 900 1702 898 1702 899 1702 899 1702 901 1702 900 1702 902 1702 900 1702 901 1702 901 1702 903 1702 902 1702 904 1712 902 1712 903 1712 903 1702 905 1702 904 1702 906 1702 904 1702 905 1702 905 1702 907 1702 906 1702 386 1713 906 1713 907 1713 907 1714 908 1714 386 1714 386 1715 908 1715 387 1715 908 1716 909 1716 387 1716 910 1717 387 1717 909 1717 909 1702 911 1702 910 1702 912 1702 910 1702 911 1702 911 1702 913 1702 912 1702 914 1718 912 1718 913 1718 913 1702 915 1702 914 1702 916 1702 914 1702 915 1702 915 1719 917 1719 916 1719 918 1702 916 1702 917 1702 917 1702 919 1702 918 1702 920 1702 918 1702 919 1702 919 1720 923 1720 920 1720 921 1721 920 1721 923 1721 923 1722 922 1722 921 1722 823 1723 381 1723 924 1723 924 1724 805 1724 823 1724 780 1725 781 1725 819 1725 380 1726 819 1726 781 1726 781 1727 780 1727 174 1727 174 1728 380 1728 781 1728 198 1729 196 1729 805 1729 805 1730 924 1730 198 1730 198 1731 924 1731 381 1731

+
+
+
+
+ + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/meshes/components/wrist/wrist_E4.dae b/URDFs/sr_description/meshes/components/wrist/wrist_E4.dae new file mode 100644 index 0000000..fe16dab --- /dev/null +++ b/URDFs/sr_description/meshes/components/wrist/wrist_E4.dae @@ -0,0 +1,133 @@ + + + + + + Illusoft Collada 1.4.0 plugin for Blender - http://colladablender.illusoft.com + Blender v:249 - Illusoft Collada Exporter v:0.3.162 + + + file:///media/ce7ff5ed-1b73-453e-869e-58fb97d47a68/ProjetHandle/ShadowHand/Modeles/VALIDE_vOptimizedWithoutDetails/BETA_shadow_hand_2012-07-22_envelop_opt_Zaligned_texture_decimate-ready.blend + + 2012-07-23T02:14:55.555034 + 2012-07-23T02:14:55.555052 + + Y_UP + + + + + + + + 0.00000 0.00000 0.00000 1 + + + 0.45000 0.45000 0.45000 1 + + + 0.90000 0.90000 0.90000 1 + + + 1.00000 1.00000 1.00000 1 + + + 0.0 + + + 1 1 1 1 + + + 0.0 + + + + + + + + + + + + + + + + -12.60386 -0.00040 -4.55191 -0.54290 13.89959 -4.46761 0.54193 13.89959 -4.46761 -1.59620 13.89959 -4.20799 1.59524 13.89959 -4.20799 -2.55677 13.89959 -3.70385 2.55581 13.89959 -3.70385 -3.36878 13.89959 -2.98447 3.36782 13.89959 -2.98447 -3.98503 13.89959 -2.09167 3.98407 13.89959 -2.09167 -4.36972 13.89959 -1.07734 4.36876 13.89959 -1.07734 -4.50048 13.89959 -0.00042 4.49952 13.89959 -0.00042 -4.36972 13.89959 1.07650 4.36876 13.89959 1.07650 -3.98503 13.89959 2.09083 3.98407 13.89959 2.09083 -3.36878 13.89959 2.98363 3.36782 13.89959 2.98363 -2.55677 13.89959 3.70301 2.55581 13.89959 3.70301 -1.59621 13.89959 4.20715 -0.54290 13.89959 4.46677 1.59524 13.89959 4.20715 0.54193 13.89959 4.46677 2.31715 10.59960 -7.13334 2.31714 10.59959 7.13250 0.78348 10.59960 -7.45934 0.78348 10.59959 7.45849 -0.78445 10.59960 -7.45934 -0.78445 10.59959 7.45849 -2.31811 10.59960 -7.13334 -2.31811 10.59959 7.13250 -3.75048 10.59960 -6.49561 -3.75048 10.59959 6.49477 -5.01896 10.59959 5.57317 -5.01896 10.59960 -5.57401 -6.06811 10.59960 -4.40881 -6.06811 10.59959 4.40797 -6.85207 10.59960 -3.05095 -6.85207 10.59960 3.05010 -7.33659 10.59960 1.55892 -7.33659 10.59960 -1.55976 -7.50048 10.59960 -0.00042 -7.33659 -10.60041 1.55892 -7.50049 -10.60041 -0.00042 -7.33659 -10.60041 -1.55976 -6.85208 -10.60040 -3.05095 -6.85208 -10.60041 3.05010 -6.06812 -10.60041 4.40797 -6.06811 -10.60041 -4.40881 -5.01897 -10.60041 -5.57401 -5.01897 -10.60041 5.57317 -3.75049 -10.60041 6.49477 -3.75048 -10.60041 -6.49561 -2.31811 -10.60041 7.13250 -2.31811 -10.60041 -7.13334 -0.78445 -10.60041 7.45849 -0.78445 -10.60041 -7.45934 0.78348 -10.60041 7.45849 0.78348 -10.60041 -7.45934 2.31714 -10.60041 7.13250 2.31714 -10.60041 -7.13334 -14.48772 7.22568 1.21112 -13.95641 7.52509 0.93113 -14.19300 7.34965 1.09963 -13.90642 5.60705 -0.55767 -13.79636 3.38683 -1.54026 -13.62562 5.80287 -0.82700 -13.37415 3.55958 -2.00872 -13.63172 7.84658 0.62766 -13.42834 6.02566 -1.14744 -13.47899 8.13542 0.34559 -13.59057 1.00859 -2.05556 -13.29065 0.99960 -2.43023 -13.81941 -3.37846 -1.52380 -14.03224 -5.53306 -0.46171 -13.55213 -0.99182 -2.09744 -13.25895 -1.00324 -2.49002 -13.38795 -3.54875 -1.98317 -13.58612 -5.82680 -0.86263 -14.26401 -7.32159 1.13379 -13.91214 -7.54561 0.91654 -13.62985 -7.86254 0.60894 -13.45037 -8.20210 0.28867 -13.43177 -8.35835 0.13871 -13.33815 -8.96163 6.94725 -14.02152 -9.25673 4.06271 -12.62189 -7.88431 7.72702 -13.68860 -9.47942 5.55454 -12.17220 -7.98916 7.62231 -12.79561 -9.12583 6.73785 -13.52762 -9.55666 3.80315 -13.12857 -9.80029 5.34117 -11.80590 -8.10198 7.60052 -12.36982 -9.38179 6.66783 -11.38435 -8.27721 7.68078 -12.05107 -9.64642 6.67054 -13.18897 -10.02901 3.50122 -12.65820 -10.25672 5.20334 -12.34419 -10.50040 5.65164 -13.10623 -10.46706 3.30983 -10.99744 -8.47381 7.83888 -11.76268 -9.96988 6.73570 -12.25473 -6.40498 7.99782 -11.72898 -6.40560 7.93281 -11.17216 -6.40683 8.02417 -10.64307 -6.40915 8.28321 -14.26038 9.15721 4.16294 -12.29217 6.40601 8.00338 -13.74552 9.47000 5.58112 -12.55224 7.89330 7.70474 -13.03981 9.03588 6.82450 -13.85801 9.33975 3.98340 -13.33376 9.66441 5.42183 -12.56829 9.24682 6.69359 -13.50539 9.60548 3.77503 -11.92678 8.05235 7.58945 -13.02474 9.90194 5.30744 -11.80182 6.40682 7.93720 -12.21385 9.49928 6.66542 -13.26845 9.92961 3.56703 -11.13580 6.40570 8.03591 -13.11173 10.18750 3.41007 -11.28393 8.31322 7.69886 -10.73077 6.40590 8.22361 -12.64398 10.38079 5.24346 -11.84269 9.83655 6.69265 -12.47477 10.49960 5.26739 -10.75736 8.63854 8.05253 -24.88471 -9.35137 23.00377 -24.13114 -9.40305 23.00179 -23.38857 -9.26547 23.01383 -22.12126 -8.46693 23.01970 -22.70383 -8.94547 23.00735 -21.39638 -7.15635 23.02859 -21.67562 -7.85566 23.01203 -23.87215 -9.40192 20.17845 -23.19525 -9.38724 17.47330 -21.99669 -8.94589 18.29033 -20.99868 -7.85505 18.54457 -21.94929 -9.39938 14.24081 -20.17987 -8.94589 13.92521 -19.26540 -7.85505 14.39999 -19.93711 -9.40192 10.96064 -17.36017 -8.94589 10.12988 -16.57709 -7.85505 10.80070 -17.34748 -9.40192 8.11977 -13.71346 -8.96542 7.08199 -13.04990 -7.81858 7.94862 -14.23772 -9.38277 5.85688 -24.88455 9.34945 22.99273 -23.38881 9.26415 22.99850 -24.13438 9.40093 22.94129 -22.70510 8.94655 22.96461 -22.12062 8.46669 23.00962 -21.39598 7.15553 23.02449 -21.67454 7.85688 22.98570 -21.99899 8.94669 18.28904 -21.00004 7.85689 18.54399 -23.36385 9.40128 17.86201 -20.18188 8.94669 13.92356 -19.26665 7.85689 14.39923 -21.37263 9.40128 13.12622 -17.36185 8.94669 10.12793 -16.57822 7.85689 10.79978 -13.63308 8.92521 7.04131 -18.28204 9.40128 9.02243 -12.95601 7.82493 7.86842 -14.24571 9.39143 5.82465 -28.29540 7.12390 23.04268 -30.07768 4.28939 23.02099 -30.54342 2.67371 23.01016 -29.31952 5.79025 23.03187 -25.59235 9.09639 23.03309 -27.04103 8.24381 23.05341 -25.28474 9.10898 19.71424 -27.61936 7.12429 17.71068 -29.29788 4.28653 17.06409 -24.50582 9.10898 16.57668 -23.27924 9.10898 13.58126 -25.81796 7.12429 12.64688 -27.20717 4.28652 11.43173 -21.63284 9.10898 10.79699 -22.97470 7.12429 8.08584 -23.91240 4.28652 6.40789 -19.60074 9.10898 8.28056 -14.54596 9.10868 4.25243 -17.22583 9.10898 6.08501 -19.22128 7.12429 4.23888 -14.43425 5.40799 -0.30267 -14.73110 7.12708 1.28862 -19.57969 4.28652 2.24588 -14.20562 3.28901 -1.33376 -30.07768 -4.29019 23.02099 -29.31952 -5.79105 23.03187 -30.54342 -2.67451 23.01016 -28.29363 -7.12628 23.04270 -27.04103 -8.24461 23.05341 -25.60065 -9.11085 23.01348 -25.46428 -9.10979 20.96733 -25.15497 -9.10979 19.02628 -24.67524 -9.10978 17.11820 -27.61719 -7.12757 17.71145 -29.29673 -4.29047 17.06458 -25.81612 -7.12757 12.64832 -23.24655 -9.10978 13.51576 -27.20625 -4.29047 11.43263 -21.96199 -9.10978 11.28491 -20.42908 -9.10979 9.21762 -22.97337 -7.12757 8.08786 -23.91183 -4.29047 6.40911 -18.66796 -9.10979 7.34085 -16.70228 -9.10979 5.67980 -14.44149 -9.10329 4.22508 -19.22062 -7.12757 4.24131 -14.62641 -7.17487 1.26451 -14.47512 -5.33858 -0.21095 -19.57957 -4.29047 2.24733 -14.24722 -3.28159 -1.25828 -13.08897 10.47856 3.10286 -13.40044 10.49960 0.03300 -13.40676 8.41941 0.07982 -13.40044 -10.50040 0.03300 -13.32003 -6.17464 -1.36950 -13.32796 6.25340 -1.48803 -13.20270 10.49960 -2.29430 -13.09723 3.74191 -2.54411 -13.05894 0.99960 -3.00666 -13.09158 -1.00050 -2.92509 -13.19020 -3.70530 -2.44498 -13.20271 -10.50040 -2.29430 -12.60386 10.49960 -4.55191 -12.60386 -10.50040 -4.55191 -11.62209 10.49960 -6.67124 -11.62209 -10.50040 -6.67124 -10.28724 10.49960 -8.58790 -10.28724 -10.50040 -8.58790 -8.63985 10.49960 -10.24366 -8.63985 -10.50040 -10.24366 -6.72998 10.49960 -11.58821 -6.72998 -10.50040 -11.58821 -4.61565 10.49959 -12.58070 -4.61565 -10.50041 -12.58070 -2.36111 10.49959 -13.19098 -2.36110 -10.50041 -13.19098 -0.03484 10.49959 -13.40051 -0.03483 -10.50041 -13.40051 2.29247 10.49959 -13.20291 2.29248 -10.50041 -13.20291 2.15348 10.49959 13.22520 2.15348 -10.50041 13.22520 -0.07688 10.49959 13.39923 -0.07689 -10.50041 13.39923 -2.30523 10.49959 13.19976 -2.30524 -10.50041 13.19976 -4.46929 10.49959 12.63234 -4.46930 -10.50041 12.63233 -6.50868 10.49959 11.71284 -6.50869 -10.50041 11.71283 -8.36659 10.49959 10.46694 -8.36661 -10.50041 10.46692 -11.33783 10.49960 7.14268 -10.58126 8.76704 8.21934 -9.99129 10.49960 8.92939 -11.34845 -10.49318 7.12164 -10.66137 -8.70710 8.12063 -10.28659 -6.40669 8.60038 -10.25925 6.40596 8.62536 -9.99131 -10.50040 8.92937 -0.00049 -15.40040 -7.50042 1.46269 -15.40040 -7.35631 -1.46366 -15.40040 -7.35631 2.86964 -15.40040 -6.92952 -2.87061 -15.40040 -6.92952 4.16629 -15.40041 -6.23644 -4.16726 -15.40040 -6.23644 5.30282 -15.40041 -5.30372 -5.30379 -15.40040 -5.30372 6.23554 -15.40041 -4.16720 -6.23651 -15.40040 -4.16720 6.92861 -15.40041 -2.87055 -6.92958 -15.40040 -2.87055 7.35540 -15.40041 -1.46360 -7.35638 -15.40040 -1.46360 7.49951 -15.40041 -0.00042 -7.50049 -15.40040 -0.00042 7.35540 -15.40041 1.46276 -7.35638 -15.40040 1.46276 6.92861 -15.40041 2.86971 -6.92958 -15.40040 2.86971 6.23553 -15.40041 4.16636 -6.23651 -15.40041 4.16636 5.30281 -15.40041 5.30288 -5.30379 -15.40041 5.30288 4.16629 -15.40041 6.23560 -4.16727 -15.40041 6.23560 2.86964 -15.40041 6.92868 -2.87061 -15.40041 6.92868 -1.46367 -15.40041 7.35547 -0.00049 -15.40041 7.49958 1.46269 -15.40041 7.35547 -0.00048 15.39959 7.49958 1.46269 15.39959 7.35547 -1.46366 15.39959 7.35547 2.86964 15.39959 6.92868 -2.87061 15.39959 6.92868 4.16629 15.39959 6.23560 -4.16726 15.39959 6.23560 5.30282 15.39959 5.30288 -0.00048 15.39959 4.49958 -5.30378 15.39959 5.30288 1.00086 15.39959 4.38676 -1.00183 15.39959 4.38676 6.23554 15.39959 4.16636 1.95199 15.39959 4.05394 -1.95296 15.39959 4.05394 -6.23651 15.39959 4.16636 -2.80619 15.39959 3.51782 -3.51872 15.39959 2.80528 -6.92958 15.39959 2.86971 -4.05484 15.39959 1.95206 -4.38766 15.39959 1.00093 -7.35637 15.39959 1.46276 -4.50048 15.39959 -0.00042 -7.50048 15.39959 -0.00042 -4.38766 15.39959 -1.00176 -4.05484 15.39959 -1.95290 -7.35637 15.39959 -1.46360 -3.51872 15.39959 -2.80612 -2.80619 15.39959 -3.51866 -6.92958 15.39960 -2.87055 1.95200 15.39959 -4.05478 -1.95296 15.39959 -4.05478 1.00086 15.39959 -4.38760 -0.00048 15.39959 -4.50042 -1.00182 15.39959 -4.38760 -6.23650 15.39959 -4.16720 5.30282 15.39959 -5.30372 -5.30378 15.39959 -5.30372 4.16630 15.39959 -6.23644 -4.16726 15.39959 -6.23644 2.86965 15.39959 -6.92952 -2.87061 15.39959 -6.92952 -1.46366 15.39959 -7.35631 -0.00048 15.39959 -7.50042 1.46270 15.39959 -7.35631 -21.30162 -6.40750 23.03941 -21.30144 6.40653 23.02324 -21.05293 -6.40666 20.48503 -21.05293 6.40585 20.48503 -20.45402 -6.40666 18.02602 -20.45402 6.40585 18.02602 -19.51434 -6.40666 15.67261 -19.51434 6.40585 15.67261 -18.25390 -6.40666 13.47585 -18.25390 6.40585 13.47586 -16.69758 -6.40666 11.47834 -16.69758 6.40585 11.47835 -14.87602 -6.40666 9.71929 -12.82573 -6.40666 8.23382 -14.87602 6.40585 9.71929 -12.82573 6.40585 8.23383 -30.41643 -1.00040 19.53470 -29.69563 0.99960 16.13403 -28.54962 0.99960 12.85194 -26.99694 0.99960 9.74162 -26.99669 -1.00040 9.74117 -25.06267 0.99960 6.85320 -25.06223 -1.00040 6.85262 -22.77773 0.99960 4.23294 -22.77734 -1.00040 4.23257 -20.17892 0.99960 1.92327 -20.17875 -1.00040 1.92313 -17.30873 0.99960 -0.03817 -14.21282 0.99960 -1.62019 -17.30859 -1.00040 -0.03825 -14.21282 -1.00040 -1.62019 -30.69927 0.99943 23.04174 -30.70291 -1.00075 23.02165 -30.41645 0.99960 19.53490 -29.69556 -1.00040 16.13377 -28.54948 -1.00040 12.85162 35.56442 -1.00041 18.82635 35.89960 1.00018 23.02512 35.89865 -1.00030 23.04285 35.60408 0.99999 18.94442 34.68587 -1.00041 14.73265 34.68535 0.99959 14.73082 33.27864 -1.00041 10.78832 33.27790 0.99959 10.78664 31.36698 -1.00041 7.06207 31.36615 0.99959 7.06070 28.98425 -1.00041 3.61868 28.98302 0.99959 3.61714 26.17130 -1.00041 0.51695 26.16953 0.99959 0.51526 22.97604 -1.00041 -2.19013 22.97423 0.99959 -2.19147 19.45300 -1.00041 -4.45602 19.45189 0.99959 -4.45665 15.66376 -1.00041 -6.24092 15.66357 0.99959 -6.24101 11.64083 -0.99333 -7.51363 11.67386 0.99959 -7.51412 26.49701 -6.40790 23.00487 26.50031 6.40680 23.03065 26.24158 -6.40714 20.03259 26.24143 6.40632 20.03162 25.59420 -6.40714 17.12513 25.59365 6.40632 17.12325 24.56920 -6.40714 14.32965 24.56801 6.40632 14.32697 23.18434 -6.40714 11.69390 23.18226 6.40632 11.69051 21.45901 -6.40714 9.25799 21.45568 6.40632 9.25390 19.44430 -6.40714 7.08838 19.44081 6.40632 7.08509 17.34859 -6.40714 5.33769 17.34648 6.40632 5.33613 15.28735 6.40805 3.98648 15.28216 -6.40734 3.98093 6.23554 15.39959 -4.16720 2.80522 15.39959 -3.51866 6.92861 15.39959 -2.87055 3.51776 15.39959 -2.80612 4.05388 15.39959 -1.95290 7.35541 15.39959 -1.46360 4.38669 15.39959 -1.00176 4.49952 15.39959 -0.00042 7.49952 15.39959 -0.00042 4.38669 15.39959 1.00093 7.35541 15.39959 1.46276 4.05388 15.39959 1.95206 3.51776 15.39959 2.80528 6.92861 15.39959 2.86971 2.80522 15.39959 3.51782 4.32370 -10.50041 12.68256 4.32371 10.49959 12.68256 6.37333 -10.50041 11.78650 6.37333 10.49959 11.78649 8.24526 -10.50041 10.56201 8.24527 10.49959 10.56200 9.88738 -10.50041 9.04324 9.88738 10.49959 9.04324 11.25394 -10.50041 7.27254 11.25394 10.49959 7.27254 12.30691 -10.50041 5.29925 12.30692 10.49959 5.29925 12.48335 -6.40739 4.90258 12.71416 -9.07247 4.22862 12.43964 6.40632 4.97975 12.68775 9.13363 4.25919 13.25704 10.50525 2.32517 13.18964 -10.50041 -2.36255 12.57940 -10.50041 -4.61647 12.89855 -9.67272 -3.62335 12.57939 10.49959 -4.61647 13.18965 10.49959 -2.36255 12.88448 9.63719 -3.66647 12.21337 7.94797 -5.50560 11.58678 -10.50041 -6.73074 12.21218 -7.94114 -5.51293 11.58677 10.49959 -6.73074 11.51189 -6.06881 -6.85762 11.51664 6.08266 -6.85008 10.24212 -10.50041 -8.64053 10.67074 0.99921 -8.11293 10.66506 -1.00030 -8.11141 10.83492 -3.55577 -7.89054 10.88949 3.53806 -7.81976 10.24211 10.49959 -8.64054 8.58626 -10.50041 -10.28782 8.58625 10.49959 -10.28783 6.66952 -10.50041 -11.62256 6.66951 10.49959 -11.62256 4.55013 -10.50041 -12.60420 4.55012 10.49959 -12.60420 35.67098 -2.91176 23.41162 35.10701 -4.69323 24.05084 34.51861 -5.79096 22.99116 32.24020 -8.24452 23.00877 30.79715 -9.11441 22.99093 33.49187 -7.12698 22.99789 30.45738 -9.11051 19.15825 32.79480 -7.12707 17.06920 34.46150 -4.29016 16.35134 29.44318 -9.13203 15.42730 30.91869 -7.12707 11.40214 32.25470 -4.29016 10.03840 27.71212 -9.11051 10.95918 27.94042 -7.12707 6.22863 26.26256 -9.11051 8.52879 28.75688 -4.29016 4.33854 24.56230 -9.11051 6.26149 22.66412 -9.11051 4.21714 23.98184 -7.12707 1.76040 24.12780 -4.29015 -0.48793 20.67170 -9.11051 2.46631 18.69316 -9.11050 1.03600 19.20498 -7.12707 -1.81966 16.78089 -9.11050 -0.10730 18.57887 -4.29015 -4.22057 14.85429 -9.11536 -1.01545 14.19183 -8.09903 -3.02073 13.46651 -6.75450 -4.84491 11.88470 -3.19872 -7.20780 12.61154 -4.96985 -6.29130 35.27751 4.28659 23.01634 34.51856 5.79020 23.02481 33.49437 7.12394 23.03323 32.24012 8.24375 23.04163 30.79967 9.11036 23.00775 32.80304 7.12410 17.09722 30.54383 9.10968 19.72866 34.46772 4.28640 16.37301 29.90321 9.10968 16.56613 30.92986 7.12410 11.42224 28.88781 9.10968 13.50447 32.26332 4.28640 10.05390 27.51255 9.10968 10.58758 27.95177 7.12410 6.24101 25.79234 9.10968 7.85021 28.76567 4.28640 4.34804 23.75453 9.10968 5.33895 23.99086 7.12410 1.76602 21.51544 9.10968 3.16539 24.13470 4.28640 -0.48361 19.20959 7.12411 -1.81921 19.24568 9.10968 1.40820 17.04753 9.10969 0.03941 18.58228 4.28640 -4.22007 13.79232 7.10996 -4.35238 14.33083 8.00472 -3.01229 14.93884 9.10969 -1.01760 11.98112 3.17161 -7.16036 12.80422 5.00471 -6.27410 29.33309 9.40134 22.94975 30.08383 9.35425 22.99638 26.59515 7.15561 23.01965 26.87466 7.85676 23.00244 26.29238 7.85724 18.31521 27.27739 8.94702 18.00122 27.31973 8.46639 23.00948 27.90369 8.94572 22.99972 28.63104 9.40172 17.51563 28.58735 9.26455 23.00108 24.77109 7.85724 13.86825 25.63348 8.94702 13.27911 26.77773 9.40172 12.35932 22.37364 7.85724 9.82570 23.04388 8.94702 9.00187 23.85976 9.40172 7.72165 19.20110 7.85724 6.35800 19.62173 8.94702 5.35638 20.01346 9.40172 3.81929 15.35070 7.89198 3.53765 15.50805 9.08422 2.16505 15.18956 9.39706 0.20453 29.33042 -9.40730 22.97453 26.87267 -7.85526 22.99909 26.29455 -7.85542 18.33118 27.31945 -8.46778 23.01072 27.90180 -8.94608 22.98559 27.27926 -8.94623 18.02046 28.13668 -9.43483 15.71140 28.58736 -9.26600 22.99869 24.77486 -7.85542 13.87991 25.63741 -8.94623 13.29348 25.54921 -9.40238 10.13518 22.37741 -7.85541 9.83324 23.04801 -8.94623 9.01154 22.76218 -9.40238 6.43190 19.20344 -7.85541 6.36204 19.62439 -8.94623 5.36206 19.34743 -9.40238 3.29801 15.38655 -7.90337 3.56958 15.48328 -9.08043 2.17480 15.21953 -9.38465 0.20242 12.71159 -6.40639 4.50438 12.74383 6.40694 4.46699 13.11625 -6.40706 4.10916 13.17147 6.40534 4.06695 13.67181 -6.40729 3.82388 13.63432 6.40488 3.83865 14.16679 -6.40621 3.72869 14.16567 6.40517 3.73141 14.74828 -6.40559 3.77486 14.78990 6.40795 3.78526 12.58938 6.40624 4.72038 12.84993 8.84319 3.96175 13.47079 10.08159 2.14671 13.19677 8.55461 3.61157 13.69240 10.33885 0.10007 13.57160 8.34648 3.40352 13.86713 9.62944 2.02199 13.98212 8.18787 3.28635 14.07981 9.87364 0.14741 14.31560 9.33661 1.97631 14.40984 8.07622 3.25155 14.50780 6.40489 3.75358 14.52968 9.59005 0.18204 14.90134 9.13856 1.99861 14.85833 8.01625 3.30744 14.85845 9.46198 0.19548 13.48269 10.32783 -1.34628 13.95208 9.60692 -1.10757 14.66569 9.18686 -1.01369 12.93925 9.41483 -3.53728 12.36359 7.69195 -5.23325 13.11882 9.01344 -3.32705 13.65545 9.95317 -1.21632 11.60970 5.81624 -6.70498 12.71295 7.44038 -4.91488 13.41292 8.65007 -3.17383 11.93168 5.52365 -6.44411 10.94455 0.99738 -7.87140 11.28216 3.39613 -7.43880 13.14305 7.23847 -4.66389 13.77247 8.35124 -3.08141 14.29804 9.36786 -1.04865 12.31590 5.27040 -6.28185 11.73384 3.19752 -7.16874 11.35846 0.99781 -7.62773 14.18860 8.09826 -3.03375 10.90901 -0.99577 -7.89165 11.23977 -0.99918 -7.68268 13.55432 -10.50586 -0.44094 12.95099 -9.37372 -3.50425 12.34374 -7.74751 -5.26691 13.12794 -9.02062 -3.32480 11.63522 -5.80562 -6.68770 12.61567 -7.37134 -5.02173 13.92358 -9.63900 -1.11594 13.37768 -8.69748 -3.18544 11.02792 -3.52860 -7.64708 11.90387 -5.55691 -6.46360 14.30893 -9.34458 -1.04496 13.69316 -8.41773 -3.09304 11.37410 -3.36257 -7.37211 13.06867 -6.99306 -4.85521 12.23053 -5.32839 -6.30559 13.73215 -10.26075 0.11352 13.65034 -9.95749 -1.21899 14.04955 -9.92929 0.15063 14.42913 -9.63355 0.17846 14.87790 -9.45857 0.19826 12.84600 -8.85458 3.98163 13.32162 -10.49276 2.06913 13.08870 -8.63163 3.70309 12.92298 -6.40751 4.29738 13.47838 -10.08774 2.15254 13.44063 -8.41393 3.46980 13.38458 -6.40547 3.96435 13.77817 -9.70742 2.04130 13.80434 -8.24599 3.32269 14.08722 -9.47522 1.99617 14.36399 -8.07932 3.24406 14.45476 -9.27130 1.97544 14.96485 -9.12934 2.00828 14.97332 -8.00720 3.33362 7.49951 -10.60041 -0.00042 7.33562 -10.60041 -1.55976 6.85111 -10.60041 -3.05095 6.85110 -10.60041 3.05010 7.33562 -10.60041 1.55892 6.06714 -10.60041 4.40797 6.06714 -10.60041 -4.40881 5.01799 -10.60041 -5.57401 5.01799 -10.60041 5.57317 3.74951 -10.60041 6.49477 3.74952 -10.60041 -6.49561 3.74952 10.59959 -6.49561 3.74952 10.59959 6.49477 5.01800 10.59959 -5.57401 5.01800 10.59959 5.57317 6.06715 10.59959 -4.40881 6.06714 10.59959 4.40797 6.85111 10.59959 3.05010 6.85111 10.59959 -3.05095 7.33562 10.59959 -1.55976 7.49952 10.59959 -0.00042 7.33562 10.59959 1.55892 13.44627 10.50242 -0.01869 35.69546 3.05739 23.43314 -25.69792 -8.06854 26.52259 -26.35478 -8.04488 26.51994 -25.26371 -8.17598 26.64023 -24.16000 -9.02968 27.71689 -24.45500 -8.67075 27.23014 -24.83796 -8.37893 26.87214 -24.45243 8.67238 27.23327 -24.16008 9.02875 27.71671 -24.83342 8.38089 26.87540 -25.25692 8.17761 26.64293 -25.69196 8.06858 26.52351 -26.35262 8.04343 26.51944 30.89098 -8.06940 26.52353 31.55164 -8.04425 26.51945 30.45594 -8.17842 26.64295 30.03244 -8.38171 26.87541 29.65145 -8.67320 27.23329 29.35909 -9.02957 27.71672 29.35902 9.02887 27.71690 29.65402 8.66993 27.23016 30.03698 8.37811 26.87215 30.46273 8.17516 26.64024 30.89694 8.06772 26.52260 31.55380 8.04406 26.51995 30.30964 -9.28881 26.71105 29.51329 -9.40195 27.42233 29.85156 -9.38048 27.02176 29.21206 -9.39401 28.27592 29.30267 -9.39645 27.86289 28.81621 -9.33038 28.16568 28.36078 -9.18566 27.93929 27.89046 -8.94547 27.58514 27.52685 -8.66804 27.22668 27.16869 -8.30602 26.77394 26.87688 -7.86445 26.30823 26.71915 -7.53458 25.98483 26.60021 -7.17856 25.66446 26.52537 -6.80088 25.35357 -25.11475 -9.28649 26.70846 -24.73201 -9.37661 26.95330 -24.45204 -9.39816 27.23272 -24.18235 -9.39973 27.66239 -24.01589 -9.38310 28.21809 -23.61292 -9.32953 28.16398 -23.27349 -9.22654 28.00972 -22.92326 -9.07597 27.77525 -22.57237 -8.86007 27.47989 -22.32934 -8.66934 27.22835 -22.09323 -8.43956 26.94403 -21.87564 -8.17419 26.63824 -21.68406 -7.87555 26.31960 -21.52446 -7.54521 25.99483 -21.40323 -7.18620 25.67105 -21.32681 -6.80432 25.35626 30.31377 9.28566 26.70846 29.93103 9.37579 26.95331 29.65106 9.39735 27.23273 29.38137 9.39891 27.66240 29.21495 9.38221 28.21792 28.80724 9.32764 28.16212 28.46433 9.22273 28.00512 28.10902 9.06841 27.76509 27.75194 8.84543 27.46115 27.50480 8.64778 27.20188 27.26728 8.41127 26.91131 27.05169 8.14141 26.60291 26.86490 7.84184 26.28602 26.64308 7.35032 25.80266 26.52453 6.79367 25.34855 -25.11072 9.28798 26.71104 -24.31433 9.40116 27.42237 -24.65256 9.37968 27.02179 -24.01304 9.39320 28.27591 -24.10299 9.39558 27.86508 -23.61179 9.32847 28.16351 -23.15257 9.18113 27.93344 -22.80202 9.00596 27.68408 -22.55539 8.84721 27.46354 -22.30408 8.64627 27.19994 -22.06303 8.40544 26.90438 -21.84580 8.13166 26.59218 -21.57421 7.67631 26.10763 -21.39569 7.15675 25.64643 -21.32504 6.79000 25.34565 -25.60049 9.11070 26.53998 -26.06235 8.87196 26.50053 -26.53616 8.59014 26.57264 -26.98871 8.28209 26.76077 -27.93840 7.48716 25.94127 -28.70745 6.64783 25.23596 -29.35557 5.73244 24.61157 -29.90789 4.69264 24.05094 -30.33595 3.53512 23.58323 -30.60797 2.28678 23.23998 30.79951 9.11069 26.53999 31.73488 8.59032 26.57257 31.26123 8.87203 26.50054 32.18773 8.28208 26.76079 33.13742 7.48715 25.94128 33.90647 6.64782 25.23597 34.55459 5.73243 24.61159 35.10691 4.69263 24.05095 30.79951 -9.11152 26.54000 31.26137 -8.87278 26.50054 31.73518 -8.59096 26.57266 32.18773 -8.28291 26.76079 33.13676 -7.48862 25.94187 33.90627 -6.64890 25.23616 34.55468 -5.73310 24.61150 -25.60049 -9.11151 26.53998 -26.53586 -8.59113 26.57256 -26.06221 -8.87285 26.50052 -26.98871 -8.28290 26.76077 -27.93774 -7.48861 25.94185 -28.70725 -6.64889 25.23615 -29.35566 -5.73309 24.61148 -29.90799 -4.69322 24.05083 -30.33597 -3.53584 23.58320 -30.70049 10.98821 34.50007 -30.70049 10.88394 32.40859 -30.70049 10.69424 36.57342 -30.70049 10.38520 30.37476 -30.70050 10.01268 38.55349 -30.70049 9.51008 28.47230 -30.70050 8.96824 40.36852 -30.70049 8.29029 26.77015 -30.70050 7.59876 41.95273 -30.70049 6.77003 25.33001 -30.70050 5.95388 43.24871 -30.70049 5.00440 24.20407 -30.70050 4.09320 44.20949 -30.70049 3.05740 23.43312 -30.70050 2.08417 44.80024 -30.70050 -0.00040 44.99957 -30.70050 -2.08498 44.80024 -30.70049 -3.05820 23.43312 -30.70050 -4.09401 44.20949 -30.70049 -5.00521 24.20407 -30.70050 -5.95468 43.24871 -30.70049 -6.77083 25.33001 -30.70050 -7.59957 41.95274 -30.70049 -8.29109 26.77015 -30.70050 -8.96904 40.36852 -30.70049 -9.51088 28.47230 -30.70050 -10.01348 38.55350 -30.70049 -10.38600 30.37476 -30.70049 -10.88474 32.40859 -30.70049 -10.69504 36.57343 -30.70049 -10.98901 34.50008 -21.30049 6.40700 25.05836 -21.30049 -6.40781 25.05836 -21.30049 7.95500 26.40277 -21.30049 -7.95582 26.40277 -21.30049 9.22661 28.01107 -21.30049 -9.22742 28.01107 -21.30049 10.17766 29.82740 -21.30049 -10.17846 29.82740 -21.30049 10.77512 31.78865 -21.30049 -10.77592 31.78866 -21.30049 10.99824 33.82669 -21.30049 -10.99904 33.82669 -21.30049 10.83929 35.87072 -21.30049 -10.84009 35.87072 -21.30049 10.30379 37.84973 -21.30049 -10.30459 37.84973 -21.30049 9.41035 39.69498 -21.30049 -9.41116 39.69498 -21.30049 8.19002 41.34239 -21.30049 -8.19083 41.34239 -21.30049 6.68519 42.73472 -21.30049 -6.68600 42.73473 -21.30049 4.94813 43.82362 -21.30049 -4.94894 43.82363 -21.30050 3.03919 44.57127 -21.30050 1.02466 44.95171 -21.30050 -3.04000 44.57127 -21.30050 -1.02547 44.95171 26.49950 1.02465 44.95172 26.49950 -1.02548 44.95172 26.49950 3.03918 44.57128 26.49950 -3.04001 44.57129 26.49951 4.94812 43.82364 26.49951 -4.94895 43.82364 26.49951 6.68518 42.73473 26.49951 -6.68601 42.73474 26.49951 8.19001 41.34240 26.49951 -8.19084 41.34240 26.49951 9.41034 39.69499 26.49951 -9.41117 39.69500 26.49951 10.30378 37.84974 26.49951 -10.30460 37.84974 26.49951 10.83928 35.87073 26.49951 -10.84010 35.87073 26.49951 10.99823 33.82670 26.49951 -10.99905 33.82671 26.49951 10.77511 31.78867 26.49951 -10.77593 31.78867 26.49951 10.17765 29.82741 26.49951 -10.17847 29.82741 26.49951 9.22661 28.01108 26.49951 -9.22743 28.01108 26.49951 7.95500 26.40278 26.49951 -7.95582 26.40278 26.49951 6.40699 25.05838 26.49951 -6.40781 25.05838 35.89951 10.98820 34.50008 35.89951 10.88393 32.40860 35.89951 10.69423 36.57343 35.89951 10.38519 30.37477 35.89951 10.01267 38.55351 35.89951 9.51007 28.47231 35.89951 8.96823 40.36853 35.89951 8.29028 26.77017 35.89951 7.59875 41.95275 35.89951 6.77002 25.33003 35.89951 5.95387 43.24872 35.89951 5.00439 24.20408 35.89951 4.09319 44.20951 35.89951 3.05739 23.43314 35.89951 2.08416 44.80026 35.89951 -0.00041 44.99959 35.89951 -2.08499 44.80026 35.89951 -3.05821 23.43314 35.89951 -4.09402 44.20951 35.89951 -5.00522 24.20408 35.89951 -5.95470 43.24872 35.89951 -6.77085 25.33003 35.89951 -7.59958 41.95275 35.89951 -8.29110 26.77017 35.89951 -8.96905 40.36853 35.89951 -9.51089 28.47231 35.89951 -10.01349 38.55351 35.89951 -10.38601 30.37477 35.89951 -10.88475 32.40860 35.89951 -10.98902 34.50009 35.89951 -10.69505 36.57344 -30.60796 -2.28766 23.24000 + + + + + + + + + + 0.00351 -0.99986 0.01651 0.00000 -0.99986 0.01683 -0.88619 0.44850 -0.11622 -0.78877 0.60651 -0.09996 -0.83885 0.52713 -0.13587 -0.65725 0.73765 -0.15457 -0.50717 0.86073 -0.04374 -0.00723 -0.99986 -0.01540 -0.00979 -0.99986 -0.01391 -0.00995 -0.99986 -0.01370 -0.01209 -0.99985 -0.01203 -0.01357 -0.99986 -0.00945 -0.01317 -0.99984 -0.01186 -0.01514 -0.99986 -0.00702 -0.01511 -0.99985 -0.00872 -0.01626 -0.99986 -0.00431 -0.01638 -0.99985 -0.00532 -0.01682 -0.99986 -0.00177 -0.01696 -0.99986 -0.00144 -0.01694 -0.99985 0.00178 -0.01949 -0.99974 0.01192 -0.02103 -0.99976 0.00683 -0.02161 -0.99974 -0.00720 -0.01202 -0.99984 0.01306 -0.01566 -0.99984 0.00904 -0.01613 -0.99984 0.00811 -0.01251 -0.99986 0.01126 -0.01174 -0.99985 0.01240 -0.00939 -0.99986 0.01401 -0.01006 -0.99985 0.01384 -0.00698 -0.99986 0.01547 -0.00939 0.99986 0.01401 -0.01174 0.99985 0.01240 -0.01251 0.99986 0.01126 -0.01364 0.99985 0.01028 -0.01460 0.99986 0.00843 -0.01435 0.99986 0.00870 -0.01944 0.99980 -0.00420 -0.01935 0.99979 0.00629 -0.01869 0.99979 0.00875 -0.01694 0.99985 0.00178 -0.01695 0.99986 -0.00144 -0.01682 0.99986 -0.00177 -0.01650 0.99985 -0.00438 -0.01602 0.99986 -0.00521 -0.01551 0.99985 -0.00718 -0.01457 0.99986 -0.00842 -0.01402 0.99985 -0.00977 -0.01253 0.99986 -0.01128 -0.01209 0.99985 -0.01203 -0.00975 0.99986 -0.01385 -0.95927 0.00000 -0.28251 -0.95855 0.00402 -0.28490 -0.95788 0.00000 -0.28717 -0.90737 0.00000 -0.42034 -0.90737 0.00000 -0.42034 -0.96656 -0.00572 -0.25638 -0.46377 -0.36064 -0.80923 -0.45318 -0.53536 -0.71275 -0.99676 0.00262 -0.08039 -0.99223 -0.09399 -0.08153 -0.94714 -0.27414 -0.16666 -0.99664 -0.00000 -0.08188 -0.97827 0.00001 -0.20735 -0.18189 -0.98107 -0.06642 -0.16835 -0.98346 -0.06677 -0.97827 -0.00001 -0.20736 -0.94410 0.00001 -0.32965 -0.94410 -0.00001 -0.32967 0.99529 0.00011 0.09690 0.99524 0.00000 0.09744 0.97160 -0.00000 0.23664 0.97160 0.00000 0.23664 0.92871 -0.00000 0.37082 0.20791 -0.00842 -0.97811 0.09802 0.00749 -0.99516 0.00000 -0.00856 -0.99996 -0.09801 0.00749 -0.99516 -0.20791 -0.00842 -0.97811 -0.29027 0.00722 -0.95692 -0.40672 -0.00803 -0.91352 -0.47139 0.00669 -0.88190 -0.58777 -0.00735 -0.80900 -0.63438 0.00589 -0.77300 -0.74313 -0.00642 -0.66912 -0.77300 0.00481 -0.63439 -0.86601 -0.00521 -0.49999 -0.88192 0.00348 -0.47139 -0.95105 -0.00374 -0.30901 -0.95694 0.00187 -0.29029 -0.99452 -0.00200 -0.10453 -0.99518 0.00000 -0.09802 -0.33023 -0.01785 0.94373 -0.23926 0.02143 0.97072 -0.11194 -0.01875 0.99354 0.00000 0.02187 0.99976 0.11194 -0.01875 0.99354 0.23926 0.02143 0.97072 0.33023 -0.01785 0.94373 0.46462 0.02008 0.88528 0.53196 -0.01607 0.84662 0.66302 0.01785 0.74839 0.70705 -0.01339 0.70704 0.82289 0.01472 0.56800 0.84668 -0.00982 0.53201 0.93496 0.01071 0.35459 0.94387 -0.00535 0.33027 0.99271 -0.00000 0.12054 0.99369 0.00624 0.11196 0.99371 0.00000 -0.11196 0.99269 0.00580 -0.12054 0.94387 -0.00535 -0.33028 0.93496 0.01071 -0.35459 0.84668 -0.00981 -0.53201 0.82290 0.01472 -0.56800 0.70704 -0.01339 -0.70704 0.66302 0.01785 -0.74839 0.53196 -0.01607 -0.84661 0.46463 0.02008 -0.88528 0.33023 -0.01785 -0.94373 0.23926 0.02143 -0.97072 0.11194 -0.01875 -0.99354 0.00000 0.02187 -0.99976 -0.11194 -0.01875 -0.99354 -0.23926 0.02143 -0.97072 -0.33023 -0.01785 -0.94373 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 -0.99452 -0.00000 0.10453 -0.99518 -0.00214 0.09802 -0.95694 0.00187 0.29028 -0.95105 -0.00374 0.30902 -0.88192 0.00348 0.47139 -0.86601 -0.00521 0.49999 -0.77300 0.00481 0.63439 -0.74313 -0.00642 0.66912 -0.63438 0.00588 0.77300 -0.58777 -0.00735 0.80900 -0.47139 0.00669 0.88190 -0.40672 -0.00803 0.91352 -0.29028 0.00722 0.95692 -0.20790 -0.00843 0.97811 -0.09801 0.00749 0.99516 0.00000 -0.00856 0.99996 0.09801 0.00749 0.99516 0.20790 -0.00843 0.97811 0.00350 0.99986 -0.01649 0.00351 0.99986 0.01650 0.00145 0.99985 -0.01703 0.00133 0.99985 0.01702 0.00000 0.99986 -0.01683 -0.00000 0.99986 0.01683 -0.00153 0.99985 -0.01702 -0.00350 0.99986 -0.01648 -0.00152 0.99985 0.01701 -0.00432 0.99985 0.01649 -0.00350 0.99986 0.01649 -0.00446 0.99985 -0.01647 -0.00688 0.99986 -0.01545 -0.00689 0.99986 0.01548 -0.00698 0.99986 0.01547 -0.00723 0.99986 -0.01540 -0.01001 0.99985 -0.01378 -0.01006 0.99985 0.01384 0.20790 0.00843 0.97811 0.09801 -0.00749 0.99516 -0.00000 0.00856 0.99996 -0.09801 -0.00749 0.99516 -0.20791 0.00843 0.97811 -0.29028 -0.00722 0.95692 -0.40672 0.00803 0.91352 -0.47139 -0.00669 0.88190 -0.58777 0.00735 0.80900 -0.63438 -0.00588 0.77300 -0.74313 0.00642 0.66912 -0.77300 -0.00481 0.63439 -0.86601 0.00521 0.49999 -0.88192 -0.00348 0.47139 -0.95105 0.00374 0.30902 -0.95694 -0.00187 0.29028 -0.99452 0.00200 0.10453 -0.99518 -0.00000 0.09802 -0.99452 0.00000 -0.10453 -0.99518 0.00214 -0.09802 -0.95694 -0.00187 -0.29029 -0.95105 0.00374 -0.30902 -0.88192 -0.00348 -0.47139 -0.86601 0.00521 -0.49999 -0.77300 -0.00481 -0.63439 -0.74313 0.00642 -0.66912 -0.63438 -0.00589 -0.77300 -0.58777 0.00735 -0.80900 -0.47139 -0.00669 -0.88190 -0.40672 0.00803 -0.91352 -0.29027 -0.00722 -0.95692 -0.20791 0.00842 -0.97811 -0.09802 -0.00749 -0.99516 0.00000 0.00856 -0.99996 0.09802 -0.00749 -0.99516 0.20791 0.00842 -0.97811 -0.00428 -0.99987 -0.01582 -0.00432 -0.99985 0.01649 -0.00689 -0.99986 0.01548 -0.00733 -0.99984 -0.01645 -0.00350 -0.99986 0.01649 -0.00149 -0.99986 -0.01650 -0.00368 -0.99984 -0.01729 -0.00152 -0.99985 0.01701 0.00000 -0.99986 -0.01683 0.00133 -0.99985 0.01702 0.00145 -0.99985 -0.01703 0.00350 -0.99986 -0.01649 -0.29843 0.80194 -0.51753 -0.45546 0.76061 -0.46263 -0.48572 0.74811 -0.45212 -0.52648 0.72710 -0.44062 -0.70516 0.61922 -0.34541 -0.68729 0.63389 -0.35471 -0.79346 0.54430 -0.27233 -0.85010 0.47351 -0.23050 -0.92476 0.35495 -0.13725 -0.88546 0.42818 -0.18060 -0.97510 0.21969 -0.03025 -0.99355 0.10933 0.02998 -0.99487 0.00529 0.10098 -0.44914 0.56393 -0.69301 -0.48712 0.33907 -0.80483 -0.46872 0.11111 -0.87633 -0.48781 0.55012 -0.67779 -0.56989 0.12661 -0.81191 -0.50827 0.32733 -0.79656 -0.52244 0.54094 -0.65912 -0.71199 0.41889 -0.56357 -0.76447 0.38273 -0.51875 -0.75314 0.23466 -0.61459 -0.75445 0.07598 -0.65194 -0.76357 0.23187 -0.60266 -0.80030 0.34611 -0.48961 -0.77744 0.07742 -0.62418 -0.89245 0.25985 -0.36881 -0.88324 0.13720 -0.44841 -0.89344 0.04446 -0.44698 -0.89802 0.12735 -0.42112 -0.93206 0.19411 -0.30591 -0.92669 0.04989 -0.37250 -0.96319 0.02410 -0.26775 -0.97120 0.12167 -0.20487 -0.98112 0.08870 -0.17186 -0.57327 0.00000 -0.81936 -0.58559 0.00572 -0.81059 -0.78071 -0.00192 -0.62489 -0.80115 0.00518 -0.59844 -0.92784 -0.00355 -0.37297 -0.93332 0.00059 -0.35905 -0.54334 -0.12355 -0.83037 -0.55062 -0.32950 -0.76697 -0.56899 -0.31769 -0.75850 -0.58230 -0.47952 -0.65650 -0.47157 -0.55221 -0.68752 -0.57960 -0.12850 -0.80470 -0.65890 -0.45141 -0.60174 -0.74087 -0.07739 -0.66717 -0.75046 -0.23110 -0.61920 -0.73276 -0.24796 -0.63370 -0.74409 -0.40715 -0.52968 -0.79988 -0.07795 -0.59507 -0.83756 -0.30814 -0.45116 -0.93299 -0.02422 -0.35908 -0.92289 -0.03443 -0.38352 -0.92643 -0.09817 -0.36343 -0.91099 -0.12348 -0.39350 -0.91770 -0.21960 -0.33106 -0.92934 -0.19612 -0.31285 -0.99452 -0.01997 -0.10259 -0.47080 -0.75241 -0.46069 -0.45668 -0.75918 -0.46378 -0.65213 -0.65623 -0.37958 -0.61916 -0.68060 -0.39169 -0.82908 -0.50451 -0.24104 -0.85407 -0.47034 -0.22212 -0.92231 -0.36337 -0.13159 -0.99192 -0.12653 0.00876 -0.98384 -0.17818 -0.01749 -0.99580 -0.01898 0.08960 0.25602 -0.67271 0.69420 0.10951 -0.95426 0.27821 -0.24299 -0.96070 -0.13420 0.02366 -0.93898 0.34315 0.41629 -0.24307 0.87614 0.25610 -0.67271 0.69417 -0.36230 -0.93025 -0.05802 0.36996 -0.25534 0.89327 0.10702 -0.62868 0.77027 -0.13311 -0.91757 0.37463 -0.52306 -0.85223 -0.01049 0.03553 -0.62578 0.77919 0.17265 -0.21866 0.96041 -0.49931 -0.86639 -0.00769 -0.29615 -0.83056 0.47167 0.11936 -0.22311 0.96746 -0.12565 -0.56539 0.81519 -0.00082 -0.19219 0.98136 -0.17977 -0.52640 0.83101 -0.39503 -0.78686 0.47414 -0.77611 -0.62215 0.10282 -0.67472 -0.72940 0.11282 -0.51628 -0.68662 0.51187 -0.15957 -0.18279 0.97011 -0.24409 -0.14826 0.95835 -0.34379 -0.44941 0.82452 -0.55399 -0.66213 0.50466 -0.36494 -0.43114 0.82519 -0.42580 -0.11643 0.89729 -0.49952 -0.34354 0.79527 -0.52836 -0.31199 0.78962 -0.69334 -0.51702 0.50197 -0.92543 -0.28426 0.25055 -0.79022 -0.55988 0.24917 -0.43711 -0.11689 0.89178 -0.84444 -0.13410 0.51859 -0.80441 -0.23405 0.54603 -0.69684 -0.15924 0.69933 -0.66097 -0.04772 0.74889 -0.66379 -0.04752 0.74641 -0.73766 -0.09046 0.66908 0.38198 -0.00000 0.92417 0.39651 0.00076 0.91803 0.12271 -0.00007 0.99244 0.13374 0.00042 0.99102 -0.16191 -0.00126 0.98680 -0.14660 -0.00049 0.98920 -0.43971 0.00043 0.89814 -0.42046 0.00134 0.90731 -0.66472 -0.00107 0.74709 -0.64854 -0.00010 0.76118 -0.20688 0.96904 -0.13476 -0.21729 0.96682 -0.13436 0.02220 0.93724 0.34797 0.18340 0.66030 0.72826 0.32370 0.26370 0.90867 -0.04563 0.93478 0.35228 0.15402 0.64342 0.74986 0.38427 0.24588 0.88988 -0.42875 0.90238 -0.04338 0.13021 0.21703 0.96744 -0.23944 0.86631 0.43837 -0.43986 0.89707 -0.04216 0.12412 0.21418 0.96888 -0.00829 0.60805 0.79386 -0.26215 0.85896 0.43984 -0.03777 0.58651 0.80906 -0.58919 0.80734 0.03251 -0.40605 0.76730 0.49635 -0.60111 0.79844 0.03407 -0.27437 0.47832 0.83423 -0.47610 0.72411 0.49900 -0.76444 0.63397 0.11712 -0.23688 0.18363 0.95403 -0.32759 0.46151 0.82444 -0.76955 0.62765 0.11774 -0.62231 0.56695 0.53971 -0.14442 0.16129 0.97628 -0.41513 0.39049 0.82170 -0.58425 0.59872 0.54789 -0.80418 0.57658 0.14438 -0.41713 0.12663 0.89998 -0.57940 0.81267 0.06214 -0.90601 0.33872 0.25379 -0.58005 0.05536 0.81270 -0.64048 0.24568 0.72761 -0.64772 0.05054 0.76020 -0.53358 0.65124 0.53960 -0.73246 0.10072 0.67332 -0.81922 0.28667 0.49668 -0.69807 0.02783 0.71549 -0.72391 0.10738 0.68148 -0.31865 -0.94762 -0.02173 -0.06834 -0.99280 -0.09833 -0.18893 -0.98183 -0.01773 0.18189 -0.98318 0.01629 0.42299 -0.90569 -0.02856 0.63070 -0.77024 0.09462 0.80590 -0.58653 0.08063 0.27517 -0.96051 0.04134 0.98733 -0.12632 0.09608 0.92845 -0.37112 0.01598 0.97574 -0.16150 0.14783 0.72060 -0.68471 0.10910 -0.19528 -0.98025 -0.03112 0.30206 -0.95068 0.07043 -0.17277 -0.98376 -0.04857 -0.18246 -0.98214 -0.04587 0.93546 -0.27020 0.22784 0.26518 -0.95786 0.11037 0.27646 -0.95469 0.11015 0.67463 -0.68266 0.28079 0.90310 -0.20439 0.37768 0.91614 -0.16395 0.36580 0.67176 -0.68543 0.28093 0.83344 -0.27693 0.47821 0.27276 -0.94729 0.16805 -0.15712 -0.98294 -0.09563 -0.16577 -0.98153 -0.09545 0.22350 -0.96046 0.16605 0.58707 -0.68199 0.43616 0.58285 -0.68612 0.43533 0.78883 -0.17497 0.58918 0.77010 -0.21665 0.60001 -0.16041 -0.97986 -0.11895 -0.14122 -0.98157 -0.12873 -0.13494 -0.98273 -0.12662 0.23734 -0.94703 0.21635 0.66915 -0.26852 0.69292 0.46707 -0.68165 0.56321 0.45988 -0.68920 0.55992 0.17772 -0.95945 0.21879 0.62189 -0.15765 0.76707 -0.12771 -0.98023 -0.15113 -0.09872 -0.98464 -0.14399 0.18438 -0.95175 0.24532 0.56828 -0.24866 0.78436 -0.09765 -0.98290 -0.15615 -0.33794 0.94076 -0.02775 -0.07269 0.99529 -0.06413 0.30268 0.95198 0.04598 0.18138 0.98333 -0.01276 0.42303 0.90386 0.06391 -0.17534 0.98415 -0.02653 0.62732 0.77298 0.09476 0.80600 0.58643 0.08040 0.98750 0.12448 0.09665 0.92894 0.36986 0.01630 0.71988 0.68544 0.10932 0.97551 0.16260 0.14814 0.93534 0.27064 0.22781 -0.19594 0.97941 -0.04864 0.28073 0.95265 0.11685 0.67397 0.68342 0.28054 0.90780 0.17821 0.37965 0.90756 0.21216 0.36238 0.67114 0.68614 0.28068 0.28346 0.95155 0.11918 -0.17073 0.98270 -0.07179 -0.16712 0.98356 -0.06843 0.83334 0.27735 0.47815 -0.17478 0.97917 -0.10335 0.58650 0.68275 0.43575 0.24297 0.95309 0.18052 0.78346 0.20920 0.58517 0.77899 0.15747 0.60694 0.58231 0.68684 0.43493 -0.14277 0.98390 -0.10752 -0.14957 0.98135 -0.12078 0.24668 0.95112 0.18578 0.66906 0.26896 0.69283 -0.13505 0.98001 -0.14608 0.45976 0.69678 0.55056 0.46368 0.68205 0.56552 0.19541 0.95351 0.22943 0.62196 0.15862 0.76681 -0.10524 0.98512 -0.13587 0.20648 0.94390 0.25772 0.56750 0.25380 0.78328 -0.10671 0.98194 -0.15621 -0.60667 0.79123 -0.07686 -0.56817 0.81074 -0.14105 -0.79584 0.53524 -0.28311 -0.57820 0.78954 -0.20569 -0.80107 0.51949 -0.29735 -0.91713 0.20731 -0.34044 -0.91737 0.23627 -0.32032 -0.54765 0.80610 -0.22425 -0.88170 0.16993 -0.44015 -0.51831 0.79181 -0.32310 -0.51464 0.80158 -0.30432 -0.71413 0.54022 -0.44517 -0.71686 0.51486 -0.47014 -0.81520 0.22276 -0.53463 -0.81227 0.21056 -0.54395 -0.45559 0.81060 -0.36791 -0.74244 0.17211 -0.64743 -0.60027 0.54466 -0.58568 -0.43952 0.78926 -0.42883 -0.67393 0.23158 -0.70157 -0.65209 0.19089 -0.73372 -0.59561 0.51069 -0.62004 -0.40107 0.80680 -0.43384 -0.33502 0.79280 -0.50914 -0.33830 0.80043 -0.49484 -0.45934 0.54863 -0.69858 -0.55491 0.18086 -0.81201 -0.47588 0.34278 -0.80996 -0.46281 0.55781 -0.68895 -0.51130 0.22340 -0.82986 -0.45217 0.11213 -0.88486 -0.88620 -0.44851 -0.11617 -0.78284 -0.60273 -0.15456 -0.84468 -0.52445 -0.10705 -0.96417 -0.23323 -0.12640 -0.66324 -0.74368 -0.08398 -0.51400 -0.84905 -0.12211 -0.64066 -0.76661 -0.04310 -0.59317 -0.79951 -0.09452 -0.57276 -0.80697 -0.14400 -0.57500 -0.79218 -0.20454 -0.54901 -0.80696 -0.21773 -0.79566 -0.53556 -0.28303 -0.80089 -0.51981 -0.29728 -0.91311 -0.22662 -0.33893 -0.88166 -0.17013 -0.44014 -0.71397 -0.54053 -0.44505 -0.50961 -0.79962 -0.31766 -0.54216 -0.78013 -0.31218 -0.71671 -0.51519 -0.47002 -0.81695 -0.21343 -0.53576 -0.80918 -0.22706 -0.54191 -0.47347 -0.80782 -0.35108 -0.74240 -0.17231 -0.64742 -0.43291 -0.79637 -0.42235 -0.45040 -0.78645 -0.42265 -0.60015 -0.54497 -0.58551 -0.59549 -0.51101 -0.61988 -0.67968 -0.19350 -0.70752 -0.64206 -0.25654 -0.72245 -0.37976 -0.80859 -0.44940 -0.33611 -0.79429 -0.50610 -0.32117 -0.80258 -0.50271 -0.45843 -0.54912 -0.69879 -0.55489 -0.18107 -0.81198 -0.50368 -0.23068 -0.83252 -0.45098 -0.13321 -0.88254 -0.99641 0.00112 -0.08466 -0.99729 0.01576 -0.07190 -0.99637 -0.00893 -0.08466 -0.99602 -0.01019 -0.08855 -0.99255 -0.00087 -0.12183 -0.98077 -0.00810 -0.19502 -0.96656 -0.00561 -0.25638 -0.98287 0.01723 -0.18351 -0.97605 -0.00303 -0.21754 -0.90737 0.00000 -0.42034 -0.82060 0.00000 -0.57150 -0.82060 0.00000 -0.57150 -0.70890 0.00000 -0.70531 -0.70890 0.00000 -0.70531 -0.57566 0.00000 -0.81769 -0.57566 0.00000 -0.81769 -0.42492 0.00000 -0.90523 -0.42492 0.00000 -0.90523 -0.26128 0.00000 -0.96526 -0.26128 0.00000 -0.96526 -0.08971 0.00000 -0.99597 -0.08971 0.00000 -0.99597 0.08460 0.00000 -0.99642 0.08460 0.00000 -0.99642 0.07779 -0.00000 0.99697 0.07779 -0.00000 0.99697 -0.08916 -0.00000 0.99602 -0.08916 -0.00000 0.99602 -0.25363 0.00000 0.96730 -0.25363 -0.00000 0.96730 -0.41102 -0.00000 0.91162 -0.41102 -0.00000 0.91162 -0.55695 -0.00000 0.83054 -0.55696 -0.00000 0.83054 -0.68736 -0.00000 0.72632 -0.68736 -0.00000 0.72632 -0.79835 0.02528 0.60167 -0.77337 0.00354 0.63395 -0.75022 -0.00000 0.66119 -0.79945 -0.02809 0.60007 -0.77570 -0.00524 0.63108 -0.74247 0.00028 0.66988 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.92871 -0.00000 0.37082 0.86737 -0.00000 0.49767 0.86737 -0.00000 0.49767 0.78883 -0.00000 0.61461 0.78883 -0.00000 0.61461 0.69466 -0.00000 0.71934 0.69466 -0.00000 0.71934 0.58671 -0.00000 0.80980 0.58671 -0.00000 0.80980 -0.89471 0.00001 -0.44664 -0.89471 -0.00001 -0.44665 -0.83090 0.00002 -0.55642 -0.83089 -0.00002 -0.55644 -0.75368 0.00002 -0.65724 -0.75367 -0.00002 -0.65725 -0.66430 0.00001 -0.74746 -0.66430 -0.00001 -0.74747 -0.56422 0.00001 -0.82563 -0.56421 -0.00001 -0.82563 -0.45503 0.00000 -0.89047 -0.45503 0.00000 -0.89047 -0.95313 0.27559 -0.12490 -0.97949 0.08775 -0.18137 -0.96015 0.26855 -0.07742 -0.96329 0.17434 -0.20417 -0.96325 -0.17453 -0.20417 -0.92437 -0.20337 -0.32278 0.94185 -0.00006 -0.33603 0.94183 0.00006 -0.33608 0.88974 -0.00006 -0.45646 0.88972 0.00006 -0.45651 0.82232 -0.00005 -0.56902 0.82229 0.00006 -0.56907 0.74075 -0.00006 -0.67178 0.74070 0.00008 -0.67184 0.64642 -0.00008 -0.76298 0.64636 0.00007 -0.76303 0.54094 -0.00007 -0.84106 0.54089 0.00004 -0.84109 0.42613 -0.00004 -0.90466 0.42611 0.00000 -0.90467 0.30163 -0.00001 -0.95343 0.30399 -0.00527 -0.95266 -0.93888 0.00001 0.34425 -0.93884 -0.00001 0.34435 -0.88525 0.00002 0.46512 -0.88518 -0.00002 0.46526 -0.81604 0.00002 0.57799 -0.81592 -0.00003 0.57816 -0.73278 0.00003 0.68046 -0.73263 -0.00002 0.68063 -0.64110 0.00002 0.76745 -0.64098 -0.00001 0.76756 -0.54819 0.00001 0.83635 -0.54884 -0.00014 0.83592 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.24257 -0.00000 0.97013 0.24257 -0.00000 0.97013 0.40057 -0.00000 0.91626 0.40058 0.00000 0.91626 0.54742 0.00000 0.83686 0.54742 0.00000 0.83686 0.67900 0.00000 0.73414 0.67900 -0.00000 0.73414 0.79165 -0.00000 0.61097 0.79165 -0.00000 0.61097 0.88225 -0.00000 0.47078 0.88225 -0.00000 0.47078 0.91370 -0.00000 0.40640 0.93759 -0.00672 0.34768 0.92759 0.00091 0.37360 0.94072 0.00403 0.33917 0.95201 0.03380 0.30420 0.96359 -0.05853 -0.26089 0.96386 0.05350 -0.26097 0.94569 -0.02266 -0.32427 0.92463 -0.04605 -0.37807 0.89371 0.15883 -0.41958 0.90505 0.01824 -0.42491 0.88798 0.00184 -0.45989 0.88884 -0.00173 -0.45821 0.80446 -0.00273 -0.59399 0.78816 -0.00081 -0.61547 0.82555 -0.00953 -0.56425 0.81766 -0.00267 -0.57570 0.83796 0.00144 -0.54573 0.77615 0.00000 -0.63054 0.79321 0.00197 -0.60894 0.81763 0.00816 -0.57568 0.70527 -0.00000 -0.70894 0.70527 -0.00000 -0.70894 0.57146 -0.00000 -0.82063 0.57145 0.00000 -0.82064 0.42028 0.00000 -0.90740 0.42028 0.00000 -0.90739 0.25633 0.00000 -0.96659 0.25633 0.00000 -0.96659 0.92086 -0.35182 -0.16806 0.98805 -0.13279 -0.07831 0.96310 -0.25221 -0.09395 0.55997 -0.81528 -0.14752 0.96392 -0.16753 -0.20687 0.57062 -0.79919 -0.18891 0.80059 -0.53741 -0.26504 0.80832 -0.51650 -0.28256 0.92052 -0.21165 -0.32842 0.92062 -0.22114 -0.32182 0.53512 -0.81793 -0.21126 0.87674 -0.17035 -0.44979 0.72731 -0.54379 -0.41870 0.53027 -0.78663 -0.31627 0.52543 -0.79526 -0.30248 0.82817 -0.23633 -0.50822 0.73286 -0.51055 -0.44973 0.80912 -0.17844 -0.55989 0.47111 -0.80823 -0.35329 0.45570 -0.78314 -0.42312 0.45228 -0.79679 -0.40070 0.62550 -0.54923 -0.55416 0.71779 -0.24703 -0.65096 0.70751 -0.19739 -0.67858 0.62275 -0.50540 -0.59728 0.38937 -0.80750 -0.44309 0.63743 -0.16613 -0.75238 0.36311 -0.78476 -0.50229 0.36445 -0.79417 -0.48628 0.49937 -0.55376 -0.66631 0.30281 -0.80734 -0.50648 0.53003 -0.19982 -0.82410 0.54348 -0.22777 -0.80793 0.48302 -0.50109 -0.71805 0.41954 -0.17523 -0.89066 0.26108 -0.79358 -0.54961 0.27943 -0.81607 -0.50592 0.29119 -0.71113 -0.63993 0.35931 -0.55539 -0.74996 0.36493 -0.23060 -0.90203 0.33497 -0.49119 -0.80407 0.34295 -0.31685 -0.88430 0.30001 -0.09841 -0.94885 0.62652 0.77786 -0.04904 0.51423 0.85038 -0.11147 0.66372 0.74398 -0.07728 0.84714 0.52213 -0.09865 0.78461 0.60341 -0.14241 0.88724 0.44844 -0.10816 0.96334 0.24121 -0.11743 0.57557 0.80940 -0.11659 0.96304 0.16869 -0.21000 0.80089 0.53729 -0.26436 0.57696 0.79404 -0.19135 0.57814 0.79331 -0.19083 0.91781 0.22441 -0.32751 0.92253 0.21302 -0.32182 0.80874 0.51608 -0.28213 0.53139 0.80923 -0.25054 0.87672 0.17034 -0.44984 0.72768 0.54363 -0.41826 0.50348 0.80399 -0.31640 0.53307 0.78864 -0.30640 0.82842 0.23633 -0.50781 0.73327 0.51016 -0.44949 0.80915 0.17803 -0.55998 0.46106 0.80464 -0.37414 0.46060 0.78844 -0.40769 0.62585 0.54904 -0.55396 0.40986 0.80854 -0.42222 0.62310 0.50504 -0.59722 0.72654 0.19459 -0.65899 0.70254 0.23030 -0.67335 0.63740 0.16593 -0.75245 0.37795 0.78665 -0.48819 0.36371 0.79527 -0.48504 0.49963 0.55355 -0.66630 0.31162 0.80775 -0.50043 0.48326 0.50075 -0.71813 0.52523 0.23894 -0.81673 0.54666 0.20310 -0.81235 0.41953 0.17511 -0.89069 0.35011 0.55871 -0.75184 0.36262 0.23283 -0.90238 0.30210 0.11146 -0.94674 0.06650 0.99566 -0.06516 0.32275 0.94614 -0.02538 -0.92863 0.37061 0.01700 -0.98830 0.12644 0.08529 -0.97655 0.17783 0.12133 -0.72577 0.68200 0.09023 -0.80640 0.58798 0.06324 -0.63167 0.77117 0.07935 -0.30573 0.95134 0.03855 -0.42260 0.90611 0.01929 -0.17883 0.98361 0.02317 0.17655 0.98403 -0.02274 0.19541 0.97992 -0.03958 -0.93709 0.27982 0.20872 -0.68650 0.68817 0.23485 -0.91286 0.23363 0.33482 -0.92958 0.18642 0.31801 -0.28472 0.95347 0.09912 -0.69326 0.67908 0.24134 -0.29299 0.95030 0.10531 0.18065 0.98172 -0.05991 0.16914 0.98372 -0.06079 0.18218 0.97951 -0.08589 -0.85436 0.26155 0.44906 -0.62159 0.69118 0.36864 -0.84706 0.17357 0.50235 -0.25513 0.95449 0.15447 -0.63028 0.67611 0.38160 0.15533 0.98303 -0.09761 0.15505 0.98308 -0.09755 -0.26621 0.94925 0.16750 -0.78398 0.27707 0.55553 0.15646 0.97949 -0.12696 -0.71551 0.21489 0.66473 -0.72337 0.19685 0.66180 -0.53117 0.69405 0.48596 -0.21531 0.95540 0.20212 -0.53911 0.67323 0.50608 -0.22613 0.94825 0.22289 0.12238 0.98444 -0.12606 0.13364 0.98224 -0.13172 -0.61744 0.26850 0.73937 0.12196 0.97995 -0.15753 -0.52822 0.26640 0.80623 -0.57997 0.18211 0.79402 -0.41981 0.69669 0.58171 -0.41718 0.70927 0.56824 -0.15676 0.95722 0.24322 0.09262 0.98453 -0.14874 -0.05901 0.99778 -0.03079 0.16281 0.97811 0.12963 0.12607 0.95961 -0.25151 0.19599 -0.98043 -0.01837 -0.96452 -0.25067 0.08283 -0.97660 -0.17782 0.12096 -0.80479 -0.58513 0.09969 -0.63328 -0.77302 0.03754 -0.72616 -0.68147 0.09107 0.21458 -0.97528 -0.05270 -0.42311 -0.90452 0.05308 -0.18723 -0.98222 -0.01389 -0.36096 -0.93046 0.06285 0.17465 -0.98431 -0.02497 -0.93721 -0.27943 0.20868 -0.68737 -0.68736 0.23467 -0.92600 -0.16505 0.33953 -0.92133 -0.22851 0.31455 -0.28110 -0.95470 0.09764 -0.69403 -0.67839 0.24106 0.20738 -0.97456 -0.08504 -0.85461 -0.26080 0.44902 0.16380 -0.98310 -0.08173 -0.32234 -0.93559 0.14413 0.17112 -0.97995 -0.10206 -0.62240 -0.69040 0.36874 -0.84740 -0.17285 0.50204 -0.24032 -0.95975 0.14533 -0.63104 -0.67540 0.38160 -0.78419 -0.27666 0.55543 -0.26047 -0.94537 0.19603 0.14875 -0.98256 -0.11155 0.14917 -0.98242 -0.11226 0.14605 -0.97994 -0.13561 -0.53184 -0.69329 0.48630 -0.71932 -0.19083 0.66796 -0.72141 -0.21084 0.65963 -0.20511 -0.95964 0.19242 -0.53977 -0.67249 0.50636 -0.21885 -0.94617 0.23847 0.12617 -0.98156 -0.14358 0.12393 -0.98306 -0.13504 -0.61764 -0.26808 0.73936 0.11562 -0.98033 -0.15994 -0.41812 -0.69623 0.58347 -0.54545 -0.11098 0.83077 -0.56890 -0.25471 0.78197 -0.14761 -0.96138 0.23227 -0.41545 -0.70916 0.56965 -0.13028 -0.97712 0.16813 0.12770 -0.96854 -0.21358 0.11576 -0.98031 -0.15997 0.11951 -0.96126 -0.24840 0.86759 -0.00004 0.49729 0.86005 -0.00067 0.51021 0.69871 0.00033 0.71540 0.68315 -0.00054 0.73028 0.45680 0.00096 0.88957 0.44236 0.00026 0.89684 0.18885 -0.00058 0.98201 0.19784 -0.00019 0.98023 -0.07915 -0.00022 0.99686 -0.08595 -0.00053 0.99630 -0.36010 0.00041 0.93291 -0.37498 -0.00025 0.92703 0.86482 0.05323 0.49925 0.89424 0.04308 0.44551 0.91976 0.13689 0.36782 0.85166 0.07061 0.51932 0.85668 0.23985 0.45669 0.74796 0.10340 0.65564 0.79318 0.34142 0.50427 0.67621 0.14507 0.72228 0.90664 0.39515 0.14784 0.54784 0.16722 0.81970 0.61468 0.48582 0.62140 0.76377 0.62501 0.16126 0.69118 0.44984 0.56560 0.43262 0.21045 0.87667 0.42687 0.61530 0.66271 0.34421 0.21590 0.91373 0.19110 0.25623 0.94754 0.74895 0.64085 0.16846 0.46141 0.60552 0.64842 0.55087 0.81731 0.16897 0.14403 0.25363 0.95652 0.23745 0.69961 0.67392 -0.06179 0.28381 0.95689 0.51464 0.83834 0.17982 0.30991 0.93560 0.16913 0.21181 0.70288 0.67904 0.02029 0.75864 0.65120 -0.08136 0.28235 0.95585 -0.10996 0.28736 0.95149 0.35288 0.92239 0.15705 -0.11065 0.75626 0.64485 -0.34752 0.28060 0.89470 0.18518 0.96802 0.16923 -0.35957 0.28417 0.88879 -0.10909 0.75662 0.64469 0.04733 0.98757 0.14990 0.91677 0.37563 -0.13579 0.76266 0.61462 -0.20148 0.77416 0.59853 -0.20600 0.53176 0.81577 -0.22750 0.57893 0.77639 -0.24914 0.36133 0.90335 -0.23110 0.44603 0.85471 -0.26558 0.19295 0.94965 -0.24683 0.25813 0.92732 -0.27101 0.95845 0.07640 -0.27484 0.96167 0.06620 -0.26611 0.93288 0.02087 -0.35958 0.90762 0.09845 -0.40808 0.87723 0.15437 -0.45457 0.91474 0.23838 -0.32622 0.88053 0.01263 -0.47382 0.88988 0.28746 -0.35422 0.87002 0.03612 -0.49170 0.84090 -0.00101 -0.54120 0.75048 0.51149 -0.41852 0.75650 0.35756 -0.54760 0.73658 0.20873 -0.64334 0.74511 0.36872 -0.55575 0.78441 0.45895 -0.41721 0.72747 0.22157 -0.64938 0.69223 0.12864 -0.71011 0.66133 0.02956 -0.74951 0.70152 0.02967 -0.71203 0.71199 0.10709 -0.69398 0.58847 0.34393 -0.73172 0.59922 0.52419 -0.60512 0.59434 0.52732 -0.60720 0.63549 0.62397 -0.45477 0.55202 0.67988 -0.48274 0.50514 0.23415 -0.83067 0.55892 0.37367 -0.74026 0.50506 0.09286 -0.85807 0.53614 0.07615 -0.84069 0.56324 0.18628 -0.80502 0.42201 0.76248 -0.49044 0.45764 0.44194 -0.77153 0.42960 0.64938 -0.62750 0.49092 0.71323 -0.50030 0.45921 0.63909 -0.61700 0.19847 0.33790 -0.92002 0.31436 0.55529 -0.76996 0.52807 0.68920 -0.49613 0.49723 0.61593 -0.61106 0.33651 0.10481 -0.93583 0.05364 0.19518 -0.97930 0.22468 0.82174 -0.52369 0.66150 -0.00244 -0.74994 0.66936 -0.00439 -0.74293 0.50732 -0.00029 -0.86175 0.53404 -0.00848 -0.84541 0.33887 0.00575 -0.94082 0.38850 -0.00667 -0.92143 0.98063 0.06166 -0.18593 0.97165 -0.08208 -0.22171 0.93339 -0.02097 -0.35826 0.90822 -0.10105 -0.40612 0.86034 -0.19098 -0.47259 0.90628 -0.30599 -0.29159 0.88367 -0.00565 -0.46808 0.51136 -0.73088 -0.45202 0.85364 -0.06651 -0.51659 0.81975 -0.01450 -0.57254 0.77556 -0.16320 -0.60981 0.82147 -0.26460 -0.50515 0.75267 -0.51166 -0.41435 0.79853 -0.43998 -0.41081 0.75471 -0.34177 -0.56001 0.78536 -0.05049 -0.61697 0.78371 -0.00159 -0.62112 0.69609 -0.11307 -0.70899 0.73667 -0.21935 -0.63969 0.66919 -0.04023 -0.74200 0.59143 -0.66370 -0.45795 0.61722 -0.49367 -0.61265 0.65964 -0.59015 -0.46540 0.63442 -0.04473 -0.77169 0.65752 -0.14718 -0.73892 0.62728 -0.48184 -0.61185 0.57209 -0.36087 -0.73653 0.53978 -0.20746 -0.81584 0.59136 -0.33954 -0.73144 0.53179 -0.08056 -0.84303 0.47428 -0.59486 -0.64900 0.52137 -0.70758 -0.47697 0.33173 -0.51922 -0.78763 0.40674 -0.65063 -0.64128 0.35598 -0.78086 -0.51336 0.43567 -0.43150 -0.78994 0.34217 -0.32854 -0.88033 0.37782 -0.29848 -0.87645 0.33477 -0.10404 -0.93654 0.38808 -0.08436 -0.91776 0.92358 -0.35766 -0.13810 0.71913 -0.66669 -0.19588 0.77454 -0.59541 -0.21350 0.60812 -0.75847 -0.23432 0.61697 -0.75020 -0.23781 0.36141 -0.89887 -0.24782 0.38620 -0.88561 -0.25795 0.20676 -0.94041 -0.26995 0.89427 -0.03537 0.44612 0.95299 -0.04742 0.29926 0.92124 -0.15104 0.35848 0.86617 -0.05843 0.49633 0.82569 -0.31028 0.47112 0.78480 -0.08791 0.61348 0.69262 -0.13759 0.70806 0.72992 -0.39709 0.55635 0.69118 -0.13805 0.70938 0.66984 -0.44980 0.59075 0.60896 -0.14973 0.77894 0.46632 -0.19921 0.86189 0.92280 -0.37521 0.08751 0.61946 -0.77197 0.14259 0.79731 -0.58492 0.14886 0.72790 -0.41384 0.54672 0.44603 -0.20223 0.87187 0.52025 -0.56828 0.63749 0.42858 -0.20872 0.87906 0.60685 -0.76770 0.20587 0.52011 -0.56833 0.63756 0.70465 -0.69221 0.15593 0.18355 -0.24618 0.95169 0.20724 -0.24957 0.94592 0.29503 -0.66866 0.68253 0.39902 -0.65383 0.64288 0.48397 -0.85199 0.19974 0.60082 -0.78524 0.14972 -0.07555 -0.28563 0.95536 0.25210 -0.94931 0.18777 0.15490 -0.71443 0.68235 -0.00465 -0.76317 0.64619 -0.10740 -0.27806 0.95454 0.35331 -0.92324 0.15096 -0.13451 -0.75583 0.64080 0.03589 -0.98353 0.17717 0.20848 -0.97041 0.12180 -0.34502 -0.29404 0.89135 -0.16838 -0.75905 0.62888 -0.42627 -0.26736 0.86418 0.01280 -0.99985 -0.01152 0.00967 -0.99986 -0.01389 0.00680 -0.99987 -0.01467 0.00679 -0.99986 0.01553 0.01086 -0.99983 -0.01494 0.00689 -0.99986 -0.01547 0.00437 -0.99985 -0.01649 0.00739 -0.99983 0.01661 0.00395 -0.99987 0.01579 0.99518 0.00000 -0.09802 0.99452 0.00200 -0.10453 0.95694 -0.00187 -0.29028 0.95105 0.00374 -0.30901 0.88192 -0.00348 -0.47139 0.86601 0.00521 -0.49999 0.77300 -0.00481 -0.63439 0.74313 0.00642 -0.66912 0.63438 -0.00589 -0.77300 0.58777 0.00735 -0.80900 0.47139 -0.00669 -0.88190 0.40672 0.00803 -0.91352 0.29027 -0.00722 -0.95692 0.29027 -0.00722 0.95692 0.40672 0.00803 0.91352 0.47139 -0.00669 0.88190 0.58777 0.00735 0.80900 0.63438 -0.00588 0.77300 0.74313 0.00642 0.66912 0.77300 -0.00481 0.63439 0.86601 0.00521 0.49999 0.88192 -0.00348 0.47139 0.95105 0.00374 0.30902 0.95694 -0.00187 0.29028 0.99518 0.00214 0.09802 0.99452 -0.00000 0.10453 0.00413 0.99985 0.01652 0.99518 -0.00000 0.09802 0.99452 -0.00200 0.10453 0.95694 0.00187 0.29028 0.95105 -0.00374 0.30902 0.88192 0.00348 0.47139 0.86601 -0.00521 0.49999 0.77300 0.00481 0.63439 0.74313 -0.00642 0.66912 0.63438 0.00588 0.77300 0.58777 -0.00735 0.80900 0.47139 0.00669 0.88190 0.40672 -0.00803 0.91352 0.29027 0.00722 0.95692 -0.99369 0.00624 -0.11196 -0.99271 0.00000 -0.12054 -0.94387 -0.00535 -0.33028 -0.93496 0.01071 -0.35459 -0.84668 -0.00981 -0.53201 -0.82290 0.01472 -0.56800 -0.70704 -0.01339 -0.70704 -0.66302 0.01785 -0.74839 -0.53196 -0.01607 -0.84661 -0.46462 0.02008 -0.88528 -0.46462 0.02008 0.88528 -0.53196 -0.01607 0.84662 -0.66302 0.01785 0.74839 -0.70705 -0.01339 0.70704 -0.82290 0.01472 0.56800 -0.84668 -0.00982 0.53201 -0.93496 0.01071 0.35458 -0.94387 -0.00535 0.33027 -0.99269 0.00580 0.12054 -0.99371 -0.00000 0.11197 0.29027 0.00722 -0.95692 0.40672 -0.00803 -0.91352 0.47139 0.00669 -0.88190 0.58777 -0.00735 -0.80900 0.63438 0.00589 -0.77300 0.74313 -0.00642 -0.66912 0.77300 0.00481 -0.63439 0.86601 -0.00521 -0.49999 0.88192 0.00348 -0.47139 0.95105 -0.00374 -0.30901 0.95694 0.00187 -0.29028 0.99518 -0.00214 -0.09802 0.99452 0.00000 -0.10453 0.97704 0.00006 -0.21303 0.97771 -0.00700 -0.20983 0.99727 -0.01551 -0.07222 0.99687 -0.00117 -0.07902 -0.97608 -0.00001 0.21740 -0.97610 0.00001 0.21734 -0.99630 -0.00001 0.08600 -0.99633 0.00008 0.08562 0.26455 0.80715 -0.52776 0.34054 0.54168 -0.76851 0.35220 0.27446 -0.89478 0.07352 0.40715 -0.91040 0.00437 0.99985 -0.01649 0.00689 0.99986 -0.01547 0.00715 0.99986 -0.01543 0.01002 0.99985 -0.01379 0.00967 0.99986 -0.01389 0.01280 0.99985 -0.01152 0.01186 0.99986 -0.01192 0.01398 0.99985 -0.00984 0.01458 0.99986 -0.00841 0.01547 0.99985 -0.00726 0.01603 0.99986 -0.00521 0.01647 0.99985 -0.00446 0.01684 0.99986 -0.00177 0.01572 0.99988 0.00165 0.01506 0.99986 0.00672 0.68740 0.72228 -0.07613 0.01634 0.99987 0.00011 0.01633 0.99986 -0.00300 0.58113 0.80877 -0.09042 0.53871 0.84142 0.04248 0.27493 0.79940 -0.53420 0.28266 0.74141 -0.60862 0.01616 0.99986 0.00525 0.01502 0.99986 0.00802 0.01462 0.99986 0.00844 0.00680 0.99986 0.01556 0.00689 0.99986 0.01548 0.00933 0.99985 0.01427 0.00991 0.99986 0.01363 0.01160 0.99985 0.01254 0.01251 0.99986 0.01126 0.01352 0.99985 0.01043 0.01186 -0.99986 -0.01192 0.01398 -0.99985 -0.00984 0.01457 -0.99986 -0.00842 0.01547 -0.99985 -0.00726 0.01603 -0.99986 -0.00521 0.01647 -0.99985 -0.00446 0.01684 -0.99986 -0.00177 0.01520 -0.99987 -0.00572 0.01573 -0.99987 0.00165 0.01740 -0.99983 0.00683 0.01709 -0.99985 0.00300 0.01750 -0.99983 0.00568 0.01480 -0.99985 0.00855 0.01489 -0.99986 0.00794 0.01287 -0.99985 0.01159 0.01325 -0.99986 0.01022 0.01037 -0.99984 0.01427 0.01124 -0.99986 0.01216 0.00933 -0.99985 0.01427 0.91325 -0.39561 -0.09728 0.84105 -0.52604 -0.12613 0.78926 -0.60701 -0.09279 0.66360 -0.74401 -0.07801 0.59337 -0.79930 -0.09497 0.51613 -0.85524 -0.04663 0.99105 0.11258 -0.07178 0.95071 0.27410 -0.14499 0.01716 0.80299 -0.59575 0.03822 0.78970 -0.61230 0.07553 0.77517 -0.62722 0.03867 0.78385 -0.61975 0.94370 0.32976 0.02619 0.00000 0.19454 -0.98089 0.00000 0.35343 -0.93546 -1.00000 -0.00059 -0.00003 -1.00000 -0.00001 -0.00006 -1.00000 0.00182 0.00003 -1.00000 -0.00001 0.00011 -1.00000 -0.00116 0.00005 -0.36527 0.03145 0.93037 -0.17217 -0.03776 0.98434 0.00495 0.02519 0.99967 0.08047 -0.00910 0.99672 0.26345 0.00853 0.96464 0.32287 -0.01482 0.94633 0.48232 0.01089 0.87593 0.53692 -0.01160 0.84355 0.68298 0.00020 0.73043 0.70697 0.01756 0.70702 0.86223 0.02244 0.50602 0.84699 0.00157 0.53161 0.95795 -0.01567 0.28651 0.97465 -0.06454 0.21420 0.90187 0.03293 0.43075 0.86639 -0.03503 0.49814 0.76322 0.02282 0.64573 0.69250 -0.01974 0.72115 0.55842 0.02039 0.82931 0.48494 -0.01025 0.87449 0.26660 -0.00817 0.96377 0.32472 0.01522 0.94569 0.08066 0.00867 0.99670 0.00713 -0.02531 0.99965 -0.17237 0.03793 0.98430 -0.36502 -0.03199 0.93045 0.36527 -0.03146 0.93037 0.17216 0.03776 0.98435 -0.00495 -0.02519 0.99967 -0.08047 0.00910 0.99672 -0.26345 -0.00853 0.96464 -0.32289 0.01483 0.94632 -0.48232 -0.01087 0.87593 -0.53689 0.01160 0.84357 -0.68299 -0.00020 0.73043 -0.70698 -0.01757 0.70702 -0.86223 -0.02245 0.50601 -0.84699 -0.00157 0.53161 -0.95795 0.01566 0.28649 -0.97470 0.06523 0.21378 -0.90210 -0.03361 0.43023 -0.86636 0.03490 0.49819 -0.76326 -0.02290 0.64568 -0.69248 0.01969 0.72116 -0.55840 -0.02044 0.82932 -0.48492 0.01021 0.87450 -0.26660 0.00817 0.96377 -0.32477 -0.01524 0.94567 -0.08066 -0.00867 0.99670 -0.00713 0.02531 0.99965 0.17236 -0.03793 0.98430 0.36502 0.03199 0.93045 -0.03482 -0.36793 -0.92920 -0.20097 -0.42995 -0.88020 0.01380 -0.46884 -0.88318 -0.00681 -0.53767 -0.84313 -0.08527 -0.60194 -0.79397 0.79985 -0.39356 -0.45316 0.27119 -0.64396 -0.71538 0.07550 -0.68176 -0.72767 0.00718 -0.70281 -0.71135 0.00314 -0.64168 -0.76696 -0.00032 -0.68772 -0.72598 -0.04496 -0.74263 -0.66820 -0.00389 -0.72847 -0.68507 0.04387 -0.78368 -0.61962 0.06918 -0.77730 -0.62532 0.03512 -0.79133 -0.61038 0.01595 -0.80410 -0.59429 0.00894 -0.81231 -0.58316 -0.00000 -0.84144 -0.54036 -0.02572 -0.78358 -0.62076 -0.00610 -0.70315 -0.71101 0.00055 -0.75203 -0.65913 0.00002 -0.75715 -0.65324 -0.00661 -0.81282 -0.58248 -0.00927 -0.81847 -0.57447 -0.00547 -0.80640 -0.59134 -0.00063 -0.77545 -0.63141 0.00001 -0.83170 -0.55522 0.00844 -0.88587 -0.46385 0.04678 -0.86190 -0.50491 0.00027 -0.89631 -0.44344 -0.00428 -0.90848 -0.41790 0.00415 -0.95659 -0.29141 -0.00446 -0.97121 -0.23816 0.00433 -0.99405 -0.10883 -0.00463 -0.99875 -0.04979 0.00449 -0.99698 0.07753 -0.00478 -0.99009 0.14038 0.00463 -0.96528 0.26119 -0.00492 -0.94554 0.32546 0.00475 -0.90004 0.43578 -0.00503 -0.86673 0.49875 0.00486 -0.80354 0.59523 -0.00512 -0.75651 0.65397 0.00494 -0.67913 0.73400 -0.00520 -0.61887 0.78548 0.00501 -0.53113 0.84728 -0.00525 -0.45880 0.88852 0.00505 -0.36468 0.93112 -0.00529 -0.28210 0.95937 0.00508 -0.18556 0.98262 -0.00531 -0.09519 0.99545 0.00509 0.00000 0.99999 -0.00531 0.09519 0.99545 0.00508 0.18556 0.98262 -0.00529 0.28210 0.95937 0.00505 0.36468 0.93112 -0.00525 0.45880 0.88852 0.00501 0.53113 0.84728 -0.00520 0.61887 0.78548 0.00494 0.67913 0.73400 -0.00512 0.75651 0.65397 0.00486 0.80354 0.59523 -0.00503 0.86673 0.49875 0.00475 0.90004 0.43578 -0.00492 0.94554 0.32546 0.00463 0.96528 0.26119 -0.00478 0.99009 0.14038 0.00449 0.99698 0.07753 -0.00463 0.99875 -0.04979 0.00433 0.99405 -0.10883 -0.00446 0.97121 -0.23816 0.00415 0.95659 -0.29141 -0.00428 0.90848 -0.41790 0.00911 0.88587 -0.46385 0.00223 0.89084 -0.45432 0.00699 0.87717 -0.48014 -0.00210 0.81283 -0.58249 -0.01778 0.78442 -0.61998 -0.00873 0.80742 -0.58992 -0.00138 0.83795 -0.54575 0.00178 0.84372 -0.53678 0.00642 0.81498 -0.57945 0.00379 0.82076 -0.57125 0.00056 0.75227 -0.65886 0.00002 0.75727 -0.65311 -0.01789 0.68761 -0.72586 -0.00017 0.71789 -0.69616 -0.00596 0.70312 -0.71104 -0.02600 0.78362 -0.62069 -0.00222 0.72810 -0.68547 0.81263 0.38213 -0.44001 0.29066 0.63961 -0.71163 0.09412 0.67880 -0.72826 0.00314 0.64164 -0.76700 -0.03556 0.53734 -0.84262 -0.00425 0.56554 -0.82471 0.01379 0.46886 -0.88317 -0.09912 0.36634 -0.92519 -0.02762 0.38325 -0.92323 -0.02688 -0.18627 -0.98213 -0.14677 -0.36417 -0.91970 0.04336 -0.34955 -0.93591 -0.01380 -0.46884 -0.88318 0.03556 -0.53734 -0.84262 0.00424 -0.56554 -0.82471 -0.80318 -0.39063 -0.44979 -0.27622 -0.64286 -0.71445 -0.07857 -0.68121 -0.72786 -0.00840 -0.70209 -0.71204 -0.00314 -0.64168 -0.76696 0.01789 -0.68761 -0.72586 0.00018 -0.71792 -0.69613 0.00286 -0.72476 -0.68899 -0.03089 -0.78406 -0.61992 -0.00293 -0.82941 -0.55863 -0.34197 -0.87867 -0.33316 -0.11643 -0.81859 -0.56245 0.02600 -0.78362 -0.62069 0.00596 -0.70312 -0.71104 -0.00056 -0.75227 -0.65885 -0.00002 -0.75727 -0.65310 0.00210 -0.81283 -0.58249 0.01778 -0.78442 -0.61998 0.00873 -0.80742 -0.58992 0.00138 -0.83795 -0.54575 -0.00911 -0.88587 -0.46385 -0.00223 -0.89084 -0.45432 -0.00683 -0.87649 -0.48137 -0.00173 -0.84413 -0.53614 0.00428 -0.90848 -0.41790 -0.00415 -0.95659 -0.29141 0.00446 -0.97121 -0.23816 -0.00433 -0.99405 -0.10883 0.00463 -0.99875 -0.04979 -0.00449 -0.99698 0.07753 0.00478 -0.99009 0.14038 -0.00463 -0.96528 0.26119 0.00492 -0.94554 0.32546 -0.00475 -0.90004 0.43578 0.00503 -0.86673 0.49875 -0.00486 -0.80354 0.59523 0.00512 -0.75651 0.65396 -0.00494 -0.67913 0.73400 0.00520 -0.61887 0.78548 -0.00501 -0.53113 0.84728 0.00525 -0.45880 0.88852 -0.00506 -0.36468 0.93112 0.00529 -0.28210 0.95937 -0.00508 -0.18556 0.98262 0.00531 -0.09519 0.99545 -0.00509 0.00000 0.99999 0.00531 0.09519 0.99545 -0.00508 0.18556 0.98262 0.00529 0.28210 0.95937 -0.00506 0.36468 0.93112 0.00525 0.45880 0.88852 -0.00501 0.53113 0.84728 0.00520 0.61887 0.78548 -0.00494 0.67913 0.73400 0.00512 0.75651 0.65397 -0.00486 0.80354 0.59523 0.00503 0.86673 0.49875 -0.00475 0.90004 0.43578 0.00492 0.94554 0.32546 -0.00463 0.96528 0.26119 0.00478 0.99009 0.14038 -0.00449 0.99698 0.07753 0.00463 0.99875 -0.04979 -0.00433 0.99405 -0.10883 0.00446 0.97121 -0.23816 -0.00415 0.95659 -0.29141 0.00428 0.90848 -0.41790 -0.00843 0.88587 -0.46385 -0.04636 0.86225 -0.50436 -0.00027 0.89631 -0.44343 0.00662 0.81282 -0.58248 0.00926 0.81843 -0.57453 0.00547 0.80640 -0.59134 0.00063 0.77545 -0.63141 -0.00005 0.83149 -0.55554 -0.03999 0.78381 -0.61972 -0.07421 0.77562 -0.62682 -0.03783 0.78992 -0.61204 -0.01720 0.80299 -0.59575 -0.00952 0.81155 -0.58420 0.00002 0.84114 -0.54082 -0.00055 0.75203 -0.65913 -0.00002 0.75714 -0.65325 0.00032 0.68772 -0.72598 0.04491 0.74257 -0.66826 0.00610 0.70316 -0.71101 0.02572 0.78358 -0.62076 0.00465 0.72532 -0.68840 -0.80926 0.38520 -0.44353 -0.27998 0.64195 -0.71380 -0.00936 0.70328 -0.71086 -0.00314 0.64164 -0.76700 0.00682 0.53767 -0.84313 0.08527 0.60194 -0.79398 -0.01379 0.46886 -0.88317 0.03480 0.36793 -0.92920 0.34049 -0.94025 0.00054 0.19600 -0.98039 -0.02028 0.18490 -0.98260 -0.01730 -0.02176 -0.99976 0.00210 0.06177 -0.99809 -0.00134 -0.18694 -0.98236 -0.00396 -0.15842 -0.98737 -0.00106 -0.01721 -0.99985 0.00212 -0.30356 -0.95281 0.00157 -0.42286 -0.90620 -0.00092 -0.45111 -0.89244 -0.00618 -0.63482 -0.77264 -0.00547 -0.60572 -0.79568 -0.00139 -0.71193 -0.70225 0.00167 -0.80791 -0.58931 -0.00061 -0.82973 -0.55809 -0.00925 -0.90215 -0.43142 -0.00005 -0.96736 -0.25093 -0.03518 -0.94470 -0.32765 -0.01338 -0.97672 -0.21321 -0.02388 -0.99790 -0.06474 0.00122 -0.31846 -0.94794 -0.00016 -0.33754 -0.94130 -0.00448 -0.23083 -0.97299 0.00271 -0.06843 -0.99765 -0.00373 -0.07245 -0.99736 -0.00434 -0.00682 -0.99998 0.00064 0.09367 -0.99560 0.00174 0.18217 -0.98327 -0.00026 0.13090 -0.99137 -0.00663 0.29065 -0.95683 0.00076 0.42336 -0.90596 -0.00269 0.39087 -0.92042 -0.00720 0.52456 -0.85137 0.00084 0.63479 -0.77267 -0.00390 0.61239 -0.79052 -0.00774 0.69745 -0.71663 0.00002 0.80804 -0.58912 -0.00166 0.76504 -0.64382 -0.01435 0.84115 -0.54080 -0.00111 0.90029 -0.43528 -0.00032 0.92873 -0.37065 -0.00849 0.94712 -0.32087 -0.00117 0.98061 -0.19596 0.00033 0.99205 -0.12537 -0.01069 0.99778 -0.06666 -0.00057 0.32250 0.94657 -0.00007 0.33781 0.94121 -0.00354 0.23142 0.97285 0.00364 0.06278 0.99802 -0.00301 0.07235 0.99737 -0.00444 0.00652 0.99998 0.00045 -0.09498 0.99548 0.00148 -0.18045 0.98358 -0.00048 -0.13177 0.99126 -0.00651 -0.29289 0.95615 0.00079 -0.42264 0.90629 -0.00282 -0.39459 0.91883 -0.00665 -0.53028 0.84782 0.00102 -0.63450 0.77291 -0.00421 -0.62037 0.78428 -0.00655 -0.70591 0.70830 0.00052 -0.80765 0.58966 -0.00253 -0.77455 0.63240 -0.01191 -0.84850 0.52920 -0.00012 -0.92892 0.37028 -0.00108 -0.90617 0.42268 -0.01397 -0.97846 0.20642 0.00241 -0.99204 0.12550 -0.01058 -0.99789 0.06487 -0.00040 -0.33892 0.94081 -0.00463 -0.33691 0.94152 -0.00493 -0.19894 0.98000 0.00410 -0.06835 0.99766 0.00152 0.06944 0.99737 -0.02058 -0.05851 0.99828 -0.00412 0.18077 0.98351 -0.00444 0.15865 0.98733 -0.00218 0.02216 0.99975 0.00095 0.30613 0.95199 0.00136 0.42117 0.90698 -0.00277 0.44349 0.89626 -0.00615 0.54157 0.84065 0.00054 0.63478 0.77268 -0.00532 0.62230 0.78277 -0.00342 0.70719 0.70703 0.00066 0.80697 0.59056 -0.00668 0.78238 0.62280 -0.00177 0.85973 0.51074 0.00191 0.92938 0.36912 -0.00027 0.94263 0.33365 -0.01100 0.98192 0.18931 -0.00020 0.99213 0.12523 -0.00049 0.99682 0.07758 -0.01825 -0.50725 0.86179 -0.00470 -0.45677 0.88900 -0.03232 -0.51241 0.85867 -0.01099 -0.56287 0.82655 -0.00059 -0.64245 0.76633 0.00115 -0.66589 0.74596 -0.01147 -0.74016 0.67239 0.00690 -0.79296 0.60905 -0.01677 -0.81693 0.57673 0.00246 -0.89256 0.45091 -0.00387 -0.87127 0.48848 -0.04762 -0.94060 0.33878 0.02242 -0.95846 0.27675 -0.06901 0.45917 0.88835 -0.00006 0.51555 0.85686 -0.00157 0.57094 0.82044 -0.03009 0.51219 0.85882 -0.00908 0.64245 0.76633 0.00115 0.66591 0.74594 -0.01143 0.74015 0.67241 0.00687 0.79297 0.60904 -0.01671 0.81693 0.57673 0.00245 0.89226 0.45054 -0.02969 0.88249 0.47033 -0.00291 0.51627 -0.85643 0.00036 0.45680 -0.88900 -0.03190 0.51240 -0.85868 -0.01086 0.56287 -0.82655 -0.00059 0.64240 -0.76637 0.00114 0.66591 -0.74595 -0.01131 0.74001 -0.67256 0.00665 0.79275 -0.60932 -0.01663 0.81691 -0.57676 0.00241 0.88251 -0.47028 -0.00285 -0.45917 -0.88835 -0.00014 -0.51541 -0.85694 -0.00158 -0.57098 -0.82041 -0.03023 -0.51220 -0.85882 -0.00918 -0.64241 -0.76636 0.00115 -0.66590 -0.74596 -0.01148 -0.74008 -0.67248 0.00681 -0.79279 -0.60926 -0.01689 -0.81693 -0.57673 0.00247 -0.89211 -0.45086 -0.02945 -0.88249 -0.47032 -0.00293 -0.94061 -0.33876 0.02242 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 -0.00000 0.00000 1.00000 -0.00001 -0.00047 1.00000 0.00000 -0.00056 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 0.00000 -1.00000 -0.00000 -0.00000 -1.00000 0.00000 -0.00039 -1.00000 0.00025 0.00122 1.00000 -0.00000 -0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00004 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00047 -0.00002 1.00000 0.00000 -0.00004 1.00000 0.00042 -0.00002 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 -0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 0.00000 1.00000 0.00000 -0.00000 -0.37891 -0.18191 -0.90738 0.06951 -0.25037 -0.96565 0.06953 0.25037 -0.96565 -0.44514 0.16704 -0.87974 -0.97863 0.19743 0.05752 -0.98789 0.08957 -0.12668 -0.95846 -0.27675 -0.06899 -0.97863 -0.19744 0.05752 -0.98833 -0.09335 -0.12041 + + + + + + + + + + + + + + +

253 0 61 0 63 0 255 1 59 1 61 1 180 2 173 2 175 2 179 3 175 3 172 3 180 4 175 4 179 4 178 5 172 5 177 5 178 6 177 6 176 6 245 7 56 7 243 7 243 8 56 8 241 8 241 9 56 9 53 9 241 10 53 10 239 10 239 11 53 11 237 11 237 12 53 12 52 12 237 13 52 13 235 13 235 14 52 14 49 14 235 15 49 15 233 15 233 16 49 16 48 16 233 17 48 17 47 17 233 18 47 18 225 18 225 19 47 19 46 19 225 20 46 20 103 20 103 21 46 21 50 21 103 22 50 22 102 22 267 23 102 23 50 23 267 24 50 24 51 24 271 25 267 25 51 25 271 26 51 26 54 26 271 27 54 27 263 27 263 28 54 28 261 28 261 29 54 29 55 29 261 30 55 30 259 30 262 31 260 31 37 31 266 32 262 32 37 32 266 33 37 33 40 33 266 34 40 34 264 34 264 35 40 35 42 35 264 36 42 36 130 36 222 37 130 37 42 37 222 38 42 38 43 38 223 39 222 39 43 39 223 40 43 40 45 40 228 41 223 41 45 41 228 42 45 42 44 42 234 43 228 43 44 43 234 44 44 44 41 44 236 45 234 45 41 45 236 46 41 46 39 46 238 47 236 47 39 47 238 48 39 48 38 48 240 49 238 49 38 49 242 50 240 50 38 50 234 51 0 51 230 51 230 52 0 52 231 52 0 53 235 53 231 53 0 54 234 54 236 54 235 55 0 55 236 55 235 56 233 56 231 56 221 57 219 57 220 57 220 58 219 58 218 58 382 59 381 59 380 59 381 60 365 60 198 60 365 61 196 61 198 61 382 62 365 62 381 62 382 63 366 63 365 63 208 64 143 64 140 64 208 65 140 65 204 65 383 66 365 66 366 66 367 67 383 67 366 67 384 68 383 68 367 68 351 69 350 69 349 69 352 70 350 70 351 70 353 71 352 71 351 71 354 72 352 72 353 72 355 73 354 73 353 73 27 74 29 74 348 74 347 75 348 75 29 75 29 76 31 76 347 76 346 77 347 77 31 77 31 78 33 78 346 78 345 79 346 79 33 79 33 80 35 80 345 80 343 81 345 81 35 81 35 82 38 82 343 82 341 83 343 83 38 83 38 84 39 84 341 84 339 85 341 85 39 85 39 86 41 86 339 86 333 87 339 87 41 87 41 88 44 88 333 88 330 89 333 89 44 89 44 90 45 90 330 90 327 91 330 91 45 91 334 92 336 92 4 92 2 93 4 93 336 93 336 94 337 94 2 94 1 95 2 95 337 95 337 96 338 96 1 96 3 97 1 97 338 97 338 98 335 98 3 98 5 99 3 99 335 99 335 100 332 100 5 100 7 101 5 101 332 101 332 102 331 102 7 102 9 103 7 103 331 103 331 104 329 104 9 104 11 105 9 105 329 105 329 106 328 106 11 106 13 107 11 107 326 107 11 108 328 108 326 108 326 109 324 109 13 109 15 110 13 110 324 110 324 111 323 111 15 111 17 112 15 112 323 112 323 113 321 113 17 113 19 114 17 114 321 114 321 115 320 115 19 115 21 116 19 116 320 116 320 117 318 117 21 117 23 118 21 118 318 118 318 119 315 119 23 119 24 120 23 120 315 120 315 121 312 121 24 121 26 122 24 122 312 122 312 123 314 123 26 123 25 124 26 124 314 124 314 125 317 125 25 125 1 126 3 126 2 126 4 127 2 127 3 127 3 128 5 128 4 128 6 129 4 129 5 129 5 130 7 130 6 130 8 131 6 131 7 131 7 132 9 132 8 132 10 133 8 133 9 133 9 134 11 134 10 134 12 135 10 135 11 135 11 136 13 136 12 136 14 137 12 137 13 137 13 138 15 138 14 138 16 139 14 139 15 139 15 140 17 140 16 140 18 141 16 141 17 141 17 142 19 142 18 142 20 143 18 143 19 143 19 144 21 144 20 144 22 145 20 145 21 145 21 146 23 146 22 146 25 147 22 147 23 147 23 148 24 148 25 148 26 149 25 149 24 149 45 150 43 150 327 150 43 151 325 151 327 151 322 152 325 152 43 152 43 153 42 153 322 153 319 154 322 154 42 154 42 155 40 155 319 155 313 156 319 156 40 156 40 157 37 157 313 157 310 158 313 158 37 158 37 159 36 159 310 159 308 160 310 160 36 160 36 161 34 161 308 161 306 162 308 162 34 162 34 163 32 163 306 163 304 164 306 164 32 164 32 165 30 165 304 165 305 166 304 166 30 166 30 167 28 167 305 167 29 168 27 168 250 168 28 169 30 169 252 169 250 170 248 170 29 170 254 171 252 171 30 171 31 172 29 172 248 172 30 173 32 173 254 173 248 174 246 174 31 174 246 175 33 175 31 175 256 176 254 176 32 176 258 177 256 177 34 177 256 178 32 178 34 178 246 179 244 179 33 179 35 180 33 180 244 180 34 181 36 181 258 181 260 182 258 182 36 182 244 183 242 183 35 183 242 184 38 184 35 184 36 185 37 185 260 185 63 186 61 186 303 186 302 187 303 187 61 187 61 188 59 188 302 188 301 189 302 189 59 189 59 190 57 190 301 190 300 191 301 191 57 191 57 192 55 192 300 192 298 193 300 193 55 193 55 194 54 194 298 194 296 195 298 195 54 195 54 196 51 196 296 196 294 197 296 197 51 197 51 198 50 198 294 198 292 199 294 199 50 199 50 200 46 200 292 200 290 201 292 201 46 201 46 202 47 202 290 202 288 203 290 203 47 203 47 204 48 204 288 204 48 205 286 205 288 205 284 206 286 206 48 206 48 207 49 207 284 207 282 208 284 208 49 208 49 209 52 209 282 209 280 210 282 210 52 210 52 211 53 211 280 211 278 212 280 212 53 212 53 213 56 213 278 213 276 214 278 214 56 214 56 215 58 215 276 215 274 216 276 216 58 216 58 217 60 217 274 217 272 218 274 218 60 218 60 219 62 219 272 219 273 220 272 220 62 220 62 221 64 221 273 221 245 222 247 222 56 222 257 223 259 223 57 223 259 224 55 224 57 224 58 225 56 225 247 225 57 226 59 226 257 226 247 227 249 227 58 227 249 228 60 228 58 228 255 229 257 229 59 229 62 230 60 230 249 230 253 231 255 231 61 231 249 232 251 232 62 232 64 233 62 233 251 233 189 234 110 234 193 234 110 235 65 235 193 235 67 236 65 236 110 236 110 237 115 237 67 237 66 238 67 238 115 238 115 239 118 239 66 239 72 240 66 240 118 240 118 241 123 241 72 241 74 242 72 242 123 242 123 243 125 243 74 243 224 244 74 244 125 244 125 245 222 245 224 245 223 246 224 246 222 246 193 247 65 247 192 247 69 248 195 248 192 248 195 249 69 249 377 249 65 250 67 250 192 250 75 251 377 251 69 251 192 252 68 252 69 252 68 253 192 253 67 253 67 254 66 254 68 254 70 255 68 255 66 255 68 256 70 256 69 256 69 257 71 257 75 257 71 258 69 258 70 258 66 259 72 259 70 259 76 260 75 260 71 260 73 261 70 261 72 261 70 262 73 262 71 262 71 263 229 263 76 263 229 264 71 264 73 264 72 265 74 265 73 265 230 266 76 266 229 266 73 267 227 267 229 267 227 268 73 268 74 268 74 269 224 269 227 269 377 270 75 270 379 270 79 271 379 271 75 271 75 272 76 272 79 272 80 273 79 273 76 273 76 274 230 274 80 274 231 275 80 275 230 275 77 276 221 276 379 276 221 277 77 277 219 277 78 278 219 278 77 278 219 279 78 279 218 279 83 280 218 280 78 280 379 281 79 281 77 281 84 282 83 282 78 282 81 283 77 283 79 283 77 284 81 284 78 284 82 285 78 285 81 285 78 286 82 286 84 286 79 287 80 287 81 287 85 288 84 288 82 288 80 289 231 289 81 289 232 290 81 290 231 290 81 291 232 291 82 291 226 292 82 292 232 292 82 293 226 293 85 293 86 294 85 294 226 294 86 295 226 295 87 295 218 296 83 296 216 296 89 297 216 297 83 297 83 298 84 298 89 298 94 299 89 299 84 299 84 300 85 300 94 300 85 301 100 301 94 301 85 302 86 302 100 302 86 303 87 303 100 303 103 304 100 304 87 304 225 305 103 305 87 305 150 306 88 306 151 306 88 307 150 307 152 307 91 308 152 308 216 308 152 309 91 309 88 309 151 310 90 310 362 310 90 311 151 311 88 311 216 312 89 312 91 312 106 313 362 313 90 313 88 314 93 314 90 314 93 315 88 315 91 315 89 316 94 316 91 316 92 317 90 317 93 317 90 318 92 318 106 318 95 319 91 319 94 319 91 320 95 320 93 320 107 321 106 321 92 321 96 322 92 322 93 322 92 323 96 323 107 323 93 324 97 324 96 324 97 325 93 325 95 325 94 326 100 326 95 326 101 327 95 327 100 327 95 328 101 328 97 328 108 329 107 329 96 329 96 330 98 330 108 330 98 331 96 331 97 331 99 332 97 332 101 332 97 333 99 333 98 333 98 334 104 334 108 334 104 335 98 335 99 335 99 336 105 336 104 336 105 337 99 337 101 337 100 338 103 338 101 338 101 339 103 339 102 339 109 340 108 340 104 340 101 341 102 341 105 341 102 342 267 342 105 342 268 343 104 343 105 343 104 344 268 344 109 344 269 345 109 345 268 345 105 346 267 346 268 346 362 347 106 347 364 347 111 348 364 348 106 348 106 349 107 349 111 349 121 350 111 350 107 350 107 351 108 351 121 351 124 352 121 352 108 352 108 353 109 353 124 353 127 354 124 354 109 354 109 355 269 355 127 355 270 356 127 356 269 356 110 357 189 357 171 357 171 358 112 358 110 358 112 359 171 359 168 359 170 360 113 360 168 360 113 361 170 361 364 361 168 362 114 362 112 362 114 363 168 363 113 363 364 364 111 364 113 364 115 365 110 365 112 365 111 366 121 366 113 366 116 367 112 367 114 367 112 368 116 368 115 368 119 369 113 369 121 369 113 370 119 370 114 370 114 371 117 371 116 371 117 372 114 372 119 372 118 373 115 373 116 373 120 374 116 374 117 374 116 375 120 375 118 375 122 376 117 376 119 376 117 377 122 377 120 377 123 378 118 378 120 378 126 379 119 379 121 379 119 380 126 380 122 380 120 381 128 381 123 381 128 382 120 382 122 382 121 383 124 383 126 383 129 384 122 384 126 384 122 385 129 385 128 385 125 386 123 386 128 386 124 387 127 387 126 387 128 388 130 388 125 388 130 389 222 389 125 389 131 390 126 390 127 390 126 391 131 391 129 391 127 392 270 392 131 392 130 393 128 393 129 393 264 394 129 394 131 394 129 395 264 395 130 395 270 396 265 396 131 396 131 397 265 397 264 397 201 398 202 398 132 398 202 399 133 399 132 399 139 400 133 400 202 400 133 401 139 401 134 401 139 402 136 402 134 402 136 403 141 403 135 403 141 404 138 404 135 404 141 405 136 405 139 405 351 406 349 406 137 406 137 407 138 407 351 407 138 408 142 408 351 408 142 409 138 409 141 409 202 410 203 410 139 410 139 411 140 411 141 411 139 412 204 412 140 412 139 413 203 413 204 413 353 414 351 414 142 414 144 415 141 415 143 415 141 416 140 416 143 416 141 417 144 417 142 417 142 418 145 418 353 418 145 419 355 419 353 419 145 420 142 420 144 420 357 421 355 421 145 421 143 422 146 422 144 422 146 423 143 423 210 423 210 424 143 424 208 424 147 425 144 425 146 425 144 426 147 426 145 426 148 427 145 427 147 427 145 428 148 428 357 428 148 429 359 429 357 429 210 430 211 430 146 430 149 431 146 431 214 431 146 432 211 432 214 432 146 433 149 433 147 433 361 434 359 434 148 434 147 435 150 435 148 435 150 436 151 436 148 436 150 437 147 437 149 437 148 438 151 438 361 438 214 439 215 439 149 439 152 440 149 440 215 440 152 441 150 441 149 441 361 442 151 442 362 442 216 443 152 443 215 443 178 444 176 444 153 444 153 445 155 445 178 445 162 446 155 446 160 446 155 447 154 447 160 447 154 448 156 448 160 448 155 449 162 449 178 449 160 450 156 450 157 450 157 451 159 451 160 451 350 452 352 452 158 452 352 453 159 453 158 453 159 454 161 454 160 454 161 455 159 455 352 455 352 456 354 456 161 456 181 457 178 457 162 457 160 458 163 458 162 458 163 459 160 459 161 459 164 460 161 460 356 460 161 461 354 461 356 461 161 462 164 462 163 462 165 463 162 463 163 463 162 464 165 464 181 464 165 465 182 465 181 465 356 466 358 466 164 466 185 467 182 467 165 467 166 468 163 468 164 468 163 469 166 469 165 469 167 470 164 470 360 470 164 471 358 471 360 471 164 472 167 472 166 472 165 473 169 473 185 473 169 474 188 474 185 474 169 475 165 475 166 475 360 476 363 476 167 476 190 477 188 477 169 477 168 478 166 478 170 478 166 479 167 479 170 479 166 480 168 480 169 480 170 481 167 481 363 481 169 482 171 482 190 482 169 483 168 483 171 483 363 484 364 484 170 484 189 485 190 485 171 485 179 486 172 486 178 486 178 487 181 487 179 487 179 488 183 488 180 488 183 489 179 489 181 489 184 490 180 490 183 490 180 491 184 491 366 491 184 492 367 492 366 492 181 493 182 493 183 493 368 494 367 494 184 494 186 495 183 495 185 495 183 496 182 496 185 496 183 497 186 497 184 497 187 498 184 498 186 498 184 499 187 499 368 499 187 500 370 500 368 500 185 501 188 501 186 501 372 502 370 502 187 502 186 503 191 503 187 503 191 504 186 504 188 504 187 505 194 505 372 505 194 506 374 506 372 506 194 507 187 507 191 507 188 508 190 508 191 508 191 509 189 509 193 509 191 510 190 510 189 510 191 511 193 511 194 511 376 512 374 512 194 512 195 513 194 513 192 513 194 514 193 514 192 514 194 515 195 515 376 515 377 516 376 516 195 516 196 517 206 517 197 517 206 518 199 518 197 518 206 519 205 519 199 519 206 520 196 520 365 520 199 521 205 521 200 521 205 522 201 522 200 522 205 523 202 523 201 523 205 524 203 524 202 524 204 525 203 525 205 525 205 526 207 526 204 526 207 527 208 527 204 527 207 528 205 528 206 528 206 529 209 529 207 529 206 530 384 530 209 530 384 531 369 531 209 531 212 532 207 532 209 532 207 533 212 533 208 533 212 534 210 534 208 534 209 535 213 535 212 535 213 536 209 536 371 536 209 537 369 537 371 537 211 538 210 538 212 538 371 539 373 539 213 539 212 540 217 540 211 540 217 541 214 541 211 541 217 542 212 542 213 542 213 543 220 543 217 543 220 544 213 544 375 544 213 545 373 545 375 545 215 546 214 546 217 546 217 547 218 547 215 547 218 548 216 548 215 548 218 549 217 549 220 549 375 550 378 550 220 550 221 551 220 551 378 551 378 552 379 552 221 552 223 553 228 553 224 553 228 554 227 554 224 554 233 555 225 555 226 555 225 556 87 556 226 556 226 557 232 557 233 557 229 558 227 558 228 558 228 559 234 559 229 559 234 560 230 560 229 560 233 561 232 561 231 561 237 562 235 562 236 562 236 563 238 563 237 563 239 564 237 564 238 564 238 565 240 565 239 565 241 566 239 566 240 566 240 567 242 567 241 567 243 568 241 568 242 568 242 569 244 569 243 569 245 570 243 570 244 570 244 571 246 571 245 571 247 572 245 572 246 572 246 573 248 573 247 573 249 574 247 574 248 574 248 575 250 575 249 575 251 576 249 576 250 576 252 577 254 577 253 577 255 578 253 578 254 578 254 579 256 579 255 579 257 580 255 580 256 580 256 581 258 581 257 581 259 582 257 582 258 582 258 583 260 583 259 583 261 584 259 584 260 584 260 585 262 585 261 585 263 586 261 586 262 586 262 587 266 587 263 587 271 588 263 588 266 588 266 589 264 589 265 589 265 590 270 590 266 590 270 591 271 591 266 591 271 592 268 592 267 592 271 593 269 593 268 593 271 594 270 594 269 594 274 595 272 595 273 595 273 596 275 596 274 596 276 597 274 597 275 597 275 598 277 598 276 598 278 599 276 599 277 599 277 600 279 600 278 600 280 601 278 601 279 601 279 602 281 602 280 602 282 603 280 603 281 603 281 604 283 604 282 604 284 605 282 605 283 605 283 606 285 606 284 606 286 607 284 607 285 607 285 608 287 608 286 608 288 609 286 609 287 609 287 610 289 610 288 610 290 611 288 611 289 611 289 612 291 612 290 612 292 613 290 613 291 613 291 614 293 614 292 614 294 615 292 615 293 615 293 616 295 616 294 616 296 617 294 617 295 617 295 618 297 618 296 618 298 619 296 619 297 619 297 620 299 620 298 620 300 621 298 621 299 621 299 622 303 622 300 622 301 623 300 623 303 623 303 624 302 624 301 624 306 625 304 625 305 625 305 626 307 626 306 626 308 627 306 627 307 627 307 628 309 628 308 628 310 629 308 629 309 629 309 630 311 630 310 630 313 631 310 631 311 631 316 632 312 632 313 632 319 633 313 633 315 633 313 634 312 634 315 634 315 635 318 635 319 635 322 636 319 636 320 636 319 637 318 637 320 637 320 638 321 638 322 638 325 639 322 639 323 639 322 640 321 640 323 640 323 641 324 641 325 641 327 642 325 642 326 642 325 643 324 643 326 643 326 644 328 644 327 644 330 645 327 645 328 645 328 646 329 646 330 646 333 647 330 647 331 647 330 648 329 648 331 648 331 649 332 649 333 649 339 650 333 650 335 650 333 651 332 651 335 651 335 652 338 652 339 652 341 653 339 653 340 653 339 654 337 654 340 654 339 655 338 655 337 655 340 656 342 656 341 656 343 657 341 657 342 657 342 658 344 658 343 658 345 659 343 659 344 659 344 660 348 660 345 660 346 661 345 661 348 661 348 662 347 662 346 662 356 663 354 663 355 663 355 664 357 664 356 664 358 665 356 665 357 665 357 666 359 666 358 666 360 667 358 667 359 667 359 668 361 668 360 668 363 669 360 669 361 669 361 670 362 670 363 670 364 671 363 671 362 671 368 672 384 672 367 672 369 673 384 673 368 673 368 674 370 674 369 674 371 675 369 675 370 675 370 676 372 676 371 676 373 677 371 677 372 677 372 678 374 678 373 678 375 679 373 679 374 679 374 680 376 680 375 680 378 681 375 681 376 681 376 682 377 682 378 682 379 683 378 683 377 683 173 684 180 684 174 684 180 685 380 685 174 685 180 686 382 686 380 686 366 687 382 687 180 687 365 688 383 688 206 688 383 689 384 689 206 689 389 690 391 690 390 690 392 691 390 691 391 691 391 692 393 692 392 692 394 693 392 693 393 693 393 694 395 694 394 694 396 695 394 695 395 695 395 696 397 696 396 696 398 697 396 697 397 697 397 698 399 698 398 698 400 699 398 699 399 699 399 700 401 700 400 700 402 701 400 701 401 701 401 702 403 702 402 702 404 703 402 703 403 703 403 704 405 704 404 704 406 705 404 705 405 705 413 706 411 706 412 706 412 707 414 707 413 707 415 708 413 708 414 708 414 709 416 709 415 709 417 710 415 710 416 710 416 711 418 711 417 711 419 712 417 712 418 712 418 713 420 713 419 713 421 714 419 714 420 714 420 715 422 715 421 715 421 716 422 716 423 716 424 717 421 717 423 717 340 718 337 718 336 718 425 719 340 719 336 719 336 720 334 720 425 720 425 721 334 721 426 721 427 722 425 722 426 722 426 723 428 723 427 723 427 724 428 724 429 724 430 725 427 725 429 725 429 726 431 726 430 726 430 727 431 727 432 727 433 728 430 728 432 728 432 729 434 729 433 729 435 730 433 730 434 730 434 731 436 731 435 731 435 732 436 732 437 732 438 733 435 733 437 733 437 734 439 734 438 734 438 735 439 735 317 735 316 736 438 736 317 736 317 737 314 737 316 737 316 738 314 738 312 738 311 739 316 739 313 739 253 740 440 740 252 740 441 741 252 741 440 741 440 742 442 742 441 742 443 743 441 743 442 743 442 744 444 744 443 744 445 745 443 745 444 745 444 746 446 746 445 746 447 747 445 747 446 747 446 748 448 748 447 748 449 749 447 749 448 749 448 750 450 750 449 750 451 751 449 751 450 751 452 752 451 752 450 752 453 753 452 753 450 753 451 754 452 754 454 754 451 755 454 755 455 755 456 756 451 756 455 756 457 757 458 757 459 757 460 758 461 758 462 758 462 759 463 759 460 759 464 760 465 760 459 760 458 761 464 761 459 761 466 762 460 762 463 762 467 763 465 763 464 763 463 764 468 764 466 764 469 765 470 765 471 765 469 766 471 766 472 766 469 767 472 767 467 767 464 768 469 768 467 768 466 769 468 769 473 769 470 770 469 770 474 770 473 771 470 771 474 771 474 772 466 772 473 772 469 773 475 773 474 773 476 774 474 774 475 774 475 775 477 775 476 775 478 776 476 776 477 776 477 777 479 777 478 777 480 778 478 778 479 778 479 779 251 779 480 779 250 780 480 780 251 780 482 781 385 781 481 781 385 782 387 782 481 782 489 783 385 783 482 783 487 784 490 784 488 784 389 785 385 785 489 785 491 786 488 786 490 786 488 787 491 787 489 787 492 788 489 788 491 788 492 789 391 789 389 789 489 790 492 790 389 790 490 791 493 791 491 791 393 792 391 792 492 792 491 793 494 793 492 793 491 794 493 794 495 794 494 795 491 795 495 795 492 796 496 796 393 796 496 797 492 797 494 797 395 798 393 798 496 798 495 799 497 799 494 799 494 800 497 800 498 800 499 801 494 801 498 801 494 802 499 802 496 802 500 803 397 803 395 803 496 804 500 804 395 804 500 805 496 805 499 805 498 806 501 806 499 806 399 807 397 807 500 807 499 808 501 808 502 808 503 809 499 809 502 809 499 810 503 810 500 810 502 811 504 811 503 811 505 812 401 812 399 812 500 813 505 813 399 813 505 814 500 814 503 814 403 815 401 815 505 815 503 816 504 816 506 816 503 817 506 817 507 817 508 818 503 818 507 818 503 819 508 819 505 819 505 820 509 820 403 820 505 821 508 821 510 821 509 822 505 822 510 822 403 823 509 823 405 823 516 824 517 824 515 824 516 825 515 825 514 825 513 826 516 826 514 826 518 827 516 827 513 827 518 828 513 828 512 828 511 829 518 829 512 829 518 830 511 830 388 830 519 831 517 831 516 831 388 832 390 832 518 832 520 833 516 833 518 833 520 834 521 834 519 834 516 835 520 835 519 835 518 836 390 836 392 836 522 837 518 837 392 837 518 838 522 838 520 838 523 839 521 839 520 839 392 840 394 840 522 840 524 841 520 841 522 841 524 842 525 842 523 842 520 843 524 843 523 843 526 844 522 844 394 844 522 845 526 845 524 845 394 846 396 846 526 846 527 847 525 847 524 847 524 848 528 848 527 848 528 849 524 849 526 849 529 850 527 850 528 850 526 851 530 851 528 851 526 852 396 852 398 852 530 853 526 853 398 853 398 854 400 854 530 854 531 855 532 855 529 855 528 856 531 856 529 856 531 857 528 857 530 857 533 858 532 858 531 858 530 859 534 859 531 859 530 860 400 860 402 860 534 861 530 861 402 861 402 862 404 862 534 862 535 863 531 863 534 863 538 864 534 864 404 864 404 865 406 865 538 865 517 866 540 866 541 866 515 867 517 867 541 867 542 868 543 868 410 868 410 869 408 869 542 869 543 870 544 870 410 870 545 871 544 871 543 871 545 872 543 872 546 872 547 873 545 873 546 873 548 874 545 874 547 874 548 875 547 875 549 875 540 876 548 876 549 876 548 877 540 877 517 877 517 878 519 878 548 878 412 879 410 879 544 879 550 880 544 880 545 880 550 881 414 881 412 881 544 882 550 882 412 882 551 883 545 883 548 883 545 884 551 884 550 884 548 885 552 885 551 885 548 886 519 886 521 886 552 887 548 887 521 887 521 888 523 888 552 888 416 889 414 889 550 889 553 890 550 890 551 890 550 891 553 891 416 891 554 892 551 892 552 892 551 893 554 893 553 893 552 894 523 894 525 894 555 895 552 895 525 895 552 896 555 896 554 896 418 897 416 897 553 897 525 898 527 898 555 898 556 899 420 899 418 899 553 900 556 900 418 900 556 901 553 901 554 901 557 902 554 902 555 902 554 903 557 903 556 903 555 904 558 904 557 904 555 905 527 905 529 905 558 906 555 906 529 906 422 907 420 907 556 907 529 908 532 908 558 908 559 909 423 909 422 909 556 910 559 910 422 910 559 911 556 911 557 911 560 912 559 912 557 912 560 913 557 913 558 913 558 914 532 914 533 914 560 915 558 915 533 915 561 916 560 916 533 916 537 917 561 917 533 917 487 918 485 918 562 918 563 919 407 919 409 919 564 920 563 920 409 920 565 921 563 921 564 921 566 922 565 922 564 922 567 923 566 923 564 923 487 924 568 924 490 924 569 925 566 925 567 925 562 926 569 926 567 926 568 927 562 927 567 927 562 928 568 928 487 928 409 929 411 929 564 929 564 930 570 930 567 930 564 931 411 931 413 931 570 932 564 932 413 932 567 933 571 933 568 933 571 934 567 934 570 934 493 935 490 935 568 935 413 936 415 936 570 936 572 937 493 937 568 937 572 938 568 938 571 938 495 939 493 939 572 939 570 940 573 940 571 940 573 941 570 941 415 941 571 942 574 942 572 942 574 943 571 943 573 943 415 944 417 944 573 944 575 945 572 945 574 945 575 946 497 946 495 946 572 947 575 947 495 947 498 948 497 948 575 948 573 949 576 949 574 949 573 950 417 950 419 950 576 951 573 951 419 951 574 952 577 952 575 952 577 953 574 953 576 953 578 954 575 954 577 954 578 955 501 955 498 955 575 956 578 956 498 956 419 957 421 957 576 957 502 958 501 958 578 958 576 959 579 959 577 959 576 960 421 960 424 960 576 961 424 961 579 961 577 962 580 962 578 962 577 963 579 963 580 963 578 964 580 964 581 964 581 965 504 965 502 965 578 966 581 966 502 966 506 967 504 967 581 967 452 968 582 968 454 968 583 969 454 969 582 969 582 970 584 970 583 970 585 971 583 971 584 971 584 972 586 972 585 972 587 973 585 973 586 973 586 974 588 974 587 974 589 975 587 975 588 975 588 976 590 976 589 976 591 977 589 977 590 977 590 978 424 978 591 978 423 979 591 979 424 979 454 980 592 980 455 980 593 981 455 981 592 981 455 982 593 982 456 982 592 983 583 983 593 983 594 984 456 984 593 984 595 985 593 985 583 985 593 986 595 986 594 986 583 987 585 987 595 987 596 988 456 988 594 988 597 989 595 989 585 989 595 990 597 990 594 990 594 991 598 991 596 991 598 992 594 992 597 992 585 993 587 993 597 993 597 994 599 994 598 994 599 995 597 995 587 995 587 996 589 996 599 996 600 997 596 997 598 997 601 998 598 998 599 998 598 999 601 999 600 999 602 1000 599 1000 589 1000 599 1001 602 1001 601 1001 589 1002 603 1002 602 1002 604 1003 600 1003 601 1003 601 1004 605 1004 604 1004 605 1005 601 1005 602 1005 602 1006 606 1006 605 1006 606 1007 602 1007 603 1007 603 1008 591 1008 606 1008 607 1009 604 1009 605 1009 606 1010 559 1010 605 1010 559 1011 606 1011 591 1011 561 1012 607 1012 605 1012 591 1013 423 1013 559 1013 560 1014 605 1014 559 1014 605 1015 560 1015 561 1015 614 1016 608 1016 596 1016 596 1017 600 1017 614 1017 609 1018 614 1018 600 1018 600 1019 604 1019 609 1019 623 1020 609 1020 604 1020 604 1021 607 1021 623 1021 610 1022 623 1022 607 1022 607 1023 561 1023 610 1023 610 1024 561 1024 537 1024 611 1025 462 1025 461 1025 461 1026 608 1026 611 1026 463 1027 462 1027 611 1027 612 1028 463 1028 611 1028 611 1029 613 1029 612 1029 613 1030 611 1030 608 1030 468 1031 463 1031 612 1031 608 1032 614 1032 613 1032 612 1033 615 1033 468 1033 473 1034 468 1034 615 1034 614 1035 609 1035 613 1035 616 1036 612 1036 613 1036 612 1037 616 1037 615 1037 613 1038 617 1038 616 1038 617 1039 613 1039 609 1039 618 1040 615 1040 616 1040 615 1041 618 1041 473 1041 619 1042 470 1042 473 1042 473 1043 620 1043 619 1043 620 1044 473 1044 618 1044 616 1045 621 1045 618 1045 621 1046 616 1046 617 1046 617 1047 622 1047 621 1047 622 1048 617 1048 609 1048 609 1049 623 1049 622 1049 618 1050 624 1050 620 1050 624 1051 618 1051 621 1051 625 1052 626 1052 619 1052 620 1053 625 1053 619 1053 625 1054 620 1054 624 1054 623 1055 610 1055 622 1055 621 1056 535 1056 624 1056 535 1057 621 1057 622 1057 627 1058 622 1058 610 1058 622 1059 627 1059 535 1059 624 1060 539 1060 625 1060 539 1061 624 1061 535 1061 627 1062 610 1062 536 1062 535 1063 627 1063 536 1063 538 1064 406 1064 626 1064 625 1065 538 1065 626 1065 610 1066 537 1066 536 1066 470 1067 619 1067 471 1067 628 1068 471 1068 619 1068 619 1069 626 1069 628 1069 629 1070 628 1070 626 1070 626 1071 406 1071 629 1071 405 1072 629 1072 406 1072 630 1073 457 1073 459 1073 459 1074 631 1074 630 1074 459 1075 465 1075 631 1075 465 1076 632 1076 631 1076 633 1077 631 1077 632 1077 631 1078 633 1078 630 1078 465 1079 467 1079 632 1079 646 1080 630 1080 633 1080 467 1081 634 1081 632 1081 467 1082 472 1082 634 1082 635 1083 632 1083 634 1083 632 1084 635 1084 633 1084 636 1085 646 1085 633 1085 633 1086 637 1086 636 1086 637 1087 633 1087 635 1087 472 1088 638 1088 634 1088 472 1089 471 1089 638 1089 639 1090 634 1090 638 1090 634 1091 639 1091 635 1091 471 1092 628 1092 638 1092 640 1093 636 1093 637 1093 641 1094 637 1094 635 1094 637 1095 641 1095 640 1095 642 1096 638 1096 628 1096 638 1097 642 1097 639 1097 635 1098 643 1098 641 1098 643 1099 635 1099 639 1099 644 1100 639 1100 642 1100 639 1101 644 1101 643 1101 628 1102 629 1102 642 1102 507 1103 641 1103 643 1103 641 1104 507 1104 640 1104 508 1105 643 1105 644 1105 643 1106 508 1106 507 1106 506 1107 640 1107 507 1107 644 1108 510 1108 508 1108 510 1109 644 1109 642 1109 642 1110 509 1110 510 1110 509 1111 642 1111 629 1111 629 1112 405 1112 509 1112 630 1113 646 1113 645 1113 647 1114 645 1114 646 1114 646 1115 636 1115 647 1115 648 1116 647 1116 636 1116 636 1117 640 1117 648 1117 649 1118 648 1118 640 1118 640 1119 506 1119 649 1119 581 1120 649 1120 506 1120 453 1121 650 1121 452 1121 453 1122 450 1122 651 1122 650 1123 453 1123 651 1123 582 1124 452 1124 650 1124 652 1125 650 1125 651 1125 650 1126 652 1126 582 1126 653 1127 582 1127 652 1127 651 1128 654 1128 652 1128 584 1129 653 1129 652 1129 655 1130 652 1130 654 1130 652 1131 655 1131 584 1131 656 1132 584 1132 655 1132 651 1133 630 1133 654 1133 654 1134 630 1134 645 1134 657 1135 654 1135 645 1135 654 1136 657 1136 655 1136 655 1137 658 1137 656 1137 658 1138 655 1138 657 1138 586 1139 656 1139 658 1139 659 1140 657 1140 645 1140 657 1141 659 1141 658 1141 645 1142 647 1142 659 1142 588 1143 586 1143 658 1143 658 1144 660 1144 588 1144 660 1145 658 1145 659 1145 659 1146 661 1146 660 1146 661 1147 659 1147 647 1147 647 1148 648 1148 661 1148 590 1149 588 1149 660 1149 662 1150 661 1150 648 1150 661 1151 662 1151 660 1151 663 1152 660 1152 662 1152 660 1153 663 1153 590 1153 648 1154 649 1154 662 1154 662 1155 580 1155 663 1155 580 1156 662 1156 649 1156 649 1157 581 1157 580 1157 424 1158 590 1158 663 1158 579 1159 663 1159 580 1159 663 1160 579 1160 424 1160 475 1161 670 1161 671 1161 477 1162 475 1162 671 1162 479 1163 477 1163 671 1163 442 1164 440 1164 673 1164 671 1165 674 1165 479 1165 479 1166 674 1166 64 1166 251 1167 479 1167 64 1167 253 1168 63 1168 673 1168 440 1169 253 1169 673 1169 287 1170 285 1170 664 1170 665 1171 664 1171 285 1171 285 1172 283 1172 665 1172 666 1173 665 1173 283 1173 283 1174 281 1174 666 1174 670 1175 666 1175 281 1175 281 1176 279 1176 670 1176 671 1177 670 1177 279 1177 279 1178 277 1178 671 1178 674 1179 671 1179 277 1179 277 1180 275 1180 674 1180 64 1181 674 1181 275 1181 275 1182 273 1182 64 1182 303 1183 299 1183 63 1183 673 1184 63 1184 299 1184 299 1185 297 1185 673 1185 672 1186 673 1186 297 1186 297 1187 295 1187 672 1187 669 1188 672 1188 295 1188 295 1189 293 1189 669 1189 667 1190 669 1190 293 1190 293 1191 291 1191 667 1191 668 1192 667 1192 291 1192 291 1193 289 1193 668 1193 668 1194 289 1194 287 1194 664 1195 668 1195 287 1195 252 1196 441 1196 28 1196 433 1197 435 1197 684 1197 685 1198 684 1198 435 1198 435 1199 438 1199 685 1199 681 1200 685 1200 438 1200 438 1201 316 1201 681 1201 680 1202 681 1202 316 1202 316 1203 311 1203 680 1203 678 1204 680 1204 311 1204 311 1205 309 1205 678 1205 676 1206 678 1206 309 1206 309 1207 307 1207 676 1207 28 1208 676 1208 307 1208 307 1209 305 1209 28 1209 16 1210 434 1210 432 1210 14 1211 16 1211 432 1211 436 1212 434 1212 16 1212 16 1213 18 1213 436 1213 437 1214 436 1214 18 1214 18 1215 20 1215 437 1215 439 1216 437 1216 20 1216 20 1217 22 1217 439 1217 317 1218 439 1218 22 1218 22 1219 25 1219 317 1219 4 1220 6 1220 334 1220 426 1221 334 1221 6 1221 6 1222 8 1222 426 1222 428 1223 426 1223 8 1223 8 1224 10 1224 428 1224 429 1225 428 1225 10 1225 10 1226 12 1226 429 1226 431 1227 429 1227 12 1227 12 1228 14 1228 431 1228 432 1229 431 1229 14 1229 348 1230 344 1230 27 1230 675 1231 27 1231 344 1231 344 1232 342 1232 675 1232 677 1233 675 1233 342 1233 342 1234 340 1234 677 1234 679 1235 677 1235 340 1235 340 1236 425 1236 679 1236 682 1237 679 1237 425 1237 425 1238 427 1238 682 1238 683 1239 682 1239 427 1239 427 1240 430 1240 683 1240 683 1241 430 1241 433 1241 684 1242 683 1242 433 1242 388 1243 389 1243 390 1243 385 1244 389 1244 388 1244 385 1245 388 1245 386 1245 385 1246 386 1246 387 1246 410 1247 412 1247 411 1247 409 1248 410 1248 411 1248 408 1249 410 1249 409 1249 407 1250 408 1250 409 1250 533 1251 536 1251 537 1251 534 1252 539 1252 535 1252 534 1253 538 1253 539 1253 538 1254 625 1254 539 1254 480 1255 250 1255 27 1255 480 1256 27 1256 675 1256 478 1257 480 1257 675 1257 478 1258 675 1258 677 1258 476 1259 478 1259 677 1259 476 1260 677 1260 679 1260 474 1261 476 1261 679 1261 466 1262 474 1262 679 1262 466 1263 679 1263 682 1263 460 1264 466 1264 682 1264 460 1265 682 1265 683 1265 460 1266 683 1266 461 1266 461 1267 683 1267 684 1267 456 1268 684 1268 685 1268 451 1269 456 1269 685 1269 461 1270 686 1270 608 1270 456 1271 686 1271 684 1271 686 1272 461 1272 684 1272 596 1273 608 1273 686 1273 456 1274 596 1274 686 1274 531 1275 536 1275 533 1275 531 1276 535 1276 536 1276 451 1277 685 1277 681 1277 449 1278 451 1278 681 1278 449 1279 681 1279 680 1279 441 1280 443 1280 28 1280 443 1281 676 1281 28 1281 443 1282 445 1282 676 1282 445 1283 678 1283 676 1283 445 1284 447 1284 678 1284 447 1285 680 1285 678 1285 447 1286 449 1286 680 1286 469 1287 670 1287 475 1287 464 1288 670 1288 469 1288 464 1289 666 1289 670 1289 458 1290 666 1290 464 1290 458 1291 665 1291 666 1291 457 1292 665 1292 458 1292 457 1293 664 1293 665 1293 457 1294 630 1294 664 1294 630 1295 668 1295 664 1295 630 1296 651 1296 668 1296 450 1297 667 1297 651 1297 651 1298 667 1298 668 1298 450 1299 669 1299 667 1299 448 1300 669 1300 450 1300 448 1301 672 1301 669 1301 446 1302 672 1302 448 1302 446 1303 673 1303 672 1303 444 1304 673 1304 446 1304 442 1305 673 1305 444 1305 482 1306 483 1306 489 1306 483 1307 488 1307 489 1307 483 1308 486 1308 488 1308 484 1309 488 1309 486 1309 484 1310 487 1310 488 1310 484 1311 485 1311 487 1311 386 1312 388 1312 687 1312 388 1313 511 1313 687 1313 841 1314 766 1314 765 1314 841 1315 767 1315 766 1315 841 1316 768 1316 767 1316 841 1317 839 1317 768 1317 789 1318 687 1318 511 1318 386 1319 687 1319 906 1319 906 1320 687 1320 789 1320 380 1321 820 1321 819 1321 380 1322 821 1322 820 1322 381 1323 821 1323 380 1323 381 1324 822 1324 821 1324 381 1325 823 1325 822 1325 785 1326 783 1326 711 1326 783 1327 784 1327 711 1327 710 1328 711 1328 784 1328 784 1329 782 1329 710 1329 709 1330 710 1330 782 1330 782 1331 742 1331 709 1331 708 1332 709 1332 742 1332 742 1333 743 1333 708 1333 707 1334 708 1334 744 1334 708 1335 743 1335 744 1335 706 1336 707 1336 745 1336 707 1337 744 1337 745 1337 706 1338 745 1338 746 1338 705 1339 715 1339 716 1339 716 1340 713 1340 705 1340 704 1341 705 1341 713 1341 713 1342 714 1342 704 1342 703 1343 704 1343 714 1343 714 1344 712 1344 703 1344 702 1345 703 1345 712 1345 700 1346 702 1346 790 1346 702 1347 712 1347 790 1347 790 1348 791 1348 700 1348 701 1349 700 1349 791 1349 791 1350 792 1350 701 1350 792 1351 793 1351 701 1351 800 1352 798 1352 689 1352 798 1353 799 1353 689 1353 688 1354 689 1354 799 1354 799 1355 797 1355 688 1355 690 1356 688 1356 797 1356 797 1357 726 1357 690 1357 693 1358 690 1358 726 1358 726 1359 727 1359 693 1359 692 1360 693 1360 728 1360 693 1361 727 1361 728 1361 691 1362 692 1362 729 1362 692 1363 728 1363 729 1363 691 1364 729 1364 730 1364 695 1365 760 1365 761 1365 761 1366 758 1366 695 1366 694 1367 695 1367 758 1367 758 1368 759 1368 694 1368 696 1369 694 1369 759 1369 759 1370 757 1370 696 1370 697 1371 696 1371 757 1371 698 1372 697 1372 772 1372 697 1373 757 1373 772 1373 772 1374 773 1374 698 1374 699 1375 698 1375 773 1375 773 1376 774 1376 699 1376 774 1377 775 1377 699 1377 825 1378 823 1378 804 1378 823 1379 805 1379 804 1379 804 1380 803 1380 825 1380 827 1381 825 1381 802 1381 825 1382 803 1382 802 1382 838 1383 840 1383 741 1383 840 1384 740 1384 741 1384 840 1385 739 1385 740 1385 840 1386 738 1386 739 1386 802 1387 801 1387 827 1387 829 1388 827 1388 800 1388 827 1389 801 1389 800 1389 737 1390 738 1390 840 1390 840 1391 842 1391 737 1391 842 1392 736 1392 737 1392 842 1393 735 1393 736 1393 842 1394 734 1394 735 1394 842 1395 733 1395 734 1395 842 1396 732 1396 733 1396 688 1397 690 1397 689 1397 800 1398 689 1398 690 1398 690 1399 693 1399 800 1399 693 1400 829 1400 800 1400 831 1401 829 1401 730 1401 829 1402 691 1402 730 1402 829 1403 692 1403 691 1403 829 1404 693 1404 692 1404 731 1405 732 1405 842 1405 842 1406 844 1406 731 1406 844 1407 730 1407 731 1407 844 1408 831 1408 730 1408 833 1409 831 1409 844 1409 844 1410 846 1410 833 1410 834 1411 833 1411 846 1411 846 1412 848 1412 834 1412 836 1413 834 1413 848 1413 848 1414 850 1414 836 1414 835 1415 836 1415 850 1415 850 1416 852 1416 835 1416 832 1417 835 1417 852 1417 852 1418 854 1418 832 1418 830 1419 832 1419 854 1419 854 1420 856 1420 830 1420 828 1421 830 1421 856 1421 856 1422 858 1422 828 1422 826 1423 828 1423 858 1423 858 1424 860 1424 826 1424 824 1425 826 1425 860 1425 860 1426 863 1426 824 1426 822 1427 824 1427 863 1427 863 1428 864 1428 822 1428 821 1429 822 1429 864 1429 864 1430 862 1430 821 1430 820 1431 821 1431 862 1431 862 1432 861 1432 820 1432 818 1433 820 1433 861 1433 861 1434 859 1434 818 1434 816 1435 818 1435 859 1435 859 1436 857 1436 816 1436 814 1437 816 1437 857 1437 857 1438 855 1438 814 1438 812 1439 814 1439 855 1439 855 1440 853 1440 812 1440 810 1441 812 1441 853 1441 853 1442 851 1442 810 1442 808 1443 810 1443 851 1443 851 1444 849 1444 808 1444 806 1445 808 1445 849 1445 849 1446 847 1446 806 1446 807 1447 806 1447 847 1447 847 1448 845 1448 807 1448 809 1449 807 1449 845 1449 845 1450 843 1450 809 1450 811 1451 809 1451 843 1451 843 1452 841 1452 760 1452 760 1453 811 1453 843 1453 841 1454 762 1454 760 1454 813 1455 811 1455 696 1455 811 1456 694 1456 696 1456 811 1457 695 1457 694 1457 811 1458 760 1458 695 1458 763 1459 762 1459 841 1459 765 1460 764 1460 841 1460 764 1461 763 1461 841 1461 696 1462 697 1462 775 1462 775 1463 813 1463 696 1463 815 1464 813 1464 776 1464 813 1465 775 1465 776 1465 699 1466 775 1466 697 1466 697 1467 698 1467 699 1467 769 1468 768 1468 839 1468 839 1469 837 1469 771 1469 771 1470 770 1470 839 1470 770 1471 769 1471 839 1471 776 1472 777 1472 815 1472 817 1473 815 1473 778 1473 815 1474 777 1474 778 1474 778 1475 779 1475 817 1475 819 1476 817 1476 780 1476 817 1477 779 1477 780 1477 387 1478 910 1478 481 1478 910 1479 912 1479 481 1479 912 1480 482 1480 481 1480 796 1481 482 1481 912 1481 912 1482 914 1482 796 1482 914 1483 795 1483 796 1483 890 1484 892 1484 725 1484 725 1485 724 1485 890 1485 724 1486 723 1486 890 1486 723 1487 722 1487 890 1487 794 1488 795 1488 914 1488 914 1489 916 1489 794 1489 916 1490 793 1490 794 1490 722 1491 721 1491 890 1491 888 1492 890 1492 719 1492 719 1493 718 1493 888 1493 890 1494 720 1494 719 1494 890 1495 721 1495 720 1495 702 1496 700 1496 701 1496 701 1497 793 1497 702 1497 703 1498 702 1498 793 1498 793 1499 916 1499 703 1499 916 1500 918 1500 703 1500 918 1501 704 1501 703 1501 918 1502 705 1502 704 1502 918 1503 715 1503 705 1503 886 1504 888 1504 715 1504 715 1505 918 1505 886 1505 888 1506 717 1506 715 1506 888 1507 718 1507 717 1507 918 1508 920 1508 886 1508 884 1509 886 1509 920 1509 920 1510 921 1510 884 1510 882 1511 884 1511 921 1511 921 1512 922 1512 882 1512 880 1513 882 1513 922 1513 922 1514 923 1514 880 1514 878 1515 880 1515 923 1515 923 1516 919 1516 878 1516 876 1517 878 1517 919 1517 919 1518 917 1518 876 1518 874 1519 876 1519 917 1519 917 1520 915 1520 874 1520 872 1521 874 1521 915 1521 915 1522 913 1522 872 1522 870 1523 872 1523 913 1523 913 1524 911 1524 870 1524 868 1525 870 1525 911 1525 911 1526 909 1526 868 1526 866 1527 868 1527 909 1527 909 1528 908 1528 866 1528 865 1529 866 1529 908 1529 908 1530 907 1530 865 1530 867 1531 865 1531 907 1531 907 1532 905 1532 867 1532 869 1533 867 1533 905 1533 905 1534 903 1534 869 1534 871 1535 869 1535 903 1535 903 1536 901 1536 871 1536 873 1537 871 1537 901 1537 901 1538 899 1538 873 1538 875 1539 873 1539 899 1539 899 1540 897 1540 875 1540 877 1541 875 1541 897 1541 897 1542 895 1542 877 1542 879 1543 877 1543 895 1543 895 1544 893 1544 879 1544 881 1545 879 1545 893 1545 893 1546 894 1546 881 1546 883 1547 881 1547 894 1547 894 1548 896 1548 883 1548 885 1549 883 1549 896 1549 896 1550 898 1550 885 1550 887 1551 885 1551 747 1551 885 1552 746 1552 747 1552 885 1553 898 1553 746 1553 898 1554 900 1554 746 1554 900 1555 706 1555 746 1555 900 1556 707 1556 706 1556 900 1557 708 1557 707 1557 747 1558 748 1558 887 1558 889 1559 887 1559 753 1559 887 1560 752 1560 753 1560 887 1561 751 1561 752 1561 887 1562 750 1562 751 1562 887 1563 749 1563 750 1563 887 1564 748 1564 749 1564 709 1565 708 1565 785 1565 708 1566 900 1566 785 1566 900 1567 902 1567 785 1567 902 1568 786 1568 785 1568 785 1569 711 1569 709 1569 710 1570 709 1570 711 1570 753 1571 754 1571 889 1571 891 1572 889 1572 756 1572 889 1573 755 1573 756 1573 889 1574 754 1574 755 1574 787 1575 786 1575 902 1575 902 1576 904 1576 787 1576 904 1577 788 1577 787 1577 789 1578 788 1578 904 1578 904 1579 906 1579 789 1579 790 1580 712 1580 485 1580 562 1581 485 1581 712 1581 712 1582 714 1582 562 1582 562 1583 713 1583 716 1583 562 1584 714 1584 713 1584 569 1585 562 1585 717 1585 562 1586 715 1586 717 1586 562 1587 716 1587 715 1587 717 1588 718 1588 569 1588 566 1589 569 1589 719 1589 569 1590 718 1590 719 1590 565 1591 566 1591 720 1591 566 1592 719 1592 720 1592 720 1593 721 1593 565 1593 563 1594 565 1594 722 1594 565 1595 721 1595 722 1595 722 1596 723 1596 563 1596 407 1597 563 1597 724 1597 563 1598 723 1598 724 1598 724 1599 725 1599 407 1599 407 1600 725 1600 892 1600 201 1601 132 1601 797 1601 132 1602 726 1602 797 1602 727 1603 726 1603 132 1603 132 1604 133 1604 727 1604 133 1605 728 1605 727 1605 133 1606 729 1606 728 1606 730 1607 729 1607 133 1607 133 1608 134 1608 730 1608 134 1609 731 1609 730 1609 732 1610 731 1610 134 1610 134 1611 136 1611 732 1611 136 1612 733 1612 732 1612 734 1613 733 1613 136 1613 136 1614 135 1614 734 1614 135 1615 735 1615 734 1615 736 1616 735 1616 135 1616 135 1617 138 1617 736 1617 138 1618 737 1618 736 1618 138 1619 738 1619 737 1619 739 1620 738 1620 138 1620 138 1621 137 1621 739 1621 137 1622 740 1622 739 1622 741 1623 740 1623 137 1623 137 1624 349 1624 741 1624 838 1625 741 1625 349 1625 515 1626 541 1626 782 1626 541 1627 742 1627 782 1627 743 1628 742 1628 541 1628 541 1629 540 1629 743 1629 540 1630 744 1630 743 1630 540 1631 745 1631 744 1631 746 1632 745 1632 540 1632 540 1633 549 1633 746 1633 549 1634 747 1634 746 1634 748 1635 747 1635 549 1635 549 1636 547 1636 748 1636 547 1637 749 1637 748 1637 750 1638 749 1638 547 1638 547 1639 546 1639 750 1639 546 1640 751 1640 750 1640 752 1641 751 1641 546 1641 546 1642 543 1642 752 1642 543 1643 753 1643 752 1643 754 1644 753 1644 543 1644 543 1645 542 1645 754 1645 542 1646 755 1646 754 1646 756 1647 755 1647 542 1647 542 1648 408 1648 756 1648 891 1649 756 1649 408 1649 772 1650 757 1650 176 1650 153 1651 176 1651 757 1651 757 1652 759 1652 153 1652 155 1653 153 1653 761 1653 153 1654 758 1654 761 1654 153 1655 759 1655 758 1655 154 1656 155 1656 762 1656 155 1657 760 1657 762 1657 155 1658 761 1658 760 1658 762 1659 763 1659 154 1659 156 1660 154 1660 764 1660 154 1661 763 1661 764 1661 764 1662 765 1662 156 1662 157 1663 156 1663 766 1663 156 1664 765 1664 766 1664 766 1665 767 1665 157 1665 159 1666 157 1666 768 1666 157 1667 767 1667 768 1667 768 1668 769 1668 159 1668 158 1669 159 1669 770 1669 159 1670 769 1670 770 1670 770 1671 771 1671 158 1671 350 1672 158 1672 837 1672 158 1673 771 1673 837 1673 176 1674 177 1674 772 1674 177 1675 773 1675 772 1675 177 1676 774 1676 773 1676 177 1677 775 1677 774 1677 776 1678 775 1678 177 1678 177 1679 172 1679 776 1679 777 1680 776 1680 172 1680 172 1681 175 1681 777 1681 778 1682 777 1682 175 1682 175 1683 173 1683 778 1683 173 1684 779 1684 778 1684 780 1685 779 1685 173 1685 173 1686 174 1686 780 1686 782 1687 784 1687 515 1687 514 1688 515 1688 785 1688 515 1689 783 1689 785 1689 515 1690 784 1690 783 1690 785 1691 786 1691 514 1691 513 1692 514 1692 786 1692 786 1693 787 1693 513 1693 512 1694 513 1694 787 1694 787 1695 788 1695 512 1695 511 1696 512 1696 789 1696 512 1697 788 1697 789 1697 485 1698 484 1698 790 1698 484 1699 791 1699 790 1699 484 1700 792 1700 791 1700 484 1701 793 1701 792 1701 794 1702 793 1702 484 1702 484 1703 486 1703 794 1703 795 1704 794 1704 486 1704 486 1705 483 1705 795 1705 796 1706 795 1706 483 1706 483 1707 482 1707 796 1707 797 1708 799 1708 201 1708 200 1709 201 1709 800 1709 201 1710 798 1710 800 1710 201 1711 799 1711 798 1711 800 1712 801 1712 200 1712 199 1713 200 1713 801 1713 801 1714 802 1714 199 1714 197 1715 199 1715 802 1715 802 1716 803 1716 197 1716 196 1717 197 1717 804 1717 197 1718 803 1718 804 1718 804 1719 805 1719 196 1719 808 1720 806 1720 807 1720 807 1721 809 1721 808 1721 810 1722 808 1722 809 1722 809 1723 811 1723 810 1723 812 1724 810 1724 811 1724 811 1725 813 1725 812 1725 814 1726 812 1726 813 1726 813 1727 815 1727 814 1727 816 1728 814 1728 815 1728 815 1729 817 1729 816 1729 818 1730 816 1730 817 1730 817 1731 819 1731 818 1731 820 1732 818 1732 819 1732 824 1733 822 1733 823 1733 823 1734 825 1734 824 1734 826 1735 824 1735 825 1735 825 1736 827 1736 826 1736 828 1737 826 1737 827 1737 827 1738 829 1738 828 1738 830 1739 828 1739 829 1739 829 1740 831 1740 830 1740 832 1741 830 1741 831 1741 831 1742 833 1742 832 1742 835 1743 832 1743 833 1743 833 1744 834 1744 835 1744 836 1745 835 1745 834 1745 350 1746 837 1746 349 1746 838 1747 349 1747 837 1747 837 1748 839 1748 838 1748 840 1749 838 1749 839 1749 839 1750 841 1750 840 1750 842 1751 840 1751 841 1751 841 1752 843 1752 842 1752 844 1753 842 1753 843 1753 843 1754 845 1754 844 1754 846 1755 844 1755 845 1755 845 1756 847 1756 846 1756 848 1757 846 1757 847 1757 847 1758 849 1758 848 1758 850 1759 848 1759 849 1759 849 1760 851 1760 850 1760 852 1761 850 1761 851 1761 851 1762 853 1762 852 1762 854 1763 852 1763 853 1763 853 1764 855 1764 854 1764 856 1765 854 1765 855 1765 855 1766 857 1766 856 1766 858 1767 856 1767 857 1767 857 1768 859 1768 858 1768 860 1769 858 1769 859 1769 859 1770 861 1770 860 1770 863 1771 860 1771 861 1771 861 1772 862 1772 863 1772 864 1773 863 1773 862 1773 865 1774 867 1774 866 1774 868 1775 866 1775 867 1775 867 1776 869 1776 868 1776 870 1777 868 1777 869 1777 869 1778 871 1778 870 1778 872 1779 870 1779 871 1779 871 1780 873 1780 872 1780 874 1781 872 1781 873 1781 873 1782 875 1782 874 1782 876 1783 874 1783 875 1783 875 1784 877 1784 876 1784 878 1785 876 1785 877 1785 877 1786 879 1786 878 1786 880 1787 878 1787 879 1787 879 1788 881 1788 880 1788 882 1789 880 1789 881 1789 881 1790 883 1790 882 1790 884 1791 882 1791 883 1791 883 1792 885 1792 884 1792 886 1793 884 1793 885 1793 885 1794 887 1794 886 1794 888 1795 886 1795 887 1795 887 1796 889 1796 888 1796 890 1797 888 1797 889 1797 889 1798 891 1798 890 1798 892 1799 890 1799 891 1799 891 1800 408 1800 892 1800 407 1801 892 1801 408 1801 893 1802 895 1802 894 1802 896 1803 894 1803 895 1803 895 1804 897 1804 896 1804 898 1805 896 1805 897 1805 897 1806 899 1806 898 1806 900 1807 898 1807 899 1807 899 1808 901 1808 900 1808 902 1809 900 1809 901 1809 901 1810 903 1810 902 1810 904 1811 902 1811 903 1811 903 1812 905 1812 904 1812 906 1813 904 1813 905 1813 905 1814 907 1814 906 1814 386 1815 906 1815 907 1815 907 1816 908 1816 386 1816 386 1817 908 1817 387 1817 908 1818 909 1818 387 1818 910 1819 387 1819 909 1819 909 1820 911 1820 910 1820 912 1821 910 1821 911 1821 911 1822 913 1822 912 1822 914 1823 912 1823 913 1823 913 1824 915 1824 914 1824 916 1825 914 1825 915 1825 915 1826 917 1826 916 1826 918 1827 916 1827 917 1827 917 1828 919 1828 918 1828 920 1829 918 1829 919 1829 919 1830 923 1830 920 1830 921 1831 920 1831 923 1831 923 1832 922 1832 921 1832 823 1833 381 1833 924 1833 924 1834 805 1834 823 1834 780 1835 781 1835 819 1835 380 1836 819 1836 781 1836 781 1837 780 1837 174 1837 174 1838 380 1838 781 1838 198 1839 196 1839 805 1839 805 1840 924 1840 198 1840 198 1841 924 1841 381 1841

+
+
+
+
+ + + + 0.00000 0.00000 0.00000 + 0 0 1 0.00000 + 0 1 0 -0.00000 + 1 0 0 0.00000 + 1.00000 1.00000 1.00000 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/URDFs/sr_description/package.xml b/URDFs/sr_description/package.xml new file mode 100644 index 0000000..ddd3df7 --- /dev/null +++ b/URDFs/sr_description/package.xml @@ -0,0 +1,53 @@ + + + + + sr_description + 1.4.0 + sr_description contains the description for Shadow Robot's Hands. + Shadow Robot's software team + + GPL + + http://ros.org/wiki/sr_description + https://github.com/shadow-robot/sr_common + https://github.com/shadow-robot/sr_common/issues + + + catkin + + + xacro + position_controllers + joint_trajectory_controller + + + liburdfdom-tools + liburdfdom-dev + urdf + gtest + + diff --git a/URDFs/sr_description/robots/sr_hand.urdf b/URDFs/sr_description/robots/sr_hand.urdf new file mode 100644 index 0000000..cbc12bd --- /dev/null +++ b/URDFs/sr_description/robots/sr_hand.urdf @@ -0,0 +1,29 @@ +gazebo_ros_control/DefaultRobotHWSimfalseGazebo/Whitefalse11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterface11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterface11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfaceGazebo/Grey11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfacetrue11sr_mechanism_model/J0Transmission1EffortJointInterfacePositionJointInterfacetrue1111000.0rh_ffdistal_collisionrh_ffdistal_collisiontruerh_ffdistal100.0contacts/rh_ff/distaltrue11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfaceGazebo/Grey11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfacetrue11sr_mechanism_model/J0Transmission1EffortJointInterfacePositionJointInterfacetrue1111000.0rh_mfdistal_collisionrh_mfdistal_collisiontruerh_mfdistal100.0contacts/rh_mf/distaltrue11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfaceGazebo/Grey11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfacetrue11sr_mechanism_model/J0Transmission1EffortJointInterfacePositionJointInterfacetrue1111000.0rh_rfdistal_collisionrh_rfdistal_collisiontruerh_rfdistal100.0contacts/rh_rf/distaltrue11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfacetrue11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfaceGazebo/Grey11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfacetrue11sr_mechanism_model/J0Transmission1EffortJointInterfacePositionJointInterfacetrue1111000.0rh_lfdistal_collisionrh_lfdistal_collisiontruerh_lfdistal100.0contacts/rh_lf/distaltrue11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfacefalse11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfacefalse11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterfacefalse11sr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterface1111000.0rh_thdistal_collisionrh_thdistal_collisiontruerh_thdistal100.0contacts/rh_th/distaltruesr_mechanism_model/SimpleTransmission1EffortJointInterfacePositionJointInterface \ No newline at end of file From af3a612746a4fc5c72d8c6f65913a3789ffe9f25 Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Tue, 11 Mar 2025 14:32:11 +0000 Subject: [PATCH 08/12] Updated RNE tests to check inertance matrix computed via RNE. Fixed some coordinate force propagation implementations to be correct and pass tests. 2 tests failing: RNE inertance matrices on 2 link robots. --- src/coordinates/coordinate_implementations.jl | 59 +++++++++++-------- src/interface.jl | 21 +++++++ src/joints/mechanism_joint.jl | 2 +- test/inverse_dynamics_test.jl | 55 ++++++++++++----- 4 files changed, 94 insertions(+), 43 deletions(-) diff --git a/src/coordinates/coordinate_implementations.jl b/src/coordinates/coordinate_implementations.jl index 94a9b0e..c643672 100644 --- a/src/coordinates/coordinate_implementations.jl +++ b/src/coordinates/coordinate_implementations.jl @@ -293,7 +293,6 @@ function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:JointSubspace} nothing end - _configuration(cache::CacheBundle, c::CMC{<:JointSubspace}) = get_q(cache, c.coord_data.joint) _velocity(cache::CacheBundle, c::CMC{<:JointSubspace}) = get_q̇(cache, c.coord_data.joint) _acceleration(cache::CacheBundle, c::CMC{<:JointSubspace}) = zero(get_q̇(cache, c.coord_data.joint)) @@ -490,28 +489,16 @@ function __acceleration!(cache::CacheBundle, cmc::CMC{<:QuaternionAttitude}) end function __propagate_opspace_force!(cache::CacheBundle, cmc::CMC{<:QuaternionAttitude}) -# c = cmc.coord_data -# fID = c.frameID - -# T⁰ᵃ = get_transform(cache, fID) -# R⁰ᵃ = rotor(T⁰ᵃ) -# ω⁰ᵃ = get_angular_vel(cache, fID) -# Ṙ⁰ᵃ = quaternion_derivative(R⁰ᵃ, ω⁰ᵃ) - -# Rᵗ⁰ = inv(c.target_rotation) - -# Ṙᵗᵃ = rotate(Rᵗ⁰, Ṙ⁰ᵃ, Val{false}()) # Dont normalize as this is a velocity - -# ż = bivector(Ṙᵗᵃ) - -# nothing + c = cmc.coord_data + rotor_wf = rotor(get_transform(cache, c.frameID)) + rotor_tw = inv(c.target_rotation) + E_wf = Transforms.quaternion_derivative_propagation(rotor_wf) + E_tw = Transforms.quatmul_matrix(rotor_tw) + E = E_tw * E_wf + f_view = f_cache_view(cache, cmc) - -# c = cmc.coord_data -# R⁰ᵃ = rotor(T⁰ᵃ) -# τ = cross(configuration(cache, cmc), f) -# get_frame_torques(cache)[fID] .+= τ -# nothing + τ = E' * SVector(0.0, f_view[1], f_view[2], f_view[3]) + get_frame_torques(cache)[c.frameID] += τ end _configuration(cache::CacheBundle, cmc::CMC{<:QuaternionAttitude}) = SVector{length(cmc), eltype(cache)}(z_cache_view(cache, cmc)) @@ -690,14 +677,23 @@ function __acceleration!(cache::CacheBundle, cmc::CMC{<:RotatedCoord}) end function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:RotatedCoord}) + # Sort out inputs c = mc.coord_data f_view = f_cache_view(cache, mc) + @assert length(f_view) == 3 + f = f_view[SVector(1, 2, 3)] # Get the force applied to the coord as an SVector f_ret = f_cache_view(cache, cache[c.world_frame_coord]) + R = rotor(get_transform(cache, c.frameID)) + z::SVector = _configuration(cache, c.world_frame_coord) + + # Apply force R * f + f_ret .+= R * f + # Apply torque R * cross(z, f) + τ = cross(R*f, z) + get_frame_torques(cache)[c.frameID] += τ nothing end - - _configuration(cache::CacheBundle, cmc::CMC{<:RotatedCoord}) = SVector{length(cmc)}(z_cache_view(cache, cmc)) _velocity(cache::CacheBundle, cmc::CMC{<:RotatedCoord}) = SVector{length(cmc)}(ż_cache_view(cache, cmc)) _jacobian(cache::CacheBundle, cmc::CMC{<:RotatedCoord}) = J_cache_view(cache, cmc) @@ -747,8 +743,8 @@ function __jacobian!(cache::CacheBundle, cmc::CMC{<:UnrotatedCoord}) J = J_cache_view(cache, cmc) fill!(J, zero(eltype(J))) # TODO do this once rather than every time J_ret = _vms_jacobian_result_view(cache, J, c.frameID) - # return RSz * -J_ωb + R⁻¹*J_z - # mul!(J, RSz, -J_ωb, R⁻¹, J_z) + # return RSz * -J_ωb + R*J_z + # mul!(J, RSz, -J_ωb, R, J_z) @assert length(c) == 3 for i in axes(J_ret, 1), j in axes(J_ret, 2) J_ij = zero(eltype(J_ret)) @@ -784,9 +780,20 @@ function __acceleration!(cache::CacheBundle, cmc::CMC{<:UnrotatedCoord}) end function __propagate_opspace_force!(cache::CacheBundle, mc::CMC{<:UnrotatedCoord}) + # Sort out inputs c = mc.coord_data f_view = f_cache_view(cache, mc) + @assert length(f_view) == 3 + f = f_view[SVector(1, 2, 3)] # Get the force applied to the coord as an SVector f_ret = f_cache_view(cache, cache[c.link_frame_coord]) + R = rotor(get_transform(cache, c.frameID)) + z::SVector = _configuration(cache, c.link_frame_coord) + + # Apply force inv(R) * f + f_ret .+= inv(R) * f + # Apply torque z × (inv(R) * f) + τ = cross(R*z, f) + get_frame_torques(cache)[c.frameID] += τ nothing end diff --git a/src/interface.jl b/src/interface.jl index b560f80..6118fd0 100644 --- a/src/interface.jl +++ b/src/interface.jl @@ -571,6 +571,27 @@ function inverse_dynamics!(bundle::MechRNEBundle, t, q, q̇, q̈, gravity) get_u(bundle) end +function _RNE_inertance_matrix!(M::Matrix, bundle::MechRNEBundle, t, q) + N = ndof(bundle.mechanism) + @assert size(M) == (N, N) + + q̇ = get_q̇(bundle) + q̈ = get_q̈(bundle) + g = get_gravity(bundle)[] + for j = 1:N + # Zero velocity and gravity + fill!(q̇, zero(eltype(q̇))) + g = zero(g) + # Set acceleration for one joint + fill!(q̈, zero(eltype(q̈))) + q̈[j] = 1.0 + # Compute inverse dynamics + u = inverse_dynamics!(bundle, t, q, q̇, q̈, g) + M[:, j] .= u + end + M +end + #==============================================================================# const VMS_CONTROL_NOTE = """ diff --git a/src/joints/mechanism_joint.jl b/src/joints/mechanism_joint.jl index a70c77d..98d4792 100644 --- a/src/joints/mechanism_joint.jl +++ b/src/joints/mechanism_joint.jl @@ -166,7 +166,7 @@ function _apply_joint_force_to_frames!( childFrameID::CompiledFrameID, u::Real) # Axis in world frame - axis = rotor(get_transform(bundle, parentFrameID)) * jointData.axis + axis = rotor(get_transform(bundle, parentFrameID)) * rotor(jointData.transform) * jointData.axis get_frame_torques(bundle)[parentFrameID] -= axis * u get_frame_torques(bundle)[childFrameID] += axis * u nothing diff --git a/test/inverse_dynamics_test.jl b/test/inverse_dynamics_test.jl index 7dcf2f5..501af79 100644 --- a/test/inverse_dynamics_test.jl +++ b/test/inverse_dynamics_test.jl @@ -1,4 +1,4 @@ -function test_inverse_dynamics(m; N=20) +function test_inverse_dynamics(m; N=3) rng = MersenneTwister(1234) for i = 1:N @@ -30,26 +30,49 @@ function _test_inverse_dynamics(m, time, q, q̇, q̈, gravity; rng=MersenneTwist # Run inverse dynamics then forward dynamics, and compare the acceleration inverse_dynamics!(icache, time, q, q̇, q̈, gravity) dynamics!(dcache, time, q, q̇, gravity, get_u(icache)) - @test get_q̈(dcache) ≈ q̈ atol=1e-7 rtol=1e-7 + skip_if_nan = any(isnan, get_q̈(dcache)) + skip_if_nan || @test get_q̈(dcache) ≈ q̈ atol=1e-7 rtol=1e-7 ############################ # Test 3 # Run inverse dynamics with a single coordinate and compare to jacobian transpose method VMRobotControl._inverse_dynamics_set_inputs!(icache, time, q, 0 .* q̇, 0 .* q̈, 0 * gravity) VMRobotControl._inverse_dynamics_forward_pass!(icache) - for coordID in values(m.rbtree.coord_id_map) - VMRobotControl._inverse_dynamics_zero!(icache) - # Apply random force to the coordinate - f = randn(rng, length(icache[coordID])) - VMRobotControl.f_cache_view(icache, icache[coordID]) .+= f - VMRobotControl._inverse_dynamics_backward_pass_a!(icache) - VMRobotControl._inverse_dynamics_backward_pass_b!(icache) - VMRobotControl._inverse_dynamics_backward_pass_c!(icache) - VMRobotControl._inverse_dynamics_backward_pass_d!(icache) - J = jacobian(dcache, coordID) - @test get_u(icache) ≈ -J' * f + + + for coords in values(m.rbtree.coordinates) + for vec in coords.tup + for coord in vec + _test_one_coord_vs_jacobian(icache, dcache, rng, coord) + end + end end - # if isa(m, CompiledMechanism) - # elseif isa(m, CompiledVirtualMechanismSystem) - # end + + ############################ + # Test 4 + # Test inertance matrix computed via RNE + _test_RNE_inertance_matrix(icache, dcache, time, q) + +end + +function _test_one_coord_vs_jacobian(icache, dcache, rng, coord) + VMRobotControl._inverse_dynamics_zero!(icache) + # Apply random force to the coordinate + f = randn(rng, length(coord)) + VMRobotControl.f_cache_view(icache, coord) .+= f + VMRobotControl._inverse_dynamics_backward_pass_b!(icache) + VMRobotControl._inverse_dynamics_backward_pass_c!(icache) + VMRobotControl._inverse_dynamics_backward_pass_d!(icache) + J = jacobian(dcache, coord) + failed = !((@test get_u(icache) ≈ -J' * f) isa Test.Pass) + failed && @info "Failed coord: $coord" +end + + +function _test_RNE_inertance_matrix(icache, dcache, t, q) + N = ndof(icache) + Mʳⁿᵉ = zeros(N, N) + VMRobotControl._RNE_inertance_matrix!(Mʳⁿᵉ, icache, t, q) + M = inertance_matrix!(dcache, t, q) + @test Mʳⁿᵉ ≈ M atol=1e-7 rtol=1e-7 end From 45edc91ba7b2d7d9a3d8dcccb814a088e6e5f861 Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Tue, 11 Mar 2025 17:23:47 +0000 Subject: [PATCH 09/12] Fixed RNE_inertance_matrix by considering only inertance components. --- RSONs/rsons/trivial2link.rson | 2 +- examples/rne_visualization.jl | 34 ++++++++++++++++++++++------------ src/interface.jl | 18 ++++++++++++++++-- 3 files changed, 39 insertions(+), 15 deletions(-) diff --git a/RSONs/rsons/trivial2link.rson b/RSONs/rsons/trivial2link.rson index c545b2e..c51afa1 100644 --- a/RSONs/rsons/trivial2link.rson +++ b/RSONs/rsons/trivial2link.rson @@ -1,7 +1,7 @@ { "rson_version": "0.1.0", "type": "mechanism", - "name": "robot2L", + "name": "trivial2link", "frames": [ "root_frame", "L1_frame", diff --git a/examples/rne_visualization.jl b/examples/rne_visualization.jl index 2c67890..d13369c 100644 --- a/examples/rne_visualization.jl +++ b/examples/rne_visualization.jl @@ -39,7 +39,8 @@ using # end # We compile the mechanism, and setup an ODE problem to simulate the dynamics of the rail robot. -m = compiled_mechanisms[end] +# m = compiled_mechanisms[5] +m = compile(parseRSON("./RSONs/rsons/trivial2link.rson")) cache = Observable(new_inverse_dynamics_cache(m)) # @testset test_inverse_dynamics(m) @@ -50,9 +51,8 @@ begin t = 0.0 q = [0.0, π/2] -q = zero_q(m) + randn(7) -q̇ = zero_q̇(m) + randn(7) -g = SVector{3, Float64}(0.0, 0.0, -10) #+ rand(SVector{3, Float64}) +q̇ = zero_q̇(m) +g = SVector{3, Float64}(0.0, 0.0, 0.0) # rng = MersenneTwister(1234) # t = 0.0 @@ -62,21 +62,30 @@ g = SVector{3, Float64}(0.0, 0.0, -10) #+ rand(SVector{3, Float64}) u = zero_u(m) -dcache = new_dynamics_cache(m) -dynamics!(dcache, t, q, q̇, g, u) -q̈ = get_q̈(dcache) +# dcache = new_dynamics_cache(m) +# dynamics!(dcache, t, q, q̇, g, u) +# q̈ = get_q̈(dcache) +onehot_q̈ = [1.0, 0.0] +q̈ = onehot_q̈ + VMRobotControl._inverse_dynamics_set_inputs!(bundle, t, q, q̇, q̈, g) VMRobotControl._inverse_dynamics_forward_pass!(bundle) VMRobotControl._inverse_dynamics_zero!(bundle) VMRobotControl._inverse_dynamics_backward_pass_a!(bundle) VMRobotControl._inverse_dynamics_backward_pass_b!(bundle) -VMRobotControl._inverse_dynamics_backward_pass_c!(bundle) -VMRobotControl._inverse_dynamics_backward_pass_d!(bundle) +# VMRobotControl._inverse_dynamics_backward_pass_c!(bundle) +# VMRobotControl._inverse_dynamics_backward_pass_d!(bundle) + +# @show get_u(bundle) + +# @show inverse_dynamics!(bundle, t, q, zero_q̇(m), onehot_q̈, 0*g) + +# _test_RNE_inertance_matrix(bundle, dcache, t, q) # q̈_out = dynamics!(dcache, t, q, q̇, g, get_u(bundle)) -@test get_u(cache[]) ≈ u atol=1e-7 rtol=1e-7 +# @test get_u(cache[]) ≈ u atol=1e-7 rtol=1e-7 # @test q̈ ≈ q̈_out atol=1e-7 rtol=1e-7 end @@ -86,6 +95,7 @@ fig = Figure() display(fig) ls = LScene(fig[1, 1]; show_axis=false) robotsketch!(ls, cache; linewidth=3, scale=0.05) +robotvisualize!(ls, cache) frameIDs = get_compiled_frameID.((cache[],), frames(cache[])) tfs = map(cache) do cache @@ -114,8 +124,8 @@ arrows!(ls, positions, τs; lengthscale=τ_scale, arrowsize=0.04, color=:blue, ) end -using Test, Random -Revise.includet("../test/inverse_dynamics_test.jl") +# using Test, Random +# Revise.includet("../test/inverse_dynamics_test.jl") @testset test_inverse_dynamics(m) # function create_rotated_cylinder_mesh(N1, N2, r1, r2, ϕ) diff --git a/src/interface.jl b/src/interface.jl index 6118fd0..9394256 100644 --- a/src/interface.jl +++ b/src/interface.jl @@ -585,8 +585,22 @@ function _RNE_inertance_matrix!(M::Matrix, bundle::MechRNEBundle, t, q) # Set acceleration for one joint fill!(q̈, zero(eltype(q̈))) q̈[j] = 1.0 - # Compute inverse dynamics - u = inverse_dynamics!(bundle, t, q, q̇, q̈, g) + # Compute inverse dynamics, on inertance/generic components only. + u = begin + _inverse_dynamics_set_inputs!(bundle, t, q, q̇, q̈, g) + _inverse_dynamics_forward_pass!(bundle) + _inverse_dynamics_zero!(bundle) + # WARNING any generic components which applies a force other than due + # to an inertance will break this computation. + inertance_components = get_inertance_components(bundle.mechanism) + foreach(inertance_components) do component + _add_opspace_force!(bundle, component) + end + _inverse_dynamics_backward_pass_b!(bundle) + _inverse_dynamics_backward_pass_c!(bundle) + _inverse_dynamics_backward_pass_d!(bundle) + get_u(bundle) + end M[:, j] .= u end M From b5b08fa285f07703d47e8e7a597ee6caa0be27e2 Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Wed, 12 Mar 2025 17:55:05 +0000 Subject: [PATCH 10/12] added allocs test for RNE --- test/inverse_dynamics_test.jl | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/test/inverse_dynamics_test.jl b/test/inverse_dynamics_test.jl index 501af79..c1ab010 100644 --- a/test/inverse_dynamics_test.jl +++ b/test/inverse_dynamics_test.jl @@ -53,6 +53,11 @@ function _test_inverse_dynamics(m, time, q, q̇, q̈, gravity; rng=MersenneTwist # Test inertance matrix computed via RNE _test_RNE_inertance_matrix(icache, dcache, time, q) + ############################ + # Test 5 + # Check no allocs + allocs = @allocated inverse_dynamics!(icache, time, q, q̇, q̈, gravity) + @test allocs == 0 end function _test_one_coord_vs_jacobian(icache, dcache, rng, coord) From b923073a5a0d694444ffef03ce6291bfb8fa7835 Mon Sep 17 00:00:00 2001 From: Daniel Larby Date: Wed, 23 Apr 2025 17:31:16 +0100 Subject: [PATCH 11/12] Update some rsons to use DAE instead of obj. --- RSONs/rsons/franka_panda/pandaDrill.rson | 16 ++++++++-------- RSONs/rsons/franka_panda/pandaVeterinarian.rson | 16 ++++++++-------- ext/VMRobotControlMakieExt.jl | 7 +++++++ 3 files changed, 23 insertions(+), 16 deletions(-) diff --git a/RSONs/rsons/franka_panda/pandaDrill.rson b/RSONs/rsons/franka_panda/pandaDrill.rson index 87388a9..c18ac0d 100644 --- a/RSONs/rsons/franka_panda/pandaDrill.rson +++ b/RSONs/rsons/franka_panda/pandaDrill.rson @@ -372,49 +372,49 @@ "type": "mesh", "frame": "root_frame", "material": "panda_white", - "filename": "./meshes/visual/link0.obj" + "filename": "./meshes/visual/link0.dae" }, "L1_mesh": { "type": "mesh", "frame": "L1_frame", "material": "panda_white", - "filename": "./meshes/visual/link1.obj" + "filename": "./meshes/visual/link1.dae" }, "L2_mesh": { "type": "mesh", "frame": "L2_frame", "material": "panda_white", - "filename": "./meshes/visual/link2.obj" + "filename": "./meshes/visual/link2.dae" }, "L3_mesh": { "type": "mesh", "frame": "L3_frame", "material": "panda_white", - "filename": "./meshes/visual/link3.obj" + "filename": "./meshes/visual/link3.dae" }, "L4_mesh": { "type": "mesh", "frame": "L4_frame", "material": "panda_white", - "filename": "./meshes/visual/link4.obj" + "filename": "./meshes/visual/link4.dae" }, "L5_mesh": { "type": "mesh", "frame": "L5_frame", "material": "panda_white", - "filename": "./meshes/visual/link5.obj" + "filename": "./meshes/visual/link5.dae" }, "L6_mesh": { "type": "mesh", "frame": "L6_frame", "material": "panda_white", - "filename": "./meshes/visual/link6.obj" + "filename": "./meshes/visual/link6.dae" }, "L7_mesh": { "type": "mesh", "frame": "L7_frame", "material": "panda_white", - "filename": "./meshes/visual/link7.obj" + "filename": "./meshes/visual/link7.dae" }, "drill_mount": { "type": "cylinder", diff --git a/RSONs/rsons/franka_panda/pandaVeterinarian.rson b/RSONs/rsons/franka_panda/pandaVeterinarian.rson index 3c89feb..448e888 100644 --- a/RSONs/rsons/franka_panda/pandaVeterinarian.rson +++ b/RSONs/rsons/franka_panda/pandaVeterinarian.rson @@ -328,49 +328,49 @@ "type": "mesh", "frame": "root_frame", "material": "panda_white", - "filename": "./meshes/visual/link0.obj" + "filename": "./meshes/visual/link0.dae" }, "L1_mesh": { "type": "mesh", "frame": "L1_frame", "material": "panda_white", - "filename": "./meshes/visual/link1.obj" + "filename": "./meshes/visual/link1.dae" }, "L2_mesh": { "type": "mesh", "frame": "L2_frame", "material": "panda_white", - "filename": "./meshes/visual/link2.obj" + "filename": "./meshes/visual/link2.dae" }, "L3_mesh": { "type": "mesh", "frame": "L3_frame", "material": "panda_white", - "filename": "./meshes/visual/link3.obj" + "filename": "./meshes/visual/link3.dae" }, "L4_mesh": { "type": "mesh", "frame": "L4_frame", "material": "panda_white", - "filename": "./meshes/visual/link4.obj" + "filename": "./meshes/visual/link4.dae" }, "L5_mesh": { "type": "mesh", "frame": "L5_frame", "material": "panda_white", - "filename": "./meshes/visual/link5.obj" + "filename": "./meshes/visual/link5.dae" }, "L6_mesh": { "type": "mesh", "frame": "L6_frame", "material": "panda_white", - "filename": "./meshes/visual/link6.obj" + "filename": "./meshes/visual/link6.dae" }, "L7_mesh": { "type": "mesh", "frame": "L7_frame", "material": "panda_white", - "filename": "./meshes/visual/link7.obj" + "filename": "./meshes/visual/link7.dae" }, "frame": { "type": "mesh", diff --git a/ext/VMRobotControlMakieExt.jl b/ext/VMRobotControlMakieExt.jl index 76b3356..af2234a 100644 --- a/ext/VMRobotControlMakieExt.jl +++ b/ext/VMRobotControlMakieExt.jl @@ -298,6 +298,13 @@ function _sketchjoint!(ax, joint::RailData, cache::Observable; (s,) end +function _sketchjoint!(ax, joint::ReferenceJoint, cache::Observable; + scale, meshcolor, linecolor, linewidth, shading) + # TODO implement + () +end + + ################################################################################ # Component Sketch ################################################################################ From 4bd60bd77db5a4f49b3662a6bce78c4c5e7d0cb3 Mon Sep 17 00:00:00 2001 From: Larbino1 Date: Thu, 12 Jun 2025 18:16:11 +0100 Subject: [PATCH 12/12] Adds CompiledVisual type, and changes Visual, for better parsing/saving of rsons/urdfs. Retains filename if mesh for a visual came from a file. Some minor updates to RNE related code. --- .../rsons/franka_panda/calibrated_frodo.rson | 684 ++++++++++++++++++ ext/VMRobotControlMakieExt.jl | 16 +- src/VMRobotControl.jl | 3 + src/compiled_mechanisms.jl | 17 +- src/components/components.jl | 87 ++- src/interface.jl | 14 +- src/joints/joint_definitions.jl | 15 +- src/rson/parsing.jl | 20 +- src/rson/rson.jl | 3 +- src/rson/serializing.jl | 53 +- src/type_stable_collection.jl | 4 +- src/urdf/parse_urdf.jl | 42 +- src/urdf/urdf.jl | 2 + 13 files changed, 867 insertions(+), 93 deletions(-) create mode 100644 RSONs/rsons/franka_panda/calibrated_frodo.rson diff --git a/RSONs/rsons/franka_panda/calibrated_frodo.rson b/RSONs/rsons/franka_panda/calibrated_frodo.rson new file mode 100644 index 0000000..d96a98e --- /dev/null +++ b/RSONs/rsons/franka_panda/calibrated_frodo.rson @@ -0,0 +1,684 @@ +{ + "rson_version": "0.1.0", + "name": "fr3", + "type": "mechanism", + "frames": [ + "base", + "fr3_link0", + "fr3_link1", + "fr3_link2", + "fr3_link3", + "fr3_link4", + "fr3_link5", + "fr3_link6", + "fr3_link7", + "fr3_link8" + ], + "joints": { + "base_joint": { + "type": "rigid", + "origin": [ + 0.0, + 0.0, + 0.0 + ], + "rotation": [ + 1.0, + 0.0, + 0.0, + 0.0 + ], + "parent": "base", + "child": "fr3_link0" + }, + "fr3_joint1": { + "type": "revolute", + "axis": [ + 0.0, + 0.0, + 1.0 + ], + "origin": [ + 0.0, + 0.0, + 0.333 + ], + "rotation": [ + 1.0, + 0.0, + 0.0, + 0.0 + ], + "parent": "fr3_link0", + "child": "fr3_link1" + }, + "fr3_joint2": { + "type": "revolute", + "axis": [ + 0.0, + 0.0, + 1.0 + ], + "origin": [ + 0.0, + 0.0, + 0.0 + ], + "rotation": [ + 0.7071067811865475, + -0.7071067811865477, + 0.0, + 0.0 + ], + "parent": "fr3_link1", + "child": "fr3_link2" + }, + "fr3_joint3": { + "type": "revolute", + "axis": [ + 0.0, + 0.0, + 1.0 + ], + "origin": [ + 0.0, + -0.316, + 0.0 + ], + "rotation": [ + 0.7071067811865475, + 0.7071067811865477, + 0.0, + 0.0 + ], + "parent": "fr3_link2", + "child": "fr3_link3" + }, + "fr3_joint4": { + "type": "revolute", + "axis": [ + 0.0, + 0.0, + 1.0 + ], + "origin": [ + 0.0825, + 0.0, + 0.0 + ], + "rotation": [ + 0.7071067811865475, + 0.7071067811865477, + 0.0, + 0.0 + ], + "parent": "fr3_link3", + "child": "fr3_link4" + }, + "fr3_joint5": { + "type": "revolute", + "axis": [ + 0.0, + 0.0, + 1.0 + ], + "origin": [ + -0.0825, + 0.384, + 0.0 + ], + "rotation": [ + 0.7071067811865475, + -0.7071067811865477, + 0.0, + 0.0 + ], + "parent": "fr3_link4", + "child": "fr3_link5" + }, + "fr3_joint6": { + "type": "revolute", + "axis": [ + 0.0, + 0.0, + 1.0 + ], + "origin": [ + 0.0, + 0.0, + 0.0 + ], + "rotation": [ + 0.7071067811865475, + 0.7071067811865477, + 0.0, + 0.0 + ], + "parent": "fr3_link5", + "child": "fr3_link6" + }, + "fr3_joint7": { + "type": "revolute", + "axis": [ + 0.0, + 0.0, + 1.0 + ], + "origin": [ + 0.088, + 0.0, + 0.0 + ], + "rotation": [ + 0.7071067811865475, + 0.7071067811865477, + 0.0, + 0.0 + ], + "parent": "fr3_link6", + "child": "fr3_link7" + }, + "fr3_joint8": { + "type": "rigid", + "origin": [ + 0.0, + 0.0, + 0.107 + ], + "rotation": [ + 1.0, + 0.0, + 0.0, + 0.0 + ], + "parent": "fr3_link7", + "child": "fr3_link8" + } + }, + "visuals": { + "fr3_link1_unnamed_visual_-3404766294979027099": { + "type": "mesh", + "frame": "fr3_link1", + "material": [ + 0.800000011920929, + 0.800000011920929, + 0.800000011920929, + 1.0 + ], + "filename": "./meshes/visual/link1.dae" + }, + "fr3_link2_unnamed_visual_-4140561980213910905": { + "type": "mesh", + "frame": "fr3_link2", + "material": [ + 0.800000011920929, + 0.800000011920929, + 0.800000011920929, + 1.0 + ], + "filename": "./meshes/visual/link2.dae" + }, + "fr3_link6_unnamed_visual_2236111102097693851": { + "type": "mesh", + "frame": "fr3_link6", + "material": [ + 0.800000011920929, + 0.800000011920929, + 0.800000011920929, + 1.0 + ], + "filename": "./meshes/visual/link6.dae" + }, + "fr3_link5_unnamed_visual_-1890705846576942535": { + "type": "mesh", + "frame": "fr3_link5", + "material": [ + 0.800000011920929, + 0.800000011920929, + 0.800000011920929, + 1.0 + ], + "filename": "./meshes/visual/link5.dae" + }, + "fr3_link3_unnamed_visual_6755134459629763805": { + "type": "mesh", + "frame": "fr3_link3", + "material": [ + 0.800000011920929, + 0.800000011920929, + 0.800000011920929, + 1.0 + ], + "filename": "./meshes/visual/link3.dae" + }, + "fr3_link0_unnamed_visual_3093320216205656838": { + "type": "mesh", + "frame": "fr3_link0", + "material": [ + 0.800000011920929, + 0.800000011920929, + 0.800000011920929, + 1.0 + ], + "filename": "./meshes/visual/link0.dae" + }, + "fr3_link4_unnamed_visual_-83914994309823005": { + "type": "mesh", + "frame": "fr3_link4", + "material": [ + 0.800000011920929, + 0.800000011920929, + 0.800000011920929, + 1.0 + ], + "filename": "./meshes/visual/link4.dae" + }, + "fr3_link7_unnamed_visual_5986153092474165795": { + "type": "mesh", + "frame": "fr3_link7", + "material": [ + 0.800000011920929, + 0.800000011920929, + 0.800000011920929, + 1.0 + ], + "filename": "./meshes/visual/link7.dae" + } + }, + "coordinates": { + "fr3_link7_mass_coord": { + "type": "frame_point", + "frame": "fr3_link7", + "point": [ + 0.0045225817, + 0.0086261921, + -0.0161633251 + ] + }, + "fr3_link4_mass_coord": { + "type": "frame_point", + "frame": "fr3_link4", + "point": [ + -0.0459100965, + 0.063049296, + -0.0085187868 + ] + }, + "fr3_link0_inertia_coord": { + "type": "frame_angular_velocity", + "frame": "fr3_link0" + }, + "fr3_link2_mass_coord": { + "type": "frame_point", + "frame": "fr3_link2", + "point": [ + 0.0031828864, + -0.0743221644, + 0.0088146084 + ] + }, + "fr3_link6_inertia_coord": { + "type": "frame_angular_velocity", + "frame": "fr3_link6" + }, + "fr3_link7_inertia_coord": { + "type": "frame_angular_velocity", + "frame": "fr3_link7" + }, + "fr3_link4_inertia_coord": { + "type": "frame_angular_velocity", + "frame": "fr3_link4" + }, + "fr3_link5_inertia_coord": { + "type": "frame_angular_velocity", + "frame": "fr3_link5" + }, + "fr3_link3_mass_coord": { + "type": "frame_point", + "frame": "fr3_link3", + "point": [ + 0.0407015686, + -0.0048200565, + -0.0289730823 + ] + }, + "fr3_link0_mass_coord": { + "type": "frame_point", + "frame": "fr3_link0", + "point": [ + -0.0172, + 0.0004, + 0.0745 + ] + }, + "fr3_link5_mass_coord": { + "type": "frame_point", + "frame": "fr3_link5", + "point": [ + -0.0016039605, + 0.0292536262, + -0.097296599 + ] + }, + "fr3_link1_mass_coord": { + "type": "frame_point", + "frame": "fr3_link1", + "point": [ + 4.128e-7, + -0.0181251324, + -0.038603597 + ] + }, + "fr3_link1_inertia_coord": { + "type": "frame_angular_velocity", + "frame": "fr3_link1" + }, + "fr3_link3_inertia_coord": { + "type": "frame_angular_velocity", + "frame": "fr3_link3" + }, + "fr3_link6_mass_coord": { + "type": "frame_point", + "frame": "fr3_link6", + "point": [ + 0.0597131221, + -0.0410294666, + -0.0101692726 + ] + }, + "fr3_link2_inertia_coord": { + "type": "frame_angular_velocity", + "frame": "fr3_link2" + } + }, + "components": { + "fr3_link1_inertia": { + "type": "inertia", + "coord": "fr3_link1_inertia_coord", + "inertia": [ + [ + 0.023927316485107913, + 1.3317903455714081e-5, + -0.00011404774918616684 + ], + [ + 1.3317903455714081e-5, + 0.0224821613275756, + -0.0019950320628240115 + ], + [ + -0.00011404774918616684, + -0.0019950320628240115, + 0.006350098258530016 + ] + ] + }, + "fr3_link2_inertia": { + "type": "inertia", + "coord": "fr3_link2_inertia_coord", + "inertia": [ + [ + 0.041938946257609425, + 0.00020257331521090626, + 0.004077784227179924 + ], + [ + 0.00020257331521090626, + 0.02514514885014724, + -0.0042252158006570156 + ], + [ + 0.004077784227179924, + -0.0042252158006570156, + 0.06170214472888839 + ] + ] + }, + "fr3_link3_inertia": { + "type": "inertia", + "coord": "fr3_link3_inertia_coord", + "inertia": [ + [ + 0.02410142547240885, + 0.002404694559042109, + -0.002856269270114313 + ], + [ + 0.002404694559042109, + 0.01974053266708178, + -0.002104212683891874 + ], + [ + -0.002856269270114313, + -0.002104212683891874, + 0.019044494482244823 + ] + ] + }, + "fr3_link0_inertia": { + "type": "inertia", + "coord": "fr3_link0_inertia_coord", + "inertia": [ + [ + 0.009, + 0.0, + 0.002 + ], + [ + 0.0, + 0.0115, + 0.0 + ], + [ + 0.002, + 0.0, + 0.0085 + ] + ] + }, + "fr3_link5_inertia": { + "type": "inertia", + "coord": "fr3_link5_inertia_coord", + "inertia": [ + [ + 0.051610278463662895, + -0.005715173387783472, + -0.0035673167625872135 + ], + [ + -0.005715173387783472, + 0.04787729713371481, + 0.010673985108535986 + ], + [ + -0.0035673167625872135, + 0.010673985108535986, + 0.016423625579357254 + ] + ] + }, + "fr3_link4_inertia": { + "type": "inertia", + "coord": "fr3_link4_inertia_coord", + "inertia": [ + [ + 0.03452998321913202, + 0.01322552265982813, + 0.01015142998484113 + ], + [ + 0.01322552265982813, + 0.028881621933049058, + -0.0009762833870704552 + ], + [ + 0.01015142998484113, + -0.0009762833870704552, + 0.04125471171146641 + ] + ] + }, + "fr3_link6_inertia": { + "type": "inertia", + "coord": "fr3_link6_inertia_coord", + "inertia": [ + [ + 0.005412333594383447, + 0.006193456360285834, + 0.0014219289306117652 + ], + [ + 0.006193456360285834, + 0.014058329545509979, + -0.0013140753741120031 + ], + [ + 0.0014219289306117652, + -0.0013140753741120031, + 0.016080817924212554 + ] + ] + }, + "fr3_link7_inertia": { + "type": "inertia", + "coord": "fr3_link7_inertia_coord", + "inertia": [ + [ + 0.00021092389150104718, + -2.433299114461931e-5, + 4.564480393778983e-5 + ], + [ + -2.433299114461931e-5, + 0.00017718568002411474, + 8.744070223226438e-5 + ], + [ + 4.564480393778983e-5, + 8.744070223226438e-5, + 5.993190599659971e-5 + ] + ] + }, + "GravityCompensator_2176280971267482541": { + "type": "gravity_compensator", + "coord": "fr3_link7_mass_coord", + "mass": 0.6271432862, + "gravity": [ + 0.0, + 0.0, + -9.81 + ] + }, + "GravityCompensator_10327230358662219347": { + "type": "gravity_compensator", + "coord": "fr3_link5_mass_coord", + "mass": 2.3271207594, + "gravity": [ + 0.0, + 0.0, + -9.81 + ] + }, + "GravityCompensator_5924892284802250340": { + "type": "gravity_compensator", + "coord": "fr3_link0_mass_coord", + "mass": 2.3966, + "gravity": [ + 0.0, + 0.0, + -9.81 + ] + }, + "GravityCompensator_15399867256900633743": { + "type": "gravity_compensator", + "coord": "fr3_link2_mass_coord", + "mass": 2.9355370338, + "gravity": [ + 0.0, + 0.0, + -9.81 + ] + }, + "GravityCompensator_2407000335280166113": { + "type": "gravity_compensator", + "coord": "fr3_link4_mass_coord", + "mass": 2.6155955791, + "gravity": [ + 0.0, + 0.0, + -9.81 + ] + }, + "GravityCompensator_18229251590064689770": { + "type": "gravity_compensator", + "coord": "fr3_link3_mass_coord", + "mass": 2.2449013699, + "gravity": [ + 0.0, + 0.0, + -9.81 + ] + }, + "GravityCompensator_5855140949912852515": { + "type": "gravity_compensator", + "coord": "fr3_link1_mass_coord", + "mass": 2.9274653454, + "gravity": [ + 0.0, + 0.0, + -9.81 + ] + }, + "GravityCompensator_11818839599249854824": { + "type": "gravity_compensator", + "coord": "fr3_link6_mass_coord", + "mass": 1.8170376524, + "gravity": [ + 0.0, + 0.0, + -9.81 + ] + }, + "fr3_link4_mass": { + "type": "point_mass", + "coord": "fr3_link4_mass_coord", + "mass": 2.6155955791 + }, + "fr3_link0_mass": { + "type": "point_mass", + "coord": "fr3_link0_mass_coord", + "mass": 2.3966 + }, + "fr3_link6_mass": { + "type": "point_mass", + "coord": "fr3_link6_mass_coord", + "mass": 1.8170376524 + }, + "fr3_link3_mass": { + "type": "point_mass", + "coord": "fr3_link3_mass_coord", + "mass": 2.2449013699 + }, + "fr3_link1_mass": { + "type": "point_mass", + "coord": "fr3_link1_mass_coord", + "mass": 2.9274653454 + }, + "fr3_link7_mass": { + "type": "point_mass", + "coord": "fr3_link7_mass_coord", + "mass": 0.6271432862 + }, + "fr3_link5_mass": { + "type": "point_mass", + "coord": "fr3_link5_mass_coord", + "mass": 2.3271207594 + }, + "fr3_link2_mass": { + "type": "point_mass", + "coord": "fr3_link2_mass_coord", + "mass": 2.9355370338 + } + } +} diff --git a/ext/VMRobotControlMakieExt.jl b/ext/VMRobotControlMakieExt.jl index af2234a..9aef804 100644 --- a/ext/VMRobotControlMakieExt.jl +++ b/ext/VMRobotControlMakieExt.jl @@ -19,6 +19,7 @@ using VMRobotControl: CompiledFrameID, CompiledJointID, CompiledCoordID, + CompiledVisual, VMSFrameID, VMSCoordID using VMRobotControl: @@ -503,21 +504,16 @@ function Makie.plot!(plot::RobotVisualize{Tuple{C}}) where C<:MechanismCacheBund frames = CompiledFrameID[] foreach(vis) do v - # geom = normal_mesh(v.geometry) - geom = v.geometry - if isa(geom, Mesh) - msh = Makie.mesh!(plot, geom; + v::CompiledVisual + msh = Makie.mesh!(plot, v.mesh; shading=plot.shading, color=v.color, specular=v.specular, shininess=v.shininess, transparency=plot.transparency - ) - push!(meshes, msh) - push!(frames, v.frame) - else - error("Unsupported geometry type: $(typeof(geom))") - end + ) + push!(meshes, msh) + push!(frames, v.frame) end function update_from_cache(cache) diff --git a/src/VMRobotControl.jl b/src/VMRobotControl.jl index 851fc61..605d8d9 100644 --- a/src/VMRobotControl.jl +++ b/src/VMRobotControl.jl @@ -224,6 +224,9 @@ import DiffResults: import GeometryBasics # Use import to avoid name conflicts +using GeometryBasics: + normal_mesh + using DigitalAssetExchangeFormatIO, FileIO, diff --git a/src/compiled_mechanisms.jl b/src/compiled_mechanisms.jl index 424632e..dc421b7 100644 --- a/src/compiled_mechanisms.jl +++ b/src/compiled_mechanisms.jl @@ -454,7 +454,14 @@ function _compile_component!( cd1 = reassign_frames(component_data, frame_id_map) cd2 = reassign_joints(cd1, joint_id_map) cd3 = reassign_coords(cd2, coord_id_map) - cc, idx = extend(cc, cd3) + cd4 = isa(cd3, Visual) ? compile_visual(cd3) : cd3 # this may return a vector of compiled visuals + if isa(cd4, AbstractVector) + for cd in cd4 + cc, idx = extend(cc, cd) + end + else + cc, idx = extend(cc, cd4) + end ret_component_id_map[id] = CompiledComponentID(idx) cc end @@ -513,7 +520,7 @@ inertances(m::CompiledMechanism) = filtertype(m.components, Inertance) storages(m::CompiledMechanism) = filtertype(m.components, Storage) dissipations(m::CompiledMechanism) = filtertype(m.components, Dissipation) generic_components(m::CompiledMechanism) = filtertype(m.components, GenericComponent) -visuals(m::CompiledMechanism) = filtertype(m.components, Visual) +visuals(m::CompiledMechanism) = filtertype(m.components, CompiledVisual) compile(m::Mechanism) = CompiledMechanism(m) @@ -538,15 +545,15 @@ get_compiled_coordID(m::CompiledMechanism, c::String) = get_compiled_coordID(m.r get_compiled_componentID(m::CompiledMechanism, c::String) = m.component_id_map[c] get_compiled_joint(m::CompiledMechanism, jointID::CompiledJointID) = joints(m)[jointID.idx] -get_compiled_coord(m::CompiledMechanism, coordID::CompiledCoordID) = coordinates(m)[coordID] -get_compiled_component(m::CompiledMechanism, componentID::CompiledComponentID) = components(m)[componentID] +get_compiled_coord(m::CompiledMechanism, coordID::CompiledCoordID) = coordinates(m)[coordID.depth][coordID.idx] +get_compiled_component(m::CompiledMechanism, componentID::CompiledComponentID) = components(m)[componentID.idx] Base.getindex(m::CompiledMechanism, id::CompiledJointID) = get_compiled_joint(m, id) Base.getindex(m::CompiledMechanism, id::CompiledCoordID) = get_compiled_coord(m, id) Base.getindex(m::CompiledMechanism, id::CompiledComponentID) = get_compiled_component(m, id) Base.setindex!(m::CompiledMechanism, val::J, id::CompiledJointID{J}) where J = joints(m)[id.idx] = val -Base.setindex!(m::CompiledMechanism, val::C, id::CompiledCoordID{C}) where C = coordinates(m)[id.idx] = val +Base.setindex!(m::CompiledMechanism, val::C, id::CompiledCoordID{C}) where C = coordinates(m)[id.depth][id.idx] = val Base.setindex!(m::CompiledMechanism, val::C, id::CompiledComponentID{C}) where C = components(m)[id.idx] = val get_force_components(m::CompiledMechanism) = filtertype(components(m), Union{Storage, Dissipation, Inertance, GenericComponent}) diff --git a/src/components/components.jl b/src/components/components.jl index 639c97f..ab6d7d4 100644 --- a/src/components/components.jl +++ b/src/components/components.jl @@ -378,41 +378,96 @@ end ##################################################### +struct MeshFromFile{M} # used for urdf/rson parsing/serializing + mesh::M + path::String +end + struct Visual{G, FID} <: ComponentData{Float64} frame::FID + transform::Union{Nothing, Transform{Float64}} geometry::G color::RGBAf specular::Float32 shininess::Float32 - function Visual(frame, geometry; color=RGBAf(1.0f0, 0.0f0, 1.0f0, 1.0f0), specular=0.2f0, shininess=32.0f0) + function Visual(frame, transform, geometry; color=RGBAf(1.0f0, 0.0f0, 1.0f0, 1.0f0), specular=0.2f0, shininess=32.0f0) if isa(geometry, GeometryBasics.GeometryPrimitive) - _mesh = GeometryBasics.normal_mesh(geometry) + # _mesh = GeometryBasics.normal_mesh(geometry) + new{typeof(geometry), typeof(frame)}(frame, transform, geometry, color, specular, shininess) elseif isa(geometry, GeometryBasics.Mesh) + _mesh = GeometryBasics.normal_mesh(geometry) + new{typeof(_mesh), typeof(frame)}(frame, transform, _mesh, color, specular, shininess) + elseif isa(geometry, MeshFromFile{<:GeometryBasics.Mesh}) _mesh = geometry + new{typeof(_mesh), typeof(frame)}(frame, transform, _mesh, color, specular, shininess) + elseif isa(geometry, MeshFromFile{DAEScene}) + new{typeof(geometry), typeof(frame)}(frame, transform, geometry, color, specular, shininess) else - error("Invalid geometry type: $(typeof(geometry))") + error("Unrecognized geometry type: $(typeof(geometry))") end - new{typeof(_mesh), typeof(frame)}(frame, _mesh, color, specular, shininess) end - function Visual(name, color, geometry) - # legacy constructor - Visual(name, geometry; color=color) - end + # function Visual(name, color, geometry) + # # legacy constructor + # Visual(name, geometry; color=color) + # end - function Visual(name, frame, color, geometry) - @warn "Visual(name, frame, color, geometry) is deprecated. Use Visual(frame, color, geometry) instead." - Visual(frame, color, geometry) - end - # Keyword constructor - Visual(; frame, geometry, color, specular, shininess) = Visual(frame, geometry; color=color, specular=specular, shininess=shininess) + # function Visual(name, frame, color, geometry) + # @warn "Visual(name, frame, color, geometry) is deprecated. Use Visual(frame, color, geometry) instead." + # Visual(frame, color, geometry) + # end + # # Keyword constructor + Visual(; frame, transform, geometry, color, specular, shininess) = Visual(frame, transform, geometry; color, specular, shininess) end function Base.:*(tf::Transform, v::Visual) - Visual(v.frame, v.color, VMRobotControl.transform_mesh(v.geometry, tf)) + if isnothing(v.transform) + remake(v; transform=tf) + else + remake(v; transform=tf*v.transform) + end end - _reassign_frames(c::Visual, frd) = remake(c; frame=get_compiled_frameID(frd, c.frame)) _reassign_joints(c::Visual, jrd) = c _reassign_coords(c::Visual, crd) = c + +struct CompiledVisual{M<:GeometryBasics.Mesh} <:ComponentData{Float64} + frame::FrameID + mesh::M + color::RGBAf + specular::Float32 + shininess::Float32 +end + +function compile_visual(v::Visual) + if isa(v.geometry, MeshFromFile{DAEScene}) + # If the geometry is a DAE scene, load it + meshes_kwargs = convert_for_glmakie(v.geometry.mesh) + return [ + begin + color = haskey(kwargs, :color) ? kwargs[:color] : v.color + specular = haskey(kwargs, :specular) ? kwargs[:specular] : v.specular + shininess = haskey(kwargs, :shininess) ? kwargs[:shininess] : v.shininess + _mesh = convert(GeometryBasics.GLNormalMesh{3}, mesh) + transformed_mesh = VMRobotControl.transform_mesh(_mesh, v.transform) + M = typeof(transformed_mesh) + CompiledVisual{M}(v.frame, transformed_mesh, color, specular, shininess) + end + for (mesh, kwargs) in meshes_kwargs + ] + end + + if isa(v.geometry, MeshFromFile{<:GeometryBasics.Mesh}) + # If the geometry is a mesh from file, load it + mesh = normal_mesh(v.geometry.mesh) + elseif isa(v.geometry, GeometryBasics.GeometryPrimitive) + # Otherwise, use the geometry as is + mesh = normal_mesh(v.geometry) + elseif isa(v.geometry, GeometryBasics.Mesh) + mesh = normal_mesh(v.geometry) + else + error("Unrecognized geometry type: $(typeof(v.geometry))") + end + CompiledVisual(v.frame, mesh, v.color, v.specular, v.shininess) +end \ No newline at end of file diff --git a/src/interface.jl b/src/interface.jl index 9394256..6b6d8f3 100644 --- a/src/interface.jl +++ b/src/interface.jl @@ -37,6 +37,7 @@ function compute_in_coordinate_order(f, coords::Vector{<:TypeStableCollection}) for tsc in coords foreach(tsc) do coord f(coord) + nothing end end nothing @@ -751,7 +752,18 @@ See also [`dynamics!`](@ref) function new_dynamics_cache end -# TODO +""" + new_inverse_dynamics_cache(m[, T]) + +Creates a cache with element type `::T` (defaulting to the eltype of the mechanism) for performing +inverse dynamics computations with the Recursive Newton Euler (RNE) algorithm on a compiled mechanism. + +This cache supports computation of frame transforms, velocities, velocity-product-accelerations. +It also supports [`configuration`](@ref), [`velocity`](@ref), [`acceleration`](@ref), but +not [`jacobian`](@ref) for coordinates. + +See also [`dynamics!`](@ref) +""" function new_inverse_dynamics_cache end """ diff --git a/src/joints/joint_definitions.jl b/src/joints/joint_definitions.jl index f545f53..a441202 100644 --- a/src/joints/joint_definitions.jl +++ b/src/joints/joint_definitions.jl @@ -623,12 +623,23 @@ function _project_forces_to_jointspace(j::RevoluteData, tf_p::Transform{T}, tf_c # The minus sign is due to the fact that the torque is expressed on the right side of the # equation - u = -dot(rotor(tf_p) * rotor(j.transform) * j.axis, τ_c) + axis = rotor(tf_p) * rotor(j.transform) * j.axis + u = -dot(axis, τ_c) return SVector(u) end function _project_forces_to_jointspace(j::PrismaticData, tf_p::Transform{T}, tf_c::Transform{T}, f_p::S, f_c::S, τ_p::S, τ_c::S) where {T, S<: SVector{3, T}} # Rotate axis to world frame, then dot with force - u = -dot(rotor(tf_c) * j.axis, f_c) + axis = rotor(tf_c) * j.axis + u = -dot(axis, f_c) + return SVector(u) +end + +function _project_forces_to_jointspace(j::RailData, tf_p::Transform{T}, tf_c::Transform{T}, f_p::S, f_c::S, τ_p::S, τ_c::S) where {T, S<: SVector{3, T}} + # Rotate axis to world frame, then dot with force + # TODO test + dspline = spline_derivative(q[1]/joint.scaling, joint.spline)/joint.scaling + axis = rotor(tfₚ) * rotor(joint.transform) * dspline + u = -dot(axis, f_c) return SVector(u) end diff --git a/src/rson/parsing.jl b/src/rson/parsing.jl index 9ce68b4..3b147ac 100644 --- a/src/rson/parsing.jl +++ b/src/rson/parsing.jl @@ -508,15 +508,15 @@ function parseVisual!(mechanism, name::JSON_STR, data, cfg::RSONParserConfig) expect = (field, TYPE) -> expectField(data, field, TYPE, cfg) if type == "box" widths = parseVec(expect("size", Vector{Any}), Float64, Val{3}(), cfg) - mesh = normal_mesh(Rect{3, Float64}(-widths./2, widths)) + geom = Rect{3, Float64}(-widths./2, widths) elseif type == "cylinder" L = expect("length", Float64) origin = L * SVector(0.0, 0.0, -0.5) extremity = L * SVector(0.0, 0.0, 0.5) - mesh = Cylinder{Float64}(origin, extremity, expect("radius", Float64)) + geom = Cylinder{Float64}(origin, extremity, expect("radius", Float64)) elseif type == "sphere" origin = SVector(0.0, 0.0, 0.0) - mesh = normal_mesh(Sphere{Float64}(origin, expect("radius", Float64))) + geom = Sphere{Float64}(origin, expect("radius", Float64)) elseif type == "mesh" if isnothing(cfg.rson_path) rson_path = "." @@ -527,6 +527,7 @@ function parseVisual!(mechanism, name::JSON_STR, data, cfg::RSONParserConfig) mesh_path = expect("filename", String) path = joinpath(rson_path, mesh_path) mesh = load_mesh(path, cfg) # This can return multiple meshes + geom = MeshFromFile(mesh, mesh_path) # MeshFromFile is a wrapper for GeometryBasics.Mesh # visual.scale = expect("scale") elseif type == "meshdata" verts = expect("vertices", Vector{Any}) @@ -534,20 +535,15 @@ function parseVisual!(mechanism, name::JSON_STR, data, cfg::RSONParserConfig) # TODO verify that verts and faces are correct types/lengths verts = [parseVertex(vert, cfg) for vert in verts] faces = [parseFace(face, cfg) for face in faces] - mesh = GeometryBasics.Mesh(verts, faces) + geom = GeometryBasics.Mesh(verts, faces) else rson_throw_exception("Unrecognised visual type '$(type)'", cfg) end frame = parseFrameOutsideFramesList(mechanism, expect("frame", Union{String, OrderedDict{String, Any}}), cfg) color = parseMaterial(expect("material", Union{String, Vector{Any}}), cfg) - if isa(mesh, Vector{<:Tuple{<:Mesh, <:NamedTuple}}) - for (i, (mesh, kwargs)) in enumerate(mesh) - add_component!(mechanism, Visual(frame, mesh; kwargs...); id=name*"_$i") - end - else - add_component!(mechanism, Visual(frame, color, mesh); id=name) - end + tf = zero(Transform{Float64}) + add_component!(mechanism, Visual(frame, tf, geom; color); id=name) check_for_remaining_fields(data, cfg) nothing else @@ -561,7 +557,7 @@ function load_mesh(path, cfg) if isa(ret, GeometryBasics.Mesh) return ret elseif isa(ret, DAEScene) - return convert_for_glmakie(ret) + return ret else throw("Unhandled mesh type $(typeof(ret))") end diff --git a/src/rson/rson.jl b/src/rson/rson.jl index c8cdc31..92e1ebd 100644 --- a/src/rson/rson.jl +++ b/src/rson/rson.jl @@ -29,7 +29,8 @@ using ..VMRobotControl: RevoluteData, PrismaticData, Rigid, - MechanismJoint + MechanismJoint, + MeshFromFile import JSON diff --git a/src/rson/serializing.jl b/src/rson/serializing.jl index f11fe2f..b2f634b 100644 --- a/src/rson/serializing.jl +++ b/src/rson/serializing.jl @@ -283,14 +283,47 @@ end # Visual function serialize_component(v::Visual) - @assert v.geometry isa Mesh - verts = GeometryBasics.coordinates(v.geometry) - faces = [Int[face...] for face in GeometryBasics.faces(v.geometry)] - OrderedDict( - "type" => "meshdata", - "frame" => v.frame, - "material" => jsonify(v.color), - "vertices" => verts, - "faces" => faces - ) + if v.geometry isa Mesh + @warn "Serializing a mesh directly will create a large rson file." + verts = GeometryBasics.coordinates(v.geometry) + faces = [Int[face...] for face in GeometryBasics.faces(v.geometry)] + OrderedDict( + "type" => "meshdata", + "frame" => v.frame, + "material" => jsonify(v.color), + "vertices" => verts, + "faces" => faces + ) + elseif v.geometry isa MeshFromFile + OrderedDict( + "type" => "mesh", + "frame" => v.frame, + "material" => jsonify(v.color), + "filename" => v.geometry.path + ) + elseif v.geometry isa Rect + OrderedDict( + "type" => "box", + "frame" => v.frame, + "material" => jsonify(v.color), + "size" => v.geometry.widths + ) + elseif v.geometry isa Cylinder + OrderedDict( + "type" => "cylinder", + "frame" => v.frame, + "material" => jsonify(v.color), + "radius" => v.geometry.radius, + "length" => norm(v.geometry.origin - v.origin.extremity) + ) + elseif v.geometry isa Sphere + OrderedDict( + "type" => "sphere", + "frame" => v.frame, + "material" => jsonify(v.color), + "radius" => v.geometry.r + ) + else + rson_throw_exception("Unrecognised visual type '$(type)'", cfg) + end end \ No newline at end of file diff --git a/src/type_stable_collection.jl b/src/type_stable_collection.jl index 2cbac6c..31cf586 100644 --- a/src/type_stable_collection.jl +++ b/src/type_stable_collection.jl @@ -74,7 +74,7 @@ end @generated function Base.getindex(c::TypeStableCollection{TUPTYPE}, i::TypeStableIdx{T}) where {TUPTYPE, T} tupidx = _get_matching_tupindex(c, T) - isnothing(tupidx) && error("Type $T not found in TypeStableCollection. Types in collection: $(map(eltype, TUPTYPE.types))") + isnothing(tupidx) && return quote error("Type $T not found in TypeStableCollection. Types in collection: $(map(eltype, TUPTYPE.types))") end return quote c.tup[$tupidx][i.vecidx] end @@ -82,7 +82,7 @@ end @generated function Base.setindex!(c::TypeStableCollection, val::T, i::TypeStableIdx{T}) where T tupidx = _get_matching_tupindex(c, T) - isnothing(tupidx) && error("Type $T not found in TypeStableCollection") + isnothing(tupidx) && return quote error("Type $T not found in TypeStableCollection") end return quote c.tup[$tupidx][i.vecidx] = val c diff --git a/src/urdf/parse_urdf.jl b/src/urdf/parse_urdf.jl index 8b7a51b..05811e3 100644 --- a/src/urdf/parse_urdf.jl +++ b/src/urdf/parse_urdf.jl @@ -237,34 +237,8 @@ function parse_visual!(mechanism, visualnode, link_frame, cfg) isnothing(geometry) && error("Geometry not specified for visual with name '$name'.") isnothing(material) && (material = cfg.default_material) - if typeof(geometry)<:Vector{<:Tuple{<:Mesh, <:NamedTuple}} - for (i, (mesh, kwargs)) in enumerate(geometry) - v = Visual(link_frame, mesh; kwargs...) - isnothing(transform) || (v = transform * v) - add_component!(mechanism, v; id=name*"_$i") - end - else - v = Visual(link_frame, geometry; material...) - isnothing(transform) || (v = transform * v) - add_component!(mechanism, v; id=name) - end - - # visual = let - # Visual(name, link_frame, material, geometry) - # end - - # # As each urdf link can have several visuals, we need to give them different names. - # visual_ids = collect(keys(VMRobotControl.visuals(mechanism))) - # # Check if name already exists, and if so, add a number to it - # i = 1 - # while true - # if (name * "_$i") in visual_ids - # i += 1 - # else - # break - # end - # end - # add_component!(mechanism, visual; id=name*"_$i") + v = Visual(link_frame, transform, geometry; material...) + add_component!(mechanism, v; id=name) end function parse_geometry(geometry_node, cfg) @@ -288,14 +262,14 @@ function parse_geometry(geometry_node, cfg) geom = Sphere3{Float64}(SVector(0, 0, 0), r) elseif nn == "mesh" filename = node["filename"] - geom = load_mesh(filename, cfg) - # This will either be a mesh, or vector of tuples containing mesh and kwargs for - # visual properties - if haskey(node, "scale") + mesh = load_mesh(filename, cfg) + if haskey(node, "scale") + # TODO this wont work with all types of mesh... should be robustified scale_vec = parse_3vec(node["scale"], cfg) scale = GeometryBasics.Point{3, Float64}(scale_vec...) - geom = VMRobotControl.rescale_geometry(geom, scale) + mesh = VMRobotControl.rescale_mesh(mesh, scale) end + geom = MeshFromFile(mesh, filename) else raise_not_recognized(nn, cfg) end @@ -321,7 +295,7 @@ function load_mesh(filename, cfg) try ret = load(path) # Try load if isa(ret, DAEScene) - return convert_for_glmakie(ret) + return ret elseif isa(ret, Mesh) return ret else diff --git a/src/urdf/urdf.jl b/src/urdf/urdf.jl index e6d8f04..ab554e3 100644 --- a/src/urdf/urdf.jl +++ b/src/urdf/urdf.jl @@ -11,6 +11,8 @@ using GeometryBasics using LinearAlgebra: Diagonal, Symmetric, issymmetric, isposdef using StaticArrays using ..VMRobotControl +using ..VMRobotControl: + MeshFromFile include("./parse_urdf.jl") end \ No newline at end of file